From 8147dddb30047261771a153e5076a76d287a1756 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 28 Oct 2021 13:58:00 -0400 Subject: [PATCH 001/758] working on global error msg --- examples/Cassie/cassie_xbox_remote.py | 3 + examples/Cassie/dispatcher_robot_in.cc | 6 + examples/Cassie/input_supervisor.cc | 145 ++++++++++++++----------- examples/Cassie/input_supervisor.h | 24 +++- examples/Cassie/integration_test.pmd | 8 +- lcmtypes/lcmt_controller_error.lcm | 8 ++ 6 files changed, 127 insertions(+), 67 deletions(-) create mode 100644 lcmtypes/lcmt_controller_error.lcm diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index fd14f6dbcf..7a19b98e68 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -1,6 +1,7 @@ import pygame import dairlib.lcmt_radio_out import lcm +import numpy as np # colors cassie_blue = (6, 61, 128) @@ -102,6 +103,8 @@ def main(): radio_msg.channel[3] = joystick.get_axis(3) radio_msg.channel[6] = radio_channel_6_pos + radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) + publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 5c18063759..62a6a9c7c3 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -3,6 +3,7 @@ #include +#include "dairlib/lcmt_controller_error.hpp" #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" @@ -91,6 +92,9 @@ int do_main(int argc, char* argv[]) { auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); + auto controller_error_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + "CONTROLLER_ERROR", &lcm_local)); auto state_receiver = builder.AddSystem(plant); auto input_supervisor_status_pub = builder.AddSystem( LcmPublisherSystem::Make( @@ -112,6 +116,8 @@ int do_main(int argc, char* argv[]) { input_supervisor->get_input_port_command()); builder.Connect(controller_switch_sub->get_output_port(), input_supervisor->get_input_port_controller_switch()); + builder.Connect(controller_error_sub->get_output_port(), + input_supervisor->get_input_port_controller_error()); builder.Connect(input_supervisor->get_output_port_status(), input_supervisor_status_pub->get_input_port()); builder.Connect(cassie_out_receiver->get_output_port(), diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 4b82850e5f..c7cb0546c5 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -1,6 +1,7 @@ #include "examples/Cassie/input_supervisor.h" #include +#include #include "dairlib/lcmt_controller_switch.hpp" #include "systems/framework/output_vector.h" @@ -30,15 +31,15 @@ InputSupervisor::InputSupervisor( } // Create input ports - command_input_port_ = this->DeclareVectorInputPort( - "u, t", TimestampedVector(num_actuators_)) - .get_index(); + command_input_port_ = + this->DeclareVectorInputPort("u, t", + TimestampedVector(num_actuators_)) + .get_index(); ; state_input_port_ = this->DeclareVectorInputPort( - "x, u, t", - OutputVector(num_positions_, num_velocities_, - num_actuators_)) + "x, u, t", OutputVector(num_positions_, num_velocities_, + num_actuators_)) .get_index(); controller_switch_input_port_ = this->DeclareAbstractInputPort( @@ -49,6 +50,11 @@ InputSupervisor::InputSupervisor( this->DeclareAbstractInputPort("lcmt_cassie_out", drake::Value{}) .get_index(); + controller_error_port_ = + this->DeclareAbstractInputPort( + "lcmt_controller_error", + drake::Value{}) + .get_index(); // Create output port for commands command_output_port_ = @@ -62,16 +68,22 @@ InputSupervisor::InputSupervisor( this->DeclareAbstractOutputPort("status", &InputSupervisor::SetStatus) .get_index(); - // Create error flag as discrete state - // Store both values in single discrete vector - status_vars_index_ = DeclareDiscreteState(2); - n_fails_index_ = 0; - status_index_ = 1; + prev_efforts_index_ = DeclareDiscreteState(num_actuators_); + + // Create error flags as discrete state + n_fails_index_ = DeclareDiscreteState(1); + status_index_ = DeclareDiscreteState(1); switch_time_index_ = DeclareDiscreteState(1); prev_efforts_time_index_ = DeclareDiscreteState(1); - prev_efforts_index_ = DeclareDiscreteState(num_actuators_); + error_shutdown_index_ = DeclareDiscreteState(1); + controller_msg_delay_index_ = DeclareDiscreteState(1); soft_estop_trigger_index_ = DeclareDiscreteState(1); is_nan_index_ = DeclareDiscreteState(1); + consecutive_failures_index_ = DeclareDiscreteState(1); + + error_indices_ = {error_shutdown_index_, controller_msg_delay_index_, + soft_estop_trigger_index_, is_nan_index_, + consecutive_failures_index_}; K_ = plant_.MakeActuationMatrix().transpose(); K_ *= kEStopGain; @@ -92,28 +104,33 @@ void InputSupervisor::SetMotorTorques(const Context& context, const auto& cassie_out = this->EvalInputValue( context, cassie_input_port_); - bool is_error = - context.get_discrete_state(status_vars_index_)[n_fails_index_] >= - min_consecutive_failures_; - is_error = - is_error || (command->get_timestamp() - - context.get_discrete_state(prev_efforts_time_index_)[0] > - kMaxControllerDelay); - is_error = - is_error || context.get_discrete_state(soft_estop_trigger_index_)[0]; - is_error = is_error || context.get_discrete_state(is_nan_index_)[0]; - if ((command->get_timestamp() - - context.get_discrete_state(prev_efforts_time_index_)[0] > - kMaxControllerDelay)) { - std::cout << "Delay between controller commands is too long, shutting down" - << std::endl; + // bool is_error = context.get_discrete_state(n_fails_index_)[0] >= + // min_consecutive_failures_; + // is_error = + // is_error || (command->get_timestamp() - + // context.get_discrete_state(prev_efforts_time_index_)[0] + // > + // kMaxControllerDelay); + // is_error = + // is_error || context.get_discrete_state(soft_estop_trigger_index_)[0]; + // is_error = is_error || context.get_discrete_state(is_nan_index_)[0]; + // if ((command->get_timestamp() - + // context.get_discrete_state(prev_efforts_time_index_)[0] > + // kMaxControllerDelay)) { + // std::cout << "Delay between controller commands is too long, shutting + // down" + // << std::endl; + // } + + // iterate through all the possible error flags + bool is_error = false; + for (int error_flag_index_ : error_indices_) { + is_error = is_error || context.get_discrete_state(error_flag_index_)[0]; } - bool is_nan = command->get_data().array().isNaN().any(); - // If the soft estop signal is triggered, applying only damping regardless of // any other controller signal - if (cassie_out->pelvis.radio.channel[15] == -1 || is_nan) { + if (cassie_out->pelvis.radio.channel[15] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); output->SetDataVector(u); return; @@ -167,12 +184,9 @@ void InputSupervisor::SetStatus( const TimestampedVector* command = (TimestampedVector*)this->EvalVectorInput(context, command_input_port_); - - output->status = - int(context.get_discrete_state(status_vars_index_)[status_index_]); + output->status = int(context.get_discrete_state(status_index_)[0]); output->utime = command->get_timestamp() * 1e6; - output->vel_limit = - bool(context.get_discrete_state(status_vars_index_)[status_index_]); + output->vel_limit = bool(context.get_discrete_state(status_index_)[0]); if (input_limit_ != std::numeric_limits::max()) { for (int i = 0; i < command->get_data().size(); i++) { @@ -188,7 +202,7 @@ void InputSupervisor::SetStatus( // Shutdown is/will soon be active (the status flag is set in a separate loop // from the actual motor torques so the update of the status bit could be // slightly off - if (context.get_discrete_state(status_vars_index_)[n_fails_index_] >= + if (context.get_discrete_state(n_fails_index_)[0] >= min_consecutive_failures_) { output->status += 4; output->shutdown = true; @@ -208,25 +222,30 @@ void InputSupervisor::UpdateErrorFlag( const auto* controller_switch = this->EvalInputValue( context, controller_switch_input_port_); + const auto* controller_error = + this->EvalInputValue( + context, controller_error_port_); const TimestampedVector* command = (TimestampedVector*)this->EvalVectorInput(context, command_input_port_); - if (command->get_timestamp() - - discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] > - kMaxControllerDelay) { - discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] = 0.0; - } else { - discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] = - command->get_timestamp(); - } - + // Note the += operator works as an or operator because we only check if the + // error flag != 0 + discrete_state->get_mutable_vector(error_shutdown_index_)[0] += + controller_error->error_code != 0; + // && + // controller_error->controller_channel == current_channel_); + discrete_state->get_mutable_vector(controller_msg_delay_index_)[0] += + (command->get_timestamp() - + context.get_discrete_state(prev_efforts_time_index_)[0] > + kMaxControllerDelay); + discrete_state->get_mutable_vector(is_nan_index_)[0] += + command->get_data().array().isNaN().any(); + discrete_state->get_mutable_vector(consecutive_failures_index_)[0] += + context.get_discrete_state(n_fails_index_)[0] >= + min_consecutive_failures_; CheckRadio(context, discrete_state); CheckVelocities(context, discrete_state); - // Only update if it's setting the error flag to true - discrete_state->get_mutable_vector(is_nan_index_)[0] = - discrete_state->get_mutable_vector(is_nan_index_)[0] || - command->get_data().array().isNaN().any(); // When receiving a new controller switch message, record the time if (discrete_state->get_mutable_vector(switch_time_index_)[0] < @@ -237,6 +256,15 @@ void InputSupervisor::UpdateErrorFlag( blend_duration_ = controller_switch->blend_duration; } + if (command->get_timestamp() - + discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] > + kMaxControllerDelay) { + discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] = 0.0; + } else { + discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] = + command->get_timestamp(); + } + // Update the previous commanded switch message unless currently blending // efforts if (command->get_timestamp() - controller_switch->utime * 1e-6 >= @@ -253,33 +281,28 @@ void InputSupervisor::CheckVelocities( (OutputVector*)this->EvalVectorInput(context, state_input_port_); const Eigen::VectorXd& velocities = state->GetVelocities(); - if (discrete_state->get_vector(status_vars_index_)[n_fails_index_] < + if (discrete_state->get_vector(n_fails_index_)[0] < min_consecutive_failures_) { // If any velocity is above the threshold, set the error flag bool is_velocity_error = (velocities.array() > max_joint_velocity_).any() || (velocities.array() < -max_joint_velocity_).any(); if (is_velocity_error) { // Increment counter - discrete_state->get_mutable_vector(status_vars_index_)[n_fails_index_] += - 1; + discrete_state->get_mutable_vector(n_fails_index_)[0] += 1; // Using the discrete state which is a vector of doubles to store a bool - discrete_state->get_mutable_vector(status_vars_index_)[status_index_] = - double(true); + discrete_state->get_mutable_vector(status_index_)[0] = double(true); std::cout << "Error! Velocity has exceeded the threshold of " << max_joint_velocity_ << std::endl; std::cout << "Consecutive error " - << discrete_state->get_vector( - status_vars_index_)[n_fails_index_] - << " of " << min_consecutive_failures_ << std::endl; + << discrete_state->get_vector(n_fails_index_)[0] << " of " + << min_consecutive_failures_ << std::endl; std::cout << "Velocity vector: " << std::endl << velocities << std::endl << std::endl; } else { // Reset counter - discrete_state->get_mutable_vector(status_vars_index_)[n_fails_index_] = - 0; - discrete_state->get_mutable_vector(status_vars_index_)[status_index_] = - double(false); + discrete_state->get_mutable_vector(n_fails_index_)[0] = 0; + discrete_state->get_mutable_vector(status_index_)[0] = double(false); } } } diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index db2d75b36f..47672f5374 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -60,6 +60,10 @@ class InputSupervisor : public drake::systems::LeafSystem { return this->get_input_port(cassie_input_port_); } + const drake::systems::InputPort& get_input_port_controller_error() const { + return this->get_input_port(controller_error_port_); + } + const drake::systems::OutputPort& get_output_port_command() const { return this->get_output_port(command_output_port_); } @@ -97,22 +101,34 @@ class InputSupervisor : public drake::systems::LeafSystem { double input_limit_; mutable double blend_duration_ = 0.0; - int soft_estop_trigger_index_; - int is_nan_index_; - int status_vars_index_; - int n_fails_index_; + +// int status_vars_index_; + int status_index_; + int n_fails_index_; // for blending controller efforts int switch_time_index_; int prev_efforts_index_; int prev_efforts_time_index_; + + // All possible error flags + int error_shutdown_index_; + int controller_msg_delay_index_; + int soft_estop_trigger_index_; + int is_nan_index_; + int consecutive_failures_index_; + + // vector of all error flags that we check + std::set error_indices_; + // leafsystem ports int state_input_port_; int command_input_port_; int controller_switch_input_port_; int cassie_input_port_; + int controller_error_port_; int command_output_port_; int status_output_port_; diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index c5714c3609..862c2e9e8a 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -50,6 +50,10 @@ group "2.simulators" { exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.95 --actuator_delay=0.005"; host = "localhost"; } + cmd "cassie_sim_dispatcher" { + exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.95 --actuator_delay=0.005 --channel_u=NETWORK_CASSIE_INPUT"; + host = "localhost"; + } } group "0.operator" { @@ -152,8 +156,8 @@ script "standing_integration_test" { stop cmd "cassie_sim"; stop cmd "osc_standing_controller (state_est)"; stop cmd "dispatcher_robot_out"; - start cmd "dispatcher_robot_out"; - start cmd "dispatcher_robot_in"; + restart cmd "dispatcher_robot_out"; + restart cmd "dispatcher_robot_in"; start cmd "osc_standing_controller (state_est)"; start cmd "cassie_mujoco_sim"; wait ms 10000; diff --git a/lcmtypes/lcmt_controller_error.lcm b/lcmtypes/lcmt_controller_error.lcm new file mode 100644 index 0000000000..e78f5aa317 --- /dev/null +++ b/lcmtypes/lcmt_controller_error.lcm @@ -0,0 +1,8 @@ +package dairlib; + +struct lcmt_controller_error +{ + int64_t utime; + int32_t error_code; + string controller_channel; +} From cb9e03e2d4bcea2346ecd3d8c18a94180e62c117 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Fri, 12 Nov 2021 17:30:28 -0500 Subject: [PATCH 002/758] initial rogress --- bindings/pydairlib/analysis/BUILD.bazel | 54 +++++ .../analysis/cassie_plotting_utils.py | 135 +++++++++++ .../pydairlib/analysis/log_plotter_cassie.py | 18 ++ .../pydairlib/analysis/process_lcm_log.py | 31 +++ bindings/pydairlib/cassie/BUILD.bazel | 54 +++++ bindings/pydairlib/cassie/__init__.py | 2 + bindings/pydairlib/cassie/cassie_utils_py.cc | 45 ++++ bindings/pydairlib/lcm/BUILD.bazel | 10 - bindings/pydairlib/lcm/process_lcm_log.py | 215 ------------------ 9 files changed, 339 insertions(+), 225 deletions(-) create mode 100644 bindings/pydairlib/analysis/BUILD.bazel create mode 100644 bindings/pydairlib/analysis/cassie_plotting_utils.py create mode 100644 bindings/pydairlib/analysis/log_plotter_cassie.py create mode 100644 bindings/pydairlib/analysis/process_lcm_log.py create mode 100644 bindings/pydairlib/cassie/BUILD.bazel create mode 100644 bindings/pydairlib/cassie/__init__.py create mode 100644 bindings/pydairlib/cassie/cassie_utils_py.cc delete mode 100644 bindings/pydairlib/lcm/process_lcm_log.py diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel new file mode 100644 index 0000000000..b30d0c1ce1 --- /dev/null +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -0,0 +1,54 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +py_library( + name = "process_lcm_log_py", + srcs = [":process_lcm_log.py"], + deps = [], +) + +py_library( + name = "cassie_plotting_utils", + srcs = ["cassie_plotting_utils.py"], + data = [ + "//examples/Cassie:cassie_urdf", + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/cassie:cassie_utils", + "//bindings/pydairlib/common", + "//bindings/pydairlib/common:plot_styler", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) + +py_binary( + name = "log_plotter_cassie", + srcs = ["log_plotter_cassie.py"], + data = [ + "//examples/Cassie:cassie_urdf", + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", + "//bindings/pydairlib/common:plot_styler", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py new file mode 100644 index 0000000000..82f684b7c7 --- /dev/null +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -0,0 +1,135 @@ +# python imports +import lcm +import numpy as np + +# dairlib imports +import dairlib +from pydairlib.cassie.cassie_utils import * +from pydairlib.common import FindResourceOrThrow +from pydarilib.common import plot_styler + +# drake imports +from pydrake.multibody.parsing import Parser +from pydrake.multibody.plant import AddMultibodyPlantSceneGraph +from pydrake.multibody.tree import JacobianWrtVariable +from pydrake.systems.framework import DiagramBuilder + +cassie_urdf = "examples/Cassie/urdf/cassie_v2.urdf" +cassie_urdf_no_springs = "examples/Cassie/urdf/cassie_fixed_springs.urdf" + +# Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays +class lcmt_osc_tracking_data_t: + def __init__(self): + self.t = [] + self.y_dim = 0 + self.name = "" + self.is_active = [] + self.y = [] + self.y_des = [] + self.error_y = [] + self.ydot = [] + self.ydot_des = [] + self.error_ydot = [] + self.yddot_des = [] + self.yddot_command = [] + self.yddot_command_sol = [] + + def append(self, msg, t): + self.t.append(t) + self.is_active.append(msg.is_active) + self.y.append(msg.y) + self.y_des.append(msg.y_des) + self.error_y.append(msg.error_y) + self.ydot.append(msg.ydot) + self.ydot_des.append(msg.ydot_des) + self.error_ydot.append(msg.error_ydot) + self.yddot_des.append(msg.yddot_des) + self.yddot_command.append(msg.yddot_command) + self.yddot_command_sol.append(msg.yddot_command_sol) + + def convertToNP(self): + self.t = np.array(self.t) + self.is_active = np.array(self.is_active) + self.y = np.array(self.y) + self.y_des = np.array(self.y_des) + self.error_y = np.array(self.error_y) + self.ydot = np.array(self.ydot) + self.ydot_des = np.array(self.ydot_des) + self.error_ydot = np.array(self.error_ydot) + self.yddot_des = np.array(self.yddot_des) + self.yddot_command = np.array(self.yddot_command) + self.yddot_command_sol = np.array(self.yddot_command_sol) + +cassie_default_channels = \ + {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, + 'CASSIE_STATE_DISPATCHER': dairlib.lcmt_robot_output, + 'CASSIE_INPUT': dairlib.lcmt_robot_input, + 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, + 'OSC_DEBUG_STANDING': dairlib.lcmt_osc_output, + 'OSC_DEBUG_WALKING': dairlib.lcmt_osc_output, + 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output, + 'OSC_DEBUG_RUNNING': dairlib.lcmt_osc_output} + +def make_plant_and_context(floating=True, springs=True): + builder = DiagramBuilder() + plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) + if (springs): + addCassieMultibody(plant, scene_graph, floating, cassie_urdf, True, True) + else: + addCassieMultibody(plant, scene_graph, floating, cassie_urdf_no_springs, + False, True) + + plant.Finalize() + return plant, plant.CreateDefaultContext() + + +def process_state_channel(state_data, plant): + t_x = [] + q = [] + u = [] + v = [] + + pos_map = pydairlib.multibody.makeNameToPositionsMap(plant) + vel_map = pydairlib.multibody.makeNameToVelocitiesMap(plant) + act_map = pydairlib.multibody.makeNameToActuatorsMap(plant) + + for msg in state_data: + q_temp = [[] for i in range(len(msg.position))] + v_temp = [[] for i in range(len(msg.velocity))] + u_temp = [[] for i in range(len(msg.effort))] + for i in range(len(q_temp)): + q_temp[pos_map[msg.position_names[i]]] = msg.position[i] + for i in range(len(v_temp)): + v_temp[vel_map[msg.velocity_names[i]]] = msg.velocity[i] + for i in range(len(u_temp)): + u_temp[act_map[msg.effort_names[i]]] = msg.effort[i] + q.append(q_temp) + v.append(v_temp) + u.append(u_temp) + t_x.append(msg.utime / 1e6) + + return np.array(t_x), np.array(q), np.array(v), np.array(u) + + +def process_effort_data(data): + u = [] + t = [] + for msg in data: + t.append(msg.utime / 1e6) + u.append(msg.efforts) + + return np.array(t), np.array(u) + + +def process_default_channels(data, plant, state_channel, input_channel, + osc_debug_channel): + + t_x, q, v, u_meas = process_state_channel(data[state_channel], plant) + t_u, u = process_effort_data(data[input_channel]) + + return {'t_x': t_x, + 'q': q, + 'v': v, + 'u_meas': u_meas, + 't_u': t_u, + 'u': u} diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py new file mode 100644 index 0000000000..322f81063d --- /dev/null +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -0,0 +1,18 @@ +import sys +import lcm +import dairlib +from process_lcm_log import get_log_data, passthrough_callback +import cassie_plotting_utils + +filename = sys.argv[1] +log = lcm.EventLog(filename, "r") + + +plant, context = cassie_plotting_utils.make_plant_and_context() + +data = get_log_data(log, cassie_plotting_utils.cassie_default_channels, + cassie_plotting_utils.process_default_channels, plant, + 'CASSIE_STATE_SIMULATION', 'CASSIE_INPUT', + 'OSC_DEBUG_WALKING') + +import pdb; pdb.set_trace() diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/analysis/process_lcm_log.py new file mode 100644 index 0000000000..c37b6b8ba6 --- /dev/null +++ b/bindings/pydairlib/analysis/process_lcm_log.py @@ -0,0 +1,31 @@ + + +def get_log_data(lcm_log, lcm_channels, data_processing_callback, *args, + **kwargs): + """ + Parses an LCM log and returns a dictionary with entries + :param lcm_log: an lcm.EventLog object + :param lcm_channels: dictionary of {channel : lcmtype} of channels to be read from the log + :param data_processing_callback: function pointer which takes as arguments + (data, args, kwargs) and where data is a dictionary with + entries {CHANNEL : [ msg for lcm msg in log with msg.channel == CHANNEL} + :param args: positional arguments for data_processing_callback + :param kwargs: keyword arguments for data_processing_callback + :return: { label : xdata, ydata } returned by data_processing_callback + """ + + data_to_process = {} + for event in lcm_log: + if event.channel in lcm_channels: + if event.channel in data_to_process: + data_to_process[event.channel].append( + lcm_channels[event.channel].decode(event.data)) + else: + data_to_process[event.channel] = \ + [lcm_channels[event.channel].decode(event.data)] + + return data_processing_callback(data_to_process, *args, *kwargs) + + +def passthrough_callback(data, *args, **kwargs): + return data diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel new file mode 100644 index 0000000000..6a3fe96e38 --- /dev/null +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -0,0 +1,54 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +pybind_py_library( + name = "cassie_utils_py", + cc_deps = [ + "//examples/Cassie:cassie_utils", + "@drake//:drake_shared_library", + ], + cc_so_name = "cassie_utils", + cc_srcs = ["cassie_utils_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + "//bindings/pydairlib/multibody:kinematic_py", + ":module_py", + ], + py_imports = ["."], +) + +# This determines how `PYTHONPATH` is configured, and how to install the +# bindings. +PACKAGE_INFO = get_pybind_package_info("//bindings") + +py_library( + name = "module_py", + srcs = [ + "__init__.py", + ], + imports = PACKAGE_INFO.py_imports, + deps = [ + "//bindings/pydairlib:module_py", + ], +) + +PY_LIBRARIES = [ + ":cassie_utils_py", +] + +# Package roll-up (for Bazel dependencies). +py_library( + name = "cassie_utils", + imports = PACKAGE_INFO.py_imports, + deps = PY_LIBRARIES, +) diff --git a/bindings/pydairlib/cassie/__init__.py b/bindings/pydairlib/cassie/__init__.py new file mode 100644 index 0000000000..5a66636f69 --- /dev/null +++ b/bindings/pydairlib/cassie/__init__.py @@ -0,0 +1,2 @@ +# Importing everything in this directory to this package +from .cassie_utils import * \ No newline at end of file diff --git a/bindings/pydairlib/cassie/cassie_utils_py.cc b/bindings/pydairlib/cassie/cassie_utils_py.cc new file mode 100644 index 0000000000..a948c83cf6 --- /dev/null +++ b/bindings/pydairlib/cassie/cassie_utils_py.cc @@ -0,0 +1,45 @@ +#include +#include +#include +#include + +#include "examples/Cassie/cassie_utils.h" + +#include "drake/multibody/plant/multibody_plant.h" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +PYBIND11_MODULE(cassie_utils, m) { + m.doc() = "Binding utility functions for Cassie"; + + using drake::multibody::MultibodyPlant; + + m.def("LeftToeFront", &dairlib::LeftToeFront) + .def("RightToeFront", &dairlib::RightToeFront) + .def("LeftToeRear", &dairlib::LeftToeRear) + .def("RightToeRear", &dairlib::RightToeRear) + .def("LeftRodOnThigh", &dairlib::LeftRodOnThigh) + .def("RightRodOnThigh", &dairlib::RightRodOnThigh) + .def("LeftRodOnHeel", &dairlib::LeftRodOnHeel) + .def("RightRodOnHeel", &dairlib::RightRodOnHeel) + .def("LeftLoopClosureEvaluator", + &dairlib::LeftLoopClosureEvaluator, py::arg("plant")) + .def("RightLoopClosureEvaluator", + &dairlib::RightLoopClosureEvaluator, py::arg("plant")) + .def("addCassieMultibody", &dairlib::addCassieMultibody, py::arg("plant"), + py::arg("scene_graph"), py::arg("floating_base"), + py::arg("filename"), py::arg("add_leaf_springs"), + py::arg("add_loop_closure")) + .def("AddImuAndAggregator", &dairlib::AddImuAndAggregator, + py::arg("builder"), py::arg("plant"), py::arg("actuation_port")); + + py::class_>(m, "SimCassieSensorAggregator") + .def(py::init&>()); +} + +} // namespace pydairlib +} // namespace dairlib \ No newline at end of file diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index cdcf1733b0..77bc988ff5 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -46,15 +46,6 @@ py_binary( ], ) -py_library( - name = "process_lcm_log_py", - srcs = [":process_lcm_log.py"], - deps = [ - ":module_py", - "//lcmtypes:lcmtypes_robot_py", - ], -) - # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") @@ -74,7 +65,6 @@ PY_LIBRARIES = [ ":dircon_trajectory_plotter", ":lcm_trajectory_plotter", ":lcm_trajectory_py", - ":process_lcm_log_py", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py deleted file mode 100644 index 93c3a0380c..0000000000 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ /dev/null @@ -1,215 +0,0 @@ -import dairlib -import drake -import numpy as np - - -# Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays -class lcmt_osc_tracking_data_t: - def __init__(self): - self.t = [] - self.y_dim = 0 - self.name = "" - self.is_active = [] - self.y = [] - self.y_des = [] - self.error_y = [] - self.ydot = [] - self.ydot_des = [] - self.error_ydot = [] - self.yddot_des = [] - self.yddot_command = [] - self.yddot_command_sol = [] - - def append(self, msg, t): - self.t.append(t) - self.is_active.append(msg.is_active) - self.y.append(msg.y) - self.y_des.append(msg.y_des) - self.error_y.append(msg.error_y) - self.ydot.append(msg.ydot) - self.ydot_des.append(msg.ydot_des) - self.error_ydot.append(msg.error_ydot) - self.yddot_des.append(msg.yddot_des) - self.yddot_command.append(msg.yddot_command) - self.yddot_command_sol.append(msg.yddot_command_sol) - - def convertToNP(self): - self.t = np.array(self.t) - self.is_active = np.array(self.is_active) - self.y = np.array(self.y) - self.y_des = np.array(self.y_des) - self.error_y = np.array(self.error_y) - self.ydot = np.array(self.ydot) - self.ydot_des = np.array(self.ydot_des) - self.error_ydot = np.array(self.error_ydot) - self.yddot_des = np.array(self.yddot_des) - self.yddot_command = np.array(self.yddot_command) - self.yddot_command_sol = np.array(self.yddot_command_sol) - - -def process_log(log, pos_map, vel_map, act_map, controller_channel): - t_x = [] - t_u = [] - t_controller_switch = [] - t_contact_info = [] - fsm = [] - q = [] - v = [] - u_meas = [] - u = [] - kp = [] - kd = [] - t_pd = [] - estop_signal = [] - switch_signal = [] - osc_debug = dict() - contact_forces = [[], [], [], []] # Allocate space for all 4 point contacts - contact_info_locs = [[], [], [], []] - cassie_out = [] # Cassie out types - osc_output = [] - u_pd = [] - t_u_pd = [] - t_lcmlog_u = [] - - full_log = dict() - channel_to_type_map = dict() - unknown_types = set() - known_lcm_types = [dairlib.lcmt_robot_output, dairlib.lcmt_cassie_out, dairlib.lcmt_controller_switch, - dairlib.lcmt_osc_output, dairlib.lcmt_pd_config, dairlib.lcmt_robot_input, - drake.lcmt_contact_results_for_viz, dairlib.lcmt_contact, dairlib.lcmt_input_supervisor_status] - osc_debug_channels = ['OSC_DEBUG_WALKING', 'OSC_DEBUG_RUNNING', 'OSC_DEBUG_STANDING', 'OSC_DEBUG_JUMPING'] - # osc_debug_channels = ['OSC_DEBUG_WALKING', 'OSC_DEBUG_RUNNING', 'OSC_DEBUG_JUMPING'] - state_feedback_channels = ['CASSIE_STATE_SIMULATION', 'CASSIE_STATE_DISPATCHER'] - - for event in log: - if event.channel not in full_log and event.channel not in unknown_types: - for lcmtype in known_lcm_types: - try: - lcmtype.decode(event.data) - channel_to_type_map[event.channel] = lcmtype - except ValueError: - continue - if event.channel in channel_to_type_map: - full_log[event.channel] = [] - else: - unknown_types.add(event.channel) - if event.channel in full_log: - full_log[event.channel].append(channel_to_type_map[event.channel].decode(event.data)) - if event.channel in state_feedback_channels: - msg = dairlib.lcmt_robot_output.decode(event.data) - q_temp = [[] for i in range(len(msg.position))] - v_temp = [[] for i in range(len(msg.velocity))] - u_temp = [[] for i in range(len(msg.effort))] - for i in range(len(q_temp)): - q_temp[pos_map[msg.position_names[i]]] = msg.position[i] - for i in range(len(v_temp)): - v_temp[vel_map[msg.velocity_names[i]]] = msg.velocity[i] - for i in range(len(u_temp)): - u_temp[act_map[msg.effort_names[i]]] = msg.effort[i] - q.append(q_temp) - v.append(v_temp) - u_meas.append(u_temp) - t_x.append(msg.utime / 1e6) - if event.channel == "CASSIE_INPUT" or event.channel == controller_channel: - msg = dairlib.lcmt_robot_input.decode(event.data) - u.append(msg.efforts) - t_u.append(msg.utime / 1e6) - if event.channel == "PD_CONTROL": - msg = dairlib.lcmt_robot_input.decode(event.data) - u_pd.append(msg.efforts) - t_u_pd.append(msg.utime / 1e6) - if event.channel == "INPUT_SWITCH": - msg = dairlib.lcmt_controller_switch.decode(event.data) - switch_signal.append(msg.channel == "OSC_STANDING") - t_controller_switch.append(msg.utime / 1e6) - if event.channel == "PD_CONFIG": - msg = dairlib.lcmt_pd_config.decode(event.data) - kp.append(msg.kp) - kd.append(msg.kd) - t_pd.append(msg.timestamp / 1e6) - if event.channel == "CASSIE_OUTPUT_ECHO": - msg = dairlib.lcmt_cassie_out.decode(event.data) - cassie_out.append(msg) - if event.channel in osc_debug_channels: - msg = dairlib.lcmt_osc_output.decode(event.data) - t_lcmlog_u.append(event.timestamp / 1e6) - osc_output.append(msg) - num_osc_tracking_data = len(msg.tracking_data) - for i in range(num_osc_tracking_data): - if msg.tracking_data[i].name not in osc_debug: - osc_debug[msg.tracking_data[i].name] = lcmt_osc_tracking_data_t() - osc_debug[msg.tracking_data[i].name].append(msg.tracking_data[i], msg.utime / 1e6) - fsm.append(msg.fsm_state) - if event.channel == "CASSIE_CONTACT_DRAKE" or event.channel == "CASSIE_CONTACT_MUJOCO": - # Need to distinguish between front and rear contact forces - # Best way is to track the contact location and group by proximity - msg = drake.lcmt_contact_results_for_viz.decode(event.data) - t_contact_info.append(msg.timestamp / 1e6) - num_left_contacts = 0 - num_right_contacts = 0 - for i in range(msg.num_point_pair_contacts): - if "toe_left" in msg.point_pair_contact_info[i].body2_name: - if(num_left_contacts >= 2): - continue - contact_info_locs[num_left_contacts].append( - msg.point_pair_contact_info[i].contact_point) - contact_forces[num_left_contacts].append( - msg.point_pair_contact_info[i].contact_force) - num_left_contacts += 1 - elif "toe_right" in msg.point_pair_contact_info[i].body2_name: - if(num_right_contacts >= 2): - continue - contact_info_locs[2 + num_right_contacts].append( - msg.point_pair_contact_info[i].contact_point) - contact_forces[2 + num_right_contacts].append( - msg.point_pair_contact_info[i].contact_force) - num_right_contacts += 1 - while num_left_contacts != 2: - contact_forces[num_left_contacts].append((0.0, 0.0, 0.0)) - contact_info_locs[num_left_contacts].append((0.0, 0.0, 0.0)) - num_left_contacts += 1 - while num_right_contacts != 2: - contact_forces[2 + num_right_contacts].append((0.0, 0.0, 0.0)) - contact_info_locs[2 + num_right_contacts].append((0.0, 0.0, - 0.0)) - num_right_contacts += 1 - - # Convert into numpy arrays - t_x = np.array(t_x) - t_u = np.array(t_u) - t_lcmlog_u = np.array(t_lcmlog_u) - t_controller_switch = np.array(t_controller_switch) - t_contact_info = np.array(t_contact_info) - t_pd = np.array(t_pd) - fsm = np.array(fsm) - q = np.array(q) - v = np.array(v) - u_meas = np.array(u_meas) - u = np.array(u) - u_pd = np.array(u_pd) - kp = np.array(kp) - kd = np.array(kd) - estop_signal = np.array(estop_signal) - switch_signal = np.array(switch_signal) - contact_forces = np.array(contact_forces) - contact_info_locs = np.array(contact_info_locs) - - for i in range(contact_info_locs.shape[1]): - # Swap front and rear contacts if necessary - # Order will be front contact in index 1 - if contact_info_locs[0, i, 0] > contact_info_locs[1, i, 0]: - contact_forces[[0, 1], i, :] = contact_forces[[1, 0], i, :] - contact_info_locs[[0, 1], i, :] = contact_info_locs[[1, 0], i, :] - if contact_info_locs[2, i, 0] > contact_info_locs[3, i, 0]: - contact_forces[[2, 3], i, :] = contact_forces[[3, 2], i, :] - contact_info_locs[[2, 3], i, :] = contact_info_locs[[3, 2], i, :] - - for key in osc_debug: - osc_debug[key].convertToNP() - - x = np.hstack((q, v)) # combine into state vector - - return x, u_meas, t_x, u, t_u, contact_forces, contact_info_locs, \ - t_contact_info, osc_debug, fsm, estop_signal, \ - switch_signal, t_controller_switch, t_pd, kp, kd, cassie_out, u_pd, \ - t_u_pd, osc_output, full_log, t_lcmlog_u From 67812744f081a4fc3a615f6ef97884edfaca4639 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 13 Nov 2021 12:33:20 -0500 Subject: [PATCH 003/758] unbound sensor aggregator for now to fix runtime error --- bindings/pydairlib/analysis/cassie_plotting_utils.py | 10 ++++++---- bindings/pydairlib/cassie/cassie_utils_py.cc | 8 +------- 2 files changed, 7 insertions(+), 11 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 82f684b7c7..d8ce9c82f4 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -6,7 +6,9 @@ import dairlib from pydairlib.cassie.cassie_utils import * from pydairlib.common import FindResourceOrThrow -from pydarilib.common import plot_styler +from pydairlib.common import plot_styler +from pydairlib.multibody import makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap + # drake imports from pydrake.multibody.parsing import Parser @@ -89,9 +91,9 @@ def process_state_channel(state_data, plant): u = [] v = [] - pos_map = pydairlib.multibody.makeNameToPositionsMap(plant) - vel_map = pydairlib.multibody.makeNameToVelocitiesMap(plant) - act_map = pydairlib.multibody.makeNameToActuatorsMap(plant) + pos_map = makeNameToPositionsMap(plant) + vel_map = makeNameToVelocitiesMap(plant) + act_map = makeNameToActuatorsMap(plant) for msg in state_data: q_temp = [[] for i in range(len(msg.position))] diff --git a/bindings/pydairlib/cassie/cassie_utils_py.cc b/bindings/pydairlib/cassie/cassie_utils_py.cc index a948c83cf6..9e728a1d6a 100644 --- a/bindings/pydairlib/cassie/cassie_utils_py.cc +++ b/bindings/pydairlib/cassie/cassie_utils_py.cc @@ -32,13 +32,7 @@ PYBIND11_MODULE(cassie_utils, m) { .def("addCassieMultibody", &dairlib::addCassieMultibody, py::arg("plant"), py::arg("scene_graph"), py::arg("floating_base"), py::arg("filename"), py::arg("add_leaf_springs"), - py::arg("add_loop_closure")) - .def("AddImuAndAggregator", &dairlib::AddImuAndAggregator, - py::arg("builder"), py::arg("plant"), py::arg("actuation_port")); - - py::class_>(m, "SimCassieSensorAggregator") - .def(py::init&>()); + py::arg("add_loop_closure")); } } // namespace pydairlib From f888dda580512985e3cff3ffc4d1332615707756 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 13 Nov 2021 13:37:43 -0500 Subject: [PATCH 004/758] more plottig utils --- bindings/pydairlib/analysis/BUILD.bazel | 9 +- .../analysis/cassie_plotting_utils.py | 112 +++++++++--------- .../pydairlib/analysis/log_plotter_cassie.py | 12 +- bindings/pydairlib/analysis/osc_debug.py | 45 +++++++ 4 files changed, 116 insertions(+), 62 deletions(-) create mode 100644 bindings/pydairlib/analysis/osc_debug.py diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index b30d0c1ce1..796da9a030 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -13,7 +13,13 @@ load( py_library( name = "process_lcm_log_py", - srcs = [":process_lcm_log.py"], + srcs = ["process_lcm_log.py"], + deps = [], +) + +py_library( + name = "osc_debug_py", + srcs = ["osc_debug.py"], deps = [], ) @@ -25,6 +31,7 @@ py_library( "@lcm//:lcm-python", ], deps = [ + ":osc_debug_py", "//bindings/pydairlib/cassie:cassie_utils", "//bindings/pydairlib/common", "//bindings/pydairlib/common:plot_styler", diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index d8ce9c82f4..85e48f9181 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -1,6 +1,7 @@ # python imports import lcm import numpy as np +import matplotlib.pyplot as plt # dairlib imports import dairlib @@ -8,7 +9,7 @@ from pydairlib.common import FindResourceOrThrow from pydairlib.common import plot_styler from pydairlib.multibody import makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap - +from osc_debug import lcmt_osc_tracking_data_t # drake imports from pydrake.multibody.parsing import Parser @@ -19,48 +20,6 @@ cassie_urdf = "examples/Cassie/urdf/cassie_v2.urdf" cassie_urdf_no_springs = "examples/Cassie/urdf/cassie_fixed_springs.urdf" -# Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays -class lcmt_osc_tracking_data_t: - def __init__(self): - self.t = [] - self.y_dim = 0 - self.name = "" - self.is_active = [] - self.y = [] - self.y_des = [] - self.error_y = [] - self.ydot = [] - self.ydot_des = [] - self.error_ydot = [] - self.yddot_des = [] - self.yddot_command = [] - self.yddot_command_sol = [] - - def append(self, msg, t): - self.t.append(t) - self.is_active.append(msg.is_active) - self.y.append(msg.y) - self.y_des.append(msg.y_des) - self.error_y.append(msg.error_y) - self.ydot.append(msg.ydot) - self.ydot_des.append(msg.ydot_des) - self.error_ydot.append(msg.error_ydot) - self.yddot_des.append(msg.yddot_des) - self.yddot_command.append(msg.yddot_command) - self.yddot_command_sol.append(msg.yddot_command_sol) - - def convertToNP(self): - self.t = np.array(self.t) - self.is_active = np.array(self.is_active) - self.y = np.array(self.y) - self.y_des = np.array(self.y_des) - self.error_y = np.array(self.error_y) - self.ydot = np.array(self.ydot) - self.ydot_des = np.array(self.ydot_des) - self.error_ydot = np.array(self.error_ydot) - self.yddot_des = np.array(self.yddot_des) - self.yddot_command = np.array(self.yddot_command) - self.yddot_command_sol = np.array(self.yddot_command_sol) cassie_default_channels = \ {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, @@ -110,28 +69,67 @@ def process_state_channel(state_data, plant): u.append(u_temp) t_x.append(msg.utime / 1e6) - return np.array(t_x), np.array(q), np.array(v), np.array(u) + return {'t_x': np.array(t_x), + 'q': np.array(q), + 'v': np.array(v), + 'u': np.array(u)} -def process_effort_data(data): +def process_effort_channel(data): u = [] t = [] for msg in data: t.append(msg.utime / 1e6) u.append(msg.efforts) - return np.array(t), np.array(u) - + return {'t_u': np.array(t), 'u': np.array(u)} -def process_default_channels(data, plant, state_channel, input_channel, - osc_debug_channel): - t_x, q, v, u_meas = process_state_channel(data[state_channel], plant) - t_u, u = process_effort_data(data[input_channel]) +def process_osc_channel(data): + t_osc = [] + osc_output = [] + osc_debug_tracking_datas = {} + fsm = [] - return {'t_x': t_x, - 'q': q, - 'v': v, - 'u_meas': u_meas, - 't_u': t_u, - 'u': u} + for msg in data: + t_osc.append(msg.utime / 1e6) + osc_output.append(msg) + num_osc_tracking_data = len(msg.tracking_data) + for i in range(num_osc_tracking_data): + if msg.tracking_data[i].name not in osc_debug_tracking_datas: + osc_debug_tracking_datas[msg.tracking_data[i].name] = \ + lcmt_osc_tracking_data_t() + osc_debug_tracking_datas[msg.tracking_data[i].name].append( + msg.tracking_data[i], msg.utime / 1e6) + fsm.append(msg.fsm_state) + + for name in osc_debug_tracking_datas.keys(): + osc_debug_tracking_datas[name] = \ + osc_debug_tracking_datas[name].convertToNP() + + return {'t_osc': t_osc, + 'osc_output': osc_output, + 'osc_debug_tracking_datas': osc_debug_tracking_datas} + + +def load_default_channels(data, plant, state_channel, input_channel, + osc_debug_channel): + + robot_output = process_state_channel(data[state_channel], plant) + robot_input = process_effort_channel(data[input_channel]) + osc_debug = process_osc_channel(data[osc_debug_channel]) + + return robot_output, robot_input, osc_debug + + +def make_channel_plot(data_dictionary, time_key, keys_to_plot, legend_entries, + plot_labels, ps=plot_styler.PlotStyler()): + legend = [] + for key in keys_to_plot: + ps.plot(data_dictionary[time_key], data_dictionary[key]) + legend.extend(legend_entries[key]) + + plt.legend(legend) + plt.xlabel(plot_labels['xlabel']) + plt.ylabel(plot_labels['ylabel']) + plt.title(plot_labels['title']) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 322f81063d..a7f3420b46 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -10,9 +10,13 @@ plant, context = cassie_plotting_utils.make_plant_and_context() -data = get_log_data(log, cassie_plotting_utils.cassie_default_channels, - cassie_plotting_utils.process_default_channels, plant, - 'CASSIE_STATE_SIMULATION', 'CASSIE_INPUT', - 'OSC_DEBUG_WALKING') +robot_input, robot_output, osc_debug = \ + get_log_data(log, + cassie_plotting_utils.cassie_default_channels, + cassie_plotting_utils.load_default_channels, + plant, + 'CASSIE_STATE_SIMULATION', + 'CASSIE_INPUT', + 'OSC_DEBUG_WALKING') import pdb; pdb.set_trace() diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py new file mode 100644 index 0000000000..dcde3bf564 --- /dev/null +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -0,0 +1,45 @@ +import numpy as np + + +# Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays +class lcmt_osc_tracking_data_t: + def __init__(self): + self.t = [] + self.y_dim = 0 + self.name = "" + self.is_active = [] + self.y = [] + self.y_des = [] + self.error_y = [] + self.ydot = [] + self.ydot_des = [] + self.error_ydot = [] + self.yddot_des = [] + self.yddot_command = [] + self.yddot_command_sol = [] + + def append(self, msg, t): + self.t.append(t) + self.is_active.append(msg.is_active) + self.y.append(msg.y) + self.y_des.append(msg.y_des) + self.error_y.append(msg.error_y) + self.ydot.append(msg.ydot) + self.ydot_des.append(msg.ydot_des) + self.error_ydot.append(msg.error_ydot) + self.yddot_des.append(msg.yddot_des) + self.yddot_command.append(msg.yddot_command) + self.yddot_command_sol.append(msg.yddot_command_sol) + + def convertToNP(self): + self.t = np.array(self.t) + self.is_active = np.array(self.is_active) + self.y = np.array(self.y) + self.y_des = np.array(self.y_des) + self.error_y = np.array(self.error_y) + self.ydot = np.array(self.ydot) + self.ydot_des = np.array(self.ydot_des) + self.error_ydot = np.array(self.error_ydot) + self.yddot_des = np.array(self.yddot_des) + self.yddot_command = np.array(self.yddot_command) + self.yddot_command_sol = np.array(self.yddot_command_sol) \ No newline at end of file From adb2526996fd2cd68e1891f8ce7b225d39253579 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 13 Nov 2021 14:48:22 -0500 Subject: [PATCH 005/758] positions plotting --- .../analysis/cassie_plotting_utils.py | 48 +++++++++---- .../pydairlib/analysis/log_plotter_cassie.py | 70 +++++++++++++++---- 2 files changed, 94 insertions(+), 24 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 85e48f9181..76e69d25e6 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -31,14 +31,15 @@ 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output, 'OSC_DEBUG_RUNNING': dairlib.lcmt_osc_output} -def make_plant_and_context(floating=True, springs=True): +def make_plant_and_context(floating_base=True, springs=True): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) if (springs): - addCassieMultibody(plant, scene_graph, floating, cassie_urdf, True, True) + addCassieMultibody(plant, scene_graph, + floating_base, cassie_urdf, True, True) else: - addCassieMultibody(plant, scene_graph, floating, cassie_urdf_no_springs, - False, True) + addCassieMultibody(plant, scene_graph, + floating_base, cassie_urdf_no_springs, False, True) plant.Finalize() return plant, plant.CreateDefaultContext() @@ -69,10 +70,10 @@ def process_state_channel(state_data, plant): u.append(u_temp) t_x.append(msg.utime / 1e6) - return {'t_x': np.array(t_x), - 'q': np.array(q), - 'v': np.array(v), - 'u': np.array(u)} + return {'t_x': np.array(t_x), + 'q': np.array(q), + 'v': np.array(v), + 'u': np.array(u)} def process_effort_channel(data): @@ -114,7 +115,6 @@ def process_osc_channel(data): def load_default_channels(data, plant, state_channel, input_channel, osc_debug_channel): - robot_output = process_state_channel(data[state_channel], plant) robot_input = process_effort_channel(data[input_channel]) osc_debug = process_osc_channel(data[osc_debug_channel]) @@ -122,14 +122,38 @@ def load_default_channels(data, plant, state_channel, input_channel, return robot_output, robot_input, osc_debug -def make_channel_plot(data_dictionary, time_key, keys_to_plot, legend_entries, - plot_labels, ps=plot_styler.PlotStyler()): +def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, + slices_to_plot, legend_entries, plot_labels, + ps=plot_styler.PlotStyler()): + plt.figure() legend = [] for key in keys_to_plot: - ps.plot(data_dictionary[time_key], data_dictionary[key]) + if key not in slices_to_plot: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice]) + else: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice, slices_to_plot[key]]) legend.extend(legend_entries[key]) plt.legend(legend) plt.xlabel(plot_labels['xlabel']) plt.ylabel(plot_labels['ylabel']) plt.title(plot_labels['title']) + + +def make_mixed_data_plot(data_dictionaries, time_keys, keys_to_plot, + legend_entries, plot_labels, + ps=plot_styler.PlotStyler()): + plt.figure() + legend = [] + for i, data_dictionary in enumerate(data_dictionaries): + time_key = time_keys[i] + for key in keys_to_plot[i]: + ps.plot(data_dictionary[time_key], data_dictionary[key]) + legend.extend(legend_entries[key]) + + plt.legend(legend) + plt.xlabel(plot_labels['xlabel']) + plt.ylabel(plot_labels['ylabel']) + plt.title(plot_labels['title']) \ No newline at end of file diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index a7f3420b46..af27c20110 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -1,22 +1,68 @@ import sys import lcm +import matplotlib.pyplot as plt +import numpy as np + import dairlib +from pydairlib.multibody import createStateNameVectorFromMap from process_lcm_log import get_log_data, passthrough_callback import cassie_plotting_utils -filename = sys.argv[1] -log = lcm.EventLog(filename, "r") + +def main(): + filename = sys.argv[1] + log = lcm.EventLog(filename, "r") + + plant, context = cassie_plotting_utils.make_plant_and_context( + floating_base=True, springs=True) + + x_names = createStateNameVectorFromMap(plant) + q_names = x_names[:plant.num_positions()] + v_names = x_names[plant.num_positions():] + + robot_output, robot_input, osc_debug = \ + get_log_data(log, + cassie_plotting_utils.cassie_default_channels, + cassie_plotting_utils.load_default_channels, + plant, + 'CASSIE_STATE_SIMULATION', + 'CASSIE_INPUT', + 'OSC_DEBUG_STANDING') + + t_x_slice = slice(robot_output['t_x'].size) + + plot_floating_base_positions(robot_output, q_names, t_x_slice) + plot_joint_positions(robot_output, q_names, t_x_slice, floating_base=True) + + plt.show() + + +def plot_floating_base_positions(robot_output, q_names, time_slice): + cassie_plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + ['q'], # key to plot + {'q': slice(0, 7)}, # slice of 'q' to plot + {'q': q_names[:7]}, # legend entries + {'xlabel': 'Time', + 'ylabel': 'Position', + 'title': 'Floating Base Positions'}) -plant, context = cassie_plotting_utils.make_plant_and_context() +def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): + q_slice = slice(7, len(q_names)) if floating_base else slice(len(q_names)) + cassie_plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + ['q'], # key to plot + {'q': q_slice}, # slice of 'q' to plot + {'q': q_names[q_slice]}, # legend entries + {'xlabel': 'Time', + 'ylabel': 'Joint Angle (rad)', + 'title': 'Joint Positions'}) -robot_input, robot_output, osc_debug = \ - get_log_data(log, - cassie_plotting_utils.cassie_default_channels, - cassie_plotting_utils.load_default_channels, - plant, - 'CASSIE_STATE_SIMULATION', - 'CASSIE_INPUT', - 'OSC_DEBUG_WALKING') +if __name__ == '__main__': + main() -import pdb; pdb.set_trace() From d63a3bf46d87b8863d2f4fcf3d35058e5abaf4c5 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 13 Nov 2021 15:00:59 -0500 Subject: [PATCH 006/758] move plotting utils from casie to common --- .../analysis/cassie_plotting_utils.py | 62 ++++++++----------- .../pydairlib/analysis/log_plotter_cassie.py | 32 ++-------- bindings/pydairlib/common/BUILD.bazel | 7 +++ bindings/pydairlib/common/plotting_utils.py | 46 ++++++++++++++ 4 files changed, 83 insertions(+), 64 deletions(-) create mode 100644 bindings/pydairlib/common/plotting_utils.py diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 76e69d25e6..24e5f3f6fb 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -7,7 +7,7 @@ import dairlib from pydairlib.cassie.cassie_utils import * from pydairlib.common import FindResourceOrThrow -from pydairlib.common import plot_styler +from pydairlib.common import plot_styler, plotting_utils from pydairlib.multibody import makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap from osc_debug import lcmt_osc_tracking_data_t @@ -122,38 +122,28 @@ def load_default_channels(data, plant, state_channel, input_channel, return robot_output, robot_input, osc_debug -def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, - slices_to_plot, legend_entries, plot_labels, - ps=plot_styler.PlotStyler()): - plt.figure() - legend = [] - for key in keys_to_plot: - if key not in slices_to_plot: - ps.plot(data_dictionary[time_key][time_slice], - data_dictionary[key][time_slice]) - else: - ps.plot(data_dictionary[time_key][time_slice], - data_dictionary[key][time_slice, slices_to_plot[key]]) - legend.extend(legend_entries[key]) - - plt.legend(legend) - plt.xlabel(plot_labels['xlabel']) - plt.ylabel(plot_labels['ylabel']) - plt.title(plot_labels['title']) - - -def make_mixed_data_plot(data_dictionaries, time_keys, keys_to_plot, - legend_entries, plot_labels, - ps=plot_styler.PlotStyler()): - plt.figure() - legend = [] - for i, data_dictionary in enumerate(data_dictionaries): - time_key = time_keys[i] - for key in keys_to_plot[i]: - ps.plot(data_dictionary[time_key], data_dictionary[key]) - legend.extend(legend_entries[key]) - - plt.legend(legend) - plt.xlabel(plot_labels['xlabel']) - plt.ylabel(plot_labels['ylabel']) - plt.title(plot_labels['title']) \ No newline at end of file +def plot_floating_base_positions(robot_output, q_names, time_slice): + plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + ['q'], # key to plot + {'q': slice(0, 7)}, # slice of 'q' to plot + {'q': q_names[:7]}, # legend entries + {'xlabel': 'Time', + 'ylabel': 'Position', + 'title': 'Floating Base Positions'}) + + +def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): + q_slice = slice(7, len(q_names)) if floating_base else slice(len(q_names)) + plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + ['q'], # key to plot + {'q': q_slice}, # slice of 'q' to plot + {'q': q_names[q_slice]}, # legend entries + {'xlabel': 'Time', + 'ylabel': 'Joint Angle (rad)', + 'title': 'Joint Positions'}) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index af27c20110..beef915f98 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -31,38 +31,14 @@ def main(): t_x_slice = slice(robot_output['t_x'].size) - plot_floating_base_positions(robot_output, q_names, t_x_slice) - plot_joint_positions(robot_output, q_names, t_x_slice, floating_base=True) + cassie_plotting_utils.plot_floating_base_positions( + robot_output, q_names, t_x_slice) + cassie_plotting_utils.plot_joint_positions( + robot_output, q_names, t_x_slice, floating_base=True) plt.show() -def plot_floating_base_positions(robot_output, q_names, time_slice): - cassie_plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel - time_slice, - ['q'], # key to plot - {'q': slice(0, 7)}, # slice of 'q' to plot - {'q': q_names[:7]}, # legend entries - {'xlabel': 'Time', - 'ylabel': 'Position', - 'title': 'Floating Base Positions'}) - - -def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): - q_slice = slice(7, len(q_names)) if floating_base else slice(len(q_names)) - cassie_plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel - time_slice, - ['q'], # key to plot - {'q': q_slice}, # slice of 'q' to plot - {'q': q_names[q_slice]}, # legend entries - {'xlabel': 'Time', - 'ylabel': 'Joint Angle (rad)', - 'title': 'Joint Positions'}) - if __name__ == '__main__': main() diff --git a/bindings/pydairlib/common/BUILD.bazel b/bindings/pydairlib/common/BUILD.bazel index ce5eb0a79b..afb6f06951 100644 --- a/bindings/pydairlib/common/BUILD.bazel +++ b/bindings/pydairlib/common/BUILD.bazel @@ -34,6 +34,12 @@ py_library( ], ) +py_library( + name = "plotting_utils", + srcs = ["plotting_utils.py"], + deps = [], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") @@ -52,6 +58,7 @@ py_library( PY_LIBRARIES = [ ":common_py", ":plot_styler", + ":plotting_utils", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py new file mode 100644 index 0000000000..de513f6c86 --- /dev/null +++ b/bindings/pydairlib/common/plotting_utils.py @@ -0,0 +1,46 @@ +import matplotlib.pyplot as plt +import plot_styler + + +def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, + slices_to_plot, legend_entries, plot_labels, + ps=plot_styler.PlotStyler()): + plt.figure() + legend = [] + for key in keys_to_plot: + if key not in slices_to_plot: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice]) + else: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice, slices_to_plot[key]]) + legend.extend(legend_entries[key]) + + plt.legend(legend) + plt.xlabel(plot_labels['xlabel']) + plt.ylabel(plot_labels['ylabel']) + plt.title(plot_labels['title']) + + +def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, + keys_to_plot, slices_to_plot, + legend_entries, plot_labels, + ps=plot_styler.PlotStyler()): + plt.figure() + legend = [] + for i, data_dictionary in enumerate(data_dictionaries): + time_key = time_keys[i] + time_slice = time_slices[i] + for key in keys_to_plot[i]: + if key not in slices_to_plot[i]: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice]) + else: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice, slices_to_plot[key]]) + legend.extend(legend_entries[key]) + + plt.legend(legend) + plt.xlabel(plot_labels['xlabel']) + plt.ylabel(plot_labels['ylabel']) + plt.title(plot_labels['title']) From f6be32ac994fc0e376480543a290e98811c55b3b Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 13 Nov 2021 15:20:59 -0500 Subject: [PATCH 007/758] add option to plot individual joint positions --- .../pydairlib/analysis/cassie_plotting_utils.py | 14 ++++++++++++++ bindings/pydairlib/analysis/log_plotter_cassie.py | 11 ++++++++++- 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 24e5f3f6fb..303afc95aa 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -147,3 +147,17 @@ def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): {'xlabel': 'Time', 'ylabel': 'Joint Angle (rad)', 'title': 'Joint Positions'}) + + +def plot_joint_positions_by_name(robot_output, q_names, time_slice, pos_map): + q_slice = [pos_map[name] for name in q_names] + plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + ['q'], # key to plot + {'q': q_slice}, # slice of 'q' to plot + {'q': q_names}, # legend entries + {'xlabel': 'Time', + 'ylabel': 'Joint Angle (rad)', + 'title': 'Joint Positions'}) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index beef915f98..b2107d3311 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -4,7 +4,10 @@ import numpy as np import dairlib -from pydairlib.multibody import createStateNameVectorFromMap +from pydairlib.multibody import \ + createStateNameVectorFromMap, createActuatorNameVectorFromMap, \ + makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap + from process_lcm_log import get_log_data, passthrough_callback import cassie_plotting_utils @@ -16,7 +19,11 @@ def main(): plant, context = cassie_plotting_utils.make_plant_and_context( floating_base=True, springs=True) + pos_map = makeNameToPositionsMap(plant) + vel_map = makeNameToVelocitiesMap(plant) + act_map = makeNameToActuatorsMap(plant) x_names = createStateNameVectorFromMap(plant) + u_names = createActuatorNameVectorFromMap(plant) q_names = x_names[:plant.num_positions()] v_names = x_names[plant.num_positions():] @@ -35,6 +42,8 @@ def main(): robot_output, q_names, t_x_slice) cassie_plotting_utils.plot_joint_positions( robot_output, q_names, t_x_slice, floating_base=True) + cassie_plotting_utils.plot_joint_positions_by_name( + robot_output, ['knee_left', 'knee_right'], t_x_slice, pos_map) plt.show() From 7a804a00e188e45e67970c1d8bfbb5922673a9d9 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sun, 14 Nov 2021 17:12:05 -0500 Subject: [PATCH 008/758] minimum plotting script functionality --- .../analysis/cassie_plotting_utils.py | 80 ++++++++++++------- .../pydairlib/analysis/log_plotter_cassie.py | 69 +++++++++++----- .../pydairlib/analysis/process_lcm_log.py | 9 ++- 3 files changed, 107 insertions(+), 51 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 303afc95aa..c44a725b3c 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -122,42 +122,68 @@ def load_default_channels(data, plant, state_channel, input_channel, return robot_output, robot_input, osc_debug -def plot_floating_base_positions(robot_output, q_names, time_slice): +def plot_q_or_v_or_u( + robot_output, key, x_names, x_slice, time_slice, + ylabel=None, title=None): + + if ylabel is None: + ylabel = key + if title is None: + title = key + plotting_utils.make_plot( robot_output, # data dict 't_x', # time channel time_slice, - ['q'], # key to plot - {'q': slice(0, 7)}, # slice of 'q' to plot - {'q': q_names[:7]}, # legend entries + [key], # key to plot + {key: x_slice}, # slice of 'q' to plot + {key: x_names}, # legend entries {'xlabel': 'Time', - 'ylabel': 'Position', - 'title': 'Floating Base Positions'}) + 'ylabel': ylabel, + 'title': title}) + + +def plot_floating_base_positions(robot_output, q_names, time_slice): + plot_q_or_v_or_u(robot_output, 'q', q_names[:7], slice(7), time_slice, + ylabel='Position', title='Floating Base Positions') def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): q_slice = slice(7, len(q_names)) if floating_base else slice(len(q_names)) - plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel - time_slice, - ['q'], # key to plot - {'q': q_slice}, # slice of 'q' to plot - {'q': q_names[q_slice]}, # legend entries - {'xlabel': 'Time', - 'ylabel': 'Joint Angle (rad)', - 'title': 'Joint Positions'}) + plot_q_or_v_or_u(robot_output, 'q', q_names[q_slice], q_slice, time_slice, + ylabel='Joint Angle (rad)', title='Joint Positions') -def plot_joint_positions_by_name(robot_output, q_names, time_slice, pos_map): +def plot_positions_by_name(robot_output, q_names, time_slice, pos_map): q_slice = [pos_map[name] for name in q_names] - plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel - time_slice, - ['q'], # key to plot - {'q': q_slice}, # slice of 'q' to plot - {'q': q_names}, # legend entries - {'xlabel': 'Time', - 'ylabel': 'Joint Angle (rad)', - 'title': 'Joint Positions'}) + plot_q_or_v_or_u(robot_output, 'q', q_names, q_slice, time_slice, + ylabel='Position', title='Select Positions') + + +def plot_floating_base_velocities(robot_output, v_names, time_slice): + plot_q_or_v_or_u(robot_output, 'v', v_names[:6], slice(6), time_slice, + ylabel='Velocity', title='Floating Base Velocities') + + +def plot_joint_velocities(robot_output, v_names, + time_slice, floating_base=True): + q_slice = slice(6, len(v_names)) if floating_base else slice(len(v_names)) + plot_q_or_v_or_u(robot_output, 'v', v_names[q_slice], q_slice, time_slice, + ylabel='Joint Vel (rad/s)', title='Joint Velocities') + + +def plot_velocities_by_name(robot_output, v_names, time_slice, vel_map): + v_slice = [vel_map[name] for name in v_names] + plot_q_or_v_or_u(robot_output, 'v', v_names, v_slice, time_slice, + ylabel='Velocity', title='Select Velocities') + + +def plot_measured_efforts(robot_output, u_names, time_slice): + plot_q_or_v_or_u(robot_output, 'u', u_names, slice(len(u_names)), + time_slice, ylabel='Efforts (Nm)', title='Joint Efforts') + + +def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): + u_slice = [u_map[name] for name in u_names] + plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, + time_slice, ylabel='Efforts (Nm)', title='Select Joint Efforts') diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index b2107d3311..bde5d9f9a4 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -8,16 +8,21 @@ createStateNameVectorFromMap, createActuatorNameVectorFromMap, \ makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap -from process_lcm_log import get_log_data, passthrough_callback -import cassie_plotting_utils +from process_lcm_log import get_log_data +import cassie_plotting_utils as cassie_plots def main(): - filename = sys.argv[1] - log = lcm.EventLog(filename, "r") - plant, context = cassie_plotting_utils.make_plant_and_context( - floating_base=True, springs=True) + # Global settings for plotting + use_floating_base = True + use_springs = True + channel_x = 'CASSIE_STATE_SIMULATION' + channel_u = 'CASSIE_INPUT' + channel_osc = 'OSC_DEBUG_STANDING' + + plant, context = cassie_plots.make_plant_and_context( + floating_base=use_floating_base, springs=use_springs) pos_map = makeNameToPositionsMap(plant) vel_map = makeNameToVelocitiesMap(plant) @@ -27,27 +32,51 @@ def main(): q_names = x_names[:plant.num_positions()] v_names = x_names[plant.num_positions():] + ''' Read the log ''' + filename = sys.argv[1] + log = lcm.EventLog(filename, "r") robot_output, robot_input, osc_debug = \ - get_log_data(log, - cassie_plotting_utils.cassie_default_channels, - cassie_plotting_utils.load_default_channels, - plant, - 'CASSIE_STATE_SIMULATION', - 'CASSIE_INPUT', - 'OSC_DEBUG_STANDING') + get_log_data(log, # log + cassie_plots.cassie_default_channels, # lcm channels + cassie_plots.load_default_channels, # processing callback + plant, channel_x, channel_u, channel_osc) # processing callback arguments + # Define x time slice t_x_slice = slice(robot_output['t_x'].size) - cassie_plotting_utils.plot_floating_base_positions( - robot_output, q_names, t_x_slice) - cassie_plotting_utils.plot_joint_positions( - robot_output, q_names, t_x_slice, floating_base=True) - cassie_plotting_utils.plot_joint_positions_by_name( - robot_output, ['knee_left', 'knee_right'], t_x_slice, pos_map) + ''' Plot Positions ''' + # Plot floating base positions if applicable + if use_floating_base: + cassie_plots.plot_floating_base_positions( + robot_output, q_names, t_x_slice) + # Plot all joint positions + cassie_plots.plot_joint_positions(robot_output, q_names, t_x_slice, + floating_base=use_floating_base) + # Plot specific positions + cassie_plots.plot_positions_by_name(robot_output, + ['knee_left', 'knee_right'], + t_x_slice, pos_map) + + ''' Plot Velocities ''' + # Plot floating base velocities if applicable + if use_floating_base: + cassie_plots.plot_floating_base_velocities( + robot_output, v_names, t_x_slice) + + # Plot all joint velocities + cassie_plots.plot_joint_velocities(robot_output, v_names, t_x_slice, + floating_base=use_floating_base) + # Plot specific velocities + cassie_plots.plot_velocities_by_name(robot_output, ['base_vz'], t_x_slice, vel_map) + + ''' Plot Efforts ''' + cassie_plots.plot_measured_efforts(robot_output, u_names, t_x_slice) + cassie_plots.plot_measured_efforts_by_name(robot_output, + ['knee_left_motor'], + t_x_slice, act_map) plt.show() if __name__ == '__main__': main() - diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/analysis/process_lcm_log.py index c37b6b8ba6..877db90dc4 100644 --- a/bindings/pydairlib/analysis/process_lcm_log.py +++ b/bindings/pydairlib/analysis/process_lcm_log.py @@ -3,12 +3,13 @@ def get_log_data(lcm_log, lcm_channels, data_processing_callback, *args, **kwargs): """ - Parses an LCM log and returns a dictionary with entries + Parses an LCM log and returns a data as specified by callback function :param lcm_log: an lcm.EventLog object - :param lcm_channels: dictionary of {channel : lcmtype} of channels to be read from the log + :param lcm_channels: dictionary with entries {channel : lcmtype} of channels + to be read from the log :param data_processing_callback: function pointer which takes as arguments - (data, args, kwargs) and where data is a dictionary with - entries {CHANNEL : [ msg for lcm msg in log with msg.channel == CHANNEL} + (data, args, kwargs) where data is a dictionary with + entries {CHANNEL : [ msg for lcm msg in log with msg.channel == CHANNEL ] } :param args: positional arguments for data_processing_callback :param kwargs: keyword arguments for data_processing_callback :return: { label : xdata, ydata } returned by data_processing_callback From 896a1166c94ffd3df763066248474280fb9e23d7 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sun, 14 Nov 2021 18:05:40 -0500 Subject: [PATCH 009/758] cleanup main --- .../analysis/cassie_plotting_utils.py | 16 ++++++++++- .../pydairlib/analysis/log_plotter_cassie.py | 28 +++++++++---------- .../pydairlib/analysis/process_lcm_log.py | 4 +-- 3 files changed, 30 insertions(+), 18 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index c44a725b3c..071b0e0ce7 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -8,7 +8,9 @@ from pydairlib.cassie.cassie_utils import * from pydairlib.common import FindResourceOrThrow from pydairlib.common import plot_styler, plotting_utils -from pydairlib.multibody import makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap +from pydairlib.multibody import makeNameToPositionsMap,\ + makeNameToVelocitiesMap, makeNameToActuatorsMap, \ + createStateNameVectorFromMap, createActuatorNameVectorFromMap from osc_debug import lcmt_osc_tracking_data_t # drake imports @@ -45,6 +47,18 @@ def make_plant_and_context(floating_base=True, springs=True): return plant, plant.CreateDefaultContext() +def make_name_to_mbp_maps(plant): + return makeNameToPositionsMap(plant), \ + makeNameToVelocitiesMap(plant), \ + makeNameToActuatorsMap + +def make_mbp_name_vectors(plant): + x_names = createStateNameVectorFromMap(plant) + u_names = createActuatorNameVectorFromMap(plant) + q_names = x_names[:plant.num_positions()] + v_names = x_names[plant.num_positions():] + return q_names, v_names, u_names + def process_state_channel(state_data, plant): t_x = [] q = [] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index bde5d9f9a4..25b1738575 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -5,8 +5,7 @@ import dairlib from pydairlib.multibody import \ - createStateNameVectorFromMap, createActuatorNameVectorFromMap, \ - makeNameToPositionsMap, makeNameToVelocitiesMap, makeNameToActuatorsMap + createStateNameVectorFromMap, createActuatorNameVectorFromMap, from process_lcm_log import get_log_data import cassie_plotting_utils as cassie_plots @@ -17,20 +16,19 @@ def main(): # Global settings for plotting use_floating_base = True use_springs = True + + # TODO: get these channels automatically from reading the log channel_x = 'CASSIE_STATE_SIMULATION' channel_u = 'CASSIE_INPUT' channel_osc = 'OSC_DEBUG_STANDING' + ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( floating_base=use_floating_base, springs=use_springs) - pos_map = makeNameToPositionsMap(plant) - vel_map = makeNameToVelocitiesMap(plant) - act_map = makeNameToActuatorsMap(plant) - x_names = createStateNameVectorFromMap(plant) - u_names = createActuatorNameVectorFromMap(plant) - q_names = x_names[:plant.num_positions()] - v_names = x_names[plant.num_positions():] + pos_map, vel_map, act_map = cassie_plots.make_name_to_mbp_maps(plant) + pos_names, vel_names, act_names = cassie_plots.make_mbp_name_vectors(plant) + ''' Read the log ''' filename = sys.argv[1] @@ -48,10 +46,10 @@ def main(): # Plot floating base positions if applicable if use_floating_base: cassie_plots.plot_floating_base_positions( - robot_output, q_names, t_x_slice) + robot_output, pos_names, t_x_slice) - # Plot all joint positions - cassie_plots.plot_joint_positions(robot_output, q_names, t_x_slice, + # Plot joint positions + cassie_plots.plot_joint_positions(robot_output, pos_names, t_x_slice, floating_base=use_floating_base) # Plot specific positions cassie_plots.plot_positions_by_name(robot_output, @@ -62,16 +60,16 @@ def main(): # Plot floating base velocities if applicable if use_floating_base: cassie_plots.plot_floating_base_velocities( - robot_output, v_names, t_x_slice) + robot_output, vel_names, t_x_slice) # Plot all joint velocities - cassie_plots.plot_joint_velocities(robot_output, v_names, t_x_slice, + cassie_plots.plot_joint_velocities(robot_output, vel_names, t_x_slice, floating_base=use_floating_base) # Plot specific velocities cassie_plots.plot_velocities_by_name(robot_output, ['base_vz'], t_x_slice, vel_map) ''' Plot Efforts ''' - cassie_plots.plot_measured_efforts(robot_output, u_names, t_x_slice) + cassie_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) cassie_plots.plot_measured_efforts_by_name(robot_output, ['knee_left_motor'], t_x_slice, act_map) diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/analysis/process_lcm_log.py index 877db90dc4..2ad66c63e5 100644 --- a/bindings/pydairlib/analysis/process_lcm_log.py +++ b/bindings/pydairlib/analysis/process_lcm_log.py @@ -3,7 +3,7 @@ def get_log_data(lcm_log, lcm_channels, data_processing_callback, *args, **kwargs): """ - Parses an LCM log and returns a data as specified by callback function + Parses an LCM log and returns data as specified by a callback function :param lcm_log: an lcm.EventLog object :param lcm_channels: dictionary with entries {channel : lcmtype} of channels to be read from the log @@ -12,7 +12,7 @@ def get_log_data(lcm_log, lcm_channels, data_processing_callback, *args, entries {CHANNEL : [ msg for lcm msg in log with msg.channel == CHANNEL ] } :param args: positional arguments for data_processing_callback :param kwargs: keyword arguments for data_processing_callback - :return: { label : xdata, ydata } returned by data_processing_callback + :return: return args of data_processing_callback """ data_to_process = {} From 4a1e9d14771aa502300c754500327f70ab94f43d Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sun, 14 Nov 2021 18:29:59 -0500 Subject: [PATCH 010/758] typo fix --- bindings/pydairlib/analysis/cassie_plotting_utils.py | 3 ++- bindings/pydairlib/analysis/log_plotter_cassie.py | 3 --- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 071b0e0ce7..53fdee9462 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -50,7 +50,8 @@ def make_plant_and_context(floating_base=True, springs=True): def make_name_to_mbp_maps(plant): return makeNameToPositionsMap(plant), \ makeNameToVelocitiesMap(plant), \ - makeNameToActuatorsMap + makeNameToActuatorsMap(plant) + def make_mbp_name_vectors(plant): x_names = createStateNameVectorFromMap(plant) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 25b1738575..0d043c92f5 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -4,9 +4,6 @@ import numpy as np import dairlib -from pydairlib.multibody import \ - createStateNameVectorFromMap, createActuatorNameVectorFromMap, - from process_lcm_log import get_log_data import cassie_plotting_utils as cassie_plots From 6ba85f8b39bd6724b686bf78ab602da3fc65e220 Mon Sep 17 00:00:00 2001 From: Brian Acosta <64998779+Brian-Acosta@users.noreply.github.com> Date: Sun, 14 Nov 2021 18:56:30 -0500 Subject: [PATCH 011/758] Adding a readme for the plotting script --- bindings/pydairlib/analysis/README.md | 20 ++++++++++++++++++++ 1 file changed, 20 insertions(+) create mode 100644 bindings/pydairlib/analysis/README.md diff --git a/bindings/pydairlib/analysis/README.md b/bindings/pydairlib/analysis/README.md new file mode 100644 index 0000000000..47463f3dc9 --- /dev/null +++ b/bindings/pydairlib/analysis/README.md @@ -0,0 +1,20 @@ +# Cassie Log Plotting Script Technical Notes + +## Reading LCM messages +To read and process lcm messages from a set of channels, a dictionary of these channels (keys) and their lcm types (items) and a corresponding processing callback function must be passed to `process_lcm_log.get_log_data()`. See `load_default_channels` in `cassie_plotting_utils` as an example callback function. + +## Default channels +*`load_default_channels`* returns the following three dictionaries, whose structure mirrors the lcm channels which their data comes from. + +### `robot_output` +This contains the robots state and *measured* inputs and timestamps, each as a numpy array where the row is the time dimension and the column is the position/velocity index. + +Dict keys: `'t_x', 'q', 'v', 'u'` + +### `robot input` +This contains the commanded inputs and timestamps. + +Dict keys: `'t_u', 'u'` + +### `osc_debug` +This contains the osc debug timestamps, the osc debug lcm messages, and a list of osc tracking datas in the same conveniece class we have been using. Implementation of further processing functions for the OSC is ongoing. From 4393e62053e90278d48cb698be702a424a0169e9 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 15 Nov 2021 11:56:23 -0500 Subject: [PATCH 012/758] modified plot styler to maintain it's own figure --- .../analysis/cassie_plotting_utils.py | 47 ++++++++++++------- .../pydairlib/analysis/log_plotter_cassie.py | 3 +- bindings/pydairlib/common/plot_styler.py | 14 ++++-- bindings/pydairlib/common/plotting_utils.py | 10 ++-- 4 files changed, 45 insertions(+), 29 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 53fdee9462..c878a27911 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -137,10 +137,14 @@ def load_default_channels(data, plant, state_channel, input_channel, return robot_output, robot_input, osc_debug +def load_state_channel(data, plant, state_channel): + return process_state_channel(data[state_channel], plant) + + def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, ylabel=None, title=None): - + ps = plot_styler.PlotStyler() if ylabel is None: ylabel = key if title is None: @@ -155,50 +159,57 @@ def plot_q_or_v_or_u( {key: x_names}, # legend entries {'xlabel': 'Time', 'ylabel': ylabel, - 'title': title}) + 'title': title}, ps) + return ps def plot_floating_base_positions(robot_output, q_names, time_slice): - plot_q_or_v_or_u(robot_output, 'q', q_names[:7], slice(7), time_slice, - ylabel='Position', title='Floating Base Positions') + return plot_q_or_v_or_u(robot_output, 'q', q_names[:7], slice(7), + time_slice, ylabel='Position', + title='Floating Base Positions') def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): q_slice = slice(7, len(q_names)) if floating_base else slice(len(q_names)) - plot_q_or_v_or_u(robot_output, 'q', q_names[q_slice], q_slice, time_slice, - ylabel='Joint Angle (rad)', title='Joint Positions') + return plot_q_or_v_or_u(robot_output, 'q', q_names[q_slice], q_slice, + time_slice, ylabel='Joint Angle (rad)', + title='Joint Positions') def plot_positions_by_name(robot_output, q_names, time_slice, pos_map): q_slice = [pos_map[name] for name in q_names] - plot_q_or_v_or_u(robot_output, 'q', q_names, q_slice, time_slice, - ylabel='Position', title='Select Positions') + return plot_q_or_v_or_u(robot_output, 'q', q_names, q_slice, time_slice, + ylabel='Position', title='Select Positions') def plot_floating_base_velocities(robot_output, v_names, time_slice): - plot_q_or_v_or_u(robot_output, 'v', v_names[:6], slice(6), time_slice, - ylabel='Velocity', title='Floating Base Velocities') + return plot_q_or_v_or_u(robot_output, 'v', v_names[:6], slice(6), + time_slice, ylabel='Velocity', + title='Floating Base Velocities') def plot_joint_velocities(robot_output, v_names, time_slice, floating_base=True): q_slice = slice(6, len(v_names)) if floating_base else slice(len(v_names)) - plot_q_or_v_or_u(robot_output, 'v', v_names[q_slice], q_slice, time_slice, - ylabel='Joint Vel (rad/s)', title='Joint Velocities') + return plot_q_or_v_or_u(robot_output, 'v', v_names[q_slice], q_slice, + time_slice, ylabel='Joint Vel (rad/s)', + title='Joint Velocities') def plot_velocities_by_name(robot_output, v_names, time_slice, vel_map): v_slice = [vel_map[name] for name in v_names] - plot_q_or_v_or_u(robot_output, 'v', v_names, v_slice, time_slice, - ylabel='Velocity', title='Select Velocities') + return plot_q_or_v_or_u(robot_output, 'v', v_names, v_slice, time_slice, + ylabel='Velocity', title='Select Velocities') def plot_measured_efforts(robot_output, u_names, time_slice): - plot_q_or_v_or_u(robot_output, 'u', u_names, slice(len(u_names)), - time_slice, ylabel='Efforts (Nm)', title='Joint Efforts') + return plot_q_or_v_or_u(robot_output, 'u', u_names, slice(len(u_names)), + time_slice, ylabel='Efforts (Nm)', + title='Joint Efforts') def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): u_slice = [u_map[name] for name in u_names] - plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, - time_slice, ylabel='Efforts (Nm)', title='Select Joint Efforts') + return plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, + time_slice, ylabel='Efforts (Nm)', + title='Select Joint Efforts') diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 0d043c92f5..6688b08467 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -1,6 +1,7 @@ import sys import lcm import matplotlib.pyplot as plt +import code import numpy as np import dairlib @@ -22,11 +23,9 @@ def main(): ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( floating_base=use_floating_base, springs=use_springs) - pos_map, vel_map, act_map = cassie_plots.make_name_to_mbp_maps(plant) pos_names, vel_names, act_names = cassie_plots.make_mbp_name_vectors(plant) - ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 75362e448f..34d1f8ce9a 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -9,7 +9,7 @@ class PlotStyler(): - def __init__(self): + def __init__(self, figure=None): # self.cmap = plt.get_cmap('tab10') self.cmap = plt.get_cmap('tab20') self.blue = '#011F5B' @@ -18,9 +18,13 @@ def __init__(self): self.grey = '#909090' self.orange = '#FE7F0E' self.directory = None + self.fig = plt.figure() if figure is None else figure + self.fig_id = self.fig.number + return def set_default_styling(self, directory=None): + plt.figure(self.fig_id) self.directory = directory matplotlib.rcParams["savefig.directory"] = directory matplotlib.rcParams['text.latex.preamble'] = [r"\usepackage{amsmath}"] @@ -37,6 +41,7 @@ def set_default_styling(self, directory=None): def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, linestyle=None, grid=True, xlabel=None, ylabel=None, title=None, legend=None, data_label=None): + plt.figure(self.fig_id) plt.plot(xdata, ydata, color=color, linestyle=linestyle, label=data_label) if xlim: plt.xlim(xlim) @@ -57,6 +62,7 @@ def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, linestyle=None, plt.grid(grid, which='major') def plot_bands(self, x_low, x_high, y_low, y_high, color='C0'): + plt.figure(self.fig_id) vertices = np.block([[x_low, x_high[::-1]], [y_low, y_high[::-1]]]).T codes = Path.LINETO * np.ones(len(vertices), dtype=Path.code_type) @@ -68,19 +74,21 @@ def plot_bands(self, x_low, x_high, y_low, y_high, color='C0'): ax.add_patch(patch) def show_fig(self): - plt.show() + self.fig.show() return def save_fig(self, filename): - + plt.figure(self.fig_id) plt.savefig(self.directory + filename, dpi=200) return def add_legend(self, legend, loc=0): + plt.figure(self.fig_id) plt.legend(legend, loc=loc) return def annotate(self, text, x, y, x_text, y_text, arrowprops=None): + plt.figure(self.fig_id) ax = plt.gca() if not arrowprops: arrowprops = dict(facecolor='black') # arrowstyle='->' diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index de513f6c86..f1db79f65c 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -4,8 +4,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, slices_to_plot, legend_entries, plot_labels, - ps=plot_styler.PlotStyler()): - plt.figure() + ps): legend = [] for key in keys_to_plot: if key not in slices_to_plot: @@ -16,7 +15,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, data_dictionary[key][time_slice, slices_to_plot[key]]) legend.extend(legend_entries[key]) - plt.legend(legend) + ps.add_legend(legend) plt.xlabel(plot_labels['xlabel']) plt.ylabel(plot_labels['ylabel']) plt.title(plot_labels['title']) @@ -25,8 +24,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, keys_to_plot, slices_to_plot, legend_entries, plot_labels, - ps=plot_styler.PlotStyler()): - plt.figure() + ps): legend = [] for i, data_dictionary in enumerate(data_dictionaries): time_key = time_keys[i] @@ -40,7 +38,7 @@ def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, data_dictionary[key][time_slice, slices_to_plot[key]]) legend.extend(legend_entries[key]) - plt.legend(legend) + ps.add_legend(legend) plt.xlabel(plot_labels['xlabel']) plt.ylabel(plot_labels['ylabel']) plt.title(plot_labels['title']) From 69d5c7b72915ad62adaccef745a019b018df6778 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 15 Nov 2021 13:45:53 -0500 Subject: [PATCH 013/758] add method to reattach plot styler figure --- bindings/pydairlib/common/plot_styler.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 34d1f8ce9a..8ed4dc8702 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -23,6 +23,9 @@ def __init__(self, figure=None): return + def attach(self): + plt.figure(self.fig_id) + def set_default_styling(self, directory=None): plt.figure(self.fig_id) self.directory = directory From 431289651687950a37ea4c0a2a50c3de27025a9e Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Thu, 18 Nov 2021 13:21:06 -0500 Subject: [PATCH 014/758] more tracking_costs --- .../analysis/cassie_plotting_utils.py | 67 +++++++++++++++---- .../pydairlib/analysis/log_plotter_cassie.py | 5 +- bindings/pydairlib/analysis/osc_debug.py | 24 ++++++- bindings/pydairlib/common/plotting_utils.py | 2 +- 4 files changed, 83 insertions(+), 15 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index c878a27911..a02285b66e 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -11,7 +11,7 @@ from pydairlib.multibody import makeNameToPositionsMap,\ makeNameToVelocitiesMap, makeNameToActuatorsMap, \ createStateNameVectorFromMap, createActuatorNameVectorFromMap -from osc_debug import lcmt_osc_tracking_data_t +from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost # drake imports from pydrake.multibody.parsing import Parser @@ -103,29 +103,50 @@ def process_effort_channel(data): def process_osc_channel(data): t_osc = [] + input_cost = [] + accel_cost = [] + soft_constraint_cost = [] + qp_solve_time = [] + u_sol = [] osc_output = [] - osc_debug_tracking_datas = {} fsm = [] + osc_debug_tracking_datas = {} for msg in data: t_osc.append(msg.utime / 1e6) + input_cost.append(msg.input_cost) + accel_cost.append(msg.acceleration_cost) + soft_constraint_cost.append(msg.soft_constraint_cost) + qp_solve_time.append(msg.qp_output.solve_time) + u_sol.append(msg.qp_output.u_sol) osc_output.append(msg) - num_osc_tracking_data = len(msg.tracking_data) - for i in range(num_osc_tracking_data): - if msg.tracking_data[i].name not in osc_debug_tracking_datas: - osc_debug_tracking_datas[msg.tracking_data[i].name] = \ + for tracking_data in msg.tracking_data: + if tracking_data.name not in osc_debug_tracking_datas: + osc_debug_tracking_datas[tracking_data.name] = \ lcmt_osc_tracking_data_t() - osc_debug_tracking_datas[msg.tracking_data[i].name].append( - msg.tracking_data[i], msg.utime / 1e6) + osc_debug_tracking_datas[tracking_data.name].append( + tracking_data, msg.utime / 1e6) + fsm.append(msg.fsm_state) - for name in osc_debug_tracking_datas.keys(): + tracking_cost_handler = osc_tracking_cost(osc_debug_tracking_datas.keys()) + for msg in data: + tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_cost) + tracking_cost = tracking_cost_handler.convertToNP() + + for name in osc_debug_tracking_datas: osc_debug_tracking_datas[name] = \ osc_debug_tracking_datas[name].convertToNP() - return {'t_osc': t_osc, + return {'t_osc': np.array(t_osc), + 'input_cost': np.array(input_cost), + 'acceleration_cost': np.array(accel_cost), + 'soft_constraint_cost': np.array(soft_constraint_cost), + 'qp_solve_time': np.array(qp_solve_time), 'osc_output': osc_output, - 'osc_debug_tracking_datas': osc_debug_tracking_datas} + 'tracking_cost': tracking_cost, + 'osc_debug_tracking_datas': osc_debug_tracking_datas, + 'fsm': np.array(fsm)} def load_default_channels(data, plant, state_channel, input_channel, @@ -155,7 +176,7 @@ def plot_q_or_v_or_u( 't_x', # time channel time_slice, [key], # key to plot - {key: x_slice}, # slice of 'q' to plot + {key: x_slice}, # slice of key to plot {key: x_names}, # legend entries {'xlabel': 'Time', 'ylabel': ylabel, @@ -213,3 +234,25 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): return plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, time_slice, ylabel='Efforts (Nm)', title='Select Joint Efforts') + + +def plot_tracking_costs(osc_debug, time_slice): + ps = plot_styler.PlotStyler() + data_dict = osc_debug['tracking_cost'] + data_dict['t_osc'] = osc_debug['t_osc'] + import pdb; pdb.set_trace() + plotting_utils.make_plot( + data_dict, + 't_osc', + time_slice, + osc_debug['tracking_cost'].keys(), + {}, + {key: [key] for key in osc_debug['tracking_cost'].keys()}, + {'xlabel': 'Time', + 'ylabel': 'Cost', + 'title': 'tracking_costs'}, ps) + return ps + + +def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): + ps.plot(fsm_time, scale*fsm_signal) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 6688b08467..28d896f85a 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -18,7 +18,7 @@ def main(): # TODO: get these channels automatically from reading the log channel_x = 'CASSIE_STATE_SIMULATION' channel_u = 'CASSIE_INPUT' - channel_osc = 'OSC_DEBUG_STANDING' + channel_osc = 'OSC_DEBUG_WALKING' ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( @@ -37,6 +37,7 @@ def main(): # Define x time slice t_x_slice = slice(robot_output['t_x'].size) + t_osc_slice = slice(osc_debug['t_osc'].size) ''' Plot Positions ''' # Plot floating base positions if applicable @@ -69,6 +70,8 @@ def main(): cassie_plots.plot_measured_efforts_by_name(robot_output, ['knee_left_motor'], t_x_slice, act_map) + + cassie_plots.plot_tracking_costs(osc_debug, t_osc_slice) plt.show() diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index dcde3bf564..823ffee97b 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -42,4 +42,26 @@ def convertToNP(self): self.error_ydot = np.array(self.error_ydot) self.yddot_des = np.array(self.yddot_des) self.yddot_command = np.array(self.yddot_command) - self.yddot_command_sol = np.array(self.yddot_command_sol) \ No newline at end of file + self.yddot_command_sol = np.array(self.yddot_command_sol) + + +class osc_tracking_cost(): + + def __init__(self, tracking_data_names): + + self.tracking_costs = {} + for name in tracking_data_names: + self.tracking_costs[name] = [] + + def append(self, tracking_data_list, tracking_cost_list): + for name, cost in zip(tracking_data_list, tracking_cost_list): + self.tracking_costs[name].append(cost) + + for name in self.tracking_costs: + if name not in tracking_cost_list: + self.tracking_costs[name].append(0.0) + + def convertToNP(self): + for name in self.tracking_costs: + self.tracking_costs[name] = np.array(self.tracking_costs[name]) + return self.tracking_costs diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index f1db79f65c..a8ef70837b 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -15,7 +15,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, data_dictionary[key][time_slice, slices_to_plot[key]]) legend.extend(legend_entries[key]) - ps.add_legend(legend) + plt.legend(legend) plt.xlabel(plot_labels['xlabel']) plt.ylabel(plot_labels['ylabel']) plt.title(plot_labels['title']) From 62bd164b4b37b789b2e515678b8589825c32ed9f Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Nov 2021 13:23:42 -0500 Subject: [PATCH 015/758] first pass on porting over running and box jumping controller --- examples/Cassie/BUILD.bazel | 92 +- examples/Cassie/multibody_sim.cc | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 44 +- examples/Cassie/osc_jump/BUILD.bazel | 5 +- .../osc_jump/convert_traj_for_controller.cc | 64 +- .../osc_jump/flight_foot_traj_generator.cc | 38 +- .../osc_jump/flight_foot_traj_generator.h | 9 +- .../osc_jump/jumping_event_based_fsm.cc | 35 +- .../Cassie/osc_jump/jumping_event_based_fsm.h | 14 +- examples/Cassie/osc_jump/osc_jumping_gains.h | 15 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 63 +- .../osc_jump/pelvis_trans_traj_generator.cc | 24 +- .../osc_jump/pelvis_trans_traj_generator.h | 3 +- .../osc_jump/toe_angle_traj_generator.cc | 26 +- .../osc_jump/toe_angle_traj_generator.h | 6 +- examples/Cassie/run_dircon_jumping.cc | 1156 +++++++++-------- examples/Cassie/run_osc_jumping_controller.cc | 149 ++- examples/Cassie/visualize_trajectory.cc | 59 +- .../impact_aware_time_based_fsm.cc | 51 +- .../impact_aware_time_based_fsm.h | 12 +- lcm/dircon_saved_trajectory.cc | 118 +- lcm/dircon_saved_trajectory.h | 53 +- lcm/lcm_trajectory.cc | 1 + lcm/lcm_trajectory.h | 9 +- solvers/BUILD.bazel | 20 +- systems/controllers/osc/BUILD.bazel | 8 + .../osc/joint_space_tracking_data.cc | 2 +- .../osc/operational_space_control.cc | 144 +- .../osc/operational_space_control.h | 40 +- systems/controllers/osc/osc_tracking_data.cc | 3 +- .../osc/relative_translation_tracking_data.cc | 2 +- .../osc/trans_space_tracking_data.cc | 3 + systems/framework/BUILD.bazel | 2 + .../trajectory_optimization/dircon/dircon.h | 4 +- 34 files changed, 1428 insertions(+), 848 deletions(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 78399ea16f..028b7911ca 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -44,6 +44,9 @@ cc_library( "//examples/Cassie:dispatcher_robot_in", "//examples/Cassie:dispatcher_robot_out", "//examples/Cassie:multibody_sim", + "//examples/Cassie:run_controller_switch", + "//examples/Cassie:run_osc_jumping_controller", + "//examples/Cassie:run_osc_running_controller", "//examples/Cassie:run_osc_standing_controller", "//examples/Cassie:run_osc_walking_controller", "//examples/Cassie/osc", @@ -195,33 +198,6 @@ cc_binary( ], ) -cc_binary( - name = "run_simple_sim", - srcs = ["run_simple_sim.cc"], - deprecation = "Attic/RigidBodyTree is deprecated.", - tags = ["manual"], - deps = [ - ":cassie_urdf", - ":cassie_utils", - "//attic/multibody:multibody_solvers", - "//systems:robot_lcm_systems", - "//systems/primitives", - "@drake//:drake_shared_library", - "@gflags", - ], -) - -cc_binary( - name = "standalone_multibody_sim", - srcs = ["standalone_multibody_sim.cc"], - deps = [ - ":cassie_urdf", - ":cassie_utils", - "@drake//:drake_shared_library", - "@gflags", - ], -) - cc_binary( name = "multibody_sim", srcs = ["multibody_sim.cc"], @@ -230,9 +206,7 @@ cc_binary( ":cassie_fixed_point_solver", ":cassie_urdf", ":cassie_utils", - "//solvers:optimization_utils", "//systems:robot_lcm_systems", - "//systems/framework:vector", "//systems/primitives", "@drake//:drake_shared_library", "@gflags", @@ -240,15 +214,17 @@ cc_binary( ) cc_binary( - name = "multibody_sim_w_platform", - srcs = ["multibody_sim_w_platform.cc"], + name = "multibody_sim_init", + srcs = ["multibody_sim_init.cc"], deps = [ ":cassie_fixed_point_solver", ":cassie_urdf", ":cassie_utils", "//lcm:trajectory_saver", "//multibody:utils", + "//solvers:optimization_utils", "//systems:robot_lcm_systems", + "//systems/framework:vector", "//systems/primitives", "@drake//:drake_shared_library", "@gflags", @@ -256,16 +232,15 @@ cc_binary( ) cc_binary( - name = "multibody_sim_w_ground_incline", - srcs = ["multibody_sim_w_ground_incline.cc"], + name = "multibody_sim_w_platform", + srcs = ["multibody_sim_w_platform.cc"], deps = [ - ":cassie_encoder", ":cassie_fixed_point_solver", ":cassie_urdf", ":cassie_utils", - "//solvers:optimization_utils", + "//lcm:trajectory_saver", + "//multibody:utils", "//systems:robot_lcm_systems", - "//systems/framework:vector", "//systems/primitives", "@drake//:drake_shared_library", "@gflags", @@ -362,6 +337,29 @@ cc_binary( "//lcm:trajectory_saver", "//multibody:utils", "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "//systems/primitives:gaussian_noise_pass_through", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "run_osc_running_controller", + srcs = ["run_osc_running_controller.cc"], + deps = [ + ":cassie_urdf", + ":cassie_utils", + "//examples/Cassie/osc", + "//examples/Cassie/osc_jump", + "//examples/Cassie/osc_run", + "//lcm:trajectory_saver", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers/osc:osc_tracking_datas", "//systems/framework:lcm_driven_loop", "//systems/primitives", "//systems/primitives:gaussian_noise_pass_through", @@ -378,6 +376,7 @@ cc_binary( ":cassie_utils", ":simulator_drift", "//examples/Cassie/osc", + "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//multibody:utils", "//multibody/kinematic", "//systems:robot_lcm_systems", @@ -446,13 +445,14 @@ cc_binary( cc_binary( name = "run_dircon_jumping", srcs = ["run_dircon_jumping.cc"], - data = glob(["examples/Cassie/urdf/cassie_fixed_springs.urdf"]), + data = glob(["examples/Cassie/urdf/*.urdf"]), deps = [ ":cassie_utils", "//common", "//lcm:dircon_trajectory_saver", "//lcm:lcm_trajectory_saver", "//multibody:visualization_utils", + "//solvers:nonlinear_cost", "//solvers:optimization_utils", "//systems/primitives", "//systems/trajectory_optimization:dircon", @@ -478,6 +478,24 @@ cc_binary( ], ) +cc_binary( + name = "run_dircon_running", + srcs = ["run_dircon_running.cc"], + data = glob(["examples/Cassie/urdf/cassie_fixed_springs.urdf"]), + deps = [ + ":cassie_utils", + "//common", + "//lcm:dircon_trajectory_saver", + "//multibody:visualization_utils", + "//solvers:cost_function_utils", + "//solvers:optimization_utils", + "//systems/primitives", + "//systems/trajectory_optimization:dircon", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "run_controller_switch", srcs = ["run_controller_switch.cc"], diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 459bf7e07b..ffcd4c0ae1 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -176,7 +176,7 @@ int do_main(int argc, char* argv[]) { VectorXd q_init, u_init, lambda_init; double mu_fp = 0; double min_normal_fp = 70; - double toe_spread = .2; + double toe_spread = .15; // Create a plant for CassieFixedPointSolver. // Note that we cannot use the plant from the above diagram, because after the // diagram is built, plant.get_actuation_input_port().HasValue(*context) diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index ebd4a19f28..097d32956a 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -24,6 +24,7 @@ #include "drake/systems/primitives/discrete_time_delay.h" using dairlib::systems::SubvectorPassThrough; +using drake::geometry::DrakeVisualizer; using drake::geometry::SceneGraph; using drake::multibody::ContactResultsToLcmSystem; using drake::multibody::MultibodyPlant; @@ -31,7 +32,6 @@ using drake::multibody::Parser; using drake::systems::Context; using drake::systems::DiagramBuilder; using drake::systems::Simulator; -using drake::geometry::DrakeVisualizer; using drake::systems::lcm::LcmPublisherSystem; @@ -59,13 +59,18 @@ DEFINE_double(publish_rate, 2000, "Publish rate for simulator"); DEFINE_double(init_height, .7, "Initial starting height of the pelvis above " "ground"); -DEFINE_double(terrain_height, 0.0, "Height of the landing terrain"); +DEFINE_double(platform_height, 0.0, "Height of the platform"); +DEFINE_double(platform_x, 0.0, "x location of the platform"); DEFINE_double(start_time, 0.0, "Starting time of the simulator, useful for initializing the " "state at a particular configuration"); DEFINE_string(traj_name, "", "Name of the saved trajectory"); DEFINE_string(folder_path, "examples/Cassie/saved_trajectories/", "Folder path for where the trajectory names are stored"); +DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); +DEFINE_bool(visualize, true, "Set to true to visualize the platform"); +DEFINE_double(actuator_delay, 0.0, + "Duration of actuator delay. Set to 0.0 by default."); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -82,15 +87,19 @@ int do_main(int argc, char* argv[]) { } std::string urdf; - urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + if (FLAGS_spring_model) { + urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + } else { + urdf = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; + } - if (FLAGS_terrain_height != 0) { + if (FLAGS_platform_height != 0) { Parser parser(&plant, &scene_graph); std::string terrain_name = - FindResourceOrThrow("examples/impact_invaraint_control/platform.urdf"); + FindResourceOrThrow("examples/impact_invariant_control/platform.urdf"); parser.AddModelFromFile(terrain_name); Eigen::Vector3d offset; - offset << 0.15, 0, FLAGS_terrain_height; + offset << FLAGS_platform_x, 0, FLAGS_platform_height; plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform(offset)); } @@ -98,8 +107,8 @@ int do_main(int argc, char* argv[]) { plant.set_penetration_allowance(FLAGS_penetration_allowance); plant.set_stiction_tolerance(FLAGS_v_stiction); - addCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, urdf, true, - true); + addCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, urdf, + FLAGS_spring_model, true); plant.Finalize(); @@ -124,7 +133,8 @@ int do_main(int argc, char* argv[]) { plant.get_actuation_input_port().size()); auto discrete_time_delay = builder.AddSystem( - 1.0 / FLAGS_publish_rate, 0, plant.num_actuators()); + 1.0 / FLAGS_publish_rate, FLAGS_actuator_delay * FLAGS_publish_rate, + plant.num_actuators()); auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); @@ -171,7 +181,7 @@ int do_main(int argc, char* argv[]) { builder.Connect(sensor_aggregator.get_output_port(0), sensor_pub->get_input_port()); - if (FLAGS_terrain_height != 0.0) { + if (FLAGS_visualize) { DrakeVisualizer::AddToBuilder(&builder, scene_graph); } @@ -195,6 +205,8 @@ int do_main(int argc, char* argv[]) { multibody::CreateWithSpringsToWithoutSpringsMapPos(plant, plant_wo_spr); Eigen::MatrixXd map_no_spring_to_spring_vel = multibody::CreateWithSpringsToWithoutSpringsMapVel(plant, plant_wo_spr); + map_no_spring_to_spring_pos.transposeInPlace(); + map_no_spring_to_spring_vel.transposeInPlace(); const DirconTrajectory& dircon_trajectory = DirconTrajectory(FLAGS_folder_path + FLAGS_traj_name); @@ -202,10 +214,14 @@ int do_main(int argc, char* argv[]) { PiecewisePolynomial state_traj = dircon_trajectory.ReconstructStateTrajectory(); - Eigen::VectorXd x_init(nx); - Eigen::VectorXd x_init_no_spring = state_traj.value(FLAGS_start_time); - x_init << map_no_spring_to_spring_pos * x_init_no_spring.head(plant_wo_spr.num_positions()), - map_no_spring_to_spring_vel * x_init_no_spring.tail(plant_wo_spr.num_velocities()); + Eigen::VectorXd x_init = Eigen::VectorXd::Zero(nx); + Eigen::VectorXd x_traj_init = state_traj.value(FLAGS_start_time); + if (FLAGS_spring_model) { + x_init << map_no_spring_to_spring_pos * x_traj_init.head(map_no_spring_to_spring_pos.cols()), + map_no_spring_to_spring_vel * x_traj_init.tail(map_no_spring_to_spring_vel.cols()); + } else { + x_init << x_traj_init; + } plant.SetPositionsAndVelocities(&plant_context, x_init); diff --git a/examples/Cassie/osc_jump/BUILD.bazel b/examples/Cassie/osc_jump/BUILD.bazel index 629ee3f5e8..4cbe0c03fe 100644 --- a/examples/Cassie/osc_jump/BUILD.bazel +++ b/examples/Cassie/osc_jump/BUILD.bazel @@ -35,7 +35,6 @@ cc_library( deps = [ ":jumping_event_based_fsm", "//multibody:utils", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -48,7 +47,6 @@ cc_library( deps = [ ":jumping_event_based_fsm", "//multibody:utils", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -61,7 +59,6 @@ cc_library( deps = [ ":jumping_event_based_fsm", "//multibody:utils", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -74,7 +71,6 @@ cc_library( deps = [ "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//lcmtypes:lcmt_robot", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -84,6 +80,7 @@ cc_library( name = "osc_jumping_gains", hdrs = ["osc_jumping_gains.h"], deps = [ + "//systems/controllers/osc:osc_gains", "@drake//:drake_shared_library", ], ) diff --git a/examples/Cassie/osc_jump/convert_traj_for_controller.cc b/examples/Cassie/osc_jump/convert_traj_for_controller.cc index 3a6782054f..97d25c476c 100644 --- a/examples/Cassie/osc_jump/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_jump/convert_traj_for_controller.cc @@ -8,6 +8,11 @@ #include "drake/multibody/plant/multibody_plant.h" +using std::map; +using std::pair; +using std::string; +using std::vector; + using drake::geometry::SceneGraph; using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; @@ -49,6 +54,11 @@ int DoMain() { Eigen::Vector3d::UnitZ()); plant.Finalize(); + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + std::unique_ptr> context = plant.CreateDefaultContext(); int nv = plant.num_velocities(); @@ -66,6 +76,8 @@ int DoMain() { std::vector all_l_foot_points; std::vector all_r_foot_points; + std::vector all_l_toe_points; + std::vector all_r_toe_points; std::vector all_l_hip_points; std::vector all_r_hip_points; std::vector all_pelvis_points; @@ -84,6 +96,8 @@ int DoMain() { int n_points = times.size(); MatrixXd l_foot_points(6, n_points); MatrixXd r_foot_points(6, n_points); + MatrixXd l_toe_points(2, n_points); + MatrixXd r_toe_points(2, n_points); MatrixXd l_hip_points(6, n_points); MatrixXd r_hip_points(6, n_points); MatrixXd pelvis_points(6, n_points); @@ -93,6 +107,7 @@ int DoMain() { VectorXd x_i = state_samples.col(i); VectorXd xdot_i = state_traj.derivative(1).value(times[i]); + plant.SetPositionsAndVelocities(context.get(), x_i); Eigen::Ref pelvis_pos_block = pelvis_points.block(0, i, 3, 1); @@ -115,6 +130,9 @@ int DoMain() { plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, *world, &r_hip_pos_block); + l_toe_points(0, i) = x_i(pos_map["toe_left"]); + r_toe_points(0, i) = x_i(pos_map["toe_right"]); + pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); @@ -144,17 +162,21 @@ int DoMain() { pelvis_points.block(3, i, 3, 1) = J_pelvis * v_i; l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; + l_toe_points(1, i) = v_i(vel_map["toe_leftdot"]); + r_toe_points(1, i) = v_i(vel_map["toe_rightdot"]); l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; } pelvis_points = pelvis_points - 0.5 * (l_foot_points + r_foot_points); - if (FLAGS_relative_feet) { - l_foot_points = l_foot_points - l_hip_points; - r_foot_points = r_foot_points - r_hip_points; - } +// if (FLAGS_relative_feet) { +// l_foot_points = l_foot_points - l_hip_points; +// r_foot_points = r_foot_points - r_hip_points; +// } all_times.push_back(times); all_l_foot_points.push_back(l_foot_points); all_r_foot_points.push_back(r_foot_points); + all_l_toe_points.push_back(l_toe_points); + all_r_toe_points.push_back(r_toe_points); all_l_hip_points.push_back(l_hip_points); all_r_hip_points.push_back(r_hip_points); all_pelvis_points.push_back(pelvis_points); @@ -177,6 +199,32 @@ int DoMain() { rfoot_traj_block.time_vector = all_times[mode]; rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", "rfoot_xdot", "rfoot_ydot", "rfoot_zdot"}; + + auto lhip_traj_block = LcmTrajectory::Trajectory(); + lhip_traj_block.traj_name = "left_hip_trajectory" + std::to_string(mode); + lhip_traj_block.datapoints = all_l_hip_points[mode]; + lhip_traj_block.time_vector = all_times[mode]; + lhip_traj_block.datatypes = {"lhip_x", "lhip_y", "lhip_z", + "lhip_xdot", "lhip_ydot", "lhip_zdot"}; + + auto rhip_traj_block = LcmTrajectory::Trajectory(); + rhip_traj_block.traj_name = "right_hip_trajectory" + std::to_string(mode); + rhip_traj_block.datapoints = all_r_hip_points[mode]; + rhip_traj_block.time_vector = all_times[mode]; + rhip_traj_block.datatypes = {"rhip_x", "rhip_y", "rhip_z", + "rhip_xdot", "rhip_ydot", "rhip_zdot"}; + + auto ltoe_traj_block = LcmTrajectory::Trajectory(); + ltoe_traj_block.traj_name = "left_toe_trajectory" + std::to_string(mode); + ltoe_traj_block.datapoints = all_l_toe_points[mode]; + ltoe_traj_block.time_vector = all_times[mode]; + ltoe_traj_block.datatypes = {"ltoe", "ltoe_dot"}; + + auto rtoe_traj_block = LcmTrajectory::Trajectory(); + rtoe_traj_block.traj_name = "right_toe_trajectory" + std::to_string(mode); + rtoe_traj_block.datapoints = all_r_toe_points[mode]; + rtoe_traj_block.time_vector = all_times[mode]; + rtoe_traj_block.datatypes = {"rtoe", "rtoe_dot"}; auto com_traj_block = LcmTrajectory::Trajectory(); com_traj_block.traj_name = "pelvis_trans_trajectory" + std::to_string(mode); @@ -196,10 +244,18 @@ int DoMain() { converted_trajectories.push_back(lfoot_traj_block); converted_trajectories.push_back(rfoot_traj_block); + converted_trajectories.push_back(lhip_traj_block); + converted_trajectories.push_back(rhip_traj_block); + converted_trajectories.push_back(ltoe_traj_block); + converted_trajectories.push_back(rtoe_traj_block); converted_trajectories.push_back(com_traj_block); converted_trajectories.push_back(pelvis_orientation_block); trajectory_names.push_back(lfoot_traj_block.traj_name); trajectory_names.push_back(rfoot_traj_block.traj_name); + trajectory_names.push_back(lhip_traj_block.traj_name); + trajectory_names.push_back(rhip_traj_block.traj_name); + trajectory_names.push_back(ltoe_traj_block.traj_name); + trajectory_names.push_back(rtoe_traj_block.traj_name); trajectory_names.push_back(com_traj_block.traj_name); trajectory_names.push_back(pelvis_orientation_block.traj_name); } diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc index 56b23c4757..2a34158f19 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc @@ -2,7 +2,6 @@ #include "multibody/multibody_utils.h" - using Eigen::Map; using Eigen::MatrixXd; using Eigen::Vector2d; @@ -28,42 +27,44 @@ namespace dairlib::examples::osc_jump { FlightFootTrajGenerator::FlightFootTrajGenerator( const MultibodyPlant& plant, Context* context, const string& hip_name, bool isLeftFoot, - const PiecewisePolynomial& foot_traj, bool relative_feet, + const PiecewisePolynomial& foot_traj, + const PiecewisePolynomial& hip_traj, bool relative_feet, double time_offset) : plant_(plant), context_(context), world_(plant.world_frame()), hip_frame_(plant.GetFrameByName(hip_name)), foot_traj_(foot_traj), + hip_traj_(hip_traj), relative_feet_(relative_feet) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; if (isLeftFoot) { - this->set_name("l_foot_traj"); - this->DeclareAbstractOutputPort("l_foot_xyz", traj_inst, + this->set_name("left_ft_traj"); + this->DeclareAbstractOutputPort("left_ft_traj", traj_inst, &FlightFootTrajGenerator::CalcTraj); } else { - this->set_name("r_foot_traj"); - this->DeclareAbstractOutputPort("r_foot_xyz", traj_inst, + this->set_name("right_ft_traj"); + this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, &FlightFootTrajGenerator::CalcTraj); } // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant_.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant_.num_positions(), plant_.num_velocities(), plant_.num_actuators())) - .get_index(); + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); // Shift trajectory by time_offset foot_traj_.shiftRight(time_offset); + hip_traj_.shiftRight(time_offset); } -PiecewisePolynomial FlightFootTrajGenerator::generateFlightTraj( +PiecewisePolynomial FlightFootTrajGenerator::GenerateFlightTraj( const VectorXd& x, double t) const { if (relative_feet_) { plant_.SetPositionsAndVelocities(context_, x); @@ -90,6 +91,11 @@ PiecewisePolynomial FlightFootTrajGenerator::generateFlightTraj( } } +PiecewisePolynomial FlightFootTrajGenerator::GenerateRelativeTraj() + const { + return foot_traj_ - hip_traj_; +} + void FlightFootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { @@ -99,14 +105,14 @@ void FlightFootTrajGenerator::CalcTraj( VectorXd x = robot_output->GetState(); double timestamp = robot_output->get_timestamp(); - // Read in finite state machine - const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); - auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (fsm_state[0] == FLIGHT) { - *casted_traj = generateFlightTraj(robot_output->GetState(), timestamp); + if(relative_feet_){ + *casted_traj = GenerateRelativeTraj(); + } + else{ + *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); } } diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.h b/examples/Cassie/osc_jump/flight_foot_traj_generator.h index efbe032d45..c9a68341da 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.h +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.h @@ -16,8 +16,9 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, const std::string& hip_name, bool isLeftFoot, - const drake::trajectories::PiecewisePolynomial& foot_traj, bool relative_feet = false, - double time_offset = 0.0); + const drake::trajectories::PiecewisePolynomial& foot_traj, + const drake::trajectories::PiecewisePolynomial& hip_traj, + bool relative_feet = false, double time_offset = 0.0); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -27,8 +28,9 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { } private: - drake::trajectories::PiecewisePolynomial generateFlightTraj( + drake::trajectories::PiecewisePolynomial GenerateFlightTraj( const Eigen::VectorXd& x, double t) const; + drake::trajectories::PiecewisePolynomial GenerateRelativeTraj() const; void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -39,6 +41,7 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::Frame& hip_frame_; drake::trajectories::PiecewisePolynomial foot_traj_; + drake::trajectories::PiecewisePolynomial hip_traj_; bool relative_feet_; int state_port_; diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc index a49c6c1695..11710ea013 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc @@ -4,6 +4,7 @@ #include using dairlib::systems::OutputVector; +using dairlib::systems::ImpactInfoVector; using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; using drake::systems::Context; @@ -28,8 +29,7 @@ JumpingEventFsm::JumpingEventFsm(const MultibodyPlant& plant, init_state_(init_state), blend_func_(blend_func) { state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + this->DeclareVectorInputPort("x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) .get_index(); @@ -43,8 +43,12 @@ JumpingEventFsm::JumpingEventFsm(const MultibodyPlant& plant, this->DeclareVectorOutputPort("fsm", BasicVector(1), &JumpingEventFsm::CalcFiniteState) .get_index(); + clock_output_port_ = + this->DeclareVectorOutputPort("t_clock", BasicVector(1), + &JumpingEventFsm::CalcClock) + .get_index(); near_impact_output_port = - this->DeclareVectorOutputPort("fsm, t_to_impact", BasicVector(2), + this->DeclareVectorOutputPort("impact_info", ImpactInfoVector(0, 0, 3), &JumpingEventFsm::CalcNearImpact) .get_index(); DeclarePerStepDiscreteUpdateEvent(&JumpingEventFsm::DiscreteVariableUpdate); @@ -90,7 +94,7 @@ EventStatus JumpingEventFsm::DiscreteVariableUpdate( prev_time << timestamp; if (abs(transition_times_[BALANCE] - timestamp - - round(transition_times_[BALANCE] - timestamp)) < 1e-3) { + round(transition_times_[BALANCE] - timestamp)) < 1e-4) { std::cout << "Time until crouch: " << round(transition_times_[BALANCE] - timestamp) << std::endl; } @@ -133,6 +137,12 @@ void JumpingEventFsm::CalcFiniteState(const Context& context, context.get_discrete_state().get_vector(fsm_idx_).get_value(); } +void JumpingEventFsm::CalcClock(const Context& context, + BasicVector* clock) const { + clock->get_mutable_value() + << context.get_discrete_state(prev_time_idx_).get_value(); +} + double alpha_sigmoid(double t, double tau, double near_impact_threshold) { double x = (t + near_impact_threshold) / tau; return exp(x) / (1 + exp(x)); @@ -143,14 +153,16 @@ double alpha_exp(double t, double tau, double near_impact_threshold) { } void JumpingEventFsm::CalcNearImpact(const Context& context, - BasicVector* near_impact) const { + ImpactInfoVector* near_impact) const { VectorXd fsm_state = context.get_discrete_state(fsm_idx_).get_value(); // Read in lcm message time const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); double timestamp = robot_output->get_timestamp(); - VectorXd is_near_impact = VectorXd::Zero(2); + near_impact->set_timestamp(timestamp); + near_impact->SetCurrentContactMode(0); + near_impact->SetAlpha(0); auto alpha_func = blend_func_ == SIGMOID ? &alpha_sigmoid : &alpha_exp; // Get current finite state @@ -159,16 +171,15 @@ void JumpingEventFsm::CalcNearImpact(const Context& context, blend_func_ == SIGMOID ? 1.5 * impact_threshold_ : impact_threshold_; if (abs(timestamp - transition_times_[FLIGHT]) < blend_window) { if (timestamp < transition_times_[FLIGHT]) { - is_near_impact(0) = alpha_func(timestamp - transition_times_[FLIGHT], - tau_, impact_threshold_); + near_impact->SetAlpha(alpha_func(timestamp - transition_times_[FLIGHT], + tau_, impact_threshold_)); } else { - is_near_impact(0) = alpha_func(transition_times_[FLIGHT] - timestamp, - tau_, impact_threshold_); + near_impact->SetAlpha(alpha_func(transition_times_[FLIGHT] - timestamp, + tau_, impact_threshold_)); } - is_near_impact(1) = LAND; + near_impact->SetCurrentContactMode(LAND); } } - near_impact->get_mutable_value() = is_near_impact; } } // namespace osc_jump diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.h b/examples/Cassie/osc_jump/jumping_event_based_fsm.h index cdecb42ae6..07a733e5ab 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.h +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.h @@ -2,6 +2,7 @@ #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" #include "systems/framework/output_vector.h" +#include "systems/framework/impact_info_vector.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/leaf_system.h" @@ -25,7 +26,8 @@ class JumpingEventFsm : public drake::systems::LeafSystem { JumpingEventFsm(const drake::multibody::MultibodyPlant& plant, const std::vector& transition_times, bool contact_based = true, double impact_threshold = 0.0, - FSM_STATE init_state = BALANCE, BLEND_FUNC blend_func = SIGMOID); + FSM_STATE init_state = BALANCE, + BLEND_FUNC blend_func = SIGMOID); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -43,6 +45,10 @@ class JumpingEventFsm : public drake::systems::LeafSystem { return this->get_output_port(fsm_output_port_); } + const drake::systems::OutputPort& get_clock_output_port() const { + return this->get_output_port(clock_output_port_); + } + const drake::systems::OutputPort& get_impact_output_port() const { return this->get_output_port(near_impact_output_port); } @@ -55,13 +61,17 @@ class JumpingEventFsm : public drake::systems::LeafSystem { void CalcFiniteState(const drake::systems::Context& context, drake::systems::BasicVector* fsm_state) const; + void CalcClock(const drake::systems::Context& context, + drake::systems::BasicVector* clock) const; + void CalcNearImpact(const drake::systems::Context& context, - drake::systems::BasicVector* fsm_state) const; + systems::ImpactInfoVector* fsm_state) const; int state_port_; int contact_port_; int switch_signal_port_; int fsm_output_port_; + int clock_output_port_; int near_impact_output_port; std::vector transition_times_; diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.h b/examples/Cassie/osc_jump/osc_jumping_gains.h index d95968af1f..164b5a3230 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.h +++ b/examples/Cassie/osc_jump/osc_jumping_gains.h @@ -1,13 +1,12 @@ #include "drake/common/yaml/yaml_read_archive.h" +#include "systems/controllers/osc/osc_gains.h" + #include "yaml-cpp/yaml.h" using Eigen::MatrixXd; -struct OSCJumpingGains { +struct OSCJumpingGains : OSCGains { // costs - double w_input; - double w_accel; - double w_soft_constraint; double x_offset; // center of mass tracking std::vector CoMW; @@ -29,9 +28,7 @@ struct OSCJumpingGains { double w_hip_yaw; double hip_yaw_kp; double hip_yaw_kd; - double impact_threshold; double landing_delay; - double mu; bool relative_feet; MatrixXd W_com; @@ -46,9 +43,7 @@ struct OSCJumpingGains { template void Serialize(Archive* a) { - a->Visit(DRAKE_NVP(w_input)); - a->Visit(DRAKE_NVP(w_accel)); - a->Visit(DRAKE_NVP(w_soft_constraint)); + OSCGains::Serialize(a); a->Visit(DRAKE_NVP(x_offset)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); @@ -65,9 +60,7 @@ struct OSCJumpingGains { a->Visit(DRAKE_NVP(w_hip_yaw)); a->Visit(DRAKE_NVP(hip_yaw_kp)); a->Visit(DRAKE_NVP(hip_yaw_kd)); - a->Visit(DRAKE_NVP(impact_threshold)); a->Visit(DRAKE_NVP(landing_delay)); - a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(relative_feet)); W_com = Eigen::Map< diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index ea3a790633..58fded635c 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,56 +1,57 @@ -w_input: 2 -w_accel: 0.000001 -w_soft_constraint: 8000 -x_offset: 0.02 -relative_feet: false +w_input: 0.000 +w_accel: 0.0000001 +w_input_reg: 0.00 +w_soft_constraint: 100 +x_offset: -0.025 +relative_feet: true mu: 0.8 -w_swing_toe: 0.1 -swing_toe_kp: 1500 +w_swing_toe: 1 +swing_toe_kp: 2000 swing_toe_kd: 10 w_hip_yaw: 100 hip_yaw_kp: 40 -hip_yaw_kd: 1 +hip_yaw_kd: 5 impact_threshold: 0.050 -landing_delay: 0.00 +landing_delay: 0.000 CoMW: - [2000, 0, 0, - 0, 200, 0, - 0, 0, 2000] + [20, 0, 0, + 0, 2, 0, + 0, 0, 20] PelvisRotW: - [100, 0, 0, - 0, 100, 0, - 0, 0, 100] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] FlightFootW: - [400, 0, 0, - 0, 400, 0, - 0, 0, 400] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] CoMKp: - [ 50, 0, 0, - 0, 50, 0, - 0, 0, 200] + [10, 0, 0, + 0, 50, 0, + 0, 0, 50] CoMKd: [ 5, 0, 0, 0, 5, 0, - 0, 0, 10] + 0, 0, 5] PelvisRotKp: - [100, 0, 0, - 0, 100, 0, + [25, 0, 0, + 0, 50, 0, 0, 0, 0] PelvisRotKd: - [10, 0, 0, + [5, 0, 0, 0, 10, 0, 0, 0, 0] FlightFootKp: - [200, 0, 0, - 0, 200, 0, - 0, 0, 400] + [150, 0, 0, + 0, 100, 0, + 0, 0, 100] FlightFootKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 5] + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 5.0] diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc index 1628aeebcc..87bfee2e7c 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc @@ -32,7 +32,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( PiecewisePolynomial& crouch_traj, const std::vector&>>& - feet_contact_points, + feet_contact_points, double time_offset, FSM_STATE init_fsm_state) : plant_(plant), context_(context), @@ -42,12 +42,13 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( time_offset_(time_offset) { this->set_name("com_traj"); // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", OutputVector(plant_.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant_.num_positions(), plant_.num_velocities(), plant_.num_actuators())) - .get_index(); - fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -144,7 +145,6 @@ PelvisTransTrajGenerator::generateBalanceTraj( VectorXd breaks_vector(2); breaks_vector << switch_time, switch_time + time_offset_; - return PiecewisePolynomial::CubicHermite( breaks_vector, pelvis_traj_points, MatrixXd::Zero(3, 2)); } @@ -187,12 +187,14 @@ PelvisTransTrajGenerator::generateLandingTraj( contact_pos_sum += position; } + contact_pos_sum *= (1.0/feet_contact_points_.size()); + const auto& x_offset = context.get_discrete_state().get_vector(pelvis_x_offset_idx_); // Only offset the x-position Vector3d offset(x_offset[0], 0, 0); - offset += 0.5 * contact_pos_sum; + offset += contact_pos_sum; auto traj_segment = crouch_traj_.slice(crouch_traj_.get_segment_index(time), 1); @@ -200,7 +202,13 @@ PelvisTransTrajGenerator::generateLandingTraj( MatrixXd offset_matrix = offset.replicate(1, breaks.size()); VectorXd breaks_vector = Eigen::Map(breaks.data(), breaks.size()); PiecewisePolynomial pelvis_x_offset = - PiecewisePolynomial::FirstOrderHold(breaks_vector, offset_matrix); + PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_matrix); + if (time > crouch_traj_.end_time()) { + Vector3d final_target_position; + final_target_position << x_offset[0] + contact_pos_sum[0], + contact_pos_sum[1], contact_pos_sum[2] + crouch_traj_.value(time)(2); + return PiecewisePolynomial(final_target_position); + } return traj_segment + pelvis_x_offset; } diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h index 7ce771c179..3b2cb83ae6 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h @@ -66,11 +66,10 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex fsm_port_; - static constexpr double kTransitionSpeed = 200.0; // 20 s/m // The trajectory optimization solution sets the final CoM very close to // rear toe contacts - this is an offset to move it closer to the center of // the support polygon - static constexpr double kLandingOffset = 0.01; // 0.04 m (4cm) + static constexpr double kLandingOffset = 0.00; // 0.04 m (4cm) // static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) }; diff --git a/examples/Cassie/osc_jump/toe_angle_traj_generator.cc b/examples/Cassie/osc_jump/toe_angle_traj_generator.cc index 7357ca74b4..bb5edd1d4d 100644 --- a/examples/Cassie/osc_jump/toe_angle_traj_generator.cc +++ b/examples/Cassie/osc_jump/toe_angle_traj_generator.cc @@ -14,24 +14,28 @@ namespace dairlib::cassie::osc_jump { FlightToeAngleTrajGenerator::FlightToeAngleTrajGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, int swing_toe_idx, + drake::systems::Context* context, + PiecewisePolynomial& toe_traj, int swing_toe_idx, const std::vector&>>& - feet_contact_points, + feet_contact_points, const std::string& traj_name) : plant_(plant), context_(context), world_(plant_.world_frame()), + toe_traj_(toe_traj), swing_toe_idx_(swing_toe_idx), feet_contact_points_(feet_contact_points) { DRAKE_DEMAND(feet_contact_points_.size() == 2); + use_traj_ = !toe_traj_.empty(); // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); - fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -71,9 +75,13 @@ void FlightToeAngleTrajGenerator::CalcTraj( // Read in finite state machine auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - *casted_traj = CalcToeAngle(robot_output->GetPositions()); + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (use_traj_) { + *casted_traj = toe_traj_; + } else { + *casted_traj = CalcToeAngle(robot_output->GetPositions()); + } } } // namespace dairlib::cassie::osc_jump diff --git a/examples/Cassie/osc_jump/toe_angle_traj_generator.h b/examples/Cassie/osc_jump/toe_angle_traj_generator.h index d9447ad9ca..ab769aa420 100644 --- a/examples/Cassie/osc_jump/toe_angle_traj_generator.h +++ b/examples/Cassie/osc_jump/toe_angle_traj_generator.h @@ -14,7 +14,8 @@ class FlightToeAngleTrajGenerator : public drake::systems::LeafSystem { public: FlightToeAngleTrajGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, int swing_toe_idx, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& toe_traj, int swing_toe_idx, const std::vector&>>& feet_contact_points, @@ -40,6 +41,9 @@ class FlightToeAngleTrajGenerator : public drake::systems::LeafSystem { drake::systems::Context* context_; const drake::multibody::BodyFrame& world_; + drake::trajectories::PiecewisePolynomial toe_traj_; + bool use_traj_; + int swing_toe_idx_; // A list of pairs of contact body frame and contact point const std::vector< diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 916165614a..fad4a21c21 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -2,9 +2,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -13,13 +13,12 @@ #include "examples/Cassie/cassie_utils.h" #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/world_point_evaluator.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" -#include "systems/trajectory_optimization/dircon_distance_data.h" -#include "systems/trajectory_optimization/dircon_kinematic_data_set.h" -#include "systems/trajectory_optimization/dircon_opt_constraints.h" -#include "systems/trajectory_optimization/dircon_position_data.h" -#include "systems/trajectory_optimization/hybrid_dircon.h" +#include "solvers/nonlinear_cost.h" +#include "systems/trajectory_optimization/dircon/dircon.h" #include "drake/multibody/parsing/parser.h" #include "drake/solvers/solve.h" @@ -40,13 +39,24 @@ using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; +using dairlib::multibody::KinematicEvaluator; +using dairlib::multibody::KinematicEvaluatorSet; +using dairlib::systems::trajectory_optimization::Dircon; +using dairlib::systems::trajectory_optimization::DirconMode; +using dairlib::systems::trajectory_optimization::DirconModeSequence; +using dairlib::systems::trajectory_optimization::PointPositionConstraint; +using dairlib::multibody::CreateWithSpringsToWithoutSpringsMapPos; +using dairlib::multibody::CreateWithSpringsToWithoutSpringsMapVel; +using dairlib::solvers::NonlinearCost; using dairlib::systems::trajectory_optimization::DirconDynamicConstraint; using dairlib::systems::trajectory_optimization::DirconKinConstraintType; using dairlib::systems::trajectory_optimization::DirconKinematicConstraint; using dairlib::systems::trajectory_optimization::DirconOptions; using dairlib::systems::trajectory_optimization::HybridDircon; -using dairlib::systems::trajectory_optimization ::PointPositionConstraint; +using dairlib::systems::trajectory_optimization::PointPositionConstraint; +using drake::VectorX; using drake::math::RotationMatrix; +using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::Body; using drake::multibody::MultibodyPlant; using drake::solvers::MathematicalProgram; @@ -67,29 +77,87 @@ DEFINE_int32(scale_option, 0, "Use 2 if seeing snopta exit 40 in log file"); DEFINE_double(tol, 1e-6, "Tolerance for constraint violation and dual gap"); DEFINE_string(load_filename, "", "File to load decision vars from."); -DEFINE_string( - data_directory, - "examples/Cassie/saved_trajectories/", - "Directory path to save decision vars to."); +DEFINE_string(data_directory, "examples/Cassie/saved_trajectories/", + "Directory path to save decision vars to."); DEFINE_string(save_filename, "default_filename", "Filename to save decision " "vars to."); DEFINE_string(traj_name, "", "File to load saved LCM trajs from."); DEFINE_bool(use_springs, false, "Whether or not to use the spring model"); +DEFINE_bool( + convert_to_springs, false, + "Whether the loaded trajectory needs to be converted to with springs"); +DEFINE_bool(ipopt, false, "Set flag to true to use ipopt instead of snopt"); +DEFINE_bool(same_knotpoints, false, + "Set flag to true if seeding with a trajectory with the same " + "number of knotpoints"); +DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); namespace dairlib { HybridDircon* createDircon(MultibodyPlant& plant); -void setKinematicConstraints(HybridDircon* trajopt, +void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant); -vector GetInitGuessForQStance(int num_knot_points, - const MultibodyPlant& plant); -vector GetInitGuessForQFlight(int num_knot_points, double apex_height, - const MultibodyPlant& plant); -vector GetInitGuessForV(const vector& q_guess, double dt, - const MultibodyPlant& plant); +void AddCosts(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence* ); +void AddCostsSprings(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence* ); MatrixXd loadSavedDecisionVars(const string& filepath); +void SetInitialGuessFromTrajectory( + Dircon& trajopt, const string& filepath, + bool same_knot_points = false, + Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); + +class JointAccelCost : public solvers::NonlinearCost { + public: + JointAccelCost(const MatrixXd& W_Q, + const drake::multibody::MultibodyPlant& plant, + const KinematicEvaluatorSet* constraints, + const std::string& description = "") + : solvers::NonlinearCost( + plant.num_positions() + plant.num_velocities() + + plant.num_actuators() + + constraints->count_full(), + description), + plant_(plant), + context_(plant_.CreateDefaultContext()), + constraints_(constraints), + n_v_(plant.num_velocities()), + n_x_(plant.num_positions() + plant.num_velocities()), + n_u_(plant.num_actuators()), + n_lambda_(constraints->count_full()), + W_Q_(W_Q){}; + + private: + void EvaluateCost(const Eigen::Ref>& x, + drake::VectorX* y) const override { + DRAKE_ASSERT(x.size() == n_x_ + n_u_ + n_lambda_); + + // Extract our input variables: + const auto x0 = x.segment(0, n_x_); + const auto u0 = x.segment(n_x_, n_u_); + VectorXd l0 = x.segment(n_x_ + n_u_, n_lambda_); + + multibody::setContext(plant_, x0, u0, context_.get()); + const VectorX xdot0 = constraints_->CalcTimeDerivatives(*context_, &l0); + + (*y) = xdot0.tail(n_v_).transpose() * W_Q_ * xdot0.tail(n_v_); + }; + + const drake::multibody::MultibodyPlant& plant_; + std::unique_ptr> context_; + const KinematicEvaluatorSet* constraints_; + + int n_v_; + int n_x_; + int n_u_; + int n_lambda_; + + MatrixXd W_Q_; +}; void DoMain() { // Drake system initialization stuff @@ -97,244 +165,234 @@ void DoMain() { SceneGraph& scene_graph = *builder.AddSystem(); scene_graph.set_name("scene_graph"); MultibodyPlant plant(0.0); + MultibodyPlant plant_vis(0.0); + + string file_name = + "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf"; + + if (FLAGS_use_springs) { + file_name = "examples/Cassie/urdf/cassie_v2_conservative.urdf"; + } + + addCassieMultibody(&plant, nullptr, true, file_name, FLAGS_use_springs, false); + + Parser parser_vis(&plant_vis, &scene_graph); + parser_vis.AddModelFromFile(file_name); - string file_name = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; - if(FLAGS_use_springs) - file_name = "examples/Cassie/urdf/cassie_v2.urdf"; - addCassieMultibody(&plant, &scene_graph, true, - file_name, false, - false); plant.Finalize(); + plant_vis.Finalize(); int n_q = plant.num_positions(); int n_v = plant.num_velocities(); int n_x = n_q + n_v; - std::cout << "nq: " << n_q << " n_v: " << n_v << " n_x: " << n_x << std::endl; + MatrixXd spr_map = MatrixXd::Zero(n_x, n_x); + if (FLAGS_use_springs && FLAGS_convert_to_springs) { + MultibodyPlant plant_wo_spr(0.0); + Parser parser(&plant_wo_spr); + parser.AddModelFromFile( + "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf"); + plant_wo_spr.Finalize(); + spr_map = CreateWithSpringsToWithoutSpringsMapPos(plant, plant_wo_spr); + } + // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); - std::cout << "Creating dircon object: " << std::endl; // Set up contact/distance constraints - const Body& toe_left = plant.GetBodyByName("toe_left"); - const Body& toe_right = plant.GetBodyByName("toe_right"); + auto left_toe_pair = LeftToeFront(plant); + auto left_heel_pair = LeftToeRear(plant); + auto right_toe_pair = RightToeFront(plant); + auto right_heel_pair = RightToeRear(plant); - Vector3d pt_front_contact(-0.0457, 0.112, 0); - Vector3d pt_rear_contact(0.088, 0, 0); + std::vector toe_active_inds{0, 1, 2}; + std::vector heel_active_inds{1, 2}; - bool isXZ = false; - Vector3d ground_normal(0, 0, 1); - auto left_toe_front_constraint = DirconPositionData( - plant, toe_left, pt_front_contact, isXZ, ground_normal); - auto left_toe_rear_constraint = DirconPositionData( - plant, toe_left, pt_rear_contact, isXZ, ground_normal); - auto right_toe_front_constraint = DirconPositionData( - plant, toe_right, pt_front_contact, isXZ, ground_normal); - auto right_toe_rear_constraint = DirconPositionData( - plant, toe_right, pt_rear_contact, isXZ, ground_normal); double mu = 1; - left_toe_front_constraint.addFixedNormalFrictionConstraints(mu); - left_toe_rear_constraint.addFixedNormalFrictionConstraints(mu); - right_toe_front_constraint.addFixedNormalFrictionConstraints(mu); - right_toe_rear_constraint.addFixedNormalFrictionConstraints(mu); - - const auto& thigh_left = plant.GetBodyByName("thigh_left"); - const auto& heel_spring_left = plant.GetBodyByName("heel_spring_left"); - const auto& thigh_right = plant.GetBodyByName("thigh_right"); - const auto& heel_spring_right = plant.GetBodyByName("heel_spring_right"); - double rod_length = 0.5012; // from cassie_utils - Vector3d pt_on_heel_spring = Vector3d(.11877, -.01, 0.0); - Vector3d pt_on_thigh_left = Vector3d(0.0, 0.0, 0.045); - Vector3d pt_on_thigh_right = Vector3d(0.0, 0.0, -0.045); - auto distance_constraint_left = DirconDistanceData( - plant, thigh_left, pt_on_thigh_left, heel_spring_left, pt_on_heel_spring, - rod_length); - auto distance_constraint_right = DirconDistanceData( - plant, thigh_right, pt_on_thigh_right, heel_spring_right, - pt_on_heel_spring, rod_length); - - // get rid of redundant constraint - vector skip_constraint_inds; - skip_constraint_inds.push_back(3); - skip_constraint_inds.push_back(9); - - // Double stance (all four contact points) - vector*> double_stance_constraints; - double_stance_constraints.push_back(&left_toe_front_constraint); - double_stance_constraints.push_back(&left_toe_rear_constraint); - double_stance_constraints.push_back(&right_toe_front_constraint); - double_stance_constraints.push_back(&right_toe_rear_constraint); - double_stance_constraints.push_back(&distance_constraint_left); - double_stance_constraints.push_back(&distance_constraint_right); - - auto double_stance_dataset = DirconKinematicDataSet( - plant, &double_stance_constraints, skip_constraint_inds); - auto double_stance_options = - DirconOptions(double_stance_dataset.countConstraints(), plant); - /// Be careful setting relative constraint, because we also skip constraints. - /// || lf | lr | rf | rr | fourbar - /// Before skipping || 0 1 2 | 3 4 5 | 6 7 8 | 9 10 11 | 12 13 - /// After skipping || 0 1 2 | 3 4 | 5 6 7 | 8 9 | 10 11 - // Set all the non-z toe constraints to be relative - double_stance_options.setConstraintRelative(0, true); - double_stance_options.setConstraintRelative(1, true); - double_stance_options.setConstraintRelative(3, true); - double_stance_options.setConstraintRelative(5, true); - double_stance_options.setConstraintRelative(6, true); - double_stance_options.setConstraintRelative(8, true); - - // Flight mode (no contact) - std::vector*> flight_mode_constraints; - flight_mode_constraints.push_back(&distance_constraint_left); - flight_mode_constraints.push_back(&distance_constraint_right); - auto flight_mode_dataset = - DirconKinematicDataSet(plant, &flight_mode_constraints); - auto flight_mode_options = - DirconOptions(flight_mode_dataset.countConstraints(), plant); - - // timesteps and modes setting - vector timesteps; // Number of timesteps per mode - timesteps.push_back(FLAGS_knot_points); - timesteps.push_back(FLAGS_knot_points); - timesteps.push_back(FLAGS_knot_points); - vector min_dt; // min/max duration per timestep - vector max_dt; // min_duration = knot_points * 0.01 ~= .1s - min_dt.push_back(.03); - min_dt.push_back(.03); - min_dt.push_back(.03); - max_dt.push_back(.3); - max_dt.push_back(.3); - max_dt.push_back(.3); - - // Add contact modes and contact decision - // variables to single vector for DIRCON - std::vector*> contact_mode_list; - std::vector options_list; - contact_mode_list.push_back(&double_stance_dataset); - contact_mode_list.push_back(&flight_mode_dataset); - contact_mode_list.push_back(&double_stance_dataset); - - options_list.push_back(double_stance_options); - options_list.push_back(flight_mode_options); - options_list.push_back(double_stance_options); - - auto trajopt = std::make_shared>( - plant, timesteps, min_dt, max_dt, contact_mode_list, options_list); - - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), "Print file", - "../jumping_snopt.out"); - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major iterations limit", 50000); - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Iterations limit", 50000); // QP subproblems - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), "Verify level", - 0); // 0 - trajopt->SetSolverOption( - drake::solvers::SnoptSolver::id(), "Scale option", - FLAGS_scale_option); // snopt doc said try 2 if seeing snopta exit 40 - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major optimality tolerance", - FLAGS_tol); // target nonlinear constraint violation - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major feasibility tolerance", - FLAGS_tol); // target complementarity gap + + auto left_toe_eval = multibody::WorldPointEvaluator( + plant, left_toe_pair.first, left_toe_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), toe_active_inds); + left_toe_eval.set_frictional(); + left_toe_eval.set_mu(mu); + auto left_heel_eval = multibody::WorldPointEvaluator( + plant, left_heel_pair.first, left_heel_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), heel_active_inds); + left_heel_eval.set_frictional(); + left_heel_eval.set_mu(mu); + auto right_toe_eval = multibody::WorldPointEvaluator( + plant, right_toe_pair.first, right_toe_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), toe_active_inds); + right_toe_eval.set_frictional(); + right_toe_eval.set_mu(mu); + auto right_heel_eval = multibody::WorldPointEvaluator( + plant, right_heel_pair.first, right_heel_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), heel_active_inds); + right_heel_eval.set_frictional(); + right_heel_eval.set_mu(mu); + + auto left_loop_eval = LeftLoopClosureEvaluator(plant); + auto right_loop_eval = RightLoopClosureEvaluator(plant); + + auto double_stance_constraints = KinematicEvaluatorSet(plant); + int left_toe_eval_ind = double_stance_constraints.add_evaluator(&left_toe_eval); + int left_heel_eval_ind = + double_stance_constraints.add_evaluator(&left_heel_eval); + int right_toe_eval_ind = double_stance_constraints.add_evaluator(&right_toe_eval); + int right_heel_eval_ind = + double_stance_constraints.add_evaluator(&right_heel_eval); + double_stance_constraints.add_evaluator(&left_loop_eval); + double_stance_constraints.add_evaluator(&right_loop_eval); + + auto flight_phase_constraints = KinematicEvaluatorSet(plant); + flight_phase_constraints.add_evaluator(&left_loop_eval); + flight_phase_constraints.add_evaluator(&right_loop_eval); + + int stance_knotpoints = FLAGS_knot_points; + int flight_phase_knotpoints = FLAGS_knot_points; + + /**** + * Mode duration constraints + */ + auto crouch_mode = DirconMode(double_stance_constraints, + stance_knotpoints, 0.5, 0.75); + auto flight_mode = DirconMode(flight_phase_constraints, + flight_phase_knotpoints, 0.25, 0.5); + auto land_mode = DirconMode(double_stance_constraints, + stance_knotpoints, 0.4, 0.6); + + crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); + crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); + crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 0); + crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 1); + crouch_mode.MakeConstraintRelative(right_toe_eval_ind, 0); + crouch_mode.MakeConstraintRelative(right_toe_eval_ind, 1); + crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 0); + crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 1); + + land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); + land_mode.MakeConstraintRelative(left_toe_eval_ind, 1); + land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 0); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 1); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 0); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 1); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 0); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 1); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); + + auto all_modes = DirconModeSequence(plant); + all_modes.AddMode(&crouch_mode); + all_modes.AddMode(&flight_mode); + all_modes.AddMode(&land_mode); + + auto trajopt = Dircon(all_modes); + + double tol = FLAGS_tol; + if (FLAGS_ipopt) { + // Ipopt settings adapted from CaSaDi and FROST + auto id = drake::solvers::IpoptSolver::id(); + trajopt.SetSolverOption(id, "tol", tol); + trajopt.SetSolverOption(id, "dual_inf_tol", tol); + trajopt.SetSolverOption(id, "constr_viol_tol", tol); + trajopt.SetSolverOption(id, "compl_inf_tol", tol); + trajopt.SetSolverOption(id, "max_iter", 1e5); + trajopt.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); + trajopt.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); + trajopt.SetSolverOption(id, "print_timing_statistics", "yes"); + trajopt.SetSolverOption(id, "print_level", 5); + trajopt.SetSolverOption(id, "output_file", "../ipopt.out"); + + // Set to ignore overall tolerance/dual infeasibility, but terminate when + // primal feasible and objective fails to increase over 5 iterations. + trajopt.SetSolverOption(id, "acceptable_compl_inf_tol", tol); + trajopt.SetSolverOption(id, "acceptable_constr_viol_tol", tol); + trajopt.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); + trajopt.SetSolverOption(id, "acceptable_tol", 1e2); + trajopt.SetSolverOption(id, "acceptable_iter", 5); + } else { + // Snopt settings + auto id = drake::solvers::SnoptSolver::id(); + if(FLAGS_use_springs){ + trajopt.SetSolverOption(id, "Print file", "../w_springs_snopt.out"); + }else{ + trajopt.SetSolverOption(id, "Print file", "../snopt.out"); + } + trajopt.SetSolverOption(id, "Major iterations limit", 1e5); + trajopt.SetSolverOption(id, "Iterations limit", 100000); + trajopt.SetSolverOption(id, "Verify level", 0); + + // snopt doc said try 2 if seeing snopta exit 40 + trajopt.SetSolverOption(id, "Scale option", 2); + trajopt.SetSolverOption(id, "Solution", "No"); + + // target nonlinear constraint violation + trajopt.SetSolverOption(id, "Major optimality tolerance", 1e-4); + + // target complementarity gap + trajopt.SetSolverOption(id, "Major feasibility tolerance", tol); + } std::cout << "Adding kinematic constraints: " << std::endl; - setKinematicConstraints(trajopt.get(), plant); + SetKinematicConstraints(&trajopt, plant); + if(FLAGS_use_springs){ + AddCostsSprings(&trajopt, plant, &all_modes); + }else{ + AddCosts(&trajopt, plant, &all_modes); + } std::cout << "Setting initial conditions: " << std::endl; vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; - int num_knot_points = trajopt->N(); + int num_knot_points = trajopt.N(); std::cout << "nq: " << n_q << endl; std::cout << "nv: " << n_v << endl; std::cout << "nu: " << plant.num_actuators() << endl; - cout << "N: " << num_knot_points; - cout << "Num decision vars: " << trajopt->decision_variables().size() << endl; - double dt = 0.1; + cout << "N: " << num_knot_points << endl; + cout << "Num decision vars: " << trajopt.decision_variables().size() << endl; if (!FLAGS_load_filename.empty()) { std::cout << "Loading: " << FLAGS_load_filename << std::endl; - MatrixXd decisionVars = - loadSavedDecisionVars(FLAGS_data_directory + FLAGS_load_filename); - trajopt->SetInitialGuessForAllVariables(decisionVars); - } else { - // Initialize all decision vars to random by default. Will be overriding - // later - trajopt->SetInitialGuessForAllVariables( - VectorXd::Random(trajopt->decision_variables().size())); - // Set the initial guess for states - - vector q_guess_stance = - GetInitGuessForQStance(num_knot_points, plant); - vector q_guess_flight = - GetInitGuessForQFlight(num_knot_points, FLAGS_height, plant); - vector v_guess_stance = - GetInitGuessForV(q_guess_stance, dt, plant); - vector v_guess_flight = - GetInitGuessForV(q_guess_flight, dt, plant); - // Set initial guess for stance - VectorXd x_guess(n_q + n_v); - for (int i = 0; i < mode_lengths[0]; ++i) { - x_guess << q_guess_stance[i], v_guess_stance[i]; - trajopt->SetInitialGuess(trajopt->state(i), x_guess); - } - // Set initial guess for flight - for (int i = 0; i < mode_lengths[1]; ++i) { - int knot_point = mode_lengths[0] - 1 + i; - x_guess << q_guess_flight[i], v_guess_flight[i]; - trajopt->SetInitialGuess(trajopt->state(knot_point), x_guess); - } - // Set initial guess for landing phase (same as stance) - for (int i = 0; i < mode_lengths[2]; ++i) { - int knot_point = mode_lengths[0] + mode_lengths[1] - 2 + i; - x_guess << q_guess_stance[i], v_guess_stance[i]; - trajopt->SetInitialGuess(trajopt->state(knot_point), x_guess); - } - } - - // To avoid NaN quaternions - for (int i = 0; i < trajopt->N(); i++) { - auto xi = trajopt->state(i); - if ((trajopt->GetInitialGuess(xi.head(4)).norm() == 0) || - std::isnan(trajopt->GetInitialGuess(xi.head(4)).norm())) { - trajopt->SetInitialGuess(xi(0), 1); - trajopt->SetInitialGuess(xi(1), 0); - trajopt->SetInitialGuess(xi(2), 0); - trajopt->SetInitialGuess(xi(3), 0); - } + // MatrixXd decisionVars = + // loadSavedDecisionVars(FLAGS_data_directory + FLAGS_load_filename); + SetInitialGuessFromTrajectory(trajopt, + FLAGS_data_directory + FLAGS_load_filename, + FLAGS_same_knotpoints, spr_map); + // trajopt->SetInitialGuessForAllVariables(decisionVars); } double alpha = .2; int num_poses = std::min(FLAGS_knot_points, 5); - trajopt->CreateVisualizationCallback( - file_name, num_poses, alpha); + trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); cout << "\nChoose the best solver: " - << drake::solvers::ChooseBestSolver(*trajopt).name() << endl; + << drake::solvers::ChooseBestSolver(trajopt).name() << endl; cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(*trajopt, trajopt->initial_guess()); - // SolutionResult solution_result = result.get_solution_result(); + const auto result = Solve(trajopt, trajopt.initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; cout << "Solve time:" << elapsed.count() << std::endl; std::cout << "Cost:" << result.get_optimal_cost() << std::endl; std::cout << "Solve result: " << result.get_solution_result() << std::endl; + std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) << std::endl; + // Save trajectory to file - DirconTrajectory saved_traj(plant, *trajopt, result, "jumping_trajectory", + DirconTrajectory saved_traj(plant, trajopt, result, "jumping_trajectory", "Decision variables and state/input trajectories " "for jumping"); saved_traj.WriteToFile(FLAGS_data_directory + FLAGS_save_filename); std::cout << "Wrote to file: " << FLAGS_data_directory + FLAGS_save_filename << std::endl; drake::trajectories::PiecewisePolynomial optimal_traj = - trajopt->ReconstructStateTrajectory(result); - multibody::connectTrajectoryVisualizer(&plant, &builder, &scene_graph, + trajopt.ReconstructStateTrajectory(result); + multibody::connectTrajectoryVisualizer(&plant_vis, &builder, &scene_graph, optimal_traj); auto diagram = builder.Build(); @@ -347,17 +405,13 @@ void DoMain() { } } -void setKinematicConstraints(HybridDircon* trajopt, +void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant) { // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); - for (const auto& pair : pos_map) { - std::cout << pair.first << ": " << pair.second << std::endl; - } - int n_q = plant.num_positions(); int n_v = plant.num_velocities(); int n_u = plant.num_actuators(); @@ -366,63 +420,64 @@ void setKinematicConstraints(HybridDircon* trajopt, int N = trajopt->N(); std::vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; - auto x0 = trajopt->initial_state(); + auto x_0 = trajopt->initial_state(); auto x_top = trajopt->state(N / 2); - auto xf = trajopt->final_state(); + auto x_f = trajopt->final_state(); auto u = trajopt->input(); - auto u0 = trajopt->input(0); - auto uf = trajopt->input(N - 1); + auto u_0 = trajopt->input(0); + auto u_f = trajopt->input(N - 1); auto x = trajopt->state(); // Duration Bounds - double min_duration = (FLAGS_duration > 0.0) ? FLAGS_duration : 1.0; - double max_duration = (FLAGS_duration > 0.0) ? FLAGS_duration : 1.5; - - trajopt->AddDurationBounds(min_duration, max_duration); // Standing constraints double rest_height = FLAGS_start_height; double eps = 1e-6; + double midpoint = 0.045; + // position constraints - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("base_x"))); - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("base_y"))); - trajopt->AddBoundingBoxConstraint(0, 0, xf(pos_map.at("base_y"))); + trajopt->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, x_0(pos_map.at("base_x"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); // initial fb orientation constraint VectorXd quat_identity(4); quat_identity << 1, 0, 0, 0; - trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x0.head(4)); - trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, xf.head(4)); + trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x_0.head(4)); + trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x_f.head(4)); // hip yaw and roll constraints - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("hip_yaw_left"))); - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("hip_yaw_right"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); - trajopt->AddBoundingBoxConstraint(0.05, 0.2, x0(pos_map.at("hip_roll_left"))); - trajopt->AddBoundingBoxConstraint(-0.2, -0.05, x0(pos_map.at("hip_roll_right"))); + trajopt->AddBoundingBoxConstraint(0.00, 0.1, + x_0(pos_map.at("hip_roll_left"))); + trajopt->AddBoundingBoxConstraint(-0.1, -0.00, + x_0(pos_map.at("hip_roll_right"))); // hip yaw and roll constraints - trajopt->AddBoundingBoxConstraint(0, 0, xf(pos_map.at("hip_yaw_left"))); - trajopt->AddBoundingBoxConstraint(0, 0, xf(pos_map.at("hip_yaw_right"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_right"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, x0(pos_map.at("toe_left"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, x0(pos_map.at("toe_right"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, xf(pos_map.at("toe_left"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, xf(pos_map.at("toe_right"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_left"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_right"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_left"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_right"))); // Jumping height constraints trajopt->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, - x0(pos_map.at("base_z"))); - trajopt->AddBoundingBoxConstraint(FLAGS_height + rest_height - eps, + x_0(pos_map.at("base_z"))); + trajopt->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, FLAGS_height + rest_height + eps, x_top(pos_map.at("base_z"))); - trajopt->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, - xf(pos_map.at("base_z"))); + trajopt->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, + 0.8 * FLAGS_height + rest_height + eps, + x_f(pos_map.at("base_z"))); // Zero starting and final velocities - trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x0.tail(n_v)); - trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == xf.tail(n_v)); + trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); + trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x_f.tail(n_v)); // create joint/motor names vector> l_r_pairs{ @@ -433,6 +488,10 @@ void setKinematicConstraints(HybridDircon* trajopt, "hip_roll", "hip_yaw", }; + vector spring_joint_names{ + "knee_joint", + "ankle_spring_joint", + }; vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; @@ -447,60 +506,68 @@ void setKinematicConstraints(HybridDircon* trajopt, motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); } } + if (FLAGS_use_springs) { + for (const auto& spring_joint_name : spring_joint_names) { + joint_names.push_back(spring_joint_name + l_r_pair.first); + } + } } - l_r_pairs.pop_back(); // Symmetry constraints for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { + trajopt->AddConstraintToAllKnotPoints( + x_0(pos_map[sym_joint_name + l_r_pair.first]) == + x_0(pos_map[sym_joint_name + l_r_pair.second])); trajopt->AddLinearConstraint( - x0(pos_map[sym_joint_name + l_r_pair.first]) == - x0(pos_map[sym_joint_name + l_r_pair.second])); - trajopt->AddLinearConstraint( - xf(pos_map[sym_joint_name + l_r_pair.first]) == - xf(pos_map[sym_joint_name + l_r_pair.second])); + x_f(pos_map[sym_joint_name + l_r_pair.first]) == + x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle - trajopt->AddLinearConstraint( - u0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - u0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); - trajopt->AddLinearConstraint( - uf(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - uf(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + trajopt->AddConstraintToAllKnotPoints( + u_0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == + u_0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + trajopt->AddConstraintToAllKnotPoints( + u_f(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == + u_f(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); } } } // joint limits std::cout << "Joint limit constraints: " << std::endl; + for (const auto& member : joint_names) { trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) <= - plant.GetJointByName(member).position_upper_limits()(0)); + plant.GetJointByName(member).position_upper_limits()(0)); trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) >= - plant.GetJointByName(member).position_lower_limits()(0)); + plant.GetJointByName(member).position_lower_limits()(0)); } // actuator limits std::cout << "Actuator limit constraints: " << std::endl; for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); - trajopt->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -300), - VectorXd::Constant(n_u, +300), ui); + trajopt->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), + VectorXd::Constant(n_u, +175), ui); } + Vector3d pt_front_contact(-0.0457, 0.112, 0); + Vector3d pt_rear_contact(0.088, 0, 0); + // toe position constraint in y direction (avoid leg crossing) // tighter constraint than before auto left_foot_y_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - 0.2 * VectorXd::Ones(1), 0.25 * VectorXd::Ones(1)); + 0.1 * VectorXd::Ones(1), 0.15 * VectorXd::Ones(1)); auto right_foot_y_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - -0.25 * VectorXd::Ones(1), -0.2 * VectorXd::Ones(1)); - for (int mode = 2; mode < 3; ++mode) { + -0.15 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + for (int mode : {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); @@ -508,329 +575,360 @@ void setKinematicConstraints(HybridDircon* trajopt, trajopt->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); } } + + // Jumping distance constraint for platform clearance + auto left_foot_x_start_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + (0 - eps) * VectorXd::Ones(1), (0 + eps) * VectorXd::Ones(1)); + auto right_foot_x_start_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + (0 - eps) * VectorXd::Ones(1), (0 + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_x_start_constraint, x_0.head(n_q)); + trajopt->AddConstraint(right_foot_x_start_constraint, x_0.head(n_q)); + + // Jumping distance constraint for platform clearance + auto left_foot_x_platform_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), + 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); + auto right_foot_x_platform_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), + 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); + trajopt->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); + // Jumping distance constraint auto left_foot_x_constraint = std::make_shared>( - plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), + plant, "toe_left", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), (FLAGS_distance - eps) * VectorXd::Ones(1), (FLAGS_distance + eps) * VectorXd::Ones(1)); auto right_foot_x_constraint = std::make_shared>( - plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), + plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), (FLAGS_distance - eps) * VectorXd::Ones(1), (FLAGS_distance + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_x_constraint, xf.head(n_q)); - trajopt->AddConstraint(right_foot_x_constraint, xf.head(n_q)); + trajopt->AddConstraint(left_foot_x_constraint, x_f.head(n_q)); + trajopt->AddConstraint(right_foot_x_constraint, x_f.head(n_q)); // Foot clearance constraint auto left_foot_z_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.75 * FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), + (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); auto right_foot_z_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.75 * FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), + (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); trajopt->AddConstraint(left_foot_z_constraint, x_top.head(n_q)); trajopt->AddConstraint(right_foot_z_constraint, x_top.head(n_q)); + auto left_foot_rear_z_final_constraint = + std::make_shared>( + plant, "toe_left", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + auto right_foot_rear_z_final_constraint = + std::make_shared>( + plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_rear_z_final_constraint, x_f.head(n_q)); + trajopt->AddConstraint(right_foot_rear_z_final_constraint, x_f.head(n_q)); + + auto left_foot_front_z_final_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + auto right_foot_front_z_final_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_front_z_final_constraint, x_f.head(n_q)); + trajopt->AddConstraint(right_foot_front_z_final_constraint, x_f.head(n_q)); + // Only add constraints of lambdas for stance modes - vector stance_modes{0, 2}; // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - for (int index = 0; index < (mode_lengths[0] - 1); index++) { - auto lambda = trajopt->force(0, index); - trajopt->AddLinearConstraint(lambda(2) >= 15); - trajopt->AddLinearConstraint(lambda(5) >= 15); - trajopt->AddLinearConstraint(lambda(8) >= 15); - trajopt->AddLinearConstraint(lambda(11) >= 15); + for (int index = 0; index < (mode_lengths[0] - 2); index++) { + auto lambda = trajopt->force_vars(0, index); + trajopt->AddLinearConstraint(lambda(2) >= 60); + trajopt->AddLinearConstraint(lambda(5) >= 60); + trajopt->AddLinearConstraint(lambda(8) >= 60); + trajopt->AddLinearConstraint(lambda(11) >= 60); } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { - auto lambda = trajopt->force(2, index); - trajopt->AddLinearConstraint(lambda(2) <= 300); - trajopt->AddLinearConstraint(lambda(5) <= 300); - trajopt->AddLinearConstraint(lambda(8) <= 300); - trajopt->AddLinearConstraint(lambda(11) <= 300); + auto lambda = trajopt->force_vars(2, index); + trajopt->AddLinearConstraint(lambda(2) <= 350); + trajopt->AddLinearConstraint(lambda(5) <= 350); + trajopt->AddLinearConstraint(lambda(8) <= 350); + trajopt->AddLinearConstraint(lambda(11) <= 350); + trajopt->AddLinearConstraint(lambda(2) >= 50); + trajopt->AddLinearConstraint(lambda(5) >= 50); + trajopt->AddLinearConstraint(lambda(8) >= 50); + trajopt->AddLinearConstraint(lambda(11) >= 50); } + // Limit the ground impulses when landing + auto Lambda = trajopt->impulse_vars(1); + trajopt->AddLinearConstraint(Lambda(2) <= 2); + trajopt->AddLinearConstraint(Lambda(5) <= 2); + trajopt->AddLinearConstraint(Lambda(8) <= 2); + trajopt->AddLinearConstraint(Lambda(11) <= 2); +} - MatrixXd Q = 0.1 * MatrixXd::Identity(n_v, n_v); - MatrixXd R = 0.005 * MatrixXd::Identity(n_u, n_u); - Q(0, 0) = 5; - Q(1, 1) = 5; - Q(2, 2) = 5; - trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); - trajopt->AddRunningCost(u.transpose() * R * u); +/****** +COSTS +******/ +void AddCosts(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence* constraints) { + auto x = trajopt->state(); + auto u = trajopt->input(); + + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); - // Add some cost to hip roll and yaw - double w_q_hip_roll = 0.3; - double w_q_hip_yaw = 0.3; - double w_q_hip_pitch = 0.0; - double w_q_quat_xyz = 0.0; - if (w_q_hip_roll) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(7, 2); - trajopt->AddCost(w_q_hip_roll * q.transpose() * q); + int n_v = plant.num_velocities(); + int n_u = plant.num_actuators(); + + // create joint/motor names + vector> l_r_pairs{ + std::pair("_left", "_right"), + std::pair("_right", "_left"), + }; + vector asy_joint_names{ + "hip_roll", + "hip_yaw", + }; + vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; + vector joint_names{}; + vector motor_names{}; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + joint_names.push_back(asy_joint_name + l_r_pair.first); + motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); + } + for (const auto& sym_joint_name : sym_joint_names) { + joint_names.push_back(sym_joint_name + l_r_pair.first); + if (sym_joint_name != "ankle_joint") { + motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); + } } } - if (w_q_hip_yaw) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(9, 2); - trajopt->AddCost(w_q_hip_yaw * q.transpose() * q); + l_r_pairs.pop_back(); + + double w_symmetry_pos = FLAGS_cost_scaling * 1e5; + double w_symmetry_vel = FLAGS_cost_scaling * 1e2; + double w_symmetry_u = FLAGS_cost_scaling * 1e2; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { + auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - + x(pos_map.at(sym_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - + x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (sym_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + + } } } - if (w_q_hip_pitch) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(11, 2); - trajopt->AddCost(w_q_hip_pitch * q.transpose() * q); + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + + x(pos_map.at(asy_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + + x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (asy_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + + } } } - if (w_q_quat_xyz) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(1, 3); - trajopt->AddCost(w_q_quat_xyz * q.transpose() * q); + + MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); + MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = 5e-1; + R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) = 5e-1; + R(act_map.at("hip_yaw_left_motor"), act_map.at("hip_yaw_left_motor")) = 5e-1; + R(act_map.at("hip_yaw_right_motor"), act_map.at("hip_yaw_right_motor")) = 5e-1; + R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) = 5e-5; + R(act_map.at("hip_pitch_right_motor"), act_map.at("hip_pitch_right_motor")) = 5e-5; + + Q *= FLAGS_cost_scaling; + R *= FLAGS_cost_scaling; + trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + trajopt->AddRunningCost(u.transpose() * R * u); + + vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, + FLAGS_knot_points}; + MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; + W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; + W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; + W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + W *= 2.0 * FLAGS_cost_scaling; + vector> joint_accel_costs; + for (int mode : {0, 1, 2}) { + joint_accel_costs.push_back( + std::make_shared(W, plant, &constraints->mode(mode).evaluators())); + for (int index = 0; index < mode_lengths[mode]; index++) { + // Assumes mode_lengths are the same across modes + auto x_i = trajopt->state_vars(mode, index); + auto u_i = trajopt->input_vars(mode, index); + auto l_i = trajopt->force_vars(mode, index); + trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } } } -vector GetInitGuessForQStance(int num_knot_points, - const MultibodyPlant& plant) { - int n_q = plant.num_positions(); +/****** +COSTS +******/ +void AddCostsSprings(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence* constraints) { + auto x = trajopt->state(); + auto u = trajopt->input(); + + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + int n_v = plant.num_velocities(); - int n_x = n_q + n_v; - map positions_map = multibody::makeNameToPositionsMap(plant); - - vector q_init_guess; - VectorXd q_ik_guess = VectorXd::Zero(n_q); - Eigen::Vector4d quat(2000.06, -0.339462, -0.609533, -0.760854); - q_ik_guess << quat.normalized(), 0.000889849, 0.000626865, 1.0009, -0.0112109, - 0.00927845, -0.000600725, -0.000895805, 1.15086, 0.610808, -1.38608, - -1.35926, 0.806192, 1.00716, -M_PI / 2, -M_PI / 2; - - for (int i = 0; i < num_knot_points; i++) { - double eps = 1e-3; - Vector3d eps_vec = eps * VectorXd::Ones(3); - Vector3d pelvis_pos( - 0.0, 0.0, - FLAGS_start_height + 0.01 * (i - num_knot_points / 2) * (i - num_knot_points / 2)); - Vector3d left_toe_pos(0.0, 0.12, 0.05); - Vector3d right_toe_pos(0.0, -0.12, 0.05); - - const auto& world_frame = plant.world_frame(); - const auto& pelvis_frame = plant.GetFrameByName("pelvis"); - const auto& toe_left_frame = plant.GetFrameByName("toe_left"); - const auto& toe_right_frame = plant.GetFrameByName("toe_right"); - - drake::multibody::InverseKinematics ik(plant); - ik.AddPositionConstraint(pelvis_frame, Vector3d(0, 0, 0), world_frame, - pelvis_pos - eps * VectorXd::Ones(3), - pelvis_pos + eps * VectorXd::Ones(3)); - ik.AddOrientationConstraint(pelvis_frame, RotationMatrix(), - world_frame, RotationMatrix(), eps); - ik.AddPositionConstraint(toe_left_frame, Vector3d(0, 0, 0), world_frame, - left_toe_pos - eps_vec, left_toe_pos + eps_vec); - ik.AddPositionConstraint(toe_right_frame, Vector3d(0, 0, 0), world_frame, - right_toe_pos - eps_vec, right_toe_pos + eps_vec); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_left")) == 0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_right")) == 0); - // Four bar linkage constraint (without spring) - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_left")) + - (ik.q())(positions_map.at("ankle_joint_left")) == - M_PI * 13 / 180.0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_right")) + - (ik.q())(positions_map.at("ankle_joint_right")) == - M_PI * 13 / 180.0); - ik.get_mutable_prog()->SetInitialGuess(ik.q(), q_ik_guess); - const auto result = Solve(ik.prog()); - const auto q_sol = result.GetSolution(ik.q()); - // cout << " q_sol = " << q_sol.transpose() << endl; - // cout << " q_sol.head(4).norm() = " << q_sol.head(4).norm() << endl; - VectorXd q_sol_normd(n_q); - q_sol_normd << q_sol.head(4).normalized(), q_sol.tail(n_q - 4); - q_ik_guess = q_sol_normd; - q_init_guess.push_back(q_sol_normd); - - bool visualize_init_traj = false; - if (visualize_init_traj) { - // Build temporary diagram for visualization - drake::systems::DiagramBuilder builder_ik; - SceneGraph& scene_graph_ik = *builder_ik.AddSystem(); - scene_graph_ik.set_name("scene_graph_ik"); - MultibodyPlant plant_ik(1e-4); - multibody::addFlatTerrain(&plant_ik, &scene_graph_ik, .8, .8); - Parser parser(&plant_ik, &scene_graph_ik); - string full_name = - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); - plant_ik.mutable_gravity_field().set_gravity_vector( - -9.81 * Eigen::Vector3d::UnitZ()); - plant_ik.Finalize(); - - // Visualize - VectorXd x_const = VectorXd::Zero(n_x); - x_const.head(n_q) = q_sol; - PiecewisePolynomial pp_xtraj(x_const); - - multibody::connectTrajectoryVisualizer(&plant_ik, &builder_ik, - &scene_graph_ik, pp_xtraj); - auto diagram = builder_ik.Build(); - drake::systems::Simulator simulator(*diagram); - simulator.set_target_realtime_rate(.1); - simulator.Initialize(); - simulator.AdvanceTo(1.0 / num_knot_points); + int n_u = plant.num_actuators(); + + // create joint/motor names + vector> l_r_pairs{ + std::pair("_left", "_right"), + std::pair("_right", "_left"), + }; + vector asy_joint_names{ + "hip_roll", + "hip_yaw", + }; + vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; + vector joint_names{}; + vector motor_names{}; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + joint_names.push_back(asy_joint_name + l_r_pair.first); + motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); + } + for (const auto& sym_joint_name : sym_joint_names) { + joint_names.push_back(sym_joint_name + l_r_pair.first); + if (sym_joint_name != "ankle_joint") { + motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); + } } } + l_r_pairs.pop_back(); - return q_init_guess; -} - -vector GetInitGuessForQFlight(int num_knot_points, double apex_height, - const MultibodyPlant& plant) { - int n_q = plant.num_positions(); - int n_v = plant.num_velocities(); - int n_x = n_q + n_v; - map positions_map = multibody::makeNameToPositionsMap(plant); - - vector q_init_guess; - VectorXd q_ik_guess = VectorXd::Zero(n_q); - Eigen::Vector4d quat(2000.06, -0.339462, -0.609533, -0.760854); - q_ik_guess << quat.normalized(), 0.000889849, 0.000626865, 1.0009, -0.0112109, - 0.00927845, -0.000600725, -0.000895805, 1.15086, 0.610808, -1.38608, - -1.35926, 0.806192, 1.00716, -M_PI / 2, -M_PI / 2; - - double factor = apex_height / (num_knot_points * num_knot_points / 4.0); - double rest_height = 1.0; - - for (int i = 0; i < num_knot_points; i++) { - double eps = 1e-3; - Vector3d eps_vec = eps * VectorXd::Ones(3); - double height_offset = apex_height - factor * (i - num_knot_points / 2.0) * - (i - num_knot_points / 2.0); - Vector3d pelvis_pos(0.0, 0.0, rest_height + height_offset); - // Do not raise the toes as much as the pelvis, (leg extension) - Vector3d left_toe_pos(0.0, 0.12, 0.05 + height_offset * 0.5); - Vector3d right_toe_pos(0.0, -0.12, 0.05 + height_offset * 0.5); - - const auto& world_frame = plant.world_frame(); - const auto& pelvis_frame = plant.GetFrameByName("pelvis"); - const auto& toe_left_frame = plant.GetFrameByName("toe_left"); - const auto& toe_right_frame = plant.GetFrameByName("toe_right"); - - drake::multibody::InverseKinematics ik(plant); - ik.AddPositionConstraint(pelvis_frame, Vector3d(0, 0, 0), world_frame, - pelvis_pos - eps * VectorXd::Ones(3), - pelvis_pos + eps * VectorXd::Ones(3)); - ik.AddOrientationConstraint(pelvis_frame, RotationMatrix(), - world_frame, RotationMatrix(), eps); - ik.AddPositionConstraint(toe_left_frame, Vector3d(0, 0, 0), world_frame, - left_toe_pos - eps_vec, left_toe_pos + eps_vec); - ik.AddPositionConstraint(toe_right_frame, Vector3d(0, 0, 0), world_frame, - right_toe_pos - eps_vec, right_toe_pos + eps_vec); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_left")) == 0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_right")) == 0); - // Four bar linkage constraint (without spring) - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_left")) + - (ik.q())(positions_map.at("ankle_joint_left")) == - M_PI * 13 / 180.0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_right")) + - (ik.q())(positions_map.at("ankle_joint_right")) == - M_PI * 13 / 180.0); - - ik.get_mutable_prog()->SetInitialGuess(ik.q(), q_ik_guess); - const auto result = Solve(ik.prog()); - const auto q_sol = result.GetSolution(ik.q()); - // cout << " q_sol = " << q_sol.transpose() << endl; - // cout << " q_sol.head(4).norm() = " << q_sol.head(4).norm() << endl; - VectorXd q_sol_normd(n_q); - q_sol_normd << q_sol.head(4).normalized(), q_sol.tail(n_q - 4); - q_ik_guess = q_sol_normd; - q_init_guess.push_back(q_sol_normd); - - bool visualize_init_traj = false; - if (visualize_init_traj) { - // Build temporary diagram for visualization - drake::systems::DiagramBuilder builder_ik; - SceneGraph& scene_graph_ik = *builder_ik.AddSystem(); - scene_graph_ik.set_name("scene_graph_ik"); - MultibodyPlant plant_ik(1e-4); - multibody::addFlatTerrain(&plant_ik, &scene_graph_ik, .8, .8); - Parser parser(&plant_ik, &scene_graph_ik); - string full_name = - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); - plant_ik.mutable_gravity_field().set_gravity_vector( - -9.81 * Eigen::Vector3d::UnitZ()); - plant_ik.Finalize(); - - // Visualize - VectorXd x_const = VectorXd::Zero(n_x); - x_const.head(n_q) = q_sol; - PiecewisePolynomial pp_xtraj(x_const); - - multibody::connectTrajectoryVisualizer(&plant_ik, &builder_ik, - &scene_graph_ik, pp_xtraj); - auto diagram = builder_ik.Build(); - drake::systems::Simulator simulator(*diagram); - simulator.set_target_realtime_rate(.1); - simulator.Initialize(); - simulator.AdvanceTo(1.0 / num_knot_points); + double w_symmetry_pos = 1e3; + double w_symmetry_vel = 1e1; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { + auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - + x(pos_map[sym_joint_name + l_r_pair.second]); + auto vel_diff = x(vel_map[sym_joint_name + l_r_pair.first + "dot"]) - + x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); } } - return q_init_guess; -} + std::cout << "n_v_: " << n_v << std::endl; + MatrixXd Q = 0.01 * MatrixXd::Identity(n_v, n_v); + MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + Q *= FLAGS_cost_scaling; + R *= FLAGS_cost_scaling; -// Get v by finite differencing q -vector GetInitGuessForV(const vector& q_guess, double dt, - const MultibodyPlant& plant) { - bool standing = false; - if (!standing) { - vector qdot_guess; - qdot_guess.push_back((q_guess[1] - q_guess[0]) / dt); - for (unsigned int i = 1; i < q_guess.size() - 1; i++) { - VectorXd v_plus = (q_guess[i + 1] - q_guess[i]) / dt; - VectorXd v_minus = (q_guess[i] - q_guess[i - 1]) / dt; - qdot_guess.push_back((v_plus + v_minus) / 2); - } - qdot_guess.push_back((q_guess.back() - q_guess[q_guess.size() - 2]) / dt); - - // Convert qdot to v - DRAKE_ASSERT(qdot_guess.size() == q_guess.size()); - vector v_seed; - for (unsigned int i = 0; i < q_guess.size(); i++) { - auto context = plant.CreateDefaultContext(); - plant.SetPositions(context.get(), q_guess[i]); - VectorXd v(plant.num_velocities()); - plant.MapQDotToVelocity(*context, qdot_guess[i], &v); - v_seed.push_back(v); - } - return v_seed; - } else { - vector v_seed; - for (unsigned int i = 0; i < q_guess.size(); ++i) { - VectorXd zeros = VectorXd::Zero(plant.num_velocities()); + trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + trajopt->AddRunningCost(u.transpose() * R * u); - v_seed.push_back(zeros); + vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, + FLAGS_knot_points}; + MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) *= 1e1; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) *= 1e1; + W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) *= 1e1; + W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) *= 1e1; + // Add no costs on spring acceleration because we can't control for that + W(vel_map["knee_joint_leftdot"], vel_map["knee_joint_leftdot"]) = 0.0; + W(vel_map["knee_joint_rightdot"], vel_map["knee_joint_rightdot"]) = 0.0; + W(vel_map["ankle_spring_joint_leftdot"], vel_map["ankle_spring_joint_leftdot"]) = 0.0; + W(vel_map["ankle_spring_joint_rightdot"], vel_map["ankle_spring_joint_rightdot"]) = 0.0; + W *= FLAGS_cost_scaling; + vector> joint_accel_costs; + for (int mode : {0, 1, 2}) { + joint_accel_costs.push_back( + std::make_shared(W, plant, &constraints->mode(mode).evaluators())); + for (int index = 0; index < mode_lengths[mode]; index++) { + // Assumes mode_lengths are the same across modes + auto x_i = trajopt->state_vars(mode, index); + auto u_i = trajopt->input_vars(mode, index); + auto l_i = trajopt->force_vars(mode, index); + trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } - return v_seed; + } +} + +void SetInitialGuessFromTrajectory(Dircon& trajopt, + const string& filepath, + bool same_knot_points, + Eigen::MatrixXd spr_map) { + DirconTrajectory previous_traj = DirconTrajectory(filepath); + if (same_knot_points) { + trajopt.SetInitialGuessForAllVariables( + previous_traj.GetDecisionVariables()); + return; + } + PiecewisePolynomial state_traj; + if (FLAGS_use_springs && FLAGS_convert_to_springs) { + std::cout << "Using spring conversion" << std::endl; + state_traj = previous_traj.ReconstructStateTrajectoryWithSprings(spr_map); + } else { + state_traj = previous_traj.ReconstructStateTrajectory(); + } + auto input_traj = previous_traj.ReconstructInputTrajectory(); + auto lambda_traj = previous_traj.ReconstructLambdaTrajectory(); + auto lambda_c_traj = previous_traj.ReconstructLambdaCTrajectory(); + auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); + + trajopt.SetInitialTrajectory(input_traj, state_traj); + for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], + lambda_c_traj[mode], gamma_traj[mode]); } } MatrixXd loadSavedDecisionVars(const string& filepath) { - DirconTrajectory loaded_decision_vars = DirconTrajectory(filepath); - for (auto& name : loaded_decision_vars.GetTrajectoryNames()) { + DirconTrajectory previous_traj = DirconTrajectory(filepath); + for (auto& name : previous_traj.GetTrajectoryNames()) { std::cout << name << std::endl; } - return loaded_decision_vars.GetDecisionVariables(); + return previous_traj.GetDecisionVariables(); } } // namespace dairlib @@ -838,4 +936,4 @@ MatrixXd loadSavedDecisionVars(const string& filepath) { int main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); dairlib::DoMain(); -} \ No newline at end of file +} diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 1bf9cb0543..ea0a8aaad5 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -1,9 +1,9 @@ + #include #include #include #include #include -#include #include #include "dairlib/lcmt_robot_input.hpp" @@ -21,10 +21,12 @@ #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/osc_tracking_data.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" namespace dairlib { @@ -44,9 +46,9 @@ using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using examples::osc_jump::FlightFootTrajGenerator; @@ -54,6 +56,7 @@ using examples::osc_jump::JumpingEventFsm; using examples::osc_jump::PelvisTransTrajGenerator; using multibody::FixedJointEvaluator; using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; @@ -76,8 +79,7 @@ DEFINE_string(simulator, "DRAKE", "contact information. Other options include MUJOCO and soon to " "include contact results from the GM contact estimator."); DEFINE_int32(init_fsm_state, osc_jump::BALANCE, "Initial state of the FSM"); -DEFINE_string(folder_path, - "examples/impact_invariant_control/saved_trajectories/", +DEFINE_string(folder_path, "examples/Cassie/saved_trajectories/", "Folder path for where the trajectory names are stored"); DEFINE_string(traj_name, "jumping_0.15h_0.3d", "File to load saved trajectories from"); @@ -93,7 +95,7 @@ int DoMain(int argc, char* argv[]) { // Built the Cassie MBPs drake::multibody::MultibodyPlant plant_w_spr(0.0); addCassieMultibody(&plant_w_spr, nullptr, true, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); plant_w_spr.Finalize(); @@ -137,6 +139,10 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial pelvis_trans_traj; PiecewisePolynomial l_foot_trajectory; PiecewisePolynomial r_foot_trajectory; + PiecewisePolynomial l_hip_trajectory; + PiecewisePolynomial r_hip_trajectory; + PiecewisePolynomial l_toe_trajectory; + PiecewisePolynomial r_toe_trajectory; PiecewisePolynomial pelvis_rot_trajectory; for (int mode = 0; mode < dircon_trajectory.GetNumModes(); ++mode) { @@ -149,6 +155,18 @@ int DoMain(int argc, char* argv[]) { const LcmTrajectory::Trajectory lcm_right_foot_traj = output_trajs.GetTrajectory("right_foot_trajectory" + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_left_hip_traj = + output_trajs.GetTrajectory("left_hip_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_right_hip_traj = + output_trajs.GetTrajectory("right_hip_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_left_toe_traj = + output_trajs.GetTrajectory("left_toe_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_right_toe_traj = + output_trajs.GetTrajectory("right_toe_trajectory" + + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_pelvis_rot_traj = output_trajs.GetTrajectory("pelvis_rot_trajectory" + std::to_string(mode)); @@ -167,6 +185,26 @@ int DoMain(int argc, char* argv[]) { lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints.topRows(3), lcm_right_foot_traj.datapoints.bottomRows(3))); + l_hip_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_left_hip_traj.time_vector, + lcm_left_hip_traj.datapoints.topRows(3), + lcm_left_hip_traj.datapoints.bottomRows(3))); + r_hip_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_right_hip_traj.time_vector, + lcm_right_hip_traj.datapoints.topRows(3), + lcm_right_hip_traj.datapoints.bottomRows(3))); + l_toe_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_left_toe_traj.time_vector, + lcm_left_toe_traj.datapoints.topRows(1), + lcm_left_toe_traj.datapoints.bottomRows(1))); + r_toe_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_right_toe_traj.time_vector, + lcm_right_toe_traj.datapoints.topRows(1), + lcm_right_toe_traj.datapoints.bottomRows(1))); pelvis_rot_trajectory.ConcatenateInTime( PiecewisePolynomial::FirstOrderHold( lcm_pelvis_rot_traj.time_vector, @@ -186,18 +224,13 @@ int DoMain(int argc, char* argv[]) { Vector3d support_center_offset; support_center_offset << gains.x_offset, 0.0, 0.0; std::vector breaks = pelvis_trans_traj.get_segment_times(); - std::vector ft_breaks = l_foot_trajectory.get_segment_times(); VectorXd breaks_vector = Eigen::Map(breaks.data(), breaks.size()); - VectorXd ft_breaks_vector = - Eigen::Map(ft_breaks.data(), ft_breaks.size()); MatrixXd offset_points = support_center_offset.replicate(1, breaks.size()); - MatrixXd ft_offset_points = - support_center_offset.replicate(1, ft_breaks_vector.size()); PiecewisePolynomial offset_traj = PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_points); pelvis_trans_traj = pelvis_trans_traj + offset_traj; - l_foot_trajectory = l_foot_trajectory - ft_offset_points; - r_foot_trajectory = r_foot_trajectory - ft_offset_points; + l_foot_trajectory = l_foot_trajectory + offset_traj; + r_foot_trajectory = r_foot_trajectory + offset_traj; /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -206,16 +239,15 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant_w_spr); // This actually outputs the target position of the pelvis not the true // center of mass - auto pelvis_trans_traj_generator = - builder.AddSystem( - plant_w_spr, context_w_spr.get(), pelvis_trans_traj, - feet_contact_points, FLAGS_delay_time); + auto com_traj_generator = builder.AddSystem( + plant_w_spr, context_w_spr.get(), pelvis_trans_traj, feet_contact_points, + FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_left", true, l_foot_trajectory, - gains.relative_feet, FLAGS_delay_time); + l_hip_trajectory, gains.relative_feet, FLAGS_delay_time); auto r_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_right", false, r_foot_trajectory, - gains.relative_feet, FLAGS_delay_time); + r_hip_trajectory, gains.relative_feet, FLAGS_delay_time); auto pelvis_rot_traj_generator = builder.AddSystem( pelvis_rot_trajectory, "pelvis_rot_tracking_data", FLAGS_delay_time); @@ -260,6 +292,9 @@ int DoMain(int argc, char* argv[]) { // Soft constraint on contacts double w_contact_relax = gains.w_soft_constraint; osc->SetWeightOfSoftContactConstraint(w_contact_relax); + // Soft constraint on contacts + double w_input_reg = gains.w_input_reg; + osc->SetInputRegularizationWeight(w_input_reg); // Contact information for OSC osc->SetContactFriction(gains.mu); @@ -314,13 +349,19 @@ int DoMain(int argc, char* argv[]) { osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ - TransTaskSpaceTrackingData pelvis_tracking_data("pelvis_traj", gains.K_p_com, + TransTaskSpaceTrackingData pelvis_tracking_data("com_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { pelvis_tracking_data.AddStateAndPointToTrack(mode, "pelvis"); } - osc->AddTrackingData(&pelvis_tracking_data); + + RotTaskSpaceTrackingData pelvis_rot_tracking_data( + "pelvis_rot_tracking_data", gains.K_p_pelvis, gains.K_d_pelvis, + gains.W_pelvis, plant_w_spr, plant_w_spr); + for (auto mode : stance_modes) { + pelvis_rot_tracking_data.AddStateAndFrameToTrack(mode, "pelvis"); + } TransTaskSpaceTrackingData left_foot_tracking_data( "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, @@ -332,13 +373,24 @@ int DoMain(int argc, char* argv[]) { right_foot_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, "toe_right"); - RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_tracking_data", gains.K_p_pelvis, gains.K_d_pelvis, - gains.W_pelvis, plant_w_spr, plant_w_spr); + TransTaskSpaceTrackingData left_hip_tracking_data( + "left_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr); + TransTaskSpaceTrackingData right_hip_tracking_data( + "right_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr); + left_hip_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, "hip_left"); + right_hip_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, + "hip_right"); - for (auto mode : stance_modes) { - pelvis_rot_tracking_data.AddStateAndFrameToTrack(mode, "pelvis"); - } + RelativeTranslationTrackingData left_foot_rel_tracking_data( + "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr, &left_foot_tracking_data, + &left_hip_tracking_data); + RelativeTranslationTrackingData right_foot_rel_tracking_data( + "right_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr, &right_foot_tracking_data, + &right_hip_tracking_data); // Flight phase hip yaw tracking MatrixXd W_hip_yaw = gains.w_hip_yaw * MatrixXd::Identity(1, 1); @@ -375,29 +427,40 @@ int DoMain(int argc, char* argv[]) { auto left_toe_angle_traj_gen = builder.AddSystem( - plant_w_spr, context_w_spr.get(), pos_map["toe_left"], - left_foot_points, "left_toe_angle_traj"); + plant_w_spr, context_w_spr.get(), l_toe_trajectory, + pos_map["toe_left"], left_foot_points, "left_toe_angle_traj"); auto right_toe_angle_traj_gen = builder.AddSystem( - plant_w_spr, context_w_spr.get(), pos_map["toe_right"], - right_foot_points, "right_toe_angle_traj"); + plant_w_spr, context_w_spr.get(), r_toe_trajectory, + pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); left_toe_angle_traj.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_left", "toe_leftdot"); right_toe_angle_traj.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_right", "toe_rightdot"); - pelvis_rot_tracking_data.SetImpactInvariantProjection(true); - left_foot_tracking_data.SetImpactInvariantProjection(true); - right_foot_tracking_data.SetImpactInvariantProjection(true); - left_toe_angle_traj.SetImpactInvariantProjection(true); - right_toe_angle_traj.SetImpactInvariantProjection(true); + osc->AddTrackingData(&pelvis_tracking_data); osc->AddTrackingData(&pelvis_rot_tracking_data); - osc->AddTrackingData(&left_foot_tracking_data); - osc->AddTrackingData(&right_foot_tracking_data); + if (gains.relative_feet) { + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_rel_tracking_data); + osc->AddTrackingData(&right_foot_rel_tracking_data); + } else { + left_foot_tracking_data.SetImpactInvariantProjection(true); + right_foot_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_tracking_data); + osc->AddTrackingData(&right_foot_tracking_data); + } osc->AddTrackingData(&left_toe_angle_traj); osc->AddTrackingData(&right_toe_angle_traj); + left_toe_angle_traj.SetImpactInvariantProjection(true); + right_toe_angle_traj.SetImpactInvariantProjection(true); + swing_hip_yaw_left_traj.SetImpactInvariantProjection(true); + swing_hip_yaw_right_traj.SetImpactInvariantProjection(true); + pelvis_rot_tracking_data.SetImpactInvariantProjection(true); + pelvis_tracking_data.SetImpactInvariantProjection(true); // Build OSC problem osc->Build(); @@ -407,12 +470,13 @@ int DoMain(int argc, char* argv[]) { // OSC connections builder.Connect(fsm->get_fsm_output_port(), osc->get_fsm_input_port()); + builder.Connect(fsm->get_clock_output_port(), osc->get_clock_input_port()); builder.Connect(fsm->get_impact_output_port(), osc->get_near_impact_input_port()); builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); - builder.Connect(pelvis_trans_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_traj")); + builder.Connect(com_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("com_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), @@ -433,7 +497,7 @@ int DoMain(int argc, char* argv[]) { // Trajectory generator connections builder.Connect(state_receiver->get_output_port(0), - pelvis_trans_traj_generator->get_state_input_port()); + com_traj_generator->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), l_foot_traj_generator->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), @@ -443,7 +507,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(state_receiver->get_output_port(0), right_toe_angle_traj_gen->get_state_input_port()); builder.Connect(fsm->get_output_port(0), - pelvis_trans_traj_generator->get_fsm_input_port()); + com_traj_generator->get_fsm_input_port()); builder.Connect(fsm->get_output_port(0), l_foot_traj_generator->get_fsm_input_port()); builder.Connect(fsm->get_output_port(0), @@ -463,11 +527,12 @@ int DoMain(int argc, char* argv[]) { // Run lcm-driven simulation // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc jumping controller")); + owned_diagram->set_name(("osc_jumping_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); return 0; diff --git a/examples/Cassie/visualize_trajectory.cc b/examples/Cassie/visualize_trajectory.cc index 6d07c2d39d..633b7dbf85 100644 --- a/examples/Cassie/visualize_trajectory.cc +++ b/examples/Cassie/visualize_trajectory.cc @@ -30,7 +30,13 @@ DEFINE_int32(visualize_mode, 0, "0 - Single animation" "1 - Looped animation" "2 - Multipose visualizer"); -DEFINE_bool(use_transparency, false, "Transparency setting for the Multipose visualizer"); +DEFINE_bool(use_transparency, false, + "Transparency setting for the Multipose visualizer"); +DEFINE_bool(use_springs, false, "Set to true if the trajectory is for the model with springs"); +DEFINE_bool( + mirror_traj, false, + "Whether or not to extend the trajectory by mirroring the trajectory. Only " + "use for periodic trajectories that are symmetric."); namespace dairlib { @@ -46,13 +52,41 @@ int DoMain() { plant.Finalize(); int nq = plant.num_positions(); + int nv = plant.num_positions(); + int nx = nq + nv; std::unique_ptr> context = plant.CreateDefaultContext(); DirconTrajectory saved_traj(FLAGS_folder_path + FLAGS_trajectory_name); - VectorXd time_vector = saved_traj.GetBreaks(); + // VectorXd time_vector = saved_traj.GetBreaks(); PiecewisePolynomial optimal_traj = saved_traj.ReconstructStateTrajectory(); + std::vector time_vector = optimal_traj.get_segment_times(); + + if (FLAGS_mirror_traj) { + auto mirrored_traj = + saved_traj.ReconstructMirrorStateTrajectory(optimal_traj.end_time()); + VectorXd x_offset = VectorXd::Zero(nx); + x_offset(4) = optimal_traj.value(optimal_traj.end_time())(4) - + optimal_traj.value(optimal_traj.start_time())(4); + std::vector x_offset_rep(mirrored_traj.get_segment_times().size(), + x_offset); + PiecewisePolynomial x_offset_traj = + PiecewisePolynomial::ZeroOrderHold( + mirrored_traj.get_segment_times(), x_offset_rep); + optimal_traj.ConcatenateInTime(mirrored_traj + x_offset_traj); + + x_offset(4) = optimal_traj.value(optimal_traj.end_time())(4) - + optimal_traj.value(optimal_traj.start_time())(4); + x_offset_rep = std::vector( + optimal_traj.get_segment_times().size(), x_offset); + + PiecewisePolynomial copy = optimal_traj; + copy.shiftRight(optimal_traj.end_time()); + x_offset_traj = PiecewisePolynomial::ZeroOrderHold( + copy.get_segment_times(), x_offset_rep); + optimal_traj.ConcatenateInTime(copy + x_offset_traj); + } if (FLAGS_visualize_mode == 0 || FLAGS_visualize_mode == 1) { multibody::connectTrajectoryVisualizer(&plant, &builder, &scene_graph, @@ -73,17 +107,20 @@ int DoMain() { poses.col(i) = optimal_traj.value( time_vector[i * time_vector.size() / FLAGS_num_poses]); } - if(FLAGS_use_transparency){ + if (FLAGS_use_transparency) { VectorXd alpha_scale = VectorXd::LinSpaced(FLAGS_num_poses, 0.2, 1.0); - multibody::MultiposeVisualizer visualizer = multibody::MultiposeVisualizer( - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"), - FLAGS_num_poses, alpha_scale.array().square()); + multibody::MultiposeVisualizer visualizer = + multibody::MultiposeVisualizer( + FindResourceOrThrow( + "examples/Cassie/urdf/cassie_fixed_springs.urdf"), + FLAGS_num_poses, alpha_scale.array().square()); visualizer.DrawPoses(poses); - } - else{ - multibody::MultiposeVisualizer visualizer = multibody::MultiposeVisualizer( - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"), - FLAGS_num_poses); + } else { + multibody::MultiposeVisualizer visualizer = + multibody::MultiposeVisualizer( + FindResourceOrThrow( + "examples/Cassie/urdf/cassie_fixed_springs.urdf"), + FLAGS_num_poses); visualizer.DrawPoses(poses); } } diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 4fef6a9e37..f7ee7f4d13 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -11,6 +11,7 @@ using std::string; namespace dairlib { using systems::OutputVector; +using systems::ImpactInfoVector; ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( const drake::multibody::MultibodyPlant& plant, @@ -22,22 +23,29 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( t0_(t0), near_impact_threshold_(near_impact_threshold), blend_func_(blend_func) { + near_impact_port_ = - this->DeclareVectorOutputPort("next_fsm, t_to_impact", - BasicVector(2), + this->DeclareVectorOutputPort("near_impact", + ImpactInfoVector(0, 0, 0), &ImpactTimeBasedFiniteStateMachine::CalcNearImpact) .get_index(); + clock_port_ = this->DeclareVectorOutputPort("clock", + BasicVector(1), + &ImpactTimeBasedFiniteStateMachine::CalcClock) + .get_index(); // Accumulate the durations to get timestamps double sum = 0; DRAKE_DEMAND(states.size() == state_durations.size()); - impact_times_.push_back(0.0); - impact_states_.push_back(0); for (int i = 0; i < states.size(); ++i) { sum += state_durations[i]; + std::cout << "i: " << i << std::endl; + std::cout << "sum: " << sum << std::endl; accu_state_durations_.push_back(sum); - impact_times_.push_back(sum); - impact_states_.push_back(states[i]); + if (states[i] == 2) { + impact_times_.push_back(sum); + impact_states_.push_back(states[i+1]); + } } period_ = sum; @@ -53,7 +61,7 @@ double alpha_exp(double t, double tau, double near_impact_threshold) { } void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( - const Context& context, BasicVector* near_impact) const { + const Context& context, ImpactInfoVector* near_impact) const { // Read in lcm message time const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); @@ -64,27 +72,42 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( // Assign the blending function ptr auto alpha_func = blend_func_ == SIGMOID ? &alpha_sigmoid : &alpha_exp; - VectorXd near_impact_data = VectorXd::Zero(2); + near_impact->set_timestamp(current_time); + near_impact->SetCurrentContactMode(0); + near_impact->SetAlpha(0); // Get current finite state if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { + if (impact_states_[i] == 2) { + continue; + } double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ : near_impact_threshold_; if (abs(remainder - impact_times_[i]) < blend_window) { if (remainder < impact_times_[i]) { - near_impact_data(0) = alpha_func(remainder - impact_times_[i], tau_, - near_impact_threshold_); + near_impact->SetAlpha(alpha_func(remainder - impact_times_[i], tau_, + near_impact_threshold_)); } else { - near_impact_data(0) = alpha_func(impact_times_[i] - remainder, tau_, - near_impact_threshold_); + near_impact->SetAlpha(alpha_func(impact_times_[i] - remainder, tau_, + near_impact_threshold_)); } - near_impact_data(1) = impact_states_[i]; + near_impact->SetCurrentContactMode(impact_states_[i]); break; } } } - near_impact->get_mutable_value() = near_impact_data; +} + +void ImpactTimeBasedFiniteStateMachine::CalcClock( + const Context& context, BasicVector* clock) const { + // Read in lcm message time + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto current_time = static_cast(robot_output->get_timestamp()); + + double remainder = fmod(current_time, period_); + clock->get_mutable_value()(0) = remainder; } } // namespace dairlib diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index 64aafd51c8..08bedf8546 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -3,6 +3,7 @@ #include #include "systems/controllers/time_based_fsm.h" +#include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" #include "drake/multibody/plant/multibody_plant.h" @@ -27,20 +28,25 @@ class ImpactTimeBasedFiniteStateMachine const drake::systems::OutputPort& get_output_port_fsm() const { return this->get_output_port(fsm_port_); } + const drake::systems::OutputPort& get_output_port_clock() const { + return this->get_output_port(clock_port_); + } const drake::systems::OutputPort& get_output_port_impact() const { return this->get_output_port(near_impact_port_); } private: void CalcNearImpact(const drake::systems::Context& context, - drake::systems::BasicVector* near_impact) const; + systems::ImpactInfoVector* near_impact) const; + void CalcClock(const drake::systems::Context& context, + drake::systems::BasicVector* clock) const; int near_impact_port_; + int clock_port_; + double t0_; std::vector states_; std::vector state_durations_; - double t0_; - std::vector accu_state_durations_; std::vector impact_states_; std::vector impact_times_; diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index 15881dd316..88adb5e64c 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -31,6 +31,7 @@ DirconTrajectory::DirconTrajectory( LcmTrajectory::Trajectory state_traj; LcmTrajectory::Trajectory state_derivative_traj; LcmTrajectory::Trajectory force_traj; + LcmTrajectory::Trajectory impulse_traj; state_traj.traj_name = "state_traj" + std::to_string(mode); state_traj.datapoints = x[mode]; @@ -48,10 +49,12 @@ DirconTrajectory::DirconTrajectory( force_traj.traj_name = "force_vars" + std::to_string(mode); std::vector force_names; std::vector collocation_force_names; + std::vector impulse_names; int num_forces = dircon.get_evaluator_set(mode).count_full(); for (int i = 0; i < num_forces; ++i) { force_names.push_back("lambda_" + std::to_string(i)); + impulse_names.push_back("Lambda_" + std::to_string(i)); collocation_force_names.push_back("lambda_c_" + std::to_string(i)); } force_traj.datatypes = force_names; @@ -60,6 +63,15 @@ DirconTrajectory::DirconTrajectory( Eigen::Map(dircon.GetForceSamplesByMode(result, mode).data(), num_forces, force_traj.time_vector.size()); + // Impulse vars + if (mode > 0) { + impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); + impulse_traj.datatypes = impulse_names; + // Get start of mode to get time of impulse + impulse_traj.time_vector = state_breaks[mode].segment(0, 1); + impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode)); + } + // Collocation force vars if (state_breaks[mode].size() > 1) { LcmTrajectory::Trajectory collocation_force_traj; @@ -99,10 +111,12 @@ DirconTrajectory::DirconTrajectory( AddTrajectory(state_traj.traj_name, state_traj); AddTrajectory(state_derivative_traj.traj_name, state_derivative_traj); AddTrajectory(force_traj.traj_name, force_traj); + AddTrajectory(impulse_traj.traj_name, impulse_traj); x_.push_back(&state_traj); xdot_.push_back(&state_derivative_traj); lambda_.push_back(&force_traj); + impulse_.push_back(&impulse_traj); } // Input trajectory @@ -144,6 +158,7 @@ DirconTrajectory::DirconTrajectory( LcmTrajectory::Trajectory state_traj; LcmTrajectory::Trajectory state_derivative_traj; LcmTrajectory::Trajectory force_traj; + LcmTrajectory::Trajectory impulse_traj; state_traj.traj_name = "state_traj" + std::to_string(mode); state_traj.datapoints = x[mode]; @@ -160,13 +175,15 @@ DirconTrajectory::DirconTrajectory( // Force vars force_traj.traj_name = "force_vars" + std::to_string(mode); std::vector force_names; + std::vector impulse_names; std::vector collocation_force_names; int num_forces = 0; for (int i = 0; i < dircon.num_kinematic_constraints_wo_skipping(mode); ++i) { force_names.push_back("lambda_" + std::to_string(num_forces)); + impulse_names.push_back("Lambda_" + std::to_string(i)); collocation_force_names.push_back("lambda_c_" + - std::to_string(num_forces)); + std::to_string(num_forces)); ++num_forces; } force_traj.traj_name = "force_vars" + std::to_string(mode); @@ -176,6 +193,15 @@ DirconTrajectory::DirconTrajectory( num_forces, force_traj.time_vector.size()); force_traj.datatypes = force_names; + // Impulse vars + if (mode > 0) { + impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); + impulse_traj.datatypes = impulse_names; + // Get start of mode to get time of impulse + impulse_traj.time_vector = state_breaks[mode].segment(0, 1); + impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode - 1)); + } + // Collocation force vars if (state_breaks[mode].size() > 1) { LcmTrajectory::Trajectory collocation_force_traj; @@ -209,6 +235,7 @@ DirconTrajectory::DirconTrajectory( AddTrajectory(state_traj.traj_name, state_traj); AddTrajectory(state_derivative_traj.traj_name, state_derivative_traj); AddTrajectory(force_traj.traj_name, force_traj); + AddTrajectory(impulse_traj.traj_name, impulse_traj); x_.push_back(&state_traj); xdot_.push_back(&state_derivative_traj); @@ -241,11 +268,8 @@ DirconTrajectory::DirconTrajectory( } PiecewisePolynomial DirconTrajectory::ReconstructStateTrajectory() -const { + const { PiecewisePolynomial state_traj; -// = -// PiecewisePolynomial::CubicHermite( -// x_[0]->time_vector, x_[0]->datapoints, xdot_[0]->datapoints); for (int mode = 0; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -258,12 +282,10 @@ const { return state_traj; } -PiecewisePolynomial DirconTrajectory::ReconstructJointTrajectory(int joint_idx) -const { +PiecewisePolynomial +DirconTrajectory::ReconstructStateTrajectoryWithSprings( + Eigen::MatrixXd& spr_to_wo_spr_map) const { PiecewisePolynomial state_traj; -// = -// PiecewisePolynomial::CubicHermite( -// x_[0]->time_vector, x_[0]->datapoints.row(joint_idx), xdot_[0]->datapoints.row(joint_idx)); for (int mode = 0; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -271,13 +293,75 @@ const { continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, x_[mode]->datapoints.row(joint_idx), xdot_[mode]->datapoints.row(joint_idx))); + x_[mode]->time_vector, spr_to_wo_spr_map * x_[mode]->datapoints, + spr_to_wo_spr_map * xdot_[mode]->datapoints)); + } + return state_traj; +} + +PiecewisePolynomial DirconTrajectory::ReconstructMirrorStateTrajectory( + double t_offset) const { + MatrixXd M = GetTrajectory("mirror_matrix").datapoints; + PiecewisePolynomial state_traj = + PiecewisePolynomial::CubicHermite( + x_[0]->time_vector + + t_offset * VectorXd::Ones(x_[0]->time_vector.size()), + M * x_[0]->datapoints, M * xdot_[0]->datapoints); + + for (int mode = 1; mode < num_modes_; ++mode) { + // Cannot form trajectory with only a single break + if (x_[mode]->time_vector.size() < 2) { + continue; + } + state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( + x_[mode]->time_vector + + t_offset * VectorXd::Ones(x_[mode]->time_vector.size()), + M * x_[mode]->datapoints, M * xdot_[mode]->datapoints)); + } + return state_traj; +} + +PiecewisePolynomial DirconTrajectory::ReconstructJointTrajectory( + int joint_idx) const { + PiecewisePolynomial state_traj = + PiecewisePolynomial::CubicHermite( + x_[0]->time_vector, x_[0]->datapoints.row(joint_idx), + xdot_[0]->datapoints.row(joint_idx)); + + for (int mode = 1; mode < num_modes_; ++mode) { + // Cannot form trajectory with only a single break + if (x_[mode]->time_vector.size() < 2) { + continue; + } + state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( + x_[mode]->time_vector, x_[mode]->datapoints.row(joint_idx), + xdot_[mode]->datapoints.row(joint_idx))); + } + return state_traj; +} + +PiecewisePolynomial DirconTrajectory::ReconstructMirrorJointTrajectory( + int joint_idx) const { + MatrixXd M = GetTrajectory("mirror_matrix").datapoints; + PiecewisePolynomial state_traj = + PiecewisePolynomial::CubicHermite( + x_[0]->time_vector, (M * x_[0]->datapoints).row(joint_idx), + (M * xdot_[0]->datapoints).row(joint_idx)); + + for (int mode = 1; mode < num_modes_; ++mode) { + // Cannot form trajectory with only a single break + if (x_[mode]->time_vector.size() < 2) { + continue; + } + state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( + x_[mode]->time_vector, (M * x_[mode]->datapoints).row(joint_idx), + (M * xdot_[mode]->datapoints).row(joint_idx))); } return state_traj; } PiecewisePolynomial DirconTrajectory::ReconstructInputTrajectory() -const { + const { PiecewisePolynomial input_traj = PiecewisePolynomial::FirstOrderHold(u_->time_vector, u_->datapoints); @@ -334,13 +418,17 @@ void DirconTrajectory::LoadFromFile(const std::string& filepath) { xdot_.push_back( &GetTrajectory("state_derivative_traj" + std::to_string(mode))); lambda_.push_back(&GetTrajectory("force_vars" + std::to_string(mode))); + if (x_[mode]->time_vector.size() > 1) { try { + if (mode > 0) { + impulse_.push_back(&GetTrajectory("impulse_vars" + std::to_string(mode))); + } lambda_c_.push_back( &GetTrajectory("collocation_force_vars" + std::to_string(mode))); gamma_c_.push_back( &GetTrajectory("collocation_slack_vars" + std::to_string(mode))); - }catch(std::exception&){ + } catch (std::exception&) { // Temporary fix to work with old versions of saved dircon trajectories continue; } @@ -355,8 +443,8 @@ Eigen::VectorXd DirconTrajectory::GetCollocationPoints( // using a + (b - a) / 2 midpoint int num_knotpoints = time_vector.size(); return time_vector.head(num_knotpoints - 1) + - 0.5 * (time_vector.tail(num_knotpoints - 1) - - time_vector.head(num_knotpoints - 1)); + 0.5 * (time_vector.tail(num_knotpoints - 1) - + time_vector.head(num_knotpoints - 1)); } } // namespace dairlib diff --git a/lcm/dircon_saved_trajectory.h b/lcm/dircon_saved_trajectory.h index 7386bdad91..8c5a659949 100644 --- a/lcm/dircon_saved_trajectory.h +++ b/lcm/dircon_saved_trajectory.h @@ -25,9 +25,9 @@ namespace dairlib { /// DirconTrajectory by default contains four Trajectory objects: the state /// trajectory, the input trajectory, the force trajectory, the contact force -/// trajectory, the collocation force trajectory, the collocation slack trajectory -/// and the decision variables. Additional trajectories can be added using -/// the AddTrajectory() function +/// trajectory, the collocation force trajectory, the collocation slack +/// trajectory and the decision variables. Additional trajectories can be added +/// using the AddTrajectory() function class DirconTrajectory : public LcmTrajectory { public: @@ -46,26 +46,33 @@ class DirconTrajectory : public LcmTrajectory { const std::string& name, const std::string& description); drake::trajectories::PiecewisePolynomial ReconstructInputTrajectory() - const; + const; drake::trajectories::PiecewisePolynomial ReconstructStateTrajectory() - const; - drake::trajectories::PiecewisePolynomial ReconstructJointTrajectory(int joint_idx) - const; - - /// Returns a vector of polynomials describing the contact forces for each mode. For use when - /// adding knot points to the initial guess - std::vector> ReconstructLambdaTrajectory() - const; - - /// Returns a vector of polynomials describing the collocation forces for each mode. For use - /// when adding knot points to the initial guess - std::vector> ReconstructLambdaCTrajectory() - const; - - /// Returns a vector of polynomials describing the collocation slack vars. For use when adding - /// knot points to the initial guess - std::vector> ReconstructGammaCTrajectory() - const; + const; + drake::trajectories::PiecewisePolynomial + ReconstructStateTrajectoryWithSprings( + Eigen::MatrixXd&) const; + drake::trajectories::PiecewisePolynomial + ReconstructMirrorStateTrajectory(double t_offset) const; + drake::trajectories::PiecewisePolynomial ReconstructJointTrajectory( + int joint_idx) const; + drake::trajectories::PiecewisePolynomial + ReconstructMirrorJointTrajectory(int joint_idx) const; + + /// Returns a vector of polynomials describing the contact forces for each + /// mode. For use when adding knot points to the initial guess + std::vector> + ReconstructLambdaTrajectory() const; + + /// Returns a vector of polynomials describing the collocation forces for each + /// mode. For use when adding knot points to the initial guess + std::vector> + ReconstructLambdaCTrajectory() const; + + /// Returns a vector of polynomials describing the collocation slack vars. For + /// use when adding knot points to the initial guess + std::vector> + ReconstructGammaCTrajectory() const; /// Loads the saved state and input trajectory as well as the decision /// variables @@ -94,6 +101,7 @@ class DirconTrajectory : public LcmTrajectory { Eigen::MatrixXd GetForceBreaks(int mode) const { return lambda_[mode]->time_vector; } + Eigen::MatrixXd GetImpulseSamples(int mode) const { return impulse_[mode - 1]->datapoints; } Eigen::MatrixXd GetCollocationForceSamples(int mode) const { return lambda_c_[mode]->datapoints; } @@ -113,6 +121,7 @@ class DirconTrajectory : public LcmTrajectory { const Trajectory* decision_vars_; const Trajectory* u_; + std::vector impulse_; std::vector lambda_; std::vector lambda_c_; std::vector gamma_c_; diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index 9708dd4c21..c1b87d9d32 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -45,6 +45,7 @@ LcmTrajectory::Trajectory::Trajectory(string traj_name, this->time_vector = VectorXd::Map(traj_block.time_vec.data(), num_points); this->datapoints = MatrixXd(num_datatypes, num_points); + DRAKE_ASSERT(traj_block.datatypes.size() == traj_block.datapoints.size()); // Convert vector> to EigenMatrix for (int i = 0; i < num_datatypes; ++i) { this->datapoints.row(i) = diff --git a/lcm/lcm_trajectory.h b/lcm/lcm_trajectory.h index 099dcc4377..bff1ab5fa9 100644 --- a/lcm/lcm_trajectory.h +++ b/lcm/lcm_trajectory.h @@ -63,7 +63,13 @@ class LcmTrajectory { lcmt_metadata GetMetadata() const { return metadata_; } const Trajectory& GetTrajectory(const std::string& trajectory_name) const { - return trajectories_.at(trajectory_name); + try { + return trajectories_.at(trajectory_name); + } catch (std::exception& e) { + std::cerr << "Trajectory: " << trajectory_name << " does not exist." + << std::endl; + throw std::out_of_range(""); + } } /// Add additional LcmTrajectory::Trajectory objects @@ -74,7 +80,6 @@ class LcmTrajectory { const std::vector& GetTrajectoryNames() const { return trajectory_names_; } - lcmt_saved_traj GenerateLcmObject() const; protected: /// Constructs a lcmt_metadata object with a specified name and description diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 722e16090d..58a61e431d 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -8,7 +8,7 @@ cc_library( deps = [ ":constraint_factory", ":nonlinear_constraint", - ] + ], ) cc_library( @@ -78,13 +78,29 @@ cc_library( ], ) +cc_library( + name = "cost_function_utils", + srcs = [ + "cost_function_utils.cc", + ], + hdrs = [ + "cost_function_utils.h", + ], + deps = [ + "nonlinear_cost", + "//systems/trajectory_optimization:dircon", + "//systems/trajectory_optimization/dircon", + "@drake//:drake_shared_library", + ], +) + cc_test( name = "cost_constraint_approximation_test", size = "small", srcs = ["test/cost_constraint_approximation_test.cc"], deps = [ - "@drake//common/test_utilities:eigen_matrix_compare", ":optimization_utils", + "@drake//common/test_utilities:eigen_matrix_compare", "@gtest//:main", ], ) diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index 674269ae0f..6ecba057a2 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -130,3 +130,11 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "osc_gains", + hdrs = ["osc_gains.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/systems/controllers/osc/joint_space_tracking_data.cc b/systems/controllers/osc/joint_space_tracking_data.cc index 7107ff1b8d..db22032d48 100644 --- a/systems/controllers/osc/joint_space_tracking_data.cc +++ b/systems/controllers/osc/joint_space_tracking_data.cc @@ -22,7 +22,7 @@ JointSpaceTrackingData::JointSpaceTrackingData( const string& name, const MatrixXd& K_p, const MatrixXd& K_d, const MatrixXd& W, const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) - : OptionsTrackingData(name, K_p.rows(), K_p.rows(), K_p, K_d, W, + : OptionsTrackingData(name, K_p.rows(), K_d.rows(), K_p, K_d, W, plant_w_spr, plant_wo_spr) { } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f31c0914c4..2044efc5ad 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -78,8 +78,10 @@ OperationalSpaceControl::OperationalSpaceControl( if (used_with_finite_state_machine) { fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); - near_impact_port_ = this->DeclareVectorInputPort("next_fsm, t_to_impact", - BasicVector(2)) + clock_port_ = this->DeclareVectorInputPort("clock", BasicVector(1)) + .get_index(); + impact_info_port_ = this->DeclareVectorInputPort("next_fsm, t_to_impact", + ImpactInfoVector(0, 0, kSpaceDim)) .get_index(); // Discrete update to record the last state event time @@ -273,6 +275,7 @@ void OperationalSpaceControl::Build() { // Construct QP prog_ = std::make_unique(); + ii_prog_ = std::make_unique(); // Size of decision variable n_h_ = (kinematic_evaluators_ == nullptr) @@ -315,6 +318,9 @@ void OperationalSpaceControl::Build() { lambda_h_ = prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); epsilon_ = prog_->NewContinuousVariables(n_c_active_, "epsilon"); + ii_lambda_c_ = ii_prog_->NewContinuousVariables(n_c_, "lambda_contact"); + ii_lambda_h_ = ii_prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); + // Add constraints // 1. Dynamics constraint dynamics_constraint_ = @@ -352,9 +358,6 @@ void OperationalSpaceControl::Build() { } } if (!all_contacts_.empty()) { - VectorXd mu_neg1(2); - VectorXd mu_1(2); - VectorXd one(1); MatrixXd A = MatrixXd(5, kSpaceDim); A << -1, 0, mu_, 0, -1, mu_, 1, 0, mu_, 0, 1, mu_, 0, 0, 1; @@ -369,7 +372,32 @@ void OperationalSpaceControl::Build() { .evaluator() .get()); } + + // friction cone constraints on impact invariant projection +// for (unsigned int j = 0; j < all_contacts_.size(); j++) { +// ii_friction_constraints_.push_back( +// ii_prog_ +// ->AddLinearConstraint( +// A, VectorXd::Zero(5), +// Eigen::VectorXd::Constant( +// 5, std::numeric_limits::infinity()), +// ii_lambda_c_.segment(kSpaceDim * j, 3)) +// .evaluator() +// .get()); +// } } + + // bounding box constraint on holonomic constraint forces impact invariant + // projection +// if (n_h_) { +// ii_holonomic_constraint_ = +// ii_prog_ +// ->AddBoundingBoxConstraint(VectorXd::Zero(n_h_), +// VectorXd::Zero(n_h_), ii_lambda_h_) +// .evaluator() +// .get(); +// } + // 5. Input constraint if (with_input_constraints_) { prog_->AddLinearConstraint(MatrixXd::Identity(n_u_, n_u_), u_min_, u_max_, @@ -399,11 +427,21 @@ void OperationalSpaceControl::Build() { VectorXd::Zero(n_v_), dv_) .evaluator() .get()); + ii_tracking_cost_.push_back( + ii_prog_ + ->Add2NormSquaredCost( + MatrixXd::Zero(tracking_data_vec_->at(i)->GetYdotDim(), + n_c_ + n_h_), + VectorXd::Zero(tracking_data_vec_->at(i)->GetYdotDim()), + {ii_lambda_c_, ii_lambda_h_}) + .evaluator() + .get()); + // TODO(yangwill): update the coefficients correctly } // 5. Joint Limit cost w_joint_limit_ = VectorXd::Zero(n_revolute_joints_); - K_joint_pos = MatrixXd::Identity(n_revolute_joints_, n_revolute_joints_); + K_joint_pos = 50 * MatrixXd::Identity(n_revolute_joints_, n_revolute_joints_); joint_limit_cost_.push_back( prog_->AddLinearCost(w_joint_limit_, 0, dv_.tail(n_revolute_joints_)) .evaluator() @@ -445,9 +483,9 @@ void OperationalSpaceControl::Build() { solver_ = std::make_unique(); drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); -// solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); - solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-7); - solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); + // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); + solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-6); solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-6); solver_options.SetOption(OsqpSolver::id(), "polish", 1); @@ -526,6 +564,22 @@ VectorXd OperationalSpaceControl::SolveQp( // TODO (yangwill): Characterize damping in cassie model // bias = bias - f_app.generalized_forces(); + // Invariant Impacts + // Only update when near an impact + bool near_impact = alpha != 0; + VectorXd v_proj = VectorXd::Zero(n_v_); + if (near_impact) { + UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, + time_since_last_state_switch, fsm_state, + next_fsm_state, M); + // Need to call Update before this to get the updated jacobian + v_proj = alpha * M_Jt_ * ii_lambda_sol_; + } + +// SetVelocitiesIfNew( +// plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, +// context_wo_spr_); + // Get J and JdotV for holonomic constraint MatrixXd J_h(n_h_, n_v_); VectorXd JdotV_h(n_h_); @@ -563,6 +617,11 @@ VectorXd OperationalSpaceControl::SolveQp( row_idx += contact_i->num_active(); } + // if(near_impact){ + // std::cout << "Jv" << J_c_active * + // (x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj) << std::endl; + // } + // Update constraints // 1. Dynamics constraint /// M*dv + bias == J_c^T*lambda_c + J_h^T*lambda_h + B*u @@ -596,7 +655,7 @@ VectorXd OperationalSpaceControl::SolveQp( contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } - // 4. Friction constraint (approximated firction cone) + // 4. Friction constraint (approximated friction cone) /// For i = active contact indices /// mu_*lambda_c(3*i+2) >= lambda_c(3*i+0) /// -mu_*lambda_c(3*i+2) <= lambda_c(3*i+0) @@ -620,18 +679,6 @@ VectorXd OperationalSpaceControl::SolveQp( } } - // Invariant Impacts - // Only update when near an impact - bool near_impact = alpha != 0; - VectorXd v_proj = VectorXd::Zero(n_v_); - if (near_impact) { - UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, - time_since_last_state_switch, fsm_state, - next_fsm_state, M, J_h); - // Need to call Update before this to get the updated jacobian - v_proj = alpha * M_Jt_ * ii_lambda_sol_; - } - // Update costs // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { @@ -733,11 +780,6 @@ VectorXd OperationalSpaceControl::SolveQp( solve_time_ = result.get_solver_details().run_time; - if (!result.is_success()) { - std::cout << "reverting to old sol" << std::endl; - return *u_sol_; - } - // Extract solutions *dv_sol_ = result.GetSolution(dv_); *u_sol_ = result.GetSolution(u_); @@ -756,29 +798,29 @@ VectorXd OperationalSpaceControl::SolveQp( void OperationalSpaceControl::UpdateImpactInvariantProjection( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const Context& context, double t, double t_since_last_state_switch, - int fsm_state, int next_fsm_state, const MatrixXd& M, - const MatrixXd& J_h) const { + int fsm_state, int next_fsm_state, const MatrixXd& M) const { auto map_iterator = contact_indices_map_.find(next_fsm_state); if (map_iterator == contact_indices_map_.end()) { throw std::out_of_range("Contact mode: " + std::to_string(next_fsm_state) + " was not found in the OSC"); } std::set next_contact_set = map_iterator->second; - int active_contact_dim = active_contact_dim_.at(next_fsm_state) + n_h_; - MatrixXd J_c_next = MatrixXd::Zero(active_contact_dim, n_v_); + int active_constraint_dim = active_contact_dim_.at(next_fsm_state) + n_h_; + MatrixXd J_next = MatrixXd::Zero(active_constraint_dim, n_v_); int row_start = 0; for (unsigned int i = 0; i < all_contacts_.size(); i++) { if (next_contact_set.find(i) != next_contact_set.end()) { - J_c_next.block(row_start, 0, kSpaceDim, n_v_) = + J_next.block(row_start, 0, kSpaceDim, n_v_) = all_contacts_[i]->EvalFullJacobian(*context_wo_spr_); row_start += kSpaceDim; } } // Holonomic constraints if (n_h_ > 0) { - J_c_next.block(row_start, 0, n_h_, n_v_) = J_h; + J_next.block(row_start, 0, n_h_, n_v_) = + kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); } - M_Jt_ = M.llt().solve(J_c_next.transpose()); + M_Jt_ = M.llt().solve(J_next.transpose()); int active_tracking_data_dim = 0; for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { @@ -808,13 +850,14 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } } } - MatrixXd A = MatrixXd::Zero(active_tracking_data_dim, active_contact_dim); + + MatrixXd A = MatrixXd::Zero(active_tracking_data_dim, active_constraint_dim); VectorXd ydot_err_vec = VectorXd::Zero(active_tracking_data_dim); int start_row = 0; for (auto tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { - A.block(start_row, 0, tracking_data->GetYDim(), active_contact_dim) = + A.block(start_row, 0, tracking_data->GetYDim(), active_constraint_dim) = tracking_data->GetJ() * M_Jt_; ydot_err_vec.segment(start_row, tracking_data->GetYDim()) = tracking_data->GetErrorYdot(); @@ -876,8 +919,10 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; - output->tracking_data.reserve(tracking_data_vec_->size()); + output->tracking_data = + std::vector(tracking_data_vec_->size()); output->tracking_cost = std::vector(tracking_data_vec_->size()); + output->tracking_data_names = std::vector(tracking_data_vec_->size()); for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); @@ -885,7 +930,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && time_since_last_state_switch <= t_e_vec_.at(i)) { - output->tracking_data_names.push_back(tracking_data->GetName()); + output->tracking_data_names[i] = tracking_data->GetName(); lcmt_osc_tracking_data osc_output; osc_output.y_dim = tracking_data->GetYDim(); osc_output.ydot_dim = tracking_data->GetYdotDim(); @@ -906,7 +951,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( CopyVectorXdToStdVector(tracking_data->GetYddotCommand()); osc_output.yddot_command_sol = CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); - output->tracking_data.push_back(osc_output); + // output->tracking_data.push_back(osc_output); + output->tracking_data[i] = osc_output; const VectorXd& ddy_t = tracking_data->GetYddotCommand(); const MatrixXd& W = tracking_data->GetWeight(); @@ -927,6 +973,7 @@ void OperationalSpaceControl::CalcOptimalInput( // Read in current state and time const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); + VectorXd q_w_spr = robot_output->GetPositions(); VectorXd v_w_spr = robot_output->GetVelocities(); @@ -949,23 +996,28 @@ void OperationalSpaceControl::CalcOptimalInput( // Read in finite state machine const BasicVector* fsm_output = (BasicVector*)this->EvalVectorInput(context, fsm_port_); + double clock_time = current_time; + if (this->get_input_port(clock_port_).HasValue(context)) { + const BasicVector* clock = + (BasicVector*)this->EvalVectorInput(context, clock_port_); + clock_time = clock->get_value()(0); + } VectorXd fsm_state = fsm_output->get_value(); double alpha = 0; int next_fsm_state = -1; if (this->get_near_impact_input_port().HasValue(context)) { - const BasicVector* near_impact = - (BasicVector*)this->EvalVectorInput(context, - near_impact_port_); - alpha = near_impact->get_value()(0); - next_fsm_state = near_impact->get_value()(1); + const ImpactInfoVector* impact_info = + (ImpactInfoVector*)this->EvalVectorInput(context, + impact_info_port_); + alpha = impact_info->GetAlpha(); + next_fsm_state = impact_info->GetCurrentContactMode(); } // Get discrete states const auto prev_event_time = context.get_discrete_state(prev_event_time_idx_).get_value(); - - u_sol = SolveQp(x_w_spr, x_wo_spr, context, current_time, fsm_state(0), + u_sol = SolveQp(x_w_spr, x_wo_spr, context, clock_time, fsm_state(0), current_time - prev_event_time(0), alpha, next_fsm_state); } else { u_sol = SolveQp(x_w_spr, x_wo_spr, context, current_time, -1, current_time, diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index c6b7299f39..9cce9b4e19 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -16,6 +16,7 @@ #include "systems/controllers/control_utils.h" #include "systems/controllers/osc/osc_tracking_data.h" #include "systems/framework/output_vector.h" +#include "systems/framework/impact_info_vector.h" #include "drake/common/trajectories/exponential_plus_piecewise_polynomial.h" #include "drake/common/trajectories/piecewise_polynomial.h" @@ -117,8 +118,11 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const drake::systems::InputPort& get_fsm_input_port() const { return this->get_input_port(fsm_port_); } + const drake::systems::InputPort& get_clock_input_port() const { + return this->get_input_port(clock_port_); + } const drake::systems::InputPort& get_near_impact_input_port() const { - return this->get_input_port(near_impact_port_); + return this->get_input_port(impact_info_port_); } const drake::systems::InputPort& get_tracking_data_input_port( const std::string& name) const { @@ -187,11 +191,29 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { double time_since_last_state_switch, double alpha, int next_fsm_state) const; + // Solves the optimization problem: + // min_{\lambda} || ydot_{des} - J_{y}(qdot + M^{-1} J_{\lambda}^T \lambda||_2 + // s.t. constraints + // In the IROS 2021 paper, the problem was unconstrained and could be solved + // using the closed form least squares solution void UpdateImpactInvariantProjection( const Eigen::VectorXd& x_w_spr, const Eigen::VectorXd& x_wo_spr, const drake::systems::Context& context, double t, double t_since_last_state_switch, int fsm_state, int next_fsm_state, - const Eigen::MatrixXd& M, const Eigen::MatrixXd& J_h) const; + const Eigen::MatrixXd& M) const; + + // Solves the optimization problem: + // min_{\lambda} || ydot_{des} - J_{y}(qdot + M^{-1} J_{\lambda}^T \lambda||_2 + // s.t. constraints + // By adding constraints on lambda, we can impose scaling on the + // impact-invariant projection. + // The current constraints are lambda \in convex_hull \alpha * [-FC, FC] + // defined by the normal impulse from the nominal trajectory + void UpdateImpactInvariantProjectionQP( + const Eigen::VectorXd& x_w_spr, const Eigen::VectorXd& x_wo_spr, + const drake::systems::Context& context, double t, + double t_since_last_state_switch, int fsm_state, int next_fsm_state, + const Eigen::MatrixXd& M) const; // Discrete update that stores the previous state transition time drake::systems::EventStatus DiscreteVariableUpdate( @@ -209,8 +231,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int osc_debug_port_; int osc_output_port_; int state_port_; + int clock_port_; int fsm_port_; - int near_impact_port_; + int impact_info_port_; // Discrete update int prev_fsm_state_idx_; @@ -272,10 +295,20 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Solver std::unique_ptr solver_; + std::unique_ptr ii_solver_; drake::solvers::SolverOptions solver_options_; // MathematicalProgram std::unique_ptr prog_; + std::unique_ptr ii_prog_; + + // Decision variables/constraints for impact invariant QP + drake::solvers::VectorXDecisionVariable ii_lambda_c_; + drake::solvers::VectorXDecisionVariable ii_lambda_h_; + std::vector ii_friction_constraints_; + std::vector ii_normal_constraints_; + drake::solvers::BoundingBoxConstraint* ii_holonomic_constraint_; + // Decision variables drake::solvers::VectorXDecisionVariable dv_; drake::solvers::VectorXDecisionVariable u_; @@ -289,6 +322,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector friction_constraints_; std::vector tracking_cost_; std::vector joint_limit_cost_; + std::vector ii_tracking_cost_; // OSC solution std::unique_ptr dv_sol_; diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index 93bd09600a..dc43e483ab 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -90,7 +90,8 @@ void OscTrackingData::UpdateDesired( y_des_ = traj.value(t); if (traj.has_derivative()) { ydot_des_ = traj.EvalDerivative(t, 1); - yddot_des_ = traj.EvalDerivative(t, 2); + yddot_des_ = traj.EvalDerivative(t, 1).bottomRows(n_ydot_); + // yddot_des_ = traj.EvalDerivative(t, 2); } // TODO (yangwill): Remove this edge case after EvalDerivative has been // implemented for ExponentialPlusPiecewisePolynomial diff --git a/systems/controllers/osc/relative_translation_tracking_data.cc b/systems/controllers/osc/relative_translation_tracking_data.cc index 1936fb4669..eaf179611d 100644 --- a/systems/controllers/osc/relative_translation_tracking_data.cc +++ b/systems/controllers/osc/relative_translation_tracking_data.cc @@ -38,7 +38,7 @@ void RelativeTranslationTrackingData::Update( const drake::trajectories::Trajectory& traj, double t, double t_gait_cycle, const int fsm_state, const VectorXd& v_proj) { // Currently there are redundant calculation here. For both to_frame_data_, - // and from_frame_data_, we don't nee to run UpdateDesired, UpdateYError, + // and from_frame_data_, we don't nee to run UpdateDesired, UpdateYError, // UpdateYdotError and UpdateYddotCmd inside Update(). // TODO: improve this to make it slightly more efficient. to_frame_data_->Update(x_w_spr, context_w_spr, x_wo_spr, context_wo_spr, traj, diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index 7962d0aa17..a16599db42 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -62,6 +62,9 @@ void TransTaskSpaceTrackingData::UpdateJ( context_wo_spr, JacobianWrtVariable::kV, *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); + if(J_.hasNaN()){ + std::cout << "Jacobian has NaNs" << std::endl; + } } void TransTaskSpaceTrackingData::UpdateJdotV( diff --git a/systems/framework/BUILD.bazel b/systems/framework/BUILD.bazel index 174c27a5f0..b2027ff5ef 100644 --- a/systems/framework/BUILD.bazel +++ b/systems/framework/BUILD.bazel @@ -9,10 +9,12 @@ cc_library( srcs = [ "output_vector.cc", "timestamped_vector.cc", + "impact_info_vector.cc", ], hdrs = [ "output_vector.h", "timestamped_vector.h", + "impact_info_vector.h", ], deps = [ "@drake//:drake_shared_library", diff --git a/systems/trajectory_optimization/dircon/dircon.h b/systems/trajectory_optimization/dircon/dircon.h index e48e201f06..6316b68680 100644 --- a/systems/trajectory_optimization/dircon/dircon.h +++ b/systems/trajectory_optimization/dircon/dircon.h @@ -188,7 +188,7 @@ class Dircon using drake::systems::trajectory_optimization::MultipleShooting::N; using drake::systems::trajectory_optimization::MultipleShooting:: - SubstitutePlaceholderVariables; + SubstitutePlaceholderVariables; int num_modes() const; @@ -203,6 +203,8 @@ class Dircon return mode_sequence_.mode(mode); } + const int get_mode_start(int index) { return mode_start_[index]; } + const drake::systems::Context& get_context(int mode, int knotpoint_index) { return *contexts_.at(mode).at(knotpoint_index); } From a4a31b5a20819e376ec0265ee17cc585d7fa1346 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Nov 2021 11:11:13 -0500 Subject: [PATCH 016/758] tuning running gains --- examples/Cassie/BUILD.bazel | 18 - examples/Cassie/integration_test.pmd | 4 + examples/Cassie/osc_run/BUILD.bazel | 78 ++ .../Cassie/osc_run/foot_traj_generator.cc | 149 ++++ examples/Cassie/osc_run/foot_traj_generator.h | 67 ++ examples/Cassie/osc_run/osc_running_gains.h | 140 ++++ .../Cassie/osc_run/osc_running_gains.yaml | 67 ++ .../osc_run/pelvis_roll_traj_generator.cc | 118 ++++ .../osc_run/pelvis_roll_traj_generator.h | 60 ++ .../osc_run/pelvis_trans_traj_generator.cc | 153 ++++ .../osc_run/pelvis_trans_traj_generator.h | 82 +++ examples/Cassie/run_dircon_running.cc | 610 ++++++++++++++++ examples/Cassie/run_osc_running_controller.cc | 666 ++++++++++++++++++ solvers/cost_function_utils.cc | 104 +++ solvers/cost_function_utils.h | 55 ++ systems/controllers/osc/osc_gains.h | 27 + systems/controllers/osc/osc_tracking_data.cc | 8 +- systems/framework/impact_info_vector.cc | 6 + systems/framework/impact_info_vector.h | 94 +++ 19 files changed, 2486 insertions(+), 20 deletions(-) create mode 100644 examples/Cassie/osc_run/BUILD.bazel create mode 100644 examples/Cassie/osc_run/foot_traj_generator.cc create mode 100644 examples/Cassie/osc_run/foot_traj_generator.h create mode 100644 examples/Cassie/osc_run/osc_running_gains.h create mode 100644 examples/Cassie/osc_run/osc_running_gains.yaml create mode 100644 examples/Cassie/osc_run/pelvis_roll_traj_generator.cc create mode 100644 examples/Cassie/osc_run/pelvis_roll_traj_generator.h create mode 100644 examples/Cassie/osc_run/pelvis_trans_traj_generator.cc create mode 100644 examples/Cassie/osc_run/pelvis_trans_traj_generator.h create mode 100644 examples/Cassie/run_dircon_running.cc create mode 100644 examples/Cassie/run_osc_running_controller.cc create mode 100644 solvers/cost_function_utils.cc create mode 100644 solvers/cost_function_utils.h create mode 100644 systems/controllers/osc/osc_gains.h create mode 100644 systems/framework/impact_info_vector.cc create mode 100644 systems/framework/impact_info_vector.h diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 028b7911ca..36df36f5cc 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -213,24 +213,6 @@ cc_binary( ], ) -cc_binary( - name = "multibody_sim_init", - srcs = ["multibody_sim_init.cc"], - deps = [ - ":cassie_fixed_point_solver", - ":cassie_urdf", - ":cassie_utils", - "//lcm:trajectory_saver", - "//multibody:utils", - "//solvers:optimization_utils", - "//systems:robot_lcm_systems", - "//systems/framework:vector", - "//systems/primitives", - "@drake//:drake_shared_library", - "@gflags", - ], -) - cc_binary( name = "multibody_sim_w_platform", srcs = ["multibody_sim_w_platform.cc"], diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index c5714c3609..143cf88c15 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -35,6 +35,10 @@ group "1.controllers-and-dispatchers" { exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=2.0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d"; host = "localhost"; } + cmd "osc_walking_controller (w_radio)" { + exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_x=CASSIE_STATE_DISPATCHER --use_radio=1 --cassie_out_channel=CASSIE_OUTPUT"; + host = "localhost"; + } } group "2.simulators" { diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel new file mode 100644 index 0000000000..2900c92997 --- /dev/null +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -0,0 +1,78 @@ +load("@drake//tools/lint:lint.bzl", "add_lint_tests") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:drake_lcm.bzl", + "drake_lcm_cc_library", + "drake_lcm_java_library", + "drake_lcm_py_library", +) +load( + "@drake//tools/skylark:drake_py.bzl", + "drake_py_binary", + "drake_py_library", + "drake_py_unittest", +) +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +cc_library( + name = "osc_run", + deps = [ + ":foot_traj_generator", + ":osc_running_gains", + ":pelvis_rot_traj_generator", + ":pelvis_trans_traj_generator", + ], +) + +cc_library( + name = "osc_running_gains", + hdrs = ["osc_running_gains.h"], + deps = [ + "//systems/controllers/osc:osc_gains", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "pelvis_trans_traj_generator", + srcs = ["pelvis_trans_traj_generator.cc"], + hdrs = ["pelvis_trans_traj_generator.h"], + deps = [ + "//multibody:utils", + "//systems/controllers/osc:osc_gains", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "pelvis_rot_traj_generator", + srcs = ["pelvis_roll_traj_generator.cc"], + hdrs = ["pelvis_roll_traj_generator.h"], + deps = [ + "//multibody:utils", + "//systems/controllers/osc:osc_gains", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "foot_traj_generator", + srcs = ["foot_traj_generator.cc"], + hdrs = ["foot_traj_generator.h"], + deps = [ + "//multibody:utils", + "//systems/controllers/osc:osc_gains", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc new file mode 100644 index 0000000000..79ce8a1774 --- /dev/null +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -0,0 +1,149 @@ +#include "foot_traj_generator.h" + +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::BodyFrame; +using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib::examples::osc_run { + +FootTrajGenerator::FootTrajGenerator( + const MultibodyPlant& plant, Context* context, + const string& hip_name, bool isLeftFoot, + const PiecewisePolynomial& foot_traj, + const PiecewisePolynomial& hip_traj, + bool relative_feet, + double time_offset) + : plant_(plant), + context_(context), + world_(plant.world_frame()), + hip_frame_(plant.GetFrameByName(hip_name)), + foot_traj_(foot_traj), + hip_traj_(hip_traj), + is_left_foot_(isLeftFoot), + relative_feet_(relative_feet) { + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + + if (isLeftFoot) { + this->set_name("left_ft_traj"); + this->DeclareAbstractOutputPort("left_ft_traj", traj_inst, + &FootTrajGenerator::CalcTraj); + } else { + this->set_name("right_ft_traj"); + this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, + &FootTrajGenerator::CalcTraj); + } + + // Input/Output Setup + state_port_ = + this->DeclareVectorInputPort("x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + target_vel_port_ = + this->DeclareVectorInputPort("v_des",BasicVector(2)).get_index(); + fsm_port_ = this->DeclareVectorInputPort("fsm",BasicVector(1)).get_index(); + + // Shift trajectory by time_offset + foot_traj_.shiftRight(time_offset); + hip_traj_.shiftRight(time_offset); +} + +PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( + const VectorXd& x, double t) const { + int n_cycles = t / (foot_traj_.end_time() - foot_traj_.start_time()); + double stride_length = foot_traj_.value(foot_traj_.end_time())(0) - + foot_traj_.value(foot_traj_.start_time())(0); + Vector3d foot_pos_offset = {n_cycles * stride_length, 0, 0}; + Vector3d foot_vel_offset = {0, 0, 0}; + VectorXd foot_offset = VectorXd(6); + foot_offset << foot_pos_offset, foot_vel_offset; + + std::vector breaks = foot_traj_.get_segment_times(); + VectorXd breaks_vector = Map(breaks.data(), breaks.size()); + MatrixXd foot_offset_points = foot_offset.replicate(1, breaks.size()); + PiecewisePolynomial foot_offset_traj = + PiecewisePolynomial::ZeroOrderHold(breaks_vector, + foot_offset_points); + if(relative_feet_){ +// std::cout << foot_traj_.value(t) << std::endl; +// std::cout << hip_traj_.value(t) << std::endl; + return foot_traj_ - hip_traj_ + foot_offset_traj; + }else{ + return foot_traj_ + foot_offset_traj; + } +} + +void FootTrajGenerator::AddRaibertCorrection( + const drake::systems::Context& context, + drake::trajectories::PiecewisePolynomial* traj) const { + + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + const auto desired_pelvis_vel = + this->EvalVectorInput(context, target_vel_port_)->get_value(); + Vector2d desired_pelvis_pos = {0.0, 0}; + VectorXd pelvis_pos = robot_output->GetPositions().segment(4, 2); + VectorXd pelvis_vel = robot_output->GetVelocities().segment(3, 2); + VectorXd pelvis_pos_err = pelvis_pos - desired_pelvis_pos; + VectorXd pelvis_vel_err = pelvis_vel - desired_pelvis_vel; + VectorXd footstep_correction = + Kp_ * (pelvis_pos_err) + + Kd_ * (pelvis_vel_err); + if(is_left_foot_){ + footstep_correction(1) -= 0.02; + }else{ + footstep_correction(1) += 0.02; + } + footstep_correction(0) -= 0.03; + std::vector breaks = traj->get_segment_times(); + VectorXd breaks_vector = Map(breaks.data(), breaks.size()); + VectorXd new_samples = VectorXd(6); + new_samples << footstep_correction, Vector3d::Zero(); + MatrixXd foot_offset_points = new_samples.replicate(1, breaks.size()); + PiecewisePolynomial foot_offset_traj = + PiecewisePolynomial::ZeroOrderHold(breaks_vector, + foot_offset_points); + *traj = *traj + foot_offset_traj; +} + +void FootTrajGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // Read in current state + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + VectorXd x = robot_output->GetState(); + double timestamp = robot_output->get_timestamp(); + + // Read in finite state machine + const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + // if (fsm_state[0] == FLIGHT) { + *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); + this->AddRaibertCorrection(context, casted_traj); + // } +} + +} // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h new file mode 100644 index 0000000000..c33c1ca30a --- /dev/null +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -0,0 +1,67 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib::examples::osc_run { + +class FootTrajGenerator : public drake::systems::LeafSystem { + public: + FootTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, const std::string& hip_name, + bool isLeftFoot, + const drake::trajectories::PiecewisePolynomial& foot_traj, + const drake::trajectories::PiecewisePolynomial& hip_traj, + bool relative_feet = false, double time_offset = 0.0); + + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_fsm_input_port() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_target_vel_input_port() const { + return this->get_input_port(target_vel_port_); + } + + void SetFootstepGains(const Eigen::MatrixXd& Kp, const Eigen::MatrixXd& Kd) { + Kp_ = Kp; + Kd_ = Kd; + }; + + private: + drake::trajectories::PiecewisePolynomial GenerateFlightTraj( + const Eigen::VectorXd& x, double t) const; + void AddRaibertCorrection( + const drake::systems::Context& context, + drake::trajectories::PiecewisePolynomial* traj) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::Frame& world_; + const drake::multibody::Frame& hip_frame_; + + // Raibert Footstep Gains + Eigen::MatrixXd Kp_ = Eigen::MatrixXd::Zero(2, 2); + Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(2, 2); + + drake::trajectories::PiecewisePolynomial foot_traj_; + drake::trajectories::PiecewisePolynomial hip_traj_; + + bool is_left_foot_; + bool relative_feet_; + int state_port_; + int target_vel_port_; + + int fsm_port_; +}; + +} // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h new file mode 100644 index 0000000000..0ad38f21c0 --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -0,0 +1,140 @@ +#include "systems/controllers/osc/osc_gains.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct OSCRunningGains : OSCGains { + double w_swing_toe; + double swing_toe_kp; + double swing_toe_kd; + double w_hip_yaw; + double hip_yaw_kp; + double hip_yaw_kd; + double w_hip_pitch; + double hip_pitch_kp; + double hip_pitch_kd; + double w_hip_roll; + double hip_roll_kp; + double hip_roll_kd; + double vel_scale_rot; + double vel_scale_trans_sagital; + double vel_scale_trans_lateral; + bool relative_feet; + bool relative_pelvis; + double rest_length; + double k_leg; + double b_leg; + + // swing foot tracking + std::vector SwingFootW; + std::vector SwingFootKp; + std::vector SwingFootKd; + // pelvis tracking + std::vector PelvisW; + std::vector PelvisKp; + std::vector PelvisKd; + // pelvis orientation tracking + std::vector FootstepKp; + std::vector FootstepKd; + + MatrixXd K_p_footstep; + MatrixXd K_d_footstep; + MatrixXd W_pelvis; + MatrixXd K_p_pelvis; + MatrixXd K_d_pelvis; + MatrixXd W_swing_foot; + MatrixXd K_p_swing_foot; + MatrixXd K_d_swing_foot; + MatrixXd W_swing_toe; + MatrixXd K_p_swing_toe; + MatrixXd K_d_swing_toe; + MatrixXd W_hip_yaw; + MatrixXd K_p_hip_yaw; + MatrixXd K_d_hip_yaw; + MatrixXd W_hip_pitch; + MatrixXd K_p_hip_pitch; + MatrixXd K_d_hip_pitch; + MatrixXd W_hip_roll; + MatrixXd K_p_hip_roll; + MatrixXd K_d_hip_roll; + + template + void Serialize(Archive* a) { + OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(w_input)); + a->Visit(DRAKE_NVP(w_accel)); + a->Visit(DRAKE_NVP(w_soft_constraint)); + a->Visit(DRAKE_NVP(impact_threshold)); + a->Visit(DRAKE_NVP(mu)); + a->Visit(DRAKE_NVP(relative_feet)); + a->Visit(DRAKE_NVP(relative_pelvis)); + a->Visit(DRAKE_NVP(rest_length)); + a->Visit(DRAKE_NVP(k_leg)); + a->Visit(DRAKE_NVP(b_leg)); + + a->Visit(DRAKE_NVP(PelvisW)); + a->Visit(DRAKE_NVP(PelvisKp)); + a->Visit(DRAKE_NVP(PelvisKd)); + a->Visit(DRAKE_NVP(FootstepKp)); + a->Visit(DRAKE_NVP(FootstepKd)); + a->Visit(DRAKE_NVP(SwingFootW)); + a->Visit(DRAKE_NVP(SwingFootKp)); + a->Visit(DRAKE_NVP(SwingFootKd)); + a->Visit(DRAKE_NVP(w_swing_toe)); + a->Visit(DRAKE_NVP(swing_toe_kp)); + a->Visit(DRAKE_NVP(swing_toe_kd)); + a->Visit(DRAKE_NVP(w_hip_yaw)); + a->Visit(DRAKE_NVP(hip_yaw_kp)); + a->Visit(DRAKE_NVP(hip_yaw_kd)); + a->Visit(DRAKE_NVP(w_hip_pitch)); + a->Visit(DRAKE_NVP(hip_pitch_kp)); + a->Visit(DRAKE_NVP(hip_pitch_kd)); + a->Visit(DRAKE_NVP(w_hip_roll)); + a->Visit(DRAKE_NVP(hip_roll_kp)); + a->Visit(DRAKE_NVP(hip_roll_kd)); + // High level command gains (with radio) + a->Visit(DRAKE_NVP(vel_scale_rot)); + a->Visit(DRAKE_NVP(vel_scale_trans_sagital)); + a->Visit(DRAKE_NVP(vel_scale_trans_lateral)); + + W_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->SwingFootW.data(), 3, 3); + K_p_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->SwingFootKp.data(), 3, 3); + K_d_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->SwingFootKd.data(), 3, 3); + W_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisW.data(), 3, 3); + K_p_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisKp.data(), 3, 3); + K_d_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisKd.data(), 3, 3); + K_p_footstep = Eigen::Map< + Eigen::Matrix>( + this->FootstepKp.data(), 3, 2); + K_d_footstep = Eigen::Map< + Eigen::Matrix>( + this->FootstepKd.data(), 3, 2); + + W_swing_toe = this->w_swing_toe * MatrixXd::Identity(1, 1); + K_p_swing_toe = this->swing_toe_kp * MatrixXd::Identity(1, 1); + K_d_swing_toe = this->swing_toe_kd * MatrixXd::Identity(1, 1); + W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); + K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); + W_hip_pitch = this->w_hip_pitch * MatrixXd::Identity(1, 1); + K_p_hip_pitch = this->hip_pitch_kp * MatrixXd::Identity(1, 1); + K_d_hip_pitch = this->hip_pitch_kd * MatrixXd::Identity(1, 1); + W_hip_roll = this->w_hip_roll * MatrixXd::Identity(1, 1); + K_p_hip_roll = this->hip_roll_kp * MatrixXd::Identity(1, 1); + K_d_hip_roll = this->hip_roll_kd * MatrixXd::Identity(1, 1); + } +}; \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml new file mode 100644 index 0000000000..06a0eb9692 --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -0,0 +1,67 @@ +w_input: 0.0000000000 +w_accel: 0.00001 +#w_soft_constraint: 1000000 +w_soft_constraint: 0.00000000 +w_input_reg: 0.0001 +impact_threshold: 0.050 +relative_feet: true +relative_pelvis: true + +# High level command gains (with radio) +vel_scale_rot: -1 +vel_scale_trans_sagital: 0.25 +vel_scale_trans_lateral: -0.15 + +# SLIP parameters +rest_length: 0.9 +k_leg: -750 +b_leg: 1 + +mu: 0.8 + +w_swing_toe: 1 +swing_toe_kp: 1500 +swing_toe_kd: 10 + +w_hip_yaw: 10 +hip_yaw_kp: 100 +hip_yaw_kd: 5 +w_hip_pitch: 5 +hip_pitch_kp: 50 +hip_pitch_kd: 20 +w_hip_roll: 10 +hip_roll_kp: 100 +hip_roll_kd: 20 + +PelvisW: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 1] +PelvisKp: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 100] +PelvisKd: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 5] +SwingFootW: + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] +SwingFootKp: + [50, 0, 0, + 0, 50, 0, + 0, 0, 50] +SwingFootKd: + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1] +FootstepKp: + [0.0, 0, + 0, 0.0, + 0, 0] +FootstepKd: + [ 0.15, 0, + 0, 0.03, + 0, 0] diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc new file mode 100644 index 0000000000..a5f03295bc --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc @@ -0,0 +1,118 @@ +#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" + +#include "multibody/multibody_utils.h" +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +using std::string; +using std::vector; + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::systems::OutputVector; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib::examples::osc { + +PelvisRollTrajGenerator::PelvisRollTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& hip_roll_traj, + drake::trajectories::PiecewisePolynomial& pelvis_roll_traj, + int axis, const std::string& system_name) + : plant_(plant), + context_(context), + world_(plant_.world_frame()), + hip_roll_traj_(hip_roll_traj), + pelvis_roll_traj_(pelvis_roll_traj), + axis_(axis) { + this->set_name(system_name); + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) + .get_index(); + + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + this->DeclareAbstractOutputPort("pelvis_rot_traj_" + std::to_string(axis), + traj_inst, + &PelvisRollTrajGenerator::CalcTraj); + + DeclarePerStepDiscreteUpdateEvent( + &PelvisRollTrajGenerator::DiscreteVariableUpdate); +} + +EventStatus PelvisRollTrajGenerator::DiscreteVariableUpdate( + const Context& context, + DiscreteValues* discrete_state) const { + return EventStatus::Succeeded(); +} + +PiecewisePolynomial PelvisRollTrajGenerator::GeneratePelvisTraj( + const systems::OutputVector* robot_output, double t, + int fsm_state) const { + VectorXd q = robot_output->GetPositions(); + VectorXd v = robot_output->GetVelocities(); + multibody::SetPositionsIfNew(plant_, q, context_); + + // int hip_roll_idx_ = 1; + // int hip_rolldot_idx_ = 3; + VectorXd correction = VectorXd::Zero(1); + + drake::math::RotationMatrix pelvis_rot = + plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) + .rotation(); + drake::math::RollPitchYawd pelvis_rpy = drake::math::RollPitchYaw(pelvis_rot); + double pelvis_roll = pelvis_rpy.roll_angle(); + + correction << pelvis_roll; + std::vector breaks = hip_roll_traj_.get_segment_times(); + VectorXd breaks_vector = Map(breaks.data(), breaks.size()); + MatrixXd foot_offset_points = correction.replicate(1, breaks.size()); + PiecewisePolynomial offset_traj = + PiecewisePolynomial::ZeroOrderHold(breaks_vector, + foot_offset_points); + return hip_roll_traj_ + offset_traj; +} + +void PelvisRollTrajGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // Read in current state + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + // Read in finite state machine + const auto& fsm_state = + this->EvalVectorInput(context, fsm_port_)->get_value()(0); + const auto& clock = + this->EvalVectorInput(context, clock_port_)->get_value()(0); + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (fsm_state == 0 || fsm_state == 1) { + *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); + } +} + +} // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.h b/examples/Cassie/osc_run/pelvis_roll_traj_generator.h new file mode 100644 index 0000000000..3d938e0ea1 --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_roll_traj_generator.h @@ -0,0 +1,60 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib::examples::osc { + +class PelvisRollTrajGenerator : public drake::systems::LeafSystem { + public: + PelvisRollTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& hip_roll_traj, + drake::trajectories::PiecewisePolynomial& pelvis_roll_traj, + int axis, const std::string& system_name); + + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_fsm_input_port() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_clock_input_port() const { + return this->get_input_port(clock_port_); + } + + private: + drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( + const systems::OutputVector* robot_output, double t, int fsm_state) const; + + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::BodyFrame& world_; + + // drake::systems::DiscreteStateIndex prev_fsm_idx_; + + // pelvis trajectory + drake::trajectories::PiecewisePolynomial hip_roll_traj_; + drake::trajectories::PiecewisePolynomial pelvis_roll_traj_; + + // A list of pairs of contact body frame and contact point + int axis_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex fsm_port_; + drake::systems::InputPortIndex clock_port_; +}; + +} // namespace dairlib::examples::osc diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc new file mode 100644 index 0000000000..cc89b84fe1 --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -0,0 +1,153 @@ +#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" + +#include "multibody/multibody_utils.h" +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +using std::string; +using std::vector; + +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::systems::OutputVector; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +// using drake::common::Polynomial; +using drake::multibody::JacobianWrtVariable; +using drake::trajectories::Trajectory; + +namespace dairlib::examples::osc { + +PelvisTransTrajGenerator::PelvisTransTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& traj, + const std::unordered_map< + int, std::vector&>>>& + feet_contact_points, + bool relative_pelvis) + : plant_(plant), + context_(context), + world_(plant_.world_frame()), + pelvis_(plant_.GetBodyByName("pelvis")), + pelvis_frame_(pelvis_.body_frame()), + traj_(traj), + feet_contact_points_(feet_contact_points), + relative_pelvis_(relative_pelvis) { + this->set_name("pelvis_trans_traj_generator"); + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) + .get_index(); + + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + this->DeclareAbstractOutputPort("pelvis_trans_traj", traj_inst, + &PelvisTransTrajGenerator::CalcTraj); + + DeclarePerStepDiscreteUpdateEvent( + &PelvisTransTrajGenerator::DiscreteVariableUpdate); +} + +EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( + const Context& context, + DiscreteValues* discrete_state) const { + return EventStatus::Succeeded(); +} + +PiecewisePolynomial PelvisTransTrajGenerator::GeneratePelvisTraj( + const VectorXd& x, double t, int fsm_state) const { + return traj_; +} + +PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( + const VectorXd& x, double t, int fsm_state) const { + // fsm_state should be unused + if (fsm_state == 2) { + // flight phase trajectory should be unused + return PiecewisePolynomial(); + } + + Vector3d f_g = {0, 0, -9.81}; + Vector3d foot_pos = Vector3d::Zero(); + Vector3d pelvis_pos = Vector3d::Zero(); + Vector3d pelvis_vel = Vector3d::Zero(); + plant_.CalcPointsPositions(*context_, + feet_contact_points_.at(fsm_state)[0].second, + Vector3d::Zero(), world_, &foot_pos); +// plant_.CalcPointsPositions(*context_, pelvis_frame_, Vector3d::Zero(), world_, +// &pelvis_pos); + pelvis_pos = plant_.CalcCenterOfMassPositionInWorld(*context_); + pelvis_vel = + plant_.EvalBodySpatialVelocityInWorld(*context_, pelvis_).translational(); + Vector3d leg_length = pelvis_pos - foot_pos; + + double compression = leg_length.norm() - rest_length_; + Vector3d f_leg = + k_leg_ * compression * leg_length.normalized() + b_leg_ * pelvis_vel; + VectorXd rddot = f_g + f_leg; + + double dt = 1e-3; + Eigen::Vector2d breaks; + breaks << t, t + dt; + MatrixXd samples(3, 2); + MatrixXd samples_dot(3, 2); + samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; + samples_dot << pelvis_vel, pelvis_vel + rddot * dt; + + // std::cout << "pelvis_pos: " << pelvis_pos.transpose() << std::endl; + // std::cout << (pelvis_pos + 0.5 * rddot * dt * dt).transpose() << + // std::endl; std::cout << "pelvis_vel: " << pelvis_vel + rddot * dt << + // std::endl; std::cout << "pelvis_acc: " << rddot.transpose() << std::endl; + +// return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( +// breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); + return PiecewisePolynomial(Vector3d{0, 0, rest_length_}); +} + +void PelvisTransTrajGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // Read in current state + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + // Read in finite state machine + const auto& fsm_state = + this->EvalVectorInput(context, fsm_port_)->get_value()(0); + const auto& clock = + this->EvalVectorInput(context, clock_port_)->get_value()(0); + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + // const drake::VectorX& x = robot_output->GetState(); + if (fsm_state == 0 || fsm_state == 1) { + if (relative_pelvis_) { + *casted_traj = + GenerateSLIPTraj(robot_output->GetState(), clock, fsm_state); + } else { + *casted_traj = + GeneratePelvisTraj(robot_output->GetState(), clock, fsm_state); + } + } +} + +} // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h new file mode 100644 index 0000000000..ba7b77b2da --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -0,0 +1,82 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib::examples::osc { + +class PelvisTransTrajGenerator : public drake::systems::LeafSystem { + public: + PelvisTransTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& traj, + const std::unordered_map< + int, std::vector&>>>& + feet_contact_points, + bool relative_pelvis = false); + + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_fsm_input_port() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_clock_input_port() const { + return this->get_input_port(clock_port_); + } + + void SetSLIPParams(double rest_length, double k_leg, double b_leg){ + rest_length_ = rest_length; + k_leg_ = k_leg; + b_leg_ = rest_length; + } + + private: + drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( + const Eigen::VectorXd& x, double t, int fsm_state) const; + + drake::trajectories::PiecewisePolynomial GenerateSLIPTraj( + const Eigen::VectorXd& x, double t, int fsm_state) const; + + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::BodyFrame& world_; + const drake::multibody::Body& pelvis_; + const drake::multibody::BodyFrame& pelvis_frame_; + const bool relative_pelvis_; + + // drake::systems::DiscreteStateIndex prev_fsm_idx_; + + // pelvis trajectory + drake::trajectories::PiecewisePolynomial traj_; + + // A list of pairs of contact body frame and contact point + const std::unordered_map< + int, std::vector&>>>& + feet_contact_points_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex fsm_port_; + drake::systems::InputPortIndex clock_port_; + + // SLIP parameters + double rest_length_ = 0.8; + double k_leg_ = 100.0; + double b_leg_ = 5.0; +}; + +} // namespace dairlib::examples::osc diff --git a/examples/Cassie/run_dircon_running.cc b/examples/Cassie/run_dircon_running.cc new file mode 100644 index 0000000000..5a39ca8b93 --- /dev/null +++ b/examples/Cassie/run_dircon_running.cc @@ -0,0 +1,610 @@ +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "examples/Cassie/cassie_utils.h" +#include "lcm/dircon_saved_trajectory.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/world_point_evaluator.h" +#include "multibody/multibody_utils.h" +#include "multibody/visualization_utils.h" +#include "systems/trajectory_optimization/dircon/dircon_mode.h" +#include "solvers/cost_function_utils.h" + +#include "drake/solvers/solve.h" +#include "drake/systems/trajectory_optimization/multiple_shooting.h" + +using std::cout; +using std::endl; +using std::map; +using std::shared_ptr; +using std::string; +using std::unordered_map; +using std::vector; + +using drake::geometry::SceneGraph; +using drake::multibody::Parser; +using Eigen::Matrix3Xd; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; +using drake::geometry::DrakeVisualizer; + +using dairlib::multibody::KinematicEvaluator; +using dairlib::multibody::KinematicEvaluatorSet; +using dairlib::systems::trajectory_optimization::Dircon; +using dairlib::systems::trajectory_optimization::DirconMode; +using dairlib::systems::trajectory_optimization::DirconModeSequence; +using dairlib::systems::trajectory_optimization::PointPositionConstraint; +using drake::math::RotationMatrix; +using drake::multibody::Body; +using drake::multibody::MultibodyPlant; +using drake::solvers::MathematicalProgram; +using drake::solvers::MathematicalProgramResult; +using drake::solvers::MatrixXDecisionVariable; +using drake::solvers::SolutionResult; +using drake::solvers::VectorXDecisionVariable; +using drake::systems::trajectory_optimization::MultipleShooting; +using drake::trajectories::PiecewisePolynomial; + +DEFINE_int32(knot_points, 16, "Number of knot points per stance mode"); +DEFINE_double(stride_length, 0.2, "Stride length."); +DEFINE_double(start_height, 0.90, "Starting pelvis height for the trajectory."); +DEFINE_double(stance_T, 0.2, "Single stance duration (s)."); +DEFINE_double(flight_phase_T, 0.1, "Flight phase duration (s)."); +DEFINE_int32(scale_option, 2, + "Scale option of SNOPT" + "Use 2 if seeing snopta exit 40 in log file"); +DEFINE_bool(scale_variables, true, "Set to false if using default scaling"); +DEFINE_bool(scale_constraints, true, "Set to false if using default scaling"); +DEFINE_double(tol, 1e-7, "Tolerance for constraint violation and dual gap"); +DEFINE_string(load_filename, "", "File to load decision vars from."); +DEFINE_string(data_directory, "examples/Cassie/saved_trajectories/", + "Directory path to save decision vars to."); +DEFINE_string(save_filename, "default_filename", + "Filename to save decision " + "vars to."); +DEFINE_bool(ipopt, false, "Set flag to true to use ipopt instead of snopt"); +DEFINE_bool(same_knotpoints, false, + "Set flag to true if seeding with a trajectory with the same " + "number of knotpoints"); + +namespace dairlib { + +void setKinematicConstraints(Dircon& trajopt, + const MultibodyPlant& plant); +MatrixXd loadSavedDecisionVars(const string& filepath); +void SetInitialGuessFromTrajectory(Dircon& trajopt, + const string& filepath, + bool same_knot_points = false); +vector createStateNameVectorFromMap(const map& pos_map, + const map& vel_map, + const map& act_map); +void DoMain() { + // Drake system initialization stuff + drake::systems::DiagramBuilder builder; + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + MultibodyPlant plant(0.0); + MultibodyPlant plant_vis(0.0); + + string file_name = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; + Parser parser(&plant); + Parser parser_vis(&plant_vis, &scene_graph); + + parser.AddModelFromFile(file_name); + parser_vis.AddModelFromFile(file_name); + plant.Finalize(); + plant_vis.Finalize(); + + int n_q = plant.num_positions(); + int n_v = plant.num_velocities(); + int n_x = n_q + n_v; + + std::cout << "nq: " << n_q << " n_v: " << n_v << " n_x: " << n_x << std::endl; + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + + // Set up contact/distance constraints + auto left_toe_pair = LeftToeFront(plant); + auto left_heel_pair = LeftToeRear(plant); + auto right_toe_pair = RightToeFront(plant); + auto right_heel_pair = RightToeRear(plant); + + std::vector toe_active_inds{0, 1, 2}; + std::vector heel_active_inds{1, 2}; + + double mu = 1; + + auto left_toe_eval = multibody::WorldPointEvaluator( + plant, left_toe_pair.first, left_toe_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), toe_active_inds); + left_toe_eval.set_frictional(); + left_toe_eval.set_mu(mu); + auto left_heel_eval = multibody::WorldPointEvaluator( + plant, left_heel_pair.first, left_heel_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), heel_active_inds); + left_heel_eval.set_frictional(); + left_heel_eval.set_mu(mu); + auto right_toe_eval = multibody::WorldPointEvaluator( + plant, right_toe_pair.first, right_toe_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), toe_active_inds); + right_toe_eval.set_frictional(); + right_toe_eval.set_mu(mu); + auto right_heel_eval = multibody::WorldPointEvaluator( + plant, right_heel_pair.first, right_heel_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), heel_active_inds); + right_heel_eval.set_frictional(); + right_heel_eval.set_mu(mu); + + auto left_loop_eval = LeftLoopClosureEvaluator(plant); + auto right_loop_eval = RightLoopClosureEvaluator(plant); + + auto left_stance_constraints = KinematicEvaluatorSet(plant); + int left_toe_eval_ind = left_stance_constraints.add_evaluator(&left_toe_eval); + int left_heel_eval_ind = + left_stance_constraints.add_evaluator(&left_heel_eval); + left_stance_constraints.add_evaluator(&left_loop_eval); + left_stance_constraints.add_evaluator(&right_loop_eval); + + auto right_stance_constraints = KinematicEvaluatorSet(plant); + int right_toe_eval_ind = + right_stance_constraints.add_evaluator(&right_toe_eval); + int right_heel_eval_ind = + right_stance_constraints.add_evaluator(&right_heel_eval); + right_stance_constraints.add_evaluator(&left_loop_eval); + right_stance_constraints.add_evaluator(&right_loop_eval); + + auto flight_phase_constraints = KinematicEvaluatorSet(plant); + flight_phase_constraints.add_evaluator(&left_loop_eval); + flight_phase_constraints.add_evaluator(&right_loop_eval); + + int stance_knotpoints = FLAGS_knot_points; + int flight_phase_knotpoints = FLAGS_knot_points / 2; + double flight_phase_T = FLAGS_flight_phase_T; + double min_T = FLAGS_stance_T; + double max_T = FLAGS_stance_T; + + auto left_stance = DirconMode(left_stance_constraints, + stance_knotpoints, min_T, max_T); + auto right_stance = DirconMode(right_stance_constraints, + stance_knotpoints, min_T, max_T); + left_stance.MakeConstraintRelative(left_toe_eval_ind, 0); // x + left_stance.MakeConstraintRelative(left_toe_eval_ind, 1); // y + left_stance.MakeConstraintRelative(left_heel_eval_ind, 0); // x + left_stance.MakeConstraintRelative(left_heel_eval_ind, 1); // y + right_stance.MakeConstraintRelative(right_toe_eval_ind, 0); // x + right_stance.MakeConstraintRelative(right_toe_eval_ind, 1); // y + right_stance.MakeConstraintRelative(right_heel_eval_ind, 0); // x + right_stance.MakeConstraintRelative(right_heel_eval_ind, 1); // y + auto flight_phase = + DirconMode(flight_phase_constraints, flight_phase_knotpoints, + flight_phase_T, flight_phase_T); + + auto all_modes = DirconModeSequence(plant); + all_modes.AddMode(&left_stance); + all_modes.AddMode(&flight_phase); + all_modes.AddMode(&right_stance); + // all_modes.AddMode(&flight_phase); + + auto trajopt = Dircon(all_modes); + + double tol = FLAGS_tol; + if (FLAGS_ipopt) { + // Ipopt settings adapted from CaSaDi and FROST + auto id = drake::solvers::IpoptSolver::id(); + trajopt.SetSolverOption(id, "tol", tol); + trajopt.SetSolverOption(id, "dual_inf_tol", tol); + trajopt.SetSolverOption(id, "constr_viol_tol", tol); + trajopt.SetSolverOption(id, "compl_inf_tol", tol); + trajopt.SetSolverOption(id, "max_iter", 1e5); + trajopt.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); + trajopt.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); + trajopt.SetSolverOption(id, "print_timing_statistics", "yes"); + trajopt.SetSolverOption(id, "print_level", 5); + trajopt.SetSolverOption(id, "output_file", "../ipopt.out"); + + // Set to ignore overall tolerance/dual infeasibility, but terminate when + // primal feasible and objective fails to increase over 5 iterations. + trajopt.SetSolverOption(id, "acceptable_compl_inf_tol", tol); + trajopt.SetSolverOption(id, "acceptable_constr_viol_tol", tol); + trajopt.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); + trajopt.SetSolverOption(id, "acceptable_tol", 1e2); + trajopt.SetSolverOption(id, "acceptable_iter", 5); + } else { + // Snopt settings + auto id = drake::solvers::SnoptSolver::id(); + trajopt.SetSolverOption(id, "Print file", "../snopt.out"); + trajopt.SetSolverOption(id, "Major iterations limit", 1e5); + trajopt.SetSolverOption(id, "Iterations limit", 100000); + trajopt.SetSolverOption(id, "Verify level", 0); + + // snopt doc said try 2 if seeing snopta exit 40 + trajopt.SetSolverOption(id, "Scale option", 2); + trajopt.SetSolverOption(id, "Solution", "No"); + + // target nonlinear constraint violation + trajopt.SetSolverOption(id, "Major optimality tolerance", 1e-4); + + // target complementarity gap + trajopt.SetSolverOption(id, "Major feasibility tolerance", tol); + } + + std::cout << "Adding kinematic constraints: " << std::endl; + setKinematicConstraints(trajopt, plant); + std::cout << "Setting initial conditions: " << std::endl; + + if (!FLAGS_load_filename.empty()) { + std::cout << "Loading: " << FLAGS_load_filename << std::endl; + SetInitialGuessFromTrajectory(trajopt, + FLAGS_data_directory + FLAGS_load_filename, + FLAGS_same_knotpoints); + } else { + trajopt.SetInitialGuessForAllVariables( + VectorXd::Random(trajopt.decision_variables().size())); + } + + auto loaded_traj = + DirconTrajectory(FLAGS_data_directory + FLAGS_load_filename); + + std::vector> x_trajs; + x_trajs.push_back(PiecewisePolynomial::CubicHermite( + loaded_traj.GetStateBreaks(0), loaded_traj.GetStateSamples(0), + loaded_traj.GetStateDerivativeSamples(0))); + x_trajs.push_back(PiecewisePolynomial::CubicHermite( + loaded_traj.GetStateBreaks(1), loaded_traj.GetStateSamples(1), + loaded_traj.GetStateDerivativeSamples(1))); + x_trajs.push_back(PiecewisePolynomial::CubicHermite( + loaded_traj.GetStateBreaks(2), loaded_traj.GetStateSamples(2), + loaded_traj.GetStateDerivativeSamples(2))); + + // To avoid NaN quaternions + for (int i = 0; i < trajopt.N(); i++) { + auto xi = trajopt.state(i); + if ((trajopt.GetInitialGuess(xi.head(4)).norm() == 0) || + std::isnan(trajopt.GetInitialGuess(xi.head(4)).norm())) { + trajopt.SetInitialGuess(xi(0), 1); + trajopt.SetInitialGuess(xi(1), 0); + trajopt.SetInitialGuess(xi(2), 0); + trajopt.SetInitialGuess(xi(3), 0); + } + } + + double alpha = .2; + int num_poses = std::min(FLAGS_knot_points, 10); + trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); + + drake::solvers::SolverId solver_id(""); + if (FLAGS_ipopt) { + solver_id = drake::solvers::IpoptSolver().id(); + cout << "\nChose manually: " << solver_id.name() << endl; + } else { + solver_id = drake::solvers::ChooseBestSolver(trajopt); + cout << "\nChose the best solver: " << solver_id.name() << endl; + } + + cout << "Solving DIRCON\n\n"; + auto start = std::chrono::high_resolution_clock::now(); + const auto result = Solve(trajopt, trajopt.initial_guess()); + // SolutionResult solution_result = result.get_solution_result(); + auto finish = std::chrono::high_resolution_clock::now(); + std::chrono::duration elapsed = finish - start; + cout << "Solve time:" << elapsed.count() << std::endl; + std::cout << "Cost:" << result.get_optimal_cost() << std::endl; + std::cout << "Solve result: " << result.get_solution_result() << std::endl; + + // Save trajectory to file + DirconTrajectory saved_traj(plant, trajopt, result, "running_trajectory", + "Decision variables and state/input trajectories " + "for walking"); + saved_traj.WriteToFile(FLAGS_data_directory + FLAGS_save_filename); + std::cout << "Wrote to file: " << FLAGS_data_directory + FLAGS_save_filename + << std::endl; + drake::trajectories::PiecewisePolynomial optimal_traj = + trajopt.ReconstructStateTrajectory(result); + multibody::connectTrajectoryVisualizer(&plant_vis, &builder, &scene_graph, + optimal_traj); + + DrakeVisualizer::AddToBuilder(&builder, scene_graph); + auto diagram = builder.Build(); + + // while (true) { + // drake::systems::Simulator simulator(*diagram); + // simulator.set_target_realtime_rate(0.1); + // simulator.Initialize(); + // simulator.AdvanceTo(optimal_traj.end_time()); + // } +} + +void setKinematicConstraints(Dircon& trajopt, + const MultibodyPlant& plant) { + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + + int n_q = plant.num_positions(); + int n_v = plant.num_velocities(); + int n_u = plant.num_actuators(); + + // Get the decision variables that will be used + int N = trajopt.N(); + auto x = trajopt.state(); + auto u = trajopt.input(); + auto x0 = trajopt.initial_state(); + auto x_mid = trajopt.state(N / 2); + auto xf = trajopt.final_state(); + auto u0 = trajopt.input(0); + auto uf = trajopt.input(N - 1); + + // Standing constraints + double start_height = FLAGS_start_height; + + // position constraints + trajopt.AddBoundingBoxConstraint(-0.25, 0.25, x0(pos_map.at("base_x"))); + trajopt.AddLinearConstraint(x0(pos_map.at("base_x")) + FLAGS_stride_length == + xf(pos_map.at("base_x"))); + trajopt.AddBoundingBoxConstraint(start_height, start_height, + x0(pos_map.at("base_z"))); + // trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("base_y")) <= 0.05); + // trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("base_y")) >= -0.05); + // initial fb orientation constraint + VectorXd quat_identity(4); + quat_identity << 1, 0, 0, 0; + trajopt.AddBoundingBoxConstraint(quat_identity, quat_identity, x0.head(4)); + trajopt.AddBoundingBoxConstraint(quat_identity, quat_identity, x_mid.head(4)); + trajopt.AddBoundingBoxConstraint(quat_identity, quat_identity, xf.head(4)); + + // periodicity constraint + trajopt.AddLinearConstraint(x0(pos_map.at("base_y")) == + -xf(pos_map.at("base_y"))); + trajopt.AddLinearConstraint(x0(pos_map.at("base_z")) == + xf(pos_map.at("base_z"))); + trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_wx")) == + xf(n_q + vel_map.at("base_wx"))); + trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_wy")) == + -xf(n_q + vel_map.at("base_wy"))); + trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_wz")) == + xf(n_q + vel_map.at("base_wz"))); + trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_vx")) == + xf(n_q + vel_map.at("base_vx"))); + trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_vy")) == + -xf(n_q + vel_map.at("base_vy"))); + trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_vz")) == + xf(n_q + vel_map.at("base_vz"))); + + // create joint/motor names + vector> l_r_pairs{ + std::pair("_left", "_right"), + std::pair("_right", "_left"), + }; + vector asy_joint_names{"hip_roll", "hip_yaw"}; + vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; + vector joint_names{}; + vector motor_names{}; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + joint_names.push_back(asy_joint_name + l_r_pair.first); + motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); + } + for (const auto& sym_joint_name : sym_joint_names) { + joint_names.push_back(sym_joint_name + l_r_pair.first); + if (sym_joint_name != "ankle_joint") { + motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); + } + } + } + + for (const auto& l_r_pair : l_r_pairs) { + // Symmetry constraints + for (const auto& sym_joint_name : sym_joint_names) { + trajopt.AddLinearConstraint( + x0(pos_map[sym_joint_name + l_r_pair.first]) == + xf(pos_map[sym_joint_name + l_r_pair.second])); + trajopt.AddLinearConstraint( + x0(n_q + vel_map.at(sym_joint_name + l_r_pair.first + "dot")) == + xf(n_q + vel_map.at(sym_joint_name + l_r_pair.second + "dot"))); + if (sym_joint_name != "ankle_joint") { // No actuator at ankle + trajopt.AddLinearConstraint( + u0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == + uf(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + } + } + // Asymmetry constraints + for (const auto& asy_joint_name : asy_joint_names) { + trajopt.AddLinearConstraint( + x0(pos_map[asy_joint_name + l_r_pair.first]) == + -xf(pos_map[asy_joint_name + l_r_pair.second])); + trajopt.AddLinearConstraint( + x0(n_q + vel_map.at(asy_joint_name + l_r_pair.first + "dot")) == + -xf(n_q + vel_map.at(asy_joint_name + l_r_pair.second + "dot"))); + if (asy_joint_name != "ankle_joint") { // No actuator at ankle + trajopt.AddLinearConstraint( + u0(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) == + -uf(act_map.at(asy_joint_name + l_r_pair.second + "_motor"))); + } + } + } + + // joint limits + std::cout << "Joint limit constraints: " << std::endl; + for (const auto& member : joint_names) { + trajopt.AddConstraintToAllKnotPoints( + x(pos_map.at(member)) <= + plant.GetJointByName(member).position_upper_limits()(0)); + trajopt.AddConstraintToAllKnotPoints( + x(pos_map.at(member)) >= + plant.GetJointByName(member).position_lower_limits()(0)); + } + + // actuator limits + std::cout << "Actuator limit constraints: " << std::endl; + for (int i = 0; i < trajopt.N(); i++) { + auto ui = trajopt.input(i); + trajopt.AddBoundingBoxConstraint(VectorXd::Constant(n_u, -200), + VectorXd::Constant(n_u, +200), ui); + } + + std::cout << "Foot placement constraints: " << std::endl; + // toe position constraint in y direction (avoid leg crossing) + // tighter constraint than before + auto left_foot_y_constraint = + std::make_shared>( + plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), + 0.10 * VectorXd::Ones(1), 0.25 * VectorXd::Ones(1)); + auto right_foot_y_constraint = + std::make_shared>( + plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), + -0.25 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + + for (int i = 0; i < N; ++i) { + auto x_i = trajopt.state(i); + trajopt.AddConstraint(left_foot_y_constraint, x_i.head(n_q)); + trajopt.AddConstraint(right_foot_y_constraint, x_i.head(n_q)); + } + + for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + for (int index = 0; index < trajopt.mode_length(mode); index++) { + // Assumes mode_lengths are the same across modes + + auto lambda = trajopt.force_vars(mode, index); + if (mode == 0 || mode == 2) { + trajopt.AddLinearConstraint(lambda(2) >= 10); + trajopt.AddLinearConstraint(lambda(5) >= 10); + } + } + } + std::cout << "Stride length constraints: " << std::endl; + // stride length constraint + auto right_foot_x_constraint = + std::make_shared>( + plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), + FLAGS_stride_length * VectorXd::Ones(1), + FLAGS_stride_length * VectorXd::Ones(1)); + auto left_foot_x_constraint = + std::make_shared>( + plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), + 0 * VectorXd::Ones(1), 0 * VectorXd::Ones(1)); + trajopt.AddConstraint(left_foot_x_constraint, x0.head(n_q)); + trajopt.AddConstraint(right_foot_x_constraint, xf.head(n_q)); + + std::cout << "Foot clearance constraints: " << std::endl; + // Foot clearance constraint + auto left_foot_z_constraint_clearance = + std::make_shared>( + plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + 0.055 * VectorXd::Ones(1), (0.15) * VectorXd::Ones(1)); + auto right_foot_z_constraint_clearance = + std::make_shared>( + plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + 0.055 * VectorXd::Ones(1), (0.15) * VectorXd::Ones(1)); + for (int i = 0; i < N; i++) { + auto x_i = trajopt.state(i); + trajopt.AddConstraint(left_foot_z_constraint_clearance, x_i.head(n_q)); + trajopt.AddConstraint(right_foot_z_constraint_clearance, x_i.head(n_q)); + trajopt.AddBoundingBoxConstraint(-1.8, -1.5, x_i[pos_map["toe_left"]]); + trajopt.AddBoundingBoxConstraint(-1.8, -1.5, x_i[pos_map["toe_right"]]); + } + + std::cout << "Miscellaneous constraints" << std::endl; + // Miscellaneous constraints + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_yaw_left")) >= -0.01); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_yaw_left")) <= 0.01); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_yaw_right")) >= -0.01); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_yaw_right")) <= 0.01); + // Miscellaneous constraints + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_roll_left")) >= 0.0); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_roll_left")) <= 0.10); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_roll_right")) >= + -0.10); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_roll_right")) <= 0.0); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_pitch_left")) >= 0.50); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_pitch_left")) <= 0.90); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_pitch_right")) >= + 0.50); + trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("hip_pitch_right")) <= + 0.90); + + std::cout << "Adding costs: " << std::endl; + double W = 1e-1; + MatrixXd Q = MatrixXd::Identity(n_v, n_v); + Q(7, 7) = 10; + Q(8, 8) = 10; +// MatrixXd R = 1e-3 * MatrixXd::Identity(n_u, n_u); +// R(8, 8) = 1; +// R(9, 9) = 1; + trajopt.AddRunningCost((x.tail(n_v).transpose() * Q * x.tail(n_v))); +// trajopt.AddRunningCost(u.transpose() * R * u); + solvers::AddPositiveWorkCost(trajopt, plant, W); + + // MatrixXd S = MatrixXd::Zero(n_u, n_v); + // S(0, 6) = 1; + // S(1, 7) = 1; + // S(2, 8) = 1; + // S(3, 9) = 1; + // S(4, 10) = 1; + // S(5, 11) = 1; + // S(6, 12) = 1; + // S(7, 13) = 1; + // S(8, 16) = 1; + // S(9, 17) = 1; + // const drake::symbolic::Expression e_max_{max(static_cast>( + // u.transpose() * S * x.tail(n_v) + u.transpose() * R * u), + // VectorXd::Zero(1))}; + // drake::symbolic::max(u.transpose() * S * x.tail(n_v), 0); + // trajopt.AddRunningCost(drake::symbolic::max(u.transpose() * S * + // x.tail(n_v), 0)); trajopt.AddRunningCost(u.transpose() * S * x.tail(n_v) + // + u.transpose() * R * u); +} + +void SetInitialGuessFromTrajectory(Dircon& trajopt, + const string& filepath, + bool same_knot_points) { + DirconTrajectory previous_traj = DirconTrajectory(filepath); + if (same_knot_points) { + trajopt.SetInitialGuessForAllVariables( + previous_traj.GetDecisionVariables()); + return; + } + auto state_traj = previous_traj.ReconstructStateTrajectory(); + auto input_traj = previous_traj.ReconstructInputTrajectory(); + auto lambda_traj = previous_traj.ReconstructLambdaTrajectory(); + auto lambda_c_traj = previous_traj.ReconstructLambdaCTrajectory(); + auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); + + trajopt.SetInitialTrajectory(input_traj, state_traj); + for (int mode = 0; mode < trajopt.num_modes() - 1; ++mode) { + if (trajopt.mode_length(mode) > 1) { + std::cout << "mode: " << mode << std::endl; + trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], + lambda_c_traj[mode], gamma_traj[mode]); + } + } +} + +MatrixXd loadSavedDecisionVars(const string& filepath) { + DirconTrajectory previous_traj = DirconTrajectory(filepath); + for (auto& name : previous_traj.GetTrajectoryNames()) { + std::cout << name << std::endl; + } + return previous_traj.GetDecisionVariables(); +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + dairlib::DoMain(); +} \ No newline at end of file diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc new file mode 100644 index 0000000000..1953380c8e --- /dev/null +++ b/examples/Cassie/run_osc_running_controller.cc @@ -0,0 +1,666 @@ +#include + +#include +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/osc/high_level_command.h" +#include "examples/Cassie/osc/swing_toe_traj_generator.h" +#include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" +#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" +#include "examples/Cassie/osc_run/foot_traj_generator.h" +//#include "examples/Cassie/osc_run/joint_space_running_gains.h" +#include "examples/Cassie/osc_run/osc_running_gains.h" +#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" +#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" +#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" +#include "lcm/dircon_saved_trajectory.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" + +namespace dairlib { + +using std::map; +using std::pair; +using std::string; +using std::vector; + +using Eigen::Matrix3d; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using drake::geometry::SceneGraph; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using examples::osc::PelvisRollTrajGenerator; +using examples::osc::PelvisTransTrajGenerator; +using examples::osc_jump::BasicTrajectoryPassthrough; +using examples::osc_run::FootTrajGenerator; +using multibody::FixedJointEvaluator; +using cassie::osc::SwingToeTrajGenerator; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::WorldYawOscViewFrame; + +namespace examples { + +DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", + "The name of the channel which receives state"); +DEFINE_string(channel_u, "CASSIE_INPUT", + "The name of the channel which publishes command"); +DEFINE_string(folder_path, "examples/Cassie/saved_trajectories/", + "Folder path for where the trajectory names are stored"); +DEFINE_string(traj_name, "running_0.00", + "File to load saved trajectories from"); +DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", + "Filepath containing gains"); +DEFINE_bool(use_radio, false, + "Set to true if sending high level commands from radio controller"); +DEFINE_string( + channel_cassie_out, "CASSIE_OUTPUT_ECHO", + "The name of the channel to receive the cassie out structure from."); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Build the controller diagram + DiagramBuilder builder; + + // Built the Cassie MBPs + drake::multibody::MultibodyPlant plant(0.0); + addCassieMultibody(&plant, nullptr, true, + "examples/Cassie/urdf/cassie_v2.urdf", + false /*spring model*/, false /*loop closure*/); + drake::multibody::MultibodyPlant plant_wo_spr(0.0); + addCassieMultibody(&plant_wo_spr, nullptr, true, + "examples/Cassie/urdf/cassie_fixed_springs.urdf", + false /*spring model*/, false /*loop closure*/); + plant.Finalize(); + plant_wo_spr.Finalize(); + + auto plant_context = plant.CreateDefaultContext(); + + // Get contact frames and position + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); + + int nv = plant.num_velocities(); + + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + + map pos_map_wo_spr = + multibody::makeNameToPositionsMap(plant_wo_spr); + + std::unordered_map< + int, std::vector&>>> + feet_contact_points; + feet_contact_points[0] = std::vector< + std::pair&>>( + {left_toe, left_heel}); + feet_contact_points[1] = std::vector< + std::pair&>>( + {right_toe, right_heel}); + + /**** Get trajectory from optimization ****/ + const DirconTrajectory& dircon_trajectory = DirconTrajectory( + FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); + + PiecewisePolynomial state_traj = + dircon_trajectory.ReconstructStateTrajectory(); + state_traj.ConcatenateInTime( + dircon_trajectory.ReconstructMirrorStateTrajectory( + state_traj.end_time())); + + /**** OSC Gains ****/ + OSCGains gains{}; + const YAML::Node& root = + YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); + drake::yaml::YamlReadArchive::Options yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); + + /**** FSM and contact mode configuration ****/ + int left_stance_state = 0; + int right_stance_state = 1; + int air_phase = 2; + double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2; + double right_support_duration = left_support_duration; + double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - + dircon_trajectory.GetStateBreaks(1)(0); + vector fsm_states = {left_stance_state, air_phase, right_stance_state, + air_phase, left_stance_state}; + std::cout << "left support duration: " << left_support_duration << std::endl; + std::cout << "flight duration: " << air_phase_duration << std::endl; + std::cout << "right support duration: " << right_support_duration << std::endl; + vector state_durations = { + left_support_duration / 2, air_phase_duration, right_support_duration, + air_phase_duration, left_support_duration / 2}; + + auto fsm = builder.AddSystem( + plant, fsm_states, state_durations, 0.0, gains.impact_threshold); + + /**** Initialize all the leaf systems ****/ + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto state_receiver = builder.AddSystem(plant); + auto command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto command_sender = builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), true); + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); + + /**** OSC setup ****/ + // Cost + MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); + osc->SetAccelerationCostForAllJoints(Q_accel); + osc->SetInputRegularizationWeight(gains.w_input_reg); + + // Soft constraint on contacts + double w_contact_relax = gains.w_soft_constraint; + osc->SetWeightOfSoftContactConstraint(w_contact_relax); + + // Contact information for OSC + osc->SetContactFriction(gains.mu); + + auto left_toe_evaluator = multibody::WorldPointEvaluator( + plant, left_toe.first, left_toe.second, Matrix3d::Identity(), + Vector3d::Zero(), {1, 2}); + auto left_heel_evaluator = multibody::WorldPointEvaluator( + plant, left_heel.first, left_heel.second, Matrix3d::Identity(), + Vector3d::Zero(), {0, 1, 2}); + auto right_toe_evaluator = multibody::WorldPointEvaluator( + plant, right_toe.first, right_toe.second, Matrix3d::Identity(), + Vector3d::Zero(), {1, 2}); + auto right_heel_evaluator = multibody::WorldPointEvaluator( + plant, right_heel.first, right_heel.second, Matrix3d::Identity(), + Vector3d::Zero(), {0, 1, 2}); + + osc->AddStateAndContactPoint(0, &left_toe_evaluator); + osc->AddStateAndContactPoint(0, &left_heel_evaluator); + osc->AddStateAndContactPoint(1, &right_toe_evaluator); + osc->AddStateAndContactPoint(1, &right_heel_evaluator); + + multibody::KinematicEvaluatorSet evaluators(plant); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + + // Fix the springs in the dynamics + auto pos_idx_map = multibody::makeNameToPositionsMap(plant); + auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + + osc->AddKinematicConstraint(&evaluators); + + /**** Tracking Data *****/ + + std::cout << "Creating tracking data. " << std::endl; + OSCRunningGains osc_gains; + drake::yaml::YamlReadArchive(root).Accept(&osc_gains); + + auto cassie_out_receiver = + builder.AddSystem(LcmSubscriberSystem::Make( + FLAGS_channel_cassie_out, &lcm)); + cassie::osc::HighLevelCommand* high_level_command; + if (FLAGS_use_radio) { + high_level_command = builder.AddSystem( + plant, plant_context.get(), osc_gains.vel_scale_rot, + osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); + builder.Connect(cassie_out_receiver->get_output_port(), + high_level_command->get_cassie_output_port()); + } else { + // high_level_command = builder.AddSystem( + // plant, plant_context.get(), gains.kp_yaw, gains.kd_yaw, + // gains.vel_max_yaw, gains.kp_pos_sagital, gains.kd_pos_sagital, + // gains.vel_max_sagital, gains.kp_pos_lateral, gains.kd_pos_lateral, + // gains.vel_max_lateral, gains.target_pos_offset, + // global_target_position, params_of_no_turning); + } + + string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; + if (osc_gains.relative_feet) { + output_traj_path += "_rel"; + } + const LcmTrajectory& output_trajs = + LcmTrajectory(FindResourceOrThrow(output_traj_path)); + PiecewisePolynomial pelvis_trans_traj; + PiecewisePolynomial l_hip_trajectory; + PiecewisePolynomial r_hip_trajectory; + PiecewisePolynomial l_foot_trajectory; + PiecewisePolynomial r_foot_trajectory; + PiecewisePolynomial pelvis_rot_trajectory; + + // for (auto name : output_trajs.GetTrajectoryNames()) { + // std::cout << name << std::endl; + // } + for (int mode = 0; mode < dircon_trajectory.GetNumModes() * 2; ++mode) { + const LcmTrajectory::Trajectory lcm_pelvis_trans_trajectory = + output_trajs.GetTrajectory("pelvis_trans_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_left_hip_traj = + output_trajs.GetTrajectory("left_hip_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_right_hip_traj = + output_trajs.GetTrajectory("right_hip_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_left_foot_traj = + output_trajs.GetTrajectory("left_foot_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_right_foot_traj = + output_trajs.GetTrajectory("right_foot_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_pelvis_rot_traj = + output_trajs.GetTrajectory("pelvis_rot_trajectory" + + std::to_string(mode)); + pelvis_trans_traj.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_pelvis_trans_trajectory.time_vector, + lcm_pelvis_trans_trajectory.datapoints.topRows(6), + lcm_pelvis_trans_trajectory.datapoints.bottomRows(6))); + l_foot_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_left_foot_traj.time_vector, + lcm_left_foot_traj.datapoints.topRows(6), + lcm_left_foot_traj.datapoints.bottomRows(6))); + r_foot_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_right_foot_traj.time_vector, + lcm_right_foot_traj.datapoints.topRows(6), + lcm_right_foot_traj.datapoints.bottomRows(6))); + l_hip_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_left_hip_traj.time_vector, + lcm_left_hip_traj.datapoints.topRows(6), + lcm_left_hip_traj.datapoints.bottomRows(6))); + r_hip_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_right_hip_traj.time_vector, + lcm_right_hip_traj.datapoints.topRows(6), + lcm_right_hip_traj.datapoints.bottomRows(6))); + pelvis_rot_trajectory.ConcatenateInTime( + PiecewisePolynomial::FirstOrderHold( + lcm_pelvis_rot_traj.time_vector, + lcm_pelvis_rot_traj.datapoints.topRows(4))); + } + + auto pelvis_trans_traj_generator = + builder.AddSystem( + plant, plant_context.get(), pelvis_trans_traj, feet_contact_points, + osc_gains.relative_pelvis); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length, + osc_gains.k_leg, osc_gains.b_leg); + auto l_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "hip_left", true, l_foot_trajectory, + l_hip_trajectory, osc_gains.relative_feet); + auto r_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "hip_right", false, r_foot_trajectory, + r_hip_trajectory, osc_gains.relative_feet); + l_foot_traj_generator->SetFootstepGains(osc_gains.K_p_footstep, + osc_gains.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_gains.K_p_footstep, + osc_gains.K_d_footstep); + + TransTaskSpaceTrackingData pelvis_tracking_data( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant); + TransTaskSpaceTrackingData left_foot_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_foot_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData stance_foot_tracking_data( + "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + pelvis_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); + pelvis_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); + left_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + "toe_right"); + stance_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + "toe_left"); + stance_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(air_phase, "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(air_phase, "toe_right"); + + TransTaskSpaceTrackingData left_hip_tracking_data( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_hip_tracking_data( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, + "hip_left"); + right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, + "hip_right"); + left_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_left"); + right_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_right"); + + WorldYawOscViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); + RelativeTranslationTrackingData left_foot_rel_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, + &left_hip_tracking_data); + RelativeTranslationTrackingData right_foot_rel_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, + &right_hip_tracking_data); + RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, + &stance_foot_tracking_data); + left_foot_rel_tracking_data.SetViewFrame(pelvis_view_frame); + right_foot_rel_tracking_data.SetViewFrame(pelvis_view_frame); + pelvis_trans_rel_tracking_data.SetViewFrame(pelvis_view_frame); + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); + + // left_foot_rel_tracking_data.DisableFeedforwardAccel({2}); + // right_foot_rel_tracking_data.DisableFeedforwardAccel({2}); + + if (osc_gains.relative_pelvis) { + osc->AddTrackingData(&pelvis_trans_rel_tracking_data); + } else { + osc->AddTrackingData(&pelvis_tracking_data); + } + + if (osc_gains.relative_feet) { + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_rel_tracking_data); + osc->AddTrackingData(&right_foot_rel_tracking_data); + } else { + left_foot_tracking_data.SetImpactInvariantProjection(true); + right_foot_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_tracking_data); + osc->AddTrackingData(&right_foot_tracking_data); + } + + // Stance hip pitch trajectory + auto hip_pitch_left_traj = dircon_trajectory.ReconstructJointTrajectory( + pos_map_wo_spr["hip_pitch_left"]); + auto hip_pitch_left_traj_mir = + dircon_trajectory.ReconstructMirrorJointTrajectory( + pos_map_wo_spr["hip_pitch_left"]); + auto hip_pitch_right_traj = dircon_trajectory.ReconstructJointTrajectory( + pos_map_wo_spr["hip_pitch_right"]); + auto hip_pitch_right_traj_mir = + dircon_trajectory.ReconstructMirrorJointTrajectory( + pos_map_wo_spr["hip_pitch_right"]); + hip_pitch_left_traj_mir.shiftRight(hip_pitch_left_traj.end_time()); + hip_pitch_right_traj_mir.shiftRight(hip_pitch_right_traj.end_time()); + hip_pitch_left_traj.ConcatenateInTime(hip_pitch_left_traj_mir); + hip_pitch_right_traj.ConcatenateInTime(hip_pitch_right_traj_mir); + auto hip_pitch_left_traj_generator = + builder.AddSystem( + hip_pitch_left_traj, "hip_pitch_left_traj_generator"); + auto hip_pitch_right_traj_generator = + builder.AddSystem( + hip_pitch_right_traj, "hip_pitch_right_traj_generator"); + JointSpaceTrackingData hip_pitch_left_tracking_data( + "hip_pitch_left_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, + osc_gains.W_hip_pitch, plant, plant); + JointSpaceTrackingData hip_pitch_right_tracking_data( + "hip_pitch_right_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, + osc_gains.W_hip_pitch, plant, plant); + std::cout << "Hip Pitch KD: " << osc_gains.K_d_hip_pitch << std::endl; + std::cout << "Hip Roll KD: " << osc_gains.K_d_hip_roll << std::endl; + hip_pitch_left_tracking_data.AddStateAndJointToTrack( + left_stance_state, "hip_pitch_left", "hip_pitch_leftdot"); + hip_pitch_right_tracking_data.AddStateAndJointToTrack( + right_stance_state, "hip_pitch_right", "hip_pitch_rightdot"); + hip_pitch_left_tracking_data.DisableFeedforwardAccel({0}); + hip_pitch_right_tracking_data.DisableFeedforwardAccel({0}); + hip_pitch_left_tracking_data.SetImpactInvariantProjection(true); + hip_pitch_right_tracking_data.SetImpactInvariantProjection(true); + osc->AddConstTrackingData(&hip_pitch_left_tracking_data, 0.6 * VectorXd::Ones(1)); + osc->AddConstTrackingData(&hip_pitch_right_tracking_data, 0.6 * VectorXd::Ones(1)); +// osc->AddTrackingData(&hip_pitch_left_tracking_data); +// osc->AddTrackingData(&hip_pitch_right_tracking_data); + + // Stance hip roll trajectory + auto hip_roll_left_traj = dircon_trajectory.ReconstructJointTrajectory( + pos_map_wo_spr["hip_roll_left"]); + auto hip_roll_left_traj_mir = + dircon_trajectory.ReconstructMirrorJointTrajectory( + pos_map_wo_spr["hip_roll_left"]); + auto hip_roll_right_traj = dircon_trajectory.ReconstructJointTrajectory( + pos_map_wo_spr["hip_roll_right"]); + auto hip_roll_right_traj_mir = + dircon_trajectory.ReconstructMirrorJointTrajectory( + pos_map_wo_spr["hip_roll_right"]); + hip_roll_left_traj_mir.shiftRight(hip_roll_left_traj.end_time()); + hip_roll_right_traj_mir.shiftRight(hip_roll_right_traj.end_time()); + hip_roll_left_traj.ConcatenateInTime(hip_roll_left_traj_mir); + hip_roll_right_traj.ConcatenateInTime(hip_roll_right_traj_mir); + PiecewisePolynomial pelvis_roll_traj = + PiecewisePolynomial(VectorXd::Zero(1)); + auto hip_roll_left_traj_generator = + builder.AddSystem( + plant, plant_context.get(), hip_roll_left_traj, pelvis_roll_traj, 1, + "hip_roll_left_traj_generator"); + auto hip_roll_right_traj_generator = + builder.AddSystem( + plant, plant_context.get(), hip_roll_right_traj, pelvis_roll_traj, 1, + "hip_roll_right_traj_generator"); + JointSpaceTrackingData hip_roll_left_tracking_data( + "hip_roll_left_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, + osc_gains.W_hip_roll, plant, plant); + JointSpaceTrackingData hip_roll_right_tracking_data( + "hip_roll_right_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, + osc_gains.W_hip_roll, plant, plant); + hip_roll_left_tracking_data.AddStateAndJointToTrack( + left_stance_state, "hip_roll_left", "hip_roll_leftdot"); + hip_roll_right_tracking_data.AddStateAndJointToTrack( + right_stance_state, "hip_roll_right", "hip_roll_rightdot"); + hip_roll_left_tracking_data.DisableFeedforwardAccel({0}); + hip_roll_right_tracking_data.DisableFeedforwardAccel({0}); + hip_roll_left_tracking_data.SetImpactInvariantProjection(true); + hip_roll_right_tracking_data.SetImpactInvariantProjection(true); + // hip_roll_left_tracking_data.AddStateAndJointToTrack( + // air_phase, "hip_roll_left", "hip_roll_leftdot"); + // hip_roll_right_tracking_data.AddStateAndJointToTrack( + // air_phase, "hip_roll_right", "hip_roll_rightdot"); + osc->AddTrackingData(&hip_roll_left_tracking_data); + osc->AddTrackingData(&hip_roll_right_tracking_data); + + // Swing toe joint trajectory + vector&>> left_foot_points = { + left_heel, left_toe}; + vector&>> right_foot_points = { + right_heel, right_toe}; + auto left_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_left"], left_foot_points, + "left_toe_angle_traj"); + auto right_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_right"], right_foot_points, + "right_toe_angle_traj"); + + // Swing toe joint tracking + JointSpaceTrackingData swing_toe_left_traj( + "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + JointSpaceTrackingData swing_toe_right_traj( + "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + swing_toe_right_traj.AddStateAndJointToTrack(left_stance_state, "toe_right", + "toe_rightdot"); + swing_toe_left_traj.AddStateAndJointToTrack(right_stance_state, "toe_left", + "toe_leftdot"); + swing_toe_right_traj.AddStateAndJointToTrack(air_phase, "toe_right", + "toe_rightdot"); + swing_toe_left_traj.AddStateAndJointToTrack(air_phase, "toe_left", + "toe_leftdot"); + swing_toe_left_traj.SetImpactInvariantProjection(true); + swing_toe_right_traj.SetImpactInvariantProjection(true); + osc->AddTrackingData(&swing_toe_left_traj); + osc->AddTrackingData(&swing_toe_right_traj); + + // Swing hip yaw joint tracking + JointSpaceTrackingData hip_yaw_left_traj( + "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + JointSpaceTrackingData hip_yaw_right_traj( + "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + hip_yaw_left_traj.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + hip_yaw_right_traj.AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); +// hip_yaw_left_traj.SetImpactInvariantProjection(true); +// hip_yaw_right_traj.SetImpactInvariantProjection(true); + osc->AddConstTrackingData(&hip_yaw_left_traj, VectorXd::Zero(1)); + osc->AddConstTrackingData(&hip_yaw_right_traj, VectorXd::Zero(1)); + + // Build OSC problem + osc->Build(); + std::cout << "Built OSC" << std::endl; + + /*****Connect ports*****/ + + // OSC connections + builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_impact(), + osc->get_near_impact_input_port()); + builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); + builder.Connect(state_receiver->get_output_port(0), + osc->get_robot_output_input_port()); + // FSM connections + builder.Connect(state_receiver->get_output_port(0), + fsm->get_input_port_state()); + + // Trajectory generator connections + builder.Connect(state_receiver->get_output_port(0), + pelvis_trans_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + pelvis_trans_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_clock(), + pelvis_trans_traj_generator->get_clock_input_port()); + builder.Connect(high_level_command->get_xy_output_port(), + l_foot_traj_generator->get_target_vel_input_port()); + builder.Connect(high_level_command->get_xy_output_port(), + r_foot_traj_generator->get_target_vel_input_port()); + builder.Connect(state_receiver->get_output_port(0), + l_foot_traj_generator->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + r_foot_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + l_foot_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + r_foot_traj_generator->get_fsm_input_port()); + builder.Connect(state_receiver->get_output_port(0), + left_toe_angle_traj_gen->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + right_toe_angle_traj_gen->get_state_input_port()); +// builder.Connect(hip_pitch_left_traj_generator->get_output_port(), +// osc->get_tracking_data_input_port("hip_pitch_left_traj")); +// builder.Connect(hip_pitch_right_traj_generator->get_output_port(), +// osc->get_tracking_data_input_port("hip_pitch_right_traj")); + builder.Connect(hip_roll_left_traj_generator->get_output_port(), + osc->get_tracking_data_input_port("hip_roll_left_traj")); + builder.Connect(hip_roll_right_traj_generator->get_output_port(), + osc->get_tracking_data_input_port("hip_roll_right_traj")); + // OSC connections + builder.Connect(pelvis_trans_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_trans_traj")); + builder.Connect(state_receiver->get_output_port(0), + hip_roll_left_traj_generator->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + hip_roll_right_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + hip_roll_left_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + hip_roll_right_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_clock(), + hip_roll_left_traj_generator->get_clock_input_port()); + builder.Connect(fsm->get_output_port_clock(), + hip_roll_right_traj_generator->get_clock_input_port()); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("left_ft_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("right_ft_traj")); + builder.Connect(left_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("left_toe_angle_traj")); + builder.Connect(right_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("right_toe_angle_traj")); + + // Publisher connections + builder.Connect(osc->get_osc_output_port(), + command_sender->get_input_port(0)); + builder.Connect(command_sender->get_output_port(0), + command_pub->get_input_port()); + builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); + + // Run lcm-driven simulation + // Create the diagram + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("osc_running_controller")); + + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} // namespace examples +} // namespace examples +} // namespace dairlib + +int main(int argc, char* argv[]) { + return dairlib::examples::DoMain(argc, argv); +} diff --git a/solvers/cost_function_utils.cc b/solvers/cost_function_utils.cc new file mode 100644 index 0000000000..9802ccdec1 --- /dev/null +++ b/solvers/cost_function_utils.cc @@ -0,0 +1,104 @@ +#include "cost_function_utils.h" +namespace dairlib { + +namespace solvers { + +using Eigen::VectorXd; +using drake::AutoDiffXd; +using drake::VectorX; +using drake::solvers::VectorXDecisionVariable; + +template +void AddPositiveWorkCost( + dairlib::systems::trajectory_optimization::Dircon& trajopt, + const drake::multibody::MultibodyPlant& plant, + double W) { + for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + int mode_start = trajopt.get_mode_start(mode); + int mode_end = trajopt.get_mode_start(mode) + trajopt.mode_length(mode) - 1; + + for (int i = mode_start; i < mode_end; ++i) { + int n_vars = 1 + 2 * plant.num_velocities() + 2 * plant.num_actuators(); + int n_v = plant.num_velocities(); + int n_u = plant.num_actuators(); + drake::solvers::VectorXDecisionVariable variables(n_vars); + variables(0) = trajopt.timestep(i)(0); + variables.segment(1, n_v) = + trajopt.state_vars(mode, i - mode_start).tail(n_v); + variables.segment(1 + n_v, n_v) = + trajopt.state_vars(mode, i + 1 - mode_start).tail(n_v); + variables.segment(1 + 2 * n_v, n_u) = + trajopt.input_vars(mode, i - mode_start); + variables.segment(1 + 2 * n_v + n_u, n_u) = + trajopt.input_vars(mode, i + 1 - mode_start); + trajopt.AddCost( + std::make_shared>(n_v, plant.num_actuators(), + plant.MakeActuationMatrix(), W, + "pos_work_cost_" + std::to_string(i)), + variables); + } + } +} + +template +PositiveMechanicalWork::PositiveMechanicalWork( + int n_v, int n_u, const Eigen::MatrixXd& B, const double W, + const std::string& description) + : solvers::NonlinearCost((1 + 2 * n_v + 2 * n_u), description), + W_(W), + B_t_(B.transpose()), + n_v_(n_v), + n_u_(n_u) { + // Checks for the provided decision vars + DRAKE_DEMAND(B.rows() == n_v_); + DRAKE_DEMAND(B.cols() == n_u_); +} + +template +T sigmoid(T val) { + return exp(val) / (1 + exp(val)); +} + +template +void PositiveMechanicalWork::EvaluateCost( + const Eigen::Ref>& x, drake::VectorX* y) const { + int start_idx = 0; + auto h = x.segment(start_idx, 1); + start_idx += 1; + auto v_i = x.segment(start_idx, n_v_); + start_idx += n_v_; + auto v_ip1 = x.segment(start_idx, n_v_); + start_idx += n_v_; + auto u_i = x.segment(start_idx, n_u_); + start_idx += n_u_; + auto u_ip1 = x.segment(start_idx, n_u_); + + T cost = T(); + VectorX actuated_velocities_i = B_t_ * v_i; + VectorX actuated_velocities_ip1 = B_t_ * v_ip1; + T zero = T(); + for (int joint_idx = 0; joint_idx < n_u_; ++joint_idx) { + cost += std::max(actuated_velocities_i(joint_idx) * u_i(joint_idx), zero); + cost += std::max(actuated_velocities_ip1(joint_idx) * u_ip1(joint_idx), zero); + // cost += sigmoid(actuated_velocities_i(joint_idx) * u_i(joint_idx)); + // cost += sigmoid(actuated_velocities_ip1(joint_idx) *u_ip1(joint_idx)); + } + cost = 0.5 * h(0) * cost; + cost *= W_; + VectorX cost_vec(1); + cost_vec << cost; + *y = cost_vec; +} + +template void AddPositiveWorkCost( + dairlib::systems::trajectory_optimization::Dircon& trajopt, + const drake::multibody::MultibodyPlant& plant, double W); +//template void AddPositiveWorkCost( +// dairlib::systems::trajectory_optimization::Dircon& trajopt, +// const drake::multibody::MultibodyPlant& plant); + +} // namespace solvers +} // namespace dairlib + +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( + class ::dairlib::solvers::PositiveMechanicalWork) \ No newline at end of file diff --git a/solvers/cost_function_utils.h b/solvers/cost_function_utils.h new file mode 100644 index 0000000000..1001c3722c --- /dev/null +++ b/solvers/cost_function_utils.h @@ -0,0 +1,55 @@ +#pragma once + +#include "solvers/nonlinear_cost.h" +#include "systems/trajectory_optimization/dircon/dircon.h" + +#include "drake/math/autodiff.h" +#include "drake/math/autodiff_gradient.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/solvers/decision_variable.h" +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/mathematical_program_result.h" + +namespace dairlib { + +namespace solvers { + +template +void AddPositiveWorkCost( + dairlib::systems::trajectory_optimization::Dircon& trajopt, + const drake::multibody::MultibodyPlant& plant, double W); + +template +class PositiveMechanicalWork : public NonlinearCost { + public: + PositiveMechanicalWork(int n_v, int n_u, const Eigen::MatrixXd& B, + double W, const std::string& description); + + private: + void EvaluateCost(const Eigen::Ref>& x, + drake::VectorX* y) const override; + double W_; // + const Eigen::MatrixXd B_t_; + int n_h_ = 2; + int n_v_; + int n_u_; +}; + +template +class ElectricalLoss : public NonlinearCost { + public: + ElectricalLoss(int n_v, int n_u, const Eigen::MatrixXd& B, + double W, const std::string& description); + + private: + void EvaluateCost(const Eigen::Ref>& x, + drake::VectorX* y) const override; + double W_; // + const Eigen::MatrixXd B_t_; + int n_h_ = 2; + int n_v_; + int n_u_; +}; + +} // namespace solvers +} // namespace dairlib diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h new file mode 100644 index 0000000000..8d3087f183 --- /dev/null +++ b/systems/controllers/osc/osc_gains.h @@ -0,0 +1,27 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct OSCGains { + // costs + double w_input; + double w_input_reg; + double w_accel; + double w_soft_constraint; + double impact_threshold; + double mu; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(w_input)); + a->Visit(DRAKE_NVP(w_input_reg)); + a->Visit(DRAKE_NVP(w_accel)); + a->Visit(DRAKE_NVP(w_soft_constraint)); + a->Visit(DRAKE_NVP(impact_threshold)); + a->Visit(DRAKE_NVP(mu)); + } +}; \ No newline at end of file diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index dc43e483ab..9e3e5ca424 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -90,8 +90,12 @@ void OscTrackingData::UpdateDesired( y_des_ = traj.value(t); if (traj.has_derivative()) { ydot_des_ = traj.EvalDerivative(t, 1); - yddot_des_ = traj.EvalDerivative(t, 1).bottomRows(n_ydot_); - // yddot_des_ = traj.EvalDerivative(t, 2); + if(traj.rows() == 2*n_ydot_){ + yddot_des_ = traj.EvalDerivative(t, 1).bottomRows(n_ydot_); + } + else{ + yddot_des_ = traj.EvalDerivative(t, 2); + } } // TODO (yangwill): Remove this edge case after EvalDerivative has been // implemented for ExponentialPlusPiecewisePolynomial diff --git a/systems/framework/impact_info_vector.cc b/systems/framework/impact_info_vector.cc new file mode 100644 index 0000000000..856d418c6a --- /dev/null +++ b/systems/framework/impact_info_vector.cc @@ -0,0 +1,6 @@ +#include "systems/framework/impact_info_vector.h" + +#include "drake/common/default_scalars.h" + +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( + class ::dairlib::systems::ImpactInfoVector) diff --git a/systems/framework/impact_info_vector.h b/systems/framework/impact_info_vector.h new file mode 100644 index 0000000000..951238fd5c --- /dev/null +++ b/systems/framework/impact_info_vector.h @@ -0,0 +1,94 @@ +#pragma once + +#include +#include + +#include "systems/framework/timestamped_vector.h" + +namespace dairlib { +namespace systems { + +using drake::VectorX; +using std::string; +using std::vector; + +/// OutputVector stores the robot output as a TimestampedVector +/// * positions +/// * velocities +/// * efforts +/// * imu accelerations +/// Can be later extended if more information is desired in here +template +class ImpactInfoVector : public TimestampedVector { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(ImpactInfoVector) + + ImpactInfoVector() = default; + + /// Initializes with the given @p size using the drake::dummy_value, which + /// is NaN when T = double. + explicit ImpactInfoVector(int num_contact, int num_holonomic, int space_dim) + : TimestampedVector(3 + num_contact + num_holonomic), + has_impulse_info_(num_contact != 0), + num_contact_impulses_(num_contact), + num_holonomic_impulses_(num_holonomic), + space_dim_(space_dim){} + + void SetCurrentContactMode(int contact_mode) { + this->get_mutable_data()(contact_mode_index_) = contact_mode; + } + + void SetAlpha(double alpha) { + this->get_mutable_data()(alpha_index_) = alpha; + } + + void SetImpulseVector(VectorX impulse) { + this->get_mutable_data().segment( + impulse_start_, num_contact_impulses_ + num_holonomic_impulses_) = + impulse; + } + + const T GetAlpha() const { + return this->GetAtIndex(alpha_index_); + } + + const T GetCurrentContactMode() const { + return this->GetAtIndex(contact_mode_index_); + } + + /// Returns a const impulse vector + const VectorX GetImpulseVector() const { + return this->get_data().segment( + impulse_start_, num_contact_impulses_ + num_holonomic_impulses_); + } + + const VectorX GetContactImpulseAtContactIndex(int contact_index) const { + return this->get_data().segment(impulse_start_ + contact_index * space_dim_, space_dim_); + } + + const T GetContactImpulseAtIndex(int index) const { + return this->GetAtIndex(impulse_start_ + index); + } + + void SetName(int index, string name) { impulse_names_[index] = name; } + + string GetName(int index) { return impulse_names_[index]; } + + protected: + virtual ImpactInfoVector* DoClone() const { + return new ImpactInfoVector(num_contact_impulses_, num_holonomic_impulses_, space_dim_); + } + + private: + bool has_impulse_info_; + const int num_contact_impulses_; + const int num_holonomic_impulses_; + const int space_dim_; + const int contact_mode_index_ = 0; + const int alpha_index_ = 1; + const int impulse_start_ = 2; + vector impulse_names_; +}; + +} // namespace systems +} // namespace dairlib From 9a7b1babf932ccae6123356d2e6d8706d7529e35 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Fri, 19 Nov 2021 12:01:57 -0500 Subject: [PATCH 017/758] add plot config file --- .../analysis/cassie_plotting_utils.py | 221 +----------------- .../pydairlib/analysis/log_plotter_cassie.py | 66 +++--- .../pydairlib/analysis/mbp_plotting_utils.py | 217 +++++++++++++++++ .../plot_configs/cassie_default_plot.yaml | 18 ++ .../plot_configs/cassie_plot_config.py | 25 ++ 5 files changed, 299 insertions(+), 248 deletions(-) create mode 100644 bindings/pydairlib/analysis/mbp_plotting_utils.py create mode 100644 bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml create mode 100644 bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index a02285b66e..a48571882d 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -5,13 +5,8 @@ # dairlib imports import dairlib -from pydairlib.cassie.cassie_utils import * -from pydairlib.common import FindResourceOrThrow -from pydairlib.common import plot_styler, plotting_utils -from pydairlib.multibody import makeNameToPositionsMap,\ - makeNameToVelocitiesMap, makeNameToActuatorsMap, \ - createStateNameVectorFromMap, createActuatorNameVectorFromMap -from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost +from pydairlib.cassie.cassie_utils import addCassieMultibody + # drake imports from pydrake.multibody.parsing import Parser @@ -33,6 +28,7 @@ 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output, 'OSC_DEBUG_RUNNING': dairlib.lcmt_osc_output} + def make_plant_and_context(floating_base=True, springs=True): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) @@ -45,214 +41,3 @@ def make_plant_and_context(floating_base=True, springs=True): plant.Finalize() return plant, plant.CreateDefaultContext() - - -def make_name_to_mbp_maps(plant): - return makeNameToPositionsMap(plant), \ - makeNameToVelocitiesMap(plant), \ - makeNameToActuatorsMap(plant) - - -def make_mbp_name_vectors(plant): - x_names = createStateNameVectorFromMap(plant) - u_names = createActuatorNameVectorFromMap(plant) - q_names = x_names[:plant.num_positions()] - v_names = x_names[plant.num_positions():] - return q_names, v_names, u_names - -def process_state_channel(state_data, plant): - t_x = [] - q = [] - u = [] - v = [] - - pos_map = makeNameToPositionsMap(plant) - vel_map = makeNameToVelocitiesMap(plant) - act_map = makeNameToActuatorsMap(plant) - - for msg in state_data: - q_temp = [[] for i in range(len(msg.position))] - v_temp = [[] for i in range(len(msg.velocity))] - u_temp = [[] for i in range(len(msg.effort))] - for i in range(len(q_temp)): - q_temp[pos_map[msg.position_names[i]]] = msg.position[i] - for i in range(len(v_temp)): - v_temp[vel_map[msg.velocity_names[i]]] = msg.velocity[i] - for i in range(len(u_temp)): - u_temp[act_map[msg.effort_names[i]]] = msg.effort[i] - q.append(q_temp) - v.append(v_temp) - u.append(u_temp) - t_x.append(msg.utime / 1e6) - - return {'t_x': np.array(t_x), - 'q': np.array(q), - 'v': np.array(v), - 'u': np.array(u)} - - -def process_effort_channel(data): - u = [] - t = [] - for msg in data: - t.append(msg.utime / 1e6) - u.append(msg.efforts) - - return {'t_u': np.array(t), 'u': np.array(u)} - - -def process_osc_channel(data): - t_osc = [] - input_cost = [] - accel_cost = [] - soft_constraint_cost = [] - qp_solve_time = [] - u_sol = [] - osc_output = [] - fsm = [] - osc_debug_tracking_datas = {} - - for msg in data: - t_osc.append(msg.utime / 1e6) - input_cost.append(msg.input_cost) - accel_cost.append(msg.acceleration_cost) - soft_constraint_cost.append(msg.soft_constraint_cost) - qp_solve_time.append(msg.qp_output.solve_time) - u_sol.append(msg.qp_output.u_sol) - osc_output.append(msg) - for tracking_data in msg.tracking_data: - if tracking_data.name not in osc_debug_tracking_datas: - osc_debug_tracking_datas[tracking_data.name] = \ - lcmt_osc_tracking_data_t() - osc_debug_tracking_datas[tracking_data.name].append( - tracking_data, msg.utime / 1e6) - - fsm.append(msg.fsm_state) - - tracking_cost_handler = osc_tracking_cost(osc_debug_tracking_datas.keys()) - for msg in data: - tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_cost) - tracking_cost = tracking_cost_handler.convertToNP() - - for name in osc_debug_tracking_datas: - osc_debug_tracking_datas[name] = \ - osc_debug_tracking_datas[name].convertToNP() - - return {'t_osc': np.array(t_osc), - 'input_cost': np.array(input_cost), - 'acceleration_cost': np.array(accel_cost), - 'soft_constraint_cost': np.array(soft_constraint_cost), - 'qp_solve_time': np.array(qp_solve_time), - 'osc_output': osc_output, - 'tracking_cost': tracking_cost, - 'osc_debug_tracking_datas': osc_debug_tracking_datas, - 'fsm': np.array(fsm)} - - -def load_default_channels(data, plant, state_channel, input_channel, - osc_debug_channel): - robot_output = process_state_channel(data[state_channel], plant) - robot_input = process_effort_channel(data[input_channel]) - osc_debug = process_osc_channel(data[osc_debug_channel]) - - return robot_output, robot_input, osc_debug - - -def load_state_channel(data, plant, state_channel): - return process_state_channel(data[state_channel], plant) - - -def plot_q_or_v_or_u( - robot_output, key, x_names, x_slice, time_slice, - ylabel=None, title=None): - ps = plot_styler.PlotStyler() - if ylabel is None: - ylabel = key - if title is None: - title = key - - plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel - time_slice, - [key], # key to plot - {key: x_slice}, # slice of key to plot - {key: x_names}, # legend entries - {'xlabel': 'Time', - 'ylabel': ylabel, - 'title': title}, ps) - return ps - - -def plot_floating_base_positions(robot_output, q_names, time_slice): - return plot_q_or_v_or_u(robot_output, 'q', q_names[:7], slice(7), - time_slice, ylabel='Position', - title='Floating Base Positions') - - -def plot_joint_positions(robot_output, q_names, time_slice, floating_base=True): - q_slice = slice(7, len(q_names)) if floating_base else slice(len(q_names)) - return plot_q_or_v_or_u(robot_output, 'q', q_names[q_slice], q_slice, - time_slice, ylabel='Joint Angle (rad)', - title='Joint Positions') - - -def plot_positions_by_name(robot_output, q_names, time_slice, pos_map): - q_slice = [pos_map[name] for name in q_names] - return plot_q_or_v_or_u(robot_output, 'q', q_names, q_slice, time_slice, - ylabel='Position', title='Select Positions') - - -def plot_floating_base_velocities(robot_output, v_names, time_slice): - return plot_q_or_v_or_u(robot_output, 'v', v_names[:6], slice(6), - time_slice, ylabel='Velocity', - title='Floating Base Velocities') - - -def plot_joint_velocities(robot_output, v_names, - time_slice, floating_base=True): - q_slice = slice(6, len(v_names)) if floating_base else slice(len(v_names)) - return plot_q_or_v_or_u(robot_output, 'v', v_names[q_slice], q_slice, - time_slice, ylabel='Joint Vel (rad/s)', - title='Joint Velocities') - - -def plot_velocities_by_name(robot_output, v_names, time_slice, vel_map): - v_slice = [vel_map[name] for name in v_names] - return plot_q_or_v_or_u(robot_output, 'v', v_names, v_slice, time_slice, - ylabel='Velocity', title='Select Velocities') - - -def plot_measured_efforts(robot_output, u_names, time_slice): - return plot_q_or_v_or_u(robot_output, 'u', u_names, slice(len(u_names)), - time_slice, ylabel='Efforts (Nm)', - title='Joint Efforts') - - -def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): - u_slice = [u_map[name] for name in u_names] - return plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, - time_slice, ylabel='Efforts (Nm)', - title='Select Joint Efforts') - - -def plot_tracking_costs(osc_debug, time_slice): - ps = plot_styler.PlotStyler() - data_dict = osc_debug['tracking_cost'] - data_dict['t_osc'] = osc_debug['t_osc'] - import pdb; pdb.set_trace() - plotting_utils.make_plot( - data_dict, - 't_osc', - time_slice, - osc_debug['tracking_cost'].keys(), - {}, - {key: [key] for key in osc_debug['tracking_cost'].keys()}, - {'xlabel': 'Time', - 'ylabel': 'Cost', - 'title': 'tracking_costs'}, ps) - return ps - - -def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): - ps.plot(fsm_time, scale*fsm_signal) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 28d896f85a..9cebf1c532 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -6,34 +6,38 @@ import dairlib from process_lcm_log import get_log_data +from cassie_plot_config import CassiePlotConfig import cassie_plotting_utils as cassie_plots +import mbp_plotting_utils as mbp_plots def main(): - # Global settings for plotting - use_floating_base = True - use_springs = True + config_file = \ + 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' + plot_config = CassiePlotConfig(config_file) + + use_floating_base = plot_config.use_floating_base + use_springs = plot_config.use_springs - # TODO: get these channels automatically from reading the log - channel_x = 'CASSIE_STATE_SIMULATION' - channel_u = 'CASSIE_INPUT' - channel_osc = 'OSC_DEBUG_WALKING' + channel_x = plot_config.channel_x + channel_u = plot_config.channel_u + channel_osc = plot_config.channel_osc ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( floating_base=use_floating_base, springs=use_springs) - pos_map, vel_map, act_map = cassie_plots.make_name_to_mbp_maps(plant) - pos_names, vel_names, act_names = cassie_plots.make_mbp_name_vectors(plant) + pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) + pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") robot_output, robot_input, osc_debug = \ - get_log_data(log, # log - cassie_plots.cassie_default_channels, # lcm channels - cassie_plots.load_default_channels, # processing callback - plant, channel_x, channel_u, channel_osc) # processing callback arguments + get_log_data(log, # log + cassie_plots.cassie_default_channels, # lcm channels + mbp_plots.load_default_channels, # processing callback + plant, channel_x, channel_u, channel_osc) # processing callback arguments # Define x time slice t_x_slice = slice(robot_output['t_x'].size) @@ -41,37 +45,39 @@ def main(): ''' Plot Positions ''' # Plot floating base positions if applicable - if use_floating_base: - cassie_plots.plot_floating_base_positions( - robot_output, pos_names, t_x_slice) + if use_floating_base and plot_config.plot_floating_base_positions: + mbp_plots.plot_floating_base_positions( + robot_output, pos_names, 7, t_x_slice) # Plot joint positions - cassie_plots.plot_joint_positions(robot_output, pos_names, t_x_slice, - floating_base=use_floating_base) + mbp_plots.plot_joint_positions(robot_output, pos_names, + 7 if use_floating_base else 0, t_x_slice) # Plot specific positions - cassie_plots.plot_positions_by_name(robot_output, - ['knee_left', 'knee_right'], - t_x_slice, pos_map) + mbp_plots.plot_positions_by_name(robot_output, + ['knee_left', 'knee_right'], + t_x_slice, pos_map) ''' Plot Velocities ''' # Plot floating base velocities if applicable - if use_floating_base: - cassie_plots.plot_floating_base_velocities( - robot_output, vel_names, t_x_slice) + if use_floating_base and plot_config.plot_floating_base_velocities: + mbp_plots.plot_floating_base_velocities( + robot_output, vel_names, 6, t_x_slice) # Plot all joint velocities - cassie_plots.plot_joint_velocities(robot_output, vel_names, t_x_slice, - floating_base=use_floating_base) + mbp_plots.plot_joint_velocities(robot_output, vel_names, + 6 if use_floating_base else 0, + t_x_slice) # Plot specific velocities - cassie_plots.plot_velocities_by_name(robot_output, ['base_vz'], t_x_slice, vel_map) + mbp_plots.plot_velocities_by_name(robot_output, ['base_vz'], + t_x_slice, vel_map) ''' Plot Efforts ''' - cassie_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) - cassie_plots.plot_measured_efforts_by_name(robot_output, + mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + mbp_plots.plot_measured_efforts_by_name(robot_output, ['knee_left_motor'], t_x_slice, act_map) - cassie_plots.plot_tracking_costs(osc_debug, t_osc_slice) + mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py new file mode 100644 index 0000000000..711c04450b --- /dev/null +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -0,0 +1,217 @@ +import numpy as np +import matplotlib.pyplot as plt + +from pydairlib.common import plot_styler, plotting_utils +from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost +from pydairlib.multibody import makeNameToPositionsMap, \ + makeNameToVelocitiesMap, makeNameToActuatorsMap, \ + createStateNameVectorFromMap, createActuatorNameVectorFromMap + + +def make_name_to_mbp_maps(plant): + return makeNameToPositionsMap(plant), \ + makeNameToVelocitiesMap(plant), \ + makeNameToActuatorsMap(plant) + + +def make_mbp_name_vectors(plant): + x_names = createStateNameVectorFromMap(plant) + u_names = createActuatorNameVectorFromMap(plant) + q_names = x_names[:plant.num_positions()] + v_names = x_names[plant.num_positions():] + return q_names, v_names, u_names + + +def plot_q_or_v_or_u( + robot_output, key, x_names, x_slice, time_slice, + ylabel=None, title=None): + ps = plot_styler.PlotStyler() + if ylabel is None: + ylabel = key + if title is None: + title = key + + plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + [key], # key to plot + {key: x_slice}, # slice of key to plot + {key: x_names}, # legend entries + {'xlabel': 'Time', + 'ylabel': ylabel, + 'title': title}, ps) + return ps + + +def process_state_channel(state_data, plant): + t_x = [] + q = [] + u = [] + v = [] + + pos_map = makeNameToPositionsMap(plant) + vel_map = makeNameToVelocitiesMap(plant) + act_map = makeNameToActuatorsMap(plant) + + for msg in state_data: + q_temp = [[] for i in range(len(msg.position))] + v_temp = [[] for i in range(len(msg.velocity))] + u_temp = [[] for i in range(len(msg.effort))] + for i in range(len(q_temp)): + q_temp[pos_map[msg.position_names[i]]] = msg.position[i] + for i in range(len(v_temp)): + v_temp[vel_map[msg.velocity_names[i]]] = msg.velocity[i] + for i in range(len(u_temp)): + u_temp[act_map[msg.effort_names[i]]] = msg.effort[i] + q.append(q_temp) + v.append(v_temp) + u.append(u_temp) + t_x.append(msg.utime / 1e6) + + return {'t_x': np.array(t_x), + 'q': np.array(q), + 'v': np.array(v), + 'u': np.array(u)} + + +def process_effort_channel(data): + u = [] + t = [] + for msg in data: + t.append(msg.utime / 1e6) + u.append(msg.efforts) + + return {'t_u': np.array(t), 'u': np.array(u)} + + +def process_osc_channel(data): + t_osc = [] + input_cost = [] + accel_cost = [] + soft_constraint_cost = [] + qp_solve_time = [] + u_sol = [] + osc_output = [] + fsm = [] + osc_debug_tracking_datas = {} + + for msg in data: + t_osc.append(msg.utime / 1e6) + input_cost.append(msg.input_cost) + accel_cost.append(msg.acceleration_cost) + soft_constraint_cost.append(msg.soft_constraint_cost) + qp_solve_time.append(msg.qp_output.solve_time) + u_sol.append(msg.qp_output.u_sol) + osc_output.append(msg) + for tracking_data in msg.tracking_data: + if tracking_data.name not in osc_debug_tracking_datas: + osc_debug_tracking_datas[tracking_data.name] = \ + lcmt_osc_tracking_data_t() + osc_debug_tracking_datas[tracking_data.name].append( + tracking_data, msg.utime / 1e6) + + fsm.append(msg.fsm_state) + + tracking_cost_handler = osc_tracking_cost(osc_debug_tracking_datas.keys()) + for msg in data: + tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_cost) + tracking_cost = tracking_cost_handler.convertToNP() + + for name in osc_debug_tracking_datas: + osc_debug_tracking_datas[name] = \ + osc_debug_tracking_datas[name].convertToNP() + + return {'t_osc': np.array(t_osc), + 'input_cost': np.array(input_cost), + 'acceleration_cost': np.array(accel_cost), + 'soft_constraint_cost': np.array(soft_constraint_cost), + 'qp_solve_time': np.array(qp_solve_time), + 'osc_output': osc_output, + 'tracking_cost': tracking_cost, + 'osc_debug_tracking_datas': osc_debug_tracking_datas, + 'fsm': np.array(fsm)} + + +def load_default_channels(data, plant, state_channel, input_channel, + osc_debug_channel): + robot_output = process_state_channel(data[state_channel], plant) + robot_input = process_effort_channel(data[input_channel]) + osc_debug = process_osc_channel(data[osc_debug_channel]) + + return robot_output, robot_input, osc_debug + + +def load_state_channel(data, plant, state_channel): + return process_state_channel(data[state_channel], plant) + + +def plot_floating_base_positions(robot_output, q_names, fb_dim, time_slice): + return plot_q_or_v_or_u(robot_output, 'q', q_names[:fb_dim], slice(fb_dim), + time_slice, ylabel='Position', + title='Floating Base Positions') + + +def plot_joint_positions(robot_output, q_names, fb_dim, time_slice): + q_slice = slice(fb_dim, len(q_names)) + return plot_q_or_v_or_u(robot_output, 'q', q_names[q_slice], q_slice, + time_slice, ylabel='Joint Angle (rad)', + title='Joint Positions') + + +def plot_positions_by_name(robot_output, q_names, time_slice, pos_map): + q_slice = [pos_map[name] for name in q_names] + return plot_q_or_v_or_u(robot_output, 'q', q_names, q_slice, time_slice, + ylabel='Position', title='Select Positions') + + +def plot_floating_base_velocities(robot_output, v_names, fb_dim, time_slice): + return plot_q_or_v_or_u(robot_output, 'v', v_names[:fb_dim], slice(fb_dim), + time_slice, ylabel='Velocity', + title='Floating Base Velocities') + + +def plot_joint_velocities(robot_output, v_names, fb_dim, time_slice): + q_slice = slice(fb_dim, len(v_names)) + return plot_q_or_v_or_u(robot_output, 'v', v_names[q_slice], q_slice, + time_slice, ylabel='Joint Vel (rad/s)', + title='Joint Velocities') + + +def plot_velocities_by_name(robot_output, v_names, time_slice, vel_map): + v_slice = [vel_map[name] for name in v_names] + return plot_q_or_v_or_u(robot_output, 'v', v_names, v_slice, time_slice, + ylabel='Velocity', title='Select Velocities') + + +def plot_measured_efforts(robot_output, u_names, time_slice): + return plot_q_or_v_or_u(robot_output, 'u', u_names, slice(len(u_names)), + time_slice, ylabel='Efforts (Nm)', + title='Joint Efforts') + + +def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): + u_slice = [u_map[name] for name in u_names] + return plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, time_slice, + ylabel='Efforts (Nm)', title='Select Joint Efforts') + + +def plot_tracking_costs(osc_debug, time_slice): + ps = plot_styler.PlotStyler() + data_dict = osc_debug['tracking_cost'] + data_dict['t_osc'] = osc_debug['t_osc'] + plotting_utils.make_plot( + data_dict, + 't_osc', + time_slice, + osc_debug['tracking_cost'].keys(), + {}, + {key: [key] for key in osc_debug['tracking_cost'].keys()}, + {'xlabel': 'Time', + 'ylabel': 'Cost', + 'title': 'tracking_costs'}, ps) + return ps + + +def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): + ps.plot(fsm_time, scale*fsm_signal) \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml new file mode 100644 index 0000000000..ce4a62c89e --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -0,0 +1,18 @@ +# LCM channels to read data from +channel_x: "CASSIE_STATE_SIMULATION" +channel_u: "CASSIE_INPUT" +channel_osc: "OSC_DEBUG_STANDING" + +# Plant properties +use_springs: true +use_floating_base: true + +# Desired plots +plot_floating_base_positions: true +plot_floating_base_velocities: true +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +special_positions_to_plot: ["knee_left"] +special_velocities_to_plot: ["base_vz"] +special_efots_to_plot: ["knee_left_motor"] \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py b/bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py new file mode 100644 index 0000000000..840bb96a8b --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py @@ -0,0 +1,25 @@ +import io +from yaml import load, dump + +try: + from yaml import CLoader as Loader, CDumper as Dumper +except ImportError: + from yaml import Loader, Dumper + + +class CassiePlotConfig(): + def __init__(self, filename): + data = load(io.open(filename, 'r'), Loader=Loader) + self.channel_x = data['channel_x'] + self.channel_u = data['channel_u'] + self.channel_osc = data['channel_osc'] + self.plot_joint_positions = data['plot_joint_positions'] + self.plot_joint_velocities = data['plot_joint_velocities'] + self.plot_measured_efforts = data['plot_measured_efforts'] + if data['pos_names']: + self.pos_names = data['pos_names'] + if data['vel_names']: + self.vel_names = data['vel_names'] + if data['act_names']: + self.act_names = data['act_names'] + self.act_names = data['act_names'] \ No newline at end of file From a578952651a1086e2684565748d3b036efb278ac Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Nov 2021 12:18:25 -0500 Subject: [PATCH 018/758] merge changes from master --- .../Cassie/osc_run/osc_running_gains.yaml | 10 +++--- examples/Cassie/run_osc_running_controller.cc | 31 ++++++++++--------- systems/controllers/osc/osc_tracking_data.cc | 7 ++--- 3 files changed, 25 insertions(+), 23 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 06a0eb9692..7dee48de93 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,5 +1,5 @@ w_input: 0.0000000000 -w_accel: 0.00001 +w_accel: 0.000001 #w_soft_constraint: 1000000 w_soft_constraint: 0.00000000 w_input_reg: 0.0001 @@ -44,7 +44,7 @@ PelvisKp: PelvisKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 5] + 0, 0, 5] SwingFootW: [1, 0, 0, 0, 1, 0, @@ -62,6 +62,6 @@ FootstepKp: 0, 0.0, 0, 0] FootstepKd: - [ 0.15, 0, - 0, 0.03, - 0, 0] + [ 0.15, 0, + 0, 0.03, + 0, 0] diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1953380c8e..b3c80db11e 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -47,6 +47,7 @@ using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; +using cassie::osc::SwingToeTrajGenerator; using drake::geometry::SceneGraph; using drake::multibody::Frame; using drake::multibody::MultibodyPlant; @@ -62,12 +63,11 @@ using examples::osc::PelvisTransTrajGenerator; using examples::osc_jump::BasicTrajectoryPassthrough; using examples::osc_run::FootTrajGenerator; using multibody::FixedJointEvaluator; -using cassie::osc::SwingToeTrajGenerator; +using multibody::WorldYawViewFrame; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -using systems::controllers::WorldYawOscViewFrame; namespace examples { @@ -164,7 +164,8 @@ int DoMain(int argc, char* argv[]) { air_phase, left_stance_state}; std::cout << "left support duration: " << left_support_duration << std::endl; std::cout << "flight duration: " << air_phase_duration << std::endl; - std::cout << "right support duration: " << right_support_duration << std::endl; + std::cout << "right support duration: " << right_support_duration + << std::endl; vector state_durations = { left_support_duration / 2, air_phase_duration, right_support_duration, air_phase_duration, left_support_duration / 2}; @@ -391,7 +392,7 @@ int DoMain(int argc, char* argv[]) { left_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_left"); right_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_right"); - WorldYawOscViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); + WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); RelativeTranslationTrackingData left_foot_rel_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, @@ -469,10 +470,12 @@ int DoMain(int argc, char* argv[]) { hip_pitch_right_tracking_data.DisableFeedforwardAccel({0}); hip_pitch_left_tracking_data.SetImpactInvariantProjection(true); hip_pitch_right_tracking_data.SetImpactInvariantProjection(true); - osc->AddConstTrackingData(&hip_pitch_left_tracking_data, 0.6 * VectorXd::Ones(1)); - osc->AddConstTrackingData(&hip_pitch_right_tracking_data, 0.6 * VectorXd::Ones(1)); -// osc->AddTrackingData(&hip_pitch_left_tracking_data); -// osc->AddTrackingData(&hip_pitch_right_tracking_data); + // osc->AddConstTrackingData(&hip_pitch_left_tracking_data, + // 0.6 * VectorXd::Ones(1)); + // osc->AddConstTrackingData(&hip_pitch_right_tracking_data, + // 0.6 * VectorXd::Ones(1)); + osc->AddTrackingData(&hip_pitch_left_tracking_data); + osc->AddTrackingData(&hip_pitch_right_tracking_data); // Stance hip roll trajectory auto hip_roll_left_traj = dircon_trajectory.ReconstructJointTrajectory( @@ -561,8 +564,8 @@ int DoMain(int argc, char* argv[]) { osc_gains.W_hip_yaw, plant, plant); hip_yaw_left_traj.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); hip_yaw_right_traj.AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); -// hip_yaw_left_traj.SetImpactInvariantProjection(true); -// hip_yaw_right_traj.SetImpactInvariantProjection(true); + // hip_yaw_left_traj.SetImpactInvariantProjection(true); + // hip_yaw_right_traj.SetImpactInvariantProjection(true); osc->AddConstTrackingData(&hip_yaw_left_traj, VectorXd::Zero(1)); osc->AddConstTrackingData(&hip_yaw_right_traj, VectorXd::Zero(1)); @@ -606,10 +609,10 @@ int DoMain(int argc, char* argv[]) { left_toe_angle_traj_gen->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), right_toe_angle_traj_gen->get_state_input_port()); -// builder.Connect(hip_pitch_left_traj_generator->get_output_port(), -// osc->get_tracking_data_input_port("hip_pitch_left_traj")); -// builder.Connect(hip_pitch_right_traj_generator->get_output_port(), -// osc->get_tracking_data_input_port("hip_pitch_right_traj")); + builder.Connect(hip_pitch_left_traj_generator->get_output_port(), + osc->get_tracking_data_input_port("hip_pitch_left_traj")); + builder.Connect(hip_pitch_right_traj_generator->get_output_port(), + osc->get_tracking_data_input_port("hip_pitch_right_traj")); builder.Connect(hip_roll_left_traj_generator->get_output_port(), osc->get_tracking_data_input_port("hip_roll_left_traj")); builder.Connect(hip_roll_right_traj_generator->get_output_port(), diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index 9e3e5ca424..70d82e2e4a 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -90,11 +90,10 @@ void OscTrackingData::UpdateDesired( y_des_ = traj.value(t); if (traj.has_derivative()) { ydot_des_ = traj.EvalDerivative(t, 1); - if(traj.rows() == 2*n_ydot_){ + if (traj.rows() == 2 * n_ydot_) { yddot_des_ = traj.EvalDerivative(t, 1).bottomRows(n_ydot_); - } - else{ - yddot_des_ = traj.EvalDerivative(t, 2); + } else { + yddot_des_ = traj.EvalDerivative(t, 2); } } // TODO (yangwill): Remove this edge case after EvalDerivative has been From 75b5d4434e9456f4f25094feb5c987c9470fb7b2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Nov 2021 12:50:17 -0500 Subject: [PATCH 019/758] need to debug box jumping controller --- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 4 ++-- examples/Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/impact_invariant_control/platform.urdf | 8 ++++---- 3 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 58fded635c..1695d0e501 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -32,8 +32,8 @@ FlightFootW: 0, 0, 1] CoMKp: [10, 0, 0, - 0, 50, 0, - 0, 0, 50] + 0, 50, 0, + 0, 0, 50] CoMKd: [ 5, 0, 0, 0, 5, 0, diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 7dee48de93..8ec10c1176 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -63,5 +63,5 @@ FootstepKp: 0, 0] FootstepKd: [ 0.15, 0, - 0, 0.03, + 0, 0.04, 0, 0] diff --git a/examples/impact_invariant_control/platform.urdf b/examples/impact_invariant_control/platform.urdf index 9930a690af..724b2fc5ee 100644 --- a/examples/impact_invariant_control/platform.urdf +++ b/examples/impact_invariant_control/platform.urdf @@ -5,18 +5,18 @@ - + - + - + - + From c723ce66fce1f1dc267ec20b72fe54e6146b67f2 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Fri, 19 Nov 2021 13:45:10 -0500 Subject: [PATCH 020/758] further yaml options - need to implement plots for osc costs and tracking datas --- bindings/pydairlib/analysis/BUILD.bazel | 24 ++++++++++++-- .../pydairlib/analysis/cassie_plot_config.py | 32 ++++++++++++++++++ .../analysis/cassie_plotting_utils.py | 3 -- .../pydairlib/analysis/log_plotter_cassie.py | 33 +++++++++++-------- .../pydairlib/analysis/mbp_plotting_utils.py | 8 +++++ .../plot_configs/cassie_default_plot.yaml | 17 +++++++--- .../plot_configs/cassie_plot_config.py | 25 -------------- 7 files changed, 92 insertions(+), 50 deletions(-) create mode 100644 bindings/pydairlib/analysis/cassie_plot_config.py delete mode 100644 bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 796da9a030..205f172c49 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -23,6 +23,26 @@ py_library( deps = [], ) +py_library( + name = "cassie_plot_config", + srcs = ["cassie_plot_config.py"], + deps = [], +) + +py_library( + name = "mbp_plotting_utils", + srcs = ["mbp_plotting_utils.py"], + data = ["@lcm//:lcm-python"], + deps = [ + ":osc_debug_py", + "//bindings/pydairlib/common:plot_styler", + "//bindings/pydairlib/common:plotting_utils", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + ], +) + py_library( name = "cassie_plotting_utils", srcs = ["cassie_plotting_utils.py"], @@ -31,10 +51,7 @@ py_library( "@lcm//:lcm-python", ], deps = [ - ":osc_debug_py", "//bindings/pydairlib/cassie:cassie_utils", - "//bindings/pydairlib/common", - "//bindings/pydairlib/common:plot_styler", "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", @@ -50,6 +67,7 @@ py_binary( "@lcm//:lcm-python", ], deps = [ + ":cassie_plot_config", "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", "//bindings/pydairlib/common:plot_styler", diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py new file mode 100644 index 0000000000..c90f5731f1 --- /dev/null +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -0,0 +1,32 @@ +import io +from yaml import load, dump + +try: + from yaml import CLoader as Loader, CDumper as Dumper +except ImportError: + from yaml import Loader, Dumper + + +class CassiePlotConfig(): + def __init__(self, filename): + data = load(io.open(filename, 'r'), Loader=Loader) + self.channel_x = data['channel_x'] + self.channel_u = data['channel_u'] + self.channel_osc = data['channel_osc'] + self.use_floating_base = data['use_floating_base'] + self.use_springs = data['use_springs'] + self.plot_floating_base_positions = data['plot_floating_base_positions'] + self.plot_floating_base_velocities = \ + data['plot_floating_base_velocities'] + self.plot_joint_positions = data['plot_joint_positions'] + self.plot_joint_velocities = data['plot_joint_velocities'] + self.plot_measured_efforts = data['plot_measured_efforts'] + self.pos_names = [] + self.vel_names = [] + self.act_names = [] + if data['special_positions_to_plot']: + self.pos_names = data['special_positions_to_plot'] + if data['special_velocities_to_plot']: + self.vel_names = data['special_velocities_to_plot'] + if data['special_efforts_to_plot']: + self.act_names = data['special_efforts_to_plot'] \ No newline at end of file diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index a48571882d..a30e310caa 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -7,11 +7,8 @@ import dairlib from pydairlib.cassie.cassie_utils import addCassieMultibody - # drake imports -from pydrake.multibody.parsing import Parser from pydrake.multibody.plant import AddMultibodyPlantSceneGraph -from pydrake.multibody.tree import JacobianWrtVariable from pydrake.systems.framework import DiagramBuilder cassie_urdf = "examples/Cassie/urdf/cassie_v2.urdf" diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 9cebf1c532..a472107be2 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -50,12 +50,13 @@ def main(): robot_output, pos_names, 7, t_x_slice) # Plot joint positions - mbp_plots.plot_joint_positions(robot_output, pos_names, - 7 if use_floating_base else 0, t_x_slice) + if plot_config.plot_joint_positions: + mbp_plots.plot_joint_positions(robot_output, pos_names, + 7 if use_floating_base else 0, t_x_slice) # Plot specific positions - mbp_plots.plot_positions_by_name(robot_output, - ['knee_left', 'knee_right'], - t_x_slice, pos_map) + if plot_config.pos_names: + mbp_plots.plot_positions_by_name(robot_output, plot_config.pos_names, + t_x_slice, pos_map) ''' Plot Velocities ''' # Plot floating base velocities if applicable @@ -64,18 +65,22 @@ def main(): robot_output, vel_names, 6, t_x_slice) # Plot all joint velocities - mbp_plots.plot_joint_velocities(robot_output, vel_names, - 6 if use_floating_base else 0, - t_x_slice) + if plot_config.plot_joint_positions: + mbp_plots.plot_joint_velocities(robot_output, vel_names, + 6 if use_floating_base else 0, + t_x_slice) # Plot specific velocities - mbp_plots.plot_velocities_by_name(robot_output, ['base_vz'], - t_x_slice, vel_map) + if plot_config.vel_names: + mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, + t_x_slice, vel_map) ''' Plot Efforts ''' - mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) - mbp_plots.plot_measured_efforts_by_name(robot_output, - ['knee_left_motor'], - t_x_slice, act_map) + if plot_config.plot_measured_efforts: + mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + if plot_config.act_names: + mbp_plots.plot_measured_efforts_by_name(robot_output, + plot_config.act_names, + t_x_slice, act_map) mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 711c04450b..34b7b6d394 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -146,6 +146,14 @@ def load_state_channel(data, plant, state_channel): return process_state_channel(data[state_channel], plant) +def load_input_channel(data, input_channel): + return process_effort_channel(data[input_channel]) + + +def load_osc_channel(data, osc_debug_channel): + return process_osc_channel(data[osc_debug_channel]) + + def plot_floating_base_positions(robot_output, q_names, fb_dim, time_slice): return plot_q_or_v_or_u(robot_output, 'q', q_names[:fb_dim], slice(fb_dim), time_slice, ylabel='Position', diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index ce4a62c89e..0c7aeb6d57 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -1,18 +1,25 @@ # LCM channels to read data from channel_x: "CASSIE_STATE_SIMULATION" channel_u: "CASSIE_INPUT" -channel_osc: "OSC_DEBUG_STANDING" +channel_osc: "OSC_DEBUG_WALKING" # Plant properties use_springs: true use_floating_base: true -# Desired plots -plot_floating_base_positions: true -plot_floating_base_velocities: true +# Desired RobotOutput plots +plot_floating_base_positions: false +plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: false special_positions_to_plot: ["knee_left"] special_velocities_to_plot: ["base_vz"] -special_efots_to_plot: ["knee_left_motor"] \ No newline at end of file +special_efforts_to_plot: ["knee_left_motor"] + +# Desired osc plots +plot_qp_costs: true +plot_tracking_costs: true +tracking_datas_to_plot: + com_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py b/bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py deleted file mode 100644 index 840bb96a8b..0000000000 --- a/bindings/pydairlib/analysis/plot_configs/cassie_plot_config.py +++ /dev/null @@ -1,25 +0,0 @@ -import io -from yaml import load, dump - -try: - from yaml import CLoader as Loader, CDumper as Dumper -except ImportError: - from yaml import Loader, Dumper - - -class CassiePlotConfig(): - def __init__(self, filename): - data = load(io.open(filename, 'r'), Loader=Loader) - self.channel_x = data['channel_x'] - self.channel_u = data['channel_u'] - self.channel_osc = data['channel_osc'] - self.plot_joint_positions = data['plot_joint_positions'] - self.plot_joint_velocities = data['plot_joint_velocities'] - self.plot_measured_efforts = data['plot_measured_efforts'] - if data['pos_names']: - self.pos_names = data['pos_names'] - if data['vel_names']: - self.vel_names = data['vel_names'] - if data['act_names']: - self.act_names = data['act_names'] - self.act_names = data['act_names'] \ No newline at end of file From f82842ddb78150f33fb076db1cfed68ab1cb59a2 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Fri, 19 Nov 2021 14:48:06 -0500 Subject: [PATCH 021/758] added capability to plot osc tracking data --- .../pydairlib/analysis/cassie_plot_config.py | 7 ++- .../pydairlib/analysis/log_plotter_cassie.py | 13 +++- .../pydairlib/analysis/mbp_plotting_utils.py | 62 ++++++++++++++++++- .../plot_configs/cassie_default_plot.yaml | 12 ++-- 4 files changed, 82 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index c90f5731f1..d1ad3a99f7 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -15,6 +15,7 @@ def __init__(self, filename): self.channel_osc = data['channel_osc'] self.use_floating_base = data['use_floating_base'] self.use_springs = data['use_springs'] + self.plot_floating_base_positions = data['plot_floating_base_positions'] self.plot_floating_base_velocities = \ data['plot_floating_base_velocities'] @@ -29,4 +30,8 @@ def __init__(self, filename): if data['special_velocities_to_plot']: self.vel_names = data['special_velocities_to_plot'] if data['special_efforts_to_plot']: - self.act_names = data['special_efforts_to_plot'] \ No newline at end of file + self.act_names = data['special_efforts_to_plot'] + + self.plot_qp_costs = data['plot_qp_costs'] + self.plot_tracking_costs = data['plot_tracking_costs'] + self.tracking_datas_to_plot = data['tracking_datas_to_plot'] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index a472107be2..89972f7415 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,7 +12,6 @@ def main(): - # Global settings for plotting config_file = \ 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' plot_config = CassiePlotConfig(config_file) @@ -82,7 +81,17 @@ def main(): plot_config.act_names, t_x_slice, act_map) - mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + if plot_config.plot_qp_costs: + mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) + if plot_config.plot_tracking_costs: + mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + + for traj_name, config in plot_config.tracking_datas_to_plot.items(): + for deriv in config['derivs']: + for dim in config['dims']: + mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, + deriv, t_osc_slice) + plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 34b7b6d394..08f9a46d03 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -119,8 +119,7 @@ def process_osc_channel(data): tracking_cost = tracking_cost_handler.convertToNP() for name in osc_debug_tracking_datas: - osc_debug_tracking_datas[name] = \ - osc_debug_tracking_datas[name].convertToNP() + osc_debug_tracking_datas[name].convertToNP() return {'t_osc': np.array(t_osc), 'input_cost': np.array(input_cost), @@ -206,8 +205,10 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): def plot_tracking_costs(osc_debug, time_slice): ps = plot_styler.PlotStyler() - data_dict = osc_debug['tracking_cost'] + data_dict = \ + {key: val for key, val in osc_debug['tracking_cost'].items()} data_dict['t_osc'] = osc_debug['t_osc'] + plotting_utils.make_plot( data_dict, 't_osc', @@ -221,5 +222,60 @@ def plot_tracking_costs(osc_debug, time_slice): return ps +def plot_general_osc_tracking_data(traj_name, deriv, dim, data, + t_osc, time_slice): + ps = plot_styler.PlotStyler() + data_dict = {key: val for key, val in data.items()} + data_dict['t_osc'] = t_osc + plotting_utils.make_plot( + data_dict, + 't_osc', + time_slice, + data.keys(), + {}, + {key: [key] for key in data.keys()}, + {'xlabel': 'Time', + 'ylabel': '', + 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) + return ps + + +def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): + tracking_data = osc_debug['osc_debug_tracking_datas'][traj] + data = {} + if deriv == 'pos': + data['y_des'] = tracking_data.y_des[:, dim] + data['y'] = tracking_data.y[:, dim] + data['error_y'] = tracking_data.error_y[:, dim] + elif deriv == 'vel': + data['ydot_des'] = tracking_data.ydot_des[:, dim] + data['ydot'] = tracking_data.ydot[:, dim] + data['error_ydot'] = tracking_data.error_ydot[:, dim] + elif deriv == 'accel': + data['yddot_des'] = tracking_data.yddot_des[:, dim] + data['yddot_command'] = tracking_data.yddot_command[:, dim] + data['yddot_command_sol'] = tracking_data.yddot_command_sol[:, dim] + + return plot_general_osc_tracking_data(traj, deriv, dim, data, + osc_debug['t_osc'], time_slice) + + +def plot_qp_costs(osc_debug, time_slice): + cost_keys = ['input_cost', 'acceleration_cost', + 'soft_constraint_cost'] + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + cost_keys, + {}, + {key: [key] for key in cost_keys}, + {'xlabel': 'Time', + 'ylabel': 'Cost', + 'title': 'OSC QP Costs'}, ps) + return ps + + def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): ps.plot(fsm_time, scale*fsm_signal) \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index 0c7aeb6d57..f0a14e02ef 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -13,13 +13,13 @@ plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: false -special_positions_to_plot: ["knee_left"] -special_velocities_to_plot: ["base_vz"] -special_efforts_to_plot: ["knee_left_motor"] +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] # Desired osc plots -plot_qp_costs: true -plot_tracking_costs: true +plot_qp_costs: false +plot_tracking_costs: false tracking_datas_to_plot: com_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} - swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} +# swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} From 663a838671b4020677175b088d6ae330a2b222b5 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Fri, 19 Nov 2021 15:03:27 -0500 Subject: [PATCH 022/758] move plot_q_v_or_u next to other plotting functions in mbp_plotting_utils --- .../pydairlib/analysis/mbp_plotting_utils.py | 44 +++++++++---------- 1 file changed, 22 insertions(+), 22 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 08f9a46d03..766aefa24b 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -22,28 +22,6 @@ def make_mbp_name_vectors(plant): return q_names, v_names, u_names -def plot_q_or_v_or_u( - robot_output, key, x_names, x_slice, time_slice, - ylabel=None, title=None): - ps = plot_styler.PlotStyler() - if ylabel is None: - ylabel = key - if title is None: - title = key - - plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel - time_slice, - [key], # key to plot - {key: x_slice}, # slice of key to plot - {key: x_names}, # legend entries - {'xlabel': 'Time', - 'ylabel': ylabel, - 'title': title}, ps) - return ps - - def process_state_channel(state_data, plant): t_x = [] q = [] @@ -153,6 +131,28 @@ def load_osc_channel(data, osc_debug_channel): return process_osc_channel(data[osc_debug_channel]) +def plot_q_or_v_or_u( + robot_output, key, x_names, x_slice, time_slice, + ylabel=None, title=None): + ps = plot_styler.PlotStyler() + if ylabel is None: + ylabel = key + if title is None: + title = key + + plotting_utils.make_plot( + robot_output, # data dict + 't_x', # time channel + time_slice, + [key], # key to plot + {key: x_slice}, # slice of key to plot + {key: x_names}, # legend entries + {'xlabel': 'Time', + 'ylabel': ylabel, + 'title': title}, ps) + return ps + + def plot_floating_base_positions(robot_output, q_names, fb_dim, time_slice): return plot_q_or_v_or_u(robot_output, 'q', q_names[:fb_dim], slice(fb_dim), time_slice, ylabel='Position', From 18b1e408ab4ac551483fda2e4e1c1493b9210ee5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Nov 2021 17:00:23 -0500 Subject: [PATCH 023/758] cleaning up and renaming code --- .../Cassie/osc_run/osc_running_gains.yaml | 4 +- .../osc_run/pelvis_roll_traj_generator.cc | 8 +- examples/Cassie/run_osc_jumping_controller.cc | 44 +++++----- examples/Cassie/run_osc_running_controller.cc | 85 ++++++++++--------- .../osc/operational_space_control.cc | 34 ++------ 5 files changed, 78 insertions(+), 97 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 8ec10c1176..97125d6a25 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -23,8 +23,8 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 10 -hip_yaw_kp: 100 +w_hip_yaw: 1 +hip_yaw_kp: 50 hip_yaw_kd: 5 w_hip_pitch: 5 hip_pitch_kp: 50 diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc index a5f03295bc..682241b4d2 100644 --- a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc @@ -88,10 +88,12 @@ PiecewisePolynomial PelvisRollTrajGenerator::GeneratePelvisTraj( correction << pelvis_roll; std::vector breaks = hip_roll_traj_.get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - MatrixXd foot_offset_points = correction.replicate(1, breaks.size()); + MatrixXd offset_angles = correction.replicate(1, breaks.size()); + for (int i = 0; i < breaks_vector.size(); ++i){ + offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); + } PiecewisePolynomial offset_traj = - PiecewisePolynomial::ZeroOrderHold(breaks_vector, - foot_offset_points); + PiecewisePolynomial::FirstOrderHold(breaks_vector, offset_angles); return hip_roll_traj_ + offset_traj; } diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index ea0a8aaad5..a0e8ad93fc 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -239,7 +239,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant_w_spr); // This actually outputs the target position of the pelvis not the true // center of mass - auto com_traj_generator = builder.AddSystem( + auto pelvis_trans_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), pelvis_trans_traj, feet_contact_points, FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( @@ -349,7 +349,7 @@ int DoMain(int argc, char* argv[]) { osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ - TransTaskSpaceTrackingData pelvis_tracking_data("com_traj", gains.K_p_com, + TransTaskSpaceTrackingData pelvis_tracking_data("pelvis_trans_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { @@ -396,27 +396,27 @@ int DoMain(int argc, char* argv[]) { MatrixXd W_hip_yaw = gains.w_hip_yaw * MatrixXd::Identity(1, 1); MatrixXd K_p_hip_yaw = gains.hip_yaw_kp * MatrixXd::Identity(1, 1); MatrixXd K_d_hip_yaw = gains.hip_yaw_kd * MatrixXd::Identity(1, 1); - JointSpaceTrackingData swing_hip_yaw_left_traj( + JointSpaceTrackingData left_hip_yaw_tracking_data( "swing_hip_yaw_left_traj", K_p_hip_yaw, K_d_hip_yaw, W_hip_yaw, plant_w_spr, plant_w_spr); - JointSpaceTrackingData swing_hip_yaw_right_traj( + JointSpaceTrackingData right_hip_yaw_tracking_data( "swing_hip_yaw_right_traj", K_p_hip_yaw, K_d_hip_yaw, W_hip_yaw, plant_w_spr, plant_w_spr); - swing_hip_yaw_left_traj.AddStateAndJointToTrack( + left_hip_yaw_tracking_data.AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); - swing_hip_yaw_right_traj.AddStateAndJointToTrack( + right_hip_yaw_tracking_data.AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_right", "hip_yaw_rightdot"); - osc->AddConstTrackingData(&swing_hip_yaw_left_traj, VectorXd::Zero(1)); - osc->AddConstTrackingData(&swing_hip_yaw_right_traj, VectorXd::Zero(1)); + osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); // Flight phase toe pitch tracking MatrixXd W_swing_toe = gains.w_swing_toe * MatrixXd::Identity(1, 1); MatrixXd K_p_swing_toe = gains.swing_toe_kp * MatrixXd::Identity(1, 1); MatrixXd K_d_swing_toe = gains.swing_toe_kd * MatrixXd::Identity(1, 1); - JointSpaceTrackingData left_toe_angle_traj( + JointSpaceTrackingData left_toe_angle_tracking_data( "left_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); - JointSpaceTrackingData right_toe_angle_traj( + JointSpaceTrackingData right_toe_angle_tracking_data( "right_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); @@ -434,9 +434,9 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), r_toe_trajectory, pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); - left_toe_angle_traj.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_left", + left_toe_angle_tracking_data.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_left", "toe_leftdot"); - right_toe_angle_traj.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_right", + right_toe_angle_tracking_data.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_right", "toe_rightdot"); osc->AddTrackingData(&pelvis_tracking_data); @@ -452,13 +452,13 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(&left_foot_tracking_data); osc->AddTrackingData(&right_foot_tracking_data); } - osc->AddTrackingData(&left_toe_angle_traj); - osc->AddTrackingData(&right_toe_angle_traj); + osc->AddTrackingData(&left_toe_angle_tracking_data); + osc->AddTrackingData(&right_toe_angle_tracking_data); - left_toe_angle_traj.SetImpactInvariantProjection(true); - right_toe_angle_traj.SetImpactInvariantProjection(true); - swing_hip_yaw_left_traj.SetImpactInvariantProjection(true); - swing_hip_yaw_right_traj.SetImpactInvariantProjection(true); + left_toe_angle_tracking_data.SetImpactInvariantProjection(true); + right_toe_angle_tracking_data.SetImpactInvariantProjection(true); +// swing_hip_yaw_left_traj.SetImpactInvariantProjection(true); +// swing_hip_yaw_right_traj.SetImpactInvariantProjection(true); pelvis_rot_tracking_data.SetImpactInvariantProjection(true); pelvis_tracking_data.SetImpactInvariantProjection(true); @@ -475,8 +475,8 @@ int DoMain(int argc, char* argv[]) { osc->get_near_impact_input_port()); builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); - builder.Connect(com_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("com_traj")); + builder.Connect(pelvis_trans_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_trans_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), @@ -497,7 +497,7 @@ int DoMain(int argc, char* argv[]) { // Trajectory generator connections builder.Connect(state_receiver->get_output_port(0), - com_traj_generator->get_state_input_port()); + pelvis_trans_traj_generator->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), l_foot_traj_generator->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), @@ -507,7 +507,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(state_receiver->get_output_port(0), right_toe_angle_traj_gen->get_state_input_port()); builder.Connect(fsm->get_output_port(0), - com_traj_generator->get_fsm_input_port()); + pelvis_trans_traj_generator->get_fsm_input_port()); builder.Connect(fsm->get_output_port(0), l_foot_traj_generator->get_fsm_input_port()); builder.Connect(fsm->get_output_port(0), diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b3c80db11e..233bf153c7 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -454,28 +454,28 @@ int DoMain(int argc, char* argv[]) { auto hip_pitch_right_traj_generator = builder.AddSystem( hip_pitch_right_traj, "hip_pitch_right_traj_generator"); - JointSpaceTrackingData hip_pitch_left_tracking_data( + JointSpaceTrackingData left_hip_pitch_tracking_data( "hip_pitch_left_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); - JointSpaceTrackingData hip_pitch_right_tracking_data( + JointSpaceTrackingData right_hip_pitch_tracking_data( "hip_pitch_right_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); std::cout << "Hip Pitch KD: " << osc_gains.K_d_hip_pitch << std::endl; std::cout << "Hip Roll KD: " << osc_gains.K_d_hip_roll << std::endl; - hip_pitch_left_tracking_data.AddStateAndJointToTrack( + left_hip_pitch_tracking_data.AddStateAndJointToTrack( left_stance_state, "hip_pitch_left", "hip_pitch_leftdot"); - hip_pitch_right_tracking_data.AddStateAndJointToTrack( + right_hip_pitch_tracking_data.AddStateAndJointToTrack( right_stance_state, "hip_pitch_right", "hip_pitch_rightdot"); - hip_pitch_left_tracking_data.DisableFeedforwardAccel({0}); - hip_pitch_right_tracking_data.DisableFeedforwardAccel({0}); - hip_pitch_left_tracking_data.SetImpactInvariantProjection(true); - hip_pitch_right_tracking_data.SetImpactInvariantProjection(true); + left_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); + right_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); + left_hip_pitch_tracking_data.SetImpactInvariantProjection(true); + right_hip_pitch_tracking_data.SetImpactInvariantProjection(true); // osc->AddConstTrackingData(&hip_pitch_left_tracking_data, // 0.6 * VectorXd::Ones(1)); // osc->AddConstTrackingData(&hip_pitch_right_tracking_data, // 0.6 * VectorXd::Ones(1)); - osc->AddTrackingData(&hip_pitch_left_tracking_data); - osc->AddTrackingData(&hip_pitch_right_tracking_data); + osc->AddTrackingData(&left_hip_pitch_tracking_data); + osc->AddTrackingData(&right_hip_pitch_tracking_data); // Stance hip roll trajectory auto hip_roll_left_traj = dircon_trajectory.ReconstructJointTrajectory( @@ -502,26 +502,26 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant, plant_context.get(), hip_roll_right_traj, pelvis_roll_traj, 1, "hip_roll_right_traj_generator"); - JointSpaceTrackingData hip_roll_left_tracking_data( + JointSpaceTrackingData left_hip_roll_tracking_data( "hip_roll_left_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, osc_gains.W_hip_roll, plant, plant); - JointSpaceTrackingData hip_roll_right_tracking_data( + JointSpaceTrackingData right_hip_roll_tracking_data( "hip_roll_right_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, osc_gains.W_hip_roll, plant, plant); - hip_roll_left_tracking_data.AddStateAndJointToTrack( + left_hip_roll_tracking_data.AddStateAndJointToTrack( left_stance_state, "hip_roll_left", "hip_roll_leftdot"); - hip_roll_right_tracking_data.AddStateAndJointToTrack( + right_hip_roll_tracking_data.AddStateAndJointToTrack( right_stance_state, "hip_roll_right", "hip_roll_rightdot"); - hip_roll_left_tracking_data.DisableFeedforwardAccel({0}); - hip_roll_right_tracking_data.DisableFeedforwardAccel({0}); - hip_roll_left_tracking_data.SetImpactInvariantProjection(true); - hip_roll_right_tracking_data.SetImpactInvariantProjection(true); + left_hip_roll_tracking_data.DisableFeedforwardAccel({0}); + right_hip_roll_tracking_data.DisableFeedforwardAccel({0}); + left_hip_roll_tracking_data.SetImpactInvariantProjection(true); + right_hip_roll_tracking_data.SetImpactInvariantProjection(true); // hip_roll_left_tracking_data.AddStateAndJointToTrack( // air_phase, "hip_roll_left", "hip_roll_leftdot"); // hip_roll_right_tracking_data.AddStateAndJointToTrack( // air_phase, "hip_roll_right", "hip_roll_rightdot"); - osc->AddTrackingData(&hip_roll_left_tracking_data); - osc->AddTrackingData(&hip_roll_right_tracking_data); + osc->AddTrackingData(&left_hip_roll_tracking_data); + osc->AddTrackingData(&right_hip_roll_tracking_data); // Swing toe joint trajectory vector&>> left_foot_points = { @@ -536,38 +536,39 @@ int DoMain(int argc, char* argv[]) { "right_toe_angle_traj"); // Swing toe joint tracking - JointSpaceTrackingData swing_toe_left_traj( + JointSpaceTrackingData left_toe_angle_tracking_data( "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); - JointSpaceTrackingData swing_toe_right_traj( + JointSpaceTrackingData right_toe_angle_tracking_data( "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); - swing_toe_right_traj.AddStateAndJointToTrack(left_stance_state, "toe_right", - "toe_rightdot"); - swing_toe_left_traj.AddStateAndJointToTrack(right_stance_state, "toe_left", - "toe_leftdot"); - swing_toe_right_traj.AddStateAndJointToTrack(air_phase, "toe_right", - "toe_rightdot"); - swing_toe_left_traj.AddStateAndJointToTrack(air_phase, "toe_left", - "toe_leftdot"); - swing_toe_left_traj.SetImpactInvariantProjection(true); - swing_toe_right_traj.SetImpactInvariantProjection(true); - osc->AddTrackingData(&swing_toe_left_traj); - osc->AddTrackingData(&swing_toe_right_traj); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + left_stance_state, "toe_right", "toe_rightdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + right_stance_state, "toe_left", "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack(air_phase, "toe_right", + "toe_rightdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack(air_phase, "toe_left", + "toe_leftdot"); + left_toe_angle_tracking_data.SetImpactInvariantProjection(true); + right_toe_angle_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_toe_angle_tracking_data); + osc->AddTrackingData(&right_toe_angle_tracking_data); // Swing hip yaw joint tracking - JointSpaceTrackingData hip_yaw_left_traj( + JointSpaceTrackingData left_hip_yaw_tracking_data( "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant, plant); - JointSpaceTrackingData hip_yaw_right_traj( + JointSpaceTrackingData right_hip_yaw_tracking_data( "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant, plant); - hip_yaw_left_traj.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); - hip_yaw_right_traj.AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - // hip_yaw_left_traj.SetImpactInvariantProjection(true); - // hip_yaw_right_traj.SetImpactInvariantProjection(true); - osc->AddConstTrackingData(&hip_yaw_left_traj, VectorXd::Zero(1)); - osc->AddConstTrackingData(&hip_yaw_right_traj, VectorXd::Zero(1)); + left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", + "hip_yaw_rightdot"); +// left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); +// right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); // Build OSC problem osc->Build(); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 2044efc5ad..a65567aa94 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -80,9 +80,10 @@ OperationalSpaceControl::OperationalSpaceControl( this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); clock_port_ = this->DeclareVectorInputPort("clock", BasicVector(1)) .get_index(); - impact_info_port_ = this->DeclareVectorInputPort("next_fsm, t_to_impact", - ImpactInfoVector(0, 0, kSpaceDim)) - .get_index(); + impact_info_port_ = + this->DeclareVectorInputPort("next_fsm, t_to_impact", + ImpactInfoVector(0, 0, kSpaceDim)) + .get_index(); // Discrete update to record the last state event time DeclarePerStepDiscreteUpdateEvent( @@ -372,32 +373,8 @@ void OperationalSpaceControl::Build() { .evaluator() .get()); } - - // friction cone constraints on impact invariant projection -// for (unsigned int j = 0; j < all_contacts_.size(); j++) { -// ii_friction_constraints_.push_back( -// ii_prog_ -// ->AddLinearConstraint( -// A, VectorXd::Zero(5), -// Eigen::VectorXd::Constant( -// 5, std::numeric_limits::infinity()), -// ii_lambda_c_.segment(kSpaceDim * j, 3)) -// .evaluator() -// .get()); -// } } - // bounding box constraint on holonomic constraint forces impact invariant - // projection -// if (n_h_) { -// ii_holonomic_constraint_ = -// ii_prog_ -// ->AddBoundingBoxConstraint(VectorXd::Zero(n_h_), -// VectorXd::Zero(n_h_), ii_lambda_h_) -// .evaluator() -// .get(); -// } - // 5. Input constraint if (with_input_constraints_) { prog_->AddLinearConstraint(MatrixXd::Identity(n_u_, n_u_), u_min_, u_max_, @@ -922,7 +899,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_data = std::vector(tracking_data_vec_->size()); output->tracking_cost = std::vector(tracking_data_vec_->size()); - output->tracking_data_names = std::vector(tracking_data_vec_->size()); + output->tracking_data_names = + std::vector(tracking_data_vec_->size()); for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); From 96eb4e28b310cb623fa292e2db40d6e85f2371e4 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Fri, 19 Nov 2021 17:21:36 -0500 Subject: [PATCH 024/758] fix osc plotting bug --- .../pydairlib/analysis/mbp_plotting_utils.py | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 766aefa24b..e663d44720 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -222,18 +222,16 @@ def plot_tracking_costs(osc_debug, time_slice): return ps -def plot_general_osc_tracking_data(traj_name, deriv, dim, data, - t_osc, time_slice): +def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): ps = plot_styler.PlotStyler() - data_dict = {key: val for key, val in data.items()} - data_dict['t_osc'] = t_osc + keys = [key for key in data.keys() if key != 't'] plotting_utils.make_plot( - data_dict, - 't_osc', + data, + 't', time_slice, - data.keys(), + keys, {}, - {key: [key] for key in data.keys()}, + {key: [key] for key in keys}, {'xlabel': 'Time', 'ylabel': '', 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) @@ -256,8 +254,8 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['yddot_command'] = tracking_data.yddot_command[:, dim] data['yddot_command_sol'] = tracking_data.yddot_command_sol[:, dim] - return plot_general_osc_tracking_data(traj, deriv, dim, data, - osc_debug['t_osc'], time_slice) + data['t'] = tracking_data.t + return plot_general_osc_tracking_data(traj, deriv, dim, data, time_slice) def plot_qp_costs(osc_debug, time_slice): From 1a1aae0e68ca7006b2fb5837fb63a23aa2aa76bd Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Nov 2021 17:23:07 -0500 Subject: [PATCH 025/758] adding plotting script for running --- .../pydairlib/analysis/log_plotter_cassie.py | 2 +- .../pydairlib/analysis/mbp_plotting_utils.py | 2 +- .../plot_configs/cassie_running_plot.yaml | 25 +++++++++++++++++++ 3 files changed, 27 insertions(+), 2 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 89972f7415..787e7083bb 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -13,7 +13,7 @@ def main(): config_file = \ - 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' + 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 766aefa24b..a308daaa6f 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -257,7 +257,7 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['yddot_command_sol'] = tracking_data.yddot_command_sol[:, dim] return plot_general_osc_tracking_data(traj, deriv, dim, data, - osc_debug['t_osc'], time_slice) + osc_debug['osc_debug_tracking_datas'][traj].t, time_slice) def plot_qp_costs(osc_debug, time_slice): diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml new file mode 100644 index 0000000000..680bbfd183 --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -0,0 +1,25 @@ +# LCM channels to read data from +channel_x: "CASSIE_STATE_SIMULATION" +channel_u: "CASSIE_INPUT" +channel_osc: "OSC_DEBUG_RUNNING" + +# Plant properties +use_springs: true +use_floating_base: true + +# Desired RobotOutput plots +plot_floating_base_positions: false +plot_floating_base_velocities: false +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Desired osc plots +plot_qp_costs: false +plot_tracking_costs: false +tracking_datas_to_plot: + pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +# swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} From c37ab82649bb7ab3c1d57bdbb25e2afed5f040fd Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Nov 2021 11:32:40 -0500 Subject: [PATCH 026/758] cleaning up controllers --- .../pydairlib/analysis/log_plotter_cassie.py | 5 +- .../plot_configs/cassie_jumping_plot.yaml | 25 ++ .../osc_jump/convert_traj_for_controller.cc | 78 ++-- .../osc_jump/flight_foot_traj_generator.cc | 5 +- examples/Cassie/osc_jump/osc_jumping_gains.h | 7 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 8 +- examples/Cassie/osc_run/BUILD.bazel | 13 + .../osc_run/convert_traj_for_controller.cc | 394 ++++++++++++++++++ .../Cassie/osc_run/foot_traj_generator.cc | 28 +- examples/Cassie/run_osc_jumping_controller.cc | 54 ++- examples/Cassie/run_osc_running_controller.cc | 20 +- .../Cassie/urdf/cassie_v2_conservative.urdf | 20 +- 12 files changed, 557 insertions(+), 100 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml create mode 100644 examples/Cassie/osc_run/convert_traj_for_controller.cc diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 787e7083bb..5e8a2ee335 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,8 +12,10 @@ def main(): + # config_file = \ + # 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' config_file = \ - 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base @@ -86,6 +88,7 @@ def main(): if plot_config.plot_tracking_costs: mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + import pdb; pdb.set_trace() for traj_name, config in plot_config.tracking_datas_to_plot.items(): for deriv in config['derivs']: for dim in config['dims']: diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml new file mode 100644 index 0000000000..5da6f782d3 --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -0,0 +1,25 @@ +# LCM channels to read data from +channel_x: "CASSIE_STATE_SIMULATION" +channel_u: "CASSIE_INPUT" +channel_osc: "OSC_DEBUG_JUMPING" + +# Plant properties +use_springs: true +use_floating_base: true + +# Desired RobotOutput plots +plot_floating_base_positions: false +plot_floating_base_velocities: false +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Desired osc plots +plot_qp_costs: false +plot_tracking_costs: false +tracking_datas_to_plot: + left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +# swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/examples/Cassie/osc_jump/convert_traj_for_controller.cc b/examples/Cassie/osc_jump/convert_traj_for_controller.cc index 97d25c476c..bf413f5dc2 100644 --- a/examples/Cassie/osc_jump/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_jump/convert_traj_for_controller.cc @@ -30,8 +30,7 @@ DEFINE_bool(relative_feet, true, "instead of as an offset from the hips"); DEFINE_string(trajectory_name, "", "File name where the optimal trajectory is stored."); -DEFINE_string(folder_path, - "", +DEFINE_string(folder_path, "", "Folder path for where the trajectory names are stored"); namespace dairlib { @@ -51,7 +50,7 @@ int DoMain() { parser.AddModelFromFile( FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); plant.mutable_gravity_field().set_gravity_vector(-9.81 * - Eigen::Vector3d::UnitZ()); + Eigen::Vector3d::UnitZ()); plant.Finalize(); // Create maps for joints @@ -62,6 +61,7 @@ int DoMain() { std::unique_ptr> context = plant.CreateDefaultContext(); int nv = plant.num_velocities(); + int nx = plant.num_positions() + plant.num_velocities(); auto l_toe_frame = &plant.GetBodyByName("toe_left").body_frame(); auto r_toe_frame = &plant.GetBodyByName("toe_right").body_frame(); @@ -94,20 +94,24 @@ int DoMain() { MatrixXd state_derivative_samples = dircon_traj.GetStateDerivativeSamples(mode); int n_points = times.size(); - MatrixXd l_foot_points(6, n_points); - MatrixXd r_foot_points(6, n_points); + MatrixXd l_foot_points(9, n_points); + MatrixXd r_foot_points(9, n_points); MatrixXd l_toe_points(2, n_points); MatrixXd r_toe_points(2, n_points); - MatrixXd l_hip_points(6, n_points); - MatrixXd r_hip_points(6, n_points); + MatrixXd l_hip_points(9, n_points); + MatrixXd r_hip_points(9, n_points); MatrixXd pelvis_points(6, n_points); MatrixXd pelvis_orientation(8, n_points); for (unsigned int i = 0; i < times.size(); ++i) { - VectorXd x_i = state_samples.col(i); - VectorXd xdot_i = state_traj.derivative(1).value(times[i]); - - + VectorXd x_i = state_samples.col(i).head(nx); + VectorXd xdot_i = state_derivative_samples.col(i); + // VectorXd xdot_i = state_traj.derivative(1).value(times[i]); +// std::cout << "x: " << state_samples.col(i) << std::endl; +// std::cout << "xdot: " << state_derivative_samples.col(i) << std::endl; +// std::cout << "nx: " << nx << std::endl; +// std::cout << x_i << std::endl; +// std::cout << xdot_i << std::endl; plant.SetPositionsAndVelocities(context.get(), x_i); Eigen::Ref pelvis_pos_block = pelvis_points.block(0, i, 3, 1); @@ -162,23 +166,39 @@ int DoMain() { pelvis_points.block(3, i, 3, 1) = J_pelvis * v_i; l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; - l_toe_points(1, i) = v_i(vel_map["toe_leftdot"]); - r_toe_points(1, i) = v_i(vel_map["toe_rightdot"]); l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; + l_toe_points(1, i) = v_i(vel_map["toe_leftdot"]); + r_toe_points(1, i) = v_i(vel_map["toe_rightdot"]); + + VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world); + l_foot_points.block(6, i, 3, 1) = + JdotV_l_foot + J_l_foot * xdot_i.tail(nv); + r_foot_points.block(6, i, 3, 1) = + JdotV_r_foot + J_r_foot * xdot_i.tail(nv); + l_hip_points.block(6, i, 3, 1) = JdotV_l_hip + J_l_hip * xdot_i.tail(nv); + r_hip_points.block(6, i, 3, 1) = JdotV_r_hip + J_r_hip * xdot_i.tail(nv); } - pelvis_points = pelvis_points - 0.5 * (l_foot_points + r_foot_points); -// if (FLAGS_relative_feet) { -// l_foot_points = l_foot_points - l_hip_points; -// r_foot_points = r_foot_points - r_hip_points; -// } + pelvis_points = pelvis_points - 0.5 * (l_foot_points.topRows(6) + r_foot_points.topRows(6)); + all_times.push_back(times); all_l_foot_points.push_back(l_foot_points); all_r_foot_points.push_back(r_foot_points); - all_l_toe_points.push_back(l_toe_points); - all_r_toe_points.push_back(r_toe_points); all_l_hip_points.push_back(l_hip_points); all_r_hip_points.push_back(r_hip_points); + all_l_toe_points.push_back(l_toe_points); + all_r_toe_points.push_back(r_toe_points); all_pelvis_points.push_back(pelvis_points); all_pelvis_orientation.push_back(pelvis_orientation); } @@ -191,28 +211,32 @@ int DoMain() { lfoot_traj_block.datapoints = all_l_foot_points[mode]; lfoot_traj_block.time_vector = all_times[mode]; lfoot_traj_block.datatypes = {"lfoot_x", "lfoot_y", "lfoot_z", - "lfoot_xdot", "lfoot_ydot", "lfoot_zdot"}; + "lfoot_xdot", "lfoot_ydot", "lfoot_zdot", + "lfoot_xddot", "lfoot_yddot", "lfoot_zddot"}; auto rfoot_traj_block = LcmTrajectory::Trajectory(); rfoot_traj_block.traj_name = "right_foot_trajectory" + std::to_string(mode); rfoot_traj_block.datapoints = all_r_foot_points[mode]; rfoot_traj_block.time_vector = all_times[mode]; rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", - "rfoot_xdot", "rfoot_ydot", "rfoot_zdot"}; - + "rfoot_xdot", "rfoot_ydot", "rfoot_zdot", + "rfoot_xddot", "rfoot_yddot", "rfoot_zddot"}; + auto lhip_traj_block = LcmTrajectory::Trajectory(); lhip_traj_block.traj_name = "left_hip_trajectory" + std::to_string(mode); lhip_traj_block.datapoints = all_l_hip_points[mode]; lhip_traj_block.time_vector = all_times[mode]; lhip_traj_block.datatypes = {"lhip_x", "lhip_y", "lhip_z", - "lhip_xdot", "lhip_ydot", "lhip_zdot"}; + "lhip_xdot", "lhip_ydot", "lhip_zdot", + "lhip_xddot", "lhip_yddot", "lhip_zddot"}; auto rhip_traj_block = LcmTrajectory::Trajectory(); rhip_traj_block.traj_name = "right_hip_trajectory" + std::to_string(mode); rhip_traj_block.datapoints = all_r_hip_points[mode]; rhip_traj_block.time_vector = all_times[mode]; rhip_traj_block.datatypes = {"rhip_x", "rhip_y", "rhip_z", - "rhip_xdot", "rhip_ydot", "rhip_zdot"}; + "rhip_xdot", "rhip_ydot", "rhip_zdot", + "rhip_xddot", "rhip_yddot", "rhip_zddot"}; auto ltoe_traj_block = LcmTrajectory::Trajectory(); ltoe_traj_block.traj_name = "left_toe_trajectory" + std::to_string(mode); @@ -267,10 +291,10 @@ int DoMain() { if (FLAGS_relative_feet) { processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + - "_processed" + "_rel"); + "_processed" + "_rel"); } else { processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + - "_processed"); + "_processed"); } return 0; } diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc index 2a34158f19..b9e542c4bc 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc @@ -28,7 +28,8 @@ FlightFootTrajGenerator::FlightFootTrajGenerator( const MultibodyPlant& plant, Context* context, const string& hip_name, bool isLeftFoot, const PiecewisePolynomial& foot_traj, - const PiecewisePolynomial& hip_traj, bool relative_feet, + const PiecewisePolynomial& hip_traj, + bool relative_feet, double time_offset) : plant_(plant), context_(context), @@ -112,7 +113,7 @@ void FlightFootTrajGenerator::CalcTraj( *casted_traj = GenerateRelativeTraj(); } else{ - *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); +// *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); } } diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.h b/examples/Cassie/osc_jump/osc_jumping_gains.h index 164b5a3230..ca80962910 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.h +++ b/examples/Cassie/osc_jump/osc_jumping_gains.h @@ -40,6 +40,9 @@ struct OSCJumpingGains : OSCGains { MatrixXd W_flight_foot; MatrixXd K_p_flight_foot; MatrixXd K_d_flight_foot; + MatrixXd W_hip_yaw; + MatrixXd K_p_hip_yaw; + MatrixXd K_d_hip_yaw; template void Serialize(Archive* a) { @@ -90,6 +93,8 @@ struct OSCJumpingGains : OSCGains { K_d_flight_foot = Eigen::Map< Eigen::Matrix>( this->FlightFootKd.data(), 3, 3); - + W_hip_yaw = w_hip_yaw * MatrixXd::Identity(1, 1); + K_p_hip_yaw = hip_yaw_kp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = hip_yaw_kd * MatrixXd::Identity(1, 1); } }; \ No newline at end of file diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 1695d0e501..1c9e068656 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -11,7 +11,7 @@ w_swing_toe: 1 swing_toe_kp: 2000 swing_toe_kd: 10 -w_hip_yaw: 100 +w_hip_yaw: 1 hip_yaw_kp: 40 hip_yaw_kd: 5 @@ -51,7 +51,7 @@ FlightFootKp: 0, 100, 0, 0, 0, 100] FlightFootKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 5.0] + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 0] diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 2900c92997..4d42efd5d4 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -32,6 +32,19 @@ cc_library( ], ) +cc_binary( + name = "convert_traj_for_controller", + srcs = ["convert_traj_for_controller.cc"], + deps = [ + "//examples/Cassie:cassie_utils", + "//lcm:lcm_trajectory_saver", + "//lcm:dircon_trajectory_saver", + "//multibody:utils", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_library( name = "osc_running_gains", hdrs = ["osc_running_gains.h"], diff --git a/examples/Cassie/osc_run/convert_traj_for_controller.cc b/examples/Cassie/osc_run/convert_traj_for_controller.cc new file mode 100644 index 0000000000..5bf42fdc09 --- /dev/null +++ b/examples/Cassie/osc_run/convert_traj_for_controller.cc @@ -0,0 +1,394 @@ +#include +#include +#include + +#include "examples/Cassie/cassie_utils.h" +#include "lcm/dircon_saved_trajectory.h" +#include "lcm/lcm_trajectory.h" + +#include "drake/multibody/plant/multibody_plant.h" + +using drake::geometry::SceneGraph; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::Context; +using drake::trajectories::PiecewisePolynomial; +using Eigen::Matrix3Xd; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +DEFINE_string(trajectory_name, "", + "File name where the optimal trajectory is stored."); +DEFINE_string(folder_path, "", + "Folder path for where the trajectory names are stored"); +DEFINE_bool(mirror_traj, false, + "Whether or not to extend the trajectory by mirroring"); + +namespace dairlib { + +/// This program pre-pelvisputes the output trajectories (center of mass, pelvis +/// orientation, feet trajectories) for the OSC controller. +/// + +int DoMain() { + // Drake system initialization + drake::systems::DiagramBuilder builder; + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + MultibodyPlant plant(1e-5); // non-zero timestep to avoid continuous + // model warnings + Parser parser(&plant, &scene_graph); + parser.AddModelFromFile( + FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); + plant.mutable_gravity_field().set_gravity_vector(-9.81 * + Eigen::Vector3d::UnitZ()); + plant.Finalize(); + + std::unique_ptr> context = plant.CreateDefaultContext(); + + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + int nx = plant.num_positions() + plant.num_velocities(); + + auto l_toe_frame = &plant.GetBodyByName("toe_left").body_frame(); + auto r_toe_frame = &plant.GetBodyByName("toe_right").body_frame(); + auto hip_left_frame = &plant.GetBodyByName("hip_left").body_frame(); + auto hip_right_frame = &plant.GetBodyByName("hip_right").body_frame(); + auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); + auto world = &plant.world_frame(); + + DirconTrajectory dircon_traj(FLAGS_folder_path + FLAGS_trajectory_name); + PiecewisePolynomial state_traj = + dircon_traj.ReconstructStateTrajectory(); + + MatrixXd M = dircon_traj.GetTrajectory("mirror_matrix").datapoints; + + double end_time = state_traj.end_time(); + + std::vector all_l_foot_points; + std::vector all_r_foot_points; + std::vector all_l_hip_points; + std::vector all_r_hip_points; + std::vector all_pelvis_points; + std::vector all_pelvis_orientation; + std::vector all_times; + Vector3d zero_offset = Vector3d::Zero(); + + for (int mode = 0; mode < dircon_traj.GetNumModes(); ++mode) { + if (dircon_traj.GetStateBreaks(mode).size() <= 1) { + continue; + } + VectorXd times = dircon_traj.GetStateBreaks(mode); + MatrixXd state_samples = dircon_traj.GetStateSamples(mode); + + int n_points = times.size(); + MatrixXd l_foot_points(9, n_points); + MatrixXd r_foot_points(9, n_points); + MatrixXd l_hip_points(9, n_points); + MatrixXd r_hip_points(9, n_points); + MatrixXd pelvis_points(9, n_points); + MatrixXd pelvis_orientation(12, n_points); + + for (unsigned int i = 0; i < times.size(); ++i) { + VectorXd x_i = state_samples.col(i).head(nx); + VectorXd xdot_i = state_samples.col(i).tail(nx); + + plant.SetPositionsAndVelocities(context.get(), x_i); + Eigen::Ref pelvis_pos_block = + pelvis_points.block(0, i, 3, 1); + Eigen::Ref l_foot_pos_block = + l_foot_points.block(0, i, 3, 1); + Eigen::Ref r_foot_pos_block = + r_foot_points.block(0, i, 3, 1); + Eigen::Ref l_hip_pos_block = + l_hip_points.block(0, i, 3, 1); + Eigen::Ref r_hip_pos_block = + r_hip_points.block(0, i, 3, 1); + plant.CalcPointsPositions(*context, *pelvis_frame, zero_offset, *world, + &pelvis_pos_block); + plant.CalcPointsPositions(*context, *l_toe_frame, zero_offset, *world, + &l_foot_pos_block); + plant.CalcPointsPositions(*context, *r_toe_frame, zero_offset, *world, + &r_foot_pos_block); + plant.CalcPointsPositions(*context, *hip_left_frame, zero_offset, *world, + &l_hip_pos_block); + plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, *world, + &r_hip_pos_block); + + pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); + pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); + + MatrixXd J_CoM(3, nv); + MatrixXd J_l_foot(3, nv); + MatrixXd J_r_foot(3, nv); + MatrixXd J_l_hip(3, nv); + MatrixXd J_r_hip(3, nv); + + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *pelvis_frame, zero_offset, + *world, *world, &J_CoM); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *l_toe_frame, zero_offset, *world, + *world, &J_l_foot); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *r_toe_frame, zero_offset, *world, + *world, &J_r_foot); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *hip_left_frame, zero_offset, + *world, *world, &J_l_hip); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *hip_right_frame, zero_offset, + *world, *world, &J_r_hip); + + VectorXd v_i = x_i.tail(nv); + pelvis_points.block(3, i, 3, 1) = J_CoM * v_i; + l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; + r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; + l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; + r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; + + VectorXd JdotV_CoM = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, *world, + *world); + VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world); + + pelvis_points.block(6, i, 3, 1) = JdotV_CoM + J_CoM * xdot_i.tail(nv); + l_foot_points.block(6, i, 3, 1) = + JdotV_l_foot + J_l_foot * xdot_i.tail(nv); + r_foot_points.block(6, i, 3, 1) = + JdotV_r_foot + J_r_foot * xdot_i.tail(nv); + l_hip_points.block(6, i, 3, 1) = JdotV_l_hip + J_l_hip * xdot_i.tail(nv); + r_hip_points.block(6, i, 3, 1) = JdotV_r_hip + J_r_hip * xdot_i.tail(nv); + } + + all_times.push_back(times); + all_l_foot_points.push_back(l_foot_points); + all_r_foot_points.push_back(r_foot_points); + all_l_hip_points.push_back(l_hip_points); + all_r_hip_points.push_back(r_hip_points); + all_pelvis_points.push_back(pelvis_points); + all_pelvis_orientation.push_back(pelvis_orientation); + } + + if (FLAGS_mirror_traj) { + double x_offset = state_traj.value(state_traj.end_time())(4) - + state_traj.value(state_traj.start_time())(4); + std::cout << "x_offset: " << x_offset << std::endl; + // Extended trajectory + for (int mode = 0; mode < dircon_traj.GetNumModes(); ++mode) { + if (dircon_traj.GetStateBreaks(mode).size() <= 1) { + continue; + } + VectorXd times = + dircon_traj.GetStateBreaks(mode) + + end_time * VectorXd::Ones(dircon_traj.GetStateBreaks(mode).size()); + MatrixXd x_samples = M * dircon_traj.GetStateSamples(mode).topRows(nx); + MatrixXd xdot_samples = + M * dircon_traj.GetStateSamples(mode).bottomRows(nx); + + int n_points = times.size(); + MatrixXd l_foot_points(9, n_points); + MatrixXd r_foot_points(9, n_points); + MatrixXd l_hip_points(9, n_points); + MatrixXd r_hip_points(9, n_points); + MatrixXd pelvis_points(9, n_points); + MatrixXd pelvis_orientation(12, n_points); + + for (unsigned int i = 0; i < times.size(); ++i) { + // VectorXd x_i = M * state_samples.col(i).head(nx); + // VectorXd xdot_i = M * state_samples.col(i).tail(nx); + VectorXd x_i = x_samples.col(i); + VectorXd xdot_i = xdot_samples.col(i); + x_i(4) = x_i(4) + x_offset; + + plant.SetPositionsAndVelocities(context.get(), x_i); + Eigen::Ref pelvis_pos_block = + pelvis_points.block(0, i, 3, 1); + Eigen::Ref l_foot_pos_block = + l_foot_points.block(0, i, 3, 1); + Eigen::Ref r_foot_pos_block = + r_foot_points.block(0, i, 3, 1); + Eigen::Ref l_hip_pos_block = + l_hip_points.block(0, i, 3, 1); + Eigen::Ref r_hip_pos_block = + r_hip_points.block(0, i, 3, 1); + plant.CalcPointsPositions(*context, *pelvis_frame, zero_offset, *world, + &pelvis_pos_block); + plant.CalcPointsPositions(*context, *l_toe_frame, zero_offset, *world, + &l_foot_pos_block); + plant.CalcPointsPositions(*context, *r_toe_frame, zero_offset, *world, + &r_foot_pos_block); + plant.CalcPointsPositions(*context, *hip_left_frame, zero_offset, + *world, &l_hip_pos_block); + plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, + *world, &r_hip_pos_block); + + pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); + pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); + + MatrixXd J_CoM(3, nv); + MatrixXd J_l_foot(3, nv); + MatrixXd J_r_foot(3, nv); + MatrixXd J_l_hip(3, nv); + MatrixXd J_r_hip(3, nv); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, + *world, *world, &J_CoM); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, + *world, *world, &J_l_foot); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, + *world, *world, &J_r_foot); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world, &J_l_hip); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world, &J_r_hip); + + VectorXd v_i = x_i.tail(nv); + pelvis_points.block(3, i, 3, 1) = J_CoM * v_i; + l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; + r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; + l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; + r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; + + VectorXd JdotV_CoM = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, + *world, *world); + VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, + *world, *world); + VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world); + + pelvis_points.block(6, i, 3, 1) = JdotV_CoM + J_CoM * xdot_i.tail(nv); + l_foot_points.block(6, i, 3, 1) = + JdotV_l_foot + J_l_foot * xdot_i.tail(nv); + r_foot_points.block(6, i, 3, 1) = + JdotV_r_foot + J_r_foot * xdot_i.tail(nv); + l_hip_points.block(6, i, 3, 1) = + JdotV_l_hip + J_l_hip * xdot_i.tail(nv); + r_hip_points.block(6, i, 3, 1) = + JdotV_r_hip + J_r_hip * xdot_i.tail(nv); + } + + all_times.push_back(times); + all_l_foot_points.push_back(l_foot_points); + all_r_foot_points.push_back(r_foot_points); + all_l_hip_points.push_back(l_hip_points); + all_r_hip_points.push_back(r_hip_points); + all_pelvis_points.push_back(pelvis_points); + all_pelvis_orientation.push_back(pelvis_orientation); + } + } + + std::vector converted_trajectories; + std::vector trajectory_names; + + std::cout << "num_modes: " << all_times.size() << std::endl; + for (int mode = 0; mode < all_times.size(); ++mode) { + auto lfoot_traj_block = LcmTrajectory::Trajectory(); + lfoot_traj_block.traj_name = "left_foot_trajectory" + std::to_string(mode); + lfoot_traj_block.datapoints = all_l_foot_points[mode]; + lfoot_traj_block.time_vector = all_times[mode]; + lfoot_traj_block.datatypes = {"lfoot_x", "lfoot_y", "lfoot_z", + "lfoot_xdot", "lfoot_ydot", "lfoot_zdot", + "lfoot_xddot", "lfoot_yddot", "lfoot_zddot"}; + + auto rfoot_traj_block = LcmTrajectory::Trajectory(); + rfoot_traj_block.traj_name = "right_foot_trajectory" + std::to_string(mode); + rfoot_traj_block.datapoints = all_r_foot_points[mode]; + rfoot_traj_block.time_vector = all_times[mode]; + rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", + "rfoot_xdot", "rfoot_ydot", "rfoot_zdot", + "rfoot_xddot", "rfoot_yddot", "rfoot_zddot"}; + + auto lhip_traj_block = LcmTrajectory::Trajectory(); + lhip_traj_block.traj_name = "left_hip_trajectory" + std::to_string(mode); + lhip_traj_block.datapoints = all_l_hip_points[mode]; + lhip_traj_block.time_vector = all_times[mode]; + lhip_traj_block.datatypes = {"lhip_x", "lhip_y", "lhip_z", + "lhip_xdot", "lhip_ydot", "lhip_zdot", + "lhip_xddot", "lhip_yddot", "lhip_zddot"}; + + auto rhip_traj_block = LcmTrajectory::Trajectory(); + rhip_traj_block.traj_name = "right_hip_trajectory" + std::to_string(mode); + rhip_traj_block.datapoints = all_r_hip_points[mode]; + rhip_traj_block.time_vector = all_times[mode]; + rhip_traj_block.datatypes = {"rhip_x", "rhip_y", "rhip_z", + "rhip_xdot", "rhip_ydot", "rhip_zdot", + "rhip_xddot", "rhip_yddot", "rhip_zddot"}; + + auto pelvis_traj_block = LcmTrajectory::Trajectory(); + pelvis_traj_block.traj_name = + "pelvis_trans_trajectory" + std::to_string(mode); + pelvis_traj_block.datapoints = all_pelvis_points[mode]; + pelvis_traj_block.time_vector = all_times[mode]; + pelvis_traj_block.datatypes = { + "pelvis_x", "pelvis_y", "pelvis_z", + "pelvis_xdot", "pelvis_ydot", "pelvis_zdot", + "pelvis_xddot", "pelvis_yddot", "pelvis_zddot"}; + + auto pelvis_orientation_block = LcmTrajectory::Trajectory(); + pelvis_orientation_block.traj_name = + "pelvis_rot_trajectory" + std::to_string(mode); + pelvis_orientation_block.datapoints = all_pelvis_orientation[mode]; + pelvis_orientation_block.time_vector = all_times[mode]; + pelvis_orientation_block.datatypes = { + "pelvis_rotw", "pelvis_rotx", "pelvis_roty", + "pelvis_rotz", "pelvis_rotwdot", "pelvis_rotxdot", + "pelvis_rotydot", "pelvis_rotzdot", "pelvis_rotwddot", + "pelvis_rotxddot", "pelvis_rotyddot", "pelvis_rotzddot"}; + + converted_trajectories.push_back(lfoot_traj_block); + converted_trajectories.push_back(rfoot_traj_block); + converted_trajectories.push_back(lhip_traj_block); + converted_trajectories.push_back(rhip_traj_block); + converted_trajectories.push_back(pelvis_traj_block); + converted_trajectories.push_back(pelvis_orientation_block); + trajectory_names.push_back(lfoot_traj_block.traj_name); + trajectory_names.push_back(rfoot_traj_block.traj_name); + trajectory_names.push_back(lhip_traj_block.traj_name); + trajectory_names.push_back(rhip_traj_block.traj_name); + trajectory_names.push_back(pelvis_traj_block.traj_name); + trajectory_names.push_back(pelvis_orientation_block.traj_name); + } + + auto processed_traj = LcmTrajectory(converted_trajectories, trajectory_names, + "walking_trajectory", + "Output trajectories " + "for Cassie walking"); + + processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + + "_processed_rel"); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + dairlib::DoMain(); +} \ No newline at end of file diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 79ce8a1774..84652dbd15 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -69,26 +69,24 @@ FootTrajGenerator::FootTrajGenerator( PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( const VectorXd& x, double t) const { - int n_cycles = t / (foot_traj_.end_time() - foot_traj_.start_time()); - double stride_length = foot_traj_.value(foot_traj_.end_time())(0) - - foot_traj_.value(foot_traj_.start_time())(0); - Vector3d foot_pos_offset = {n_cycles * stride_length, 0, 0}; - Vector3d foot_vel_offset = {0, 0, 0}; - VectorXd foot_offset = VectorXd(6); - foot_offset << foot_pos_offset, foot_vel_offset; +// int n_cycles = t / (foot_traj_.end_time() - foot_traj_.start_time()); +// double stride_length = foot_traj_.value(foot_traj_.end_time())(0) - +// foot_traj_.value(foot_traj_.start_time())(0); +// Vector3d foot_pos_offset = {n_cycles * stride_length, 0, 0}; +// Vector3d foot_vel_offset = {0, 0, 0}; +// VectorXd foot_offset = VectorXd(6); +// foot_offset << foot_pos_offset, foot_vel_offset; std::vector breaks = foot_traj_.get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - MatrixXd foot_offset_points = foot_offset.replicate(1, breaks.size()); - PiecewisePolynomial foot_offset_traj = - PiecewisePolynomial::ZeroOrderHold(breaks_vector, - foot_offset_points); +// MatrixXd foot_offset_points = foot_offset.replicate(1, breaks.size()); +// PiecewisePolynomial foot_offset_traj = +// PiecewisePolynomial::ZeroOrderHold(breaks_vector, +// foot_offset_points); if(relative_feet_){ -// std::cout << foot_traj_.value(t) << std::endl; -// std::cout << hip_traj_.value(t) << std::endl; - return foot_traj_ - hip_traj_ + foot_offset_traj; + return foot_traj_ - hip_traj_; }else{ - return foot_traj_ + foot_offset_traj; + return foot_traj_; } } diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index a0e8ad93fc..ac9e5c2c84 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -178,23 +178,23 @@ int DoMain(int argc, char* argv[]) { l_foot_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_left_foot_traj.time_vector, - lcm_left_foot_traj.datapoints.topRows(3), - lcm_left_foot_traj.datapoints.bottomRows(3))); + lcm_left_foot_traj.datapoints.topRows(6), + lcm_left_foot_traj.datapoints.bottomRows(6))); r_foot_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_right_foot_traj.time_vector, - lcm_right_foot_traj.datapoints.topRows(3), - lcm_right_foot_traj.datapoints.bottomRows(3))); + lcm_right_foot_traj.datapoints.topRows(6), + lcm_right_foot_traj.datapoints.bottomRows(6))); l_hip_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_left_hip_traj.time_vector, - lcm_left_hip_traj.datapoints.topRows(3), - lcm_left_hip_traj.datapoints.bottomRows(3))); + lcm_left_hip_traj.datapoints.topRows(6), + lcm_left_hip_traj.datapoints.bottomRows(6))); r_hip_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_right_hip_traj.time_vector, - lcm_right_hip_traj.datapoints.topRows(3), - lcm_right_hip_traj.datapoints.bottomRows(3))); + lcm_right_hip_traj.datapoints.topRows(6), + lcm_right_hip_traj.datapoints.bottomRows(6))); l_toe_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_left_toe_traj.time_vector, @@ -229,8 +229,6 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial offset_traj = PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_points); pelvis_trans_traj = pelvis_trans_traj + offset_traj; - l_foot_trajectory = l_foot_trajectory + offset_traj; - r_foot_trajectory = r_foot_trajectory + offset_traj; /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -239,9 +237,10 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant_w_spr); // This actually outputs the target position of the pelvis not the true // center of mass - auto pelvis_trans_traj_generator = builder.AddSystem( - plant_w_spr, context_w_spr.get(), pelvis_trans_traj, feet_contact_points, - FLAGS_delay_time); + auto pelvis_trans_traj_generator = + builder.AddSystem( + plant_w_spr, context_w_spr.get(), pelvis_trans_traj, + feet_contact_points, FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_left", true, l_foot_trajectory, l_hip_trajectory, gains.relative_feet, FLAGS_delay_time); @@ -349,9 +348,9 @@ int DoMain(int argc, char* argv[]) { osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ - TransTaskSpaceTrackingData pelvis_tracking_data("pelvis_trans_traj", gains.K_p_com, - gains.K_d_com, gains.W_com, - plant_w_spr, plant_w_spr); + TransTaskSpaceTrackingData pelvis_tracking_data( + "pelvis_trans_traj", gains.K_p_com, gains.K_d_com, gains.W_com, + plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { pelvis_tracking_data.AddStateAndPointToTrack(mode, "pelvis"); } @@ -393,15 +392,12 @@ int DoMain(int argc, char* argv[]) { &right_hip_tracking_data); // Flight phase hip yaw tracking - MatrixXd W_hip_yaw = gains.w_hip_yaw * MatrixXd::Identity(1, 1); - MatrixXd K_p_hip_yaw = gains.hip_yaw_kp * MatrixXd::Identity(1, 1); - MatrixXd K_d_hip_yaw = gains.hip_yaw_kd * MatrixXd::Identity(1, 1); JointSpaceTrackingData left_hip_yaw_tracking_data( - "swing_hip_yaw_left_traj", K_p_hip_yaw, K_d_hip_yaw, W_hip_yaw, - plant_w_spr, plant_w_spr); + "swing_hip_yaw_left_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, + gains.W_hip_yaw, plant_w_spr, plant_w_spr); JointSpaceTrackingData right_hip_yaw_tracking_data( - "swing_hip_yaw_right_traj", K_p_hip_yaw, K_d_hip_yaw, W_hip_yaw, - plant_w_spr, plant_w_spr); + "swing_hip_yaw_right_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, + gains.W_hip_yaw, plant_w_spr, plant_w_spr); left_hip_yaw_tracking_data.AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); right_hip_yaw_tracking_data.AddStateAndJointToTrack( @@ -434,10 +430,10 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), r_toe_trajectory, pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); - left_toe_angle_tracking_data.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_left", - "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_right", - "toe_rightdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + osc_jump::FLIGHT, "toe_left", "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + osc_jump::FLIGHT, "toe_right", "toe_rightdot"); osc->AddTrackingData(&pelvis_tracking_data); osc->AddTrackingData(&pelvis_rot_tracking_data); @@ -457,8 +453,8 @@ int DoMain(int argc, char* argv[]) { left_toe_angle_tracking_data.SetImpactInvariantProjection(true); right_toe_angle_tracking_data.SetImpactInvariantProjection(true); -// swing_hip_yaw_left_traj.SetImpactInvariantProjection(true); -// swing_hip_yaw_right_traj.SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); pelvis_rot_tracking_data.SetImpactInvariantProjection(true); pelvis_tracking_data.SetImpactInvariantProjection(true); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 233bf153c7..cdb8288279 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -96,7 +96,7 @@ int DoMain(int argc, char* argv[]) { // Built the Cassie MBPs drake::multibody::MultibodyPlant plant(0.0); addCassieMultibody(&plant, nullptr, true, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); drake::multibody::MultibodyPlant plant_wo_spr(0.0); addCassieMultibody(&plant_wo_spr, nullptr, true, @@ -357,25 +357,25 @@ int DoMain(int argc, char* argv[]) { TransTaskSpaceTrackingData pelvis_tracking_data( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant, plant); + TransTaskSpaceTrackingData stance_foot_tracking_data( + "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); TransTaskSpaceTrackingData left_foot_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); TransTaskSpaceTrackingData right_foot_tracking_data( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData stance_foot_tracking_data( - "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); pelvis_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); pelvis_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); - left_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, - "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, - "toe_right"); stance_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, "toe_left"); stance_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + "toe_right"); left_foot_tracking_data.AddStateAndPointToTrack(air_phase, "toe_left"); right_foot_tracking_data.AddStateAndPointToTrack(air_phase, "toe_right"); @@ -516,10 +516,6 @@ int DoMain(int argc, char* argv[]) { right_hip_roll_tracking_data.DisableFeedforwardAccel({0}); left_hip_roll_tracking_data.SetImpactInvariantProjection(true); right_hip_roll_tracking_data.SetImpactInvariantProjection(true); - // hip_roll_left_tracking_data.AddStateAndJointToTrack( - // air_phase, "hip_roll_left", "hip_roll_leftdot"); - // hip_roll_right_tracking_data.AddStateAndJointToTrack( - // air_phase, "hip_roll_right", "hip_roll_rightdot"); osc->AddTrackingData(&left_hip_roll_tracking_data); osc->AddTrackingData(&right_hip_roll_tracking_data); diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 2dce39b96a..5c5471cbdc 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -462,7 +462,7 @@ @@ -614,7 +614,7 @@ - + @@ -623,7 +623,7 @@ - + @@ -633,7 +633,7 @@ - + @@ -642,7 +642,7 @@ - + @@ -652,7 +652,8 @@ - + + @@ -661,7 +662,8 @@ - + + @@ -784,7 +786,7 @@ - + @@ -793,7 +795,7 @@ - + From a857255ab1bec6e6eb1ad3153f8e3067d40c177d Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Nov 2021 13:29:31 -0500 Subject: [PATCH 027/758] adding view frame to constraints --- .../osc_run/pelvis_roll_traj_generator.cc | 10 ++++------ examples/Cassie/run_osc_running_controller.cc | 18 ++++++++++-------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc index 682241b4d2..860eff7334 100644 --- a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc @@ -75,8 +75,6 @@ PiecewisePolynomial PelvisRollTrajGenerator::GeneratePelvisTraj( VectorXd v = robot_output->GetVelocities(); multibody::SetPositionsIfNew(plant_, q, context_); - // int hip_roll_idx_ = 1; - // int hip_rolldot_idx_ = 3; VectorXd correction = VectorXd::Zero(1); drake::math::RotationMatrix pelvis_rot = @@ -89,11 +87,11 @@ PiecewisePolynomial PelvisRollTrajGenerator::GeneratePelvisTraj( std::vector breaks = hip_roll_traj_.get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); MatrixXd offset_angles = correction.replicate(1, breaks.size()); - for (int i = 0; i < breaks_vector.size(); ++i){ - offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); - } +// for (int i = 0; i < breaks_vector.size(); ++i){ +// offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); +// } PiecewisePolynomial offset_traj = - PiecewisePolynomial::FirstOrderHold(breaks_vector, offset_angles); + PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_angles); return hip_roll_traj_ + offset_traj; } diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index cdb8288279..36c1ef6818 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -200,17 +200,19 @@ int DoMain(int argc, char* argv[]) { // Contact information for OSC osc->SetContactFriction(gains.mu); + const auto& pelvis = plant.GetBodyByName("pelvis"); + multibody::WorldYawViewFrame view_frame(pelvis); auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant, left_toe.first, left_toe.second, Matrix3d::Identity(), + plant, left_toe.first, left_toe.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant, left_heel.first, left_heel.second, Matrix3d::Identity(), + plant, left_heel.first, left_heel.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant, right_toe.first, right_toe.second, Matrix3d::Identity(), + plant, right_toe.first, right_toe.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant, right_heel.first, right_heel.second, Matrix3d::Identity(), + plant, right_heel.first, right_heel.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); osc->AddStateAndContactPoint(0, &left_toe_evaluator); @@ -392,7 +394,7 @@ int DoMain(int argc, char* argv[]) { left_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_left"); right_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_right"); - WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); +// WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); RelativeTranslationTrackingData left_foot_rel_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, @@ -405,9 +407,9 @@ int DoMain(int argc, char* argv[]) { "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, &stance_foot_tracking_data); - left_foot_rel_tracking_data.SetViewFrame(pelvis_view_frame); - right_foot_rel_tracking_data.SetViewFrame(pelvis_view_frame); - pelvis_trans_rel_tracking_data.SetViewFrame(pelvis_view_frame); + left_foot_rel_tracking_data.SetViewFrame(view_frame); + right_foot_rel_tracking_data.SetViewFrame(view_frame); + pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); From f1bd51f52d4741527d89369b8793e5d52a317a3f Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 23 Nov 2021 14:39:09 -0500 Subject: [PATCH 028/758] need to work on distinguishing flight phases --- .../pydairlib/analysis/log_plotter_cassie.py | 13 +-- .../pydairlib/analysis/mbp_plotting_utils.py | 35 +++--- bindings/pydairlib/analysis/osc_debug.py | 104 +++++++++--------- .../plot_configs/cassie_running_plot.yaml | 8 +- bindings/pydairlib/common/plot_styler.py | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 60 +++++----- .../Cassie/osc_run/osc_running_gains.yaml | 22 ++-- examples/Cassie/run_osc_running_controller.cc | 8 -- .../impact_aware_time_based_fsm.cc | 2 - .../osc/operational_space_control.cc | 3 +- 10 files changed, 124 insertions(+), 133 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 5e8a2ee335..e15ff1ae37 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,10 +12,10 @@ def main(): - # config_file = \ - # 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' config_file = \ - 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' + 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = \ + # 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base @@ -36,9 +36,9 @@ def main(): log = lcm.EventLog(filename, "r") robot_output, robot_input, osc_debug = \ get_log_data(log, # log - cassie_plots.cassie_default_channels, # lcm channels - mbp_plots.load_default_channels, # processing callback - plant, channel_x, channel_u, channel_osc) # processing callback arguments + cassie_plots.cassie_default_channels, # lcm channels + mbp_plots.load_default_channels, # processing callback + plant, channel_x, channel_u, channel_osc) # processing callback arguments # Define x time slice t_x_slice = slice(robot_output['t_x'].size) @@ -88,7 +88,6 @@ def main(): if plot_config.plot_tracking_costs: mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) - import pdb; pdb.set_trace() for traj_name, config in plot_config.tracking_datas_to_plot.items(): for deriv in config['derivs']: for dim in config['dims']: diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index a308daaa6f..94e30a3b2c 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -83,12 +83,12 @@ def process_osc_channel(data): u_sol.append(msg.qp_output.u_sol) osc_output.append(msg) for tracking_data in msg.tracking_data: - if tracking_data.name not in osc_debug_tracking_datas: - osc_debug_tracking_datas[tracking_data.name] = \ - lcmt_osc_tracking_data_t() - osc_debug_tracking_datas[tracking_data.name].append( - tracking_data, msg.utime / 1e6) - + if tracking_data.name != '': + if tracking_data.name not in osc_debug_tracking_datas: + osc_debug_tracking_datas[tracking_data.name] = \ + lcmt_osc_tracking_data_t() + osc_debug_tracking_datas[tracking_data.name].append( + tracking_data, msg.utime / 1e6) fsm.append(msg.fsm_state) tracking_cost_handler = osc_tracking_cost(osc_debug_tracking_datas.keys()) @@ -132,21 +132,22 @@ def load_osc_channel(data, osc_debug_channel): def plot_q_or_v_or_u( - robot_output, key, x_names, x_slice, time_slice, - ylabel=None, title=None): + robot_output, key, x_names, x_slice, time_slice, + ylabel=None, title=None): ps = plot_styler.PlotStyler() + ps.set_default_styling() if ylabel is None: ylabel = key if title is None: title = key plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel + robot_output, # data dict + 't_x', # time channel time_slice, - [key], # key to plot - {key: x_slice}, # slice of key to plot - {key: x_names}, # legend entries + [key], # key to plot + {key: x_slice}, # slice of key to plot + {key: x_names}, # legend entries {'xlabel': 'Time', 'ylabel': ylabel, 'title': title}, ps) @@ -205,10 +206,10 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): def plot_tracking_costs(osc_debug, time_slice): ps = plot_styler.PlotStyler() + ps.set_default_styling() data_dict = \ {key: val for key, val in osc_debug['tracking_cost'].items()} data_dict['t_osc'] = osc_debug['t_osc'] - plotting_utils.make_plot( data_dict, 't_osc', @@ -225,6 +226,7 @@ def plot_tracking_costs(osc_debug, time_slice): def plot_general_osc_tracking_data(traj_name, deriv, dim, data, t_osc, time_slice): ps = plot_styler.PlotStyler() + ps.set_default_styling() data_dict = {key: val for key, val in data.items()} data_dict['t_osc'] = t_osc plotting_utils.make_plot( @@ -250,7 +252,8 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): elif deriv == 'vel': data['ydot_des'] = tracking_data.ydot_des[:, dim] data['ydot'] = tracking_data.ydot[:, dim] - data['error_ydot'] = tracking_data.error_ydot[:, dim] + data['error_ydot'] = tracking_data.ydot_des[:, dim] - tracking_data.ydot[:, dim] + data['projected_error_ydot'] = tracking_data.error_ydot[:, dim] elif deriv == 'accel': data['yddot_des'] = tracking_data.yddot_des[:, dim] data['yddot_command'] = tracking_data.yddot_command[:, dim] @@ -278,4 +281,4 @@ def plot_qp_costs(osc_debug, time_slice): def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): - ps.plot(fsm_time, scale*fsm_signal) \ No newline at end of file + ps.plot(fsm_time, scale * fsm_signal) diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 823ffee97b..5833dab871 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -3,65 +3,65 @@ # Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays class lcmt_osc_tracking_data_t: - def __init__(self): - self.t = [] - self.y_dim = 0 - self.name = "" - self.is_active = [] - self.y = [] - self.y_des = [] - self.error_y = [] - self.ydot = [] - self.ydot_des = [] - self.error_ydot = [] - self.yddot_des = [] - self.yddot_command = [] - self.yddot_command_sol = [] + def __init__(self): + self.t = [] + self.y_dim = 0 + self.name = "" + self.is_active = [] + self.y = [] + self.y_des = [] + self.error_y = [] + self.ydot = [] + self.ydot_des = [] + self.error_ydot = [] + self.yddot_des = [] + self.yddot_command = [] + self.yddot_command_sol = [] - def append(self, msg, t): - self.t.append(t) - self.is_active.append(msg.is_active) - self.y.append(msg.y) - self.y_des.append(msg.y_des) - self.error_y.append(msg.error_y) - self.ydot.append(msg.ydot) - self.ydot_des.append(msg.ydot_des) - self.error_ydot.append(msg.error_ydot) - self.yddot_des.append(msg.yddot_des) - self.yddot_command.append(msg.yddot_command) - self.yddot_command_sol.append(msg.yddot_command_sol) + def append(self, msg, t): + self.t.append(t) + self.is_active.append(msg.is_active) + self.y.append(msg.y) + self.y_des.append(msg.y_des) + self.error_y.append(msg.error_y) + self.ydot.append(msg.ydot) + self.ydot_des.append(msg.ydot_des) + self.error_ydot.append(msg.error_ydot) + self.yddot_des.append(msg.yddot_des) + self.yddot_command.append(msg.yddot_command) + self.yddot_command_sol.append(msg.yddot_command_sol) - def convertToNP(self): - self.t = np.array(self.t) - self.is_active = np.array(self.is_active) - self.y = np.array(self.y) - self.y_des = np.array(self.y_des) - self.error_y = np.array(self.error_y) - self.ydot = np.array(self.ydot) - self.ydot_des = np.array(self.ydot_des) - self.error_ydot = np.array(self.error_ydot) - self.yddot_des = np.array(self.yddot_des) - self.yddot_command = np.array(self.yddot_command) - self.yddot_command_sol = np.array(self.yddot_command_sol) + def convertToNP(self): + self.t = np.array(self.t) + self.is_active = np.array(self.is_active) + self.y = np.array(self.y) + self.y_des = np.array(self.y_des) + self.error_y = np.array(self.error_y) + self.ydot = np.array(self.ydot) + self.ydot_des = np.array(self.ydot_des) + self.error_ydot = np.array(self.error_ydot) + self.yddot_des = np.array(self.yddot_des) + self.yddot_command = np.array(self.yddot_command) + self.yddot_command_sol = np.array(self.yddot_command_sol) class osc_tracking_cost(): - def __init__(self, tracking_data_names): + def __init__(self, tracking_data_names): - self.tracking_costs = {} - for name in tracking_data_names: - self.tracking_costs[name] = [] + self.tracking_costs = {} + for name in tracking_data_names: + self.tracking_costs[name] = [] - def append(self, tracking_data_list, tracking_cost_list): - for name, cost in zip(tracking_data_list, tracking_cost_list): - self.tracking_costs[name].append(cost) + def append(self, tracking_data_list, tracking_cost_list): + for name, cost in zip(tracking_data_list, tracking_cost_list): + self.tracking_costs[name].append(cost) - for name in self.tracking_costs: - if name not in tracking_cost_list: - self.tracking_costs[name].append(0.0) + for name in self.tracking_costs: + if name not in tracking_data_list: + self.tracking_costs[name].append(0.0) - def convertToNP(self): - for name in self.tracking_costs: - self.tracking_costs[name] = np.array(self.tracking_costs[name]) - return self.tracking_costs + def convertToNP(self): + for name in self.tracking_costs: + self.tracking_costs[name] = np.array(self.tracking_costs[name]) + return self.tracking_costs diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 680bbfd183..2f8b462bd8 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -18,8 +18,10 @@ special_velocities_to_plot: [] special_efforts_to_plot: [] # Desired osc plots -plot_qp_costs: false -plot_tracking_costs: false +plot_qp_costs: true +plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel', 'accel']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} +# left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} # swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 8ed4dc8702..63d41d6633 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -30,7 +30,7 @@ def set_default_styling(self, directory=None): plt.figure(self.fig_id) self.directory = directory matplotlib.rcParams["savefig.directory"] = directory - matplotlib.rcParams['text.latex.preamble'] = [r"\usepackage{amsmath}"] + matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" # matplotlib.rcParams['figure.figsize'] = 20, 12 # matplotlib.rcParams['figure.figsize'] = 20, 6 matplotlib.rcParams['figure.figsize'] = 8, 5 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 84652dbd15..a7735341d6 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -28,8 +28,7 @@ FootTrajGenerator::FootTrajGenerator( const MultibodyPlant& plant, Context* context, const string& hip_name, bool isLeftFoot, const PiecewisePolynomial& foot_traj, - const PiecewisePolynomial& hip_traj, - bool relative_feet, + const PiecewisePolynomial& hip_traj, bool relative_feet, double time_offset) : plant_(plant), context_(context), @@ -53,14 +52,15 @@ FootTrajGenerator::FootTrajGenerator( } // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); target_vel_port_ = - this->DeclareVectorInputPort("v_des",BasicVector(2)).get_index(); - fsm_port_ = this->DeclareVectorInputPort("fsm",BasicVector(1)).get_index(); + this->DeclareVectorInputPort("v_des", BasicVector(2)).get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); // Shift trajectory by time_offset foot_traj_.shiftRight(time_offset); @@ -69,23 +69,9 @@ FootTrajGenerator::FootTrajGenerator( PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( const VectorXd& x, double t) const { -// int n_cycles = t / (foot_traj_.end_time() - foot_traj_.start_time()); -// double stride_length = foot_traj_.value(foot_traj_.end_time())(0) - -// foot_traj_.value(foot_traj_.start_time())(0); -// Vector3d foot_pos_offset = {n_cycles * stride_length, 0, 0}; -// Vector3d foot_vel_offset = {0, 0, 0}; -// VectorXd foot_offset = VectorXd(6); -// foot_offset << foot_pos_offset, foot_vel_offset; - - std::vector breaks = foot_traj_.get_segment_times(); - VectorXd breaks_vector = Map(breaks.data(), breaks.size()); -// MatrixXd foot_offset_points = foot_offset.replicate(1, breaks.size()); -// PiecewisePolynomial foot_offset_traj = -// PiecewisePolynomial::ZeroOrderHold(breaks_vector, -// foot_offset_points); - if(relative_feet_){ + if (relative_feet_) { return foot_traj_ - hip_traj_; - }else{ + } else { return foot_traj_; } } @@ -93,29 +79,41 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( void FootTrajGenerator::AddRaibertCorrection( const drake::systems::Context& context, drake::trajectories::PiecewisePolynomial* traj) const { - const auto robot_output = this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel = this->EvalVectorInput(context, target_vel_port_)->get_value(); + + VectorXd q = robot_output->GetPositions(); + multibody::SetPositionsIfNew(plant_, q, context_); + Vector2d desired_pelvis_pos = {0.0, 0}; VectorXd pelvis_pos = robot_output->GetPositions().segment(4, 2); VectorXd pelvis_vel = robot_output->GetVelocities().segment(3, 2); VectorXd pelvis_pos_err = pelvis_pos - desired_pelvis_pos; VectorXd pelvis_vel_err = pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = - Kp_ * (pelvis_pos_err) + - Kd_ * (pelvis_vel_err); - if(is_left_foot_){ + Kp_ * (pelvis_pos_err) + Kd_ * (pelvis_vel_err); + if (is_left_foot_) { footstep_correction(1) -= 0.02; - }else{ + } else { footstep_correction(1) += 0.02; } footstep_correction(0) -= 0.03; + Vector3d pelvis_heading_vec = + plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) + .rotation() + .col(0); + double approx_pelvis_yaw = + atan2(pelvis_heading_vec(1), pelvis_heading_vec(0)); + Eigen::Matrix3d rot; + rot << cos(approx_pelvis_yaw), -sin(approx_pelvis_yaw), 0, + sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; + std::vector breaks = traj->get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); VectorXd new_samples = VectorXd(6); - new_samples << footstep_correction, Vector3d::Zero(); + new_samples << rot.transpose() * footstep_correction, Vector3d::Zero(); MatrixXd foot_offset_points = new_samples.replicate(1, breaks.size()); PiecewisePolynomial foot_offset_traj = PiecewisePolynomial::ZeroOrderHold(breaks_vector, diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 97125d6a25..fa042c5328 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0000000000 -w_accel: 0.000001 +w_accel: 0.0000 #w_soft_constraint: 1000000 -w_soft_constraint: 0.00000000 +w_soft_constraint: 10.0 w_input_reg: 0.0001 impact_threshold: 0.050 relative_feet: true @@ -23,9 +23,9 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 1 -hip_yaw_kp: 50 -hip_yaw_kd: 5 +w_hip_yaw: 0.1 +hip_yaw_kp: 100 +hip_yaw_kd: 20 w_hip_pitch: 5 hip_pitch_kp: 50 hip_pitch_kd: 20 @@ -40,11 +40,11 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 100] + 0, 0, 90] PelvisKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 5] + 0, 0, 5] SwingFootW: [1, 0, 0, 0, 1, 0, @@ -52,7 +52,7 @@ SwingFootW: SwingFootKp: [50, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 50] SwingFootKd: [ 1, 0, 0, 0, 1, 0, @@ -62,6 +62,6 @@ FootstepKp: 0, 0.0, 0, 0] FootstepKd: - [ 0.15, 0, - 0, 0.04, - 0, 0] + [ 0.1, 0, + 0, 0.04, + 0, 0] diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 36c1ef6818..c61e4d9fcf 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -264,13 +264,6 @@ int DoMain(int argc, char* argv[]) { osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); builder.Connect(cassie_out_receiver->get_output_port(), high_level_command->get_cassie_output_port()); - } else { - // high_level_command = builder.AddSystem( - // plant, plant_context.get(), gains.kp_yaw, gains.kd_yaw, - // gains.vel_max_yaw, gains.kp_pos_sagital, gains.kd_pos_sagital, - // gains.vel_max_sagital, gains.kp_pos_lateral, gains.kd_pos_lateral, - // gains.vel_max_lateral, gains.target_pos_offset, - // global_target_position, params_of_no_turning); } string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; @@ -413,7 +406,6 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_rel_tracking_data.DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data.DisableFeedforwardAccel({2}); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index f7ee7f4d13..9b26767936 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -39,8 +39,6 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( DRAKE_DEMAND(states.size() == state_durations.size()); for (int i = 0; i < states.size(); ++i) { sum += state_durations[i]; - std::cout << "i: " << i << std::endl; - std::cout << "sum: " << sum << std::endl; accu_state_durations_.push_back(sum); if (states[i] == 2) { impact_times_.push_back(sum); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index a65567aa94..653c918443 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -904,11 +904,11 @@ void OperationalSpaceControl::AssignOscLcmOutput( for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); + output->tracking_data_names[i] = tracking_data->GetName(); if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && time_since_last_state_switch <= t_e_vec_.at(i)) { - output->tracking_data_names[i] = tracking_data->GetName(); lcmt_osc_tracking_data osc_output; osc_output.y_dim = tracking_data->GetYDim(); osc_output.ydot_dim = tracking_data->GetYdotDim(); @@ -929,7 +929,6 @@ void OperationalSpaceControl::AssignOscLcmOutput( CopyVectorXdToStdVector(tracking_data->GetYddotCommand()); osc_output.yddot_command_sol = CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); - // output->tracking_data.push_back(osc_output); output->tracking_data[i] = osc_output; const VectorXd& ddy_t = tracking_data->GetYddotCommand(); From 819b2bc7a5cc866ff37fd544c2aacc0b898df8c2 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Tue, 23 Nov 2021 20:12:19 -0500 Subject: [PATCH 029/758] bug fix --- bindings/pydairlib/analysis/osc_debug.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 823ffee97b..7d6cdbdebc 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -58,7 +58,7 @@ def append(self, tracking_data_list, tracking_cost_list): self.tracking_costs[name].append(cost) for name in self.tracking_costs: - if name not in tracking_cost_list: + if name not in tracking_data_list: self.tracking_costs[name].append(0.0) def convertToNP(self): From 6a184f97d302f34a630a9b07a81c35c64862a5b8 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Tue, 23 Nov 2021 20:23:36 -0500 Subject: [PATCH 030/758] allow tracking_datas_to_plot to be empty --- .../pydairlib/analysis/log_plotter_cassie.py | 19 ++++++++++--------- .../plot_configs/cassie_default_plot.yaml | 6 +++--- 2 files changed, 13 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 89972f7415..86ab694d69 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -33,10 +33,10 @@ def main(): filename = sys.argv[1] log = lcm.EventLog(filename, "r") robot_output, robot_input, osc_debug = \ - get_log_data(log, # log - cassie_plots.cassie_default_channels, # lcm channels - mbp_plots.load_default_channels, # processing callback - plant, channel_x, channel_u, channel_osc) # processing callback arguments + get_log_data(log, # log + cassie_plots.cassie_default_channels, # lcm channels + mbp_plots.load_default_channels, # processing callback + plant, channel_x, channel_u, channel_osc) # processing callback arguments # Define x time slice t_x_slice = slice(robot_output['t_x'].size) @@ -86,11 +86,12 @@ def main(): if plot_config.plot_tracking_costs: mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) - for traj_name, config in plot_config.tracking_datas_to_plot.items(): - for deriv in config['derivs']: - for dim in config['dims']: - mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, - deriv, t_osc_slice) + if plot_config.tracking_datas_to_plot: + for traj_name, config in plot_config.tracking_datas_to_plot.items(): + for deriv in config['derivs']: + for dim in config['dims']: + mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, + deriv, t_osc_slice) plt.show() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index f0a14e02ef..a8f562aff2 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -18,8 +18,8 @@ special_velocities_to_plot: [] special_efforts_to_plot: [] # Desired osc plots -plot_qp_costs: false -plot_tracking_costs: false +plot_qp_costs: true +plot_tracking_costs: true tracking_datas_to_plot: com_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} -# swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} + swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} From 63ea7977c91e3d3dadd4b8590b34a5e4d180575f Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 24 Nov 2021 11:17:10 -0500 Subject: [PATCH 031/758] pelvis is much more stable, need to improve the tracking tradeoffs still --- .../pydairlib/analysis/log_plotter_cassie.py | 3 +- bindings/pydairlib/analysis/osc_debug.py | 6 +- .../plot_configs/cassie_running_plot.yaml | 5 +- examples/Cassie/osc_run/BUILD.bazel | 17 +- .../Cassie/osc_run/foot_traj_generator.cc | 6 +- examples/Cassie/osc_run/osc_running_gains.h | 19 +++ .../Cassie/osc_run/osc_running_gains.yaml | 38 +++-- .../osc_run/pelvis_pitch_traj_generator.cc | 120 +++++++++++++++ .../osc_run/pelvis_pitch_traj_generator.h | 60 ++++++++ examples/Cassie/run_osc_running_controller.cc | 145 ++++++++++++++---- .../impact_aware_time_based_fsm.cc | 2 +- 11 files changed, 364 insertions(+), 57 deletions(-) create mode 100644 examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc create mode 100644 examples/Cassie/osc_run/pelvis_pitch_traj_generator.h diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index e15ff1ae37..a088071a41 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -91,8 +91,9 @@ def main(): for traj_name, config in plot_config.tracking_datas_to_plot.items(): for deriv in config['derivs']: for dim in config['dims']: - mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, + ps = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) + mbp_plots.add_fsm_to_plot(ps, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) plt.show() diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 5833dab871..445b922942 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -57,9 +57,9 @@ def append(self, tracking_data_list, tracking_cost_list): for name, cost in zip(tracking_data_list, tracking_cost_list): self.tracking_costs[name].append(cost) - for name in self.tracking_costs: - if name not in tracking_data_list: - self.tracking_costs[name].append(0.0) + # for name in self.tracking_costs: + # if name not in tracking_data_list: + # self.tracking_costs[name].append(0.0) def convertToNP(self): for name in self.tracking_costs: diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 2f8b462bd8..8f0d002e05 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -21,7 +21,8 @@ special_efforts_to_plot: [] plot_qp_costs: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel', 'accel']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['vel', 'accel']} hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} -# left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} + left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} # swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 4d42efd5d4..47a1a56fe3 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -27,7 +27,8 @@ cc_library( deps = [ ":foot_traj_generator", ":osc_running_gains", - ":pelvis_rot_traj_generator", + ":pelvis_roll_traj_generator", + ":pelvis_pitch_traj_generator", ":pelvis_trans_traj_generator", ], ) @@ -67,7 +68,7 @@ cc_library( ) cc_library( - name = "pelvis_rot_traj_generator", + name = "pelvis_roll_traj_generator", srcs = ["pelvis_roll_traj_generator.cc"], hdrs = ["pelvis_roll_traj_generator.h"], deps = [ @@ -78,6 +79,18 @@ cc_library( ], ) +cc_library( + name = "pelvis_pitch_traj_generator", + srcs = ["pelvis_pitch_traj_generator.cc"], + hdrs = ["pelvis_pitch_traj_generator.h"], + deps = [ + "//multibody:utils", + "//systems/controllers/osc:osc_gains", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "foot_traj_generator", srcs = ["foot_traj_generator.cc"], diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index a7735341d6..3ddd4c3581 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -95,11 +95,11 @@ void FootTrajGenerator::AddRaibertCorrection( VectorXd footstep_correction = Kp_ * (pelvis_pos_err) + Kd_ * (pelvis_vel_err); if (is_left_foot_) { - footstep_correction(1) -= 0.02; + footstep_correction(1) -= 0.03; } else { - footstep_correction(1) += 0.02; + footstep_correction(1) += 0.03; } - footstep_correction(0) -= 0.03; + footstep_correction(0) -= 0.02; Vector3d pelvis_heading_vec = plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) .rotation() diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 0ad38f21c0..05b3a21c49 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -31,6 +31,10 @@ struct OSCRunningGains : OSCGains { std::vector SwingFootW; std::vector SwingFootKp; std::vector SwingFootKd; + // swing foot tracking for the non-touchdown foot + std::vector LiftoffSwingFootW; + std::vector LiftoffSwingFootKp; + std::vector LiftoffSwingFootKd; // pelvis tracking std::vector PelvisW; std::vector PelvisKp; @@ -47,6 +51,9 @@ struct OSCRunningGains : OSCGains { MatrixXd W_swing_foot; MatrixXd K_p_swing_foot; MatrixXd K_d_swing_foot; + MatrixXd W_liftoff_swing_foot; + MatrixXd K_p_liftoff_swing_foot; + MatrixXd K_d_liftoff_swing_foot; MatrixXd W_swing_toe; MatrixXd K_p_swing_toe; MatrixXd K_d_swing_toe; @@ -82,6 +89,9 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(SwingFootW)); a->Visit(DRAKE_NVP(SwingFootKp)); a->Visit(DRAKE_NVP(SwingFootKd)); + a->Visit(DRAKE_NVP(LiftoffSwingFootW)); + a->Visit(DRAKE_NVP(LiftoffSwingFootKp)); + a->Visit(DRAKE_NVP(LiftoffSwingFootKd)); a->Visit(DRAKE_NVP(w_swing_toe)); a->Visit(DRAKE_NVP(swing_toe_kp)); a->Visit(DRAKE_NVP(swing_toe_kd)); @@ -108,6 +118,15 @@ struct OSCRunningGains : OSCGains { K_d_swing_foot = Eigen::Map< Eigen::Matrix>( this->SwingFootKd.data(), 3, 3); + W_liftoff_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->LiftoffSwingFootW.data(), 3, 3); + K_p_liftoff_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->LiftoffSwingFootKp.data(), 3, 3); + K_d_liftoff_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->LiftoffSwingFootKd.data(), 3, 3); W_pelvis = Eigen::Map< Eigen::Matrix>( this->PelvisW.data(), 3, 3); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index fa042c5328..c8c49af40a 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -2,7 +2,7 @@ w_input: 0.0000000000 w_accel: 0.0000 #w_soft_constraint: 1000000 w_soft_constraint: 10.0 -w_input_reg: 0.0001 +w_input_reg: 0.00001 impact_threshold: 0.050 relative_feet: true relative_pelvis: true @@ -23,16 +23,25 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 0.1 +w_hip_yaw: 0.05 hip_yaw_kp: 100 hip_yaw_kd: 20 w_hip_pitch: 5 -hip_pitch_kp: 50 +hip_pitch_kp: 100 hip_pitch_kd: 20 -w_hip_roll: 10 +w_hip_roll: 5 hip_roll_kp: 100 hip_roll_kd: 20 +FootstepKp: + [0.0, 0, + 0, 0.0, + 0, 0] +FootstepKd: + [ 0.05, 0, + 0, 0.04, + 0, 0] + PelvisW: [ 0, 0, 0, 0, 0, 0, @@ -54,14 +63,19 @@ SwingFootKp: 0, 50, 0, 0, 0, 50] SwingFootKd: + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1] +LiftoffSwingFootW: + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] +LiftoffSwingFootKp: + [50, 0, 0, + 0, 50, 0, + 0, 0, 50] +LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, 0, 0, 1] -FootstepKp: - [0.0, 0, - 0, 0.0, - 0, 0] -FootstepKd: - [ 0.1, 0, - 0, 0.04, - 0, 0] + diff --git a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc new file mode 100644 index 0000000000..2517b66a22 --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc @@ -0,0 +1,120 @@ +#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" + +#include "multibody/multibody_utils.h" +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +using std::string; +using std::vector; + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::systems::OutputVector; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib::examples::osc { + +PelvisPitchTrajGenerator::PelvisPitchTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& hip_pitch_traj, + drake::trajectories::PiecewisePolynomial& pelvis_pitch_traj, + int axis, const std::string& system_name) + : plant_(plant), + context_(context), + world_(plant_.world_frame()), + hip_pitch_traj_(hip_pitch_traj), + pelvis_pitch_traj_(pelvis_pitch_traj), + axis_(axis) { + this->set_name(system_name); + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) + .get_index(); + + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + this->DeclareAbstractOutputPort("pelvis_rot_traj_" + std::to_string(axis), + traj_inst, + &PelvisPitchTrajGenerator::CalcTraj); + + DeclarePerStepDiscreteUpdateEvent( + &PelvisPitchTrajGenerator::DiscreteVariableUpdate); +} + +EventStatus PelvisPitchTrajGenerator::DiscreteVariableUpdate( + const Context& context, + DiscreteValues* discrete_state) const { + return EventStatus::Succeeded(); +} + +PiecewisePolynomial PelvisPitchTrajGenerator::GeneratePelvisTraj( + const systems::OutputVector* robot_output, double t, + int fsm_state) const { + VectorXd q = robot_output->GetPositions(); + VectorXd v = robot_output->GetVelocities(); + multibody::SetPositionsIfNew(plant_, q, context_); + + VectorXd correction = VectorXd::Zero(1); + + drake::math::RotationMatrix pelvis_rot = + plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) + .rotation(); + drake::math::RollPitchYawd pelvis_rpy = drake::math::RollPitchYaw(pelvis_rot); + double pelvis_pitch = pelvis_rpy.pitch_angle(); + + // correction << pelvis_pitch + q(7); + correction << pelvis_pitch; + std::vector breaks = hip_pitch_traj_.get_segment_times(); + VectorXd breaks_vector = Map(breaks.data(), breaks.size()); + MatrixXd offset_angles = correction.replicate(1, breaks.size()); + for (int i = 0; i < breaks_vector.size(); ++i) { + offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); + } + PiecewisePolynomial offset_traj = + PiecewisePolynomial::FirstOrderHold(breaks_vector, offset_angles); + return hip_pitch_traj_ - offset_traj; + // return offset_traj; +} + +void PelvisPitchTrajGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // Read in current state + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + // Read in finite state machine + const auto& fsm_state = + this->EvalVectorInput(context, fsm_port_)->get_value()(0); + const auto& clock = + this->EvalVectorInput(context, clock_port_)->get_value()(0); + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (fsm_state == 0 || fsm_state == 1) { + *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); + } +} + +} // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.h b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.h new file mode 100644 index 0000000000..34475b8d0f --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.h @@ -0,0 +1,60 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib::examples::osc { + +class PelvisPitchTrajGenerator : public drake::systems::LeafSystem { + public: + PelvisPitchTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& hip_pitch_traj, + drake::trajectories::PiecewisePolynomial& pelvis_pitch_traj, + int axis, const std::string& system_name); + + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_fsm_input_port() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_clock_input_port() const { + return this->get_input_port(clock_port_); + } + + private: + drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( + const systems::OutputVector* robot_output, double t, int fsm_state) const; + + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::BodyFrame& world_; + + // drake::systems::DiscreteStateIndex prev_fsm_idx_; + + // pelvis trajectory + drake::trajectories::PiecewisePolynomial hip_pitch_traj_; + drake::trajectories::PiecewisePolynomial pelvis_pitch_traj_; + + // A list of pairs of contact body frame and contact point + int axis_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex fsm_port_; + drake::systems::InputPortIndex clock_port_; +}; + +} // namespace dairlib::examples::osc diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c61e4d9fcf..5095d70096 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -12,8 +12,8 @@ #include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" #include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" -//#include "examples/Cassie/osc_run/joint_space_running_gains.h" #include "examples/Cassie/osc_run/osc_running_gains.h" +#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" @@ -58,6 +58,7 @@ using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using drake::trajectories::PiecewisePolynomial; +using examples::osc::PelvisPitchTrajGenerator; using examples::osc::PelvisRollTrajGenerator; using examples::osc::PelvisTransTrajGenerator; using examples::osc_jump::BasicTrajectoryPassthrough; @@ -155,13 +156,15 @@ int DoMain(int argc, char* argv[]) { /**** FSM and contact mode configuration ****/ int left_stance_state = 0; int right_stance_state = 1; - int air_phase = 2; + int right_touchdown_air_phase = 2; + int left_touchdown_air_phase = 3; double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2; double right_support_duration = left_support_duration; double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - dircon_trajectory.GetStateBreaks(1)(0); - vector fsm_states = {left_stance_state, air_phase, right_stance_state, - air_phase, left_stance_state}; + vector fsm_states = {left_stance_state, right_touchdown_air_phase, + right_stance_state, left_touchdown_air_phase, + left_stance_state}; std::cout << "left support duration: " << left_support_duration << std::endl; std::cout << "flight duration: " << air_phase_duration << std::endl; std::cout << "right support duration: " << right_support_duration @@ -206,19 +209,19 @@ int DoMain(int argc, char* argv[]) { plant, left_toe.first, left_toe.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant, left_heel.first, left_heel.second, view_frame, Matrix3d::Identity(), - Vector3d::Zero(), {0, 1, 2}); + plant, left_heel.first, left_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant, right_toe.first, right_toe.second, view_frame, Matrix3d::Identity(), - Vector3d::Zero(), {1, 2}); + plant, right_toe.first, right_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant, right_heel.first, right_heel.second, view_frame, Matrix3d::Identity(), - Vector3d::Zero(), {0, 1, 2}); + plant, right_heel.first, right_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(0, &left_toe_evaluator); - osc->AddStateAndContactPoint(0, &left_heel_evaluator); - osc->AddStateAndContactPoint(1, &right_toe_evaluator); - osc->AddStateAndContactPoint(1, &right_heel_evaluator); + osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); + osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); + osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); + osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); multibody::KinematicEvaluatorSet evaluators(plant); auto left_loop = LeftLoopClosureEvaluator(plant); @@ -371,8 +374,21 @@ int DoMain(int argc, char* argv[]) { "toe_left"); right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(air_phase, "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(air_phase, "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "toe_right"); + + TransTaskSpaceTrackingData left_foot_yz_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_foot_yz_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_foot_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "toe_left"); + right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "toe_right"); TransTaskSpaceTrackingData left_hip_tracking_data( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -384,10 +400,22 @@ int DoMain(int argc, char* argv[]) { "hip_left"); right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "hip_right"); - left_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_left"); - right_hip_tracking_data.AddStateAndPointToTrack(air_phase, "hip_right"); + right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "hip_right"); + left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "hip_left"); + + TransTaskSpaceTrackingData left_hip_yz_tracking_data( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_hip_yz_tracking_data( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "hip_left"); + right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "hip_right"); -// WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); RelativeTranslationTrackingData left_foot_rel_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, @@ -396,18 +424,28 @@ int DoMain(int argc, char* argv[]) { "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, &right_hip_tracking_data); + RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( + "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); + RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( + "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, &stance_foot_tracking_data); left_foot_rel_tracking_data.SetViewFrame(view_frame); right_foot_rel_tracking_data.SetViewFrame(view_frame); + left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); + right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_rel_tracking_data.DisableFeedforwardAccel({2}); - // right_foot_rel_tracking_data.DisableFeedforwardAccel({2}); + left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); if (osc_gains.relative_pelvis) { osc->AddTrackingData(&pelvis_trans_rel_tracking_data); @@ -420,6 +458,10 @@ int DoMain(int argc, char* argv[]) { right_foot_rel_tracking_data.SetImpactInvariantProjection(true); osc->AddTrackingData(&left_foot_rel_tracking_data); osc->AddTrackingData(&right_foot_rel_tracking_data); +// left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); +// right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_yz_rel_tracking_data); + osc->AddTrackingData(&right_foot_yz_rel_tracking_data); } else { left_foot_tracking_data.SetImpactInvariantProjection(true); right_foot_tracking_data.SetImpactInvariantProjection(true); @@ -438,28 +480,41 @@ int DoMain(int argc, char* argv[]) { auto hip_pitch_right_traj_mir = dircon_trajectory.ReconstructMirrorJointTrajectory( pos_map_wo_spr["hip_pitch_right"]); + PiecewisePolynomial pelvis_pitch_traj = + PiecewisePolynomial(VectorXd::Zero(1)); hip_pitch_left_traj_mir.shiftRight(hip_pitch_left_traj.end_time()); hip_pitch_right_traj_mir.shiftRight(hip_pitch_right_traj.end_time()); hip_pitch_left_traj.ConcatenateInTime(hip_pitch_left_traj_mir); hip_pitch_right_traj.ConcatenateInTime(hip_pitch_right_traj_mir); + // auto hip_pitch_left_traj_generator = + // builder.AddSystem( + // hip_pitch_left_traj, "hip_pitch_left_traj_generator"); + // auto hip_pitch_right_traj_generator = + // builder.AddSystem( + // hip_pitch_right_traj, "hip_pitch_right_traj_generator"); auto hip_pitch_left_traj_generator = - builder.AddSystem( - hip_pitch_left_traj, "hip_pitch_left_traj_generator"); + builder.AddSystem( + plant, plant_context.get(), hip_pitch_left_traj, pelvis_pitch_traj, 1, + "hip_pitch_left_traj_generator"); auto hip_pitch_right_traj_generator = - builder.AddSystem( - hip_pitch_right_traj, "hip_pitch_right_traj_generator"); + builder.AddSystem( + plant, plant_context.get(), hip_pitch_right_traj, pelvis_pitch_traj, + 1, "hip_pitch_right_traj_generator"); + JointSpaceTrackingData left_hip_pitch_tracking_data( "hip_pitch_left_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); JointSpaceTrackingData right_hip_pitch_tracking_data( "hip_pitch_right_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); - std::cout << "Hip Pitch KD: " << osc_gains.K_d_hip_pitch << std::endl; - std::cout << "Hip Roll KD: " << osc_gains.K_d_hip_roll << std::endl; left_hip_pitch_tracking_data.AddStateAndJointToTrack( left_stance_state, "hip_pitch_left", "hip_pitch_leftdot"); + left_hip_pitch_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "hip_pitch_left", "hip_pitch_leftdot"); right_hip_pitch_tracking_data.AddStateAndJointToTrack( right_stance_state, "hip_pitch_right", "hip_pitch_rightdot"); + right_hip_pitch_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "hip_pitch_right", "hip_pitch_rightdot"); left_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); right_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); left_hip_pitch_tracking_data.SetImpactInvariantProjection(true); @@ -504,8 +559,12 @@ int DoMain(int argc, char* argv[]) { osc_gains.W_hip_roll, plant, plant); left_hip_roll_tracking_data.AddStateAndJointToTrack( left_stance_state, "hip_roll_left", "hip_roll_leftdot"); + left_hip_roll_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "hip_roll_left", "hip_roll_leftdot"); right_hip_roll_tracking_data.AddStateAndJointToTrack( right_stance_state, "hip_roll_right", "hip_roll_rightdot"); + right_hip_roll_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "hip_roll_right", "hip_roll_rightdot"); left_hip_roll_tracking_data.DisableFeedforwardAccel({0}); right_hip_roll_tracking_data.DisableFeedforwardAccel({0}); left_hip_roll_tracking_data.SetImpactInvariantProjection(true); @@ -536,10 +595,14 @@ int DoMain(int argc, char* argv[]) { left_stance_state, "toe_right", "toe_rightdot"); left_toe_angle_tracking_data.AddStateAndJointToTrack( right_stance_state, "toe_left", "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack(air_phase, "toe_right", - "toe_rightdot"); - left_toe_angle_tracking_data.AddStateAndJointToTrack(air_phase, "toe_left", - "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "toe_right", "toe_rightdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "toe_left", "toe_leftdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data.SetImpactInvariantProjection(true); right_toe_angle_tracking_data.SetImpactInvariantProjection(true); osc->AddTrackingData(&left_toe_angle_tracking_data); @@ -555,8 +618,8 @@ int DoMain(int argc, char* argv[]) { left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); -// left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); -// right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); @@ -623,10 +686,26 @@ int DoMain(int argc, char* argv[]) { hip_roll_left_traj_generator->get_clock_input_port()); builder.Connect(fsm->get_output_port_clock(), hip_roll_right_traj_generator->get_clock_input_port()); + builder.Connect(state_receiver->get_output_port(0), + hip_pitch_left_traj_generator->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + hip_pitch_right_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + hip_pitch_left_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + hip_pitch_right_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_clock(), + hip_pitch_left_traj_generator->get_clock_input_port()); + builder.Connect(fsm->get_output_port_clock(), + hip_pitch_right_traj_generator->get_clock_input_port()); builder.Connect(l_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("right_ft_traj")); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("left_ft_z_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), osc->get_tracking_data_input_port("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 9b26767936..c3482a3a2a 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -40,7 +40,7 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( for (int i = 0; i < states.size(); ++i) { sum += state_durations[i]; accu_state_durations_.push_back(sum); - if (states[i] == 2) { + if (states[i] >= 2) { impact_times_.push_back(sum); impact_states_.push_back(states[i+1]); } From ace9ada5b7b524d734b6f87012177295454ddf56 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 24 Nov 2021 14:22:39 -0500 Subject: [PATCH 032/758] need to work on impact timing --- .../plot_configs/cassie_running_plot.yaml | 4 ++-- .../Cassie/osc_run/osc_running_gains.yaml | 22 +++++++++---------- examples/Cassie/run_osc_running_controller.cc | 4 ++-- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 8f0d002e05..abade990c2 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -12,7 +12,7 @@ plot_floating_base_positions: false plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: false +plot_measured_efforts: true special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [] @@ -22,7 +22,7 @@ plot_qp_costs: true plot_tracking_costs: true tracking_datas_to_plot: pelvis_trans_traj: {'dims': [2], 'derivs': ['vel', 'accel']} - hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} # swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c8c49af40a..635f81ead3 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,15 +1,15 @@ w_input: 0.0000000000 w_accel: 0.0000 #w_soft_constraint: 1000000 -w_soft_constraint: 10.0 -w_input_reg: 0.00001 +w_soft_constraint: 100.0 +w_input_reg: 0.001 impact_threshold: 0.050 relative_feet: true relative_pelvis: true # High level command gains (with radio) -vel_scale_rot: -1 -vel_scale_trans_sagital: 0.25 +vel_scale_rot: -0.5 +vel_scale_trans_sagital: 0.125 vel_scale_trans_lateral: -0.15 # SLIP parameters @@ -25,7 +25,7 @@ swing_toe_kd: 10 w_hip_yaw: 0.05 hip_yaw_kp: 100 -hip_yaw_kd: 20 +hip_yaw_kd: 15 w_hip_pitch: 5 hip_pitch_kp: 100 hip_pitch_kd: 20 @@ -34,11 +34,11 @@ hip_roll_kp: 100 hip_roll_kd: 20 FootstepKp: - [0.0, 0, - 0, 0.0, - 0, 0] + [0.00, 0, + 0, 0.00, + 0, 0] FootstepKd: - [ 0.05, 0, + [ 0.06, 0, 0, 0.04, 0, 0] @@ -56,8 +56,8 @@ PelvisKd: 0, 0, 5] SwingFootW: [1, 0, 0, - 0, 1, 0, - 0, 0, 1] + 0, 5, 0, + 0, 0, 1] SwingFootKp: [50, 0, 0, 0, 50, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 5095d70096..395d510eb6 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -158,10 +158,10 @@ int DoMain(int argc, char* argv[]) { int right_stance_state = 1; int right_touchdown_air_phase = 2; int left_touchdown_air_phase = 3; - double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2; + double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2 - 0.030; double right_support_duration = left_support_duration; double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - - dircon_trajectory.GetStateBreaks(1)(0); + dircon_trajectory.GetStateBreaks(1)(0) + 0.030; vector fsm_states = {left_stance_state, right_touchdown_air_phase, right_stance_state, left_touchdown_air_phase, left_stance_state}; From 83140747520c4623b298b65636c7bc86177bea8b Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 27 Nov 2021 17:45:02 -0500 Subject: [PATCH 033/758] added points position plotting and foot position defaults --- .../pydairlib/analysis/cassie_plot_config.py | 5 ++- .../analysis/cassie_plotting_utils.py | 15 +++++++ .../pydairlib/analysis/log_plotter_cassie.py | 13 ++++++ .../pydairlib/analysis/mbp_plotting_utils.py | 42 +++++++++++++++++++ .../plot_configs/cassie_default_plot.yaml | 5 +++ 5 files changed, 79 insertions(+), 1 deletion(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index d1ad3a99f7..d17571ec21 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -31,7 +31,10 @@ def __init__(self, filename): self.vel_names = data['special_velocities_to_plot'] if data['special_efforts_to_plot']: self.act_names = data['special_efforts_to_plot'] - + if data['foot_positions_to_plot']: + self.foot_positions_to_plot = data['foot_positions_to_plot'] + self.foot_xyz_to_plot = data['foot_xyz_to_plot'] + self.pt_on_foot_to_plot = data['pt_on_foot_to_plot'] self.plot_qp_costs = data['plot_qp_costs'] self.plot_tracking_costs = data['plot_tracking_costs'] self.tracking_datas_to_plot = data['tracking_datas_to_plot'] diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index a30e310caa..8d0f0b62d1 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -38,3 +38,18 @@ def make_plant_and_context(floating_base=True, springs=True): plant.Finalize() return plant, plant.CreateDefaultContext() + + +def get_toe_frames_and_points(plant): + front_contact_pt = np.array((-0.0457, 0.112, 0)) + rear_contact_pt = np.array((0.088, 0, 0)) + mid_contact_pt = 0.5 * (front_contact_pt + rear_contact_pt) + + left_frame = plant.GetBodyByName("toe_left") + right_frame = plant.GetBodyByName("toe_right") + + frames = {"left": left_frame, "right": right_frame} + pts = {"rear": rear_contact_pt, "mid": mid_contact_pt, + "front": front_contact_pt} + + return frames, pts diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 86ab694d69..412ffc9169 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -81,6 +81,7 @@ def main(): plot_config.act_names, t_x_slice, act_map) + ''' Plot OSC ''' if plot_config.plot_qp_costs: mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) if plot_config.plot_tracking_costs: @@ -93,6 +94,18 @@ def main(): mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) + if plot_config.foot_positions_to_plot: + _, pts_map = cassie_plots.get_toe_frames_and_points(plant) + foot_frames = [] + dims = {} + pts = {} + for pos in plot_config.foot_positions_to_plot: + foot_frames.append('toe_' + pos) + dims['toe_' + pos] = plot_config.foot_xyz_to_plot[pos] + pts['toe_' + pos] = pts_map[plot_config.pt_on_foot_to_plot] + + mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, + foot_frames, pts, dims) plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index e663d44720..c921ffbdc2 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -63,6 +63,21 @@ def process_effort_channel(data): return {'t_u': np.array(t), 'u': np.array(u)} +def make_point_positions_from_q( + q, plant, context, frame, pt_on_frame, frame_to_calc_position_in=None): + + if frame_to_calc_position_in is None: + frame_to_calc_position_in = plant.world_frame() + + pos = np.zeros((q.shape[0], 3)) + for i, generalized_pos in enumerate(q): + plant.SetPositions(context, generalized_pos) + pos[i] = plant.CalcPointsPositions(context, frame, pt_on_frame, + frame_to_calc_position_in).ravel() + + return pos + + def process_osc_channel(data): t_osc = [] input_cost = [] @@ -203,6 +218,33 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): ylabel='Efforts (Nm)', title='Select Joint Efforts') +def plot_points_positions(robot_output, time_slice, plant, context, frame_names, + pts, dims): + + dim_map = ['_x', '_y', '_z'] + data_dict = {'t': robot_output['t_x']} + legend_entries = {} + for name in frame_names: + frame = plant.GetBodyByName(name).body_frame() + pt = pts[name] + data_dict[name] = make_point_positions_from_q(robot_output['q'], + plant, context, frame, pt) + legend_entries[name] = [name + dim_map[dim] for dim in dims[name]] + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + data_dict, + 't', + time_slice, + frame_names, + dims, + legend_entries, + {'title': 'Point Positions', + 'xlabel': 'time (s)', + 'ylabel': 'pos (m)'}, ps) + + return ps + + def plot_tracking_costs(osc_debug, time_slice): ps = plot_styler.PlotStyler() data_dict = \ diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index a8f562aff2..dcf0ea7d02 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -17,6 +17,11 @@ special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [] +# Foot position plots +foot_positions_to_plot: ['right', 'left'] +foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} +pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' + # Desired osc plots plot_qp_costs: true plot_tracking_costs: true From e05fdd0071f1ef2a27c8992af3b2b8c64aa6e971 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Sat, 27 Nov 2021 17:46:22 -0500 Subject: [PATCH 034/758] minor comment --- bindings/pydairlib/analysis/log_plotter_cassie.py | 1 + 1 file changed, 1 insertion(+) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 412ffc9169..7033fabb64 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -94,6 +94,7 @@ def main(): mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) + ''' Plot Foot Positions ''' if plot_config.foot_positions_to_plot: _, pts_map = cassie_plots.get_toe_frames_and_points(plant) foot_frames = [] From 70e186af8a8501f98d7145f9dad09902e07e8d40 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Nov 2021 14:33:42 -0500 Subject: [PATCH 035/758] jumping with state estimator is fine now, need to work on stress tests --- .../plot_configs/cassie_jumping_plot.yaml | 7 +++--- .../plot_configs/cassie_running_plot.yaml | 7 +++--- examples/Cassie/cassie_state_estimator.cc | 8 +++++-- .../Cassie/osc_jump/osc_jumping_gains.yaml | 8 +++---- .../Cassie/osc_run/foot_traj_generator.cc | 6 ++--- examples/Cassie/osc_run/foot_traj_generator.h | 9 ++++++++ examples/Cassie/osc_run/osc_running_gains.h | 5 ++++ .../Cassie/osc_run/osc_running_gains.yaml | 23 +++++++++++-------- examples/Cassie/run_osc_running_controller.cc | 9 ++++++-- .../osc/operational_space_control.cc | 2 +- 10 files changed, 56 insertions(+), 28 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 5da6f782d3..18c82a5c3e 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -12,14 +12,15 @@ plot_floating_base_positions: false plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: false +plot_measured_efforts: true special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [] # Desired osc plots plot_qp_costs: false -plot_tracking_costs: false +plot_tracking_costs: true tracking_datas_to_plot: - left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + left_ft_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} + right_ft_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} # swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index abade990c2..cd8a04c77e 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -21,8 +21,9 @@ special_efforts_to_plot: [] plot_qp_costs: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['vel', 'accel']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['accel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} - left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} - left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} + hip_roll_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} +# left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} +# left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} # swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 31b7e5ee73..55c4f3f0aa 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -225,8 +225,9 @@ void CassieStateEstimator::solveFourbarLinkage( double spring_length = rod_on_heel_springs_[0].first.norm(); // Spring rest angle offset double spring_rest_offset = - atan(rod_on_heel_springs_[0].first(1) / rod_on_heel_springs_[0].first(0)); - + atan2(rod_on_heel_springs_[0].first(1), rod_on_heel_springs_[0].first(0)); +// std::cout << "spring length" << spring_length << std::endl; +// std::cout << "spring rest offset" << spring_rest_offset << std::endl; plant_.SetPositions(context_.get(), q); for (int i = 0; i < 2; i++) { @@ -299,6 +300,9 @@ void CassieStateEstimator::solveFourbarLinkage( else *right_heel_spring = spring_deflect_sign * heel_spring_angle - spring_rest_offset; +// std::cout << "terms: " << std::endl; +// std::cout << r_sol_wrt_heel_base << std::endl; +// std::cout << spring_rest_dir_wrt_spring_base << std::endl; } // end for } diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 1c9e068656..6c0940df2f 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,8 +1,8 @@ w_input: 0.000 w_accel: 0.0000001 -w_input_reg: 0.00 +w_input_reg: 0.01 w_soft_constraint: 100 -x_offset: -0.025 +x_offset: 0.00 relative_feet: true mu: 0.8 @@ -31,7 +31,7 @@ FlightFootW: 0, 1, 0, 0, 0, 1] CoMKp: - [10, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 50] CoMKd: @@ -52,6 +52,6 @@ FlightFootKp: 0, 0, 100] FlightFootKd: [ 0, 0, 0, - 0, 0, 0, + 0, 0, 0, 0, 0, 0] diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 3ddd4c3581..f4f04d5d05 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -95,11 +95,11 @@ void FootTrajGenerator::AddRaibertCorrection( VectorXd footstep_correction = Kp_ * (pelvis_pos_err) + Kd_ * (pelvis_vel_err); if (is_left_foot_) { - footstep_correction(1) -= 0.03; + footstep_correction(1) -= center_line_offset_; } else { - footstep_correction(1) += 0.03; + footstep_correction(1) += center_line_offset_; } - footstep_correction(0) -= 0.02; + footstep_correction(0) += footstep_offset_; Vector3d pelvis_heading_vec = plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) .rotation() diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index c33c1ca30a..f9e775eb0a 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -34,6 +34,11 @@ class FootTrajGenerator : public drake::systems::LeafSystem { Kd_ = Kd; }; + void SetFootPlacementOffsets(double center_line_offset, double footstep_offset){ + center_line_offset_ = center_line_offset; + footstep_offset_ = footstep_offset; + } + private: drake::trajectories::PiecewisePolynomial GenerateFlightTraj( const Eigen::VectorXd& x, double t) const; @@ -49,6 +54,10 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::Frame& world_; const drake::multibody::Frame& hip_frame_; + // Foot placement constants + double center_line_offset_; + double footstep_offset_; + // Raibert Footstep Gains Eigen::MatrixXd Kp_ = Eigen::MatrixXd::Zero(2, 2); Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(2, 2); diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 05b3a21c49..e75e12d99f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -27,6 +27,9 @@ struct OSCRunningGains : OSCGains { double k_leg; double b_leg; + double center_line_offset; + double footstep_offset; + // swing foot tracking std::vector SwingFootW; std::vector SwingFootKp; @@ -80,6 +83,8 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(rest_length)); a->Visit(DRAKE_NVP(k_leg)); a->Visit(DRAKE_NVP(b_leg)); + a->Visit(DRAKE_NVP(center_line_offset)); + a->Visit(DRAKE_NVP(footstep_offset)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 635f81ead3..b212085ea4 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0000000000 w_accel: 0.0000 #w_soft_constraint: 1000000 -w_soft_constraint: 100.0 +w_soft_constraint: 10000.0 w_input_reg: 0.001 impact_threshold: 0.050 relative_feet: true @@ -9,7 +9,7 @@ relative_pelvis: true # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.125 +vel_scale_trans_sagital: 1.0 vel_scale_trans_lateral: -0.15 # SLIP parameters @@ -23,23 +23,26 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 0.05 +w_hip_yaw: 200 hip_yaw_kp: 100 hip_yaw_kd: 15 w_hip_pitch: 5 hip_pitch_kp: 100 -hip_pitch_kd: 20 +hip_pitch_kd: 10 w_hip_roll: 5 hip_roll_kp: 100 -hip_roll_kd: 20 +hip_roll_kd: 10 +# Foot placement parameters +footstep_offset: -0.025 +center_line_offset: 0.05 FootstepKp: [0.00, 0, 0, 0.00, 0, 0] FootstepKd: [ 0.06, 0, - 0, 0.04, + 0, 0.03, 0, 0] PelvisW: @@ -64,15 +67,15 @@ SwingFootKp: 0, 0, 50] SwingFootKd: [ 1, 0, 0, - 0, 1, 0, + 0, 1, 0, 0, 0, 1] LiftoffSwingFootW: - [1, 0, 0, - 0, 1, 0, + [0.1, 0, 0, + 0, 0.5, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, - 0, 50, 0, + 0, 25, 0, 0, 0, 50] LiftoffSwingFootKd: [ 1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 395d510eb6..aca37cae22 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -87,6 +87,7 @@ DEFINE_bool(use_radio, false, DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); +DEFINE_double(fsm_time_offset, 0.0, "Time (s) in the fsm to move from the stance phase to the flight phase"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -158,10 +159,10 @@ int DoMain(int argc, char* argv[]) { int right_stance_state = 1; int right_touchdown_air_phase = 2; int left_touchdown_air_phase = 3; - double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2 - 0.030; + double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2 - FLAGS_fsm_time_offset; double right_support_duration = left_support_duration; double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - - dircon_trajectory.GetStateBreaks(1)(0) + 0.030; + dircon_trajectory.GetStateBreaks(1)(0) + FLAGS_fsm_time_offset; vector fsm_states = {left_stance_state, right_touchdown_air_phase, right_stance_state, left_touchdown_air_phase, left_stance_state}; @@ -351,6 +352,10 @@ int DoMain(int argc, char* argv[]) { osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_p_footstep, osc_gains.K_d_footstep); + l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.center_line_offset, + osc_gains.footstep_offset); + r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.center_line_offset, + osc_gains.footstep_offset); TransTaskSpaceTrackingData pelvis_tracking_data( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 653c918443..43fdb7ed8c 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -461,7 +461,7 @@ void OperationalSpaceControl::Build() { drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); - solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-7); solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-6); solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-6); From 59e45fba8ae53f9bbe64cea4f05cf06cf1569ea6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 30 Nov 2021 10:34:18 -0500 Subject: [PATCH 036/758] parameters for meeting with michael --- examples/Cassie/dispatcher_robot_out.cc | 2 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 4 +-- .../Cassie/osc_run/foot_traj_generator.cc | 27 ++++++++++--------- examples/Cassie/osc_run/osc_running_gains.h | 4 +-- .../Cassie/osc_run/osc_running_gains.yaml | 22 +++++++-------- 5 files changed, 30 insertions(+), 29 deletions(-) diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 105836e7f1..b9fc211d3a 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -363,7 +363,7 @@ int do_main(int argc, char* argv[]) { // Hacks -- for some reason, sometimes the lcm from Mujoco is not in order if (prev_time > time) { - std::cout << time << std::endl; + std::cout << "time: " << time << std::endl; continue; } diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 6c0940df2f..71402735d3 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -2,7 +2,7 @@ w_input: 0.000 w_accel: 0.0000001 w_input_reg: 0.01 w_soft_constraint: 100 -x_offset: 0.00 +x_offset: -0.02 relative_feet: true mu: 0.8 @@ -31,7 +31,7 @@ FlightFootW: 0, 1, 0, 0, 0, 1] CoMKp: - [50, 0, 0, + [25, 0, 0, 0, 50, 0, 0, 0, 50] CoMKd: diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index f4f04d5d05..792669656b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -87,19 +87,6 @@ void FootTrajGenerator::AddRaibertCorrection( VectorXd q = robot_output->GetPositions(); multibody::SetPositionsIfNew(plant_, q, context_); - Vector2d desired_pelvis_pos = {0.0, 0}; - VectorXd pelvis_pos = robot_output->GetPositions().segment(4, 2); - VectorXd pelvis_vel = robot_output->GetVelocities().segment(3, 2); - VectorXd pelvis_pos_err = pelvis_pos - desired_pelvis_pos; - VectorXd pelvis_vel_err = pelvis_vel - desired_pelvis_vel; - VectorXd footstep_correction = - Kp_ * (pelvis_pos_err) + Kd_ * (pelvis_vel_err); - if (is_left_foot_) { - footstep_correction(1) -= center_line_offset_; - } else { - footstep_correction(1) += center_line_offset_; - } - footstep_correction(0) += footstep_offset_; Vector3d pelvis_heading_vec = plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) .rotation() @@ -110,6 +97,20 @@ void FootTrajGenerator::AddRaibertCorrection( rot << cos(approx_pelvis_yaw), -sin(approx_pelvis_yaw), 0, sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; + Vector3d desired_pelvis_pos = {0.0, 0, 0}; + VectorXd pelvis_pos = robot_output->GetPositions().segment(4, 3); + VectorXd pelvis_vel = robot_output->GetVelocities().segment(3, 3); + VectorXd pelvis_pos_err = rot.transpose() * pelvis_pos - desired_pelvis_pos; + VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; + VectorXd footstep_correction = + Kp_ * (pelvis_pos_err) + Kd_ * (pelvis_vel_err); + if (is_left_foot_) { + footstep_correction(1) -= center_line_offset_; + } else { + footstep_correction(1) += center_line_offset_; + } + footstep_correction(0) += footstep_offset_; + std::vector breaks = traj->get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); VectorXd new_samples = VectorXd(6); diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index e75e12d99f..b7beeb366b 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -143,10 +143,10 @@ struct OSCRunningGains : OSCGains { this->PelvisKd.data(), 3, 3); K_p_footstep = Eigen::Map< Eigen::Matrix>( - this->FootstepKp.data(), 3, 2); + this->FootstepKp.data(), 3, 3); K_d_footstep = Eigen::Map< Eigen::Matrix>( - this->FootstepKd.data(), 3, 2); + this->FootstepKd.data(), 3, 3); W_swing_toe = this->w_swing_toe * MatrixXd::Identity(1, 1); K_p_swing_toe = this->swing_toe_kp * MatrixXd::Identity(1, 1); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index b212085ea4..f3f8990644 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -9,7 +9,7 @@ relative_pelvis: true # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 1.0 +vel_scale_trans_sagital: 0.5 vel_scale_trans_lateral: -0.15 # SLIP parameters @@ -30,20 +30,20 @@ w_hip_pitch: 5 hip_pitch_kp: 100 hip_pitch_kd: 10 w_hip_roll: 5 -hip_roll_kp: 100 +hip_roll_kp: 50 hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.025 -center_line_offset: 0.05 +footstep_offset: -0.033 +center_line_offset: 0.06 FootstepKp: - [0.00, 0, - 0, 0.00, - 0, 0] + [0.00, 0, 0, + 0, 0.000, 0, + 0, 0, 0] FootstepKd: - [ 0.06, 0, - 0, 0.03, - 0, 0] + [ 0.02, 0, 0, + 0, 0.031, 0, + 0, 0, 0] PelvisW: [ 0, 0, 0, @@ -74,7 +74,7 @@ LiftoffSwingFootW: 0, 0.5, 0, 0, 0, 1] LiftoffSwingFootKp: - [50, 0, 0, + [25, 0, 0, 0, 25, 0, 0, 0, 50] LiftoffSwingFootKd: From 33c67939d507f23e3409124373f29e69e84ddb1f Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Dec 2021 13:54:50 -0500 Subject: [PATCH 037/758] removing unused slip params --- examples/Cassie/osc_run/osc_running_gains.h | 4 ---- examples/Cassie/osc_run/osc_running_gains.yaml | 8 +++----- examples/Cassie/osc_run/pelvis_trans_traj_generator.h | 6 +----- examples/Cassie/run_osc_running_controller.cc | 5 +++-- 4 files changed, 7 insertions(+), 16 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index b7beeb366b..231279dba8 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -24,8 +24,6 @@ struct OSCRunningGains : OSCGains { bool relative_feet; bool relative_pelvis; double rest_length; - double k_leg; - double b_leg; double center_line_offset; double footstep_offset; @@ -81,8 +79,6 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); a->Visit(DRAKE_NVP(rest_length)); - a->Visit(DRAKE_NVP(k_leg)); - a->Visit(DRAKE_NVP(b_leg)); a->Visit(DRAKE_NVP(center_line_offset)); a->Visit(DRAKE_NVP(footstep_offset)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index f3f8990644..78f9395818 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -14,8 +14,6 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.9 -k_leg: -750 -b_leg: 1 mu: 0.8 @@ -34,7 +32,7 @@ hip_roll_kp: 50 hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.033 +footstep_offset: -0.045 center_line_offset: 0.06 FootstepKp: [0.00, 0, 0, @@ -42,7 +40,7 @@ FootstepKp: 0, 0, 0] FootstepKd: [ 0.02, 0, 0, - 0, 0.031, 0, + 0, 0.041, 0, 0, 0, 0] PelvisW: @@ -67,7 +65,7 @@ SwingFootKp: 0, 0, 50] SwingFootKd: [ 1, 0, 0, - 0, 1, 0, + 0, 3, 0, 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index ba7b77b2da..4038395f20 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -31,11 +31,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { return this->get_input_port(clock_port_); } - void SetSLIPParams(double rest_length, double k_leg, double b_leg){ - rest_length_ = rest_length; - k_leg_ = k_leg; - b_leg_ = rest_length; - } + void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } private: drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index aca37cae22..ee34e2c87b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -340,8 +340,9 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant, plant_context.get(), pelvis_trans_traj, feet_contact_points, osc_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length, - osc_gains.k_leg, osc_gains.b_leg); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + // osc_gains.k_leg, + // osc_gains.b_leg); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "hip_left", true, l_foot_trajectory, l_hip_trajectory, osc_gains.relative_feet); From 00679d1cfec2682131ac374d5f87274fbf11e7ca Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Thu, 2 Dec 2021 13:17:09 -0500 Subject: [PATCH 038/758] add NaN mask to only plot tracking_datas when active --- bindings/pydairlib/analysis/osc_debug.py | 21 +++++++++++++++++++-- 1 file changed, 19 insertions(+), 2 deletions(-) diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 7d6cdbdebc..8cb04550a5 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -1,9 +1,10 @@ import numpy as np - +from math import nan # Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays class lcmt_osc_tracking_data_t: - def __init__(self): + def __init__(self, gap_threshold=0.01): + self.t_thresh=gap_threshold self.t = [] self.y_dim = 0 self.name = "" @@ -19,6 +20,22 @@ def __init__(self): self.yddot_command_sol = [] def append(self, msg, t): + self.y_dim = len(msg.y) + self.ydot_dim = len(msg.ydot) + + if self.t and (t - self.t[-1]) > self.t_thresh: + self.t.append(nan) + self.is_active.append(nan) + self.y.append([nan for _ in range(self.y_dim)]) + self.y_des.append([nan for _ in range(self.y_dim)]) + self.error_y.append([nan for _ in range(self.ydot_dim)]) + self.ydot.append([nan for _ in range(self.ydot_dim)]) + self.ydot_des.append([nan for _ in range(self.ydot_dim)]) + self.error_ydot.append([nan for _ in range(self.ydot_dim)]) + self.yddot_des.append([nan for _ in range(self.ydot_dim)]) + self.yddot_command.append([nan for _ in range(self.ydot_dim)]) + self.yddot_command_sol.append([nan for _ in range(self.ydot_dim)]) + self.t.append(t) self.is_active.append(msg.is_active) self.y.append(msg.y) From 68277281aa4d0e91527d25701356e4607743a65a Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Dec 2021 13:28:41 -0500 Subject: [PATCH 039/758] updating plotting script to not plot inactive tracking data --- .../pydairlib/analysis/plot_configs/cassie_running_plot.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index cd8a04c77e..0e507ec9dc 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -17,6 +17,11 @@ special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [] +# Foot position plots +foot_positions_to_plot: ['right', 'left'] +foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} +pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' + # Desired osc plots plot_qp_costs: true plot_tracking_costs: true From 472833636e08882d3ea3e59db5e9f8b3bee91efe Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Dec 2021 16:57:27 -0500 Subject: [PATCH 040/758] generalizing input supervisor --- .../director_scripts/controller_status.py | 69 +++++++++ examples/Cassie/dispatcher_robot_in.cc | 29 +++- examples/Cassie/input_supervisor.cc | 132 +++++++----------- examples/Cassie/input_supervisor.h | 33 +++-- examples/Cassie/integration_test.pmd | 29 +++- examples/Cassie/run_controller_switch.cc | 3 +- examples/Cassie/test/input_supervisor_test.cc | 46 +----- lcmtypes/lcmt_input_supervisor_status.lcm | 7 +- multibody/multibody_utils.cc | 4 +- 9 files changed, 196 insertions(+), 156 deletions(-) create mode 100644 examples/Cassie/director_scripts/controller_status.py diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py new file mode 100644 index 0000000000..d421dea56f --- /dev/null +++ b/examples/Cassie/director_scripts/controller_status.py @@ -0,0 +1,69 @@ +# Note that this script runs in the main context of drake-visulizer, +# where many modules and variables already exist in the global scope. +from director import lcmUtils +from director import applogic +import time +import dairlib.lcmt_robot_output + + +class InputSupervisorVisualizer(object): + + def __init__(self): + self._name = "Input Supervisor Visualizer" + self._real_time = [] + self._msg_time = [] + self._subscriber = None + self._current_channel_ = "" + + self.set_enabled(True) + + def add_subscriber(self): + if (self._subscriber is not None): + return + + channel = "INPUT_SUPERVISOR_STATUS" + + self._subscriber = lcmUtils.addSubscriber( + channel, + messageClass=dairlib.lcmt_input_supervisor_status, + callback=self.handle_message) + + def remove_subscriber(self): + if (self._subscriber is None): + return + + lcmUtils.removeSubscriber(self._subscriber) + self._subscriber = None + vis.updateText('', 'text') + + def is_enabled(self): + return self._subscriber is not None + + def set_enabled(self, enable): + if enable: + self.add_subscriber() + else: + self.remove_subscriber() + + def handle_message(self, msg): + shutdown = msg.shutdown + + status_list = ["shutdown: %i" % shutdown] + for error_flag_idx in range(msg.num_status): + status_list.append(msg.status_names[error_flag_idx] + ': ' + str(msg.status_states[error_flag_idx])) + + vis.updateText("\n".join(status_list), 'contact_text') + +def init_visualizer(): + viz = InputSupervisorVisualizer() + # vis.addText('supervisor_text') + + # Adds to the "Tools" menu. + applogic.MenuActionToggleHelper( + 'Tools', viz._name, + viz.is_enabled, viz.set_enabled) + return viz + + +# Creates the visualizer when this script is executed. +viz = init_visualizer() diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 62a6a9c7c3..79b81e4518 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -55,6 +55,9 @@ DEFINE_string(control_channel_name_2, "OSC_STANDING", "The name of the lcm channel that sends Cassie's state"); DEFINE_string(control_channel_name_3, "OSC_WALKING", "The name of the lcm channel that sends Cassie's state"); +DEFINE_bool( + sim, false, + "Whether or not this dispatcher is being used with the simulated robot"); // Cassie model parameter DEFINE_bool(floating_base, true, "Fixed or floating base model"); @@ -76,6 +79,10 @@ int do_main(int argc, char* argv[]) { true /*spring model*/, false /*loop closure*/); plant.Finalize(); + std::cout << "channel_1: " << FLAGS_control_channel_name_1 << std::endl; + std::cout << "channel_2: " << FLAGS_control_channel_name_2 << std::endl; + std::cout << "channel_3: " << FLAGS_control_channel_name_3 << std::endl; + // Channel name of the input switch std::string switch_channel = "INPUT_SWITCH"; @@ -108,8 +115,8 @@ int do_main(int argc, char* argv[]) { } auto input_supervisor = builder.AddSystem( - plant, FLAGS_max_joint_velocity, input_supervisor_update_period, - FLAGS_supervisor_N, input_limit); + plant, FLAGS_control_channel_name_1, FLAGS_max_joint_velocity, + input_supervisor_update_period, FLAGS_supervisor_N, input_limit); builder.Connect(state_receiver->get_output_port(0), input_supervisor->get_input_port_state()); builder.Connect(command_receiver->get_output_port(0), @@ -136,15 +143,23 @@ int do_main(int argc, char* argv[]) { // Create and connect LCM command echo to network auto net_command_sender = builder.AddSystem(plant); - auto net_command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - "NETWORK_CASSIE_INPUT", &lcm_network, {TriggerType::kPeriodic}, - FLAGS_pub_rate)); + + LcmPublisherSystem* command_pub; + if (FLAGS_sim) { + command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); + } else { + command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "NETWORK_CASSIE_INPUT", &lcm_network, {TriggerType::kPeriodic}, + FLAGS_pub_rate)); + } builder.Connect(input_supervisor->get_output_port_command(), net_command_sender->get_input_port(0)); - builder.Connect(*net_command_sender, *net_command_pub); + builder.Connect(*net_command_sender, *command_pub); // Finish building the diagram auto owned_diagram = builder.Build(); diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index c7cb0546c5..a7648a3d3d 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -17,12 +17,13 @@ using systems::TimestampedVector; InputSupervisor::InputSupervisor( const drake::multibody::MultibodyPlant& plant, - double max_joint_velocity, double update_period, - int min_consecutive_failures, double input_limit) + const std::string initial_channel, double max_joint_velocity, + double update_period, int min_consecutive_failures, double input_limit) : plant_(plant), num_actuators_(plant_.num_actuators()), num_positions_(plant_.num_positions()), num_velocities_(plant_.num_velocities()), + current_channel_(initial_channel), min_consecutive_failures_(min_consecutive_failures), max_joint_velocity_(max_joint_velocity), input_limit_(input_limit) { @@ -70,20 +71,19 @@ InputSupervisor::InputSupervisor( prev_efforts_index_ = DeclareDiscreteState(num_actuators_); + error_indices_["controller_delay"] = 0; + error_indices_["soft_estop"] = 1; + error_indices_["is_nan"] = 2; + error_indices_["consecutive_failures"] = 3; + error_indices_["controller_flag"] = 4; + // Create error flags as discrete state n_fails_index_ = DeclareDiscreteState(1); - status_index_ = DeclareDiscreteState(1); switch_time_index_ = DeclareDiscreteState(1); prev_efforts_time_index_ = DeclareDiscreteState(1); - error_shutdown_index_ = DeclareDiscreteState(1); - controller_msg_delay_index_ = DeclareDiscreteState(1); - soft_estop_trigger_index_ = DeclareDiscreteState(1); - is_nan_index_ = DeclareDiscreteState(1); - consecutive_failures_index_ = DeclareDiscreteState(1); + shutdown_index_ = DeclareDiscreteState(1); - error_indices_ = {error_shutdown_index_, controller_msg_delay_index_, - soft_estop_trigger_index_, is_nan_index_, - consecutive_failures_index_}; + error_indices_index_ = DeclareDiscreteState(error_indices_.size()); K_ = plant_.MakeActuationMatrix().transpose(); K_ *= kEStopGain; @@ -104,28 +104,11 @@ void InputSupervisor::SetMotorTorques(const Context& context, const auto& cassie_out = this->EvalInputValue( context, cassie_input_port_); - // bool is_error = context.get_discrete_state(n_fails_index_)[0] >= - // min_consecutive_failures_; - // is_error = - // is_error || (command->get_timestamp() - - // context.get_discrete_state(prev_efforts_time_index_)[0] - // > - // kMaxControllerDelay); - // is_error = - // is_error || context.get_discrete_state(soft_estop_trigger_index_)[0]; - // is_error = is_error || context.get_discrete_state(is_nan_index_)[0]; - // if ((command->get_timestamp() - - // context.get_discrete_state(prev_efforts_time_index_)[0] > - // kMaxControllerDelay)) { - // std::cout << "Delay between controller commands is too long, shutting - // down" - // << std::endl; - // } - // iterate through all the possible error flags bool is_error = false; - for (int error_flag_index_ : error_indices_) { - is_error = is_error || context.get_discrete_state(error_flag_index_)[0]; + for (const auto& error_flags : error_indices_) { + is_error = is_error || context.get_discrete_state().get_value( + error_indices_index_)[error_flags.second]; } // If the soft estop signal is triggered, applying only damping regardless of @@ -184,35 +167,16 @@ void InputSupervisor::SetStatus( const TimestampedVector* command = (TimestampedVector*)this->EvalVectorInput(context, command_input_port_); - output->status = int(context.get_discrete_state(status_index_)[0]); output->utime = command->get_timestamp() * 1e6; - output->vel_limit = bool(context.get_discrete_state(status_index_)[0]); - - if (input_limit_ != std::numeric_limits::max()) { - for (int i = 0; i < command->get_data().size(); i++) { - double command_value = command->get_data()(i); - if (command_value > input_limit_ || command_value < -input_limit_) { - output->status += 2; - output->act_limit = true; - break; - } - } - } - - // Shutdown is/will soon be active (the status flag is set in a separate loop - // from the actual motor torques so the update of the status bit could be - // slightly off - if (context.get_discrete_state(n_fails_index_)[0] >= - min_consecutive_failures_) { - output->status += 4; - output->shutdown = true; - } - - if ((command->get_timestamp() - - context.get_discrete_state(prev_efforts_time_index_)[0] > - kMaxControllerDelay)) { - output->act_delay = true; - output->shutdown = true; + output->shutdown = context.get_discrete_state().get_value(shutdown_index_)[0]; + output->num_status = error_indices_.size(); + output->status_names = std::vector(error_indices_.size()); + output->status_states = std::vector(error_indices_.size()); + for (const auto& error_flags : error_indices_) { + output->status_names[error_flags.second] = error_flags.first; + output->status_states[error_flags.second] = + context.get_discrete_state().get_value( + error_indices_index_)[error_flags.second]; } } @@ -231,37 +195,47 @@ void InputSupervisor::UpdateErrorFlag( // Note the += operator works as an or operator because we only check if the // error flag != 0 - discrete_state->get_mutable_vector(error_shutdown_index_)[0] += + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("controller_flag")] = controller_error->error_code != 0; - // && - // controller_error->controller_channel == current_channel_); - discrete_state->get_mutable_vector(controller_msg_delay_index_)[0] += + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("controller_delay")] = (command->get_timestamp() - context.get_discrete_state(prev_efforts_time_index_)[0] > kMaxControllerDelay); - discrete_state->get_mutable_vector(is_nan_index_)[0] += + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("is_nan")] = command->get_data().array().isNaN().any(); - discrete_state->get_mutable_vector(consecutive_failures_index_)[0] += + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("consecutive_failures")] = context.get_discrete_state(n_fails_index_)[0] >= min_consecutive_failures_; CheckRadio(context, discrete_state); CheckVelocities(context, discrete_state); + bool is_error = false; + for (const auto& error_flags : error_indices_) { + is_error = is_error || context.get_discrete_state().get_value( + error_indices_index_)[error_flags.second]; + } + discrete_state->get_mutable_value(shutdown_index_)[0] = is_error; + // When receiving a new controller switch message, record the time - if (discrete_state->get_mutable_vector(switch_time_index_)[0] < + if (discrete_state->get_mutable_value(switch_time_index_)[0] < controller_switch->utime * 1e-6) { std::cout << "Got new switch message" << std::endl; - discrete_state->get_mutable_vector(switch_time_index_)[0] = + current_channel_ = controller_switch->channel; + discrete_state->get_mutable_value(switch_time_index_)[0] = controller_switch->utime * 1e-6; blend_duration_ = controller_switch->blend_duration; } if (command->get_timestamp() - - discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] > + discrete_state->get_mutable_value(prev_efforts_time_index_)[0] > kMaxControllerDelay) { - discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] = 0.0; + discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = 0.0; } else { - discrete_state->get_mutable_vector(prev_efforts_time_index_)[0] = + discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = command->get_timestamp(); } @@ -269,8 +243,8 @@ void InputSupervisor::UpdateErrorFlag( // efforts if (command->get_timestamp() - controller_switch->utime * 1e-6 >= blend_duration_) { - discrete_state->get_mutable_vector(prev_efforts_index_) - .get_mutable_value() = command->get_value(); + discrete_state->get_mutable_value(prev_efforts_index_) = + command->get_value(); } } @@ -281,28 +255,25 @@ void InputSupervisor::CheckVelocities( (OutputVector*)this->EvalVectorInput(context, state_input_port_); const Eigen::VectorXd& velocities = state->GetVelocities(); - if (discrete_state->get_vector(n_fails_index_)[0] < + if (discrete_state->get_value(n_fails_index_)[0] < min_consecutive_failures_) { // If any velocity is above the threshold, set the error flag bool is_velocity_error = (velocities.array() > max_joint_velocity_).any() || (velocities.array() < -max_joint_velocity_).any(); if (is_velocity_error) { // Increment counter - discrete_state->get_mutable_vector(n_fails_index_)[0] += 1; - // Using the discrete state which is a vector of doubles to store a bool - discrete_state->get_mutable_vector(status_index_)[0] = double(true); + discrete_state->get_mutable_value(n_fails_index_)[0] += 1; std::cout << "Error! Velocity has exceeded the threshold of " << max_joint_velocity_ << std::endl; std::cout << "Consecutive error " - << discrete_state->get_vector(n_fails_index_)[0] << " of " + << discrete_state->get_value(n_fails_index_)[0] << " of " << min_consecutive_failures_ << std::endl; std::cout << "Velocity vector: " << std::endl << velocities << std::endl << std::endl; } else { // Reset counter - discrete_state->get_mutable_vector(n_fails_index_)[0] = 0; - discrete_state->get_mutable_vector(status_index_)[0] = double(false); + discrete_state->get_mutable_value(n_fails_index_)[0] = 0; } } } @@ -313,7 +284,8 @@ void InputSupervisor::CheckRadio( const auto& cassie_out = this->EvalInputValue( context, cassie_input_port_); if (cassie_out->pelvis.radio.channel[15] == -1) { - discrete_state->get_mutable_vector(soft_estop_trigger_index_)[0] = 1; + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("soft_estop")] = 1; } } diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index 47672f5374..f67c26d470 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -40,6 +40,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // replaced with a joint-specific vectors. explicit InputSupervisor( const drake::multibody::MultibodyPlant& plant, + std::string initial_channel, double max_joint_velocity, double update_period, int min_consecutive_failures = 1, double input_limit = std::numeric_limits::max()); @@ -87,6 +88,8 @@ class InputSupervisor : public drake::systems::LeafSystem { void SetStatus(const drake::systems::Context& context, dairlib::lcmt_input_supervisor_status* output) const; + + void CheckVelocities(const drake::systems::Context &context, drake::systems::DiscreteValues* discrete_state) const; void CheckRadio(const drake::systems::Context &context, drake::systems::DiscreteValues* discrete_state) const; @@ -95,33 +98,37 @@ class InputSupervisor : public drake::systems::LeafSystem { const int num_actuators_; const int num_positions_; const int num_velocities_; + + // + mutable std::string current_channel_; + // supervisor settings const int min_consecutive_failures_; double max_joint_velocity_; double input_limit_; mutable double blend_duration_ = 0.0; - - -// int status_vars_index_; - - int status_index_; + // For keeping track of things that require multiple failures int n_fails_index_; + // for blending controller efforts int switch_time_index_; int prev_efforts_index_; int prev_efforts_time_index_; + // for keeping track of all sources of error + int shutdown_index_; + int error_indices_index_; - // All possible error flags - int error_shutdown_index_; - int controller_msg_delay_index_; - int soft_estop_trigger_index_; - int is_nan_index_; - int consecutive_failures_index_; +// int controller_msg_delay_index_; +// int soft_estop_trigger_index_; +// int is_nan_index_; +// int consecutive_failures_index_; - // vector of all error flags that we check - std::set error_indices_; + // map of all possible error flags that we check + // string: name of error to check + // int: index in the discrete state + std::unordered_map error_indices_; // leafsystem ports int state_input_port_; diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 862c2e9e8a..5cab89a152 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -39,7 +39,7 @@ group "1.controllers-and-dispatchers" { group "2.simulators" { cmd "cassie_sim" { - exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.95"; + exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.9"; host = "localhost"; } cmd "cassie_mujoco_sim" { @@ -62,7 +62,7 @@ group "0.operator" { host = "localhost"; } cmd "drake_director" { - exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time.py --use_builtin_scripts=point_pair_contact"; + exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --use_builtin_scripts=point_pair_contact,frame"; host = "localhost"; } cmd "state_visualizer (dispatcher)" { @@ -70,7 +70,11 @@ group "0.operator" { host = "localhost"; } cmd "switch_to_standing" { - exec = "bazel-bin/examples/Cassie/run_controller_switch --switch_channel=PD_CONTROLLER --new_channel=OSC_STANDING"; + exec = "bazel-bin/examples/Cassie/run_controller_switch --channel_x=CASSIE_STATE_SIMULATION --new_channel=OSC_STANDING"; + host = "localhost"; + } + cmd "switch_to_walking" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --channel_x=CASSIE_STATE_SIMULATION --new_channel=OSC_WALKING --blend_duration=0.25 --fsm_offset=0.7"; host = "localhost"; } } @@ -86,6 +90,25 @@ group "3.lcm-tools" { } } +group "4.controllers_with_different_channels" { + cmd "osc_standing_controller (dispatchers)" { + exec = "bazel-bin/examples/Cassie/run_osc_standing_controller --height=.85 --channel_u=OSC_STANDING"; + host = "localhost"; + } + cmd "dispatcher_robot_in_sim" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_1=OSC_STANDING --sim=1"; + host = "localhost"; + } + cmd "osc_walking_controller (dispatchers)" { + exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_u=OSC_WALKING --cassie_out_channel=CASSIE_OUTPUT --use_radio=1"; + host = "localhost"; + } + cmd "dispatcher_robot_out_sim" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=true"; + host = "localhost"; + } +} + script "full_integration_test" { run_script "standing_integration_test"; diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index fe31a607a2..b1de38ef71 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -22,13 +22,12 @@ DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", DEFINE_string(switch_channel, "INPUT_SWITCH", "The name of the channel which sends the channel name that " "dispatcher_in listens to"); -DEFINE_string(new_channel, "PD_CONTROLLER", +DEFINE_string(new_channel, "PD_CONTROL", "The name of the new lcm channel that dispatcher_in listens to " "after switch"); DEFINE_int32(n_publishes, 10, "The simulation gets updated until it publishes the channel name " "n_publishes times"); - DEFINE_int32(n_period_delay, -1, "the number of periods before we start publishing the new channel " "name. If the value is non-positive, the channel name is published" diff --git a/examples/Cassie/test/input_supervisor_test.cc b/examples/Cassie/test/input_supervisor_test.cc index 7ae0a8c515..d1f0c47ecc 100644 --- a/examples/Cassie/test/input_supervisor_test.cc +++ b/examples/Cassie/test/input_supervisor_test.cc @@ -22,7 +22,7 @@ class InputSupervisorTest : public ::testing::Test { true /*spring model*/, false /*loop closure*/); plant_.Finalize(); supervisor_ = std::make_unique( - plant_, 10.0, 0.01, min_consecutive_failures, 20.0); + plant_, "DEFAULT_CONTROL_CHANNEL", 10.0, 0.01, min_consecutive_failures, 20.0); context_ = supervisor_->CreateDefaultContext(); status_output_ = std::make_unique(); cassie_out_ = std::make_unique(); @@ -55,50 +55,6 @@ class InputSupervisorTest : public ::testing::Test { std::unique_ptr> context_; }; -TEST_F(InputSupervisorTest, StatusBitTest) { - double output_bit; - VectorXd zero_input = VectorXd::Zero(plant_.num_actuators()); - command_input_->get_mutable_value() = zero_input; - cassie_out_->pelvis.radio.channel[15] = 0; - - supervisor_->get_input_port_command().FixValue(context_.get(), - *command_input_); - supervisor_->get_input_port_cassie().FixValue(context_.get(), - *cassie_out_); - supervisor_->SetStatus(*context_, status_output_.get()); - output_bit = status_output_->status; - EXPECT_EQ(output_bit, 0); - - VectorXd large_input = 100 * VectorXd::Ones(plant_.num_actuators()); - command_input_->get_mutable_value() = large_input; - supervisor_->get_input_port_command().FixValue(context_.get(), - *command_input_); - supervisor_->SetStatus(*context_, status_output_.get()); - output_bit = status_output_->status; - EXPECT_EQ(output_bit, 2); - - VectorXd high_velocities = 100 * VectorXd::Ones(plant_.num_velocities()); - state_input_->SetVelocities(high_velocities); - supervisor_->get_input_port_state().FixValue(context_.get(), *state_input_); - supervisor_->get_input_port_controller_switch().FixValue( - context_.get(), - *std::make_unique>()); - supervisor_->UpdateErrorFlag(*context_, - &context_->get_mutable_discrete_state()); - supervisor_->SetStatus(*context_, status_output_.get()); - output_bit = status_output_->status; - EXPECT_EQ(output_bit, 3); - - // Trigger the min_consecutive_failures - for (int i = 0; i < min_consecutive_failures; ++i) { - supervisor_->UpdateErrorFlag(*context_, - &context_->get_mutable_discrete_state()); - } - supervisor_->SetStatus(*context_, status_output_.get()); - output_bit = status_output_->status; - EXPECT_EQ(output_bit, 7); -} - TEST_F(InputSupervisorTest, BlendEffortsTest) { VectorXd prev_input = VectorXd::Zero(plant_.num_actuators()); VectorXd desired_input = 10 * VectorXd::Ones(plant_.num_actuators()); diff --git a/lcmtypes/lcmt_input_supervisor_status.lcm b/lcmtypes/lcmt_input_supervisor_status.lcm index d11c8abd96..8468d519b4 100644 --- a/lcmtypes/lcmt_input_supervisor_status.lcm +++ b/lcmtypes/lcmt_input_supervisor_status.lcm @@ -3,9 +3,8 @@ package dairlib; struct lcmt_input_supervisor_status { int64_t utime; // timestamp in microseconds - int64_t status; boolean shutdown; - boolean vel_limit; - boolean act_limit; - boolean act_delay; + int32_t num_status; + string status_names[num_status]; + boolean status_states[num_status]; } \ No newline at end of file diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index b11e4dcef7..0a9d5e4349 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -136,8 +136,8 @@ void addFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, "collision", friction); // Add visual for the ground. - plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), - "visual"); +// plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), +// "visual"); } /// Construct a map between joint names and position indices From a7fcc5309f96ec1b603982ccd78f74e4d406ae1a Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Dec 2021 12:57:19 -0500 Subject: [PATCH 041/758] adding controller channel to director --- .../director_scripts/controller_status.py | 2 +- examples/Cassie/dispatcher_robot_in.cc | 31 ++++----- examples/Cassie/input_supervisor.cc | 14 ++-- examples/Cassie/input_supervisor.h | 9 +-- examples/Cassie/integration_test.pmd | 2 +- examples/Cassie/run_controller_switch.cc | 2 +- lcmtypes/lcmt_input_supervisor_status.lcm | 1 + .../controllers/controller_failure_signal.cc | 65 +++++++++++++++++++ .../controllers/controller_failure_signal.h | 28 ++++++++ 9 files changed, 125 insertions(+), 29 deletions(-) create mode 100644 systems/controllers/controller_failure_signal.cc create mode 100644 systems/controllers/controller_failure_signal.h diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py index d421dea56f..1d5179ddf8 100644 --- a/examples/Cassie/director_scripts/controller_status.py +++ b/examples/Cassie/director_scripts/controller_status.py @@ -48,7 +48,7 @@ def set_enabled(self, enable): def handle_message(self, msg): shutdown = msg.shutdown - status_list = ["shutdown: %i" % shutdown] + status_list = ["active channel: " + msg.active_channel, "shutdown: %i" % shutdown] for error_flag_idx in range(msg.num_status): status_list.append(msg.status_names[error_flag_idx] + ': ' + str(msg.status_states[error_flag_idx])) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 79b81e4518..0063cce4a4 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -49,12 +49,10 @@ DEFINE_int64(supervisor_N, 10, "Maximum allowed consecutive failures of velocity limit."); DEFINE_string(state_channel_name, "CASSIE_STATE_DISPATCHER", "The name of the lcm channel that sends Cassie's state"); -DEFINE_string(control_channel_name_1, "PD_CONTROL", - "The name of the lcm channel that sends Cassie's state"); -DEFINE_string(control_channel_name_2, "OSC_STANDING", - "The name of the lcm channel that sends Cassie's state"); -DEFINE_string(control_channel_name_3, "OSC_WALKING", - "The name of the lcm channel that sends Cassie's state"); +DEFINE_string(control_channel_name_initial, "", + "The initial LCM channel to listen for motor commands from"); +DEFINE_string(control_channel_name_additional, "", + "An additional LCM channel to listen for motor commands from"); DEFINE_bool( sim, false, "Whether or not this dispatcher is being used with the simulated robot"); @@ -79,9 +77,10 @@ int do_main(int argc, char* argv[]) { true /*spring model*/, false /*loop closure*/); plant.Finalize(); - std::cout << "channel_1: " << FLAGS_control_channel_name_1 << std::endl; - std::cout << "channel_2: " << FLAGS_control_channel_name_2 << std::endl; - std::cout << "channel_3: " << FLAGS_control_channel_name_3 << std::endl; + std::cout << "initial channel: " << FLAGS_control_channel_name_initial + << std::endl; + std::cout << "additional channel: " << FLAGS_control_channel_name_additional + << std::endl; // Channel name of the input switch std::string switch_channel = "INPUT_SWITCH"; @@ -115,7 +114,7 @@ int do_main(int argc, char* argv[]) { } auto input_supervisor = builder.AddSystem( - plant, FLAGS_control_channel_name_1, FLAGS_max_joint_velocity, + plant, FLAGS_control_channel_name_initial, FLAGS_max_joint_velocity, input_supervisor_update_period, FLAGS_supervisor_N, input_limit); builder.Connect(state_receiver->get_output_port(0), input_supervisor->get_input_port_state()); @@ -166,16 +165,18 @@ int do_main(int argc, char* argv[]) { owned_diagram->set_name("dispatcher_robot_in"); // Channel names of the controllers - std::vector input_channels; - input_channels.push_back(FLAGS_control_channel_name_1); - input_channels.push_back(FLAGS_control_channel_name_2); - input_channels.push_back(FLAGS_control_channel_name_3); + std::vector input_channels = {"PD_CONTROL", "OSC_STANDING", + "OSC_WALKING", "OSC_JUMPING", + "OSC_RUNNING"}; + if (!FLAGS_control_channel_name_additional.empty()) { + input_channels.push_back(FLAGS_control_channel_name_additional); + } // Run lcm-driven simulation systems::LcmDrivenLoop loop(&lcm_local, std::move(owned_diagram), command_receiver, - input_channels, FLAGS_control_channel_name_1, switch_channel, true); + input_channels, FLAGS_control_channel_name_initial, switch_channel, true); loop.Simulate(); return 0; diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index a7648a3d3d..f723440f72 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -23,7 +23,7 @@ InputSupervisor::InputSupervisor( num_actuators_(plant_.num_actuators()), num_positions_(plant_.num_positions()), num_velocities_(plant_.num_velocities()), - current_channel_(initial_channel), + active_channel_(initial_channel), min_consecutive_failures_(min_consecutive_failures), max_joint_velocity_(max_joint_velocity), input_limit_(input_limit) { @@ -71,11 +71,16 @@ InputSupervisor::InputSupervisor( prev_efforts_index_ = DeclareDiscreteState(num_actuators_); + /// controller_delay: triggers when there is too long between consecutive controller messages + /// soft_estop: (operator_triggered) triggers when the soft-estop is engaged by the operator + /// is_nan: triggers whenever a NaN is received by the dispatcher to prevent sending bad motor commands + /// consecutive_failures: triggers whenever the velocity or actuator limits are reached + /// controller_failure_delay: triggers whenever the active controller channel sends a failure message error_indices_["controller_delay"] = 0; error_indices_["soft_estop"] = 1; error_indices_["is_nan"] = 2; error_indices_["consecutive_failures"] = 3; - error_indices_["controller_flag"] = 4; + error_indices_["controller_failure_flag"] = 4; // Create error flags as discrete state n_fails_index_ = DeclareDiscreteState(1); @@ -168,6 +173,7 @@ void InputSupervisor::SetStatus( (TimestampedVector*)this->EvalVectorInput(context, command_input_port_); output->utime = command->get_timestamp() * 1e6; + output->active_channel = active_channel_; output->shutdown = context.get_discrete_state().get_value(shutdown_index_)[0]; output->num_status = error_indices_.size(); output->status_names = std::vector(error_indices_.size()); @@ -196,7 +202,7 @@ void InputSupervisor::UpdateErrorFlag( // Note the += operator works as an or operator because we only check if the // error flag != 0 discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("controller_flag")] = + error_indices_index_)[error_indices_.at("controller_failure_flag")] = controller_error->error_code != 0; discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("controller_delay")] = @@ -224,7 +230,7 @@ void InputSupervisor::UpdateErrorFlag( if (discrete_state->get_mutable_value(switch_time_index_)[0] < controller_switch->utime * 1e-6) { std::cout << "Got new switch message" << std::endl; - current_channel_ = controller_switch->channel; + active_channel_ = controller_switch->channel; discrete_state->get_mutable_value(switch_time_index_)[0] = controller_switch->utime * 1e-6; blend_duration_ = controller_switch->blend_duration; diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index f67c26d470..7fc8be67ef 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -99,8 +99,8 @@ class InputSupervisor : public drake::systems::LeafSystem { const int num_positions_; const int num_velocities_; - // - mutable std::string current_channel_; + // active controller channel + mutable std::string active_channel_; // supervisor settings const int min_consecutive_failures_; @@ -120,11 +120,6 @@ class InputSupervisor : public drake::systems::LeafSystem { int shutdown_index_; int error_indices_index_; -// int controller_msg_delay_index_; -// int soft_estop_trigger_index_; -// int is_nan_index_; -// int consecutive_failures_index_; - // map of all possible error flags that we check // string: name of error to check // int: index in the discrete state diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 5cab89a152..4a29662305 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -62,7 +62,7 @@ group "0.operator" { host = "localhost"; } cmd "drake_director" { - exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --use_builtin_scripts=point_pair_contact,frame"; + exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --use_builtin_scripts=point_pair_contact"; host = "localhost"; } cmd "state_visualizer (dispatcher)" { diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index b1de38ef71..c85a26da31 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -25,7 +25,7 @@ DEFINE_string(switch_channel, "INPUT_SWITCH", DEFINE_string(new_channel, "PD_CONTROL", "The name of the new lcm channel that dispatcher_in listens to " "after switch"); -DEFINE_int32(n_publishes, 10, +DEFINE_int32(n_publishes, 1, "The simulation gets updated until it publishes the channel name " "n_publishes times"); DEFINE_int32(n_period_delay, -1, diff --git a/lcmtypes/lcmt_input_supervisor_status.lcm b/lcmtypes/lcmt_input_supervisor_status.lcm index 8468d519b4..730adbf234 100644 --- a/lcmtypes/lcmt_input_supervisor_status.lcm +++ b/lcmtypes/lcmt_input_supervisor_status.lcm @@ -3,6 +3,7 @@ package dairlib; struct lcmt_input_supervisor_status { int64_t utime; // timestamp in microseconds + string active_channel; boolean shutdown; int32_t num_status; string status_names[num_status]; diff --git a/systems/controllers/controller_failure_signal.cc b/systems/controllers/controller_failure_signal.cc new file mode 100644 index 0000000000..4cc1ae99c5 --- /dev/null +++ b/systems/controllers/controller_failure_signal.cc @@ -0,0 +1,65 @@ +#include "systems/controllers/controller_failure_signal.h" + +#include + +using std::cout; +using std::endl; +using std::string; + +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; + +namespace dairlib { +namespace systems { + +ControllerFailureSignal::ControllerFailureSignal( + const drake::multibody::MultibodyPlant& plant, + std::vector fsm_states_of_interest, int prev_fsm_state, + bool set_current_time_until_first_state_switch) + : fsm_states_of_interest_(fsm_states_of_interest), + set_current_time_until_first_state_switch_( + set_current_time_until_first_state_switch) { + this->set_name("fsm_event_time"); + + // Input/Output Setup + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + robot_output_port_ = + this->DeclareVectorInputPort("x, u, t", + OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); + start_time_port_ = + this->DeclareVectorOutputPort( + "t_start", BasicVector(1), + &ControllerFailureSignal::AssignStartTimeOfCurrentState) + .get_index(); + if (!fsm_states_of_interest.empty()) { + start_time_of_interest_port_ = + this->DeclareVectorOutputPort( + "t_start_state_of_interest", BasicVector(1), + &ControllerFailureSignal::AssignStartTimeOfStateOfInterest) + .get_index(); + } + + // Per-step update to record the previous state and the previous event time + DeclarePerStepDiscreteUpdateEvent( + &ControllerFailureSignal::DiscreteVariableUpdate); + // The start time of the current fsm state + prev_time_idx_ = this->DeclareDiscreteState(1); + // The start time of the most recent fsm state that we are interested + prev_time_of_state_of_interest_idx_ = this->DeclareDiscreteState(1); + +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/controller_failure_signal.h b/systems/controllers/controller_failure_signal.h new file mode 100644 index 0000000000..95aa487bbc --- /dev/null +++ b/systems/controllers/controller_failure_signal.h @@ -0,0 +1,28 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" +#include "drake/multibody/parsing/parser.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// ControllerFailureSignal +class ControllerFailureSignal : public drake::systems::LeafSystem { + public: + ControllerFailureSignal( + const drake::multibody::MultibodyPlant& plant, + std::vector fsm_states_of_interest = {}, + int prev_fsm_state = -std::numeric_limits::infinity(), + bool set_current_time_until_first_state_switch = false); + + + private: + + +}; + +} // namespace systems +} // namespace dairlib From 491624c73987f9db3de6d0c263d017793c26eda1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Dec 2021 15:06:44 -0500 Subject: [PATCH 042/758] adding functionality to detect controller failures --- .../director_scripts/controller_status.py | 7 ++- examples/Cassie/dispatcher_robot_in.cc | 4 +- examples/Cassie/input_supervisor.cc | 6 +-- lcmtypes/lcmt_controller_error.lcm | 8 --- lcmtypes/lcmt_controller_failure.lcm | 9 ++++ systems/controllers/BUILD.bazel | 11 ++++ .../controllers/controller_failure_signal.cc | 54 ++++++------------- .../controllers/controller_failure_signal.h | 25 +++++---- 8 files changed, 63 insertions(+), 61 deletions(-) delete mode 100644 lcmtypes/lcmt_controller_error.lcm create mode 100644 lcmtypes/lcmt_controller_failure.lcm diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py index 1d5179ddf8..b467547c12 100644 --- a/examples/Cassie/director_scripts/controller_status.py +++ b/examples/Cassie/director_scripts/controller_status.py @@ -15,6 +15,10 @@ def __init__(self): self._subscriber = None self._current_channel_ = "" + self.text_box = vis.TextItem('safety_info', 'safety_info', view) + self.text_box.setProperty('Font Size', 18) + self.text_box.setProperty('Position', [1600, 10]) + self.set_enabled(True) def add_subscriber(self): @@ -52,7 +56,8 @@ def handle_message(self, msg): for error_flag_idx in range(msg.num_status): status_list.append(msg.status_names[error_flag_idx] + ': ' + str(msg.status_states[error_flag_idx])) - vis.updateText("\n".join(status_list), 'contact_text') + # vis.updateText("\n".join(status_list), 'safety_info') + self.text_box.setProperty('Text', "\n".join(status_list)) def init_visualizer(): viz = InputSupervisorVisualizer() diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 0063cce4a4..58b85cf4ee 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -3,7 +3,7 @@ #include -#include "dairlib/lcmt_controller_error.hpp" +#include "dairlib/lcmt_controller_failure.hpp" #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" @@ -99,7 +99,7 @@ int do_main(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); auto controller_error_sub = builder.AddSystem( - LcmSubscriberSystem::Make( + LcmSubscriberSystem::Make( "CONTROLLER_ERROR", &lcm_local)); auto state_receiver = builder.AddSystem(plant); auto input_supervisor_status_pub = builder.AddSystem( diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index f723440f72..2d27524338 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -1,7 +1,7 @@ #include "examples/Cassie/input_supervisor.h" #include -#include +#include #include "dairlib/lcmt_controller_switch.hpp" #include "systems/framework/output_vector.h" @@ -54,7 +54,7 @@ InputSupervisor::InputSupervisor( controller_error_port_ = this->DeclareAbstractInputPort( "lcmt_controller_error", - drake::Value{}) + drake::Value{}) .get_index(); // Create output port for commands @@ -193,7 +193,7 @@ void InputSupervisor::UpdateErrorFlag( this->EvalInputValue( context, controller_switch_input_port_); const auto* controller_error = - this->EvalInputValue( + this->EvalInputValue( context, controller_error_port_); const TimestampedVector* command = (TimestampedVector*)this->EvalVectorInput(context, diff --git a/lcmtypes/lcmt_controller_error.lcm b/lcmtypes/lcmt_controller_error.lcm deleted file mode 100644 index e78f5aa317..0000000000 --- a/lcmtypes/lcmt_controller_error.lcm +++ /dev/null @@ -1,8 +0,0 @@ -package dairlib; - -struct lcmt_controller_error -{ - int64_t utime; - int32_t error_code; - string controller_channel; -} diff --git a/lcmtypes/lcmt_controller_failure.lcm b/lcmtypes/lcmt_controller_failure.lcm new file mode 100644 index 0000000000..d2767b8e7d --- /dev/null +++ b/lcmtypes/lcmt_controller_failure.lcm @@ -0,0 +1,9 @@ +package dairlib; + +struct lcmt_controller_failure +{ + int64_t utime; + int32_t error_code; // determines which kind of failure mitigation (1: complete shutdown, 2: pure damping) + string error_name; + string controller_channel; +} diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index c578438005..db49962d8d 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -105,6 +105,17 @@ cc_library( ], ) +cc_library( + name = "controller_failure_signal", + srcs = ["controller_failure_signal.cc"], + hdrs = ["controller_failure_signal.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "fsm_event_time", srcs = ["fsm_event_time.cc"], diff --git a/systems/controllers/controller_failure_signal.cc b/systems/controllers/controller_failure_signal.cc index 4cc1ae99c5..46eb703d58 100644 --- a/systems/controllers/controller_failure_signal.cc +++ b/systems/controllers/controller_failure_signal.cc @@ -20,46 +20,24 @@ using drake::systems::EventStatus; namespace dairlib { namespace systems { -ControllerFailureSignal::ControllerFailureSignal( - const drake::multibody::MultibodyPlant& plant, - std::vector fsm_states_of_interest, int prev_fsm_state, - bool set_current_time_until_first_state_switch) - : fsm_states_of_interest_(fsm_states_of_interest), - set_current_time_until_first_state_switch_( - set_current_time_until_first_state_switch) { - this->set_name("fsm_event_time"); - - // Input/Output Setup - fsm_port_ = - this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); - robot_output_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), - plant.num_velocities(), - plant.num_actuators())) - .get_index(); - start_time_port_ = - this->DeclareVectorOutputPort( - "t_start", BasicVector(1), - &ControllerFailureSignal::AssignStartTimeOfCurrentState) - .get_index(); - if (!fsm_states_of_interest.empty()) { - start_time_of_interest_port_ = - this->DeclareVectorOutputPort( - "t_start_state_of_interest", BasicVector(1), - &ControllerFailureSignal::AssignStartTimeOfStateOfInterest) - .get_index(); +ControllerFailureAggregator::ControllerFailureAggregator( + std::string controller_channel_name, int num_input_ports) { + this->set_name("controller_failure_aggregator"); + for (int i = 0; i < num_input_ports; ++i) { + input_ports_.push_back( + this->DeclareVectorInputPort("failure_signal" + std::to_string(i), + BasicVector(1)) + .get_index()); } - - // Per-step update to record the previous state and the previous event time - DeclarePerStepDiscreteUpdateEvent( - &ControllerFailureSignal::DiscreteVariableUpdate); - // The start time of the current fsm state - prev_time_idx_ = this->DeclareDiscreteState(1); - // The start time of the most recent fsm state that we are interested - prev_time_of_state_of_interest_idx_ = this->DeclareDiscreteState(1); - + output_port_ = this->DeclareAbstractOutputPort( + "lcmt_controller_failure", + &ControllerFailureAggregator::AggregateFailureSignals) + .get_index(); } +void ControllerFailureAggregator::AggregateFailureSignals( + const drake::systems::Context& context, + dairlib::lcmt_controller_failure* output) const {} + } // namespace systems } // namespace dairlib diff --git a/systems/controllers/controller_failure_signal.h b/systems/controllers/controller_failure_signal.h index 95aa487bbc..c788fdc445 100644 --- a/systems/controllers/controller_failure_signal.h +++ b/systems/controllers/controller_failure_signal.h @@ -2,26 +2,33 @@ #include +#include + #include "systems/framework/output_vector.h" -#include "drake/multibody/parsing/parser.h" + #include "drake/systems/framework/leaf_system.h" namespace dairlib { namespace systems { -/// ControllerFailureSignal -class ControllerFailureSignal : public drake::systems::LeafSystem { +/// ControllerFailureSignal compiles all the failure possiblities and outputs a +/// lcmt_controller_failure whenever a single failure occurs +class ControllerFailureAggregator : public drake::systems::LeafSystem { public: - ControllerFailureSignal( - const drake::multibody::MultibodyPlant& plant, - std::vector fsm_states_of_interest = {}, - int prev_fsm_state = -std::numeric_limits::infinity(), - bool set_current_time_until_first_state_switch = false); + ControllerFailureAggregator(std::string controller_channel_name, + int num_input_ports); + int AddFailureSignalPort() { + input_ports_.push_back(input_ports_.size()); + return input_ports_.back(); + } private: + void AggregateFailureSignals(const drake::systems::Context& context, + dairlib::lcmt_controller_failure* output) const; - + std::vector input_ports_; + int output_port_; }; } // namespace systems From ffd21a7794ec2b16bc72a7057451730037eadac2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Dec 2021 17:01:01 -0500 Subject: [PATCH 043/758] adding controller triggered failures as well --- examples/Cassie/input_supervisor.cc | 10 ++++---- examples/Cassie/input_supervisor.h | 2 +- examples/Cassie/run_osc_jumping_controller.cc | 12 ++++++++-- lcmtypes/lcmt_controller_failure.lcm | 3 ++- systems/controllers/BUILD.bazel | 6 ++--- ...al.cc => controller_failure_aggregator.cc} | 24 +++++++++++++++---- ...gnal.h => controller_failure_aggregator.h} | 9 ++++--- systems/controllers/osc/BUILD.bazel | 3 ++- .../osc/operational_space_control.cc | 18 +++++++++++++- .../osc/operational_space_control.h | 7 ++++++ 10 files changed, 71 insertions(+), 23 deletions(-) rename systems/controllers/{controller_failure_signal.cc => controller_failure_aggregator.cc} (55%) rename systems/controllers/{controller_failure_signal.h => controller_failure_aggregator.h} (80%) diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 2d27524338..4939c3c332 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -17,7 +17,7 @@ using systems::TimestampedVector; InputSupervisor::InputSupervisor( const drake::multibody::MultibodyPlant& plant, - const std::string initial_channel, double max_joint_velocity, + const std::string& initial_channel, double max_joint_velocity, double update_period, int min_consecutive_failures, double input_limit) : plant_(plant), num_actuators_(plant_.num_actuators()), @@ -201,9 +201,11 @@ void InputSupervisor::UpdateErrorFlag( // Note the += operator works as an or operator because we only check if the // error flag != 0 - discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("controller_failure_flag")] = - controller_error->error_code != 0; + if(controller_error->controller_channel == active_channel_){ + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("controller_failure_flag")] = + controller_error->error_code != 0; + } discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("controller_delay")] = (command->get_timestamp() - diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index 7fc8be67ef..8a13d97ec9 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -40,7 +40,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // replaced with a joint-specific vectors. explicit InputSupervisor( const drake::multibody::MultibodyPlant& plant, - std::string initial_channel, + const std::string& initial_channel, double max_joint_velocity, double update_period, int min_consecutive_failures = 1, double input_limit = std::numeric_limits::max()); diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 1bf9cb0543..6a851a21f2 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -18,6 +18,7 @@ #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" +#include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/osc_tracking_data.h" @@ -46,7 +47,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using examples::osc_jump::FlightFootTrajGenerator; @@ -232,7 +233,11 @@ int DoMain(int argc, char* argv[]) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_JUMPING", &lcm, TriggerTypeSet({TriggerType::kForced}))); - + auto failure_aggregator = + builder.AddSystem(FLAGS_channel_u, 1); + auto controller_failure_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); // For contact-based fsm LcmSubscriberSystem* contact_results_sub = nullptr; if (FLAGS_simulator == "DRAKE") { @@ -459,6 +464,9 @@ int DoMain(int argc, char* argv[]) { builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_failure_output_port(), failure_aggregator->get_input_port(0)); + builder.Connect(failure_aggregator->get_status_output_port(), controller_failure_pub->get_input_port()); + // Run lcm-driven simulation // Create the diagram diff --git a/lcmtypes/lcmt_controller_failure.lcm b/lcmtypes/lcmt_controller_failure.lcm index d2767b8e7d..6056778b1c 100644 --- a/lcmtypes/lcmt_controller_failure.lcm +++ b/lcmtypes/lcmt_controller_failure.lcm @@ -3,7 +3,8 @@ package dairlib; struct lcmt_controller_failure { int64_t utime; - int32_t error_code; // determines which kind of failure mitigation (1: complete shutdown, 2: pure damping) + // determines which kind of failure mitigation (1: complete shutdown, 2: pure damping) + int32_t error_code; string error_name; string controller_channel; } diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index db49962d8d..b1d6704998 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -106,9 +106,9 @@ cc_library( ) cc_library( - name = "controller_failure_signal", - srcs = ["controller_failure_signal.cc"], - hdrs = ["controller_failure_signal.h"], + name = "controller_failure_aggregator", + srcs = ["controller_failure_aggregator.cc"], + hdrs = ["controller_failure_aggregator.h"], deps = [ "//lcmtypes:lcmt_robot", "//systems/framework:vector", diff --git a/systems/controllers/controller_failure_signal.cc b/systems/controllers/controller_failure_aggregator.cc similarity index 55% rename from systems/controllers/controller_failure_signal.cc rename to systems/controllers/controller_failure_aggregator.cc index 46eb703d58..b771d3e86e 100644 --- a/systems/controllers/controller_failure_signal.cc +++ b/systems/controllers/controller_failure_aggregator.cc @@ -1,4 +1,4 @@ -#include "systems/controllers/controller_failure_signal.h" +#include "systems/controllers/controller_failure_aggregator.h" #include @@ -21,15 +21,16 @@ namespace dairlib { namespace systems { ControllerFailureAggregator::ControllerFailureAggregator( - std::string controller_channel_name, int num_input_ports) { + std::string controller_channel, int num_input_ports) : + controller_channel_(controller_channel){ this->set_name("controller_failure_aggregator"); for (int i = 0; i < num_input_ports; ++i) { input_ports_.push_back( this->DeclareVectorInputPort("failure_signal" + std::to_string(i), - BasicVector(1)) + TimestampedVector(1)) .get_index()); } - output_port_ = this->DeclareAbstractOutputPort( + status_output_port_ = this->DeclareAbstractOutputPort( "lcmt_controller_failure", &ControllerFailureAggregator::AggregateFailureSignals) .get_index(); @@ -37,7 +38,20 @@ ControllerFailureAggregator::ControllerFailureAggregator( void ControllerFailureAggregator::AggregateFailureSignals( const drake::systems::Context& context, - dairlib::lcmt_controller_failure* output) const {} + dairlib::lcmt_controller_failure* output) const { + int status = 0; + double timestamp; + for (auto port : input_ports_) { + const TimestampedVector* is_error = + (TimestampedVector*)this->EvalVectorInput(context, port); + status = std::max(status, (int) is_error->get_value()(0)); + timestamp = is_error->get_timestamp(); + } + output->controller_channel = controller_channel_; + output->error_code = status; + output->utime = timestamp * 1e6; + output->error_name = ""; +} } // namespace systems } // namespace dairlib diff --git a/systems/controllers/controller_failure_signal.h b/systems/controllers/controller_failure_aggregator.h similarity index 80% rename from systems/controllers/controller_failure_signal.h rename to systems/controllers/controller_failure_aggregator.h index c788fdc445..b201f5dabf 100644 --- a/systems/controllers/controller_failure_signal.h +++ b/systems/controllers/controller_failure_aggregator.h @@ -18,17 +18,16 @@ class ControllerFailureAggregator : public drake::systems::LeafSystem { ControllerFailureAggregator(std::string controller_channel_name, int num_input_ports); - int AddFailureSignalPort() { - input_ports_.push_back(input_ports_.size()); - return input_ports_.back(); + const drake::systems::OutputPort& get_status_output_port() const { + return this->get_output_port(status_output_port_); } - private: void AggregateFailureSignals(const drake::systems::Context& context, dairlib::lcmt_controller_failure* output) const; + std::string controller_channel_; std::vector input_ports_; - int output_port_; + int status_output_port_; }; } // namespace systems diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index 316948a5cb..7e975c48d8 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -18,6 +18,7 @@ cc_library( "//multibody/kinematic", "//solvers:fast_osqp_solver", "//systems/controllers:control_utils", + "//systems/controllers:controller_failure_aggregator", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -52,8 +53,8 @@ cc_library( hdrs = ["options_tracking_data.h"], deps = [ ":osc_tracking_data", - "//multibody:view_frame", "//multibody:utils", + "//multibody:view_frame", "//systems/framework:vector", "@drake//:drake_shared_library", ], diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f31c0914c4..0ddab6c78a 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -98,6 +98,11 @@ OperationalSpaceControl::OperationalSpaceControl( "lcmt_osc_debug", &OperationalSpaceControl::AssignOscLcmOutput) .get_index(); + failure_port_ = + this->DeclareVectorOutputPort("failure_signal", TimestampedVector(1), + &OperationalSpaceControl::CheckTracking) + .get_index(); + const std::map& vel_map_wo_spr = multibody::makeNameToVelocitiesMap(plant_wo_spr); @@ -445,7 +450,7 @@ void OperationalSpaceControl::Build() { solver_ = std::make_unique(); drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); -// solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); + // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-7); solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); @@ -977,4 +982,15 @@ void OperationalSpaceControl::CalcOptimalInput( control->set_timestamp(robot_output->get_timestamp()); } +void OperationalSpaceControl::CheckTracking( + const drake::systems::Context& context, + TimestampedVector* output) const { + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + output->set_timestamp(robot_output->get_timestamp()); + if (context.get_time() > 5.0) { + output->get_mutable_value()(0) = 1.0; + } +} + } // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index c6b7299f39..d69a4273c6 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -109,6 +109,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const drake::systems::OutputPort& get_osc_debug_port() const { return this->get_output_port(osc_debug_port_); } + const drake::systems::OutputPort& get_failure_output_port() const { + return this->get_output_port(failure_port_); + } // Input/output ports const drake::systems::InputPort& get_robot_output_input_port() const { @@ -201,6 +204,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void AssignOscLcmOutput(const drake::systems::Context& context, dairlib::lcmt_osc_output* output) const; + void CheckTracking(const drake::systems::Context& context, + TimestampedVector* output) const; + // Output function void CalcOptimalInput(const drake::systems::Context& context, systems::TimestampedVector* control) const; @@ -211,6 +217,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int state_port_; int fsm_port_; int near_impact_port_; + int failure_port_; // Discrete update int prev_fsm_state_idx_; From 198ef3d96586e7be48294e5d425be5967dc6f5a8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Dec 2021 17:14:11 -0500 Subject: [PATCH 044/758] removing out-of-date test --- examples/Cassie/BUILD.bazel | 14 --- examples/Cassie/test/input_supervisor_test.cc | 95 ------------------- 2 files changed, 109 deletions(-) delete mode 100644 examples/Cassie/test/input_supervisor_test.cc diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index f716e6d31e..79157fe7d4 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -102,20 +102,6 @@ cc_library( ], ) -cc_test( - name = "input_supervisor_test", - size = "small", - srcs = ["test/input_supervisor_test.cc"], - deps = [ - "//examples/Cassie:cassie_urdf", - "//examples/Cassie:cassie_utils", - "//examples/Cassie:input_supervisor", - "//systems/primitives", - "@drake//:drake_shared_library", - "@gtest//:main", - ], -) - cc_library( name = "sim_cassie_sensor_aggregator", srcs = ["sim_cassie_sensor_aggregator.cc"], diff --git a/examples/Cassie/test/input_supervisor_test.cc b/examples/Cassie/test/input_supervisor_test.cc deleted file mode 100644 index d1f0c47ecc..0000000000 --- a/examples/Cassie/test/input_supervisor_test.cc +++ /dev/null @@ -1,95 +0,0 @@ -#include "examples/Cassie/input_supervisor.h" - -#include -#include - -#include "dairlib/lcmt_controller_switch.hpp" -#include "examples/Cassie/cassie_utils.h" - -#include "drake/multibody/plant/multibody_plant.h" - -namespace dairlib { -namespace systems { - -using Eigen::VectorXd; - -class InputSupervisorTest : public ::testing::Test { - protected: - InputSupervisorTest() - : plant_(drake::multibody::MultibodyPlant(0.0)) { - addCassieMultibody(&plant_, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2.urdf", - true /*spring model*/, false /*loop closure*/); - plant_.Finalize(); - supervisor_ = std::make_unique( - plant_, "DEFAULT_CONTROL_CHANNEL", 10.0, 0.01, min_consecutive_failures, 20.0); - context_ = supervisor_->CreateDefaultContext(); - status_output_ = std::make_unique(); - cassie_out_ = std::make_unique(); - motor_output_ = - std::make_unique>(plant_.num_actuators()); - command_input_ = - std::make_unique>(plant_.num_actuators()); - state_input_ = std::make_unique>( - plant_.num_positions(), plant_.num_velocities(), - plant_.num_actuators()); - -// command_input_port_ = supervisor_->get_input_port_command().get_index(); - state_input_port_ = supervisor_->get_input_port_state().get_index(); -// controller_switch_input_port_ = -// supervisor_->get_input_port_controller_switch().get_index(); - } - -// int command_input_port_; - int state_input_port_; -// int controller_switch_input_port_; - drake::multibody::MultibodyPlant plant_; - const int min_consecutive_failures = 5; - std::unique_ptr supervisor_; - std::unique_ptr status_output_; - std::unique_ptr cassie_out_; - std::unique_ptr> motor_output_; - std::unique_ptr> command_input_; - std::unique_ptr> state_input_; - // std::unique_ptr controller_switch_input_; - std::unique_ptr> context_; -}; - -TEST_F(InputSupervisorTest, BlendEffortsTest) { - VectorXd prev_input = VectorXd::Zero(plant_.num_actuators()); - VectorXd desired_input = 10 * VectorXd::Ones(plant_.num_actuators()); - double blend_start_time = 0.5; - double timestamp = 1.0; - double blend_duration = 1.0; - std::unique_ptr> switch_msg = - std::make_unique>(); - cassie_out_->pelvis.radio.channel[15] = 0; - switch_msg->get_mutable_value().blend_duration = blend_duration; - switch_msg->get_mutable_value().utime = blend_start_time * 1e6; - command_input_->get_mutable_value() = desired_input; - command_input_->set_timestamp(timestamp); - supervisor_->get_input_port_state().FixValue(context_.get(), *state_input_); - supervisor_->get_input_port_cassie().FixValue(context_.get(), - *cassie_out_); - supervisor_->get_input_port_controller_switch().FixValue( - context_.get(), (drake::AbstractValue&)*switch_msg); - supervisor_->get_input_port_command().FixValue(context_.get(), - *command_input_); - supervisor_->UpdateErrorFlag(*context_, - &context_->get_mutable_discrete_state()); - supervisor_->SetMotorTorques(*context_, motor_output_.get()); - - VectorXd output_from_supervisor = motor_output_->get_value(); - double alpha = (timestamp - blend_start_time) / blend_duration; - - EXPECT_EQ(context_->get_discrete_state().get_vector(1)[0], blend_start_time); - EXPECT_EQ(output_from_supervisor, alpha * desired_input); -} - -} // namespace systems -} // namespace dairlib - -int main(int argc, char** argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} From 464c576ae4352d5519d2fc0c476d8ecdb4f6fa6c Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Dec 2021 16:01:39 -0500 Subject: [PATCH 045/758] addressing comments, making errors latching --- examples/Cassie/BUILD.bazel | 16 ++++ examples/Cassie/dispatcher_robot_in.cc | 40 +++++++- examples/Cassie/input_supervisor.cc | 78 +++++++++------ examples/Cassie/input_supervisor.h | 29 ++++-- examples/Cassie/integration_test.pmd | 12 ++- examples/Cassie/run_osc_jumping_controller.cc | 2 +- examples/Cassie/test/input_supervisor_test.cc | 95 +++++++++++++++++++ .../osc/operational_space_control.cc | 3 +- 8 files changed, 229 insertions(+), 46 deletions(-) create mode 100644 examples/Cassie/test/input_supervisor_test.cc diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 79157fe7d4..48cfc3a821 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -102,6 +102,20 @@ cc_library( ], ) +cc_test( + name = "input_supervisor_test", + size = "small", + srcs = ["test/input_supervisor_test.cc"], + deps = [ + "//examples/Cassie:cassie_urdf", + "//examples/Cassie:cassie_utils", + "//examples/Cassie:input_supervisor", + "//systems/primitives", + "@drake//:drake_shared_library", + "@gtest//:main", + ], +) + cc_library( name = "sim_cassie_sensor_aggregator", srcs = ["sim_cassie_sensor_aggregator.cc"], @@ -299,6 +313,8 @@ cc_binary( "//examples/Cassie/networking:cassie_udp_pub_sub", "//lcmtypes:lcmt_robot", "//systems:robot_lcm_systems", + "//systems/controllers:linear_controller", + "//systems/controllers:pd_config_lcm", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", "@gflags", diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 58b85cf4ee..e8a7803338 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -11,6 +11,8 @@ #include "examples/Cassie/networking/cassie_input_translator.h" #include "examples/Cassie/networking/cassie_udp_publisher.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/linear_controller.h" +#include "systems/controllers/pd_config_lcm.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" @@ -83,11 +85,18 @@ int do_main(int argc, char* argv[]) { << std::endl; // Channel name of the input switch - std::string switch_channel = "INPUT_SWITCH"; + const std::string switch_channel = "INPUT_SWITCH"; + const std::string channel_config = "PD_CONFIG"; // Create LCM receiver for commands auto command_receiver = builder.AddSystem(plant); + // Safety Controller + auto controller = builder.AddSystem( + plant.num_positions(), plant.num_velocities(), plant.num_actuators()); + // Create config receiver. + auto config_receiver = builder.AddSystem(plant); + // Create state estimate receiver, used for safety checks auto state_sub = builder.AddSystem(LcmSubscriberSystem::Make( @@ -128,6 +137,12 @@ int do_main(int argc, char* argv[]) { input_supervisor_status_pub->get_input_port()); builder.Connect(cassie_out_receiver->get_output_port(), input_supervisor->get_input_port_cassie()); + builder.Connect(state_receiver->get_output_port(0), + controller->get_input_port_output()); + builder.Connect(config_receiver->get_output_port(0), + controller->get_input_port_config()); + builder.Connect(controller->get_output_port(0), + input_supervisor->get_input_port_safety_controller()); // Create and connect translator auto input_translator = @@ -172,11 +187,32 @@ int do_main(int argc, char* argv[]) { input_channels.push_back(FLAGS_control_channel_name_additional); } + + // Run lcm-driven simulation systems::LcmDrivenLoop loop(&lcm_local, std::move(owned_diagram), command_receiver, - input_channels, FLAGS_control_channel_name_initial, switch_channel, true); + input_channels, FLAGS_control_channel_name_initial, switch_channel, + true); + + auto msg = dairlib::lcmt_pd_config(); + msg.timestamp = 0; + msg.num_joints = 10; + msg.joint_names = {"hip_roll_left_motor", "hip_roll_right_motor", + "hip_yaw_left_motor", "hip_yaw_right_motor", + "hip_pitch_left_motor", "hip_pitch_right_motor", + "knee_left_motor", "knee_right_motor", + "toe_left_motor", "toe_right_motor"}; + msg.desired_position = {-0.01, .01, 0, 0, 0.55, 0.55, -1.5, -1.5, -1.8, -1.8}; + msg.desired_velocity = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + msg.kp = {80,80,50,50,50,50,100,100,10,10}; + msg.kd = {1, 1, 1, 1, 1, 1, 10, 10, 1, 1}; + config_receiver->get_input_port().FixValue( + &(loop.get_diagram()->GetMutableSubsystemContext(*config_receiver, + &loop.get_diagram_mutable_context())), + msg); + loop.Simulate(); return 0; diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 4939c3c332..8e74bfbe93 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -36,7 +36,10 @@ InputSupervisor::InputSupervisor( this->DeclareVectorInputPort("u, t", TimestampedVector(num_actuators_)) .get_index(); - ; + safety_command_input_port_ = + this->DeclareVectorInputPort("safety: u, t", + TimestampedVector(num_actuators_)) + .get_index(); state_input_port_ = this->DeclareVectorInputPort( "x, u, t", OutputVector(num_positions_, num_velocities_, @@ -71,11 +74,16 @@ InputSupervisor::InputSupervisor( prev_efforts_index_ = DeclareDiscreteState(num_actuators_); - /// controller_delay: triggers when there is too long between consecutive controller messages - /// soft_estop: (operator_triggered) triggers when the soft-estop is engaged by the operator - /// is_nan: triggers whenever a NaN is received by the dispatcher to prevent sending bad motor commands - /// consecutive_failures: triggers whenever the velocity or actuator limits are reached - /// controller_failure_delay: triggers whenever the active controller channel sends a failure message + /// controller_delay: triggers when there is too long between consecutive + /// controller messages + /// soft_estop: (operator_triggered) triggers when the soft-estop is engaged + /// by the operator. + /// is_nan: triggers whenever a NaN is received by the dispatcher to prevent + /// sending bad motor commands. + /// consecutive_failures: triggers whenever the velocity or actuator limits + /// are reached. + /// controller_failure_flag: triggers whenever the active + /// controller channel sends a failure message. error_indices_["controller_delay"] = 0; error_indices_["soft_estop"] = 1; error_indices_["is_nan"] = 2; @@ -103,6 +111,9 @@ void InputSupervisor::SetMotorTorques(const Context& context, const TimestampedVector* command = (TimestampedVector*)this->EvalVectorInput(context, command_input_port_); + const TimestampedVector* safety_command = + (TimestampedVector*)this->EvalVectorInput( + context, safety_command_input_port_); const OutputVector* state = (OutputVector*)this->EvalVectorInput(context, state_input_port_); @@ -145,7 +156,8 @@ void InputSupervisor::SetMotorTorques(const Context& context, output->SetDataVector(command->get_value()); } } else { - output->SetDataVector(Eigen::VectorXd::Zero(num_actuators_)); + output->SetDataVector(safety_command->get_value()); + return; } // Blend the efforts between the previous controller effort and the current @@ -156,7 +168,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, if (alpha <= 1.0) { Eigen::VectorXd blended_effort = - alpha * command->get_value() + + alpha * output->get_data() + (1 - alpha) * context.get_discrete_state(prev_efforts_index_).get_value(); output->SetDataVector(blended_effort); @@ -192,6 +204,8 @@ void InputSupervisor::UpdateErrorFlag( const auto* controller_switch = this->EvalInputValue( context, controller_switch_input_port_); + const OutputVector* robot_state = + (OutputVector*)this->EvalVectorInput(context, state_input_port_); const auto* controller_error = this->EvalInputValue( context, controller_error_port_); @@ -201,23 +215,26 @@ void InputSupervisor::UpdateErrorFlag( // Note the += operator works as an or operator because we only check if the // error flag != 0 - if(controller_error->controller_channel == active_channel_){ + if (controller_error->controller_channel == active_channel_ && + controller_error->error_code != 0) { discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("controller_failure_flag")] = - controller_error->error_code != 0; + error_indices_index_)[error_indices_.at("controller_failure_flag")] = 1; } - discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("controller_delay")] = - (command->get_timestamp() - + if ((robot_state->get_timestamp() - context.get_discrete_state(prev_efforts_time_index_)[0] > - kMaxControllerDelay); - discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("is_nan")] = - command->get_data().array().isNaN().any(); - discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("consecutive_failures")] = - context.get_discrete_state(n_fails_index_)[0] >= - min_consecutive_failures_; + kMaxControllerDelay)) { + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("controller_delay")] = 1; + } + if (command->get_data().array().isNaN().any()){ + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("is_nan")] = 0; + } + if ( context.get_discrete_state(n_fails_index_)[0] >= + min_consecutive_failures_){ + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("consecutive_failures")] = 1; + } CheckRadio(context, discrete_state); CheckVelocities(context, discrete_state); @@ -238,14 +255,15 @@ void InputSupervisor::UpdateErrorFlag( blend_duration_ = controller_switch->blend_duration; } - if (command->get_timestamp() - - discrete_state->get_mutable_value(prev_efforts_time_index_)[0] > - kMaxControllerDelay) { - discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = 0.0; - } else { - discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = - command->get_timestamp(); - } + // if (command->get_timestamp() - + // discrete_state->get_mutable_value(prev_efforts_time_index_)[0] > + // kMaxControllerDelay) { + // discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = 0.0; + // } else { + // + // } + discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = + command->get_timestamp(); // Update the previous commanded switch message unless currently blending // efforts diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index 8a13d97ec9..2b7ab26388 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -1,8 +1,9 @@ #pragma once #include -#include "systems/framework/timestamped_vector.h" #include "dairlib/lcmt_input_supervisor_status.hpp" +#include "systems/framework/timestamped_vector.h" + #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/leaf_system.h" @@ -40,20 +41,25 @@ class InputSupervisor : public drake::systems::LeafSystem { // replaced with a joint-specific vectors. explicit InputSupervisor( const drake::multibody::MultibodyPlant& plant, - const std::string& initial_channel, - double max_joint_velocity, double update_period, - int min_consecutive_failures = 1, + const std::string& initial_channel, double max_joint_velocity, + double update_period, int min_consecutive_failures = 1, double input_limit = std::numeric_limits::max()); const drake::systems::InputPort& get_input_port_command() const { return this->get_input_port(command_input_port_); } + const drake::systems::InputPort& get_input_port_safety_controller() + const { + return this->get_input_port(safety_command_input_port_); + } + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_input_port_); } - const drake::systems::InputPort& get_input_port_controller_switch() const { + const drake::systems::InputPort& get_input_port_controller_switch() + const { return this->get_input_port(controller_switch_input_port_); } @@ -61,7 +67,8 @@ class InputSupervisor : public drake::systems::LeafSystem { return this->get_input_port(cassie_input_port_); } - const drake::systems::InputPort& get_input_port_controller_error() const { + const drake::systems::InputPort& get_input_port_controller_error() + const { return this->get_input_port(controller_error_port_); } @@ -88,10 +95,11 @@ class InputSupervisor : public drake::systems::LeafSystem { void SetStatus(const drake::systems::Context& context, dairlib::lcmt_input_supervisor_status* output) const; - - - void CheckVelocities(const drake::systems::Context &context, drake::systems::DiscreteValues* discrete_state) const; - void CheckRadio(const drake::systems::Context &context, drake::systems::DiscreteValues* discrete_state) const; + void CheckVelocities( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + void CheckRadio(const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; private: const drake::multibody::MultibodyPlant& plant_; @@ -128,6 +136,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // leafsystem ports int state_input_port_; int command_input_port_; + int safety_command_input_port_; int controller_switch_input_port_; int cassie_input_port_; int controller_error_port_; diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 4a29662305..7eaf2400f7 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -62,7 +62,7 @@ group "0.operator" { host = "localhost"; } cmd "drake_director" { - exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --use_builtin_scripts=point_pair_contact"; + exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --script=examples/Cassie/director_scripts/pd_panel.py --use_builtin_scripts=point_pair_contact"; host = "localhost"; } cmd "state_visualizer (dispatcher)" { @@ -77,6 +77,10 @@ group "0.operator" { exec = "bazel-bin/examples/Cassie/run_controller_switch --channel_x=CASSIE_STATE_SIMULATION --new_channel=OSC_WALKING --blend_duration=0.25 --fsm_offset=0.7"; host = "localhost"; } + cmd "switch_to_jumping" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --channel_x=CASSIE_STATE_SIMULATION --new_channel=OSC_JUMPING"; + host = "localhost"; + } } group "3.lcm-tools" { @@ -96,7 +100,7 @@ group "4.controllers_with_different_channels" { host = "localhost"; } cmd "dispatcher_robot_in_sim" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_1=OSC_STANDING --sim=1"; + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=OSC_STANDING --sim=1"; host = "localhost"; } cmd "osc_walking_controller (dispatchers)" { @@ -107,6 +111,10 @@ group "4.controllers_with_different_channels" { exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=true"; host = "localhost"; } + cmd "osc_jumping_controller (dispatchers)" { + exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=15.0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d --channel_u=OSC_JUMPING"; + host = "localhost"; + } } diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 6a851a21f2..124902234e 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -94,7 +94,7 @@ int DoMain(int argc, char* argv[]) { // Built the Cassie MBPs drake::multibody::MultibodyPlant plant_w_spr(0.0); addCassieMultibody(&plant_w_spr, nullptr, true, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); plant_w_spr.Finalize(); diff --git a/examples/Cassie/test/input_supervisor_test.cc b/examples/Cassie/test/input_supervisor_test.cc new file mode 100644 index 0000000000..4e6650b92d --- /dev/null +++ b/examples/Cassie/test/input_supervisor_test.cc @@ -0,0 +1,95 @@ +#include "examples/Cassie/input_supervisor.h" + +#include +#include +#include + +#include "dairlib/lcmt_controller_switch.hpp" +#include "examples/Cassie/cassie_utils.h" + +#include "drake/multibody/plant/multibody_plant.h" + +namespace dairlib { +namespace systems { + +using Eigen::VectorXd; + +class InputSupervisorTest : public ::testing::Test { + protected: + InputSupervisorTest() + : plant_(drake::multibody::MultibodyPlant(0.0)) { + addCassieMultibody(&plant_, nullptr, true /*floating base*/, + "examples/Cassie/urdf/cassie_v2.urdf", + true /*spring model*/, false /*loop closure*/); + plant_.Finalize(); + supervisor_ = std::make_unique( + plant_, "DEFAULT_CONTROL_CHANNEL", 10.0, 0.01, min_consecutive_failures, + 20.0); + context_ = supervisor_->CreateDefaultContext(); + status_output_ = std::make_unique(); + cassie_out_ = std::make_unique(); + motor_output_ = + std::make_unique>(plant_.num_actuators()); + command_input_ = + std::make_unique>(plant_.num_actuators()); + state_input_ = std::make_unique>( + plant_.num_positions(), plant_.num_velocities(), + plant_.num_actuators()); + + state_input_port_ = supervisor_->get_input_port_state().get_index(); + } + + int state_input_port_; + drake::multibody::MultibodyPlant plant_; + const int min_consecutive_failures = 5; + std::unique_ptr supervisor_; + std::unique_ptr status_output_; + std::unique_ptr cassie_out_; + std::unique_ptr> motor_output_; + std::unique_ptr> command_input_; + std::unique_ptr> state_input_; + std::unique_ptr> context_; +}; + +TEST_F(InputSupervisorTest, BlendEffortsTest) { + VectorXd prev_input = VectorXd::Zero(plant_.num_actuators()); + VectorXd desired_input = 10 * VectorXd::Ones(plant_.num_actuators()); + double blend_start_time = 0.5; + double timestamp = 1.0; + double blend_duration = 1.0; + std::unique_ptr> switch_msg = + std::make_unique>(); + std::unique_ptr> controller_failure = + std::make_unique>(); + cassie_out_->pelvis.radio.channel[15] = 0; + switch_msg->get_mutable_value().blend_duration = blend_duration; + switch_msg->get_mutable_value().utime = blend_start_time * 1e6; + command_input_->get_mutable_value() = desired_input; + command_input_->set_timestamp(timestamp); + supervisor_->get_input_port_state().FixValue(context_.get(), *state_input_); + supervisor_->get_input_port_cassie().FixValue(context_.get(), *cassie_out_); + supervisor_->get_input_port_safety_controller().FixValue(context_.get(), + *command_input_); + supervisor_->get_input_port_controller_switch().FixValue( + context_.get(), (drake::AbstractValue&)*switch_msg); + supervisor_->get_input_port_controller_error().FixValue( + context_.get(), (drake::AbstractValue&)*controller_failure); + supervisor_->get_input_port_command().FixValue(context_.get(), + *command_input_); + supervisor_->UpdateErrorFlag(*context_, + &context_->get_mutable_discrete_state()); + supervisor_->SetMotorTorques(*context_, motor_output_.get()); + + VectorXd output_from_supervisor = motor_output_->get_value(); + double alpha = (timestamp - blend_start_time) / blend_duration; + + EXPECT_EQ(output_from_supervisor, alpha * desired_input); +} + +} // namespace systems +} // namespace dairlib + +int main(int argc, char** argv) { + ::testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 0ddab6c78a..52faa84f9a 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -988,7 +988,8 @@ void OperationalSpaceControl::CheckTracking( const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); - if (context.get_time() > 5.0) { + output->get_mutable_value()(0) = 0.0; + if (abs(robot_output->get_timestamp() - 5.0) < 5e-3) { output->get_mutable_value()(0) = 1.0; } } From f22589f30c93df901e2fdfe2007676a7887f10bb Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Dec 2021 17:31:05 -0500 Subject: [PATCH 046/758] pretty major bug in computing velocity from simulated encoders --- examples/Cassie/cassie_encoder.cc | 26 ++++++++++++++------------ examples/Cassie/cassie_encoder.h | 2 +- 2 files changed, 15 insertions(+), 13 deletions(-) diff --git a/examples/Cassie/cassie_encoder.cc b/examples/Cassie/cassie_encoder.cc index dbaf47f19d..98c0246190 100644 --- a/examples/Cassie/cassie_encoder.cc +++ b/examples/Cassie/cassie_encoder.cc @@ -14,8 +14,10 @@ CassieEncoder::CassieEncoder(const drake::multibody::MultibodyPlant& pla num_velocities_(plant.num_velocities()), joint_pos_indices_(joint_pos_indices), joint_vel_indices_(joint_vel_indices), - ticks_per_revolution_(ticks_per_revolution), - joint_filters_(std::vector(ticks_per_revolution_.size())) { + ticks_per_revolution_(ticks_per_revolution){ + for (int i = 0; i < ticks_per_revolution_.size(); ++i){ + joint_filters_.push_back(std::make_unique()); + } this->DeclareVectorInputPort("robot_state", systems::BasicVector(num_positions_ + num_velocities_)); this->DeclareVectorOutputPort("filtered_state", @@ -37,7 +39,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, // joint_encoders for (int joint_index = 0; joint_index < joint_pos_indices_.size(); ++joint_index) { - JointFilter filter = joint_filters_[joint_index]; + auto filter = joint_filters_[joint_index].get(); // Position using std::floor; @@ -51,34 +53,34 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, // Initialize unfiltered signal array to prevent bad transients bool allzero = true; for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { - allzero &= filter.x[i] == 0; + allzero &= filter->x[i] == 0; } if (allzero) { // If all filter values are zero, initialize the signal array // with the current encoder value for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { - filter.x[i] = q_filtered[joint_pos_indices_[joint_index]]; + filter->x[i] = q_filtered[joint_pos_indices_[joint_index]]; } } // Shift and update signal arrays for (int i = CASSIE_JOINT_FILTER_NB - 1; i > 0; --i) { - filter.x[i] = filter.x[i - 1]; + filter->x[i] = filter->x[i - 1]; } - filter.x[0] = q[joint_pos_indices_[joint_index]]; + filter->x[0] = q[joint_pos_indices_[joint_index]]; for (int i = CASSIE_JOINT_FILTER_NA - 1; i > 0; --i) { - filter.y[i] = filter.y[i - 1]; + filter->y[i] = filter->y[i - 1]; } // Compute filter value - filter.y[0] = 0; + filter->y[0] = 0; for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { - filter.y[0] += filter.x[i] * joint_filter_b[i]; + filter->y[0] += filter->x[i] * joint_filter_b[i]; } for (int i = 1; i < CASSIE_JOINT_FILTER_NA; ++i) { - filter.y[0] -= filter.y[i] * joint_filter_a[i]; + filter->y[0] -= filter->y[i] * joint_filter_a[i]; } - v_filtered[joint_vel_indices_[joint_index]] = filter.y[0]; + v_filtered[joint_vel_indices_[joint_index]] = filter->y[0]; } VectorXd x_filtered = VectorXd::Zero(num_positions_ + num_velocities_); diff --git a/examples/Cassie/cassie_encoder.h b/examples/Cassie/cassie_encoder.h index 3d06957c9a..f25131b1ae 100644 --- a/examples/Cassie/cassie_encoder.h +++ b/examples/Cassie/cassie_encoder.h @@ -56,7 +56,7 @@ class CassieEncoder final : public drake::systems::LeafSystem { std::vector joint_pos_indices_; std::vector joint_vel_indices_; std::vector ticks_per_revolution_; - std::vector joint_filters_; + std::vector> joint_filters_; }; } // namespace dairlib From d2cefd546af40b83fbbebf5ace1aace66d3401cb Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Dec 2021 17:31:39 -0500 Subject: [PATCH 047/758] small safety controller changes --- examples/Cassie/dispatcher_robot_in.cc | 6 +++--- examples/Cassie/input_supervisor.cc | 7 ------- systems/controllers/osc/operational_space_control.cc | 2 +- 3 files changed, 4 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index e8a7803338..912cd123f7 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -204,10 +204,10 @@ int do_main(int argc, char* argv[]) { "hip_pitch_left_motor", "hip_pitch_right_motor", "knee_left_motor", "knee_right_motor", "toe_left_motor", "toe_right_motor"}; - msg.desired_position = {-0.01, .01, 0, 0, 0.55, 0.55, -1.5, -1.5, -1.8, -1.8}; + msg.desired_position = {-0.01, .01, 0, 0, 0.55, 0.55, -1.7, -1.7, -1.8, -1.8}; msg.desired_velocity = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; - msg.kp = {80,80,50,50,50,50,100,100,10,10}; - msg.kd = {1, 1, 1, 1, 1, 1, 10, 10, 1, 1}; + msg.kp = {50, 50, 50, 50, 50, 50, 50, 50, 20, 20}; + msg.kd = {5, 5, 5, 5, 5, 5, 5, 5, 5, 5}; config_receiver->get_input_port().FixValue( &(loop.get_diagram()->GetMutableSubsystemContext(*config_receiver, &loop.get_diagram_mutable_context())), diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 8e74bfbe93..3f5320c24c 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -255,13 +255,6 @@ void InputSupervisor::UpdateErrorFlag( blend_duration_ = controller_switch->blend_duration; } - // if (command->get_timestamp() - - // discrete_state->get_mutable_value(prev_efforts_time_index_)[0] > - // kMaxControllerDelay) { - // discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = 0.0; - // } else { - // - // } discrete_state->get_mutable_value(prev_efforts_time_index_)[0] = command->get_timestamp(); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 52faa84f9a..e19b1b5d3e 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -989,7 +989,7 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (abs(robot_output->get_timestamp() - 5.0) < 5e-3) { + if (abs(robot_output->get_timestamp() - 15.0) < 5e-3) { output->get_mutable_value()(0) = 1.0; } } From 050a5e8fb6c591d6aec0df95732d128b1b32a982 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Dec 2021 17:58:50 -0500 Subject: [PATCH 048/758] small changes --- examples/Cassie/cassie_encoder.cc | 5 +++-- examples/Cassie/integration_test.pmd | 10 +++++----- 2 files changed, 8 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/cassie_encoder.cc b/examples/Cassie/cassie_encoder.cc index 98c0246190..81171e6db1 100644 --- a/examples/Cassie/cassie_encoder.cc +++ b/examples/Cassie/cassie_encoder.cc @@ -31,7 +31,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, *this->template EvalVectorInput(context, 0); VectorXd q = input.get_value().head(num_positions_); - VectorXd v = input.get_value().head(num_velocities_); + VectorXd v = input.get_value().tail(num_velocities_); VectorXd q_filtered = q; VectorXd v_filtered = v; @@ -84,7 +84,8 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, } VectorXd x_filtered = VectorXd::Zero(num_positions_ + num_velocities_); - x_filtered << q_filtered, v_filtered; + x_filtered << q_filtered, v; +// x_filtered << q, v; output->set_value(x_filtered); } diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 7eaf2400f7..f695799e57 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -24,7 +24,7 @@ group "1.controllers-and-dispatchers" { host = "localhost"; } cmd "dispatcher_robot_in" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_1=CASSIE_INPUT"; + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=CASSIE_INPUT"; host = "localhost"; } cmd "osc_jumping_controller" { @@ -62,7 +62,7 @@ group "0.operator" { host = "localhost"; } cmd "drake_director" { - exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --script=examples/Cassie/director_scripts/pd_panel.py --use_builtin_scripts=point_pair_contact"; + exec = "bazel-bin/director/drake-director --script=examples/Cassie/director_scripts/show_time_hardware.py --script=examples/Cassie/director_scripts/controller_status.py --use_builtin_scripts=point_pair_contact"; host = "localhost"; } cmd "state_visualizer (dispatcher)" { @@ -78,7 +78,7 @@ group "0.operator" { host = "localhost"; } cmd "switch_to_jumping" { - exec = "bazel-bin/examples/Cassie/run_controller_switch --channel_x=CASSIE_STATE_SIMULATION --new_channel=OSC_JUMPING"; + exec = "bazel-bin/examples/Cassie/run_controller_switch --channel_x=CASSIE_STATE_SIMULATION --new_channel=OSC_JUMPING --blend_duration=1.0"; host = "localhost"; } } @@ -104,7 +104,7 @@ group "4.controllers_with_different_channels" { host = "localhost"; } cmd "osc_walking_controller (dispatchers)" { - exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_u=OSC_WALKING --cassie_out_channel=CASSIE_OUTPUT --use_radio=1"; + exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_u=OSC_WALKING --cassie_out_channel=CASSIE_OUTPUT --use_radio=1 --channel_x=CASSIE_STATE_DISPATCHER"; host = "localhost"; } cmd "dispatcher_robot_out_sim" { @@ -112,7 +112,7 @@ group "4.controllers_with_different_channels" { host = "localhost"; } cmd "osc_jumping_controller (dispatchers)" { - exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=15.0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d --channel_u=OSC_JUMPING"; + exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=5.0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d --channel_u=OSC_JUMPING"; host = "localhost"; } } From c4d5367d4f9287099e0c6622eb8089846571ba23 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Dec 2021 12:28:57 -0500 Subject: [PATCH 049/758] making the logic in input supervisor clearer --- examples/Cassie/cassie_encoder.cc | 2 +- examples/Cassie/dispatcher_robot_in.cc | 17 ++--- examples/Cassie/input_supervisor.cc | 86 +++++++++++++------------- examples/Cassie/input_supervisor.h | 2 +- 4 files changed, 53 insertions(+), 54 deletions(-) diff --git a/examples/Cassie/cassie_encoder.cc b/examples/Cassie/cassie_encoder.cc index 81171e6db1..2962ca23c0 100644 --- a/examples/Cassie/cassie_encoder.cc +++ b/examples/Cassie/cassie_encoder.cc @@ -84,7 +84,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, } VectorXd x_filtered = VectorXd::Zero(num_positions_ + num_velocities_); - x_filtered << q_filtered, v; + x_filtered << q_filtered, v_filtered; // x_filtered << q, v; output->set_value(x_filtered); } diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 912cd123f7..48bcfdccc4 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -45,7 +45,7 @@ DEFINE_string( "The name of the channel to receive the cassie out structure from."); DEFINE_double(max_joint_velocity, 20, "Maximum joint velocity before error is triggered"); -DEFINE_double(input_limit, -1, +DEFINE_double(input_limit, 300, "Maximum torque limit. Negative values are inf."); DEFINE_int64(supervisor_N, 10, "Maximum allowed consecutive failures of velocity limit."); @@ -180,15 +180,16 @@ int do_main(int argc, char* argv[]) { owned_diagram->set_name("dispatcher_robot_in"); // Channel names of the controllers - std::vector input_channels = {"PD_CONTROL", "OSC_STANDING", - "OSC_WALKING", "OSC_JUMPING", + std::vector input_channels = {FLAGS_control_channel_name_initial, + "PD_CONTROL", + "OSC_STANDING", + "OSC_WALKING", + "OSC_JUMPING", "OSC_RUNNING"}; if (!FLAGS_control_channel_name_additional.empty()) { input_channels.push_back(FLAGS_control_channel_name_additional); } - - // Run lcm-driven simulation systems::LcmDrivenLoop @@ -209,9 +210,9 @@ int do_main(int argc, char* argv[]) { msg.kp = {50, 50, 50, 50, 50, 50, 50, 50, 20, 20}; msg.kd = {5, 5, 5, 5, 5, 5, 5, 5, 5, 5}; config_receiver->get_input_port().FixValue( - &(loop.get_diagram()->GetMutableSubsystemContext(*config_receiver, - &loop.get_diagram_mutable_context())), - msg); + &(loop.get_diagram()->GetMutableSubsystemContext( + *config_receiver, &loop.get_diagram_mutable_context())), + msg); loop.Simulate(); diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 3f5320c24c..3d8acb3790 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -127,38 +127,8 @@ void InputSupervisor::SetMotorTorques(const Context& context, error_indices_index_)[error_flags.second]; } - // If the soft estop signal is triggered, applying only damping regardless of - // any other controller signal - if (cassie_out->pelvis.radio.channel[15] == -1) { - Eigen::VectorXd u = -K_ * state->GetVelocities(); - output->SetDataVector(u); - return; - } - - // If there has not been an error, copy over the command. - // If there has been an error, set the command to all zeros + // always set the timestamp of the output message output->set_timestamp(command->get_timestamp()); - if (!is_error) { - // If input_limit_ has been set, limit inputs to - // [-input_limit_, input_limit_] - if (input_limit_ != std::numeric_limits::max()) { - for (int i = 0; i < command->get_data().size(); i++) { - double command_value = command->get_data()(i); - if (command_value > input_limit_) { - command_value = input_limit_; - } else if (command_value < -input_limit_) { - command_value = -input_limit_; - } - output->get_mutable_data()(i) = command_value; - } - } else { - // Can copy entire raw vector - output->SetDataVector(command->get_value()); - } - } else { - output->SetDataVector(safety_command->get_value()); - return; - } // Blend the efforts between the previous controller effort and the current // commanded effort using linear interpolation @@ -166,14 +136,42 @@ void InputSupervisor::SetMotorTorques(const Context& context, context.get_discrete_state(switch_time_index_)[0]) / blend_duration_; - if (alpha <= 1.0) { + /// Hierarchy in controllers goes: + /// Note: 1-4 are all limited by the specified input limits + /// 0. Manual estop (outside of input supervisor) + /// 1. soft-estop (also sets more conservative input limits) + /// 2. safety_pd_controller + /// 3. blended efforts from switching control signals + /// 4. command from controller + + // If the soft estop signal is triggered, applying only damping regardless of + // any other controller signal + if (cassie_out->pelvis.radio.channel[15] == -1) { + Eigen::VectorXd u = -K_ * state->GetVelocities(); + input_limit_ = 20; + output->SetDataVector(u); + } else if (is_error) { + output->SetDataVector(safety_command->get_value()); + } else if (alpha < 1.0) { Eigen::VectorXd blended_effort = - alpha * output->get_data() + + alpha * command->get_value() + (1 - alpha) * context.get_discrete_state(prev_efforts_index_).get_value(); output->SetDataVector(blended_effort); - if (fmod(command->get_timestamp(), 0.5) < 1e-4) { - std::cout << "Blending efforts" << std::endl; + } else { + output->get_mutable_data() = command->get_data(); + } + + // Apply input_limits + if (input_limit_ != std::numeric_limits::max()) { + for (int i = 0; i < command->get_data().size(); i++) { + double command_value = output->get_data()(i); + if (command_value > input_limit_) { + command_value = input_limit_; + } else if (command_value < -input_limit_) { + command_value = -input_limit_; + } + output->get_mutable_data()(i) = command_value; } } } @@ -220,18 +218,18 @@ void InputSupervisor::UpdateErrorFlag( discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("controller_failure_flag")] = 1; } - if ((robot_state->get_timestamp() - - context.get_discrete_state(prev_efforts_time_index_)[0] > - kMaxControllerDelay)) { - discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("controller_delay")] = 1; - } - if (command->get_data().array().isNaN().any()){ + // if ((robot_state->get_timestamp() - + // context.get_discrete_state(prev_efforts_time_index_)[0] > + // kMaxControllerDelay)) { + // discrete_state->get_mutable_value( + // error_indices_index_)[error_indices_.at("controller_delay")] = 1; + // } + if (command->get_data().array().isNaN().any()) { discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("is_nan")] = 0; } - if ( context.get_discrete_state(n_fails_index_)[0] >= - min_consecutive_failures_){ + if (context.get_discrete_state(n_fails_index_)[0] >= + min_consecutive_failures_) { discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("consecutive_failures")] = 1; } diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index 2b7ab26388..fbc8291ca9 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -113,7 +113,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // supervisor settings const int min_consecutive_failures_; double max_joint_velocity_; - double input_limit_; + mutable double input_limit_; mutable double blend_duration_ = 0.0; // For keeping track of things that require multiple failures From fdf33017c3d3458c02c4aebf700c60e6ed9dd56d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Dec 2021 17:15:54 -0500 Subject: [PATCH 050/758] adding robot state as backup signal to drive the system --- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/input_supervisor.cc | 14 +++++---- systems/framework/lcm_driven_loop.h | 39 ++++++++++++++++++++++---- 3 files changed, 43 insertions(+), 12 deletions(-) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 48bcfdccc4..2abd7a9632 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -195,7 +195,7 @@ int do_main(int argc, char* argv[]) { dairlib::lcmt_controller_switch> loop(&lcm_local, std::move(owned_diagram), command_receiver, input_channels, FLAGS_control_channel_name_initial, switch_channel, - true); + true, FLAGS_state_channel_name); auto msg = dairlib::lcmt_pd_config(); msg.timestamp = 0; diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 3d8acb3790..e2d4138e60 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -149,8 +149,10 @@ void InputSupervisor::SetMotorTorques(const Context& context, if (cassie_out->pelvis.radio.channel[15] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); input_limit_ = 20; + output->set_timestamp(state->get_timestamp()); output->SetDataVector(u); } else if (is_error) { + output->set_timestamp(safety_command->get_timestamp()); output->SetDataVector(safety_command->get_value()); } else if (alpha < 1.0) { Eigen::VectorXd blended_effort = @@ -218,12 +220,12 @@ void InputSupervisor::UpdateErrorFlag( discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("controller_failure_flag")] = 1; } - // if ((robot_state->get_timestamp() - - // context.get_discrete_state(prev_efforts_time_index_)[0] > - // kMaxControllerDelay)) { - // discrete_state->get_mutable_value( - // error_indices_index_)[error_indices_.at("controller_delay")] = 1; - // } + if ((robot_state->get_timestamp() - + context.get_discrete_state(prev_efforts_time_index_)[0] > + kMaxControllerDelay)) { + discrete_state->get_mutable_value( + error_indices_index_)[error_indices_.at("controller_delay")] = 1; + } if (command->get_data().array().isNaN().any()) { discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("is_nan")] = 0; diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index 37c2e7a779..685ebce307 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -88,7 +88,8 @@ class LcmDrivenLoop { const drake::systems::LeafSystem* lcm_parser, std::vector input_channels, const std::string& active_channel, - const std::string& switch_channel, bool is_forced_publish) + const std::string& switch_channel, bool is_forced_publish, + const std::string& backup_drive_channel = "") : drake_lcm_(drake_lcm), lcm_parser_(lcm_parser), is_forced_publish_(is_forced_publish) { @@ -127,6 +128,11 @@ class LcmDrivenLoop { DRAKE_DEMAND(is_name_match); active_channel_ = active_channel; + + if (!backup_drive_channel.empty()) { + state_sub_ = std::make_unique>( + drake_lcm_, backup_drive_channel); + } }; /// Constructor for single-input LcmDrivenLoop without lcm_parser @@ -192,6 +198,7 @@ class LcmDrivenLoop { // Wait for new InputMessageType messages and SwitchMessageType messages. bool is_new_input_message = false; bool is_new_switch_message = false; + bool is_new_state_message = false; LcmHandleSubscriptionsUntil(drake_lcm_, [&]() { if (name_to_input_sub_map_.at(active_channel_).count() > 0) { is_new_input_message = true; @@ -201,11 +208,23 @@ class LcmDrivenLoop { is_new_switch_message = true; } } - return is_new_input_message || is_new_switch_message; + // Check the backup signal used to drive the system + if (state_sub_ != nullptr) { + if (state_sub_->count() > 0) { + if (state_sub_->message().utime * 1e-6 - last_input_msg_time_ > + 0.1) { + too_long_between_input_messages_ = true; + } + is_new_state_message = too_long_between_input_messages_; + } + } + + return is_new_input_message || is_new_switch_message || + is_new_state_message; }); // Update the diagram context when there is new input message - if (is_new_input_message) { + if (is_new_input_message || too_long_between_input_messages_) { // Write the InputMessageType message into the context if lcm_parser is // provided if (lcm_parser_ != nullptr) { @@ -216,8 +235,15 @@ class LcmDrivenLoop { } // Get message time from the active channel to advance - time = - name_to_input_sub_map_.at(active_channel_).message().utime * 1e-6; + if (is_new_input_message) { + time = + name_to_input_sub_map_.at(active_channel_).message().utime * 1e-6; + last_input_msg_time_ = time; + } else { + // use the robot state to advance + time = state_sub_->message().utime * 1e-6; + state_sub_->clear(); + } // Check if we are very far ahead or behind // (likely due to a restart of the driving clock) @@ -291,8 +317,11 @@ class LcmDrivenLoop { nullptr; std::map> name_to_input_sub_map_; + std::unique_ptr> state_sub_; bool is_forced_publish_; + bool too_long_between_input_messages_ = false; + double last_input_msg_time_; }; } // namespace systems From 4b50c5dfaa22beb9eb21ab57e01da1bf1d533273 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Dec 2021 12:18:04 -0500 Subject: [PATCH 051/758] defaults to driving on robot state when any error flag is raised --- examples/Cassie/BUILD.bazel | 15 +- examples/Cassie/cassie_lcm_driven_loop.h | 339 ++++++++++++++++++ examples/Cassie/dispatcher_robot_in.cc | 9 +- examples/Cassie/input_supervisor.cc | 17 +- examples/Cassie/input_supervisor.h | 10 + examples/Cassie/integration_test.pmd | 10 +- .../osc/operational_space_control.cc | 2 +- 7 files changed, 392 insertions(+), 10 deletions(-) create mode 100644 examples/Cassie/cassie_lcm_driven_loop.h diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 48cfc3a821..f54f46d0bb 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -306,6 +306,7 @@ cc_binary( name = "dispatcher_robot_in", srcs = ["dispatcher_robot_in.cc"], deps = [ + ":cassie_lcm_driven_loop", ":cassie_state_estimator", ":cassie_urdf", ":cassie_utils", @@ -315,12 +316,24 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/controllers:linear_controller", "//systems/controllers:pd_config_lcm", - "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", "@gflags", ], ) +cc_library( + name = "cassie_lcm_driven_loop", + srcs = [ + ], + hdrs = [ + "cassie_lcm_driven_loop.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "@drake//:drake_shared_library", + ], +) + cc_binary( name = "log_timing_test", srcs = ["test/log_timing_test.cc"], diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h new file mode 100644 index 0000000000..793cfe5bc0 --- /dev/null +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -0,0 +1,339 @@ +#pragma once + +#include +#include +#include + +#include "dairlib/lcmt_controller_switch.hpp" + +#include "drake/lcm/drake_lcm.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "drake/systems/lcm/serializer.h" + +namespace dairlib { + +/// LcmDrivenLoop runs the simulation of a diagram (the whole system) of which +/// the update is triggered by the incoming lcm messages. +/// It can handle single and multiple incoming lcm message types. +/// In the case of single message type, the diagram is triggered by this lcm +/// trivially. +/// In the case of multiple message types (we call these messages the input +/// messages), the user has to provide one extra lcm message type (we call this +/// message the switch message) which tells LcmDrivenLoop the channel that it +/// should listen to for the simulation update. + +/// WARNING: Currently, we update the value of the first InputPort of +/// `lcm_parser` with the incoming lcm message. This would cause a problem if +/// the user has a `lcm_parser` with multiple InputPort's. + +/// Notice that diagram.Publish() is for dispatching the publish of +/// TriggerType::kForced type. In LcmPublisherSystem, both periodic and +/// per-step publishes are also forced publish. +/// https://github.com/RobotLocomotion/drake/blob/03fe7e4/systems/lcm/lcm_publisher_system.h#L54-L56 +/// Therefore, in the case of periodic and per-step publishes, we should +/// not run diagram.Publish() after AdvanceTo(). Otherwise, we double +/// publish. +/// With the above things being said, the parameter is_forced_publish_ should be +/// set to true only when LcmPublisher is of TriggerType::kForced type and NOT +/// other types. + +/// Procedures to use LcmDrivenLoop: +/// 1. construct LcmDrivenLoop +/// 2. (if it's multi-input) the user can set the initial channel that +/// LcmDrivenLoop listens to by calling SetInitActiveChannel(). +/// 3. run Simulate() + +/// Note that we implement the class only in the header file because we don't +/// know what MessageTypes are beforehand. + +// We set a default value for SwitchMessageType so that we can generalize this +// to both single and multi inputs. +template +class CassieLcmDrivenLoop { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CassieLcmDrivenLoop) + + /// Constructor for single-input LcmDrivenLoop + /// @param drake_lcm DrakeLcm + /// @param diagram A Drake diagram + /// @param lcm_parser The LeafSystem of the diagram that parses the + /// incoming lcm message + /// @param input_channel The name of the input channel + /// @param is_forced_publish A flag which enables publishing via diagram. + CassieLcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, + std::unique_ptr> diagram, + const drake::systems::LeafSystem* lcm_parser, + const std::string& input_channel, bool is_forced_publish) + : CassieLcmDrivenLoop(drake_lcm, std::move(diagram), lcm_parser, + std::vector(1, input_channel), + input_channel, "", is_forced_publish){}; + + /// Constructor for multi-input LcmDrivenLoop + /// @param drake_lcm DrakeLcm + /// @param diagram A Drake diagram + /// @param lcm_parser The LeafSystem of the diagram that parses the + /// incoming lcm message + /// @param input_channels The names of the input channels + /// @param active_channel The name of the initial active input channel + /// @param switch_channel The name of the switch channel + /// @param is_forced_publish A flag which enables publishing via diagram. + CassieLcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, + std::unique_ptr> diagram, + const drake::systems::LeafSystem* lcm_parser, + std::vector input_channels, + const std::string& active_channel, + const std::string& switch_channel, bool is_forced_publish, + const std::string& backup_drive_channel = "") + : drake_lcm_(drake_lcm), + lcm_parser_(lcm_parser), + is_forced_publish_(is_forced_publish) { + // Move simulator + if (!diagram->get_name().empty()) { + diagram_name_ = diagram->get_name(); + } + diagram_ptr_ = diagram.get(); + simulator_ = + std::make_unique>(std::move(diagram)); + + // Create subscriber for the switch (in the case of multi-input) + DRAKE_DEMAND(!input_channels.empty()); + if (input_channels.size() > 1) { + DRAKE_DEMAND(!switch_channel.empty()); + switch_sub_ = std::make_unique>( + drake_lcm_, switch_channel); + } + + // Create subscribers for inputs + for (const auto& name : input_channels) { + std::cout << "Constructing subscriber for " << name << std::endl; + name_to_input_sub_map_.insert(std::make_pair( + name, drake::lcm::Subscriber(drake_lcm_, name))); + } + + // Make sure input_channels contains active_channel, and then set initial + // active channel + bool is_name_match = false; + for (const auto& name : input_channels) { + if (name.compare(active_channel) == 0) { + is_name_match = true; + break; + } + } + DRAKE_DEMAND(is_name_match); + + active_channel_ = active_channel; + + if (!backup_drive_channel.empty()) { + state_sub_ = std::make_unique>( + drake_lcm_, backup_drive_channel); + failure_sub_ = + std::make_unique>( + drake_lcm_, "CONTROLLER_ERROR"); + } + }; + + /// Constructor for single-input LcmDrivenLoop without lcm_parser + /// @param drake_lcm DrakeLcm + /// @param diagram A Drake diagram + /// @param input_channel The name of the input channel + /// @param is_forced_publish A flag which enables publishing via diagram. + /// The use case is that the user only need the time from lcm message. + CassieLcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, + std::unique_ptr> diagram, + const std::string& input_channel, bool is_forced_publish) + : CassieLcmDrivenLoop(drake_lcm, std::move(diagram), nullptr, + std::vector(1, input_channel), + input_channel, "", is_forced_publish){}; + + // Getters for diagram and its context + drake::systems::Diagram* get_diagram() { return diagram_ptr_; } + drake::systems::Context& get_diagram_mutable_context() { + return simulator_->get_mutable_context(); + } + + // Start simulating the diagram + void Simulate(double end_time = std::numeric_limits::infinity()) { + // Get mutable contexts + auto& diagram_context = simulator_->get_mutable_context(); + + // Wait for the first message. + drake::log()->info("Waiting for first lcm input message"); + LcmHandleSubscriptionsUntil(drake_lcm_, [&]() { + return name_to_input_sub_map_.at(active_channel_).count() > 0; + }); + + // Initialize the context time. + const double t0 = + name_to_input_sub_map_.at(active_channel_).message().utime * 1e-6; + diagram_context.SetTime(t0); + + // "Simulator" time + double time = 0; // initialize the current time with 0 + // Variable needed for the driven loop + std::string previous_active_channel_name = active_channel_; + + // Run the simulation until end_time + /// Structure of the code: + /// While() { + /// Wait for new InputMessageType and SwitchMessageType messages. + /// + /// if(there is new InputMessageType message) { + /// Update diagram context and advance time. + /// Clear input channel messages. + /// } + /// + /// if(there is new SwitchMessageType message) { + /// Update active input channel name. + /// Clear switch channel messages. + /// if(switch to a new input channel) { + /// Clear message in new active input channel. + /// } + /// } + /// } + drake::log()->info(diagram_name_ + " started"); + while (time < end_time) { + // Wait for new InputMessageType messages and SwitchMessageType messages. + bool is_new_input_message = false; + bool is_new_switch_message = false; + bool is_new_state_message = false; + LcmHandleSubscriptionsUntil(drake_lcm_, [&]() { + if (name_to_input_sub_map_.at(active_channel_).count() > 0) { + is_new_input_message = true; + } + if (switch_sub_ != nullptr) { + if (switch_sub_->count() > 0) { + is_new_switch_message = true; + } + } + // Check the backup signal used to drive the system + if (state_sub_ != nullptr) { + if (state_sub_->count() > 0) { + if (state_sub_->message().utime * 1e-6 - last_input_msg_time_ > + 0.1) { + too_long_between_input_messages_ = true; + } + is_new_state_message = too_long_between_input_messages_; + } + } + if (failure_sub_ != nullptr) { + if (failure_sub_->count() > 0) { + if (failure_sub_->message().controller_channel == + "GLOBAL_CHANNEL" && + failure_sub_->message().error_code != 0) { + too_long_between_input_messages_ = true; + } + } + } + + return is_new_input_message || is_new_switch_message || + is_new_state_message; + }); + + // Update the diagram context when there is new input message + if (is_new_input_message || too_long_between_input_messages_) { + // Write the InputMessageType message into the context if lcm_parser is + // provided + if (lcm_parser_ != nullptr) { + lcm_parser_->get_input_port(0).FixValue( + &(diagram_ptr_->GetMutableSubsystemContext(*lcm_parser_, + &diagram_context)), + name_to_input_sub_map_.at(active_channel_).message()); + } + + // Get message time from the active channel to advance + if (is_new_input_message) { + time = + name_to_input_sub_map_.at(active_channel_).message().utime * 1e-6; + last_input_msg_time_ = time; + } else { + // use the robot state to advance + time = state_sub_->message().utime * 1e-6; + state_sub_->clear(); + } + + // Check if we are very far ahead or behind + // (likely due to a restart of the driving clock) + if (time > simulator_->get_context().get_time() + 1.0 || + time < simulator_->get_context().get_time()) { + std::cout << diagram_name_ + " time is " + << simulator_->get_context().get_time() + << ", but stepping to " << time << std::endl; + std::cout << "Difference is too large, resetting " + diagram_name_ + + " time.\n"; + simulator_->get_mutable_context().SetTime(time); + simulator_->Initialize(); + } + + simulator_->AdvanceTo(time); + if (is_forced_publish_) { + // Force-publish via the diagram + diagram_ptr_->Publish(diagram_context); + } + + // Clear messages in the current input channel + name_to_input_sub_map_.at(active_channel_).clear(); + } + + // Update the name of the active channel if there are multiple inputs and + // there is new switch message + if (is_new_switch_message) { + // Check if the channel name is a key of the map. If it is, we update + // the active channel name and clear switch_sub_'s message. If it is + // not we do not update the active channel name. + if (name_to_input_sub_map_.count(switch_sub_->message().channel) == 1) { + active_channel_ = switch_sub_->message().channel; + } else { + std::cout << switch_sub_->message().channel << " doesn't exist\n"; + } + + // Advancing the simulator here ensure that the switch message is + // received in the leaf systems without the encountering a race + // condition when constructing a separate LcmSubscriberSystem that + // listens to the same channel. Advancing the simulator, ensures that + // the LCM message used here successfully arrives at the input port of + // the other LcmSubscriberSystem + simulator_->AdvanceTo(time); + if (is_forced_publish_) { + // Force-publish via the diagram + diagram_ptr_->Publish(diagram_context); + } + + // Clear messages in the switch channel + switch_sub_->clear(); + + // Clear messages in the new input channel if we just switched input + // channel in the current loop + if (previous_active_channel_name.compare(active_channel_) != 0) { + name_to_input_sub_map_.at(active_channel_).clear(); + } + } + previous_active_channel_name = active_channel_; + } + }; + + private: + drake::lcm::DrakeLcm* drake_lcm_; + drake::systems::Diagram* diagram_ptr_; + const drake::systems::LeafSystem* lcm_parser_; + std::unique_ptr> simulator_; + + std::string diagram_name_ = "diagram"; + std::string active_channel_; + std::unique_ptr> switch_sub_ = + nullptr; + std::map> + name_to_input_sub_map_; + std::unique_ptr> state_sub_; + std::unique_ptr> failure_sub_; + + bool is_forced_publish_; + bool too_long_between_input_messages_ = false; + double last_input_msg_time_; +}; + +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 2abd7a9632..1c28da1953 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -13,7 +13,7 @@ #include "multibody/multibody_utils.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" -#include "systems/framework/lcm_driven_loop.h" +#include "examples/Cassie/cassie_lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "drake/lcm/drake_lcm.h" @@ -110,6 +110,9 @@ int do_main(int argc, char* argv[]) { auto controller_error_sub = builder.AddSystem( LcmSubscriberSystem::Make( "CONTROLLER_ERROR", &lcm_local)); + auto controller_error_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm_local)); auto state_receiver = builder.AddSystem(plant); auto input_supervisor_status_pub = builder.AddSystem( LcmPublisherSystem::Make( @@ -143,6 +146,8 @@ int do_main(int argc, char* argv[]) { controller->get_input_port_config()); builder.Connect(controller->get_output_port(0), input_supervisor->get_input_port_safety_controller()); + builder.Connect(input_supervisor->get_output_port_failure(), + controller_error_pub->get_input_port()); // Create and connect translator auto input_translator = @@ -191,7 +196,7 @@ int do_main(int argc, char* argv[]) { } // Run lcm-driven simulation - systems::LcmDrivenLoop loop(&lcm_local, std::move(owned_diagram), command_receiver, input_channels, FLAGS_control_channel_name_initial, switch_channel, diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index e2d4138e60..56c6ba91eb 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -71,6 +71,11 @@ InputSupervisor::InputSupervisor( status_output_port_ = this->DeclareAbstractOutputPort("status", &InputSupervisor::SetStatus) .get_index(); + // Create output port for status + failure_output_port_ = + this->DeclareAbstractOutputPort("failure_status", + &InputSupervisor::SetFailureStatus) + .get_index(); prev_efforts_index_ = DeclareDiscreteState(num_actuators_); @@ -148,7 +153,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, // any other controller signal if (cassie_out->pelvis.radio.channel[15] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); - input_limit_ = 20; + input_limit_ = 100; output->set_timestamp(state->get_timestamp()); output->SetDataVector(u); } else if (is_error) { @@ -198,6 +203,16 @@ void InputSupervisor::SetStatus( } } +void InputSupervisor::SetFailureStatus( + const drake::systems::Context& context, + dairlib::lcmt_controller_failure* output) const { + output->utime = context.get_time() * 1e6; + output->error_code = + context.get_discrete_state().get_value(shutdown_index_)[0]; + output->controller_channel = "GLOBAL_ERROR"; + output->error_name = ""; +} + void InputSupervisor::UpdateErrorFlag( const Context& context, DiscreteValues* discrete_state) const { diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index fbc8291ca9..99c4fede1b 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -2,6 +2,7 @@ #include #include "dairlib/lcmt_input_supervisor_status.hpp" +#include "dairlib/lcmt_controller_failure.hpp" #include "systems/framework/timestamped_vector.h" #include "drake/multibody/plant/multibody_plant.h" @@ -80,6 +81,10 @@ class InputSupervisor : public drake::systems::LeafSystem { return this->get_output_port(status_output_port_); } + const drake::systems::OutputPort& get_output_port_failure() const { + return this->get_output_port(failure_output_port_); + } + void SetMotorTorques(const drake::systems::Context& context, systems::TimestampedVector* output) const; void UpdateErrorFlag( @@ -95,6 +100,10 @@ class InputSupervisor : public drake::systems::LeafSystem { void SetStatus(const drake::systems::Context& context, dairlib::lcmt_input_supervisor_status* output) const; + // Output a failure message when any error is triggered + void SetFailureStatus(const drake::systems::Context& context, + dairlib::lcmt_controller_failure* output) const; + void CheckVelocities( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; @@ -142,6 +151,7 @@ class InputSupervisor : public drake::systems::LeafSystem { int controller_error_port_; int command_output_port_; int status_output_port_; + int failure_output_port_; Eigen::MatrixXd K_; }; diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index f695799e57..656060ff51 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -96,23 +96,23 @@ group "3.lcm-tools" { group "4.controllers_with_different_channels" { cmd "osc_standing_controller (dispatchers)" { - exec = "bazel-bin/examples/Cassie/run_osc_standing_controller --height=.85 --channel_u=OSC_STANDING"; + exec = "bazel-bin/examples/Cassie/run_osc_standing_controller --channel_x=CASSIE_STATE_DISPATCHER --height=.9 --channel_u=OSC_STANDING"; host = "localhost"; } cmd "dispatcher_robot_in_sim" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=OSC_STANDING --sim=1"; + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=OSC_STANDING --sim=1 --max_joint_velocity=30"; host = "localhost"; } cmd "osc_walking_controller (dispatchers)" { - exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_u=OSC_WALKING --cassie_out_channel=CASSIE_OUTPUT --use_radio=1 --channel_x=CASSIE_STATE_DISPATCHER"; + exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_WALKING --cassie_out_channel=CASSIE_OUTPUT --use_radio=1"; host = "localhost"; } cmd "dispatcher_robot_out_sim" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=true"; + exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=1"; host = "localhost"; } cmd "osc_jumping_controller (dispatchers)" { - exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=5.0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d --channel_u=OSC_JUMPING"; + exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=10 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d --channel_u=OSC_JUMPING"; host = "localhost"; } } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index e19b1b5d3e..52faa84f9a 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -989,7 +989,7 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (abs(robot_output->get_timestamp() - 15.0) < 5e-3) { + if (abs(robot_output->get_timestamp() - 5.0) < 5e-3) { output->get_mutable_value()(0) = 1.0; } } From fe73555ad5ad8b1c405d457a4ffde6bb3e32d4f0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Dec 2021 12:25:28 -0500 Subject: [PATCH 052/758] publishing status on network at pub rate --- examples/Cassie/dispatcher_robot_in.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 1c28da1953..a590a2730c 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -116,7 +116,7 @@ int do_main(int argc, char* argv[]) { auto state_receiver = builder.AddSystem(plant); auto input_supervisor_status_pub = builder.AddSystem( LcmPublisherSystem::Make( - "INPUT_SUPERVISOR_STATUS", &lcm_local, {TriggerType::kForced})); + "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, FLAGS_pub_rate)); builder.Connect(*state_sub, *state_receiver); double input_supervisor_update_period = 1.0 / 1000.0; From 9a62dda2a348485bb90d3ee03ce4fe125750eec4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Dec 2021 14:31:01 -0500 Subject: [PATCH 053/758] adding safety controllers --- examples/Cassie/integration_test.pmd | 6 +---- .../Cassie/osc_jump/osc_jumping_gains.yaml | 2 +- examples/Cassie/run_osc_jumping_controller.cc | 11 ++++++++ examples/Cassie/run_osc_running_controller.cc | 25 +++++++++++++++---- .../impact_invariant_control/platform.urdf | 8 +++--- .../osc/operational_space_control.cc | 9 ++++++- .../osc/operational_space_control.h | 10 ++++++++ systems/robot_lcm_systems.cc | 20 +++++++++------ 8 files changed, 68 insertions(+), 23 deletions(-) diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 84e6e9be49..0dc970f1b2 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -35,15 +35,11 @@ group "1.controllers-and-dispatchers" { exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=2.0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=jumping_0.15h_0.3d"; host = "localhost"; } - cmd "osc_walking_controller (w_radio)" { - exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_x=CASSIE_STATE_DISPATCHER --use_radio=1 --cassie_out_channel=CASSIE_OUTPUT"; - host = "localhost"; - } } group "2.simulators" { cmd "cassie_sim" { - exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.9"; + exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.9 --publish_rate=2000"; host = "localhost"; } cmd "cassie_mujoco_sim" { diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 71402735d3..c7bca569ba 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -2,7 +2,7 @@ w_input: 0.000 w_accel: 0.0000001 w_input_reg: 0.01 w_soft_constraint: 100 -x_offset: -0.02 +x_offset: 0.027 relative_feet: true mu: 0.8 diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index ac9e5c2c84..a5bb2c703b 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -18,6 +18,7 @@ #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" +#include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/osc_tracking_data.h" @@ -263,6 +264,12 @@ int DoMain(int argc, char* argv[]) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_JUMPING", &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto failure_aggregator = + builder.AddSystem(FLAGS_channel_u, + 1); + auto controller_failure_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); // For contact-based fsm LcmSubscriberSystem* contact_results_sub = nullptr; @@ -519,6 +526,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_failure_output_port(), + failure_aggregator->get_input_port(0)); + builder.Connect(failure_aggregator->get_status_output_port(), + controller_failure_pub->get_input_port()); // Run lcm-driven simulation // Create the diagram diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index ee34e2c87b..3c828032c9 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -21,6 +21,7 @@ #include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/relative_translation_tracking_data.h" @@ -87,7 +88,9 @@ DEFINE_bool(use_radio, false, DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); -DEFINE_double(fsm_time_offset, 0.0, "Time (s) in the fsm to move from the stance phase to the flight phase"); +DEFINE_double( + fsm_time_offset, 0.0, + "Time (s) in the fsm to move from the stance phase to the flight phase"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -159,10 +162,12 @@ int DoMain(int argc, char* argv[]) { int right_stance_state = 1; int right_touchdown_air_phase = 2; int left_touchdown_air_phase = 3; - double left_support_duration = dircon_trajectory.GetStateBreaks(1)(0) * 2 - FLAGS_fsm_time_offset; + double left_support_duration = + dircon_trajectory.GetStateBreaks(1)(0) * 2 - FLAGS_fsm_time_offset; double right_support_duration = left_support_duration; double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - - dircon_trajectory.GetStateBreaks(1)(0) + FLAGS_fsm_time_offset; + dircon_trajectory.GetStateBreaks(1)(0) + + FLAGS_fsm_time_offset; vector fsm_states = {left_stance_state, right_touchdown_air_phase, right_stance_state, left_touchdown_air_phase, left_stance_state}; @@ -190,6 +195,12 @@ int DoMain(int argc, char* argv[]) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto failure_aggregator = + builder.AddSystem(FLAGS_channel_u, + 1); + auto controller_failure_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); /**** OSC setup ****/ // Cost @@ -464,8 +475,8 @@ int DoMain(int argc, char* argv[]) { right_foot_rel_tracking_data.SetImpactInvariantProjection(true); osc->AddTrackingData(&left_foot_rel_tracking_data); osc->AddTrackingData(&right_foot_rel_tracking_data); -// left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); -// right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); osc->AddTrackingData(&left_foot_yz_rel_tracking_data); osc->AddTrackingData(&right_foot_yz_rel_tracking_data); } else { @@ -723,6 +734,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_failure_output_port(), + failure_aggregator->get_input_port(0)); + builder.Connect(failure_aggregator->get_status_output_port(), + controller_failure_pub->get_input_port()); // Run lcm-driven simulation // Create the diagram diff --git a/examples/impact_invariant_control/platform.urdf b/examples/impact_invariant_control/platform.urdf index 724b2fc5ee..9bf231e9c1 100644 --- a/examples/impact_invariant_control/platform.urdf +++ b/examples/impact_invariant_control/platform.urdf @@ -5,18 +5,18 @@ - + - + - + - + diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 54835504aa..c9a4a8724c 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -854,6 +854,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( const Context& context, dairlib::lcmt_osc_output* output) const { auto state = (OutputVector*)this->EvalVectorInput(context, state_port_); + total_cost_ = 0; int fsm_state = -1; if (used_with_finite_state_machine_) { auto fsm_output = @@ -907,6 +908,10 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_data_names = std::vector(tracking_data_vec_->size()); + total_cost_ += output->acceleration_cost; + total_cost_ += output->input_cost; + total_cost_ += output->soft_constraint_cost; + for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); output->tracking_data_names[i] = tracking_data->GetName(); @@ -943,6 +948,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_cost[i] = (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); + total_cost_ += output->tracking_cost[i]; } } @@ -1018,7 +1024,8 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (abs(robot_output->get_timestamp() - 5.0) < 5e-3) { + std::cout << "total cost: " << total_cost_ << std::endl; + if (total_cost_ > 5e4 || isnan(total_cost_)) { output->get_mutable_value()(0) = 1.0; } } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 9cce9b4e19..45691ffd81 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -110,6 +110,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const drake::systems::OutputPort& get_osc_debug_port() const { return this->get_output_port(osc_debug_port_); } + const drake::systems::OutputPort& get_failure_output_port() const { + return this->get_output_port(failure_port_); + } // Input/output ports const drake::systems::InputPort& get_robot_output_input_port() const { @@ -226,6 +229,10 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Output function void CalcOptimalInput(const drake::systems::Context& context, systems::TimestampedVector* control) const; + // Safety function that triggers when the tracking cost is too high + void CheckTracking( + const drake::systems::Context& context, + TimestampedVector* output) const; // Input/Output ports int osc_debug_port_; @@ -234,6 +241,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int clock_port_; int fsm_port_; int impact_info_port_; + int failure_port_; // Discrete update int prev_fsm_state_idx_; @@ -389,6 +397,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::QuadraticCost* input_reg_cost_; double w_input_reg_ = -1; Eigen::MatrixXd W_input_reg_; + + mutable double total_cost_ = 0; }; } // namespace dairlib::systems::controllers diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 8a6afd5ddb..5dca4e70cd 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -147,8 +147,12 @@ void RobotOutputSender::Output(const Context& context, state_msg->velocity.resize(num_velocities_); for (int i = 0; i < num_positions_; i++) { - state_msg->position[i] = state->GetAtIndex(i); state_msg->position_names[i] = ordered_position_names_[i]; + if (std::isnan(state->GetAtIndex(i))) { + state_msg->position[i] = 0; + } else { + state_msg->position[i] = state->GetAtIndex(i); + } } for (int i = 0; i < num_velocities_; i++) { state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); @@ -185,7 +189,8 @@ RobotInputReceiver::RobotInputReceiver( actuatorIndexMap_ = multibody::makeNameToActuatorsMap(plant); this->DeclareAbstractInputPort("lcmt_robot_input", drake::Value{}); - this->DeclareVectorOutputPort("u, t", TimestampedVector(num_actuators_), + this->DeclareVectorOutputPort("u, t", + TimestampedVector(num_actuators_), &RobotInputReceiver::CopyInputOut); } @@ -217,7 +222,8 @@ RobotCommandSender::RobotCommandSender( ordered_actuator_names_.push_back(plant.get_joint_actuator(i).name()); } - this->DeclareVectorInputPort("u, t", TimestampedVector(num_actuators_)); + this->DeclareVectorInputPort("u, t", + TimestampedVector(num_actuators_)); this->DeclareAbstractOutputPort("lcmt_robot_input", &RobotCommandSender::OutputCommand); } @@ -234,12 +240,12 @@ void RobotCommandSender::OutputCommand( input_msg->efforts.resize(num_actuators_); for (int i = 0; i < num_actuators_; i++) { input_msg->effort_names[i] = ordered_actuator_names_[i]; - if(std::isnan(command->GetAtIndex(i))){ + if (std::isnan(command->GetAtIndex(i))) { input_msg->efforts[i] = 0; - } - else{ + } else { input_msg->efforts[i] = command->GetAtIndex(i); - } } + } + } } } // namespace systems From 0c0482cbba09ec5db633796190f34c039473e4f8 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Sat, 11 Dec 2021 18:12:19 -0500 Subject: [PATCH 054/758] Fixes for recent Drake deprecations --- examples/Cassie/run_controller_switch.cc | 2 +- examples/Cassie/run_lqr_balancing.cc | 4 ++-- examples/Cassie/run_osc_jumping_controller.cc | 9 +++---- .../Cassie/run_osc_standing_controller.cc | 10 +++----- examples/Cassie/run_osc_walking_controller.cc | 10 ++++---- .../run_joint_space_walking_controller.cc | 10 ++++---- examples/simple_examples/autoDiff_example.cc | 18 +++++++------- multibody/multibody_utils.cc | 13 +++++----- solvers/nonlinear_constraint.cc | 12 +++++----- solvers/optimization_utils.cc | 24 +++++++++---------- .../controllers/constrained_lqr_controller.cc | 20 ++++++++-------- .../dircon/dynamics_cache.cc | 4 ++-- 12 files changed, 62 insertions(+), 74 deletions(-) diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index fe31a607a2..f52feafe0f 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -15,7 +15,7 @@ namespace dairlib { using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", "The name of the channel which receives state"); diff --git a/examples/Cassie/run_lqr_balancing.cc b/examples/Cassie/run_lqr_balancing.cc index 0080006c24..090ba938fa 100644 --- a/examples/Cassie/run_lqr_balancing.cc +++ b/examples/Cassie/run_lqr_balancing.cc @@ -1,4 +1,4 @@ -#include + #include #include "drake/lcm/drake_lcm.h" #include "drake/math/autodiff.h" @@ -143,7 +143,7 @@ int do_main(int argc, char* argv[]) { VectorXd xul(plant.num_positions() + plant.num_velocities() + plant.num_actuators() + evaluators.count_full()); xul << q, VectorXd::Zero(plant.num_velocities()), u, lambda; - AutoDiffVecXd xul_ad = drake::math::initializeAutoDiff(xul); + AutoDiffVecXd xul_ad = drake::math::InitializeAutoDiff(xul); AutoDiffVecXd x_ad = xul_ad.head(plant.num_positions() + plant.num_velocities()); diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 1bf9cb0543..c50c2d9584 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -1,4 +1,4 @@ -#include +#include #include #include #include @@ -46,7 +46,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using examples::osc_jump::FlightFootTrajGenerator; @@ -116,10 +116,7 @@ int DoMain(int argc, char* argv[]) { feet_contact_points = {left_toe, right_toe}; /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - OSCJumpingGains gains; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); - drake::yaml::YamlReadArchive(root).Accept(&gains); + auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index a91278c082..c57b41fd3e 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -11,8 +11,7 @@ #include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" -#include "yaml-cpp/yaml.h" -#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/common/yaml/yaml_io.h" #include "systems/controllers/osc/options_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/controllers/osc/com_tracking_data.h" @@ -39,7 +38,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; @@ -136,10 +135,7 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - OSCStandingGains gains; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); - drake::yaml::YamlReadArchive(root).Accept(&gains); + auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); MatrixXd K_p_com = Eigen::Map< Eigen::Matrix>( diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 7f9a719b32..c79f49f37a 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -27,7 +27,7 @@ #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" -#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -49,7 +49,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using multibody::WorldYawViewFrame; using systems::controllers::ComTrackingData; @@ -91,10 +91,8 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Read-in the parameters - OSCWalkingGains gains; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); - drake::yaml::YamlReadArchive(root).Accept(&gains); + auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); + // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 354f8be9f4..8c9205a6ae 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -16,7 +16,7 @@ #include "systems/robot_lcm_systems.h" #include "yaml-cpp/yaml.h" -#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -40,7 +40,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using systems::controllers::JointSpaceTrackingData; @@ -91,10 +91,8 @@ int DoMain(int argc, char* argv[]) { map act_map = multibody::makeNameToActuatorsMap(plant); /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - JointSpaceWalkingGains gains; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); - drake::yaml::YamlReadArchive(root).Accept(&gains); + auto gains = + drake::yaml::LoadYamlFile(FLAGS_gains_filename); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( diff --git a/examples/simple_examples/autoDiff_example.cc b/examples/simple_examples/autoDiff_example.cc index 7949aa4eff..3d1c8eceb7 100644 --- a/examples/simple_examples/autoDiff_example.cc +++ b/examples/simple_examples/autoDiff_example.cc @@ -9,9 +9,9 @@ using Eigen::MatrixXd; using drake::AutoDiffVecXd; using drake::AutoDiffXd; using drake::math::DiscardGradient; -using drake::math::autoDiffToValueMatrix; -using drake::math::autoDiffToGradientMatrix; -using drake::math::initializeAutoDiff; +using drake::math::ExtractValue; +using drake::math::ExtractGradient; +using drake::math::InitializeAutoDiff; int main() { int x_dim = 2; @@ -22,11 +22,11 @@ int main() { // Declare autoDiff x VectorXd x_val(x_dim); x_val << M_PI/2, 3; - AutoDiffVecXd x = initializeAutoDiff(x_val); + AutoDiffVecXd x = InitializeAutoDiff(x_val); // Compute jacobian of x // Default wrt itself since it's not derived from other autoDiff - MatrixXd dxdSTH = autoDiffToGradientMatrix(x); + MatrixXd dxdSTH = ExtractGradient(x); cout << "dxdSTH = \n" << dxdSTH << "\n\n"; ////////////////////////////////////////////////////////// @@ -37,11 +37,11 @@ int main() { cos(x(0)) + sqrt(x(1)); // Get the value of y - VectorXd y_val = autoDiffToValueMatrix(y); + VectorXd y_val = ExtractValue(y); cout << "y_val = \n" << y_val << "\n\n"; // Compute jacobian of y wrt x - MatrixXd dydx = autoDiffToGradientMatrix(y); + MatrixXd dydx = ExtractGradient(y); cout << "dydx = \n" << dydx << "\n\n"; ////////////////////////////////////////////////////////// @@ -50,12 +50,12 @@ int main() { z << y(0) + y(1); // Get the value of z - VectorXd z_val = autoDiffToValueMatrix(z); + VectorXd z_val = ExtractValue(z); cout << "z_val = \n" << z_val << "\n\n"; // Compute jacobian of z wrt x // Note that it's wrt x instead of wrt y - MatrixXd dzdSTH = autoDiffToGradientMatrix(z); + MatrixXd dzdSTH = ExtractGradient(z); cout << "dzdSTH = \n" << dzdSTH << "\n\n"; diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index b11e4dcef7..a876edcd35 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -14,8 +14,8 @@ using drake::AutoDiffXd; using drake::VectorX; using drake::geometry::HalfSpace; using drake::geometry::SceneGraph; -using drake::math::autoDiffToGradientMatrix; -using drake::math::autoDiffToValueMatrix; +using drake::math::ExtractGradient; +using drake::math::ExtractValue; using drake::multibody::BodyIndex; using drake::multibody::JointActuatorIndex; using drake::multibody::JointIndex; @@ -32,11 +32,11 @@ bool AreVectorsEqual(const Eigen::Ref& a, if (a.rows() != b.rows()) { return false; } - if (autoDiffToValueMatrix(a) != autoDiffToValueMatrix(b)) { + if (ExtractValue(a) != ExtractValue(b)) { return false; } - const Eigen::MatrixXd a_gradient = autoDiffToGradientMatrix(a); - const Eigen::MatrixXd b_gradient = autoDiffToGradientMatrix(b); + const Eigen::MatrixXd a_gradient = ExtractGradient(a); + const Eigen::MatrixXd b_gradient = ExtractGradient(b); if (a_gradient.rows() != b_gradient.rows() || a_gradient.cols() != b_gradient.cols()) { return false; @@ -52,8 +52,7 @@ bool AreVectorsEqual(const Eigen::Ref& a, template VectorX getInput(const MultibodyPlant& plant, const Context& context) { if (plant.num_actuators() > 0) { - VectorX input = plant.EvalEigenVectorInput( - context, plant.get_actuation_input_port().get_index()); + VectorX input = plant.get_actuation_input_port().Eval(context); return input; } else { return VectorX(0); diff --git a/solvers/nonlinear_constraint.cc b/solvers/nonlinear_constraint.cc index 0376ded62b..7dc961fc58 100644 --- a/solvers/nonlinear_constraint.cc +++ b/solvers/nonlinear_constraint.cc @@ -46,8 +46,8 @@ template <> void NonlinearConstraint::DoEval( const Eigen::Ref& x, Eigen::VectorXd* y) const { AutoDiffVecXd y_t; - EvaluateConstraint(drake::math::initializeAutoDiff(x), &y_t); - *y = drake::math::autoDiffToValueMatrix(y_t); + EvaluateConstraint(drake::math::InitializeAutoDiff(x), &y_t); + *y = drake::math::ExtractValue(y_t); this->ScaleConstraint(y); } @@ -69,10 +69,10 @@ void NonlinearConstraint::DoEval( template <> void NonlinearConstraint::DoEval( const Eigen::Ref& x, AutoDiffVecXd* y) const { - MatrixXd original_grad = drake::math::autoDiffToGradientMatrix(x); + MatrixXd original_grad = drake::math::ExtractGradient(x); // forward differencing - VectorXd x_val = drake::math::autoDiffToValueMatrix(x); + VectorXd x_val = drake::math::ExtractValue(x); VectorXd y0, yi; EvaluateConstraint(x_val, &y0); @@ -87,9 +87,9 @@ void NonlinearConstraint::DoEval( // Profiling identified dy * original_grad as a significant runtime event, // even though it is almost always the identity matrix. if (original_grad.isIdentity(1e-16)) { - *y = drake::math::initializeAutoDiffGivenGradientMatrix(y0, dy); + *y = drake::math::InitializeAutoDiff(y0, dy); } else { - *y = drake::math::initializeAutoDiffGivenGradientMatrix(y0, + *y = drake::math::InitializeAutoDiff(y0, dy * original_grad); } diff --git a/solvers/optimization_utils.cc b/solvers/optimization_utils.cc index cba06d6a45..691d8ce3c6 100644 --- a/solvers/optimization_utils.cc +++ b/solvers/optimization_utils.cc @@ -6,9 +6,9 @@ using drake::solvers::Constraint; using drake::solvers::Binding; using drake::solvers::MathematicalProgram; using drake::AutoDiffVecXd; -using drake::math::initializeAutoDiff; -using drake::math::autoDiffToGradientMatrix; -using drake::math::autoDiffToValueMatrix; +using drake::math::InitializeAutoDiff; +using drake::math::ExtractGradient; +using drake::math::ExtractValue; namespace dairlib { namespace solvers { @@ -49,15 +49,15 @@ double SecondOrderCost(const MathematicalProgram& prog, const VectorXd& x_nom, if (variables.size() == 0) continue; AutoDiffVecXd y_val = - initializeAutoDiff(VectorXd::Zero(1), variables.size()); + InitializeAutoDiff(VectorXd::Zero(1), variables.size()); VectorXd x_binding(variables.size()); for (int i = 0; i < variables.size(); i++) { x_binding(i) = x_nom(prog.FindDecisionVariableIndex(variables(i))); } - AutoDiffVecXd x_val = initializeAutoDiff(x_binding); + AutoDiffVecXd x_val = InitializeAutoDiff(x_binding); binding.evaluator()->Eval(x_val, &y_val); - MatrixXd gradient_x = autoDiffToGradientMatrix(y_val); - VectorXd y = autoDiffToValueMatrix(y_val); + MatrixXd gradient_x = ExtractGradient(y_val); + VectorXd y = ExtractValue(y_val); c += y(0); // costs are length 1 for (int i = 0; i < variables.size(); i++) { (*w)(prog.FindDecisionVariableIndex(variables(i))) += gradient_x(0, i); @@ -65,12 +65,12 @@ double SecondOrderCost(const MathematicalProgram& prog, const VectorXd& x_nom, // forward differencing for Hessian AutoDiffVecXd y_hessian = - initializeAutoDiff(VectorXd::Zero(1), variables.size()); + InitializeAutoDiff(VectorXd::Zero(1), variables.size()); for (int i = 0; i < variables.size(); i++) { x_val(i) += eps; binding.evaluator()->Eval(x_val, &y_hessian); x_val(i) -= eps; - MatrixXd gradient_hessian = autoDiffToGradientMatrix(y_hessian); + MatrixXd gradient_hessian = ExtractGradient(y_hessian); for (int j = 0; j <= i; j++) { int ind_i = prog.FindDecisionVariableIndex(variables(i)); int ind_j = prog.FindDecisionVariableIndex(variables(j)); @@ -121,12 +121,12 @@ void LinearizeConstraints(const MathematicalProgram& prog, const VectorXd& x, for (int i = 0; i < variables.size(); i++) { x_binding(i) = x(prog.FindDecisionVariableIndex(variables(i))); } - AutoDiffVecXd x_val = initializeAutoDiff(x_binding); + AutoDiffVecXd x_val = InitializeAutoDiff(x_binding); // Evaluate constraint and extract gradient binding.evaluator()->Eval(x_val, &y_val); - MatrixXd dx = autoDiffToGradientMatrix(y_val); + MatrixXd dx = ExtractGradient(y_val); - y->segment(constraint_index, n) = autoDiffToValueMatrix(y_val); + y->segment(constraint_index, n) = ExtractValue(y_val); for (int i = 0; i < variables.size(); i++) { A->block(constraint_index, prog.FindDecisionVariableIndex(variables(i)), n, 1) = dx.col(i); diff --git a/systems/controllers/constrained_lqr_controller.cc b/systems/controllers/constrained_lqr_controller.cc index 29ac01922f..a8bc44f596 100644 --- a/systems/controllers/constrained_lqr_controller.cc +++ b/systems/controllers/constrained_lqr_controller.cc @@ -12,9 +12,9 @@ using drake::MatrixX; using drake::VectorX; using drake::AutoDiffXd; using drake::AutoDiffVecXd; -using drake::math::initializeAutoDiff; -using drake::math::autoDiffToGradientMatrix; -using drake::math::autoDiffToValueMatrix; +using drake::math::InitializeAutoDiff; +using drake::math::ExtractGradient; +using drake::math::ExtractValue; using drake::systems::Context; using drake::systems::controllers::LinearQuadraticRegulator; @@ -82,7 +82,7 @@ ConstrainedLQRController::ConstrainedLQRController( MatrixXd F_quat = MatrixXd::Zero(num_quat, J_active_qdot.cols() + J_active_v.cols()); for (int i = 0; i < num_quat; i++) { - F_quat.row(i).segment(quat_start.at(i), 4) = autoDiffToValueMatrix( + F_quat.row(i).segment(quat_start.at(i), 4) = ExtractValue( plant_.GetPositions(context).segment(quat_start.at(i),4)); } @@ -91,10 +91,10 @@ ConstrainedLQRController::ConstrainedLQRController( // Fx = 0 (where x is the full state vector of the model) MatrixXd F(J_active_qdot.rows() + J_active_v.rows() + num_quat, J_active_qdot.cols() + J_active_v.cols()); - F << autoDiffToValueMatrix(J_active_qdot), + F << ExtractValue(J_active_qdot), MatrixXd::Zero(J_active_qdot.rows(), J_active_v.cols()), MatrixXd::Zero(J_active_v.rows(), J_active_qdot.cols()), - autoDiffToValueMatrix(J_active_v), + ExtractValue(J_active_v), F_quat; // Computing the null space of F @@ -111,11 +111,11 @@ ConstrainedLQRController::ConstrainedLQRController( VectorXd xu(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); - auto x = autoDiffToValueMatrix(plant_.GetPositionsAndVelocities(context)); + auto x = ExtractValue(plant_.GetPositionsAndVelocities(context)); auto u = - autoDiffToValueMatrix(plant_.get_actuation_input_port().Eval(context)); + ExtractValue(plant_.get_actuation_input_port().Eval(context)); xu << x, u; - AutoDiffVecXd xu_ad = initializeAutoDiff(xu); + AutoDiffVecXd xu_ad = InitializeAutoDiff(xu); AutoDiffVecXd x_ad = xu_ad.head(plant_.num_positions() + plant_.num_velocities()); @@ -126,7 +126,7 @@ ConstrainedLQRController::ConstrainedLQRController( AutoDiffVecXd xdot = evaluators_.CalcTimeDerivatives(*context_ad); - MatrixXd AB = autoDiffToGradientMatrix(xdot); + MatrixXd AB = ExtractGradient(xdot); MatrixXd A = AB.leftCols(plant_.num_positions() + plant_.num_velocities()); MatrixXd B = AB.rightCols(plant_.num_actuators()); diff --git a/systems/trajectory_optimization/dircon/dynamics_cache.cc b/systems/trajectory_optimization/dircon/dynamics_cache.cc index 5f17cb09c8..860b0e66c3 100644 --- a/systems/trajectory_optimization/dircon/dynamics_cache.cc +++ b/systems/trajectory_optimization/dircon/dynamics_cache.cc @@ -63,8 +63,8 @@ bool AreVectorsEqual(const Eigen::Ref& a, if (a.value() != b.value()) { return false; } - const Eigen::MatrixXd& a_gradient = drake::math::autoDiffToGradientMatrix(a); - const Eigen::MatrixXd& b_gradient = drake::math::autoDiffToGradientMatrix(b); + const Eigen::MatrixXd& a_gradient = drake::math::ExtractGradient(a); + const Eigen::MatrixXd& b_gradient = drake::math::ExtractGradient(b); return a_gradient == b_gradient; } From e6db7e374750d2061ff5813e16381920286f5985 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Sat, 11 Dec 2021 18:14:36 -0500 Subject: [PATCH 055/758] Update Drake commit number --- WORKSPACE | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/WORKSPACE b/WORKSPACE index 42bc993276..7910ea6606 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,9 +11,9 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "2f16f87df02d7c6ef436fb87437e59a3df840bb5" +DRAKE_COMMIT = "5357d9aad2a9e34c8a2d283de7a93a6595c5293a" -DRAKE_CHECKSUM = "fb65e3f2949a7d50075afa658ec0043b6c8a32f8f692628032c53a18176eff76" +DRAKE_CHECKSUM = "7fa094858de3bb7989cd86de7eb9e61e248c6a4bb862f891a6c8e419c2fc6745" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. # DRAKE_CHECKSUM = "0" * 64 From 334f48f0f63695d3884976f616b928043b967d05 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Sat, 11 Dec 2021 23:42:17 -0500 Subject: [PATCH 056/758] Fix unit tests due to Drake #16035 --- .../Cassie/test/cassie_state_estimator_test.cc | 14 ++++++-------- .../kinematic/test/kinematic_evaluator_test.cc | 4 ++-- 2 files changed, 8 insertions(+), 10 deletions(-) diff --git a/examples/Cassie/test/cassie_state_estimator_test.cc b/examples/Cassie/test/cassie_state_estimator_test.cc index 99434449e0..4d6255c342 100644 --- a/examples/Cassie/test/cassie_state_estimator_test.cc +++ b/examples/Cassie/test/cassie_state_estimator_test.cc @@ -106,9 +106,9 @@ class ContactEstimationTest : public ::testing::Test { TEST_F(ContactEstimationTest, solveFourbarLinkageTest) { // Example position (floating base position doesn't affect the result) VectorXd q_init(plant_.num_positions()); - q_init << 1, VectorXd::Zero(6), -0.084017, 0.084017, -0.00120735, 0.00120735, - 0.366012, 0.366012, -0.6305, -0.6305, 0.00205363, 0.00205363, 0.838878, - 0.838878, 0, 0.205351, 0, 0.205351; + q_init << 1, VectorXd::Zero(6), -0.084017, -0.00120735, 0.366012, -0.6305, + 0.00205363, 0.838878, 0, 0.205351, + 0.084017, 0.00120735, 0.366012, -0.6305, 0.00205363, 0.838878, 0, 0.205351; // Get the angles analytically double calc_left_heel_spring, calc_right_heel_spring; @@ -137,7 +137,7 @@ TEST_F(ContactEstimationTest, solveFourbarLinkageTest) { } program.SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major feasibility tolerance", 1e-8); + "Major feasibility tolerance", 1e-6); program.SetInitialGuess(q, q_init); const auto result = Solve(program); VectorXd q_sol = result.GetSolution(q); @@ -147,10 +147,8 @@ TEST_F(ContactEstimationTest, solveFourbarLinkageTest) { double nlp_right_heel_spring = q_sol(positionIndexMap.at("ankle_spring_joint_right")); - EXPECT_TRUE((calc_left_heel_spring - nlp_left_heel_spring) < 1e-10); - EXPECT_TRUE((calc_right_heel_spring - nlp_right_heel_spring) < 1e-10); - EXPECT_TRUE((calc_left_heel_spring - nlp_left_heel_spring) > -1e-10); - EXPECT_TRUE((calc_right_heel_spring - nlp_right_heel_spring) > -1e-10); + EXPECT_NEAR(calc_left_heel_spring, nlp_left_heel_spring, 1e-5); + EXPECT_NEAR(calc_right_heel_spring, nlp_right_heel_spring, 1e-5); } } // namespace diff --git a/multibody/kinematic/test/kinematic_evaluator_test.cc b/multibody/kinematic/test/kinematic_evaluator_test.cc index 242975d027..e917a025d3 100644 --- a/multibody/kinematic/test/kinematic_evaluator_test.cc +++ b/multibody/kinematic/test/kinematic_evaluator_test.cc @@ -76,7 +76,7 @@ TEST_F(KinematicEvaluatorTest, WorldPointEvaluatorTest) { auto J = evaluator.EvalFullJacobian(*context); MatrixXd J_expected(3, 6); J_expected.row(0) << 0, 0, 0, 0, 0, 0; - J_expected.row(1) << -1, 0, 1, 1, 0, .5; + J_expected.row(1) << -1, 0, 1, 0, 1, .5; J_expected.row(2) << 0, 1, 0, 0, 0, 0; EXPECT_TRUE(CompareMatrices(J, J_expected, tolerance)); @@ -134,7 +134,7 @@ TEST_F(KinematicEvaluatorTest, DistanceEvaluatorTest) { // Test q = pi/2, legs straight down VectorXd q = VectorXd::Zero(plant_->num_positions()); - q(3) = M_PI/2.0; + q(4) = M_PI/2.0; plant_->SetPositions(context.get(), q); VectorXd v = Eigen::VectorXd::Random(plant_->num_velocities()); plant_->SetVelocities(context.get(), v); From 8d96f092d333f592fa2eb1f3302b04ff7b2b710f Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Dec 2021 17:44:57 -0500 Subject: [PATCH 057/758] always using the radio --- examples/Cassie/run_osc_running_controller.cc | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 3c828032c9..d4f1493415 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -83,8 +83,6 @@ DEFINE_string(traj_name, "running_0.00", "File to load saved trajectories from"); DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", "Filepath containing gains"); -DEFINE_bool(use_radio, false, - "Set to true if sending high level commands from radio controller"); DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); @@ -273,13 +271,11 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_channel_cassie_out, &lcm)); cassie::osc::HighLevelCommand* high_level_command; - if (FLAGS_use_radio) { - high_level_command = builder.AddSystem( - plant, plant_context.get(), osc_gains.vel_scale_rot, - osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); - builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_output_port()); - } + high_level_command = builder.AddSystem( + plant, plant_context.get(), osc_gains.vel_scale_rot, + osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); + builder.Connect(cassie_out_receiver->get_output_port(), + high_level_command->get_cassie_output_port()); string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; if (osc_gains.relative_feet) { From 64f43cb781da65fa705d6a9cdd73c48e61c90553 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Dec 2021 17:45:58 -0500 Subject: [PATCH 058/758] small printing changes --- .../analysis/plot_configs/cassie_running_plot.yaml | 13 +++++++------ .../controllers/osc/operational_space_control.cc | 13 +++++++++---- 2 files changed, 16 insertions(+), 10 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 0e507ec9dc..50dcbd386c 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -26,9 +26,10 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' plot_qp_costs: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['accel']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} - hip_roll_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} -# left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} -# left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} -# swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} +# pelvis_trans_traj: {'dims': [2], 'derivs': ['accel']} + # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} + # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} + left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']} + right_ft_traj: {'dims': [0, 2], 'derivs': ['pos', 'accel']} + left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index c9a4a8724c..6db69087a0 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -558,9 +558,9 @@ VectorXd OperationalSpaceControl::SolveQp( v_proj = alpha * M_Jt_ * ii_lambda_sol_; } -// SetVelocitiesIfNew( -// plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, -// context_wo_spr_); + // SetVelocitiesIfNew( + // plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, + // context_wo_spr_); // Get J and JdotV for holonomic constraint MatrixXd J_h(n_h_, n_v_); @@ -762,6 +762,11 @@ VectorXd OperationalSpaceControl::SolveQp( solve_time_ = result.get_solver_details().run_time; + // if (result.get_optimal_cost() < -1e6) { + // std::cout << "qp cost: " << result.get_optimal_cost() << std::endl; + // return VectorXd::Zero(n_u_); + // } + // Extract solutions *dv_sol_ = result.GetSolution(dv_); *u_sol_ = result.GetSolution(u_); @@ -1024,7 +1029,7 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - std::cout << "total cost: " << total_cost_ << std::endl; + // std::cout << "total cost: " << total_cost_ << std::endl; if (total_cost_ > 5e4 || isnan(total_cost_)) { output->get_mutable_value()(0) = 1.0; } From 26e1d612f0a54442d02e9fee62b406acdf664354 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 13 Dec 2021 20:42:22 -0500 Subject: [PATCH 059/758] working on documentation --- bindings/pydairlib/analysis/README.md | 6 +++--- bindings/pydairlib/analysis/osc_debug.py | 6 +++++- bindings/pydairlib/common/plotting_utils.py | 14 ++++++++++++++ 3 files changed, 22 insertions(+), 4 deletions(-) diff --git a/bindings/pydairlib/analysis/README.md b/bindings/pydairlib/analysis/README.md index 47463f3dc9..3de7620761 100644 --- a/bindings/pydairlib/analysis/README.md +++ b/bindings/pydairlib/analysis/README.md @@ -1,7 +1,7 @@ -# Cassie Log Plotting Script Technical Notes +# Log Plotting Script Technical Notes ## Reading LCM messages -To read and process lcm messages from a set of channels, a dictionary of these channels (keys) and their lcm types (items) and a corresponding processing callback function must be passed to `process_lcm_log.get_log_data()`. See `load_default_channels` in `cassie_plotting_utils` as an example callback function. +To read and process lcm messages from a set of channels, a dictionary of these channels (keys) and their lcm types (items) and a corresponding processing callback function must be passed to `process_lcm_log.get_log_data()`. See `load_default_channels` in `mbp_plotting_utils` as an example callback function. ## Default channels *`load_default_channels`* returns the following three dictionaries, whose structure mirrors the lcm channels which their data comes from. @@ -17,4 +17,4 @@ This contains the commanded inputs and timestamps. Dict keys: `'t_u', 'u'` ### `osc_debug` -This contains the osc debug timestamps, the osc debug lcm messages, and a list of osc tracking datas in the same conveniece class we have been using. Implementation of further processing functions for the OSC is ongoing. +This contains the osc debug timestamps, the osc debug lcm messages, and a list of osc tracking datas in the same conveniece class we have been using for Cassie logs (see `osc_debug.py`). diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 8cb04550a5..2efc621ba4 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -23,6 +23,9 @@ def append(self, msg, t): self.y_dim = len(msg.y) self.ydot_dim = len(msg.ydot) + # If there is a large gap between tracking datas, append + # NaNs as a mask for plotting to avoid fictitious lines + # appearing in plots if self.t and (t - self.t[-1]) > self.t_thresh: self.t.append(nan) self.is_active.append(nan) @@ -61,7 +64,8 @@ def convertToNP(self): self.yddot_command = np.array(self.yddot_command) self.yddot_command_sol = np.array(self.yddot_command_sol) - +# Helper class to easily get a list of acceleration tracking costs, +# Setting the cost to zero when a tracking data is not active class osc_tracking_cost(): def __init__(self, tracking_data_names): diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index a8ef70837b..d29a0ecfcd 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -1,7 +1,21 @@ import matplotlib.pyplot as plt import plot_styler +""" +Plots data on the given plot_styler plot. +:param data_dictionary: dictionary containing the data to be plotted. It should +contain a time channel of length N and at least one data channel of size NxM +:param time_key: The dictionary key of the time channel in data_dictionary +:param time_slice: Slice object representing time indices to plot +:param keys_to_plot: List of keys (['a_key'] for a single key) to plot. +data_dictionary[key] should be a Nx something array +:param slices_to_plot: dictionary with the keys in keys_to_plot with what slice +each datapoint should be plotted for each data channel +:param legend_entries: Dictionary of list of strings r=which will become the +legend entry for each data channel - i.e. {'pos' : ['x', 'y', 'z']} if plotting +one 3 dimensional data channel named 'pos' +""" def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, slices_to_plot, legend_entries, plot_labels, ps): From ab0500bc148676c81dde32052fea3d478a18e642 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 13 Dec 2021 23:37:09 -0500 Subject: [PATCH 060/758] comments and reading full qp output --- bindings/pydairlib/analysis/README.md | 7 +++++++ .../pydairlib/analysis/mbp_plotting_utils.py | 18 ++++++++++++++++-- 2 files changed, 23 insertions(+), 2 deletions(-) diff --git a/bindings/pydairlib/analysis/README.md b/bindings/pydairlib/analysis/README.md index 3de7620761..107ec343e8 100644 --- a/bindings/pydairlib/analysis/README.md +++ b/bindings/pydairlib/analysis/README.md @@ -18,3 +18,10 @@ Dict keys: `'t_u', 'u'` ### `osc_debug` This contains the osc debug timestamps, the osc debug lcm messages, and a list of osc tracking datas in the same conveniece class we have been using for Cassie logs (see `osc_debug.py`). + +Dict keys : +``` +'t_osc', 'input_cost', 'acceleration_cost', 'soft_constraint_cost', +'qp_solve_time', 'u_sol', 'lambda_c_sol, 'lambda_h_sol', 'dv_sol', +'epsilon_sol', 'osc_output', 'tracking_cost', 'osc_debug_tracking_datas', 'fsm' +``` \ No newline at end of file diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index c921ffbdc2..2a5c39882c 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -85,6 +85,10 @@ def process_osc_channel(data): soft_constraint_cost = [] qp_solve_time = [] u_sol = [] + lambda_c_sol = [] + lambda_h_sol = [] + dv_sol = [] + epsilon_sol = [] osc_output = [] fsm = [] osc_debug_tracking_datas = {} @@ -96,6 +100,11 @@ def process_osc_channel(data): soft_constraint_cost.append(msg.soft_constraint_cost) qp_solve_time.append(msg.qp_output.solve_time) u_sol.append(msg.qp_output.u_sol) + lambda_c_sol.append(msg.qp_output.lambda_c_sol) + lambda_h_sol.append(msg.qp_output.lambda_h_sol) + dv_sol.append(msg.qp_output.dv_sol) + epsilon_sol.append(msg.qp_output.epsilon_sol) + osc_output.append(msg) for tracking_data in msg.tracking_data: if tracking_data.name not in osc_debug_tracking_datas: @@ -119,10 +128,15 @@ def process_osc_channel(data): 'acceleration_cost': np.array(accel_cost), 'soft_constraint_cost': np.array(soft_constraint_cost), 'qp_solve_time': np.array(qp_solve_time), - 'osc_output': osc_output, + 'u_sol': np.array(u_sol), + 'lambda_c_sol': np.array(lambda_c_sol), + 'lambda_h_sol': np.array(lambda_h_sol), + 'dv_sol': np.array(dv_sol), + 'epsilon_sol': np.array(epsilon_sol), 'tracking_cost': tracking_cost, 'osc_debug_tracking_datas': osc_debug_tracking_datas, - 'fsm': np.array(fsm)} + 'fsm': np.array(fsm), + 'osc_output': osc_output} def load_default_channels(data, plant, state_channel, input_channel, From 62c485a162a8f6cf325221c3e5681f94b719c6c4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Dec 2021 10:20:30 -0500 Subject: [PATCH 061/758] checking dimension when using trajectories in terms of x xdot --- systems/controllers/osc/osc_tracking_data.cc | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index 70d82e2e4a..b7116762b6 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -87,18 +87,21 @@ void OscTrackingData::UpdateDesired( const drake::trajectories::Trajectory& traj, double t, double t_since_state_switch) { // 2. Update desired output - y_des_ = traj.value(t); if (traj.has_derivative()) { - ydot_des_ = traj.EvalDerivative(t, 1); if (traj.rows() == 2 * n_ydot_) { + y_des_ = traj.value(t).topRows(n_y_); + ydot_des_ = traj.EvalDerivative(t, 1).topRows(n_ydot_); yddot_des_ = traj.EvalDerivative(t, 1).bottomRows(n_ydot_); } else { + y_des_ = traj.value(t); + ydot_des_ = traj.EvalDerivative(t, 1); yddot_des_ = traj.EvalDerivative(t, 2); } } // TODO (yangwill): Remove this edge case after EvalDerivative has been // implemented for ExponentialPlusPiecewisePolynomial else { + y_des_ = traj.value(t); ydot_des_ = traj.MakeDerivative(1)->value(t); yddot_des_ = traj.MakeDerivative(2)->value(t); } From 025e2d43126adb075a144baacd09fad4b562c094 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Thu, 16 Dec 2021 14:11:46 -0500 Subject: [PATCH 062/758] ready to merge plots --- .../pydairlib/analysis/cassie_plot_config.py | 25 ++++++---- .../pydairlib/analysis/log_plotter_cassie.py | 4 ++ .../pydairlib/analysis/mbp_plotting_utils.py | 47 +++++++++++++++++++ .../plot_configs/cassie_default_plot.yaml | 1 + bindings/pydairlib/common/plotting_utils.py | 14 +++++- 5 files changed, 79 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index d17571ec21..20cd995182 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -22,19 +22,24 @@ def __init__(self, filename): self.plot_joint_positions = data['plot_joint_positions'] self.plot_joint_velocities = data['plot_joint_velocities'] self.plot_measured_efforts = data['plot_measured_efforts'] - self.pos_names = [] - self.vel_names = [] - self.act_names = [] - if data['special_positions_to_plot']: - self.pos_names = data['special_positions_to_plot'] - if data['special_velocities_to_plot']: - self.vel_names = data['special_velocities_to_plot'] - if data['special_efforts_to_plot']: - self.act_names = data['special_efforts_to_plot'] + self.pos_names = \ + data['special_positions_to_plot'] if \ + data['special_positions_to_plot'] else [] + self.vel_names = \ + data['special_velocities_to_plot'] if \ + data['special_velocities_to_plot'] else [] + self.act_names = \ + data['special_efforts_to_plot'] if \ + data['special_efforts_to_plot'] else [] if data['foot_positions_to_plot']: self.foot_positions_to_plot = data['foot_positions_to_plot'] self.foot_xyz_to_plot = data['foot_xyz_to_plot'] self.pt_on_foot_to_plot = data['pt_on_foot_to_plot'] + else: + self.foot_positions_to_plot = [] + self.plot_qp_costs = data['plot_qp_costs'] self.plot_tracking_costs = data['plot_tracking_costs'] - self.tracking_datas_to_plot = data['tracking_datas_to_plot'] + self.plot_qp_solve_time = data['plot_qp_solve_time'] + self.tracking_datas_to_plot = \ + data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 7033fabb64..e8f95aee40 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -107,6 +107,10 @@ def main(): mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, foot_frames, pts, dims) + + if plot_config.plot_qp_solve_time: + mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2a5c39882c..2a31d04b2d 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -331,5 +331,52 @@ def plot_qp_costs(osc_debug, time_slice): return ps +def plot_qp_solve_time(osc_debug, time_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + ['qp_solve_time'], + {}, + {}, + {'xlabel': 'Timestamp', + 'ylabel': 'Solve Time ', + 'title': 'OSC QP Solve Time'}, ps) + return ps + + +def plot_lambda_c_sol(osc_debug, time_slice, lambda_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + ['lambda_c_sol'], + {'lambda_c_sol': lambda_slice}, + {'lambda_c_sol': ['lambda_c_' + i for i in + plotting_utils.slice_to_string_list(lambda_slice)]}, + {'xlabel': 'time', + 'ylabel': 'lambda', + 'title': 'OSC contact force solution'}, ps) + return ps + + +def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + ['epsilon_sol'], + {'epsilon_sol': epsilon_slice}, + {'epsilon_sol': ['epsilon_sol' + i for i in + plotting_utils.slice_to_string_list(epsilon_slice)]}, + {'xlabel': 'time', + 'ylabel': 'epsilon', + 'title': 'OSC soft constraint epsilon sol'}, ps) + return ps + + def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): ps.plot(fsm_time, scale*fsm_signal) \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index dcf0ea7d02..4803485e3a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -25,6 +25,7 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_tracking_costs: true +plot_qp_solve_time: true tracking_datas_to_plot: com_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index d29a0ecfcd..a74a69b324 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -14,8 +14,9 @@ :param legend_entries: Dictionary of list of strings r=which will become the legend entry for each data channel - i.e. {'pos' : ['x', 'y', 'z']} if plotting one 3 dimensional data channel named 'pos' - """ + + def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, slices_to_plot, legend_entries, plot_labels, ps): @@ -27,7 +28,8 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, else: ps.plot(data_dictionary[time_key][time_slice], data_dictionary[key][time_slice, slices_to_plot[key]]) - legend.extend(legend_entries[key]) + if key in legend_entries: + legend.extend(legend_entries[key]) plt.legend(legend) plt.xlabel(plot_labels['xlabel']) @@ -56,3 +58,11 @@ def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, plt.xlabel(plot_labels['xlabel']) plt.ylabel(plot_labels['ylabel']) plt.title(plot_labels['title']) + + +def slice_to_string_list(slice_): + if isinstance(slice_, slice): + return [str(i) for i in range(slice_.start, slice_.stop, + slice_.step if slice_.step else 1)] + if isinstance(slice_, list): + return [str(i) for i in slice_] From 705345df601a7fb8e0604e4d1661a1d39a5734dd Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Thu, 16 Dec 2021 14:14:16 -0500 Subject: [PATCH 063/758] Update analysis readme --- bindings/pydairlib/analysis/README.md | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/bindings/pydairlib/analysis/README.md b/bindings/pydairlib/analysis/README.md index 107ec343e8..f6008e3ec9 100644 --- a/bindings/pydairlib/analysis/README.md +++ b/bindings/pydairlib/analysis/README.md @@ -24,4 +24,9 @@ Dict keys : 't_osc', 'input_cost', 'acceleration_cost', 'soft_constraint_cost', 'qp_solve_time', 'u_sol', 'lambda_c_sol, 'lambda_h_sol', 'dv_sol', 'epsilon_sol', 'osc_output', 'tracking_cost', 'osc_debug_tracking_datas', 'fsm' -``` \ No newline at end of file +``` + +# Ongoing Progress: +As of Dec. 16 2021, plotting for `lambda_c_sol` and `epsilon_sol` in `osc_debug` +have been implemented but not added to `cassie_plot_config` or the default yaml +file From 034bed6a2d709b2ce26a1c0f187f9c48fa824e2b Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 5 Jan 2022 15:18:57 -0500 Subject: [PATCH 064/758] need to improve pitch and roll trajectories --- .../plot_configs/cassie_running_plot.yaml | 16 +- .../pydairlib/lcm/lcm_trajectory_plotter.py | 260 ++++++++++++------ examples/Cassie/multibody_sim.cc | 8 +- .../Cassie/osc_run/foot_traj_generator.cc | 223 +++++++++++---- examples/Cassie/osc_run/foot_traj_generator.h | 43 ++- examples/Cassie/osc_run/osc_running_gains.h | 10 +- .../Cassie/osc_run/osc_running_gains.yaml | 35 ++- .../osc_run/pelvis_pitch_traj_generator.cc | 15 +- .../osc_run/pelvis_roll_traj_generator.cc | 18 +- .../osc_run/pelvis_roll_traj_generator.h | 17 +- examples/Cassie/run_osc_running_controller.cc | 105 ++++--- 11 files changed, 495 insertions(+), 255 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 50dcbd386c..0ce93ca5d7 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -24,12 +24,14 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true +plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [2], 'derivs': ['accel']} - # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} - # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} - left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']} - right_ft_traj: {'dims': [0, 2], 'derivs': ['pos', 'accel']} - left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} +# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} +# hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} + hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} +# left_ft_traj: {'dims': [2], 'derivs': ['pos']} +# right_ft_traj: {'dims': [2], 'derivs': ['pos']} +# left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} +# right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} diff --git a/bindings/pydairlib/lcm/lcm_trajectory_plotter.py b/bindings/pydairlib/lcm/lcm_trajectory_plotter.py index 81a562028f..31c94ad2e2 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/lcm_trajectory_plotter.py @@ -5,97 +5,181 @@ def main(): - loadedTrajs = lcm_trajectory.LcmTrajectory() - # loadedTrajs.LoadFromFile( - # "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/jumping_0.15h_0.3d_processed") - # loadedTrajs.LoadFromFile( - # "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/walking_0.16.0_processed") - loadedTrajs.LoadFromFile( - "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/running_0.25_processed") - - lcm_left_foot_traj = loadedTrajs.GetTrajectory("left_foot_trajectory0") - lcm_right_foot_traj = loadedTrajs.GetTrajectory("right_foot_trajectory0") - lcm_pelvis_traj = loadedTrajs.GetTrajectory("pelvis_trans_trajectory0") - # lcm_pelvis_traj = loadedTrajs.GetTrajectory("pelvis_rot_trajectory0") - - # import pdb; pdb.set_trace() - # left_foot_traj = PiecewisePolynomial.CubicHermite(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints[0:6], - # lcm_left_foot_traj.datapoints[3:9]) - # right_foot_traj = PiecewisePolynomial.CubicHermite(lcm_right_foot_traj.time_vector, - # lcm_right_foot_traj.datapoints[0:6], - # lcm_right_foot_traj.datapoints[3:9]) - # pelvis_traj = PiecewisePolynomial.CubicHermite(lcm_pelvis_traj.time_vector, lcm_pelvis_traj.datapoints[0:6], - # lcm_pelvis_traj.datapoints[3:9]) - x_slice = slice(0,3) - xdot_slice = slice(3,6) - left_foot_traj = PiecewisePolynomial.CubicHermite(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints[x_slice], - lcm_left_foot_traj.datapoints[xdot_slice]) - right_foot_traj = PiecewisePolynomial.CubicHermite(lcm_right_foot_traj.time_vector, - lcm_right_foot_traj.datapoints[x_slice], - lcm_right_foot_traj.datapoints[xdot_slice]) - pelvis_traj = PiecewisePolynomial.CubicHermite(lcm_pelvis_traj.time_vector, lcm_pelvis_traj.datapoints[x_slice], - lcm_pelvis_traj.datapoints[xdot_slice]) - for mode in range(1, 6): - lcm_left_foot_traj = loadedTrajs.GetTrajectory("left_foot_trajectory" + str(mode)) - lcm_right_foot_traj = loadedTrajs.GetTrajectory("right_foot_trajectory" + str(mode)) - lcm_pelvis_traj = loadedTrajs.GetTrajectory("pelvis_trans_trajectory" + str(mode)) - - left_foot_traj.ConcatenateInTime( - PiecewisePolynomial.CubicHermite(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints[x_slice], - lcm_left_foot_traj.datapoints[xdot_slice])) - right_foot_traj.ConcatenateInTime( - PiecewisePolynomial.CubicHermite(lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints[x_slice], - lcm_right_foot_traj.datapoints[xdot_slice])) - pelvis_traj.ConcatenateInTime( - PiecewisePolynomial.CubicHermite(lcm_pelvis_traj.time_vector, lcm_pelvis_traj.datapoints[x_slice], - lcm_pelvis_traj.datapoints[xdot_slice])) - - # plt.figure('accel') - # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,2:3]) - # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,5:6]) - # plt.plot(times, accel[:, -1]) - # plt.figure("left_foot pos") - # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,0:3]) - # plt.legend(['x','y','z']) - # plt.figure("left_foot vel") - # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,3:6]) - # plt.legend(['x','y','z']) - # plt.figure("right_foot pos") - # plt.plot(lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints.T[:,0:3]) - # plt.legend(['x','y','z']) - # plt.figure("right_foot vel") - # plt.plot(lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints.T[:,3:6]) - # plt.legend(['x','y','z']) - - plot_trajectory(pelvis_traj, 'pelvis') - # plot_trajectory(left_foot_traj, 'left_foot') - # plot_trajectory(right_foot_traj, 'right_foot') - plt.show() + loadedTrajs = lcm_trajectory.LcmTrajectory() + # loadedTrajs.LoadFromFile( + # "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/jumping_0.15h_0.3d_processed") + # loadedTrajs.LoadFromFile( + # "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/walking_0.16.0_processed") + loadedTrajs.LoadFromFile( + "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/running_0.00_processed_rel") + + lcm_left_foot_traj = loadedTrajs.GetTrajectory("left_foot_trajectory0") + lcm_right_foot_traj = loadedTrajs.GetTrajectory("right_foot_trajectory0") + lcm_left_hip_traj = loadedTrajs.GetTrajectory("left_hip_trajectory0") + lcm_right_hip_traj = loadedTrajs.GetTrajectory("right_hip_trajectory0") + lcm_pelvis_traj = loadedTrajs.GetTrajectory("pelvis_trans_trajectory0") + # lcm_pelvis_traj = loadedTrajs.GetTrajectory("pelvis_rot_trajectory0") + + x_slice = slice(0, 6) + xdot_slice = slice(3, 9) + left_foot_traj = PiecewisePolynomial.CubicHermite(lcm_left_foot_traj.time_vector, + lcm_left_foot_traj.datapoints[x_slice], + lcm_left_foot_traj.datapoints[xdot_slice]) + right_foot_traj = PiecewisePolynomial.CubicHermite(lcm_right_foot_traj.time_vector, + lcm_right_foot_traj.datapoints[x_slice], + lcm_right_foot_traj.datapoints[xdot_slice]) + left_hip_traj = PiecewisePolynomial.CubicHermite(lcm_left_hip_traj.time_vector, + lcm_left_hip_traj.datapoints[x_slice], + lcm_left_hip_traj.datapoints[xdot_slice]) + right_hip_traj = PiecewisePolynomial.CubicHermite(lcm_right_hip_traj.time_vector, + lcm_right_hip_traj.datapoints[x_slice], + lcm_right_hip_traj.datapoints[xdot_slice]) + pelvis_traj = PiecewisePolynomial.CubicHermite(lcm_pelvis_traj.time_vector, lcm_pelvis_traj.datapoints[x_slice], + lcm_pelvis_traj.datapoints[xdot_slice]) + for mode in range(1, 6): + lcm_left_foot_traj = loadedTrajs.GetTrajectory("left_foot_trajectory" + str(mode)) + lcm_right_foot_traj = loadedTrajs.GetTrajectory("right_foot_trajectory" + str(mode)) + lcm_left_hip_traj = loadedTrajs.GetTrajectory("left_hip_trajectory" + str(mode)) + lcm_right_hip_traj = loadedTrajs.GetTrajectory("right_hip_trajectory" + str(mode)) + lcm_pelvis_traj = loadedTrajs.GetTrajectory("pelvis_trans_trajectory" + str(mode)) + + left_foot_traj.ConcatenateInTime( + PiecewisePolynomial.CubicHermite(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints[x_slice], + lcm_left_foot_traj.datapoints[xdot_slice])) + right_foot_traj.ConcatenateInTime( + PiecewisePolynomial.CubicHermite(lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints[x_slice], + lcm_right_foot_traj.datapoints[xdot_slice])) + left_hip_traj.ConcatenateInTime( + PiecewisePolynomial.CubicHermite(lcm_left_hip_traj.time_vector, lcm_left_hip_traj.datapoints[x_slice], + lcm_left_hip_traj.datapoints[xdot_slice])) + right_hip_traj.ConcatenateInTime( + PiecewisePolynomial.CubicHermite(lcm_right_hip_traj.time_vector, lcm_right_hip_traj.datapoints[x_slice], + lcm_right_hip_traj.datapoints[xdot_slice])) + pelvis_traj.ConcatenateInTime( + PiecewisePolynomial.CubicHermite(lcm_pelvis_traj.time_vector, lcm_pelvis_traj.datapoints[x_slice], + lcm_pelvis_traj.datapoints[xdot_slice])) + + # plt.figure('accel') + # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,2:3]) + # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,5:6]) + # plt.plot(times, accel[:, -1]) + # plt.figure("left_foot pos") + # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,0:3]) + # plt.legend(['x','y','z']) + # plt.figure("left_foot vel") + # plt.plot(lcm_left_foot_traj.time_vector, lcm_left_foot_traj.datapoints.T[:,3:6]) + # plt.legend(['x','y','z']) + # plt.figure("right_foot pos") + # plt.plot(lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints.T[:,0:3]) + # plt.legend(['x','y','z']) + # plt.figure("right_foot vel") + # plt.plot(lcm_right_foot_traj.time_vector, lcm_right_foot_traj.datapoints.T[:,3:6]) + # plt.legend(['x','y','z']) + + # reconstruct_trajectory(left_foot_traj) + reconstruct_trajectory_left_ft(left_foot_traj) + + # plot_trajectory(pelvis_traj, 'pelvis') + # plot_trajectory(left_foot_traj - left_hip_traj, 'left_foot') + # plot_trajectory(right_foot_traj, 'right_foot') + plt.show() def plot_trajectory(traj_of_interest, traj_name): - times = np.arange(traj_of_interest.start_time(), traj_of_interest.end_time(), 0.001) - # times = np.arange(traj_of_interest.start_time(), 0.2, 0.001) - y_dim = 3 - accel = np.zeros((times.shape[0], y_dim)) - pos = np.zeros((times.shape[0], y_dim)) - vel = np.zeros((times.shape[0], y_dim)) - for i in range(times.shape[0]): - pos[i, :] = traj_of_interest.value(times[i])[:, 0] - vel[i, :] = traj_of_interest.EvalDerivative(times[i], 1)[:, 0] - accel[i, :] = traj_of_interest.EvalDerivative(times[i], 2)[:, 0] - - plt.figure(traj_name + "_pos") - plt.plot(times, pos) - plt.legend(['x', 'y', 'z', 'xdot', 'ydot', 'zdot']) - plt.figure(traj_name + "_vel") - plt.plot(times, vel) - plt.legend(['xdot', 'ydot', 'zdot', 'xddot', 'yddot', 'zddot']) - plt.figure(traj_name + "_acc") - plt.plot(times, accel) - plt.legend(['xdot', 'ydot', 'zdot', 'xddot', 'yddot', 'zddot']) - # plt.legend(['pos','vel','accel']) + times = np.arange(traj_of_interest.start_time(), traj_of_interest.end_time(), 5e-4) + # times = np.arange(traj_of_interest.start_time(), 0.2, 0.001) + y_dim = 3 + accel = np.zeros((times.shape[0], y_dim)) + pos = np.zeros((times.shape[0], y_dim)) + vel = np.zeros((times.shape[0], y_dim)) + for i in range(times.shape[0]): + pos[i, :] = traj_of_interest.value(times[i])[:3, 0] + vel[i, :] = traj_of_interest.EvalDerivative(times[i], 1)[:3, 0] + accel[i, :] = traj_of_interest.EvalDerivative(times[i], 2)[-3:, 0] + + plt.figure(traj_name + "_pos") + plt.plot(times, pos) + plt.legend(['x', 'y', 'z', 'xdot', 'ydot', 'zdot']) + plt.figure(traj_name + "xz") + plt.plot(pos[:, 0], pos[:, 2]) + plt.legend(['xz']) + plt.figure(traj_name + "_vel") + plt.plot(times, vel) + plt.legend(['xdot', 'ydot', 'zdot', 'xddot', 'yddot', 'zddot']) + plt.figure(traj_name + "_acc") + plt.plot(times, accel) + plt.legend(['xdot', 'ydot', 'zdot', 'xddot', 'yddot', 'zddot']) + # plt.legend(['pos','vel','accel']) + + +def reconstruct_trajectory(trajectory): + T_waypoints = np.array([0.4, 0.8, 1.0]) + Y = np.zeros((3, 3)) + start_pos = np.array([0, 0, 0]) + end_pos = np.array([0.2, 0.1, 0]) + Y[0] = start_pos + Y[1] = start_pos + 0.85 * (end_pos - start_pos) + Y[1, 2] += 0.05 + Y[2] = end_pos + Y = Y.T + print(Y) + + Ydot_start = np.zeros(3) + Ydot_end = np.zeros(3) + + # traj = PiecewisePolynomial.CubicShapePreserving(T_waypoints, Y, True) + # traj = PiecewisePolynomial.CubicWithContinuousSecondDerivatives(T_waypoints, Y, Ydot_start, Ydot_end) + traj = PiecewisePolynomial.CubicWithContinuousSecondDerivatives(T_waypoints, Y, Ydot_start, Ydot_end) + + plot_trajectory(traj, "reconstructed_trajectory") + return traj + + +def reconstruct_trajectory_left_ft(trajectory): + ref = reconstruct_trajectory(trajectory) + + T_waypoints_0 = np.array([0.0, 0.3, 0.5]) + T_waypoints_midpoint = np.array([0.5, 0.9]) + T_waypoints_1 = np.array([0.9, 1.0]) + Y = np.zeros((3, 3)) + + start_pos = ref.value(0.5)[:, 0] + mid_pos = ref.value(0.8)[:, 0] + # end_pos = np.array([0.2, 0.1, 0]) + end_pos = ref.value(1.0)[:, 0] + Y[0] = start_pos + Y[1] = mid_pos + Y[2] = end_pos + Y = Y.T + print(Y) + + segment_0_start = ref.value(0.5)[:, 0] + segment_0_midpoint = ref.value(0.8)[:, 0] + segment_0_end = ref.value(1.0)[:, 0] + d_segment_0_start = ref.EvalDerivative(0.5, 1)[:, 0] + d_segment_0_midpoint = ref.EvalDerivative(0.8, 1)[:, 0] + d_segment_0_end = ref.EvalDerivative(1.0, 1)[:, 0] + segment_1_start = ref.value(0.4)[:, 0] + segment_1_end = ref.value(0.5)[:, 0] + d_segment_1_start = ref.EvalDerivative(0.4, 1)[:, 0] + d_segment_1_end = ref.EvalDerivative(0.5, 1)[:, 0] + + Ydot_start = np.zeros(3) + Ydot_end = np.zeros(3) + + print(np.array([end_pos, segment_1_start])) + # traj = PiecewisePolynomial.CubicShapePreserving(T_waypoints, Y, True) + traj_0 = PiecewisePolynomial.CubicHermite(T_waypoints_0, + np.array([segment_0_start, segment_0_midpoint, segment_0_end]).T, + np.array([d_segment_0_start, d_segment_0_midpoint, d_segment_0_end]).T) + traj_midpoint = PiecewisePolynomial.ZeroOrderHold(T_waypoints_midpoint, np.array([end_pos, end_pos]).T) + traj_1 = PiecewisePolynomial.CubicHermite(T_waypoints_1, np.array([segment_1_start, segment_1_end]).T, + np.array([d_segment_1_start, d_segment_1_end]).T) + + traj_0.ConcatenateInTime(traj_midpoint) + traj_0.ConcatenateInTime(traj_1) + plot_trajectory(traj_0, "reconstructed_trajectory_left") if __name__ == "__main__": - main() + main() diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index ffcd4c0ae1..3965e6ee55 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -63,12 +63,16 @@ DEFINE_double(init_height, .7, "ground"); DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); -DEFINE_string(radio_channel, "CASSIE_VIRTUAL_RADIO" ,"LCM channel for virtual radio command"); +DEFINE_string(radio_channel, "CASSIE_VIRTUAL_RADIO", + "LCM channel for virtual radio command"); DEFINE_string(channel_u, "CASSIE_INPUT", "LCM channel to receive controller inputs on"); DEFINE_double(actuator_delay, 0.0, "Duration of actuator delay. Set to 0.0 by default."); DEFINE_bool(publish_efforts, true, "Flag to publish the efforts."); +DEFINE_double(start_time, 0.0, + "Starting time of the simulator, useful for initializing the " + "state at a particular configuration"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -196,7 +200,7 @@ int do_main(int argc, char* argv[]) { } plant.SetPositions(&plant_context, q_init); plant.SetVelocities(&plant_context, VectorXd::Zero(plant.num_velocities())); - + diagram_context->SetTime(FLAGS_start_time); Simulator simulator(*diagram, std::move(diagram_context)); if (!FLAGS_time_stepping) { diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 792669656b..ebeba76309 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -24,28 +24,30 @@ using drake::trajectories::Trajectory; namespace dairlib::examples::osc_run { -FootTrajGenerator::FootTrajGenerator( - const MultibodyPlant& plant, Context* context, - const string& hip_name, bool isLeftFoot, - const PiecewisePolynomial& foot_traj, - const PiecewisePolynomial& hip_traj, bool relative_feet, - double time_offset) +FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, + Context* context, + const string& foot_name, + const string& hip_name, bool relative_feet, + std::vector state_durations) : plant_(plant), context_(context), world_(plant.world_frame()), + foot_frame_(plant.GetFrameByName(foot_name)), hip_frame_(plant.GetFrameByName(hip_name)), - foot_traj_(foot_traj), - hip_traj_(hip_traj), - is_left_foot_(isLeftFoot), - relative_feet_(relative_feet) { + relative_feet_(relative_feet), + state_durations_(state_durations) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; - if (isLeftFoot) { + if (foot_name == "toe_left") { + is_left_foot_ = true; + stance_state_ = 0; this->set_name("left_ft_traj"); this->DeclareAbstractOutputPort("left_ft_traj", traj_inst, &FootTrajGenerator::CalcTraj); } else { + is_left_foot_ = false; + stance_state_ = 1; this->set_name("right_ft_traj"); this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, &FootTrajGenerator::CalcTraj); @@ -57,35 +59,75 @@ FootTrajGenerator::FootTrajGenerator( plant_.num_velocities(), plant_.num_actuators())) .get_index(); - target_vel_port_ = - this->DeclareVectorInputPort("v_des", BasicVector(2)).get_index(); - fsm_port_ = - this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); - - // Shift trajectory by time_offset - foot_traj_.shiftRight(time_offset); - hip_traj_.shiftRight(time_offset); + target_vel_port_ = this->DeclareVectorInputPort( + "v_des", BasicVector(VectorXd::Zero(2))) + .get_index(); + fsm_port_ = this->DeclareVectorInputPort( + "fsm", BasicVector(VectorXd::Zero(1))) + .get_index(); + + // The swing foot position in the beginning of the swing phase + initial_foot_pos_idx_ = this->DeclareDiscreteState(3); + initial_hip_pos_idx_ = this->DeclareDiscreteState(3); + pelvis_yaw_idx_ = this->DeclareDiscreteState(1); + + // State variables inside this controller block + DeclarePerStepDiscreteUpdateEvent(&FootTrajGenerator::DiscreteVariableUpdate); } -PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( - const VectorXd& x, double t) const { - if (relative_feet_) { - return foot_traj_ - hip_traj_; - } else { - return foot_traj_; +EventStatus FootTrajGenerator::DiscreteVariableUpdate( + const Context& context, + DiscreteValues* discrete_state) const { + // Read in current state + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + // Read in finite state machine + VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); + + VectorXd q = robot_output->GetPositions(); + multibody::SetPositionsIfNew(plant_, q, context_); + + Vector3d pelvis_heading_vec = + plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) + .rotation() + .col(0); + double approx_pelvis_yaw = + atan2(pelvis_heading_vec(1), pelvis_heading_vec(0)); + discrete_state->get_mutable_vector(pelvis_yaw_idx_).get_mutable_value()(0) = + approx_pelvis_yaw; + + Eigen::Matrix3d rot; + rot << cos(approx_pelvis_yaw), -sin(approx_pelvis_yaw), 0, + sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; + + // Only update the current foot position when in stance ( + if (fsm_state(0) == stance_state_ || robot_output->get_timestamp() < 0.201) { + auto foot_pos = discrete_state->get_mutable_vector(initial_foot_pos_idx_) + .get_mutable_value(); + plant_.CalcPointsPositions(*context_, foot_frame_, Vector3d::Zero(), world_, + &foot_pos); + auto hip_pos = discrete_state->get_mutable_vector(initial_hip_pos_idx_) + .get_mutable_value(); + plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, + &hip_pos); + foot_pos = rot.transpose() * foot_pos; + hip_pos = rot.transpose() * hip_pos; } + + return EventStatus::Succeeded(); } -void FootTrajGenerator::AddRaibertCorrection( - const drake::systems::Context& context, - drake::trajectories::PiecewisePolynomial* traj) const { +PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( + const drake::systems::Context& context) const { const auto robot_output = this->template EvalVectorInput(context, state_port_); - const auto desired_pelvis_vel = + const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); VectorXd q = robot_output->GetPositions(); - multibody::SetPositionsIfNew(plant_, q, context_); + VectorXd v = robot_output->GetVelocities(); + multibody::SetPositionsAndVelocitiesIfNew( + plant_, robot_output->GetState(), context_); Vector3d pelvis_heading_vec = plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) @@ -97,49 +139,118 @@ void FootTrajGenerator::AddRaibertCorrection( rot << cos(approx_pelvis_yaw), -sin(approx_pelvis_yaw), 0, sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; - Vector3d desired_pelvis_pos = {0.0, 0, 0}; - VectorXd pelvis_pos = robot_output->GetPositions().segment(4, 3); - VectorXd pelvis_vel = robot_output->GetVelocities().segment(3, 3); - VectorXd pelvis_pos_err = rot.transpose() * pelvis_pos - desired_pelvis_pos; + // TODO(yangwill): should not use estimated pelvis velocity - from discussion + // with OSU DRL + Vector3d desired_pelvis_vel; + desired_pelvis_vel << desired_pelvis_vel_xy, 0; + VectorXd pelvis_vel = v.segment(3, 3); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; - VectorXd footstep_correction = - Kp_ * (pelvis_pos_err) + Kd_ * (pelvis_vel_err); + VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { - footstep_correction(1) -= center_line_offset_; - } else { footstep_correction(1) += center_line_offset_; + } else { + footstep_correction(1) -= center_line_offset_; } footstep_correction(0) += footstep_offset_; + footstep_correction(2) = 0; + + std::vector T_waypoints; + std::vector T_waypoints_0; + std::vector T_waypoints_1; + std::vector T_waypoints_2; + T_waypoints = {state_durations_[1], + state_durations_[1] + + 2.0 / 3.0 * (state_durations_[4] - state_durations_[1]), + state_durations_[4]}; + T_waypoints_0 = { + state_durations_[0], + (state_durations_[3] - state_durations_[4]) + + 2.0 / 3.0 * (0.1 + state_durations_[2] - state_durations_[0]), + state_durations_[2]}; + T_waypoints_1 = {state_durations_[2], state_durations_[3]}; + T_waypoints_2 = {state_durations_[3], state_durations_[4]}; + + auto foot_pos = context.get_discrete_state(initial_foot_pos_idx_).get_value(); + auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); + std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); + VectorXd start_pos = foot_pos - hip_pos; + Y[0] = start_pos; + Y[0](2) = -0.86; + Y[1] = start_pos + 0.85 * footstep_correction; + Y[1](2) = -0.83; + Y[2] = start_pos + footstep_correction; + Y[2](2) = -0.86; - std::vector breaks = traj->get_segment_times(); - VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - VectorXd new_samples = VectorXd(6); - new_samples << rot.transpose() * footstep_correction, Vector3d::Zero(); - MatrixXd foot_offset_points = new_samples.replicate(1, breaks.size()); - PiecewisePolynomial foot_offset_traj = - PiecewisePolynomial::ZeroOrderHold(breaks_vector, - foot_offset_points); - *traj = *traj + foot_offset_traj; + MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); + MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); + Y_dot_end(2) = -0.1; + + PiecewisePolynomial swing_foot_spline = + PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + T_waypoints, Y, Y_dot_start, Y_dot_end); + +// std::cout << "state durations" << std::endl; +// for(auto t : state_durations_){ +// std::cout << t << std::endl; +// } +// std::cout << "break points" << std::endl; +// for(auto t : T_waypoints){ +// std::cout << t << std::endl; +// } + + if (is_left_foot_) { + return swing_foot_spline; + } else { + // MatrixXd Y0 = MatrixXd::Zero(3, 3); + // MatrixXd Ydot0 = MatrixXd::Zero(3, 3); + // MatrixXd Y1 = MatrixXd::Zero(2, 3); + // MatrixXd Ydot1 = MatrixXd::Zero(2, 3); + std::vector Y0(T_waypoints_0.size(), VectorXd::Zero(3)); + std::vector Ydot0(T_waypoints_0.size(), VectorXd::Zero(3)); + std::vector Y2(T_waypoints_1.size(), VectorXd::Zero(3)); + std::vector Ydot2(T_waypoints_1.size(), VectorXd::Zero(3)); + Y0[0] = swing_foot_spline.value(state_durations_[2]); + Y0[1] = swing_foot_spline.value(T_waypoints[1]); + Y0[2] = swing_foot_spline.value(T_waypoints[2]); + Ydot0[0] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); + Ydot0[1] = swing_foot_spline.EvalDerivative(T_waypoints[1], 1); + Ydot0[2] = swing_foot_spline.EvalDerivative(T_waypoints[2], 1); + Y2[0] = swing_foot_spline.value(state_durations_[1]); + Y2[1] = swing_foot_spline.value(state_durations_[2]); + Ydot2[0] = swing_foot_spline.EvalDerivative(state_durations_[1], 1); + Ydot2[1] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); + PiecewisePolynomial offset_swing_foot_spline = + PiecewisePolynomial::CubicHermite(T_waypoints_0, Y0, Ydot0); + offset_swing_foot_spline.ConcatenateInTime( + PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); + offset_swing_foot_spline.ConcatenateInTime( + PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); +// for (auto t : offset_swing_foot_spline.get_segment_times()){ +// std::cout << t << std::endl; +// } + return offset_swing_foot_spline; + } + // return swing_foot_spline; } void FootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { // Read in current state - const auto robot_output = - this->template EvalVectorInput(context, state_port_); - VectorXd x = robot_output->GetState(); - double timestamp = robot_output->get_timestamp(); - - // Read in finite state machine - const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); + // const auto robot_output = + // this->template EvalVectorInput(context, state_port_); + // VectorXd x = robot_output->GetState(); + // double timestamp = robot_output->get_timestamp(); + // + // // Read in finite state machine + // const auto fsm_state = this->EvalVectorInput(context, + // fsm_port_)->get_value(); auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); // if (fsm_state[0] == FLIGHT) { - *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); - this->AddRaibertCorrection(context, casted_traj); + *casted_traj = GenerateFlightTraj(context); // } } diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index f9e775eb0a..2e03621d5f 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -11,13 +11,10 @@ namespace dairlib::examples::osc_run { class FootTrajGenerator : public drake::systems::LeafSystem { public: - FootTrajGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, const std::string& hip_name, - bool isLeftFoot, - const drake::trajectories::PiecewisePolynomial& foot_traj, - const drake::trajectories::PiecewisePolynomial& hip_traj, - bool relative_feet = false, double time_offset = 0.0); + FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const std::string& foot_name, const std::string& hip_name, + bool relative_feet, std::vector state_durations); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -29,22 +26,20 @@ class FootTrajGenerator : public drake::systems::LeafSystem { return this->get_input_port(target_vel_port_); } - void SetFootstepGains(const Eigen::MatrixXd& Kp, const Eigen::MatrixXd& Kd) { - Kp_ = Kp; - Kd_ = Kd; - }; + void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; - void SetFootPlacementOffsets(double center_line_offset, double footstep_offset){ + void SetFootPlacementOffsets(double center_line_offset, + double footstep_offset) { center_line_offset_ = center_line_offset; footstep_offset_ = footstep_offset; } private: - drake::trajectories::PiecewisePolynomial GenerateFlightTraj( - const Eigen::VectorXd& x, double t) const; - void AddRaibertCorrection( + drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, - drake::trajectories::PiecewisePolynomial* traj) const; + drake::systems::DiscreteValues* discrete_state) const; + drake::trajectories::PiecewisePolynomial GenerateFlightTraj( + const drake::systems::Context& context) const; void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -52,25 +47,29 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; const drake::multibody::Frame& world_; + const drake::multibody::Frame& foot_frame_; const drake::multibody::Frame& hip_frame_; + // Foot spline parameters + std::vector state_durations_; + // Foot placement constants double center_line_offset_; double footstep_offset_; // Raibert Footstep Gains - Eigen::MatrixXd Kp_ = Eigen::MatrixXd::Zero(2, 2); - Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(2, 2); - - drake::trajectories::PiecewisePolynomial foot_traj_; - drake::trajectories::PiecewisePolynomial hip_traj_; + Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(3, 3); bool is_left_foot_; bool relative_feet_; + int stance_state_; + int state_port_; int target_vel_port_; - int fsm_port_; + int initial_foot_pos_idx_; + int initial_hip_pos_idx_; + int pelvis_yaw_idx_; }; } // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 231279dba8..59cd7174aa 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -24,6 +24,8 @@ struct OSCRunningGains : OSCGains { bool relative_feet; bool relative_pelvis; double rest_length; + double stance_duration; + double flight_duration; double center_line_offset; double footstep_offset; @@ -41,10 +43,8 @@ struct OSCRunningGains : OSCGains { std::vector PelvisKp; std::vector PelvisKd; // pelvis orientation tracking - std::vector FootstepKp; std::vector FootstepKd; - MatrixXd K_p_footstep; MatrixXd K_d_footstep; MatrixXd W_pelvis; MatrixXd K_p_pelvis; @@ -79,13 +79,14 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); a->Visit(DRAKE_NVP(rest_length)); + a->Visit(DRAKE_NVP(stance_duration)); + a->Visit(DRAKE_NVP(flight_duration)); a->Visit(DRAKE_NVP(center_line_offset)); a->Visit(DRAKE_NVP(footstep_offset)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); a->Visit(DRAKE_NVP(PelvisKd)); - a->Visit(DRAKE_NVP(FootstepKp)); a->Visit(DRAKE_NVP(FootstepKd)); a->Visit(DRAKE_NVP(SwingFootW)); a->Visit(DRAKE_NVP(SwingFootKp)); @@ -137,9 +138,6 @@ struct OSCRunningGains : OSCGains { K_d_pelvis = Eigen::Map< Eigen::Matrix>( this->PelvisKd.data(), 3, 3); - K_p_footstep = Eigen::Map< - Eigen::Matrix>( - this->FootstepKp.data(), 3, 3); K_d_footstep = Eigen::Map< Eigen::Matrix>( this->FootstepKd.data(), 3, 3); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 78f9395818..d5fe291a26 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0000000000 w_accel: 0.0000 #w_soft_constraint: 1000000 -w_soft_constraint: 10000.0 +w_soft_constraint: 1000.0 w_input_reg: 0.001 impact_threshold: 0.050 relative_feet: true @@ -14,6 +14,8 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.9 +stance_duration: 0.33 +flight_duration: 0.1 mu: 0.8 @@ -30,17 +32,12 @@ hip_pitch_kd: 10 w_hip_roll: 5 hip_roll_kp: 50 hip_roll_kd: 10 - # Foot placement parameters -footstep_offset: -0.045 -center_line_offset: 0.06 -FootstepKp: - [0.00, 0, 0, - 0, 0.000, 0, - 0, 0, 0] +footstep_offset: 0.00 +center_line_offset: -0.02 FootstepKd: - [ 0.02, 0, 0, - 0, 0.041, 0, + [ 0.2, 0, 0, + 0, 0.01, 0, 0, 0, 0] PelvisW: @@ -50,7 +47,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 90] + 0, 0, 100] PelvisKd: [ 0, 0, 0, 0, 0, 0, @@ -60,21 +57,21 @@ SwingFootW: 0, 5, 0, 0, 0, 1] SwingFootKp: - [50, 0, 0, - 0, 50, 0, - 0, 0, 50] + [200, 0, 0, + 0, 200, 0, + 0, 0, 100] SwingFootKd: - [ 1, 0, 0, - 0, 3, 0, - 0, 0, 1] + [10, 0, 0, + 0, 3, 0, + 0, 0, 10] LiftoffSwingFootW: [0.1, 0, 0, 0, 0.5, 0, 0, 0, 1] LiftoffSwingFootKp: [25, 0, 0, - 0, 25, 0, - 0, 0, 50] + 0, 25, 0, + 0, 0, 50] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc index 2517b66a22..522a8eda58 100644 --- a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc @@ -85,16 +85,17 @@ PiecewisePolynomial PelvisPitchTrajGenerator::GeneratePelvisTraj( // correction << pelvis_pitch + q(7); correction << pelvis_pitch; +// std::cout << correction << std::endl; std::vector breaks = hip_pitch_traj_.get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); MatrixXd offset_angles = correction.replicate(1, breaks.size()); - for (int i = 0; i < breaks_vector.size(); ++i) { - offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); - } +// for (int i = 0; i < breaks_vector.size(); ++i) { +// offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); +// } PiecewisePolynomial offset_traj = PiecewisePolynomial::FirstOrderHold(breaks_vector, offset_angles); return hip_pitch_traj_ - offset_traj; - // return offset_traj; + // return -offset_traj; } void PelvisPitchTrajGenerator::CalcTraj( @@ -112,9 +113,9 @@ void PelvisPitchTrajGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (fsm_state == 0 || fsm_state == 1) { - *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); - } + // if (fsm_state == 0 || fsm_state == 1) { + *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); + // } } } // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc index 860eff7334..2d2c7cea15 100644 --- a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc @@ -31,14 +31,12 @@ namespace dairlib::examples::osc { PelvisRollTrajGenerator::PelvisRollTrajGenerator( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& hip_roll_traj, - drake::trajectories::PiecewisePolynomial& pelvis_roll_traj, - int axis, const std::string& system_name) + drake::trajectories::PiecewisePolynomial& hip_roll_traj, int axis, + const std::string& system_name) : plant_(plant), context_(context), world_(plant_.world_frame()), hip_roll_traj_(hip_roll_traj), - pelvis_roll_traj_(pelvis_roll_traj), axis_(axis) { this->set_name(system_name); // Input/Output Setup @@ -87,12 +85,14 @@ PiecewisePolynomial PelvisRollTrajGenerator::GeneratePelvisTraj( std::vector breaks = hip_roll_traj_.get_segment_times(); VectorXd breaks_vector = Map(breaks.data(), breaks.size()); MatrixXd offset_angles = correction.replicate(1, breaks.size()); -// for (int i = 0; i < breaks_vector.size(); ++i){ -// offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); -// } + // for (int i = 0; i < breaks_vector.size(); ++i) { + // offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); + // } + // std::cout << "breaks vector: " << breaks_vector << std::endl; PiecewisePolynomial offset_traj = PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_angles); return hip_roll_traj_ + offset_traj; + // return offset_traj; } void PelvisRollTrajGenerator::CalcTraj( @@ -110,9 +110,7 @@ void PelvisRollTrajGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (fsm_state == 0 || fsm_state == 1) { - *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); - } + *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); } } // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.h b/examples/Cassie/osc_run/pelvis_roll_traj_generator.h index 3d938e0ea1..617c628006 100644 --- a/examples/Cassie/osc_run/pelvis_roll_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_roll_traj_generator.h @@ -14,9 +14,13 @@ class PelvisRollTrajGenerator : public drake::systems::LeafSystem { PelvisRollTrajGenerator( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& hip_roll_traj, - drake::trajectories::PiecewisePolynomial& pelvis_roll_traj, - int axis, const std::string& system_name); + drake::trajectories::PiecewisePolynomial& hip_roll_traj, int axis, + const std::string& system_name); + + PelvisRollTrajGenerator(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + double offset, int axis, + const std::string& system_name); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -30,7 +34,8 @@ class PelvisRollTrajGenerator : public drake::systems::LeafSystem { private: drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( - const systems::OutputVector* robot_output, double t, int fsm_state) const; + const systems::OutputVector* robot_output, double t, + int fsm_state) const; drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, @@ -43,11 +48,9 @@ class PelvisRollTrajGenerator : public drake::systems::LeafSystem { drake::systems::Context* context_; const drake::multibody::BodyFrame& world_; - // drake::systems::DiscreteStateIndex prev_fsm_idx_; - // pelvis trajectory drake::trajectories::PiecewisePolynomial hip_roll_traj_; - drake::trajectories::PiecewisePolynomial pelvis_roll_traj_; + double neutral_offset_; // A list of pairs of contact body frame and contact point int axis_; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index d4f1493415..e4a65fe1a8 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -155,27 +155,45 @@ int DoMain(int argc, char* argv[]) { yaml_options.allow_yaml_with_no_cpp = true; drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); + OSCRunningGains osc_gains; + drake::yaml::YamlReadArchive(root).Accept(&osc_gains); + /**** FSM and contact mode configuration ****/ int left_stance_state = 0; int right_stance_state = 1; int right_touchdown_air_phase = 2; int left_touchdown_air_phase = 3; - double left_support_duration = - dircon_trajectory.GetStateBreaks(1)(0) * 2 - FLAGS_fsm_time_offset; - double right_support_duration = left_support_duration; - double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - - dircon_trajectory.GetStateBreaks(1)(0) + - FLAGS_fsm_time_offset; + // double left_support_duration = + // dircon_trajectory.GetStateBreaks(1)(0) * 2 - FLAGS_fsm_time_offset; + // double right_support_duration = left_support_duration; + // double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - + // dircon_trajectory.GetStateBreaks(1)(0) + + // FLAGS_fsm_time_offset; vector fsm_states = {left_stance_state, right_touchdown_air_phase, right_stance_state, left_touchdown_air_phase, left_stance_state}; - std::cout << "left support duration: " << left_support_duration << std::endl; - std::cout << "flight duration: " << air_phase_duration << std::endl; - std::cout << "right support duration: " << right_support_duration - << std::endl; + // std::cout << "left support duration: " << left_support_duration << + // std::endl; std::cout << "flight duration: " << air_phase_duration << + // std::endl; std::cout << "right support duration: " << + // right_support_duration + // << std::endl; vector state_durations = { - left_support_duration / 2, air_phase_duration, right_support_duration, - air_phase_duration, left_support_duration / 2}; + osc_gains.stance_duration, osc_gains.flight_duration, + osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; + vector accumulated_state_durations; + accumulated_state_durations.push_back(0); + std::cout << accumulated_state_durations.back() << std::endl; + for (double state_duration : state_durations) { + accumulated_state_durations.push_back(accumulated_state_durations.back() + + state_duration); + std::cout << accumulated_state_durations.back() << std::endl; + } + accumulated_state_durations.pop_back(); +// std::cout << accumulated_state_durations.back() << std::endl; + // VectorXd left_leg_active_duration(2); + // left_leg_active_duration << accumulated_state_durations[0], + // accumulated_state_durations VectorXd right_leg_active_duration = + // VectorXd{accumulated_state_durations[0]}; auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, gains.impact_threshold); @@ -264,8 +282,6 @@ int DoMain(int argc, char* argv[]) { /**** Tracking Data *****/ std::cout << "Creating tracking data. " << std::endl; - OSCRunningGains osc_gains; - drake::yaml::YamlReadArchive(root).Accept(&osc_gains); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( @@ -281,6 +297,7 @@ int DoMain(int argc, char* argv[]) { if (osc_gains.relative_feet) { output_traj_path += "_rel"; } + std::cout << "trajectory name: " << output_traj_path << std::endl; const LcmTrajectory& output_trajs = LcmTrajectory(FindResourceOrThrow(output_traj_path)); PiecewisePolynomial pelvis_trans_traj; @@ -290,9 +307,6 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial r_foot_trajectory; PiecewisePolynomial pelvis_rot_trajectory; - // for (auto name : output_trajs.GetTrajectoryNames()) { - // std::cout << name << std::endl; - // } for (int mode = 0; mode < dircon_trajectory.GetNumModes() * 2; ++mode) { const LcmTrajectory::Trajectory lcm_pelvis_trans_trajectory = output_trajs.GetTrajectory("pelvis_trans_trajectory" + @@ -343,6 +357,11 @@ int DoMain(int argc, char* argv[]) { lcm_pelvis_rot_traj.datapoints.topRows(4))); } + // std::cout << "left_foot_trajectory" << std::endl; + // for (auto t : l_foot_trajectory.get_segment_times()) { + // std::cout << t << std::endl; + // } + auto pelvis_trans_traj_generator = builder.AddSystem( plant, plant_context.get(), pelvis_trans_traj, feet_contact_points, @@ -351,15 +370,13 @@ int DoMain(int argc, char* argv[]) { // osc_gains.k_leg, // osc_gains.b_leg); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "hip_left", true, l_foot_trajectory, - l_hip_trajectory, osc_gains.relative_feet); + plant, plant_context.get(), "toe_left", "hip_left", + osc_gains.relative_feet, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "hip_right", false, r_foot_trajectory, - r_hip_trajectory, osc_gains.relative_feet); - l_foot_traj_generator->SetFootstepGains(osc_gains.K_p_footstep, - osc_gains.K_d_footstep); - r_foot_traj_generator->SetFootstepGains(osc_gains.K_p_footstep, - osc_gains.K_d_footstep); + plant, plant_context.get(), "toe_right", "hip_right", + osc_gains.relative_feet, accumulated_state_durations); + l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.center_line_offset, osc_gains.footstep_offset); r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.center_line_offset, @@ -505,13 +522,27 @@ int DoMain(int argc, char* argv[]) { // auto hip_pitch_right_traj_generator = // builder.AddSystem( // hip_pitch_right_traj, "hip_pitch_right_traj_generator"); + MatrixXd left_hip_pitch_neutral_angle(1, 2); + left_hip_pitch_neutral_angle << 0.055, 0.055; + MatrixXd right_hip_pitch_neutral_angle(1, 2); + right_hip_pitch_neutral_angle << 0.055, 0.055; + VectorXd full_trajectory_breaks(2); + full_trajectory_breaks << 0, accumulated_state_durations.back(); + PiecewisePolynomial left_hip_pitch_traj = + PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, + left_hip_pitch_neutral_angle); + PiecewisePolynomial right_hip_pitch_traj = + PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, + right_hip_pitch_neutral_angle); + + // TODO(yangwil): generate pitch trajectory auto hip_pitch_left_traj_generator = builder.AddSystem( - plant, plant_context.get(), hip_pitch_left_traj, pelvis_pitch_traj, 1, + plant, plant_context.get(), left_hip_pitch_traj, pelvis_pitch_traj, 1, "hip_pitch_left_traj_generator"); auto hip_pitch_right_traj_generator = builder.AddSystem( - plant, plant_context.get(), hip_pitch_right_traj, pelvis_pitch_traj, + plant, plant_context.get(), right_hip_pitch_traj, pelvis_pitch_traj, 1, "hip_pitch_right_traj_generator"); JointSpaceTrackingData left_hip_pitch_tracking_data( @@ -554,15 +585,27 @@ int DoMain(int argc, char* argv[]) { hip_roll_right_traj_mir.shiftRight(hip_roll_right_traj.end_time()); hip_roll_left_traj.ConcatenateInTime(hip_roll_left_traj_mir); hip_roll_right_traj.ConcatenateInTime(hip_roll_right_traj_mir); - PiecewisePolynomial pelvis_roll_traj = - PiecewisePolynomial(VectorXd::Zero(1)); + MatrixXd left_hip_roll_neutral_angle(1, 2); + left_hip_roll_neutral_angle << 0.02, 0.02; + MatrixXd right_hip_roll_neutral_angle(1, 2); + right_hip_roll_neutral_angle << -0.02, -0.02; +// VectorXd full_trajectory_breaks(2); + full_trajectory_breaks << 0, accumulated_state_durations.back(); + PiecewisePolynomial left_hip_roll_traj = + PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, + left_hip_roll_neutral_angle); + PiecewisePolynomial right_hip_roll_traj = + PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, + right_hip_roll_neutral_angle); + + // TODO(yangwil): generate roll trajectory auto hip_roll_left_traj_generator = builder.AddSystem( - plant, plant_context.get(), hip_roll_left_traj, pelvis_roll_traj, 1, + plant, plant_context.get(), left_hip_roll_traj, 1, "hip_roll_left_traj_generator"); auto hip_roll_right_traj_generator = builder.AddSystem( - plant, plant_context.get(), hip_roll_right_traj, pelvis_roll_traj, 1, + plant, plant_context.get(), right_hip_roll_traj, 1, "hip_roll_right_traj_generator"); JointSpaceTrackingData left_hip_roll_tracking_data( "hip_roll_left_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, From 73663e5350cda616f655b22b6a3541f9240b6b99 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 5 Jan 2022 16:05:43 -0500 Subject: [PATCH 065/758] need to tune footstep, but rest of trajectory is smooth --- examples/Cassie/osc_run/osc_running_gains.h | 19 ++ .../Cassie/osc_run/osc_running_gains.yaml | 28 +- examples/Cassie/run_osc_running_controller.cc | 272 ++++++++++-------- 3 files changed, 187 insertions(+), 132 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 59cd7174aa..605b887bb7 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -42,6 +42,10 @@ struct OSCRunningGains : OSCGains { std::vector PelvisW; std::vector PelvisKp; std::vector PelvisKd; + // pelvis tracking + std::vector PelvisRotW; + std::vector PelvisRotKp; + std::vector PelvisRotKd; // pelvis orientation tracking std::vector FootstepKd; @@ -49,6 +53,9 @@ struct OSCRunningGains : OSCGains { MatrixXd W_pelvis; MatrixXd K_p_pelvis; MatrixXd K_d_pelvis; + MatrixXd W_pelvis_rot; + MatrixXd K_p_pelvis_rot; + MatrixXd K_d_pelvis_rot; MatrixXd W_swing_foot; MatrixXd K_p_swing_foot; MatrixXd K_d_swing_foot; @@ -87,6 +94,9 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); a->Visit(DRAKE_NVP(PelvisKd)); + a->Visit(DRAKE_NVP(PelvisRotW)); + a->Visit(DRAKE_NVP(PelvisRotKp)); + a->Visit(DRAKE_NVP(PelvisRotKd)); a->Visit(DRAKE_NVP(FootstepKd)); a->Visit(DRAKE_NVP(SwingFootW)); a->Visit(DRAKE_NVP(SwingFootKp)); @@ -138,6 +148,15 @@ struct OSCRunningGains : OSCGains { K_d_pelvis = Eigen::Map< Eigen::Matrix>( this->PelvisKd.data(), 3, 3); + W_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotW.data(), 3, 3); + K_p_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKp.data(), 3, 3); + K_d_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKd.data(), 3, 3); K_d_footstep = Eigen::Map< Eigen::Matrix>( this->FootstepKd.data(), 3, 3); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d5fe291a26..983ece4e02 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -14,7 +14,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.9 -stance_duration: 0.33 +stance_duration: 0.40 flight_duration: 0.1 mu: 0.8 @@ -33,11 +33,11 @@ w_hip_roll: 5 hip_roll_kp: 50 hip_roll_kd: 10 # Foot placement parameters -footstep_offset: 0.00 -center_line_offset: -0.02 +footstep_offset: -0.001 +center_line_offset: -0.025 FootstepKd: [ 0.2, 0, 0, - 0, 0.01, 0, + 0, 0.025, 0, 0, 0, 0] PelvisW: @@ -47,22 +47,34 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 100] + 0, 0, 90] PelvisKd: [ 0, 0, 0, 0, 0, 0, 0, 0, 5] +PelvisRotW: + [1, 0, 0, + 0, 1, 0, + 0, 0, 0] +PelvisRotKp: + [100, 0, 0, + 0, 50, 0, + 0, 0, 0] +PelvisRotKd: + [5, 0, 0, + 0, 5, 0, + 0, 0, 0] SwingFootW: [1, 0, 0, 0, 5, 0, 0, 0, 1] SwingFootKp: - [200, 0, 0, - 0, 200, 0, + [150, 0, 0, + 0, 150, 0, 0, 0, 100] SwingFootKd: [10, 0, 0, - 0, 3, 0, + 0, 10, 0, 0, 0, 10] LiftoffSwingFootW: [0.1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index e4a65fe1a8..f8669efa64 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -7,6 +7,7 @@ #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" @@ -189,7 +190,7 @@ int DoMain(int argc, char* argv[]) { std::cout << accumulated_state_durations.back() << std::endl; } accumulated_state_durations.pop_back(); -// std::cout << accumulated_state_durations.back() << std::endl; + // std::cout << accumulated_state_durations.back() << std::endl; // VectorXd left_leg_active_duration(2); // left_leg_active_duration << accumulated_state_durations[0], // accumulated_state_durations VectorXd right_leg_active_duration = @@ -535,98 +536,114 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, right_hip_pitch_neutral_angle); - // TODO(yangwil): generate pitch trajectory - auto hip_pitch_left_traj_generator = - builder.AddSystem( - plant, plant_context.get(), left_hip_pitch_traj, pelvis_pitch_traj, 1, - "hip_pitch_left_traj_generator"); - auto hip_pitch_right_traj_generator = - builder.AddSystem( - plant, plant_context.get(), right_hip_pitch_traj, pelvis_pitch_traj, - 1, "hip_pitch_right_traj_generator"); - - JointSpaceTrackingData left_hip_pitch_tracking_data( - "hip_pitch_left_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, - osc_gains.W_hip_pitch, plant, plant); - JointSpaceTrackingData right_hip_pitch_tracking_data( - "hip_pitch_right_traj", osc_gains.K_p_hip_pitch, osc_gains.K_d_hip_pitch, - osc_gains.W_hip_pitch, plant, plant); - left_hip_pitch_tracking_data.AddStateAndJointToTrack( - left_stance_state, "hip_pitch_left", "hip_pitch_leftdot"); - left_hip_pitch_tracking_data.AddStateAndJointToTrack( - right_touchdown_air_phase, "hip_pitch_left", "hip_pitch_leftdot"); - right_hip_pitch_tracking_data.AddStateAndJointToTrack( - right_stance_state, "hip_pitch_right", "hip_pitch_rightdot"); - right_hip_pitch_tracking_data.AddStateAndJointToTrack( - left_touchdown_air_phase, "hip_pitch_right", "hip_pitch_rightdot"); - left_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); - right_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); - left_hip_pitch_tracking_data.SetImpactInvariantProjection(true); - right_hip_pitch_tracking_data.SetImpactInvariantProjection(true); - // osc->AddConstTrackingData(&hip_pitch_left_tracking_data, - // 0.6 * VectorXd::Ones(1)); - // osc->AddConstTrackingData(&hip_pitch_right_tracking_data, - // 0.6 * VectorXd::Ones(1)); - osc->AddTrackingData(&left_hip_pitch_tracking_data); - osc->AddTrackingData(&right_hip_pitch_tracking_data); - - // Stance hip roll trajectory - auto hip_roll_left_traj = dircon_trajectory.ReconstructJointTrajectory( - pos_map_wo_spr["hip_roll_left"]); - auto hip_roll_left_traj_mir = - dircon_trajectory.ReconstructMirrorJointTrajectory( - pos_map_wo_spr["hip_roll_left"]); - auto hip_roll_right_traj = dircon_trajectory.ReconstructJointTrajectory( - pos_map_wo_spr["hip_roll_right"]); - auto hip_roll_right_traj_mir = - dircon_trajectory.ReconstructMirrorJointTrajectory( - pos_map_wo_spr["hip_roll_right"]); - hip_roll_left_traj_mir.shiftRight(hip_roll_left_traj.end_time()); - hip_roll_right_traj_mir.shiftRight(hip_roll_right_traj.end_time()); - hip_roll_left_traj.ConcatenateInTime(hip_roll_left_traj_mir); - hip_roll_right_traj.ConcatenateInTime(hip_roll_right_traj_mir); - MatrixXd left_hip_roll_neutral_angle(1, 2); - left_hip_roll_neutral_angle << 0.02, 0.02; - MatrixXd right_hip_roll_neutral_angle(1, 2); - right_hip_roll_neutral_angle << -0.02, -0.02; -// VectorXd full_trajectory_breaks(2); - full_trajectory_breaks << 0, accumulated_state_durations.back(); - PiecewisePolynomial left_hip_roll_traj = - PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, - left_hip_roll_neutral_angle); - PiecewisePolynomial right_hip_roll_traj = - PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, - right_hip_roll_neutral_angle); - - // TODO(yangwil): generate roll trajectory - auto hip_roll_left_traj_generator = - builder.AddSystem( - plant, plant_context.get(), left_hip_roll_traj, 1, - "hip_roll_left_traj_generator"); - auto hip_roll_right_traj_generator = - builder.AddSystem( - plant, plant_context.get(), right_hip_roll_traj, 1, - "hip_roll_right_traj_generator"); - JointSpaceTrackingData left_hip_roll_tracking_data( - "hip_roll_left_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, - osc_gains.W_hip_roll, plant, plant); - JointSpaceTrackingData right_hip_roll_tracking_data( - "hip_roll_right_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, - osc_gains.W_hip_roll, plant, plant); - left_hip_roll_tracking_data.AddStateAndJointToTrack( - left_stance_state, "hip_roll_left", "hip_roll_leftdot"); - left_hip_roll_tracking_data.AddStateAndJointToTrack( - right_touchdown_air_phase, "hip_roll_left", "hip_roll_leftdot"); - right_hip_roll_tracking_data.AddStateAndJointToTrack( - right_stance_state, "hip_roll_right", "hip_roll_rightdot"); - right_hip_roll_tracking_data.AddStateAndJointToTrack( - left_touchdown_air_phase, "hip_roll_right", "hip_roll_rightdot"); - left_hip_roll_tracking_data.DisableFeedforwardAccel({0}); - right_hip_roll_tracking_data.DisableFeedforwardAccel({0}); - left_hip_roll_tracking_data.SetImpactInvariantProjection(true); - right_hip_roll_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_hip_roll_tracking_data); - osc->AddTrackingData(&right_hip_roll_tracking_data); + // // TODO(yangwil): generate pitch trajectory + // auto hip_pitch_left_traj_generator = + // builder.AddSystem( + // plant, plant_context.get(), left_hip_pitch_traj, + // pelvis_pitch_traj, 1, "hip_pitch_left_traj_generator"); + // auto hip_pitch_right_traj_generator = + // builder.AddSystem( + // plant, plant_context.get(), right_hip_pitch_traj, + // pelvis_pitch_traj, 1, "hip_pitch_right_traj_generator"); + // + // JointSpaceTrackingData left_hip_pitch_tracking_data( + // "hip_pitch_left_traj", osc_gains.K_p_hip_pitch, + // osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); + // JointSpaceTrackingData right_hip_pitch_tracking_data( + // "hip_pitch_right_traj", osc_gains.K_p_hip_pitch, + // osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); + // left_hip_pitch_tracking_data.AddStateAndJointToTrack( + // left_stance_state, "hip_pitch_left", "hip_pitch_leftdot"); + // left_hip_pitch_tracking_data.AddStateAndJointToTrack( + // right_touchdown_air_phase, "hip_pitch_left", "hip_pitch_leftdot"); + // right_hip_pitch_tracking_data.AddStateAndJointToTrack( + // right_stance_state, "hip_pitch_right", "hip_pitch_rightdot"); + // right_hip_pitch_tracking_data.AddStateAndJointToTrack( + // left_touchdown_air_phase, "hip_pitch_right", "hip_pitch_rightdot"); + // left_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); + // right_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); + // left_hip_pitch_tracking_data.SetImpactInvariantProjection(true); + // right_hip_pitch_tracking_data.SetImpactInvariantProjection(true); + // // osc->AddConstTrackingData(&hip_pitch_left_tracking_data, + // // 0.6 * VectorXd::Ones(1)); + // // osc->AddConstTrackingData(&hip_pitch_right_tracking_data, + // // 0.6 * VectorXd::Ones(1)); + // osc->AddTrackingData(&left_hip_pitch_tracking_data); + // osc->AddTrackingData(&right_hip_pitch_tracking_data); + // + // // Stance hip roll trajectory + // auto hip_roll_left_traj = dircon_trajectory.ReconstructJointTrajectory( + // pos_map_wo_spr["hip_roll_left"]); + // auto hip_roll_left_traj_mir = + // dircon_trajectory.ReconstructMirrorJointTrajectory( + // pos_map_wo_spr["hip_roll_left"]); + // auto hip_roll_right_traj = dircon_trajectory.ReconstructJointTrajectory( + // pos_map_wo_spr["hip_roll_right"]); + // auto hip_roll_right_traj_mir = + // dircon_trajectory.ReconstructMirrorJointTrajectory( + // pos_map_wo_spr["hip_roll_right"]); + // hip_roll_left_traj_mir.shiftRight(hip_roll_left_traj.end_time()); + // hip_roll_right_traj_mir.shiftRight(hip_roll_right_traj.end_time()); + // hip_roll_left_traj.ConcatenateInTime(hip_roll_left_traj_mir); + // hip_roll_right_traj.ConcatenateInTime(hip_roll_right_traj_mir); + // MatrixXd left_hip_roll_neutral_angle(1, 2); + // left_hip_roll_neutral_angle << 0.02, 0.02; + // MatrixXd right_hip_roll_neutral_angle(1, 2); + // right_hip_roll_neutral_angle << -0.02, -0.02; + // VectorXd full_trajectory_breaks(2); + // full_trajectory_breaks << 0, accumulated_state_durations.back(); + // PiecewisePolynomial left_hip_roll_traj = + // PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, + // left_hip_roll_neutral_angle); + // PiecewisePolynomial right_hip_roll_traj = + // PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, + // right_hip_roll_neutral_angle); + // + // // TODO(yangwil): generate roll trajectory + // auto hip_roll_left_traj_generator = + // builder.AddSystem( + // plant, plant_context.get(), left_hip_roll_traj, 1, + // "hip_roll_left_traj_generator"); + // auto hip_roll_right_traj_generator = + // builder.AddSystem( + // plant, plant_context.get(), right_hip_roll_traj, 1, + // "hip_roll_right_traj_generator"); + // JointSpaceTrackingData left_hip_roll_tracking_data( + // "hip_roll_left_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, + // osc_gains.W_hip_roll, plant, plant); + // JointSpaceTrackingData right_hip_roll_tracking_data( + // "hip_roll_right_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, + // osc_gains.W_hip_roll, plant, plant); + // left_hip_roll_tracking_data.AddStateAndJointToTrack( + // left_stance_state, "hip_roll_left", "hip_roll_leftdot"); + // left_hip_roll_tracking_data.AddStateAndJointToTrack( + // right_touchdown_air_phase, "hip_roll_left", "hip_roll_leftdot"); + // right_hip_roll_tracking_data.AddStateAndJointToTrack( + // right_stance_state, "hip_roll_right", "hip_roll_rightdot"); + // right_hip_roll_tracking_data.AddStateAndJointToTrack( + // left_touchdown_air_phase, "hip_roll_right", "hip_roll_rightdot"); + // left_hip_roll_tracking_data.DisableFeedforwardAccel({0}); + // right_hip_roll_tracking_data.DisableFeedforwardAccel({0}); + // left_hip_roll_tracking_data.SetImpactInvariantProjection(true); + // right_hip_roll_tracking_data.SetImpactInvariantProjection(true); + // osc->AddTrackingData(&left_hip_roll_tracking_data); + // osc->AddTrackingData(&right_hip_roll_tracking_data); + + auto heading_traj_generator = builder.AddSystem( + plant, plant_context.get()); + + + RotTaskSpaceTrackingData pelvis_rot_tracking_data( + "pelvis_rot_tracking_data", osc_gains.K_p_pelvis_rot, + osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, + "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_touchdown_air_phase, "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_touchdown_air_phase, + "pelvis"); + pelvis_rot_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&pelvis_rot_tracking_data); // Swing toe joint trajectory vector&>> left_foot_points = { @@ -719,41 +736,48 @@ int DoMain(int argc, char* argv[]) { left_toe_angle_traj_gen->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), right_toe_angle_traj_gen->get_state_input_port()); - builder.Connect(hip_pitch_left_traj_generator->get_output_port(), - osc->get_tracking_data_input_port("hip_pitch_left_traj")); - builder.Connect(hip_pitch_right_traj_generator->get_output_port(), - osc->get_tracking_data_input_port("hip_pitch_right_traj")); - builder.Connect(hip_roll_left_traj_generator->get_output_port(), - osc->get_tracking_data_input_port("hip_roll_left_traj")); - builder.Connect(hip_roll_right_traj_generator->get_output_port(), - osc->get_tracking_data_input_port("hip_roll_right_traj")); + // builder.Connect(hip_pitch_left_traj_generator->get_output_port(), + // osc->get_tracking_data_input_port("hip_pitch_left_traj")); + // builder.Connect(hip_pitch_right_traj_generator->get_output_port(), + // osc->get_tracking_data_input_port("hip_pitch_right_traj")); + // builder.Connect(hip_roll_left_traj_generator->get_output_port(), + // osc->get_tracking_data_input_port("hip_roll_left_traj")); + // builder.Connect(hip_roll_right_traj_generator->get_output_port(), + // osc->get_tracking_data_input_port("hip_roll_right_traj")); // OSC connections builder.Connect(pelvis_trans_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("pelvis_trans_traj")); builder.Connect(state_receiver->get_output_port(0), - hip_roll_left_traj_generator->get_state_input_port()); - builder.Connect(state_receiver->get_output_port(0), - hip_roll_right_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - hip_roll_left_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - hip_roll_right_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_clock(), - hip_roll_left_traj_generator->get_clock_input_port()); - builder.Connect(fsm->get_output_port_clock(), - hip_roll_right_traj_generator->get_clock_input_port()); - builder.Connect(state_receiver->get_output_port(0), - hip_pitch_left_traj_generator->get_state_input_port()); - builder.Connect(state_receiver->get_output_port(0), - hip_pitch_right_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - hip_pitch_left_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - hip_pitch_right_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_clock(), - hip_pitch_left_traj_generator->get_clock_input_port()); - builder.Connect(fsm->get_output_port_clock(), - hip_pitch_right_traj_generator->get_clock_input_port()); + heading_traj_generator->get_state_input_port()); + builder.Connect(high_level_command->get_yaw_output_port(), + heading_traj_generator->get_yaw_input_port()); + builder.Connect( + heading_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_rot_tracking_data")); + // builder.Connect(state_receiver->get_output_port(0), + // hip_roll_left_traj_generator->get_state_input_port()); + // builder.Connect(state_receiver->get_output_port(0), + // hip_roll_right_traj_generator->get_state_input_port()); + // builder.Connect(fsm->get_output_port_fsm(), + // hip_roll_left_traj_generator->get_fsm_input_port()); + // builder.Connect(fsm->get_output_port_fsm(), + // hip_roll_right_traj_generator->get_fsm_input_port()); + // builder.Connect(fsm->get_output_port_clock(), + // hip_roll_left_traj_generator->get_clock_input_port()); + // builder.Connect(fsm->get_output_port_clock(), + // hip_roll_right_traj_generator->get_clock_input_port()); + // builder.Connect(state_receiver->get_output_port(0), + // hip_pitch_left_traj_generator->get_state_input_port()); + // builder.Connect(state_receiver->get_output_port(0), + // hip_pitch_right_traj_generator->get_state_input_port()); + // builder.Connect(fsm->get_output_port_fsm(), + // hip_pitch_left_traj_generator->get_fsm_input_port()); + // builder.Connect(fsm->get_output_port_fsm(), + // hip_pitch_right_traj_generator->get_fsm_input_port()); + // builder.Connect(fsm->get_output_port_clock(), + // hip_pitch_left_traj_generator->get_clock_input_port()); + // builder.Connect(fsm->get_output_port_clock(), + // hip_pitch_right_traj_generator->get_clock_input_port()); builder.Connect(l_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), From 61cb7bda36769b39f3ced026bdbd8c9148eeb8a5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Jan 2022 11:01:08 -0500 Subject: [PATCH 066/758] working on making running stable --- .../plot_configs/cassie_running_plot.yaml | 5 ++--- examples/Cassie/osc_run/foot_traj_generator.cc | 9 ++++++++- examples/Cassie/osc_run/osc_running_gains.yaml | 15 +++++++-------- examples/Cassie/run_osc_running_controller.cc | 4 ++-- 4 files changed, 19 insertions(+), 14 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 0ce93ca5d7..02af525300 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -27,10 +27,9 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos', 'vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} -# hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} - hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} # left_ft_traj: {'dims': [2], 'derivs': ['pos']} # right_ft_traj: {'dims': [2], 'derivs': ['pos']} # left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index ebeba76309..e0e3153647 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -176,8 +176,15 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; Y[0](2) = -0.86; + Y[1] = start_pos + 0.85 * footstep_correction; - Y[1](2) = -0.83; + if (is_left_foot_) { + Y[1](1) += 0.5 * center_line_offset_; + } else { + Y[1](1) -= 0.5 * center_line_offset_; + } + Y[1](2) = -0.845; + Y[2] = start_pos + footstep_correction; Y[2](2) = -0.86; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 983ece4e02..11cd1158cc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -14,8 +14,8 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.9 -stance_duration: 0.40 -flight_duration: 0.1 +stance_duration: 0.37 +flight_duration: 0.13 mu: 0.8 @@ -34,12 +34,11 @@ hip_roll_kp: 50 hip_roll_kd: 10 # Foot placement parameters footstep_offset: -0.001 -center_line_offset: -0.025 +center_line_offset: -0.02 FootstepKd: [ 0.2, 0, 0, - 0, 0.025, 0, + 0, 0.05, 0, 0, 0, 0] - PelvisW: [ 0, 0, 0, 0, 0, 0, @@ -58,11 +57,11 @@ PelvisRotW: 0, 0, 0] PelvisRotKp: [100, 0, 0, - 0, 50, 0, + 0, 100, 0, 0, 0, 0] PelvisRotKd: - [5, 0, 0, - 0, 5, 0, + [10, 0, 0, + 0, 10, 0, 0, 0, 0] SwingFootW: [1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index f8669efa64..6e10c63113 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -634,7 +634,7 @@ int DoMain(int argc, char* argv[]) { RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_tracking_data", osc_gains.K_p_pelvis_rot, + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, @@ -753,7 +753,7 @@ int DoMain(int argc, char* argv[]) { heading_traj_generator->get_yaw_input_port()); builder.Connect( heading_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_tracking_data")); + osc->get_tracking_data_input_port("pelvis_rot_traj")); // builder.Connect(state_receiver->get_output_port(0), // hip_roll_left_traj_generator->get_state_input_port()); // builder.Connect(state_receiver->get_output_port(0), From 97f93b69b5b0e110c038bf158d32bcbca0ff7d01 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Jan 2022 14:44:20 -0500 Subject: [PATCH 067/758] need to improve estimate of pelvis vel --- .../plot_configs/cassie_running_plot.yaml | 16 +- .../pydairlib/lcm/lcm_trajectory_plotter.py | 3 + .../Cassie/osc_run/osc_running_gains.yaml | 42 ++--- examples/Cassie/run_osc_running_controller.cc | 150 +++--------------- 4 files changed, 52 insertions(+), 159 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 02af525300..65b60bcaf1 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -27,10 +27,12 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos', 'vel']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} -# left_ft_traj: {'dims': [2], 'derivs': ['pos']} -# right_ft_traj: {'dims': [2], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} +# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} +# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} +# hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} +# hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} +# left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} +# right_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} +# left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} +# right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} diff --git a/bindings/pydairlib/lcm/lcm_trajectory_plotter.py b/bindings/pydairlib/lcm/lcm_trajectory_plotter.py index 31c94ad2e2..3d7b020833 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/lcm_trajectory_plotter.py @@ -103,6 +103,9 @@ def plot_trajectory(traj_of_interest, traj_name): plt.figure(traj_name + "xz") plt.plot(pos[:, 0], pos[:, 2]) plt.legend(['xz']) + plt.figure(traj_name + "yz") + plt.plot(pos[:, 1], pos[:, 2]) + plt.legend(['yz']) plt.figure(traj_name + "_vel") plt.plot(times, vel) plt.legend(['xdot', 'ydot', 'zdot', 'xddot', 'yddot', 'zddot']) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 11cd1158cc..25886de175 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -14,8 +14,8 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.9 -stance_duration: 0.37 -flight_duration: 0.13 +stance_duration: 0.36 +flight_duration: 0.11 mu: 0.8 @@ -23,7 +23,7 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 200 +w_hip_yaw: 100 hip_yaw_kp: 100 hip_yaw_kd: 15 w_hip_pitch: 5 @@ -33,11 +33,11 @@ w_hip_roll: 5 hip_roll_kp: 50 hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.001 -center_line_offset: -0.02 +footstep_offset: -0.0075 +center_line_offset: -0.05 FootstepKd: - [ 0.2, 0, 0, - 0, 0.05, 0, + [ 0.15, 0, 0, + 0, 0.1, 0, 0, 0, 0] PelvisW: [ 0, 0, 0, @@ -46,45 +46,45 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 90] + 0, 0, 92] PelvisKd: [ 0, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [1, 0, 0, + [2, 0, 0, 0, 1, 0, - 0, 0, 0] + 0, 0, 0] PelvisRotKp: [100, 0, 0, - 0, 100, 0, + 0, 25, 0, 0, 0, 0] PelvisRotKd: [10, 0, 0, - 0, 10, 0, + 0, 1, 0, 0, 0, 0] SwingFootW: [1, 0, 0, - 0, 5, 0, + 0, 25, 0, 0, 0, 1] SwingFootKp: - [150, 0, 0, - 0, 150, 0, - 0, 0, 100] + [125, 0, 0, + 0, 125, 0, + 0, 0, 50] SwingFootKd: [10, 0, 0, - 0, 10, 0, - 0, 0, 10] + 0, 20, 0, + 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, - 0, 0.5, 0, + 0, 2, 0, 0, 0, 1] LiftoffSwingFootKp: [25, 0, 0, - 0, 25, 0, + 0, 200, 0, 0, 0, 50] LiftoffSwingFootKd: [ 1, 0, 0, - 0, 1, 0, + 0, 1, 0, 0, 0, 1] diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 6e10c63113..80c3ed19ca 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -472,33 +472,20 @@ int DoMain(int argc, char* argv[]) { left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); +// left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); +// right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - if (osc_gains.relative_pelvis) { - osc->AddTrackingData(&pelvis_trans_rel_tracking_data); - } else { - osc->AddTrackingData(&pelvis_tracking_data); - } - - if (osc_gains.relative_feet) { - left_foot_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_foot_rel_tracking_data); - osc->AddTrackingData(&right_foot_rel_tracking_data); - // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_foot_yz_rel_tracking_data); - osc->AddTrackingData(&right_foot_yz_rel_tracking_data); - } else { - left_foot_tracking_data.SetImpactInvariantProjection(true); - right_foot_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_foot_tracking_data); - osc->AddTrackingData(&right_foot_tracking_data); - } + osc->AddTrackingData(&pelvis_trans_rel_tracking_data); + osc->AddTrackingData(&left_foot_rel_tracking_data); + osc->AddTrackingData(&right_foot_rel_tracking_data); + osc->AddTrackingData(&left_foot_yz_rel_tracking_data); + osc->AddTrackingData(&right_foot_yz_rel_tracking_data); // Stance hip pitch trajectory auto hip_pitch_left_traj = dircon_trajectory.ReconstructJointTrajectory( @@ -517,12 +504,6 @@ int DoMain(int argc, char* argv[]) { hip_pitch_right_traj_mir.shiftRight(hip_pitch_right_traj.end_time()); hip_pitch_left_traj.ConcatenateInTime(hip_pitch_left_traj_mir); hip_pitch_right_traj.ConcatenateInTime(hip_pitch_right_traj_mir); - // auto hip_pitch_left_traj_generator = - // builder.AddSystem( - // hip_pitch_left_traj, "hip_pitch_left_traj_generator"); - // auto hip_pitch_right_traj_generator = - // builder.AddSystem( - // hip_pitch_right_traj, "hip_pitch_right_traj_generator"); MatrixXd left_hip_pitch_neutral_angle(1, 2); left_hip_pitch_neutral_angle << 0.055, 0.055; MatrixXd right_hip_pitch_neutral_angle(1, 2); @@ -536,110 +517,18 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, right_hip_pitch_neutral_angle); - // // TODO(yangwil): generate pitch trajectory - // auto hip_pitch_left_traj_generator = - // builder.AddSystem( - // plant, plant_context.get(), left_hip_pitch_traj, - // pelvis_pitch_traj, 1, "hip_pitch_left_traj_generator"); - // auto hip_pitch_right_traj_generator = - // builder.AddSystem( - // plant, plant_context.get(), right_hip_pitch_traj, - // pelvis_pitch_traj, 1, "hip_pitch_right_traj_generator"); - // - // JointSpaceTrackingData left_hip_pitch_tracking_data( - // "hip_pitch_left_traj", osc_gains.K_p_hip_pitch, - // osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); - // JointSpaceTrackingData right_hip_pitch_tracking_data( - // "hip_pitch_right_traj", osc_gains.K_p_hip_pitch, - // osc_gains.K_d_hip_pitch, osc_gains.W_hip_pitch, plant, plant); - // left_hip_pitch_tracking_data.AddStateAndJointToTrack( - // left_stance_state, "hip_pitch_left", "hip_pitch_leftdot"); - // left_hip_pitch_tracking_data.AddStateAndJointToTrack( - // right_touchdown_air_phase, "hip_pitch_left", "hip_pitch_leftdot"); - // right_hip_pitch_tracking_data.AddStateAndJointToTrack( - // right_stance_state, "hip_pitch_right", "hip_pitch_rightdot"); - // right_hip_pitch_tracking_data.AddStateAndJointToTrack( - // left_touchdown_air_phase, "hip_pitch_right", "hip_pitch_rightdot"); - // left_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); - // right_hip_pitch_tracking_data.DisableFeedforwardAccel({0}); - // left_hip_pitch_tracking_data.SetImpactInvariantProjection(true); - // right_hip_pitch_tracking_data.SetImpactInvariantProjection(true); - // // osc->AddConstTrackingData(&hip_pitch_left_tracking_data, - // // 0.6 * VectorXd::Ones(1)); - // // osc->AddConstTrackingData(&hip_pitch_right_tracking_data, - // // 0.6 * VectorXd::Ones(1)); - // osc->AddTrackingData(&left_hip_pitch_tracking_data); - // osc->AddTrackingData(&right_hip_pitch_tracking_data); - // - // // Stance hip roll trajectory - // auto hip_roll_left_traj = dircon_trajectory.ReconstructJointTrajectory( - // pos_map_wo_spr["hip_roll_left"]); - // auto hip_roll_left_traj_mir = - // dircon_trajectory.ReconstructMirrorJointTrajectory( - // pos_map_wo_spr["hip_roll_left"]); - // auto hip_roll_right_traj = dircon_trajectory.ReconstructJointTrajectory( - // pos_map_wo_spr["hip_roll_right"]); - // auto hip_roll_right_traj_mir = - // dircon_trajectory.ReconstructMirrorJointTrajectory( - // pos_map_wo_spr["hip_roll_right"]); - // hip_roll_left_traj_mir.shiftRight(hip_roll_left_traj.end_time()); - // hip_roll_right_traj_mir.shiftRight(hip_roll_right_traj.end_time()); - // hip_roll_left_traj.ConcatenateInTime(hip_roll_left_traj_mir); - // hip_roll_right_traj.ConcatenateInTime(hip_roll_right_traj_mir); - // MatrixXd left_hip_roll_neutral_angle(1, 2); - // left_hip_roll_neutral_angle << 0.02, 0.02; - // MatrixXd right_hip_roll_neutral_angle(1, 2); - // right_hip_roll_neutral_angle << -0.02, -0.02; - // VectorXd full_trajectory_breaks(2); - // full_trajectory_breaks << 0, accumulated_state_durations.back(); - // PiecewisePolynomial left_hip_roll_traj = - // PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, - // left_hip_roll_neutral_angle); - // PiecewisePolynomial right_hip_roll_traj = - // PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, - // right_hip_roll_neutral_angle); - // - // // TODO(yangwil): generate roll trajectory - // auto hip_roll_left_traj_generator = - // builder.AddSystem( - // plant, plant_context.get(), left_hip_roll_traj, 1, - // "hip_roll_left_traj_generator"); - // auto hip_roll_right_traj_generator = - // builder.AddSystem( - // plant, plant_context.get(), right_hip_roll_traj, 1, - // "hip_roll_right_traj_generator"); - // JointSpaceTrackingData left_hip_roll_tracking_data( - // "hip_roll_left_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, - // osc_gains.W_hip_roll, plant, plant); - // JointSpaceTrackingData right_hip_roll_tracking_data( - // "hip_roll_right_traj", osc_gains.K_p_hip_roll, osc_gains.K_d_hip_roll, - // osc_gains.W_hip_roll, plant, plant); - // left_hip_roll_tracking_data.AddStateAndJointToTrack( - // left_stance_state, "hip_roll_left", "hip_roll_leftdot"); - // left_hip_roll_tracking_data.AddStateAndJointToTrack( - // right_touchdown_air_phase, "hip_roll_left", "hip_roll_leftdot"); - // right_hip_roll_tracking_data.AddStateAndJointToTrack( - // right_stance_state, "hip_roll_right", "hip_roll_rightdot"); - // right_hip_roll_tracking_data.AddStateAndJointToTrack( - // left_touchdown_air_phase, "hip_roll_right", "hip_roll_rightdot"); - // left_hip_roll_tracking_data.DisableFeedforwardAccel({0}); - // right_hip_roll_tracking_data.DisableFeedforwardAccel({0}); - // left_hip_roll_tracking_data.SetImpactInvariantProjection(true); - // right_hip_roll_tracking_data.SetImpactInvariantProjection(true); - // osc->AddTrackingData(&left_hip_roll_tracking_data); - // osc->AddTrackingData(&right_hip_roll_tracking_data); - - auto heading_traj_generator = builder.AddSystem( - plant, plant_context.get()); - + auto heading_traj_generator = + builder.AddSystem(plant, + plant_context.get()); RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, - osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot, plant, plant); pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_touchdown_air_phase, "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_touchdown_air_phase, + "pelvis"); pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_touchdown_air_phase, "pelvis"); pelvis_rot_tracking_data.SetImpactInvariantProjection(true); @@ -751,9 +640,8 @@ int DoMain(int argc, char* argv[]) { heading_traj_generator->get_state_input_port()); builder.Connect(high_level_command->get_yaw_output_port(), heading_traj_generator->get_yaw_input_port()); - builder.Connect( - heading_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_traj")); + builder.Connect(heading_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_rot_traj")); // builder.Connect(state_receiver->get_output_port(0), // hip_roll_left_traj_generator->get_state_input_port()); // builder.Connect(state_receiver->get_output_port(0), From fb795c80a0f589d69478dd8966a08431647622ab Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Jan 2022 15:16:14 -0500 Subject: [PATCH 068/758] removing unused dependencies on nominal trajectory --- .../Cassie/osc_run/osc_running_gains.yaml | 8 +- examples/Cassie/run_osc_running_controller.cc | 170 +----------------- 2 files changed, 10 insertions(+), 168 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 25886de175..78d4ae26cc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -33,10 +33,10 @@ w_hip_roll: 5 hip_roll_kp: 50 hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.0075 +footstep_offset: -0.000 center_line_offset: -0.05 FootstepKd: - [ 0.15, 0, 0, + [ 0.1, 0, 0, 0, 0.1, 0, 0, 0, 0] PelvisW: @@ -61,10 +61,10 @@ PelvisRotKp: 0, 0, 0] PelvisRotKd: [10, 0, 0, - 0, 1, 0, + 0, 1, 0, 0, 0, 0] SwingFootW: - [1, 0, 0, + [25, 0, 0, 0, 25, 0, 0, 0, 1] SwingFootKp: diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 80c3ed19ca..c09bf3722c 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -78,10 +78,6 @@ DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "The name of the channel which receives state"); DEFINE_string(channel_u, "CASSIE_INPUT", "The name of the channel which publishes command"); -DEFINE_string(folder_path, "examples/Cassie/saved_trajectories/", - "Folder path for where the trajectory names are stored"); -DEFINE_string(traj_name, "running_0.00", - "File to load saved trajectories from"); DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", "Filepath containing gains"); DEFINE_string( @@ -139,14 +135,6 @@ int DoMain(int argc, char* argv[]) { {right_toe, right_heel}); /**** Get trajectory from optimization ****/ - const DirconTrajectory& dircon_trajectory = DirconTrajectory( - FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); - - PiecewisePolynomial state_traj = - dircon_trajectory.ReconstructStateTrajectory(); - state_traj.ConcatenateInTime( - dircon_trajectory.ReconstructMirrorStateTrajectory( - state_traj.end_time())); /**** OSC Gains ****/ OSCGains gains{}; @@ -164,20 +152,11 @@ int DoMain(int argc, char* argv[]) { int right_stance_state = 1; int right_touchdown_air_phase = 2; int left_touchdown_air_phase = 3; - // double left_support_duration = - // dircon_trajectory.GetStateBreaks(1)(0) * 2 - FLAGS_fsm_time_offset; - // double right_support_duration = left_support_duration; - // double air_phase_duration = dircon_trajectory.GetStateBreaks(2)(0) - - // dircon_trajectory.GetStateBreaks(1)(0) + - // FLAGS_fsm_time_offset; + vector fsm_states = {left_stance_state, right_touchdown_air_phase, right_stance_state, left_touchdown_air_phase, left_stance_state}; - // std::cout << "left support duration: " << left_support_duration << - // std::endl; std::cout << "flight duration: " << air_phase_duration << - // std::endl; std::cout << "right support duration: " << - // right_support_duration - // << std::endl; + vector state_durations = { osc_gains.stance_duration, osc_gains.flight_duration, osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; @@ -190,11 +169,6 @@ int DoMain(int argc, char* argv[]) { std::cout << accumulated_state_durations.back() << std::endl; } accumulated_state_durations.pop_back(); - // std::cout << accumulated_state_durations.back() << std::endl; - // VectorXd left_leg_active_duration(2); - // left_leg_active_duration << accumulated_state_durations[0], - // accumulated_state_durations VectorXd right_leg_active_duration = - // VectorXd{accumulated_state_durations[0]}; auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, gains.impact_threshold); @@ -294,82 +268,12 @@ int DoMain(int argc, char* argv[]) { builder.Connect(cassie_out_receiver->get_output_port(), high_level_command->get_cassie_output_port()); - string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; - if (osc_gains.relative_feet) { - output_traj_path += "_rel"; - } - std::cout << "trajectory name: " << output_traj_path << std::endl; - const LcmTrajectory& output_trajs = - LcmTrajectory(FindResourceOrThrow(output_traj_path)); - PiecewisePolynomial pelvis_trans_traj; - PiecewisePolynomial l_hip_trajectory; - PiecewisePolynomial r_hip_trajectory; - PiecewisePolynomial l_foot_trajectory; - PiecewisePolynomial r_foot_trajectory; - PiecewisePolynomial pelvis_rot_trajectory; - - for (int mode = 0; mode < dircon_trajectory.GetNumModes() * 2; ++mode) { - const LcmTrajectory::Trajectory lcm_pelvis_trans_trajectory = - output_trajs.GetTrajectory("pelvis_trans_trajectory" + - std::to_string(mode)); - const LcmTrajectory::Trajectory lcm_left_hip_traj = - output_trajs.GetTrajectory("left_hip_trajectory" + - std::to_string(mode)); - const LcmTrajectory::Trajectory lcm_right_hip_traj = - output_trajs.GetTrajectory("right_hip_trajectory" + - std::to_string(mode)); - const LcmTrajectory::Trajectory lcm_left_foot_traj = - output_trajs.GetTrajectory("left_foot_trajectory" + - std::to_string(mode)); - const LcmTrajectory::Trajectory lcm_right_foot_traj = - output_trajs.GetTrajectory("right_foot_trajectory" + - std::to_string(mode)); - const LcmTrajectory::Trajectory lcm_pelvis_rot_traj = - output_trajs.GetTrajectory("pelvis_rot_trajectory" + - std::to_string(mode)); - pelvis_trans_traj.ConcatenateInTime( - PiecewisePolynomial::CubicHermite( - lcm_pelvis_trans_trajectory.time_vector, - lcm_pelvis_trans_trajectory.datapoints.topRows(6), - lcm_pelvis_trans_trajectory.datapoints.bottomRows(6))); - l_foot_trajectory.ConcatenateInTime( - PiecewisePolynomial::CubicHermite( - lcm_left_foot_traj.time_vector, - lcm_left_foot_traj.datapoints.topRows(6), - lcm_left_foot_traj.datapoints.bottomRows(6))); - r_foot_trajectory.ConcatenateInTime( - PiecewisePolynomial::CubicHermite( - lcm_right_foot_traj.time_vector, - lcm_right_foot_traj.datapoints.topRows(6), - lcm_right_foot_traj.datapoints.bottomRows(6))); - l_hip_trajectory.ConcatenateInTime( - PiecewisePolynomial::CubicHermite( - lcm_left_hip_traj.time_vector, - lcm_left_hip_traj.datapoints.topRows(6), - lcm_left_hip_traj.datapoints.bottomRows(6))); - r_hip_trajectory.ConcatenateInTime( - PiecewisePolynomial::CubicHermite( - lcm_right_hip_traj.time_vector, - lcm_right_hip_traj.datapoints.topRows(6), - lcm_right_hip_traj.datapoints.bottomRows(6))); - pelvis_rot_trajectory.ConcatenateInTime( - PiecewisePolynomial::FirstOrderHold( - lcm_pelvis_rot_traj.time_vector, - lcm_pelvis_rot_traj.datapoints.topRows(4))); - } - - // std::cout << "left_foot_trajectory" << std::endl; - // for (auto t : l_foot_trajectory.get_segment_times()) { - // std::cout << t << std::endl; - // } - + auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = builder.AddSystem( - plant, plant_context.get(), pelvis_trans_traj, feet_contact_points, + plant, plant_context.get(), default_traj, feet_contact_points, osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); - // osc_gains.k_leg, - // osc_gains.b_leg); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "hip_left", osc_gains.relative_feet, accumulated_state_durations); @@ -478,8 +382,8 @@ int DoMain(int argc, char* argv[]) { left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); -// left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); -// right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); osc->AddTrackingData(&pelvis_trans_rel_tracking_data); osc->AddTrackingData(&left_foot_rel_tracking_data); @@ -487,36 +391,6 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(&left_foot_yz_rel_tracking_data); osc->AddTrackingData(&right_foot_yz_rel_tracking_data); - // Stance hip pitch trajectory - auto hip_pitch_left_traj = dircon_trajectory.ReconstructJointTrajectory( - pos_map_wo_spr["hip_pitch_left"]); - auto hip_pitch_left_traj_mir = - dircon_trajectory.ReconstructMirrorJointTrajectory( - pos_map_wo_spr["hip_pitch_left"]); - auto hip_pitch_right_traj = dircon_trajectory.ReconstructJointTrajectory( - pos_map_wo_spr["hip_pitch_right"]); - auto hip_pitch_right_traj_mir = - dircon_trajectory.ReconstructMirrorJointTrajectory( - pos_map_wo_spr["hip_pitch_right"]); - PiecewisePolynomial pelvis_pitch_traj = - PiecewisePolynomial(VectorXd::Zero(1)); - hip_pitch_left_traj_mir.shiftRight(hip_pitch_left_traj.end_time()); - hip_pitch_right_traj_mir.shiftRight(hip_pitch_right_traj.end_time()); - hip_pitch_left_traj.ConcatenateInTime(hip_pitch_left_traj_mir); - hip_pitch_right_traj.ConcatenateInTime(hip_pitch_right_traj_mir); - MatrixXd left_hip_pitch_neutral_angle(1, 2); - left_hip_pitch_neutral_angle << 0.055, 0.055; - MatrixXd right_hip_pitch_neutral_angle(1, 2); - right_hip_pitch_neutral_angle << 0.055, 0.055; - VectorXd full_trajectory_breaks(2); - full_trajectory_breaks << 0, accumulated_state_durations.back(); - PiecewisePolynomial left_hip_pitch_traj = - PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, - left_hip_pitch_neutral_angle); - PiecewisePolynomial right_hip_pitch_traj = - PiecewisePolynomial::ZeroOrderHold(full_trajectory_breaks, - right_hip_pitch_neutral_angle); - auto heading_traj_generator = builder.AddSystem(plant, plant_context.get()); @@ -625,14 +499,6 @@ int DoMain(int argc, char* argv[]) { left_toe_angle_traj_gen->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), right_toe_angle_traj_gen->get_state_input_port()); - // builder.Connect(hip_pitch_left_traj_generator->get_output_port(), - // osc->get_tracking_data_input_port("hip_pitch_left_traj")); - // builder.Connect(hip_pitch_right_traj_generator->get_output_port(), - // osc->get_tracking_data_input_port("hip_pitch_right_traj")); - // builder.Connect(hip_roll_left_traj_generator->get_output_port(), - // osc->get_tracking_data_input_port("hip_roll_left_traj")); - // builder.Connect(hip_roll_right_traj_generator->get_output_port(), - // osc->get_tracking_data_input_port("hip_roll_right_traj")); // OSC connections builder.Connect(pelvis_trans_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("pelvis_trans_traj")); @@ -642,30 +508,6 @@ int DoMain(int argc, char* argv[]) { heading_traj_generator->get_yaw_input_port()); builder.Connect(heading_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("pelvis_rot_traj")); - // builder.Connect(state_receiver->get_output_port(0), - // hip_roll_left_traj_generator->get_state_input_port()); - // builder.Connect(state_receiver->get_output_port(0), - // hip_roll_right_traj_generator->get_state_input_port()); - // builder.Connect(fsm->get_output_port_fsm(), - // hip_roll_left_traj_generator->get_fsm_input_port()); - // builder.Connect(fsm->get_output_port_fsm(), - // hip_roll_right_traj_generator->get_fsm_input_port()); - // builder.Connect(fsm->get_output_port_clock(), - // hip_roll_left_traj_generator->get_clock_input_port()); - // builder.Connect(fsm->get_output_port_clock(), - // hip_roll_right_traj_generator->get_clock_input_port()); - // builder.Connect(state_receiver->get_output_port(0), - // hip_pitch_left_traj_generator->get_state_input_port()); - // builder.Connect(state_receiver->get_output_port(0), - // hip_pitch_right_traj_generator->get_state_input_port()); - // builder.Connect(fsm->get_output_port_fsm(), - // hip_pitch_left_traj_generator->get_fsm_input_port()); - // builder.Connect(fsm->get_output_port_fsm(), - // hip_pitch_right_traj_generator->get_fsm_input_port()); - // builder.Connect(fsm->get_output_port_clock(), - // hip_pitch_left_traj_generator->get_clock_input_port()); - // builder.Connect(fsm->get_output_port_clock(), - // hip_pitch_right_traj_generator->get_clock_input_port()); builder.Connect(l_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), From ff94aa46b27cf9603946a5aced3d6d7101489ee7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Jan 2022 16:14:56 -0500 Subject: [PATCH 069/758] adding procman script to git --- examples/Cassie/cassie_dynamic_motions.pmd | 186 ++++++++++++++++++ examples/Cassie/osc_run/osc_running_gains.h | 36 ++-- .../Cassie/osc_run/osc_running_gains.yaml | 16 +- 3 files changed, 212 insertions(+), 26 deletions(-) create mode 100644 examples/Cassie/cassie_dynamic_motions.pmd diff --git a/examples/Cassie/cassie_dynamic_motions.pmd b/examples/Cassie/cassie_dynamic_motions.pmd new file mode 100644 index 0000000000..a89d50f2e5 --- /dev/null +++ b/examples/Cassie/cassie_dynamic_motions.pmd @@ -0,0 +1,186 @@ +group "0.operator" { + cmd "drake-director-clean" { + exec = "bazel-bin/director/drake-director --use_builtin_scripts=point_pair_contact --script=examples/Cassie/director_scripts/show_time.py --script=examples/Cassie/director_scripts/controller_status.py"; + host = "localhost"; + } + cmd "switch_to_jump" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=\"PD_CONTROL\" --n_publishes=1"; + host = "localhost"; + } + cmd "4.state-visualizer-floating" { + exec = "bazel-bin/examples/Cassie/visualizer --channel=CASSIE_STATE_SIMULATION"; + host = "localhost"; + } + cmd "0.drake-director" { + exec = "bazel-bin/director/drake-director --use_builtin_scripts=point_pair_contact,frame,image --script examples/Cassie/director_scripts/pd_panel.py --script examples/Cassie/director_scripts/show_time.py"; + host = "localhost"; + } + cmd "state-visualizer-dispatcher" { + exec = "bazel-bin/examples/Cassie/visualizer --channel=CASSIE_STATE_DISPATCHER"; + host = "localhost"; + } + cmd "switch_to_running" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=\"OSC_RUNNING\" --n_publishes=1 --channel_x=CASSIE_STATE_SIMULATION --fsm_period=0.47 --fsm_offset=0.2 --blend_duration=0.05 --n_period_delay=1"; + host = "localhost"; + } +} + +group "5.trajectory-optimization" { + cmd "dircon_jumping" { + exec = "bazel-bin/examples/Cassie/run_dircon_jumping --height=0.4 --distance=0.3 --start_height=0.8 --knot_points=12 --save_filename=\"jumping_box_0.4h_0.3d_2\" --load_filename=\"jumping_box_0.4h_0.3d_9\" --same_knotpoints=1 --cost_scaling=5e-5 --tol=1e-7"; + host = "localhost"; + } + cmd "visualize_jumping_trajectory" { + exec = "bazel-bin/examples/Cassie/visualize_trajectory --folder_path=\"examples/Cassie/saved_trajectories/\" --realtime_rate=1.0 --num_poses=20 --visualize_mode=1 --use_transparency=1 --trajectory_name=\"jumping_box_0.4h_0.3d_1\""; + host = "localhost"; + } + cmd "convert_traj_for_sim_jumping" { + exec = "bazel-bin/examples/Cassie/osc_jump/convert_traj_for_sim --trajectory_name=\"jumping_0.15h_0.3d\" "; + host = "localhost"; + } + cmd "convert_traj_for_controller" { + exec = "bazel-bin/examples/Cassie/osc_jump/convert_traj_for_controller --folder_path=\"/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/\" --trajectory_name=\"jumping_box_0.5h_0.3d_1\" --relative_feet=1"; + host = "localhost"; + } + cmd "visualize_walking_trajectory" { + exec = "bazel-bin/examples/Cassie/visualize_trajectory --folder_path=\"/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/\" --trajectory_name=\"walking_0.5\" --realtime_rate=0.1 --num_poses=6 --visualize_mode=1 --use_transparency=1"; + host = "localhost"; + } + cmd "convert_traj_for_walking" { + exec = "bazel-bin/examples/Cassie/osc_run/convert_traj_for_controller --folder_path=\"/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/\" --trajectory_name=running_0.00 --mirror_traj=1"; + host = "localhost"; + } + cmd "dircon_walking" { + exec = "bazel-bin/examples/Cassie/run_dircon_walking --stride_length=0.2 --knot_points=16 --save_filename=walking_0.16.0 --load_filename=walking_0.5 --duration=0.8 --scale_constraints=1"; + host = "localhost"; + } + cmd "dircon_running" { + exec = "bazel-bin/examples/Cassie/run_dircon_running --stride_length=0.00 --start_height=0.85 --knot_points=16 --save_filename=\"running_0.00_work3\" --load_filename=\"running_0.00_work3\" --ipopt=0 --tol=1e-6 --stance_T=0.2 --flight_phase_T=0.10 --same_knotpoints=1"; + host = "localhost"; + } + cmd "visualize_running_trajectory" { + exec = "bazel-bin/examples/Cassie/visualize_trajectory --folder_path=\"/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/\" --realtime_rate=1.0 --num_poses=12 --visualize_mode=1 --use_transparency=1 --trajectory_name=\"running_0.25\" --mirror_traj=1"; + host = "localhost"; + } + cmd "dircon_jumping_w_springs" { + exec = "bazel-bin/examples/Cassie/run_dircon_jumping --height=0.4 --distance=0.3 --start_height=0.8 --knot_points=16 --save_filename=\"springs/jumping_box_0.4h_0.3d_6\" --load_filename=\"springs/jumping_box_0.4h_0.3d_5\" --same_knotpoints=1 --use_springs=1 --convert_to_springs=0 --tol=1e-3 --ipopt=0"; + host = "localhost"; + } +} + +group "1.simulated-robot" { + cmd "dispatcher-robot-in" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --floating_base=true --max_joint_velocity=60 --control_channel_name_initial=\"OSC_STANDING\" --sim=1"; + host = "localhost"; + } + cmd "dispatcher-robot-out (lcm)" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=true --floating_base=true --contact_force_threshold=60"; + host = "localhost"; + } + cmd "mbp_sim_default" { + exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.9 --target_realtime_rate=0.5 --dt=8e-5 --publish_rate=2000 --actuator_delay=0.000 --start_time=0.0"; + host = "localhost"; + } + cmd "mbp_sim_playback" { + exec = "bazel-bin/examples/Cassie/multibody_sim_playback --publish_rate=2000 --end_time=40.0 --dt=8e-5 --target_realtime_rate=0.1 --spring_model=1 --log_num=28 --start_time=30.595"; + host = "localhost"; + } + cmd "mbp_sim_w_platform" { + exec = "bazel-bin/examples/Cassie/multibody_sim_w_platform --publish_rate=2000 --end_time=10.0 --dt=8e-5 --start_time=0.000 --target_realtime_rate=1.0 --traj_name=\"jumping_box_0.5h_0.3d_1\" --platform_height=0.4 --platform_x=0.25 --spring_model=1 --actuator_delay=0.000 --visualize=1"; + host = "localhost"; + } + cmd "mbp_sim_running" { + exec = "bazel-bin/examples/Cassie/multibody_sim_w_platform --publish_rate=2000 --end_time=60.0 --dt=8e-5 --start_time=0.000 --target_realtime_rate=1.0 --traj_name=\"running_0.00\" --spring_model=1 --actuator_delay=0.000 --visualize=0"; + host = "localhost"; + } + cmd "cassie-mujoco" { + exec = "/home/yangwill/workspace/experimental/cassie-mujoco-sim/test/cassiesim -r -s"; + host = "localhost"; + } +} + +group "3.lcm-tools" { + cmd "0.lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "localhost"; + } + cmd "1.signal-scope" { + exec = "bazel-bin/signalscope/signal-scope"; + host = "localhost"; + } +} + +group "2.controllers" { + cmd "osc_standing_controller" { + exec = "bazel-bin/examples/Cassie/run_osc_standing_controller --height=0.92 --cassie_out_channel=CASSIE_OUTPUT --channel_u=OSC_STANDING"; + host = "localhost"; + } + cmd "pd-controller" { + exec = "bazel-bin/examples/Cassie/run_pd_controller --channel_u=\"PD_CONTROL\""; + host = "localhost"; + } + cmd "osc_jumping_controller" { + exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=2.0 --contact_based_fsm=0 --channel_x=CASSIE_STATE_DISPATCHER --traj_name=\"jumping_box_0.5h_0.3d_1\""; + host = "localhost"; + } + cmd "osc_walking_controller" { + exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --use_radio=1 --cassie_out_channel=CASSIE_OUTPUT --channel_u=OSC_WALKING"; + host = "localhost"; + } + cmd "osc_walking_controller_tracking" { + exec = "bazel-bin/examples/Cassie/run_osc_walking_controller_tracking --traj_name=\"walking_0.5\""; + host = "localhost"; + } + cmd "osc_running_controller" { + exec = "bazel-bin/examples/Cassie/run_osc_running_controller --channel_cassie_out=CASSIE_OUTPUT --fsm_time_offset=0.031 --channel_u=OSC_RUNNING"; + host = "localhost"; + } +} + + +script "osc-jumping (drake)" { + stop cmd "osc_jumping_controller"; + stop cmd "mbp_sim" wait "stopped"; + start cmd "osc_jumping_controller" wait "running"; + start cmd "mbp_sim"; +} + +script "osc-jumping (mujoco)" { + stop cmd "osc_jumping_controller (mujoco)"; + stop cmd "dispatcher-robot-in"; + stop cmd "cassie-mujoco" wait "stopped"; + start cmd "osc_jumping_controller (mujoco)" wait "running"; + start cmd "dispatcher-robot-in"; + start cmd "cassie-mujoco"; +} + +script "osc_standing (mujoco)" { + start cmd "cassie-mujoco"; + start cmd "dispatcher-robot-in"; + start cmd "osc_standing_controller"; +} + +script "run-mujoco-lcm-pd-control" { + run_script "start-operator-MBP"; + start cmd "3.cassie-mujoco-fixed-base"; + start cmd "2.a.dispatcher-robot-out (lcm)"; + start cmd "3.dispatcher-robot-in"; + start cmd "0.pd-controller"; +} + +script "run-real-robot-pd-control" { + run_script "start-operator-real-robot"; + start cmd "0.dispatcher-robot-out-real-robot"; + start cmd "1.dispatcher-robot-in-real-robot"; + start cmd "2.pd-controller-real-robot"; +} + +script "switch-to-standing" { + start cmd "osc_standing_controller"; + stop cmd "osc_walking_controller"; +} + +script "switch-to-walking" { + start cmd "osc_walking_controller"; + stop cmd "osc_standing_controller"; +} diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 605b887bb7..b10a41da23 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -68,12 +68,12 @@ struct OSCRunningGains : OSCGains { MatrixXd W_hip_yaw; MatrixXd K_p_hip_yaw; MatrixXd K_d_hip_yaw; - MatrixXd W_hip_pitch; - MatrixXd K_p_hip_pitch; - MatrixXd K_d_hip_pitch; - MatrixXd W_hip_roll; - MatrixXd K_p_hip_roll; - MatrixXd K_d_hip_roll; +// MatrixXd W_hip_pitch; +// MatrixXd K_p_hip_pitch; +// MatrixXd K_d_hip_pitch; +// MatrixXd W_hip_roll; +// MatrixXd K_p_hip_roll; +// MatrixXd K_d_hip_roll; template void Serialize(Archive* a) { @@ -110,12 +110,12 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(w_hip_yaw)); a->Visit(DRAKE_NVP(hip_yaw_kp)); a->Visit(DRAKE_NVP(hip_yaw_kd)); - a->Visit(DRAKE_NVP(w_hip_pitch)); - a->Visit(DRAKE_NVP(hip_pitch_kp)); - a->Visit(DRAKE_NVP(hip_pitch_kd)); - a->Visit(DRAKE_NVP(w_hip_roll)); - a->Visit(DRAKE_NVP(hip_roll_kp)); - a->Visit(DRAKE_NVP(hip_roll_kd)); +// a->Visit(DRAKE_NVP(w_hip_pitch)); +// a->Visit(DRAKE_NVP(hip_pitch_kp)); +// a->Visit(DRAKE_NVP(hip_pitch_kd)); +// a->Visit(DRAKE_NVP(w_hip_roll)); +// a->Visit(DRAKE_NVP(hip_roll_kp)); +// a->Visit(DRAKE_NVP(hip_roll_kd)); // High level command gains (with radio) a->Visit(DRAKE_NVP(vel_scale_rot)); a->Visit(DRAKE_NVP(vel_scale_trans_sagital)); @@ -167,11 +167,11 @@ struct OSCRunningGains : OSCGains { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); - W_hip_pitch = this->w_hip_pitch * MatrixXd::Identity(1, 1); - K_p_hip_pitch = this->hip_pitch_kp * MatrixXd::Identity(1, 1); - K_d_hip_pitch = this->hip_pitch_kd * MatrixXd::Identity(1, 1); - W_hip_roll = this->w_hip_roll * MatrixXd::Identity(1, 1); - K_p_hip_roll = this->hip_roll_kp * MatrixXd::Identity(1, 1); - K_d_hip_roll = this->hip_roll_kd * MatrixXd::Identity(1, 1); +// W_hip_pitch = this->w_hip_pitch * MatrixXd::Identity(1, 1); +// K_p_hip_pitch = this->hip_pitch_kp * MatrixXd::Identity(1, 1); +// K_d_hip_pitch = this->hip_pitch_kd * MatrixXd::Identity(1, 1); +// W_hip_roll = this->w_hip_roll * MatrixXd::Identity(1, 1); +// K_p_hip_roll = this->hip_roll_kp * MatrixXd::Identity(1, 1); +// K_d_hip_roll = this->hip_roll_kd * MatrixXd::Identity(1, 1); } }; \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 78d4ae26cc..2e56e7c364 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -26,17 +26,17 @@ swing_toe_kd: 10 w_hip_yaw: 100 hip_yaw_kp: 100 hip_yaw_kd: 15 -w_hip_pitch: 5 -hip_pitch_kp: 100 -hip_pitch_kd: 10 -w_hip_roll: 5 -hip_roll_kp: 50 -hip_roll_kd: 10 +#w_hip_pitch: 5 +#hip_pitch_kp: 100 +#hip_pitch_kd: 10 +#w_hip_roll: 5 +#hip_roll_kp: 50 +#hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.000 +footstep_offset: 0.01 center_line_offset: -0.05 FootstepKd: - [ 0.1, 0, 0, + [ 0.2, 0, 0, 0, 0.1, 0, 0, 0, 0] PelvisW: From e0e9087708036438c7eb41521652626c3cd176b3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 11 Jan 2022 14:31:09 -0500 Subject: [PATCH 070/758] useless tuning, not sure how to keep it stable --- .../plot_configs/cassie_running_plot.yaml | 8 ++-- .../Cassie/osc_jump/osc_jumping_gains.yaml | 6 +-- .../Cassie/osc_run/foot_traj_generator.cc | 39 ++++++++++++------- examples/Cassie/osc_run/foot_traj_generator.h | 3 ++ .../Cassie/osc_run/osc_running_gains.yaml | 36 ++++++++--------- 5 files changed, 53 insertions(+), 39 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 65b60bcaf1..c8ce58642c 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -29,10 +29,10 @@ plot_tracking_costs: true tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos']} - hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} -# left_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} -# right_ft_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} -# left_ft_z_traj: {'dims': [1], 'derivs': ['pos', 'vel', 'accel']} + left_ft_traj: {'dims': [1], 'derivs': ['pos']} + right_ft_traj: {'dims': [1], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} # right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index c7bca569ba..f4ebb654d9 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -2,7 +2,7 @@ w_input: 0.000 w_accel: 0.0000001 w_input_reg: 0.01 w_soft_constraint: 100 -x_offset: 0.027 +x_offset: 0.025 relative_feet: true mu: 0.8 @@ -16,7 +16,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 5 impact_threshold: 0.050 -landing_delay: 0.000 +landing_delay: 0.050 CoMW: [20, 0, 0, @@ -31,7 +31,7 @@ FlightFootW: 0, 1, 0, 0, 0, 1] CoMKp: - [25, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 50] CoMKd: diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index e0e3153647..6313dfaf53 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -70,6 +70,7 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, initial_foot_pos_idx_ = this->DeclareDiscreteState(3); initial_hip_pos_idx_ = this->DeclareDiscreteState(3); pelvis_yaw_idx_ = this->DeclareDiscreteState(1); + pelvis_vel_est_idx_ = this->DeclareDiscreteState(3); // State variables inside this controller block DeclarePerStepDiscreteUpdateEvent(&FootTrajGenerator::DiscreteVariableUpdate); @@ -85,6 +86,7 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); VectorXd q = robot_output->GetPositions(); + VectorXd v = robot_output->GetVelocities(); multibody::SetPositionsIfNew(plant_, q, context_); Vector3d pelvis_heading_vec = @@ -112,7 +114,14 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( &hip_pos); foot_pos = rot.transpose() * foot_pos; hip_pos = rot.transpose() * hip_pos; + auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) + .get_mutable_value(); + pelvis_vel = 0.9 * v.segment(3, 3) + 0.1 * pelvis_vel; + std::cout << "stance state: " << stance_state_ << std::endl; +// pelvis_vel = Vector3d::Zero(); } +// if (fsm_state(0) != stance_state_) { +// } return EventStatus::Succeeded(); } @@ -144,6 +153,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); + pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { @@ -175,7 +185,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; - Y[0](2) = -0.86; + + Y[0](2) = -REST_LENGTH; Y[1] = start_pos + 0.85 * footstep_correction; if (is_left_foot_) { @@ -183,10 +194,10 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( } else { Y[1](1) -= 0.5 * center_line_offset_; } - Y[1](2) = -0.845; + Y[1](2) = -REST_LENGTH + 0.01; Y[2] = start_pos + footstep_correction; - Y[2](2) = -0.86; + Y[2](2) = -REST_LENGTH; MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); @@ -196,14 +207,14 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, Y_dot_start, Y_dot_end); -// std::cout << "state durations" << std::endl; -// for(auto t : state_durations_){ -// std::cout << t << std::endl; -// } -// std::cout << "break points" << std::endl; -// for(auto t : T_waypoints){ -// std::cout << t << std::endl; -// } + // std::cout << "state durations" << std::endl; + // for(auto t : state_durations_){ + // std::cout << t << std::endl; + // } + // std::cout << "break points" << std::endl; + // for(auto t : T_waypoints){ + // std::cout << t << std::endl; + // } if (is_left_foot_) { return swing_foot_spline; @@ -232,9 +243,9 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); offset_swing_foot_spline.ConcatenateInTime( PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); -// for (auto t : offset_swing_foot_spline.get_segment_times()){ -// std::cout << t << std::endl; -// } + // for (auto t : offset_swing_foot_spline.get_segment_times()){ + // std::cout << t << std::endl; + // } return offset_swing_foot_spline; } // return swing_foot_spline; diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 2e03621d5f..4d880279eb 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -7,6 +7,8 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" +const double REST_LENGTH = 0.75; + namespace dairlib::examples::osc_run { class FootTrajGenerator : public drake::systems::LeafSystem { @@ -70,6 +72,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { int initial_foot_pos_idx_; int initial_hip_pos_idx_; int pelvis_yaw_idx_; + int pelvis_vel_est_idx_; }; } // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 2e56e7c364..7cfbb81ec5 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,8 +1,8 @@ w_input: 0.0000000000 -w_accel: 0.0000 +w_accel: 0.0001 #w_soft_constraint: 1000000 -w_soft_constraint: 1000.0 -w_input_reg: 0.001 +w_soft_constraint: 100.0 +w_input_reg: 0.002 impact_threshold: 0.050 relative_feet: true relative_pelvis: true @@ -13,9 +13,9 @@ vel_scale_trans_sagital: 0.5 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.9 -stance_duration: 0.36 -flight_duration: 0.11 +rest_length: 0.8 +stance_duration: 0.3 +flight_duration: 0.12 mu: 0.8 @@ -33,11 +33,11 @@ hip_yaw_kd: 15 #hip_roll_kp: 50 #hip_roll_kd: 10 # Foot placement parameters -footstep_offset: 0.01 -center_line_offset: -0.05 +footstep_offset: -0.000 +center_line_offset: -0.04 FootstepKd: - [ 0.2, 0, 0, - 0, 0.1, 0, + [ 0.27, 0, 0, + 0, 0.06, 0, 0, 0, 0] PelvisW: [ 0, 0, 0, @@ -46,7 +46,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 92] + 0, 0, 90] PelvisKd: [ 0, 0, 0, 0, 0, 0, @@ -56,12 +56,12 @@ PelvisRotW: 0, 1, 0, 0, 0, 0] PelvisRotKp: - [100, 0, 0, - 0, 25, 0, + [250, 0, 0, + 0, 100, 0, 0, 0, 0] PelvisRotKd: - [10, 0, 0, - 0, 1, 0, + [25, 0, 0, + 0, 10, 0, 0, 0, 0] SwingFootW: [25, 0, 0, @@ -80,9 +80,9 @@ LiftoffSwingFootW: 0, 2, 0, 0, 0, 1] LiftoffSwingFootKp: - [25, 0, 0, - 0, 200, 0, - 0, 0, 50] + [50, 0, 0, + 0, 100, 0, + 0, 0, 10] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, From 0713907fb1b426b84146dbc175ac998c81ac1916 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 11 Jan 2022 15:43:31 -0500 Subject: [PATCH 071/758] adding visualization for debugging --- director/scripts/VisualizationGUI.py | 8 +- director/scripts/cassie_test.json | 169 +++++++++++++++------------ 2 files changed, 96 insertions(+), 81 deletions(-) diff --git a/director/scripts/VisualizationGUI.py b/director/scripts/VisualizationGUI.py index 6c70a4ddc3..e65a35a188 100644 --- a/director/scripts/VisualizationGUI.py +++ b/director/scripts/VisualizationGUI.py @@ -75,8 +75,9 @@ def readJSONFile(self): # use dialog box to get JSON directory mainWindow = director.applogic.getMainWindow() - fileFilters = "Data Files (*.json)"; - filename = QtGui.QFileDialog.getOpenFileName(mainWindow, "Open...", os.getcwd(), fileFilters, "", QtGui.QFileDialog.DontUseNativeDialog) + fileFilters = "Data Files (*.json)" + print(os.getcwd() + 'director/scripts/') + filename = QtGui.QFileDialog.getOpenFileName(mainWindow, "Open...", os.getcwd() + '/director/scripts/', fileFilters, '', QtGui.QFileDialog.DontUseNativeDialog) if not filename: return @@ -329,9 +330,6 @@ def state_handler(self, msg): currShape.point, self.plant.world_frame()) next_loc = pt_world.transpose()[0] - elif (currShape.category == "com"): - next_loc = self.plant.CalcCenterOfMassPosition(context = self.context) - elif (currShape.category == "lcm"): # in the case of an lcm message do not do anything as this is # handled by the abstract handler diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index 504954f2c6..d652f546de 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -2,80 +2,97 @@ "model_file": "examples/Cassie/urdf/cassie_v2.urdf", "channelName": "CASSIE_STATE_SIMULATION", "data": [ - {"name": "toe_point", - "source_data" : {"category":"kinematic", - "frame":"toe_left", - "point":[0, 0, 0] - }, - "type_data": {"color":[0, 1, 0], - "alpha": 0.5, - "type": "point", - "radius": 0.05 - } - - }, - {"name": "right_toe_line", - "source_data" : {"category":"kinematic", - "frame":"toe_right", - "point":[0, 0, 0] - }, - "type_data" : {"color":[1, 0, 1], - "alpha": 0.5, - "type": "line", - "thickness": 0.01, - "history": 2 - } - }, - {"name": "left_toe_axes", - "source_data" : {"category":"kinematic", - "frame":"toe_left", - "point":[0, 0, 0] - }, - "type_data" : {"alpha": 0.5, - "type": "axes", - "thickness": 0.01, - "length": 0.25 - } - }, - {"name": "com_point", - "source_data" : {"category":"com"}, - "type_data" : {"color":[0, 1, 0], - "alpha": 0.5, - "type": "point", - "radius": 0.05 - } - }, - - {"name": "right_toe_axis", - "source_data" : {"category":"lcm", - "abstract_channel" : "CASSIE_STATE_SIMULATION", - "abstract_type" : "dairlib.lcmt_robot_output", - "abstract_field" : "position", - "quaternion_index" : 0, - "frame": "toe_right", - "point": [0, 0, 0] - }, - "type_data": {"alpha": 0.5, - "type": "axes", - "thickness": 0.01, - "length": 0.25 - } - }, - {"name": "lcm_line", - "source_data" : {"category":"lcm", - "abstract_channel" : "OSC_DEBUG", - "abstract_type" : "dairlib.lcmt_osc_output", - "abstract_field" : "tracking_data[%d].y", - "index_field": "tracking_data_names", - "index_element": "lipm_traj", - "x_index" : 0 - }, - "type_data": {"color":[0, 0, 1], - "alpha": 0.5, - "type": "line", - "thickness": 0.01, - "history": -1 - } - } - ] + { + "name": "pelvis", + "source_data": { + "category": "kinematic", + "frame": "pelvis", + "point": [ + 0, + 0, + 0 + ] + }, + "type_data": { + "color": [ + 0, + 0, + 1 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.01, + "history": 2 + } + }, + { + "name": "left_toe_line", + "source_data": { + "category": "kinematic", + "frame": "toe_left", + "point": [ + 0, + 0, + 0 + ] + }, + "type_data": { + "color": [ + 1, + 0, + 1 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.01, + "history": 2 + } + }, + { + "name": "right_toe_line", + "source_data": { + "category": "kinematic", + "frame": "toe_right", + "point": [ + 0, + 0, + 0 + ] + }, + "type_data": { + "color": [ + 1, + 0, + 1 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.01, + "history": 2 + } + }, + { + "name": "desired_foot_position", + "source_data": { + "category": "lcm", + "abstract_channel": "OSC_DEBUG_RUNNING", + "abstract_type": "dairlib.lcmt_osc_output", + "abstract_field": "tracking_data[%d].y", + "index_field": "tracking_data_names", + "index_element": "left_ft_traj", + "x_index": 0 + }, + "type_data": { + "color": [ + 0, + 0, + 1 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.01, + "history": -1 + } + } + ] } From e206dafc2a66e3cce70e2b2c476229fd2aeedc8a Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 13 Jan 2022 10:59:55 -0500 Subject: [PATCH 072/758] quick deprecation fixes, not complete --- .../Cassie/osc_run/osc_running_gains.yaml | 6 ++--- examples/Cassie/run_controller_switch.cc | 2 +- examples/Cassie/run_dircon_jumping.cc | 6 ++--- examples/Cassie/run_dircon_running.cc | 2 +- examples/Cassie/run_dircon_walking.cc | 2 +- .../Cassie/run_osc_standing_controller.cc | 2 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- examples/PlanarWalker/run_gait_dircon.cc | 2 +- .../run_dircon_walking.cc | 2 +- .../run_joint_space_walking_controller.cc | 2 +- solvers/nonlinear_constraint.cc | 12 +++++----- solvers/optimization_utils.cc | 24 +++++++++---------- .../trajectory_optimization/dircon/dircon.cc | 10 ++++---- .../passive_constrained_pendulum_dircon.cc | 2 +- .../trajectory_optimization/hybrid_dircon.cc | 16 ++++++------- .../passive_constrained_pendulum_dircon.cc | 4 +++- 16 files changed, 49 insertions(+), 47 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 7cfbb81ec5..a54a1294d0 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -15,9 +15,9 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.8 stance_duration: 0.3 -flight_duration: 0.12 +flight_duration: 0.1 -mu: 0.8 +mu: 0.6 w_swing_toe: 1 swing_toe_kp: 1500 @@ -37,7 +37,7 @@ footstep_offset: -0.000 center_line_offset: -0.04 FootstepKd: [ 0.27, 0, 0, - 0, 0.06, 0, + 0, 0.04, 0, 0, 0, 0] PelvisW: [ 0, 0, 0, diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index c85a26da31..3cffa3d095 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -15,7 +15,7 @@ namespace dairlib { using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", "The name of the channel which receives state"); diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index fad4a21c21..d5c9514916 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -374,7 +374,7 @@ void DoMain() { cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(trajopt, trajopt.initial_guess()); + const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; cout << "Solve time:" << elapsed.count() << std::endl; @@ -798,7 +798,7 @@ void AddCosts(Dircon* trajopt, auto x_i = trajopt->state_vars(mode, index); auto u_i = trajopt->input_vars(mode, index); auto l_i = trajopt->force_vars(mode, index); - trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } } } @@ -889,7 +889,7 @@ void AddCostsSprings(Dircon* trajopt, auto x_i = trajopt->state_vars(mode, index); auto u_i = trajopt->input_vars(mode, index); auto l_i = trajopt->force_vars(mode, index); - trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } } } diff --git a/examples/Cassie/run_dircon_running.cc b/examples/Cassie/run_dircon_running.cc index 5a39ca8b93..81286b5f92 100644 --- a/examples/Cassie/run_dircon_running.cc +++ b/examples/Cassie/run_dircon_running.cc @@ -296,7 +296,7 @@ void DoMain() { cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(trajopt, trajopt.initial_guess()); + const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); // SolutionResult solution_result = result.get_solution_result(); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; diff --git a/examples/Cassie/run_dircon_walking.cc b/examples/Cassie/run_dircon_walking.cc index 60e2447448..6156efa903 100644 --- a/examples/Cassie/run_dircon_walking.cc +++ b/examples/Cassie/run_dircon_walking.cc @@ -916,7 +916,7 @@ void DoMain(double duration, double stride_length, double ground_incline, cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(*trajopt, trajopt->initial_guess()); + const auto result = drake::solvers::Solve(*trajopt, trajopt->initial_guess()); SolutionResult solution_result = result.get_solution_result(); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index a91278c082..160116e37a 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -39,7 +39,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 7f9a719b32..049bedb841 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -49,7 +49,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using multibody::WorldYawViewFrame; using systems::controllers::ComTrackingData; diff --git a/examples/PlanarWalker/run_gait_dircon.cc b/examples/PlanarWalker/run_gait_dircon.cc index dc41b2478b..c36743e58d 100644 --- a/examples/PlanarWalker/run_gait_dircon.cc +++ b/examples/PlanarWalker/run_gait_dircon.cc @@ -192,7 +192,7 @@ void runDircon( visualizer_poses, 0.2, "base"); auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(trajopt, trajopt.initial_guess()); + const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; std::cout << "Solve time:" << elapsed.count() < run_traj_opt( // Solve the traj optimization problem auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(*trajopt, trajopt->initial_guess()); + const auto result = drake::solvers::Solve(*trajopt, trajopt->initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; std::cout << "Solve time:" << elapsed.count() << std::endl; diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 354f8be9f4..02b9264836 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -40,7 +40,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using systems::controllers::JointSpaceTrackingData; diff --git a/solvers/nonlinear_constraint.cc b/solvers/nonlinear_constraint.cc index 0376ded62b..7dc961fc58 100644 --- a/solvers/nonlinear_constraint.cc +++ b/solvers/nonlinear_constraint.cc @@ -46,8 +46,8 @@ template <> void NonlinearConstraint::DoEval( const Eigen::Ref& x, Eigen::VectorXd* y) const { AutoDiffVecXd y_t; - EvaluateConstraint(drake::math::initializeAutoDiff(x), &y_t); - *y = drake::math::autoDiffToValueMatrix(y_t); + EvaluateConstraint(drake::math::InitializeAutoDiff(x), &y_t); + *y = drake::math::ExtractValue(y_t); this->ScaleConstraint(y); } @@ -69,10 +69,10 @@ void NonlinearConstraint::DoEval( template <> void NonlinearConstraint::DoEval( const Eigen::Ref& x, AutoDiffVecXd* y) const { - MatrixXd original_grad = drake::math::autoDiffToGradientMatrix(x); + MatrixXd original_grad = drake::math::ExtractGradient(x); // forward differencing - VectorXd x_val = drake::math::autoDiffToValueMatrix(x); + VectorXd x_val = drake::math::ExtractValue(x); VectorXd y0, yi; EvaluateConstraint(x_val, &y0); @@ -87,9 +87,9 @@ void NonlinearConstraint::DoEval( // Profiling identified dy * original_grad as a significant runtime event, // even though it is almost always the identity matrix. if (original_grad.isIdentity(1e-16)) { - *y = drake::math::initializeAutoDiffGivenGradientMatrix(y0, dy); + *y = drake::math::InitializeAutoDiff(y0, dy); } else { - *y = drake::math::initializeAutoDiffGivenGradientMatrix(y0, + *y = drake::math::InitializeAutoDiff(y0, dy * original_grad); } diff --git a/solvers/optimization_utils.cc b/solvers/optimization_utils.cc index cba06d6a45..691d8ce3c6 100644 --- a/solvers/optimization_utils.cc +++ b/solvers/optimization_utils.cc @@ -6,9 +6,9 @@ using drake::solvers::Constraint; using drake::solvers::Binding; using drake::solvers::MathematicalProgram; using drake::AutoDiffVecXd; -using drake::math::initializeAutoDiff; -using drake::math::autoDiffToGradientMatrix; -using drake::math::autoDiffToValueMatrix; +using drake::math::InitializeAutoDiff; +using drake::math::ExtractGradient; +using drake::math::ExtractValue; namespace dairlib { namespace solvers { @@ -49,15 +49,15 @@ double SecondOrderCost(const MathematicalProgram& prog, const VectorXd& x_nom, if (variables.size() == 0) continue; AutoDiffVecXd y_val = - initializeAutoDiff(VectorXd::Zero(1), variables.size()); + InitializeAutoDiff(VectorXd::Zero(1), variables.size()); VectorXd x_binding(variables.size()); for (int i = 0; i < variables.size(); i++) { x_binding(i) = x_nom(prog.FindDecisionVariableIndex(variables(i))); } - AutoDiffVecXd x_val = initializeAutoDiff(x_binding); + AutoDiffVecXd x_val = InitializeAutoDiff(x_binding); binding.evaluator()->Eval(x_val, &y_val); - MatrixXd gradient_x = autoDiffToGradientMatrix(y_val); - VectorXd y = autoDiffToValueMatrix(y_val); + MatrixXd gradient_x = ExtractGradient(y_val); + VectorXd y = ExtractValue(y_val); c += y(0); // costs are length 1 for (int i = 0; i < variables.size(); i++) { (*w)(prog.FindDecisionVariableIndex(variables(i))) += gradient_x(0, i); @@ -65,12 +65,12 @@ double SecondOrderCost(const MathematicalProgram& prog, const VectorXd& x_nom, // forward differencing for Hessian AutoDiffVecXd y_hessian = - initializeAutoDiff(VectorXd::Zero(1), variables.size()); + InitializeAutoDiff(VectorXd::Zero(1), variables.size()); for (int i = 0; i < variables.size(); i++) { x_val(i) += eps; binding.evaluator()->Eval(x_val, &y_hessian); x_val(i) -= eps; - MatrixXd gradient_hessian = autoDiffToGradientMatrix(y_hessian); + MatrixXd gradient_hessian = ExtractGradient(y_hessian); for (int j = 0; j <= i; j++) { int ind_i = prog.FindDecisionVariableIndex(variables(i)); int ind_j = prog.FindDecisionVariableIndex(variables(j)); @@ -121,12 +121,12 @@ void LinearizeConstraints(const MathematicalProgram& prog, const VectorXd& x, for (int i = 0; i < variables.size(); i++) { x_binding(i) = x(prog.FindDecisionVariableIndex(variables(i))); } - AutoDiffVecXd x_val = initializeAutoDiff(x_binding); + AutoDiffVecXd x_val = InitializeAutoDiff(x_binding); // Evaluate constraint and extract gradient binding.evaluator()->Eval(x_val, &y_val); - MatrixXd dx = autoDiffToGradientMatrix(y_val); + MatrixXd dx = ExtractGradient(y_val); - y->segment(constraint_index, n) = autoDiffToValueMatrix(y_val); + y->segment(constraint_index, n) = ExtractValue(y_val); for (int i = 0; i < variables.size(); i++) { A->block(constraint_index, prog.FindDecisionVariableIndex(variables(i)), n, 1) = dx.col(i); diff --git a/systems/trajectory_optimization/dircon/dircon.cc b/systems/trajectory_optimization/dircon/dircon.cc index cc716662da..ad72a4afc3 100644 --- a/systems/trajectory_optimization/dircon/dircon.cc +++ b/systems/trajectory_optimization/dircon/dircon.cc @@ -152,7 +152,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, plant_, mode.evaluators(), contexts_[i_mode].at(j).get(), contexts_[i_mode].at(j + 1).get(), i_mode, j, cache_[i_mode].get()); constraint->SetConstraintScaling(mode.GetDynamicsScale()); - AddConstraint( + this->prog().AddConstraint( constraint, {timestep(mode_start_[i_mode] + j), state_vars(i_mode, j), state_vars(i_mode, j + 1), input_vars(i_mode, j), @@ -192,7 +192,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, "kinematic_position[" + std::to_string(i_mode) + "][" + std::to_string(j) + "]"); pos_constraint->SetConstraintScaling(mode.GetKinPositionScale()); - AddConstraint(pos_constraint, + this->prog().AddConstraint(pos_constraint, {state_vars(i_mode, j).head(plant_.num_positions()), offset_vars(i_mode)}); } @@ -211,7 +211,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, "kinematic_velocity[" + std::to_string(i_mode) + "][" + std::to_string(j) + "]"); vel_constraint->SetConstraintScaling(mode.GetKinVelocityScale()); - AddConstraint(vel_constraint, state_vars(i_mode, j)); + this->prog().AddConstraint(vel_constraint, state_vars(i_mode, j)); } } @@ -222,7 +222,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, std::to_string(j) + "]", cache_[i_mode].get()); accel_constraint->SetConstraintScaling(mode.GetKinAccelerationScale()); - AddConstraint(accel_constraint, + this->prog().AddConstraint(accel_constraint, {state_vars(i_mode, j), input_vars(i_mode, j), force_vars(i_mode, j)}); } @@ -243,7 +243,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, "impact[" + std::to_string(i_mode) + "]"); impact_constraint->SetConstraintScaling(mode.GetImpactScale()); - AddConstraint( + this->prog().AddConstraint( impact_constraint, {state_vars(i_mode - 1, pre_impact_index), impulse_vars(i_mode - 1), post_impact_velocity_vars(i_mode - 1)}); diff --git a/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc index 77b8cf0204..1d69f69025 100644 --- a/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc @@ -153,7 +153,7 @@ void runDircon() { auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(trajopt, trajopt.initial_guess()); + const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; std::cout << "Solve time:" << elapsed.count() <::HybridDircon(const MultibodyPlant& plant, options[i].getDynConstraintScaling()); for (int j = 0; j < mode_lengths_[i] - 1; j++) { int time_index = mode_start_[i] + j; - AddConstraint( + this->prog().AddConstraint( dynamic_constraint, {h_vars().segment(time_index, 1), state_vars_by_mode(i, j), state_vars_by_mode(i, j + 1), @@ -168,7 +168,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getKinConstraintScaling()); for (int j = 1; j < mode_lengths_[i] - 1; j++) { int time_index = mode_start_[i] + j; - AddConstraint( + this->prog().AddConstraint( kinematic_constraint, {state_vars_by_mode(i, j), u_vars().segment(time_index * num_inputs(), num_inputs()), @@ -184,7 +184,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getStartType()); kinematic_constraint_start->SetConstraintScaling( options[i].getKinConstraintScalingStart()); - AddConstraint( + this->prog().AddConstraint( kinematic_constraint_start, {state_vars_by_mode(i, 0), u_vars().segment(mode_start_[i] * num_inputs(), num_inputs()), @@ -202,7 +202,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getEndType()); kinematic_constraint_end->SetConstraintScaling( options[i].getKinConstraintScalingEnd()); - AddConstraint( + this->prog().AddConstraint( kinematic_constraint_end, {state_vars_by_mode(i, mode_lengths_[i] - 1), u_vars().segment( @@ -221,7 +221,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, DirconKinematicData* constraint_j = constraints_[i]->getConstraint(j); for (int k = 0; k < constraint_j->numForceConstraints(); k++) { - AddConstraint( + this->prog().AddConstraint( constraint_j->getForceConstraint(k), force_vars(i).segment(start_index, constraint_j->getLength())); } @@ -247,7 +247,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, plant_, *constraints_[i]); impact_constraint->SetConstraintScaling( options[i].getImpConstraintScaling()); - AddConstraint(impact_constraint, + this->prog().AddConstraint(impact_constraint, {state_vars_by_mode(i - 1, mode_lengths_[i - 1] - 1), impulse_vars(i - 1), v_post_impact_vars_by_mode(i - 1)}); @@ -257,7 +257,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, DirconKinematicData* constraint_j = constraints_[i]->getConstraint(j); for (int k = 0; k < constraint_j->numForceConstraints(); k++) { - AddConstraint(constraint_j->getForceConstraint(k), + this->prog().AddConstraint(constraint_j->getForceConstraint(k), impulse_vars(i - 1).segment( start_index, constraint_j->getLength())); } @@ -266,7 +266,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, } else { auto x_vars_prev = state_vars_by_mode(i - 1, mode_lengths_[i - 1] - 1); - AddConstraint(v_post_impact_vars_by_mode(i - 1) == + this->prog().AddConstraint(v_post_impact_vars_by_mode(i - 1) == x_vars_prev.tail(plant.num_velocities())); } } diff --git a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc index 269073b122..75f3e0afa0 100644 --- a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc @@ -105,7 +105,9 @@ void runDircon() { trajopt->AddLinearConstraint(x0(0) == 1); auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(*trajopt, trajopt->initial_guess()); + auto solver = drake::solvers::SnoptSolver(); + + const auto result = solver.Solve(trajopt->prog(), trajopt->initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; std::cout << "Solve time:" << elapsed.count() < Date: Thu, 13 Jan 2022 12:48:15 -0500 Subject: [PATCH 073/758] almost stable, looks much better, using pelvis instead of hips --- .../pydairlib/analysis/log_plotter_cassie.py | 11 ++--- .../plot_configs/cassie_running_plot.yaml | 18 ++++---- director/scripts/cassie_test.json | 4 +- .../Cassie/osc_run/foot_traj_generator.cc | 45 ++++++++++--------- examples/Cassie/osc_run/foot_traj_generator.h | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 40 ++++++++--------- .../osc_run/pelvis_trans_traj_generator.cc | 9 +++- examples/Cassie/run_osc_running_controller.cc | 14 ++++-- 8 files changed, 79 insertions(+), 64 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index e8f95aee40..9f8d4d7e63 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,8 +12,9 @@ def main(): - config_file = \ - 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = \ + # 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base @@ -33,9 +34,9 @@ def main(): filename = sys.argv[1] log = lcm.EventLog(filename, "r") robot_output, robot_input, osc_debug = \ - get_log_data(log, # log - cassie_plots.cassie_default_channels, # lcm channels - mbp_plots.load_default_channels, # processing callback + get_log_data(log, # log + cassie_plots.cassie_default_channels, # lcm channels + mbp_plots.load_default_channels, # processing callback plant, channel_x, channel_u, channel_osc) # processing callback arguments # Define x time slice diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index c8ce58642c..2ae470f680 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -27,12 +27,12 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} -# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} -# hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} -# hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [1], 'derivs': ['pos']} - right_ft_traj: {'dims': [1], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} + # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} + # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} + left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index d652f546de..f08914472c 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -72,7 +72,7 @@ } }, { - "name": "desired_foot_position", + "name": "left_ft_traj_des", "source_data": { "category": "lcm", "abstract_channel": "OSC_DEBUG_RUNNING", @@ -91,7 +91,7 @@ "alpha": 0.5, "type": "line", "thickness": 0.01, - "history": -1 + "history": 2 } } ] diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 6313dfaf53..3bbcf2b89a 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -1,5 +1,7 @@ #include "foot_traj_generator.h" +#include + #include "multibody/multibody_utils.h" using Eigen::Map; @@ -103,7 +105,7 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; // Only update the current foot position when in stance ( - if (fsm_state(0) == stance_state_ || robot_output->get_timestamp() < 0.201) { + if (fsm_state(0) == stance_state_) { auto foot_pos = discrete_state->get_mutable_vector(initial_foot_pos_idx_) .get_mutable_value(); plant_.CalcPointsPositions(*context_, foot_frame_, Vector3d::Zero(), world_, @@ -115,12 +117,13 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( foot_pos = rot.transpose() * foot_pos; hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - .get_mutable_value(); + .get_mutable_value(); pelvis_vel = 0.9 * v.segment(3, 3) + 0.1 * pelvis_vel; - std::cout << "stance state: " << stance_state_ << std::endl; -// pelvis_vel = Vector3d::Zero(); + // pelvis_vel = v.segment(3, 3); + // std::cout << "stance state: " << stance_state_ << std::endl; + // pelvis_vel = Vector3d::Zero(); } -// if (fsm_state(0) != stance_state_) { + // if (fsm_state(0) != stance_state_) { // } return EventStatus::Succeeded(); @@ -153,7 +156,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); - pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); + // pelvis_vel(0) = + // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { @@ -185,19 +189,25 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; - Y[0](2) = -REST_LENGTH; - Y[1] = start_pos + 0.85 * footstep_correction; + Y[1](2) = -REST_LENGTH + 0.01; + Y[2] = start_pos + footstep_correction; + Y[2](2) = -REST_LENGTH; + + // corrections if (is_left_foot_) { - Y[1](1) += 0.5 * center_line_offset_; + Y[1](1) += 0.25 * center_line_offset_; +// Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); + Y[1](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); + Y[2](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); } else { - Y[1](1) -= 0.5 * center_line_offset_; + Y[1](1) -= 0.25 * center_line_offset_; +// Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); + Y[1](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); + Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); } - Y[1](2) = -REST_LENGTH + 0.01; - Y[2] = start_pos + footstep_correction; - Y[2](2) = -REST_LENGTH; MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); @@ -207,15 +217,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, Y_dot_start, Y_dot_end); - // std::cout << "state durations" << std::endl; - // for(auto t : state_durations_){ - // std::cout << t << std::endl; - // } - // std::cout << "break points" << std::endl; - // for(auto t : T_waypoints){ - // std::cout << t << std::endl; - // } - if (is_left_foot_) { return swing_foot_spline; } else { diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 4d880279eb..9998f6959c 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -7,7 +7,7 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" -const double REST_LENGTH = 0.75; +const double REST_LENGTH = 0.8; namespace dairlib::examples::osc_run { diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index a54a1294d0..715c32e330 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,5 +1,5 @@ w_input: 0.0000000000 -w_accel: 0.0001 +w_accel: 0.0000 #w_soft_constraint: 1000000 w_soft_constraint: 100.0 w_input_reg: 0.002 @@ -14,8 +14,8 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.8 -stance_duration: 0.3 -flight_duration: 0.1 +stance_duration: 0.30 +flight_duration: 0.08 mu: 0.6 @@ -23,7 +23,7 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 100 +w_hip_yaw: 1 hip_yaw_kp: 100 hip_yaw_kd: 15 #w_hip_pitch: 5 @@ -33,55 +33,55 @@ hip_yaw_kd: 15 #hip_roll_kp: 50 #hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.000 -center_line_offset: -0.04 +footstep_offset: -0.045 +center_line_offset: 0.045 FootstepKd: - [ 0.27, 0, 0, - 0, 0.04, 0, + [ 0.15, 0, 0, + 0, 0.32, 0, 0, 0, 0] PelvisW: [ 0, 0, 0, 0, 0, 0, - 0, 0, 1] + 0, 0, 5] PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 90] + 0, 0, 125] PelvisKd: [ 0, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [2, 0, 0, - 0, 1, 0, + [1, 0, 0, + 0, 0.1, 0, 0, 0, 0] PelvisRotKp: - [250, 0, 0, + [100, 0, 0, 0, 100, 0, 0, 0, 0] PelvisRotKd: - [25, 0, 0, + [10, 0, 0, 0, 10, 0, 0, 0, 0] SwingFootW: - [25, 0, 0, - 0, 25, 0, + [5, 0, 0, + 0, 10, 0, 0, 0, 1] SwingFootKp: [125, 0, 0, 0, 125, 0, 0, 0, 50] SwingFootKd: - [10, 0, 0, - 0, 20, 0, + [15, 0, 0, + 0, 15, 0, 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, - 0, 2, 0, + 0, 1, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, - 0, 100, 0, + 0, 125, 0, 0, 0, 10] LiftoffSwingFootKd: [ 1, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index cc89b84fe1..f954d98aee 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -120,7 +120,14 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( // breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); - return PiecewisePolynomial(Vector3d{0, 0, rest_length_}); + double y_dist_des = 0; + if(fsm_state == 0){ + y_dist_des = -0.2; + } + else if (fsm_state == 1){ + y_dist_des = 0.2; + } + return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); } void PelvisTransTrajGenerator::CalcTraj( diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c09bf3722c..8e12dde4a5 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -325,6 +325,12 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, "toe_right"); +// TransTaskSpaceTrackingData left_hip_tracking_data( +// "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, +// osc_gains.W_swing_foot, plant, plant); +// TransTaskSpaceTrackingData right_hip_tracking_data( +// "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, +// osc_gains.W_swing_foot, plant, plant); TransTaskSpaceTrackingData left_hip_tracking_data( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); @@ -332,13 +338,13 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, - "hip_left"); + "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, - "hip_right"); + "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_right"); + "pelvis"); left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_left"); + "pelvis"); TransTaskSpaceTrackingData left_hip_yz_tracking_data( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, From 7afa96826e05176901837e58636b73a6e343bbe6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 13 Jan 2022 13:28:45 -0500 Subject: [PATCH 074/758] sometimes stable --- .../Cassie/osc_run/foot_traj_generator.cc | 18 ++++++------ .../Cassie/osc_run/osc_running_gains.yaml | 28 +++++++++---------- 2 files changed, 22 insertions(+), 24 deletions(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 3bbcf2b89a..29a8d3274d 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -124,7 +124,7 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( // pelvis_vel = Vector3d::Zero(); } // if (fsm_state(0) != stance_state_) { -// } + // } return EventStatus::Succeeded(); } @@ -156,8 +156,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); - // pelvis_vel(0) = - // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); + pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { @@ -198,17 +197,16 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // corrections if (is_left_foot_) { Y[1](1) += 0.25 * center_line_offset_; -// Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); - Y[1](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); - Y[2](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); + // Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); + Y[1](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); + Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); } else { Y[1](1) -= 0.25 * center_line_offset_; -// Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); - Y[1](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); - Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); + // Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); + Y[1](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); + Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); } - MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); Y_dot_end(2) = -0.1; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 715c32e330..2bd39428c9 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -13,7 +13,7 @@ vel_scale_trans_sagital: 0.5 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.8 +rest_length: 0.80 stance_duration: 0.30 flight_duration: 0.08 @@ -33,35 +33,35 @@ hip_yaw_kd: 15 #hip_roll_kp: 50 #hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.045 -center_line_offset: 0.045 +footstep_offset: -0.05 +center_line_offset: 0.06 FootstepKd: - [ 0.15, 0, 0, - 0, 0.32, 0, + [ 0.4, 0, 0, + 0, 0.425, 0, 0, 0, 0] PelvisW: - [ 0, 0, 0, - 0, 0, 0, + [0.1, 0, 0, + 0, 0.1, 0, 0, 0, 5] PelvisKp: - [ 0, 0, 0, + [0, 0, 0, 0, 0, 0, - 0, 0, 125] + 0, 0, 110] PelvisKd: - [ 0, 0, 0, - 0, 0, 0, + [ 5, 0, 0, + 0, 5, 0, 0, 0, 5] PelvisRotW: - [1, 0, 0, + [0.1, 0, 0, 0, 0.1, 0, 0, 0, 0] PelvisRotKp: [100, 0, 0, - 0, 100, 0, + 0, 50, 0, 0, 0, 0] PelvisRotKd: [10, 0, 0, - 0, 10, 0, + 0, 2.5, 0, 0, 0, 0] SwingFootW: [5, 0, 0, From 9cca080af39c42986434d0f40468a6bc6eed072e Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 14 Jan 2022 14:43:26 -0500 Subject: [PATCH 075/758] small gain chnges --- .../plot_configs/cassie_running_plot.yaml | 15 ++++++++------- examples/Cassie/osc_run/foot_traj_generator.cc | 3 ++- examples/Cassie/osc_run/osc_running_gains.yaml | 16 ++++++++-------- .../osc_run/pelvis_trans_traj_generator.cc | 4 ++-- 4 files changed, 20 insertions(+), 18 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 2ae470f680..a68b96a1eb 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -27,12 +27,13 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['pos']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['pos']} - hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} +# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} +# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['accel']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} - right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} +# left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} +# right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} +# left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} +# right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 29a8d3274d..491486a7e6 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -118,7 +118,7 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) .get_mutable_value(); - pelvis_vel = 0.9 * v.segment(3, 3) + 0.1 * pelvis_vel; + pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; // pelvis_vel = Vector3d::Zero(); @@ -157,6 +157,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); +// pelvis_vel(1) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 2bd39428c9..4fb237bc73 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,8 +1,8 @@ w_input: 0.0000000000 -w_accel: 0.0000 +w_accel: 0.00001 #w_soft_constraint: 1000000 -w_soft_constraint: 100.0 -w_input_reg: 0.002 +w_soft_constraint: 1000.0 +w_input_reg: 0.01 impact_threshold: 0.050 relative_feet: true relative_pelvis: true @@ -34,18 +34,18 @@ hip_yaw_kd: 15 #hip_roll_kd: 10 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.06 +center_line_offset: 0.05 FootstepKd: [ 0.4, 0, 0, - 0, 0.425, 0, + 0, 0.45, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, 0, 0.1, 0, 0, 0, 5] PelvisKp: - [0, 0, 0, - 0, 0, 0, + [ 1, 0, 0, + 0, 1, 0, 0, 0, 110] PelvisKd: [ 5, 0, 0, @@ -61,7 +61,7 @@ PelvisRotKp: 0, 0, 0] PelvisRotKd: [10, 0, 0, - 0, 2.5, 0, + 0, 10, 0, 0, 0, 0] SwingFootW: [5, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index f954d98aee..a4d6b6c18a 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -122,10 +122,10 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( // breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); double y_dist_des = 0; if(fsm_state == 0){ - y_dist_des = -0.2; + y_dist_des = -0.15; } else if (fsm_state == 1){ - y_dist_des = 0.2; + y_dist_des = 0.15; } return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); } From f7771795c06a4bf2490ef8797861b0e75ea2996b Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 14 Jan 2022 15:21:54 -0500 Subject: [PATCH 076/758] fixing indexing issues --- bindings/pydairlib/lcm/lcm_trajectory_py.cc | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 24 +--- .../osc_jump/convert_traj_for_controller.cc | 2 +- .../osc_run/convert_traj_for_controller.cc | 2 +- examples/Cassie/run_dircon_jumping.cc | 117 +++++++++--------- examples/Cassie/run_dircon_running.cc | 59 ++++----- examples/Cassie/run_osc_jumping_controller.cc | 2 +- examples/Cassie/visualize_trajectory.cc | 2 +- .../five_link_biped_sim.cc | 2 +- .../run_joint_space_walking_controller.cc | 17 +-- lcm/dircon_saved_trajectory.cc | 86 ++++++++++--- lcm/dircon_saved_trajectory.h | 31 +++-- 12 files changed, 192 insertions(+), 154 deletions(-) diff --git a/bindings/pydairlib/lcm/lcm_trajectory_py.cc b/bindings/pydairlib/lcm/lcm_trajectory_py.cc index 29e5aad034..0ac8c4423c 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_py.cc +++ b/bindings/pydairlib/lcm/lcm_trajectory_py.cc @@ -49,7 +49,7 @@ PYBIND11_MODULE(lcm_trajectory, m) { .def("GetTrajectory", &LcmTrajectory::GetTrajectory, py::arg("trajectory_name")); py::class_(m, "DirconTrajectory") - .def(py::init()) + .def(py::init&, const std::string&>()) .def("WriteToFile", &LcmTrajectory::WriteToFile, py::arg("trajectory_name")) .def("GetMetadata", &LcmTrajectory::GetMetadata) diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 097d32956a..d426d23415 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -195,35 +195,15 @@ int do_main(int argc, char* argv[]) { Context& plant_context = diagram->GetMutableSubsystemContext(plant, diagram_context.get()); - MultibodyPlant plant_wo_spr(FLAGS_dt); // non-zero timestep to avoid - // Parser parser_wo_spr(&plant_wo_spr, &scene_graph); - addCassieMultibody(&plant_wo_spr, &scene_graph, FLAGS_floating_base, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", false, - true); - plant_wo_spr.Finalize(); - Eigen::MatrixXd map_no_spring_to_spring_pos = - multibody::CreateWithSpringsToWithoutSpringsMapPos(plant, plant_wo_spr); - Eigen::MatrixXd map_no_spring_to_spring_vel = - multibody::CreateWithSpringsToWithoutSpringsMapVel(plant, plant_wo_spr); - map_no_spring_to_spring_pos.transposeInPlace(); - map_no_spring_to_spring_vel.transposeInPlace(); - const DirconTrajectory& dircon_trajectory = - DirconTrajectory(FLAGS_folder_path + FLAGS_traj_name); + DirconTrajectory(plant, FLAGS_folder_path + FLAGS_traj_name); PiecewisePolynomial state_traj = dircon_trajectory.ReconstructStateTrajectory(); - Eigen::VectorXd x_init = Eigen::VectorXd::Zero(nx); Eigen::VectorXd x_traj_init = state_traj.value(FLAGS_start_time); - if (FLAGS_spring_model) { - x_init << map_no_spring_to_spring_pos * x_traj_init.head(map_no_spring_to_spring_pos.cols()), - map_no_spring_to_spring_vel * x_traj_init.tail(map_no_spring_to_spring_vel.cols()); - } else { - x_init << x_traj_init; - } - plant.SetPositionsAndVelocities(&plant_context, x_init); + plant.SetPositionsAndVelocities(&plant_context, x_traj_init); diagram_context->SetTime(FLAGS_start_time); Simulator simulator(*diagram, std::move(diagram_context)); diff --git a/examples/Cassie/osc_jump/convert_traj_for_controller.cc b/examples/Cassie/osc_jump/convert_traj_for_controller.cc index bf413f5dc2..4fa65af470 100644 --- a/examples/Cassie/osc_jump/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_jump/convert_traj_for_controller.cc @@ -70,7 +70,7 @@ int DoMain() { auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); auto world = &plant.world_frame(); - DirconTrajectory dircon_traj(FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory dircon_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); PiecewisePolynomial state_traj = dircon_traj.ReconstructStateTrajectory(); diff --git a/examples/Cassie/osc_run/convert_traj_for_controller.cc b/examples/Cassie/osc_run/convert_traj_for_controller.cc index 5bf42fdc09..c501eee35b 100644 --- a/examples/Cassie/osc_run/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_run/convert_traj_for_controller.cc @@ -59,7 +59,7 @@ int DoMain() { auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); auto world = &plant.world_frame(); - DirconTrajectory dircon_traj(FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory dircon_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); PiecewisePolynomial state_traj = dircon_traj.ReconstructStateTrajectory(); diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index d5c9514916..85342b0fcf 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -13,8 +13,8 @@ #include "examples/Cassie/cassie_utils.h" #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" -#include "multibody/kinematic/world_point_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/world_point_evaluator.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" #include "solvers/nonlinear_cost.h" @@ -39,18 +39,17 @@ using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; -using dairlib::multibody::KinematicEvaluator; -using dairlib::multibody::KinematicEvaluatorSet; -using dairlib::systems::trajectory_optimization::Dircon; -using dairlib::systems::trajectory_optimization::DirconMode; -using dairlib::systems::trajectory_optimization::DirconModeSequence; -using dairlib::systems::trajectory_optimization::PointPositionConstraint; using dairlib::multibody::CreateWithSpringsToWithoutSpringsMapPos; using dairlib::multibody::CreateWithSpringsToWithoutSpringsMapVel; +using dairlib::multibody::KinematicEvaluator; +using dairlib::multibody::KinematicEvaluatorSet; using dairlib::solvers::NonlinearCost; +using dairlib::systems::trajectory_optimization::Dircon; using dairlib::systems::trajectory_optimization::DirconDynamicConstraint; using dairlib::systems::trajectory_optimization::DirconKinConstraintType; using dairlib::systems::trajectory_optimization::DirconKinematicConstraint; +using dairlib::systems::trajectory_optimization::DirconMode; +using dairlib::systems::trajectory_optimization::DirconModeSequence; using dairlib::systems::trajectory_optimization::DirconOptions; using dairlib::systems::trajectory_optimization::HybridDircon; using dairlib::systems::trajectory_optimization::PointPositionConstraint; @@ -99,16 +98,14 @@ HybridDircon* createDircon(MultibodyPlant& plant); void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant); -void AddCosts(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence* ); +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence*); void AddCostsSprings(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence* ); -MatrixXd loadSavedDecisionVars(const string& filepath); + const MultibodyPlant& plant, + DirconModeSequence*); void SetInitialGuessFromTrajectory( - Dircon& trajopt, const string& filepath, - bool same_knot_points = false, + Dircon& trajopt, const MultibodyPlant& plant, + const string& filepath, bool same_knot_points = false, Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); class JointAccelCost : public solvers::NonlinearCost { @@ -119,8 +116,7 @@ class JointAccelCost : public solvers::NonlinearCost { const std::string& description = "") : solvers::NonlinearCost( plant.num_positions() + plant.num_velocities() + - plant.num_actuators() + - constraints->count_full(), + plant.num_actuators() + constraints->count_full(), description), plant_(plant), context_(plant_.CreateDefaultContext()), @@ -142,7 +138,8 @@ class JointAccelCost : public solvers::NonlinearCost { VectorXd l0 = x.segment(n_x_ + n_u_, n_lambda_); multibody::setContext(plant_, x0, u0, context_.get()); - const VectorX xdot0 = constraints_->CalcTimeDerivatives(*context_, &l0); + const VectorX xdot0 = + constraints_->CalcTimeDerivatives(*context_, &l0); (*y) = xdot0.tail(n_v_).transpose() * W_Q_ * xdot0.tail(n_v_); }; @@ -174,7 +171,8 @@ void DoMain() { file_name = "examples/Cassie/urdf/cassie_v2_conservative.urdf"; } - addCassieMultibody(&plant, nullptr, true, file_name, FLAGS_use_springs, false); + addCassieMultibody(&plant, nullptr, true, file_name, FLAGS_use_springs, + false); Parser parser_vis(&plant_vis, &scene_graph); parser_vis.AddModelFromFile(file_name); @@ -237,10 +235,12 @@ void DoMain() { auto right_loop_eval = RightLoopClosureEvaluator(plant); auto double_stance_constraints = KinematicEvaluatorSet(plant); - int left_toe_eval_ind = double_stance_constraints.add_evaluator(&left_toe_eval); + int left_toe_eval_ind = + double_stance_constraints.add_evaluator(&left_toe_eval); int left_heel_eval_ind = double_stance_constraints.add_evaluator(&left_heel_eval); - int right_toe_eval_ind = double_stance_constraints.add_evaluator(&right_toe_eval); + int right_toe_eval_ind = + double_stance_constraints.add_evaluator(&right_toe_eval); int right_heel_eval_ind = double_stance_constraints.add_evaluator(&right_heel_eval); double_stance_constraints.add_evaluator(&left_loop_eval); @@ -261,7 +261,7 @@ void DoMain() { auto flight_mode = DirconMode(flight_phase_constraints, flight_phase_knotpoints, 0.25, 0.5); auto land_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.4, 0.6); + stance_knotpoints, 0.4, 0.6); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); @@ -317,9 +317,9 @@ void DoMain() { } else { // Snopt settings auto id = drake::solvers::SnoptSolver::id(); - if(FLAGS_use_springs){ + if (FLAGS_use_springs) { trajopt.SetSolverOption(id, "Print file", "../w_springs_snopt.out"); - }else{ + } else { trajopt.SetSolverOption(id, "Print file", "../snopt.out"); } trajopt.SetSolverOption(id, "Major iterations limit", 1e5); @@ -339,9 +339,9 @@ void DoMain() { std::cout << "Adding kinematic constraints: " << std::endl; SetKinematicConstraints(&trajopt, plant); - if(FLAGS_use_springs){ + if (FLAGS_use_springs) { AddCostsSprings(&trajopt, plant, &all_modes); - }else{ + } else { AddCosts(&trajopt, plant, &all_modes); } std::cout << "Setting initial conditions: " << std::endl; @@ -357,9 +357,7 @@ void DoMain() { if (!FLAGS_load_filename.empty()) { std::cout << "Loading: " << FLAGS_load_filename << std::endl; - // MatrixXd decisionVars = - // loadSavedDecisionVars(FLAGS_data_directory + FLAGS_load_filename); - SetInitialGuessFromTrajectory(trajopt, + SetInitialGuessFromTrajectory(trajopt, plant, FLAGS_data_directory + FLAGS_load_filename, FLAGS_same_knotpoints, spr_map); // trajopt->SetInitialGuessForAllVariables(decisionVars); @@ -381,7 +379,8 @@ void DoMain() { std::cout << "Cost:" << result.get_optimal_cost() << std::endl; std::cout << "Solve result: " << result.get_solution_result() << std::endl; - std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) << std::endl; + std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) + << std::endl; // Save trajectory to file DirconTrajectory saved_traj(plant, trajopt, result, "jumping_trajectory", @@ -437,7 +436,8 @@ void SetKinematicConstraints(Dircon* trajopt, double midpoint = 0.045; // position constraints - trajopt->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, x_0(pos_map.at("base_x"))); + trajopt->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, + x_0(pos_map.at("base_x"))); trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); @@ -688,9 +688,8 @@ void SetKinematicConstraints(Dircon* trajopt, /****** COSTS ******/ -void AddCosts(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence* constraints) { +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence* constraints) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -741,9 +740,8 @@ void AddCosts(Dircon* trajopt, if (sym_joint_name != "ankle_joint") { auto act_diff = u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } } } @@ -758,21 +756,25 @@ void AddCosts(Dircon* trajopt, if (asy_joint_name != "ankle_joint") { auto act_diff = u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } } } MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); - R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = 5e-1; - R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) = 5e-1; + R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = + 5e-1; + R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) = + 5e-1; R(act_map.at("hip_yaw_left_motor"), act_map.at("hip_yaw_left_motor")) = 5e-1; - R(act_map.at("hip_yaw_right_motor"), act_map.at("hip_yaw_right_motor")) = 5e-1; - R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) = 5e-5; - R(act_map.at("hip_pitch_right_motor"), act_map.at("hip_pitch_right_motor")) = 5e-5; + R(act_map.at("hip_yaw_right_motor"), act_map.at("hip_yaw_right_motor")) = + 5e-1; + R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) = + 5e-5; + R(act_map.at("hip_pitch_right_motor"), act_map.at("hip_pitch_right_motor")) = + 5e-5; Q *= FLAGS_cost_scaling; R *= FLAGS_cost_scaling; @@ -791,8 +793,8 @@ void AddCosts(Dircon* trajopt, W *= 2.0 * FLAGS_cost_scaling; vector> joint_accel_costs; for (int mode : {0, 1, 2}) { - joint_accel_costs.push_back( - std::make_shared(W, plant, &constraints->mode(mode).evaluators())); + joint_accel_costs.push_back(std::make_shared( + W, plant, &constraints->mode(mode).evaluators())); for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state_vars(mode, index); @@ -807,8 +809,8 @@ void AddCosts(Dircon* trajopt, COSTS ******/ void AddCostsSprings(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence* constraints) { + const MultibodyPlant& plant, + DirconModeSequence* constraints) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -877,13 +879,15 @@ void AddCostsSprings(Dircon* trajopt, // Add no costs on spring acceleration because we can't control for that W(vel_map["knee_joint_leftdot"], vel_map["knee_joint_leftdot"]) = 0.0; W(vel_map["knee_joint_rightdot"], vel_map["knee_joint_rightdot"]) = 0.0; - W(vel_map["ankle_spring_joint_leftdot"], vel_map["ankle_spring_joint_leftdot"]) = 0.0; - W(vel_map["ankle_spring_joint_rightdot"], vel_map["ankle_spring_joint_rightdot"]) = 0.0; + W(vel_map["ankle_spring_joint_leftdot"], + vel_map["ankle_spring_joint_leftdot"]) = 0.0; + W(vel_map["ankle_spring_joint_rightdot"], + vel_map["ankle_spring_joint_rightdot"]) = 0.0; W *= FLAGS_cost_scaling; vector> joint_accel_costs; for (int mode : {0, 1, 2}) { - joint_accel_costs.push_back( - std::make_shared(W, plant, &constraints->mode(mode).evaluators())); + joint_accel_costs.push_back(std::make_shared( + W, plant, &constraints->mode(mode).evaluators())); for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state_vars(mode, index); @@ -895,10 +899,11 @@ void AddCostsSprings(Dircon* trajopt, } void SetInitialGuessFromTrajectory(Dircon& trajopt, + const MultibodyPlant& plant, const string& filepath, bool same_knot_points, Eigen::MatrixXd spr_map) { - DirconTrajectory previous_traj = DirconTrajectory(filepath); + DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); if (same_knot_points) { trajopt.SetInitialGuessForAllVariables( previous_traj.GetDecisionVariables()); @@ -923,14 +928,6 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, } } -MatrixXd loadSavedDecisionVars(const string& filepath) { - DirconTrajectory previous_traj = DirconTrajectory(filepath); - for (auto& name : previous_traj.GetTrajectoryNames()) { - std::cout << name << std::endl; - } - return previous_traj.GetDecisionVariables(); -} - } // namespace dairlib int main(int argc, char* argv[]) { diff --git a/examples/Cassie/run_dircon_running.cc b/examples/Cassie/run_dircon_running.cc index 81286b5f92..f99f0bf016 100644 --- a/examples/Cassie/run_dircon_running.cc +++ b/examples/Cassie/run_dircon_running.cc @@ -17,8 +17,8 @@ #include "multibody/kinematic/world_point_evaluator.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" -#include "systems/trajectory_optimization/dircon/dircon_mode.h" #include "solvers/cost_function_utils.h" +#include "systems/trajectory_optimization/dircon/dircon_mode.h" #include "drake/solvers/solve.h" #include "drake/systems/trajectory_optimization/multiple_shooting.h" @@ -31,13 +31,13 @@ using std::string; using std::unordered_map; using std::vector; +using drake::geometry::DrakeVisualizer; using drake::geometry::SceneGraph; using drake::multibody::Parser; using Eigen::Matrix3Xd; using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; -using drake::geometry::DrakeVisualizer; using dairlib::multibody::KinematicEvaluator; using dairlib::multibody::KinematicEvaluatorSet; @@ -82,10 +82,10 @@ namespace dairlib { void setKinematicConstraints(Dircon& trajopt, const MultibodyPlant& plant); -MatrixXd loadSavedDecisionVars(const string& filepath); -void SetInitialGuessFromTrajectory(Dircon& trajopt, - const string& filepath, - bool same_knot_points = false); +void SetInitialGuessFromTrajectory( + Dircon& trajopt, + const MultibodyPlant& plant, const string& filepath, + bool same_knot_points = false); vector createStateNameVectorFromMap(const map& pos_map, const map& vel_map, const map& act_map); @@ -247,7 +247,7 @@ void DoMain() { if (!FLAGS_load_filename.empty()) { std::cout << "Loading: " << FLAGS_load_filename << std::endl; - SetInitialGuessFromTrajectory(trajopt, + SetInitialGuessFromTrajectory(trajopt, plant, FLAGS_data_directory + FLAGS_load_filename, FLAGS_same_knotpoints); } else { @@ -255,19 +255,19 @@ void DoMain() { VectorXd::Random(trajopt.decision_variables().size())); } - auto loaded_traj = - DirconTrajectory(FLAGS_data_directory + FLAGS_load_filename); - - std::vector> x_trajs; - x_trajs.push_back(PiecewisePolynomial::CubicHermite( - loaded_traj.GetStateBreaks(0), loaded_traj.GetStateSamples(0), - loaded_traj.GetStateDerivativeSamples(0))); - x_trajs.push_back(PiecewisePolynomial::CubicHermite( - loaded_traj.GetStateBreaks(1), loaded_traj.GetStateSamples(1), - loaded_traj.GetStateDerivativeSamples(1))); - x_trajs.push_back(PiecewisePolynomial::CubicHermite( - loaded_traj.GetStateBreaks(2), loaded_traj.GetStateSamples(2), - loaded_traj.GetStateDerivativeSamples(2))); + // auto loaded_traj = + // DirconTrajectory(plant, FLAGS_data_directory + FLAGS_load_filename); + // + // std::vector> x_trajs; + // x_trajs.push_back(PiecewisePolynomial::CubicHermite( + // loaded_traj.GetStateBreaks(0), loaded_traj.GetStateSamples(0), + // loaded_traj.GetStateDerivativeSamples(0))); + // x_trajs.push_back(PiecewisePolynomial::CubicHermite( + // loaded_traj.GetStateBreaks(1), loaded_traj.GetStateSamples(1), + // loaded_traj.GetStateDerivativeSamples(1))); + // x_trajs.push_back(PiecewisePolynomial::CubicHermite( + // loaded_traj.GetStateBreaks(2), loaded_traj.GetStateSamples(2), + // loaded_traj.GetStateDerivativeSamples(2))); // To avoid NaN quaternions for (int i = 0; i < trajopt.N(); i++) { @@ -541,11 +541,11 @@ void setKinematicConstraints(Dircon& trajopt, MatrixXd Q = MatrixXd::Identity(n_v, n_v); Q(7, 7) = 10; Q(8, 8) = 10; -// MatrixXd R = 1e-3 * MatrixXd::Identity(n_u, n_u); -// R(8, 8) = 1; -// R(9, 9) = 1; + // MatrixXd R = 1e-3 * MatrixXd::Identity(n_u, n_u); + // R(8, 8) = 1; + // R(9, 9) = 1; trajopt.AddRunningCost((x.tail(n_v).transpose() * Q * x.tail(n_v))); -// trajopt.AddRunningCost(u.transpose() * R * u); + // trajopt.AddRunningCost(u.transpose() * R * u); solvers::AddPositiveWorkCost(trajopt, plant, W); // MatrixXd S = MatrixXd::Zero(n_u, n_v); @@ -570,9 +570,10 @@ void setKinematicConstraints(Dircon& trajopt, } void SetInitialGuessFromTrajectory(Dircon& trajopt, + const MultibodyPlant& plant, const string& filepath, bool same_knot_points) { - DirconTrajectory previous_traj = DirconTrajectory(filepath); + DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); if (same_knot_points) { trajopt.SetInitialGuessForAllVariables( previous_traj.GetDecisionVariables()); @@ -594,14 +595,6 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, } } -MatrixXd loadSavedDecisionVars(const string& filepath) { - DirconTrajectory previous_traj = DirconTrajectory(filepath); - for (auto& name : previous_traj.GetTrajectoryNames()) { - std::cout << name << std::endl; - } - return previous_traj.GetDecisionVariables(); -} - } // namespace dairlib int main(int argc, char* argv[]) { diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index a5bb2c703b..79cfc00fd3 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -125,7 +125,7 @@ int DoMain(int argc, char* argv[]) { drake::yaml::YamlReadArchive(root).Accept(&gains); /**** Get trajectory from optimization ****/ - const DirconTrajectory& dircon_trajectory = DirconTrajectory( + const DirconTrajectory& dircon_trajectory = DirconTrajectory(plant_w_spr, FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; if (gains.relative_feet) { diff --git a/examples/Cassie/visualize_trajectory.cc b/examples/Cassie/visualize_trajectory.cc index 633b7dbf85..a1f0959624 100644 --- a/examples/Cassie/visualize_trajectory.cc +++ b/examples/Cassie/visualize_trajectory.cc @@ -56,7 +56,7 @@ int DoMain() { int nx = nq + nv; std::unique_ptr> context = plant.CreateDefaultContext(); - DirconTrajectory saved_traj(FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory saved_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); // VectorXd time_vector = saved_traj.GetBreaks(); PiecewisePolynomial optimal_traj = diff --git a/examples/impact_invariant_control/five_link_biped_sim.cc b/examples/impact_invariant_control/five_link_biped_sim.cc index b00b9643e9..c70da07c5e 100644 --- a/examples/impact_invariant_control/five_link_biped_sim.cc +++ b/examples/impact_invariant_control/five_link_biped_sim.cc @@ -93,7 +93,7 @@ int do_main(int argc, char* argv[]) { plant.set_penetration_allowance(FLAGS_penetration_allowance); const DirconTrajectory& loaded_traj = - DirconTrajectory(FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory(plant, FLAGS_folder_path + FLAGS_trajectory_name); auto state_traj = loaded_traj.ReconstructStateTrajectory(); // Create input receiver. diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 02b9264836..288a5faaa7 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -10,8 +10,8 @@ #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "yaml-cpp/yaml.h" @@ -38,9 +38,9 @@ using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using systems::controllers::JointSpaceTrackingData; @@ -98,7 +98,7 @@ int DoMain(int argc, char* argv[]) { /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( - FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); + plant, FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); PiecewisePolynomial state_traj = dircon_trajectory.ReconstructStateTrajectory(); @@ -109,9 +109,11 @@ int DoMain(int argc, char* argv[]) { vector fsm_states; vector state_durations; fsm_states = {0, 1, 0}; - state_durations = {dircon_trajectory.GetStateBreaks(1)(0), - dircon_trajectory.GetStateBreaks(2)(0) - dircon_trajectory.GetStateBreaks(1)(0), - state_traj.end_time() - dircon_trajectory.GetStateBreaks(2)(0)}; + state_durations = { + dircon_trajectory.GetStateBreaks(1)(0), + dircon_trajectory.GetStateBreaks(2)(0) - + dircon_trajectory.GetStateBreaks(1)(0), + state_traj.end_time() - dircon_trajectory.GetStateBreaks(2)(0)}; auto state_receiver = builder.AddSystem(plant); auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, gains.impact_threshold); @@ -167,8 +169,7 @@ int DoMain(int argc, char* argv[]) { joint_tracking_data_vec[joint_idx]->AddJointToTrack(joint_name, joint_name + "dot"); joint_tracking_data_vec[joint_idx]->SetImpactInvariantProjection(true); - auto joint_traj = dircon_trajectory.ReconstructJointTrajectory( - pos_map_wo_spr[joint_name]); + auto joint_traj = dircon_trajectory.ReconstructJointTrajectory(joint_name); auto joint_traj_generator = builder.AddSystem( joint_traj, joint_name + "_traj"); joint_trajs.push_back(joint_traj_generator); diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index 88adb5e64c..9807d37434 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -199,7 +199,8 @@ DirconTrajectory::DirconTrajectory( impulse_traj.datatypes = impulse_names; // Get start of mode to get time of impulse impulse_traj.time_vector = state_breaks[mode].segment(0, 1); - impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode - 1)); + impulse_traj.datapoints = + result.GetSolution(dircon.impulse_vars(mode - 1)); } // Collocation force vars @@ -277,7 +278,8 @@ PiecewisePolynomial DirconTrajectory::ReconstructStateTrajectory() continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, x_[mode]->datapoints, xdot_[mode]->datapoints)); + x_[mode]->time_vector, state_map_ * x_[mode]->datapoints, + state_map_ * xdot_[mode]->datapoints)); } return state_traj; } @@ -306,7 +308,8 @@ PiecewisePolynomial DirconTrajectory::ReconstructMirrorStateTrajectory( PiecewisePolynomial::CubicHermite( x_[0]->time_vector + t_offset * VectorXd::Ones(x_[0]->time_vector.size()), - M * x_[0]->datapoints, M * xdot_[0]->datapoints); + state_map_ * M * x_[0]->datapoints, + state_map_ * M * xdot_[0]->datapoints); for (int mode = 1; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -316,17 +319,18 @@ PiecewisePolynomial DirconTrajectory::ReconstructMirrorStateTrajectory( state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( x_[mode]->time_vector + t_offset * VectorXd::Ones(x_[mode]->time_vector.size()), - M * x_[mode]->datapoints, M * xdot_[mode]->datapoints)); + state_map_ * M * x_[mode]->datapoints, + state_map_ * M * xdot_[mode]->datapoints)); } return state_traj; } PiecewisePolynomial DirconTrajectory::ReconstructJointTrajectory( - int joint_idx) const { + std::string joint_name) const { PiecewisePolynomial state_traj = PiecewisePolynomial::CubicHermite( - x_[0]->time_vector, x_[0]->datapoints.row(joint_idx), - xdot_[0]->datapoints.row(joint_idx)); + x_[0]->time_vector, x_[0]->datapoints.row(pos_map_.at(joint_name)), + xdot_[0]->datapoints.row(pos_map_.at(joint_name))); for (int mode = 1; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -334,19 +338,21 @@ PiecewisePolynomial DirconTrajectory::ReconstructJointTrajectory( continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, x_[mode]->datapoints.row(joint_idx), - xdot_[mode]->datapoints.row(joint_idx))); + x_[mode]->time_vector, + x_[mode]->datapoints.row(pos_map_.at(joint_name)), + xdot_[mode]->datapoints.row(pos_map_.at(joint_name)))); } return state_traj; } PiecewisePolynomial DirconTrajectory::ReconstructMirrorJointTrajectory( - int joint_idx) const { + std::string joint_name) const { MatrixXd M = GetTrajectory("mirror_matrix").datapoints; PiecewisePolynomial state_traj = PiecewisePolynomial::CubicHermite( - x_[0]->time_vector, (M * x_[0]->datapoints).row(joint_idx), - (M * xdot_[0]->datapoints).row(joint_idx)); + x_[0]->time_vector, + (state_map_ * M * x_[0]->datapoints).row(pos_map_.at(joint_name)), + (state_map_ * M * xdot_[0]->datapoints).row(pos_map_.at(joint_name))); for (int mode = 1; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -354,8 +360,10 @@ PiecewisePolynomial DirconTrajectory::ReconstructMirrorJointTrajectory( continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, (M * x_[mode]->datapoints).row(joint_idx), - (M * xdot_[mode]->datapoints).row(joint_idx))); + x_[mode]->time_vector, + (state_map_ * M * x_[mode]->datapoints).row(pos_map_.at(joint_name)), + (state_map_ * M * xdot_[mode]->datapoints) + .row(pos_map_.at(joint_name)))); } return state_traj; } @@ -363,8 +371,8 @@ PiecewisePolynomial DirconTrajectory::ReconstructMirrorJointTrajectory( PiecewisePolynomial DirconTrajectory::ReconstructInputTrajectory() const { PiecewisePolynomial input_traj = - PiecewisePolynomial::FirstOrderHold(u_->time_vector, - u_->datapoints); + PiecewisePolynomial::FirstOrderHold( + u_->time_vector, actuator_map_ * u_->datapoints); return input_traj; } @@ -404,7 +412,8 @@ DirconTrajectory::ReconstructGammaCTrajectory() const { return gamma_c_traj; } -void DirconTrajectory::LoadFromFile(const std::string& filepath) { +void DirconTrajectory::LoadFromFile(const MultibodyPlant& plant, + const std::string& filepath) { LcmTrajectory::LoadFromFile(filepath); // Find all the state trajectories @@ -422,7 +431,8 @@ void DirconTrajectory::LoadFromFile(const std::string& filepath) { if (x_[mode]->time_vector.size() > 1) { try { if (mode > 0) { - impulse_.push_back(&GetTrajectory("impulse_vars" + std::to_string(mode))); + impulse_.push_back( + &GetTrajectory("impulse_vars" + std::to_string(mode))); } lambda_c_.push_back( &GetTrajectory("collocation_force_vars" + std::to_string(mode))); @@ -436,6 +446,46 @@ void DirconTrajectory::LoadFromFile(const std::string& filepath) { } u_ = &GetTrajectory("input_traj"); decision_vars_ = &GetTrajectory("decision_vars"); + + // Finished loading in trajectories, now constructing maps to be compatible + // with old trajectories + + auto pos_map = multibody::makeNameToPositionsMap(plant); + auto vel_map = multibody::makeNameToVelocitiesMap(plant); + auto act_map = multibody::makeNameToActuatorsMap(plant); + state_map_ = MatrixXd::Zero(plant.num_positions() + plant.num_velocities(), + x_[0]->datapoints.rows()); + int nq = plant.num_positions(); + + for (int i = 0; i < x_[0]->datatypes.size(); ++i) { + auto state_name = x_[0]->datatypes.at(i); + if (pos_map.count(state_name)) { + state_map_(pos_map[state_name], i) = 1; + pos_map_[state_name] = i; + } else if (vel_map.count(state_name)) { + state_map_(nq + vel_map[state_name], i) = 1; + vel_map_[state_name] = i; + } else { + std::cerr << "Trajectory contains state names that are present in the " + "supplied MultibodyPlant." + << std::endl; + } + } + + DRAKE_DEMAND(plant.num_actuators() == u_->datapoints.rows()); + actuator_map_ = MatrixXd::Zero(plant.num_actuators(), plant.num_actuators()); + + for (int i = 0; i < u_->datatypes.size(); ++i) { + auto motor_name = u_->datatypes.at(i); + if (act_map.count(motor_name)) { + actuator_map_(act_map[motor_name], i) = 1; + act_map_[motor_name] = i; + } else { + std::cerr << "Trajectory contains state names that are present in the " + "supplied MultibodyPlant." + << std::endl; + } + } } Eigen::VectorXd DirconTrajectory::GetCollocationPoints( diff --git a/lcm/dircon_saved_trajectory.h b/lcm/dircon_saved_trajectory.h index 8c5a659949..578d25c96b 100644 --- a/lcm/dircon_saved_trajectory.h +++ b/lcm/dircon_saved_trajectory.h @@ -31,7 +31,10 @@ namespace dairlib { class DirconTrajectory : public LcmTrajectory { public: - DirconTrajectory(const std::string& filepath) { LoadFromFile(filepath); } + DirconTrajectory(const drake::multibody::MultibodyPlant& plant, + const std::string& filepath) { + LoadFromFile(plant, filepath); + } DirconTrajectory( const drake::multibody::MultibodyPlant& plant, @@ -50,14 +53,13 @@ class DirconTrajectory : public LcmTrajectory { drake::trajectories::PiecewisePolynomial ReconstructStateTrajectory() const; drake::trajectories::PiecewisePolynomial - ReconstructStateTrajectoryWithSprings( - Eigen::MatrixXd&) const; + ReconstructStateTrajectoryWithSprings(Eigen::MatrixXd&) const; drake::trajectories::PiecewisePolynomial ReconstructMirrorStateTrajectory(double t_offset) const; drake::trajectories::PiecewisePolynomial ReconstructJointTrajectory( - int joint_idx) const; + std::string joint_name) const; drake::trajectories::PiecewisePolynomial - ReconstructMirrorJointTrajectory(int joint_idx) const; + ReconstructMirrorJointTrajectory(std::string joint_name) const; /// Returns a vector of polynomials describing the contact forces for each /// mode. For use when adding knot points to the initial guess @@ -76,7 +78,10 @@ class DirconTrajectory : public LcmTrajectory { /// Loads the saved state and input trajectory as well as the decision /// variables - void LoadFromFile(const std::string& filepath) override; + /// A MultibodyPlant is required due to possible state and actuator indexing + /// conflicts. + void LoadFromFile(const drake::multibody::MultibodyPlant& plant, + const std::string& filepath); Eigen::MatrixXd GetStateSamples(int mode) const { DRAKE_DEMAND(mode >= 0); @@ -101,7 +106,9 @@ class DirconTrajectory : public LcmTrajectory { Eigen::MatrixXd GetForceBreaks(int mode) const { return lambda_[mode]->time_vector; } - Eigen::MatrixXd GetImpulseSamples(int mode) const { return impulse_[mode - 1]->datapoints; } + Eigen::MatrixXd GetImpulseSamples(int mode) const { + return impulse_[mode - 1]->datapoints; + } Eigen::MatrixXd GetCollocationForceSamples(int mode) const { return lambda_c_[mode]->datapoints; } @@ -127,5 +134,15 @@ class DirconTrajectory : public LcmTrajectory { std::vector gamma_c_; std::vector x_; std::vector xdot_; + + // convenience map + // NOTE: + std::map pos_map_; + std::map vel_map_; + std::map act_map_; + // map from possibly old state indices to current state indices + Eigen::MatrixXd state_map_; + // map from possibly old actuator indices to current actuator indices + Eigen::MatrixXd actuator_map_; }; } // namespace dairlib From 04c9e7a6da3c93857752edd223f1c8ead6b90abd Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 17 Jan 2022 15:37:05 -0500 Subject: [PATCH 077/758] gains stable with state estimator for > 30s --- examples/Cassie/BUILD.bazel | 23 + .../Cassie/osc_run/foot_traj_generator.cc | 10 +- examples/Cassie/osc_run/foot_traj_generator.h | 9 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_hopping_controller.cc | 527 ++++++++++++++++++ examples/Cassie/run_osc_running_controller.cc | 29 +- 6 files changed, 573 insertions(+), 27 deletions(-) create mode 100644 examples/Cassie/run_osc_hopping_controller.cc diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 0ca1389752..cdbec1376c 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -47,6 +47,7 @@ cc_library( "//examples/Cassie:run_controller_switch", "//examples/Cassie:run_osc_jumping_controller", "//examples/Cassie:run_osc_running_controller", + "//examples/Cassie:run_osc_hopping_controller", "//examples/Cassie:run_osc_standing_controller", "//examples/Cassie:run_osc_walking_controller", "//examples/Cassie/osc", @@ -365,6 +366,28 @@ cc_binary( ], ) +cc_binary( + name = "run_osc_hopping_controller", + srcs = ["run_osc_hopping_controller.cc"], + deps = [ + ":cassie_urdf", + ":cassie_utils", + "//examples/Cassie/osc", + "//examples/Cassie/osc_jump", + "//examples/Cassie/osc_run", + "//lcm:trajectory_saver", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers/osc:osc_tracking_datas", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "//systems/primitives:gaussian_noise_pass_through", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "run_osc_walking_controller", srcs = ["run_osc_walking_controller.cc"], diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 491486a7e6..cc0a1fc97b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -30,6 +30,7 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, Context* context, const string& foot_name, const string& hip_name, bool relative_feet, + const int stance_state, std::vector state_durations) : plant_(plant), context_(context), @@ -37,19 +38,18 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, foot_frame_(plant.GetFrameByName(foot_name)), hip_frame_(plant.GetFrameByName(hip_name)), relative_feet_(relative_feet), + stance_state_(stance_state), state_durations_(state_durations) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; if (foot_name == "toe_left") { is_left_foot_ = true; - stance_state_ = 0; this->set_name("left_ft_traj"); this->DeclareAbstractOutputPort("left_ft_traj", traj_inst, &FootTrajGenerator::CalcTraj); } else { is_left_foot_ = false; - stance_state_ = 1; this->set_name("right_ft_traj"); this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, &FootTrajGenerator::CalcTraj); @@ -189,11 +189,11 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; - Y[0](2) = -REST_LENGTH; + Y[0](2) = -rest_length_; Y[1] = start_pos + 0.85 * footstep_correction; - Y[1](2) = -REST_LENGTH + 0.01; + Y[1](2) = -rest_length_ + 0.01; Y[2] = start_pos + footstep_correction; - Y[2](2) = -REST_LENGTH; + Y[2](2) = -rest_length_; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 9998f6959c..2939ca5931 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -7,8 +7,6 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" -const double REST_LENGTH = 0.8; - namespace dairlib::examples::osc_run { class FootTrajGenerator : public drake::systems::LeafSystem { @@ -16,7 +14,8 @@ class FootTrajGenerator : public drake::systems::LeafSystem { FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, const std::string& foot_name, const std::string& hip_name, - bool relative_feet, std::vector state_durations); + bool relative_feet, int stance_state, + std::vector state_durations); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -30,8 +29,9 @@ class FootTrajGenerator : public drake::systems::LeafSystem { void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; - void SetFootPlacementOffsets(double center_line_offset, + void SetFootPlacementOffsets(double rest_length, double center_line_offset, double footstep_offset) { + rest_length_ = rest_length; center_line_offset_ = center_line_offset; footstep_offset_ = footstep_offset; } @@ -56,6 +56,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { std::vector state_durations_; // Foot placement constants + double rest_length_; double center_line_offset_; double footstep_offset_; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4fb237bc73..0ea963d866 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -3,7 +3,7 @@ w_accel: 0.00001 #w_soft_constraint: 1000000 w_soft_constraint: 1000.0 w_input_reg: 0.01 -impact_threshold: 0.050 +impact_threshold: 0.025 relative_feet: true relative_pelvis: true diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc new file mode 100644 index 0000000000..b2e3f95770 --- /dev/null +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -0,0 +1,527 @@ +#include + +#include +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/osc/heading_traj_generator.h" +#include "examples/Cassie/osc/high_level_command.h" +#include "examples/Cassie/osc/swing_toe_traj_generator.h" +#include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" +#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" +#include "examples/Cassie/osc_run/foot_traj_generator.h" +#include "examples/Cassie/osc_run/osc_running_gains.h" +#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" +#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" +#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" +#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" +#include "lcm/dircon_saved_trajectory.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/controller_failure_aggregator.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" + +namespace dairlib { + +using std::map; +using std::pair; +using std::string; +using std::vector; + +using Eigen::Matrix3d; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using cassie::osc::SwingToeTrajGenerator; +using drake::geometry::SceneGraph; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using examples::osc::PelvisPitchTrajGenerator; +using examples::osc::PelvisRollTrajGenerator; +using examples::osc::PelvisTransTrajGenerator; +using examples::osc_jump::BasicTrajectoryPassthrough; +using examples::osc_run::FootTrajGenerator; +using multibody::FixedJointEvaluator; +using multibody::WorldYawViewFrame; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +namespace examples { + +DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", + "The name of the channel which receives state"); +DEFINE_string(channel_u, "CASSIE_INPUT", + "The name of the channel which publishes command"); +DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", + "Filepath containing gains"); +DEFINE_string( + channel_cassie_out, "CASSIE_OUTPUT_ECHO", + "The name of the channel to receive the cassie out structure from."); +DEFINE_double( + fsm_time_offset, 0.0, + "Time (s) in the fsm to move from the stance phase to the flight phase"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Build the controller diagram + DiagramBuilder builder; + + // Built the Cassie MBPs + drake::multibody::MultibodyPlant plant(0.0); + addCassieMultibody(&plant, nullptr, true, + "examples/Cassie/urdf/cassie_v2_conservative.urdf", + false /*spring model*/, false /*loop closure*/); + plant.Finalize(); + + auto plant_context = plant.CreateDefaultContext(); + + // Get contact frames and position + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); + + int nv = plant.num_velocities(); + + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + + std::unordered_map< + int, std::vector&>>> + feet_contact_points; + feet_contact_points[0] = std::vector< + std::pair&>>( + {left_toe, left_heel}); + feet_contact_points[1] = std::vector< + std::pair&>>( + {right_toe, right_heel}); + + /**** Get trajectory from optimization ****/ + + /**** OSC Gains ****/ + OSCGains gains{}; + const YAML::Node& root = + YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); + drake::yaml::YamlReadArchive::Options yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); + + OSCRunningGains osc_gains; + drake::yaml::YamlReadArchive(root).Accept(&osc_gains); + + /**** FSM and contact mode configuration ****/ + int stance_state = 0; + int air_state = 1; + + vector fsm_states = {stance_state, air_state, stance_state, air_state, + stance_state}; + + vector state_durations = { + osc_gains.stance_duration, osc_gains.flight_duration, + osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; + vector accumulated_state_durations; + accumulated_state_durations.push_back(0); + std::cout << accumulated_state_durations.back() << std::endl; + for (double state_duration : state_durations) { + accumulated_state_durations.push_back(accumulated_state_durations.back() + + state_duration); + std::cout << accumulated_state_durations.back() << std::endl; + } + accumulated_state_durations.pop_back(); + + auto fsm = builder.AddSystem( + plant, fsm_states, state_durations, 0.0, gains.impact_threshold); + + /**** Initialize all the leaf systems ****/ + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto state_receiver = builder.AddSystem(plant); + auto command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto command_sender = builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), true); + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto failure_aggregator = + builder.AddSystem(FLAGS_channel_u, + 1); + auto controller_failure_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); + + /**** OSC setup ****/ + // Cost + MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); + osc->SetAccelerationCostForAllJoints(Q_accel); + osc->SetInputRegularizationWeight(gains.w_input_reg); + + // Soft constraint on contacts + double w_contact_relax = gains.w_soft_constraint; + osc->SetWeightOfSoftContactConstraint(w_contact_relax); + + // Contact information for OSC + osc->SetContactFriction(gains.mu); + + const auto& pelvis = plant.GetBodyByName("pelvis"); + multibody::WorldYawViewFrame view_frame(pelvis); + auto left_toe_evaluator = multibody::WorldPointEvaluator( + plant, left_toe.first, left_toe.second, view_frame, Matrix3d::Identity(), + Vector3d::Zero(), {1, 2}); + auto left_heel_evaluator = multibody::WorldPointEvaluator( + plant, left_heel.first, left_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + auto right_toe_evaluator = multibody::WorldPointEvaluator( + plant, right_toe.first, right_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); + auto right_heel_evaluator = multibody::WorldPointEvaluator( + plant, right_heel.first, right_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + + osc->AddStateAndContactPoint(stance_state, &left_toe_evaluator); + osc->AddStateAndContactPoint(stance_state, &left_heel_evaluator); + osc->AddStateAndContactPoint(stance_state, &right_toe_evaluator); + osc->AddStateAndContactPoint(stance_state, &right_heel_evaluator); + + multibody::KinematicEvaluatorSet evaluators(plant); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + + // Fix the springs in the dynamics + auto pos_idx_map = multibody::makeNameToPositionsMap(plant); + auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + + osc->AddKinematicConstraint(&evaluators); + + /**** Tracking Data *****/ + + std::cout << "Creating tracking data. " << std::endl; + + auto cassie_out_receiver = + builder.AddSystem(LcmSubscriberSystem::Make( + FLAGS_channel_cassie_out, &lcm)); + cassie::osc::HighLevelCommand* high_level_command; + high_level_command = builder.AddSystem( + plant, plant_context.get(), osc_gains.vel_scale_rot, + osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); + builder.Connect(cassie_out_receiver->get_output_port(), + high_level_command->get_cassie_output_port()); + + auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); + auto pelvis_trans_traj_generator = + builder.AddSystem( + plant, plant_context.get(), default_traj, feet_contact_points, + osc_gains.relative_pelvis); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + auto l_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "toe_left", "hip_left", + osc_gains.relative_feet, 0, accumulated_state_durations); + auto r_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "toe_right", "hip_right", + osc_gains.relative_feet, 0, accumulated_state_durations); + l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + osc_gains.center_line_offset, + osc_gains.footstep_offset); + r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + osc_gains.center_line_offset, + osc_gains.footstep_offset); + + TransTaskSpaceTrackingData pelvis_tracking_data( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant); + TransTaskSpaceTrackingData stance_foot_tracking_data( + "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData left_foot_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_foot_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + pelvis_tracking_data.AddStateAndPointToTrack(stance_state, "pelvis"); + stance_foot_tracking_data.AddStateAndPointToTrack(stance_state, "toe_left"); + // stance_foot_tracking_data.AddStateAndPointToTrack(stance_state, + // "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(stance_state, "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(stance_state, "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(air_state, "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(air_state, "toe_right"); + + TransTaskSpaceTrackingData left_foot_yz_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_foot_yz_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_foot_yz_tracking_data.AddStateAndPointToTrack(air_state, "toe_left"); + right_foot_yz_tracking_data.AddStateAndPointToTrack(air_state, "toe_right"); + + // TransTaskSpaceTrackingData left_hip_tracking_data( + // "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + // osc_gains.W_swing_foot, plant, plant); + // TransTaskSpaceTrackingData right_hip_tracking_data( + // "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + // osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData left_hip_tracking_data( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_hip_tracking_data( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_tracking_data.AddStateAndPointToTrack(stance_state, "pelvis"); + right_hip_tracking_data.AddStateAndPointToTrack(stance_state, "pelvis"); + right_hip_tracking_data.AddStateAndPointToTrack(air_state, "pelvis"); + left_hip_tracking_data.AddStateAndPointToTrack(air_state, "pelvis"); + + TransTaskSpaceTrackingData left_hip_yz_tracking_data( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_hip_yz_tracking_data( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_yz_tracking_data.AddStateAndPointToTrack(air_state, "hip_left"); + right_hip_yz_tracking_data.AddStateAndPointToTrack(air_state, "hip_right"); + + RelativeTranslationTrackingData left_foot_rel_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, + &left_hip_tracking_data); + RelativeTranslationTrackingData right_foot_rel_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, + &right_hip_tracking_data); + RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( + "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); + RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( + "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); + RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, + &stance_foot_tracking_data); + left_foot_rel_tracking_data.SetViewFrame(view_frame); + right_foot_rel_tracking_data.SetViewFrame(view_frame); + left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); + right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); + pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); + + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); + // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + + osc->AddTrackingData(&pelvis_trans_rel_tracking_data); + osc->AddTrackingData(&left_foot_rel_tracking_data); + osc->AddTrackingData(&right_foot_rel_tracking_data); + osc->AddTrackingData(&left_foot_yz_rel_tracking_data); + osc->AddTrackingData(&right_foot_yz_rel_tracking_data); + + auto heading_traj_generator = + builder.AddSystem(plant, + plant_context.get()); + + RotTaskSpaceTrackingData pelvis_rot_tracking_data( + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot, plant, plant); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(stance_state, "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(air_state, "pelvis"); + pelvis_rot_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&pelvis_rot_tracking_data); + + // Swing toe joint trajectory + vector&>> left_foot_points = { + left_heel, left_toe}; + vector&>> right_foot_points = { + right_heel, right_toe}; + auto left_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_left"], left_foot_points, + "left_toe_angle_traj"); + auto right_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_right"], right_foot_points, + "right_toe_angle_traj"); + + // Swing toe joint tracking + JointSpaceTrackingData left_toe_angle_tracking_data( + "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + JointSpaceTrackingData right_toe_angle_tracking_data( + "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + left_toe_angle_tracking_data.AddStateAndJointToTrack(stance_state, "toe_left", + "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + stance_state, "toe_right", "toe_rightdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack(air_state, "toe_left", + "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack(air_state, "toe_right", + "toe_rightdot"); + left_toe_angle_tracking_data.SetImpactInvariantProjection(true); + right_toe_angle_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_toe_angle_tracking_data); + osc->AddTrackingData(&right_toe_angle_tracking_data); + + // Swing hip yaw joint tracking + JointSpaceTrackingData left_hip_yaw_tracking_data( + "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + JointSpaceTrackingData right_hip_yaw_tracking_data( + "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", + "hip_yaw_rightdot"); + // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + + // Build OSC problem + osc->Build(); + std::cout << "Built OSC" << std::endl; + + /*****Connect ports*****/ + + // OSC connections + builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_impact(), + osc->get_near_impact_input_port()); + builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); + builder.Connect(state_receiver->get_output_port(0), + osc->get_robot_output_input_port()); + // FSM connections + builder.Connect(state_receiver->get_output_port(0), + fsm->get_input_port_state()); + + // Trajectory generator connections + builder.Connect(state_receiver->get_output_port(0), + pelvis_trans_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + pelvis_trans_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_clock(), + pelvis_trans_traj_generator->get_clock_input_port()); + builder.Connect(high_level_command->get_xy_output_port(), + l_foot_traj_generator->get_target_vel_input_port()); + builder.Connect(high_level_command->get_xy_output_port(), + r_foot_traj_generator->get_target_vel_input_port()); + builder.Connect(state_receiver->get_output_port(0), + l_foot_traj_generator->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + r_foot_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + l_foot_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + r_foot_traj_generator->get_fsm_input_port()); + builder.Connect(state_receiver->get_output_port(0), + left_toe_angle_traj_gen->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + right_toe_angle_traj_gen->get_state_input_port()); + // OSC connections + builder.Connect(pelvis_trans_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_trans_traj")); + builder.Connect(state_receiver->get_output_port(0), + heading_traj_generator->get_state_input_port()); + builder.Connect(high_level_command->get_yaw_output_port(), + heading_traj_generator->get_yaw_input_port()); + builder.Connect(heading_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_rot_traj")); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("left_ft_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("right_ft_traj")); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("left_ft_z_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("right_ft_z_traj")); + builder.Connect(left_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("left_toe_angle_traj")); + builder.Connect(right_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("right_toe_angle_traj")); + + // Publisher connections + builder.Connect(osc->get_osc_output_port(), + command_sender->get_input_port(0)); + builder.Connect(command_sender->get_output_port(0), + command_pub->get_input_port()); + builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_failure_output_port(), + failure_aggregator->get_input_port(0)); + builder.Connect(failure_aggregator->get_status_output_port(), + controller_failure_pub->get_input_port()); + + // Run lcm-driven simulation + // Create the diagram + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("osc_running_controller")); + + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} // namespace examples +} // namespace examples +} // namespace dairlib + +int main(int argc, char* argv[]) { + return dairlib::examples::DoMain(argc, argv); +} diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 8e12dde4a5..c04851962c 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -98,12 +98,7 @@ int DoMain(int argc, char* argv[]) { addCassieMultibody(&plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); - drake::multibody::MultibodyPlant plant_wo_spr(0.0); - addCassieMultibody(&plant_wo_spr, nullptr, true, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", - false /*spring model*/, false /*loop closure*/); plant.Finalize(); - plant_wo_spr.Finalize(); auto plant_context = plant.CreateDefaultContext(); @@ -120,8 +115,6 @@ int DoMain(int argc, char* argv[]) { map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); - map pos_map_wo_spr = - multibody::makeNameToPositionsMap(plant_wo_spr); std::unordered_map< int, std::vectorSetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "hip_left", - osc_gains.relative_feet, accumulated_state_durations); + osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "hip_right", - osc_gains.relative_feet, accumulated_state_durations); + osc_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.center_line_offset, + l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + osc_gains.center_line_offset, osc_gains.footstep_offset); - r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.center_line_offset, + r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + osc_gains.center_line_offset, osc_gains.footstep_offset); TransTaskSpaceTrackingData pelvis_tracking_data( @@ -433,18 +428,18 @@ int DoMain(int argc, char* argv[]) { JointSpaceTrackingData right_toe_angle_tracking_data( "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); - right_toe_angle_tracking_data.AddStateAndJointToTrack( - left_stance_state, "toe_right", "toe_rightdot"); left_toe_angle_tracking_data.AddStateAndJointToTrack( right_stance_state, "toe_left", "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( - right_touchdown_air_phase, "toe_right", "toe_rightdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( - left_touchdown_air_phase, "toe_right", "toe_rightdot"); left_toe_angle_tracking_data.AddStateAndJointToTrack( right_touchdown_air_phase, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data.AddStateAndJointToTrack( left_touchdown_air_phase, "toe_left", "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + left_stance_state, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "toe_right", "toe_rightdot"); left_toe_angle_tracking_data.SetImpactInvariantProjection(true); right_toe_angle_tracking_data.SetImpactInvariantProjection(true); osc->AddTrackingData(&left_toe_angle_tracking_data); From 16bf02ee6876bea2fb3f098b5c702be469f136c5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 18 Jan 2022 17:10:35 -0500 Subject: [PATCH 078/758] small changes --- .../pydairlib/analysis/log_plotter_cassie.py | 11 +++++---- .../pydairlib/analysis/mbp_plotting_utils.py | 3 ++- .../plot_configs/cassie_running_plot.yaml | 23 ++++++++++--------- .../Cassie/osc_run/foot_traj_generator.cc | 15 ++++++++---- .../Cassie/osc_run/osc_running_gains.yaml | 4 ++-- examples/Cassie/run_osc_running_controller.cc | 5 ++-- .../osc/operational_space_control.cc | 3 ++- .../osc/operational_space_control.h | 1 + 8 files changed, 39 insertions(+), 26 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 9f8d4d7e63..82a405d8f4 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -61,18 +61,21 @@ def main(): ''' Plot Velocities ''' # Plot floating base velocities if applicable if use_floating_base and plot_config.plot_floating_base_velocities: - mbp_plots.plot_floating_base_velocities( + plot = mbp_plots.plot_floating_base_velocities( robot_output, vel_names, 6, t_x_slice) # Plot all joint velocities if plot_config.plot_joint_positions: - mbp_plots.plot_joint_velocities(robot_output, vel_names, + plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 6 if use_floating_base else 0, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + # Plot specific velocities if plot_config.vel_names: - mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, - t_x_slice, vel_map) + plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, + t_x_slice, vel_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.1) ''' Plot Efforts ''' if plot_config.plot_measured_efforts: diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2a31d04b2d..dd49d08e92 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -304,7 +304,8 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): elif deriv == 'vel': data['ydot_des'] = tracking_data.ydot_des[:, dim] data['ydot'] = tracking_data.ydot[:, dim] - data['error_ydot'] = tracking_data.error_ydot[:, dim] + data['error_ydot'] = tracking_data.ydot_des[:, dim] - tracking_data.ydot[:, dim] + data['projected_error_ydot'] = tracking_data.error_ydot[:, dim] elif deriv == 'accel': data['yddot_des'] = tracking_data.yddot_des[:, dim] data['yddot_command'] = tracking_data.yddot_command[:, dim] diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index a68b96a1eb..b3da54f979 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,5 +1,5 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_SIMULATION" +channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_RUNNING" @@ -9,17 +9,18 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false -plot_floating_base_velocities: false +plot_floating_base_velocities: true plot_joint_positions: false -plot_joint_velocities: false +plot_joint_velocities: true plot_measured_efforts: true -special_positions_to_plot: [] -special_velocities_to_plot: [] +special_positions_to_plot: ['base_x', 'base_y'] +special_velocities_to_plot: ['base_vx', 'base_vy'] special_efforts_to_plot: [] # Foot position plots foot_positions_to_plot: ['right', 'left'] -foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} +#foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} +foot_xyz_to_plot: {'right': [1], 'left': [1]} pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots @@ -29,11 +30,11 @@ plot_tracking_costs: true tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['accel']} +# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['accel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} -# left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} -# right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + left_ft_traj: {'dims': [0], 'derivs': ['pos', 'vel']} +# right_ft_traj: {'dims': [0], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [0], 'derivs': ['pos', 'vel']} +# right_ft_z_traj: {'dims': [0], 'derivs': ['pos']} diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index cc0a1fc97b..82c080a975 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -118,13 +118,18 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) .get_mutable_value(); - pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; +// std::cout << "name: " << this->get_name() << std::endl; +// std::cout << "stored: " << pelvis_vel(0) << std::endl; +// std::cout << "current: " << v(3) << std::endl; +// std::cout << "difference: " << pelvis_vel(0) - v(3) << std::endl; + pelvis_vel(0) = 0.5 * v(3) + 0.5 * pelvis_vel(0); +// pelvis_vel(1) = 0.99 * v(4) + 0.01 * pelvis_vel(1); // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; // pelvis_vel = Vector3d::Zero(); } - // if (fsm_state(0) != stance_state_) { - // } +// if (fsm_state(0) != stance_state_) { +// } return EventStatus::Succeeded(); } @@ -199,12 +204,12 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( if (is_left_foot_) { Y[1](1) += 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); - Y[1](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); + Y[1](1) = drake::math::saturate(Y[1](1), center_line_offset_, 0.2); Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); } else { Y[1](1) -= 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); - Y[1](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); + Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -center_line_offset_); Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); } diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 0ea963d866..07af7f4023 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -9,13 +9,13 @@ relative_pelvis: true # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.5 +vel_scale_trans_sagital: 0.1 vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.80 stance_duration: 0.30 -flight_duration: 0.08 +flight_duration: 0.09 mu: 0.6 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c04851962c..8a5c63e82f 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -34,6 +34,7 @@ #include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -380,8 +381,8 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); +// left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); +// right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 6db69087a0..f5fcda8e96 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -916,6 +916,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( total_cost_ += output->acceleration_cost; total_cost_ += output->input_cost; total_cost_ += output->soft_constraint_cost; + soft_constraint_cost_ = output->soft_constraint_cost; for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); @@ -1030,7 +1031,7 @@ void OperationalSpaceControl::CheckTracking( output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; // std::cout << "total cost: " << total_cost_ << std::endl; - if (total_cost_ > 5e4 || isnan(total_cost_)) { + if (soft_constraint_cost_ > 1e2 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 45691ffd81..d8ad25635d 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -399,6 +399,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::MatrixXd W_input_reg_; mutable double total_cost_ = 0; + mutable double soft_constraint_cost_ = 0; }; } // namespace dairlib::systems::controllers From d28a36257076e340a49c38c06a783528b38f04c1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 19 Jan 2022 17:39:22 -0500 Subject: [PATCH 079/758] small tuning changes, need to plot foot pos in world --- .../plot_configs/cassie_running_plot.yaml | 4 +- director/scripts/VisualizationGUI.py | 1 + director/scripts/cassie_test.json | 75 ++++++++++++++++++- .../Cassie/osc_run/foot_traj_generator.cc | 66 ++++++++-------- .../Cassie/osc_run/osc_running_gains.yaml | 24 +++--- examples/Cassie/run_osc_running_controller.cc | 4 +- .../osc/operational_space_control.cc | 2 +- 7 files changed, 122 insertions(+), 54 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index b3da54f979..a3bdc666ec 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -34,7 +34,7 @@ tracking_datas_to_plot: # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [0], 'derivs': ['pos', 'vel']} + left_ft_traj: {'dims': [0, 2], 'derivs': ['pos', 'vel']} # right_ft_traj: {'dims': [0], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [0], 'derivs': ['pos', 'vel']} + left_ft_z_traj: {'dims': [0, 2], 'derivs': ['pos', 'vel']} # right_ft_z_traj: {'dims': [0], 'derivs': ['pos']} diff --git a/director/scripts/VisualizationGUI.py b/director/scripts/VisualizationGUI.py index e65a35a188..38f18c61fd 100644 --- a/director/scripts/VisualizationGUI.py +++ b/director/scripts/VisualizationGUI.py @@ -167,6 +167,7 @@ def clearHistory(self): Function for setting the flag for clearing the history of any line present ''' self.clear = True + self.state_handler(self.msg) def placeCheckBoxes(self): ''' diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index f08914472c..436f69bbba 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -72,7 +72,7 @@ } }, { - "name": "left_ft_traj_des", + "name": "left_ft_traj", "source_data": { "category": "lcm", "abstract_channel": "OSC_DEBUG_RUNNING", @@ -90,8 +90,77 @@ ], "alpha": 0.5, "type": "line", - "thickness": 0.01, - "history": 2 + "thickness": 0.005, + "history": 5 + } + }, + { + "name": "left_ft_traj_des", + "source_data": { + "category": "lcm", + "abstract_channel": "OSC_DEBUG_RUNNING", + "abstract_type": "dairlib.lcmt_osc_output", + "abstract_field": "tracking_data[%d].y_des", + "index_field": "tracking_data_names", + "index_element": "left_ft_traj", + "x_index": 0 + }, + "type_data": { + "color": [ + 1, + 0, + 1 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.005, + "history": 5 + } + }, + { + "name": "right_ft_traj", + "source_data": { + "category": "lcm", + "abstract_channel": "OSC_DEBUG_RUNNING", + "abstract_type": "dairlib.lcmt_osc_output", + "abstract_field": "tracking_data[%d].y", + "index_field": "tracking_data_names", + "index_element": "right_ft_traj", + "x_index": 0 + }, + "type_data": { + "color": [ + 1, + 0, + 0 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.005, + "history": 5 + } + }, + { + "name": "right_ft_traj_des", + "source_data": { + "category": "lcm", + "abstract_channel": "OSC_DEBUG_RUNNING", + "abstract_type": "dairlib.lcmt_osc_output", + "abstract_field": "tracking_data[%d].y_des", + "index_field": "tracking_data_names", + "index_element": "right_ft_traj", + "x_index": 0 + }, + "type_data": { + "color": [ + 1, + 0, + 1 + ], + "alpha": 0.5, + "type": "line", + "thickness": 0.005, + "history": 5 } } ] diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 82c080a975..cc33f8b04b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -118,18 +118,18 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) .get_mutable_value(); -// std::cout << "name: " << this->get_name() << std::endl; -// std::cout << "stored: " << pelvis_vel(0) << std::endl; -// std::cout << "current: " << v(3) << std::endl; -// std::cout << "difference: " << pelvis_vel(0) - v(3) << std::endl; + // std::cout << "name: " << this->get_name() << std::endl; + // std::cout << "stored: " << pelvis_vel(0) << std::endl; + // std::cout << "current: " << v(3) << std::endl; + // std::cout << "difference: " << pelvis_vel(0) - v(3) << std::endl; pelvis_vel(0) = 0.5 * v(3) + 0.5 * pelvis_vel(0); -// pelvis_vel(1) = 0.99 * v(4) + 0.01 * pelvis_vel(1); + // pelvis_vel(1) = 0.99 * v(4) + 0.01 * pelvis_vel(1); // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; // pelvis_vel = Vector3d::Zero(); } -// if (fsm_state(0) != stance_state_) { -// } + // if (fsm_state(0) != stance_state_) { + // } return EventStatus::Succeeded(); } @@ -139,7 +139,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( const auto robot_output = this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = - this->EvalVectorInput(context, target_vel_port_)->get_value(); + this->EvalVectorInput(context, target_vel_port_)->value(); VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); @@ -159,12 +159,27 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // TODO(yangwill): should not use estimated pelvis velocity - from discussion // with OSU DRL Vector3d desired_pelvis_vel; - desired_pelvis_vel << desired_pelvis_vel_xy, 0; - VectorXd pelvis_vel = v.segment(3, 3); - pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); -// pelvis_vel(1) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); - VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; - VectorXd footstep_correction = Kd_ * (pelvis_vel_err); + desired_pelvis_vel << desired_pelvis_vel_xy(1), desired_pelvis_vel_xy(0), 0; + + Vector3d stance_foot_pos; + if (is_left_foot_) { + plant_.CalcPointsPositions(*context_, + plant_.GetBodyByName("toe_right").body_frame(), + Vector3d::Zero(), world_, &stance_foot_pos); + } else { + plant_.CalcPointsPositions(*context_, + plant_.GetBodyByName("toe_left").body_frame(), + Vector3d::Zero(), world_, &stance_foot_pos); + } + drake::multibody::SpatialMomentum momentum = + plant_.CalcSpatialMomentumInWorldAboutPoint(*context_, stance_foot_pos); + Vector3d L = momentum.rotational(); + + // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); + // pelvis_vel(1) = + // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); + Vector3d pelvis_vel_err = rot.transpose() * L - desired_pelvis_vel; + Vector3d footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { footstep_correction(1) += center_line_offset_; } else { @@ -202,12 +217,12 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // corrections if (is_left_foot_) { - Y[1](1) += 0.25 * center_line_offset_; +// Y[1](1) += 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); Y[1](1) = drake::math::saturate(Y[1](1), center_line_offset_, 0.2); Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); } else { - Y[1](1) -= 0.25 * center_line_offset_; +// Y[1](1) -= 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -center_line_offset_); Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); @@ -215,7 +230,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); - Y_dot_end(2) = -0.1; +// Y_dot_end(2) = -0.1; PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( @@ -224,10 +239,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( if (is_left_foot_) { return swing_foot_spline; } else { - // MatrixXd Y0 = MatrixXd::Zero(3, 3); - // MatrixXd Ydot0 = MatrixXd::Zero(3, 3); - // MatrixXd Y1 = MatrixXd::Zero(2, 3); - // MatrixXd Ydot1 = MatrixXd::Zero(2, 3); std::vector Y0(T_waypoints_0.size(), VectorXd::Zero(3)); std::vector Ydot0(T_waypoints_0.size(), VectorXd::Zero(3)); std::vector Y2(T_waypoints_1.size(), VectorXd::Zero(3)); @@ -248,26 +259,13 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); offset_swing_foot_spline.ConcatenateInTime( PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); - // for (auto t : offset_swing_foot_spline.get_segment_times()){ - // std::cout << t << std::endl; - // } return offset_swing_foot_spline; } - // return swing_foot_spline; } void FootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { - // Read in current state - // const auto robot_output = - // this->template EvalVectorInput(context, state_port_); - // VectorXd x = robot_output->GetState(); - // double timestamp = robot_output->get_timestamp(); - // - // // Read in finite state machine - // const auto fsm_state = this->EvalVectorInput(context, - // fsm_port_)->get_value(); auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 07af7f4023..0fad51d648 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -9,15 +9,15 @@ relative_pelvis: true # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.1 +vel_scale_trans_sagital: 5.0 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.80 +rest_length: 0.8 stance_duration: 0.30 flight_duration: 0.09 -mu: 0.6 +mu: 0.8 w_swing_toe: 1 swing_toe_kp: 1500 @@ -33,16 +33,16 @@ hip_yaw_kd: 15 #hip_roll_kp: 50 #hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.05 -center_line_offset: 0.05 +footstep_offset: -0.04 +center_line_offset: 0.03 FootstepKd: - [ 0.4, 0, 0, - 0, 0.45, 0, + [ 0.0, 0.01, 0, + -0.1, 0.0, 0, 0, 0, 0] PelvisW: - [0.1, 0, 0, - 0, 0.1, 0, - 0, 0, 5] + [0.0, 0, 0, + 0, 0.1, 0, + 0, 0, 5] PelvisKp: [ 1, 0, 0, 0, 1, 0, @@ -56,11 +56,11 @@ PelvisRotW: 0, 0.1, 0, 0, 0, 0] PelvisRotKp: - [100, 0, 0, + [250, 0, 0, 0, 50, 0, 0, 0, 0] PelvisRotKd: - [10, 0, 0, + [25, 0, 0, 0, 10, 0, 0, 0, 0] SwingFootW: diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 8a5c63e82f..23ca5d3a57 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -335,12 +335,12 @@ int DoMain(int argc, char* argv[]) { osc_gains.W_swing_foot, plant, plant); left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); + left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, "pelvis"); - left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); TransTaskSpaceTrackingData left_hip_yz_tracking_data( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f5fcda8e96..d11fb5df4b 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -816,7 +816,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { VectorXd v_proj = VectorXd::Zero(n_v_); - active_tracking_data_dim += tracking_data->GetYDim(); + active_tracking_data_dim += tracking_data->GetYdotDim(); if (fixed_position_vec_.at(i).size() != 0) { // Create constant trajectory and update tracking_data->Update( From a15b33a9e1cf924232ffaf42a82df6e0a09f6a7a Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 20 Jan 2022 12:27:20 -0500 Subject: [PATCH 080/758] fixed wrt bugs --- .../plot_configs/cassie_running_plot.yaml | 4 ++-- director/scripts/cassie_test.json | 6 ++--- .../Cassie/osc_run/foot_traj_generator.cc | 22 +++++++++++++------ .../Cassie/osc_run/osc_running_gains.yaml | 10 ++++----- examples/Cassie/run_osc_running_controller.cc | 8 +++---- 5 files changed, 29 insertions(+), 21 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index a3bdc666ec..0eb78e8c23 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -34,7 +34,7 @@ tracking_datas_to_plot: # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [0, 2], 'derivs': ['pos', 'vel']} + left_ft_traj: {'dims': [0, 1], 'derivs': ['pos', 'vel']} # right_ft_traj: {'dims': [0], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [0, 2], 'derivs': ['pos', 'vel']} + left_ft_z_traj: {'dims': [0, 1], 'derivs': ['pos', 'vel']} # right_ft_z_traj: {'dims': [0], 'derivs': ['pos']} diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index 436f69bbba..72499cbb5d 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -125,7 +125,7 @@ "abstract_type": "dairlib.lcmt_osc_output", "abstract_field": "tracking_data[%d].y", "index_field": "tracking_data_names", - "index_element": "right_ft_traj", + "index_element": "left_ft_z_traj", "x_index": 0 }, "type_data": { @@ -148,13 +148,13 @@ "abstract_type": "dairlib.lcmt_osc_output", "abstract_field": "tracking_data[%d].y_des", "index_field": "tracking_data_names", - "index_element": "right_ft_traj", + "index_element": "left_ft_z_traj", "x_index": 0 }, "type_data": { "color": [ 1, - 0, + 1, 1 ], "alpha": 0.5, diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index cc33f8b04b..56128ca9fb 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -114,8 +114,10 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( .get_mutable_value(); plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, &hip_pos); - foot_pos = rot.transpose() * foot_pos; - hip_pos = rot.transpose() * hip_pos; + // foot_pos = rot.transpose() * foot_pos; + // hip_pos = rot.transpose() * hip_pos; + foot_pos = foot_pos; + hip_pos = hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) .get_mutable_value(); // std::cout << "name: " << this->get_name() << std::endl; @@ -162,10 +164,15 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( desired_pelvis_vel << desired_pelvis_vel_xy(1), desired_pelvis_vel_xy(0), 0; Vector3d stance_foot_pos; + Vector3d pelvis_pos; + plant_.CalcPointsPositions(*context_, + plant_.GetBodyByName("pelvis").body_frame(), + Vector3d::Zero(), world_, &pelvis_pos); if (is_left_foot_) { plant_.CalcPointsPositions(*context_, plant_.GetBodyByName("toe_right").body_frame(), Vector3d::Zero(), world_, &stance_foot_pos); + } else { plant_.CalcPointsPositions(*context_, plant_.GetBodyByName("toe_left").body_frame(), @@ -178,7 +185,9 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); // pelvis_vel(1) = // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); - Vector3d pelvis_vel_err = rot.transpose() * L - desired_pelvis_vel; + // Vector3d pelvis_vel_err = rot.transpose() * L - desired_pelvis_vel; + + Vector3d pelvis_vel_err = L - desired_pelvis_vel; Vector3d footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { footstep_correction(1) += center_line_offset_; @@ -217,12 +226,12 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // corrections if (is_left_foot_) { -// Y[1](1) += 0.25 * center_line_offset_; + // Y[1](1) += 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); Y[1](1) = drake::math::saturate(Y[1](1), center_line_offset_, 0.2); Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); } else { -// Y[1](1) -= 0.25 * center_line_offset_; + // Y[1](1) -= 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -center_line_offset_); Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); @@ -230,7 +239,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); -// Y_dot_end(2) = -0.1; + // Y_dot_end(2) = -0.1; PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( @@ -266,7 +275,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( void FootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { - auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 0fad51d648..934c0e91a7 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -33,11 +33,11 @@ hip_yaw_kd: 15 #hip_roll_kp: 50 #hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.04 +footstep_offset: -0.0 center_line_offset: 0.03 FootstepKd: - [ 0.0, 0.01, 0, - -0.1, 0.0, 0, + [ 0.0, 0.012, 0, + -0.08, 0.0, 0, 0, 0, 0] PelvisW: [0.0, 0, 0, @@ -56,7 +56,7 @@ PelvisRotW: 0, 0.1, 0, 0, 0, 0] PelvisRotKp: - [250, 0, 0, + [125, 0, 0, 0, 50, 0, 0, 0, 0] PelvisRotKd: @@ -64,7 +64,7 @@ PelvisRotKd: 0, 10, 0, 0, 0, 0] SwingFootW: - [5, 0, 0, + [10, 0, 0, 0, 10, 0, 0, 0, 1] SwingFootKp: diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 23ca5d3a57..6228cb5a46 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -269,10 +269,10 @@ int DoMain(int argc, char* argv[]) { osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "hip_left", + plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "hip_right", + plant, plant_context.get(), "toe_right", "pelvis", osc_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); @@ -349,9 +349,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); + "pelvis"); right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); + "pelvis"); RelativeTranslationTrackingData left_foot_rel_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, From 4bd3add35878c9c333614a876a42aec061ea9436 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 21 Jan 2022 14:47:46 -0500 Subject: [PATCH 081/758] working in drake and mujoco --- .../plot_configs/cassie_running_plot.yaml | 29 ++++--- examples/Cassie/multibody_sim.cc | 3 +- examples/Cassie/osc/osc_standing_gains.yaml | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 79 ++++++++----------- .../Cassie/osc_run/osc_running_gains.yaml | 38 ++++----- examples/Cassie/run_osc_running_controller.cc | 17 ++-- .../Cassie/urdf/cassie_v2_conservative.urdf | 8 +- .../osc/operational_space_control.cc | 8 +- 8 files changed, 86 insertions(+), 98 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 0eb78e8c23..1b8fd3a200 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,5 +1,5 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_DISPATCHER" +channel_x: "CASSIE_STATE_SIMULATION" channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_RUNNING" @@ -9,18 +9,17 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false -plot_floating_base_velocities: true +plot_floating_base_velocities: false plot_joint_positions: false -plot_joint_velocities: true +plot_joint_velocities: false plot_measured_efforts: true -special_positions_to_plot: ['base_x', 'base_y'] -special_velocities_to_plot: ['base_vx', 'base_vy'] +special_positions_to_plot: [] +special_velocities_to_plot: [] special_efforts_to_plot: [] # Foot position plots foot_positions_to_plot: ['right', 'left'] -#foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} -foot_xyz_to_plot: {'right': [1], 'left': [1]} +foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots @@ -28,13 +27,13 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} -# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} -# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['accel']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} + pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} + # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['accel']} + # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [0, 1], 'derivs': ['pos', 'vel']} -# right_ft_traj: {'dims': [0], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [0, 1], 'derivs': ['pos', 'vel']} -# right_ft_z_traj: {'dims': [0], 'derivs': ['pos']} + left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 3965e6ee55..bd5e6cfad9 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -61,6 +61,7 @@ DEFINE_double(publish_rate, 1000, "Publish rate for simulator"); DEFINE_double(init_height, .7, "Initial starting height of the pelvis above " "ground"); +DEFINE_double(toe_spread, .15, "Initial toe spread in m."); DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); DEFINE_string(radio_channel, "CASSIE_VIRTUAL_RADIO", @@ -180,7 +181,7 @@ int do_main(int argc, char* argv[]) { VectorXd q_init, u_init, lambda_init; double mu_fp = 0; double min_normal_fp = 70; - double toe_spread = .15; + double toe_spread = FLAGS_toe_spread; // Create a plant for CassieFixedPointSolver. // Note that we cannot use the plant from the above diagram, because after the // diagram is built, plant.get_actuation_input_port().HasValue(*context) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 4d28ca8b62..c819249bcb 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -31,7 +31,7 @@ CoMKp: CoMKd: [ 0.5, 0, 0, 0, 0.75, 0, - 0, 0, 1] + 0, 0, 5] PelvisRotKp: [10, 0, 0, 0, 30, 0, diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 56128ca9fb..9e35223c0b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -114,24 +114,17 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( .get_mutable_value(); plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, &hip_pos); - // foot_pos = rot.transpose() * foot_pos; - // hip_pos = rot.transpose() * hip_pos; - foot_pos = foot_pos; - hip_pos = hip_pos; + foot_pos = rot.transpose() * foot_pos; + hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) .get_mutable_value(); - // std::cout << "name: " << this->get_name() << std::endl; - // std::cout << "stored: " << pelvis_vel(0) << std::endl; - // std::cout << "current: " << v(3) << std::endl; - // std::cout << "difference: " << pelvis_vel(0) - v(3) << std::endl; - pelvis_vel(0) = 0.5 * v(3) + 0.5 * pelvis_vel(0); - // pelvis_vel(1) = 0.99 * v(4) + 0.01 * pelvis_vel(1); + pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; // pelvis_vel = Vector3d::Zero(); } - // if (fsm_state(0) != stance_state_) { - // } + // if (fsm_state(0) != stance_state_) { + // } return EventStatus::Succeeded(); } @@ -141,7 +134,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( const auto robot_output = this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = - this->EvalVectorInput(context, target_vel_port_)->value(); + this->EvalVectorInput(context, target_vel_port_)->get_value(); VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); @@ -161,34 +154,12 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // TODO(yangwill): should not use estimated pelvis velocity - from discussion // with OSU DRL Vector3d desired_pelvis_vel; - desired_pelvis_vel << desired_pelvis_vel_xy(1), desired_pelvis_vel_xy(0), 0; - - Vector3d stance_foot_pos; - Vector3d pelvis_pos; - plant_.CalcPointsPositions(*context_, - plant_.GetBodyByName("pelvis").body_frame(), - Vector3d::Zero(), world_, &pelvis_pos); - if (is_left_foot_) { - plant_.CalcPointsPositions(*context_, - plant_.GetBodyByName("toe_right").body_frame(), - Vector3d::Zero(), world_, &stance_foot_pos); - - } else { - plant_.CalcPointsPositions(*context_, - plant_.GetBodyByName("toe_left").body_frame(), - Vector3d::Zero(), world_, &stance_foot_pos); - } - drake::multibody::SpatialMomentum momentum = - plant_.CalcSpatialMomentumInWorldAboutPoint(*context_, stance_foot_pos); - Vector3d L = momentum.rotational(); - - // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); - // pelvis_vel(1) = - // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); - // Vector3d pelvis_vel_err = rot.transpose() * L - desired_pelvis_vel; - - Vector3d pelvis_vel_err = L - desired_pelvis_vel; - Vector3d footstep_correction = Kd_ * (pelvis_vel_err); + desired_pelvis_vel << desired_pelvis_vel_xy, 0; + VectorXd pelvis_vel = v.segment(3, 3); + pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); +// pelvis_vel(1) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); + VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; + VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { footstep_correction(1) += center_line_offset_; } else { @@ -221,17 +192,17 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[0](2) = -rest_length_; Y[1] = start_pos + 0.85 * footstep_correction; Y[1](2) = -rest_length_ + 0.01; - Y[2] = start_pos + footstep_correction; + Y[2] = footstep_correction; Y[2](2) = -rest_length_; // corrections if (is_left_foot_) { - // Y[1](1) += 0.25 * center_line_offset_; + Y[1](1) -= 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); Y[1](1) = drake::math::saturate(Y[1](1), center_line_offset_, 0.2); Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); } else { - // Y[1](1) -= 0.25 * center_line_offset_; + Y[1](1) += 0.25 * center_line_offset_; // Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -center_line_offset_); Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); @@ -239,7 +210,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); - // Y_dot_end(2) = -0.1; + Y_dot_end(2) = -0.1; PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( @@ -248,6 +219,10 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( if (is_left_foot_) { return swing_foot_spline; } else { + // MatrixXd Y0 = MatrixXd::Zero(3, 3); + // MatrixXd Ydot0 = MatrixXd::Zero(3, 3); + // MatrixXd Y1 = MatrixXd::Zero(2, 3); + // MatrixXd Ydot1 = MatrixXd::Zero(2, 3); std::vector Y0(T_waypoints_0.size(), VectorXd::Zero(3)); std::vector Ydot0(T_waypoints_0.size(), VectorXd::Zero(3)); std::vector Y2(T_waypoints_1.size(), VectorXd::Zero(3)); @@ -268,13 +243,27 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); offset_swing_foot_spline.ConcatenateInTime( PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); + // for (auto t : offset_swing_foot_spline.get_segment_times()){ + // std::cout << t << std::endl; + // } return offset_swing_foot_spline; } + // return swing_foot_spline; } void FootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { + // Read in current state + // const auto robot_output = + // this->template EvalVectorInput(context, state_port_); + // VectorXd x = robot_output->GetState(); + // double timestamp = robot_output->get_timestamp(); + // + // // Read in finite state machine + // const auto fsm_state = this->EvalVectorInput(context, + // fsm_port_)->get_value(); + auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 934c0e91a7..8e8639e8a7 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0000000000 -w_accel: 0.00001 +w_accel: 0.00000 #w_soft_constraint: 1000000 -w_soft_constraint: 1000.0 +w_soft_constraint: 0.01 w_input_reg: 0.01 impact_threshold: 0.025 relative_feet: true @@ -9,15 +9,15 @@ relative_pelvis: true # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 5.0 +vel_scale_trans_sagital: 0.2 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.8 +rest_length: 0.85 stance_duration: 0.30 flight_duration: 0.09 -mu: 0.8 +mu: 0.6 w_swing_toe: 1 swing_toe_kp: 1500 @@ -33,38 +33,38 @@ hip_yaw_kd: 15 #hip_roll_kp: 50 #hip_roll_kd: 10 # Foot placement parameters -footstep_offset: -0.0 +footstep_offset: -0.04 center_line_offset: 0.03 FootstepKd: - [ 0.0, 0.012, 0, - -0.08, 0.0, 0, + [ 0.2, 0, 0, + 0, 0.4, 0, 0, 0, 0] PelvisW: - [0.0, 0, 0, + [0.1, 0, 0, 0, 0.1, 0, 0, 0, 5] PelvisKp: - [ 1, 0, 0, + [ 0, 0, 0, 0, 1, 0, - 0, 0, 110] + 0, 0, 95] PelvisKd: - [ 5, 0, 0, + [ 1, 0, 0, 0, 5, 0, 0, 0, 5] PelvisRotW: [0.1, 0, 0, - 0, 0.1, 0, + 0, 0.05, 0, 0, 0, 0] PelvisRotKp: - [125, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 0] PelvisRotKd: - [25, 0, 0, + [5, 0, 0, 0, 10, 0, 0, 0, 0] SwingFootW: - [10, 0, 0, + [50, 0, 0, 0, 10, 0, 0, 0, 1] SwingFootKp: @@ -72,8 +72,8 @@ SwingFootKp: 0, 125, 0, 0, 0, 50] SwingFootKd: - [15, 0, 0, - 0, 15, 0, + [10, 0, 0, + 0, 10, 0, 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, @@ -81,7 +81,7 @@ LiftoffSwingFootW: 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, - 0, 125, 0, + 0, 50, 0, 0, 0, 10] LiftoffSwingFootKd: [ 1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 6228cb5a46..bc5972445b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -34,7 +34,6 @@ #include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" -#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -269,8 +268,8 @@ int DoMain(int argc, char* argv[]) { osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", - osc_gains.relative_feet, 0, accumulated_state_durations); + plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, + 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", osc_gains.relative_feet, 1, accumulated_state_durations); @@ -335,12 +334,12 @@ int DoMain(int argc, char* argv[]) { osc_gains.W_swing_foot, plant, plant); left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); - left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, "pelvis"); + left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "pelvis"); TransTaskSpaceTrackingData left_hip_yz_tracking_data( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -349,9 +348,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, - "pelvis"); + "hip_left"); right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); + "hip_right"); RelativeTranslationTrackingData left_foot_rel_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -381,8 +380,8 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); -// left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); -// right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 5c5471cbdc..95d62e6c23 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -672,7 +672,7 @@ - + @@ -681,7 +681,7 @@ - + @@ -786,7 +786,7 @@ - + @@ -795,7 +795,7 @@ - + diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index d11fb5df4b..f899f199dc 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -633,7 +633,7 @@ VectorXd OperationalSpaceControl::SolveQp( MatrixXd A_c = MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_); A_c.block(0, 0, n_c_active_, n_v_) = J_c_active; A_c.block(0, n_v_, n_c_active_, n_c_active_) = - MatrixXd::Identity(n_c_active_, n_c_active_); + 0.01 * MatrixXd::Identity(n_c_active_, n_c_active_); contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -844,11 +844,11 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( for (auto tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { - A.block(start_row, 0, tracking_data->GetYDim(), active_constraint_dim) = + A.block(start_row, 0, tracking_data->GetYdotDim(), active_constraint_dim) = tracking_data->GetJ() * M_Jt_; - ydot_err_vec.segment(start_row, tracking_data->GetYDim()) = + ydot_err_vec.segment(start_row, tracking_data->GetYdotDim()) = tracking_data->GetErrorYdot(); - start_row += tracking_data->GetYDim(); + start_row += tracking_data->GetYdotDim(); } } From b6a6303ef9a11669ea49dc485e697e3eb0e41d17 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 21 Jan 2022 17:05:29 -0500 Subject: [PATCH 082/758] small deprecation fix --- examples/Cassie/run_osc_standing_controller.cc | 2 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index a91278c082..160116e37a 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -39,7 +39,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 7f9a719b32..049bedb841 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -49,7 +49,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using multibody::WorldYawViewFrame; using systems::controllers::ComTrackingData; From 96bf9c2261947aaab8dd5e079476e493cfb3b54f Mon Sep 17 00:00:00 2001 From: Yu-Ming Chen Date: Sat, 22 Jan 2022 23:02:55 -0500 Subject: [PATCH 083/758] Remove hard-coded indices in dircon walking example --- examples/Cassie/run_dircon_walking.cc | 224 ++++++++++++++++++++------ 1 file changed, 173 insertions(+), 51 deletions(-) diff --git a/examples/Cassie/run_dircon_walking.cc b/examples/Cassie/run_dircon_walking.cc index 60e2447448..460ea962eb 100644 --- a/examples/Cassie/run_dircon_walking.cc +++ b/examples/Cassie/run_dircon_walking.cc @@ -114,10 +114,33 @@ vector GetInitGuessForQ(int N, double stride_length, vector q_init_guess; VectorXd q_ik_guess = VectorXd::Zero(n_q); + + map pos_value_map; Eigen::Vector4d quat(2000.06, -0.339462, -0.609533, -0.760854); - q_ik_guess << quat.normalized(), 0.000889849, 0.000626865, 1.0009, -0.0112109, - 0.00927845, -0.000600725, -0.000895805, 1.15086, 0.610808, -1.38608, - -1.35926, 0.806192, 1.00716, -M_PI / 2, -M_PI / 2; + quat.normalize(); + pos_value_map["base_qw"] = quat(0); + pos_value_map["base_qx"] = quat(1); + pos_value_map["base_qy"] = quat(2); + pos_value_map["base_qz"] = quat(3); + pos_value_map["base_x"] = 0.000889849; + pos_value_map["base_y"] = 0.000626865; + pos_value_map["base_z"] = 1.0009; + pos_value_map["hip_roll_left"] = -0.0112109; + pos_value_map["hip_roll_right"] = 0.00927845; + pos_value_map["hip_yaw_left"] = -0.000600725; + pos_value_map["hip_yaw_right"] = -0.000895805; + pos_value_map["hip_pitch_left"] = 1.15086; + pos_value_map["hip_pitch_right"] = 0.610808; + pos_value_map["knee_left"] = -1.38608; + pos_value_map["knee_right"] = -1.35926; + pos_value_map["ankle_joint_left"] = 0.806192; + pos_value_map["ankle_joint_right"] = 1.00716; + pos_value_map["toe_left"] = -M_PI / 2; + pos_value_map["toe_right"] = -M_PI / 2; + + for (auto pair : pos_value_map) { + q_ik_guess(positions_map.at(pair.first)) = pair.second; + } for (int i = 0; i < N; i++) { double eps = 1e-3; @@ -386,20 +409,86 @@ void DoMain(double duration, double stride_length, double ground_incline, options_list[i].setConstraintRelative(1, true); options_list[i].setConstraintRelative(3, true); } + + int base_qw_idx = pos_map.at("base_qw"); + int base_qx_idx = pos_map.at("base_qx"); + int base_qy_idx = pos_map.at("base_qy"); + int base_qz_idx = pos_map.at("base_qz"); + int base_x_idx = pos_map.at("base_x"); + int base_y_idx = pos_map.at("base_y"); + int base_z_idx = pos_map.at("base_z"); + int hip_roll_left_idx = pos_map.at("hip_roll_left"); + int hip_roll_right_idx = pos_map.at("hip_roll_right"); + int hip_yaw_left_idx = pos_map.at("hip_yaw_left"); + int hip_yaw_right_idx = pos_map.at("hip_yaw_right"); + int hip_pitch_left_idx = pos_map.at("hip_pitch_left"); + int hip_pitch_right_idx = pos_map.at("hip_pitch_right"); + int knee_left_idx = pos_map.at("knee_left"); + int knee_right_idx = pos_map.at("knee_right"); + int ankle_joint_left_idx = pos_map.at("ankle_joint_left"); + int ankle_joint_right_idx = pos_map.at("ankle_joint_right"); + int toe_left_idx = pos_map.at("toe_left"); + int toe_right_idx = pos_map.at("toe_right"); + + int base_wx_idx = vel_map.at("base_wx"); + int base_wy_idx = vel_map.at("base_wy"); + int base_wz_idx = vel_map.at("base_wz"); + int base_vx_idx = vel_map.at("base_vx"); + int base_vy_idx = vel_map.at("base_vy"); + int base_vz_idx = vel_map.at("base_vz"); + int hip_roll_leftdot_idx = vel_map.at("hip_roll_leftdot"); + int hip_roll_rightdot_idx = vel_map.at("hip_roll_rightdot"); + int hip_yaw_leftdot_idx = vel_map.at("hip_yaw_leftdot"); + int hip_yaw_rightdot_idx = vel_map.at("hip_yaw_rightdot"); + int hip_pitch_leftdot_idx = vel_map.at("hip_pitch_leftdot"); + int hip_pitch_rightdot_idx = vel_map.at("hip_pitch_rightdot"); + int knee_leftdot_idx = vel_map.at("knee_leftdot"); + int knee_rightdot_idx = vel_map.at("knee_rightdot"); + int ankle_joint_leftdot_idx = vel_map.at("ankle_joint_leftdot"); + int ankle_joint_rightdot_idx = vel_map.at("ankle_joint_rightdot"); + int toe_leftdot_idx = vel_map.at("toe_leftdot"); + int toe_rightdot_idx = vel_map.at("toe_rightdot"); + + int hip_roll_left_motor_idx = act_map.at("hip_roll_left_motor"); + int hip_roll_right_motor_idx = act_map.at("hip_roll_right_motor"); + int hip_yaw_left_motor_idx = act_map.at("hip_yaw_left_motor"); + int hip_yaw_right_motor_idx = act_map.at("hip_yaw_right_motor"); + int hip_pitch_left_motor_idx = act_map.at("hip_pitch_left_motor"); + int hip_pitch_right_motor_idx = act_map.at("hip_pitch_right_motor"); + int knee_left_motor_idx = act_map.at("knee_left_motor"); + int knee_right_motor_idx = act_map.at("knee_right_motor"); + int toe_left_motor_idx = act_map.at("toe_left_motor"); + int toe_right_motor_idx = act_map.at("toe_right_motor"); + // Constraint scaling if (FLAGS_is_scale_constraint) { for (int i = 0; i < 2; i++) { double s = 1; // scale everything together // Dynamic constraints - options_list[i].setDynConstraintScaling({0, 1, 2, 3}, s * 1.0 / 30.0); options_list[i].setDynConstraintScaling( - {4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16}, s * 1.0 / 60.0); - options_list[i].setDynConstraintScaling({17, 18}, s * 1.0 / 300.0); + {base_qw_idx, base_qx_idx, base_qy_idx, base_qz_idx}, s * 1.0 / 30.0); + options_list[i].setDynConstraintScaling( + {base_x_idx, base_y_idx, base_z_idx, hip_roll_left_idx, + hip_roll_right_idx, hip_yaw_left_idx, hip_yaw_right_idx, + hip_pitch_left_idx, hip_pitch_right_idx, knee_left_idx, + knee_right_idx, ankle_joint_left_idx, ankle_joint_right_idx}, + s * 1.0 / 60.0); + options_list[i].setDynConstraintScaling({toe_left_idx, toe_right_idx}, + s * 1.0 / 300.0); + options_list[i].setDynConstraintScaling( + {n_q + base_wx_idx, n_q + base_wy_idx, n_q + base_wz_idx, + n_q + base_vx_idx, n_q + base_vy_idx, n_q + base_vz_idx, + n_q + hip_roll_leftdot_idx, n_q + hip_roll_rightdot_idx, + n_q + hip_yaw_leftdot_idx, n_q + hip_yaw_rightdot_idx}, + s * 1.0 / 600.0); options_list[i].setDynConstraintScaling( - {19, 20, 21, 22, 23, 24, 25, 26, 27, 28}, s * 1.0 / 600.0); - options_list[i].setDynConstraintScaling({29, 30, 31, 32, 33, 34}, - s * 1.0 / 3000.0); - options_list[i].setDynConstraintScaling({35, 36}, s * 1.0 / 60000.0); + {n_q + hip_pitch_leftdot_idx, n_q + hip_pitch_rightdot_idx, + n_q + knee_leftdot_idx, n_q + knee_rightdot_idx, + n_q + ankle_joint_leftdot_idx, n_q + ankle_joint_rightdot_idx}, + s * 1.0 / 3000.0); + options_list[i].setDynConstraintScaling( + {n_q + toe_leftdot_idx, n_q + toe_rightdot_idx}, s * 1.0 / 60000.0); + // Kinematic constraints int n_l = options_list[i].getNumConstraints(); options_list[i].setKinConstraintScaling({0, 1, 2, 3, 4}, s / 6000.0); @@ -412,13 +501,22 @@ void DoMain(double duration, double stride_length, double ground_incline, options_list[i].setKinConstraintScaling({2 * n_l + 5, 2 * n_l + 6}, s * 20); // Impact constraints - options_list[i].setImpConstraintScaling({0, 1, 2}, s / 50.0); - options_list[i].setImpConstraintScaling({3, 4, 5}, s / 300.0); - options_list[i].setImpConstraintScaling({6, 7}, s / 24.0); - options_list[i].setImpConstraintScaling({8, 9}, s / 6.0); - options_list[i].setImpConstraintScaling({10, 11, 12, 13}, s / 12.0); - options_list[i].setImpConstraintScaling({14, 15}, s / 2.0); - options_list[i].setImpConstraintScaling({16, 17}, s); + options_list[i].setImpConstraintScaling( + {base_wx_idx, base_wy_idx, base_wz_idx}, s / 50.0); + options_list[i].setImpConstraintScaling( + {base_vx_idx, base_vy_idx, base_vz_idx}, s / 300.0); + options_list[i].setImpConstraintScaling( + {hip_roll_leftdot_idx, hip_roll_rightdot_idx}, s / 24.0); + options_list[i].setImpConstraintScaling( + {hip_yaw_leftdot_idx, hip_yaw_rightdot_idx}, s / 6.0); + options_list[i].setImpConstraintScaling( + {hip_pitch_leftdot_idx, hip_pitch_rightdot_idx, knee_leftdot_idx, + knee_rightdot_idx}, + s / 12.0); + options_list[i].setImpConstraintScaling( + {ankle_joint_leftdot_idx, ankle_joint_rightdot_idx}, s / 2.0); + options_list[i].setImpConstraintScaling( + {toe_leftdot_idx, toe_rightdot_idx}, s); } } @@ -619,7 +717,7 @@ void DoMain(double duration, double stride_length, double ground_incline, trajopt->AddConstraint(right_foot_constraint_z, x_mid.head(n_q)); // Optional -- constraint on initial floating base - trajopt->AddConstraint(x0(0) == 1); + trajopt->AddConstraint(x0(pos_map.at("base_qw")) == 1); // Optional -- constraint on the forces magnitude /*for (unsigned int mode = 0; mode < num_time_samples.size(); mode++) { for (int index = 0; index < num_time_samples[mode]; index++) { @@ -673,17 +771,24 @@ void DoMain(double duration, double stride_length, double ground_incline, // time trajopt->ScaleTimeVariables(0.008); // state - trajopt->ScaleStateVariables({0, 1, 2, 3}, 0.5); + trajopt->ScaleStateVariables( + {base_qw_idx, base_qx_idx, base_qy_idx, base_qz_idx}, 0.5); if (s_q_toe > 1) { - trajopt->ScaleStateVariables({n_q - 2, n_q - 1}, s_q_toe); + trajopt->ScaleStateVariables({toe_left_idx, toe_right_idx}, s_q_toe); } - idx_list.clear(); - for (int i = n_q; i < n_q + n_v - 2; i++) { - idx_list.push_back(i); + std::set idx_set; + for (int i = n_q; i < n_q + n_v; i++) { + idx_set.insert(i); } + idx_set.erase(n_q + vel_map.at("toe_leftdot")); + idx_set.erase(n_q + vel_map.at("toe_rightdot")); + idx_list.clear(); + idx_list.assign(idx_set.begin(), idx_set.end()); trajopt->ScaleStateVariables(idx_list, 10); - trajopt->ScaleStateVariable(n_q + n_v - 2, 10 * s_v_toe_l); - trajopt->ScaleStateVariable(n_q + n_v - 1, 10 * s_v_toe_r); + trajopt->ScaleStateVariable(n_q + vel_map.at("toe_leftdot"), + 10 * s_v_toe_l); + trajopt->ScaleStateVariable(n_q + vel_map.at("toe_rightdot"), + 10 * s_v_toe_r); // input trajopt->ScaleInputVariables({0, 1, 2, 3, 4, 5, 6, 7, 8, 9}, 100); // force @@ -698,7 +803,7 @@ void DoMain(double duration, double stride_length, double ground_incline, } trajopt->ScaleForceVariables(1, idx_list, 1000); // impulse - trajopt->ScaleImpulseVariables(0, idx_list, 10); + trajopt->ScaleImpulseVariables(base_wx_idx, idx_list, 10); // quaternion slack trajopt->ScaleQuaternionSlackVariables(30); // Constraint slack @@ -710,8 +815,10 @@ void DoMain(double duration, double stride_length, double ground_incline, MatrixXd W_Q = w_Q * MatrixXd::Identity(n_v, n_v); MatrixXd W_R = w_R * MatrixXd::Identity(n_u, n_u); - W_Q(n_v - 2, n_v - 2) /= (s_v_toe_l * s_v_toe_l); - W_Q(n_v - 1, n_v - 1) /= (s_v_toe_r * s_v_toe_r); + W_Q(vel_map.at("toe_leftdot"), vel_map.at("toe_leftdot")) /= + (s_v_toe_l * s_v_toe_l); + W_Q(vel_map.at("toe_rightdot"), vel_map.at("toe_rightdot")) /= + (s_v_toe_r * s_v_toe_r); trajopt->AddRunningCost(x.tail(n_v).transpose() * W_Q * x.tail(n_v)); trajopt->AddRunningCost(u.transpose() * W_R * u); @@ -735,8 +842,10 @@ void DoMain(double duration, double stride_length, double ground_incline, } // add cost on vel difference wrt time MatrixXd Q_v_diff = w_v_diff * MatrixXd::Identity(n_v, n_v); - Q_v_diff(n_v - 2, n_v - 2) /= (s_v_toe_l * s_v_toe_l); - Q_v_diff(n_v - 1, n_v - 1) /= (s_v_toe_r * s_v_toe_r); + Q_v_diff(vel_map.at("toe_leftdot"), vel_map.at("toe_leftdot")) /= + (s_v_toe_l * s_v_toe_l); + Q_v_diff(vel_map.at("toe_rightdot"), vel_map.at("toe_rightdot")) /= + (s_v_toe_r * s_v_toe_r); if (w_v_diff) { for (int i = 0; i < N - 1; i++) { auto v0 = trajopt->state(i).tail(n_v); @@ -755,19 +864,23 @@ void DoMain(double duration, double stride_length, double ground_incline, // add cost on joint position if (w_q_hip_roll) { for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(7, 2); - trajopt->AddCost(w_q_hip_roll * q.transpose() * q); + auto q1 = trajopt->state(i).segment<1>(hip_roll_left_idx); + auto q2 = trajopt->state(i).segment<1>(hip_roll_right_idx); + trajopt->AddCost(w_q_hip_yaw * q1.transpose() * q1); + trajopt->AddCost(w_q_hip_yaw * q2.transpose() * q2); } } if (w_q_hip_yaw) { for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(9, 2); - trajopt->AddCost(w_q_hip_yaw * q.transpose() * q); + auto q1 = trajopt->state(i).segment<1>(hip_yaw_left_idx); + auto q2 = trajopt->state(i).segment<1>(hip_yaw_right_idx); + trajopt->AddCost(w_q_hip_yaw * q1.transpose() * q1); + trajopt->AddCost(w_q_hip_yaw * q2.transpose() * q2); } } if (w_q_quat_xyz) { for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(1, 3); + auto q = trajopt->state(i).segment(base_qx_idx, 3); trajopt->AddCost(w_q_quat_xyz * q.transpose() * q); } } @@ -801,11 +914,11 @@ void DoMain(double duration, double stride_length, double ground_incline, // These guesses are from a good solution for (int i = 0; i < N; i++) { auto u = trajopt->input(i); - trajopt->SetInitialGuess(u(0), 20); - trajopt->SetInitialGuess(u(2), -30); - trajopt->SetInitialGuess(u(4), 30); - trajopt->SetInitialGuess(u(6), 50); - trajopt->SetInitialGuess(u(8), 20); + trajopt->SetInitialGuess(u(hip_roll_left_motor_idx), 20); + trajopt->SetInitialGuess(u(hip_yaw_left_motor_idx), -30); + trajopt->SetInitialGuess(u(hip_pitch_left_motor_idx), 30); + trajopt->SetInitialGuess(u(knee_left_motor_idx), 50); + trajopt->SetInitialGuess(u(toe_left_motor_idx), 20); } // initial guess for force (also forces at collocation) for (int i = 0; i < N; i++) { @@ -879,12 +992,13 @@ void DoMain(double duration, double stride_length, double ground_incline, // produces NAN value in some calculation. for (int i = 0; i < N; i++) { auto xi = trajopt->state(i); - if ((trajopt->GetInitialGuess(xi.head(4)).norm() == 0) || - std::isnan(trajopt->GetInitialGuess(xi.head(4)).norm())) { - trajopt->SetInitialGuess(xi(0), 1); - trajopt->SetInitialGuess(xi(1), 0); - trajopt->SetInitialGuess(xi(2), 0); - trajopt->SetInitialGuess(xi(3), 0); + if ((trajopt->GetInitialGuess(xi.segment<4>(base_qw_idx)).norm() == 0) || + std::isnan( + trajopt->GetInitialGuess(xi.segment<4>(base_qw_idx)).norm())) { + trajopt->SetInitialGuess(xi(pos_map.at("base_qw")), 1); + trajopt->SetInitialGuess(xi(pos_map.at("base_qx")), 0); + trajopt->SetInitialGuess(xi(pos_map.at("base_qy")), 0); + trajopt->SetInitialGuess(xi(pos_map.at("base_qz")), 0); } } @@ -1061,22 +1175,30 @@ void DoMain(double duration, double stride_length, double ground_incline, // add cost on joint position double cost_q_hip_roll = 0; for (int i = 0; i < N; i++) { - auto q = result.GetSolution(trajopt->state(i).segment(7, 2)); - cost_q_hip_roll += w_q_hip_roll * q.transpose() * q; + auto q1 = + result.GetSolution(trajopt->state(i).segment<1>(hip_roll_left_idx)); + auto q2 = + result.GetSolution(trajopt->state(i).segment<1>(hip_roll_right_idx)); + cost_q_hip_roll += w_q_hip_roll * q1.transpose() * q1; + cost_q_hip_roll += w_q_hip_roll * q2.transpose() * q2; } total_cost += cost_q_hip_roll; cout << "cost_q_hip_roll = " << cost_q_hip_roll << endl; double cost_q_hip_yaw = 0; for (int i = 0; i < N; i++) { - auto q = result.GetSolution(trajopt->state(i).segment(9, 2)); - cost_q_hip_yaw += w_q_hip_yaw * q.transpose() * q; + auto q1 = + result.GetSolution(trajopt->state(i).segment<1>(hip_yaw_left_idx)); + auto q2 = + result.GetSolution(trajopt->state(i).segment<1>(hip_yaw_right_idx)); + cost_q_hip_roll += w_q_hip_yaw * q1.transpose() * q1; + cost_q_hip_roll += w_q_hip_yaw * q2.transpose() * q2; } total_cost += cost_q_hip_yaw; cout << "cost_q_hip_yaw = " << cost_q_hip_yaw << endl; // add cost on quaternion double cost_q_quat_xyz = 0; for (int i = 0; i < N; i++) { - auto q = result.GetSolution(trajopt->state(i).segment(1, 3)); + auto q = result.GetSolution(trajopt->state(i).segment(base_qx_idx, 3)); cost_q_quat_xyz += w_q_quat_xyz * q.transpose() * q; } total_cost += cost_q_quat_xyz; From 298e6c36d76ddffeb37c49dc0cef98a51a322841 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 23 Jan 2022 16:35:35 -0500 Subject: [PATCH 084/758] addressing joint indexing change from drake --- bindings/pydairlib/lcm/lcm_trajectory_py.cc | 3 +- examples/Cassie/BUILD.bazel | 3 +- examples/Cassie/multibody_sim_w_platform.cc | 50 +- .../osc_jump/convert_traj_for_controller.cc | 2 +- .../osc_jump/flight_foot_traj_generator.cc | 43 +- .../osc_jump/flight_foot_traj_generator.h | 9 +- examples/Cassie/osc_jump/osc_jumping_gains.h | 9 + .../Cassie/osc_jump/osc_jumping_gains.yaml | 65 +- .../osc_jump/toe_angle_traj_generator.cc | 28 +- .../osc_jump/toe_angle_traj_generator.h | 6 +- examples/Cassie/run_dircon_jumping.cc | 1153 +++++++++-------- examples/Cassie/run_osc_jumping_controller.cc | 198 ++- examples/Cassie/visualize_trajectory.cc | 61 +- .../five_link_biped_sim.cc | 2 +- .../run_joint_space_walking_controller.cc | 25 +- lcm/dircon_saved_trajectory.cc | 166 ++- lcm/dircon_saved_trajectory.h | 70 +- solvers/nonlinear_cost.cc | 11 +- 18 files changed, 1145 insertions(+), 759 deletions(-) diff --git a/bindings/pydairlib/lcm/lcm_trajectory_py.cc b/bindings/pydairlib/lcm/lcm_trajectory_py.cc index 29e5aad034..47257cf938 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_py.cc +++ b/bindings/pydairlib/lcm/lcm_trajectory_py.cc @@ -49,8 +49,7 @@ PYBIND11_MODULE(lcm_trajectory, m) { .def("GetTrajectory", &LcmTrajectory::GetTrajectory, py::arg("trajectory_name")); py::class_(m, "DirconTrajectory") - .def(py::init()) - .def("WriteToFile", &LcmTrajectory::WriteToFile, + .def(py::init&, const std::string&>()) .def("WriteToFile", &LcmTrajectory::WriteToFile, py::arg("trajectory_name")) .def("GetMetadata", &LcmTrajectory::GetMetadata) .def("GetTrajectoryNames", &LcmTrajectory::GetTrajectoryNames) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index f716e6d31e..5449b88b63 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -364,7 +364,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/framework:lcm_driven_loop", "//systems/primitives", - "//systems/primitives:gaussian_noise_pass_through", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -457,6 +457,7 @@ cc_binary( "//solvers:optimization_utils", "//systems/primitives", "//systems/trajectory_optimization:dircon", + "//solvers:nonlinear_cost", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index ebd4a19f28..d426d23415 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -24,6 +24,7 @@ #include "drake/systems/primitives/discrete_time_delay.h" using dairlib::systems::SubvectorPassThrough; +using drake::geometry::DrakeVisualizer; using drake::geometry::SceneGraph; using drake::multibody::ContactResultsToLcmSystem; using drake::multibody::MultibodyPlant; @@ -31,7 +32,6 @@ using drake::multibody::Parser; using drake::systems::Context; using drake::systems::DiagramBuilder; using drake::systems::Simulator; -using drake::geometry::DrakeVisualizer; using drake::systems::lcm::LcmPublisherSystem; @@ -59,13 +59,18 @@ DEFINE_double(publish_rate, 2000, "Publish rate for simulator"); DEFINE_double(init_height, .7, "Initial starting height of the pelvis above " "ground"); -DEFINE_double(terrain_height, 0.0, "Height of the landing terrain"); +DEFINE_double(platform_height, 0.0, "Height of the platform"); +DEFINE_double(platform_x, 0.0, "x location of the platform"); DEFINE_double(start_time, 0.0, "Starting time of the simulator, useful for initializing the " "state at a particular configuration"); DEFINE_string(traj_name, "", "Name of the saved trajectory"); DEFINE_string(folder_path, "examples/Cassie/saved_trajectories/", "Folder path for where the trajectory names are stored"); +DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); +DEFINE_bool(visualize, true, "Set to true to visualize the platform"); +DEFINE_double(actuator_delay, 0.0, + "Duration of actuator delay. Set to 0.0 by default."); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -82,15 +87,19 @@ int do_main(int argc, char* argv[]) { } std::string urdf; - urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + if (FLAGS_spring_model) { + urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + } else { + urdf = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; + } - if (FLAGS_terrain_height != 0) { + if (FLAGS_platform_height != 0) { Parser parser(&plant, &scene_graph); std::string terrain_name = - FindResourceOrThrow("examples/impact_invaraint_control/platform.urdf"); + FindResourceOrThrow("examples/impact_invariant_control/platform.urdf"); parser.AddModelFromFile(terrain_name); Eigen::Vector3d offset; - offset << 0.15, 0, FLAGS_terrain_height; + offset << FLAGS_platform_x, 0, FLAGS_platform_height; plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform(offset)); } @@ -98,8 +107,8 @@ int do_main(int argc, char* argv[]) { plant.set_penetration_allowance(FLAGS_penetration_allowance); plant.set_stiction_tolerance(FLAGS_v_stiction); - addCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, urdf, true, - true); + addCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, urdf, + FLAGS_spring_model, true); plant.Finalize(); @@ -124,7 +133,8 @@ int do_main(int argc, char* argv[]) { plant.get_actuation_input_port().size()); auto discrete_time_delay = builder.AddSystem( - 1.0 / FLAGS_publish_rate, 0, plant.num_actuators()); + 1.0 / FLAGS_publish_rate, FLAGS_actuator_delay * FLAGS_publish_rate, + plant.num_actuators()); auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); @@ -171,7 +181,7 @@ int do_main(int argc, char* argv[]) { builder.Connect(sensor_aggregator.get_output_port(0), sensor_pub->get_input_port()); - if (FLAGS_terrain_height != 0.0) { + if (FLAGS_visualize) { DrakeVisualizer::AddToBuilder(&builder, scene_graph); } @@ -185,29 +195,15 @@ int do_main(int argc, char* argv[]) { Context& plant_context = diagram->GetMutableSubsystemContext(plant, diagram_context.get()); - MultibodyPlant plant_wo_spr(FLAGS_dt); // non-zero timestep to avoid - // Parser parser_wo_spr(&plant_wo_spr, &scene_graph); - addCassieMultibody(&plant_wo_spr, &scene_graph, FLAGS_floating_base, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", false, - true); - plant_wo_spr.Finalize(); - Eigen::MatrixXd map_no_spring_to_spring_pos = - multibody::CreateWithSpringsToWithoutSpringsMapPos(plant, plant_wo_spr); - Eigen::MatrixXd map_no_spring_to_spring_vel = - multibody::CreateWithSpringsToWithoutSpringsMapVel(plant, plant_wo_spr); - const DirconTrajectory& dircon_trajectory = - DirconTrajectory(FLAGS_folder_path + FLAGS_traj_name); + DirconTrajectory(plant, FLAGS_folder_path + FLAGS_traj_name); PiecewisePolynomial state_traj = dircon_trajectory.ReconstructStateTrajectory(); - Eigen::VectorXd x_init(nx); - Eigen::VectorXd x_init_no_spring = state_traj.value(FLAGS_start_time); - x_init << map_no_spring_to_spring_pos * x_init_no_spring.head(plant_wo_spr.num_positions()), - map_no_spring_to_spring_vel * x_init_no_spring.tail(plant_wo_spr.num_velocities()); + Eigen::VectorXd x_traj_init = state_traj.value(FLAGS_start_time); - plant.SetPositionsAndVelocities(&plant_context, x_init); + plant.SetPositionsAndVelocities(&plant_context, x_traj_init); diagram_context->SetTime(FLAGS_start_time); Simulator simulator(*diagram, std::move(diagram_context)); diff --git a/examples/Cassie/osc_jump/convert_traj_for_controller.cc b/examples/Cassie/osc_jump/convert_traj_for_controller.cc index 3a6782054f..8f8e5a6803 100644 --- a/examples/Cassie/osc_jump/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_jump/convert_traj_for_controller.cc @@ -60,7 +60,7 @@ int DoMain() { auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); auto world = &plant.world_frame(); - DirconTrajectory dircon_traj(FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory dircon_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); PiecewisePolynomial state_traj = dircon_traj.ReconstructStateTrajectory(); diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc index 56b23c4757..0893ac46dd 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc @@ -2,7 +2,6 @@ #include "multibody/multibody_utils.h" - using Eigen::Map; using Eigen::MatrixXd; using Eigen::Vector2d; @@ -28,42 +27,45 @@ namespace dairlib::examples::osc_jump { FlightFootTrajGenerator::FlightFootTrajGenerator( const MultibodyPlant& plant, Context* context, const string& hip_name, bool isLeftFoot, - const PiecewisePolynomial& foot_traj, bool relative_feet, + const PiecewisePolynomial& foot_traj, + const PiecewisePolynomial& hip_traj, + bool relative_feet, double time_offset) : plant_(plant), context_(context), world_(plant.world_frame()), hip_frame_(plant.GetFrameByName(hip_name)), foot_traj_(foot_traj), + hip_traj_(hip_traj), relative_feet_(relative_feet) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; if (isLeftFoot) { - this->set_name("l_foot_traj"); - this->DeclareAbstractOutputPort("l_foot_xyz", traj_inst, + this->set_name("left_ft_traj"); + this->DeclareAbstractOutputPort("left_ft_traj", traj_inst, &FlightFootTrajGenerator::CalcTraj); } else { - this->set_name("r_foot_traj"); - this->DeclareAbstractOutputPort("r_foot_xyz", traj_inst, + this->set_name("right_ft_traj"); + this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, &FlightFootTrajGenerator::CalcTraj); } // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); // Shift trajectory by time_offset foot_traj_.shiftRight(time_offset); + hip_traj_.shiftRight(time_offset); } -PiecewisePolynomial FlightFootTrajGenerator::generateFlightTraj( +PiecewisePolynomial FlightFootTrajGenerator::GenerateFlightTraj( const VectorXd& x, double t) const { if (relative_feet_) { plant_.SetPositionsAndVelocities(context_, x); @@ -90,6 +92,11 @@ PiecewisePolynomial FlightFootTrajGenerator::generateFlightTraj( } } +PiecewisePolynomial FlightFootTrajGenerator::GenerateRelativeTraj() +const { + return foot_traj_ - hip_traj_; +} + void FlightFootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { @@ -99,14 +106,14 @@ void FlightFootTrajGenerator::CalcTraj( VectorXd x = robot_output->GetState(); double timestamp = robot_output->get_timestamp(); - // Read in finite state machine - const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); - auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (fsm_state[0] == FLIGHT) { - *casted_traj = generateFlightTraj(robot_output->GetState(), timestamp); + if(relative_feet_){ + *casted_traj = GenerateRelativeTraj(); + } + else{ +// *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); } } diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.h b/examples/Cassie/osc_jump/flight_foot_traj_generator.h index efbe032d45..c9a68341da 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.h +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.h @@ -16,8 +16,9 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, const std::string& hip_name, bool isLeftFoot, - const drake::trajectories::PiecewisePolynomial& foot_traj, bool relative_feet = false, - double time_offset = 0.0); + const drake::trajectories::PiecewisePolynomial& foot_traj, + const drake::trajectories::PiecewisePolynomial& hip_traj, + bool relative_feet = false, double time_offset = 0.0); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -27,8 +28,9 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { } private: - drake::trajectories::PiecewisePolynomial generateFlightTraj( + drake::trajectories::PiecewisePolynomial GenerateFlightTraj( const Eigen::VectorXd& x, double t) const; + drake::trajectories::PiecewisePolynomial GenerateRelativeTraj() const; void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -39,6 +41,7 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::Frame& hip_frame_; drake::trajectories::PiecewisePolynomial foot_traj_; + drake::trajectories::PiecewisePolynomial hip_traj_; bool relative_feet_; int state_port_; diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.h b/examples/Cassie/osc_jump/osc_jumping_gains.h index d95968af1f..ba1d59ad1e 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.h +++ b/examples/Cassie/osc_jump/osc_jumping_gains.h @@ -6,6 +6,7 @@ using Eigen::MatrixXd; struct OSCJumpingGains { // costs double w_input; + double w_input_reg; double w_accel; double w_soft_constraint; double x_offset; @@ -43,10 +44,15 @@ struct OSCJumpingGains { MatrixXd W_flight_foot; MatrixXd K_p_flight_foot; MatrixXd K_d_flight_foot; + MatrixXd W_hip_yaw; + MatrixXd K_p_hip_yaw; + MatrixXd K_d_hip_yaw; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(w_input)); + a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(w_accel)); a->Visit(DRAKE_NVP(w_soft_constraint)); a->Visit(DRAKE_NVP(x_offset)); @@ -97,6 +103,9 @@ struct OSCJumpingGains { K_d_flight_foot = Eigen::Map< Eigen::Matrix>( this->FlightFootKd.data(), 3, 3); + W_hip_yaw = w_hip_yaw * MatrixXd::Identity(1, 1); + K_p_hip_yaw = hip_yaw_kp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = hip_yaw_kd * MatrixXd::Identity(1, 1); } }; \ No newline at end of file diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index ea3a790633..f4ebb654d9 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,56 +1,57 @@ -w_input: 2 -w_accel: 0.000001 -w_soft_constraint: 8000 -x_offset: 0.02 -relative_feet: false +w_input: 0.000 +w_accel: 0.0000001 +w_input_reg: 0.01 +w_soft_constraint: 100 +x_offset: 0.025 +relative_feet: true mu: 0.8 -w_swing_toe: 0.1 -swing_toe_kp: 1500 +w_swing_toe: 1 +swing_toe_kp: 2000 swing_toe_kd: 10 -w_hip_yaw: 100 +w_hip_yaw: 1 hip_yaw_kp: 40 -hip_yaw_kd: 1 +hip_yaw_kd: 5 impact_threshold: 0.050 -landing_delay: 0.00 +landing_delay: 0.050 CoMW: - [2000, 0, 0, - 0, 200, 0, - 0, 0, 2000] + [20, 0, 0, + 0, 2, 0, + 0, 0, 20] PelvisRotW: - [100, 0, 0, - 0, 100, 0, - 0, 0, 100] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] FlightFootW: - [400, 0, 0, - 0, 400, 0, - 0, 0, 400] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] CoMKp: - [ 50, 0, 0, - 0, 50, 0, - 0, 0, 200] + [50, 0, 0, + 0, 50, 0, + 0, 0, 50] CoMKd: [ 5, 0, 0, 0, 5, 0, - 0, 0, 10] + 0, 0, 5] PelvisRotKp: - [100, 0, 0, - 0, 100, 0, + [25, 0, 0, + 0, 50, 0, 0, 0, 0] PelvisRotKd: - [10, 0, 0, + [5, 0, 0, 0, 10, 0, 0, 0, 0] FlightFootKp: - [200, 0, 0, - 0, 200, 0, - 0, 0, 400] + [150, 0, 0, + 0, 100, 0, + 0, 0, 100] FlightFootKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 5] + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 0] diff --git a/examples/Cassie/osc_jump/toe_angle_traj_generator.cc b/examples/Cassie/osc_jump/toe_angle_traj_generator.cc index 7357ca74b4..78f9d21ae6 100644 --- a/examples/Cassie/osc_jump/toe_angle_traj_generator.cc +++ b/examples/Cassie/osc_jump/toe_angle_traj_generator.cc @@ -14,7 +14,8 @@ namespace dairlib::cassie::osc_jump { FlightToeAngleTrajGenerator::FlightToeAngleTrajGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, int swing_toe_idx, + drake::systems::Context* context, + PiecewisePolynomial& toe_traj, int swing_toe_idx, const std::vector&>>& feet_contact_points, @@ -22,16 +23,19 @@ FlightToeAngleTrajGenerator::FlightToeAngleTrajGenerator( : plant_(plant), context_(context), world_(plant_.world_frame()), + toe_traj_(toe_traj), swing_toe_idx_(swing_toe_idx), feet_contact_points_(feet_contact_points) { DRAKE_DEMAND(feet_contact_points_.size() == 2); + use_traj_ = !toe_traj_.empty(); // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", OutputVector(plant.num_positions(), - plant.num_velocities(), - plant.num_actuators())) - .get_index(); - fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -71,9 +75,13 @@ void FlightToeAngleTrajGenerator::CalcTraj( // Read in finite state machine auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - *casted_traj = CalcToeAngle(robot_output->GetPositions()); + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (use_traj_) { + *casted_traj = toe_traj_; + } else { + *casted_traj = CalcToeAngle(robot_output->GetPositions()); + } } } // namespace dairlib::cassie::osc_jump diff --git a/examples/Cassie/osc_jump/toe_angle_traj_generator.h b/examples/Cassie/osc_jump/toe_angle_traj_generator.h index d9447ad9ca..ab769aa420 100644 --- a/examples/Cassie/osc_jump/toe_angle_traj_generator.h +++ b/examples/Cassie/osc_jump/toe_angle_traj_generator.h @@ -14,7 +14,8 @@ class FlightToeAngleTrajGenerator : public drake::systems::LeafSystem { public: FlightToeAngleTrajGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, int swing_toe_idx, + drake::systems::Context* context, + drake::trajectories::PiecewisePolynomial& toe_traj, int swing_toe_idx, const std::vector&>>& feet_contact_points, @@ -40,6 +41,9 @@ class FlightToeAngleTrajGenerator : public drake::systems::LeafSystem { drake::systems::Context* context_; const drake::multibody::BodyFrame& world_; + drake::trajectories::PiecewisePolynomial toe_traj_; + bool use_traj_; + int swing_toe_idx_; // A list of pairs of contact body frame and contact point const std::vector< diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 916165614a..625967f547 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -2,9 +2,9 @@ #include #include -#include #include #include +#include #include #include #include @@ -13,13 +13,12 @@ #include "examples/Cassie/cassie_utils.h" #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/world_point_evaluator.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" -#include "systems/trajectory_optimization/dircon_distance_data.h" -#include "systems/trajectory_optimization/dircon_kinematic_data_set.h" -#include "systems/trajectory_optimization/dircon_opt_constraints.h" -#include "systems/trajectory_optimization/dircon_position_data.h" -#include "systems/trajectory_optimization/hybrid_dircon.h" +#include "solvers/nonlinear_cost.h" +#include "systems/trajectory_optimization/dircon/dircon.h" #include "drake/multibody/parsing/parser.h" #include "drake/solvers/solve.h" @@ -40,13 +39,23 @@ using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; +using dairlib::multibody::CreateWithSpringsToWithoutSpringsMapPos; +using dairlib::multibody::CreateWithSpringsToWithoutSpringsMapVel; +using dairlib::multibody::KinematicEvaluator; +using dairlib::multibody::KinematicEvaluatorSet; +using dairlib::solvers::NonlinearCost; +using dairlib::systems::trajectory_optimization::Dircon; using dairlib::systems::trajectory_optimization::DirconDynamicConstraint; using dairlib::systems::trajectory_optimization::DirconKinConstraintType; using dairlib::systems::trajectory_optimization::DirconKinematicConstraint; +using dairlib::systems::trajectory_optimization::DirconMode; +using dairlib::systems::trajectory_optimization::DirconModeSequence; using dairlib::systems::trajectory_optimization::DirconOptions; using dairlib::systems::trajectory_optimization::HybridDircon; -using dairlib::systems::trajectory_optimization ::PointPositionConstraint; +using dairlib::systems::trajectory_optimization::PointPositionConstraint; +using drake::VectorX; using drake::math::RotationMatrix; +using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::Body; using drake::multibody::MultibodyPlant; using drake::solvers::MathematicalProgram; @@ -67,29 +76,85 @@ DEFINE_int32(scale_option, 0, "Use 2 if seeing snopta exit 40 in log file"); DEFINE_double(tol, 1e-6, "Tolerance for constraint violation and dual gap"); DEFINE_string(load_filename, "", "File to load decision vars from."); -DEFINE_string( - data_directory, - "examples/Cassie/saved_trajectories/", - "Directory path to save decision vars to."); +DEFINE_string(data_directory, "examples/Cassie/saved_trajectories/", + "Directory path to save decision vars to."); DEFINE_string(save_filename, "default_filename", "Filename to save decision " "vars to."); DEFINE_string(traj_name, "", "File to load saved LCM trajs from."); DEFINE_bool(use_springs, false, "Whether or not to use the spring model"); +DEFINE_bool( + convert_to_springs, false, + "Whether the loaded trajectory needs to be converted to with springs"); +DEFINE_bool(ipopt, false, "Set flag to true to use ipopt instead of snopt"); +DEFINE_bool(same_knotpoints, false, + "Set flag to true if seeding with a trajectory with the same " + "number of knotpoints"); +DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); namespace dairlib { HybridDircon* createDircon(MultibodyPlant& plant); -void setKinematicConstraints(HybridDircon* trajopt, +void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant); -vector GetInitGuessForQStance(int num_knot_points, - const MultibodyPlant& plant); -vector GetInitGuessForQFlight(int num_knot_points, double apex_height, - const MultibodyPlant& plant); -vector GetInitGuessForV(const vector& q_guess, double dt, - const MultibodyPlant& plant); -MatrixXd loadSavedDecisionVars(const string& filepath); +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence*); +void AddCostsSprings(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence*); +void SetInitialGuessFromTrajectory( + Dircon& trajopt, const MultibodyPlant& plant, + const string& filepath, bool same_knot_points = false, + Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); + +class JointAccelCost : public solvers::NonlinearCost { + public: + JointAccelCost(const MatrixXd& W_Q, + const drake::multibody::MultibodyPlant& plant, + const KinematicEvaluatorSet* constraints, + const std::string& description = "") + : solvers::NonlinearCost( + plant.num_positions() + plant.num_velocities() + + plant.num_actuators() + constraints->count_full(), + description), + plant_(plant), + context_(plant_.CreateDefaultContext()), + constraints_(constraints), + n_v_(plant.num_velocities()), + n_x_(plant.num_positions() + plant.num_velocities()), + n_u_(plant.num_actuators()), + n_lambda_(constraints->count_full()), + W_Q_(W_Q){}; + + private: + void EvaluateCost(const Eigen::Ref>& x, + drake::VectorX* y) const override { + DRAKE_ASSERT(x.size() == n_x_ + n_u_ + n_lambda_); + + // Extract our input variables: + const auto x0 = x.segment(0, n_x_); + const auto u0 = x.segment(n_x_, n_u_); + VectorXd l0 = x.segment(n_x_ + n_u_, n_lambda_); + + multibody::setContext(plant_, x0, u0, context_.get()); + const VectorX xdot0 = + constraints_->CalcTimeDerivatives(*context_, &l0); + + (*y) = xdot0.tail(n_v_).transpose() * W_Q_ * xdot0.tail(n_v_); + }; + + const drake::multibody::MultibodyPlant& plant_; + std::unique_ptr> context_; + const KinematicEvaluatorSet* constraints_; + + int n_v_; + int n_x_; + int n_u_; + int n_lambda_; + + MatrixXd W_Q_; +}; void DoMain() { // Drake system initialization stuff @@ -97,244 +162,236 @@ void DoMain() { SceneGraph& scene_graph = *builder.AddSystem(); scene_graph.set_name("scene_graph"); MultibodyPlant plant(0.0); + MultibodyPlant plant_vis(0.0); + + string file_name = + "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf"; - string file_name = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; - if(FLAGS_use_springs) - file_name = "examples/Cassie/urdf/cassie_v2.urdf"; - addCassieMultibody(&plant, &scene_graph, true, - file_name, false, + if (FLAGS_use_springs) { + file_name = "examples/Cassie/urdf/cassie_v2_conservative.urdf"; + } + + addCassieMultibody(&plant, nullptr, true, file_name, FLAGS_use_springs, false); + + Parser parser_vis(&plant_vis, &scene_graph); + parser_vis.AddModelFromFile(file_name); + plant.Finalize(); + plant_vis.Finalize(); int n_q = plant.num_positions(); int n_v = plant.num_velocities(); int n_x = n_q + n_v; - std::cout << "nq: " << n_q << " n_v: " << n_v << " n_x: " << n_x << std::endl; + MatrixXd spr_map = MatrixXd::Zero(n_x, n_x); + if (FLAGS_use_springs && FLAGS_convert_to_springs) { + MultibodyPlant plant_wo_spr(0.0); + Parser parser(&plant_wo_spr); + parser.AddModelFromFile( + "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf"); + plant_wo_spr.Finalize(); + spr_map = CreateWithSpringsToWithoutSpringsMapPos(plant, plant_wo_spr); + } + // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); - std::cout << "Creating dircon object: " << std::endl; // Set up contact/distance constraints - const Body& toe_left = plant.GetBodyByName("toe_left"); - const Body& toe_right = plant.GetBodyByName("toe_right"); + auto left_toe_pair = LeftToeFront(plant); + auto left_heel_pair = LeftToeRear(plant); + auto right_toe_pair = RightToeFront(plant); + auto right_heel_pair = RightToeRear(plant); - Vector3d pt_front_contact(-0.0457, 0.112, 0); - Vector3d pt_rear_contact(0.088, 0, 0); + std::vector toe_active_inds{0, 1, 2}; + std::vector heel_active_inds{1, 2}; - bool isXZ = false; - Vector3d ground_normal(0, 0, 1); - auto left_toe_front_constraint = DirconPositionData( - plant, toe_left, pt_front_contact, isXZ, ground_normal); - auto left_toe_rear_constraint = DirconPositionData( - plant, toe_left, pt_rear_contact, isXZ, ground_normal); - auto right_toe_front_constraint = DirconPositionData( - plant, toe_right, pt_front_contact, isXZ, ground_normal); - auto right_toe_rear_constraint = DirconPositionData( - plant, toe_right, pt_rear_contact, isXZ, ground_normal); double mu = 1; - left_toe_front_constraint.addFixedNormalFrictionConstraints(mu); - left_toe_rear_constraint.addFixedNormalFrictionConstraints(mu); - right_toe_front_constraint.addFixedNormalFrictionConstraints(mu); - right_toe_rear_constraint.addFixedNormalFrictionConstraints(mu); - - const auto& thigh_left = plant.GetBodyByName("thigh_left"); - const auto& heel_spring_left = plant.GetBodyByName("heel_spring_left"); - const auto& thigh_right = plant.GetBodyByName("thigh_right"); - const auto& heel_spring_right = plant.GetBodyByName("heel_spring_right"); - double rod_length = 0.5012; // from cassie_utils - Vector3d pt_on_heel_spring = Vector3d(.11877, -.01, 0.0); - Vector3d pt_on_thigh_left = Vector3d(0.0, 0.0, 0.045); - Vector3d pt_on_thigh_right = Vector3d(0.0, 0.0, -0.045); - auto distance_constraint_left = DirconDistanceData( - plant, thigh_left, pt_on_thigh_left, heel_spring_left, pt_on_heel_spring, - rod_length); - auto distance_constraint_right = DirconDistanceData( - plant, thigh_right, pt_on_thigh_right, heel_spring_right, - pt_on_heel_spring, rod_length); - - // get rid of redundant constraint - vector skip_constraint_inds; - skip_constraint_inds.push_back(3); - skip_constraint_inds.push_back(9); - - // Double stance (all four contact points) - vector*> double_stance_constraints; - double_stance_constraints.push_back(&left_toe_front_constraint); - double_stance_constraints.push_back(&left_toe_rear_constraint); - double_stance_constraints.push_back(&right_toe_front_constraint); - double_stance_constraints.push_back(&right_toe_rear_constraint); - double_stance_constraints.push_back(&distance_constraint_left); - double_stance_constraints.push_back(&distance_constraint_right); - - auto double_stance_dataset = DirconKinematicDataSet( - plant, &double_stance_constraints, skip_constraint_inds); - auto double_stance_options = - DirconOptions(double_stance_dataset.countConstraints(), plant); - /// Be careful setting relative constraint, because we also skip constraints. - /// || lf | lr | rf | rr | fourbar - /// Before skipping || 0 1 2 | 3 4 5 | 6 7 8 | 9 10 11 | 12 13 - /// After skipping || 0 1 2 | 3 4 | 5 6 7 | 8 9 | 10 11 - // Set all the non-z toe constraints to be relative - double_stance_options.setConstraintRelative(0, true); - double_stance_options.setConstraintRelative(1, true); - double_stance_options.setConstraintRelative(3, true); - double_stance_options.setConstraintRelative(5, true); - double_stance_options.setConstraintRelative(6, true); - double_stance_options.setConstraintRelative(8, true); - - // Flight mode (no contact) - std::vector*> flight_mode_constraints; - flight_mode_constraints.push_back(&distance_constraint_left); - flight_mode_constraints.push_back(&distance_constraint_right); - auto flight_mode_dataset = - DirconKinematicDataSet(plant, &flight_mode_constraints); - auto flight_mode_options = - DirconOptions(flight_mode_dataset.countConstraints(), plant); - - // timesteps and modes setting - vector timesteps; // Number of timesteps per mode - timesteps.push_back(FLAGS_knot_points); - timesteps.push_back(FLAGS_knot_points); - timesteps.push_back(FLAGS_knot_points); - vector min_dt; // min/max duration per timestep - vector max_dt; // min_duration = knot_points * 0.01 ~= .1s - min_dt.push_back(.03); - min_dt.push_back(.03); - min_dt.push_back(.03); - max_dt.push_back(.3); - max_dt.push_back(.3); - max_dt.push_back(.3); - - // Add contact modes and contact decision - // variables to single vector for DIRCON - std::vector*> contact_mode_list; - std::vector options_list; - contact_mode_list.push_back(&double_stance_dataset); - contact_mode_list.push_back(&flight_mode_dataset); - contact_mode_list.push_back(&double_stance_dataset); - - options_list.push_back(double_stance_options); - options_list.push_back(flight_mode_options); - options_list.push_back(double_stance_options); - - auto trajopt = std::make_shared>( - plant, timesteps, min_dt, max_dt, contact_mode_list, options_list); - - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), "Print file", - "../jumping_snopt.out"); - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major iterations limit", 50000); - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Iterations limit", 50000); // QP subproblems - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), "Verify level", - 0); // 0 - trajopt->SetSolverOption( - drake::solvers::SnoptSolver::id(), "Scale option", - FLAGS_scale_option); // snopt doc said try 2 if seeing snopta exit 40 - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major optimality tolerance", - FLAGS_tol); // target nonlinear constraint violation - trajopt->SetSolverOption(drake::solvers::SnoptSolver::id(), - "Major feasibility tolerance", - FLAGS_tol); // target complementarity gap + + auto left_toe_eval = multibody::WorldPointEvaluator( + plant, left_toe_pair.first, left_toe_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), toe_active_inds); + left_toe_eval.set_frictional(); + left_toe_eval.set_mu(mu); + auto left_heel_eval = multibody::WorldPointEvaluator( + plant, left_heel_pair.first, left_heel_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), heel_active_inds); + left_heel_eval.set_frictional(); + left_heel_eval.set_mu(mu); + auto right_toe_eval = multibody::WorldPointEvaluator( + plant, right_toe_pair.first, right_toe_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), toe_active_inds); + right_toe_eval.set_frictional(); + right_toe_eval.set_mu(mu); + auto right_heel_eval = multibody::WorldPointEvaluator( + plant, right_heel_pair.first, right_heel_pair.second, + Eigen::Matrix3d::Identity(), Eigen::Vector3d::Zero(), heel_active_inds); + right_heel_eval.set_frictional(); + right_heel_eval.set_mu(mu); + + auto left_loop_eval = LeftLoopClosureEvaluator(plant); + auto right_loop_eval = RightLoopClosureEvaluator(plant); + + auto double_stance_constraints = KinematicEvaluatorSet(plant); + int left_toe_eval_ind = + double_stance_constraints.add_evaluator(&left_toe_eval); + int left_heel_eval_ind = + double_stance_constraints.add_evaluator(&left_heel_eval); + int right_toe_eval_ind = + double_stance_constraints.add_evaluator(&right_toe_eval); + int right_heel_eval_ind = + double_stance_constraints.add_evaluator(&right_heel_eval); + double_stance_constraints.add_evaluator(&left_loop_eval); + double_stance_constraints.add_evaluator(&right_loop_eval); + + auto flight_phase_constraints = KinematicEvaluatorSet(plant); + flight_phase_constraints.add_evaluator(&left_loop_eval); + flight_phase_constraints.add_evaluator(&right_loop_eval); + + int stance_knotpoints = FLAGS_knot_points; + int flight_phase_knotpoints = FLAGS_knot_points; + + /**** + * Mode duration constraints + */ + auto crouch_mode = DirconMode(double_stance_constraints, + stance_knotpoints, 0.5, 0.75); + auto flight_mode = DirconMode(flight_phase_constraints, + flight_phase_knotpoints, 0.25, 0.5); + auto land_mode = DirconMode(double_stance_constraints, + stance_knotpoints, 0.4, 0.6); + + crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); + crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); + crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 0); + crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 1); + crouch_mode.MakeConstraintRelative(right_toe_eval_ind, 0); + crouch_mode.MakeConstraintRelative(right_toe_eval_ind, 1); + crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 0); + crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 1); + + land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); + land_mode.MakeConstraintRelative(left_toe_eval_ind, 1); + land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 0); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 1); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 0); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 1); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 0); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 1); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); + + auto all_modes = DirconModeSequence(plant); + all_modes.AddMode(&crouch_mode); + all_modes.AddMode(&flight_mode); + all_modes.AddMode(&land_mode); + + auto trajopt = Dircon(all_modes); + + double tol = FLAGS_tol; + if (FLAGS_ipopt) { + // Ipopt settings adapted from CaSaDi and FROST + auto id = drake::solvers::IpoptSolver::id(); + trajopt.SetSolverOption(id, "tol", tol); + trajopt.SetSolverOption(id, "dual_inf_tol", tol); + trajopt.SetSolverOption(id, "constr_viol_tol", tol); + trajopt.SetSolverOption(id, "compl_inf_tol", tol); + trajopt.SetSolverOption(id, "max_iter", 1e5); + trajopt.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); + trajopt.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); + trajopt.SetSolverOption(id, "print_timing_statistics", "yes"); + trajopt.SetSolverOption(id, "print_level", 5); + trajopt.SetSolverOption(id, "output_file", "../ipopt.out"); + + // Set to ignore overall tolerance/dual infeasibility, but terminate when + // primal feasible and objective fails to increase over 5 iterations. + trajopt.SetSolverOption(id, "acceptable_compl_inf_tol", tol); + trajopt.SetSolverOption(id, "acceptable_constr_viol_tol", tol); + trajopt.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); + trajopt.SetSolverOption(id, "acceptable_tol", 1e2); + trajopt.SetSolverOption(id, "acceptable_iter", 5); + } else { + // Snopt settings + auto id = drake::solvers::SnoptSolver::id(); + if (FLAGS_use_springs) { + trajopt.SetSolverOption(id, "Print file", "../w_springs_snopt.out"); + } else { + trajopt.SetSolverOption(id, "Print file", "../snopt.out"); + } + trajopt.SetSolverOption(id, "Major iterations limit", 1e5); + trajopt.SetSolverOption(id, "Iterations limit", 100000); + trajopt.SetSolverOption(id, "Verify level", 0); + + // snopt doc said try 2 if seeing snopta exit 40 + trajopt.SetSolverOption(id, "Scale option", 2); + trajopt.SetSolverOption(id, "Solution", "No"); + + // target nonlinear constraint violation + trajopt.SetSolverOption(id, "Major optimality tolerance", 1e-4); + + // target complementarity gap + trajopt.SetSolverOption(id, "Major feasibility tolerance", tol); + } std::cout << "Adding kinematic constraints: " << std::endl; - setKinematicConstraints(trajopt.get(), plant); + SetKinematicConstraints(&trajopt, plant); + if (FLAGS_use_springs) { + AddCostsSprings(&trajopt, plant, &all_modes); + } else { + AddCosts(&trajopt, plant, &all_modes); + } std::cout << "Setting initial conditions: " << std::endl; vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; - int num_knot_points = trajopt->N(); + int num_knot_points = trajopt.N(); std::cout << "nq: " << n_q << endl; std::cout << "nv: " << n_v << endl; std::cout << "nu: " << plant.num_actuators() << endl; - cout << "N: " << num_knot_points; - cout << "Num decision vars: " << trajopt->decision_variables().size() << endl; - double dt = 0.1; + cout << "N: " << num_knot_points << endl; + cout << "Num decision vars: " << trajopt.decision_variables().size() << endl; if (!FLAGS_load_filename.empty()) { std::cout << "Loading: " << FLAGS_load_filename << std::endl; - MatrixXd decisionVars = - loadSavedDecisionVars(FLAGS_data_directory + FLAGS_load_filename); - trajopt->SetInitialGuessForAllVariables(decisionVars); - } else { - // Initialize all decision vars to random by default. Will be overriding - // later - trajopt->SetInitialGuessForAllVariables( - VectorXd::Random(trajopt->decision_variables().size())); - // Set the initial guess for states - - vector q_guess_stance = - GetInitGuessForQStance(num_knot_points, plant); - vector q_guess_flight = - GetInitGuessForQFlight(num_knot_points, FLAGS_height, plant); - vector v_guess_stance = - GetInitGuessForV(q_guess_stance, dt, plant); - vector v_guess_flight = - GetInitGuessForV(q_guess_flight, dt, plant); - // Set initial guess for stance - VectorXd x_guess(n_q + n_v); - for (int i = 0; i < mode_lengths[0]; ++i) { - x_guess << q_guess_stance[i], v_guess_stance[i]; - trajopt->SetInitialGuess(trajopt->state(i), x_guess); - } - // Set initial guess for flight - for (int i = 0; i < mode_lengths[1]; ++i) { - int knot_point = mode_lengths[0] - 1 + i; - x_guess << q_guess_flight[i], v_guess_flight[i]; - trajopt->SetInitialGuess(trajopt->state(knot_point), x_guess); - } - // Set initial guess for landing phase (same as stance) - for (int i = 0; i < mode_lengths[2]; ++i) { - int knot_point = mode_lengths[0] + mode_lengths[1] - 2 + i; - x_guess << q_guess_stance[i], v_guess_stance[i]; - trajopt->SetInitialGuess(trajopt->state(knot_point), x_guess); - } - } - - // To avoid NaN quaternions - for (int i = 0; i < trajopt->N(); i++) { - auto xi = trajopt->state(i); - if ((trajopt->GetInitialGuess(xi.head(4)).norm() == 0) || - std::isnan(trajopt->GetInitialGuess(xi.head(4)).norm())) { - trajopt->SetInitialGuess(xi(0), 1); - trajopt->SetInitialGuess(xi(1), 0); - trajopt->SetInitialGuess(xi(2), 0); - trajopt->SetInitialGuess(xi(3), 0); - } + SetInitialGuessFromTrajectory(trajopt, plant, + FLAGS_data_directory + FLAGS_load_filename, + FLAGS_same_knotpoints, spr_map); + // trajopt->SetInitialGuessForAllVariables(decisionVars); } double alpha = .2; int num_poses = std::min(FLAGS_knot_points, 5); - trajopt->CreateVisualizationCallback( - file_name, num_poses, alpha); + trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); cout << "\nChoose the best solver: " - << drake::solvers::ChooseBestSolver(*trajopt).name() << endl; + << drake::solvers::ChooseBestSolver(trajopt).name() << endl; cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = Solve(*trajopt, trajopt->initial_guess()); - // SolutionResult solution_result = result.get_solution_result(); + const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; cout << "Solve time:" << elapsed.count() << std::endl; std::cout << "Cost:" << result.get_optimal_cost() << std::endl; std::cout << "Solve result: " << result.get_solution_result() << std::endl; + std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) + << std::endl; + // Save trajectory to file - DirconTrajectory saved_traj(plant, *trajopt, result, "jumping_trajectory", + DirconTrajectory saved_traj(plant, trajopt, result, "jumping_trajectory", "Decision variables and state/input trajectories " "for jumping"); saved_traj.WriteToFile(FLAGS_data_directory + FLAGS_save_filename); std::cout << "Wrote to file: " << FLAGS_data_directory + FLAGS_save_filename << std::endl; drake::trajectories::PiecewisePolynomial optimal_traj = - trajopt->ReconstructStateTrajectory(result); - multibody::connectTrajectoryVisualizer(&plant, &builder, &scene_graph, + trajopt.ReconstructStateTrajectory(result); + multibody::connectTrajectoryVisualizer(&plant_vis, &builder, &scene_graph, optimal_traj); auto diagram = builder.Build(); @@ -347,17 +404,13 @@ void DoMain() { } } -void setKinematicConstraints(HybridDircon* trajopt, +void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant) { // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); - for (const auto& pair : pos_map) { - std::cout << pair.first << ": " << pair.second << std::endl; - } - int n_q = plant.num_positions(); int n_v = plant.num_velocities(); int n_u = plant.num_actuators(); @@ -366,63 +419,65 @@ void setKinematicConstraints(HybridDircon* trajopt, int N = trajopt->N(); std::vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; - auto x0 = trajopt->initial_state(); + auto x_0 = trajopt->initial_state(); auto x_top = trajopt->state(N / 2); - auto xf = trajopt->final_state(); + auto x_f = trajopt->final_state(); auto u = trajopt->input(); - auto u0 = trajopt->input(0); - auto uf = trajopt->input(N - 1); + auto u_0 = trajopt->input(0); + auto u_f = trajopt->input(N - 1); auto x = trajopt->state(); // Duration Bounds - double min_duration = (FLAGS_duration > 0.0) ? FLAGS_duration : 1.0; - double max_duration = (FLAGS_duration > 0.0) ? FLAGS_duration : 1.5; - - trajopt->AddDurationBounds(min_duration, max_duration); // Standing constraints double rest_height = FLAGS_start_height; double eps = 1e-6; + double midpoint = 0.045; + // position constraints - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("base_x"))); - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("base_y"))); - trajopt->AddBoundingBoxConstraint(0, 0, xf(pos_map.at("base_y"))); + trajopt->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, + x_0(pos_map.at("base_x"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); // initial fb orientation constraint VectorXd quat_identity(4); quat_identity << 1, 0, 0, 0; - trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x0.head(4)); - trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, xf.head(4)); + trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x_0.head(4)); + trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x_f.head(4)); // hip yaw and roll constraints - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("hip_yaw_left"))); - trajopt->AddBoundingBoxConstraint(0, 0, x0(pos_map.at("hip_yaw_right"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); - trajopt->AddBoundingBoxConstraint(0.05, 0.2, x0(pos_map.at("hip_roll_left"))); - trajopt->AddBoundingBoxConstraint(-0.2, -0.05, x0(pos_map.at("hip_roll_right"))); + trajopt->AddBoundingBoxConstraint(0.00, 0.1, + x_0(pos_map.at("hip_roll_left"))); + trajopt->AddBoundingBoxConstraint(-0.1, -0.00, + x_0(pos_map.at("hip_roll_right"))); // hip yaw and roll constraints - trajopt->AddBoundingBoxConstraint(0, 0, xf(pos_map.at("hip_yaw_left"))); - trajopt->AddBoundingBoxConstraint(0, 0, xf(pos_map.at("hip_yaw_right"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); + trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_right"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, x0(pos_map.at("toe_left"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, x0(pos_map.at("toe_right"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, xf(pos_map.at("toe_left"))); - trajopt->AddBoundingBoxConstraint(-1.9, -1.8, xf(pos_map.at("toe_right"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_left"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_right"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_left"))); + trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_right"))); // Jumping height constraints trajopt->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, - x0(pos_map.at("base_z"))); - trajopt->AddBoundingBoxConstraint(FLAGS_height + rest_height - eps, + x_0(pos_map.at("base_z"))); + trajopt->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, FLAGS_height + rest_height + eps, x_top(pos_map.at("base_z"))); - trajopt->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, - xf(pos_map.at("base_z"))); + trajopt->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, + 0.8 * FLAGS_height + rest_height + eps, + x_f(pos_map.at("base_z"))); // Zero starting and final velocities - trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x0.tail(n_v)); - trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == xf.tail(n_v)); + trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); + trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x_f.tail(n_v)); // create joint/motor names vector> l_r_pairs{ @@ -433,6 +488,10 @@ void setKinematicConstraints(HybridDircon* trajopt, "hip_roll", "hip_yaw", }; + vector spring_joint_names{ + "knee_joint", + "ankle_spring_joint", + }; vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; @@ -447,32 +506,37 @@ void setKinematicConstraints(HybridDircon* trajopt, motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); } } + if (FLAGS_use_springs) { + for (const auto& spring_joint_name : spring_joint_names) { + joint_names.push_back(spring_joint_name + l_r_pair.first); + } + } } - l_r_pairs.pop_back(); // Symmetry constraints for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { + trajopt->AddConstraintToAllKnotPoints( + x_0(pos_map[sym_joint_name + l_r_pair.first]) == + x_0(pos_map[sym_joint_name + l_r_pair.second])); trajopt->AddLinearConstraint( - x0(pos_map[sym_joint_name + l_r_pair.first]) == - x0(pos_map[sym_joint_name + l_r_pair.second])); - trajopt->AddLinearConstraint( - xf(pos_map[sym_joint_name + l_r_pair.first]) == - xf(pos_map[sym_joint_name + l_r_pair.second])); + x_f(pos_map[sym_joint_name + l_r_pair.first]) == + x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle - trajopt->AddLinearConstraint( - u0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - u0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); - trajopt->AddLinearConstraint( - uf(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - uf(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + trajopt->AddConstraintToAllKnotPoints( + u_0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == + u_0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + trajopt->AddConstraintToAllKnotPoints( + u_f(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == + u_f(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); } } } // joint limits std::cout << "Joint limit constraints: " << std::endl; + for (const auto& member : joint_names) { trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) <= @@ -486,21 +550,24 @@ void setKinematicConstraints(HybridDircon* trajopt, std::cout << "Actuator limit constraints: " << std::endl; for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); - trajopt->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -300), - VectorXd::Constant(n_u, +300), ui); + trajopt->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), + VectorXd::Constant(n_u, +175), ui); } + Vector3d pt_front_contact(-0.0457, 0.112, 0); + Vector3d pt_rear_contact(0.088, 0, 0); + // toe position constraint in y direction (avoid leg crossing) // tighter constraint than before auto left_foot_y_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - 0.2 * VectorXd::Ones(1), 0.25 * VectorXd::Ones(1)); + 0.1 * VectorXd::Ones(1), 0.15 * VectorXd::Ones(1)); auto right_foot_y_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - -0.25 * VectorXd::Ones(1), -0.2 * VectorXd::Ones(1)); - for (int mode = 2; mode < 3; ++mode) { + -0.15 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + for (int mode : {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); @@ -508,329 +575,357 @@ void setKinematicConstraints(HybridDircon* trajopt, trajopt->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); } } + + // Jumping distance constraint for platform clearance + auto left_foot_x_start_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + (0 - eps) * VectorXd::Ones(1), (0 + eps) * VectorXd::Ones(1)); + auto right_foot_x_start_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + (0 - eps) * VectorXd::Ones(1), (0 + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_x_start_constraint, x_0.head(n_q)); + trajopt->AddConstraint(right_foot_x_start_constraint, x_0.head(n_q)); + + // Jumping distance constraint for platform clearance + auto left_foot_x_platform_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), + 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); + auto right_foot_x_platform_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), + 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); + trajopt->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); + // Jumping distance constraint auto left_foot_x_constraint = std::make_shared>( - plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), + plant, "toe_left", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), (FLAGS_distance - eps) * VectorXd::Ones(1), (FLAGS_distance + eps) * VectorXd::Ones(1)); auto right_foot_x_constraint = std::make_shared>( - plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), + plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), (FLAGS_distance - eps) * VectorXd::Ones(1), (FLAGS_distance + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_x_constraint, xf.head(n_q)); - trajopt->AddConstraint(right_foot_x_constraint, xf.head(n_q)); + trajopt->AddConstraint(left_foot_x_constraint, x_f.head(n_q)); + trajopt->AddConstraint(right_foot_x_constraint, x_f.head(n_q)); // Foot clearance constraint auto left_foot_z_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.75 * FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), + (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); auto right_foot_z_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.75 * FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), + (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); trajopt->AddConstraint(left_foot_z_constraint, x_top.head(n_q)); trajopt->AddConstraint(right_foot_z_constraint, x_top.head(n_q)); + auto left_foot_rear_z_final_constraint = + std::make_shared>( + plant, "toe_left", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + auto right_foot_rear_z_final_constraint = + std::make_shared>( + plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_rear_z_final_constraint, x_f.head(n_q)); + trajopt->AddConstraint(right_foot_rear_z_final_constraint, x_f.head(n_q)); + + auto left_foot_front_z_final_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + auto right_foot_front_z_final_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), + (FLAGS_height - eps) * VectorXd::Ones(1), + (FLAGS_height + eps) * VectorXd::Ones(1)); + trajopt->AddConstraint(left_foot_front_z_final_constraint, x_f.head(n_q)); + trajopt->AddConstraint(right_foot_front_z_final_constraint, x_f.head(n_q)); + // Only add constraints of lambdas for stance modes - vector stance_modes{0, 2}; // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - for (int index = 0; index < (mode_lengths[0] - 1); index++) { - auto lambda = trajopt->force(0, index); - trajopt->AddLinearConstraint(lambda(2) >= 15); - trajopt->AddLinearConstraint(lambda(5) >= 15); - trajopt->AddLinearConstraint(lambda(8) >= 15); - trajopt->AddLinearConstraint(lambda(11) >= 15); + for (int index = 0; index < (mode_lengths[0] - 2); index++) { + auto lambda = trajopt->force_vars(0, index); + trajopt->AddLinearConstraint(lambda(2) >= 60); + trajopt->AddLinearConstraint(lambda(5) >= 60); + trajopt->AddLinearConstraint(lambda(8) >= 60); + trajopt->AddLinearConstraint(lambda(11) >= 60); } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { - auto lambda = trajopt->force(2, index); - trajopt->AddLinearConstraint(lambda(2) <= 300); - trajopt->AddLinearConstraint(lambda(5) <= 300); - trajopt->AddLinearConstraint(lambda(8) <= 300); - trajopt->AddLinearConstraint(lambda(11) <= 300); + auto lambda = trajopt->force_vars(2, index); + trajopt->AddLinearConstraint(lambda(2) <= 350); + trajopt->AddLinearConstraint(lambda(5) <= 350); + trajopt->AddLinearConstraint(lambda(8) <= 350); + trajopt->AddLinearConstraint(lambda(11) <= 350); + trajopt->AddLinearConstraint(lambda(2) >= 50); + trajopt->AddLinearConstraint(lambda(5) >= 50); + trajopt->AddLinearConstraint(lambda(8) >= 50); + trajopt->AddLinearConstraint(lambda(11) >= 50); } + // Limit the ground impulses when landing + auto Lambda = trajopt->impulse_vars(1); + trajopt->AddLinearConstraint(Lambda(2) <= 2); + trajopt->AddLinearConstraint(Lambda(5) <= 2); + trajopt->AddLinearConstraint(Lambda(8) <= 2); + trajopt->AddLinearConstraint(Lambda(11) <= 2); +} - MatrixXd Q = 0.1 * MatrixXd::Identity(n_v, n_v); - MatrixXd R = 0.005 * MatrixXd::Identity(n_u, n_u); - Q(0, 0) = 5; - Q(1, 1) = 5; - Q(2, 2) = 5; - trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); - trajopt->AddRunningCost(u.transpose() * R * u); +/****** +COSTS +******/ +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence* constraints) { + auto x = trajopt->state(); + auto u = trajopt->input(); - // Add some cost to hip roll and yaw - double w_q_hip_roll = 0.3; - double w_q_hip_yaw = 0.3; - double w_q_hip_pitch = 0.0; - double w_q_quat_xyz = 0.0; - if (w_q_hip_roll) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(7, 2); - trajopt->AddCost(w_q_hip_roll * q.transpose() * q); + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + + int n_v = plant.num_velocities(); + int n_u = plant.num_actuators(); + + // create joint/motor names + vector> l_r_pairs{ + std::pair("_left", "_right"), + std::pair("_right", "_left"), + }; + vector asy_joint_names{ + "hip_roll", + "hip_yaw", + }; + vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; + vector joint_names{}; + vector motor_names{}; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + joint_names.push_back(asy_joint_name + l_r_pair.first); + motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); + } + for (const auto& sym_joint_name : sym_joint_names) { + joint_names.push_back(sym_joint_name + l_r_pair.first); + if (sym_joint_name != "ankle_joint") { + motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); + } } } - if (w_q_hip_yaw) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(9, 2); - trajopt->AddCost(w_q_hip_yaw * q.transpose() * q); + l_r_pairs.pop_back(); + + double w_symmetry_pos = FLAGS_cost_scaling * 1e5; + double w_symmetry_vel = FLAGS_cost_scaling * 1e2; + double w_symmetry_u = FLAGS_cost_scaling * 1e2; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { + auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - + x(pos_map.at(sym_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - + x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (sym_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + } } } - if (w_q_hip_pitch) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(11, 2); - trajopt->AddCost(w_q_hip_pitch * q.transpose() * q); + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + + x(pos_map.at(asy_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + + x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (asy_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + } } } - if (w_q_quat_xyz) { - for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(1, 3); - trajopt->AddCost(w_q_quat_xyz * q.transpose() * q); + + MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); + MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = + 5e-1; + R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) = + 5e-1; + R(act_map.at("hip_yaw_left_motor"), act_map.at("hip_yaw_left_motor")) = 5e-1; + R(act_map.at("hip_yaw_right_motor"), act_map.at("hip_yaw_right_motor")) = + 5e-1; + R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) = + 5e-5; + R(act_map.at("hip_pitch_right_motor"), act_map.at("hip_pitch_right_motor")) = + 5e-5; + + Q *= FLAGS_cost_scaling; + R *= FLAGS_cost_scaling; + trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + trajopt->AddRunningCost(u.transpose() * R * u); + + vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, + FLAGS_knot_points}; + MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; + W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; + W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; + W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + W *= 2.0 * FLAGS_cost_scaling; + vector> joint_accel_costs; + for (int mode : {0, 1, 2}) { + joint_accel_costs.push_back(std::make_shared( + W, plant, &constraints->mode(mode).evaluators())); + for (int index = 0; index < mode_lengths[mode]; index++) { + // Assumes mode_lengths are the same across modes + auto x_i = trajopt->state_vars(mode, index); + auto u_i = trajopt->input_vars(mode, index); + auto l_i = trajopt->force_vars(mode, index); + trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } } } -vector GetInitGuessForQStance(int num_knot_points, - const MultibodyPlant& plant) { - int n_q = plant.num_positions(); +/****** +COSTS +******/ +void AddCostsSprings(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence* constraints) { + auto x = trajopt->state(); + auto u = trajopt->input(); + + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + int n_v = plant.num_velocities(); - int n_x = n_q + n_v; - map positions_map = multibody::makeNameToPositionsMap(plant); - - vector q_init_guess; - VectorXd q_ik_guess = VectorXd::Zero(n_q); - Eigen::Vector4d quat(2000.06, -0.339462, -0.609533, -0.760854); - q_ik_guess << quat.normalized(), 0.000889849, 0.000626865, 1.0009, -0.0112109, - 0.00927845, -0.000600725, -0.000895805, 1.15086, 0.610808, -1.38608, - -1.35926, 0.806192, 1.00716, -M_PI / 2, -M_PI / 2; - - for (int i = 0; i < num_knot_points; i++) { - double eps = 1e-3; - Vector3d eps_vec = eps * VectorXd::Ones(3); - Vector3d pelvis_pos( - 0.0, 0.0, - FLAGS_start_height + 0.01 * (i - num_knot_points / 2) * (i - num_knot_points / 2)); - Vector3d left_toe_pos(0.0, 0.12, 0.05); - Vector3d right_toe_pos(0.0, -0.12, 0.05); - - const auto& world_frame = plant.world_frame(); - const auto& pelvis_frame = plant.GetFrameByName("pelvis"); - const auto& toe_left_frame = plant.GetFrameByName("toe_left"); - const auto& toe_right_frame = plant.GetFrameByName("toe_right"); - - drake::multibody::InverseKinematics ik(plant); - ik.AddPositionConstraint(pelvis_frame, Vector3d(0, 0, 0), world_frame, - pelvis_pos - eps * VectorXd::Ones(3), - pelvis_pos + eps * VectorXd::Ones(3)); - ik.AddOrientationConstraint(pelvis_frame, RotationMatrix(), - world_frame, RotationMatrix(), eps); - ik.AddPositionConstraint(toe_left_frame, Vector3d(0, 0, 0), world_frame, - left_toe_pos - eps_vec, left_toe_pos + eps_vec); - ik.AddPositionConstraint(toe_right_frame, Vector3d(0, 0, 0), world_frame, - right_toe_pos - eps_vec, right_toe_pos + eps_vec); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_left")) == 0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_right")) == 0); - // Four bar linkage constraint (without spring) - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_left")) + - (ik.q())(positions_map.at("ankle_joint_left")) == - M_PI * 13 / 180.0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_right")) + - (ik.q())(positions_map.at("ankle_joint_right")) == - M_PI * 13 / 180.0); - ik.get_mutable_prog()->SetInitialGuess(ik.q(), q_ik_guess); - const auto result = Solve(ik.prog()); - const auto q_sol = result.GetSolution(ik.q()); - // cout << " q_sol = " << q_sol.transpose() << endl; - // cout << " q_sol.head(4).norm() = " << q_sol.head(4).norm() << endl; - VectorXd q_sol_normd(n_q); - q_sol_normd << q_sol.head(4).normalized(), q_sol.tail(n_q - 4); - q_ik_guess = q_sol_normd; - q_init_guess.push_back(q_sol_normd); - - bool visualize_init_traj = false; - if (visualize_init_traj) { - // Build temporary diagram for visualization - drake::systems::DiagramBuilder builder_ik; - SceneGraph& scene_graph_ik = *builder_ik.AddSystem(); - scene_graph_ik.set_name("scene_graph_ik"); - MultibodyPlant plant_ik(1e-4); - multibody::addFlatTerrain(&plant_ik, &scene_graph_ik, .8, .8); - Parser parser(&plant_ik, &scene_graph_ik); - string full_name = - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); - plant_ik.mutable_gravity_field().set_gravity_vector( - -9.81 * Eigen::Vector3d::UnitZ()); - plant_ik.Finalize(); - - // Visualize - VectorXd x_const = VectorXd::Zero(n_x); - x_const.head(n_q) = q_sol; - PiecewisePolynomial pp_xtraj(x_const); - - multibody::connectTrajectoryVisualizer(&plant_ik, &builder_ik, - &scene_graph_ik, pp_xtraj); - auto diagram = builder_ik.Build(); - drake::systems::Simulator simulator(*diagram); - simulator.set_target_realtime_rate(.1); - simulator.Initialize(); - simulator.AdvanceTo(1.0 / num_knot_points); + int n_u = plant.num_actuators(); + + // create joint/motor names + vector> l_r_pairs{ + std::pair("_left", "_right"), + std::pair("_right", "_left"), + }; + vector asy_joint_names{ + "hip_roll", + "hip_yaw", + }; + vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; + vector joint_names{}; + vector motor_names{}; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + joint_names.push_back(asy_joint_name + l_r_pair.first); + motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); + } + for (const auto& sym_joint_name : sym_joint_names) { + joint_names.push_back(sym_joint_name + l_r_pair.first); + if (sym_joint_name != "ankle_joint") { + motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); + } } } + l_r_pairs.pop_back(); - return q_init_guess; -} - -vector GetInitGuessForQFlight(int num_knot_points, double apex_height, - const MultibodyPlant& plant) { - int n_q = plant.num_positions(); - int n_v = plant.num_velocities(); - int n_x = n_q + n_v; - map positions_map = multibody::makeNameToPositionsMap(plant); - - vector q_init_guess; - VectorXd q_ik_guess = VectorXd::Zero(n_q); - Eigen::Vector4d quat(2000.06, -0.339462, -0.609533, -0.760854); - q_ik_guess << quat.normalized(), 0.000889849, 0.000626865, 1.0009, -0.0112109, - 0.00927845, -0.000600725, -0.000895805, 1.15086, 0.610808, -1.38608, - -1.35926, 0.806192, 1.00716, -M_PI / 2, -M_PI / 2; - - double factor = apex_height / (num_knot_points * num_knot_points / 4.0); - double rest_height = 1.0; - - for (int i = 0; i < num_knot_points; i++) { - double eps = 1e-3; - Vector3d eps_vec = eps * VectorXd::Ones(3); - double height_offset = apex_height - factor * (i - num_knot_points / 2.0) * - (i - num_knot_points / 2.0); - Vector3d pelvis_pos(0.0, 0.0, rest_height + height_offset); - // Do not raise the toes as much as the pelvis, (leg extension) - Vector3d left_toe_pos(0.0, 0.12, 0.05 + height_offset * 0.5); - Vector3d right_toe_pos(0.0, -0.12, 0.05 + height_offset * 0.5); - - const auto& world_frame = plant.world_frame(); - const auto& pelvis_frame = plant.GetFrameByName("pelvis"); - const auto& toe_left_frame = plant.GetFrameByName("toe_left"); - const auto& toe_right_frame = plant.GetFrameByName("toe_right"); - - drake::multibody::InverseKinematics ik(plant); - ik.AddPositionConstraint(pelvis_frame, Vector3d(0, 0, 0), world_frame, - pelvis_pos - eps * VectorXd::Ones(3), - pelvis_pos + eps * VectorXd::Ones(3)); - ik.AddOrientationConstraint(pelvis_frame, RotationMatrix(), - world_frame, RotationMatrix(), eps); - ik.AddPositionConstraint(toe_left_frame, Vector3d(0, 0, 0), world_frame, - left_toe_pos - eps_vec, left_toe_pos + eps_vec); - ik.AddPositionConstraint(toe_right_frame, Vector3d(0, 0, 0), world_frame, - right_toe_pos - eps_vec, right_toe_pos + eps_vec); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_left")) == 0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("hip_yaw_right")) == 0); - // Four bar linkage constraint (without spring) - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_left")) + - (ik.q())(positions_map.at("ankle_joint_left")) == - M_PI * 13 / 180.0); - ik.get_mutable_prog()->AddLinearConstraint( - (ik.q())(positions_map.at("knee_right")) + - (ik.q())(positions_map.at("ankle_joint_right")) == - M_PI * 13 / 180.0); - - ik.get_mutable_prog()->SetInitialGuess(ik.q(), q_ik_guess); - const auto result = Solve(ik.prog()); - const auto q_sol = result.GetSolution(ik.q()); - // cout << " q_sol = " << q_sol.transpose() << endl; - // cout << " q_sol.head(4).norm() = " << q_sol.head(4).norm() << endl; - VectorXd q_sol_normd(n_q); - q_sol_normd << q_sol.head(4).normalized(), q_sol.tail(n_q - 4); - q_ik_guess = q_sol_normd; - q_init_guess.push_back(q_sol_normd); - - bool visualize_init_traj = false; - if (visualize_init_traj) { - // Build temporary diagram for visualization - drake::systems::DiagramBuilder builder_ik; - SceneGraph& scene_graph_ik = *builder_ik.AddSystem(); - scene_graph_ik.set_name("scene_graph_ik"); - MultibodyPlant plant_ik(1e-4); - multibody::addFlatTerrain(&plant_ik, &scene_graph_ik, .8, .8); - Parser parser(&plant_ik, &scene_graph_ik); - string full_name = - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); - plant_ik.mutable_gravity_field().set_gravity_vector( - -9.81 * Eigen::Vector3d::UnitZ()); - plant_ik.Finalize(); - - // Visualize - VectorXd x_const = VectorXd::Zero(n_x); - x_const.head(n_q) = q_sol; - PiecewisePolynomial pp_xtraj(x_const); - - multibody::connectTrajectoryVisualizer(&plant_ik, &builder_ik, - &scene_graph_ik, pp_xtraj); - auto diagram = builder_ik.Build(); - drake::systems::Simulator simulator(*diagram); - simulator.set_target_realtime_rate(.1); - simulator.Initialize(); - simulator.AdvanceTo(1.0 / num_knot_points); + double w_symmetry_pos = 1e3; + double w_symmetry_vel = 1e1; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { + auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - + x(pos_map[sym_joint_name + l_r_pair.second]); + auto vel_diff = x(vel_map[sym_joint_name + l_r_pair.first + "dot"]) - + x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); } } - return q_init_guess; -} + std::cout << "n_v_: " << n_v << std::endl; + MatrixXd Q = 0.01 * MatrixXd::Identity(n_v, n_v); + MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + Q *= FLAGS_cost_scaling; + R *= FLAGS_cost_scaling; -// Get v by finite differencing q -vector GetInitGuessForV(const vector& q_guess, double dt, - const MultibodyPlant& plant) { - bool standing = false; - if (!standing) { - vector qdot_guess; - qdot_guess.push_back((q_guess[1] - q_guess[0]) / dt); - for (unsigned int i = 1; i < q_guess.size() - 1; i++) { - VectorXd v_plus = (q_guess[i + 1] - q_guess[i]) / dt; - VectorXd v_minus = (q_guess[i] - q_guess[i - 1]) / dt; - qdot_guess.push_back((v_plus + v_minus) / 2); - } - qdot_guess.push_back((q_guess.back() - q_guess[q_guess.size() - 2]) / dt); - - // Convert qdot to v - DRAKE_ASSERT(qdot_guess.size() == q_guess.size()); - vector v_seed; - for (unsigned int i = 0; i < q_guess.size(); i++) { - auto context = plant.CreateDefaultContext(); - plant.SetPositions(context.get(), q_guess[i]); - VectorXd v(plant.num_velocities()); - plant.MapQDotToVelocity(*context, qdot_guess[i], &v); - v_seed.push_back(v); - } - return v_seed; - } else { - vector v_seed; - for (unsigned int i = 0; i < q_guess.size(); ++i) { - VectorXd zeros = VectorXd::Zero(plant.num_velocities()); + trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + trajopt->AddRunningCost(u.transpose() * R * u); - v_seed.push_back(zeros); + vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, + FLAGS_knot_points}; + MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) *= 1e1; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) *= 1e1; + W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) *= 1e1; + W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) *= 1e1; + // Add no costs on spring acceleration because we can't control for that + W(vel_map["knee_joint_leftdot"], vel_map["knee_joint_leftdot"]) = 0.0; + W(vel_map["knee_joint_rightdot"], vel_map["knee_joint_rightdot"]) = 0.0; + W(vel_map["ankle_spring_joint_leftdot"], + vel_map["ankle_spring_joint_leftdot"]) = 0.0; + W(vel_map["ankle_spring_joint_rightdot"], + vel_map["ankle_spring_joint_rightdot"]) = 0.0; + W *= FLAGS_cost_scaling; + vector> joint_accel_costs; + for (int mode : {0, 1, 2}) { + joint_accel_costs.push_back(std::make_shared( + W, plant, &constraints->mode(mode).evaluators())); + for (int index = 0; index < mode_lengths[mode]; index++) { + // Assumes mode_lengths are the same across modes + auto x_i = trajopt->state_vars(mode, index); + auto u_i = trajopt->input_vars(mode, index); + auto l_i = trajopt->force_vars(mode, index); + trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } - return v_seed; } } -MatrixXd loadSavedDecisionVars(const string& filepath) { - DirconTrajectory loaded_decision_vars = DirconTrajectory(filepath); - for (auto& name : loaded_decision_vars.GetTrajectoryNames()) { - std::cout << name << std::endl; +void SetInitialGuessFromTrajectory(Dircon& trajopt, + const MultibodyPlant& plant, + const string& filepath, + bool same_knot_points, + Eigen::MatrixXd spr_map) { + DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); + if (same_knot_points) { + trajopt.SetInitialGuessForAllVariables( + previous_traj.GetDecisionVariables()); + return; + } + PiecewisePolynomial state_traj; + if (FLAGS_use_springs && FLAGS_convert_to_springs) { + std::cout << "Using spring conversion" << std::endl; + state_traj = previous_traj.ReconstructStateTrajectoryWithSprings(spr_map); + } else { + state_traj = previous_traj.ReconstructStateTrajectory(); + } + auto input_traj = previous_traj.ReconstructInputTrajectory(); + auto lambda_traj = previous_traj.ReconstructLambdaTrajectory(); + auto lambda_c_traj = previous_traj.ReconstructLambdaCTrajectory(); + auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); + + trajopt.SetInitialTrajectory(input_traj, state_traj); + for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], + lambda_c_traj[mode], gamma_traj[mode]); } - return loaded_decision_vars.GetDecisionVariables(); } } // namespace dairlib @@ -838,4 +933,4 @@ MatrixXd loadSavedDecisionVars(const string& filepath) { int main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); dairlib::DoMain(); -} \ No newline at end of file +} diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index c50c2d9584..973d5dd500 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -1,9 +1,9 @@ + #include #include #include #include #include -#include #include #include "dairlib/lcmt_robot_input.hpp" @@ -21,10 +21,12 @@ #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/osc_tracking_data.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" namespace dairlib { @@ -44,9 +46,9 @@ using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using examples::osc_jump::FlightFootTrajGenerator; @@ -54,6 +56,7 @@ using examples::osc_jump::JumpingEventFsm; using examples::osc_jump::PelvisTransTrajGenerator; using multibody::FixedJointEvaluator; using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; @@ -76,8 +79,7 @@ DEFINE_string(simulator, "DRAKE", "contact information. Other options include MUJOCO and soon to " "include contact results from the GM contact estimator."); DEFINE_int32(init_fsm_state, osc_jump::BALANCE, "Initial state of the FSM"); -DEFINE_string(folder_path, - "examples/impact_invariant_control/saved_trajectories/", +DEFINE_string(folder_path, "examples/Cassie/saved_trajectories/", "Folder path for where the trajectory names are stored"); DEFINE_string(traj_name, "jumping_0.15h_0.3d", "File to load saved trajectories from"); @@ -93,7 +95,7 @@ int DoMain(int argc, char* argv[]) { // Built the Cassie MBPs drake::multibody::MultibodyPlant plant_w_spr(0.0); addCassieMultibody(&plant_w_spr, nullptr, true, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); plant_w_spr.Finalize(); @@ -119,8 +121,8 @@ int DoMain(int argc, char* argv[]) { auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); /**** Get trajectory from optimization ****/ - const DirconTrajectory& dircon_trajectory = DirconTrajectory( - FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); + const DirconTrajectory& dircon_trajectory = DirconTrajectory(plant_w_spr, + FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; if (gains.relative_feet) { output_traj_path += "_rel"; @@ -134,21 +136,37 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial pelvis_trans_traj; PiecewisePolynomial l_foot_trajectory; PiecewisePolynomial r_foot_trajectory; + PiecewisePolynomial l_hip_trajectory; + PiecewisePolynomial r_hip_trajectory; + PiecewisePolynomial l_toe_trajectory; + PiecewisePolynomial r_toe_trajectory; PiecewisePolynomial pelvis_rot_trajectory; for (int mode = 0; mode < dircon_trajectory.GetNumModes(); ++mode) { const LcmTrajectory::Trajectory lcm_pelvis_trans_trajectory = output_trajs.GetTrajectory("pelvis_trans_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_foot_traj = output_trajs.GetTrajectory("left_foot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_foot_traj = output_trajs.GetTrajectory("right_foot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_left_hip_traj = + output_trajs.GetTrajectory("left_hip_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_right_hip_traj = + output_trajs.GetTrajectory("right_hip_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_left_toe_traj = + output_trajs.GetTrajectory("left_toe_trajectory" + + std::to_string(mode)); + const LcmTrajectory::Trajectory lcm_right_toe_traj = + output_trajs.GetTrajectory("right_toe_trajectory" + + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_pelvis_rot_traj = output_trajs.GetTrajectory("pelvis_rot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); pelvis_trans_traj.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_pelvis_trans_trajectory.time_vector, @@ -157,13 +175,33 @@ int DoMain(int argc, char* argv[]) { l_foot_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_left_foot_traj.time_vector, - lcm_left_foot_traj.datapoints.topRows(3), - lcm_left_foot_traj.datapoints.bottomRows(3))); + lcm_left_foot_traj.datapoints.topRows(6), + lcm_left_foot_traj.datapoints.bottomRows(6))); r_foot_trajectory.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_right_foot_traj.time_vector, - lcm_right_foot_traj.datapoints.topRows(3), - lcm_right_foot_traj.datapoints.bottomRows(3))); + lcm_right_foot_traj.datapoints.topRows(6), + lcm_right_foot_traj.datapoints.bottomRows(6))); + l_hip_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_left_hip_traj.time_vector, + lcm_left_hip_traj.datapoints.topRows(6), + lcm_left_hip_traj.datapoints.bottomRows(6))); + r_hip_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_right_hip_traj.time_vector, + lcm_right_hip_traj.datapoints.topRows(6), + lcm_right_hip_traj.datapoints.bottomRows(6))); + l_toe_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_left_toe_traj.time_vector, + lcm_left_toe_traj.datapoints.topRows(1), + lcm_left_toe_traj.datapoints.bottomRows(1))); + r_toe_trajectory.ConcatenateInTime( + PiecewisePolynomial::CubicHermite( + lcm_right_toe_traj.time_vector, + lcm_right_toe_traj.datapoints.topRows(1), + lcm_right_toe_traj.datapoints.bottomRows(1))); pelvis_rot_trajectory.ConcatenateInTime( PiecewisePolynomial::FirstOrderHold( lcm_pelvis_rot_traj.time_vector, @@ -174,7 +212,7 @@ int DoMain(int argc, char* argv[]) { double flight_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(1)(0); double land_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(2)(0) + - gains.landing_delay; + gains.landing_delay; std::vector transition_times = {0.0, FLAGS_delay_time, flight_time, land_time}; @@ -183,18 +221,11 @@ int DoMain(int argc, char* argv[]) { Vector3d support_center_offset; support_center_offset << gains.x_offset, 0.0, 0.0; std::vector breaks = pelvis_trans_traj.get_segment_times(); - std::vector ft_breaks = l_foot_trajectory.get_segment_times(); VectorXd breaks_vector = Eigen::Map(breaks.data(), breaks.size()); - VectorXd ft_breaks_vector = - Eigen::Map(ft_breaks.data(), ft_breaks.size()); MatrixXd offset_points = support_center_offset.replicate(1, breaks.size()); - MatrixXd ft_offset_points = - support_center_offset.replicate(1, ft_breaks_vector.size()); PiecewisePolynomial offset_traj = PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_points); pelvis_trans_traj = pelvis_trans_traj + offset_traj; - l_foot_trajectory = l_foot_trajectory - ft_offset_points; - r_foot_trajectory = r_foot_trajectory - ft_offset_points; /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -209,10 +240,10 @@ int DoMain(int argc, char* argv[]) { feet_contact_points, FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_left", true, l_foot_trajectory, - gains.relative_feet, FLAGS_delay_time); + l_hip_trajectory, gains.relative_feet, FLAGS_delay_time); auto r_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_right", false, r_foot_trajectory, - gains.relative_feet, FLAGS_delay_time); + r_hip_trajectory, gains.relative_feet, FLAGS_delay_time); auto pelvis_rot_traj_generator = builder.AddSystem( pelvis_rot_trajectory, "pelvis_rot_tracking_data", FLAGS_delay_time); @@ -257,6 +288,9 @@ int DoMain(int argc, char* argv[]) { // Soft constraint on contacts double w_contact_relax = gains.w_soft_constraint; osc->SetWeightOfSoftContactConstraint(w_contact_relax); + // Soft constraint on contacts + double w_input_reg = gains.w_input_reg; + osc->SetInputRegularizationWeight(w_input_reg); // Contact information for OSC osc->SetContactFriction(gains.mu); @@ -311,13 +345,19 @@ int DoMain(int argc, char* argv[]) { osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ - TransTaskSpaceTrackingData pelvis_tracking_data("pelvis_traj", gains.K_p_com, - gains.K_d_com, gains.W_com, - plant_w_spr, plant_w_spr); + TransTaskSpaceTrackingData pelvis_tracking_data( + "pelvis_trans_traj", gains.K_p_com, gains.K_d_com, gains.W_com, + plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { pelvis_tracking_data.AddStateAndPointToTrack(mode, "pelvis"); } - osc->AddTrackingData(&pelvis_tracking_data); + + RotTaskSpaceTrackingData pelvis_rot_tracking_data( + "pelvis_rot_tracking_data", gains.K_p_pelvis, gains.K_d_pelvis, + gains.W_pelvis, plant_w_spr, plant_w_spr); + for (auto mode : stance_modes) { + pelvis_rot_tracking_data.AddStateAndFrameToTrack(mode, "pelvis"); + } TransTaskSpaceTrackingData left_foot_tracking_data( "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, @@ -329,39 +369,47 @@ int DoMain(int argc, char* argv[]) { right_foot_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, "toe_right"); - RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_tracking_data", gains.K_p_pelvis, gains.K_d_pelvis, - gains.W_pelvis, plant_w_spr, plant_w_spr); + TransTaskSpaceTrackingData left_hip_tracking_data( + "left_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr); + TransTaskSpaceTrackingData right_hip_tracking_data( + "right_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr); + left_hip_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, "hip_left"); + right_hip_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, + "hip_right"); - for (auto mode : stance_modes) { - pelvis_rot_tracking_data.AddStateAndFrameToTrack(mode, "pelvis"); - } + RelativeTranslationTrackingData left_foot_rel_tracking_data( + "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr, &left_foot_tracking_data, + &left_hip_tracking_data); + RelativeTranslationTrackingData right_foot_rel_tracking_data( + "right_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, + gains.W_flight_foot, plant_w_spr, plant_w_spr, &right_foot_tracking_data, + &right_hip_tracking_data); // Flight phase hip yaw tracking - MatrixXd W_hip_yaw = gains.w_hip_yaw * MatrixXd::Identity(1, 1); - MatrixXd K_p_hip_yaw = gains.hip_yaw_kp * MatrixXd::Identity(1, 1); - MatrixXd K_d_hip_yaw = gains.hip_yaw_kd * MatrixXd::Identity(1, 1); - JointSpaceTrackingData swing_hip_yaw_left_traj( - "swing_hip_yaw_left_traj", K_p_hip_yaw, K_d_hip_yaw, W_hip_yaw, - plant_w_spr, plant_w_spr); - JointSpaceTrackingData swing_hip_yaw_right_traj( - "swing_hip_yaw_right_traj", K_p_hip_yaw, K_d_hip_yaw, W_hip_yaw, - plant_w_spr, plant_w_spr); - swing_hip_yaw_left_traj.AddStateAndJointToTrack( + JointSpaceTrackingData left_hip_yaw_tracking_data( + "swing_hip_yaw_left_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, + gains.W_hip_yaw, plant_w_spr, plant_w_spr); + JointSpaceTrackingData right_hip_yaw_tracking_data( + "swing_hip_yaw_right_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, + gains.W_hip_yaw, plant_w_spr, plant_w_spr); + left_hip_yaw_tracking_data.AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); - swing_hip_yaw_right_traj.AddStateAndJointToTrack( + right_hip_yaw_tracking_data.AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_right", "hip_yaw_rightdot"); - osc->AddConstTrackingData(&swing_hip_yaw_left_traj, VectorXd::Zero(1)); - osc->AddConstTrackingData(&swing_hip_yaw_right_traj, VectorXd::Zero(1)); + osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); // Flight phase toe pitch tracking MatrixXd W_swing_toe = gains.w_swing_toe * MatrixXd::Identity(1, 1); MatrixXd K_p_swing_toe = gains.swing_toe_kp * MatrixXd::Identity(1, 1); MatrixXd K_d_swing_toe = gains.swing_toe_kd * MatrixXd::Identity(1, 1); - JointSpaceTrackingData left_toe_angle_traj( + JointSpaceTrackingData left_toe_angle_tracking_data( "left_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); - JointSpaceTrackingData right_toe_angle_traj( + JointSpaceTrackingData right_toe_angle_tracking_data( "right_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); @@ -372,29 +420,40 @@ int DoMain(int argc, char* argv[]) { auto left_toe_angle_traj_gen = builder.AddSystem( - plant_w_spr, context_w_spr.get(), pos_map["toe_left"], - left_foot_points, "left_toe_angle_traj"); + plant_w_spr, context_w_spr.get(), l_toe_trajectory, + pos_map["toe_left"], left_foot_points, "left_toe_angle_traj"); auto right_toe_angle_traj_gen = builder.AddSystem( - plant_w_spr, context_w_spr.get(), pos_map["toe_right"], - right_foot_points, "right_toe_angle_traj"); + plant_w_spr, context_w_spr.get(), r_toe_trajectory, + pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); - left_toe_angle_traj.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_left", - "toe_leftdot"); - right_toe_angle_traj.AddStateAndJointToTrack(osc_jump::FLIGHT, "toe_right", - "toe_rightdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + osc_jump::FLIGHT, "toe_left", "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + osc_jump::FLIGHT, "toe_right", "toe_rightdot"); - pelvis_rot_tracking_data.SetImpactInvariantProjection(true); - left_foot_tracking_data.SetImpactInvariantProjection(true); - right_foot_tracking_data.SetImpactInvariantProjection(true); - left_toe_angle_traj.SetImpactInvariantProjection(true); - right_toe_angle_traj.SetImpactInvariantProjection(true); + osc->AddTrackingData(&pelvis_tracking_data); osc->AddTrackingData(&pelvis_rot_tracking_data); - osc->AddTrackingData(&left_foot_tracking_data); - osc->AddTrackingData(&right_foot_tracking_data); - osc->AddTrackingData(&left_toe_angle_traj); - osc->AddTrackingData(&right_toe_angle_traj); + if (gains.relative_feet) { + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_rel_tracking_data); + osc->AddTrackingData(&right_foot_rel_tracking_data); + } else { + left_foot_tracking_data.SetImpactInvariantProjection(true); + right_foot_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_foot_tracking_data); + osc->AddTrackingData(&right_foot_tracking_data); + } + osc->AddTrackingData(&left_toe_angle_tracking_data); + osc->AddTrackingData(&right_toe_angle_tracking_data); + left_toe_angle_tracking_data.SetImpactInvariantProjection(true); + right_toe_angle_tracking_data.SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + pelvis_rot_tracking_data.SetImpactInvariantProjection(true); + pelvis_tracking_data.SetImpactInvariantProjection(true); // Build OSC problem osc->Build(); @@ -409,7 +468,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); builder.Connect(pelvis_trans_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_traj")); + osc->get_tracking_data_input_port("pelvis_trans_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), @@ -460,11 +519,12 @@ int DoMain(int argc, char* argv[]) { // Run lcm-driven simulation // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc jumping controller")); + owned_diagram->set_name(("osc_jumping_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); return 0; diff --git a/examples/Cassie/visualize_trajectory.cc b/examples/Cassie/visualize_trajectory.cc index 6d07c2d39d..90318e337e 100644 --- a/examples/Cassie/visualize_trajectory.cc +++ b/examples/Cassie/visualize_trajectory.cc @@ -30,7 +30,13 @@ DEFINE_int32(visualize_mode, 0, "0 - Single animation" "1 - Looped animation" "2 - Multipose visualizer"); -DEFINE_bool(use_transparency, false, "Transparency setting for the Multipose visualizer"); +DEFINE_bool(use_transparency, false, + "Transparency setting for the Multipose visualizer"); +DEFINE_bool(use_springs, false, "Set to true if the trajectory is for the model with springs"); +DEFINE_bool( + mirror_traj, false, + "Whether or not to extend the trajectory by mirroring the trajectory. Only " + "use for periodic trajectories that are symmetric."); namespace dairlib { @@ -46,13 +52,41 @@ int DoMain() { plant.Finalize(); int nq = plant.num_positions(); + int nv = plant.num_positions(); + int nx = nq + nv; std::unique_ptr> context = plant.CreateDefaultContext(); - DirconTrajectory saved_traj(FLAGS_folder_path + FLAGS_trajectory_name); - VectorXd time_vector = saved_traj.GetBreaks(); + DirconTrajectory saved_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); + // VectorXd time_vector = saved_traj.GetBreaks(); PiecewisePolynomial optimal_traj = saved_traj.ReconstructStateTrajectory(); + std::vector time_vector = optimal_traj.get_segment_times(); + + if (FLAGS_mirror_traj) { + auto mirrored_traj = + saved_traj.ReconstructMirrorStateTrajectory(optimal_traj.end_time()); + VectorXd x_offset = VectorXd::Zero(nx); + x_offset(4) = optimal_traj.value(optimal_traj.end_time())(4) - + optimal_traj.value(optimal_traj.start_time())(4); + std::vector x_offset_rep(mirrored_traj.get_segment_times().size(), + x_offset); + PiecewisePolynomial x_offset_traj = + PiecewisePolynomial::ZeroOrderHold( + mirrored_traj.get_segment_times(), x_offset_rep); + optimal_traj.ConcatenateInTime(mirrored_traj + x_offset_traj); + + x_offset(4) = optimal_traj.value(optimal_traj.end_time())(4) - + optimal_traj.value(optimal_traj.start_time())(4); + x_offset_rep = std::vector( + optimal_traj.get_segment_times().size(), x_offset); + + PiecewisePolynomial copy = optimal_traj; + copy.shiftRight(optimal_traj.end_time()); + x_offset_traj = PiecewisePolynomial::ZeroOrderHold( + copy.get_segment_times(), x_offset_rep); + optimal_traj.ConcatenateInTime(copy + x_offset_traj); + } if (FLAGS_visualize_mode == 0 || FLAGS_visualize_mode == 1) { multibody::connectTrajectoryVisualizer(&plant, &builder, &scene_graph, @@ -73,17 +107,20 @@ int DoMain() { poses.col(i) = optimal_traj.value( time_vector[i * time_vector.size() / FLAGS_num_poses]); } - if(FLAGS_use_transparency){ + if (FLAGS_use_transparency) { VectorXd alpha_scale = VectorXd::LinSpaced(FLAGS_num_poses, 0.2, 1.0); - multibody::MultiposeVisualizer visualizer = multibody::MultiposeVisualizer( - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"), - FLAGS_num_poses, alpha_scale.array().square()); + multibody::MultiposeVisualizer visualizer = + multibody::MultiposeVisualizer( + FindResourceOrThrow( + "examples/Cassie/urdf/cassie_fixed_springs.urdf"), + FLAGS_num_poses, alpha_scale.array().square()); visualizer.DrawPoses(poses); - } - else{ - multibody::MultiposeVisualizer visualizer = multibody::MultiposeVisualizer( - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"), - FLAGS_num_poses); + } else { + multibody::MultiposeVisualizer visualizer = + multibody::MultiposeVisualizer( + FindResourceOrThrow( + "examples/Cassie/urdf/cassie_fixed_springs.urdf"), + FLAGS_num_poses); visualizer.DrawPoses(poses); } } diff --git a/examples/impact_invariant_control/five_link_biped_sim.cc b/examples/impact_invariant_control/five_link_biped_sim.cc index b00b9643e9..c70da07c5e 100644 --- a/examples/impact_invariant_control/five_link_biped_sim.cc +++ b/examples/impact_invariant_control/five_link_biped_sim.cc @@ -93,7 +93,7 @@ int do_main(int argc, char* argv[]) { plant.set_penetration_allowance(FLAGS_penetration_allowance); const DirconTrajectory& loaded_traj = - DirconTrajectory(FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory(plant, FLAGS_folder_path + FLAGS_trajectory_name); auto state_traj = loaded_traj.ReconstructStateTrajectory(); // Create input receiver. diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 8c9205a6ae..288a5faaa7 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -10,13 +10,13 @@ #include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "yaml-cpp/yaml.h" -#include "drake/common/yaml/yaml_io.h" +#include "drake/common/yaml/yaml_read_archive.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -38,9 +38,9 @@ using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using systems::controllers::JointSpaceTrackingData; @@ -91,12 +91,14 @@ int DoMain(int argc, char* argv[]) { map act_map = multibody::makeNameToActuatorsMap(plant); /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - auto gains = - drake::yaml::LoadYamlFile(FLAGS_gains_filename); + JointSpaceWalkingGains gains; + const YAML::Node& root = + YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); + drake::yaml::YamlReadArchive(root).Accept(&gains); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( - FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); + plant, FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); PiecewisePolynomial state_traj = dircon_trajectory.ReconstructStateTrajectory(); @@ -107,9 +109,11 @@ int DoMain(int argc, char* argv[]) { vector fsm_states; vector state_durations; fsm_states = {0, 1, 0}; - state_durations = {dircon_trajectory.GetStateBreaks(1)(0), - dircon_trajectory.GetStateBreaks(2)(0) - dircon_trajectory.GetStateBreaks(1)(0), - state_traj.end_time() - dircon_trajectory.GetStateBreaks(2)(0)}; + state_durations = { + dircon_trajectory.GetStateBreaks(1)(0), + dircon_trajectory.GetStateBreaks(2)(0) - + dircon_trajectory.GetStateBreaks(1)(0), + state_traj.end_time() - dircon_trajectory.GetStateBreaks(2)(0)}; auto state_receiver = builder.AddSystem(plant); auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, gains.impact_threshold); @@ -165,8 +169,7 @@ int DoMain(int argc, char* argv[]) { joint_tracking_data_vec[joint_idx]->AddJointToTrack(joint_name, joint_name + "dot"); joint_tracking_data_vec[joint_idx]->SetImpactInvariantProjection(true); - auto joint_traj = dircon_trajectory.ReconstructJointTrajectory( - pos_map_wo_spr[joint_name]); + auto joint_traj = dircon_trajectory.ReconstructJointTrajectory(joint_name); auto joint_traj_generator = builder.AddSystem( joint_traj, joint_name + "_traj"); joint_trajs.push_back(joint_traj_generator); diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index 15881dd316..840dd70557 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -31,6 +31,7 @@ DirconTrajectory::DirconTrajectory( LcmTrajectory::Trajectory state_traj; LcmTrajectory::Trajectory state_derivative_traj; LcmTrajectory::Trajectory force_traj; + LcmTrajectory::Trajectory impulse_traj; state_traj.traj_name = "state_traj" + std::to_string(mode); state_traj.datapoints = x[mode]; @@ -48,10 +49,12 @@ DirconTrajectory::DirconTrajectory( force_traj.traj_name = "force_vars" + std::to_string(mode); std::vector force_names; std::vector collocation_force_names; + std::vector impulse_names; int num_forces = dircon.get_evaluator_set(mode).count_full(); for (int i = 0; i < num_forces; ++i) { force_names.push_back("lambda_" + std::to_string(i)); + impulse_names.push_back("Lambda_" + std::to_string(i)); collocation_force_names.push_back("lambda_c_" + std::to_string(i)); } force_traj.datatypes = force_names; @@ -60,6 +63,15 @@ DirconTrajectory::DirconTrajectory( Eigen::Map(dircon.GetForceSamplesByMode(result, mode).data(), num_forces, force_traj.time_vector.size()); + // Impulse vars + if (mode > 0) { + impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); + impulse_traj.datatypes = impulse_names; + // Get start of mode to get time of impulse + impulse_traj.time_vector = state_breaks[mode].segment(0, 1); + impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode)); + } + // Collocation force vars if (state_breaks[mode].size() > 1) { LcmTrajectory::Trajectory collocation_force_traj; @@ -99,10 +111,12 @@ DirconTrajectory::DirconTrajectory( AddTrajectory(state_traj.traj_name, state_traj); AddTrajectory(state_derivative_traj.traj_name, state_derivative_traj); AddTrajectory(force_traj.traj_name, force_traj); + AddTrajectory(impulse_traj.traj_name, impulse_traj); x_.push_back(&state_traj); xdot_.push_back(&state_derivative_traj); lambda_.push_back(&force_traj); + impulse_.push_back(&impulse_traj); } // Input trajectory @@ -144,6 +158,7 @@ DirconTrajectory::DirconTrajectory( LcmTrajectory::Trajectory state_traj; LcmTrajectory::Trajectory state_derivative_traj; LcmTrajectory::Trajectory force_traj; + LcmTrajectory::Trajectory impulse_traj; state_traj.traj_name = "state_traj" + std::to_string(mode); state_traj.datapoints = x[mode]; @@ -160,11 +175,13 @@ DirconTrajectory::DirconTrajectory( // Force vars force_traj.traj_name = "force_vars" + std::to_string(mode); std::vector force_names; + std::vector impulse_names; std::vector collocation_force_names; int num_forces = 0; for (int i = 0; i < dircon.num_kinematic_constraints_wo_skipping(mode); ++i) { force_names.push_back("lambda_" + std::to_string(num_forces)); + impulse_names.push_back("Lambda_" + std::to_string(i)); collocation_force_names.push_back("lambda_c_" + std::to_string(num_forces)); ++num_forces; @@ -176,6 +193,16 @@ DirconTrajectory::DirconTrajectory( num_forces, force_traj.time_vector.size()); force_traj.datatypes = force_names; + // Impulse vars + if (mode > 0) { + impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); + impulse_traj.datatypes = impulse_names; + // Get start of mode to get time of impulse + impulse_traj.time_vector = state_breaks[mode].segment(0, 1); + impulse_traj.datapoints = + result.GetSolution(dircon.impulse_vars(mode - 1)); + } + // Collocation force vars if (state_breaks[mode].size() > 1) { LcmTrajectory::Trajectory collocation_force_traj; @@ -209,6 +236,7 @@ DirconTrajectory::DirconTrajectory( AddTrajectory(state_traj.traj_name, state_traj); AddTrajectory(state_derivative_traj.traj_name, state_derivative_traj); AddTrajectory(force_traj.traj_name, force_traj); + AddTrajectory(impulse_traj.traj_name, impulse_traj); x_.push_back(&state_traj); xdot_.push_back(&state_derivative_traj); @@ -243,9 +271,6 @@ DirconTrajectory::DirconTrajectory( PiecewisePolynomial DirconTrajectory::ReconstructStateTrajectory() const { PiecewisePolynomial state_traj; -// = -// PiecewisePolynomial::CubicHermite( -// x_[0]->time_vector, x_[0]->datapoints, xdot_[0]->datapoints); for (int mode = 0; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -253,17 +278,16 @@ const { continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, x_[mode]->datapoints, xdot_[mode]->datapoints)); + x_[mode]->time_vector, state_map_ * x_[mode]->datapoints, + state_map_ * xdot_[mode]->datapoints)); } return state_traj; } -PiecewisePolynomial DirconTrajectory::ReconstructJointTrajectory(int joint_idx) -const { +PiecewisePolynomial +DirconTrajectory::ReconstructStateTrajectoryWithSprings( + Eigen::MatrixXd& spr_to_wo_spr_map) const { PiecewisePolynomial state_traj; -// = -// PiecewisePolynomial::CubicHermite( -// x_[0]->time_vector, x_[0]->datapoints.row(joint_idx), xdot_[0]->datapoints.row(joint_idx)); for (int mode = 0; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -271,7 +295,75 @@ const { continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, x_[mode]->datapoints.row(joint_idx), xdot_[mode]->datapoints.row(joint_idx))); + x_[mode]->time_vector, spr_to_wo_spr_map * x_[mode]->datapoints, + spr_to_wo_spr_map * xdot_[mode]->datapoints)); + } + return state_traj; +} + +PiecewisePolynomial DirconTrajectory::ReconstructMirrorStateTrajectory( + double t_offset) const { + MatrixXd M = GetTrajectory("mirror_matrix").datapoints; + PiecewisePolynomial state_traj = + PiecewisePolynomial::CubicHermite( + x_[0]->time_vector + + t_offset * VectorXd::Ones(x_[0]->time_vector.size()), + state_map_ * M * x_[0]->datapoints, + state_map_ * M * xdot_[0]->datapoints); + + for (int mode = 1; mode < num_modes_; ++mode) { + // Cannot form trajectory with only a single break + if (x_[mode]->time_vector.size() < 2) { + continue; + } + state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( + x_[mode]->time_vector + + t_offset * VectorXd::Ones(x_[mode]->time_vector.size()), + state_map_ * M * x_[mode]->datapoints, + state_map_ * M * xdot_[mode]->datapoints)); + } + return state_traj; +} + +PiecewisePolynomial DirconTrajectory::ReconstructJointTrajectory( + std::string joint_name) const { + PiecewisePolynomial state_traj = + PiecewisePolynomial::CubicHermite( + x_[0]->time_vector, x_[0]->datapoints.row(pos_map_.at(joint_name)), + xdot_[0]->datapoints.row(pos_map_.at(joint_name))); + + for (int mode = 1; mode < num_modes_; ++mode) { + // Cannot form trajectory with only a single break + if (x_[mode]->time_vector.size() < 2) { + continue; + } + state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( + x_[mode]->time_vector, + x_[mode]->datapoints.row(pos_map_.at(joint_name)), + xdot_[mode]->datapoints.row(pos_map_.at(joint_name)))); + } + return state_traj; +} + +PiecewisePolynomial DirconTrajectory::ReconstructMirrorJointTrajectory( + std::string joint_name) const { + MatrixXd M = GetTrajectory("mirror_matrix").datapoints; + PiecewisePolynomial state_traj = + PiecewisePolynomial::CubicHermite( + x_[0]->time_vector, + (state_map_ * M * x_[0]->datapoints).row(pos_map_.at(joint_name)), + (state_map_ * M * xdot_[0]->datapoints).row(pos_map_.at(joint_name))); + + for (int mode = 1; mode < num_modes_; ++mode) { + // Cannot form trajectory with only a single break + if (x_[mode]->time_vector.size() < 2) { + continue; + } + state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( + x_[mode]->time_vector, + (state_map_ * M * x_[mode]->datapoints).row(pos_map_.at(joint_name)), + (state_map_ * M * xdot_[mode]->datapoints) + .row(pos_map_.at(joint_name)))); } return state_traj; } @@ -279,8 +371,8 @@ const { PiecewisePolynomial DirconTrajectory::ReconstructInputTrajectory() const { PiecewisePolynomial input_traj = - PiecewisePolynomial::FirstOrderHold(u_->time_vector, - u_->datapoints); + PiecewisePolynomial::FirstOrderHold( + u_->time_vector, actuator_map_ * u_->datapoints); return input_traj; } @@ -320,7 +412,8 @@ DirconTrajectory::ReconstructGammaCTrajectory() const { return gamma_c_traj; } -void DirconTrajectory::LoadFromFile(const std::string& filepath) { +void DirconTrajectory::LoadFromFileWithPlant(const MultibodyPlant& plant, + const std::string& filepath) { LcmTrajectory::LoadFromFile(filepath); // Find all the state trajectories @@ -334,13 +427,18 @@ void DirconTrajectory::LoadFromFile(const std::string& filepath) { xdot_.push_back( &GetTrajectory("state_derivative_traj" + std::to_string(mode))); lambda_.push_back(&GetTrajectory("force_vars" + std::to_string(mode))); + if (x_[mode]->time_vector.size() > 1) { try { + if (mode > 0) { + impulse_.push_back( + &GetTrajectory("impulse_vars" + std::to_string(mode))); + } lambda_c_.push_back( &GetTrajectory("collocation_force_vars" + std::to_string(mode))); gamma_c_.push_back( &GetTrajectory("collocation_slack_vars" + std::to_string(mode))); - }catch(std::exception&){ + } catch (std::exception&) { // Temporary fix to work with old versions of saved dircon trajectories continue; } @@ -348,6 +446,46 @@ void DirconTrajectory::LoadFromFile(const std::string& filepath) { } u_ = &GetTrajectory("input_traj"); decision_vars_ = &GetTrajectory("decision_vars"); + + // Finished loading in trajectories, now constructing maps to be compatible + // with old trajectories + + auto pos_map = multibody::makeNameToPositionsMap(plant); + auto vel_map = multibody::makeNameToVelocitiesMap(plant); + auto act_map = multibody::makeNameToActuatorsMap(plant); + state_map_ = MatrixXd::Zero(plant.num_positions() + plant.num_velocities(), + x_[0]->datapoints.rows()); + int nq = plant.num_positions(); + + for (int i = 0; i < x_[0]->datatypes.size(); ++i) { + auto state_name = x_[0]->datatypes.at(i); + if (pos_map.count(state_name)) { + state_map_(pos_map[state_name], i) = 1; + pos_map_[state_name] = i; + } else if (vel_map.count(state_name)) { + state_map_(nq + vel_map[state_name], i) = 1; + vel_map_[state_name] = i; + } else { + std::cerr << "Trajectory contains state names that are present in the " + "supplied MultibodyPlant." + << std::endl; + } + } + + DRAKE_DEMAND(plant.num_actuators() == u_->datapoints.rows()); + actuator_map_ = MatrixXd::Zero(plant.num_actuators(), plant.num_actuators()); + + for (int i = 0; i < u_->datatypes.size(); ++i) { + auto motor_name = u_->datatypes.at(i); + if (act_map.count(motor_name)) { + actuator_map_(act_map[motor_name], i) = 1; + act_map_[motor_name] = i; + } else { + std::cerr << "Trajectory contains state names that are present in the " + "supplied MultibodyPlant." + << std::endl; + } + } } Eigen::VectorXd DirconTrajectory::GetCollocationPoints( diff --git a/lcm/dircon_saved_trajectory.h b/lcm/dircon_saved_trajectory.h index 7386bdad91..fb0f79d072 100644 --- a/lcm/dircon_saved_trajectory.h +++ b/lcm/dircon_saved_trajectory.h @@ -25,13 +25,16 @@ namespace dairlib { /// DirconTrajectory by default contains four Trajectory objects: the state /// trajectory, the input trajectory, the force trajectory, the contact force -/// trajectory, the collocation force trajectory, the collocation slack trajectory -/// and the decision variables. Additional trajectories can be added using -/// the AddTrajectory() function +/// trajectory, the collocation force trajectory, the collocation slack +/// trajectory and the decision variables. Additional trajectories can be added +/// using the AddTrajectory() function class DirconTrajectory : public LcmTrajectory { public: - DirconTrajectory(const std::string& filepath) { LoadFromFile(filepath); } + DirconTrajectory(const drake::multibody::MultibodyPlant& plant, + const std::string& filepath) { + LoadFromFileWithPlant(plant, filepath); + } DirconTrajectory( const drake::multibody::MultibodyPlant& plant, @@ -49,27 +52,36 @@ class DirconTrajectory : public LcmTrajectory { const; drake::trajectories::PiecewisePolynomial ReconstructStateTrajectory() const; - drake::trajectories::PiecewisePolynomial ReconstructJointTrajectory(int joint_idx) - const; - - /// Returns a vector of polynomials describing the contact forces for each mode. For use when - /// adding knot points to the initial guess - std::vector> ReconstructLambdaTrajectory() - const; - - /// Returns a vector of polynomials describing the collocation forces for each mode. For use - /// when adding knot points to the initial guess - std::vector> ReconstructLambdaCTrajectory() - const; - - /// Returns a vector of polynomials describing the collocation slack vars. For use when adding - /// knot points to the initial guess - std::vector> ReconstructGammaCTrajectory() - const; + drake::trajectories::PiecewisePolynomial + ReconstructStateTrajectoryWithSprings(Eigen::MatrixXd&) const; + drake::trajectories::PiecewisePolynomial + ReconstructMirrorStateTrajectory(double t_offset) const; + drake::trajectories::PiecewisePolynomial ReconstructJointTrajectory( + std::string joint_name) const; + drake::trajectories::PiecewisePolynomial + ReconstructMirrorJointTrajectory(std::string joint_name) const; + + /// Returns a vector of polynomials describing the contact forces for each + /// mode. For use when adding knot points to the initial guess + std::vector> + ReconstructLambdaTrajectory() const; + + /// Returns a vector of polynomials describing the collocation forces for each + /// mode. For use when adding knot points to the initial guess + std::vector> + ReconstructLambdaCTrajectory() const; + + /// Returns a vector of polynomials describing the collocation slack vars. For + /// use when adding knot points to the initial guess + std::vector> + ReconstructGammaCTrajectory() const; /// Loads the saved state and input trajectory as well as the decision /// variables - void LoadFromFile(const std::string& filepath) override; + /// A MultibodyPlant is required due to possible state and actuator indexing + /// conflicts. + void LoadFromFileWithPlant(const drake::multibody::MultibodyPlant& plant, + const std::string& filepath); Eigen::MatrixXd GetStateSamples(int mode) const { DRAKE_DEMAND(mode >= 0); @@ -94,6 +106,9 @@ class DirconTrajectory : public LcmTrajectory { Eigen::MatrixXd GetForceBreaks(int mode) const { return lambda_[mode]->time_vector; } + Eigen::MatrixXd GetImpulseSamples(int mode) const { + return impulse_[mode - 1]->datapoints; + } Eigen::MatrixXd GetCollocationForceSamples(int mode) const { return lambda_c_[mode]->datapoints; } @@ -113,10 +128,21 @@ class DirconTrajectory : public LcmTrajectory { const Trajectory* decision_vars_; const Trajectory* u_; + std::vector impulse_; std::vector lambda_; std::vector lambda_c_; std::vector gamma_c_; std::vector x_; std::vector xdot_; + + // convenience map + // NOTE: + std::map pos_map_; + std::map vel_map_; + std::map act_map_; + // map from possibly old state indices to current state indices + Eigen::MatrixXd state_map_; + // map from possibly old actuator indices to current actuator indices + Eigen::MatrixXd actuator_map_; }; } // namespace dairlib diff --git a/solvers/nonlinear_cost.cc b/solvers/nonlinear_cost.cc index a7f9c5821e..e6d2159f0d 100644 --- a/solvers/nonlinear_cost.cc +++ b/solvers/nonlinear_cost.cc @@ -27,8 +27,8 @@ template <> void NonlinearCost::DoEval( const Eigen::Ref& x, Eigen::VectorXd* y) const { AutoDiffVecXd y_t; - EvaluateCost(drake::math::initializeAutoDiff(x), &y_t); - *y = drake::math::autoDiffToValueMatrix(y_t); + EvaluateCost(drake::math::InitializeAutoDiff(x), &y_t); + *y = drake::math::ExtractValue(y_t); } template @@ -47,10 +47,10 @@ void NonlinearCost::DoEval(const Eigen::Ref& x, template <> void NonlinearCost::DoEval(const Eigen::Ref& x, AutoDiffVecXd* y) const { - MatrixXd original_grad = drake::math::autoDiffToGradientMatrix(x); + MatrixXd original_grad = drake::math::ExtractGradient(x); // forward differencing - VectorXd x_val = drake::math::autoDiffToValueMatrix(x); + VectorXd x_val = drake::math::ExtractValue(x); VectorXd y0, yi; EvaluateCost(x_val, &y0); @@ -61,8 +61,7 @@ void NonlinearCost::DoEval(const Eigen::Ref& x, x_val(i) -= eps_; dy.col(i) = (yi - y0) / eps_; } - drake::math::initializeAutoDiffGivenGradientMatrix(y0, dy * original_grad, - *y); + *y = drake::math::InitializeAutoDiff(y0, dy * original_grad); } } // namespace solvers From c573a7e7afa60b7dc5cf9f8d200034e920d7619c Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 24 Jan 2022 09:36:27 -0500 Subject: [PATCH 085/758] update some plotting functions to compensate for joint reordering --- bindings/pydairlib/analysis/mbp_plotting_utils.py | 9 +++++++-- 1 file changed, 7 insertions(+), 2 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2a31d04b2d..b0756ad6cf 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -53,12 +53,17 @@ def process_state_channel(state_data, plant): 'u': np.array(u)} -def process_effort_channel(data): +def process_effort_channel(data, plant): u = [] t = [] + + act_map = makeNameToActuatorsMap(plant) for msg in data: + u_temp = [[] for i in range(len(msg.effort))] + for i in range(len(u_temp)): + u_temp[act_map[msg.effort_names[i]]] = msg.efforts[i] t.append(msg.utime / 1e6) - u.append(msg.efforts) + u.append(msg.u_temp) return {'t_u': np.array(t), 'u': np.array(u)} From 452ba3fd13c4c5a0669240d3438accae88a7f4d3 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 24 Jan 2022 10:32:10 -0500 Subject: [PATCH 086/758] updated plotting script to allow for new joint orderings - we still assume floating base comes first --- .../pydairlib/analysis/mbp_plotting_utils.py | 52 ++++++++++++++----- 1 file changed, 38 insertions(+), 14 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index b0756ad6cf..1346d6581a 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -22,6 +22,33 @@ def make_mbp_name_vectors(plant): return q_names, v_names, u_names +def make_joint_order_permutation_matrix(names_in_old_order, names_in_new_order): + n = len(names_in_new_order) + perm = np.zeros((n, n), dtype=int) + for i, name in enumerate(names_in_new_order): + try: + j = names_in_old_order.index(name) + except ValueError: + print(f"Error: {name} not found in old joint ordering") + raise + except BaseException as err: + print(f"Unexpected {err}, {type(err)}") + raise + perm[i, j] = 1 + return perm + + +def make_joint_order_permutations(robot_output_message, plant): + qnames, vnames, unames = make_mbp_name_vectors(plant) + qperm = make_joint_order_permutation_matrix( + robot_output_message.position_names, qnames) + vperm = make_joint_order_permutation_matrix( + robot_output_message.velocity_names, vnames) + uperm = make_joint_order_permutation_matrix( + robot_output_message.effort_names, unames) + return qperm, vperm, uperm + + def process_state_channel(state_data, plant): t_x = [] q = [] @@ -59,7 +86,7 @@ def process_effort_channel(data, plant): act_map = makeNameToActuatorsMap(plant) for msg in data: - u_temp = [[] for i in range(len(msg.effort))] + u_temp = [[] for i in range(len(msg.efforts))] for i in range(len(u_temp)): u_temp[act_map[msg.effort_names[i]]] = msg.efforts[i] t.append(msg.utime / 1e6) @@ -144,27 +171,24 @@ def process_osc_channel(data): 'osc_output': osc_output} +def permute_osc_joint_ordering(osc_data, robot_output_msg, plant): + _, vperm, uperm = make_joint_order_permutations(robot_output_msg, plant) + osc_data['u_sol'] = (osc_data['u_sol'] @ uperm.T) + osc_data['dv_sol'] = (osc_data['dv_sol'] @ vperm.T) + return osc_data + + def load_default_channels(data, plant, state_channel, input_channel, osc_debug_channel): robot_output = process_state_channel(data[state_channel], plant) - robot_input = process_effort_channel(data[input_channel]) + robot_input = process_effort_channel(data[input_channel], plant) osc_debug = process_osc_channel(data[osc_debug_channel]) + osc_debug = permute_osc_joint_ordering( + osc_debug, data[state_channel][0], plant) return robot_output, robot_input, osc_debug -def load_state_channel(data, plant, state_channel): - return process_state_channel(data[state_channel], plant) - - -def load_input_channel(data, input_channel): - return process_effort_channel(data[input_channel]) - - -def load_osc_channel(data, osc_debug_channel): - return process_osc_channel(data[osc_debug_channel]) - - def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, ylabel=None, title=None): From 2ad0d2b5840c839eaa90a2168d1451fba508516e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 24 Jan 2022 11:10:49 -0500 Subject: [PATCH 087/758] small deprecation fixes --- examples/Cassie/run_controller_switch.cc | 2 +- .../run_joint_space_walking_controller.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index c85a26da31..3cffa3d095 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -15,7 +15,7 @@ namespace dairlib { using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", "The name of the channel which receives state"); diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 354f8be9f4..02b9264836 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -40,7 +40,7 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::lcm::TriggerTypeSet; +using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; using examples::osc_jump::BasicTrajectoryPassthrough; using systems::controllers::JointSpaceTrackingData; From 5632df4c6fa064534d8d98513b166d1dddc29055 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Mon, 24 Jan 2022 11:20:59 -0500 Subject: [PATCH 088/758] bug fixes --- bindings/pydairlib/analysis/BUILD.bazel | 6 ++-- .../analysis/cassie_plotting_utils.py | 3 ++ .../pydairlib/analysis/mbp_plotting_utils.py | 2 +- .../plot_configs/cassie_default_plot.yaml | 6 ++-- .../pydairlib/analysis/process_lcm_log.py | 32 +++++++++++++++++-- 5 files changed, 40 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 205f172c49..1d04ebb2f0 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -11,10 +11,10 @@ load( "pybind_py_library", ) -py_library( - name = "process_lcm_log_py", +py_binary( + name = "process_lcm_log", srcs = ["process_lcm_log.py"], - deps = [], + deps = ["@lcm//:lcm-python"], ) py_library( diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 8d0f0b62d1..8fb92dc3d3 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -19,6 +19,9 @@ {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, 'CASSIE_STATE_DISPATCHER': dairlib.lcmt_robot_output, 'CASSIE_INPUT': dairlib.lcmt_robot_input, + 'OSC_WALKING': dairlib.lcmt_robot_input, + 'OSC_STANDING': dairlib.lcmt_robot_input, + 'OSC_JUMPING': dairlib.lcmt_robot_input, 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, 'OSC_DEBUG_STANDING': dairlib.lcmt_osc_output, 'OSC_DEBUG_WALKING': dairlib.lcmt_osc_output, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 1346d6581a..49041592a8 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -90,7 +90,7 @@ def process_effort_channel(data, plant): for i in range(len(u_temp)): u_temp[act_map[msg.effort_names[i]]] = msg.efforts[i] t.append(msg.utime / 1e6) - u.append(msg.u_temp) + u.append(u_temp) return {'t_u': np.array(t), 'u': np.array(u)} diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index 4803485e3a..605338c9cf 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -1,6 +1,6 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_SIMULATION" -channel_u: "CASSIE_INPUT" +channel_x: "CASSIE_STATE_DISPATCHER" +channel_u: "OSC_WALKING" channel_osc: "OSC_DEBUG_WALKING" # Plant properties @@ -27,5 +27,5 @@ plot_qp_costs: true plot_tracking_costs: true plot_qp_solve_time: true tracking_datas_to_plot: - com_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + lipm_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/analysis/process_lcm_log.py index 2ad66c63e5..21d8f078a1 100644 --- a/bindings/pydairlib/analysis/process_lcm_log.py +++ b/bindings/pydairlib/analysis/process_lcm_log.py @@ -1,5 +1,3 @@ - - def get_log_data(lcm_log, lcm_channels, data_processing_callback, *args, **kwargs): """ @@ -28,5 +26,35 @@ def get_log_data(lcm_log, lcm_channels, data_processing_callback, *args, return data_processing_callback(data_to_process, *args, *kwargs) +def get_log_summary(lcm_log): + channels = {} + for event in lcm_log: + if event.channel not in channels: + channels[event.channel] = 0 + else: + channels[event.channel] = channels[event.channel] + 1 + return channels + + +def print_log_summary(filename, log): + print(f"Channels in{filename}:\n") + summary = get_log_summary(log) + for channel, count in summary.items(): + print(f"{channel}: {count:06} messages") + + def passthrough_callback(data, *args, **kwargs): return data + + +def main(): + import lcm + import sys + + logfile = sys.argv[1] + log = lcm.EventLog(logfile, "r") + print_log_summary(logfile, log) + + +if __name__ == "__main__": + main() From 97aa0e3ac6dd57f4f71091abddbab54ea3679a9a Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 24 Jan 2022 11:57:58 -0500 Subject: [PATCH 089/758] more joint indexing changes --- .../osc_jump/convert_traj_for_controller.cc | 120 ++++++++++++++---- .../run_joint_space_walking_controller.cc | 8 +- lcm/dircon_saved_trajectory.h | 17 ++- 3 files changed, 111 insertions(+), 34 deletions(-) diff --git a/examples/Cassie/osc_jump/convert_traj_for_controller.cc b/examples/Cassie/osc_jump/convert_traj_for_controller.cc index 8f8e5a6803..2c5e5cea44 100644 --- a/examples/Cassie/osc_jump/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_jump/convert_traj_for_controller.cc @@ -8,6 +8,11 @@ #include "drake/multibody/plant/multibody_plant.h" +using std::map; +using std::pair; +using std::string; +using std::vector; + using drake::geometry::SceneGraph; using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; @@ -25,8 +30,7 @@ DEFINE_bool(relative_feet, true, "instead of as an offset from the hips"); DEFINE_string(trajectory_name, "", "File name where the optimal trajectory is stored."); -DEFINE_string(folder_path, - "", +DEFINE_string(folder_path, "", "Folder path for where the trajectory names are stored"); namespace dairlib { @@ -46,12 +50,18 @@ int DoMain() { parser.AddModelFromFile( FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); plant.mutable_gravity_field().set_gravity_vector(-9.81 * - Eigen::Vector3d::UnitZ()); + Eigen::Vector3d::UnitZ()); plant.Finalize(); + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + std::unique_ptr> context = plant.CreateDefaultContext(); int nv = plant.num_velocities(); + int nx = plant.num_positions() + plant.num_velocities(); auto l_toe_frame = &plant.GetBodyByName("toe_left").body_frame(); auto r_toe_frame = &plant.GetBodyByName("toe_right").body_frame(); @@ -60,12 +70,15 @@ int DoMain() { auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); auto world = &plant.world_frame(); - DirconTrajectory dircon_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); + DirconTrajectory dircon_traj(plant, + FLAGS_folder_path + FLAGS_trajectory_name); PiecewisePolynomial state_traj = dircon_traj.ReconstructStateTrajectory(); std::vector all_l_foot_points; std::vector all_r_foot_points; + std::vector all_l_toe_points; + std::vector all_r_toe_points; std::vector all_l_hip_points; std::vector all_r_hip_points; std::vector all_pelvis_points; @@ -82,17 +95,18 @@ int DoMain() { MatrixXd state_derivative_samples = dircon_traj.GetStateDerivativeSamples(mode); int n_points = times.size(); - MatrixXd l_foot_points(6, n_points); - MatrixXd r_foot_points(6, n_points); - MatrixXd l_hip_points(6, n_points); - MatrixXd r_hip_points(6, n_points); + MatrixXd l_foot_points(9, n_points); + MatrixXd r_foot_points(9, n_points); + MatrixXd l_toe_points(2, n_points); + MatrixXd r_toe_points(2, n_points); + MatrixXd l_hip_points(9, n_points); + MatrixXd r_hip_points(9, n_points); MatrixXd pelvis_points(6, n_points); MatrixXd pelvis_orientation(8, n_points); for (unsigned int i = 0; i < times.size(); ++i) { - VectorXd x_i = state_samples.col(i); - VectorXd xdot_i = state_traj.derivative(1).value(times[i]); - + VectorXd x_i = state_samples.col(i).head(nx); + VectorXd xdot_i = state_derivative_samples.col(i); plant.SetPositionsAndVelocities(context.get(), x_i); Eigen::Ref pelvis_pos_block = pelvis_points.block(0, i, 3, 1); @@ -115,6 +129,9 @@ int DoMain() { plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, *world, &r_hip_pos_block); + l_toe_points(0, i) = x_i(pos_map["toe_left"]); + r_toe_points(0, i) = x_i(pos_map["toe_right"]); + pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); @@ -146,17 +163,38 @@ int DoMain() { r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; + l_toe_points(1, i) = v_i(vel_map["toe_leftdot"]); + r_toe_points(1, i) = v_i(vel_map["toe_rightdot"]); + + VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world); + l_foot_points.block(6, i, 3, 1) = + JdotV_l_foot + J_l_foot * xdot_i.tail(nv); + r_foot_points.block(6, i, 3, 1) = + JdotV_r_foot + J_r_foot * xdot_i.tail(nv); + l_hip_points.block(6, i, 3, 1) = JdotV_l_hip + J_l_hip * xdot_i.tail(nv); + r_hip_points.block(6, i, 3, 1) = JdotV_r_hip + J_r_hip * xdot_i.tail(nv); } - pelvis_points = pelvis_points - 0.5 * (l_foot_points + r_foot_points); - if (FLAGS_relative_feet) { - l_foot_points = l_foot_points - l_hip_points; - r_foot_points = r_foot_points - r_hip_points; - } + pelvis_points = pelvis_points - + 0.5 * (l_foot_points.topRows(6) + r_foot_points.topRows(6)); + all_times.push_back(times); all_l_foot_points.push_back(l_foot_points); all_r_foot_points.push_back(r_foot_points); all_l_hip_points.push_back(l_hip_points); all_r_hip_points.push_back(r_hip_points); + all_l_toe_points.push_back(l_toe_points); + all_r_toe_points.push_back(r_toe_points); all_pelvis_points.push_back(pelvis_points); all_pelvis_orientation.push_back(pelvis_orientation); } @@ -168,15 +206,45 @@ int DoMain() { lfoot_traj_block.traj_name = "left_foot_trajectory" + std::to_string(mode); lfoot_traj_block.datapoints = all_l_foot_points[mode]; lfoot_traj_block.time_vector = all_times[mode]; - lfoot_traj_block.datatypes = {"lfoot_x", "lfoot_y", "lfoot_z", - "lfoot_xdot", "lfoot_ydot", "lfoot_zdot"}; + lfoot_traj_block.datatypes = {"lfoot_x", "lfoot_y", "lfoot_z", + "lfoot_xdot", "lfoot_ydot", "lfoot_zdot", + "lfoot_xddot", "lfoot_yddot", "lfoot_zddot"}; auto rfoot_traj_block = LcmTrajectory::Trajectory(); rfoot_traj_block.traj_name = "right_foot_trajectory" + std::to_string(mode); rfoot_traj_block.datapoints = all_r_foot_points[mode]; rfoot_traj_block.time_vector = all_times[mode]; - rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", - "rfoot_xdot", "rfoot_ydot", "rfoot_zdot"}; + rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", + "rfoot_xdot", "rfoot_ydot", "rfoot_zdot", + "rfoot_xddot", "rfoot_yddot", "rfoot_zddot"}; + + auto lhip_traj_block = LcmTrajectory::Trajectory(); + lhip_traj_block.traj_name = "left_hip_trajectory" + std::to_string(mode); + lhip_traj_block.datapoints = all_l_hip_points[mode]; + lhip_traj_block.time_vector = all_times[mode]; + lhip_traj_block.datatypes = {"lhip_x", "lhip_y", "lhip_z", + "lhip_xdot", "lhip_ydot", "lhip_zdot", + "lhip_xddot", "lhip_yddot", "lhip_zddot"}; + + auto rhip_traj_block = LcmTrajectory::Trajectory(); + rhip_traj_block.traj_name = "right_hip_trajectory" + std::to_string(mode); + rhip_traj_block.datapoints = all_r_hip_points[mode]; + rhip_traj_block.time_vector = all_times[mode]; + rhip_traj_block.datatypes = {"rhip_x", "rhip_y", "rhip_z", + "rhip_xdot", "rhip_ydot", "rhip_zdot", + "rhip_xddot", "rhip_yddot", "rhip_zddot"}; + + auto ltoe_traj_block = LcmTrajectory::Trajectory(); + ltoe_traj_block.traj_name = "left_toe_trajectory" + std::to_string(mode); + ltoe_traj_block.datapoints = all_l_toe_points[mode]; + ltoe_traj_block.time_vector = all_times[mode]; + ltoe_traj_block.datatypes = {"ltoe", "ltoe_dot"}; + + auto rtoe_traj_block = LcmTrajectory::Trajectory(); + rtoe_traj_block.traj_name = "right_toe_trajectory" + std::to_string(mode); + rtoe_traj_block.datapoints = all_r_toe_points[mode]; + rtoe_traj_block.time_vector = all_times[mode]; + rtoe_traj_block.datatypes = {"rtoe", "rtoe_dot"}; auto com_traj_block = LcmTrajectory::Trajectory(); com_traj_block.traj_name = "pelvis_trans_trajectory" + std::to_string(mode); @@ -196,10 +264,18 @@ int DoMain() { converted_trajectories.push_back(lfoot_traj_block); converted_trajectories.push_back(rfoot_traj_block); + converted_trajectories.push_back(lhip_traj_block); + converted_trajectories.push_back(rhip_traj_block); + converted_trajectories.push_back(ltoe_traj_block); + converted_trajectories.push_back(rtoe_traj_block); converted_trajectories.push_back(com_traj_block); converted_trajectories.push_back(pelvis_orientation_block); trajectory_names.push_back(lfoot_traj_block.traj_name); trajectory_names.push_back(rfoot_traj_block.traj_name); + trajectory_names.push_back(lhip_traj_block.traj_name); + trajectory_names.push_back(rhip_traj_block.traj_name); + trajectory_names.push_back(ltoe_traj_block.traj_name); + trajectory_names.push_back(rtoe_traj_block.traj_name); trajectory_names.push_back(com_traj_block.traj_name); trajectory_names.push_back(pelvis_orientation_block.traj_name); } @@ -211,10 +287,10 @@ int DoMain() { if (FLAGS_relative_feet) { processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + - "_processed" + "_rel"); + "_processed" + "_rel"); } else { processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + - "_processed"); + "_processed"); } return 0; } diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 288a5faaa7..96214086f7 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -16,7 +16,7 @@ #include "systems/robot_lcm_systems.h" #include "yaml-cpp/yaml.h" -#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -91,10 +91,8 @@ int DoMain(int argc, char* argv[]) { map act_map = multibody::makeNameToActuatorsMap(plant); /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - JointSpaceWalkingGains gains; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); - drake::yaml::YamlReadArchive(root).Accept(&gains); + JointSpaceWalkingGains gains = + drake::yaml::LoadYamlFile(FLAGS_gains_filename); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( diff --git a/lcm/dircon_saved_trajectory.h b/lcm/dircon_saved_trajectory.h index fb0f79d072..b4cb246735 100644 --- a/lcm/dircon_saved_trajectory.h +++ b/lcm/dircon_saved_trajectory.h @@ -49,9 +49,9 @@ class DirconTrajectory : public LcmTrajectory { const std::string& name, const std::string& description); drake::trajectories::PiecewisePolynomial ReconstructInputTrajectory() - const; + const; drake::trajectories::PiecewisePolynomial ReconstructStateTrajectory() - const; + const; drake::trajectories::PiecewisePolynomial ReconstructStateTrajectoryWithSprings(Eigen::MatrixXd&) const; drake::trajectories::PiecewisePolynomial @@ -80,25 +80,28 @@ class DirconTrajectory : public LcmTrajectory { /// variables /// A MultibodyPlant is required due to possible state and actuator indexing /// conflicts. - void LoadFromFileWithPlant(const drake::multibody::MultibodyPlant& plant, - const std::string& filepath); + void LoadFromFileWithPlant( + const drake::multibody::MultibodyPlant& plant, + const std::string& filepath); Eigen::MatrixXd GetStateSamples(int mode) const { DRAKE_DEMAND(mode >= 0); DRAKE_DEMAND(mode < num_modes_); - return x_[mode]->datapoints; + return state_map_ * x_[mode]->datapoints; } Eigen::MatrixXd GetStateDerivativeSamples(int mode) const { DRAKE_DEMAND(mode >= 0); DRAKE_DEMAND(mode < num_modes_); - return xdot_[mode]->datapoints; + return state_map_ * xdot_[mode]->datapoints; } Eigen::MatrixXd GetStateBreaks(int mode) const { DRAKE_DEMAND(mode >= 0); DRAKE_DEMAND(mode < num_modes_); return x_[mode]->time_vector; } - Eigen::MatrixXd GetInputSamples() const { return u_->datapoints; } + Eigen::MatrixXd GetInputSamples() const { + return actuator_map_ * u_->datapoints; + } Eigen::MatrixXd GetBreaks() const { return u_->time_vector; } Eigen::MatrixXd GetForceSamples(int mode) const { return lambda_[mode]->datapoints; From a8b77ed10b3c3a99c317af96ae47f435f6ae5a51 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 24 Jan 2022 17:24:56 -0500 Subject: [PATCH 090/758] small changes --- examples/Cassie/integration_test.pmd | 24 ++++++++++-------- .../jumping_0.15h_0.3d_processed_rel | Bin 7778 -> 15770 bytes .../osc/operational_space_control.cc | 3 ++- .../osc/operational_space_control.h | 4 +++ systems/robot_lcm_systems.cc | 22 ++++++++++------ 5 files changed, 34 insertions(+), 19 deletions(-) diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 656060ff51..e47817f73d 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -1,4 +1,4 @@ -group "1.controllers-and-dispatchers" { +group "1.controllers (standalone)" { cmd "osc_standing_controller (state_est)" { exec = "bazel-bin/examples/Cassie/run_osc_standing_controller --channel_x=CASSIE_STATE_DISPATCHER --height=.85"; host = "localhost"; @@ -11,10 +11,6 @@ group "1.controllers-and-dispatchers" { exec = "bazel-bin/examples/Cassie/run_osc_walking_controller --channel_x=CASSIE_STATE_DISPATCHER"; host = "localhost"; } - cmd "dispatcher_robot_out" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=true"; - host = "localhost"; - } cmd "osc_standing_controller" { exec = "bazel-bin/examples/Cassie/run_osc_standing_controller --height=.85"; host = "localhost"; @@ -23,10 +19,6 @@ group "1.controllers-and-dispatchers" { exec = "bazel-bin/examples/Cassie/run_pd_controller"; host = "localhost"; } - cmd "dispatcher_robot_in" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=CASSIE_INPUT"; - host = "localhost"; - } cmd "osc_jumping_controller" { exec = "bazel-bin/examples/Cassie/run_osc_jumping_controller --channel_u=CASSIE_INPUT --delay_time=2.0 --channel_x=CASSIE_STATE_SIMULATION --traj_name=jumping_0.15h_0.3d"; host = "localhost"; @@ -37,7 +29,19 @@ group "1.controllers-and-dispatchers" { } } -group "2.simulators" { +group "2.simulators-and-dispatchers" { + cmd "dispatcher_robot_in" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=CASSIE_INPUT"; + host = "localhost"; + } + cmd "dispatcher_robot_out" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --simulation=true"; + host = "localhost"; + } + cmd "dispatcher_robot_in (from standing)" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --control_channel_name_initial=OSC_STANDING --sim=1"; + host = "localhost"; + } cmd "cassie_sim" { exec = "bazel-bin/examples/Cassie/multibody_sim --init_height=0.9"; host = "localhost"; diff --git a/examples/impact_invariant_control/saved_trajectories/jumping_0.15h_0.3d_processed_rel b/examples/impact_invariant_control/saved_trajectories/jumping_0.15h_0.3d_processed_rel index 3b1122e98456dde305cc962ac915f745fb120a29..ae5a371166708961b7574eee5a85f8e408005b40 100644 GIT binary patch literal 15770 zcmd6O2{=_<+y9XvM9C19sglrSs>pC3Ly;j*BZWHSE3i-s@iXxK8-&s^A;Iout6waGTU^ zZFp6TZFoh+c|}AHii;oIx1U#3SX7iAYs9gfbG~3_Wpmch$-(%Xxv7(_gBz)OhlaD0 zowF0~O0AW-Bd>+61FwRyqob8M@6sqzS0PbjGhs7PlYJ86!ln{plIF(7lETKKBKsxG zM8x-rSeO{^6PDN~vfrG1KMrgJyPdi9MJq=`2V18<+*XuyF^EHxLz5d) zI8X7w(Ck_b{1-DAnu$61Ee(&+LvHQcykKaqP*fz`2ZrV+%Cs~OVdE0*B&O|Pm^1|( z4xP;A+5hpSD4h8~IFYHx2lD#@;$#LlfrfxK+qCjMkP=ibZ=4AP;nF99sxPm@T2|9o z-HP_b(KsBu+`#^^GU^yS75S+wV-g6FueR{$r;I`P>>9%#6q_OBo7B2Xk}n`YnVr#U z{2pAdCfL89KeId@-4lGfS=L<@U94@`5L`=*bW^yr(z2Y9+)4UvqkWu6tZO#(M_w=D z7Cd2k;qB_|pM2e#g}XGD$HRGQM

#Cs=O~pOg+}Lj3i6Bbeo=z-*g^;HbJb7@aS2 ze5zXyr+&Hm`)soZy+MD5>neMf$D@ZASy|p&_`?hBIz~EbdKB!v*81dJC%A2?=#+WV zg>IZyx|@3|1nE5E9(b9`ge=ab+H#FK$!t3x>mqfi1Vw$lHc>THh|*+q(jUGbhf5Vd zEy5Z0qBMpQo(R78C}p9oLF8H>%5?nh!xbHYasvVg`eipVO`q32Fu>Wt$Lie%HZD0p z_@dK@6W9okGAnaxe#C<#@l^Z)<2kUp7R%b%QUj(#CdPXRU7#$-F6~P#xIBLh8UC@v zTu9Y_pk4n9OrpF9W&Jv#uo zqx1H8lUY#ERH`U7a~6tTZ`(I<@HTw0AAEe!;3||k?;lZRVubReM;g6vyo7T1%W8bg z#}Q%v1XV!%5kzEnx_9n17a|Gt7BNZs^U-v zEd?T~X>V#wegu8jf~v#}xuEBhm(s$qEa+jrbFKV34fIf(eO;dy0X+&dv!+FH(Bo3} z;q9g==y~|AVO@te^n`^+3;W%NrrVz%d(V16EpN-hHGDBt@83dL!{K8$8fUX@rqIIo`1TNuDKu4k`uW=pa%j4>KaM(2 z5sk{cyBlNi8KqOwP^oR7gI5+->b`3a0+M!n$oVZCCAtj@>K|GS&&q`Y^>ZBIq2;Pm zd3hfp`Z#m;%XD+FaCm)}&EW_1i$^>hrj*3Gjb{ORmFsYJpuELXEVj z-#wGcnw{P+i}9b}fVv)!CbS@z`=*?LbyBHfqC#SP)##uz!Tj~)5!aRu`9V+G}d)k>xnK6Lq*Qh@gx*muwDj%dWF96Xz zOYe<9AP`Se__#IWfv7Dk@qMt|+)A-csdNSX6~?&1 zC%-!DqB^>1aLcXY4kdCWnyeN3sEO>)ow(PY;EJ3@2cr$zlaRH-^sNE~Ii#Peu`4sN zWQ8$?R~5f>D!+<;%vk@-4D3XoY=<}^l-|SpM7e7wQeOe-1mEyhmVo4q_|q3X#vtNK z%k2pE?U@TtY;R{YFc273f?X7FnwB2mAw$M&*=~CC5od&Mf{1Y z-{Rp}+;+aQX(4!M)Aq7DxEZ4Lg}%O;Wm{s5HvBplqo3n9_(k447IX6mr;Kf=lxd)_dwW4lR%{jX&+y0{SU?<7Z(|W zTwG*~#SY7ivDoKN)CyxP^<3tJrLKP>R~UnRQDj)y{$4Ts*JVb9*q+HlL$g3a?iVv; zTr2c}j0{CaWMmobBI71W0WxxB9wgzsT9q#<$6gK#9UCeeaz3j1Rt%MOmv39&v>(H- zc~88fQCa^frbBB(vG${u1wn?WYheeL2!rd1DC@$D zMxdjod3z#S7->fcwqJdlicU+_@Qj9G^wwcB-VZHE%CtAC$5}IL_3Z|SoliWG9+h0v z%p?wJ=(z^GH^3o5=h$FN2^%UA0XqQZBLXjI$L1&g#ih-@J~mQaQ9hF(kquCUPqS*-w`P;Q9yQ;mxeU=ybBDpL$mRgq? zgkib!Qtu^tMRqLFD?GAsNi)SPGaJW0XjUTR*WIc8Vsx((v(e}i9aFOwgnlZNjXpik zfrc#`cSX6bMct#04?1Bpsx=s?wO-`|2JgKX311$;+m1&8EL64N|7QQWX9MZr>yqRX zanKChoY&h9SW_d{h|Nlli7Y67+uit%(jF9N{Kh&?^(Bn-GZcu?4#RgrPrJSvcQoXq z)8AC+jz+cc#}Zs<&`&}}R2F?D>WTU!T;|jZ#ik8zQW^pH)tg@5;%3t(eM3{*3yX>g zxkO%J4>`uwOT3fWy!e+~l^hsyXg6~a*yul#?g+;|K@co7sysW-3eQd;2&fe#} zt=fP_0$Otdll%!R>Vh{0C|C)!0b0hz1}6yAx|Cb>t*r^`?F19~o4Vl(v+0q1n-DxB z&*l#!f)&_nqIOs|JV=EV!-H&Z{TCr3yv!bSqyp&&(StjKk9;nIR1y~X0#P(FF-_e7 z@<}u@fRb0Kml{Rt;VY?Ld(ZOwLg8$=yf-xOk@1xIRx%PSu930*L=_3QY?&jH@!E_y z3AYLx9U$X0PcG!Ss1FrCzY2L5FUnqg(+7F3&u;HM9sqf67O9@adm+y~`TOCHK*+nC z_5EsHI&$<72gqjo!xN+!}D9Fo={;}H!oXd3Gtn{4-p!C7|K2E zJMD#GRG(vQ8pL;<{G{fCAikUVe(@}ajE>2z+XqDHvRY=RNbezQ9<3*1*B%oO5XL6a<8J0UQ3z6mCf2RMxLS%(YXh_o}{r*`l0c_Pv z7VPtch!Y~OT_~vF>3Hx^*N$FzK{d0JeG4iS_x z_{f$XLdOI=aOgm$LwisF0a$K#2xV&0gXm7bolXIVL9&91o-h3~?7MYn*WDi$AnZEz zjU{H^ity@=fk~(g_~|G-7JM`9dDI>iKR~S@;suo_$O@6RO6z z2VaTdpy5QageWa$){}&fUxEx(d(i7x86l)keXc%P8{nqK?R}vYTwsn{A0uFJ5tP<% zP0BvE8l8rs{T>-j$WHMk-~0vEMd4FlAhV74k%iVxVF*0=BwzS>7QFrL+ayul137Ce z=c%}3;hRTleJ}$NS`JWiG}Q#bK=1c@|1P^F;ggAdx__S#S#j0=4c@CoVL-s`j)>D2 zy+Oe3Tkm-wml-Wg$!?!>zJV5WID};TWianm4{=IQ4$XTCPG$@`EP1a?&`1Px<8^*N z)abn@)$EoIl*x*h)=w%z8{IBlcTZ(#3l4ty>!S+PCEy5wrL$0^*l4z9+hCU3jy4WE zd6KpBzYroT!jo=U82qz3*0L}__j@k&x$nq@XKy16*K#>Qnl9^FP8T=GDYLe^_f!o& zKWjG;ptpr`VdnHH>q5*D*-NpzBy>d>2Key8qPpD_QX_Wz01M?UfX$XHg&Lri64~@r(7?>`1&jU&4G6pg~3oFBpwYqlj`XM z-wv_5HO|sQ1FH?AA)hGJ+r$MDtbCw))S%a~qYxUru8hBwYlHrwoT-+N&&k5zjRy|O z6x;Xlsp`ScXsfX7HT^Jr{GR+&W(>5?IUT-s+7d;m-90zKL_lLIX@Vupj|ohy&cnRg zF9;hvYo1I7MdH;Qg-+)S4imNnZz-$3){S446rj8RWE6o(qWG&sm^z-S+|12e#*4rs zb**GQryuH>5el;6X(6z3T-{|P9f;>V?ZUvn#tFZflqU$Wb6!=C7$Zpb1`8cuh$0+zw{bc(YDYLxWw`djNawhSL!#zneGL|AHGNzvtA)}9nFB!$UlSyd*@sa}>#auq1JeS*-R8-1Pp6jhb zt}scIcd`F|p2Iql>b{-A6fRNq)}pU6 z+&y!i`9Zs~^0d@Fun(5iFB%(wq0Df5h7k!TQZq>?OPRt(AR#@~Iu8;uQ0S6SdXDnd zBeCc`u=VhxRT}RiLAj9A<1{itieHXgJ#36aYTC+-B^ko#_`zsmiw_PN)m@EC-{*r& zRSjcyZN|ySQwK>+>`%>Z9KTFcipL?!X~#+xUL4@w_f<+@iV4jPVU zLV2zoEhOC5nJ9rF%GfByA>Jzu83}pFamEBC6+8|yRXGDU>rcO7^2VcwrE-tgrwgMS z9_li?V~mhr$#(x=(>Ubh@{ZcNwHcf?y1ChDV)O~&?RQ;qU?VEsFv)>Ka)nfbJFxj{ zYH#-rR>pzU(;`)20uB_8ofge+!2xfp#^J13YzF_i*7}MBrCG7M|H)wIvek`JW~Orm z4E<4}Qy=st=b)G6#{y5#grXpu9SRPU!^qjPyPZJ*4>rSwK3H5B+`auQ%fAs;tZoe+ zZ>NyfF;HWA(jWCj8V+9+p)gH64+r5|S5U$u;K%pV{-UXuox3!fl%E$MYy6mEi#QW* z#p>?rc+TP@oCRIN3ELZ05}->Uu6{HuAG$1$u$)Hj(DnSzN1gG@(3P7SDijzAUFDZX zHig`ThIeHhdKvLh)z3SwvpyE8vS-#zeE1I4!Qaeh22G(NnxTADS|pX&v^P&BUrF4_&X#%M^-MuN5dM~k@W+qSLH?@kb{ftl*dUt zvNX1-k%U-utn#|d%T~24!HJLW=XYnKq4a0#^oc#FZS~86RWht7hxpoElZORTTqhgW zKjs7?ZCl%huWulAVEoj$j{`)SF1;xxN(&2;UpqUFy8=T~YjvZ=>|kj0 zq^7)!&EjZ`t6g_Di30z5%r|zMA!Je#nP%?fxng68O#B|GQ0RxE^UMZu73X#!>pOh8 z6^UHPQQ0<^v%771JUIG~_DF>kfiI7jDy?B8JfLF^Vp7tDN7lC-ta6{jW4~^nuO?;? z_1dP{B;y^5dneudRDWsq*!`7}v4vUH4Rm48B)fm~Dr9P`C)Hk(gN%-!TG+Au06K4` zRyDV~3|;9`sAZ$4K;GkP?Ze-0T)scjQ7F%pkn%<+1)5FLy1yf9d{EKX)IlV*l~Y8- zOAg(x8WLPp6$z0kJg<#5A3`}+)A!PI3$s?A{8rVoDhkE#P_TWm=M236khN}-Za;cx zbhIAL8zR?xzS9FOwJ2b_>a@dwU=;9hqsG)sGjhd`Zb#3$WF##v)UOfR0C^v*yskTr zLC&5u(b#D{D41HHi1ILmyK_~Ci&zw)@n&P8Y^x~heS~=Lo)IQcAAIs=t+srYeDCHj zx90IE?rv?X{nQl{T$aM>$(jz&(sxEE6>LVg7P`I|HZr1kg-w1x_q|5QE`iQaP6b^t zlsC!_NW`B14?*t#kf8XVV_++b{a;rdUTyH+xr$yG#hy@}tFqxl(K}3Rq?Clvi$f)p zcdoRc$Cs&3KHq>)fM)k~-HY^K`5?}Jc>5^`efqIrn|C)5mEN+tw<-fsddBpAJ3SEf z3_fv7nga2-)8`}ASgh-mK~|zkArQ|z+r|6+3=pmMsnR^h#@VKxl2gHg!C@gz4pFAi z^Fa0U(a2BG^ETIt`_UEXsh+mEVCxLMf(#WJrv;%mBeiwYa0m2dYvtXPNPq$A`gypH zlR3fKPJM0vS9o`!K5@Ny4`j;lmCrap>UV)=k1A+E7i# zgF$$lfmxE~du8}_UAT}<)fdlHSkqRMI0so862&1zO{kl3CsYS(qn~o3S_~(wVZ6-B z)}1{T^?$$Hmt2(##a&m%T0H%&JE_?LQh4f5qBf9%mt{(`a&*{3xOIZ)O)(jin_3uRrU z#yK?Y7!I%c=4Z5QKtg;_;FN->A;jOydN}s207EKIr8XTb^d(0#GGc;-ypHp;zY)c- z(`vVHHHI^Nhcv=u_nLp;z&?*GKR>aSgmm&K62q*YRDm8Oobfw=C*g4a77TD%Rc-zx zlBe*hqN6Imu*-mjDp{kNbwXWO&r`7(P6+Uvv7;7nP#5}G&aKKm2F_LpO=KvltYmi z%JL6SlJ-Ga0kcs833qI2#sHVqbA?3Wz}m@RsVg4H55<&jE&uhGOV?r8QK-!wj~NMuvH}{UH~yb$c>cZ48GDie z`JmONf6C|vMDgJn=I9dO!-Y!;IiFcDA7IMfQWb9~*&(mn#OncHg;#4k3Y^4vgdAR8 zHXu=6g9hi9P24EIRX#+cLJt)_rTZE|cLo(bnxeZeXpc&c&Igz>yg^^`I(NiqgfEAe zmkmgW{necnIPwdU*`0iD>nA{Vkn+8t+D|0sOz`&{UC6C?erFGbC*+6?L}qU1S`IH` z1|*gShJE9KSamMu!FpH_KX&cmVI`PNQ6EgF#QktkQZhbqZ^1F9%&W-3t_M2&i7Jrhm3sDS~0<=)0lRL#g^@X@^* zRVi2*PirTmp8PV))4Wb31M=k>4;w5=1CcwqIuG#B25I-DE$aP2lg@6~1jpJ)Ro2 ziz+dD5w>u|%??`dqxQFgLt$T92%@wS?9@KOgk2(;`DZUB6IkdC1okFo5*Yci!%8i; z5!ffPH&xuvMiWiUQC%lm@KpPsXzNsp!)#&*r628WH1YXxUTsJyK{AS=U7)p@aAdPd ztUK#LyjuFOiwF}Z{5s}iPx+aZu&uz&mii}-AUJ<9oDL3fA51!&PmcP|TLt9ha%Y(TiUC7QG*q=!w73V=Hc3 z6v*kTcVOf&Qak*sF52N91kz|#=KFD=B?Su+wFr6#wpJseM9R_Y{XY?L-}{dzr7;w( z=O2u?fr!F--%X?g5Rq@**7A%kB63#w&dA05L&17u{UIdbG4!OHHQVWgKu>E$ABW`w z=oM4(9Qt|>dJ74|WhHdbS4KTo#6AuK>~#?gKk{XcP2F_6bz~nz9n-`|x_^cYW_3G3 zx@gG15H5>P+XG*e%Y^Q2#zU28%qxfKwNP6~H8z^G3z{Rc-8k(AR}?IVT{>(5x>0Z^ zYRowHb^}uVT6=6TK@*IqI_WK$^T3`VHvF^V0r1>(^I6`pouFDSsPWcmMn=v5G}HzT z!z*21Q~gg45a;?Nn{9j)^4O*LkG5T2ZjZqFOJn*2zKrQ5QKVFK|KGK=G>bxN?;JtldkZ#sNxB?5DNo zv_YY&uKU8XQ&G)rOS}5Kmv~m*8t$OdX9OC5;Z9>UMf~b6u3$+4Ygnj_`>u(o@r+sW zEOreEc-|ewT|{wuJX<7xDK>Hr2AlZD6|kK!@l3W3_l_`f_CeQEm{z(9)kC*A!n0W z8C)nLg9@5S)d3Vq?BVffJSBf#>VZko!*FcM*{U_GE&))(y$~<+E*$E*(^kmyMHUTjDaeW`&OjsjEeXAp zwlJH!VJoNb2J|bx)yn-wFT@`1V`Qq|3VFgw+T!U0P{%e;VgJY<`cA&MycC1ZdSTP(e02UkygPb7*N5!_ zq?n{t$5M+zM&$XP0$m5l<|_6wX6jl_^j_Zj5s~$r&+a>45s}ulxn1ZpmdM?_=2)FO zB1~NP%)Rw4A`IvBsvS*2gh8q86^^CLiQdawKMV|*-p%N^?4N)WLj;SPV8LT`c0wzt)Kq4!3|I` zQ;{cQ#D~&ZE2yfZpP`00imm&PYoo4~4brs? zHf!$Mu z%ogvC-9I@&yg&X|0hInMYeo7@jqBphGl!%Z}_7fo<+PcAOolT0Ymd>{3TrDdzh_x|C3A>G~XB@lN!% zjit|me*r~iYzb46e1aVH^vvEA6Cs2-lh(PdeED44vP&J^Jf0TiX#5U&Yp~VX>ouS| z+?KcU*U2M)?c`e#L_QP{@W$Edj0CzLaay6;QfcK}+oDUo2))dGRHHhj2^qUir&C)K zAll~mjiTKq@JR2BUTxP5oC{NXol@z6{62(>TO900A%n^bnf-K&F7+^Wc%8>!(7Uq= z{NE3)i4E%q--WfFy@vAOCs1&<;Rqi@da9rK))a`s+$}}UsPmxEFb{G2y-G_i^~0#f zGlcF=`y7nC^A1h$m4Yr`qh`ZT*hz$J1-lCdV$kcwU6r~=6WS^K;)*!Kpv~@P#TM<9 zMVGp_1%!y)yS1YWbIEI_^aXs|h+Y**)jq%X9Yq-rrl`q#qnByf*&AIv;KCNGGgqWV zA+waNpDv8#&-u@D#s8VhR~Gx0h|MJA%Z&jo}4Eb|B zgWT}@ED3Vc|Cq}C*V((j^$?TA(O+GV-1yrIlIQW;3zApB?svYSqlB@{^|Nm;9xBvG`DHc=`(Q7Yb%eTj*&HscVL z5|xpJ6k^6srG>ZpP3!gh>p9=&kLP->`+V>FbI!FRJ?5%zQA^n>BcyG7Bob-fM$Ztk zwXYXhPlv3lZ@NO)R7amz>*>a++Aj0-^VKmhF!VBB;j8E6=WVQSDww1WsGw_886roGY2}(xyc9!PHJH_8tYcp}IJXK;#O+WSuXN>SuWbkfH z?qMe-DJTj1+#!{`0BS^fdu5;HL+Qw*`()I9$jtU#Bk`EdycjVNz1fFEuq4(JCFTk| zm93~y%M>k-m(Pcq*(EQ}RR;pIJ0)-CmP#n|X*}-T{U6+ZRqt+=%!NFrc5g|QD`ctm zUk;29f{c3!xzYDEfZ1>3M3#sI=I~7!p_O-m`PILTtRoIA@$5qLO@Y8tThKT-rw3SO zv#w@5Y66x`;8qVtHL%t;3|oxdI)#ym+8G)4neo;wz-eTz&6R{y$1y~DH`PqL#-wXVeCtG zX!n#C^t=n6mfl(iwLZD}8ks6soU5Un>~Du?`>EgR(Ks^Z+=2@tWV{i&&h<{BJB2i= z@O_4sr6|#@;6kXF$r4nGVDVO?V|*guFL=;?`LhL&V<_})qj^yiT0vuI+hO4O3ho-gG_;mS5`ySAid;So#$Ig*g@7?yMrMDd-k?#o4UwCKsLMe z)HEG}6uV5j81}F)Tk?#WQ!DJ5xuQg9qVuoGhWzi_minK9;at0>4%0#j7}jrah^<$E z!HJTx4`rueASo#+S~Uc?A<}2Wo~i&>d?N2nPv$R|@l5uLe58nTA%PH-P};fx$9H!w zO%Ibm?)w8oKg`EA*NL_O{&V13e0o-O<2)$nyA~@gz=n&r4F5?T$%g1dMNv0QLm)g< zYTt;z6^7lIZ*zct0P~eEu$fIRy%#4(BGQUlQ7-4Sl)7`sY%UT&n~-1R&s z*b-%8vc!>jqJ)LaYU&j^JO0mK-aw*Y`TPYJ<$=&X->KDxULRzy0{>dwEdrxK zc;ekbqfevdcuha1Xw;?+GcV3u{FQGQX}JG7B~u=0*A*Tly^KNH=U204%Y zU7S`;;wP+_vu?jw$}ryFd!14d=Y@^7Pc&cp?!@PMS=rAwcwk$-zz5~HOzgT*6=v>7 z-OO5GY#SkNybkwYQ?xqPCXeUjgOhF+jKR`5W^Sn_B;2JCHmk!z0S|3+cCheUhLKKv z4#l1)@E_PSEmtE z9=mo%gfk8WyXYJ+j=-T!MxGn_zeN+rwOn{DQ6h2|T2P_x!6VoAVIoiyyyN&GM?+vq zDQ&4{EQYeM&=70JZn(|u%IHv}L0;YU>5OO+WT|U(-matl2&Xt}g)pp|VgG4KLlv^< ze8=vJEJN1u&`opP-H;XVMX)J35?LNz>8wj6WI5m29k-fyw%;^wsl{bvt!_Sfd?8lFEkuVn|BIXJ3 zY+_4|fE#YQxrg{P;NQu_F^>8pNE4XWl3OGLS&6GtiFz{Jnl_+^E7(Hu`BBZJm*Y?# z*ASyM`g~=R6}qUCNNB_iewz@_OP_OnOPDTVpr;k16>`BEOxOZqDisgGAku2-g>FC4 z3H#D4oni1drFj0RJxGYmT|{*NZUFms z5&Wl};p_!x9M2hCWiJL_l2n$4YY5m#EiS5Z`^N~k!z06pib)JwlcDl$@8Vw>)ow#k zCSUX0aAqmQZ%etabCU%HucKcXw+_PH*)87$6tkf@qO?6xyc*sZ3Ch2EkpLruuiGzj z_QAxk_yc{BJHPoX^Z%)25K;RE5>gsF)*oz#I1|#HQVju!9Ljp^Yf%l}dZI0)`{Q^f zx@^@ZvE7)WVRCu4&wrTHj+3+5EkLWH?zI$n1GK&&e?t8<(4v(WtcjoljrxGm+nf)y z@SsSynJPdF3x1q9P6pccjEyZX9s_M--;mIx_>WXtDekGQjGVejx#dD{k@Lpyq3JDk z22qZU0IqgPC)Nvhj{%eU^3nB0$OFQ$7pQYamFILca7Zrh0mmmlKa3d zlPbluHeiW3EEdQS8^_C{#z!OiDzV(M`>xork62r|=&+-m1vVd5#xS-Ab_bu(d^x6u zL(6*R7#$DAp@*uveEhHW{zWto6vfR-5qx})h>eR@@+Zj=#3JCcCfK~gS-+nsW|+_A zq1cZ4M}90Yeqt8y9EewKt;0V}(INH@TT)}`8p!uhcG=Jn3uS(7`%*3LLpAyP+RmQM ze`^>YP=dfqwQ@o8KJ<6u&dS;tWT zPh`}{Kl0-+CH}=0OGzB+!tY7Lk8$wMx6!YP0XT51D#g_J9CCx6I^#?Za>*YmwH(9# zPGmpj-vH3|IeBVLkqEqhsO0@*q8BEna>Sp!6NL$L_W-f{doaGeo*e&D3r1$pW2L== zfD_phb&2|9@R$4^rI4F4=c7ShKRm0rIO>;Q3hmbjzR>J6XjkA2FMMPPt!cJa3ENLX z$HjiO~-$Xd}N5!kF_>K9P#3%m5 zpEJPEp8WxNKIOFD!P6obJ+)1ugB=7nDeTtJU3S1|FN*qbsSBzKSF z)qgJc$qLN!R_iXfxdIC!3KbS$3>L4Ijp(0MkEP5*4%$aPVnyNR8ChjF zeuIiy^#|lQyuFX_4busSrd(wt7*}xce#xH4IlSJS5SVSWfsEXJRr3GYpF!?Ih3my^ z>R(X(1i9}`XlK^o1FsnPJj=5(t570y43br zWG}?_4`0xwYDWA5d2tNh%iQs(K(+*1JT65Z#Bl8FloI}W`Yv|(tByO*Nx|0L9}_On z&tuEWEAsDR2^?7S#=YMl^%uy$31JtwoO-6$3?qW|y7Fh$;9ax_u~S_cCX(KXJIW~n zC*Vs{AHy7*FUP)b&v{!doOhyahU#0}-@sW&EaUm;sVWaT=07LnpChg%Z#VRvC;Rh# frr8fD3Gp@=8N!D$pC~k+$EQn>&6J2HbNT-PKvz6s diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 52faa84f9a..0290bc8d32 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -862,6 +862,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * (*epsilon_sol_))(0) : 0; + soft_constraint_cost_ = output->soft_constraint_cost; output->tracking_data_names.clear(); output->tracking_data.clear(); @@ -989,7 +990,7 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (abs(robot_output->get_timestamp() - 5.0) < 5e-3) { + if (soft_constraint_cost_ > 1e2 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index d69a4273c6..6b74a938fa 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -362,6 +362,10 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::QuadraticCost* input_reg_cost_; double w_input_reg_ = -1; Eigen::MatrixXd W_input_reg_; + + // store costs for failure checking + mutable double total_cost_ = 0; + mutable double soft_constraint_cost_ = 0; }; } // namespace dairlib::systems::controllers diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 8a6afd5ddb..975ecb0a33 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -147,8 +147,12 @@ void RobotOutputSender::Output(const Context& context, state_msg->velocity.resize(num_velocities_); for (int i = 0; i < num_positions_; i++) { - state_msg->position[i] = state->GetAtIndex(i); state_msg->position_names[i] = ordered_position_names_[i]; + if (std::isnan(state->GetAtIndex(i))) { + state_msg->position[i] = 0; + } else { + state_msg->position[i] = state->GetAtIndex(i); + } } for (int i = 0; i < num_velocities_; i++) { state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); @@ -185,7 +189,8 @@ RobotInputReceiver::RobotInputReceiver( actuatorIndexMap_ = multibody::makeNameToActuatorsMap(plant); this->DeclareAbstractInputPort("lcmt_robot_input", drake::Value{}); - this->DeclareVectorOutputPort("u, t", TimestampedVector(num_actuators_), + this->DeclareVectorOutputPort("u, t", + TimestampedVector(num_actuators_), &RobotInputReceiver::CopyInputOut); } @@ -217,7 +222,8 @@ RobotCommandSender::RobotCommandSender( ordered_actuator_names_.push_back(plant.get_joint_actuator(i).name()); } - this->DeclareVectorInputPort("u, t", TimestampedVector(num_actuators_)); + this->DeclareVectorInputPort("u, t", + TimestampedVector(num_actuators_)); this->DeclareAbstractOutputPort("lcmt_robot_input", &RobotCommandSender::OutputCommand); } @@ -234,13 +240,13 @@ void RobotCommandSender::OutputCommand( input_msg->efforts.resize(num_actuators_); for (int i = 0; i < num_actuators_; i++) { input_msg->effort_names[i] = ordered_actuator_names_[i]; - if(std::isnan(command->GetAtIndex(i))){ + if (std::isnan(command->GetAtIndex(i))) { input_msg->efforts[i] = 0; - } - else{ + } else { input_msg->efforts[i] = command->GetAtIndex(i); - } } + } + } } } // namespace systems -} // namespace dairlib +} // namespace dairlib \ No newline at end of file From ecfac2d22a2d2d4cc286e0c98afaba0ac1a1e8cf Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 24 Jan 2022 17:28:29 -0500 Subject: [PATCH 091/758] still looking into encoder issues --- examples/Cassie/cassie_encoder.cc | 19 ++++++++++--------- examples/Cassie/cassie_encoder.h | 2 -- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/cassie_encoder.cc b/examples/Cassie/cassie_encoder.cc index 2962ca23c0..1ab49bc9a3 100644 --- a/examples/Cassie/cassie_encoder.cc +++ b/examples/Cassie/cassie_encoder.cc @@ -15,7 +15,7 @@ CassieEncoder::CassieEncoder(const drake::multibody::MultibodyPlant& pla joint_pos_indices_(joint_pos_indices), joint_vel_indices_(joint_vel_indices), ticks_per_revolution_(ticks_per_revolution){ - for (int i = 0; i < ticks_per_revolution_.size(); ++i){ + for (int i = 0; i < joint_vel_indices_.size(); ++i){ joint_filters_.push_back(std::make_unique()); } this->DeclareVectorInputPort("robot_state", @@ -27,17 +27,17 @@ CassieEncoder::CassieEncoder(const drake::multibody::MultibodyPlant& pla void CassieEncoder::UpdateFilter(const drake::systems::Context& context, systems::BasicVector* output) const { - const systems::BasicVector& input = + const systems::BasicVector& x = *this->template EvalVectorInput(context, 0); - VectorXd q = input.get_value().head(num_positions_); - VectorXd v = input.get_value().tail(num_velocities_); + VectorXd q = x.value().head(num_positions_); + VectorXd v = x.value().tail(num_velocities_); - VectorXd q_filtered = q; - VectorXd v_filtered = v; + VectorXd q_filtered = VectorXd::Zero(num_positions_); + VectorXd v_filtered = VectorXd::Zero(num_velocities_); // joint_encoders - for (int joint_index = 0; joint_index < joint_pos_indices_.size(); + for (int joint_index = 0; joint_index < joint_filters_.size(); ++joint_index) { auto filter = joint_filters_[joint_index].get(); @@ -56,6 +56,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, allzero &= filter->x[i] == 0; } if (allzero) { + std::cout << "Initializing with current encoder value:" << std::endl; // If all filter values are zero, initialize the signal array // with the current encoder value for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { @@ -67,7 +68,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, for (int i = CASSIE_JOINT_FILTER_NB - 1; i > 0; --i) { filter->x[i] = filter->x[i - 1]; } - filter->x[0] = q[joint_pos_indices_[joint_index]]; + filter->x[0] = q_filtered[joint_pos_indices_[joint_index]]; for (int i = CASSIE_JOINT_FILTER_NA - 1; i > 0; --i) { filter->y[i] = filter->y[i - 1]; } @@ -84,7 +85,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, } VectorXd x_filtered = VectorXd::Zero(num_positions_ + num_velocities_); - x_filtered << q_filtered, v_filtered; + x_filtered << q_filtered, v; // x_filtered << q, v; output->set_value(x_filtered); } diff --git a/examples/Cassie/cassie_encoder.h b/examples/Cassie/cassie_encoder.h index f25131b1ae..e94cb1764f 100644 --- a/examples/Cassie/cassie_encoder.h +++ b/examples/Cassie/cassie_encoder.h @@ -42,8 +42,6 @@ class CassieEncoder final : public drake::systems::LeafSystem { systems::BasicVector* output) const; private: - /// Unused: this filter is for the measured motor torques which are not being - /// used struct JointFilter { double x[CASSIE_JOINT_FILTER_NB]; double y[CASSIE_JOINT_FILTER_NA]; From 76fa4a10b597a86836dfc176167925fb2a37907c Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 25 Jan 2022 12:01:35 -0500 Subject: [PATCH 092/758] merge fixes --- examples/Cassie/BUILD.bazel | 4 +--- examples/Cassie/osc_run/osc_running_gains.yaml | 12 ++++++------ systems/trajectory_optimization/dircon/dircon.cc | 10 +++++----- systems/trajectory_optimization/hybrid_dircon.cc | 16 ++++++++-------- .../test/passive_constrained_pendulum_dircon.cc | 2 +- 5 files changed, 21 insertions(+), 23 deletions(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 3577069867..13be2370d7 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -45,9 +45,9 @@ cc_library( "//examples/Cassie:dispatcher_robot_out", "//examples/Cassie:multibody_sim", "//examples/Cassie:run_controller_switch", + "//examples/Cassie:run_osc_hopping_controller", "//examples/Cassie:run_osc_jumping_controller", "//examples/Cassie:run_osc_running_controller", - "//examples/Cassie:run_osc_hopping_controller", "//examples/Cassie:run_osc_standing_controller", "//examples/Cassie:run_osc_walking_controller", "//examples/Cassie/osc", @@ -382,7 +382,6 @@ cc_binary( "//systems/controllers/osc:osc_tracking_datas", "//systems/framework:lcm_driven_loop", "//systems/primitives", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -477,7 +476,6 @@ cc_binary( "//solvers:optimization_utils", "//systems/primitives", "//systems/trajectory_optimization:dircon", - "//solvers:nonlinear_cost", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 8e8639e8a7..257755a7c3 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -17,7 +17,7 @@ rest_length: 0.85 stance_duration: 0.30 flight_duration: 0.09 -mu: 0.6 +mu: 0.4 w_swing_toe: 1 swing_toe_kp: 1500 @@ -34,22 +34,22 @@ hip_yaw_kd: 15 #hip_roll_kd: 10 # Foot placement parameters footstep_offset: -0.04 -center_line_offset: 0.03 +center_line_offset: 0.04 FootstepKd: [ 0.2, 0, 0, 0, 0.4, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, - 0, 0.1, 0, + 0, 0, 0, 0, 0, 5] PelvisKp: [ 0, 0, 0, - 0, 1, 0, + 0, 0, 0, 0, 0, 95] PelvisKd: [ 1, 0, 0, - 0, 5, 0, + 0, 0, 0, 0, 0, 5] PelvisRotW: [0.1, 0, 0, @@ -60,7 +60,7 @@ PelvisRotKp: 0, 50, 0, 0, 0, 0] PelvisRotKd: - [5, 0, 0, + [15, 0, 0, 0, 10, 0, 0, 0, 0] SwingFootW: diff --git a/systems/trajectory_optimization/dircon/dircon.cc b/systems/trajectory_optimization/dircon/dircon.cc index ad72a4afc3..43a05f57a0 100644 --- a/systems/trajectory_optimization/dircon/dircon.cc +++ b/systems/trajectory_optimization/dircon/dircon.cc @@ -152,7 +152,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, plant_, mode.evaluators(), contexts_[i_mode].at(j).get(), contexts_[i_mode].at(j + 1).get(), i_mode, j, cache_[i_mode].get()); constraint->SetConstraintScaling(mode.GetDynamicsScale()); - this->prog().AddConstraint( + this->AddConstraint( constraint, {timestep(mode_start_[i_mode] + j), state_vars(i_mode, j), state_vars(i_mode, j + 1), input_vars(i_mode, j), @@ -192,7 +192,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, "kinematic_position[" + std::to_string(i_mode) + "][" + std::to_string(j) + "]"); pos_constraint->SetConstraintScaling(mode.GetKinPositionScale()); - this->prog().AddConstraint(pos_constraint, + this->AddConstraint(pos_constraint, {state_vars(i_mode, j).head(plant_.num_positions()), offset_vars(i_mode)}); } @@ -211,7 +211,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, "kinematic_velocity[" + std::to_string(i_mode) + "][" + std::to_string(j) + "]"); vel_constraint->SetConstraintScaling(mode.GetKinVelocityScale()); - this->prog().AddConstraint(vel_constraint, state_vars(i_mode, j)); + this->AddConstraint(vel_constraint, state_vars(i_mode, j)); } } @@ -222,7 +222,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, std::to_string(j) + "]", cache_[i_mode].get()); accel_constraint->SetConstraintScaling(mode.GetKinAccelerationScale()); - this->prog().AddConstraint(accel_constraint, + this->AddConstraint(accel_constraint, {state_vars(i_mode, j), input_vars(i_mode, j), force_vars(i_mode, j)}); } @@ -243,7 +243,7 @@ Dircon::Dircon(std::unique_ptr> my_sequence, "impact[" + std::to_string(i_mode) + "]"); impact_constraint->SetConstraintScaling(mode.GetImpactScale()); - this->prog().AddConstraint( + this->AddConstraint( impact_constraint, {state_vars(i_mode - 1, pre_impact_index), impulse_vars(i_mode - 1), post_impact_velocity_vars(i_mode - 1)}); diff --git a/systems/trajectory_optimization/hybrid_dircon.cc b/systems/trajectory_optimization/hybrid_dircon.cc index bc7a4606ba..9a08d791db 100644 --- a/systems/trajectory_optimization/hybrid_dircon.cc +++ b/systems/trajectory_optimization/hybrid_dircon.cc @@ -144,7 +144,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getDynConstraintScaling()); for (int j = 0; j < mode_lengths_[i] - 1; j++) { int time_index = mode_start_[i] + j; - this->prog().AddConstraint( + this->AddConstraint( dynamic_constraint, {h_vars().segment(time_index, 1), state_vars_by_mode(i, j), state_vars_by_mode(i, j + 1), @@ -168,7 +168,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getKinConstraintScaling()); for (int j = 1; j < mode_lengths_[i] - 1; j++) { int time_index = mode_start_[i] + j; - this->prog().AddConstraint( + this->AddConstraint( kinematic_constraint, {state_vars_by_mode(i, j), u_vars().segment(time_index * num_inputs(), num_inputs()), @@ -184,7 +184,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getStartType()); kinematic_constraint_start->SetConstraintScaling( options[i].getKinConstraintScalingStart()); - this->prog().AddConstraint( + this->AddConstraint( kinematic_constraint_start, {state_vars_by_mode(i, 0), u_vars().segment(mode_start_[i] * num_inputs(), num_inputs()), @@ -202,7 +202,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, options[i].getEndType()); kinematic_constraint_end->SetConstraintScaling( options[i].getKinConstraintScalingEnd()); - this->prog().AddConstraint( + this->AddConstraint( kinematic_constraint_end, {state_vars_by_mode(i, mode_lengths_[i] - 1), u_vars().segment( @@ -221,7 +221,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, DirconKinematicData* constraint_j = constraints_[i]->getConstraint(j); for (int k = 0; k < constraint_j->numForceConstraints(); k++) { - this->prog().AddConstraint( + this->AddConstraint( constraint_j->getForceConstraint(k), force_vars(i).segment(start_index, constraint_j->getLength())); } @@ -247,7 +247,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, plant_, *constraints_[i]); impact_constraint->SetConstraintScaling( options[i].getImpConstraintScaling()); - this->prog().AddConstraint(impact_constraint, + this->AddConstraint(impact_constraint, {state_vars_by_mode(i - 1, mode_lengths_[i - 1] - 1), impulse_vars(i - 1), v_post_impact_vars_by_mode(i - 1)}); @@ -257,7 +257,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, DirconKinematicData* constraint_j = constraints_[i]->getConstraint(j); for (int k = 0; k < constraint_j->numForceConstraints(); k++) { - this->prog().AddConstraint(constraint_j->getForceConstraint(k), + this->AddConstraint(constraint_j->getForceConstraint(k), impulse_vars(i - 1).segment( start_index, constraint_j->getLength())); } @@ -266,7 +266,7 @@ HybridDircon::HybridDircon(const MultibodyPlant& plant, } else { auto x_vars_prev = state_vars_by_mode(i - 1, mode_lengths_[i - 1] - 1); - this->prog().AddConstraint(v_post_impact_vars_by_mode(i - 1) == + this->AddConstraint(v_post_impact_vars_by_mode(i - 1) == x_vars_prev.tail(plant.num_velocities())); } } diff --git a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc index 75f3e0afa0..02408e4995 100644 --- a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc @@ -107,7 +107,7 @@ void runDircon() { auto start = std::chrono::high_resolution_clock::now(); auto solver = drake::solvers::SnoptSolver(); - const auto result = solver.Solve(trajopt->prog(), trajopt->initial_guess()); + const auto result = solver.Solve(*trajopt, trajopt->initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; std::cout << "Solve time:" << elapsed.count() < Date: Thu, 27 Jan 2022 11:53:50 -0500 Subject: [PATCH 093/758] small adjustments --- .../pydairlib/analysis/log_plotter_cassie.py | 3 +- bindings/pydairlib/analysis/osc_debug.py | 12 ++-- .../plot_configs/cassie_running_plot.yaml | 18 +++--- examples/Cassie/BUILD.bazel | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 3 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 4 +- .../Cassie/osc_run/osc_running_gains.yaml | 30 ++++----- examples/Cassie/run_dircon_jumping.cc | 62 ++++++++++--------- examples/Cassie/run_osc_running_controller.cc | 10 +-- ...=> cassie_fixed_springs_conservative.urdf} | 0 .../impact_aware_time_based_fsm.cc | 13 +++- lcm/dircon_saved_trajectory.cc | 14 ++--- .../osc/operational_space_control.cc | 42 +++++++------ 14 files changed, 112 insertions(+), 103 deletions(-) rename examples/Cassie/urdf/{cassie_fixed_spring_conservative.urdf => cassie_fixed_springs_conservative.urdf} (100%) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 82a405d8f4..d85d647646 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -113,7 +113,8 @@ def main(): foot_frames, pts, dims) if plot_config.plot_qp_solve_time: - mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.25) plt.show() diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 2efc621ba4..bf294a55ee 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -1,10 +1,11 @@ import numpy as np from math import nan + # Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays class lcmt_osc_tracking_data_t: def __init__(self, gap_threshold=0.01): - self.t_thresh=gap_threshold + self.t_thresh = gap_threshold self.t = [] self.y_dim = 0 self.name = "" @@ -23,9 +24,6 @@ def append(self, msg, t): self.y_dim = len(msg.y) self.ydot_dim = len(msg.ydot) - # If there is a large gap between tracking datas, append - # NaNs as a mask for plotting to avoid fictitious lines - # appearing in plots if self.t and (t - self.t[-1]) > self.t_thresh: self.t.append(nan) self.is_active.append(nan) @@ -78,9 +76,9 @@ def append(self, tracking_data_list, tracking_cost_list): for name, cost in zip(tracking_data_list, tracking_cost_list): self.tracking_costs[name].append(cost) - for name in self.tracking_costs: - if name not in tracking_data_list: - self.tracking_costs[name].append(0.0) + # for name in self.tracking_costs: + # if name not in tracking_data_list: + # self.tracking_costs[name].append(0.0) def convertToNP(self): for name in self.tracking_costs: diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1b8fd3a200..1e401fd618 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -27,13 +27,15 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['accel']} - # hip_yaw_left_traj: {'dims': [0], 'derivs': ['pos']} - # hip_roll_left_traj: {'dims': [0], 'derivs': ['pos']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} +# hip_roll_left_traj: {'dims': [0], 'derivs': ['vel']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} - right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + left_ft_traj: {'dims': [2], 'derivs': ['vel']} + right_ft_traj: {'dims': [2], 'derivs': ['vel']} + left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} + right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} +# left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} +# right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 13be2370d7..9ee378ee73 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -465,8 +465,8 @@ cc_binary( cc_binary( name = "run_dircon_jumping", srcs = ["run_dircon_jumping.cc"], - data = glob(["examples/Cassie/urdf/*.urdf"]), deps = [ + ":cassie_urdf", ":cassie_utils", "//common", "//lcm:dircon_trajectory_saver", diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index d426d23415..9056b6efa8 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -59,6 +59,7 @@ DEFINE_double(publish_rate, 2000, "Publish rate for simulator"); DEFINE_double(init_height, .7, "Initial starting height of the pelvis above " "ground"); +DEFINE_string(channel_u, "CASSIE_INPUT", "LCM channel to receive controller commands from"); DEFINE_double(platform_height, 0.0, "Height of the platform"); DEFINE_double(platform_x, 0.0, "x location of the platform"); DEFINE_double(start_time, 0.0, @@ -126,7 +127,7 @@ int do_main(int argc, char* argv[]) { auto lcm = builder.AddSystem(); auto input_sub = builder.AddSystem(LcmSubscriberSystem::Make( - "CASSIE_INPUT", lcm)); + FLAGS_channel_u, lcm)); auto input_receiver = builder.AddSystem(plant); auto passthrough = builder.AddSystem( input_receiver->get_output_port(0).size(), 0, diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index f4ebb654d9..49f3ccb49f 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -2,7 +2,7 @@ w_input: 0.000 w_accel: 0.0000001 w_input_reg: 0.01 w_soft_constraint: 100 -x_offset: 0.025 +x_offset: 0.0 relative_feet: true mu: 0.8 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 9e35223c0b..2ecb65d382 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -174,12 +174,12 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector T_waypoints_2; T_waypoints = {state_durations_[1], state_durations_[1] + - 2.0 / 3.0 * (state_durations_[4] - state_durations_[1]), + 1.5 / 3.0 * (state_durations_[4] - state_durations_[1]), state_durations_[4]}; T_waypoints_0 = { state_durations_[0], (state_durations_[3] - state_durations_[4]) + - 2.0 / 3.0 * (0.1 + state_durations_[2] - state_durations_[0]), + 1.5 / 3.0 * (0.1 + state_durations_[2] - state_durations_[0]), state_durations_[2]}; T_waypoints_1 = {state_durations_[2], state_durations_[3]}; T_waypoints_2 = {state_durations_[3], state_durations_[4]}; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 257755a7c3..ae3e5381fc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,4 +1,4 @@ -w_input: 0.0000000000 +w_input: 0.00000 w_accel: 0.00000 #w_soft_constraint: 1000000 w_soft_constraint: 0.01 @@ -15,7 +15,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.85 stance_duration: 0.30 -flight_duration: 0.09 +flight_duration: 0.08 mu: 0.4 @@ -24,17 +24,11 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 1 -hip_yaw_kp: 100 -hip_yaw_kd: 15 -#w_hip_pitch: 5 -#hip_pitch_kp: 100 -#hip_pitch_kd: 10 -#w_hip_roll: 5 -#hip_roll_kp: 50 -#hip_roll_kd: 10 +hip_yaw_kp: 200 +hip_yaw_kd: 20 # Foot placement parameters -footstep_offset: -0.04 -center_line_offset: 0.04 +footstep_offset: -0.05 +center_line_offset: 0.05 FootstepKd: [ 0.2, 0, 0, 0, 0.4, 0, @@ -46,21 +40,21 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 95] + 0, 0, 85] PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [0.1, 0, 0, - 0, 0.05, 0, + [1, 0, 0, + 0, 0.1, 0, 0, 0, 0] PelvisRotKp: [50, 0, 0, 0, 50, 0, 0, 0, 0] PelvisRotKd: - [15, 0, 0, + [10, 0, 0, 0, 10, 0, 0, 0, 0] SwingFootW: @@ -77,12 +71,12 @@ SwingFootKd: 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, - 0, 1, 0, + 0, 10, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, - 0, 0, 10] + 0, 0, 50] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 625967f547..381e1df4cb 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -64,7 +64,6 @@ using drake::solvers::MatrixXDecisionVariable; using drake::solvers::SolutionResult; using drake::solvers::VectorXDecisionVariable; using drake::systems::trajectory_optimization::MultipleShooting; -using drake::trajectories::PiecewisePolynomial; DEFINE_int32(knot_points, 10, "Number of knot points per contact mode"); DEFINE_double(height, 0.2, "Target height for jumping."); @@ -115,9 +114,9 @@ class JointAccelCost : public solvers::NonlinearCost { const KinematicEvaluatorSet* constraints, const std::string& description = "") : solvers::NonlinearCost( - plant.num_positions() + plant.num_velocities() + - plant.num_actuators() + constraints->count_full(), - description), + plant.num_positions() + plant.num_velocities() + + plant.num_actuators() + constraints->count_full(), + description), plant_(plant), context_(plant_.CreateDefaultContext()), constraints_(constraints), @@ -379,8 +378,8 @@ void DoMain() { std::cout << "Cost:" << result.get_optimal_cost() << std::endl; std::cout << "Solve result: " << result.get_solution_result() << std::endl; - std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) - << std::endl; +// std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) +// << std::endl; // Save trajectory to file DirconTrajectory saved_traj(plant, trajopt, result, "jumping_trajectory", @@ -468,9 +467,16 @@ void SetKinematicConstraints(Dircon* trajopt, // Jumping height constraints trajopt->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); - trajopt->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, - FLAGS_height + rest_height + eps, - x_top(pos_map.at("base_z"))); + if (FLAGS_height < 0) { + trajopt->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, + 0.5 * FLAGS_height + rest_height - eps, + x_top(pos_map.at("base_z"))); + + } else { + trajopt->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, + FLAGS_height + rest_height + eps, + x_top(pos_map.at("base_z"))); + } trajopt->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, 0.8 * FLAGS_height + rest_height + eps, x_f(pos_map.at("base_z"))); @@ -519,17 +525,17 @@ void SetKinematicConstraints(Dircon* trajopt, for (const auto& sym_joint_name : sym_joint_names) { trajopt->AddConstraintToAllKnotPoints( x_0(pos_map[sym_joint_name + l_r_pair.first]) == - x_0(pos_map[sym_joint_name + l_r_pair.second])); + x_0(pos_map[sym_joint_name + l_r_pair.second])); trajopt->AddLinearConstraint( x_f(pos_map[sym_joint_name + l_r_pair.first]) == - x_f(pos_map[sym_joint_name + l_r_pair.second])); + x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle trajopt->AddConstraintToAllKnotPoints( u_0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - u_0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + u_0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); trajopt->AddConstraintToAllKnotPoints( u_f(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - u_f(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + u_f(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); } } } @@ -540,10 +546,10 @@ void SetKinematicConstraints(Dircon* trajopt, for (const auto& member : joint_names) { trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) <= - plant.GetJointByName(member).position_upper_limits()(0)); + plant.GetJointByName(member).position_upper_limits()(0)); trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) >= - plant.GetJointByName(member).position_lower_limits()(0)); + plant.GetJointByName(member).position_lower_limits()(0)); } // actuator limits @@ -732,15 +738,15 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - - x(pos_map.at(sym_joint_name + l_r_pair.second)); + x(pos_map.at(sym_joint_name + l_r_pair.second)); auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - - x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); + x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); if (sym_joint_name != "ankle_joint") { auto act_diff = u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); } } @@ -748,15 +754,15 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, for (const auto& l_r_pair : l_r_pairs) { for (const auto& asy_joint_name : asy_joint_names) { auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + - x(pos_map.at(asy_joint_name + l_r_pair.second)); + x(pos_map.at(asy_joint_name + l_r_pair.second)); auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + - x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); + x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); if (asy_joint_name != "ankle_joint") { auto act_diff = u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); } } @@ -852,9 +858,9 @@ void AddCostsSprings(Dircon* trajopt, for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - - x(pos_map[sym_joint_name + l_r_pair.second]); + x(pos_map[sym_joint_name + l_r_pair.second]); auto vel_diff = x(vel_map[sym_joint_name + l_r_pair.first + "dot"]) - - x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); + x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); } @@ -909,7 +915,7 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, previous_traj.GetDecisionVariables()); return; } - PiecewisePolynomial state_traj; + drake::trajectories::PiecewisePolynomial state_traj; if (FLAGS_use_springs && FLAGS_convert_to_springs) { std::cout << "Using spring conversion" << std::endl; state_traj = previous_traj.ReconstructStateTrajectoryWithSprings(spr_map); @@ -922,10 +928,10 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); trajopt.SetInitialTrajectory(input_traj, state_traj); - for (int mode = 0; mode < trajopt.num_modes(); ++mode) { - trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], - lambda_c_traj[mode], gamma_traj[mode]); - } +// for (int mode = 0; mode < trajopt.num_modes(); ++mode) { +// trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], +// lambda_c_traj[mode], gamma_traj[mode]); +// } } } // namespace dairlib diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index bc5972445b..a0f869c80a 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -320,12 +320,6 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, "toe_right"); -// TransTaskSpaceTrackingData left_hip_tracking_data( -// "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, -// osc_gains.W_swing_foot, plant, plant); -// TransTaskSpaceTrackingData right_hip_tracking_data( -// "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, -// osc_gains.W_swing_foot, plant, plant); TransTaskSpaceTrackingData left_hip_tracking_data( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); @@ -380,8 +374,8 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); +// left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); +// right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); diff --git a/examples/Cassie/urdf/cassie_fixed_spring_conservative.urdf b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf similarity index 100% rename from examples/Cassie/urdf/cassie_fixed_spring_conservative.urdf rename to examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index c3482a3a2a..170cda090c 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -37,6 +37,8 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( // Accumulate the durations to get timestamps double sum = 0; DRAKE_DEMAND(states.size() == state_durations.size()); + impact_times_.push_back(0); + impact_states_.push_back(states[0]); for (int i = 0; i < states.size(); ++i) { sum += state_durations[i]; accu_state_durations_.push_back(sum); @@ -46,6 +48,11 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( } } + std::cout << "Impact times: " << std::endl; + for(int i = 0; i < impact_times_.size(); ++i){ + std::cout << impact_times_[i] << std::endl; + } + period_ = sum; } @@ -76,9 +83,9 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( // Get current finite state if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { - if (impact_states_[i] == 2) { - continue; - } +// if (impact_states_[i] > 2) { +// continue; +// } double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ : near_impact_threshold_; diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index 840dd70557..c77850ead1 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -64,13 +64,13 @@ DirconTrajectory::DirconTrajectory( num_forces, force_traj.time_vector.size()); // Impulse vars - if (mode > 0) { - impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); - impulse_traj.datatypes = impulse_names; - // Get start of mode to get time of impulse - impulse_traj.time_vector = state_breaks[mode].segment(0, 1); - impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode)); - } +// if (mode < num_modes_ - 1) { +// impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); +// impulse_traj.datatypes = impulse_names; +// // Get start of mode to get time of impulse +// impulse_traj.time_vector = state_breaks[mode].segment(0, 1); +// impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode)); +// } // Collocation force vars if (state_breaks[mode].size() > 1) { diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f899f199dc..4239f37f56 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -101,10 +101,10 @@ OperationalSpaceControl::OperationalSpaceControl( "lcmt_osc_debug", &OperationalSpaceControl::AssignOscLcmOutput) .get_index(); - failure_port_ = - this->DeclareVectorOutputPort("failure_signal", TimestampedVector(1), - &OperationalSpaceControl::CheckTracking) - .get_index(); + failure_port_ = this->DeclareVectorOutputPort( + "failure_signal", TimestampedVector(1), + &OperationalSpaceControl::CheckTracking) + .get_index(); const std::map& vel_map_wo_spr = multibody::makeNameToVelocitiesMap(plant_wo_spr); @@ -761,11 +761,7 @@ VectorXd OperationalSpaceControl::SolveQp( const MathematicalProgramResult result = solver_->Solve(*prog_); solve_time_ = result.get_solver_details().run_time; - - // if (result.get_optimal_cost() < -1e6) { - // std::cout << "qp cost: " << result.get_optimal_cost() << std::endl; - // return VectorXd::Zero(n_u_); - // } + // solve_time_ = alpha; // Extract solutions *dv_sol_ = result.GetSolution(dv_); @@ -844,8 +840,8 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( for (auto tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { - A.block(start_row, 0, tracking_data->GetYdotDim(), active_constraint_dim) = - tracking_data->GetJ() * M_Jt_; + A.block(start_row, 0, tracking_data->GetYdotDim(), + active_constraint_dim) = tracking_data->GetJ() * M_Jt_; ydot_err_vec.segment(start_row, tracking_data->GetYdotDim()) = tracking_data->GetErrorYdot(); start_row += tracking_data->GetYdotDim(); @@ -922,15 +918,25 @@ void OperationalSpaceControl::AssignOscLcmOutput( auto tracking_data = tracking_data_vec_->at(i); output->tracking_data_names[i] = tracking_data->GetName(); + lcmt_osc_tracking_data osc_output; + osc_output.y_dim = tracking_data->GetYDim(); + osc_output.ydot_dim = tracking_data->GetYdotDim(); + osc_output.name = tracking_data->GetName(); + osc_output.is_active = tracking_data->IsActive(fsm_state); + osc_output.y = std::vector(osc_output.y_dim); + osc_output.y_des = std::vector(osc_output.y_dim); + osc_output.error_y = std::vector(osc_output.ydot_dim); + osc_output.ydot = std::vector(osc_output.ydot_dim); + osc_output.ydot_des = std::vector(osc_output.ydot_dim); + osc_output.error_ydot = std::vector(osc_output.ydot_dim); + osc_output.yddot_des = std::vector(osc_output.ydot_dim); + osc_output.yddot_command = std::vector(osc_output.ydot_dim); + osc_output.yddot_command_sol = std::vector(osc_output.ydot_dim); + + output->tracking_cost[i] = 0; if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && time_since_last_state_switch <= t_e_vec_.at(i)) { - lcmt_osc_tracking_data osc_output; - osc_output.y_dim = tracking_data->GetYDim(); - osc_output.ydot_dim = tracking_data->GetYdotDim(); - osc_output.name = tracking_data->GetName(); - // This should always be true - osc_output.is_active = tracking_data->IsActive(fsm_state); osc_output.y = CopyVectorXdToStdVector(tracking_data->GetY()); osc_output.y_des = CopyVectorXdToStdVector(tracking_data->GetYDes()); osc_output.error_y = CopyVectorXdToStdVector(tracking_data->GetErrorY()); @@ -945,7 +951,6 @@ void OperationalSpaceControl::AssignOscLcmOutput( CopyVectorXdToStdVector(tracking_data->GetYddotCommand()); osc_output.yddot_command_sol = CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); - output->tracking_data[i] = osc_output; const VectorXd& ddy_t = tracking_data->GetYddotCommand(); const MatrixXd& W = tracking_data->GetWeight(); @@ -956,6 +961,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); total_cost_ += output->tracking_cost[i]; } + output->tracking_data[i] = osc_output; } output->num_tracking_data = output->tracking_data_names.size(); From 4792f222cdc1152812d5987a202c773e903d9bd4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 28 Jan 2022 13:13:17 -0500 Subject: [PATCH 094/758] small changes, found a memory leak in fastosqp --- examples/Cassie/osc/high_level_command.h | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 10 ++-- examples/Cassie/run_dircon_jumping.cc | 4 -- examples/Cassie/run_osc_hopping_controller.cc | 2 +- examples/Cassie/run_osc_running_controller.cc | 13 ++--- examples/Cassie/run_osc_walking_controller.cc | 2 +- solvers/fast_osqp_solver.cc | 47 +++++++++++++------ .../osc/operational_space_control.cc | 32 ++++--------- .../osc/operational_space_control.h | 11 +---- 9 files changed, 55 insertions(+), 68 deletions(-) diff --git a/examples/Cassie/osc/high_level_command.h b/examples/Cassie/osc/high_level_command.h index d977fed94e..4027d2ee64 100644 --- a/examples/Cassie/osc/high_level_command.h +++ b/examples/Cassie/osc/high_level_command.h @@ -75,7 +75,7 @@ class HighLevelCommand : public drake::systems::LeafSystem { const drake::systems::OutputPort& get_yaw_output_port() const { return this->get_output_port(yaw_port_); } - const drake::systems::InputPort& get_cassie_output_port() const { + const drake::systems::InputPort& get_cassie_out_input_port() const { return this->get_input_port(cassie_out_port_); } const drake::systems::OutputPort& get_xy_output_port() const { diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index ae3e5381fc..05e413ecb3 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,5 +1,5 @@ -w_input: 0.00000 -w_accel: 0.00000 +w_input: 0.000001 +w_accel: 0.000001 #w_soft_constraint: 1000000 w_soft_constraint: 0.01 w_input_reg: 0.01 @@ -48,15 +48,15 @@ PelvisKd: PelvisRotW: [1, 0, 0, 0, 0.1, 0, - 0, 0, 0] + 0, 0, 1] PelvisRotKp: [50, 0, 0, 0, 50, 0, - 0, 0, 0] + 0, 0, 0] PelvisRotKd: [10, 0, 0, 0, 10, 0, - 0, 0, 0] + 0, 0, 10] SwingFootW: [50, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 381e1df4cb..c945610eef 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -359,7 +359,6 @@ void DoMain() { SetInitialGuessFromTrajectory(trajopt, plant, FLAGS_data_directory + FLAGS_load_filename, FLAGS_same_knotpoints, spr_map); - // trajopt->SetInitialGuessForAllVariables(decisionVars); } double alpha = .2; @@ -378,9 +377,6 @@ void DoMain() { std::cout << "Cost:" << result.get_optimal_cost() << std::endl; std::cout << "Solve result: " << result.get_solution_result() << std::endl; -// std::cout << "Lambda sol: " << result.GetSolution(trajopt.impulse_vars(1)) -// << std::endl; - // Save trajectory to file DirconTrajectory saved_traj(plant, trajopt, result, "jumping_trajectory", "Decision variables and state/input trajectories " diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index b2e3f95770..db67b08aae 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -255,7 +255,7 @@ int DoMain(int argc, char* argv[]) { plant, plant_context.get(), osc_gains.vel_scale_rot, osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_output_port()); + high_level_command->get_cassie_out_input_port()); auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index a0f869c80a..4b3f513df0 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -115,7 +115,6 @@ int DoMain(int argc, char* argv[]) { map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); - std::unordered_map< int, std::vector&>>> @@ -259,7 +258,7 @@ int DoMain(int argc, char* argv[]) { plant, plant_context.get(), osc_gains.vel_scale_rot, osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_output_port()); + high_level_command->get_cassie_out_input_port()); auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = @@ -326,10 +325,8 @@ int DoMain(int argc, char* argv[]) { TransTaskSpaceTrackingData right_hip_tracking_data( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, - "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, - "pelvis"); + left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); + right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, "pelvis"); left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, @@ -374,8 +371,8 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); -// left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); -// right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index c79f49f37a..2a69b1aea2 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -177,7 +177,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_output_port()); + high_level_command->get_cassie_out_input_port()); } else { high_level_command = builder.AddSystem( plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 7942239bf5..a31e2bb254 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -105,7 +105,8 @@ void ParseLinearConstraints( const MathematicalProgram& prog, const std::vector>& linear_constraints, std::vector>* A_triplets, std::vector* l, - std::vector* u, int* num_A_rows) { + std::vector* u, int* num_A_rows, + std::unordered_map, int>* constraint_start_row) { // Loop over the linear constraints, stack them to get l, u and A. for (const auto& constraint : linear_constraints) { const std::vector x_indices = @@ -114,7 +115,7 @@ void ParseLinearConstraints( SparseMatrixToTriplets(constraint.evaluator()->A()); const Binding constraint_cast = BindingDynamicCast(constraint); -// constraint_start_row->emplace(constraint_cast, *num_A_rows); + constraint_start_row->emplace(constraint_cast, *num_A_rows); // Append constraint.A to osqp A. for (const auto& Ai_triplet : Ai_triplets) { A_triplets->emplace_back(*num_A_rows + Ai_triplet.row(), @@ -135,11 +136,13 @@ void ParseLinearConstraints( void ParseBoundingBoxConstraints( const MathematicalProgram& prog, std::vector>* A_triplets, std::vector* l, - std::vector* u, int* num_A_rows) { + std::vector* u, int* num_A_rows, + std::unordered_map, int>* constraint_start_row) { // Loop over the linear constraints, stack them to get l, u and A. for (const auto& constraint : prog.bounding_box_constraints()) { const Binding constraint_cast = BindingDynamicCast(constraint); + constraint_start_row->emplace(constraint_cast, *num_A_rows); // Append constraint.A to osqp A. for (int i = 0; i < static_cast(constraint.GetNumElements()); ++i) { A_triplets->emplace_back( @@ -160,16 +163,18 @@ void ParseBoundingBoxConstraints( void ParseAllLinearConstraints( const MathematicalProgram& prog, Eigen::SparseMatrix* A, - std::vector* l, std::vector* u) { + std::vector* l, std::vector* u, + std::unordered_map, int>* constraint_start_row) { std::vector> A_triplets; l->clear(); u->clear(); int num_A_rows = 0; ParseLinearConstraints(prog, prog.linear_constraints(), &A_triplets, l, u, - &num_A_rows); + &num_A_rows, constraint_start_row); ParseLinearConstraints(prog, prog.linear_equality_constraints(), &A_triplets, - l, u, &num_A_rows); - ParseBoundingBoxConstraints(prog, &A_triplets, l, u, &num_A_rows); + l, u, &num_A_rows, constraint_start_row); + ParseBoundingBoxConstraints(prog, &A_triplets, l, u, &num_A_rows, + constraint_start_row); A->resize(num_A_rows, prog.num_vars()); A->setFromTriplets(A_triplets.begin(), A_triplets.end()); } @@ -199,9 +204,9 @@ csc* EigenSparseToCSC(const Eigen::SparseMatrix& mat) { } template -void SetFastOsqpSolverSetting( - const std::unordered_map& options, - const std::string& option_name, T2* osqp_setting_field) { +void SetFastOsqpSolverSetting(const std::unordered_map& options, + const std::string& option_name, + T2* osqp_setting_field) { const auto it = options.find(option_name); if (it != options.end()) { *osqp_setting_field = it->second; @@ -295,12 +300,12 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, // linear_constraint_start_row[binding] stores the starting row index in A // corresponding to the linear constraint `binding`. -// std::unordered_map, int> constraint_start_row; + std::unordered_map, int> constraint_start_row; // Parse the linear constraints. Eigen::SparseMatrix A_sparse; std::vector l, u; - ParseAllLinearConstraints(prog, &A_sparse, &l, &u); + ParseAllLinearConstraints(prog, &A_sparse, &l, &u, &constraint_start_row); // Now pass the constraint and cost to osqp data. osqp_data_ = nullptr; @@ -340,7 +345,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, "OsqpSolver doesn't support the feature of variable scaling."); } - OsqpSolverDetails& solver_details = + auto solver_details = result->SetSolverDetailsType(); // OSQP solves a convex quadratic programming problem @@ -356,10 +361,14 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, ParseQuadraticCosts(prog, &P_sparse, &q, &constant_cost_term); ParseLinearCosts(prog, &q, &constant_cost_term); + // linear_constraint_start_row[binding] stores the starting row index in A + // corresponding to the linear constraint `binding`. + std::unordered_map, int> constraint_start_row; + // Parse the linear constraints. Eigen::SparseMatrix A_sparse; std::vector l, u; - ParseAllLinearConstraints(prog, &A_sparse, &l, &u); + ParseAllLinearConstraints(prog, &A_sparse, &l, &u, &constraint_start_row); csc* P_csc = EigenSparseToCSC(P_sparse); csc* A_csc = EigenSparseToCSC(A_sparse); @@ -435,6 +444,16 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, } } result->set_solution_result(solution_result.value()); + +// osqp_cleanup(workspace_); + c_free(P_csc->x); + c_free(P_csc->i); + c_free(P_csc->p); + c_free(P_csc); + c_free(A_csc->x); + c_free(A_csc->i); + c_free(A_csc->p); + c_free(A_csc); } } // namespace solvers diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 4239f37f56..8cace84a3b 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -281,7 +281,6 @@ void OperationalSpaceControl::Build() { // Construct QP prog_ = std::make_unique(); - ii_prog_ = std::make_unique(); // Size of decision variable n_h_ = (kinematic_evaluators_ == nullptr) @@ -324,9 +323,6 @@ void OperationalSpaceControl::Build() { lambda_h_ = prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); epsilon_ = prog_->NewContinuousVariables(n_c_active_, "epsilon"); - ii_lambda_c_ = ii_prog_->NewContinuousVariables(n_c_, "lambda_contact"); - ii_lambda_h_ = ii_prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); - // Add constraints // 1. Dynamics constraint dynamics_constraint_ = @@ -409,16 +405,6 @@ void OperationalSpaceControl::Build() { VectorXd::Zero(n_v_), dv_) .evaluator() .get()); - ii_tracking_cost_.push_back( - ii_prog_ - ->Add2NormSquaredCost( - MatrixXd::Zero(tracking_data_vec_->at(i)->GetYdotDim(), - n_c_ + n_h_), - VectorXd::Zero(tracking_data_vec_->at(i)->GetYdotDim()), - {ii_lambda_c_, ii_lambda_h_}) - .evaluator() - .get()); - // TODO(yangwill): update the coefficients correctly } // 5. Joint Limit cost @@ -458,8 +444,7 @@ void OperationalSpaceControl::Build() { W_input_reg_ = w_input_reg_ * MatrixXd::Identity(n_u_, n_u_); input_reg_cost_ = prog_->AddQuadraticCost(W_input_reg_, VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); + .evaluator(); } solver_ = std::make_unique(); @@ -557,7 +542,6 @@ VectorXd OperationalSpaceControl::SolveQp( // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; } - // SetVelocitiesIfNew( // plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, // context_wo_spr_); @@ -759,6 +743,8 @@ VectorXd OperationalSpaceControl::SolveQp( // Solve the QP const MathematicalProgramResult result = solver_->Solve(*prog_); +// auto osqp_solver = drake::solvers::OsqpSolver(); +// const MathematicalProgramResult result = osqp_solver.Solve(*prog_); solve_time_ = result.get_solver_details().run_time; // solve_time_ = alpha; @@ -971,7 +957,7 @@ void OperationalSpaceControl::CalcOptimalInput( const drake::systems::Context& context, systems::TimestampedVector* control) const { // Read in current state and time - const OutputVector* robot_output = + auto robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); VectorXd q_w_spr = robot_output->GetPositions(); @@ -994,12 +980,10 @@ void OperationalSpaceControl::CalcOptimalInput( VectorXd u_sol(n_u_); if (used_with_finite_state_machine_) { // Read in finite state machine - const BasicVector* fsm_output = - (BasicVector*)this->EvalVectorInput(context, fsm_port_); + auto fsm_output = this->EvalVectorInput(context, fsm_port_); double clock_time = current_time; if (this->get_input_port(clock_port_).HasValue(context)) { - const BasicVector* clock = - (BasicVector*)this->EvalVectorInput(context, clock_port_); + auto clock = this->EvalVectorInput(context, clock_port_); clock_time = clock->get_value()(0); } VectorXd fsm_state = fsm_output->get_value(); @@ -1007,7 +991,7 @@ void OperationalSpaceControl::CalcOptimalInput( double alpha = 0; int next_fsm_state = -1; if (this->get_near_impact_input_port().HasValue(context)) { - const ImpactInfoVector* impact_info = + auto impact_info = (ImpactInfoVector*)this->EvalVectorInput(context, impact_info_port_); alpha = impact_info->GetAlpha(); @@ -1032,7 +1016,7 @@ void OperationalSpaceControl::CalcOptimalInput( void OperationalSpaceControl::CheckTracking( const drake::systems::Context& context, TimestampedVector* output) const { - const OutputVector* robot_output = + auto robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index d8ad25635d..1af9336c49 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -303,19 +303,11 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Solver std::unique_ptr solver_; - std::unique_ptr ii_solver_; drake::solvers::SolverOptions solver_options_; // MathematicalProgram std::unique_ptr prog_; - std::unique_ptr ii_prog_; - // Decision variables/constraints for impact invariant QP - drake::solvers::VectorXDecisionVariable ii_lambda_c_; - drake::solvers::VectorXDecisionVariable ii_lambda_h_; - std::vector ii_friction_constraints_; - std::vector ii_normal_constraints_; - drake::solvers::BoundingBoxConstraint* ii_holonomic_constraint_; // Decision variables drake::solvers::VectorXDecisionVariable dv_; @@ -330,7 +322,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector friction_constraints_; std::vector tracking_cost_; std::vector joint_limit_cost_; - std::vector ii_tracking_cost_; // OSC solution std::unique_ptr dv_sol_; @@ -394,7 +385,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::VectorXDecisionVariable epsilon_blend_; // Optional feature -- regularizing input - drake::solvers::QuadraticCost* input_reg_cost_; + std::shared_ptr input_reg_cost_; double w_input_reg_ = -1; Eigen::MatrixXd W_input_reg_; From af1f93711e67a7207d3c1c4c6ed8a162e1c638f3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 2 Feb 2022 12:37:27 -0500 Subject: [PATCH 095/758] small plotting changes, logging qp solve time --- .../analysis/cassie_plotting_utils.py | 1 + .../pydairlib/analysis/log_plotter_cassie.py | 4 +- .../plot_configs/cassie_running_plot.yaml | 4 +- .../plot_configs/running_hardware.yaml | 41 ++++++ examples/Cassie/cassie_hardware.pmd | 117 +++++++++++++++--- examples/Cassie/input_supervisor.cc | 22 ++-- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- solvers/fast_osqp_solver.cc | 2 +- .../osc/operational_space_control.cc | 3 - 9 files changed, 157 insertions(+), 39 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/running_hardware.yaml diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 8fb92dc3d3..6179905924 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -22,6 +22,7 @@ 'OSC_WALKING': dairlib.lcmt_robot_input, 'OSC_STANDING': dairlib.lcmt_robot_input, 'OSC_JUMPING': dairlib.lcmt_robot_input, + 'OSC_RUNNING': dairlib.lcmt_robot_input, 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, 'OSC_DEBUG_STANDING': dairlib.lcmt_osc_output, 'OSC_DEBUG_WALKING': dairlib.lcmt_osc_output, diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index d85d647646..d0d659b7e0 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -84,6 +84,9 @@ def main(): mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, t_x_slice, act_map) + # plt.figure("efforts") + # plt.plot(robot_input['t_u'], robot_input['u']) + ''' Plot OSC ''' if plot_config.plot_qp_costs: @@ -114,7 +117,6 @@ def main(): if plot_config.plot_qp_solve_time: plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.25) plt.show() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1e401fd618..ee0506e387 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,6 +1,6 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_SIMULATION" -channel_u: "CASSIE_INPUT" +channel_x: "CASSIE_STATE_DISPATCHER" +channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" # Plant properties diff --git a/bindings/pydairlib/analysis/plot_configs/running_hardware.yaml b/bindings/pydairlib/analysis/plot_configs/running_hardware.yaml new file mode 100644 index 0000000000..ee0506e387 --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/running_hardware.yaml @@ -0,0 +1,41 @@ +# LCM channels to read data from +channel_x: "CASSIE_STATE_DISPATCHER" +channel_u: "OSC_RUNNING" +channel_osc: "OSC_DEBUG_RUNNING" + +# Plant properties +use_springs: true +use_floating_base: true + +# Desired RobotOutput plots +plot_floating_base_positions: false +plot_floating_base_velocities: false +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: true +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Foot position plots +foot_positions_to_plot: ['right', 'left'] +foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} +pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' + +# Desired osc plots +plot_qp_costs: true +plot_qp_solve_time: true +plot_tracking_costs: true +tracking_datas_to_plot: + pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} + # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} +# hip_roll_left_traj: {'dims': [0], 'derivs': ['vel']} + # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} + left_ft_traj: {'dims': [2], 'derivs': ['vel']} + right_ft_traj: {'dims': [2], 'derivs': ['vel']} + left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} + right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} +# left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} +# right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/cassie_hardware.pmd b/examples/Cassie/cassie_hardware.pmd index 0b9aa8b0d8..d0ae6aeec5 100644 --- a/examples/Cassie/cassie_hardware.pmd +++ b/examples/Cassie/cassie_hardware.pmd @@ -1,6 +1,6 @@ group "0.operator" { cmd "0.drake-director-real-robot" { - exec = "bazel-bin/director/drake-director --use_builtin_scripts=contact,frame,image --script examples/Cassie/director_scripts/pd_panel.py --script examples/Cassie/director_scripts/show_time.py --script examples/Cassie/director_scripts/set_channel_network.py"; + exec = "bazel-bin/director/drake-director --use_builtin_scripts=contact,frame,image --script examples/Cassie/director_scripts/pd_panel.py --script examples/Cassie/director_scripts/show_time_hardware.py --script examples/Cassie/director_scripts/set_channel_network.py --script examples/Cassie/director_scripts/controller_status.py"; host = "localhost"; } cmd "1.state-visualizer-real-robot" { @@ -10,50 +10,127 @@ group "0.operator" { } group "1.cassie-robot" { + cmd "0.dispatcher-robot-out-real-robot" { + exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --address 10.10.10.100 --floating_base=true --test_mode=2"; + host = "dair-cassie"; + } cmd "1.dispatcher-robot-in-real-robot" { exec = "bazel-bin/examples/Cassie/dispatcher_robot_in --port 25000 --address 10.10.10.3 --floating_base=true"; host = "dair-cassie"; } cmd "2.pd-controller-real-robot" { - exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_pd_controller"; + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_pd_controller --channel_x=CASSIE_STATE_DISPATCHER --channel_u=PD_CONTROL"; host = "dair-cassie"; } - cmd "4.walking-controller-real-robot" { - exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_walking_controller --channel=CASSIE_STATE_DISPATCHER"; + cmd "3.0 standing-controller-real-robot" { + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_standing_controller --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_STANDING --cost_weight_multiplier=1.0"; host = "dair-cassie"; } - cmd "3.standing-controller-real-robot" { - exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_standing_controller --channel=CASSIE_STATE_DISPATCHER"; + cmd "3.1 standing-controller-real-robot (radio)" { + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_standing_controller --use_radio --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_STANDING --cost_weight_multiplier=1.0"; host = "dair-cassie"; } - cmd "0.dispatcher-robot-out-real-robot" { - exec = "bazel-bin/examples/Cassie/dispatcher_robot_out --port 25001 --address 10.10.10.100 --test_mode=0"; + cmd "4.0 walking-controller-real-robot" { + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_walking_controller --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_WALKING"; + host = "dair-cassie"; + } + cmd "4.1 walking-controller-real-robot (radio)" { + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_walking_controller --use_radio --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_WALKING"; + host = "dair-cassie"; + } + cmd "5.0 running-controller-real-robot" { + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_running_controller --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_RUNNING"; + host = "dair-cassie"; + } + cmd "5.1 running-controller-real-robot (radio)" { + exec = "/home/dair/workspace/dairlib/bazel-bin/examples/Cassie/run_osc_running_controller --use_radio=1 --channel_x=CASSIE_STATE_DISPATCHER --channel_u=OSC_RUNNING"; host = "dair-cassie"; } } -group "2.lcm-tools" { - cmd "1.signal-scope" { - exec = "bazel-bin/signalscope/signal-scope"; - host = "localhost"; +group "2.controller-switch-commands" { + cmd "controller-switch-to-standing" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=OSC_STANDING --channel_x=CASSIE_STATE_DISPATCHER --blend_duration=1.0"; + host = "dair-cassie"; + } + cmd "controller-switch-to-walking" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=OSC_WALKING --channel_x=CASSIE_STATE_DISPATCHER --blend_duration=0.01 --fsm_period=0.4 --fsm_offset=.35 --n_period_delay=2"; + host = "dair-cassie"; + } + cmd "controller-switch-to-jumping" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=OSC_JUMPING --channel_x=CASSIE_STATE_DISPATCHER"; + host = "dair-cassie"; + } + cmd "controller-switch-to-running" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=OSC_RUNNING --channel_x=CASSIE_STATE_DISPATCHER"; + host = "dair-cassie"; + } + cmd "controller-switch-to-pd" { + exec = "bazel-bin/examples/Cassie/run_controller_switch --new_channel=PD_CONTROL --channel_x=CASSIE_STATE_DISPATCHER"; + host = "dair-cassie"; + } +} + +group "3.lcm-tools" { + cmd "0.cassie-lcm-logger" { + exec = "python3 examples/Cassie/start_logging.py"; + host = "dair-cassie"; } cmd "0.lcm-spy" { exec = "bazel-bin/lcmtypes/dair-lcm-spy"; host = "localhost"; } + cmd "1.signal-scope" { + exec = "bazel-bin/signalscope/signal-scope"; + host = "localhost"; + } } -script "run-real-robot-pd-control" { - run_script "start-operator-real-robot"; +script "initialize_standing" { + stop group "1.cassie-robot"; + stop cmd "0.cassie-lcm-logger"; start cmd "0.dispatcher-robot-out-real-robot"; start cmd "1.dispatcher-robot-in-real-robot"; start cmd "2.pd-controller-real-robot"; } -script "start-operator-real-robot" { - stop cmd "1.state-visualizer-real-robot"; - stop cmd "2.drake-director-real-robot"; - start cmd "2.drake-director-real-robot"; - wait ms 3000; - start cmd "1.state-visualizer-real-robot"; +script "setup_from_pd_to_osc_standing" { + restart cmd "0.dispatcher-robot-out-real-robot"; + start cmd "3.0 standing-controller-real-robot"; } + +script "setup_from_pd_to_osc_standing (radio)" { + restart cmd "0.dispatcher-robot-out-real-robot"; + start cmd "3.1 standing-controller-real-robot (radio)"; +} + +script "switch_to_standing" { + start cmd "controller-switch-to-standing"; + wait ms 1000; + stop cmd "2.pd-controller-real-robot"; +} + +script "switch_to_walking" { + start cmd "controller-switch-to-walking"; + wait ms 2000; + stop cmd "3.0 standing-controller-real-robot"; + stop cmd "3.1 standing-controller-real-robot (radio)"; +} + +script "switch_to_walking_start_logging" { + start cmd "0.cassie-lcm-logger"; + wait ms 100; + start cmd "controller-switch-to-walking"; + wait ms 2000; + stop cmd "3.0 standing-controller-real-robot"; + stop cmd "3.1 standing-controller-real-robot (radio)"; +} + +script "switch_to_running_start_logging" { + start cmd "0.cassie-lcm-logger"; + wait ms 100; + start cmd "controller-switch-to-running"; + wait ms 2000; + stop cmd "3.0 standing-controller-real-robot"; + stop cmd "3.1 standing-controller-real-robot (radio)"; +} \ No newline at end of file diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 56c6ba91eb..68d09cfa05 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -128,7 +128,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, // iterate through all the possible error flags bool is_error = false; for (const auto& error_flags : error_indices_) { - is_error = is_error || context.get_discrete_state().get_value( + is_error = is_error || context.get_discrete_state().value( error_indices_index_)[error_flags.second]; } @@ -158,12 +158,12 @@ void InputSupervisor::SetMotorTorques(const Context& context, output->SetDataVector(u); } else if (is_error) { output->set_timestamp(safety_command->get_timestamp()); - output->SetDataVector(safety_command->get_value()); + output->SetDataVector(safety_command->value()); } else if (alpha < 1.0) { Eigen::VectorXd blended_effort = - alpha * command->get_value() + + alpha * command->value() + (1 - alpha) * - context.get_discrete_state(prev_efforts_index_).get_value(); + context.get_discrete_state(prev_efforts_index_).value(); output->SetDataVector(blended_effort); } else { output->get_mutable_data() = command->get_data(); @@ -191,14 +191,14 @@ void InputSupervisor::SetStatus( command_input_port_); output->utime = command->get_timestamp() * 1e6; output->active_channel = active_channel_; - output->shutdown = context.get_discrete_state().get_value(shutdown_index_)[0]; + output->shutdown = context.get_discrete_state().value(shutdown_index_)[0]; output->num_status = error_indices_.size(); output->status_names = std::vector(error_indices_.size()); output->status_states = std::vector(error_indices_.size()); for (const auto& error_flags : error_indices_) { output->status_names[error_flags.second] = error_flags.first; output->status_states[error_flags.second] = - context.get_discrete_state().get_value( + context.get_discrete_state().value( error_indices_index_)[error_flags.second]; } } @@ -208,7 +208,7 @@ void InputSupervisor::SetFailureStatus( dairlib::lcmt_controller_failure* output) const { output->utime = context.get_time() * 1e6; output->error_code = - context.get_discrete_state().get_value(shutdown_index_)[0]; + context.get_discrete_state().value(shutdown_index_)[0]; output->controller_channel = "GLOBAL_ERROR"; output->error_name = ""; } @@ -255,7 +255,7 @@ void InputSupervisor::UpdateErrorFlag( bool is_error = false; for (const auto& error_flags : error_indices_) { - is_error = is_error || context.get_discrete_state().get_value( + is_error = is_error || context.get_discrete_state().value( error_indices_index_)[error_flags.second]; } discrete_state->get_mutable_value(shutdown_index_)[0] = is_error; @@ -278,7 +278,7 @@ void InputSupervisor::UpdateErrorFlag( if (command->get_timestamp() - controller_switch->utime * 1e-6 >= blend_duration_) { discrete_state->get_mutable_value(prev_efforts_index_) = - command->get_value(); + command->value(); } } @@ -289,7 +289,7 @@ void InputSupervisor::CheckVelocities( (OutputVector*)this->EvalVectorInput(context, state_input_port_); const Eigen::VectorXd& velocities = state->GetVelocities(); - if (discrete_state->get_value(n_fails_index_)[0] < + if (discrete_state->value(n_fails_index_)[0] < min_consecutive_failures_) { // If any velocity is above the threshold, set the error flag bool is_velocity_error = (velocities.array() > max_joint_velocity_).any() || @@ -300,7 +300,7 @@ void InputSupervisor::CheckVelocities( std::cout << "Error! Velocity has exceeded the threshold of " << max_joint_velocity_ << std::endl; std::cout << "Consecutive error " - << discrete_state->get_value(n_fails_index_)[0] << " of " + << discrete_state->value(n_fails_index_)[0] << " of " << min_consecutive_failures_ << std::endl; std::cout << "Velocity vector: " << std::endl << velocities << std::endl diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 05e413ecb3..88f7d4c892 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -80,5 +80,5 @@ LiftoffSwingFootKp: LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 1] + 0, 0, 2] diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index a31e2bb254..b1e6bc13d5 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -345,7 +345,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, "OsqpSolver doesn't support the feature of variable scaling."); } - auto solver_details = + OsqpSolverDetails& solver_details = result->SetSolverDetailsType(); // OSQP solves a convex quadratic programming problem diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 8cace84a3b..e426abf8e3 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -743,11 +743,8 @@ VectorXd OperationalSpaceControl::SolveQp( // Solve the QP const MathematicalProgramResult result = solver_->Solve(*prog_); -// auto osqp_solver = drake::solvers::OsqpSolver(); -// const MathematicalProgramResult result = osqp_solver.Solve(*prog_); solve_time_ = result.get_solver_details().run_time; - // solve_time_ = alpha; // Extract solutions *dv_sol_ = result.GetSolution(dv_); From 6206ebae9cc6adb79873335bb98a785e99d0e482 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 2 Feb 2022 14:22:11 -0500 Subject: [PATCH 096/758] gain tuning, adding input limits --- examples/Cassie/dispatcher_robot_in.cc | 14 +++++--- examples/Cassie/input_supervisor.cc | 35 +++++++------------ examples/Cassie/input_supervisor.h | 10 +++--- .../Cassie/osc_run/osc_running_gains.yaml | 10 +++--- examples/Cassie/test/input_supervisor_test.cc | 6 ++-- .../Cassie/urdf/cassie_v2_conservative.urdf | 20 +++++------ .../osc/operational_space_control.cc | 2 +- 7 files changed, 47 insertions(+), 50 deletions(-) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index a590a2730c..3459d3865b 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -75,7 +75,7 @@ int do_main(int argc, char* argv[]) { // Build Cassie MBP drake::multibody::MultibodyPlant plant(0.0); addCassieMultibody(&plant, nullptr, FLAGS_floating_base /*floating base*/, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); plant.Finalize(); @@ -120,14 +120,18 @@ int do_main(int argc, char* argv[]) { builder.Connect(*state_sub, *state_receiver); double input_supervisor_update_period = 1.0 / 1000.0; - double input_limit = FLAGS_input_limit; - if (input_limit < 0) { - input_limit = std::numeric_limits::max(); + + + // Get input limits + int nu = plant.num_actuators(); + VectorXd input_limit(nu); + for (drake::multibody::JointActuatorIndex i(0); i < nu; ++i) { + input_limit(i) = plant.get_joint_actuator(i).effort_limit(); } auto input_supervisor = builder.AddSystem( plant, FLAGS_control_channel_name_initial, FLAGS_max_joint_velocity, - input_supervisor_update_period, FLAGS_supervisor_N, input_limit); + input_supervisor_update_period, input_limit, FLAGS_supervisor_N); builder.Connect(state_receiver->get_output_port(0), input_supervisor->get_input_port_state()); builder.Connect(command_receiver->get_output_port(0), diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 68d09cfa05..ef382aae20 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -18,7 +18,7 @@ using systems::TimestampedVector; InputSupervisor::InputSupervisor( const drake::multibody::MultibodyPlant& plant, const std::string& initial_channel, double max_joint_velocity, - double update_period, int min_consecutive_failures, double input_limit) + double update_period, Eigen::VectorXd& input_limit, int min_consecutive_failures) : plant_(plant), num_actuators_(plant_.num_actuators()), num_positions_(plant_.num_positions()), @@ -27,9 +27,6 @@ InputSupervisor::InputSupervisor( min_consecutive_failures_(min_consecutive_failures), max_joint_velocity_(max_joint_velocity), input_limit_(input_limit) { - if (input_limit_ == std::numeric_limits::max()) { - std::cout << "Warning. No input limits have been set." << std::endl; - } // Create input ports command_input_port_ = @@ -153,7 +150,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, // any other controller signal if (cassie_out->pelvis.radio.channel[15] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); - input_limit_ = 100; + input_limit_ = 100 * Eigen::VectorXd::Ones(num_actuators_); output->set_timestamp(state->get_timestamp()); output->SetDataVector(u); } else if (is_error) { @@ -162,24 +159,21 @@ void InputSupervisor::SetMotorTorques(const Context& context, } else if (alpha < 1.0) { Eigen::VectorXd blended_effort = alpha * command->value() + - (1 - alpha) * - context.get_discrete_state(prev_efforts_index_).value(); + (1 - alpha) * context.get_discrete_state(prev_efforts_index_).value(); output->SetDataVector(blended_effort); } else { output->get_mutable_data() = command->get_data(); } // Apply input_limits - if (input_limit_ != std::numeric_limits::max()) { - for (int i = 0; i < command->get_data().size(); i++) { - double command_value = output->get_data()(i); - if (command_value > input_limit_) { - command_value = input_limit_; - } else if (command_value < -input_limit_) { - command_value = -input_limit_; - } - output->get_mutable_data()(i) = command_value; + for (int i = 0; i < command->get_data().size(); i++) { + double command_value = output->get_data()(i); + if (command_value > input_limit_(i)) { + command_value = input_limit_(i); + } else if (command_value < -input_limit_(i)) { + command_value = -input_limit_(i); } + output->get_mutable_data()(i) = command_value; } } @@ -207,8 +201,7 @@ void InputSupervisor::SetFailureStatus( const drake::systems::Context& context, dairlib::lcmt_controller_failure* output) const { output->utime = context.get_time() * 1e6; - output->error_code = - context.get_discrete_state().value(shutdown_index_)[0]; + output->error_code = context.get_discrete_state().value(shutdown_index_)[0]; output->controller_channel = "GLOBAL_ERROR"; output->error_name = ""; } @@ -277,8 +270,7 @@ void InputSupervisor::UpdateErrorFlag( // efforts if (command->get_timestamp() - controller_switch->utime * 1e-6 >= blend_duration_) { - discrete_state->get_mutable_value(prev_efforts_index_) = - command->value(); + discrete_state->get_mutable_value(prev_efforts_index_) = command->value(); } } @@ -289,8 +281,7 @@ void InputSupervisor::CheckVelocities( (OutputVector*)this->EvalVectorInput(context, state_input_port_); const Eigen::VectorXd& velocities = state->GetVelocities(); - if (discrete_state->value(n_fails_index_)[0] < - min_consecutive_failures_) { + if (discrete_state->value(n_fails_index_)[0] < min_consecutive_failures_) { // If any velocity is above the threshold, set the error flag bool is_velocity_error = (velocities.array() > max_joint_velocity_).any() || (velocities.array() < -max_joint_velocity_).any(); diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index 99c4fede1b..178b0af5d9 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -1,8 +1,8 @@ #pragma once #include -#include "dairlib/lcmt_input_supervisor_status.hpp" #include "dairlib/lcmt_controller_failure.hpp" +#include "dairlib/lcmt_input_supervisor_status.hpp" #include "systems/framework/timestamped_vector.h" #include "drake/multibody/plant/multibody_plant.h" @@ -43,8 +43,8 @@ class InputSupervisor : public drake::systems::LeafSystem { explicit InputSupervisor( const drake::multibody::MultibodyPlant& plant, const std::string& initial_channel, double max_joint_velocity, - double update_period, int min_consecutive_failures = 1, - double input_limit = std::numeric_limits::max()); + double update_period, Eigen::VectorXd& input_limit, + int min_consecutive_failures = 1); const drake::systems::InputPort& get_input_port_command() const { return this->get_input_port(command_input_port_); @@ -102,7 +102,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // Output a failure message when any error is triggered void SetFailureStatus(const drake::systems::Context& context, - dairlib::lcmt_controller_failure* output) const; + dairlib::lcmt_controller_failure* output) const; void CheckVelocities( const drake::systems::Context& context, @@ -122,7 +122,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // supervisor settings const int min_consecutive_failures_; double max_joint_velocity_; - mutable double input_limit_; + mutable Eigen::VectorXd input_limit_; mutable double blend_duration_ = 0.0; // For keeping track of things that require multiple failures diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 88f7d4c892..d5d86e566d 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -24,8 +24,8 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 1 -hip_yaw_kp: 200 -hip_yaw_kd: 20 +hip_yaw_kp: 40 +hip_yaw_kd: 0.5 # Foot placement parameters footstep_offset: -0.05 center_line_offset: 0.05 @@ -50,13 +50,13 @@ PelvisRotW: 0, 0.1, 0, 0, 0, 1] PelvisRotKp: - [50, 0, 0, + [200, 0, 0, 0, 50, 0, 0, 0, 0] PelvisRotKd: - [10, 0, 0, + [5, 0, 0, 0, 10, 0, - 0, 0, 10] + 0, 0, 0] SwingFootW: [50, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/test/input_supervisor_test.cc b/examples/Cassie/test/input_supervisor_test.cc index 4e6650b92d..30e5c0c029 100644 --- a/examples/Cassie/test/input_supervisor_test.cc +++ b/examples/Cassie/test/input_supervisor_test.cc @@ -22,9 +22,10 @@ class InputSupervisorTest : public ::testing::Test { "examples/Cassie/urdf/cassie_v2.urdf", true /*spring model*/, false /*loop closure*/); plant_.Finalize(); + input_limits_ = 20.0 * VectorXd::Ones(plant_.num_actuators()); supervisor_ = std::make_unique( - plant_, "DEFAULT_CONTROL_CHANNEL", 10.0, 0.01, min_consecutive_failures, - 20.0); + plant_, "DEFAULT_CONTROL_CHANNEL", 10.0, 0.01, input_limits_, + min_consecutive_failures); context_ = supervisor_->CreateDefaultContext(); status_output_ = std::make_unique(); cassie_out_ = std::make_unique(); @@ -41,6 +42,7 @@ class InputSupervisorTest : public ::testing::Test { int state_input_port_; drake::multibody::MultibodyPlant plant_; + Eigen::VectorXd input_limits_; const int min_consecutive_failures = 5; std::unique_ptr supervisor_; std::unique_ptr status_output_; diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 95d62e6c23..bfcdaaee02 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -614,7 +614,7 @@ - + @@ -623,7 +623,7 @@ - + @@ -633,7 +633,7 @@ - + @@ -642,7 +642,7 @@ - + @@ -653,7 +653,7 @@ - + @@ -663,7 +663,7 @@ - + @@ -672,7 +672,7 @@ - + @@ -681,7 +681,7 @@ - + @@ -786,7 +786,7 @@ - + @@ -795,7 +795,7 @@ - + diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index e426abf8e3..14b29666ee 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1018,7 +1018,7 @@ void OperationalSpaceControl::CheckTracking( output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; // std::cout << "total cost: " << total_cost_ << std::endl; - if (soft_constraint_cost_ > 1e2 || isnan(soft_constraint_cost_)) { + if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } } From 3946979df68f434c2d356ee94971c7ebb9da0f7f Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 2 Feb 2022 15:58:49 -0500 Subject: [PATCH 097/758] adding all osqp params to osc, gain changes --- .../Cassie/osc_run/osc_running_gains.yaml | 8 +++---- .../osc/operational_space_control.cc | 21 ++++++++++++++----- 2 files changed, 20 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d5d86e566d..e5e5c00028 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -24,8 +24,8 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 1 -hip_yaw_kp: 40 -hip_yaw_kd: 0.5 +hip_yaw_kp: 60 +hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 center_line_offset: 0.05 @@ -50,7 +50,7 @@ PelvisRotW: 0, 0.1, 0, 0, 0, 1] PelvisRotKp: - [200, 0, 0, + [100, 0, 0, 0, 50, 0, 0, 0, 0] PelvisRotKd: @@ -67,7 +67,7 @@ SwingFootKp: 0, 0, 50] SwingFootKd: [10, 0, 0, - 0, 10, 0, + 0, 2, 0, 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 14b29666ee..c5e591f2c8 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -451,13 +451,24 @@ void OperationalSpaceControl::Build() { drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); - solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-7); - solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-6); - solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); - solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "rho", 0.1); + solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "max_iter", 4000); + solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); + solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-5); + solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-5); + solver_options.SetOption(OsqpSolver::id(), "alpha", 1.6); + solver_options.SetOption(OsqpSolver::id(), "delta", 1e-6); solver_options.SetOption(OsqpSolver::id(), "polish", 1); + solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 3); solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); - solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_fraction", 1); + solver_options.SetOption(OsqpSolver::id(), "check_termination", 10); + solver_options.SetOption(OsqpSolver::id(), "scaling", 10); + solver_options.SetOption(OsqpSolver::id(), "adaptive_rho", 1); + solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_interval", 0); + solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_tolerance", 5); + solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_fraction", 0.4); std::cout << solver_options << std::endl; solver_->InitializeSolver(*prog_, solver_options); } From 2f89481d1fa5bf42c2e48df0334339b7e20ce7dd Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 8 Feb 2022 11:15:49 -0500 Subject: [PATCH 098/758] looking into osqp settings, tuning based on hardware results --- bindings/pydairlib/analysis/BUILD.bazel | 18 ++ .../analysis/osqp_settings_sandbox.py | 127 ++++++++++++ .../plot_configs/cassie_running_plot.yaml | 14 +- bindings/pydairlib/analysis/qp_test.py | 180 ++++++++++++++++++ .../Cassie/osc_run/osc_running_gains.yaml | 18 +- lcmtypes/lcmt_qp.lcm | 17 ++ solvers/BUILD.bazel | 1 + solvers/fast_osqp_solver.cc | 36 ++++ .../osc/operational_space_control.cc | 8 +- 9 files changed, 399 insertions(+), 20 deletions(-) create mode 100644 bindings/pydairlib/analysis/osqp_settings_sandbox.py create mode 100644 bindings/pydairlib/analysis/qp_test.py create mode 100644 lcmtypes/lcmt_qp.lcm diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 1d04ebb2f0..4eb70bbd1f 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -17,6 +17,24 @@ py_binary( deps = ["@lcm//:lcm-python"], ) +py_binary( + name = "qp_test", + srcs = ["qp_test.py"], + deps = [ + "//lcmtypes:lcmtypes_robot_py", + "@lcm//:lcm-python", + ], +) + +py_binary( + name = "osqp_settings_sandbox", + srcs = ["osqp_settings_sandbox.py"], + deps = [ + "//lcmtypes:lcmtypes_robot_py", + "@lcm//:lcm-python", + ], +) + py_library( name = "osc_debug_py", srcs = ["osc_debug.py"], diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py new file mode 100644 index 0000000000..4f28f2a1e7 --- /dev/null +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -0,0 +1,127 @@ +import lcm +import numpy as np +from process_lcm_log import get_log_data +from dairlib import lcmt_qp +import sys + +import osqp +from scipy.sparse import csc_matrix + + +def ParseQP(data): + qp_list = [] + + for msg in data["QP_LOG"]: + # import pdb; pdb.set_trace() + qp = {"Q": np.asarray(msg.Q), + "w": np.asarray(msg.w), + "A_ineq": np.asarray(msg.A_ineq), + "ineq_lb": np.asarray(msg.ineq_lb), + "ineq_ub": np.asarray(msg.ineq_ub), + "A_eq": np.asarray(msg.A_eq), + "b_eq": np.asarray(msg.b_eq), + "x_lb": np.asarray(msg.x_lb), + "x_ub": np.asarray(msg.x_ub), + } + + qp_list.append(qp) + + return qp_list + + +def solve_osqp(qp, settings): + Q = qp["Q"] + qp["Q"].T - np.diag(np.diag(qp["Q"])) + Q = Q + 1e-6 * np.eye(Q.shape[0]) + m = osqp.OSQP() + m.setup( + P=csc_matrix(Q), q=qp["w"], + A=csc_matrix(qp["A_ineq"]), + l=qp["ineq_lb"], u=qp["ineq_ub"], + eps_abs=settings['eps_abs'], + eps_rel=settings['eps_rel'], + eps_prim_inf=settings['eps_prim_inf'], + eps_dual_inf=settings['eps_dual_inf'], + polish=settings['polish'], + scaled_termination=settings['scaled_termination'], + adaptive_rho_fraction=settings['adaptive_rho_fraction'], + verbose=settings['verbose'], + warm_start=settings['warm_start'], + rho=settings['rho'], + check_termination=settings['check_termination']) + + qp_result = m.solve() + + # if qp_result.info.run_time > 5e-3: + # import pdb; pdb.set_trace() + return {'iter': qp_result.info.iter, + 'run_time': qp_result.info.run_time, + 'status': qp_result.info.status, + 'obj_val': qp_result.info.obj_val, + 'pri_res': qp_result.info.pri_res, + 'dual_res': qp_result.info.dua_res, + 'sol': qp_result.x} + + +def main(): + + # filename = "/home/brian/workspace/logs/qp_logging/lcmlog00" + filename = sys.argv[1] + log = lcm.EventLog(filename, "r") + qp_list = get_log_data(log, {"QP_LOG": lcmt_qp}, ParseQP) + + qp_list = qp_list[:5000][::10] + run_times = np.zeros((len(qp_list),)) + obj_vals = np.zeros((len(qp_list),)) + pri_eps_vals = np.zeros((len(qp_list,))) + sols = np.zeros((len(qp_list,), 60)) + + for i, qp in enumerate(qp_list): + osqp_settings = \ + {'eps_abs': 1e-5, + 'eps_rel': 1e-5, + 'eps_prim_inf': 1e-5, + 'eps_dual_inf': 1e-5, + 'polish': 1, + 'scaled_termination': 1, + 'adaptive_rho': 1, + 'adaptive_rho_fraction': 0.4, + 'verbose': 0, + 'warm_start': 1, + 'rho': 1e-4, + 'sigma': 1e-6, + 'alpha': 1.6, + 'delta': 1e-6, + 'check_termination': 25} + + osqp_result = solve_osqp(qp, osqp_settings) + run_times[i] = osqp_result['run_time'] + obj_vals[i] = osqp_result['obj_val'] + pri_eps_vals[i] = osqp_result['pri_res'] + pri_eps_vals[i] = osqp_result['pri_res'] + sols[i] = osqp_result['sol'] + + + print(f'OSQP mean runtime: {np.mean(run_times)}') + print(f'OSQP mean objective: {np.mean(obj_vals)}') + print(f'OSQP mean primal residuals: {np.mean(pri_eps_vals)}') + + import matplotlib.pyplot as plt + + fig, axs = plt.subplots(3, 1, sharex=True) + + axs[0].plot(obj_vals, label='OSQP') + axs[0].legend() + axs[0].set_title('Objective values per QP') + + axs[1].plot(run_times) + axs[1].set_title('Solve times per QP') + + axs[2].plot(sols[:, 22:32]) + axs[2].set_title('QP solutions') + plt.show() + import pdb;pdb.set_trace() + + + +if __name__ == '__main__': + main() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index ee0506e387..4679d4147d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -27,15 +27,15 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} +# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} - hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} +# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # hip_roll_left_traj: {'dims': [0], 'derivs': ['vel']} # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} - left_ft_traj: {'dims': [2], 'derivs': ['vel']} - right_ft_traj: {'dims': [2], 'derivs': ['vel']} - left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} - right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} +# left_ft_traj: {'dims': [2], 'derivs': ['vel']} +# right_ft_traj: {'dims': [2], 'derivs': ['vel']} +# left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} +# right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/analysis/qp_test.py b/bindings/pydairlib/analysis/qp_test.py new file mode 100644 index 0000000000..bc6225fb44 --- /dev/null +++ b/bindings/pydairlib/analysis/qp_test.py @@ -0,0 +1,180 @@ +import lcm +import numpy as np +from process_lcm_log import get_log_data +from dairlib import lcmt_qp +# import qpoases +import time +import sys +# import qpsolvers + +import osqp +# import gurobipy as gp +from scipy.sparse import csc_matrix + +def ConvertIneq(A_ineq, ineq_lb, ineq_ub): + is_equality = ineq_ub - ineq_lb < 1e-6 + + # Parse out equality constraints + b_eq = ineq_ub[is_equality] + A_eq = A_ineq[is_equality, :] + A_ineq = A_ineq[is_equality == False, :] + ineq_lb = ineq_lb[is_equality == False] + ineq_ub = ineq_ub[is_equality == False] + + # Convert to Ax <= b + ub_active = ineq_ub <= 1e10 + lb_active = ineq_lb >= -1e10 + A_ineq = np.vstack((A_ineq[ub_active,:], -A_ineq[lb_active,:])) + b_ineq = np.hstack((ineq_ub[ub_active], -ineq_lb[lb_active])) + + return (A_ineq, b_ineq, A_eq, b_eq) + +def ParseQP(data): + qp_list = [] + + for msg in data["QP_LOG"]: + # import pdb; pdb.set_trace() + qp = {"Q": np.asarray(msg.Q), + "w": np.asarray(msg.w), + "A_ineq": np.asarray(msg.A_ineq), + "ineq_lb": np.asarray(msg.ineq_lb), + "ineq_ub": np.asarray(msg.ineq_ub), + "A_eq": np.asarray(msg.A_eq), + "b_eq": np.asarray(msg.b_eq), + "x_lb": np.asarray(msg.x_lb), + "x_ub": np.asarray(msg.x_ub), + } + + qp_list.append(qp) + + return qp_list + +# filename = "/home/posa/workspace/osc_qp.log" +filename = sys.argv[1] +log = lcm.EventLog(filename, "r") +qp_list = \ + get_log_data(log, + {"QP_LOG": lcmt_qp}, + ParseQP) + + +qp_list = qp_list[:200] +run_times = np.zeros((len(qp_list), 1)) +obj_vals = np.zeros((len(qp_list), 1)) +run_times_gr = np.zeros((len(qp_list), 1)) +obj_vals_gr = np.zeros((len(qp_list), 1)) +run_times_qpo = np.zeros((len(qp_list), 1)) +obj_vals_qpo = np.zeros((len(qp_list), 1)) +run_times_other = np.zeros((len(qp_list), 1)) +obj_vals_other = np.zeros((len(qp_list), 1)) + + +for i, qp in enumerate(qp_list): + Q = qp["Q"] + qp["Q"].T - np.diag(np.diag(qp["Q"])) + Q = Q + 1e-7*np.eye(Q.shape[0]) + # Q = qp["Q"] + + # qp["A_ineq"] = np.vstack((qp["A_ineq"][:68,:], qp["A_ineq"][69:, :])) + # qp["ineq_lb"] = np.hstack((qp["ineq_lb"][:68], qp["ineq_lb"][69:])) + # qp["ineq_ub"] = np.hstack((qp["ineq_ub"][:68], qp["ineq_ub"][69:])) + + # if i == 0:? + m = osqp.OSQP() + m.setup(P=csc_matrix(Q), q=qp["w"], A=csc_matrix(qp["A_ineq"]), l=qp["ineq_lb"], u=qp["ineq_ub"]) + m.update_settings(eps_abs=1e-7, einitps_rel=1e-7, eps_prim_inf=1e-6, eps_dual_inf=1e-6, polish=1, scaled_termination=1, adaptive_rho_fraction=1, verbose=0, warm_start=0, rho=.1, check_termination=3) + # m.update_settings(eps_abs=1e-7, eps_rel=1e-7, eps_prim_inf=1e-6, eps_dual_inf=1e-6, polish=1, scaled_termination=1, adaptive_rho_fraction=1, verbose=0, warm_start=0, rho=.1, check_termination=3) + # else: + # # import pdb; pdb.set_trace() + # m.update(q=qp["w"], Ax=csc_matrix(qp["A_ineq"]).data, l=qp["ineq_lb"], u=qp["ineq_ub"]) + results = m.solve() + run_times[i] = results.info.run_time + obj_vals[i] = results.info.obj_val + + (A_ineq, b_ineq, A_eq, b_eq) = ConvertIneq(qp["A_ineq"], qp["ineq_lb"], qp["ineq_ub"]) + + # + # GUROBI + # + # m_gr = gp.Model() + # m.Params.FeasibilityTol = 1e-4 + # m.Params.OptimalityTol = 1e-4 + # m_gr.Params.LogToConsole = 0 + # m_gr.Params.method = -1 + # x = m_gr.addMVar(Q.shape[0], lb=-float('inf'), ub=float('inf')) + # obj = x @ (Q/2) @ x + qp["w"] @ x + # obj = x @ x + # m_gr.setObjective(obj) + + # m_gr.addConstr(A_ineq @ x <= b_ineq) + # m_gr.addConstr(A_eq @ x == b_eq) + + # m_gr.optimize() + # run_times_gr[i] = m_gr.Runtime + # obj_vals_gr[i] = obj.getValue() + + # + # QPOASES + # + + # nWSR = np.array([10000]) + # nx = Q.shape[0] + # m_qpo = qpoases.PyQProblem(nx, qp["A_ineq"].shape[0]) + # options = qpoases.PyOptions() + # options.printLevel = qpoases.PyPrintLevel.NONE + # options.terminationTolerance = 1e-6 + # options.boundTolerance = 1e-6 + # options.enableEqualities = 1 + # options.enableFarBounds = 0 + # options.enableDriftCorrection = 0 + # options.enableFlippingBounds = 0 + # options.enableInertiaCorrection = 0 + # m_qpo.setOptions(options) + # + # start = time.time() + # m_qpo.init(Q, qp["w"], qp["A_ineq"].T, -np.full(nx, 1e10), np.full(nx, 1e10), qp["ineq_lb"], qp["ineq_ub"], nWSR) + # obj_vals_qpo[i] = m_qpo.getObjVal() + # run_times_qpo[i] = time.time() - start + + # # + # # qpsolvers + # # + # solvers = ['cvxopt', 'cvxpy', 'ecos', 'gurobi', 'osqp', 'qpoases', 'quadprog', 'scs'] + # other_i = 6 + # start = time.time() + # x_other = qpsolvers.solve_qp(Q, qp["w"], A_ineq, b_ineq, A_eq, b_eq, -np.full(nx, 1e10), np.full(nx, 1e10), solver=solvers[other_i]) + # run_times_other[i] = time.time() - start + # # import pdb; pdb.set_trace() + # if x_other is not None: + # obj_vals_other[i] = .5*x_other @ Q @ x_other + qp["w"]@x_other + # else: + # obj_vals_other[i] = 1e3 + + +print(np.mean(run_times)) +print(np.mean(obj_vals)) + +# print(np.mean(run_times_gr)) +# print(np.mean(obj_vals_gr)) +# +# print(np.mean(run_times_qpo)) +# print(np.mean(obj_vals_qpo)) + + +import matplotlib.pyplot as plt +fig, axs = plt.subplots(2, 1, sharex=True) + + +axs[0].plot(obj_vals, label='OSQP') +axs[0].plot(obj_vals_gr, label='Gurobi') +axs[0].plot(obj_vals_qpo, label='QPOASES') +# axs[0].plot(obj_vals_other, label=solvers[other_i]) +axs[0].legend() +axs[0].set_title('Objective values per QP') + +axs[1].plot(run_times) +axs[1].plot(run_times_gr) +axs[1].plot(run_times_qpo) +# axs[1].plot(run_times_other) +axs[1].set_title('Solve times per QP') +plt.show() +import pdb; pdb.set_trace() diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e5e5c00028..4947f22027 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -23,11 +23,11 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 1 +w_hip_yaw: 2.5 hip_yaw_kp: 60 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: -0.05 +footstep_offset: -0.03 center_line_offset: 0.05 FootstepKd: [ 0.2, 0, 0, @@ -36,7 +36,7 @@ FootstepKd: PelvisW: [0.1, 0, 0, 0, 0, 0, - 0, 0, 5] + 0, 0, 1] PelvisKp: [ 0, 0, 0, 0, 0, 0, @@ -48,22 +48,22 @@ PelvisKd: PelvisRotW: [1, 0, 0, 0, 0.1, 0, - 0, 0, 1] + 0, 0, 0] PelvisRotKp: - [100, 0, 0, - 0, 50, 0, + [25, 0, 0, + 0, 20, 0, 0, 0, 0] PelvisRotKd: [5, 0, 0, - 0, 10, 0, + 0, 5, 0, 0, 0, 0] SwingFootW: - [50, 0, 0, + [10, 0, 0, 0, 10, 0, 0, 0, 1] SwingFootKp: [125, 0, 0, - 0, 125, 0, + 0, 60, 0, 0, 0, 50] SwingFootKd: [10, 0, 0, diff --git a/lcmtypes/lcmt_qp.lcm b/lcmtypes/lcmt_qp.lcm new file mode 100644 index 0000000000..3b59298f5c --- /dev/null +++ b/lcmtypes/lcmt_qp.lcm @@ -0,0 +1,17 @@ +package dairlib; + +struct lcmt_qp +{ + int32_t n_x; + int32_t n_ineq; + int32_t n_eq; + double Q[n_x][n_x]; + double w[n_x]; + double A_ineq[n_ineq][n_x]; + double ineq_lb[n_ineq]; + double ineq_ub[n_ineq]; + double A_eq[n_eq][n_x]; + double b_eq[n_eq]; + double x_lb[n_x]; + double x_ub[n_x]; +} \ No newline at end of file diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 58a61e431d..898e6e85eb 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -34,6 +34,7 @@ cc_library( "fast_osqp_solver.h", ], deps = [ + "//lcmtypes:lcmt_robot", "@drake//:drake_shared_library", "@osqp", ], diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index b1e6bc13d5..1ffcb48b80 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -2,6 +2,8 @@ #include +#include "dairlib/lcmt_qp.hpp" +#include #include #include "drake/common/text_logging.h" @@ -380,6 +382,40 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; + lcmt_qp msg; + msg.n_x = prog.num_vars(); + + Eigen::MatrixXd Q(P_sparse); + + // Note: Amessage is transposed, becaues Eigen defaults to column major + for (int i = 0; i < prog.num_vars(); i++) { + msg.Q.push_back(std::vector(Q.col(i).data(), + Q.col(i).data() + prog.num_vars())); + } + msg.w = q; + + + Eigen::MatrixXd A(A_sparse); + + // std::cout << A.row(68) << std::endl; + msg.n_ineq = A.rows(); + for (int i = 0; i < A.rows(); i++) { + std::vector row(A.cols()); + for (int j = 0; j < A.cols(); j++) { + row[j] = A(i,j); + } + msg.A_ineq.push_back(row); + } + + msg.ineq_lb = l; + msg.ineq_ub = u; + msg.x_lb = std::vector(prog.num_vars(), -std::numeric_limits::infinity()); + msg.x_ub = std::vector(prog.num_vars(), std::numeric_limits::infinity()); + + msg.n_eq = 0; + lcm::LCM lcm; + lcm.publish("QP_LOG", &msg); + // Solve problem. if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index c5e591f2c8..bdbe343a4d 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -451,8 +451,8 @@ void OperationalSpaceControl::Build() { drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); - solver_options.SetOption(OsqpSolver::id(), "rho", 0.1); - solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "rho", 0.0001); + solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-5); solver_options.SetOption(OsqpSolver::id(), "max_iter", 4000); solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-6); solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); @@ -463,7 +463,7 @@ void OperationalSpaceControl::Build() { solver_options.SetOption(OsqpSolver::id(), "polish", 1); solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 3); solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); - solver_options.SetOption(OsqpSolver::id(), "check_termination", 10); + solver_options.SetOption(OsqpSolver::id(), "check_termination", 25); solver_options.SetOption(OsqpSolver::id(), "scaling", 10); solver_options.SetOption(OsqpSolver::id(), "adaptive_rho", 1); solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_interval", 0); @@ -1029,7 +1029,7 @@ void OperationalSpaceControl::CheckTracking( output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; // std::cout << "total cost: " << total_cost_ << std::endl; - if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { + if (soft_constraint_cost_ > 5e2 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } } From 98ff86a2d3359a910f208162401323af5be7c6ff Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 22 Feb 2022 09:05:47 -0500 Subject: [PATCH 099/758] fixing merge issues, osqp time limit doesn't seem to be enforced --- .../analysis/osqp_settings_sandbox.py | 3 +- examples/Cassie/BUILD.bazel | 1 - examples/Cassie/run_dircon_jumping.cc | 4 +- examples/Cassie/run_osc_running_controller.cc | 4 +- .../Cassie/run_osc_walking_controller_alip.cc | 2 +- solvers/fast_osqp_solver.cc | 82 ++++++++++--------- solvers/fast_osqp_solver.h | 21 ++++- 7 files changed, 72 insertions(+), 45 deletions(-) diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index 4f28f2a1e7..f18dfb9d70 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -91,7 +91,8 @@ def main(): 'sigma': 1e-6, 'alpha': 1.6, 'delta': 1e-6, - 'check_termination': 25} + 'check_termination': 25, + 'time_limit': 1e-3} osqp_result = solve_osqp(qp, osqp_settings) run_times[i] = osqp_result['run_time'] diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index c5ed5794af..7564a3e87f 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -358,7 +358,6 @@ cc_binary( "//lcm:trajectory_saver", "//multibody:utils", "//systems:robot_lcm_systems", - "//systems:system_utils", "//systems/controllers/osc:osc_tracking_datas", "//systems/framework:lcm_driven_loop", "//systems/primitives", diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index c945610eef..7d3ebb845d 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -802,7 +802,7 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, auto x_i = trajopt->state_vars(mode, index); auto u_i = trajopt->input_vars(mode, index); auto l_i = trajopt->force_vars(mode, index); - trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } } } @@ -895,7 +895,7 @@ void AddCostsSprings(Dircon* trajopt, auto x_i = trajopt->state_vars(mode, index); auto u_i = trajopt->input_vars(mode, index); auto l_i = trajopt->force_vars(mode, index); - trajopt->AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); } } } diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 4b3f513df0..a0ba275a86 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -86,6 +86,7 @@ DEFINE_string( DEFINE_double( fsm_time_offset, 0.0, "Time (s) in the fsm to move from the stance phase to the flight phase"); +DEFINE_double(qp_time_limit, 0.0, "Time limit (s) for the OSC QP"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -174,7 +175,8 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true); + plant, plant, plant_context.get(), plant_context.get(), true, false, + FLAGS_qp_time_limit); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index ea0731abd8..4bc91e2166 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -174,7 +174,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_output_port()); + high_level_command->get_cassie_out_input_port()); } else { high_level_command = builder.AddSystem( plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 1ffcb48b80..9f78d9212f 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -2,16 +2,16 @@ #include -#include "dairlib/lcmt_qp.hpp" #include #include +#include "dairlib/lcmt_qp.hpp" + #include "drake/common/text_logging.h" #include "drake/math/eigen_sparse_triplet.h" #include "drake/solvers/mathematical_program.h" #include "drake/solvers/osqp_solver.h" - using drake::math::SparseMatrixToTriplets; using drake::solvers::Binding; using drake::solvers::Constraint; @@ -206,9 +206,9 @@ csc* EigenSparseToCSC(const Eigen::SparseMatrix& mat) { } template -void SetFastOsqpSolverSetting(const std::unordered_map& options, - const std::string& option_name, - T2* osqp_setting_field) { +void SetFastOsqpSolverSetting( + const std::unordered_map& options, + const std::string& option_name, T2* osqp_setting_field) { const auto it = options.find(option_name); if (it != options.end()) { *osqp_setting_field = it->second; @@ -240,32 +240,34 @@ void SetFastOsqpSolverSettings(const SolverOptions& solver_options, SetFastOsqpSolverSetting(options_double, "eps_abs", &(settings->eps_abs)); SetFastOsqpSolverSetting(options_double, "eps_rel", &(settings->eps_rel)); SetFastOsqpSolverSetting(options_double, "eps_prim_inf", - &(settings->eps_prim_inf)); + &(settings->eps_prim_inf)); SetFastOsqpSolverSetting(options_double, "eps_dual_inf", - &(settings->eps_dual_inf)); + &(settings->eps_dual_inf)); SetFastOsqpSolverSetting(options_double, "alpha", &(settings->alpha)); SetFastOsqpSolverSetting(options_double, "delta", &(settings->delta)); // Default polish to true, to get an accurate solution. SetFastOsqpSolverSettingWithDefaultValue(options_int, "polish", - &(settings->polish), 1); + &(settings->polish), 1); SetFastOsqpSolverSetting(options_int, "polish_refine_iter", - &(settings->polish_refine_iter)); + &(settings->polish_refine_iter)); SetFastOsqpSolverSettingWithDefaultValue(options_int, "verbose", - &(settings->verbose), 0); + &(settings->verbose), 0); SetFastOsqpSolverSetting(options_int, "scaled_termination", - &(settings->scaled_termination)); + &(settings->scaled_termination)); SetFastOsqpSolverSetting(options_int, "check_termination", - &(settings->check_termination)); + &(settings->check_termination)); SetFastOsqpSolverSetting(options_int, "warm_start", &(settings->warm_start)); SetFastOsqpSolverSetting(options_int, "scaling", &(settings->scaling)); - SetFastOsqpSolverSetting(options_int, "adaptive_rho", &(settings->adaptive_rho)); + SetFastOsqpSolverSetting(options_int, "adaptive_rho", + &(settings->adaptive_rho)); SetFastOsqpSolverSetting(options_double, "adaptive_rho_interval", - &(settings->adaptive_rho_interval)); + &(settings->adaptive_rho_interval)); SetFastOsqpSolverSetting(options_double, "adaptive_rho_tolerance", - &(settings->adaptive_rho_tolerance)); + &(settings->adaptive_rho_tolerance)); SetFastOsqpSolverSetting(options_double, "adaptive_rho_fraction", - &(settings->adaptive_rho_fraction)); - SetFastOsqpSolverSetting(options_double, "time_limit", &(settings->time_limit)); + &(settings->adaptive_rho_fraction)); + SetFastOsqpSolverSetting(options_double, "time_limit", + &(settings->time_limit)); } template @@ -328,6 +330,7 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, osqp_settings_ = static_cast(c_malloc(sizeof(OSQPSettings))); osqp_set_default_settings(osqp_settings_); SetFastOsqpSolverSettings(solver_options, osqp_settings_); + std::cout << osqp_settings_->time_limit << std::endl; // Setup workspace. workspace_ = nullptr; @@ -336,6 +339,7 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, if (osqp_setup_err != 0) { std::cerr << "Error setting up osqp solver."; } + is_init_ = true; } void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, @@ -378,7 +382,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, osqp_update_bounds(workspace_, l.data(), u.data()); osqp_update_P_A(workspace_, P_csc->x, OSQP_NULL, P_csc->nzmax, A_csc->x, OSQP_NULL, A_csc->nzmax); - SetFastOsqpSolverSettings(merged_options, osqp_settings_); +// SetFastOsqpSolverSettings(merged_options, osqp_settings_); // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; @@ -394,7 +398,6 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, } msg.w = q; - Eigen::MatrixXd A(A_sparse); // std::cout << A.row(68) << std::endl; @@ -402,15 +405,17 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, for (int i = 0; i < A.rows(); i++) { std::vector row(A.cols()); for (int j = 0; j < A.cols(); j++) { - row[j] = A(i,j); + row[j] = A(i, j); } msg.A_ineq.push_back(row); } msg.ineq_lb = l; msg.ineq_ub = u; - msg.x_lb = std::vector(prog.num_vars(), -std::numeric_limits::infinity()); - msg.x_ub = std::vector(prog.num_vars(), std::numeric_limits::infinity()); + msg.x_lb = std::vector(prog.num_vars(), + -std::numeric_limits::infinity()); + msg.x_ub = std::vector(prog.num_vars(), + std::numeric_limits::infinity()); msg.n_eq = 0; lcm::LCM lcm; @@ -440,6 +445,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, switch (workspace_->info->status_val) { case OSQP_SOLVED: + this->EnableWarmStart(); case OSQP_SOLVED_INACCURATE: { const Eigen::Map> osqp_sol( workspace_->solution->x, prog.num_vars()); @@ -449,12 +455,12 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, solver_details.y = Eigen::Map(workspace_->solution->y, workspace_->data->m); solution_result = SolutionResult::kSolutionFound; -// SetDualSolution(prog.linear_constraints(), solver_details.y, -// constraint_start_row, result); -// SetDualSolution(prog.linear_equality_constraints(), solver_details.y, -// constraint_start_row, result); -// SetDualSolution(prog.bounding_box_constraints(), solver_details.y, -// constraint_start_row, result); + SetDualSolution(prog.linear_constraints(), solver_details.y, + constraint_start_row, result); + SetDualSolution(prog.linear_equality_constraints(), solver_details.y, + constraint_start_row, result); + SetDualSolution(prog.bounding_box_constraints(), solver_details.y, + constraint_start_row, result); break; } @@ -481,15 +487,17 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, } result->set_solution_result(solution_result.value()); -// osqp_cleanup(workspace_); - c_free(P_csc->x); - c_free(P_csc->i); - c_free(P_csc->p); - c_free(P_csc); - c_free(A_csc->x); - c_free(A_csc->i); - c_free(A_csc->p); - c_free(A_csc); + // osqp_cleanup(workspace_); + if (warm_start_) { + c_free(P_csc->x); + c_free(P_csc->i); + c_free(P_csc->p); + c_free(P_csc); + c_free(A_csc->x); + c_free(A_csc->i); + c_free(A_csc->p); + c_free(A_csc); + } } } // namespace solvers diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index ff56780f16..8dbfd5285c 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -37,6 +37,21 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { void InitializeSolver(const drake::solvers::MathematicalProgram&, const drake::solvers::SolverOptions&); + /// Solver will automatically reenable warm starting after a successful solve + void DisableWarmStart() const { + osqp_settings_->warm_start = false; + warm_start_ = false; + is_init_ = false; + } + /// Solver will automatically reenable warm starting after a successful solve + void EnableWarmStart() const { + osqp_settings_->warm_start = true; + warm_start_ = true; + } + + bool IsInitialized()const{ + return is_init_; + } // A using-declaration adds these methods into our class's Doxygen. using SolverBase::Solve; @@ -47,8 +62,10 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { drake::solvers::MathematicalProgramResult*) const final; OSQPData* osqp_data_; - OSQPSettings* osqp_settings_; - OSQPWorkspace* workspace_; + mutable OSQPSettings* osqp_settings_; + mutable OSQPWorkspace* workspace_; + mutable bool warm_start_ = true; + mutable bool is_init_ = false; }; } // namespace solvers } // namespace dairlib From f35a071798399797b68c3ceb91d89c614789e00c Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 1 Mar 2022 13:40:03 -0500 Subject: [PATCH 100/758] updating the regularization costs methods and how we log them --- examples/Cassie/run_osc_jumping_controller.cc | 11 +-- .../Cassie/run_osc_standing_controller.cc | 6 +- examples/Cassie/run_osc_walking_controller.cc | 7 +- .../Cassie/run_osc_walking_controller_alip.cc | 7 +- .../run_joint_space_walking_controller.cc | 4 +- lcmtypes/lcmt_osc_output.lcm | 11 +-- .../osc/operational_space_control.cc | 70 +++++++++++-------- .../osc/operational_space_control.h | 23 +++--- 8 files changed, 77 insertions(+), 62 deletions(-) diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 973d5dd500..5ca4c9b307 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -107,7 +107,8 @@ int DoMain(int argc, char* argv[]) { auto right_toe = RightToeFront(plant_w_spr); auto right_heel = RightToeRear(plant_w_spr); - int nv = plant_w_spr.num_velocities(); + int n_v = plant_w_spr.num_velocities(); + int n_u = plant_w_spr.num_actuators(); // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant_w_spr); @@ -283,14 +284,14 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost - MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); - osc->SetAccelerationCostForAllJoints(Q_accel); + MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); + osc->SetAccelerationCostWeights(Q_accel); // Soft constraint on contacts double w_contact_relax = gains.w_soft_constraint; - osc->SetWeightOfSoftContactConstraint(w_contact_relax); + osc->SetSoftConstraintWeight(w_contact_relax); // Soft constraint on contacts double w_input_reg = gains.w_input_reg; - osc->SetInputRegularizationWeight(w_input_reg); + osc->SetInputSmoothingWeights(gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Contact information for OSC osc->SetContactFriction(gains.mu); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index f028c6c1da..bd77402180 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -233,11 +233,11 @@ int DoMain(int argc, char* argv[]) { // We don't want w_contact_relax to be too big, cause we want tracking // error to be important double w_contact_relax = gains.w_soft_constraint; - osc->SetWeightOfSoftContactConstraint(w_contact_relax); + osc->SetSoftConstraintWeight(w_contact_relax); // Friction coefficient double mu = 0.8; osc->SetContactFriction(mu); - // Add contact points (The position doesn't matter. It's not used in OSC) + // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( plant_wo_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); @@ -257,7 +257,7 @@ int DoMain(int argc, char* argv[]) { // Cost int n_v = plant_wo_springs.num_velocities(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); - osc->SetAccelerationCostForAllJoints(Q_accel); + osc->SetAccelerationCostWeights(Q_accel); // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing // ComTrackingData center_of_mass_traj("com_traj", K_p_com, K_d_com, diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index c79f49f37a..e34f390c8b 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -369,9 +369,10 @@ int DoMain(int argc, char* argv[]) { // Cost int n_v = plant_w_spr.num_velocities(); + int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); - osc->SetAccelerationCostForAllJoints(Q_accel); - osc->SetInputRegularizationWeight(gains.w_input_reg); + osc->SetAccelerationCostWeights(Q_accel); + osc->SetInputSmoothingWeights(gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -412,7 +413,7 @@ int DoMain(int argc, char* argv[]) { // Soft constraint // w_contact_relax shouldn't be too big, cause we want tracking error to be // important - osc->SetWeightOfSoftContactConstraint(gains.w_soft_constraint); + osc->SetSoftConstraintWeight(gains.w_soft_constraint); // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points (The position doesn't matter. It's not used in OSC) diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index ea0731abd8..8eb9e0e8a9 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -335,9 +335,10 @@ int DoMain(int argc, char* argv[]) { // Cost int n_v = plant_w_spr.num_velocities(); + int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); - osc->SetAccelerationCostForAllJoints(Q_accel); - osc->SetInputRegularizationWeight(gains.w_input_reg); + osc->SetAccelerationCostWeights(Q_accel); + osc->SetInputSmoothingWeights(gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -378,7 +379,7 @@ int DoMain(int argc, char* argv[]) { // Soft constraint // w_contact_relax shouldn't be too big, cause we want tracking error to be // important - osc->SetWeightOfSoftContactConstraint(gains.w_soft_constraint); + osc->SetSoftConstraintWeight(gains.w_soft_constraint); // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points (The position doesn't matter. It's not used in OSC) diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 96214086f7..38320134bd 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -128,10 +128,10 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); - osc->SetAccelerationCostForAllJoints(Q_accel); + osc->SetAccelerationCostWeights(Q_accel); // Soft constraint on contacts double w_contact_relax = gains.w_soft_constraint; - osc->SetWeightOfSoftContactConstraint(w_contact_relax); + osc->SetSoftConstraintWeight(w_contact_relax); // Contact information for OSC osc->SetContactFriction(gains.mu); diff --git a/lcmtypes/lcmt_osc_output.lcm b/lcmtypes/lcmt_osc_output.lcm index 7629411ebe..57e7187198 100644 --- a/lcmtypes/lcmt_osc_output.lcm +++ b/lcmtypes/lcmt_osc_output.lcm @@ -5,13 +5,14 @@ struct lcmt_osc_output int64_t utime; int32_t fsm_state; int32_t num_tracking_data; + int32_t num_regularization_costs; - lcmt_osc_tracking_data tracking_data[num_tracking_data]; lcmt_osc_qp_output qp_output; + + lcmt_osc_tracking_data tracking_data[num_tracking_data]; string tracking_data_names[num_tracking_data]; + double tracking_costs [num_tracking_data]; - double input_cost; - double acceleration_cost; - double soft_constraint_cost; - double tracking_cost [num_tracking_data]; + double regularization_costs [num_regularization_costs]; + string regularization_cost_names [num_regularization_costs]; } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f31c0914c4..ffa35bd17e 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -164,16 +164,6 @@ void OperationalSpaceControl::SetUpDoubleSupportPhaseBlending( ds_states_ = ds_states; } -// Cost methods -void OperationalSpaceControl::AddAccelerationCost( - const std::string& joint_vel_name, double w) { - if (W_joint_accel_.size() == 0) { - W_joint_accel_ = Eigen::MatrixXd::Zero(n_v_, n_v_); - } - int idx = makeNameToVelocitiesMap(plant_wo_spr_).at(joint_vel_name); - W_joint_accel_(idx, idx) += w; -} - // Constraint methods void OperationalSpaceControl::AddContactPoint( const WorldPointEvaluator* evaluator) { @@ -247,6 +237,10 @@ void OperationalSpaceControl::CheckCostSettings() { if (W_input_.size() != 0) { DRAKE_DEMAND((W_input_.rows() == n_u_) && (W_input_.cols() == n_u_)); } + if (W_input_smoothing_.size() != 0) { + DRAKE_DEMAND((W_input_smoothing_.rows() == n_u_) && + (W_input_smoothing_.cols() == n_u_)); + } if (W_joint_accel_.size() != 0) { DRAKE_DEMAND((W_joint_accel_.rows() == n_v_) && (W_joint_accel_.cols() == n_v_)); @@ -392,6 +386,13 @@ void OperationalSpaceControl::Build() { w_soft_constraint_ * MatrixXd::Identity(n_c_active_, n_c_active_), VectorXd::Zero(n_c_active_), epsilon_); } + // (Testing) 7. Cost for staying close to the previous input + if (W_input_smoothing_.size() > 0) { + input_reg_cost_ = + prog_->AddQuadraticCost(W_input_smoothing_, VectorXd::Zero(n_u_), u_) + .evaluator() + .get(); + } // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { tracking_cost_.push_back(prog_ @@ -433,19 +434,10 @@ void OperationalSpaceControl::Build() { prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); } - // (Testing) 7. Cost for staying close to the previous input - if (w_input_reg_ > 0) { - W_input_reg_ = w_input_reg_ * MatrixXd::Identity(n_u_, n_u_); - input_reg_cost_ = - prog_->AddQuadraticCost(W_input_reg_, VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); - } - solver_ = std::make_unique(); drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); -// solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); + // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-7); solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); @@ -723,9 +715,9 @@ VectorXd OperationalSpaceControl::SolveQp( } // (Testing) 7. Cost for staying close to the previous input - if (w_input_reg_ > 0) { - input_reg_cost_->UpdateCoefficients(W_input_reg_, - -W_input_reg_ * (*u_sol_)); + if (W_input_smoothing_.size() > 0) { + input_reg_cost_->UpdateCoefficients(W_input_smoothing_, + -W_input_smoothing_ * (*u_sol_)); } // Solve the QP @@ -844,23 +836,40 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->utime = state->get_timestamp() * 1e6; output->fsm_state = fsm_state; - output->input_cost = + double input_cost = (W_input_.size() > 0) ? (0.5 * (*u_sol_).transpose() * W_input_ * (*u_sol_))(0) : 0; - output->acceleration_cost = + double acceleration_cost = (W_joint_accel_.size() > 0) ? (0.5 * (*dv_sol_).transpose() * W_joint_accel_ * (*dv_sol_))(0) : 0; - output->soft_constraint_cost = + double soft_constraint_cost = (w_soft_constraint_ > 0) ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * (*epsilon_sol_))(0) : 0; + double input_smoothing_cost = + (W_input_smoothing_.size() > 0) + ? (0.5 * (*u_sol_).transpose() * W_input_smoothing_ * (*u_sol_))(0) + : 0; + + output->regularization_costs.clear(); + output->regularization_cost_names.clear(); + + output->regularization_costs.reserve(4); + output->regularization_costs.push_back(input_cost); + output->regularization_cost_names.push_back("input_cost"); + output->regularization_costs.push_back(acceleration_cost); + output->regularization_cost_names.push_back("acceleration_cost"); + output->regularization_costs.push_back(soft_constraint_cost); + output->regularization_cost_names.push_back("soft_constraint_cost"); + output->regularization_costs.push_back(input_smoothing_cost); + output->regularization_cost_names.push_back("input_smoothing_cost"); output->tracking_data_names.clear(); output->tracking_data.clear(); - output->tracking_cost.clear(); + output->tracking_costs.clear(); lcmt_osc_qp_output qp_output; qp_output.solve_time = solve_time_; @@ -877,7 +886,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->qp_output = qp_output; output->tracking_data.reserve(tracking_data_vec_->size()); - output->tracking_cost = std::vector(tracking_data_vec_->size()); + output->tracking_costs = std::vector(tracking_data_vec_->size()); for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); @@ -912,13 +921,14 @@ void OperationalSpaceControl::AssignOscLcmOutput( const MatrixXd& W = tracking_data->GetWeight(); const MatrixXd& J_t = tracking_data->GetJ(); const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); - output->tracking_cost[i] = + output->tracking_costs[i] = (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); } } output->num_tracking_data = output->tracking_data_names.size(); + output->num_regularization_costs = output->regularization_cost_names.size(); } void OperationalSpaceControl::CalcOptimalInput( @@ -977,4 +987,4 @@ void OperationalSpaceControl::CalcOptimalInput( control->set_timestamp(robot_output->get_timestamp()); } -} // namespace dairlib::systems::controllers +} // namespace dairlib::systems::controllers \ No newline at end of file diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index c6b7299f39..70cada0d85 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -130,19 +130,22 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { return this->get_input_port(0); } - // Cost methods - void SetInputCost(const Eigen::MatrixXd& W) { W_input_ = W; } - void SetAccelerationCostForAllJoints(const Eigen::MatrixXd& W) { + // Regularization cost weights + void SetInputCostWeights(const Eigen::MatrixXd& W) { W_input_ = W; } + void SetAccelerationCostWeights(const Eigen::MatrixXd& W) { W_joint_accel_ = W; } - void AddAccelerationCost(const std::string& joint_vel_name, double w); + void SetInputSmoothingWeights(const Eigen::MatrixXd& W) { + W_input_smoothing_ = W; + } + void SetSoftConstraintWeight(double w_soft_constraint) { + w_soft_constraint_ = w_soft_constraint; + } // Constraint methods void DisableAcutationConstraint() { with_input_constraints_ = false; } void SetContactFriction(double mu) { mu_ = mu; } - void SetWeightOfSoftContactConstraint(double w_soft_constraint) { - w_soft_constraint_ = w_soft_constraint; - } + void AddContactPoint(const multibody::WorldPointEvaluator* evaluator); void AddStateAndContactPoint( int state, const multibody::WorldPointEvaluator* evaluator); @@ -169,7 +172,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int left_support_state, int right_support_state, std::vector ds_states); - void SetInputRegularizationWeight(double w) { w_input_reg_ = w; } // OSC LeafSystem builder void Build(); @@ -307,10 +309,10 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { /// could consider using acceleration cost instead. Eigen::MatrixXd W_input_; // Input cost weight Eigen::MatrixXd W_joint_accel_; // Joint acceleration cost weight + Eigen::MatrixXd W_input_smoothing_; // OSC constraint members bool with_input_constraints_ = true; - // Soft contact penalty coefficient and friction cone coefficient double mu_ = -1; // Friction coefficients double w_soft_constraint_ = -1; @@ -353,8 +355,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Optional feature -- regularizing input drake::solvers::QuadraticCost* input_reg_cost_; - double w_input_reg_ = -1; - Eigen::MatrixXd W_input_reg_; + }; } // namespace dairlib::systems::controllers From 76daf5cf02549974960ba729cc85215084d6c347 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 1 Mar 2022 14:53:50 -0500 Subject: [PATCH 101/758] playing with qp costs --- .../analysis/osqp_settings_sandbox.py | 3 +- .../Cassie/osc_run/osc_running_gains.yaml | 18 ++++-- examples/Cassie/run_osc_hopping_controller.cc | 8 ++- examples/Cassie/run_osc_running_controller.cc | 10 +-- .../Cassie/run_osc_standing_controller.cc | 6 +- .../osc/operational_space_control.cc | 64 +++++++++++-------- .../osc/operational_space_control.h | 7 +- systems/controllers/osc/osc_gains.h | 23 +++++++ 8 files changed, 96 insertions(+), 43 deletions(-) diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index f18dfb9d70..4f8356d4dc 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -73,6 +73,7 @@ def main(): run_times = np.zeros((len(qp_list),)) obj_vals = np.zeros((len(qp_list),)) pri_eps_vals = np.zeros((len(qp_list,))) + # sols = np.zeros((len(qp_list,), 60)) sols = np.zeros((len(qp_list,), 60)) for i, qp in enumerate(qp_list): @@ -92,7 +93,7 @@ def main(): 'alpha': 1.6, 'delta': 1e-6, 'check_termination': 25, - 'time_limit': 1e-3} + 'time_limit': 1e-4} osqp_result = solve_osqp(qp, osqp_settings) run_times[i] = osqp_result['run_time'] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4947f22027..940b947569 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,15 @@ w_input: 0.000001 -w_accel: 0.000001 +w_accel: 0.0001 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [1, 0.9, 0.5, 0.1, 1, + 1, 0.9, 0.5, 0.1, 1] +W_lambda_reg: [1, 1, 1, + 1, 1, 1] #w_soft_constraint: 1000000 -w_soft_constraint: 0.01 +w_soft_constraint: 0.0 w_input_reg: 0.01 impact_threshold: 0.025 relative_feet: true @@ -23,11 +31,11 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 2.5 +w_hip_yaw: 1 hip_yaw_kp: 60 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: -0.03 +footstep_offset: -0.05 center_line_offset: 0.05 FootstepKd: [ 0.2, 0, 0, @@ -36,7 +44,7 @@ FootstepKd: PelvisW: [0.1, 0, 0, 0, 0, 0, - 0, 0, 1] + 0, 0, 5] PelvisKp: [ 0, 0, 0, 0, 0, 0, diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index db67b08aae..ff35e28237 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -109,6 +109,7 @@ int DoMain(int argc, char* argv[]) { auto right_heel = RightToeRear(plant); int nv = plant.num_velocities(); + int nu = plant.num_velocities(); // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); @@ -185,12 +186,13 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); - osc->SetAccelerationCostForAllJoints(Q_accel); - osc->SetInputRegularizationWeight(gains.w_input_reg); + osc->SetAccelerationCostWeights(Q_accel); + osc->SetInputSmoothingWeights(gains.w_input_reg * + MatrixXd::Identity(nu, nu)); // Soft constraint on contacts double w_contact_relax = gains.w_soft_constraint; - osc->SetWeightOfSoftContactConstraint(w_contact_relax); + osc->SetSoftConstraintWeight(w_contact_relax); // Contact information for OSC osc->SetContactFriction(gains.mu); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index a0ba275a86..b5e18f6a74 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -189,13 +189,13 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost - MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); - osc->SetAccelerationCostForAllJoints(Q_accel); - osc->SetInputRegularizationWeight(gains.w_input_reg); + /// REGULARIZATION COSTS + osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); + osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetLambdaRegularizationWeight(1e-8 * gains.W_lambda_regularization); // Soft constraint on contacts - double w_contact_relax = gains.w_soft_constraint; - osc->SetWeightOfSoftContactConstraint(w_contact_relax); + osc->SetSoftConstraintWeight(gains.w_soft_constraint); // Contact information for OSC osc->SetContactFriction(gains.mu); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index bd77402180..a3b7b662a5 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -267,9 +267,9 @@ int DoMain(int argc, char* argv[]) { "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, plant_w_springs, plant_wo_springs); center_of_mass_traj.AddPointToTrack("pelvis"); - double cutoff_freq = 5; // in Hz - double tau = 1 / (2 * M_PI * cutoff_freq); - center_of_mass_traj.SetLowPassFilter(tau, {1}); + // double cutoff_freq = 5; // in Hz + // double tau = 1 / (2 * M_PI * cutoff_freq); + center_of_mass_traj.SetLowPassFilter(0.09, {1}); osc->AddTrackingData(¢er_of_mass_traj); // Pelvis rotation tracking RotTaskSpaceTrackingData pelvis_rot_traj( diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 7a5ed9e27f..ca8398e734 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -304,6 +304,7 @@ void OperationalSpaceControl::Build() { lambda_c_sol_ = std::make_unique(n_c_); lambda_h_sol_ = std::make_unique(n_h_); epsilon_sol_ = std::make_unique(n_c_active_); + u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); lambda_c_sol_->setZero(); @@ -386,6 +387,10 @@ void OperationalSpaceControl::Build() { if (W_joint_accel_.size() > 0) { prog_->AddQuadraticCost(W_joint_accel_, VectorXd::Zero(n_v_), dv_); } + // 3. constraint force cost + if (W_lambda_reg_.size() > 0) { + prog_->AddQuadraticCost(W_lambda_reg_, VectorXd::Zero(n_h_), lambda_h_); + } // 3. Soft constraint cost if (w_soft_constraint_ > 0) { prog_->AddQuadraticCost( @@ -394,7 +399,7 @@ void OperationalSpaceControl::Build() { } // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0) { - input_reg_cost_ = + input_smoothing_cost_ = prog_->AddQuadraticCost(W_input_smoothing_, VectorXd::Zero(n_u_), u_) .evaluator() .get(); @@ -443,11 +448,11 @@ void OperationalSpaceControl::Build() { solver_ = std::make_unique(); drake::solvers::SolverOptions solver_options; solver_options.SetOption(OsqpSolver::id(), "verbose", 0); - // solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); + solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); solver_options.SetOption(OsqpSolver::id(), "rho", 0.0001); - solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-5); + solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-6); solver_options.SetOption(OsqpSolver::id(), "max_iter", 4000); - solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-6); + solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-5); solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-5); solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-5); @@ -736,22 +741,31 @@ VectorXd OperationalSpaceControl::SolveQp( // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0) { - input_reg_cost_->UpdateCoefficients(W_input_smoothing_, - -W_input_smoothing_ * (*u_sol_)); + input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, + -W_input_smoothing_ * (*u_prev_)); } + if (!solver_->IsInitialized()) { + solver_->InitializeSolver(*prog_, solver_options_); + } // Solve the QP const MathematicalProgramResult result = solver_->Solve(*prog_); + if (result.is_success()) { + // Extract solutions + *dv_sol_ = result.GetSolution(dv_); + *u_sol_ = result.GetSolution(u_); + *lambda_c_sol_ = result.GetSolution(lambda_c_); + *lambda_h_sol_ = result.GetSolution(lambda_h_); + *epsilon_sol_ = result.GetSolution(epsilon_); + *u_prev_ = *u_sol_; + } else { + std::cerr << "QP did not solve in time!" << std::endl; + solver_->DisableWarmStart(); + *u_prev_ = VectorXd::Zero(n_u_); + } solve_time_ = result.get_solver_details().run_time; - // Extract solutions - *dv_sol_ = result.GetSolution(dv_); - *u_sol_ = result.GetSolution(u_); - *lambda_c_sol_ = result.GetSolution(lambda_c_); - *lambda_h_sol_ = result.GetSolution(lambda_h_); - *epsilon_sol_ = result.GetSolution(epsilon_); - for (auto tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state)) { tracking_data->StoreYddotCommandSol(*dv_sol_); @@ -868,7 +882,11 @@ void OperationalSpaceControl::AssignOscLcmOutput( : 0; double input_smoothing_cost = (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_).transpose() * W_input_smoothing_ * (*u_sol_))(0) + ? (0.5 * (*u_sol_- *u_prev_).transpose() * W_input_smoothing_ * (*u_sol_ - *u_prev_))(0) + : 0; + double lambda_h_cost = + (W_lambda_reg_.size() > 0) + ? (0.5 * (*lambda_h_sol_).transpose() * W_input_smoothing_ * (*lambda_h_sol_))(0) : 0; output->regularization_costs.clear(); @@ -883,6 +901,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->regularization_cost_names.push_back("soft_constraint_cost"); output->regularization_costs.push_back(input_smoothing_cost); output->regularization_cost_names.push_back("input_smoothing_cost"); + output->regularization_costs.push_back(lambda_h_cost); + output->regularization_cost_names.push_back("lambda_h_cost"); output->tracking_data_names.clear(); output->tracking_data.clear(); @@ -904,15 +924,10 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_data = std::vector(tracking_data_vec_->size()); - output->tracking_cost = std::vector(tracking_data_vec_->size()); + output->tracking_costs = std::vector(tracking_data_vec_->size()); output->tracking_data_names = std::vector(tracking_data_vec_->size()); - total_cost_ += output->acceleration_cost; - total_cost_ += output->input_cost; - total_cost_ += output->soft_constraint_cost; - soft_constraint_cost_ = output->soft_constraint_cost; - for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i); output->tracking_data_names[i] = tracking_data->GetName(); @@ -932,7 +947,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command = std::vector(osc_output.ydot_dim); osc_output.yddot_command_sol = std::vector(osc_output.ydot_dim); - output->tracking_cost[i] = 0; + output->tracking_costs[i] = 0; if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && time_since_last_state_switch <= t_e_vec_.at(i)) { @@ -958,7 +973,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_costs[i] = (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); - total_cost_ += output->tracking_cost[i]; + total_cost_ += output->tracking_costs[i]; } output->tracking_data[i] = osc_output; } @@ -1005,9 +1020,8 @@ void OperationalSpaceControl::CalcOptimalInput( double alpha = 0; int next_fsm_state = -1; if (this->get_near_impact_input_port().HasValue(context)) { - auto impact_info = - (ImpactInfoVector*)this->EvalVectorInput(context, - impact_info_port_); + auto impact_info = (ImpactInfoVector*)this->EvalVectorInput( + context, impact_info_port_); alpha = impact_info->GetAlpha(); next_fsm_state = impact_info->GetCurrentContactMode(); } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 101c75ffcd..bed950737a 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -148,6 +148,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void SetSoftConstraintWeight(double w_soft_constraint) { w_soft_constraint_ = w_soft_constraint; } + void SetLambdaRegularizationWeight(const Eigen::MatrixXd& W) { + W_lambda_reg_ = W; + } // Constraint methods void DisableAcutationConstraint() { with_input_constraints_ = false; } @@ -324,6 +327,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector friction_constraints_; std::vector tracking_cost_; std::vector joint_limit_cost_; + drake::solvers::QuadraticCost* input_smoothing_cost_; // OSC solution std::unique_ptr dv_sol_; @@ -331,6 +335,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::unique_ptr lambda_c_sol_; std::unique_ptr lambda_h_sol_; std::unique_ptr epsilon_sol_; + std::unique_ptr u_prev_; mutable double solve_time_; mutable Eigen::VectorXd ii_lambda_sol_; @@ -343,6 +348,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::MatrixXd W_input_; // Input cost weight Eigen::MatrixXd W_joint_accel_; // Joint acceleration cost weight Eigen::MatrixXd W_input_smoothing_; + Eigen::MatrixXd W_lambda_reg_; // OSC constraint members bool with_input_constraints_ = true; @@ -387,7 +393,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::VectorXDecisionVariable epsilon_blend_; // Optional feature -- regularizing input - std::shared_ptr input_reg_cost_; mutable double total_cost_ = 0; mutable double soft_constraint_cost_ = 0; }; diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index 8d3087f183..ba59649391 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -14,6 +14,13 @@ struct OSCGains { double w_soft_constraint; double impact_threshold; double mu; + std::vector W_accel; + std::vector W_input_reg; + std::vector W_lambda_reg; + + MatrixXd W_acceleration; + MatrixXd W_input_regularization; + MatrixXd W_lambda_regularization; template void Serialize(Archive* a) { @@ -23,5 +30,21 @@ struct OSCGains { a->Visit(DRAKE_NVP(w_soft_constraint)); a->Visit(DRAKE_NVP(impact_threshold)); a->Visit(DRAKE_NVP(mu)); + a->Visit(DRAKE_NVP(W_accel)); + a->Visit(DRAKE_NVP(W_input_reg)); + a->Visit(DRAKE_NVP(W_lambda_reg)); + + Eigen::VectorXd w_acceleration = + Eigen::Map(this->W_accel.data(), + this->W_accel.size()); + Eigen::VectorXd w_input_regularization = + Eigen::Map(this->W_input_reg.data(), + this->W_input_reg.size()); + Eigen::VectorXd w_lambda_regularization = + Eigen::Map( + this->W_lambda_reg.data(), this->W_lambda_reg.size()); + W_acceleration = w_acceleration.asDiagonal(); + W_input_regularization = w_input_regularization.asDiagonal(); + W_lambda_regularization = w_lambda_regularization.asDiagonal(); } }; \ No newline at end of file From f3f8ce5344b112024afd60841eb1f3ecebafcc14 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 1 Mar 2022 16:24:12 -0500 Subject: [PATCH 102/758] adding stiffness settings for mbp sim --- bindings/pydairlib/multibody/multibody_py.cc | 10 +++++----- .../director_scripts/controller_status.py | 2 +- examples/Cassie/multibody_sim.cc | 2 +- .../Cassie/multibody_sim_w_ground_incline.cc | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 6 +++--- examples/Cassie/run_dircon_walking.cc | 4 ++-- examples/Cassie/run_osc_running_controller.cc | 3 ++- examples/Cassie/standalone_multibody_sim.cc | 2 +- examples/Cassie/visualizer.cc | 2 +- .../five_link_biped_sim.cc | 2 +- lcmtypes/lcmt_osc_output.lcm | 5 ++--- multibody/multibody_utils.cc | 19 ++++++++++++++----- multibody/multibody_utils.h | 5 +++-- .../osc/operational_space_control.cc | 2 +- 15 files changed, 39 insertions(+), 29 deletions(-) diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index c76f8a8a7d..1ee5a1c5b5 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -38,11 +38,11 @@ PYBIND11_MODULE(multibody, m) { .def("createActuatorNameVectorFromMap", &dairlib::multibody::createActuatorNameVectorFromMap, py::arg("plant")) - .def("addFlatTerrain", - &dairlib::multibody::addFlatTerrain, py::arg("plant"), - py::arg("scene_graph"), py::arg("mu_static"), py::arg("mu_kinetic"), - py::arg("normal_W") = Eigen::Vector3d(0, 0, 1)); - + .def("AddFlatTerrain", &dairlib::multibody::AddFlatTerrain, + py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"), + py::arg("mu_kinetic"), + py::arg("normal_W") = Eigen::Vector3d(0, 0, 1), + py::arg("stiffness") = 1e4, py::arg("dissipation_rate") = 0.5); } } // namespace pydairlib diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py index cc01ff3f5f..b467547c12 100644 --- a/examples/Cassie/director_scripts/controller_status.py +++ b/examples/Cassie/director_scripts/controller_status.py @@ -17,7 +17,7 @@ def __init__(self): self.text_box = vis.TextItem('safety_info', 'safety_info', view) self.text_box.setProperty('Font Size', 18) - self.text_box.setProperty('Position', [0, 1600]) + self.text_box.setProperty('Position', [1600, 10]) self.set_enabled(True) diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index bd5e6cfad9..6d1bc53a9c 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -86,7 +86,7 @@ int do_main(int argc, char* argv[]) { const double time_step = FLAGS_time_stepping ? FLAGS_dt : 0.0; MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::addFlatTerrain(&plant, &scene_graph, .8, .8); + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); } std::string urdf; diff --git a/examples/Cassie/multibody_sim_w_ground_incline.cc b/examples/Cassie/multibody_sim_w_ground_incline.cc index e2f29e9dc1..25a78fe613 100644 --- a/examples/Cassie/multibody_sim_w_ground_incline.cc +++ b/examples/Cassie/multibody_sim_w_ground_incline.cc @@ -150,7 +150,7 @@ int do_main(int argc, char* argv[]) { drake::multibody::MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::addFlatTerrain(&plant, &scene_graph, .8, .8, ground_normal); + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8, ground_normal); } std::string urdf; diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 9056b6efa8..87d19153ff 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -84,7 +84,7 @@ int do_main(int argc, char* argv[]) { const double time_step = FLAGS_dt; MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::addFlatTerrain(&plant, &scene_graph, .8, .8); + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); } std::string urdf; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 940b947569..716b3d9ec4 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,13 +1,13 @@ w_input: 0.000001 -w_accel: 0.0001 +w_accel: 0.00001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 1, 1, 0.9, 0.5, 0.1, 1] -W_lambda_reg: [1, 1, 1, - 1, 1, 1] +W_lambda_reg: [0.001, 0.001, 0.01, + 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 w_soft_constraint: 0.0 w_input_reg: 0.01 diff --git a/examples/Cassie/run_dircon_walking.cc b/examples/Cassie/run_dircon_walking.cc index a15bb24c97..cb43f307fc 100644 --- a/examples/Cassie/run_dircon_walking.cc +++ b/examples/Cassie/run_dircon_walking.cc @@ -200,7 +200,7 @@ vector GetInitGuessForQ(int N, double stride_length, scene_graph_ik.set_name("scene_graph_ik"); MultibodyPlant plant_ik(0.0); Vector3d ground_normal(sin(ground_incline), 0, cos(ground_incline)); - multibody::addFlatTerrain(&plant_ik, &scene_graph_ik, .8, .8, + multibody::AddFlatTerrain(&plant_ik, &scene_graph_ik, .8, .8, ground_normal); Parser parser(&plant_ik, &scene_graph_ik); string full_name = @@ -291,7 +291,7 @@ void DoMain(double duration, double stride_length, double ground_incline, MultibodyPlant plant(0.0); Vector3d ground_normal(sin(ground_incline), 0, cos(ground_incline)); - multibody::addFlatTerrain(&plant, &scene_graph, 1, 1, ground_normal); + multibody::AddFlatTerrain(&plant, &scene_graph, 1, 1, ground_normal); Parser parser(&plant, &scene_graph); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b5e18f6a74..f20338baf2 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -192,7 +192,8 @@ int DoMain(int argc, char* argv[]) { /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); - osc->SetLambdaRegularizationWeight(1e-8 * gains.W_lambda_regularization); +// osc->SetInputCostWeights(1e-3 * gains.W_input_regularization); + osc->SetLambdaRegularizationWeight(1e-6 * gains.W_lambda_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(gains.w_soft_constraint); diff --git a/examples/Cassie/standalone_multibody_sim.cc b/examples/Cassie/standalone_multibody_sim.cc index d1d70ec4fb..cfbc181777 100644 --- a/examples/Cassie/standalone_multibody_sim.cc +++ b/examples/Cassie/standalone_multibody_sim.cc @@ -48,7 +48,7 @@ int do_main(int argc, char* argv[]) { *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::addFlatTerrain(&plant, &scene_graph, .8, .8); + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); } addCassieMultibody(&plant, &scene_graph, FLAGS_floating_base); diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 88db9be042..23939581ef 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -61,7 +61,7 @@ int do_main(int argc, char* argv[]) { // Ground direction Eigen::Vector3d ground_normal(sin(FLAGS_ground_incline), 0, cos(FLAGS_ground_incline)); - multibody::addFlatTerrain(&plant, &scene_graph, 0.8, 0.8, ground_normal); + multibody::AddFlatTerrain(&plant, &scene_graph, 0.8, 0.8, ground_normal); } plant.Finalize(); diff --git a/examples/impact_invariant_control/five_link_biped_sim.cc b/examples/impact_invariant_control/five_link_biped_sim.cc index c70da07c5e..e0ad093cd3 100644 --- a/examples/impact_invariant_control/five_link_biped_sim.cc +++ b/examples/impact_invariant_control/five_link_biped_sim.cc @@ -83,7 +83,7 @@ int do_main(int argc, char* argv[]) { parser.AddModelFromFile(full_name); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform()); - multibody::addFlatTerrain(&plant, &scene_graph, .8, .8); // Add ground + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); // Add ground plant.Finalize(); int nv = plant.num_velocities(); diff --git a/lcmtypes/lcmt_osc_output.lcm b/lcmtypes/lcmt_osc_output.lcm index 57e7187198..8dc99a866f 100644 --- a/lcmtypes/lcmt_osc_output.lcm +++ b/lcmtypes/lcmt_osc_output.lcm @@ -8,11 +8,10 @@ struct lcmt_osc_output int32_t num_regularization_costs; lcmt_osc_qp_output qp_output; - - lcmt_osc_tracking_data tracking_data[num_tracking_data]; string tracking_data_names[num_tracking_data]; double tracking_costs [num_tracking_data]; - double regularization_costs [num_regularization_costs]; string regularization_cost_names [num_regularization_costs]; + + lcmt_osc_tracking_data tracking_data[num_tracking_data]; } diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 3fc030d456..7add8dba41 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -5,6 +5,7 @@ #include "drake/common/drake_assert.h" #include "drake/math/autodiff_gradient.h" +#include "drake/geometry/proximity_properties.h" namespace dairlib { namespace multibody { @@ -118,23 +119,31 @@ void SetInputsIfNew(const MultibodyPlant& plant, } } + template -void addFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, +void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, - Eigen::Vector3d normal_W) { + Eigen::Vector3d normal_W, double stiffness, double dissipation_rate) { if (!plant->geometry_source_is_registered()) { plant->RegisterAsSourceForSceneGraph(scene_graph); } Eigen::Vector3d point_W(0, 0, 0); - drake::multibody::CoulombFriction friction(mu_static, mu_kinetic); // A half-space for the ground geometry. const drake::math::RigidTransformd X_WG( HalfSpace::MakePose(normal_W, point_W)); + drake::geometry::ProximityProperties props; + props.AddProperty("material", "point_contact_stiffness", stiffness); + props.AddProperty("material", "hunt_crossley_dissipation", + dissipation_rate); + props.AddProperty(drake::geometry::internal::kMaterialGroup, + drake::geometry::internal::kFriction, + drake::multibody::CoulombFriction(mu_static, mu_kinetic)); + plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), - "collision", friction); + "collision", props); // Add visual for the ground. // plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), @@ -510,7 +519,7 @@ template vector createActuatorNameVectorFromMap(const MultibodyPlant createActuatorNameVectorFromMap(const MultibodyPlant& plant); // NOLINT template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT -template void addFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W); // NOLINT +template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W, double stiffness, double dissipation_rate); // NOLINT template VectorX getInput(const MultibodyPlant& plant, const Context& context); // NOLINT template VectorX getInput(const MultibodyPlant& plant, const Context& context); // NOLINT template std::unique_ptr> createContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref& input); // NOLINT diff --git a/multibody/multibody_utils.h b/multibody/multibody_utils.h index 61c96f93fe..7a38af2bc4 100644 --- a/multibody/multibody_utils.h +++ b/multibody/multibody_utils.h @@ -64,10 +64,11 @@ void SetInputsIfNew(const drake::multibody::MultibodyPlant& plant, /// default direction) // TODO: we might want to add other types of terrain in the future template -void addFlatTerrain(drake::multibody::MultibodyPlant* plant, +void AddFlatTerrain(drake::multibody::MultibodyPlant* plant, drake::geometry::SceneGraph* scene_graph, double mu_static, double mu_kinetic, - Eigen::Vector3d normal_W = Eigen::Vector3d(0, 0, 1)); + Eigen::Vector3d normal_W = Eigen::Vector3d(0, 0, 1), + double stiffness = 1e4, double dissipation_rate = 5); /// Given a MultiBodyTree, builds a map from position name to position index template diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index ca8398e734..2572ce4ae4 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -886,7 +886,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( : 0; double lambda_h_cost = (W_lambda_reg_.size() > 0) - ? (0.5 * (*lambda_h_sol_).transpose() * W_input_smoothing_ * (*lambda_h_sol_))(0) + ? (0.5 * (*lambda_h_sol_).transpose() * W_lambda_reg_ * (*lambda_h_sol_))(0) : 0; output->regularization_costs.clear(); From 995ccfd5e488c6d82129198e74debc174bc1ee7b Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 4 Mar 2022 14:05:06 -0500 Subject: [PATCH 103/758] attempting to improve running qp --- examples/Cassie/BUILD.bazel | 3 +- .../director_scripts/controller_status.py | 2 +- examples/Cassie/multibody_sim.cc | 27 ++++++-- .../Cassie/osc_jump/osc_jumping_gains.yaml | 20 ++++-- .../Cassie/osc_run/osc_running_gains.yaml | 16 +++-- examples/Cassie/run_osc_hopping_controller.cc | 10 +-- examples/Cassie/run_osc_jumping_controller.cc | 17 +++-- examples/Cassie/run_osc_running_controller.cc | 22 ++++--- .../Cassie/run_osc_standing_controller.cc | 2 +- examples/Cassie/urdf/cassie_v2.urdf | 8 +-- multibody/multibody_utils.cc | 26 +++++--- multibody/multibody_utils.h | 2 +- solvers/fast_osqp_solver.cc | 16 ++++- solvers/fast_osqp_solver.h | 3 + systems/controllers/BUILD.bazel | 14 ++++ systems/controllers/geared_motor.cc | 66 +++++++++++++++++++ systems/controllers/geared_motor.h | 58 ++++++++++++++++ .../osc/operational_space_control.cc | 53 +++++++++++---- .../osc/operational_space_control.h | 21 +++--- systems/controllers/osc/osc_gains.h | 19 ++++-- 20 files changed, 323 insertions(+), 82 deletions(-) create mode 100644 systems/controllers/geared_motor.cc create mode 100644 systems/controllers/geared_motor.h diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 7564a3e87f..90a20b36d1 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -210,6 +210,7 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//systems:robot_lcm_systems", + "//systems/controllers:geared_motor", "//systems/primitives", "@drake//:drake_shared_library", "@gflags", @@ -358,11 +359,11 @@ cc_binary( "//lcm:trajectory_saver", "//multibody:utils", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/controllers/osc:osc_tracking_datas", "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", - "//systems:system_utils", "@gflags", ], ) diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py index b467547c12..459162ea9f 100644 --- a/examples/Cassie/director_scripts/controller_status.py +++ b/examples/Cassie/director_scripts/controller_status.py @@ -17,7 +17,7 @@ def __init__(self): self.text_box = vis.TextItem('safety_info', 'safety_info', view) self.text_box.setProperty('Font Size', 18) - self.text_box.setProperty('Position', [1600, 10]) + self.text_box.setProperty('Position', [1200, 10]) self.set_enabled(True) diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 6d1bc53a9c..bd02d6f401 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -9,6 +9,7 @@ #include "examples/Cassie/cassie_fixed_point_solver.h" #include "examples/Cassie/cassie_utils.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/geared_motor.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" @@ -86,7 +87,8 @@ int do_main(int argc, char* argv[]) { const double time_step = FLAGS_time_stepping ? FLAGS_dt : 0.0; MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); + // multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); + multibody::AddFlatTerrain(&plant, &scene_graph, 1e4, 1e2); } std::string urdf; @@ -132,8 +134,9 @@ int do_main(int argc, char* argv[]) { contact_results_publisher.set_name("contact_results_publisher"); // Sensor aggregator and publisher of lcmt_cassie_out - auto radio_sub = builder.AddSystem( - LcmSubscriberSystem::Make(FLAGS_radio_channel, lcm)); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + FLAGS_radio_channel, lcm)); const auto& sensor_aggregator = AddImuAndAggregator(&builder, plant, passthrough->get_output_port()); @@ -141,15 +144,31 @@ int do_main(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); + std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, + 303.687, 303.687, 136.136, 136.135, 575.958}; + + auto cassie_motor = builder.AddSystem(plant, omega_max); + // connect leaf systems builder.Connect(*input_sub, *input_receiver); - builder.Connect(*input_receiver, *passthrough); + bool motor_model = true; + if (motor_model) { + builder.Connect(input_receiver->get_output_port(), + cassie_motor->get_input_port_command()); + builder.Connect(cassie_motor->get_output_port(), + passthrough->get_input_port()); + } else { + builder.Connect(input_receiver->get_output_port(), + passthrough->get_input_port()); + } builder.Connect(passthrough->get_output_port(), discrete_time_delay->get_input_port()); builder.Connect(discrete_time_delay->get_output_port(), plant.get_actuation_input_port()); builder.Connect(plant.get_state_output_port(), state_sender->get_input_port_state()); + builder.Connect(plant.get_state_output_port(), + cassie_motor->get_input_port_state()); builder.Connect(discrete_time_delay->get_output_port(), state_sender->get_input_port_effort()); builder.Connect(*state_sender, *state_pub); diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 49f3ccb49f..b5fd616ce3 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,8 +1,16 @@ w_input: 0.000 w_accel: 0.0000001 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [1, 0.9, 0.5, 0.1, 1, + 1, 0.9, 0.5, 0.1, 1] +W_lambda_reg: [0.001, 0.001, 0.01, + 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 100 -x_offset: 0.0 +x_offset: -0.0 relative_feet: true mu: 0.8 @@ -16,7 +24,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 5 impact_threshold: 0.050 -landing_delay: 0.050 +landing_delay: 0.000 CoMW: [20, 0, 0, @@ -31,11 +39,11 @@ FlightFootW: 0, 1, 0, 0, 0, 1] CoMKp: - [50, 0, 0, + [25, 0, 0, 0, 50, 0, 0, 0, 50] CoMKd: - [ 5, 0, 0, + [ 7.5, 0, 0, 0, 5, 0, 0, 0, 5] PelvisRotKp: @@ -47,11 +55,11 @@ PelvisRotKd: 0, 10, 0, 0, 0, 0] FlightFootKp: - [150, 0, 0, + [50, 0, 0, 0, 100, 0, 0, 0, 100] FlightFootKd: - [ 0, 0, 0, + [20, 0, 0, 0, 0, 0, 0, 0, 0] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 716b3d9ec4..25adaf2318 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,15 +1,19 @@ -w_input: 0.000001 +w_input: 0.00001 w_accel: 0.00001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe -W_accel: [1, 1, 1, 1, 1, 1, +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 1, 1, 0.9, 0.5, 0.1, 1] -W_lambda_reg: [0.001, 0.001, 0.01, +W_lambda_c_reg: [1, 1, 0.01, + 1, 1, 0.01, + 1, 1, 0.01, + 1, 1, 0.01] +W_lambda_h_reg: [0.001, 0.001, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 -w_soft_constraint: 0.0 +w_soft_constraint: 0.000 w_input_reg: 0.01 impact_threshold: 0.025 relative_feet: true @@ -38,7 +42,7 @@ hip_yaw_kd: 1 footstep_offset: -0.05 center_line_offset: 0.05 FootstepKd: - [ 0.2, 0, 0, + [ 0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] PelvisW: @@ -48,7 +52,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 85] + 0, 0, 70] PelvisKd: [ 1, 0, 0, 0, 0, 0, diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index ff35e28237..c322b59226 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -1,5 +1,6 @@ #include +#include #include #include @@ -130,15 +131,10 @@ int DoMain(int argc, char* argv[]) { /**** Get trajectory from optimization ****/ /**** OSC Gains ****/ - OSCGains gains{}; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; - drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); - - OSCRunningGains osc_gains; - drake::yaml::YamlReadArchive(root).Accept(&osc_gains); + OSCGains gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); + OSCRunningGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename)); /**** FSM and contact mode configuration ****/ int stance_state = 0; diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 170e79e2fa..e0033e9372 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -1,4 +1,5 @@ +#include #include #include #include @@ -120,14 +121,15 @@ int DoMain(int argc, char* argv[]) { feet_contact_points = {left_toe, right_toe}; /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - OSCJumpingGains gains; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); - drake::yaml::YamlReadArchive(root).Accept(&gains); + // OSCJumpingGains gains; + // const YAML::Node& root = + // YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); + OSCJumpingGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename)); /**** Get trajectory from optimization ****/ - const DirconTrajectory& dircon_trajectory = DirconTrajectory(plant_w_spr, - FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); + const DirconTrajectory& dircon_trajectory = DirconTrajectory( + plant_w_spr, FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; if (gains.relative_feet) { output_traj_path += "_rel"; @@ -301,7 +303,8 @@ int DoMain(int argc, char* argv[]) { osc->SetSoftConstraintWeight(w_contact_relax); // Soft constraint on contacts double w_input_reg = gains.w_input_reg; - osc->SetInputSmoothingWeights(gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingWeights(gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Contact information for OSC osc->SetContactFriction(gains.mu); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index f20338baf2..8d1a3d441f 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -1,5 +1,6 @@ #include +#include #include #include @@ -130,15 +131,17 @@ int DoMain(int argc, char* argv[]) { /**** Get trajectory from optimization ****/ /**** OSC Gains ****/ - OSCGains gains{}; - const YAML::Node& root = - YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); +// OSCGains gains; +// const YAML::Node& root = +// YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; - drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); +// drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); - OSCRunningGains osc_gains; - drake::yaml::YamlReadArchive(root).Accept(&osc_gains); + OSCGains gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); + OSCRunningGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename)); + +// drake::yaml::YamlReadArchive(root).Accept(&osc_gains); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -191,9 +194,10 @@ int DoMain(int argc, char* argv[]) { // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); -// osc->SetInputCostWeights(1e-3 * gains.W_input_regularization); - osc->SetLambdaRegularizationWeight(1e-6 * gains.W_lambda_regularization); +// osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); +// osc->SetLambdaContactRegularizationWeight(1e-4 * gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(gains.w_soft_constraint); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index a3b7b662a5..8dfcc1d166 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -269,7 +269,7 @@ int DoMain(int argc, char* argv[]) { center_of_mass_traj.AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); - center_of_mass_traj.SetLowPassFilter(0.09, {1}); + center_of_mass_traj.SetLowPassFilter(0.03, {1}); osc->AddTrackingData(¢er_of_mass_traj); // Pelvis rotation tracking RotTaskSpaceTrackingData pelvis_rot_traj( diff --git a/examples/Cassie/urdf/cassie_v2.urdf b/examples/Cassie/urdf/cassie_v2.urdf index 109157cd9a..8b9c985987 100644 --- a/examples/Cassie/urdf/cassie_v2.urdf +++ b/examples/Cassie/urdf/cassie_v2.urdf @@ -713,7 +713,7 @@ - + @@ -722,7 +722,7 @@ - + @@ -763,7 +763,7 @@ - + @@ -773,7 +773,7 @@ - + diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 7add8dba41..3a964aaaa3 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -129,21 +129,29 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, } Eigen::Vector3d point_W(0, 0, 0); + drake::multibody::CoulombFriction friction(mu_static, mu_kinetic); // A half-space for the ground geometry. const drake::math::RigidTransformd X_WG( HalfSpace::MakePose(normal_W, point_W)); - drake::geometry::ProximityProperties props; - props.AddProperty("material", "point_contact_stiffness", stiffness); - props.AddProperty("material", "hunt_crossley_dissipation", - dissipation_rate); - props.AddProperty(drake::geometry::internal::kMaterialGroup, - drake::geometry::internal::kFriction, - drake::multibody::CoulombFriction(mu_static, mu_kinetic)); - plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), - "collision", props); + + if (stiffness != 0){ + drake::geometry::ProximityProperties props; + props.AddProperty("material", "point_contact_stiffness", stiffness); + props.AddProperty("material", "hunt_crossley_dissipation", + dissipation_rate); + props.AddProperty(drake::geometry::internal::kMaterialGroup, + drake::geometry::internal::kFriction, + friction); + plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), + "collision", props); + } + else{ + plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), + "collision", friction); + } // Add visual for the ground. // plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), diff --git a/multibody/multibody_utils.h b/multibody/multibody_utils.h index 7a38af2bc4..3441ed17df 100644 --- a/multibody/multibody_utils.h +++ b/multibody/multibody_utils.h @@ -68,7 +68,7 @@ void AddFlatTerrain(drake::multibody::MultibodyPlant* plant, drake::geometry::SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W = Eigen::Vector3d(0, 0, 1), - double stiffness = 1e4, double dissipation_rate = 5); + double stiffness = 0, double dissipation_rate = 0); /// Given a MultiBodyTree, builds a map from position name to position index template diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 9f78d9212f..9ee9639e08 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -342,6 +342,20 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, is_init_ = true; } +void FastOsqpSolver::WarmStart(const Eigen::VectorXd& primal, + const Eigen::VectorXd& dual) { + std::vector x, y; + x.reserve(primal.size()); + y.reserve(dual.size()); + for (int i = 0; i < primal.size(); ++i) { + x.push_back(ConvertInfinity(primal(i))); + } + for (int i = 0; i < dual.size(); ++i){ + y.push_back(ConvertInfinity(dual(i))); + } + osqp_warm_start(workspace_, x.data(), y.data()); +} + void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, const Eigen::VectorXd& initial_guess, const SolverOptions& merged_options, @@ -382,7 +396,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, osqp_update_bounds(workspace_, l.data(), u.data()); osqp_update_P_A(workspace_, P_csc->x, OSQP_NULL, P_csc->nzmax, A_csc->x, OSQP_NULL, A_csc->nzmax); -// SetFastOsqpSolverSettings(merged_options, osqp_settings_); + // SetFastOsqpSolverSettings(merged_options, osqp_settings_); // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index 8dbfd5285c..3b97ef0949 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -49,6 +49,9 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { warm_start_ = true; } + void WarmStart(const Eigen::VectorXd& primal, + const Eigen::VectorXd& dual); + bool IsInitialized()const{ return is_init_; } diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 6127e479d3..374c87611f 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -57,6 +57,20 @@ cc_library( ], ) +cc_library( + name = "geared_motor", + srcs = [ + "geared_motor.cc", + ], + hdrs = [ + "geared_motor.h", + ], + deps = [ + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "constrained_lqr_controller", srcs = [ diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc new file mode 100644 index 0000000000..49426305ce --- /dev/null +++ b/systems/controllers/geared_motor.cc @@ -0,0 +1,66 @@ +#include "systems/controllers/geared_motor.h" + +#include + +namespace dairlib { +namespace systems { + +using drake::multibody::JointActuator; +using drake::multibody::MultibodyPlant; +using drake::systems::kUseDefaultName; + +GearedMotor::GearedMotor(const MultibodyPlant& plant, + const std::vector& max_motor_speeds) + : n_q(plant.num_positions()), + n_v(plant.num_velocities()), + n_u(plant.num_actuators()), + B_(plant.MakeActuationMatrix()) { + for (int i = 0; i < n_u; ++i) { + const JointActuator& joint_actuator = + plant.get_joint_actuator(drake::multibody::JointActuatorIndex(i)); + actuator_gear_ratios.push_back(joint_actuator.default_gear_ratio()); + actuator_ranges.push_back(joint_actuator.effort_limit()); + actuator_max_speeds.push_back(max_motor_speeds[i]); + } + systems::TimestampedVector input(plant.num_actuators()); + systems::TimestampedVector output(plant.num_actuators()); + + command_input_port_ = + this->DeclareVectorInputPort("u_cmd", input).get_index(); + state_input_port_ = + this->DeclareVectorInputPort("x", BasicVector(n_q + n_v)) + .get_index(); + this->DeclareVectorOutputPort("u_motor", output, + &GearedMotor::CalcTorqueOutput); +} + +void GearedMotor::CalcTorqueOutput( + const drake::systems::Context& context, + systems::TimestampedVector* output) const { + const systems::TimestampedVector& u = + *this->template EvalVectorInput(context, + command_input_port_); + const systems::BasicVector& x = + *this->template EvalVectorInput(context, state_input_port_); + Eigen::VectorXd actuator_velocities = B_.transpose() * x.value().tail(n_v); + Eigen::VectorXd tau = Eigen::VectorXd::Zero(n_u); + for (int i = 0; i < n_u; ++i) { + double ratio = actuator_gear_ratios[i]; + double tmax = actuator_ranges[i]; + double w = actuator_velocities[i]; + double wmax = actuator_max_speeds[i]; + + // Calculate torque limit based on motor speed + double tlim = 2 * tmax * (1 - fabs(w) / wmax); + tlim = fmax(fmin(tlim, tmax), 0); + + // Compute motor-side torque + // tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); + tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); + } + output->SetDataVector(tau); + output->set_timestamp(u.get_timestamp()); +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/geared_motor.h b/systems/controllers/geared_motor.h new file mode 100644 index 0000000000..ff3cc9db24 --- /dev/null +++ b/systems/controllers/geared_motor.h @@ -0,0 +1,58 @@ +#pragma once + +#include + +#include +#include "systems/framework/timestamped_vector.h" +#include "systems/framework/output_vector.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// This class is copied from drake/systems/primitives/PassThrough +/// with the modification that it only passes through a subset of the vector +class GearedMotor : public drake::systems::LeafSystem { + public: + /// Constructs a pass through system (`y = u.segment(start,length)`). + /// @param vector_size the length of the input vector + /// @param start the initial index of the subvector + /// @param length number of elements in the subvector + GearedMotor(const drake::multibody::MultibodyPlant& plant, const std::vector& max_motor_speeds); + + const drake::systems::InputPort& get_input_port_command() const { + return drake::systems::LeafSystem::get_input_port(command_input_port_); + } + + const drake::systems::InputPort& get_input_port_state() const { + return drake::systems::LeafSystem::get_input_port(state_input_port_); + } + + /// Returns the sole output port. + const drake::systems::OutputPort& get_output_port() const { + return drake::systems::LeafSystem::get_output_port(0); + } + + protected: + void CalcTorqueOutput( + const drake::systems::Context& context, + systems::TimestampedVector* output) const; + + private: + bool is_abstract() const { return false;} + + const int n_q; + const int n_v; + const int n_u; + const Eigen::MatrixXd B_; + int command_input_port_; + int state_input_port_; + + std::vector actuator_gear_ratios; + std::vector actuator_ranges; + std::vector actuator_max_speeds; +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 2572ce4ae4..763fd57716 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -381,17 +381,25 @@ void OperationalSpaceControl::Build() { // Add costs // 1. input cost if (W_input_.size() > 0) { + DRAKE_DEMAND(W_input_.rows() == n_u_); prog_->AddQuadraticCost(W_input_, VectorXd::Zero(n_u_), u_); } // 2. acceleration cost if (W_joint_accel_.size() > 0) { + DRAKE_DEMAND(W_joint_accel_.rows() == n_v_); prog_->AddQuadraticCost(W_joint_accel_, VectorXd::Zero(n_v_), dv_); } + // 3. contact force cost + if (W_lambda_c_reg_.size() > 0) { + DRAKE_DEMAND(W_lambda_c_reg_.rows() == n_c_); + prog_->AddQuadraticCost(W_lambda_c_reg_, VectorXd::Zero(n_c_), lambda_c_); + } // 3. constraint force cost - if (W_lambda_reg_.size() > 0) { - prog_->AddQuadraticCost(W_lambda_reg_, VectorXd::Zero(n_h_), lambda_h_); + if (W_lambda_h_reg_.size() > 0) { + DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); + prog_->AddQuadraticCost(W_lambda_h_reg_, VectorXd::Zero(n_h_), lambda_h_); } - // 3. Soft constraint cost + // 4. Soft constraint cost if (w_soft_constraint_ > 0) { prog_->AddQuadraticCost( w_soft_constraint_ * MatrixXd::Identity(n_c_active_, n_c_active_), @@ -451,7 +459,7 @@ void OperationalSpaceControl::Build() { solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); solver_options.SetOption(OsqpSolver::id(), "rho", 0.0001); solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-6); - solver_options.SetOption(OsqpSolver::id(), "max_iter", 4000); + solver_options.SetOption(OsqpSolver::id(), "max_iter", 100); solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-5); solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-5); @@ -467,6 +475,7 @@ void OperationalSpaceControl::Build() { solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_interval", 0); solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_tolerance", 5); solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_fraction", 0.4); + solver_options.SetOption(OsqpSolver::id(), "warm_start", 1); std::cout << solver_options << std::endl; solver_->InitializeSolver(*prog_, solver_options); } @@ -592,6 +601,9 @@ VectorXd OperationalSpaceControl::SolveQp( row_idx += contact_i->num_active(); } +// std::cout << "JdotV_h" << JdotV_h.transpose() << std::endl; +// std::cout << "JdotV_c" << JdotV_c_active.transpose() << std::endl; + // Update constraints // 1. Dynamics constraint /// M*dv + bias == J_c^T*lambda_c + J_h^T*lambda_h + B*u @@ -742,12 +754,19 @@ VectorXd OperationalSpaceControl::SolveQp( // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0) { input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, - -W_input_smoothing_ * (*u_prev_)); + -W_input_smoothing_ * (*u_prev_)); } if (!solver_->IsInitialized()) { solver_->InitializeSolver(*prog_, solver_options_); } + + if (initial_guess_x_.count(fsm_state) > 0) { + // std::cout << "Setting initial guess: " << fsm_state << std::endl; + solver_->WarmStart(initial_guess_x_.at(fsm_state), + initial_guess_y_.at(fsm_state)); + } + // Solve the QP const MathematicalProgramResult result = solver_->Solve(*prog_); if (result.is_success()) { @@ -758,6 +777,8 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); *u_prev_ = *u_sol_; + initial_guess_x_[fsm_state] = result.GetSolution(); + initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { std::cerr << "QP did not solve in time!" << std::endl; solver_->DisableWarmStart(); @@ -882,13 +903,20 @@ void OperationalSpaceControl::AssignOscLcmOutput( : 0; double input_smoothing_cost = (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_- *u_prev_).transpose() * W_input_smoothing_ * (*u_sol_ - *u_prev_))(0) - : 0; - double lambda_h_cost = - (W_lambda_reg_.size() > 0) - ? (0.5 * (*lambda_h_sol_).transpose() * W_lambda_reg_ * (*lambda_h_sol_))(0) + ? (0.5 * (*u_sol_ - *u_prev_).transpose() * W_input_smoothing_ * + (*u_sol_ - *u_prev_))(0) : 0; - + double lambda_h_cost = (W_lambda_h_reg_.size() > 0) + ? (0.5 * (*lambda_h_sol_).transpose() * + W_lambda_h_reg_ * (*lambda_h_sol_))(0) + : 0; + double lambda_c_cost = (W_lambda_c_reg_.size() > 0) + ? (0.5 * (*lambda_c_sol_).transpose() * + W_lambda_c_reg_ * (*lambda_c_sol_))(0) + : 0; + total_cost_ += input_cost + acceleration_cost + soft_constraint_cost + + input_smoothing_cost + lambda_h_cost + lambda_c_cost; + soft_constraint_cost_ = soft_constraint_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); @@ -901,6 +929,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->regularization_cost_names.push_back("soft_constraint_cost"); output->regularization_costs.push_back(input_smoothing_cost); output->regularization_cost_names.push_back("input_smoothing_cost"); + output->regularization_costs.push_back(lambda_c_cost); + output->regularization_cost_names.push_back("lambda_c_cost"); output->regularization_costs.push_back(lambda_h_cost); output->regularization_cost_names.push_back("lambda_h_cost"); @@ -977,6 +1007,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( } output->tracking_data[i] = osc_output; } +// std::cout << total_cost_ << std::endl; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index bed950737a..a011e04eed 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -15,8 +15,8 @@ #include "solvers/fast_osqp_solver.h" #include "systems/controllers/control_utils.h" #include "systems/controllers/osc/osc_tracking_data.h" -#include "systems/framework/output_vector.h" #include "systems/framework/impact_info_vector.h" +#include "systems/framework/output_vector.h" #include "drake/common/trajectories/exponential_plus_piecewise_polynomial.h" #include "drake/common/trajectories/piecewise_polynomial.h" @@ -148,8 +148,11 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void SetSoftConstraintWeight(double w_soft_constraint) { w_soft_constraint_ = w_soft_constraint; } - void SetLambdaRegularizationWeight(const Eigen::MatrixXd& W) { - W_lambda_reg_ = W; + void SetLambdaContactRegularizationWeight(const Eigen::MatrixXd& W) { + W_lambda_c_reg_ = W; + } + void SetLambdaHolonomicRegularizationWeight(const Eigen::MatrixXd& W) { + W_lambda_h_reg_ = W; } // Constraint methods @@ -235,9 +238,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void CalcOptimalInput(const drake::systems::Context& context, systems::TimestampedVector* control) const; // Safety function that triggers when the tracking cost is too high - void CheckTracking( - const drake::systems::Context& context, - TimestampedVector* output) const; + void CheckTracking(const drake::systems::Context& context, + TimestampedVector* output) const; // Input/Output ports int osc_debug_port_; @@ -313,7 +315,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // MathematicalProgram std::unique_ptr prog_; - // Decision variables drake::solvers::VectorXDecisionVariable dv_; drake::solvers::VectorXDecisionVariable u_; @@ -348,7 +349,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::MatrixXd W_input_; // Input cost weight Eigen::MatrixXd W_joint_accel_; // Joint acceleration cost weight Eigen::MatrixXd W_input_smoothing_; - Eigen::MatrixXd W_lambda_reg_; + Eigen::MatrixXd W_lambda_c_reg_; + Eigen::MatrixXd W_lambda_h_reg_; // OSC constraint members bool with_input_constraints_ = true; @@ -366,6 +368,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // single_contact_mode_ is true if there is only 1 contact mode in OSC bool single_contact_mode_ = false; + mutable std::unordered_map initial_guess_x_ = {}; + mutable std::unordered_map initial_guess_y_ = {}; + // OSC tracking data (stored as a pointer because of caching) std::unique_ptr> tracking_data_vec_ = std::make_unique>(); diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index ba59649391..81fa530ee6 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -16,11 +16,13 @@ struct OSCGains { double mu; std::vector W_accel; std::vector W_input_reg; - std::vector W_lambda_reg; + std::vector W_lambda_c_reg; + std::vector W_lambda_h_reg; MatrixXd W_acceleration; MatrixXd W_input_regularization; - MatrixXd W_lambda_regularization; + MatrixXd W_lambda_c_regularization; + MatrixXd W_lambda_h_regularization; template void Serialize(Archive* a) { @@ -32,7 +34,8 @@ struct OSCGains { a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(W_accel)); a->Visit(DRAKE_NVP(W_input_reg)); - a->Visit(DRAKE_NVP(W_lambda_reg)); + a->Visit(DRAKE_NVP(W_lambda_c_reg)); + a->Visit(DRAKE_NVP(W_lambda_h_reg)); Eigen::VectorXd w_acceleration = Eigen::Map(this->W_accel.data(), @@ -40,11 +43,15 @@ struct OSCGains { Eigen::VectorXd w_input_regularization = Eigen::Map(this->W_input_reg.data(), this->W_input_reg.size()); - Eigen::VectorXd w_lambda_regularization = + Eigen::VectorXd w_lambda_c_regularization = Eigen::Map( - this->W_lambda_reg.data(), this->W_lambda_reg.size()); + this->W_lambda_c_reg.data(), this->W_lambda_c_reg.size()); + Eigen::VectorXd w_lambda_h_regularization = + Eigen::Map( + this->W_lambda_h_reg.data(), this->W_lambda_h_reg.size()); W_acceleration = w_acceleration.asDiagonal(); W_input_regularization = w_input_regularization.asDiagonal(); - W_lambda_regularization = w_lambda_regularization.asDiagonal(); + W_lambda_c_regularization = w_lambda_c_regularization.asDiagonal(); + W_lambda_h_regularization = w_lambda_h_regularization.asDiagonal(); } }; \ No newline at end of file From e25f5f11c8015400416ba999f848b2cd4c8f0db1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 4 Mar 2022 14:07:05 -0500 Subject: [PATCH 104/758] updating qp analysis script --- .../analysis/osqp_settings_sandbox.py | 31 ++++++++++++++----- 1 file changed, 24 insertions(+), 7 deletions(-) diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index 4f8356d4dc..713da54d13 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -30,8 +30,9 @@ def ParseQP(data): def solve_osqp(qp, settings): - Q = qp["Q"] + qp["Q"].T - np.diag(np.diag(qp["Q"])) - Q = Q + 1e-6 * np.eye(Q.shape[0]) + Q = qp["Q"] + # Q = qp["Q"] + qp["Q"].T - np.diag(np.diag(qp["Q"])) + # Q = Q + 1e-6 * np.eye(Q.shape[0]) m = osqp.OSQP() m.setup( P=csc_matrix(Q), q=qp["w"], @@ -47,6 +48,7 @@ def solve_osqp(qp, settings): verbose=settings['verbose'], warm_start=settings['warm_start'], rho=settings['rho'], + max_iter=settings['max_iter'], check_termination=settings['check_termination']) qp_result = m.solve() @@ -56,6 +58,7 @@ def solve_osqp(qp, settings): return {'iter': qp_result.info.iter, 'run_time': qp_result.info.run_time, 'status': qp_result.info.status, + 'y_sol': qp_result.y, 'obj_val': qp_result.info.obj_val, 'pri_res': qp_result.info.pri_res, 'dual_res': qp_result.info.dua_res, @@ -69,16 +72,18 @@ def main(): log = lcm.EventLog(filename, "r") qp_list = get_log_data(log, {"QP_LOG": lcmt_qp}, ParseQP) - qp_list = qp_list[:5000][::10] + # qp_list = qp_list[:2000][::10] + qp_list = qp_list[2000:5000][::10] run_times = np.zeros((len(qp_list),)) obj_vals = np.zeros((len(qp_list),)) pri_eps_vals = np.zeros((len(qp_list,))) # sols = np.zeros((len(qp_list,), 60)) sols = np.zeros((len(qp_list,), 60)) + iters = np.zeros((len(qp_list,),)) for i, qp in enumerate(qp_list): osqp_settings = \ - {'eps_abs': 1e-5, + {'eps_abs': 1e-7, 'eps_rel': 1e-5, 'eps_prim_inf': 1e-5, 'eps_dual_inf': 1e-5, @@ -92,6 +97,7 @@ def main(): 'sigma': 1e-6, 'alpha': 1.6, 'delta': 1e-6, + 'max_iter': 200, 'check_termination': 25, 'time_limit': 1e-4} @@ -101,6 +107,9 @@ def main(): pri_eps_vals[i] = osqp_result['pri_res'] pri_eps_vals[i] = osqp_result['pri_res'] sols[i] = osqp_result['sol'] + iters[i] = osqp_result['iter'] + + # import pdb; pdb.set_trace() print(f'OSQP mean runtime: {np.mean(run_times)}') @@ -109,7 +118,7 @@ def main(): import matplotlib.pyplot as plt - fig, axs = plt.subplots(3, 1, sharex=True) + fig, axs = plt.subplots(4, 1, sharex=True) axs[0].plot(obj_vals, label='OSQP') axs[0].legend() @@ -118,8 +127,16 @@ def main(): axs[1].plot(run_times) axs[1].set_title('Solve times per QP') - axs[2].plot(sols[:, 22:32]) - axs[2].set_title('QP solutions') + # axs[2].plot(iters) + # axs[2].set_title('QP solutions') + + axs[2].plot(sols[:, 22:24]) + axs[2].plot(sols[:, 28:30]) + axs[2].set_title('Knee Torque Solutions') + + axs[3].plot(sols[:, 24:28]) + axs[3].plot(sols[:, 30:32]) + axs[3].set_title('QP solutions') plt.show() import pdb;pdb.set_trace() From eb98dfb7cae99a2055d396ac81106dcae607819d Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 7 Mar 2022 11:31:41 -0500 Subject: [PATCH 105/758] qp numerics are improved slightly, bad scaling in soft constraint --- .../analysis/cassie_plotting_utils.py | 1 + .../pydairlib/analysis/mbp_plotting_utils.py | 68 ++++++++++-------- bindings/pydairlib/analysis/osc_debug.py | 20 ++++++ .../analysis/osqp_settings_sandbox.py | 69 ++++++++++++------- .../Cassie/osc_run/osc_running_gains.yaml | 22 +++--- .../osc/operational_space_control.cc | 4 +- 6 files changed, 119 insertions(+), 65 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 6179905924..984515f8db 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -32,6 +32,7 @@ def make_plant_and_context(floating_base=True, springs=True): builder = DiagramBuilder() + import pdb; pdb.set_trace() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) if (springs): addCassieMultibody(plant, scene_graph, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 737b7e7d70..639bb76e03 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -2,7 +2,7 @@ import matplotlib.pyplot as plt from pydairlib.common import plot_styler, plotting_utils -from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost +from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost, osc_regularlization_tracking_cost from pydairlib.multibody import makeNameToPositionsMap, \ makeNameToVelocitiesMap, makeNameToActuatorsMap, \ createStateNameVectorFromMap, createActuatorNameVectorFromMap @@ -96,8 +96,7 @@ def process_effort_channel(data, plant): def make_point_positions_from_q( - q, plant, context, frame, pt_on_frame, frame_to_calc_position_in=None): - + q, plant, context, frame, pt_on_frame, frame_to_calc_position_in=None): if frame_to_calc_position_in is None: frame_to_calc_position_in = plant.world_frame() @@ -112,9 +111,10 @@ def make_point_positions_from_q( def process_osc_channel(data): t_osc = [] - input_cost = [] - accel_cost = [] - soft_constraint_cost = [] + # input_cost = [] + # accel_cost = [] + # soft_constraint_cost = [] + regularization_costs = osc_regularlization_tracking_cost(data[0].regularization_cost_names) qp_solve_time = [] u_sol = [] lambda_c_sol = [] @@ -127,9 +127,7 @@ def process_osc_channel(data): for msg in data: t_osc.append(msg.utime / 1e6) - input_cost.append(msg.input_cost) - accel_cost.append(msg.acceleration_cost) - soft_constraint_cost.append(msg.soft_constraint_cost) + regularization_costs.append(msg.regularization_cost_names, msg.regularization_costs) qp_solve_time.append(msg.qp_output.solve_time) u_sol.append(msg.qp_output.u_sol) lambda_c_sol.append(msg.qp_output.lambda_c_sol) @@ -149,16 +147,14 @@ def process_osc_channel(data): tracking_cost_handler = osc_tracking_cost(osc_debug_tracking_datas.keys()) for msg in data: - tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_cost) + tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_costs) tracking_cost = tracking_cost_handler.convertToNP() for name in osc_debug_tracking_datas: osc_debug_tracking_datas[name].convertToNP() return {'t_osc': np.array(t_osc), - 'input_cost': np.array(input_cost), - 'acceleration_cost': np.array(accel_cost), - 'soft_constraint_cost': np.array(soft_constraint_cost), + 'regularization_costs': regularization_costs, 'qp_solve_time': np.array(qp_solve_time), 'u_sol': np.array(u_sol), 'lambda_c_sol': np.array(lambda_c_sol), @@ -190,8 +186,8 @@ def load_default_channels(data, plant, state_channel, input_channel, def plot_q_or_v_or_u( - robot_output, key, x_names, x_slice, time_slice, - ylabel=None, title=None): + robot_output, key, x_names, x_slice, time_slice, + ylabel=None, title=None): ps = plot_styler.PlotStyler() if ylabel is None: ylabel = key @@ -199,12 +195,12 @@ def plot_q_or_v_or_u( title = key plotting_utils.make_plot( - robot_output, # data dict - 't_x', # time channel + robot_output, # data dict + 't_x', # time channel time_slice, - [key], # key to plot - {key: x_slice}, # slice of key to plot - {key: x_names}, # legend entries + [key], # key to plot + {key: x_slice}, # slice of key to plot + {key: x_names}, # legend entries {'xlabel': 'Time', 'ylabel': ylabel, 'title': title}, ps) @@ -263,7 +259,6 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): def plot_points_positions(robot_output, time_slice, plant, context, frame_names, pts, dims): - dim_map = ['_x', '_y', '_z'] data_dict = {'t': robot_output['t_x']} legend_entries = {} @@ -345,19 +340,36 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): def plot_qp_costs(osc_debug, time_slice): - cost_keys = ['input_cost', 'acceleration_cost', - 'soft_constraint_cost'] + # cost_keys = ['input_cost', 'acceleration_cost', + # 'soft_constraint_cost'] + # ps = plot_styler.PlotStyler() + # plotting_utils.make_plot( + # osc_debug, + # 't_osc', + # time_slice, + # cost_keys, + # {}, + # {key: [key] for key in cost_keys}, + # {'xlabel': 'Time', + # 'ylabel': 'Cost', + # 'title': 'OSC QP Costs'}, ps) + # return ps ps = plot_styler.PlotStyler() + regularization_cost = osc_debug['regularization_costs'].regularization_costs + data_dict = \ + {key: val for key, val in regularization_cost.items()} + data_dict['t_osc'] = osc_debug['t_osc'] + plotting_utils.make_plot( - osc_debug, + data_dict, 't_osc', time_slice, - cost_keys, + regularization_cost.keys(), {}, - {key: [key] for key in cost_keys}, + {key: [key] for key in regularization_cost.keys()}, {'xlabel': 'Time', 'ylabel': 'Cost', - 'title': 'OSC QP Costs'}, ps) + 'title': 'tracking_costs'}, ps) return ps @@ -409,4 +421,4 @@ def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): - ps.plot(fsm_time, scale*fsm_signal) \ No newline at end of file + ps.plot(fsm_time, scale * fsm_signal) diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index bf294a55ee..52abf035d7 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -84,3 +84,23 @@ def convertToNP(self): for name in self.tracking_costs: self.tracking_costs[name] = np.array(self.tracking_costs[name]) return self.tracking_costs + + +# Helper class to easily get a list of acceleration tracking costs, +# Setting the cost to zero when a tracking data is not active +class osc_regularlization_tracking_cost(): + + def __init__(self, regularization_data_names): + + self.regularization_costs = {} + for name in regularization_data_names: + self.regularization_costs[name] = [] + + def append(self, regularization_cost_names_list, regularization_cost_list): + for name, cost in zip(regularization_cost_names_list, regularization_cost_list): + self.regularization_costs[name].append(cost) + + def convertToNP(self): + for name in self.regularization_costs: + self.regularization_costs[name] = np.array(self.regularization_costs[name]) + return self.regularization_costs diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index 713da54d13..874a452b2d 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -3,10 +3,12 @@ from process_lcm_log import get_log_data from dairlib import lcmt_qp import sys +import matplotlib.pyplot as plt import osqp from scipy.sparse import csc_matrix +saved_sols_folder = '/home/yangwill/Documents/research/projects/cassie/hardware/gain_tuning/qp_settings/cost_tuning/qp_formulation/' def ParseQP(data): qp_list = [] @@ -81,25 +83,26 @@ def main(): sols = np.zeros((len(qp_list,), 60)) iters = np.zeros((len(qp_list,),)) + osqp_settings = \ + {'eps_abs': 1e-7, + 'eps_rel': 1e-5, + 'eps_prim_inf': 1e-5, + 'eps_dual_inf': 1e-5, + 'polish': 1, + 'scaled_termination': 1, + 'adaptive_rho': 1, + 'adaptive_rho_fraction': 0.4, + 'verbose': 0, + 'warm_start': 1, + 'rho': 1e-4, + 'sigma': 1e-6, + 'alpha': 1.6, + 'delta': 1e-6, + 'max_iter': 200, + 'check_termination': 25, + 'time_limit': 1e-4} + for i, qp in enumerate(qp_list): - osqp_settings = \ - {'eps_abs': 1e-7, - 'eps_rel': 1e-5, - 'eps_prim_inf': 1e-5, - 'eps_dual_inf': 1e-5, - 'polish': 1, - 'scaled_termination': 1, - 'adaptive_rho': 1, - 'adaptive_rho_fraction': 0.4, - 'verbose': 0, - 'warm_start': 1, - 'rho': 1e-4, - 'sigma': 1e-6, - 'alpha': 1.6, - 'delta': 1e-6, - 'max_iter': 200, - 'check_termination': 25, - 'time_limit': 1e-4} osqp_result = solve_osqp(qp, osqp_settings) run_times[i] = osqp_result['run_time'] @@ -110,18 +113,21 @@ def main(): iters[i] = osqp_result['iter'] # import pdb; pdb.set_trace() - + log_name = filename.split('/')[-1] + np.save(saved_sols_folder + log_name + '_' + str(osqp_settings['max_iter']), sols) print(f'OSQP mean runtime: {np.mean(run_times)}') print(f'OSQP mean objective: {np.mean(obj_vals)}') print(f'OSQP mean primal residuals: {np.mean(pri_eps_vals)}') - import matplotlib.pyplot as plt fig, axs = plt.subplots(4, 1, sharex=True) - axs[0].plot(obj_vals, label='OSQP') - axs[0].legend() + # axs[0].plot(obj_vals, label='OSQP') + # axs[0].plot(sols[:, 44:50]) + # axs[0].plot(sols[:, 55:60]) + axs[0].plot(sols[:, 44:50]) + axs[0].legend(['0','1','2','3','4']) axs[0].set_title('Objective values per QP') axs[1].plot(run_times) @@ -137,10 +143,25 @@ def main(): axs[3].plot(sols[:, 24:28]) axs[3].plot(sols[:, 30:32]) axs[3].set_title('QP solutions') - plt.show() - import pdb;pdb.set_trace() +def compare_sols(): + # sol0 = np.load(saved_sols_folder + 'lcmlog-drake0_1000.npy') + sol0 = np.load(saved_sols_folder + 'lcmlog-drake1_1000.npy') + # sol1 = np.load(saved_sols_folder + 'lcmlog-drake0_200.npy') + sol1 = np.load(saved_sols_folder + 'lcmlog-drake1_200.npy') + fig, axs = plt.subplots(5, 1, sharex=True) + # a = np.max(sol0 - sol1, axis=0) + a = np.average(sol0 - sol1, axis=0) + + axs[0].plot(a[0:22]) + axs[1].plot(a[22:32]) + axs[2].plot(a[32:44]) + axs[3].plot(a[44:50]) + axs[4].plot(a[50:60]) if __name__ == '__main__': + # compare_sols() main() + plt.show() + diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 25adaf2318..b8fab590c0 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -6,14 +6,14 @@ W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 1, 1, 0.9, 0.5, 0.1, 1] -W_lambda_c_reg: [1, 1, 0.01, - 1, 1, 0.01, - 1, 1, 0.01, - 1, 1, 0.01] -W_lambda_h_reg: [0.001, 0.001, 0.01, +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 -w_soft_constraint: 0.000 +w_soft_constraint: 0.00001 w_input_reg: 0.01 impact_threshold: 0.025 relative_feet: true @@ -35,15 +35,15 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 1 +w_hip_yaw: 5 hip_yaw_kp: 60 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 center_line_offset: 0.05 FootstepKd: - [ 0.3, 0, 0, - 0, 0.4, 0, + [ 0.2, 0, 0, + 0, 0.45, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, @@ -62,11 +62,11 @@ PelvisRotW: 0, 0.1, 0, 0, 0, 0] PelvisRotKp: - [25, 0, 0, + [40, 0, 0, 0, 20, 0, 0, 0, 0] PelvisRotKd: - [5, 0, 0, + [10, 0, 0, 0, 5, 0, 0, 0, 0] SwingFootW: diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 763fd57716..cdd615d33c 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -633,7 +633,7 @@ VectorXd OperationalSpaceControl::SolveQp( MatrixXd A_c = MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_); A_c.block(0, 0, n_c_active_, n_v_) = J_c_active; A_c.block(0, n_v_, n_c_active_, n_c_active_) = - 0.01 * MatrixXd::Identity(n_c_active_, n_c_active_); + 0.001 * MatrixXd::Identity(n_c_active_, n_c_active_); contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -1022,11 +1022,11 @@ void OperationalSpaceControl::CalcOptimalInput( VectorXd q_w_spr = robot_output->GetPositions(); VectorXd v_w_spr = robot_output->GetVelocities(); - VectorXd x_w_spr(plant_w_spr_.num_positions() + plant_w_spr_.num_velocities()); x_w_spr << q_w_spr, v_w_spr; + double timestamp = robot_output->get_timestamp(); double current_time = timestamp; if (print_tracking_info_) { From 8f21f2dfc0eeea5a274989ac1ea43710d0580d12 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 7 Mar 2022 17:28:50 -0500 Subject: [PATCH 106/758] running osqp changes --- .../analysis/osqp_settings_sandbox.py | 43 ++++++++++--------- examples/Cassie/osc/osc_standing_gains.yaml | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_hopping_controller.cc | 8 +++- examples/Cassie/run_osc_running_controller.cc | 28 ++++++------ .../run_joint_space_walking_controller.cc | 8 +++- .../osc/operational_space_control.cc | 36 +++------------- .../osc/operational_space_control.h | 2 +- 8 files changed, 61 insertions(+), 68 deletions(-) diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index 874a452b2d..d015bab7e9 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -10,6 +10,7 @@ saved_sols_folder = '/home/yangwill/Documents/research/projects/cassie/hardware/gain_tuning/qp_settings/cost_tuning/qp_formulation/' + def ParseQP(data): qp_list = [] @@ -68,42 +69,43 @@ def solve_osqp(qp, settings): def main(): - # filename = "/home/brian/workspace/logs/qp_logging/lcmlog00" filename = sys.argv[1] log = lcm.EventLog(filename, "r") qp_list = get_log_data(log, {"QP_LOG": lcmt_qp}, ParseQP) # qp_list = qp_list[:2000][::10] - qp_list = qp_list[2000:5000][::10] + # qp_list = qp_list[:5000][::10] run_times = np.zeros((len(qp_list),)) obj_vals = np.zeros((len(qp_list),)) - pri_eps_vals = np.zeros((len(qp_list,))) + pri_eps_vals = np.zeros((len(qp_list, ))) # sols = np.zeros((len(qp_list,), 60)) - sols = np.zeros((len(qp_list,), 60)) - iters = np.zeros((len(qp_list,),)) + sols = np.zeros((len(qp_list, ), 52)) + iters = np.zeros((len(qp_list, ),)) osqp_settings = \ - {'eps_abs': 1e-7, + {'rho': 1e-4, + 'sigma': 1e-6, + 'max_iter': 100, + 'eps_abs': 1e-5, 'eps_rel': 1e-5, 'eps_prim_inf': 1e-5, 'eps_dual_inf': 1e-5, - 'polish': 1, - 'scaled_termination': 1, - 'adaptive_rho': 1, - 'adaptive_rho_fraction': 0.4, - 'verbose': 0, - 'warm_start': 1, - 'rho': 1e-4, - 'sigma': 1e-6, 'alpha': 1.6, + 'linsys_solver': 0, 'delta': 1e-6, - 'max_iter': 200, + 'polish': 1, + 'polish_refine_iter': 3, + 'verbose': 0, + 'scaled_termination': 1, 'check_termination': 25, - 'time_limit': 1e-4} + 'warm_start': 1, + 'adaptive_rho': 1, + 'adaptive_rho_interval': 0, + 'adaptive_rho_tolerance': 5, + 'adaptive_rho_fraction': 0.4} for i, qp in enumerate(qp_list): - osqp_result = solve_osqp(qp, osqp_settings) run_times[i] = osqp_result['run_time'] obj_vals[i] = osqp_result['obj_val'] @@ -120,14 +122,13 @@ def main(): print(f'OSQP mean objective: {np.mean(obj_vals)}') print(f'OSQP mean primal residuals: {np.mean(pri_eps_vals)}') - fig, axs = plt.subplots(4, 1, sharex=True) # axs[0].plot(obj_vals, label='OSQP') # axs[0].plot(sols[:, 44:50]) # axs[0].plot(sols[:, 55:60]) - axs[0].plot(sols[:, 44:50]) - axs[0].legend(['0','1','2','3','4']) + axs[0].plot(sols[:, 32:42]) + axs[0].legend(['0', '1', '2', '3', '4']) axs[0].set_title('Objective values per QP') axs[1].plot(run_times) @@ -144,6 +145,7 @@ def main(): axs[3].plot(sols[:, 30:32]) axs[3].set_title('QP solutions') + def compare_sols(): # sol0 = np.load(saved_sols_folder + 'lcmlog-drake0_1000.npy') sol0 = np.load(saved_sols_folder + 'lcmlog-drake1_1000.npy') @@ -164,4 +166,3 @@ def compare_sols(): # compare_sols() main() plt.show() - diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index c819249bcb..8d63504d96 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -12,7 +12,7 @@ cols: 3 w_input: 0 #w_accel: 0.00001 w_accel: 0.00000001 -w_soft_constraint: 200 +w_soft_constraint: 0 HipYawKp: 10 HipYawKd: 1 HipYawW: 0 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index b8fab590c0..fef311b5f2 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -13,7 +13,7 @@ W_lambda_c_reg: [1, 0.001, 0.01, W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 -w_soft_constraint: 0.00001 +w_soft_constraint: 0.001 w_input_reg: 0.01 impact_threshold: 0.025 relative_feet: true diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index c322b59226..72608badd6 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -81,6 +81,9 @@ DEFINE_string(channel_u, "CASSIE_INPUT", "The name of the channel which publishes command"); DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "Filepath containing qp settings"); DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); @@ -135,6 +138,9 @@ int DoMain(int argc, char* argv[]) { yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename)); + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ int stance_state = 0; @@ -432,7 +438,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 8d1a3d441f..4a604ff3c5 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -81,6 +81,9 @@ DEFINE_string(channel_u, "CASSIE_INPUT", "The name of the channel which publishes command"); DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "Filepath containing qp settings"); DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); @@ -131,17 +134,16 @@ int DoMain(int argc, char* argv[]) { /**** Get trajectory from optimization ****/ /**** OSC Gains ****/ -// OSCGains gains; -// const YAML::Node& root = -// YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; -// drake::yaml::YamlReadArchive(root, yaml_options).Accept(&gains); - OSCGains gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); - OSCRunningGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename)); - -// drake::yaml::YamlReadArchive(root).Accept(&osc_gains); + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); + OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename)); + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -194,10 +196,12 @@ int DoMain(int argc, char* argv[]) { // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); -// osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + // osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); -// osc->SetLambdaContactRegularizationWeight(1e-4 * gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); + // osc->SetLambdaContactRegularizationWeight(1e-4 * + // gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(gains.w_soft_constraint); @@ -459,7 +463,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 38320134bd..73974ecbec 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -60,6 +60,9 @@ DEFINE_string( gains_filename, "examples/impact_invariant_control/joint_space_walking_gains.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "Filepath containing qp settings"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -93,6 +96,9 @@ int DoMain(int argc, char* argv[]) { /**** Convert the gains from the yaml struct to Eigen Matrices ****/ JointSpaceWalkingGains gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( @@ -178,7 +184,7 @@ int DoMain(int argc, char* argv[]) { } // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index cdd615d33c..6321886cc1 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -263,7 +263,7 @@ void OperationalSpaceControl::CheckConstraintSettings() { } } -void OperationalSpaceControl::Build() { +void OperationalSpaceControl::Build(const solvers::OSQPSettingsYaml& osqp_settings) { // Checker CheckCostSettings(); CheckConstraintSettings(); @@ -454,30 +454,7 @@ void OperationalSpaceControl::Build() { } solver_ = std::make_unique(); - drake::solvers::SolverOptions solver_options; - solver_options.SetOption(OsqpSolver::id(), "verbose", 0); - solver_options.SetOption(OsqpSolver::id(), "time_limit", qp_time_limit_); - solver_options.SetOption(OsqpSolver::id(), "rho", 0.0001); - solver_options.SetOption(OsqpSolver::id(), "sigma", 1e-6); - solver_options.SetOption(OsqpSolver::id(), "max_iter", 100); - solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-5); - solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); - solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-5); - solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-5); - solver_options.SetOption(OsqpSolver::id(), "alpha", 1.6); - solver_options.SetOption(OsqpSolver::id(), "delta", 1e-6); - solver_options.SetOption(OsqpSolver::id(), "polish", 1); - solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 3); - solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); - solver_options.SetOption(OsqpSolver::id(), "check_termination", 25); - solver_options.SetOption(OsqpSolver::id(), "scaling", 10); - solver_options.SetOption(OsqpSolver::id(), "adaptive_rho", 1); - solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_interval", 0); - solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_tolerance", 5); - solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_fraction", 0.4); - solver_options.SetOption(OsqpSolver::id(), "warm_start", 1); - std::cout << solver_options << std::endl; - solver_->InitializeSolver(*prog_, solver_options); + solver_->InitializeSolver(*prog_, osqp_settings); } drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( @@ -757,12 +734,11 @@ VectorXd OperationalSpaceControl::SolveQp( -W_input_smoothing_ * (*u_prev_)); } - if (!solver_->IsInitialized()) { - solver_->InitializeSolver(*prog_, solver_options_); - } +// if (!solver_->IsInitialized()) { +// solver_->InitializeSolver(*prog_); +// } if (initial_guess_x_.count(fsm_state) > 0) { - // std::cout << "Setting initial guess: " << fsm_state << std::endl; solver_->WarmStart(initial_guess_x_.at(fsm_state), initial_guess_y_.at(fsm_state)); } @@ -781,7 +757,7 @@ VectorXd OperationalSpaceControl::SolveQp( initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { std::cerr << "QP did not solve in time!" << std::endl; - solver_->DisableWarmStart(); +// solver_->DisableWarmStart(); *u_prev_ = VectorXd::Zero(n_u_); } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index a011e04eed..ce33e727c6 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -187,7 +187,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector ds_states); // OSC LeafSystem builder - void Build(); + void Build(const solvers::OSQPSettingsYaml&); private: // Osc checkers and constructor-related methods From 0882d8ca9f11d40f70cc9f6e76bf8f27c3849209 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 7 Mar 2022 17:29:11 -0500 Subject: [PATCH 107/758] rest of osqp changes --- .../osc_run/osc_running_qp_settings.yaml | 21 +++++++ examples/Cassie/run_osc_jumping_controller.cc | 10 ++-- .../Cassie/run_osc_standing_controller.cc | 30 ++++++---- examples/Cassie/run_osc_walking_controller.cc | 8 ++- .../Cassie/run_osc_walking_controller_alip.cc | 24 +++++--- solvers/BUILD.bazel | 11 ++++ solvers/default_osc_osqp_settings.yaml | 21 +++++++ solvers/fast_osqp_solver.cc | 38 +++++++++--- solvers/fast_osqp_solver.h | 13 +++-- solvers/osqp_settings_yaml.h | 58 +++++++++++++++++++ 10 files changed, 195 insertions(+), 39 deletions(-) create mode 100644 examples/Cassie/osc_run/osc_running_qp_settings.yaml create mode 100644 solvers/default_osc_osqp_settings.yaml create mode 100644 solvers/osqp_settings_yaml.h diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml new file mode 100644 index 0000000000..7ec5059213 --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -0,0 +1,21 @@ +rho: 0.0001 +sigma: 1e-6 +max_iter: 200 +eps_abs: 1e-5 +eps_rel: 1e-5 +eps_prim_inf: 1e-5 +eps_dual_inf: 1e-5 +alpha: 1.6 +linsys_solver: 0 +delta: 1e-6 +polish: 1 +polish_refine_iter: 3 +verbose: 0 +scaled_termination: 1 +check_termination: 25 +warm_start: 1 +scaling: 10 +adaptive_rho: 1 +adaptive_rho_interval: 0 +adaptive_rho_tolerance: 5 +adaptive_rho_fraction: 0.4 diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index e0033e9372..0ded95f1c4 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -87,6 +87,8 @@ DEFINE_string(traj_name, "jumping_0.15h_0.3d", "File to load saved trajectories from"); DEFINE_string(gains_filename, "examples/Cassie/osc_jump/osc_jumping_gains.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", + "Filepath containing qp settings"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -121,11 +123,11 @@ int DoMain(int argc, char* argv[]) { feet_contact_points = {left_toe, right_toe}; /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - // OSCJumpingGains gains; - // const YAML::Node& root = - // YAML::LoadFile(FindResourceOrThrow(FLAGS_gains_filename)); OSCJumpingGains gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( @@ -470,7 +472,7 @@ int DoMain(int argc, char* argv[]) { pelvis_tracking_data.SetImpactInvariantProjection(true); // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 8dfcc1d166..e91ab0851e 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -8,16 +8,16 @@ #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/osc/operational_space_control.h" -#include "systems/framework/lcm_driven_loop.h" -#include "systems/robot_lcm_systems.h" -#include "drake/common/yaml/yaml_io.h" -#include "systems/controllers/osc/options_tracking_data.h" -#include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/controllers/osc/com_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/options_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -36,9 +36,9 @@ using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; @@ -60,6 +60,8 @@ DEFINE_double(cost_weight_multiplier, 1.0, DEFINE_double(height, .8, "The initial COM height (m)"); DEFINE_string(gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", + "Filepath containing qp settings"); DEFINE_bool(use_radio, false, "use the radio to set height or not"); DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); @@ -135,7 +137,11 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); + auto gains = + drake::yaml::LoadYamlFile(FLAGS_gains_filename); + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); MatrixXd K_p_com = Eigen::Map< Eigen::Matrix>( @@ -201,7 +207,8 @@ int DoMain(int argc, char* argv[]) { std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); + plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, + FLAGS_use_radio); auto pelvis_rot_traj_generator = builder.AddSystem( plant_w_springs, context_w_spr.get(), feet_contact_points, @@ -281,7 +288,8 @@ int DoMain(int argc, char* argv[]) { // Hip yaw joint tracking // We use hip yaw joint tracking instead of pelvis yaw tracking because the - // foot sometimes rotates about yaw, and we need hip yaw joint to go back to 0. + // foot sometimes rotates about yaw, and we need hip yaw joint to go back to + // 0. double w_hip_yaw = 0.5; double hip_yaw_kp = 40; double hip_yaw_kd = 0.5; @@ -299,7 +307,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&right_hip_yaw_traj, VectorXd::Zero(1)); // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); // Connect ports builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 6cd1ce1060..98e4a70a85 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -76,6 +76,8 @@ DEFINE_string( "The name of the channel to receive the cassie out structure from."); DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", + "Filepath containing qp settings"); DEFINE_bool(publish_osc_data, true, "whether to publish lcm messages for OscTrackData"); DEFINE_bool(print_osc, false, "whether to print the osc debug message or not"); @@ -92,7 +94,9 @@ int DoMain(int argc, char* argv[]) { // Read-in the parameters auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); @@ -574,7 +578,7 @@ int DoMain(int argc, char* argv[]) { {post_left_double_support_state, post_right_double_support_state}); // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_robot_output_input_port()); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 61dfe12cc0..2832b8d3f1 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -11,8 +11,9 @@ #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/fsm_event_time.h" +#include "systems/controllers/alip_swing_ft_traj_gen.h" #include "systems/controllers/alip_traj_gen.h" +#include "systems/controllers/fsm_event_time.h" #include "systems/controllers/osc/com_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" @@ -20,7 +21,6 @@ #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" -#include "systems/controllers/alip_swing_ft_traj_gen.h" #include "systems/controllers/time_based_fsm.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" @@ -45,9 +45,9 @@ using Eigen::VectorXd; using drake::multibody::Frame; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using multibody::WorldYawViewFrame; using systems::controllers::ComTrackingData; @@ -74,6 +74,8 @@ DEFINE_string( "The name of the channel to receive the cassie out structure from."); DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", "Filepath containing gains"); +DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", + "Filepath containing qp settings"); DEFINE_bool(publish_osc_data, true, "whether to publish lcm messages for OscTrackData"); DEFINE_bool(print_osc, false, "whether to print the osc debug message or not"); @@ -90,7 +92,9 @@ int DoMain(int argc, char* argv[]) { // Read-in the parameters auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)); // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); if (FLAGS_spring_model) { @@ -338,7 +342,8 @@ int DoMain(int argc, char* argv[]) { int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingWeights(gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingWeights(gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -482,8 +487,9 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(&swing_ft_traj_global); } - ComTrackingData center_of_mass_traj("alip_com_traj", gains.K_p_com, gains.K_d_com, - gains.W_com, plant_w_spr, plant_w_spr); + ComTrackingData center_of_mass_traj("alip_com_traj", gains.K_p_com, + gains.K_d_com, gains.W_com, plant_w_spr, + plant_w_spr); // FiniteStatesToTrack cannot be empty center_of_mass_traj.AddFiniteStateToTrack(-1); osc->AddTrackingData(¢er_of_mass_traj); @@ -532,13 +538,13 @@ int DoMain(int argc, char* argv[]) { {post_left_double_support_state, post_right_double_support_state}); // Build OSC problem - osc->Build(); + osc->Build(osqp_settings); // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_robot_output_input_port()); builder.Connect(fsm->get_output_port(0), osc->get_fsm_input_port()); builder.Connect(alip_traj_generator->get_output_port_com(), - osc->get_tracking_data_input_port("alip_com_traj")); + osc->get_tracking_data_input_port("alip_com_traj")); builder.Connect(swing_ft_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("swing_ft_traj")); builder.Connect(head_traj_gen->get_output_port(0), diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 898e6e85eb..dfc1fcf0b4 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -34,12 +34,23 @@ cc_library( "fast_osqp_solver.h", ], deps = [ + ":osqp_settings_yaml", "//lcmtypes:lcmt_robot", "@drake//:drake_shared_library", "@osqp", ], ) +cc_library( + name = "osqp_settings_yaml", + srcs = [ + "osqp_settings_yaml.h", + ], + deps = [ + "@drake//:drake_shared_library", + ], +) + cc_library( name = "nonlinear_constraint", srcs = [ diff --git a/solvers/default_osc_osqp_settings.yaml b/solvers/default_osc_osqp_settings.yaml new file mode 100644 index 0000000000..7ec5059213 --- /dev/null +++ b/solvers/default_osc_osqp_settings.yaml @@ -0,0 +1,21 @@ +rho: 0.0001 +sigma: 1e-6 +max_iter: 200 +eps_abs: 1e-5 +eps_rel: 1e-5 +eps_prim_inf: 1e-5 +eps_dual_inf: 1e-5 +alpha: 1.6 +linsys_solver: 0 +delta: 1e-6 +polish: 1 +polish_refine_iter: 3 +verbose: 0 +scaled_termination: 1 +check_termination: 25 +warm_start: 1 +scaling: 10 +adaptive_rho: 1 +adaptive_rho_interval: 0 +adaptive_rho_tolerance: 5 +adaptive_rho_fraction: 0.4 diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 9ee9639e08..48030afde8 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -292,8 +292,9 @@ void SetDualSolution( bool FastOsqpSolver::is_available() { return true; } -void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, - const SolverOptions& solver_options) { +void FastOsqpSolver::InitializeSolver( + const MathematicalProgram& prog, + const solvers::OSQPSettingsYaml& solver_options) { // Get the cost for the QP. Eigen::SparseMatrix P_sparse; std::vector q(prog.num_vars(), 0); @@ -325,12 +326,9 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, osqp_data_->l = l.data(); osqp_data_->u = u.data(); - // Define Solver settings as default. - // Problem settings osqp_settings_ = static_cast(c_malloc(sizeof(OSQPSettings))); osqp_set_default_settings(osqp_settings_); - SetFastOsqpSolverSettings(solver_options, osqp_settings_); - std::cout << osqp_settings_->time_limit << std::endl; + SetOsqpSolverSettingsFromYaml(solver_options); // Setup workspace. workspace_ = nullptr; @@ -342,6 +340,32 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, is_init_ = true; } +void FastOsqpSolver::SetOsqpSolverSettingsFromYaml( + const solvers::OSQPSettingsYaml& solver_options) { + osqp_settings_->rho = solver_options.rho; + osqp_settings_->sigma = solver_options.sigma; + osqp_settings_->max_iter = solver_options.max_iter; + osqp_settings_->eps_abs = solver_options.eps_abs; + osqp_settings_->eps_rel = solver_options.eps_rel; + osqp_settings_->eps_prim_inf = solver_options.eps_prim_inf; + osqp_settings_->eps_dual_inf = solver_options.eps_dual_inf; + osqp_settings_->alpha = solver_options.alpha; + + osqp_settings_->delta = solver_options.delta; + osqp_settings_->polish = solver_options.polish; + osqp_settings_->polish_refine_iter = solver_options.polish_refine_iter; + osqp_settings_->verbose = solver_options.verbose; + osqp_settings_->scaled_termination = solver_options.scaled_termination; + osqp_settings_->check_termination = solver_options.check_termination; + osqp_settings_->warm_start = solver_options.warm_start; + osqp_settings_->scaling = solver_options.scaling; + osqp_settings_->adaptive_rho = solver_options.adaptive_rho; + osqp_settings_->adaptive_rho_interval = solver_options.adaptive_rho_interval; + osqp_settings_->adaptive_rho_tolerance = + solver_options.adaptive_rho_tolerance; + osqp_settings_->adaptive_rho_fraction = solver_options.adaptive_rho_fraction; +} + void FastOsqpSolver::WarmStart(const Eigen::VectorXd& primal, const Eigen::VectorXd& dual) { std::vector x, y; @@ -350,7 +374,7 @@ void FastOsqpSolver::WarmStart(const Eigen::VectorXd& primal, for (int i = 0; i < primal.size(); ++i) { x.push_back(ConvertInfinity(primal(i))); } - for (int i = 0; i < dual.size(); ++i){ + for (int i = 0; i < dual.size(); ++i) { y.push_back(ConvertInfinity(dual(i))); } osqp_warm_start(workspace_, x.data(), y.data()); diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index 3b97ef0949..7bbd771348 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -2,6 +2,8 @@ #include +#include "solvers/osqp_settings_yaml.h" + #include "drake/common/drake_copyable.h" #include "drake/solvers/osqp_solver.h" #include "drake/solvers/solver_base.h" @@ -36,7 +38,9 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { //@} void InitializeSolver(const drake::solvers::MathematicalProgram&, - const drake::solvers::SolverOptions&); + const solvers::OSQPSettingsYaml& solver_options); + void SetOsqpSolverSettingsFromYaml(const solvers::OSQPSettingsYaml&); + /// Solver will automatically reenable warm starting after a successful solve void DisableWarmStart() const { osqp_settings_->warm_start = false; @@ -49,12 +53,9 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { warm_start_ = true; } - void WarmStart(const Eigen::VectorXd& primal, - const Eigen::VectorXd& dual); + void WarmStart(const Eigen::VectorXd& primal, const Eigen::VectorXd& dual); - bool IsInitialized()const{ - return is_init_; - } + bool IsInitialized() const { return is_init_; } // A using-declaration adds these methods into our class's Doxygen. using SolverBase::Solve; diff --git a/solvers/osqp_settings_yaml.h b/solvers/osqp_settings_yaml.h new file mode 100644 index 0000000000..fcd4cc6a07 --- /dev/null +++ b/solvers/osqp_settings_yaml.h @@ -0,0 +1,58 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +namespace dairlib { +namespace solvers { +struct OSQPSettingsYaml { + double rho; + double sigma; + int max_iter; + double eps_abs; + double eps_rel; + double eps_prim_inf; + double eps_dual_inf; + double alpha; + int linsys_solver; + double delta; + int polish; + int polish_refine_iter; + int verbose; + int scaled_termination; + int check_termination; + int warm_start; + int scaling; + int adaptive_rho; + int adaptive_rho_interval; + double adaptive_rho_tolerance; + double adaptive_rho_fraction; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(rho)); + a->Visit(DRAKE_NVP(sigma)); + a->Visit(DRAKE_NVP(max_iter)); + a->Visit(DRAKE_NVP(eps_abs)); + a->Visit(DRAKE_NVP(eps_rel)); + a->Visit(DRAKE_NVP(eps_prim_inf)); + a->Visit(DRAKE_NVP(eps_dual_inf)); + a->Visit(DRAKE_NVP(alpha)); + a->Visit(DRAKE_NVP(linsys_solver)); + a->Visit(DRAKE_NVP(delta)); + a->Visit(DRAKE_NVP(polish)); + a->Visit(DRAKE_NVP(polish_refine_iter)); + a->Visit(DRAKE_NVP(verbose)); + a->Visit(DRAKE_NVP(scaled_termination)); + a->Visit(DRAKE_NVP(check_termination)); + a->Visit(DRAKE_NVP(warm_start)); + a->Visit(DRAKE_NVP(scaling)); + a->Visit(DRAKE_NVP(adaptive_rho)); + a->Visit(DRAKE_NVP(adaptive_rho_interval)); + a->Visit(DRAKE_NVP(adaptive_rho_tolerance)); + a->Visit(DRAKE_NVP(adaptive_rho_fraction)); + } +}; +} // namespace solvers +} // namespace dairlib \ No newline at end of file From 00e62560e9a405381d073f9ec67a07efed02abce Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 7 Mar 2022 17:46:22 -0500 Subject: [PATCH 108/758] merging in the encoder from error_flag --- examples/Cassie/cassie_encoder.cc | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/cassie_encoder.cc b/examples/Cassie/cassie_encoder.cc index 2962ca23c0..7679873774 100644 --- a/examples/Cassie/cassie_encoder.cc +++ b/examples/Cassie/cassie_encoder.cc @@ -15,7 +15,7 @@ CassieEncoder::CassieEncoder(const drake::multibody::MultibodyPlant& pla joint_pos_indices_(joint_pos_indices), joint_vel_indices_(joint_vel_indices), ticks_per_revolution_(ticks_per_revolution){ - for (int i = 0; i < ticks_per_revolution_.size(); ++i){ + for (int i = 0; i < joint_vel_indices_.size(); ++i){ joint_filters_.push_back(std::make_unique()); } this->DeclareVectorInputPort("robot_state", @@ -27,17 +27,17 @@ CassieEncoder::CassieEncoder(const drake::multibody::MultibodyPlant& pla void CassieEncoder::UpdateFilter(const drake::systems::Context& context, systems::BasicVector* output) const { - const systems::BasicVector& input = + const systems::BasicVector& x = *this->template EvalVectorInput(context, 0); - VectorXd q = input.get_value().head(num_positions_); - VectorXd v = input.get_value().tail(num_velocities_); + VectorXd q = x.value().head(num_positions_); + VectorXd v = x.value().tail(num_velocities_); - VectorXd q_filtered = q; - VectorXd v_filtered = v; + VectorXd q_filtered = VectorXd::Zero(num_positions_); + VectorXd v_filtered = VectorXd::Zero(num_velocities_); // joint_encoders - for (int joint_index = 0; joint_index < joint_pos_indices_.size(); + for (int joint_index = 0; joint_index < joint_filters_.size(); ++joint_index) { auto filter = joint_filters_[joint_index].get(); @@ -56,6 +56,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, allzero &= filter->x[i] == 0; } if (allzero) { + std::cout << "Initializing with current encoder value:" << std::endl; // If all filter values are zero, initialize the signal array // with the current encoder value for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { @@ -67,7 +68,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, for (int i = CASSIE_JOINT_FILTER_NB - 1; i > 0; --i) { filter->x[i] = filter->x[i - 1]; } - filter->x[0] = q[joint_pos_indices_[joint_index]]; + filter->x[0] = q_filtered[joint_pos_indices_[joint_index]]; for (int i = CASSIE_JOINT_FILTER_NA - 1; i > 0; --i) { filter->y[i] = filter->y[i - 1]; } @@ -85,7 +86,6 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, VectorXd x_filtered = VectorXd::Zero(num_positions_ + num_velocities_); x_filtered << q_filtered, v_filtered; -// x_filtered << q, v; output->set_value(x_filtered); } From 6c19c65b504d4ebc3c45a77c03fcf70a9d8cdc49 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 8 Mar 2022 11:58:02 -0500 Subject: [PATCH 109/758] properly modeling the encoders --- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/cassie_encoder.cc | 109 ++++++++++++++++++++++-------- examples/Cassie/cassie_encoder.h | 57 +++++++++++++--- examples/Cassie/cassie_utils.cc | 31 +-------- examples/Cassie/multibody_sim.cc | 3 +- 5 files changed, 131 insertions(+), 70 deletions(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index feda9ad8e7..4c71392409 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -552,6 +552,7 @@ cc_library( ], deps = [ "//systems/framework:vector", + "//multibody:utils", "@drake//:drake_shared_library", ], ) diff --git a/examples/Cassie/cassie_encoder.cc b/examples/Cassie/cassie_encoder.cc index 1ab49bc9a3..82a2fee52a 100644 --- a/examples/Cassie/cassie_encoder.cc +++ b/examples/Cassie/cassie_encoder.cc @@ -2,52 +2,104 @@ #include +#include "multibody/multibody_utils.h" + namespace dairlib { using Eigen::VectorXd; -CassieEncoder::CassieEncoder(const drake::multibody::MultibodyPlant& plant, - std::vector& joint_pos_indices, - std::vector& joint_vel_indices, - std::vector& ticks_per_revolution) +CassieEncoder::CassieEncoder( + const drake::multibody::MultibodyPlant& plant) : num_positions_(plant.num_positions()), - num_velocities_(plant.num_velocities()), - joint_pos_indices_(joint_pos_indices), - joint_vel_indices_(joint_vel_indices), - ticks_per_revolution_(ticks_per_revolution){ - for (int i = 0; i < joint_vel_indices_.size(); ++i){ - joint_filters_.push_back(std::make_unique()); + num_velocities_(plant.num_velocities()) { + auto pos_map = multibody::makeNameToPositionsMap(plant); + auto vel_map = multibody::makeNameToVelocitiesMap(plant); + + for (int i = 0; i < plant.num_joints(); ++i) { + auto& joint = plant.get_joint(drake::multibody::JointIndex(i)); + if (joint_encoder_resolutions.count(joint.name())) { + auto filter = std::make_shared(); + filter->joint_pos_index = pos_map[joint.name()]; + filter->joint_vel_index = vel_map[joint.name() + "dot"]; + filter->joint_encoder_resolution = + joint_encoder_resolutions.at(joint.name()); + joint_filters_.push_back(filter); + } + if (drive_encoder_resolutions.count(joint.name())) { + auto filter = std::make_shared(); + filter->drive_pos_index = pos_map[joint.name()]; + filter->drive_vel_index = vel_map[joint.name() + "dot"]; + filter->drive_encoder_resolution = + drive_encoder_resolutions.at(joint.name()); + filter->gear_ratio = drive_gear_ratios.at(joint.name()); + drive_filters_.push_back(filter); + } } - this->DeclareVectorInputPort("robot_state", + this->DeclareVectorInputPort( + "robot_state", systems::BasicVector(num_positions_ + num_velocities_)); - this->DeclareVectorOutputPort("filtered_state", + this->DeclareVectorOutputPort( + "filtered_state", systems::BasicVector(num_positions_ + num_velocities_), &CassieEncoder::UpdateFilter); } void CassieEncoder::UpdateFilter(const drake::systems::Context& context, - systems::BasicVector* output) const { + systems::BasicVector* output) const { const systems::BasicVector& x = *this->template EvalVectorInput(context, 0); VectorXd q = x.value().head(num_positions_); VectorXd v = x.value().tail(num_velocities_); - VectorXd q_filtered = VectorXd::Zero(num_positions_); - VectorXd v_filtered = VectorXd::Zero(num_velocities_); + VectorXd q_filtered = q; + VectorXd v_filtered = v; + + // drive encoders + for (const auto& filter : drive_filters_) { + // Position + using std::floor; + double ratio = filter->gear_ratio; + double scale = (2.0 * M_PI) / filter->drive_encoder_resolution / ratio; + const int encoder_value = q[filter->drive_pos_index] * ratio / + (2.0 * M_PI) * filter->drive_encoder_resolution; + q_filtered[filter->drive_pos_index] = encoder_value * scale; + + // Velocity + // Initialize unfiltered signal array to prevent bad transients + bool allzero = true; + for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { + allzero &= filter->x[i] == 0; + } + if (allzero) { + // If all filter values are zero, initialize the signal array + // with the current encoder value + for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { + filter->x[i] = encoder_value; + } + } - // joint_encoders - for (int joint_index = 0; joint_index < joint_filters_.size(); - ++joint_index) { - auto filter = joint_filters_[joint_index].get(); + // Shift and update unfiltered signal array + for (int i = DRIVE_FILTER_NB - 1; i > 0; --i) { + filter->x[i] = filter->x[i - 1]; + } + filter->x[0] = encoder_value; + // Compute filter value + int y = 0; + for (int i = 0; i < DRIVE_FILTER_NB; ++i) { + y += filter->x[i] * drive_filter_b[i]; + } + v_filtered[filter->drive_vel_index] = y * scale / M_PI; + } + // joint encoders + for (const auto& filter : joint_filters_) { // Position using std::floor; const double ticks_per_radian = - ticks_per_revolution_[joint_index] / (2.0 * M_PI); - q_filtered[joint_pos_indices_[joint_index]] = - floor(q[joint_pos_indices_[joint_index]] * ticks_per_radian) / - ticks_per_radian; + filter->joint_encoder_resolution / (2.0 * M_PI); + q_filtered[filter->joint_pos_index] = + floor(q[filter->joint_pos_index] * ticks_per_radian) / ticks_per_radian; // Velocity // Initialize unfiltered signal array to prevent bad transients @@ -56,11 +108,10 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, allzero &= filter->x[i] == 0; } if (allzero) { - std::cout << "Initializing with current encoder value:" << std::endl; // If all filter values are zero, initialize the signal array // with the current encoder value for (int i = 0; i < CASSIE_JOINT_FILTER_NB; ++i) { - filter->x[i] = q_filtered[joint_pos_indices_[joint_index]]; + filter->x[i] = q_filtered[filter->joint_pos_index]; } } @@ -68,7 +119,7 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, for (int i = CASSIE_JOINT_FILTER_NB - 1; i > 0; --i) { filter->x[i] = filter->x[i - 1]; } - filter->x[0] = q_filtered[joint_pos_indices_[joint_index]]; + filter->x[0] = q_filtered[filter->joint_pos_index]; for (int i = CASSIE_JOINT_FILTER_NA - 1; i > 0; --i) { filter->y[i] = filter->y[i - 1]; } @@ -81,12 +132,10 @@ void CassieEncoder::UpdateFilter(const drake::systems::Context& context, for (int i = 1; i < CASSIE_JOINT_FILTER_NA; ++i) { filter->y[0] -= filter->y[i] * joint_filter_a[i]; } - v_filtered[joint_vel_indices_[joint_index]] = filter->y[0]; + v_filtered[filter->joint_vel_index] = filter->y[0]; } - VectorXd x_filtered = VectorXd::Zero(num_positions_ + num_velocities_); - x_filtered << q_filtered, v; -// x_filtered << q, v; + x_filtered << q_filtered, v_filtered; output->set_value(x_filtered); } diff --git a/examples/Cassie/cassie_encoder.h b/examples/Cassie/cassie_encoder.h index e94cb1764f..a2e5a011ca 100644 --- a/examples/Cassie/cassie_encoder.h +++ b/examples/Cassie/cassie_encoder.h @@ -15,14 +15,48 @@ namespace dairlib { #define CASSIE_ENC_RES_LOW 8192 #define CASSIE_ENC_RES_HIGH 262144 +#define DRIVE_FILTER_NB 9 #define CASSIE_JOINT_FILTER_NB 4 #define CASSIE_JOINT_FILTER_NA 3 +static int drive_filter_b[DRIVE_FILTER_NB] = {2727, 534, -2658, -795, 72, + 110, 19, -6, -3}; + static double joint_filter_b[CASSIE_JOINT_FILTER_NB] = {12.348, 12.348, -12.348, - -12.348}; + -12.348}; static double joint_filter_a[CASSIE_JOINT_FILTER_NA] = {1.0, -1.7658, 0.79045}; +static std::map drive_encoder_resolutions = { + {"hip_roll_left", CASSIE_ENC_RES_LOW}, + {"hip_yaw_left", CASSIE_ENC_RES_LOW}, + {"hip_pitch_left", CASSIE_ENC_RES_LOW}, + {"knee_left", CASSIE_ENC_RES_LOW}, + {"toe_left", CASSIE_ENC_RES_HIGH}, + {"hip_roll_right", CASSIE_ENC_RES_LOW}, + {"hip_yaw_right", CASSIE_ENC_RES_LOW}, + {"hip_pitch_right", CASSIE_ENC_RES_LOW}, + {"knee_right", CASSIE_ENC_RES_LOW}, + {"toe_right", CASSIE_ENC_RES_HIGH}}; + +static std::map drive_gear_ratios = { + {"hip_roll_left", 25}, + {"hip_yaw_left", 25}, + {"hip_pitch_left", 16}, + {"knee_left", 16}, + {"toe_left", 50}, + {"hip_roll_right", 25}, + {"hip_yaw_right", 25}, + {"hip_pitch_right", 16}, + {"knee_right", 16}, + {"toe_right", 50}}; + +static std::map joint_encoder_resolutions = { + {"knee_joint_left", CASSIE_ENC_RES_HIGH}, + {"ankle_joint_left", CASSIE_ENC_RES_HIGH}, + {"knee_joint_right", CASSIE_ENC_RES_HIGH}, + {"ankle_joint_right", CASSIE_ENC_RES_HIGH}}; + /// Class to capture the quantization effects of Cassie's encoders /// The resolution and velocity filter values are taken from the supplied MuJoCo /// simulator from Agility Robotics @@ -30,10 +64,7 @@ class CassieEncoder final : public drake::systems::LeafSystem { public: DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CassieEncoder) - explicit CassieEncoder(const drake::multibody::MultibodyPlant& plant, - std::vector& joint_pos_indices, - std::vector& joint_vel_indices, - std::vector& ticks_per_revolution); + explicit CassieEncoder(const drake::multibody::MultibodyPlant& plant); ~CassieEncoder() override = default; @@ -42,7 +73,17 @@ class CassieEncoder final : public drake::systems::LeafSystem { systems::BasicVector* output) const; private: + struct DriveFilter { + int drive_pos_index; + int drive_vel_index; + int drive_encoder_resolution; // ticks per rotation + int gear_ratio; // ticks per rotation + int x[DRIVE_FILTER_NB]; + }; struct JointFilter { + int joint_pos_index; + int joint_vel_index; + int joint_encoder_resolution; // ticks per rotation double x[CASSIE_JOINT_FILTER_NB]; double y[CASSIE_JOINT_FILTER_NA]; }; @@ -51,10 +92,8 @@ class CassieEncoder final : public drake::systems::LeafSystem { int num_positions_; int num_velocities_; - std::vector joint_pos_indices_; - std::vector joint_vel_indices_; - std::vector ticks_per_revolution_; - std::vector> joint_filters_; + std::vector> joint_filters_; + std::vector> drive_filters_; }; } // namespace dairlib diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index d84d245994..4e0a3d4953 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -201,37 +201,8 @@ const systems::SimCassieSensorAggregator& AddImuAndAggregator( std::vector joint_pos_indices; std::vector joint_vel_indices; std::vector ticks_per_revolution; - std::map joint_encoder_resolutions = { - {"hip_roll_left", CASSIE_ENC_RES_LOW}, - {"hip_roll_right", CASSIE_ENC_RES_LOW}, - {"hip_yaw_left", CASSIE_ENC_RES_LOW}, - {"hip_yaw_right", CASSIE_ENC_RES_LOW}, - {"hip_pitch_left", CASSIE_ENC_RES_LOW}, - {"hip_pitch_right", CASSIE_ENC_RES_LOW}, - {"knee_left", CASSIE_ENC_RES_LOW}, - {"knee_right", CASSIE_ENC_RES_LOW}, - {"knee_joint_left", CASSIE_ENC_RES_HIGH}, - {"knee_joint_right", CASSIE_ENC_RES_HIGH}, - {"ankle_joint_left", CASSIE_ENC_RES_HIGH}, - {"ankle_joint_right", CASSIE_ENC_RES_HIGH}, - {"toe_left", CASSIE_ENC_RES_LOW}, - {"toe_right", CASSIE_ENC_RES_LOW}}; - auto pos_map = multibody::makeNameToPositionsMap(plant); - auto vel_map = multibody::makeNameToVelocitiesMap(plant); - for (int i = 0; i < plant.num_joints(); ++i) { - auto& joint = plant.get_joint(drake::multibody::JointIndex(i)); - if (joint_encoder_resolutions.find(joint.name()) != - joint_encoder_resolutions.end()) { - joint_pos_indices.push_back(pos_map[joint.name()]); - joint_vel_indices.push_back(vel_map[joint.name() + "dot"]); - ticks_per_revolution.push_back( - joint_encoder_resolutions.at(joint.name())); - } - } - - const auto& encoders = builder->AddSystem( - plant, joint_pos_indices, joint_vel_indices, ticks_per_revolution); + const auto& encoders = builder->AddSystem(plant); auto sensor_aggregator = builder->AddSystem(plant); diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 459bf7e07b..e97da64108 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -61,6 +61,7 @@ DEFINE_double(publish_rate, 1000, "Publish rate for simulator"); DEFINE_double(init_height, .7, "Initial starting height of the pelvis above " "ground"); +DEFINE_double(toe_spread, .15, "Initial toe spread in m."); DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); DEFINE_string(radio_channel, "CASSIE_VIRTUAL_RADIO" ,"LCM channel for virtual radio command"); @@ -176,7 +177,7 @@ int do_main(int argc, char* argv[]) { VectorXd q_init, u_init, lambda_init; double mu_fp = 0; double min_normal_fp = 70; - double toe_spread = .2; + double toe_spread = FLAGS_toe_spread; // Create a plant for CassieFixedPointSolver. // Note that we cannot use the plant from the above diagram, because after the // diagram is built, plant.get_actuation_input_port().HasValue(*context) From 338f958101ce222f900988b4165cfc0ef42e5f8d Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 13:53:32 -0500 Subject: [PATCH 110/758] getting ready for hardware --- bindings/pydairlib/analysis/cassie_plotting_utils.py | 1 - examples/Cassie/cassie_state_estimator.h | 8 ++++---- examples/Cassie/osc_run/osc_running_gains.yaml | 4 ++-- systems/controllers/osc/operational_space_control.cc | 2 +- 4 files changed, 7 insertions(+), 8 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 984515f8db..6179905924 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -32,7 +32,6 @@ def make_plant_and_context(floating_base=True, springs=True): builder = DiagramBuilder() - import pdb; pdb.set_trace() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) if (springs): addCassieMultibody(plant, scene_graph, diff --git a/examples/Cassie/cassie_state_estimator.h b/examples/Cassie/cassie_state_estimator.h index 2f76f9bdfb..d65e49dec6 100644 --- a/examples/Cassie/cassie_state_estimator.h +++ b/examples/Cassie/cassie_state_estimator.h @@ -213,10 +213,10 @@ class CassieStateEstimator : public drake::systems::LeafSystem { // Heel ~??? // https://drive.google.com/file/d/1o7QS4ZksU91EBIpwtNnKpunob93BKiX_ // https://drive.google.com/file/d/1mlDzi0fa-YHopeRHaa-z88fPGuI2Aziv - const double knee_spring_threshold_ctrl_ = -0.015; - const double knee_spring_threshold_ekf_ = -0.015; - const double heel_spring_threshold_ctrl_ = -0.01; - const double heel_spring_threshold_ekf_ = -0.01; + const double knee_spring_threshold_ctrl_ = -0.020; + const double knee_spring_threshold_ekf_ = -0.020; + const double heel_spring_threshold_ctrl_ = -0.02; + const double heel_spring_threshold_ekf_ = -0.02; const double w_soft_constraint_ = 100; // Soft constraint cost const double contact_force_threshold_; // Soft constraint cost diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index fef311b5f2..a338dd30bb 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -13,7 +13,7 @@ W_lambda_c_reg: [1, 0.001, 0.01, W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 -w_soft_constraint: 0.001 +w_soft_constraint: 100 w_input_reg: 0.01 impact_threshold: 0.025 relative_feet: true @@ -40,7 +40,7 @@ hip_yaw_kp: 60 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.05 +center_line_offset: 0.075 FootstepKd: [ 0.2, 0, 0, 0, 0.45, 0, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 6321886cc1..f817aeafb1 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -756,7 +756,7 @@ VectorXd OperationalSpaceControl::SolveQp( initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { - std::cerr << "QP did not solve in time!" << std::endl; +// std::cerr << "QP did not solve in time!" << std::endl; // solver_->DisableWarmStart(); *u_prev_ = VectorXd::Zero(n_u_); } From a0003972f2e3d886b60fdff0a0af155976160322 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 14:05:48 -0500 Subject: [PATCH 111/758] adding ekf filtering --- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/run_osc_running_controller.cc | 6 ++ systems/filters/BUILD.bazel | 20 +++++ .../filters/floating_base_velocity_filter.h | 19 ++++ systems/filters/output_vector_filter.cc | 86 +++++++++++++++++++ systems/filters/output_vector_filter.h | 48 +++++++++++ 6 files changed, 180 insertions(+) create mode 100644 systems/filters/BUILD.bazel create mode 100644 systems/filters/floating_base_velocity_filter.h create mode 100644 systems/filters/output_vector_filter.cc create mode 100644 systems/filters/output_vector_filter.h diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 002fc563f3..7ea8ab75d6 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -360,6 +360,7 @@ cc_binary( "//multibody:utils", "//systems:robot_lcm_systems", "//systems:system_utils", + "//systems/filters:floating_base_velocity_filter", "//systems/controllers/osc:osc_tracking_datas", "//systems/framework:lcm_driven_loop", "//systems/primitives", diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 4a604ff3c5..3953dd5b94 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -29,6 +29,7 @@ #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/filters/floating_base_velocity_filter.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -191,6 +192,9 @@ int DoMain(int argc, char* argv[]) { auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); + std::vector tau = {.001, .03, .001}; + auto ekf_filter = + builder.AddSystem(plant, tau); /**** OSC setup ****/ // Cost @@ -474,6 +478,8 @@ int DoMain(int argc, char* argv[]) { osc->get_near_impact_input_port()); builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); builder.Connect(state_receiver->get_output_port(0), + ekf_filter->get_input_port()); + builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), diff --git a/systems/filters/BUILD.bazel b/systems/filters/BUILD.bazel new file mode 100644 index 0000000000..4ed72c9e48 --- /dev/null +++ b/systems/filters/BUILD.bazel @@ -0,0 +1,20 @@ +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "output_vector_filter", + srcs = ["output_vector_filter.cc"], + hdrs = ["output_vector_filter.h"], + deps = [ + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "floating_base_velocity_filter", + hdrs = ["floating_base_velocity_filter.h"], + deps = [ + ":output_vector_filter", + "@drake//:drake_shared_library", + ], +) diff --git a/systems/filters/floating_base_velocity_filter.h b/systems/filters/floating_base_velocity_filter.h new file mode 100644 index 0000000000..287f2f9054 --- /dev/null +++ b/systems/filters/floating_base_velocity_filter.h @@ -0,0 +1,19 @@ +#pragma once +#include "output_vector_filter.h" +#include "drake/multibody/plant/multibody_plant.h" + +/// Specialization of Timestamped Low Pass Filter for floting base velocity +/// estimates +namespace dairlib::systems { + +class FloatingBaseVelocityFilter : public OutputVectorFilter { + public: + FloatingBaseVelocityFilter( + const drake::multibody::MultibodyPlant& plant, + const std::vector& tau) : + OutputVectorFilter( + plant, tau, std::vector{plant.num_positions() + 3, + plant.num_positions() + 4, + plant.num_positions() + 5}){}; +}; +} diff --git a/systems/filters/output_vector_filter.cc b/systems/filters/output_vector_filter.cc new file mode 100644 index 0000000000..fd5a21c1a0 --- /dev/null +++ b/systems/filters/output_vector_filter.cc @@ -0,0 +1,86 @@ +#include "output_vector_filter.h" +#include "systems/framework/output_vector.h" + +using Eigen::VectorXd; +using Eigen::MatrixXd; +using drake::systems::LeafSystem; +using drake::systems::Context; + + +namespace dairlib::systems { + +OutputVectorFilter::OutputVectorFilter( + const drake::multibody::MultibodyPlant& plant, + const std::vector& tau, + std::optional> filter_idxs) + : n_y_filt_(tau.size()), tau_(tau) { + int n_y = plant.num_positions() + + plant.num_velocities() + plant.num_actuators() + 3; + + DRAKE_DEMAND(filter_idxs.has_value() || tau.size() == n_y); + if (filter_idxs.has_value()) { + DRAKE_DEMAND(filter_idxs->size() == tau.size()); + } + + if (!filter_idxs.has_value()){ + std::vector idxs(n_y); + std::iota(idxs.begin(), idxs.end(), 0); + filter_idxs_ = idxs; + } else { + filter_idxs_ = filter_idxs.value(); + } + + OutputVector model_vector( + plant.num_positions(), plant.num_velocities(), plant.num_actuators()); + + this->DeclareVectorInputPort("x", model_vector); + this->DeclareVectorOutputPort("y", model_vector, + &OutputVectorFilter::CopyFilterValues); + this->DeclarePerStepDiscreteUpdateEvent( + &OutputVectorFilter::DiscreteVariableUpdate); + + prev_val_idx_ = this->DeclareDiscreteState(VectorXd::Zero(n_y)); + prev_time_idx_ = this->DeclareDiscreteState(VectorXd::Zero(1)); +} + +drake::systems::EventStatus OutputVectorFilter::DiscreteVariableUpdate( + const drake::systems::Context &context, + drake::systems::DiscreteValues *discrete_state) const { + + const OutputVector* y_t = + (OutputVector*)EvalVectorInput(context, 0); + + double dt = y_t->get_timestamp() - + discrete_state->get_value(prev_time_idx_)[0]; + VectorXd y = y_t->get_data(); + VectorXd y_prev = discrete_state->get_value(prev_val_idx_); + + for (int i = 0; i < n_y_filt_; i++){ + double alpha = dt / (dt + tau_.at(i)); + y(filter_idxs_.at(i)) = + alpha * y(filter_idxs_.at(i)) + + (1.0 - alpha) * y_prev(filter_idxs_.at(i)); + } + discrete_state->get_mutable_value(prev_time_idx_) << + y_t->get_timestamp() * VectorXd::Ones(1) ; + discrete_state->get_mutable_value(prev_val_idx_) << y; + + return drake::systems::EventStatus::Succeeded(); +} + +void OutputVectorFilter::CopyFilterValues( + const drake::systems::Context &context, + dairlib::systems::OutputVector *y) const { + + auto y_curr = (OutputVector*)EvalVectorInput(context, 0); + + y->SetDataVector(y_curr->get_data()); + y->set_timestamp(y_curr->get_timestamp()); + if (context.get_discrete_state(prev_time_idx_).get_value()[0] >= .001){ + VectorXd y_filt = context.get_discrete_state(prev_val_idx_).get_value(); + for (auto& i : filter_idxs_) { + y->get_mutable_value()[i] = y_filt(i); + } + } +} +} \ No newline at end of file diff --git a/systems/filters/output_vector_filter.h b/systems/filters/output_vector_filter.h new file mode 100644 index 0000000000..23536263f7 --- /dev/null +++ b/systems/filters/output_vector_filter.h @@ -0,0 +1,48 @@ +#pragma once + +#include "drake/systems/framework/leaf_system.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "systems/framework/output_vector.h" + +/// TimestampedLowpassFilter implements a first order vector-valued linear +/// lowpass filter. Since the control loops we use generally do not have +/// a fixed sampling rate, we implement this filter using timestamped vectors +/// to achieve the desired time constant / cutoff frequency + + +using Eigen::VectorXd; +using Eigen::MatrixXd; +using drake::systems::LeafSystem; +using drake::systems::Context; + +namespace dairlib::systems { + +/// Filter system - +/// tau is the cutoff frequency for each index listed in filter idxs +/// n_y is the length of the base vector that will be filtered +/// filter_idxs is the indexes of the input vector to be filtered +/// Note: If filter_idxs is not supplied, then the length of tau must be n_y +class OutputVectorFilter : public LeafSystem { + public: + // For cutoff frequency w_c (in rad/s), tau = 1/w_c, + // For cutoff frequency f in Hz, tau = 1/(2*pi*f) + OutputVectorFilter( + const drake::multibody::MultibodyPlant& plant, + const std::vector& tau, + std::optional> filter_idxs); + + private: + void CopyFilterValues(const drake::systems::Context &context, + OutputVector *y) const; + + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + std::vector filter_idxs_; + const int n_y_filt_; + const std::vector& tau_; // time constant + int prev_val_idx_; + int prev_time_idx_; +}; +} From b3dd8da11b18f2880ec88ba384f8aa5664296b3c Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 14:57:36 -0500 Subject: [PATCH 112/758] small gain tuning --- examples/Cassie/osc_run/osc_running_gains.yaml | 10 +++++----- examples/Cassie/run_osc_running_controller.cc | 2 +- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index a338dd30bb..14d4b7bcd7 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -14,7 +14,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 w_soft_constraint: 100 -w_input_reg: 0.01 +w_input_reg: 0.001 impact_threshold: 0.025 relative_feet: true relative_pelvis: true @@ -35,7 +35,7 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 5 +w_hip_yaw: 1 hip_yaw_kp: 60 hip_yaw_kd: 1 # Foot placement parameters @@ -75,11 +75,11 @@ SwingFootW: 0, 0, 1] SwingFootKp: [125, 0, 0, - 0, 60, 0, + 0, 80, 0, 0, 0, 50] SwingFootKd: - [10, 0, 0, - 0, 2, 0, + [5, 0, 0, + 0, 1.5, 0, 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 3953dd5b94..ebca35cc7a 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -192,7 +192,7 @@ int DoMain(int argc, char* argv[]) { auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - std::vector tau = {.001, .03, .001}; + std::vector tau = {.001, .01, .001}; auto ekf_filter = builder.AddSystem(plant, tau); From 6d9f373ff92dc61a0b201c5abd396ac90c892498 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 15:39:00 -0500 Subject: [PATCH 113/758] attempting more aggresive foot tracking --- .../pydairlib/analysis/plot_configs/cassie_running_plot.yaml | 4 ++-- examples/Cassie/osc_run/foot_traj_generator.cc | 2 +- examples/Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 4679d4147d..d75c3a626b 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -8,8 +8,8 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false -plot_floating_base_velocities: false +plot_floating_base_positions: true +plot_floating_base_velocities: true plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 2ecb65d382..047b56d04f 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -191,7 +191,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[0] = start_pos; Y[0](2) = -rest_length_; Y[1] = start_pos + 0.85 * footstep_correction; - Y[1](2) = -rest_length_ + 0.01; + Y[1](2) = -rest_length_ + 0.02; Y[2] = footstep_correction; Y[2](2) = -rest_length_; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 14d4b7bcd7..7ff4ccdc56 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,4 +1,4 @@ -w_input: 0.00001 +w_input: 0.00000 w_accel: 0.00001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index ebca35cc7a..e9104974a9 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -192,7 +192,7 @@ int DoMain(int argc, char* argv[]) { auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - std::vector tau = {.001, .01, .001}; + std::vector tau = {.05, .05, .01}; auto ekf_filter = builder.AddSystem(plant, tau); From 0dcee4099a477dc9b40e41a45b6db2f30175a349 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 15:41:58 -0500 Subject: [PATCH 114/758] pelvis orientation gains' --- examples/Cassie/osc_run/osc_running_gains.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 7ff4ccdc56..babb1ffcf9 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -66,8 +66,8 @@ PelvisRotKp: 0, 20, 0, 0, 0, 0] PelvisRotKd: - [10, 0, 0, - 0, 5, 0, + [7.5, 0, 0, + 0, 2.5, 0, 0, 0, 0] SwingFootW: [10, 0, 0, From ab5bc0598eaafe5f92ec88c6e4e833144102a215 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 15:43:55 -0500 Subject: [PATCH 115/758] updating logging script to copy running gains --- examples/Cassie/start_logging.py | 3 +++ 1 file changed, 3 insertions(+) diff --git a/examples/Cassie/start_logging.py b/examples/Cassie/start_logging.py index 1193cd0bb4..f8bd8c73b2 100644 --- a/examples/Cassie/start_logging.py +++ b/examples/Cassie/start_logging.py @@ -13,6 +13,7 @@ def main(): standing_gains = dair + "examples/Cassie/osc/osc_standing_gains.yaml" walking_gains = dair + "examples/Cassie/osc/osc_walking_gains.yaml" alip_walking_gains = dair + "examples/Cassie/osc/alip_osc_walking_gains.yaml" + running_gains = dair + "examples/Cassie/osc_run/osc_running_gains.yaml" if not os.path.isdir(logdir): os.mkdir(logdir) @@ -37,6 +38,8 @@ def main(): subprocess.run(['cp', walking_gains, 'walking_gains_%s.yaml' % log_num]) subprocess.run(['cp', alip_walking_gains, 'walking_gains_alip_%s.yaml' % log_num]) + subprocess.run(['cp', running_gains, + 'running_gains_%s.yaml' % log_num]) subprocess.run(['lcm-logger', '-f', 'lcmlog-%s' % log_num]) From 35590c055e6d0e134f0d5a215d8fe316086f37c2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 15:55:25 -0500 Subject: [PATCH 116/758] adding flag to log QP --- solvers/fast_osqp_solver.cc | 57 +++++++++++++++++++------------------ 1 file changed, 30 insertions(+), 27 deletions(-) diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 48030afde8..e5059e81a5 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -424,40 +424,43 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; - lcmt_qp msg; - msg.n_x = prog.num_vars(); + if(false){ + lcmt_qp msg; + msg.n_x = prog.num_vars(); - Eigen::MatrixXd Q(P_sparse); + Eigen::MatrixXd Q(P_sparse); - // Note: Amessage is transposed, becaues Eigen defaults to column major - for (int i = 0; i < prog.num_vars(); i++) { - msg.Q.push_back(std::vector(Q.col(i).data(), - Q.col(i).data() + prog.num_vars())); - } - msg.w = q; + // Note: Amessage is transposed, becaues Eigen defaults to column major + for (int i = 0; i < prog.num_vars(); i++) { + msg.Q.push_back(std::vector(Q.col(i).data(), + Q.col(i).data() + prog.num_vars())); + } + msg.w = q; - Eigen::MatrixXd A(A_sparse); + Eigen::MatrixXd A(A_sparse); - // std::cout << A.row(68) << std::endl; - msg.n_ineq = A.rows(); - for (int i = 0; i < A.rows(); i++) { - std::vector row(A.cols()); - for (int j = 0; j < A.cols(); j++) { - row[j] = A(i, j); + // std::cout << A.row(68) << std::endl; + msg.n_ineq = A.rows(); + for (int i = 0; i < A.rows(); i++) { + std::vector row(A.cols()); + for (int j = 0; j < A.cols(); j++) { + row[j] = A(i, j); + } + msg.A_ineq.push_back(row); } - msg.A_ineq.push_back(row); - } - msg.ineq_lb = l; - msg.ineq_ub = u; - msg.x_lb = std::vector(prog.num_vars(), - -std::numeric_limits::infinity()); - msg.x_ub = std::vector(prog.num_vars(), - std::numeric_limits::infinity()); + msg.ineq_lb = l; + msg.ineq_ub = u; + msg.x_lb = std::vector(prog.num_vars(), + -std::numeric_limits::infinity()); + msg.x_ub = std::vector(prog.num_vars(), + std::numeric_limits::infinity()); + + msg.n_eq = 0; + lcm::LCM lcm; + lcm.publish("QP_LOG", &msg); + } - msg.n_eq = 0; - lcm::LCM lcm; - lcm.publish("QP_LOG", &msg); // Solve problem. if (!solution_result) { From d8f41b2844decb99c554e1635951614579d4cc0d Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 16:52:38 -0500 Subject: [PATCH 117/758] gains used for last hardware experiments --- solvers/fast_osqp_solver.cc | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index e5059e81a5..655ad9b82b 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -424,7 +424,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; - if(false){ + if (false) { lcmt_qp msg; msg.n_x = prog.num_vars(); @@ -461,7 +461,6 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, lcm.publish("QP_LOG", &msg); } - // Solve problem. if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); From 22f80cb789c91ac7628b1de57aa957278d0072b7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 9 Mar 2022 16:52:44 -0500 Subject: [PATCH 118/758] more tuning in sim --- examples/Cassie/osc_run/osc_running_gains.yaml | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index babb1ffcf9..71ed932029 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,8 +4,8 @@ w_accel: 0.00001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 1, - 1, 0.9, 0.5, 0.1, 1] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, @@ -29,14 +29,14 @@ rest_length: 0.85 stance_duration: 0.30 flight_duration: 0.08 -mu: 0.4 +mu: 0.6 w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 1 -hip_yaw_kp: 60 +w_hip_yaw: 2.5 +hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 @@ -52,19 +52,19 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 70] + 0, 0, 85] PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: [1, 0, 0, - 0, 0.1, 0, - 0, 0, 0] + 0, 2.5, 0, + 0, 0, 0.1] PelvisRotKp: [40, 0, 0, 0, 20, 0, - 0, 0, 0] + 0, 0, 1] PelvisRotKd: [7.5, 0, 0, 0, 2.5, 0, From 10727042ae84d55724372031ee7eba6c9e6d3713 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 10 Mar 2022 20:45:53 -0500 Subject: [PATCH 119/758] work in progress commit. --- bindings/pydairlib/BUILD.bazel | 1 + bindings/pydairlib/lcm/BUILD.bazel | 23 ++++++- bindings/pydairlib/lcm/__init__.py | 2 + bindings/pydairlib/systems/BUILD.bazel | 19 ++++++ bindings/pydairlib/systems/__init__.py | 4 ++ bindings/pydairlib/systems/primitives_py.cc | 2 +- .../pydairlib/systems/robot_lcm_systems_py.cc | 11 +++- examples/Cassie/multibody_sim.cc | 32 ++------- examples/trifinger/BUILD.bazel | 21 ++++++ multibody/multibody_utils.cc | 1 - systems/BUILD.bazel | 1 + systems/robot_lcm_systems.cc | 66 +++++++++++++++++++ systems/robot_lcm_systems.h | 16 +++++ 13 files changed, 167 insertions(+), 32 deletions(-) diff --git a/bindings/pydairlib/BUILD.bazel b/bindings/pydairlib/BUILD.bazel index aad0803165..ea52f6db6a 100644 --- a/bindings/pydairlib/BUILD.bazel +++ b/bindings/pydairlib/BUILD.bazel @@ -30,6 +30,7 @@ PY_LIBRARIES = [ "//bindings/pydairlib/common", "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index 77bc988ff5..a98bb27ba7 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -1,4 +1,4 @@ -# -*- python -*- + # -*- python -*- load("@drake//tools/install:install.bzl", "install") package(default_visibility = ["//visibility:public"]) @@ -11,6 +11,26 @@ load( "pybind_py_library", ) + +pybind_py_library( + name = "lcm_py", + cc_deps = [ + "//lcmtypes:lcmt_robot", + "@drake//bindings/pydrake/systems:lcm_pybind", + ], + cc_srcs = [ + "lcm_py.cc", + "lcm_py_bind_cpp_serializers.h", + "lcm_py_bind_cpp_serializers.cc", + ], + py_deps = [ + "@drake//bindings/pydrake", + "//lcmtypes:lcmtypes_robot_py", + ], + py_imports = ["."], +) + + pybind_py_library( name = "lcm_trajectory_py", cc_deps = [ @@ -65,6 +85,7 @@ PY_LIBRARIES = [ ":dircon_trajectory_plotter", ":lcm_trajectory_plotter", ":lcm_trajectory_py", + ":lcm_py", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/lcm/__init__.py b/bindings/pydairlib/lcm/__init__.py index e69de29bb2..718b93b986 100644 --- a/bindings/pydairlib/lcm/__init__.py +++ b/bindings/pydairlib/lcm/__init__.py @@ -0,0 +1,2 @@ +from .lcm_trajectory import * +from .lcm_py import * \ No newline at end of file diff --git a/bindings/pydairlib/systems/BUILD.bazel b/bindings/pydairlib/systems/BUILD.bazel index 30de587406..e36283d3c4 100644 --- a/bindings/pydairlib/systems/BUILD.bazel +++ b/bindings/pydairlib/systems/BUILD.bazel @@ -41,6 +41,24 @@ pybind_py_library( py_imports = ["."], ) + +pybind_py_library( + name = "framework_py", + cc_deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:lcm_driven_loop", + "@drake//:drake_shared_library", + ], + cc_so_name = "framework", + cc_srcs = ["framework_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + ":module_py", + ], + py_imports = ["."], +) + + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") @@ -59,6 +77,7 @@ py_library( PY_LIBRARIES = [ ":robot_lcm_systems_py", ":primitives_py", + ":framework_py", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/systems/__init__.py b/bindings/pydairlib/systems/__init__.py index e69de29bb2..27b8d70eb5 100644 --- a/bindings/pydairlib/systems/__init__.py +++ b/bindings/pydairlib/systems/__init__.py @@ -0,0 +1,4 @@ +# Importing everything in this directory to this package +from .robot_lcm_systems import * +from .primitives import * +from .framework import * \ No newline at end of file diff --git a/bindings/pydairlib/systems/primitives_py.cc b/bindings/pydairlib/systems/primitives_py.cc index ac0d8f2458..52e1752ff7 100644 --- a/bindings/pydairlib/systems/primitives_py.cc +++ b/bindings/pydairlib/systems/primitives_py.cc @@ -48,4 +48,4 @@ PYBIND11_MODULE(primitives, m) { } } // namespace pydairlib -} // namespace dairlib \ No newline at end of file +} // namespace dairlib diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 85bad8e44f..8f538725f6 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -26,7 +26,16 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotOutputSender") .def(py::init&, bool>()); + py::class_>( + m, "RobotCommandSender") + .def(py::init&>()); + m.def("AddActuatorAndStateLcm", + &dairlib::systems::AddActuatorAndStateLcm, py::arg("builder"), + py::arg("plant"), py::arg("lcm"), py::arg("actuator_channel"), + py::arg("state_channel"), py::arg("publish_rate"), + py::arg("publish_efforts"), py::arg("actuator_delay")); + } } // namespace pydairlib -} // namespace dairlib \ No newline at end of file +} // namespace dairlib diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 459bf7e07b..b1e2a2c912 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -24,7 +24,6 @@ #include "drake/systems/primitives/discrete_time_delay.h" namespace dairlib { -using dairlib::systems::SubvectorPassThrough; using drake::geometry::SceneGraph; using drake::multibody::ContactResultsToLcmSystem; using drake::multibody::MultibodyPlant; @@ -100,22 +99,10 @@ int do_main(int argc, char* argv[]) { // Create lcm systems. auto lcm = builder.AddSystem(); - auto input_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - FLAGS_channel_u, lcm)); - auto input_receiver = builder.AddSystem(plant); - auto passthrough = builder.AddSystem( - input_receiver->get_output_port(0).size(), 0, - plant.get_actuation_input_port().size()); - auto discrete_time_delay = - builder.AddSystem( - 1.0 / FLAGS_publish_rate, FLAGS_actuator_delay * FLAGS_publish_rate, - plant.num_actuators()); - auto state_pub = - builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); - auto state_sender = builder.AddSystem( - plant, FLAGS_publish_efforts); + + auto passthrough = systems::AddActuatorAndStateLcm( + &builder, plant, lcm, FLAGS_channel_u, "CASSIE_STATE_SIMULATION", + FLAGS_publish_rate, FLAGS_publish_efforts, FLAGS_actuator_delay); // Contact Information ContactResultsToLcmSystem& contact_viz = @@ -137,17 +124,6 @@ int do_main(int argc, char* argv[]) { "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); // connect leaf systems - builder.Connect(*input_sub, *input_receiver); - builder.Connect(*input_receiver, *passthrough); - builder.Connect(passthrough->get_output_port(), - discrete_time_delay->get_input_port()); - builder.Connect(discrete_time_delay->get_output_port(), - plant.get_actuation_input_port()); - builder.Connect(plant.get_state_output_port(), - state_sender->get_input_port_state()); - builder.Connect(discrete_time_delay->get_output_port(), - state_sender->get_input_port_effort()); - builder.Connect(*state_sender, *state_pub); builder.Connect( plant.get_geometry_poses_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); diff --git a/examples/trifinger/BUILD.bazel b/examples/trifinger/BUILD.bazel index ff4373d2ed..94bd735fc7 100644 --- a/examples/trifinger/BUILD.bazel +++ b/examples/trifinger/BUILD.bazel @@ -24,4 +24,25 @@ py_binary( "@drake//bindings/pydrake", ], data = [":trifinger_urdf"], +) + + +py_binary( + name = "simulate_trifinger_lcm", + srcs = ["simulate_trifinger_lcm.py"], + deps = [ + "//bindings/pydairlib", + "@drake//bindings/pydrake", + ], + data = [":trifinger_urdf"], +) + +py_binary( + name = "lcm_control_demo", + srcs = ["lcm_control_demo.py"], + deps = [ + "//bindings/pydairlib", + "@drake//bindings/pydrake", + ], + data = [":trifinger_urdf"], ) \ No newline at end of file diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 884f8c8054..825dd1c716 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -489,7 +489,6 @@ Eigen::MatrixXd JwrtqdotToJwrtv( return ret; } - template int QuaternionStartIndex(const MultibodyPlant& plant); // NOLINT template int QuaternionStartIndex(const MultibodyPlant& plant); // NOLINT template std::vector QuaternionStartIndices(const MultibodyPlant& plant); // NOLINT diff --git a/systems/BUILD.bazel b/systems/BUILD.bazel index 9d1b86ce29..bbc897c752 100644 --- a/systems/BUILD.bazel +++ b/systems/BUILD.bazel @@ -10,6 +10,7 @@ cc_library( "//lcmtypes:lcmt_robot", "//multibody:utils", "//systems/framework:vector", + "//systems/primitives", "@drake//:drake_shared_library", "@lcm", ], diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 8a6afd5ddb..779983c30e 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -2,12 +2,23 @@ #include "multibody/multibody_utils.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "drake/systems/primitives/discrete_time_delay.h" + +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" + namespace dairlib { namespace systems { using drake::multibody::JointActuatorIndex; using drake::multibody::JointIndex; +using drake::multibody::MultibodyPlant; using drake::systems::Context; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; using drake::systems::LeafSystem; using Eigen::VectorXd; using std::string; @@ -242,5 +253,60 @@ void RobotCommandSender::OutputCommand( } } } +SubvectorPassThrough* AddActuatorAndStateLcm( + drake::systems::DiagramBuilder* builder, + const MultibodyPlant& plant, + drake::systems::lcm::LcmInterfaceSystem* lcm, + std::string actuator_channel, + std::string state_channel, + double publish_rate, + bool publish_efforts, + double actuator_delay) { + + // Create LCM input for actuators + auto input_sub = + builder->AddSystem(LcmSubscriberSystem::Make( + actuator_channel, lcm)); + auto input_receiver = builder->AddSystem(plant); + auto passthrough = builder->AddSystem( + input_receiver->get_output_port(0).size(), 0, + plant.get_actuation_input_port().size()); + builder->Connect(*input_sub, *input_receiver); + builder->Connect(*input_receiver, *passthrough); + + // Create LCM output for state and efforts + auto state_pub = + builder->AddSystem(LcmPublisherSystem::Make( + state_channel, lcm, 1.0 / publish_rate)); + auto state_sender = builder->AddSystem( + plant, publish_efforts); + builder->Connect(plant.get_state_output_port(), + state_sender->get_input_port_state()); + + // Add delay, if used, and associated connections + if (actuator_delay > 0) { + auto discrete_time_delay = + builder->AddSystem( + 1.0 / publish_rate, actuator_delay * publish_rate, + plant.num_actuators()); + builder->Connect(*passthrough, *discrete_time_delay); + builder->Connect(discrete_time_delay->get_output_port(), + plant.get_actuation_input_port()); + + builder->Connect(discrete_time_delay->get_output_port(), + state_sender->get_input_port_effort()); + } else { + builder->Connect(passthrough->get_output_port(), + plant.get_actuation_input_port()); + builder->Connect(passthrough->get_output_port(), + state_sender->get_input_port_effort()); + } + + builder->Connect(*state_sender, *state_pub); + + return passthrough; +} + + } // namespace systems } // namespace dairlib diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index a5778ca3a5..4d8172aaff 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -8,9 +8,11 @@ #include "dairlib/lcmt_robot_output.hpp" #include "systems/framework/output_vector.h" #include "systems/framework/timestamped_vector.h" +#include "systems/primitives/subvector_pass_through.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/leaf_system.h" +#include "drake/systems/lcm/lcm_interface_system.h" namespace dairlib { namespace systems { @@ -112,5 +114,19 @@ class RobotCommandSender : public drake::systems::LeafSystem { std::map actuatorIndexMap_; }; + +/// Adds LCM +/// +/// +SubvectorPassThrough* AddActuatorAndStateLcm( + drake::systems::DiagramBuilder* builder, + const drake::multibody::MultibodyPlant& plant, + drake::systems::lcm::LcmInterfaceSystem* lcm, + std::string actuator_channel, + std::string state_channel, + double publish_rate, + bool publish_efforts = true, + double actuator_delay = 0); + } // namespace systems } // namespace dairlib From af742daf056f9879a5b3d1e4a9c8a3157d20e627 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 10 Mar 2022 20:52:35 -0500 Subject: [PATCH 120/758] Uncomitted code! --- bindings/pydairlib/lcm/lcm_py.cc | 23 +++ .../lcm/lcm_py_bind_cpp_serializers.cc | 31 ++++ .../lcm/lcm_py_bind_cpp_serializers.h | 26 ++++ bindings/pydairlib/systems/framework_py.cc | 32 +++++ examples/trifinger/lcm_control_demo.py | 133 ++++++++++++++++++ examples/trifinger/simulate_trifinger_lcm.py | 92 ++++++++++++ 6 files changed, 337 insertions(+) create mode 100644 bindings/pydairlib/lcm/lcm_py.cc create mode 100644 bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc create mode 100644 bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h create mode 100644 bindings/pydairlib/systems/framework_py.cc create mode 100644 examples/trifinger/lcm_control_demo.py create mode 100644 examples/trifinger/simulate_trifinger_lcm.py diff --git a/bindings/pydairlib/lcm/lcm_py.cc b/bindings/pydairlib/lcm/lcm_py.cc new file mode 100644 index 0000000000..bbd16d2302 --- /dev/null +++ b/bindings/pydairlib/lcm/lcm_py.cc @@ -0,0 +1,23 @@ +#include + +#include "bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h" +#include "pybind11/eval.h" +#include "pybind11/pybind11.h" + +#include "drake/bindings/pydrake/pydrake_pybind.h" + +namespace dairlib { +namespace pydairlib { + +using dairlib::pydairlib::BindCppSerializers; + +// pybind11 trampoline class to permit overriding virtual functions in +// Python. +PYBIND11_MODULE(lcm_py, m) { +// PYDRAKE_PREVENT_PYTHON3_MODULE_REIMPORT(m); + // Bind C++ serializers. + BindCppSerializers(); +} + +} // namespace pydrake +} // namespace drake \ No newline at end of file diff --git a/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc new file mode 100644 index 0000000000..f41936d54b --- /dev/null +++ b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc @@ -0,0 +1,31 @@ +#include "bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h" + +#include "dairlib/lcmt_cassie_out.hpp" +#include "dairlib/lcmt_contact.hpp" +#include "dairlib/lcmt_osc_output.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "dairlib/lcmt_osc_qp_output.hpp" +#include "dairlib/lcmt_osc_tracking_data.hpp" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_saved_traj.hpp" + +#include "drake/bindings/pydrake/systems/lcm_pybind.h" + +namespace dairlib { +namespace pydairlib { + +void BindCppSerializers() { + // N.B. At least one type should be bound to ensure the template is defined. + // N.B. These should be placed in the same order as the headers. + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); +} + +} // namespace pydairlib +} // namespace dairlib diff --git a/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h new file mode 100644 index 0000000000..5c537b32d9 --- /dev/null +++ b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h @@ -0,0 +1,26 @@ +#pragma once + +/** +@file +LCM types in C++ and Python are implemented differently, and thus cannot simply +be passed back and forth between the two languages. The simplest method to +communicate the structures is to expose the serialization of C++ `Value<>`s to +Python, so that Python can serialize and deserialize between C++ and Python +types. + +For more usages in Python, see the following in `_lcm_extra.py`: +- _make_lcm_subscriber / LcmSubscriberSystem.Make +- _make_lcm_publisher / LcmPublisherSystem.Make +*/ + +namespace dairlib { +namespace pydairlib { +//namespace pysystems { +//namespace pylcm { + +void BindCppSerializers(); + +//} // namespace pylcm +//} // namespace pysystems +} // namespace pydrake +} // namespace drake diff --git a/bindings/pydairlib/systems/framework_py.cc b/bindings/pydairlib/systems/framework_py.cc new file mode 100644 index 0000000000..a33c2d2c47 --- /dev/null +++ b/bindings/pydairlib/systems/framework_py.cc @@ -0,0 +1,32 @@ +#include +#include +#include +#include + +#include "systems/framework/lcm_driven_loop.h" + +#include "dairlib/lcmt_robot_output.hpp" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +using LcmOutputDrivenLoop = systems::LcmDrivenLoop; + +PYBIND11_MODULE(framework, m) { + +py::class_(m, "LcmOutputDrivenLoop") + .def(py::init>, + const drake::systems::LeafSystem*, + const std::string&, bool>(), py::arg("drake_lcm"), + py::arg("diagram"), py::arg("lcm_parser"), + py::arg("input_channel"), py::arg("is_forced_publish")) + .def("Simulate", &LcmOutputDrivenLoop::Simulate, + py::arg("end_time") = std::numeric_limits::infinity()); + +} + +} // namespace pydairlib +} // namespace dairlib diff --git a/examples/trifinger/lcm_control_demo.py b/examples/trifinger/lcm_control_demo.py new file mode 100644 index 0000000000..4447dfdc5e --- /dev/null +++ b/examples/trifinger/lcm_control_demo.py @@ -0,0 +1,133 @@ +from pydrake.all import (AbstractValue, DiagramBuilder, DrakeLcm, LeafSystem, MultibodyPlant, + Parser, RigidTransform, Subscriber, LcmPublisherSystem) +from dairlib import (lcmt_robot_output, lcmt_robot_input) + +import pydairlib.common +from pydairlib.systems import (RobotCommandSender, RobotOutputReceiver, LcmOutputDrivenLoop) + +import pydrake.systems.lcm as mut + + +# A demo controller system +class TrifingerDemoController(LeafSystem): + def __init__(self, plant): + LeafSystem.__init__(self) + + self.plant = plant + + # Input is state, output is torque (control action) + # Input port is realy a RobotOutputVector, which needs to be bound to Python + self.DeclareVectorInputPort("x, u, t", plant.num_positions() + + plant.num_velocities() + plant.num_actuators() + 4) + self.DeclareVectorOutputPort("u", plant.num_actuators()+1, self.CalcControl) + + def CalcControl(self, context, output): + x = self.EvalVectorInput(context, 0).get_value() + # q and v are [fingers; cube] + # cube position is [quat; xyz] and velocity [ang_vel; xyz] + q = x[0:self.plant.num_positions()] + v = x[self.plant.num_positions():self.plant.num_positions() + + self.plant.num_velocities()] + # u = -.03*np.ones(self.plant.num_actuators()) + + # use a simple PD controller with constant setpoint + kp = 10 + kd = 2 + q_des = np.array([.1, 0, -1, .1, -.5, -1, .1, -.5, -1]) + u = kp*(q_des - q[0:9]) - kd * v[0:9] + + # concatenate time to output (actually a TimestampedVector, which needs to + # be bound to Python) + output.SetFromVector(np.append(u, context.time())) + +lcm = DrakeLcm() + +plant = MultibodyPlant(0.0) + +# The package addition here seems necessary due to how the URDF is defined +parser = Parser(plant) +parser.package_map().Add("robot_properties_fingers", + "examples/trifinger/robot_properties_fingers") +parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( + "examples/trifinger/robot_properties_fingers/urdf/trifinger_minimal_collision.urdf")) +parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( + "examples/trifinger/robot_properties_fingers/cube/cube_v2.urdf")) + +# Fix the base of the finger to the world +X_WI = RigidTransform.Identity() +plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base_link"), X_WI) +plant.Finalize() + + +builder = DiagramBuilder() + +state_receiver = builder.AddSystem(RobotOutputReceiver(plant)) +controller = builder.AddSystem(TrifingerDemoController(plant)) +builder.Connect(state_receiver.get_output_port(0), controller.get_input_port(0)) + +control_sender = builder.AddSystem(RobotCommandSender(plant)) +builder.Connect(controller.get_output_port(), control_sender.get_input_port(0)) + +# control_serializer = +control_publisher = builder.AddSystem(LcmPublisherSystem.Make( + channel="TRIFINGER_INPUT", lcm_type=lcmt_robot_input, lcm=lcm, + publish_period=0.0, use_cpp_serializer=True)) +builder.Connect(control_sender.get_output_port(), + control_publisher.get_input_port()) + +diagram = builder.Build() + + + +context = diagram.CreateDefaultContext() +receiver_context = diagram.GetMutableSubsystemContext(state_receiver, context) + +loop = LcmOutputDrivenLoop(drake_lcm=lcm, diagram=diagram, + lcm_parser=state_receiver, + input_channel="TRIFINGER_OUTPUT", + is_forced_publish=True) + +loop.Simulate(100) + +# input_sub = Subscriber(lcm, "TRIFINGER_OUTPUT", lcmt_robot_output) + +# while True: +# lcm.HandleSubscriptions(0) +# if (input_sub.count > 0): +# print(input_sub.message) +# state_receiver.get_input_port(0).FixValue( +# receiver_context, AbstractValue.Make(input_sub.message)) +# input_sub.clear() + + + + +# from pydairlib.multibody import (addFlatTerrain, makeNameToPositionsMap) +# import pydairlib.common + +# # A demo controller system +# class TrifingerDemoController(LeafSystem): +# def __init__(self, plant): +# LeafSystem.__init__(self) + +# self.plant = plant + +# # Input is state, output is torque (control action) +# self.DeclareVectorInputPort("x", plant.num_positions() + +# plant.num_velocities()) +# self.DeclareVectorOutputPort("u", plant.num_actuators(), self.CalcControl) + +# def CalcControl(self, context, output): +# x = self.EvalVectorInput(context, 0).get_value() +# # q and v are [fingers; cube] +# # cube position is [quat; xyz] and velocity [ang_vel; xyz] +# q = x[0:self.plant.num_positions()] +# v = x[self.plant.num_positions():] +# # u = -.03*np.ones(self.plant.num_actuators()) + +# # use a simple PD controller with constant setpoint +# kp = 10 +# kd = 2 +# q_des = np.array([.1, 0, -1, .1, -.5, -1, .1, -.5, -1]) +# u = kp*(q_des - q[0:9]) - kd * v[0:9] +# output.SetFromVector(u) diff --git a/examples/trifinger/simulate_trifinger_lcm.py b/examples/trifinger/simulate_trifinger_lcm.py new file mode 100644 index 0000000000..4aa1e36e65 --- /dev/null +++ b/examples/trifinger/simulate_trifinger_lcm.py @@ -0,0 +1,92 @@ +from pydrake.all import * + +from pydairlib.multibody import (addFlatTerrain, makeNameToPositionsMap) +from pydairlib.systems import AddActuatorAndStateLcm +import pydairlib.common + +# Load the URDF and the cube +builder = DiagramBuilder() +sim_dt = 2e-4 +output_dt = 1e-3 + +plant, scene_graph = AddMultibodyPlantSceneGraph(builder, sim_dt) +addFlatTerrain(plant=plant, scene_graph=scene_graph, mu_static=1.0, + mu_kinetic=1.0) + +# The package addition here seems necessary due to how the URDF is defined +parser = Parser(plant) +parser.package_map().Add("robot_properties_fingers", + "examples/trifinger/robot_properties_fingers") +parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( + "examples/trifinger/robot_properties_fingers/urdf/trifinger_minimal_collision.urdf")) +parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( + "examples/trifinger/robot_properties_fingers/cube/cube_v2.urdf")) + +# Fix the base of the finger to the world +X_WI = RigidTransform.Identity() +plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base_link"), X_WI) +plant.Finalize() + +drake_lcm = DrakeLcm() +lcm = builder.AddSystem(LcmInterfaceSystem(drake_lcm)); + + +passthrough = AddActuatorAndStateLcm(builder=builder, plant=plant, lcm=lcm, + actuator_channel="TRIFINGER_INPUT", + state_channel="TRIFINGER_OUTPUT", + publish_rate=1/output_dt, + publish_efforts=True, + actuator_delay=0.0) +# Constuct the simulator and visualizer +DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) + +# Data logging [x;u] +nq = plant.num_positions() +nv = plant.num_velocities() +nu = plant.num_actuators() +logger = builder.AddSystem(VectorLogSink(nq + nv + nu, output_dt)) + +# Multiplex state and input for logger +mux = builder.AddSystem(Multiplexer([nq + nv, nu])) + +builder.Connect(plant.get_state_output_port(), mux.get_input_port(0)) +builder.Connect(passthrough.get_output_port(), mux.get_input_port(1)) +builder.Connect(mux.get_output_port(0), logger.get_input_port(0)) + + +diagram = builder.Build() + +simulator = Simulator(diagram) +simulator.Initialize() + +# Change the real-time rate to above 1 to simulate faster +simulator.set_target_realtime_rate(1) + +plant_context = diagram.GetMutableSubsystemContext( + plant, simulator.get_mutable_context()) + +# Set the initial state +q = np.zeros(nq) +q_map = makeNameToPositionsMap(plant) +q[q_map['finger_base_to_upper_joint_0']] = 0 +q[q_map['finger_upper_to_middle_joint_0']] = -1 +q[q_map['finger_middle_to_lower_joint_0']] = -1.5 +q[q_map['finger_base_to_upper_joint_0']] = 0 +q[q_map['finger_upper_to_middle_joint_120']] = -1 +q[q_map['finger_middle_to_lower_joint_120']] = -1.5 +q[q_map['finger_base_to_upper_joint_240']] = 0 +q[q_map['finger_upper_to_middle_joint_240']] = -1 +q[q_map['finger_middle_to_lower_joint_240']] = -1.5 +q[q_map['base_qw']] = 1 +q[q_map['base_qx']] = 0 +q[q_map['base_qz']] = 0 +q[q_map['base_x']] = 0 +q[q_map['base_y']] = 0 +q[q_map['base_z']] = .05 +plant.SetPositions(plant_context, q) + +# Simulate for 3 seconds +simulator.AdvanceTo(3) + +# numpy array of data (nq+nv+nu) x n_time +data = logger.FindLog(simulator.get_context()).data() From a5ce03fbf53f4d5cbd06fafe4e833668f059baa1 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 10 Mar 2022 22:35:49 -0500 Subject: [PATCH 121/758] Add basic bindings for TimestampedVector and OutputVector --- bindings/pydairlib/systems/BUILD.bazel | 1 + bindings/pydairlib/systems/framework_py.cc | 25 ++++++++++++++++++++++ 2 files changed, 26 insertions(+) diff --git a/bindings/pydairlib/systems/BUILD.bazel b/bindings/pydairlib/systems/BUILD.bazel index e36283d3c4..a3b3df2840 100644 --- a/bindings/pydairlib/systems/BUILD.bazel +++ b/bindings/pydairlib/systems/BUILD.bazel @@ -47,6 +47,7 @@ pybind_py_library( cc_deps = [ "//lcmtypes:lcmt_robot", "//systems/framework:lcm_driven_loop", + "//systems/framework:vector", "@drake//:drake_shared_library", ], cc_so_name = "framework", diff --git a/bindings/pydairlib/systems/framework_py.cc b/bindings/pydairlib/systems/framework_py.cc index a33c2d2c47..cbb5c45ddc 100644 --- a/bindings/pydairlib/systems/framework_py.cc +++ b/bindings/pydairlib/systems/framework_py.cc @@ -4,6 +4,8 @@ #include #include "systems/framework/lcm_driven_loop.h" +#include "systems/framework/output_vector.h" +#include "systems/framework/timestamped_vector.h" #include "dairlib/lcmt_robot_output.hpp" @@ -26,6 +28,29 @@ py::class_(m, "LcmOutputDrivenLoop") .def("Simulate", &LcmOutputDrivenLoop::Simulate, py::arg("end_time") = std::numeric_limits::infinity()); +py::class_, + drake::systems::BasicVector>(m, "TimestampedVector") + .def(py::init(), py::arg("data_size")) + .def("set_timestamp", &systems::TimestampedVector::set_timestamp, + py::arg("timestamp")) + .def("get_timestamp", &systems::TimestampedVector::get_timestamp) + .def("get_data", &systems::TimestampedVector::get_data) + .def("SetDataVector", &systems::TimestampedVector::SetDataVector, + py::arg("value")); + +py::class_, + drake::systems::BasicVector>(m, "OutputVector") + .def(py::init(), py::arg("num_positions"), + py::arg("num_velocities"), py::arg("num_efforts")) + .def("SetPositions", &systems::OutputVector::SetPositions, + py::arg("positions")) + .def("SetVelocities", &systems::OutputVector::SetVelocities, + py::arg("velocities")) + .def("SetState", &systems::OutputVector::SetState, + py::arg("state")) + .def("GetPositions", &systems::OutputVector::GetPositions) + .def("GetVelocities", &systems::OutputVector::GetVelocities) + .def("GetState", &systems::OutputVector::GetState); } } // namespace pydairlib From be781ea50d194ef7c219af5dbb5a764e40d9a31b Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 10 Mar 2022 22:37:21 -0500 Subject: [PATCH 122/758] Cleanup --- systems/framework/timestamped_vector.h | 2 +- systems/robot_lcm_systems.cc | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/systems/framework/timestamped_vector.h b/systems/framework/timestamped_vector.h index d47fe554b4..ef93cec31b 100644 --- a/systems/framework/timestamped_vector.h +++ b/systems/framework/timestamped_vector.h @@ -27,7 +27,7 @@ class TimestampedVector : public drake::systems::BasicVector { : BasicVector(data_size + 1), timestep_index_(data_size) {} /// Constructs a TimestampedVector with the specified @p data. - explicit TimestampedVector(const VectorX& data) + explicit TimestampedVector(const VectorX& data) : TimestampedVector(data.size()) { VectorX data_timestamped = VectorX(data.size() + 1); data_timestamped.head(data.size()) = data; diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 779983c30e..2e47e0fed5 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -250,7 +250,8 @@ void RobotCommandSender::OutputCommand( } else{ input_msg->efforts[i] = command->GetAtIndex(i); - } } + } + } } SubvectorPassThrough* AddActuatorAndStateLcm( From 93bbf889e7ed26081d1d5ce044e4bf3462571a58 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 10 Mar 2022 23:13:53 -0500 Subject: [PATCH 123/758] Testing lcm driven simulation --- examples/trifinger/lcm_control_demo.py | 91 ++++++-------------- examples/trifinger/simulate_trifinger_lcm.py | 12 ++- systems/framework/lcm_driven_loop.h | 8 +- 3 files changed, 37 insertions(+), 74 deletions(-) diff --git a/examples/trifinger/lcm_control_demo.py b/examples/trifinger/lcm_control_demo.py index 4447dfdc5e..4c688f8511 100644 --- a/examples/trifinger/lcm_control_demo.py +++ b/examples/trifinger/lcm_control_demo.py @@ -1,12 +1,16 @@ -from pydrake.all import (AbstractValue, DiagramBuilder, DrakeLcm, LeafSystem, MultibodyPlant, - Parser, RigidTransform, Subscriber, LcmPublisherSystem) from dairlib import (lcmt_robot_output, lcmt_robot_input) import pydairlib.common -from pydairlib.systems import (RobotCommandSender, RobotOutputReceiver, LcmOutputDrivenLoop) +import pydairlib.lcm +from pydairlib.systems import (RobotCommandSender, RobotOutputReceiver, + LcmOutputDrivenLoop, OutputVector, + TimestampedVector) -import pydrake.systems.lcm as mut +from pydrake.all import (AbstractValue, DiagramBuilder, DrakeLcm, LeafSystem, + MultibodyPlant, Parser, RigidTransform, Subscriber, + LcmPublisherSystem, TriggerType) +import numpy as np # A demo controller system class TrifingerDemoController(LeafSystem): @@ -16,29 +20,30 @@ def __init__(self, plant): self.plant = plant # Input is state, output is torque (control action) - # Input port is realy a RobotOutputVector, which needs to be bound to Python - self.DeclareVectorInputPort("x, u, t", plant.num_positions() + - plant.num_velocities() + plant.num_actuators() + 4) - self.DeclareVectorOutputPort("u", plant.num_actuators()+1, self.CalcControl) + self.DeclareVectorInputPort("x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + self.DeclareVectorOutputPort("u", TimestampedVector(plant.num_actuators()), + self.CalcControl) def CalcControl(self, context, output): - x = self.EvalVectorInput(context, 0).get_value() + q = self.EvalVectorInput(context, 0).GetPositions() + v = self.EvalVectorInput(context, 0).GetVelocities() # q and v are [fingers; cube] # cube position is [quat; xyz] and velocity [ang_vel; xyz] - q = x[0:self.plant.num_positions()] - v = x[self.plant.num_positions():self.plant.num_positions() + - self.plant.num_velocities()] + # q = x[0:self.plant.num_positions()] + # v = x[self.plant.num_positions():self.plant.num_positions() + + # self.plant.num_velocities()] # u = -.03*np.ones(self.plant.num_actuators()) # use a simple PD controller with constant setpoint - kp = 10 - kd = 2 + kp = 8 + kd = 1 q_des = np.array([.1, 0, -1, .1, -.5, -1, .1, -.5, -1]) u = kp*(q_des - q[0:9]) - kd * v[0:9] - # concatenate time to output (actually a TimestampedVector, which needs to - # be bound to Python) - output.SetFromVector(np.append(u, context.time())) + output.SetDataVector(u) + output.set_timestamp(context.get_time()) lcm = DrakeLcm() @@ -58,7 +63,6 @@ def CalcControl(self, context, output): plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base_link"), X_WI) plant.Finalize() - builder = DiagramBuilder() state_receiver = builder.AddSystem(RobotOutputReceiver(plant)) @@ -68,17 +72,15 @@ def CalcControl(self, context, output): control_sender = builder.AddSystem(RobotCommandSender(plant)) builder.Connect(controller.get_output_port(), control_sender.get_input_port(0)) -# control_serializer = -control_publisher = builder.AddSystem(LcmPublisherSystem.Make( +control_publisher = builder.AddSystem(LcmPublisherSystem.MakeWithTriggers( channel="TRIFINGER_INPUT", lcm_type=lcmt_robot_input, lcm=lcm, + publish_triggers={TriggerType.kForced}, publish_period=0.0, use_cpp_serializer=True)) builder.Connect(control_sender.get_output_port(), control_publisher.get_input_port()) diagram = builder.Build() - - context = diagram.CreateDefaultContext() receiver_context = diagram.GetMutableSubsystemContext(state_receiver, context) @@ -87,47 +89,4 @@ def CalcControl(self, context, output): input_channel="TRIFINGER_OUTPUT", is_forced_publish=True) -loop.Simulate(100) - -# input_sub = Subscriber(lcm, "TRIFINGER_OUTPUT", lcmt_robot_output) - -# while True: -# lcm.HandleSubscriptions(0) -# if (input_sub.count > 0): -# print(input_sub.message) -# state_receiver.get_input_port(0).FixValue( -# receiver_context, AbstractValue.Make(input_sub.message)) -# input_sub.clear() - - - - -# from pydairlib.multibody import (addFlatTerrain, makeNameToPositionsMap) -# import pydairlib.common - -# # A demo controller system -# class TrifingerDemoController(LeafSystem): -# def __init__(self, plant): -# LeafSystem.__init__(self) - -# self.plant = plant - -# # Input is state, output is torque (control action) -# self.DeclareVectorInputPort("x", plant.num_positions() + -# plant.num_velocities()) -# self.DeclareVectorOutputPort("u", plant.num_actuators(), self.CalcControl) - -# def CalcControl(self, context, output): -# x = self.EvalVectorInput(context, 0).get_value() -# # q and v are [fingers; cube] -# # cube position is [quat; xyz] and velocity [ang_vel; xyz] -# q = x[0:self.plant.num_positions()] -# v = x[self.plant.num_positions():] -# # u = -.03*np.ones(self.plant.num_actuators()) - -# # use a simple PD controller with constant setpoint -# kp = 10 -# kd = 2 -# q_des = np.array([.1, 0, -1, .1, -.5, -1, .1, -.5, -1]) -# u = kp*(q_des - q[0:9]) - kd * v[0:9] -# output.SetFromVector(u) +loop.Simulate(10) diff --git a/examples/trifinger/simulate_trifinger_lcm.py b/examples/trifinger/simulate_trifinger_lcm.py index 4aa1e36e65..049d86fb66 100644 --- a/examples/trifinger/simulate_trifinger_lcm.py +++ b/examples/trifinger/simulate_trifinger_lcm.py @@ -6,8 +6,8 @@ # Load the URDF and the cube builder = DiagramBuilder() -sim_dt = 2e-4 -output_dt = 1e-3 +sim_dt = 1e-4 +output_dt = 5e-4 plant, scene_graph = AddMultibodyPlantSceneGraph(builder, sim_dt) addFlatTerrain(plant=plant, scene_graph=scene_graph, mu_static=1.0, @@ -57,6 +57,10 @@ diagram = builder.Build() simulator = Simulator(diagram) + +simulator.set_publish_every_time_step(False); +simulator.set_publish_at_initialization(False); + simulator.Initialize() # Change the real-time rate to above 1 to simulate faster @@ -85,8 +89,8 @@ q[q_map['base_z']] = .05 plant.SetPositions(plant_context, q) -# Simulate for 3 seconds -simulator.AdvanceTo(3) +# Simulate for 10 seconds +simulator.AdvanceTo(10) # numpy array of data (nq+nv+nu) x n_time data = logger.FindLog(simulator.get_context()).data() diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index 37c2e7a779..534b5d4f03 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -99,6 +99,7 @@ class LcmDrivenLoop { diagram_ptr_ = diagram.get(); simulator_ = std::make_unique>(std::move(diagram)); + simulator_->set_publish_at_initialization(false); // Create subscriber for the switch (in the case of multi-input) DRAKE_DEMAND(!input_channels.empty()); @@ -154,9 +155,9 @@ class LcmDrivenLoop { auto& diagram_context = simulator_->get_mutable_context(); // Wait for the first message. - drake::log()->info("Waiting for first lcm input message"); + drake::log()->info("Waiting for two lcm input messages"); LcmHandleSubscriptionsUntil(drake_lcm_, [&]() { - return name_to_input_sub_map_.at(active_channel_).count() > 0; + return name_to_input_sub_map_.at(active_channel_).count() > 1; }); // Initialize the context time. @@ -165,7 +166,7 @@ class LcmDrivenLoop { diagram_context.SetTime(t0); // "Simulator" time - double time = 0; // initialize the current time with 0 + double time = t0; // initialize the current time with 0 // Variable needed for the driven loop std::string previous_active_channel_name = active_channel_; @@ -231,7 +232,6 @@ class LcmDrivenLoop { simulator_->get_mutable_context().SetTime(time); simulator_->Initialize(); } - simulator_->AdvanceTo(time); if (is_forced_publish_) { // Force-publish via the diagram From add83548ed5556e40ad8cb3448bb45e7e2972560 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 10 Mar 2022 23:17:41 -0500 Subject: [PATCH 124/758] Cleanup --- examples/trifinger/lcm_control_demo.py | 6 ------ systems/framework/lcm_driven_loop.h | 2 +- 2 files changed, 1 insertion(+), 7 deletions(-) diff --git a/examples/trifinger/lcm_control_demo.py b/examples/trifinger/lcm_control_demo.py index 4c688f8511..f7f571b800 100644 --- a/examples/trifinger/lcm_control_demo.py +++ b/examples/trifinger/lcm_control_demo.py @@ -29,12 +29,6 @@ def __init__(self, plant): def CalcControl(self, context, output): q = self.EvalVectorInput(context, 0).GetPositions() v = self.EvalVectorInput(context, 0).GetVelocities() - # q and v are [fingers; cube] - # cube position is [quat; xyz] and velocity [ang_vel; xyz] - # q = x[0:self.plant.num_positions()] - # v = x[self.plant.num_positions():self.plant.num_positions() + - # self.plant.num_velocities()] - # u = -.03*np.ones(self.plant.num_actuators()) # use a simple PD controller with constant setpoint kp = 8 diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index 534b5d4f03..b958f3ddb2 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -166,7 +166,7 @@ class LcmDrivenLoop { diagram_context.SetTime(t0); // "Simulator" time - double time = t0; // initialize the current time with 0 + double time = 0; // initialize the current time with 0 // Variable needed for the driven loop std::string previous_active_channel_name = active_channel_; From a1c0ede44af88f5e1bf0f9b7def735e2beac1972 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Fri, 11 Mar 2022 16:28:41 -0500 Subject: [PATCH 125/758] Peer review. --- .../pydairlib/systems/robot_lcm_systems_py.cc | 11 ++++++----- examples/Cassie/multibody_sim.cc | 2 +- examples/trifinger/lcm_control_demo.py | 2 +- examples/trifinger/simulate_trifinger_lcm.py | 15 ++++++--------- systems/framework/lcm_driven_loop.h | 4 ++-- systems/robot_lcm_systems.cc | 2 +- systems/robot_lcm_systems.h | 2 +- 7 files changed, 18 insertions(+), 20 deletions(-) diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 8f538725f6..ec9a40e0db 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -29,11 +29,12 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotCommandSender") .def(py::init&>()); - m.def("AddActuatorAndStateLcm", - &dairlib::systems::AddActuatorAndStateLcm, py::arg("builder"), - py::arg("plant"), py::arg("lcm"), py::arg("actuator_channel"), - py::arg("state_channel"), py::arg("publish_rate"), - py::arg("publish_efforts"), py::arg("actuator_delay")); + m.def("AddActuationRecieverAndStateSenderLcm", + &dairlib::systems::AddActuationRecieverAndStateSenderLcm, + py::arg("builder"), py::arg("plant"), py::arg("lcm"), + py::arg("actuator_channel"), py::arg("state_channel"), + py::arg("publish_rate"), py::arg("publish_efforts"), + py::arg("actuator_delay")); } diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index b1e2a2c912..c6a06c4ca4 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -100,7 +100,7 @@ int do_main(int argc, char* argv[]) { // Create lcm systems. auto lcm = builder.AddSystem(); - auto passthrough = systems::AddActuatorAndStateLcm( + auto passthrough = systems::AddActuationRecieverAndStateSenderLcm( &builder, plant, lcm, FLAGS_channel_u, "CASSIE_STATE_SIMULATION", FLAGS_publish_rate, FLAGS_publish_efforts, FLAGS_actuator_delay); diff --git a/examples/trifinger/lcm_control_demo.py b/examples/trifinger/lcm_control_demo.py index f7f571b800..6564c38c9f 100644 --- a/examples/trifinger/lcm_control_demo.py +++ b/examples/trifinger/lcm_control_demo.py @@ -66,7 +66,7 @@ def CalcControl(self, context, output): control_sender = builder.AddSystem(RobotCommandSender(plant)) builder.Connect(controller.get_output_port(), control_sender.get_input_port(0)) -control_publisher = builder.AddSystem(LcmPublisherSystem.MakeWithTriggers( +control_publisher = builder.AddSystem(LcmPublisherSystem.Make( channel="TRIFINGER_INPUT", lcm_type=lcmt_robot_input, lcm=lcm, publish_triggers={TriggerType.kForced}, publish_period=0.0, use_cpp_serializer=True)) diff --git a/examples/trifinger/simulate_trifinger_lcm.py b/examples/trifinger/simulate_trifinger_lcm.py index 049d86fb66..e3f6f7329d 100644 --- a/examples/trifinger/simulate_trifinger_lcm.py +++ b/examples/trifinger/simulate_trifinger_lcm.py @@ -1,7 +1,7 @@ from pydrake.all import * from pydairlib.multibody import (addFlatTerrain, makeNameToPositionsMap) -from pydairlib.systems import AddActuatorAndStateLcm +from pydairlib.systems import AddActuationRecieverAndStateSenderLcm import pydairlib.common # Load the URDF and the cube @@ -31,12 +31,10 @@ lcm = builder.AddSystem(LcmInterfaceSystem(drake_lcm)); -passthrough = AddActuatorAndStateLcm(builder=builder, plant=plant, lcm=lcm, - actuator_channel="TRIFINGER_INPUT", - state_channel="TRIFINGER_OUTPUT", - publish_rate=1/output_dt, - publish_efforts=True, - actuator_delay=0.0) +passthrough = AddActuationRecieverAndStateSenderLcm( + builder=builder, plant=plant, lcm=lcm, actuator_channel="TRIFINGER_INPUT", + state_channel="TRIFINGER_OUTPUT", publish_rate=1/output_dt, + publish_efforts=True, actuator_delay=0.0) # Constuct the simulator and visualizer DrakeVisualizer.AddToBuilder(builder=builder, scene_graph=scene_graph) @@ -61,8 +59,6 @@ simulator.set_publish_every_time_step(False); simulator.set_publish_at_initialization(False); -simulator.Initialize() - # Change the real-time rate to above 1 to simulate faster simulator.set_target_realtime_rate(1) @@ -89,6 +85,7 @@ q[q_map['base_z']] = .05 plant.SetPositions(plant_context, q) +simulator.Initialize() # Simulate for 10 seconds simulator.AdvanceTo(10) diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index b958f3ddb2..123e22c4b0 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -155,9 +155,9 @@ class LcmDrivenLoop { auto& diagram_context = simulator_->get_mutable_context(); // Wait for the first message. - drake::log()->info("Waiting for two lcm input messages"); + drake::log()->info("Waiting for the first lcm input messages"); LcmHandleSubscriptionsUntil(drake_lcm_, [&]() { - return name_to_input_sub_map_.at(active_channel_).count() > 1; + return name_to_input_sub_map_.at(active_channel_).count() > 0; }); // Initialize the context time. diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 2e47e0fed5..b0c79e4ad9 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -254,7 +254,7 @@ void RobotCommandSender::OutputCommand( } } -SubvectorPassThrough* AddActuatorAndStateLcm( +SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const MultibodyPlant& plant, drake::systems::lcm::LcmInterfaceSystem* lcm, diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 4d8172aaff..53a34bec22 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -118,7 +118,7 @@ class RobotCommandSender : public drake::systems::LeafSystem { /// Adds LCM /// /// -SubvectorPassThrough* AddActuatorAndStateLcm( +SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const drake::multibody::MultibodyPlant& plant, drake::systems::lcm::LcmInterfaceSystem* lcm, From 3cccb81c12afb08550650dad4fffa2b58d6533c2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 11 Mar 2022 16:51:05 -0500 Subject: [PATCH 126/758] controller bindings are actually relatively simple to write --- bindings/pydairlib/analysis/BUILD.bazel | 2 +- bindings/pydairlib/cassie/BUILD.bazel | 63 ++- bindings/pydairlib/cassie/cassie_actor.py | 26 + bindings/pydairlib/cassie/cassie_gym.py | 98 ++++ bindings/pydairlib/cassie/cassie_gym_test.py | 17 + .../cassie/cassie_running_controller.py | 81 +++ bindings/pydairlib/cassie/cassie_traj.py | 79 +++ bindings/pydairlib/cassie/controllers_py.cc | 40 ++ .../pydairlib/cassie/input_supervisor_py.cc | 39 ++ bindings/pydairlib/lcm/lcm_trajectory_py.cc | 4 +- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/diagrams/BUILD.bazel | 63 +++ .../Cassie/diagrams/cassie_sim_diagram.cc | 5 + examples/Cassie/diagrams/cassie_sim_diagram.h | 52 ++ .../osc_running_controller_diagram.cc | 523 ++++++++++++++++++ .../diagrams/osc_running_controller_diagram.h | 56 ++ examples/Cassie/input_supervisor.h | 1 - examples/Cassie/multibody_sim.cc | 21 +- examples/Cassie/run_osc_running_controller.cc | 9 +- examples/Cassie/test/input_supervisor_test.cc | 17 +- 20 files changed, 1167 insertions(+), 30 deletions(-) create mode 100644 bindings/pydairlib/cassie/cassie_actor.py create mode 100644 bindings/pydairlib/cassie/cassie_gym.py create mode 100644 bindings/pydairlib/cassie/cassie_gym_test.py create mode 100644 bindings/pydairlib/cassie/cassie_running_controller.py create mode 100644 bindings/pydairlib/cassie/cassie_traj.py create mode 100644 bindings/pydairlib/cassie/controllers_py.cc create mode 100644 bindings/pydairlib/cassie/input_supervisor_py.cc create mode 100644 examples/Cassie/diagrams/BUILD.bazel create mode 100644 examples/Cassie/diagrams/cassie_sim_diagram.cc create mode 100644 examples/Cassie/diagrams/cassie_sim_diagram.h create mode 100644 examples/Cassie/diagrams/osc_running_controller_diagram.cc create mode 100644 examples/Cassie/diagrams/osc_running_controller_diagram.h diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 4eb70bbd1f..67833800c1 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -69,7 +69,7 @@ py_library( "@lcm//:lcm-python", ], deps = [ - "//bindings/pydairlib/cassie:cassie_utils", + "//bindings/pydairlib/cassie:cassie", "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index 6a3fe96e38..ecc89a5db7 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -11,6 +11,34 @@ load( "pybind_py_library", ) +py_library( + name = "cassie_gym", + srcs = ["cassie_gym.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie", + "//bindings/pydairlib/common", + "//bindings/pydairlib/systems:systems", + "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems:primitives_py", + ], +) + +py_binary( + name = "cassie_gym_test", + srcs = ["cassie_gym_test.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie_gym", + "//bindings/pydairlib/cassie:cassie", + ], +) + +py_library( + name = "cassie_traj", + srcs = ["cassie_traj.py"], + deps = [ + ], +) + pybind_py_library( name = "cassie_utils_py", cc_deps = [ @@ -27,6 +55,36 @@ pybind_py_library( py_imports = ["."], ) +#pybind_py_library( +# name = "input_supervisor_py", +# cc_deps = [ +# "//examples/Cassie:input_supervisor", +# "@drake//:drake_shared_library", +# ], +# cc_so_name = "input_supervisor", +# cc_srcs = ["input_supervisor_py.cc"], +# py_deps = [ +# "@drake//bindings/pydrake", +# ":module_py", +# ], +# py_imports = ["."], +#) + +pybind_py_library( + name = "controllers_py", + cc_deps = [ + "@drake//:drake_shared_library", + "//examples/Cassie/diagrams:osc_running_controller_diagram", + ], + cc_so_name = "controllers", + cc_srcs = ["controllers_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + ":module_py", + ], + py_imports = ["."], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") @@ -44,11 +102,12 @@ py_library( PY_LIBRARIES = [ ":cassie_utils_py", + ":controllers_py", ] # Package roll-up (for Bazel dependencies). py_library( - name = "cassie_utils", + name = "cassie", imports = PACKAGE_INFO.py_imports, deps = PY_LIBRARIES, -) +) \ No newline at end of file diff --git a/bindings/pydairlib/cassie/cassie_actor.py b/bindings/pydairlib/cassie/cassie_actor.py new file mode 100644 index 0000000000..45c87e0d12 --- /dev/null +++ b/bindings/pydairlib/cassie/cassie_actor.py @@ -0,0 +1,26 @@ +import numpy as np +from cassie.cassie_traj import * + +from pydrake.multibody.parsing import Parser +from pydrake.systems.framework import DiagramBuilder +from pydrake.multibody.plant import * +from pydrake.systems.analysis import Simulator + +from pydairlib.common import FindResourceOrThrow +from pydairlib.cassie.cassie_utils import * +from pydairlib.multibody import * +from pydairlib.systems.primitives import * + + +class CassieActor(): + def __init__(self): + pass + + def make(self): + pass + + def reset(self): + pass + + def eval(self, action=np.zeros(10)): + pass diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py new file mode 100644 index 0000000000..0f2a79fd06 --- /dev/null +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -0,0 +1,98 @@ +import numpy as np +from cassie_traj import * + +from pydrake.multibody.parsing import Parser +from pydrake.systems.framework import DiagramBuilder +from pydrake.multibody.plant import * +from pydrake.systems.analysis import Simulator + +from pydairlib.common import FindResourceOrThrow +from pydairlib.cassie.cassie_utils import * +from pydairlib.multibody import * +from pydairlib.systems.primitives import * +from pydairlib.systems.robot_lcm_systems import RobotOutputSender + +class CassieGym(): + def __init__(self, visualize=False): + self.sim_dt = 5e-5 + self.visualize = visualize + # hardware logs are 50ms long and start approximately 5ms before impact + # the simulator will check to make sure ground reaction forces are first detected within 3-7ms + self.start_time = 0.00 + self.current_time = 0.00 + self.end_time = 0.05 + self.traj = CassieTraj() + self.hardware_traj = None + self.action_dim = 10 + self.state_dim = 45 + self.x_init = np.array([1, 0, 0, 0, 0, 0, 1, + -0.0304885, 0, 0.466767, -1.15602, -0.037542, 1.45243, -0.0257992, -1.59913, + 0.0304885, 0, 0.466767, -1.15602, -0.0374859, 1.45244, -0.0259075, -1.59919, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) + self.default_contact_params = {"mu": 0.8, + "stiffness": 4e4, + "dissipation": 0.5} + self.controller = None + + def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): + self.builder = DiagramBuilder() + self.dt = 5e-4 + self.params = self.default_contact_params + + terrain_normal = np.array([0.0, 0.0, 1.0]) + self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, self.sim_dt) + addCassieMultibody(self.plant, self.scene_graph, True, urdf, True, True) + AddFlatTerrain(self.plant, self.scene_graph, self.params['mu'], self.params['mu'], terrain_normal, + self.params['stiffness'], self.params['dissipation']) + self.plant.Finalize() + self.state_sender = self.builder.AddSystem(RobotOutputSender(self.plant, False)) + self.builder.Connect(self.plant.get_state_output_port(), self.state_sender.get_input_port(0)) + self.builder.AddSystem(controller) + self.controller = controller + self.builder.Connect(self.controller.get_control_output_port(), self.plant.get_actuation_input_port()) + # self.builder.Connect(self.controller.get_control_output_port(), self.state_sender.get_input_port_effort()) + self.builder.Connect(self.state_sender.get_output_port(), self.controller.get_state_input_port()) + + self.diagram = self.builder.Build() + self.sim = Simulator(self.diagram) + + self.plant_context = self.diagram.GetMutableSubsystemContext(self.plant, self.sim.get_mutable_context()) + self.sim.get_mutable_context().SetTime(self.start_time) + self.reset() + + def reset(self): + self.traj = CassieTraj() + self.plant.SetPositionsAndVelocities(self.plant.GetMyMutableContextFromRoot( + self.sim.get_mutable_context()), self.x_init) + self.sim.get_mutable_context().SetTime(self.start_time) + self.traj.update(self.start_time, self.x_init, + np.zeros(self.action_dim)) + self.sim.Initialize() + self.current_time = self.start_time + return + + def advance_to(self, time): + while self.current_time < time: + self.step() + return self.traj + + def get_state(self): + return self.traj.get_positions()[-1] + + def step(self, action=np.zeros(10)): + next_timestep = self.sim.get_context().get_time() + self.dt + self.sim.AdvanceTo(next_timestep) + + cassie_state = self.plant.GetPositionsAndVelocities( + self.plant.GetMyMutableContextFromRoot( + self.sim.get_mutable_context())) + self.current_time = next_timestep + self.traj.update(next_timestep, cassie_state, action) + return cassie_state + + def get_traj(self): + return self.traj + + # Some simulators for Cassie require cleanup + def free_sim(self): + return diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py new file mode 100644 index 0000000000..aed0b07d48 --- /dev/null +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -0,0 +1,17 @@ +from cassie_gym import * +# from cassie_utils import * +from pydairlib.cassie.controllers import OSCRunningControllerFactory +# from controllers import OSCRunningControllerFactory + +def main(): + osc_gains = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' + controller = OSCRunningControllerFactory(osc_gains, osqp_settings) + gym_env = CassieGym(visualize=True) + gym_env.make(controller=controller) + + gym_env.advance_to(10) + import pdb; pdb.set_trace() + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/bindings/pydairlib/cassie/cassie_running_controller.py b/bindings/pydairlib/cassie/cassie_running_controller.py new file mode 100644 index 0000000000..2e2d71ff4e --- /dev/null +++ b/bindings/pydairlib/cassie/cassie_running_controller.py @@ -0,0 +1,81 @@ +import numpy as np +from cassie_actor import * + +from pydrake.multibody.parsing import Parser +from pydrake.systems.framework import DiagramBuilder +from pydrake.multibody.plant import * +from pydrake.systems.analysis import Simulator + +from pydairlib.common import FindResourceOrThrow +from pydairlib.cassie.cassie_utils import * +from pydairlib.multibody import * +from pydairlib.systems.primitives import * + + +class CassieRunningController(CassieActor): + def __init__(self, visualize=False): + self.sim_dt = 5e-5 + self.action_dim = 10 + self.state_dim = 45 + + def make(self, params): + self.builder = DiagramBuilder() + self.dt = 5e-4 + self.params = params + + terrain_normal = np.array([0.0, 0.0, 1.0]) + self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, self.sim_dt) + AddCassieMultibody(self.plant, self.scene_graph, True, urdf, True, True) + AddFlatTerrain(self.plant, self.scene_graph, params['mu'], params['mu'], terrain_normal, params['stiffness'], + params['dissipation']) + + self.plant.Finalize() + + self.builder.Connect(self.controller_inputs.get_command_output_port(), self.passthrough.get_input_port()) + self.builder.Connect(self.passthrough.get_output_port(), self.plant.get_actuation_input_port()) + self.diagram = self.builder.Build() + self.sim = Simulator(self.diagram) + + self.plant_context = self.diagram.GetMutableSubsystemContext(self.plant, self.sim.get_mutable_context()) + self.sim.get_mutable_context().SetTime(self.start_time) + self.reset() + + def reset(self): + self.traj = CassieTraj() + self.plant.SetPositionsAndVelocities(self.plant.GetMyMutableContextFromRoot( + self.sim.get_mutable_context()), self.x_init) + self.sim.get_mutable_context().SetTime(self.start_time) + self.traj.update(self.start_time, self.x_init, + np.zeros(self.action_dim)) + self.sim.Initialize() + self.current_time = self.start_time + return + + def advance_to(self, time): + while self.current_time < time: + self.step() + return self.traj + + def get_state(self): + return self.traj.get_positions()[-1] + + def step(self, action=np.zeros(10)): + next_timestep = self.sim.get_context().get_time() + self.dt + if self.controller: + action = self.controller.eval(self.get_state()) + self.plant.get_actuation_input_port().FixValue(self.plant_context, action) + self.sim.AdvanceTo(next_timestep) + + cassie_state = self.plant.GetPositionsAndVelocities( + self.plant.GetMyMutableContextFromRoot( + self.sim.get_mutable_context())) + self.current_time = next_timestep + self.traj.update(next_timestep, cassie_state, action) + return cassie_state + + def get_traj(self): + return self.traj + + # Some simulators for Cassie require cleanup + def free_sim(self): + return diff --git a/bindings/pydairlib/cassie/cassie_traj.py b/bindings/pydairlib/cassie/cassie_traj.py new file mode 100644 index 0000000000..8bedc23dee --- /dev/null +++ b/bindings/pydairlib/cassie/cassie_traj.py @@ -0,0 +1,79 @@ +import numpy as np +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R + +CASSIE_QUATERNION_SLICE = slice(0, 4) +CASSIE_POSITION_SLICE = slice(4, 23) +CASSIE_OMEGA_SLICE = slice(23, 26) +CASSIE_VELOCITY_SLICE = slice(26, 45) +CASSIE_JOINT_POSITION_SLICE = slice(7, 23) +CASSIE_JOINT_VELOCITY_SLICE = slice(29, 45) +CASSIE_FB_POSITION_SLICE = slice(4, 7) +CASSIE_FB_VELOCITY_SLICE = slice(26, 29) + +CASSIE_NX = 45 +CASSIE_NQ = 23 +CASSIE_NV = 22 +CASSIE_NU = 10 +CASSIE_NL = 12 + +# 10000 dts / 2000Hz = 5 seconds +CASSIE_EPS_LENGTH = 10000 + + +class CassieTraj(): + + def __init__(self): + self.t = np.zeros((CASSIE_EPS_LENGTH,)) + self.x_samples = np.zeros((CASSIE_EPS_LENGTH, CASSIE_NX)) # Cannot be empty + self.u_samples = np.zeros((CASSIE_EPS_LENGTH, CASSIE_NU)) # Cannot be empty + self.lambda_traj = np.zeros((CASSIE_EPS_LENGTH, CASSIE_NL)) # May be empty + + def time_to_index(self, t): + if int(t * 2000) >= self.u_samples.shape[0]: + print("time %.2f is out of bounds" % t) + return int(t * 2000) + + def get_positions(self): + return self.x_samples[:, CASSIE_POSITION_SLICE] + + def get_orientations(self): + return self.x_samples[:, CASSIE_QUATERNION_SLICE] + + def get_velocities(self): + return self.x_samples[:, CASSIE_VELOCITY_SLICE] + + def get_omegas(self): + return self.x_samples[:, CASSIE_OMEGA_SLICE] + + def plot_positions(self): + plt.plot(self.t, self.x_samples[:, CASSIE_POSITION_SLICE]) + + def plot_velocities(self): + plt.plot(self.t, self.x_samples[:, CASSIE_VELOCITY_SLICE]) + + def plot_efforts(self): + plt.plot(self.t, self.u_samples) + + def update(self, t, state, action): + index = self.time_to_index(t) + self.x_samples[index] = state + self.u_samples[index] = action + self.t[index] = t + +def quat_to_rotation(q): + return R.from_quat([q[1], q[2], q[3], q[0]]) + + +def reexpress_state_local_to_global_omega(state): + new_state = state.flatten() + rot = quat_to_rotation(new_state[CASSIE_QUATERNION_SLICE]) + new_state[CASSIE_OMEGA_SLICE] = rot.apply(new_state[CASSIE_OMEGA_SLICE]) + return new_state + + +def reexpress_state_global_to_local_omega(state): + new_state = state.flatten() + rot = quat_to_rotation(new_state[CASSIE_QUATERNION_SLICE]) + new_state[CASSIE_OMEGA_SLICE] = rot.apply(new_state[CASSIE_OMEGA_SLICE], inverse=True) + return new_state diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc new file mode 100644 index 0000000000..bcada0fc69 --- /dev/null +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -0,0 +1,40 @@ +#include +#include +#include +#include + +#include "examples/Cassie/diagrams/osc_running_controller_diagram.h" + +#include "drake/multibody/plant/multibody_plant.h" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +using examples::controllers::OSCRunningControllerDiagram; + +PYBIND11_MODULE(controllers, m) { + m.doc() = "Binding controller factories for Cassie"; + + using py_rvp = py::return_value_policy; + + py::class_>( + m, "OSCRunningControllerFactory") + .def(py::init(), + py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) + .def("get_state_input_port", + &OSCRunningControllerDiagram::get_state_input_port, + py_rvp::reference_internal) + .def("get_cassie_out_input_port", + &OSCRunningControllerDiagram::get_cassie_out_input_port, + py_rvp::reference_internal) + .def("get_control_output_port", + &OSCRunningControllerDiagram::get_control_output_port, + py_rvp::reference_internal) + .def("get_controller_failure_output_port", + &OSCRunningControllerDiagram::get_controller_failure_output_port, + py_rvp::reference_internal); +} +} // namespace pydairlib +} // namespace dairlib \ No newline at end of file diff --git a/bindings/pydairlib/cassie/input_supervisor_py.cc b/bindings/pydairlib/cassie/input_supervisor_py.cc new file mode 100644 index 0000000000..39012d7dcd --- /dev/null +++ b/bindings/pydairlib/cassie/input_supervisor_py.cc @@ -0,0 +1,39 @@ +#include +#include +#include +#include + +#include "examples/Cassie/input_supervisor.h" + +#include "drake/multibody/plant/multibody_plant.h" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +PYBIND11_MODULE(cassie_utils, m) { + m.doc() = "Binding utility functions for Cassie"; + + using drake::multibody::MultibodyPlant; + + py::class_(m, "InputSupervisor") + .def(py::init&, + const std::string&, double, double, Eigen::VectorXd&>()) + .def("get_input_port_command", &InputSupervisor::get_input_port_command) + .def("get_input_port_safety_controller", + &InputSupervisor::get_input_port_safety_controller) + .def("get_input_port_state", &InputSupervisor::get_input_port_state) + .def("get_input_port_controller_switch", + &InputSupervisor::get_input_port_controller_switch) + .def("get_input_port_cassie", &InputSupervisor::get_input_port_cassie) + .def("get_input_port_controller_error", + &InputSupervisor::get_input_port_controller_error) + .def("get_output_port_command", &InputSupervisor::get_output_port_command) + .def("get_output_port_status", &InputSupervisor::get_output_port_status) + .def("get_output_port_failure", + &InputSupervisor::get_output_port_failure); +} + +} // namespace pydairlib +} // namespace dairlib \ No newline at end of file diff --git a/bindings/pydairlib/lcm/lcm_trajectory_py.cc b/bindings/pydairlib/lcm/lcm_trajectory_py.cc index 47257cf938..088add2010 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_py.cc +++ b/bindings/pydairlib/lcm/lcm_trajectory_py.cc @@ -49,7 +49,9 @@ PYBIND11_MODULE(lcm_trajectory, m) { .def("GetTrajectory", &LcmTrajectory::GetTrajectory, py::arg("trajectory_name")); py::class_(m, "DirconTrajectory") - .def(py::init&, const std::string&>()) .def("WriteToFile", &LcmTrajectory::WriteToFile, + .def(py::init&, + const std::string&>()) + .def("WriteToFile", &LcmTrajectory::WriteToFile, py::arg("trajectory_name")) .def("GetMetadata", &LcmTrajectory::GetMetadata) .def("GetTrajectoryNames", &LcmTrajectory::GetTrajectoryNames) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 7ea8ab75d6..fd3e3158da 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -212,6 +212,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/controllers:geared_motor", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel new file mode 100644 index 0000000000..91d1d2e823 --- /dev/null +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -0,0 +1,63 @@ +load("@drake//tools/lint:lint.bzl", "add_lint_tests") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:drake_lcm.bzl", + "drake_lcm_cc_library", + "drake_lcm_java_library", + "drake_lcm_py_library", +) +load( + "@drake//tools/skylark:drake_py.bzl", + "drake_py_binary", + "drake_py_library", + "drake_py_unittest", +) +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +cc_library( + name = "osc_running_controller_diagram", + srcs = ["osc_running_controller_diagram.cc"], + hdrs = ["osc_running_controller_diagram.h"], + deps = [ + "//examples/impact_invariant_control:impact_aware_time_based_fsm", + "//examples/Cassie:cassie_urdf", + "//examples/Cassie:cassie_utils", + "//examples/Cassie/osc_run:osc_run", + "//examples/Cassie/osc:osc", + "//lcm:trajectory_saver", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/filters:floating_base_velocity_filter", + "//systems/controllers/osc:osc_tracking_datas", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "cassie_sim_diagram", + srcs = ["cassie_sim_diagram.cc"], + hdrs = ["cassie_sim_diagram.h"], + deps = [ + "//examples/Cassie:cassie_encoder", + "//examples/Cassie:cassie_fixed_point_solver", + "//examples/Cassie:cassie_urdf", + "//examples/Cassie:cassie_utils", + "//systems:robot_lcm_systems", + "//systems/controllers:geared_motor", + "//systems/primitives", + "//systems:system_utils", + "@drake//:drake_shared_library", + "@gflags", + ], +) diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc new file mode 100644 index 0000000000..78f9e32a4e --- /dev/null +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -0,0 +1,5 @@ +// +// Created by yangwill on 3/11/22. +// + +#include "cassie_sim_diagram.h" diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h new file mode 100644 index 0000000000..89c53e3414 --- /dev/null +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -0,0 +1,52 @@ +#pragma once + +#include +#include + +#include "drake/common/drake_copyable.h" +#include "drake/systems/framework/diagram.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/framework/system.h" + +namespace dairlib { +namespace examples { + +class CassieSimDiagram : public drake::systems::Diagram { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CassieSimDiagram) + + /// @param[in] osc_gains_filename filepath containing the osc_running_gains. + /// @param[in] osqp_settings filepath containing the osqp settings. + CassieSimDiagram(const std::string& osc_gains_filename, + const std::string& osqp_settings_filename); + + /// @return the input port for the actuation command. + const drake::systems::InputPort& get_actuation_input_port() const { + return this->get_input_port(actuation_input_port_index_); + } + + /// @return the input port for the radio struct. + const drake::systems::InputPort& get_radio_input_port() const { + return this->get_input_port(radio_input_port_index_); + } + + /// @return the output port for the plant state as an OutputVector. + const drake::systems::OutputPort& get_state_output_port() const { + return this->get_output_port(state_output_port_index_); + } + + /// @return the output port for the failure status of the controller. + const drake::systems::OutputPort& get_cassie_out_output_port_index() + const { + return this->get_output_port(cassie_out_output_port_index_); + } + + private: + const int actuation_input_port_index_ = 0; + const int radio_input_port_index_ = 1; + const int state_output_port_index_ = 0; + const int cassie_out_output_port_index_ = 1; +}; + +} // namespace examples +} // namespace dairlib diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc new file mode 100644 index 0000000000..2a87156304 --- /dev/null +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -0,0 +1,523 @@ +#include "osc_running_controller_diagram.h" + +#include + +#include +#include +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/osc/heading_traj_generator.h" +#include "examples/Cassie/osc/high_level_command.h" +#include "examples/Cassie/osc/swing_toe_traj_generator.h" +#include "examples/Cassie/osc_run/foot_traj_generator.h" +#include "examples/Cassie/osc_run/osc_running_gains.h" +#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" +#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" +#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" +#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" +#include "lcm/dircon_saved_trajectory.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/controller_failure_aggregator.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/filters/floating_base_velocity_filter.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" + +namespace dairlib { + +using std::map; +using std::pair; +using std::string; +using std::vector; + +using Eigen::Matrix3d; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using cassie::osc::SwingToeTrajGenerator; +using drake::geometry::SceneGraph; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using examples::osc::PelvisPitchTrajGenerator; +using examples::osc::PelvisRollTrajGenerator; +using examples::osc::PelvisTransTrajGenerator; +using examples::osc_run::FootTrajGenerator; +using multibody::FixedJointEvaluator; +using multibody::WorldYawViewFrame; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +namespace examples { +namespace controllers { + +OSCRunningControllerDiagram::OSCRunningControllerDiagram( + const string& osc_gains_filename, const string& osqp_settings_filename) { + // Build the controller diagram + DiagramBuilder builder; + + // Built the Cassie MBPs + drake::multibody::MultibodyPlant plant(0.0); + addCassieMultibody(&plant, nullptr, true, + "examples/Cassie/urdf/cassie_v2_conservative.urdf", + false /*spring model*/, false /*loop closure*/); + plant.Finalize(); + + auto plant_context = plant.CreateDefaultContext(); + + // Get contact frames and position + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); + + int nv = plant.num_velocities(); + + // Create maps for joints + map pos_map = multibody::makeNameToPositionsMap(plant); + map vel_map = multibody::makeNameToVelocitiesMap(plant); + map act_map = multibody::makeNameToActuatorsMap(plant); + + std::unordered_map< + int, std::vector&>>> + feet_contact_points; + feet_contact_points[0] = std::vector< + std::pair&>>( + {left_toe, left_heel}); + feet_contact_points[1] = std::vector< + std::pair&>>( + {right_toe, right_heel}); + + /**** Get trajectory from optimization ****/ + + /**** OSC Gains ****/ + drake::yaml::YamlReadArchive::Options yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_gains_filename), {}, {}, yaml_options); + OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_gains_filename)); + solvers::OSQPSettingsYaml osqp_settings = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(osqp_settings_filename)); + + /**** FSM and contact mode configuration ****/ + int left_stance_state = 0; + int right_stance_state = 1; + int right_touchdown_air_phase = 2; + int left_touchdown_air_phase = 3; + + vector fsm_states = {left_stance_state, right_touchdown_air_phase, + right_stance_state, left_touchdown_air_phase, + left_stance_state}; + + vector state_durations = { + osc_gains.stance_duration, osc_gains.flight_duration, + osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; + vector accumulated_state_durations; + accumulated_state_durations.push_back(0); + std::cout << accumulated_state_durations.back() << std::endl; + for (double state_duration : state_durations) { + accumulated_state_durations.push_back(accumulated_state_durations.back() + + state_duration); + std::cout << accumulated_state_durations.back() << std::endl; + } + accumulated_state_durations.pop_back(); + + auto fsm = builder.AddSystem( + plant, fsm_states, state_durations, 0.0, gains.impact_threshold); + + /**** Initialize all the leaf systems ****/ + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto state_receiver = builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), true, false); + auto failure_aggregator = + builder.AddSystem( + control_channel_name_, 1); + auto passthrough = builder.AddSystem( + osc->get_output_port(0).size(), 0, + plant.get_actuation_input_port().size()); + std::vector tau = {.05, .05, .01}; + auto ekf_filter = + builder.AddSystem(plant, tau); + + /**** OSC setup ****/ + // Cost + /// REGULARIZATION COSTS + osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); + // osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + // osc->SetLambdaContactRegularizationWeight(1e-4 * + // gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); + + // Soft constraint on contacts + osc->SetSoftConstraintWeight(gains.w_soft_constraint); + + // Contact information for OSC + osc->SetContactFriction(gains.mu); + + const auto& pelvis = plant.GetBodyByName("pelvis"); + multibody::WorldYawViewFrame view_frame(pelvis); + auto left_toe_evaluator = multibody::WorldPointEvaluator( + plant, left_toe.first, left_toe.second, view_frame, Matrix3d::Identity(), + Vector3d::Zero(), {1, 2}); + auto left_heel_evaluator = multibody::WorldPointEvaluator( + plant, left_heel.first, left_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + auto right_toe_evaluator = multibody::WorldPointEvaluator( + plant, right_toe.first, right_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); + auto right_heel_evaluator = multibody::WorldPointEvaluator( + plant, right_heel.first, right_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + + osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); + osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); + osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); + osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); + + multibody::KinematicEvaluatorSet evaluators(plant); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + + // Fix the springs in the dynamics + auto pos_idx_map = multibody::makeNameToPositionsMap(plant); + auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + + osc->AddKinematicConstraint(&evaluators); + + /**** Tracking Data *****/ + + std::cout << "Creating tracking data. " << std::endl; + + // auto cassie_out_receiver = + // builder.AddSystem(LcmSubscriberSystem::Make( + // FLAGS_channel_cassie_out, &lcm)); + cassie::osc::HighLevelCommand* high_level_command; + high_level_command = builder.AddSystem( + plant, plant_context.get(), osc_gains.vel_scale_rot, + osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); + + auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); + auto pelvis_trans_traj_generator = + builder.AddSystem( + plant, plant_context.get(), default_traj, feet_contact_points, + osc_gains.relative_pelvis); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + auto l_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, + 0, accumulated_state_durations); + auto r_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "toe_right", "pelvis", + osc_gains.relative_feet, 1, accumulated_state_durations); + l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + osc_gains.center_line_offset, + osc_gains.footstep_offset); + r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + osc_gains.center_line_offset, + osc_gains.footstep_offset); + + TransTaskSpaceTrackingData pelvis_tracking_data( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant); + TransTaskSpaceTrackingData stance_foot_tracking_data( + "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData left_foot_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_foot_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + pelvis_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); + pelvis_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); + stance_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + "toe_left"); + stance_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + "toe_right"); + left_foot_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "toe_left"); + right_foot_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "toe_right"); + + TransTaskSpaceTrackingData left_foot_yz_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_foot_yz_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_foot_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "toe_left"); + right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "toe_right"); + + TransTaskSpaceTrackingData left_hip_tracking_data( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_hip_tracking_data( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); + right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); + right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "pelvis"); + left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "pelvis"); + + TransTaskSpaceTrackingData left_hip_yz_tracking_data( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + TransTaskSpaceTrackingData right_hip_yz_tracking_data( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + "hip_left"); + right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + "hip_right"); + + RelativeTranslationTrackingData left_foot_rel_tracking_data( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, + &left_hip_tracking_data); + RelativeTranslationTrackingData right_foot_rel_tracking_data( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, + &right_hip_tracking_data); + RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( + "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); + RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( + "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); + RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, + &stance_foot_tracking_data); + left_foot_rel_tracking_data.SetViewFrame(view_frame); + right_foot_rel_tracking_data.SetViewFrame(view_frame); + left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); + right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); + pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); + + left_foot_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_rel_tracking_data.SetImpactInvariantProjection(true); + // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); + // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); + + osc->AddTrackingData(&pelvis_trans_rel_tracking_data); + osc->AddTrackingData(&left_foot_rel_tracking_data); + osc->AddTrackingData(&right_foot_rel_tracking_data); + osc->AddTrackingData(&left_foot_yz_rel_tracking_data); + osc->AddTrackingData(&right_foot_yz_rel_tracking_data); + + auto heading_traj_generator = + builder.AddSystem(plant, + plant_context.get()); + + RotTaskSpaceTrackingData pelvis_rot_tracking_data( + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot, plant, plant); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, + "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_touchdown_air_phase, + "pelvis"); + pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_touchdown_air_phase, + "pelvis"); + pelvis_rot_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&pelvis_rot_tracking_data); + + // Swing toe joint trajectory + vector&>> left_foot_points = { + left_heel, left_toe}; + vector&>> right_foot_points = { + right_heel, right_toe}; + auto left_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_left"], left_foot_points, + "left_toe_angle_traj"); + auto right_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_right"], right_foot_points, + "right_toe_angle_traj"); + + // Swing toe joint tracking + JointSpaceTrackingData left_toe_angle_tracking_data( + "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + JointSpaceTrackingData right_toe_angle_tracking_data( + "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + right_stance_state, "toe_left", "toe_leftdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "toe_left", "toe_leftdot"); + left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "toe_left", "toe_leftdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + left_stance_state, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_touchdown_air_phase, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data.AddStateAndJointToTrack( + left_touchdown_air_phase, "toe_right", "toe_rightdot"); + left_toe_angle_tracking_data.SetImpactInvariantProjection(true); + right_toe_angle_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(&left_toe_angle_tracking_data); + osc->AddTrackingData(&right_toe_angle_tracking_data); + + // Swing hip yaw joint tracking + JointSpaceTrackingData left_hip_yaw_tracking_data( + "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + JointSpaceTrackingData right_hip_yaw_tracking_data( + "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", + "hip_yaw_rightdot"); + // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); + osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + + // Build OSC problem + osc->Build(osqp_settings); + std::cout << "Built OSC" << std::endl; + + /*****Connect ports*****/ + + // OSC connections + builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_impact(), + osc->get_near_impact_input_port()); + builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); + builder.Connect(state_receiver->get_output_port(0), + ekf_filter->get_input_port()); + builder.Connect(ekf_filter->get_output_port(), + osc->get_robot_output_input_port()); + // FSM connections + builder.Connect(state_receiver->get_output_port(0), + fsm->get_input_port_state()); + + // Trajectory generator connections + builder.Connect(state_receiver->get_output_port(0), + pelvis_trans_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + pelvis_trans_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_clock(), + pelvis_trans_traj_generator->get_clock_input_port()); + builder.Connect(high_level_command->get_xy_output_port(), + l_foot_traj_generator->get_target_vel_input_port()); + builder.Connect(high_level_command->get_xy_output_port(), + r_foot_traj_generator->get_target_vel_input_port()); + builder.Connect(state_receiver->get_output_port(0), + l_foot_traj_generator->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + r_foot_traj_generator->get_state_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + l_foot_traj_generator->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_fsm(), + r_foot_traj_generator->get_fsm_input_port()); + builder.Connect(state_receiver->get_output_port(0), + left_toe_angle_traj_gen->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + right_toe_angle_traj_gen->get_state_input_port()); + // OSC connections + builder.Connect(pelvis_trans_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_trans_traj")); + builder.Connect(state_receiver->get_output_port(0), + heading_traj_generator->get_state_input_port()); + builder.Connect(high_level_command->get_yaw_output_port(), + heading_traj_generator->get_yaw_input_port()); + builder.Connect(heading_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_rot_traj")); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("left_ft_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("right_ft_traj")); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("left_ft_z_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("right_ft_z_traj")); + builder.Connect(left_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("left_toe_angle_traj")); + builder.Connect(right_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("right_toe_angle_traj")); + builder.Connect(osc->get_osc_output_port(), + passthrough->get_input_port()); + + // Publisher connections + builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); + builder.ExportInput(high_level_command->get_cassie_out_input_port(), + "lcmt_cassie_out"); + builder.ExportOutput(passthrough->get_output_port()); + builder.ExportOutput(failure_aggregator->get_status_output_port()); + + // Run lcm-driven simulation + // Create the diagram as itself + builder.BuildInto(this); + // owned_diagram->set_name(("osc_running_controller")); +} + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h new file mode 100644 index 0000000000..4fe3d85c3a --- /dev/null +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -0,0 +1,56 @@ +#pragma once + +#include +#include + +#include "drake/common/drake_copyable.h" +#include "drake/systems/framework/diagram.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/framework/system.h" + +namespace dairlib { +namespace examples { +namespace controllers { + +class OSCRunningControllerDiagram : public drake::systems::Diagram { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(OSCRunningControllerDiagram) + + /// @param[in] osc_gains_filename filepath containing the osc_running_gains. + /// @param[in] osqp_settings filepath containing the osqp settings. + OSCRunningControllerDiagram(const std::string& osc_gains_filename, + const std::string& osqp_settings_filename); + + /// @return the input port for the plant state. + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_input_port_index_); + } + + /// @return the input port for the cassie_out struct (containing radio commands). + const drake::systems::InputPort& get_cassie_out_input_port() const { + return this->get_input_port(cassie_out_input_port_index_); + } + + /// @return the output port for the controller torques. + const drake::systems::OutputPort& get_control_output_port() const { + return this->get_output_port(control_output_port_index_); + } + + /// @return the output port for the failure status of the controller. + const drake::systems::OutputPort& get_controller_failure_output_port() + const { + return this->get_output_port(controller_failure_port_index_); + } + + private: + const int state_input_port_index_ = 0; + const int cassie_out_input_port_index_ = 1; + const int control_output_port_index_ = 0; + const int controller_failure_port_index_ = 1; + + const std::string control_channel_name_ = "OSC_RUNNING"; +}; + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/Cassie/input_supervisor.h b/examples/Cassie/input_supervisor.h index 178b0af5d9..2d19415a06 100644 --- a/examples/Cassie/input_supervisor.h +++ b/examples/Cassie/input_supervisor.h @@ -110,7 +110,6 @@ class InputSupervisor : public drake::systems::LeafSystem { void CheckRadio(const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; - private: const drake::multibody::MultibodyPlant& plant_; const int num_actuators_; const int num_positions_; diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index bd02d6f401..c4d747d7a2 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -12,6 +12,7 @@ #include "systems/controllers/geared_motor.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_contact_results_for_viz.hpp" @@ -151,16 +152,10 @@ int do_main(int argc, char* argv[]) { // connect leaf systems builder.Connect(*input_sub, *input_receiver); - bool motor_model = true; - if (motor_model) { - builder.Connect(input_receiver->get_output_port(), - cassie_motor->get_input_port_command()); - builder.Connect(cassie_motor->get_output_port(), - passthrough->get_input_port()); - } else { - builder.Connect(input_receiver->get_output_port(), - passthrough->get_input_port()); - } + builder.Connect(input_receiver->get_output_port(), + cassie_motor->get_input_port_command()); + builder.Connect(cassie_motor->get_output_port(), + passthrough->get_input_port()); builder.Connect(passthrough->get_output_port(), discrete_time_delay->get_input_port()); builder.Connect(discrete_time_delay->get_output_port(), @@ -187,6 +182,8 @@ int do_main(int argc, char* argv[]) { sensor_pub->get_input_port()); auto diagram = builder.Build(); + diagram->set_name(("multibody_sim")); + DrawAndSaveDiagramGraph(*diagram); // Create a context for this system: std::unique_ptr> diagram_context = @@ -220,6 +217,10 @@ int do_main(int argc, char* argv[]) { } plant.SetPositions(&plant_context, q_init); plant.SetVelocities(&plant_context, VectorXd::Zero(plant.num_velocities())); + VectorXd x = plant.GetPositionsAndVelocities(plant_context); + const static Eigen::IOFormat CSVFormat(Eigen::StreamPrecision, + Eigen::DontAlignCols, ", ", "\n"); + std::cout << "x_init: " << x.transpose().format(CSVFormat) << std::endl; diagram_context->SetTime(FLAGS_start_time); Simulator simulator(*diagram, std::move(diagram_context)); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index e9104974a9..0c29bc01ab 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -88,10 +88,6 @@ DEFINE_string(osqp_settings, DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); -DEFINE_double( - fsm_time_offset, 0.0, - "Time (s) in the fsm to move from the stance phase to the flight phase"); -DEFINE_double(qp_time_limit, 0.0, "Time limit (s) for the OSC QP"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -181,8 +177,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true, false, - FLAGS_qp_time_limit); + plant, plant, plant_context.get(), plant_context.get(), true, false); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -553,7 +548,7 @@ int DoMain(int argc, char* argv[]) { loop.Simulate(); return 0; -} // namespace examples +} } // namespace examples } // namespace dairlib diff --git a/examples/Cassie/test/input_supervisor_test.cc b/examples/Cassie/test/input_supervisor_test.cc index 30e5c0c029..4124075ed6 100644 --- a/examples/Cassie/test/input_supervisor_test.cc +++ b/examples/Cassie/test/input_supervisor_test.cc @@ -29,14 +29,12 @@ class InputSupervisorTest : public ::testing::Test { context_ = supervisor_->CreateDefaultContext(); status_output_ = std::make_unique(); cassie_out_ = std::make_unique(); - motor_output_ = - std::make_unique>(plant_.num_actuators()); command_input_ = std::make_unique>(plant_.num_actuators()); state_input_ = std::make_unique>( plant_.num_positions(), plant_.num_velocities(), plant_.num_actuators()); - + output_ = supervisor_->AllocateOutput(); state_input_port_ = supervisor_->get_input_port_state().get_index(); } @@ -44,10 +42,11 @@ class InputSupervisorTest : public ::testing::Test { drake::multibody::MultibodyPlant plant_; Eigen::VectorXd input_limits_; const int min_consecutive_failures = 5; + std::unique_ptr> output_; std::unique_ptr supervisor_; std::unique_ptr status_output_; std::unique_ptr cassie_out_; - std::unique_ptr> motor_output_; + // std::unique_ptr> motor_output_; std::unique_ptr> command_input_; std::unique_ptr> state_input_; std::unique_ptr> context_; @@ -78,11 +77,13 @@ TEST_F(InputSupervisorTest, BlendEffortsTest) { context_.get(), (drake::AbstractValue&)*controller_failure); supervisor_->get_input_port_command().FixValue(context_.get(), *command_input_); - supervisor_->UpdateErrorFlag(*context_, - &context_->get_mutable_discrete_state()); - supervisor_->SetMotorTorques(*context_, motor_output_.get()); - VectorXd output_from_supervisor = motor_output_->get_value(); + supervisor_->CalcOutput(*context_, output_.get()); + const TimestampedVector* motor_output = + dynamic_cast*>( + output_->get_vector_data(0)); + + VectorXd output_from_supervisor = motor_output->get_data(); double alpha = (timestamp - blend_start_time) / blend_duration; EXPECT_EQ(output_from_supervisor, alpha * desired_input); From 8023526569e3008235651ba3cca303ae280a878b Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Sat, 12 Mar 2022 14:32:09 -0500 Subject: [PATCH 127/758] Add documentatation. Fix a bug if publish_efforts=false --- systems/robot_lcm_systems.cc | 12 ++++++++---- systems/robot_lcm_systems.h | 21 ++++++++++++++++++++- 2 files changed, 28 insertions(+), 5 deletions(-) diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index b0c79e4ad9..bcc5c017fc 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -294,13 +294,17 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( builder->Connect(discrete_time_delay->get_output_port(), plant.get_actuation_input_port()); - builder->Connect(discrete_time_delay->get_output_port(), - state_sender->get_input_port_effort()); + if (publish_efforts) { + builder->Connect(discrete_time_delay->get_output_port(), + state_sender->get_input_port_effort()); + } } else { builder->Connect(passthrough->get_output_port(), plant.get_actuation_input_port()); - builder->Connect(passthrough->get_output_port(), - state_sender->get_input_port_effort()); + if (publish_efforts) { + builder->Connect(passthrough->get_output_port(), + state_sender->get_input_port_effort()); + } } builder->Connect(*state_sender, *state_pub); diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 53a34bec22..74f384f2d7 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -115,9 +115,28 @@ class RobotCommandSender : public drake::systems::LeafSystem { }; -/// Adds LCM /// +/// Convenience method to add and connect leaf systems for controlling +/// a MultibodyPlant via LCM. Makes two prmary connections: +/// (1) connects the state output from the plant to a RobotOutputSender and +/// LCM publisher, publishing lcmt_robot_output +/// (2) connects the actuation input port of the plant to a RobotInputReceiver +/// and LCM receiver, receiving lcmt_robot_input /// +/// If an actuator delay is specified, also adds a DiscreteTimeDelay block +/// between the input receiver and plant. This delay will also be applied to the +/// efforts sent to the RobotOutputSender (if publish_efforts = true). +/// +/// @param builder +/// @param lcm The LcmInterfaceSystem to publish and receive on. Typically +/// from `builder.AddSystem(LcmInterfaceSystem(...))`; +/// @param actuator_channel The LCM channel name for the lcmt_robot_input +/// @param state_channel The LCM channel name for the lcmt_robot_output +/// @param publish_rate The frequency, in Hz, to publish at +/// @param publish_efforts If true, the RobotOutputSender will also publish +/// actuator efforts. +/// @param actuator_delay The delay, in seconds, will be discretized according +/// to publish_rate SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const drake::multibody::MultibodyPlant& plant, From 1c0b32400bc2d2ba86629fb2ec0e47e574685632 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 14 Mar 2022 11:38:46 -0400 Subject: [PATCH 128/758] working on sim diagram --- .../Cassie/diagrams/cassie_sim_diagram.cc | 146 +++++++++++++++++- examples/Cassie/diagrams/cassie_sim_diagram.h | 11 +- .../osc_running_controller_diagram.cc | 4 +- 3 files changed, 152 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 78f9e32a4e..563aa962d3 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -1,5 +1,145 @@ -// -// Created by yangwill on 3/11/22. -// #include "cassie_sim_diagram.h" + +#include "dairlib/lcmt_cassie_out.hpp" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_fixed_point_solver.h" +#include "examples/Cassie/cassie_utils.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/geared_motor.h" +#include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/lcm/drake_lcm.h" +#include "drake/lcmt_contact_results_for_viz.hpp" +#include "drake/multibody/plant/contact_results_to_lcm.h" +#include "drake/systems/analysis/runge_kutta2_integrator.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "drake/systems/primitives/discrete_time_delay.h" + +namespace dairlib { +namespace examples { + +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::SceneGraph; +using drake::multibody::ContactResultsToLcmSystem; +using drake::multibody::MultibodyPlant; +using drake::systems::Context; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using drake::math::RotationMatrix; +using Eigen::Matrix3d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +CassieSimDiagram::CassieSimDiagram(const std::string& urdf, double mu, + double stiffness, double dissipation_rate) { + // Plant/System initialization + DiagramBuilder builder; + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + + const double time_step = dt_; + MultibodyPlant& plant = *builder.AddSystem(time_step); + multibody::AddFlatTerrain(&plant, &scene_graph, mu, mu, + Eigen::Vector3d(0, 0, 1), stiffness, + dissipation_rate); + + addCassieMultibody(&plant, &scene_graph, true, urdf, true, true); + plant.Finalize(); + + // Create lcm systems. +// auto lcm = builder.AddSystem(); +// auto input_sub = +// builder.AddSystem(LcmSubscriberSystem::Make( +// FLAGS_channel_u, lcm)); + auto input_receiver = builder.AddSystem(plant); + auto passthrough = builder.AddSystem( + input_receiver->get_output_port(0).size(), 0, + plant.get_actuation_input_port().size()); + auto discrete_time_delay = + builder.AddSystem( + 1e-3, FLAGS_actuator_delay * FLAGS_publish_rate, + plant.num_actuators()); +// auto state_pub = +// builder.AddSystem(LcmPublisherSystem::Make( +// "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); + auto state_sender = builder.AddSystem( + plant, true); + + // Contact Information +// ContactResultsToLcmSystem& contact_viz = +// *builder.template AddSystem>(plant); +// contact_viz.set_name("contact_visualization"); +// auto& contact_results_publisher = *builder.AddSystem( +// LcmPublisherSystem::Make( +// "CASSIE_CONTACT_DRAKE", lcm, 1.0 / FLAGS_publish_rate)); +// contact_results_publisher.set_name("contact_results_publisher"); + + // Sensor aggregator and publisher of lcmt_cassie_out +// auto radio_sub = +// builder.AddSystem(LcmSubscriberSystem::Make( +// FLAGS_radio_channel, lcm)); + const auto& sensor_aggregator = + AddImuAndAggregator(&builder, plant, passthrough->get_output_port()); + +// auto sensor_pub = +// builder.AddSystem(LcmPublisherSystem::Make( +// "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); + + std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, + 303.687, 303.687, 136.136, 136.135, 575.958}; + + auto cassie_motor = builder.AddSystem(plant, omega_max); + + // connect leaf systems +// builder.Connect(*input_sub, *input_receiver); + builder.Connect(input_receiver->get_output_port(), + cassie_motor->get_input_port_command()); + builder.Connect(cassie_motor->get_output_port(), + passthrough->get_input_port()); + builder.Connect(passthrough->get_output_port(), + discrete_time_delay->get_input_port()); + builder.Connect(discrete_time_delay->get_output_port(), + plant.get_actuation_input_port()); + builder.Connect(plant.get_state_output_port(), + state_sender->get_input_port_state()); + builder.Connect(plant.get_state_output_port(), + cassie_motor->get_input_port_state()); + builder.Connect(discrete_time_delay->get_output_port(), + state_sender->get_input_port_effort()); +// builder.Connect(*state_sender, *state_pub); + builder.Connect( + plant.get_geometry_poses_output_port(), + scene_graph.get_source_pose_port(plant.get_source_id().value())); + builder.Connect(scene_graph.get_query_output_port(), + plant.get_geometry_query_input_port()); +// builder.Connect(plant.get_contact_results_output_port(), +// contact_viz.get_input_port(0)); +// builder.Connect(contact_viz.get_output_port(0), +// contact_results_publisher.get_input_port()); +// builder.Connect(radio_sub->get_output_port(), +// sensor_aggregator.get_input_port_radio()); +// builder.Connect(sensor_aggregator.get_output_port(0), +// sensor_pub->get_input_port()); + + builder.ExportInput(input_receiver->get_input_port(), + "u"); + builder.ExportInput(sensor_aggregator.get_input_port(), "radio"); + builder.ExportOutput(state_sender->get_output_port(0)); + builder.ExportOutput(sensor_aggregator.get_output_port(0)); + + auto diagram = builder.Build(); + diagram->set_name(("multibody_sim")); +} +} // namespace examples +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 89c53e3414..72f10f7ee8 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -15,10 +15,10 @@ class CassieSimDiagram : public drake::systems::Diagram { public: DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CassieSimDiagram) - /// @param[in] osc_gains_filename filepath containing the osc_running_gains. - /// @param[in] osqp_settings filepath containing the osqp settings. - CassieSimDiagram(const std::string& osc_gains_filename, - const std::string& osqp_settings_filename); + /// @param[in] urdf filepath containing the osc_running_gains. + CassieSimDiagram( + const std::string& urdf = "examples/Cassie/urdf/cassie_v2.urdf", + double mu = 0.8, double stiffness = 1e4, double dissipation_rate = 1e2); /// @return the input port for the actuation command. const drake::systems::InputPort& get_actuation_input_port() const { @@ -46,6 +46,9 @@ class CassieSimDiagram : public drake::systems::Diagram { const int radio_input_port_index_ = 1; const int state_output_port_index_ = 0; const int cassie_out_output_port_index_ = 1; + const double actuator_delay = 3e-3; // 3ms + const double actuator_update_rate = + const double dt_ = 8e-5; }; } // namespace examples diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 2a87156304..e0cb0e0d04 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -509,8 +509,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); builder.ExportInput(high_level_command->get_cassie_out_input_port(), "lcmt_cassie_out"); - builder.ExportOutput(passthrough->get_output_port()); - builder.ExportOutput(failure_aggregator->get_status_output_port()); + builder.ExportOutput(passthrough->get_output_port(), "u"); + builder.ExportOutput(failure_aggregator->get_status_output_port(), "failure_status"); // Run lcm-driven simulation // Create the diagram as itself From 7f941def91a8549ea26f4801e56067aa8628d8b9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 14 Mar 2022 17:01:36 -0400 Subject: [PATCH 129/758] need to connect the radio port to avoid segfaults --- bindings/pydairlib/cassie/BUILD.bazel | 16 +++ bindings/pydairlib/cassie/cassie_gym.py | 35 +++-- bindings/pydairlib/cassie/cassie_gym_test.py | 48 ++++++- bindings/pydairlib/cassie/simulators_py.cc | 41 ++++++ bindings/pydairlib/multibody/multibody_py.cc | 2 +- examples/Cassie/cassie_utils.cc | 2 +- .../Cassie/diagrams/cassie_sim_diagram.cc | 135 ++++++++++-------- examples/Cassie/diagrams/cassie_sim_diagram.h | 13 +- .../osc_running_controller_diagram.cc | 13 +- 9 files changed, 215 insertions(+), 90 deletions(-) create mode 100644 bindings/pydairlib/cassie/simulators_py.cc diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index ecc89a5db7..ca43515eab 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -85,6 +85,21 @@ pybind_py_library( py_imports = ["."], ) +pybind_py_library( + name = "simulators_py", + cc_deps = [ + "@drake//:drake_shared_library", + "//examples/Cassie/diagrams:cassie_sim_diagram", + ], + cc_so_name = "simulators", + cc_srcs = ["simulators_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + ":module_py", + ], + py_imports = ["."], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") @@ -103,6 +118,7 @@ py_library( PY_LIBRARIES = [ ":cassie_utils_py", ":controllers_py", + ":simulators_py", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index 0f2a79fd06..2fdb00eae4 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -11,6 +11,7 @@ from pydairlib.multibody import * from pydairlib.systems.primitives import * from pydairlib.systems.robot_lcm_systems import RobotOutputSender +from pydairlib.cassie.simulators import CassieSimDiagram class CassieGym(): def __init__(self, visualize=False): @@ -34,28 +35,32 @@ def __init__(self, visualize=False): "dissipation": 0.5} self.controller = None - def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): + def make(self, controller, urdf): self.builder = DiagramBuilder() self.dt = 5e-4 - self.params = self.default_contact_params + # self.params = self.default_contact_params + self.plant = MultibodyPlant(self.dt) + # terrain_normal = np.array([0.0, 0.0, 1.0]) + # self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, self.sim_dt) + # addCassieMultibody(self.plant, self.scene_graph, True, urdf, True, True) + # AddFlatTerrain(self.plant, self.scene_graph, self.params['mu'], self.params['mu'], terrain_normal, + # self.params['stiffness'], self.params['dissipation']) + # self.builder.AddSystem(self.plant) + # self.plant.Finalize() - terrain_normal = np.array([0.0, 0.0, 1.0]) - self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, self.sim_dt) - addCassieMultibody(self.plant, self.scene_graph, True, urdf, True, True) - AddFlatTerrain(self.plant, self.scene_graph, self.params['mu'], self.params['mu'], terrain_normal, - self.params['stiffness'], self.params['dissipation']) - self.plant.Finalize() - self.state_sender = self.builder.AddSystem(RobotOutputSender(self.plant, False)) - self.builder.Connect(self.plant.get_state_output_port(), self.state_sender.get_input_port(0)) - self.builder.AddSystem(controller) self.controller = controller - self.builder.Connect(self.controller.get_control_output_port(), self.plant.get_actuation_input_port()) - # self.builder.Connect(self.controller.get_control_output_port(), self.state_sender.get_input_port_effort()) - self.builder.Connect(self.state_sender.get_output_port(), self.controller.get_state_input_port()) + self.simulator = CassieSimDiagram(self.plant, urdf, 0.8, 1e4, 1e2) + self.plant = self.simulator.get_plant() + self.builder.AddSystem(self.controller) + self.builder.AddSystem(self.simulator) + + self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) + self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) + self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), self.controller.get_cassie_out_input_port()) + # self.builder.Connect(self.controller, self.simulator.get_radio_input_port()) self.diagram = self.builder.Build() self.sim = Simulator(self.diagram) - self.plant_context = self.diagram.GetMutableSubsystemContext(self.plant, self.sim.get_mutable_context()) self.sim.get_mutable_context().SetTime(self.start_time) self.reset() diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index aed0b07d48..e244f688d6 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -1,17 +1,59 @@ from cassie_gym import * # from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory +from pydairlib.cassie.simulators import CassieSimDiagram + + # from controllers import OSCRunningControllerFactory +def reexecute_if_unbuffered(): + """Ensures that output is immediately flushed (e.g. for segfaults). + ONLY use this at your entrypoint. Otherwise, you may have code be + re-executed that will clutter your console.""" + import os + import shlex + import sys + if os.environ.get("PYTHONUNBUFFERED") in (None, ""): + os.environ["PYTHONUNBUFFERED"] = "1" + argv = list(sys.argv) + if argv[0] != sys.executable: + argv.insert(0, sys.executable) + cmd = " ".join([shlex.quote(arg) for arg in argv]) + sys.stdout.flush() + os.execv(argv[0], argv) + + +def traced(func, ignoredirs=None): + """Decorates func such that its execution is traced, but filters out any + Python code outside of the system prefix.""" + import functools + import sys + import trace + if ignoredirs is None: + ignoredirs = ["/usr", sys.prefix] + tracer = trace.Trace(trace=1, count=0, ignoredirs=ignoredirs) + + @functools.wraps(func) + def wrapped(*args, **kwargs): + return tracer.runfunc(func, *args, **kwargs) + + return wrapped + +@traced def main(): osc_gains = 'examples/Cassie/osc_run/osc_running_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' + urdf = 'examples/Cassie/urdf/cassie_v2.urdf' + + terrain_normal = np.array([0.0, 0.0, 1.0]) + controller = OSCRunningControllerFactory(osc_gains, osqp_settings) gym_env = CassieGym(visualize=True) - gym_env.make(controller=controller) + gym_env.make(controller, urdf) gym_env.advance_to(10) - import pdb; pdb.set_trace() + if __name__ == '__main__': - main() \ No newline at end of file + reexecute_if_unbuffered() + main() diff --git a/bindings/pydairlib/cassie/simulators_py.cc b/bindings/pydairlib/cassie/simulators_py.cc new file mode 100644 index 0000000000..762243cc38 --- /dev/null +++ b/bindings/pydairlib/cassie/simulators_py.cc @@ -0,0 +1,41 @@ +#include +#include +#include +#include + +#include "examples/Cassie/diagrams/cassie_sim_diagram.h" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +using examples::CassieSimDiagram; + +PYBIND11_MODULE(simulators, m) { + m.doc() = "Binding controller factories for Cassie"; + + using py_rvp = py::return_value_policy; + + py::class_>(m, "CassieSimDiagram") + .def(py::init< + std::unique_ptr>, + const std::string&, double, double, double>(), + py::arg("plant"), py::arg("urdf"), py::arg("mu"), py::arg("stiffness"), + py::arg("dissipation_rate")) + .def("get_plant", &CassieSimDiagram::get_plant, + py_rvp::reference_internal) + .def("get_actuation_input_port", + &CassieSimDiagram::get_actuation_input_port, + py_rvp::reference_internal) + .def("get_radio_input_port", &CassieSimDiagram::get_radio_input_port, + py_rvp::reference_internal) + .def("get_state_output_port", &CassieSimDiagram::get_state_output_port, + py_rvp::reference_internal) + .def("get_cassie_out_output_port_index", + &CassieSimDiagram::get_cassie_out_output_port_index, + py_rvp::reference_internal); +} +} // namespace pydairlib +} // namespace dairlib \ No newline at end of file diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index 1ee5a1c5b5..5b72fc9fe0 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -14,7 +14,7 @@ namespace pydairlib { using multibody::MultiposeVisualizer; PYBIND11_MODULE(multibody, m) { - py::module::import("pydrake.all"); +// py::module::import("pydrake.all"); m.doc() = "Binding utility functions for MultibodyPlant"; diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index 4e0a3d4953..da3c31a85b 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -206,7 +206,7 @@ const systems::SimCassieSensorAggregator& AddImuAndAggregator( auto sensor_aggregator = builder->AddSystem(plant); - builder->Connect(actuation_port, sensor_aggregator->get_input_port_input()); +// builder->Connect(actuation_port, sensor_aggregator->get_input_port_input()); builder->Connect(plant.get_state_output_port(), encoders->get_input_port()); builder->Connect(encoders->get_output_port(), sensor_aggregator->get_input_port_state()); diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 563aa962d3..3471ec456d 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -41,68 +41,80 @@ using Eigen::Matrix3d; using Eigen::Vector3d; using Eigen::VectorXd; -CassieSimDiagram::CassieSimDiagram(const std::string& urdf, double mu, - double stiffness, double dissipation_rate) { +CassieSimDiagram::CassieSimDiagram( + std::unique_ptr> plant, + const std::string& urdf, double mu, double stiffness, + double dissipation_rate) { // Plant/System initialization DiagramBuilder builder; - SceneGraph& scene_graph = *builder.AddSystem(); - scene_graph.set_name("scene_graph"); - - const double time_step = dt_; - MultibodyPlant& plant = *builder.AddSystem(time_step); - multibody::AddFlatTerrain(&plant, &scene_graph, mu, mu, + // auto pair = drake::multibody::AddMultibodyPlantSceneGraph(&builder, dt_); + // std::tie(plant, scene_graph_) = pair; + scene_graph_ = builder.AddSystem(); + scene_graph_->set_name("scene_graph"); + + std::cout << "Here: " << std::endl; + plant.get(); + std::cout << "Here: " << std::endl; + // const double time_step = dt_; + // builder.AddSystem(std::move(plant)); + plant_ = builder.AddSystem(std::move(plant)); + addCassieMultibody(plant_, scene_graph_, true, urdf, true, true); + std::cout << "Here: " << std::endl; + multibody::AddFlatTerrain(plant_, scene_graph_, mu, mu, Eigen::Vector3d(0, 0, 1), stiffness, dissipation_rate); - - addCassieMultibody(&plant, &scene_graph, true, urdf, true, true); - plant.Finalize(); + // + plant_->Finalize(); + std::cout << "Here: " << std::endl; // Create lcm systems. -// auto lcm = builder.AddSystem(); -// auto input_sub = -// builder.AddSystem(LcmSubscriberSystem::Make( -// FLAGS_channel_u, lcm)); - auto input_receiver = builder.AddSystem(plant); + // auto lcm = builder.AddSystem(); + // auto input_sub = + // builder.AddSystem(LcmSubscriberSystem::Make( + // FLAGS_channel_u, lcm)); + auto input_receiver = builder.AddSystem(*plant_); auto passthrough = builder.AddSystem( input_receiver->get_output_port(0).size(), 0, - plant.get_actuation_input_port().size()); + plant_->get_actuation_input_port().size()); auto discrete_time_delay = builder.AddSystem( - 1e-3, FLAGS_actuator_delay * FLAGS_publish_rate, - plant.num_actuators()); -// auto state_pub = -// builder.AddSystem(LcmPublisherSystem::Make( -// "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); - auto state_sender = builder.AddSystem( - plant, true); + actuator_update_rate, actuator_delay / actuator_update_rate, + plant_->num_actuators()); + // auto state_pub = + // builder.AddSystem(LcmPublisherSystem::Make( + // "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); + auto state_sender = + builder.AddSystem(*plant_, true); // Contact Information -// ContactResultsToLcmSystem& contact_viz = -// *builder.template AddSystem>(plant); -// contact_viz.set_name("contact_visualization"); -// auto& contact_results_publisher = *builder.AddSystem( -// LcmPublisherSystem::Make( -// "CASSIE_CONTACT_DRAKE", lcm, 1.0 / FLAGS_publish_rate)); -// contact_results_publisher.set_name("contact_results_publisher"); + // ContactResultsToLcmSystem& contact_viz = + // *builder.template AddSystem>(plant); + // contact_viz.set_name("contact_visualization"); + // auto& contact_results_publisher = *builder.AddSystem( + // LcmPublisherSystem::Make( + // "CASSIE_CONTACT_DRAKE", lcm, 1.0 / FLAGS_publish_rate)); + // contact_results_publisher.set_name("contact_results_publisher"); // Sensor aggregator and publisher of lcmt_cassie_out -// auto radio_sub = -// builder.AddSystem(LcmSubscriberSystem::Make( -// FLAGS_radio_channel, lcm)); + // auto radio_sub = + // builder.AddSystem(LcmSubscriberSystem::Make( + // FLAGS_radio_channel, lcm)); const auto& sensor_aggregator = - AddImuAndAggregator(&builder, plant, passthrough->get_output_port()); + AddImuAndAggregator(&builder, *plant_, passthrough->get_output_port()); + std::cout << "Here: " << std::endl; -// auto sensor_pub = -// builder.AddSystem(LcmPublisherSystem::Make( -// "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); + // auto sensor_pub = + // builder.AddSystem(LcmPublisherSystem::Make( + // "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, 303.687, 303.687, 136.136, 136.135, 575.958}; - auto cassie_motor = builder.AddSystem(plant, omega_max); + auto cassie_motor = + builder.AddSystem(*plant_, omega_max); // connect leaf systems -// builder.Connect(*input_sub, *input_receiver); + // builder.Connect(*input_sub, *input_receiver); builder.Connect(input_receiver->get_output_port(), cassie_motor->get_input_port_command()); builder.Connect(cassie_motor->get_output_port(), @@ -110,36 +122,35 @@ CassieSimDiagram::CassieSimDiagram(const std::string& urdf, double mu, builder.Connect(passthrough->get_output_port(), discrete_time_delay->get_input_port()); builder.Connect(discrete_time_delay->get_output_port(), - plant.get_actuation_input_port()); - builder.Connect(plant.get_state_output_port(), + plant_->get_actuation_input_port()); + builder.Connect(plant_->get_state_output_port(), state_sender->get_input_port_state()); - builder.Connect(plant.get_state_output_port(), + builder.Connect(plant_->get_state_output_port(), cassie_motor->get_input_port_state()); builder.Connect(discrete_time_delay->get_output_port(), state_sender->get_input_port_effort()); -// builder.Connect(*state_sender, *state_pub); + // builder.Connect(*state_sender, *state_pub); builder.Connect( - plant.get_geometry_poses_output_port(), - scene_graph.get_source_pose_port(plant.get_source_id().value())); - builder.Connect(scene_graph.get_query_output_port(), - plant.get_geometry_query_input_port()); -// builder.Connect(plant.get_contact_results_output_port(), -// contact_viz.get_input_port(0)); -// builder.Connect(contact_viz.get_output_port(0), -// contact_results_publisher.get_input_port()); -// builder.Connect(radio_sub->get_output_port(), -// sensor_aggregator.get_input_port_radio()); -// builder.Connect(sensor_aggregator.get_output_port(0), -// sensor_pub->get_input_port()); - - builder.ExportInput(input_receiver->get_input_port(), - "u"); - builder.ExportInput(sensor_aggregator.get_input_port(), "radio"); + plant_->get_geometry_poses_output_port(), + scene_graph_->get_source_pose_port(plant_->get_source_id().value())); + builder.Connect(scene_graph_->get_query_output_port(), + plant_->get_geometry_query_input_port()); + // builder.Connect(plant.get_contact_results_output_port(), + // contact_viz.get_input_port(0)); + // builder.Connect(contact_viz.get_output_port(0), + // contact_results_publisher.get_input_port()); + // builder.Connect(radio_sub->get_output_port(), + // sensor_aggregator.get_input_port_radio()); + // builder.Connect(sensor_aggregator.get_output_port(0), + // sensor_pub->get_input_port()); + + builder.ExportInput(input_receiver->get_input_port(), "u"); + builder.ExportInput(sensor_aggregator.get_input_port_radio(), "radio"); builder.ExportOutput(state_sender->get_output_port(0)); builder.ExportOutput(sensor_aggregator.get_output_port(0)); - auto diagram = builder.Build(); - diagram->set_name(("multibody_sim")); + builder.BuildInto(this); + std::cout << "Built simulator" << std::endl; } } // namespace examples } // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 72f10f7ee8..b6e67576ca 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -3,6 +3,8 @@ #include #include +#include + #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" #include "drake/systems/framework/diagram_builder.h" @@ -16,7 +18,7 @@ class CassieSimDiagram : public drake::systems::Diagram { DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CassieSimDiagram) /// @param[in] urdf filepath containing the osc_running_gains. - CassieSimDiagram( + CassieSimDiagram(std::unique_ptr> plant, const std::string& urdf = "examples/Cassie/urdf/cassie_v2.urdf", double mu = 0.8, double stiffness = 1e4, double dissipation_rate = 1e2); @@ -41,13 +43,18 @@ class CassieSimDiagram : public drake::systems::Diagram { return this->get_output_port(cassie_out_output_port_index_); } + const drake::multibody::MultibodyPlant& get_plant() { return *plant_; } + private: +// drake::multibody::MultibodyPlant& plant_ref_; + drake::multibody::MultibodyPlant* plant_; + drake::geometry::SceneGraph* scene_graph_; const int actuation_input_port_index_ = 0; const int radio_input_port_index_ = 1; const int state_output_port_index_ = 0; const int cassie_out_output_port_index_ = 1; - const double actuator_delay = 3e-3; // 3ms - const double actuator_update_rate = + const double actuator_delay = 3e-3; // 3ms + const double actuator_update_rate = 1e-3; // 1ms const double dt_ = 8e-5; }; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index e0cb0e0d04..3a99bc4e3b 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -159,14 +159,15 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant); + auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), true, false); auto failure_aggregator = builder.AddSystem( control_channel_name_, 1); - auto passthrough = builder.AddSystem( - osc->get_output_port(0).size(), 0, - plant.get_actuation_input_port().size()); +// auto passthrough = builder.AddSystem( +// osc->get_output_port(0).size(), 0, +// plant.get_actuation_input_port().size()); std::vector tau = {.05, .05, .01}; auto ekf_filter = builder.AddSystem(plant, tau); @@ -503,13 +504,15 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.Connect(right_toe_angle_traj_gen->get_output_port(0), osc->get_tracking_data_input_port("right_toe_angle_traj")); builder.Connect(osc->get_osc_output_port(), - passthrough->get_input_port()); + command_sender->get_input_port(0)); +// builder.Connect(osc->get_osc_output_port(), +// passthrough->get_input_port()); // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); builder.ExportInput(high_level_command->get_cassie_out_input_port(), "lcmt_cassie_out"); - builder.ExportOutput(passthrough->get_output_port(), "u"); + builder.ExportOutput(command_sender->get_output_port(), "u, t"); builder.ExportOutput(failure_aggregator->get_status_output_port(), "failure_status"); // Run lcm-driven simulation From d4213e716da3ae26df79bfbf602eb97fd13962d4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 14 Mar 2022 17:07:46 -0400 Subject: [PATCH 130/758] cleaning up code --- bindings/pydairlib/cassie/cassie_gym.py | 9 ---- bindings/pydairlib/cassie/cassie_gym_test.py | 2 - .../Cassie/diagrams/cassie_sim_diagram.cc | 48 +------------------ .../osc_running_controller_diagram.cc | 8 ++-- 4 files changed, 4 insertions(+), 63 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index 2fdb00eae4..2a32733134 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -38,16 +38,7 @@ def __init__(self, visualize=False): def make(self, controller, urdf): self.builder = DiagramBuilder() self.dt = 5e-4 - # self.params = self.default_contact_params self.plant = MultibodyPlant(self.dt) - # terrain_normal = np.array([0.0, 0.0, 1.0]) - # self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, self.sim_dt) - # addCassieMultibody(self.plant, self.scene_graph, True, urdf, True, True) - # AddFlatTerrain(self.plant, self.scene_graph, self.params['mu'], self.params['mu'], terrain_normal, - # self.params['stiffness'], self.params['dissipation']) - # self.builder.AddSystem(self.plant) - # self.plant.Finalize() - self.controller = controller self.simulator = CassieSimDiagram(self.plant, urdf, 0.8, 1e4, 1e2) self.plant = self.simulator.get_plant() diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index e244f688d6..65adeadf24 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -45,8 +45,6 @@ def main(): osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' - terrain_normal = np.array([0.0, 0.0, 1.0]) - controller = OSCRunningControllerFactory(osc_gains, osqp_settings) gym_env = CassieGym(visualize=True) diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 3471ec456d..4d784466b2 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -45,33 +45,17 @@ CassieSimDiagram::CassieSimDiagram( std::unique_ptr> plant, const std::string& urdf, double mu, double stiffness, double dissipation_rate) { - // Plant/System initialization DiagramBuilder builder; - // auto pair = drake::multibody::AddMultibodyPlantSceneGraph(&builder, dt_); - // std::tie(plant, scene_graph_) = pair; scene_graph_ = builder.AddSystem(); scene_graph_->set_name("scene_graph"); - std::cout << "Here: " << std::endl; - plant.get(); - std::cout << "Here: " << std::endl; - // const double time_step = dt_; - // builder.AddSystem(std::move(plant)); plant_ = builder.AddSystem(std::move(plant)); addCassieMultibody(plant_, scene_graph_, true, urdf, true, true); - std::cout << "Here: " << std::endl; multibody::AddFlatTerrain(plant_, scene_graph_, mu, mu, Eigen::Vector3d(0, 0, 1), stiffness, dissipation_rate); - // plant_->Finalize(); - std::cout << "Here: " << std::endl; - // Create lcm systems. - // auto lcm = builder.AddSystem(); - // auto input_sub = - // builder.AddSystem(LcmSubscriberSystem::Make( - // FLAGS_channel_u, lcm)); auto input_receiver = builder.AddSystem(*plant_); auto passthrough = builder.AddSystem( input_receiver->get_output_port(0).size(), 0, @@ -80,32 +64,11 @@ CassieSimDiagram::CassieSimDiagram( builder.AddSystem( actuator_update_rate, actuator_delay / actuator_update_rate, plant_->num_actuators()); - // auto state_pub = - // builder.AddSystem(LcmPublisherSystem::Make( - // "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); auto state_sender = builder.AddSystem(*plant_, true); - // Contact Information - // ContactResultsToLcmSystem& contact_viz = - // *builder.template AddSystem>(plant); - // contact_viz.set_name("contact_visualization"); - // auto& contact_results_publisher = *builder.AddSystem( - // LcmPublisherSystem::Make( - // "CASSIE_CONTACT_DRAKE", lcm, 1.0 / FLAGS_publish_rate)); - // contact_results_publisher.set_name("contact_results_publisher"); - - // Sensor aggregator and publisher of lcmt_cassie_out - // auto radio_sub = - // builder.AddSystem(LcmSubscriberSystem::Make( - // FLAGS_radio_channel, lcm)); const auto& sensor_aggregator = AddImuAndAggregator(&builder, *plant_, passthrough->get_output_port()); - std::cout << "Here: " << std::endl; - - // auto sensor_pub = - // builder.AddSystem(LcmPublisherSystem::Make( - // "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, 303.687, 303.687, 136.136, 136.135, 575.958}; @@ -114,7 +77,6 @@ CassieSimDiagram::CassieSimDiagram( builder.AddSystem(*plant_, omega_max); // connect leaf systems - // builder.Connect(*input_sub, *input_receiver); builder.Connect(input_receiver->get_output_port(), cassie_motor->get_input_port_command()); builder.Connect(cassie_motor->get_output_port(), @@ -129,20 +91,11 @@ CassieSimDiagram::CassieSimDiagram( cassie_motor->get_input_port_state()); builder.Connect(discrete_time_delay->get_output_port(), state_sender->get_input_port_effort()); - // builder.Connect(*state_sender, *state_pub); builder.Connect( plant_->get_geometry_poses_output_port(), scene_graph_->get_source_pose_port(plant_->get_source_id().value())); builder.Connect(scene_graph_->get_query_output_port(), plant_->get_geometry_query_input_port()); - // builder.Connect(plant.get_contact_results_output_port(), - // contact_viz.get_input_port(0)); - // builder.Connect(contact_viz.get_output_port(0), - // contact_results_publisher.get_input_port()); - // builder.Connect(radio_sub->get_output_port(), - // sensor_aggregator.get_input_port_radio()); - // builder.Connect(sensor_aggregator.get_output_port(0), - // sensor_pub->get_input_port()); builder.ExportInput(input_receiver->get_input_port(), "u"); builder.ExportInput(sensor_aggregator.get_input_port_radio(), "radio"); @@ -150,6 +103,7 @@ CassieSimDiagram::CassieSimDiagram( builder.ExportOutput(sensor_aggregator.get_output_port(0)); builder.BuildInto(this); + this->set_name("cassie_sim"); std::cout << "Built simulator" << std::endl; } } // namespace examples diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 3a99bc4e3b..1197b9a9c8 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -505,8 +505,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->get_tracking_data_input_port("right_toe_angle_traj")); builder.Connect(osc->get_osc_output_port(), command_sender->get_input_port(0)); -// builder.Connect(osc->get_osc_output_port(), -// passthrough->get_input_port()); // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); @@ -515,10 +513,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.ExportOutput(command_sender->get_output_port(), "u, t"); builder.ExportOutput(failure_aggregator->get_status_output_port(), "failure_status"); - // Run lcm-driven simulation - // Create the diagram as itself builder.BuildInto(this); - // owned_diagram->set_name(("osc_running_controller")); + this->set_name(("osc_running_controller")); + std::cout << "Built controller" << std::endl; + } } // namespace controllers From bf73e9ea6ed979f70dd78ea48507fa084efb5766 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 15 Mar 2022 16:39:00 -0400 Subject: [PATCH 131/758] attempting to use stance foot to reduce sensitivty to state estimator --- examples/Cassie/osc_run/foot_traj_generator.cc | 18 ++++++++++++++++-- examples/Cassie/osc_run/foot_traj_generator.h | 9 ++++++--- examples/Cassie/osc_run/osc_running_gains.yaml | 4 ++-- examples/Cassie/run_osc_hopping_controller.cc | 4 ++-- examples/Cassie/run_osc_running_controller.cc | 4 ++-- 5 files changed, 28 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 047b56d04f..f750fc8830 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -29,6 +29,7 @@ namespace dairlib::examples::osc_run { FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, Context* context, const string& foot_name, + const string& stance_foot_name, const string& hip_name, bool relative_feet, const int stance_state, std::vector state_durations) @@ -36,6 +37,8 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, context_(context), world_(plant.world_frame()), foot_frame_(plant.GetFrameByName(foot_name)), + stance_foot_frame_(plant.GetFrameByName(stance_foot_name)), + stance_foot_name_(stance_foot_name), hip_frame_(plant.GetFrameByName(hip_name)), relative_feet_(relative_feet), stance_state_(stance_state), @@ -135,6 +138,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); + VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); @@ -156,8 +160,18 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); - pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); -// pelvis_vel(1) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); + // VectorXd stance_foot_vel = plant_.CalcVel(*context_, + // plant_.GetBodyByName("")); + VectorXd stance_foot_vel = plant_.GetBodyByName(stance_foot_name_) + .EvalSpatialVelocityInWorld(*context_) + .translational(); + if (fsm_state[0] < 2) { + pelvis_vel = pelvis_vel - stance_foot_vel; + } + // pelvis_vel(0) = + // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); + // pelvis_vel(1) = + // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 2939ca5931..12e40413bc 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -13,9 +13,10 @@ class FootTrajGenerator : public drake::systems::LeafSystem { public: FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - const std::string& foot_name, const std::string& hip_name, - bool relative_feet, int stance_state, - std::vector state_durations); + const std::string& foot_name, + const std::string& stance_foot_name, + const std::string& hip_name, bool relative_feet, + int stance_state, std::vector state_durations); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -50,6 +51,8 @@ class FootTrajGenerator : public drake::systems::LeafSystem { drake::systems::Context* context_; const drake::multibody::Frame& world_; const drake::multibody::Frame& foot_frame_; + const drake::multibody::Frame& stance_foot_frame_; + std::string stance_foot_name_; const drake::multibody::Frame& hip_frame_; // Foot spline parameters diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 71ed932029..b6008cbe56 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,7 +40,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.075 +center_line_offset: 0.05 FootstepKd: [ 0.2, 0, 0, 0, 0.45, 0, @@ -92,5 +92,5 @@ LiftoffSwingFootKp: LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 2] + 0, 0, 0] diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index 72608badd6..6c9d351ea8 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -268,10 +268,10 @@ int DoMain(int argc, char* argv[]) { osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "hip_left", + plant, plant_context.get(), "toe_left", "toe_right", "hip_left", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "hip_right", + plant, plant_context.get(), "toe_right", "toe_left", "hip_right", osc_gains.relative_feet, 0, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index e9104974a9..8459f3c7fb 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -282,10 +282,10 @@ int DoMain(int argc, char* argv[]) { osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, + plant, plant_context.get(), "toe_left", "toe_right", "pelvis", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "pelvis", + plant, plant_context.get(), "toe_right", "toe_left", "pelvis", osc_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); From 58fa0a9671dc9a106fdc20d056cc4bce47a8d213 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 15 Mar 2022 16:56:17 -0400 Subject: [PATCH 132/758] Revert "attempting to use stance foot to reduce sensitivty to state estimator" This reverts commit bf73e9ea6ed979f70dd78ea48507fa084efb5766. --- examples/Cassie/osc_run/foot_traj_generator.cc | 18 ++---------------- examples/Cassie/osc_run/foot_traj_generator.h | 9 +++------ examples/Cassie/osc_run/osc_running_gains.yaml | 4 ++-- examples/Cassie/run_osc_hopping_controller.cc | 4 ++-- examples/Cassie/run_osc_running_controller.cc | 4 ++-- 5 files changed, 11 insertions(+), 28 deletions(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index f750fc8830..047b56d04f 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -29,7 +29,6 @@ namespace dairlib::examples::osc_run { FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, Context* context, const string& foot_name, - const string& stance_foot_name, const string& hip_name, bool relative_feet, const int stance_state, std::vector state_durations) @@ -37,8 +36,6 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, context_(context), world_(plant.world_frame()), foot_frame_(plant.GetFrameByName(foot_name)), - stance_foot_frame_(plant.GetFrameByName(stance_foot_name)), - stance_foot_name_(stance_foot_name), hip_frame_(plant.GetFrameByName(hip_name)), relative_feet_(relative_feet), stance_state_(stance_state), @@ -138,7 +135,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); - VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); @@ -160,18 +156,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); - // VectorXd stance_foot_vel = plant_.CalcVel(*context_, - // plant_.GetBodyByName("")); - VectorXd stance_foot_vel = plant_.GetBodyByName(stance_foot_name_) - .EvalSpatialVelocityInWorld(*context_) - .translational(); - if (fsm_state[0] < 2) { - pelvis_vel = pelvis_vel - stance_foot_vel; - } - // pelvis_vel(0) = - // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); - // pelvis_vel(1) = - // context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); + pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); +// pelvis_vel(1) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 12e40413bc..2939ca5931 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -13,10 +13,9 @@ class FootTrajGenerator : public drake::systems::LeafSystem { public: FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - const std::string& foot_name, - const std::string& stance_foot_name, - const std::string& hip_name, bool relative_feet, - int stance_state, std::vector state_durations); + const std::string& foot_name, const std::string& hip_name, + bool relative_feet, int stance_state, + std::vector state_durations); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -51,8 +50,6 @@ class FootTrajGenerator : public drake::systems::LeafSystem { drake::systems::Context* context_; const drake::multibody::Frame& world_; const drake::multibody::Frame& foot_frame_; - const drake::multibody::Frame& stance_foot_frame_; - std::string stance_foot_name_; const drake::multibody::Frame& hip_frame_; // Foot spline parameters diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index b6008cbe56..71ed932029 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,7 +40,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.05 +center_line_offset: 0.075 FootstepKd: [ 0.2, 0, 0, 0, 0.45, 0, @@ -92,5 +92,5 @@ LiftoffSwingFootKp: LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 0] + 0, 0, 2] diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index 6c9d351ea8..72608badd6 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -268,10 +268,10 @@ int DoMain(int argc, char* argv[]) { osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "toe_right", "hip_left", + plant, plant_context.get(), "toe_left", "hip_left", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "toe_left", "hip_right", + plant, plant_context.get(), "toe_right", "hip_right", osc_gains.relative_feet, 0, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 8459f3c7fb..e9104974a9 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -282,10 +282,10 @@ int DoMain(int argc, char* argv[]) { osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "toe_right", "pelvis", osc_gains.relative_feet, + plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "toe_left", "pelvis", + plant, plant_context.get(), "toe_right", "pelvis", osc_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); From 3cfc98b0809dc13aaffe4e34225517bb7f4a9d2a Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 16 Mar 2022 12:23:33 -0400 Subject: [PATCH 133/758] working on debugging osc diagram in c++ --- bindings/pydairlib/cassie/BUILD.bazel | 7 +- bindings/pydairlib/cassie/cassie_gym.py | 24 +++++-- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/cassie_utils.cc | 2 +- examples/Cassie/diagrams/BUILD.bazel | 9 +++ .../Cassie/diagrams/cassie_sim_diagram.cc | 25 +++++-- examples/Cassie/diagrams/cassie_sim_diagram.h | 12 +++- .../osc_running_controller_diagram.cc | 22 +++--- .../Cassie/osc_run/osc_running_gains.yaml | 10 +-- examples/Cassie/run_pd_controller.cc | 67 +++++++++++++++---- systems/controllers/geared_motor.h | 7 -- .../osc/operational_space_control.cc | 44 +++++++++--- .../filters/floating_base_velocity_filter.h | 13 ++-- systems/filters/output_vector_filter.cc | 46 ++++++------- systems/framework/impact_info_vector.h | 8 --- systems/primitives/BUILD.bazel | 15 +++++ systems/primitives/radio_parser.cc | 32 +++++++++ systems/primitives/radio_parser.h | 32 +++++++++ 18 files changed, 275 insertions(+), 101 deletions(-) create mode 100644 systems/primitives/radio_parser.cc create mode 100644 systems/primitives/radio_parser.h diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index ca43515eab..ed3031cc81 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -16,7 +16,7 @@ py_library( srcs = ["cassie_gym.py"], deps = [ "//bindings/pydairlib/cassie:cassie", - "//bindings/pydairlib/common", + "//bindings/pydairlib", "//bindings/pydairlib/systems:systems", "//bindings/pydairlib/multibody", "//bindings/pydairlib/systems:primitives_py", @@ -89,12 +89,15 @@ pybind_py_library( name = "simulators_py", cc_deps = [ "@drake//:drake_shared_library", + "@drake//bindings/pydrake/common:value_pybind", "//examples/Cassie/diagrams:cassie_sim_diagram", ], cc_so_name = "simulators", - cc_srcs = ["simulators_py.cc"], + cc_srcs = ["simulators_py.cc", + ], py_deps = [ "@drake//bindings/pydrake", + "//bindings/pydairlib/lcm:lcm", ":module_py", ], py_imports = ["."], diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index 2a32733134..c3da4bad5f 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -11,8 +11,10 @@ from pydairlib.multibody import * from pydairlib.systems.primitives import * from pydairlib.systems.robot_lcm_systems import RobotOutputSender +from dairlib import lcmt_radio_out from pydairlib.cassie.simulators import CassieSimDiagram + class CassieGym(): def __init__(self, visualize=False): self.sim_dt = 5e-5 @@ -41,29 +43,37 @@ def make(self, controller, urdf): self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSimDiagram(self.plant, urdf, 0.8, 1e4, 1e2) - self.plant = self.simulator.get_plant() + self.new_plant = self.simulator.get_plant() + # self.sensor_aggregator = self.simulator.get_sensor_aggregator() self.builder.AddSystem(self.controller) self.builder.AddSystem(self.simulator) self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) - self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), self.controller.get_cassie_out_input_port()) + self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), + self.controller.get_cassie_out_input_port()) # self.builder.Connect(self.controller, self.simulator.get_radio_input_port()) self.diagram = self.builder.Build() self.sim = Simulator(self.diagram) - self.plant_context = self.diagram.GetMutableSubsystemContext(self.plant, self.sim.get_mutable_context()) + self.plant_context = self.diagram.GetMutableSubsystemContext(self.new_plant, self.sim.get_mutable_context()) + self.simulator_context = self.diagram.GetMutableSubsystemContext(self.simulator, self.sim.get_mutable_context()) self.sim.get_mutable_context().SetTime(self.start_time) self.reset() def reset(self): self.traj = CassieTraj() - self.plant.SetPositionsAndVelocities(self.plant.GetMyMutableContextFromRoot( + self.new_plant.SetPositionsAndVelocities(self.new_plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context()), self.x_init) self.sim.get_mutable_context().SetTime(self.start_time) self.traj.update(self.start_time, self.x_init, np.zeros(self.action_dim)) self.sim.Initialize() + cassie_state = self.plant.GetPositionsAndVelocities( + self.plant.GetMyMutableContextFromRoot( + self.sim.get_mutable_context())) + import pdb; + pdb.set_trace() self.current_time = self.start_time return @@ -75,8 +85,12 @@ def advance_to(self, time): def get_state(self): return self.traj.get_positions()[-1] - def step(self, action=np.zeros(10)): + def step(self, action=np.ones(18)): next_timestep = self.sim.get_context().get_time() + self.dt + # action = lcmt_radio_out + # self.simulator.get_radio_input_port().FixValue(self.simulator_context, AbstractValue.Make(action)) + + self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.sim.AdvanceTo(next_timestep) cassie_state = self.plant.GetPositionsAndVelocities( diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index fd3e3158da..f2ca15e8b1 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -178,6 +178,7 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//common", + "//examples/Cassie/diagrams:diagrams", "//systems:robot_lcm_systems", "//systems/controllers", "//systems/controllers:pd_config_lcm", diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index da3c31a85b..4e0a3d4953 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -206,7 +206,7 @@ const systems::SimCassieSensorAggregator& AddImuAndAggregator( auto sensor_aggregator = builder->AddSystem(plant); -// builder->Connect(actuation_port, sensor_aggregator->get_input_port_input()); + builder->Connect(actuation_port, sensor_aggregator->get_input_port_input()); builder->Connect(plant.get_state_output_port(), encoders->get_input_port()); builder->Connect(encoders->get_output_port(), sensor_aggregator->get_input_port_state()); diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel index 91d1d2e823..5d470df576 100644 --- a/examples/Cassie/diagrams/BUILD.bazel +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -22,6 +22,14 @@ load( "pybind_py_library", ) +cc_library( + name = "diagrams", + deps = [ + ":osc_running_controller_diagram", + ":cassie_sim_diagram", + ], +) + cc_library( name = "osc_running_controller_diagram", srcs = ["osc_running_controller_diagram.cc"], @@ -56,6 +64,7 @@ cc_library( "//systems:robot_lcm_systems", "//systems/controllers:geared_motor", "//systems/primitives", + "//systems/primitives:radio_parser", "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 4d784466b2..e8ee20dfd7 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -1,6 +1,8 @@ #include "cassie_sim_diagram.h" +#include + #include "dairlib/lcmt_cassie_out.hpp" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" @@ -8,6 +10,7 @@ #include "examples/Cassie/cassie_utils.h" #include "multibody/multibody_utils.h" #include "systems/controllers/geared_motor.h" +#include "systems/primitives/radio_parser.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -67,14 +70,18 @@ CassieSimDiagram::CassieSimDiagram( auto state_sender = builder.AddSystem(*plant_, true); - const auto& sensor_aggregator = - AddImuAndAggregator(&builder, *plant_, passthrough->get_output_port()); + auto constant_source = + builder.AddSystem( + VectorXd::Zero(10)); + sensor_aggregator_ = &AddImuAndAggregator(&builder, *plant_, + constant_source->get_output_port()); std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, 303.687, 303.687, 136.136, 136.135, 575.958}; auto cassie_motor = builder.AddSystem(*plant_, omega_max); + auto radio_parser = builder.AddSystem(); // connect leaf systems builder.Connect(input_receiver->get_output_port(), @@ -96,14 +103,18 @@ CassieSimDiagram::CassieSimDiagram( scene_graph_->get_source_pose_port(plant_->get_source_id().value())); builder.Connect(scene_graph_->get_query_output_port(), plant_->get_geometry_query_input_port()); + builder.Connect(radio_parser->get_output_port(), + sensor_aggregator_->get_input_port_radio()); - builder.ExportInput(input_receiver->get_input_port(), "u"); - builder.ExportInput(sensor_aggregator.get_input_port_radio(), "radio"); - builder.ExportOutput(state_sender->get_output_port(0)); - builder.ExportOutput(sensor_aggregator.get_output_port(0)); + builder.ExportInput(input_receiver->get_input_port(), "u, t"); + builder.ExportInput(radio_parser->get_input_port(), "raw_radio"); + builder.ExportOutput(state_sender->get_output_port(0), "x, u, t"); + builder.ExportOutput(sensor_aggregator_->get_output_port(0), + "lcmt_cassie_out"); builder.BuildInto(this); - this->set_name("cassie_sim"); + this->set_name("cassie_sim_diagram"); + DrawAndSaveDiagramGraph(*this); std::cout << "Built simulator" << std::endl; } } // namespace examples diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index b6e67576ca..2f826a3147 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -5,6 +5,8 @@ #include +#include "examples/Cassie/sim_cassie_sensor_aggregator.h" + #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" #include "drake/systems/framework/diagram_builder.h" @@ -43,11 +45,17 @@ class CassieSimDiagram : public drake::systems::Diagram { return this->get_output_port(cassie_out_output_port_index_); } - const drake::multibody::MultibodyPlant& get_plant() { return *plant_; } + const drake::multibody::MultibodyPlant& get_plant() { + return *plant_; + } + // const drake::systems::System& get_sensor_aggregator() { return + // *sensor_aggregator_; } const drake::systems::System& + // get_radio_parser() { return *radio_parser_; } private: -// drake::multibody::MultibodyPlant& plant_ref_; drake::multibody::MultibodyPlant* plant_; + const systems::SimCassieSensorAggregator* sensor_aggregator_; + // const systems::RadioParser* radio_parser_; drake::geometry::SceneGraph* scene_graph_; const int actuation_input_port_index_ = 0; const int radio_input_port_index_ = 1; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 1197b9a9c8..a4a1ebec24 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -104,6 +104,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( map vel_map = multibody::makeNameToVelocitiesMap(plant); map act_map = multibody::makeNameToActuatorsMap(plant); + std::cout << "state size : " << std::endl; + std::cout << plant.num_positions() + plant.num_velocities() << std::endl; + std::unordered_map< int, std::vector&>>> @@ -162,12 +165,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), true, false); - auto failure_aggregator = - builder.AddSystem( - control_channel_name_, 1); -// auto passthrough = builder.AddSystem( -// osc->get_output_port(0).size(), 0, -// plant.get_actuation_input_port().size()); + // auto failure_aggregator = + // builder.AddSystem( + // control_channel_name_, 1); + // auto passthrough = builder.AddSystem( + // osc->get_output_port(0).size(), 0, + // plant.get_actuation_input_port().size()); std::vector tau = {.05, .05, .01}; auto ekf_filter = builder.AddSystem(plant, tau); @@ -511,12 +514,13 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.ExportInput(high_level_command->get_cassie_out_input_port(), "lcmt_cassie_out"); builder.ExportOutput(command_sender->get_output_port(), "u, t"); - builder.ExportOutput(failure_aggregator->get_status_output_port(), "failure_status"); + // builder.ExportOutput(failure_aggregator->get_status_output_port(), + // "failure_status"); builder.BuildInto(this); - this->set_name(("osc_running_controller")); + this->set_name(("osc_running_controller_diagram")); + DrawAndSaveDiagramGraph(*this); std::cout << "Built controller" << std::endl; - } } // namespace controllers diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 71ed932029..d4d47162b5 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -62,12 +62,12 @@ PelvisRotW: 0, 2.5, 0, 0, 0, 0.1] PelvisRotKp: - [40, 0, 0, - 0, 20, 0, + [50, 0, 0, + 0, 100, 0, 0, 0, 1] PelvisRotKd: [7.5, 0, 0, - 0, 2.5, 0, + 0, 5, 0, 0, 0, 0] SwingFootW: [10, 0, 0, @@ -79,7 +79,7 @@ SwingFootKp: 0, 0, 50] SwingFootKd: [5, 0, 0, - 0, 1.5, 0, + 0, 59, 0, 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, @@ -92,5 +92,5 @@ LiftoffSwingFootKp: LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 2] + 0, 0, 0] diff --git a/examples/Cassie/run_pd_controller.cc b/examples/Cassie/run_pd_controller.cc index 1fb58a8bed..2e00a82321 100644 --- a/examples/Cassie/run_pd_controller.cc +++ b/examples/Cassie/run_pd_controller.cc @@ -1,19 +1,22 @@ +#include #include -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" - #include "dairlib/lcmt_pd_config.hpp" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/diagrams/cassie_sim_diagram.h" +#include "examples/Cassie/diagrams/osc_running_controller_diagram.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" + namespace dairlib { using drake::geometry::SceneGraph; @@ -64,8 +67,7 @@ int doMain(int argc, char* argv[]) { // Create config receiver. auto config_sub = builder.AddSystem( LcmSubscriberSystem::Make(channel_config, lcm)); - auto config_receiver = - builder.AddSystem(plant); + auto config_receiver = builder.AddSystem(plant); builder.Connect(config_sub->get_output_port(), config_receiver->get_input_port(0)); @@ -73,15 +75,13 @@ int doMain(int argc, char* argv[]) { auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( channel_u, lcm, 1.0 / 1000.0)); - auto command_sender = - builder.AddSystem(plant); + auto command_sender = builder.AddSystem(plant); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); auto controller = builder.AddSystem( - plant.num_positions(), plant.num_velocities(), - plant.num_actuators()); + plant.num_positions(), plant.num_velocities(), plant.num_actuators()); builder.Connect(state_receiver->get_output_port(0), controller->get_input_port_output()); @@ -114,6 +114,47 @@ int doMain(int argc, char* argv[]) { return 0; } +int doMainTest(int argc, char* argv[]) { + DiagramBuilder builder; + std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + std::string osc_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; + std::string osqp_settings = + "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; + std::unique_ptr> plant = + std::make_unique>(1e-5); + + auto sim_diagram = builder.AddSystem( + std::move(plant), urdf, 0.4, 1e4, 1e2); + auto controller_diagram = + builder.AddSystem( + osc_gains, osqp_settings); + const MultibodyPlant& new_plant = sim_diagram->get_plant(); + + builder.Connect(controller_diagram->get_control_output_port(), + sim_diagram->get_actuation_input_port()); + builder.Connect(sim_diagram->get_state_output_port(), + controller_diagram->get_state_input_port()); + builder.Connect(sim_diagram->get_cassie_out_output_port_index(), + controller_diagram->get_cassie_out_input_port()); + + auto diagram = builder.Build(); + std::unique_ptr> diagram_context = + diagram->CreateDefaultContext(); + VectorXd x_init = VectorXd::Zero(45); + x_init << 1, 0, 0, 0, 0, 0, 1, -0.0304885, 0, 0.466767, -1.15602, -0.037542, + 1.45243, -0.0257992, -1.59913, 0.0304885, 0, 0.466767, -1.15602, + -0.0374859, 1.45244, -0.0259075, -1.59919, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + Context& plant_context = + diagram->GetMutableSubsystemContext(new_plant, diagram_context.get()); + drake::systems::Simulator simulator(*diagram, + std::move(diagram_context)); + new_plant.SetPositionsAndVelocities(&plant_context, x_init); + // auto sim = drake::systems::Simulator(diagram); + simulator.AdvanceTo(5.0); +} + } // namespace dairlib -int main(int argc, char* argv[]) { return dairlib::doMain(argc, argv); } +// int main(int argc, char* argv[]) { return dairlib::doMain(argc, argv); } +int main(int argc, char* argv[]) { return dairlib::doMainTest(argc, argv); } diff --git a/systems/controllers/geared_motor.h b/systems/controllers/geared_motor.h index ff3cc9db24..b1789e4d7a 100644 --- a/systems/controllers/geared_motor.h +++ b/systems/controllers/geared_motor.h @@ -11,14 +11,8 @@ namespace dairlib { namespace systems { -/// This class is copied from drake/systems/primitives/PassThrough -/// with the modification that it only passes through a subset of the vector class GearedMotor : public drake::systems::LeafSystem { public: - /// Constructs a pass through system (`y = u.segment(start,length)`). - /// @param vector_size the length of the input vector - /// @param start the initial index of the subvector - /// @param length number of elements in the subvector GearedMotor(const drake::multibody::MultibodyPlant& plant, const std::vector& max_motor_speeds); const drake::systems::InputPort& get_input_port_command() const { @@ -29,7 +23,6 @@ class GearedMotor : public drake::systems::LeafSystem { return drake::systems::LeafSystem::get_input_port(state_input_port_); } - /// Returns the sole output port. const drake::systems::OutputPort& get_output_port() const { return drake::systems::LeafSystem::get_output_port(0); } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f817aeafb1..42e0a33210 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -62,6 +62,10 @@ OperationalSpaceControl::OperationalSpaceControl( qp_time_limit_(qp_time_limit) { this->set_name("OSC"); + std::cout << "in constructor" << std::endl; + std::cout << plant_w_spr_.num_positions() + plant_w_spr_.num_velocities() + << std::endl; + n_q_ = plant_wo_spr.num_positions(); n_v_ = plant_wo_spr.num_velocities(); n_u_ = plant_wo_spr.num_actuators(); @@ -263,7 +267,8 @@ void OperationalSpaceControl::CheckConstraintSettings() { } } -void OperationalSpaceControl::Build(const solvers::OSQPSettingsYaml& osqp_settings) { +void OperationalSpaceControl::Build( + const solvers::OSQPSettingsYaml& osqp_settings) { // Checker CheckCostSettings(); CheckConstraintSettings(); @@ -578,8 +583,8 @@ VectorXd OperationalSpaceControl::SolveQp( row_idx += contact_i->num_active(); } -// std::cout << "JdotV_h" << JdotV_h.transpose() << std::endl; -// std::cout << "JdotV_c" << JdotV_c_active.transpose() << std::endl; + // std::cout << "JdotV_h" << JdotV_h.transpose() << std::endl; + // std::cout << "JdotV_c" << JdotV_c_active.transpose() << std::endl; // Update constraints // 1. Dynamics constraint @@ -734,9 +739,9 @@ VectorXd OperationalSpaceControl::SolveQp( -W_input_smoothing_ * (*u_prev_)); } -// if (!solver_->IsInitialized()) { -// solver_->InitializeSolver(*prog_); -// } + // if (!solver_->IsInitialized()) { + // solver_->InitializeSolver(*prog_); + // } if (initial_guess_x_.count(fsm_state) > 0) { solver_->WarmStart(initial_guess_x_.at(fsm_state), @@ -756,8 +761,8 @@ VectorXd OperationalSpaceControl::SolveQp( initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { -// std::cerr << "QP did not solve in time!" << std::endl; -// solver_->DisableWarmStart(); + // std::cerr << "QP did not solve in time!" << std::endl; + // solver_->DisableWarmStart(); *u_prev_ = VectorXd::Zero(n_u_); } @@ -891,7 +896,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( W_lambda_c_reg_ * (*lambda_c_sol_))(0) : 0; total_cost_ += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost; + input_smoothing_cost + lambda_h_cost + lambda_c_cost; soft_constraint_cost_ = soft_constraint_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); @@ -983,7 +988,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( } output->tracking_data[i] = osc_output; } -// std::cout << total_cost_ << std::endl; + // std::cout << total_cost_ << std::endl; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); @@ -1000,9 +1005,13 @@ void OperationalSpaceControl::CalcOptimalInput( VectorXd v_w_spr = robot_output->GetVelocities(); VectorXd x_w_spr(plant_w_spr_.num_positions() + plant_w_spr_.num_velocities()); + // VectorXd x_w_spr(n_q_ + n_v_); + std::cout << q_w_spr.size() << std::endl; + std::cout << v_w_spr.size() << std::endl; + std::cout << plant_w_spr_.num_positions() << std::endl; + std::cout << plant_w_spr_.num_velocities() << std::endl; x_w_spr << q_w_spr, v_w_spr; - double timestamp = robot_output->get_timestamp(); double current_time = timestamp; if (print_tracking_info_) { @@ -1012,6 +1021,9 @@ void OperationalSpaceControl::CalcOptimalInput( VectorXd x_wo_spr(n_q_ + n_v_); x_wo_spr << map_position_from_spring_to_no_spring_ * q_w_spr, map_velocity_from_spring_to_no_spring_ * v_w_spr; + // std::cout << "In function: " << std::endl; + // std::cout << plant_w_spr_.num_positions() + plant_w_spr_.num_velocities() + // << std::endl; VectorXd u_sol(n_u_); if (used_with_finite_state_machine_) { @@ -1022,6 +1034,7 @@ void OperationalSpaceControl::CalcOptimalInput( auto clock = this->EvalVectorInput(context, clock_port_); clock_time = clock->get_value()(0); } + VectorXd fsm_state = fsm_output->get_value(); double alpha = 0; @@ -1036,8 +1049,17 @@ void OperationalSpaceControl::CalcOptimalInput( // Get discrete states const auto prev_event_time = context.get_discrete_state(prev_event_time_idx_).get_value(); + // std::cout << fsm_state(0) << std::endl; + // std::cout << clock_time << std::endl; + // std::cout << prev_event_time(0) << std::endl; + // std::cout << alpha << std::endl; + // std::cout << next_fsm_state << std::endl; + // std::cout << current_time << std::endl; + std::cout << x_w_spr.transpose() << std::endl; + std::cout << x_wo_spr.transpose() << std::endl; u_sol = SolveQp(x_w_spr, x_wo_spr, context, clock_time, fsm_state(0), current_time - prev_event_time(0), alpha, next_fsm_state); + } else { u_sol = SolveQp(x_w_spr, x_wo_spr, context, current_time, -1, current_time, 0, -1); diff --git a/systems/filters/floating_base_velocity_filter.h b/systems/filters/floating_base_velocity_filter.h index 287f2f9054..604d1c9db7 100644 --- a/systems/filters/floating_base_velocity_filter.h +++ b/systems/filters/floating_base_velocity_filter.h @@ -1,5 +1,6 @@ #pragma once #include "output_vector_filter.h" + #include "drake/multibody/plant/multibody_plant.h" /// Specialization of Timestamped Low Pass Filter for floting base velocity @@ -10,10 +11,10 @@ class FloatingBaseVelocityFilter : public OutputVectorFilter { public: FloatingBaseVelocityFilter( const drake::multibody::MultibodyPlant& plant, - const std::vector& tau) : - OutputVectorFilter( - plant, tau, std::vector{plant.num_positions() + 3, - plant.num_positions() + 4, - plant.num_positions() + 5}){}; + const std::vector& tau) + : OutputVectorFilter(plant, tau, + std::vector{plant.num_positions() + 3, + plant.num_positions() + 4, + plant.num_positions() + 5}){}; }; -} +} // namespace dairlib::systems diff --git a/systems/filters/output_vector_filter.cc b/systems/filters/output_vector_filter.cc index fd5a21c1a0..114f26660e 100644 --- a/systems/filters/output_vector_filter.cc +++ b/systems/filters/output_vector_filter.cc @@ -1,28 +1,27 @@ #include "output_vector_filter.h" + #include "systems/framework/output_vector.h" -using Eigen::VectorXd; -using Eigen::MatrixXd; -using drake::systems::LeafSystem; using drake::systems::Context; - +using drake::systems::LeafSystem; +using Eigen::MatrixXd; +using Eigen::VectorXd; namespace dairlib::systems { OutputVectorFilter::OutputVectorFilter( const drake::multibody::MultibodyPlant& plant, - const std::vector& tau, - std::optional> filter_idxs) + const std::vector& tau, std::optional> filter_idxs) : n_y_filt_(tau.size()), tau_(tau) { - int n_y = plant.num_positions() + - plant.num_velocities() + plant.num_actuators() + 3; + int n_y = plant.num_positions() + plant.num_velocities() + + plant.num_actuators() + 3; DRAKE_DEMAND(filter_idxs.has_value() || tau.size() == n_y); if (filter_idxs.has_value()) { DRAKE_DEMAND(filter_idxs->size() == tau.size()); } - if (!filter_idxs.has_value()){ + if (!filter_idxs.has_value()) { std::vector idxs(n_y); std::iota(idxs.begin(), idxs.end(), 0); filter_idxs_ = idxs; @@ -44,43 +43,40 @@ OutputVectorFilter::OutputVectorFilter( } drake::systems::EventStatus OutputVectorFilter::DiscreteVariableUpdate( - const drake::systems::Context &context, - drake::systems::DiscreteValues *discrete_state) const { - + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { const OutputVector* y_t = (OutputVector*)EvalVectorInput(context, 0); - double dt = y_t->get_timestamp() - - discrete_state->get_value(prev_time_idx_)[0]; + double dt = + y_t->get_timestamp() - discrete_state->get_value(prev_time_idx_)[0]; VectorXd y = y_t->get_data(); VectorXd y_prev = discrete_state->get_value(prev_val_idx_); - for (int i = 0; i < n_y_filt_; i++){ + for (int i = 0; i < n_y_filt_; i++) { double alpha = dt / (dt + tau_.at(i)); - y(filter_idxs_.at(i)) = - alpha * y(filter_idxs_.at(i)) + - (1.0 - alpha) * y_prev(filter_idxs_.at(i)); + y(filter_idxs_.at(i)) = alpha * y(filter_idxs_.at(i)) + + (1.0 - alpha) * y_prev(filter_idxs_.at(i)); } - discrete_state->get_mutable_value(prev_time_idx_) << - y_t->get_timestamp() * VectorXd::Ones(1) ; + discrete_state->get_mutable_value(prev_time_idx_) + << y_t->get_timestamp() * VectorXd::Ones(1); discrete_state->get_mutable_value(prev_val_idx_) << y; return drake::systems::EventStatus::Succeeded(); } void OutputVectorFilter::CopyFilterValues( - const drake::systems::Context &context, - dairlib::systems::OutputVector *y) const { - + const drake::systems::Context& context, + dairlib::systems::OutputVector* y) const { auto y_curr = (OutputVector*)EvalVectorInput(context, 0); y->SetDataVector(y_curr->get_data()); y->set_timestamp(y_curr->get_timestamp()); - if (context.get_discrete_state(prev_time_idx_).get_value()[0] >= .001){ + if (context.get_discrete_state(prev_time_idx_).get_value()[0] >= .001) { VectorXd y_filt = context.get_discrete_state(prev_val_idx_).get_value(); for (auto& i : filter_idxs_) { y->get_mutable_value()[i] = y_filt(i); } } } -} \ No newline at end of file +} // namespace dairlib::systems \ No newline at end of file diff --git a/systems/framework/impact_info_vector.h b/systems/framework/impact_info_vector.h index 951238fd5c..3a5dc42777 100644 --- a/systems/framework/impact_info_vector.h +++ b/systems/framework/impact_info_vector.h @@ -12,12 +12,6 @@ using drake::VectorX; using std::string; using std::vector; -/// OutputVector stores the robot output as a TimestampedVector -/// * positions -/// * velocities -/// * efforts -/// * imu accelerations -/// Can be later extended if more information is desired in here template class ImpactInfoVector : public TimestampedVector { public: @@ -25,8 +19,6 @@ class ImpactInfoVector : public TimestampedVector { ImpactInfoVector() = default; - /// Initializes with the given @p size using the drake::dummy_value, which - /// is NaN when T = double. explicit ImpactInfoVector(int num_contact, int num_holonomic, int space_dim) : TimestampedVector(3 + num_contact + num_holonomic), has_impulse_info_(num_contact != 0), diff --git a/systems/primitives/BUILD.bazel b/systems/primitives/BUILD.bazel index e54463d314..d07aa4ceee 100644 --- a/systems/primitives/BUILD.bazel +++ b/systems/primitives/BUILD.bazel @@ -37,6 +37,21 @@ cc_library( ], ) +cc_library( + name = "radio_parser", + srcs = [ + "radio_parser.cc", + ], + hdrs = [ + "radio_parser.h", + ], + deps = [ + "//systems/framework:vector", + "//lcmtypes:lcmt_robot", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "gaussian_noise_pass_through", srcs = ["gaussian_noise_pass_through.cc"], diff --git a/systems/primitives/radio_parser.cc b/systems/primitives/radio_parser.cc new file mode 100644 index 0000000000..1694e70bc5 --- /dev/null +++ b/systems/primitives/radio_parser.cc @@ -0,0 +1,32 @@ +#include "systems/primitives/radio_parser.h" + +#include + +namespace dairlib { +namespace systems { + +using drake::systems::BasicVector; +RadioParser::RadioParser() { + data_input_port_ = + this->DeclareVectorInputPort("raw_radio", BasicVector(2 + 16)) + .get_index(); + this->DeclareAbstractOutputPort("radio_out", dairlib::lcmt_radio_out(), + &RadioParser::CalcRadioOutput); +} + +void RadioParser::CalcRadioOutput( + const drake::systems::Context& context, + dairlib::lcmt_radio_out* output) const { + const BasicVector& data = + *this->template EvalVectorInput(context, data_input_port_); + output->radioReceiverSignalGood = data[0]; + output->receiverMedullaSignalGood = data[1]; + for (int i = 0; i < 16; ++i) { + output->channel[i] = data.value()[2 + i]; + std::cout << "channel: " << i << output->channel[i] << std::endl; + } + std::cout << "here finally: " << std::endl; +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/primitives/radio_parser.h b/systems/primitives/radio_parser.h new file mode 100644 index 0000000000..754054ed7e --- /dev/null +++ b/systems/primitives/radio_parser.h @@ -0,0 +1,32 @@ +#pragma once + +#include + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +class RadioParser : public drake::systems::LeafSystem { + public: + RadioParser(); + + const drake::systems::InputPort& get_input_port() const { + return drake::systems::LeafSystem::get_input_port(0); + } + + const drake::systems::OutputPort& get_output_port() const { + return drake::systems::LeafSystem::get_output_port(0); + } + + protected: + void CalcRadioOutput(const drake::systems::Context& context, + dairlib::lcmt_radio_out* output) const; + + private: + bool is_abstract() const { return false; } + int data_input_port_; +}; + +} // namespace systems +} // namespace dairlib From 66db01a56546e462965f9e665ff4679f77189b8d Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 16 Mar 2022 16:32:43 -0400 Subject: [PATCH 134/758] dealing with annoying scope issues --- bindings/pydairlib/cassie/controllers_py.cc | 4 +- examples/Cassie/BUILD.bazel | 17 ++++ examples/Cassie/closed_loop_running_sim.cc | 77 +++++++++++++++++++ examples/Cassie/diagrams/cassie_sim_diagram.h | 2 +- .../osc_running_controller_diagram.cc | 4 +- .../diagrams/osc_running_controller_diagram.h | 5 +- examples/Cassie/run_pd_controller.cc | 42 +--------- 7 files changed, 104 insertions(+), 47 deletions(-) create mode 100644 examples/Cassie/closed_loop_running_sim.cc diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index bcada0fc69..3d472d9a12 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -21,8 +21,8 @@ PYBIND11_MODULE(controllers, m) { py::class_>( m, "OSCRunningControllerFactory") - .def(py::init(), - py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) + .def(py::init&, const std::string&, const std::string&>(), + py::arg("plant"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) .def("get_state_input_port", &OSCRunningControllerDiagram::get_state_input_port, py_rvp::reference_internal) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index f2ca15e8b1..16be9405de 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -187,6 +187,23 @@ cc_binary( ], ) +cc_binary( + name = "closed_loop_running_sim", + srcs = ["closed_loop_running_sim.cc"], + deps = [ + ":cassie_urdf", + ":cassie_utils", + "//common", + "//examples/Cassie/diagrams:diagrams", + "//systems:robot_lcm_systems", + "//systems/controllers", + "//systems/controllers:pd_config_lcm", + "//systems:system_utils", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "visualizer", srcs = ["visualizer.cc"], diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc new file mode 100644 index 0000000000..23def114dd --- /dev/null +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -0,0 +1,77 @@ +#include +#include + +#include "dairlib/lcmt_pd_config.hpp" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/diagrams/cassie_sim_diagram.h" +#include "examples/Cassie/diagrams/osc_running_controller_diagram.h" +#include "systems/controllers/linear_controller.h" +#include "systems/controllers/pd_config_lcm.h" +#include "systems/robot_lcm_systems.h" + +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "systems/system_utils.h" + +namespace dairlib { +using drake::multibody::MultibodyPlant; +using drake::systems::DiagramBuilder; + +namespace examples { + +int DoMain(int argc, char* argv[]) { + DiagramBuilder builder; + std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + std::string osc_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; + std::string osqp_settings = + "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; + std::unique_ptr> plant = + std::make_unique>(1e-5); + MultibodyPlant controller_plant = + MultibodyPlant(1e-5); +// auto controller_context = controller_plant.CreateDefaultContext(); + + auto sim_diagram = builder.AddSystem( + std::move(plant), urdf, 0.4, 1e4, 1e2); + MultibodyPlant& new_plant = sim_diagram->get_plant(); + auto controller_diagram = + builder.AddSystem( + controller_plant, osc_gains, osqp_settings); + + builder.Connect(controller_diagram->get_control_output_port(), + sim_diagram->get_actuation_input_port()); + builder.Connect(sim_diagram->get_state_output_port(), + controller_diagram->get_state_input_port()); + builder.Connect(sim_diagram->get_cassie_out_output_port_index(), + controller_diagram->get_cassie_out_input_port()); + + auto diagram = builder.Build(); + diagram->set_name("cassie_running_gym"); + DrawAndSaveDiagramGraph(*diagram); + std::cout << "built diagram: " << std::endl; + std::unique_ptr> diagram_context = + diagram->CreateDefaultContext(); + VectorXd x_init = VectorXd::Zero(45); + x_init << 1, 0, 0, 0, 0, 0, 1, -0.0304885, 0, 0.466767, -1.15602, -0.037542, + 1.45243, -0.0257992, -1.59913, 0.0304885, 0, 0.466767, -1.15602, + -0.0374859, 1.45244, -0.0259075, -1.59919, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + Context& plant_context = + diagram->GetMutableSubsystemContext(new_plant, diagram_context.get()); + drake::systems::Simulator simulator(*diagram, + std::move(diagram_context)); + new_plant.SetPositionsAndVelocities(&plant_context, x_init); + // auto sim = drake::systems::Simulator(diagram); + std::cout << "advancing simulator: " << std::endl; + simulator.AdvanceTo(5.0); +} +}} + +int main(int argc, char* argv[]) { + return dairlib::examples::DoMain(argc, argv); +} diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 2f826a3147..9a01aedb0f 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -45,7 +45,7 @@ class CassieSimDiagram : public drake::systems::Diagram { return this->get_output_port(cassie_out_output_port_index_); } - const drake::multibody::MultibodyPlant& get_plant() { + drake::multibody::MultibodyPlant& get_plant() { return *plant_; } // const drake::systems::System& get_sensor_aggregator() { return diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index a4a1ebec24..bb3e079b46 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -78,18 +78,18 @@ namespace examples { namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( + drake::multibody::MultibodyPlant& plant, const string& osc_gains_filename, const string& osqp_settings_filename) { // Build the controller diagram DiagramBuilder builder; // Built the Cassie MBPs - drake::multibody::MultibodyPlant plant(0.0); addCassieMultibody(&plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); plant.Finalize(); - auto plant_context = plant.CreateDefaultContext(); + plant_context = plant.CreateDefaultContext(); // Get contact frames and position auto left_toe = LeftToeFront(plant); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index 4fe3d85c3a..e45790d5da 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -2,6 +2,7 @@ #include #include +#include #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" @@ -18,7 +19,7 @@ class OSCRunningControllerDiagram : public drake::systems::Diagram { /// @param[in] osc_gains_filename filepath containing the osc_running_gains. /// @param[in] osqp_settings filepath containing the osqp settings. - OSCRunningControllerDiagram(const std::string& osc_gains_filename, + OSCRunningControllerDiagram(drake::multibody::MultibodyPlant& plant, const std::string& osc_gains_filename, const std::string& osqp_settings_filename); /// @return the input port for the plant state. @@ -43,6 +44,8 @@ class OSCRunningControllerDiagram : public drake::systems::Diagram { } private: + std::unique_ptr> plant_context; + const int state_input_port_index_ = 0; const int cassie_out_input_port_index_ = 1; const int control_output_port_index_ = 0; diff --git a/examples/Cassie/run_pd_controller.cc b/examples/Cassie/run_pd_controller.cc index 2e00a82321..6309ddf033 100644 --- a/examples/Cassie/run_pd_controller.cc +++ b/examples/Cassie/run_pd_controller.cc @@ -114,47 +114,7 @@ int doMain(int argc, char* argv[]) { return 0; } -int doMainTest(int argc, char* argv[]) { - DiagramBuilder builder; - std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; - std::string osc_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; - std::string osqp_settings = - "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; - std::unique_ptr> plant = - std::make_unique>(1e-5); - - auto sim_diagram = builder.AddSystem( - std::move(plant), urdf, 0.4, 1e4, 1e2); - auto controller_diagram = - builder.AddSystem( - osc_gains, osqp_settings); - const MultibodyPlant& new_plant = sim_diagram->get_plant(); - - builder.Connect(controller_diagram->get_control_output_port(), - sim_diagram->get_actuation_input_port()); - builder.Connect(sim_diagram->get_state_output_port(), - controller_diagram->get_state_input_port()); - builder.Connect(sim_diagram->get_cassie_out_output_port_index(), - controller_diagram->get_cassie_out_input_port()); - - auto diagram = builder.Build(); - std::unique_ptr> diagram_context = - diagram->CreateDefaultContext(); - VectorXd x_init = VectorXd::Zero(45); - x_init << 1, 0, 0, 0, 0, 0, 1, -0.0304885, 0, 0.466767, -1.15602, -0.037542, - 1.45243, -0.0257992, -1.59913, 0.0304885, 0, 0.466767, -1.15602, - -0.0374859, 1.45244, -0.0259075, -1.59919, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; - Context& plant_context = - diagram->GetMutableSubsystemContext(new_plant, diagram_context.get()); - drake::systems::Simulator simulator(*diagram, - std::move(diagram_context)); - new_plant.SetPositionsAndVelocities(&plant_context, x_init); - // auto sim = drake::systems::Simulator(diagram); - simulator.AdvanceTo(5.0); -} - } // namespace dairlib // int main(int argc, char* argv[]) { return dairlib::doMain(argc, argv); } -int main(int argc, char* argv[]) { return dairlib::doMainTest(argc, argv); } +int main(int argc, char* argv[]) { return dairlib::doMain(argc, argv); } From b83699fb7c3c5770fa1084505268587cd399aceb Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 16 Mar 2022 17:02:46 -0400 Subject: [PATCH 135/758] merging with master --- bindings/pydairlib/analysis/log_plotter_cassie.py | 5 +++-- bindings/pydairlib/multibody/multibody_py.cc | 2 +- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 4699182d24..ff5880877e 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,8 +12,9 @@ def main(): - config_file = \ - 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = \ + # 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index d1db1db227..20edddf8ba 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -39,7 +39,7 @@ PYBIND11_MODULE(multibody, m) { &dairlib::multibody::createActuatorNameVectorFromMap, py::arg("plant")) .def("addFlatTerrain", - &dairlib::multibody::addFlatTerrain, py::arg("plant"), + &dairlib::multibody::AddFlatTerrain, py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"), py::arg("mu_kinetic"), py::arg("normal_W") = Eigen::Vector3d(0, 0, 1), py::arg("stiffness") = 1e4, py::arg("dissipation_rate") = 0.5, From 533ce6f41eddea9a624ee3219a81470fc04beea9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 16 Mar 2022 17:06:46 -0400 Subject: [PATCH 136/758] fixing plotting yaml --- .../pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml | 3 +++ .../pydairlib/analysis/plot_configs/cassie_running_plot.yaml | 3 +++ 2 files changed, 6 insertions(+) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 18c82a5c3e..b40798887d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -3,6 +3,9 @@ channel_x: "CASSIE_STATE_SIMULATION" channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_JUMPING" +# Log time to stop at (seconds, -1 for whole log) +end_time: -1 + # Plant properties use_springs: true use_floating_base: true diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index d75c3a626b..65643554f7 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -3,6 +3,9 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" +# Log time to stop at (seconds, -1 for whole log) +end_time: -1 + # Plant properties use_springs: true use_floating_base: true From 8dfe3f5b6a30fd97a9d5567119c9f3f02f6bca2f Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 12:08:15 -0400 Subject: [PATCH 137/758] merging with master --- .../osc_run/osc_running_qp_settings.yaml | 1 + examples/Cassie/run_osc_hopping_controller.cc | 7 +- examples/Cassie/run_osc_jumping_controller.cc | 6 +- examples/Cassie/run_osc_running_controller.cc | 10 ++- .../Cassie/run_osc_standing_controller.cc | 5 +- examples/Cassie/run_osc_walking_controller.cc | 5 +- .../Cassie/run_osc_walking_controller_alip.cc | 5 +- .../run_joint_space_walking_controller.cc | 8 +- solvers/fast_osqp_solver.cc | 73 +------------------ solvers/fast_osqp_solver.h | 5 +- .../osc/operational_space_control.cc | 2 +- .../osc/operational_space_control.h | 2 +- 12 files changed, 24 insertions(+), 105 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 7ec5059213..c63e78deb6 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -19,3 +19,4 @@ adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 +time_limit: 0 diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc index 72608badd6..6d45501866 100644 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ b/examples/Cassie/run_osc_hopping_controller.cc @@ -138,9 +138,6 @@ int DoMain(int argc, char* argv[]) { yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename)); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ int stance_state = 0; @@ -437,8 +434,10 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->SetOsqpSolverOptionsFromYaml( + FLAGS_osqp_settings); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 0ded95f1c4..c75ab3466c 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -125,9 +125,6 @@ int DoMain(int argc, char* argv[]) { /**** Convert the gains from the yaml struct to Eigen Matrices ****/ OSCJumpingGains gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( @@ -471,8 +468,9 @@ int DoMain(int argc, char* argv[]) { pelvis_rot_tracking_data.SetImpactInvariantProjection(true); pelvis_tracking_data.SetImpactInvariantProjection(true); + osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index e9104974a9..0ab9f2f181 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -142,9 +142,9 @@ int DoMain(int argc, char* argv[]) { FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); +// solvers::OSQPSettingsYaml osqp_settings = +// drake::yaml::LoadYamlFile( +// FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -466,8 +466,10 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->SetOsqpSolverOptionsFromYaml( + FLAGS_osqp_settings); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index e91ab0851e..0d35f50818 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -139,9 +139,6 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); MatrixXd K_p_com = Eigen::Map< Eigen::Matrix>( @@ -307,7 +304,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&right_hip_yaw_traj, VectorXd::Zero(1)); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); // Connect ports builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index ad87e42e88..d70ba79a82 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -94,9 +94,6 @@ int DoMain(int argc, char* argv[]) { // Read-in the parameters auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); @@ -581,7 +578,7 @@ int DoMain(int argc, char* argv[]) { "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml"); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_robot_output_input_port()); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 0c4143503a..7a4c2c4c69 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -92,9 +92,6 @@ int DoMain(int argc, char* argv[]) { // Read-in the parameters auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); if (FLAGS_spring_model) { @@ -540,7 +537,7 @@ int DoMain(int argc, char* argv[]) { osc->SetOsqpSolverOptionsFromYaml( "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml"); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_robot_output_input_port()); diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 73974ecbec..79662af514 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -96,9 +96,6 @@ int DoMain(int argc, char* argv[]) { /**** Convert the gains from the yaml struct to Eigen Matrices ****/ JointSpaceWalkingGains gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( @@ -182,9 +179,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(joint_trajs[joint_idx]->get_output_port(), osc->get_tracking_data_input_port(joint_name + "_traj")); } - + osc->SetOsqpSolverOptionsFromYaml( + FLAGS_osqp_settings); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 655ad9b82b..219c2f8448 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -2,11 +2,8 @@ #include -#include #include -#include "dairlib/lcmt_qp.hpp" - #include "drake/common/text_logging.h" #include "drake/math/eigen_sparse_triplet.h" #include "drake/solvers/mathematical_program.h" @@ -292,9 +289,8 @@ void SetDualSolution( bool FastOsqpSolver::is_available() { return true; } -void FastOsqpSolver::InitializeSolver( - const MathematicalProgram& prog, - const solvers::OSQPSettingsYaml& solver_options) { +void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, + const SolverOptions& solver_options) { // Get the cost for the QP. Eigen::SparseMatrix P_sparse; std::vector q(prog.num_vars(), 0); @@ -328,7 +324,7 @@ void FastOsqpSolver::InitializeSolver( osqp_settings_ = static_cast(c_malloc(sizeof(OSQPSettings))); osqp_set_default_settings(osqp_settings_); - SetOsqpSolverSettingsFromYaml(solver_options); + SetFastOsqpSolverSettings(solver_options, osqp_settings_); // Setup workspace. workspace_ = nullptr; @@ -340,32 +336,6 @@ void FastOsqpSolver::InitializeSolver( is_init_ = true; } -void FastOsqpSolver::SetOsqpSolverSettingsFromYaml( - const solvers::OSQPSettingsYaml& solver_options) { - osqp_settings_->rho = solver_options.rho; - osqp_settings_->sigma = solver_options.sigma; - osqp_settings_->max_iter = solver_options.max_iter; - osqp_settings_->eps_abs = solver_options.eps_abs; - osqp_settings_->eps_rel = solver_options.eps_rel; - osqp_settings_->eps_prim_inf = solver_options.eps_prim_inf; - osqp_settings_->eps_dual_inf = solver_options.eps_dual_inf; - osqp_settings_->alpha = solver_options.alpha; - - osqp_settings_->delta = solver_options.delta; - osqp_settings_->polish = solver_options.polish; - osqp_settings_->polish_refine_iter = solver_options.polish_refine_iter; - osqp_settings_->verbose = solver_options.verbose; - osqp_settings_->scaled_termination = solver_options.scaled_termination; - osqp_settings_->check_termination = solver_options.check_termination; - osqp_settings_->warm_start = solver_options.warm_start; - osqp_settings_->scaling = solver_options.scaling; - osqp_settings_->adaptive_rho = solver_options.adaptive_rho; - osqp_settings_->adaptive_rho_interval = solver_options.adaptive_rho_interval; - osqp_settings_->adaptive_rho_tolerance = - solver_options.adaptive_rho_tolerance; - osqp_settings_->adaptive_rho_fraction = solver_options.adaptive_rho_fraction; -} - void FastOsqpSolver::WarmStart(const Eigen::VectorXd& primal, const Eigen::VectorXd& dual) { std::vector x, y; @@ -424,43 +394,6 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; - if (false) { - lcmt_qp msg; - msg.n_x = prog.num_vars(); - - Eigen::MatrixXd Q(P_sparse); - - // Note: Amessage is transposed, becaues Eigen defaults to column major - for (int i = 0; i < prog.num_vars(); i++) { - msg.Q.push_back(std::vector(Q.col(i).data(), - Q.col(i).data() + prog.num_vars())); - } - msg.w = q; - - Eigen::MatrixXd A(A_sparse); - - // std::cout << A.row(68) << std::endl; - msg.n_ineq = A.rows(); - for (int i = 0; i < A.rows(); i++) { - std::vector row(A.cols()); - for (int j = 0; j < A.cols(); j++) { - row[j] = A(i, j); - } - msg.A_ineq.push_back(row); - } - - msg.ineq_lb = l; - msg.ineq_ub = u; - msg.x_lb = std::vector(prog.num_vars(), - -std::numeric_limits::infinity()); - msg.x_ub = std::vector(prog.num_vars(), - std::numeric_limits::infinity()); - - msg.n_eq = 0; - lcm::LCM lcm; - lcm.publish("QP_LOG", &msg); - } - // Solve problem. if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index 7bbd771348..ee3e52a0ab 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -2,8 +2,6 @@ #include -#include "solvers/osqp_settings_yaml.h" - #include "drake/common/drake_copyable.h" #include "drake/solvers/osqp_solver.h" #include "drake/solvers/solver_base.h" @@ -38,8 +36,7 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { //@} void InitializeSolver(const drake::solvers::MathematicalProgram&, - const solvers::OSQPSettingsYaml& solver_options); - void SetOsqpSolverSettingsFromYaml(const solvers::OSQPSettingsYaml&); + const drake::solvers::SolverOptions&); /// Solver will automatically reenable warm starting after a successful solve void DisableWarmStart() const { diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 663862ce4c..0af021cd14 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -263,7 +263,7 @@ void OperationalSpaceControl::CheckConstraintSettings() { } } -void OperationalSpaceControl::Build(const solvers::OSQPSettingsYaml& osqp_settings) { +void OperationalSpaceControl::Build() { // Checker CheckCostSettings(); CheckConstraintSettings(); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index d94866e632..2cf6be8420 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -194,7 +194,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { FindResourceOrThrow(yaml_string)).osqp_options); }; // OSC LeafSystem builder - void Build(const solvers::OSQPSettingsYaml&); + void Build(); private: // Osc checkers and constructor-related methods From 2e3f00248ee4079cd0f092a501b4606c16b43de9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 14:46:48 -0400 Subject: [PATCH 138/758] working on moving variables --- examples/Cassie/closed_loop_running_sim.cc | 5 + .../osc_running_controller_diagram.cc | 270 +++++++++--------- .../diagrams/osc_running_controller_diagram.h | 52 +++- multibody/kinematic/distance_evaluator.h | 2 +- 4 files changed, 183 insertions(+), 146 deletions(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 23def114dd..28c2b1a4db 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -34,6 +34,11 @@ int DoMain(int argc, char* argv[]) { std::make_unique>(1e-5); MultibodyPlant controller_plant = MultibodyPlant(1e-5); + // Built the Cassie MBPs + addCassieMultibody(&controller_plant, nullptr, true, + "examples/Cassie/urdf/cassie_v2_conservative.urdf", + false /*spring model*/, false /*loop closure*/); + controller_plant.Finalize(); // auto controller_context = controller_plant.CreateDefaultContext(); auto sim_diagram = builder.AddSystem( diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index bb3e079b46..f3f06cf732 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -79,38 +79,52 @@ namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::multibody::MultibodyPlant& plant, - const string& osc_gains_filename, const string& osqp_settings_filename) { + const OSCGains& osc_gains, const OSCRunningGains& osc_running_gains) + : pos_map(multibody::makeNameToPositionsMap(plant)), + vel_map(multibody::makeNameToVelocitiesMap(plant)), + act_map(multibody::makeNameToActuatorsMap(plant)), + left_toe(LeftToeFront(plant)), + left_heel(LeftToeRear(plant)), + right_toe(RightToeFront(plant)), + right_heel(RightToeRear(plant)), + view_frame( + multibody::WorldYawViewFrame(plant.GetBodyByName("pelvis"))), + left_toe_evaluator(multibody::WorldPointEvaluator( + plant, left_toe.first, left_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2})), + left_heel_evaluator(multibody::WorldPointEvaluator( + plant, left_heel.first, left_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2})), + right_toe_evaluator(multibody::WorldPointEvaluator( + plant, right_toe.first, right_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2})), + right_heel_evaluator(multibody::WorldPointEvaluator( + plant, right_heel.first, right_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2})), + left_loop(LeftLoopClosureEvaluator(plant)), + right_loop(RightLoopClosureEvaluator(plant)), + evaluators(multibody::KinematicEvaluatorSet(plant)), + left_fixed_knee_spring( + FixedJointEvaluator(plant, pos_map.at("knee_joint_left"), + vel_map.at("knee_joint_leftdot"), 0)), + right_fixed_knee_spring( + FixedJointEvaluator(plant, pos_map.at("knee_joint_right"), + vel_map.at("knee_joint_rightdot"), 0)), + left_fixed_ankle_spring( + FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_left"), + vel_map.at("ankle_spring_joint_leftdot"), 0)), + right_fixed_ankle_spring( + FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_right"), + vel_map.at("ankle_spring_joint_rightdot"), 0)), + osc_gains_(osc_gains), + osc_running_gains_(osc_running_gains) + +{ + std::cout << " here : " << std::endl; + // Build the controller diagram DiagramBuilder builder; - - // Built the Cassie MBPs - addCassieMultibody(&plant, nullptr, true, - "examples/Cassie/urdf/cassie_v2_conservative.urdf", - false /*spring model*/, false /*loop closure*/); - plant.Finalize(); - plant_context = plant.CreateDefaultContext(); - - // Get contact frames and position - auto left_toe = LeftToeFront(plant); - auto left_heel = LeftToeRear(plant); - auto right_toe = RightToeFront(plant); - auto right_heel = RightToeRear(plant); - - int nv = plant.num_velocities(); - - // Create maps for joints - map pos_map = multibody::makeNameToPositionsMap(plant); - map vel_map = multibody::makeNameToVelocitiesMap(plant); - map act_map = multibody::makeNameToActuatorsMap(plant); - - std::cout << "state size : " << std::endl; - std::cout << plant.num_positions() + plant.num_velocities() << std::endl; - - std::unordered_map< - int, std::vector&>>> - feet_contact_points; feet_contact_points[0] = std::vector< std::pair&>>( {left_toe, left_heel}); @@ -118,34 +132,34 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( std::pair&>>( {right_toe, right_heel}); - /**** Get trajectory from optimization ****/ - + std::cout << " here : " << std::endl; /**** OSC Gains ****/ drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; - OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gains_filename), {}, {}, yaml_options); - OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gains_filename)); - solvers::OSQPSettingsYaml osqp_settings = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(osqp_settings_filename)); - /**** FSM and contact mode configuration ****/ int left_stance_state = 0; int right_stance_state = 1; int right_touchdown_air_phase = 2; int left_touchdown_air_phase = 3; - vector fsm_states = {left_stance_state, right_touchdown_air_phase, - right_stance_state, left_touchdown_air_phase, - left_stance_state}; - - vector state_durations = { - osc_gains.stance_duration, osc_gains.flight_duration, - osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; - vector accumulated_state_durations; + fsm_states = vector(); + fsm_states.push_back(left_stance_state); + fsm_states.push_back(right_touchdown_air_phase); + fsm_states.push_back(right_stance_state); + fsm_states.push_back(left_touchdown_air_phase); + fsm_states.push_back(left_stance_state); + + state_durations = vector(); + state_durations.push_back(osc_running_gains_.stance_duration); + state_durations.push_back(osc_running_gains_.flight_duration); + state_durations.push_back(osc_running_gains_.stance_duration); + state_durations.push_back(osc_running_gains_.flight_duration); + state_durations.push_back(0.0); + // vector state_durations = { + // osc_running_gains_.stance_duration, osc_running_gains_.flight_duration, + // osc_running_gains_.stance_duration, osc_running_gains_.flight_duration, 0.0}; + accumulated_state_durations = vector(); accumulated_state_durations.push_back(0); std::cout << accumulated_state_durations.back() << std::endl; for (double state_duration : state_durations) { @@ -156,7 +170,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( accumulated_state_durations.pop_back(); auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, gains.impact_threshold); + plant, fsm_states, state_durations, 0.0, osc_gains_.impact_threshold); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -178,61 +192,33 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - // osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); - osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + osc->SetAccelerationCostWeights(osc_gains_.w_accel * osc_gains_.W_acceleration); + // osc->SetInputSmoothingWeights(1e-3 * osc_gains_.W_input_regularization); + osc->SetInputCostWeights(osc_gains_.w_input * osc_gains_.W_input_regularization); // osc->SetLambdaContactRegularizationWeight(1e-4 * - // gains.W_lambda_c_regularization); + // osc_gains_.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); + osc_gains_.W_lambda_h_regularization); // Soft constraint on contacts - osc->SetSoftConstraintWeight(gains.w_soft_constraint); + osc->SetSoftConstraintWeight(osc_gains_.w_soft_constraint); // Contact information for OSC - osc->SetContactFriction(gains.mu); - - const auto& pelvis = plant.GetBodyByName("pelvis"); - multibody::WorldYawViewFrame view_frame(pelvis); - auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant, left_toe.first, left_toe.second, view_frame, Matrix3d::Identity(), - Vector3d::Zero(), {1, 2}); - auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant, left_heel.first, left_heel.second, view_frame, - Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant, right_toe.first, right_toe.second, view_frame, - Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant, right_heel.first, right_heel.second, view_frame, - Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + osc->SetContactFriction(osc_gains_.mu); + + // multibody::WorldYawViewFrame view_frame(pelvis); osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); - multibody::KinematicEvaluatorSet evaluators(plant); - auto left_loop = LeftLoopClosureEvaluator(plant); - auto right_loop = RightLoopClosureEvaluator(plant); + // multibody::KinematicEvaluatorSet evaluators(plant); + evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); // Fix the springs in the dynamics - auto pos_idx_map = multibody::makeNameToPositionsMap(plant); - auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); - auto left_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), - vel_idx_map.at("knee_joint_leftdot"), 0); - auto right_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), - vel_idx_map.at("knee_joint_rightdot"), 0); - auto left_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), - vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - auto right_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), - vel_idx_map.at("ankle_spring_joint_rightdot"), 0); evaluators.add_evaluator(&left_fixed_knee_spring); evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); @@ -249,42 +235,42 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // FLAGS_channel_cassie_out, &lcm)); cassie::osc::HighLevelCommand* high_level_command; high_level_command = builder.AddSystem( - plant, plant_context.get(), osc_gains.vel_scale_rot, - osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); + plant, plant_context.get(), osc_running_gains_.vel_scale_rot, + osc_running_gains_.vel_scale_trans_sagital, osc_running_gains_.vel_scale_trans_lateral); auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, - osc_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + osc_running_gains_.relative_pelvis); + pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains_.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, + plant, plant_context.get(), "toe_left", "pelvis", osc_running_gains_.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", - osc_gains.relative_feet, 1, accumulated_state_durations); - l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, - osc_gains.center_line_offset, - osc_gains.footstep_offset); - r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, - osc_gains.center_line_offset, - osc_gains.footstep_offset); + osc_running_gains_.relative_feet, 1, accumulated_state_durations); + l_foot_traj_generator->SetFootstepGains(osc_running_gains_.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_running_gains_.K_d_footstep); + l_foot_traj_generator->SetFootPlacementOffsets(osc_running_gains_.rest_length, + osc_running_gains_.center_line_offset, + osc_running_gains_.footstep_offset); + r_foot_traj_generator->SetFootPlacementOffsets(osc_running_gains_.rest_length, + osc_running_gains_.center_line_offset, + osc_running_gains_.footstep_offset); TransTaskSpaceTrackingData pelvis_tracking_data( - "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis, plant, plant); + "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, osc_running_gains_.K_d_pelvis, + osc_running_gains_.W_pelvis, plant, plant); TransTaskSpaceTrackingData stance_foot_tracking_data( - "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "stance_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); TransTaskSpaceTrackingData left_foot_tracking_data( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "left_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); TransTaskSpaceTrackingData right_foot_tracking_data( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "right_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); pelvis_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); pelvis_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); stance_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, @@ -301,22 +287,22 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "toe_right"); TransTaskSpaceTrackingData left_foot_yz_tracking_data( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "left_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); TransTaskSpaceTrackingData right_foot_yz_tracking_data( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "right_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); left_foot_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, "toe_left"); right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, "toe_right"); TransTaskSpaceTrackingData left_hip_tracking_data( - "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "left_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); TransTaskSpaceTrackingData right_hip_tracking_data( - "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "right_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, @@ -325,35 +311,35 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "pelvis"); TransTaskSpaceTrackingData left_hip_yz_tracking_data( - "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "left_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); TransTaskSpaceTrackingData right_hip_yz_tracking_data( - "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + "right_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant); left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, "hip_left"); right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, "hip_right"); RelativeTranslationTrackingData left_foot_rel_tracking_data( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, + "left_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant, &left_foot_tracking_data, &left_hip_tracking_data); RelativeTranslationTrackingData right_foot_rel_tracking_data( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, + "right_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, + osc_running_gains_.W_swing_foot, plant, plant, &right_foot_tracking_data, &right_hip_tracking_data); RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( - "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + "left_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, + osc_running_gains_.K_d_liftoff_swing_foot, osc_running_gains_.W_liftoff_swing_foot, plant, plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( - "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, + "right_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, + osc_running_gains_.K_d_liftoff_swing_foot, osc_running_gains_.W_liftoff_swing_foot, plant, plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( - "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, + "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, osc_running_gains_.K_d_pelvis, + osc_running_gains_.W_pelvis, plant, plant, &pelvis_tracking_data, &stance_foot_tracking_data); left_foot_rel_tracking_data.SetViewFrame(view_frame); right_foot_rel_tracking_data.SetViewFrame(view_frame); @@ -380,8 +366,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( plant_context.get()); RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, - osc_gains.W_pelvis_rot, plant, plant); + "pelvis_rot_traj", osc_running_gains_.K_p_pelvis_rot, osc_running_gains_.K_d_pelvis_rot, + osc_running_gains_.W_pelvis_rot, plant, plant); pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, "pelvis"); @@ -406,11 +392,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Swing toe joint tracking JointSpaceTrackingData left_toe_angle_tracking_data( - "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, - osc_gains.W_swing_toe, plant, plant); + "left_toe_angle_traj", osc_running_gains_.K_p_swing_toe, osc_running_gains_.K_d_swing_toe, + osc_running_gains_.W_swing_toe, plant, plant); JointSpaceTrackingData right_toe_angle_tracking_data( - "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, - osc_gains.W_swing_toe, plant, plant); + "right_toe_angle_traj", osc_running_gains_.K_p_swing_toe, osc_running_gains_.K_d_swing_toe, + osc_running_gains_.W_swing_toe, plant, plant); left_toe_angle_tracking_data.AddStateAndJointToTrack( right_stance_state, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data.AddStateAndJointToTrack( @@ -430,11 +416,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Swing hip yaw joint tracking JointSpaceTrackingData left_hip_yaw_tracking_data( - "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, - osc_gains.W_hip_yaw, plant, plant); + "hip_yaw_left_traj", osc_running_gains_.K_p_hip_yaw, osc_running_gains_.K_d_hip_yaw, + osc_running_gains_.W_hip_yaw, plant, plant); JointSpaceTrackingData right_hip_yaw_tracking_data( - "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, - osc_gains.W_hip_yaw, plant, plant); + "hip_yaw_right_traj", osc_running_gains_.K_p_hip_yaw, osc_running_gains_.K_d_hip_yaw, + osc_running_gains_.W_hip_yaw, plant, plant); left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); @@ -444,7 +430,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); // Build OSC problem - osc->Build(osqp_settings); + osc->Build(); std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index e45790d5da..a4d669476d 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -2,8 +2,16 @@ #include #include + #include +#include "examples/Cassie/osc_run/osc_running_gains.h" +#include "multibody/kinematic/distance_evaluator.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/world_point_evaluator.h" +#include "systems/controllers/osc/osc_gains.h" + #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" #include "drake/systems/framework/diagram_builder.h" @@ -13,13 +21,15 @@ namespace dairlib { namespace examples { namespace controllers { -class OSCRunningControllerDiagram : public drake::systems::Diagram { +class OSCRunningControllerDiagram final + : public drake::systems::Diagram { public: DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(OSCRunningControllerDiagram) /// @param[in] osc_gains_filename filepath containing the osc_running_gains. /// @param[in] osqp_settings filepath containing the osqp settings. - OSCRunningControllerDiagram(drake::multibody::MultibodyPlant& plant, const std::string& osc_gains_filename, + OSCRunningControllerDiagram(drake::multibody::MultibodyPlant& plant, + const std::string& osc_gains_filename, const std::string& osqp_settings_filename); /// @return the input port for the plant state. @@ -27,7 +37,8 @@ class OSCRunningControllerDiagram : public drake::systems::Diagram { return this->get_input_port(state_input_port_index_); } - /// @return the input port for the cassie_out struct (containing radio commands). + /// @return the input port for the cassie_out struct (containing radio + /// commands). const drake::systems::InputPort& get_cassie_out_input_port() const { return this->get_input_port(cassie_out_input_port_index_); } @@ -44,8 +55,43 @@ class OSCRunningControllerDiagram : public drake::systems::Diagram { } private: + std::map pos_map; + std::map vel_map; + std::map act_map; + std::pair&> + left_toe; + std::pair&> + left_heel; + std::pair&> + right_toe; + std::pair&> + right_heel; + multibody::WorldYawViewFrame view_frame; + multibody::WorldPointEvaluator left_toe_evaluator; + multibody::WorldPointEvaluator left_heel_evaluator; + multibody::WorldPointEvaluator right_toe_evaluator; + multibody::WorldPointEvaluator right_heel_evaluator; + multibody::DistanceEvaluator left_loop; + multibody::DistanceEvaluator right_loop; + std::unordered_map< + int, std::vector&>>> + feet_contact_points; + std::vector fsm_states; + std::vector state_durations; + std::vector accumulated_state_durations; std::unique_ptr> plant_context; + multibody::KinematicEvaluatorSet evaluators; + + multibody::FixedJointEvaluator left_fixed_knee_spring; + multibody::FixedJointEvaluator right_fixed_knee_spring; + multibody::FixedJointEvaluator left_fixed_ankle_spring; + multibody::FixedJointEvaluator right_fixed_ankle_spring; + + OSCGains osc_gains_; + OSCRunningGains osc_running_gains_; + const int state_input_port_index_ = 0; const int cassie_out_input_port_index_ = 1; const int control_output_port_index_ = 0; diff --git a/multibody/kinematic/distance_evaluator.h b/multibody/kinematic/distance_evaluator.h index d34dcd1f4d..490cecc40d 100644 --- a/multibody/kinematic/distance_evaluator.h +++ b/multibody/kinematic/distance_evaluator.h @@ -14,7 +14,7 @@ namespace multibody { /// The one exception is Jdotv, since Drake does not currently support /// MultibodyPlant.CalcBiasSpatialAcceleration with non-world frames, template -class DistanceEvaluator : public KinematicEvaluator { +class DistanceEvaluator final : public KinematicEvaluator { public: /// Constructor for DistanceEvaluator /// @param plant From c0f62c7dc0cf481c8b3344914cf0267d752d6c54 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 15:02:57 -0400 Subject: [PATCH 139/758] need to merge in master --- examples/Cassie/closed_loop_running_sim.cc | 11 ++++-- .../diagrams/osc_running_controller_diagram.h | 34 +++++++++++++++++-- examples/Cassie/osc_run/osc_running_gains.h | 2 ++ .../osc/operational_space_control.h | 9 ++--- 4 files changed, 47 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 28c2b1a4db..4be0eae0f8 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -1,3 +1,4 @@ +#include #include #include @@ -10,13 +11,13 @@ #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" -#include "systems/system_utils.h" namespace dairlib { using drake::multibody::MultibodyPlant; @@ -27,7 +28,7 @@ namespace examples { int DoMain(int argc, char* argv[]) { DiagramBuilder builder; std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; - std::string osc_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; + std::string osc_gains_filename = "examples/Cassie/osc_run/osc_running_gains.yaml"; std::string osqp_settings = "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; std::unique_ptr> plant = @@ -44,9 +45,13 @@ int DoMain(int argc, char* argv[]) { auto sim_diagram = builder.AddSystem( std::move(plant), urdf, 0.4, 1e4, 1e2); MultibodyPlant& new_plant = sim_diagram->get_plant(); + drake::yaml::YamlReadArchive::Options yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + OSCGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(osc_gains_filename), {}, {}, yaml_options); + OSCRunningGains osc_running_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(osc_gains_filename)); auto controller_diagram = builder.AddSystem( - controller_plant, osc_gains, osqp_settings); + controller_plant, osc_gains, osc_running_gains); builder.Connect(controller_diagram->get_control_output_port(), sim_diagram->get_actuation_input_port()); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index a4d669476d..aab3a33f4b 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -11,6 +11,11 @@ #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/kinematic/world_point_evaluator.h" #include "systems/controllers/osc/osc_gains.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/com_tracking_data.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" @@ -21,6 +26,11 @@ namespace dairlib { namespace examples { namespace controllers { +using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::JointSpaceTrackingData; + class OSCRunningControllerDiagram final : public drake::systems::Diagram { public: @@ -29,8 +39,7 @@ class OSCRunningControllerDiagram final /// @param[in] osc_gains_filename filepath containing the osc_running_gains. /// @param[in] osqp_settings filepath containing the osqp settings. OSCRunningControllerDiagram(drake::multibody::MultibodyPlant& plant, - const std::string& osc_gains_filename, - const std::string& osqp_settings_filename); + const OSCGains& osc_gains, const OSCRunningGains& osc_running_gains); /// @return the input port for the plant state. const drake::systems::InputPort& get_state_input_port() const { @@ -89,6 +98,27 @@ class OSCRunningControllerDiagram final multibody::FixedJointEvaluator left_fixed_ankle_spring; multibody::FixedJointEvaluator right_fixed_ankle_spring; + std::unique_ptr pelvis_tracking_data; + std::unique_ptr stance_foot_tracking_data; + std::unique_ptr left_foot_tracking_data; + std::unique_ptr right_foot_tracking_data; + std::unique_ptr left_foot_yz_tracking_data; + std::unique_ptr right_foot_yz_tracking_data; + std::unique_ptr left_hip_tracking_data; + std::unique_ptr right_hip_tracking_data; + std::unique_ptr left_hip_yz_tracking_data; + std::unique_ptr right_hip_yz_tracking_data; + std::unique_ptr left_foot_rel_tracking_data; + std::unique_ptr right_foot_rel_tracking_data; + std::unique_ptr left_foot_yz_rel_tracking_data; + std::unique_ptr right_foot_yz_rel_tracking_data; + std::unique_ptr pelvis_trans_rel_tracking_data; + std::unique_ptr pelvis_rot_tracking_data; + std::unique_ptr left_toe_angle_tracking_data; + std::unique_ptr right_toe_angle_tracking_data; + std::unique_ptr left_hip_yaw_tracking_data; + std::unique_ptr right_hip_yaw_tracking_data; + OSCGains osc_gains_; OSCRunningGains osc_running_gains_; diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index b10a41da23..8e31363f34 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -1,3 +1,5 @@ +#pragma once + #include "systems/controllers/osc/osc_gains.h" #include "yaml-cpp/yaml.h" diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index ce33e727c6..ffe51c2062 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -173,11 +173,11 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void AddConstTrackingData( OscTrackingData* tracking_data, const Eigen::VectorXd& v, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); - std::vector* GetAllTrackingData() { + std::vector>* GetAllTrackingData() { return tracking_data_vec_.get(); } OscTrackingData* GetTrackingDataByIndex(int index) { - return tracking_data_vec_->at(index); + return tracking_data_vec_->at(index).get(); } // Optional features @@ -372,8 +372,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { mutable std::unordered_map initial_guess_y_ = {}; // OSC tracking data (stored as a pointer because of caching) - std::unique_ptr> tracking_data_vec_ = - std::make_unique>(); + std::unique_ptr>> + tracking_data_vec_ = + std::make_unique>>(); // Fixed position of constant trajectories std::vector fixed_position_vec_; From f542329d0ab50313143e416830bf2f1a8692129c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 15:43:31 -0400 Subject: [PATCH 140/758] diagram finally runs, bug in toe traj --- examples/Cassie/closed_loop_running_sim.cc | 2 + .../Cassie/diagrams/cassie_sim_diagram.cc | 5 +- .../osc_running_controller_diagram.cc | 345 +++++++++--------- .../diagrams/osc_running_controller_diagram.h | 30 +- .../osc/operational_space_control.cc | 22 +- .../osc/operational_space_control.h | 4 +- systems/controllers/osc/osc_tracking_data.h | 2 + .../filters/floating_base_velocity_filter.h | 2 +- systems/filters/output_vector_filter.cc | 2 +- systems/filters/output_vector_filter.h | 4 +- systems/primitives/radio_parser.cc | 9 +- 11 files changed, 226 insertions(+), 201 deletions(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 4be0eae0f8..f724a61fc7 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -60,6 +60,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(sim_diagram->get_cassie_out_output_port_index(), controller_diagram->get_cassie_out_input_port()); + auto diagram = builder.Build(); diagram->set_name("cassie_running_gym"); DrawAndSaveDiagramGraph(*diagram); @@ -79,6 +80,7 @@ int DoMain(int argc, char* argv[]) { // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; simulator.AdvanceTo(5.0); + return 0; } }} diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index e8ee20dfd7..21c5a14481 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -25,6 +25,7 @@ #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/primitives/discrete_time_delay.h" +#include "drake/geometry/drake_visualizer.h" namespace dairlib { namespace examples { @@ -38,7 +39,7 @@ using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; - +using drake::geometry::DrakeVisualizer; using drake::math::RotationMatrix; using Eigen::Matrix3d; using Eigen::Vector3d; @@ -111,7 +112,7 @@ CassieSimDiagram::CassieSimDiagram( builder.ExportOutput(state_sender->get_output_port(0), "x, u, t"); builder.ExportOutput(sensor_aggregator_->get_output_port(0), "lcmt_cassie_out"); - + DrakeVisualizer::AddToBuilder(&builder, *scene_graph_); builder.BuildInto(this); this->set_name("cassie_sim_diagram"); DrawAndSaveDiagramGraph(*this); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index f3f06cf732..c8cdba0d72 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -78,8 +78,8 @@ namespace examples { namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( - drake::multibody::MultibodyPlant& plant, - const OSCGains& osc_gains, const OSCRunningGains& osc_running_gains) + drake::multibody::MultibodyPlant& plant, const OSCGains& osc_gains, + const OSCRunningGains& osc_running_gains) : pos_map(multibody::makeNameToPositionsMap(plant)), vel_map(multibody::makeNameToVelocitiesMap(plant)), act_map(multibody::makeNameToActuatorsMap(plant)), @@ -87,6 +87,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( left_heel(LeftToeRear(plant)), right_toe(RightToeFront(plant)), right_heel(RightToeRear(plant)), + left_foot_points({left_toe, left_heel}), + right_foot_points({right_toe, right_heel}), view_frame( multibody::WorldYawViewFrame(plant.GetBodyByName("pelvis"))), left_toe_evaluator(multibody::WorldPointEvaluator( @@ -117,10 +119,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_right"), vel_map.at("ankle_spring_joint_rightdot"), 0)), osc_gains_(osc_gains), - osc_running_gains_(osc_running_gains) - -{ - std::cout << " here : " << std::endl; + osc_running_gains_(osc_running_gains){ // Build the controller diagram DiagramBuilder builder; @@ -132,7 +131,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( std::pair&>>( {right_toe, right_heel}); - std::cout << " here : " << std::endl; /**** OSC Gains ****/ drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; @@ -156,9 +154,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( state_durations.push_back(osc_running_gains_.stance_duration); state_durations.push_back(osc_running_gains_.flight_duration); state_durations.push_back(0.0); - // vector state_durations = { - // osc_running_gains_.stance_duration, osc_running_gains_.flight_duration, - // osc_running_gains_.stance_duration, osc_running_gains_.flight_duration, 0.0}; + accumulated_state_durations = vector(); accumulated_state_durations.push_back(0); std::cout << accumulated_state_durations.back() << std::endl; @@ -192,13 +188,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_gains_.w_accel * osc_gains_.W_acceleration); - // osc->SetInputSmoothingWeights(1e-3 * osc_gains_.W_input_regularization); - osc->SetInputCostWeights(osc_gains_.w_input * osc_gains_.W_input_regularization); - // osc->SetLambdaContactRegularizationWeight(1e-4 * - // osc_gains_.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - osc_gains_.W_lambda_h_regularization); + osc->SetAccelerationCostWeights(osc_gains_.w_accel * + osc_gains_.W_acceleration); + osc->SetInputCostWeights(osc_gains_.w_input * + osc_gains_.W_input_regularization); + osc->SetLambdaHolonomicRegularizationWeight( + 1e-5 * osc_gains_.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(osc_gains_.w_soft_constraint); @@ -206,15 +201,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Contact information for OSC osc->SetContactFriction(osc_gains_.mu); - // multibody::WorldYawViewFrame view_frame(pelvis); - osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); - // multibody::KinematicEvaluatorSet evaluators(plant); - evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); @@ -236,7 +227,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( cassie::osc::HighLevelCommand* high_level_command; high_level_command = builder.AddSystem( plant, plant_context.get(), osc_running_gains_.vel_scale_rot, - osc_running_gains_.vel_scale_trans_sagital, osc_running_gains_.vel_scale_trans_lateral); + osc_running_gains_.vel_scale_trans_sagital, + osc_running_gains_.vel_scale_trans_lateral); auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = @@ -245,144 +237,159 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains_.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains_.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", osc_running_gains_.relative_feet, - 0, accumulated_state_durations); + plant, plant_context.get(), "toe_left", "pelvis", + osc_running_gains_.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", osc_running_gains_.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_running_gains_.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains_.K_d_footstep); - l_foot_traj_generator->SetFootPlacementOffsets(osc_running_gains_.rest_length, - osc_running_gains_.center_line_offset, - osc_running_gains_.footstep_offset); - r_foot_traj_generator->SetFootPlacementOffsets(osc_running_gains_.rest_length, - osc_running_gains_.center_line_offset, - osc_running_gains_.footstep_offset); - - TransTaskSpaceTrackingData pelvis_tracking_data( - "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, osc_running_gains_.K_d_pelvis, - osc_running_gains_.W_pelvis, plant, plant); - TransTaskSpaceTrackingData stance_foot_tracking_data( - "stance_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData left_foot_tracking_data( - "left_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_foot_tracking_data( - "right_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - pelvis_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); - pelvis_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); - stance_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, - "toe_left"); - stance_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, - "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, - "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, - "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, - "toe_right"); - - TransTaskSpaceTrackingData left_foot_yz_tracking_data( - "left_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_foot_yz_tracking_data( - "right_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - left_foot_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + l_foot_traj_generator->SetFootPlacementOffsets( + osc_running_gains_.rest_length, osc_running_gains_.center_line_offset, + osc_running_gains_.footstep_offset); + r_foot_traj_generator->SetFootPlacementOffsets( + osc_running_gains_.rest_length, osc_running_gains_.center_line_offset, + osc_running_gains_.footstep_offset); + + pelvis_tracking_data = std::make_unique( + "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, + osc_running_gains_.K_d_pelvis, osc_running_gains_.W_pelvis, plant, plant); + stance_foot_tracking_data = std::make_unique( + "stance_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + left_foot_tracking_data = std::make_unique( + "left_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + right_foot_tracking_data = std::make_unique( + "right_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + pelvis_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); + stance_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, "toe_left"); - right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "toe_right"); - - TransTaskSpaceTrackingData left_hip_tracking_data( - "left_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_hip_tracking_data( - "right_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + stance_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, + "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, + "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, + "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + "toe_right"); + + left_foot_yz_tracking_data = std::make_unique( + "left_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + right_foot_yz_tracking_data = std::make_unique( + "right_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + left_foot_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + "toe_left"); + right_foot_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + "toe_right"); + + left_hip_tracking_data = std::make_unique( + "left_hip_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + right_hip_tracking_data = std::make_unique( + "right_hip_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, "pelvis"); - left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); - - TransTaskSpaceTrackingData left_hip_yz_tracking_data( - "left_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_hip_yz_tracking_data( - "right_hip_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant); - left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + + left_hip_yz_tracking_data = std::make_unique( + "left_hip_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + right_hip_yz_tracking_data = std::make_unique( + "right_hip_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + plant); + left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "hip_left"); - right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, "hip_right"); - RelativeTranslationTrackingData left_foot_rel_tracking_data( - "left_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant, &left_foot_tracking_data, - &left_hip_tracking_data); - RelativeTranslationTrackingData right_foot_rel_tracking_data( - "right_ft_traj", osc_running_gains_.K_p_swing_foot, osc_running_gains_.K_d_swing_foot, - osc_running_gains_.W_swing_foot, plant, plant, &right_foot_tracking_data, - &right_hip_tracking_data); - RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( - "left_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, - osc_running_gains_.K_d_liftoff_swing_foot, osc_running_gains_.W_liftoff_swing_foot, plant, - plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); - RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( - "right_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, - osc_running_gains_.K_d_liftoff_swing_foot, osc_running_gains_.W_liftoff_swing_foot, plant, - plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); - RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( - "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, osc_running_gains_.K_d_pelvis, - osc_running_gains_.W_pelvis, plant, plant, &pelvis_tracking_data, - &stance_foot_tracking_data); - left_foot_rel_tracking_data.SetViewFrame(view_frame); - right_foot_rel_tracking_data.SetViewFrame(view_frame); - left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); - right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); - pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); - - left_foot_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - - osc->AddTrackingData(&pelvis_trans_rel_tracking_data); - osc->AddTrackingData(&left_foot_rel_tracking_data); - osc->AddTrackingData(&right_foot_rel_tracking_data); - osc->AddTrackingData(&left_foot_yz_rel_tracking_data); - osc->AddTrackingData(&right_foot_yz_rel_tracking_data); - + left_foot_rel_tracking_data = + std::make_unique( + "left_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, + plant, plant, left_foot_tracking_data.get(), left_hip_tracking_data.get()); + right_foot_rel_tracking_data = + std::make_unique( + "right_ft_traj", osc_running_gains_.K_p_swing_foot, + osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, + plant, plant, right_foot_tracking_data.get(), right_hip_tracking_data.get()); + left_foot_yz_rel_tracking_data = + std::make_unique( + "left_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, + osc_running_gains_.K_d_liftoff_swing_foot, + osc_running_gains_.W_liftoff_swing_foot, plant, plant, + left_foot_yz_tracking_data.get(), left_hip_yz_tracking_data.get()); + right_foot_yz_rel_tracking_data = + std::make_unique( + "right_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, + osc_running_gains_.K_d_liftoff_swing_foot, + osc_running_gains_.W_liftoff_swing_foot, plant, plant, + right_foot_yz_tracking_data.get(), right_hip_yz_tracking_data.get()); + pelvis_trans_rel_tracking_data = + std::make_unique( + "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, + osc_running_gains_.K_d_pelvis, osc_running_gains_.W_pelvis, plant, + plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); + left_foot_rel_tracking_data->SetViewFrame(view_frame); + right_foot_rel_tracking_data->SetViewFrame(view_frame); + left_foot_yz_rel_tracking_data->SetViewFrame(view_frame); + right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); + pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); + + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); + +// std::cout << "here: " << std::endl; + osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); + +// std::cout << "here 1: " << std::endl; auto heading_traj_generator = builder.AddSystem(plant, plant_context.get()); - RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_traj", osc_running_gains_.K_p_pelvis_rot, osc_running_gains_.K_d_pelvis_rot, - osc_running_gains_.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, + pelvis_rot_tracking_data = std::make_unique( + "pelvis_rot_traj", osc_running_gains_.K_p_pelvis_rot, + osc_running_gains_.K_d_pelvis_rot, osc_running_gains_.W_pelvis_rot, plant, + plant); + pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_touchdown_air_phase, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_touchdown_air_phase, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_touchdown_air_phase, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_touchdown_air_phase, "pelvis"); - pelvis_rot_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&pelvis_rot_tracking_data); + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); // Swing toe joint trajectory - vector&>> left_foot_points = { - left_heel, left_toe}; - vector&>> right_foot_points = { - right_heel, right_toe}; +// vector&>> left_foot_points = { +// left_heel, left_toe}; +// vector&>> right_foot_points = { +// right_heel, right_toe}; auto left_toe_angle_traj_gen = builder.AddSystem( plant, plant_context.get(), pos_map["toe_left"], left_foot_points, "left_toe_angle_traj"); @@ -391,43 +398,47 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_toe_angle_traj"); // Swing toe joint tracking - JointSpaceTrackingData left_toe_angle_tracking_data( - "left_toe_angle_traj", osc_running_gains_.K_p_swing_toe, osc_running_gains_.K_d_swing_toe, - osc_running_gains_.W_swing_toe, plant, plant); - JointSpaceTrackingData right_toe_angle_tracking_data( - "right_toe_angle_traj", osc_running_gains_.K_p_swing_toe, osc_running_gains_.K_d_swing_toe, - osc_running_gains_.W_swing_toe, plant, plant); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data = std::make_unique( + "left_toe_angle_traj", osc_running_gains_.K_p_swing_toe, + osc_running_gains_.K_d_swing_toe, osc_running_gains_.W_swing_toe, plant, + plant); + right_toe_angle_tracking_data = std::make_unique( + "right_toe_angle_traj", osc_running_gains_.K_p_swing_toe, + osc_running_gains_.K_d_swing_toe, osc_running_gains_.W_swing_toe, plant, + plant); + left_toe_angle_tracking_data->AddStateAndJointToTrack( right_stance_state, "toe_left", "toe_leftdot"); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data->AddStateAndJointToTrack( right_touchdown_air_phase, "toe_left", "toe_leftdot"); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data->AddStateAndJointToTrack( left_touchdown_air_phase, "toe_left", "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( left_stance_state, "toe_right", "toe_rightdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( right_touchdown_air_phase, "toe_right", "toe_rightdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( left_touchdown_air_phase, "toe_right", "toe_rightdot"); - left_toe_angle_tracking_data.SetImpactInvariantProjection(true); - right_toe_angle_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_toe_angle_tracking_data); - osc->AddTrackingData(&right_toe_angle_tracking_data); + left_toe_angle_tracking_data->SetImpactInvariantProjection(true); + right_toe_angle_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); // Swing hip yaw joint tracking - JointSpaceTrackingData left_hip_yaw_tracking_data( - "hip_yaw_left_traj", osc_running_gains_.K_p_hip_yaw, osc_running_gains_.K_d_hip_yaw, - osc_running_gains_.W_hip_yaw, plant, plant); - JointSpaceTrackingData right_hip_yaw_tracking_data( - "hip_yaw_right_traj", osc_running_gains_.K_p_hip_yaw, osc_running_gains_.K_d_hip_yaw, - osc_running_gains_.W_hip_yaw, plant, plant); - left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); - right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", + left_hip_yaw_tracking_data = std::make_unique( + "hip_yaw_left_traj", osc_running_gains_.K_p_hip_yaw, + osc_running_gains_.K_d_hip_yaw, osc_running_gains_.W_hip_yaw, plant, + plant); + right_hip_yaw_tracking_data = std::make_unique( + "hip_yaw_right_traj", osc_running_gains_.K_p_hip_yaw, + osc_running_gains_.K_d_hip_yaw, osc_running_gains_.W_hip_yaw, plant, + plant); + left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); - osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); // Build OSC problem osc->Build(); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index aab3a33f4b..4ff7b50cd0 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -10,12 +10,12 @@ #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/kinematic/world_point_evaluator.h" -#include "systems/controllers/osc/osc_gains.h" -#include "systems/controllers/osc/trans_space_tracking_data.h" -#include "systems/controllers/osc/rot_space_tracking_data.h" -#include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/com_tracking_data.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/osc_gains.h" #include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" @@ -26,10 +26,10 @@ namespace dairlib { namespace examples { namespace controllers { -using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::JointSpaceTrackingData; using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; -using systems::controllers::JointSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; class OSCRunningControllerDiagram final : public drake::systems::Diagram { @@ -39,7 +39,8 @@ class OSCRunningControllerDiagram final /// @param[in] osc_gains_filename filepath containing the osc_running_gains. /// @param[in] osqp_settings filepath containing the osqp settings. OSCRunningControllerDiagram(drake::multibody::MultibodyPlant& plant, - const OSCGains& osc_gains, const OSCRunningGains& osc_running_gains); + const OSCGains& osc_gains, + const OSCRunningGains& osc_running_gains); /// @return the input port for the plant state. const drake::systems::InputPort& get_state_input_port() const { @@ -75,6 +76,12 @@ class OSCRunningControllerDiagram final right_toe; std::pair&> right_heel; + std::vector< + std::pair&>> + left_foot_points; + std::vector< + std::pair&>> + right_foot_points; multibody::WorldYawViewFrame view_frame; multibody::WorldPointEvaluator left_toe_evaluator; multibody::WorldPointEvaluator left_heel_evaluator; @@ -110,9 +117,12 @@ class OSCRunningControllerDiagram final std::unique_ptr right_hip_yz_tracking_data; std::unique_ptr left_foot_rel_tracking_data; std::unique_ptr right_foot_rel_tracking_data; - std::unique_ptr left_foot_yz_rel_tracking_data; - std::unique_ptr right_foot_yz_rel_tracking_data; - std::unique_ptr pelvis_trans_rel_tracking_data; + std::unique_ptr + left_foot_yz_rel_tracking_data; + std::unique_ptr + right_foot_yz_rel_tracking_data; + std::unique_ptr + pelvis_trans_rel_tracking_data; std::unique_ptr pelvis_rot_tracking_data; std::unique_ptr left_toe_angle_tracking_data; std::unique_ptr right_toe_angle_tracking_data; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 0af021cd14..4602d0fa94 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -210,16 +210,16 @@ void OperationalSpaceControl::AddKinematicConstraint( } // Tracking data methods -void OperationalSpaceControl::AddTrackingData(OscTrackingData* tracking_data, +void OperationalSpaceControl::AddTrackingData(std::unique_ptr tracking_data, double t_lb, double t_ub) { - tracking_data_vec_->push_back(tracking_data); + tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(VectorXd::Zero(0)); t_s_vec_.push_back(t_lb); t_e_vec_.push_back(t_ub); // Construct input ports and add element to traj_name_to_port_index_map_ if // the port for the traj is not created yet - string traj_name = tracking_data->GetName(); + string traj_name = tracking_data_vec_->back()->GetName(); if (traj_name_to_port_index_map_.find(traj_name) == traj_name_to_port_index_map_.end()) { PiecewisePolynomial pp = PiecewisePolynomial(); @@ -232,9 +232,9 @@ void OperationalSpaceControl::AddTrackingData(OscTrackingData* tracking_data, } } void OperationalSpaceControl::AddConstTrackingData( - OscTrackingData* tracking_data, const VectorXd& v, double t_lb, + std::unique_ptr tracking_data, const VectorXd& v, double t_lb, double t_ub) { - tracking_data_vec_->push_back(tracking_data); + tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(v); t_s_vec_.push_back(t_lb); t_e_vec_.push_back(t_ub); @@ -267,7 +267,7 @@ void OperationalSpaceControl::Build() { // Checker CheckCostSettings(); CheckConstraintSettings(); - for (auto tracking_data : *tracking_data_vec_) { + for (auto& tracking_data : *tracking_data_vec_) { tracking_data->CheckOscTrackingData(); DRAKE_DEMAND(&tracking_data->plant_w_spr() == &plant_w_spr_); DRAKE_DEMAND(&tracking_data->plant_wo_spr() == &plant_wo_spr_); @@ -641,7 +641,7 @@ VectorXd OperationalSpaceControl::SolveQp( // Update costs // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { - auto tracking_data = tracking_data_vec_->at(i); + auto tracking_data = tracking_data_vec_->at(i).get(); if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && @@ -763,7 +763,7 @@ VectorXd OperationalSpaceControl::SolveQp( solve_time_ = result.get_solver_details().run_time; - for (auto tracking_data : *tracking_data_vec_) { + for (auto& tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state)) { tracking_data->StoreYddotCommandSol(*dv_sol_); } @@ -800,7 +800,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( int active_tracking_data_dim = 0; for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { - auto tracking_data = tracking_data_vec_->at(i); + auto tracking_data = tracking_data_vec_->at(i).get(); if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { @@ -830,7 +830,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( MatrixXd A = MatrixXd::Zero(active_tracking_data_dim, active_constraint_dim); VectorXd ydot_err_vec = VectorXd::Zero(active_tracking_data_dim); int start_row = 0; - for (auto tracking_data : *tracking_data_vec_) { + for (auto& tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { A.block(start_row, 0, tracking_data->GetYdotDim(), @@ -935,7 +935,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( std::vector(tracking_data_vec_->size()); for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { - auto tracking_data = tracking_data_vec_->at(i); + auto tracking_data = tracking_data_vec_->at(i).get(); output->tracking_data_names[i] = tracking_data->GetName(); lcmt_osc_tracking_data osc_output; diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 86a10c9030..d6bd4f4af1 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -168,10 +168,10 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { /// The third argument is used to set a period in which OSC does not track the /// desired traj (the period starts when the finite state machine switches to /// a new state) - void AddTrackingData(OscTrackingData* tracking_data, double t_lb = 0, + void AddTrackingData(std::unique_ptr tracking_data, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); void AddConstTrackingData( - OscTrackingData* tracking_data, const Eigen::VectorXd& v, double t_lb = 0, + std::unique_ptr tracking_data, const Eigen::VectorXd& v, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); std::vector>* GetAllTrackingData() { return tracking_data_vec_.get(); diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index b9f68ebae5..418dde4dec 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -24,6 +24,8 @@ class OscTrackingData { const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); +// virtual ~OscTrackingData(); + // Update() updates the caches. It does the following things in order: // - updates the current fsm state // - update the actual outputs diff --git a/systems/filters/floating_base_velocity_filter.h b/systems/filters/floating_base_velocity_filter.h index 604d1c9db7..916e526776 100644 --- a/systems/filters/floating_base_velocity_filter.h +++ b/systems/filters/floating_base_velocity_filter.h @@ -11,7 +11,7 @@ class FloatingBaseVelocityFilter : public OutputVectorFilter { public: FloatingBaseVelocityFilter( const drake::multibody::MultibodyPlant& plant, - const std::vector& tau) + const std::vector tau) : OutputVectorFilter(plant, tau, std::vector{plant.num_positions() + 3, plant.num_positions() + 4, diff --git a/systems/filters/output_vector_filter.cc b/systems/filters/output_vector_filter.cc index 114f26660e..a0ce5cf755 100644 --- a/systems/filters/output_vector_filter.cc +++ b/systems/filters/output_vector_filter.cc @@ -11,7 +11,7 @@ namespace dairlib::systems { OutputVectorFilter::OutputVectorFilter( const drake::multibody::MultibodyPlant& plant, - const std::vector& tau, std::optional> filter_idxs) + const std::vector tau, std::optional> filter_idxs) : n_y_filt_(tau.size()), tau_(tau) { int n_y = plant.num_positions() + plant.num_velocities() + plant.num_actuators() + 3; diff --git a/systems/filters/output_vector_filter.h b/systems/filters/output_vector_filter.h index 23536263f7..69349d99dc 100644 --- a/systems/filters/output_vector_filter.h +++ b/systems/filters/output_vector_filter.h @@ -28,7 +28,7 @@ class OutputVectorFilter : public LeafSystem { // For cutoff frequency f in Hz, tau = 1/(2*pi*f) OutputVectorFilter( const drake::multibody::MultibodyPlant& plant, - const std::vector& tau, + const std::vector tau, std::optional> filter_idxs); private: @@ -41,7 +41,7 @@ class OutputVectorFilter : public LeafSystem { std::vector filter_idxs_; const int n_y_filt_; - const std::vector& tau_; // time constant + const std::vector tau_; // time constant int prev_val_idx_; int prev_time_idx_; }; diff --git a/systems/primitives/radio_parser.cc b/systems/primitives/radio_parser.cc index 1694e70bc5..329463edd8 100644 --- a/systems/primitives/radio_parser.cc +++ b/systems/primitives/radio_parser.cc @@ -17,15 +17,14 @@ RadioParser::RadioParser() { void RadioParser::CalcRadioOutput( const drake::systems::Context& context, dairlib::lcmt_radio_out* output) const { - const BasicVector& data = - *this->template EvalVectorInput(context, data_input_port_); + Eigen::VectorXd data = Eigen::VectorXd::Zero(18); +// const BasicVector& data = +// *this->template EvalVectorInput(context, data_input_port_); output->radioReceiverSignalGood = data[0]; output->receiverMedullaSignalGood = data[1]; for (int i = 0; i < 16; ++i) { - output->channel[i] = data.value()[2 + i]; - std::cout << "channel: " << i << output->channel[i] << std::endl; + output->channel[i] = data[2 + i]; } - std::cout << "here finally: " << std::endl; } } // namespace systems From bc5fc61be308bf8c9f62f51513345f385df7fd80 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 15:49:44 -0400 Subject: [PATCH 141/758] closed loop sim working in c++ test --- examples/Cassie/closed_loop_running_sim.cc | 6 +++--- examples/Cassie/diagrams/osc_running_controller_diagram.cc | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index f724a61fc7..afd414c341 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -32,9 +32,9 @@ int DoMain(int argc, char* argv[]) { std::string osqp_settings = "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; std::unique_ptr> plant = - std::make_unique>(1e-5); + std::make_unique>(8e-5); MultibodyPlant controller_plant = - MultibodyPlant(1e-5); + MultibodyPlant(8e-5); // Built the Cassie MBPs addCassieMultibody(&controller_plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", @@ -79,7 +79,7 @@ int DoMain(int argc, char* argv[]) { new_plant.SetPositionsAndVelocities(&plant_context, x_init); // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; - simulator.AdvanceTo(5.0); + simulator.AdvanceTo(20.0); return 0; } }} diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index c8cdba0d72..02b8fff874 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -87,8 +87,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( left_heel(LeftToeRear(plant)), right_toe(RightToeFront(plant)), right_heel(RightToeRear(plant)), - left_foot_points({left_toe, left_heel}), - right_foot_points({right_toe, right_heel}), + left_foot_points({left_heel, left_toe}), + right_foot_points({right_heel, right_toe}), view_frame( multibody::WorldYawViewFrame(plant.GetBodyByName("pelvis"))), left_toe_evaluator(multibody::WorldPointEvaluator( From 7678211158fc233b19fa31eaa651fe9808402bb0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 16:31:12 -0400 Subject: [PATCH 142/758] gym finally works --- bindings/pydairlib/cassie/BUILD.bazel | 16 ++ bindings/pydairlib/cassie/cassie_gym.py | 12 +- bindings/pydairlib/cassie/cassie_gym_test.py | 46 +----- bindings/pydairlib/cassie/yaml_structs_py.cc | 23 +++ examples/Cassie/closed_loop_running_sim.cc | 19 +-- .../osc_running_controller_diagram.cc | 148 +++++++++--------- .../diagrams/osc_running_controller_diagram.h | 8 +- systems/primitives/radio_parser.cc | 5 +- 8 files changed, 141 insertions(+), 136 deletions(-) create mode 100644 bindings/pydairlib/cassie/yaml_structs_py.cc diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index ed3031cc81..7bdd335250 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -29,6 +29,7 @@ py_binary( deps = [ "//bindings/pydairlib/cassie:cassie_gym", "//bindings/pydairlib/cassie:cassie", + "@drake//bindings/pydrake", ], ) @@ -85,6 +86,21 @@ pybind_py_library( py_imports = ["."], ) +pybind_py_library( + name = "dairlib_yaml_py", + cc_deps = [ + "@drake//:drake_shared_library", + "//examples/Cassie/osc_run:osc_running_gains", + ], + cc_so_name = "dairlib_yaml", + cc_srcs = ["yaml_structs_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + ":module_py", + ], + py_imports = ["."], +) + pybind_py_library( name = "simulators_py", cc_deps = [ diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index c3da4bad5f..b10ba530d5 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -39,7 +39,7 @@ def __init__(self, visualize=False): def make(self, controller, urdf): self.builder = DiagramBuilder() - self.dt = 5e-4 + self.dt = 5e-5 self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSimDiagram(self.plant, urdf, 0.8, 1e4, 1e2) @@ -72,8 +72,7 @@ def reset(self): cassie_state = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context())) - import pdb; - pdb.set_trace() + self.current_time = self.start_time return @@ -85,19 +84,20 @@ def advance_to(self, time): def get_state(self): return self.traj.get_positions()[-1] - def step(self, action=np.ones(18)): + def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt + action[5] = 1 # action = lcmt_radio_out # self.simulator.get_radio_input_port().FixValue(self.simulator_context, AbstractValue.Make(action)) self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.sim.AdvanceTo(next_timestep) - + # import pdb; pdb.set_trace() cassie_state = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context())) self.current_time = next_timestep - self.traj.update(next_timestep, cassie_state, action) + self.traj.update(next_timestep, cassie_state, action[:10]) return cassie_state def get_traj(self): diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index 65adeadf24..f4ed59cca2 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -2,50 +2,21 @@ # from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory from pydairlib.cassie.simulators import CassieSimDiagram - +from pydrake.common.yaml import yaml_load # from controllers import OSCRunningControllerFactory -def reexecute_if_unbuffered(): - """Ensures that output is immediately flushed (e.g. for segfaults). - ONLY use this at your entrypoint. Otherwise, you may have code be - re-executed that will clutter your console.""" - import os - import shlex - import sys - if os.environ.get("PYTHONUNBUFFERED") in (None, ""): - os.environ["PYTHONUNBUFFERED"] = "1" - argv = list(sys.argv) - if argv[0] != sys.executable: - argv.insert(0, sys.executable) - cmd = " ".join([shlex.quote(arg) for arg in argv]) - sys.stdout.flush() - os.execv(argv[0], argv) - - -def traced(func, ignoredirs=None): - """Decorates func such that its execution is traced, but filters out any - Python code outside of the system prefix.""" - import functools - import sys - import trace - if ignoredirs is None: - ignoredirs = ["/usr", sys.prefix] - tracer = trace.Trace(trace=1, count=0, ignoredirs=ignoredirs) - - @functools.wraps(func) - def wrapped(*args, **kwargs): - return tracer.runfunc(func, *args, **kwargs) - - return wrapped - -@traced def main(): - osc_gains = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' + # osc_gains = yaml_load(filename=osc_gains_filename) + # import pdb; pdb.set_trace() - controller = OSCRunningControllerFactory(osc_gains, osqp_settings) + controller_plant = MultibodyPlant(1e-5) + addCassieMultibody(controller_plant, None, True, urdf, False, False) + controller_plant.Finalize() + controller = OSCRunningControllerFactory(controller_plant, osc_gains_filename, osqp_settings) gym_env = CassieGym(visualize=True) gym_env.make(controller, urdf) @@ -53,5 +24,4 @@ def main(): if __name__ == '__main__': - reexecute_if_unbuffered() main() diff --git a/bindings/pydairlib/cassie/yaml_structs_py.cc b/bindings/pydairlib/cassie/yaml_structs_py.cc new file mode 100644 index 0000000000..346f719a49 --- /dev/null +++ b/bindings/pydairlib/cassie/yaml_structs_py.cc @@ -0,0 +1,23 @@ +#include +#include +#include +#include +#include "examples/Cassie/osc_run/osc_running_gains.h" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +PYBIND11_MODULE(dairlib_yaml, m) { + m.doc() = "Binding controller factories for Cassie"; + + using py_rvp = py::return_value_policy; + + py::class_(m, "OSCGains") + .def(py::init<>()); + py::class_(m, "OSCRunningGains") + .def(py::init<>()); +} +} // namespace pydairlib +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index afd414c341..28c2b1a4db 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -1,4 +1,3 @@ -#include #include #include @@ -11,13 +10,13 @@ #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" +#include "systems/system_utils.h" namespace dairlib { using drake::multibody::MultibodyPlant; @@ -28,13 +27,13 @@ namespace examples { int DoMain(int argc, char* argv[]) { DiagramBuilder builder; std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; - std::string osc_gains_filename = "examples/Cassie/osc_run/osc_running_gains.yaml"; + std::string osc_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; std::string osqp_settings = "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; std::unique_ptr> plant = - std::make_unique>(8e-5); + std::make_unique>(1e-5); MultibodyPlant controller_plant = - MultibodyPlant(8e-5); + MultibodyPlant(1e-5); // Built the Cassie MBPs addCassieMultibody(&controller_plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", @@ -45,13 +44,9 @@ int DoMain(int argc, char* argv[]) { auto sim_diagram = builder.AddSystem( std::move(plant), urdf, 0.4, 1e4, 1e2); MultibodyPlant& new_plant = sim_diagram->get_plant(); - drake::yaml::YamlReadArchive::Options yaml_options; - yaml_options.allow_yaml_with_no_cpp = true; - OSCGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(osc_gains_filename), {}, {}, yaml_options); - OSCRunningGains osc_running_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(osc_gains_filename)); auto controller_diagram = builder.AddSystem( - controller_plant, osc_gains, osc_running_gains); + controller_plant, osc_gains, osqp_settings); builder.Connect(controller_diagram->get_control_output_port(), sim_diagram->get_actuation_input_port()); @@ -60,7 +55,6 @@ int DoMain(int argc, char* argv[]) { builder.Connect(sim_diagram->get_cassie_out_output_port_index(), controller_diagram->get_cassie_out_input_port()); - auto diagram = builder.Build(); diagram->set_name("cassie_running_gym"); DrawAndSaveDiagramGraph(*diagram); @@ -79,8 +73,7 @@ int DoMain(int argc, char* argv[]) { new_plant.SetPositionsAndVelocities(&plant_context, x_init); // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; - simulator.AdvanceTo(20.0); - return 0; + simulator.AdvanceTo(5.0); } }} diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 02b8fff874..9f5d7cc116 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -78,8 +78,8 @@ namespace examples { namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( - drake::multibody::MultibodyPlant& plant, const OSCGains& osc_gains, - const OSCRunningGains& osc_running_gains) + drake::multibody::MultibodyPlant& plant, + const string& osc_gainsfilename, const string& osqp_settings_filename) : pos_map(multibody::makeNameToPositionsMap(plant)), vel_map(multibody::makeNameToVelocitiesMap(plant)), act_map(multibody::makeNameToActuatorsMap(plant)), @@ -117,9 +117,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( vel_map.at("ankle_spring_joint_leftdot"), 0)), right_fixed_ankle_spring( FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_right"), - vel_map.at("ankle_spring_joint_rightdot"), 0)), - osc_gains_(osc_gains), - osc_running_gains_(osc_running_gains){ + vel_map.at("ankle_spring_joint_rightdot"), 0)){ // Build the controller diagram DiagramBuilder builder; @@ -135,6 +133,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; + OSCGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_gainsfilename), {}, {}, yaml_options); + OSCRunningGains osc_running_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_gainsfilename)); + /**** FSM and contact mode configuration ****/ int left_stance_state = 0; int right_stance_state = 1; @@ -149,10 +152,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( fsm_states.push_back(left_stance_state); state_durations = vector(); - state_durations.push_back(osc_running_gains_.stance_duration); - state_durations.push_back(osc_running_gains_.flight_duration); - state_durations.push_back(osc_running_gains_.stance_duration); - state_durations.push_back(osc_running_gains_.flight_duration); + state_durations.push_back(osc_running_gains.stance_duration); + state_durations.push_back(osc_running_gains.flight_duration); + state_durations.push_back(osc_running_gains.stance_duration); + state_durations.push_back(osc_running_gains.flight_duration); state_durations.push_back(0.0); accumulated_state_durations = vector(); @@ -166,7 +169,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( accumulated_state_durations.pop_back(); auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, osc_gains_.impact_threshold); + plant, fsm_states, state_durations, 0.0, osc_gains.impact_threshold); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -188,18 +191,18 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_gains_.w_accel * - osc_gains_.W_acceleration); - osc->SetInputCostWeights(osc_gains_.w_input * - osc_gains_.W_input_regularization); + osc->SetAccelerationCostWeights(osc_gains.w_accel * + osc_gains.W_acceleration); + osc->SetInputCostWeights(osc_gains.w_input * + osc_gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight( - 1e-5 * osc_gains_.W_lambda_h_regularization); + 1e-5 * osc_gains.W_lambda_h_regularization); // Soft constraint on contacts - osc->SetSoftConstraintWeight(osc_gains_.w_soft_constraint); + osc->SetSoftConstraintWeight(osc_gains.w_soft_constraint); // Contact information for OSC - osc->SetContactFriction(osc_gains_.mu); + osc->SetContactFriction(osc_gains.mu); osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); @@ -226,45 +229,45 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // FLAGS_channel_cassie_out, &lcm)); cassie::osc::HighLevelCommand* high_level_command; high_level_command = builder.AddSystem( - plant, plant_context.get(), osc_running_gains_.vel_scale_rot, - osc_running_gains_.vel_scale_trans_sagital, - osc_running_gains_.vel_scale_trans_lateral); + plant, plant_context.get(), osc_running_gains.vel_scale_rot, + osc_running_gains.vel_scale_trans_sagital, + osc_running_gains.vel_scale_trans_lateral); auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, - osc_running_gains_.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains_.rest_length); + osc_running_gains.relative_pelvis); + pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", - osc_running_gains_.relative_feet, 0, accumulated_state_durations); + osc_running_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", - osc_running_gains_.relative_feet, 1, accumulated_state_durations); - l_foot_traj_generator->SetFootstepGains(osc_running_gains_.K_d_footstep); - r_foot_traj_generator->SetFootstepGains(osc_running_gains_.K_d_footstep); + osc_running_gains.relative_feet, 1, accumulated_state_durations); + l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains_.rest_length, osc_running_gains_.center_line_offset, - osc_running_gains_.footstep_offset); + osc_running_gains.rest_length, osc_running_gains.center_line_offset, + osc_running_gains.footstep_offset); r_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains_.rest_length, osc_running_gains_.center_line_offset, - osc_running_gains_.footstep_offset); + osc_running_gains.rest_length, osc_running_gains.center_line_offset, + osc_running_gains.footstep_offset); pelvis_tracking_data = std::make_unique( - "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, - osc_running_gains_.K_d_pelvis, osc_running_gains_.W_pelvis, plant, plant); + "pelvis_trans_traj", osc_running_gains.K_p_pelvis, + osc_running_gains.K_d_pelvis, osc_running_gains.W_pelvis, plant, plant); stance_foot_tracking_data = std::make_unique( - "stance_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "stance_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_foot_tracking_data = std::make_unique( - "left_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "left_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); right_foot_tracking_data = std::make_unique( - "right_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "right_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); pelvis_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); pelvis_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); @@ -282,12 +285,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "toe_right"); left_foot_yz_tracking_data = std::make_unique( - "left_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "left_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); right_foot_yz_tracking_data = std::make_unique( - "right_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "right_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_foot_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "toe_left"); @@ -295,12 +298,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "toe_right"); left_hip_tracking_data = std::make_unique( - "left_hip_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "left_hip_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); right_hip_tracking_data = std::make_unique( - "right_hip_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "right_hip_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); @@ -310,12 +313,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "pelvis"); left_hip_yz_tracking_data = std::make_unique( - "left_hip_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "left_hip_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); right_hip_yz_tracking_data = std::make_unique( - "right_hip_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, plant, + "right_hip_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "hip_left"); @@ -324,30 +327,30 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( left_foot_rel_tracking_data = std::make_unique( - "left_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, + "left_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant, left_foot_tracking_data.get(), left_hip_tracking_data.get()); right_foot_rel_tracking_data = std::make_unique( - "right_ft_traj", osc_running_gains_.K_p_swing_foot, - osc_running_gains_.K_d_swing_foot, osc_running_gains_.W_swing_foot, + "right_ft_traj", osc_running_gains.K_p_swing_foot, + osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), right_hip_tracking_data.get()); left_foot_yz_rel_tracking_data = std::make_unique( - "left_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, - osc_running_gains_.K_d_liftoff_swing_foot, - osc_running_gains_.W_liftoff_swing_foot, plant, plant, + "left_ft_z_traj", osc_running_gains.K_p_liftoff_swing_foot, + osc_running_gains.K_d_liftoff_swing_foot, + osc_running_gains.W_liftoff_swing_foot, plant, plant, left_foot_yz_tracking_data.get(), left_hip_yz_tracking_data.get()); right_foot_yz_rel_tracking_data = std::make_unique( - "right_ft_z_traj", osc_running_gains_.K_p_liftoff_swing_foot, - osc_running_gains_.K_d_liftoff_swing_foot, - osc_running_gains_.W_liftoff_swing_foot, plant, plant, + "right_ft_z_traj", osc_running_gains.K_p_liftoff_swing_foot, + osc_running_gains.K_d_liftoff_swing_foot, + osc_running_gains.W_liftoff_swing_foot, plant, plant, right_foot_yz_tracking_data.get(), right_hip_yz_tracking_data.get()); pelvis_trans_rel_tracking_data = std::make_unique( - "pelvis_trans_traj", osc_running_gains_.K_p_pelvis, - osc_running_gains_.K_d_pelvis, osc_running_gains_.W_pelvis, plant, + "pelvis_trans_traj", osc_running_gains.K_p_pelvis, + osc_running_gains.K_d_pelvis, osc_running_gains.W_pelvis, plant, plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); left_foot_rel_tracking_data->SetViewFrame(view_frame); right_foot_rel_tracking_data->SetViewFrame(view_frame); @@ -372,8 +375,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( plant_context.get()); pelvis_rot_tracking_data = std::make_unique( - "pelvis_rot_traj", osc_running_gains_.K_p_pelvis_rot, - osc_running_gains_.K_d_pelvis_rot, osc_running_gains_.W_pelvis_rot, plant, + "pelvis_rot_traj", osc_running_gains.K_p_pelvis_rot, + osc_running_gains.K_d_pelvis_rot, osc_running_gains.W_pelvis_rot, plant, plant); pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, @@ -399,12 +402,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Swing toe joint tracking left_toe_angle_tracking_data = std::make_unique( - "left_toe_angle_traj", osc_running_gains_.K_p_swing_toe, - osc_running_gains_.K_d_swing_toe, osc_running_gains_.W_swing_toe, plant, + "left_toe_angle_traj", osc_running_gains.K_p_swing_toe, + osc_running_gains.K_d_swing_toe, osc_running_gains.W_swing_toe, plant, plant); right_toe_angle_tracking_data = std::make_unique( - "right_toe_angle_traj", osc_running_gains_.K_p_swing_toe, - osc_running_gains_.K_d_swing_toe, osc_running_gains_.W_swing_toe, plant, + "right_toe_angle_traj", osc_running_gains.K_p_swing_toe, + osc_running_gains.K_d_swing_toe, osc_running_gains.W_swing_toe, plant, plant); left_toe_angle_tracking_data->AddStateAndJointToTrack( right_stance_state, "toe_left", "toe_leftdot"); @@ -425,12 +428,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Swing hip yaw joint tracking left_hip_yaw_tracking_data = std::make_unique( - "hip_yaw_left_traj", osc_running_gains_.K_p_hip_yaw, - osc_running_gains_.K_d_hip_yaw, osc_running_gains_.W_hip_yaw, plant, + "hip_yaw_left_traj", osc_running_gains.K_p_hip_yaw, + osc_running_gains.K_d_hip_yaw, osc_running_gains.W_hip_yaw, plant, plant); right_hip_yaw_tracking_data = std::make_unique( - "hip_yaw_right_traj", osc_running_gains_.K_p_hip_yaw, - osc_running_gains_.K_d_hip_yaw, osc_running_gains_.W_hip_yaw, plant, + "hip_yaw_right_traj", osc_running_gains.K_p_hip_yaw, + osc_running_gains.K_d_hip_yaw, osc_running_gains.W_hip_yaw, plant, plant); left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", @@ -441,6 +444,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); // Build OSC problem + osc->SetOsqpSolverOptionsFromYaml(osqp_settings_filename); osc->Build(); std::cout << "Built OSC" << std::endl; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index 4ff7b50cd0..626aed505f 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -39,8 +39,8 @@ class OSCRunningControllerDiagram final /// @param[in] osc_gains_filename filepath containing the osc_running_gains. /// @param[in] osqp_settings filepath containing the osqp settings. OSCRunningControllerDiagram(drake::multibody::MultibodyPlant& plant, - const OSCGains& osc_gains, - const OSCRunningGains& osc_running_gains); + const std::string& osc_gains_filename, + const std::string& osqp_settings_filename); /// @return the input port for the plant state. const drake::systems::InputPort& get_state_input_port() const { @@ -129,8 +129,8 @@ class OSCRunningControllerDiagram final std::unique_ptr left_hip_yaw_tracking_data; std::unique_ptr right_hip_yaw_tracking_data; - OSCGains osc_gains_; - OSCRunningGains osc_running_gains_; +// OSCGains osc_gains_; +// OSCRunningGains osc_running_gains_; const int state_input_port_index_ = 0; const int cassie_out_input_port_index_ = 1; diff --git a/systems/primitives/radio_parser.cc b/systems/primitives/radio_parser.cc index 329463edd8..8cad3488b6 100644 --- a/systems/primitives/radio_parser.cc +++ b/systems/primitives/radio_parser.cc @@ -17,9 +17,8 @@ RadioParser::RadioParser() { void RadioParser::CalcRadioOutput( const drake::systems::Context& context, dairlib::lcmt_radio_out* output) const { - Eigen::VectorXd data = Eigen::VectorXd::Zero(18); -// const BasicVector& data = -// *this->template EvalVectorInput(context, data_input_port_); + const BasicVector& data = + *this->template EvalVectorInput(context, data_input_port_); output->radioReceiverSignalGood = data[0]; output->receiverMedullaSignalGood = data[1]; for (int i = 0; i < 16; ++i) { From b16fabfa20601365bc8ef6c33b5c10cbc446541c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 16:50:43 -0400 Subject: [PATCH 143/758] running gym works, need to fix rest of files --- bindings/pydairlib/cassie/cassie_gym.py | 17 ++++++++++------- bindings/pydairlib/cassie/cassie_gym_test.py | 2 +- bindings/pydairlib/cassie/cassie_traj.py | 2 +- 3 files changed, 12 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index b10ba530d5..fc8dd3a9a8 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -17,7 +17,7 @@ class CassieGym(): def __init__(self, visualize=False): - self.sim_dt = 5e-5 + # self.sim_dt = 8e-5 self.visualize = visualize # hardware logs are 50ms long and start approximately 5ms before impact # the simulator will check to make sure ground reaction forces are first detected within 3-7ms @@ -28,10 +28,10 @@ def __init__(self, visualize=False): self.hardware_traj = None self.action_dim = 10 self.state_dim = 45 - self.x_init = np.array([1, 0, 0, 0, 0, 0, 1, - -0.0304885, 0, 0.466767, -1.15602, -0.037542, 1.45243, -0.0257992, -1.59913, - 0.0304885, 0, 0.466767, -1.15602, -0.0374859, 1.45244, -0.0259075, -1.59919, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) + self.x_init = np.array( + [1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, + -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) self.default_contact_params = {"mu": 0.8, "stiffness": 4e4, "dissipation": 0.5} @@ -39,7 +39,7 @@ def __init__(self, visualize=False): def make(self, controller, urdf): self.builder = DiagramBuilder() - self.dt = 5e-5 + self.dt = 8e-5 self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSimDiagram(self.plant, urdf, 0.8, 1e4, 1e2) @@ -86,7 +86,10 @@ def get_state(self): def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt - action[5] = 1 + forward_vel = 0.25 + lateral_vel = 0.1 + action[2] = forward_vel + action[3] = lateral_vel # action = lcmt_radio_out # self.simulator.get_radio_input_port().FixValue(self.simulator_context, AbstractValue.Make(action)) diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index f4ed59cca2..bf65eaa41d 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -13,7 +13,7 @@ def main(): # osc_gains = yaml_load(filename=osc_gains_filename) # import pdb; pdb.set_trace() - controller_plant = MultibodyPlant(1e-5) + controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() controller = OSCRunningControllerFactory(controller_plant, osc_gains_filename, osqp_settings) diff --git a/bindings/pydairlib/cassie/cassie_traj.py b/bindings/pydairlib/cassie/cassie_traj.py index 8bedc23dee..3557155952 100644 --- a/bindings/pydairlib/cassie/cassie_traj.py +++ b/bindings/pydairlib/cassie/cassie_traj.py @@ -18,7 +18,7 @@ CASSIE_NL = 12 # 10000 dts / 2000Hz = 5 seconds -CASSIE_EPS_LENGTH = 10000 +CASSIE_EPS_LENGTH = 100000 class CassieTraj(): From 2f9f8f43a45d9a37debbb08cb87a6fb0d9f3b88e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 17 Mar 2022 17:42:30 -0400 Subject: [PATCH 144/758] updating syntax to reflect new osc convention --- examples/Cassie/BUILD.bazel | 22 - examples/Cassie/run_osc_hopping_controller.cc | 530 ------------------ examples/Cassie/run_osc_jumping_controller.cc | 94 ++-- examples/Cassie/run_osc_running_controller.cc | 164 +++--- .../Cassie/run_osc_standing_controller.cc | 26 +- examples/Cassie/run_osc_walking_controller.cc | 80 +-- .../Cassie/run_osc_walking_controller_alip.cc | 76 +-- .../run_joint_space_walking_controller.cc | 6 +- 8 files changed, 223 insertions(+), 775 deletions(-) delete mode 100644 examples/Cassie/run_osc_hopping_controller.cc diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 450de6fa1b..f6bb046e26 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -45,7 +45,6 @@ cc_library( "//examples/Cassie:dispatcher_robot_out", "//examples/Cassie:multibody_sim", "//examples/Cassie:run_controller_switch", - "//examples/Cassie:run_osc_hopping_controller", "//examples/Cassie:run_osc_jumping_controller", "//examples/Cassie:run_osc_running_controller", "//examples/Cassie:run_osc_standing_controller", @@ -388,27 +387,6 @@ cc_binary( ], ) -cc_binary( - name = "run_osc_hopping_controller", - srcs = ["run_osc_hopping_controller.cc"], - deps = [ - ":cassie_urdf", - ":cassie_utils", - "//examples/Cassie/osc", - "//examples/Cassie/osc_jump", - "//examples/Cassie/osc_run", - "//lcm:trajectory_saver", - "//multibody:utils", - "//systems:robot_lcm_systems", - "//systems:system_utils", - "//systems/controllers/osc:osc_tracking_datas", - "//systems/framework:lcm_driven_loop", - "//systems/primitives", - "@drake//:drake_shared_library", - "@gflags", - ], -) - cc_binary( name = "run_osc_walking_controller", srcs = ["run_osc_walking_controller.cc"], diff --git a/examples/Cassie/run_osc_hopping_controller.cc b/examples/Cassie/run_osc_hopping_controller.cc deleted file mode 100644 index 6d45501866..0000000000 --- a/examples/Cassie/run_osc_hopping_controller.cc +++ /dev/null @@ -1,530 +0,0 @@ -#include - -#include -#include -#include - -#include "common/find_resource.h" -#include "dairlib/lcmt_robot_input.hpp" -#include "dairlib/lcmt_robot_output.hpp" -#include "examples/Cassie/cassie_utils.h" -#include "examples/Cassie/osc/heading_traj_generator.h" -#include "examples/Cassie/osc/high_level_command.h" -#include "examples/Cassie/osc/swing_toe_traj_generator.h" -#include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" -#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" -#include "examples/Cassie/osc_run/foot_traj_generator.h" -#include "examples/Cassie/osc_run/osc_running_gains.h" -#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" -#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" -#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" -#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" -#include "lcm/dircon_saved_trajectory.h" -#include "lcm/lcm_trajectory.h" -#include "multibody/kinematic/fixed_joint_evaluator.h" -#include "multibody/multibody_utils.h" -#include "systems/controllers/controller_failure_aggregator.h" -#include "systems/controllers/osc/joint_space_tracking_data.h" -#include "systems/controllers/osc/operational_space_control.h" -#include "systems/controllers/osc/relative_translation_tracking_data.h" -#include "systems/controllers/osc/rot_space_tracking_data.h" -#include "systems/controllers/osc/trans_space_tracking_data.h" -#include "systems/framework/lcm_driven_loop.h" -#include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" -#include "yaml-cpp/yaml.h" - -#include "drake/common/yaml/yaml_read_archive.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_publisher_system.h" - -namespace dairlib { - -using std::map; -using std::pair; -using std::string; -using std::vector; - -using Eigen::Matrix3d; -using Eigen::MatrixXd; -using Eigen::Vector3d; -using Eigen::VectorXd; - -using cassie::osc::SwingToeTrajGenerator; -using drake::geometry::SceneGraph; -using drake::multibody::Frame; -using drake::multibody::MultibodyPlant; -using drake::multibody::Parser; -using drake::systems::DiagramBuilder; -using drake::systems::TriggerType; -using drake::systems::TriggerTypeSet; -using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::LcmSubscriberSystem; -using drake::trajectories::PiecewisePolynomial; -using examples::osc::PelvisPitchTrajGenerator; -using examples::osc::PelvisRollTrajGenerator; -using examples::osc::PelvisTransTrajGenerator; -using examples::osc_jump::BasicTrajectoryPassthrough; -using examples::osc_run::FootTrajGenerator; -using multibody::FixedJointEvaluator; -using multibody::WorldYawViewFrame; -using systems::controllers::JointSpaceTrackingData; -using systems::controllers::RelativeTranslationTrackingData; -using systems::controllers::RotTaskSpaceTrackingData; -using systems::controllers::TransTaskSpaceTrackingData; - -namespace examples { - -DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", - "The name of the channel which receives state"); -DEFINE_string(channel_u, "CASSIE_INPUT", - "The name of the channel which publishes command"); -DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", - "Filepath containing gains"); -DEFINE_string(osqp_settings, - "examples/Cassie/osc_run/osc_running_qp_settings.yaml", - "Filepath containing qp settings"); -DEFINE_string( - channel_cassie_out, "CASSIE_OUTPUT_ECHO", - "The name of the channel to receive the cassie out structure from."); -DEFINE_double( - fsm_time_offset, 0.0, - "Time (s) in the fsm to move from the stance phase to the flight phase"); - -int DoMain(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - - // Build the controller diagram - DiagramBuilder builder; - - // Built the Cassie MBPs - drake::multibody::MultibodyPlant plant(0.0); - addCassieMultibody(&plant, nullptr, true, - "examples/Cassie/urdf/cassie_v2_conservative.urdf", - false /*spring model*/, false /*loop closure*/); - plant.Finalize(); - - auto plant_context = plant.CreateDefaultContext(); - - // Get contact frames and position - auto left_toe = LeftToeFront(plant); - auto left_heel = LeftToeRear(plant); - auto right_toe = RightToeFront(plant); - auto right_heel = RightToeRear(plant); - - int nv = plant.num_velocities(); - int nu = plant.num_velocities(); - - // Create maps for joints - map pos_map = multibody::makeNameToPositionsMap(plant); - map vel_map = multibody::makeNameToVelocitiesMap(plant); - map act_map = multibody::makeNameToActuatorsMap(plant); - - std::unordered_map< - int, std::vector&>>> - feet_contact_points; - feet_contact_points[0] = std::vector< - std::pair&>>( - {left_toe, left_heel}); - feet_contact_points[1] = std::vector< - std::pair&>>( - {right_toe, right_heel}); - - /**** Get trajectory from optimization ****/ - - /**** OSC Gains ****/ - drake::yaml::YamlReadArchive::Options yaml_options; - yaml_options.allow_yaml_with_no_cpp = true; - OSCGains gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); - OSCRunningGains osc_gains = drake::yaml::LoadYamlFile(FindResourceOrThrow(FLAGS_gains_filename)); - - /**** FSM and contact mode configuration ****/ - int stance_state = 0; - int air_state = 1; - - vector fsm_states = {stance_state, air_state, stance_state, air_state, - stance_state}; - - vector state_durations = { - osc_gains.stance_duration, osc_gains.flight_duration, - osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; - vector accumulated_state_durations; - accumulated_state_durations.push_back(0); - std::cout << accumulated_state_durations.back() << std::endl; - for (double state_duration : state_durations) { - accumulated_state_durations.push_back(accumulated_state_durations.back() + - state_duration); - std::cout << accumulated_state_durations.back() << std::endl; - } - accumulated_state_durations.pop_back(); - - auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, gains.impact_threshold); - - /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - - auto state_receiver = builder.AddSystem(plant); - auto command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); - auto command_sender = builder.AddSystem(plant); - auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true); - auto osc_debug_pub = - builder.AddSystem(LcmPublisherSystem::Make( - "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); - auto failure_aggregator = - builder.AddSystem(FLAGS_channel_u, - 1); - auto controller_failure_pub = builder.AddSystem( - LcmPublisherSystem::Make( - "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - - /**** OSC setup ****/ - // Cost - MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(nv, nv); - osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingWeights(gains.w_input_reg * - MatrixXd::Identity(nu, nu)); - - // Soft constraint on contacts - double w_contact_relax = gains.w_soft_constraint; - osc->SetSoftConstraintWeight(w_contact_relax); - - // Contact information for OSC - osc->SetContactFriction(gains.mu); - - const auto& pelvis = plant.GetBodyByName("pelvis"); - multibody::WorldYawViewFrame view_frame(pelvis); - auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant, left_toe.first, left_toe.second, view_frame, Matrix3d::Identity(), - Vector3d::Zero(), {1, 2}); - auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant, left_heel.first, left_heel.second, view_frame, - Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant, right_toe.first, right_toe.second, view_frame, - Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant, right_heel.first, right_heel.second, view_frame, - Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - - osc->AddStateAndContactPoint(stance_state, &left_toe_evaluator); - osc->AddStateAndContactPoint(stance_state, &left_heel_evaluator); - osc->AddStateAndContactPoint(stance_state, &right_toe_evaluator); - osc->AddStateAndContactPoint(stance_state, &right_heel_evaluator); - - multibody::KinematicEvaluatorSet evaluators(plant); - auto left_loop = LeftLoopClosureEvaluator(plant); - auto right_loop = RightLoopClosureEvaluator(plant); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); - - // Fix the springs in the dynamics - auto pos_idx_map = multibody::makeNameToPositionsMap(plant); - auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); - auto left_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), - vel_idx_map.at("knee_joint_leftdot"), 0); - auto right_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), - vel_idx_map.at("knee_joint_rightdot"), 0); - auto left_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), - vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - auto right_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), - vel_idx_map.at("ankle_spring_joint_rightdot"), 0); - evaluators.add_evaluator(&left_fixed_knee_spring); - evaluators.add_evaluator(&right_fixed_knee_spring); - evaluators.add_evaluator(&left_fixed_ankle_spring); - evaluators.add_evaluator(&right_fixed_ankle_spring); - - osc->AddKinematicConstraint(&evaluators); - - /**** Tracking Data *****/ - - std::cout << "Creating tracking data. " << std::endl; - - auto cassie_out_receiver = - builder.AddSystem(LcmSubscriberSystem::Make( - FLAGS_channel_cassie_out, &lcm)); - cassie::osc::HighLevelCommand* high_level_command; - high_level_command = builder.AddSystem( - plant, plant_context.get(), osc_gains.vel_scale_rot, - osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); - builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_out_input_port()); - - auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); - auto pelvis_trans_traj_generator = - builder.AddSystem( - plant, plant_context.get(), default_traj, feet_contact_points, - osc_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); - auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "hip_left", - osc_gains.relative_feet, 0, accumulated_state_durations); - auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "hip_right", - osc_gains.relative_feet, 0, accumulated_state_durations); - l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, - osc_gains.center_line_offset, - osc_gains.footstep_offset); - r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, - osc_gains.center_line_offset, - osc_gains.footstep_offset); - - TransTaskSpaceTrackingData pelvis_tracking_data( - "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis, plant, plant); - TransTaskSpaceTrackingData stance_foot_tracking_data( - "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData left_foot_tracking_data( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_foot_tracking_data( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - pelvis_tracking_data.AddStateAndPointToTrack(stance_state, "pelvis"); - stance_foot_tracking_data.AddStateAndPointToTrack(stance_state, "toe_left"); - // stance_foot_tracking_data.AddStateAndPointToTrack(stance_state, - // "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(stance_state, "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(stance_state, "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(air_state, "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(air_state, "toe_right"); - - TransTaskSpaceTrackingData left_foot_yz_tracking_data( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_foot_yz_tracking_data( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - left_foot_yz_tracking_data.AddStateAndPointToTrack(air_state, "toe_left"); - right_foot_yz_tracking_data.AddStateAndPointToTrack(air_state, "toe_right"); - - // TransTaskSpaceTrackingData left_hip_tracking_data( - // "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - // osc_gains.W_swing_foot, plant, plant); - // TransTaskSpaceTrackingData right_hip_tracking_data( - // "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - // osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData left_hip_tracking_data( - "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_hip_tracking_data( - "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data.AddStateAndPointToTrack(stance_state, "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(stance_state, "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(air_state, "pelvis"); - left_hip_tracking_data.AddStateAndPointToTrack(air_state, "pelvis"); - - TransTaskSpaceTrackingData left_hip_yz_tracking_data( - "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_hip_yz_tracking_data( - "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - left_hip_yz_tracking_data.AddStateAndPointToTrack(air_state, "hip_left"); - right_hip_yz_tracking_data.AddStateAndPointToTrack(air_state, "hip_right"); - - RelativeTranslationTrackingData left_foot_rel_tracking_data( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, - &left_hip_tracking_data); - RelativeTranslationTrackingData right_foot_rel_tracking_data( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, - &right_hip_tracking_data); - RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( - "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, - plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); - RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( - "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, - plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); - RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( - "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, - &stance_foot_tracking_data); - left_foot_rel_tracking_data.SetViewFrame(view_frame); - right_foot_rel_tracking_data.SetViewFrame(view_frame); - left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); - right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); - pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); - - left_foot_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - - osc->AddTrackingData(&pelvis_trans_rel_tracking_data); - osc->AddTrackingData(&left_foot_rel_tracking_data); - osc->AddTrackingData(&right_foot_rel_tracking_data); - osc->AddTrackingData(&left_foot_yz_rel_tracking_data); - osc->AddTrackingData(&right_foot_yz_rel_tracking_data); - - auto heading_traj_generator = - builder.AddSystem(plant, - plant_context.get()); - - RotTaskSpaceTrackingData pelvis_rot_tracking_data( - "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, - osc_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(stance_state, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(air_state, "pelvis"); - pelvis_rot_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&pelvis_rot_tracking_data); - - // Swing toe joint trajectory - vector&>> left_foot_points = { - left_heel, left_toe}; - vector&>> right_foot_points = { - right_heel, right_toe}; - auto left_toe_angle_traj_gen = builder.AddSystem( - plant, plant_context.get(), pos_map["toe_left"], left_foot_points, - "left_toe_angle_traj"); - auto right_toe_angle_traj_gen = builder.AddSystem( - plant, plant_context.get(), pos_map["toe_right"], right_foot_points, - "right_toe_angle_traj"); - - // Swing toe joint tracking - JointSpaceTrackingData left_toe_angle_tracking_data( - "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, - osc_gains.W_swing_toe, plant, plant); - JointSpaceTrackingData right_toe_angle_tracking_data( - "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, - osc_gains.W_swing_toe, plant, plant); - left_toe_angle_tracking_data.AddStateAndJointToTrack(stance_state, "toe_left", - "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( - stance_state, "toe_right", "toe_rightdot"); - left_toe_angle_tracking_data.AddStateAndJointToTrack(air_state, "toe_left", - "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack(air_state, "toe_right", - "toe_rightdot"); - left_toe_angle_tracking_data.SetImpactInvariantProjection(true); - right_toe_angle_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_toe_angle_tracking_data); - osc->AddTrackingData(&right_toe_angle_tracking_data); - - // Swing hip yaw joint tracking - JointSpaceTrackingData left_hip_yaw_tracking_data( - "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, - osc_gains.W_hip_yaw, plant, plant); - JointSpaceTrackingData right_hip_yaw_tracking_data( - "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, - osc_gains.W_hip_yaw, plant, plant); - left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); - right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", - "hip_yaw_rightdot"); - // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); - osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); - - osc->SetOsqpSolverOptionsFromYaml( - FLAGS_osqp_settings); - // Build OSC problem - osc->Build(); - std::cout << "Built OSC" << std::endl; - - /*****Connect ports*****/ - - // OSC connections - builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_impact(), - osc->get_near_impact_input_port()); - builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); - builder.Connect(state_receiver->get_output_port(0), - osc->get_robot_output_input_port()); - // FSM connections - builder.Connect(state_receiver->get_output_port(0), - fsm->get_input_port_state()); - - // Trajectory generator connections - builder.Connect(state_receiver->get_output_port(0), - pelvis_trans_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - pelvis_trans_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_clock(), - pelvis_trans_traj_generator->get_clock_input_port()); - builder.Connect(high_level_command->get_xy_output_port(), - l_foot_traj_generator->get_target_vel_input_port()); - builder.Connect(high_level_command->get_xy_output_port(), - r_foot_traj_generator->get_target_vel_input_port()); - builder.Connect(state_receiver->get_output_port(0), - l_foot_traj_generator->get_state_input_port()); - builder.Connect(state_receiver->get_output_port(0), - r_foot_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - l_foot_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - r_foot_traj_generator->get_fsm_input_port()); - builder.Connect(state_receiver->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); - builder.Connect(state_receiver->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); - // OSC connections - builder.Connect(pelvis_trans_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_trans_traj")); - builder.Connect(state_receiver->get_output_port(0), - heading_traj_generator->get_state_input_port()); - builder.Connect(high_level_command->get_yaw_output_port(), - heading_traj_generator->get_yaw_input_port()); - builder.Connect(heading_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_traj")); - builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_traj")); - builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_traj")); - builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_z_traj")); - builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_z_traj")); - builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); - builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); - - // Publisher connections - builder.Connect(osc->get_osc_output_port(), - command_sender->get_input_port(0)); - builder.Connect(command_sender->get_output_port(0), - command_pub->get_input_port()); - builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); - builder.Connect(osc->get_failure_output_port(), - failure_aggregator->get_input_port(0)); - builder.Connect(failure_aggregator->get_status_output_port(), - controller_failure_pub->get_input_port()); - - // Run lcm-driven simulation - // Create the diagram - auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc_running_controller")); - - // Run lcm-driven simulation - systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); - DrawAndSaveDiagramGraph(*loop.get_diagram()); - loop.Simulate(); - - return 0; -} // namespace examples -} // namespace examples -} // namespace dairlib - -int main(int argc, char* argv[]) { - return dairlib::examples::DoMain(argc, argv); -} diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index c75ab3466c..e6a88890ff 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -358,71 +358,71 @@ int DoMain(int argc, char* argv[]) { osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ - TransTaskSpaceTrackingData pelvis_tracking_data( + auto pelvis_tracking_data = std::make_unique ( "pelvis_trans_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { - pelvis_tracking_data.AddStateAndPointToTrack(mode, "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); } - RotTaskSpaceTrackingData pelvis_rot_tracking_data( + auto pelvis_rot_tracking_data = std::make_unique ( "pelvis_rot_tracking_data", gains.K_p_pelvis, gains.K_d_pelvis, gains.W_pelvis, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { - pelvis_rot_tracking_data.AddStateAndFrameToTrack(mode, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack(mode, "pelvis"); } - TransTaskSpaceTrackingData left_foot_tracking_data( + auto left_foot_tracking_data = std::make_unique ( "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, gains.W_flight_foot, plant_w_spr, plant_w_spr); - TransTaskSpaceTrackingData right_foot_tracking_data( + auto right_foot_tracking_data = std::make_unique ( "right_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, gains.W_flight_foot, plant_w_spr, plant_w_spr); - left_foot_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, + left_foot_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, "toe_right"); - TransTaskSpaceTrackingData left_hip_tracking_data( + auto left_hip_tracking_data = std::make_unique ( "left_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, gains.W_flight_foot, plant_w_spr, plant_w_spr); - TransTaskSpaceTrackingData right_hip_tracking_data( + auto right_hip_tracking_data = std::make_unique ( "right_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, gains.W_flight_foot, plant_w_spr, plant_w_spr); - left_hip_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, "hip_left"); - right_hip_tracking_data.AddStateAndPointToTrack(osc_jump::FLIGHT, + left_hip_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, "hip_left"); + right_hip_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, "hip_right"); - RelativeTranslationTrackingData left_foot_rel_tracking_data( + auto left_foot_rel_tracking_data = std::make_unique ( "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr, &left_foot_tracking_data, - &left_hip_tracking_data); - RelativeTranslationTrackingData right_foot_rel_tracking_data( + gains.W_flight_foot, plant_w_spr, plant_w_spr, left_foot_tracking_data.get(), + left_hip_tracking_data.get()); + auto right_foot_rel_tracking_data = std::make_unique ( "right_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr, &right_foot_tracking_data, - &right_hip_tracking_data); + gains.W_flight_foot, plant_w_spr, plant_w_spr, right_foot_tracking_data.get(), + right_hip_tracking_data.get()); // Flight phase hip yaw tracking - JointSpaceTrackingData left_hip_yaw_tracking_data( + auto left_hip_yaw_tracking_data = std::make_unique ( "swing_hip_yaw_left_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, gains.W_hip_yaw, plant_w_spr, plant_w_spr); - JointSpaceTrackingData right_hip_yaw_tracking_data( + auto right_hip_yaw_tracking_data = std::make_unique ( "swing_hip_yaw_right_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, gains.W_hip_yaw, plant_w_spr, plant_w_spr); - left_hip_yaw_tracking_data.AddStateAndJointToTrack( + left_hip_yaw_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); - right_hip_yaw_tracking_data.AddStateAndJointToTrack( + right_hip_yaw_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_right", "hip_yaw_rightdot"); - osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); - osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); // Flight phase toe pitch tracking MatrixXd W_swing_toe = gains.w_swing_toe * MatrixXd::Identity(1, 1); MatrixXd K_p_swing_toe = gains.swing_toe_kp * MatrixXd::Identity(1, 1); MatrixXd K_d_swing_toe = gains.swing_toe_kd * MatrixXd::Identity(1, 1); - JointSpaceTrackingData left_toe_angle_tracking_data( + auto left_toe_angle_tracking_data = std::make_unique ( "left_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); - JointSpaceTrackingData right_toe_angle_tracking_data( + auto right_toe_angle_tracking_data = std::make_unique ( "right_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); @@ -440,33 +440,33 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), r_toe_trajectory, pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "toe_left", "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "toe_right", "toe_rightdot"); - osc->AddTrackingData(&pelvis_tracking_data); - osc->AddTrackingData(&pelvis_rot_tracking_data); + osc->AddTrackingData(std::move(pelvis_tracking_data)); + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); if (gains.relative_feet) { - left_foot_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_foot_rel_tracking_data); - osc->AddTrackingData(&right_foot_rel_tracking_data); + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); } else { - left_foot_tracking_data.SetImpactInvariantProjection(true); - right_foot_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_foot_tracking_data); - osc->AddTrackingData(&right_foot_tracking_data); + left_foot_tracking_data->SetImpactInvariantProjection(true); + right_foot_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(left_foot_tracking_data)); + osc->AddTrackingData(std::move(right_foot_tracking_data)); } - osc->AddTrackingData(&left_toe_angle_tracking_data); - osc->AddTrackingData(&right_toe_angle_tracking_data); - - left_toe_angle_tracking_data.SetImpactInvariantProjection(true); - right_toe_angle_tracking_data.SetImpactInvariantProjection(true); - left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - pelvis_rot_tracking_data.SetImpactInvariantProjection(true); - pelvis_tracking_data.SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); + + left_toe_angle_tracking_data->SetImpactInvariantProjection(true); + right_toe_angle_tracking_data->SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + pelvis_tracking_data->SetImpactInvariantProjection(true); osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 6c96a762cc..1ec25800d4 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -291,124 +291,124 @@ int DoMain(int argc, char* argv[]) { osc_gains.center_line_offset, osc_gains.footstep_offset); - TransTaskSpaceTrackingData pelvis_tracking_data( + auto pelvis_tracking_data = std::make_unique ( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant, plant); - TransTaskSpaceTrackingData stance_foot_tracking_data( + auto stance_foot_tracking_data = std::make_unique ( "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData left_foot_tracking_data( + auto left_foot_tracking_data = std::make_unique ( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_foot_tracking_data( + auto right_foot_tracking_data = std::make_unique ( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - pelvis_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); - pelvis_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); - stance_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + pelvis_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); + stance_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, "toe_left"); - stance_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + stance_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(right_stance_state, + left_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(left_stance_state, + right_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); - left_foot_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + left_foot_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, "toe_left"); - right_foot_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + right_foot_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "toe_right"); - TransTaskSpaceTrackingData left_foot_yz_tracking_data( + auto left_foot_yz_tracking_data = std::make_unique ( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_foot_yz_tracking_data( + auto right_foot_yz_tracking_data = std::make_unique ( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_foot_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + left_foot_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "toe_left"); - right_foot_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + right_foot_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, "toe_right"); - TransTaskSpaceTrackingData left_hip_tracking_data( + auto left_hip_tracking_data = std::make_unique ( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_hip_tracking_data( + auto right_hip_tracking_data = std::make_unique ( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data.AddStateAndPointToTrack(right_stance_state, "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(left_stance_state, "pelvis"); - right_hip_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "pelvis"); - left_hip_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, "pelvis"); - TransTaskSpaceTrackingData left_hip_yz_tracking_data( + auto left_hip_yz_tracking_data = std::make_unique ( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - TransTaskSpaceTrackingData right_hip_yz_tracking_data( + auto right_hip_yz_tracking_data = std::make_unique ( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, + left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, "hip_left"); - right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, + right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, "hip_right"); - RelativeTranslationTrackingData left_foot_rel_tracking_data( + auto left_foot_rel_tracking_data = std::make_unique ( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, &left_foot_tracking_data, - &left_hip_tracking_data); - RelativeTranslationTrackingData right_foot_rel_tracking_data( + osc_gains.W_swing_foot, plant, plant, left_foot_tracking_data.get(), + left_hip_tracking_data.get()); + auto right_foot_rel_tracking_data = std::make_unique ( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, &right_foot_tracking_data, - &right_hip_tracking_data); - RelativeTranslationTrackingData left_foot_yz_rel_tracking_data( + osc_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), + right_hip_tracking_data.get()); + auto left_foot_yz_rel_tracking_data = std::make_unique ( "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, - plant, &left_foot_yz_tracking_data, &left_hip_yz_tracking_data); - RelativeTranslationTrackingData right_foot_yz_rel_tracking_data( + plant, left_foot_yz_tracking_data.get(), left_hip_yz_tracking_data.get()); + auto right_foot_yz_rel_tracking_data = std::make_unique ( "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, - plant, &right_foot_yz_tracking_data, &right_hip_yz_tracking_data); - RelativeTranslationTrackingData pelvis_trans_rel_tracking_data( + plant, right_foot_yz_tracking_data.get(), right_hip_yz_tracking_data.get()); + auto pelvis_trans_rel_tracking_data = std::make_unique ( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis, plant, plant, &pelvis_tracking_data, - &stance_foot_tracking_data); - left_foot_rel_tracking_data.SetViewFrame(view_frame); - right_foot_rel_tracking_data.SetViewFrame(view_frame); - left_foot_yz_rel_tracking_data.SetViewFrame(view_frame); - right_foot_yz_rel_tracking_data.SetViewFrame(view_frame); - pelvis_trans_rel_tracking_data.SetViewFrame(view_frame); - - left_foot_rel_tracking_data.SetImpactInvariantProjection(true); - right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); + osc_gains.W_pelvis, plant, plant, pelvis_tracking_data.get(), + stance_foot_tracking_data.get()); + left_foot_rel_tracking_data->SetViewFrame(view_frame); + right_foot_rel_tracking_data->SetViewFrame(view_frame); + left_foot_yz_rel_tracking_data->SetViewFrame(view_frame); + right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); + pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); + + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + // left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + // right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - osc->AddTrackingData(&pelvis_trans_rel_tracking_data); - osc->AddTrackingData(&left_foot_rel_tracking_data); - osc->AddTrackingData(&right_foot_rel_tracking_data); - osc->AddTrackingData(&left_foot_yz_rel_tracking_data); - osc->AddTrackingData(&right_foot_yz_rel_tracking_data); + osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); auto heading_traj_generator = builder.AddSystem(plant, plant_context.get()); - RotTaskSpaceTrackingData pelvis_rot_tracking_data( + auto pelvis_rot_tracking_data = std::make_unique ( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_stance_state, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_stance_state, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(left_touchdown_air_phase, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_touchdown_air_phase, "pelvis"); - pelvis_rot_tracking_data.AddStateAndFrameToTrack(right_touchdown_air_phase, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_touchdown_air_phase, "pelvis"); - pelvis_rot_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&pelvis_rot_tracking_data); + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); // Swing toe joint trajectory vector&>> left_foot_points = { @@ -423,43 +423,43 @@ int DoMain(int argc, char* argv[]) { "right_toe_angle_traj"); // Swing toe joint tracking - JointSpaceTrackingData left_toe_angle_tracking_data( + auto left_toe_angle_tracking_data = std::make_unique ( "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); - JointSpaceTrackingData right_toe_angle_tracking_data( + auto right_toe_angle_tracking_data = std::make_unique ( "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data->AddStateAndJointToTrack( right_stance_state, "toe_left", "toe_leftdot"); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data->AddStateAndJointToTrack( right_touchdown_air_phase, "toe_left", "toe_leftdot"); - left_toe_angle_tracking_data.AddStateAndJointToTrack( + left_toe_angle_tracking_data->AddStateAndJointToTrack( left_touchdown_air_phase, "toe_left", "toe_leftdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( left_stance_state, "toe_right", "toe_rightdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( right_touchdown_air_phase, "toe_right", "toe_rightdot"); - right_toe_angle_tracking_data.AddStateAndJointToTrack( + right_toe_angle_tracking_data->AddStateAndJointToTrack( left_touchdown_air_phase, "toe_right", "toe_rightdot"); - left_toe_angle_tracking_data.SetImpactInvariantProjection(true); - right_toe_angle_tracking_data.SetImpactInvariantProjection(true); - osc->AddTrackingData(&left_toe_angle_tracking_data); - osc->AddTrackingData(&right_toe_angle_tracking_data); + left_toe_angle_tracking_data->SetImpactInvariantProjection(true); + right_toe_angle_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); // Swing hip yaw joint tracking - JointSpaceTrackingData left_hip_yaw_tracking_data( + auto left_hip_yaw_tracking_data = std::make_unique ( "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant, plant); - JointSpaceTrackingData right_hip_yaw_tracking_data( + auto right_hip_yaw_tracking_data = std::make_unique ( "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant, plant); - left_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); - right_hip_yaw_tracking_data.AddJointToTrack("hip_yaw_right", + left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); - osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); + // left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + // right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); osc->SetOsqpSolverOptionsFromYaml( FLAGS_osqp_settings); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 0d35f50818..9ab3d6d572 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -267,21 +267,21 @@ int DoMain(int argc, char* argv[]) { // ComTrackingData center_of_mass_traj("com_traj", K_p_com, K_d_com, // W_com * FLAGS_cost_weight_multiplier, // plant_w_springs, plant_wo_springs); - TransTaskSpaceTrackingData center_of_mass_traj( + auto center_of_mass_traj = std::make_unique( "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, plant_w_springs, plant_wo_springs); - center_of_mass_traj.AddPointToTrack("pelvis"); + center_of_mass_traj->AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); - center_of_mass_traj.SetLowPassFilter(0.03, {1}); - osc->AddTrackingData(¢er_of_mass_traj); + center_of_mass_traj->SetLowPassFilter(0.03, {1}); + osc->AddTrackingData(std::move(center_of_mass_traj)); // Pelvis rotation tracking - RotTaskSpaceTrackingData pelvis_rot_traj( + auto pelvis_rot_traj = std::make_unique( "pelvis_rot_traj", K_p_pelvis, K_d_pelvis, W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, plant_wo_springs); - pelvis_rot_traj.AddFrameToTrack("pelvis"); - osc->AddTrackingData(&pelvis_rot_traj); + pelvis_rot_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_rot_traj)); // Hip yaw joint tracking // We use hip yaw joint tracking instead of pelvis yaw tracking because the @@ -290,18 +290,18 @@ int DoMain(int argc, char* argv[]) { double w_hip_yaw = 0.5; double hip_yaw_kp = 40; double hip_yaw_kd = 0.5; - JointSpaceTrackingData left_hip_yaw_traj( + auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), plant_w_springs, plant_wo_springs); - JointSpaceTrackingData right_hip_yaw_traj( + auto right_hip_yaw_traj = std::make_unique( "right_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), plant_w_springs, plant_wo_springs); - left_hip_yaw_traj.AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); - osc->AddConstTrackingData(&left_hip_yaw_traj, VectorXd::Zero(1)); - right_hip_yaw_traj.AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - osc->AddConstTrackingData(&right_hip_yaw_traj, VectorXd::Zero(1)); + left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); + right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); + osc->AddConstTrackingData(std::move(right_hip_yaw_traj), VectorXd::Zero(1)); // Build OSC problem osc->Build(); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index d70ba79a82..81d48eb2ba 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -476,98 +476,98 @@ int DoMain(int argc, char* argv[]) { swing_ft_accel_gain_multiplier_breaks, swing_ft_accel_gain_multiplier_samples); - TransTaskSpaceTrackingData swing_foot_data( + auto swing_foot_data = std::make_unique ( "swing_ft_data", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); - swing_foot_data.AddStateAndPointToTrack(left_stance_state, "toe_right"); - swing_foot_data.AddStateAndPointToTrack(right_stance_state, "toe_left"); - ComTrackingData com_data("com_data", gains.K_p_swing_foot, + swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); + swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); + auto com_data = std::make_unique ("com_data", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); - com_data.AddFiniteStateToTrack(left_stance_state); - com_data.AddFiniteStateToTrack(right_stance_state); - RelativeTranslationTrackingData swing_ft_traj_local( + com_data->AddFiniteStateToTrack(left_stance_state); + com_data->AddFiniteStateToTrack(right_stance_state); + auto swing_ft_traj_local = std::make_unique ( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, - gains.W_swing_foot, plant_w_spr, plant_w_spr, &swing_foot_data, - &com_data); + gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), + com_data.get()); WorldYawViewFrame pelvis_view_frame(plant_w_spr.GetBodyByName("pelvis")); - swing_ft_traj_local.SetViewFrame(pelvis_view_frame); + swing_ft_traj_local->SetViewFrame(pelvis_view_frame); - TransTaskSpaceTrackingData swing_ft_traj_global( + auto swing_ft_traj_global = std::make_unique ( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); - swing_ft_traj_global.AddStateAndPointToTrack(left_stance_state, "toe_right"); - swing_ft_traj_global.AddStateAndPointToTrack(right_stance_state, "toe_left"); + swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); + swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); if (FLAGS_spring_model) { // swing_ft_traj.DisableFeedforwardAccel({2}); } if (wrt_com_in_local_frame) { - swing_ft_traj_local.SetTimeVaryingGains( + swing_ft_traj_local->SetTimeVaryingGains( swing_ft_gain_multiplier_gain_multiplier); - swing_ft_traj_local.SetFeedforwardAccelMultiplier( + swing_ft_traj_local->SetFeedforwardAccelMultiplier( swing_ft_accel_gain_multiplier_gain_multiplier); - osc->AddTrackingData(&swing_ft_traj_local); + osc->AddTrackingData(std::move(swing_ft_traj_local)); } else { - swing_ft_traj_global.SetTimeVaryingGains( + swing_ft_traj_global->SetTimeVaryingGains( swing_ft_gain_multiplier_gain_multiplier); - swing_ft_traj_global.SetFeedforwardAccelMultiplier( + swing_ft_traj_global->SetFeedforwardAccelMultiplier( swing_ft_accel_gain_multiplier_gain_multiplier); - osc->AddTrackingData(&swing_ft_traj_global); + osc->AddTrackingData(std::move(swing_ft_traj_global)); } // Center of mass tracking bool use_pelvis_for_lipm_tracking = true; - TransTaskSpaceTrackingData pelvis_traj("lipm_traj", gains.K_p_com, + auto pelvis_traj = std::make_unique ("lipm_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, plant_w_spr); - pelvis_traj.AddPointToTrack("pelvis"); - ComTrackingData center_of_mass_traj("lipm_traj", gains.K_p_com, gains.K_d_com, + pelvis_traj->AddPointToTrack("pelvis"); + auto center_of_mass_traj = std::make_unique ("lipm_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, plant_w_spr); if (use_pelvis_for_lipm_tracking) { - osc->AddTrackingData(&pelvis_traj); + osc->AddTrackingData(std::move(pelvis_traj)); } else { - osc->AddTrackingData(¢er_of_mass_traj); + osc->AddTrackingData(std::move(center_of_mass_traj)); } // Pelvis rotation tracking (pitch and roll) - RotTaskSpaceTrackingData pelvis_balance_traj( + auto pelvis_balance_traj = std::make_unique ( "pelvis_balance_traj", gains.K_p_pelvis_balance, gains.K_d_pelvis_balance, gains.W_pelvis_balance, plant_w_spr, plant_w_spr); - pelvis_balance_traj.AddFrameToTrack("pelvis"); - osc->AddTrackingData(&pelvis_balance_traj); + pelvis_balance_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) - RotTaskSpaceTrackingData pelvis_heading_traj( + auto pelvis_heading_traj = std::make_unique ( "pelvis_heading_traj", gains.K_p_pelvis_heading, gains.K_d_pelvis_heading, gains.W_pelvis_heading, plant_w_spr, plant_w_spr); - pelvis_heading_traj.AddFrameToTrack("pelvis"); - osc->AddTrackingData(&pelvis_heading_traj, + pelvis_heading_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_heading_traj), gains.period_of_no_heading_control); // Swing toe joint tracking - JointSpaceTrackingData swing_toe_traj_left( + auto swing_toe_traj_left = std::make_unique ( "left_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, gains.W_swing_toe, plant_w_spr, plant_w_spr); - JointSpaceTrackingData swing_toe_traj_right( + auto swing_toe_traj_right = std::make_unique ( "right_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, gains.W_swing_toe, plant_w_spr, plant_w_spr); - swing_toe_traj_right.AddStateAndJointToTrack(left_stance_state, "toe_right", + swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", "toe_rightdot"); - swing_toe_traj_left.AddStateAndJointToTrack(right_stance_state, "toe_left", + swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", "toe_leftdot"); - osc->AddTrackingData(&swing_toe_traj_left); - osc->AddTrackingData(&swing_toe_traj_right); + osc->AddTrackingData(std::move(swing_toe_traj_left)); + osc->AddTrackingData(std::move(swing_toe_traj_right)); // Swing hip yaw joint tracking - JointSpaceTrackingData swing_hip_yaw_traj( + auto swing_hip_yaw_traj = std::make_unique ( "swing_hip_yaw_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, gains.W_hip_yaw, plant_w_spr, plant_w_spr); - swing_hip_yaw_traj.AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", + swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", "hip_yaw_rightdot"); - swing_hip_yaw_traj.AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", + swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", "hip_yaw_leftdot"); - osc->AddConstTrackingData(&swing_hip_yaw_traj, VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); // Set double support duration for force blending osc->SetUpDoubleSupportPhaseBlending( diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 7a4c2c4c69..ff7c829931 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -443,91 +443,91 @@ int DoMain(int argc, char* argv[]) { swing_ft_accel_gain_multiplier_breaks, swing_ft_accel_gain_multiplier_samples); - TransTaskSpaceTrackingData swing_foot_data( + auto swing_foot_data = std::make_unique ( "swing_ft_data", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); - swing_foot_data.AddStateAndPointToTrack(left_stance_state, "toe_right"); - swing_foot_data.AddStateAndPointToTrack(right_stance_state, "toe_left"); - ComTrackingData com_data("com_data", gains.K_p_swing_foot, + swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); + swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); + auto com_data = std::make_unique ("com_data", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); - com_data.AddFiniteStateToTrack(left_stance_state); - com_data.AddFiniteStateToTrack(right_stance_state); - RelativeTranslationTrackingData swing_ft_traj_local( + com_data->AddFiniteStateToTrack(left_stance_state); + com_data->AddFiniteStateToTrack(right_stance_state); + auto swing_ft_traj_local = std::make_unique ( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, - gains.W_swing_foot, plant_w_spr, plant_w_spr, &swing_foot_data, - &com_data); + gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), + com_data.get()); WorldYawViewFrame pelvis_view_frame(plant_w_spr.GetBodyByName("pelvis")); - swing_ft_traj_local.SetViewFrame(pelvis_view_frame); + swing_ft_traj_local->SetViewFrame(pelvis_view_frame); - TransTaskSpaceTrackingData swing_ft_traj_global( + auto swing_ft_traj_global = std::make_unique ( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); - swing_ft_traj_global.AddStateAndPointToTrack(left_stance_state, "toe_right"); - swing_ft_traj_global.AddStateAndPointToTrack(right_stance_state, "toe_left"); + swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); + swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); if (FLAGS_spring_model) { // swing_ft_traj.DisableFeedforwardAccel({2}); } if (wrt_com_in_local_frame) { - swing_ft_traj_local.SetTimeVaryingGains( + swing_ft_traj_local->SetTimeVaryingGains( swing_ft_gain_multiplier_gain_multiplier); - swing_ft_traj_local.SetFeedforwardAccelMultiplier( + swing_ft_traj_local->SetFeedforwardAccelMultiplier( swing_ft_accel_gain_multiplier_gain_multiplier); - osc->AddTrackingData(&swing_ft_traj_local); + osc->AddTrackingData(std::move(swing_ft_traj_local)); } else { - swing_ft_traj_global.SetTimeVaryingGains( + swing_ft_traj_global->SetTimeVaryingGains( swing_ft_gain_multiplier_gain_multiplier); - swing_ft_traj_global.SetFeedforwardAccelMultiplier( + swing_ft_traj_global->SetFeedforwardAccelMultiplier( swing_ft_accel_gain_multiplier_gain_multiplier); - osc->AddTrackingData(&swing_ft_traj_global); + osc->AddTrackingData(std::move(swing_ft_traj_global)); } - ComTrackingData center_of_mass_traj("alip_com_traj", gains.K_p_com, + auto center_of_mass_traj = std::make_unique ("alip_com_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, plant_w_spr); // FiniteStatesToTrack cannot be empty - center_of_mass_traj.AddFiniteStateToTrack(-1); - osc->AddTrackingData(¢er_of_mass_traj); + center_of_mass_traj->AddFiniteStateToTrack(-1); + osc->AddTrackingData(std::move(center_of_mass_traj)); // Pelvis rotation tracking (pitch and roll) - RotTaskSpaceTrackingData pelvis_balance_traj( + auto pelvis_balance_traj = std::make_unique ( "pelvis_balance_traj", gains.K_p_pelvis_balance, gains.K_d_pelvis_balance, gains.W_pelvis_balance, plant_w_spr, plant_w_spr); - pelvis_balance_traj.AddFrameToTrack("pelvis"); - osc->AddTrackingData(&pelvis_balance_traj); + pelvis_balance_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) - RotTaskSpaceTrackingData pelvis_heading_traj( + auto pelvis_heading_traj = std::make_unique ( "pelvis_heading_traj", gains.K_p_pelvis_heading, gains.K_d_pelvis_heading, gains.W_pelvis_heading, plant_w_spr, plant_w_spr); - pelvis_heading_traj.AddFrameToTrack("pelvis"); - osc->AddTrackingData(&pelvis_heading_traj, + pelvis_heading_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_heading_traj), gains.period_of_no_heading_control); // Swing toe joint tracking - JointSpaceTrackingData swing_toe_traj_left( + auto swing_toe_traj_left = std::make_unique ( "left_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, gains.W_swing_toe, plant_w_spr, plant_w_spr); - JointSpaceTrackingData swing_toe_traj_right( + auto swing_toe_traj_right = std::make_unique ( "right_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, gains.W_swing_toe, plant_w_spr, plant_w_spr); - swing_toe_traj_right.AddStateAndJointToTrack(left_stance_state, "toe_right", + swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", "toe_rightdot"); - swing_toe_traj_left.AddStateAndJointToTrack(right_stance_state, "toe_left", + swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", "toe_leftdot"); - osc->AddTrackingData(&swing_toe_traj_left); - osc->AddTrackingData(&swing_toe_traj_right); + osc->AddTrackingData(std::move(swing_toe_traj_left)); + osc->AddTrackingData(std::move(swing_toe_traj_right)); // Swing hip yaw joint tracking - JointSpaceTrackingData swing_hip_yaw_traj( + auto swing_hip_yaw_traj = std::make_unique ( "swing_hip_yaw_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, gains.W_hip_yaw, plant_w_spr, plant_w_spr); - swing_hip_yaw_traj.AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", + swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", "hip_yaw_rightdot"); - swing_hip_yaw_traj.AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", + swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", "hip_yaw_leftdot"); - osc->AddConstTrackingData(&swing_hip_yaw_traj, VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); // Set double support duration for force blending osc->SetUpDoubleSupportPhaseBlending( diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 79662af514..08931bf80c 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -154,7 +154,7 @@ int DoMain(int argc, char* argv[]) { map pos_map_wo_spr = multibody::makeNameToPositionsMap(plant); std::vector joint_trajs; - std::vector> joint_tracking_data_vec; + std::vector> joint_tracking_data_vec; std::vector actuated_joint_names = { "left_hip_pin", "right_hip_pin", "left_knee_pin", "right_knee_pin"}; @@ -165,7 +165,7 @@ int DoMain(int argc, char* argv[]) { MatrixXd W = gains.JointW[joint_idx] * MatrixXd::Identity(1, 1); MatrixXd K_p = gains.JointKp[joint_idx] * MatrixXd::Identity(1, 1); MatrixXd K_d = gains.JointKd[joint_idx] * MatrixXd::Identity(1, 1); - joint_tracking_data_vec.push_back(std::make_shared( + joint_tracking_data_vec.push_back(std::make_unique( joint_name + "_traj", K_p, K_d, W, plant, plant)); joint_tracking_data_vec[joint_idx]->AddJointToTrack(joint_name, joint_name + "dot"); @@ -174,7 +174,7 @@ int DoMain(int argc, char* argv[]) { auto joint_traj_generator = builder.AddSystem( joint_traj, joint_name + "_traj"); joint_trajs.push_back(joint_traj_generator); - osc->AddTrackingData(joint_tracking_data_vec[joint_idx].get()); + osc->AddTrackingData(std::move(joint_tracking_data_vec[joint_idx])); builder.Connect(joint_trajs[joint_idx]->get_output_port(), osc->get_tracking_data_input_port(joint_name + "_traj")); From 684cba4aa43feeea19a1031230ddfeab22b44f0d Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 18 Mar 2022 13:19:06 -0400 Subject: [PATCH 145/758] walking bindings almost done, need to figure out discrete update --- bindings/pydairlib/cassie/BUILD.bazel | 1 + bindings/pydairlib/cassie/cassie_gym_test.py | 11 +- bindings/pydairlib/cassie/controllers_py.cc | 21 +- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/closed_loop_running_sim.cc | 14 +- examples/Cassie/diagrams/BUILD.bazel | 24 + .../Cassie/diagrams/cassie_sim_diagram.cc | 12 +- .../osc_walking_controller_diagram.cc | 459 ++++++++++++++++++ .../diagrams/osc_walking_controller_diagram.h | 162 +++++++ examples/Cassie/multibody_sim.cc | 12 +- examples/Cassie/osc/osc_walking_gains.h | 2 + examples/Cassie/run_osc_walking_controller.cc | 2 + systems/controllers/geared_motor.cc | 13 +- systems/controllers/geared_motor.h | 2 +- systems/controllers/lipm_traj_gen.cc | 10 + 15 files changed, 715 insertions(+), 31 deletions(-) create mode 100644 examples/Cassie/diagrams/osc_walking_controller_diagram.cc create mode 100644 examples/Cassie/diagrams/osc_walking_controller_diagram.h diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index 7bdd335250..74857c6928 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -76,6 +76,7 @@ pybind_py_library( cc_deps = [ "@drake//:drake_shared_library", "//examples/Cassie/diagrams:osc_running_controller_diagram", + "//examples/Cassie/diagrams:osc_walking_controller_diagram", ], cc_so_name = "controllers", cc_srcs = ["controllers_py.cc"], diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index bf65eaa41d..344b36ad13 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -1,22 +1,21 @@ from cassie_gym import * # from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory +from pydairlib.cassie.controllers import OSCWalkingControllerFactory from pydairlib.cassie.simulators import CassieSimDiagram from pydrake.common.yaml import yaml_load -# from controllers import OSCRunningControllerFactory - def main(): - osc_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' - # osc_gains = yaml_load(filename=osc_gains_filename) - # import pdb; pdb.set_trace() controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, False, osc_walking_gains_filename, osqp_settings) gym_env = CassieGym(visualize=True) gym_env.make(controller, urdf) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index 3d472d9a12..41a5026134 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -4,6 +4,7 @@ #include #include "examples/Cassie/diagrams/osc_running_controller_diagram.h" +#include "examples/Cassie/diagrams/osc_walking_controller_diagram.h" #include "drake/multibody/plant/multibody_plant.h" @@ -13,13 +14,14 @@ namespace dairlib { namespace pydairlib { using examples::controllers::OSCRunningControllerDiagram; +using examples::controllers::OSCWalkingControllerDiagram; PYBIND11_MODULE(controllers, m) { m.doc() = "Binding controller factories for Cassie"; using py_rvp = py::return_value_policy; - py::class_>( + py::class_>( m, "OSCRunningControllerFactory") .def(py::init&, const std::string&, const std::string&>(), py::arg("plant"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) @@ -35,6 +37,23 @@ PYBIND11_MODULE(controllers, m) { .def("get_controller_failure_output_port", &OSCRunningControllerDiagram::get_controller_failure_output_port, py_rvp::reference_internal); + + py::class_>( + m, "OSCWalkingControllerFactory") + .def(py::init&, bool, const std::string&, const std::string&>(), + py::arg("plant"), py::arg("has_double_stance"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) + .def("get_state_input_port", + &OSCWalkingControllerDiagram::get_state_input_port, + py_rvp::reference_internal) + .def("get_cassie_out_input_port", + &OSCWalkingControllerDiagram::get_cassie_out_input_port, + py_rvp::reference_internal) + .def("get_control_output_port", + &OSCWalkingControllerDiagram::get_control_output_port, + py_rvp::reference_internal) + .def("get_controller_failure_output_port", + &OSCWalkingControllerDiagram::get_controller_failure_output_port, + py_rvp::reference_internal); } } // namespace pydairlib } // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index f6bb046e26..3d3e8526cf 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -403,6 +403,7 @@ cc_binary( "//systems/controllers:fsm_event_time", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 28c2b1a4db..30e480a0d3 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -7,16 +7,18 @@ #include "examples/Cassie/cassie_utils.h" #include "examples/Cassie/diagrams/cassie_sim_diagram.h" #include "examples/Cassie/diagrams/osc_running_controller_diagram.h" +#include "examples/Cassie/diagrams/osc_walking_controller_diagram.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" -#include "systems/system_utils.h" +#include "drake/systems/primitives/zero_order_hold.h" namespace dairlib { using drake::multibody::MultibodyPlant; @@ -27,7 +29,8 @@ namespace examples { int DoMain(int argc, char* argv[]) { DiagramBuilder builder; std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; - std::string osc_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; + std::string osc_running_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; + std::string osc_walking_gains = "examples/Cassie/osc/osc_walking_gains.yaml"; std::string osqp_settings = "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; std::unique_ptr> plant = @@ -44,9 +47,12 @@ int DoMain(int argc, char* argv[]) { auto sim_diagram = builder.AddSystem( std::move(plant), urdf, 0.4, 1e4, 1e2); MultibodyPlant& new_plant = sim_diagram->get_plant(); +// auto controller_diagram = +// builder.AddSystem( +// controller_plant, osc_gains, osqp_settings); auto controller_diagram = - builder.AddSystem( - controller_plant, osc_gains, osqp_settings); + builder.AddSystem( + controller_plant, true, osc_walking_gains, osqp_settings); builder.Connect(controller_diagram->get_control_output_port(), sim_diagram->get_actuation_input_port()); diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel index 5d470df576..a6b6c79520 100644 --- a/examples/Cassie/diagrams/BUILD.bazel +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -26,6 +26,7 @@ cc_library( name = "diagrams", deps = [ ":osc_running_controller_diagram", + ":osc_walking_controller_diagram", ":cassie_sim_diagram", ], ) @@ -52,6 +53,29 @@ cc_library( ], ) +cc_library( + name = "osc_walking_controller_diagram", + srcs = ["osc_walking_controller_diagram.cc"], + hdrs = ["osc_walking_controller_diagram.h"], + deps = [ + "//examples/impact_invariant_control:impact_aware_time_based_fsm", + "//examples/Cassie:cassie_urdf", + "//examples/Cassie:cassie_utils", + "//examples/Cassie/osc:osc", + "//lcm:trajectory_saver", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/filters:floating_base_velocity_filter", + "//systems/controllers/osc:osc_tracking_datas", + "//systems/controllers/osc:osc_gains", + "//systems/controllers:fsm_event_time", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "cassie_sim_diagram", srcs = ["cassie_sim_diagram.cc"], diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 21c5a14481..4cc5b835ae 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -67,7 +67,7 @@ CassieSimDiagram::CassieSimDiagram( auto discrete_time_delay = builder.AddSystem( actuator_update_rate, actuator_delay / actuator_update_rate, - plant_->num_actuators()); + plant_->num_actuators() + 1); auto state_sender = builder.AddSystem(*plant_, true); @@ -86,18 +86,18 @@ CassieSimDiagram::CassieSimDiagram( // connect leaf systems builder.Connect(input_receiver->get_output_port(), - cassie_motor->get_input_port_command()); - builder.Connect(cassie_motor->get_output_port(), - passthrough->get_input_port()); - builder.Connect(passthrough->get_output_port(), discrete_time_delay->get_input_port()); builder.Connect(discrete_time_delay->get_output_port(), + passthrough->get_input_port()); + builder.Connect(passthrough->get_output_port(), + cassie_motor->get_input_port_command()); + builder.Connect(cassie_motor->get_output_port(), plant_->get_actuation_input_port()); builder.Connect(plant_->get_state_output_port(), state_sender->get_input_port_state()); builder.Connect(plant_->get_state_output_port(), cassie_motor->get_input_port_state()); - builder.Connect(discrete_time_delay->get_output_port(), + builder.Connect(cassie_motor->get_output_port(), state_sender->get_input_port_effort()); builder.Connect( plant_->get_geometry_poses_output_port(), diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc new file mode 100644 index 0000000000..b04b9f03a4 --- /dev/null +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -0,0 +1,459 @@ +#include "osc_walking_controller_diagram.h" + +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/osc/heading_traj_generator.h" +#include "examples/Cassie/osc/high_level_command.h" +#include "examples/Cassie/osc/osc_walking_gains.h" +#include "examples/Cassie/osc/swing_toe_traj_generator.h" +#include "examples/Cassie/osc/walking_speed_control.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/fsm_event_time.h" +#include "systems/controllers/lipm_traj_gen.h" +#include "systems/controllers/osc/com_tracking_data.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/options_tracking_data.h" +#include "systems/controllers/osc/osc_tracking_data.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/controllers/swing_ft_traj_gen.h" +#include "systems/controllers/time_based_fsm.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/common/yaml/yaml_io.h" +#include "drake/systems/framework/diagram_builder.h" + +namespace dairlib { + +using std::map; +using std::pair; +using std::string; +using std::vector; + +using Eigen::Matrix3d; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using cassie::osc::SwingToeTrajGenerator; +using drake::geometry::SceneGraph; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +//using drake::systems::lcm::LcmPublisherSystem; +//using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using multibody::FixedJointEvaluator; +using multibody::WorldYawViewFrame; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +namespace examples { +namespace controllers { + +OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( + drake::multibody::MultibodyPlant& plant, bool has_double_stance, + const string& osc_walking_gains_filename, const string& osqp_settings_filename) + : pos_map(multibody::makeNameToPositionsMap(plant)), + vel_map(multibody::makeNameToVelocitiesMap(plant)), + act_map(multibody::makeNameToActuatorsMap(plant)), + left_toe(LeftToeFront(plant)), + left_heel(LeftToeRear(plant)), + right_toe(RightToeFront(plant)), + right_heel(RightToeRear(plant)), + left_toe_mid(std::pair&>( + (left_toe.first + left_heel.first) / 2, plant.GetFrameByName("toe_left"))), + right_toe_mid(std::pair&>( + (left_toe.first + left_heel.first) / 2, plant.GetFrameByName("toe_right"))), + left_toe_origin(std::pair&>( + Vector3d::Zero(), plant.GetFrameByName("toe_left"))), + right_toe_origin(std::pair&>( + Vector3d::Zero(), plant.GetFrameByName("toe_right"))), + left_right_foot({left_toe_origin, right_toe_origin}), + left_foot_points({left_heel, left_toe}), + right_foot_points({right_heel, right_toe}), + view_frame( + multibody::WorldYawViewFrame(plant.GetBodyByName("pelvis"))), + left_toe_evaluator(multibody::WorldPointEvaluator( + plant, left_toe.first, left_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2})), + left_heel_evaluator(multibody::WorldPointEvaluator( + plant, left_heel.first, left_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2})), + right_toe_evaluator(multibody::WorldPointEvaluator( + plant, right_toe.first, right_toe.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2})), + right_heel_evaluator(multibody::WorldPointEvaluator( + plant, right_heel.first, right_heel.second, view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2})), + left_loop(LeftLoopClosureEvaluator(plant)), + right_loop(RightLoopClosureEvaluator(plant)), + evaluators(multibody::KinematicEvaluatorSet(plant)), + left_fixed_knee_spring( + FixedJointEvaluator(plant, pos_map.at("knee_joint_left"), + vel_map.at("knee_joint_leftdot"), 0)), + right_fixed_knee_spring( + FixedJointEvaluator(plant, pos_map.at("knee_joint_right"), + vel_map.at("knee_joint_rightdot"), 0)), + left_fixed_ankle_spring( + FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_left"), + vel_map.at("ankle_spring_joint_leftdot"), 0)), + right_fixed_ankle_spring( + FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_right"), + vel_map.at("ankle_spring_joint_rightdot"), 0)) { + // Build the controller diagram + DiagramBuilder builder; + plant_context = plant.CreateDefaultContext(); + feet_contact_points[0] = std::vector< + std::pair&>>( + {left_toe, left_heel}); + feet_contact_points[1] = std::vector< + std::pair&>>( + {right_toe, right_heel}); + + /**** OSC Gains ****/ + OSCWalkingGains osc_walking_gains = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_walking_gains_filename)); + + /**** FSM and contact mode configuration ****/ + int left_stance_state = 0; + int right_stance_state = 1; + int post_left_double_support_state = 3; + int post_right_double_support_state = 4; + double left_support_duration = osc_walking_gains.ss_time; + double right_support_duration = osc_walking_gains.ss_time; + double double_support_duration = osc_walking_gains.ds_time; + // vector fsm_states; + // vector state_durations; + if (has_double_stance) { + fsm_states = {left_stance_state, right_stance_state}; + state_durations = {left_support_duration, right_support_duration}; + } else { + fsm_states = {left_stance_state, post_left_double_support_state, + right_stance_state, post_right_double_support_state}; + state_durations = {left_support_duration, double_support_duration, + right_support_duration, double_support_duration}; + } + single_support_states = {left_stance_state, right_stance_state}; + double_support_states = {post_left_double_support_state, + post_right_double_support_state}; + unordered_fsm_states = {left_stance_state, right_stance_state, + post_left_double_support_state, + post_right_double_support_state}; + unordered_state_durations = {left_support_duration, right_support_duration, + double_support_duration, + double_support_duration}; + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + left_right_support_fsm_states = {left_stance_state, right_stance_state}; + left_right_support_state_durations = {left_support_duration, + right_support_duration}; + swing_ft_gain_multiplier_breaks = {0, left_support_duration / 2, + left_support_duration}; + swing_ft_gain_multiplier_samples = + std::vector < + drake::MatrixX>(3, drake::MatrixX::Identity(3, 3)); + swing_ft_gain_multiplier_samples[2](2, 2) *= 0.3; + swing_ft_gain_multiplier_gain_multiplier = + PiecewisePolynomial::FirstOrderHold( + swing_ft_gain_multiplier_breaks, swing_ft_gain_multiplier_samples); + swing_ft_accel_gain_multiplier_breaks = {0, left_support_duration / 2, + left_support_duration * 3 / 4, + left_support_duration}; + swing_ft_accel_gain_multiplier_samples = + std::vector < + drake::MatrixX>(4, drake::MatrixX::Identity(3, 3)); + swing_ft_accel_gain_multiplier_samples[2](2, 2) *= 0; + swing_ft_accel_gain_multiplier_samples[3](2, 2) *= 0; + swing_ft_accel_gain_multiplier_gain_multiplier = + PiecewisePolynomial::FirstOrderHold( + swing_ft_accel_gain_multiplier_breaks, + swing_ft_accel_gain_multiplier_samples); + + /**** Initialize all the leaf systems ****/ + + auto state_receiver = builder.AddSystem(plant); + auto command_sender = builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), true, false); + auto fsm = builder.AddSystem( + plant, fsm_states, state_durations); + auto liftoff_event_time = + builder.AddSystem( + plant, single_support_states); + auto touchdown_event_time = + builder.AddSystem( + plant, double_support_states); + liftoff_event_time->set_name("liftoff_time"); + touchdown_event_time->set_name("touchdown_time"); + /**** OSC setup ****/ + + /// REGULARIZATION COSTS + int n_v = plant.num_velocities(); + int n_u = plant.num_actuators(); + MatrixXd Q_accel = osc_walking_gains.w_accel * MatrixXd::Identity(n_v, n_v); + osc->SetAccelerationCostWeights(Q_accel); + osc->SetInputSmoothingWeights(osc_walking_gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + // Soft constraint on contacts + osc->SetSoftConstraintWeight(osc_walking_gains.w_soft_constraint); + + // Contact information for OSC + osc->SetContactFriction(osc_walking_gains.mu); + + osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); + osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); + osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); + osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); + + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + + // Fix the springs in the dynamics + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + + osc->AddKinematicConstraint(&evaluators); + + /**** Trajectory Generators ****/ + + std::cout << "Creating output trajectory leaf systems. " << std::endl; + + cassie::osc::HighLevelCommand* high_level_command; + high_level_command = builder.AddSystem( + plant, plant_context.get(), osc_walking_gains.vel_scale_rot, + osc_walking_gains.vel_scale_trans_sagital, + osc_walking_gains.vel_scale_trans_lateral); + auto head_traj_gen = builder.AddSystem( + plant, plant_context.get()); + auto lipm_traj_generator = builder.AddSystem( + plant, plant_context.get(), osc_walking_gains.lipm_height, unordered_fsm_states, + unordered_state_durations, contact_points_in_each_state); + auto pelvis_traj_generator = builder.AddSystem( + plant, plant_context.get(), osc_walking_gains.lipm_height, unordered_fsm_states, + unordered_state_durations, contact_points_in_each_state, false); + auto walking_speed_control = + builder.AddSystem( + plant, plant_context.get(), osc_walking_gains.k_ff_lateral, osc_walking_gains.k_fb_lateral, + osc_walking_gains.k_ff_sagittal, osc_walking_gains.k_fb_sagittal, left_support_duration, 0, + osc_walking_gains.relative_swing_ft); + auto swing_ft_traj_generator = + builder.AddSystem( + plant, plant_context.get(), left_right_support_fsm_states, + left_right_support_state_durations, left_right_foot, "pelvis", + double_support_duration, osc_walking_gains.mid_foot_height, + osc_walking_gains.final_foot_height, osc_walking_gains.final_foot_velocity_z, + osc_walking_gains.max_CoM_to_footstep_dist, osc_walking_gains.footstep_offset, + osc_walking_gains.center_line_offset, osc_walking_gains.relative_swing_ft); + auto left_toe_angle_traj_gen = + builder.AddSystem( + plant, plant_context.get(), pos_map["toe_left"], left_foot_points, + "left_toe_angle_traj"); + auto right_toe_angle_traj_gen = + builder.AddSystem( + plant, plant_context.get(), pos_map["toe_right"], right_foot_points, + "right_toe_angle_traj"); + + /**** Tracking Data *****/ + + std::cout << "Creating tracking data. " << std::endl; + + swing_foot_data = std::make_unique( + "swing_ft_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant, plant); + swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); + swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); + com_data = std::make_unique( + "com_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant, plant); + com_data->AddFiniteStateToTrack(left_stance_state); + com_data->AddFiniteStateToTrack(right_stance_state); + swing_ft_traj_local = std::make_unique( + "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant, plant, swing_foot_data.get(), + com_data.get()); +// WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); + swing_ft_traj_local->SetViewFrame(view_frame); + + swing_ft_traj_global = std::make_unique( + "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant, plant); + swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); + swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); + if (osc_walking_gains.relative_swing_ft) { + swing_ft_traj_local->SetTimeVaryingGains( + swing_ft_gain_multiplier_gain_multiplier); + swing_ft_traj_local->SetFeedforwardAccelMultiplier( + swing_ft_accel_gain_multiplier_gain_multiplier); + osc->AddTrackingData(std::move(swing_ft_traj_local)); + } else { + swing_ft_traj_global->SetTimeVaryingGains( + swing_ft_gain_multiplier_gain_multiplier); + swing_ft_traj_global->SetFeedforwardAccelMultiplier( + swing_ft_accel_gain_multiplier_gain_multiplier); + osc->AddTrackingData(std::move(swing_ft_traj_global)); + } + bool use_pelvis_for_lipm_tracking = true; + + pelvis_traj = std::make_unique( + "lipm_traj", osc_walking_gains.K_p_com, osc_walking_gains.K_d_com, osc_walking_gains.W_com, plant, + plant); + pelvis_traj->AddPointToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_traj)); + + pelvis_balance_traj = std::make_unique ( + "pelvis_balance_traj", osc_walking_gains.K_p_pelvis_balance, osc_walking_gains.K_d_pelvis_balance, + osc_walking_gains.W_pelvis_balance, plant, plant); + pelvis_balance_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_balance_traj)); + // Pelvis rotation tracking (yaw) + pelvis_heading_traj = std::make_unique ( + "pelvis_heading_traj", osc_walking_gains.K_p_pelvis_heading, osc_walking_gains.K_d_pelvis_heading, + osc_walking_gains.W_pelvis_heading, plant, plant); + pelvis_heading_traj->AddFrameToTrack("pelvis"); + osc->AddTrackingData(std::move(pelvis_heading_traj), + osc_walking_gains.period_of_no_heading_control); + + swing_toe_traj_left = std::make_unique ( + "left_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, + osc_walking_gains.W_swing_toe, plant, plant); + swing_toe_traj_right = std::make_unique ( + "right_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, + osc_walking_gains.W_swing_toe, plant, plant); + swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", + "toe_leftdot"); + swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", + "toe_rightdot"); + osc->AddTrackingData(std::move(swing_toe_traj_left)); + osc->AddTrackingData(std::move(swing_toe_traj_right)); + + swing_hip_yaw_traj = std::make_unique ( + "swing_hip_yaw_traj", osc_walking_gains.K_p_hip_yaw, osc_walking_gains.K_d_hip_yaw, + osc_walking_gains.W_hip_yaw, plant, plant); + swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", + "hip_yaw_rightdot"); + swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", + "hip_yaw_leftdot"); + osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); + + + /**** OSC settings ****/ + + // Build OSC problem + // Set double support duration for force blending + osc->SetUpDoubleSupportPhaseBlending( + double_support_duration, left_stance_state, right_stance_state, + {post_left_double_support_state, post_right_double_support_state}); + + osc->SetOsqpSolverOptionsFromYaml(osqp_settings_filename); + + // Build OSC problem + osc->Build(); + std::cout << "Built OSC" << std::endl; + + /*****Connect ports*****/ + + // OSC connections +// builder.Connect(cassie_out_receiver->get_output_port(), +// high_level_command->get_cassie_out_input_port()); + builder.Connect(state_receiver->get_output_port(0), + high_level_command->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + head_traj_gen->get_state_input_port()); + builder.Connect(high_level_command->get_yaw_output_port(), + head_traj_gen->get_yaw_input_port()); + builder.Connect(state_receiver->get_output_port(0), + fsm->get_input_port_state()); + builder.Connect(fsm->get_output_port(0), + liftoff_event_time->get_input_port_fsm()); + builder.Connect(state_receiver->get_output_port(0), + liftoff_event_time->get_input_port_state()); + builder.Connect(fsm->get_output_port(0), + touchdown_event_time->get_input_port_fsm()); + builder.Connect(state_receiver->get_output_port(0), + touchdown_event_time->get_input_port_state()); + builder.Connect(fsm->get_output_port(0), + lipm_traj_generator->get_input_port_fsm()); + builder.Connect(touchdown_event_time->get_output_port_event_time(), + lipm_traj_generator->get_input_port_touchdown_time()); + builder.Connect(state_receiver->get_output_port(0), + lipm_traj_generator->get_input_port_state()); + builder.Connect(fsm->get_output_port(0), + pelvis_traj_generator->get_input_port_fsm()); + builder.Connect(touchdown_event_time->get_output_port_event_time(), + pelvis_traj_generator->get_input_port_touchdown_time()); + builder.Connect(state_receiver->get_output_port(0), + pelvis_traj_generator->get_input_port_state()); + builder.Connect(high_level_command->get_xy_output_port(), + walking_speed_control->get_input_port_des_hor_vel()); + builder.Connect(state_receiver->get_output_port(0), + walking_speed_control->get_input_port_state()); + builder.Connect(lipm_traj_generator->get_output_port_lipm_from_current(), + walking_speed_control->get_input_port_com()); + builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), + walking_speed_control->get_input_port_fsm_switch_time()); + builder.Connect(fsm->get_output_port(0), + swing_ft_traj_generator->get_input_port_fsm()); + builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), + swing_ft_traj_generator->get_input_port_fsm_switch_time()); + builder.Connect(state_receiver->get_output_port(0), + swing_ft_traj_generator->get_input_port_state()); + builder.Connect(lipm_traj_generator->get_output_port_lipm_from_current(), + swing_ft_traj_generator->get_input_port_com()); + builder.Connect(walking_speed_control->get_output_port(0), + swing_ft_traj_generator->get_input_port_sc()); + builder.Connect(state_receiver->get_output_port(0), + left_toe_angle_traj_gen->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + right_toe_angle_traj_gen->get_state_input_port()); + builder.Connect(state_receiver->get_output_port(0), + osc->get_robot_output_input_port()); + builder.Connect(fsm->get_output_port(0), osc->get_fsm_input_port()); + builder.Connect( + pelvis_traj_generator->get_output_port_lipm_from_touchdown(), + osc->get_tracking_data_input_port("lipm_traj")); + builder.Connect(swing_ft_traj_generator->get_output_port(0), + osc->get_tracking_data_input_port("swing_ft_traj")); + builder.Connect(head_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_heading_traj")); + builder.Connect(head_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("pelvis_balance_traj")); + builder.Connect(left_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("left_toe_angle_traj")); + builder.Connect(right_toe_angle_traj_gen->get_output_port(0), + osc->get_tracking_data_input_port("right_toe_angle_traj")); + builder.Connect(osc->get_output_port(0), command_sender->get_input_port(0)); + + // Publisher connections + builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); + builder.ExportInput(high_level_command->get_cassie_out_input_port(), + "lcmt_cassie_out"); + builder.ExportOutput(command_sender->get_output_port(), "u, t"); + // builder.ExportOutput(failure_aggregator->get_status_output_port(), + // "failure_status"); + + builder.BuildInto(this); + this->set_name(("osc_walking_controller_diagram")); + DrawAndSaveDiagramGraph(*this); + std::cout << "Built controller" << std::endl; +} + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.h b/examples/Cassie/diagrams/osc_walking_controller_diagram.h new file mode 100644 index 0000000000..f0be45a13a --- /dev/null +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.h @@ -0,0 +1,162 @@ +#pragma once + +#include +#include + +#include +#include + +#include "examples/Cassie/osc/osc_walking_gains.h" +#include "multibody/kinematic/distance_evaluator.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/world_point_evaluator.h" +#include "systems/controllers/osc/com_tracking_data.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/osc_gains.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" + +#include "drake/common/drake_copyable.h" +#include "drake/systems/framework/diagram.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/framework/system.h" + +namespace dairlib { +namespace examples { +namespace controllers { + +using drake::multibody::Frame; +using Eigen::Vector3d; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::ComTrackingData; + +class OSCWalkingControllerDiagram final + : public drake::systems::Diagram { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(OSCWalkingControllerDiagram) + + /// @param[in] osc_gains_filename filepath containing the osc_running_gains. + /// @param[in] osqp_settings filepath containing the osqp settings. + OSCWalkingControllerDiagram(drake::multibody::MultibodyPlant& plant, + bool has_double_stance, + const std::string& osc_gains_filename, + const std::string& osqp_settings_filename); + + /// @return the input port for the plant state. + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_input_port_index_); + } + + /// @return the input port for the cassie_out struct (containing radio + /// commands). + const drake::systems::InputPort& get_cassie_out_input_port() const { + return this->get_input_port(cassie_out_input_port_index_); + } + + /// @return the output port for the controller torques. + const drake::systems::OutputPort& get_control_output_port() const { + return this->get_output_port(control_output_port_index_); + } + + /// @return the output port for the failure status of the controller. + const drake::systems::OutputPort& get_controller_failure_output_port() + const { + return this->get_output_port(controller_failure_port_index_); + } + + private: + std::map pos_map; + std::map vel_map; + std::map act_map; + std::pair&> + left_toe; + std::pair&> + left_heel; + std::pair&> + right_toe; + std::pair&> + right_heel; + std::pair&> + left_toe_mid; + std::pair&> + right_toe_mid; + std::pair&> + left_toe_origin; + std::pair&> + right_toe_origin; + std::vector< + std::pair&>> + left_foot_points; + std::vector< + std::pair&>> + right_foot_points; + multibody::WorldYawViewFrame view_frame; + multibody::WorldPointEvaluator left_toe_evaluator; + multibody::WorldPointEvaluator left_heel_evaluator; + multibody::WorldPointEvaluator right_toe_evaluator; + multibody::WorldPointEvaluator right_heel_evaluator; + multibody::DistanceEvaluator left_loop; + multibody::DistanceEvaluator right_loop; + std::unordered_map< + int, std::vector&>>> + feet_contact_points; + std::vector fsm_states; + std::vector state_durations; + std::vector single_support_states; + std::vector double_support_states; + std::vector unordered_fsm_states; + std::vector unordered_state_durations; + std::vector&>>> + contact_points_in_each_state; + std::unique_ptr> plant_context; + std::vector left_right_support_fsm_states; + std::vector left_right_support_state_durations; + std::vector&>> left_right_foot; + std::vector swing_ft_gain_multiplier_breaks; + std::vector> swing_ft_gain_multiplier_samples; + drake::trajectories::PiecewisePolynomial + swing_ft_gain_multiplier_gain_multiplier; + std::vector swing_ft_accel_gain_multiplier_breaks; + std::vector> swing_ft_accel_gain_multiplier_samples; + drake::trajectories::PiecewisePolynomial + swing_ft_accel_gain_multiplier_gain_multiplier; + + multibody::KinematicEvaluatorSet evaluators; + + multibody::FixedJointEvaluator left_fixed_knee_spring; + multibody::FixedJointEvaluator right_fixed_knee_spring; + multibody::FixedJointEvaluator left_fixed_ankle_spring; + multibody::FixedJointEvaluator right_fixed_ankle_spring; + + std::unique_ptr swing_foot_data; + std::unique_ptr com_data; + std::unique_ptr swing_ft_traj_local; + std::unique_ptr swing_ft_traj_global; + + std::unique_ptr pelvis_traj; + + std::unique_ptr pelvis_balance_traj; + std::unique_ptr pelvis_heading_traj; + + std::unique_ptr swing_toe_traj_left; + std::unique_ptr swing_toe_traj_right; + + std::unique_ptr swing_hip_yaw_traj; + + const int state_input_port_index_ = 0; + const int cassie_out_input_port_index_ = 1; + const int control_output_port_index_ = 0; + const int controller_failure_port_index_ = 1; + + const std::string control_channel_name_ = "OSC_WALKING"; +}; + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index c4d747d7a2..1d29c812c3 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -118,7 +118,7 @@ int do_main(int argc, char* argv[]) { auto discrete_time_delay = builder.AddSystem( 1.0 / FLAGS_publish_rate, FLAGS_actuator_delay * FLAGS_publish_rate, - plant.num_actuators()); + plant.num_actuators() + 1); auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( "CASSIE_STATE_SIMULATION", lcm, 1.0 / FLAGS_publish_rate)); @@ -153,18 +153,18 @@ int do_main(int argc, char* argv[]) { // connect leaf systems builder.Connect(*input_sub, *input_receiver); builder.Connect(input_receiver->get_output_port(), - cassie_motor->get_input_port_command()); - builder.Connect(cassie_motor->get_output_port(), - passthrough->get_input_port()); - builder.Connect(passthrough->get_output_port(), discrete_time_delay->get_input_port()); builder.Connect(discrete_time_delay->get_output_port(), + passthrough->get_input_port()); + builder.Connect(passthrough->get_output_port(), + cassie_motor->get_input_port_command()); + builder.Connect(cassie_motor->get_output_port(), plant.get_actuation_input_port()); builder.Connect(plant.get_state_output_port(), state_sender->get_input_port_state()); builder.Connect(plant.get_state_output_port(), cassie_motor->get_input_port_state()); - builder.Connect(discrete_time_delay->get_output_port(), + builder.Connect(cassie_motor->get_output_port(), state_sender->get_input_port_effort()); builder.Connect(*state_sender, *state_pub); builder.Connect( diff --git a/examples/Cassie/osc/osc_walking_gains.h b/examples/Cassie/osc/osc_walking_gains.h index c4bb627788..ae2e398bb0 100644 --- a/examples/Cassie/osc/osc_walking_gains.h +++ b/examples/Cassie/osc/osc_walking_gains.h @@ -1,3 +1,5 @@ +#pragma once + #include "drake/common/yaml/yaml_read_archive.h" #include "yaml-cpp/yaml.h" diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 81d48eb2ba..78099d3581 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -26,6 +26,7 @@ #include "systems/controllers/time_based_fsm.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" @@ -616,6 +617,7 @@ int DoMain(int argc, char* argv[]) { owned_diagram->set_name("osc walking controller"); // Run lcm-driven simulation + DrawAndSaveDiagramGraph(*owned_diagram); systems::LcmDrivenLoop loop( &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc index 49426305ce..f11037ab1b 100644 --- a/systems/controllers/geared_motor.cc +++ b/systems/controllers/geared_motor.cc @@ -22,8 +22,8 @@ GearedMotor::GearedMotor(const MultibodyPlant& plant, actuator_ranges.push_back(joint_actuator.effort_limit()); actuator_max_speeds.push_back(max_motor_speeds[i]); } - systems::TimestampedVector input(plant.num_actuators()); - systems::TimestampedVector output(plant.num_actuators()); + systems::BasicVector input(plant.num_actuators()); + systems::BasicVector output(plant.num_actuators()); command_input_port_ = this->DeclareVectorInputPort("u_cmd", input).get_index(); @@ -36,9 +36,9 @@ GearedMotor::GearedMotor(const MultibodyPlant& plant, void GearedMotor::CalcTorqueOutput( const drake::systems::Context& context, - systems::TimestampedVector* output) const { - const systems::TimestampedVector& u = - *this->template EvalVectorInput(context, + systems::BasicVector* output) const { + const systems::BasicVector& u = + *this->template EvalVectorInput(context, command_input_port_); const systems::BasicVector& x = *this->template EvalVectorInput(context, state_input_port_); @@ -58,8 +58,7 @@ void GearedMotor::CalcTorqueOutput( // tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); } - output->SetDataVector(tau); - output->set_timestamp(u.get_timestamp()); + output->SetFromVector(tau); } } // namespace systems diff --git a/systems/controllers/geared_motor.h b/systems/controllers/geared_motor.h index b1789e4d7a..a894ecaa78 100644 --- a/systems/controllers/geared_motor.h +++ b/systems/controllers/geared_motor.h @@ -30,7 +30,7 @@ class GearedMotor : public drake::systems::LeafSystem { protected: void CalcTorqueOutput( const drake::systems::Context& context, - systems::TimestampedVector* output) const; + systems::BasicVector* output) const; private: bool is_abstract() const { return false;} diff --git a/systems/controllers/lipm_traj_gen.cc b/systems/controllers/lipm_traj_gen.cc index 6ad6258be9..633017eb35 100644 --- a/systems/controllers/lipm_traj_gen.cc +++ b/systems/controllers/lipm_traj_gen.cc @@ -100,6 +100,7 @@ LIPMTrajGenerator::LIPMTrajGenerator( EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( const Context& context, DiscreteValues* discrete_state) const { + std::cout << "discrete var update:" << std::endl; // Read in previous touchdown time auto prev_touchdown_time = discrete_state->get_mutable_vector(prev_touchdown_time_idx_) @@ -112,6 +113,7 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( // when entering a new stance phase if (fsm_state != discrete_state->get_vector(prev_fsm_idx_).GetAtIndex(0)) { + std::cout << "discrete var update:" << std::endl; prev_touchdown_time << touchdown_time; // Read in current state @@ -203,6 +205,12 @@ ExponentialPlusPiecewisePolynomial LIPMTrajGenerator::ConstructLipmTraj( double CoM_wrt_foot_z = (CoM(2) - stance_foot_pos(2)); double dCoM_wrt_foot_x = dCoM(0); double dCoM_wrt_foot_y = dCoM(1); + std::cout << this->get_name() << std::endl; + std::cout << CoM_wrt_foot_x << std::endl; + std::cout << CoM_wrt_foot_y << std::endl; + std::cout << CoM_wrt_foot_z << std::endl; + std::cout << dCoM_wrt_foot_x << std::endl; + std::cout << dCoM_wrt_foot_y << std::endl; DRAKE_DEMAND(CoM_wrt_foot_z > 0); // create a 3D one-segment polynomial for ExponentialPlusPiecewisePolynomial @@ -339,6 +347,7 @@ void LIPMTrajGenerator::CalcTrajFromCurrent( // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); + std::cout << "From current: " << std::endl; *exp_pp_traj = ConstructLipmTraj(CoM, dCoM, stance_foot_pos, start_time, end_time); } @@ -383,6 +392,7 @@ void LIPMTrajGenerator::CalcTrajFromTouchdown( // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); + std::cout << "From touchdown: " << std::endl; *exp_pp_traj = ConstructLipmTraj( CoM_at_touchdown, dCoM_at_touchdown, stance_foot_pos_at_touchdown, prev_touchdown_time, end_time_of_this_fsm_state); From 0df09b97adf3da4cd26c21d4a54d5fdaf489012d Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 18 Mar 2022 14:12:00 -0400 Subject: [PATCH 146/758] fixing radio input port for cpp testing --- bindings/pydairlib/cassie/cassie_gym_test.py | 4 +- examples/Cassie/closed_loop_running_sim.cc | 20 +++++---- .../Cassie/diagrams/cassie_sim_diagram.cc | 8 +++- systems/controllers/lipm_traj_gen.cc | 42 +++++++++---------- 4 files changed, 41 insertions(+), 33 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index 344b36ad13..b2cf1cf4d7 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -14,8 +14,8 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - controller = OSCWalkingControllerFactory(controller_plant, False, osc_walking_gains_filename, osqp_settings) + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, False, osc_walking_gains_filename, osqp_settings) gym_env = CassieGym(visualize=True) gym_env.make(controller, urdf) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 30e480a0d3..7f043efe65 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -34,9 +34,9 @@ int DoMain(int argc, char* argv[]) { std::string osqp_settings = "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; std::unique_ptr> plant = - std::make_unique>(1e-5); + std::make_unique>(8e-5); MultibodyPlant controller_plant = - MultibodyPlant(1e-5); + MultibodyPlant(8e-5); // Built the Cassie MBPs addCassieMultibody(&controller_plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", @@ -47,12 +47,12 @@ int DoMain(int argc, char* argv[]) { auto sim_diagram = builder.AddSystem( std::move(plant), urdf, 0.4, 1e4, 1e2); MultibodyPlant& new_plant = sim_diagram->get_plant(); -// auto controller_diagram = -// builder.AddSystem( -// controller_plant, osc_gains, osqp_settings); auto controller_diagram = - builder.AddSystem( - controller_plant, true, osc_walking_gains, osqp_settings); + builder.AddSystem( + controller_plant, osc_running_gains, osqp_settings); +// auto controller_diagram = +// builder.AddSystem( +// controller_plant, true, osc_walking_gains, osqp_settings); builder.Connect(controller_diagram->get_control_output_port(), sim_diagram->get_actuation_input_port()); @@ -67,6 +67,7 @@ int DoMain(int argc, char* argv[]) { std::cout << "built diagram: " << std::endl; std::unique_ptr> diagram_context = diagram->CreateDefaultContext(); + VectorXd x_init = VectorXd::Zero(45); x_init << 1, 0, 0, 0, 0, 0, 1, -0.0304885, 0, 0.466767, -1.15602, -0.037542, 1.45243, -0.0257992, -1.59913, 0.0304885, 0, 0.466767, -1.15602, @@ -76,7 +77,12 @@ int DoMain(int argc, char* argv[]) { diagram->GetMutableSubsystemContext(new_plant, diagram_context.get()); drake::systems::Simulator simulator(*diagram, std::move(diagram_context)); + Context& simulator_context = diagram->GetMutableSubsystemContext(*sim_diagram, &simulator.get_mutable_context()); + + sim_diagram->get_radio_input_port().FixValue(&simulator_context, Eigen::VectorXd::Zero(18)); + new_plant.SetPositionsAndVelocities(&plant_context, x_init); + simulator.Initialize(); // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; simulator.AdvanceTo(5.0); diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 4cc5b835ae..eca8ebfb5a 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -2,6 +2,7 @@ #include "cassie_sim_diagram.h" #include +#include #include "dairlib/lcmt_cassie_out.hpp" #include "dairlib/lcmt_robot_input.hpp" @@ -15,6 +16,7 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" +#include "drake/geometry/drake_visualizer.h" #include "drake/lcm/drake_lcm.h" #include "drake/lcmt_contact_results_for_viz.hpp" #include "drake/multibody/plant/contact_results_to_lcm.h" @@ -25,7 +27,6 @@ #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/primitives/discrete_time_delay.h" -#include "drake/geometry/drake_visualizer.h" namespace dairlib { namespace examples { @@ -74,6 +75,9 @@ CassieSimDiagram::CassieSimDiagram( auto constant_source = builder.AddSystem( VectorXd::Zero(10)); + auto input_zero_order_hold = + builder.AddSystem( + 0.001, plant_->num_actuators() + 1); sensor_aggregator_ = &AddImuAndAggregator(&builder, *plant_, constant_source->get_output_port()); @@ -86,6 +90,8 @@ CassieSimDiagram::CassieSimDiagram( // connect leaf systems builder.Connect(input_receiver->get_output_port(), + input_zero_order_hold->get_input_port()); + builder.Connect(input_zero_order_hold->get_output_port(), discrete_time_delay->get_input_port()); builder.Connect(discrete_time_delay->get_output_port(), passthrough->get_input_port()); diff --git a/systems/controllers/lipm_traj_gen.cc b/systems/controllers/lipm_traj_gen.cc index 633017eb35..c06c3f6a15 100644 --- a/systems/controllers/lipm_traj_gen.cc +++ b/systems/controllers/lipm_traj_gen.cc @@ -100,7 +100,7 @@ LIPMTrajGenerator::LIPMTrajGenerator( EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( const Context& context, DiscreteValues* discrete_state) const { - std::cout << "discrete var update:" << std::endl; +// std::cout << "discrete var update:" << std::endl; // Read in previous touchdown time auto prev_touchdown_time = discrete_state->get_mutable_vector(prev_touchdown_time_idx_) @@ -113,7 +113,6 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( // when entering a new stance phase if (fsm_state != discrete_state->get_vector(prev_fsm_idx_).GetAtIndex(0)) { - std::cout << "discrete var update:" << std::endl; prev_touchdown_time << touchdown_time; // Read in current state @@ -142,7 +141,7 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( &position); stance_foot_pos += position; } - stance_foot_pos /= contact_points_in_each_state_[mode_index].size(); + stance_foot_pos *= (1.0 / contact_points_in_each_state_[mode_index].size()); // Get center of mass position and velocity Vector3d CoM; @@ -160,16 +159,15 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( plant_.GetBodyByName("pelvis").body_frame(), VectorXd::Zero(3), world_, world_, &J); } +// std::cout << "updating COM:" << std::endl; +// std::cout << this->get_name() << std::endl; +// std::cout << CoM << std::endl; Vector3d dCoM = J * v; - discrete_state->get_mutable_vector(stance_foot_pos_idx_).get_mutable_value() - << stance_foot_pos; - discrete_state->get_mutable_vector(touchdown_com_pos_idx_) - .get_mutable_value() - << CoM; - discrete_state->get_mutable_vector(touchdown_com_vel_idx_) - .get_mutable_value() - << dCoM; + discrete_state->get_mutable_vector(stance_foot_pos_idx_) + .set_value(stance_foot_pos); + discrete_state->get_mutable_vector(touchdown_com_pos_idx_).set_value(CoM); + discrete_state->get_mutable_vector(touchdown_com_vel_idx_).set_value(dCoM); // Testing // Heuristic ratio for LIPM dyanmics (because the centroidal angular @@ -205,12 +203,6 @@ ExponentialPlusPiecewisePolynomial LIPMTrajGenerator::ConstructLipmTraj( double CoM_wrt_foot_z = (CoM(2) - stance_foot_pos(2)); double dCoM_wrt_foot_x = dCoM(0); double dCoM_wrt_foot_y = dCoM(1); - std::cout << this->get_name() << std::endl; - std::cout << CoM_wrt_foot_x << std::endl; - std::cout << CoM_wrt_foot_y << std::endl; - std::cout << CoM_wrt_foot_z << std::endl; - std::cout << dCoM_wrt_foot_x << std::endl; - std::cout << dCoM_wrt_foot_y << std::endl; DRAKE_DEMAND(CoM_wrt_foot_z > 0); // create a 3D one-segment polynomial for ExponentialPlusPiecewisePolynomial @@ -347,7 +339,9 @@ void LIPMTrajGenerator::CalcTrajFromCurrent( // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); - std::cout << "From current: " << std::endl; +// std::cout << "From current: " << std::endl; +// std::cout << context.get_discrete_state(touchdown_com_pos_idx_).value() << std::endl; +// std::cout << this->get_name() << std::endl; *exp_pp_traj = ConstructLipmTraj(CoM, dCoM, stance_foot_pos, start_time, end_time); } @@ -378,21 +372,23 @@ void LIPMTrajGenerator::CalcTrajFromTouchdown( // Get center of mass position and velocity const auto CoM_at_touchdown = - context.get_discrete_state(touchdown_com_pos_idx_).get_value(); + context.get_discrete_state(touchdown_com_pos_idx_).value(); const auto dCoM_at_touchdown = - context.get_discrete_state(touchdown_com_vel_idx_).get_value(); + context.get_discrete_state(touchdown_com_vel_idx_).value(); // Stance foot position const auto stance_foot_pos_at_touchdown = - context.get_discrete_state(stance_foot_pos_idx_).get_value(); + context.get_discrete_state(stance_foot_pos_idx_).value(); double prev_touchdown_time = - this->EvalVectorInput(context, touchdown_time_port_)->get_value()(0); + this->EvalVectorInput(context, touchdown_time_port_)->value()(0); // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); - std::cout << "From touchdown: " << std::endl; +// std::cout << "From touchdown: " << std::endl; +// std::cout << CoM_at_touchdown << std::endl; +// std::cout << this->get_name() << std::endl; *exp_pp_traj = ConstructLipmTraj( CoM_at_touchdown, dCoM_at_touchdown, stance_foot_pos_at_touchdown, prev_touchdown_time, end_time_of_this_fsm_state); From ea3c2d09d8524956a9b32b85cadfde3c2fc9e1e7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 18 Mar 2022 14:14:53 -0400 Subject: [PATCH 147/758] cleaning up running controller --- .../Cassie/diagrams/osc_running_controller_diagram.cc | 11 ----------- 1 file changed, 11 deletions(-) diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 9f5d7cc116..3dfb270089 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -224,9 +224,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( std::cout << "Creating tracking data. " << std::endl; - // auto cassie_out_receiver = - // builder.AddSystem(LcmSubscriberSystem::Make( - // FLAGS_channel_cassie_out, &lcm)); cassie::osc::HighLevelCommand* high_level_command; high_level_command = builder.AddSystem( plant, plant_context.get(), osc_running_gains.vel_scale_rot, @@ -362,14 +359,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_foot_rel_tracking_data->SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); -// std::cout << "here: " << std::endl; osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); -// std::cout << "here 1: " << std::endl; auto heading_traj_generator = builder.AddSystem(plant, plant_context.get()); @@ -389,10 +384,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); // Swing toe joint trajectory -// vector&>> left_foot_points = { -// left_heel, left_toe}; -// vector&>> right_foot_points = { -// right_heel, right_toe}; auto left_toe_angle_traj_gen = builder.AddSystem( plant, plant_context.get(), pos_map["toe_left"], left_foot_points, "left_toe_angle_traj"); @@ -438,8 +429,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - // left_hip_yaw_tracking_data.SetImpactInvariantProjection(true); - // right_hip_yaw_tracking_data.SetImpactInvariantProjection(true); osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); From af45c69d0fc56cbad5fb74b4b8c333952ed806e9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 18 Mar 2022 14:24:11 -0400 Subject: [PATCH 148/758] adding bindings for input supervisor --- bindings/pydairlib/cassie/BUILD.bazel | 28 +++++++++++++------------- examples/Cassie/dispatcher_robot_in.cc | 8 ++++---- 2 files changed, 18 insertions(+), 18 deletions(-) diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index 74857c6928..004280f87e 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -56,20 +56,20 @@ pybind_py_library( py_imports = ["."], ) -#pybind_py_library( -# name = "input_supervisor_py", -# cc_deps = [ -# "//examples/Cassie:input_supervisor", -# "@drake//:drake_shared_library", -# ], -# cc_so_name = "input_supervisor", -# cc_srcs = ["input_supervisor_py.cc"], -# py_deps = [ -# "@drake//bindings/pydrake", -# ":module_py", -# ], -# py_imports = ["."], -#) +pybind_py_library( + name = "input_supervisor_py", + cc_deps = [ + "//examples/Cassie:input_supervisor", + "@drake//:drake_shared_library", + ], + cc_so_name = "input_supervisor", + cc_srcs = ["input_supervisor_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + ":module_py", + ], + py_imports = ["."], +) pybind_py_library( name = "controllers_py", diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 3459d3865b..2e5f6b0471 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -92,7 +92,7 @@ int do_main(int argc, char* argv[]) { auto command_receiver = builder.AddSystem(plant); // Safety Controller - auto controller = builder.AddSystem( + auto safety_controller = builder.AddSystem( plant.num_positions(), plant.num_velocities(), plant.num_actuators()); // Create config receiver. auto config_receiver = builder.AddSystem(plant); @@ -145,10 +145,10 @@ int do_main(int argc, char* argv[]) { builder.Connect(cassie_out_receiver->get_output_port(), input_supervisor->get_input_port_cassie()); builder.Connect(state_receiver->get_output_port(0), - controller->get_input_port_output()); + safety_controller->get_input_port_output()); builder.Connect(config_receiver->get_output_port(0), - controller->get_input_port_config()); - builder.Connect(controller->get_output_port(0), + safety_controller->get_input_port_config()); + builder.Connect(safety_controller->get_output_port(0), input_supervisor->get_input_port_safety_controller()); builder.Connect(input_supervisor->get_output_port_failure(), controller_error_pub->get_input_port()); From 63000a235d7c6e5a68570317a684768145a0d093 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 10:52:09 -0400 Subject: [PATCH 149/758] added walking example --- bindings/pydairlib/cassie/cassie_gym.py | 6 ++- bindings/pydairlib/cassie/cassie_gym_test.py | 5 +- .../osc_walking_controller_diagram.cc | 49 ++++++++++++++----- examples/Cassie/osc/osc_walking_gains.yaml | 2 +- systems/controllers/lipm_traj_gen.cc | 34 ++++++------- 5 files changed, 58 insertions(+), 38 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index fc8dd3a9a8..57a16cfb48 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -86,8 +86,10 @@ def get_state(self): def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt - forward_vel = 0.25 - lateral_vel = 0.1 + # forward_vel = 0.25 + # lateral_vel = 0.1 + forward_vel = 0 + lateral_vel = 0 action[2] = forward_vel action[3] = lateral_vel # action = lcmt_radio_out diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index b2cf1cf4d7..036b0c7e2b 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -9,13 +9,14 @@ def main(): osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' + default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, False, osc_walking_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) gym_env = CassieGym(visualize=True) gym_env.make(controller, urdf) diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index b04b9f03a4..cbe49e765b 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -139,27 +139,32 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( // vector fsm_states; // vector state_durations; if (has_double_stance) { - fsm_states = {left_stance_state, right_stance_state}; - state_durations = {left_support_duration, right_support_duration}; - } else { fsm_states = {left_stance_state, post_left_double_support_state, right_stance_state, post_right_double_support_state}; state_durations = {left_support_duration, double_support_duration, right_support_duration, double_support_duration}; + unordered_fsm_states = {left_stance_state, right_stance_state, + post_left_double_support_state, + post_right_double_support_state}; + unordered_state_durations = {left_support_duration, right_support_duration, + double_support_duration, + double_support_duration}; + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + + } else { + fsm_states = {left_stance_state, right_stance_state}; + state_durations = {left_support_duration, right_support_duration}; + unordered_fsm_states = {left_stance_state, right_stance_state}; + unordered_state_durations = {left_support_duration, right_support_duration}; + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); } single_support_states = {left_stance_state, right_stance_state}; double_support_states = {post_left_double_support_state, post_right_double_support_state}; - unordered_fsm_states = {left_stance_state, right_stance_state, - post_left_double_support_state, - post_right_double_support_state}; - unordered_state_durations = {left_support_duration, right_support_duration, - double_support_duration, - double_support_duration}; - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); left_right_support_fsm_states = {left_stance_state, right_stance_state}; left_right_support_state_durations = {left_support_duration, right_support_duration}; @@ -219,6 +224,24 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); + if (has_double_stance) { + osc->AddStateAndContactPoint(post_left_double_support_state, + &left_toe_evaluator); + osc->AddStateAndContactPoint(post_left_double_support_state, + &left_heel_evaluator); + osc->AddStateAndContactPoint(post_left_double_support_state, + &right_toe_evaluator); + osc->AddStateAndContactPoint(post_left_double_support_state, + &right_heel_evaluator); + osc->AddStateAndContactPoint(post_right_double_support_state, + &left_toe_evaluator); + osc->AddStateAndContactPoint(post_right_double_support_state, + &left_heel_evaluator); + osc->AddStateAndContactPoint(post_right_double_support_state, + &right_toe_evaluator); + osc->AddStateAndContactPoint(post_right_double_support_state, + &right_heel_evaluator); + } evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); diff --git a/examples/Cassie/osc/osc_walking_gains.yaml b/examples/Cassie/osc/osc_walking_gains.yaml index 4ed826acf8..49a2d568ff 100644 --- a/examples/Cassie/osc/osc_walking_gains.yaml +++ b/examples/Cassie/osc/osc_walking_gains.yaml @@ -48,7 +48,7 @@ final_foot_height: 0.0 final_foot_velocity_z: 0.0 # LIPM trajectory -lipm_height: 0.9 +lipm_height: 0.85 # OSC gains mu: 0.8 diff --git a/systems/controllers/lipm_traj_gen.cc b/systems/controllers/lipm_traj_gen.cc index c06c3f6a15..cdfebe1822 100644 --- a/systems/controllers/lipm_traj_gen.cc +++ b/systems/controllers/lipm_traj_gen.cc @@ -92,7 +92,7 @@ LIPMTrajGenerator::LIPMTrajGenerator( // The stance foot position in the beginning of the swing phase stance_foot_pos_idx_ = this->DeclareDiscreteState(3); // COM state at touchdown - touchdown_com_pos_idx_ = this->DeclareDiscreteState(3); + touchdown_com_pos_idx_ = this->DeclareDiscreteState(Vector3d(0, 0, 0.9)); touchdown_com_vel_idx_ = this->DeclareDiscreteState(3); prev_fsm_idx_ = this->DeclareDiscreteState(-1 * VectorXd::Ones(1)); } @@ -100,7 +100,6 @@ LIPMTrajGenerator::LIPMTrajGenerator( EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( const Context& context, DiscreteValues* discrete_state) const { -// std::cout << "discrete var update:" << std::endl; // Read in previous touchdown time auto prev_touchdown_time = discrete_state->get_mutable_vector(prev_touchdown_time_idx_) @@ -141,7 +140,7 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( &position); stance_foot_pos += position; } - stance_foot_pos *= (1.0 / contact_points_in_each_state_[mode_index].size()); + stance_foot_pos /= contact_points_in_each_state_[mode_index].size(); // Get center of mass position and velocity Vector3d CoM; @@ -159,15 +158,16 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( plant_.GetBodyByName("pelvis").body_frame(), VectorXd::Zero(3), world_, world_, &J); } -// std::cout << "updating COM:" << std::endl; -// std::cout << this->get_name() << std::endl; -// std::cout << CoM << std::endl; Vector3d dCoM = J * v; - discrete_state->get_mutable_vector(stance_foot_pos_idx_) - .set_value(stance_foot_pos); - discrete_state->get_mutable_vector(touchdown_com_pos_idx_).set_value(CoM); - discrete_state->get_mutable_vector(touchdown_com_vel_idx_).set_value(dCoM); + discrete_state->get_mutable_vector(stance_foot_pos_idx_).get_mutable_value() + << stance_foot_pos; + discrete_state->get_mutable_vector(touchdown_com_pos_idx_) + .get_mutable_value() + << CoM; + discrete_state->get_mutable_vector(touchdown_com_vel_idx_) + .get_mutable_value() + << dCoM; // Testing // Heuristic ratio for LIPM dyanmics (because the centroidal angular @@ -339,9 +339,6 @@ void LIPMTrajGenerator::CalcTrajFromCurrent( // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); -// std::cout << "From current: " << std::endl; -// std::cout << context.get_discrete_state(touchdown_com_pos_idx_).value() << std::endl; -// std::cout << this->get_name() << std::endl; *exp_pp_traj = ConstructLipmTraj(CoM, dCoM, stance_foot_pos, start_time, end_time); } @@ -372,23 +369,20 @@ void LIPMTrajGenerator::CalcTrajFromTouchdown( // Get center of mass position and velocity const auto CoM_at_touchdown = - context.get_discrete_state(touchdown_com_pos_idx_).value(); + context.get_discrete_state(touchdown_com_pos_idx_).get_value(); const auto dCoM_at_touchdown = - context.get_discrete_state(touchdown_com_vel_idx_).value(); + context.get_discrete_state(touchdown_com_vel_idx_).get_value(); // Stance foot position const auto stance_foot_pos_at_touchdown = - context.get_discrete_state(stance_foot_pos_idx_).value(); + context.get_discrete_state(stance_foot_pos_idx_).get_value(); double prev_touchdown_time = - this->EvalVectorInput(context, touchdown_time_port_)->value()(0); + this->EvalVectorInput(context, touchdown_time_port_)->get_value()(0); // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); -// std::cout << "From touchdown: " << std::endl; -// std::cout << CoM_at_touchdown << std::endl; -// std::cout << this->get_name() << std::endl; *exp_pp_traj = ConstructLipmTraj( CoM_at_touchdown, dCoM_at_touchdown, stance_foot_pos_at_touchdown, prev_touchdown_time, end_time_of_this_fsm_state); From 52b1105d66ba742345846e722cbf6c2f15c3cb76 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 10:58:26 -0400 Subject: [PATCH 150/758] small code cleanup --- bindings/pydairlib/cassie/cassie_gym.py | 8 ++++---- .../Cassie/diagrams/osc_running_controller_diagram.cc | 2 -- examples/Cassie/diagrams/osc_running_controller_diagram.h | 3 --- .../Cassie/diagrams/osc_walking_controller_diagram.cc | 2 +- examples/Cassie/diagrams/osc_walking_controller_diagram.h | 4 ++-- 5 files changed, 7 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index 57a16cfb48..920cafe9ba 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -86,10 +86,10 @@ def get_state(self): def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt - # forward_vel = 0.25 - # lateral_vel = 0.1 - forward_vel = 0 - lateral_vel = 0 + forward_vel = 0.25 + lateral_vel = 0.1 + # forward_vel = 0 + # lateral_vel = 0 action[2] = forward_vel action[3] = lateral_vel # action = lcmt_radio_out diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 3dfb270089..0219998a4a 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -7,8 +7,6 @@ #include #include "common/find_resource.h" -#include "dairlib/lcmt_robot_input.hpp" -#include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" #include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index 626aed505f..d99758bd00 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -129,9 +129,6 @@ class OSCRunningControllerDiagram final std::unique_ptr left_hip_yaw_tracking_data; std::unique_ptr right_hip_yaw_tracking_data; -// OSCGains osc_gains_; -// OSCRunningGains osc_running_gains_; - const int state_input_port_index_ = 0; const int cassie_out_input_port_index_ = 1; const int control_output_port_index_ = 0; diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index cbe49e765b..129ee752a2 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -124,7 +124,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( {right_toe, right_heel}); /**** OSC Gains ****/ - OSCWalkingGains osc_walking_gains = + auto osc_walking_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(osc_walking_gains_filename)); diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.h b/examples/Cassie/diagrams/osc_walking_controller_diagram.h index f0be45a13a..34f6788921 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.h @@ -29,11 +29,11 @@ namespace controllers { using drake::multibody::Frame; using Eigen::Vector3d; +using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -using systems::controllers::ComTrackingData; class OSCWalkingControllerDiagram final : public drake::systems::Diagram { @@ -89,6 +89,7 @@ class OSCWalkingControllerDiagram final left_toe_origin; std::pair&> right_toe_origin; + std::vector&>> left_right_foot; std::vector< std::pair&>> left_foot_points; @@ -117,7 +118,6 @@ class OSCWalkingControllerDiagram final std::unique_ptr> plant_context; std::vector left_right_support_fsm_states; std::vector left_right_support_state_durations; - std::vector&>> left_right_foot; std::vector swing_ft_gain_multiplier_breaks; std::vector> swing_ft_gain_multiplier_samples; drake::trajectories::PiecewisePolynomial From 2134f11531bb807fce37f96a151229e4120895fb Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 11:06:22 -0400 Subject: [PATCH 151/758] merging with master --- bindings/pydairlib/cassie/cassie_gym_test.py | 4 ++-- examples/Cassie/diagrams/osc_running_controller_diagram.cc | 7 ------- 2 files changed, 2 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index 036b0c7e2b..08a21282cc 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -15,8 +15,8 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) gym_env = CassieGym(visualize=True) gym_env.make(controller, urdf) diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 0219998a4a..6ad8a6a10d 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -28,7 +28,6 @@ #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/filters/floating_base_velocity_filter.h" -#include "systems/framework/lcm_driven_loop.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -36,7 +35,6 @@ #include "drake/common/yaml/yaml_read_archive.h" #include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_publisher_system.h" namespace dairlib { @@ -58,8 +56,6 @@ using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; -using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::LcmSubscriberSystem; using drake::trajectories::PiecewisePolynomial; using examples::osc::PelvisPitchTrajGenerator; using examples::osc::PelvisRollTrajGenerator; @@ -169,9 +165,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, osc_gains.impact_threshold); - /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( From e56d2c36fae14c915fddeb4a27cb4f45b3f816dc Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 11:12:35 -0400 Subject: [PATCH 152/758] pulling action outside of env --- bindings/pydairlib/cassie/cassie_gym.py | 9 --------- bindings/pydairlib/cassie/cassie_gym_test.py | 10 +++++++--- 2 files changed, 7 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index 920cafe9ba..d12f4a6ad9 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -86,15 +86,6 @@ def get_state(self): def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt - forward_vel = 0.25 - lateral_vel = 0.1 - # forward_vel = 0 - # lateral_vel = 0 - action[2] = forward_vel - action[3] = lateral_vel - # action = lcmt_radio_out - # self.simulator.get_radio_input_port().FixValue(self.simulator_context, AbstractValue.Make(action)) - self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.sim.AdvanceTo(next_timestep) # import pdb; pdb.set_trace() diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index 08a21282cc..fc5f90c55b 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -15,13 +15,17 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) gym_env = CassieGym(visualize=True) gym_env.make(controller, urdf) - gym_env.advance_to(10) + action = np.zeros(18) + action[2] = 0.25 + while gym_env.current_time < 10: + gym_env.step(action) + if __name__ == '__main__': main() From f85937ec6b9c35f3af34f9e1d917c60a1422c3e1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 11:28:05 -0400 Subject: [PATCH 153/758] returning state in test script --- bindings/pydairlib/cassie/cassie_gym.py | 5 +---- bindings/pydairlib/cassie/cassie_gym_test.py | 2 +- bindings/pydairlib/cassie/cassie_traj.py | 1 + 3 files changed, 3 insertions(+), 5 deletions(-) diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/cassie_gym.py index d12f4a6ad9..d3e1d83226 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/cassie_gym.py @@ -81,17 +81,14 @@ def advance_to(self, time): self.step() return self.traj - def get_state(self): - return self.traj.get_positions()[-1] - def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.sim.AdvanceTo(next_timestep) - # import pdb; pdb.set_trace() cassie_state = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context())) + self.current_time = next_timestep self.traj.update(next_timestep, cassie_state, action[:10]) return cassie_state diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/cassie_gym_test.py index fc5f90c55b..1685c8dc08 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/cassie_gym_test.py @@ -25,7 +25,7 @@ def main(): action = np.zeros(18) action[2] = 0.25 while gym_env.current_time < 10: - gym_env.step(action) + state = gym_env.step(action) if __name__ == '__main__': main() diff --git a/bindings/pydairlib/cassie/cassie_traj.py b/bindings/pydairlib/cassie/cassie_traj.py index 3557155952..b05490cf7d 100644 --- a/bindings/pydairlib/cassie/cassie_traj.py +++ b/bindings/pydairlib/cassie/cassie_traj.py @@ -35,6 +35,7 @@ def time_to_index(self, t): return int(t * 2000) def get_positions(self): + import pdb; pdb.set_trace() return self.x_samples[:, CASSIE_POSITION_SLICE] def get_orientations(self): From 63ea6d65de96bef46186ee9245939ca4e49a68aa Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 16:04:17 -0400 Subject: [PATCH 154/758] working on reward functions --- bindings/pydairlib/cassie/BUILD.bazel | 43 ---------- .../cassie/cassie_running_controller.py | 81 ------------------- .../pydairlib/cassie/gym_envs/BUILD.bazel | 61 ++++++++++++++ .../cassie/{ => gym_envs}/cassie_actor.py | 0 .../cassie/{ => gym_envs}/cassie_gym.py | 23 ++++-- .../cassie/{ => gym_envs}/cassie_gym_test.py | 14 +++- .../cassie/{ => gym_envs}/cassie_traj.py | 1 - .../pydairlib/cassie/gym_envs/reward_base.py | 23 ++++++ .../cassie/gym_envs/reward_osudrl.py | 80 ++++++++++++++++++ bindings/pydairlib/cassie/yaml_structs_py.cc | 23 ------ examples/trifinger/simulate_trifinger.py | 53 ++++++------ 11 files changed, 216 insertions(+), 186 deletions(-) delete mode 100644 bindings/pydairlib/cassie/cassie_running_controller.py create mode 100644 bindings/pydairlib/cassie/gym_envs/BUILD.bazel rename bindings/pydairlib/cassie/{ => gym_envs}/cassie_actor.py (100%) rename bindings/pydairlib/cassie/{ => gym_envs}/cassie_gym.py (84%) rename bindings/pydairlib/cassie/{ => gym_envs}/cassie_gym_test.py (66%) rename bindings/pydairlib/cassie/{ => gym_envs}/cassie_traj.py (98%) create mode 100644 bindings/pydairlib/cassie/gym_envs/reward_base.py create mode 100644 bindings/pydairlib/cassie/gym_envs/reward_osudrl.py delete mode 100644 bindings/pydairlib/cassie/yaml_structs_py.cc diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index 004280f87e..e854064681 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -11,34 +11,6 @@ load( "pybind_py_library", ) -py_library( - name = "cassie_gym", - srcs = ["cassie_gym.py"], - deps = [ - "//bindings/pydairlib/cassie:cassie", - "//bindings/pydairlib", - "//bindings/pydairlib/systems:systems", - "//bindings/pydairlib/multibody", - "//bindings/pydairlib/systems:primitives_py", - ], -) - -py_binary( - name = "cassie_gym_test", - srcs = ["cassie_gym_test.py"], - deps = [ - "//bindings/pydairlib/cassie:cassie_gym", - "//bindings/pydairlib/cassie:cassie", - "@drake//bindings/pydrake", - ], -) - -py_library( - name = "cassie_traj", - srcs = ["cassie_traj.py"], - deps = [ - ], -) pybind_py_library( name = "cassie_utils_py", @@ -87,21 +59,6 @@ pybind_py_library( py_imports = ["."], ) -pybind_py_library( - name = "dairlib_yaml_py", - cc_deps = [ - "@drake//:drake_shared_library", - "//examples/Cassie/osc_run:osc_running_gains", - ], - cc_so_name = "dairlib_yaml", - cc_srcs = ["yaml_structs_py.cc"], - py_deps = [ - "@drake//bindings/pydrake", - ":module_py", - ], - py_imports = ["."], -) - pybind_py_library( name = "simulators_py", cc_deps = [ diff --git a/bindings/pydairlib/cassie/cassie_running_controller.py b/bindings/pydairlib/cassie/cassie_running_controller.py deleted file mode 100644 index 2e2d71ff4e..0000000000 --- a/bindings/pydairlib/cassie/cassie_running_controller.py +++ /dev/null @@ -1,81 +0,0 @@ -import numpy as np -from cassie_actor import * - -from pydrake.multibody.parsing import Parser -from pydrake.systems.framework import DiagramBuilder -from pydrake.multibody.plant import * -from pydrake.systems.analysis import Simulator - -from pydairlib.common import FindResourceOrThrow -from pydairlib.cassie.cassie_utils import * -from pydairlib.multibody import * -from pydairlib.systems.primitives import * - - -class CassieRunningController(CassieActor): - def __init__(self, visualize=False): - self.sim_dt = 5e-5 - self.action_dim = 10 - self.state_dim = 45 - - def make(self, params): - self.builder = DiagramBuilder() - self.dt = 5e-4 - self.params = params - - terrain_normal = np.array([0.0, 0.0, 1.0]) - self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, self.sim_dt) - AddCassieMultibody(self.plant, self.scene_graph, True, urdf, True, True) - AddFlatTerrain(self.plant, self.scene_graph, params['mu'], params['mu'], terrain_normal, params['stiffness'], - params['dissipation']) - - self.plant.Finalize() - - self.builder.Connect(self.controller_inputs.get_command_output_port(), self.passthrough.get_input_port()) - self.builder.Connect(self.passthrough.get_output_port(), self.plant.get_actuation_input_port()) - self.diagram = self.builder.Build() - self.sim = Simulator(self.diagram) - - self.plant_context = self.diagram.GetMutableSubsystemContext(self.plant, self.sim.get_mutable_context()) - self.sim.get_mutable_context().SetTime(self.start_time) - self.reset() - - def reset(self): - self.traj = CassieTraj() - self.plant.SetPositionsAndVelocities(self.plant.GetMyMutableContextFromRoot( - self.sim.get_mutable_context()), self.x_init) - self.sim.get_mutable_context().SetTime(self.start_time) - self.traj.update(self.start_time, self.x_init, - np.zeros(self.action_dim)) - self.sim.Initialize() - self.current_time = self.start_time - return - - def advance_to(self, time): - while self.current_time < time: - self.step() - return self.traj - - def get_state(self): - return self.traj.get_positions()[-1] - - def step(self, action=np.zeros(10)): - next_timestep = self.sim.get_context().get_time() + self.dt - if self.controller: - action = self.controller.eval(self.get_state()) - self.plant.get_actuation_input_port().FixValue(self.plant_context, action) - self.sim.AdvanceTo(next_timestep) - - cassie_state = self.plant.GetPositionsAndVelocities( - self.plant.GetMyMutableContextFromRoot( - self.sim.get_mutable_context())) - self.current_time = next_timestep - self.traj.update(next_timestep, cassie_state, action) - return cassie_state - - def get_traj(self): - return self.traj - - # Some simulators for Cassie require cleanup - def free_sim(self): - return diff --git a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel new file mode 100644 index 0000000000..d33a0ebef0 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel @@ -0,0 +1,61 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + + +py_library( + name = "cassie_gym", + srcs = ["cassie_gym.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie", + "//bindings/pydairlib", + "//bindings/pydairlib/systems:systems", + "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems:primitives_py", + ":cassie_env_state", + ], +) + + +py_binary( + name = "cassie_gym_test", + srcs = ["cassie_gym_test.py"], + deps = [ + ":cassie_gym", + ":cassie_env_rewards", + "//bindings/pydairlib/cassie:cassie", + "@drake//bindings/pydrake", + ], +) + +py_library( + name = "cassie_traj", + srcs = ["cassie_traj.py"], + deps = [ + ], +) + +py_library( + name = "cassie_env_state", + srcs = ["cassie_env_state.py"], + deps = [ + ], +) + +py_library( + name = "cassie_env_rewards", + srcs = ["reward_base.py", + "reward_osudrl.py"], + deps = [ + ":cassie_env_state" + ], +) \ No newline at end of file diff --git a/bindings/pydairlib/cassie/cassie_actor.py b/bindings/pydairlib/cassie/gym_envs/cassie_actor.py similarity index 100% rename from bindings/pydairlib/cassie/cassie_actor.py rename to bindings/pydairlib/cassie/gym_envs/cassie_actor.py diff --git a/bindings/pydairlib/cassie/cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py similarity index 84% rename from bindings/pydairlib/cassie/cassie_gym.py rename to bindings/pydairlib/cassie/gym_envs/cassie_gym.py index d3e1d83226..6fe909ab4c 100644 --- a/bindings/pydairlib/cassie/cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py @@ -13,12 +13,14 @@ from pydairlib.systems.robot_lcm_systems import RobotOutputSender from dairlib import lcmt_radio_out from pydairlib.cassie.simulators import CassieSimDiagram +from pydairlib.cassie.gym_envs.cassie_env_state import CassieEnvState class CassieGym(): - def __init__(self, visualize=False): + def __init__(self, reward_func, visualize=False): # self.sim_dt = 8e-5 self.visualize = visualize + self.reward_func = reward_func # hardware logs are 50ms long and start approximately 5ms before impact # the simulator will check to make sure ground reaction forces are first detected within 3-7ms self.start_time = 0.00 @@ -35,6 +37,7 @@ def __init__(self, visualize=False): self.default_contact_params = {"mu": 0.8, "stiffness": 4e4, "dissipation": 0.5} + self.prev_cassie_state = None self.controller = None def make(self, controller, urdf): @@ -68,12 +71,13 @@ def reset(self): self.sim.get_mutable_context().SetTime(self.start_time) self.traj.update(self.start_time, self.x_init, np.zeros(self.action_dim)) - self.sim.Initialize() - cassie_state = self.plant.GetPositionsAndVelocities( + x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context())) - + u = np.zeros(10) + self.sim.Initialize() self.current_time = self.start_time + self.prev_cassie_state = CassieEnvState(self.current_time, x, u, np.zeros(18)) return def advance_to(self, time): @@ -85,13 +89,16 @@ def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.sim.AdvanceTo(next_timestep) - cassie_state = self.plant.GetPositionsAndVelocities( + x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context())) - + u = np.zeros(10) self.current_time = next_timestep - self.traj.update(next_timestep, cassie_state, action[:10]) - return cassie_state + cassie_state = CassieEnvState(self.current_time, x, u, action) + reward = self.reward_func.compute_reward(cassie_state, self.prev_cassie_state) + self.prev_cassie_state = cassie_state + # self.traj.update(next_timestep, cassie_state, action[:10]) + return cassie_state, reward def get_traj(self): return self.traj diff --git a/bindings/pydairlib/cassie/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py similarity index 66% rename from bindings/pydairlib/cassie/cassie_gym_test.py rename to bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 1685c8dc08..e287ce4190 100644 --- a/bindings/pydairlib/cassie/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -3,6 +3,7 @@ from pydairlib.cassie.controllers import OSCRunningControllerFactory from pydairlib.cassie.controllers import OSCWalkingControllerFactory from pydairlib.cassie.simulators import CassieSimDiagram +from pydairlib.cassie.gym_envs.reward_osudrl import RewardOSUDRL from pydrake.common.yaml import yaml_load def main(): @@ -11,13 +12,18 @@ def main(): osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' + reward_function_weights = '' controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) - gym_env = CassieGym(visualize=True) + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + + # reward_func = RewardOSUDRL(reward_function_weights) + reward_func = RewardOSUDRL() + + gym_env = CassieGym(reward_func, visualize=True) gym_env.make(controller, urdf) @@ -25,7 +31,7 @@ def main(): action = np.zeros(18) action[2] = 0.25 while gym_env.current_time < 10: - state = gym_env.step(action) + state, reward = gym_env.step(action) if __name__ == '__main__': main() diff --git a/bindings/pydairlib/cassie/cassie_traj.py b/bindings/pydairlib/cassie/gym_envs/cassie_traj.py similarity index 98% rename from bindings/pydairlib/cassie/cassie_traj.py rename to bindings/pydairlib/cassie/gym_envs/cassie_traj.py index b05490cf7d..3557155952 100644 --- a/bindings/pydairlib/cassie/cassie_traj.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_traj.py @@ -35,7 +35,6 @@ def time_to_index(self, t): return int(t * 2000) def get_positions(self): - import pdb; pdb.set_trace() return self.x_samples[:, CASSIE_POSITION_SLICE] def get_orientations(self): diff --git a/bindings/pydairlib/cassie/gym_envs/reward_base.py b/bindings/pydairlib/cassie/gym_envs/reward_base.py new file mode 100644 index 0000000000..01d7900963 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/reward_base.py @@ -0,0 +1,23 @@ +import numpy as np +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R +import pickle + +CASSIE_QUATERNION_SLICE = slice(0, 4) +CASSIE_POSITION_SLICE = slice(4, 23) +CASSIE_OMEGA_SLICE = slice(23, 26) +CASSIE_VELOCITY_SLICE = slice(26, 45) +CASSIE_JOINT_POSITION_SLICE = slice(7, 23) +CASSIE_JOINT_VELOCITY_SLICE = slice(29, 45) +CASSIE_FB_POSITION_SLICE = slice(4, 7) +CASSIE_FB_VELOCITY_SLICE = slice(26, 29) +LOSS_WEIGHTS_FOLDER = 'examples/contact_parameter_learning/cassie_loss_weights/' + +class RewardBase(): + + def __init__(self, weights_filename): + weights = self.load_weights(weights_filename) + + def compute_reward(self, state): + reward = 0 + return reward \ No newline at end of file diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py new file mode 100644 index 0000000000..61538b7730 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -0,0 +1,80 @@ +import numpy as np +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R +import pickle + +CASSIE_QUATERNION_SLICE = slice(0, 4) +CASSIE_POSITION_SLICE = slice(4, 23) +CASSIE_OMEGA_SLICE = slice(23, 26) +CASSIE_VELOCITY_SLICE = slice(26, 45) +CASSIE_JOINT_POSITION_SLICE = slice(7, 23) +CASSIE_JOINT_VELOCITY_SLICE = slice(29, 45) +CASSIE_FB_POSITION_SLICE = slice(4, 7) +CASSIE_FB_VELOCITY_SLICE = slice(26, 29) +LOSS_WEIGHTS_FOLDER = 'examples/contact_parameter_learning/cassie_loss_weights/' + +class RewardOSUDRL(): + + def __init__(self, weights_filename=None): + if weights_filename: + weights = self.load_weights(weights_filename) + return + + def load_weights(self, filename): + with open(LOSS_WEIGHTS_FOLDER + filename + '.pkl', 'rb') as f: + return pickle.load(f) + + def compute_reward(self, cassie_env_state, prev_cassie_env_state): + + + pos = cassie_env_state.get_positions() + vel = cassie_env_state.get_velocities() + com_pos = cassie_env_state.get_fb_positions() + com_vel = cassie_env_state.get_fb_velocities() + joint_pos = cassie_env_state.get_joint_positions() + joint_vel = cassie_env_state.get_joint_velocities() + torques = cassie_env_state.get_inputs() + prev_torques = prev_cassie_env_state.get_inputs() + + des_forward_vel = cassie_env_state.get_desired_forward_velocity() + + orient_targ = np.array([1, 0, 0, 0]) + + com_orient_error = 0 + foot_orient_error = 0 + com_vel_error = 0 + straight_diff = 0 + foot_vel_error = 0 + foot_frc_error = 0 + + # com orient error + com_orient_error += 15 * (1 - np.inner(orient_targ, pos[CASSIE_QUATERNION_SLICE]) ** 2) + + # foot orient error + # foot_orient_error += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) + foot_orient_error += 0 + + # com vel error + com_vel_error += np.linalg.norm(com_vel - des_forward_vel) + + # straight difference penalty + straight_diff = np.abs(com_pos[1]) # straight difference penalty + if straight_diff < 0.05: + straight_diff = 0 + height_diff = np.abs(com_pos[2] - 0.9) # height deadzone is range from 0.05 to 0.2 meters depending on speed + deadzone_size = 0.05 + 0.05 * des_forward_vel + if height_diff < deadzone_size: + height_diff = 0 + pelvis_acc = 0.25 * (np.abs(com_vel.sum())) + pelvis_motion = straight_diff + height_diff + pelvis_acc + + hip_roll_penalty = np.abs(joint_vel[0]) + np.abs(joint_vel[7]) + + torque_penalty = 0.25 * (sum(np.abs(prev_torques - torques)) / len(torques)) + + reward = 0.200 * np.exp(-(com_orient_error + foot_orient_error)) + \ + 0.150 * np.exp(-pelvis_motion) + \ + 0.150 * np.exp(-com_vel_error) + \ + 0.050 * np.exp(-hip_roll_penalty) + \ + 0.025 * np.exp(-torque_penalty) + return reward \ No newline at end of file diff --git a/bindings/pydairlib/cassie/yaml_structs_py.cc b/bindings/pydairlib/cassie/yaml_structs_py.cc deleted file mode 100644 index 346f719a49..0000000000 --- a/bindings/pydairlib/cassie/yaml_structs_py.cc +++ /dev/null @@ -1,23 +0,0 @@ -#include -#include -#include -#include -#include "examples/Cassie/osc_run/osc_running_gains.h" - -namespace py = pybind11; - -namespace dairlib { -namespace pydairlib { - -PYBIND11_MODULE(dairlib_yaml, m) { - m.doc() = "Binding controller factories for Cassie"; - - using py_rvp = py::return_value_policy; - - py::class_(m, "OSCGains") - .def(py::init<>()); - py::class_(m, "OSCRunningGains") - .def(py::init<>()); -} -} // namespace pydairlib -} // namespace dairlib \ No newline at end of file diff --git a/examples/trifinger/simulate_trifinger.py b/examples/trifinger/simulate_trifinger.py index d20ec2e4b4..1c91adc7ff 100644 --- a/examples/trifinger/simulate_trifinger.py +++ b/examples/trifinger/simulate_trifinger.py @@ -3,32 +3,34 @@ from pydairlib.multibody import (addFlatTerrain, makeNameToPositionsMap) import pydairlib.common + # A demo controller system class TrifingerDemoController(LeafSystem): - def __init__(self, plant): - LeafSystem.__init__(self) - - self.plant = plant - - # Input is state, output is torque (control action) - self.DeclareVectorInputPort("x", plant.num_positions() + - plant.num_velocities()) - self.DeclareVectorOutputPort("u", plant.num_actuators(), self.CalcControl) - - def CalcControl(self, context, output): - x = self.EvalVectorInput(context, 0).get_value() - # q and v are [fingers; cube] - # cube position is [quat; xyz] and velocity [ang_vel; xyz] - q = x[0:self.plant.num_positions()] - v = x[self.plant.num_positions():] - # u = -.03*np.ones(self.plant.num_actuators()) - - # use a simple PD controller with constant setpoint - kp = 10 - kd = 2 - q_des = np.array([.1, 0, -1, .1, -.5, -1, .1, -.5, -1]) - u = kp*(q_des - q[0:9]) - kd * v[0:9] - output.SetFromVector(u) + def __init__(self, plant): + LeafSystem.__init__(self) + + self.plant = plant + + # Input is state, output is torque (control action) + self.DeclareVectorInputPort("x", plant.num_positions() + + plant.num_velocities()) + self.DeclareVectorOutputPort("u", plant.num_actuators(), self.CalcControl) + + def CalcControl(self, context, output): + x = self.EvalVectorInput(context, 0).get_value() + # q and v are [fingers; cube] + # cube position is [quat; xyz] and velocity [ang_vel; xyz] + q = x[0:self.plant.num_positions()] + v = x[self.plant.num_positions():] + # u = -.03*np.ones(self.plant.num_actuators()) + + # use a simple PD controller with constant setpoint + kp = 10 + kd = 2 + q_des = np.array([.1, 0, -1, .1, -.5, -1, .1, -.5, -1]) + u = kp * (q_des - q[0:9]) - kd * v[0:9] + output.SetFromVector(u) + # Load the URDF and the cube builder = DiagramBuilder() @@ -73,7 +75,6 @@ def CalcControl(self, context, output): builder.Connect(controller.get_output_port(0), mux.get_input_port(1)) builder.Connect(mux.get_output_port(0), logger.get_input_port(0)) - diagram = builder.Build() simulator = Simulator(diagram) @@ -109,4 +110,4 @@ def CalcControl(self, context, output): simulator.AdvanceTo(3) # numpy array of data (nq+nv+nu) x n_time -data = logger.FindLog(simulator.get_context()).data() \ No newline at end of file +data = logger.FindLog(simulator.get_context()).data() From d924fcd4cb6e967cf7d19247f33267b1d81ec8d5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 16:52:54 -0400 Subject: [PATCH 155/758] need to get motor commands without recomputing --- bindings/pydairlib/cassie/controllers_py.cc | 3 + .../pydairlib/cassie/gym_envs/cassie_gym.py | 24 ++++-- .../cassie/gym_envs/cassie_gym_test.py | 3 + .../cassie/gym_envs/reward_osudrl.py | 10 ++- .../Cassie/diagrams/cassie_sim_diagram.cc | 4 +- .../osc_running_controller_diagram.cc | 73 ++++++++++--------- .../diagrams/osc_running_controller_diagram.h | 8 +- .../osc/operational_space_control.cc | 2 + 8 files changed, 79 insertions(+), 48 deletions(-) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index 41a5026134..f66ba28a14 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -34,6 +34,9 @@ PYBIND11_MODULE(controllers, m) { .def("get_control_output_port", &OSCRunningControllerDiagram::get_control_output_port, py_rvp::reference_internal) + .def("get_torque_output_port", + &OSCRunningControllerDiagram::get_torque_output_port, + py_rvp::reference_internal) .def("get_controller_failure_output_port", &OSCRunningControllerDiagram::get_controller_failure_output_port, py_rvp::reference_internal); diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py index 6fe909ab4c..c0c665f230 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py @@ -18,7 +18,7 @@ class CassieGym(): def __init__(self, reward_func, visualize=False): - # self.sim_dt = 8e-5 + self.sim_dt = 1e-3 self.visualize = visualize self.reward_func = reward_func # hardware logs are 50ms long and start approximately 5ms before impact @@ -59,8 +59,9 @@ def make(self, controller, urdf): self.diagram = self.builder.Build() self.sim = Simulator(self.diagram) - self.plant_context = self.diagram.GetMutableSubsystemContext(self.new_plant, self.sim.get_mutable_context()) self.simulator_context = self.diagram.GetMutableSubsystemContext(self.simulator, self.sim.get_mutable_context()) + self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.sim.get_mutable_context()) + self.controller_output_port = self.controller.get_torque_output_port() self.sim.get_mutable_context().SetTime(self.start_time) self.reset() @@ -73,7 +74,7 @@ def reset(self): np.zeros(self.action_dim)) x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( - self.sim.get_mutable_context())) + self.sim.get_context())) u = np.zeros(10) self.sim.Initialize() self.current_time = self.start_time @@ -86,16 +87,23 @@ def advance_to(self, time): return self.traj def step(self, action=np.zeros(18)): - next_timestep = self.sim.get_context().get_time() + self.dt + # next_timestep = self.sim.get_context().get_time() + self.dt + next_timestep = self.sim.get_context().get_time() + self.sim_dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) - self.sim.AdvanceTo(next_timestep) + self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) + self.current_time = next_timestep + x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( - self.sim.get_mutable_context())) - u = np.zeros(10) - self.current_time = next_timestep + self.sim.get_context())) + # print(next_timestep) + u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp + # u = self.controller_output_port.Eval(self.sim.get_context())[:-1] # remove the timestamp + # print(u) + # u = np.zeros(10) cassie_state = CassieEnvState(self.current_time, x, u, action) reward = self.reward_func.compute_reward(cassie_state, self.prev_cassie_state) + # reward = 0 self.prev_cassie_state = cassie_state # self.traj.update(next_timestep, cassie_state, action[:10]) return cassie_state, reward diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index e287ce4190..ba4c82cd76 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -30,8 +30,11 @@ def main(): action = np.zeros(18) action[2] = 0.25 + cumulative_reward = 0 while gym_env.current_time < 10: state, reward = gym_env.step(action) + cumulative_reward += reward + print(cumulative_reward) if __name__ == '__main__': main() diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index 61538b7730..21beb82fa5 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -55,7 +55,7 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): foot_orient_error += 0 # com vel error - com_vel_error += np.linalg.norm(com_vel - des_forward_vel) + com_vel_error += np.linalg.norm(com_vel[0] - des_forward_vel) # straight difference penalty straight_diff = np.abs(com_pos[1]) # straight difference penalty @@ -77,4 +77,12 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): 0.150 * np.exp(-com_vel_error) + \ 0.050 * np.exp(-hip_roll_penalty) + \ 0.025 * np.exp(-torque_penalty) + + + # print(0.200 * np.exp(-(com_orient_error + foot_orient_error))) + # print(0.150 * np.exp(-pelvis_motion)) + # print(0.150 * np.exp(-com_vel_error)) + # print(0.050 * np.exp(-hip_roll_penalty)) + # print(0.025 * np.exp(-torque_penalty)) + # import pdb; pdb.set_trace() return reward \ No newline at end of file diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index eca8ebfb5a..a6c95500da 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -113,9 +113,9 @@ CassieSimDiagram::CassieSimDiagram( builder.Connect(radio_parser->get_output_port(), sensor_aggregator_->get_input_port_radio()); - builder.ExportInput(input_receiver->get_input_port(), "u, t"); + builder.ExportInput(input_receiver->get_input_port(), "lcmt_robot_input"); builder.ExportInput(radio_parser->get_input_port(), "raw_radio"); - builder.ExportOutput(state_sender->get_output_port(0), "x, u, t"); + builder.ExportOutput(state_sender->get_output_port(0), "lcmt_robot_output"); builder.ExportOutput(sensor_aggregator_->get_output_port(0), "lcmt_cassie_out"); DrakeVisualizer::AddToBuilder(&builder, *scene_graph_); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 6ad8a6a10d..761052f03d 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -111,8 +111,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( vel_map.at("ankle_spring_joint_leftdot"), 0)), right_fixed_ankle_spring( FixedJointEvaluator(plant, pos_map.at("ankle_spring_joint_right"), - vel_map.at("ankle_spring_joint_rightdot"), 0)){ - + vel_map.at("ankle_spring_joint_rightdot"), 0)) { // Build the controller diagram DiagramBuilder builder; plant_context = plant.CreateDefaultContext(); @@ -129,8 +128,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( OSCGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(osc_gainsfilename), {}, {}, yaml_options); - OSCRunningGains osc_running_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gainsfilename)); + OSCRunningGains osc_running_gains = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_gainsfilename)); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -169,12 +169,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), true, false); - // auto failure_aggregator = - // builder.AddSystem( - // control_channel_name_, 1); - // auto passthrough = builder.AddSystem( - // osc->get_output_port(0).size(), 0, - // plant.get_actuation_input_port().size()); + auto failure_aggregator = + builder.AddSystem( + control_channel_name_, 1); std::vector tau = {.05, .05, .01}; auto ekf_filter = builder.AddSystem(plant, tau); @@ -182,8 +179,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_gains.w_accel * - osc_gains.W_acceleration); + osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); osc->SetInputCostWeights(osc_gains.w_input * osc_gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight( @@ -309,20 +305,22 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); + "hip_left"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); + "hip_right"); left_foot_rel_tracking_data = std::make_unique( "left_ft_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, - plant, plant, left_foot_tracking_data.get(), left_hip_tracking_data.get()); + plant, plant, left_foot_tracking_data.get(), + left_hip_tracking_data.get()); right_foot_rel_tracking_data = std::make_unique( "right_ft_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, - plant, plant, right_foot_tracking_data.get(), right_hip_tracking_data.get()); + plant, plant, right_foot_tracking_data.get(), + right_hip_tracking_data.get()); left_foot_yz_rel_tracking_data = std::make_unique( "left_ft_z_traj", osc_running_gains.K_p_liftoff_swing_foot, @@ -364,13 +362,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "pelvis_rot_traj", osc_running_gains.K_p_pelvis_rot, osc_running_gains.K_d_pelvis_rot, osc_running_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, + "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, - "pelvis"); + "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_touchdown_air_phase, - "pelvis"); + "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_touchdown_air_phase, - "pelvis"); + "pelvis"); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -383,11 +382,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_toe_angle_traj"); // Swing toe joint tracking - left_toe_angle_tracking_data = std::make_unique( + left_toe_angle_tracking_data = std::make_unique( "left_toe_angle_traj", osc_running_gains.K_p_swing_toe, osc_running_gains.K_d_swing_toe, osc_running_gains.W_swing_toe, plant, plant); - right_toe_angle_tracking_data = std::make_unique( + right_toe_angle_tracking_data = std::make_unique( "right_toe_angle_traj", osc_running_gains.K_p_swing_toe, osc_running_gains.K_d_swing_toe, osc_running_gains.W_swing_toe, plant, plant); @@ -409,19 +408,20 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); // Swing hip yaw joint tracking - left_hip_yaw_tracking_data = std::make_unique( + left_hip_yaw_tracking_data = std::make_unique( "hip_yaw_left_traj", osc_running_gains.K_p_hip_yaw, - osc_running_gains.K_d_hip_yaw, osc_running_gains.W_hip_yaw, plant, - plant); - right_hip_yaw_tracking_data = std::make_unique( + osc_running_gains.K_d_hip_yaw, osc_running_gains.W_hip_yaw, plant, plant); + right_hip_yaw_tracking_data = std::make_unique( "hip_yaw_right_traj", osc_running_gains.K_p_hip_yaw, - osc_running_gains.K_d_hip_yaw, osc_running_gains.W_hip_yaw, plant, - plant); - left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + osc_running_gains.K_d_hip_yaw, osc_running_gains.W_hip_yaw, plant, plant); + left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", + "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", - "hip_yaw_rightdot"); - osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); - osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); + "hip_yaw_rightdot"); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), + VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), + VectorXd::Zero(1)); // Build OSC problem osc->SetOsqpSolverOptionsFromYaml(osqp_settings_filename); @@ -491,12 +491,13 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( command_sender->get_input_port(0)); // Publisher connections - builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); + builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); builder.ExportInput(high_level_command->get_cassie_out_input_port(), "lcmt_cassie_out"); - builder.ExportOutput(command_sender->get_output_port(), "u, t"); - // builder.ExportOutput(failure_aggregator->get_status_output_port(), - // "failure_status"); + builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); + builder.ExportOutput(osc->get_osc_output_port(), "u, t"); + builder.ExportOutput(failure_aggregator->get_status_output_port(), + "lcmt_controller_failure"); builder.BuildInto(this); this->set_name(("osc_running_controller_diagram")); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index d99758bd00..03363af32a 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -58,6 +58,11 @@ class OSCRunningControllerDiagram final return this->get_output_port(control_output_port_index_); } + /// @return the output port for the controller torques. + const drake::systems::OutputPort& get_torque_output_port() const { + return this->get_output_port(torque_output_port_index_); + } + /// @return the output port for the failure status of the controller. const drake::systems::OutputPort& get_controller_failure_output_port() const { @@ -132,7 +137,8 @@ class OSCRunningControllerDiagram final const int state_input_port_index_ = 0; const int cassie_out_input_port_index_ = 1; const int control_output_port_index_ = 0; - const int controller_failure_port_index_ = 1; + const int torque_output_port_index_ = 1; + const int controller_failure_port_index_ = 2; const std::string control_channel_name_ = "OSC_RUNNING"; }; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 4602d0fa94..52b8dbf43b 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1004,6 +1004,8 @@ void OperationalSpaceControl::CalcOptimalInput( double timestamp = robot_output->get_timestamp(); + + std::cout << "t_osc: " << timestamp << std::endl; double current_time = timestamp; if (print_tracking_info_) { cout << "\n\ncurrent_time = " << current_time << endl; From 7399b4bbfc9ec0c9f2f7aedca09d06768cc7c1b1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 21 Mar 2022 21:31:03 -0400 Subject: [PATCH 156/758] minimal example of gain learning can run --- bindings/pydairlib/cassie/BUILD.bazel | 10 ++ .../pydairlib/cassie/gym_envs/BUILD.bazel | 9 ++ .../pydairlib/cassie/gym_envs/cassie_gym.py | 13 +- .../cassie/gym_envs/cassie_gym_test.py | 8 +- bindings/pydairlib/cassie/learn_osc_gains.py | 125 ++++++++++++++++++ bindings/pydairlib/cassie/simulators_py.cc | 4 +- .../Cassie/diagrams/cassie_sim_diagram.cc | 15 ++- examples/Cassie/diagrams/cassie_sim_diagram.h | 2 +- .../osc_run/learned_osc_running_gains.yaml | 40 ++++++ .../Cassie/osc_run/osc_running_gains.yaml | 30 ++--- .../osc/operational_space_control.cc | 1 - 11 files changed, 222 insertions(+), 35 deletions(-) create mode 100644 bindings/pydairlib/cassie/learn_osc_gains.py create mode 100644 examples/Cassie/osc_run/learned_osc_running_gains.yaml diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index e854064681..d60a404415 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -77,6 +77,16 @@ pybind_py_library( py_imports = ["."], ) +py_binary( + name = "learn_osc_gains", + srcs = ["learn_osc_gains.py"], + deps = [ + "//bindings/pydairlib/cassie/gym_envs:cassie_gym_all", + "//bindings/pydairlib/cassie:cassie", + "@drake//bindings/pydrake", + ], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") diff --git a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel index d33a0ebef0..d3268f1587 100644 --- a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel +++ b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel @@ -11,6 +11,15 @@ load( "pybind_py_library", ) +py_library( + name = "cassie_gym_all", + srcs = [], + deps = [ + ":cassie_gym", + ":cassie_env_rewards", + ], +) + py_library( name = "cassie_gym", diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py index c0c665f230..6c07fc9877 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py @@ -1,5 +1,4 @@ import numpy as np -from cassie_traj import * from pydrake.multibody.parsing import Parser from pydrake.systems.framework import DiagramBuilder @@ -26,7 +25,7 @@ def __init__(self, reward_func, visualize=False): self.start_time = 0.00 self.current_time = 0.00 self.end_time = 0.05 - self.traj = CassieTraj() + # self.traj = CassieTraj() self.hardware_traj = None self.action_dim = 10 self.state_dim = 45 @@ -45,7 +44,7 @@ def make(self, controller, urdf): self.dt = 8e-5 self.plant = MultibodyPlant(self.dt) self.controller = controller - self.simulator = CassieSimDiagram(self.plant, urdf, 0.8, 1e4, 1e2) + self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) self.new_plant = self.simulator.get_plant() # self.sensor_aggregator = self.simulator.get_sensor_aggregator() self.builder.AddSystem(self.controller) @@ -66,12 +65,12 @@ def make(self, controller, urdf): self.reset() def reset(self): - self.traj = CassieTraj() + # self.traj = CassieTraj() self.new_plant.SetPositionsAndVelocities(self.new_plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context()), self.x_init) self.sim.get_mutable_context().SetTime(self.start_time) - self.traj.update(self.start_time, self.x_init, - np.zeros(self.action_dim)) + # self.traj.update(self.start_time, self.x_init, + # np.zeros(self.action_dim)) x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_context())) @@ -84,7 +83,7 @@ def reset(self): def advance_to(self, time): while self.current_time < time: self.step() - return self.traj + return def step(self, action=np.zeros(18)): # next_timestep = self.sim.get_context().get_time() + self.dt diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index ba4c82cd76..4f22cd60e2 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -7,7 +7,7 @@ from pydrake.common.yaml import yaml_load def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -31,7 +31,11 @@ def main(): action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 - while gym_env.current_time < 10: + while gym_env.current_time < 5.0: + state, reward = gym_env.step(action) + cumulative_reward += reward + gym_env.reset() + while gym_env.current_time < 5.0: state, reward = gym_env.step(action) cumulative_reward += reward print(cumulative_reward) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py new file mode 100644 index 0000000000..1d5d97b655 --- /dev/null +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -0,0 +1,125 @@ +import numpy as np +import os +import pickle +from json import dump, load + +import nevergrad as ng + +from pydairlib.cassie.gym_envs.cassie_gym import * +# from cassie_utils import * +from pydairlib.cassie.controllers import OSCRunningControllerFactory +from pydairlib.cassie.controllers import OSCWalkingControllerFactory +from pydairlib.cassie.simulators import CassieSimDiagram +from pydairlib.cassie.gym_envs.reward_osudrl import RewardOSUDRL +from pydrake.common.yaml import yaml_load, yaml_dump +import time + +import yaml + +class OSCGainsOptimizer(): + + def __init__(self, budget, reward_function): + self.budget = budget + self.total_loss = 0 + self.reward_function = reward_function + self.end_time = 5.0 + self.gym_env = None + self.sim = None + self.controller = None + + self.urdf = 'examples/Cassie/urdf/cassie_v2.urdf' + self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' + + self.drake_params_folder = "bindings/pydairlib/cassie/optimal_gains/" + self.date_prefix = time.strftime("%Y_%m_%d_%H") + self.loss_over_time = [] + + self.default_osc_gains = { + 'swing_foot_kp': np.array([125, 80, 50]), + 'swing_foot_kd': np.array([5, 5, 1]), + 'pelvis_rot_kp': np.array([50, 100]), + 'pelvis_rot_kd': np.array([10, 5]), + 'w_input_reg': 0.001} + + def save_params(self, folder, params, budget): + with open(folder + self.date_prefix + '_' + str(budget) + '.pkl', 'wb') as f: + pickle.dump(params, f, pickle.HIGHEST_PROTOCOL) + + def load_params(self, param_file, folder): + with open(folder + param_file + '.pkl', 'rb') as f: + return pickle.load(f) + + + def write_params(self, params): + gains = yaml_load(filename=self.default_osc_running_gains_filename, private=True) + new_gains = gains.copy() + new_swing_foot_kp = [0]*9 + new_swing_foot_kd = [0]*9 + new_pelvis_rot_kp = [0]*9 + new_pelvis_rot_kd = [0]*9 + + new_swing_foot_kp[0] = float(params['swing_foot_kp'][0]) + new_swing_foot_kp[4] = float(params['swing_foot_kp'][1]) + new_swing_foot_kp[8] = float(params['swing_foot_kp'][2]) + new_swing_foot_kd[0] = float(params['swing_foot_kd'][0]) + new_swing_foot_kd[4] = float(params['swing_foot_kd'][1]) + new_swing_foot_kd[8] = float(params['swing_foot_kd'][2]) + new_pelvis_rot_kp[0] = float(params['pelvis_rot_kp'][0]) + new_pelvis_rot_kp[4] = float(params['pelvis_rot_kp'][1]) + new_pelvis_rot_kd[0] = float(params['pelvis_rot_kd'][0]) + new_pelvis_rot_kd[4] = float(params['pelvis_rot_kd'][1]) + new_gains['SwingFootKp'] = new_swing_foot_kp + new_gains['SwingFootKd'] = new_swing_foot_kd + new_gains['PelvisRotKp'] = new_pelvis_rot_kp + new_gains['PelvisRotKd'] = new_pelvis_rot_kd + new_gains['w_input_reg'] = params['w_input_reg'] + # import pdb; pdb.set_trace() + yaml_dump(new_gains, filename=self.osc_running_gains_filename) + # yaml_dump(gains, filename=self.osc_running_gains_filename) + + def get_single_loss(self, params): + self.write_params(params) + controller_plant = MultibodyPlant(8e-5) + addCassieMultibody(controller_plant, None, True, self.urdf, False, False) + controller_plant.Finalize() + self.controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, self.osqp_settings) + self.gym_env.make(self.controller, self.urdf) + # rollout a trajectory and compute the loss + cumulative_reward = 0 + while self.gym_env.current_time < 5.0: + state, reward = self.gym_env.step(np.zeros(18)) + cumulative_reward += reward + self.loss_over_time.append(cumulative_reward) + print(cumulative_reward) + return -cumulative_reward + + def learn_drake_params(self, batch=True): + self.loss_over_time = [] + self.default_params = ng.p.Dict( + swing_foot_kp=ng.p.Array(shape=(3,)).set_bounds(lower=0., upper=150.), + swing_foot_kd=ng.p.Array(shape=(3,)).set_bounds(lower=0., upper=10.), + pelvis_rot_kp=ng.p.Array(shape=(2,)).set_bounds(lower=0., upper=150.), + pelvis_rot_kd=ng.p.Array(shape=(2,)).set_bounds(lower=0., upper=10.), + w_input_reg=ng.p.Log(lower=0.00001, upper=0.001), + ) + self.gym_env = CassieGym(self.reward_function, visualize=False) + self.default_params.value = self.default_osc_gains + optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) + params = optimizer.minimize(self.get_single_loss) + loss_samples = np.array(self.loss_over_time) + np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) + self.save_params(self.drake_params_folder, params, budget) + +if __name__ == '__main__': + # budget = 2000 + budget = 2000 + + reward_function = RewardOSUDRL() + + optimizer = OSCGainsOptimizer(budget, reward_function) + # optimizer.get_single_loss(optimizer.default_osc_gains) + # optimizer.write_params(optimizer.default_osc_gains) + optimizer.learn_drake_params() + diff --git a/bindings/pydairlib/cassie/simulators_py.cc b/bindings/pydairlib/cassie/simulators_py.cc index 762243cc38..2c7e0355bb 100644 --- a/bindings/pydairlib/cassie/simulators_py.cc +++ b/bindings/pydairlib/cassie/simulators_py.cc @@ -21,8 +21,8 @@ PYBIND11_MODULE(simulators, m) { drake::systems::Diagram>(m, "CassieSimDiagram") .def(py::init< std::unique_ptr>, - const std::string&, double, double, double>(), - py::arg("plant"), py::arg("urdf"), py::arg("mu"), py::arg("stiffness"), + const std::string&, bool, double, double, double>(), + py::arg("plant"), py::arg("urdf"), py::arg("visualize"), py::arg("mu"), py::arg("stiffness"), py::arg("dissipation_rate")) .def("get_plant", &CassieSimDiagram::get_plant, py_rvp::reference_internal) diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index a6c95500da..2703b4f54d 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -32,7 +32,9 @@ namespace dairlib { namespace examples { using dairlib::systems::SubvectorPassThrough; +using drake::geometry::DrakeVisualizer; using drake::geometry::SceneGraph; +using drake::math::RotationMatrix; using drake::multibody::ContactResultsToLcmSystem; using drake::multibody::MultibodyPlant; using drake::systems::Context; @@ -40,15 +42,13 @@ using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::geometry::DrakeVisualizer; -using drake::math::RotationMatrix; using Eigen::Matrix3d; using Eigen::Vector3d; using Eigen::VectorXd; CassieSimDiagram::CassieSimDiagram( std::unique_ptr> plant, - const std::string& urdf, double mu, double stiffness, + const std::string& urdf, bool visualize, double mu, double stiffness, double dissipation_rate) { DiagramBuilder builder; scene_graph_ = builder.AddSystem(); @@ -75,9 +75,8 @@ CassieSimDiagram::CassieSimDiagram( auto constant_source = builder.AddSystem( VectorXd::Zero(10)); - auto input_zero_order_hold = - builder.AddSystem( - 0.001, plant_->num_actuators() + 1); + auto input_zero_order_hold = builder.AddSystem( + 0.001, plant_->num_actuators() + 1); sensor_aggregator_ = &AddImuAndAggregator(&builder, *plant_, constant_source->get_output_port()); @@ -118,7 +117,9 @@ CassieSimDiagram::CassieSimDiagram( builder.ExportOutput(state_sender->get_output_port(0), "lcmt_robot_output"); builder.ExportOutput(sensor_aggregator_->get_output_port(0), "lcmt_cassie_out"); - DrakeVisualizer::AddToBuilder(&builder, *scene_graph_); + if (visualize) { + DrakeVisualizer::AddToBuilder(&builder, *scene_graph_); + } builder.BuildInto(this); this->set_name("cassie_sim_diagram"); DrawAndSaveDiagramGraph(*this); diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 9a01aedb0f..8aed40f84d 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -21,7 +21,7 @@ class CassieSimDiagram : public drake::systems::Diagram { /// @param[in] urdf filepath containing the osc_running_gains. CassieSimDiagram(std::unique_ptr> plant, - const std::string& urdf = "examples/Cassie/urdf/cassie_v2.urdf", + const std::string& urdf = "examples/Cassie/urdf/cassie_v2.urdf", bool visualize = false, double mu = 0.8, double stiffness = 1e4, double dissipation_rate = 1e2); /// @return the input port for the actuation command. diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml new file mode 100644 index 0000000000..707e09fe74 --- /dev/null +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -0,0 +1,40 @@ +FootstepKd: [0.2, 0, 0, 0, 0.45, 0, 0, 0, 0] +LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] +LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] +LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] +PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] +PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] +PelvisRotKd: [9.013098354712552, 0, 0, 0, 5.890550647773381, 0, 0, 0, 0] +PelvisRotKp: [47.69813767696465, 0, 0, 0, 100.05199703112916, 0, 0, 0, 0] +PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] +PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] +SwingFootKd: [4.204174090159518, 0, 0, 0, 6.414419020162894, 0, 0, 0, 2.4081571611097052] +SwingFootKp: [124.64305393422285, 0, 0, 0, 79.96891548545914, 0, 0, 0, 49.80295035635085] +SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] +W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] +center_line_offset: 0.075 +flight_duration: 0.08 +footstep_offset: -0.05 +hip_yaw_kd: 1 +hip_yaw_kp: 40 +impact_threshold: 0.025 +mu: 0.6 +relative_feet: true +relative_pelvis: true +rest_length: 0.85 +stance_duration: 0.3 +swing_toe_kd: 10 +swing_toe_kp: 1500 +vel_scale_rot: -0.5 +vel_scale_trans_lateral: -0.15 +vel_scale_trans_sagital: 0.2 +w_accel: 1.0e-05 +w_hip_yaw: 2.5 +w_input: 0.0 +w_input_reg: 0.0007966140696922753 +w_soft_constraint: 100 +w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d4d47162b5..e4a972c0d4 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -62,33 +62,33 @@ PelvisRotW: 0, 2.5, 0, 0, 0, 0.1] PelvisRotKp: - [50, 0, 0, - 0, 100, 0, - 0, 0, 1] + [50., 0, 0, + 0, 100., 0, + 0, 0, 0.] PelvisRotKd: - [7.5, 0, 0, - 0, 5, 0, - 0, 0, 0] + [10., 0, 0, + 0, 5., 0, + 0, 0, 0.] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] SwingFootKp: - [125, 0, 0, - 0, 80, 0, - 0, 0, 50] + [125., 0, 0, + 0, 80., 0, + 0, 0, 50.] SwingFootKd: - [5, 0, 0, - 0, 59, 0, - 0, 0, 1] + [5., 0, 0, + 0, 5., 0, + 0, 0, 1.] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] LiftoffSwingFootKp: - [50, 0, 0, - 0, 50, 0, - 0, 0, 50] + [50., 0, 0, + 0, 50., 0, + 0, 0, 50.] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 52b8dbf43b..63f5b15d83 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1005,7 +1005,6 @@ void OperationalSpaceControl::CalcOptimalInput( double timestamp = robot_output->get_timestamp(); - std::cout << "t_osc: " << timestamp << std::endl; double current_time = timestamp; if (print_tracking_info_) { cout << "\n\ncurrent_time = " << current_time << endl; From 031f4e30c3c7b6b6f0aab2ad64faa7880f392ba6 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Tue, 22 Mar 2022 10:19:16 -0400 Subject: [PATCH 157/758] Update Drake commit and fix missing include --- WORKSPACE | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/WORKSPACE b/WORKSPACE index 3b41de00aa..e42f784543 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,9 +11,9 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "eea358cebed239bd528a886ebef5a6c16365006e" +DRAKE_COMMIT = "a6005354c97db4160d67ee735b1e01efcd633d9b" -DRAKE_CHECKSUM = "3e7ad19d4004578dbb0aa097225e3d1c02ee3632110534497c315fba104021b8" +DRAKE_CHECKSUM = "708cc2f868be1b07c87c730ffb423b87b0cd6120f7e9e7fe65b56139c832704a" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. # DRAKE_CHECKSUM = "0" * 64 From 2eaa94fb26aa6a600a9521735ba6073e24c9ee3f Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Tue, 22 Mar 2022 10:24:15 -0400 Subject: [PATCH 158/758] Add missing include and bindings for RobotOutputSender port getters. --- bindings/pydairlib/systems/robot_lcm_systems_py.cc | 8 ++++++-- systems/framework/lcm_driven_loop.h | 2 ++ 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index ec9a40e0db..c5bfca18fe 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -16,6 +16,7 @@ PYBIND11_MODULE(robot_lcm_systems, m) { m.doc() = "Binding robot lcm systems"; using drake::multibody::MultibodyPlant; + using systems::RobotOutputSender; py::class_>( m, "RobotOutputReceiver") @@ -23,9 +24,12 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotInputReceiver") .def(py::init&>()); - py::class_>( + py::class_>( m, "RobotOutputSender") - .def(py::init&, bool>()); + .def(py::init&, bool>()) + .def("get_input_port_state", &RobotOutputSender::get_input_port_state) + .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort) + .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu); py::class_>( m, "RobotCommandSender") .def(py::init&>()); diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index e8ecbbf542..efb419e8ac 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -14,6 +14,8 @@ #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/lcm/serializer.h" +#include "dairlib/lcmt_robot_output.hpp" + namespace dairlib { namespace systems { From ccd7c6f7ecd952b1d05aee23ce6568af5f783d79 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Tue, 22 Mar 2022 10:41:27 -0400 Subject: [PATCH 159/758] Fix include ordering --- systems/framework/lcm_driven_loop.h | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index efb419e8ac..8026d1f5d3 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -5,6 +5,7 @@ #include #include "dairlib/lcmt_controller_switch.hpp" +#include "dairlib/lcmt_robot_output.hpp" #include "drake/lcm/drake_lcm.h" #include "drake/systems/analysis/simulator.h" @@ -14,8 +15,6 @@ #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/lcm/serializer.h" -#include "dairlib/lcmt_robot_output.hpp" - namespace dairlib { namespace systems { From d492c9a0083d1a62acf7c4dc1863ba261845ab36 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 22 Mar 2022 13:03:26 -0400 Subject: [PATCH 160/758] learning gains --- .../pydairlib/analysis/mbp_plotting_utils.py | 2 +- .../plot_configs/cassie_running_plot.yaml | 12 +- .../pydairlib/cassie/gym_envs/cassie_gym.py | 23 ++- .../cassie/gym_envs/cassie_gym_test.py | 2 +- .../cassie/gym_envs/reward_osudrl.py | 20 +-- bindings/pydairlib/cassie/learn_osc_gains.py | 72 ++++---- .../osc_run/learned_osc_running_gains.yaml | 17 +- .../Cassie/osc_run/osc_running_gains.yaml | 6 +- examples/Cassie/run_osc_running_controller.cc | 157 ++++++++++-------- 9 files changed, 163 insertions(+), 148 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 639bb76e03..2e2d4b1e30 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -369,7 +369,7 @@ def plot_qp_costs(osc_debug, time_slice): {key: [key] for key in regularization_cost.keys()}, {'xlabel': 'Time', 'ylabel': 'Cost', - 'title': 'tracking_costs'}, ps) + 'title': 'regularization_costs'}, ps) return ps diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 65643554f7..7697a21d1e 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -33,12 +33,10 @@ tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# hip_roll_left_traj: {'dims': [0], 'derivs': ['vel']} - # hip_pitch_left_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'acc']} -# left_ft_traj: {'dims': [2], 'derivs': ['vel']} -# right_ft_traj: {'dims': [2], 'derivs': ['vel']} -# left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} -# right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} + left_ft_traj: {'dims': [2], 'derivs': ['vel']} + right_ft_traj: {'dims': [2], 'derivs': ['vel']} + left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} + right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py index 6c07fc9877..500e66c900 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym.py @@ -38,6 +38,9 @@ def __init__(self, reward_func, visualize=False): "dissipation": 0.5} self.prev_cassie_state = None self.controller = None + self.terminated = False + self.initialized = False + def make(self, controller, urdf): self.builder = DiagramBuilder() @@ -63,6 +66,7 @@ def make(self, controller, urdf): self.controller_output_port = self.controller.get_torque_output_port() self.sim.get_mutable_context().SetTime(self.start_time) self.reset() + self.initialized = True def reset(self): # self.traj = CassieTraj() @@ -78,14 +82,22 @@ def reset(self): self.sim.Initialize() self.current_time = self.start_time self.prev_cassie_state = CassieEnvState(self.current_time, x, u, np.zeros(18)) + self.cassie_state = CassieEnvState(self.current_time, x, u, np.zeros(18)) + self.terminated = False return def advance_to(self, time): - while self.current_time < time: + while self.current_time < time and not self.terminated: self.step() return + def check_termination(self): + return self.cassie_state.get_fb_positions()[2] < 0.4 + + def step(self, action=np.zeros(18)): + if not self.initialized: + print("Call make() before calling step() or advance()") # next_timestep = self.sim.get_context().get_time() + self.dt next_timestep = self.sim.get_context().get_time() + self.sim_dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) @@ -100,12 +112,13 @@ def step(self, action=np.zeros(18)): # u = self.controller_output_port.Eval(self.sim.get_context())[:-1] # remove the timestamp # print(u) # u = np.zeros(10) - cassie_state = CassieEnvState(self.current_time, x, u, action) - reward = self.reward_func.compute_reward(cassie_state, self.prev_cassie_state) + self.cassie_state = CassieEnvState(self.current_time, x, u, action) + reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) + self.terminated = self.check_termination() # reward = 0 - self.prev_cassie_state = cassie_state + self.prev_cassie_state = self.cassie_state # self.traj.update(next_timestep, cassie_state, action[:10]) - return cassie_state, reward + return self.cassie_state, reward def get_traj(self): return self.traj diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 4f22cd60e2..a02c01ebfc 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -31,7 +31,7 @@ def main(): action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 - while gym_env.current_time < 5.0: + while gym_env.current_time < 7.5: state, reward = gym_env.step(action) cumulative_reward += reward gym_env.reset() diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index 21beb82fa5..9bb63354d8 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -35,24 +35,24 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): joint_vel = cassie_env_state.get_joint_velocities() torques = cassie_env_state.get_inputs() prev_torques = prev_cassie_env_state.get_inputs() + com_angular_velocity = cassie_env_state.get_omegas() des_forward_vel = cassie_env_state.get_desired_forward_velocity() orient_targ = np.array([1, 0, 0, 0]) com_orient_error = 0 - foot_orient_error = 0 + hip_yaw_penalty = 0 com_vel_error = 0 straight_diff = 0 foot_vel_error = 0 foot_frc_error = 0 # com orient error - com_orient_error += 15 * (1 - np.inner(orient_targ, pos[CASSIE_QUATERNION_SLICE]) ** 2) - + com_orient_error += 10 * (1 - np.inner(orient_targ, cassie_env_state.get_orientations()) ** 2) # foot orient error - # foot_orient_error += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) - foot_orient_error += 0 + # hip_yaw_penalty += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) + hip_yaw_penalty += np.abs(joint_vel[1]) + np.abs(joint_vel[8]) # com vel error com_vel_error += np.linalg.norm(com_vel[0] - des_forward_vel) @@ -61,25 +61,25 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): straight_diff = np.abs(com_pos[1]) # straight difference penalty if straight_diff < 0.05: straight_diff = 0 - height_diff = np.abs(com_pos[2] - 0.9) # height deadzone is range from 0.05 to 0.2 meters depending on speed + height_diff = np.abs(com_pos[2] - 0.85) # height deadzone is range from 0.05 to 0.2 meters depending on speed deadzone_size = 0.05 + 0.05 * des_forward_vel if height_diff < deadzone_size: height_diff = 0 - pelvis_acc = 0.25 * (np.abs(com_vel.sum())) + pelvis_acc = 0.25 * (np.abs(com_angular_velocity.sum())) pelvis_motion = straight_diff + height_diff + pelvis_acc hip_roll_penalty = np.abs(joint_vel[0]) + np.abs(joint_vel[7]) - torque_penalty = 0.25 * (sum(np.abs(prev_torques - torques)) / len(torques)) + torque_penalty = 0.5 * (sum(np.abs(prev_torques - torques)) / len(torques)) - reward = 0.200 * np.exp(-(com_orient_error + foot_orient_error)) + \ + reward = 0.200 * np.exp(-(com_orient_error + hip_yaw_penalty)) + \ 0.150 * np.exp(-pelvis_motion) + \ 0.150 * np.exp(-com_vel_error) + \ 0.050 * np.exp(-hip_roll_penalty) + \ 0.025 * np.exp(-torque_penalty) - # print(0.200 * np.exp(-(com_orient_error + foot_orient_error))) + # print(0.200 * np.exp(-(com_orient_error + hip_yaw_penalty))) # print(0.150 * np.exp(-pelvis_motion)) # print(0.150 * np.exp(-com_vel_error)) # print(0.050 * np.exp(-hip_roll_penalty)) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 1d5d97b655..5457ebdc22 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -2,7 +2,7 @@ import os import pickle from json import dump, load - +import concurrent.futures as futures import nevergrad as ng from pydairlib.cassie.gym_envs.cassie_gym import * @@ -13,9 +13,10 @@ from pydairlib.cassie.gym_envs.reward_osudrl import RewardOSUDRL from pydrake.common.yaml import yaml_load, yaml_dump import time - +import matplotlib.pyplot as plt import yaml + class OSCGainsOptimizer(): def __init__(self, budget, reward_function): @@ -37,11 +38,11 @@ def __init__(self, budget, reward_function): self.loss_over_time = [] self.default_osc_gains = { - 'swing_foot_kp': np.array([125, 80, 50]), - 'swing_foot_kd': np.array([5, 5, 1]), - 'pelvis_rot_kp': np.array([50, 100]), - 'pelvis_rot_kd': np.array([10, 5]), - 'w_input_reg': 0.001} + 'SwingFootKp': np.array([125, 80, 50]), + 'SwingFootKd': np.array([5, 5, 1]), + 'FootstepKd': np.array([0.2, 0.45, 0]), + 'center_line_offset': 0.03, + } def save_params(self, folder, params, budget): with open(folder + self.date_prefix + '_' + str(budget) + '.pkl', 'wb') as f: @@ -51,75 +52,62 @@ def load_params(self, param_file, folder): with open(folder + param_file + '.pkl', 'rb') as f: return pickle.load(f) - def write_params(self, params): gains = yaml_load(filename=self.default_osc_running_gains_filename, private=True) new_gains = gains.copy() - new_swing_foot_kp = [0]*9 - new_swing_foot_kd = [0]*9 - new_pelvis_rot_kp = [0]*9 - new_pelvis_rot_kd = [0]*9 - - new_swing_foot_kp[0] = float(params['swing_foot_kp'][0]) - new_swing_foot_kp[4] = float(params['swing_foot_kp'][1]) - new_swing_foot_kp[8] = float(params['swing_foot_kp'][2]) - new_swing_foot_kd[0] = float(params['swing_foot_kd'][0]) - new_swing_foot_kd[4] = float(params['swing_foot_kd'][1]) - new_swing_foot_kd[8] = float(params['swing_foot_kd'][2]) - new_pelvis_rot_kp[0] = float(params['pelvis_rot_kp'][0]) - new_pelvis_rot_kp[4] = float(params['pelvis_rot_kp'][1]) - new_pelvis_rot_kd[0] = float(params['pelvis_rot_kd'][0]) - new_pelvis_rot_kd[4] = float(params['pelvis_rot_kd'][1]) - new_gains['SwingFootKp'] = new_swing_foot_kp - new_gains['SwingFootKd'] = new_swing_foot_kd - new_gains['PelvisRotKp'] = new_pelvis_rot_kp - new_gains['PelvisRotKd'] = new_pelvis_rot_kd - new_gains['w_input_reg'] = params['w_input_reg'] - # import pdb; pdb.set_trace() + for key in params: + if hasattr(params[key], "__len__"): + new_gains[key] = np.diag(params[key]).flatten().tolist() + else: + new_gains[key] = params[key] yaml_dump(new_gains, filename=self.osc_running_gains_filename) - # yaml_dump(gains, filename=self.osc_running_gains_filename) def get_single_loss(self, params): self.write_params(params) controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, self.urdf, False, False) controller_plant.Finalize() - self.controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, self.osqp_settings) + self.controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, + self.osqp_settings) self.gym_env.make(self.controller, self.urdf) # rollout a trajectory and compute the loss cumulative_reward = 0 - while self.gym_env.current_time < 5.0: + while self.gym_env.current_time < 7.5 and not self.gym_env.terminated: state, reward = self.gym_env.step(np.zeros(18)) cumulative_reward += reward self.loss_over_time.append(cumulative_reward) - print(cumulative_reward) + print(-cumulative_reward) return -cumulative_reward def learn_drake_params(self, batch=True): self.loss_over_time = [] self.default_params = ng.p.Dict( - swing_foot_kp=ng.p.Array(shape=(3,)).set_bounds(lower=0., upper=150.), - swing_foot_kd=ng.p.Array(shape=(3,)).set_bounds(lower=0., upper=10.), - pelvis_rot_kp=ng.p.Array(shape=(2,)).set_bounds(lower=0., upper=150.), - pelvis_rot_kd=ng.p.Array(shape=(2,)).set_bounds(lower=0., upper=10.), - w_input_reg=ng.p.Log(lower=0.00001, upper=0.001), + SwingFootKp=ng.p.Array(lower=0., upper=150., shape=(3,)), + SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), + center_line_offset=ng.p.Scalar(lower=0.01, upper=0.1), ) - self.gym_env = CassieGym(self.reward_function, visualize=False) + self.gym_env = CassieGym(self.reward_function, visualize=True) self.default_params.value = self.default_osc_gains optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) + # with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: params = optimizer.minimize(self.get_single_loss) loss_samples = np.array(self.loss_over_time) np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) self.save_params(self.drake_params_folder, params, budget) + if __name__ == '__main__': # budget = 2000 - budget = 2000 + budget = 1000 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function) - # optimizer.get_single_loss(optimizer.default_osc_gains) - # optimizer.write_params(optimizer.default_osc_gains) optimizer.learn_drake_params() + # optimal_params = optimizer.load_params('2022_03_22_11_100', optimizer.drake_params_folder).value + # optimizer.write_params(optimal_params) + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_100.npy') + # plt.plot(reward_over_time) + # plt.show() diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 707e09fe74..6a9aa2a43d 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,22 +1,25 @@ -FootstepKd: [0.2, 0, 0, 0, 0.45, 0, 0, 0, 0] +FootstepKd: [0.23903044158385484, 0.0, 0.0, 0.0, 0.5277918292893192, 0.0, 0.0, 0.0, + 0.3348254165589458] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [9.013098354712552, 0, 0, 0, 5.890550647773381, 0, 0, 0, 0] -PelvisRotKp: [47.69813767696465, 0, 0, 0, 100.05199703112916, 0, 0, 0, 0] +PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] +PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [4.204174090159518, 0, 0, 0, 6.414419020162894, 0, 0, 0, 2.4081571611097052] -SwingFootKp: [124.64305393422285, 0, 0, 0, 79.96891548545914, 0, 0, 0, 49.80295035635085] +SwingFootKd: [8.457110869021973, 0.0, 0.0, 0.0, 6.337030429693949, 0.0, 0.0, 0.0, + 0.19627803553381146] +SwingFootKp: [114.74294024181081, 0.0, 0.0, 0.0, 135.42922767990683, 0.0, 0.0, 0.0, + 45.87269559307247] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.075 +center_line_offset: 0.026528125472685925 flight_duration: 0.08 footstep_offset: -0.05 hip_yaw_kd: 1 @@ -35,6 +38,6 @@ vel_scale_trans_sagital: 0.2 w_accel: 1.0e-05 w_hip_yaw: 2.5 w_input: 0.0 -w_input_reg: 0.0007966140696922753 +w_input_reg: 0.001 w_soft_constraint: 100 w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e4a972c0d4..e078e08283 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,9 +40,9 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.075 +center_line_offset: 0.042 FootstepKd: - [ 0.2, 0, 0, + [ 0.3, 0, 0, 0, 0.45, 0, 0, 0, 0] PelvisW: @@ -79,7 +79,7 @@ SwingFootKp: 0, 0, 50.] SwingFootKd: [5., 0, 0, - 0, 5., 0, + 0, 4., 0, 0, 0, 1.] LiftoffSwingFootW: [0.1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1ec25800d4..6f746fe481 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -138,9 +138,9 @@ int DoMain(int argc, char* argv[]) { FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); -// solvers::OSQPSettingsYaml osqp_settings = -// drake::yaml::LoadYamlFile( -// FindResourceOrThrow(FLAGS_osqp_settings)); + // solvers::OSQPSettingsYaml osqp_settings = + // drake::yaml::LoadYamlFile( + // FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -291,88 +291,98 @@ int DoMain(int argc, char* argv[]) { osc_gains.center_line_offset, osc_gains.footstep_offset); - auto pelvis_tracking_data = std::make_unique ( + auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant, plant); - auto stance_foot_tracking_data = std::make_unique ( + auto stance_foot_tracking_data = std::make_unique( "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - auto left_foot_tracking_data = std::make_unique ( + auto left_foot_tracking_data = std::make_unique( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - auto right_foot_tracking_data = std::make_unique ( + auto right_foot_tracking_data = std::make_unique( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); pelvis_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); pelvis_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); stance_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, - "toe_left"); + "toe_left"); stance_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, - "toe_right"); + "toe_right"); left_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, - "toe_left"); + "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, - "toe_right"); + "toe_right"); left_foot_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "toe_left"); + "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "toe_right"); + "toe_right"); - auto left_foot_yz_tracking_data = std::make_unique ( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); - auto right_foot_yz_tracking_data = std::make_unique ( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + auto left_foot_yz_tracking_data = + std::make_unique( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + auto right_foot_yz_tracking_data = + std::make_unique( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); left_foot_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "toe_left"); + "toe_left"); right_foot_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "toe_right"); + "toe_right"); - auto left_hip_tracking_data = std::make_unique ( + auto left_hip_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - auto right_hip_tracking_data = std::make_unique ( + auto right_hip_tracking_data = std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "pelvis"); + "pelvis"); left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); + "pelvis"); - auto left_hip_yz_tracking_data = std::make_unique ( + auto left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - auto right_hip_yz_tracking_data = std::make_unique ( - "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant); + auto right_hip_yz_tracking_data = + std::make_unique( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); + "hip_left"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); - - auto left_foot_rel_tracking_data = std::make_unique ( - "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, left_foot_tracking_data.get(), - left_hip_tracking_data.get()); - auto right_foot_rel_tracking_data = std::make_unique ( - "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, - osc_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), - right_hip_tracking_data.get()); - auto left_foot_yz_rel_tracking_data = std::make_unique ( - "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, - plant, left_foot_yz_tracking_data.get(), left_hip_yz_tracking_data.get()); - auto right_foot_yz_rel_tracking_data = std::make_unique ( - "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, plant, - plant, right_foot_yz_tracking_data.get(), right_hip_yz_tracking_data.get()); - auto pelvis_trans_rel_tracking_data = std::make_unique ( - "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis, plant, plant, pelvis_tracking_data.get(), - stance_foot_tracking_data.get()); + "hip_right"); + + auto left_foot_rel_tracking_data = + std::make_unique( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, left_foot_tracking_data.get(), + left_hip_tracking_data.get()); + auto right_foot_rel_tracking_data = + std::make_unique( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), + right_hip_tracking_data.get()); + auto left_foot_yz_rel_tracking_data = + std::make_unique( + "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, + plant, plant, left_foot_yz_tracking_data.get(), + left_hip_yz_tracking_data.get()); + auto right_foot_yz_rel_tracking_data = + std::make_unique( + "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, + osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, + plant, plant, right_foot_yz_tracking_data.get(), + right_hip_yz_tracking_data.get()); + auto pelvis_trans_rel_tracking_data = + std::make_unique( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant, pelvis_tracking_data.get(), + stance_foot_tracking_data.get()); left_foot_rel_tracking_data->SetViewFrame(view_frame); right_foot_rel_tracking_data->SetViewFrame(view_frame); left_foot_yz_rel_tracking_data->SetViewFrame(view_frame); @@ -381,8 +391,8 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); - // right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); @@ -397,16 +407,17 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant, plant_context.get()); - auto pelvis_rot_tracking_data = std::make_unique ( + auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, + "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, - "pelvis"); + "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_touchdown_air_phase, - "pelvis"); + "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_touchdown_air_phase, - "pelvis"); + "pelvis"); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -423,10 +434,10 @@ int DoMain(int argc, char* argv[]) { "right_toe_angle_traj"); // Swing toe joint tracking - auto left_toe_angle_tracking_data = std::make_unique ( + auto left_toe_angle_tracking_data = std::make_unique( "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); - auto right_toe_angle_tracking_data = std::make_unique ( + auto right_toe_angle_tracking_data = std::make_unique( "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); left_toe_angle_tracking_data->AddStateAndJointToTrack( @@ -447,22 +458,24 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); // Swing hip yaw joint tracking - auto left_hip_yaw_tracking_data = std::make_unique ( + auto left_hip_yaw_tracking_data = std::make_unique( "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant, plant); - auto right_hip_yaw_tracking_data = std::make_unique ( + auto right_hip_yaw_tracking_data = std::make_unique( "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant, plant); - left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); + left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", + "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", - "hip_yaw_rightdot"); - // left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); - // right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); - osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); - osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); - - osc->SetOsqpSolverOptionsFromYaml( - FLAGS_osqp_settings); + "hip_yaw_rightdot"); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), + VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), + VectorXd::Zero(1)); + + osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem osc->Build(); std::cout << "Built OSC" << std::endl; From 84debad96c640df8e8fb79d2edcf80b1b53b9ee3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 23 Mar 2022 14:03:59 -0400 Subject: [PATCH 161/758] adding mujoco to gym env --- .../plot_configs/cassie_running_plot.yaml | 8 +- .../cassie/gym_envs/cassie_env_state.py | 62 + .../cassie/gym_envs/cassie_gym_test.py | 12 +- .../pydairlib/cassie/gym_envs/cassiemujoco.py | 859 +++++++++++++ .../cassie/gym_envs/cassiemujoco_ctypes.py | 1116 +++++++++++++++++ .../cassie/gym_envs/libcassiemujoco.so | Bin 0 -> 257696 bytes .../cassie/gym_envs/mujoco_cassie_sim.py | 120 ++ bindings/pydairlib/cassie/learn_osc_gains.py | 12 +- .../osc_run/learned_osc_running_gains.yaml | 14 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 14 +- 11 files changed, 2188 insertions(+), 31 deletions(-) create mode 100644 bindings/pydairlib/cassie/gym_envs/cassie_env_state.py create mode 100644 bindings/pydairlib/cassie/gym_envs/cassiemujoco.py create mode 100755 bindings/pydairlib/cassie/gym_envs/cassiemujoco_ctypes.py create mode 100755 bindings/pydairlib/cassie/gym_envs/libcassiemujoco.so create mode 100644 bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 7697a21d1e..74a6995e12 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -30,13 +30,13 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} + pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} - hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [2], 'derivs': ['vel']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} +# left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} right_ft_traj: {'dims': [2], 'derivs': ['vel']} - left_ft_z_traj: {'dims': [2], 'derivs': ['vel']} +# left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py b/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py new file mode 100644 index 0000000000..3a8717b303 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py @@ -0,0 +1,62 @@ +import numpy as np +import matplotlib.pyplot as plt +from scipy.spatial.transform import Rotation as R + +CASSIE_QUATERNION_SLICE = slice(0, 4) +CASSIE_POSITION_SLICE = slice(4, 23) +CASSIE_OMEGA_SLICE = slice(23, 26) +CASSIE_VELOCITY_SLICE = slice(26, 45) +CASSIE_JOINT_POSITION_SLICE = slice(7, 23) +CASSIE_JOINT_VELOCITY_SLICE = slice(29, 45) +CASSIE_FB_POSITION_SLICE = slice(4, 7) +CASSIE_FB_VELOCITY_SLICE = slice(26, 29) + +CASSIE_NX = 45 +CASSIE_NQ = 23 +CASSIE_NV = 22 +CASSIE_NU = 10 +CASSIE_NACTION = 18 + + +class CassieEnvState(): + def __init__(self, t, x, u, action): + self.t = t + self.x = x + self.u = u + self.action = action + + def get_positions(self): + return self.x[CASSIE_POSITION_SLICE] + + def get_orientations(self): + return self.x[CASSIE_QUATERNION_SLICE] + + def get_velocities(self): + return self.x[CASSIE_VELOCITY_SLICE] + + def get_omegas(self): + return self.x[CASSIE_OMEGA_SLICE] + + def get_inputs(self): + return self.u + + def get_action(self): + return self.action + + def get_fb_positions(self): + return self.x[CASSIE_FB_POSITION_SLICE] + + def get_fb_velocities(self): + return self.x[CASSIE_FB_VELOCITY_SLICE] + + def get_joint_positions(self): + return self.x[CASSIE_JOINT_POSITION_SLICE] + + def get_joint_velocities(self): + return self.x[CASSIE_JOINT_VELOCITY_SLICE] + + def get_desired_forward_velocity(self): + return self.action[2] + + def get_desired_lateral_velocity(self): + return self.action[3] diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index a02c01ebfc..4c750ff6d5 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -31,14 +31,14 @@ def main(): action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 - while gym_env.current_time < 7.5: + while gym_env.current_time < 20.0: state, reward = gym_env.step(action) cumulative_reward += reward - gym_env.reset() - while gym_env.current_time < 5.0: - state, reward = gym_env.step(action) - cumulative_reward += reward - print(cumulative_reward) + # gym_env.reset() + # while gym_env.current_time < 5.0: + # state, reward = gym_env.step(action) + # cumulative_reward += reward + # print(cumulative_reward) if __name__ == '__main__': main() diff --git a/bindings/pydairlib/cassie/gym_envs/cassiemujoco.py b/bindings/pydairlib/cassie/gym_envs/cassiemujoco.py new file mode 100644 index 0000000000..826356c451 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/cassiemujoco.py @@ -0,0 +1,859 @@ +# Copyright (c) 2018 Dynamic Robotics Laboratory +# +# Permission to use, copy, modify, and distribute this software for any +# purpose with or without fee is hereby granted, provided that the above +# copyright notice and this permission notice appear in all copies. +# +# THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES +# WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF +# MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR +# ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES +# WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN +# ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF +# OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. + +from cassiemujoco_ctypes import * +import os +import ctypes +import numpy as np + +# from envs.terrains.rand import * + +# Get base directory +_dir_path = os.path.dirname(os.path.realpath(__file__)) + +# Initialize libcassiesim +default_model = "../model/cassie.xml" +cassie_mujoco_init(str.encode(default_model)) + +# Interface classes +# Note: Making the optional argument be a global var be default is perhaps not the safest thing to do +class CassieSim: + def __init__(self, modelfile=default_model, terrain=False, perception=False, reinit=False): + + if modelfile is not default_model: + self.modelfile = modelfile + else: + base = 'cassie' + if perception: + base += '_perception' + if terrain: + base += '_hfield' + self.modelfile = os.path.join(_dir_path, base + '.xml') + + self.c = cassie_sim_init(self.modelfile.encode('utf-8'), True) + + if terrain: + x_res, y_res = self.get_hfield_nrow(), self.get_hfield_ncol() + self.hfields = generate_perlin(x_res, y_res) + + params_array = (ctypes.c_int32 * 6)() + cassie_sim_params(self.c, params_array) + self.nv = cassie_sim_nv(self.c) + self.nbody = cassie_sim_nbody(self.c) + self.nq = cassie_sim_nq(self.c) + self.ngeom = cassie_sim_ngeom(self.c) + + def randomize_terrain(self): + hfield = self.hfields[np.random.randint(len(self.hfields))] + self.set_hfield_data(hfield.flatten()) + return hfield + + def step(self, u): + y = cassie_out_t() + cassie_sim_step(self.c, y, u) + return y + + def step_pd(self, u): + y = state_out_t() + cassie_sim_step_pd(self.c, y, u) + return y + + def integrate_pos(self): + y = state_out_t() + cassie_integrate_pos(self.c, y) + return y + + def get_state(self): + s = CassieState() + cassie_get_state(self.c, s.s) + return s + + def set_state(self, s): + cassie_set_state(self.c, s.s) + + def time(self): + timep = cassie_sim_time(self.c) + return timep[0] + + def qpos(self): + qposp = cassie_sim_qpos(self.c) + return qposp[:self.nq] + + def qpos_full(self): + qposp = cassie_sim_qpos(self.c) + return qposp[:self.nq] + + def qvel(self): + qvelp = cassie_sim_qvel(self.c) + return qvelp[:self.nv] + + def qvel_full(self): + qvelp = cassie_sim_qvel(self.c) + return qvelp[:self.nv] + + def qacc(self): + qaccp = cassie_sim_qacc(self.c) + return qaccp[:self.nv] + + def xpos(self, body_name): + xposp = cassie_sim_xpos(self.c, body_name.encode()) + return xposp[:3] + + def xquat(self, body_name): + xquatp = cassie_sim_xquat(self.c, body_name.encode()) + return xquatp[:4] + + def set_time(self, time): + timep = cassie_sim_time(self.c) + timep[0] = time + + def set_qpos(self, qpos): + qposp = cassie_sim_qpos(self.c) + for i in range(min(len(qpos), self.nq)): + qposp[i] = qpos[i] + + def set_qvel(self, qvel): + qvelp = cassie_sim_qvel(self.c) + for i in range(min(len(qvel), self.nv)): + qvelp[i] = qvel[i] + + def hold(self): + cassie_sim_hold(self.c) + + def release(self): + cassie_sim_release(self.c) + + def apply_force(self, xfrc, body_name="cassie-pelvis"): + xfrc_array = (ctypes.c_double * 6)() + for i in range(len(xfrc)): + xfrc_array[i] = xfrc[i] + cassie_sim_apply_force(self.c, xfrc_array, body_name.encode()) + + def sense_ground(self): + percept = (ctypes.c_double * 6)() + cassie_sim_read_rangefinder(self.c, percept) + + ret = np.zeros(6) + for i in range(6): + ret[i] = percept[i] + return ret + + def get_jacobian(self, name): + jacp = np.zeros(3*self.nv) + jacp_array = (ctypes.c_double * (3*self.nv))() + cassie_sim_get_jacobian(self.c, jacp_array, name.encode()) + for i in range(3*self.nv): + jacp[i] = jacp_array[i] + return jacp + + def get_jacobian_full(self, name): + jacp = np.zeros(3*self.nv) + jacp_array = (ctypes.c_double * (3*self.nv))() + jacr = np.zeros(3*self.nv) + jacr_array = (ctypes.c_double * (3*self.nv))() + cassie_sim_get_jacobian_full(self.c, jacp_array, jacr_array, name.encode()) + for i in range(3*self.nv): + jacp[i] = jacp_array[i] + jacr[i] = jacr_array[i] + return jacp, jacr + + def get_jacobian_full_site(self, name): + jacp = np.zeros(3*self.nv) + jacp_array = (ctypes.c_double * (3*self.nv))() + jacr = np.zeros(3*self.nv) + jacr_array = (ctypes.c_double * (3*self.nv))() + cassie_sim_get_jacobian_full_site(self.c, jacp_array, jacr_array, name.encode()) + for i in range(3*self.nv): + jacp[i] = jacp_array[i] + jacr[i] = jacr_array[i] + return jacp, jacr + + def get_foot_forces(self): + force = np.zeros(12) + frc_array = (ctypes.c_double * 12)() + cassie_sim_foot_forces(self.c, frc_array) + for i in range(12): + force[i] = frc_array[i] + lfrc = np.sqrt(np.power(force[0:3], 2).sum()) + rfrc = np.sqrt(np.power(force[6:9], 2).sum()) + return lfrc, rfrc + + # Returns 2 arrays each 6 long, the toe force and heel force. Each array is in order of + # left foot (3) and then right foot (3) + def get_heeltoe_forces(self): + toe_force = np.zeros(6) + heel_force = np.zeros(6) + toe_array = (ctypes.c_double * 6)() + heel_array = (ctypes.c_double * 6)() + cassie_sim_heeltoe_forces(self.c, toe_array, heel_array) + for i in range(6): + toe_force[i] = toe_array[i] + heel_force[i] = heel_array[i] + return toe_force, heel_force + + def foot_pos(self): + pos_array = (ctypes.c_double * 6)() + cassie_sim_foot_positions(self.c, pos_array) + pos = [] + for i in range(6): + pos.append(pos_array[i]) + return pos + + def foot_vel(self, vel): + vel_array = (ctypes.c_double * 12)() + cassie_sim_foot_velocities(self.c, vel_array) + for i in range(12): + vel[i] = vel_array[i] + + def body_vel(self, vel, body_name): + vel_array = (ctypes.c_double * 6)() + cassie_sim_body_vel(self.c, vel_array, body_name.encode()) + for i in range(6): + vel[i] = vel_array[i] + + # Returns the center of mass position vector in world frame + def center_of_mass_position(self): + pos_array = (ctypes.c_double * 3)() + cassie_sim_cm_position(self.c, pos_array) + pos = [] + for i in range(3): + pos.append(pos_array[i]) + return pos + + # Returns the center of mass velocity vector in world frame + def center_of_mass_velocity(self): + vel_array = (ctypes.c_double * 3)() + cassie_sim_cm_velocity(self.c, vel_array) + vel = [] + for i in range(3): + vel.append(vel_array[i]) + return vel + + # Returns 3x3 rotational intertia matrix of the robot around its center + # of mass in the pelvis frame. [kg*m^2] + def centroid_inertia(self): + I_array = (ctypes.c_double * 9)() + cassie_sim_centroid_inertia(self.c, I_array) + Icm = [] + for i in range(9): + Icm.append(I_array[i]) + return Icm + + # Return the angular momentum of the robot in the world frame. + def angular_momentum(self): + L_array = (ctypes.c_double * 3)() + cassie_sim_angular_momentum(self.c, L_array) + L_return = [] + for i in range(3): + L_return.append(L_array[i]) + return L_return + + # Return the full 32x32 mass matrix of Cassie. + def full_mass_matrix(self): + M_array = (ctypes.c_double * (32 * 32))() + cassie_sim_full_mass_matrix(self.c, M_array) + M_return = np.zeros((32,32)) + for i in range(32): + for j in range(32): + M_return[i,j] = M_array[i*32+j] + return M_return + + def constraint_jacobian(self): + J_array = (ctypes.c_double * (6 * 32))() + err_array = (ctypes.c_double * (6))() + cassie_sim_loop_constraint_info(self.c, J_array, err_array) + J_return = np.zeros((6,32)) + for i in range(6): + for j in range(32): + J_return[i,j] = J_array[i*32+j] + return J_return + + def constraint_error(self): + J_array = (ctypes.c_double * (6 * 32))() + err_array = (ctypes.c_double * (6))() + cassie_sim_loop_constraint_info(self.c, J_array, err_array) + err_return = np.zeros((6,1)) + for i in range(6): + err_return[i] = err_array[i] + return err_return + + # Return the minimal actuated mass matrix of Cassie. Contains 6 for floating + # base, 5 for left leg motors, 5 for right leg motors. + def minimal_mass_matrix(self): + ind_full_idx = [0,1,2,3,4,5,6,7,8,12,18,19,20,21,25,31] + dep_full_idx = [9,10,11,14,22,23,24,27] + ind_idx = np.arange(0, 16) + dep_idx = np.arange(16, 24) + spring_idx = [13, 15, 26, 28] + + J_c = self.constraint_jacobian() + J_c[:, 0:6] = 0 # Zero out floating base coordinates + J_c_div = J_c[:, ind_full_idx + dep_full_idx] + J_c_div[J_c_div < 1e-5] = 0 # Zero out very small terms for numerical stabilityL + + M = self.full_mass_matrix() + M_div_temp = M[:, ind_full_idx + dep_full_idx] + M_div = M_div_temp[ind_full_idx + dep_full_idx, :] + + G = np.linalg.lstsq(J_c_div[:, dep_idx], -J_c_div[:, ind_idx]) + + # print(G[0].shape) + P = np.block([[np.eye(16)], [G[0]]]) + M_minimal = P.T @ M_div @ P + + #J_c_dep = J_c[:, (13,24)] + # This gets hard + # import sys + # np.set_printoptions(threshold=sys.maxsize) + M_print = M_div[:, ind_idx] + M_print = M_print[ind_idx, :] + + # print("M") + # print(M_print) + # print("M_minimal") + # print(M_minimal) + + + return M_minimal + + + def foot_quat(self, quat): + quat_array = (ctypes.c_double * 4)() + cassie_sim_foot_quat(self.c, quat_array) + for i in range(4): + quat[i] = quat_array[i] + + def clear_forces(self): + cassie_sim_clear_forces(self.c) + + def get_dof_damping(self): + ptr = cassie_sim_dof_damping(self.c) + ret = np.zeros(self.nv) + for i in range(self.nv): + ret[i] = ptr[i] + return ret + + def get_body_mass(self): + ptr = cassie_sim_body_mass(self.c) + ret = np.zeros(self.nbody) + for i in range(self.nbody): + ret[i] = ptr[i] + return ret + + def get_body_ipos(self): + nbody = self.nbody * 3 + ptr = cassie_sim_body_ipos(self.c) + ret = np.zeros(nbody) + for i in range(nbody): + ret[i] = ptr[i] + return ret + + def get_body_pos(self, name): + ptr = cassie_sim_get_body_name_pos(self.c, name.encode()) + ret = np.zeros(3) + for i in range(3): + ret[i] = ptr[i] + return ret + + def get_geom_friction(self): + ptr = cassie_sim_geom_friction(self.c) + ret = np.zeros(self.ngeom * 3) + for i in range(self.ngeom * 3): + ret[i] = ptr[i] + return ret + + def get_geom_rgba(self, name=None): + if name is not None: + ptr = cassie_sim_geom_name_rgba(self.c, name.encode()) + ret = np.zeros(4) + for i in range(4): + ret[i] = ptr[i] + else: + ptr = cassie_sim_geom_rgba(self.c) + ret = np.zeros(self.ngeom * 4) + for i in range(self.ngeom * 4): + ret[i] = ptr[i] + return ret + + def get_geom_quat(self, name=None): + if name is not None: + ptr = cassie_sim_geom_name_quat(self.c, name.encode()) + ret = np.zeros(4) + for i in range(4): + ret[i] = ptr[i] + else: + ptr = cassie_sim_geom_quat(self.c) + ret = np.zeros(self.ngeom * 4) + for i in range(self.ngeom * 4): + ret[i] = ptr[i] + return ret + + def get_geom_pos(self, name=None): + if name is not None: + ptr = cassie_sim_geom_name_pos(self.c, name.encode()) + ret = np.zeros(3) + for i in range(3): + ret[i] = ptr[i] + else: + ptr = cassie_sim_geom_pos(self.c) + ret = np.zeros(self.ngeom * 3) + for i in range(self.ngeom * 3): + ret[i] = ptr[i] + return ret + + def get_geom_size(self, name=None): + if name is not None: + ptr = cassie_sim_geom_name_size(self.c, name.encode()) + ret = np.zeros(3) + for i in range(3): + ret[i] = ptr[i] + else: + ptr = cassie_sim_geom_size(self.c) + ret = np.zeros(self.ngeom * 3) + for i in range(self.ngeom * 3): + ret[i] = ptr[i] + return ret + + def set_dof_damping(self, data): + c_arr = (ctypes.c_double * self.nv)() + + if len(data) != self.nv: + print("SIZE MISMATCH SET_DOF_DAMPING()") + exit(1) + + for i in range(self.nv): + c_arr[i] = data[i] + + cassie_sim_set_dof_damping(self.c, c_arr) + + def set_body_mass(self, data, name=None): + # If no name is provided, set ALL body masses and assume "data" is array + # containing masses for every body + if name is None: + c_arr = (ctypes.c_double * self.nbody)() + + if len(data) != self.nbody: + print("SIZE MISMATCH SET_BODY_MASS()") + exit(1) + + for i in range(self.nbody): + c_arr[i] = data[i] + + cassie_sim_set_body_mass(self.c, c_arr) + # If name is provided, only set mass for specified body and assume + # "data" is a single double + else: + cassie_sim_set_body_name_mass(self.c, name.encode(), ctypes.c_double(data)) + + def set_body_pos(self, name, data): + if len(data) != 3: + print("SIZE MISMATCH SET BODY POS") + exit(1) + c_arr = (ctypes.c_double * 3)() + for i in range(3): + c_arr[i] = data[i] + cassie_sim_set_body_name_pos(self.c, name.encode(), c_arr) + + def set_body_ipos(self, data): + nbody = self.nbody * 3 + c_arr = (ctypes.c_double * nbody)() + + if len(data) != nbody: + print("SIZE MISMATCH SET_BODY_IPOS()") + exit(1) + + for i in range(nbody): + c_arr[i] = data[i] + + cassie_sim_set_body_ipos(self.c, c_arr) + + def set_geom_friction(self, data, name=None): + if name is None: + c_arr = (ctypes.c_double * (self.ngeom*3))() + + if len(data) != self.ngeom*3: + print("SIZE MISMATCH SET_GEOM_FRICTION()") + exit(1) + + for i in range(self.ngeom*3): + c_arr[i] = data[i] + + cassie_sim_set_geom_friction(self.c, c_arr) + else: + fric_array = (ctypes.c_double * 3)() + for i in range(3): + fric_array[i] = data[i] + cassie_sim_set_geom_name_friction(self.c, name.encode(), fric_array) + + + def set_geom_rgba(self, data, name=None): + if name is None: + ngeom = self.ngeom * 4 + + if len(data) != ngeom: + print("SIZE MISMATCH SET_GEOM_RGBA()") + exit(1) + + c_arr = (ctypes.c_float * ngeom)() + + for i in range(ngeom): + c_arr[i] = data[i] + + cassie_sim_set_geom_rgba(self.c, c_arr) + else: + rgba_array = (ctypes.c_float * 4)() + for i in range(4): + rgba_array[i] = data[i] + cassie_sim_set_geom_name_rgba(self.c, name.encode(), rgba_array) + + def set_geom_quat(self, data, name=None): + if name is None: + ngeom = self.ngeom * 4 + + if len(data) != ngeom: + print("SIZE MISMATCH SET_GEOM_QUAT()") + exit(1) + + c_arr = (ctypes.c_double * ngeom)() + + for i in range(ngeom): + c_arr[i] = data[i] + + cassie_sim_set_geom_quat(self.c, c_arr) + else: + quat_array = (ctypes.c_double * 4)() + for i in range(4): + quat_array[i] = data[i] + cassie_sim_set_geom_name_quat(self.c, name.encode(), quat_array) + + + def set_geom_pos(self, data, name=None): + if name is None: + ngeom = self.ngeom * 3 + + if len(data) != ngeom: + print("SIZE MISMATCH SET_GEOM_POS()") + exit(1) + + c_arr = (ctypes.c_double * ngeom)() + + for i in range(ngeom): + c_arr[i] = data[i] + + cassie_sim_set_geom_pos(self.c, c_arr) + else: + array = (ctypes.c_double * 3)() + for i in range(3): + array[i] = data[i] + cassie_sim_set_geom_name_pos(self.c, name.encode(), array) + + def set_geom_size(self, data, name=None): + if name is None: + ngeom = self.ngeom * 3 + + if len(data) != ngeom: + print("SIZE MISMATCH SET_GEOM_POS()") + exit(1) + + c_arr = (ctypes.c_double * ngeom)() + + for i in range(ngeom): + c_arr[i] = data[i] + + cassie_sim_set_geom_size(self.c, c_arr) + else: + array = (ctypes.c_double * 3)() + for i in range(3): + array[i] = data[i] + cassie_sim_set_geom_name_size(self.c, name.encode(), array) + + def set_const(self): + cassie_sim_set_const(self.c) + + def full_reset(self): + cassie_sim_full_reset(self.c) + + def get_hfield_nrow(self): + return cassie_sim_get_hfield_nrow(self.c) + + def get_hfield_ncol(self): + return cassie_sim_get_hfield_ncol(self.c) + + def get_nhfielddata(self): + return cassie_sim_get_nhfielddata(self.c) + + def get_hfield_size(self): + ret = np.zeros(4) + ptr = cassie_sim_get_hfield_size(self.c) + for i in range(4): + ret[i] = ptr[i] + return ret + + # Note that data has to be a flattened array. If flattening 2d numpy array, rows are y axis + # and cols are x axis. The data must also be normalized to (0-1) + def set_hfield_data(self, data, vis=None): + nhfielddata = self.get_nhfielddata() + if len(data) != nhfielddata: + print("SIZE MISMATCH SET_HFIELD_DATA") + exit(1) + data_arr = (ctypes.c_float * nhfielddata)(*data) + cassie_sim_set_hfielddata(self.c, ctypes.cast(data_arr, ctypes.POINTER(ctypes.c_float))) + + if vis is not None: + cassie_vis_remakeSceneCon(vis) + + def get_hfield_data(self): + nhfielddata = self.get_nhfielddata() + ret = np.zeros(nhfielddata) + ptr = cassie_sim_hfielddata(self.c) + for i in range(nhfielddata): + ret[i] = ptr[i] + return ret + + def set_hfield_size(self, data): + if len(data) != 4: + print("SIZE MISMATCH SET_HFIELD_SIZE") + exit(1) + size_array = (ctypes.c_double * 4)() + for i in range(4): + size_array[i] = data[i] + cassie_sim_set_hfield_size(self.c, size_array) + + # Returns a pointer to an array of joint_filter_t objects. Can be accessed/indexed as a usual python array of + # joint filter objects + def get_joint_filter(self): + j_filters = cassie_sim_joint_filter(self.c) + return j_filters + + # Set interal state of the joint filters. Takes in 2 arrays of values (x and y), which should be 6*4 and 6*3 long respectively. + # (6 joints, for each joint x has 4 values y has 3) + def set_joint_filter(self, x, y): + x_arr = (ctypes.c_double * (6*4))(*x) + y_arr = (ctypes.c_double * (6*3))(*y) + cassie_sim_set_joint_filter(self.c, ctypes.cast(x_arr, ctypes.POINTER(ctypes.c_double)), ctypes.cast(y_arr, ctypes.POINTER(ctypes.c_double))) + + # Returns a pointer to an array of drive_filter_t objects. Can be accessed/indexed as a usual python array of + # drive filter objects + def get_drive_filter(self): + d_filters = cassie_sim_drive_filter(self.c) + return d_filters + + # Set interal state of the drive filters. Takes in an array of values (x), which should be 10*9 long. + # (10 motor, for each motor have 9 values) + def set_drive_filter(self, x): + x_arr = (ctypes.c_int * (10*9))(*x) + cassie_sim_set_drive_filter(self.c, ctypes.cast(x_arr, ctypes.POINTER(ctypes.c_int))) + + # Get the current state of the torque delay array. Returns a 2d numpy array of size (10, 6), + # number of motors by number of delay cycles + def get_torque_delay(self): + t_arr = (ctypes.c_double * 60)() + cassie_sim_torque_delay(self.c, t_arr) + return np.array(t_arr[:]).reshape((10, 6)) + + # Set the torque delay state. Takes in a 2d numpy array of size (10, 6), number of motors by number of delay cycles + def set_torque_delay(self, data): + set_t_arr = (ctypes.c_double * 60)(*data.flatten()) + cassie_sim_set_torque_delay(self.c, ctypes.cast(set_t_arr, ctypes.POINTER(ctypes.c_double))) + + def __del__(self): + cassie_sim_free(self.c) + +class CassieVis: + def __init__(self, c, offscreen=False): + self.v = cassie_vis_init(c.c, c.modelfile.encode('utf-8'), ctypes.c_bool(offscreen)) + self.is_recording = False + + def draw(self, c): + state = cassie_vis_draw(self.v, c.c) + return state + + def valid(self): + return cassie_vis_valid(self.v) + + def ispaused(self): + return cassie_vis_paused(self.v) + + def remake(self): + cassie_vis_remakeSceneCon(self.v) + + # Applies the inputted force to the inputted body. "xfrc_apply" should contain the force/torque to + # apply in Cartesian coords as a 6-long array (first 3 are force, last 3 are torque). "body_name" + # should be a string matching a body name in the XML file. If "body_name" doesn't match an existing + # body name, then no force will be applied. + def apply_force(self, xfrc_apply, body_name): + xfrc_array = (ctypes.c_double * 6)() + for i in range(len(xfrc_apply)): + xfrc_array[i] = xfrc_apply[i] + cassie_vis_apply_force(self.v, xfrc_array, body_name.encode()) + + def add_marker(self, pos, size, rgba, so3): + pos_array = (ctypes.c_double * 3)() + for i in range(len(pos)): + pos_array[i] = pos[i] + size_array = (ctypes.c_double * 3)() + for i in range(len(size)): + size_array[i] = size[i] + rgba_array = (ctypes.c_double * 4)() + for i in range(len(rgba)): + rgba_array[i] = rgba[i] + so3_array = (ctypes.c_double * 9)() + for i in range(len(so3)): + so3_array[i] = so3[i] + cassie_vis_add_marker(self.v, pos_array, size_array, rgba_array, so3_array) + + def remove_marker(self, id_val): + cassie_vis_remove_marker(self.v, id_val) + + def clear_markers(self): + cassie_vis_clear_markers(self.v) + + def update_marker(self, id_val, pos, size, rgba, so3): + pos_array = (ctypes.c_double * 3)() + size_array = (ctypes.c_double * 3)() + rgba_array = (ctypes.c_double * 4)() + so3_array = (ctypes.c_double * 9)() + for i in range(len(pos)): + pos_array[i] = pos[i] + for i in range(len(size)): + size_array[i] = size[i] + for i in range(len(rgba)): + rgba_array[i] = rgba[i] + for i in range(len(so3)): + so3_array[i] = so3[i] + cassie_vis_update_marker_pos(self.v, ctypes.c_int(id_val), pos_array) + cassie_vis_update_marker_size(self.v, ctypes.c_int(id_val), size_array) + cassie_vis_update_marker_rgba(self.v, ctypes.c_int(id_val), rgba_array) + cassie_vis_update_marker_orient(self.v, ctypes.c_int(id_val), so3_array) + + def reset(self, c): + cassie_vis_full_reset(self.v, c.c) + #cassie_vis_close(self.v) + #cassie_vis_free(self.v) + #delattr(self, 'v') + #self.v = cassie_vis_init(c.c, c.modelfile.encode('utf-8')) + + def set_cam(self, body_name, zoom, azimuth, elevation): + cassie_vis_set_cam(self.v, body_name.encode(), zoom, azimuth, elevation) + + def window_resize(self, width=1200, height=900): + cassie_vis_window_resize(self.v, ctypes.c_int(width), ctypes.c_int(height)) + + def attach_cam(self, cam_name='egocentric'): + cassie_vis_attach_cam(self.v, cam_name.encode()) + + def init_depth(self, width, height): + cassie_vis_init_depth(self.v, ctypes.c_int(width), ctypes.c_int(height)) + + def get_depth_size(self): + size = cassie_vis_get_depth_size(self.v) + return size + + def draw_depth(self, c, width=30, height=30): + depth = cassie_vis_draw_depth(self.v, c.c, ctypes.c_int(width), ctypes.c_int(height)) + return depth[:width*height] + + def init_recording(self, filename, width=1920, height=1080): + cassie_vis_init_recording(self.v, filename.encode(), ctypes.c_int(width), ctypes.c_int(height)) + self.is_recording = True + + def record_frame(self): + cassie_vis_record_frame(self.v) + + def close_recording(self): + cassie_vis_close_recording(self.v) + self.is_recording = False + + def __del__(self): + cassie_vis_free(self.v) + +class CassieUdp: + def __init__(self, remote_addr='127.0.0.1', remote_port='25000', + local_addr='0.0.0.0', local_port='25001'): + self.sock = udp_init_client(str.encode(remote_addr), + str.encode(remote_port), + str.encode(local_addr), + str.encode(local_port)) + self.packet_header_info = packet_header_info_t() + self.recvlen = 2 + 697 + self.sendlen = 2 + 58 + self.recvlen_pd = 2 + 493 + self.sendlen_pd = 2 + 476 + self.recvbuf = (ctypes.c_ubyte * max(self.recvlen, self.recvlen_pd))() + self.sendbuf = (ctypes.c_ubyte * max(self.sendlen, self.sendlen_pd))() + self.inbuf = ctypes.cast(ctypes.byref(self.recvbuf, 2), + ctypes.POINTER(ctypes.c_ubyte)) + self.outbuf = ctypes.cast(ctypes.byref(self.sendbuf, 2), + ctypes.POINTER(ctypes.c_ubyte)) + + def send(self, u): + pack_cassie_user_in_t(u, self.outbuf) + send_packet(self.sock, self.sendbuf, self.sendlen, None, 0) + + def send_pd(self, u): + pack_pd_in_t(u, self.outbuf) + send_packet(self.sock, self.sendbuf, self.sendlen_pd, None, 0) + + def recv_wait(self): + nbytes = -1 + while nbytes != self.recvlen: + nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen, + None, None) + process_packet_header(self.packet_header_info, + self.recvbuf, self.sendbuf) + cassie_out = cassie_out_t() + unpack_cassie_out_t(self.inbuf, cassie_out) + return cassie_out + + def recv_wait_pd(self): + nbytes = -1 + while nbytes != self.recvlen_pd: + nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen_pd, + None, None) + process_packet_header(self.packet_header_info, + self.recvbuf, self.sendbuf) + state_out = state_out_t() + unpack_state_out_t(self.inbuf, state_out) + return state_out + + def recv_newest(self): + nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen, + None, None) + if nbytes != self.recvlen: + return None + process_packet_header(self.packet_header_info, + self.recvbuf, self.sendbuf) + cassie_out = cassie_out_t() + unpack_cassie_out_t(self.inbuf, cassie_out) + return cassie_out + + def recv_newest_pd(self): + nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen_pd, + None, None) + if nbytes != self.recvlen_pd: + return None + process_packet_header(self.packet_header_info, + self.recvbuf, self.sendbuf) + state_out = state_out_t() + unpack_state_out_t(self.inbuf, state_out) + return state_out + + def delay(self): + return ord(self.packet_header_info.delay) + + def seq_num_in_diff(self): + return ord(self.packet_header_info.seq_num_in_diff) + + def __del__(self): + udp_close(self.sock) diff --git a/bindings/pydairlib/cassie/gym_envs/cassiemujoco_ctypes.py b/bindings/pydairlib/cassie/gym_envs/cassiemujoco_ctypes.py new file mode 100755 index 0000000000..ecbc48bd50 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/cassiemujoco_ctypes.py @@ -0,0 +1,1116 @@ +# -*- coding: utf-8 -*- +# +# TARGET arch is: ['-I/usr/include/clang/6.0/include', '-Iinclude'] +# WORD_SIZE is: 8 +# POINTER_SIZE is: 8 +# LONGDOUBLE_SIZE is: 16 +# +import ctypes +import os +_dir_path = os.path.dirname(os.path.realpath(__file__)) + + +_libraries = {} +_libraries['./libcassiemujoco.so'] = ctypes.CDLL(_dir_path + '/libcassiemujoco.so') +# if local wordsize is same as target, keep ctypes pointer function. +if ctypes.sizeof(ctypes.c_void_p) == 8: + POINTER_T = ctypes.POINTER +else: + # required to access _ctypes + import _ctypes + # Emulate a pointer class using the approriate c_int32/c_int64 type + # The new class should have : + # ['__module__', 'from_param', '_type_', '__dict__', '__weakref__', '__doc__'] + # but the class should be submitted to a unique instance for each base type + # to that if A == B, POINTER_T(A) == POINTER_T(B) + ctypes._pointer_t_type_cache = {} + def POINTER_T(pointee): + # a pointer should have the same length as LONG + fake_ptr_base_type = ctypes.c_uint64 + # specific case for c_void_p + if pointee is None: # VOID pointer type. c_void_p. + pointee = type(None) # ctypes.c_void_p # ctypes.c_ulong + clsname = 'c_void' + else: + clsname = pointee.__name__ + if clsname in ctypes._pointer_t_type_cache: + return ctypes._pointer_t_type_cache[clsname] + # make template + class _T(_ctypes._SimpleCData,): + _type_ = 'L' + _subtype_ = pointee + def _sub_addr_(self): + return self.value + def __repr__(self): + return '%s(%d)'%(clsname, self.value) + def contents(self): + raise TypeError('This is not a ctypes pointer.') + def __init__(self, **args): + raise TypeError('This is not a ctypes pointer. It is not instanciable.') + _class = type('LP_%d_%s'%(8, clsname), (_T,),{}) + ctypes._pointer_t_type_cache[clsname] = _class + return _class + +c_int128 = ctypes.c_ubyte*16 +c_uint128 = c_int128 +void = None +if ctypes.sizeof(ctypes.c_longdouble) == 16: + c_long_double_t = ctypes.c_longdouble +else: + c_long_double_t = ctypes.c_ubyte*16 + + + +size_t = ctypes.c_uint64 +socklen_t = ctypes.c_uint32 +class struct_sockaddr(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('sa_family', ctypes.c_uint16), + ('sa_data', ctypes.c_char * 14), + ] + +ssize_t = ctypes.c_int64 +class struct_CassieCoreSim(ctypes.Structure): + pass + +cassie_core_sim_t = struct_CassieCoreSim +cassie_core_sim_alloc = _libraries['./libcassiemujoco.so'].cassie_core_sim_alloc +cassie_core_sim_alloc.restype = POINTER_T(struct_CassieCoreSim) +cassie_core_sim_alloc.argtypes = [] +cassie_core_sim_copy = _libraries['./libcassiemujoco.so'].cassie_core_sim_copy +cassie_core_sim_copy.restype = None +cassie_core_sim_copy.argtypes = [POINTER_T(struct_CassieCoreSim), POINTER_T(struct_CassieCoreSim)] +cassie_core_sim_free = _libraries['./libcassiemujoco.so'].cassie_core_sim_free +cassie_core_sim_free.restype = None +cassie_core_sim_free.argtypes = [POINTER_T(struct_CassieCoreSim)] +cassie_core_sim_setup = _libraries['./libcassiemujoco.so'].cassie_core_sim_setup +cassie_core_sim_setup.restype = None +cassie_core_sim_setup.argtypes = [POINTER_T(struct_CassieCoreSim)] +class struct_c__SA_cassie_user_in_t(ctypes.Structure): + pass + +class struct_c__SA_cassie_out_t(ctypes.Structure): + pass + +class struct_c__SA_cassie_in_t(ctypes.Structure): + pass + +cassie_core_sim_step = _libraries['./libcassiemujoco.so'].cassie_core_sim_step +cassie_core_sim_step.restype = None +cassie_core_sim_step.argtypes = [POINTER_T(struct_CassieCoreSim), POINTER_T(struct_c__SA_cassie_user_in_t), POINTER_T(struct_c__SA_cassie_out_t), POINTER_T(struct_c__SA_cassie_in_t)] +class struct_c__SA_elmo_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('controlWord', ctypes.c_uint16), + ('PADDING_0', ctypes.c_ubyte * 6), + ('torque', ctypes.c_double), + ] + +elmo_in_t = struct_c__SA_elmo_in_t +class struct_c__SA_cassie_leg_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('hipRollDrive', elmo_in_t), + ('hipYawDrive', elmo_in_t), + ('hipPitchDrive', elmo_in_t), + ('kneeDrive', elmo_in_t), + ('footDrive', elmo_in_t), + ] + +cassie_leg_in_t = struct_c__SA_cassie_leg_in_t +class struct_c__SA_radio_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('channel', ctypes.c_int16 * 14), + ] + +radio_in_t = struct_c__SA_radio_in_t +class struct_c__SA_cassie_pelvis_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('radio', radio_in_t), + ('sto', ctypes.c_bool), + ('piezoState', ctypes.c_bool), + ('piezoTone', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte), + ] + +cassie_pelvis_in_t = struct_c__SA_cassie_pelvis_in_t +struct_c__SA_cassie_in_t._pack_ = True # source:False +struct_c__SA_cassie_in_t._fields_ = [ + ('pelvis', cassie_pelvis_in_t), + ('leftLeg', cassie_leg_in_t), + ('rightLeg', cassie_leg_in_t), +] + +cassie_in_t = struct_c__SA_cassie_in_t +pack_cassie_in_t = _libraries['./libcassiemujoco.so'].pack_cassie_in_t +pack_cassie_in_t.restype = None +pack_cassie_in_t.argtypes = [POINTER_T(struct_c__SA_cassie_in_t), POINTER_T(ctypes.c_ubyte)] +unpack_cassie_in_t = _libraries['./libcassiemujoco.so'].unpack_cassie_in_t +unpack_cassie_in_t.restype = None +unpack_cassie_in_t.argtypes = [POINTER_T(ctypes.c_ubyte), POINTER_T(struct_c__SA_cassie_in_t)] +DiagnosticCodes = ctypes.c_int16 +class struct_c__SA_battery_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('dataGood', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 7), + ('stateOfCharge', ctypes.c_double), + ('voltage', ctypes.c_double * 12), + ('current', ctypes.c_double), + ('temperature', ctypes.c_double * 4), + ] + +battery_out_t = struct_c__SA_battery_out_t +class struct_c__SA_cassie_joint_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('position', ctypes.c_double), + ('velocity', ctypes.c_double), + ] + +cassie_joint_out_t = struct_c__SA_cassie_joint_out_t +class struct_c__SA_elmo_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('statusWord', ctypes.c_uint16), + ('PADDING_0', ctypes.c_ubyte * 6), + ('position', ctypes.c_double), + ('velocity', ctypes.c_double), + ('torque', ctypes.c_double), + ('driveTemperature', ctypes.c_double), + ('dcLinkVoltage', ctypes.c_double), + ('torqueLimit', ctypes.c_double), + ('gearRatio', ctypes.c_double), + ] + +elmo_out_t = struct_c__SA_elmo_out_t +class struct_c__SA_cassie_leg_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('hipRollDrive', elmo_out_t), + ('hipYawDrive', elmo_out_t), + ('hipPitchDrive', elmo_out_t), + ('kneeDrive', elmo_out_t), + ('footDrive', elmo_out_t), + ('shinJoint', cassie_joint_out_t), + ('tarsusJoint', cassie_joint_out_t), + ('footJoint', cassie_joint_out_t), + ('medullaCounter', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte), + ('medullaCpuLoad', ctypes.c_uint16), + ('reedSwitchState', ctypes.c_bool), + ('PADDING_1', ctypes.c_ubyte * 3), + ] + +cassie_leg_out_t = struct_c__SA_cassie_leg_out_t +class struct_c__SA_radio_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('radioReceiverSignalGood', ctypes.c_bool), + ('receiverMedullaSignalGood', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 6), + ('channel', ctypes.c_double * 16), + ] + +radio_out_t = struct_c__SA_radio_out_t +class struct_c__SA_target_pc_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('etherCatStatus', ctypes.c_int32 * 6), + ('etherCatNotifications', ctypes.c_int32 * 21), + ('PADDING_0', ctypes.c_ubyte * 4), + ('taskExecutionTime', ctypes.c_double), + ('overloadCounter', ctypes.c_uint32), + ('PADDING_1', ctypes.c_ubyte * 4), + ('cpuTemperature', ctypes.c_double), + ] + +target_pc_out_t = struct_c__SA_target_pc_out_t +class struct_c__SA_vectornav_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('dataGood', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte), + ('vpeStatus', ctypes.c_uint16), + ('PADDING_1', ctypes.c_ubyte * 4), + ('pressure', ctypes.c_double), + ('temperature', ctypes.c_double), + ('magneticField', ctypes.c_double * 3), + ('angularVelocity', ctypes.c_double * 3), + ('linearAcceleration', ctypes.c_double * 3), + ('orientation', ctypes.c_double * 4), + ] + +vectornav_out_t = struct_c__SA_vectornav_out_t +class struct_c__SA_cassie_pelvis_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('targetPc', target_pc_out_t), + ('battery', battery_out_t), + ('radio', radio_out_t), + ('vectorNav', vectornav_out_t), + ('medullaCounter', ctypes.c_ubyte), + ('PADDING_0', ctypes.c_ubyte), + ('medullaCpuLoad', ctypes.c_uint16), + ('bleederState', ctypes.c_bool), + ('leftReedSwitchState', ctypes.c_bool), + ('rightReedSwitchState', ctypes.c_bool), + ('PADDING_1', ctypes.c_ubyte), + ('vtmTemperature', ctypes.c_double), + ] + +cassie_pelvis_out_t = struct_c__SA_cassie_pelvis_out_t +struct_c__SA_cassie_out_t._pack_ = True # source:False +struct_c__SA_cassie_out_t._fields_ = [ + ('pelvis', cassie_pelvis_out_t), + ('leftLeg', cassie_leg_out_t), + ('rightLeg', cassie_leg_out_t), + ('isCalibrated', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte), + ('messages', ctypes.c_int16 * 4), + ('PADDING_1', ctypes.c_ubyte * 6), +] + +cassie_out_t = struct_c__SA_cassie_out_t +pack_cassie_out_t = _libraries['./libcassiemujoco.so'].pack_cassie_out_t +pack_cassie_out_t.restype = None +pack_cassie_out_t.argtypes = [POINTER_T(struct_c__SA_cassie_out_t), POINTER_T(ctypes.c_ubyte)] +unpack_cassie_out_t = _libraries['./libcassiemujoco.so'].unpack_cassie_out_t +unpack_cassie_out_t.restype = None +unpack_cassie_out_t.argtypes = [POINTER_T(ctypes.c_ubyte), POINTER_T(struct_c__SA_cassie_out_t)] +struct_c__SA_cassie_user_in_t._pack_ = True # source:False +struct_c__SA_cassie_user_in_t._fields_ = [ + ('torque', ctypes.c_double * 10), + ('telemetry', ctypes.c_int16 * 9), + ('PADDING_0', ctypes.c_ubyte * 6), +] + +cassie_user_in_t = struct_c__SA_cassie_user_in_t +pack_cassie_user_in_t = _libraries['./libcassiemujoco.so'].pack_cassie_user_in_t +pack_cassie_user_in_t.restype = None +pack_cassie_user_in_t.argtypes = [POINTER_T(struct_c__SA_cassie_user_in_t), POINTER_T(ctypes.c_ubyte)] +unpack_cassie_user_in_t = _libraries['./libcassiemujoco.so'].unpack_cassie_user_in_t +unpack_cassie_user_in_t.restype = None +unpack_cassie_user_in_t.argtypes = [POINTER_T(ctypes.c_ubyte), POINTER_T(struct_c__SA_cassie_user_in_t)] +class struct_cassie_sim(ctypes.Structure): + pass + +cassie_sim_t = struct_cassie_sim +class struct_cassie_vis(ctypes.Structure): + pass + +cassie_vis_t = struct_cassie_vis +class struct_cassie_state(ctypes.Structure): + pass + +cassie_state_t = struct_cassie_state +cassie_mujoco_init = _libraries['./libcassiemujoco.so'].cassie_mujoco_init +cassie_mujoco_init.restype = ctypes.c_bool +cassie_mujoco_init.argtypes = [POINTER_T(ctypes.c_char)] +cassie_cleanup = _libraries['./libcassiemujoco.so'].cassie_cleanup +cassie_cleanup.restype = None +cassie_cleanup.argtypes = [] +cassie_reload_xml = _libraries['./libcassiemujoco.so'].cassie_reload_xml +cassie_reload_xml.restype = ctypes.c_bool +cassie_reload_xml.argtypes = [ctypes.c_char_p] +cassie_sim_init = _libraries['./libcassiemujoco.so'].cassie_sim_init +cassie_sim_init.restype = POINTER_T(struct_cassie_sim) +cassie_sim_init.argtypes = [ctypes.c_char_p, ctypes.c_bool] +cassie_sim_duplicate = _libraries['./libcassiemujoco.so'].cassie_sim_duplicate +cassie_sim_duplicate.restype = POINTER_T(struct_cassie_sim) +cassie_sim_duplicate.argtypes = [POINTER_T(struct_cassie_sim)] +cassie_sim_copy = _libraries['./libcassiemujoco.so'].cassie_sim_copy +cassie_sim_copy.restype = None +cassie_sim_copy.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_cassie_sim)] +cassie_sim_free = _libraries['./libcassiemujoco.so'].cassie_sim_free +cassie_sim_free.restype = None +cassie_sim_free.argtypes = [POINTER_T(struct_cassie_sim)] +cassie_sim_step_ethercat = _libraries['./libcassiemujoco.so'].cassie_sim_step_ethercat +cassie_sim_step_ethercat.restype = None +cassie_sim_step_ethercat.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_c__SA_cassie_out_t), POINTER_T(struct_c__SA_cassie_in_t)] +cassie_sim_step = _libraries['./libcassiemujoco.so'].cassie_sim_step +cassie_sim_step.restype = None +cassie_sim_step.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_c__SA_cassie_out_t), POINTER_T(struct_c__SA_cassie_user_in_t)] +class struct_c__SA_state_out_t(ctypes.Structure): + pass + +class struct_c__SA_pd_in_t(ctypes.Structure): + pass + +class struct_c__SA_joint_filter_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('x', ctypes.c_double * 4), + ('y', ctypes.c_double * 3), + ] +joint_filter_t = struct_c__SA_joint_filter_t + +class struct_c__SA_drive_filter_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('x', ctypes.c_double * 9), + ] +drive_filter_t = struct_c__SA_drive_filter_t + +cassie_sim_step_pd = _libraries['./libcassiemujoco.so'].cassie_sim_step_pd +cassie_sim_step_pd.restype = None +cassie_sim_step_pd.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_c__SA_state_out_t), POINTER_T(struct_c__SA_pd_in_t)] + +cassie_integrate_pos = _libraries['./libcassiemujoco.so'].cassie_integrate_pos +cassie_integrate_pos.restype = None +cassie_integrate_pos.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_c__SA_state_out_t)] + +cassie_sim_time = _libraries['./libcassiemujoco.so'].cassie_sim_time +cassie_sim_time.restype = POINTER_T(ctypes.c_double) +cassie_sim_time.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_qpos = _libraries['./libcassiemujoco.so'].cassie_sim_qpos +cassie_sim_qpos.restype = POINTER_T(ctypes.c_double) +cassie_sim_qpos.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_qvel = _libraries['./libcassiemujoco.so'].cassie_sim_qvel +cassie_sim_qvel.restype = POINTER_T(ctypes.c_double) +cassie_sim_qvel.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_qacc = _libraries['./libcassiemujoco.so'].cassie_sim_qacc +cassie_sim_qacc.restype = POINTER_T(ctypes.c_double) +cassie_sim_qacc.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_mjmodel = _libraries['./libcassiemujoco.so'].cassie_sim_mjmodel +cassie_sim_mjmodel.restype = POINTER_T(None) +cassie_sim_mjmodel.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_mjdata = _libraries['./libcassiemujoco.so'].cassie_sim_mjdata +cassie_sim_mjdata.restype = POINTER_T(None) +cassie_sim_mjdata.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_check_obstacle_collision = _libraries['./libcassiemujoco.so'].cassie_sim_check_obstacle_collision +cassie_sim_check_obstacle_collision.restype = ctypes.c_bool +cassie_sim_check_obstacle_collision.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_check_self_collision = _libraries['./libcassiemujoco.so'].cassie_sim_check_self_collision +cassie_sim_check_self_collision.restype = ctypes.c_bool +cassie_sim_check_self_collision.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_foot_forces = _libraries['./libcassiemujoco.so'].cassie_sim_foot_forces +cassie_sim_foot_forces.restype = None +cassie_sim_foot_forces.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 12] + +cassie_sim_heeltoe_forces = _libraries['./libcassiemujoco.so'].cassie_sim_heeltoe_forces +cassie_sim_heeltoe_forces.restype = None +cassie_sim_heeltoe_forces.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 6, ctypes.c_double * 6] + +cassie_sim_foot_positions = _libraries['./libcassiemujoco.so'].cassie_sim_foot_positions +cassie_sim_foot_positions.restype = None +cassie_sim_foot_positions.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 6] + +cassie_sim_foot_velocities = _libraries['./libcassiemujoco.so'].cassie_sim_foot_velocities +cassie_sim_foot_velocities.restype = None +cassie_sim_foot_velocities.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 12] + +cassie_sim_cm_position = _libraries['./libcassiemujoco.so'].cassie_sim_cm_position +cassie_sim_cm_position.restype = None +cassie_sim_cm_position.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 3] + +cassie_sim_cm_velocity = _libraries['./libcassiemujoco.so'].cassie_sim_cm_velocity +cassie_sim_cm_velocity.restype = None +cassie_sim_cm_velocity.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 3] + +cassie_sim_centroid_inertia = _libraries['./libcassiemujoco.so'].cassie_sim_centroid_inertia +cassie_sim_centroid_inertia.restype = None +cassie_sim_centroid_inertia.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 9] + +cassie_sim_angular_momentum = _libraries['./libcassiemujoco.so'].cassie_sim_angular_momentum +cassie_sim_angular_momentum.restype = None +cassie_sim_angular_momentum.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 3] + +cassie_sim_full_mass_matrix = _libraries['./libcassiemujoco.so'].cassie_sim_full_mass_matrix +cassie_sim_full_mass_matrix.restype = None +cassie_sim_full_mass_matrix.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * (32*32)] + +cassie_sim_minimal_mass_matrix = _libraries['./libcassiemujoco.so'].cassie_sim_minimal_mass_matrix +cassie_sim_minimal_mass_matrix.restype = None +cassie_sim_minimal_mass_matrix.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * (16*16)] + +cassie_sim_loop_constraint_info = _libraries['./libcassiemujoco.so'].cassie_sim_loop_constraint_info +cassie_sim_loop_constraint_info.restype = None +cassie_sim_loop_constraint_info.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * (6*32), ctypes.c_double * (6)] + +cassie_sim_foot_quat = _libraries['./libcassiemujoco.so'].cassie_sim_foot_orient +cassie_sim_foot_quat.restype = None +cassie_sim_foot_quat.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 4] + +cassie_sim_body_vel = _libraries['./libcassiemujoco.so'].cassie_sim_body_velocities +cassie_sim_body_vel.restype = None +cassie_sim_body_vel.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 6, ctypes.c_char_p] + +cassie_sim_apply_force = _libraries['./libcassiemujoco.so'].cassie_sim_apply_force +cassie_sim_apply_force.restype = None +cassie_sim_apply_force.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 6, ctypes.c_char_p] + +cassie_sim_xpos = _libraries['./libcassiemujoco.so'].cassie_sim_xpos +cassie_sim_xpos.restype = POINTER_T(ctypes.c_double) +cassie_sim_xpos.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_xquat = _libraries['./libcassiemujoco.so'].cassie_sim_xquat +cassie_sim_xquat.restype = POINTER_T(ctypes.c_double) +cassie_sim_xquat.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_clear_forces = _libraries['./libcassiemujoco.so'].cassie_sim_clear_forces +cassie_sim_clear_forces.restype = None +cassie_sim_clear_forces.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_hold = _libraries['./libcassiemujoco.so'].cassie_sim_hold +cassie_sim_hold.restype = None +cassie_sim_hold.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_release = _libraries['./libcassiemujoco.so'].cassie_sim_release +cassie_sim_release.restype = None +cassie_sim_release.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_radio = _libraries['./libcassiemujoco.so'].cassie_sim_radio +cassie_sim_radio.restype = None +cassie_sim_radio.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 16] + +cassie_sim_full_reset = _libraries['./libcassiemujoco.so'].cassie_sim_full_reset +cassie_sim_full_reset.restype = None +cassie_sim_full_reset.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_hfield_nrow = _libraries['./libcassiemujoco.so'].cassie_sim_get_hfield_nrow +cassie_sim_get_hfield_nrow.restype = ctypes.c_int32 +cassie_sim_get_hfield_nrow.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_hfield_ncol = _libraries['./libcassiemujoco.so'].cassie_sim_get_hfield_ncol +cassie_sim_get_hfield_ncol.restype = ctypes.c_int32 +cassie_sim_get_hfield_ncol.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_nhfielddata = _libraries['./libcassiemujoco.so'].cassie_sim_get_nhfielddata +cassie_sim_get_nhfielddata.restype = ctypes.c_int32 +cassie_sim_get_nhfielddata.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_hfield_size = _libraries['./libcassiemujoco.so'].cassie_sim_get_hfield_size +cassie_sim_get_hfield_size.restype = POINTER_T(ctypes.c_double) +cassie_sim_get_hfield_size.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_set_hfield_size = _libraries['./libcassiemujoco.so'].cassie_sim_set_hfield_size +cassie_sim_set_hfield_size.restype = None +cassie_sim_set_hfield_size.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 4] + +cassie_sim_hfielddata = _libraries['./libcassiemujoco.so'].cassie_sim_hfielddata +cassie_sim_hfielddata.restype = POINTER_T(ctypes.c_float) +cassie_sim_hfielddata.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_set_hfielddata = _libraries['./libcassiemujoco.so'].cassie_sim_set_hfielddata +cassie_sim_set_hfielddata.restype = None +cassie_sim_set_hfielddata.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_float)] + +cassie_vis_init = _libraries['./libcassiemujoco.so'].cassie_vis_init +cassie_vis_init.restype = POINTER_T(struct_cassie_vis) +cassie_vis_init.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p,ctypes.c_bool] + +cassie_vis_close = _libraries['./libcassiemujoco.so'].cassie_vis_close +cassie_vis_close.restype = None +cassie_vis_close.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_free = _libraries['./libcassiemujoco.so'].cassie_vis_free +cassie_vis_free.restype = None +cassie_vis_free.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_draw = _libraries['./libcassiemujoco.so'].cassie_vis_draw +cassie_vis_draw.restype = ctypes.c_bool +cassie_vis_draw.argtypes = [POINTER_T(struct_cassie_vis), POINTER_T(struct_cassie_sim)] + +cassie_vis_set_cam = _libraries['./libcassiemujoco.so'].cassie_vis_set_cam +cassie_vis_set_cam.restype = None +cassie_vis_set_cam.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_char_p, ctypes.c_double, ctypes.c_double, ctypes.c_double] + +cassie_vis_window_resize = _libraries['./libcassiemujoco.so'].cassie_vis_window_resize +cassie_vis_window_resize.restype = None +cassie_vis_window_resize.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int32, ctypes.c_int32] + +cassie_vis_attach_cam = _libraries['./libcassiemujoco.so'].cassie_vis_attach_cam +cassie_vis_attach_cam.restype = None +cassie_vis_attach_cam.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_char_p] + +cassie_vis_draw_depth = _libraries['./libcassiemujoco.so'].cassie_vis_draw_depth +cassie_vis_draw_depth.restype = POINTER_T(ctypes.c_float) +cassie_vis_draw_depth.argtypes = [POINTER_T(struct_cassie_vis), POINTER_T(struct_cassie_sim), ctypes.c_int32, ctypes.c_int32] + +cassie_vis_get_depth_size = _libraries['./libcassiemujoco.so'].cassie_vis_get_depth_size +cassie_vis_get_depth_size.restype = ctypes.c_int32 +cassie_vis_get_depth_size.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int32, ctypes.c_int32] + +cassie_vis_init_depth = _libraries['./libcassiemujoco.so'].cassie_vis_init_depth +cassie_vis_init_depth.restype = None +cassie_vis_init_depth.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int, ctypes.c_int] + +cassie_vis_valid = _libraries['./libcassiemujoco.so'].cassie_vis_valid +cassie_vis_valid.restype = ctypes.c_bool +cassie_vis_valid.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_paused = _libraries['./libcassiemujoco.so'].cassie_vis_paused +cassie_vis_paused.restype = ctypes.c_bool +cassie_vis_paused.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_apply_force = _libraries['./libcassiemujoco.so'].cassie_vis_apply_force +cassie_vis_apply_force.restype = None +cassie_vis_apply_force.argtypes = [POINTER_T(struct_cassie_vis), POINTER_T(ctypes.c_double), ctypes.c_char_p] + +cassie_vis_add_marker = _libraries['./libcassiemujoco.so'].cassie_vis_add_marker +cassie_vis_add_marker.restype = None +cassie_vis_add_marker.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_double * 3, ctypes.c_double * 3, ctypes.c_double * 4, ctypes.c_double * 9] + +cassie_vis_remove_marker = _libraries['./libcassiemujoco.so'].cassie_vis_remove_marker +cassie_vis_remove_marker.restype = None +cassie_vis_remove_marker.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int] + +cassie_vis_clear_markers = _libraries['./libcassiemujoco.so'].cassie_vis_clear_markers +cassie_vis_clear_markers.restype = None +cassie_vis_clear_markers.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_update_marker_pos = _libraries['./libcassiemujoco.so'].cassie_vis_update_marker_pos +cassie_vis_update_marker_pos.restype = None +cassie_vis_update_marker_pos.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int, ctypes.c_double * 3] + +cassie_vis_update_marker_size = _libraries['./libcassiemujoco.so'].cassie_vis_update_marker_size +cassie_vis_update_marker_size.restype = None +cassie_vis_update_marker_size.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int, ctypes.c_double * 3] + +cassie_vis_update_marker_rgba = _libraries['./libcassiemujoco.so'].cassie_vis_update_marker_rgba +cassie_vis_update_marker_rgba.restype = None +cassie_vis_update_marker_rgba.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int, ctypes.c_double * 4] + +cassie_vis_update_marker_orient = _libraries['./libcassiemujoco.so'].cassie_vis_update_marker_orient +cassie_vis_update_marker_orient.restype = None +cassie_vis_update_marker_orient.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_int, ctypes.c_double * 9] + +cassie_vis_full_reset = _libraries['./libcassiemujoco.so'].cassie_vis_full_reset +cassie_vis_full_reset.restype = None +cassie_vis_full_reset.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_remakeSceneCon = _libraries['./libcassiemujoco.so'].cassie_vis_remakeSceneCon +cassie_vis_remakeSceneCon.restype = None +cassie_vis_remakeSceneCon.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_init_recording = _libraries['./libcassiemujoco.so'].cassie_vis_init_recording +cassie_vis_init_recording.restype = None +cassie_vis_init_recording.argtypes = [POINTER_T(struct_cassie_vis), ctypes.c_char_p, ctypes.c_int32, ctypes.c_int32] + +cassie_vis_record_frame = _libraries['./libcassiemujoco.so'].cassie_vis_record_frame +cassie_vis_record_frame.restype = None +cassie_vis_record_frame.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_vis_close_recording = _libraries['./libcassiemujoco.so'].cassie_vis_close_recording +cassie_vis_close_recording.restype = None +cassie_vis_close_recording.argtypes = [POINTER_T(struct_cassie_vis)] + +cassie_state_alloc = _libraries['./libcassiemujoco.so'].cassie_state_alloc +cassie_state_alloc.restype = POINTER_T(struct_cassie_state) +cassie_state_alloc.argtypes = [] + +cassie_state_duplicate = _libraries['./libcassiemujoco.so'].cassie_state_duplicate +cassie_state_duplicate.restype = POINTER_T(struct_cassie_state) +cassie_state_duplicate.argtypes = [POINTER_T(struct_cassie_state)] + +cassie_state_copy = _libraries['./libcassiemujoco.so'].cassie_state_copy +cassie_state_copy.restype = None +cassie_state_copy.argtypes = [POINTER_T(struct_cassie_state), POINTER_T(struct_cassie_state)] + +cassie_state_free = _libraries['./libcassiemujoco.so'].cassie_state_free +cassie_state_free.restype = None +cassie_state_free.argtypes = [POINTER_T(struct_cassie_state)] + +cassie_state_time = _libraries['./libcassiemujoco.so'].cassie_state_time +cassie_state_time.restype = POINTER_T(ctypes.c_double) +cassie_state_time.argtypes = [POINTER_T(struct_cassie_state)] + +cassie_state_qpos = _libraries['./libcassiemujoco.so'].cassie_state_qpos +cassie_state_qpos.restype = POINTER_T(ctypes.c_double) +cassie_state_qpos.argtypes = [POINTER_T(struct_cassie_state)] + +cassie_state_qvel = _libraries['./libcassiemujoco.so'].cassie_state_qvel +cassie_state_qvel.restype = POINTER_T(ctypes.c_double) +cassie_state_qvel.argtypes = [POINTER_T(struct_cassie_state)] + +cassie_get_state = _libraries['./libcassiemujoco.so'].cassie_get_state +cassie_get_state.restype = None +cassie_get_state.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_cassie_state)] + +cassie_set_state = _libraries['./libcassiemujoco.so'].cassie_set_state +cassie_set_state.restype = None +cassie_set_state.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(struct_cassie_state)] + +cassie_sim_read_rangefinder = _libraries['./libcassiemujoco.so'].cassie_sim_read_rangefinder +cassie_sim_read_rangefinder.restype = None +cassie_sim_read_rangefinder.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 6] + +#cassie_sim_foot_positions.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_double * 6] + +cassie_sim_dof_damping = _libraries['./libcassiemujoco.so'].cassie_sim_dof_damping +cassie_sim_dof_damping.restype = POINTER_T(ctypes.c_double) +cassie_sim_dof_damping.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_set_dof_damping = _libraries['./libcassiemujoco.so'].cassie_sim_set_dof_damping +cassie_sim_set_dof_damping.restype = None +cassie_sim_set_dof_damping.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_body_mass = _libraries['./libcassiemujoco.so'].cassie_sim_body_mass +cassie_sim_body_mass.restype = POINTER_T(ctypes.c_double) +cassie_sim_body_mass.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_set_body_mass = _libraries['./libcassiemujoco.so'].cassie_sim_set_body_mass +cassie_sim_set_body_mass.restype = None +cassie_sim_set_body_mass.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_body_name_mass = _libraries['./libcassiemujoco.so'].cassie_sim_set_body_name_mass +cassie_sim_set_body_name_mass.restype = None +cassie_sim_set_body_name_mass.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, ctypes.c_double] + +cassie_sim_body_ipos = _libraries['./libcassiemujoco.so'].cassie_sim_body_ipos +cassie_sim_body_ipos.restype = POINTER_T(ctypes.c_double) +cassie_sim_body_ipos.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_body_name_pos = _libraries['./libcassiemujoco.so'].cassie_sim_get_body_name_pos +cassie_sim_get_body_name_pos.restype = POINTER_T(ctypes.c_double) +cassie_sim_get_body_name_pos.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_set_body_name_pos = _libraries['./libcassiemujoco.so'].cassie_sim_set_body_name_pos +cassie_sim_set_body_name_pos.restype = None +cassie_sim_set_body_name_pos.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, POINTER_T(ctypes.c_double)] + +cassie_sim_set_body_ipos = _libraries['./libcassiemujoco.so'].cassie_sim_set_body_ipos +cassie_sim_set_body_ipos.restype = None +cassie_sim_set_body_ipos.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_geom_friction = _libraries['./libcassiemujoco.so'].cassie_sim_geom_friction +cassie_sim_geom_friction.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_friction.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_set_geom_friction = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_friction +cassie_sim_set_geom_friction.restype = None +cassie_sim_set_geom_friction.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_geom_name_friction = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_name_friction +cassie_sim_set_geom_name_friction.restype = None +cassie_sim_set_geom_name_friction.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, POINTER_T(ctypes.c_double)] + +cassie_sim_geom_rgba = _libraries['./libcassiemujoco.so'].cassie_sim_geom_rgba +cassie_sim_geom_rgba.restype = POINTER_T(ctypes.c_float) +cassie_sim_geom_rgba.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_geom_name_rgba = _libraries['./libcassiemujoco.so'].cassie_sim_geom_name_rgba +cassie_sim_geom_name_rgba.restype = POINTER_T(ctypes.c_float) +cassie_sim_geom_name_rgba.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_set_geom_rgba = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_rgba +cassie_sim_set_geom_rgba.restype = None +cassie_sim_set_geom_rgba.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_float)] + +cassie_sim_set_geom_name_rgba = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_name_rgba +cassie_sim_set_geom_name_rgba.restype = None +cassie_sim_set_geom_name_rgba.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, POINTER_T(ctypes.c_float)] + +cassie_sim_geom_quat = _libraries['./libcassiemujoco.so'].cassie_sim_geom_quat +cassie_sim_geom_quat.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_quat.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_geom_name_quat = _libraries['./libcassiemujoco.so'].cassie_sim_geom_name_quat +cassie_sim_geom_name_quat.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_name_quat.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_set_geom_quat = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_quat +cassie_sim_set_geom_quat.restype = None +cassie_sim_set_geom_quat.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_geom_name_quat = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_name_quat +cassie_sim_set_geom_name_quat.restype = None +cassie_sim_set_geom_name_quat.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, POINTER_T(ctypes.c_double)] + +cassie_sim_geom_pos = _libraries['./libcassiemujoco.so'].cassie_sim_geom_pos +cassie_sim_geom_pos.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_pos.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_geom_name_pos = _libraries['./libcassiemujoco.so'].cassie_sim_geom_name_pos +cassie_sim_geom_name_pos.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_name_pos.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_set_geom_pos = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_pos +cassie_sim_set_geom_pos.restype = None +cassie_sim_set_geom_pos.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_geom_name_pos = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_name_pos +cassie_sim_set_geom_name_pos.restype = None +cassie_sim_set_geom_name_pos.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, POINTER_T(ctypes.c_double)] + +cassie_sim_geom_size = _libraries['./libcassiemujoco.so'].cassie_sim_geom_size +cassie_sim_geom_size.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_size.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_geom_name_size = _libraries['./libcassiemujoco.so'].cassie_sim_geom_name_size +cassie_sim_geom_name_size.restype = POINTER_T(ctypes.c_double) +cassie_sim_geom_name_size.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p] + +cassie_sim_set_geom_size = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_size +cassie_sim_set_geom_size.restype = None +cassie_sim_set_geom_size.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_geom_name_size = _libraries['./libcassiemujoco.so'].cassie_sim_set_geom_name_size +cassie_sim_set_geom_name_size.restype = None +cassie_sim_set_geom_name_size.argtypes = [POINTER_T(struct_cassie_sim), ctypes.c_char_p, POINTER_T(ctypes.c_double)] + +cassie_sim_set_const = _libraries['./libcassiemujoco.so'].cassie_sim_set_const +cassie_sim_set_const.restype = None +cassie_sim_set_const.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_params = _libraries['./libcassiemujoco.so'].cassie_sim_params +cassie_sim_params.restype = None +cassie_sim_params.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_int32)] + +cassie_sim_joint_filter = _libraries['./libcassiemujoco.so'].cassie_sim_joint_filter +cassie_sim_joint_filter.restype = POINTER_T(joint_filter_t) +cassie_sim_joint_filter.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_joint_filter = _libraries['./libcassiemujoco.so'].cassie_sim_get_joint_filter +cassie_sim_get_joint_filter.restype = None +cassie_sim_get_joint_filter.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_joint_filter = _libraries['./libcassiemujoco.so'].cassie_sim_set_joint_filter +cassie_sim_set_joint_filter.restype = None +cassie_sim_set_joint_filter.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double), POINTER_T(ctypes.c_double)] + +cassie_sim_drive_filter = _libraries['./libcassiemujoco.so'].cassie_sim_drive_filter +cassie_sim_drive_filter.restype = POINTER_T(drive_filter_t) +cassie_sim_drive_filter.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_drive_filter = _libraries['./libcassiemujoco.so'].cassie_sim_drive_filter +cassie_sim_get_drive_filter.restype = None +cassie_sim_get_drive_filter.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_drive_filter = _libraries['./libcassiemujoco.so'].cassie_sim_set_drive_filter +cassie_sim_set_drive_filter.restype = None +cassie_sim_set_drive_filter.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_torque_delay = _libraries['./libcassiemujoco.so'].cassie_sim_torque_delay +cassie_sim_torque_delay.restype = None +cassie_sim_torque_delay.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] + +cassie_sim_set_torque_delay = _libraries['./libcassiemujoco.so'].cassie_sim_set_torque_delay +cassie_sim_set_torque_delay.restype = None +cassie_sim_set_torque_delay.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double)] +cassie_sim_nv = _libraries['./libcassiemujoco.so'].cassie_sim_nv +cassie_sim_nv.restype = ctypes.c_int32 +cassie_sim_nv.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_nbody = _libraries['./libcassiemujoco.so'].cassie_sim_nbody +cassie_sim_nbody.restype = ctypes.c_int32 +cassie_sim_nbody.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_ngeom = _libraries['./libcassiemujoco.so'].cassie_sim_ngeom +cassie_sim_ngeom.restype = ctypes.c_int32 +cassie_sim_ngeom.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_nq = _libraries['./libcassiemujoco.so'].cassie_sim_nq +cassie_sim_nq.restype = ctypes.c_int32 +cassie_sim_nq.argtypes = [POINTER_T(struct_cassie_sim)] + +cassie_sim_get_jacobian = _libraries['./libcassiemujoco.so'].cassie_sim_get_jacobian +cassie_sim_get_jacobian.restype = None +cassie_sim_get_jacobian.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double), ctypes.c_char_p] + +cassie_sim_get_jacobian_full = _libraries['./libcassiemujoco.so'].cassie_sim_get_jacobian_full +cassie_sim_get_jacobian_full.restype = None +cassie_sim_get_jacobian_full.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double), POINTER_T(ctypes.c_double), ctypes.c_char_p] + +cassie_sim_get_jacobian_full_site = _libraries['./libcassiemujoco.so'].cassie_sim_get_jacobian_full_site +cassie_sim_get_jacobian_full_site.restype = None +cassie_sim_get_jacobian_full_site.argtypes = [POINTER_T(struct_cassie_sim), POINTER_T(ctypes.c_double), POINTER_T(ctypes.c_double), ctypes.c_char_p] + +class struct_c__SA_pd_motor_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('torque', ctypes.c_double * 5), + ('pTarget', ctypes.c_double * 5), + ('dTarget', ctypes.c_double * 5), + ('pGain', ctypes.c_double * 5), + ('dGain', ctypes.c_double * 5), + ] + +pd_motor_in_t = struct_c__SA_pd_motor_in_t +class struct_c__SA_pd_task_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('torque', ctypes.c_double * 6), + ('pTarget', ctypes.c_double * 6), + ('dTarget', ctypes.c_double * 6), + ('pGain', ctypes.c_double * 6), + ('dGain', ctypes.c_double * 6), + ] + +pd_task_in_t = struct_c__SA_pd_task_in_t +class struct_c__SA_pd_leg_in_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('taskPd', pd_task_in_t), + ('motorPd', pd_motor_in_t), + ] + +pd_leg_in_t = struct_c__SA_pd_leg_in_t +struct_c__SA_pd_in_t._pack_ = True # source:False +struct_c__SA_pd_in_t._fields_ = [ + ('leftLeg', pd_leg_in_t), + ('rightLeg', pd_leg_in_t), + ('telemetry', ctypes.c_double * 9), +] + +pd_in_t = struct_c__SA_pd_in_t +pack_pd_in_t = _libraries['./libcassiemujoco.so'].pack_pd_in_t +pack_pd_in_t.restype = None +pack_pd_in_t.argtypes = [POINTER_T(struct_c__SA_pd_in_t), POINTER_T(ctypes.c_ubyte)] +unpack_pd_in_t = _libraries['./libcassiemujoco.so'].unpack_pd_in_t +unpack_pd_in_t.restype = None +unpack_pd_in_t.argtypes = [POINTER_T(ctypes.c_ubyte), POINTER_T(struct_c__SA_pd_in_t)] +class struct_PdInput(ctypes.Structure): + pass + +pd_input_t = struct_PdInput +pd_input_alloc = _libraries['./libcassiemujoco.so'].pd_input_alloc +pd_input_alloc.restype = POINTER_T(struct_PdInput) +pd_input_alloc.argtypes = [] +pd_input_copy = _libraries['./libcassiemujoco.so'].pd_input_copy +pd_input_copy.restype = None +pd_input_copy.argtypes = [POINTER_T(struct_PdInput), POINTER_T(struct_PdInput)] +pd_input_free = _libraries['./libcassiemujoco.so'].pd_input_free +pd_input_free.restype = None +pd_input_free.argtypes = [POINTER_T(struct_PdInput)] +pd_input_setup = _libraries['./libcassiemujoco.so'].pd_input_setup +pd_input_setup.restype = None +pd_input_setup.argtypes = [POINTER_T(struct_PdInput)] +pd_input_step = _libraries['./libcassiemujoco.so'].pd_input_step +pd_input_step.restype = None +pd_input_step.argtypes = [POINTER_T(struct_PdInput), POINTER_T(struct_c__SA_pd_in_t), POINTER_T(struct_c__SA_cassie_out_t), POINTER_T(struct_c__SA_cassie_user_in_t)] +class struct_c__SA_state_battery_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('stateOfCharge', ctypes.c_double), + ('current', ctypes.c_double), + ] + +state_battery_out_t = struct_c__SA_state_battery_out_t +class struct_c__SA_state_foot_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('position', ctypes.c_double * 3), + ('orientation', ctypes.c_double * 4), + ('footRotationalVelocity', ctypes.c_double * 3), + ('footTranslationalVelocity', ctypes.c_double * 3), + ('toeForce', ctypes.c_double * 3), + ('heelForce', ctypes.c_double * 3), + ] + +state_foot_out_t = struct_c__SA_state_foot_out_t +class struct_c__SA_state_joint_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('position', ctypes.c_double * 6), + ('velocity', ctypes.c_double * 6), + ] + +state_joint_out_t = struct_c__SA_state_joint_out_t +class struct_c__SA_state_motor_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('position', ctypes.c_double * 10), + ('velocity', ctypes.c_double * 10), + ('torque', ctypes.c_double * 10), + ] + +state_motor_out_t = struct_c__SA_state_motor_out_t +class struct_c__SA_state_pelvis_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('position', ctypes.c_double * 3), + ('orientation', ctypes.c_double * 4), + ('rotationalVelocity', ctypes.c_double * 3), + ('translationalVelocity', ctypes.c_double * 3), + ('translationalAcceleration', ctypes.c_double * 3), + ('externalMoment', ctypes.c_double * 3), + ('externalForce', ctypes.c_double * 3), + ] + +state_pelvis_out_t = struct_c__SA_state_pelvis_out_t +class struct_c__SA_state_radio_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('channel', ctypes.c_double * 16), + ('signalGood', ctypes.c_bool), + ('PADDING_0', ctypes.c_ubyte * 7), + ] + +state_radio_out_t = struct_c__SA_state_radio_out_t +class struct_c__SA_state_terrain_out_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('height', ctypes.c_double), + ('slope', ctypes.c_double * 2), + ] + +state_terrain_out_t = struct_c__SA_state_terrain_out_t +struct_c__SA_state_out_t._pack_ = True # source:False +struct_c__SA_state_out_t._fields_ = [ + ('pelvis', state_pelvis_out_t), + ('leftFoot', state_foot_out_t), + ('rightFoot', state_foot_out_t), + ('terrain', state_terrain_out_t), + ('motor', state_motor_out_t), + ('joint', state_joint_out_t), + ('radio', state_radio_out_t), + ('battery', state_battery_out_t), +] + +state_out_t = struct_c__SA_state_out_t +pack_state_out_t = _libraries['./libcassiemujoco.so'].pack_state_out_t +pack_state_out_t.restype = None +pack_state_out_t.argtypes = [POINTER_T(struct_c__SA_state_out_t), POINTER_T(ctypes.c_ubyte)] +unpack_state_out_t = _libraries['./libcassiemujoco.so'].unpack_state_out_t +unpack_state_out_t.restype = None +unpack_state_out_t.argtypes = [POINTER_T(ctypes.c_ubyte), POINTER_T(struct_c__SA_state_out_t)] +class struct_StateOutput(ctypes.Structure): + pass + +state_output_t = struct_StateOutput +state_output_alloc = _libraries['./libcassiemujoco.so'].state_output_alloc +state_output_alloc.restype = POINTER_T(struct_StateOutput) +state_output_alloc.argtypes = [] +state_output_copy = _libraries['./libcassiemujoco.so'].state_output_copy +state_output_copy.restype = None +state_output_copy.argtypes = [POINTER_T(struct_StateOutput), POINTER_T(struct_StateOutput)] +state_output_free = _libraries['./libcassiemujoco.so'].state_output_free +state_output_free.restype = None +state_output_free.argtypes = [POINTER_T(struct_StateOutput)] +state_output_setup = _libraries['./libcassiemujoco.so'].state_output_setup +state_output_setup.restype = None +state_output_setup.argtypes = [POINTER_T(struct_StateOutput)] +state_output_step = _libraries['./libcassiemujoco.so'].state_output_step +state_output_step.restype = None +state_output_step.argtypes = [POINTER_T(struct_StateOutput), POINTER_T(struct_c__SA_cassie_out_t), POINTER_T(struct_c__SA_state_out_t)] +class struct_c__SA_packet_header_info_t(ctypes.Structure): + _pack_ = True # source:False + _fields_ = [ + ('seq_num_out', ctypes.c_char), + ('seq_num_in_last', ctypes.c_char), + ('delay', ctypes.c_char), + ('seq_num_in_diff', ctypes.c_char), + ] + +packet_header_info_t = struct_c__SA_packet_header_info_t +process_packet_header = _libraries['./libcassiemujoco.so'].process_packet_header +process_packet_header.restype = None +process_packet_header.argtypes = [POINTER_T(struct_c__SA_packet_header_info_t), POINTER_T(ctypes.c_ubyte), POINTER_T(ctypes.c_ubyte)] +udp_init_host = _libraries['./libcassiemujoco.so'].udp_init_host +udp_init_host.restype = ctypes.c_int32 +udp_init_host.argtypes = [POINTER_T(ctypes.c_char), POINTER_T(ctypes.c_char)] +udp_init_client = _libraries['./libcassiemujoco.so'].udp_init_client +udp_init_client.restype = ctypes.c_int32 +udp_init_client.argtypes = [POINTER_T(ctypes.c_char), POINTER_T(ctypes.c_char), POINTER_T(ctypes.c_char), POINTER_T(ctypes.c_char)] +udp_close = _libraries['./libcassiemujoco.so'].udp_close +udp_close.restype = None +udp_close.argtypes = [ctypes.c_int32] +get_newest_packet = _libraries['./libcassiemujoco.so'].get_newest_packet +get_newest_packet.restype = ssize_t +get_newest_packet.argtypes = [ctypes.c_int32, POINTER_T(None), size_t, POINTER_T(struct_sockaddr), POINTER_T(ctypes.c_uint32)] +wait_for_packet = _libraries['./libcassiemujoco.so'].wait_for_packet +wait_for_packet.restype = ssize_t +wait_for_packet.argtypes = [ctypes.c_int32, POINTER_T(None), size_t, POINTER_T(struct_sockaddr), POINTER_T(ctypes.c_uint32)] +send_packet = _libraries['./libcassiemujoco.so'].send_packet +send_packet.restype = ssize_t +send_packet.argtypes = [ctypes.c_int32, POINTER_T(None), size_t, POINTER_T(struct_sockaddr), socklen_t] + +__all__ = \ + ['cassie_pelvis_in_t', 'struct_StateOutput', 'cassie_state_t', + 'cassie_sim_check_self_collision', 'cassie_vis_free', + 'cassie_in_t', 'state_terrain_out_t', 'struct_c__SA_pd_leg_in_t', + 'cassie_state_free', 'struct_c__SA_state_battery_out_t', + 'elmo_in_t', 'state_joint_out_t', 'send_packet', + 'cassie_pelvis_out_t', 'cassie_cleanup', + 'struct_c__SA_state_radio_out_t', 'cassie_vis_valid', + 'pd_input_setup', 'pd_leg_in_t', 'cassie_mujoco_init', + 'cassie_state_copy', 'cassie_core_sim_setup', 'battery_out_t', + 'cassie_sim_hold', 'struct_CassieCoreSim', 'cassie_core_sim_step', + 'pack_cassie_out_t', 'cassie_out_t', 'radio_in_t', + 'unpack_cassie_out_t', 'struct_c__SA_pd_task_in_t', + 'struct_PdInput', 'udp_init_client', 'pd_motor_in_t', + 'cassie_sim_t', 'cassie_core_sim_alloc', 'get_newest_packet', + 'size_t', 'struct_c__SA_vectornav_out_t', + 'struct_c__SA_pd_motor_in_t', 'cassie_get_state', + 'state_battery_out_t', 'struct_c__SA_state_pelvis_out_t', + 'cassie_state_qpos', 'cassie_state_qvel', 'state_radio_out_t', + 'struct_c__SA_pd_in_t', 'udp_close', 'state_output_free', + 'cassie_core_sim_free', 'pd_task_in_t', 'packet_header_info_t', + 'pd_in_t', 'struct_cassie_vis', 'struct_c__SA_elmo_out_t', + 'pack_pd_in_t', 'struct_c__SA_radio_out_t', 'pd_input_alloc', + 'DiagnosticCodes', 'unpack_state_out_t', 'target_pc_out_t', + 'cassie_sim_duplicate', 'cassie_state_alloc', 'cassie_sim_init', + 'struct_c__SA_cassie_user_in_t', 'struct_c__SA_radio_in_t', + 'socklen_t', 'cassie_vis_init', 'state_out_t', + 'struct_c__SA_cassie_in_t', 'pd_input_free', 'state_output_alloc', + 'struct_c__SA_cassie_leg_out_t', + 'struct_c__SA_cassie_pelvis_in_t', 'unpack_pd_in_t', + 'cassie_user_in_t', 'cassie_sim_clear_forces', 'cassie_vis_t', + 'struct_c__SA_target_pc_out_t', 'pd_input_step', + 'cassie_set_state', 'struct_c__SA_battery_out_t', + 'vectornav_out_t', 'struct_c__SA_packet_header_info_t', + 'cassie_sim_step_pd', 'struct_sockaddr', 'cassie_vis_draw','cassie_integrate_pos', + 'cassie_core_sim_copy', 'unpack_cassie_in_t', 'struct_cassie_sim', + 'unpack_cassie_user_in_t', 'cassie_sim_step', 'udp_init_host', + 'state_motor_out_t', 'cassie_core_sim_t', 'pack_state_out_t', + 'cassie_sim_mjdata', 'state_output_setup', 'cassie_sim_mjmodel', + 'state_foot_out_t', 'state_output_t', 'cassie_sim_time', + 'cassie_sim_step_ethercat', 'cassie_sim_check_obstacle_collision', + 'elmo_out_t', 'pack_cassie_in_t', 'cassie_sim_apply_force','cassie_sim_full_reset', + 'cassie_leg_out_t', 'wait_for_packet', + 'struct_c__SA_cassie_leg_in_t', 'struct_c__SA_state_joint_out_t', + 'process_packet_header', 'cassie_sim_release', 'cassie_sim_foot_forces', + 'cassie_sim_foot_positions', 'cassie_sim_foot_velocities', 'struct_c__SA_state_foot_out_t', + 'cassie_sim_cm_position','cassie_sim_centroid_inertia', + 'cassie_sim_cm_velocity','cassie_sim_angular_momentum', + 'cassie_sim_full_mass_matrix','cassie_sim_minimal_mass_matrix', + 'pd_input_t', 'pack_cassie_user_in_t', 'cassie_state_duplicate', + 'state_pelvis_out_t', 'struct_c__SA_state_terrain_out_t', + 'cassie_sim_free', 'cassie_sim_xpos', 'cassie_sim_xquat', 'ssize_t', 'state_output_copy', + 'cassie_sim_radio', 'cassie_vis_close', 'cassie_vis_paused', 'radio_out_t', + 'state_output_step', 'struct_c__SA_state_motor_out_t', + 'struct_cassie_state', 'cassie_state_time', 'cassie_sim_qvel', + 'cassie_sim_qpos', 'cassie_sim_qacc', 'struct_c__SA_elmo_in_t', 'cassie_joint_out_t', + 'cassie_leg_in_t', 'struct_c__SA_cassie_joint_out_t', + 'struct_c__SA_state_out_t', 'struct_c__SA_cassie_pelvis_out_t', + 'pd_input_copy', 'cassie_sim_copy', 'struct_c__SA_cassie_out_t', + 'cassie_sim_dof_damping', 'cassie_sim_set_dof_damping', + 'cassie_sim_body_mass', 'cassie_sim_set_body_mass', + 'cassie_sim_loop_constraint_info', + 'cassie_sim_body_ipos', 'cassie_sim_set_body_ipos', + 'cassie_sim_geom_friction', 'cassie_sim_set_geom_friction', + 'cassie_sim_set_const', + 'cassie_sim_geom_rgba', 'cassie_sim_geom_name_rgba', 'cassie_sim_set_geom_rgba', 'cassie_sim_set_geom_name_rgba', + 'cassie_sim_geom_quat', 'cassie_sim_geom_name_quat', 'cassie_sim_set_geom_quat', 'cassie_sim_set_geom_name_quat', + 'cassie_sim_geom_pos', 'cassie_sim_geom_name_pos', 'cassie_sim_set_geom_pos', 'cassie_sim_set_geom_name_pos', + 'cassie_sim_geom_size', 'cassie_sim_geom_name_size', 'cassie_sim_set_geom_size', 'cassie_sim_set_geom_name_size', + 'cassie_sim_set_geom_name_friction', 'cassie_reload_xml', 'cassie_vis_apply_force', + 'cassie_vis_add_marker', 'cassie_vis_remove_marker', 'cassie_vis_clear_markers', + 'cassie_vis_update_marker_pos', 'cassie_vis_update_marker_size', 'cassie_vis_update_marker_rgba', 'cassie_vis_update_marker_orient', + 'cassie_sim_foot_quat', 'cassie_sim_body_vel', 'cassie_sim_set_body_name_mass', + 'cassie_sim_get_hfield_nrow', 'cassie_sim_get_hfield_ncol', 'cassie_sim_get_nhfielddata', + 'cassie_sim_get_hfield_size', 'cassie_sim_set_hfield_size', 'cassie_sim_hfielddata', 'cassie_sim_set_hfielddata', + 'cassie_sim_foot_quat', 'cassie_sim_body_vel', 'cassie_sim_set_body_name_mass', 'cassie_vis_set_cam', + 'cassie_sim_joint_filter', 'cassie_sim_drive_filter', 'cassie_sim_set_joint_filter', 'cassie_sim_set_drive_filter', + 'cassie_sim_get_joint_filter', 'cassie_sim_get_drive_filter', + 'cassie_sim_torque_delay', 'cassie_sim_set_torque_delay', 'drive_filter_t', 'joint_filter_t', + 'cassie_sim_params', 'cassie_sim_nv', 'cassie_sim_nbody', 'cassie_sim_nq', 'cassie_sim_ngeom', + 'cassie_vis_record_frame', 'cassie_vis_init_recording', 'cassie_vis_close_recording', 'cassie_vis_window_resize', 'cassie_vis_attach_cam', + 'cassie_vis_draw_depth', 'cassie_vis_get_depth_size', 'cassie_vis_init_depth', 'cassie_vis_attach_cam', 'cassie_vis_remakeSceneCon', 'cassie_vis_full_reset', + 'cassie_sim_get_jacobian', 'cassie_sim_get_jacobian_full', 'cassie_sim_get_jacobian_full_site', 'cassie_sim_get_body_name_pos', 'cassie_sim_set_body_name_pos', + 'cassie_sim_heeltoe_forces'] + + diff --git a/bindings/pydairlib/cassie/gym_envs/libcassiemujoco.so b/bindings/pydairlib/cassie/gym_envs/libcassiemujoco.so new file mode 100755 index 0000000000000000000000000000000000000000..08a0a2c8f85114675c7ceb289e96cb99793dbff7 GIT binary patch literal 257696 zcmeFad0-S();C<)Fk-Mfm}pScR>Mqi7$!lOAr5E@uMF%NR*1id`A6oQ&V$%2^yY zwm0NN!ZuZ4##ONjp3;aTGEeZ4*ZOaxIl#D@@8k6Hq&^W>ceapcT+R0lLQwMq;=bmm z!moMp;=bM034)M%k`{Ddi@dKz-e+99r0I;S6r+%ibdDFO=lo>L;f$UN!^*64Dr%<{{I7!Q?m(NyyzGC=I ztW8;;0w^fN=sSJ%#zO^lyA8Wmv+=w<*?WC0>b*QlgYZNU$rh)|J+T^M__dr{vm|B!9GjOqSw~kAmRXShr%c zM=7?bK`9CC(JCcex2jz^KPJU`wzW=iM@5~NZYx6O23ez&JJ#6FQ`~PTwx(DmJyD4l z6^-n13EgNq?4Yx7PR5yolLY7Dbl{{aawSeWW{Hb32iLhc=i^*}^BSCV6yPkxS%mXi zoW(flD8+dl&T^a;IB&qY5GNf~;=;c-;@2hlCAik&ycy>*iQR(h3Y;r(uEI&>TZfa5 zMx1|QO8n@!tj4* z!ud~}&)|F(=LP@CoFC%+6lWLCy*NL^xgRGTpX2-jX8>mq=Rus`;Oxfv9ZovF$N3Y^9-K#T{)}^$ z<8S|Z&l_`vW7bnw6yNaLj-Nh`J-gvpbk(qtNh_|+DXhKLl~Vof>&~Ydb2q#m3LYQf zON(k6ec&H!O3zhkTt>=7_0!{>q=P+xLa? z{G&-{y!-0R8Rw@D{qs|0`(vuqKR-Qx=`EMrZ!UfO%NK3ymb`O#__Pbu^46>0EMIx{ z$&bJE+o>O=)=zyl@xf&^e`#;EMHT<}+t1ohy|CT$_1=%RxMSWMaFul?2|Zh$P_MuKs&Ubw5qqpL*5A#! z?RSUvbtf%Z{bu1UBfd_${k?a~o=Yn{t1>tKijy*bIVmG^(nEuqU9+G6ymRMAtCnB< z%I?yCK6`)k_iM-hG~#%mXGH#upC`p-)C_JL_f66#^FB|Sn($@PqEFV&jr)Ac`h)iF zwe!E+@aQ>@*AISS(+@ZO{qzz0pPPHleMP4|_2u4I@}BOF9rxM8Q!Dd7-`qK5$xGLL zlJ%R5YpweZCQTo^-QYYrUPop(=6L)F7=7riv-n^nJ!efNyZ9~-UDJ+qH6*N2SU@%XlixWC?T?Y*(5%y?|yr-xU~E1pw1cgltpPkgy&e)RVXp2_+{-lh9L zJ!ACQ3w{&z%1tdVO~2$ByEVt?wc|5>7VtP7k|I`efOgqI_iFZN6sZX z_hw)6_}~MF59Lle^TmmocBlW$tCnT2_(RvDuJ@uIUO!>w-vdW`&fDGKRkqgsm}7q^ zuW;eF!w#)DzvGnjZ|x^daV)IZ{)>0r*1C_keg0PYMfJng=$q45J^pci!{_%EUgSId z;KzG@b>WS7ow@exSv$VV{-h}Vg}76nxvsc%zweEoF1W^a^l$Iwug;wL#hGhA`_&Cw z(>FZv&ELnxeP3R(uu(7Rx!~oMO<9kvJ@T6~t!Zanx#Fy~DMzlkY~Q-`27R>tqEA+} z-9GF$!%*HYTvYTye#6%Ib>3kCggyLa{jjQwtEu|;du)zVl%f5EoRZi-K5PK|<(U5C zZ;9?7uNeS;&(eQ<>PKz;=t=EdfBIiBfc)qI^v{p#U(Un<;y*S(y1ySF{*(dieC_~t zduo9A&km5U`2*;`c7XUF4S*L6Am{nm{_TV4iVbJvQ9OX0dl9j}@_Kv#I}9Dbo^K5x z=aK>JwsC;`P9H$e_uz2->G|Ht{o~~W$lovk9ydUKsgLe2-S-E`*Qf#H%o-qHGY7zL z7@&Ly4sz3 zzvc2zRxP?}2xK=qK0Pa%%v6w<&A2by0#^5X^GOoK=q$>O5i zGeoA_CV(*#Pvdfg{AnO?(D;mwgED^SX2EBRi{i$W(ru``xG48?{YAR6N1Ow@(D4;cl4Bh%^hfdW zLE}@xJI@lhQ7#v7`9jW85pR;XD5=tJh0<b)mQ+=Msr` zQ-g-1P6k{c<@lw2E)~H_z08+e`oF9m%E{86c4-HrjlJYlseijrVMOL8e zrJO%VJ2dSP0L_i*$dvh2?i0LI%DG#n>y+sl`oAgjW!)~~|4!D&S0E=*IaMi~iwxq3 zlXBL`_?;1Um?!n@S|sF1cT_%uJhDSxnZO^Gat_J(-8BN@{l)~~{i0{E@Ozmn*dNcqNM$0&&}mGSdrxf}lWqSP}_*7w;m1Amm|)qRx^FipyN zNZKb)+6UE{j~!BujRp)j5RH$)vb=0t1pl_gFOYb51b&&6Z+lThtd;Q-WIeJzE`XWR z4wGfRtP%N&m*v$g+a<%EZPGse8-$#FQvL>syCptO;ulEy-LDJ4u-mU>ew!`>f#Wj~ ztn88TyLJnpTH?Q!<=gzB0KS&^aYOzG0?3v4^Rho`X%m1$;@#5U((e`kqVX|X+Q<2n z;2WiV%4NO^uNSzH-!(FR^FIYHi(gqN+rutt_=zHW%5un~`qES=;_rc6I_{V4IWKU5 zFJKgFda~Z-9TLD(QlA^79jqS-9L3GYW6};-JmljRaZ$3Q{`Lw1{8r+x$acejqX2G| z_%AYk`a%I1<$ev)r+TEwdL)ZSxk#p~MEK7_=|AbRf3!*YPbLUEG|Ppy)e^r_`g3zc zd-$D{(=Geo;nHqz$#S&Hay0zvkn}4%WgG{JiI0~JJ>L}k`_gc8hsbu-FL1+ub|779 zx83uEoPY>cQe?Va9svwOKTSu6w5MGlC+@^dj{m>mz-}g)X z{VPR8qd(mb`%%8SWIJZ){}&lQT{_gKGTloI`LetWzxo*ABqv?AdzLFiItOHV70P*e@ z`y26-WO+HIzrnnGL`ytR;-^WxLCWu5CjexVk3UKOu{i}_DD5^&+QIgQz=w;A@_>}@ zFA>1MB<_@Q6e-6TA5uS0c5^#~;1cLT$4Am1?6Sd_C}8EV#N85ak$9{0e89 z-;(~Hw^9I=691Fb-zm#$io}n~@^UW`z2~-7s_<6$Cb?*2u6%;51xwEDhl$2JNURSZ$Ra!l3`sB*0MWwTfuB|K;Vf}{`6xS9NlvOM$ zs;s!VRH>}EcH!v7Ril4TR7oX~W0c~e#fvLS3yQ0%OA8iPEG$@D>Z);`h`LIhO4-7q zTKrTjQWlmjTv)XPNt1%bHxv|?-%wCiR8e`teMOa(RmI9eafwW-xXO9c33rrLmzF9u zi<~T0=vJ|)z!d>i)woW;Y8IDP7ntKZO9WfwDq1u~DOwE0omEQ}T#Ks~Qyz+u{^A>} zT?)r^LZ--lA4}Qp9&#Nx2uCA(9oZ`|eu)Jz9O0>GFxODMinQlQj?k%l0 zoDHQ+j_WEl0LoDqAZ&f(lG0w6mWUIcBmGz)u8M`dVg$lP6Bftp=ps&7g%D6ljkB_% z*re2wip2#>VS=iq1=XdCsRB!(6tK9mYU#o%GvX|Q3&38Y&QP2ssP-kw5_0P4Mb$Ty zR!=QOxxk186uOY1#Y$;yh0A;w*`lP>=_*Ha5T0g9bV92y+2V3k zG+Zf=+-7lAHA8}|ah6a%%POuDyo|w-P5KwP(72Stix-;Hqr!`T*rQ-1G-4$ci>_13 z$|`FXmn%-;X(ov$0OqnHqX-!VWz|I})v~446;QKgab+p$s7VZGxi2}iBv6VPLsMm< zrm-5u$u$ck{-gDAmM$_2Dsnn2Z=(8999Fo(KC*-gs;aqyn9>gqufFcuBD2u&(8xjz z4>h?nWxu$xw5Yn*GfXK~mr~mzL(GYhHwjNNqljK~L+Q-o(nY0{(T11=mDN;Mk~_m* z5|y1!fvc+e#+p+2S7lLeuRvh~;p7KsFQ8RfMJ4(~vpn|U0m25lhvZ#fg~o6Ic>{$F zgbUY(qxTjL<)*0ERY0wZsPoiCm|c)!RM&8~j}8P4tT|KEioo-^yT*;?Aj)t5A$*fa ztUqxJukUR!jB+S1t0=83iPXD)lx!wK!Ws(_MJoLlL5unqXu1oXbYJ5eE^tvbS{IZ1 z^zT&FMI{xzEhJmE6z+|#$8=|TRb`j~L%+?(1k^=>WW&khHUTw!ipAM zS5rx?NYz5*zoxhCCXI?08v2A)almMZpk!ZL!Lf0FbyWq8;!3Ms6=C&=v)q5)ILMF} zX1?O`QVdoXmsVoDgAq%`;>ZL!yy{xi7dS%yaZqC-s`SF^7gnLwGTX;lgbpMuX{ssL zq5CaZgr4Pu%F-KZZmr1#1K+|SkZmcN^YlnJ6 zBLn)<=r<%1?3Kf*m^-+zj6??XrP6OmBp9AbS#?EmqzCrK=r54kDz0J!8T;P{R`g@t zzPqS`nZ1g%;n4m9N~+2VN{SXbY5ZfV$hfE2RUPJ>Y^DA(#Ihq*>Nmjw5+jRTUsPOm zZAHUuJTeE2`bf9H8i0SJvciu&HWeNh|{@Hk>tQR$xgl zURfm{;NWEoWws1Y$5s3DTCB9jDYqk>?h)~0P4Q!uU!l+`jE*%N|0Lxe89%9_VhFuK z^GMkJF?>JW;~GZkM=Sr3=^O9m$Yof?DW4Clm+##ec)G;9o+kgK9EiiSW&GL*JVD~_2;9)8F#@;B_)QV`P>HXL zzzuzxBk(h1{Phv|Fp0NB;D$b}5%_sBzCQxLK;qjYa6?XK1U^c}?~1@jOFR&P8*;iM z@QY>qo(Oz`#Fb~IUkmqF4Ew}K;Mp?1H3H9(cuE9r=wpk(9Ws7e1b(^1(<5+0&iDxY zDjDA%fghYL@}oxJhMc?z{AwvDKLVd8@xln)kW(Ik7s>d}2)tP0wGp^sXLkgCy^P-& zfmcerDFQd-tc$>JlJT1(@MRKTAAuYBYKg!bWc=0${C0`^BXC2`_6WRD#_x>4|0MC< z5x60zD*`v#)j$NkR?6v)zzsP)5%?oAzVckS|3516_z2vvvo!*LPR37(z+aHKEdn?6 zNsGWcWc>69e4E6_N8pAWdj$TTjIT!E|B`rK1a8R5kH9~d@e3pHFC|_cfg5t15%{IE zg?(!y@WWD$I|4W4G)CY`zL3)tfk#VxT?B5(X^y}@n4nk-yMOEl6Y4HZpaBl;2AQ06K%Z1fk9XAn1=XuCcK*fc{H2w zRR)ObdJ}H!xuf6~6F$roztx1lXTtp^`~efb-Gpy2;hiS@Zzg=V2~RiST_${@2@jZX zuLqjvf=9X@IzBnsB+b zfbVjfaBRWoJsM4TQ!lD0O(q-z{@!Dq37^)B;$2@8jx8;{$9fa~RWAy^HQ`U1@KzIU z>=~h8zX_LHQ~0j!CY(x@H0%f&4fQ?!qZInHzqvYgr}JB@h1E- z6K*%*KbUaUgr8}`^GvwIgy);^vrKrQ34hpxmz(hECfsSlhnw(P6E3%Gaj4sbpKXfY zXu{7i;Y}v|Tob;|gxgGbvkAY>gs(T@IVQZtgr8@^TTS?W6Ye+R=bP~DCj0^u-f6;9 zP55pTKEi}|nebnk@PG;bwF&Pw;UAdr9uvORge!7hPi^6MCOqDRr~Q%v|a z6K*r%WhOk$guiaW(@pq=CVadJUueSZCj4>}u9|Sogy)&?-iA7{eXoABS8@D>yP z2NT|E!sS*#4)vSx@uv9OP58woywimL(S-kp{Er3xV}buz;6E1lj|Ki?f&W^=@)#I?lJ(m}9``MJc?l0mSO`5DC1QbEwq{50Ze${%cDeiHFC)ekl^ ze=+ei#SbgAfBdZK|Aw*BA%vH!F1+V5l>U8ppE&PiKi)4(8_!@@icV`D$HL` zJWZK`-9K~r6HiN+!7k?K5>Hd4U?=l4h^MJh(9ird;%Q10Y+-&9@neZ^X8vO0X$ll< zVtx$qH1!F(nZJ;Dn(_pl%%4v@O=*IK%%4eoCh>X94<(+aHbFb{gNdgpO)#DLXyPXj zZ)5)G0`L=ww=(}7@s|*wr)x^`3J*Y5$J@Ho%-+h$JpZGlDyO^I#{FTIaGCza( z8N~aUpGN#l;#-)XMEoq`o0-3u_}RoaF+Ya*ImEk}zmWK=hyU-^7uH zXt#ZF=hG##$CZqx{Q0XzQ+{%&%W|%pB5sja#6N-tK=qCLjxHmQt6I0(_RXbgTThG{ zwN>4D+?50YuSfy$p{_E^xhO5;e(EpW6FYFPQuCYHs%PTkh^eUB=dJ`*pLqNH7$tBu ztQ080&(^pH5HD&0?hU&?xDACfm))qa_YPAIM8SYmc+Jbn{WOH@5}1l4j?%T7(n z@Q0FjAb%altO=>^S}V{kpb@#|ba!o{Qe$=34pl65PvHikZ^yCur>VYKsn(7oNo}fj zsN?YbdGV^xm73JilNf^}l2Y+AKQ%s-JPd+2(Pvx`EtI?uDraf_R_f8F)cY-U_kwUQ z8>;x6F*T>Umsyof)LFS=e9owj?yFwYJ!(!A?0IK%W|Y!#_(BJgJZ4RWbZccQy49CD zlh0H-_FU7}@y<1`)%$Bkt3KU^sG;NvDgYh1D^V{Jd9Aq`9dFva1zXBSTh6URD)|1V zuJ48bRokh3=kR&#NXwzU6-pk9n-8>=HEp5~#IfSkPe9+h{G_bqc|Y{E)X#;bgHx$M zW*#A%E3&^&LFOHlc^B@2s-QVr9Y?P6t9mQxtoj;B&yK@a54rm!XzFQCQGHF6%g~5_ zpbZgrCV5#`WzCtQZOxkPC=O=L;?mR(t1AzxP|Z}1b*c2SClzG~w`X~NiE?GAxVLG<(+5@H)MI~&Rsx59 z3Waj@ms3goO~93`ZFQ-X38GbB@`Z>LO1=rHcN|HJyArvg2&t4M99ddjY8q&`|33!B zDD7>viFK(efLsLRi-3jLZln70tQr0T$y_fy{wUS6ImOd+x}~m@Qqc!nHl3XLLCqIg z`kK_Wbl1A}wwtSNOKkw%(KGV4R2#I>)}*H6l4W^eP3pY}C<8DSfcxcG3RWy@>X?9e zC|<{rsx^EcDYb@0k+vk>@fQ?L*GwB-~_P%O)jrx23KCaXiP;Ep?YOkzuL3 zpYt=uQa6{8i!60HOpLYEEkjV&E8uX;I7?kM*pbxY>ISn9_kb}kBvyiU)v z)$g+0J_1md=VkW2XiMF3WWaDm9vR0WT+|=WF`K0>z@mO@ss9>1uAZESXX~D$C6?Pi z0qgl{jN#H+^6wFn>w7lUj?a*Uk`=VJ!HtMx$VNVt;NJ;wyHYcvf`1{>@_cq`Ittg* z9hKDxvJP#U9SVh#3-K+C;LS4n$f#fyleeUfMN3)?`lS-clkIe_{%k5WM20S*#T{f+(fEC{@dBuV zhN<-dQhYTBhAX6QYiL3s9iim+DQC^-zR3_{qTm%MbhHxLhtW#Bb{K7)95S zojLy2`(CAKRG{KJXh&lqJ^6X;zF2v58&J#YEa>amY;w+f5ZLFO#TXX^&qkaq`ZNu< z)phg{s4NufA{YZUp_UFUU|ni8_%bpQfJyF`M{yH48ExPwiW&SDcU^Umf^TB8ZatRO z$6(vwJZiRIL5Bf1mEjPdirS&}%74BtbrgU`H11~clSn)zL|qVFsgCjTuo6-T~q9M0~?KpO|I|aPCYPPp6lRZlC zpO85vwUHEYQsJRaE9?%k6Q1P`i37#t-PY1OG(iCSyF2rM;guJ4^c^ zYgU%_hA}`aH;pE;Q}byk@hm#zj33dCU_=;7E(5oTGz36np~==z@(jXYon9<4lza&= z9xF9Y9-8I(Io6fWV?`2!A!14>IT;a9))<_1963E3Lplr^5iz=^T7QPdVD&$)C`Z?d zdb|aaw|f4JyhUY%w((#Ph!XI88wwpLXtF#%)7m)M+BkFQl=`nNbqk>!jeMwgQ?f1D z0ZtObRGIDr=xZa>?Gu_23XFnSk#I94sJe%H9lO;x)((bR%cvjGP6oK0JePZJSjsfK zx)B;+ELR>jwzBgGS7bw}u}sPMkp{Z1FF>5%8ZJheWM|%xWT~eS4qJyl z@{4wk44q|Jvu%p+x@anwcv&t9q2z@~f`o3%P9;B994IbZ$G!_O6WA7;N{Cp@Vl{y~ zQZbw1A^3Ey8;Q?K#UK`u^PqGg%FN+IjE=+CbYWCZL)(r6*L1S|F&DY!HH;G5L&@LH zj8U|X{JB}4P?V+N9i)MhY&;FRs`{N|4qx^{49b6W_)1dk>NLZ~l<=3iMQhcVWQ6v~RMtp8|8g zhAdA{$hF^a*)3&#`Ri>jq_}PElr}`ZH&Z(XUl^}y390NQ4s_!24&N=Q!^2vUv<$y? zOR5bHMNO!Zv5VUZ2NM4CH=z)gL#I2mqnpmcgkAd-{p6F#h+3STI$X^R)SU0oF>%Ux zP1U}FvJNV;PXix9-(0Qzz;iM`8M_b$eCPo*2+cI%OY5zUHA7Jq$2+txBWsxH1pbbQ zz2kS0zg+F7tU0;bTUoQGYaPO9V#l;+Hz-2P% z2@0aww4RrsJLC1**nl5FS(q>Oge-L*%V2A^_9f;rs_sk)_)(VV1?p)!!nc~j9$_O{ z>hI^UTT)X3GayaXZ%MTVRHD!>B_Mu=f75yJ4cIz?Y#q4mD~c7~BNbEaDHHweEGjP)Q(jmxsqiM)IzFP9&{fg0 z3YVBDBwnHkY-VfLtYG))D}+BHZKDwWCJh~LGV~weJ6IOEj&zO>d`;Rzer%X&*^L7k z(4B;CI3bxQ!TVb?uh!c5zH>l4g$BTWKQk!+uR2eD{Upb`ok zxCgPOe~DPfrQPELvj|@q7y_v$*w6C(Nf^vDo@9CcRID6jUzii6y=A{}X;kACQQ3`C zqwS4LV;Z9yr$te@Q+=7eaXdy|s`kT7)wjf^qMh>HnnwLr;5aGmd#Mn?8_VHOs_(gc z(19-mz8#~qjd=q1gATj}97EB1E5>T7zAPRMwya#@S6xH_<<jINL|7{zloP>{7Oo zU95=Bg#?+y_`p-7h|W2*1{9H98|7VQclj4#*%kFk)lb4y%#RVk7S6xmX++S+$I)bU zi-=G5QT0nh$!|L->E-c(L7ePzYhXH?dwEJA`*SFw9a<24X@6LX1Njrm1OD_6s0TZm z?aThOR^Vp)vOlc=PWC0EM%Y)n(^#kod+COK*{&x0vRzH~CA*sJ3wJttS+6_A2d0xE z!kw&v=00N^_B|WfHo240UcFifv4K3kdE!G5hz>WD+{i?1YTyi5Etk6cz;alNC~IKf zK0#4e#?3_?H5XhT#hN7>YypYXzCptQiGf47hYA|Epy5XKwTtyr{Z$1cp3n#j5;SRN zgj=4UI>u;^sC>YW4d>(DoED?h`CUWN#MXygr>Gv5s9^QhJh(B|YcZyB;|YxW(vBW1 z&u;U&S#{;oj$?BjscEVYnMb6P$$TPROj?N?&twXb6PUCSX=k#K$ZRIdiBy?%66s*FmdHGix23wJ zMzfeB1t~0_IeNxH+BMS+{PRnu2h8+|XCP zs(wYSTK}4*?jS;DXM8=Anp{*5DlfJ8rAJVfj$#iD|5abCMb(ZvGW`~hACc9HP!BGi z%~5L1OY0FqyOUz0hk6P#aK3YdvNK;|4={Z@r>1>Kh}j9 z)9d$J>P8`Z+2Tf6Gb^*xQr`v*^t(w$<_=5!KGH|~K^1j{1{m#IZaUu|?eINJmTup7 z)A>7MFn&l#4JDteqDkOQ2sQCpFVb=jT0vO(30mjOnuX^cG{e9Yjc1)=<`zo+U@A2v zn66_8t7<_W6@`*tViY43Od>L191JNjYbCuy$-hHbzC(YQxVf+qhLJq-Ha&0AcCvx8 zwau{Iwgb^vhMSVHKTz`-8@2BS!@m$~Ct?{ZcGD3L@k#bP*=mUS8sa5>+81vG;st3& zMfRsPj_+q<#sW)fKW(DAYuRvAEe-`Xb9ERir#k7vSRAqW$v4j?s4J zYMpJtb938zY*9NM8kQ_yYddRZhw+<7E>>*$~6_q13K=$q?O9w(Da;L;7+`n;s z^1VtzLdm}Y+KO-aC>veK2i4KcZ?NF|Vs*uJ&aelf_|hHC7d%PL?5uec z$)}%ts?rfWw5xBv3OQ{o=iB42cLe`ia^{(9VPS_~dCKtP(@a>(d)rdFInjGRuIQGY#Dxxh$}P0|eG@oUKl|oC;yFPeYD&gyQ!@5A^jGZI zi=(!6MRx?Q+ST#FRr?+KbK?m@FWv3XpGpUfhJ{5Rvz|Qx%ZS~*Xl;layVB%igi=P;7Ctk%HfR%{7ii6ysqyITC6 z8ns>3SJRS>>Z{u}912pZfmVv1J<_l0S_+n7Fow_C2~S5zjxRepO7$gto8@y24ILO- z)A&V*x1&%SUbKuGmKsGQX?YHq{q9tMyB$ z0`=&UZMnjqqt!h~8FgejQoCIaRj-dn?sI)t#!k}5#!t$0#mBnRJjdc&<00O1#cn)| z8+9?Pxh2X`yeCJ0WF46$M;AhJwVlCFXzhpF1=E6pX@nxiPqMyJ(T9?k;e*yx#uJ`rL8`4Y`6G$85&$Xq=(Ly>A|r_FM+9+~4I%XPscoKa{2_o5 zqtj8bz6V7W^bN$K`t=6*dFJsD#=qZf;#Ob#oORPDz6q^V&;G7Z^6T~(NTc?j77H{F zts=t?PmakS)n?X5MyaC08ovW%=(tlU=qp}DX7x*SmK@hl-bj6BlFae`FXr4Z1QS6Ch~yW*$#GAaR;8{&d+@ z->cL;hmuc26jgskVdnUyR2;9cbah)jfpoYMc}g<=BT7o>i@gi%f9CRaPy877N7YrXxn9k9-N3F+95#o}$j zG6)rVi2jwwFK}JcS{e3~AU#Xn!^j7X2gNvrAsS}UVr~L8dt8<(ma8xez%b(*?Aw4& zXdL48XRNS;erFPXGrKMITX0(@R)s9}FOp3CB`Omv})Wo~gZ)u?u@V zxQd~ZcYP5ZzSkojbuYu8i^XtlRw`yBW5(KkyVyqcaU?JGVf}AoBbpC%h;dVKv+8>} z)s2i$i|ph`=@c{pLCo2SyTst~h_f49Vc_%kX_aaBMkIixc=*qd=iiGK=Eb7zV;_b> z8>t&`XxQ&`C@}Rs$%DbbOu-)=3|s_kiWV?QaG4~OMo5SYm*7Cuz_;&)Nu5a8$Klxf zdx5$A(XPqMW8Q^`%TEE_(~*1n==?^L`~v?o)^ zV?xQdPl!=`6XwxSaWYq%aVPJgr|XC4VJ5j>U=*4GVuWkqiel+oKO2LI1C^kuw~*^- zQ0UfoqZQVWOqK*CgV$rg8W@bM_l;+$exX|bz@E$v6_4Xzr7=P%`Be1%s&AQ!db1Jh zH;OjdPE~Z?g3yT9(UHma$e~ZI&Cc9vS?#6rFMbQnC7%1lY8WM8cC`%+qnGAOfG44E zP4sq2#!5^;GPI+~+btOzF+Gw=BZm4X5`d|1qL*f9#9$Vi=%q;;F?M2T9*3sOuF%5x zW**hU5;wm?^MIfePDc5a`rbOTSJ!MUj+BLj?33_-DOO`$P5S$#F0Ar)$*{_uV9fIm zbGp$Y-5yxnXkX3g|FJjyFk3ZC@ocO0lHr6~I4y2Z!t!_TF3w*Q()n-5Z#2uNwvsZ- z@@bYT+y5~67Yq66Qog!vYAs@tq2>Au&3|U9dI6^Cdt9{`mbwv)RWWR{8Y<^cD>pY2 zmbn|xYO&gyoq2xE0dR}cFg$as+9&GBt!mreI6QNEUiIBFq>HEKzGsJ!q`((c#jsf= zTl-9uskWeY9t!rAos@A*rh;n_L(cp@qjm3bH++Jsy23yMbzBBw{RjTui5)CZ_^Mi! zmJ;@NslJ<|)RiF~cY5!I6FGbdcfc-#a-q{S--J`hxuoH8;x*16LDGCVz2?I`uxFx| zG7FjplZjqgh<58VU)?F9DkOTTFcAYI%|vgjptCr(UovK2%SxH%yX}-74oUQO;+mVe zeeub;KGmjXZm+JuV?S$r`<9v%I|TM5@@NSp!Fjg!EeliZ>4e*DG>ifbAHM_J8LW1@ z^!vIPsyZ}W@{L>7**DRh@D5pia&43tMm5n*oI%P4OJJS5433o!7+i0q=9o6hD&>K> zG~%dQGnY;r)obQ@D>id>3M2J`1++He8~4N8eG1;U%UBb62&&5YtnY%M)#1C6v8EGmkbvquhJug%aNCm!Px1Z z6Ljfke5?BA*kA+7E9|i((jKcRfNUa-(33cbGEEjbV!fM`B9nN94SEuDU?GIULdUE! z`9#viDok-K5q1f)2PX_&VHc}cm?AL;cCm7L2%y?-^$JrYl3lFQ6iAC0VTweui@tup{o3Phda9!O8f>Tp4QeP8sWk zW*O_TZX@hLD>BLP?@lKQvNre;i0flr;`*S10PuI)#C5eDS4v@Z9^FBd*GUxOcnd-3 zY(J9l!w=zAS>6e)un!ZdFb)%GnzxaO zQ7{V=>6({{Q_mR-gD^2(^R8oJg66%S3A^T{Qq^;^HSZ%#sG4^@6Aombi9F3q&YsOQYrye~6RsClW}^_&vT+s;I}=H1RjrRIHu38&^ISJHD_n)h8MYBld} zCT`KZ9}&?&?yGspb@T?B@M_-uOgAzeVEQ(u4>C<&u6fBH^@cS}f6w$frhAyCEe4wR zXQrE(R=8*$VLF!S^-RYz{Up-~Ot&y?W%^mBlbCL0I)&+%nI6uxpJ^M@?M$aKy`AYa zrr%(C6w{qdr!)O7(_@*Y-dppIXZjf`0xrrl?FxXGGEF@{9F^$=rYo7IHU;j=bQ04prfD<)r)8S{ z@*Mn@X&cjSrvLX;ZPWaM#`hR66vEs7O@ClC!zr>EK3cWfjk~C45X~@}{JWbOS(qZ4 zV;~Ru87WPX&GOMIuL5hL8BGz5G2*PYF;bHv8)d|?%Q&LZMI3IP+xIO<5sf(zE_IS4 zo8ww^+r^^W?nzu>qlOwi7G2O;(S`b{p2Q_~qD6N@l<2OAlHF8K;-W&tD&`&+$-qZ6KLEk=-x(TN^78A0qfaJQ?H_mW? zbnXeX2I>`bZ!6=}E9l;rnWkPr_xhQpUP1S^Gflk$_Xq3*+8~`f11%?3=gvUOiPyO^ z&~g%Vb`LGbs&i+c_z@VH_sXU>PPx!7NOq!zN6O zg+Z7Y4{I>J@Zv8q?G( z=-yFGQ?HE;$(7kz#cQZ{rf!091g3djG)0q)8)^$PGk>>f#R>>otkZQ%hHvSSw_t{YX*-_wkYt|u#Y+Y=9IVDkhG%~C$9WNL5+`Gm z3=2q;3=2q?_t;6mc*&^5*d>!kj4GLYV)6td)&uh;!-*D3hNaPm2T0LEy2mM*a$;&F z<0Qr{nOb5R1v7~?Xp#(Tuud|pL9<}E@u1t*OP(4H;#(w7jRoV;khE>}wZ)=vfbxEGu4iXcPJhd6bcT1ky3gUYNKZ&!Z#1m*;<(7f*k~eg=f;Ue< z#q&mo?=ODb;P9=YyyRxS_u8fpw#DVzT}i-AIFk2gxC6`o2Mdy6yXBr`&A?LC6c^8JV84T9wGF zPDZAraIw)C;T-DKudxzI>mkdB%@G5M%f&z)Ac5(w7n&gl}1;FC{hz-?Dmz zJ0+5DS-rxS5?8t9&E!kS!z%VI%uOi{l{YY6SrHAATv-tfl3ZC44U$}0A-m!hv`)}R z(9}9X8Od0QA-6#+vHn7aCnk+T$d8CgCx%LbnDNBe1VgP8mUbj#BPLxkEMUC6$4()3 z$*9DrlF1_`Pcr$$0w# zO$kokNSNR~+tPS{bMTUv!nUjShU5D>o~ed(uI6Kd3z%pn}O7+WXoc(orE!>*2_mn=COt+Hw99E~%ce2{Hu?OQ?Zp)nF&d3?mXe)utt-AY&r z0_`c0@_TvRo^LLH(x(OK>tVfT@A^LPCtp8c_-s7VaN$io`AW6eL$mTAO*~Co9`HaI z06miLa^Ss)J6rLz`T|%aSM#g-WbAI(+WUU>@6M)Y5izX+ zg{L)1KjTCVU-Qxwo)~x<)}$pv9_KBWjExvlg`%Mw!gy6O>BNw36f&NeM#IBy6K!Tqdy#Adb8W zS;qYbHi`D~3~ULHcj&8x4y#xPUE_B)^*hv9+JjeXarjhh20xyw9i?Z>p5y1(Eq8Ct z9l0adbM%}n%iWvRk^jm*?|rnc6tL~Q;|}d@b>!OypF48rdB<}-M>x=4cidH~`fjwS z*lr6+OY*TVEUsw_ZD~y#vJO|gx{|v&8c#3rH5=qO9#)I91Au!C1Ak_&=A_c*#^p+) zX3#syDiyjt%`~6GeM1zw5BJj*4?sy6H<Z4kbV(gj=jDiJB45V6XgKqNd@?IcYL<; z0<;;m9?nNE9j0e|ec*R!zq2!sx+?VKjx%BuypUe^IYa}p)X}m9?d;F|2irXdenK)*}wIxCa+Yoh}oflTK#p2$BYdxhd_ObWYrEO584ux%wGwPo<4) z<$VpZ6Qy5k+I~d&I;Ugr{0OPNIYNNUQScH-!+wIBtYzsPA4J~Jr$+A`_TUA$BQUKc za{rRtw&aZTB~|+(;P@w0F22+D=@6xLJF-r1;9y@bedVbqZ6{Oql}9N=wOqd0r$*ru z9XFx;4FAP=r0$(3u_qk^lDc=E1)<^_2=%*e{X)}8DBwE@HOJp_5WChX{+91SsMtJR z@2B{wBEHUOxEW7}8J+XCgv&heMqt5)un}chlLIeTVlcYDD=SppgNph&RWA81Hg+x0 z3l>>3*dQwpcA+86*6$i-$OTlgl0O+*R+RQlTXr zN{^x^VGMS}I!~ou^|Jh^j$iWI&^YmM6+yndSdTvrTPM-H_>xdSyp^mC-Z;4&tr|@O z(KhB!c7j1+F2%mlWZI=m8$A;ztL(ve2_AlIgQB$C&f$B8_Hy96Q8J>$u`98jz8I(a z?i$XQ=TdM9B~L>%+L4-zS0)|WUTo?n97Yx|wurY^a`AqPe60mr;z^*mA7Pgmxl^ds&8(b#>NU*KqeT`fSfQ7)sUeA`!gT@za0~ zcXuxvsTeUXI3dQ1NFiIFoH_-Y4o8#b89!!(9QqLL6nr0RmP3zg1_7a*S=}dc=|JMw z6u6gNghbzl_q&&kQ7rZEqYd0zPv6x8K>GYb6{B@H!Kg&gfC6rh{louqMw5_l82bNGCI5~sjjRo`*7MKC?lsmlkj!#UW6KRuq5+4jPGPd|MydyMMmT@R~KG;z5<@iWSl;Ckl33NR! z_7hs3kNY?guPt;((e~;!o8vocoPF@=Tkq5x2!Rkzz87fgN_6FL!}fH>(GwF z`7~C;i8k+8VpOiDJ!(qkXO`Q^0dp%p662EP*c^-|hsP_~`ncn#lHc|}NYN7-v-RN^ zq_iPY=1$8Re^%x@^x2i{lY6qT(psmHdYPZNV)3HtpYchU%$-@5yS7gCxqgr8SeaUw zZF#;YTibzG??TBw$jH^F(BKZcFYy@^d<}`mGI9t}%HcKfxy5gH?7Zr0eb#O1s@_me zA3cfr3&r#$&44qbawm1-=Q3o|T8sgVHM=vuDLS-d+@W*z&k-qZ2gRX^fGhOfbhuOr5{9fz;{z~bGD z(8<2oOFP=G3bnUQzHn=HR1bvDg8IdsSULdhNLA61w0(vzMqZtrnupDfG5C7TN2*Va zw=}3coWWNEs4PU;9aW=x)Tkr>rtGNPR*SoZU-h;tHA^r-B~LUBiFlnTYZLkwe6|cp zqV!AfeGK}5qYc0F@u`R3qisX}8OFC90b2nFqi_pG@#y^!i{h3b?qCs@0o;)iJOY`4 zv5$#%faXX4v+?#ueAXuyuLZ{U4YpUnbBw|E7_ons#@nTO@@z!@FUQ-Hace*0?Fp#^ zxpD7Udnk*pS$o1*`&)EhxjGGdjPdP>1MLpP!4UT?y7UdSKSe==4Yb#?DCG6O7-f%u z(fjtt^LTqgDv!0x`EE=DdKHNnXkRL{NXG?VXq1VE542_4eZ$+{A%5>D`xSP}uu=BX zh*5T*eqrP7$c*(4ovpzv2&H}^e7t>vHobS)gTErT`uLHE@hAJ&EPPyX-6Qxz!}Q_+ zHKlR{o`nA%)?>VuZ6_J@+U4yJZ&CffQheX(NZ=#(E!+ITYV4<+A%7@{Y@cc@OL z*kK@2d)Z#8-%ZU^VomSl+^X^-m;4JH+~7p2RZ$h%qgXPD05S zNtF-9{w|D6Y}ET; zAsFdX=fg_;5>LK+dA$DTM)W51hGR0uZ}>(Q^&3~B-@rGU;y2OSNUnYfR#WU~N+;<_ zX?PDBcfNQ!0`M)9nGe%TAzKeWYPs7#oW46y-X~LhQ17Va_LsTltsD;t+1jzoeWPB% z%@7vbiq7~0RbNT6jiiu9Ybg0DN+VgM@!?;?)3DSRp(5n!gR-?RD7CgP;v6WG6t(zA z%ZB_|Re!M&@^XDi-MKzjw@oeHBeXuD7L3#QXsacPXdi+VCghL$meA@J1@IU0xh169kCV`(t?}a$v@~;^=_&3OBaT22M<7S6t$vO(C569N%5nsPIGqS0IgMQ$ zrzXYS%?Q#G2;xWtuN|&j2LtiAK$O1tu48U-I~7?Lx*RmVs$oEd0*-7dA*}h zy!t;D->YguPY_EB)v?i743AeQDzIhER|g(4=9}b?C(a4+F|A+lRys`t55qH^9lun? z4gF`>8(v}>$aSUTms{(d)YTwX0%C!m(!_JCOYj|Cn(AOCtxt`$Y@n*^i|w!=*R;kl zLg|Lyw7B+JH+_dXvmIZrUU`uIn7Hb>EwzW^Wwzr*53O@V2%I{y9j``N>feC?8g8I* zph~YdSz)SB@~d%_+!VNcO^b@v3!jhF!l$76>bs8T8EvtcgS#yowyEoKeX;E*kXk!_ zu)x-Kx>^XT+=ic4DhaqjbyG*%P`8--Ctlx-kivAp)BK>;HHkQry1_Ix3+CDuFyj$r zZYO?bbm8Y_x0?BFjVEjhQ8OGR)+J{SV%DH~9I-u0@O&s8c=$n{AM~~t#^=(0rcW_& zD`9FWr|hOVIo{RXhwo&^k`X4P_8B}$8oX0o`I)fzJF2G(7XMJqe78S~zgu%4%-mz( zG`Z9*A_02U#<2GloD^Pf)B?G_=M)-8+>6F4E7jnhL^pkt1PIm^ zdlDP1f|+3h(_|COTr%ytbirI}2h(g9%=LL-*5?VPx)4lDp?BY`KwXA3cYkOVK_6yi#PP<>180R+{YKi3UIa;`I&s!nt^N zXflnY!=sscBe6fDUwu5RfuYZWK7G>v@91+ls@Edxxa;q;$XTdw{ad7r+CK$0`k&c@ zmV;C*jq$=58bU6tl?Rb=6w1>06Dr=swHs&!zkwbgz)@=H1@Kp-L)K#HeB^RBxg=n$ zq^nx3joQRevJF`ht>fOl%6dZUh{qz-I&L4hbzJ$GXdB;EF+ivvi~$0*jr0cdNz>8! zdiM9^wtW+0ZYb9(FsAQ0s!dpVp^jzL56B!@>M0dqAo)J(yQh%zFrex!{B*=uUqC)T zvKwDyJjc>7kLvZ2G#^*XZ|4u9H8G}-S?jrW9-GfEyNC$Ktas((ZY08i)KYicaP8bc~i8Z}r@9Fcmqum%;+KitCEtt;j#iVRE zn3^WMaY?Ho>i|I1E*hjxco!kd{T+MqkF~eW%ir7HR-BJH_0^pnTdw{AvX{4X?78}L zNWtXs>W}d{@l#x2Tjn39^=nsqTF2}2_jkN>^|y#S-QTgyI%Pc+UuMJP(oYaPE3w!P zZcoP_=Whj4vmMA}u8`@t7t_?lvpSX~q5|RvSxTIlMnBXsEW#7cs)ghei_*f|54@B} zeFA^=egSQH5tchV|5VV@dWLBeMc9G)b5Kl)GLY>p>>Ip~Mg<;661tQFv>uapk64fC zx4z$ZoW^gT@n zLX^J#SoUw+9*R{JdVg5M%F4B76~+mjF;$(c8j$2dFf02H)KSXb$8@%Kautzmd~_ZN&;t5bsiQs%ph+LWeUb{h?1F zeVMR+hfw3$Qz`uewmy4PMWeKLEF00Aw(CN*m=;cAcih}n^GSI6H6MiY(DH=-gX{x^ z-F^C=6ruk~x>Y+}&x_UO#OitR+8mgZ9<*t567VffZH`s9r(okaZZe)9zDJ(~!J{=} zW{8duQ?gfoCKI0~o*=>r@Y!6lHkTJaKV**>;Y74>`<B&O~s&j z8a8}JY7HAf7}-1x>&cW7NqAd{X&(zkpnWV9r*9ui z-}jd2LBOSKqEPZ<^htgFG^%ZVR`JDd?t5N~aRix4>_0*M@87-!LXOG4_WtZ^MYMls zU%K&sjeVyc4Yw~_CDOhG{u}#-@aH3h|Kj^cTvBSdeNkBzJpV?taQmL5*QWTActXz4 z7xhNE(KiYHdlUSZw|FhdCf~iZ?W<_a1@K)uIsT6HU*0j39cAq6>a6*gJP?sZd!ucZ z`>0I*hY<+vqdHpimB=54L;UTVUjO^G$QLpt{Eu@LX&(Z6?L+PTJ4PL+r!ri>KkXs= z%*GhX8e>?3k)!A8yhZM95Mf*7?8^V2_Q#!2zEkmcbKtkV?@Gx;9oQ@jcVMVv%yke{+$No)YBJUyYdFtm=#LsAx8xP&{ymGVp(> zd-wP#tE+7|Ako;OnNYCNik<49L6HUzZLFr9Xn=_ZO%=>cjF^hXXpzJkFo@z~~%3FVBXw>Aq zOLp9SA}l}6yCm|fTd;h@heE8+;8Qd$$k`X%DfcdJEQ=lo7gYzRHsy`jkv9U*FidU9 z!;6d~wqe9K|7kdfwx7&L!VjPA*O}u@81ZZWjguH0Kx~C2EjPju>ZonBkJ=%9s7q(9 znZM`YZ_FHJC+8@qSY|&o#s~jaUihsUR$k8Q|Az8%hNRv9#pUJBPi*DI3&($7Ud|Me z{{!V^Z@^w&cEk1mZFw0{cT9OPdvno!JQV--Vxb~?1n&R+x0dA#TuaSW3e@==oIKE` z<=XtvByC<2&C1Z4#jgKZbMO!fEN&l^oe4+BHQ);Bt4O!<`{B-slVtAOB}Rj#M=L$48A!q65h( zuwy%rI^VC~M?b%h_VZ3WwqbYkOoqB;d}h`u7QsslFwvjHbWObfDCeh!`1SmhJb)0N zKf?!$6UamQ^#KHl4>#j|A&G!DL-EzZSkP8p@IWYNT;GzljJhb22w!(i}BR=o8gkmr=o?wV7{YYYo+7dUabg7cBAc|NHu9Azz`wo^!0v&xo&tKKQX; zK2xn;G?r*ixA3ThEu69-8mcSdte{oX!ns#VmPI|Gx+W#^Wlj*QIE5an>s4Zt5U2V< z!O8Rzfzh&@hYWCDeFO50}6V$?cGAEsZa!; z@VXxI%ASLoGEmWAw%iB9TL?tJ)lIs!gg9& z9dP`5Jv@QCA(IJZwRbVJ!Oc96=Lv3Pu|-tk>kPkc19QIB9Hlytxx#=j@vS>-dGO5f z6ZZtyCgEmf=n9jLU0eu253M2bG|zeugnlJ(9RRK*1}1h--%7|24Z)D{tugRLUYK2z zLXLr%$tkOGRp6W@kP6n&U(&u2kAd!LVBcQcY16E(s zMrVLGty*|H|8RwGR7T#CNJ{>3?F=J!mt`VmSET1H`Kln&SNJL(6qPthfcc^SK6FhO z(*V8uynC>mG5(Z#`2L4Qj*BuP`(}@Kz=fbOLgc>81#KD$ln4gl%HZi4U|>2^D!&Z< zr5dIbU86D>9~VPCIC~p*(7hSi!zB>kwrKgU5!ufRcScM7unaoRU%nDt2qE^!ZD3Ku z+7MoPqh36$mPoH2gfw~~WKDVvOQ+UvPLr#UCVd}5k(n2OC<`&R!SFe_$l=8sn&9l* zx9iN%8dz}q*y8pUp>&*Cvz`*KFWE1gZ6Rg;^!zG}|c z$34MDmIaKNMuB1U>sJRS?ZX>*FM>|Rk-j*+*2#6Yg)iB7$J=Lgu~oE!9hk!!j8r~WcL?~2f6M{`H) z%C)LK&KQn~#KWP{SHXIDXf&D|P$#}{MQF4ai~sx1 z#Zr+E^Zc`uTbAkhs;Q2=B}cxMTEh~E+w7UrCj0V2tGY03o5IR*@$bN%9~!^3R`TWi z-@=Jy#blbnHOyZyWiNwk$sls^Iz%uZJNc0zk{7r?KR?*q58bklAaBm7XLGFgW&}qa zVIFQr#hx^JD|0bt_lKQ1bIyIGv*T{x&d!`0@QmT$qz;5T3?5$xesJ(%VDhzCmvmg| zNPRe*lRC8ngfXcPcfh*y2VIeclb<(^>aNOj$((NZuy^dV$l#bRZpGTk%}w9p4yr31 zBSaYz=4DvUMf-y7MmtEnnaiJ7rbjOHy@bO=S&@f)+d(agf_g_ces1oGd=Ja8iyYVX z!&TJZnR6D_bPsu-hwIu{`Tg5Bj&*l>^yXYP(qt?5JB6<`$mqA`vNySV~e_1!m_{|`99}?|WK?qH?|@s<>Y@lqXC|7y2$gQp zq~57D`xoOybOERAId}s5ClJGR|9Qa$yf+*@2HHS7I_@DjaxQs$K6c~S28O9MSo`Ah z>Flfg+o=T1bC@Ef4?s$p+Q2fEm~UXYvfi9(eK;eS`xQ&%=^ zHw)MpWU9S@T2PJAxs%iF|Nn1vFRdHi=stu9pwVUO_thT8sOk=M zuZQ|;9DnGz^b3#mI!?+LVgt@s*ks7+ic1xSpYiAdkz0;Gz<%xMlzTbe#><{OUlRS! zLbmGFF0u@bDNaIFqb3|b$-$BGPwyGF-5KTN8~isToi=`^gAX`uLx^hEdJr+x!SRX; z6N){Ej=pxuBRcn^so+3I=8Zm$Ziash6vc)Dbut1)?KhZEdBGK5-;?ne-dXq=CVBAa z+yiJC37YGII+Uakz-NHi*mx6?N+1LB2ii3V#$NP~i zY4VmJ zX!<~6EKME~gj*j-jHT%df``lXfy7vvz94wGTpmb-d^2w;kQjdc)-h3byhDPC@*D;! zXrjDP<8P1hg_^EXUhv9}_0^U#DrPLpAd2VcJi)A^;~qmk=+kx=AldY3yEXIGmLC1O z5}x2CTFiUkypc2dQ|2Fr>WK&J66-xUI-f{it_R@aiD7QHV>s>}HRO)Z53*k6hnibZ z^-P)0kT2r!9ddG96q`4;zG-f#K{=oK?ck`OsUz zy^bPJjP(-qAfvPHHvLAHuUS)G<&)_jnE5(6e(>POZcY*4RgKe@44baQED8X&N%y%b zcrc;N(>5dDd1v`8x6b7mpMt-2VYGw2c03-1LRS*?!LPqYK}55~)WP-VFTa6Qu#*49 zh+$T}x&!5eyT!l8Cls4pJa|6W%{c0`VNi!Tp>aEY1sIrz7{b<#(HmaV87QCYa#Q?0 zet`$dadHj-$~)}0xVVED`vlXx{Bb++Bm1?>+|n1kuV-YEm3#o0Jpw+kocCwk#|8i`Pv|PL>dAZY4ei*rH5w=+=HLUhxx!UCF`Z zq;Ay235nzmWfv|+FoG%3EhxoP@#exNFztB-OfDPKZ|_&8-y5dif@vd|@Tt^n3ym9r zFrt;hiz_wCBrk@5Z#k9OeZ12sn_>7aM9L;1`6d{?)0FS0=XZv*x*xnsz3V^q;k^y>!Mfx3Tk&G zAAAi?{2_PVhLuc?=mm=H7{b~T*eQxV8pk+$s_iX~SMP=L8900WJzUFkblhJk6wF>m zV@GlaJ;vYm6pyJfTWg0p>0KCWk^o*`LqDXXBiC zY~A>*_eq=&31xpo>VtQJYHgDSW`@$=0DbcaRDtMN<@7Q8gI5u8h#i2LT3x`2Og3lJIXhvLs>UDU3+qF2KR;yNHD@J_jUl-T+s0o+5>c ze2>gGC@EJ-rz-OqCqK;%tDwhoh-No0#6>xao)K%`lb<-=qgM1qP`DsrOw^C?0ay-SfIMMf&}B9THx z+=?8%Qxa?|wPh=Ewj%#jBtYaWMMf*~u_EtM+lh+&1Fa;If3G6>l=+PL7R>HZq(_nG zDI?`0n7vt%*A!V#hfqXsGf1dZTdLS;eUs%K%BAi}HIa&@_2aeMZS~_eR2HotHB`nbmXG@g z5t6H^wM;#_T|JtnLHH$H(W@1?Mv+St@e#R5k&6|XtjKgCrz!G1MVyLcGZB&$8KKA+ zMJ^?BfK5#>`@@$dd5%{kjmV3Nyrjs$TrgP4AJU)yrO00t`ACuTDYHhA-zoC8A`ih8 zU989hitJLPkH{^G+^R^2B5x46Qjx0^X;I`(BAJRzQDmJWMC4D3{8^FhiqsIPSL8Q}JgdkYA`29` zN0Fx#`5dlju_8Ar@&_Q%JSAPJq(_wbZL0a9BAJRjq{#C`#wl`&B6W&57{x(6`i25< zn1&E>)z9AvjNwNs9bPk&Q&s6d9w)4;6Wa+Wv*c326{} zUee$kMZ}+X6nR&X@rp=%wkgu7$afUkPHlfwQe+fEutJe~MZUa43flXWnXkwK zMLtx7=^MQP2*y3hbLL}RUdDCF9!T&x#R~Lwh6ZaMYo)6Ul=yh9TKYmBtJ+lpYV^@t z*#Q4*XyAtVZu%zOl%G-~o8cd#|HF~jRQQI0%h|WW7(RH557)5Z&&4VP?buP)&bk9#=lU@+~Kyj@p=xR&r;Y z?@{IRDqqDA-_^pmGS1hee3{Dk^C7;og|8yc*Qk6c%6HKa-`C)aXI76v&kweuPy2nO zhZ&Y-cU2&rFudz6#T@C&>QD5#+nC>pq1$`NNx2C$`TY)Za}XCM|G9?$3Ixd75&amR zdV*eO-&)Y&*)!lCHcb3wxq5atg+DnYOe?@-^Xsjf<37wLQn9dqkqSA<+rC`(fzY<&^;Dn zGhG=JV8D|oe-R$?t4dqu;=^@R>hy3yi+>|HPdJH6tLUU9ix!HzQ941XmbXJmq!LWV zsNq$k%w7FSY7K6P!=)7ADLXe;W8MdKazQCx*yG0YqvL*y8#?na^3vPQcJMJ$UaNL= z+(d+b1_0i!Hs$EialZf~W{aXemTQ>5xd~MO&6rcTFBLVQLhpgTZ`Kc1J-PuN+RiUx6qKJrU``^!WkOsT!9d{1GcsfImPpgY6K}k7ge|dhm((d;f{_d!3As_eE)SeVjB4>BboIO#e2KI0F(5%zQS?RjlV*ZMsCocazq>V zZ+C9H|5Qw5L2`s>LW!<+T?;s;jjU*O=G}=Iu)os5QdsTcymQXq=%zO*@FwS3ddlVD zWiA$W=NDo-zYL~DP-mIVD|UIPl4x6F+*I{>IB+zrNBGYP36 zyz7;BH+V^BbWj!Ncv?i2R$yGYCY%TZZoA7 zkVflDSAE=yrU5#r?HN}I#MKAhpKBBahOAv;m2~xk6*AAcnkXZrFiBGpmtI3!=1PJu zAT4t_83y5UD`};x#E@3H{ID^txUr8xe#CVpY|0)>2yzNrX;leZ8*GveJ+R~lvx~MN zQzd>W)MZovn~D~$`fX$Zo7nQ?!@opF>q~pTitk&S*Q?{5E6js)GQ0wF&YUDKiRKow z(xO$_ji?^e&uRfl`&qB!(=Gk183;Q2S?|CzG^d+yfWamiWygHh;gV_b|GJ;m0ongy zKWjD`Nh`Sv;gNpUWylQldwCBr0&xWbVftA=623s3??=j)u6$>c4^Zigd21$|S{ zTe)}vIFF9=fR6OevqrfN{=lr)V@EG`>2SBmxj-e)49n4RnULalG9|kC#`v0>t0=za zw$z8uH>%?pB=_G=N3`+Lk<~Z3F$LQgQ5NDjT-7c=cu4pG^EN2!L_%*e^oh(jGKLKy zi;PQlWC^j?5U+@Hv2CKdYvTkb35-b@Vq)9$+<`>N3*xTfXdwd+TY5BvVo94bdgumr z)zBWI#M@?XWmzF~YcEz1ZFdU=lb_pkO!w(KrHoBVbP+V-JI4E|TF|JiB%cdmj(0|{ z!dHxZ*MaXKu9Zsu)v=m>ZaAipgG&(w$Lc6F9I51J0LNrG}LTD~6jS<-V^xoI@Jg z5)=i)(FuFo(N4#|$Lyr-H~~3?EJ~ZsTT7<%T9E0uB_wS+?}nJ}!SmQ&s>Xt=8zpfj z4yj?*e(1j5Jd3x<;y$3ibK~@j=9VUGPez@yeXY44dCAXkS{9qLt(vldqem;Rq3`tL z8~sh)^y_oc@@eQwt?6D6CV>EJ5v-HdS`2HZT4$r*c^)okb)uJotwi_^I@&YPaG`kv zf(s8~6F0ORLG9o+)59z&>k~{_AbNGo#3Ey1g1aEu^t?qIg1=2w~>v;k$^!q z@S8)H<|HHBOBN7XQJwHnL7e?6+}dS?Ym!ihBuHf{Q?ovfIDs(GVMAyQ8;+(phud(p z#W{Kn$C@|?du0qjdz&JyEkK~OrasQ$kNeLrAdx^EX)>}6S?W!VKaPYA(pY7XsyNbX zkeW7wQ~+U%G3P=H5BavSiyZJxlwYO z6nP8wP>b3-u$eH_P5Yv>)?S!MzA>M}(Hs@xn0>Hs=vRjJ7)|6+5{fnG4Jl%dc?0%F zhuYtPy(S%YD%t@@sD#B5j+Y?WSjNIWn6{xp%rPG^5>;yd8q6EKv@c3)FMx>%c#Vf1 zlF`E`LsN=PmR~@u*{x!@>Lx9e347=J3!S(R=kA`A&YKsW)kkL-SVI>1KEL}-)a;4P zO{_fcFFb1(f0Uc4;Z*sv!c3+T)+b!oQ$h1^dGd+y6e^uDRZhK~TNj@73RUz9jVgNM zDmptx-2I+-mNck}cs(=~y^aQxlJ9}Pv7h|^uJw&!S{rzAFDbloEBQ&vC$zf>8Ep*( zbR@J!rGGvYlU6wT)WoB7Nhk;=x7KZtF_s0*ZQG`j7bje=6<8K$Al3f<}4T$ z6)@Qm)>jy^Uhu&Txiv51nI`FqsP3iKo@hh~RUBMp^E2q@S$Jji~ds+Xe86y1CG9!932UiCJYm`LrRitczoRN3=XHdF#K zjWQIg^5l6`)_3y5HksmzpBsMsr!C5`2;x!aT^)l5Hj@<*^RFh;k9Cc-=( z-cZo+-n{UvBat`nemg~#RZVPfqB4*Zh4-xesti~?l`O1iXVLw%Gw0p|qS{Z1j)fJG zPa}s9gkke-@5~wDJJOkxR`>~=-UxqoP|%6^s319To0Oqf45J@T&{;x;_y-bn=J60c zmY_3xOu$C?7%26Y37sJ0QYu4cx+Tb8CCE&H1i8J5nWPfM*|+}!nRNI-O^Fh*0UN23 z$%gFS1MU4x2Z=b?O`Ji_WF8L178I!ypqO}q;-)@OObkI`F(t*s?cM`}kwlE{J#ZKf z6OVfj48UPRfA4`Ka10M~qy%9esE{xZ8LHZgMqru5!HCZ;0fWAUDgp!!F9e4R&jN?ZPK9C^| zH?$r}OqKn z?t3NfZh{K9Uyi%Ohy~m)#obbsKKH#S?tu!43UdctKg1_8P(1#8hIgQ1t1Zt4GF}@B zID{DRgph_FRE9o5)hK|nBM=#*I8mboBBK>2YTPJpBWeVZ z$Q97ZxIwgd!Y^iPJ#s)N^P>}p_a(f+(#6_UV5r;Tgs>rOjT3qep(9S{HiU4TPy#|^ zz_%mru2=W=xVwes|Br`P}K!*}RFO(yLF>T?r(#y2YD zmmZ;`wSw*ep9YnmR_Pt4d2!Ok(JY-meAG*nxxr0lG-d_rZj{~|K8h7|r+GhvXYJkO z>F|95`SwiO)4ZQX1~JT0`zMj#;9Ly9Ryb25-A|O!d7zM29` z;B)F^kN|#!qd{m$AjXa=DIemHO&2ZO@w@=e*xX(GGOyJqWj9^8P9GnoLtY#zT7=v7 zpY`Irg7;mVHhc&FZ{h!K+`vD6J<=V0(Z(jm;vwI=;MoQYypHitGEX4q`t@O_s3OJrHWIK&KtYyEvPhZ{h5cBUB~h z2S<$zO%^#C0@AH_gzD97U8ANBPzD{%>(#xXMa{-Gm59`H^Z7x}g?`xOG;_Feo2&9hLc z9`zmU?D)k@)GA+NH$$_n_$#E``D@9r&-W(E{Xan)q)#~6Cz{R!@M%ISOsNZtF&y=s zUlo@c^d;X%`w}#S7or;3q;n!cRP5{6y*2)}Km*EN@ec9u(&BA)_QJ>Ig#z zTFheHJDVo_dAMo1+9>!Qh|RrZ#HnjEYz_Ui4`gg(BbTJrOnTvP%a;%Q4Vk1bLh+?p zHLC^A`3H&l*4Fq80`+@n?rp^t0y5s z>&8%~*75Ky!`inW7S3mOcI1rh=*+ofEKbpCS;5>@2Z^bfVS}U7QYG6})@9{Vvj|oZ~!7XFO#gr%4a%9dE z7h#(-0dCAern%h=L=0SbL#i9HQ?bPJRYn5?f@4JvYV9~Blp^hqqrHdfzRGB(FAQ8% z+6BY{X8d%ynan~;wis#7%F&xJO-QvEx6HhmGwEht3sYcoHKOeWl!jCVxj&iNh1lr~ z);lx9poiiy?k67#01{;;zn1M@5>B1T38NZ^e*T&{QjiO$T7k~&vEhz zslR>#6MMtHd#7MGGGe;HL1pO7@FY7=2+EBNJV}3Qa{)-mwT$GqW+7|PcX5M&l2k)p zgjTOp{(E6R>~cB}p;i+KoGGzOYs3mMW4S?MyKpjkA8Da7(grg0Tl)!K+xu$bta|*& zZ3pl`?)1l#Js*JSH3;0Oy+RgAF>=~*>j&Rc}9Mi&JbMp4ox=QRnh3)0k+IuMnnI0pPX=HjOu^lt~ zDsW*!;1VOiiAQ>pWdx!|AfN*OK+x2O7)9ZOPEI;%BxR9${YIc(1^zQ3u*nGY8y`Hz zhnNvqqXK0Kfdxh&W(1g-%%3EhiySkWRN(swfs2hml4_J&HYmX3=@eM60Xc7J4%d)?Us46!-QX709`@7e zF_wR^83w;IU77gBNdx@e=PKbg7zdhcmg|~+Hesd_!QrDphj_~+{dBUR4~tDPyiU5N z4V>I=bGmH0885$QaE&?N<;K!9mV;$I+Yc#Nu#T>lM_f&6c~bTUsKP8N3{zq1rov*S zc}VM0+Vt5<^ODAxf$yForInG^qqGOS620R+q3a41ts>eB6adyVapAh_G$Pfm0D?g< zs^ERDkxJ*T2hy1m5UO;IQu=yBkAbd~Hc-%8yn9R@maV?!30+YFSL&~MCKK~`S0Du3 zLG-QEO;?nN@27c&A71}1i&^X*o?k~f_@?vgIZL+U>9Yc!WWNf^#C3>AhUE5Y!NG8}Ih{D#4uV0ca$KDb(AQEwPL35JK2p;H(f*)yT3vtwW} zCZDeGPWNaq?opm5!;@)vFntJ~0_C|5JZ$YU=>vN!_#QRUzHnkV`lFvn+Q<}Q9F%lM zgB?9p!B$BhBgs@o#%zxsxkMy4NZJ^XDGV?YeNVw=Nf!e$bpdupw<_2uX<|UhV|+cM z%?j#-xB;1}klY##5Hv(d$&P_}+oQj-Q6>36jYNw{#g{{(YGewiXyL@J=+6MgyCp~t zuXs?dB@A6GCz8i>RR+qX+^~;=d*jQ^vKNmt!oe^Q$)rP+vn$h=`7hkZCarH>#sD>4 zcvFAh8L;ttkCwL=k%^_&tz~cK(AFc#k1>F31yiO2R!++&f}% z{6ulr!X5d`O<(ri4~wby;$C}$}0`-hI>Vz8?;`HPuIgpyNVycOU?ExBnRT&yI0_jjXiuw;$uaFX5K(UjirERDQj* zb-h+>qd}V~wv%DIUThB7_({N~QrL>bHWs#Gv7G|jY_X-oX4>e!LdolDCKnF^&*`2K znpBAI%`9)}gNGN4Os(F9D|cX>KXS1H_jBVK^2KlUwS&g_6>Myc44#XBZ*s+zY;?TI zWnva5H_;p@tjT0&e{fQ`CcHS87w&~-CXLL;o{EXxo>0Z?xUH&$t?=oWkk|CC6a8TA zvd8=8Ihz-7Tt3yB@9q1M1jDW2&I^q$Ox^Tz273{LedebU?0ZKpPBX#Y(|0mxS`SRP zG5eE#m4>?|PtEl-QA= zZ4o12<#_vk^9kY`yXW91jQom=893C&q4SelN{}gi(|#N;FZj&j6_&IUVB+N!Z1r%^ z=A_L@8;3p9Gih_v=BBNHwgNrh-*>}BP?dNduRfLG{6p`RUIM-j<#pEO$f>6vGlLvmB5ZP07n>RAB zI3Ev~Zz^|+%}dp`9V@uULP}U}>ZY4AbFEuk9@q-qxz=N{@e+<}3LuEL@#MEyLN&0s z*fkdJV(hZwO<+8To|$j)gm}zsw#v7jl)e_YZgHi{?=4U^y(F@`sJtxlLeV`{@UbGY zt!RsMfesa|kS@=`qSXu#SU34$A};F~ODLG@Iz4sM3ijW`QI@)Cb(1t#r*TWfireaNOr|Ii_b{icm(fpjfT}3n4O)v@x8#+d8r#;vZnnY*XmKw;SS9EJ{Zo< z4a}a98@T>FYuY)vR=0viG61C$MDJ$P;?`7&g`6#um6CxiKy(+Xx zIaYY-^z+1i0ih|7x#q&ujW=b%GX0XsKZcq{1eR%K@b;%mr)M)XKVxX7QvFp7h%a9lIag*bg(8i zOP3UU6&&U2D_(eP3bs3&a)S?4v2m+FGq>8$cn>)0m<%ZKjiaE46GC-NH;h4x!a!Fr zRftZ4cHW=1qRXH=&EyfAuOky{3K)uo<+?)$ZH{SX8jtWZ2|e8GPCeQ`E$^YvJy0b+ zMyWH`nu=+YqHwO&u07nv4M|iwu(;tOMvbjGf*oUk@Ss);ftYAt+;ABg1{|xot&}fo zuI3hZ#^F`4>US*Qt}w0BI};M)+U z9cyzkt-;S1TJ#o(pw0dheH&OD`a+`{lD@QIX)~BksxA)YGARreCU!V2oT+q zL&G&x0>d}%;V1hfK)JyUG(-xcQB(&eT`OmGaBbKloYlZqo)S27tqqUS2?ae=a9q(A zZkfi{g*&2;^}hGtyl;+sAGLWO4{bka!A1$mG4Y7m6k&K`k7APXSHzGVDR4^;q{G5e zvD0d7VUQOtZvPlbirs9_z!|I&0T5+m#M;fsxFLkATDhP{fhYv5n&;rcCzFSxNX%#L z5CLRhH?UHx<_snuV9iZz^OQtTPS&7GCBK=P_7Z`j|-70Y(O_a z7P&E|Sbbq<>H-sea2W71qbX)*>Nc9P40yy2_89OY19IL!Q8juEm}$UKb}(wdNe1NP ze?l^5zzhS9wu4Dng<`RC8IUvd2}vF_Bj^OkM9Vbpv34ehA)anDaK#{@Asrx7>|~QD z>4xcaJCif6)__hsm|;MN0bO=5%YdT|m|+Lq223&FBs=Ia;3xxT+Q9+?CK>P|JLomw z5lql9akA`Si2-8ke0kDV!C6h#e~ZwKoQxZi*Uc5saWdkr|#4mKI^Z3BAk;Cci07_it5wi)m>1D4pq zumQUbc#9qEGT@5_EVF~%2JAB6Tszofz)k~J*uh={h7DM02crgj&VW^Ru-|}f2E5M> z#tit30sVF`iHkERJS_&Swu3whN$^Pn2JE22fa?vo%nqg-@G*cWc05SL#_dc)t_N?P zwG{}@9OZSq?_h(Kg5pCio;AwHMd7UIv|3j?@;df8F@`S74Tg@OF65us6RAo&IX74{ zibbv}ZCW~%WMV2{aYo*WcvUlPfxNWqfvwb=y0MN!)?90GMQ*U2VWZvDQ(q%!h|lKu*yA{6xpE?8+>eh?8jXY{+h7f_}qu{`VPGEU5EEs7Y zuRLed6>Mei8e{fv!DX#I6TgAlvryZ^l;5}`ur^;sONAWj zB6F~{Q#H(04bQ<9sGT8B>RqAX8}Ya{O>f!FKBRl8JNHBE4(ZjwGTd{{-IwS2kCJ)&~IRk=078Dh^7 zf#8K8D2f3RH*OEC3aI2-A=j*=WH3~(3jRYCEQ2dhYr&DaF%nq*I4ptMCx}_gpA=&w zhrS5LGh)=Tv>^wpRheIm*89Y0pG(84Pc1 z1GN$1sXZXZ@{h#W_^BA1|3M>I?owlE5EqxD0I8@=>&h zvP5J&?AEFjK`#w#vhu=$UZME?5t81+a2oFE9*4ld5 ztyL@eyL^rC@Dmzr;I}du;z!Y1`-sr_4YXD@3Fl+{UArE?{E*<|7N~uaj!iZE_yuY= z2!dpPN?BaO^0YcK0(` zd_NSf&~Nob-EeofypG>&%&6(c9ZVu6fjL;GpK!B1@80s&{7yra&Rkwl6gr(Mk7OjI zIJ21>ESwuTQiKOF$_KC|L^t4JQ6H1P73i&mA;P_I*uD6VqEI?r9e0i0iGZ!(XCIP` zM1!<7!D}j^1=mkEIN9_Br!Qm>IgN_VkeFEiNm0#Mh5#E+INposWP5yv%Gj_~!-hd8 zie;vI1^XhhiG_*0usjNVvONzb9=!zZ-tszjH&QpQU>`zYXkJ>!u7xnc6C2Z#}h|7m4Mr7WQ!DBcM52DwN1$M3CWg8IK)QE6I^jJW$r5qYvNdq zA2aKj8Vk#Ng6qyCig>bzPtgL1cIGTB?~UA#T{j?lEa_N4(P_gJ5w8#-QPo8uTrP%f zpCpp$SCH$%e@T-fox(NiPf(9QF{G*0ICL zqQL$gdXw|AuxDyslpSl_1+{SAUiO;3wBgKk+9~q>(?>QUa%i_(F<@@83EiKVULk_z^{ zG$bMTsSUO4*0Y~2iz|S;4D4hq(Z%M%2s~dErK#RFOw!`8O4dJ=wu@dSF@Ak_zd4Ev zY$T)@LJE(rjut8x+<-WUVBsqrrhiKZlrvBvH+>x_-;l}F94MD9ObDb?xV8!xdgECX z26u^u@$n40LH8QEU!!J56l+bgFRwCilZve>qq{0?dBBLTf$87EaX^ynRzjP^`p96i z2NGXi#nLwRi1YC%omFYI z{V+Y&TK0UXjC~m@OW|4K(V_w?ltkE@fm!Q>nYwZH<&@W|yA8{a?3e^rW#HGpg=3K< z1ZI-BrWqH9CjKoPjfk2|IKjh?3$(GbzqF2HgUG^pPhYL(6W6M_?s}M=Ib(`G;fm;L zjsiM!PAl4vmTYO=9pXBZ>rC@j7pcGs4n^RuyIH_z*xU&6kQnVEx|-d-*G1kTkQeQ?bg z_7#5GvDgcH9Y+@|ce%mUOKC-31XuqDZAi}Gir>SwwC-{I2G?0D>~I zv_dTJxxpUiH@KJ9u_F!-wI|-l&RTHA^W&*F9(U-4J^n|%sydo^#Q@_J|fb{ zo+g4m3Jk$@?-NPgxaA0;5IdMl>)5-u8d8X__y=*TM*5$tza${158(Z$f()`EWTAY? zqW$Iy*en^xB7X*~h8_(?Hw(s)C8GJX0RE zVxu2Uwxs=VJQXmGJ~$q)H;(t=Si1%ec+cI{(yfHKd_8HXSS^CdT74&cc)ZQf!$b5) zskJs{$X!EZ>0%(T8@mnGYr|M#fNkzESk#8G(9!FD8;!+>v?L6t;@@GG4$@L=G?p*Y z95$M1wrbODG?pgvIc+qSK+-a7G?p_&du@Kb2Fc-WW!Uoqlkcq(+qw$OSmJWmM z1jnP&PI4%$%|~uO04ot03E(lfwhhpeBkEaW!)6Mt}J|Ku>!nK(tTHE7p$pbFF5UIokWs5_ZDvHCR9TY=ErB zVi2qb4#_Ytodrj(6}n7}8n-|tbOg7UPY1`xOY1m#M#MO%4X)$J7$IZbgmH_qbEM0V zxrOry4uuiGZt8lda9utr4bPF%P)W+_0ugLCO;wdD=YSY-;TROg zToCb%fO=LY825pINmBXs^H;{2Rzo%H2qB9Ki~w9q>%35fBB+LXw2nh)C}$ysv5dNc>o~@?8Xg19YN!V(xS9iOXy=$1#!6w^!jU$FSUL5BU^P4f zJ3QuC8^{{rTgOp2q*ys&GzoDF2iy!zm9nySLgFzP_y&ND)eFXxAXp7-JFJHFum@NB zDG=PkfjJ7^>LxW;$k4iBJs6kPaTv`HCrW^b1n9=s6Z$xM#|PnQ4zS^T1~`;0gUgbx zq1DhPBK3kF1WN|ofwy6KPI+a_FW(y_DNzP+yUmG6ckgDGWH|DaEpv4I8U_+nDS$?p053$!s zs|{L@jmCAr)*;f?+i3BxZkvt9sztuAjmC;YT9=K+xT}eVl3G1pZQn|*<_l7g_;zabiL_;R;iBiG@V+$rCD{HcwpU?0D7H6X+bg!WVS7Vt z@4)tw*!IG75X`>WVKgpG%jOS2Ec)-1M%m3Nh9*N>?DWoh>BM^xTgn*H#I%9~2FuO39$7iP zH2b!Zl{ux^b4ONQTAF>=$jXaLvloo4{9$SKqLGyoOSAnWE6*y;t{GW5zBK!}k(J*q z&2ArAnO2&;Wn|^IOS8ixE0eLO_WQ_@>QlI~heu!W6zt)YRDIRle%$N7ovv&;9#a$X z`wwNmC^nxbrYNt)rgNPPaGbz-vFUh(7JDA;Q;|^wh1u-Yu9AT z<~5y9!(0hAmLE>Lu^vCSuJiZ&B8QmG_hHkdo*R@a-e*cA2TV~ zYZ;q3tJ`DE>V-u&9mXc&3?;TDT%9q0OhhJV8SI>*8}mXp$F_kI-IRnw-Td)$c8z3@HMO4em@s>FPL97< zBf(^fGVNqKry)sVX*epNRSXi?i|mfOR?_7`YGxrEysdKL)FzWUCBst(IttgNn40H4%F3>y%lYg^t@wFrB7PjL#XLep`hEZGXPi&KXSX`;YGvvy z5hoKD?7nRR{|HIkcnoD@EpuR@V|7@yNwngX4U>uD8NwMxIC6uHG&<*;pT4@A%9th; zUeQlsY;NV;ROg(F(^n)RECTNYT$c_P<{DcB%}%e&h@)Z5HTHuF*~YLWOmnw7WnBT} zkP{Pt=oWHljaY)+%FeW~j*SdS$)9GFlb3nWY$VxFqO`bLvXc21NNepbzTXtLx^1N6jcZ)lOU zXyA-Fq7dq(S4fLq1_zPm;7PXoBEnK`u#uRLjD+1}y_8spWD!Paqf`NvB8Iw` zACxn~OhS%y0BJd5gklmQ!;B5XqSx$+E+aEGh}Sb{@r~kN70D*`bYPMq8L*7NgnNKY zUlsK-0G>GLH6RyYsDZQAG@WqgTQz<-VPq<*Gw4_m;)(}8=A46vQ9v}FK-e|M?l}{x zpQZ_E1?`DQXuI$g)_U$ulU6_)AMUu*(S@U~iu?eXLITE96g*u93j@>qm3Rg~mX8wr zk$lE_G+Cqw4mh6ZrWl%TH&yPtG5v{NBf!EC;s=O<#hOt87+|n12O^X7G-aAu8hRw) zddP~eZKCA4qCq1_dM|G%Z2755!~5t_U_t9mgd2 zGi>%S&tD-jX-{>jTh8#|W4gHsZVVyt8*F542JNZ0$phIhh}|Ey)^-Za3XX~NALUz% z9WdvmTWh&?ffksxB;Q()0ct5uw#{>6p8aEm{3{2449W+ z2F6@#)g$D$)^h0&8d*!M+FMxV2g=(^;2O4$45Ho#6H9ws+rhNWqm{XpMGlHiS49Q% zA1a(Q5jPjP5Vy5u_ux0)hYTY>zj4XC_{i6I6=$f=fy*KbQGI#IXU?gG`*Go0A?|^j zSoo@}e@m-~V>r4dy9>u0(QF&*2`Frm-Zj02vYF$X~W8EANhx26{)2%t}e`TrQ2$}vS7_LFU7Q9H3nbWFE& z!?^HGcgmQ5fe+_#iV%|#V{uKGgVCw7Yja0VE7F^S&McCZ$IgyZ$L>Q2n(L_|R)kf% ziF(m(PCC=US-58?EZ)euMGfLNR>m2Y&W?#=_jcxFvQw6Uk4Ylb6?rAWSs58Ycu%@V(uV+AV^?h9DV&@>iE$Q-v-!O`HR!z|c|{+MGO z3p2UdyWNmUhRiWLbqWSC+8Ie7!vx$PT+QMhagISgRv}HXz#1mAZM7F{$PPz&34ZkG zCK_BPnXtT1sXYTYr1g9|d*AT=>6 zsF;45T)fkilU3UVZgOZbNLyS&wi0Dqfb*JY%;4}~I})lF)S9MkK?Nbrp|s6@#tL$7 zmD?yiPT-O!rrqN;5Cf52V?RTaw17?8VkeshHinU%gU3L zw9c^;vL!03NsoCKIZE9zGPaAF zq-jPi*+*rXRKqNi=_=l^D|_Y^xJtzGQ5eK1j1( zWp-?^n<^@bVv+taT_()!C7>mm1zmz=m5j&!{UW^)d+*pDZcWe+1O~05X=0;a&8bZo zqP8G(a?^Dp;1l&CN5rw4e280<ay6!N zX$n5NNaR5t)~o&vVGU1+1wL3OUrIC((&=O`h4GFR;UZVq5m+a+qGn32z%4yD9Y$;3 z-!-<&k~Sz<#}cWv)=|gLBjg+18q!8LL%~y^Rp=Au&)H7r_>9d-QbLjG0NCozGfbeLIg=%dNEuxOhYav0O}KIM=meV4ix zld>;YmoO%oY=o-NluKh|ZkdOEKit7ORzQ@eEv#YS4sjflj}4S6Bm)dY{S}NoG_<%{ zzoQUcR)!>4r@a8Qfm@4YA8`E61Y8Z(O%0eeKnoyND=ar|5InOZ_zGOA*6<=*1c1BqcXGXriz=VRBfa~B4EW__M`~h`u(5%Pq8tO-b9i@q0p_e%PDO2;Q zH8jy^uUGflHkkR=@-8K>)p1VRDh_Y*EnOx?(;ZXp&-eY`hM)l!|ToL!9%DFMzBuO3tIstoM>JoJyF2=5g)6@fh@z!*D=#nI!RWO#B#!Y ze-ibHm_EZq8OBlE)u*##%Vj7O(fvPd<1&C-Ls2ni(m$q052$zQEUUkAse>wBsVY zg}C(=Y;a*XgAlZ-^oap=Mz(qJ*b(fvxH52K@P|T8k38(<>cK6p%xI>n zI=@U*K|?|0AupeK`YwS%2YA4l>+<5>Po^BgG8L@R7``$H!o}{mTm>#q#pM^#_Y}zf zVH_yIRjas4F1nq7rYaRyAvJMJ32ymJ9!-T$sN94TRIb|PXG%N_9(Oco7d3aZQ97N{ z?_%*hdb@HIBgTWc#jT#Q`-+pFCpKd^wni{WXD~7?m*8;D>xKh(~yl@H@)B%;i_$q;HWxjR232gEE$Zw_hDM1P;)C$hS;$0ARlj{5TFu z7SKNg;yqz7!E!PheI!;~G68S?PpV(Qpm2n;${Dzr)*ir2BdBM^j@DtGbQ zaDc&7305<2v`Vq;t~e&S!J6ib7OPr`O}sL^00h1iC$FRCpQ!YN-^ZmTM_AcB(KCii zH!<3jMs+DpzKhaFK9=~ftzf9uljGUq)J=x6mgfQliBvPW~R{Y88&hsx2NaC&M*@9Ji?E?9tS`1l6hp>P$6SB#;P&qX%h6V|GZ*nGx@lC z>poV#;^gl_H2V9Gq$mgpMWI02U9_rRtfm59M0gQAbeod$=i=nguyZSV^KdygK7aC! z@h0~WzG66>DR4T~b`W+cJlC}L6_MTX>i8$Z$-|}7MOp&&5a9!T!@}%9n3I1^;3Wkv zZon2ZTrJPG;*f9r3c3az7he;nO5^T>0502~@JDP;BlNIH>ngNV7$Xmb#` zHO{Lo*FJ9#dQxd;z=KNz6mu3%% z_hYd<5FR@mb|TElEd&NXl*pXF?FiC!H|mK4_2i^>x&|^Ne;nuE6UWk7haQ9&66pM$ zq<&tAwtnvq0Tt=3z1rWa1mccqZ_zd)mN zM#{Y-D{)m>wRF-Gy9H8fo&*CoKt86liy9Por_5W)712F;z93?G;)KfwfQ!j6AZ)f zSZeK+f~)SnY&fDBAAF7N2pYb`ymy|pTc*DAE$no_MO}H;D?{t>)*uEf;Z%;uT2nqp zc!C#TFq{M%hRU&i4(M9@VdMpWg~upcqiV&*h}K@U;=;Dp9<@4Q?N)0BtX*o&oDsYh zN6K2maC(9jZdlvYit}WxEov>u54Nm9GNT^Vgpq=%RrO4ExIg3ey1vE zaKbGDtlW)$xFEO&g2DPGuwZa^(S!^M%KWY=UqZ5~jG=APP`1d&46*6ba0Q|g4u?O3 z>fv3tQ7<>L(Vxe=Oh{XxfdoCovM8;2y&;r3DA*DYR{>nj9^-mk1`mM4ap`VV*X)jS z$jA>ISs+j}6DFTZIqO7(Xzy4)yV&SQ{5m_PV5;x)u~8BVn2a4`-}Qv_O*fD#NaDOM zk|l;zMaw__>3^ZNV}7v&7$*OsB!e{*fr*z#)R$JO$MJhV!-%E%8nWYta9l6XFyTB{ zCazP(qTfSVGT+cxFN}AlKjeXXL}VxK;0J{QlHEH`2^CNfZb>6-55m|VY6_?Z_m@|Q z>1bt|(Oo6#Gg=u12>_!f0bsJpfi!Z!AEp}hve>{KVmi~!#N%=({26cry_^Sue=U$A zHOOfdUU}ZyZG2`TgL6q00Iu;a3B);i$nn)g+2_nCuMrN!b-i#vtL)W;Y)@P^8b@UI z2S_ZAa3V%xUct$bLB|rAgyF$QZplMP+k_J#>=GR)nDvHJrfCok2i*uq0IIkO`_LMr zGnA=FaJ?YV(IyCVaE~x!*ChyI*JETFDmV=bZBY;q%TT?#gDIF*k(5e@MMB)7$dU{} zpd*Wjgdk?L>7+0G@x*z&ap_DndyH=x2$+HRbBv`P{$U6VI*$7poI5^&2eVlHP*4kS z&o6N=@x$dyJft5ke>8`Jx2E zQ{z>9LqBsF)89$zZgi;G;8e4@#Lz1Y-7n@n(ZzeeMnxQ0j2?-jhD^~X-Q*(jQ%~?wVe8Kip<;sj*18E_Js{iollGl9b?ek(hi|6w=;csIB{rlXT2TsR^E)7fruPPUBDBmi1JAf%a zcqD8+V9O6m1Mdm8w;)0Yc|$s5fY)Ab6*~QyjMzWuXXCP zdXAbHh}4*%kZ>N@J+mFwAXiPWUu!$yhKxv`i~g!gXjrKtBAwHy^zii z;iBa}?`~vx6O}D;v@<#|TQg{4Wul(y7CAOB&0#iYso5wAwaC%nQFqAj)vO^uUY?Qg z^P8yd4HB$DM{^t9OMItdXK$uwNk=9N6+hsfCENMhRZdUjFTQKLv6r%k0pjRs(7Ok7 z4>`TCY{Sr+kBZ@~sYiWyX$%7>y#LmLVfeMQbmK{~%gOgDhIW@nVcCkF|F!*q!jV0` zYh%JQ=oobzI_t%w(C=R48+8Kw>W5!&ct_LGtq#YiQ5aN@IzgE*iU>#k?8}S6g2^|& za0{?5kbFuK~poE=tWjE<+w$TN2Ait-(|= zvSw*}#A+4Epj$g5D z>|ZoW2M2lTC)a=;e$V8$VQ->O(Q#*=e{)~E>OT$6d&X)L#UPS5LEV~gy#Q0KRO~dT7IM+s~O5^dnO*twG-)F zCf>}0xwlu0H*+ysWugg9+Cl*X1r1Y>VEJ)EL4);2!U28WpSAW$PAWd)o%_6=Kc2o` z%|3hYwbx#I?X}lld+q(*yRAytYYYohlV}Il1e%u=>Wm#cx)t(kJil*85qZ*)_f>}s zjSM3*MaIyeo;E>YuFo_XA6pV9E%3w|B|5VceN`0pxz_uJ zxJgk_?zzo-wrVLbC%Jd)ghKwIM3UOH$@OZ=eK|GvUw?u%je_FidrV@p;8JB@RU$ym zZZG+z#N@Y|r4#x63gp{{JhBl&d(M*eCfh|{S)sbldAMTBSW>^L2gSr*`)Gp~lLDS? z9(L@odd?ZF*m8+MpEFXiWe2~CD*^G}NUJs!tFq6p%JqoYWOffWemfGu+g#dZU6mbQ z#fNs5U^}(!0&d<#!_kOpvhIY2x2!wc3D~(!S`bzdH|M|bjJlhb1F$yj#Fv&qw(>yP zsREkf%~%`%1VH-=jL=5kEt&= zo-vky`b@YKCS zADH_1h$&&76MXnEURBHy*|wk&V*L7@@mU-A0!fIaQsj5$mbddTwL&J~5QI zy~i{B&dVNx!65R#g-SA(O3?b-Op=xOy$*M z{O2L!>R}yZ;tXl^i^GMhhj|n4epteDvV$8MdAAgw?~$vyiDZLPuEQcYeD!0%{>Zy@ z<2i>aw*Cu<>6x;BQMYeA^9i!YhabM|$21?5^cvG*fI4#Zi`Hcam~5ub867@walT^f zhVzYeChO$BC?OdY`_$^t()|@%Z&5Y4)ZR@sG`^Zi&T+%`I|m&8XTxv4>=)w9%N1Kc zsrC-8x%z1))@P6lukql;V-;KfY`JA2XDrSmF*=>-uJf>?$r<0@?D3vfLdiM8%hR7q zWI7x1#CVKmJX^8(uc=E1Js6QZ@Hc2f`FW0cXrxj{ZWkSmS*8)Ij+wA%pRNC=Qr>VG zM)XsD|CnH+9t~qcC+`5Fp5_5APqXsm1rj48k+@YuOL;7BF_fhvZxa)biE=t}^3##G z@gPmw9rHeIJpYFh@q_Uh-zTK^F;y?*OF!KRrKu!Zk;RPfZ;fsy|iTRn#?S!n{Pcbsb_UE%0L$ z&~U}(3Xyv_egOsa;`21@h#uv2iO_?zV$F!8Op%A#{XMJ)YxT0PREe}8_8vpjwa;}t zs*Emq97k_PT0p}Jt;MWvqdd{6(VhPoOJ;Se>4`&)07PXi)SW+;4Cq+K@1RuF!^Xfu za&?%3BoVy7Shzyuzj^pODLf z$n}hos#z-AS*L{TkMsY-NzMqKIGIppaI`KH1uP8~@(L$m{w5WnFJ~3$6KaZPx)i1p zIinSWWkf}mdJ&^4)RK;-i|m6&bz+kj?b8U#M^0FWH^2xxoXR*MC{+VZxfKd4t#;(j zn!WMNQHbwvb#xug9vXx4-};_)QBDP>DY4dz_>?Fq@EYk)jiOAmDA}SSaN8K{EIK_^ zbhc)!=7Mtr1vx@PGLjj>j=Cd`PE_ar*3nq2r)%yh_EVJ?=^OBxdv>Yjw>q(%T{FZU zO7(~%$ZLd$$S(3f82G-r5dF!=r{mUzld) zK6PfTH>6{ysJh9~bgDo=1M6C?SfaDsi+6g%5}jQtveb(>IS6tSMa5E~(Db8eq2Ed% z7V7??!BgX3LWOnW(BQH0b3k}cQdeZfPLDbHtqHZj3$P(Y218~H*%lKAZ!0IDTHwQL{2SJ${n1J#$2U8n>x4uzNDJe9Xhn5#ik5$ZNi9foGP0z0Nl808cKw;&b-pr@GkXXkRL?NU&rzhc8(U25rPP{!fYpCzto zd`#pFI0Tc~b$TE9Iy4m^yHuXsE)_Ykk%>6bu`{HNi13ZoKZZ7%m-?ZYhn~Yo7XUc6>U~zfO6GlOzYmaR`Y51J2(5F42e@ z|ItwW8YYv)dWLyvX%7#!r5Dzs60xWSA1rI`^?3ij2qx z6$7#Cj4>lCCvx*U1e}hS3@Gu~c*zRt(cp{gi#{3-*nrbPIuS}iDxI0yL z=Tl4?7g@E@k`H^e)>6ord$L#8Un5|i7rrRui*@RxS`YiHL;hcTevh~y_;Uh$yTkQV z1^7yZ>1giB%I8?a@d{6kyVY-$>vyddM*6vNZilD4K*8m5#TUn#KwPlyi03{cTGK3+ zC1^-~B$(^sx%Vr*EuR1Hp5J3q3+;0pXHFUuzsk#$E&HOuByuLKYZ(FC84mZvKUUr) z%G+4|L+Z`6sO(+w!mE{rluWA5?JS4r*9ogXD!Wp7S|R~&qlbZE1ELVQ&XoEHuzxMs zd*X~#@o)jBS|Q#;&z7B|bl~b7Zi&S=@>nmt`yxo})+uiXnbYj6rCR-Yn z(l5#~Zyd~rtAJU2bs=%vxO5e=rl)LP%xa_AI zO8Cdn7<6np^@^JLq!RCl%N|rn;mS~W*v1`GjK|&MvKjk-V>Jy)^mUm+vX&pDAsurB zM}wNI!3^|+jfaVMh8fOW+Qcz+6FtVYwVW!VgLXP2n3UpI#knzclu1F_)wGoV<5-FD zxX2rznxXpZQ1fYA5Gs3N++R+pvb5~F`1?{zV;GPUps3F$t7C~A8}~=v8<}0gLIH#5 zveE)C;GLMxDe&@d0N?3t%V@HM&c0Tqr{RIpi8m|0Kh9WsA?|Y?L}mZu@okE8^5pG;7oHFwe}Z@$nlv3PoU6POVw+ip>eH!T2(Zftj28Bm06wGN z0PbXj%8XVU7yi$XIH^P{jkWw0CDP0hRd+&aLKyeCPFVQGBE}2jzLr4Fm84B$91a*I z$Ru(y5XfDjbge^rV&3a)G>XRp#PNooH8I4!a?mLrEd?A2fR8D&%>l;);6y3lfB*x) zNC4OuC>~J!ta!dcn(ZXmFoD~5D|0`+AmD)DzXt?1nb9+r2kiO)+ZAf&3$Cc_UL_(1 z>x6)IygL+b5=H4mhj(M5uPIRTmVl($@*}ghRX!EU|2g@R+k4f0DFH!2gBR{Aw~%R8 z;r6)fB`&yA;bbWMnBpg3h9Ja|rSY7$=k?WvxcU1EIGjA*F(&_CI_juWoN^}KS%z$rSbfgmd@rj<&%3e`^d)2fJ-uy z4?oqC0mruRbZ<$YlmH;*AQ7}A?_Q>p`3D|1HX&T_e2+)SIU(*Ca5@*>N1}MRi?|oN z6n!p8ME?K~E+DIDaXkN8k2K$TaTG1C;%Qz2{!VKRh~g{e%r!rk$b+tt!T@o5$! zkyS=F5-W*35TC8@HzcXmN=M?ZQT*I^?#&7h$MY@3{jy&1#c`R1g_LaVCD&QmXs(63 zQ%up(X@9A-Lvh9=XEz@->`uL=x2dP#@Z5JRb2roE?i5qg($u8>{F>_edm+~&8{&TJ zPK<<81%AYP&@+XQgm!CWH23}=7(j>HIMLjDJ>DrXr4H%Bx!+OR-EsHMP{!i2hmOQO z+mr^(Pr2<9Tk(t+6c*V2JH&KLW4^8Up}5nO7dE2J4qDq3SU)(v)Al$_u0b7(jiMs{(9DtLyIgA?oj|GPM!SeTQJMSzA=cekLHMeA9Wr zTico8m6w0~yIACfxNMvPEN&U>+6>TON7l;jeoU#daDzBS!RX-IS?v|1BOizR@oA+a zx1{cjM;LAxbI8ISA_MH(ElhOyh6BqE6=rM{zz_RuOi*>#bk%sBOzayoK0F#Tl_BoK zqcP*dqcP*dqcP*dqcIGR#!TM0oeIMv6^2JDvo56ju)xD&aqxw7A10|xGQ@3oa437! zNW~Xr>71p3)}g@@Y3Gr++bt}dXKL3G)|3J|5_goVI~XfFLwnags`g^yD84@~JJyk& zeV5X)lx!uR_A?!_w`B9%LRr@CYed{uW4@5Rqjmid>|;-TjkXS=o(35sj8WC2M7fL4 z_*084#kOP7%KlHvJP12P+S>R*$`3K@&zK_;?unOFD?B$YE4NZ>vD(oE$0|{PM_AMs zq8_vQ3OWrPym~D5rDF$F-}et#V={BB@fhSsKyp~yG$1$-pK+V=k0@SrcZ6Cxlwoej z;3+=L8FQrQa!Z$sHu7x{`PFIV5>MB_WZ@w;EXCgt3RNqU+G-prmU`omT*>UJ#HXF^ zB}Lj(8m?w7(#{h+eLw4D*`nC%TypEX$!vY8(_p=gS0rK&zyef5=6}Ehy{i_5-jVZvTW96pgr(#4`@pD=EZ-LnP8TOBSlp!5^to;t}q8e&ZG!?7E`Oaa@h zJThuyBGEIde9~(z9?ky?QJqfov`a|n7B)hnv;RzqTCUKn6GKJ$fOxT_NwgDg*J89$#|1;>X6BQN;^<{wZ86 z%fG2~mQ?1o+IS{Qi|FhPO4}ZrPYBptBv{hdDm|UZSU+u#-T8C3S)^xQp*-r#3qK2t z5wEAa)#^d~FcKCE20deSGmDQvvwUeRNu#q*_DsC;anG0$o#^ysMs&toyyE@_Av-nh zZgrWKKd7fU5ck}OA-`AU_X#l^$Cb{E41kRa{n2uH$!>vej&tT!Bc3L%OxaPV-4-Iq zaazKjvc1{~bIRXd>+M5%o$+!ZoUx6G() zu|ge^xHHae^SsmkQfYUxdQ=?0*bapSZ6ZWvh3^@>Pc=u}hbsORME7@;d1u_c&JZQ~ zyTqe(+^JQ%{0Zh*qma!zge`(2Z1xJ+ifQ~F?Aohl@5N&1cSoCsD~wbd&@+k5qzQSH zvB5=rjvw>$L6A=M`=Chllq-F67z_-a$lw|??IsU67!+sa+GX8`Y+JsM3u`C1E0uP) z_u`0^YYZ#VMqgoWXv|qNi-XUJV*ddbGapK5Uz6@A5hCMY0qs$)7bD# z=G~Ns>P_crLhvX1Z8|irvH9XFb7ITabkT zL1>r9&p((yl>*PhC(W|k;@!sf=Rl4aZKek z`tq236HM^b7>}79ES(cSA>VotybXqrQy(GS`h@i60N<-{_l$s#Dy~^Wq4}rqoC^nv z|BoJ|ztCM1mWRXI(i7d29?#@0j53w#7cM*eRNt>=_B?#YqAxm3Lav;QgmvlF|IrU$-K* z9W`CV$ws^*6=484fvIqWoHGeZPlwH`DNYWg6S**E&9cb(3j~oX=P8< z!lot&kt-gCpslr`ABF2Y10iV?sa8GR3pUN zWXobw6IlMqyRArPFZe={J5zSv3X|WC$AhrQdEcO#s%EO;JAhF0h$t!G{ve*e&C&IU zNdevVRKJkZ5Z^9KM}4+yHHG)LkmxWefttV<^O)yX1T?cc(`$!?4c?HRDi1qVS^gw1 zVm(V;eo`kLd7-m7UXm_u(MGlhB&+L)I>h?)f{CWVyECb_Vo_MKO_`E-4jA^M@l;~-DbYfUCrJlonz$T zcWo54{i6b8Olj1JoTub}Wq!Oa{(+*;fUI-GU}%{ty9dPxg#$_xwNurPY0K}&oHZI! z&HI!=p>`uX(P671*kUU7u&q~nTFBE1hXW3Y9#dkcn*+FWofq<5V`SWGuicF43^P@mW?OoIXhO^m+qwT?*I4*aPRLY*TQj z5)NxI#8$I@AGDoJh`W>%sg!J2BAv5M;eJ>~hqUs0sD7rZe{ z&@33X#MpdeZEBHIQ!KL*Zp*-@R%>clb{uRh`^p|`qK%5Y9#coD&hJ#>;rNW6-OA)c z6`|jsDtm3nfL*gR3z&Vf9X!5)Np?oF3Z)}g0_>BmbIdmPu=;vBP%=c6Z*-tR`VZlGCGP`lbC>@-`itl%~H(k(K?dhi9$alR**Hn7C zs}=~%soYY=B3)SJd1wD;rJWVKFaWcWxK6H&Fi!UXjK3l5uHlV&kAUgIauwcq=H8+D zOVI##$1WI1%^brTw#W*RiT3cN@!WG&un?VX;ia*U9S~1QQ&28%VdTSNF*`PA#b^J- z*ou^Uo{bE#^(Dyf3EI+++ohwRuh}IRFlP_7xAc7>zyZ2P;l^rh9QT`E$Bx1V(vm)& z|1D)=d3&g|=!`x~<2y1TI{-CP)rT>#c?G9hhahb87J<;!X1O?rm9)dvyzi3ML8{CD0A9Mc={_k?d_f?TI|y= z^7Kvk{Bey18mUmj9zR1+6i;8lA@gYNqzx7(KdX>ai`MdVJomd+Vgrs9pzaqGjucZr zbWE>9KQhc-+J95tVN6EyU5`a`|3PVKNH_xN!29@RzBEfEn)^xRBZ9Ujp?`WM;^sbJ z*Ic;Mu4GB0nbDF99KOda!*o>KcIr+FpU!O3syb=xJK|tFibw&E*fkg%C)JqApa0bR-CxQ_qGI$ zYmuWh#`@UjSs_-Ut?>$R@i0ejn}BvZkn&rtP&9Ymz3P{!TjOJ>egm^N3&%1g(#bu8 zl9AI9a&5G2nBMK0`_Go4{WB8xxn`Jqg%azv`-WfFCOc4klEh-^fdKg4($Wpa*l6ye z($YTaqPagCptN@1z&I94bEbY8V{>T56Tra_r)MMpe$NwG!$YKIdWd63092C!qEqO# zy9K}mY107t0Pv3`0Of(uCZR228V!ION&rpd(@cI6MY#Ew$~!&o+$Pww;`#3@MPTCx zKAk6^G&7)DM4@+wLhDor^>21S*ogaM<>4%8CQp>uhTG%cbp$D6NjQX%jyiqt@VTWU zUN|T?3hy$?6Yh3JJdKrjWd4=>p}`Z(wp;km0oXzhicD&F@qQL=f-ei*26_e6Y&n|Cacdv1P zFRti=24Nu2XUwoC10l_ZIqb~<*A(K$W-XZ=N5;8{e<0vCwFN#m!F&U`cwVEs#VSkm z)fzIK0EQ&;J!H67_uZ#H1~8s zNk8LAe-L<$*`Fi&Ncq}$;iJW5Hk=pkosL|}`4wdBAtl%VMgI>Hv7yB-U%!59h_8tk z{_Aup2E|TqfoT)3WO2OkBhzTu^}D246wx_fzY(o2O8ICcaZyOz;fc_BYV4c*G~->< zsO~_)i2@YfHbK^(5dUl%M_ItpYB?Ij*k#R@*toDsVVWpWxGzZqQEHq&+)9_e3uV(GTob<;a#^T)~c9WoNztxeJVCsgEc%sNP$ zY}z`*=`218-{-Bwb)036L4`to*fp{F@EK;7PU#d0*thSY zMy9tW#n&{x250>=F*cFe}tGZYhy59G5kU zSY+oig%q-FGxXvRxW%a!bBQ(v{n!}%|Gu3@551v1G-xl~cAF!1$Or!@t*qKaJ?@>3x+jfNrhPa>I77g>67`^=2~XvtTr_3@{%Bk2vRLqq6qOqO#Ai4}nb^kbaDxruJCrgl~Htj>BR} z-tcq9?YQh#0ccx-uG4Ot@2`@v)-ZBUh_O9vcpZ-We7=pAT&Voraqy@`OAZJTdrMv7 z8wNy|%R`@Sq!CY6gt3$Nc<1WzRR)^H#&l-s7?8_(2P)rH?yS=6Kr(i7tTJUEInzi>Dp9t{J5?ZRmO zfD+RQA0^rm4!Z}fR-%ua(#bdNZk&OnyEIppo~Jl{ov+^Mfy1N+QbkHLHlaEyQ3e3GO>WtWNo zy2n6$!|X@;osRt^_g!(OH^6*B>37BMvtbXcN$G?(&A=5K=tzH^^S|sC$J4P->i14o zCklaY7U_hV;}qI-20NTvr^o%~cSDamBHv5X8k@Z|R8vaDj!pSi9o5<18rv~RrBh0? z6~N|-D0|M@HM1$EIuMfS-7eozBi?RAC;Dth?MS14#>_-)n@JlQeW6@n4d9zf8f7N* z@UzB~Y+s3}ZA-CF2Cc!{G%XmjwwX}NTq?!BRUjA*mY&&46H~SN#ROt^Oh(kH))dK; zZ%@fztdA&tqm7B;O$HFV!wtpr%H7ueVWVxsEaCH;M&zYLPa&W zT}%mh#>*@@+?!*{04?@tzTⅆMkkF@mzn9Q^zA@~Q;J&8TybZWDeCJTQ zL8h%IeWn)n!iMVC+E{0|jGTs$Ga(HdcFEd9n#ukqo{d*00oxnW8;Ik9z)s%8Hk%R& zBMAXO6T~sE8(+f3`xHIh-z?dh;!DTfsqn#As&gG_(4lY9PE7qof5zEa^K%m08+|lr zN6m2u*TYg)qMNGyx|vN}V&j>1yOP@0Y@!s|hd6XaPpw)6L6O2kF5BEQQT%){jJS@J zvUNWOM{{QRH~(d3>K#1k-??AO?{48^d0`me zlhIO=H^8{|h7Z^Yd*&#EThSX7>T&{wd`xEx6z2FQsSG~MY*sq`p|vGnO84!sINn`_ zSSm@MCi>eI-&oy0p>Q&BXQd3=srB6kr%xO`o(XWB&9)f9HVg2z0lv=Tn@0nDm*RTp z#>385&u_D9d}vRD+B})Kt6cCciF>Lo(<-O4G{J5t<=up3tjyBh&kjjVZ)APncL!kFH1fZu&$ar3@M;pzw zZ$8^8mY3$9649W-=J++Ab9O95UR z+w)LE^-F0&fi)>PY`;H`ZEVklVSe_F3d@1Gr(Agl!gyg-1WV2UsCdp-mqDJe+qZKU+pD@Ghu+Ld3)TyL%cYUdU5#gPkN4mJvA!G0Mca; zOdLJNalW60vd(>0Gw00J3#drbeh2uP_5jzYATvX@}%q>k5%yfMvBl-?)li zdXg`W!88YTWSFEoi!FJq`p*OO!Mflm1>K9l6f+vZG}M^+1+5bX7C-5cyTc9 zX;S0qy>$wg#+}ttdODT389P&H1v&?tX+Xcl%k3OU)9>qIzwGJ&cGvE>r%L4x$39D- ztm}kdWuc)~@N{~O&4ibdxRJdJvlpXWm1#IuNt@&D9RftlHF@D78E5;va5$z1+&yvk zq^J2uPz40#TPNEYetUsnsD2II{qo7(wZe@0mk#qT=g})1^lv`tN9ykOFjn_TqE7ej z)U6@IQzvICMX5;%o!o8Xh7!G@gf3a37x7iCl-GYH$GQshCWi0BcP5B`#T$Oip8MW} zUd>G?;qUg`M}NL^&#&Laxc?qE``s^~e;Ak8+h#$E0ecW+VR8xVs!mxDP`2N2QUBm)X%N%sU`Rqxn$GcVJQXF7d2BErr2R z7NHOz-^`O~ry`&uH);%C@AaqIXjhzhVV&qh9gi73iO#@kyY^A}Ey{=95jDQRMwO9> z=YkNYvGI`XAl-c_(2#886?k#vWi~~u#Jul|Y~vIYf3qZGP{*UwQP^O`#HFmY7D@E2 z6zJS%rNcZ;+&Tv(*ed?gPA>o1^L^c-)nQBv>~XRWB*F8{6>S>BpDa`JvLi-c`{zbhC;iz@`&HL?#-De-WbG6FPmW@B=YcaU?{V zc`VkTnAD(E7;aOs`z6O8{_3xP-OjxeBNbb(+y(WAuNfS_m>(5?qMJfCRu7Dyb&q1L z(86g;yLv=ELS3&?azTkNek-F)MiC(b%nOfi zB-`(uWo>iybJFc>00ulopicwTt^?Pvuq&T>WPIRT#KWx&elg6O!sQI(SAVC7kM=!$ z)4QQ~aQuIKQ|-lzTmFBUCGATBt`$w)Nj%&m>WGdVe;XL=9^J#&42-X*WRVZz(lxW< z1LLR8#An|Uaky8V7-{%0oJ>unIr*YEvtqNS+eHMDunEOcZIL7|ohU9|dwik@H+`fN zeiE|ar_#VSjQQY|g+oE=yqC%Tk`#vedF9F6dF9Ner(Cd3?d%hrDx2YvPy4f|xy0u{KWi@3_%;%Xo&t8lnphqF~mA#sb{=|eb1var^KK)XIia@%4QVH!O(83)G_TExQpnv>K&ivG_h5k|NKcpP6WhS?E zCfCqd8%aZ2zA)<0V>8hCnV%Ekr_fG1pf11EKkBb4{>TLK`H)3YyRe^R&>+HIQjxsSlDNnr|tGo5$F%YWtKh~?tFk|6NaikTs=v6t z;v22iyu^^qy}xEv?zRDFYgn0U)ss&^Y}rZi`d|0z#VCSx9yEE7@}R+kqz82#)Ot|k zLA3|EQyDCk9z-6Ldoag?Nw06hgS-c09*laR$G5<;&w~LEc6re2L7=+JV>>)(_h6d` ztsb;^(CooF51KqkdC=fN(t|n=Y6-+2l~<@-g_R*xUn#yTgpv%!*M+bygq0zj5Z{r< zsA~s|(2t#6;Ya(n@MA}N_|e)Der#*y$Ew^G>EZl4{so`O-wzFd@xGb+_`f@P+?+Y% zzu3wvU1le#_rI;Q{I#SdHxHGgM&``C;5B|$ru0Ftc6(l3j}7V>Kc2FjzCT}Yw-4z- z`{@T{XT4)D>bb0OeWjMd>#Nc5JRQ0F%D>fH_T?o{fGziD?EP7Ip16 zg|+v)dEUO3^v)OMO4xnnXY1PhCy#hrevv+KCxPp?@_KjEaC90BXstM~*-kBA@hxik z%*9s^XyJ-`u$9&FvNi{Ulm?z4|42&p8UpHVGA>ZdI#Ro>7T}t>3C3V~L{i?_dI$~P8 zEZgy@H7Yksu#6{b32=ewg9n0Vh-Gt+63OOXo`hv>eO4te((e!< z2e16^U4hnOTX!lhVrhp|yofcPK)f_HH`f{{CKE-K? zy&pbGgs13&M7+kEp>$u7PeC98Zy;nD4=vCF0=XhqWz8u@@T%IA?fEy$>p6~Ih84Zm z)=W9EY;G43e@&apX86lG5Zg{7_gxK8^@=8tVOlhYVFs*=8qFvt&W(T8V5k?()=G*- zWEI&dNi7N#*fji&gEF-u(~YF2oX&Y4S_+Rq>Fc2 zvpY_bsAv1WOpM@d#Nd;Bg9LIK!7lkU3FLZ$UGg;&`~|UW?sG)Mlp4`RGinvm1Zg!f z#fXCLq~anJ*apw@v2DHR%%XV8vusQk8CC2Co=k62Hq;Lt;@R|OB9aJa{A;`$3jQLi z0@I5u5?i36Rpp^z8(}v0E^CiH;0Zgl^8o|4SzB!@0tU1YBUom6JvUfh&njZnJ0l!L z8q_`(V_nLpG40e+lu#<)p~{QG070QM0Nh!UQ*5;;hSDz2^11*WP&|y6UeELPQ+HA5 zD7LG#SODL56nK%AWo@pbsFC(Jdiy^}8&R}kdAIv6i;6-JwmmH`pA`^mmw-P)p?cv&h5tN zf9@o%9h?8Tiyzt@(970|KGnXet;b3qi~On-U7J+6@iYCa=ql@+luB8rOhw;ZM+6E6 zs9DtBXR_BybTZ8K!+`y&CM2)U!mrgPxKjjbkv8Z`9nh{Uwz%o}+b_{`N^{JOqZ z%}J7tved-5Dtl4&vNkgfmSxYc;V#=zOTGGS%eWR=aM|}Sz+JV^eqQt*Y@S{NIR9P1 z4p{2dNxVrrE%p6%7*e||_2ZXOg(j0#+4EOn3u(@wwiFn4@H2aLIjEafWv{-0ia*UO zyRDjHq3-L(pFbU*Onm&U{Q2+)mu0^udkHGqg}JTM=Ap^Nmt=iFMXO={hKvT9vQ04A z?~Exg`^C>0NJon$e(4`AW}9NX-@Ahtgf&~FdlG!i)%s_G}L;W?qoV6_b#YY91{n9fQ+w!6Xx0!*#`@pXf z)ziaz1)V1qY!qd;+-fnCYTgoloAe$Jz%TIdOYc%{_KV9Dv-VrElikAA z*ic#WTELB`;+$X^BK!Y09}8e}`Hqdh`gQxvdShlip_jUGSWPb{F5w9-Np`aBKb5W* z^6wmITfu8pW<4a^u6SG4tn0QF3+!!nsKVuvnNS#B8_$Qd$&$1e`8|W9x`?Ajub!Lr zf}1kZpwo-!q!n?PVt8f!inoTs)aCc72RPw%WXh>3!BE8NYVnG9m11sN@g9NKmVgV9 z(&|Fm46$`ZVw0uBHk6bN#O6{ZX|o&5rSeK>TXC7{Xexm#lG$96CVVCBZ7Io`-QL!c zoFbz3lC&aWJ4(`wu%NG@rAt{;>vPtDlZihJY}%L1p3h@2cJDbPUsO5#@`lmlV1O=g zzKC~BHjMK6^M=v4A_UAriSyNy%qwhkfRMsT3L7sc6X(||y+##Lw%TeS)gCBlaOftW zjVq+D6Lhnnc{00Iqmy{M!?gfsjV4Q4L?V~W+IpNEwT0MDG7!{M+lr={Uc8|wt;L@B zG{pRVVtc!Y3B|WcF_y|hB!XuP?{5g|G&Q$NI~FlXH$uyA72Z;;Gg9FbE+gZEDtojf zJ8tDz9|XE2B5hl{s4v-eyRi=d^+0JADs;3UE6utGM2;G6&oOSBS}0|N_1sa6I9h_~ zqyeL%C||i&Q86Qix7qsEv9PV2xJ|0RR0MAu2?;Y&2+~PMYHfB=-7+S)AeKTjYUNNe zNKiiH)mTfmMCeu}&rwJbab`v?w^W8?Yan1X7B~5;=4X&hsHn5p?V7^cwrUER>GuI* z#eTOY@#=dRxWA_?K2U;5^IJ(56h))>?8$E`RxA{=>gd)=F+OycRD-&@Dx}TOZCneg zx=8<+Y6V){D`F@roTKG&29qY?A_mRG!eIRsXeg>NG5=_+M~h`P^B#=Q*A+;xHkDu~ zVzs{e9l|M!T2(fPBecKEY~93dNp*RUN;*2_-EQncw3;k;Mor$fE+ovzD7d$@D0P;y z+|urdj1Ndws~`|S<1C1q6(@a1NEdIYey5kRc9Pp0a;=TT_gUQJbHE|hD$0#oY^zKq zl%l==BD%(ujK@K3o%;Adaxh;-I2IKAmV7`*d`RFEj>Sx)SJr>t%&1q^Zo2-@ZW5uU@&2*1pVX6nj+$6Z@2bV~owOGPfXg6Dq8; zDzd7z0t$x4&y@c1N&9%fY^zK%>g_10mwMb3n_WH7|8-TMQi~Vr9|?6%t$%^o0CoAx zdsFMjhR0dMlR)ddX`Mgyi3BiHDfI_X|8-Y(lumcN#hgq>k|ba|_Yver+n?`WlP zGP|5rLE?+$T7Qvdehdnf5Ki_tCJkTWJCyz`TG`K( z%thARGdrq0%xFQ1z-m28wjC|gs!%0aqvS;%h4g9v{oYub+oQ6@2>IbdisL{)r zeY2%jX`$Ih31wv(tJ%J=UB6Z4xKG719$!A9M%M(=>lD&cA#P`N z$zMI7K`_%T)*UTWNGF_mRhOc-r97J0vQC76qrq^Zlq_CaTut3Zs+HSOEVnbHY}uuh z*6%(8f#U1sy%il>_L0VD-)d`(ty*QklL58Ym*ntj>f`xrMpr_y{>V?iRt6Yn`H%(> z+&FL8)*{vXX1{c0?%K)Sq~t5Ff1US$XRSNRRpC_ipUCC7B9aguKlb*cRw3-Nf07N- z`Ut@HRcWdJz8ZskxQ58_12w}h?RoSq`gz~mfxR{wer?a-TljSmzs_`j#m4m<+KSFE z*9e#RaDtONwxjiR9696Fw#4=AJgBa(UEZtPK1k@85SI(lJRte1A?E#fUhPTGyO%?D zu|7=CO&S0hl9xsLP-xyB9`eiB7Y4dUY%2O}TKN5@S=EmD^QpB+AGY6zyS0;YuGsgX(Y7-RWp^sXT`^gY7F#` z=}c;iB1clZJjk%9v7CsFo^*5tuUT`~Od)aA2yODLbmDSdSdyzVcBFpF`!>&!*;nfr zyQ>ISE*jV{cV(_FTDfSj;+CvU+w(>tSf6Um<3s;hfLCaU&=|ny2juHW@$oz}RsTR2s zlcHc1&)XE@%e(mIclj=GAJjL&k60zNlP|(_m9L$8wJX^20|i z-dC|Tr(AnEC%U2>Y}eEvqgPadl0Gd&D{4W!f{wlV;o(D9!|ki>A)yzyfNT6DPT!t{ z>OJ#h{|lx3RiO(=hY7!-e%{b3aPSzPm?;0@eZ}xFIRUxK4@lW#vUm@|q1?Bm7d`zeEmDpy95sBlAp=1^$kGSV2uR98o z#POA{hx4JMA%%0r(KuE6mtPN(H26U8&G>WbIgs*L{beh&uU?+a{`}Hpc0X<$GuI2z zU&DouRMMPf3*bQFh6UB||A*E*@xE+?d79WiFKCB#`D@urpuqJ4y>&sCxOpJeNSQ+7 zV=(1V>aqn$Ug~4uI*=+GGO6LYLE*n_L6t$ZHLv9N7&En)6S5L{xA;sr7L@*Td-30PaqGklGHW${HN}%L}#%eIc=GL2dra zRxWaSZe3vO$3u;mQH+80XI|hR7wn)we&cM=T|xpk9@z|yS9zYQ6WdZ;Vy8zL5$4?x zlz(ra?)zyt$Hg$u8I_Uvb09^pBVuLuDlH9Bb)fj%0xk3M$2(fViMa!+vS5u`iatJI z-wl=}3@OY^=D+`8>kDV&vIR|Q#4DeIfPT*?(pLpj%Ep!PWzT?xM)*2i_B5)DHqZDV zou?Kxi-CKU@k!5cnwF7GuYN-raWSLCO3<{%vTkM6Sq4a2m`fm&E5^(IQ5k>cC8j&% z)&;F<;lakTP0B9!Y{{QmZ@osZ|DEz){E)TOWzg!YmQuQ0c_W@z>{Cgp^6HiMbZR;tWpDKC)80;m6U85t@J91bRgACl3mXX!#H(OB_lNyl zv4b&Rtwm=aBZwn>0eFBi>qtH0m&zr_!eR~_j?Z{0*mxNOb8%eu z5t2#b)wL68sxh6^4@{>XAxCD?k;b_nw8V5`wM@`slY5s&P^a!_L^14+|IHPUtCj=t zS51>J=|-xlKtHoaw$tE;P*Jt8d>|9|fUY-BkTFF;j_Cc22)KX=&6p&tZ z`ogb~N~nT|8dpg^Wj^pLqQx5il>CCjEWA?Tk;X^3%Slh01RYa|Pg`jKiAy0YTKF+V zlxu1w4GnZ|yznYVQnu-{sxY;jKSr*!a#jBMYn{kHFsQg}@6AA^A*+TbmqeD6q`#H+ zy9#002Z{@!I69+T#ST*EfLK_F&-k^<7oz3mV%0pWk}0h^|JhK_HI~mk`6czBzUp4D z9;@GnyXw5Fv24&vCoZhX|E1xJirT0KZCSRT-2BO&vE*cd?q)DyF2r*OtRTFvWhFcR zO*e_ixa=zm52LE<6#KHpIP*WN$q+}AofY2jTFk*wn!Dzz`o{XJX3k&LU$HX#z54gp zU#>av(aTq5A7oBE!kkzugQgJuVaclE)&;V>csRQdy$L&I@a8|{7u$z=rS=~UJaH^3 zm&)3Uq}|P0`zSd|z+llUwp*_hc{LafGOa~$jY>MRz8SOYP!fTw}@}XRItQhaiPM zG7E{z;a_64q@35YH=c9cf=?Y^ajX2Biv58ipH&kI(NY+;@f>PV+Fb!)Mfs=Rbi>8T zHfQ?u`q9mMI#d1Qomqc%{WTntyOn}Mm$4G z|5y6tK*g4uWm4_s6;l3J&TK-&8CkW~sQk{E|4MrC~S%gg42l?|J;A5bN6ak0}pFhD(B9pRrgq1JD zAygm#+{Z^f`;>&4&2<<=0HNo1PP=2yv^G2PzFiiD9#DFU=3t9|MAP^w~(4 z{PSAhQp&tj_}0YFTj5H>T8M6jwzYh5qjzdfjrqFcLbNcDeBX7vFVWeS3DAl{wj{N)!YyXYa*U-Ti?>YP?()K*gU->y&&b+GEhgakmzE7Tc{Q#+* zbF7UBIY(O~|1JH0c`NgpQ{ZBJVM?w9hTd+L*Za*q@d?I=t`EG24;_snK4z4t^GP9} z1sSgB?fmXE*N(0QEJXEm$Gj)xgn5d||3kgRCWi;(O}mhE4xZqSVW@o|_3t)rh6nl3 zyD;yEMd!;92>w*}HBR7gdV=Ob_R}dn8}S*?$~P0;L=Vq!IRU@aIrhxofrn}eS%49(Bztd@qt$2@fm(tZ+ik# zHGFOgy@YSvx{uMRaF-J*)%@-sC3&OF01(F`N#3+g5%o$D!cmMKD;cue1Jcz_hfIpx32c(ip+V` zUGa_OyK9&CS7a7?WTTe9SH-BU+JE8X3`w2K}njFZO|0r4zV6`MJ)1M)hrPT~J@~&C3=XN8=#2|HIkK2ePa0C4ki36`9kW)bG?TAF9Zl z?2+%*E+4MQyxAiIwafQZWVHW7ac|L2h|D^rQjzI@Gf96xBsTxXF%`|L#@DvLfzc~O z3CvZ>9^-J5?u6y6A(^|NYUQH)aShHpYNiZeHUt(?Y~#o0`X2<(JDgHKn(*?eaSGCd)CtE@SV-D$wd|9owZ+ zeyg&4k<0B^hW+OJFdxl2i`uLa+ASxG^IM|vHyJkn5B>uTgALaHABePR9v#I9<^BF` z<^k^sYpXSVb$0xy*7NLlWb8L4tj>-d#fN@<(1>ezb@t_zS>|QlfS{Yh)%LG(%?vT^ zevH1IIW||RULf|c_BIZ@MY|TwB%wLwkmyiNVbUK=&wIRd<}dD+Zj8FOsYJm{I35>> zGF2+Ytnmc%o1daC@F=_iMg27%_SGuXOq!l2)z2sMX&%i~Vwy*HJ+$u@0MboDz8ir5 zUGK`1M1_wtbvz;VNXaV{xlA%oY9e?F#J>_^9xA?&i`>rQqBOESYcg@wHsRE4^^ATz zIaL1veYria(}0NRCX3EiAw0xH{y4K`{aUQYLtI!@dxvt*jk(;Nm#Bv7Pr*j4 zKZS2p`2Jrz16;j+LW;`^HsDoZO79w~zYcSiXj%+|W#a&;@* zU*5{E>wA-J?9dbvn|7#mVym*+6%iX52%?s>W0N`Sw`ALeTF&`P7h;TOFO9hHa1I?W z<)YHouBr7)t2mzAD@-{*WIQax3llwz`K zrw3hq>i=QT$%LmxW7Y`iCTr8gbX2Sgx`tKrZ&NmQemmKA0dtybn`BOnIHQq-n)-e?_wtAJH^K%*{0^c~HS;g?L&Q7h$zQ7b??aJ8!t7LW%iZqQTbN2Dl z>g)*QG?TC@`&9mqy|kjMvw0fAp=k%U5yS=)Y+@Z?i{a=iT@zQf1@a_z8Zrjb2ad2rH$WO13=#^GuJ10rplxRedU%(tEuOLCN*=+Q@)^% zQROYPH8&#Ywhqrrbj$&{SfKip9fi0mg{@Tz+6; z3n$3M6tc&@puSzH*{4vmb^6toQzK*;SS%wh(3A!Ok)c%KQYj&sPmwEJ-O z#)0hREHF3iseQO2QJeYu?e&N+?!HX~ddeZNnT%CKrO}V`iKDaRw!U=`8;LGR(Cz%tgk(z`6+3U1hBc9!(3t-=KNV2=KL8A^ZpqP!`Lp4 zwaCX(x1*Rf8xn?mr9d)-TEX>0_w~{qU7=G|{-ZMq&@}bC%y?LBup8;nqci_p4k=p!e|H&f{FM z$L<72v<9fvk6Ye@@9%ML*W;FbF+*al%d`)GyL&_hb?Y{Vq97$Tq@@!_=2#gPcw0ib zI#G6n_s-4|%CO=m?6Q*K$-l*RzpZ`oMLEAn5ymtK=1Ba#)_$oUz46PTvPyF|Zs~Op5g8T_T%mg`^A7+Bg<%f;hTfc&NhC`%0 zXn?kN}cHN!JRG<@AXBSAI; z!3MMRoW*>lQHCh_OyVfF z#vsW1xD`+@G+i38VUv;IgQ8o_VLRY^E7`=J%Q5FB(E2t{nA27ra$x+S;Y!*0)#Eh{-cgV89q!Q3kcY0PVc{kX5_#frOWo zuuoKqiwGt6F5<1Y5AT8PRt>U6#gEb9hf~u+>9WYiT{QkNTtYMFxmLEV#@4arTe9t9 zerjbtv0<*6UW2f#30+(2N~}>Dnz>G$+z(Y8(m%gF$s(^*Ec`{j@P2j&^esKG)e-51`doinh%}j%JT~xo03v_GwO?OY~ z)?bM>Q6Dn;xLk08hrF4Q(^QPv$Z0OdY~-{On{8cwWkk>{6M*v}Zv@aBA^z8o$Y5Cey>Tn|u!B9P~D>SRKqeW@?G$rIf#*g2iZoq>askiYR*ANE3 zzMRJHLT({Zu@V=uv(jD2>VNr-**8Xs9qmH4-ob@jZoL#-$asybhz||Qg^X4;7Y=rV z`CMNT2=Gym(+E@XLiDAcpl!{8zPoi1eCEvEmB^xy76?p15dyF8ibti|oDM!k*~ z+2G8JtYa`mE8D!t!FfDKE#}=q^BY5OccmxbUS7itfC+Zr@EzDq_=_9l-j;bp;!8>p zckmtW=Z&c&?o~ENG9G2~Cd-lR9_4g+m0O>B2}vQ*ud^l^Vpc!tb&98Xr7NVXM^Gph zCA(Ku;Zc?rEJ_Xw6Jlr#OZWIo zRs%Mr#+2-DLsOHqBmHg`MX5%-|A}d(Mz$Hc<8Q+)?S9MOIo}oD^8b_hF6e*jG-qYK zTWCal8Y}ka|FQXNWt%VK2B-qR4u13f@|$0X$#K8=qf1?lQWa9LrB+55>uzOeRF(S8 zOHGtFR9M)PO#8hE7)pC|*0e7b9!vu9A@Vusyp$IA=03719)FVbx{L!RWz9=smOf=S z>i}b7OxA(Kl}ap+U6zbyTqO<^6U_q9s4x(-n>83^TZ2iSsO_Tg@nxm`OFQ6SRS;ZM!7TxOX z1Q#)hi#9$LVjGp%qm`EQ|B*eq>IWu&qG46`m&G~ax0s~)KL)zQ7L~qs(V8|!wOMHU zY8AI=`A1j$zh_R)_BVgUtDEI-c2j2d7FonVl(bEoloA(Ng_`I!0K+&c>8;<#9#pZW zpcpuxL#(+Nn_f1sN}ci1DW9=PzR&icb#!3^ehFtFKFoHf}|lIr-+ zkBL_EXKO2qd%+!16#@E8vKN%as_e^{h#WP@UqzYW`?$<5`?5|R1nV#ui#jI!n|9)u zjv92#vJ)S*qXy1gK8a?z+>GeY*oi;VPrkCWLxvnRFqUtOdP?lXVNMs=y9LF4 zEISdqvE8*of3OpI6gWL^Qbz)K7bNO4LlN;)hY`1pf1GebvgkMk8tXVfqEkGOlZ!Kk zsiEP*yr*%eJu9BiG8i9EJx7Vu^V5eJbQZOshiQA&EX$fqbQcZA=Rm@@d-J+wq;j0V zBL+%@dfgh7B{;yEo>Ql5aJg~*&EN+w)^h)1-s-?=oFiGh!)!&q+{R9m87I@w?8OZ_ z&~|G4kc`AfICRQs$Fp#*DL>7_J8t@Qm}!VHX5kS|E6_Z{OPb6>9bwoHGwhI^GOahr z?4@$1o?trmREZX{8x)c~VA(~RZ+hpUDP)f*J8R2%&0k8TaC68VQ|@d_v(>WP9t<+A z62HwXy!#O_(!uJ&@sXE`_TcNf;VLpW`dKq~nXU7PJE7Ki#GOzVdBmMi^+c$lY|*mc zwlSaq*DJCK)n0|x(*O9T!1&i*)Sjyp^W z>OZx9wQUGr-^8lW?%7e=3QPNtO6P2Bw9L#WpRFRbXP0nt;hw}o=BGXqNOTW)YM+ML z%C^teVd=K>bJe0B-n6vn8+tb%AuJkNTUNP|(*>Kr;JrPoGupkkOMFAM_Py@xZhS)} zwe>0*>rc_EM2Q}m+cdR1B4o324iv9kG;z~1Zoa0^?%S{!@~(}B)}B^*EzZDAXLhT! zI>elb;e^YG(u&jf1d+pw0)4ak?F|)$z-BaLGP|i4yKUNj?sJ>Q77W3x;|q+F4g~WZ zgN|E8@I5Eo`YtXVI>XYzE|9ct_V(H-X4=iEu*owwwe#o3F8Og*~g7Xqen%i$g7j13JZzTDH5^!b2w!uc9^0$GF~4lTgz$n#_nAXxzu(x8qI`DF$M-xtt)B~#Z5IsR9Uf^aB-odV{gjzza?RNH#J+K%-@uuOhy4R#WOoEC zfu0NbVmZ$3(kLh?o>#oM!vLCTLfJ?F-X?RnwVQPNz{ei4(f-!>+$SmdzvILoFT+Vg z$=}=AJbtPk3(tk`2C6wM7c#s^cVW{W$RS+1NndQ%${~20b25{#m7)#>OnqDo2uA)`XZ`7aP@fo zzhRz;ke)7Ker5d$Ec0vN(zmP3ZedG-@~d*!q5Y%H6K~RqoW0Ao-D!8ZqFowjF{Li# zWcZIog6NXgX$t9bYYYf8Y0cu!kKhid=Kj%g$eB7P7s#9c3g!{%R^81K{rMA0;VVec zc68Y&;e8X*JogcPaRIb&8>w1V0H}e-8YZ7sHLtAKhm$>lri{I(_{w@j^+254CIT@G z?U6z6+ycrhBhd`9Dut&8u>Ej?k$b3DqKKRrWdiU^79PO{Y)>R$ZtsdUGNkoJ2_B ztKU@4p4PPQd?#;SmAkPw|27F13p@mMQ+1Epqj&iX@3-|K$+wPS!lMSInoFLlh6XQZ z4f9y)$E?ZhF6p7QXII*pM=qVYkrM)&s=M3OT%P(G5XQ9&EA1h&hsFQxqgJWRt7zo%Oole;oQXZa883`!|rc*{k%E)xe zSV(zn_@&hMHEd*Rsf%*${5Xcx1J;@egZmJ>AH|f(kn;F+${bsmeTZ}FMHu^tipGvk zr$hnf$>C?Ym4mbWy{eBEbyq5fAGRI9YlfWncsBKfWocon2RvUHx^~kkH?}JC8Kfm+ z;#LHzHlVBGr>Bc)@hI3s(QMb$DlaCdLh{sfidLTX*ywc1x{xwCog({8?~}eXJfD@c+T214+~|(PRB|3s>ZWZx z@|k);jlR5HIHxedb7PXm`m^CO9*ka#%=d+N0};L@?bCPz^G^)N4i%gP*2cOJ9wyS+ zDp=m9-X>UmTi3yJo$08jPR-{-fM0U7#dozZ%IicGJn3)X2j2>w0PMNE`mSU?BK;MU zwD~R+`32V?^qVvr7OL2#D$n*}&st}pIN~h}S>P)7K$W5G!$VWm=hTMeMz(6AT z1$lqVq=#KXPNn&ykxv+kK)K0o5xI$Nk#dvRBIT9p6;bTS`$hug65?5un}8N6H$f~S zHyJDK0qyhE!HXHJX4vtqutJU3pAyoBD6 z6!HM$7(KJRolQE9XQZR;^7zXl61rb7$yuleALgzo$eQBmDVxXmag1R#b7cu{G(Hypcz6jP`pPT-%ka;+ z4?y$nG$J!}UXs}wZMQS*hpw;O-i1Ad(Qr9hc7Dtg>BU-msg+rr^^Trmo=%qWq~!ZZ z=JV{(kS1$Lvy2a>a7$&lnA&1aXFhsNH5^t8=3w_)3nG4S8)BlZMky%ZHa%3qWgSu5 z05r+^Y8!FluE&SUTff3Fj@6;hmaoFU`WU+AC9)_nQ7oZbHjWuS+f!wC8=e|V9ZpSA z-}a_Z-}Yv!uO+d)T`6#NdzYn5Chi#sF!zjDN+IfZ1s{1QrtzPvR|+XUh(9qNK?!tA z)v;KkpHMJTBZ@pD^V$|=NW$75vj=j)ZM*K<{iBvb8|cjy8C%& zd4!U8Hz+OeFixJZQfure zHkhkby*PJ-DIK~WmQ0`Jteyqb29qq_EPZKCb} zX6=38>#pki|AaOYg?c}?v>L~{MX~c1C<{OA)_$RnC6H<=tzMvv`;kz)Z@y@^%E&C$ z)@xZv_5M|RseGRq|NGyvF{E8mu!d=}G@6dR;uu2@GgIKPQKb5#{RFShet0e*y-hN0 z#F-`%HzYp_r}j?aCSSsbU3h1k4>t`Z{D=$phgCV{AdwSp%@BIn<>9yb@NoxkXD5Zf z-iND|l7FN3PkFzppYRpQxD%i9{!;HxdcU<;#9KuHzRbs4J;1MqO6jc%;7@peg->7M z{R!`1?)~N7U+Mj2-fxW<_yX^@b_u_GTsg?3JiL2YnVmP@-@|@n?dr$z!iA=Yv&k@(k-0WN75zEp}gpUDwR8)ULgJf>XBISjBb4 zHI4nnHH~|@81MXtV)xb089aFYE4XK30NCQqbrSmr51;=FLe64a)RgXdVF~aWnx~QT ze@bY~hg=^H433@uG$H5skUDMxIeI>C#aoI^;a>aVB2ce^@y~*7GsA=k?cg=stpT$R z?)uQQ&UxxW8|6FCrqJ}OfUcf2WcagOycN2x^=yn%r2ZN#0>+Ah2Ogz11&q=e=K*7YM?9v4(X?ka#z_jXfN{9s0b@_WL#}fw>*Haz zUhcuLH!1gU*j*uaBr$OnK zZeW+Lopb&;*uHPaJT&E@>sg##zTo^}V)`+5-IBI-j7;q3oBZ! zyQ1vuvqaxTnMLm3P+>88AL=f?_ESxUaPOs>i0W?AX6u#qQp5R!!AmTj{&?Z}I`{hC0p86a~P))17?0yT?P=ho&Z^1cpPP;ON~b zSA~$~xd?r8V7W({A<7~^K({nQ0o?|jkM{*cD8N2I)4A0L*au14>pdaY4br4YMA`Cr zVo9I$Pt;5wA(E3`l5*I&{^@ydrI|-adIX&{#ucZ4)KqQfje5&h6O12mNCOljR;7>VZ8g zL-viXQittYcAoaqoxPF1iLejWa-{*Z2e*XT;fN9NwbUEFWo0c55x(ico5Jj*5*-U$ zO?1o1ttPynGpr6lU)UE&l*_n#=drM_Lf?;t-8~W`z3E}2d_$N`D&m;>>Yj4F0$yg? zZZO5I4hn>WT*N`g3glMi9XHkuI8rP<_8AG zR+aVD<1HS%5jm_1Go}HQeomwG=|rndh(fk?*r0CWc!_j`0-hv5qZck!^IKiUZYb-l zz{V91uB;tY)FYHgCQyk~E#+>p8^YEK^Q`0$%64{BNJXHT^nv#eUK?iW&9e+}O0x$K z$ZUMKhxD#^jVOgbsaPbJlN42snn+|lxdXf!q1fh&Vo?Zy7^qr?!G=PGzn{)C%4j1W}o6+m(2j35JFH)70AI>09!Ak&Y^)v$8K^kI=C$k;*iYc`D- zm;~wgRjMk`dFXeptzy!oFbv5D?W0Pz35Mv|Eq4I6%BLGXbbGr!XTq%^4BFFyv(b4s zS%=@5=7Y7r&aMw%9o$WC ze6#B@a6|ENM~^N2-mdJNx~h_QO2)iW722iWyn58fSs9y zj640858R5UB#V^CUE$dKFOg(z#>$~Yg8z}k+WxyFHuQfZvHu=PaqXDwsU)VgWetR! zUAQ^huW$*Euu8KPH)qWz;!k@2s7u?LkN^qa;KR+L;jj1pBDwe*yg!ip+O5mZdUtWr zfmPouK4Z>YMdy5Uxd-oXVDo-iZmV+VugZSpM0NAj53qR*DT9xeHoJyoI`I?C&f&o) z);&8ov5r}diyr;V+X#7z|3@$W^{VFAsv2KEBX;|9y3xg6LzqtdeDKh^2_T=3-ML5y zji(c1{67!i+*sxZ4)AI&WlTId`0TnT0DLNThhB}~YdCh-w>j@0%Y2hxv$9oO%~=9gi>+%+qPxBR%Kalgg`iPenZHa3RgD|UCf)guhle9fo17!zoXlPuUTJ88WcXD#5louyD)oD<DyG84?Bg^b*O>9Uy0Je&hAL_r_modu1N+*a(qa;*&ejxHHTM@EsA79m_ASJ% zt-GIb(2uYZA1xjDT3za^4^~jZ17G7dO8X+k83z1>2BSa)q<9m+IR@C{0n6STaIOK~ z=>f~%9I(Uyx!Tl7C*Bm~b;5$6v#y1Ciy8#}P?I73n09G~j z$4*z?RV$`q*#QT5_13j@{R3ayl={+Oq&@Cy;%)%^dk(717me!5T|JOl)jXB?bu3eg zzGg4$Rkz3}R|%oaNOiW7{l>g&GPYiqrGAv+fZlt2bU-w%k&6l}>P#P{7aA-@S@nv? zW1m-}BZTFoD2}4aEyZI#DnZm4QB=aB{>?{K5H%-?s<5bk@KMW&nj1wex2W5FR3%X* zQBmwfRdz(+pnSwszviCN{x$ih}>(0cE2mbz* zz#>Nt&_!a}gVym`Dc!e=#M-+P+_-P6$yT2!Q}2(J$LA~3TK0UPrXo7s9gvmo#wpsw z*;!Fn`OUMUSWpzQ(lv`A_dP2sJ+mU+_pGe!nic83XJw_|M;5Z;0$f&xT%={ieaDrR zZ&HFMXQdv%H_wV1XJw^nR;2r$m6e>2EM&z6xU96fNXv@* zrbW*O-L@5r8N-YFnZ{w~ebzQ!F*G-(8QTX8xol6+;GuW;omheGn{v}VFV;T5ew6kO z&=1rtE^F`MLmNypliE+le8#By&=4AuyFFo752^PxEI)gaY{M7ZZBpvoG3e9KMPp67 z;zyS-XUBmY7~582bM8C>SnH!mld05v`%$CY!xM;Lqu66LtU&xYc zjN{$j$Od3KwB{}hBD1# zI;K8KH62`_RGYMYDc;vca5Q!&wGHgjaqAO_FUfuqKHOfet_AEMvt46ur`;6WHCfTC z1JylT4SqrRBlclcPy{#|)$EM0dcT9U5*@JRhHtQSmMeU7$cq>8&K{Su&MD;-ze-t0 zZ6D) zMf=3G2=aHuHoagbp`Jy9?d_KAdvYoO}J+VRtDy{g*6YEH(F;-?({8QzT1k4=G7K zNtkM41rCB08nw3?K|igt1zBzPa~=z8Cq!^k1Yb@aBvtL0QYDqD-BQ`Kji~-`aBW<(DzEF8svh72?O?~D#1-*r_CB@`iV%*9B|#y7ABiY!oGTCziKg4 z5(c|H(Wyz6!NtrtEUJB$nrUy7YLV9N<6|j&OYJ_Z=wgmSHl;@CrH@iNtJrBa{HT)d z)1CMnEmB;%7CB!d9SEHM9AvWQim<&>fXDeB39}pZtsNgWj~%#u-$xPX!7y8{IL6r8 z!81^`nN1~_ktPDAKAhk2+lsUhdN(4uGHll@1S#yrW$g?YVMW5$iJj;Auy2EsTMQMh zhm7N?H87hTNXOeP8@RUn25y%Nr#L*X_UQr|%^(!eXg0;6xq`Vof$t0Z5^{w`Qo}7$ zcO4dYDSS?9$`(!7>+%e*;JKw=wzNbjS55?s%ZxLURwyZ}1wBg23`M=6#_GsD$lj^l zVV~+F5^?Kphneme@iQ6vrjWGJikp70J6I>d=GlJ+PAdzn_XcRV6;9olE`(NsEF{X^ zm->|oQ5$;L!Y!hsEY$j`cy>bxxfWZ2F-Dk!Q8{5$XlhuTlz>=19UZ)~)({!z0F@ah zwFO&dn_otZ;{u`vhe)}wi5<-yjYgQYhlshO=S0P2EAA-gKI8PX{z|BTP3Lr!6aafKBuXjXE{xy8NT%?1NuX72yak87)I+;<` zebxp#8?3l*;7tKqKWdB<4(>)p0AUNt1AEqnF9BgYU3+tuW-T*_QHU0i1@mGdq{D~& zvJj$$W5G-+gv}ndOIJ>JEp9a2Hln)>*t2yq^?r|MhWd~XnV~-HLuRNS@gYXt zNR0cCm&8jEBM{>y;KO#;c8*$nB$+6ulRni9^(h}RLtRVT;(3O;7Pkv|H|k|R#Hd$9 z)GG_rwfwDKi7S_gx)!~KXNJ0#y%jP;T?^kQQ(x{wX7aAZZowG!4H5PF0(C8pzmd9@ z#80N4@*y+SwJd%zbuEl5q)_g;h+ap5o)*hZEL-(abpy9cXKATWi5nXRs@A$~sax1) zcmo$eDU@xgH}cv7QH<7t-eAfld(I-+dU~Tw=nY{%JrBE+TOm*AN4Kc>7WGC<`BZ#o zzh`IXu-IXyz+ZJuEIVN^jh)hWzMo@*PrEdoiZsTi9=Ane#9AXej%x4_l=4!Qc21(# z!Y8dJu7FP(9O0AhM);()e5-Zql)gszq^ZJJ4uirc&76%-IvL@UHb(fQhY>z$py2~g z(&LeiNkC{ik z7I=K71s3e(?4o-#Bx;*-ZKP&w?Y}@d7 zZ66hQRr*@zc-0Hwmq_%+rbr4_{%Uvc32$^Iio8=op+NNw?+M*uYc0I&q@Sobw+OSt z_Ezl-Z)~e+Sv6F6H^@@5153NCVwvTde7Bd9br$I~w+>eme?0t(c3q+uS8uR+Ap*3K z0{IX?=*B3t!-sBEXnhpg@V?yLS25t;Bw@K^`~tg{CS%BeeNvn<#3 z+hIF9AO$Wrf5N%2a$?nc#0`-vd z;a)y%o4=k+I?A$fo|mNPspg<1ce#4$`FN&GtWGBmu%)TwZ6%`49ueKQdc1btSLPTu zela|rX;YfxY>XqF?{sH|6gK9LAN#9G`d zn&TGfvegyE)lJpQzDWibyttu_kTrE$-PKSODxo zQmZazMB>g!PCUM!+%W+&^otXiBBxJ<^Pb;3U)n|9-NDc7m-QljP4iExu3M8``O2Ba zMOA;y@x-cYS6zIpYTcUVad#ecO}4I#SFs!Re=sOwl5Sr1Y>pW=KdyPI?2ZI>+Rzg6 zZ#UmkR75b{vz9ilJ*dex${MSK-qMA?*f!Em#jh+=P-ByVzNa)KXxwTEc9-#}4Y$&A z!k7)aa>|`k;hah_@X5C@xCX-&8+EI~yRO(;T+`gx52amyx*4hm8fA?2XOv~miwVqG zkP&O?;CoH;-Qo@*&KpCB#?n?yhbryDC7cudcyr@d@skU0XWX7++FmnSFfs>5Al>1h z+GKagx-6?vmf7S*ip0D;`1d!;vKfHT8GtO5Wuawx;cJ(^geDO|9kGynd`Ar*WF(2B zKR#14pBwxqNgFphz^0kloc}z~*v41##!r4)B)a%Ej^#pN92czW0DA&cGoMA64*iKh zDc>frGCnK^jmryPDSaW9jUK3_EsAQ{6@9VB;DG8Qpc+)s$zr3vKHj|Jb41zPHMrC# z#i@|KW*fKS6B`Nd*5Dqn&^6^BxLG-BaxpDka>>~cE;-X!L4SN6nfV;`pF%nA0A(*d zpbiu3??7XMud5;O@#dBb`4pYy-c89pv1Dyd#J0+lkGHDN10}uZr9U)b(O>W&mqFD(Fd)?{Xad0k*0Kf5Q7sbVc*L z@LP%qRz=)7$(?9cFo6sC%=qr-Pk{Ut<-PI@%j+-~Z_VVNFlD@2E*VeStz0*+^!|G` z$WO-WUHIb59Ng{(=U;06S?P19r0?+Qdz`zwA9wtH@I;Q*=CIq}dsiWQ*&PjUw_GQ1 z^ao>$E>HnAKdwx*loIX~u}oiX_2E4-Y*?C@PlFUH5scFQ8fGnFStO~(guVbz%>qw) z@KL~3aRZoWDR~67kw`cA*hdt5pm8}~{VA&6M;&kpmy=Mz4L-P^VEJ>W_&ZMV_nhMI zm!IC4jYG)BE=RdCk_y$fg72D^g%61W-sO1J6kOza9tHzhc&EHXClw8%zx3c6J@~`c z8;kE8^$gtX<7*I((ru7Cee=S9vNG6Fq+}eS+USEjTqW2!spN!j_2F#>-WYiBCLjC- z1s`avAy|JZgqhC`GoSS{pIiN>u(x?M9|esSY9-=!+K|*2;`jkkYnr(Z1n@2oeyO9n z0TBHuYL}0yP*n4dge$fkLq2$kOR;fQiX%SicZd>(@l*U$r}#^S62V3AWk%vNHH|-S zIL+{o*Ag#!L;pv+;!k(y#cemM-PL2>x1@z|Z( zxF8xGbk|=#UcmqQAIb$fvdrM?2gxEMvtz4fmswW!{Y^xiLR5G_<_LQ zl!;NcREUWl$HZ@gS*;9AXgk}Q<6A()o|?2Vllxs!U06N>f-z9&0egL z#Ic$zvrpR+>;Xx<&P5`cDOuh8H1Bmu0E|*>`XwK~sR4fMHsOKW(!qr;AQi~V{9utJUG2>AGG&==Bv|A6qj9cyte#^x@cglU z<8L7xA;tCDlGF~++~qBobt&!xr7ah0U~&7gdSaSa0CxLh`nUZmKNGx-$1e=a$C7-Hn)fvFW-+Qpxj*@XHlca=5G~YGw?sRZA z%eEKYAG_;)lyfZeZhn>FPrkrTzI1#6mkwSuq5W3no?!Jsu`P}UzIM&}FCDYuR|)3V zqj41W2+vSxkItR@RV6hBOb7EWmpW{_h*v_(Y3r1O+kXI;S011oq*Na|P(5xRRgJHm z5zC0!AR3c1p&t!PzG#&yEcq)`P-PWsY|urgfOK8l|8G`rpI!GPG5e}xS3DB?Vn0#s z%D)CnH7)J33EUV}WFZ$lLF{?_UsGDsa#l^tHQ2@_Z>jN*oyP8Z3VgB5`WgzHZ(N%mnw*Pe)_8M!+kkB4X)P|bJOSe>kcoYavLpLT z-DC50Q1UsIf=T~>AWt2ABjz#GCBE*3Qs&J}Gc76~`0KkbIwa-!J%MupRyp;Z+Ig5Q z4*B&wQ88Oxe&#I4F{#TrBDC$I2V;M=N7IPdBWwq?lv#icD#CnxRm1AW!Q$18d*-Ze z+#ggoKQf{Dn!>$VdZ6>7JtBRTNFS{o9e8&7)*nw?f$!r;N2d8OKxQI2W#@ryOXo=K zC~^Htz?t6KVSPL@@!~9bSRWkoz!j($eYiAs*XPjbSmx7Svok07P}JLFcm0^ps_#pn zvCNP7z9Rent1o_}xwn*DG`>`v>5u)xp7IA`w?7R;OP@lyXf1p8XD-iP_HOO2{Wjri z>h=tLZQDg_2Ae+n!z~X~XRC^wx$5wRLuW6>o|pY7gqPjxmtqk6?Nw|>rr z`2@ejl_+kxi|dNrb(O_k$#3JH zx2$;h*57e4J+Zs~P%+i}wcD&HR{f)i_u%e;rcRhj2vpZ_|OZRGj(ui$d& zE5X^%ec<)xKF!G!{`pOG&}TKf+Q^o<&V?-pSVUI58vE;Z+$*!|ZlYgvzmwXUZ0+Gd zL34NNlk=oj=rE&{~Ynr?39pGC4ln4Q+z*(KGp9Hh|Ldu}d1R)V3FT|Jq)EV65 zyg^{i;;6K7?^~ODFT;NyW}&FL^}T#HzXo)I4;h^5SEp1zVs~xFD#tRP;a5A{8}~{O z!HUW4Pge6}B*0wxD~7nvSLnGuD~U7lFH8&idWm>4YbpAPKjBC7?1$I0A3{A9{-+as zrv^@X2h#Np)SI!YI`LhW&t19~fPd8t$>CK0#AQC5j>m?VWTO&1%=2ec2j@C~8)N_3?e&Yh~mQtGB=fq5?a63VVSbxW*vr4_}~O;3L2e?71Y|JMnGw zNaqi#vX?C&GyN-Gi)FWAkJn`1{|8rQ&we}aBIW>DovkUaxztX?SH=E*@0v^PfPSof zPgN-<_G2`mRgJ$oGj_+de0?~(U{3R))q9?w^Xj41uRd8kUDf#GIjg9SRVxn0?)((< zCbaRf+rLfGwz#g+*V5sI2kG;qE}YZ2r?@%W0mbZxiY2WJ=g{yM-xAW1J6PS)JxUD0 zp$g`3YDsnWxBsBJxm)mLd&w2qvo8RA&X)59?%=pHF119FEm^Y##ZOeXw97nF4V7+H z^Vq6pjyugCcbgbjEjhfVrB$|JZShNMi=Y2+_Wg%Hl3h2iXw4kEaDW;vfsjclOfY}o zilt>&(-&Pz>2gT#9UsnKcyv|s(^Y$ZamGN^_9fRM7|w{imzt|&N^*6%rKu<$?AF^) z*QWlQdED(wZYn2#j-w}$*srRK53MSGY}JY;#hb@#8WV*uhxtoj&zh?M&F#S@d*`^dgf zt^R}BH1UaFIz6TaOwb1@x$p&Q!}LXivBq~%r_>5fJVP&rL8c!G-SJh74^2irrLv~k zt(9{>mkP;_K+4tQcyigc)bCsy?GWBR?EI#X#J5VL23cFU@W~Uu#%3GV7KfDsqlT3m z?@Uqkl9{CrJl4QrolbbHfyWvc)`{cnQY+XmdU>-wPBEjrG{_|{#*KCox^TCdgF#Kd{ONe~Ch{BdmVCnUW>i`n6&;3ED)MGj$eW|W zt}&y=x}03{)??TMPlZDOF8<`aegb{4^C-KJ=dV{?{K&-TxkZ$AsfF_<U=3GC4HKy`f7v$mdfocfCX;=a~8tDZYhA3y#dTR5f0nh0$BMQ zz|^DgM1QXUmUshL#SGZ5(N&j)iZ_6%hvBguDS$111DLuN9_;@BMtt=g>v%*J?2`v8 zBe__`Zt=*f57toeR*j<}tHvj`5Nhp0^T5Q{t!}yYh6g|(;7oM$p$YZK-1#BZus@h- z&t2bfg>~Ly*?&fbC;kVqxs&ww+^a^dKBn1gNO8yRJWH+iJz++^i7sT8bJv_s{I0Q3 zZEg9)d^{($Yv)`w?(uXxJbx`b_j)`Vz=LTuz7I`&M_b;h1oGlq1EdN)>ipe)qQk1* z`1&6)ahwl4aNvN^Wd|I1U|&x=e_Wa!v7tm zFaEz!I>4&`f7wX3MzW2J?3KYYZpt9*{^3Xe z8!Vuw;Cu}7N>$s%FWWpicHlX5ZX8=SwlUM}0H8|1#ZX^%9e+h@$l z4l3KZQiYN*DqIRKESPkof=M?jm~=;l4Q58=O-;L}5_l>c&H{eoLf1C^_hiJi9!x== znvw53^52*dPvw-1+(X+m^L~9z^U%z6`ReA!tNz$OVQ(7)j&o7;2BumEs?x##EYt7X z^mBPBh1J=Gp^)!W0h8yKElw~{;EMU7i@BGdH?&%=PONVERK=>>?~mOc+oWF1g1y`) zKQj2l0zDlXBunX&AHkrqC{f1A=0gi!(Ds{S>N2&Kshtr}&05a$o!|tM+JLOPXo2{0 z;%l0@MlK!XnlwN`*#p9qHsRCeh7@svTXKCwMHEr0Ay_)P5X)bIBWeMmy>`R|JRRN+ zZuQBMNk+?~+GJK! zo+Yi}gXM|kq+H$7+T{>s$0akkZPF$Ik!(^qND|sAfKazOgm!er0JU#mP0M?XUmrIG zlGWKY?=7!c@$lxLrg>VYxL2?EVeGHILRo1e#@zP~?A!h>u1?qX20J*S&}ueoSTNoG z=|skfRKb;$j!6z+xs(p9)I&~W>RsBTOS_?1R5?xfnQ}!YYgRlIyYsa_BR8Pbfg1;1 zU$s9oN~VieAIOZ$<&PUsKBT!=cNyJ_sd?u-XMvZO5$Lu@O{YrUu0WkhV+6?PnycxR z6oA0h{OBE*Y?1RvZmY%H)b!3j6<+4@?STTE@%SS%Oy=Q5zx)Y^s7afQ- zp0|-N-FpVSU6obSGVjh&!bUh@!kkGX-!(jvN9NZwA01>$2DuMQ6k2gWphG5|Y?(S+ zye$O7)BHcEvo1fj*`eLsAT*MC7P0gt1eA|=4$IXQTQ>R2xxFzafJZ)NaTPvJH>LFT z7r}{uv^bRy7oJegkZ-vm3KkCjyYqL6q1SF*xR6;~^su#v_=erEuIaMwxdP(;KI1yo zC|yUP8i(ZO*{_28=`;5$r$uf`eIG*Km+Exv^5}!8O((jAmGE|Bk!+~6d4uV?M;X`j z>*E+udeEcWtKrYB1P-m^M)ZpqjxjIeiry7po-4AP-*hQ<$C)3;G%(fu0BBg;OB~@} z-vb2x`6GOcF=x-EVw#Ez2ifOcJH(#C{=wtS935vu|7a~MdFvkqP&aEltqJgv*qvXv zk!-SnbH8LGp>JElW282k~?tJ2Z0k=CW2|YcFd!z;h<5?}HOu9P+&d&*?2MUMdNIcE%%{+L3Ne8W_pmZE_kWoe+CeT^x zNYGW6*mX&rrt;~yQx9(Xv{F8o<09v(?(;62C~7Vhb>P}0j?;?sx2}6-@T`v==eRAm z{GOAV0DX%yPD@yZig%kls6fnOeN46J!C2#q%ED3D%j*)QIU%QyYcsBHhle;Y7`}!a zbXn{e@0?+yMzAkbR;$cX|D(F}Xp`Lq+d3>BoRI85t_pHq*N9{kZ>=D5ym7z{yc_{4 z9Fs-qMUhA1aH8U&N;zL4j`GiDhJ#T{?A5-f-(hJ1Hw^Qb;D^?Y#KtF`AnbQbuo48YfG9!k;TAF;@ z5lJe9g&ju~ucTa#bI1QR+)BGSe4M=uPjQ0uC0w0UeT0^Q_ad&Z9po@9@6nyb-f1;J zd#-?H*q+2gjeoKH)(2s>ad=8P`}z&2 zc)lZ*vwkAmkxntK9J(_r)~)>SKu^akn%slu?l7C3EuvZ zOJ*ejO?(d2%`1DQSTeEfpTlO4mW(Avw{il)CarM|uwCgn_^e&TW;b}E=MAF61pxH| zeU_`qrxWus0)LTXtl(Ev{=?sau`1#fd}EUYzDfnlqFB`K7eba2-vn{ zTzX=bjUMqw`n8wyrxHUxurViYpUe$zw`{T$TNuv>IJdh3cRV0DfbB)r3-@Sx zEqR*ZfJ?5O2kpN9*lX4`O-)qtLqD+O+0vQh>A>BVkPiB0Q+JjZ10a-C>ro~DqEB9r z$7g~YIxK6rMsahh(;Mw}&sD3T-L`}-GOxEebgezk?F@wWQirxXn9Ws`sYoX36LxEO z0h-=6=XR_6G5)LjEK?TgxjLNc7G@-6mRzOcGbc2iJwAE8!7%gjB4~OYn!YLOpGOnP zBpo{$W*V-)B(_R<{Ven=@OSi%G79|(-+b8Xi()znHY4WLrKsk zLxW%99q)EYj12^5C9gJAC<- zWt!B!6521arA}_`4Qie5P(+vj9#vKv;A3FVd9_dCY2E7DaIZQv@kVNso;u+6 zNg5|vk2)TlK|i)y!fUvfA|F_V5$dGnGTs`r=;*6tF?>mBEf;$cNR4bLog~TQb07 zCYJdMhp}_YvK4o=WfLd3b#)+VlEe>GZKB1d$yc-6xzUL$W1Sd8bU<&|NJK>TCKb6k zT>Sfw$V$asWz2IUr05s$Ida!?UC5312$Q%> zy~EyKE@t*zTC2AtdlTllz{;z&Oxd`e9{eVbSh3j=0g7HGFrc$I#!QM*0Z}YdVqzct zY}B$yVRgDUw~hhFQLOx)O`J=IpW)x^FFZ-HMoJo1AuCy*_@3`VTJ33=?=ToL6cXvE2eb zTw7A)C}fp*{47@^tVW3^1KO7=IR}j6_i+s#TD9~?!n7lFdCiCO?hrY`A5u8S=FB}O z>{jk1lYVo9rT?h-!(q1sM|f7%mOOR$c(`41_l4am3Z?6E=~mw1@OoRu+MlGSi$nyM z<{}RH@1YuA8ZQ2nVBzIMa^b-WkFw}6TEU{r9j=vE%iWexX>@K?+!b6ZVTu$uV|O0< z4R38OU3b0W8pD$JxbzF<4(z#rR-AL(vWh}f?|>sUZqGUY!p9I0ueng)(%hP)zzgUL zPm4PD_FEmR)p&2|?ULk9-uAjXoY$srq$SNlN6;Wj{9Y3^laE5OE%B(txRGyaP&hPD zbtzhk;2JD;3Fj4A<#9G;@oh?pDKKH>xiCa9JHeU`7T=_}>BKZF_*%vBM8kS6FIu4L zCh={FOp$oqi2+)1ovt3wbP0JL-tP_)sBsvtH4p#P?ix#iwG|cCS%(!^m8MBbvyPy^bm-eY zL&(v76(f=57K!PXdnp%GyYOrv|2g5x@Ba`fvTy5?=El2AC0!_#TDo9ft&3l}#<>fB zTW%wzc?mZSIcqYnlrXqqdXj|RB+NT+7GQ-3eBq$!43nFrR&y-M&nqxWZFP*mP6F*_ zBQW;()bENg(!v$N9@^(HnLQv;lf%TFLM&<5yHpG7gsG9C0wgOW{;{ zY22y*!e<_EyowdwNww(rgn=4;9}zreCUY3iMn&^IL0`ggZ>2_Ua^`YNw_)R!C@aFa zi$^?P@bJDV%}zS1^H%%tNe@5j!{6<~+pSS1{Z$@r+`+XUadfi74&HhdnkhOYy&F;> zOld`coV0hDp9{ZSB6q`In!&Y?w=x9YouFoF%)zxE@$ueLL|2e!I(+<;k9U=tE`j{V z!;+uhk8r?mxBFchF8XWp2Mgsg2ps}ULp>F~>N-K=K8R0U0jOAM*giTki++z(cxtJ= z3b`U&w7`YvO|L6uxPyhiB?_RcG4TWopJ!TJdQIOm$T;&5mb^@$T>v%~mb|F%yQxao zgo}P6V8eX@cbb90QM2SsIsdId=`#hE>tN*_<`0%yxKPaDZZXk?zHEd;bxzoxaLg>- z;_#CJ&rwO8P~^i*xgdlBXfqNtJAb4&YMB`c{NHk^m04Au9VurX=G3mt8Ww+Gz9lR% zf0~CQw0x9LW%`93cb9j2yxZm74)3;kH|O0Z?>2aMtGTtABJVn#ug#baGi_-#h?c!f z0>W=PjC;iUO-J!NwM@CXa%os{>;O3(2^X7-`sp$Ql~%MU1V~Qs{p>WiySN?ceM5a^xbRC#kPnu9RqjC^m$3{5%f4X= zFQqeZDGGKeFUVaA5&+5tpm2_N-K<3Po|exFtMg%2(!06rM4bTAm3hSHIzsI!??1=+ zJ8R?@EX>4Qm}_1lzd8;F>3SL*Eh*>0KC&PBJjFBWa4n9>uPwJ+zc%jR9z#uCJXeOD zNxZsP>b1=~L%{S63@~44F&92C=rUzy>5{NDL6HsYIai&@U~#)5N$lKsuK}GKcG}

dH1|cxf3NihU8C8;lV&^UNuU)!6W95$zR^he3d0hehjSGr=qwe!<6(DBf~6wZ!t;)>X zabt{v4~9#h*ee>C1*7AqAT*_b#`Ibot53(Rmu>w)!kP5PM`KR#e=`u z;g_K30AE1|_;9%Rb1v}!)4lX;si)R4gzGvN!OQd)=&)y4@*xEr$LLU6+Hfg3Cn^2t z)JKaJ4TELpSZ>1-b6Y~U3bO-ZEn%yT9f0|@P@P4m$CQz-uFw(wmqwEpR-JOVi6UBu zBTi{rHyBy`UWtd~QiA`abfo|C9&0778P@17-fcUm7zSpEQ6{!K3Ym?bg6pECdg~pg zOwuR?ORp9DHDPrKOkJGr(lZJ6O6)u!m`mjUE?g zJGx67TzE7e6)l|h4I9p|+q#!|ZnqJxZ3!vo%3G9%yqFq*+x&-lLrwKC&4666%oJ>p zz&QVi5YWmzEh!Q5?9~tRGHI(Ud*Ca()!UK|rKOfCa)1x@mgrxT*iqBbS*DMykb|Xr ze_*+?Ng;Hs!I!QiGGNmp2;&c3SjJizXuDP2F>|_w-#y}y8}p*^g>QbP~5vF`5>*$wLCV-|6#5K1wsK-%gt=S*E5v#YPOne z*yZ3vXA@7v^+xq3r|^R*n;t@xJ@R5(oz&y)yIe9q>+QC&3jf2vjuOW=i;1jx|B>ZC zo^7+h>luUOYdg&tkJNS=(^&BL7!X>H05lEB`f*sYP=Uv5vsOiLhb@P-Zn#OK-{n|{ zs**h^DHa|?$Jpw^E!!$OT+<=koJUZP>(uCYtro9pWy!R9%oK}bz4nL7s}z$sKY~n`YUZuEDrL#9Jo~jhihhS$UtdjukRRj-)abVj~}P3awBT zssfV9^myLXYGjOITrrIQRNbfXXWOh$dWDUYi^N{3aHT9FqqZuO^yrO!+sb<|m60JE zs7kYvbzW_!)yb-JYmadstG&O@vSDZP1?cRco6h$z-PVDsE2xCKYh9I3^9-jn_tKP` z{XHkuJubhl>E_$Sh#QD@)j757fIO@AHPE+Ozekr`OETM+w3;sC+U~9GOM2@?_C%sr zrK0O$>m6M0q!jWt*8Y_fOFAozYv2i| zHVi8o-8kah)={|(XU3hsJ7<-fr6%X^bG?^%-<0$BN^IKNcE>ktWyN+j7FJf=Dif{h zq@eslo(dU?Znl(;Y!3hU2bEk(&5+b5Py0nGgks6vl9^NcbksCqjg-99CAaIN3)I~* zA|2N$QQWpdUl1lN+%>oRWAv(^XGEdM)n zu0g_nN#(~s<%koUHxsE_q`50d>bfPi&Tr*7*FIzVL+}BJF#s(}~$>W-CYWCDNqg0sW z0*8rwS-I}Cy-QZM8m9de{!MF{bkknDef095fzymNWlRTg{@>3*!G1y&=rDJ+B8f?> zOo3DVd+5V&OK|7>W|o`yc^IE0%mwt|9lV{Ra zY};-vF7Q^^7*pGu>7r_0mMxXQc5YR;-Y5WjQr~I6ktpxi{-6?A+S>a?~mM z%LTRnt{7WOtXIsKwm+VgdO)B_1#D*2Md8(3)|ukY^Yom)wJowSH42qe)3or#jzB`yDpe^6x!7yX53)P?hI`?hFt9!1Cwr%Ddpi$CqU$K%x=_>Vtn00EFrljkJnQ@0>W7%V3i`&*s5XjQnVAwGZv?mnpGP#r1^?>~r0G4n5 zx6;nx@df2O&o(lLds(x>ucQy@!k2wPe#*;6QE6T%aByz(M(KZI)1RPcRj-uvC%Jc!>Jx7>M_E zIYyk;?+cers^AWXE04%U7?vUQyiIUvIxJE^(s$sOZDOk$PnDSGJX2R!r(oy1!oWII zlTo1NSju4KKe}+YZGnljf06&FiY9Ptnfcm1+5$PGJT?03>+CBAuou2|B-{k;Ea-;8ngh4cQ{g&#%=C71KL^tlIZ~YNM zXKIa9EJ~NTRL~6;{nC`1aNf`;!k!K6`3qiA&SS-W$^q(bl+Rw5-(b;qm1-=E^10}t z2n%77MU<_Qc8j2%o1lV{Zu4u71lxR=d0hD!L1~@Kgz`B8SnQV#bXnZwF>DkDvU!dC zn4lt6Q2CEW`j6aG4q|$_Z(8( ztz!2JiG(LjJ~r22OL)XHhz)H2l@J~fLL2`AT!+GO9RurA37VgJJ z7>*_v?zY%miT0I%QD9OdwE3G#Fv(}w6nlwdDaEpFd zalrhMbLV|fu5?%$ly`UoOA{=bqqy@}LvcLyS?h>0TC?WytJYJymcIHg!b|!Q=F*j( ziBs1V2<9DCoZxl30GaGG*tl&8QvX8zt$F{bz~f;y2QjS+J_EL6bTUfj8K+G5Iz8z$ ziR}v)XB?JnM8*6Rzj4XHbKLZ4v){JDR3rWtgM2A;tyXZ`qc?2^q6>syJtGO~aBazX#t%Iz`R@(q-DB~=yh~hod(IV5rp;WoI#Ez+ ze)VdHJGq4U>~N)4@(W`sSY|Gz+of>Yb@NML2dyM%^{=#cVcCP0GrhtPy7nUi7lfH6J8ZZ52?X&PWX$Q-`Fbj`KTGAxFm-Mo24yWO9k`0#KGz(8b zs-!Wg-WzsSiXSqx)TNE2`W%vLw-O`n-HN+6bW29~SNt=6tRp+D!-psWZBfp4$xK}l z&U?Qi^YLy&%#`V6@*j?Ns0Ay3{=f0hbO@b5&I#wu_2~kcN76kCoUQ~K2bmvH1S|hl zi6JJ5X$1pFEMe$@^eAC&wFq^N?W%ndoqkt(@} zv^w{xv)*a8LQ8k3iPmtU4t`C~?7kX7ZSiug=RH`&o$5%0CG(X7CQ0Asa^e>AFu9*K zzEDs*Zpo6gsQ@O)yQ8?UQ(j<)xpW^j?A;;n_Ir1icYD0s<=qZ*-+WQeS#$6^qmqdX zZ)CW=WwW6g^0m{*bI_qwXkjcB5$2q{rmVdw{OOwOaRyL}E!8zB}2#@sU6TjWniBW@N`t;bep+x=Wmk#(>CBg9(6 z)0&y~Up1<;k2N_QE@~xCmGWgO$kJT`G;^gjiJ&{Fe$Y{Se8A029Aq8LamoH&UX@gi z7(bhSv^vSpkR3PQ1?MqE-b>}l zvzC9HxeU~1q#yQeX@?ZCK3cDNyv$&^FkErn5%zoBVE2;@gD&C|x*}L)sk=Koprt)1+v& z+r1N~@F}S^cv8kru&}?A^cdD2TpD1e><_}bGaP<*e^AomBF!wX{H~=4OKuhAgRBu_ zfvj^#rZx)eZol6vo$6~7wQY%q#9>Yx?G9Tj52+Dupkf%8D%k^vNRBKL&4zkD2 zdUs3>DQmQ_%S4!jJ?3Zkn{|o!?lKuM8nukVw1iHYW*1v zCL0BV0SUzjX(k0!HHV2;=xWIi#bnoEt=rRz)n4v6hA%n?mff)ALWNzxb|9DuOvG-H z55vP*!sD!2Qsst>l3&cj&UA?q3rYR3=yuAII_Fc@dpC(|nk9+ReRV6Nnyj^zK5*Mw zXoqm;1J|**NBZZ=L`h82S4{K3^m<8%R9cxpG1TwsBD+nUKIh|; ziU(J{!t<gzc;f2|`#VQj zwJ27<>z_L)MAb<_ceL9`5TmnPNr84F!+54f{^tFe4W!nA&S)|#lT>XLgRk8UXUKAGjrZCUB!qP42vJho&x$_iWTruM z5K+@&Cu%8h2BP>^H@Eh9_zGo|Il}-~sN3~Si6zt<9SX@*@*&jq9wfUUCJv+OonReK-QfKl_$l^!TZiHu zDAx<`bYNWWWqhRP@6)w9?UVR)>wj6l-nUZyoB!`K&s`;DG=IXG*gU;0p>59e2pvkM z^e$p@Fp z*qm6eE)hZv%`%`~t+rIG6#4msGh~ckPiLTN1=ppX;0;qQug&@0 zDnuFuMLx1XI`fe!RU};6B|~X$b97~7_0GJD@v8Q;Q#GFXWU0{fj5EX_wi{ifRno`)nex_1F>5(d=@Iv$G{_#dA6v^QaML4M zD(R7Q@TCC@H+48kK@V6EiT$f>W!B$w$+mN7Sz?c*LZ`pSRRp6sFvE|va&|~u`iA5x zWEIhqq%uMAJZZ|IK$WT7F%)YzbD#Rwc!eRKd)SXEgi=j9m?IK-x$K(Yck+U$lv?oY z0o47Y+z@b`mU=VwMyW3KG>}h&**!@=#zV|tw#NYxS(#E}S?tXGLEcs07q(9s2SHz# z6)ej{I*57@E{=x12~pPl62iGNbWIyt7pTyMo7Sh_rE}-<@$Yi}-mQYkvkl4)wsM!g zaUO4Xw+vuj2A}nZ`SbJp$^^V8>@#2(Y*HegYVR@Q74K`1|J=}>aC#PTKFh1yT;XPR zde8no!JUB-?Asu~FSvl>L1F}9G4;mB{JwHe%8F}`3|7#WP#9;^>+P8M#S1v_F`s4d zKhel|{?7;FVfRK-+v5m~?o!XHrW&P@uyd>M!V)tlscF)rl;)Vy7}LDP?E|@8g1V*I zmt&%(!|aluqnTz|+qDPnx-$TsVS-lycKrv|TT*2#X@c6BI?CElyXEAtRSsr*eQKe# z)Z;$D&d8@3o|8wWfjh)5MX2>~F8Or=cWvaFW_w>31?lYfP$>x}%~)N%9#|Tc7{uFT z#H=D{#5OvBz8)pa$J?bv0J>84M53E%vO^wA=M-23^%E|1=rqpqLH7ou>6P?})Q<^u6Ba`D%jf4_yRgxfcWwr&rU3xEMW>i~)e`A`aj^t$krR8V@LLODwI z8~End@p{=duZ7%bY!{|It8%n+)bZ<%@vPLE=2xNB=}NDTYd>~s>-_xD!FPq7QWo{z zO*Ql^a6ahVs9cRpPjP-VJYK&DfQ{k!I4RX-_H*X)EMz`^)EOaytX1KY`6rI&61Nu-g-E%iZ+NPl{%}V7AkB zcQDyu=Xc$c?ZkVYtnaa%E~>+^_*bn+j&4ka(OA-&vvf;3CtdnQ|8DV#rC-_!9F3!T z(a>4^4ezheE=CNv&2|!BFF!ojd$_L(4vn?Z$@V4P6&B70JGrm1bUwDF%$nW4Kq2{{ z?}+qK(m5$M>0?Jv8=Ld7>n zgv!U$t-weTWy+kz3i?W6M6r7q_An(Xw$gED@E9}LnkC_7mbrMZpCRfk_kNpcB0k~$ zIqN>nXPr4ce_CkijM#JS52jum7+a-m4zjC>qFk;N52g$<@1h3wtm4co!l_go#cA_a z9tI|T@?QbcSK~n1n`C$a5!0H6P_N4lc?#K-5m1QnJs9Q-0mk?sQ@cVh2;+RvC9&K0 zkmFV%Wbo44PnFf>jJ;Bh!JI}A z5%Xi^69L)2a0E0O<(>+AN)@xs-)O|R2T>K9RK6rAaecDJ8Q-%7 zWsJ`jlyQEFppFQks#r1-)P_id0yBneHuVB1^Zr1M4+1Rre(TlaPk6uUY5%7JI-Oun zqbUkfhQ-Cn88$v0HEn?u_=Z5}s_PsgjMB8(dfsNkfb;DKUO z!2`uy!2`uM>4NbB#g2jpid_W{6ni31fnq`w+X|?l*irC6v8&*LVo$*X#a$69b_Ls< zYax$nAqsgMjywg5DN)>2Kn2DAf(MF21rHR53mzyQiBO56%x!_9Ol^Up%&d7LinleX zh#`8UfDNLf1rJ2W3m%A07CaC&yB7&IkY<_(!OGkfh|1KROw{hRgy4~D(A z;Kn4PZI)yF*#kHO$OD>K=+HNZ+;ei-AG~JboI&_`8fLN<8>Vh9!|FTA4lV(I1Z7J+T!tLQ_ z265Q@jFkL{Dxgs5{rA-?eEQ}eYc$s5<0=#vjd}>5^x;Vtp0!b!AHfBVjx8zA8kP!O z(xHBwdT*WE2(yRjUmmE~xcIGdFJwOe1&v>+Ezo?s!zdMpeclz-*- zq*&L3rWsf4iNwlXS@1BX>rpB}Gm~o=kjA9KlzVd%E5CWC(X@x^2)EZXX>Q!5EhkaQ zc^(p{a88O?J+?XTNokb*2Gh(B+ZX44vB_%~s zsEy*f-I(s$vPU$g>(-b~aYJID+X^Dj;VzNM&p$TPBs~xH-kb#^ckxBjp+;}m%5-KJ z=XwPSv1#DGUP zIfG8al1$Rjxm)uh7&J=bNVs?j5I54ItWCQ?qdYZ$T5Y3cL<7#_mRKQ{l?S;DLZB4t z22mi(NuTA7_|;+esDeG$J~k2z=P=tSU%a6BrNJFk@5|1R2{P5D3ZF zMtjItofrHWGkPe2HQxx#MqkKul6b>txuPDb?;+`_Lo!=L(eP~4QMTckgwx$X!_2G@ zRjyta7gMOVlk!wkl>N%gRM^WbRsk- z)jtH_M_KNm*J&iHtVhWuVdeAWdTFfBs+Zjz>XJwVoJ?RE$!GqE2@u0(!?W2nQvAXNE~__n$&(XS zTA`>-tGag9kZG`6Cx@;LCs;8Z5Y*^^TX}!V4V>HopA+iOvARWbc?>PQmW#}*ZqQ|; z+Y%>8NGET;UyfxXz$1hV^1oMka(%;NI*qj*xD(nP$;O5v4T&h!Ou&cgePwx#y>B~M zO1IbT`br0>8jfl7CRKjCq_dTurY>dJ?Z67UH2NZKhaYgYX~3n(huBu>ui6N5Hu|!_ zOBfo+TA7F5a!b*Vtw1Gp9Vgu4(t0+XnR3)@k2eXCL7D z$F(6^B(%k3TY_PX+qE`v^G>~9*Z^nLsPoo8X*cPQvA-s-ZM>;=Y2L(p0Q&evh4D99FB5b zTAoL|5ZuH&{?736WCTs9tvE(cMQmH5=_q>zg6S(M6gI;&&ACU@(L2Jt4sz(z zABEFB6W{n-_x|ajPk+|@8_duC=+u^?BA;{){1|5Oq3kmd%M0F`iK{_IVRXs{ zA)h`O1pM7H8My9hTDINE)ZusgtbE%9yqihD7W60{`C6^XGt-WL{CJ%m>-NvA_{Vh8 zfhWcW8zT~UVyt7x&#IjxMxhwez#2jr_rwBEEbznvBR0|8W*oZiFgY<~A;yZ zcSRG|*86f?!^`tbSw1&9^Z1^7dGF<_b*q~nwa54JJia&j)}kU_*PH8K*IPAoaew0< z72k4}!#7?6zE!dBW)n=ru<%~$wp*~~i8)!FZPhCk*o&aI$o#!WyuVw!8*8%ZGDUXw z<5|`GkiOfS_+HD4Wm@gR-)cK3`LK5t6q2a~qUzVZ+A4sfy#+Wq=V&Vez6R%Ldn3LY z=Tzd1XZ}VT2nH%w-Tq4K_Q?+w6*Z)TqS)=PSBV{W$tZ`I{`D5T%^9si6PjeY0pF1G zX`>!KtzQ$TX$^c`&ZlW1d|IC-uHMCIJz7{?I<1P!$3_t#x0i1WdP|dqoCx=5_D40orlrpW(vmFY#T)H%$=Ed5Yd2pW z$Yawec*^AoG?9a+LY{K(sg$R}dy+NTq{UVeP_yFk&GDM-N6HBdYF6-I{oFNTv{e*g zt1=Lmm5jGFRRuE&tFW+23k$SWhmK*AEZZx5aI0ci)7(1jQKWdwN~OjtS1L;5Mbd1^ zs`UPU_TB|P%HrxDe@K9)0pmi^##_6#Xk!Z)1ucp-8vu2i2C5a0ll#!;il4;XKrQ_A*?1 z1%3Z%4GR156=>(thYk~@qp`WfOZ4x%&xog3G~=2+TbAV zAYFPIKSR>8iO>5k!EFlo5(J;oWAn%_QZc%V|Gmcad5w?e$g?7yZd~R9{cdNyBajpV zSUvFaw`>vJY{qs|oc5RE@ob}5a%%CkWKhU)JTrxH3D3|9N9r8*qy)jMCQ@uyH$m_b z0lI%t_!>-t4L%0v_AiDRg^B$^&*sU%IcpRjV%!{@jg=#bqU@A z;5dj>u&2ojX=sD#E-(39G}__1T8hpvH>|-F>0$xAaqaN#lQA+%1=00v=FWE>+nb7L z@05By5aMTUW$z&q*@2z|Nj;fqB$H`Y(2YIl4^Tt9Q9C&Af;D>P7q2ly84ix_+PSZA zo$A)M$xI!q1TS8s&Y>t$E~rf^NH=A%nwG)l&~j@P>RBgM_#VE_b8z$@WoICm%>8iO ze1}LPCV<&Wx(qi|827qNMvCFI$GGndh#O}kNckRR89s5(XAzEeC>`875~Qgq6MZ_$ zzNMA!{i9a7=BWbtfo>+n$D}A`>s>BZQ_NQQ9WXG!Z!XB9lB1*~*Qg$;f`g->)A(M$l!Ql0 ztaC^9m_w`s)+a7X9P@|HH^y^g)B${%1MfIQC-4SJs#VnnGE~jcM;ckCBoD}f1tt$3 zDP?TY9n-OsAEDCv#*)sM|LM#*hVABBRVBOu6O}mVu{WfdE&}^3sXl0!xH#g2f~Ro9 zB3DDO*%%uz>4AA5lm~l;q~4_Z$m4Hrs$f;EZjzhS(D7>xHWjey^e#Fbjd2$p7<4rD zxkqDPCPp8JnFE6k%08bCSj2Q}_60CT?gtXh&i3J{EDB3Aj*U>MVBHhwsSj0GEciqNpYM1p%DAnIG+iRNwLu;AN zWSO>Tna*UHwy1?OlUZre!ko!Gv}h^Lq=iFch8T-)@liB+_)7DJzfNUsTI!u;y zFV;;9OB1EyXCIaB7wbk2{UBd{S~qetFBu9TcZ*MwzoD0;d7U(Ura;QWb$j z$%tfpR0~TK6}g%=XRMlEWg6Kmv}(cNch#n8DZnJ>Vb&WQl5?u9f3?rY;XwA6Lr}Yk zeswpZK;^Z9C9frimKD?A!O8*3^q@*7ekhg|olu{!kadkhwulZQ3vlH%?|`E2!Bfu= z3DJ~E<9D^K&^tvzQTKkDldSuLqs%D+bRLt5v1U=>=@5akl=48u7tr}hXf!LGg^7YN zZ+AZl&0(dl(@LMitgq8bpTn%L(@LMiN?)gyKF3w*>k=yc*FJZp2Te(qbz12G zR5~!J^mS}3NN9kSzAlrF1D=3Xx)G<%Gdj zF{&b<84gG#8aw!t5N;udIO!bWkbH+3Jsgs6SCy~jOpDxFb9>?nfUWYCKBgc|}T+qZELLw#nND9u)Va7zb? zewZqNgz62Jp4-@;qI979hSf)Di)o>I4Qm8pVb9vf*iRDe&FJ zWWtK4s9WP{#$-oZq>iHwv|eyGFx^~90i{I^379tQJWUOE+Zi!b{$F2f2KEP9OlFc!q~$d=7h>YtV$Tg+T2C@+9iL1iT&4}Q%;d& ziAtb|oK&QqOEM<4=Bm>p5jpH*(PldB_79OkXjdA+zU?WAR`GaBmA3iy7g2mpt9G zCm%~$))O8kMVOl~G?~eCFPRXXfLMfl^eQCjAinyGFA@Bl&(B@?&}1t6feFv!(D6f= zqWE~x10hS$OL~rKCf9)pU3fmJ0ndV-REH2@?p7wP6n5$FDZJQc0)IGlkOkY6iH*;m;=M@Z@$;Z z<%yPiGl{~tRei(C-KK6vLjQJkx2n5C-EHdbQn$nk{%&=5sDH1zyVUIhp(L>FOzN2a37sd*>>FNB6(-lmj<- zIaz=Ml(?;yNnJKt4mPe>1;>!iobSML=1E@a{syK8yIFhjyl%abh2z6ADIJg5G8zGs z0}+pyfNa|=TgLDRV%Wm7KHSZ+WsgY5ThU(5;MT*%Zbr(skLT)Ldrh}U3F2K!54kWg z@UVUjSN~h_EmAJnQ72ia?-Mu}`5fNuLlaoYNat})8F(0idEcAz^5P9#0Q^?LbFlUK z&3AqXV)bNJ$G@T@Sn(=0Is)4(%rfs9g6e8fby*cL)o)G=eG*!w>e8a>vZ_t}RbBYe zKvs8)QI|*uov;hJLMSlajHB0PQBYkjq`I_tVoHEt%Hkql;Sv#E&Z7 z60ojfy39*=ND0%037&A?95D%+6=ArWHTknz#nnc?YcnFJ-a*HP3x46uIed zgJ?K-{+m4WJ8c^P;uj@h@ zu*kL(M>RK7A9g;3#k{ZMd^MjREjSF>TUe=h?!&s#W~xbNb`I8jxRCT*!Mj-b+s5kR zqFaE%*uAVR+`?Lx=i3UmNc|Ew-4A+UeA1Wxuv8mu7(~QMw&A6E83y5{8lS__>W%0+ z$@65vN77j}@$4venNY@v!fPWCJiQH14V$y}L}Hl`$=#bIl4H{E z-YSvAq&1qbZ($YpPSYFVjDqw=lDz=EPr`11_%yVcP_8uWGKeb;y+ELrnoy>JrVn?_ z-c6ea&B5jM4wn%KT-o1zPNgTkU z2qbAg-Cr-fjTIz4(pv?R`E*FarHOw=lw!o;`8Lh~m_+G$v3sAY$%46iy+q3;eebSw4fMSKW|l+7+F7WQ&*dCwyUc>Z}rU`e8$+&&g>%UVn%Y% zvyo+vQrxyla2!Qd|FHODhlk=FicbdaZ=TgbS-TYT8(wpg9kL75y+{2k#65b0BU#`V zGY*bkkpc&n^YOxCbVCHdIu50j+O44)5vp@XCGICUI9koms|)ca6cRE z@Y#`l1uuZ^p;%KDOA8;t3zVlVm@W}7h3TMNtRi`rpl()@BxWD4T^zk)vIckrq6P59 zBq$(bJl{sByTD3#4j_&vMj08Q&+#UN-v0&YbZ)GVv@nMFZP|aIexb~c1py1M-v-f1&P~ij9_cI-h=S^y&f!l`svM&#jy9HH=DMcED{%+_O^)iW7FQo zE?4{lbjirfaK&^D%$smoD>2+q1hLA@%F0Yk}L^w_%p+}zU1D%gf zPrtr+2n4=};*yCqId5alF>(`5D*R5=)p%?!&c3!l4rMk;r@^l&ahEa0vr1`-cXVcd z2d}dMHA!vajjepWXd4s|b3qv)&%!(O*AWq`7pK+W!@b2=Q3xYXJI~_W+haaW@kZfZ zxPLDu11o&zJG{!qV@8~_(CiQ518)q}h-+ujSMXF(3%^qY3+9YVuz+|OEyT-U5Iu^GAR0_oq0{cD!MC&UgZz&+J@%<+HfIrKa0oioGCq_D8?gY4(2iUAY$nr}f_CjS=Y(?CF(pT`y zP}riwivwdH$>J)o4cyuJv&K<3?qr2_ZoKxm8+SS^YKZB87)ZS$ol^gdZ%pnVCF8r# zGo)q4P}I^2=HI{G-;Cu}Y&!w42LK9U%~OhhU1(P%W1SGaJy49n9Lz}@+HZIBLwjZC*?-~k5n zqC(vLja7Baq6=QI@8l?B7fO}YZx+As5*u{~bquf(fku?JD`mHY6>4t2)sMv#G)<<7 zcyN@VpQz>3&iLT)GUFZUVBfi-OC3IIR1xe3$bN8!hb}Xe!{wC)7%Bu%4&B0&i41L! zLIcVHTu>j2b`ymIHKR5p1W+d1SbQj845o_;yZEJ)ZKedl7_h;MW9R62)Xtn9g})ii zAt(&-En8K*jNn-AVa6Ew_abPMh!a-7J5hmu z))g#nUVjNIK98{MECnVeQ1 zzk;k#(P-HgKZ*+!;xCsuiIp%riT z+iyM+O(nWhSDvng|56-Eqgc#iH_Ono^Ucf6w-l)Wv81BV&b(jhk~tSarj^?N8v| z#^wZ(=A7_Eb3z9tybLFzEbj;SIxi~)_9upFInKsqxR3fFX?=jOmS?%x^q>bHLIn~g z!BQz=*4vcD0!=o7u!3mCNL!7Mj5f9|99pgdS7fcQ?4;9b!^04XjO`dzZHgf#nynWp zbVVk{czk4R%<++7TB6z7YGdL|)x^{|P)rT0;-YDQweBuG9O8;AI+*D=_r-GSwh{E& z2&T6oA0OjIihSH+dOKY5WsB+joW77wPqg;8?@>jdYv_)U%Z zc#(*?HfO~wth>#Onxi6jn{n>WQ~QtNQ;{O%>)drnjr>;Owshu^zIWp?67i+Sl)`P) z0`b7tDNQBOgPe$4s%Y7$)vJ&d4hZd}NTk#aq^8O1mX6ZMWb81z_V%axBMjEXf|tz_2*S-DTb?v#tY2;|-gIKx6_>fdd%q65D9Esfl5gKsEukJU3zb8m-iuA0?+0NHLt<)9w+gT%Jpn9Wsp z2&<{>PeP&;w!)BfswUU3NLHI2SS-|ko234) zs!KOV#j0z-%~1nXm-i`djFKHuQe6Y=inE)dKH7~GdLRi8^ zoqYv77z2NNE6PjWVyf9WPcQa>x1A|qq!Ue~H!v_Gxq(|^B_0Na=o`o?J{{I4Y*KJT z7XS)wRZjM(`7PTx4UkWb+D&NEE?Q)p^sMIn(EnZR%#hNsN$CxyPvi_{MT8LA*rF%d z##mZr+Zz(n3-Ovw$r1!;%e{d+uo$|7p~0G>eRh{dkgopSa34_wZO2Nv|J#ZHA6DhM z7W<3UE!_iUb@dOa0XDnP&G!Bd1j(OT%);q4X`hN&4$f>tAblF?QzJ`yCOyPr&q>K|MszqAAR=%j zjfCB@m6=(Fue}n64C9T@!Yi93Y#BbnY4|qFki5)uXPfd19}H-zCY(T(lrJ;8hB4&d z8DThEjo@Q-!8R~C11|0Zp2%daUM+}-U#pjS>$zx~?7U+f`OWWh2xc<JP@JcefM$MTZc}eS2y69po|k`vTncG&Sws0z`{>4 zizlWFf%%d_^8=Fz8OYInc)lR+ZJQ*|9+|2mK^+u_2~002zHICmDJ}aAEc?KFqUg|= zAB;g%FI1oCPh3KKzWEaOcVhKY%Hi*5by9oCq^*Tw_^`BDsy!z>Om?F@EVhF3G7g*wktw~Nvz-%jEDn2ND z8Vy~F5(zR1E5z9^QxgY0cS@PZGU$Q%gQzx3nIj5^Wq;7KLCgG3b~uQ7bFZNr_JFc% zC2Abl5q6}^(3S#2S9p|ihi1=@F%nlLVHh>Tqd6j&fdqb;_8UjeQGNsv_vge|a30q%4Wjz$&gL*q9=6!2SM zy-kM&c+^cw-2yzvMxfXNJkKVjZUHgnz|m@fRu#J50&NPkSzte6;cDHs3>`W*S)UY0 zr_Ywj^x^vxnY7~LYL+8iIX3$ZhwMdTkUI-h7}wXiF4M&x1Fxt#sV2jU^(I8@&GCi` z0_g9hA4hL0Gvs9+Gv;CC%%>sOHG+{MS~%8sW-lAHd~7-b$`Khl=Z*EkX~sOfU62{M z-OUH@Nn^=WH8zE$Y^-Ni^YXD7=n;!ebC+==@9`VQw!#SDPqvi9&&0&_Sow5!UUU9f zKZ3Q2S0iGbOwNdMK0J08!-AQ8WoI@S0%T|h1H%?0Y)33?1vY)Zi+4=RMm;>XO9OHo zV8C0(Mu;G6uZC?zSOKJ3;R)B`tya>OvQMYEt5y^7p8mYT!F-!itCfz?D{;0zO(!;E35PzH{;1_>*| z5sg87CJ09n!$9q#M*$fzIIu6r@WH`=47ZQ%h6j^&4BR+DlV?3)Akseog)+=Iq*hXkD`+k#-P3mX**2YoyjV*}z zZB;+ht2U0hXKY2xZUYan_Npe_ejA_q zp*6((Qt-smHvJ}RXKTzaUHzoTlpJR$BK@EslYwL(eg6tCYl$`jdk;K7P#3*c-8gm^ zsCb#yF@0B=f1>$Zh2h%+|D#tNI}%#b66_k_<2DiMmY%J|d2)6J{+4Z-R6gE6@qX-^ z3J3hn(u?J{v;^R5zb$~{m-#Jnz&^iO?7w{degHaKD(OzU$U}vs!%OSaqYhc*p~}(6 zN1se}1dt}GJ~5xc%-SO5B9RCnYl<+fGTFP}3lNMAzU;&D&3P*_vBl&!e+)jcFTvme z1AVCc4B(|(k77y^kUiLWO?H~c0B6>V*CrvXJn65vv^7)yN)lJd`pw0uT1MFtBT3G}fp%{og3<9;niQd&J zPFQ`Vj{$dtZYU0|L920q+oh`TbpgW7*j}M49atyH!IT2ciySDMM%1MrOOnmo!hAAI zlDfDBo$3M?+7`zss8K5`zInw~ke)-omBWM7EUH@EnK&(TRn4Af!KzWsYJN}S(DgNB z+(c|vKkpLOgrlX~Xum@@H?t9{Zf-M^Msp1Ce^VJ}xRvqTe_0vN`*-MJF$;U3CGVCd z_S4W7`4Y|Qrbf8j3P@k8moClon?MOFW)-l2zWQ+%1hSe}L0Q_jxfGBFIyKFueAYzo zpfW=9o_K(ox20D!PpUl+>d?HU9oe#~sB7XaD|{Ht>>_I`0&2cLP1l0LD$PZ7O`_4y z@5IMpg-=9?&K(D8_^x*awdz5Rbx^nQXN*Guv^=ym1?2H2zBS?xK62LC-*VQbO!49S zAmf9#GF-ofAgZi>?gtfdcM8^SAcIRdmeb*K&cRW4b|Feo`A$$z?y+*1P_AH5t^R$HtE4Z9r)%WLLV67!y!*m_|6av3&^!1ZJ6@>+iJ%cSck*3U;*n{{DhNNCu9 zT30b$cUV`LuDjIry$A~fz?~LoRe=2d)x)+~ybU<|6E-#SuLGXf{JjpKOwIS&@$guV zXUM*9-_H+u`OxTgVE5K_J!eF@iECeH$${(MlWkqN2$#qczr|G2*>~)p^t)eNVrP4R zem#2{qKj2?h^xRH(2*Q^|#pf7>Dd)0?_V+t_SL@0G%-K_TKJ|nOnBV%-7^;DvX9eS z>`R1Vo6jnN%BPm_5vOmQ%GQE?AQ(S+%ObwwvlXb0IqyFvF| zalcJx0SuR5dVzO{F@M}2DUg%vDElKnRdZcQXWOE^?$!|-@&v#7UTy#Z$W z;;pRn)-+UAIj594-to0wXJV!^p*lRtIi;$>d%pLSGH+$g;*zS$GH-QB?V@0bP00(ob6AzuMSfdwNQ}#M95>r|cEIZjromW{MJl9E0J!Qg~!=|Q1Xd4tR{Vy;Uy z0w~cX+<+CqV3m2Q4+Yg%Fp~;`r-y4prKi^gtIAIgHU=I4g|ntRRh0{7Vx9SVQ~j9sjMjrEfHW^u&%x~wA6*nDp?fF3DwjG8|!l# zYHNcvM$U|2yxcZs!Q~k6@r>f zZK$sg)g*e&Ev*ezRVAVq1eeA^NNH{@ly^Zxd3msQZsj#5>vNZsgr^ErXVL(79&-UD z5+DHC(-$MZ#vfuXt}F|NsL$dLAW&NgHCj3=gwhR}?8nL_77-96$p&#{$3n5J3or*Y z5UO?8$*hvb%4#IrRVlGTo?8)Ws49~ZmC%MK5$$I;xzDKzmYC!kem|DeIjf;4(@N?~ET4TgY}Qp9tP9p#M|r4r zNl9%PLjZ-A)z$O4d`TG;p_1K)5mtS%iLtIe7(PR|@o=VnAf^5-tc5Nkpb1lhj;lU5 zR9hOPy9NqyW~IbbS#~B}M9a~i%;LjUC8bkCWlQyOZY7!r&_$Is!D@6zr7E&oh1WGK zsILtMO`;m4P{7_$bWN}}BoDQr`iq05vr6jci4*)2<)ONviXi-qv!wpaiyBIp=Z2zi zE%E?gI2ISNEa#R6YnY71DCqK%hN}90pd7LHyBfk}$aue7*>j}Bb_=*LtVN0l&@Bdn zwe=0P3rvJ?y8=`~q21o-TY{w~X(i!s)l&7d#k;u3jiQv8?pm8}?LFKn$*o-2P-~c& z)qalJBIeEQMvqg5u7&cD#@eb9))LtIC7=&03sg1+tLhx-yc@0xm4>`Ep?Zu6+UxbZ za%9wU=2n!j%bV+5Qdt`;XZPS-;>-z_Gn-VqIZk$288mQl(3!hv>4H$BbAgi^TIkGh z{3Yl>PIu-87gn<`9OvYfd2>QlX#Nu%qhJaS21tcJiFLIr-ka8dOn?>1FH$U=GMsJqkvh>I>Q(nEW zso%{Rk z-Q!!^_Mh>=b}P|@`#2`2<1%mdd!_rgE6r*gF*f76H3zn9dY-ePw-B&|4O2SWp!lUs_dJ zx+rySxTG|gI=!wmbq?E*w*+?7lGJ?IVEQ;Mw4_EK=ZEznP=dxaKb$(vEy;wB6P{CF zTjd=9H^#;|ud(>NWwj*>O_cI<+1!fC^7<<@?E;A)iyw)YToNC&aNt2J#VgjO@TX#A zU*bin)K!FP>q{Hz>r$sThD&P7PA`SEQW8cv!mjdqQ^mMW%|&0ThI{H<44K|?GvFEr z&96Avdq!qvzn5{D=5D%%RMYrVO_z|0PNQ^@6@O_cRGoTpWpIfXgCB+?^Njwhrml)k z(=}O7b;Z2Z`d@&)kH$YbAP(rY<)~+GNm&_;hB{M9I!iFUld{stuTS9PKu}j&GoiYq zabYl2Z7q44`QC4NIb}GH|5HWfr}K;@wIM{mq_V8OVjRmDwv~55(0fYdIPXG?C#O`} z0CD^kL8{?D4B#DK=^gJKU+%?>#XG*F#yh_B+{IoP>5XTe4InILk++WXrtzh<<=!*C z?H#|k-21h~_8?&5vZ2usACSEJ>)6!=J_8YMa zgY{nM6U=jO8OHch47*EHol_=E$~@=ny3;3Ai2 zbx{SH7kVH}PU&ZzEK(ZAn8EV*sd8fx8R4JG&q*7nZxc;QK9xTvzb3S>sy_oi{ty0s zq2t=54kK;984s`8?-Tc`M}6KV+?nk&?&EyN4ZS#R{BJTW z?J(otq3sw*Hf89 z6%cplhiP|@sT?agK90uUm+&_Rf5+hOIQ)GTfBYqew__{E;zU{WbIV|O$2s38WB@Al zwA^r9|b~dbRTXz7=m>wDl{)7O8)x(tiIrTfeg6tsmqnp6C1jx}7&+ z;f2?{{*#BZPU|~;#53ZzwZ4YD`Uz_-+d|j?d?Wh&-TQ42jlz0$rG<%{!)_9QYYaj4O1{`VeI#r zVPQOi+W<$vM*RN`919zJVC(63^gqRA$Ie5h`b-i|^x67KD7P#v->mrZ8snQNzelr7 z_zWY*ceC&AU*ebgpzq@O`2F!dmEWxX+YRmbq59vb{)N6nzj*Htvle(%o=x9iRO53j zovLyyJyG4(-_ohEcx-%$lzlRO*USF{P{;ftpOH#mPkGAkx6sf{XP4>y;+;9y&q3M=gq7;k1GCI^!WF)rsQt8uHww@tlaJ| zZ8&iH3t1n$bmh4(Zh1fJ`JZ0@)~`C=$Xfa5k-sc%{&`mYGT$W^Hgso=o3rGl>)Tqh zzBK0i=EJ{yEo<6e#?1WhyQWM_e(d(YUr5iGvGDwFOj{yy%BE~QZrz;!`rEo`*I&9TZ`a%#zx|^JTV5`E>7!}C z6aLlbzW-)h%bo*kv-4KgR5r z;`z(D9k2Vo`khw~PkT`0+-c*9c=z+%;PEVWv$I$x3IPSrL3+C|1xjstNXK#{`#FqFVFAIT9`KB-t&BqW@&kx zd!3~BmTznQ_zdm9S55fqR(IToMo=}xFu`fsb{3zbK;+}7Gie&)!a>4XTO>HZtbXF zW#vx2?CCqV{xa)}KOc7bC#gTo;;?bi*57HkJF?CRJoBHSrpY-c9(&%L2YxUqhjs+) zgNF^?v)$l(m9HmD-P==N+!+2&>H}GJ+?hEt>094B_7_?H*RH{ZBRjIxf4hkDF82uy zKW^yTZy4(Pm7%5Do>$$b_)mpK&VAFkSNz7%`yTLlJN|H4^^a~i@2f(8c%GKm_V+5@ zShZ#U-t*u3!6_>%Z`|Tj_wVA?BfQHy9Qg&#Z+T}++ut8+Po%$7{C9@0|9@k@?c1I} z)y}haTR*>P{{gM%F+SsC`<;G1`()E&-GkA8H=l{8H|yLrnXlipbo%* `OuZH`q z`ACfSUkzvVBT?R`x$X5ihHvotvvN$m`?TIao!^H0tnxpN|DcoP1RPk>cx4NY`A zy;+Yu|LgbvcJSTp6ZhXU`K)4_PRFtBHeSAMFIh&O2VgZe-(2MvIRK_j3yf_5B+JkV~e#gE~F zHV)iofEEwwi>?A~1HBK_i#79IpsiR--wWyt?ThXQ?Hbk>Jr9%o;^BSK0#MHv`l8E0 zBcQi~c7Z+&>ciJWx0?3sOPA@=qsSDpuC=; z7j!5V1p+uikPcc5Iu6uxbYJvx&|Vx!xDhlHClA^{+dy}NwvR@6(AEo(Zn{A?fp&pD4C>8?o`Lp)?x%Ye20d1cHIiSv5=s#!|=q}K<}`iJ-lpnV`<)&__@&=;ff9pkYuS=#8KO(Dk6jp!a}w zgYE(CsDQrV!+*X?RnQC22IcmPEe35}csRNV)Kh;rx(Bp( z@!@F7$&kDBaC9taI08Pdpx$Sr(G$la9iW+@0Z>0Ee{5F#4Y_8HGo;Zoj#?inel*G|iKnmOk_75ld1cPS){LzBzF$Vm9HYf$sXtp(uu!*e?T5 zm*X$;>Y->g68*o}1>mIcaKI`c28x)4VN1r>AAC8J3-vxpMflw8>3h$V-bPUz?gX z8Ax_o#?&+~IH#t0rlzIjjgYjw4H3@1L(!L$2az=`CTm(++mPf7kjMd~O&^i;RNAH? zrD^R$YC*HX>Nt}jG9NVZ_Mzx>#)Guplr%jpy@hFAGjv*7#>!!k-!wd!mXYmB8(5jo zRS0_v!oH|sHJ`|Z=F=ZbTW(r7X(LhwX$kqv9wD-xhpdcu4n=<)lZAA+%S`f_!!nze z7D!q+m@Eth7?T}mIb>njm)|7(KM7bPu#Jd^`D{soYOF!MdRGpekro+}JPZZrMO~ZH zpT?owi@z#_>;0cY(TN&vO_D#YIB832nrC`iihqQ|`1n1mk+5&ZGDHY z>SO}D2iRFeBrS`esV1HI@aux#8!^9FI%DxuMm_k}zYm*#)Nl9o2Mg|YZ?}p#F zm|u2U`pV=PY2HiH(x-_wOF3-?-}B(Z@GC#&VK=aDV79J^bpv}P0s9cx9$;THK}8-v z`Sl^N$*ddv8u51`FfVM&6Nt@W`^{mwBP~f6re)-&W#*<$&Q0^>rulQz0=a1gxoO3@ zX%$e<+_c7A=s|AUD*UzLZ$19n@V5zn?fBb@zm6e+H18~1FWHYihE~y(yb^W8bgxI; zoroJ|g#6f-+ykr&SaD2$q-+=t?JF~>ByI8~X}+Y{X_L`drWqAPAA=6yf)Pb-=gbk8 z!im79KxaTfGa!E?`nfLH&{G(r)C+WYWpWPXUnL2JD0ne_lfkh8iEkyuYlhju*0vyGk-q(EeGb{n|Y6Fer{$vx+z)O{M1e`DTbRaV9k}kzP1op?ui*n?Q`NUU1a#?55Pn+Dy$cn5B?)DKd7YtZ0bnT^wh`FQf853#$&=$2A%@& z6vlX#k|j@BWDHsbo?E~Jvw{7;XC~xl;;{|*?ZCgIWwZuO1$Clz?n~-26=|v&eMmmS zJdZG&Fh@BSy2N_az7%?^eW~<+*(}!!(z;TT9~roxhcweB$6}7vh&jx6;5Owb?Hclm zt@=tG=Yy{meC_1JkM&**Y#io2Y)||Vs|U6oSTOJ-)ZG*)L>cB^ z=i%At!PQhFX%}PhunK-v^piOKu{uC&OP^u7CCLZppS!`E#Q5-I-pYXO!ko^HH3I9z z{BAhvia+wL0oIWkkF^1N*n@e5a2dY)fNce)i`Ei$7qAa84{Jsr!5`(l0xbOH_^`de zs({g-KhmM-Fe?(UbYNw`K;%chac~p^v-LsD2kdfSwx6OcGY=T$!E_Z}o`aGkZxwK+ z$K7W~fGr1x>4*HtcMGspz`o%s!%e{MNbidqvmOT42CT>xwhP$X34D8j^#EgC^T#;$ z1KSJCofgjNdtKOA@bRl4hk#|p^yfn9Lz2ge{=nie@;Lt=b3En`t~7HkAbbMmI^f}t z@p4_@6=3JP__#)pauRHCGU3N~xn3{^n4f^?t!;A)Vr?!TULD{&4}2HLxAmE9>(YnL zpxq>GeHw9gI`Ov^+c>(2R;_q_E3!l~(U5RH` zzmdoBbOwyrE8TrJY9Iq_tq8LlVS=$RG6uu8Y#Mrv6u~s76YA0kX6!gR;VZ3fEirsS5Pxod_s z4NqRIr6%nk#_za^T8C1`v3y)9_ESz;3i)`M+AZLdIY&QVKJt5mZLre*!8dXe=I=}| ze#E$@)(C8^AO>3xZ0K3>{qH@%9AGIfz7AlA5O%y`Ow04Y(!s~JYRVpsN9@)jn-q!n z5cquHdq%@@9Q0sPa0u804cnA-ndlqSISzgvtaaIW1LN|+F%sCP#Z>{mN#J{ia`9ta z%YpR*8z`>z@EiK=__*!?<^cP&xSj`J2Ka7fMEEf-t{dI~Y@oP?B6C|4;z|d0AFyf) z=&w)Cx#rkHWSRKz-y!hXv5Ilc1D1}pz=7i8r(4Fsk6Gc5Wq2d73}AT#BraQDvF0K5 zbr1Lg;CqIA_%W^yU?b1%i=IgUVVjbQq`oNk75HVsFJJvuCRw?qHVYzmCln} zHCvy%-}AGdWj8ww{p<-=ywu4&@UNN*`H0KZ$>mZftgkTqZinB*m|tJwW&m6T*`(1?$iZ?~eOKVC}$cJ!OC| z6WBe#mg6~Qe>Wv#d`(Tl9FuEWm?RoI;d1agSlfPq1EPDpp`9>Y3;uy)oo45=Q$QJ4!-Fgt8m)>AqPbrROKrA=Z^u`+2frfjCYPJ&+r{4S;3{=R`@ z8x{!6svg_l<=|@r-#anB*m}qlZoV5SFVGjgf_yT+5F3bN2jrPKI_u>g$^##ZlRsh| zz-|WyGf;lSo(Hx*fv*SHEiR1h;1IA@U=Izb*M8{r3eoEvM9BP%<2wSZ*{9Rql6-UA zY)M`-G`ZI{0G8c6@TJf1i*Cd-bup;~Q)VnOFl}M@-2*=~LHSXqZUnX!SPKt zJ|6Z0Ul06xmKl`%W=>jfN}kO*LT;%p^fBrU)V&Go z+QrEa!WuSn1fUMbjmyCo{$XGAyC`QVgNtRJFw3;|_{oCI6}0hBImQ-1_6W+k19Gue;AoYfVn>8j&jNXlO67w*#DtiO!D1yRGmmebL_*0AM*^ zXv#-)_5xFDvDuwem`>|X8qr_S2 zJY8oWj(&M4c%VlslkyBt>QLdK?ze$w_qm5-{To%_K480mad@HZ+31)>|0xf+TmM-; zdzF7a%V$3FHRrSGPx8qAY_VR(VR5cI_i(h4a#%iY{Yk!1xUB+_|8nqW&c!<_mVv7e z5PeI|#4N)o92eS9h0YqvpMN-7V#+KtX@luEC&OmgJEWOuy-8SW9dMqEw@7BqbP^VJ z(n}6Ur%>JuzA2i39z&*?(r)I#e{$*J=v6XKAd{xOs{T%sH2_;q>?>~se`ERK=xj#N zUrsan*Ar&Qf`X_VrNq_~>M`t?^#m^XQ5N5uF2DM4v~BEQvW&@L7AM@ok{-0O_`-&I zb0UnXu62i_J?F&98oWJgbNG)*R#L9?UuBTf_{`zx`|KB(zd~2Ln%zGZ%rs4mt0pRG zQ;KF!(sK{wWbQc}Jstg+$eH!o^!W5)Ha*j2{pLf+Nq_fnv@)b}@?Gh1jZH4IOw+S; zQNJW(fB5kJ_`EBlF`I;SFb~*dU`Jo5^8eBLkh=QMC02(u>HW? z?Vr56fjgU{aqS<-=fBTO;PVpryaYZkfzM0e^Ah;H1U@eTR|$kKHjYfCoYM1mDs6lG ztb4w3#@zOuE2l#83mC#B9R3=!Y5bdW$fRwXjT`2<{AddEhpCDDHmN^MQ~6o{j}Av^ zr8>o$9y_<2>=iagU!OY>4Pe*79@GUUPAT}~{E9!53Oux%Cl!mm)8Z}jNIr3z#UD*= z{<_aM)Z(p^jN7I&pb_J>vixj(xDHU#-#gLZIJYHkn~q*}zki1D$M@z0+fTmENlKE~WP?eN5>KO8=_#W2M9AX#7e~ReHA4T%{K)Emyi&=}M)yD!ohT{YoEG z`hwEGD*agL@VOel(o>b5tu$BZ#Y)SSE>^ly>8(odQhLAA$CSRH^sh=kRyus1#;^2L zrDrS6ReG_~a;1xvu2g!f(z}%2ukQ$Pfj?i}vlH-3 z)cy8+lRuk}Ld7pj;4e{ksZty7RqC!vz?Z6fnNll%rMhoQz*njJ`w6(M&s!7lJJfxb zQk$MF>V6=Bf2X=1Pr(1E?iUmAH`V>O1UyU2>w^T`DKO=jq}1m3b=9L$3HSr5uU}Ez zrvIDj9+!Zhq3#(uIp=ya<}YZdsc-O}GhyO{%<*S@yFr|1Tz6*Xgv?2&8Q6*A{I=md z+i*@i%`1RavO#DvtdYrf0C({uJ4rEn!3AUNPmb9M@%T{3+7t2kFvpI|@%V7Zj_2|C z7aVIB#N#P3`yn2OwV>lvJf4cPG;YK^C*x~q?Fs!4eUkA7n2rJQqhfZLTUs)|!lwOB zJbtv}4I4d)$30Hl;(_o{F}p6Ff3#!mxp@3b&Or7+GOVuFUkxPxn3$awFXz};zZ;Lk zTDyNBIo2BM=cZjd)Oj!3kC-Rgvq=M#CrV84-h^^KS#fJW8!6bPf`=ir9yLAIj?NYQ z$nxPn6UJ-paVux3@DE(h1Eqhx@PFB9e87~0wNLL;+?#+uq4<7Hr{#Z9@ty>n@6MR7 z-UR%R;^74OsmM6_D-!Ti1wYp5(eab7fcVQ){*DCx9L0+h@Iu9X33!>}fdsr>aeo3H zQM`R?e7W7EctHX`&wemplN0dYDxR5uKc%>nfWM@8Mgsn};^_(aCyIL#@ZsnOnVysc zJYDgMgnV&+NB(dEewO0J33#sJ1qt|k#RCcWRf_u+N3!L&Oz}+#{Oc57pMdkaPo}dq z0l!~yZvxI+M9IG@p&VXNJd%LFrFdq7oI{FdB;cc<9+W>h0Urxo`i(}DPdl$YSNYo# z_&MxS&aQ;?1Qp+tfG<(QM@xDzsnTwNWi&Ip6Prz z0bi&1)&%@N6>nGE_LIL+d{Y9xUGcUA{8`10Dc+rzvC1u?kH|Y+$AcfAVE%(;(-MGX2typ z_|FvgCE&kSJTn3BP<(O%{+z#mk+H39EZyf*>gtGFkjJ@Ud= zmP1McJ_-wH#GM5E>x%az$e*lucLL7(8OZ*bCHx*|`7K62RXv3a#D5w1lkjC?yIyJe zOGM6*c4m#>N7}JVfb+}7iT3mNRZj1g`1IT=_>uPQ)=^B)k@JFkz(1P(@SjZz(^cH> z6!#r4_%{r3{$%l51IU>?JiactGP%g1L2wT`I>zfOH_S+x{Ein~9WHXV@`vv+;7awI zH3)yvAo$fPrw zDc{lh8mIVIEnZ;&Is1&q@q#Opi)2~;9~sc2e)AO%-)n#-#jjSpt-}B|JvS-d`k=x6 z%K!9elg4ARuXsT73w4!Wk(I-VA%0e$ z8?2n)8{B8I;j}0o-eK@F4RL-cxH?=U0z;SSZ<}cZ>{Gu7RZhnu16cjpt$4Sl)7ICU ziidw^__es5WT+IX?1zzm*eV{OSzBc0iN< zOpVa?12u{}n+;=7`I{AQ`>g@iD!y6qi0ZAC^SI#3Im!f5qUkw;Yd;Tl{@fA+k3N_)CHtUibg+D1V36ubjUGLozy8>1S>;-1fZX z7{$Z84Q};(tl)0R=J|Z(_i8$!e)7v#y!Qd)w&T}A#eG^1Rwr+;{92y2pZTf9A2o7p z`9EmoXgY2G_It&>3H&KAq@{oGn)W4osUh+W;Wx6~|Nq^}(f;8}>NyMrLOIn8)(>W#C?UivRCa<@c$cT&mt#ihH#mZdANT@!}sEfb)F*mI-d2 z-T&XD{1M&%Am8c%!+%&gnlD?w|E0L|zL6qlNAUPN#XTn)1stZ4Jg0cKCQ!cP0Kc~c zS0)$fQ~uUs1Io90@R*7Yhvn9BwZX49#2IaI?U!u%k5fET({J@QSMe_G0H&y%%LG@4 zi&QIrZ-W7w)vr-;kH(AYmfz|@qT;yAW;8`lCEukG148mWd{9zrx?D*2G zxaYej((^R#jf#8g4Itk{!DGAPZQ4%dJQ47nig)X{WA*b-f~!y$sgizpq~lfnl(Rta ze@EqXCFEk%Vhn#yTbJX~gg z>58utTpcd*E9EavXcyZRkLWnnu3=ssM9zDI;K|3D^6|W41Xw-icLdQSkNBOY{DFk@ zoTGS~_9uu=ezUCnEymrg_I#z{-LDy3&JN;nx#G@!25&ONS*v*O?FO*l-`J>lSnX}w zZ*Q^kJB=R7IVJ?{w73ek^RjNm+qEB?sPXm+t_~MT{<0~z$YKL-QopBl{us~!Q_d{G z?>OZTylWWc{39MuQ@mKmmqL|uj^f@Q8Nk{Dev51QpQ!wo39b$o2`Rrv+e@+ftx-Hv z+lw84f2nvt%M;y;{2o@kL+cB}ocx|v+)@3p^BsQwk?k&`@!q5SA1U7ZvH`5V4No`x z&e^8E9priA_Jt}9c^7k$=fDRANSr*rNwBy=z#XGd!y{K~jAhbF4gHjQ_x;@2wf`K1Bm8zgw-SwNP9SLaPOzdu*J_%6f0TID>Tc(3B}Z4~%D zE4VVb$Q#NZSY$xkuYNQL{}+y9dXD_@yP5;x{Lbb;_yvNG!~kbx$u~*xc$MOrT0RvT z)wPOusNG`qWG!&7^0>)n<@Y4?GrvmYJ|JqYfU z*4Ee6<2v98r4Fv&3@)t1U9+`C_0>hCRiT<-ol{g)7Ajg;6;Fe98oOyQUz)ZNRw5GBMcNCT^Ey7)zwM!kjZ?veap}Kl0g1B6`#rcL#3d=2?@@cCO+L$cgZ`nF+bmTZQrYOnr9UF0M%I z@^Q?@^OxNr6>lTZ(>j66D zm|xsY_pXq!-YQ31k;~83zYX9Uf91U^nCsU280xyw-ePE}v0Ln2So}ry)}#M&cp|Qw z$jwdR381-MoM2H=?wssd(~G9ho>o-k$oR*hu`Xl_xM*78?Ce>2IY4L3o?kTGuL1ni z<^Y;EE5`<%k$>UT?EIn&b93iTpI0<5dusmlBHN^EgRJqQ#_B4I)Kylaa|DK4XBP%B z?D8V*g|!@i>me7nX_uDN7nN2l^7&@u=S|HiIuqNLCpil-fY&VU$IhH^meWucHXR+q z)yUoKVnG1ot18IpK!-(u$JW_<*h$c#mxn zuAnS&XBTPb<@KQjl_fQDoqeKbMR{egs;sC6_XEd!L0C9c=f+GMEw8MC% zP+dK1s&3FEny#-5CW1Q_C}cxb32deiZ;fxLcKa~}Qn}@|mFD(&S5e12rSR%tF*xBe ztLH zYydV10~Hy|(e(4GEU^?(^J75~S@l)MaI(?>8NEp?AGaR61rU$dop5N0tL)E-F-whc zh=?JYSt(j6I9Dp-i&a_`q6#l*s4R0yca?(*Q>_>2JDOQl)CXbja@ zm^Gue6YO8sperGgIow4XDn%H~GhAM!6+u*EXaQ8Vv-E3Dl2%RYDQ`qXLkU6g^DrhGNC(ZbL|3 ze~83<$3k4)P!gw~wGB0{3~6z&2&Mg@BMsG-;dX0xK~a`;3h{ZOHQ|KCT_{03py3SDj5JU zV#gJkbUYliMN3MnWE^%y(XWUJ8rokz%1u?1832a#+R|8CCCuyDt7CeBHd#{B5SwAJ zz~lN=SL`wa4%Sx$X@IzEy85cbj!@F$9*Usvu%{s$l_#;W(;u)XnM6@INqAgW64R)} zhAa9{_2As1wz9E*aFNziRJ5=aj#c zWHz9K2lTQuytF?@XH0UcL$HW2RxXYeKMO$WFtNK3+fLIJD=POe#8NT6hFNKWfl*o0 z9~+h0M7N-!z8;-6?8UkY*fg%Zvh)TUwqQm{D|M$UmJU&D_8sx@856;sa%K-Vm=~d| zaLTGe;b1}v6B09^r3Mj=k_sLFrET|*{i4@s;HGiAvv+lQZK)Hk4V4C=1~eU*T^I$h z0;|Quh);cac~wJQMLgz8pVU&!lA+;SUK^_Z2kiAlHAfb%skPYZK@KX$l$u!&vB{5> zv}kK$DrC%oAy#wdpwSQ1lZqwbRv~G9T*Sg#JB@?sldh&L7_P6dC>i4nBby=-Y0NdP z9rdZK>8~N9<5tzsuHr3)SQ{37iQ^{_MYjqs=V|@ZWOi8NG5wV$I+LM^M z6UVE>xs&wA^_BH7+-+V_23TY%sg8?m;Bl5&k`7O@B%>6E3ROZ_GoNANb+xNQKQdc7 zBMYM^ir0Y!m>tF=uJqS1Q5-PY1r5q|HCwAIlyr&c(c>_#_=YNJu?K6hl4$*0>k<}X z^}~8pYaz~ztq4_>#oIQbp0Uvzj9wui6tdm&JPSo9D z(Jg6+S&_!+Dh}w*l9F1?YX>)&j;ybLSeY_-#UiBHDjlp@DKgFRi0MYn)wX;YS#6Lt zIzS(Y^#Yj0@om#go#xD*7H{QKjx;$dSSpV83Wv6u;1U?(R)bBS$V{=h^pi4~gMQOeM&Gikx}^!j9Twz`A~;J*xT=ViQ8Uas zb)~iFnG*C4whxw0IWQCzl{Vr{LuHM;Di}CjNCovylbJY^;1mdR7W|73T~_svTO~!x z&}IgPhPtX?FdQ$!Rgu(1!%p)_hiG;W|F}qz^!_E5x_THK|EIIFcX1+$qWBbIDce~I zQ*7&Cxn=MV5F2YvOxUcf$+9~uv9+-fL9i4tjj|SkAcCEhjoVt-2mwL1)W+I#-hIF9 z^PwPKm^t^|_s;vs4EdP3b5hMxpF4j$%MRxLp7Q&Qnoci$KO71B{lF>SY~D}0?b%^B zI^5YEU({uiRGJPCrcF1#I}M)ULyzne_+jlStvolpvD-0=$rzD5|{-npsa=e>K@pb6 zj8xw6{7+xELz7lgPRm*AF`&z^S@nCSDmyRnr! zr+OAw6_ok>D9vM)=Jc47kM0GS{(G|^Y-AsFdQizn9|L5*bU_)sU-8k=0N?rn@xmCF z&_g-p_&i4ll3z&sdi{?xe?1Di92wgdW?)rpo+#|`;q&|<=>OI(tseiSDoZ{(AK>aj z$v!>)MBm6cr;YOqoww!Fi10eoo-+7e70x+=k8a4(Kk|>o^%CKuFY-F`S6-Zqbu%u< z@t*431U@<>kDf(j&*Z}3gP&Aa^3j!RmcjqbfysTq1HV*!^rTjPfM2%3#8Rng+Kj+g zIqqxSEI(iT{dq(dw<2$d_AO4v6QSpSsfxqDQpMfYR${fpR6lqT;~#CNV$%70AeVLX m{^PvF_1vRr+Mj%k=!fbJgmG!=+?_x1Uww<{4;p5y`M&_OUkcd( literal 0 HcmV?d00001 diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py new file mode 100644 index 0000000000..f0dba2727b --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py @@ -0,0 +1,120 @@ +import numpy as np +import xml.etree.ElementTree as ET + +from cassie_sim_data.cassie_sim_traj import * +from cassie_sim_data.cassie_hardware_traj import * +# from cassie_sim_data.cassie_traj import reexpress_state_local_to_global_omega, reexpress_state_global_to_local_omega + +from cassiemujoco import * +from mujoco_lcm_utils import * +from drake_to_mujoco_converter import DrakeToMujocoConverter + + +class MuJoCoCassieSim(): + + def __init__(self, visualize=False): + self.sim_dt = 5e-5 + self.dt = 5e-4 + self.visualize = visualize + # hardware logs are 50ms long and start approximately 5ms before impact + # the simulator will check to make sure ground reaction forces are first detected within 3-7ms + self.start_time = 0.00 + self.end_time = 0.05 + self.sample_period = 2e-3 + + # Will read in the default mujoco model and write a new model with the updated contact parameters + self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' + self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' + self.tree = ET.parse(self.default_model_file) + + self.traj = CassieSimTraj() + self.hardware_traj = None + self.drake_to_mujoco_converter = DrakeToMujocoConverter(self.sim_dt) + self.cassie_in = cassie_user_in_t() + self.default_params = {"stiffness": 2000, + "damping": 36.02, + "mu_tangent": 0.18} + + self.actuator_index_map = {'hip_roll_left_motor': 0, + 'hip_yaw_left_motor': 1, + 'hip_pitch_left_motor': 2, + 'knee_left_motor': 3, + 'toe_left_motor': 4, + 'hip_roll_right_motor': 5, + 'hip_yaw_right_motor': 6, + 'hip_pitch_right_motor': 7, + 'knee_right_motor': 8, + 'toe_right_motor': 9} + + def make(self, params, hardware_traj_num, xml='cassie_new_params.xml'): + + stiffness = params['stiffness'] + damping = params['damping'] + mu_tangent = params['mu_tangent'] + self.tree.getroot().find('default').find('geom').set('solref', '%.5f %.5f' % (-stiffness, -damping)) + self.tree.getroot().find('default').find('geom').set('friction', + '%.5f %.5f %.5f' % (mu_tangent, .001, .001)) + self.tree.write(self.default_model_directory + xml) + self.cassie_env = CassieSim(self.default_model_directory + xml) + if self.visualize: + self.cassie_vis = CassieVis(self.cassie_env) + self.hardware_traj = CassieHardwareTraj(hardware_traj_num) + self.reset(hardware_traj_num) + + def reset(self, hardware_traj_num): + self.hardware_traj = CassieHardwareTraj(hardware_traj_num) + self.traj = CassieSimTraj() + x_init = self.hardware_traj.get_initial_state() + + q_mujoco, v_mujoco = self.drake_to_mujoco_converter.convert_to_mujoco( + reexpress_state_global_to_local_omega(x_init)) + mujoco_state = self.cassie_env.get_state() + mujoco_state.set_qpos(q_mujoco) + mujoco_state.set_qvel(v_mujoco) + mujoco_state.set_time(self.start_time) + self.cassie_env.set_state(mujoco_state) + + self.traj.update(self.start_time, self.hardware_traj.get_initial_state(), + self.hardware_traj.get_action(self.start_time)) + self.current_time = self.start_time + return + + def advance_to(self, time): + while (self.current_time < time): + self.sim_step() + return self.traj + + def sim_step(self, action=None): + next_timestep = self.cassie_env.time() + self.dt + action = self.hardware_traj.get_action(next_timestep) + cassie_in, u_mujoco = self.pack_input(self.cassie_in, action) + while self.cassie_env.time() < next_timestep: + self.cassie_env.step(cassie_in) + if self.visualize: + self.cassie_vis.draw(self.cassie_env) + # get current state + t = self.cassie_env.time() + q = self.cassie_env.qpos() + v = self.cassie_env.qvel() + q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) + self.current_time = t + cassie_state = np.hstack((q, v)) + cassie_state = reexpress_state_local_to_global_omega(cassie_state) + self.traj.update(t, cassie_state, action) + # print(cassie_state) + return cassie_state + + def get_traj(self): + return self.traj + + def pack_input(self, cassie_in, u_drake): + act_map = self.drake_to_mujoco_converter.act_map + # Set control parameters + u_mujoco = np.zeros(10) + for u_name in act_map: + cassie_in.torque[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] + u_mujoco[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] + return cassie_in, u_mujoco + + def free_sim(self): + del self.cassie_env diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 5457ebdc22..18bc336059 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -104,10 +104,10 @@ def learn_drake_params(self, batch=True): reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function) - optimizer.learn_drake_params() + # optimizer.learn_drake_params() - # optimal_params = optimizer.load_params('2022_03_22_11_100', optimizer.drake_params_folder).value - # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_100.npy') - # plt.plot(reward_over_time) - # plt.show() + optimal_params = optimizer.load_params('2022_03_22_12_1000', optimizer.drake_params_folder).value + optimizer.write_params(optimal_params) + reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + plt.plot(reward_over_time) + plt.show() diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 6a9aa2a43d..2a5e91bbe0 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,5 +1,5 @@ -FootstepKd: [0.23903044158385484, 0.0, 0.0, 0.0, 0.5277918292893192, 0.0, 0.0, 0.0, - 0.3348254165589458] +FootstepKd: [0.28910336679523946, 0.0, 0.0, 0.0, 0.5112178517397016, 0.0, 0.0, 0.0, + 0.3166509796509417] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] @@ -9,17 +9,17 @@ PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [8.457110869021973, 0.0, 0.0, 0.0, 6.337030429693949, 0.0, 0.0, 0.0, - 0.19627803553381146] -SwingFootKp: [114.74294024181081, 0.0, 0.0, 0.0, 135.42922767990683, 0.0, 0.0, 0.0, - 45.87269559307247] +SwingFootKd: [5.536817809152063, 0.0, 0.0, 0.0, 10.070248157027194, 0.0, 0.0, 0.0, + 6.803172290271984] +SwingFootKp: [132.83922083157395, 0.0, 0.0, 0.0, 128.500849333657, 0.0, 0.0, 0.0, + 72.69194792349245] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.026528125472685925 +center_line_offset: 0.010111174272404566 flight_duration: 0.08 footstep_offset: -0.05 hip_yaw_kd: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e078e08283..69a6fdb070 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,7 +40,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.042 +center_line_offset: 0.03 FootstepKd: [ 0.3, 0, 0, 0, 0.45, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 6f746fe481..bacb58ec65 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -195,10 +195,10 @@ int DoMain(int argc, char* argv[]) { // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - // osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - // osc->SetLambdaContactRegularizationWeight(1e-4 * - // gains.W_lambda_c_regularization); +// osc->SetLambdaContactRegularizationWeight(1e-4 * +// gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); @@ -352,9 +352,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); + "pelvis"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); + "pelvis"); auto left_foot_rel_tracking_data = std::make_unique( @@ -468,8 +468,8 @@ int DoMain(int argc, char* argv[]) { "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); - right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); +// left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); +// right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), From 3c778fa576bca7320532dbb560c725e2e977de53 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 23 Mar 2022 14:52:17 -0400 Subject: [PATCH 162/758] adding mujoco sim to gym --- .../pydairlib/cassie/gym_envs/BUILD.bazel | 41 ++- .../cassie/gym_envs/cassie_gym_test.py | 10 +- .../{cassie_gym.py => drake_cassie_gym.py} | 9 +- .../gym_envs/drake_to_mujoco_converter.py | 327 ++++++++++++++++++ .../cassie/gym_envs/mujoco_cassie_gym.py | 154 +++++++++ .../cassie/gym_envs/mujoco_cassie_sim.py | 120 ------- .../cassie/gym_envs/mujoco_lcm_utils.py | 164 +++++++++ bindings/pydairlib/cassie/learn_osc_gains.py | 35 +- .../osc_run/learned_osc_running_gains.yaml | 14 +- 9 files changed, 719 insertions(+), 155 deletions(-) rename bindings/pydairlib/cassie/gym_envs/{cassie_gym.py => drake_cassie_gym.py} (95%) create mode 100644 bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py create mode 100644 bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py delete mode 100644 bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py create mode 100644 bindings/pydairlib/cassie/gym_envs/mujoco_lcm_utils.py diff --git a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel index d3268f1587..89a9601660 100644 --- a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel +++ b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel @@ -15,15 +15,15 @@ py_library( name = "cassie_gym_all", srcs = [], deps = [ - ":cassie_gym", + ":drake_cassie_gym", ":cassie_env_rewards", ], ) py_library( - name = "cassie_gym", - srcs = ["cassie_gym.py"], + name = "drake_cassie_gym", + srcs = ["drake_cassie_gym.py"], deps = [ "//bindings/pydairlib/cassie:cassie", "//bindings/pydairlib", @@ -34,12 +34,45 @@ py_library( ], ) +py_library( + name = "mujoco_lcm_utils", + srcs = ["mujoco_lcm_utils.py"], + deps = [ + "//lcmtypes:lcmtypes_robot_py", + ], +) + +py_library( + name = "drake_to_mujoco_converter", + srcs = ["drake_to_mujoco_converter.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie_utils_py", + "//lcmtypes:lcmtypes_robot_py", + "@drake//bindings/pydrake", + ], +) + + +py_library( + name = "mujoco_cassie_gym", + srcs = ["mujoco_cassie_gym.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie", + "//bindings/pydairlib", + "//bindings/pydairlib/systems:systems", + "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems:primitives_py", + ":cassie_env_state", + ":drake_to_mujoco_converter", + ], +) + py_binary( name = "cassie_gym_test", srcs = ["cassie_gym_test.py"], deps = [ - ":cassie_gym", + ":drake_cassie_gym", ":cassie_env_rewards", "//bindings/pydairlib/cassie:cassie", "@drake//bindings/pydrake", diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 4c750ff6d5..6881e9e8f6 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -1,4 +1,5 @@ -from cassie_gym import * +from drake_cassie_gym import * +from mujoco_cassie_gym import * # from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory from pydairlib.cassie.controllers import OSCWalkingControllerFactory @@ -6,6 +7,7 @@ from pydairlib.cassie.gym_envs.reward_osudrl import RewardOSUDRL from pydrake.common.yaml import yaml_load + def main(): osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' @@ -23,9 +25,11 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - gym_env = CassieGym(reward_func, visualize=True) + # gym_env = DrakeCassieGym(reward_func, visualize=True) + gym_env = MuJoCoCassieGym(reward_func, visualize=True) - gym_env.make(controller, urdf) + # gym_env.make(controller, urdf) + gym_env.make(controller) action = np.zeros(18) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py similarity index 95% rename from bindings/pydairlib/cassie/gym_envs/cassie_gym.py rename to bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 500e66c900..a472940498 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -15,7 +15,7 @@ from pydairlib.cassie.gym_envs.cassie_env_state import CassieEnvState -class CassieGym(): +class DrakeCassieGym(): def __init__(self, reward_func, visualize=False): self.sim_dt = 1e-3 self.visualize = visualize @@ -42,7 +42,7 @@ def __init__(self, reward_func, visualize=False): self.initialized = False - def make(self, controller, urdf): + def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.builder = DiagramBuilder() self.dt = 8e-5 self.plant = MultibodyPlant(self.dt) @@ -101,8 +101,9 @@ def step(self, action=np.zeros(18)): # next_timestep = self.sim.get_context().get_time() + self.dt next_timestep = self.sim.get_context().get_time() + self.sim_dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) - self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) - self.current_time = next_timestep + # self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) + self.sim.AdvanceTo(next_timestep, decimals=3) + self.current_time = self.sim.get_context().get_time() x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( diff --git a/bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py b/bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py new file mode 100644 index 0000000000..958f24df9d --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py @@ -0,0 +1,327 @@ +import numpy as np +from pydrake.multibody.inverse_kinematics import InverseKinematics +from pydrake.multibody.parsing import Parser +from pydrake.systems.framework import DiagramBuilder +from pydrake.multibody.plant import MultibodyPlant, AddMultibodyPlantSceneGraph, CoulombFriction +from pydairlib.common import FindResourceOrThrow +from pydairlib.cassie.cassie_utils import * +from scipy.spatial.transform import Rotation as R +from pydairlib.multibody import * +from pydrake.solvers.mathematicalprogram import MathematicalProgram, Solve +from pydrake.geometry import SceneGraph, DrakeVisualizer, HalfSpace, Box +from pydairlib.multibody import MultiposeVisualizer + + +class DrakeToMujocoConverter(): + + def __init__(self, drake_sim_dt=5e-5): + self.builder = DiagramBuilder() + self.drake_sim_dt = drake_sim_dt + self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, drake_sim_dt) + addCassieMultibody(self.plant, self.scene_graph, True, + "examples/Cassie/urdf/cassie_v2.urdf", False, False) + self.plant.Finalize() + + self.foot_crank_builder = DiagramBuilder() + self.foot_crank_plant, self.foot_crank_scene_graph = AddMultibodyPlantSceneGraph(self.foot_crank_builder, + drake_sim_dt) + + Parser(self.foot_crank_plant).AddModelFromFile( + FindResourceOrThrow('examples/Cassie/urdf/cassie_foot_crank.urdf')) + self.foot_crank_plant.Finalize() + + self.knee_linkage_builder = DiagramBuilder() + self.knee_linkage_plant, self.knee_linkage_scene_graph = AddMultibodyPlantSceneGraph(self.knee_linkage_builder, + drake_sim_dt) + + Parser(self.knee_linkage_plant).AddModelFromFile( + FindResourceOrThrow('examples/Cassie/urdf/cassie_knee_linkage.urdf')) + self.knee_linkage_plant.Finalize() + + self.diagram = self.builder.Build() + self.diagram_context = self.diagram.CreateDefaultContext() + + # Print the indices for the newly constructed plants + # self.print_pos_indices(self.knee_linkage_plant) + # self.print_pos_indices(self.plant) + + self.pos_map = makeNameToPositionsMap(self.plant) + self.vel_map = makeNameToVelocitiesMap(self.plant) + self.act_map = makeNameToActuatorsMap(self.plant) + + self.map_q_drake_to_mujoco = np.zeros((23, 35)) + self.map_v_drake_to_mujoco = np.zeros((22, 32)) + + self.generate_matrices() + + self.world = self.plant.world_frame() + self.context = self.plant.CreateDefaultContext() + self.foot_crank_context = self.foot_crank_plant.CreateDefaultContext() + self.ik_solver = InverseKinematics(self.foot_crank_plant, self.foot_crank_context, with_joint_limits=True) + self.left_thigh_rod = LeftRodOnThigh(self.plant) + self.right_thigh_rod = RightRodOnThigh(self.plant) + self.left_heel_rod = LeftRodOnHeel(self.plant) + self.right_heel_rod = RightRodOnHeel(self.plant) + + self.left_achilles_frame = np.zeros((3, 3)) + self.left_achilles_frame[:, 0] = np.array([0.7922, -0.60599, -0.072096]) + self.left_achilles_frame[:, 1] = -np.array([0.60349, 0.79547, -0.054922]) + self.left_achilles_frame[:, 2] = np.cross(self.left_achilles_frame[:, 0], self.left_achilles_frame[:, 1]) + self.right_achilles_frame = np.zeros((3, 3)) + self.right_achilles_frame[:, 0] = np.array([0.7922, -0.60599, 0.072096]) + self.right_achilles_frame[:, 1] = -np.array([0.60349, 0.79547, 0.054922]) + self.right_achilles_frame[:, 2] = np.cross(self.right_achilles_frame[:, 0], self.right_achilles_frame[:, 1]) + + self.plantar_rod_frame = self.foot_crank_plant.GetBodyByName('plantar_rod_left').body_frame() + self.toe_left_frame = self.foot_crank_plant.GetBodyByName('toe_left').body_frame() + self.plantar_rod_anchor_point = np.array([0.35012, 0, 0]) + self.toe_left_anchor_point = np.array([0.04885482, 0.00394248, 0.01484]) + + self.ik_solver.AddPositionConstraint(self.plantar_rod_frame, self.plantar_rod_anchor_point, self.toe_left_frame, + self.toe_left_anchor_point, + self.toe_left_anchor_point) + self.toe_angle_constraint = self.ik_solver.prog().AddLinearEqualityConstraint(self.ik_solver.q()[7], 0) + self.ik_solver.prog().AddLinearEqualityConstraint(self.ik_solver.q()[0:7], np.array([1, 0, 0, 0, 0, 0, 0])) + + def print_pos_indices(self, plant): + name_map = makeNameToPositionsMap(plant) + for name in name_map: + print(name + ': ' + str(name_map[name])) + + def print_vel_indices(self, plant): + name_map = makeNameToVelocitiesMap(plant) + for name in name_map: + print(name + ': ' + str(name_map[name])) + + def convert_to_drake(self, q, v): + q_drake = np.zeros(23) + v_drake = np.zeros(22) + q_drake = self.map_q_drake_to_mujoco.T @ q + v_drake = self.map_v_drake_to_mujoco.T @ v + + return q_drake, v_drake + + def convert_to_mujoco(self, x_i): + q = x_i[0:23] + v = x_i[23:45] + q_missing, v_missing = self.solve_IK(x_i) + + q_copy = self.map_q_drake_to_mujoco @ q + v_copy = self.map_v_drake_to_mujoco @ v + q_full = q_missing + q_copy + v_full = v_missing + v_copy + return q_full, v_full + + def visualize_entire_leg(self, x): + self.plant.SetPositionsAndVelocities(self.context, x) + q_missing, _ = self.solve_IK(x) + quat = q_missing[10:14] + + rot = R.from_quat(np.hstack((quat[1:4], quat[0]))) + euler_vec = rot.as_euler('xyz') + + toe_left_ang = x[self.pos_map['toe_left']] + self.toe_angle_constraint.evaluator().UpdateCoefficients(Aeq=[[1]], beq=[toe_left_ang]) + self.ik_solver.prog().SetInitialGuess(self.ik_solver.q(), + np.array( + [1, 0, 0, 0, 0, 0, 0, toe_left_ang, toe_left_ang, -toe_left_ang])) + result = Solve(self.ik_solver.prog()) + left_foot_crank_state = result.GetSolution() + + builder = DiagramBuilder() + + plant = MultibodyPlant(self.drake_sim_dt) + scene_graph = builder.AddSystem(SceneGraph()) + + Parser(plant).AddModelFromFile(FindResourceOrThrow('examples/Cassie/urdf/cassie_left_leg.urdf')) + plant.Finalize() + self.print_pos_indices(plant) + + plant_context = plant.CreateDefaultContext() + print(plant.num_positions()) + fb_state = np.array([1, 0, 0, 0, 0, 0, 0]) + left_leg_state = np.zeros(17) + left_leg_state[0:7] = fb_state + left_leg_state[7:10] = euler_vec + left_leg_state[10] = x[self.pos_map["knee_left"]] + left_leg_state[11] = x[self.pos_map["knee_joint_left"]] + left_leg_state[12] = x[self.pos_map["ankle_joint_left"]] + left_leg_state[13] = x[self.pos_map["ankle_spring_joint_left"]] + left_leg_state[14:17] = left_foot_crank_state[-3:] + plant.SetPositions(plant_context, left_leg_state) + + visualizer = MultiposeVisualizer('examples/Cassie/urdf/cassie_left_leg.urdf', 1, '') + visualizer.DrawPoses(left_leg_state) + + def visualize_state_lower(self, x): + self.plant.SetPositionsAndVelocities(self.context, x) + toe_left_ang = x[self.pos_map['toe_left']] + self.toe_angle_constraint.evaluator().UpdateCoefficients(Aeq=[[1]], beq=[toe_left_ang]) + self.ik_solver.prog().SetInitialGuess(self.ik_solver.q(), + np.array( + [1, 0, 0, 0, 0, 0, 0, toe_left_ang, toe_left_ang, -toe_left_ang])) + result = Solve(self.ik_solver.prog()) + left_foot_crank_state = result.GetSolution() + visualizer = MultiposeVisualizer('examples/Cassie/urdf/cassie_foot_crank.urdf', 1, '') + visualizer.DrawPoses(left_foot_crank_state) + + def visualize_state_upper(self, x): + q_missing, _ = self.solve_IK(x) + quat = q_missing[10:14] + + rot = R.from_quat(np.hstack((quat[1:4], quat[0]))) + euler_vec = rot.as_euler('xyz') + + fb_state = np.array([1, 0, 0, 0, 0, 0, 0]) + knee_linkage_state = np.zeros(14) + knee_linkage_state[0:7] = fb_state + knee_linkage_state[7:10] = euler_vec + knee_linkage_state[10] = x[self.pos_map["knee_left"]] + knee_linkage_state[11] = x[self.pos_map["knee_joint_left"]] + knee_linkage_state[12] = x[self.pos_map["ankle_joint_left"]] + knee_linkage_state[13] = x[self.pos_map["ankle_spring_joint_left"]] + + visualizer = MultiposeVisualizer('examples/Cassie/urdf/cassie_knee_linkage.urdf', 1, '') + visualizer.DrawPoses(knee_linkage_state) + + def estimate_omega_bar(self, quat1, quat2, dt): + R1 = R.from_quat(np.hstack((quat1[1:4], quat1[0]))) + R2 = R.from_quat(np.hstack((quat2[1:4], quat2[0]))) + R_rel = R1.inv() * R2 + omega = R_rel.as_rotvec() / dt + return R1.apply(omega) + + def solve_for_achilles_rod_quats(self, q): + self.plant.SetPositions(self.context, q) + left_thigh = self.plant.CalcPointsPositions(self.context, self.left_thigh_rod[1], self.left_thigh_rod[0], + self.world) + right_thigh = self.plant.CalcPointsPositions(self.context, self.right_thigh_rod[1], self.right_thigh_rod[0], + self.world) + left_heel = self.plant.CalcPointsPositions(self.context, self.left_heel_rod[1], self.left_heel_rod[0], + self.world) + right_heel = self.plant.CalcPointsPositions(self.context, self.right_heel_rod[1], self.right_heel_rod[0], + self.world) + l_hip_pitch_frame = self.plant.CalcRelativeTransform(self.context, self.world, self.left_thigh_rod[1]) + r_hip_pitch_frame = self.plant.CalcRelativeTransform(self.context, self.world, self.right_thigh_rod[1]) + + world_frame = np.eye(3) + l_x_vec = (left_heel - left_thigh)[:, 0] + l_x_vec *= 1 / np.linalg.norm(l_x_vec) + l_y_vec = np.cross(l_x_vec, -world_frame[1]) + l_y_vec *= 1 / np.linalg.norm(l_y_vec) + l_z_vec = np.cross(l_x_vec, l_y_vec) + l_z_vec *= 1 / np.linalg.norm(l_z_vec) + + r_x_vec = (right_heel - right_thigh)[:, 0] + r_x_vec *= 1 / np.linalg.norm(r_x_vec) + r_y_vec = np.cross(r_x_vec, -world_frame[1]) + r_y_vec *= 1 / np.linalg.norm(r_y_vec) + r_z_vec = np.cross(r_x_vec, r_y_vec) + r_z_vec *= 1 / np.linalg.norm(r_z_vec) + + l_bar_frame = R.from_matrix(np.vstack((l_x_vec, l_y_vec, l_z_vec)).T) + r_bar_frame = R.from_matrix(np.vstack((r_x_vec, r_y_vec, r_z_vec)).T) + l_bar_euler = R.from_matrix( + self.left_achilles_frame @ l_hip_pitch_frame.rotation().matrix().T @ l_bar_frame.as_matrix()).as_euler( + 'xyz') + r_bar_euler = R.from_matrix( + self.right_achilles_frame @ r_hip_pitch_frame.rotation().matrix().T @ r_bar_frame.as_matrix()).as_euler( + 'xyz') + + l_bar_quat = R.from_euler('xyz', -l_bar_euler).as_quat() + r_bar_quat = R.from_euler('xyz', -r_bar_euler).as_quat() + l_bar_quat = np.hstack((l_bar_quat[3], l_bar_quat[0:3])) + r_bar_quat = np.hstack((r_bar_quat[3], r_bar_quat[0:3])) + + return l_bar_quat, r_bar_quat, l_hip_pitch_frame, r_hip_pitch_frame + + def solve_IK(self, x): + toe_ang = x[self.pos_map['toe_left']] + self.toe_angle_constraint.evaluator().UpdateCoefficients(Aeq=[[1]], beq=[toe_ang]) + self.ik_solver.prog().SetInitialGuess(self.ik_solver.q(), + np.array([1, 0, 0, 0, 0, 0, 0, toe_ang, toe_ang, -toe_ang])) + result = Solve(self.ik_solver.prog()) + left_foot_crank_state = result.GetSolution() + toe_ang = x[self.pos_map['toe_right']] + self.toe_angle_constraint.evaluator().UpdateCoefficients(Aeq=[[1]], beq=[toe_ang]) + self.ik_solver.prog().SetInitialGuess(self.ik_solver.q(), + np.array([1, 0, 0, 0, 0, 0, 0, toe_ang, toe_ang, -toe_ang])) + result = Solve(self.ik_solver.prog()) + right_foot_crank_state = result.GetSolution() + + q = x[:self.plant.num_positions()] + v = x[-self.plant.num_velocities():] + l_bar_quat, r_bar_quat, l_hip_pitch_frame, r_hip_pitch_frame = self.solve_for_achilles_rod_quats(q) + q_dt = q + self.plant.MapVelocityToQDot(self.context, v) * self.drake_sim_dt + l_bar_quat_dt, r_bar_quat_dt, _, _ = self.solve_for_achilles_rod_quats(q_dt) + + l_bar_omega = self.estimate_omega_bar(l_bar_quat, l_bar_quat_dt, self.drake_sim_dt) + r_bar_omega = self.estimate_omega_bar(r_bar_quat, r_bar_quat_dt, self.drake_sim_dt) + + l_bar_quat_gt = np.array([0.9785, -0.0164, 0.01787, -0.2049]) + r_bar_quat_gt = np.array([0.9786, 0.00386, -0.01524, -0.2051]) + + q_missing = np.zeros(35) + v_missing = np.zeros(32) + + left_foot_crank_ang = left_foot_crank_state[8] + left_plantar_rod = left_foot_crank_state[9] + right_foot_crank_ang = right_foot_crank_state[8] + right_plantar_rod = right_foot_crank_state[9] + q_missing[10:14] = l_bar_quat + q_missing[18] = left_foot_crank_ang + q_missing[19] = left_plantar_rod + q_missing[24:28] = r_bar_quat + q_missing[32] = right_foot_crank_ang + q_missing[33] = right_plantar_rod + + v_missing[16] = x[23 + self.vel_map['toe_leftdot']] + v_missing[17] = -x[23 + self.vel_map['toe_leftdot']] + v_missing[29] = x[23 + self.vel_map['toe_rightdot']] + v_missing[30] = -x[23 + self.vel_map['toe_rightdot']] + + v_missing[9:12] = l_bar_omega + v_missing[22:25] = r_bar_omega + + return q_missing, v_missing + + def generate_matrices(self): + self.map_q_drake_to_mujoco = np.zeros((35, 23)) + self.map_v_drake_to_mujoco = np.zeros((32, 22)) + self.map_q_drake_to_mujoco[0:3, 4:7] = np.eye(3) + self.map_q_drake_to_mujoco[3:7, 0:4] = np.eye(4) + self.map_q_drake_to_mujoco[7, self.pos_map["hip_roll_left"]] = 1 + self.map_q_drake_to_mujoco[8, self.pos_map["hip_yaw_left"]] = 1 + self.map_q_drake_to_mujoco[9, self.pos_map["hip_pitch_left"]] = 1 + self.map_q_drake_to_mujoco[14, self.pos_map["knee_left"]] = 1 + self.map_q_drake_to_mujoco[15, self.pos_map["knee_joint_left"]] = 1 + self.map_q_drake_to_mujoco[16, self.pos_map["ankle_joint_left"]] = 1 + self.map_q_drake_to_mujoco[17, self.pos_map["ankle_spring_joint_left"]] = 1 + self.map_q_drake_to_mujoco[20, self.pos_map["toe_left"]] = 1 + self.map_q_drake_to_mujoco[21, self.pos_map["hip_roll_right"]] = 1 + self.map_q_drake_to_mujoco[22, self.pos_map["hip_yaw_right"]] = 1 + self.map_q_drake_to_mujoco[23, self.pos_map["hip_pitch_right"]] = 1 + self.map_q_drake_to_mujoco[28, self.pos_map["knee_right"]] = 1 + self.map_q_drake_to_mujoco[29, self.pos_map["knee_joint_right"]] = 1 + self.map_q_drake_to_mujoco[30, self.pos_map["ankle_joint_right"]] = 1 + self.map_q_drake_to_mujoco[31, self.pos_map["ankle_spring_joint_right"]] = 1 + self.map_q_drake_to_mujoco[34, self.pos_map["toe_right"]] = 1 + + self.map_v_drake_to_mujoco[0:3, 3:6] = np.eye(3) + self.map_v_drake_to_mujoco[3:6, 0:3] = np.eye(3) + self.map_v_drake_to_mujoco[6, self.vel_map["hip_roll_leftdot"]] = 1 + self.map_v_drake_to_mujoco[7, self.vel_map["hip_yaw_leftdot"]] = 1 + self.map_v_drake_to_mujoco[8, self.vel_map["hip_pitch_leftdot"]] = 1 + self.map_v_drake_to_mujoco[12, self.vel_map["knee_leftdot"]] = 1 + self.map_v_drake_to_mujoco[13, self.vel_map["knee_joint_leftdot"]] = 1 + self.map_v_drake_to_mujoco[14, self.vel_map["ankle_joint_leftdot"]] = 1 + self.map_v_drake_to_mujoco[15, self.vel_map["ankle_spring_joint_leftdot"]] = 1 + self.map_v_drake_to_mujoco[18, self.vel_map["toe_leftdot"]] = 1 + self.map_v_drake_to_mujoco[19, self.vel_map["hip_roll_rightdot"]] = 1 + self.map_v_drake_to_mujoco[20, self.vel_map["hip_yaw_rightdot"]] = 1 + self.map_v_drake_to_mujoco[21, self.vel_map["hip_pitch_rightdot"]] = 1 + self.map_v_drake_to_mujoco[25, self.vel_map["knee_rightdot"]] = 1 + self.map_v_drake_to_mujoco[26, self.vel_map["knee_joint_rightdot"]] = 1 + self.map_v_drake_to_mujoco[27, self.vel_map["ankle_joint_rightdot"]] = 1 + self.map_v_drake_to_mujoco[28, self.vel_map["ankle_spring_joint_rightdot"]] = 1 + self.map_v_drake_to_mujoco[31, self.vel_map["toe_rightdot"]] = 1 diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py new file mode 100644 index 0000000000..6a4b6de91f --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -0,0 +1,154 @@ +import numpy as np + +from pydrake.multibody.parsing import Parser +from pydrake.systems.framework import DiagramBuilder +from pydrake.multibody.plant import * +from pydrake.systems.analysis import Simulator + +from pydairlib.common import FindResourceOrThrow +from pydairlib.cassie.cassie_utils import * +from pydairlib.multibody import * +from pydairlib.systems.primitives import * +# from dairlib import lcmt_radio_out +from pydairlib.cassie.gym_envs.cassie_env_state import CassieEnvState +from drake_to_mujoco_converter import DrakeToMujocoConverter + + +from cassiemujoco import * +from mujoco_lcm_utils import * +from drake_to_mujoco_converter import DrakeToMujocoConverter + +class MuJoCoCassieGym(): + def __init__(self, reward_func, visualize=False): + self.sim_dt = 8e-5 + self.gym_dt = 1e-3 + self.visualize = visualize + self.reward_func = reward_func + # hardware logs are 50ms long and start approximately 5ms before impact + # the simulator will check to make sure ground reaction forces are first detected within 3-7ms + self.start_time = 0.00 + self.current_time = 0.00 + self.end_time = 7.5 + + self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' + self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' + + self.action_dim = 10 + self.state_dim = 45 + self.x_init = np.array( + [1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, + -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) + self.prev_cassie_state = None + self.controller = None + self.terminated = False + self.initialized = False + self.actuator_index_map = {'hip_roll_left_motor': 0, + 'hip_yaw_left_motor': 1, + 'hip_pitch_left_motor': 2, + 'knee_left_motor': 3, + 'toe_left_motor': 4, + 'hip_roll_right_motor': 5, + 'hip_yaw_right_motor': 6, + 'hip_pitch_right_motor': 7, + 'knee_right_motor': 8, + 'toe_right_motor': 9} + + + def make(self, controller, model_xml='cassie.xml'): + self.builder = DiagramBuilder() + self.dt = 8e-5 + self.plant = MultibodyPlant(self.dt) + self.controller = controller + self.simulator = CassieSim(self.default_model_directory + model_xml) + # self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) + # self.new_plant = self.simulator.get_plant() + # self.sensor_aggregator = self.simulator.get_sensor_aggregator() + self.builder.AddSystem(self.controller) + # self.builder.AddSystem(self.simulator) + + # self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) + # self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) + # self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), + # self.controller.get_cassie_out_input_port()) + # self.builder.Connect(self.controller, self.simulator.get_radio_input_port()) + self.drake_to_mujoco_converter = DrakeToMujocoConverter(self.sim_dt) + + self.diagram = self.builder.Build() + self.sim = Simulator(self.diagram) + # self.simulator_context = self.diagram.GetMutableSubsystemContext(self.simulator, self.sim.get_mutable_context()) + self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.sim.get_mutable_context()) + self.controller_output_port = self.controller.get_state_input_port() + self.controller_state_input_port = self.controller.get_torque_output_port() + self.sim.get_mutable_context().SetTime(self.start_time) + self.reset() + self.initialized = True + + def reset(self): + # self.traj = CassieTraj() + q_mujoco, v_mujoco = self.drake_to_mujoco_converter.convert_to_mujoco( + reexpress_state_global_to_local_omega(self.x_init)) + mujoco_state = self.simulator.get_state() + mujoco_state.set_qpos(q_mujoco) + mujoco_state.set_qvel(v_mujoco) + mujoco_state.set_time(self.start_time) + self.simulator.set_state(mujoco_state) + self.sim.get_mutable_context().SetTime(self.start_time) + u = np.zeros(10) + self.sim.Initialize() + self.current_time = self.start_time + self.prev_cassie_state = CassieEnvState(self.current_time, self.x_init, u, np.zeros(18)) + self.cassie_state = CassieEnvState(self.current_time, self.x_init, u, np.zeros(18)) + self.terminated = False + return + + def advance_to(self, time): + while self.current_time < time and not self.terminated: + self.step() + return + + def check_termination(self): + return self.cassie_state.get_fb_positions()[2] < 0.4 + + + def step(self, action=np.zeros(18)): + if not self.initialized: + print("Call make() before calling step() or advance()") + + + next_timestep = self.sim.get_context().get_time() + self.gym_dt + self.simulator.controller_state_input_port().FixValue(self.controller_context, self.cassie_state.x) + u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp + cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) + + self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) + while self.cassie_env.time() < next_timestep: + self.cassie_env.step(cassie_in) + if self.visualize: + self.cassie_vis.draw(self.cassie_env) + + self.current_time = next_timestep + t = self.cassie_env.time() + q = self.cassie_env.qpos() + v = self.cassie_env.qvel() + q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) + self.current_time = t + x = np.hstack((q, v)) + x = reexpress_state_local_to_global_omega(x) + self.cassie_state = CassieEnvState(self.current_time, x, u, action) + reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) + self.terminated = self.check_termination() + self.prev_cassie_state = self.cassie_state + return self.cassie_state, reward + + def pack_input(self, cassie_in, u_drake): + act_map = self.drake_to_mujoco_converter.act_map + # Set control parameters + u_mujoco = np.zeros(10) + for u_name in act_map: + cassie_in.torque[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] + u_mujoco[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] + return cassie_in, u_mujoco + + def free_sim(self): + del self.cassie_env diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py deleted file mode 100644 index f0dba2727b..0000000000 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_sim.py +++ /dev/null @@ -1,120 +0,0 @@ -import numpy as np -import xml.etree.ElementTree as ET - -from cassie_sim_data.cassie_sim_traj import * -from cassie_sim_data.cassie_hardware_traj import * -# from cassie_sim_data.cassie_traj import reexpress_state_local_to_global_omega, reexpress_state_global_to_local_omega - -from cassiemujoco import * -from mujoco_lcm_utils import * -from drake_to_mujoco_converter import DrakeToMujocoConverter - - -class MuJoCoCassieSim(): - - def __init__(self, visualize=False): - self.sim_dt = 5e-5 - self.dt = 5e-4 - self.visualize = visualize - # hardware logs are 50ms long and start approximately 5ms before impact - # the simulator will check to make sure ground reaction forces are first detected within 3-7ms - self.start_time = 0.00 - self.end_time = 0.05 - self.sample_period = 2e-3 - - # Will read in the default mujoco model and write a new model with the updated contact parameters - self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' - self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' - self.tree = ET.parse(self.default_model_file) - - self.traj = CassieSimTraj() - self.hardware_traj = None - self.drake_to_mujoco_converter = DrakeToMujocoConverter(self.sim_dt) - self.cassie_in = cassie_user_in_t() - self.default_params = {"stiffness": 2000, - "damping": 36.02, - "mu_tangent": 0.18} - - self.actuator_index_map = {'hip_roll_left_motor': 0, - 'hip_yaw_left_motor': 1, - 'hip_pitch_left_motor': 2, - 'knee_left_motor': 3, - 'toe_left_motor': 4, - 'hip_roll_right_motor': 5, - 'hip_yaw_right_motor': 6, - 'hip_pitch_right_motor': 7, - 'knee_right_motor': 8, - 'toe_right_motor': 9} - - def make(self, params, hardware_traj_num, xml='cassie_new_params.xml'): - - stiffness = params['stiffness'] - damping = params['damping'] - mu_tangent = params['mu_tangent'] - self.tree.getroot().find('default').find('geom').set('solref', '%.5f %.5f' % (-stiffness, -damping)) - self.tree.getroot().find('default').find('geom').set('friction', - '%.5f %.5f %.5f' % (mu_tangent, .001, .001)) - self.tree.write(self.default_model_directory + xml) - self.cassie_env = CassieSim(self.default_model_directory + xml) - if self.visualize: - self.cassie_vis = CassieVis(self.cassie_env) - self.hardware_traj = CassieHardwareTraj(hardware_traj_num) - self.reset(hardware_traj_num) - - def reset(self, hardware_traj_num): - self.hardware_traj = CassieHardwareTraj(hardware_traj_num) - self.traj = CassieSimTraj() - x_init = self.hardware_traj.get_initial_state() - - q_mujoco, v_mujoco = self.drake_to_mujoco_converter.convert_to_mujoco( - reexpress_state_global_to_local_omega(x_init)) - mujoco_state = self.cassie_env.get_state() - mujoco_state.set_qpos(q_mujoco) - mujoco_state.set_qvel(v_mujoco) - mujoco_state.set_time(self.start_time) - self.cassie_env.set_state(mujoco_state) - - self.traj.update(self.start_time, self.hardware_traj.get_initial_state(), - self.hardware_traj.get_action(self.start_time)) - self.current_time = self.start_time - return - - def advance_to(self, time): - while (self.current_time < time): - self.sim_step() - return self.traj - - def sim_step(self, action=None): - next_timestep = self.cassie_env.time() + self.dt - action = self.hardware_traj.get_action(next_timestep) - cassie_in, u_mujoco = self.pack_input(self.cassie_in, action) - while self.cassie_env.time() < next_timestep: - self.cassie_env.step(cassie_in) - if self.visualize: - self.cassie_vis.draw(self.cassie_env) - # get current state - t = self.cassie_env.time() - q = self.cassie_env.qpos() - v = self.cassie_env.qvel() - q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) - self.current_time = t - cassie_state = np.hstack((q, v)) - cassie_state = reexpress_state_local_to_global_omega(cassie_state) - self.traj.update(t, cassie_state, action) - # print(cassie_state) - return cassie_state - - def get_traj(self): - return self.traj - - def pack_input(self, cassie_in, u_drake): - act_map = self.drake_to_mujoco_converter.act_map - # Set control parameters - u_mujoco = np.zeros(10) - for u_name in act_map: - cassie_in.torque[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] - u_mujoco[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] - return cassie_in, u_mujoco - - def free_sim(self): - del self.cassie_env diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_lcm_utils.py b/bindings/pydairlib/cassie/gym_envs/mujoco_lcm_utils.py new file mode 100644 index 0000000000..ad59047563 --- /dev/null +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_lcm_utils.py @@ -0,0 +1,164 @@ +import numpy as np +from scipy.spatial.transform import Rotation as R + +import dairlib + +def init_robot_output(): + robot_output_message = dairlib.lcmt_robot_output() + # Although this is different than the ordering of MBP, state receiver will rearrange accordingly + robot_output_message.position_names = 23*[''] + robot_output_message.position = 23 * [0] + robot_output_message.position_names[0] = 'base_x' + robot_output_message.position_names[1] = 'base_y' + robot_output_message.position_names[2] = 'base_z' + robot_output_message.position_names[3] = 'base_qw' + robot_output_message.position_names[4] = 'base_qx' + robot_output_message.position_names[5] = 'base_qy' + robot_output_message.position_names[6] = 'base_qz' + + robot_output_message.velocity_names = 22*[''] + robot_output_message.velocity = 23 * [0] + robot_output_message.velocity_names[0] = 'base_vx' + robot_output_message.velocity_names[1] = 'base_vy' + robot_output_message.velocity_names[2] = 'base_vz' + robot_output_message.velocity_names[3] = 'base_wx' + robot_output_message.velocity_names[4] = 'base_wy' + robot_output_message.velocity_names[5] = 'base_wz' + + qoffset = 7 + voffset = 6 + + robot_output_message.num_positions = 16 + qoffset + robot_output_message.num_velocities = 16 + voffset + + robot_output_message.position_names[qoffset] = 'hip_roll_left' + robot_output_message.position_names[qoffset + 1] = 'hip_yaw_left' + robot_output_message.position_names[qoffset + 2] = 'hip_pitch_left' + robot_output_message.position_names[qoffset + 3] = 'knee_left' + robot_output_message.position_names[qoffset + 4] = 'toe_left' + robot_output_message.position_names[qoffset + 5] = 'knee_joint_left' + robot_output_message.position_names[qoffset + 6] = 'ankle_joint_left' + robot_output_message.position_names[qoffset + 7] = 'ankle_spring_joint_left' + robot_output_message.position_names[qoffset + 8] = 'hip_roll_right' + robot_output_message.position_names[qoffset + 9] = 'hip_yaw_right' + robot_output_message.position_names[qoffset + 10] = 'hip_pitch_right' + robot_output_message.position_names[qoffset + 11] = 'knee_right' + robot_output_message.position_names[qoffset + 12] = 'toe_right' + robot_output_message.position_names[qoffset + 13] = 'knee_joint_right' + robot_output_message.position_names[qoffset + 14] = 'ankle_joint_right' + robot_output_message.position_names[qoffset + 15] = 'ankle_spring_joint_right' + + robot_output_message.velocity_names[voffset] = 'hip_roll_leftdot' + robot_output_message.velocity_names[voffset + 1] = 'hip_yaw_leftdot' + robot_output_message.velocity_names[voffset + 2] = 'hip_pitch_leftdot' + robot_output_message.velocity_names[voffset + 3] = 'knee_leftdot' + robot_output_message.velocity_names[voffset + 4] = 'toe_leftdot' + robot_output_message.velocity_names[voffset + 5] = 'knee_joint_leftdot' + robot_output_message.velocity_names[voffset + 6] = 'ankle_joint_leftdot' + robot_output_message.velocity_names[voffset + 7] = 'ankle_spring_joint_leftdot' + robot_output_message.velocity_names[voffset + 8] = 'hip_roll_rightdot' + robot_output_message.velocity_names[voffset + 9] = 'hip_yaw_rightdot' + robot_output_message.velocity_names[voffset + 10] = 'hip_pitch_rightdot' + robot_output_message.velocity_names[voffset + 11] = 'knee_rightdot' + robot_output_message.velocity_names[voffset + 12] = 'toe_rightdot' + robot_output_message.velocity_names[voffset + 13] = 'knee_joint_rightdot' + robot_output_message.velocity_names[voffset + 14] = 'ankle_joint_rightdot' + robot_output_message.velocity_names[voffset + 15] = 'ankle_spring_joint_rightdot' + + robot_output_message.num_efforts = 10 + robot_output_message.effort = 10 * [0] + robot_output_message.effort_names = 10 * [''] + robot_output_message.effort_names[0] = 'hip_roll_left_motor' + robot_output_message.effort_names[1] = 'hip_yaw_left_motor' + robot_output_message.effort_names[2] = 'hip_pitch_left_motor' + robot_output_message.effort_names[3] = 'knee_left_motor' + robot_output_message.effort_names[4] = 'toe_left_motor' + robot_output_message.effort_names[5] = 'hip_roll_right_motor' + robot_output_message.effort_names[6] = 'hip_yaw_right_motor' + robot_output_message.effort_names[7] = 'hip_pitch_right_motor' + robot_output_message.effort_names[8] = 'knee_right_motor' + robot_output_message.effort_names[9] = 'toe_right_motor' + return robot_output_message + +def init_cassie_out(): + return + +def pack_robot_output(robot_output, q, v, u, t): + q = np.array(q) + v = np.array(v) + u = np.array(u) + # import pdb; pdb.set_trace() + robot_output.utime = int(t * 1e6) + # If we are not in a floating base, need to skip the first 7 postions + # (x,y,z,quat) and the first 6 velocities (linear and ang. velocity) + qoffset = 0 + voffset = 0 + floating_base = True + if floating_base: + qoffset = 7 + voffset = 6 + + # Get positions + + # See cassiemujoco.h cassie_sim_qpos for ordering of q + # q starts with floating base coordinates and left hip, identical to + # the joint ordering chosen in cassiesim.c for the message + # The offsetting here is to (1) get the proper length and (2) skip floating + # base coordinates if necessary + for i in range(3 + qoffset): + robot_output.position[i] = q[7 - qoffset + i] + + # remainder of left leg + robot_output.position[3 + qoffset] = q[14] # knee + robot_output.position[4 + qoffset] = q[20] # foot + robot_output.position[5 + qoffset] = q[15] # shin + robot_output.position[6 + qoffset] = q[16] # tarsus + robot_output.position[7 + qoffset] = q[17] # heel spring + + # right hip, also in identical order + robot_output.position[8 + qoffset] = q[21] + robot_output.position[9 + qoffset] = q[22] + robot_output.position[10 + qoffset] = q[23] + + # remainder of right leg + robot_output.position[11 + qoffset] = q[28] # knee + robot_output.position[12 + qoffset] = q[34] # foot + robot_output.position[13 + qoffset] = q[29] # shin + robot_output.position[14 + qoffset] = q[30] # tarsus + robot_output.position[15 + qoffset] = q[31] # heel spring + + # get velocities + # See cassiemujoco.h cassie_sim_qvel for ordering of v + # floating base and left hip + for i in range(3 + voffset): + robot_output.velocity[i] = v[6 - voffset + i] + + # Convert rotational velocity to global frame + # rot = R.from_quat([q[6], q[3], q[4], q[5]]) + # robot_output.velocity[3:6] = rot.as_dcm() @ robot_output.velocity[3:6] + # remainder of left leg + robot_output.velocity[3 + voffset] = v[12] # knee + robot_output.velocity[4 + voffset] = v[18] # foot + robot_output.velocity[5 + voffset] = v[13] # shin + robot_output.velocity[6 + voffset] = v[14] # tarsus + robot_output.velocity[7 + voffset] = v[15] # heel spring + + # right hip + robot_output.velocity[8 + voffset] = v[19] + robot_output.velocity[9 + voffset] = v[20] + robot_output.velocity[10 + voffset] = v[21] + + + # remainder of right leg + robot_output.velocity[11 + voffset] = v[25] # knee + robot_output.velocity[12 + voffset] = v[31] # foot + robot_output.velocity[13 + voffset] = v[26] # shin + robot_output.velocity[14 + voffset] = v[27] # tarsus + robot_output.velocity[15 + voffset] = v[28] # heel spring + + # Efforts + # Ordered list of drive_out_t addresses + for i in range(10): + robot_output.effort[i] = u[i] + + return diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 18bc336059..1f7e48376c 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -5,7 +5,7 @@ import concurrent.futures as futures import nevergrad as ng -from pydairlib.cassie.gym_envs.cassie_gym import * +from pydairlib.cassie.gym_envs.drake_cassie_gym import * # from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory from pydairlib.cassie.controllers import OSCWalkingControllerFactory @@ -64,22 +64,23 @@ def write_params(self, params): def get_single_loss(self, params): self.write_params(params) + gym_env = DrakeCassieGym(self.reward_function, visualize=True) controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, self.urdf, False, False) controller_plant.Finalize() - self.controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, + controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, self.osqp_settings) - self.gym_env.make(self.controller, self.urdf) + gym_env.make(controller, self.urdf) # rollout a trajectory and compute the loss cumulative_reward = 0 - while self.gym_env.current_time < 7.5 and not self.gym_env.terminated: - state, reward = self.gym_env.step(np.zeros(18)) + while gym_env.current_time < 7.5 and not gym_env.terminated: + state, reward = gym_env.step(np.zeros(18)) cumulative_reward += reward self.loss_over_time.append(cumulative_reward) print(-cumulative_reward) return -cumulative_reward - def learn_drake_params(self, batch=True): + def learn_gains(self, batch=True): self.loss_over_time = [] self.default_params = ng.p.Dict( SwingFootKp=ng.p.Array(lower=0., upper=150., shape=(3,)), @@ -87,11 +88,11 @@ def learn_drake_params(self, batch=True): FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), center_line_offset=ng.p.Scalar(lower=0.01, upper=0.1), ) - self.gym_env = CassieGym(self.reward_function, visualize=True) self.default_params.value = self.default_osc_gains - optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) - # with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: - params = optimizer.minimize(self.get_single_loss) + optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget, num_workers=10) + with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: + # recommendation = optimizer.minimize(square, executor=executor, batch_mode=False) + params = optimizer.minimize(self.get_single_loss, executor, batch_mode=True) loss_samples = np.array(self.loss_over_time) np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) self.save_params(self.drake_params_folder, params, budget) @@ -99,15 +100,15 @@ def learn_drake_params(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 1000 + budget = 5 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function) - # optimizer.learn_drake_params() + optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_22_12_1000', optimizer.drake_params_folder).value - optimizer.write_params(optimal_params) - reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - plt.plot(reward_over_time) - plt.show() + # optimal_params = optimizer.load_params('2022_03_22_12_1000', optimizer.drake_params_folder).value + # optimizer.write_params(optimal_params) + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + # plt.plot(reward_over_time) + # plt.show() diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 2a5e91bbe0..319f626703 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,5 +1,5 @@ -FootstepKd: [0.28910336679523946, 0.0, 0.0, 0.0, 0.5112178517397016, 0.0, 0.0, 0.0, - 0.3166509796509417] +FootstepKd: [0.2856883832745447, 0.0, 0.0, 0.0, 0.4713051840283412, 0.0, 0.0, 0.0, + 0.009341449817435035] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] @@ -9,17 +9,17 @@ PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [5.536817809152063, 0.0, 0.0, 0.0, 10.070248157027194, 0.0, 0.0, 0.0, - 6.803172290271984] -SwingFootKp: [132.83922083157395, 0.0, 0.0, 0.0, 128.500849333657, 0.0, 0.0, 0.0, - 72.69194792349245] +SwingFootKd: [3.244158138852018, 0.0, 0.0, 0.0, 5.567615547490108, 0.0, 0.0, 0.0, + 1.6063658571340755] +SwingFootKp: [130.03881803493078, 0.0, 0.0, 0.0, 79.25991410071981, 0.0, 0.0, 0.0, + 53.370277764220475] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.010111174272404566 +center_line_offset: 0.08826086956521739 flight_duration: 0.08 footstep_offset: -0.05 hip_yaw_kd: 1 From d8eddd0e7acc7d8691076b7e75eba8c44caa18ea Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 23 Mar 2022 15:48:41 -0400 Subject: [PATCH 163/758] TODOs: find a way bind either lcmtypes for FixValue or add RobotOutputSender to controller diagram --- bindings/pydairlib/cassie/cassie_utils_py.cc | 16 +- .../pydairlib/cassie/gym_envs/BUILD.bazel | 54 +-- .../cassie/gym_envs/cassie_env_state.py | 16 + .../cassie/gym_envs/mujoco_cassie_gym.py | 40 ++- bindings/pydairlib/cassie/mujoco/BUILD.bazel | 51 +++ .../{gym_envs => mujoco}/cassiemujoco.py | 112 ++++-- .../cassiemujoco_ctypes.py | 0 .../drake_to_mujoco_converter.py | 16 +- .../{gym_envs => mujoco}/libcassiemujoco.so | Bin .../{gym_envs => mujoco}/mujoco_lcm_utils.py | 0 examples/Cassie/urdf/cassie_foot_crank.urdf | 134 +++++++ examples/Cassie/urdf/cassie_knee_linkage.urdf | 229 ++++++++++++ examples/Cassie/urdf/cassie_left_leg.urdf | 335 ++++++++++++++++++ 13 files changed, 895 insertions(+), 108 deletions(-) create mode 100644 bindings/pydairlib/cassie/mujoco/BUILD.bazel rename bindings/pydairlib/cassie/{gym_envs => mujoco}/cassiemujoco.py (93%) rename bindings/pydairlib/cassie/{gym_envs => mujoco}/cassiemujoco_ctypes.py (100%) rename bindings/pydairlib/cassie/{gym_envs => mujoco}/drake_to_mujoco_converter.py (95%) rename bindings/pydairlib/cassie/{gym_envs => mujoco}/libcassiemujoco.so (100%) rename bindings/pydairlib/cassie/{gym_envs => mujoco}/mujoco_lcm_utils.py (100%) create mode 100644 examples/Cassie/urdf/cassie_foot_crank.urdf create mode 100644 examples/Cassie/urdf/cassie_knee_linkage.urdf create mode 100644 examples/Cassie/urdf/cassie_left_leg.urdf diff --git a/bindings/pydairlib/cassie/cassie_utils_py.cc b/bindings/pydairlib/cassie/cassie_utils_py.cc index 9e728a1d6a..7d249d5936 100644 --- a/bindings/pydairlib/cassie/cassie_utils_py.cc +++ b/bindings/pydairlib/cassie/cassie_utils_py.cc @@ -17,14 +17,14 @@ PYBIND11_MODULE(cassie_utils, m) { using drake::multibody::MultibodyPlant; - m.def("LeftToeFront", &dairlib::LeftToeFront) - .def("RightToeFront", &dairlib::RightToeFront) - .def("LeftToeRear", &dairlib::LeftToeRear) - .def("RightToeRear", &dairlib::RightToeRear) - .def("LeftRodOnThigh", &dairlib::LeftRodOnThigh) - .def("RightRodOnThigh", &dairlib::RightRodOnThigh) - .def("LeftRodOnHeel", &dairlib::LeftRodOnHeel) - .def("RightRodOnHeel", &dairlib::RightRodOnHeel) + m.def("LeftToeFront", &dairlib::LeftToeFront, py::return_value_policy::reference) + .def("RightToeFront", &dairlib::RightToeFront, py::return_value_policy::reference) + .def("LeftToeRear", &dairlib::LeftToeRear, py::return_value_policy::reference) + .def("RightToeRear", &dairlib::RightToeRear, py::return_value_policy::reference) + .def("LeftRodOnThigh", &dairlib::LeftRodOnThigh, py::return_value_policy::reference) + .def("RightRodOnThigh", &dairlib::RightRodOnThigh, py::return_value_policy::reference) + .def("LeftRodOnHeel", &dairlib::LeftRodOnHeel, py::return_value_policy::reference) + .def("RightRodOnHeel", &dairlib::RightRodOnHeel, py::return_value_policy::reference) .def("LeftLoopClosureEvaluator", &dairlib::LeftLoopClosureEvaluator, py::arg("plant")) .def("RightLoopClosureEvaluator", diff --git a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel index 89a9601660..bcb457bc78 100644 --- a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel +++ b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel @@ -16,6 +16,7 @@ py_library( srcs = [], deps = [ ":drake_cassie_gym", + ":mujoco_cassie_gym", ":cassie_env_rewards", ], ) @@ -34,45 +35,11 @@ py_library( ], ) -py_library( - name = "mujoco_lcm_utils", - srcs = ["mujoco_lcm_utils.py"], - deps = [ - "//lcmtypes:lcmtypes_robot_py", - ], -) - -py_library( - name = "drake_to_mujoco_converter", - srcs = ["drake_to_mujoco_converter.py"], - deps = [ - "//bindings/pydairlib/cassie:cassie_utils_py", - "//lcmtypes:lcmtypes_robot_py", - "@drake//bindings/pydrake", - ], -) - - -py_library( - name = "mujoco_cassie_gym", - srcs = ["mujoco_cassie_gym.py"], - deps = [ - "//bindings/pydairlib/cassie:cassie", - "//bindings/pydairlib", - "//bindings/pydairlib/systems:systems", - "//bindings/pydairlib/multibody", - "//bindings/pydairlib/systems:primitives_py", - ":cassie_env_state", - ":drake_to_mujoco_converter", - ], -) - - py_binary( name = "cassie_gym_test", srcs = ["cassie_gym_test.py"], deps = [ - ":drake_cassie_gym", + ":cassie_gym_all", ":cassie_env_rewards", "//bindings/pydairlib/cassie:cassie", "@drake//bindings/pydrake", @@ -100,4 +67,19 @@ py_library( deps = [ ":cassie_env_state" ], -) \ No newline at end of file +) + + +py_library( + name = "mujoco_cassie_gym", + srcs = ["mujoco_cassie_gym.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie", + "//bindings/pydairlib/cassie/mujoco:cassie_mujoco_all", + "//bindings/pydairlib", + "//bindings/pydairlib/systems:systems", + "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems:primitives_py", + ":cassie_env_state", + ], +) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py b/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py index 3a8717b303..dbe93318e1 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_env_state.py @@ -60,3 +60,19 @@ def get_desired_forward_velocity(self): def get_desired_lateral_velocity(self): return self.action[3] + + +def quat_to_rotation(q): + return R.from_quat([q[1], q[2], q[3], q[0]]) + +def reexpress_state_local_to_global_omega(state): + new_state = state.flatten() + rot = quat_to_rotation(new_state[CASSIE_QUATERNION_SLICE]) + new_state[CASSIE_OMEGA_SLICE] = rot.apply(new_state[CASSIE_OMEGA_SLICE]) + return new_state + +def reexpress_state_global_to_local_omega(state): + new_state = state.flatten() + rot = quat_to_rotation(new_state[CASSIE_QUATERNION_SLICE]) + new_state[CASSIE_OMEGA_SLICE] = rot.apply(new_state[CASSIE_OMEGA_SLICE], inverse=True) + return new_state diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 6a4b6de91f..12317ec22e 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -10,13 +10,15 @@ from pydairlib.multibody import * from pydairlib.systems.primitives import * # from dairlib import lcmt_radio_out -from pydairlib.cassie.gym_envs.cassie_env_state import CassieEnvState -from drake_to_mujoco_converter import DrakeToMujocoConverter +from pydairlib.cassie.gym_envs.cassie_env_state import CassieEnvState, quat_to_rotation, \ + reexpress_state_local_to_global_omega, reexpress_state_global_to_local_omega +from pydairlib.cassie.mujoco.drake_to_mujoco_converter import DrakeToMujocoConverter +# from drake_to_mujoco_converter import DrakeToMujocoConverter +from pydairlib.cassie.mujoco.cassiemujoco import * +from pydairlib.cassie.mujoco.mujoco_lcm_utils import * +from pydairlib.cassie.mujoco.drake_to_mujoco_converter import DrakeToMujocoConverter -from cassiemujoco import * -from mujoco_lcm_utils import * -from drake_to_mujoco_converter import DrakeToMujocoConverter class MuJoCoCassieGym(): def __init__(self, reward_func, visualize=False): @@ -54,13 +56,14 @@ def __init__(self, reward_func, visualize=False): 'knee_right_motor': 8, 'toe_right_motor': 9} - def make(self, controller, model_xml='cassie.xml'): self.builder = DiagramBuilder() self.dt = 8e-5 self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSim(self.default_model_directory + model_xml) + if self.visualize: + self.cassie_vis = CassieVis(self.simulator) # self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) # self.new_plant = self.simulator.get_plant() # self.sensor_aggregator = self.simulator.get_sensor_aggregator() @@ -77,9 +80,10 @@ def make(self, controller, model_xml='cassie.xml'): self.diagram = self.builder.Build() self.sim = Simulator(self.diagram) # self.simulator_context = self.diagram.GetMutableSubsystemContext(self.simulator, self.sim.get_mutable_context()) - self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.sim.get_mutable_context()) - self.controller_output_port = self.controller.get_state_input_port() - self.controller_state_input_port = self.controller.get_torque_output_port() + self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, + self.sim.get_mutable_context()) + self.controller_state_input_port = self.controller.get_state_input_port() + self.controller_output_port = self.controller.get_torque_output_port() self.sim.get_mutable_context().SetTime(self.start_time) self.reset() self.initialized = True @@ -110,27 +114,25 @@ def advance_to(self, time): def check_termination(self): return self.cassie_state.get_fb_positions()[2] < 0.4 - def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") - next_timestep = self.sim.get_context().get_time() + self.gym_dt - self.simulator.controller_state_input_port().FixValue(self.controller_context, self.cassie_state.x) - u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp + self.controller_state_input_port.FixValue(self.controller_context, self.cassie_state.x) + u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) - while self.cassie_env.time() < next_timestep: - self.cassie_env.step(cassie_in) + while self.simulator.time() < next_timestep: + self.simulator.step(cassie_in) if self.visualize: - self.cassie_vis.draw(self.cassie_env) + self.cassie_vis.draw(self.simulator) self.current_time = next_timestep - t = self.cassie_env.time() - q = self.cassie_env.qpos() - v = self.cassie_env.qvel() + t = self.simulator.time() + q = self.simulator.qpos() + v = self.simulator.qvel() q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) self.current_time = t x = np.hstack((q, v)) diff --git a/bindings/pydairlib/cassie/mujoco/BUILD.bazel b/bindings/pydairlib/cassie/mujoco/BUILD.bazel new file mode 100644 index 0000000000..e74c661ec5 --- /dev/null +++ b/bindings/pydairlib/cassie/mujoco/BUILD.bazel @@ -0,0 +1,51 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + + +py_library( + name = "cassie_mujoco_all", + srcs = [], + deps = [ + ":mujoco_lcm_utils", + ":drake_to_mujoco_converter", + ":cassie_mujoco_py", + ], +) + + +py_library( + name = "mujoco_lcm_utils", + srcs = ["mujoco_lcm_utils.py"], + deps = [ + "//lcmtypes:lcmtypes_robot_py", + ], +) + +py_library( + name = "drake_to_mujoco_converter", + srcs = ["drake_to_mujoco_converter.py"], + deps = [ + "//bindings/pydairlib/cassie:cassie_utils_py", + "//lcmtypes:lcmtypes_robot_py", + "@drake//bindings/pydrake", + ], +) + +py_library( + name = "cassie_mujoco_py", + srcs = [ + "cassiemujoco.py", + "cassiemujoco_ctypes.py", + ], + deps = [], +) diff --git a/bindings/pydairlib/cassie/gym_envs/cassiemujoco.py b/bindings/pydairlib/cassie/mujoco/cassiemujoco.py similarity index 93% rename from bindings/pydairlib/cassie/gym_envs/cassiemujoco.py rename to bindings/pydairlib/cassie/mujoco/cassiemujoco.py index 826356c451..b1c4205fa3 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassiemujoco.py +++ b/bindings/pydairlib/cassie/mujoco/cassiemujoco.py @@ -12,7 +12,7 @@ # ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF # OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE. -from cassiemujoco_ctypes import * +from pydairlib.cassie.mujoco.cassiemujoco_ctypes import * import os import ctypes import numpy as np @@ -189,7 +189,7 @@ def get_foot_forces(self): rfrc = np.sqrt(np.power(force[6:9], 2).sum()) return lfrc, rfrc - # Returns 2 arrays each 6 long, the toe force and heel force. Each array is in order of + # Returns 2 arrays each 6 long, the toe force and heel force. Each array is in order of # left foot (3) and then right foot (3) def get_heeltoe_forces(self): toe_force = np.zeros(6) @@ -285,10 +285,10 @@ def constraint_error(self): cassie_sim_loop_constraint_info(self.c, J_array, err_array) err_return = np.zeros((6,1)) for i in range(6): - err_return[i] = err_array[i] + err_return[i] = err_array[i] return err_return - # Return the minimal actuated mass matrix of Cassie. Contains 6 for floating + # Return the minimal actuated mass matrix of Cassie. Contains 6 for floating # base, 5 for left leg motors, 5 for right leg motors. def minimal_mass_matrix(self): ind_full_idx = [0,1,2,3,4,5,6,7,8,12,18,19,20,21,25,31] @@ -300,8 +300,8 @@ def minimal_mass_matrix(self): J_c = self.constraint_jacobian() J_c[:, 0:6] = 0 # Zero out floating base coordinates J_c_div = J_c[:, ind_full_idx + dep_full_idx] - J_c_div[J_c_div < 1e-5] = 0 # Zero out very small terms for numerical stabilityL - + J_c_div[J_c_div < 1e-5] = 0 # Zero out very small terms for numerical stabilityL + M = self.full_mass_matrix() M_div_temp = M[:, ind_full_idx + dep_full_idx] M_div = M_div_temp[ind_full_idx + dep_full_idx, :] @@ -313,7 +313,7 @@ def minimal_mass_matrix(self): M_minimal = P.T @ M_div @ P #J_c_dep = J_c[:, (13,24)] - # This gets hard + # This gets hard # import sys # np.set_printoptions(threshold=sys.maxsize) M_print = M_div[:, ind_idx] @@ -326,7 +326,7 @@ def minimal_mass_matrix(self): return M_minimal - + def foot_quat(self, quat): quat_array = (ctypes.c_double * 4)() @@ -343,7 +343,7 @@ def get_dof_damping(self): for i in range(self.nv): ret[i] = ptr[i] return ret - + def get_body_mass(self): ptr = cassie_sim_body_mass(self.c) ret = np.zeros(self.nbody) @@ -411,7 +411,7 @@ def get_geom_pos(self, name=None): for i in range(self.ngeom * 3): ret[i] = ptr[i] return ret - + def get_geom_size(self, name=None): if name is not None: ptr = cassie_sim_geom_name_size(self.c, name.encode()) @@ -431,7 +431,7 @@ def set_dof_damping(self, data): if len(data) != self.nv: print("SIZE MISMATCH SET_DOF_DAMPING()") exit(1) - + for i in range(self.nv): c_arr[i] = data[i] @@ -446,7 +446,7 @@ def set_body_mass(self, data, name=None): if len(data) != self.nbody: print("SIZE MISMATCH SET_BODY_MASS()") exit(1) - + for i in range(self.nbody): c_arr[i] = data[i] @@ -458,7 +458,7 @@ def set_body_mass(self, data, name=None): def set_body_pos(self, name, data): if len(data) != 3: - print("SIZE MISMATCH SET BODY POS") + print("SIZE MISMATCH SET BODY POS") exit(1) c_arr = (ctypes.c_double * 3)() for i in range(3): @@ -472,7 +472,7 @@ def set_body_ipos(self, data): if len(data) != nbody: print("SIZE MISMATCH SET_BODY_IPOS()") exit(1) - + for i in range(nbody): c_arr[i] = data[i] @@ -499,24 +499,24 @@ def set_geom_friction(self, data, name=None): def set_geom_rgba(self, data, name=None): if name is None: - ngeom = self.ngeom * 4 + ngeom = self.ngeom * 4 - if len(data) != ngeom: - print("SIZE MISMATCH SET_GEOM_RGBA()") - exit(1) + if len(data) != ngeom: + print("SIZE MISMATCH SET_GEOM_RGBA()") + exit(1) - c_arr = (ctypes.c_float * ngeom)() + c_arr = (ctypes.c_float * ngeom)() - for i in range(ngeom): - c_arr[i] = data[i] + for i in range(ngeom): + c_arr[i] = data[i] - cassie_sim_set_geom_rgba(self.c, c_arr) + cassie_sim_set_geom_rgba(self.c, c_arr) else: rgba_array = (ctypes.c_float * 4)() for i in range(4): rgba_array[i] = data[i] cassie_sim_set_geom_name_rgba(self.c, name.encode(), rgba_array) - + def set_geom_quat(self, data, name=None): if name is None: ngeom = self.ngeom * 4 @@ -537,7 +537,7 @@ def set_geom_quat(self, data, name=None): quat_array[i] = data[i] cassie_sim_set_geom_name_quat(self.c, name.encode(), quat_array) - + def set_geom_pos(self, data, name=None): if name is None: ngeom = self.ngeom * 3 @@ -612,7 +612,7 @@ def set_hfield_data(self, data, vis=None): if vis is not None: cassie_vis_remakeSceneCon(vis) - + def get_hfield_data(self): nhfielddata = self.get_nhfielddata() ret = np.zeros(nhfielddata) @@ -636,7 +636,7 @@ def get_joint_filter(self): j_filters = cassie_sim_joint_filter(self.c) return j_filters - # Set interal state of the joint filters. Takes in 2 arrays of values (x and y), which should be 6*4 and 6*3 long respectively. + # Set interal state of the joint filters. Takes in 2 arrays of values (x and y), which should be 6*4 and 6*3 long respectively. # (6 joints, for each joint x has 4 values y has 3) def set_joint_filter(self, x, y): x_arr = (ctypes.c_double * (6*4))(*x) @@ -655,7 +655,7 @@ def set_drive_filter(self, x): x_arr = (ctypes.c_int * (10*9))(*x) cassie_sim_set_drive_filter(self.c, ctypes.cast(x_arr, ctypes.POINTER(ctypes.c_int))) - # Get the current state of the torque delay array. Returns a 2d numpy array of size (10, 6), + # Get the current state of the torque delay array. Returns a 2d numpy array of size (10, 6), # number of motors by number of delay cycles def get_torque_delay(self): t_arr = (ctypes.c_double * 60)() @@ -670,6 +670,40 @@ def set_torque_delay(self, data): def __del__(self): cassie_sim_free(self.c) +class CassieState: + def __init__(self): + self.s = cassie_state_alloc() + + def time(self): + timep = cassie_state_time(self.s) + return timep[0] + + def qpos(self): + qposp = cassie_state_qpos(self.s) + return qposp[:35] + + def qvel(self): + qvelp = cassie_state_qvel(self.s) + return qvelp[:32] + + def set_time(self, time): + timep = cassie_state_time(self.s) + timep[0] = time + + def set_qpos(self, qpos): + qposp = cassie_state_qpos(self.s) + for i in range(min(len(qpos), 35)): + qposp[i] = qpos[i] + + def set_qvel(self, qvel): + qvelp = cassie_state_qvel(self.s) + for i in range(min(len(qvel), 32)): + qvelp[i] = qvel[i] + + def __del__(self): + cassie_state_free(self.s) + + class CassieVis: def __init__(self, c, offscreen=False): self.v = cassie_vis_init(c.c, c.modelfile.encode('utf-8'), ctypes.c_bool(offscreen)) @@ -688,10 +722,10 @@ def ispaused(self): def remake(self): cassie_vis_remakeSceneCon(self.v) - # Applies the inputted force to the inputted body. "xfrc_apply" should contain the force/torque to - # apply in Cartesian coords as a 6-long array (first 3 are force, last 3 are torque). "body_name" + # Applies the inputted force to the inputted body. "xfrc_apply" should contain the force/torque to + # apply in Cartesian coords as a 6-long array (first 3 are force, last 3 are torque). "body_name" # should be a string matching a body name in the XML file. If "body_name" doesn't match an existing - # body name, then no force will be applied. + # body name, then no force will be applied. def apply_force(self, xfrc_apply, body_name): xfrc_array = (ctypes.c_double * 6)() for i in range(len(xfrc_apply)): @@ -795,7 +829,7 @@ def __init__(self, remote_addr='127.0.0.1', remote_port='25000', self.inbuf = ctypes.cast(ctypes.byref(self.recvbuf, 2), ctypes.POINTER(ctypes.c_ubyte)) self.outbuf = ctypes.cast(ctypes.byref(self.sendbuf, 2), - ctypes.POINTER(ctypes.c_ubyte)) + ctypes.POINTER(ctypes.c_ubyte)) def send(self, u): pack_cassie_user_in_t(u, self.outbuf) @@ -809,9 +843,9 @@ def recv_wait(self): nbytes = -1 while nbytes != self.recvlen: nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen, - None, None) + None, None) process_packet_header(self.packet_header_info, - self.recvbuf, self.sendbuf) + self.recvbuf, self.sendbuf) cassie_out = cassie_out_t() unpack_cassie_out_t(self.inbuf, cassie_out) return cassie_out @@ -820,31 +854,31 @@ def recv_wait_pd(self): nbytes = -1 while nbytes != self.recvlen_pd: nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen_pd, - None, None) + None, None) process_packet_header(self.packet_header_info, - self.recvbuf, self.sendbuf) + self.recvbuf, self.sendbuf) state_out = state_out_t() unpack_state_out_t(self.inbuf, state_out) return state_out def recv_newest(self): nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen, - None, None) + None, None) if nbytes != self.recvlen: return None process_packet_header(self.packet_header_info, - self.recvbuf, self.sendbuf) + self.recvbuf, self.sendbuf) cassie_out = cassie_out_t() unpack_cassie_out_t(self.inbuf, cassie_out) return cassie_out def recv_newest_pd(self): nbytes = get_newest_packet(self.sock, self.recvbuf, self.recvlen_pd, - None, None) + None, None) if nbytes != self.recvlen_pd: return None process_packet_header(self.packet_header_info, - self.recvbuf, self.sendbuf) + self.recvbuf, self.sendbuf) state_out = state_out_t() unpack_state_out_t(self.inbuf, state_out) return state_out diff --git a/bindings/pydairlib/cassie/gym_envs/cassiemujoco_ctypes.py b/bindings/pydairlib/cassie/mujoco/cassiemujoco_ctypes.py similarity index 100% rename from bindings/pydairlib/cassie/gym_envs/cassiemujoco_ctypes.py rename to bindings/pydairlib/cassie/mujoco/cassiemujoco_ctypes.py diff --git a/bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py similarity index 95% rename from bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py rename to bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py index 958f24df9d..e2cee6dcb3 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_to_mujoco_converter.py +++ b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py @@ -15,11 +15,16 @@ class DrakeToMujocoConverter(): def __init__(self, drake_sim_dt=5e-5): + self.left_leg_urdf = FindResourceOrThrow('examples/Cassie/urdf/cassie_left_leg.urdf') + self.cassie_v2_urdf = FindResourceOrThrow('examples/Cassie/urdf/cassie_v2.urdf') + self.foot_crank_urdf = FindResourceOrThrow('examples/Cassie/urdf/cassie_foot_crank.urdf') + self.knee_linkage_urdf = FindResourceOrThrow('examples/Cassie/urdf/cassie_knee_linkage.urdf') + self.builder = DiagramBuilder() self.drake_sim_dt = drake_sim_dt self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, drake_sim_dt) addCassieMultibody(self.plant, self.scene_graph, True, - "examples/Cassie/urdf/cassie_v2.urdf", False, False) + 'examples/Cassie/urdf/cassie_v2.urdf', False, False) self.plant.Finalize() self.foot_crank_builder = DiagramBuilder() @@ -27,15 +32,14 @@ def __init__(self, drake_sim_dt=5e-5): drake_sim_dt) Parser(self.foot_crank_plant).AddModelFromFile( - FindResourceOrThrow('examples/Cassie/urdf/cassie_foot_crank.urdf')) + self.foot_crank_urdf) self.foot_crank_plant.Finalize() self.knee_linkage_builder = DiagramBuilder() self.knee_linkage_plant, self.knee_linkage_scene_graph = AddMultibodyPlantSceneGraph(self.knee_linkage_builder, drake_sim_dt) - Parser(self.knee_linkage_plant).AddModelFromFile( - FindResourceOrThrow('examples/Cassie/urdf/cassie_knee_linkage.urdf')) + Parser(self.knee_linkage_plant).AddModelFromFile(self.knee_linkage_urdf) self.knee_linkage_plant.Finalize() self.diagram = self.builder.Build() @@ -133,7 +137,7 @@ def visualize_entire_leg(self, x): plant = MultibodyPlant(self.drake_sim_dt) scene_graph = builder.AddSystem(SceneGraph()) - Parser(plant).AddModelFromFile(FindResourceOrThrow('examples/Cassie/urdf/cassie_left_leg.urdf')) + Parser(plant).AddModelFromFile(self.left_leg_urdf) plant.Finalize() self.print_pos_indices(plant) @@ -150,7 +154,7 @@ def visualize_entire_leg(self, x): left_leg_state[14:17] = left_foot_crank_state[-3:] plant.SetPositions(plant_context, left_leg_state) - visualizer = MultiposeVisualizer('examples/Cassie/urdf/cassie_left_leg.urdf', 1, '') + visualizer = MultiposeVisualizer(self.left_leg_urdf, 1, '') visualizer.DrawPoses(left_leg_state) def visualize_state_lower(self, x): diff --git a/bindings/pydairlib/cassie/gym_envs/libcassiemujoco.so b/bindings/pydairlib/cassie/mujoco/libcassiemujoco.so similarity index 100% rename from bindings/pydairlib/cassie/gym_envs/libcassiemujoco.so rename to bindings/pydairlib/cassie/mujoco/libcassiemujoco.so diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_lcm_utils.py b/bindings/pydairlib/cassie/mujoco/mujoco_lcm_utils.py similarity index 100% rename from bindings/pydairlib/cassie/gym_envs/mujoco_lcm_utils.py rename to bindings/pydairlib/cassie/mujoco/mujoco_lcm_utils.py diff --git a/examples/Cassie/urdf/cassie_foot_crank.urdf b/examples/Cassie/urdf/cassie_foot_crank.urdf new file mode 100644 index 0000000000..b0e2111df1 --- /dev/null +++ b/examples/Cassie/urdf/cassie_foot_crank.urdf @@ -0,0 +1,134 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/examples/Cassie/urdf/cassie_knee_linkage.urdf b/examples/Cassie/urdf/cassie_knee_linkage.urdf new file mode 100644 index 0000000000..c1618a1b76 --- /dev/null +++ b/examples/Cassie/urdf/cassie_knee_linkage.urdf @@ -0,0 +1,229 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/examples/Cassie/urdf/cassie_left_leg.urdf b/examples/Cassie/urdf/cassie_left_leg.urdf new file mode 100644 index 0000000000..d235568aaf --- /dev/null +++ b/examples/Cassie/urdf/cassie_left_leg.urdf @@ -0,0 +1,335 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file From 3a7a076fb59e397e3f22cbbda7bd974b82ea39ac Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 23 Mar 2022 16:24:56 -0400 Subject: [PATCH 164/758] small progress --- bindings/pydairlib/cassie/controllers_py.cc | 3 +++ .../pydairlib/cassie/gym_envs/cassie_gym_test.py | 13 ++++++------- .../pydairlib/cassie/gym_envs/drake_cassie_gym.py | 4 +--- .../pydairlib/cassie/gym_envs/mujoco_cassie_gym.py | 1 + .../diagrams/osc_walking_controller_diagram.cc | 4 +++- .../diagrams/osc_walking_controller_diagram.h | 8 +++++++- 6 files changed, 21 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index f66ba28a14..5b32558620 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -54,6 +54,9 @@ PYBIND11_MODULE(controllers, m) { .def("get_control_output_port", &OSCWalkingControllerDiagram::get_control_output_port, py_rvp::reference_internal) + .def("get_torque_output_port", + &OSCWalkingControllerDiagram::get_torque_output_port, + py_rvp::reference_internal) .def("get_controller_failure_output_port", &OSCWalkingControllerDiagram::get_controller_failure_output_port, py_rvp::reference_internal); diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 6881e9e8f6..23668ffa83 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,7 +9,8 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -19,19 +20,17 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - # gym_env = DrakeCassieGym(reward_func, visualize=True) - gym_env = MuJoCoCassieGym(reward_func, visualize=True) + gym_env = DrakeCassieGym(reward_func, visualize=True) + # gym_env = MuJoCoCassieGym(reward_func, visualize=True) - # gym_env.make(controller, urdf) gym_env.make(controller) - action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index a472940498..2b5ef142fa 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -102,7 +102,7 @@ def step(self, action=np.zeros(18)): next_timestep = self.sim.get_context().get_time() + self.sim_dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) # self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) - self.sim.AdvanceTo(next_timestep, decimals=3) + self.sim.AdvanceTo(next_timestep) self.current_time = self.sim.get_context().get_time() x = self.plant.GetPositionsAndVelocities( @@ -110,8 +110,6 @@ def step(self, action=np.zeros(18)): self.sim.get_context())) # print(next_timestep) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp - # u = self.controller_output_port.Eval(self.sim.get_context())[:-1] # remove the timestamp - # print(u) # u = np.zeros(10) self.cassie_state = CassieEnvState(self.current_time, x, u, action) reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 12317ec22e..9ff505e529 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -119,6 +119,7 @@ def step(self, action=np.zeros(18)): print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.gym_dt + import pdb; pdb.set_trace() self.controller_state_input_port.FixValue(self.controller_context, self.cassie_state.x) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 129ee752a2..98ea96b8ee 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -467,7 +467,9 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); builder.ExportInput(high_level_command->get_cassie_out_input_port(), "lcmt_cassie_out"); - builder.ExportOutput(command_sender->get_output_port(), "u, t"); + builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); + builder.ExportOutput(osc->get_osc_output_port(), "u, t"); + // builder.ExportOutput(failure_aggregator->get_status_output_port(), // "failure_status"); diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.h b/examples/Cassie/diagrams/osc_walking_controller_diagram.h index 34f6788921..6728c4e38c 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.h @@ -63,6 +63,11 @@ class OSCWalkingControllerDiagram final return this->get_output_port(control_output_port_index_); } + /// @return the output port for the controller torques. + const drake::systems::OutputPort& get_torque_output_port() const { + return this->get_output_port(torque_output_port_index_); + } + /// @return the output port for the failure status of the controller. const drake::systems::OutputPort& get_controller_failure_output_port() const { @@ -152,7 +157,8 @@ class OSCWalkingControllerDiagram final const int state_input_port_index_ = 0; const int cassie_out_input_port_index_ = 1; const int control_output_port_index_ = 0; - const int controller_failure_port_index_ = 1; + const int torque_output_port_index_ = 1; + const int controller_failure_port_index_ = 2; const std::string control_channel_name_ = "OSC_WALKING"; }; From df5ee2c21af1dfeef1ac8ebb7457af32b9bf488f Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 24 Mar 2022 10:56:15 -0400 Subject: [PATCH 165/758] removing couts in running controller diagram --- .../plot_configs/cassie_running_plot.yaml | 12 ++--- .../cassie/gym_envs/cassie_gym_test.py | 4 +- .../cassie/gym_envs/mujoco_cassie_gym.py | 5 ++- bindings/pydairlib/cassie/learn_osc_gains.py | 44 ++++++++++++------- .../pydairlib/systems/robot_lcm_systems_py.cc | 12 ++++- examples/Cassie/diagrams/cassie_sim_diagram.h | 2 +- .../osc_running_controller_diagram.cc | 6 +-- .../osc_run/learned_osc_running_gains.yaml | 19 ++++---- .../Cassie/osc_run/osc_running_gains.yaml | 4 +- examples/Cassie/run_osc_running_controller.cc | 2 +- .../impact_aware_time_based_fsm.cc | 8 ++-- systems/controllers/osc/osc_tracking_data.cc | 2 +- 12 files changed, 70 insertions(+), 50 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 74a6995e12..84eeb2d3e1 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -12,12 +12,12 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: true -plot_floating_base_velocities: true +plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true -special_positions_to_plot: [] -special_velocities_to_plot: [] +special_positions_to_plot: ['base_y'] +special_velocities_to_plot: ['base_vy'] special_efforts_to_plot: [] # Foot position plots @@ -34,9 +34,9 @@ tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} - right_ft_traj: {'dims': [2], 'derivs': ['vel']} + left_ft_traj: {'dims': [1], 'derivs': ['pos']} +# right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} # left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [2], 'derivs': ['vel']} +# right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 23668ffa83..04b298d099 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -26,8 +26,8 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - gym_env = DrakeCassieGym(reward_func, visualize=True) - # gym_env = MuJoCoCassieGym(reward_func, visualize=True) + # gym_env = DrakeCassieGym(reward_func, visualize=True) + gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 9ff505e529..75759a1d11 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -19,6 +19,8 @@ from pydairlib.cassie.mujoco.mujoco_lcm_utils import * from pydairlib.cassie.mujoco.drake_to_mujoco_converter import DrakeToMujocoConverter +from pydairlib.systems import (RobotOutputSender, RobotOutputReceiver, OutputVector, + TimestampedVector) class MuJoCoCassieGym(): def __init__(self, reward_func, visualize=False): @@ -67,7 +69,9 @@ def make(self, controller, model_xml='cassie.xml'): # self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) # self.new_plant = self.simulator.get_plant() # self.sensor_aggregator = self.simulator.get_sensor_aggregator() + self.robot_output_sender = RobotOutputSender(self.plant, True) self.builder.AddSystem(self.controller) + self.builder.AddSystem(self.robot_output_sender) # self.builder.AddSystem(self.simulator) # self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) @@ -119,7 +123,6 @@ def step(self, action=np.zeros(18)): print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.gym_dt - import pdb; pdb.set_trace() self.controller_state_input_port.FixValue(self.controller_context, self.cassie_state.x) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 1f7e48376c..a913e91e6e 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -38,10 +38,17 @@ def __init__(self, budget, reward_function): self.loss_over_time = [] self.default_osc_gains = { + # 'PelvisKp': np.array([0, 0, 85]), + # 'PelvisKd': np.array([1, 0, 5]), + # 'PelvisRotKp': np.array([50, 100, 0]), + # 'PelvisRotKd': np.array([10, 5, 1]), 'SwingFootKp': np.array([125, 80, 50]), 'SwingFootKd': np.array([5, 5, 1]), - 'FootstepKd': np.array([0.2, 0.45, 0]), + # 'FootstepKd': np.array([0.2, 0.45, 0]), 'center_line_offset': 0.03, + 'rest_length': 0.85, + 'stance_duration': 0.30, + 'flight_duration': 0.08, } def save_params(self, folder, params, budget): @@ -64,7 +71,7 @@ def write_params(self, params): def get_single_loss(self, params): self.write_params(params) - gym_env = DrakeCassieGym(self.reward_function, visualize=True) + gym_env = DrakeCassieGym(self.reward_function, visualize=False) controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, self.urdf, False, False) controller_plant.Finalize() @@ -83,16 +90,23 @@ def get_single_loss(self, params): def learn_gains(self, batch=True): self.loss_over_time = [] self.default_params = ng.p.Dict( - SwingFootKp=ng.p.Array(lower=0., upper=150., shape=(3,)), + # PelvisKp=ng.p.Array(lower=50., upper=150., shape=(3,)), + # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), + # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), + # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - center_line_offset=ng.p.Scalar(lower=0.01, upper=0.1), + # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), + center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), + rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), + flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) self.default_params.value = self.default_osc_gains - optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget, num_workers=10) - with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: + optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) + # with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: # recommendation = optimizer.minimize(square, executor=executor, batch_mode=False) - params = optimizer.minimize(self.get_single_loss, executor, batch_mode=True) + params = optimizer.minimize(self.get_single_loss) loss_samples = np.array(self.loss_over_time) np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) self.save_params(self.drake_params_folder, params, budget) @@ -100,15 +114,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 5 + budget = 1000 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function) - optimizer.learn_gains() + # optimizer.learn_gains() - # optimal_params = optimizer.load_params('2022_03_22_12_1000', optimizer.drake_params_folder).value - # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - # plt.plot(reward_over_time) - # plt.show() + optimal_params = optimizer.load_params('2022_03_23_16_1000', optimizer.drake_params_folder).value + optimizer.write_params(optimal_params) + reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + plt.plot(reward_over_time) + plt.show() diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 85bad8e44f..59c645377d 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -16,6 +16,7 @@ PYBIND11_MODULE(robot_lcm_systems, m) { m.doc() = "Binding robot lcm systems"; using drake::multibody::MultibodyPlant; + using systems::RobotOutputSender; py::class_>( m, "RobotOutputReceiver") @@ -23,9 +24,16 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotInputReceiver") .def(py::init&>()); - py::class_>( + py::class_>( m, "RobotOutputSender") - .def(py::init&, bool>()); + .def(py::init&, bool>()) + .def("get_input_port_state", &RobotOutputSender::get_input_port_state) + .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort) + .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu); + py::class_>( + m, "RobotCommandSender") + .def(py::init&>()); + } } // namespace pydairlib diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 8aed40f84d..1356932962 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -61,7 +61,7 @@ class CassieSimDiagram : public drake::systems::Diagram { const int radio_input_port_index_ = 1; const int state_output_port_index_ = 0; const int cassie_out_output_port_index_ = 1; - const double actuator_delay = 3e-3; // 3ms + const double actuator_delay = 5e-3; // 5ms const double actuator_update_rate = 1e-3; // 1ms const double dt_ = 8e-5; }; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 761052f03d..f4113efd34 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -154,11 +154,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( accumulated_state_durations = vector(); accumulated_state_durations.push_back(0); - std::cout << accumulated_state_durations.back() << std::endl; for (double state_duration : state_durations) { accumulated_state_durations.push_back(accumulated_state_durations.back() + state_duration); - std::cout << accumulated_state_durations.back() << std::endl; } accumulated_state_durations.pop_back(); @@ -172,7 +170,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto failure_aggregator = builder.AddSystem( control_channel_name_, 1); - std::vector tau = {.05, .05, .01}; + std::vector tau = {.05, .1, .01}; auto ekf_filter = builder.AddSystem(plant, tau); @@ -209,8 +207,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** Tracking Data *****/ - std::cout << "Creating tracking data. " << std::endl; - cassie::osc::HighLevelCommand* high_level_command; high_level_command = builder.AddSystem( plant, plant_context.get(), osc_running_gains.vel_scale_rot, diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 319f626703..4ce6e486ef 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,5 +1,4 @@ -FootstepKd: [0.2856883832745447, 0.0, 0.0, 0.0, 0.4713051840283412, 0.0, 0.0, 0.0, - 0.009341449817435035] +FootstepKd: [0.2, 0, 0, 0, 0.45, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] @@ -9,18 +8,18 @@ PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [3.244158138852018, 0.0, 0.0, 0.0, 5.567615547490108, 0.0, 0.0, 0.0, - 1.6063658571340755] -SwingFootKp: [130.03881803493078, 0.0, 0.0, 0.0, 79.25991410071981, 0.0, 0.0, 0.0, - 53.370277764220475] +SwingFootKd: [6.981824273605074, 0.0, 0.0, 0.0, 6.077399963928823, 0.0, 0.0, 0.0, + 3.6565557857296147] +SwingFootKp: [147.18543294545597, 0.0, 0.0, 0.0, 87.66776852252649, 0.0, 0.0, 0.0, + 70.4516871540254] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.08826086956521739 -flight_duration: 0.08 +center_line_offset: 0.0517159042021505 +flight_duration: 0.06105100492064167 footstep_offset: -0.05 hip_yaw_kd: 1 hip_yaw_kp: 40 @@ -28,8 +27,8 @@ impact_threshold: 0.025 mu: 0.6 relative_feet: true relative_pelvis: true -rest_length: 0.85 -stance_duration: 0.3 +rest_length: 0.8479107448465333 +stance_duration: 0.3044202907926943 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 69a6fdb070..d51e18aec7 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -42,7 +42,7 @@ hip_yaw_kd: 1 footstep_offset: -0.05 center_line_offset: 0.03 FootstepKd: - [ 0.3, 0, 0, + [ 0.2, 0, 0, 0, 0.45, 0, 0, 0, 0] PelvisW: @@ -79,7 +79,7 @@ SwingFootKp: 0, 0, 50.] SwingFootKd: [5., 0, 0, - 0, 4., 0, + 0, 5., 0, 0, 0, 1.] LiftoffSwingFootW: [0.1, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index bacb58ec65..921616e6b0 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -187,7 +187,7 @@ int DoMain(int argc, char* argv[]) { auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - std::vector tau = {.05, .05, .01}; + std::vector tau = {.05, .1, .01}; auto ekf_filter = builder.AddSystem(plant, tau); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 170cda090c..e156e3e47c 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -48,10 +48,10 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( } } - std::cout << "Impact times: " << std::endl; - for(int i = 0; i < impact_times_.size(); ++i){ - std::cout << impact_times_[i] << std::endl; - } +// std::cout << "Impact times: " << std::endl; +// for(int i = 0; i < impact_times_.size(); ++i){ +// std::cout << impact_times_[i] << std::endl; +// } period_ = sum; } diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index b7116762b6..81bb6da152 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -130,7 +130,7 @@ void OscTrackingData::AddFiniteStateToTrack(int state) { // Run this function in OSC constructor to make sure that users constructed // OscTrackingData correctly. void OscTrackingData::CheckOscTrackingData() { - cout << "Checking " << name_ << endl; +// cout << "Checking " << name_ << endl; CheckDerivedOscTrackingData(); DRAKE_DEMAND((K_p_.rows() == n_ydot_) && (K_p_.cols() == n_ydot_)); From 469e170ca9ed258bb8016ed06f9dbfb3ad854303 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 24 Mar 2022 11:35:50 -0400 Subject: [PATCH 166/758] need to add cassie_out to gym --- bindings/pydairlib/cassie/controllers_py.cc | 2 ++ .../cassie/gym_envs/cassie_gym_test.py | 4 +-- .../cassie/gym_envs/mujoco_cassie_gym.py | 30 +++++++------------ bindings/pydairlib/systems/__init__.py | 3 ++ .../pydairlib/systems/robot_lcm_systems_py.cc | 7 +++-- .../osc_running_controller_diagram.cc | 3 +- .../diagrams/osc_running_controller_diagram.h | 5 ++++ 7 files changed, 29 insertions(+), 25 deletions(-) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index 5b32558620..7934b93485 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -25,6 +25,8 @@ PYBIND11_MODULE(controllers, m) { m, "OSCRunningControllerFactory") .def(py::init&, const std::string&, const std::string&>(), py::arg("plant"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) + .def("get_plant", &OSCRunningControllerDiagram::get_plant, + py_rvp::reference_internal) .def("get_state_input_port", &OSCRunningControllerDiagram::get_state_input_port, py_rvp::reference_internal) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 04b298d099..14b2ad4f4d 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -20,8 +20,8 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 75759a1d11..d0b3a18dde 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -19,8 +19,7 @@ from pydairlib.cassie.mujoco.mujoco_lcm_utils import * from pydairlib.cassie.mujoco.drake_to_mujoco_converter import DrakeToMujocoConverter -from pydairlib.systems import (RobotOutputSender, RobotOutputReceiver, OutputVector, - TimestampedVector) +from pydairlib.systems import (RobotOutputSender, RobotOutputReceiver) class MuJoCoCassieGym(): def __init__(self, reward_func, visualize=False): @@ -36,7 +35,8 @@ def __init__(self, reward_func, visualize=False): self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' - + self.cassie_in = cassie_user_in_t() + self.cassie_out = cassie_out_t() self.action_dim = 10 self.state_dim = 45 self.x_init = np.array( @@ -61,32 +61,24 @@ def __init__(self, reward_func, visualize=False): def make(self, controller, model_xml='cassie.xml'): self.builder = DiagramBuilder() self.dt = 8e-5 - self.plant = MultibodyPlant(self.dt) + # self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSim(self.default_model_directory + model_xml) if self.visualize: self.cassie_vis = CassieVis(self.simulator) - # self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) - # self.new_plant = self.simulator.get_plant() - # self.sensor_aggregator = self.simulator.get_sensor_aggregator() - self.robot_output_sender = RobotOutputSender(self.plant, True) self.builder.AddSystem(self.controller) + self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), True) self.builder.AddSystem(self.robot_output_sender) - # self.builder.AddSystem(self.simulator) - # self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) - # self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) - # self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), - # self.controller.get_cassie_out_input_port()) - # self.builder.Connect(self.controller, self.simulator.get_radio_input_port()) + self.builder.Connect(self.robot_output_sender.get_output_port(), self.controller.get_state_input_port()) self.drake_to_mujoco_converter = DrakeToMujocoConverter(self.sim_dt) self.diagram = self.builder.Build() self.sim = Simulator(self.diagram) - # self.simulator_context = self.diagram.GetMutableSubsystemContext(self.simulator, self.sim.get_mutable_context()) + self.robot_output_sender_context = self.diagram.GetMutableSubsystemContext(self.robot_output_sender, + self.sim.get_mutable_context()) self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.sim.get_mutable_context()) - self.controller_state_input_port = self.controller.get_state_input_port() self.controller_output_port = self.controller.get_torque_output_port() self.sim.get_mutable_context().SetTime(self.start_time) self.reset() @@ -123,11 +115,11 @@ def step(self, action=np.zeros(18)): print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.gym_dt - self.controller_state_input_port.FixValue(self.controller_context, self.cassie_state.x) + self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) + import pdb; pdb.set_trace() u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) - - self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) + self.sim.AdvanceTo(next_timestep) while self.simulator.time() < next_timestep: self.simulator.step(cassie_in) if self.visualize: diff --git a/bindings/pydairlib/systems/__init__.py b/bindings/pydairlib/systems/__init__.py index e69de29bb2..6d9cbd8491 100644 --- a/bindings/pydairlib/systems/__init__.py +++ b/bindings/pydairlib/systems/__init__.py @@ -0,0 +1,3 @@ +# Importing everything in this directory to this package +from .robot_lcm_systems import * +from .primitives import * diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 59c645377d..922f4eca69 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -17,6 +17,7 @@ PYBIND11_MODULE(robot_lcm_systems, m) { using drake::multibody::MultibodyPlant; using systems::RobotOutputSender; + using py_rvp = py::return_value_policy; py::class_>( m, "RobotOutputReceiver") @@ -27,9 +28,9 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotOutputSender") .def(py::init&, bool>()) - .def("get_input_port_state", &RobotOutputSender::get_input_port_state) - .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort) - .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu); + .def("get_input_port_state", &RobotOutputSender::get_input_port_state, py_rvp::reference_internal) + .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort, py_rvp::reference_internal) + .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu, py_rvp::reference_internal); py::class_>( m, "RobotCommandSender") .def(py::init&>()); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index f4113efd34..baacdb9f20 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -74,7 +74,8 @@ namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::multibody::MultibodyPlant& plant, const string& osc_gainsfilename, const string& osqp_settings_filename) - : pos_map(multibody::makeNameToPositionsMap(plant)), + : plant_(&plant), + pos_map(multibody::makeNameToPositionsMap(plant)), vel_map(multibody::makeNameToVelocitiesMap(plant)), act_map(multibody::makeNameToActuatorsMap(plant)), left_toe(LeftToeFront(plant)), diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index 03363af32a..c30fed4ce1 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -69,7 +69,12 @@ class OSCRunningControllerDiagram final return this->get_output_port(controller_failure_port_index_); } + drake::multibody::MultibodyPlant& get_plant() { + return *plant_; + } + private: + drake::multibody::MultibodyPlant* plant_; std::map pos_map; std::map vel_map; std::map act_map; From aa99353d26143418402ecbb0563db411c9392e21 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 25 Mar 2022 18:35:12 -0400 Subject: [PATCH 167/758] mujoco gym works as well --- bindings/pydairlib/cassie/controllers_py.cc | 6 +- .../cassie/gym_envs/cassie_gym_test.py | 7 +- .../cassie/gym_envs/drake_cassie_gym.py | 5 +- .../cassie/gym_envs/mujoco_cassie_gym.py | 84 ++++++++++++++++++- bindings/pydairlib/cassie/learn_osc_gains.py | 39 +++++---- bindings/pydairlib/lcm/BUILD.bazel | 1 + bindings/pydairlib/lcm/lcm_py.cc | 3 + .../lcm/lcm_py_bind_cpp_serializers.h | 1 + .../pydairlib/systems/robot_lcm_systems_py.cc | 7 +- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/closed_loop_running_sim.cc | 15 ++-- examples/Cassie/diagrams/BUILD.bazel | 1 + .../osc_running_controller_diagram.cc | 8 +- .../diagrams/osc_running_controller_diagram.h | 6 +- .../osc_walking_controller_diagram.cc | 2 +- examples/Cassie/osc/high_level_command.cc | 17 ++-- examples/Cassie/osc/high_level_command.h | 6 +- .../osc_run/learned_osc_running_gains.yaml | 18 ++-- examples/Cassie/run_osc_running_controller.cc | 9 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- .../Cassie/run_osc_walking_controller_alip.cc | 2 +- systems/controllers/BUILD.bazel | 23 +++++ systems/controllers/cassie_out_to_radio.cc | 31 ++++++- systems/controllers/cassie_out_to_radio.h | 40 +++++++-- 24 files changed, 255 insertions(+), 79 deletions(-) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index 7934b93485..a0922b30b3 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -30,8 +30,8 @@ PYBIND11_MODULE(controllers, m) { .def("get_state_input_port", &OSCRunningControllerDiagram::get_state_input_port, py_rvp::reference_internal) - .def("get_cassie_out_input_port", - &OSCRunningControllerDiagram::get_cassie_out_input_port, + .def("get_radio_input_port", + &OSCRunningControllerDiagram::get_radio_input_port, py_rvp::reference_internal) .def("get_control_output_port", &OSCRunningControllerDiagram::get_control_output_port, @@ -50,7 +50,7 @@ PYBIND11_MODULE(controllers, m) { .def("get_state_input_port", &OSCWalkingControllerDiagram::get_state_input_port, py_rvp::reference_internal) - .def("get_cassie_out_input_port", + .def("get_radio_input_port", &OSCWalkingControllerDiagram::get_cassie_out_input_port, py_rvp::reference_internal) .def("get_control_output_port", diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 14b2ad4f4d..2d94d4d709 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -28,13 +28,12 @@ def main(): # gym_env = DrakeCassieGym(reward_func, visualize=True) gym_env = MuJoCoCassieGym(reward_func, visualize=True) - gym_env.make(controller) action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 - while gym_env.current_time < 20.0: + while gym_env.current_time < 50.0: state, reward = gym_env.step(action) cumulative_reward += reward # gym_env.reset() diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 2b5ef142fa..b353f7f1b6 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -55,8 +55,8 @@ def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) - self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), - self.controller.get_cassie_out_input_port()) + # self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), + # self.controller.get_cassie_out_input_port()) # self.builder.Connect(self.controller, self.simulator.get_radio_input_port()) self.diagram = self.builder.Build() @@ -101,6 +101,7 @@ def step(self, action=np.zeros(18)): # next_timestep = self.sim.get_context().get_time() + self.dt next_timestep = self.sim.get_context().get_time() + self.sim_dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) + self.controller.get_radio_input_port().FixValue(self.controller_context, action) # self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) self.sim.AdvanceTo(next_timestep) self.current_time = self.sim.get_context().get_time() diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index d0b3a18dde..355d77016b 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -9,7 +9,7 @@ from pydairlib.cassie.cassie_utils import * from pydairlib.multibody import * from pydairlib.systems.primitives import * -# from dairlib import lcmt_radio_out +from dairlib import lcmt_cassie_out from pydairlib.cassie.gym_envs.cassie_env_state import CassieEnvState, quat_to_rotation, \ reexpress_state_local_to_global_omega, reexpress_state_global_to_local_omega from pydairlib.cassie.mujoco.drake_to_mujoco_converter import DrakeToMujocoConverter @@ -37,6 +37,7 @@ def __init__(self, reward_func, visualize=False): self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' self.cassie_in = cassie_user_in_t() self.cassie_out = cassie_out_t() + self.cassie_out_lcm = lcmt_cassie_out() self.action_dim = 10 self.state_dim = 45 self.x_init = np.array( @@ -67,7 +68,8 @@ def make(self, controller, model_xml='cassie.xml'): if self.visualize: self.cassie_vis = CassieVis(self.simulator) self.builder.AddSystem(self.controller) - self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), True) + # self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), True) + self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), False) self.builder.AddSystem(self.robot_output_sender) self.builder.Connect(self.robot_output_sender.get_output_port(), self.controller.get_state_input_port()) @@ -80,6 +82,7 @@ def make(self, controller, model_xml='cassie.xml'): self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.sim.get_mutable_context()) self.controller_output_port = self.controller.get_torque_output_port() + self.radio_input_port = self.controller.get_radio_input_port() self.sim.get_mutable_context().SetTime(self.start_time) self.reset() self.initialized = True @@ -99,6 +102,9 @@ def reset(self): self.current_time = self.start_time self.prev_cassie_state = CassieEnvState(self.current_time, self.x_init, u, np.zeros(18)) self.cassie_state = CassieEnvState(self.current_time, self.x_init, u, np.zeros(18)) + cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) + self.cassie_out = self.simulator.step(cassie_in) + self.cassie_out_lcm = self.pack_cassie_out(self.cassie_out) self.terminated = False return @@ -115,8 +121,10 @@ def step(self, action=np.zeros(18)): print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.gym_dt + # action[2] = 0.75 self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) - import pdb; pdb.set_trace() + self.radio_input_port.FixValue(self.controller_context, action) + u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) self.sim.AdvanceTo(next_timestep) @@ -148,5 +156,75 @@ def pack_input(self, cassie_in, u_drake): u_mujoco[self.actuator_index_map[u_name]] = u_drake[act_map[u_name]] return cassie_in, u_mujoco + def pack_cassie_out(self, cassie_out): + cassie_out_lcm = lcmt_cassie_out() + cassie_out_lcm.utime = self.current_time * 1e6 + cassie_out_lcm.pelvis.targetPc.etherCatStatus = cassie_out.pelvis.targetPc.etherCatStatus + cassie_out_lcm.pelvis.targetPc.etherCatNotifications = cassie_out.pelvis.targetPc.etherCatNotifications + cassie_out_lcm.pelvis.targetPc.taskExecutionTime = cassie_out.pelvis.targetPc.taskExecutionTime + cassie_out_lcm.pelvis.targetPc.overloadCounter = cassie_out.pelvis.targetPc.overloadCounter + cassie_out_lcm.pelvis.targetPc.cpuTemperature = cassie_out.pelvis.targetPc.cpuTemperature + cassie_out_lcm.pelvis.battery.dataGood = cassie_out.pelvis.battery.dataGood + cassie_out_lcm.pelvis.battery.stateOfCharge = cassie_out.pelvis.battery.stateOfCharge + cassie_out_lcm.pelvis.battery.current = cassie_out.pelvis.battery.current + cassie_out_lcm.pelvis.battery.voltage = cassie_out.pelvis.battery.voltage + cassie_out_lcm.pelvis.battery.temperature = cassie_out.pelvis.battery.temperature + cassie_out_lcm.pelvis.radio.radioReceiverSignalGood = cassie_out.pelvis.radio.radioReceiverSignalGood + cassie_out_lcm.pelvis.radio.receiverMedullaSignalGood = cassie_out.pelvis.radio.receiverMedullaSignalGood + cassie_out_lcm.pelvis.radio.channel = cassie_out.pelvis.radio.channel + cassie_out_lcm.pelvis.radio.receiverMedullaSignalGood = cassie_out.pelvis.radio.receiverMedullaSignalGood + cassie_out_lcm.pelvis.battery.temperature = cassie_out.pelvis.battery.temperature + cassie_out_lcm.pelvis.vectorNav.dataGood = cassie_out.pelvis.vectorNav.dataGood + cassie_out_lcm.pelvis.vectorNav.vpeStatus = cassie_out.pelvis.vectorNav.vpeStatus + cassie_out_lcm.pelvis.vectorNav.pressure = cassie_out.pelvis.vectorNav.pressure + cassie_out_lcm.pelvis.vectorNav.temperature = cassie_out.pelvis.vectorNav.temperature + cassie_out_lcm.pelvis.vectorNav.magneticField = cassie_out.pelvis.vectorNav.magneticField + cassie_out_lcm.pelvis.vectorNav.angularVelocity = cassie_out.pelvis.vectorNav.angularVelocity + cassie_out_lcm.pelvis.vectorNav.linearAcceleration = cassie_out.pelvis.vectorNav.linearAcceleration + cassie_out_lcm.pelvis.vectorNav.orientation = cassie_out.pelvis.vectorNav.orientation + cassie_out_lcm.pelvis.medullaCounter = cassie_out.pelvis.medullaCounter + cassie_out_lcm.pelvis.medullaCpuLoad = cassie_out.pelvis.medullaCpuLoad + cassie_out_lcm.pelvis.bleederState = cassie_out.pelvis.bleederState + cassie_out_lcm.pelvis.leftReedSwitchState = cassie_out.pelvis.leftReedSwitchState + cassie_out_lcm.pelvis.rightReedSwitchState = cassie_out.pelvis.rightReedSwitchState + cassie_out_lcm.pelvis.vtmTemperature = cassie_out.pelvis.vtmTemperature + + cassie_out_lcm.isCalibrated = cassie_out.isCalibrated + cassie_out_lcm.pelvis.vectorNav.temperature = cassie_out.pelvis.vectorNav.temperature + + self.copy_leg(cassie_out_lcm.leftLeg, cassie_out.leftLeg) + self.copy_leg(cassie_out_lcm.rightLeg, cassie_out.rightLeg) + + # import pdb; pdb.set_trace() + + # copy_vector_int16(cassie_out->messages, + # message->messages, 4); + + def copy_leg(self, cassie_leg_out_lcm, cassie_leg_out): + self.copy_elmo(cassie_leg_out_lcm.hipRollDrive, cassie_leg_out.hipRollDrive) + self.copy_elmo(cassie_leg_out_lcm.hipYawDrive, cassie_leg_out.hipYawDrive) + self.copy_elmo(cassie_leg_out_lcm.hipPitchDrive, cassie_leg_out.hipPitchDrive) + self.copy_elmo(cassie_leg_out_lcm.kneeDrive, cassie_leg_out.kneeDrive) + self.copy_elmo(cassie_leg_out_lcm.footDrive, cassie_leg_out.footDrive) + cassie_leg_out_lcm.shinJoint.position = cassie_leg_out.shinJoint.position + cassie_leg_out_lcm.shinJoint.velocity = cassie_leg_out.shinJoint.velocity + cassie_leg_out_lcm.tarsusJoint.position = cassie_leg_out.tarsusJoint.position + cassie_leg_out_lcm.tarsusJoint.velocity = cassie_leg_out.tarsusJoint.velocity + cassie_leg_out_lcm.footJoint.position = cassie_leg_out.footJoint.position + cassie_leg_out_lcm.footJoint.velocity = cassie_leg_out.footJoint.velocity + cassie_leg_out_lcm.medullaCounter = cassie_leg_out.medullaCounter + cassie_leg_out_lcm.medullaCpuLoad = cassie_leg_out.medullaCpuLoad + cassie_leg_out_lcm.reedSwitchState = cassie_leg_out.reedSwitchState + + def copy_elmo(self, elmo_out_lcm, elmo_out): + elmo_out_lcm.statusWord = elmo_out.statusWord + elmo_out_lcm.position = elmo_out.position + elmo_out_lcm.velocity = elmo_out.velocity + elmo_out_lcm.torque = elmo_out.torque + elmo_out_lcm.driveTemperature = elmo_out.driveTemperature + elmo_out_lcm.dcLinkVoltage = elmo_out.dcLinkVoltage + elmo_out_lcm.torqueLimit = elmo_out.torqueLimit + elmo_out_lcm.gearRatio = elmo_out.gearRatio + def free_sim(self): del self.cassie_env diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index a913e91e6e..0b4ecb4ff1 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -6,6 +6,8 @@ import nevergrad as ng from pydairlib.cassie.gym_envs.drake_cassie_gym import * +from pydairlib.cassie.gym_envs.mujoco_cassie_gym import * + # from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory from pydairlib.cassie.controllers import OSCWalkingControllerFactory @@ -19,7 +21,7 @@ class OSCGainsOptimizer(): - def __init__(self, budget, reward_function): + def __init__(self, budget, reward_function, visualize=False): self.budget = budget self.total_loss = 0 self.reward_function = reward_function @@ -27,8 +29,10 @@ def __init__(self, budget, reward_function): self.gym_env = None self.sim = None self.controller = None + self.visualize = visualize self.urdf = 'examples/Cassie/urdf/cassie_v2.urdf' + self.controller_urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' @@ -38,7 +42,7 @@ def __init__(self, budget, reward_function): self.loss_over_time = [] self.default_osc_gains = { - # 'PelvisKp': np.array([0, 0, 85]), + 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), # 'PelvisRotKd': np.array([10, 5, 1]), @@ -71,13 +75,18 @@ def write_params(self, params): def get_single_loss(self, params): self.write_params(params) - gym_env = DrakeCassieGym(self.reward_function, visualize=False) + if np.random.random() < 0.5: + print('drake_sim') + gym_env = DrakeCassieGym(self.reward_function, visualize=self.visualize) + else: + print('mujoco') + gym_env = MuJoCoCassieGym(self.reward_function, visualize=self.visualize) controller_plant = MultibodyPlant(8e-5) - addCassieMultibody(controller_plant, None, True, self.urdf, False, False) + addCassieMultibody(controller_plant, None, True, self.controller_urdf, False, False) controller_plant.Finalize() controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, - self.osqp_settings) - gym_env.make(controller, self.urdf) + self.osqp_settings) + gym_env.make(controller) # rollout a trajectory and compute the loss cumulative_reward = 0 while gym_env.current_time < 7.5 and not gym_env.terminated: @@ -90,7 +99,7 @@ def get_single_loss(self, params): def learn_gains(self, batch=True): self.loss_over_time = [] self.default_params = ng.p.Dict( - # PelvisKp=ng.p.Array(lower=50., upper=150., shape=(3,)), + PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), @@ -105,7 +114,7 @@ def learn_gains(self, batch=True): self.default_params.value = self.default_osc_gains optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) # with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: - # recommendation = optimizer.minimize(square, executor=executor, batch_mode=False) + # recommendation = optimizer.minimize(square, executor=executor, batch_mode=False) params = optimizer.minimize(self.get_single_loss) loss_samples = np.array(self.loss_over_time) np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) @@ -118,11 +127,11 @@ def learn_gains(self, batch=True): reward_function = RewardOSUDRL() - optimizer = OSCGainsOptimizer(budget, reward_function) - # optimizer.learn_gains() + optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) + optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_23_16_1000', optimizer.drake_params_folder).value - optimizer.write_params(optimal_params) - reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - plt.plot(reward_over_time) - plt.show() + # optimal_params = optimizer.load_params('2022_03_24_17_1000', optimizer.drake_params_folder).value + # optimizer.write_params(optimal_params) + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + # plt.plot(reward_over_time) + # plt.show() diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index a98bb27ba7..d40bcb5b64 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -17,6 +17,7 @@ pybind_py_library( cc_deps = [ "//lcmtypes:lcmt_robot", "@drake//bindings/pydrake/systems:lcm_pybind", + "@drake//bindings/pydrake/common:value_pybind", ], cc_srcs = [ "lcm_py.cc", diff --git a/bindings/pydairlib/lcm/lcm_py.cc b/bindings/pydairlib/lcm/lcm_py.cc index bbd16d2302..dab04cbacf 100644 --- a/bindings/pydairlib/lcm/lcm_py.cc +++ b/bindings/pydairlib/lcm/lcm_py.cc @@ -3,8 +3,10 @@ #include "bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h" #include "pybind11/eval.h" #include "pybind11/pybind11.h" +#include "dairlib/lcmt_cassie_out.hpp" #include "drake/bindings/pydrake/pydrake_pybind.h" +#include "drake/bindings/pydrake/common/value_pybind.h" namespace dairlib { namespace pydairlib { @@ -17,6 +19,7 @@ PYBIND11_MODULE(lcm_py, m) { // PYDRAKE_PREVENT_PYTHON3_MODULE_REIMPORT(m); // Bind C++ serializers. BindCppSerializers(); + drake::pydrake::AddValueInstantiation(m); } } // namespace pydrake diff --git a/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h index 5c537b32d9..baddb291c6 100644 --- a/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h +++ b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.h @@ -13,6 +13,7 @@ For more usages in Python, see the following in `_lcm_extra.py`: - _make_lcm_publisher / LcmPublisherSystem.Make */ +#include namespace dairlib { namespace pydairlib { //namespace pysystems { diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index c5bfca18fe..faf28fba7b 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -17,6 +17,7 @@ PYBIND11_MODULE(robot_lcm_systems, m) { using drake::multibody::MultibodyPlant; using systems::RobotOutputSender; + using py_rvp = py::return_value_policy; py::class_>( m, "RobotOutputReceiver") @@ -27,9 +28,9 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotOutputSender") .def(py::init&, bool>()) - .def("get_input_port_state", &RobotOutputSender::get_input_port_state) - .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort) - .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu); + .def("get_input_port_state", &RobotOutputSender::get_input_port_state, py_rvp::reference_internal) + .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort, py_rvp::reference_internal) + .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu, py_rvp::reference_internal); py::class_>( m, "RobotCommandSender") .def(py::init&>()); diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 3d3e8526cf..52519f00fc 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -380,6 +380,7 @@ cc_binary( "//systems:system_utils", "//systems/filters:floating_base_velocity_filter", "//systems/controllers/osc:osc_tracking_datas", + "//systems/controllers:controllers_all", "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 7f043efe65..2cb8c3b0b8 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -45,7 +45,7 @@ int DoMain(int argc, char* argv[]) { // auto controller_context = controller_plant.CreateDefaultContext(); auto sim_diagram = builder.AddSystem( - std::move(plant), urdf, 0.4, 1e4, 1e2); + std::move(plant), urdf, 0.4, 1e5, 1e2); MultibodyPlant& new_plant = sim_diagram->get_plant(); auto controller_diagram = builder.AddSystem( @@ -58,8 +58,8 @@ int DoMain(int argc, char* argv[]) { sim_diagram->get_actuation_input_port()); builder.Connect(sim_diagram->get_state_output_port(), controller_diagram->get_state_input_port()); - builder.Connect(sim_diagram->get_cassie_out_output_port_index(), - controller_diagram->get_cassie_out_input_port()); +// builder.Connect(sim_diagram->get_cassie_out_output_port_index(), +// controller_diagram->get_cassie_out_input_port()); auto diagram = builder.Build(); diagram->set_name("cassie_running_gym"); @@ -69,17 +69,18 @@ int DoMain(int argc, char* argv[]) { diagram->CreateDefaultContext(); VectorXd x_init = VectorXd::Zero(45); - x_init << 1, 0, 0, 0, 0, 0, 1, -0.0304885, 0, 0.466767, -1.15602, -0.037542, - 1.45243, -0.0257992, -1.59913, 0.0304885, 0, 0.466767, -1.15602, - -0.0374859, 1.45244, -0.0259075, -1.59919, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; + x_init << 1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, + -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; Context& plant_context = diagram->GetMutableSubsystemContext(new_plant, diagram_context.get()); drake::systems::Simulator simulator(*diagram, std::move(diagram_context)); Context& simulator_context = diagram->GetMutableSubsystemContext(*sim_diagram, &simulator.get_mutable_context()); + Context& controller_context = diagram->GetMutableSubsystemContext(*controller_diagram, &simulator.get_mutable_context()); sim_diagram->get_radio_input_port().FixValue(&simulator_context, Eigen::VectorXd::Zero(18)); + controller_diagram->get_radio_input_port().FixValue(&controller_context, Eigen::VectorXd::Zero(18)); new_plant.SetPositionsAndVelocities(&plant_context, x_init); simulator.Initialize(); diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel index a6b6c79520..60af582573 100644 --- a/examples/Cassie/diagrams/BUILD.bazel +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -49,6 +49,7 @@ cc_library( "//systems/controllers/osc:osc_tracking_datas", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems/primitives:radio_parser", "@drake//:drake_shared_library", ], ) diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index baacdb9f20..8925b487e8 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -28,6 +28,7 @@ #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/filters/floating_base_velocity_filter.h" +#include "systems/primitives/radio_parser.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -168,6 +169,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), true, false); + auto radio_parser = builder.AddSystem(); auto failure_aggregator = builder.AddSystem( control_channel_name_, 1); @@ -486,11 +488,13 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->get_tracking_data_input_port("right_toe_angle_traj")); builder.Connect(osc->get_osc_output_port(), command_sender->get_input_port(0)); + builder.Connect(radio_parser->get_output_port(), + high_level_command->get_radio_input_port()); // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); - builder.ExportInput(high_level_command->get_cassie_out_input_port(), - "lcmt_cassie_out"); + builder.ExportInput(radio_parser->get_input_port(), + "raw_radio"); builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); builder.ExportOutput(osc->get_osc_output_port(), "u, t"); builder.ExportOutput(failure_aggregator->get_status_output_port(), diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index c30fed4ce1..bbfabbb491 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -49,8 +49,8 @@ class OSCRunningControllerDiagram final /// @return the input port for the cassie_out struct (containing radio /// commands). - const drake::systems::InputPort& get_cassie_out_input_port() const { - return this->get_input_port(cassie_out_input_port_index_); + const drake::systems::InputPort& get_radio_input_port() const { + return this->get_input_port(radio_input_port_index_); } /// @return the output port for the controller torques. @@ -140,7 +140,7 @@ class OSCRunningControllerDiagram final std::unique_ptr right_hip_yaw_tracking_data; const int state_input_port_index_ = 0; - const int cassie_out_input_port_index_ = 1; + const int radio_input_port_index_ = 1; const int control_output_port_index_ = 0; const int torque_output_port_index_ = 1; const int controller_failure_port_index_ = 2; diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 98ea96b8ee..e0dd47dacf 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -465,7 +465,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); - builder.ExportInput(high_level_command->get_cassie_out_input_port(), + builder.ExportInput(high_level_command->get_radio_input_port(), "lcmt_cassie_out"); builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); builder.ExportOutput(osc->get_osc_output_port(), "u, t"); diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index ca10a9e401..96c455f565 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -43,12 +43,11 @@ HighLevelCommand::HighLevelCommand( drake::systems::Context* context, double vel_scale_rot, double vel_scale_trans_sagital, double vel_scale_trans_lateral) : HighLevelCommand(plant, context) { - cassie_out_port_ = - this->DeclareAbstractInputPort("lcmt_cassie_output", - drake::Value{}) + radio_out_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) .get_index(); use_radio_command_ = true; - vel_scale_rot_ = vel_scale_rot; vel_scale_trans_sagital_ = vel_scale_trans_sagital; vel_scale_trans_lateral_ = vel_scale_trans_lateral; @@ -111,16 +110,16 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( const Context& context, DiscreteValues* discrete_state) const { if (use_radio_command_) { - const auto& cassie_out = this->EvalInputValue( - context, cassie_out_port_); + const auto& radio_out = this->EvalInputValue( + context, radio_out_port_); // TODO(yangwill) make sure there is a message available // des_vel indices: 0: yaw_vel (right joystick left/right) // 1: saggital_vel (left joystick up/down) // 2: lateral_vel (left joystick left/right) Vector3d des_vel; - des_vel << vel_scale_rot_ * cassie_out->pelvis.radio.channel[3], - vel_scale_trans_sagital_ * cassie_out->pelvis.radio.channel[0], - vel_scale_trans_lateral_ * cassie_out->pelvis.radio.channel[1]; + des_vel << vel_scale_rot_ * radio_out->channel[3], + vel_scale_trans_sagital_ * radio_out->channel[0], + vel_scale_trans_lateral_ * radio_out->channel[1]; discrete_state->get_mutable_vector(des_vel_idx_).set_value(des_vel); } else { discrete_state->get_mutable_vector(des_vel_idx_) diff --git a/examples/Cassie/osc/high_level_command.h b/examples/Cassie/osc/high_level_command.h index 4027d2ee64..228e86fa0d 100644 --- a/examples/Cassie/osc/high_level_command.h +++ b/examples/Cassie/osc/high_level_command.h @@ -75,8 +75,8 @@ class HighLevelCommand : public drake::systems::LeafSystem { const drake::systems::OutputPort& get_yaw_output_port() const { return this->get_output_port(yaw_port_); } - const drake::systems::InputPort& get_cassie_out_input_port() const { - return this->get_input_port(cassie_out_port_); + const drake::systems::InputPort& get_radio_input_port() const { + return this->get_input_port(radio_out_port_); } const drake::systems::OutputPort& get_xy_output_port() const { return this->get_output_port(xy_port_); @@ -110,7 +110,7 @@ class HighLevelCommand : public drake::systems::LeafSystem { int state_port_; int yaw_port_; int xy_port_; - int cassie_out_port_ = -1; + int radio_out_port_ = -1; // Indices for the discrete states of this leafsystem drake::systems::DiscreteStateIndex des_vel_idx_; diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 4ce6e486ef..e579da1f38 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -3,23 +3,23 @@ LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] +PelvisKp: [58.69651493481853, 0.0, 0.0, 0.0, 36.86831846956082, 0.0, 0.0, 0.0, 134.9722705422692] PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [6.981824273605074, 0.0, 0.0, 0.0, 6.077399963928823, 0.0, 0.0, 0.0, - 3.6565557857296147] -SwingFootKp: [147.18543294545597, 0.0, 0.0, 0.0, 87.66776852252649, 0.0, 0.0, 0.0, - 70.4516871540254] +SwingFootKd: [6.184287991604621, 0.0, 0.0, 0.0, 12.33458087407842, 0.0, 0.0, 0.0, + 6.001919613735179] +SwingFootKp: [101.29500573242039, 0.0, 0.0, 0.0, 72.7231411452184, 0.0, 0.0, 0.0, + 85.72574891431772] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.0517159042021505 -flight_duration: 0.06105100492064167 +center_line_offset: 0.03229512503184142 +flight_duration: 0.07102876166265246 footstep_offset: -0.05 hip_yaw_kd: 1 hip_yaw_kp: 40 @@ -27,8 +27,8 @@ impact_threshold: 0.025 mu: 0.6 relative_feet: true relative_pelvis: true -rest_length: 0.8479107448465333 -stance_duration: 0.3044202907926943 +rest_length: 0.8458962719169322 +stance_duration: 0.2697674609581958 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 921616e6b0..2c6884a939 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -23,6 +23,7 @@ #include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/cassie_out_to_radio.h" #include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" @@ -184,6 +185,8 @@ int DoMain(int argc, char* argv[]) { auto failure_aggregator = builder.AddSystem(FLAGS_channel_u, 1); + auto cassie_out_to_radio = + builder.AddSystem(); auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -267,8 +270,6 @@ int DoMain(int argc, char* argv[]) { high_level_command = builder.AddSystem( plant, plant_context.get(), osc_gains.vel_scale_rot, osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); - builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_out_input_port()); auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = @@ -541,6 +542,10 @@ int DoMain(int argc, char* argv[]) { osc->get_tracking_data_input_port("right_toe_angle_traj")); // Publisher connections + builder.Connect(cassie_out_receiver->get_output_port(), + cassie_out_to_radio->get_input_port()); + builder.Connect(cassie_out_to_radio->get_output_port(), + high_level_command->get_radio_input_port()); builder.Connect(osc->get_osc_output_port(), command_sender->get_input_port(0)); builder.Connect(command_sender->get_output_port(0), diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 78099d3581..62ffe53ae5 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -179,7 +179,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_out_input_port()); + high_level_command->get_radio_input_port()); } else { high_level_command = builder.AddSystem( plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index ff7c829931..23b38fc0ab 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -175,7 +175,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(cassie_out_receiver->get_output_port(), - high_level_command->get_cassie_out_input_port()); + high_level_command->get_radio_input_port()); } else { high_level_command = builder.AddSystem( plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 374c87611f..48fbd3f483 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -2,6 +2,19 @@ load("@drake//tools/lint:lint.bzl", "add_lint_tests") package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "controllers_all", + srcs = [], + deps = [ + ":affine_controller", + ":geared_motor", + ":cassie_out_to_radio", + ":controller_failure_aggregator", + ":fsm_event_time", + ], +) + cc_library( name = "control_utils", srcs = [ @@ -28,6 +41,16 @@ cc_library( "@lcm", ], ) +cc_library( + name = "cassie_out_to_radio", + srcs = ["cassie_out_to_radio.cc"], + hdrs = ["cassie_out_to_radio.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "@drake//:drake_shared_library", + "@lcm", + ], +) cc_library( name = "linear_controller", diff --git a/systems/controllers/cassie_out_to_radio.cc b/systems/controllers/cassie_out_to_radio.cc index 4c6749ef28..91ef4e2e6a 100644 --- a/systems/controllers/cassie_out_to_radio.cc +++ b/systems/controllers/cassie_out_to_radio.cc @@ -1,5 +1,28 @@ -// -// Created by yangwill on 3/24/22. -// +#include "systems/controllers/cassie_out_to_radio.h" -#include "cassie_out_to_radio.h" +namespace dairlib { +namespace systems { + +using drake::systems::kUseDefaultName; + +CassieOutToRadio::CassieOutToRadio(){ + cassie_out_input_port_ = + this->DeclareAbstractInputPort("lcmt_cassie_out", + drake::Value{}) + .get_index(); + radio_output_port_ = + this->DeclareAbstractOutputPort("lcmt_radio_out", + &CassieOutToRadio::CalcRadioOut) + .get_index(); +} + +void CassieOutToRadio::CalcRadioOut( + const drake::systems::Context& context, + dairlib::lcmt_radio_out* output) const { + const dairlib::lcmt_cassie_out* cassie_output = this->EvalInputValue( + context, cassie_out_input_port_); + *output = cassie_output->pelvis.radio; +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/cassie_out_to_radio.h b/systems/controllers/cassie_out_to_radio.h index ed6380fd44..cf97652bee 100644 --- a/systems/controllers/cassie_out_to_radio.h +++ b/systems/controllers/cassie_out_to_radio.h @@ -1,10 +1,36 @@ -// -// Created by yangwill on 3/24/22. -// +#pragma once +#include "dairlib/lcmt_cassie_out.hpp" +#include "dairlib/lcmt_radio_out.hpp" +#include -#ifndef DAIRLIB_SYSTEMS_CONTROLLERS_CASSIE_OUT_TO_RADIO_H_ -#define DAIRLIB_SYSTEMS_CONTROLLERS_CASSIE_OUT_TO_RADIO_H_ +#include "drake/systems/framework/leaf_system.h" -class cassie_out_to_radio {}; +namespace dairlib { +namespace systems { -#endif // DAIRLIB_SYSTEMS_CONTROLLERS_CASSIE_OUT_TO_RADIO_H_ +class CassieOutToRadio : public drake::systems::LeafSystem { + public: + CassieOutToRadio(); + + const drake::systems::InputPort& get_input_port() const { + return drake::systems::LeafSystem::get_input_port(0); + } + + const drake::systems::OutputPort& get_output_port() const { + return drake::systems::LeafSystem::get_output_port(0); + } + + protected: + void CalcRadioOut( + const drake::systems::Context& context, + dairlib::lcmt_radio_out* output) const; + + private: + bool is_abstract() const { return false;} + + int cassie_out_input_port_; + int radio_output_port_; +}; + +} // namespace systems +} // namespace dairlib From 13e8203d3ca356c8e1919c3155032d88e41c2f3e Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 26 Mar 2022 18:50:22 -0400 Subject: [PATCH 168/758] walking controller adapted for mujoco as well --- bindings/pydairlib/cassie/controllers_py.cc | 4 +++- .../cassie/gym_envs/cassie_gym_test.py | 8 ++++---- bindings/pydairlib/cassie/learn_osc_gains.py | 12 ++++++------ .../cassie/mujoco/libcassiemujoco.so | Bin 257696 -> 257696 bytes examples/Cassie/diagrams/BUILD.bazel | 1 + .../osc_walking_controller_diagram.cc | 11 ++++++++--- .../diagrams/osc_walking_controller_diagram.h | 11 ++++++++--- .../osc_run/learned_osc_running_gains.yaml | 18 +++++++++--------- 8 files changed, 39 insertions(+), 26 deletions(-) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index a0922b30b3..0affd39263 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -47,11 +47,13 @@ PYBIND11_MODULE(controllers, m) { m, "OSCWalkingControllerFactory") .def(py::init&, bool, const std::string&, const std::string&>(), py::arg("plant"), py::arg("has_double_stance"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) + .def("get_plant", &OSCWalkingControllerDiagram::get_plant, + py_rvp::reference_internal) .def("get_state_input_port", &OSCWalkingControllerDiagram::get_state_input_port, py_rvp::reference_internal) .def("get_radio_input_port", - &OSCWalkingControllerDiagram::get_cassie_out_input_port, + &OSCWalkingControllerDiagram::get_radio_input_port, py_rvp::reference_internal) .def("get_control_output_port", &OSCWalkingControllerDiagram::get_control_output_port, diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 2d94d4d709..7204161e61 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -20,8 +20,8 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 0b4ecb4ff1..7518e09829 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -128,10 +128,10 @@ def learn_gains(self, batch=True): reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - optimizer.learn_gains() + # optimizer.learn_gains() - # optimal_params = optimizer.load_params('2022_03_24_17_1000', optimizer.drake_params_folder).value - # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - # plt.plot(reward_over_time) - # plt.show() + optimal_params = optimizer.load_params('2022_03_25_17_1000', optimizer.drake_params_folder).value + optimizer.write_params(optimal_params) + reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + plt.plot(reward_over_time) + plt.show() diff --git a/bindings/pydairlib/cassie/mujoco/libcassiemujoco.so b/bindings/pydairlib/cassie/mujoco/libcassiemujoco.so index 08a0a2c8f85114675c7ceb289e96cb99793dbff7..c34f8fa1a8e4ae269480c3d612c7a438275e67ac 100755 GIT binary patch delta 45328 zcmbrndwh(?7eBtw#A;k3yI58TL85U9QKE`eLZYieqb|);p;4E*i+cz*8X@~xskBcS zw~)G~jY}$G;}Sx$NeCL35~UTF@&qLnRgtp4b7p2q`}_S~-#@k zgZJ+}w{OghBxmZ8+-RjkgU%jh2e|kOUT8k5tok!G9>^gNivrIIW2T605I}n7mn|Z^H$wE~0`d zoOU|2{4LJcY~*}PEnfOUiH1_Aak>sKG`H&t`5exeBlw#@0OfVNIAbJ>sad1B4>ST% z-n<1`q42ZddkKDT!EXx!C|@?8Gx`a>w}_l3l{1CHauO}3`!UYqLYg^6Ya%mYAo#gEIm0CC*Q^4M z(NNSy?z+>^`+^@dn)8cNuHy`d5Bq#5>Mz^Q={R0!!bG6_7jVX8!7mkKHA)P|JmK$@2E5%~ z=a`^bjJayef#Rx?u18x#J5^WTMN z;HNR@VIy-fdEppbCbHaWVJJgX42@==OlRxA=d=ipCRKztS&S>^_-H692*&{opVY=& zZ=nmXxI}a-j}~bCD#EV2uWW7H`9m)e&2C&xb64mEP2-GCg1WcU#7jyb2!EY=0QD^?mA0)z+e1h|1gnWH5O5^r3 z#;2NLydF(|;cwi3{B;%a4cf{rK)faynh`_X)m6Y2Bo$IqE;wFb%RXJPa=2 zb4zGl6SYU(0?OaK*PIFyLt0CMaz zLd2s?SWXn-m?WCvC5D5udEW|o-C?d@%-f-vF4Bva2y`IhD?OUF`7rf6F8UcSGy}xY zPyL%S_J}H{ind1G;e6;p_Sq%cT5(C)+O)HzQO-AQN}{JJ_nUS$NB<|j(?xHk?&P{& zywL2f&*QEu;EdIRKU54K-8s&Hs@Ug=uoJb9(=8wz_&F!Sn8Cx?U*jCskDXOjQUw2hBII!*b}rwU7n*6p z(Wq3;a7NmW@;Gx!E%>)WV{iZ+$`u0yBFsKS@KXi9k>IZo6(oPh8PHJn`JWgWQ8PIm z1r5c|a1n`QxFeLs%{!Tcgg`@%Yw(GL4wMY%8snh?{9G4(9T&^#KwfAn1wU8tGXy_d z+ybd0lR)6ur=u9raYc;muW^Rzq5z^#bHSf@p|J^vG-ceO7ziDHCOPl1b;^_$FqXxw z*+ukV1JP5tx48JHywJQ9L(MCnGn~~w7V`f0Ie&t^OfM|3cgA36%pU4g`Ckuw9njt`{gg% z?X*MS0{yMH$mGqMF2c}7(U6L%oZ+mXk@Fr~%=ykoV1{U5*%8i<7j_nle$t)djGqMm zsc1l%7}3)iAMUa4qN9?(;gZheHAoE6vT2;(llQO2=E_^3*~P6j#$sfwG||-b?&NP18vLFGS1Ya+D`6JDW9mobR+ZQw%u&v)rNjBI2XP2noN# z<-rR3^b+mJ5bbCq_)CSIpr5#%rXYu((awj)4n~?aVv41iD4ux9!r!+UuF*^tLsoZ^ zGZex9UR01Q-Z@~Tu+L)QXtZz?)Y)gFkdGGfJcmG3n}`-9Ps{A!wQk@TQ_>M5bi!f0 z<4j3eI=EI3st$+AIznTz#=4rU0p=kt8i!#S{54tU0V7tYUSbmSbU+x@x9_9)JR=ZZ zruclUVK`0FnE5Temky0?5`QbtVe+3q8z zzr%H6>x?k;dO!RXk#kkGtY+2(of`3`2~Mwn20vbV9o%F1@d_A1s*Y&|js;5t zE%^?EiCxt4Ritf^VRof&WP4Rci90qH!i>5H%>pe+>DZ~=*4Ob?s zc3MB>@cgeEUIo-%tsm}fv_EfO%iCcnQARI_X!rJY94$v&K~}Z?!mf>|R~U~h{ER9e zc2&8ypgD01R-P|t?S3%`J0M2`u)}aHNb!wnAw5?@V_Ju#03yvBG{R(gX-aU+?PZET zj#8SrS~ZqclYq=?N zDAGPi30T;dOzNx5U)WyyLrGouZmR$kvmU`Z*kE|%Fw6$laUG;G)%UvcY++mJw&Jm< zGwFU$`EXHh^IP|zCz6hO$3e49Fi@i*6d~UJ*h&A~g}y*42&q?2DjX>ds4*-`-Eqa? z2)2|S_5urG7HEOn{L4ghObppCt~nfsRe17+SzbYV)VD4R8VDF%=G^Nh-L?T|nhO;Vpxrg09{h4o6nscR4?%j1ET<=!|L)Q8H=*j~oIpyqT%y>!Xp zD4*hRIMmZhx5XW$bINCnJ&3ip61(_^I=wF8y;kmjMd`d`W}TB48I^rm*}3GiI-hbX z{Ib$u=_jr)E-N(0@M+1 zPW62!R}HzG*}>dFa_e{g%{}{%GB)m8V^+x<&Zvvd%rf?p;9YZ%7@E5%?T)xl#UPt#$i~3G+s1@i!jSQhr#8IjWEky7AJ?{ZjU#H zEssW74S#iY(Lh5SKKX#)(o3X4Dt7k+ZrdTp(w)2|0MR za+1JSM!*GFm>-pYd$4h2G+H}`H%9*LP~%t0aDkl7sf=TuU|f;GSWpf6#;QpardF>L zoYiT_Vbv4~Y-KiFfT5ka%+P4#+7f1`O1HO+aYh)wst}xm8n}N{h1+XM-byoFn)y(er(y!D8?CWToKJU z(6FAM%^GGB_Etv-j(PPYWU-bd3UFl%T!5jyam>&NK^L92q+ zVBkO=2N@c074&mK>jbTVjzQcgXjegd30fy;-#W1Vi3W{=;V%Td1l?26xK@e=g9Pm_ zXp^Av1qAVMK?eysLeM5bM+rJy(39%GTMjx9AsEp@AWG0Nf}SMkI6+4XI#JLuf=(86 zoS@eUI#JN6f=(86nprT`2}XvXQw5zZ=rlp+3OYm3MS{*2bcvvI1zjrWB0-l4x*Hc#0|1q8FwiscQU`7?GvP!qBC*zDZ@>B`;^}Yzk8DV^#GMnH%2|3sd zsb+{55|D(k;Q4nz5NO$AnATt;#rq5s&GB`N6Kdqy5jb128E1l#-3^$yMn*Bykc6M> zzlwvAi6l?Lc=bB>u1LjE`vJIH%1n$lio6K!K4+W}MxGbZ6(fWN)9FfIxIoiubA@T1 zgq4<7Z!>z>lL>|zsfh`KhY^f3!N~I-$n1(?oYBUWiA)BJc|r8iJCS6;^B}?DNtStz zgAS`+5rusPZmwf?Mi@oj8x4MDGuB`uPkiW5DdU71S7J{y&*Pkx;V5KbN);TQWLaf6 zKv-qDaKW-=cs$FNB2nrwYwARz)MM7viA1T#tf>=;Qa=E)rcNYE{Q$_CI*};#m^F1G zOX@||)UD)MQokY*dk1iqC9Cx-l97gNxsqo|y~vt6{!j#gRH4ALq<%%3pm~=OQolljfd>0t0(TX(ub_1j&z39w1;Z!=dJ5W0&_ROs6|_mv{(=q{ zbWcG?2s%j6QGzxJdXk{SC7vx;MhixS5Qq_Ul%V4TJxS1sf{qq+vY=xGy-v_^f=(55 zqM*|Roop7248d3@=xjl!3OZNNX@V{ibcUcy1f4DDQbFemx=heTf>s6HtVA#>1fvva zmMt@H#1ClHaaRVu?#DsL^U0{yY%JgQBl0*MU+89)q_Twx)-?c`< zwa$mPZBTP$DywN5(%hJtN%f@hFqoiU%EDKP>cd8;)U@oOmvVi*C;5AyQoY{e1En#} zj$N$LwM^Fju*#C1o1%fY!R}5ruo%0Pu|1t^r*s)(*KVvtZtxg$ztMkeRWS4-vXc}e z4EL_Nhj8ECWVuplO2a}Rcnz%bb@PQ1R#vVaBAWaYF?vWedRMpyv?Yg>%_%+VCIcVI~KXjMel}jKq!d;QJj3y1-m8dOE$sY}rgn*>B+J74HUmrJNado@-(#*xt^x9`7Ve2 zu~WJE-OOhHxM5r}OX1Z9-;u3H@FmA#_|;9BymdY4<)+ly_BN^Gruc31A-~jDhHne? zw$=v~%MJC&4h&C@t{UGWZ-!Z(n5nXjq53H-(j&G@t)!=PP(ss|L72DWLD?~Of8M+ql0*yL4O*yf>S;Kx%&0!5J zE3&uULiN^G<>7XprY`kdG!dVQ6#|FhVO?Ab`>n3xyW>v7-0krGdh8_|=ICkJPNn6} z_uZnmIvn^)=6+B+y^b<@X9x0L9c9f1urq-@#T zjeJ;33HhNT`Q1gC^@H4eD}?jClk?VwSWbpOWv*eCawzJ<(y5E``wwmEi~t-4(-;>; zm)?@Jb5Z=$`;g~EnUUVA&QFA4xkOo;eu_-rq>SBdB)*%J*xen;NTQ_e_Ucq0MBwF? zz4%U&u;)U&O*QYF`229Tq^AC|QF*$%U26{%vOH#?au~)lmEJH8*@B6~kS8g<_p~E( zBxT&5J|sz_e7C1(gFzY>&7me3+oZtT8A;HiYOfpm|fzb+wcShXfbe4|O# zXp(9LNx7zVrljsC594@p7!;>uQY?%W?K5R)c5CwaGi7dey9rPJs$s>>h;O_$Gb_Rd ztUZB^hHq>bt=i@P|AOTJ!N?k`i1ga2gdJK+wr*9<9J)z9daCR@ z>_aq9mCJ`8lXokX!XpF7<0p#yQ6G}}MCoz#F}d=m@^;PuvieVDW{wXD`cqk(vya#+ zln;&#ATuj6S07s|kt>gsw{t^WEsqKKXnmy2$!$aWK2m7zJ-7L=6e9;qk$VN55p`42DZac=V9hwCmXvoeNavyd0Tn%Hd#W8y5_=7 zt}0#y$KCyKz0W!a7w{bh<2~h3fj7B-S7}`Mh3>mAF{{A}@^7$=rz&46*1|Y)B2IBD z>eTcIsQtf8?!C)QzPwYzq)&(%6 zL$giRw_w`7XcDd+^^3u`p4lca5`{*pbcYjRR3h}hb#Q@iOvdvPJnoBNPYa0JC%W4I zXk3DCDj!BjVdK)WK?*9!2JJ9wc4=Ll!M$w1#vdL%Sc@;Kr6;p<75{<(lO?B&`E%^~ z7LfkEajwaF5a$h`n4m+&YTcJl^kGu>KR`ue z4(<8}_)~!uBqc;ML4865lu&IcaxGa!tVqxxcXgT{1O%+2yoF2MDU=Vq*-%C{*0_T)i#qU_hk zq+nh4o5MY?p|4fGc}_pn4qynX#OT>k9V)b;44UCq{;{7J9;h(Ak%gdJhAkQJ930fw z@?zH&@K+BUgd;E1=$^0~aBwpkT`K$Jn#syK%Kl<$Rw`=VKGh~^9b8Dj$;o)7{8r-O$p*ib zje3-ebIQe_oMJfN+H6XSPlfyoBLxQ>P#K&uaw?ZoUYs(*j2a|;IpxbKe@@|S8?c^8 zSrek5f-q}_5%N4x*+7}B8R0m1Em_zP)(kw`XtIuu^980Qs|+P92^enhAqs58zmnV& z7Q#hXlHX}KbJF!01kWcm0S1#Lr4-~|?|=;)H#`eWrQiq)u?E$GczN91HnaXNrGS*F9kqbB>vGx|*cm7AvbUzyR`LNp7{5 zvH{`O07!eRPK#xTH5pq0eg(b-WN`coaCtP$C&R34umvB+`5w+4ci?Tv-dCDwGy})g z`Z3gUWw5o@Q|4*`{OwdfPdRt7<2wz(_J=z6jk)fjFwQ!E?CQSpgnQ^ut&8jnJD=v) z%Zui=N65&fl;q2uqyi=9^3;y6YP%;qgo*|x9gKsD4@1g>WO2kFJYo}#(yMqU!rMvG z5#{lvX66HeK8z1wU>ey}n0MN;0?a86L-K!QRLr!ZW0w`+tGdH5jmhLhU?7v`@E0$2 z%Uta9-Vhw^!({BV9CrUzk6EdLlA1i*G2CH~?WBe#{IT>Mn6V=Y8=Vho!z&!<1;^(@ zww(jd%vPo7wRj%Z1tRpl-{<{mvW6DDp2WE)RH5t3^5Z1h^@Y@E$i&Xh?NNw5S`KFC zv9K%lU{}1su`@y}=R++w23te^!jYk?U*Nv4$X+?-jA`5{)-}rci@yI?J!8h6xdru> zf6XTEA#Bk2_{TwGx?Y3vjHw64dEZ3@-mu~zKAJ(}hNnQYvv5#DbnwPtzFjt1&JVGA z|Hk~YvU|yWUlQIv*2WYB@i_s0+p9a(KgXV~NsT|2!Y-J`UATDH>T18;p}<}#7eP9N z9NOtm$f@OSYjTANGB{2Pm}6{VEFT-?rSg> z(oaeCueE=YRDY24Q@^D8zzfo7g4>^l>rbT9;QmQ;9NMBi2zM#>S2r-e8gA|s42PA) zw|w~vcn!HTlfQ=CDD9*BaTY%3?(>%eRf$$QUTsTe%v8d!4sA6Go|u5Kg8($-V0RQRxh{wH#gKs}8V9+?Q=6Tg@)lZ;8xbRYk zfF@kPy|W2+7U5-Mbor6#O1EEpg2p3l9R`oUCGfAC!w}D`!2TLqx(wdKy#NarV68o~ zHpdGH=lPMHGn93|v?D{nzh9b|d!Teu4(2j(bR?4>9pQYOJBgzsnRu<%X4bobJ#g%M z*uVUjBSo-33UzZwn%8t>25aBH9Cdw+e8Xs0UWzqTi*7b%T@>+4r%s>5-JZ=~PH zieZ0s=}%CBMY{{lB;>j;KLOd({&J>v?;<7cH&3!)in8T5SRYxW9RIDWxfAU6TC{6H zCH}d?eR(66X#*ReZjwPi<@Id27Lyz4ls$r?DD%WQrlGYMpZ**b?syZxMU^2R&nj6&!p zABY>vNAQCD)_ic)>Z;C!ehKZG`@m+hYON^bT|=nfJTCO15c&p$CV~*G4hTDjA19$m zPdIiHz=hb}KFGaavqm$7CD2n?dkK96RhIW-X;s_gzqLB$eim{bT<%c;c!#6M*#xKD z9wGOHQ?hGOQFLs z4z;X-eXuCh&cd4EQ=s)Yr=;I(;W`)?4xhKrC_ml&fb2c17;kwtT2Tx_!AD`_Y390x zxF7TZzUfvk^E&FrM{>PWf&k+^|z{FT5zhR6QYdqff8` z*EKgRNjnWP!ZAeEC*vIsri_bo37~I^4_tE^8UcE1Pb)odw>GCcg_*Xx9W>yI*Z3}K zSPDTn5R{l#I(YU$(z!VSyzPn6wg$FFEGgg$ut2gNP-;t#yv31X6t2fvPfs!7Q(X95 zF-&pQKPNFezi{XThwea3)hisy<;XFPdX@~)5Sq!Mh<_>F!lsPi$on;ww7H1%=7={(4)KaMBhs29bvd%1Ba0Dviz5|9EDHN3 z;B8{j&PEshz+hVgFLP)ISL%t#MUEWh$R>__h2{=%WGhF$=Ey&YY~e^EM-n-*2oW|6 ztbsE)VqVUn2!y6`rQsY}%#o4M3Uw$)dU0erM;ar-#)vi0iz5>`(hCt!u2Y*Mqd8(k z#DyadAq|;fu+tnU^%dUR)<6g3N)RsRNF7A(aO8K6{Kk>Lfl^N+VzverbEt$v ze?Ual46gJeM^19&0U~QTLOF7fBPS49%#kG=`JN*bUHF_M<2bT`Bfp}KX@Z&gJ&;4I zIMg2~wKG@h!jWYhS&v9#ju<#Hiz6!$d4b`x23Ffy6rwodiAWhoZgS)!j-Z@bE#Ocg zhXOft9+h@;WDiHWapVe6>NgxwIMSXY0jLwhk%b)b;7BGSV>t2|N9u9pgc;3+a43{R zFUGNc-GWF5j&$V61CESFM8^?5N3L^Z5F*dUu_*kV&!SMmkzhowbL3Z!t4 zl0$hMI>40-h@^4kdyZ`5$Pq-o;>c=_e8UkLk+~e1$B~sBaYy7+j*Q~S{Be+?VGIW# z6vUxm4o&4sjSy+ak+(TAh9lnrrPk+&8%Kr$qE>y*n*Sn?H9w3CuR=37I8w%u{tPi| z7a?TlPyvVD)fe zBQ~W!he9~y%9Wl0rMBlt2ade@oQ13f>bP@6$C1Yzd4f8BL0W-Z;n_(Rg$EpoK^LxZ zp%WZB$)Ot@8IKk1;z$}tu5g4^l*Ey*IC7RFtU+@)GM6KH9GQ>SWR83a zNCc#-0~|VlP+txOaiyIc`34amj$aj=XuKI2i@Ks zHX4)b-*4U^9EPG37(SeKJi@49itPe(7JP&FYZ?a2a5+*5df1IzoyOiE=0klJZ5e2> z3Dt7`W)Q(5ZWtB$`VC?TlS_5V?c{R)T<(38<8Kh?zePLODYuQwxpFzLH*&8)!lDf^ zI|cD{0CZ>>sDqEv8^Oy=(90>8!sW8L+?`RcE8ffGDsn|bHh^4#7UL|H?|6!HXRsUC zY%;|2(x>>6$mf7&KKV=1`U1k{eS9i66lCCWHXFDgTE62sEC40LYr^?MFkfs1^F`;Z zK4ua)43qWbF|br~j#s3*e1`q<`lVwvEbtAqXDL)S zL1D5+c$IGkLm)mLYpeNg(EJNtTU*rrqml{r1)&<1{qIv}6%A0Rhzoh3rJ65PRTG&d zvw9WAQ2914^;h

idUFsRvMKDHke1p_(r?4k5G}g=8+2jzTr-Bf|43DAb(`t;i;A z{@p&UkP1a9caT!kWu^b)HXX-6ziQl<_k_Q3fy+2C4v6ELCLS8~y-|3Fe3Bbx_3NCg zBtPy*s*Wo;k2jdxje*n98MW~JyWer>1b74BN1Ne`8q2-;(f+Fd3=e+>-DVK@RD7(x!i4{%|I zRY`V28kP$jhOdERHKgMZfbWXnR^0;N4746)j=&;=!!V`>12P9)3h$DJ;F?TpK(B+i zVd(vDrXORz^>1cS3&y>l^QIO!&v7ja_0Q%gv;OoQ-Uu|x(_XQqad^>#TOYv?T?u0T{nrvH{=+yPQi|0IU+gvXROke-0d!1eI#$xv4|A z`tk;l9**HU4m;K!eEeOY)gK|Whw=UF&=|O->@R(_IF?|6rywpImhmN633hXvqAYt7 zKw3^vvY)gd*%Ot^Pu?My#w&FzJCd2>m3J#UkofV+xJq9#cD#~Q+1cyQ2}Cn77?1Qr zzh`4TVA!o1xKJ7zP0YMj*+n9Ck0|y3YDaz;r*!|Td(hKi*jR{lJdE4_WYj2N@r=6S zFkE3qh3_`8jG6>P5VF;bVJxH08pkqf1L$CjHU_j)-t*4W}B$E0~d_pg6rQ1&R~MsPPw@} zqlR<2#c$*WFu6phoHy9RuN(!m14)PBIgBj`%Royl?+2~L3N(Bjq-zjv`#B81034Py z%{xlSI1FWAj<46v7~x#6yEN3fUe^n*Z~&bATnYQTrTOIN*j??Hd&h}^aUK|A5svXw z1^=p3Fjp{C6pSzI$)w5zv(hQ0fyQDr1bU81;0Y+^uo2q%dUv{w!!Qfo#V=i{Z+#3- z!j(}C9L}%2)NR9*de8mL)As!*&E-L=$HzfOkc7mJyAv6Z$U{)BW+JbKy9MQ3K<>d+ zkZAK?OOmj36NV;R?$Z3%##^Itb_qs~qsSUC^4nghreNWKk{`}=7g#%gj7T+@Bh=PZkH%_ zqiOF&DPR24PJaW)ftC+U@Gl%HfBu=W`JYbY!e`2ve~O54jI#FS9CB#1Qt#CVWW{J@ z_^bCxNNr%>wej)mi)K4p&A|pr8=UVAHNgPfu*Osb? z=P-KyEh&~n45vd}B@YrgoKA6-+LLC(=^9tbui=wn(3Wa_QZ6J&d$$O;`@`rZSLtI? zFr50-Pa0)b_-|j)f^n8$Fc1Usq~LQisto zb)|M5I)pFEdn&5HDu`vkp)kmFe$R)}&2^)>G)|GmYw4wA7&>qP{xqPCK4;S)r zLut!;QfCr0ln$vUHR+g$a&by;WYm)bRt}}B>q)K1 zkfAiAp47d8FB6on!j_1((@@)!deTaX3>-pZ-J}GM$X?)GtZq*bGzPp(iNf;s7`LNC zs7C`SiTpm8e&0a4M_LS_-?&Q|vk*ency@Y_MD8cKsKt*?Ep_vc}7Z!Y93;e_do)6$vFc+(J3H~TxW_9f4 z5?6#ov@p^0wF%fx!kgou5Qq~3L9Yd-ae*~LAXx~QUJDH30&|&wF0dAOn}4EeX*bxb z?H}=hiMRD_E)*_=%AiCcJCh0LGA`Zes3uZ#`7X>xAmTYJAaG~_qo;%F;4ndPgD}Ztl1~3W)!Gx zYH(RwfooUmBR5u;l!{RhI^kHs!uCb#V}IMsrqWB&(5oNzM}*eM%1CW^Kf2UIdWW3x zr~5sm*=>ph9u>^xBCvekKF6O8@JMZ9Fdfib3M5rsXhL(zm-O|c`X>PLhR)|dULGQ+$#!+Yxh{YJV)_rU?UAq?BMp= z$$PZL=aTWQo+!2L9_{_P)ZE+>iDg2i8LHft!@PUK?y;c}GobTiC33?dTt04s%S-)s z?;`Z1Qa)pU5P6;{M*!vatQy0n^JJwHiALn1Kv-#ZLQyDu3n6AIf}6r`GG*)9YzLP1n{5}WU+*L_tXHtcYIEmJ0IJBS4q@sJdEwdoZ)u>P&VeG#MmB(K(!7#k`Kj7=h*%l z4TW&MfK^;ij6@vX5vni80%M#Qiyw|~FSR~5%Y1?{*p&sZ7$B%7Qu`5_zJG`N_@Pss z#SjO%Nj-Om>Ly6d+qOo*-CPjw$7-;ZhS4|@sdYmv`3@Zdg67KSK+NER+DAaJ)`Z)S zfH_}v1Oj*i!{N}HH*lo381;H^*y${ubFrhZUg+zODAAZ(4m^sM<6(eDfjKdtA!DpD zBVUn+!*{VC$cEKO;oyYqvJtOibphLWsZGbSS|^5RwXF5P=3`H91hX+XCZf5hPa>9x zSmieZcN_-;Vx8a-025*Bi5)_k|6HQ8CQ41r(-|yZv{y!+2K{fnS#ZI(K0-edO9YPq zn2PEEcHyA*11Gof9F{Qe)uI5qLUY^o))@ zCcQAIzacCm91Gt9FtMN-?b{-?XAuZ0qnjtg)8-%&t;=W*5?hcUW%N1_=0qfJ-}sk# zU;8zFi$b3vod0jw3u@O!A&|}izd27K7#Cq2>R=qYO-HKAmxWO0_qG!=;u!4;YS0kB zg~>o$Y1Ed zIWX&Ul-k^9OYNk_SFZe5M0=Hsq+PL1oFmPv-E{0dXh4-N2!Bx{!T$wJ^Qt1Wk@sv* z7D``AB=HuVA1ie=yu6J+Pmz-N6!1#7wU)I=gfZ_(*X;LYy-P1~g<(#KNWuTb)u?6abb`kUdEWkMMpYL>2$O*d$V zIB8;=7DcSfQ<$aOkwsu#>w5$GG_&v(&gY;0M)$`_UlX~AhAxx3l6FNj2FuDqnvP{| zA^mNcG=fYnqyb+7-J_6B`ceudj|=ENq>mQRTVG0p$@Bu+H6Hlw3TR9`>f3GUNRx+G z>5~L$5TRFT-xZRtd0rkmBnQsB3XbQ&gZ(l#Rkz1f2~E8iq5b&^YkCrfNj0HxtQ;6! z3QQN-&4fy^x-~&43~4Ed(fTA*RtMQpSeMijL3kBlLYWcTVPH{xb&|y)uuT(QZ_Xqp zCA$^y`f~gktqXirN?lhnoLMlbX&1lw+> zuh4H3rQRgv3O%1FwQ8^!Wv|Iq5OcTaEA&;OG|l`A>jOBG&WB&%1*G%jgls|IVt51| z2`s?wI4tlu#AEe2UZUQU$d8wQwm*m{fi`HjBK;sD7hc|=!Lbo9pdp4NWNwtTORxlG z;}ci3q6?gN+4iSJ>IZMuKhprK)VbyPOCV7!C&Zz7$lvRcwnpTFa6rx_y37i*mZ%!M zZ}GaGoRtP4gcFMq;Hxg+Gr@e0%;4AvJo2pl6q(g>LJ3-~7g2$=6k*_@mH|$SgXF9j zQFC43y|y?{SS*6p)8?xrJy9>x&Z{J^2JpQfa1b83Q11^HY2+%Yd4q%+y!97p!YZki zISzT?Xpu0Fzl>$?C>yW@A0wZ!R`cKoj6<+k&Wc81Vf+(eAco24IR?JB60)hhv5|Oe zUppI_vHGk@XaGFBAAEsVAB8QB)vw|4)n`QscMc@ORt&eOoJq)z1Gc{=qgsiisoJc}w!y}_&b zoPa@APhOKNEG`5l1}Yn9jQ>gdFxjveC7~xT*fVAACn(VohT8*KI}ESWVSJ2|4IiKo z)95W58ge4CfUCvJ+UM|HSQ&gvN&AxrMFj@ah1xSj?bne9wWm322ZP+%3mjRKDkM(> z&22-xb4uvg)sjb_^+G+-sSeFF)IwKS7pF(?fn6^$;2ugs#xi1{w#nLiCDgWB+FSPn zsVx2$Dlb%X;_XJB)tt8-&z zUPLvF49^?z6LDZafrUFS;yKL1UgAPa6?p1)AHh7hXY(TdLFV&(TI*}c(_D=FN;zR2 zYgT`-j+($o#$Z5JS;Pg_i0t7uo6{-Si6D!2huaL~Wy(7+w5Y@A>d2E|XAi~;WwxFJ zndY+31}v*1;d?NVckI=*be>br(d}PLZ9L{9a9d7dDH_HZs{oqS`5Z0#T58g;GgH*3 zMDRP?^VM1E`i<0vTsTWReIvc?WwGHiLDsGZIoNPS`; z)3k4;md)Qsp-Olpz}iK=o!&ghI({KFvW34hx{U$ld^VrF+IFSYDc;k(_3q# z0d23J0<*C&7h)}ojkJSZzbnYZrw`PdcbX1b3(LeC8Bf0^2pv@9lnkD({4!5b>srZU zg?M8A-!GzNR0`=`Q3yh@`h+wv0$@ZDXe3}-$Cg}VpicV$OYDJd za#AA4JZ}`z&(?v5>4h|Q9n52A6w-C;U}+!daqFeE4V$A5Jo8u&seUue2;WbqQJaDP_YZW}X4L<|_RD5mgA6!Mze|;Fnm>gj0x))RG9b3< z;52qG8U`ctf$TH-2!gsScJCHPX!jgt!fZIJUMLLn5K|5?<7FQ&RD#jR5&=vLjok7M zR94&mfR=SR>-e)WfeGbBXx%%4N%itBhWb3pp}MV7%PwDGJ&>n|2oo5l{1eUP+h8K# z1l9-J9VQk#o!j?0bo5r~orX!s&y#c52n4x#IrO`&Qjd0l$nP)Xx8kzAxQ<^i@;b^% zqAv~YbLh*h&`%GKQjcxYyLE4~hU)xoAEl$V!5nYPQMz)Q)VJ;m86RuVD7pe`A{d8_?C1Qgp=59bMq6}4AHrz9iiv8OHDtU$pq%eg~(ilT9xt| zoWa8oPGXPKYIt13jBq4kFe5}h9K)yI^ zo4Z3AAem1dLIvFp960&GbL2`OJhPAq(xaiwKhYKff-}WAujg=XVGO`oAuz>c&+RQ_ z2IH&{9$?XIgg}L8N@(Ybu6~rwZc@}9BWHyR$#Ud6)l0>*Y&$U7q!LV)3H2i636pFh z2cE8aV^Yp45rXDyN_RJ-w8SQw78^}SgG@flM)#yiE#DrC)tsmY;~(aCVM2q=HQo z=4V;>Ym*6yFt=fk;7VD0@gTaS+mp-MpyY z+dfDRSn!${Cc}5LbZ$$L!TJnF_ADS+Up>&t+UZDOCykN=#%9s8KS*BwOxf70Uq?Si-ZBl`yemB~IXAa`zB1m@?eKvbU^dB~IjEa#wbMzDk!onm)}0 z?DZrLCvWgg{(T2%m)%ke^LkLki5$M3=7`CfVHH|?AfMm>&g34*32X)inthqZRCuAo zX&X+@fcXyBND)&vC%t1GAO22yPaLDgv~8oDQWwVx_S%$8dTF=RpjD9;r#ISNnlq4Wk#wmPoyRr;rKC<@;&q9_fQN;qVnxoD4*Pks1>>_MI#{%-($W z)4hA7ejfF)5{PguEMeHOSsM(yx%+9|z0!|l;C`C37kVu6NBYZN>0OeSK^yIp+O>M{ zBg(^U|DyZ^d!{l2gEtH&G|)WxqbD+?R?WMk zl^PSc{1c5ZgTtI4gH}WJ4XaTgPv*~6m?_2YqaA;gdNj}6%M7#OK;at3KR$qD?Kk`A z;vc1U9j2f_o}9wdtbPsi9SnSl{QmIXjY9$G5BJhDKT0jzd2snPB3%YHM7qlN7FI4Y zaA1SIRJUJhQuo;&tX!w9y_fp$m)ecmi8S1Z6=*XP*SqyO(d;3n3p|Wie_5=n!JHNz z(k$OCZ2u?TuTz*UeG;4F){}EoHsoUY8~nUI^vC^DBNDxb7VL+i;n+uwsH zDS4O=?M6pnm4r2hfA1cQ8opd&N1uRSH^*g{{Y*gS(;(=wAJT1ev*1t#`SN?)Dw~uoc|1?XmBFl_ z3Ot-~BoU5svAaqwOSX+UB+akWFnc}Lq33IgFP3_`ZlrflN_oV^Leul4BJy4$otG~~ zk*3S(m3)}_EvK}uUFuI-ZK5C9;rVcUBVAyZyvd&%X^LI)Bu_Tlj@qSZ5*fdSb|{3k z!oSzk1%*-oNnB6&7Q(@h-1YQaq12k>thfDHDEYYf?Sx+<;NQH$Z#^EyAEHnj0#E!L zmFCTtB+IWYw)HQT#?&W+X4$q~k(SjbMdNMl?nrkDDH}^0+>_oXLG$R4doXRW`mMzx$Fg)Sb)D^^R6oefEl_!QpdJU3TLo+uF&C z7!Ss-MQAl#d^_LhuGYgwr8@jG`oH^9^G;Woo}O=RsqL9H*k8a+o8{hYZwa=&zl?>- z-9Dq|q4K_SKtp{rhF7~{4pbW}yRBtrbnr{xu!I{1yBC!a+S$m9h1!C^*ebSjtsWdh zeIH0|%_n9vY&h&wu3)BMw+WjZ0^2bUBD6mMtWM{EbC=2sotTP*m zk*wDFrDJ&!wzi^RhUc~escWzd0LYJcT^V@>(DB}r@UgK==&;g>K#*mh6oH5`@OPy9 z%i`b!ys+M>Y0Mvg3DIv6vfz#S7p5y~Z`CZ(hsp?EH*A8*KEoNR^JC>jc`k1Af^YE7 z^C2R|@>8JC0Ugkf(+7CBz?1tuWC$>TgXROg_WN2-r!W|303{wo%vi;*~ z*|TaU3h0Nyy{ijofl`RFdpK4fi3e}w05@(#>$iY*eJnL@NI&IO+nBDbT`-e=@>ufg zosIN0P|sz)$Ugg+fG!lyM?`8*&Sy2jSpc<*FyJl>xX+}=A4}aoo5g7TAb<6Sj8(ke zY=(W}NNp^jY5@lV3ub_|Jm>CeG_MHv0n0xz?4OP`$=Xj*=0POel7T{uXlj_$lJ4;(1G`LY#oDl=2)^Y2Ax=of5<9la z_l!D_gL@bg<}{PLQJ?lC!TgOEQ*t}q2Yj#UoFs6=4@kpqV=fq30P)lrQn>`|&FR;$ z17pBj4m^&230Gm(oLrdF9LB@AaCjaCOW|Z094A&gVl^*jx`3fQ%s<$IjDv-D+P(wn zOT6E)P3b`3#OIlow%HxY;`(GrLtDkWWVCnFkSldaM19&LoaDF+ta@pC7EWFgvfkD9*DwOxdLP%e^%+Up)^+jwM?*i4A|Jby zR%@s&io`ZL{11*_`2xOH;L!iDT4M_xOPWe95id3Lv(Jfv#N4IxKPUb!I~^MO{pX|| z39Loo0JGVp#VZXRHjWH2C@=YM%Ere)lkuFp;p%e@JvffEb;$%P@O?KQm-Lq!Tdncr zEkasL)NLZ^M*tZ*k$h=h2-@oS+b^M)X8JsQfkAu5f(Nu8(lD{fb_F-9W(NELB>ZyY zww|006m+@?>F4^)2+sHUoy#4W#A!c9*U*o7qu&A*(-Vb(b-X;12BlhZi_Z9hj5ANY z^%A=88TwaI#r!FOuVlaR5qRj_Q!K$b{Fxu10|lKPg)}%9&G|kLx!jRBPWv&shJNyY z^lA7c=!Ppd=@*kohrZV^B9<%o)45hx_z!;AZyCoM@rwOKruG8F6aFWNaPfcQK+PM2 z+?Yq6`(9{h$t2RLbuu#&@2>+i651<_4+3ZL1Gk3a57#EEVJVsfvL}!@fPTYq300PW3GlFx4O6`m zjxhX>8(oC>Bq44V;$@=7RxdPbrx1h3C)J>CQ8Xy_T(3-mn1H$=9EN`v#7zv3*9kmP z;K6{8nLCvFH94qt1#R{KIcj=RPB*=d@YFBkWKU)ju$05_gd(;=m zTIgG3?>f9VKX_s1tL`h#;P*^ob#B8e=;!mvSaS2R%|4$fF68=M`spGvpIkpr|2C8U z)DTN3(VV9laiqWP&segDkOt>y>QWL#cAurw%iY5XAGqrY=Rb~Jvn3~x6p8$FnRZ!8 z-f!@3DM($D%djooN@?s$vZ~FVE5L(n?!}k(4D;asM?*RdU-DioHQ0Z)wNE4-5?Oee zhFZuBQs=TQ%R>4}4e)=igvnzmOzJ!jT%yEE-X_*dwvJX3EOm*1|Ah<9_=8!s+fm4a z)jDqT0Zd8YWwS2`sHcy-#3LZ}F4{J(B7YF_&t>|*)x?hkT%m_nlbD7ZFT+SZ5vxzo zz&Be!F#a;_pG*dk0heiVGBJ|wm+245q>?ynbj#NykmTCvZ&)s~QO|Fn>}R8q-;fdH z!9kjd^zMW7$v5!um~fE3rvTmVAdOLAEM3W>g$nSKvuJ~FNmnvD%NG1CIRMY?Q}pjO z|QF;dcb#IMQEs6w+m}Z5((d2rXnvNw`3&W^>_yGGrFZ zZrRMDZVy{yhB-g}Pr?weBve+99AE*CmAK%7fku)CYMZTQ}3^q@o@S zl_#tnxZ29>R#Zq;X)x@ypD7v35E3gb>!`~-I2dhz7Cr~ZYI3GDDQFQi<9_6 zPO@QKA+20TdXlb%)NeiUAfAPE;Ci@o%L?dM>xoz0W6(Oh1@{)v?DeEmn>a@6cd)Vf zAo8MpYJ>{AE!uG8!=ygCfY#nX+74=t^fft!FVw(dRXpx4=mI+mxkgap3K2Tt^9p+j zHrvF?(2i7CWnjY?c2b|%>D&#Z11Yf6R4ljJZD%%+5Xn3(pVjErf|an+f=Zckf-4V^ zTYZlE{gcP!3}>*6hb7Byat>Q(h7^$vynI;pWs1Idy8-iJ4MBg5JMgxk;EC9XLeyr9 zF`a?Cp{6JX*Pl^lb9yNpujF znL2`lc&o?i3^^xha0+SUQG!@o*^`y9_-*9A8Zu7O87ZWT|7xKNjfpG4^rjXA4f>EfOoWvHZ0I$FhLc6L?aDD{~r9P=l@XvF8ibga` zI!OaJlXQkNHPP_l(|A9p#IMK7`tLzo9Ifu8xC6Oor6JV^cp zTY4He*m4u^KEno-fUda)qb4C7nef=yfkJIre$#%3*V~{!hsmC6a_Ral#M5H{@?v3? zjXNCJgV8#_0lBnf3wgV-576KPI3g@-8|Bh^sl=ntis_BlIUP8be9sr z$CXQDU?AFr1YpF*T4iluE*+an_I{j#7Vy0nOTfJl2j5xN&XWTZ1m73=u#YhTX?Ufa zhb83eC0N1&Eu&#+f5~w=_B+zbBZTR}UI~{^2x76&1q?q=hhmG78<|W329!2tns@dIt+W%EH^?an4Kd7cz{-JHA-n!=m&c z@)F23@^R#Vu~D$C#RYwi=g^O~l9pjM;O7VTh7A@NQu|S;TE9bOLi#nlM|Flp$OrG) z5bP$e@r9nl_5G`$=N8sK02yM25w0r-L!)OCm)hpR~ ziF-H@uD;>j1N%8_e^BfJWFdy@{jk<=IZT)AARgukT%Mn?0C~1{jhnJCI0pU)W9z=# zK>s#B4bl~Hu=O63!@U9A2k0-~hY{t|i7Uftjydve@N7pJW)JYN5eLrT>5cr_c!Rw- zL|g16K6UdL0>>&2(?L6lhsQpoVJ*CbcV9vfKiUz{Fs$WwgY%S;fJ^q-TKyG<9-LMOMpM?C2aBE{ug~vIIE8zaw z^xQ7;PD5M{0sbBq72tbk(}rmzhRn9nRcXYN%(2n*G}00#cCEr75pCXtA})T#0iw~75>~iNLzhRdNnLQ$Yj@eVUmLSiVxDM-;@31G2lOt zwoNY}4qFHqYd8}W2`g{1)_#!6Kac|QN0zO1Iyom1&ja+&-2`UJo9LuHFmL*MBi)5% zHmtj2xo{)(*$eZmHXG^Uy+GgIK#%N&`P8Njln7B*{$mj=qmiwE;bRCPnV?w zjSmu>UOipQgP;sJc_ceDHZ7Eokf@V;D+Z`zhtt2WFWMEsb7O5L9_vv-PbcC$nlu~W3$!&2LasIVt6 z24^JWy`3$qa))?y59`9JcZe7FuwJeGBtKn{Rk}m0-@_bi(hd>a!#aD$6Mv*Y?m-c+ z(=RFfHQ8v}GF|3fh&Qhs9}mR<7z82hlQ5zSvXV%1KW3yE$%haFA5Hyf4s{V++{G-} zjihwl=yXAJd+A62!)5A7#h<1Z>)&rT#H*F8cTAmZIlTP3X-n9=U2Lyp8SN(#hpThv zBA$|Ani%nt>NHkB3S&Ufl{0B{3JAJ7_Ng2KFrkZ1 zVKSuvGdP8@P8&1?zAos=w^vPlkIe{+U%gEVwnTj^8+MD{lVuIuCYq}-M;1Y@E^=Ux z6HCf85OHtnhF$6*B42y6>PbpW|HW& zB%^d^^f`|nkuXN;;v?XY)8zj-5{@2EByMi_U=-~P|A9X94c$9YP`kXFkzGU^ZTrq=kISJAK60sy2fr@Q!wt&B*Xbe79Qa* zHzIt#@I2jnIE5Z~g=#=<@`zDz>QzYbOH{jO3NYrTy|1?J6i3gaETTqhAv7NA3) zg6KUuqE_s;0AadraRsR%=>US(n%c z5Y}s!Eo+h#7DS}37x+w7F8jP(Bp<M~|@1qbti1`9wiwshUUo$uORHc&WGS zz+86I7QK;lZnmrRtDRovTp7mVHKt&p+zBJ|hswntkFWw3UoP6#viR5-(m9VEnw{u9ka&^_7I+oYw{+&yq zJsba5MxPJBuV45GXZP9CATc?iOv;n{<*bBWsL#>{vV3-O&v7dSetx$X%UdZXo?$<- z`xaGA_zT1RhkB3r^fNTimmN~0PoK7lf@4Ya3}jAT8tdbhq9x+#p1y{l`V`Gdk6F9J$cFWx!YVjp19ASte$~K zj08u&=QYBHC*TpIt&p8Uq%URix1t}mLJpESt&se!=&@GFMY3^L$W5W~IH7`ZeReo09X%P4GaQz0_``OO!{@YdLaF%oV}^ZY}?u}oWKmA8#of^1r`E* zKsPV|TmUqhksi=)HklpU7={Cg->&c&ej{X-f(Qcl09|1rvkq9#Lgr;sm*MM znNjFx-eed6^a0a=!M-6g2k5>R1@VvqJVm4c^aB0BRlo}1Hedi)0}KM|fks-$q?bB& zU=z>*w4uS>{X=FF&YvWFd3Kz91L{1P-8&fM2rex z{WCBKXgmvpfDT~z-N+ai2lTk$NrA@=bO3$8e4rm#1grphfdSwuU_Edf(D@wN7U*~x zy*nOqpcCkv7Bb6#e&9Bs@d}!j!fFXNOP@n_o06KyB z2^jzN@4-?K{%TkXOgn`L-N0W&TLS~QTi^p$Tt?>u+P^_>?vC(}XiK0oyxH^uZMc4Q z5@^TGx(1-*nP#)29dckY&<%6|y}*26@TF$c?}5iv(rnfP9iC>>_&E}u+iZ3P2Cz}d z2io6gHn#y?OPkF)U_CZ0H;Bi*=$u681)5DCu%fZqJV(e))7}Fa#GB@1pmT|7?g6@h zbwKyuOtWJW3<0)EhQ|+&qw4ps@!ia`(|{WuV|$&Aiiw-gABnNE(wMmH7+ZEs6jTj- zGu^0YXfk*FZ@op99;OWAI`js9*JRRsMUJ>AZWtMNa9zQrfy0DJPMny*Tji#J$fTe& zWNJ(lyp(w!l%0_Mf0T9oa&!lkMW=nY_c0 zt`K2GyCu2~Q5-l_rEzRI_V1WcPC^v@#rl6 zbeK*2aTdQPH|gI^rbla#jd>9mY~Y@w6j9Fk47w;O88;cS%Re-kQ?$MVSOU)Rqev{_ z!@8Zk(PSVFT=jgjp1wzhv|8?NcNhME3VGv8IdKBR-}kt^Z0OHjVy!TkuCv8aIBhl>G7VCz4h4!Qi|@#LR^}G5%Tjw?Y0<|ZDNB)E1cSCLsC5lhiyvnjw{37`M*|*2{f-BD! zeHZb>0o&lOh5Vxy`PYE+4hxy-#K~Fy>07JdImk8-6Y~%^-oVg02|X(=Hatd0aHS85 z1B-aPCj*x8sYDuT6yDn3Ew}b|% z*TG@Jl#aNQ;OKL>rmkWXQsCxIuT3j;gT)ob8vQZy9E`ZSaqqD#n-b+(ims#ha)TI?yE_ z6^F^61OJty;(O95gWq;a+`kNb4gBtNV#+e`bdamNEZ$v)vOD1)oF$r<@ot`C_>+e= zo3Y_A2wQjT<)b5qE#bU%IQo&Qht<$Yda(IcJ5rf;g0q7|x5APVV|y6GK$ex#1K+Z& z)O{~#{m0uP@Ho2ZSh+fiwLacIG6{#hfscrfeK2|){G}5FTh99?E+8KNit{VlTIIx~ zv307k2O{W)tjr}IUXBIz0{pJ$#ggSzk=W(9Ul5-x=kbww@cX8UMx+&40)PFBqVEcx z+nUaZXJ+6?l_XME@Hnwz1r$1BNGGoshgYDs3gNFmD_XCFe>420K{1y6SK)X6DAugx zx$y&W{#!N4yw#JbcjSTdO%jceXRd~ST%~z?t$}lbYgud5(`v!zgO8|Mp3U!TCH(7n zKC2s5)wqsFMBSZ{n%1xXs}o;+vG~>gbJEjN(=t-~_puL3%@DC$c}`W~R-P0_+VkG# zFGhqJxD~+9GS~L1*2Bgt8F)-H4wO2=ET_HMU5-v-4~e<9Zn`$I~MS3L+4OWVo z2#;+x&DsNKjtuI0h~Dm-6- z@v`P^A1cC1?@i4cM-)F&>z~46LHX2=Qw>4q6mmPYzU#E)#~TPsw_gh?ic~mJ^Cztg zf-0fux(fec@pE;2Jw|U5zw*yv9fZA#+tjHZ8i|;q$sXSdrEZ;#hFH9^$FN3vp5_CG zmA*FLc-qq6sCcWPU)6lY$BK6-Yugx0wIKMR*jGgjI95r%RC>lfEq6>+#174$)Vxzy ztX1Lv)I2VZvbUe5F!+PU|n$yiFH)rRH~O z-tJd~mCgr}*GhPN@w2_WU3{=e5!SH{jP%wid8&?=ft@-TSy8J9tB`q` zw`<szmKP; zyWUc~JfFeKF-~QzZc;p*$;froeDI8zhIk&gP8W?OU7nV^0xJBv0^@lro;Dn#M!I>H zzODdkSZ%QQlSXZ=<67W5aeIU)tfo|uK(ZLUpQqkUUu7dF=W<}g z&y?IQmha~ynDdnQWIxYMw_lQ4hVDGZJgt`YC&iytVEk6|!Odc94SK2jqL^2M>Bf6h zDWqz>e_8QQDFQ+1IOZcV&pS(nvos&Cd7tiRnB}BP(Y#9!E8RTC1DX%03NJLQ=OmA5 zf%`8i0l5){myRs5N9tin^L&U1l zceLEus3QCVDW2>+quod2G7NFC!UNDN^(_@7K9m?V783 zdy-glkf+9{y{h6ZR$xrm@`?@OBIKTm)k$t%wISKUDL6UGYdjx+gT>Fja-EiD!z%_fmyCrpr28^ML3XI3K z+~-wTYpB$trkD1<$+n^Ey$VcviRx<8k_#bh@7Q22*()NGyIY^ z5KX#=H1E~xY*4q$3z|>+O6fhP3s|Cgca7rbD==1S-nB&%6AbHV-6kyvjN(#a4a7<- zgFmS%Z>uw=a~K)wEmJ95JDQ;8?PtXIwN$`Ym3*55=`bXhayNX`3H#fl9_c^{8cx4uh9F4IbG-TKxnwq5gnT?y#) z($#3*rfV6KlXRyv@6_up$|l_f%?DJz_ZU01;NM!{xMP8ij8mm|4iVFi@zk(1vGEv> zWv(+~-!ZIP4bxQoDLR>nT0QuhB8F*xw&uO>Dgr+pBi$;^yBif@?F-)4eEmC0?+pb; zmF8W4kc9Aj!27WJDPsEv{Izs>F z`1nH%Imb&P{y6kpFDbc8&mp4_LE8U6Vj|=$cuA}{&ew$Xuj+S#uk6kuu8YH8@zmCJ cx>Mlr*Z37b7Iv=c(AV4y3wuNy`iB4GKhuDh0ssI2 delta 42989 zcmb5XdtB7T_dmX`!8N=fi@Hh}iV8|9gem0>#XBl0sU`UM-ldZ6?|EismHdAG`SEz?lKeorQKbyBD_jUH&HO9e1CqTR{P)nFU)8YbM3XNGyn2iUB33Gn?p($ z0ZAJr`yBZ&^{;F))ihN%S!Nj@)CjjF?v`|41;=|!IEzbyRneFF zNP1GCB)qKXp_=0FjSu)MRrKE!|M9(&po})9ph(qcJrH!8$*+-QuzN`$ahxoB44VC% zqJJsr>6PR&6i-r=I6;=H$cO2ARY{+}MG__{`qy9(6@McMZ-|)MOr~2Xi-5c!JuoYQ zGm3t^o}{-|^u}Niil#|I7exn0vant1u8W&K37)3v)ay4kOBorxo$JUU3=Qsu3X7WTl zQ+0+U)fvDi{thDm6eyEQ?o>s8SLImrVM*}hm`OQs{1ZuMs^TNcpd8gZ#tL|l$@D5D zse<_zq`)xwFtt@4o0dsJl2XJ~#Yw7Sj{`@PXOm}Qr zDN<>=s%(o&^u!&K5T@w2l+x&fk`S$osH6DrI3#_J;(x&rr=8rsl!KG!^|g6@5>$Z&&rl9Wnx};kG#C4w7B` z9aM18pJEI&!E5nXRmC@`NS2Q&dSgYu^9;R@3Rlo}$v9o{S65kTSuY4fOao;-rmo6f z%QNe}w8XnDMEqTHL`M@Ii=C3Qj7e)XIr ze4yw}Rq(TZl7!zC{juV|b6yg9Df(6#xRE|Ng@Rx+#VX*AN{0wF%z#h)y{_Vslr78i zR5(T}HxkE6y2rhRia+anNmrwyX@VMFuBt#s3IB{&>Ne_aQjvR8N|<`6)Q`I@3E8U3 zamrWAMM?KG{aWQ~%3)(g-EghII8nDQiA9n(i5CzK`a7z^Xpv#;YVtJfZPl>Roh2v2B>r|O<4s3o`K~0^=wD@ZMKbC0rS^1pPVHAQY_)0ndlquI`p< znkum=s?|(6lAfvPpQ?~YsF3ee^kJ$s6IE;KQq1(bnv+tV=?piNSp^>pMw`hqnBRcA zl#f?cH$SEneWL^-#3XMrT~QTx^i-hI)YIE80Vh2XYFO~?FBO%k@FuE$Fi+KQ(v(1u zS~=NNl6|W@zH><`@K+5R>!GX3#glw*slZxP;)E*)#w$Y$l%bwTJBgoGP7$gJJOZ_0 zfEd_Sf*``;k12YbqSsRNIjVv?OC$k~ioZ`i^L3IeC#uK|QjrKcY%&=i)oWohDF)Ai zf@UN#ASG5xj6?aGc z1(^0q#$)nfawvmxev}4HN9gEpw5N~FH^#nzTy{$GOR5EHphEH^S`CRqBy4)5QY}ZV z5Ixo3R{U45NybsC&kRP(iv}4Z={J;~cAmbHEeN$tqZDvd=ZYSu=rM}lQ1K1=P!j4W|7h%7 zr-E9ZJ~mU*RbMvcCyFqI)DH3~wD_-m*9NK$?@QuJ9$&mHwPQx|;n zH_S6>d@YJL6TKtQ-#co?i&pkFm1NU6m9kmeCBabi?^FfRYIa4Yh`*1Np+U+}&mgr- z@dqh>Iffvrb(9Bj6LOmcE$L-*KAf0lK`X@Alf9ky{Zjq$8MKTbL5oc7=Vb!f9xBO; zBItSF&uAmdnbESmEJl`B$I0?adNGf&zix6{dqG2teTp|Ku(-ZGJ;lxZ~{C&S=!kLE?SCjEj zvyz;F6W(s?kiK3m$O|&u+m%h0NV_dA6TCnnh+I-m%)Du6x2(q5v9C5c7E9jG^mbJi zGBYi%z9IxO{axLDfnfUWVWm577_G)NXPa&siR0?n7T^4T+$5J>vp^>|$+u_RRBhE7 zbx~V++!XFra8tNf!A)|nf}3cohkc}*)L7oGzGR8?+2YE2>a)kqz+a5J?^+}GBtnlX zPB2F;@8f0am0s+&&J!Oh1-t6P-(Kn6g1uccZ^%y;*Y)d0^YOu!VI-6OM@;&Dh`4TF zH{KjyU-LC)jc?12^v>NrzK6y#?;6^BkJ#tezMR<5|I}~Hw1+xS%L3Qt>u$IB?8>`g zw4L~w*1*^|F|yV9o)quN!Tz!7KgXn(#@Ig!wz#c31$9ucrB}MEC47nvM$YA4wFbcF zmyGbFms;;HW6;{Yd;}G6N=vP)zkMSnJv9-sKmxD-o?G_*IE}s6)rgW!;z>!D~b)Be<; zwwj5?xb)Oue2TG~H+D82PFYa%c@iu48x-vCy#HdQV7Jv`WKNB5^6mvnft}vqbsah{ zKKqm0{!}8--_TOyoKbIDJ=QncXfv&$Z!J_4W6w7Mc3U5JGDc5(L2F~AO>5ZgQYSBy zHl@$&G3k$D(%h5V#iZ^bF4JVQYp19tpBjW9v+JiHQCCKOG~OB9)hK82;0TvN4^EDbqW#bsdeZ(_hrWjH}aMZ7_w{>^rFrkqm#htv`UY z$AYoeHTr__%8bTZV`IpSa5nj-@#&2Aww^c95*fRKQ{Yw%GBydJ=oTD7jnn~Dn>n{!u($qv0!!GJ^dfGQAE4+U)tGgpdA1$HvMl@E{t;d zZ3h8%SRfFa{*P<@dE@kl%^H8+!ON7HQO&53Nl%PQV zib$m6l${y5l#_Pr%9dWHq3)2$uNa@E1lpX$k+Fdwc<;96Q<**t!iU)OU)|QOPj$qm z-xP6jTbn#3Vi+81w?;xM9C3$K0^-{s+C<|=Oa>QITSkwdn6`T-RgcM-OA}a3+kGD- zIv-eS6ki`Q#lMF|!%#k#7>lpZe10y?d>YUqrU0uAQQ`_qbi8&Eee8O>8aHcpJMZOeEg2o;ll7%}x(BfgLoPw`h3-}kFb6_HgB zEL_$*!GEr-_r6~bSOpYTm0MKxeq@V9R$uN1Tb|lLbmR8CnPf+9+Go+Vn)lr9b}Iu# zgzPr|(ylv*CL@-*KXgYMERjk(?lkUv+bA$#C#6oYH@xa*k}USAm;xa7?Jnb`tVV2S zQ0~AiKj!~BvS#vbWU@axZA|(vV(|X>w@_pHiojT78+uk_M5R}HL5#htcWnB;82h$u znI;TUF9lMPc-fOG5dw07ARoszfgpn<$maxk`wPak6;|5{g+^O4T1OLu_BSM5f@O|J z(xdQ>AWszJWPj&_!37wGsqN?wjW3pN6xUSI_~H{qUK5{0=pjJuD+Q*xn&u*oF?Mug zI6E??Ri%(nKvSy5d|XTiB}0c5xjJukyXWU7t^9~JnqP!5@Ik205a~}diVLUv zQPtjPB6IX!qsE$7s+vHjqG_+uZ%t?RXs@wgO>>sxZ|q+40%Ok`7uSSRsq)$mteL;j zZEbVrtZTf#b{Lyg*EqhmE*nxK(+OpGij1Sf| zsd+uFB| zaen<$w%%$?-q4iIuo{^gLRfFBQM{phaCvR&v{zisH&IaXE#)*kUW-ltGsd3hkAmBJ zqP7vXF<7_fxZNqqFPbL5kdoZm)meZNxoanm;8+Lo0_rj{0#Hv5cZ{?(PFbd z8=YSka38B7JCgWWt31bm9H zo4flO*EUaJk82olIgMFi4P#197nV`O*q&3LjjEA*K4+N5UfE!@`Jq{0)eTtdmRk~n zgYfUjVE@twk1>_BUQ1?28@_8>Yt@Y{KQw2rS2wQxpx3Ke-OJQ=@07*e()V^lUFesk zcvN>=?^ZKj&uvu2iD)C2j#e{La_h6j)r_p%4s3Ka<8p3;DxD-2QO&5lnX_$e`^ z-xiT_TTcs-_DDmq5O7;tRW&x`HDTAQ7^m_&ut(m8-_|xYc6xi6w%4K1W<(8KX$;=_ zMvcKlqP>2Qep->cbL$n2)%@Q0dRwqx_3zQi9@)Cj$1v%(cC74WoY*$rYmeE>h~9pH zt^C%gw&PW=gO$9D?mI?%^{?cWo3o>-R^?141rQ^kk+dto;zgd&d)Z8+$M4L`sJhGM zm&z(qhk^RlE}Pdq&C7Tp|0}k5v#~9|wO0^|xAUiYEjD=>V|LeP)@8ZryH9DA;+DGI z#?_tA$1HnHD}*b%@xBS&zfcLUQJ~n(+eG0@Q3^Iwlho*y@3TLsJ8;lNnudzM<8V!m2jpctE*Gn3)&3_xu9r)Gf=HF_K=(b+}pHY4w+IuM|ZtJrD8C?&Cu-N|@V-Nmb zW9I+JTtB3@+dAW~+);;Wd(|C^z0Z*`b~$dxq<1fAS%98?*O-5Fk8kE}@_Z87w>{p* zZX3go1+yWyjoHWEwfNa-Xv6!_Wh_!%UUsAWSPE;IZp=L1qHgm$|A)%@w}r|Hcq4hD zGX8g=veEBC<+XVgRi2tBRBCgL?2}FEYIwu>f2{oLH{;gH389PdM%4@NYu>%=9q`sM z%Tw&0ey8ODqQ#~^bXy0P8Mad`S?pZnhg0oXL7MT$sk-dPGUK_^O?}qjrBHROm1Rcz z)9uWG!CG({I9A*V@@e&od2Kx7o(nGl9X~Te>^H(JTFN=hyqDKk7WF z^MHXdAODsj=KQ>P3^quIJ;uf}IW~km|2POS>1j#g(LD$2AUYzAu}?!vr;R4=2bK>< z7hmu0-(|XnX4n>Ee-5M_^N^54{ggIrX&UxFLH|}RY#EcDmnh}NhB|+*eZ2Vk>;7HZ z&|>Ms7?S86FWAp(HpOq>R)Re!RJV=9eyLp$YtK3diu2KnX%@^)u=kU7s0HOk5h%x` z=a-PV_TBftB~!Q3x&ywX#VO`(V2({+?ILv`#|xRft0aR}%?NR7A7lTILTWC8-s|xf zoY(chI`dKe@?=ZvQ0MjGftLBqM(pGgv3CfDI_UW0(b8YKHz#M1s}>SVV^Gq7ff_McqyCG4GXOj z-#I0ZZTMLBG-T&stE&}+Q4NKxVyG;6|94dSAS$K5f?2JYAxfEyy$c@8 zktKgwDv+fhS@Orq9Gs!D6e>%Uw2-4!JFqq=L4P9j$JlfHG0da1O_Y|zAtUYEc8Qiu z2^Hx%Fq2$Q&!><;`aT}el?Yv_Zp}CCEmE2h)deS+h;>N7=d{AgJ4amUkNb?My(Y$< zNp0NC9$g6x)z9{`x43S6`qN~s`rLVoxzhvS*7}BEpUSsgZ=C2I!hTh&5-(>}zeY+Pr zAB5NRT~>&X2O5?*XM`VAh1n&On*kf(ulS7mS6XQMjcXUjz2>g$n^r1fwmX8>vZ;Th z?7#p=?}2V>;?Fcf_weqOv72^|cF-*AX_JrlWufG@c2GP51f!94skY7k8KR3uSJjvw z?>jC8|H4KD*4pu+@~QHr&DC@!8phrcZki`A1)eUt8v4*&7ld5?$>NNEz)|~r+T}aTGw4A%co*$>FBl^D0FUnamwWwd-swji#Ol2e~qD+ z>-E5kqY8fKU9`d$(a)ynKiU363+zlk-#z`;zV>d9sO_rn^W9wHyf^%C%!mV`H4Yj> zFGhr^HW=Xj|F027Q6o_PmVTvH=NW<5K9LE#9f^yCJx)<6eu2L?wB6`?>#3as!nj z$*JzrIS;W4A3GgE@odl=Z(i$QY55_|{kP;2*;Q+XvEf={_Qy2i__fy>TmUyPvCDhK zH4{xoQ?gim{NdU?&4~UvxPSaKO7htVyLvar7GNi_O=!1av7=w69Kp`{eCWalf7g#Q z#D^f)(W&ACGVlfLongs6thD`9BlqW!=o_?0WgkeZTm07wOG}|;5;pLm=?$T25_SNf z?K`1uQVar7YUz5A2L0h{u`a)~I)gArtt zU3suox>M1ER)~z+4e30HV!3BD=2LnVb&ZB7_S<9ZZQRyX2%FrTe;HArPZrmbDe{xQ z>+xh%l3x7}>|hZT z$zxYT?3qw{cs5IJKmm3|V$=Vy$9c9lV3EG>{?=+iW*L`8P>Nxc(S}4B>2{N z_~;BX#vb*GExf2@&1!aw*l=eb_deUf1NdIx?Z-Ku+6z61aT9~V@!a9XF;>w+qDPn(!FItnFIU( z7qIiWBe(+7mop{PSBmLNFl_}BUaFNItA=WkJ~)L*lT2c(7krqvZ!D_G~@dxSQJ3#ETzT!Owj&+1z=Q!L%QU1t>IK`^@7 zV2%2pkp}$%(X4_UZ#s8)J|*h+vzX(i40QGT0DAYE%dn|Ue_*cD7GIhh8U<=D?eM=FRw5 zE88M!j>(uD9EYXO4!WC!M!EYQI&9PT;Gsx(A6i3YMBO6l#}hzJFA|-mucZG7`fj>B zF2kba8VGw%zElov=SJQBez=?#AcXxVMN$XsH+R~31QmOIx~@~ zjQZsyoPgZTlg7NVhPHAKvygWEHJ(P0+p@;FB$2)!%oz|8R$1shC?m2ZSv&82!1k#3 z3CoCV3KBSnqU3r{B7-GTkC=x_Qa4F@UNYA|jcY)z&Jt=SAwLPVM!UG0O2i_O8WQ=6 z5Fd&BjnfCz?IV#mw1ev&!bAxpk?IneO2~PM?5!wcGY=wYkA&9!N9bijR!ijbib7@! zA$EyOmPi#@(H}6?^}a-gNQ6n`Fd>5_5-kz;1nMT~=DnmYN+i9ltQZ{bXX#5 zP_1jZL_U>BzC=b6B67qYl_Zg^68V&n2~y?_iDXM;G$8{e(gBDKcCVJuRD#+{sF4)< zrb0yxB;qZROo@%<0_+GW{)~8kp&W|Ovnj|?5Hmx8z9$i(9nJM zOs84-JZ1d}qwtTqw$o!O^oe)TL1dpuBT<^(VsY&T755_@qov+4Qf&`e<2aOD{Up*~ zB5ft26Vh5DkrD})NKZln2(j6t>PaX_LQ&+jNeXEasVR~6gxsV-#2)qQQ4x;H67eJC zutbhX=Gihhttu0(E0B#dO1Ot1-cOC@wsLIz5%SyIR*krNUrC1j*TMoFYl zB0mz+TOxfVk|U7`ghWWBr9{4!2=UombtF_*LKzZjNOu2AtznOPbVT@?Dv_q7?q`Wy zm&go>q!CggkpmJLD-kc!wn-wJB{EbZe&nBPp@bGmsJDb}qvZNfBFPeIFOh6Q5+(AM zL|RB>86iC+(o-Tq5?Me<3yFkD#6pNI-8_+?ni8rdp-NI{6e0J=i6}fcETV94oM_i- zWcFo=T#?An68Vl~iY4Nd$d3|vlaTci*&va9<1j=cP0|ROFQEkz+9`!b5HeLF(i)qf zg(%!VD5B6*BBG*861gmqK#2&4iX>7jky;YjN7}xV$a*007~3jIs1lj*g@ooyp})t9 z^!S;CrbuL}M1GYBh1fL|2;J5gF$K2;PPW9g2Xo9}qsd>bUR^ng2G@U{zCpOH{vFWE~Ihc>tdc(a~FE&6#JTE3CNr)6)Os>9zU52BwBGADbX*xlS_&Zkb0Kll>qi0cH~S0o1KxFAU13uCe%EiPHO3wvRQe4Rfqe_u|MP}3 zZlbJh5=sAlPcVG}rV5q)^tPvp;lxxTnZ}YP&+84EHmaA@WOKbpTq`A4_h;*iRrOUO zrdg6Hh?pwA*z{LSSCEaRx@0OZc&5GqifIQiwU$h03s|H7`uDoxT0~sF;Bu9}Wf=c7 zYQCuiN$fkj4gO7uIw1=qP}pOt6JTtHikaPjl9*#PGTQm2K)fxEzy% z4MDf{%l&8syaC9YF1WTgJ6PWIdJ)?C0?5LJpq4l)e+!Iw6L;y90(dTX6X}AxRYAbr z*7icpuHZyb3PA~bH=Xy*4qgC)=C)Q7(zrkKa33wu?CsUHDO};Y28!KUj_}c*5}j@B z2c?&NmoNmI3~uYD3IvQCYv7`(H{BfZaQI`{9ocsK^**F;`|o`wcUTI%>^-V zpHcWAbkGQ3rR(s5DPQ!E7$%Xdf4Qo_ZF0XM!Z5qQH|;y@?E(G;J&x`g-Wu+9m#y`@ zkpj4=fD^-wsE57!TymmyruewNc}s}Tu7TlUH*MsITTY$#yo$0*OT;YzdOzDf99_!! zDAY{3gdLuJDRJ2NraLx1!#*%hJd9-TO)$L6Utr!7jV9$Uv)~EFkn-ki&v;{Qc{6ru zypdZT%Dx|OTq+L_>iixvz0(=Z>yLKdM)g3kPajb6w2pW$xB0&>X>3T5k?^PqdpORR z{itoeP%?>0ZERiXVLlP>m_!QX+*s=4ulNr?xA8tEgUCC)Zu90baM%$ z#E9Afalq6PO|lu*u0x-UsILgVc^8AFCn_GdH3DLC!*2I5&xT#_5YL9)r#iYY5}@Wd z<7;<)TTMh32ZFPMQ&eI!q)^LEI6==+^cOvh1&Yvy7*qGR5nNXlv8#v61ZSz50UkmS z5y;@tF!;%FZX>s~5Z?EqJGidFWF$WMyE2d_^eM=7Z|I_-T9|E@~En7X3g(o4vY38 z8Ad%oxdiI?M&@n<2b%E$tO{U*{cbX>|gw>XLt+;*V4O$94W*EiIhQ*ZDW#YkrRSlJ&q6dfN5K z|AHx-94<%YI@W$B2?2Of7JPvT3Q44jlQ_H*1E=Y!Ka_caj*F!-O;7CHdkXy z-{6O=T3W!yE-)_Hk{u0SU}R<@J+BY^qV>2=3K ze{D%6W_pc>2WqjlPohK?Zs?D?ae5yi^`!Y@dMUp4;Jp&pTaw{Z#h@xm3wpv3Eg8lr zhB&1m^a(=)$q=I$go)*rvy45Jogr97#$=n&#v)3W2CRsBvY1Ricm~W!4oHW26o^Z>TC7% zSK5h)=Zk>g0G^^}L3KE9-|u=}f_Wks3Z#$%+~@kYt&q$XflwfY6QI*|r7dsJK&!|0 zw&fk@xwb-EIWnrz9)q9`btII3XAizTj3Z5?|W zXpdOUq}~*(c=KrSOfYBl=0_W8FS8fga@JV;ppkzciRbi^&vo>?|6+cG$nOO6xn6v6 zV=apHYQxVo)60sAbpo%Bt+hFrtF_dg z-)SMHMTZANpjV3m_-xTLG;&IE#RhIy|{zsQMx&_DM z@&w4_dv~z9?&EY8iXx*ua!F1*DCcKfhABpi5ds*LWU`-eEO{lE+I?q>4%+V2`7YbJW4)26q|T@kR(DnC`3GM z9w-sI179XcsEU`WrV}+-2>5*+Tp(*YBx=H{vzBE4EI361K2?c88Ua@JfFhQt_mS6A z@Bw|kr+*e~6LAE3rvmz$2c>&eU^_%sToDY)t{`&c3{ilHXPH7m2|1(?`P9v)L|Hwh z$Dajfk@Cvm-sHvji{rHyny(dXeqK;I#T$*g56y?GYm}0)49!&c50R1~JsIOkRL?zbzoestk{7Q%=Jiaj)XnN(uFi9 z*&0N)YQ!;8YL2Q-np2VBiBP8!I@uET3%*otavJ&|d{d`Pw_c$VB_~FgGWv|c;hub& z%jsEeQ7Kxko5zw$YUyQAJDqZ(K(dCMqbDJDq+bdd1u$2Fk%v6sPJr`p5+$zm>@zW5 z_?}kBmM>ual=EJ~LC7x*7QuyWpDFo`^dxX6z$_96DBQr!AnpN|0Tl5D_<@uR`P2iF z+8kMNWEv66^b1fo2x0FJ{-J^|{t&L49fWg(Fm8hSdPQjwX%ORxh*-pXz;eqV47T^^ zj#`4bH=J5MQEStwE@0PJw?tchq{hxTXAu(CLYZ$OIGNyNh)1iY-jHCv?Z$V5-oC|O zNYeam=cv&2ze*yUMQCn}pz-EHf`cVIo=C`-B`LcV(>(WQi58+?)C)SW)x ze{m$Gp>FO(rRxdjg~n(~k`R)G#@7Xc+kR9R;;H-e5tRTMT2V-hwyzNd$c&1JKM74# zhMVqeddxq5UkmR<2DwUbg%b)!s+O^cX)=g{8cy(c1SjJveT)dIzjI}RIgo() zF8;^+m~ARk;e8kP`2dC6aN9M&#ap0YJ4c09|5YFAydb+M+Kk}Z|Am84yE%t|a@;tC zSz$&0!oO3HC&x5f8DNrD`p$eSf1b zFJ{ieP9_@u8X7XN%Wu5;Y;9Vj6J-<`zwG&hA#6)=zmCeGRDL)sthCgzdbU|7f+dsHaJT0I#0ie&sA(Tfn|M&KIR?E!ouLyo8=zkMnYRT8{JZPqo+C_G3KlQ(&-@FGm?m&sL2b`175u?jPXTotZoP?%gxh&fr0Dj=el?z4o1k}Zp(i5bJv zd{OqxAYs?CBgAaUXhR@g1q4%Wym{pnxZ6)uYl&*~j;uF-wBXWx>d5-?BShH})$baQ z|3a%@^A*XL9jEBw*Z4fptJaYwgjBx9bH32JG&)K0$(Fo=KT&J4UxtPF$LT%?iEh`e zKV9Xu=WC7nEf#!!87|@*p`XB9cMU`RACNT2XgZb28w^owdlc(Px9 zkgB&P(Npy^&a(L9@WK2iwQX5^0bbtVaB}=ZIAXm-#AUkq2t6U}|0gbe!qO<`Wk=^P zwJvzGzQofEExdliOW-)9r=^g346CIVQMShyfH~6V5cK6aE%n%iu@m5_m|@OCn~aXsuE(UGVrx47N{HyjjxOgp=g#ULq#@<&7o4KxsSxA_Zz2 z$`t>-&Vjo1Fma+KPdamT^IGC)j&v*2%`55i2IR+3-O7ncNVM0jZ_7f$J}H)}n`1!H zVO!?9yD}(kJhG@gN7defXsCUir*A2^-*YXXL+LpwKF=c# zH?4ytCz^OeyiDwB36ZaoI*eHU6sVQD`PK9Mxh2}Bs+=_7n+*IM-?Icu(z#RyUnue2 z)6H*Exs~oSjh>k3#1oUjL@Kw}&Ei=e@5ay>HBQJ{e8jUTz8skm_!7~s>uDm~Me+Bs z3VTEwEe~L+PdfsO&}WO{|0Ux6Vm@f87HF$S^m}^R65&=?XeUV!=2I{*svN`*{-C@_ zjUGOGWjT`?5xmqpe0CEpS6@w`B^gmJPuL5&Y>F50{CO5U_4JTi^ej)ncRCVoILj+p z0(YF{e=XG-1?(f>x}G71Xylow0B+4X%Ok$h>eQSi1pPAOWzP=mcb3P0r8Q!W&hn4G z(wYXH--8LGTsN1357$>?_NUFmHYS$is4m`|dxjT%rFCqyOlZ-~hSaubI&F2L5mM-h z#wtI<8!ywoW9QEBqsz3e0V7V6xqfLmgdft)UT3Im3EOa*H~(7e=Sz5T;ZThJXsITr z`Mj^S;07iV+Nno{(zBIr_7+Sd^h?zIUZ?q?ueIjv>?wZ#Yps60&rgBr9;O6*c_!t5 z)H4+0qEozOCiX*LCx-HbVlb@Eq9Njx{u}-ai#o;M%EX`OpIis z^(|3otfL-F29`L!WKh^fp-(rjI>oDgqcvf(Pw|(((Rws)L28q+780H%Cpe)utSJ#` z_CdY1PVr?B2q-&2G`~gBWT2sE=E&hH%De^$Lq`;+vX`EAPNW0A z2}W}G+J=MZnC;HdP%z`gQmStf(F}dHoD?vt6EEl^PVhe8Vjq0)3I6W4NTv2CxcytL zUi~`6U!G7%^<5S9`DNar$m9LB>Iq&4T_F~H&xF#E{C3|WRyK4OW^0n zc|?}ht$j2xCHtkVgA#!8C6Gv?VVyi_EI^C7Jw2%fR_Yn^Bo_G6alSbV7M365hqADa z-F=L^vaqv{a_(|%am{hZ$WmRdju6ce$N10{+FW+8ZIi|Vj_`%6uxb8b9xq;n zm0Zs}{trEC=kaE%@w~Q$4_l2D;ip^p7AgzqTt~CDvjp zJrr+#gdcSRvq)!G5;0>Pvcw5usveR=LdZTb5MWt2T54WR!mdd_kY-E%5;<3<38tcW zvu`p~x|)c3Eg>EE@x=97{g*CNJs79IQ7WRLqPVc0ejO?z{UlK=H&OO^;N;oswU=vN zB0Gxoe360Rb2|Cm_1Y^;~=C zs;vkIUn?iyumNkl+r|9H4O*wFXUQ;3c>9WZ&_=CZo$VqZ7PEZn)Yn7uiur3BwchOg zVxGBCt3RR_@m!}~V+rgoKcB%HTPbK)FvL;6hi#U?h7vmgEHgs%3cQSA?OIBWfI8_( zuRuq@oFTf+wZS+HvH09C;`Ot&x^M0g43qTzL_A1R82@Pnj}*=j(`h-TYpe*@5QY^Y z;p%0_=To93qsDu*y7bEst4c&n^bhF!polNbMnd*3aujE4Jv3X*y(C~+O^H+7d6Iq) zg+MbA!JS=5wl+pUXr(ym$r{e*YXQ)z5Ja`u^BGLU&a^7T1ePQ+1QmklkuH$U=F{=1 z^l&{dPI0!aD1J`OWq%bwoEDW(c~yz~S5PSyaewPyDC=o=HBeM%p5N%av z(arf(psX3HM}D8r19P>Yh_l`CG^DH8bi-RdSo;`F*k}Q7IxxE3pgz9IuM2> zLu-1r*UjQd3pp(ABJz2^Em}a`Zo7azS;W!e4b!iC7q@NEUa*w{q=g*4p608?n)M<{ zl<9>Mpp{&io+egcko-bOjKd2ZE!${$2I41DB2z8hJmu9(Wcqu`*(su|mTk-Q%&L?t z)M`6+^58tJSZ3@Z1-@ovV8cacqzJ4m+NFGH+xtLgbJk#foMZQYs2wVhfmR*=W* z>_lqx&*S}fYSAn#k1yD%1=y+xVeFC!XZ*71yQ@%YeXvC+&9lgIpawpCJDEyppu*T!$+G75hJ}2w>(@EV1JuQcxQ1>O#H|VQVsC+LzBT+qhvt61$`(z78r~icA z+`>zCX$M->6B-k+_2ZY1ZxUi~o)L<@9=|mDzBX;UFu|b9We}R|VXmV%A9pI)$?qK( z_h{R+fS9GUGnf~Bhwf(VoQIoTqF1>hmO3^SYE!G!^j;wxlzWN~X9dQu=pK0!S^52BH6j+{P8i|3$d)=^^a=}na>JG=i^$4SJ>ZkAA9cS z;aguj=ocJZZ-b_O7plT<6_hqla~P+z;nmr)8IF5bw2!MZ{|Sz%ziBraix|s?-^R6? z`7`-9x3O&cZ4SS68^`DYGkNVhS{MIWbI8x(#q<^2vU&8CWExotKH~4)(b};VbNKo@ zSZI&_i0=b8JDkR=-o?z_XgqIm7h3L*<8RRO=s2E2&sF32`n%fOmgBQU^u89S%C5I@ z<>ybW#q-581vNpOmkgqFGr#e{(_Mk1`CET#*5}@XkV_lQXa1@AcYjmzP7Y3TU3~X3 zIuc%@J|c15M?S^DNm2YrD7z4Ej+5-GGeEL1DvCU7&;TH;HTxZ`Q4{+K zV4jXX2s^P|V_rx=Qz`Kzn(90kM0QNq=))j>F!f}f^{ zH@{BcaS3{2FRvWLn>!P>MPlj*lH_p6l3)%aY>C8VfZ@b!c}{sR!CZ&n84?a`hyvz; zk>XdFY}R^I#9K!B3_MSX(^#BE{f|l)unho2BaV9shk=d^9!=B6KZF7iPY;41>mk1@ zL_MP-Nw%x5E>7TuwRJ^h5l$Pl93+`!OIR~uiEe(m;*)H+7cc9^A($SrO4T5qr}W8m z%nRG_&hr%^hxETtK8kYWm$JMiIED6cFmtC9L4j!!v~7`n0q92+(CHGTwgd9AK;nhc z_vmwb9XFLG;Z592rv_-Ro8JW)B%G?$g0td$7}U3(Q11c3C2Z90Gg1(f{rb|WBVY74 zZux|z@B@Ei8|t$Wloq;qg}*5YD&3FQ{1ARH{igucv2Of;f`KU^msV z;=Z<+u|dNf?aFcgiCGgIGahLZysECjuTRK}+x+ez&FU~~?7qfc8tZT~*1k&R0eu0_ zm(c6gSz0AFAi;6b!s`07w%s^B_&a=FWXGQK$_ahU@xOkl&mTpwUN3EJN@23BF2R=` z;CR}6dQ!ta2tDjtD#2_)#F}P%dp@NlOSAnPDujFjy2JJd;Ta0IKI}$5S<(uiWE$dW zvECudgK(V9`7II`#y~p_nnX|HQ>;C|085%3LAaZXuVWD7IovG6?P6ClRr7G77Zha+ z`)~xAf{k}R<7L)~O>XDd@iN1O&lj3H_O@alRcGG>IHIH3DsOh*&v7$`Evv+;HRP#% zSqS?p$g#dJ!)1++>pQahu^+3jb+!4Nc$V+ARD0~`p|eMfm0BF#6Bv&5R@88OHk>uC z>NT^H#(x;i26%Una!@}>uN9Q~UwLVcMPpc9&1;=m^dycX9tMFm(u`aA{6~6pE_KEEPq+MIe9-);chIH_v_1E7bcqoTa84H_j z-solzCPqe~h+k`1Nk6ZMa+E4>pdVQTJvUy`Ln0;LPP(#BYDBq${Pd^tFOcAdc}l?& z`P{h^_fGtt6odny2_nCk1 z{gSN>*a%Nic!6|a+5Bh9SrqmPVjC2x zn}sWrjza}3tV>0}aRlS{m~D!Ev|>M2NqTTq)i@Cz#C^c50c%CH3={F;7r93xD3G^i zd1>56_!5DqS`h`B5 zf<-t8Xq$o}L`_DhjHOYc$S+EX(G?`lDX6}e79p&5Jtc_p{b$PFq!V62fG?lKMzO^Y zx%XuB)cXJOh{>!k+kD?)o6IU{?EFKXHidO%#rGWtr!d@P>++BI;~-enexj@V1m z55iA;V8;D%47J#iau8`oXo<7sphLx-XM~^kopYGJcam)JS#_WPFpIs#THbe9ZOrgu zEpGGmpRlQ{#ZSEFJl2(uN@bkIonM^Jx;i?~X4#AlKg;jTVTtVDGkn)v){3XiWs&Sl zQAlUcogpy?>vtLwV_4(kd|Wyk$!4D7C(_w|w&f%}`#662l-*!;YuzAIEnVdG4?6V3 z^^Y1i99J_~rp6jv;kGYW#~O35g6o2Ql{`tk$`5_PK5O*o3TPP2gXGSh)rnvJr}8>_ z$9p)-YQ5~3F`or!?7(HdXaTS1*s+iYF(+t7zWENQfC=fBzV{S0t~JI0O$upFF48;vfmkty~2OuER3aH;Z>Hf z={3tP;}`D=ll|yo8g-acm$|Wo^PE^}~w0q!++(~Zf)<^#zIVzT6kQyjbzEIKBH zGH8F)>bBaVZ3NcZs;8ZFskiy2FPldK_wgk9D0MZoe)s5;E{{RJ1^K59XwYxfSI zSht=fRR&I%1efkJhw20UDABPD5YJjT4U$^q9wyekYmP6@Vz00{$9bD9)~wkF#166E z^aQ)V*fsOZ&mu8oN*ASWz;XT=*6oa5qMIBPLy5gkkVf}{M66|8Zeaa6vbXUc6FY*nSw*@7i1S@Dg) zllF(mh>(6n#8I2t7h0W#JqD4*I7jVrlozjH%~+kI{0=?;JmPp^CF`cyb{!Tq`ivJ( z?6Z(iuAb&CL*$bn@vvC=w7x*kRBTwb((}bGGsXvR(2B9?D+EKSw}IHW0%HWl9kknr zgt_tiNm^{hgoApEs2*{dh8CaIAUeIUV+vbxl=$<9xzB3Wpzb^=kRWz)k|byyafo+a z&DzxIOoFM{WNHorsi$L?$LA1Vu$t8h2qLVp9w?sJ`u3N$T1|)e?$zw2h${!BEUZa5 z1i`>2B(O|3?*>rZxiLk5hZ-+Iu_8O6LHqk^DVOa zu+5T_48&K|aHU)3l~+Pk263YQ`;)VF-JDUvzhB2T4fuUO==9c0PvAj>!*(%f7wJ)F z6g`yaIK{}LGF~X1^u%y|gr3-*6=iJfAKA~p|Bf{XSSaLhQX=`&qD3q$k*oIeTi>z9 zwuwY9(-*ZNdV4y(vsgzcS}4(W;*5=MUg0v6zmlydb!En@axGb2ErL(Hcvtk5w6qAt zBg)j{59!$=N@WSB!B;D!|2`Nn6o*=pF~oNt|8_mAANw5W#hu&Zcm*lNhzSR^F2Urt zNVcfOdeAAY7b)0EUlfX#quu@U5DLj85W<;GUS$L89~8V<4DROEP)5Hswm;1q7YxMm zr##;LxR_7hz@n=DN>WIcD^9*=1FOS&I&oCW3R!h0|7s&^60oI6n35JjmlJT|E24 zERtjCGnm-*T?zT?@-E27ghN-l;G>fPItA#e-$F)(d?bZ&mt&HC9hR-WN}~rX93g?j zbS0y>GR3U-UOs*k3#nR5*p5pTMSR&N77*YjPV9sqm(7ZB|O;@ z$qTvfX69ctqmX>j%`^A%mYWgt*Qq>E&y)kNUmh(%;A7Z?LjL|{*7%Je!ZA0Ap%vXS zl*-8#v!LVpBhBqth+!e{8hji3bVyXj`@9{$}AY#)o-?RYw}g2FqK=a zw0U|W7iF4A5Moz1#XNqCWbQ^nSaFKk1N)R6s0?OWkGOg+7ptp0xo*PZl7fcyT7PJC zJ^V&2t}^?dqwr#2s7j*C^z0zwLYc|(q9khCWXozX6k!8;1*GZJA9wrxvOR6{y0jzm z%ocurCu`U2JF?G9&lmG?xg}$pY{STOqW97BR6a#6*utZBu}19mE&Q!rEWBo4!VjSj z&IqO7?vFBW;mdciddzzZ-@S`9sd|TkaY~Omm&^ay#iH5PTpp3n>e$v0y+{{JP{>&~ zQMrt4w5*;k>Q2D9tCwCv9UxtJkW80F^r*?ixf3JOjL882u3lbaCvm=mIcdoYF9wG{B63 zRK`4QqApOThYb9|v2!<@p#`{d1hCrswrohXCX1Sv!}}FrjNAoWUgN+T=Url^j)+@R z_tlI)kZ9ELKszq8Bg$9O4uB>H60B3Jd1P1W@+J!OJy$_?iOi&^^36iu0W6@?=G~1J zRt0V*;yrBnf*2tg16N9#Fh;GTqBzk~_0@NjAzy6fO$%AO@S#M%j+Gu3$n%9fMltDe zU<1Oi;O-=!K0P;c{BTJC^V-Ze6tZRs|7;>0=jRvHHIjS!YL^^Ie98zTy)$0CfQ$%S zCV2f;Q*dbTzX`=YYlw(@8}nfltqiX~+wXMiz-KdWxtGaeXgq%wje< zX6KCof>VUp7Bd#2WYCwUI2s7q+NL9)yZ-@fCnZ z)}R0)EZR>@ut=<+DW|UMY4I}G0+$I4p~j@}#YWz#7)dZrD$SHDA*th4rK64PKq9Z} z5l!ifAUfp=@>{HmkoR6nPmqw2dfXeNE&dhs+#{OOW4Vj3!xl5YE{BMCUC%T<5f*nE z0-KXkjA|khc!z8(jKJtak;&D4HVE9}(`qAc?qsco{vniGBE>Tq@A$MlL~j;lGWd{) z9{PG88U!qnM}&ol2-b5lVwT84Nh9VA6}iZ~4Sc(k)vuFTfnP?)61iXl|DCWIqH;vM z!rE}c2HtQVYhnwN7+OeO*2vW}MWkR{L&ETWBb-OM?Ru0iBwV0d4@Z%KE{cFy_;%HO zS`&!zH(Er>64rsrnCmUnD==>U_8rPNffw^6?}Op9YLZ@@YgLu{(@eCOK?nHoJHBc^ z+g@|pI$>~{h3Lz0@A^AFv4pi^C)e^-C9F}+#{w4@D8zM+%Io;K5_FL7*YZatEWmfs zTC%f`{y&5@Y};Di5)lm`S1g*PLp`T=vK)+asQ)8@ZFP( zx7vh3Po=f|s{^cF9bc&j=TBJW-NPLdIC5bPKXiaK>9t{v(Bs6A`UfH$k}JybYBmAm z3dw+#U>~eelP&q8O>nz+0f6Gp&GjGY`v#NO@^%Li(s$SJ!3SCWs;^R&7&Bj8%WVg- zKWtgc7lY20tl?V^Vn?rFHC1bg%vsGJL$0nJWqP-#bdB07K;1lR4aaX*^$6nXzY=*`JH3Ei%ZXJ9ocxt1c6=^V|9(->L7M zdRLvQx_#4)r&42f@V8E?{R+B}{^Xo})xwXCGU9mR;icK~9()-b#4q(!K+k=Canc*} zg%QU|`QAA%8Yf{CzO9~HTGcsfNj)!aRa5#uN;co(gl70YdO@GuQa#_$s^M;Umk$pgYXenr0<9r zm^P@*(5H>s@;dBd=^G+c^NO@#^{?~wZFpQ;_d5TuP5n)++8B86Pb%JiuvPQS^BA7} z8+hq?JZ5QF8+iM?n$=w`TF(FY8x3}8;PP+k;}-ST$NAi=>V9>?&I(z z*%Y;}oqwInGS&a+%e&sg7I^CH^wqa{Hau;wTG)e%ezr?3IQk{5X&S}0nlT&2$llNy zKO^{t8FP@%Z^n$D5q#T>xky)U#@rO!DPwC>y|kBt*Z^91 zp2r?hzeo?fn8yxT)bEG#ynHlp#PGm^e0GaP{c~^bp3Vl0w`eilcgU^b*V2ynjCFiP zhPdyu!2N?)WUeO#j!tKHS@+ndIphD$$?9w#$F-=Q-&IlU*Q2@{=m4$;I)Sx77q9{7 z2etrx(Wo8)hJlF*ilW7$dN$Aw%m+Gv#Xu*}4fFz61B30z4;a>?dY^7+z7o^%GY}rd zWr^w4ApF3+K${xVTYx?m)9F{omAIIG1sLiQ(E%E#unrgkHUS;+ zF+B|Q1LN?CP7pW{s3gR6C(xD{)9JG&7qF$f2N`vb>1`lgGtt zCyziUkUms$0ha;2z-pi$=&6Gc9vRb{fzFJWeij%4UI1#DFN z07Ii=dLz&=78Rj5aC|Q`WC98RIwvDPU>KO#8}YlK2ZpD_^o2lgPRyh4BE|1w`WaFH zKxH~A2=oG#zUZL>R1jzfrU4zm$v`*I2@C?ufWCWC zaf$2=EHU??Z<8T`xN@4d?|rf!d6i{shng^a7p0Ex;hK2^hH_ zLj<(Jhg|^LfeL(>7nlZgK7fh=eZV4M*aN`}q47av1XLcvDgcInEkOTFOirM87A7aq z2aHPw4@?F&0yBU?paU3r7(E8GJ%Y&zbj?MDfIi>_U=2Y<%u1jQ zSPZlS-9QI$HP8vH1-gI@z%cMEFt`wtE(LZ^qeZ|Fa0}2@g1G_o0?z{7i_jATpa-S_ z!@$V{u>K9 zKriqN(Enacw+%v10keS-U_MZ3z^WL8_3wQjH3i{pL`{L=V@NO<{5P1TK=-$3IndRH zApwTYVYv-K{AYAIP>Eu;1A{Z$^)tZG>~{SMF!D&dKF|jJ+;-g#v;p&hcAyLB!>e_> zJP@>H?fO|@q_ka+|0iVpLc2Z`=*D5j1q@ZT>y1F|#dbXe^x_bsq=Ltm$3dJ|9shJdy&bba7ZR0P=74#5c_Kk!;9+oO8U!Ctv1 zNn4{%PfD(0_b1uZU{Z2Ul9rPc4^su-tg1vJQT@OEuiYWj4z5GF1iSseM0NNlBM^sQ z##8oo;_$Yb*wtR-DJxit zrIn9a!AA5wb1|yJMHzwWLZ2sx`O+1v_uXw!VMn{6x&+l(aOlb#Tznjw1a7=VaAkmj z;B1%pkrix3-{wnE9iGkz#rWF*U5G#Mdp6G!;vf8;-JW;uZ&BSNEvSx#UC{BDqxzGS zBif1I@SA5rOQ~`Tp{xHbs+UN62e2HRa)qasv#En?u158Bq%+c~Rn$Q?MBB*b8m}y8 zscOwNzO$SSwzTnMoo80y$WeEl=T)#Qbyt+Hs9-bHvUYx= zf(`fhuwOSKHwsiG*DZ>YfxVj=PJy^(;A+9Sh(I8&8r-=~Tpc(&_IqruM##Y5M#>Ld z12K6?T8)~Ul)Q%JB-yIsRCfY@b|veJ+kA|#UCD;w19|@bN|vHltNg@DHqz6ILjvC7 zFankO1UjGv2ZoLuy{6NQ!-LiOce@&J!GxPRKe#3hJCrapTCo@0esI6TET%wZw1B&W zJ$_vryp~C}fpqu3IdKHsVsMnmw2Q+8TiA(92KNNGj&m;q5f?bKt0)f#xMFbT{OUvH z&jd*s!Xx4cnWQ}^r_N&VRH2S@-3zW995yy1P^MeJRf8MRp%-_7tH)QTbzHMe;QZj` zbx0fXfV|Mj@Eo}B!O@Y80u^!v+&OR^D?^9INC%GAwGCVp+!VPM)~NS)x8_taHq?@k zcuRZ^-upbeH1`fnjBn7Jf zYH(>2`0%wXb!-D&9!Zr#T8xu#=3L;Kzqv6yk zZs_WuyYq(5W$374HP8j2BbfrBA6!!>ZZEj~9XPs6w1C?S4xIhX-hb9G<~ftY>3WlhOKYTv(>VMk$~pU+Hn`QJSII&@H^5f4QEeW)?&C z!|q42GfreTj)tF^M?Pa#QyM2veTk*cZlE;In|FgCxH@p~vqqr)Is>k@lil~=wshcV z@MDL3@y&KsjS)LQclrXFKJHu~Q#QNQ$4<&6ogg=o+BITr&cV!D?{( zXYte;c)&);(fNEv4a>7eA-kUBTWi?JtPEV-+_;5|km(4huDRf=!Bc%G&^Q%=t6$77 zBagg#$Yn3z+`j$bmVujOq`=Aqwu1A6qr;jR3L%^WU;8qz+${vJjKTb7x*E!PHew1UR3wJ;99`Z^i*<_ zv>BK%Mw=)d_>OJLr8XJ%ywZmh=WWveO(dluoraK(?Rd1tedBocuH2 zw3+3lIB+?f{HT88ghS&$6WsVm`9`kSxaISgKeKH4=#^RaOnY{^Z9?XqJb5R}4b0uihFQqC z@*Va}7fX=;(!jn_BX0#x>}K!BS<3kfAF?~3=kI>Vc4kHXgpv@FajT(l5C`vGN}}Sp zD&poW|HkB>bH)wP6A-ODmPj-aqNJ=$(~3d%=o5&RwUsC+{5-q!?g zuD-uY-to!J`COHJp4+_G}?`6sR4hTM9+MmK!Lgjc1#UYjMFccc3y>`;zXDf&s;bWcUFVd>3n0j7x?KP*zQ)lhvR>x8*^Z@OFZ4pAS)T;he2 zcgl9j>MQfid}>8L=7d>p=5s>u4pG}~$_A-$ALa)F7(jo4(EN|EQw~UdaFHO)0c@3g zSXRL7@V}b*9pqX2F+r5q_NAp8b_>HNrTsd|`#%!I zX36iCyjM;XGoMclUK-)iMvsqJ&lJBb%zTjWt4!?3;S)bXCAFYPkSWt;cNdj(Gzr3N zWTE66Kfc-iDarfgGTSKg@krh-D~YHPY9()5VMK3N`pI?tp_!mf7~?&L5n-lGk$Rh4r)83#CwbQe3nLYZx)GHT7 zf^papDIAo%Hc%`9(*gdw#r)DcMq?@I_1=?$ze9l1DtY`@b zg*Hmwe^u~3`NqW}ZaSV4$@>S3Mjn@Kt&qG+^jUAk zY*ejOID@?825dt#1VKLmt2UWq<)svJLO== zdMb+~A3DOP9>saq)oH{JNxiq6zYV>rwej;uG1$&db`x+PsGD= zT%MME_%DKgQZ}$$^2%PpR|!xyOFmL(5OWptDc*LeaOW^XV=lyfW&zEj%M)e6%_c8% zHcvER$v2+l7n{*QZ>cDGm#n}kd2n({k3$Cq3b*zb4R`)5;=5%z>5_LzPcuiTl?jr! z$&NBTWxmOaj^%G2W9c4Ej=oDKu8~G|Ir^p-dsp&K*$J5RMre|JQ1&vMlMzlyUXlB) zbO#E3s%WeVQSR+ZgG}%@sfc_l2y=~F<$kD)<p1JLMo#hr$FXlUJ}=Bm zWH$4qx&L1TF;(&vlGol9#6z+Z>848cv0W5|S?oKKckLARFUfoYl8*?Udp>39suN$m z@hL0KQW}Mo@z@k%$*m%DyR6JYnMsA@g9G@3Em(qDr>TBW>b?6#f~_(geey|_b-uwr zY@wyJNGQyuO;=q*{|WE)87@=4d-?j$;N)Fg*bR{Rv`V}1S^ni`SaOP+r<{PD%`FUE zVnQp^k%013-s1D2SAE~|O()n^i#;&vB-@NHgZ_aZInOc^%H*WL& plant, bool has_double_stance, const string& osc_walking_gains_filename, const string& osqp_settings_filename) - : pos_map(multibody::makeNameToPositionsMap(plant)), + : plant_(&plant), + pos_map(multibody::makeNameToPositionsMap(plant)), vel_map(multibody::makeNameToVelocitiesMap(plant)), act_map(multibody::makeNameToActuatorsMap(plant)), left_toe(LeftToeFront(plant)), @@ -204,6 +206,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( auto touchdown_event_time = builder.AddSystem( plant, double_support_states); + auto radio_parser = builder.AddSystem(); liftoff_event_time->set_name("liftoff_time"); touchdown_event_time->set_name("touchdown_time"); /**** OSC setup ****/ @@ -462,11 +465,13 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( builder.Connect(right_toe_angle_traj_gen->get_output_port(0), osc->get_tracking_data_input_port("right_toe_angle_traj")); builder.Connect(osc->get_output_port(0), command_sender->get_input_port(0)); + builder.Connect(radio_parser->get_output_port(), + high_level_command->get_radio_input_port()); // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); - builder.ExportInput(high_level_command->get_radio_input_port(), - "lcmt_cassie_out"); + builder.ExportInput(radio_parser->get_input_port(), + "raw_radio"); builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); builder.ExportOutput(osc->get_osc_output_port(), "u, t"); diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.h b/examples/Cassie/diagrams/osc_walking_controller_diagram.h index 6728c4e38c..b6155b8370 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.h @@ -54,8 +54,8 @@ class OSCWalkingControllerDiagram final /// @return the input port for the cassie_out struct (containing radio /// commands). - const drake::systems::InputPort& get_cassie_out_input_port() const { - return this->get_input_port(cassie_out_input_port_index_); + const drake::systems::InputPort& get_radio_input_port() const { + return this->get_input_port(radio_input_port_index_); } /// @return the output port for the controller torques. @@ -74,7 +74,12 @@ class OSCWalkingControllerDiagram final return this->get_output_port(controller_failure_port_index_); } + drake::multibody::MultibodyPlant& get_plant() { + return *plant_; + } + private: + drake::multibody::MultibodyPlant* plant_; std::map pos_map; std::map vel_map; std::map act_map; @@ -155,7 +160,7 @@ class OSCWalkingControllerDiagram final std::unique_ptr swing_hip_yaw_traj; const int state_input_port_index_ = 0; - const int cassie_out_input_port_index_ = 1; + const int radio_input_port_index_ = 1; const int control_output_port_index_ = 0; const int torque_output_port_index_ = 1; const int controller_failure_port_index_ = 2; diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index e579da1f38..5bf409df15 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -3,23 +3,23 @@ LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [58.69651493481853, 0.0, 0.0, 0.0, 36.86831846956082, 0.0, 0.0, 0.0, 134.9722705422692] +PelvisKp: [85.74429563681282, 0.0, 0.0, 0.0, 21.57873464698917, 0.0, 0.0, 0.0, 137.43739267179197] PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [6.184287991604621, 0.0, 0.0, 0.0, 12.33458087407842, 0.0, 0.0, 0.0, - 6.001919613735179] -SwingFootKp: [101.29500573242039, 0.0, 0.0, 0.0, 72.7231411452184, 0.0, 0.0, 0.0, - 85.72574891431772] +SwingFootKd: [8.078917410827255, 0.0, 0.0, 0.0, 12.576529765299595, 0.0, 0.0, 0.0, + 2.431152422425895] +SwingFootKp: [101.03127214896419, 0.0, 0.0, 0.0, 59.42442696850133, 0.0, 0.0, 0.0, + 63.23743619668404] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.03229512503184142 -flight_duration: 0.07102876166265246 +center_line_offset: 0.03547263514242609 +flight_duration: 0.07371200188107095 footstep_offset: -0.05 hip_yaw_kd: 1 hip_yaw_kp: 40 @@ -27,8 +27,8 @@ impact_threshold: 0.025 mu: 0.6 relative_feet: true relative_pelvis: true -rest_length: 0.8458962719169322 -stance_duration: 0.2697674609581958 +rest_length: 0.8473166415309785 +stance_duration: 0.2885407656243229 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 From b20450c80123a7176065ed63cbf437aa751e60d2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 26 Mar 2022 19:13:11 -0400 Subject: [PATCH 169/758] copied domain randomization code from apex --- .../cassie/gym_envs/cassie_gym_test.py | 6 +- .../cassie/gym_envs/mujoco_cassie_gym.py | 179 ++++++++++++++++-- .../cassie/gym_envs/reward_osudrl.py | 5 + 3 files changed, 175 insertions(+), 15 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 7204161e61..debb8204da 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -20,8 +20,8 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() @@ -33,7 +33,7 @@ def main(): action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 - while gym_env.current_time < 50.0: + while gym_env.current_time < 50.0 and not gym_env.terminated: state, reward = gym_env.step(action) cumulative_reward += reward # gym_env.reset() diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 355d77016b..7c0a02a645 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -1,4 +1,5 @@ import numpy as np +import math from pydrake.multibody.parsing import Parser from pydrake.systems.framework import DiagramBuilder @@ -21,6 +22,7 @@ from pydairlib.systems import (RobotOutputSender, RobotOutputReceiver) + class MuJoCoCassieGym(): def __init__(self, reward_func, visualize=False): self.sim_dt = 8e-5 @@ -59,14 +61,51 @@ def __init__(self, reward_func, visualize=False): 'knee_right_motor': 8, 'toe_right_motor': 9} - def make(self, controller, model_xml='cassie.xml'): + def make(self, controller, model_xml='cassie.xml', dynamics_randomization=True): self.builder = DiagramBuilder() - self.dt = 8e-5 - # self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSim(self.default_model_directory + model_xml) if self.visualize: self.cassie_vis = CassieVis(self.simulator) + + ''' + Copied from apex/cassie.py + ''' + self.max_simrate = 1.2 * self.gym_dt + self.min_simrate = 0.8 * self.gym_dt + self.dynamics_randomization = dynamics_randomization + self.dynamics_randomization = dynamics_randomization + self.slope_rand = dynamics_randomization + self.joint_rand = dynamics_randomization + + self.max_pitch_incline = 0.03 + self.max_roll_incline = 0.03 + + self.encoder_noise = 0.01 + + self.damping_low = 0.3 + self.damping_high = 5.0 + + self.mass_low = 0.5 + self.mass_high = 1.5 + + self.fric_low = 0.4 + self.fric_high = 1.1 + + self.speed = 0 + self.side_speed = 0 + self.orient_add = 0 + + self.default_damping = self.simulator.get_dof_damping() + self.default_mass = self.simulator.get_body_mass() + self.default_ipos = self.simulator.get_body_ipos() + self.default_fric = self.simulator.get_geom_friction() + self.default_rgba = self.simulator.get_geom_rgba() + self.default_quat = self.simulator.get_geom_quat() + + self.motor_encoder_noise = np.zeros(10) + self.joint_encoder_noise = np.zeros(6) + self.builder.AddSystem(self.controller) # self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), True) self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), False) @@ -76,19 +115,111 @@ def make(self, controller, model_xml='cassie.xml'): self.drake_to_mujoco_converter = DrakeToMujocoConverter(self.sim_dt) self.diagram = self.builder.Build() - self.sim = Simulator(self.diagram) + self.drake_sim = Simulator(self.diagram) self.robot_output_sender_context = self.diagram.GetMutableSubsystemContext(self.robot_output_sender, - self.sim.get_mutable_context()) + self.drake_sim.get_mutable_context()) self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, - self.sim.get_mutable_context()) + self.drake_sim.get_mutable_context()) self.controller_output_port = self.controller.get_torque_output_port() self.radio_input_port = self.controller.get_radio_input_port() - self.sim.get_mutable_context().SetTime(self.start_time) + self.drake_sim.get_mutable_context().SetTime(self.start_time) self.reset() self.initialized = True def reset(self): - # self.traj = CassieTraj() + + if self.dynamics_randomization: + damp = self.default_damping + + pelvis_damp_range = [[damp[0], damp[0]], + [damp[1], damp[1]], + [damp[2], damp[2]], + [damp[3], damp[3]], + [damp[4], damp[4]], + [damp[5], damp[5]]] # 0->5 + + hip_damp_range = [[damp[6] * self.damping_low, damp[6] * self.damping_high], + [damp[7] * self.damping_low, damp[7] * self.damping_high], + [damp[8] * self.damping_low, damp[8] * self.damping_high]] # 6->8 and 19->21 + + achilles_damp_range = [[damp[9] * self.damping_low, damp[9] * self.damping_high], + [damp[10] * self.damping_low, damp[10] * self.damping_high], + [damp[11] * self.damping_low, damp[11] * self.damping_high]] # 9->11 and 22->24 + + knee_damp_range = [[damp[12] * self.damping_low, damp[12] * self.damping_high]] # 12 and 25 + shin_damp_range = [[damp[13] * self.damping_low, damp[13] * self.damping_high]] # 13 and 26 + tarsus_damp_range = [[damp[14] * self.damping_low, damp[14] * self.damping_high]] # 14 and 27 + + heel_damp_range = [[damp[15], damp[15]]] # 15 and 28 + fcrank_damp_range = [[damp[16] * self.damping_low, damp[16] * self.damping_high]] # 16 and 29 + prod_damp_range = [[damp[17], damp[17]]] # 17 and 30 + foot_damp_range = [[damp[18] * self.damping_low, damp[18] * self.damping_high]] # 18 and 31 + + side_damp = hip_damp_range + achilles_damp_range + knee_damp_range + shin_damp_range + tarsus_damp_range + heel_damp_range + fcrank_damp_range + prod_damp_range + foot_damp_range + damp_range = pelvis_damp_range + side_damp + side_damp + damp_noise = [np.random.uniform(a, b) for a, b in damp_range] + + m = self.default_mass + pelvis_mass_range = [[self.mass_low * m[1], self.mass_high * m[1]]] # 1 + hip_mass_range = [[self.mass_low * m[2], self.mass_high * m[2]], # 2->4 and 14->16 + [self.mass_low * m[3], self.mass_high * m[3]], + [self.mass_low * m[4], self.mass_high * m[4]]] + + achilles_mass_range = [[self.mass_low * m[5], self.mass_high * m[5]]] # 5 and 17 + knee_mass_range = [[self.mass_low * m[6], self.mass_high * m[6]]] # 6 and 18 + knee_spring_mass_range = [[self.mass_low * m[7], self.mass_high * m[7]]] # 7 and 19 + shin_mass_range = [[self.mass_low * m[8], self.mass_high * m[8]]] # 8 and 20 + tarsus_mass_range = [[self.mass_low * m[9], self.mass_high * m[9]]] # 9 and 21 + heel_spring_mass_range = [[self.mass_low * m[10], self.mass_high * m[10]]] # 10 and 22 + fcrank_mass_range = [[self.mass_low * m[11], self.mass_high * m[11]]] # 11 and 23 + prod_mass_range = [[self.mass_low * m[12], self.mass_high * m[12]]] # 12 and 24 + foot_mass_range = [[self.mass_low * m[13], self.mass_high * m[13]]] # 13 and 25 + + side_mass = hip_mass_range + achilles_mass_range \ + + knee_mass_range + knee_spring_mass_range \ + + shin_mass_range + tarsus_mass_range \ + + heel_spring_mass_range + fcrank_mass_range \ + + prod_mass_range + foot_mass_range + + mass_range = [[0, 0]] + pelvis_mass_range + side_mass + side_mass + mass_noise = [np.random.uniform(a, b) for a, b in mass_range] + + delta = 0.0 + com_noise = [0, 0, 0] + [np.random.uniform(val - delta, val + delta) for val in self.default_ipos[3:]] + + fric_noise = [] + translational = np.random.uniform(self.fric_low, self.fric_high) + torsional = np.random.uniform(1e-4, 5e-4) + rolling = np.random.uniform(1e-4, 2e-4) + for _ in range(int(len(self.default_fric) / 3)): + fric_noise += [translational, torsional, rolling] + + self.simulator.set_dof_damping(np.clip(damp_noise, 0, None)) + self.simulator.set_body_mass(np.clip(mass_noise, 0, None)) + self.simulator.set_body_ipos(com_noise) + self.simulator.set_geom_friction(np.clip(fric_noise, 0, None)) + else: + self.simulator.set_body_mass(self.default_mass) + self.simulator.set_body_ipos(self.default_ipos) + self.simulator.set_dof_damping(self.default_damping) + self.simulator.set_geom_friction(self.default_fric) + + if self.slope_rand: + geom_plane = [np.random.uniform(-self.max_roll_incline, self.max_roll_incline), + np.random.uniform(-self.max_pitch_incline, self.max_pitch_incline), 0] + quat_plane = euler2quat(z=geom_plane[2], y=geom_plane[1], x=geom_plane[0]) + geom_quat = list(quat_plane) + list(self.default_quat[4:]) + self.simulator.set_geom_quat(geom_quat) + else: + self.simulator.set_geom_quat(self.default_quat) + + if self.joint_rand: + self.motor_encoder_noise = np.random.uniform(-self.encoder_noise, self.encoder_noise, size=10) + self.joint_encoder_noise = np.random.uniform(-self.encoder_noise, self.encoder_noise, size=6) + else: + self.motor_encoder_noise = np.zeros(10) + self.joint_encoder_noise = np.zeros(6) + q_mujoco, v_mujoco = self.drake_to_mujoco_converter.convert_to_mujoco( reexpress_state_global_to_local_omega(self.x_init)) mujoco_state = self.simulator.get_state() @@ -96,9 +227,9 @@ def reset(self): mujoco_state.set_qvel(v_mujoco) mujoco_state.set_time(self.start_time) self.simulator.set_state(mujoco_state) - self.sim.get_mutable_context().SetTime(self.start_time) + self.drake_sim.get_mutable_context().SetTime(self.start_time) u = np.zeros(10) - self.sim.Initialize() + self.drake_sim.Initialize() self.current_time = self.start_time self.prev_cassie_state = CassieEnvState(self.current_time, self.x_init, u, np.zeros(18)) self.cassie_state = CassieEnvState(self.current_time, self.x_init, u, np.zeros(18)) @@ -120,14 +251,18 @@ def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") - next_timestep = self.sim.get_context().get_time() + self.gym_dt + if self.dynamics_randomization: + timestep = np.random.uniform(self.max_simrate, self.min_simrate) + else: + timestep = self.gym_dt + next_timestep = self.drake_sim.get_context().get_time() + timestep # action[2] = 0.75 self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) self.radio_input_port.FixValue(self.controller_context, action) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) - self.sim.AdvanceTo(next_timestep) + self.drake_sim.AdvanceTo(next_timestep) while self.simulator.time() < next_timestep: self.simulator.step(cassie_in) if self.visualize: @@ -228,3 +363,23 @@ def copy_elmo(self, elmo_out_lcm, elmo_out): def free_sim(self): del self.cassie_env + + +def euler2quat(z=0, y=0, x=0): + z = z / 2.0 + y = y / 2.0 + x = x / 2.0 + cz = math.cos(z) + sz = math.sin(z) + cy = math.cos(y) + sy = math.sin(y) + cx = math.cos(x) + sx = math.sin(x) + result = np.array([ + cx * cy * cz - sx * sy * sz, + cx * sy * sz + cy * cz * sx, + cx * cz * sy - sx * cy * sz, + cx * cy * sz + sx * cz * sy]) + if result[0] < 0: + result = -result + return result diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index 9bb63354d8..e0308a2822 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -18,6 +18,11 @@ class RewardOSUDRL(): def __init__(self, weights_filename=None): if weights_filename: weights = self.load_weights(weights_filename) + self.neutral_foot_orient = np.array([-0.24790886454547323, -0.24679713195445646, -0.6609396704367185, 0.663921021343526]) + self.l_foot_orient = 0 + self.r_foot_orient = 0 + + return def load_weights(self, filename): From 8d86171aea33b886ffbaf6c296ec67a9d7be3e82 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 26 Mar 2022 19:36:10 -0400 Subject: [PATCH 170/758] need to clean up code --- bindings/pydairlib/cassie/learn_osc_gains.py | 39 ++++++++++++------- .../osc_running_controller_diagram.cc | 2 - .../osc_run/learned_osc_running_gains.yaml | 28 ++++++------- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- 4 files changed, 39 insertions(+), 32 deletions(-) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 7518e09829..2216e733e3 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -42,7 +42,10 @@ def __init__(self, budget, reward_function, visualize=False): self.loss_over_time = [] self.default_osc_gains = { - 'PelvisKp': np.array([0, 0, 85]), + 'mu': 0.6, + 'w_hip_yaw': 2.5, + 'hip_yaw_kp': 40, + # 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), # 'PelvisRotKd': np.array([10, 5, 1]), @@ -50,7 +53,8 @@ def __init__(self, budget, reward_function, visualize=False): 'SwingFootKd': np.array([5, 5, 1]), # 'FootstepKd': np.array([0.2, 0.45, 0]), 'center_line_offset': 0.03, - 'rest_length': 0.85, + # 'rest_length': 0.85, + 'footstep_offset': -0.05, 'stance_duration': 0.30, 'flight_duration': 0.08, } @@ -75,11 +79,11 @@ def write_params(self, params): def get_single_loss(self, params): self.write_params(params) - if np.random.random() < 0.5: + if np.random.random() < 0.0: print('drake_sim') gym_env = DrakeCassieGym(self.reward_function, visualize=self.visualize) else: - print('mujoco') + # print('mujoco') gym_env = MuJoCoCassieGym(self.reward_function, visualize=self.visualize) controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, self.controller_urdf, False, False) @@ -93,13 +97,15 @@ def get_single_loss(self, params): state, reward = gym_env.step(np.zeros(18)) cumulative_reward += reward self.loss_over_time.append(cumulative_reward) - print(-cumulative_reward) + # print(-cumulative_reward) return -cumulative_reward def learn_gains(self, batch=True): - self.loss_over_time = [] self.default_params = ng.p.Dict( - PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), + mu=ng.p.Scalar(lower=0.4, upper=1.0), + w_hip_yaw=ng.p.Scalar(lower=0, upper=10), + hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), + # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), @@ -107,12 +113,15 @@ def learn_gains(self, batch=True): SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), - rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) + self.loss_over_time = [] self.default_params.value = self.default_osc_gains optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) + optimizer.register_callback("tell", ng.callbacks.ProgressBar()) # with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: # recommendation = optimizer.minimize(square, executor=executor, batch_mode=False) params = optimizer.minimize(self.get_single_loss) @@ -123,15 +132,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 1000 + budget = 2000 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - # optimizer.learn_gains() + optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_25_17_1000', optimizer.drake_params_folder).value - optimizer.write_params(optimal_params) - reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - plt.plot(reward_over_time) - plt.show() + # optimal_params = optimizer.load_params('2022_03_25_17_1000', optimizer.drake_params_folder).value + # optimizer.write_params(optimal_params) + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + # plt.plot(reward_over_time) + # plt.show() diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 8925b487e8..d390679dd9 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -425,7 +425,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Build OSC problem osc->SetOsqpSolverOptionsFromYaml(osqp_settings_filename); osc->Build(); - std::cout << "Built OSC" << std::endl; /*****Connect ports*****/ @@ -503,7 +502,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.BuildInto(this); this->set_name(("osc_running_controller_diagram")); DrawAndSaveDiagramGraph(*this); - std::cout << "Built controller" << std::endl; } } // namespace controllers diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 5bf409df15..51ef20a5f0 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -3,39 +3,39 @@ LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [85.74429563681282, 0.0, 0.0, 0.0, 21.57873464698917, 0.0, 0.0, 0.0, 137.43739267179197] +PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] -PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 0.0] +PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [8.078917410827255, 0.0, 0.0, 0.0, 12.576529765299595, 0.0, 0.0, 0.0, - 2.431152422425895] -SwingFootKp: [101.03127214896419, 0.0, 0.0, 0.0, 59.42442696850133, 0.0, 0.0, 0.0, - 63.23743619668404] +SwingFootKd: [7.470159439828845, 0.0, 0.0, 0.0, 12.580856772920194, 0.0, 0.0, 0.0, + 2.082002568974916] +SwingFootKp: [114.16480444536955, 0.0, 0.0, 0.0, 100.03932909749986, 0.0, 0.0, 0.0, + 54.79286331701048] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.03547263514242609 -flight_duration: 0.07371200188107095 -footstep_offset: -0.05 +center_line_offset: 0.03977871878316904 +flight_duration: 0.07977287590217821 +footstep_offset: -0.06099934134060533 hip_yaw_kd: 1 -hip_yaw_kp: 40 +hip_yaw_kp: 50.15472945993452 impact_threshold: 0.025 -mu: 0.6 +mu: 0.7552292632842741 relative_feet: true relative_pelvis: true -rest_length: 0.8473166415309785 -stance_duration: 0.2885407656243229 +rest_length: 0.85 +stance_duration: 0.2976513438348498 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 vel_scale_trans_sagital: 0.2 w_accel: 1.0e-05 -w_hip_yaw: 2.5 +w_hip_yaw: 1.9711914198221558 w_input: 0.0 w_input_reg: 0.001 w_soft_constraint: 100 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d51e18aec7..c8c8768482 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -64,7 +64,7 @@ PelvisRotW: PelvisRotKp: [50., 0, 0, 0, 100., 0, - 0, 0, 0.] + 0, 0, 1.] PelvisRotKd: [10., 0, 0, 0, 5., 0, From 74849948e3aa28b703b05573d870d7f0a411f897 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 28 Mar 2022 13:33:30 -0400 Subject: [PATCH 171/758] learned gains dont seem to be much better, reducing range of domain randomization --- .../cassie/gym_envs/cassie_gym_test.py | 11 +- .../cassie/gym_envs/drake_cassie_gym.py | 16 - .../cassie/gym_envs/mujoco_cassie_gym.py | 278 +++++++++--------- bindings/pydairlib/cassie/learn_osc_gains.py | 38 ++- .../osc_run/learned_osc_running_gains.yaml | 29 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- 6 files changed, 188 insertions(+), 186 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index debb8204da..e949b6d688 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -33,10 +33,9 @@ def main(): action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 - while gym_env.current_time < 50.0 and not gym_env.terminated: - state, reward = gym_env.step(action) - cumulative_reward += reward - # gym_env.reset() + while 1: + cumulative_reward = gym_env.advance_to(20) + gym_env.reset() # while gym_env.current_time < 5.0: # state, reward = gym_env.step(action) # cumulative_reward += reward diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index b353f7f1b6..1d8d7883d2 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -20,12 +20,9 @@ def __init__(self, reward_func, visualize=False): self.sim_dt = 1e-3 self.visualize = visualize self.reward_func = reward_func - # hardware logs are 50ms long and start approximately 5ms before impact - # the simulator will check to make sure ground reaction forces are first detected within 3-7ms self.start_time = 0.00 self.current_time = 0.00 self.end_time = 0.05 - # self.traj = CassieTraj() self.hardware_traj = None self.action_dim = 10 self.state_dim = 45 @@ -33,9 +30,6 @@ def __init__(self, reward_func, visualize=False): [1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) - self.default_contact_params = {"mu": 0.8, - "stiffness": 4e4, - "dissipation": 0.5} self.prev_cassie_state = None self.controller = None self.terminated = False @@ -49,7 +43,6 @@ def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.controller = controller self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) self.new_plant = self.simulator.get_plant() - # self.sensor_aggregator = self.simulator.get_sensor_aggregator() self.builder.AddSystem(self.controller) self.builder.AddSystem(self.simulator) @@ -69,12 +62,9 @@ def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.initialized = True def reset(self): - # self.traj = CassieTraj() self.new_plant.SetPositionsAndVelocities(self.new_plant.GetMyMutableContextFromRoot( self.sim.get_mutable_context()), self.x_init) self.sim.get_mutable_context().SetTime(self.start_time) - # self.traj.update(self.start_time, self.x_init, - # np.zeros(self.action_dim)) x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_context())) @@ -98,26 +88,20 @@ def check_termination(self): def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") - # next_timestep = self.sim.get_context().get_time() + self.dt next_timestep = self.sim.get_context().get_time() + self.sim_dt self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.controller.get_radio_input_port().FixValue(self.controller_context, action) - # self.sim.AdvanceTo(np.around(next_timestep, decimals=3)) self.sim.AdvanceTo(next_timestep) self.current_time = self.sim.get_context().get_time() x = self.plant.GetPositionsAndVelocities( self.plant.GetMyMutableContextFromRoot( self.sim.get_context())) - # print(next_timestep) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp - # u = np.zeros(10) self.cassie_state = CassieEnvState(self.current_time, x, u, action) reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() - # reward = 0 self.prev_cassie_state = self.cassie_state - # self.traj.update(next_timestep, cassie_state, action[:10]) return self.cassie_state, reward def get_traj(self): diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 7c0a02a645..dc992a2985 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -24,7 +24,7 @@ class MuJoCoCassieGym(): - def __init__(self, reward_func, visualize=False): + def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamics_randomization=True): self.sim_dt = 8e-5 self.gym_dt = 1e-3 self.visualize = visualize @@ -37,33 +37,7 @@ def __init__(self, reward_func, visualize=False): self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' - self.cassie_in = cassie_user_in_t() - self.cassie_out = cassie_out_t() - self.cassie_out_lcm = lcmt_cassie_out() - self.action_dim = 10 - self.state_dim = 45 - self.x_init = np.array( - [1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, - -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) - self.prev_cassie_state = None - self.controller = None - self.terminated = False - self.initialized = False - self.actuator_index_map = {'hip_roll_left_motor': 0, - 'hip_yaw_left_motor': 1, - 'hip_pitch_left_motor': 2, - 'knee_left_motor': 3, - 'toe_left_motor': 4, - 'hip_roll_right_motor': 5, - 'hip_yaw_right_motor': 6, - 'hip_pitch_right_motor': 7, - 'knee_right_motor': 8, - 'toe_right_motor': 9} - def make(self, controller, model_xml='cassie.xml', dynamics_randomization=True): - self.builder = DiagramBuilder() - self.controller = controller self.simulator = CassieSim(self.default_model_directory + model_xml) if self.visualize: self.cassie_vis = CassieVis(self.simulator) @@ -83,13 +57,18 @@ def make(self, controller, model_xml='cassie.xml', dynamics_randomization=True): self.encoder_noise = 0.01 - self.damping_low = 0.3 - self.damping_high = 5.0 + # self.damping_low = 0.3 + self.damping_low = 0.8 + # self.damping_high = 5.0 + self.damping_high = 2.0 - self.mass_low = 0.5 - self.mass_high = 1.5 + # self.mass_low = 0.5 + self.mass_low = 0.8 + # self.mass_high = 1.5 + self.mass_high = 1.2 - self.fric_low = 0.4 + # self.fric_low = 0.4 + self.fric_low = 0.6 self.fric_high = 1.1 self.speed = 0 @@ -106,8 +85,35 @@ def make(self, controller, model_xml='cassie.xml', dynamics_randomization=True): self.motor_encoder_noise = np.zeros(10) self.joint_encoder_noise = np.zeros(6) + self.cassie_in = cassie_user_in_t() + self.cassie_out = cassie_out_t() + self.cassie_out_lcm = lcmt_cassie_out() + self.action_dim = 10 + self.state_dim = 45 + self.x_init = np.array( + [1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, + -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) + self.prev_cassie_state = None + self.controller = None + self.terminated = False + self.initialized = False + self.actuator_index_map = {'hip_roll_left_motor': 0, + 'hip_yaw_left_motor': 1, + 'hip_pitch_left_motor': 2, + 'knee_left_motor': 3, + 'toe_left_motor': 4, + 'hip_roll_right_motor': 5, + 'hip_yaw_right_motor': 6, + 'hip_pitch_right_motor': 7, + 'knee_right_motor': 8, + 'toe_right_motor': 9} + + def make(self, controller): + self.builder = DiagramBuilder() + self.controller = controller + self.builder.AddSystem(self.controller) - # self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), True) self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), False) self.builder.AddSystem(self.robot_output_sender) @@ -127,98 +133,7 @@ def make(self, controller, model_xml='cassie.xml', dynamics_randomization=True): self.initialized = True def reset(self): - - if self.dynamics_randomization: - damp = self.default_damping - - pelvis_damp_range = [[damp[0], damp[0]], - [damp[1], damp[1]], - [damp[2], damp[2]], - [damp[3], damp[3]], - [damp[4], damp[4]], - [damp[5], damp[5]]] # 0->5 - - hip_damp_range = [[damp[6] * self.damping_low, damp[6] * self.damping_high], - [damp[7] * self.damping_low, damp[7] * self.damping_high], - [damp[8] * self.damping_low, damp[8] * self.damping_high]] # 6->8 and 19->21 - - achilles_damp_range = [[damp[9] * self.damping_low, damp[9] * self.damping_high], - [damp[10] * self.damping_low, damp[10] * self.damping_high], - [damp[11] * self.damping_low, damp[11] * self.damping_high]] # 9->11 and 22->24 - - knee_damp_range = [[damp[12] * self.damping_low, damp[12] * self.damping_high]] # 12 and 25 - shin_damp_range = [[damp[13] * self.damping_low, damp[13] * self.damping_high]] # 13 and 26 - tarsus_damp_range = [[damp[14] * self.damping_low, damp[14] * self.damping_high]] # 14 and 27 - - heel_damp_range = [[damp[15], damp[15]]] # 15 and 28 - fcrank_damp_range = [[damp[16] * self.damping_low, damp[16] * self.damping_high]] # 16 and 29 - prod_damp_range = [[damp[17], damp[17]]] # 17 and 30 - foot_damp_range = [[damp[18] * self.damping_low, damp[18] * self.damping_high]] # 18 and 31 - - side_damp = hip_damp_range + achilles_damp_range + knee_damp_range + shin_damp_range + tarsus_damp_range + heel_damp_range + fcrank_damp_range + prod_damp_range + foot_damp_range - damp_range = pelvis_damp_range + side_damp + side_damp - damp_noise = [np.random.uniform(a, b) for a, b in damp_range] - - m = self.default_mass - pelvis_mass_range = [[self.mass_low * m[1], self.mass_high * m[1]]] # 1 - hip_mass_range = [[self.mass_low * m[2], self.mass_high * m[2]], # 2->4 and 14->16 - [self.mass_low * m[3], self.mass_high * m[3]], - [self.mass_low * m[4], self.mass_high * m[4]]] - - achilles_mass_range = [[self.mass_low * m[5], self.mass_high * m[5]]] # 5 and 17 - knee_mass_range = [[self.mass_low * m[6], self.mass_high * m[6]]] # 6 and 18 - knee_spring_mass_range = [[self.mass_low * m[7], self.mass_high * m[7]]] # 7 and 19 - shin_mass_range = [[self.mass_low * m[8], self.mass_high * m[8]]] # 8 and 20 - tarsus_mass_range = [[self.mass_low * m[9], self.mass_high * m[9]]] # 9 and 21 - heel_spring_mass_range = [[self.mass_low * m[10], self.mass_high * m[10]]] # 10 and 22 - fcrank_mass_range = [[self.mass_low * m[11], self.mass_high * m[11]]] # 11 and 23 - prod_mass_range = [[self.mass_low * m[12], self.mass_high * m[12]]] # 12 and 24 - foot_mass_range = [[self.mass_low * m[13], self.mass_high * m[13]]] # 13 and 25 - - side_mass = hip_mass_range + achilles_mass_range \ - + knee_mass_range + knee_spring_mass_range \ - + shin_mass_range + tarsus_mass_range \ - + heel_spring_mass_range + fcrank_mass_range \ - + prod_mass_range + foot_mass_range - - mass_range = [[0, 0]] + pelvis_mass_range + side_mass + side_mass - mass_noise = [np.random.uniform(a, b) for a, b in mass_range] - - delta = 0.0 - com_noise = [0, 0, 0] + [np.random.uniform(val - delta, val + delta) for val in self.default_ipos[3:]] - - fric_noise = [] - translational = np.random.uniform(self.fric_low, self.fric_high) - torsional = np.random.uniform(1e-4, 5e-4) - rolling = np.random.uniform(1e-4, 2e-4) - for _ in range(int(len(self.default_fric) / 3)): - fric_noise += [translational, torsional, rolling] - - self.simulator.set_dof_damping(np.clip(damp_noise, 0, None)) - self.simulator.set_body_mass(np.clip(mass_noise, 0, None)) - self.simulator.set_body_ipos(com_noise) - self.simulator.set_geom_friction(np.clip(fric_noise, 0, None)) - else: - self.simulator.set_body_mass(self.default_mass) - self.simulator.set_body_ipos(self.default_ipos) - self.simulator.set_dof_damping(self.default_damping) - self.simulator.set_geom_friction(self.default_fric) - - if self.slope_rand: - geom_plane = [np.random.uniform(-self.max_roll_incline, self.max_roll_incline), - np.random.uniform(-self.max_pitch_incline, self.max_pitch_incline), 0] - quat_plane = euler2quat(z=geom_plane[2], y=geom_plane[1], x=geom_plane[0]) - geom_quat = list(quat_plane) + list(self.default_quat[4:]) - self.simulator.set_geom_quat(geom_quat) - else: - self.simulator.set_geom_quat(self.default_quat) - - if self.joint_rand: - self.motor_encoder_noise = np.random.uniform(-self.encoder_noise, self.encoder_noise, size=10) - self.joint_encoder_noise = np.random.uniform(-self.encoder_noise, self.encoder_noise, size=6) - else: - self.motor_encoder_noise = np.zeros(10) - self.joint_encoder_noise = np.zeros(6) + self.randomize_sim_params() q_mujoco, v_mujoco = self.drake_to_mujoco_converter.convert_to_mujoco( reexpress_state_global_to_local_omega(self.x_init)) @@ -227,6 +142,7 @@ def reset(self): mujoco_state.set_qvel(v_mujoco) mujoco_state.set_time(self.start_time) self.simulator.set_state(mujoco_state) + self.drake_sim.get_mutable_context().SetTime(self.start_time) u = np.zeros(10) self.drake_sim.Initialize() @@ -240,9 +156,11 @@ def reset(self): return def advance_to(self, time): + cumulative_reward = 0 while self.current_time < time and not self.terminated: - self.step() - return + _, reward = self.step() + cumulative_reward += reward + return cumulative_reward def check_termination(self): return self.cassie_state.get_fb_positions()[2] < 0.4 @@ -256,7 +174,7 @@ def step(self, action=np.zeros(18)): else: timestep = self.gym_dt next_timestep = self.drake_sim.get_context().get_time() + timestep - # action[2] = 0.75 + self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) self.radio_input_port.FixValue(self.controller_context, action) @@ -329,11 +247,7 @@ def pack_cassie_out(self, cassie_out): self.copy_leg(cassie_out_lcm.leftLeg, cassie_out.leftLeg) self.copy_leg(cassie_out_lcm.rightLeg, cassie_out.rightLeg) - - # import pdb; pdb.set_trace() - - # copy_vector_int16(cassie_out->messages, - # message->messages, 4); + return cassie_out_lcm def copy_leg(self, cassie_leg_out_lcm, cassie_leg_out): self.copy_elmo(cassie_leg_out_lcm.hipRollDrive, cassie_leg_out.hipRollDrive) @@ -361,8 +275,102 @@ def copy_elmo(self, elmo_out_lcm, elmo_out): elmo_out_lcm.torqueLimit = elmo_out.torqueLimit elmo_out_lcm.gearRatio = elmo_out.gearRatio - def free_sim(self): - del self.cassie_env + def randomize_sim_params(self): + if self.dynamics_randomization: + damp = self.default_damping + + pelvis_damp_range = [[damp[0], damp[0]], + [damp[1], damp[1]], + [damp[2], damp[2]], + [damp[3], damp[3]], + [damp[4], damp[4]], + [damp[5], damp[5]]] # 0->5 + + hip_damp_range = [[damp[6] * self.damping_low, damp[6] * self.damping_high], + [damp[7] * self.damping_low, damp[7] * self.damping_high], + [damp[8] * self.damping_low, damp[8] * self.damping_high]] # 6->8 and 19->21 + + achilles_damp_range = [[damp[9] * self.damping_low, damp[9] * self.damping_high], + [damp[10] * self.damping_low, damp[10] * self.damping_high], + [damp[11] * self.damping_low, damp[11] * self.damping_high]] # 9->11 and 22->24 + + knee_damp_range = [[damp[12] * self.damping_low, damp[12] * self.damping_high]] # 12 and 25 + shin_damp_range = [[damp[13] * self.damping_low, damp[13] * self.damping_high]] # 13 and 26 + tarsus_damp_range = [[damp[14] * self.damping_low, damp[14] * self.damping_high]] # 14 and 27 + + heel_damp_range = [[damp[15], damp[15]]] # 15 and 28 + fcrank_damp_range = [[damp[16] * self.damping_low, damp[16] * self.damping_high]] # 16 and 29 + prod_damp_range = [[damp[17], damp[17]]] # 17 and 30 + foot_damp_range = [[damp[18] * self.damping_low, damp[18] * self.damping_high]] # 18 and 31 + + side_damp = hip_damp_range + achilles_damp_range + knee_damp_range + shin_damp_range + tarsus_damp_range + heel_damp_range + fcrank_damp_range + prod_damp_range + foot_damp_range + damp_range = pelvis_damp_range + side_damp + side_damp + damp_noise = [np.random.uniform(a, b) for a, b in damp_range] + + m = self.default_mass + pelvis_mass_range = [[self.mass_low * m[1], self.mass_high * m[1]]] # 1 + hip_mass_range = [[self.mass_low * m[2], self.mass_high * m[2]], # 2->4 and 14->16 + [self.mass_low * m[3], self.mass_high * m[3]], + [self.mass_low * m[4], self.mass_high * m[4]]] + + achilles_mass_range = [[self.mass_low * m[5], self.mass_high * m[5]]] # 5 and 17 + knee_mass_range = [[self.mass_low * m[6], self.mass_high * m[6]]] # 6 and 18 + knee_spring_mass_range = [[self.mass_low * m[7], self.mass_high * m[7]]] # 7 and 19 + shin_mass_range = [[self.mass_low * m[8], self.mass_high * m[8]]] # 8 and 20 + tarsus_mass_range = [[self.mass_low * m[9], self.mass_high * m[9]]] # 9 and 21 + heel_spring_mass_range = [[self.mass_low * m[10], self.mass_high * m[10]]] # 10 and 22 + fcrank_mass_range = [[self.mass_low * m[11], self.mass_high * m[11]]] # 11 and 23 + prod_mass_range = [[self.mass_low * m[12], self.mass_high * m[12]]] # 12 and 24 + foot_mass_range = [[self.mass_low * m[13], self.mass_high * m[13]]] # 13 and 25 + + side_mass = hip_mass_range + achilles_mass_range \ + + knee_mass_range + knee_spring_mass_range \ + + shin_mass_range + tarsus_mass_range \ + + heel_spring_mass_range + fcrank_mass_range \ + + prod_mass_range + foot_mass_range + + mass_range = [[0, 0]] + pelvis_mass_range + side_mass + side_mass + mass_noise = [np.random.uniform(a, b) for a, b in mass_range] + + delta = 0.0 + com_noise = [0, 0, 0] + [np.random.uniform(val - delta, val + delta) for val in self.default_ipos[3:]] + + fric_noise = [] + translational = np.random.uniform(self.fric_low, self.fric_high) + torsional = np.random.uniform(1e-4, 5e-4) + rolling = np.random.uniform(1e-4, 2e-4) + for _ in range(int(len(self.default_fric) / 3)): + fric_noise += [translational, torsional, rolling] + + self.simulator.set_dof_damping(np.clip(damp_noise, 0, None)) + self.simulator.set_body_mass(np.clip(mass_noise, 0, None)) + self.simulator.set_body_ipos(com_noise) + self.simulator.set_geom_friction(np.clip(fric_noise, 0, None)) + else: + self.simulator.set_body_mass(self.default_mass) + self.simulator.set_body_ipos(self.default_ipos) + self.simulator.set_dof_damping(self.default_damping) + self.simulator.set_geom_friction(self.default_fric) + + if self.slope_rand: + geom_plane = [np.random.uniform(-self.max_roll_incline, self.max_roll_incline), + np.random.uniform(-self.max_pitch_incline, self.max_pitch_incline), 0] + quat_plane = euler2quat(z=geom_plane[2], y=geom_plane[1], x=geom_plane[0]) + geom_quat = list(quat_plane) + list(self.default_quat[4:]) + self.simulator.set_geom_quat(geom_quat) + else: + self.simulator.set_geom_quat(self.default_quat) + + if self.joint_rand: + self.motor_encoder_noise = np.random.uniform(-self.encoder_noise, self.encoder_noise, size=10) + self.joint_encoder_noise = np.random.uniform(-self.encoder_noise, self.encoder_noise, size=6) + else: + self.motor_encoder_noise = np.zeros(10) + self.joint_encoder_noise = np.zeros(6) + + +def free_sim(self): + del self.cassie_env def euler2quat(z=0, y=0, x=0): diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 2216e733e3..c027a2cb0f 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -8,7 +8,6 @@ from pydairlib.cassie.gym_envs.drake_cassie_gym import * from pydairlib.cassie.gym_envs.mujoco_cassie_gym import * -# from cassie_utils import * from pydairlib.cassie.controllers import OSCRunningControllerFactory from pydairlib.cassie.controllers import OSCWalkingControllerFactory from pydairlib.cassie.simulators import CassieSimDiagram @@ -42,15 +41,17 @@ def __init__(self, budget, reward_function, visualize=False): self.loss_over_time = [] self.default_osc_gains = { + 'w_soft_constraint': 100, + 'w_input_reg': 0.001, 'mu': 0.6, 'w_hip_yaw': 2.5, 'hip_yaw_kp': 40, # 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), - # 'PelvisRotKd': np.array([10, 5, 1]), - 'SwingFootKp': np.array([125, 80, 50]), - 'SwingFootKd': np.array([5, 5, 1]), + 'PelvisRotKd': np.array([10, 5, 1]), + # 'SwingFootKp': np.array([125, 80, 50]), + # 'SwingFootKd': np.array([5, 5, 1]), # 'FootstepKd': np.array([0.2, 0.45, 0]), 'center_line_offset': 0.03, # 'rest_length': 0.85, @@ -77,6 +78,14 @@ def write_params(self, params): new_gains[key] = params[key] yaml_dump(new_gains, filename=self.osc_running_gains_filename) + def get_batch_loss(self, params): + batch_size = 5 + batch_reward = 0 + for i in range(batch_size): + batch_reward += self.get_single_loss(params) + self.loss_over_time.append(batch_reward) + return -batch_reward + def get_single_loss(self, params): self.write_params(params) if np.random.random() < 0.0: @@ -96,21 +105,22 @@ def get_single_loss(self, params): while gym_env.current_time < 7.5 and not gym_env.terminated: state, reward = gym_env.step(np.zeros(18)) cumulative_reward += reward - self.loss_over_time.append(cumulative_reward) # print(-cumulative_reward) return -cumulative_reward def learn_gains(self, batch=True): self.default_params = ng.p.Dict( + w_soft_constraint=ng.p.Log(lower=1.0, upper=1000.0), + w_input_reg=ng.p.Log(lower=1e-5, upper=1e-1), mu=ng.p.Scalar(lower=0.4, upper=1.0), w_hip_yaw=ng.p.Scalar(lower=0, upper=10), hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), - # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), - SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + # SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), + # SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), @@ -120,11 +130,13 @@ def learn_gains(self, batch=True): ) self.loss_over_time = [] self.default_params.value = self.default_osc_gains - optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) + # optimizer = ng.optimizers.NGOpt(parametrization=self.default_params, budget=self.budget) + optimizer = ng.optimizers.CMandAS3(parametrization=self.default_params, budget=self.budget) optimizer.register_callback("tell", ng.callbacks.ProgressBar()) # with futures.ThreadPoolExecutor(max_workers=optimizer.num_workers) as executor: # recommendation = optimizer.minimize(square, executor=executor, batch_mode=False) - params = optimizer.minimize(self.get_single_loss) + # params = optimizer.minimize(self.get_single_loss) + params = optimizer.minimize(self.get_batch_loss) loss_samples = np.array(self.loss_over_time) np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) self.save_params(self.drake_params_folder, params, budget) @@ -132,15 +144,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 2000 + budget = 400 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) optimizer.learn_gains() - # optimal_params = optimizer.load_params('2022_03_25_17_1000', optimizer.drake_params_folder).value + # optimal_params = optimizer.load_params('2022_03_28_10_2000', optimizer.drake_params_folder).value # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') # plt.plot(reward_over_time) # plt.show() diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 51ef20a5f0..1b353d3bae 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,42 +1,41 @@ -FootstepKd: [0.2, 0, 0, 0, 0.45, 0, 0, 0, 0] +FootstepKd: [0.2, 0, 0, 0, 0.6, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] +PelvisRotKd: [8.007578412812107, 0.0, 0.0, 0.0, 4.913462935995132, 0.0, 0.0, 0.0, + 0.7440873948839031] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [7.470159439828845, 0.0, 0.0, 0.0, 12.580856772920194, 0.0, 0.0, 0.0, - 2.082002568974916] -SwingFootKp: [114.16480444536955, 0.0, 0.0, 0.0, 100.03932909749986, 0.0, 0.0, 0.0, - 54.79286331701048] +SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] +SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 50.0] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.03977871878316904 -flight_duration: 0.07977287590217821 -footstep_offset: -0.06099934134060533 +center_line_offset: 0.03991021548115632 +flight_duration: 0.09540234606274277 +footstep_offset: -0.06664347604624206 hip_yaw_kd: 1 -hip_yaw_kp: 50.15472945993452 +hip_yaw_kp: 46.109776573830196 impact_threshold: 0.025 -mu: 0.7552292632842741 +mu: 0.7277522312143554 relative_feet: true relative_pelvis: true rest_length: 0.85 -stance_duration: 0.2976513438348498 +stance_duration: 0.27674339686830957 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 vel_scale_trans_sagital: 0.2 w_accel: 1.0e-05 -w_hip_yaw: 1.9711914198221558 +w_hip_yaw: 3.557575837752117 w_input: 0.0 -w_input_reg: 0.001 -w_soft_constraint: 100 +w_input_reg: 0.0005213211013769204 +w_soft_constraint: 185.3467755476298 w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c8c8768482..3681f6e190 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -43,7 +43,7 @@ footstep_offset: -0.05 center_line_offset: 0.03 FootstepKd: [ 0.2, 0, 0, - 0, 0.45, 0, + 0, 0.6, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, From c6af3f5f4c5494438e101e74f8af6c861a76dcf3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 28 Mar 2022 13:39:23 -0400 Subject: [PATCH 172/758] updating running controller --- examples/Cassie/osc_run/osc_running_gains.h | 3 ++ .../Cassie/osc_run/osc_running_gains.yaml | 25 ++++++++------- examples/Cassie/run_osc_running_controller.cc | 31 +++++++------------ 3 files changed, 28 insertions(+), 31 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index b10a41da23..edf6f738ad 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -30,6 +30,8 @@ struct OSCRunningGains : OSCGains { double center_line_offset; double footstep_offset; + std::vector ekf_filter_tau; + // swing foot tracking std::vector SwingFootW; std::vector SwingFootKp; @@ -90,6 +92,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(flight_duration)); a->Visit(DRAKE_NVP(center_line_offset)); a->Visit(DRAKE_NVP(footstep_offset)); + a->Visit(DRAKE_NVP(ekf_filter_tau)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 71ed932029..a2daaae9a5 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,10 +40,11 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.075 +center_line_offset: 0.03 +ekf_filter_tau: [0.05, 0.1, 0.01] FootstepKd: [ 0.2, 0, 0, - 0, 0.45, 0, + 0, 0.6, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, @@ -62,13 +63,13 @@ PelvisRotW: 0, 2.5, 0, 0, 0, 0.1] PelvisRotKp: - [40, 0, 0, - 0, 20, 0, - 0, 0, 1] + [50., 0, 0, + 0, 100., 0, + 0, 0, 1.] PelvisRotKd: - [7.5, 0, 0, - 0, 2.5, 0, - 0, 0, 0] + [10., 0, 0, + 0, 5., 0, + 0, 0, 0.] SwingFootW: [10, 0, 0, 0, 10, 0, @@ -78,9 +79,9 @@ SwingFootKp: 0, 80, 0, 0, 0, 50] SwingFootKd: - [5, 0, 0, - 0, 1.5, 0, - 0, 0, 1] + [5., 0, 0, + 0, 5., 0, + 0, 0, 1.] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, @@ -92,5 +93,5 @@ LiftoffSwingFootKp: LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 2] + 0, 0, 0] diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 0ab9f2f181..9cb516f0f4 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -88,10 +88,6 @@ DEFINE_string(osqp_settings, DEFINE_string( channel_cassie_out, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); -DEFINE_double( - fsm_time_offset, 0.0, - "Time (s) in the fsm to move from the stance phase to the flight phase"); -DEFINE_double(qp_time_limit, 0.0, "Time limit (s) for the OSC QP"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -142,9 +138,9 @@ int DoMain(int argc, char* argv[]) { FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); -// solvers::OSQPSettingsYaml osqp_settings = -// drake::yaml::LoadYamlFile( -// FindResourceOrThrow(FLAGS_osqp_settings)); + // solvers::OSQPSettingsYaml osqp_settings = + // drake::yaml::LoadYamlFile( + // FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -181,8 +177,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true, false, - FLAGS_qp_time_limit); + plant, plant, plant_context.get(), plant_context.get(), true, false); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -192,15 +187,14 @@ int DoMain(int argc, char* argv[]) { auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - std::vector tau = {.05, .05, .01}; - auto ekf_filter = - builder.AddSystem(plant, tau); + auto ekf_filter = builder.AddSystem( + plant, osc_gains.ekf_filter_tau); /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - // osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); // osc->SetLambdaContactRegularizationWeight(1e-4 * // gains.W_lambda_c_regularization); @@ -354,9 +348,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data.AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); + "pelvis"); right_hip_yz_tracking_data.AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); + "pelvis"); RelativeTranslationTrackingData left_foot_rel_tracking_data( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -386,8 +380,8 @@ int DoMain(int argc, char* argv[]) { left_foot_rel_tracking_data.SetImpactInvariantProjection(true); right_foot_rel_tracking_data.SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); - // right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data.SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data.SetImpactInvariantProjection(true); // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); @@ -466,8 +460,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(&left_hip_yaw_tracking_data, VectorXd::Zero(1)); osc->AddConstTrackingData(&right_hip_yaw_tracking_data, VectorXd::Zero(1)); - osc->SetOsqpSolverOptionsFromYaml( - FLAGS_osqp_settings); + osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem osc->Build(); std::cout << "Built OSC" << std::endl; From 2f54e3e613aafcdcc8b5f573f99638370e657dbb Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 29 Mar 2022 10:05:34 -0400 Subject: [PATCH 173/758] learned new running gains --- bindings/pydairlib/cassie/learn_osc_gains.py | 28 +++--- examples/Cassie/BUILD.bazel | 1 + .../osc_running_controller_diagram.cc | 4 +- examples/Cassie/osc/BUILD.bazel | 9 ++ examples/Cassie/osc/osc_standing_gains.h | 36 +++++++ examples/Cassie/osc/osc_standing_gains.yaml | 17 +++- .../Cassie/osc_run/foot_traj_generator.cc | 4 +- examples/Cassie/osc_run/foot_traj_generator.h | 4 +- .../osc_run/learned_osc_running_gains.yaml | 34 ++++--- examples/Cassie/osc_run/osc_running_gains.h | 23 +---- .../Cassie/osc_run/osc_running_gains.yaml | 4 +- examples/Cassie/run_osc_running_controller.cc | 6 +- .../Cassie/run_osc_standing_controller.cc | 96 ++++++------------- .../osc/trans_space_tracking_data.cc | 6 ++ 14 files changed, 150 insertions(+), 122 deletions(-) create mode 100644 examples/Cassie/osc/osc_standing_gains.h diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index c027a2cb0f..160a5da8e8 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -50,9 +50,9 @@ def __init__(self, budget, reward_function, visualize=False): # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), 'PelvisRotKd': np.array([10, 5, 1]), - # 'SwingFootKp': np.array([125, 80, 50]), - # 'SwingFootKd': np.array([5, 5, 1]), - # 'FootstepKd': np.array([0.2, 0.45, 0]), + 'SwingFootKp': np.array([125, 80, 50]), + 'SwingFootKd': np.array([5, 5, 1]), + 'FootstepKd': np.array([0.2, 0.45, 0]), 'center_line_offset': 0.03, # 'rest_length': 0.85, 'footstep_offset': -0.05, @@ -84,7 +84,7 @@ def get_batch_loss(self, params): for i in range(batch_size): batch_reward += self.get_single_loss(params) self.loss_over_time.append(batch_reward) - return -batch_reward + return batch_reward def get_single_loss(self, params): self.write_params(params) @@ -119,9 +119,9 @@ def learn_gains(self, batch=True): # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - # SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), - # SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), + SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), + SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), @@ -144,15 +144,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 400 + budget = 2000 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - optimizer.learn_gains() + # optimizer.learn_gains() - # optimal_params = optimizer.load_params('2022_03_28_10_2000', optimizer.drake_params_folder).value - # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') - # plt.plot(reward_over_time) - # plt.show() + optimal_params = optimizer.load_params('2022_03_28_18_2000', optimizer.drake_params_folder).value + optimizer.write_params(optimal_params) + reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') + plt.plot(reward_over_time) + plt.show() diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 52519f00fc..cd5f7d87eb 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -442,6 +442,7 @@ cc_binary( "//multibody/kinematic", "//systems:robot_lcm_systems", "//systems/controllers/osc:operational_space_control", + "//systems/controllers/osc:osc_gains", "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index d390679dd9..f0fcc65f17 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -232,10 +232,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( osc_running_gains.rest_length, osc_running_gains.center_line_offset, - osc_running_gains.footstep_offset); + osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( osc_running_gains.rest_length, osc_running_gains.center_line_offset, - osc_running_gains.footstep_offset); + osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_running_gains.K_p_pelvis, diff --git a/examples/Cassie/osc/BUILD.bazel b/examples/Cassie/osc/BUILD.bazel index c949bc5051..88f67b839f 100644 --- a/examples/Cassie/osc/BUILD.bazel +++ b/examples/Cassie/osc/BUILD.bazel @@ -8,6 +8,7 @@ cc_library( "//examples/Cassie/osc:heading_traj_generator", "//examples/Cassie/osc:high_level_command", "//examples/Cassie/osc:osc_walking_gains", + "//examples/Cassie/osc:osc_standing_gains", "//examples/Cassie/osc:standing_com_traj", "//examples/Cassie/osc:standing_pelvis_traj", "//examples/Cassie/osc:swing_toe_traj", @@ -101,3 +102,11 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "osc_standing_gains", + hdrs = ["osc_standing_gains.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h new file mode 100644 index 0000000000..af5a684553 --- /dev/null +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -0,0 +1,36 @@ +#pragma once + +#include "systems/controllers/osc/osc_gains.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +struct OSCStandingGains : OSCGains { + int rows; + int cols; + double HipYawKp; + double HipYawKd; + double HipYawW; + std::vector CoMKp; + std::vector CoMKd; + std::vector PelvisRotKp; + std::vector PelvisRotKd; + std::vector CoMW; + std::vector PelvisW; + + template + void Serialize(Archive* a) { + OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(rows)); + a->Visit(DRAKE_NVP(cols)); + a->Visit(DRAKE_NVP(CoMKp)); + a->Visit(DRAKE_NVP(CoMKd)); + a->Visit(DRAKE_NVP(PelvisRotKp)); + a->Visit(DRAKE_NVP(PelvisRotKd)); + a->Visit(DRAKE_NVP(HipYawKp)); + a->Visit(DRAKE_NVP(HipYawKd)); + a->Visit(DRAKE_NVP(CoMW)); + a->Visit(DRAKE_NVP(PelvisW)); + a->Visit(DRAKE_NVP(HipYawW)); + } +}; diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 8d63504d96..8a1272b025 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -10,9 +10,22 @@ rows: 3 cols: 3 w_input: 0 -#w_accel: 0.00001 w_accel: 0.00000001 -w_soft_constraint: 0 +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.001] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] +w_soft_constraint: 100 +w_input_reg: 0.001 +impact_threshold: 0.025 +mu: 0.6 HipYawKp: 10 HipYawKd: 1 HipYawW: 0 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 047b56d04f..4231704a37 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -191,9 +191,9 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[0] = start_pos; Y[0](2) = -rest_length_; Y[1] = start_pos + 0.85 * footstep_correction; - Y[1](2) = -rest_length_ + 0.02; + Y[1](2) = -rest_length_ + mid_foot_height_; Y[2] = footstep_correction; - Y[2](2) = -rest_length_; + Y[2](2) = -rest_length_ + mid_foot_height_ / 2; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 2939ca5931..ebccdf4f57 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -30,10 +30,11 @@ class FootTrajGenerator : public drake::systems::LeafSystem { void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; void SetFootPlacementOffsets(double rest_length, double center_line_offset, - double footstep_offset) { + double footstep_offset, double mid_foot_height) { rest_length_ = rest_length; center_line_offset_ = center_line_offset; footstep_offset_ = footstep_offset; + mid_foot_height_ = mid_foot_height; } private: @@ -59,6 +60,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { double rest_length_; double center_line_offset_; double footstep_offset_; + double mid_foot_height_; // Raibert Footstep Gains Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(3, 3); diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 1b353d3bae..1862e262e4 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,41 +1,47 @@ -FootstepKd: [0.2, 0, 0, 0, 0.6, 0, 0, 0, 0] +FootstepKd: [0.20630578931908952, 0.0, 0.0, 0.0, 0.5022846733099167, 0.0, 0.0, 0.0, + 0.014419706168051383] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [8.007578412812107, 0.0, 0.0, 0.0, 4.913462935995132, 0.0, 0.0, 0.0, - 0.7440873948839031] +PelvisRotKd: [14.754198175926723, 0.0, 0.0, 0.0, 10.15048844191982, 0.0, 0.0, 0.0, + 3.9038583836913308] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] -SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 50.0] +SwingFootKd: [5.8013545212157736, 0.0, 0.0, 0.0, 8.37349939782334, 0.0, 0.0, 0.0, + 4.294753134633737] +SwingFootKp: [111.90374548402804, 0.0, 0.0, 0.0, 93.51462206597392, 0.0, 0.0, 0.0, + 75.82806014571253] SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.03991021548115632 -flight_duration: 0.09540234606274277 -footstep_offset: -0.06664347604624206 +#center_line_offset: 0.03036161874399593 +center_line_offset: 0.04036161874399593 +ekf_filter_tau: [0.05, 0.1, 0.01] +flight_duration: 0.053967347248977025 +footstep_offset: -0.044971023856448855 hip_yaw_kd: 1 -hip_yaw_kp: 46.109776573830196 +hip_yaw_kp: 48.17643439890748 impact_threshold: 0.025 -mu: 0.7277522312143554 +mid_foot_height: 0.05 +mu: 0.6097124570750189 relative_feet: true relative_pelvis: true rest_length: 0.85 -stance_duration: 0.27674339686830957 +stance_duration: 0.2949526396548052 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 vel_scale_trans_sagital: 0.2 w_accel: 1.0e-05 -w_hip_yaw: 3.557575837752117 +w_hip_yaw: 2.0187541880806643 w_input: 0.0 -w_input_reg: 0.0005213211013769204 -w_soft_constraint: 185.3467755476298 +w_input_reg: 0.004802653072422612 +w_soft_constraint: 111.82117439652899 w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 8e31363f34..2190272219 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -31,6 +31,9 @@ struct OSCRunningGains : OSCGains { double center_line_offset; double footstep_offset; + double mid_foot_height; + + std::vector ekf_filter_tau; // swing foot tracking std::vector SwingFootW; @@ -70,12 +73,6 @@ struct OSCRunningGains : OSCGains { MatrixXd W_hip_yaw; MatrixXd K_p_hip_yaw; MatrixXd K_d_hip_yaw; -// MatrixXd W_hip_pitch; -// MatrixXd K_p_hip_pitch; -// MatrixXd K_d_hip_pitch; -// MatrixXd W_hip_roll; -// MatrixXd K_p_hip_roll; -// MatrixXd K_d_hip_roll; template void Serialize(Archive* a) { @@ -92,6 +89,8 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(flight_duration)); a->Visit(DRAKE_NVP(center_line_offset)); a->Visit(DRAKE_NVP(footstep_offset)); + a->Visit(DRAKE_NVP(mid_foot_height)); + a->Visit(DRAKE_NVP(ekf_filter_tau)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); @@ -112,12 +111,6 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(w_hip_yaw)); a->Visit(DRAKE_NVP(hip_yaw_kp)); a->Visit(DRAKE_NVP(hip_yaw_kd)); -// a->Visit(DRAKE_NVP(w_hip_pitch)); -// a->Visit(DRAKE_NVP(hip_pitch_kp)); -// a->Visit(DRAKE_NVP(hip_pitch_kd)); -// a->Visit(DRAKE_NVP(w_hip_roll)); -// a->Visit(DRAKE_NVP(hip_roll_kp)); -// a->Visit(DRAKE_NVP(hip_roll_kd)); // High level command gains (with radio) a->Visit(DRAKE_NVP(vel_scale_rot)); a->Visit(DRAKE_NVP(vel_scale_trans_sagital)); @@ -169,11 +162,5 @@ struct OSCRunningGains : OSCGains { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); -// W_hip_pitch = this->w_hip_pitch * MatrixXd::Identity(1, 1); -// K_p_hip_pitch = this->hip_pitch_kp * MatrixXd::Identity(1, 1); -// K_d_hip_pitch = this->hip_pitch_kd * MatrixXd::Identity(1, 1); -// W_hip_roll = this->w_hip_roll * MatrixXd::Identity(1, 1); -// K_p_hip_roll = this->hip_roll_kp * MatrixXd::Identity(1, 1); -// K_d_hip_roll = this->hip_roll_kd * MatrixXd::Identity(1, 1); } }; \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 3681f6e190..71a30e69bf 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -18,6 +18,7 @@ w_input_reg: 0.001 impact_threshold: 0.025 relative_feet: true relative_pelvis: true +ekf_filter_tau: [0.05, 0.1, 0.01] # High level command gains (with radio) vel_scale_rot: -0.5 @@ -40,7 +41,8 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.03 +center_line_offset: 0.05 +mid_foot_height: 0.05 FootstepKd: [ 0.2, 0, 0, 0, 0.6, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 2c6884a939..b9be4035fc 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -287,10 +287,12 @@ int DoMain(int argc, char* argv[]) { r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, osc_gains.center_line_offset, - osc_gains.footstep_offset); + osc_gains.footstep_offset, + osc_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, osc_gains.center_line_offset, - osc_gains.footstep_offset); + osc_gains.footstep_offset, + osc_gains.mid_foot_height); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 9ab3d6d572..e8b619d5a5 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -5,6 +5,7 @@ #include "dairlib/lcmt_target_standing_height.hpp" #include "examples/Cassie/cassie_utils.h" #include "examples/Cassie/osc/standing_com_traj.h" +#include "examples/Cassie/osc/osc_standing_gains.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" @@ -12,6 +13,7 @@ #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/options_tracking_data.h" +#include "systems/controllers/osc/osc_gains.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" @@ -58,8 +60,8 @@ DEFINE_bool(print_osc, false, "whether to print the osc debug message or not"); DEFINE_double(cost_weight_multiplier, 1.0, "A cosntant times with cost weight of OSC traj tracking"); DEFINE_double(height, .8, "The initial COM height (m)"); -DEFINE_string(gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", - "Filepath containing gains"); +DEFINE_string(osc_gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", + "Filepath containing osc_gains"); DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", "Filepath containing qp settings"); DEFINE_bool(use_radio, false, "use the radio to set height or not"); @@ -71,41 +73,6 @@ DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); // Maybe we need to update the lcm driven loop to clear the queue of lcm message // if it's more than one message? -struct OSCStandingGains { - int rows; - int cols; - double w_input; - double w_accel; - double w_soft_constraint; - double HipYawKp; - double HipYawKd; - double HipYawW; - std::vector CoMKp; - std::vector CoMKd; - std::vector PelvisRotKp; - std::vector PelvisRotKd; - std::vector CoMW; - std::vector PelvisW; - - template - void Serialize(Archive* a) { - a->Visit(DRAKE_NVP(rows)); - a->Visit(DRAKE_NVP(cols)); - a->Visit(DRAKE_NVP(w_input)); - a->Visit(DRAKE_NVP(w_accel)); - a->Visit(DRAKE_NVP(w_soft_constraint)); - a->Visit(DRAKE_NVP(CoMKp)); - a->Visit(DRAKE_NVP(CoMKd)); - a->Visit(DRAKE_NVP(PelvisRotKp)); - a->Visit(DRAKE_NVP(PelvisRotKd)); - a->Visit(DRAKE_NVP(HipYawKp)); - a->Visit(DRAKE_NVP(HipYawKd)); - a->Visit(DRAKE_NVP(CoMW)); - a->Visit(DRAKE_NVP(PelvisW)); - a->Visit(DRAKE_NVP(HipYawW)); - } -}; - int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -137,39 +104,36 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - auto gains = - drake::yaml::LoadYamlFile(FLAGS_gains_filename); +// auto osc_gains = +// drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); + drake::yaml::YamlReadArchive::Options yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osc_gains_filename), {}, {}, yaml_options); + OSCStandingGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osc_gains_filename)); MatrixXd K_p_com = Eigen::Map< Eigen::Matrix>( - gains.CoMKp.data(), gains.rows, gains.cols); + osc_gains.CoMKp.data(), osc_gains.rows, osc_gains.cols); MatrixXd K_d_com = Eigen::Map< Eigen::Matrix>( - gains.CoMKd.data(), gains.rows, gains.cols); + osc_gains.CoMKd.data(), osc_gains.rows, osc_gains.cols); MatrixXd K_p_pelvis = Eigen::Map< Eigen::Matrix>( - gains.PelvisRotKp.data(), gains.rows, gains.cols); + osc_gains.PelvisRotKp.data(), osc_gains.rows, osc_gains.cols); MatrixXd K_d_pelvis = Eigen::Map< Eigen::Matrix>( - gains.PelvisRotKd.data(), gains.rows, gains.cols); - MatrixXd K_p_hip_yaw = gains.HipYawKp * MatrixXd::Identity(1, 1); - MatrixXd K_d_hip_yaw = gains.HipYawKd * MatrixXd::Identity(1, 1); + osc_gains.PelvisRotKd.data(), osc_gains.rows, osc_gains.cols); + MatrixXd K_p_hip_yaw = osc_gains.HipYawKp * MatrixXd::Identity(1, 1); + MatrixXd K_d_hip_yaw = osc_gains.HipYawKd * MatrixXd::Identity(1, 1); MatrixXd W_com = Eigen::Map< Eigen::Matrix>( - gains.CoMW.data(), gains.rows, gains.cols); + osc_gains.CoMW.data(), osc_gains.rows, osc_gains.cols); MatrixXd W_pelvis = Eigen::Map< Eigen::Matrix>( - gains.PelvisW.data(), gains.rows, gains.cols); - MatrixXd W_hip_yaw = gains.HipYawW * MatrixXd::Identity(1, 1); - std::cout << "w input (not used): \n" << gains.w_input << std::endl; - std::cout << "w accel: \n" << gains.w_accel << std::endl; - std::cout << "w soft constraint: \n" << gains.w_soft_constraint << std::endl; - std::cout << "COM Kp: \n" << K_p_com << std::endl; - std::cout << "COM Kd: \n" << K_d_com << std::endl; - std::cout << "Pelvis Rot Kp: \n" << K_p_pelvis << std::endl; - std::cout << "Pelvis Rot Kd: \n" << K_d_pelvis << std::endl; - std::cout << "COM W: \n" << W_com << std::endl; - std::cout << "Pelvis W: \n" << W_pelvis << std::endl; + osc_gains.PelvisW.data(), osc_gains.rows, osc_gains.cols); + MatrixXd W_hip_yaw = osc_gains.HipYawW * MatrixXd::Identity(1, 1); // Create Lcm subsriber for lcmt_target_standing_height auto target_height_receiver = builder.AddSystem( @@ -233,14 +197,9 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); osc->AddKinematicConstraint(&evaluators); - // Soft constraint - // We don't want w_contact_relax to be too big, cause we want tracking - // error to be important - double w_contact_relax = gains.w_soft_constraint; - osc->SetSoftConstraintWeight(w_contact_relax); + // Friction coefficient - double mu = 0.8; - osc->SetContactFriction(mu); + osc->SetContactFriction(gains.mu); // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( plant_wo_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), @@ -260,8 +219,13 @@ int DoMain(int argc, char* argv[]) { osc->AddContactPoint(&right_heel_evaluator); // Cost int n_v = plant_wo_springs.num_velocities(); - MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); - osc->SetAccelerationCostWeights(Q_accel); + + osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); + osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); +// osc->SetLambdaHolonomicRegularizationWeight(1e-5 * +// gains.W_lambda_h_regularization); + // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing // ComTrackingData center_of_mass_traj("com_traj", K_p_com, K_d_com, diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index a16599db42..3859d5df01 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -62,6 +62,12 @@ void TransTaskSpaceTrackingData::UpdateJ( context_wo_spr, JacobianWrtVariable::kV, *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); + if(fsm_state_ < 2){ + J_(2, 8) = 0; + J_(2, 16) = 0; + J_(2, 6) = 0; + J_(2, 14) = 0; + } if(J_.hasNaN()){ std::cout << "Jacobian has NaNs" << std::endl; } From 6954477a8b1e8e539d0ddba9eb93aea5525eac7a Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 30 Mar 2022 12:25:33 -0400 Subject: [PATCH 174/758] learning weights and other parameters --- .../pydairlib/analysis/log_plotter_cassie.py | 9 ++- .../plot_configs/cassie_running_plot.yaml | 14 ++-- .../cassie/gym_envs/cassie_gym_test.py | 29 ++++---- .../cassie/gym_envs/mujoco_cassie_gym.py | 5 +- .../cassie/gym_envs/reward_osudrl.py | 2 +- bindings/pydairlib/cassie/learn_osc_gains.py | 69 +++++++++++-------- examples/Cassie/cassie_lcm_driven_loop.h | 7 +- examples/Cassie/integration_test.pmd | 12 ++-- .../Cassie/osc_run/foot_traj_generator.cc | 3 +- .../osc_run/learned_osc_running_gains.yaml | 52 +++++++------- .../Cassie/osc_run/osc_running_gains.yaml | 6 +- .../osc/trans_space_tracking_data.cc | 6 -- 12 files changed, 114 insertions(+), 100 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index ff5880877e..2eab85d3d4 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -73,8 +73,10 @@ def main(): t_x_slice) # Plot specific velocities if plot_config.vel_names: - mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, + plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, t_x_slice, vel_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + ''' Plot Efforts ''' if plot_config.plot_measured_efforts: @@ -94,8 +96,9 @@ def main(): for traj_name, config in plot_config.tracking_datas_to_plot.items(): for deriv in config['derivs']: for dim in config['dims']: - mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, + plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) ''' Plot Foot Positions ''' if plot_config.foot_positions_to_plot: @@ -108,7 +111,7 @@ def main(): dims['toe_' + pos] = plot_config.foot_xyz_to_plot[pos] pts['toe_' + pos] = pts_map[plot_config.pt_on_foot_to_plot] - mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, + plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, foot_frames, pts, dims) if plot_config.plot_qp_solve_time: diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 84eeb2d3e1..c9cee1241a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -16,8 +16,8 @@ plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true -special_positions_to_plot: ['base_y'] -special_velocities_to_plot: ['base_vy'] +special_positions_to_plot: [] +special_velocities_to_plot: ['base_vx', 'base_vy'] special_efforts_to_plot: [] # Foot position plots @@ -28,15 +28,15 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_qp_solve_time: true -plot_tracking_costs: true +plot_tracking_costs: false tracking_datas_to_plot: pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} -# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} left_ft_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + right_ft_traj: {'dims': [1], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index e949b6d688..e78cd0c246 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -17,25 +17,28 @@ def main(): urdf = 'examples/Cassie/urdf/cassie_v2.urdf' reward_function_weights = '' - controller_plant = MultibodyPlant(8e-5) - addCassieMultibody(controller_plant, None, True, urdf, False, False) - controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) - # reward_func = RewardOSUDRL(reward_function_weights) - reward_func = RewardOSUDRL() - - # gym_env = DrakeCassieGym(reward_func, visualize=True) - gym_env = MuJoCoCassieGym(reward_func, visualize=True) - gym_env.make(controller) action = np.zeros(18) action[2] = 0.25 cumulative_reward = 0 while 1: - cumulative_reward = gym_env.advance_to(20) - gym_env.reset() + controller_plant = MultibodyPlant(8e-5) + addCassieMultibody(controller_plant, None, True, urdf, False, False) + controller_plant.Finalize() + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + + # reward_func = RewardOSUDRL(reward_function_weights) + reward_func = RewardOSUDRL() + + # gym_env = DrakeCassieGym(reward_func, visualize=True) + gym_env = MuJoCoCassieGym(reward_func, visualize=True) + gym_env.make(controller) + cumulative_reward = gym_env.advance_to(7.5) + print(cumulative_reward) + gym_env.free_sim() + # gym_env.reset() # while gym_env.current_time < 5.0: # state, reward = gym_env.step(action) # cumulative_reward += reward diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index dc992a2985..3e974d5913 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -369,8 +369,9 @@ def randomize_sim_params(self): self.joint_encoder_noise = np.zeros(6) -def free_sim(self): - del self.cassie_env + def free_sim(self): + del self.simulator + del self.cassie_vis def euler2quat(z=0, y=0, x=0): diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index e0308a2822..52ac9f1f3d 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -80,7 +80,7 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): reward = 0.200 * np.exp(-(com_orient_error + hip_yaw_penalty)) + \ 0.150 * np.exp(-pelvis_motion) + \ 0.150 * np.exp(-com_vel_error) + \ - 0.050 * np.exp(-hip_roll_penalty) + \ + 0.100 * np.exp(-hip_roll_penalty) + \ 0.025 * np.exp(-torque_penalty) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 160a5da8e8..86bbd1f400 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -32,8 +32,9 @@ def __init__(self, budget, reward_function, visualize=False): self.urdf = 'examples/Cassie/urdf/cassie_v2.urdf' self.controller_urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' - self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' - self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + # self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + self.osc_running_gains_filename = 'examples/Cassie/osc_run/new_learned_osc_running_gains.yaml' self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' self.drake_params_folder = "bindings/pydairlib/cassie/optimal_gains/" @@ -41,23 +42,31 @@ def __init__(self, budget, reward_function, visualize=False): self.loss_over_time = [] self.default_osc_gains = { - 'w_soft_constraint': 100, - 'w_input_reg': 0.001, + 'mu': 0.6, 'w_hip_yaw': 2.5, - 'hip_yaw_kp': 40, + 'PelvisRotW': np.array([1, 2.5, 0.1]), + 'SwingFootW': np.array([10, 10, 1]), + 'LiftoffSwingFootW': np.array([0.1, 10, 1]), + 'w_accel': 1e-5, + 'w_soft_constraint': 100, + 'w_input_reg': 0.001, + 'w_swing_toe': 1, + # 'hip_yaw_kp': 40, # 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), - 'PelvisRotKd': np.array([10, 5, 1]), - 'SwingFootKp': np.array([125, 80, 50]), - 'SwingFootKd': np.array([5, 5, 1]), - 'FootstepKd': np.array([0.2, 0.45, 0]), - 'center_line_offset': 0.03, + # 'PelvisRotKd': np.array([10, 5, 1]), + # 'SwingFootKp': np.array([125, 80, 50]), + # 'SwingFootKd': np.array([5, 5, 1]), + # 'FootstepKd': np.array([0.2, 0.45, 0]), + # 'center_line_offset': 0.03, # 'rest_length': 0.85, 'footstep_offset': -0.05, - 'stance_duration': 0.30, - 'flight_duration': 0.08, + 'impact_threshold': 0.025, + 'ekf_filter_tau': np.array([0.05, 0.1, 0.01]), + # 'stance_duration': 0.30, + # 'flight_duration': 0.08, } def save_params(self, folder, params, budget): @@ -110,23 +119,27 @@ def get_single_loss(self, params): def learn_gains(self, batch=True): self.default_params = ng.p.Dict( + w_accel=ng.p.Log(lower=1e-5, upper=1e-1), w_soft_constraint=ng.p.Log(lower=1.0, upper=1000.0), w_input_reg=ng.p.Log(lower=1e-5, upper=1e-1), + w_swing_toe=ng.p.Log(lower=1e-1, upper=1e2), mu=ng.p.Scalar(lower=0.4, upper=1.0), w_hip_yaw=ng.p.Scalar(lower=0, upper=10), - hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), + # hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), - # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), - PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), - SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), + PelvisRotW=ng.p.Array(lower=0., upper=10., shape=(3,)), + # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + SwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), + LiftoffSwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), + ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), + # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), + # center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), - stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), - flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), + impact_threshold=ng.p.Scalar(lower=0.0, upper=0.05), + # stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), + # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) self.loss_over_time = [] self.default_params.value = self.default_osc_gains @@ -144,15 +157,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 2000 + budget = 250 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - # optimizer.learn_gains() + optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_28_18_2000', optimizer.drake_params_folder).value - optimizer.write_params(optimal_params) - reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') - plt.plot(reward_over_time) - plt.show() + # optimal_params = optimizer.load_params('2022_03_29_17_1000', optimizer.drake_params_folder).value + # optimizer.write_params(optimal_params) + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + # plt.plot(reward_over_time) + # plt.show() diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index 793cfe5bc0..68e5b1e5ca 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -265,11 +265,12 @@ class CassieLcmDrivenLoop { << ", but stepping to " << time << std::endl; std::cout << "Difference is too large, resetting " + diagram_name_ + " time.\n"; - simulator_->get_mutable_context().SetTime(time); - simulator_->Initialize(); +// simulator_->get_mutable_context().SetTime(time); +// simulator_->Initialize(); + }else{ + simulator_->AdvanceTo(time); } - simulator_->AdvanceTo(time); if (is_forced_publish_) { // Force-publish via the diagram diagram_ptr_->Publish(diagram_context); diff --git a/examples/Cassie/integration_test.pmd b/examples/Cassie/integration_test.pmd index 3bb522684d..814b61f035 100644 --- a/examples/Cassie/integration_test.pmd +++ b/examples/Cassie/integration_test.pmd @@ -157,8 +157,8 @@ script "jumping_integration_test" { start cmd "cassie_mujoco_sim"; wait ms 10000; stop cmd "state_visualizer (dispatcher)"; - stop group "1.controllers-and-dispatchers"; - stop group "2.simulators"; + stop group "1.controllers (standalone)"; + stop group "2.simulators-and-dispatchers"; } script "mujoco_standing" { @@ -197,8 +197,8 @@ script "standing_integration_test" { start cmd "cassie_mujoco_sim"; wait ms 10000; stop cmd "state_visualizer (dispatcher)"; - stop group "1.controllers-and-dispatchers"; - stop group "2.simulators"; + stop group "1.controllers (standalone)"; + stop group "2.simulators-and-dispatchers"; } script "walking_integration_test" { @@ -232,6 +232,6 @@ script "walking_integration_test" { start cmd "cassie_mujoco_sim"; wait ms 10000; stop cmd "state_visualizer (dispatcher)"; - stop group "1.controllers-and-dispatchers"; - stop group "2.simulators"; + stop group "1.controllers (standalone)"; + stop group "2.simulators-and-dispatchers"; } diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 4231704a37..68c543c576 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -157,7 +157,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); -// pelvis_vel(1) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); +// pelvis_vel(1) *= 0.75; +// pelvis_vel(1) += 0.25 * context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 1862e262e4..6793e666dc 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,47 +1,45 @@ -FootstepKd: [0.20630578931908952, 0.0, 0.0, 0.0, 0.5022846733099167, 0.0, 0.0, 0.0, - 0.014419706168051383] +FootstepKd: [0.2, 0, 0, 0, 0.6, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] -LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, 0, 0, 1] +LiftoffSwingFootW: [6.322440230563972, 0.0, 0.0, 0.0, 8.993672023870989, 0.0, 0.0, + 0.0, 1.734133659416978] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [14.754198175926723, 0.0, 0.0, 0.0, 10.15048844191982, 0.0, 0.0, 0.0, - 3.9038583836913308] +PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 75] +PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] -PelvisRotW: [1, 0, 0, 0, 2.5, 0, 0, 0, 0.1] +PelvisRotW: [0.5110557066090032, 0.0, 0.0, 0.0, 3.9209573198037515, 0.0, 0.0, 0.0, + 1.2240961503444014] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [5.8013545212157736, 0.0, 0.0, 0.0, 8.37349939782334, 0.0, 0.0, 0.0, - 4.294753134633737] -SwingFootKp: [111.90374548402804, 0.0, 0.0, 0.0, 93.51462206597392, 0.0, 0.0, 0.0, - 75.82806014571253] -SwingFootW: [10, 0, 0, 0, 10, 0, 0, 0, 1] +SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] +SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 50.0] +SwingFootW: [4.808984643590918, 0.0, 0.0, 0.0, 7.587482274675776, 0.0, 0.0, 0.0, 0.1847132353267522] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -#center_line_offset: 0.03036161874399593 -center_line_offset: 0.04036161874399593 -ekf_filter_tau: [0.05, 0.1, 0.01] -flight_duration: 0.053967347248977025 -footstep_offset: -0.044971023856448855 +center_line_offset: 0.05 +ekf_filter_tau: [0.02633446032692358, 0.0, 0.0, 0.0, 0.07060155525047082, 0.0, 0.0, + 0.0, 0.04205462025236817] +flight_duration: 0.08 +footstep_offset: -0.06885692335510914 hip_yaw_kd: 1 -hip_yaw_kp: 48.17643439890748 -impact_threshold: 0.025 -mid_foot_height: 0.05 -mu: 0.6097124570750189 +hip_yaw_kp: 40 +impact_threshold: 0.014728618928927382 +mid_foot_height: 0.03 +mu: 0.6850430136891841 relative_feet: true relative_pelvis: true rest_length: 0.85 -stance_duration: 0.2949526396548052 +stance_duration: 0.3 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 vel_scale_trans_sagital: 0.2 -w_accel: 1.0e-05 -w_hip_yaw: 2.0187541880806643 +w_accel: 3.415131452923321e-05 +w_hip_yaw: 1.2329995123069186 w_input: 0.0 -w_input_reg: 0.004802653072422612 -w_soft_constraint: 111.82117439652899 -w_swing_toe: 1 +w_input_reg: 0.00015678365454145407 +w_soft_constraint: 265.76721638554557 +w_swing_toe: 0.44285002839273585 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 71a30e69bf..32d1083fcd 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -42,7 +42,7 @@ hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 center_line_offset: 0.05 -mid_foot_height: 0.05 +mid_foot_height: 0.03 FootstepKd: [ 0.2, 0, 0, 0, 0.6, 0, @@ -54,7 +54,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 85] + 0, 0, 75] PelvisKd: [ 1, 0, 0, 0, 0, 0, @@ -73,7 +73,7 @@ PelvisRotKd: 0, 0, 0.] SwingFootW: [10, 0, 0, - 0, 10, 0, + 0, 50, 0, 0, 0, 1] SwingFootKp: [125., 0, 0, diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index 3859d5df01..a16599db42 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -62,12 +62,6 @@ void TransTaskSpaceTrackingData::UpdateJ( context_wo_spr, JacobianWrtVariable::kV, *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); - if(fsm_state_ < 2){ - J_(2, 8) = 0; - J_(2, 16) = 0; - J_(2, 6) = 0; - J_(2, 14) = 0; - } if(J_.hasNaN()){ std::cout << "Jacobian has NaNs" << std::endl; } From 220e3d6b4c2d96656981e08ef4094587a14cdc74 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 31 Mar 2022 11:25:22 -0400 Subject: [PATCH 175/758] fixes for jumping, small tweaks in code --- .../cassie/gym_envs/cassie_gym_test.py | 2 +- bindings/pydairlib/cassie/learn_osc_gains.py | 27 ++-- examples/Cassie/input_supervisor.cc | 5 + examples/Cassie/multibody_sim_w_platform.cc | 33 +++- examples/Cassie/osc/osc_standing_gains.yaml | 2 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 14 +- .../Cassie/osc_run/osc_running_gains.yaml | 4 +- examples/Cassie/run_osc_jumping_controller.cc | 143 ++++++++++-------- .../Cassie/run_osc_standing_controller.cc | 16 +- solvers/default_osc_osqp_settings.yaml | 1 + .../osc/operational_space_control.cc | 36 +++-- 11 files changed, 179 insertions(+), 104 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index e78cd0c246..c95c01d3f6 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,7 +9,7 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/new_learned_osc_running_gains.yaml' # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 86bbd1f400..54c5ee74c0 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -57,14 +57,14 @@ def __init__(self, budget, reward_function, visualize=False): # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), # 'PelvisRotKd': np.array([10, 5, 1]), - # 'SwingFootKp': np.array([125, 80, 50]), - # 'SwingFootKd': np.array([5, 5, 1]), + 'SwingFootKp': np.array([125, 80, 50]), + 'SwingFootKd': np.array([5, 5, 1]), # 'FootstepKd': np.array([0.2, 0.45, 0]), # 'center_line_offset': 0.03, # 'rest_length': 0.85, 'footstep_offset': -0.05, 'impact_threshold': 0.025, - 'ekf_filter_tau': np.array([0.05, 0.1, 0.01]), + # 'ekf_filter_tau': np.array([0.05, 0.1, 0.01]), # 'stance_duration': 0.30, # 'flight_duration': 0.08, } @@ -131,8 +131,10 @@ def learn_gains(self, batch=True): PelvisRotW=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), SwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), + SwingFootKp=ng.p.Array(lower=25., upper=200., shape=(3,)), + SwingFootKd=ng.p.Array(lower=0.1, upper=10., shape=(3,)), LiftoffSwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), - ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), + # ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), # center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), @@ -157,15 +159,16 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 250 + budget = 1000 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - optimizer.learn_gains() - - # optimal_params = optimizer.load_params('2022_03_29_17_1000', optimizer.drake_params_folder).value - # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - # plt.plot(reward_over_time) - # plt.show() + # optimizer.learn_gains() + + optimal_params = optimizer.load_params('2022_03_30_16_1000', optimizer.drake_params_folder).value + optimizer.write_params(optimal_params) + reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + import pdb; pdb.set_trace() + plt.plot(reward_over_time) + plt.show() diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index ef382aae20..2487151b4c 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -145,6 +145,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, /// 2. safety_pd_controller /// 3. blended efforts from switching control signals /// 4. command from controller + auto prev_efforts = context.get_discrete_state(prev_efforts_index_).value(); // If the soft estop signal is triggered, applying only damping regardless of // any other controller signal @@ -173,6 +174,10 @@ void InputSupervisor::SetMotorTorques(const Context& context, } else if (command_value < -input_limit_(i)) { command_value = -input_limit_(i); } +// if(i < 2){ +// command_value += -0.2 * K_.row(i) * state->GetVelocities(); +// command_value = 0.95 * command_value + 0.05 * prev_efforts(i); +// } output->get_mutable_data()(i) = command_value; } } diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 136b1dc67c..8a4ed4b0ee 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -5,6 +5,7 @@ #include "dairlib/lcmt_cassie_out.hpp" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_fixed_point_solver.h" #include "examples/Cassie/cassie_utils.h" #include "lcm/dircon_saved_trajectory.h" #include "multibody/multibody_utils.h" @@ -72,6 +73,8 @@ DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); DEFINE_bool(visualize, true, "Set to true to visualize the platform"); DEFINE_double(actuator_delay, 0.0, "Duration of actuator delay. Set to 0.0 by default."); +DEFINE_bool(use_traj_state, false, + "Whether to intialize the sim from a specific state"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -201,7 +204,35 @@ int do_main(int argc, char* argv[]) { Eigen::VectorXd x_traj_init = state_traj.value(FLAGS_start_time); - plant.SetPositionsAndVelocities(&plant_context, x_traj_init); + if (FLAGS_use_traj_state){ + plant.SetPositionsAndVelocities(&plant_context, x_traj_init); + }else{ + Eigen::VectorXd q_init, u_init, lambda_init; + double mu_fp = 0; + double min_normal_fp = 70; + double toe_spread = 0.1; + // Create a plant for CassieFixedPointSolver. + // Note that we cannot use the plant from the above diagram, because after the + // diagram is built, plant.get_actuation_input_port().HasValue(*context) + // throws a segfault error + drake::multibody::MultibodyPlant plant_for_solver(0.0); + addCassieMultibody(&plant_for_solver, nullptr, + FLAGS_floating_base /*floating base*/, urdf, + FLAGS_spring_model, true); + plant_for_solver.Finalize(); + if (FLAGS_floating_base) { + CassieFixedPointSolver(plant_for_solver, FLAGS_init_height, mu_fp, + min_normal_fp, true, toe_spread, &q_init, &u_init, + &lambda_init); + } else { + CassieFixedBaseFixedPointSolver(plant_for_solver, &q_init, &u_init, + &lambda_init); + } + plant.SetPositions(&plant_context, q_init); + plant.SetVelocities(&plant_context, Eigen::VectorXd::Zero(plant.num_velocities())); + } + + diagram_context->SetTime(FLAGS_start_time); Simulator simulator(*diagram, std::move(diagram_context)); diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 8a1272b025..bfe01f4c0b 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -38,7 +38,7 @@ PelvisW: 0, 2, 0, 0, 0, 0] CoMKp: - [ 20, 0, 0, + [ 50, 0, 0, 0, 20, 0, 0, 0, 20] CoMKd: diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index b5fd616ce3..6f5f4383f6 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,13 +1,17 @@ w_input: 0.000 w_accel: 0.0000001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe -W_accel: [1, 1, 1, 1, 1, 1, +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 1, - 1, 0.9, 0.5, 0.1, 1] -W_lambda_reg: [0.001, 0.001, 0.01, - 0.01, 0.02, 0.02] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 100 x_offset: -0.0 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 32d1083fcd..a69537d4fc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -28,7 +28,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.85 stance_duration: 0.30 -flight_duration: 0.08 +flight_duration: 0.15 mu: 0.6 @@ -41,7 +41,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: -0.05 -center_line_offset: 0.05 +center_line_offset: 0.08 mid_foot_height: 0.03 FootstepKd: [ 0.2, 0, 0, diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index e6a88890ff..9220e1308b 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -123,14 +123,19 @@ int DoMain(int argc, char* argv[]) { feet_contact_points = {left_toe, right_toe}; /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - OSCJumpingGains gains = drake::yaml::LoadYamlFile( + drake::yaml::YamlReadArchive::Options yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); + OSCJumpingGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); /**** Get trajectory from optimization ****/ const DirconTrajectory& dircon_trajectory = DirconTrajectory( plant_w_spr, FindResourceOrThrow(FLAGS_folder_path + FLAGS_traj_name)); string output_traj_path = FLAGS_folder_path + FLAGS_traj_name + "_processed"; - if (gains.relative_feet) { + if (osc_gains.relative_feet) { output_traj_path += "_rel"; } const LcmTrajectory& output_trajs = @@ -218,14 +223,14 @@ int DoMain(int argc, char* argv[]) { double flight_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(1)(0); double land_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(2)(0) + - gains.landing_delay; + osc_gains.landing_delay; std::vector transition_times = {0.0, FLAGS_delay_time, flight_time, land_time}; // Offset the output trajectories to account for the starting global position // of the robot Vector3d support_center_offset; - support_center_offset << gains.x_offset, 0.0, 0.0; + support_center_offset << osc_gains.x_offset, 0.0, 0.0; std::vector breaks = pelvis_trans_traj.get_segment_times(); VectorXd breaks_vector = Eigen::Map(breaks.data(), breaks.size()); MatrixXd offset_points = support_center_offset.replicate(1, breaks.size()); @@ -246,10 +251,10 @@ int DoMain(int argc, char* argv[]) { feet_contact_points, FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_left", true, l_foot_trajectory, - l_hip_trajectory, gains.relative_feet, FLAGS_delay_time); + l_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); auto r_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_right", false, r_foot_trajectory, - r_hip_trajectory, gains.relative_feet, FLAGS_delay_time); + r_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); auto pelvis_rot_traj_generator = builder.AddSystem( pelvis_rot_trajectory, "pelvis_rot_tracking_data", FLAGS_delay_time); @@ -273,7 +278,7 @@ int DoMain(int argc, char* argv[]) { LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - // For contact-based fsm + // For contact-based fsm LcmSubscriberSystem* contact_results_sub = nullptr; if (FLAGS_simulator == "DRAKE") { contact_results_sub = builder.AddSystem( @@ -295,15 +300,16 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost - MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); - osc->SetAccelerationCostWeights(Q_accel); + osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); + // Soft constraint on contacts - double w_contact_relax = gains.w_soft_constraint; - osc->SetSoftConstraintWeight(w_contact_relax); + osc->SetSoftConstraintWeight(gains.w_soft_constraint); + // Soft constraint on contacts - double w_input_reg = gains.w_input_reg; - osc->SetInputSmoothingWeights(gains.w_input_reg * - MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); // Contact information for OSC osc->SetContactFriction(gains.mu); @@ -356,73 +362,83 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_fixed_ankle_spring); osc->AddKinematicConstraint(&evaluators); + std::cout << " here: " << std::endl; /**** Tracking Data for OSC *****/ - auto pelvis_tracking_data = std::make_unique ( - "pelvis_trans_traj", gains.K_p_com, gains.K_d_com, gains.W_com, - plant_w_spr, plant_w_spr); + auto pelvis_tracking_data = std::make_unique( + "pelvis_trans_traj", osc_gains.K_p_com, osc_gains.K_d_com, + osc_gains.W_com, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); } - auto pelvis_rot_tracking_data = std::make_unique ( - "pelvis_rot_tracking_data", gains.K_p_pelvis, gains.K_d_pelvis, - gains.W_pelvis, plant_w_spr, plant_w_spr); + auto pelvis_rot_tracking_data = std::make_unique( + "pelvis_rot_tracking_data", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { pelvis_rot_tracking_data->AddStateAndFrameToTrack(mode, "pelvis"); } + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + pelvis_tracking_data->SetImpactInvariantProjection(true); - auto left_foot_tracking_data = std::make_unique ( - "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr); - auto right_foot_tracking_data = std::make_unique ( - "right_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr); - left_foot_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, "toe_left"); + auto left_foot_tracking_data = std::make_unique( + "left_ft_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, + osc_gains.W_flight_foot, plant_w_spr, plant_w_spr); + auto right_foot_tracking_data = std::make_unique( + "right_ft_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, + osc_gains.W_flight_foot, plant_w_spr, plant_w_spr); + left_foot_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, + "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, - "toe_right"); - - auto left_hip_tracking_data = std::make_unique ( - "left_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr); - auto right_hip_tracking_data = std::make_unique ( - "right_hip_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr); + "toe_right"); + + auto left_hip_tracking_data = std::make_unique( + "left_hip_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, + osc_gains.W_flight_foot, plant_w_spr, plant_w_spr); + auto right_hip_tracking_data = std::make_unique( + "right_hip_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, + osc_gains.W_flight_foot, plant_w_spr, plant_w_spr); left_hip_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, "hip_left"); right_hip_tracking_data->AddStateAndPointToTrack(osc_jump::FLIGHT, - "hip_right"); - - auto left_foot_rel_tracking_data = std::make_unique ( - "left_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr, left_foot_tracking_data.get(), - left_hip_tracking_data.get()); - auto right_foot_rel_tracking_data = std::make_unique ( - "right_ft_traj", gains.K_p_flight_foot, gains.K_d_flight_foot, - gains.W_flight_foot, plant_w_spr, plant_w_spr, right_foot_tracking_data.get(), - right_hip_tracking_data.get()); + "hip_right"); + + auto left_foot_rel_tracking_data = + std::make_unique( + "left_ft_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, + osc_gains.W_flight_foot, plant_w_spr, plant_w_spr, + left_foot_tracking_data.get(), left_hip_tracking_data.get()); + auto right_foot_rel_tracking_data = + std::make_unique( + "right_ft_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, + osc_gains.W_flight_foot, plant_w_spr, plant_w_spr, + right_foot_tracking_data.get(), right_hip_tracking_data.get()); // Flight phase hip yaw tracking - auto left_hip_yaw_tracking_data = std::make_unique ( - "swing_hip_yaw_left_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, - gains.W_hip_yaw, plant_w_spr, plant_w_spr); - auto right_hip_yaw_tracking_data = std::make_unique ( - "swing_hip_yaw_right_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, - gains.W_hip_yaw, plant_w_spr, plant_w_spr); + auto left_hip_yaw_tracking_data = std::make_unique( + "swing_hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant_w_spr, plant_w_spr); + auto right_hip_yaw_tracking_data = std::make_unique( + "swing_hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant_w_spr, plant_w_spr); left_hip_yaw_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_right", "hip_yaw_rightdot"); - osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); - osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), + VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), + VectorXd::Zero(1)); // Flight phase toe pitch tracking - MatrixXd W_swing_toe = gains.w_swing_toe * MatrixXd::Identity(1, 1); - MatrixXd K_p_swing_toe = gains.swing_toe_kp * MatrixXd::Identity(1, 1); - MatrixXd K_d_swing_toe = gains.swing_toe_kd * MatrixXd::Identity(1, 1); - auto left_toe_angle_tracking_data = std::make_unique ( + MatrixXd W_swing_toe = osc_gains.w_swing_toe * MatrixXd::Identity(1, 1); + MatrixXd K_p_swing_toe = osc_gains.swing_toe_kp * MatrixXd::Identity(1, 1); + MatrixXd K_d_swing_toe = osc_gains.swing_toe_kd * MatrixXd::Identity(1, 1); + auto left_toe_angle_tracking_data = std::make_unique( "left_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); - auto right_toe_angle_tracking_data = std::make_unique ( + auto right_toe_angle_tracking_data = std::make_unique( "right_toe_angle_traj", K_p_swing_toe, K_d_swing_toe, W_swing_toe, plant_w_spr, plant_w_spr); @@ -447,7 +463,7 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(pelvis_tracking_data)); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); - if (gains.relative_feet) { + if (osc_gains.relative_feet) { left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); @@ -458,15 +474,10 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(left_foot_tracking_data)); osc->AddTrackingData(std::move(right_foot_tracking_data)); } - osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); - osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); - left_toe_angle_tracking_data->SetImpactInvariantProjection(true); right_toe_angle_tracking_data->SetImpactInvariantProjection(true); - left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); - right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); - pelvis_rot_tracking_data->SetImpactInvariantProjection(true); - pelvis_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index e8b619d5a5..3be21af121 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -4,11 +4,12 @@ #include "dairlib/lcmt_robot_output.hpp" #include "dairlib/lcmt_target_standing_height.hpp" #include "examples/Cassie/cassie_utils.h" -#include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/osc_standing_gains.h" +#include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/com_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" @@ -79,7 +80,7 @@ int DoMain(int argc, char* argv[]) { // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_springs(0.0); addCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); plant_w_springs.Finalize(); // Build fix-spring Cassie MBP @@ -163,6 +164,13 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_STANDING", &lcm_local, TriggerTypeSet({TriggerType::kForced}))); + auto failure_aggregator = + builder.AddSystem(FLAGS_channel_u, + 1); + auto controller_failure_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm_local, TriggerTypeSet({TriggerType::kForced}))); + // Create desired center of mass traj std::vector&>> @@ -279,6 +287,10 @@ int DoMain(int argc, char* argv[]) { osc->get_tracking_data_input_port("com_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("pelvis_rot_traj")); + builder.Connect(osc->get_failure_output_port(), + failure_aggregator->get_input_port(0)); + builder.Connect(failure_aggregator->get_status_output_port(), + controller_failure_pub->get_input_port()); // Create the diagram auto owned_diagram = builder.Build(); diff --git a/solvers/default_osc_osqp_settings.yaml b/solvers/default_osc_osqp_settings.yaml index 7ec5059213..f92be5a6c5 100644 --- a/solvers/default_osc_osqp_settings.yaml +++ b/solvers/default_osc_osqp_settings.yaml @@ -19,3 +19,4 @@ adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 +time_limit: 0.0 diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 63f5b15d83..4d8e016b2b 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -210,8 +210,8 @@ void OperationalSpaceControl::AddKinematicConstraint( } // Tracking data methods -void OperationalSpaceControl::AddTrackingData(std::unique_ptr tracking_data, - double t_lb, double t_ub) { +void OperationalSpaceControl::AddTrackingData( + std::unique_ptr tracking_data, double t_lb, double t_ub) { tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(VectorXd::Zero(0)); t_s_vec_.push_back(t_lb); @@ -232,8 +232,8 @@ void OperationalSpaceControl::AddTrackingData(std::unique_ptr t } } void OperationalSpaceControl::AddConstTrackingData( - std::unique_ptr tracking_data, const VectorXd& v, double t_lb, - double t_ub) { + std::unique_ptr tracking_data, const VectorXd& v, + double t_lb, double t_ub) { tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(v); t_s_vec_.push_back(t_lb); @@ -307,6 +307,7 @@ void OperationalSpaceControl::Build() { u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); + u_prev_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); epsilon_sol_->setZero(); @@ -578,8 +579,8 @@ VectorXd OperationalSpaceControl::SolveQp( row_idx += contact_i->num_active(); } -// std::cout << "JdotV_h" << JdotV_h.transpose() << std::endl; -// std::cout << "JdotV_c" << JdotV_c_active.transpose() << std::endl; + // std::cout << "JdotV_h" << JdotV_h.transpose() << std::endl; + // std::cout << "JdotV_c" << JdotV_c_active.transpose() << std::endl; // Update constraints // 1. Dynamics constraint @@ -734,9 +735,9 @@ VectorXd OperationalSpaceControl::SolveQp( -W_input_smoothing_ * (*u_prev_)); } -// if (!solver_->IsInitialized()) { -// solver_->InitializeSolver(*prog_); -// } + // if (!solver_->IsInitialized()) { + // solver_->InitializeSolver(*prog_); + // } if (initial_guess_x_.count(fsm_state) > 0) { solver_->WarmStart(initial_guess_x_.at(fsm_state), @@ -756,8 +757,8 @@ VectorXd OperationalSpaceControl::SolveQp( initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { -// std::cerr << "QP did not solve in time!" << std::endl; -// solver_->DisableWarmStart(); + // std::cerr << "QP did not solve in time!" << std::endl; + // solver_->DisableWarmStart(); *u_prev_ = VectorXd::Zero(n_u_); } @@ -891,7 +892,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( W_lambda_c_reg_ * (*lambda_c_sol_))(0) : 0; total_cost_ += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost; + input_smoothing_cost + lambda_h_cost + lambda_c_cost; soft_constraint_cost_ = soft_constraint_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); @@ -983,7 +984,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( } output->tracking_data[i] = osc_output; } -// std::cout << total_cost_ << std::endl; + // std::cout << total_cost_ << std::endl; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); @@ -1002,7 +1003,6 @@ void OperationalSpaceControl::CalcOptimalInput( plant_w_spr_.num_velocities()); x_w_spr << q_w_spr, v_w_spr; - double timestamp = robot_output->get_timestamp(); double current_time = timestamp; @@ -1057,6 +1057,14 @@ void OperationalSpaceControl::CheckTracking( output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; // std::cout << "total cost: " << total_cost_ << std::endl; +// bool joint_error = false; +// auto q = +// (map_position_from_spring_to_no_spring_ * robot_output->GetPositions()) +// .segment(7, n_revolute_joints_); +// for (int i = 0; i < n_revolute_joints_; ++i) { +// joint_error = joint_error || q(i) < q_min_(i); +// joint_error = joint_error || q(i) > q_max_(i); +// } if (soft_constraint_cost_ > 5e2 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } From a4f2075831ea120478dddd4fbcd5de5516bfe26a Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 31 Mar 2022 11:34:46 -0400 Subject: [PATCH 176/758] fixing one gain --- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 14 +++++++------- examples/Cassie/osc_run/osc_running_gains.yaml | 2 +- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 6f5f4383f6..464d6bca69 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -12,12 +12,12 @@ W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -w_input_reg: 0.01 +w_input_reg: 0.001 w_soft_constraint: 100 -x_offset: -0.0 +x_offset: -0.02 relative_feet: true -mu: 0.8 +mu: 0.4 w_swing_toe: 1 swing_toe_kp: 2000 @@ -43,7 +43,7 @@ FlightFootW: 0, 1, 0, 0, 0, 1] CoMKp: - [25, 0, 0, + [30, 0, 0, 0, 50, 0, 0, 0, 50] CoMKd: @@ -59,11 +59,11 @@ PelvisRotKd: 0, 10, 0, 0, 0, 0] FlightFootKp: - [50, 0, 0, + [100, 0, 0, 0, 100, 0, 0, 0, 100] FlightFootKd: - [20, 0, 0, - 0, 0, 0, + [10, 0, 0, + 0, 10, 0, 0, 0, 0] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index a69537d4fc..f90e08943d 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -28,7 +28,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.85 stance_duration: 0.30 -flight_duration: 0.15 +flight_duration: 0.08 mu: 0.6 From 56ff9915dc57c55b2c054aa79e81383260bf3d94 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 31 Mar 2022 13:55:23 -0400 Subject: [PATCH 177/758] foot traj changes --- examples/Cassie/osc_run/foot_traj_generator.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 68c543c576..3750e4ab3c 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -156,7 +156,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); - pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); +// pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); // pelvis_vel(1) *= 0.75; // pelvis_vel(1) += 0.25 * context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; From 2932cbe81b9983cf5a888139bc8901471c221d76 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 31 Mar 2022 16:16:50 -0400 Subject: [PATCH 178/758] fixing walking controller --- .../analysis/plot_configs/cassie_running_plot.yaml | 14 +++++++------- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/run_osc_walking_controller.cc | 5 +++++ 3 files changed, 13 insertions(+), 7 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index c9cee1241a..452a3918ad 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -28,15 +28,15 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_qp_solve_time: true -plot_tracking_costs: false +plot_tracking_costs: true tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} +# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} +# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [1], 'derivs': ['pos']} - right_ft_traj: {'dims': [1], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} +# left_ft_traj: {'dims': [1], 'derivs': ['pos']} +# right_ft_traj: {'dims': [1], 'derivs': ['pos']} +# left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} +# right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index cd5f7d87eb..8e139b7241 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -404,6 +404,7 @@ cc_binary( "//systems/controllers:fsm_event_time", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems/controllers:controllers_all", "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 62ffe53ae5..7a7888f66a 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -12,6 +12,7 @@ #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/cassie_out_to_radio.h" #include "systems/controllers/fsm_event_time.h" #include "systems/controllers/lipm_traj_gen.h" #include "systems/controllers/osc/com_tracking_data.h" @@ -145,6 +146,8 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant_w_spr); + auto cassie_out_to_radio = + builder.AddSystem(); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -179,6 +182,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(cassie_out_receiver->get_output_port(), + cassie_out_to_radio->get_input_port()); + builder.Connect(cassie_out_to_radio->get_output_port(), high_level_command->get_radio_input_port()); } else { high_level_command = builder.AddSystem( From f547a99ad0f5f80f60ebb24de824d4db5497a1b9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 1 Apr 2022 10:54:59 -0400 Subject: [PATCH 179/758] fixing missing default destructor --- systems/controllers/osc/osc_tracking_data.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index 418dde4dec..e1373d7424 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -24,7 +24,7 @@ class OscTrackingData { const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); -// virtual ~OscTrackingData(); + virtual ~OscTrackingData() = default; // Update() updates the caches. It does the following things in order: // - updates the current fsm state From adec0700c7228697b12c37d318443ab8dff47047 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 1 Apr 2022 11:23:51 -0400 Subject: [PATCH 180/758] changing relative tracking data to be purely leg length --- examples/Cassie/osc_run/osc_running_gains.h | 6 +++-- .../Cassie/osc_run/osc_running_gains.yaml | 15 ++++++------ examples/Cassie/run_osc_running_controller.cc | 24 +++++++++---------- 3 files changed, 24 insertions(+), 21 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 2190272219..0379867f43 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -25,7 +25,8 @@ struct OSCRunningGains : OSCGains { double vel_scale_trans_lateral; bool relative_feet; bool relative_pelvis; - double rest_length; + double slip_rest_length; + double leg_rest_length; double stance_duration; double flight_duration; @@ -84,7 +85,8 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); - a->Visit(DRAKE_NVP(rest_length)); + a->Visit(DRAKE_NVP(slip_rest_length)); + a->Visit(DRAKE_NVP(leg_rest_length)); a->Visit(DRAKE_NVP(stance_duration)); a->Visit(DRAKE_NVP(flight_duration)); a->Visit(DRAKE_NVP(center_line_offset)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index f90e08943d..e154c74d39 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -26,8 +26,9 @@ vel_scale_trans_sagital: 0.2 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.85 -stance_duration: 0.30 +slip_rest_length: 0.85 +leg_rest_length: 0.70 +stance_duration: 0.29 flight_duration: 0.08 mu: 0.6 @@ -40,12 +41,12 @@ w_hip_yaw: 2.5 hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: -0.05 -center_line_offset: 0.08 +footstep_offset: 0 +center_line_offset: -0.05 mid_foot_height: 0.03 FootstepKd: [ 0.2, 0, 0, - 0, 0.6, 0, + 0, 0.4, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, @@ -60,7 +61,7 @@ PelvisKd: 0, 0, 0, 0, 0, 5] PelvisRotW: - [1, 0, 0, + [0.5, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisRotKp: @@ -78,7 +79,7 @@ SwingFootW: SwingFootKp: [125., 0, 0, 0, 80., 0, - 0, 0, 50.] + 0, 0, 100.] SwingFootKd: [5., 0, 0, 0, 5., 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b9be4035fc..36336129c5 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -276,20 +276,20 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.slip_rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, + plant, plant_context.get(), "toe_left", "thigh_left", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "pelvis", + plant, plant_context.get(), "toe_right", "thigh_right", osc_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.leg_rest_length, osc_gains.center_line_offset, osc_gains.footstep_offset, osc_gains.mid_foot_height); - r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.rest_length, + r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.leg_rest_length, osc_gains.center_line_offset, osc_gains.footstep_offset, osc_gains.mid_foot_height); @@ -340,12 +340,12 @@ int DoMain(int argc, char* argv[]) { auto right_hip_tracking_data = std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "thigh_left"); + right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "thigh_right"); left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); + "thigh_left"); + right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + "thigh_right"); auto left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -355,9 +355,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "pelvis"); + "thigh_left"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); + "thigh_right"); auto left_foot_rel_tracking_data = std::make_unique( From d1a4f6e21d2c93d7a993ba9d0d4b73ef85c3c4f8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 1 Apr 2022 12:35:26 -0400 Subject: [PATCH 181/758] removing diagrams dependency from pd controller --- examples/Cassie/BUILD.bazel | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 8e139b7241..e500aca4b5 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -177,7 +177,6 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//common", - "//examples/Cassie/diagrams:diagrams", "//systems:robot_lcm_systems", "//systems/controllers", "//systems/controllers:pd_config_lcm", From 2025ad673a5d414b0e2c37fa000c5dfc91107213 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 1 Apr 2022 13:19:31 -0400 Subject: [PATCH 182/758] small compilation changes and gains --- .../osc_running_controller_diagram.cc | 24 +++++++++---------- .../Cassie/osc_run/osc_running_gains.yaml | 16 ++++++------- examples/Cassie/run_pd_controller.cc | 2 -- 3 files changed, 20 insertions(+), 22 deletions(-) diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index f0fcc65f17..99d8e6b868 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -221,20 +221,20 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_running_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.rest_length); + pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.slip_rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", + plant, plant_context.get(), "toe_left", "thigh_left", osc_running_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "pelvis", + plant, plant_context.get(), "toe_right", "thigh_right", osc_running_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.rest_length, osc_running_gains.center_line_offset, + osc_running_gains.leg_rest_length, osc_running_gains.center_line_offset, osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.rest_length, osc_running_gains.center_line_offset, + osc_running_gains.leg_rest_length, osc_running_gains.center_line_offset, osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); pelvis_tracking_data = std::make_unique( @@ -288,12 +288,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "thigh_left"); + right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "thigh_right"); left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); + "thigh_left"); + right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + "thigh_right"); left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_running_gains.K_p_swing_foot, @@ -304,9 +304,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); + "thigh_left"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); + "thigh_right"); left_foot_rel_tracking_data = std::make_unique( diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e154c74d39..c367e37230 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -22,12 +22,12 @@ ekf_filter_tau: [0.05, 0.1, 0.01] # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.2 +vel_scale_trans_sagital: 0.6 vel_scale_trans_lateral: -0.15 # SLIP parameters slip_rest_length: 0.85 -leg_rest_length: 0.70 +leg_rest_length: 0.73 stance_duration: 0.29 flight_duration: 0.08 @@ -42,10 +42,10 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: 0 -center_line_offset: -0.05 -mid_foot_height: 0.03 +center_line_offset: -0.07 +mid_foot_height: 0.05 FootstepKd: - [ 0.2, 0, 0, + [ 0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] PelvisW: @@ -55,13 +55,13 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 75] + 0, 0, 85] PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [0.5, 0, 0, + [1.0, 0, 0, 0, 2.5, 0, 0, 0, 0.1] PelvisRotKp: @@ -75,7 +75,7 @@ PelvisRotKd: SwingFootW: [10, 0, 0, 0, 50, 0, - 0, 0, 1] + 0, 0, 0.1] SwingFootKp: [125., 0, 0, 0, 80., 0, diff --git a/examples/Cassie/run_pd_controller.cc b/examples/Cassie/run_pd_controller.cc index 6309ddf033..c6e2e2c49f 100644 --- a/examples/Cassie/run_pd_controller.cc +++ b/examples/Cassie/run_pd_controller.cc @@ -5,8 +5,6 @@ #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" -#include "examples/Cassie/diagrams/cassie_sim_diagram.h" -#include "examples/Cassie/diagrams/osc_running_controller_diagram.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" From 19c4e1a88e2fda6e0aa796b01274fc250a22ddf5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 4 Apr 2022 13:59:32 -0400 Subject: [PATCH 183/758] small changes --- .../pydairlib/analysis/log_plotter_cassie.py | 1 + .../cassie/gym_envs/cassie_gym_test.py | 2 +- .../cassie/gym_envs/mujoco_cassie_gym.py | 28 +++++++--- .../cassie/gym_envs/reward_osudrl.py | 54 ++++++++++++++++--- bindings/pydairlib/cassie/learn_osc_gains.py | 46 ++++++++-------- examples/Cassie/cassie_state_estimator.cc | 20 +++---- .../osc_run/learned_osc_running_gains.yaml | 47 ++++++++-------- .../Cassie/osc_run/osc_running_gains.yaml | 8 +-- examples/Cassie/run_osc_running_controller.cc | 3 -- examples/Cassie/visualizer.cc | 7 +++ 10 files changed, 140 insertions(+), 76 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 2eab85d3d4..7bae60f233 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -113,6 +113,7 @@ def main(): plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, foot_frames, pts, dims) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) if plot_config.plot_qp_solve_time: mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index c95c01d3f6..e78cd0c246 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,7 +9,7 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/new_learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 3e974d5913..794eb46429 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -1,3 +1,5 @@ +import copy + import numpy as np import math @@ -45,8 +47,8 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic ''' Copied from apex/cassie.py ''' - self.max_simrate = 1.2 * self.gym_dt - self.min_simrate = 0.8 * self.gym_dt + self.max_simrate = 1.3 * self.gym_dt + self.min_simrate = 0.7 * self.gym_dt self.dynamics_randomization = dynamics_randomization self.dynamics_randomization = dynamics_randomization self.slope_rand = dynamics_randomization @@ -108,6 +110,16 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic 'hip_pitch_right_motor': 7, 'knee_right_motor': 8, 'toe_right_motor': 9} + # sim states + self.l_foot_frc = 0 + self.r_foot_frc = 0 + foot_pos = np.zeros(6) + self.l_foot_pos = np.zeros(3) + self.r_foot_pos = np.zeros(3) + self.l_foot_orient_cost = 0 + self.r_foot_orient_cost = 0 + self.neutral_foot_orient = np.array( + [-0.24790886454547323, -0.24679713195445646, -0.6609396704367185, 0.663921021343526]) def make(self, controller): self.builder = DiagramBuilder() @@ -181,21 +193,26 @@ def step(self, action=np.zeros(18)): u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) self.drake_sim.AdvanceTo(next_timestep) + self.reward_func.reset_clock_reward() while self.simulator.time() < next_timestep: self.simulator.step(cassie_in) + foot_pos = self.simulator.foot_pos() + self.reward_func.update_clock_reward(self.simulator.get_foot_forces(), foot_pos, + self.simulator.xquat("left-foot"), self.simulator.xquat("right-foot")) + if self.visualize: self.cassie_vis.draw(self.simulator) self.current_time = next_timestep t = self.simulator.time() - q = self.simulator.qpos() - v = self.simulator.qvel() + q = np.copy(self.simulator.qpos()) + v = np.copy(self.simulator.qvel()) q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) self.current_time = t x = np.hstack((q, v)) x = reexpress_state_local_to_global_omega(x) self.cassie_state = CassieEnvState(self.current_time, x, u, action) - reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) + reward = self.reward_func.compute_reward(timestep, self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() self.prev_cassie_state = self.cassie_state return self.cassie_state, reward @@ -368,7 +385,6 @@ def randomize_sim_params(self): self.motor_encoder_noise = np.zeros(10) self.joint_encoder_noise = np.zeros(6) - def free_sim(self): del self.simulator del self.cassie_vis diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index 52ac9f1f3d..7f68d4855c 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -1,4 +1,5 @@ import numpy as np +import copy import matplotlib.pyplot as plt from scipy.spatial.transform import Rotation as R import pickle @@ -21,7 +22,14 @@ def __init__(self, weights_filename=None): self.neutral_foot_orient = np.array([-0.24790886454547323, -0.24679713195445646, -0.6609396704367185, 0.663921021343526]) self.l_foot_orient = 0 self.r_foot_orient = 0 - + self.l_foot_frc = 0 + self.r_foot_frc = 0 + self.l_foot_pos = np.zeros(3) + self.r_foot_pos = np.zeros(3) + self.l_foot_vel = np.zeros(3) + self.r_foot_vel = np.zeros(3) + self.l_foot_orient_cost = 0 + self.r_foot_orient_cost = 0 return @@ -29,9 +37,31 @@ def load_weights(self, filename): with open(LOSS_WEIGHTS_FOLDER + filename + '.pkl', 'rb') as f: return pickle.load(f) - def compute_reward(self, cassie_env_state, prev_cassie_env_state): - - + def reset_clock_reward(self): + self.l_foot_frc = 0 + self.r_foot_frc = 0 + foot_pos = np.zeros(6) + self.l_foot_pos = np.zeros(3) + self.r_foot_pos = np.zeros(3) + self.l_foot_vel = np.zeros(3) + self.r_foot_vel = np.zeros(3) + self.l_foot_orient_cost = 0 + self.r_foot_orient_cost = 0 + + def update_clock_reward(self, foot_forces, foot_pos, l_foot_quat, r_foot_quat): + prev_foot = copy.deepcopy(np.hstack((self.l_foot_pos, self.r_foot_pos))) + self.l_foot_frc += foot_forces[0] + self.r_foot_frc += foot_forces[1] + # Relative Foot Position tracking + self.l_foot_pos += foot_pos[0:3] + self.r_foot_pos += foot_pos[3:6] + # Foot Orientation Cost + self.l_foot_orient_cost += (1 - np.inner(self.neutral_foot_orient, l_foot_quat) ** 2) + self.r_foot_orient_cost += (1 - np.inner(self.neutral_foot_orient, r_foot_quat) ** 2) + self.l_foot_vel = (foot_pos[0:3] - prev_foot[0:3]) / 0.0005 + self.r_foot_vel = (foot_pos[3:6] - prev_foot[3:6]) / 0.0005 + + def compute_reward(self, timestep, cassie_env_state, prev_cassie_env_state): pos = cassie_env_state.get_positions() vel = cassie_env_state.get_velocities() com_pos = cassie_env_state.get_fb_positions() @@ -47,17 +77,27 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): orient_targ = np.array([1, 0, 0, 0]) com_orient_error = 0 - hip_yaw_penalty = 0 + # hip_yaw_penalty = 0 com_vel_error = 0 straight_diff = 0 foot_vel_error = 0 foot_frc_error = 0 + foot_orient_error = 0 + + + self.l_foot_frc /= timestep + self.r_foot_frc /= timestep + self.l_foot_pos /= timestep + self.r_foot_pos /= timestep + self.l_foot_orient_cost /= timestep + self.r_foot_orient_cost /= timestep # com orient error com_orient_error += 10 * (1 - np.inner(orient_targ, cassie_env_state.get_orientations()) ** 2) # foot orient error # hip_yaw_penalty += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) - hip_yaw_penalty += np.abs(joint_vel[1]) + np.abs(joint_vel[8]) + foot_orient_error += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) + # hip_yaw_penalty += np.abs(joint_vel[1]) + np.abs(joint_vel[8]) # com vel error com_vel_error += np.linalg.norm(com_vel[0] - des_forward_vel) @@ -77,7 +117,7 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): torque_penalty = 0.5 * (sum(np.abs(prev_torques - torques)) / len(torques)) - reward = 0.200 * np.exp(-(com_orient_error + hip_yaw_penalty)) + \ + reward = 0.200 * np.exp(-(com_orient_error + foot_orient_error)) + \ 0.150 * np.exp(-pelvis_motion) + \ 0.150 * np.exp(-com_vel_error) + \ 0.100 * np.exp(-hip_roll_penalty) + \ diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 54c5ee74c0..ace52367a9 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -32,9 +32,9 @@ def __init__(self, budget, reward_function, visualize=False): self.urdf = 'examples/Cassie/urdf/cassie_v2.urdf' self.controller_urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' - self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' # self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - self.osc_running_gains_filename = 'examples/Cassie/osc_run/new_learned_osc_running_gains.yaml' + self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' self.drake_params_folder = "bindings/pydairlib/cassie/optimal_gains/" @@ -42,30 +42,31 @@ def __init__(self, budget, reward_function, visualize=False): self.loss_over_time = [] self.default_osc_gains = { - - 'mu': 0.6, + 'w_accel': 1e-5, + 'w_soft_constraint': 100, + 'w_input_reg': 0.001, + # 'w_swing_toe': 1, + # 'mu': 0.6, 'w_hip_yaw': 2.5, 'PelvisRotW': np.array([1, 2.5, 0.1]), 'SwingFootW': np.array([10, 10, 1]), + # 'SwingFootKp': np.array([125, 80, 50]), + # 'SwingFootKd': np.array([5, 5, 1]), 'LiftoffSwingFootW': np.array([0.1, 10, 1]), - 'w_accel': 1e-5, - 'w_soft_constraint': 100, - 'w_input_reg': 0.001, - 'w_swing_toe': 1, # 'hip_yaw_kp': 40, # 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), # 'PelvisRotKd': np.array([10, 5, 1]), - 'SwingFootKp': np.array([125, 80, 50]), - 'SwingFootKd': np.array([5, 5, 1]), # 'FootstepKd': np.array([0.2, 0.45, 0]), - # 'center_line_offset': 0.03, - # 'rest_length': 0.85, + 'center_line_offset': -0.05, + 'mid_foot_height': 0.05, + # 'slip_rest_length': 0.85, + 'leg_rest_length': 0.73, 'footstep_offset': -0.05, 'impact_threshold': 0.025, # 'ekf_filter_tau': np.array([0.05, 0.1, 0.01]), - # 'stance_duration': 0.30, + 'stance_duration': 0.30, # 'flight_duration': 0.08, } @@ -122,8 +123,8 @@ def learn_gains(self, batch=True): w_accel=ng.p.Log(lower=1e-5, upper=1e-1), w_soft_constraint=ng.p.Log(lower=1.0, upper=1000.0), w_input_reg=ng.p.Log(lower=1e-5, upper=1e-1), - w_swing_toe=ng.p.Log(lower=1e-1, upper=1e2), - mu=ng.p.Scalar(lower=0.4, upper=1.0), + # w_swing_toe=ng.p.Log(lower=1e-1, upper=1e2), + # mu=ng.p.Scalar(lower=0.4, upper=1.0), w_hip_yaw=ng.p.Scalar(lower=0, upper=10), # hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), @@ -131,16 +132,18 @@ def learn_gains(self, batch=True): PelvisRotW=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), SwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), - SwingFootKp=ng.p.Array(lower=25., upper=200., shape=(3,)), - SwingFootKd=ng.p.Array(lower=0.1, upper=10., shape=(3,)), + # SwingFootKp=ng.p.Array(lower=25., upper=200., shape=(3,)), + # SwingFootKd=ng.p.Array(lower=0.1, upper=10., shape=(3,)), LiftoffSwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), # ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - # center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), - # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + center_line_offset=ng.p.Scalar(lower=-0.1, upper=0.1), + mid_foot_height=ng.p.Scalar(lower=0.00, upper=0.2), + # slip_rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + leg_rest_length=ng.p.Scalar(lower=0.65, upper=0.85), footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), impact_threshold=ng.p.Scalar(lower=0.0, upper=0.05), - # stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), + stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) self.loss_over_time = [] @@ -166,9 +169,8 @@ def learn_gains(self, batch=True): optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) # optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_30_16_1000', optimizer.drake_params_folder).value + optimal_params = optimizer.load_params('2022_04_01_13_1000', optimizer.drake_params_folder).value optimizer.write_params(optimal_params) reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - import pdb; pdb.set_trace() plt.plot(reward_over_time) plt.show() diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 55c4f3f0aa..1629dd2ce1 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -778,9 +778,9 @@ EventStatus CassieStateEstimator::Update( std::vector> contacts; contacts.push_back(std::pair(0, left_contact)); - contacts.push_back(std::pair(1, left_contact)); +// contacts.push_back(std::pair(1, left_contact)); contacts.push_back(std::pair(2, right_contact)); - contacts.push_back(std::pair(3, right_contact)); +// contacts.push_back(std::pair(3, right_contact)); ekf.setContacts(contacts); // Step 4 - EKF (measurement step) @@ -834,14 +834,14 @@ EventStatus CassieStateEstimator::Update( J_wrt_joints * cov_w_ * J_wrt_joints.transpose(); inekf::Kinematics rear_frame(2 * i, rear_toe_pose, rear_covariance); measured_kinematics.push_back(rear_frame); - plant_.CalcJacobianTranslationalVelocity( - *context_, JacobianWrtVariable::kV, *toe_frames_[i], - front_contact_disp_, pelvis_frame_, pelvis_frame_, &J); - J_wrt_joints = J.block(0, 6, 3, 16); - front_covariance.block<3, 3>(3, 3) = - J_wrt_joints * cov_w_ * J_wrt_joints.transpose(); - inekf::Kinematics front_frame(2 * i + 1, front_toe_pose, front_covariance); - measured_kinematics.push_back(front_frame); +// plant_.CalcJacobianTranslationalVelocity( +// *context_, JacobianWrtVariable::kV, *toe_frames_[i], +// front_contact_disp_, pelvis_frame_, pelvis_frame_, &J); +// J_wrt_joints = J.block(0, 6, 3, 16); +// front_covariance.block<3, 3>(3, 3) = +// J_wrt_joints * cov_w_ * J_wrt_joints.transpose(); +// inekf::Kinematics front_frame(2 * i + 1, front_toe_pose, front_covariance); +// measured_kinematics.push_back(front_frame); if (print_info_to_terminal_) { cout << "covariance.block<3, 3>(3, 3) = \n" diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 6793e666dc..c78d2e9860 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,45 +1,46 @@ -FootstepKd: [0.2, 0, 0, 0, 0.6, 0, 0, 0, 0] +FootstepKd: [0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] -LiftoffSwingFootW: [6.322440230563972, 0.0, 0.0, 0.0, 8.993672023870989, 0.0, 0.0, - 0.0, 1.734133659416978] +LiftoffSwingFootW: [7.144166007860841, 0.0, 0.0, 0.0, 8.596750916240502, 0.0, 0.0, + 0.0, 1.4076824740242297] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 75] +PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] -PelvisRotW: [0.5110557066090032, 0.0, 0.0, 0.0, 3.9209573198037515, 0.0, 0.0, 0.0, - 1.2240961503444014] +PelvisRotW: [0.6364374014159452, 0.0, 0.0, 0.0, 4.997119812582846, 0.0, 0.0, 0.0, + 3.460720520954281] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] -SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 50.0] -SwingFootW: [4.808984643590918, 0.0, 0.0, 0.0, 7.587482274675776, 0.0, 0.0, 0.0, 0.1847132353267522] +SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 100.0] +SwingFootW: [7.538167086337688, 0.0, 0.0, 0.0, 6.1943522883064235, 0.0, 0.0, 0.0, + 0.30982473652366876] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.05 -ekf_filter_tau: [0.02633446032692358, 0.0, 0.0, 0.0, 0.07060155525047082, 0.0, 0.0, - 0.0, 0.04205462025236817] +center_line_offset: -0.0928432911384609 +ekf_filter_tau: [0.05, 0.1, 0.01] flight_duration: 0.08 -footstep_offset: -0.06885692335510914 +footstep_offset: -0.012320997242337556 hip_yaw_kd: 1 hip_yaw_kp: 40 -impact_threshold: 0.014728618928927382 -mid_foot_height: 0.03 -mu: 0.6850430136891841 +impact_threshold: 0.0056836061741421945 +leg_rest_length: 0.7428311641420621 +mid_foot_height: 0.025207261756909058 +mu: 0.6 relative_feet: true relative_pelvis: true -rest_length: 0.85 -stance_duration: 0.3 +slip_rest_length: 0.85 +stance_duration: 0.360593719177106 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 -vel_scale_trans_sagital: 0.2 -w_accel: 3.415131452923321e-05 -w_hip_yaw: 1.2329995123069186 +vel_scale_trans_sagital: 0.6 +w_accel: 1.4667819237751144e-05 +w_hip_yaw: 2.372629080594821 w_input: 0.0 -w_input_reg: 0.00015678365454145407 -w_soft_constraint: 265.76721638554557 -w_swing_toe: 0.44285002839273585 +w_input_reg: 0.0028058089238522156 +w_soft_constraint: 196.4314177420529 +w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c367e37230..2d57181637 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -71,11 +71,11 @@ PelvisRotKp: PelvisRotKd: [10., 0, 0, 0, 5., 0, - 0, 0, 0.] + 0, 0, 1.] SwingFootW: [10, 0, 0, 0, 50, 0, - 0, 0, 0.1] + 0, 0, 1] SwingFootKp: [125., 0, 0, 0, 80., 0, @@ -87,11 +87,11 @@ SwingFootKd: LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, - 0, 0, 1] + 0, 0, 2.0] LiftoffSwingFootKp: [50., 0, 0, 0, 50., 0, - 0, 0, 50.] + 0, 0, 25.] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 36336129c5..ff85a4bf57 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -12,7 +12,6 @@ #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" -#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" #include "examples/Cassie/osc_run/osc_running_gains.h" #include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" @@ -111,8 +110,6 @@ int DoMain(int argc, char* argv[]) { auto right_toe = RightToeFront(plant); auto right_heel = RightToeRear(plant); - int nv = plant.num_velocities(); - // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 23939581ef..59db038e41 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -9,6 +9,8 @@ #include "systems/robot_lcm_systems.h" #include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" @@ -113,6 +115,11 @@ int do_main(int argc, char* argv[]) { DrakeVisualizer::AddToBuilder(&builder, scene_graph); + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0/30.0; + auto meshcat = std::make_shared(); + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, scene_graph, meshcat, std::move(params)); // state_receiver->set_publish_period(1.0/30.0); // framerate auto diagram = builder.Build(); From 382160b89fa3f7b044fb347c43053b8a06e22c3e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 4 Apr 2022 15:24:26 -0400 Subject: [PATCH 184/758] small tweaks --- examples/Cassie/cassie_lcm_driven_loop.h | 7 +++---- examples/Cassie/osc_run/learned_osc_running_gains.yaml | 4 ++-- 2 files changed, 5 insertions(+), 6 deletions(-) diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index 68e5b1e5ca..793cfe5bc0 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -265,12 +265,11 @@ class CassieLcmDrivenLoop { << ", but stepping to " << time << std::endl; std::cout << "Difference is too large, resetting " + diagram_name_ + " time.\n"; -// simulator_->get_mutable_context().SetTime(time); -// simulator_->Initialize(); - }else{ - simulator_->AdvanceTo(time); + simulator_->get_mutable_context().SetTime(time); + simulator_->Initialize(); } + simulator_->AdvanceTo(time); if (is_forced_publish_) { // Force-publish via the diagram diagram_ptr_->Publish(diagram_context); diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index c78d2e9860..8d97ce52bc 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,11 +1,11 @@ FootstepKd: [0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] -LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] +LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 25.0] LiftoffSwingFootW: [7.144166007860841, 0.0, 0.0, 0.0, 8.596750916240502, 0.0, 0.0, 0.0, 1.4076824740242297] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] +PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] PelvisRotW: [0.6364374014159452, 0.0, 0.0, 0.0, 4.997119812582846, 0.0, 0.0, 0.0, 3.460720520954281] From aca090b0a96dcfbe14455bc660872e40757d3730 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Apr 2022 13:00:34 -0400 Subject: [PATCH 185/758] small tweaks --- .../Cassie/osc_run/foot_traj_generator.cc | 6 ++-- .../osc_run/learned_osc_running_gains.yaml | 35 +++++++++---------- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 1 + .../osc/operational_space_control.cc | 7 ++-- 5 files changed, 27 insertions(+), 24 deletions(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 3750e4ab3c..226cdc0e97 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -190,11 +190,13 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; - Y[0](2) = -rest_length_; + if(start_pos(2) == 0){ + Y[0](2) = -rest_length_; + } Y[1] = start_pos + 0.85 * footstep_correction; Y[1](2) = -rest_length_ + mid_foot_height_; Y[2] = footstep_correction; - Y[2](2) = -rest_length_ + mid_foot_height_ / 2; + Y[2](2) = -rest_length_; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 8d97ce52bc..ee396d7b76 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,46 +1,45 @@ FootstepKd: [0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 25.0] -LiftoffSwingFootW: [7.144166007860841, 0.0, 0.0, 0.0, 8.596750916240502, 0.0, 0.0, - 0.0, 1.4076824740242297] +LiftoffSwingFootW: [4.898730697522512, 0.0, 0.0, 0.0, 8.875684478053362, 0.0, 0.0, + 0.0, 1.00009386127649773] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] +PelvisRotKd: [1.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] -PelvisRotW: [0.6364374014159452, 0.0, 0.0, 0.0, 4.997119812582846, 0.0, 0.0, 0.0, - 3.460720520954281] +PelvisRotW: [1.8267599797810719, 0.0, 0.0, 0.0, 3.8477334733635615, 0.0, 0.0, 0.0, + 0.34454081183859286] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 100.0] -SwingFootW: [7.538167086337688, 0.0, 0.0, 0.0, 6.1943522883064235, 0.0, 0.0, 0.0, - 0.30982473652366876] +SwingFootW: [7.269772242193404, 0.0, 0.0, 0.0, 8.775354732789877, 0.0, 0.0, 0.0, 4.207052632433897] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: -0.0928432911384609 +center_line_offset: -0.07562414926528944 ekf_filter_tau: [0.05, 0.1, 0.01] flight_duration: 0.08 -footstep_offset: -0.012320997242337556 +footstep_offset: -0.0616278401208792 hip_yaw_kd: 1 hip_yaw_kp: 40 -impact_threshold: 0.0056836061741421945 -leg_rest_length: 0.7428311641420621 -mid_foot_height: 0.025207261756909058 -mu: 0.6 +impact_threshold: 0.031058496546898063 +leg_rest_length: 0.7589273904289638 +mid_foot_height: 0.08 +mu: 0.4 relative_feet: true relative_pelvis: true slip_rest_length: 0.85 -stance_duration: 0.360593719177106 +stance_duration: 0.30294579134157734 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 vel_scale_trans_sagital: 0.6 -w_accel: 1.4667819237751144e-05 -w_hip_yaw: 2.372629080594821 +w_accel: 1.9323569255081364e-05 +w_hip_yaw: 2.404801763917696 w_input: 0.0 -w_input_reg: 0.0028058089238522156 -w_soft_constraint: 196.4314177420529 +w_input_reg: 0.0008379026259671483 +w_soft_constraint: 105.44932351736742 w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 2d57181637..3b1ce30d47 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -42,7 +42,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters footstep_offset: 0 -center_line_offset: -0.07 +center_line_offset: -0.04 mid_foot_height: 0.05 FootstepKd: [ 0.3, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index ff85a4bf57..e88a17508b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -273,6 +273,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_gains.relative_pelvis); + accumulated_state_durations.back() += 0.05; pelvis_trans_traj_generator->SetSLIPParams(osc_gains.slip_rest_length); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "thigh_left", osc_gains.relative_feet, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 4d8e016b2b..dd6d3dcc2f 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -753,13 +753,14 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); + u_sol_->row(0) = 0.95 * u_sol_->row(0) + 0.05 * u_prev_->row(0); + u_sol_->row(1) = 0.95 * u_sol_->row(1) + 0.05 * u_prev_->row(1); *u_prev_ = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { - // std::cerr << "QP did not solve in time!" << std::endl; - // solver_->DisableWarmStart(); - *u_prev_ = VectorXd::Zero(n_u_); +// *u_prev_ = VectorXd::Zero(n_u_); + *u_prev_ = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } solve_time_ = result.get_solver_details().run_time; From 74128213f31291af2f3fc77c52eb5808d2f32c12 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Apr 2022 14:39:52 -0400 Subject: [PATCH 186/758] small plotting changes --- .../pydairlib/analysis/mbp_plotting_utils.py | 11 ++++++++++- .../plot_configs/cassie_running_plot.yaml | 16 ++++++++-------- .../pydairlib/cassie/gym_envs/cassie_gym_test.py | 4 ++-- bindings/pydairlib/cassie/learn_osc_gains.py | 10 +++++----- 4 files changed, 25 insertions(+), 16 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2e2d4b1e30..cd3093bbd7 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -421,4 +421,13 @@ def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): - ps.plot(fsm_time, scale * fsm_signal) + ax = ps.fig.axes[0] + ymin, ymax = ax.get_ylim() + + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 0), alpha=0.1, color=ps.blue) + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 1), alpha=0.1, color=ps.blue) + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 2), alpha=0.1, color=ps.grey) + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 3), alpha=0.1, color=ps.grey) + ax.relim() + + # ps.plot(fsm_time, scale * fsm_signal) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 452a3918ad..7902d9e270 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -11,7 +11,7 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true +plot_floating_base_positions: false plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false @@ -26,17 +26,17 @@ foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: true -plot_qp_solve_time: true +plot_qp_costs: false +plot_qp_solve_time: false plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} +# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# left_ft_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_traj: {'dims': [1], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} + left_ft_traj: {'dims': [2], 'derivs': ['pos']} + right_ft_traj: {'dims': [2], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index e78cd0c246..9be01b0a9e 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index ace52367a9..bb0a21b934 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -32,13 +32,13 @@ def __init__(self, budget, reward_function, visualize=False): self.urdf = 'examples/Cassie/urdf/cassie_v2.urdf' self.controller_urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' - self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' # self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' self.drake_params_folder = "bindings/pydairlib/cassie/optimal_gains/" self.date_prefix = time.strftime("%Y_%m_%d_%H") + self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains_' + self.date_prefix + '.yaml' self.loss_over_time = [] self.default_osc_gains = { @@ -60,7 +60,7 @@ def __init__(self, budget, reward_function, visualize=False): # 'PelvisRotKd': np.array([10, 5, 1]), # 'FootstepKd': np.array([0.2, 0.45, 0]), 'center_line_offset': -0.05, - 'mid_foot_height': 0.05, + # 'mid_foot_height': 0.05, # 'slip_rest_length': 0.85, 'leg_rest_length': 0.73, 'footstep_offset': -0.05, @@ -138,11 +138,11 @@ def learn_gains(self, batch=True): # ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), center_line_offset=ng.p.Scalar(lower=-0.1, upper=0.1), - mid_foot_height=ng.p.Scalar(lower=0.00, upper=0.2), + # mid_foot_height=ng.p.Scalar(lower=0.00, upper=0.2), # slip_rest_length=ng.p.Scalar(lower=0.8, upper=0.9), leg_rest_length=ng.p.Scalar(lower=0.65, upper=0.85), footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), - impact_threshold=ng.p.Scalar(lower=0.0, upper=0.05), + impact_threshold=ng.p.Scalar(lower=0.025, upper=0.05), stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) From 5ac279ffaccf6afce36e29bdbee003b18397a769 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Apr 2022 16:25:48 -0400 Subject: [PATCH 187/758] small changes --- bindings/pydairlib/analysis/log_plotter_cassie.py | 4 +++- bindings/pydairlib/analysis/mbp_plotting_utils.py | 11 ++++------- bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py | 10 +++++----- .../pydairlib/cassie/gym_envs/drake_cassie_gym.py | 2 +- .../pydairlib/cassie/gym_envs/mujoco_cassie_gym.py | 4 ++-- 5 files changed, 15 insertions(+), 16 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 7bae60f233..fae3cafdac 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -80,7 +80,9 @@ def main(): ''' Plot Efforts ''' if plot_config.plot_measured_efforts: - mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + if plot_config.act_names: mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index cd3093bbd7..162da95180 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -424,10 +424,7 @@ def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): ax = ps.fig.axes[0] ymin, ymax = ax.get_ylim() - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 0), alpha=0.1, color=ps.blue) - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 1), alpha=0.1, color=ps.blue) - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 2), alpha=0.1, color=ps.grey) - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == 3), alpha=0.1, color=ps.grey) - ax.relim() - - # ps.plot(fsm_time, scale * fsm_signal) + # uses default color map + for i in np.unique(fsm_signal): + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), alpha=0.2) + ax.relim() \ No newline at end of file diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 9be01b0a9e..155301d529 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -20,7 +20,7 @@ def main(): action = np.zeros(18) - action[2] = 0.25 + action[2] = 1.0 cumulative_reward = 0 while 1: controller_plant = MultibodyPlant(8e-5) @@ -32,8 +32,8 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - # gym_env = DrakeCassieGym(reward_func, visualize=True) - gym_env = MuJoCoCassieGym(reward_func, visualize=True) + gym_env = DrakeCassieGym(reward_func, visualize=True) + # gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) cumulative_reward = gym_env.advance_to(7.5) print(cumulative_reward) diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 1d8d7883d2..758d8b2560 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -99,7 +99,7 @@ def step(self, action=np.zeros(18)): self.sim.get_context())) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp self.cassie_state = CassieEnvState(self.current_time, x, u, action) - reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) + reward = self.reward_func.compute_reward(self.sim_dt, self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() self.prev_cassie_state = self.cassie_state return self.cassie_state, reward diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 794eb46429..2a2b1c513d 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -37,8 +37,8 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic self.current_time = 0.00 self.end_time = 7.5 - self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' - self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' + self.default_model_directory = '/homef/yangwill/workspace/cassie-mujoco-sim/model/' + self.default_model_file = '/homef/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' self.simulator = CassieSim(self.default_model_directory + model_xml) if self.visualize: From 384bff41a5662dd932321ee5e6549f4058f42cfd Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Apr 2022 16:26:31 -0400 Subject: [PATCH 188/758] more changes --- bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py | 8 ++++---- bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 155301d529..8ddeb57f18 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -26,14 +26,14 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - gym_env = DrakeCassieGym(reward_func, visualize=True) - # gym_env = MuJoCoCassieGym(reward_func, visualize=True) + # gym_env = DrakeCassieGym(reward_func, visualize=True) + gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) cumulative_reward = gym_env.advance_to(7.5) print(cumulative_reward) diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 2a2b1c513d..794eb46429 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -37,8 +37,8 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic self.current_time = 0.00 self.end_time = 7.5 - self.default_model_directory = '/homef/yangwill/workspace/cassie-mujoco-sim/model/' - self.default_model_file = '/homef/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' + self.default_model_directory = '/home/yangwill/workspace/cassie-mujoco-sim/model/' + self.default_model_file = '/home/yangwill/workspace/cassie-mujoco-sim/model/cassie.xml' self.simulator = CassieSim(self.default_model_directory + model_xml) if self.visualize: From f3c1e2c73caa8d7008564469d045293623568f70 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 6 Apr 2022 15:50:19 -0400 Subject: [PATCH 189/758] small changes, but going to revert to march 28 commit --- .../plot_configs/cassie_running_plot.yaml | 8 +- examples/Cassie/osc/osc_standing_gains.yaml | 12 +-- .../Cassie/osc_run/osc_running_gains.yaml | 16 ++-- .../Cassie/run_osc_standing_controller.cc | 94 +++++++++++-------- 4 files changed, 73 insertions(+), 57 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 7902d9e270..9b5359f902 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -34,9 +34,9 @@ tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [2], 'derivs': ['pos']} - right_ft_traj: {'dims': [2], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [2], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} + left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} + right_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index bfe01f4c0b..2d6f959278 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -10,10 +10,10 @@ rows: 3 cols: 3 w_input: 0 -w_accel: 0.00000001 +w_accel: 0.00001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.001] + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, @@ -25,10 +25,10 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, w_soft_constraint: 100 w_input_reg: 0.001 impact_threshold: 0.025 -mu: 0.6 -HipYawKp: 10 +mu: 0.2 +HipYawKp: 100 HipYawKd: 1 -HipYawW: 0 +HipYawW: 100 CoMW: [20, 0, 0, 0, 20, 0, diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 3b1ce30d47..ee084f0d3b 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -26,10 +26,10 @@ vel_scale_trans_sagital: 0.6 vel_scale_trans_lateral: -0.15 # SLIP parameters -slip_rest_length: 0.85 -leg_rest_length: 0.73 -stance_duration: 0.29 -flight_duration: 0.08 +slip_rest_length: 0.9 +leg_rest_length: 0.75 +stance_duration: 0.30 +flight_duration: 0.10 mu: 0.6 @@ -43,10 +43,10 @@ hip_yaw_kd: 1 # Foot placement parameters footstep_offset: 0 center_line_offset: -0.04 -mid_foot_height: 0.05 +mid_foot_height: 0.1 FootstepKd: - [ 0.3, 0, 0, - 0, 0.4, 0, + [ 0.25, 0, 0, + 0, 0.25, 0, 0, 0, 0] PelvisW: [0.1, 0, 0, @@ -55,7 +55,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 85] + 0, 0, 50] PelvisKd: [ 1, 0, 0, 0, 0, 0, diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 3be21af121..38c18d103e 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -8,6 +8,7 @@ #include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" #include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/com_tracking_data.h" @@ -47,6 +48,7 @@ using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; +using multibody::FixedJointEvaluator; DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "LCM channel for receiving state. " @@ -78,28 +80,23 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Build Cassie MBP - drake::multibody::MultibodyPlant plant_w_springs(0.0); - addCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, + drake::multibody::MultibodyPlant plant(0.0); + addCassieMultibody(&plant, nullptr, true /*floating base*/, "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); - plant_w_springs.Finalize(); + plant.Finalize(); // Build fix-spring Cassie MBP - drake::multibody::MultibodyPlant plant_wo_springs(0.0); - addCassieMultibody(&plant_wo_springs, nullptr, true, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", false, - false); - plant_wo_springs.Finalize(); - auto context_w_spr = plant_w_springs.CreateDefaultContext(); - auto context_wo_spr = plant_wo_springs.CreateDefaultContext(); + auto context_w_spr = plant.CreateDefaultContext(); + auto context_wo_spr = plant.CreateDefaultContext(); // Get contact frames and position (doesn't matter whether we use // plant_w_springs or plant_wo_springs because the contact frames exit in both // plants) - auto left_toe = LeftToeFront(plant_wo_springs); - auto left_heel = LeftToeRear(plant_wo_springs); - auto right_toe = RightToeFront(plant_wo_springs); - auto right_heel = RightToeRear(plant_wo_springs); + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); // Build the controller diagram DiagramBuilder builder; @@ -143,7 +140,7 @@ int DoMain(int argc, char* argv[]) { // Create state receiver. auto state_receiver = - builder.AddSystem(plant_w_springs); + builder.AddSystem(plant); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( @@ -154,7 +151,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = - builder.AddSystem(plant_w_springs); + builder.AddSystem(plant); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -176,11 +173,11 @@ int DoMain(int argc, char* argv[]) { std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, + plant, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); auto pelvis_rot_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, + plant, context_w_spr.get(), feet_contact_points, "pelvis_rot_traj"); builder.Connect(state_receiver->get_output_port(0), com_traj_generator->get_input_port_state()); @@ -195,44 +192,64 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_springs, plant_wo_springs, context_w_spr.get(), + plant, plant, context_w_spr.get(), context_wo_spr.get(), false, FLAGS_print_osc, FLAGS_qp_time_limit); // Distance constraint - multibody::KinematicEvaluatorSet evaluators(plant_wo_springs); - auto left_loop = LeftLoopClosureEvaluator(plant_wo_springs); - auto right_loop = RightLoopClosureEvaluator(plant_wo_springs); + multibody::KinematicEvaluatorSet evaluators(plant); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); - osc->AddKinematicConstraint(&evaluators); // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), + plant, left_toe.first, left_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - osc->AddContactPoint(&left_toe_evaluator); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, left_heel.first, left_heel.second, Matrix3d::Identity(), + plant, left_heel.first, left_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddContactPoint(&left_heel_evaluator); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, right_toe.first, right_toe.second, Matrix3d::Identity(), + plant, right_toe.first, right_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - osc->AddContactPoint(&right_toe_evaluator); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, right_heel.first, right_heel.second, + plant, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + osc->AddContactPoint(&left_toe_evaluator); + osc->AddContactPoint(&left_heel_evaluator); + osc->AddContactPoint(&right_toe_evaluator); osc->AddContactPoint(&right_heel_evaluator); + + auto pos_idx_map = multibody::makeNameToPositionsMap(plant); + auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + osc->AddKinematicConstraint(&evaluators); + // Cost - int n_v = plant_wo_springs.num_velocities(); + int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); -// osc->SetLambdaHolonomicRegularizationWeight(1e-5 * -// gains.W_lambda_h_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing @@ -240,8 +257,8 @@ int DoMain(int argc, char* argv[]) { // W_com * FLAGS_cost_weight_multiplier, // plant_w_springs, plant_wo_springs); auto center_of_mass_traj = std::make_unique( - "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, - plant_w_springs, plant_wo_springs); + "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, plant, + plant); center_of_mass_traj->AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); @@ -250,8 +267,7 @@ int DoMain(int argc, char* argv[]) { // Pelvis rotation tracking auto pelvis_rot_traj = std::make_unique( "pelvis_rot_traj", K_p_pelvis, K_d_pelvis, - W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, - plant_wo_springs); + W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); pelvis_rot_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_rot_traj)); @@ -265,11 +281,11 @@ int DoMain(int argc, char* argv[]) { auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant_w_springs, plant_wo_springs); + plant, plant); auto right_hip_yaw_traj = std::make_unique( "right_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant_w_springs, plant_wo_springs); + plant, plant); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); From 7c7ad6aa34805d2e6314d7a0b6c7bc8adae97572 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 6 Apr 2022 16:10:34 -0400 Subject: [PATCH 190/758] cherry picking important commits --- .../pydairlib/analysis/log_plotter_cassie.py | 5 +- .../pydairlib/analysis/mbp_plotting_utils.py | 8 +- .../plot_configs/cassie_running_plot.yaml | 16 ++-- .../cassie/gym_envs/cassie_gym_test.py | 8 +- .../cassie/gym_envs/drake_cassie_gym.py | 2 +- .../cassie/gym_envs/mujoco_cassie_gym.py | 26 +++-- .../cassie/gym_envs/reward_osudrl.py | 54 +++++++++-- bindings/pydairlib/cassie/learn_osc_gains.py | 46 ++++----- examples/Cassie/BUILD.bazel | 1 - examples/Cassie/cassie_lcm_driven_loop.h | 7 +- examples/Cassie/cassie_state_estimator.cc | 20 ++-- examples/Cassie/osc/osc_standing_gains.yaml | 12 +-- .../osc_run/learned_osc_running_gains.yaml | 50 +++++----- examples/Cassie/run_osc_running_controller.cc | 3 - .../Cassie/run_osc_standing_controller.cc | 94 +++++++++++-------- examples/Cassie/run_pd_controller.cc | 2 - examples/Cassie/visualizer.cc | 7 ++ 17 files changed, 221 insertions(+), 140 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 2eab85d3d4..fae3cafdac 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -80,7 +80,9 @@ def main(): ''' Plot Efforts ''' if plot_config.plot_measured_efforts: - mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + if plot_config.act_names: mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, @@ -113,6 +115,7 @@ def main(): plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, foot_frames, pts, dims) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) if plot_config.plot_qp_solve_time: mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2e2d4b1e30..162da95180 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -421,4 +421,10 @@ def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): - ps.plot(fsm_time, scale * fsm_signal) + ax = ps.fig.axes[0] + ymin, ymax = ax.get_ylim() + + # uses default color map + for i in np.unique(fsm_signal): + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), alpha=0.2) + ax.relim() \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 452a3918ad..9b5359f902 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -11,7 +11,7 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true +plot_floating_base_positions: false plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false @@ -26,17 +26,17 @@ foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: true -plot_qp_solve_time: true +plot_qp_costs: false +plot_qp_solve_time: false plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [2], 'derivs': ['pos', 'vel']} +# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# left_ft_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_traj: {'dims': [1], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [1], 'derivs': ['pos']} + left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} + right_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} + right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index c95c01d3f6..8ddeb57f18 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,7 +9,7 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/new_learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' @@ -20,14 +20,14 @@ def main(): action = np.zeros(18) - action[2] = 0.25 + action[2] = 1.0 cumulative_reward = 0 while 1: controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 1d8d7883d2..758d8b2560 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -99,7 +99,7 @@ def step(self, action=np.zeros(18)): self.sim.get_context())) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp self.cassie_state = CassieEnvState(self.current_time, x, u, action) - reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) + reward = self.reward_func.compute_reward(self.sim_dt, self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() self.prev_cassie_state = self.cassie_state return self.cassie_state, reward diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 3e974d5913..78dadc805e 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -45,8 +45,8 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic ''' Copied from apex/cassie.py ''' - self.max_simrate = 1.2 * self.gym_dt - self.min_simrate = 0.8 * self.gym_dt + self.max_simrate = 1.3 * self.gym_dt + self.min_simrate = 0.7 * self.gym_dt self.dynamics_randomization = dynamics_randomization self.dynamics_randomization = dynamics_randomization self.slope_rand = dynamics_randomization @@ -108,6 +108,16 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic 'hip_pitch_right_motor': 7, 'knee_right_motor': 8, 'toe_right_motor': 9} + # sim states + self.l_foot_frc = 0 + self.r_foot_frc = 0 + foot_pos = np.zeros(6) + self.l_foot_pos = np.zeros(3) + self.r_foot_pos = np.zeros(3) + self.l_foot_orient_cost = 0 + self.r_foot_orient_cost = 0 + self.neutral_foot_orient = np.array( + [-0.24790886454547323, -0.24679713195445646, -0.6609396704367185, 0.663921021343526]) def make(self, controller): self.builder = DiagramBuilder() @@ -181,21 +191,26 @@ def step(self, action=np.zeros(18)): u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) self.drake_sim.AdvanceTo(next_timestep) + self.reward_func.reset_clock_reward() while self.simulator.time() < next_timestep: self.simulator.step(cassie_in) + foot_pos = self.simulator.foot_pos() + self.reward_func.update_clock_reward(self.simulator.get_foot_forces(), foot_pos, + self.simulator.xquat("left-foot"), self.simulator.xquat("right-foot")) + if self.visualize: self.cassie_vis.draw(self.simulator) self.current_time = next_timestep t = self.simulator.time() - q = self.simulator.qpos() - v = self.simulator.qvel() + q = np.copy(self.simulator.qpos()) + v = np.copy(self.simulator.qvel()) q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) self.current_time = t x = np.hstack((q, v)) x = reexpress_state_local_to_global_omega(x) self.cassie_state = CassieEnvState(self.current_time, x, u, action) - reward = self.reward_func.compute_reward(self.cassie_state, self.prev_cassie_state) + reward = self.reward_func.compute_reward(timestep, self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() self.prev_cassie_state = self.cassie_state return self.cassie_state, reward @@ -368,7 +383,6 @@ def randomize_sim_params(self): self.motor_encoder_noise = np.zeros(10) self.joint_encoder_noise = np.zeros(6) - def free_sim(self): del self.simulator del self.cassie_vis diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index 52ac9f1f3d..7f68d4855c 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -1,4 +1,5 @@ import numpy as np +import copy import matplotlib.pyplot as plt from scipy.spatial.transform import Rotation as R import pickle @@ -21,7 +22,14 @@ def __init__(self, weights_filename=None): self.neutral_foot_orient = np.array([-0.24790886454547323, -0.24679713195445646, -0.6609396704367185, 0.663921021343526]) self.l_foot_orient = 0 self.r_foot_orient = 0 - + self.l_foot_frc = 0 + self.r_foot_frc = 0 + self.l_foot_pos = np.zeros(3) + self.r_foot_pos = np.zeros(3) + self.l_foot_vel = np.zeros(3) + self.r_foot_vel = np.zeros(3) + self.l_foot_orient_cost = 0 + self.r_foot_orient_cost = 0 return @@ -29,9 +37,31 @@ def load_weights(self, filename): with open(LOSS_WEIGHTS_FOLDER + filename + '.pkl', 'rb') as f: return pickle.load(f) - def compute_reward(self, cassie_env_state, prev_cassie_env_state): - - + def reset_clock_reward(self): + self.l_foot_frc = 0 + self.r_foot_frc = 0 + foot_pos = np.zeros(6) + self.l_foot_pos = np.zeros(3) + self.r_foot_pos = np.zeros(3) + self.l_foot_vel = np.zeros(3) + self.r_foot_vel = np.zeros(3) + self.l_foot_orient_cost = 0 + self.r_foot_orient_cost = 0 + + def update_clock_reward(self, foot_forces, foot_pos, l_foot_quat, r_foot_quat): + prev_foot = copy.deepcopy(np.hstack((self.l_foot_pos, self.r_foot_pos))) + self.l_foot_frc += foot_forces[0] + self.r_foot_frc += foot_forces[1] + # Relative Foot Position tracking + self.l_foot_pos += foot_pos[0:3] + self.r_foot_pos += foot_pos[3:6] + # Foot Orientation Cost + self.l_foot_orient_cost += (1 - np.inner(self.neutral_foot_orient, l_foot_quat) ** 2) + self.r_foot_orient_cost += (1 - np.inner(self.neutral_foot_orient, r_foot_quat) ** 2) + self.l_foot_vel = (foot_pos[0:3] - prev_foot[0:3]) / 0.0005 + self.r_foot_vel = (foot_pos[3:6] - prev_foot[3:6]) / 0.0005 + + def compute_reward(self, timestep, cassie_env_state, prev_cassie_env_state): pos = cassie_env_state.get_positions() vel = cassie_env_state.get_velocities() com_pos = cassie_env_state.get_fb_positions() @@ -47,17 +77,27 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): orient_targ = np.array([1, 0, 0, 0]) com_orient_error = 0 - hip_yaw_penalty = 0 + # hip_yaw_penalty = 0 com_vel_error = 0 straight_diff = 0 foot_vel_error = 0 foot_frc_error = 0 + foot_orient_error = 0 + + + self.l_foot_frc /= timestep + self.r_foot_frc /= timestep + self.l_foot_pos /= timestep + self.r_foot_pos /= timestep + self.l_foot_orient_cost /= timestep + self.r_foot_orient_cost /= timestep # com orient error com_orient_error += 10 * (1 - np.inner(orient_targ, cassie_env_state.get_orientations()) ** 2) # foot orient error # hip_yaw_penalty += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) - hip_yaw_penalty += np.abs(joint_vel[1]) + np.abs(joint_vel[8]) + foot_orient_error += 10 * (self.l_foot_orient_cost + self.r_foot_orient_cost) + # hip_yaw_penalty += np.abs(joint_vel[1]) + np.abs(joint_vel[8]) # com vel error com_vel_error += np.linalg.norm(com_vel[0] - des_forward_vel) @@ -77,7 +117,7 @@ def compute_reward(self, cassie_env_state, prev_cassie_env_state): torque_penalty = 0.5 * (sum(np.abs(prev_torques - torques)) / len(torques)) - reward = 0.200 * np.exp(-(com_orient_error + hip_yaw_penalty)) + \ + reward = 0.200 * np.exp(-(com_orient_error + foot_orient_error)) + \ 0.150 * np.exp(-pelvis_motion) + \ 0.150 * np.exp(-com_vel_error) + \ 0.100 * np.exp(-hip_roll_penalty) + \ diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 54c5ee74c0..bb0a21b934 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -34,38 +34,39 @@ def __init__(self, budget, reward_function, visualize=False): self.controller_urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' # self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - self.osc_running_gains_filename = 'examples/Cassie/osc_run/new_learned_osc_running_gains.yaml' self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' self.drake_params_folder = "bindings/pydairlib/cassie/optimal_gains/" self.date_prefix = time.strftime("%Y_%m_%d_%H") + self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains_' + self.date_prefix + '.yaml' self.loss_over_time = [] self.default_osc_gains = { - - 'mu': 0.6, + 'w_accel': 1e-5, + 'w_soft_constraint': 100, + 'w_input_reg': 0.001, + # 'w_swing_toe': 1, + # 'mu': 0.6, 'w_hip_yaw': 2.5, 'PelvisRotW': np.array([1, 2.5, 0.1]), 'SwingFootW': np.array([10, 10, 1]), + # 'SwingFootKp': np.array([125, 80, 50]), + # 'SwingFootKd': np.array([5, 5, 1]), 'LiftoffSwingFootW': np.array([0.1, 10, 1]), - 'w_accel': 1e-5, - 'w_soft_constraint': 100, - 'w_input_reg': 0.001, - 'w_swing_toe': 1, # 'hip_yaw_kp': 40, # 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), # 'PelvisRotKd': np.array([10, 5, 1]), - 'SwingFootKp': np.array([125, 80, 50]), - 'SwingFootKd': np.array([5, 5, 1]), # 'FootstepKd': np.array([0.2, 0.45, 0]), - # 'center_line_offset': 0.03, - # 'rest_length': 0.85, + 'center_line_offset': -0.05, + # 'mid_foot_height': 0.05, + # 'slip_rest_length': 0.85, + 'leg_rest_length': 0.73, 'footstep_offset': -0.05, 'impact_threshold': 0.025, # 'ekf_filter_tau': np.array([0.05, 0.1, 0.01]), - # 'stance_duration': 0.30, + 'stance_duration': 0.30, # 'flight_duration': 0.08, } @@ -122,8 +123,8 @@ def learn_gains(self, batch=True): w_accel=ng.p.Log(lower=1e-5, upper=1e-1), w_soft_constraint=ng.p.Log(lower=1.0, upper=1000.0), w_input_reg=ng.p.Log(lower=1e-5, upper=1e-1), - w_swing_toe=ng.p.Log(lower=1e-1, upper=1e2), - mu=ng.p.Scalar(lower=0.4, upper=1.0), + # w_swing_toe=ng.p.Log(lower=1e-1, upper=1e2), + # mu=ng.p.Scalar(lower=0.4, upper=1.0), w_hip_yaw=ng.p.Scalar(lower=0, upper=10), # hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), @@ -131,16 +132,18 @@ def learn_gains(self, batch=True): PelvisRotW=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), SwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), - SwingFootKp=ng.p.Array(lower=25., upper=200., shape=(3,)), - SwingFootKd=ng.p.Array(lower=0.1, upper=10., shape=(3,)), + # SwingFootKp=ng.p.Array(lower=25., upper=200., shape=(3,)), + # SwingFootKd=ng.p.Array(lower=0.1, upper=10., shape=(3,)), LiftoffSwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), # ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - # center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), - # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + center_line_offset=ng.p.Scalar(lower=-0.1, upper=0.1), + # mid_foot_height=ng.p.Scalar(lower=0.00, upper=0.2), + # slip_rest_length=ng.p.Scalar(lower=0.8, upper=0.9), + leg_rest_length=ng.p.Scalar(lower=0.65, upper=0.85), footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), - impact_threshold=ng.p.Scalar(lower=0.0, upper=0.05), - # stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), + impact_threshold=ng.p.Scalar(lower=0.025, upper=0.05), + stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) self.loss_over_time = [] @@ -166,9 +169,8 @@ def learn_gains(self, batch=True): optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) # optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_30_16_1000', optimizer.drake_params_folder).value + optimal_params = optimizer.load_params('2022_04_01_13_1000', optimizer.drake_params_folder).value optimizer.write_params(optimal_params) reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') - import pdb; pdb.set_trace() plt.plot(reward_over_time) plt.show() diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 8e139b7241..e500aca4b5 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -177,7 +177,6 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//common", - "//examples/Cassie/diagrams:diagrams", "//systems:robot_lcm_systems", "//systems/controllers", "//systems/controllers:pd_config_lcm", diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index 68e5b1e5ca..793cfe5bc0 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -265,12 +265,11 @@ class CassieLcmDrivenLoop { << ", but stepping to " << time << std::endl; std::cout << "Difference is too large, resetting " + diagram_name_ + " time.\n"; -// simulator_->get_mutable_context().SetTime(time); -// simulator_->Initialize(); - }else{ - simulator_->AdvanceTo(time); + simulator_->get_mutable_context().SetTime(time); + simulator_->Initialize(); } + simulator_->AdvanceTo(time); if (is_forced_publish_) { // Force-publish via the diagram diagram_ptr_->Publish(diagram_context); diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 55c4f3f0aa..1629dd2ce1 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -778,9 +778,9 @@ EventStatus CassieStateEstimator::Update( std::vector> contacts; contacts.push_back(std::pair(0, left_contact)); - contacts.push_back(std::pair(1, left_contact)); +// contacts.push_back(std::pair(1, left_contact)); contacts.push_back(std::pair(2, right_contact)); - contacts.push_back(std::pair(3, right_contact)); +// contacts.push_back(std::pair(3, right_contact)); ekf.setContacts(contacts); // Step 4 - EKF (measurement step) @@ -834,14 +834,14 @@ EventStatus CassieStateEstimator::Update( J_wrt_joints * cov_w_ * J_wrt_joints.transpose(); inekf::Kinematics rear_frame(2 * i, rear_toe_pose, rear_covariance); measured_kinematics.push_back(rear_frame); - plant_.CalcJacobianTranslationalVelocity( - *context_, JacobianWrtVariable::kV, *toe_frames_[i], - front_contact_disp_, pelvis_frame_, pelvis_frame_, &J); - J_wrt_joints = J.block(0, 6, 3, 16); - front_covariance.block<3, 3>(3, 3) = - J_wrt_joints * cov_w_ * J_wrt_joints.transpose(); - inekf::Kinematics front_frame(2 * i + 1, front_toe_pose, front_covariance); - measured_kinematics.push_back(front_frame); +// plant_.CalcJacobianTranslationalVelocity( +// *context_, JacobianWrtVariable::kV, *toe_frames_[i], +// front_contact_disp_, pelvis_frame_, pelvis_frame_, &J); +// J_wrt_joints = J.block(0, 6, 3, 16); +// front_covariance.block<3, 3>(3, 3) = +// J_wrt_joints * cov_w_ * J_wrt_joints.transpose(); +// inekf::Kinematics front_frame(2 * i + 1, front_toe_pose, front_covariance); +// measured_kinematics.push_back(front_frame); if (print_info_to_terminal_) { cout << "covariance.block<3, 3>(3, 3) = \n" diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index bfe01f4c0b..2d6f959278 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -10,10 +10,10 @@ rows: 3 cols: 3 w_input: 0 -w_accel: 0.00000001 +w_accel: 0.00001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.001] + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, @@ -25,10 +25,10 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, w_soft_constraint: 100 w_input_reg: 0.001 impact_threshold: 0.025 -mu: 0.6 -HipYawKp: 10 +mu: 0.2 +HipYawKp: 100 HipYawKd: 1 -HipYawW: 0 +HipYawW: 100 CoMW: [20, 0, 0, 0, 20, 0, diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 6793e666dc..ee396d7b76 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,45 +1,45 @@ -FootstepKd: [0.2, 0, 0, 0, 0.6, 0, 0, 0, 0] +FootstepKd: [0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] -LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0] -LiftoffSwingFootW: [6.322440230563972, 0.0, 0.0, 0.0, 8.993672023870989, 0.0, 0.0, - 0.0, 1.734133659416978] +LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 25.0] +LiftoffSwingFootW: [4.898730697522512, 0.0, 0.0, 0.0, 8.875684478053362, 0.0, 0.0, + 0.0, 1.00009386127649773] PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 75] -PelvisRotKd: [10.0, 0, 0, 0, 5.0, 0, 0, 0, 0.0] +PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] +PelvisRotKd: [1.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] -PelvisRotW: [0.5110557066090032, 0.0, 0.0, 0.0, 3.9209573198037515, 0.0, 0.0, 0.0, - 1.2240961503444014] +PelvisRotW: [1.8267599797810719, 0.0, 0.0, 0.0, 3.8477334733635615, 0.0, 0.0, 0.0, + 0.34454081183859286] PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] -SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 50.0] -SwingFootW: [4.808984643590918, 0.0, 0.0, 0.0, 7.587482274675776, 0.0, 0.0, 0.0, 0.1847132353267522] +SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 100.0] +SwingFootW: [7.269772242193404, 0.0, 0.0, 0.0, 8.775354732789877, 0.0, 0.0, 0.0, 4.207052632433897] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: 0.05 -ekf_filter_tau: [0.02633446032692358, 0.0, 0.0, 0.0, 0.07060155525047082, 0.0, 0.0, - 0.0, 0.04205462025236817] +center_line_offset: -0.07562414926528944 +ekf_filter_tau: [0.05, 0.1, 0.01] flight_duration: 0.08 -footstep_offset: -0.06885692335510914 +footstep_offset: -0.0616278401208792 hip_yaw_kd: 1 hip_yaw_kp: 40 -impact_threshold: 0.014728618928927382 -mid_foot_height: 0.03 -mu: 0.6850430136891841 +impact_threshold: 0.031058496546898063 +leg_rest_length: 0.7589273904289638 +mid_foot_height: 0.08 +mu: 0.4 relative_feet: true relative_pelvis: true -rest_length: 0.85 -stance_duration: 0.3 +slip_rest_length: 0.85 +stance_duration: 0.30294579134157734 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 -vel_scale_trans_sagital: 0.2 -w_accel: 3.415131452923321e-05 -w_hip_yaw: 1.2329995123069186 +vel_scale_trans_sagital: 0.6 +w_accel: 1.9323569255081364e-05 +w_hip_yaw: 2.404801763917696 w_input: 0.0 -w_input_reg: 0.00015678365454145407 -w_soft_constraint: 265.76721638554557 -w_swing_toe: 0.44285002839273585 +w_input_reg: 0.0008379026259671483 +w_soft_constraint: 105.44932351736742 +w_swing_toe: 1 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b9be4035fc..5e84963d00 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -12,7 +12,6 @@ #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" -#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" #include "examples/Cassie/osc_run/osc_running_gains.h" #include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" @@ -111,8 +110,6 @@ int DoMain(int argc, char* argv[]) { auto right_toe = RightToeFront(plant); auto right_heel = RightToeRear(plant); - int nv = plant.num_velocities(); - // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 3be21af121..38c18d103e 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -8,6 +8,7 @@ #include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" #include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/com_tracking_data.h" @@ -47,6 +48,7 @@ using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; +using multibody::FixedJointEvaluator; DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "LCM channel for receiving state. " @@ -78,28 +80,23 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Build Cassie MBP - drake::multibody::MultibodyPlant plant_w_springs(0.0); - addCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, + drake::multibody::MultibodyPlant plant(0.0); + addCassieMultibody(&plant, nullptr, true /*floating base*/, "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); - plant_w_springs.Finalize(); + plant.Finalize(); // Build fix-spring Cassie MBP - drake::multibody::MultibodyPlant plant_wo_springs(0.0); - addCassieMultibody(&plant_wo_springs, nullptr, true, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", false, - false); - plant_wo_springs.Finalize(); - auto context_w_spr = plant_w_springs.CreateDefaultContext(); - auto context_wo_spr = plant_wo_springs.CreateDefaultContext(); + auto context_w_spr = plant.CreateDefaultContext(); + auto context_wo_spr = plant.CreateDefaultContext(); // Get contact frames and position (doesn't matter whether we use // plant_w_springs or plant_wo_springs because the contact frames exit in both // plants) - auto left_toe = LeftToeFront(plant_wo_springs); - auto left_heel = LeftToeRear(plant_wo_springs); - auto right_toe = RightToeFront(plant_wo_springs); - auto right_heel = RightToeRear(plant_wo_springs); + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); // Build the controller diagram DiagramBuilder builder; @@ -143,7 +140,7 @@ int DoMain(int argc, char* argv[]) { // Create state receiver. auto state_receiver = - builder.AddSystem(plant_w_springs); + builder.AddSystem(plant); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( @@ -154,7 +151,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = - builder.AddSystem(plant_w_springs); + builder.AddSystem(plant); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -176,11 +173,11 @@ int DoMain(int argc, char* argv[]) { std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, + plant, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); auto pelvis_rot_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, + plant, context_w_spr.get(), feet_contact_points, "pelvis_rot_traj"); builder.Connect(state_receiver->get_output_port(0), com_traj_generator->get_input_port_state()); @@ -195,44 +192,64 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_springs, plant_wo_springs, context_w_spr.get(), + plant, plant, context_w_spr.get(), context_wo_spr.get(), false, FLAGS_print_osc, FLAGS_qp_time_limit); // Distance constraint - multibody::KinematicEvaluatorSet evaluators(plant_wo_springs); - auto left_loop = LeftLoopClosureEvaluator(plant_wo_springs); - auto right_loop = RightLoopClosureEvaluator(plant_wo_springs); + multibody::KinematicEvaluatorSet evaluators(plant); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); - osc->AddKinematicConstraint(&evaluators); // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), + plant, left_toe.first, left_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - osc->AddContactPoint(&left_toe_evaluator); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, left_heel.first, left_heel.second, Matrix3d::Identity(), + plant, left_heel.first, left_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddContactPoint(&left_heel_evaluator); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, right_toe.first, right_toe.second, Matrix3d::Identity(), + plant, right_toe.first, right_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - osc->AddContactPoint(&right_toe_evaluator); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, right_heel.first, right_heel.second, + plant, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + osc->AddContactPoint(&left_toe_evaluator); + osc->AddContactPoint(&left_heel_evaluator); + osc->AddContactPoint(&right_toe_evaluator); osc->AddContactPoint(&right_heel_evaluator); + + auto pos_idx_map = multibody::makeNameToPositionsMap(plant); + auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + osc->AddKinematicConstraint(&evaluators); + // Cost - int n_v = plant_wo_springs.num_velocities(); + int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); -// osc->SetLambdaHolonomicRegularizationWeight(1e-5 * -// gains.W_lambda_h_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing @@ -240,8 +257,8 @@ int DoMain(int argc, char* argv[]) { // W_com * FLAGS_cost_weight_multiplier, // plant_w_springs, plant_wo_springs); auto center_of_mass_traj = std::make_unique( - "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, - plant_w_springs, plant_wo_springs); + "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, plant, + plant); center_of_mass_traj->AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); @@ -250,8 +267,7 @@ int DoMain(int argc, char* argv[]) { // Pelvis rotation tracking auto pelvis_rot_traj = std::make_unique( "pelvis_rot_traj", K_p_pelvis, K_d_pelvis, - W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, - plant_wo_springs); + W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); pelvis_rot_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_rot_traj)); @@ -265,11 +281,11 @@ int DoMain(int argc, char* argv[]) { auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant_w_springs, plant_wo_springs); + plant, plant); auto right_hip_yaw_traj = std::make_unique( "right_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant_w_springs, plant_wo_springs); + plant, plant); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); diff --git a/examples/Cassie/run_pd_controller.cc b/examples/Cassie/run_pd_controller.cc index 6309ddf033..c6e2e2c49f 100644 --- a/examples/Cassie/run_pd_controller.cc +++ b/examples/Cassie/run_pd_controller.cc @@ -5,8 +5,6 @@ #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" -#include "examples/Cassie/diagrams/cassie_sim_diagram.h" -#include "examples/Cassie/diagrams/osc_running_controller_diagram.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 23939581ef..59db038e41 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -9,6 +9,8 @@ #include "systems/robot_lcm_systems.h" #include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" @@ -113,6 +115,11 @@ int do_main(int argc, char* argv[]) { DrakeVisualizer::AddToBuilder(&builder, scene_graph); + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0/30.0; + auto meshcat = std::make_shared(); + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, scene_graph, meshcat, std::move(params)); // state_receiver->set_publish_period(1.0/30.0); // framerate auto diagram = builder.Build(); From eaea8fdcdc47322831249b34bb9f84d9ab45e4fe Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 29 Mar 2022 10:05:34 -0400 Subject: [PATCH 191/758] trying to revert --- bindings/pydairlib/cassie/learn_osc_gains.py | 66 ++++------- .../osc_running_controller_diagram.cc | 24 ++-- examples/Cassie/osc/osc_standing_gains.yaml | 46 +++---- .../Cassie/osc_run/foot_traj_generator.cc | 2 +- .../osc_run/learned_osc_running_gains.yaml | 74 ++++++------ .../Cassie/osc_run/osc_running_gains.yaml | 63 +++++----- examples/Cassie/run_osc_running_controller.cc | 38 +++--- .../Cassie/run_osc_standing_controller.cc | 112 +++++++----------- .../osc/trans_space_tracking_data.cc | 8 +- 9 files changed, 197 insertions(+), 236 deletions(-) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index bb0a21b934..160a5da8e8 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -32,42 +32,32 @@ def __init__(self, budget, reward_function, visualize=False): self.urdf = 'examples/Cassie/urdf/cassie_v2.urdf' self.controller_urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' - self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - # self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + self.default_osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' self.osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' self.drake_params_folder = "bindings/pydairlib/cassie/optimal_gains/" self.date_prefix = time.strftime("%Y_%m_%d_%H") - self.osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains_' + self.date_prefix + '.yaml' self.loss_over_time = [] self.default_osc_gains = { - 'w_accel': 1e-5, 'w_soft_constraint': 100, 'w_input_reg': 0.001, - # 'w_swing_toe': 1, - # 'mu': 0.6, + 'mu': 0.6, 'w_hip_yaw': 2.5, - 'PelvisRotW': np.array([1, 2.5, 0.1]), - 'SwingFootW': np.array([10, 10, 1]), - # 'SwingFootKp': np.array([125, 80, 50]), - # 'SwingFootKd': np.array([5, 5, 1]), - 'LiftoffSwingFootW': np.array([0.1, 10, 1]), - # 'hip_yaw_kp': 40, + 'hip_yaw_kp': 40, # 'PelvisKp': np.array([0, 0, 85]), # 'PelvisKd': np.array([1, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), - # 'PelvisRotKd': np.array([10, 5, 1]), - # 'FootstepKd': np.array([0.2, 0.45, 0]), - 'center_line_offset': -0.05, - # 'mid_foot_height': 0.05, - # 'slip_rest_length': 0.85, - 'leg_rest_length': 0.73, + 'PelvisRotKd': np.array([10, 5, 1]), + 'SwingFootKp': np.array([125, 80, 50]), + 'SwingFootKd': np.array([5, 5, 1]), + 'FootstepKd': np.array([0.2, 0.45, 0]), + 'center_line_offset': 0.03, + # 'rest_length': 0.85, 'footstep_offset': -0.05, - 'impact_threshold': 0.025, - # 'ekf_filter_tau': np.array([0.05, 0.1, 0.01]), 'stance_duration': 0.30, - # 'flight_duration': 0.08, + 'flight_duration': 0.08, } def save_params(self, folder, params, budget): @@ -120,31 +110,23 @@ def get_single_loss(self, params): def learn_gains(self, batch=True): self.default_params = ng.p.Dict( - w_accel=ng.p.Log(lower=1e-5, upper=1e-1), w_soft_constraint=ng.p.Log(lower=1.0, upper=1000.0), w_input_reg=ng.p.Log(lower=1e-5, upper=1e-1), - # w_swing_toe=ng.p.Log(lower=1e-1, upper=1e2), - # mu=ng.p.Scalar(lower=0.4, upper=1.0), + mu=ng.p.Scalar(lower=0.4, upper=1.0), w_hip_yaw=ng.p.Scalar(lower=0, upper=10), - # hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), + hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), - PelvisRotW=ng.p.Array(lower=0., upper=10., shape=(3,)), - # PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), - SwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), - # SwingFootKp=ng.p.Array(lower=25., upper=200., shape=(3,)), - # SwingFootKd=ng.p.Array(lower=0.1, upper=10., shape=(3,)), - LiftoffSwingFootW=ng.p.Array(lower=0., upper=10., shape=(3,)), - # ekf_filter_tau=ng.p.Array(lower=0., upper=0.1, shape=(3,)), - # FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - center_line_offset=ng.p.Scalar(lower=-0.1, upper=0.1), - # mid_foot_height=ng.p.Scalar(lower=0.00, upper=0.2), - # slip_rest_length=ng.p.Scalar(lower=0.8, upper=0.9), - leg_rest_length=ng.p.Scalar(lower=0.65, upper=0.85), + # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), + PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), + SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), + FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), + center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), + # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), - impact_threshold=ng.p.Scalar(lower=0.025, upper=0.05), stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), - # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), + flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) self.loss_over_time = [] self.default_params.value = self.default_osc_gains @@ -162,15 +144,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 1000 + budget = 2000 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) # optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_04_01_13_1000', optimizer.drake_params_folder).value + optimal_params = optimizer.load_params('2022_03_28_18_2000', optimizer.drake_params_folder).value optimizer.write_params(optimal_params) - reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_1000.npy') + reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') plt.plot(reward_over_time) plt.show() diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 99d8e6b868..f0fcc65f17 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -221,20 +221,20 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_running_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.slip_rest_length); + pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "thigh_left", + plant, plant_context.get(), "toe_left", "pelvis", osc_running_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "thigh_right", + plant, plant_context.get(), "toe_right", "pelvis", osc_running_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.leg_rest_length, osc_running_gains.center_line_offset, + osc_running_gains.rest_length, osc_running_gains.center_line_offset, osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.leg_rest_length, osc_running_gains.center_line_offset, + osc_running_gains.rest_length, osc_running_gains.center_line_offset, osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); pelvis_tracking_data = std::make_unique( @@ -288,12 +288,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "thigh_left"); - right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "thigh_right"); - left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "thigh_left"); + left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "thigh_right"); + "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + "pelvis"); left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_running_gains.K_p_swing_foot, @@ -304,9 +304,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "thigh_left"); + "hip_left"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "thigh_right"); + "hip_right"); left_foot_rel_tracking_data = std::make_unique( diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 2d6f959278..49fc6520db 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -10,37 +10,37 @@ rows: 3 cols: 3 w_input: 0 -w_accel: 0.00001 -W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5] -W_lambda_c_reg: [1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01] -W_lambda_h_reg: [0.01, 0.01, 0.01, - 0.01, 0.02, 0.02] +w_accel: 0.00000001 +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.001 ] +W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01 ] +W_lambda_h_reg: [ 0.01, 0.01, 0.01, + 0.01, 0.02, 0.02 ] w_soft_constraint: 100 w_input_reg: 0.001 impact_threshold: 0.025 -mu: 0.2 -HipYawKp: 100 +mu: 0.6 +HipYawKp: 10 HipYawKd: 1 -HipYawW: 100 +HipYawW: 0 CoMW: - [20, 0, 0, - 0, 20, 0, - 0, 0, 5] + [ 20, 0, 0, + 0, 20, 0, + 0, 0, 5 ] PelvisW: - [2, 0, 0, - 0, 2, 0, - 0, 0, 0] + [ 2, 0, 0, + 0, 2, 0, + 0, 0, 0 ] CoMKp: - [ 50, 0, 0, + [ 20, 0, 0, 0, 20, 0, - 0, 0, 20] + 0, 0, 20 ] CoMKd: [ 0.5, 0, 0, 0, 0.75, 0, diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 226cdc0e97..422e848862 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -196,7 +196,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[1] = start_pos + 0.85 * footstep_correction; Y[1](2) = -rest_length_ + mid_foot_height_; Y[2] = footstep_correction; - Y[2](2) = -rest_length_; + Y[2](2) = -rest_length_ + mid_foot_height_ / 2; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index ee396d7b76..3024cb734a 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,45 +1,47 @@ -FootstepKd: [0.3, 0, 0, 0, 0.4, 0, 0, 0, 0] -LiftoffSwingFootKd: [1, 0, 0, 0, 1, 0, 0, 0, 0] -LiftoffSwingFootKp: [50.0, 0, 0, 0, 50.0, 0, 0, 0, 25.0] -LiftoffSwingFootW: [4.898730697522512, 0.0, 0.0, 0.0, 8.875684478053362, 0.0, 0.0, - 0.0, 1.00009386127649773] -PelvisKd: [1, 0, 0, 0, 0, 0, 0, 0, 5] -PelvisKp: [0, 0, 0, 0, 0, 0, 0, 0, 85] -PelvisRotKd: [1.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] -PelvisRotKp: [50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0] -PelvisRotW: [1.8267599797810719, 0.0, 0.0, 0.0, 3.8477334733635615, 0.0, 0.0, 0.0, - 0.34454081183859286] -PelvisW: [0.1, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [5.0, 0, 0, 0, 5.0, 0, 0, 0, 1.0] -SwingFootKp: [125.0, 0, 0, 0, 80.0, 0, 0, 0, 100.0] -SwingFootW: [7.269772242193404, 0.0, 0.0, 0.0, 8.775354732789877, 0.0, 0.0, 0.0, 4.207052632433897] -W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] -W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] -W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -center_line_offset: -0.07562414926528944 -ekf_filter_tau: [0.05, 0.1, 0.01] -flight_duration: 0.08 -footstep_offset: -0.0616278401208792 +FootstepKd: [ 0.20630578931908952, 0.0, 0.0, 0.0, 0.5022846733099167, 0.0, 0.0, 0.0, + 0.014419706168051383 ] +LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, 0, 0, 0 ] +LiftoffSwingFootKp: [ 50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0 ] +LiftoffSwingFootW: [ 0.1, 0, 0, 0, 10, 0, 0, 0, 1 ] +PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5 ] +PelvisKp: [ 0, 0, 0, 0, 0, 0, 0, 0, 85 ] +PelvisRotKd: [ 14.754198175926723, 0.0, 0.0, 0.0, 10.15048844191982, 0.0, 0.0, 0.0, + 3.9038583836913308 ] +PelvisRotKp: [ 50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0 ] +PelvisRotW: [ 1, 0, 0, 0, 2.5, 0, 0, 0, 0.1 ] +PelvisW: [ 0.1, 0, 0, 0, 0, 0, 0, 0, 5 ] +SwingFootKd: [ 5.8013545212157736, 0.0, 0.0, 0.0, 8.37349939782334, 0.0, 0.0, 0.0, + 4.294753134633737 ] +SwingFootKp: [ 111.90374548402804, 0.0, 0.0, 0.0, 93.51462206597392, 0.0, 0.0, 0.0, + 75.82806014571253 ] +SwingFootW: [ 10, 0, 0, 0, 10, 0, 0, 0, 1 ] +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] +W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] +W_lambda_h_reg: [ 0.01, 0.01, 0.01, 0.01, 0.02, 0.02 ] +#center_line_offset: 0.03036161874399593 +center_line_offset: 0.04036161874399593 +ekf_filter_tau: [ 0.05, 0.1, 0.01 ] +flight_duration: 0.053967347248977025 +footstep_offset: -0.044971023856448855 hip_yaw_kd: 1 -hip_yaw_kp: 40 -impact_threshold: 0.031058496546898063 -leg_rest_length: 0.7589273904289638 -mid_foot_height: 0.08 -mu: 0.4 +hip_yaw_kp: 48.17643439890748 +impact_threshold: 0.025 +mid_foot_height: 0.05 +mu: 0.6097124570750189 relative_feet: true relative_pelvis: true -slip_rest_length: 0.85 -stance_duration: 0.30294579134157734 +rest_length: 0.85 +stance_duration: 0.2949526396548052 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 -vel_scale_trans_sagital: 0.6 -w_accel: 1.9323569255081364e-05 -w_hip_yaw: 2.404801763917696 +vel_scale_trans_sagital: 0.2 +w_accel: 1.0e-05 +w_hip_yaw: 2.0187541880806643 w_input: 0.0 -w_input_reg: 0.0008379026259671483 -w_soft_constraint: 105.44932351736742 +w_input_reg: 0.004802653072422612 +w_soft_constraint: 111.82117439652899 w_swing_toe: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index ee084f0d3b..d95d039cd5 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -22,14 +22,13 @@ ekf_filter_tau: [0.05, 0.1, 0.01] # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.6 +vel_scale_trans_sagital: 0.2 vel_scale_trans_lateral: -0.15 # SLIP parameters -slip_rest_length: 0.9 -leg_rest_length: 0.75 +rest_length: 0.85 stance_duration: 0.30 -flight_duration: 0.10 +flight_duration: 0.08 mu: 0.6 @@ -41,57 +40,57 @@ w_hip_yaw: 2.5 hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: 0 -center_line_offset: -0.04 -mid_foot_height: 0.1 +footstep_offset: -0.05 +center_line_offset: 0.05 +mid_foot_height: 0.05 FootstepKd: - [ 0.25, 0, 0, - 0, 0.25, 0, - 0, 0, 0] + [ 0.2, 0, 0, + 0, 0.6, 0, + 0, 0, 0 ] PelvisW: - [0.1, 0, 0, - 0, 0, 0, - 0, 0, 5] + [ 0.1, 0, 0, + 0, 0, 0, + 0, 0, 5 ] PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 50] + 0, 0, 85 ] PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [1.0, 0, 0, - 0, 2.5, 0, - 0, 0, 0.1] + [ 1, 0, 0, + 0, 2.5, 0, + 0, 0, 0.1 ] PelvisRotKp: [50., 0, 0, 0, 100., 0, 0, 0, 1.] PelvisRotKd: - [10., 0, 0, - 0, 5., 0, - 0, 0, 1.] + [ 10., 0, 0, + 0, 5., 0, + 0, 0, 0. ] SwingFootW: - [10, 0, 0, - 0, 50, 0, - 0, 0, 1] + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 1 ] SwingFootKp: - [125., 0, 0, - 0, 80., 0, - 0, 0, 100.] + [ 125., 0, 0, + 0, 80., 0, + 0, 0, 50. ] SwingFootKd: [5., 0, 0, 0, 5., 0, 0, 0, 1.] LiftoffSwingFootW: - [0.1, 0, 0, - 0, 10, 0, - 0, 0, 2.0] + [ 0.1, 0, 0, + 0, 10, 0, + 0, 0, 1 ] LiftoffSwingFootKp: - [50., 0, 0, - 0, 50., 0, - 0, 0, 25.] + [ 50., 0, 0, + 0, 50., 0, + 0, 0, 50. ] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index e88a17508b..05f93aa27b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -12,6 +12,7 @@ #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" +#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" #include "examples/Cassie/osc_run/osc_running_gains.h" #include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" @@ -110,6 +111,8 @@ int DoMain(int argc, char* argv[]) { auto right_toe = RightToeFront(plant); auto right_heel = RightToeRear(plant); + int nv = plant.num_velocities(); + // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); @@ -273,24 +276,21 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_gains.relative_pelvis); - accumulated_state_durations.back() += 0.05; - pelvis_trans_traj_generator->SetSLIPParams(osc_gains.slip_rest_length); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "thigh_left", osc_gains.relative_feet, + plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, 0, accumulated_state_durations); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "thigh_right", + plant, plant_context.get(), "toe_right", "pelvis", osc_gains.relative_feet, 1, accumulated_state_durations); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); - l_foot_traj_generator->SetFootPlacementOffsets(osc_gains.leg_rest_length, - osc_gains.center_line_offset, - osc_gains.footstep_offset, - osc_gains.mid_foot_height); - r_foot_traj_generator->SetFootPlacementOffsets(osc_gains.leg_rest_length, - osc_gains.center_line_offset, - osc_gains.footstep_offset, - osc_gains.mid_foot_height); + l_foot_traj_generator->SetFootPlacementOffsets( + osc_gains.rest_length, osc_gains.center_line_offset, + osc_gains.footstep_offset, osc_gains.mid_foot_height); + r_foot_traj_generator->SetFootPlacementOffsets( + osc_gains.rest_length, osc_gains.center_line_offset, + osc_gains.footstep_offset, osc_gains.mid_foot_height); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, @@ -338,12 +338,12 @@ int DoMain(int argc, char* argv[]) { auto right_hip_tracking_data = std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "thigh_left"); - right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "thigh_right"); - left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "thigh_left"); + left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "thigh_right"); + "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + "pelvis"); auto left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -353,9 +353,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "thigh_left"); + "pelvis"); right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "thigh_right"); + "pelvis"); auto left_foot_rel_tracking_data = std::make_unique( diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 38c18d103e..6c93608b1f 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -8,9 +8,7 @@ #include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "multibody/kinematic/kinematic_evaluator_set.h" -#include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/controller_failure_aggregator.h" #include "systems/controllers/osc/com_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" @@ -48,7 +46,6 @@ using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -using multibody::FixedJointEvaluator; DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "LCM channel for receiving state. " @@ -80,30 +77,35 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Build Cassie MBP - drake::multibody::MultibodyPlant plant(0.0); - addCassieMultibody(&plant, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2_conservative.urdf", + drake::multibody::MultibodyPlant plant_w_springs(0.0); + addCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, + "examples/Cassie/urdf/cassie_v2.urdf", true /*spring model*/, false /*loop closure*/); - plant.Finalize(); + plant_w_springs.Finalize(); // Build fix-spring Cassie MBP + drake::multibody::MultibodyPlant plant_wo_springs(0.0); + addCassieMultibody(&plant_wo_springs, nullptr, true, + "examples/Cassie/urdf/cassie_fixed_springs.urdf", false, + false); + plant_wo_springs.Finalize(); - auto context_w_spr = plant.CreateDefaultContext(); - auto context_wo_spr = plant.CreateDefaultContext(); + auto context_w_spr = plant_w_springs.CreateDefaultContext(); + auto context_wo_spr = plant_wo_springs.CreateDefaultContext(); // Get contact frames and position (doesn't matter whether we use // plant_w_springs or plant_wo_springs because the contact frames exit in both // plants) - auto left_toe = LeftToeFront(plant); - auto left_heel = LeftToeRear(plant); - auto right_toe = RightToeFront(plant); - auto right_heel = RightToeRear(plant); + auto left_toe = LeftToeFront(plant_wo_springs); + auto left_heel = LeftToeRear(plant_wo_springs); + auto right_toe = RightToeFront(plant_wo_springs); + auto right_heel = RightToeRear(plant_wo_springs); // Build the controller diagram DiagramBuilder builder; drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); -// auto osc_gains = -// drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); + // auto osc_gains = + // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); drake::yaml::YamlReadArchive::Options yaml_options; yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile( @@ -140,7 +142,7 @@ int DoMain(int argc, char* argv[]) { // Create state receiver. auto state_receiver = - builder.AddSystem(plant); + builder.AddSystem(plant_w_springs); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( @@ -151,7 +153,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = - builder.AddSystem(plant); + builder.AddSystem(plant_w_springs); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -161,23 +163,16 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_STANDING", &lcm_local, TriggerTypeSet({TriggerType::kForced}))); - auto failure_aggregator = - builder.AddSystem(FLAGS_channel_u, - 1); - auto controller_failure_pub = builder.AddSystem( - LcmPublisherSystem::Make( - "CONTROLLER_ERROR", &lcm_local, TriggerTypeSet({TriggerType::kForced}))); - // Create desired center of mass traj std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant, context_w_spr.get(), feet_contact_points, FLAGS_height, + plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); auto pelvis_rot_traj_generator = builder.AddSystem( - plant, context_w_spr.get(), feet_contact_points, + plant_w_springs, context_w_spr.get(), feet_contact_points, "pelvis_rot_traj"); builder.Connect(state_receiver->get_output_port(0), com_traj_generator->get_input_port_state()); @@ -192,64 +187,44 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant, plant, context_w_spr.get(), + plant_w_springs, plant_wo_springs, context_w_spr.get(), context_wo_spr.get(), false, FLAGS_print_osc, FLAGS_qp_time_limit); // Distance constraint - multibody::KinematicEvaluatorSet evaluators(plant); - auto left_loop = LeftLoopClosureEvaluator(plant); - auto right_loop = RightLoopClosureEvaluator(plant); + multibody::KinematicEvaluatorSet evaluators(plant_wo_springs); + auto left_loop = LeftLoopClosureEvaluator(plant_wo_springs); + auto right_loop = RightLoopClosureEvaluator(plant_wo_springs); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); + osc->AddKinematicConstraint(&evaluators); // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant, left_toe.first, left_toe.second, Matrix3d::Identity(), + plant_wo_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); + osc->AddContactPoint(&left_toe_evaluator); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant, left_heel.first, left_heel.second, Matrix3d::Identity(), + plant_wo_springs, left_heel.first, left_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + osc->AddContactPoint(&left_heel_evaluator); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant, right_toe.first, right_toe.second, Matrix3d::Identity(), + plant_wo_springs, right_toe.first, right_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); + osc->AddContactPoint(&right_toe_evaluator); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant, right_heel.first, right_heel.second, + plant_wo_springs, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddContactPoint(&left_toe_evaluator); - osc->AddContactPoint(&left_heel_evaluator); - osc->AddContactPoint(&right_toe_evaluator); osc->AddContactPoint(&right_heel_evaluator); - - auto pos_idx_map = multibody::makeNameToPositionsMap(plant); - auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); - auto left_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), - vel_idx_map.at("knee_joint_leftdot"), 0); - auto right_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), - vel_idx_map.at("knee_joint_rightdot"), 0); - auto left_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), - vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - auto right_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), - vel_idx_map.at("ankle_spring_joint_rightdot"), 0); - evaluators.add_evaluator(&left_fixed_knee_spring); - evaluators.add_evaluator(&right_fixed_knee_spring); - evaluators.add_evaluator(&left_fixed_ankle_spring); - evaluators.add_evaluator(&right_fixed_ankle_spring); - osc->AddKinematicConstraint(&evaluators); - // Cost - int n_v = plant.num_velocities(); + int n_v = plant_wo_springs.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); + // osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + // gains.W_lambda_h_regularization); // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing @@ -257,8 +232,8 @@ int DoMain(int argc, char* argv[]) { // W_com * FLAGS_cost_weight_multiplier, // plant_w_springs, plant_wo_springs); auto center_of_mass_traj = std::make_unique( - "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, plant, - plant); + "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, + plant_w_springs, plant_wo_springs); center_of_mass_traj->AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); @@ -267,7 +242,8 @@ int DoMain(int argc, char* argv[]) { // Pelvis rotation tracking auto pelvis_rot_traj = std::make_unique( "pelvis_rot_traj", K_p_pelvis, K_d_pelvis, - W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); + W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, + plant_wo_springs); pelvis_rot_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_rot_traj)); @@ -281,11 +257,11 @@ int DoMain(int argc, char* argv[]) { auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant, plant); + plant_w_springs, plant_wo_springs); auto right_hip_yaw_traj = std::make_unique( "right_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant, plant); + plant_w_springs, plant_wo_springs); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); @@ -303,10 +279,6 @@ int DoMain(int argc, char* argv[]) { osc->get_tracking_data_input_port("com_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), osc->get_tracking_data_input_port("pelvis_rot_traj")); - builder.Connect(osc->get_failure_output_port(), - failure_aggregator->get_input_port(0)); - builder.Connect(failure_aggregator->get_status_output_port(), - controller_failure_pub->get_input_port()); // Create the diagram auto owned_diagram = builder.Build(); diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index a16599db42..addfa910bd 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -62,7 +62,13 @@ void TransTaskSpaceTrackingData::UpdateJ( context_wo_spr, JacobianWrtVariable::kV, *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); - if(J_.hasNaN()){ + if (fsm_state_ < 2) { + J_(2, 8) = 0; + J_(2, 16) = 0; + J_(2, 6) = 0; + J_(2, 14) = 0; + } + if (J_.hasNaN()) { std::cout << "Jacobian has NaNs" << std::endl; } } From 13a62e02e0f824ede38de21670fa1b931ee31e55 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 6 Apr 2022 16:52:38 -0400 Subject: [PATCH 192/758] small changes --- .../Cassie/osc_run/foot_traj_generator.cc | 5 -- examples/Cassie/osc_run/osc_running_gains.h | 6 +-- .../Cassie/osc_run/osc_running_gains.yaml | 50 +++++++++---------- 3 files changed, 27 insertions(+), 34 deletions(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 422e848862..147d94fe60 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -156,9 +156,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; VectorXd pelvis_vel = v.segment(3, 3); -// pelvis_vel(0) = context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(0); -// pelvis_vel(1) *= 0.75; -// pelvis_vel(1) += 0.25 * context.get_discrete_state(pelvis_vel_est_idx_).GetAtIndex(1); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd footstep_correction = Kd_ * (pelvis_vel_err); if (is_left_foot_) { @@ -201,12 +198,10 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // corrections if (is_left_foot_) { Y[1](1) -= 0.25 * center_line_offset_; - // Y[0](1) = drake::math::saturate(Y[2](1), 0.05, 0.2); Y[1](1) = drake::math::saturate(Y[1](1), center_line_offset_, 0.2); Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); } else { Y[1](1) += 0.25 * center_line_offset_; - // Y[0](1) = drake::math::saturate(Y[2](1), -0.2, -0.05); Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -center_line_offset_); Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); } diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 0379867f43..2190272219 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -25,8 +25,7 @@ struct OSCRunningGains : OSCGains { double vel_scale_trans_lateral; bool relative_feet; bool relative_pelvis; - double slip_rest_length; - double leg_rest_length; + double rest_length; double stance_duration; double flight_duration; @@ -85,8 +84,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); - a->Visit(DRAKE_NVP(slip_rest_length)); - a->Visit(DRAKE_NVP(leg_rest_length)); + a->Visit(DRAKE_NVP(rest_length)); a->Visit(DRAKE_NVP(stance_duration)); a->Visit(DRAKE_NVP(flight_duration)); a->Visit(DRAKE_NVP(center_line_offset)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d95d039cd5..b2345185a4 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -44,53 +44,53 @@ footstep_offset: -0.05 center_line_offset: 0.05 mid_foot_height: 0.05 FootstepKd: - [ 0.2, 0, 0, - 0, 0.6, 0, - 0, 0, 0 ] + [ 0.2, 0, 0, + 0, 0.6, 0, + 0, 0, 0] PelvisW: - [ 0.1, 0, 0, - 0, 0, 0, - 0, 0, 5 ] + [0.1, 0, 0, + 0, 0, 0, + 0, 0, 5] PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 85 ] + 0, 0, 85] PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [ 1, 0, 0, - 0, 2.5, 0, - 0, 0, 0.1 ] + [1, 0, 0, + 0, 2.5, 0, + 0, 0, 0.1] PelvisRotKp: [50., 0, 0, 0, 100., 0, 0, 0, 1.] PelvisRotKd: - [ 10., 0, 0, - 0, 5., 0, - 0, 0, 0. ] + [4., 0, 0, + 0, 5., 0, + 0, 0, 0.] SwingFootW: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 1 ] + [10, 0, 0, + 0, 10, 0, + 0, 0, 1] SwingFootKp: - [ 125., 0, 0, - 0, 80., 0, - 0, 0, 50. ] + [125, 0, 0, + 0, 100, 0, + 0, 0, 50] SwingFootKd: [5., 0, 0, 0, 5., 0, 0, 0, 1.] LiftoffSwingFootW: - [ 0.1, 0, 0, - 0, 10, 0, - 0, 0, 1 ] + [0.1, 0, 0, + 0, 10, 0, + 0, 0, 1] LiftoffSwingFootKp: - [ 50., 0, 0, - 0, 50., 0, - 0, 0, 50. ] + [50, 0, 0, + 0, 50, 0, + 0, 0, 50] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, From 439afc860000dcafda4fb66e73995dac45361f34 Mon Sep 17 00:00:00 2001 From: Brian Acosta Date: Thu, 7 Apr 2022 10:06:17 -0400 Subject: [PATCH 193/758] option to ignore joint in tracking data jacobian --- .../controllers/osc/options_tracking_data.cc | 18 ++++++++++++++++++ .../controllers/osc/options_tracking_data.h | 5 +++++ 2 files changed, 23 insertions(+) diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index f3a0d72bb2..c8a541f205 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -37,6 +37,12 @@ void OptionsTrackingData::UpdateActual( JdotV_ = view_frame_rot_T_ * JdotV_; } + if (joint_idx_to_ignore_.count(fsm_state_)) { + for (int idx : joint_idx_to_ignore_[fsm_state_]) { + J_.col(idx) = VectorXd::Zero(J_.rows()); + } + } + UpdateFilters(t); } @@ -113,6 +119,18 @@ void OptionsTrackingData::SetLowPassFilter(double tau, } } +void OptionsTrackingData::AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, + int fsm_state) { + DRAKE_DEMAND(std::find(active_fsm_states_.begin(), + active_fsm_states_.end(), + fsm_state) != active_fsm_states_.end()); + if (joint_idx_to_ignore_.count(fsm_state)) { + joint_idx_to_ignore_[fsm_state_].push_back(joint_vel_idx); + } else { + joint_idx_to_ignore_[fsm_state_] = {joint_vel_idx}; + } +} + void OptionsTrackingData::SetTimeVaryingGains( const drake::trajectories::Trajectory& gain_multiplier) { DRAKE_DEMAND(gain_multiplier.cols() == n_ydot_); diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index 4723bc2a93..268a13b902 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -43,6 +43,10 @@ class OptionsTrackingData : public OscTrackingData { idx_zero_feedforward_accel_ = indices; }; + // Ignore a joint to ignore in jacobian calculation. + // State must be added to the tracking data already + void AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, int fsm_state); + private: void UpdateActual( const Eigen::VectorXd& x_w_spr, @@ -64,6 +68,7 @@ class OptionsTrackingData : public OscTrackingData { Eigen::VectorXd filtered_ydot_; double tau_ = -1; std::set low_pass_filter_element_idx_; + std::map> joint_idx_to_ignore_; double last_timestamp_ = -1; }; From e9b9a12ee90e9581b2d04c6b21fe054a4f5400e1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 7 Apr 2022 11:47:04 -0400 Subject: [PATCH 194/758] small gain changes --- .../plot_configs/cassie_running_plot.yaml | 17 +++++++------ .../Cassie/osc_run/osc_running_gains.yaml | 18 ++++++------- examples/Cassie/run_osc_running_controller.cc | 4 +-- .../osc/operational_space_control.cc | 25 ++++++++++--------- 4 files changed, 33 insertions(+), 31 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 9b5359f902..5e70dff465 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -4,7 +4,8 @@ channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) -end_time: -1 +#end_time: -1 +end_time: 30 # Plant properties use_springs: true @@ -13,7 +14,7 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false plot_floating_base_velocities: false -plot_joint_positions: false +plot_joint_positions: true plot_joint_velocities: false plot_measured_efforts: true special_positions_to_plot: [] @@ -26,17 +27,17 @@ foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: false -plot_qp_solve_time: false +plot_qp_costs: true +plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} - right_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} - left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} - right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} +# left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} +# right_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} +# left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} +# right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index b2345185a4..38eee065e1 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,12 +4,12 @@ w_accel: 0.00001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5] +W_input_reg: [1, 0.9, 0.5, 0.1, 10, + 1, 0.9, 0.5, 0.1, 10] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01] + 1, 0.001, 0.01, + 1, 0.001, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 @@ -40,7 +40,7 @@ w_hip_yaw: 2.5 hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: -0.05 +footstep_offset: -0.00 center_line_offset: 0.05 mid_foot_height: 0.05 FootstepKd: @@ -54,7 +54,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 85] + 0, 0, 75] PelvisKd: [ 1, 0, 0, 0, 0, 0, @@ -62,15 +62,15 @@ PelvisKd: PelvisRotW: [1, 0, 0, 0, 2.5, 0, - 0, 0, 0.1] + 0, 0, 20] PelvisRotKp: [50., 0, 0, 0, 100., 0, - 0, 0, 1.] + 0, 0, 0.] PelvisRotKd: [4., 0, 0, 0, 5., 0, - 0, 0, 0.] + 0, 0, 1.] SwingFootW: [10, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 05f93aa27b..b9bad28e11 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -200,8 +200,8 @@ int DoMain(int argc, char* argv[]) { osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); -// osc->SetLambdaContactRegularizationWeight(1e-4 * -// gains.W_lambda_c_regularization); + osc->SetLambdaContactRegularizationWeight(1e-4 * + gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index dd6d3dcc2f..47e9182559 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -525,7 +525,7 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd grav = plant_wo_spr_.CalcGravityGeneralizedForces(*context_wo_spr_); bias = bias - grav; // TODO (yangwill): Characterize damping in cassie model - // bias = bias - f_app.generalized_forces(); +// bias = bias - f_app.generalized_forces(); // Invariant Impacts // Only update when near an impact @@ -755,11 +755,11 @@ VectorXd OperationalSpaceControl::SolveQp( *epsilon_sol_ = result.GetSolution(epsilon_); u_sol_->row(0) = 0.95 * u_sol_->row(0) + 0.05 * u_prev_->row(0); u_sol_->row(1) = 0.95 * u_sol_->row(1) + 0.05 * u_prev_->row(1); - *u_prev_ = *u_sol_; + // *u_prev_ = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { -// *u_prev_ = VectorXd::Zero(n_u_); + // *u_prev_ = VectorXd::Zero(n_u_); *u_prev_ = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } @@ -986,7 +986,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_data[i] = osc_output; } // std::cout << total_cost_ << std::endl; - + *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); } @@ -1058,14 +1058,15 @@ void OperationalSpaceControl::CheckTracking( output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; // std::cout << "total cost: " << total_cost_ << std::endl; -// bool joint_error = false; -// auto q = -// (map_position_from_spring_to_no_spring_ * robot_output->GetPositions()) -// .segment(7, n_revolute_joints_); -// for (int i = 0; i < n_revolute_joints_; ++i) { -// joint_error = joint_error || q(i) < q_min_(i); -// joint_error = joint_error || q(i) > q_max_(i); -// } + // bool joint_error = false; + // auto q = + // (map_position_from_spring_to_no_spring_ * + // robot_output->GetPositions()) + // .segment(7, n_revolute_joints_); + // for (int i = 0; i < n_revolute_joints_; ++i) { + // joint_error = joint_error || q(i) < q_min_(i); + // joint_error = joint_error || q(i) > q_max_(i); + // } if (soft_constraint_cost_ > 5e2 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } From d777fc2aba2b8d8fb69cd90717df1f0bf2f4a01f Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 29 Apr 2022 14:04:20 -0400 Subject: [PATCH 195/758] current running progress --- .../plot_configs/cassie_running_plot.yaml | 10 +-- .../Cassie/osc_run/osc_running_gains.yaml | 40 ++++++------ .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_jumping_controller.cc | 4 +- examples/Cassie/run_osc_running_controller.cc | 33 +++++++++- .../Cassie/run_osc_standing_controller.cc | 4 +- .../Cassie/run_osc_walking_controller_alip.cc | 6 +- examples/Cassie/urdf/cassie_v2.urdf | 4 +- .../Cassie/urdf/cassie_v2_conservative.urdf | 32 +++++----- multibody/multibody_utils.cc | 12 ++-- .../osc/operational_space_control.cc | 63 +++++++++++++++++-- .../osc/trans_space_tracking_data.cc | 10 ++- 12 files changed, 159 insertions(+), 61 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 5e70dff465..fc5728a6f9 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -31,13 +31,13 @@ plot_qp_costs: true plot_qp_solve_time: true plot_tracking_costs: true tracking_datas_to_plot: -# pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']} + pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['vel']} # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} -# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# left_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} + pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} + left_ft_traj: {'dims': [1, 2], 'derivs': ['vel']} # right_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} -# left_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} + left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 38eee065e1..e4884974eb 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,15 +1,15 @@ -w_input: 0.00000 -w_accel: 0.00001 +w_input: 0.0001 +w_accel: 0.0001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 10, - 1, 0.9, 0.5, 0.1, 10] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01] + 1, 0.1, 0.01, + 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 @@ -28,7 +28,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.85 stance_duration: 0.30 -flight_duration: 0.08 +flight_duration: 0.1 mu: 0.6 @@ -40,8 +40,8 @@ w_hip_yaw: 2.5 hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: -0.00 -center_line_offset: 0.05 +footstep_offset: -0.05 +center_line_offset: 0.04 mid_foot_height: 0.05 FootstepKd: [ 0.2, 0, 0, @@ -54,30 +54,30 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 75] + 0, 0, 70] PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: [1, 0, 0, - 0, 2.5, 0, - 0, 0, 20] + 0, 10, 0, + 0, 0, 0] PelvisRotKp: - [50., 0, 0, + [100., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [4., 0, 0, + [10., 0, 0, 0, 5., 0, 0, 0, 1.] SwingFootW: [10, 0, 0, - 0, 10, 0, - 0, 0, 1] + 0, 100, 0, + 0, 0, 5] SwingFootKp: [125, 0, 0, - 0, 100, 0, + 0, 50, 0, 0, 0, 50] SwingFootKd: [5., 0, 0, @@ -85,7 +85,7 @@ SwingFootKd: 0, 0, 1.] LiftoffSwingFootW: [0.1, 0, 0, - 0, 10, 0, + 0, 100, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, @@ -93,6 +93,6 @@ LiftoffSwingFootKp: 0, 0, 50] LiftoffSwingFootKd: [ 1, 0, 0, - 0, 1, 0, - 0, 0, 0] + 0, 5, 0, + 0, 0, 1] diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index c63e78deb6..ef9835eff9 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 200 +max_iter: 1000 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 9220e1308b..15787ac22b 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -87,7 +87,7 @@ DEFINE_string(traj_name, "jumping_0.15h_0.3d", "File to load saved trajectories from"); DEFINE_string(gains_filename, "examples/Cassie/osc_jump/osc_jumping_gains.yaml", "Filepath containing gains"); -DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", +DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", "Filepath containing qp settings"); int DoMain(int argc, char* argv[]) { @@ -100,7 +100,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant_w_spr(0.0); addCassieMultibody(&plant_w_spr, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", - false /*spring model*/, false /*loop closure*/); + true /*spring model*/, false /*loop closure*/); plant_w_spr.Finalize(); auto context_w_spr = plant_w_spr.CreateDefaultContext(); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b9bad28e11..d9e4d66e6c 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -100,7 +100,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); addCassieMultibody(&plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", - false /*spring model*/, false /*loop closure*/); + true /*spring model*/, false /*loop closure*/); plant.Finalize(); auto plant_context = plant.CreateDefaultContext(); @@ -256,6 +256,10 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); +// osc->AddStateAndContactPoint(left_stance_state, &left_fixed_knee_spring); +// osc->AddStateAndContactPoint(right_stance_state, &right_fixed_knee_spring); +// osc->AddStateAndContactPoint(left_stance_state, &left_fixed_ankle_spring); +// osc->AddStateAndContactPoint(right_stance_state, &right_fixed_ankle_spring); osc->AddKinematicConstraint(&evaluators); @@ -390,6 +394,33 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); +// left_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// vel_map["hip_yaw_leftdot"], right_stance_state); +// left_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// vel_map["hip_yaw_leftdot"], right_touchdown_air_phase); +// right_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// vel_map["hip_yaw_rightdot"], left_stance_state); +// right_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// vel_map["hip_yaw_rightdot"], left_touchdown_air_phase); + pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], left_stance_state); + pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], right_stance_state); + pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], left_stance_state); + pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], right_stance_state); + +// left_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// pos_map["hip_pitch_left"], right_stance_state); +// left_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// pos_map["hip_pitch_left"], right_touchdown_air_phase); +// right_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// pos_map["hip_pitch_right"], left_stance_state); +// right_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( +// pos_map["hip_pitch_right"], left_touchdown_air_phase); + +// left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); +// right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); + left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 6c93608b1f..d8022ad3a8 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -79,13 +79,13 @@ int DoMain(int argc, char* argv[]) { // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_springs(0.0); addCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); plant_w_springs.Finalize(); // Build fix-spring Cassie MBP drake::multibody::MultibodyPlant plant_wo_springs(0.0); addCassieMultibody(&plant_wo_springs, nullptr, true, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", false, + "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf", false, false); plant_wo_springs.Finalize(); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 23b38fc0ab..5f9964961b 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -214,7 +214,7 @@ int DoMain(int argc, char* argv[]) { state_durations = {left_support_duration, double_support_duration, right_support_duration, double_support_duration}; } - auto fsm = builder.AddSystem( + auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); builder.Connect(simulator_drift->get_output_port(0), fsm->get_input_port_state()); @@ -448,11 +448,13 @@ int DoMain(int argc, char* argv[]) { gains.W_swing_foot, plant_w_spr, plant_w_spr); swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); + swing_foot_data->SetImpactInvariantProjection(true); auto com_data = std::make_unique ("com_data", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); + com_data->SetImpactInvariantProjection(true); auto swing_ft_traj_local = std::make_unique ( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), @@ -496,12 +498,14 @@ int DoMain(int argc, char* argv[]) { "pelvis_balance_traj", gains.K_p_pelvis_balance, gains.K_d_pelvis_balance, gains.W_pelvis_balance, plant_w_spr, plant_w_spr); pelvis_balance_traj->AddFrameToTrack("pelvis"); + pelvis_balance_traj->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) auto pelvis_heading_traj = std::make_unique ( "pelvis_heading_traj", gains.K_p_pelvis_heading, gains.K_d_pelvis_heading, gains.W_pelvis_heading, plant_w_spr, plant_w_spr); pelvis_heading_traj->AddFrameToTrack("pelvis"); + pelvis_heading_traj->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_heading_traj), gains.period_of_no_heading_control); diff --git a/examples/Cassie/urdf/cassie_v2.urdf b/examples/Cassie/urdf/cassie_v2.urdf index 46284e004a..b8ec0ff559 100644 --- a/examples/Cassie/urdf/cassie_v2.urdf +++ b/examples/Cassie/urdf/cassie_v2.urdf @@ -615,7 +615,7 @@ - + @@ -624,7 +624,7 @@ - + diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 7be788d201..04d2720659 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -615,7 +615,7 @@ - + @@ -624,7 +624,7 @@ - + @@ -634,7 +634,7 @@ - + @@ -643,7 +643,7 @@ - + @@ -654,7 +654,7 @@ - + @@ -664,7 +664,7 @@ - + @@ -673,7 +673,7 @@ - + @@ -682,7 +682,7 @@ - + @@ -716,7 +716,7 @@ - + @@ -725,7 +725,7 @@ - + @@ -748,7 +748,7 @@ - + @@ -757,7 +757,7 @@ - + @@ -767,7 +767,7 @@ - + @@ -777,7 +777,7 @@ - + @@ -787,7 +787,7 @@ - + @@ -796,7 +796,7 @@ - + diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 63d71f1eb8..c628e4f493 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -376,13 +376,15 @@ Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos( bool successfully_added = false; for (auto pos_pair_w_spr : pos_map_w_spr) { if (pos_pair_wo_spr.first == pos_pair_w_spr.first) { - ret(pos_pair_wo_spr.second, pos_pair_w_spr.second) = 1; +// if (pos_pair_w_spr.first.find("ankle_spring") == std::string::npos && pos_pair_w_spr.first.find("knee_joint") == std::string::npos){ + ret(pos_pair_wo_spr.second, pos_pair_w_spr.second) = 1; +// } successfully_added = true; } } DRAKE_DEMAND(successfully_added); } - +// std::cout << ret << std::endl; return ret; } @@ -402,13 +404,15 @@ Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel( bool successfully_added = false; for (auto vel_pair_w_spr : vel_map_w_spr) { if (vel_pair_wo_spr.first == vel_pair_w_spr.first) { - ret(vel_pair_wo_spr.second, vel_pair_w_spr.second) = 1; +// if (vel_pair_w_spr.first.find("ankle_spring") == std::string::npos && vel_pair_w_spr.first.find("knee_joint") == std::string::npos){ + ret(vel_pair_wo_spr.second, vel_pair_w_spr.second) = 1; +// } successfully_added = true; } } DRAKE_DEMAND(successfully_added); } - +// std::cout << ret << std::endl; return ret; } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 47e9182559..f3ff76bc17 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -295,6 +295,7 @@ void OperationalSpaceControl::Build() { all_contacts_[i]->EvalFullJacobian(*context_wo_spr_).rows(); } } +// std::cout << contact_map.first << ", " << active_contact_dim << std::endl; active_contact_dim_[contact_map.first] = active_contact_dim; } @@ -525,7 +526,8 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd grav = plant_wo_spr_.CalcGravityGeneralizedForces(*context_wo_spr_); bias = bias - grav; // TODO (yangwill): Characterize damping in cassie model -// bias = bias - f_app.generalized_forces(); +// std::cout << f_app.generalized_forces().transpose() << std::endl; + bias = bias - f_app.generalized_forces(); // Invariant Impacts // Only update when near an impact @@ -537,6 +539,7 @@ VectorXd OperationalSpaceControl::SolveQp( next_fsm_state, M); // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; +// std::cout << v_proj.transpose() << std::endl; } // SetVelocitiesIfNew( // plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, @@ -610,8 +613,13 @@ VectorXd OperationalSpaceControl::SolveQp( /// -> [J_c_active, I]* [dv, epsilon]^T == -JdotV_c_active MatrixXd A_c = MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_); A_c.block(0, 0, n_c_active_, n_v_) = J_c_active; + MatrixXd weight = 0.001 * MatrixXd::Identity(n_c_active_, n_c_active_); + weight(0, 0) *= 1e-3; + weight(1, 1) *= 1e-3; + weight(3, 3) *= 1e-3; + weight(4, 4) *= 1e-3; A_c.block(0, n_v_, n_c_active_, n_c_active_) = - 0.001 * MatrixXd::Identity(n_c_active_, n_c_active_); + weight; contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -779,15 +787,20 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( int fsm_state, int next_fsm_state, const MatrixXd& M) const { auto map_iterator = contact_indices_map_.find(next_fsm_state); if (map_iterator == contact_indices_map_.end()) { - throw std::out_of_range("Contact mode: " + std::to_string(next_fsm_state) + - " was not found in the OSC"); + ii_lambda_sol_ = VectorXd::Zero(n_c_ + n_h_); + M_Jt_ = MatrixXd::Zero(n_v_, n_c_ + n_h_); + return; +// throw std::out_of_range("Contact mode: " + std::to_string(next_fsm_state) + +// " was not found in the OSC"); } std::set next_contact_set = map_iterator->second; int active_constraint_dim = active_contact_dim_.at(next_fsm_state) + n_h_; +// std::cout << "active constraint dim: " << active_constraint_dim << std::endl; MatrixXd J_next = MatrixXd::Zero(active_constraint_dim, n_v_); int row_start = 0; for (unsigned int i = 0; i < all_contacts_.size(); i++) { if (next_contact_set.find(i) != next_contact_set.end()) { +// std::cout << i << std::endl; J_next.block(row_start, 0, kSpaceDim, n_v_) = all_contacts_[i]->EvalFullJacobian(*context_wo_spr_); row_start += kSpaceDim; @@ -798,6 +811,8 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( J_next.block(row_start, 0, n_h_, n_v_) = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); } +// std::cout << "J: " << std::endl; +// std::cout << J_next << std::endl; M_Jt_ = M.llt().solve(J_next.transpose()); int active_tracking_data_dim = 0; @@ -843,7 +858,26 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } } - ii_lambda_sol_ = A.completeOrthogonalDecomposition().solve(ydot_err_vec); +// int n_holonomic_constraints = n_h_; + MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); + MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + n_h_, active_constraint_dim + n_h_); + MatrixXd C = J_h * M_Jt_; + VectorXd Ab = A.transpose() * ydot_err_vec; + VectorXd d = J_h * x_w_spr.tail(n_v_); + A_constrained.block(0, 0, active_constraint_dim, active_constraint_dim) = A.transpose() * A; + A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = C; + A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = C.transpose(); + VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); + b_constrained << Ab, d; + // A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = MatriXd; + +// ii_lambda_sol_ = A.completeOrthogonalDecomposition().solve(ydot_err_vec); + ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition().solve(b_constrained).head(active_constraint_dim); + +// std::cout << "constraint velocity: " << (J_h * (x_w_spr.tail(n_v_))).transpose() << std::endl; +// std::cout << "projected velocity: " << (J_h * (x_w_spr.tail(n_v_) + M_Jt_ * ii_lambda_sol_)).transpose() << std::endl; + +// std::cout << ii_lambda_sol_.transpose() << std::endl; } void OperationalSpaceControl::AssignOscLcmOutput( @@ -1035,6 +1069,25 @@ void OperationalSpaceControl::CalcOptimalInput( next_fsm_state = impact_info->GetCurrentContactMode(); } +// if(fsm_state(0) == 0){ +// x_wo_spr[19] = 0; +// x_wo_spr[21] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } +// else if(fsm_state(0) == 1){ +// x_wo_spr[11] = 0; +// x_wo_spr[13] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } +// else{ +// x_wo_spr[11] = 0; +// x_wo_spr[13] = 0; +// x_wo_spr[19] = 0; +// x_wo_spr[21] = 0; +// } + // Get discrete states const auto prev_event_time = context.get_discrete_state(prev_event_time_idx_).get_value(); diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index addfa910bd..8443906321 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -63,11 +63,17 @@ void TransTaskSpaceTrackingData::UpdateJ( *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); if (fsm_state_ < 2) { - J_(2, 8) = 0; - J_(2, 16) = 0; +// J_(2, 8) = 0; +// J_(2, 16) = 0; J_(2, 6) = 0; J_(2, 14) = 0; } + if (fsm_state_ >= 2) { + J_(2, 7) = 0; + J_(2, 15) = 0; +// J_(2, 6) = 0; +// J_(2, 14) = 0; + } if (J_.hasNaN()) { std::cout << "Jacobian has NaNs" << std::endl; } From 988053453616e51855c7fc2db9ef078205bf422b Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 2 May 2022 15:26:01 -0400 Subject: [PATCH 196/758] updating readme --- examples/Cassie/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/README.md b/examples/Cassie/README.md index fbd298338c..c7f5eb3a73 100644 --- a/examples/Cassie/README.md +++ b/examples/Cassie/README.md @@ -2,7 +2,7 @@ Launch bot-procman-sherrif using the cassie_test.pmd configuration file. Currently, you must bein the root `dairlib` directory for this to work properly. ``` -bot-procman-sherrif examples/Cassie/cassie_test.pmd +bot-procman-sheriff -l examples/Cassie/cassie_simulation.pmd ``` Note: if you've installed libbot2, using apt, `bot-procman-sherrif` is probably located in `/opt/libbot2/0.0.1.20180130/bin/` or a similar directory. Running `bot-procman-sherrif -l` will allow you to skip the "Spawn local deputy" step. From b96a9719949566472def9b387b0fc6d8c96563e7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 10 May 2022 11:41:59 -0400 Subject: [PATCH 197/758] working on improving running --- .../pydairlib/analysis/cassie_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_cassie.py | 16 ++-- .../pydairlib/analysis/mbp_plotting_utils.py | 33 ++++++-- .../plot_configs/cassie_running_plot.yaml | 42 ++++++----- .../cassie/gym_envs/cassie_gym_test.py | 12 ++- bindings/pydairlib/common/plot_styler.py | 18 +++-- bindings/pydairlib/common/plotting_utils.py | 2 +- examples/Cassie/BUILD.bazel | 1 + .../osc_running_controller_diagram.cc | 8 +- .../Cassie/osc/swing_toe_traj_generator.cc | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 75 +++++++++++++++---- examples/Cassie/osc_run/foot_traj_generator.h | 13 +++- examples/Cassie/osc_run/osc_running_gains.h | 8 +- .../Cassie/osc_run/osc_running_gains.yaml | 21 +++--- .../osc_run/osc_running_qp_settings.yaml | 4 +- examples/Cassie/run_osc_running_controller.cc | 13 +++- .../Cassie/run_osc_walking_controller_alip.cc | 3 +- .../osc/operational_space_control.cc | 42 +++++------ 18 files changed, 203 insertions(+), 111 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index b88b347376..df4817f1ff 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -41,5 +41,6 @@ def __init__(self, filename): self.plot_qp_costs = data['plot_qp_costs'] self.plot_tracking_costs = data['plot_tracking_costs'] self.plot_qp_solve_time = data['plot_qp_solve_time'] + self.fsm_state_names = data['fsm_state_names'] self.tracking_datas_to_plot = \ data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index fae3cafdac..a4c933a9f9 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -34,10 +34,10 @@ def main(): filename = sys.argv[1] log = lcm.EventLog(filename, "r") robot_output, robot_input, osc_debug = \ - get_log_data(log, # log - cassie_plots.cassie_default_channels, # lcm channels + get_log_data(log, # log + cassie_plots.cassie_default_channels, # lcm channels plot_config.end_time, - mbp_plots.load_default_channels, # processing callback + mbp_plots.load_default_channels, # processing callback plant, channel_x, channel_u, channel_osc) # processing callback arguments print('Finished processing log - making plots') @@ -75,13 +75,13 @@ def main(): if plot_config.vel_names: plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, t_x_slice, vel_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) ''' Plot Efforts ''' if plot_config.plot_measured_efforts: plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.act_names: mbp_plots.plot_measured_efforts_by_name(robot_output, @@ -99,8 +99,8 @@ def main(): for deriv in config['derivs']: for dim in config['dims']: plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, - deriv, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + deriv, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) ''' Plot Foot Positions ''' if plot_config.foot_positions_to_plot: @@ -115,7 +115,7 @@ def main(): plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, foot_frames, pts, dims) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], scale=0.05) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_qp_solve_time: mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 162da95180..34bbe5e973 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -1,5 +1,6 @@ import numpy as np import matplotlib.pyplot as plt +from matplotlib.patches import Patch from pydairlib.common import plot_styler, plotting_utils from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost, osc_regularlization_tracking_cost @@ -268,6 +269,7 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, data_dict[name] = make_point_positions_from_q(robot_output['q'], plant, context, frame, pt) legend_entries[name] = [name + dim_map[dim] for dim in dims[name]] + ps = plot_styler.PlotStyler() plotting_utils.make_plot( data_dict, @@ -276,9 +278,20 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, frame_names, dims, legend_entries, - {'title': 'Point Positions', + {'title': 'Running', 'xlabel': 'time (s)', - 'ylabel': 'pos (m)'}, ps) + 'ylabel': 'foot vertical position (m)'}, ps) + + import matplotlib + legend_elements = [matplotlib.patches.Patch(facecolor=ps.cmap(0), alpha=0.3, label='Left Stance (LS)'), + matplotlib.patches.Patch(facecolor=ps.cmap(4), alpha=0.3, label='Left Liftoff (LF)'), + matplotlib.patches.Patch(facecolor=ps.cmap(2), alpha=0.3, label='Right Stance (RS)'), + matplotlib.patches.Patch(facecolor=ps.cmap(6), alpha=0.3, label='Right Liftoff (RF)')] + legend = plt.legend(legend_elements, ['Left Stance (LS)', + 'Left Liftoff (LF)', + 'Right Stance (RS)', + 'Right Liftoff (RF)'], loc=1) + plt.gca().add_artist(legend) return ps @@ -420,11 +433,21 @@ def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): return ps -def add_fsm_to_plot(ps, fsm_time, fsm_signal, scale=1): +def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names = []): ax = ps.fig.axes[0] ymin, ymax = ax.get_ylim() + # uses default color map + legend_elements = [] for i in np.unique(fsm_signal): - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), alpha=0.2) - ax.relim() \ No newline at end of file + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2*i), alpha=0.2) + if len(fsm_state_names) == np.unique(fsm_signal).shape[0]: + legend_elements.append(Patch(facecolor=ps.cmap(2*i), alpha=0.3, label=fsm_state_names[i])) + + if len(legend_elements) > 0: + legend = ax.legend(legend_elements, fsm_state_names, loc=4) + # ps.add_legend(legend, loc=4) + # ax.add_artist(legend) + # ax.add_artist(legend) + ax.relim() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index fc5728a6f9..6908c4969a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,11 +1,12 @@ # LCM channels to read data from +#channel_x: "CASSIE_STATE_SIMULATION" channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) #end_time: -1 -end_time: 30 +end_time: -1 # Plant properties use_springs: true @@ -14,30 +15,35 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false plot_floating_base_velocities: false -plot_joint_positions: true +plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: true -special_positions_to_plot: [] -special_velocities_to_plot: ['base_vx', 'base_vy'] -special_efforts_to_plot: [] +plot_measured_efforts: false +special_positions_to_plot: [ ] +special_velocities_to_plot: [] +special_efforts_to_plot: [ ] + +# Finite State Machine Names +fsm_state_names: ['Left Stance (LS)', 'Left Flight (LF)', 'Right Stance (RS)', 'Right Flight (RF)'] # Foot position plots -foot_positions_to_plot: ['right', 'left'] -foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} +#foot_positions_to_plot: [ 'right', 'left' ] +foot_positions_to_plot: [] +#foot_xyz_to_plot: { 'right': [ 0, 2 ], 'left': [ 0, 2 ] } +foot_xyz_to_plot: { } pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: true -plot_qp_solve_time: true -plot_tracking_costs: true +plot_qp_costs: false +plot_qp_solve_time: false +plot_tracking_costs: false tracking_datas_to_plot: - pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['vel']} +# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel' ] } # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} - pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} - hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [1, 2], 'derivs': ['vel']} -# right_ft_traj: {'dims': [1, 2], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} +# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} +# hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} + left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} +# right_ft_traj: {'dims': [2], 'derivs': ['vel']} + left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} # right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} - left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} +# left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 8ddeb57f18..5527b9a02c 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,16 +9,14 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' - osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' reward_function_weights = '' - - action = np.zeros(18) action[2] = 1.0 cumulative_reward = 0 @@ -26,8 +24,8 @@ def main(): controller_plant = MultibodyPlant(8e-5) addCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() - # controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) - controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) + controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) + # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 63d41d6633..f2eb27bf1f 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -17,8 +17,12 @@ def __init__(self, figure=None): self.yellow = '#F2C100' self.grey = '#909090' self.orange = '#FE7F0E' - self.directory = None - self.fig = plt.figure() if figure is None else figure + # self.directory = None + self.dpi = 200 + self.directory = '/home/yangwill/Pictures/plot_styler/' + self.fig = plt.figure(dpi=self.dpi) if figure is None else figure + matplotlib.rcParams['figure.figsize'] = 8, 4 + self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] self.fig_id = self.fig.number return @@ -33,7 +37,7 @@ def set_default_styling(self, directory=None): matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" # matplotlib.rcParams['figure.figsize'] = 20, 12 # matplotlib.rcParams['figure.figsize'] = 20, 6 - matplotlib.rcParams['figure.figsize'] = 8, 5 + matplotlib.rcParams['figure.figsize'] = 8, 16 matplotlib.rcParams['figure.autolayout'] = True font = {'size': 18} matplotlib.rc('font', **font) @@ -82,12 +86,14 @@ def show_fig(self): def save_fig(self, filename): plt.figure(self.fig_id) - plt.savefig(self.directory + filename, dpi=200) + plt.savefig(self.directory + filename, dpi=self.dpi) return def add_legend(self, legend, loc=0): - plt.figure(self.fig_id) - plt.legend(legend, loc=loc) + # plt.figure(self.fig_id) + ax = self.fig.axes[0] + legend = ax.legend(legend, loc=loc) + ax.add_artist(legend) return def annotate(self, text, x, y, x_text, y_text, arrowprops=None): diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index a74a69b324..893525c347 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -31,7 +31,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, if key in legend_entries: legend.extend(legend_entries[key]) - plt.legend(legend) + plt.legend(legend, loc=1) plt.xlabel(plot_labels['xlabel']) plt.ylabel(plot_labels['ylabel']) plt.title(plot_labels['title']) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index e500aca4b5..504873343c 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -418,6 +418,7 @@ cc_binary( ":cassie_utils", ":simulator_drift", "//examples/Cassie/osc", + "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//multibody:utils", "//multibody:view_frame", "//multibody/kinematic", diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index f0fcc65f17..0fb8fde0dd 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -231,11 +231,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.rest_length, osc_running_gains.center_line_offset, - osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); + osc_running_gains.rest_length, osc_running_gains.footstep_lateral_offset, + osc_running_gains.footstep_sagital_offset, osc_running_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.rest_length, osc_running_gains.center_line_offset, - osc_running_gains.footstep_offset, osc_running_gains.mid_foot_height); + osc_running_gains.rest_length, osc_running_gains.footstep_lateral_offset, + osc_running_gains.footstep_sagital_offset, osc_running_gains.mid_foot_height); pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_running_gains.K_p_pelvis, diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index ab17451608..bea932fb12 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -63,7 +63,7 @@ void SwingToeTrajGenerator::CalcTraj( double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); - des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; + des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.125; auto* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 147d94fe60..12f678c1b7 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -8,6 +8,7 @@ using Eigen::Map; using Eigen::MatrixXd; using Eigen::Vector2d; using Eigen::Vector3d; +using Eigen::Vector4d; using Eigen::VectorXd; using std::string; @@ -67,6 +68,9 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, fsm_port_ = this->DeclareVectorInputPort( "fsm", BasicVector(VectorXd::Zero(1))) .get_index(); + clock_port_ = this->DeclareVectorInputPort( + "clock", BasicVector(VectorXd::Zero(1))) + .get_index(); // The swing foot position in the beginning of the swing phase initial_foot_pos_idx_ = this->DeclareDiscreteState(3); @@ -76,6 +80,8 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, // State variables inside this controller block DeclarePerStepDiscreteUpdateEvent(&FootTrajGenerator::DiscreteVariableUpdate); + + m_ = plant_.CalcTotalMass(*context_); } EventStatus FootTrajGenerator::DiscreteVariableUpdate( @@ -135,6 +141,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); + double clock = this->EvalVectorInput(context, clock_port_)->get_value()(0); VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); @@ -153,18 +160,55 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // TODO(yangwill): should not use estimated pelvis velocity - from discussion // with OSU DRL + Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; + /// ALIP + // x refers to sagital plane + // y refers to the lateral plane + auto foot_pos = context.get_discrete_state(initial_foot_pos_idx_).get_value(); + Vector3d pelvis_pos; + plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, + &pelvis_pos); + // double L_y_des = desired_pelvis_vel(0) * (pelvis_pos(2) - foot_pos(2)) * + // m_; double L_x_offset = + // -desired_pelvis_vel(1) * (pelvis_pos(2) - foot_pos(2)) * m_; + // Vector3d L = plant_.CalcSpatialMomentumInWorldAboutPoint(*context_, + // foot_pos) + // .rotational(); + // double H = pelvis_pos(2) - foot_pos(2); + // double omega = sqrt(9.81 / H); + // double T = state_durations_[4] - state_durations_[1]; + // Vector3d L_pred = m_ * H * omega * sinh(omega * (T - clock)) * pelvis_pos + // + + // cosh(omega * (T - clock)) * L; + // double L_x_n = 0.5 * m_ * H * lateral_offset_ * + // (omega * sinh(omega * T) / (1 + cosh(omega * T))); + // Vector2d L_i = multibody::ReExpressWorldVector2InBodyYawFrame( + // plant_, *context_, "pelvis", L_pred.head(2)); + // double p_x_ft_to_com = + // (L_y_des - cosh(omega * T) * L_i(1)) / (m_ * H * omega * sinh(omega * + // T)); + // double p_y_ft_to_com = -(L_x_offset + L_x_n - cosh(omega * T) * L_i(0)) / + // (m_ * H * omega * sinh(omega * T)); + // Vector2d foot_end_pos_xy = Vector2d(-p_x_ft_to_com, p_y_ft_to_com); + // + // Vector3d foot_end_pos_des = Vector3d::Zero(); + // foot_end_pos_des << foot_end_pos_xy, 0; + + // /// ALIP + // VectorXd pelvis_vel = v.segment(3, 3); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; - VectorXd footstep_correction = Kd_ * (pelvis_vel_err); + VectorXd foot_end_pos_des = Kd_ * (pelvis_vel_err); + if (is_left_foot_) { - footstep_correction(1) += center_line_offset_; + foot_end_pos_des(1) += lateral_offset_; } else { - footstep_correction(1) -= center_line_offset_; + foot_end_pos_des(1) -= lateral_offset_; } - footstep_correction(0) += footstep_offset_; - footstep_correction(2) = 0; + foot_end_pos_des(0) += sagital_offset_; + foot_end_pos_des(2) = 0; std::vector T_waypoints; std::vector T_waypoints_0; @@ -182,28 +226,29 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( T_waypoints_1 = {state_durations_[2], state_durations_[3]}; T_waypoints_2 = {state_durations_[3], state_durations_[4]}; - auto foot_pos = context.get_discrete_state(initial_foot_pos_idx_).get_value(); + // auto foot_pos = + // context.get_discrete_state(initial_foot_pos_idx_).get_value(); auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; - if(start_pos(2) == 0){ + if (start_pos(2) == 0) { Y[0](2) = -rest_length_; } - Y[1] = start_pos + 0.85 * footstep_correction; + Y[1] = start_pos + 0.85 * foot_end_pos_des; Y[1](2) = -rest_length_ + mid_foot_height_; - Y[2] = footstep_correction; + Y[2] = foot_end_pos_des; Y[2](2) = -rest_length_ + mid_foot_height_ / 2; // corrections if (is_left_foot_) { - Y[1](1) -= 0.25 * center_line_offset_; - Y[1](1) = drake::math::saturate(Y[1](1), center_line_offset_, 0.2); - Y[2](1) = drake::math::saturate(Y[2](1), center_line_offset_, 0.2); + Y[1](1) -= 0.25 * lateral_offset_; + Y[1](1) = drake::math::saturate(Y[1](1), lateral_offset_, 0.2); + Y[2](1) = drake::math::saturate(Y[2](1), lateral_offset_, 0.2); } else { - Y[1](1) += 0.25 * center_line_offset_; - Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -center_line_offset_); - Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -center_line_offset_); + Y[1](1) += 0.25 * lateral_offset_; + Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -lateral_offset_); + Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -lateral_offset_); } MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index ebccdf4f57..72b8b7eb52 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -23,6 +23,9 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::systems::InputPort& get_fsm_input_port() const { return this->get_input_port(fsm_port_); } + const drake::systems::InputPort& get_clock_input_port() const { + return this->get_input_port(clock_port_); + } const drake::systems::InputPort& get_target_vel_input_port() const { return this->get_input_port(target_vel_port_); } @@ -32,8 +35,8 @@ class FootTrajGenerator : public drake::systems::LeafSystem { void SetFootPlacementOffsets(double rest_length, double center_line_offset, double footstep_offset, double mid_foot_height) { rest_length_ = rest_length; - center_line_offset_ = center_line_offset; - footstep_offset_ = footstep_offset; + lateral_offset_ = center_line_offset; + sagital_offset_ = footstep_offset; mid_foot_height_ = mid_foot_height; } @@ -58,9 +61,10 @@ class FootTrajGenerator : public drake::systems::LeafSystem { // Foot placement constants double rest_length_; - double center_line_offset_; - double footstep_offset_; + double lateral_offset_; + double sagital_offset_; double mid_foot_height_; + double m_; // Raibert Footstep Gains Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(3, 3); @@ -72,6 +76,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { int state_port_; int target_vel_port_; int fsm_port_; + int clock_port_; int initial_foot_pos_idx_; int initial_hip_pos_idx_; int pelvis_yaw_idx_; diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 2190272219..455d4362a5 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -29,8 +29,8 @@ struct OSCRunningGains : OSCGains { double stance_duration; double flight_duration; - double center_line_offset; - double footstep_offset; + double footstep_lateral_offset; + double footstep_sagital_offset; double mid_foot_height; std::vector ekf_filter_tau; @@ -87,8 +87,8 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(rest_length)); a->Visit(DRAKE_NVP(stance_duration)); a->Visit(DRAKE_NVP(flight_duration)); - a->Visit(DRAKE_NVP(center_line_offset)); - a->Visit(DRAKE_NVP(footstep_offset)); + a->Visit(DRAKE_NVP(footstep_lateral_offset)); + a->Visit(DRAKE_NVP(footstep_sagital_offset)); a->Visit(DRAKE_NVP(mid_foot_height)); a->Visit(DRAKE_NVP(ekf_filter_tau)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e4884974eb..56b345e110 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,17 +40,18 @@ w_hip_yaw: 2.5 hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters -footstep_offset: -0.05 -center_line_offset: 0.04 +#footstep_offset: -0.05 +footstep_sagital_offset: -0.05 +footstep_lateral_offset: 0.04 mid_foot_height: 0.05 FootstepKd: - [ 0.2, 0, 0, - 0, 0.6, 0, - 0, 0, 0] + [ 0.2, 0, 0, + 0, 0.6, 0, + 0, 0, 0 ] PelvisW: - [0.1, 0, 0, - 0, 0, 0, - 0, 0, 5] + [ 0.1, 0, 0, + 0, 0, 0, + 0, 0, 5 ] PelvisKp: [ 0, 0, 0, 0, 0, 0, @@ -76,7 +77,7 @@ SwingFootW: 0, 100, 0, 0, 0, 5] SwingFootKp: - [125, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 50] SwingFootKd: @@ -92,7 +93,7 @@ LiftoffSwingFootKp: 0, 50, 0, 0, 0, 50] LiftoffSwingFootKd: - [ 1, 0, 0, + [ 5, 0, 0, 0, 5, 0, 0, 0, 1] diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index ef9835eff9..46b10d706d 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 1000 +max_iter: 200 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -9,7 +9,7 @@ alpha: 1.6 linsys_solver: 0 delta: 1e-6 polish: 1 -polish_refine_iter: 3 +polish_refine_iter: 1 verbose: 0 scaled_termination: 1 check_termination: 25 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index d9e4d66e6c..cfce52160b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -290,11 +290,11 @@ int DoMain(int argc, char* argv[]) { l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_gains.rest_length, osc_gains.center_line_offset, - osc_gains.footstep_offset, osc_gains.mid_foot_height); + osc_gains.rest_length, osc_gains.footstep_lateral_offset, + osc_gains.footstep_sagital_offset, osc_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( - osc_gains.rest_length, osc_gains.center_line_offset, - osc_gains.footstep_offset, osc_gains.mid_foot_height); + osc_gains.rest_length, osc_gains.footstep_lateral_offset, + osc_gains.footstep_sagital_offset, osc_gains.mid_foot_height); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, @@ -542,6 +542,11 @@ int DoMain(int argc, char* argv[]) { l_foot_traj_generator->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), r_foot_traj_generator->get_state_input_port()); + + builder.Connect(fsm->get_output_port_clock(), + l_foot_traj_generator->get_clock_input_port()); + builder.Connect(fsm->get_output_port_clock(), + r_foot_traj_generator->get_clock_input_port()); builder.Connect(fsm->get_output_port_fsm(), l_foot_traj_generator->get_fsm_input_port()); builder.Connect(fsm->get_output_port_fsm(), diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 5f9964961b..e1f5ce12dd 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -8,6 +8,7 @@ #include "examples/Cassie/osc/osc_walking_gains.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/simulator_drift.h" +#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" @@ -214,7 +215,7 @@ int DoMain(int argc, char* argv[]) { state_durations = {left_support_duration, double_support_duration, right_support_duration, double_support_duration}; } - auto fsm = builder.AddSystem( + auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); builder.Connect(simulator_drift->get_output_port(0), fsm->get_input_port_state()); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f3ff76bc17..1c0f664d2c 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -539,7 +539,7 @@ VectorXd OperationalSpaceControl::SolveQp( next_fsm_state, M); // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; -// std::cout << v_proj.transpose() << std::endl; + // std::cout << v_proj.transpose() << std::endl; } // SetVelocitiesIfNew( // plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, @@ -761,8 +761,8 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); - u_sol_->row(0) = 0.95 * u_sol_->row(0) + 0.05 * u_prev_->row(0); - u_sol_->row(1) = 0.95 * u_sol_->row(1) + 0.05 * u_prev_->row(1); + // u_sol_->row(0) = 0.95 * u_sol_->row(0) + 0.05 * u_prev_->row(0); + // u_sol_->row(1) = 0.95 * u_sol_->row(1) + 0.05 * u_prev_->row(1); // *u_prev_ = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; @@ -1069,24 +1069,24 @@ void OperationalSpaceControl::CalcOptimalInput( next_fsm_state = impact_info->GetCurrentContactMode(); } -// if(fsm_state(0) == 0){ -// x_wo_spr[19] = 0; -// x_wo_spr[21] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } -// else if(fsm_state(0) == 1){ -// x_wo_spr[11] = 0; -// x_wo_spr[13] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } -// else{ -// x_wo_spr[11] = 0; -// x_wo_spr[13] = 0; -// x_wo_spr[19] = 0; -// x_wo_spr[21] = 0; -// } + if (fsm_state(0) == 0) { + x_wo_spr[19] = 0; + x_wo_spr[21] = 0; + x_wo_spr[33] = 0; + x_wo_spr[41] = 0; + } else if (fsm_state(0) == 1) { + x_wo_spr[11] = 0; + x_wo_spr[13] = 0; + x_wo_spr[33] = 0; + x_wo_spr[41] = 0; + } else { + x_wo_spr[11] = 0; + x_wo_spr[13] = 0; + x_wo_spr[19] = 0; + x_wo_spr[21] = 0; + x_wo_spr[33] = 0; + x_wo_spr[41] = 0; + } // Get discrete states const auto prev_event_time = From 29ae579b71b5a5a3369a2b68b40f5d6d08af9abf Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 10 May 2022 12:01:47 -0400 Subject: [PATCH 198/758] fixing alip controller --- examples/Cassie/BUILD.bazel | 1 + .../Cassie/osc/osc_walking_gains_alip.yaml | 4 +-- .../Cassie/run_osc_walking_controller_alip.cc | 7 +++- .../osc/operational_space_control.cc | 36 +++++++++---------- 4 files changed, 27 insertions(+), 21 deletions(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 504873343c..d806a2bd44 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -425,6 +425,7 @@ cc_binary( "//solvers:osqp_solver_options", "//systems:robot_lcm_systems", "//systems/controllers:fsm_event_time", + "//systems/controllers:controllers_all", "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 44cd54c296..0e59f97bdc 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -43,12 +43,12 @@ ds_time: 0.1 max_CoM_to_footstep_dist: 0.55 footstep_offset: 0.25 center_line_offset: 0.03 -mid_foot_height: 0.2 +mid_foot_height: 0.1 final_foot_height: 0.0 final_foot_velocity_z: 0.0 # LIPM trajectory -lipm_height: 0.85 +lipm_height: 0.75 # OSC gains mu: 0.75 diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index e1f5ce12dd..2f565e1921 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -15,6 +15,7 @@ #include "systems/controllers/alip_swing_ft_traj_gen.h" #include "systems/controllers/alip_traj_gen.h" #include "systems/controllers/fsm_event_time.h" +#include "systems/controllers/cassie_out_to_radio.h" #include "systems/controllers/osc/com_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" @@ -97,7 +98,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant_w_spr(0.0); if (FLAGS_spring_model) { addCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2.urdf", + "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); } else { addCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, @@ -142,6 +143,8 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant_w_spr); + auto cassie_out_to_radio = + builder.AddSystem(); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -176,6 +179,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(cassie_out_receiver->get_output_port(), + cassie_out_to_radio->get_input_port()); + builder.Connect(cassie_out_to_radio->get_output_port(), high_level_command->get_radio_input_port()); } else { high_level_command = builder.AddSystem( diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 1c0f664d2c..2a9c3eaeea 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1069,24 +1069,24 @@ void OperationalSpaceControl::CalcOptimalInput( next_fsm_state = impact_info->GetCurrentContactMode(); } - if (fsm_state(0) == 0) { - x_wo_spr[19] = 0; - x_wo_spr[21] = 0; - x_wo_spr[33] = 0; - x_wo_spr[41] = 0; - } else if (fsm_state(0) == 1) { - x_wo_spr[11] = 0; - x_wo_spr[13] = 0; - x_wo_spr[33] = 0; - x_wo_spr[41] = 0; - } else { - x_wo_spr[11] = 0; - x_wo_spr[13] = 0; - x_wo_spr[19] = 0; - x_wo_spr[21] = 0; - x_wo_spr[33] = 0; - x_wo_spr[41] = 0; - } +// if (fsm_state(0) == 0) { +// x_wo_spr[19] = 0; +// x_wo_spr[21] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } else if (fsm_state(0) == 1) { +// x_wo_spr[11] = 0; +// x_wo_spr[13] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } else { +// x_wo_spr[11] = 0; +// x_wo_spr[13] = 0; +// x_wo_spr[19] = 0; +// x_wo_spr[21] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } // Get discrete states const auto prev_event_time = From 354a5ee745be0e9941595d18e73d68c3015f401e Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 10 May 2022 12:58:40 -0400 Subject: [PATCH 199/758] updating alip gains --- examples/Cassie/osc/osc_walking_gains.h | 2 ++ examples/Cassie/osc/osc_walking_gains_alip.yaml | 1 + examples/Cassie/run_osc_walking_controller_alip.cc | 2 +- 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/examples/Cassie/osc/osc_walking_gains.h b/examples/Cassie/osc/osc_walking_gains.h index ae2e398bb0..435dd31086 100644 --- a/examples/Cassie/osc/osc_walking_gains.h +++ b/examples/Cassie/osc/osc_walking_gains.h @@ -12,6 +12,7 @@ struct OSCWalkingGains { double w_accel; double w_soft_constraint; double w_input_reg; + double impact_threshold; bool relative_swing_ft; std::vector pelvis_xyz_vel_filter_tau; std::vector CoMW; @@ -92,6 +93,7 @@ struct OSCWalkingGains { a->Visit(DRAKE_NVP(w_soft_constraint)); a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(relative_swing_ft)); + a->Visit(DRAKE_NVP(impact_threshold)); a->Visit(DRAKE_NVP(pelvis_xyz_vel_filter_tau)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 0e59f97bdc..d5237a41f6 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -38,6 +38,7 @@ k_fb_lateral: 0.1 # Finite state machine ss_time: 0.3 ds_time: 0.1 +impact_threshold: 0.025 # Swing foot trajectory max_CoM_to_footstep_dist: 0.55 diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 2f565e1921..ec297f128a 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -221,7 +221,7 @@ int DoMain(int argc, char* argv[]) { right_support_duration, double_support_duration}; } auto fsm = builder.AddSystem( - plant_w_spr, fsm_states, state_durations); + plant_w_spr, fsm_states, state_durations, 0.0, gains.impact_threshold); builder.Connect(simulator_drift->get_output_port(0), fsm->get_input_port_state()); From ba1d552fe45a182f40dbc21d3c1d8ebd6df71c67 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 11 May 2022 14:05:52 -0400 Subject: [PATCH 200/758] running works well on mujoco and drake --- .../pydairlib/analysis/cassie_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_cassie.py | 4 +++ .../pydairlib/analysis/mbp_plotting_utils.py | 26 +++++++++++++++++++ .../plot_configs/cassie_running_plot.yaml | 16 +++++++----- examples/Cassie/cassie_lcm_driven_loop.h | 2 +- examples/Cassie/dispatcher_robot_in.cc | 24 ++++++++--------- .../Cassie/osc/osc_walking_gains_alip.yaml | 4 +-- .../Cassie/osc_run/osc_running_gains.yaml | 6 ++--- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/urdf/cassie_v2.urdf | 4 +-- solvers/default_osc_osqp_settings.yaml | 2 +- systems/controllers/geared_motor.cc | 4 +-- .../osc/operational_space_control.cc | 20 +++++++------- .../osc/operational_space_control.h | 3 ++- 14 files changed, 77 insertions(+), 41 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index df4817f1ff..2c1942ecde 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -22,6 +22,7 @@ def __init__(self, filename): self.plot_joint_positions = data['plot_joint_positions'] self.plot_joint_velocities = data['plot_joint_velocities'] self.plot_measured_efforts = data['plot_measured_efforts'] + self.plot_commanded_efforts = data['plot_commanded_efforts'] self.pos_names = \ data['special_positions_to_plot'] if \ data['special_positions_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index a4c933a9f9..53482f1774 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -83,6 +83,10 @@ def main(): plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + if plot_config.plot_commanded_efforts: + plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + if plot_config.act_names: mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 34bbe5e973..a4d66aae8a 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -207,6 +207,27 @@ def plot_q_or_v_or_u( 'title': title}, ps) return ps +def plot_u_cmd( + robot_input, key, x_names, x_slice, time_slice, + ylabel=None, title=None): + ps = plot_styler.PlotStyler() + if ylabel is None: + ylabel = key + if title is None: + title = key + + plotting_utils.make_plot( + robot_input, # data dict + 't_u', # time channel + time_slice, + [key], # key to plot + {key: x_slice}, # slice of key to plot + {key: x_names}, # legend entries + {'xlabel': 'Time', + 'ylabel': ylabel, + 'title': title}, ps) + return ps + def plot_floating_base_positions(robot_output, q_names, fb_dim, time_slice): return plot_q_or_v_or_u(robot_output, 'q', q_names[:fb_dim], slice(fb_dim), @@ -251,6 +272,11 @@ def plot_measured_efforts(robot_output, u_names, time_slice): time_slice, ylabel='Efforts (Nm)', title='Joint Efforts') +def plot_commanded_efforts(robot_input, u_names, time_slice): + return plot_u_cmd(robot_input, 'u', u_names, slice(len(u_names)), + time_slice, ylabel='Efforts (Nm)', + title='Commanded Joint Efforts') + def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): u_slice = [u_map[name] for name in u_names] diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 6908c4969a..2fdf0037ae 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -2,6 +2,7 @@ #channel_x: "CASSIE_STATE_SIMULATION" channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" +#channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) @@ -15,9 +16,10 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false plot_floating_base_velocities: false -plot_joint_positions: false +plot_joint_positions: true plot_joint_velocities: false -plot_measured_efforts: false +plot_measured_efforts: true +plot_commanded_efforts: true special_positions_to_plot: [ ] special_velocities_to_plot: [] special_efforts_to_plot: [ ] @@ -33,17 +35,17 @@ foot_xyz_to_plot: { } pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: false -plot_qp_solve_time: false -plot_tracking_costs: false +plot_qp_costs: true +plot_qp_solve_time: true +plot_tracking_costs: true tracking_datas_to_plot: # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel' ] } # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + left_ft_traj: {'dims': [1], 'derivs': ['pos']} # right_ft_traj: {'dims': [2], 'derivs': ['vel']} - left_ft_z_traj: {'dims': [0, 1, 2], 'derivs': ['pos']} + left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} # right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index 793cfe5bc0..0e25583a01 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -214,7 +214,7 @@ class CassieLcmDrivenLoop { if (state_sub_ != nullptr) { if (state_sub_->count() > 0) { if (state_sub_->message().utime * 1e-6 - last_input_msg_time_ > - 0.1) { + 0.02) { too_long_between_input_messages_ = true; } is_new_state_message = too_long_between_input_messages_; diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 2e5f6b0471..fc0a0795f3 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -6,6 +6,7 @@ #include "dairlib/lcmt_controller_failure.hpp" #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_lcm_driven_loop.h" #include "examples/Cassie/cassie_utils.h" #include "examples/Cassie/input_supervisor.h" #include "examples/Cassie/networking/cassie_input_translator.h" @@ -13,7 +14,6 @@ #include "multibody/multibody_utils.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" -#include "examples/Cassie/cassie_lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "drake/lcm/drake_lcm.h" @@ -116,12 +116,12 @@ int do_main(int argc, char* argv[]) { auto state_receiver = builder.AddSystem(plant); auto input_supervisor_status_pub = builder.AddSystem( LcmPublisherSystem::Make( - "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, FLAGS_pub_rate)); + "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, + FLAGS_pub_rate)); builder.Connect(*state_sub, *state_receiver); double input_supervisor_update_period = 1.0 / 1000.0; - // Get input limits int nu = plant.num_actuators(); VectorXd input_limit(nu); @@ -167,22 +167,22 @@ int do_main(int argc, char* argv[]) { // Create and connect LCM command echo to network auto net_command_sender = builder.AddSystem(plant); - LcmPublisherSystem* command_pub; - if (FLAGS_sim) { - command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); - } else { - command_pub = + LcmPublisherSystem* command_pub_network; + if (!FLAGS_sim) { + command_pub_network = builder.AddSystem(LcmPublisherSystem::Make( "NETWORK_CASSIE_INPUT", &lcm_network, {TriggerType::kPeriodic}, FLAGS_pub_rate)); + builder.Connect(*net_command_sender, *command_pub_network); } + auto command_pub_local = + builder.AddSystem(LcmPublisherSystem::Make( + "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); builder.Connect(input_supervisor->get_output_port_command(), net_command_sender->get_input_port(0)); - builder.Connect(*net_command_sender, *command_pub); + builder.Connect(*net_command_sender, *command_pub_local); // Finish building the diagram auto owned_diagram = builder.Build(); @@ -201,7 +201,7 @@ int do_main(int argc, char* argv[]) { // Run lcm-driven simulation CassieLcmDrivenLoop + dairlib::lcmt_controller_switch> loop(&lcm_local, std::move(owned_diagram), command_receiver, input_channels, FLAGS_control_channel_name_initial, switch_channel, true, FLAGS_state_channel_name); diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index d5237a41f6..8f67a58769 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -45,7 +45,7 @@ max_CoM_to_footstep_dist: 0.55 footstep_offset: 0.25 center_line_offset: 0.03 mid_foot_height: 0.1 -final_foot_height: 0.0 +final_foot_height: 0.00 final_foot_velocity_z: 0.0 # LIPM trajectory @@ -62,7 +62,7 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 0.5 +w_hip_yaw: 2.5 hip_yaw_kp: 40 hip_yaw_kd: 0.5 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 56b345e110..62bdffead4 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -14,7 +14,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 w_soft_constraint: 100 -w_input_reg: 0.001 +w_input_reg: 0.1 impact_threshold: 0.025 relative_feet: true relative_pelvis: true @@ -45,7 +45,7 @@ footstep_sagital_offset: -0.05 footstep_lateral_offset: 0.04 mid_foot_height: 0.05 FootstepKd: - [ 0.2, 0, 0, + [ 0.25, 0, 0, 0, 0.6, 0, 0, 0, 0 ] PelvisW: @@ -85,7 +85,7 @@ SwingFootKd: 0, 5., 0, 0, 0, 1.] LiftoffSwingFootW: - [0.1, 0, 0, + [1, 0, 0, 0, 100, 0, 0, 0, 1] LiftoffSwingFootKp: diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 46b10d706d..21759909aa 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 200 +max_iter: 50 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/urdf/cassie_v2.urdf b/examples/Cassie/urdf/cassie_v2.urdf index b8ec0ff559..46284e004a 100644 --- a/examples/Cassie/urdf/cassie_v2.urdf +++ b/examples/Cassie/urdf/cassie_v2.urdf @@ -615,7 +615,7 @@ - + @@ -624,7 +624,7 @@ - + diff --git a/solvers/default_osc_osqp_settings.yaml b/solvers/default_osc_osqp_settings.yaml index f92be5a6c5..8463e69c11 100644 --- a/solvers/default_osc_osqp_settings.yaml +++ b/solvers/default_osc_osqp_settings.yaml @@ -9,7 +9,7 @@ alpha: 1.6 linsys_solver: 0 delta: 1e-6 polish: 1 -polish_refine_iter: 3 +polish_refine_iter: 1 verbose: 0 scaled_termination: 1 check_termination: 25 diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc index f11037ab1b..c0b5091da1 100644 --- a/systems/controllers/geared_motor.cc +++ b/systems/controllers/geared_motor.cc @@ -55,8 +55,8 @@ void GearedMotor::CalcTorqueOutput( tlim = fmax(fmin(tlim, tmax), 0); // Compute motor-side torque - // tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); - tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); + tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); +// tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); } output->SetFromVector(tau); } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 2a9c3eaeea..f3b9ee698b 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -305,10 +305,10 @@ void OperationalSpaceControl::Build() { lambda_c_sol_ = std::make_unique(n_c_); lambda_h_sol_ = std::make_unique(n_h_); epsilon_sol_ = std::make_unique(n_c_active_); - u_prev_ = std::make_unique(n_u_); +// u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); - u_prev_->setZero(); +// u_prev_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); epsilon_sol_->setZero(); @@ -738,9 +738,11 @@ VectorXd OperationalSpaceControl::SolveQp( } // (Testing) 7. Cost for staying close to the previous input - if (W_input_smoothing_.size() > 0) { + if (W_input_smoothing_.size() > 0 && initial_guess_x_.count(fsm_state) > 0) { +// input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, +// -W_input_smoothing_ * (*u_prev_)); input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, - -W_input_smoothing_ * (*u_prev_)); + -W_input_smoothing_ * u_prev_[fsm_state]); } // if (!solver_->IsInitialized()) { @@ -763,12 +765,12 @@ VectorXd OperationalSpaceControl::SolveQp( *epsilon_sol_ = result.GetSolution(epsilon_); // u_sol_->row(0) = 0.95 * u_sol_->row(0) + 0.05 * u_prev_->row(0); // u_sol_->row(1) = 0.95 * u_sol_->row(1) + 0.05 * u_prev_->row(1); - // *u_prev_ = *u_sol_; + u_prev_[fsm_state] = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { // *u_prev_ = VectorXd::Zero(n_u_); - *u_prev_ = 0.9 * *u_sol_ + VectorXd::Random(n_u_); + u_prev_[fsm_state] = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } solve_time_ = result.get_solver_details().run_time; @@ -915,8 +917,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( : 0; double input_smoothing_cost = (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_ - *u_prev_).transpose() * W_input_smoothing_ * - (*u_sol_ - *u_prev_))(0) + ? (0.5 * (*u_sol_ - u_prev_[fsm_state]).transpose() * W_input_smoothing_ * + (*u_sol_ - u_prev_[fsm_state]))(0) : 0; double lambda_h_cost = (W_lambda_h_reg_.size() > 0) ? (0.5 * (*lambda_h_sol_).transpose() * @@ -1020,7 +1022,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_data[i] = osc_output; } // std::cout << total_cost_ << std::endl; - *u_prev_ = *u_sol_; +// *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index d6bd4f4af1..912a051f2f 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -346,7 +346,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::unique_ptr lambda_c_sol_; std::unique_ptr lambda_h_sol_; std::unique_ptr epsilon_sol_; - std::unique_ptr u_prev_; +// std::unique_ptr u_prev_; mutable double solve_time_; mutable Eigen::VectorXd ii_lambda_sol_; @@ -380,6 +380,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { mutable std::unordered_map initial_guess_x_ = {}; mutable std::unordered_map initial_guess_y_ = {}; + mutable std::unordered_map u_prev_ = {}; // OSC tracking data (stored as a pointer because of caching) std::unique_ptr>> From b18ed3520f93d1950efb2d9250d403ab1d2c98ac Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 11 May 2022 15:09:52 -0400 Subject: [PATCH 201/758] getting walking to work again --- .../pydairlib/analysis/log_plotter_cassie.py | 3 +- .../plot_configs/cassie_default_plot.yaml | 10 ++-- .../plot_configs/cassie_running_plot.yaml | 4 +- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/cassie_lcm_driven_loop.h | 2 +- examples/Cassie/osc/osc_walking_gains.h | 16 ++++++ .../Cassie/osc/osc_walking_gains_alip.yaml | 16 ++++-- .../Cassie/run_osc_walking_controller_alip.cc | 52 +++++++++++++------ solvers/default_osc_osqp_settings.yaml | 8 +-- systems/controllers/geared_motor.cc | 4 +- .../osc/operational_space_control.cc | 25 ++++----- 11 files changed, 96 insertions(+), 45 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 53482f1774..1a25d93ab8 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,7 +12,8 @@ def main(): - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' # config_file = \ # 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index 03bc8ed8e6..fd5abbf1d7 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -1,6 +1,6 @@ # LCM channels to read data from channel_x: "CASSIE_STATE_DISPATCHER" -channel_u: "OSC_WALKING" +channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_WALKING" # Log time to stop at (seconds, -1 for whole log) @@ -15,11 +15,15 @@ plot_floating_base_positions: false plot_floating_base_velocities: false plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: false +plot_measured_efforts: true +plot_commanded_efforts: true special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [] +# Finite State Machine Names +fsm_state_names: ['Left Stance (LS)', 'Left Flight (LF)', ' ', 'Right Stance (RS)', 'Right Flight (RF)'] + # Foot position plots foot_positions_to_plot: ['right', 'left'] foot_xyz_to_plot: {'right': [0, 1, 2], 'left': [0, 1, 2]} @@ -30,5 +34,5 @@ plot_qp_costs: true plot_tracking_costs: true plot_qp_solve_time: true tracking_datas_to_plot: - lipm_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + alip_com_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 2fdf0037ae..e75b4d1a2f 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -43,9 +43,9 @@ tracking_datas_to_plot: # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} - left_ft_traj: {'dims': [1], 'derivs': ['pos']} +# left_ft_traj: {'dims': [1], 'derivs': ['pos']} # right_ft_traj: {'dims': [2], 'derivs': ['vel']} - left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} +# left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} # right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index d806a2bd44..7278fe651e 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -426,6 +426,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/controllers:fsm_event_time", "//systems/controllers:controllers_all", + "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index 0e25583a01..793cfe5bc0 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -214,7 +214,7 @@ class CassieLcmDrivenLoop { if (state_sub_ != nullptr) { if (state_sub_->count() > 0) { if (state_sub_->message().utime * 1e-6 - last_input_msg_time_ > - 0.02) { + 0.1) { too_long_between_input_messages_ = true; } is_new_state_message = too_long_between_input_messages_; diff --git a/examples/Cassie/osc/osc_walking_gains.h b/examples/Cassie/osc/osc_walking_gains.h index 435dd31086..5c16148aa7 100644 --- a/examples/Cassie/osc/osc_walking_gains.h +++ b/examples/Cassie/osc/osc_walking_gains.h @@ -84,6 +84,11 @@ struct OSCWalkingGains { MatrixXd K_p_hip_yaw; MatrixXd K_d_hip_yaw; + std::vector W_lambda_c_reg; + std::vector W_lambda_h_reg; + MatrixXd W_lambda_c_regularization; + MatrixXd W_lambda_h_regularization; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(rows)); @@ -193,5 +198,16 @@ struct OSCWalkingGains { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); + + a->Visit(DRAKE_NVP(W_lambda_c_reg)); + a->Visit(DRAKE_NVP(W_lambda_h_reg)); + Eigen::VectorXd w_lambda_c_regularization = + Eigen::Map( + this->W_lambda_c_reg.data(), this->W_lambda_c_reg.size()); + Eigen::VectorXd w_lambda_h_regularization = + Eigen::Map( + this->W_lambda_h_reg.data(), this->W_lambda_h_reg.size()); + W_lambda_c_regularization = w_lambda_c_regularization.asDiagonal(); + W_lambda_h_regularization = w_lambda_h_regularization.asDiagonal(); } }; diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 8f67a58769..9668d38e1a 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -44,25 +44,31 @@ impact_threshold: 0.025 max_CoM_to_footstep_dist: 0.55 footstep_offset: 0.25 center_line_offset: 0.03 -mid_foot_height: 0.1 -final_foot_height: 0.00 +mid_foot_height: 0.2 +final_foot_height: 0.0 final_foot_velocity_z: 0.0 # LIPM trajectory lipm_height: 0.75 # OSC gains -mu: 0.75 +mu: 0.4 w_accel: 0.00000001 -w_soft_constraint: 80 +w_soft_constraint: 150 w_input_reg: 0.0000003 +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 2.5 +w_hip_yaw: 0.5 hip_yaw_kp: 40 hip_yaw_kd: 0.5 diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index ec297f128a..40b9285d4f 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -25,11 +25,13 @@ #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/controllers/time_based_fsm.h" #include "systems/framework/lcm_driven_loop.h" +#include "systems/filters/floating_base_velocity_filter.h" #include "systems/robot_lcm_systems.h" #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_scope_system.h" namespace dairlib { @@ -88,6 +90,8 @@ DEFINE_bool(is_two_phase, false, DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); DEFINE_bool(spring_model, true, ""); +DEFINE_bool(publish_filtered_state, false, + "whether to publish the low pass filtered state"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -99,7 +103,7 @@ int DoMain(int argc, char* argv[]) { if (FLAGS_spring_model) { addCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, "examples/Cassie/urdf/cassie_v2_conservative.urdf", - true /*spring model*/, false /*loop closure*/); + false /*spring model*/, false /*loop closure*/); } else { addCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, "examples/Cassie/urdf/cassie_fixed_springs.urdf", @@ -136,6 +140,18 @@ int DoMain(int argc, char* argv[]) { // Create state receiver. auto state_receiver = builder.AddSystem(plant_w_spr); + auto pelvis_filt = + builder.AddSystem( + plant_w_spr, gains.pelvis_xyz_vel_filter_tau); + builder.Connect(*state_receiver, *pelvis_filt); + + if (FLAGS_publish_filtered_state) { + auto [filtered_state_scope, filtered_state_sender]= + // AddToBuilder will add the systems to the diagram and connect their ports + drake::systems::lcm::LcmScopeSystem::AddToBuilder( + &builder, &lcm_local,pelvis_filt->get_output_port(), + "CASSIE_STATE_FB_FILTERED", 0); + } // Create command sender. auto command_pub = @@ -162,7 +178,7 @@ int DoMain(int argc, char* argv[]) { auto simulator_drift = builder.AddSystem(plant_w_spr, drift_mean, drift_cov); - builder.Connect(state_receiver->get_output_port(0), + builder.Connect(pelvis_filt->get_output_port(0), simulator_drift->get_input_port_state()); // Create human high-level control @@ -190,7 +206,7 @@ int DoMain(int argc, char* argv[]) { gains.vel_max_lateral, gains.target_pos_offset, global_target_position, params_of_no_turning); } - builder.Connect(state_receiver->get_output_port(0), + builder.Connect(pelvis_filt->get_output_port(0), high_level_command->get_state_input_port()); // Create heading traj generator @@ -232,7 +248,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, single_support_states); liftoff_event_time->set_name("liftoff_time"); - builder.Connect(fsm->get_output_port(0), + builder.Connect(fsm->get_output_port_fsm(), liftoff_event_time->get_input_port_fsm()); builder.Connect(simulator_drift->get_output_port(0), liftoff_event_time->get_input_port_state()); @@ -242,7 +258,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, double_support_states); touchdown_event_time->set_name("touchdown_time"); - builder.Connect(fsm->get_output_port(0), + builder.Connect(fsm->get_output_port_fsm(), touchdown_event_time->get_input_port_fsm()); builder.Connect(simulator_drift->get_output_port(0), touchdown_event_time->get_input_port_state()); @@ -276,7 +292,7 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), desired_com_height, unordered_fsm_states, unordered_state_durations, contact_points_in_each_state); - builder.Connect(fsm->get_output_port(0), + builder.Connect(fsm->get_output_port_fsm(), alip_traj_generator->get_input_port_fsm()); builder.Connect(touchdown_event_time->get_output_port_event_time(), alip_traj_generator->get_input_port_touchdown_time()); @@ -305,7 +321,7 @@ int DoMain(int argc, char* argv[]) { gains.final_foot_height, gains.final_foot_velocity_z, gains.max_CoM_to_footstep_dist, gains.footstep_offset, gains.center_line_offset, wrt_com_in_local_frame); - builder.Connect(fsm->get_output_port(0), + builder.Connect(fsm->get_output_port_fsm(), swing_ft_traj_generator->get_input_port_fsm()); builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), swing_ft_traj_generator->get_input_port_fsm_switch_time()); @@ -330,9 +346,9 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, context_w_spr.get(), pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); - builder.Connect(state_receiver->get_output_port(0), + builder.Connect(pelvis_filt->get_output_port(0), left_toe_angle_traj_gen->get_state_input_port()); - builder.Connect(state_receiver->get_output_port(0), + builder.Connect(pelvis_filt->get_output_port(0), right_toe_angle_traj_gen->get_state_input_port()); // Create Operational space control @@ -345,8 +361,12 @@ int DoMain(int argc, char* argv[]) { int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingWeights(gains.w_input_reg * - MatrixXd::Identity(n_u, n_u)); + osc->SetLambdaContactRegularizationWeight(1e-4 * + gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); +// osc->SetInputSmoothingWeights(gains.w_input_reg * +// MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -460,7 +480,7 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, plant_w_spr); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); - com_data->SetImpactInvariantProjection(true); +// com_data->SetImpactInvariantProjection(true); auto swing_ft_traj_local = std::make_unique ( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), @@ -544,14 +564,16 @@ int DoMain(int argc, char* argv[]) { double_support_duration, left_stance_state, right_stance_state, {post_left_double_support_state, post_right_double_support_state}); - osc->SetOsqpSolverOptionsFromYaml( - "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml"); +// osc->SetOsqpSolverOptionsFromYaml( +// "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml"); + osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); + // Build OSC problem osc->Build(); // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_robot_output_input_port()); - builder.Connect(fsm->get_output_port(0), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); builder.Connect(alip_traj_generator->get_output_port_com(), osc->get_tracking_data_input_port("alip_com_traj")); builder.Connect(swing_ft_traj_generator->get_output_port(0), diff --git a/solvers/default_osc_osqp_settings.yaml b/solvers/default_osc_osqp_settings.yaml index 8463e69c11..7e854f7779 100644 --- a/solvers/default_osc_osqp_settings.yaml +++ b/solvers/default_osc_osqp_settings.yaml @@ -1,15 +1,15 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 200 -eps_abs: 1e-5 -eps_rel: 1e-5 +max_iter: 1000 +eps_abs: 1e-7 +eps_rel: 1e-7 eps_prim_inf: 1e-5 eps_dual_inf: 1e-5 alpha: 1.6 linsys_solver: 0 delta: 1e-6 polish: 1 -polish_refine_iter: 1 +polish_refine_iter: 3 verbose: 0 scaled_termination: 1 check_termination: 25 diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc index c0b5091da1..09457349ce 100644 --- a/systems/controllers/geared_motor.cc +++ b/systems/controllers/geared_motor.cc @@ -55,8 +55,8 @@ void GearedMotor::CalcTorqueOutput( tlim = fmax(fmin(tlim, tmax), 0); // Compute motor-side torque - tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); -// tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); +// tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); + tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); } output->SetFromVector(tau); } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f3b9ee698b..814e5b91c2 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -527,7 +527,7 @@ VectorXd OperationalSpaceControl::SolveQp( bias = bias - grav; // TODO (yangwill): Characterize damping in cassie model // std::cout << f_app.generalized_forces().transpose() << std::endl; - bias = bias - f_app.generalized_forces(); +// bias = bias - f_app.generalized_forces(); // Invariant Impacts // Only update when near an impact @@ -1071,17 +1071,18 @@ void OperationalSpaceControl::CalcOptimalInput( next_fsm_state = impact_info->GetCurrentContactMode(); } -// if (fsm_state(0) == 0) { -// x_wo_spr[19] = 0; -// x_wo_spr[21] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } else if (fsm_state(0) == 1) { -// x_wo_spr[11] = 0; -// x_wo_spr[13] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } else { + if (fsm_state(0) == 0) { + x_wo_spr[19] = 0; + x_wo_spr[21] = 0; + x_wo_spr[33] = 0; + x_wo_spr[41] = 0; + } else if (fsm_state(0) == 1) { + x_wo_spr[11] = 0; + x_wo_spr[13] = 0; + x_wo_spr[33] = 0; + x_wo_spr[41] = 0; + } +// else { // x_wo_spr[11] = 0; // x_wo_spr[13] = 0; // x_wo_spr[19] = 0; From 1ac6a175f3a0744908900909102c94daabe10668 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 11 May 2022 16:13:56 -0400 Subject: [PATCH 202/758] setting two triggers for soft estop --- bindings/pydairlib/analysis/log_plotter_cassie.py | 8 +++++--- bindings/pydairlib/analysis/mbp_plotting_utils.py | 6 +++--- .../analysis/plot_configs/cassie_running_plot.yaml | 4 ++-- examples/Cassie/input_supervisor.cc | 2 +- examples/Cassie/osc_run/osc_running_gains.yaml | 4 ++-- examples/Cassie/run_osc_walking_controller_alip.cc | 2 +- 6 files changed, 14 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 1a25d93ab8..6fc9cf659a 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -12,8 +12,8 @@ def main(): - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' # config_file = \ # 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) @@ -69,9 +69,11 @@ def main(): # Plot all joint velocities if plot_config.plot_joint_positions: - mbp_plots.plot_joint_velocities(robot_output, vel_names, + plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 6 if use_floating_base else 0, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + # Plot specific velocities if plot_config.vel_names: plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index a4d66aae8a..0054fe0b3e 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -471,9 +471,9 @@ def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names = []): if len(fsm_state_names) == np.unique(fsm_signal).shape[0]: legend_elements.append(Patch(facecolor=ps.cmap(2*i), alpha=0.3, label=fsm_state_names[i])) - if len(legend_elements) > 0: - legend = ax.legend(legend_elements, fsm_state_names, loc=4) + # if len(legend_elements) > 0: + # legend = ax.legend(legend_elements, fsm_state_names, loc=4) # ps.add_legend(legend, loc=4) # ax.add_artist(legend) # ax.add_artist(legend) - ax.relim() + # ax.relim() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index e75b4d1a2f..60ff4c518c 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,8 +1,8 @@ # LCM channels to read data from #channel_x: "CASSIE_STATE_SIMULATION" channel_x: "CASSIE_STATE_DISPATCHER" -channel_u: "OSC_RUNNING" -#channel_u: "CASSIE_INPUT" +#channel_u: "OSC_RUNNING" +channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 2487151b4c..40c16983f8 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -149,7 +149,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, // If the soft estop signal is triggered, applying only damping regardless of // any other controller signal - if (cassie_out->pelvis.radio.channel[15] == -1) { + if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[12] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); input_limit_ = 100 * Eigen::VectorXd::Ones(num_actuators_); output->set_timestamp(state->get_timestamp()); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 62bdffead4..32fb55b434 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -26,7 +26,7 @@ vel_scale_trans_sagital: 0.2 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.85 +rest_length: 0.87 stance_duration: 0.30 flight_duration: 0.1 @@ -57,7 +57,7 @@ PelvisKp: 0, 0, 0, 0, 0, 70] PelvisKd: - [ 1, 0, 0, + [ 0, 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 40b9285d4f..c2d147e005 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -78,7 +78,7 @@ DEFINE_string( "The name of the channel to receive the cassie out structure from."); DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", "Filepath containing gains"); -DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", +DEFINE_string(osqp_settings, "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml", "Filepath containing qp settings"); DEFINE_bool(publish_osc_data, true, "whether to publish lcm messages for OscTrackData"); From da8e2a88d44db37efe74a6c55a2fe0464015ca6e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 May 2022 11:17:48 -0400 Subject: [PATCH 203/758] more tuning --- .../pydairlib/analysis/cassie_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_cassie.py | 2 + .../pydairlib/analysis/mbp_plotting_utils.py | 13 +++ .../plot_configs/cassie_running_plot.yaml | 9 +- examples/Cassie/osc/osc_standing_gains.yaml | 3 +- .../Cassie/osc_run/osc_running_gains.yaml | 7 +- examples/Cassie/run_osc_running_controller.cc | 8 +- .../impact_aware_time_based_fsm.cc | 5 +- .../impact_aware_time_based_fsm.h | 2 +- multibody/multibody_utils.cc | 4 +- .../osc/operational_space_control.cc | 97 +++++++++++-------- .../osc/operational_space_control.h | 1 + systems/controllers/osc/osc_gains.h | 2 + 13 files changed, 96 insertions(+), 58 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index 2c1942ecde..bc9c48972a 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -42,6 +42,7 @@ def __init__(self, filename): self.plot_qp_costs = data['plot_qp_costs'] self.plot_tracking_costs = data['plot_tracking_costs'] self.plot_qp_solve_time = data['plot_qp_solve_time'] + self.plot_qp_solutions = data['plot_qp_solutions'] self.fsm_state_names = data['fsm_state_names'] self.tracking_datas_to_plot = \ data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 6fc9cf659a..5f0aa1ec84 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -98,6 +98,8 @@ def main(): ''' Plot OSC ''' if plot_config.plot_qp_costs: mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) + if plot_config.plot_qp_solutions: + mbp_plots.plot_qp_solutions(osc_debug, t_osc_slice) if plot_config.plot_tracking_costs: mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 0054fe0b3e..56e1b50f29 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -411,6 +411,19 @@ def plot_qp_costs(osc_debug, time_slice): 'title': 'regularization_costs'}, ps) return ps +def plot_qp_solutions(osc_debug, time_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + ['lambda_c_sol'], + {}, + {}, + {'xlabel': 'Timestamp', + 'ylabel': 'Solve Time ', + 'title': 'OSC Lambda Solutions'}, ps) + return ps def plot_qp_solve_time(osc_debug, time_slice): ps = plot_styler.PlotStyler() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 60ff4c518c..8867abd99c 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -16,7 +16,7 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false plot_floating_base_velocities: false -plot_joint_positions: true +plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true @@ -35,9 +35,10 @@ foot_xyz_to_plot: { } pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: true -plot_qp_solve_time: true -plot_tracking_costs: true +plot_qp_costs: false +plot_qp_solve_time: false +plot_qp_solutions: true +plot_tracking_costs: false tracking_datas_to_plot: # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel' ] } # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 49fc6520db..c1d5d96cd6 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -24,7 +24,8 @@ W_lambda_h_reg: [ 0.01, 0.01, 0.01, 0.01, 0.02, 0.02 ] w_soft_constraint: 100 w_input_reg: 0.001 -impact_threshold: 0.025 +impact_threshold: 0.00 +impact_tau: 0.00 mu: 0.6 HipYawKp: 10 HipYawKd: 1 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 32fb55b434..011d0f6a9f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -15,7 +15,8 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, #w_soft_constraint: 1000000 w_soft_constraint: 100 w_input_reg: 0.1 -impact_threshold: 0.025 +impact_threshold: 0.1 +impact_tau: 0.05 relative_feet: true relative_pelvis: true ekf_filter_tau: [0.05, 0.1, 0.01] @@ -28,7 +29,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.87 stance_duration: 0.30 -flight_duration: 0.1 +flight_duration: 0.10 mu: 0.6 @@ -65,7 +66,7 @@ PelvisRotW: 0, 10, 0, 0, 0, 0] PelvisRotKp: - [100., 0, 0, + [20., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index cfce52160b..faf2e89ff2 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -167,7 +167,7 @@ int DoMain(int argc, char* argv[]) { accumulated_state_durations.pop_back(); auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, gains.impact_threshold); + plant, fsm_states, state_durations, 0.0, gains.impact_threshold, gains.impact_tau); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -406,6 +406,8 @@ int DoMain(int argc, char* argv[]) { pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], right_stance_state); pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], left_stance_state); pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], right_stance_state); + pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], left_stance_state); + pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], right_stance_state); // left_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( // pos_map["hip_pitch_left"], right_stance_state); @@ -420,14 +422,14 @@ int DoMain(int argc, char* argv[]) { // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); +// left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); +// right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); - // left_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); - // right_foot_yz_rel_tracking_data.DisableFeedforwardAccel({0, 1, 2}); osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index e156e3e47c..4813b44805 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -16,7 +16,7 @@ using systems::ImpactInfoVector; ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( const drake::multibody::MultibodyPlant& plant, const std::vector& states, const std::vector& state_durations, - double t0, double near_impact_threshold, BLEND_FUNC blend_func) + double t0, double near_impact_threshold, double tau, BLEND_FUNC blend_func) : TimeBasedFiniteStateMachine(plant, states, state_durations, t0), states_(states), state_durations_(state_durations), @@ -83,9 +83,6 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( // Get current finite state if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { -// if (impact_states_[i] > 2) { -// continue; -// } double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ : near_impact_threshold_; diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index 08bedf8546..3cad6c91b4 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -20,7 +20,7 @@ class ImpactTimeBasedFiniteStateMachine const drake::multibody::MultibodyPlant& plant, const std::vector& states, const std::vector& state_durations, double t0 = 0, - double near_impact_threshold = 0, BLEND_FUNC blend_func = SIGMOID); + double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index c628e4f493..3f8042b94d 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -156,8 +156,8 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, // Add visual for the ground. if (show_ground) { - plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), - "visual"); +// plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), +// "visual"); } } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 814e5b91c2..f7ee519682 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -295,7 +295,8 @@ void OperationalSpaceControl::Build() { all_contacts_[i]->EvalFullJacobian(*context_wo_spr_).rows(); } } -// std::cout << contact_map.first << ", " << active_contact_dim << std::endl; + // std::cout << contact_map.first << ", " << active_contact_dim << + // std::endl; active_contact_dim_[contact_map.first] = active_contact_dim; } @@ -305,10 +306,10 @@ void OperationalSpaceControl::Build() { lambda_c_sol_ = std::make_unique(n_c_); lambda_h_sol_ = std::make_unique(n_h_); epsilon_sol_ = std::make_unique(n_c_active_); -// u_prev_ = std::make_unique(n_u_); + // u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); -// u_prev_->setZero(); + // u_prev_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); epsilon_sol_->setZero(); @@ -394,7 +395,11 @@ void OperationalSpaceControl::Build() { // 3. contact force cost if (W_lambda_c_reg_.size() > 0) { DRAKE_DEMAND(W_lambda_c_reg_.rows() == n_c_); - prog_->AddQuadraticCost(W_lambda_c_reg_, VectorXd::Zero(n_c_), lambda_c_); + lambda_c_smoothing_cost_ = + prog_ + ->AddQuadraticCost(W_lambda_c_reg_, VectorXd::Zero(n_c_), lambda_c_) + .evaluator() + .get(); } // 3. constraint force cost if (W_lambda_h_reg_.size() > 0) { @@ -526,8 +531,8 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd grav = plant_wo_spr_.CalcGravityGeneralizedForces(*context_wo_spr_); bias = bias - grav; // TODO (yangwill): Characterize damping in cassie model -// std::cout << f_app.generalized_forces().transpose() << std::endl; -// bias = bias - f_app.generalized_forces(); + // std::cout << f_app.generalized_forces().transpose() << std::endl; + // bias = bias - f_app.generalized_forces(); // Invariant Impacts // Only update when near an impact @@ -618,8 +623,7 @@ VectorXd OperationalSpaceControl::SolveQp( weight(1, 1) *= 1e-3; weight(3, 3) *= 1e-3; weight(4, 4) *= 1e-3; - A_c.block(0, n_v_, n_c_active_, n_c_active_) = - weight; + A_c.block(0, n_v_, n_c_active_, n_c_active_) = weight; contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -739,10 +743,12 @@ VectorXd OperationalSpaceControl::SolveQp( // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0 && initial_guess_x_.count(fsm_state) > 0) { -// input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, -// -W_input_smoothing_ * (*u_prev_)); - input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, - -W_input_smoothing_ * u_prev_[fsm_state]); + input_smoothing_cost_->UpdateCoefficients( + W_input_smoothing_, -W_input_smoothing_ * u_prev_[fsm_state]); + } + if (W_lambda_c_reg_.size() > 0) { + lambda_c_smoothing_cost_->UpdateCoefficients(100 * alpha * W_lambda_c_reg_, + VectorXd::Zero(n_c_)); } // if (!solver_->IsInitialized()) { @@ -792,17 +798,19 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( ii_lambda_sol_ = VectorXd::Zero(n_c_ + n_h_); M_Jt_ = MatrixXd::Zero(n_v_, n_c_ + n_h_); return; -// throw std::out_of_range("Contact mode: " + std::to_string(next_fsm_state) + -// " was not found in the OSC"); + // throw std::out_of_range("Contact mode: " + + // std::to_string(next_fsm_state) + + // " was not found in the OSC"); } std::set next_contact_set = map_iterator->second; int active_constraint_dim = active_contact_dim_.at(next_fsm_state) + n_h_; -// std::cout << "active constraint dim: " << active_constraint_dim << std::endl; + // std::cout << "active constraint dim: " << active_constraint_dim << + // std::endl; MatrixXd J_next = MatrixXd::Zero(active_constraint_dim, n_v_); int row_start = 0; for (unsigned int i = 0; i < all_contacts_.size(); i++) { if (next_contact_set.find(i) != next_contact_set.end()) { -// std::cout << i << std::endl; + // std::cout << i << std::endl; J_next.block(row_start, 0, kSpaceDim, n_v_) = all_contacts_[i]->EvalFullJacobian(*context_wo_spr_); row_start += kSpaceDim; @@ -813,8 +821,8 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( J_next.block(row_start, 0, n_h_, n_v_) = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); } -// std::cout << "J: " << std::endl; -// std::cout << J_next << std::endl; + // std::cout << "J: " << std::endl; + // std::cout << J_next << std::endl; M_Jt_ = M.llt().solve(J_next.transpose()); int active_tracking_data_dim = 0; @@ -860,26 +868,35 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } } -// int n_holonomic_constraints = n_h_; + // int n_holonomic_constraints = n_h_; MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); - MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + n_h_, active_constraint_dim + n_h_); + MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + n_h_, + active_constraint_dim + n_h_); MatrixXd C = J_h * M_Jt_; VectorXd Ab = A.transpose() * ydot_err_vec; VectorXd d = J_h * x_w_spr.tail(n_v_); - A_constrained.block(0, 0, active_constraint_dim, active_constraint_dim) = A.transpose() * A; - A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = C; - A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = C.transpose(); + A_constrained.block(0, 0, active_constraint_dim, active_constraint_dim) = + A.transpose() * A; + A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = + C; + A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = + C.transpose(); VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); b_constrained << Ab, d; - // A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = MatriXd; + // A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) + // = MatriXd; -// ii_lambda_sol_ = A.completeOrthogonalDecomposition().solve(ydot_err_vec); - ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition().solve(b_constrained).head(active_constraint_dim); + // ii_lambda_sol_ = A.completeOrthogonalDecomposition().solve(ydot_err_vec); + ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition() + .solve(b_constrained) + .head(active_constraint_dim); -// std::cout << "constraint velocity: " << (J_h * (x_w_spr.tail(n_v_))).transpose() << std::endl; -// std::cout << "projected velocity: " << (J_h * (x_w_spr.tail(n_v_) + M_Jt_ * ii_lambda_sol_)).transpose() << std::endl; + // std::cout << "constraint velocity: " << (J_h * + // (x_w_spr.tail(n_v_))).transpose() << std::endl; std::cout << "projected + // velocity: " << (J_h * (x_w_spr.tail(n_v_) + M_Jt_ * + // ii_lambda_sol_)).transpose() << std::endl; -// std::cout << ii_lambda_sol_.transpose() << std::endl; + // std::cout << ii_lambda_sol_.transpose() << std::endl; } void OperationalSpaceControl::AssignOscLcmOutput( @@ -917,8 +934,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( : 0; double input_smoothing_cost = (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_ - u_prev_[fsm_state]).transpose() * W_input_smoothing_ * - (*u_sol_ - u_prev_[fsm_state]))(0) + ? (0.5 * (*u_sol_ - u_prev_[fsm_state]).transpose() * + W_input_smoothing_ * (*u_sol_ - u_prev_[fsm_state]))(0) : 0; double lambda_h_cost = (W_lambda_h_reg_.size() > 0) ? (0.5 * (*lambda_h_sol_).transpose() * @@ -1022,7 +1039,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->tracking_data[i] = osc_output; } // std::cout << total_cost_ << std::endl; -// *u_prev_ = *u_sol_; + // *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); } @@ -1082,14 +1099,14 @@ void OperationalSpaceControl::CalcOptimalInput( x_wo_spr[33] = 0; x_wo_spr[41] = 0; } -// else { -// x_wo_spr[11] = 0; -// x_wo_spr[13] = 0; -// x_wo_spr[19] = 0; -// x_wo_spr[21] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } + // else { + // x_wo_spr[11] = 0; + // x_wo_spr[13] = 0; + // x_wo_spr[19] = 0; + // x_wo_spr[21] = 0; + // x_wo_spr[33] = 0; + // x_wo_spr[41] = 0; + // } // Get discrete states const auto prev_event_time = diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 912a051f2f..ff9f6e9cff 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -339,6 +339,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector tracking_cost_; std::vector joint_limit_cost_; drake::solvers::QuadraticCost* input_smoothing_cost_; + drake::solvers::QuadraticCost* lambda_c_smoothing_cost_; // OSC solution std::unique_ptr dv_sol_; diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index 81fa530ee6..ef91673570 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -13,6 +13,7 @@ struct OSCGains { double w_accel; double w_soft_constraint; double impact_threshold; + double impact_tau; double mu; std::vector W_accel; std::vector W_input_reg; @@ -31,6 +32,7 @@ struct OSCGains { a->Visit(DRAKE_NVP(w_accel)); a->Visit(DRAKE_NVP(w_soft_constraint)); a->Visit(DRAKE_NVP(impact_threshold)); + a->Visit(DRAKE_NVP(impact_tau)); a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(W_accel)); a->Visit(DRAKE_NVP(W_input_reg)); From 72051a633fe40148727a756190d2e1da30416c97 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 May 2022 11:33:45 -0400 Subject: [PATCH 204/758] trying to avoid entering torque limits --- examples/Cassie/osc_run/osc_running_gains.yaml | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 011d0f6a9f..a93f8a8caa 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -43,10 +43,11 @@ hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.05 -footstep_lateral_offset: 0.04 +footstep_lateral_offset: 0.055 # mujoco +#footstep_lateral_offset: 0.045 mid_foot_height: 0.05 FootstepKd: - [ 0.25, 0, 0, + [ 0.3, 0, 0, 0, 0.6, 0, 0, 0, 0 ] PelvisW: @@ -56,7 +57,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 70] + 0, 0, 60] PelvisKd: [ 0, 0, 0, 0, 0, 0, @@ -70,7 +71,7 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [10., 0, 0, + [5., 0, 0, 0, 5., 0, 0, 0, 1.] SwingFootW: @@ -87,7 +88,7 @@ SwingFootKd: 0, 0, 1.] LiftoffSwingFootW: [1, 0, 0, - 0, 100, 0, + 0, 1, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, From cefebdf7d19d291b85bd7717228f385f39850653 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 May 2022 13:20:34 -0400 Subject: [PATCH 205/758] updating input supervisor triggers --- examples/Cassie/input_supervisor.cc | 4 ++-- examples/Cassie/osc/osc_walking_gains_alip.yaml | 2 +- examples/Cassie/osc/swing_toe_traj_generator.cc | 3 ++- examples/Cassie/osc_run/osc_running_gains.yaml | 8 +++++--- examples/Cassie/run_osc_walking_controller_alip.cc | 12 ++++++------ systems/controllers/geared_motor.cc | 5 +++-- 6 files changed, 19 insertions(+), 15 deletions(-) diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 40c16983f8..812945a476 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -149,7 +149,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, // If the soft estop signal is triggered, applying only damping regardless of // any other controller signal - if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[12] == -1) { + if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[13] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); input_limit_ = 100 * Eigen::VectorXd::Ones(num_actuators_); output->set_timestamp(state->get_timestamp()); @@ -313,7 +313,7 @@ void InputSupervisor::CheckRadio( drake::systems::DiscreteValues* discrete_state) const { const auto& cassie_out = this->EvalInputValue( context, cassie_input_port_); - if (cassie_out->pelvis.radio.channel[15] == -1) { + if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[13]) { discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("soft_estop")] = 1; } diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 9668d38e1a..8457c2c4d5 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -45,7 +45,7 @@ max_CoM_to_footstep_dist: 0.55 footstep_offset: 0.25 center_line_offset: 0.03 mid_foot_height: 0.2 -final_foot_height: 0.0 +final_foot_height: 0.025 final_foot_velocity_z: 0.0 # LIPM trajectory diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index bea932fb12..dbbda3aea7 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -63,7 +63,8 @@ void SwingToeTrajGenerator::CalcTraj( double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); - des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.125; +// des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.125; + des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; auto* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index a93f8a8caa..fa68bacfaa 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -30,6 +30,8 @@ vel_scale_trans_lateral: -0.15 rest_length: 0.87 stance_duration: 0.30 flight_duration: 0.10 +#stance_duration: 0.7 +#flight_duration: 0.09 mu: 0.6 @@ -44,7 +46,7 @@ hip_yaw_kd: 1 #footstep_offset: -0.05 footstep_sagital_offset: -0.05 footstep_lateral_offset: 0.055 # mujoco -#footstep_lateral_offset: 0.045 +#footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.05 FootstepKd: [ 0.3, 0, 0, @@ -57,11 +59,11 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 60] + 0, 0, 65] PelvisKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 5] + 0, 0, 4] PelvisRotW: [1, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index c2d147e005..b2910ca69c 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -361,12 +361,12 @@ int DoMain(int argc, char* argv[]) { int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetLambdaContactRegularizationWeight(1e-4 * - gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); -// osc->SetInputSmoothingWeights(gains.w_input_reg * -// MatrixXd::Identity(n_u, n_u)); +// osc->SetLambdaContactRegularizationWeight(1e-4 * +// gains.W_lambda_c_regularization); +// osc->SetLambdaHolonomicRegularizationWeight(1e-5 * +// gains.W_lambda_h_regularization); + osc->SetInputSmoothingWeights(gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc index 09457349ce..b701e8e0b4 100644 --- a/systems/controllers/geared_motor.cc +++ b/systems/controllers/geared_motor.cc @@ -55,8 +55,9 @@ void GearedMotor::CalcTorqueOutput( tlim = fmax(fmin(tlim, tmax), 0); // Compute motor-side torque -// tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]); - tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); + tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]) * ratio; + +// tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); } output->SetFromVector(tau); } From 3e7845f411e33ad4023dfa121d9052d14e5e6c3e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 May 2022 15:03:54 -0400 Subject: [PATCH 206/758] blending torques --- .../plot_configs/cassie_running_plot.yaml | 6 ++--- .../Cassie/osc/swing_toe_traj_generator.cc | 4 ++-- .../Cassie/osc_run/osc_running_gains.yaml | 6 ++--- .../osc/operational_space_control.cc | 24 ++++++++++++++++--- 4 files changed, 29 insertions(+), 11 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 8867abd99c..b1820cbdf3 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,8 +1,8 @@ # LCM channels to read data from #channel_x: "CASSIE_STATE_SIMULATION" channel_x: "CASSIE_STATE_DISPATCHER" -#channel_u: "OSC_RUNNING" -channel_u: "CASSIE_INPUT" +channel_u: "OSC_RUNNING" +#channel_u: "CASSIE_INPUT" channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) @@ -36,7 +36,7 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: false -plot_qp_solve_time: false +plot_qp_solve_time: true plot_qp_solutions: true plot_tracking_costs: false tracking_datas_to_plot: diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index dbbda3aea7..3f832fd066 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -63,8 +63,8 @@ void SwingToeTrajGenerator::CalcTraj( double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); -// des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.125; - des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; + des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.05; +// des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; auto* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index fa68bacfaa..9eac332476 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -15,8 +15,8 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, #w_soft_constraint: 1000000 w_soft_constraint: 100 w_input_reg: 0.1 -impact_threshold: 0.1 -impact_tau: 0.05 +impact_threshold: 0.05 +impact_tau: 0.025 relative_feet: true relative_pelvis: true ekf_filter_tau: [0.05, 0.1, 0.01] @@ -73,7 +73,7 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [5., 0, 0, + [1., 0, 0, 0, 5., 0, 0, 0, 1.] SwingFootW: diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f7ee519682..83ccbf39eb 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -762,6 +762,8 @@ VectorXd OperationalSpaceControl::SolveQp( // Solve the QP const MathematicalProgramResult result = solver_->Solve(*prog_); + solve_time_ = result.get_solver_details().run_time; + if (result.is_success()) { // Extract solutions *dv_sol_ = result.GetSolution(dv_); @@ -769,8 +771,25 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); - // u_sol_->row(0) = 0.95 * u_sol_->row(0) + 0.05 * u_prev_->row(0); - // u_sol_->row(1) = 0.95 * u_sol_->row(1) + 0.05 * u_prev_->row(1); + if(fsm_state >= 2 && initial_guess_x_.size() == 4){ + double clock_time; + if (this->get_input_port(clock_port_).HasValue(context)) { + auto clock = this->EvalVectorInput(context, clock_port_); + clock_time = clock->get_value()(0); + } + if(fsm_state == 2){ + double blend = 1 - exp(-((clock_time - 0.3) + 0.01) / 0.015); + solve_time_ = blend; + u_sol_->row(6) = blend * u_sol_->row(6) + (1 - blend) * u_prev_[0].row(6); +// u_sol_->row(0) = blend * u_sol_->row(0) + (1 - blend) * u_prev_[0].row(0); + } + if(fsm_state == 3){ + double blend = 1 - exp(-((clock_time - 0.7) + 0.01) / 0.015); + solve_time_ = blend; + u_sol_->row(7) = blend * u_sol_->row(7) + (1 - blend) * u_prev_[1].row(7); +// u_sol_->row(1) = blend * u_sol_->row(1) + (1 - blend) * u_prev_[1].row(1); + } + } u_prev_[fsm_state] = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; @@ -779,7 +798,6 @@ VectorXd OperationalSpaceControl::SolveQp( u_prev_[fsm_state] = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } - solve_time_ = result.get_solver_details().run_time; for (auto& tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state)) { From 03d44aadee922a4c06b34ca786d5684f26b4fb11 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 May 2022 17:04:29 -0400 Subject: [PATCH 207/758] blending torques --- .../plot_configs/cassie_running_plot.yaml | 8 ++++---- .../Cassie/osc_run/osc_running_gains.yaml | 6 +++--- examples/Cassie/run_osc_running_controller.cc | 4 ++-- .../osc/operational_space_control.cc | 20 +++++++++++-------- 4 files changed, 21 insertions(+), 17 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index b1820cbdf3..ae1b86b56f 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -28,10 +28,10 @@ special_efforts_to_plot: [ ] fsm_state_names: ['Left Stance (LS)', 'Left Flight (LF)', 'Right Stance (RS)', 'Right Flight (RF)'] # Foot position plots -#foot_positions_to_plot: [ 'right', 'left' ] -foot_positions_to_plot: [] -#foot_xyz_to_plot: { 'right': [ 0, 2 ], 'left': [ 0, 2 ] } -foot_xyz_to_plot: { } +foot_positions_to_plot: [ 'right', 'left' ] +#foot_positions_to_plot: [] +foot_xyz_to_plot: { 'right': [ 0, 2 ], 'left': [ 0, 2 ] } +#foot_xyz_to_plot: { } pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 9eac332476..86af2770b8 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -15,8 +15,8 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, #w_soft_constraint: 1000000 w_soft_constraint: 100 w_input_reg: 0.1 -impact_threshold: 0.05 -impact_tau: 0.025 +impact_threshold: 0.1 +impact_tau: 0.05 relative_feet: true relative_pelvis: true ekf_filter_tau: [0.05, 0.1, 0.01] @@ -47,7 +47,7 @@ hip_yaw_kd: 1 footstep_sagital_offset: -0.05 footstep_lateral_offset: 0.055 # mujoco #footstep_lateral_offset: 0.04 # drake -mid_foot_height: 0.05 +mid_foot_height: 0.07 FootstepKd: [ 0.3, 0, 0, 0, 0.6, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index faf2e89ff2..23a0b29ca8 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -420,8 +420,8 @@ int DoMain(int argc, char* argv[]) { // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); - left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); - right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); +// left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); +// right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 83ccbf39eb..492b69dfdf 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -778,16 +778,20 @@ VectorXd OperationalSpaceControl::SolveQp( clock_time = clock->get_value()(0); } if(fsm_state == 2){ - double blend = 1 - exp(-((clock_time - 0.3) + 0.01) / 0.015); - solve_time_ = blend; - u_sol_->row(6) = blend * u_sol_->row(6) + (1 - blend) * u_prev_[0].row(6); -// u_sol_->row(0) = blend * u_sol_->row(0) + (1 - blend) * u_prev_[0].row(0); + double blend_in = 1 - exp(-((0.4 - clock_time) + 0.01) / 0.010); + double blend_out = 1 - exp(-((clock_time - 0.3) + 0.01) / 0.010); + u_sol_->row(6) = blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); + u_sol_->row(7) = blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); + u_sol_->row(0) = blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); +// u_sol_->row(1) = blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); } if(fsm_state == 3){ - double blend = 1 - exp(-((clock_time - 0.7) + 0.01) / 0.015); - solve_time_ = blend; - u_sol_->row(7) = blend * u_sol_->row(7) + (1 - blend) * u_prev_[1].row(7); -// u_sol_->row(1) = blend * u_sol_->row(1) + (1 - blend) * u_prev_[1].row(1); + double blend_in = 1 - exp(-((0.8 - clock_time) + 0.01) / 0.010); + double blend_out = 1 - exp(-((clock_time - 0.7) + 0.01) / 0.010); + u_sol_->row(6) = blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); + u_sol_->row(7) = blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); +// u_sol_->row(0) = blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); + u_sol_->row(1) = blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); } } u_prev_[fsm_state] = *u_sol_; From 569322d652188d5b1f4c90c8aa8c1966131ddc78 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 May 2022 17:13:15 -0400 Subject: [PATCH 208/758] updating input supervisor typo --- examples/Cassie/input_supervisor.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/input_supervisor.cc b/examples/Cassie/input_supervisor.cc index 812945a476..8b93bbf754 100644 --- a/examples/Cassie/input_supervisor.cc +++ b/examples/Cassie/input_supervisor.cc @@ -313,7 +313,7 @@ void InputSupervisor::CheckRadio( drake::systems::DiscreteValues* discrete_state) const { const auto& cassie_out = this->EvalInputValue( context, cassie_input_port_); - if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[13]) { + if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[13] == -1) { discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("soft_estop")] = 1; } From 60733c721a000415598a6df35fa73e9ea335e46b Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 13 May 2022 10:54:36 -0400 Subject: [PATCH 209/758] updating plottig script --- .../pydairlib/analysis/mbp_plotting_utils.py | 20 +++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 56e1b50f29..43a7166c90 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -308,16 +308,16 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, 'xlabel': 'time (s)', 'ylabel': 'foot vertical position (m)'}, ps) - import matplotlib - legend_elements = [matplotlib.patches.Patch(facecolor=ps.cmap(0), alpha=0.3, label='Left Stance (LS)'), - matplotlib.patches.Patch(facecolor=ps.cmap(4), alpha=0.3, label='Left Liftoff (LF)'), - matplotlib.patches.Patch(facecolor=ps.cmap(2), alpha=0.3, label='Right Stance (RS)'), - matplotlib.patches.Patch(facecolor=ps.cmap(6), alpha=0.3, label='Right Liftoff (RF)')] - legend = plt.legend(legend_elements, ['Left Stance (LS)', - 'Left Liftoff (LF)', - 'Right Stance (RS)', - 'Right Liftoff (RF)'], loc=1) - plt.gca().add_artist(legend) + # import matplotlib + # legend_elements = [matplotlib.patches.Patch(facecolor=ps.cmap(0), alpha=0.3, label='Left Stance (LS)'), + # matplotlib.patches.Patch(facecolor=ps.cmap(4), alpha=0.3, label='Left Liftoff (LF)'), + # matplotlib.patches.Patch(facecolor=ps.cmap(2), alpha=0.3, label='Right Stance (RS)'), + # matplotlib.patches.Patch(facecolor=ps.cmap(6), alpha=0.3, label='Right Liftoff (RF)')] + # legend = plt.legend(legend_elements, ['Left Stance (LS)', + # 'Left Liftoff (LF)', + # 'Right Stance (RS)', + # 'Right Liftoff (RF)'], loc=1) + # plt.gca().add_artist(legend) return ps From 1946c509ab8e724fa3b1c16e2a434166892424c2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 17 May 2022 12:43:39 -0400 Subject: [PATCH 210/758] updating logging script --- examples/Cassie/start_logging.py | 25 +++++++++++++------------ 1 file changed, 13 insertions(+), 12 deletions(-) diff --git a/examples/Cassie/start_logging.py b/examples/Cassie/start_logging.py index f8bd8c73b2..c4ed5dee2f 100644 --- a/examples/Cassie/start_logging.py +++ b/examples/Cassie/start_logging.py @@ -6,20 +6,24 @@ def main(): + sim = (os.getlogin() == 'brian') curr_date = date.today().strftime("%m_%d_%y") year = date.today().strftime("%Y") - logdir = f"{os.getenv('HOME')}/logs/{year}/{curr_date}" - dair = f"{os.getenv('HOME')}/workspace/dairlib/" - standing_gains = dair + "examples/Cassie/osc/osc_standing_gains.yaml" - walking_gains = dair + "examples/Cassie/osc/osc_walking_gains.yaml" - alip_walking_gains = dair + "examples/Cassie/osc/alip_osc_walking_gains.yaml" - running_gains = dair + "examples/Cassie/osc_run/osc_running_gains.yaml" + + logdir = \ + f"{os.getenv('HOME')}/workspace/logs/cassie_simulation/{year}/{curr_date}" \ + if sim else f"{os.getenv('HOME')}/logs/{year}/{curr_date}" + + current_dair_dir = f"{os.getcwd()}/" + standing_gains = current_dair_dir + "examples/Cassie/osc/osc_standing_gains.yaml" + walking_gains = current_dair_dir + "examples/Cassie/osc/osc_walking_gains.yaml" + alip_gains = current_dair_dir + "examples/Cassie/osc/osc_walking_gains_alip.yaml" if not os.path.isdir(logdir): os.mkdir(logdir) - git_diff = subprocess.check_output(['git', 'diff'], cwd=dair) - commit_tag = subprocess.check_output(['git', 'rev-parse', 'HEAD'], cwd=dair) + git_diff = subprocess.check_output(['git', 'diff'], cwd=current_dair_dir) + commit_tag = subprocess.check_output(['git', 'rev-parse', 'HEAD'], cwd=current_dair_dir) os.chdir(logdir) current_logs = sorted(glob.glob('lcmlog-*')) @@ -36,10 +40,7 @@ def main(): subprocess.run(['cp', standing_gains, 'standing_gains_%s.yaml' % log_num]) subprocess.run(['cp', walking_gains, 'walking_gains_%s.yaml' % log_num]) - subprocess.run(['cp', alip_walking_gains, - 'walking_gains_alip_%s.yaml' % log_num]) - subprocess.run(['cp', running_gains, - 'running_gains_%s.yaml' % log_num]) + subprocess.run(['cp', alip_gains, 'walking_gains_alip%s.yaml' % log_num]) subprocess.run(['lcm-logger', '-f', 'lcmlog-%s' % log_num]) From 706416df9968384eee74a096c6d72e0a019d6ab3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 17 May 2022 15:26:07 -0400 Subject: [PATCH 211/758] adding tuning footstep gains from radio --- .../pydairlib/analysis/log_plotter_cassie.py | 1 + examples/Cassie/cassie_xbox_remote.py | 19 ++++++++++++++++-- examples/Cassie/osc_run/BUILD.bazel | 1 + .../Cassie/osc_run/foot_traj_generator.cc | 20 ++++++++++++++++--- examples/Cassie/osc_run/foot_traj_generator.h | 4 ++++ examples/Cassie/run_osc_running_controller.cc | 4 ++++ 6 files changed, 44 insertions(+), 5 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 5f0aa1ec84..d198edb983 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -40,6 +40,7 @@ def main(): plot_config.end_time, mbp_plots.load_default_channels, # processing callback plant, channel_x, channel_u, channel_osc) # processing callback arguments + import pdb; pdb.set_trace() print('Finished processing log - making plots') # Define x time slice diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index e767d78ead..23b192822e 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -53,6 +53,12 @@ def main(): radio_channel_6_pos = 0 radio_channel_6_delta = 0.05 + radio_channel_4_pos = 0 + radio_channel_4_delta = 0.05 + + radio_channel_5_pos = 0 + radio_channel_5_delta = 0.05 + if (pygame.joystick.get_count() != 1): raise RuntimeError("Please connect exactly one controller") @@ -82,8 +88,15 @@ def main(): radio_channel_6_pos += radio_channel_6_delta * hat_val[1] # saturate between -1 and 1 radio_channel_6_pos = min(max(radio_channel_6_pos, -1), 1) - - + if event.type == pygame.JOYBUTTONDOWN: + radio_channel_4_pos += -radio_channel_5_delta * joystick.get_button(2) + radio_channel_5_delta * joystick.get_button(1) + radio_channel_5_pos += -radio_channel_4_delta * joystick.get_button(0) + radio_channel_4_delta * joystick.get_button(3) + # for i in range(joystick.get_numbuttons()): + # print(i) + # print(joystick.get_button(i)) + + textPrint.print(screen, "Left Knob position: {:.2f}".format(radio_channel_4_pos)) + textPrint.print(screen, "Right Knob position: {:.2f}".format(radio_channel_5_pos)) textPrint.print(screen, "Side dial position: {:.2f}".format(radio_channel_6_pos)) # ALL CODE TO DRAW SHOULD GO ABOVE THIS COMMENT @@ -98,6 +111,8 @@ def main(): radio_msg.channel[1] = joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(4) radio_msg.channel[3] = joystick.get_axis(3) + radio_msg.channel[4] = radio_channel_4_pos + radio_msg.channel[5] = radio_channel_5_pos radio_msg.channel[6] = radio_channel_6_pos radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 47a1a56fe3..d7b8d61814 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -97,6 +97,7 @@ cc_library( hdrs = ["foot_traj_generator.h"], deps = [ "//multibody:utils", + "//lcmtypes:lcmt_robot", "//systems/controllers/osc:osc_gains", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 12f678c1b7..f0ac0fa71e 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -2,6 +2,7 @@ #include +#include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" using Eigen::Map; @@ -71,6 +72,10 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, clock_port_ = this->DeclareVectorInputPort( "clock", BasicVector(VectorXd::Zero(1))) .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); // The swing foot position in the beginning of the swing phase initial_foot_pos_idx_ = this->DeclareDiscreteState(3); @@ -143,6 +148,15 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( this->EvalVectorInput(context, target_vel_port_)->get_value(); double clock = this->EvalVectorInput(context, clock_port_)->get_value()(0); + double lateral_radio_tuning = 1.0; + double sagital_radio_tuning = 1.0; + if (this->get_input_port(radio_port_).HasValue(context)) { + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + lateral_radio_tuning += radio_out->channel[4]; + sagital_radio_tuning += radio_out->channel[5]; + } + VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); multibody::SetPositionsAndVelocitiesIfNew( @@ -203,11 +217,11 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( VectorXd foot_end_pos_des = Kd_ * (pelvis_vel_err); if (is_left_foot_) { - foot_end_pos_des(1) += lateral_offset_; + foot_end_pos_des(1) += lateral_radio_tuning * lateral_offset_; } else { - foot_end_pos_des(1) -= lateral_offset_; + foot_end_pos_des(1) -= lateral_radio_tuning * lateral_offset_; } - foot_end_pos_des(0) += sagital_offset_; + foot_end_pos_des(0) += sagital_radio_tuning * sagital_offset_; foot_end_pos_des(2) = 0; std::vector T_waypoints; diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 72b8b7eb52..e22329d831 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -29,6 +29,9 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::systems::InputPort& get_target_vel_input_port() const { return this->get_input_port(target_vel_port_); } + const drake::systems::InputPort& get_radio_input_port() const { + return this->get_input_port(radio_port_); + } void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; @@ -77,6 +80,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { int target_vel_port_; int fsm_port_; int clock_port_; + int radio_port_; int initial_foot_pos_idx_; int initial_hip_pos_idx_; int pelvis_yaw_idx_; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 23a0b29ca8..9ad84504c9 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -544,6 +544,10 @@ int DoMain(int argc, char* argv[]) { l_foot_traj_generator->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), r_foot_traj_generator->get_state_input_port()); + builder.Connect(cassie_out_to_radio->get_output_port(), + l_foot_traj_generator->get_radio_input_port()); + builder.Connect(cassie_out_to_radio->get_output_port(), + r_foot_traj_generator->get_radio_input_port()); builder.Connect(fsm->get_output_port_clock(), l_foot_traj_generator->get_clock_input_port()); From 205dc171c1316a380f1e5ff44ab42c077a031e95 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 17 May 2022 16:54:48 -0400 Subject: [PATCH 212/758] setting different blending parameters --- examples/Cassie/osc_run/osc_running_gains.yaml | 4 ++-- examples/Cassie/run_osc_running_controller.cc | 4 ++-- systems/controllers/osc/operational_space_control.cc | 10 ++++++---- 3 files changed, 10 insertions(+), 8 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 86af2770b8..2febd57dcc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -47,7 +47,7 @@ hip_yaw_kd: 1 footstep_sagital_offset: -0.05 footstep_lateral_offset: 0.055 # mujoco #footstep_lateral_offset: 0.04 # drake -mid_foot_height: 0.07 +mid_foot_height: 0.1 FootstepKd: [ 0.3, 0, 0, 0, 0.6, 0, @@ -95,7 +95,7 @@ LiftoffSwingFootW: LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 35] LiftoffSwingFootKd: [ 5, 0, 0, 0, 5, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 9ad84504c9..b628425a41 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -420,8 +420,8 @@ int DoMain(int argc, char* argv[]) { // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); -// left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); -// right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 492b69dfdf..d151d828fd 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -771,6 +771,8 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); + double window = 0.01; + double tau = 0.01; if(fsm_state >= 2 && initial_guess_x_.size() == 4){ double clock_time; if (this->get_input_port(clock_port_).HasValue(context)) { @@ -778,16 +780,16 @@ VectorXd OperationalSpaceControl::SolveQp( clock_time = clock->get_value()(0); } if(fsm_state == 2){ - double blend_in = 1 - exp(-((0.4 - clock_time) + 0.01) / 0.010); - double blend_out = 1 - exp(-((clock_time - 0.3) + 0.01) / 0.010); + double blend_in = 1 - exp(-((0.4 - clock_time) + window) / tau); + double blend_out = 1 - exp(-((clock_time - 0.3) + window) / (2*tau)); u_sol_->row(6) = blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); u_sol_->row(7) = blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); u_sol_->row(0) = blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); // u_sol_->row(1) = blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); } if(fsm_state == 3){ - double blend_in = 1 - exp(-((0.8 - clock_time) + 0.01) / 0.010); - double blend_out = 1 - exp(-((clock_time - 0.7) + 0.01) / 0.010); + double blend_in = 1 - exp(-((0.8 - clock_time) + window) / tau); + double blend_out = 1 - exp(-((clock_time - 0.7) + window) / (2*tau)); u_sol_->row(6) = blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); u_sol_->row(7) = blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); // u_sol_->row(0) = blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); From 8ad05e3b393a25fab3c223d1d3726a50f3c05759 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 31 May 2022 09:50:15 -0400 Subject: [PATCH 213/758] adding contact processing --- .../analysis/cassie_plotting_utils.py | 4 + .../pydairlib/analysis/log_plotter_cassie.py | 9 ++- .../pydairlib/analysis/mbp_plotting_utils.py | 80 ++++++++++++++++--- .../pydairlib/analysis/process_lcm_log.py | 3 +- 4 files changed, 84 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 6179905924..6e5915e603 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -5,6 +5,7 @@ # dairlib imports import dairlib +import drake from pydairlib.cassie.cassie_utils import addCassieMultibody # drake imports @@ -29,6 +30,9 @@ 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output, 'OSC_DEBUG_RUNNING': dairlib.lcmt_osc_output} +cassie_contact_channels = \ + {'CASSIE_CONTACT_DRAKE': drake.lcmt_contact_results_for_viz} + def make_plant_and_context(floating_base=True, springs=True): builder = DiagramBuilder() diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index d198edb983..fc8b49f81d 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -31,6 +31,8 @@ def main(): pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) + import time + ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") @@ -40,7 +42,12 @@ def main(): plot_config.end_time, mbp_plots.load_default_channels, # processing callback plant, channel_x, channel_u, channel_osc) # processing callback arguments - import pdb; pdb.set_trace() + + contact_output = get_log_data(log, # log + cassie_plots.cassie_contact_channels, # lcm channels + plot_config.end_time, + mbp_plots.load_force_channels, # processing callback + 'CASSIE_CONTACT_DRAKE') # processing callback arguments print('Finished processing log - making plots') # Define x time slice diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 43a7166c90..be75c5b64e 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -168,6 +168,59 @@ def process_osc_channel(data): 'osc_output': osc_output} +def process_contact_channel(data): + t_contact_info = [] + contact_forces = [[], [], [], []] # Allocate space for all 4 point contacts + contact_info_locs = [[], [], [], []] + for msg in data: + t_contact_info.append(msg.timestamp / 1e6) + num_left_contacts = 0 + num_right_contacts = 0 + for i in range(msg.num_point_pair_contacts): + if "toe_left" in msg.point_pair_contact_info[i].body2_name: + if (num_left_contacts >= 2): + continue + contact_info_locs[num_left_contacts].append( + msg.point_pair_contact_info[i].contact_point) + contact_forces[num_left_contacts].append( + msg.point_pair_contact_info[i].contact_force) + num_left_contacts += 1 + elif "toe_right" in msg.point_pair_contact_info[i].body2_name: + if (num_right_contacts >= 2): + continue + contact_info_locs[2 + num_right_contacts].append( + msg.point_pair_contact_info[i].contact_point) + contact_forces[2 + num_right_contacts].append( + msg.point_pair_contact_info[i].contact_force) + num_right_contacts += 1 + while num_left_contacts != 2: + contact_forces[num_left_contacts].append((0.0, 0.0, 0.0)) + contact_info_locs[num_left_contacts].append((0.0, 0.0, 0.0)) + num_left_contacts += 1 + while num_right_contacts != 2: + contact_forces[2 + num_right_contacts].append((0.0, 0.0, 0.0)) + contact_info_locs[2 + num_right_contacts].append((0.0, 0.0, + 0.0)) + num_right_contacts += 1 + + t_contact_info = np.array(t_contact_info) + contact_forces = np.array(contact_forces) + contact_info_locs = np.array(contact_info_locs) + + for i in range(contact_info_locs.shape[1]): + # Swap front and rear contacts if necessary + # Order will be front contact in index 1 + if contact_info_locs[0, i, 0] > contact_info_locs[1, i, 0]: + contact_forces[[0, 1], i, :] = contact_forces[[1, 0], i, :] + contact_info_locs[[0, 1], i, :] = contact_info_locs[[1, 0], i, :] + if contact_info_locs[2, i, 0] > contact_info_locs[3, i, 0]: + contact_forces[[2, 3], i, :] = contact_forces[[3, 2], i, :] + contact_info_locs[[2, 3], i, :] = contact_info_locs[[3, 2], i, :] + return {'t_lambda': t_contact_info, + 'lambda_c': contact_forces, + 'p_lambda_c': contact_info_locs} + + def permute_osc_joint_ordering(osc_data, robot_output_msg, plant): _, vperm, uperm = make_joint_order_permutations(robot_output_msg, plant) osc_data['u_sol'] = (osc_data['u_sol'] @ uperm.T) @@ -186,6 +239,10 @@ def load_default_channels(data, plant, state_channel, input_channel, return robot_output, robot_input, osc_debug +def load_force_channels(data, contact_force_channel): + contact_info = process_contact_channel(data[contact_force_channel]) + return contact_info + def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, ylabel=None, title=None): @@ -207,6 +264,7 @@ def plot_q_or_v_or_u( 'title': title}, ps) return ps + def plot_u_cmd( robot_input, key, x_names, x_slice, time_slice, ylabel=None, title=None): @@ -272,10 +330,11 @@ def plot_measured_efforts(robot_output, u_names, time_slice): time_slice, ylabel='Efforts (Nm)', title='Joint Efforts') + def plot_commanded_efforts(robot_input, u_names, time_slice): return plot_u_cmd(robot_input, 'u', u_names, slice(len(u_names)), - time_slice, ylabel='Efforts (Nm)', - title='Commanded Joint Efforts') + time_slice, ylabel='Efforts (Nm)', + title='Commanded Joint Efforts') def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): @@ -411,6 +470,7 @@ def plot_qp_costs(osc_debug, time_slice): 'title': 'regularization_costs'}, ps) return ps + def plot_qp_solutions(osc_debug, time_slice): ps = plot_styler.PlotStyler() plotting_utils.make_plot( @@ -425,6 +485,7 @@ def plot_qp_solutions(osc_debug, time_slice): 'title': 'OSC Lambda Solutions'}, ps) return ps + def plot_qp_solve_time(osc_debug, time_slice): ps = plot_styler.PlotStyler() plotting_utils.make_plot( @@ -472,21 +533,20 @@ def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): return ps -def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names = []): +def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names=[]): ax = ps.fig.axes[0] ymin, ymax = ax.get_ylim() - # uses default color map legend_elements = [] for i in np.unique(fsm_signal): - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2*i), alpha=0.2) + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2 * i), alpha=0.2) if len(fsm_state_names) == np.unique(fsm_signal).shape[0]: - legend_elements.append(Patch(facecolor=ps.cmap(2*i), alpha=0.3, label=fsm_state_names[i])) + legend_elements.append(Patch(facecolor=ps.cmap(2 * i), alpha=0.3, label=fsm_state_names[i])) # if len(legend_elements) > 0: # legend = ax.legend(legend_elements, fsm_state_names, loc=4) - # ps.add_legend(legend, loc=4) - # ax.add_artist(legend) - # ax.add_artist(legend) - # ax.relim() + # ps.add_legend(legend, loc=4) + # ax.add_artist(legend) + # ax.add_artist(legend) + # ax.relim() diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/analysis/process_lcm_log.py index 7a651fc284..4bac5d030c 100644 --- a/bindings/pydairlib/analysis/process_lcm_log.py +++ b/bindings/pydairlib/analysis/process_lcm_log.py @@ -15,8 +15,9 @@ def get_log_data(lcm_log, lcm_channels, end_time, data_processing_callback, *arg data_to_process = {} print('Processing LCM log (this may take a while)...') - t = lcm_log.read_next_event().timestamp + # import pdb; pdb.set_trace() lcm_log.seek(0) + t = lcm_log.read_next_event().timestamp for event in lcm_log: if event.channel in lcm_channels: if event.channel in data_to_process: From 2be14477163d562e9152b9775e55990e881ee657 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Jun 2022 10:30:32 -0400 Subject: [PATCH 214/758] tuning in drake with correct motor model --- .../director_scripts/show_time_hardware.py | 10 +++-- examples/Cassie/multibody_sim.cc | 12 +++--- .../Cassie/osc_run/osc_running_gains.yaml | 41 +++++++++---------- examples/Cassie/run_osc_running_controller.cc | 2 +- examples/Cassie/urdf/cassie_v2.urdf | 20 ++++----- .../Cassie/urdf/cassie_v2_conservative.urdf | 4 +- systems/controllers/geared_motor.cc | 6 +-- .../osc/operational_space_control.cc | 35 ++++------------ 8 files changed, 55 insertions(+), 75 deletions(-) diff --git a/examples/Cassie/director_scripts/show_time_hardware.py b/examples/Cassie/director_scripts/show_time_hardware.py index a48b0a6984..5555f62c5b 100644 --- a/examples/Cassie/director_scripts/show_time_hardware.py +++ b/examples/Cassie/director_scripts/show_time_hardware.py @@ -4,6 +4,7 @@ from director import applogic import time import dairlib.lcmt_robot_output +import numpy as np class TimeVisualizer(object): @@ -25,8 +26,8 @@ def add_subscriber(self): if 'pd_panel_state_channel' in globals(): channel = pd_panel_state_channel else: - channel = "NETWORK_CASSIE_STATE_DISPATCHER" - # channel = "CASSIE_STATE_SIMULATION" + # channel = "NETWORK_CASSIE_STATE_DISPATCHER" + channel = "CASSIE_STATE_SIMULATION" self._subscriber = lcmUtils.addSubscriber( channel, @@ -53,11 +54,13 @@ def set_enabled(self, enable): def handle_message(self, msg): msg_time = msg.utime * 1e-6 # convert from microseconds pelvis_height = (msg.position)[6] # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[3:5]) # convert from microseconds self._real_time.append(time.time()) self._msg_time.append(msg_time) my_text = 'time: %.3f' % msg_time pelvis_height_text = 'pelvis height: %.3f' % pelvis_height + pelvis_velocity_text = 'pelvis velocity: %.3f' % pelvis_velocity if (len(self._real_time) >= self._num_msg_for_average): self._real_time.pop(0) @@ -70,7 +73,8 @@ def handle_message(self, msg): #my_text = my_text + ', real time factor: %.2f' % rt_ratio - vis.updateText(my_text + '\n' + pelvis_height_text, 'text') + vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text, 'text') + # vis.updateText(my_text + '\n' + pelvis_velocity_text, 'text') def init_visualizer(): diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 1d29c812c3..169667240a 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -138,18 +138,18 @@ int do_main(int argc, char* argv[]) { auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_radio_channel, lcm)); + // Order of joint actuators is not depth-first + std::vector omega_max = {303.687, 303.687, 303.687, 303.687, 136.136, + 136.135, 136.136, 136.135, 575.958, 575.958}; + + auto cassie_motor = builder.AddSystem(plant, omega_max); const auto& sensor_aggregator = - AddImuAndAggregator(&builder, plant, passthrough->get_output_port()); + AddImuAndAggregator(&builder, plant, cassie_motor->get_output_port()); auto sensor_pub = builder.AddSystem(LcmPublisherSystem::Make( "CASSIE_OUTPUT", lcm, 1.0 / FLAGS_publish_rate)); - std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, - 303.687, 303.687, 136.136, 136.135, 575.958}; - - auto cassie_motor = builder.AddSystem(plant, omega_max); - // connect leaf systems builder.Connect(*input_sub, *input_receiver); builder.Connect(input_receiver->get_output_port(), diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 2febd57dcc..d1877d31c0 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,11 +1,11 @@ -w_input: 0.0001 +w_input: 0.0000 w_accel: 0.0001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5] +W_input_reg: [5, 0.9, 0.5, 0.1, 5, + 5, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, @@ -19,17 +19,17 @@ impact_threshold: 0.1 impact_tau: 0.05 relative_feet: true relative_pelvis: true -ekf_filter_tau: [0.05, 0.1, 0.01] +ekf_filter_tau: [0.05, 0.01, 0.01] # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.2 +vel_scale_trans_sagital: 1.0 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.87 -stance_duration: 0.30 -flight_duration: 0.10 +rest_length: 1.0 +stance_duration: 0.20 +flight_duration: 0.1 #stance_duration: 0.7 #flight_duration: 0.09 @@ -44,36 +44,35 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.05 -footstep_lateral_offset: 0.055 # mujoco -#footstep_lateral_offset: 0.04 # drake +footstep_sagital_offset: -0.09 +footstep_lateral_offset: 0.045 # drake mid_foot_height: 0.1 FootstepKd: [ 0.3, 0, 0, - 0, 0.6, 0, + 0, 0.65, 0, 0, 0, 0 ] PelvisW: - [ 0.1, 0, 0, + [ 0, 0, 0, 0, 0, 0, 0, 0, 5 ] PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 65] + 0, 0, 30] PelvisKd: [ 0, 0, 0, 0, 0, 0, 0, 0, 4] PelvisRotW: - [1, 0, 0, - 0, 10, 0, - 0, 0, 0] + [5, 0, 0, + 0, 1, 0, + 0, 0, 5] PelvisRotKp: [20., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [1., 0, 0, + [10., 0, 0, 0, 5., 0, 0, 0, 1.] SwingFootW: @@ -82,12 +81,12 @@ SwingFootW: 0, 0, 5] SwingFootKp: [50, 0, 0, - 0, 50, 0, - 0, 0, 50] + 0, 75, 0, + 0, 0, 45] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 1.] + 0, 0, 2.] LiftoffSwingFootW: [1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b628425a41..df496d5904 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -190,7 +190,7 @@ int DoMain(int argc, char* argv[]) { auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); - std::vector tau = {.05, .1, .01}; + std::vector tau = {.05, .01, .01}; auto ekf_filter = builder.AddSystem(plant, tau); diff --git a/examples/Cassie/urdf/cassie_v2.urdf b/examples/Cassie/urdf/cassie_v2.urdf index 46284e004a..d7110db6ee 100644 --- a/examples/Cassie/urdf/cassie_v2.urdf +++ b/examples/Cassie/urdf/cassie_v2.urdf @@ -614,7 +614,7 @@ - + @@ -623,7 +623,7 @@ - + @@ -633,7 +633,7 @@ - + @@ -642,7 +642,7 @@ - + @@ -652,7 +652,7 @@ - + @@ -661,7 +661,7 @@ - + @@ -670,7 +670,7 @@ - + @@ -679,7 +679,7 @@ - + @@ -784,7 +784,7 @@ - + @@ -793,7 +793,7 @@ - + diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 04d2720659..23db5d2b58 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -672,7 +672,7 @@ - + @@ -681,7 +681,7 @@ - + diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc index b701e8e0b4..af0b444e82 100644 --- a/systems/controllers/geared_motor.cc +++ b/systems/controllers/geared_motor.cc @@ -19,7 +19,7 @@ GearedMotor::GearedMotor(const MultibodyPlant& plant, const JointActuator& joint_actuator = plant.get_joint_actuator(drake::multibody::JointActuatorIndex(i)); actuator_gear_ratios.push_back(joint_actuator.default_gear_ratio()); - actuator_ranges.push_back(joint_actuator.effort_limit()); + actuator_ranges.push_back(joint_actuator.effort_limit() / joint_actuator.default_gear_ratio()); actuator_max_speeds.push_back(max_motor_speeds[i]); } systems::BasicVector input(plant.num_actuators()); @@ -47,7 +47,7 @@ void GearedMotor::CalcTorqueOutput( for (int i = 0; i < n_u; ++i) { double ratio = actuator_gear_ratios[i]; double tmax = actuator_ranges[i]; - double w = actuator_velocities[i]; + double w = actuator_velocities[i] * ratio; double wmax = actuator_max_speeds[i]; // Calculate torque limit based on motor speed @@ -56,8 +56,6 @@ void GearedMotor::CalcTorqueOutput( // Compute motor-side torque tau[i] = copysign(fmin(fabs(u[i] / ratio), tlim), u[i]) * ratio; - -// tau[i] = copysign(fmin(fabs(u[i]), tlim), u[i]); } output->SetFromVector(tau); } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index d151d828fd..ff9fdbef65 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -544,7 +544,6 @@ VectorXd OperationalSpaceControl::SolveQp( next_fsm_state, M); // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; - // std::cout << v_proj.transpose() << std::endl; } // SetVelocitiesIfNew( // plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, @@ -587,9 +586,6 @@ VectorXd OperationalSpaceControl::SolveQp( row_idx += contact_i->num_active(); } - // std::cout << "JdotV_h" << JdotV_h.transpose() << std::endl; - // std::cout << "JdotV_c" << JdotV_c_active.transpose() << std::endl; - // Update constraints // 1. Dynamics constraint /// M*dv + bias == J_c^T*lambda_c + J_h^T*lambda_h + B*u @@ -747,7 +743,7 @@ VectorXd OperationalSpaceControl::SolveQp( W_input_smoothing_, -W_input_smoothing_ * u_prev_[fsm_state]); } if (W_lambda_c_reg_.size() > 0) { - lambda_c_smoothing_cost_->UpdateCoefficients(100 * alpha * W_lambda_c_reg_, + lambda_c_smoothing_cost_->UpdateCoefficients(1000 * alpha * W_lambda_c_reg_, VectorXd::Zero(n_c_)); } @@ -780,19 +776,19 @@ VectorXd OperationalSpaceControl::SolveQp( clock_time = clock->get_value()(0); } if(fsm_state == 2){ - double blend_in = 1 - exp(-((0.4 - clock_time) + window) / tau); - double blend_out = 1 - exp(-((clock_time - 0.3) + window) / (2*tau)); + double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); + double blend_out = 1 - exp(-((clock_time - 0.2) + window) / tau); u_sol_->row(6) = blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); u_sol_->row(7) = blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); u_sol_->row(0) = blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); -// u_sol_->row(1) = blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); + u_sol_->row(1) = blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); } if(fsm_state == 3){ - double blend_in = 1 - exp(-((0.8 - clock_time) + window) / tau); - double blend_out = 1 - exp(-((clock_time - 0.7) + window) / (2*tau)); + double blend_in = 1 - exp(-((0.6 - clock_time) + window) / tau); + double blend_out = 1 - exp(-((clock_time - 0.5) + window) / tau); u_sol_->row(6) = blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); u_sol_->row(7) = blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); -// u_sol_->row(0) = blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); + u_sol_->row(0) = blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); u_sol_->row(1) = blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); } } @@ -822,14 +818,9 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( ii_lambda_sol_ = VectorXd::Zero(n_c_ + n_h_); M_Jt_ = MatrixXd::Zero(n_v_, n_c_ + n_h_); return; - // throw std::out_of_range("Contact mode: " + - // std::to_string(next_fsm_state) + - // " was not found in the OSC"); } std::set next_contact_set = map_iterator->second; int active_constraint_dim = active_contact_dim_.at(next_fsm_state) + n_h_; - // std::cout << "active constraint dim: " << active_constraint_dim << - // std::endl; MatrixXd J_next = MatrixXd::Zero(active_constraint_dim, n_v_); int row_start = 0; for (unsigned int i = 0; i < all_contacts_.size(); i++) { @@ -845,8 +836,6 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( J_next.block(row_start, 0, n_h_, n_v_) = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); } - // std::cout << "J: " << std::endl; - // std::cout << J_next << std::endl; M_Jt_ = M.llt().solve(J_next.transpose()); int active_tracking_data_dim = 0; @@ -907,20 +896,10 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( C.transpose(); VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); b_constrained << Ab, d; - // A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) - // = MatriXd; - // ii_lambda_sol_ = A.completeOrthogonalDecomposition().solve(ydot_err_vec); ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition() .solve(b_constrained) .head(active_constraint_dim); - - // std::cout << "constraint velocity: " << (J_h * - // (x_w_spr.tail(n_v_))).transpose() << std::endl; std::cout << "projected - // velocity: " << (J_h * (x_w_spr.tail(n_v_) + M_Jt_ * - // ii_lambda_sol_)).transpose() << std::endl; - - // std::cout << ii_lambda_sol_.transpose() << std::endl; } void OperationalSpaceControl::AssignOscLcmOutput( From 9f18650c133140cb64f5dd796b5a702bd5952b75 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Jun 2022 10:43:25 -0400 Subject: [PATCH 215/758] committing gains for now --- examples/Cassie/osc_run/osc_running_gains.yaml | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d1877d31c0..1a6b734eb8 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,8 +4,8 @@ w_accel: 0.0001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [5, 0.9, 0.5, 0.1, 5, - 5, 0.9, 0.5, 0.1, 5] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, @@ -44,9 +44,9 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.09 +footstep_sagital_offset: -0.13 footstep_lateral_offset: 0.045 # drake -mid_foot_height: 0.1 +mid_foot_height: 0.05 FootstepKd: [ 0.3, 0, 0, 0, 0.65, 0, @@ -68,12 +68,12 @@ PelvisRotW: 0, 1, 0, 0, 0, 5] PelvisRotKp: - [20., 0, 0, - 0, 100., 0, + [400., 0, 0, + 0, 200., 0, 0, 0, 0.] PelvisRotKd: - [10., 0, 0, - 0, 5., 0, + [15., 0, 0, + 0, 10., 0, 0, 0, 1.] SwingFootW: [10, 0, 0, From 8dc906f42e99b88777842bf0a760bbc054d9f1cf Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Jun 2022 10:43:52 -0400 Subject: [PATCH 216/758] small plotter change --- bindings/pydairlib/analysis/log_plotter_cassie.py | 11 ++++------- 1 file changed, 4 insertions(+), 7 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index fc8b49f81d..39a31a3b9d 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -31,8 +31,6 @@ def main(): pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) - import time - ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") @@ -78,17 +76,16 @@ def main(): # Plot all joint velocities if plot_config.plot_joint_positions: plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, - 6 if use_floating_base else 0, - t_x_slice) + 6 if use_floating_base else 0, + t_x_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) # Plot specific velocities if plot_config.vel_names: plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, - t_x_slice, vel_map) + t_x_slice, vel_map) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - ''' Plot Efforts ''' if plot_config.plot_measured_efforts: plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) @@ -131,7 +128,7 @@ def main(): pts['toe_' + pos] = pts_map[plot_config.pt_on_foot_to_plot] plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, - foot_frames, pts, dims) + foot_frames, pts, dims) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_qp_solve_time: From 6e3bf3cb49cd5e2b58ba433f22cdffea6a925040 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Jun 2022 12:24:26 -0400 Subject: [PATCH 217/758] cleaning code --- systems/controllers/geared_motor.cc | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/systems/controllers/geared_motor.cc b/systems/controllers/geared_motor.cc index af0b444e82..336655df94 100644 --- a/systems/controllers/geared_motor.cc +++ b/systems/controllers/geared_motor.cc @@ -24,11 +24,12 @@ GearedMotor::GearedMotor(const MultibodyPlant& plant, } systems::BasicVector input(plant.num_actuators()); systems::BasicVector output(plant.num_actuators()); + systems::BasicVector state(n_q + n_v); command_input_port_ = this->DeclareVectorInputPort("u_cmd", input).get_index(); state_input_port_ = - this->DeclareVectorInputPort("x", BasicVector(n_q + n_v)) + this->DeclareVectorInputPort("x", state) .get_index(); this->DeclareVectorOutputPort("u_motor", output, &GearedMotor::CalcTorqueOutput); @@ -42,6 +43,7 @@ void GearedMotor::CalcTorqueOutput( command_input_port_); const systems::BasicVector& x = *this->template EvalVectorInput(context, state_input_port_); + Eigen::VectorXd actuator_velocities = B_.transpose() * x.value().tail(n_v); Eigen::VectorXd tau = Eigen::VectorXd::Zero(n_u); for (int i = 0; i < n_u; ++i) { From 4fbefd951382d22cdadeae61c31926538e64ee31 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Jun 2022 14:14:37 -0400 Subject: [PATCH 218/758] drake trajopt deprecation fixes --- examples/Cassie/run_dircon_jumping.cc | 164 +++++++++++++------------- examples/Cassie/run_dircon_running.cc | 133 +++++++++++---------- solvers/cost_function_utils.cc | 2 +- 3 files changed, 152 insertions(+), 147 deletions(-) diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 7d3ebb845d..cb808c05d0 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -290,50 +290,51 @@ void DoMain() { all_modes.AddMode(&land_mode); auto trajopt = Dircon(all_modes); + auto& prog = trajopt.prog(); double tol = FLAGS_tol; if (FLAGS_ipopt) { // Ipopt settings adapted from CaSaDi and FROST auto id = drake::solvers::IpoptSolver::id(); - trajopt.SetSolverOption(id, "tol", tol); - trajopt.SetSolverOption(id, "dual_inf_tol", tol); - trajopt.SetSolverOption(id, "constr_viol_tol", tol); - trajopt.SetSolverOption(id, "compl_inf_tol", tol); - trajopt.SetSolverOption(id, "max_iter", 1e5); - trajopt.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); - trajopt.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); - trajopt.SetSolverOption(id, "print_timing_statistics", "yes"); - trajopt.SetSolverOption(id, "print_level", 5); - trajopt.SetSolverOption(id, "output_file", "../ipopt.out"); + prog.SetSolverOption(id, "tol", tol); + prog.SetSolverOption(id, "dual_inf_tol", tol); + prog.SetSolverOption(id, "constr_viol_tol", tol); + prog.SetSolverOption(id, "compl_inf_tol", tol); + prog.SetSolverOption(id, "max_iter", 1e5); + prog.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); + prog.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); + prog.SetSolverOption(id, "print_timing_statistics", "yes"); + prog.SetSolverOption(id, "print_level", 5); + prog.SetSolverOption(id, "output_file", "../ipopt.out"); // Set to ignore overall tolerance/dual infeasibility, but terminate when // primal feasible and objective fails to increase over 5 iterations. - trajopt.SetSolverOption(id, "acceptable_compl_inf_tol", tol); - trajopt.SetSolverOption(id, "acceptable_constr_viol_tol", tol); - trajopt.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); - trajopt.SetSolverOption(id, "acceptable_tol", 1e2); - trajopt.SetSolverOption(id, "acceptable_iter", 5); + prog.SetSolverOption(id, "acceptable_compl_inf_tol", tol); + prog.SetSolverOption(id, "acceptable_constr_viol_tol", tol); + prog.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); + prog.SetSolverOption(id, "acceptable_tol", 1e2); + prog.SetSolverOption(id, "acceptable_iter", 5); } else { // Snopt settings auto id = drake::solvers::SnoptSolver::id(); if (FLAGS_use_springs) { - trajopt.SetSolverOption(id, "Print file", "../w_springs_snopt.out"); + prog.SetSolverOption(id, "Print file", "../w_springs_snopt.out"); } else { - trajopt.SetSolverOption(id, "Print file", "../snopt.out"); + prog.SetSolverOption(id, "Print file", "../snopt.out"); } - trajopt.SetSolverOption(id, "Major iterations limit", 1e5); - trajopt.SetSolverOption(id, "Iterations limit", 100000); - trajopt.SetSolverOption(id, "Verify level", 0); + prog.SetSolverOption(id, "Major iterations limit", 1e5); + prog.SetSolverOption(id, "Iterations limit", 100000); + prog.SetSolverOption(id, "Verify level", 0); // snopt doc said try 2 if seeing snopta exit 40 - trajopt.SetSolverOption(id, "Scale option", 2); - trajopt.SetSolverOption(id, "Solution", "No"); + prog.SetSolverOption(id, "Scale option", 2); + prog.SetSolverOption(id, "Solution", "No"); // target nonlinear constraint violation - trajopt.SetSolverOption(id, "Major optimality tolerance", 1e-4); + prog.SetSolverOption(id, "Major optimality tolerance", 1e-4); // target complementarity gap - trajopt.SetSolverOption(id, "Major feasibility tolerance", tol); + prog.SetSolverOption(id, "Major feasibility tolerance", tol); } std::cout << "Adding kinematic constraints: " << std::endl; @@ -352,7 +353,7 @@ void DoMain() { std::cout << "nv: " << n_v << endl; std::cout << "nu: " << plant.num_actuators() << endl; cout << "N: " << num_knot_points << endl; - cout << "Num decision vars: " << trajopt.decision_variables().size() << endl; + cout << "Num decision vars: " << prog.decision_variables().size() << endl; if (!FLAGS_load_filename.empty()) { std::cout << "Loading: " << FLAGS_load_filename << std::endl; @@ -366,11 +367,11 @@ void DoMain() { trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); cout << "\nChoose the best solver: " - << drake::solvers::ChooseBestSolver(trajopt).name() << endl; + << drake::solvers::ChooseBestSolver(prog).name() << endl; cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); + const auto result = drake::solvers::Solve(prog, prog.initial_guess()); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; cout << "Solve time:" << elapsed.count() << std::endl; @@ -401,6 +402,7 @@ void DoMain() { void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant) { + auto *prog = &trajopt->prog(); // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); @@ -431,55 +433,55 @@ void SetKinematicConstraints(Dircon* trajopt, double midpoint = 0.045; // position constraints - trajopt->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, + prog->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, x_0(pos_map.at("base_x"))); - trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); - trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); + prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); + prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); // initial fb orientation constraint VectorXd quat_identity(4); quat_identity << 1, 0, 0, 0; - trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x_0.head(4)); - trajopt->AddBoundingBoxConstraint(quat_identity, quat_identity, x_f.head(4)); + prog->AddBoundingBoxConstraint(quat_identity, quat_identity, x_0.head(4)); + prog->AddBoundingBoxConstraint(quat_identity, quat_identity, x_f.head(4)); // hip yaw and roll constraints - trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); - trajopt->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); + prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); + prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); - trajopt->AddBoundingBoxConstraint(0.00, 0.1, + prog->AddBoundingBoxConstraint(0.00, 0.1, x_0(pos_map.at("hip_roll_left"))); - trajopt->AddBoundingBoxConstraint(-0.1, -0.00, + prog->AddBoundingBoxConstraint(-0.1, -0.00, x_0(pos_map.at("hip_roll_right"))); // hip yaw and roll constraints - trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); - trajopt->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_right"))); + prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); + prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_right"))); - trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_left"))); - trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_right"))); - trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_left"))); - trajopt->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_right"))); + prog->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_left"))); + prog->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_right"))); + prog->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_left"))); + prog->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_right"))); // Jumping height constraints - trajopt->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, + prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); if (FLAGS_height < 0) { - trajopt->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, + prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, 0.5 * FLAGS_height + rest_height - eps, x_top(pos_map.at("base_z"))); } else { - trajopt->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, + prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, FLAGS_height + rest_height + eps, x_top(pos_map.at("base_z"))); } - trajopt->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, + prog->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, 0.8 * FLAGS_height + rest_height + eps, x_f(pos_map.at("base_z"))); // Zero starting and final velocities - trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); - trajopt->AddLinearConstraint(VectorXd::Zero(n_v) == x_f.tail(n_v)); + prog->AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); + prog->AddLinearConstraint(VectorXd::Zero(n_v) == x_f.tail(n_v)); // create joint/motor names vector> l_r_pairs{ @@ -522,7 +524,7 @@ void SetKinematicConstraints(Dircon* trajopt, trajopt->AddConstraintToAllKnotPoints( x_0(pos_map[sym_joint_name + l_r_pair.first]) == x_0(pos_map[sym_joint_name + l_r_pair.second])); - trajopt->AddLinearConstraint( + prog->AddLinearConstraint( x_f(pos_map[sym_joint_name + l_r_pair.first]) == x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle @@ -552,7 +554,7 @@ void SetKinematicConstraints(Dircon* trajopt, std::cout << "Actuator limit constraints: " << std::endl; for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); - trajopt->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), + prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), VectorXd::Constant(n_u, +175), ui); } @@ -573,8 +575,8 @@ void SetKinematicConstraints(Dircon* trajopt, for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); - trajopt->AddConstraint(left_foot_y_constraint, x_i.head(n_q)); - trajopt->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); + prog->AddConstraint(left_foot_y_constraint, x_i.head(n_q)); + prog->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); } } @@ -587,8 +589,8 @@ void SetKinematicConstraints(Dircon* trajopt, std::make_shared>( plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), (0 - eps) * VectorXd::Ones(1), (0 + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_x_start_constraint, x_0.head(n_q)); - trajopt->AddConstraint(right_foot_x_start_constraint, x_0.head(n_q)); + prog->AddConstraint(left_foot_x_start_constraint, x_0.head(n_q)); + prog->AddConstraint(right_foot_x_start_constraint, x_0.head(n_q)); // Jumping distance constraint for platform clearance auto left_foot_x_platform_constraint = @@ -601,8 +603,8 @@ void SetKinematicConstraints(Dircon* trajopt, plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); - trajopt->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); + prog->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); // Jumping distance constraint auto left_foot_x_constraint = @@ -615,8 +617,8 @@ void SetKinematicConstraints(Dircon* trajopt, plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), (FLAGS_distance - eps) * VectorXd::Ones(1), (FLAGS_distance + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_x_constraint, x_f.head(n_q)); - trajopt->AddConstraint(right_foot_x_constraint, x_f.head(n_q)); + prog->AddConstraint(left_foot_x_constraint, x_f.head(n_q)); + prog->AddConstraint(right_foot_x_constraint, x_f.head(n_q)); // Foot clearance constraint auto left_foot_z_constraint = @@ -629,8 +631,8 @@ void SetKinematicConstraints(Dircon* trajopt, plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_z_constraint, x_top.head(n_q)); - trajopt->AddConstraint(right_foot_z_constraint, x_top.head(n_q)); + prog->AddConstraint(left_foot_z_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_z_constraint, x_top.head(n_q)); auto left_foot_rear_z_final_constraint = std::make_shared>( @@ -642,8 +644,8 @@ void SetKinematicConstraints(Dircon* trajopt, plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), (FLAGS_height - eps) * VectorXd::Ones(1), (FLAGS_height + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_rear_z_final_constraint, x_f.head(n_q)); - trajopt->AddConstraint(right_foot_rear_z_final_constraint, x_f.head(n_q)); + prog->AddConstraint(left_foot_rear_z_final_constraint, x_f.head(n_q)); + prog->AddConstraint(right_foot_rear_z_final_constraint, x_f.head(n_q)); auto left_foot_front_z_final_constraint = std::make_shared>( @@ -655,36 +657,36 @@ void SetKinematicConstraints(Dircon* trajopt, plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), (FLAGS_height - eps) * VectorXd::Ones(1), (FLAGS_height + eps) * VectorXd::Ones(1)); - trajopt->AddConstraint(left_foot_front_z_final_constraint, x_f.head(n_q)); - trajopt->AddConstraint(right_foot_front_z_final_constraint, x_f.head(n_q)); + prog->AddConstraint(left_foot_front_z_final_constraint, x_f.head(n_q)); + prog->AddConstraint(right_foot_front_z_final_constraint, x_f.head(n_q)); // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground for (int index = 0; index < (mode_lengths[0] - 2); index++) { auto lambda = trajopt->force_vars(0, index); - trajopt->AddLinearConstraint(lambda(2) >= 60); - trajopt->AddLinearConstraint(lambda(5) >= 60); - trajopt->AddLinearConstraint(lambda(8) >= 60); - trajopt->AddLinearConstraint(lambda(11) >= 60); + prog->AddLinearConstraint(lambda(2) >= 60); + prog->AddLinearConstraint(lambda(5) >= 60); + prog->AddLinearConstraint(lambda(8) >= 60); + prog->AddLinearConstraint(lambda(11) >= 60); } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); - trajopt->AddLinearConstraint(lambda(2) <= 350); - trajopt->AddLinearConstraint(lambda(5) <= 350); - trajopt->AddLinearConstraint(lambda(8) <= 350); - trajopt->AddLinearConstraint(lambda(11) <= 350); - trajopt->AddLinearConstraint(lambda(2) >= 50); - trajopt->AddLinearConstraint(lambda(5) >= 50); - trajopt->AddLinearConstraint(lambda(8) >= 50); - trajopt->AddLinearConstraint(lambda(11) >= 50); + prog->AddLinearConstraint(lambda(2) <= 350); + prog->AddLinearConstraint(lambda(5) <= 350); + prog->AddLinearConstraint(lambda(8) <= 350); + prog->AddLinearConstraint(lambda(11) <= 350); + prog->AddLinearConstraint(lambda(2) >= 50); + prog->AddLinearConstraint(lambda(5) >= 50); + prog->AddLinearConstraint(lambda(8) >= 50); + prog->AddLinearConstraint(lambda(11) >= 50); } // Limit the ground impulses when landing auto Lambda = trajopt->impulse_vars(1); - trajopt->AddLinearConstraint(Lambda(2) <= 2); - trajopt->AddLinearConstraint(Lambda(5) <= 2); - trajopt->AddLinearConstraint(Lambda(8) <= 2); - trajopt->AddLinearConstraint(Lambda(11) <= 2); + prog->AddLinearConstraint(Lambda(2) <= 2); + prog->AddLinearConstraint(Lambda(5) <= 2); + prog->AddLinearConstraint(Lambda(8) <= 2); + prog->AddLinearConstraint(Lambda(11) <= 2); } /****** @@ -907,7 +909,7 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, Eigen::MatrixXd spr_map) { DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); if (same_knot_points) { - trajopt.SetInitialGuessForAllVariables( + trajopt.prog().SetInitialGuessForAllVariables( previous_traj.GetDecisionVariables()); return; } diff --git a/examples/Cassie/run_dircon_running.cc b/examples/Cassie/run_dircon_running.cc index f99f0bf016..fd1ec8fc4e 100644 --- a/examples/Cassie/run_dircon_running.cc +++ b/examples/Cassie/run_dircon_running.cc @@ -199,46 +199,47 @@ void DoMain() { // all_modes.AddMode(&flight_phase); auto trajopt = Dircon(all_modes); + auto& prog = trajopt.prog(); double tol = FLAGS_tol; if (FLAGS_ipopt) { // Ipopt settings adapted from CaSaDi and FROST auto id = drake::solvers::IpoptSolver::id(); - trajopt.SetSolverOption(id, "tol", tol); - trajopt.SetSolverOption(id, "dual_inf_tol", tol); - trajopt.SetSolverOption(id, "constr_viol_tol", tol); - trajopt.SetSolverOption(id, "compl_inf_tol", tol); - trajopt.SetSolverOption(id, "max_iter", 1e5); - trajopt.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); - trajopt.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); - trajopt.SetSolverOption(id, "print_timing_statistics", "yes"); - trajopt.SetSolverOption(id, "print_level", 5); - trajopt.SetSolverOption(id, "output_file", "../ipopt.out"); + prog.SetSolverOption(id, "tol", tol); + prog.SetSolverOption(id, "dual_inf_tol", tol); + prog.SetSolverOption(id, "constr_viol_tol", tol); + prog.SetSolverOption(id, "compl_inf_tol", tol); + prog.SetSolverOption(id, "max_iter", 1e5); + prog.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); + prog.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); + prog.SetSolverOption(id, "print_timing_statistics", "yes"); + prog.SetSolverOption(id, "print_level", 5); + prog.SetSolverOption(id, "output_file", "../ipopt.out"); // Set to ignore overall tolerance/dual infeasibility, but terminate when // primal feasible and objective fails to increase over 5 iterations. - trajopt.SetSolverOption(id, "acceptable_compl_inf_tol", tol); - trajopt.SetSolverOption(id, "acceptable_constr_viol_tol", tol); - trajopt.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); - trajopt.SetSolverOption(id, "acceptable_tol", 1e2); - trajopt.SetSolverOption(id, "acceptable_iter", 5); + prog.SetSolverOption(id, "acceptable_compl_inf_tol", tol); + prog.SetSolverOption(id, "acceptable_constr_viol_tol", tol); + prog.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); + prog.SetSolverOption(id, "acceptable_tol", 1e2); + prog.SetSolverOption(id, "acceptable_iter", 5); } else { // Snopt settings auto id = drake::solvers::SnoptSolver::id(); - trajopt.SetSolverOption(id, "Print file", "../snopt.out"); - trajopt.SetSolverOption(id, "Major iterations limit", 1e5); - trajopt.SetSolverOption(id, "Iterations limit", 100000); - trajopt.SetSolverOption(id, "Verify level", 0); + prog.SetSolverOption(id, "Print file", "../snopt.out"); + prog.SetSolverOption(id, "Major iterations limit", 1e5); + prog.SetSolverOption(id, "Iterations limit", 100000); + prog.SetSolverOption(id, "Verify level", 0); // snopt doc said try 2 if seeing snopta exit 40 - trajopt.SetSolverOption(id, "Scale option", 2); - trajopt.SetSolverOption(id, "Solution", "No"); + prog.SetSolverOption(id, "Scale option", 2); + prog.SetSolverOption(id, "Solution", "No"); // target nonlinear constraint violation - trajopt.SetSolverOption(id, "Major optimality tolerance", 1e-4); + prog.SetSolverOption(id, "Major optimality tolerance", 1e-4); // target complementarity gap - trajopt.SetSolverOption(id, "Major feasibility tolerance", tol); + prog.SetSolverOption(id, "Major feasibility tolerance", tol); } std::cout << "Adding kinematic constraints: " << std::endl; @@ -251,8 +252,8 @@ void DoMain() { FLAGS_data_directory + FLAGS_load_filename, FLAGS_same_knotpoints); } else { - trajopt.SetInitialGuessForAllVariables( - VectorXd::Random(trajopt.decision_variables().size())); + prog.SetInitialGuessForAllVariables( + VectorXd::Random(prog.decision_variables().size())); } // auto loaded_traj = @@ -272,12 +273,12 @@ void DoMain() { // To avoid NaN quaternions for (int i = 0; i < trajopt.N(); i++) { auto xi = trajopt.state(i); - if ((trajopt.GetInitialGuess(xi.head(4)).norm() == 0) || - std::isnan(trajopt.GetInitialGuess(xi.head(4)).norm())) { - trajopt.SetInitialGuess(xi(0), 1); - trajopt.SetInitialGuess(xi(1), 0); - trajopt.SetInitialGuess(xi(2), 0); - trajopt.SetInitialGuess(xi(3), 0); + if ((prog.GetInitialGuess(xi.head(4)).norm() == 0) || + std::isnan(prog.GetInitialGuess(xi.head(4)).norm())) { + prog.SetInitialGuess(xi(0), 1); + prog.SetInitialGuess(xi(1), 0); + prog.SetInitialGuess(xi(2), 0); + prog.SetInitialGuess(xi(3), 0); } } @@ -290,13 +291,13 @@ void DoMain() { solver_id = drake::solvers::IpoptSolver().id(); cout << "\nChose manually: " << solver_id.name() << endl; } else { - solver_id = drake::solvers::ChooseBestSolver(trajopt); + solver_id = drake::solvers::ChooseBestSolver(prog); cout << "\nChose the best solver: " << solver_id.name() << endl; } cout << "Solving DIRCON\n\n"; auto start = std::chrono::high_resolution_clock::now(); - const auto result = drake::solvers::Solve(trajopt, trajopt.initial_guess()); + const auto result = drake::solvers::Solve(prog, prog.initial_guess()); // SolutionResult solution_result = result.get_solution_result(); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; @@ -329,6 +330,8 @@ void DoMain() { void setKinematicConstraints(Dircon& trajopt, const MultibodyPlant& plant) { + auto& prog = trajopt.prog(); + // Create maps for joints map pos_map = multibody::makeNameToPositionsMap(plant); map vel_map = multibody::makeNameToVelocitiesMap(plant); @@ -352,36 +355,36 @@ void setKinematicConstraints(Dircon& trajopt, double start_height = FLAGS_start_height; // position constraints - trajopt.AddBoundingBoxConstraint(-0.25, 0.25, x0(pos_map.at("base_x"))); - trajopt.AddLinearConstraint(x0(pos_map.at("base_x")) + FLAGS_stride_length == + prog.AddBoundingBoxConstraint(-0.25, 0.25, x0(pos_map.at("base_x"))); + prog.AddLinearConstraint(x0(pos_map.at("base_x")) + FLAGS_stride_length == xf(pos_map.at("base_x"))); - trajopt.AddBoundingBoxConstraint(start_height, start_height, + prog.AddBoundingBoxConstraint(start_height, start_height, x0(pos_map.at("base_z"))); // trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("base_y")) <= 0.05); // trajopt.AddConstraintToAllKnotPoints(x(pos_map.at("base_y")) >= -0.05); // initial fb orientation constraint VectorXd quat_identity(4); quat_identity << 1, 0, 0, 0; - trajopt.AddBoundingBoxConstraint(quat_identity, quat_identity, x0.head(4)); - trajopt.AddBoundingBoxConstraint(quat_identity, quat_identity, x_mid.head(4)); - trajopt.AddBoundingBoxConstraint(quat_identity, quat_identity, xf.head(4)); + prog.AddBoundingBoxConstraint(quat_identity, quat_identity, x0.head(4)); + prog.AddBoundingBoxConstraint(quat_identity, quat_identity, x_mid.head(4)); + prog.AddBoundingBoxConstraint(quat_identity, quat_identity, xf.head(4)); // periodicity constraint - trajopt.AddLinearConstraint(x0(pos_map.at("base_y")) == + prog.AddLinearConstraint(x0(pos_map.at("base_y")) == -xf(pos_map.at("base_y"))); - trajopt.AddLinearConstraint(x0(pos_map.at("base_z")) == + prog.AddLinearConstraint(x0(pos_map.at("base_z")) == xf(pos_map.at("base_z"))); - trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_wx")) == + prog.AddLinearConstraint(x0(n_q + vel_map.at("base_wx")) == xf(n_q + vel_map.at("base_wx"))); - trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_wy")) == + prog.AddLinearConstraint(x0(n_q + vel_map.at("base_wy")) == -xf(n_q + vel_map.at("base_wy"))); - trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_wz")) == + prog.AddLinearConstraint(x0(n_q + vel_map.at("base_wz")) == xf(n_q + vel_map.at("base_wz"))); - trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_vx")) == + prog.AddLinearConstraint(x0(n_q + vel_map.at("base_vx")) == xf(n_q + vel_map.at("base_vx"))); - trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_vy")) == + prog.AddLinearConstraint(x0(n_q + vel_map.at("base_vy")) == -xf(n_q + vel_map.at("base_vy"))); - trajopt.AddLinearConstraint(x0(n_q + vel_map.at("base_vz")) == + prog.AddLinearConstraint(x0(n_q + vel_map.at("base_vz")) == xf(n_q + vel_map.at("base_vz"))); // create joint/motor names @@ -409,28 +412,28 @@ void setKinematicConstraints(Dircon& trajopt, for (const auto& l_r_pair : l_r_pairs) { // Symmetry constraints for (const auto& sym_joint_name : sym_joint_names) { - trajopt.AddLinearConstraint( + prog.AddLinearConstraint( x0(pos_map[sym_joint_name + l_r_pair.first]) == xf(pos_map[sym_joint_name + l_r_pair.second])); - trajopt.AddLinearConstraint( + prog.AddLinearConstraint( x0(n_q + vel_map.at(sym_joint_name + l_r_pair.first + "dot")) == xf(n_q + vel_map.at(sym_joint_name + l_r_pair.second + "dot"))); if (sym_joint_name != "ankle_joint") { // No actuator at ankle - trajopt.AddLinearConstraint( + prog.AddLinearConstraint( u0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == uf(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); } } // Asymmetry constraints for (const auto& asy_joint_name : asy_joint_names) { - trajopt.AddLinearConstraint( + prog.AddLinearConstraint( x0(pos_map[asy_joint_name + l_r_pair.first]) == -xf(pos_map[asy_joint_name + l_r_pair.second])); - trajopt.AddLinearConstraint( + prog.AddLinearConstraint( x0(n_q + vel_map.at(asy_joint_name + l_r_pair.first + "dot")) == -xf(n_q + vel_map.at(asy_joint_name + l_r_pair.second + "dot"))); if (asy_joint_name != "ankle_joint") { // No actuator at ankle - trajopt.AddLinearConstraint( + prog.AddLinearConstraint( u0(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) == -uf(act_map.at(asy_joint_name + l_r_pair.second + "_motor"))); } @@ -452,7 +455,7 @@ void setKinematicConstraints(Dircon& trajopt, std::cout << "Actuator limit constraints: " << std::endl; for (int i = 0; i < trajopt.N(); i++) { auto ui = trajopt.input(i); - trajopt.AddBoundingBoxConstraint(VectorXd::Constant(n_u, -200), + prog.AddBoundingBoxConstraint(VectorXd::Constant(n_u, -200), VectorXd::Constant(n_u, +200), ui); } @@ -470,8 +473,8 @@ void setKinematicConstraints(Dircon& trajopt, for (int i = 0; i < N; ++i) { auto x_i = trajopt.state(i); - trajopt.AddConstraint(left_foot_y_constraint, x_i.head(n_q)); - trajopt.AddConstraint(right_foot_y_constraint, x_i.head(n_q)); + prog.AddConstraint(left_foot_y_constraint, x_i.head(n_q)); + prog.AddConstraint(right_foot_y_constraint, x_i.head(n_q)); } for (int mode = 0; mode < trajopt.num_modes(); ++mode) { @@ -480,8 +483,8 @@ void setKinematicConstraints(Dircon& trajopt, auto lambda = trajopt.force_vars(mode, index); if (mode == 0 || mode == 2) { - trajopt.AddLinearConstraint(lambda(2) >= 10); - trajopt.AddLinearConstraint(lambda(5) >= 10); + prog.AddLinearConstraint(lambda(2) >= 10); + prog.AddLinearConstraint(lambda(5) >= 10); } } } @@ -496,8 +499,8 @@ void setKinematicConstraints(Dircon& trajopt, std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(1, 0, 0), 0 * VectorXd::Ones(1), 0 * VectorXd::Ones(1)); - trajopt.AddConstraint(left_foot_x_constraint, x0.head(n_q)); - trajopt.AddConstraint(right_foot_x_constraint, xf.head(n_q)); + prog.AddConstraint(left_foot_x_constraint, x0.head(n_q)); + prog.AddConstraint(right_foot_x_constraint, xf.head(n_q)); std::cout << "Foot clearance constraints: " << std::endl; // Foot clearance constraint @@ -511,10 +514,10 @@ void setKinematicConstraints(Dircon& trajopt, 0.055 * VectorXd::Ones(1), (0.15) * VectorXd::Ones(1)); for (int i = 0; i < N; i++) { auto x_i = trajopt.state(i); - trajopt.AddConstraint(left_foot_z_constraint_clearance, x_i.head(n_q)); - trajopt.AddConstraint(right_foot_z_constraint_clearance, x_i.head(n_q)); - trajopt.AddBoundingBoxConstraint(-1.8, -1.5, x_i[pos_map["toe_left"]]); - trajopt.AddBoundingBoxConstraint(-1.8, -1.5, x_i[pos_map["toe_right"]]); + prog.AddConstraint(left_foot_z_constraint_clearance, x_i.head(n_q)); + prog.AddConstraint(right_foot_z_constraint_clearance, x_i.head(n_q)); + prog.AddBoundingBoxConstraint(-1.8, -1.5, x_i[pos_map["toe_left"]]); + prog.AddBoundingBoxConstraint(-1.8, -1.5, x_i[pos_map["toe_right"]]); } std::cout << "Miscellaneous constraints" << std::endl; @@ -575,7 +578,7 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, bool same_knot_points) { DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); if (same_knot_points) { - trajopt.SetInitialGuessForAllVariables( + trajopt.prog().SetInitialGuessForAllVariables( previous_traj.GetDecisionVariables()); return; } diff --git a/solvers/cost_function_utils.cc b/solvers/cost_function_utils.cc index 9802ccdec1..b696011ba5 100644 --- a/solvers/cost_function_utils.cc +++ b/solvers/cost_function_utils.cc @@ -31,7 +31,7 @@ void AddPositiveWorkCost( trajopt.input_vars(mode, i - mode_start); variables.segment(1 + 2 * n_v + n_u, n_u) = trajopt.input_vars(mode, i + 1 - mode_start); - trajopt.AddCost( + trajopt.prog().AddCost( std::make_shared>(n_v, plant.num_actuators(), plant.MakeActuationMatrix(), W, "pos_work_cost_" + std::to_string(i)), From 1563b9a91fe8f51c4ee65fd3328c6e99a40b5951 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Jun 2022 14:41:07 -0400 Subject: [PATCH 219/758] updating learning script --- bindings/pydairlib/cassie/learn_osc_gains.py | 26 ++++++++++---------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 160a5da8e8..f2c7716b46 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -46,18 +46,18 @@ def __init__(self, budget, reward_function, visualize=False): 'mu': 0.6, 'w_hip_yaw': 2.5, 'hip_yaw_kp': 40, - # 'PelvisKp': np.array([0, 0, 85]), - # 'PelvisKd': np.array([1, 0, 5]), + 'PelvisKp': np.array([0, 0, 50]), + 'PelvisKd': np.array([0, 0, 5]), # 'PelvisRotKp': np.array([50, 100, 0]), 'PelvisRotKd': np.array([10, 5, 1]), 'SwingFootKp': np.array([125, 80, 50]), 'SwingFootKd': np.array([5, 5, 1]), 'FootstepKd': np.array([0.2, 0.45, 0]), - 'center_line_offset': 0.03, + # 'center_line_offset': 0.03, # 'rest_length': 0.85, - 'footstep_offset': -0.05, - 'stance_duration': 0.30, - 'flight_duration': 0.08, + # 'footstep_offset': -0.05, + # 'stance_duration': 0.30, + # 'flight_duration': 0.08, } def save_params(self, folder, params, budget): @@ -115,18 +115,18 @@ def learn_gains(self, batch=True): mu=ng.p.Scalar(lower=0.4, upper=1.0), w_hip_yaw=ng.p.Scalar(lower=0, upper=10), hip_yaw_kp=ng.p.Scalar(lower=20, upper=80), - # PelvisKp=ng.p.Array(lower=0., upper=150., shape=(3,)), - # PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), + PelvisKp=ng.p.Array(lower=0., upper=75., shape=(3,)), + PelvisKd=ng.p.Array(lower=0., upper=10., shape=(3,)), # PelvisRotKp=ng.p.Array(lower=20., upper=150., shape=(3,)), PelvisRotKd=ng.p.Array(lower=0., upper=15., shape=(3,)), SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), + # center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), - footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), - stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), - flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), + # footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), + # stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), + # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) self.loss_over_time = [] self.default_params.value = self.default_osc_gains @@ -149,7 +149,7 @@ def learn_gains(self, batch=True): reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - # optimizer.learn_gains() + optimizer.learn_gains() optimal_params = optimizer.load_params('2022_03_28_18_2000', optimizer.drake_params_folder).value optimizer.write_params(optimal_params) From d2a50e71f6c8f677d492fdf981f44c135df434e3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Jun 2022 09:39:58 -0400 Subject: [PATCH 220/758] learning gains again --- .../cassie/gym_envs/cassie_gym_test.py | 6 +- .../cassie/gym_envs/drake_cassie_gym.py | 1 + .../cassie/gym_envs/mujoco_cassie_gym.py | 7 ++ bindings/pydairlib/cassie/learn_osc_gains.py | 28 +++---- .../osc_run/learned_osc_running_gains.yaml | 76 +++++++++---------- 5 files changed, 64 insertions(+), 54 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 5527b9a02c..161910581b 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -30,8 +30,8 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - # gym_env = DrakeCassieGym(reward_func, visualize=True) - gym_env = MuJoCoCassieGym(reward_func, visualize=True) + gym_env = DrakeCassieGym(reward_func, visualize=True) + # gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) cumulative_reward = gym_env.advance_to(7.5) print(cumulative_reward) diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 758d8b2560..5db61bc607 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -89,6 +89,7 @@ def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.sim_dt + action[2] = 1.0 self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) self.controller.get_radio_input_port().FixValue(self.controller_context, action) self.sim.AdvanceTo(next_timestep) diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 794eb46429..7b815102e1 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -177,6 +177,12 @@ def advance_to(self, time): def check_termination(self): return self.cassie_state.get_fb_positions()[2] < 0.4 + def velocity_profile(self, timestep): + velocity_command = np.zeros(18) + velocity_command[2] = min(1.0 * timestep, 4.0) + # velocity_command[2] = 5.0 + return velocity_command + def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") @@ -188,6 +194,7 @@ def step(self, action=np.zeros(18)): next_timestep = self.drake_sim.get_context().get_time() + timestep self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) + action = self.velocity_profile(timestep) self.radio_input_port.FixValue(self.controller_context, action) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index f2c7716b46..22124db572 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -53,9 +53,10 @@ def __init__(self, budget, reward_function, visualize=False): 'SwingFootKp': np.array([125, 80, 50]), 'SwingFootKd': np.array([5, 5, 1]), 'FootstepKd': np.array([0.2, 0.45, 0]), - # 'center_line_offset': 0.03, - # 'rest_length': 0.85, - # 'footstep_offset': -0.05, + 'footstep_sagital_offset': 0, + 'mid_foot_height': 0.05, + 'rest_length': 0.95, + 'footstep_lateral_offset': 0.045, # 'stance_duration': 0.30, # 'flight_duration': 0.08, } @@ -102,7 +103,7 @@ def get_single_loss(self, params): gym_env.make(controller) # rollout a trajectory and compute the loss cumulative_reward = 0 - while gym_env.current_time < 7.5 and not gym_env.terminated: + while gym_env.current_time < gym_env.end_time and not gym_env.terminated: state, reward = gym_env.step(np.zeros(18)) cumulative_reward += reward # print(-cumulative_reward) @@ -122,9 +123,10 @@ def learn_gains(self, batch=True): SwingFootKp=ng.p.Array(lower=20., upper=150., shape=(3,)), SwingFootKd=ng.p.Array(lower=0., upper=15., shape=(3,)), FootstepKd=ng.p.Array(lower=0., upper=1., shape=(3,)), - # center_line_offset=ng.p.Scalar(lower=0.03, upper=0.075), - # rest_length=ng.p.Scalar(lower=0.8, upper=0.9), - # footstep_offset=ng.p.Scalar(lower=-0.1, upper=0.05), + footstep_sagital_offset=ng.p.Scalar(lower=-0.1, upper=0.1), + mid_foot_height=ng.p.Scalar(lower=0.03, upper=0.15), + rest_length=ng.p.Scalar(lower=0.8, upper=1.0), + footstep_lateral_offset=ng.p.Scalar(lower=-0.1, upper=0.05), # stance_duration=ng.p.Scalar(lower=0.25, upper=0.40), # flight_duration=ng.p.Scalar(lower=0.05, upper=0.15), ) @@ -144,15 +146,15 @@ def learn_gains(self, batch=True): if __name__ == '__main__': # budget = 2000 - budget = 2000 + budget = 500 reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) optimizer.learn_gains() - optimal_params = optimizer.load_params('2022_03_28_18_2000', optimizer.drake_params_folder).value - optimizer.write_params(optimal_params) - reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') - plt.plot(reward_over_time) - plt.show() + # optimal_params = optimizer.load_params('2022_06_02_11_2000', optimizer.drake_params_folder).value + # optimizer.write_params(optimal_params) + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') + # plt.plot(reward_over_time) + # plt.show() diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 3024cb734a..4d84ca7536 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,47 +1,47 @@ -FootstepKd: [ 0.20630578931908952, 0.0, 0.0, 0.0, 0.5022846733099167, 0.0, 0.0, 0.0, - 0.014419706168051383 ] -LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, 0, 0, 0 ] -LiftoffSwingFootKp: [ 50.0, 0, 0, 0, 50.0, 0, 0, 0, 50.0 ] -LiftoffSwingFootW: [ 0.1, 0, 0, 0, 10, 0, 0, 0, 1 ] -PelvisKd: [ 1, 0, 0, 0, 0, 0, 0, 0, 5 ] -PelvisKp: [ 0, 0, 0, 0, 0, 0, 0, 0, 85 ] -PelvisRotKd: [ 14.754198175926723, 0.0, 0.0, 0.0, 10.15048844191982, 0.0, 0.0, 0.0, - 3.9038583836913308 ] -PelvisRotKp: [ 50.0, 0, 0, 0, 100.0, 0, 0, 0, 1.0 ] -PelvisRotW: [ 1, 0, 0, 0, 2.5, 0, 0, 0, 0.1 ] -PelvisW: [ 0.1, 0, 0, 0, 0, 0, 0, 0, 5 ] -SwingFootKd: [ 5.8013545212157736, 0.0, 0.0, 0.0, 8.37349939782334, 0.0, 0.0, 0.0, - 4.294753134633737 ] -SwingFootKp: [ 111.90374548402804, 0.0, 0.0, 0.0, 93.51462206597392, 0.0, 0.0, 0.0, - 75.82806014571253 ] -SwingFootW: [ 10, 0, 0, 0, 10, 0, 0, 0, 1 ] -W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] -W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] -W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] -W_lambda_h_reg: [ 0.01, 0.01, 0.01, 0.01, 0.02, 0.02 ] -#center_line_offset: 0.03036161874399593 -center_line_offset: 0.04036161874399593 -ekf_filter_tau: [ 0.05, 0.1, 0.01 ] -flight_duration: 0.053967347248977025 -footstep_offset: -0.044971023856448855 +FootstepKd: [0.46841073050690146, 0.0, 0.0, 0.0, 0.748560743315644, 0.0, 0.0, 0.0, + 0.44242891152442715] +LiftoffSwingFootKd: [5, 0, 0, 0, 5, 0, 0, 0, 1] +LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, 0, 0, 35] +LiftoffSwingFootW: [1, 0, 0, 0, 1, 0, 0, 0, 1] +PelvisKd: [4.948999143556126, 0.0, 0.0, 0.0, 6.5301848218127985, 0.0, 0.0, 0.0, 7.298373841539416] +PelvisKp: [19.100237370072687, 0.0, 0.0, 0.0, 57.36403593132101, 0.0, 0.0, 0.0, 55.648318752411384] +PelvisRotKd: [10.250875681407072, 0.0, 0.0, 0.0, 7.733517734123472, 0.0, 0.0, 0.0, + 3.9099864773828106] +PelvisRotKp: [400.0, 0, 0, 0, 200.0, 0, 0, 0, 0.0] +PelvisRotW: [5, 0, 0, 0, 1, 0, 0, 0, 5] +PelvisW: [0, 0, 0, 0, 0, 0, 0, 0, 5] +SwingFootKd: [4.511797455205392, 0.0, 0.0, 0.0, 10.116363856408572, 0.0, 0.0, 0.0, + 1.4546311014385775] +SwingFootKp: [132.8249342477374, 0.0, 0.0, 0.0, 113.15628351311878, 0.0, 0.0, 0.0, + 63.12354541559851] +SwingFootW: [10, 0, 0, 0, 100, 0, 0, 0, 5] +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] +W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] +ekf_filter_tau: [0.05, 0.01, 0.01] +flight_duration: 0.1 +footstep_lateral_offset: 0.006180317224739254 +footstep_sagital_offset: 0.014871427401484165 hip_yaw_kd: 1 -hip_yaw_kp: 48.17643439890748 -impact_threshold: 0.025 -mid_foot_height: 0.05 -mu: 0.6097124570750189 +hip_yaw_kp: 32.86695254058621 +impact_tau: 0.05 +impact_threshold: 0.1 +mid_foot_height: 0.04035365095366986 +mu: 0.5394085182898759 relative_feet: true relative_pelvis: true -rest_length: 0.85 -stance_duration: 0.2949526396548052 +rest_length: 0.9739036240530025 +stance_duration: 0.2 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 -vel_scale_trans_sagital: 0.2 -w_accel: 1.0e-05 -w_hip_yaw: 2.0187541880806643 +vel_scale_trans_sagital: 1.0 +w_accel: 0.0001 +w_hip_yaw: 0.875707580415595 w_input: 0.0 -w_input_reg: 0.004802653072422612 -w_soft_constraint: 111.82117439652899 +w_input_reg: 0.0005387738161234992 +w_soft_constraint: 56.674999872454705 w_swing_toe: 1 From 57469d459c1c40617a27eab5680c145667f57063 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Jun 2022 11:46:16 -0400 Subject: [PATCH 221/758] big merge with master --- bindings/pydairlib/cassie/BUILD.bazel | 2 +- .../cassie/gym_envs/cassie_gym_test.py | 8 +- .../pydairlib/cassie/input_supervisor_py.cc | 2 +- .../mujoco/drake_to_mujoco_converter.py | 12 +- bindings/pydairlib/multibody/multibody_py.cc | 2 + examples/Cassie/BUILD.bazel | 16 +- examples/Cassie/closed_loop_running_sim.cc | 2 +- examples/Cassie/diagrams/BUILD.bazel | 4 +- .../Cassie/diagrams/cassie_sim_diagram.cc | 17 +-- examples/Cassie/diagrams/cassie_sim_diagram.h | 4 +- .../osc_running_controller_diagram.cc | 41 ++--- .../osc_walking_controller_diagram.cc | 6 +- examples/Cassie/multibody_sim_w_platform.cc | 2 +- examples/Cassie/osc/BUILD.bazel | 2 + examples/Cassie/osc/osc_walking_gains_alip.h | 23 ++- .../Cassie/osc/osc_walking_gains_alip.yaml | 36 +++-- examples/Cassie/osc_run/osc_running_gains.h | 5 - .../Cassie/osc_run/osc_running_gains.yaml | 14 +- examples/Cassie/run_dircon_running.cc | 14 +- examples/Cassie/run_osc_running_controller.cc | 17 +-- examples/Cassie/run_osc_walking_controller.cc | 24 ++- .../Cassie/run_osc_walking_controller_alip.cc | 143 +++++++++--------- systems/controllers/BUILD.bazel | 15 -- .../osc/operational_space_control.cc | 10 -- .../controllers/osc/options_tracking_data.cc | 4 +- .../controllers/osc/options_tracking_data.h | 2 +- systems/framework/geared_motor.cc | 2 +- 27 files changed, 199 insertions(+), 230 deletions(-) diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index d60a404415..bccab2efd8 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -31,7 +31,7 @@ pybind_py_library( pybind_py_library( name = "input_supervisor_py", cc_deps = [ - "//examples/Cassie:input_supervisor", + "//examples/Cassie/systems:input_supervisor", "@drake//:drake_shared_library", ], cc_so_name = "input_supervisor", diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 161910581b..f295e42876 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -11,7 +11,7 @@ def main(): osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' - # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains.yaml' + # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains_alip.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' @@ -22,7 +22,7 @@ def main(): cumulative_reward = 0 while 1: controller_plant = MultibodyPlant(8e-5) - addCassieMultibody(controller_plant, None, True, urdf, False, False) + AddCassieMultibody(controller_plant, None, True, urdf, False, False) controller_plant.Finalize() controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) @@ -30,8 +30,8 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - gym_env = DrakeCassieGym(reward_func, visualize=True) - # gym_env = MuJoCoCassieGym(reward_func, visualize=True) + # gym_env = DrakeCassieGym(reward_func, visualize=True) + gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) cumulative_reward = gym_env.advance_to(7.5) print(cumulative_reward) diff --git a/bindings/pydairlib/cassie/input_supervisor_py.cc b/bindings/pydairlib/cassie/input_supervisor_py.cc index 39012d7dcd..7ee93ccbe1 100644 --- a/bindings/pydairlib/cassie/input_supervisor_py.cc +++ b/bindings/pydairlib/cassie/input_supervisor_py.cc @@ -3,7 +3,7 @@ #include #include -#include "examples/Cassie/input_supervisor.h" +#include "examples/Cassie/systems/input_supervisor.h" #include "drake/multibody/plant/multibody_plant.h" diff --git a/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py index e2cee6dcb3..b33ac9ecd7 100644 --- a/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py +++ b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py @@ -23,7 +23,7 @@ def __init__(self, drake_sim_dt=5e-5): self.builder = DiagramBuilder() self.drake_sim_dt = drake_sim_dt self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, drake_sim_dt) - addCassieMultibody(self.plant, self.scene_graph, True, + AddCassieMultibody(self.plant, self.scene_graph, True, 'examples/Cassie/urdf/cassie_v2.urdf', False, False) self.plant.Finalize() @@ -49,9 +49,9 @@ def __init__(self, drake_sim_dt=5e-5): # self.print_pos_indices(self.knee_linkage_plant) # self.print_pos_indices(self.plant) - self.pos_map = makeNameToPositionsMap(self.plant) - self.vel_map = makeNameToVelocitiesMap(self.plant) - self.act_map = makeNameToActuatorsMap(self.plant) + self.pos_map = MakeNameToPositionsMap(self.plant) + self.vel_map = MakeNameToVelocitiesMap(self.plant) + self.act_map = MakeNameToActuatorsMap(self.plant) self.map_q_drake_to_mujoco = np.zeros((23, 35)) self.map_v_drake_to_mujoco = np.zeros((22, 32)) @@ -88,12 +88,12 @@ def __init__(self, drake_sim_dt=5e-5): self.ik_solver.prog().AddLinearEqualityConstraint(self.ik_solver.q()[0:7], np.array([1, 0, 0, 0, 0, 0, 0])) def print_pos_indices(self, plant): - name_map = makeNameToPositionsMap(plant) + name_map = MakeNameToPositionsMap(plant) for name in name_map: print(name + ': ' + str(name_map[name])) def print_vel_indices(self, plant): - name_map = makeNameToVelocitiesMap(plant) + name_map = MakeNameToVelocitiesMap(plant) for name in name_map: print(name + ': ' + str(name_map[name])) diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index 896d7e4789..852d3cd26c 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -42,6 +42,8 @@ PYBIND11_MODULE(multibody, m) { py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"), py::arg("mu_kinetic"), py::arg("normal_W") = Eigen::Vector3d(0, 0, 1), + py::arg("stiffness") = 0, + py::arg("dissipation_rate") = 0, py::arg("show_ground") = 1); } diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 29044f73b9..7639cae371 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -194,7 +194,7 @@ cc_binary( "//examples/Cassie/systems:cassie_encoder", "//solvers:optimization_utils", "//systems:robot_lcm_systems", - "//systems/controllers:geared_motor", + "//systems/framework:geared_motor", "//systems/primitives", "//systems:system_utils", "@drake//:drake_shared_library", @@ -379,6 +379,7 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//examples/Cassie/osc", + "//examples/Cassie/systems:cassie_out_to_radio", "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//multibody:utils", "//multibody:view_frame", @@ -564,19 +565,6 @@ py_binary( ], ) -cc_library( - name = "cassie_encoder", - srcs = ["cassie_encoder.cc"], - hdrs = [ - "cassie_encoder.h", - ], - deps = [ - "//multibody:utils", - "//systems/framework:vector", - "@drake//:drake_shared_library", - ], -) - py_binary( name = "cassie_virtual_remote_py", srcs = ["cassie_virtual_remote.py"], diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 2cb8c3b0b8..ca71363601 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -38,7 +38,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant controller_plant = MultibodyPlant(8e-5); // Built the Cassie MBPs - addCassieMultibody(&controller_plant, nullptr, true, + AddCassieMultibody(&controller_plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); controller_plant.Finalize(); diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel index bc61fac65a..120b0b2e8b 100644 --- a/examples/Cassie/diagrams/BUILD.bazel +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -83,12 +83,12 @@ cc_library( srcs = ["cassie_sim_diagram.cc"], hdrs = ["cassie_sim_diagram.h"], deps = [ - "//examples/Cassie:cassie_encoder", + "//examples/Cassie/systems:cassie_encoder", "//examples/Cassie:cassie_fixed_point_solver", "//examples/Cassie:cassie_urdf", "//examples/Cassie:cassie_utils", "//systems:robot_lcm_systems", - "//systems/controllers:geared_motor", + "//systems/framework:geared_motor", "//systems/primitives", "//systems/primitives:radio_parser", "//systems:system_utils", diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 2703b4f54d..e079265974 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -10,7 +10,7 @@ #include "examples/Cassie/cassie_fixed_point_solver.h" #include "examples/Cassie/cassie_utils.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/geared_motor.h" +#include "systems/framework/geared_motor.h" #include "systems/primitives/radio_parser.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" @@ -55,7 +55,7 @@ CassieSimDiagram::CassieSimDiagram( scene_graph_->set_name("scene_graph"); plant_ = builder.AddSystem(std::move(plant)); - addCassieMultibody(plant_, scene_graph_, true, urdf, true, true); + AddCassieMultibody(plant_, scene_graph_, true, urdf, true, true); multibody::AddFlatTerrain(plant_, scene_graph_, mu, mu, Eigen::Vector3d(0, 0, 1), stiffness, dissipation_rate); @@ -80,11 +80,8 @@ CassieSimDiagram::CassieSimDiagram( sensor_aggregator_ = &AddImuAndAggregator(&builder, *plant_, constant_source->get_output_port()); - std::vector omega_max = {303.687, 303.687, 136.136, 136.135, 575.958, - 303.687, 303.687, 136.136, 136.135, 575.958}; + cassie_motor_ = &AddMotorModel(&builder, *plant); - auto cassie_motor = - builder.AddSystem(*plant_, omega_max); auto radio_parser = builder.AddSystem(); // connect leaf systems @@ -95,14 +92,14 @@ CassieSimDiagram::CassieSimDiagram( builder.Connect(discrete_time_delay->get_output_port(), passthrough->get_input_port()); builder.Connect(passthrough->get_output_port(), - cassie_motor->get_input_port_command()); - builder.Connect(cassie_motor->get_output_port(), + cassie_motor_->get_input_port_command()); + builder.Connect(cassie_motor_->get_output_port(), plant_->get_actuation_input_port()); builder.Connect(plant_->get_state_output_port(), state_sender->get_input_port_state()); builder.Connect(plant_->get_state_output_port(), - cassie_motor->get_input_port_state()); - builder.Connect(cassie_motor->get_output_port(), + cassie_motor_->get_input_port_state()); + builder.Connect(cassie_motor_->get_output_port(), state_sender->get_input_port_effort()); builder.Connect( plant_->get_geometry_poses_output_port(), diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 1356932962..005805e0ae 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -5,7 +5,8 @@ #include -#include "examples/Cassie/sim_cassie_sensor_aggregator.h" +#include "examples/Cassie/systems/sim_cassie_sensor_aggregator.h" +#include "systems/framework/geared_motor.h" #include "drake/common/drake_copyable.h" #include "drake/systems/framework/diagram.h" @@ -55,6 +56,7 @@ class CassieSimDiagram : public drake::systems::Diagram { private: drake::multibody::MultibodyPlant* plant_; const systems::SimCassieSensorAggregator* sensor_aggregator_; + const systems::GearedMotor* cassie_motor_; // const systems::RadioParser* radio_parser_; drake::geometry::SceneGraph* scene_graph_; const int actuation_input_port_index_ = 0; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 0fb8fde0dd..00115bbb48 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -74,11 +74,11 @@ namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::multibody::MultibodyPlant& plant, - const string& osc_gainsfilename, const string& osqp_settings_filename) + const string& osc_gains_filename, const string& osqp_settings_filename) : plant_(&plant), - pos_map(multibody::makeNameToPositionsMap(plant)), - vel_map(multibody::makeNameToVelocitiesMap(plant)), - act_map(multibody::makeNameToActuatorsMap(plant)), + pos_map(multibody::MakeNameToPositionsMap(plant)), + vel_map(multibody::MakeNameToVelocitiesMap(plant)), + act_map(multibody::MakeNameToActuatorsMap(plant)), left_toe(LeftToeFront(plant)), left_heel(LeftToeRear(plant)), right_toe(RightToeFront(plant)), @@ -125,14 +125,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( {right_toe, right_heel}); /**** OSC Gains ****/ - drake::yaml::YamlReadArchive::Options yaml_options; + drake::yaml::LoadYamlOptions yaml_options; yaml_options.allow_yaml_with_no_cpp = true; - OSCGains osc_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gainsfilename), {}, {}, yaml_options); + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_running_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gainsfilename)); + FindResourceOrThrow(osc_gains_filename)); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -163,7 +163,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( accumulated_state_durations.pop_back(); auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, osc_gains.impact_threshold); + plant, fsm_states, state_durations, 0.0, + osc_running_gains.impact_threshold); auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); @@ -180,17 +181,18 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); - osc->SetInputCostWeights(osc_gains.w_input * - osc_gains.W_input_regularization); + osc->SetAccelerationCostWeights(osc_running_gains.w_accel * + osc_running_gains.W_acceleration); + osc->SetInputCostWeights(osc_running_gains.w_input * + osc_running_gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight( - 1e-5 * osc_gains.W_lambda_h_regularization); + 1e-5 * osc_running_gains.W_lambda_h_regularization); // Soft constraint on contacts - osc->SetSoftConstraintWeight(osc_gains.w_soft_constraint); + osc->SetSoftConstraintWeight(osc_running_gains.w_soft_constraint); // Contact information for OSC - osc->SetContactFriction(osc_gains.mu); + osc->SetContactFriction(osc_running_gains.mu); osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); @@ -232,10 +234,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( osc_running_gains.rest_length, osc_running_gains.footstep_lateral_offset, - osc_running_gains.footstep_sagital_offset, osc_running_gains.mid_foot_height); + osc_running_gains.footstep_sagital_offset, + osc_running_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( osc_running_gains.rest_length, osc_running_gains.footstep_lateral_offset, - osc_running_gains.footstep_sagital_offset, osc_running_gains.mid_foot_height); + osc_running_gains.footstep_sagital_offset, + osc_running_gains.mid_foot_height); pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_running_gains.K_p_pelvis, @@ -492,8 +496,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); - builder.ExportInput(radio_parser->get_input_port(), - "raw_radio"); + builder.ExportInput(radio_parser->get_input_port(), "raw_radio"); builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); builder.ExportOutput(osc->get_osc_output_port(), "u, t"); builder.ExportOutput(failure_aggregator->get_status_output_port(), diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 76262096b8..122c4a61c9 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -68,9 +68,9 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( drake::multibody::MultibodyPlant& plant, bool has_double_stance, const string& osc_walking_gains_filename, const string& osqp_settings_filename) : plant_(&plant), - pos_map(multibody::makeNameToPositionsMap(plant)), - vel_map(multibody::makeNameToVelocitiesMap(plant)), - act_map(multibody::makeNameToActuatorsMap(plant)), + pos_map(multibody::MakeNameToPositionsMap(plant)), + vel_map(multibody::MakeNameToVelocitiesMap(plant)), + act_map(multibody::MakeNameToActuatorsMap(plant)), left_toe(LeftToeFront(plant)), left_heel(LeftToeRear(plant)), right_toe(RightToeFront(plant)), diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 614835b0af..e963e0eaeb 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -217,7 +217,7 @@ int do_main(int argc, char* argv[]) { // diagram is built, plant.get_actuation_input_port().HasValue(*context) // throws a segfault error drake::multibody::MultibodyPlant plant_for_solver(0.0); - addCassieMultibody(&plant_for_solver, nullptr, + AddCassieMultibody(&plant_for_solver, nullptr, FLAGS_floating_base /*floating base*/, urdf, FLAGS_spring_model, true); plant_for_solver.Finalize(); diff --git a/examples/Cassie/osc/BUILD.bazel b/examples/Cassie/osc/BUILD.bazel index 3ee2a461c5..ff942be658 100644 --- a/examples/Cassie/osc/BUILD.bazel +++ b/examples/Cassie/osc/BUILD.bazel @@ -10,11 +10,13 @@ cc_library( "//examples/Cassie/osc:hip_yaw_traj_gen", "//examples/Cassie/osc:osc_walking_gains", "//examples/Cassie/osc:osc_walking_gains_alip", + "//examples/Cassie/osc:osc_standing_gains", "//examples/Cassie/osc:standing_com_traj", "//examples/Cassie/osc:standing_pelvis_traj", "//examples/Cassie/osc:swing_toe_traj", "//examples/Cassie/osc:walking_speed_control", "//systems/controllers:alip_swing_ft_traj_gen", + "//systems/controllers/osc:osc_gains", "//systems/controllers:alip_traj_gen", "//systems/controllers:lipm_traj_gen", "//systems/controllers:swing_ft_traj_gen", diff --git a/examples/Cassie/osc/osc_walking_gains_alip.h b/examples/Cassie/osc/osc_walking_gains_alip.h index 54a4c0c142..57773f4624 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.h +++ b/examples/Cassie/osc/osc_walking_gains_alip.h @@ -1,16 +1,16 @@ -#include "drake/common/yaml/yaml_read_archive.h" +#pragma once + +#include "systems/controllers/osc/osc_gains.h" #include "yaml-cpp/yaml.h" +#include "drake/common/yaml/yaml_read_archive.h" + using Eigen::MatrixXd; using Eigen::VectorXd; -struct OSCWalkingGainsALIP { +struct OSCWalkingGainsALIP : OSCGains { int rows; int cols; - double mu; - double w_accel; - double w_soft_constraint; - double w_input_reg; std::vector pelvis_xyz_vel_filter_tau; std::vector CoMW; std::vector CoMKp; @@ -84,12 +84,9 @@ struct OSCWalkingGainsALIP { template void Serialize(Archive* a) { + OSCGains::Serialize(a); a->Visit(DRAKE_NVP(rows)); a->Visit(DRAKE_NVP(cols)); - a->Visit(DRAKE_NVP(mu)); - a->Visit(DRAKE_NVP(w_accel)); - a->Visit(DRAKE_NVP(w_soft_constraint)); - a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(pelvis_xyz_vel_filter_tau)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); @@ -191,7 +188,9 @@ struct OSCWalkingGainsALIP { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); - Q_alip_kalman_filter = Eigen::Map(this->AlipKalmanQ.data(), 4); - R_alip_kalman_filter = Eigen::Map(this->AlipKalmanR.data(), 4); + Q_alip_kalman_filter = + Eigen::Map(this->AlipKalmanQ.data(), 4); + R_alip_kalman_filter = + Eigen::Map(this->AlipKalmanR.data(), 4); } }; diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index d8123aa9d5..ae5ae78b46 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -1,3 +1,24 @@ +# OSC gains +w_input: 0.0000 +w_input_reg: 0.0000 +w_accel: 0.0001 +w_soft_constraint: 100 +impact_threshold: 0.1 +impact_tau: 0.05 +mu: 0.6 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] + rows: 3 cols: 3 @@ -29,7 +50,6 @@ target_pos_offset: 0 # -0.16 # Finite state machine ss_time: 0.3 ds_time: 0.1 -impact_threshold: 0.025 # Distance of contact point from foot rear (0 is heel, 1 is toe) contact_point_pos: 0.35 @@ -45,18 +65,10 @@ final_foot_velocity_z: 0.0 # LIPM trajectory lipm_height: 0.85 -# OSC gains -mu: 0.6 -w_accel: 0.00000001 -w_soft_constraint: 80 -w_input_reg: 0.0000003 -W_lambda_c_reg: [1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01] -W_lambda_h_reg: [0.01, 0.01, 0.01, - 0.01, 0.02, 0.02] + +#w_soft_constraint: 1000000 + w_swing_toe: 1 swing_toe_kp: 1500 diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 455d4362a5..6026cd337f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -77,11 +77,6 @@ struct OSCRunningGains : OSCGains { template void Serialize(Archive* a) { OSCGains::Serialize(a); - a->Visit(DRAKE_NVP(w_input)); - a->Visit(DRAKE_NVP(w_accel)); - a->Visit(DRAKE_NVP(w_soft_constraint)); - a->Visit(DRAKE_NVP(impact_threshold)); - a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); a->Visit(DRAKE_NVP(rest_length)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 1a6b734eb8..36cfd7454f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,5 +1,10 @@ w_input: 0.0000 +w_input_reg: 0.1 w_accel: 0.0001 +w_soft_constraint: 100 +impact_threshold: 0.1 +impact_tau: 0.05 +mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, @@ -13,10 +18,7 @@ W_lambda_c_reg: [1, 0.001, 0.01, W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 -w_soft_constraint: 100 -w_input_reg: 0.1 -impact_threshold: 0.1 -impact_tau: 0.05 + relative_feet: true relative_pelvis: true ekf_filter_tau: [0.05, 0.01, 0.01] @@ -30,10 +32,8 @@ vel_scale_trans_lateral: -0.15 rest_length: 1.0 stance_duration: 0.20 flight_duration: 0.1 -#stance_duration: 0.7 -#flight_duration: 0.09 -mu: 0.6 + w_swing_toe: 1 swing_toe_kp: 1500 diff --git a/examples/Cassie/run_dircon_running.cc b/examples/Cassie/run_dircon_running.cc index fd1ec8fc4e..1a67cc9888 100644 --- a/examples/Cassie/run_dircon_running.cc +++ b/examples/Cassie/run_dircon_running.cc @@ -112,9 +112,9 @@ void DoMain() { std::cout << "nq: " << n_q << " n_v: " << n_v << " n_x: " << n_x << std::endl; // Create maps for joints - map pos_map = multibody::makeNameToPositionsMap(plant); - map vel_map = multibody::makeNameToVelocitiesMap(plant); - map act_map = multibody::makeNameToActuatorsMap(plant); + map pos_map = multibody::MakeNameToPositionsMap(plant); + map vel_map = multibody::MakeNameToVelocitiesMap(plant); + map act_map = multibody::MakeNameToActuatorsMap(plant); // Set up contact/distance constraints auto left_toe_pair = LeftToeFront(plant); @@ -314,7 +314,7 @@ void DoMain() { << std::endl; drake::trajectories::PiecewisePolynomial optimal_traj = trajopt.ReconstructStateTrajectory(result); - multibody::connectTrajectoryVisualizer(&plant_vis, &builder, &scene_graph, + multibody::ConnectTrajectoryVisualizer(&plant_vis, &builder, &scene_graph, optimal_traj); DrakeVisualizer::AddToBuilder(&builder, scene_graph); @@ -333,9 +333,9 @@ void setKinematicConstraints(Dircon& trajopt, auto& prog = trajopt.prog(); // Create maps for joints - map pos_map = multibody::makeNameToPositionsMap(plant); - map vel_map = multibody::makeNameToVelocitiesMap(plant); - map act_map = multibody::makeNameToActuatorsMap(plant); + map pos_map = multibody::MakeNameToPositionsMap(plant); + map vel_map = multibody::MakeNameToVelocitiesMap(plant); + map act_map = multibody::MakeNameToActuatorsMap(plant); int n_q = plant.num_positions(); int n_v = plant.num_velocities(); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index df496d5904..6de9455017 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -34,9 +34,8 @@ #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "yaml-cpp/yaml.h" -#include "drake/common/yaml/yaml_read_archive.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -98,7 +97,7 @@ int DoMain(int argc, char* argv[]) { // Built the Cassie MBPs drake::multibody::MultibodyPlant plant(0.0); - addCassieMultibody(&plant, nullptr, true, + AddCassieMultibody(&plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); plant.Finalize(); @@ -114,9 +113,9 @@ int DoMain(int argc, char* argv[]) { int nv = plant.num_velocities(); // Create maps for joints - map pos_map = multibody::makeNameToPositionsMap(plant); - map vel_map = multibody::makeNameToVelocitiesMap(plant); - map act_map = multibody::makeNameToActuatorsMap(plant); + map pos_map = multibody::MakeNameToPositionsMap(plant); + map vel_map = multibody::MakeNameToVelocitiesMap(plant); + map act_map = multibody::MakeNameToActuatorsMap(plant); std::unordered_map< int, std::vector( @@ -238,8 +237,8 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_loop); // Fix the springs in the dynamics - auto pos_idx_map = multibody::makeNameToPositionsMap(plant); - auto vel_idx_map = multibody::makeNameToVelocitiesMap(plant); + auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); + auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant); auto left_fixed_knee_spring = FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), vel_idx_map.at("knee_joint_leftdot"), 0); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index dc3eeff7e6..a90af13477 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -3,7 +3,6 @@ #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" -#include "examples/Cassie/systems/simulator_drift.h" #include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/osc_walking_gains.h" @@ -161,11 +160,6 @@ int DoMain(int argc, char* argv[]) { // Note that we didn't add drift to yaw angle here because it requires // changing SimulatorDrift. - auto simulator_drift = - builder.AddSystem(plant_w_spr, drift_mean, drift_cov); - builder.Connect(state_receiver->get_output_port(0), - simulator_drift->get_input_port_state()); - // Create human high-level control Eigen::Vector2d global_target_position(gains.global_target_position_x, gains.global_target_position_y); @@ -201,7 +195,7 @@ int DoMain(int argc, char* argv[]) { // Create heading traj generator auto head_traj_gen = builder.AddSystem( plant_w_spr, context_w_spr.get()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), head_traj_gen->get_state_input_port()); builder.Connect(high_level_command->get_yaw_output_port(), head_traj_gen->get_yaw_input_port()); @@ -227,7 +221,7 @@ int DoMain(int argc, char* argv[]) { } auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), fsm->get_input_port_state()); // Create leafsystem that record the switching time of the FSM @@ -239,7 +233,7 @@ int DoMain(int argc, char* argv[]) { liftoff_event_time->set_name("liftoff_time"); builder.Connect(fsm->get_output_port(0), liftoff_event_time->get_input_port_fsm()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), liftoff_event_time->get_input_port_state()); std::vector double_support_states = {post_left_double_support_state, post_right_double_support_state}; @@ -249,7 +243,7 @@ int DoMain(int argc, char* argv[]) { touchdown_event_time->set_name("touchdown_time"); builder.Connect(fsm->get_output_port(0), touchdown_event_time->get_input_port_fsm()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), touchdown_event_time->get_input_port_state()); // Create CoM trajectory generator @@ -285,7 +279,7 @@ int DoMain(int argc, char* argv[]) { lipm_traj_generator->get_input_port_fsm()); builder.Connect(touchdown_event_time->get_output_port_event_time(), lipm_traj_generator->get_input_port_touchdown_time()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), lipm_traj_generator->get_input_port_state()); // We can use the same desired_com_height for pelvis_traj_generator as we use @@ -301,7 +295,7 @@ int DoMain(int argc, char* argv[]) { pelvis_traj_generator->get_input_port_fsm()); builder.Connect(touchdown_event_time->get_output_port_event_time(), pelvis_traj_generator->get_input_port_touchdown_time()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), pelvis_traj_generator->get_input_port_state()); // Create velocity control by foot placement @@ -313,7 +307,7 @@ int DoMain(int argc, char* argv[]) { left_support_duration, 0, wrt_com_in_local_frame); builder.Connect(high_level_command->get_xy_output_port(), walking_speed_control->get_input_port_des_hor_vel()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), walking_speed_control->get_input_port_state()); builder.Connect(lipm_traj_generator->get_output_port_lipm_from_current(), walking_speed_control->get_input_port_com()); @@ -345,7 +339,7 @@ int DoMain(int argc, char* argv[]) { swing_ft_traj_generator->get_input_port_fsm()); builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), swing_ft_traj_generator->get_input_port_fsm_switch_time()); - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), swing_ft_traj_generator->get_input_port_state()); builder.Connect(lipm_traj_generator->get_output_port_lipm_from_current(), swing_ft_traj_generator->get_input_port_com()); @@ -588,7 +582,7 @@ int DoMain(int argc, char* argv[]) { // Build OSC problem osc->Build(); // Connect ports - builder.Connect(simulator_drift->get_output_port(0), + builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); builder.Connect(fsm->get_output_port(0), osc->get_fsm_input_port()); if (use_pelvis_for_lipm_tracking) { diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index aa8d8e9e13..c2458571cf 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -3,14 +3,14 @@ #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" -#include "examples/Cassie/systems/simulator_drift.h" -#include "examples/Cassie/osc/hip_yaw_traj_gen.h" #include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" +#include "examples/Cassie/osc/hip_yaw_traj_gen.h" #include "examples/Cassie/osc/osc_walking_gains_alip.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" -#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" #include "examples/Cassie/systems/cassie_out_to_radio.h" +#include "examples/Cassie/systems/simulator_drift.h" +#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" @@ -21,12 +21,13 @@ #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/options_tracking_data.h" +#include "systems/controllers/osc/osc_gains.h" #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/controllers/time_based_fsm.h" -#include "systems/framework/lcm_driven_loop.h" #include "systems/filters/floating_base_velocity_filter.h" +#include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "drake/common/yaml/yaml_io.h" @@ -79,8 +80,8 @@ DEFINE_bool(use_radio, false, DEFINE_string( cassie_out_channel, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); -DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", - "Filepath containing gains"); +DEFINE_string(osc_walking_gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", + "Filepath containing osc_walking_gains"); DEFINE_string(osqp_settings, "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml", "Filepath containing qp settings"); DEFINE_bool(publish_osc_data, true, @@ -100,7 +101,11 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Read-in the parameters - auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + OSCGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osc_walking_gains_filename), {}, {}, yaml_options); + OSCWalkingGainsALIP osc_walking_gains = drake::yaml::LoadYamlFile(FLAGS_osc_walking_gains_filename); // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); @@ -132,7 +137,7 @@ int DoMain(int argc, char* argv[]) { // Get body frames and points Vector3d center_of_pressure = left_heel.first + - gains.contact_point_pos * (left_toe.first - left_heel.first); + osc_walking_gains.contact_point_pos * (left_toe.first - left_heel.first); auto left_toe_mid = std::pair&>( center_of_pressure, plant_w_spr.GetFrameByName("toe_left")); auto right_toe_mid = std::pair&>( @@ -147,7 +152,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant_w_spr); auto pelvis_filt = builder.AddSystem( - plant_w_spr, gains.pelvis_xyz_vel_filter_tau); + plant_w_spr, osc_walking_gains.pelvis_xyz_vel_filter_tau); builder.Connect(*state_receiver, *pelvis_filt); if (FLAGS_publish_filtered_state) { @@ -186,19 +191,16 @@ int DoMain(int argc, char* argv[]) { builder.Connect(pelvis_filt->get_output_port(0), simulator_drift->get_input_port_state()); - auto cassie_out_to_radio = - builder.AddSystem(); - // Create human high-level control - Eigen::Vector2d global_target_position(gains.global_target_position_x, - gains.global_target_position_y); - Eigen::Vector2d params_of_no_turning(gains.yaw_deadband_blur, - gains.yaw_deadband_radius); + Eigen::Vector2d global_target_position(osc_walking_gains.global_target_position_x, + osc_walking_gains.global_target_position_y); + Eigen::Vector2d params_of_no_turning(osc_walking_gains.yaw_deadband_blur, + osc_walking_gains.yaw_deadband_radius); cassie::osc::HighLevelCommand* high_level_command; if (FLAGS_use_radio) { high_level_command = builder.AddSystem( - plant_w_spr, context_w_spr.get(), gains.vel_scale_rot, - gains.vel_scale_trans_sagital, gains.vel_scale_trans_lateral, 0.4); + plant_w_spr, context_w_spr.get(), osc_walking_gains.vel_scale_rot, + osc_walking_gains.vel_scale_trans_sagital, osc_walking_gains.vel_scale_trans_lateral, 0.4); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); @@ -208,10 +210,10 @@ int DoMain(int argc, char* argv[]) { high_level_command->get_radio_input_port()); } else { high_level_command = builder.AddSystem( - plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, - gains.vel_max_yaw, gains.kp_pos_sagital, gains.kd_pos_sagital, - gains.vel_max_sagital, gains.kp_pos_lateral, gains.kd_pos_lateral, - gains.vel_max_lateral, gains.target_pos_offset, global_target_position, + plant_w_spr, context_w_spr.get(), osc_walking_gains.kp_yaw, osc_walking_gains.kd_yaw, + osc_walking_gains.vel_max_yaw, osc_walking_gains.kp_pos_sagital, osc_walking_gains.kd_pos_sagital, + osc_walking_gains.vel_max_sagital, osc_walking_gains.kp_pos_lateral, osc_walking_gains.kd_pos_lateral, + osc_walking_gains.vel_max_lateral, osc_walking_gains.target_pos_offset, global_target_position, params_of_no_turning); } builder.Connect(pelvis_filt->get_output_port(0), @@ -230,9 +232,9 @@ int DoMain(int argc, char* argv[]) { int right_stance_state = 1; int post_left_double_support_state = 3; int post_right_double_support_state = 4; - double left_support_duration = gains.ss_time; - double right_support_duration = gains.ss_time; - double double_support_duration = gains.ds_time; + double left_support_duration = osc_walking_gains.ss_time; + double right_support_duration = osc_walking_gains.ss_time; + double double_support_duration = osc_walking_gains.ds_time; vector fsm_states; vector state_durations; if (FLAGS_is_two_phase) { @@ -240,12 +242,13 @@ int DoMain(int argc, char* argv[]) { state_durations = {left_support_duration, right_support_duration}; } else { fsm_states = {left_stance_state, post_left_double_support_state, - right_stance_state, post_right_double_support_state}; + right_stance_state, post_right_double_support_state, + left_stance_state}; state_durations = {left_support_duration, double_support_duration, - right_support_duration, double_support_duration}; + right_support_duration, double_support_duration, 0.0}; } auto fsm = builder.AddSystem( - plant_w_spr, fsm_states, state_durations, 0.0, gains.impact_threshold); + plant_w_spr, fsm_states, state_durations, 0.0, osc_gains.impact_threshold); builder.Connect(simulator_drift->get_output_port(0), fsm->get_input_port_state()); @@ -274,7 +277,7 @@ int DoMain(int argc, char* argv[]) { // Create CoM trajectory generator // Note that we are tracking COM acceleration instead of position and velocity // because we construct the LIPM traj which starts from the current state - double desired_com_height = gains.lipm_height; + double desired_com_height = osc_walking_gains.lipm_height; vector unordered_fsm_states; vector unordered_state_durations; vector&>>> @@ -299,8 +302,8 @@ int DoMain(int argc, char* argv[]) { auto alip_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), desired_com_height, unordered_fsm_states, unordered_state_durations, - contact_points_in_each_state, gains.Q_alip_kalman_filter.asDiagonal(), - gains.R_alip_kalman_filter.asDiagonal()); + contact_points_in_each_state, osc_walking_gains.Q_alip_kalman_filter.asDiagonal(), + osc_walking_gains.R_alip_kalman_filter.asDiagonal()); builder.Connect(fsm->get_output_port(0), alip_traj_generator->get_input_port_fsm()); @@ -326,10 +329,10 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, context_w_spr.get(), left_right_support_fsm_states, left_right_support_state_durations, left_right_foot, "pelvis", - double_support_duration, gains.mid_foot_height, - gains.final_foot_height, gains.final_foot_velocity_z, - gains.max_CoM_to_footstep_dist, gains.footstep_offset, - gains.center_line_offset); + double_support_duration, osc_walking_gains.mid_foot_height, + osc_walking_gains.final_foot_height, osc_walking_gains.final_foot_velocity_z, + osc_walking_gains.max_CoM_to_footstep_dist, osc_walking_gains.footstep_offset, + osc_walking_gains.center_line_offset); builder.Connect(fsm->get_output_port(0), swing_ft_traj_generator->get_input_port_fsm()); builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), @@ -368,13 +371,13 @@ int DoMain(int argc, char* argv[]) { // Cost int n_v = plant_w_spr.num_velocities(); int n_u = plant_w_spr.num_actuators(); - MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); + MatrixXd Q_accel = osc_walking_gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); -// osc->SetLambdaContactRegularizationWeight(1e-4 * -// gains.W_lambda_c_regularization); -// osc->SetLambdaHolonomicRegularizationWeight(1e-5 * -// gains.W_lambda_h_regularization); - osc->SetInputSmoothingWeights(gains.w_input_reg * + osc->SetLambdaContactRegularizationWeight(1e-4 * + osc_walking_gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + osc_walking_gains.W_lambda_h_regularization); + osc->SetInputSmoothingWeights(osc_walking_gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Constraints in OSC @@ -416,9 +419,9 @@ int DoMain(int argc, char* argv[]) { // Soft constraint // w_contact_relax shouldn't be too big, cause we want tracking error to be // important - osc->SetSoftConstraintWeight(gains.w_soft_constraint); + osc->SetSoftConstraintWeight(osc_walking_gains.w_soft_constraint); // Friction coefficient - osc->SetContactFriction(gains.mu); + osc->SetContactFriction(osc_walking_gains.mu); // Add contact points (The position doesn't matter. It's not used in OSC) const auto& pelvis = plant_w_spr.GetBodyByName("pelvis"); multibody::WorldYawViewFrame view_frame(pelvis); @@ -479,35 +482,35 @@ int DoMain(int argc, char* argv[]) { swing_ft_accel_gain_multiplier_samples); auto swing_foot_data = std::make_unique ( - "swing_ft_data", gains.K_p_swing_foot, gains.K_d_swing_foot, - gains.W_swing_foot, plant_w_spr, plant_w_spr); + "swing_ft_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr); swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); swing_foot_data->SetImpactInvariantProjection(true); auto vel_map = MakeNameToVelocitiesMap(plant_w_spr); - swing_foot_data.AddJointAndStateToIgnoreInJacobian( + swing_foot_data->AddJointAndStateToIgnoreInJacobian( vel_map["hip_yaw_right"], left_stance_state); - swing_foot_data.AddJointAndStateToIgnoreInJacobian( + swing_foot_data->AddJointAndStateToIgnoreInJacobian( vel_map["hip_yaw_left"], right_stance_state); - auto com_data = std::make_unique ("com_data", gains.K_p_swing_foot, - gains.K_d_swing_foot, gains.W_swing_foot, + auto com_data = std::make_unique ("com_data", osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); // com_data->SetImpactInvariantProjection(true); auto swing_ft_traj_local = std::make_unique ( - "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, - gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), + "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), com_data.get()); WorldYawViewFrame pelvis_view_frame(plant_w_spr.GetBodyByName("pelvis")); swing_ft_traj_local->SetViewFrame(pelvis_view_frame); auto swing_ft_traj_global = std::make_unique ( - "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, - gains.W_swing_foot, plant_w_spr, plant_w_spr); + "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr); swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); @@ -522,8 +525,8 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(swing_ft_traj_local)); - auto center_of_mass_traj = std::make_unique ("alip_com_traj", gains.K_p_com, - gains.K_d_com, gains.W_com, plant_w_spr, + auto center_of_mass_traj = std::make_unique ("alip_com_traj", osc_walking_gains.K_p_com, + osc_walking_gains.K_d_com, osc_walking_gains.W_com, plant_w_spr, plant_w_spr); // FiniteStatesToTrack cannot be empty center_of_mass_traj->AddFiniteStateToTrack(-1); @@ -531,27 +534,27 @@ int DoMain(int argc, char* argv[]) { // Pelvis rotation tracking (pitch and roll) auto pelvis_balance_traj = std::make_unique ( - "pelvis_balance_traj", gains.K_p_pelvis_balance, gains.K_d_pelvis_balance, - gains.W_pelvis_balance, plant_w_spr, plant_w_spr); + "pelvis_balance_traj", osc_walking_gains.K_p_pelvis_balance, osc_walking_gains.K_d_pelvis_balance, + osc_walking_gains.W_pelvis_balance, plant_w_spr, plant_w_spr); pelvis_balance_traj->AddFrameToTrack("pelvis"); pelvis_balance_traj->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) auto pelvis_heading_traj = std::make_unique ( - "pelvis_heading_traj", gains.K_p_pelvis_heading, gains.K_d_pelvis_heading, - gains.W_pelvis_heading, plant_w_spr, plant_w_spr); + "pelvis_heading_traj", osc_walking_gains.K_p_pelvis_heading, osc_walking_gains.K_d_pelvis_heading, + osc_walking_gains.W_pelvis_heading, plant_w_spr, plant_w_spr); pelvis_heading_traj->AddFrameToTrack("pelvis"); pelvis_heading_traj->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_heading_traj), - gains.period_of_no_heading_control); + osc_walking_gains.period_of_no_heading_control); // Swing toe joint tracking auto swing_toe_traj_left = std::make_unique ( - "left_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, - gains.W_swing_toe, plant_w_spr, plant_w_spr); + "left_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, + osc_walking_gains.W_swing_toe, plant_w_spr, plant_w_spr); auto swing_toe_traj_right = std::make_unique ( - "right_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, - gains.W_swing_toe, plant_w_spr, plant_w_spr); + "right_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, + osc_walking_gains.W_swing_toe, plant_w_spr, plant_w_spr); swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", "toe_rightdot"); swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", @@ -565,22 +568,21 @@ int DoMain(int argc, char* argv[]) { // Swing hip yaw joint tracking auto swing_hip_yaw_traj = std::make_unique ( - "swing_hip_yaw_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, - gains.W_hip_yaw, plant_w_spr, plant_w_spr); + "swing_hip_yaw_traj", osc_walking_gains.K_p_hip_yaw, osc_walking_gains.K_d_hip_yaw, + osc_walking_gains.W_hip_yaw, plant_w_spr, plant_w_spr); swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", "hip_yaw_rightdot"); swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", "hip_yaw_leftdot"); - osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); if (FLAGS_use_radio) { builder.Connect(cassie_out_to_radio->get_output_port(), hip_yaw_traj_gen->get_radio_input_port()); builder.Connect(fsm->get_output_port_fsm(), hip_yaw_traj_gen->get_fsm_input_port()); - osc->AddTrackingData(&swing_hip_yaw_traj); + osc->AddTrackingData(std::move(swing_hip_yaw_traj)); } else { - osc->AddConstTrackingData(&swing_hip_yaw_traj, VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); } // Set double support duration for force blending @@ -588,8 +590,7 @@ int DoMain(int argc, char* argv[]) { double_support_duration, left_stance_state, right_stance_state, {post_left_double_support_state, post_right_double_support_state}); -// osc->SetOsqpSolverOptionsFromYaml( -// "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml"); + osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 5cb0c47105..bbeb76e64a 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -8,7 +8,6 @@ cc_library( srcs = [], deps = [ ":affine_controller", - ":geared_motor", ":cassie_out_to_radio", ":controller_failure_aggregator", ":fsm_event_time", @@ -80,20 +79,6 @@ cc_library( ], ) -cc_library( - name = "geared_motor", - srcs = [ - "geared_motor.cc", - ], - hdrs = [ - "geared_motor.h", - ], - deps = [ - "//systems/framework:vector", - "@drake//:drake_shared_library", - ], -) - cc_library( name = "constrained_lqr_controller", srcs = [ diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index afa6be3e84..33cd342568 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -173,16 +173,6 @@ void OperationalSpaceControl::SetUpDoubleSupportPhaseBlending( ds_states_ = ds_states; } -// Cost methods -void OperationalSpaceControl::AddAccelerationCost( - const std::string& joint_vel_name, double w) { - if (W_joint_accel_.size() == 0) { - W_joint_accel_ = Eigen::MatrixXd::Zero(n_v_, n_v_); - } - int idx = MakeNameToVelocitiesMap(plant_wo_spr_).at(joint_vel_name); - W_joint_accel_(idx, idx) += w; -} - void OperationalSpaceControl::AddInputCostByJointAndFsmState( const std::string& joint_u_name, int fsm, double w) { if (W_input_.size() == 0) { diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index c8a541f205..a82910bb65 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -125,9 +125,9 @@ void OptionsTrackingData::AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, active_fsm_states_.end(), fsm_state) != active_fsm_states_.end()); if (joint_idx_to_ignore_.count(fsm_state)) { - joint_idx_to_ignore_[fsm_state_].push_back(joint_vel_idx); + joint_idx_to_ignore_[fsm_state].push_back(joint_vel_idx); } else { - joint_idx_to_ignore_[fsm_state_] = {joint_vel_idx}; + joint_idx_to_ignore_[fsm_state] = {joint_vel_idx}; } } diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index 268a13b902..a422b93528 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -68,7 +68,7 @@ class OptionsTrackingData : public OscTrackingData { Eigen::VectorXd filtered_ydot_; double tau_ = -1; std::set low_pass_filter_element_idx_; - std::map> joint_idx_to_ignore_; + std::unordered_map> joint_idx_to_ignore_; double last_timestamp_ = -1; }; diff --git a/systems/framework/geared_motor.cc b/systems/framework/geared_motor.cc index 4ec0d7b731..bfc0e3fcfe 100644 --- a/systems/framework/geared_motor.cc +++ b/systems/framework/geared_motor.cc @@ -61,4 +61,4 @@ void GearedMotor::CalcTorqueOutput( } } // namespace systems -} // namespace dairlib +} // namespace dairlib \ No newline at end of file From af8533cd5e0cff761f42809db0f95b5f6742816e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Jun 2022 11:57:58 -0400 Subject: [PATCH 222/758] updating log plotter scripts to reflect naming change --- .../analysis/cassie_plotting_utils.py | 6 ++--- .../pydairlib/analysis/mbp_plotting_utils.py | 24 +++++++++---------- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index a777f518ab..224b7bb273 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -8,7 +8,7 @@ import drake # dairlib python binding imports -from pydairlib.cassie.cassie_utils import addCassieMultibody +from pydairlib.cassie.cassie_utils import AddCassieMultibody # drake imports from pydrake.multibody.plant import AddMultibodyPlantSceneGraph @@ -39,10 +39,10 @@ def make_plant_and_context(floating_base=True, springs=True): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) if (springs): - addCassieMultibody(plant, scene_graph, + AddCassieMultibody(plant, scene_graph, floating_base, cassie_urdf, True, True) else: - addCassieMultibody(plant, scene_graph, + AddCassieMultibody(plant, scene_graph, floating_base, cassie_urdf_no_springs, False, True) plant.Finalize() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 3e9977a3dd..288d6a2d54 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -4,20 +4,20 @@ from pydairlib.common import plot_styler, plotting_utils from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost -from pydairlib.multibody import makeNameToPositionsMap, \ - makeNameToVelocitiesMap, makeNameToActuatorsMap, \ - createStateNameVectorFromMap, createActuatorNameVectorFromMap +from pydairlib.multibody import MakeNameToPositionsMap, \ + MakeNameToVelocitiesMap, MakeNameToActuatorsMap, \ + CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap def make_name_to_mbp_maps(plant): - return makeNameToPositionsMap(plant), \ - makeNameToVelocitiesMap(plant), \ - makeNameToActuatorsMap(plant) + return MakeNameToPositionsMap(plant), \ + MakeNameToVelocitiesMap(plant), \ + MakeNameToActuatorsMap(plant) def make_mbp_name_vectors(plant): - x_names = createStateNameVectorFromMap(plant) - u_names = createActuatorNameVectorFromMap(plant) + x_names = CreateStateNameVectorFromMap(plant) + u_names = CreateActuatorNameVectorFromMap(plant) q_names = x_names[:plant.num_positions()] v_names = x_names[plant.num_positions():] return q_names, v_names, u_names @@ -56,9 +56,9 @@ def process_state_channel(state_data, plant): u = [] v = [] - pos_map = makeNameToPositionsMap(plant) - vel_map = makeNameToVelocitiesMap(plant) - act_map = makeNameToActuatorsMap(plant) + pos_map = MakeNameToPositionsMap(plant) + vel_map = MakeNameToVelocitiesMap(plant) + act_map = MakeNameToActuatorsMap(plant) for msg in state_data: q_temp = [[] for i in range(len(msg.position))] @@ -85,7 +85,7 @@ def process_effort_channel(data, plant): u = [] t = [] - act_map = makeNameToActuatorsMap(plant) + act_map = MakeNameToActuatorsMap(plant) for msg in data: u_temp = [[] for i in range(len(msg.efforts))] for i in range(len(u_temp)): From c9d6a34de406e7764d1e9c9835076d5ecb4f06aa Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Jun 2022 13:54:44 -0400 Subject: [PATCH 223/758] ignoring state in jacobian caused issues --- .../cassie/gym_envs/cassie_gym_test.py | 2 +- .../osc_running_controller_diagram.cc | 22 ++++++++++++------- examples/Cassie/multibody_sim.cc | 2 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 1 + .../Cassie/osc_run/osc_running_gains.yaml | 2 -- examples/Cassie/run_osc_jumping_controller.cc | 2 +- examples/Cassie/run_osc_running_controller.cc | 12 +++++----- .../Cassie/run_osc_standing_controller.cc | 2 +- .../osc/operational_space_control.cc | 14 +++++++++--- 9 files changed, 36 insertions(+), 23 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index f295e42876..af8ab20d47 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains_alip.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 00115bbb48..b54bcf4b7c 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -164,7 +164,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, - osc_running_gains.impact_threshold); + osc_running_gains.impact_threshold, osc_running_gains.impact_tau); auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); @@ -174,19 +174,20 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto failure_aggregator = builder.AddSystem( control_channel_name_, 1); - std::vector tau = {.05, .1, .01}; + std::vector tau = {.05, .01, .01}; auto ekf_filter = builder.AddSystem(plant, tau); /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_running_gains.w_accel * - osc_running_gains.W_acceleration); - osc->SetInputCostWeights(osc_running_gains.w_input * - osc_running_gains.W_input_regularization); - osc->SetLambdaHolonomicRegularizationWeight( - 1e-5 * osc_running_gains.W_lambda_h_regularization); + osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); + osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight(1e-4 * + gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * + gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(osc_running_gains.w_soft_constraint); @@ -347,8 +348,13 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); + left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index c1caa86848..10685e3d9e 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -88,7 +88,7 @@ int do_main(int argc, char* argv[]) { const double time_step = FLAGS_time_stepping ? FLAGS_dt : 0.0; MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8, {0, 0, 1}, 1e4, 1e2); } std::string urdf; diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 464d6bca69..733e652bb5 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -28,6 +28,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 5 impact_threshold: 0.050 +impact_tau: 0.005 landing_delay: 0.000 CoMW: diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 36cfd7454f..7e945594fc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -33,8 +33,6 @@ rest_length: 1.0 stance_duration: 0.20 flight_duration: 0.1 - - w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 55154a4852..9ee9700c7c 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -123,7 +123,7 @@ int DoMain(int argc, char* argv[]) { feet_contact_points = {left_toe, right_toe}; /**** Convert the gains from the yaml struct to Eigen Matrices ****/ - drake::yaml::YamlReadArchive::Options yaml_options; + drake::yaml::LoadYamlOptions yaml_options; yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile( diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 6de9455017..ca984dbaec 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -401,12 +401,12 @@ int DoMain(int argc, char* argv[]) { // vel_map["hip_yaw_rightdot"], left_stance_state); // right_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( // vel_map["hip_yaw_rightdot"], left_touchdown_air_phase); - pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], left_stance_state); - pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], right_stance_state); - pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], left_stance_state); - pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], right_stance_state); - pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], left_stance_state); - pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], right_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], left_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], right_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], left_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], right_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], left_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], right_stance_state); // left_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( // pos_map["hip_pitch_left"], right_stance_state); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 8c58691642..e878289563 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -107,7 +107,7 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // auto osc_gains = // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); - drake::yaml::YamlReadArchive::Options yaml_options; + drake::yaml::LoadYamlOptions yaml_options; yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_osc_gains_filename), {}, {}, yaml_options); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 33cd342568..6fdb759d57 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -618,10 +618,18 @@ VectorXd OperationalSpaceControl::SolveQp( /// JdotV_c_active + J_c_active*dv == -epsilon /// -> J_c_active*dv + I*epsilon == -JdotV_c_active /// -> [J_c_active, I]* [dv, epsilon]^T == -JdotV_c_active + MatrixXd A_c = MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_); + A_c.block(0, 0, n_c_active_, n_v_) = J_c_active; - A_c.block(0, n_v_, n_c_active_, n_c_active_) = - MatrixXd::Identity(n_c_active_, n_c_active_); + MatrixXd weight = 0.001 * MatrixXd::Identity(n_c_active_, n_c_active_); + weight(0, 0) *= 1e-3; + weight(1, 1) *= 1e-3; + weight(3, 3) *= 1e-3; + weight(4, 4) *= 1e-3; + A_c.block(0, n_v_, n_c_active_, n_c_active_) = weight; +// A_c.block(0, n_v_, n_c_active_, n_c_active_) = +// MatrixXd::Identity(n_c_active_, n_c_active_); contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -1147,7 +1155,7 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (soft_constraint_cost_ > 1e2 || isnan(soft_constraint_cost_)) { + if (soft_constraint_cost_ > 5e2 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } } From 4c2e5c71225849069fb878a037514252f31b8cb6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Jun 2022 14:53:58 -0400 Subject: [PATCH 224/758] updating learning scripts --- bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py | 2 +- bindings/pydairlib/cassie/gym_envs/reward_osudrl.py | 6 +++++- bindings/pydairlib/cassie/learn_osc_gains.py | 7 ++++--- examples/Cassie/osc_run/osc_running_gains.yaml | 2 +- 4 files changed, 11 insertions(+), 6 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 7b815102e1..1023e033e5 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -194,7 +194,7 @@ def step(self, action=np.zeros(18)): next_timestep = self.drake_sim.get_context().get_time() + timestep self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) - action = self.velocity_profile(timestep) + action = self.velocity_profile(next_timestep) self.radio_input_port.FixValue(self.controller_context, action) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp diff --git a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py index 7f68d4855c..45d8eb087d 100644 --- a/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py +++ b/bindings/pydairlib/cassie/gym_envs/reward_osudrl.py @@ -112,6 +112,10 @@ def compute_reward(self, timestep, cassie_env_state, prev_cassie_env_state): height_diff = 0 pelvis_acc = 0.25 * (np.abs(com_angular_velocity.sum())) pelvis_motion = straight_diff + height_diff + pelvis_acc + # print("vel_tracking") + # print(com_vel_error) + # print("pelvis_motion") + # print(pelvis_motion) hip_roll_penalty = np.abs(joint_vel[0]) + np.abs(joint_vel[7]) @@ -119,7 +123,7 @@ def compute_reward(self, timestep, cassie_env_state, prev_cassie_env_state): reward = 0.200 * np.exp(-(com_orient_error + foot_orient_error)) + \ 0.150 * np.exp(-pelvis_motion) + \ - 0.150 * np.exp(-com_vel_error) + \ + 0.250 * np.exp(-com_vel_error) + \ 0.100 * np.exp(-hip_roll_penalty) + \ 0.025 * np.exp(-torque_penalty) diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 22124db572..721b902738 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -95,8 +95,9 @@ def get_single_loss(self, params): else: # print('mujoco') gym_env = MuJoCoCassieGym(self.reward_function, visualize=self.visualize) + gym_env.end_time = self.end_time controller_plant = MultibodyPlant(8e-5) - addCassieMultibody(controller_plant, None, True, self.controller_urdf, False, False) + AddCassieMultibody(controller_plant, None, True, self.controller_urdf, False, False) controller_plant.Finalize() controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, self.osqp_settings) @@ -153,8 +154,8 @@ def learn_gains(self, batch=True): optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) optimizer.learn_gains() - # optimal_params = optimizer.load_params('2022_06_02_11_2000', optimizer.drake_params_folder).value + # optimal_params = optimizer.load_params('2022_06_09_15_500', optimizer.drake_params_folder).value # optimizer.write_params(optimal_params) - # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_2000.npy') + # reward_over_time = np.load('bindings/pydairlib/cassie/optimal_gains/loss_trajectory_500.npy') # plt.plot(reward_over_time) # plt.show() diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 7e945594fc..d0b69d5d08 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -25,7 +25,7 @@ ekf_filter_tau: [0.05, 0.01, 0.01] # High level command gains (with radio) vel_scale_rot: -0.5 -vel_scale_trans_sagital: 1.0 +vel_scale_trans_sagital: 0.25 vel_scale_trans_lateral: -0.15 # SLIP parameters From dc37c4eae832cc9813983f54e5d83a9449c7d928 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Jun 2022 14:51:27 -0400 Subject: [PATCH 225/758] working on variable time fsm --- bindings/pydairlib/cassie/learn_osc_gains.py | 45 +- bindings/pydairlib/cassie/optimizers/ppo.py | 586 ++++++++++++++++++ .../osc_run/learned_osc_running_gains.yaml | 40 +- .../variable_time_fsm.cc | 115 ++++ .../variable_time_fsm.h | 59 ++ 5 files changed, 823 insertions(+), 22 deletions(-) create mode 100644 bindings/pydairlib/cassie/optimizers/ppo.py create mode 100644 examples/impact_invariant_control/variable_time_fsm.cc create mode 100644 examples/impact_invariant_control/variable_time_fsm.h diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index 721b902738..f4aaaa82d1 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -24,7 +24,7 @@ def __init__(self, budget, reward_function, visualize=False): self.budget = budget self.total_loss = 0 self.reward_function = reward_function - self.end_time = 5.0 + self.end_time = 10.0 self.gym_env = None self.sim = None self.controller = None @@ -144,6 +144,46 @@ def learn_gains(self, batch=True): np.save(self.drake_params_folder + 'loss_trajectory_' + str(self.budget), loss_samples) self.save_params(self.drake_params_folder, params, budget) + def learn_gains_apex(self): + from optimizers.ppo import run_experiment + import argparse + parser = argparse.ArgumentParser() + + # general args + parser.add_argument("--logdir", type=str, default="./trained_models/ppo/") # Where to log diagnostics to + parser.add_argument("--seed", default=0, type=int) # Sets Gym, PyTorch and Numpy seeds + parser.add_argument("--history", default=0, type=int) # number of previous states to use as input + parser.add_argument("--redis_address", type=str, default=None) # address of redis server (for cluster setups) + parser.add_argument("--viz_port", default=8097) # (deprecated) visdom server port + + # PPO algo args + parser.add_argument("--input_norm_steps", type=int, default=10000) + parser.add_argument("--n_itr", type=int, default=10000, help="Number of iterations of the learning algorithm") + parser.add_argument("--lr", type=float, default=1e-4, help="Adam learning rate") # Xie + parser.add_argument("--eps", type=float, default=1e-5, help="Adam epsilon (for numerical stability)") + parser.add_argument("--lam", type=float, default=0.95, help="Generalized advantage estimate discount") + parser.add_argument("--gamma", type=float, default=0.99, help="MDP discount") + parser.add_argument("--anneal", default=1.0, action='store_true', help="anneal rate for stddev") + parser.add_argument("--learn_stddev", default=False, action='store_true', help="learn std_dev or keep it fixed") + parser.add_argument("--std_dev", type=int, default=-1.5, help="exponent of exploration std_dev") + parser.add_argument("--entropy_coeff", type=float, default=0.0, help="Coefficient for entropy regularization") + parser.add_argument("--clip", type=float, default=0.2, help="Clipping parameter for PPO surrogate loss") + parser.add_argument("--minibatch_size", type=int, default=64, help="Batch size for PPO updates") + parser.add_argument("--epochs", type=int, default=3, help="Number of optimization epochs per PPO update") #Xie + parser.add_argument("--num_steps", type=int, default=5096, help="Number of sampled timesteps per gradient estimate") + parser.add_argument("--use_gae", type=bool, default=True,help="Whether or not to calculate returns using Generalized Advantage Estimation") + parser.add_argument("--num_procs", type=int, default=30, help="Number of threads to train on") + parser.add_argument("--max_grad_norm", type=float, default=0.05, help="Value to clip gradients at.") + parser.add_argument("--max_traj_len", type=int, default=400, help="Max episode horizon") + parser.add_argument("--recurrent", action='store_true') + parser.add_argument("--bounded", type=bool, default=False) + args = parser.parse_args() + + args = parse_previous(args) + + run_experiment(args) + + if __name__ == '__main__': # budget = 2000 @@ -152,7 +192,8 @@ def learn_gains(self, batch=True): reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - optimizer.learn_gains() + # optimizer.learn_gains() + optimizer.learn_gains_apex() # optimal_params = optimizer.load_params('2022_06_09_15_500', optimizer.drake_params_folder).value # optimizer.write_params(optimal_params) diff --git a/bindings/pydairlib/cassie/optimizers/ppo.py b/bindings/pydairlib/cassie/optimizers/ppo.py new file mode 100644 index 0000000000..4b106fe946 --- /dev/null +++ b/bindings/pydairlib/cassie/optimizers/ppo.py @@ -0,0 +1,586 @@ +"""Proximal Policy Optimization (clip objective).""" +from copy import deepcopy + +import torch +import torch.optim as optim +from torch.utils.data.sampler import BatchSampler, SubsetRandomSampler +from torch.distributions import kl_divergence + +from torch.nn.utils.rnn import pad_sequence + +import time + +import numpy as np +import os, sys + +import ray + +import pickle + +class PPOBuffer: + """ + A buffer for storing trajectory data and calculating returns for the policy + and critic updates. + This container is intentionally not optimized w.r.t. to memory allocation + speed because such allocation is almost never a bottleneck for policy + gradient. + + On the other hand, experience buffers are a frequent source of + off-by-one errors and other bugs in policy gradient implementations, so + this code is optimized for clarity and readability, at the expense of being + (very) marginally slower than some other implementations. + (Premature optimization is the root of all evil). + """ + def __init__(self, gamma=0.99, lam=0.95, use_gae=False): + self.states = [] + self.actions = [] + self.rewards = [] + self.values = [] + self.returns = [] + + self.ep_returns = [] # for logging + self.ep_lens = [] + + self.gamma, self.lam = gamma, lam + + self.ptr = 0 + self.traj_idx = [0] + + def __len__(self): + return len(self.states) + + def storage_size(self): + return len(self.states) + + def store(self, state, action, reward, value): + """ + Append one timestep of agent-environment interaction to the buffer. + """ + # TODO: make sure these dimensions really make sense + self.states += [state.squeeze(0)] + self.actions += [action.squeeze(0)] + self.rewards += [reward.squeeze(0)] + self.values += [value.squeeze(0)] + + self.ptr += 1 + + def finish_path(self, last_val=None): + self.traj_idx += [self.ptr] + rewards = self.rewards[self.traj_idx[-2]:self.traj_idx[-1]] + + returns = [] + + R = last_val.squeeze(0).copy() # Avoid copy? + for reward in reversed(rewards): + R = self.gamma * R + reward + returns.insert(0, R) # TODO: self.returns.insert(self.path_idx, R) ? + # also technically O(k^2), may be worth just reversing list + # BUG? This is adding copies of R by reference (?) + + self.returns += returns + + self.ep_returns += [np.sum(rewards)] + self.ep_lens += [len(rewards)] + + def get(self): + return( + self.states, + self.actions, + self.returns, + self.values + ) + +class PPO: + def __init__(self, args, save_path): + self.env_name = args['env_name'] + self.gamma = args['gamma'] + self.lam = args['lam'] + self.lr = args['lr'] + self.eps = args['eps'] + self.entropy_coeff = args['entropy_coeff'] + self.clip = args['clip'] + self.minibatch_size = args['minibatch_size'] + self.epochs = args['epochs'] + self.num_steps = args['num_steps'] + self.max_traj_len = args['max_traj_len'] + self.use_gae = args['use_gae'] + self.n_proc = args['num_procs'] + self.grad_clip = args['max_grad_norm'] + self.recurrent = args['recurrent'] + + self.total_steps = 0 + self.highest_reward = -1 + self.limit_cores = 0 + + self.save_path = save_path + + # os.environ['OMP_NUM_THREA DS'] = '1' + # if args['redis_address'] is not None: + # ray.init(num_cpos=self.n_proc, redis_address=args['redis_address']) + # else: + # ray.init(num_cpus=self.n_proc) + + def save(self, policy, critic): + + try: + os.makedirs(self.save_path) + except OSError: + pass + filetype = ".pt" # pytorch model + torch.save(policy, os.path.join(self.save_path, "actor" + filetype)) + torch.save(critic, os.path.join(self.save_path, "critic" + filetype)) + + @ray.remote + @torch.no_grad() + def sample(self, env_fn, policy, critic, min_steps, max_traj_len, deterministic=False, anneal=1.0, term_thresh=0): + """ + Sample at least min_steps number of total timesteps, truncating + trajectories only if they exceed max_traj_len number of timesteps + """ + torch.set_num_threads(1) # By default, PyTorch will use multiple cores to speed up operations. + # This can cause issues when Ray also uses multiple cores, especially on machines + # with a lot of CPUs. I observed a significant speedup when limiting PyTorch + # to a single core - I think it basically stopped ray workers from stepping on each + # other's toes. + + # env = WrapEnv(env_fn) # TODO + env = MuJoCoCassieGym(self.reward_function, visualize=self.visualize) + env.end_time = self.end_time + controller_plant = MultibodyPlant(8e-5) + AddCassieMultibody(controller_plant, None, True, self.controller_urdf, False, False) + controller_plant.Finalize() + controller = OSCRunningControllerFactory(controller_plant, self.osc_running_gains_filename, + self.osqp_settings) + env.make(controller) + + memory = PPOBuffer(self.gamma, self.lam) + + num_steps = 0 + while num_steps < min_steps: + state = torch.Tensor(env.reset()) + + done = False + value = 0 + traj_len = 0 + + if hasattr(policy, 'init_hidden_state'): + policy.init_hidden_state() + + if hasattr(critic, 'init_hidden_state'): + critic.init_hidden_state() + + while not done and traj_len < max_traj_len: + action = policy(state, deterministic=False, anneal=anneal) + value = critic(state) + + next_state, reward, done, _ = env.step(action.numpy(), term_thresh=term_thresh) + + memory.store(state.numpy(), action.numpy(), reward, value.numpy()) + + state = torch.Tensor(next_state) + + traj_len += 1 + num_steps += 1 + + value = critic(state) + memory.finish_path(last_val=(not done) * value.numpy()) + + return memory + + def sample_parallel(self, env_fn, policy, critic, min_steps, max_traj_len, deterministic=False, anneal=1.0, term_thresh=0): + + worker = self.sample + args = (self, env_fn, policy, critic, min_steps // self.n_proc, max_traj_len, deterministic, anneal, term_thresh) + + # Create pool of workers, each getting data for min_steps + workers = [worker.remote(*args) for _ in range(self.n_proc)] + + result = [] + total_steps = 0 + + while total_steps < min_steps: + # get result from a worker + ready_ids, _ = ray.wait(workers, num_returns=1) + + # update result + result.append(ray.get(ready_ids[0])) + + # remove ready_ids from workers (O(n)) but n isn't that big + workers.remove(ready_ids[0]) + + # update total steps + total_steps += len(result[-1]) + + # start a new worker + workers.append(worker.remote(*args)) + + # O(n) + def merge(buffers): + merged = PPOBuffer(self.gamma, self.lam) + for buf in buffers: + offset = len(merged) + + merged.states += buf.states + merged.actions += buf.actions + merged.rewards += buf.rewards + merged.values += buf.values + merged.returns += buf.returns + + merged.ep_returns += buf.ep_returns + merged.ep_lens += buf.ep_lens + + merged.traj_idx += [offset + i for i in buf.traj_idx[1:]] + merged.ptr += buf.ptr + + return merged + + total_buf = merge(result) + + return total_buf + + def sample_parallel_old(self, env_fn, policy, critic, min_steps, max_traj_len, deterministic=False, anneal=1.0): + + result = [] + total_steps = 0 + + real_proc = self.n_proc + if self.limit_cores: + real_proc = 48 - 16*int(np.log2(60 / env_fn().simrate)) + print("limit cores active, using {} cores".format(real_proc)) + args = (self, env_fn, policy, critic, min_steps*self.n_proc // real_proc, max_traj_len, deterministic) + result_ids = [self.sample.remote(*args) for _ in range(real_proc)] + result = ray.get(result_ids) + + # O(n) + def merge(buffers): + merged = PPOBuffer(self.gamma, self.lam) + for buf in buffers: + offset = len(merged) + + merged.states += buf.states + merged.actions += buf.actions + merged.rewards += buf.rewards + merged.values += buf.values + merged.returns += buf.returns + + merged.ep_returns += buf.ep_returns + merged.ep_lens += buf.ep_lens + + merged.traj_idx += [offset + i for i in buf.traj_idx[1:]] + merged.ptr += buf.ptr + + return merged + + total_buf = merge(result) + + return total_buf + + def update_policy(self, obs_batch, action_batch, return_batch, advantage_batch, mask, env_fn, mirror_observation=None, mirror_action=None): + policy = self.policy + critic = self.critic + old_policy = self.old_policy + + values = critic(obs_batch) + pdf = policy.distribution(obs_batch) + + # TODO, move this outside loop? + with torch.no_grad(): + old_pdf = old_policy.distribution(obs_batch) + old_log_probs = old_pdf.log_prob(action_batch).sum(-1, keepdim=True) + + log_probs = pdf.log_prob(action_batch).sum(-1, keepdim=True) + + ratio = (log_probs - old_log_probs).exp() + + cpi_loss = ratio * advantage_batch * mask + clip_loss = ratio.clamp(1.0 - self.clip, 1.0 + self.clip) * advantage_batch * mask + actor_loss = -torch.min(cpi_loss, clip_loss).mean() + + critic_loss = 0.5 * ((return_batch - values) * mask).pow(2).mean() + + entropy_penalty = -(self.entropy_coeff * pdf.entropy() * mask).mean() + + # Mirror Symmetry Loss + if mirror_observation is not None and mirror_action is not None: + env = env_fn() + deterministic_actions = policy(obs_batch) + if env.clock_based: + if self.recurrent: + mir_obs = torch.stack([mirror_observation(obs_batch[i,:,:], env.clock_inds) for i in range(obs_batch.shape[0])]) + mirror_actions = policy(mir_obs) + else: + mir_obs = mirror_observation(obs_batch, env.clock_inds) + mirror_actions = policy(mir_obs) + else: + if self.recurrent: + mirror_actions = policy(mirror_observation(torch.stack([mirror_observation(obs_batch[i,:,:]) for i in range(obs_batch.shape[0])]))) + else: + mirror_actions = policy(mirror_observation(obs_batch)) + mirror_actions = mirror_action(mirror_actions) + mirror_loss = 0.4 * (deterministic_actions - mirror_actions).pow(2).mean() + else: + mirror_loss = 0 + + self.actor_optimizer.zero_grad() + (actor_loss + mirror_loss + entropy_penalty).backward() + + # Clip the gradient norm to prevent "unlucky" minibatches from + # causing pathological updates + torch.nn.utils.clip_grad_norm_(policy.parameters(), self.grad_clip) + self.actor_optimizer.step() + + self.critic_optimizer.zero_grad() + critic_loss.backward() + + # Clip the gradient norm to prevent "unlucky" minibatches from + # causing pathological updates + torch.nn.utils.clip_grad_norm_(critic.parameters(), self.grad_clip) + self.critic_optimizer.step() + + with torch.no_grad(): + kl = kl_divergence(pdf, old_pdf) + + if mirror_observation is not None and mirror_action is not None: + mirror_loss_return = mirror_loss.item() + else: + mirror_loss_return = 0 + return actor_loss.item(), pdf.entropy().mean().item(), critic_loss.item(), ratio.mean().item(), kl.mean().item(), mirror_loss_return + + def train(self, + env_fn, + policy, + critic, + n_itr, + logger=None, anneal_rate=1.0): + + self.old_policy = deepcopy(policy) + self.policy = policy + self.critic = critic + + self.actor_optimizer = optim.Adam(policy.parameters(), lr=self.lr, eps=self.eps) + self.critic_optimizer = optim.Adam(critic.parameters(), lr=self.lr, eps=self.eps) + + start_time = time.time() + + env = env_fn() + obs_mirr, act_mirr = None, None + if hasattr(env, 'mirror_observation'): + if env.clock_based: + obs_mirr = env.mirror_clock_observation + else: + obs_mirr = env.mirror_observation + + if hasattr(env, 'mirror_action'): + act_mirr = env.mirror_action + + curr_anneal = 1.0 + curr_thresh = 0 + start_itr = 0 + ep_counter = 0 + do_term = False + for itr in range(n_itr): + print("********** Iteration {} ************".format(itr)) + + sample_start = time.time() + if self.highest_reward > (2/3)*self.max_traj_len and curr_anneal > 0.5: + curr_anneal *= anneal_rate + if do_term and curr_thresh < 0.35: + curr_thresh = .1 * 1.0006**(itr-start_itr) + batch = self.sample_parallel(env_fn, self.policy, self.critic, self.num_steps, self.max_traj_len, anneal=curr_anneal, term_thresh=curr_thresh) + + print("time elapsed: {:.2f} s".format(time.time() - start_time)) + samp_time = time.time() - sample_start + print("sample time elapsed: {:.2f} s".format(samp_time)) + + observations, actions, returns, values = map(torch.Tensor, batch.get()) + + advantages = returns - values + advantages = (advantages - advantages.mean()) / (advantages.std() + self.eps) + + minibatch_size = self.minibatch_size or advantages.numel() + + print("timesteps in batch: %i" % advantages.numel()) + self.total_steps += advantages.numel() + + self.old_policy.load_state_dict(policy.state_dict()) + + optimizer_start = time.time() + + for epoch in range(self.epochs): + losses = [] + entropies = [] + kls = [] + if self.recurrent: + random_indices = SubsetRandomSampler(range(len(batch.traj_idx)-1)) + sampler = BatchSampler(random_indices, minibatch_size, drop_last=False) + else: + random_indices = SubsetRandomSampler(range(advantages.numel())) + sampler = BatchSampler(random_indices, minibatch_size, drop_last=True) + + for indices in sampler: + if self.recurrent: + obs_batch = [observations[batch.traj_idx[i]:batch.traj_idx[i+1]] for i in indices] + action_batch = [actions[batch.traj_idx[i]:batch.traj_idx[i+1]] for i in indices] + return_batch = [returns[batch.traj_idx[i]:batch.traj_idx[i+1]] for i in indices] + advantage_batch = [advantages[batch.traj_idx[i]:batch.traj_idx[i+1]] for i in indices] + mask = [torch.ones_like(r) for r in return_batch] + + obs_batch = pad_sequence(obs_batch, batch_first=False) + action_batch = pad_sequence(action_batch, batch_first=False) + return_batch = pad_sequence(return_batch, batch_first=False) + advantage_batch = pad_sequence(advantage_batch, batch_first=False) + mask = pad_sequence(mask, batch_first=False) + else: + obs_batch = observations[indices] + action_batch = actions[indices] + return_batch = returns[indices] + advantage_batch = advantages[indices] + mask = 1 + + scalars = self.update_policy(obs_batch, action_batch, return_batch, advantage_batch, mask, env_fn, mirror_observation=obs_mirr, mirror_action=act_mirr) + actor_loss, entropy, critic_loss, ratio, kl, mirror_loss = scalars + + entropies.append(entropy) + kls.append(kl) + losses.append([actor_loss, entropy, critic_loss, ratio, kl, mirror_loss]) + + # TODO: add verbosity arguments to suppress this + print(' '.join(["%g"%x for x in np.mean(losses, axis=0)])) + + # Early stopping + if np.mean(kl) > 0.02: + print("Max kl reached, stopping optimization early.") + break + + opt_time = time.time() - optimizer_start + print("optimizer time elapsed: {:.2f} s".format(opt_time)) + + if np.mean(batch.ep_lens) >= self.max_traj_len * 0.75: + ep_counter += 1 + if do_term == False and ep_counter > 50: + do_term = True + start_itr = itr + + if logger is not None: + evaluate_start = time.time() + test = self.sample_parallel(env_fn, self.policy, self.critic, self.num_steps // 2, self.max_traj_len, deterministic=True) + eval_time = time.time() - evaluate_start + print("evaluate time elapsed: {:.2f} s".format(eval_time)) + + avg_eval_reward = np.mean(test.ep_returns) + avg_batch_reward = np.mean(batch.ep_returns) + avg_ep_len = np.mean(batch.ep_lens) + mean_losses = np.mean(losses, axis=0) + # print("avg eval reward: {:.2f}".format(avg_eval_reward)) + + sys.stdout.write("-" * 37 + "\n") + sys.stdout.write("| %15s | %15s |" % ('Return (test)', avg_eval_reward) + "\n") + sys.stdout.write("| %15s | %15s |" % ('Return (batch)', avg_batch_reward) + "\n") + sys.stdout.write("| %15s | %15s |" % ('Mean Eplen', avg_ep_len) + "\n") + sys.stdout.write("| %15s | %15s |" % ('Mean KL Div', "%8.3g" % kl) + "\n") + sys.stdout.write("| %15s | %15s |" % ('Mean Entropy', "%8.3g" % entropy) + "\n") + sys.stdout.write("-" * 37 + "\n") + sys.stdout.flush() + + entropy = np.mean(entropies) + kl = np.mean(kls) + + logger.add_scalar("Test/Return", avg_eval_reward, itr) + logger.add_scalar("Train/Return", avg_batch_reward, itr) + logger.add_scalar("Train/Mean Eplen", avg_ep_len, itr) + logger.add_scalar("Train/Mean KL Div", kl, itr) + logger.add_scalar("Train/Mean Entropy", entropy, itr) + + logger.add_scalar("Misc/Critic Loss", mean_losses[2], itr) + logger.add_scalar("Misc/Actor Loss", mean_losses[0], itr) + logger.add_scalar("Misc/Mirror Loss", mean_losses[5], itr) + logger.add_scalar("Misc/Timesteps", self.total_steps, itr) + + logger.add_scalar("Misc/Sample Times", samp_time, itr) + logger.add_scalar("Misc/Optimize Times", opt_time, itr) + logger.add_scalar("Misc/Evaluation Times", eval_time, itr) + logger.add_scalar("Misc/Termination Threshold", curr_thresh, itr) + + # TODO: add option for how often to save model + if self.highest_reward < avg_eval_reward: + self.highest_reward = avg_eval_reward + self.save(policy, critic) + +def run_experiment(args): + from util.env import env_factory + from util.log import create_logger + + # wrapper function for creating parallelized envs + env_fn = env_factory(args.env_name, simrate=args.simrate, command_profile=args.command_profile, input_profile=args.input_profile, learn_gains=args.learn_gains, dynamics_randomization=args.dyn_random, reward=args.reward, history=args.history, mirror=args.mirror, ik_baseline=args.ik_baseline, no_delta=args.no_delta, traj=args.traj) + obs_dim = env_fn().observation_space.shape[0] + action_dim = env_fn().action_space.shape[0] + + # Set up Parallelism + os.environ['OMP_NUM_THREADS'] = '1' + if not ray.is_initialized(): + if args.redis_address is not None: + ray.init(num_cpus=args.num_procs, redis_address=args.redis_address) + else: + ray.init(num_cpus=args.num_procs) + + # Set seeds + torch.manual_seed(args.seed) + np.random.seed(args.seed) + + if args.previous is not None: + policy = torch.load(os.path.join(args.previous, "actor.pt")) + critic = torch.load(os.path.join(args.previous, "critic.pt")) + # TODO: add ability to load previous hyperparameters, if this is something that we event want + # with open(args.previous + "experiment.pkl", 'rb') as file: + # args = pickle.loads(file.read()) + print("loaded model from {}".format(args.previous)) + else: + if args.recurrent: + policy = Gaussian_LSTM_Actor(obs_dim, action_dim, fixed_std=np.exp(-2), env_name=args.env_name) + critic = LSTM_V(obs_dim) + else: + if args.learn_stddev: + policy = Gaussian_FF_Actor(obs_dim, action_dim, fixed_std=None, env_name=args.env_name, bounded=args.bounded) + else: + policy = Gaussian_FF_Actor(obs_dim, action_dim, fixed_std=np.exp(args.std_dev), env_name=args.env_name, bounded=args.bounded) + critic = FF_V(obs_dim) + + with torch.no_grad(): + policy.obs_mean, policy.obs_std = map(torch.Tensor, get_normalization_params(iter=args.input_norm_steps, noise_std=1, policy=policy, env_fn=env_fn, procs=args.num_procs)) + critic.obs_mean = policy.obs_mean + critic.obs_std = policy.obs_std + + policy.train() + critic.train() + + print("obs_dim: {}, action_dim: {}".format(obs_dim, action_dim)) + + # create a tensorboard logging object + logger = create_logger(args) + + algo = PPO(args=vars(args), save_path=logger.dir) + + print() + print("Synchronous Distributed Proximal Policy Optimization:") + print(" ├ recurrent: {}".format(args.recurrent)) + print(" ├ run name: {}".format(args.run_name)) + print(" ├ max traj len: {}".format(args.max_traj_len)) + print(" ├ seed: {}".format(args.seed)) + print(" ├ num procs: {}".format(args.num_procs)) + print(" ├ lr: {}".format(args.lr)) + print(" ├ eps: {}".format(args.eps)) + print(" ├ lam: {}".format(args.lam)) + print(" ├ gamma: {}".format(args.gamma)) + print(" ├ learn stddev: {}".format(args.learn_stddev)) + print(" ├ std_dev: {}".format(args.std_dev)) + print(" ├ entropy coeff: {}".format(args.entropy_coeff)) + print(" ├ clip: {}".format(args.clip)) + print(" ├ minibatch size: {}".format(args.minibatch_size)) + print(" ├ epochs: {}".format(args.epochs)) + print(" ├ num steps: {}".format(args.num_steps)) + print(" ├ use gae: {}".format(args.use_gae)) + print(" ├ max grad norm: {}".format(args.max_grad_norm)) + print(" └ max traj len: {}".format(args.max_traj_len)) + print() + + algo.train(env_fn, policy, critic, args.n_itr, logger=logger, anneal_rate=args.anneal) \ No newline at end of file diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 4d84ca7536..4c4603c78b 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,19 +1,19 @@ -FootstepKd: [0.46841073050690146, 0.0, 0.0, 0.0, 0.748560743315644, 0.0, 0.0, 0.0, - 0.44242891152442715] +FootstepKd: [0.24014605123137836, 0.0, 0.0, 0.0, 0.5215537630402741, 0.0, 0.0, 0.0, + 0.10406524421712957] LiftoffSwingFootKd: [5, 0, 0, 0, 5, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, 0, 0, 35] LiftoffSwingFootW: [1, 0, 0, 0, 1, 0, 0, 0, 1] -PelvisKd: [4.948999143556126, 0.0, 0.0, 0.0, 6.5301848218127985, 0.0, 0.0, 0.0, 7.298373841539416] -PelvisKp: [19.100237370072687, 0.0, 0.0, 0.0, 57.36403593132101, 0.0, 0.0, 0.0, 55.648318752411384] -PelvisRotKd: [10.250875681407072, 0.0, 0.0, 0.0, 7.733517734123472, 0.0, 0.0, 0.0, - 3.9099864773828106] +PelvisKd: [3.313929750151991, 0.0, 0.0, 0.0, 7.291707347196438, 0.0, 0.0, 0.0, 9.813500192113974] +PelvisKp: [38.559293759237576, 0.0, 0.0, 0.0, 9.609034361274885, 0.0, 0.0, 0.0, 50.194944722723434] +PelvisRotKd: [12.210892635723313, 0.0, 0.0, 0.0, 5.513701361351321, 0.0, 0.0, 0.0, + 3.756526642513079] PelvisRotKp: [400.0, 0, 0, 0, 200.0, 0, 0, 0, 0.0] PelvisRotW: [5, 0, 0, 0, 1, 0, 0, 0, 5] PelvisW: [0, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [4.511797455205392, 0.0, 0.0, 0.0, 10.116363856408572, 0.0, 0.0, 0.0, - 1.4546311014385775] -SwingFootKp: [132.8249342477374, 0.0, 0.0, 0.0, 113.15628351311878, 0.0, 0.0, 0.0, - 63.12354541559851] +SwingFootKd: [8.052187951590337, 0.0, 0.0, 0.0, 7.941424047902412, 0.0, 0.0, 0.0, + 4.740321014078774] +SwingFootKp: [119.02780136838098, 0.0, 0.0, 0.0, 86.4442874886555, 0.0, 0.0, 0.0, + 68.66666275104173] SwingFootW: [10, 0, 0, 0, 100, 0, 0, 0, 5] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] @@ -22,26 +22,26 @@ W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] ekf_filter_tau: [0.05, 0.01, 0.01] flight_duration: 0.1 -footstep_lateral_offset: 0.006180317224739254 -footstep_sagital_offset: 0.014871427401484165 +footstep_lateral_offset: 0.006256616070335045 +footstep_sagital_offset: 0.08033678283597007 hip_yaw_kd: 1 -hip_yaw_kp: 32.86695254058621 +hip_yaw_kp: 49.45039358599729 impact_tau: 0.05 impact_threshold: 0.1 -mid_foot_height: 0.04035365095366986 -mu: 0.5394085182898759 +mid_foot_height: 0.04698180774188275 +mu: 0.5968077063775069 relative_feet: true relative_pelvis: true -rest_length: 0.9739036240530025 +rest_length: 0.965295603135476 stance_duration: 0.2 swing_toe_kd: 10 swing_toe_kp: 1500 vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 -vel_scale_trans_sagital: 1.0 +vel_scale_trans_sagital: 0.25 w_accel: 0.0001 -w_hip_yaw: 0.875707580415595 +w_hip_yaw: 1.6983797290405045 w_input: 0.0 -w_input_reg: 0.0005387738161234992 -w_soft_constraint: 56.674999872454705 +w_input_reg: 0.00015457437376796958 +w_soft_constraint: 239.7104282566615 w_swing_toe: 1 diff --git a/examples/impact_invariant_control/variable_time_fsm.cc b/examples/impact_invariant_control/variable_time_fsm.cc new file mode 100644 index 0000000000..f9c07abc15 --- /dev/null +++ b/examples/impact_invariant_control/variable_time_fsm.cc @@ -0,0 +1,115 @@ +#include "examples/impact_invariant_control/variable_time_fsm.h" + +using std::cout; +using std::endl; + +using drake::systems::BasicVector; +using drake::systems::Context; +using Eigen::VectorXd; +using std::string; + +namespace dairlib { + +using systems::OutputVector; +using systems::ImpactInfoVector; + +VariableTimeFiniteStateMachine::VariableTimeFiniteStateMachine( + const drake::multibody::MultibodyPlant& plant, + const std::vector& states, const std::vector& state_durations, + double t0, double near_impact_threshold, double tau, BLEND_FUNC blend_func) + : ImpactTimeBasedFiniteStateMachine(plant, states, state_durations, t0), + states_(states), + state_durations_(state_durations), + t0_(t0), + near_impact_threshold_(near_impact_threshold), + blend_func_(blend_func) { + + near_impact_port_ = + this->DeclareVectorOutputPort("near_impact", + ImpactInfoVector(0, 0, 0), + &VariableTimeFiniteStateMachine::CalcNearImpact) + .get_index(); + clock_port_ = this->DeclareVectorOutputPort("clock", + BasicVector(1), + &VariableTimeFiniteStateMachine::CalcClock) + .get_index(); + + // Accumulate the durations to get timestamps + double sum = 0; + DRAKE_DEMAND(states.size() == state_durations.size()); + impact_times_.push_back(0); + impact_states_.push_back(states[0]); + for (int i = 0; i < states.size(); ++i) { + sum += state_durations[i]; + accu_state_durations_.push_back(sum); + if (states[i] >= 2) { + impact_times_.push_back(sum); + impact_states_.push_back(states[i+1]); + } + } + + // std::cout << "Impact times: " << std::endl; + // for(int i = 0; i < impact_times_.size(); ++i){ + // std::cout << impact_times_[i] << std::endl; + // } + + period_ = sum; +} + +double alpha_sigmoid(double t, double tau, double near_impact_threshold) { + double x = (t + near_impact_threshold) / tau; + return exp(x) / (1 + exp(x)); +} + +double alpha_exp(double t, double tau, double near_impact_threshold) { + return 1 - exp(-(t + near_impact_threshold) / tau); +} + +void VariableTimeFiniteStateMachine::CalcNearImpact( + const Context& context, ImpactInfoVector* near_impact) const { + // Read in lcm message time + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto current_time = static_cast(robot_output->get_timestamp()); + + double remainder = fmod(current_time, period_); + + // Assign the blending function ptr + auto alpha_func = blend_func_ == SIGMOID ? &alpha_sigmoid : &alpha_exp; + + near_impact->set_timestamp(current_time); + near_impact->SetCurrentContactMode(0); + near_impact->SetAlpha(0); + // Get current finite state + if (current_time >= t0_) { + for (int i = 0; i < impact_states_.size(); ++i) { + double blend_window = blend_func_ == SIGMOID + ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; + if (abs(remainder - impact_times_[i]) < blend_window) { + if (remainder < impact_times_[i]) { + near_impact->SetAlpha(alpha_func(remainder - impact_times_[i], tau_, + near_impact_threshold_)); + } else { + near_impact->SetAlpha(alpha_func(impact_times_[i] - remainder, tau_, + near_impact_threshold_)); + } + near_impact->SetCurrentContactMode(impact_states_[i]); + break; + } + } + } +} + +void VariableTimeFiniteStateMachine::CalcClock( + const Context& context, BasicVector* clock) const { + // Read in lcm message time + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto current_time = static_cast(robot_output->get_timestamp()); + + double remainder = fmod(current_time, period_); + clock->get_mutable_value()(0) = remainder; +} + +} // namespace dairlib diff --git a/examples/impact_invariant_control/variable_time_fsm.h b/examples/impact_invariant_control/variable_time_fsm.h new file mode 100644 index 0000000000..e89bc01970 --- /dev/null +++ b/examples/impact_invariant_control/variable_time_fsm.h @@ -0,0 +1,59 @@ +#pragma once + +#include + +#include "systems/controllers/time_based_fsm.h" +#include "systems/framework/impact_info_vector.h" +#include "systems/framework/output_vector.h" + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +enum BLEND_FUNC { SIGMOID, EXP }; + +class VariableTimeFiniteStateMachine + : public systems::ImpactTimeBasedFiniteStateMachine { + public: + VariableTimeFiniteStateMachine( + const drake::multibody::MultibodyPlant& plant, + const std::vector& states, + const std::vector& state_durations, double t0 = 0, + double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::OutputPort& get_output_port_fsm() const { + return this->get_output_port(fsm_port_); + } + const drake::systems::OutputPort& get_output_port_clock() const { + return this->get_output_port(clock_port_); + } + const drake::systems::OutputPort& get_output_port_impact() const { + return this->get_output_port(near_impact_port_); + } + + private: + void CalcNearImpact(const drake::systems::Context& context, + systems::ImpactInfoVector* near_impact) const; + void CalcClock(const drake::systems::Context& context, + drake::systems::BasicVector* clock) const; + + int near_impact_port_; + int clock_port_; + + double t0_; + std::vector states_; + std::vector state_durations_; + std::vector accu_state_durations_; + std::vector impact_states_; + std::vector impact_times_; + double period_; + double tau_ = 0.0025; + double near_impact_threshold_; + BLEND_FUNC blend_func_; +}; + +} // namespace dairlib From 7fde8d3f9a8db33d27f0a0b81335156b4b1faec4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Jun 2022 16:27:35 -0400 Subject: [PATCH 226/758] fixing iostream dependency issues --- examples/Cassie/BUILD.bazel | 11 -- examples/Cassie/cassie_fixed_point_solver.cc | 7 +- examples/Cassie/cassie_lcm_driven_loop.h | 1 + examples/Cassie/find_fixed_point.cc | 1 + .../test/cassie_udp_publisher_test.cc | 1 + examples/Cassie/osc/heading_traj_generator.cc | 2 - examples/Cassie/osc/high_level_command.cc | 7 - .../solver_settings/osqp_options_walking.yaml | 2 +- examples/Cassie/osc/standing_com_traj.cc | 3 - examples/Cassie/osc/walking_speed_control.cc | 2 - .../osc_jump/jumping_event_based_fsm.cc | 1 + examples/Cassie/run_controller_switch.cc | 1 + examples/Cassie/run_dircon_jumping.cc | 1 + examples/Cassie/run_dircon_walking.cc | 1 + .../Cassie/run_osc_standing_controller.cc | 3 +- examples/Cassie/run_osc_walking_controller.cc | 3 +- .../Cassie/run_osc_walking_controller_alip.cc | 3 +- examples/Cassie/run_pd_controller.cc | 2 - examples/Cassie/standalone_multibody_sim.cc | 141 ------------------ examples/Cassie/systems/input_supervisor.cc | 1 + .../systems/sim_cassie_sensor_aggregator.cc | 2 - examples/Cassie/test/parse_log_test.cc | 1 + examples/Cassie/visualizer.cc | 2 - examples/PlanarWalker/run_gait_dircon.cc | 1 + .../impact_aware_time_based_fsm.cc | 2 - .../run_dircon_walking.cc | 1 + lcm/dircon_saved_trajectory.cc | 1 + lcm/lcm_trajectory.cc | 1 + multibody/geom_geom_collider.cc | 1 + .../test/kinematic_evaluator_caching_test.cc | 1 + multibody/test/geom_geom_collider_test.cc | 1 + solvers/fast_osqp_solver.cc | 52 +++++-- solvers/optimization_utils.cc | 1 + solvers/osqp_options_default.yaml | 2 +- systems/controllers/alip_swing_ft_traj_gen.cc | 2 - systems/controllers/alip_traj_gen.cc | 8 +- .../controller_failure_aggregator.cc | 2 - .../endeffector_position_controller.cc | 1 + .../endeffector_velocity_controller.cc | 1 + systems/controllers/fsm_event_time.cc | 2 - systems/controllers/lipm_traj_gen.cc | 2 +- .../osc/operational_space_control.cc | 12 +- .../osc/operational_space_control.h | 7 +- systems/controllers/osc/osc_tracking_data.cc | 6 +- .../osc/rot_space_tracking_data.cc | 1 + systems/controllers/pd_config_lcm.cc | 4 +- systems/controllers/swing_ft_traj_gen.cc | 2 - systems/controllers/time_based_fsm.cc | 3 - .../log_parser/test/parse_generic_log_test.cc | 1 + systems/robot_lcm_systems.h | 3 +- .../passive_constrained_pendulum_dircon.cc | 1 + .../trajectory_optimization/hybrid_dircon.cc | 4 +- .../passive_constrained_pendulum_dircon.cc | 1 + systems/vector_scope.cc | 1 + 54 files changed, 82 insertions(+), 245 deletions(-) delete mode 100644 examples/Cassie/standalone_multibody_sim.cc diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index f99f0e0073..e30e881b34 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -181,17 +181,6 @@ cc_binary( ], ) -cc_binary( - name = "standalone_multibody_sim", - srcs = ["standalone_multibody_sim.cc"], - deps = [ - ":cassie_urdf", - ":cassie_utils", - "@drake//:drake_shared_library", - "@gflags", - ], -) - cc_binary( name = "multibody_sim", srcs = ["multibody_sim.cc"], diff --git a/examples/Cassie/cassie_fixed_point_solver.cc b/examples/Cassie/cassie_fixed_point_solver.cc index 04b8229a46..430ed70e27 100644 --- a/examples/Cassie/cassie_fixed_point_solver.cc +++ b/examples/Cassie/cassie_fixed_point_solver.cc @@ -1,4 +1,5 @@ #include "examples/Cassie/cassie_fixed_point_solver.h" +#include #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/kinematic/world_point_evaluator.h" @@ -75,7 +76,6 @@ void CassieFixedPointSolver( auto program = multibody::MultibodyProgram(plant); - std::cout << "N***** " << evaluators.count_active() << std::endl; auto positions_map = multibody::MakeNameToPositionsMap(plant); auto q = program.AddPositionVariables(); @@ -255,10 +255,6 @@ void CassieFixedBaseFixedPointSolver( const auto result = drake::solvers::Solve(program, guess); auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; - std::cout << "Solve time:" << elapsed.count() << std::endl; - - std::cout << to_string(result.get_solution_result()) << std::endl; - std::cout << "Cost:" << result.get_optimal_cost() << std::endl; // Draw final pose if (visualize_model_urdf != "") { @@ -499,7 +495,6 @@ void CassieInitStateSolver( // Snopt settings // program.SetSolverOption(drake::solvers::SnoptSolver::id(), "Print file", // "../snopt_test.out"); - std::cout << "Save log to ../snopt_test.out\n"; program.SetSolverOption(drake::solvers::SnoptSolver::id(), "Verify level", 0); program.SetSolverOption(drake::solvers::SnoptSolver::id(), "Major optimality tolerance", 1e-2); diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index d5f1744bf0..c928540bdf 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -3,6 +3,7 @@ #include #include #include +#include #include "dairlib/lcmt_controller_switch.hpp" diff --git a/examples/Cassie/find_fixed_point.cc b/examples/Cassie/find_fixed_point.cc index 3a925fabac..cd8da78398 100644 --- a/examples/Cassie/find_fixed_point.cc +++ b/examples/Cassie/find_fixed_point.cc @@ -1,4 +1,5 @@ #include +#include #include #include "examples/Cassie/cassie_fixed_point_solver.h" diff --git a/examples/Cassie/networking/test/cassie_udp_publisher_test.cc b/examples/Cassie/networking/test/cassie_udp_publisher_test.cc index e145e14c19..37ce9363d7 100644 --- a/examples/Cassie/networking/test/cassie_udp_publisher_test.cc +++ b/examples/Cassie/networking/test/cassie_udp_publisher_test.cc @@ -1,4 +1,5 @@ #include +#include #include #include "drake/lcm/drake_lcm.h" diff --git a/examples/Cassie/osc/heading_traj_generator.cc b/examples/Cassie/osc/heading_traj_generator.cc index 4baf54d7fa..30bd5af970 100644 --- a/examples/Cassie/osc/heading_traj_generator.cc +++ b/examples/Cassie/osc/heading_traj_generator.cc @@ -6,8 +6,6 @@ #include "multibody/multibody_utils.h" -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index d9f4baf93e..31a57e7386 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -10,8 +10,6 @@ #include "drake/math/quaternion.h" #include "drake/math/saturate.h" -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; @@ -180,11 +178,6 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( // PD position control double des_yaw_vel = kp_yaw_ * heading_error + kd_yaw_ * (-yaw_vel); des_yaw_vel = drake::math::saturate(des_yaw_vel, -vel_max_yaw_, vel_max_yaw_); - /*cout << "desired_yaw= " << desired_yaw << endl; - cout << "approx_pelvis_yaw= " << approx_pelvis_yaw << endl; - cout << "heading_error= " << heading_error << endl; - cout << "des_yaw_vel= " << des_yaw_vel << endl; - cout << "\n";*/ // Convex combination of 0 and desired yaw velocity double weight = 1 / (1 + exp(-params_of_no_turning_(0) * diff --git a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml index d9ca698535..50822be399 100644 --- a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml +++ b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml @@ -10,7 +10,7 @@ linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 3 -verbose: 0 +verbose: 1 scaled_termination: 1 check_termination: 25 warm_start: 1 diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index b3d6fcabfe..7a26b62f73 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -7,9 +7,6 @@ #include "multibody/multibody_utils.h" -using std::cout; -using std::endl; - using Eigen::MatrixXd; using Eigen::Vector2d; using Eigen::Vector3d; diff --git a/examples/Cassie/osc/walking_speed_control.cc b/examples/Cassie/osc/walking_speed_control.cc index 0cc96128e4..87ab17ca48 100644 --- a/examples/Cassie/osc/walking_speed_control.cc +++ b/examples/Cassie/osc/walking_speed_control.cc @@ -8,8 +8,6 @@ #include "drake/math/quaternion.h" -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc index a49c6c1695..0b275cfb1e 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc @@ -1,6 +1,7 @@ #include "examples/Cassie/osc_jump/jumping_event_based_fsm.h" #include +#include #include using dairlib::systems::OutputVector; diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index 3cffa3d095..c5647aa877 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -1,4 +1,5 @@ #include +#include #include diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index c25d38c88e..846e656dee 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -1,6 +1,7 @@ #include #include #include +#include #include #include diff --git a/examples/Cassie/run_dircon_walking.cc b/examples/Cassie/run_dircon_walking.cc index b37cc47118..4f5c14cde4 100644 --- a/examples/Cassie/run_dircon_walking.cc +++ b/examples/Cassie/run_dircon_walking.cc @@ -1,4 +1,5 @@ #include +#include #include #include #include diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 744326e7ee..e8922a510d 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -55,7 +55,6 @@ DEFINE_string(channel_u, "CASSIE_INPUT", DEFINE_string( cassie_out_channel, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); -DEFINE_bool(print_osc, false, "whether to print the osc debug message or not"); DEFINE_double(cost_weight_multiplier, 1.0, "A cosntant times with cost weight of OSC traj tracking"); DEFINE_double(height, .8, "The initial COM height (m)"); @@ -224,7 +223,7 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( plant_w_springs, plant_wo_springs, context_w_spr.get(), - context_wo_spr.get(), false, FLAGS_print_osc, FLAGS_qp_time_limit); + context_wo_spr.get(), false, FLAGS_qp_time_limit); // Distance constraint multibody::KinematicEvaluatorSet evaluators(plant_wo_springs); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index d31dca9f93..db0105acc3 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -79,7 +79,6 @@ DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains.yaml", "Filepath containing gains"); DEFINE_bool(publish_osc_data, true, "whether to publish lcm messages for OscTrackData"); -DEFINE_bool(print_osc, false, "whether to print the osc debug message or not"); DEFINE_bool(is_two_phase, false, "true: only right/left single support" @@ -372,7 +371,7 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true, - FLAGS_print_osc, FLAGS_qp_time_limit); + FLAGS_qp_time_limit); // Cost int n_v = plant_w_spr.num_velocities(); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 91aa95e863..e7e56d5be0 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -83,7 +83,6 @@ DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", "Filepath containing gains"); DEFINE_bool(publish_osc_data, true, "whether to publish lcm messages for OscTrackData"); -DEFINE_bool(print_osc, false, "whether to print the osc debug message or not"); DEFINE_bool(is_two_phase, false, "true: only right/left single support" @@ -358,7 +357,7 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true, - FLAGS_print_osc, FLAGS_qp_time_limit); + FLAGS_qp_time_limit); // Cost int n_v = plant_w_spr.num_velocities(); diff --git a/examples/Cassie/run_pd_controller.cc b/examples/Cassie/run_pd_controller.cc index 1db0a053db..c47c7c836f 100644 --- a/examples/Cassie/run_pd_controller.cc +++ b/examples/Cassie/run_pd_controller.cc @@ -89,8 +89,6 @@ int doMain(int argc, char* argv[]) { builder.Connect(config_receiver->get_output_port(0), controller->get_input_port_config()); - std::cout << controller->get_output_port(0).size() << std::endl; - std::cout << command_sender->get_input_port(0).size() << std::endl; builder.Connect(controller->get_output_port(0), command_sender->get_input_port(0)); diff --git a/examples/Cassie/standalone_multibody_sim.cc b/examples/Cassie/standalone_multibody_sim.cc deleted file mode 100644 index 6e01f77f9b..0000000000 --- a/examples/Cassie/standalone_multibody_sim.cc +++ /dev/null @@ -1,141 +0,0 @@ -#include - -#include -#include "drake/lcm/drake_lcm.h" -#include "drake/geometry/drake_visualizer.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/primitives/constant_vector_source.h" -#include "drake/multibody/tree/revolute_joint.h" -#include "drake/systems/analysis/runge_kutta2_integrator.h" - -#include "multibody/multibody_utils.h" -#include "examples/Cassie/cassie_utils.h" - -namespace dairlib { -using drake::geometry::DrakeVisualizer; -using drake::geometry::HalfSpace; -using drake::geometry::SceneGraph; -using drake::multibody::MultibodyPlant; -using drake::multibody::RevoluteJoint; -using drake::systems::Context; -using drake::systems::DiagramBuilder; -using drake::systems::Simulator; - -// Simulation parameters. -DEFINE_bool(floating_base, true, "Fixed or floating base model"); - -DEFINE_double(target_realtime_rate, 1.0, - "Desired rate relative to real time. See documentation for " - "Simulator::set_target_realtime_rate() for details."); -DEFINE_bool(time_stepping, false, "If 'true', the plant is modeled as a " - "discrete system with periodic updates. " - "If 'false', the plant is modeled as a continuous system."); -DEFINE_double(dt, 1e-4, "The step size to use for compliant, ignored for time_stepping)"); - -int do_main(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - - DiagramBuilder builder; - - SceneGraph& scene_graph = *builder.AddSystem(); - scene_graph.set_name("scene_graph"); - - const double time_step = FLAGS_time_stepping ? FLAGS_dt : 0.0; - - MultibodyPlant& plant = - *builder.AddSystem(time_step); - - if (FLAGS_floating_base) { - multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); - } - - AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base); - - plant.Finalize(); - - std::map actuatorIndexMap = - multibody::MakeNameToActuatorsMap(plant); - - for (auto const& x : actuatorIndexMap) { - std::cout << x.first // string (key) - << ':' - << x.second // string's value - << std::endl; - } - - auto input_source = - builder.AddSystem>( - Eigen::VectorXd::Zero(plant.num_actuators())); - - builder.Connect(input_source->get_output_port(), - plant.get_actuation_input_port()); - - builder.Connect( - plant.get_geometry_poses_output_port(), - scene_graph.get_source_pose_port(plant.get_source_id().value())); - - builder.Connect(scene_graph.get_query_output_port(), - plant.get_geometry_query_input_port()); - - DrakeVisualizer::AddToBuilder(&builder, scene_graph); - - auto diagram = builder.Build(); - - - // Create a context for this system: - std::unique_ptr> diagram_context = - diagram->CreateDefaultContext(); - diagram->SetDefaultContext(diagram_context.get()); - Context& plant_context = - diagram->GetMutableSubsystemContext(plant, diagram_context.get()); - - - plant.GetJointByName("hip_pitch_left"). - set_angle(&plant_context, .269); - plant.GetJointByName("knee_left"). - set_angle(&plant_context, -.644); - plant.GetJointByName("ankle_joint_left"). - set_angle(&plant_context, .792); - plant.GetJointByName("toe_left"). - set_angle(&plant_context, -M_PI/3); - - plant.GetJointByName("hip_pitch_right"). - set_angle(&plant_context, .269); - plant.GetJointByName("knee_right"). - set_angle(&plant_context, -.644); - plant.GetJointByName("ankle_joint_right"). - set_angle(&plant_context, .792); - plant.GetJointByName("toe_right"). - set_angle(&plant_context, -M_PI/3); - - if (FLAGS_floating_base) { - const drake::math::RigidTransformd transform( - drake::math::RotationMatrix(), Eigen::Vector3d(0, 0, 1.2)); - plant.SetFreeBodyPose(&plant_context, plant.GetBodyByName("pelvis"), - transform); - } - - Simulator simulator(*diagram, std::move(diagram_context)); - - if (!FLAGS_time_stepping) { - // simulator.get_mutable_integrator()->set_maximum_step_size(0.01); - // simulator.get_mutable_integrator()->set_target_accuracy(1e-1); - // simulator.get_mutable_integrator()->set_fixed_step_mode(true); - simulator.reset_integrator>( - FLAGS_dt); - } - - simulator.set_target_realtime_rate(FLAGS_target_realtime_rate); - simulator.Initialize(); - simulator.AdvanceTo(std::numeric_limits::infinity()); - - return 0; -} - -} // namespace dairlib - -int main(int argc, char* argv[]) { - return dairlib::do_main(argc, argv); -} diff --git a/examples/Cassie/systems/input_supervisor.cc b/examples/Cassie/systems/input_supervisor.cc index c0d0941fc5..047f6c780d 100644 --- a/examples/Cassie/systems/input_supervisor.cc +++ b/examples/Cassie/systems/input_supervisor.cc @@ -1,6 +1,7 @@ #include "examples/Cassie/systems/input_supervisor.h" #include +#include #include #include "dairlib/lcmt_controller_switch.hpp" diff --git a/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc b/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc index f72f5e4b28..290dde3739 100644 --- a/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc +++ b/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc @@ -10,8 +10,6 @@ using dairlib::systems::TimestampedVector; using Eigen::VectorXd; using drake::systems::Context; using std::map; -using std::cout; -using std::endl; SimCassieSensorAggregator::SimCassieSensorAggregator( const drake::multibody::MultibodyPlant& plant) { diff --git a/examples/Cassie/test/parse_log_test.cc b/examples/Cassie/test/parse_log_test.cc index 4c53ef8f4e..c6fae83d6d 100644 --- a/examples/Cassie/test/parse_log_test.cc +++ b/examples/Cassie/test/parse_log_test.cc @@ -1,4 +1,5 @@ #include "drake/lcm/drake_lcm_log.h" +#include #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_log_playback_system.h" diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 437a75cd46..e78556114a 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -43,8 +43,6 @@ using drake::multibody::UnitInertia; using drake::systems::Simulator; using drake::systems::lcm::LcmSubscriberSystem; using drake::systems::rendering::MultibodyPositionToGeometryPose; -using std::cout; -using std::endl; int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); diff --git a/examples/PlanarWalker/run_gait_dircon.cc b/examples/PlanarWalker/run_gait_dircon.cc index 0f100ff45e..cc0a32266a 100644 --- a/examples/PlanarWalker/run_gait_dircon.cc +++ b/examples/PlanarWalker/run_gait_dircon.cc @@ -1,4 +1,5 @@ #include +#include #include #include diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 4fef6a9e37..1208e67cfc 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -1,7 +1,5 @@ #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" -using std::cout; -using std::endl; using drake::systems::BasicVector; using drake::systems::Context; diff --git a/examples/impact_invariant_control/run_dircon_walking.cc b/examples/impact_invariant_control/run_dircon_walking.cc index f05a4352aa..24d1af030e 100644 --- a/examples/impact_invariant_control/run_dircon_walking.cc +++ b/examples/impact_invariant_control/run_dircon_walking.cc @@ -1,5 +1,6 @@ #include #include +#include #include diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index e01a1d2b5e..aecada4a67 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -1,4 +1,5 @@ #include "dircon_saved_trajectory.h" +#include #include "multibody/multibody_utils.h" diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index 9708dd4c21..6c257b64c9 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include #include #include diff --git a/multibody/geom_geom_collider.cc b/multibody/geom_geom_collider.cc index 4141768725..60d79fe659 100644 --- a/multibody/geom_geom_collider.cc +++ b/multibody/geom_geom_collider.cc @@ -1,4 +1,5 @@ #include "multibody/geom_geom_collider.h" +#include "multibody/geom_geom_collider.h" #include "drake/math/rotation_matrix.h" diff --git a/multibody/kinematic/test/kinematic_evaluator_caching_test.cc b/multibody/kinematic/test/kinematic_evaluator_caching_test.cc index 7dddc0fc3d..43cd3e62fe 100644 --- a/multibody/kinematic/test/kinematic_evaluator_caching_test.cc +++ b/multibody/kinematic/test/kinematic_evaluator_caching_test.cc @@ -1,4 +1,5 @@ #include +#include #include "examples/Cassie/cassie_utils.h" #include "multibody/kinematic/kinematic_evaluator_set.h" diff --git a/multibody/test/geom_geom_collider_test.cc b/multibody/test/geom_geom_collider_test.cc index af5ad25442..bcee569344 100644 --- a/multibody/test/geom_geom_collider_test.cc +++ b/multibody/test/geom_geom_collider_test.cc @@ -1,6 +1,7 @@ #include "multibody/multibody_utils.h" #include "multibody/geom_geom_collider.h" #include "common/find_resource.h" +#include #include "drake/geometry/scene_graph.h" #include "drake/multibody/parsing/parser.h" diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index a5755d4bb2..280c37f6e1 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -39,18 +39,18 @@ void ParseQuadraticCosts(const MathematicalProgram& prog, const std::vector x_indices = prog.FindDecisionVariableIndices(x); // Add quadratic_cost.Q to the Hessian P. - const std::vector> Qi_triplets = - SparseMatrixToTriplets(quadratic_cost.evaluator()->Q()); - P_triplets.reserve(P_triplets.size() + Qi_triplets.size()); - for (int i = 0; i < static_cast(Qi_triplets.size()); ++i) { - // Unpack the field of the triplet (for clarity below). - const int row = x_indices[Qi_triplets[i].row()]; - const int col = x_indices[Qi_triplets[i].col()]; - const double value = Qi_triplets[i].value(); - // Since OSQP 0.6.0 the P matrix is required to be upper triangular, so - // we only add upper triangular entries to P_triplets. - if (row <= col) { - P_triplets.emplace_back(row, col, static_cast(value)); + // Since OSQP 0.6.0 the P matrix is required to be upper triangular, so + // we only add upper triangular entries to P_triplets. + const Eigen::MatrixXd& Q = quadratic_cost.evaluator()->Q(); + for (int col = 0; col < Q.cols(); ++col) { + for (int row = 0; (row <= col) && (row < Q.rows()); ++row) { + const double value = Q(row, col); + if (value == 0.0) { + continue; + } + const int x_row = x_indices[row]; + const int x_col = x_indices[col]; + P_triplets.emplace_back(x_row, x_col, static_cast(value)); } } @@ -62,6 +62,27 @@ void ParseQuadraticCosts(const MathematicalProgram& prog, // Add quadratic_cost.c to constant term *constant_cost_term += quadratic_cost.evaluator()->c(); } + +// // Scale the matrix P in the cost. +// // Note that the linear term is scaled in ParseLinearCosts(). +// const auto& scale_map = prog.GetVariableScaling(); +// if (!scale_map.empty()) { +// for (auto& triplet : P_triplets) { +// // Column +// const auto column = scale_map.find(triplet.col()); +// if (column != scale_map.end()) { +// triplet = Eigen::Triplet(triplet.row(), triplet.col(), +// triplet.value() * (column->second)); +// } +// // Row +// const auto row = scale_map.find(triplet.row()); +// if (row != scale_map.end()) { +// triplet = Eigen::Triplet(triplet.row(), triplet.col(), +// triplet.value() * (row->second)); +// } +// } +// } + P->resize(prog.num_vars(), prog.num_vars()); P->setFromTriplets(P_triplets.begin(), P_triplets.end()); } @@ -111,7 +132,8 @@ void ParseLinearConstraints( const std::vector x_indices = prog.FindDecisionVariableIndices(constraint.variables()); const std::vector> Ai_triplets = - SparseMatrixToTriplets(constraint.evaluator()->A()); + drake::math::SparseMatrixToTriplets( + constraint.evaluator()->get_sparse_A()); const Binding constraint_cast = BindingDynamicCast(constraint); constraint_start_row->emplace(constraint_cast, *num_A_rows); @@ -332,9 +354,7 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, workspace_ = nullptr; const c_int osqp_setup_err = osqp_setup(&workspace_, osqp_data_, osqp_settings_); - if (osqp_setup_err != 0) { - std::cerr << "Error setting up osqp solver."; - } + DRAKE_DEMAND(osqp_setup_err == 0); } void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, diff --git a/solvers/optimization_utils.cc b/solvers/optimization_utils.cc index 691d8ce3c6..ee3d55e6b5 100644 --- a/solvers/optimization_utils.cc +++ b/solvers/optimization_utils.cc @@ -1,4 +1,5 @@ #include "solvers/optimization_utils.h" +#include using Eigen::MatrixXd; using Eigen::VectorXd; diff --git a/solvers/osqp_options_default.yaml b/solvers/osqp_options_default.yaml index 68b6ab24df..e87aadf35b 100644 --- a/solvers/osqp_options_default.yaml +++ b/solvers/osqp_options_default.yaml @@ -10,7 +10,7 @@ linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 3 -verbose: 0 +verbose: 1 scaled_termination: 1 check_termination: 25 warm_start: 1 diff --git a/systems/controllers/alip_swing_ft_traj_gen.cc b/systems/controllers/alip_swing_ft_traj_gen.cc index 710f3eb857..5b754d2c9a 100644 --- a/systems/controllers/alip_swing_ft_traj_gen.cc +++ b/systems/controllers/alip_swing_ft_traj_gen.cc @@ -10,8 +10,6 @@ #include "systems/controllers/control_utils.h" #include "multibody/multibody_utils.h" -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; diff --git a/systems/controllers/alip_traj_gen.cc b/systems/controllers/alip_traj_gen.cc index e694ba9ce3..88dd7e76db 100644 --- a/systems/controllers/alip_traj_gen.cc +++ b/systems/controllers/alip_traj_gen.cc @@ -10,8 +10,6 @@ #include -using std::cout; -using std::endl; using std::string; using std::vector; @@ -331,11 +329,7 @@ int ALIPTrajGenerator::GetModeIdx(int fsm_state) const { unordered_fsm_states_.end(), fsm_state); int mode_index = std::distance(unordered_fsm_states_.begin(), it); - if (it == unordered_fsm_states_.end()) { - cout << "WARNING: fsm state number " << fsm_state - << " doesn't exist in ALIPTrajGenerator\n"; - mode_index = 0; - } + DRAKE_DEMAND(it != unordered_fsm_states_.end()); return mode_index; } diff --git a/systems/controllers/controller_failure_aggregator.cc b/systems/controllers/controller_failure_aggregator.cc index b771d3e86e..cbf26572a4 100644 --- a/systems/controllers/controller_failure_aggregator.cc +++ b/systems/controllers/controller_failure_aggregator.cc @@ -2,8 +2,6 @@ #include -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; diff --git a/systems/controllers/endeffector_position_controller.cc b/systems/controllers/endeffector_position_controller.cc index d3c074a13f..9b15a51528 100644 --- a/systems/controllers/endeffector_position_controller.cc +++ b/systems/controllers/endeffector_position_controller.cc @@ -1,4 +1,5 @@ #include "systems/controllers/endeffector_position_controller.h" +#include namespace dairlib{ namespace systems{ diff --git a/systems/controllers/endeffector_velocity_controller.cc b/systems/controllers/endeffector_velocity_controller.cc index fdd4ba02d1..188c55d867 100644 --- a/systems/controllers/endeffector_velocity_controller.cc +++ b/systems/controllers/endeffector_velocity_controller.cc @@ -1,4 +1,5 @@ #include "systems/controllers/endeffector_velocity_controller.h" +#include namespace dairlib{ namespace systems{ diff --git a/systems/controllers/fsm_event_time.cc b/systems/controllers/fsm_event_time.cc index b5038e317c..d6a1c8f525 100644 --- a/systems/controllers/fsm_event_time.cc +++ b/systems/controllers/fsm_event_time.cc @@ -2,8 +2,6 @@ #include -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; diff --git a/systems/controllers/lipm_traj_gen.cc b/systems/controllers/lipm_traj_gen.cc index 6ad6258be9..2e5d8964e8 100644 --- a/systems/controllers/lipm_traj_gen.cc +++ b/systems/controllers/lipm_traj_gen.cc @@ -2,7 +2,7 @@ #include -#include +#include #include #include diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index ea477c8e2f..7dfda22aac 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1,6 +1,7 @@ #include "systems/controllers/osc/operational_space_control.h" #include +#include #include "common/eigen_utils.h" #include "multibody/multibody_utils.h" @@ -50,7 +51,7 @@ OperationalSpaceControl::OperationalSpaceControl( const MultibodyPlant& plant_wo_spr, drake::systems::Context* context_w_spr, drake::systems::Context* context_wo_spr, - bool used_with_finite_state_machine, bool print_tracking_info, + bool used_with_finite_state_machine, double qp_time_limit) : plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), @@ -59,7 +60,6 @@ OperationalSpaceControl::OperationalSpaceControl( world_w_spr_(plant_w_spr_.world_frame()), world_wo_spr_(plant_wo_spr_.world_frame()), used_with_finite_state_machine_(used_with_finite_state_machine), - print_tracking_info_(print_tracking_info), qp_time_limit_(qp_time_limit) { this->set_name("OSC"); @@ -746,7 +746,10 @@ VectorXd OperationalSpaceControl::SolveQp( } // Solve the QP - const MathematicalProgramResult result = solver_->Solve(*prog_); +// const MathematicalProgramResult result = solver_->Solve(*prog_); + auto osqp_solver = drake::solvers::OsqpSolver(); +// osqp_solver->S + const MathematicalProgramResult result = osqp_solver.Solve(*prog_); solve_time_ = result.get_solver_details().run_time; @@ -954,9 +957,6 @@ void OperationalSpaceControl::CalcOptimalInput( double timestamp = robot_output->get_timestamp(); double current_time = timestamp; - if (print_tracking_info_) { - cout << "\n\ncurrent_time = " << current_time << endl; - } VectorXd x_wo_spr(n_q_ + n_v_); x_wo_spr << map_position_from_spring_to_no_spring_ * q_w_spr, diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 694daa58ad..d831ed4c32 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -5,6 +5,7 @@ #include #include #include +#include #include @@ -100,8 +101,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_wo_spr, drake::systems::Context* context_w_spr, drake::systems::Context* context_wo_spr, - bool used_with_finite_state_machine = true, - bool print_tracking_info = false, double qp_time_limit = 0); + bool used_with_finite_state_machine = true, double qp_time_limit = 0); const drake::systems::OutputPort& get_osc_output_port() const { return this->get_output_port(osc_output_port_); @@ -281,9 +281,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // flag indicating whether using osc with finite state machine or not bool used_with_finite_state_machine_; - // flag indicating whether to print the tracking related values or not - bool print_tracking_info_; - // floating base model flag bool is_quaternion_; diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index 5e9906ae76..17fe03ec0c 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -2,6 +2,7 @@ #include #include +#include #include @@ -111,11 +112,6 @@ void OscTrackingData::StoreYddotCommandSol(const VectorXd& dv) { } void OscTrackingData::AddFiniteStateToTrack(int state) { - // Avoid repeated states - if (active_fsm_states_.count(state)) { - std::cout << "FSM state: " << state << " was already included in " << name_ - << std::endl; - } DRAKE_DEMAND(!active_fsm_states_.count(state)); active_fsm_states_.insert(state); } diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index ff2dd3f1e0..6a4a5fcc6d 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -1,4 +1,5 @@ #include "rot_space_tracking_data.h" +#include using Eigen::Isometry3d; using Eigen::MatrixXd; diff --git a/systems/controllers/pd_config_lcm.cc b/systems/controllers/pd_config_lcm.cc index c08a5654a7..41f225b824 100644 --- a/systems/controllers/pd_config_lcm.cc +++ b/systems/controllers/pd_config_lcm.cc @@ -1,5 +1,6 @@ #include "systems/controllers/pd_config_lcm.h" #include "multibody/multibody_utils.h" +#include namespace dairlib { namespace systems { @@ -62,8 +63,9 @@ PDConfigReceiver::PDConfigReceiver(const MultibodyPlant& plant) { index_q = k; } } - if (index_q != -1) + if (index_q != -1){ actuatorToPositionIndexMap_[j] = index_q; + } std::cout << "Map u_ind:" << j << " q_ind: " << index_q << " v_ind: " << index << std::endl; } diff --git a/systems/controllers/swing_ft_traj_gen.cc b/systems/controllers/swing_ft_traj_gen.cc index e698f1ef47..9020d1288f 100644 --- a/systems/controllers/swing_ft_traj_gen.cc +++ b/systems/controllers/swing_ft_traj_gen.cc @@ -9,8 +9,6 @@ #include #include "systems/controllers/control_utils.h" -using std::cout; -using std::endl; using std::string; using Eigen::MatrixXd; diff --git a/systems/controllers/time_based_fsm.cc b/systems/controllers/time_based_fsm.cc index 009d830208..fc169b378a 100644 --- a/systems/controllers/time_based_fsm.cc +++ b/systems/controllers/time_based_fsm.cc @@ -2,9 +2,6 @@ #include "dairlib/lcmt_target_standing_height.hpp" -using std::cout; -using std::endl; - using drake::systems::Context; using drake::systems::DiscreteUpdateEvent; using drake::systems::DiscreteValues; diff --git a/systems/log_parser/test/parse_generic_log_test.cc b/systems/log_parser/test/parse_generic_log_test.cc index bda0f63213..db37ed6e5e 100644 --- a/systems/log_parser/test/parse_generic_log_test.cc +++ b/systems/log_parser/test/parse_generic_log_test.cc @@ -1,4 +1,5 @@ #include +#include #include "systems/log_parser/generic_lcm_log_parser.h" #include "examples/Cassie/cassie_utils.h" #include "systems/robot_lcm_systems.h" diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 74f384f2d7..18c7e07e81 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -52,8 +52,7 @@ class RobotOutputSender : public drake::systems::LeafSystem { } const drake::systems::InputPort& get_input_port_effort() const { - if(!publish_efforts_) - std::cerr << "RobotOutputSender not configured to publish efforts." << std::endl; + DRAKE_DEMAND(publish_efforts_); return this->get_input_port(effort_input_port_); } diff --git a/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc index 2258d9c89f..e7f519360b 100644 --- a/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc @@ -4,6 +4,7 @@ #include #include +#include #include diff --git a/systems/trajectory_optimization/hybrid_dircon.cc b/systems/trajectory_optimization/hybrid_dircon.cc index 86cacb66e8..25efaff47e 100644 --- a/systems/trajectory_optimization/hybrid_dircon.cc +++ b/systems/trajectory_optimization/hybrid_dircon.cc @@ -4,6 +4,7 @@ #include #include #include +#include #include "multibody/multibody_utils.h" @@ -310,9 +311,6 @@ VectorXDecisionVariable HybridDircon::state_vars_by_mode( VectorXDecisionVariable ret(num_states()); return x_vars().segment((mode_start_[mode] + time_index) * num_states(), num_states()); - // std::cout << Eigen::VectorBlock(ret, 0, - // num_states()) << std::endl; return - // Eigen::VectorBlock(ret, 0, num_states()); } } diff --git a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc index eef8d1709e..e5d3dcebc0 100644 --- a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc @@ -1,4 +1,5 @@ #include +#include #include #include diff --git a/systems/vector_scope.cc b/systems/vector_scope.cc index 9988b9f62e..7b6322122b 100644 --- a/systems/vector_scope.cc +++ b/systems/vector_scope.cc @@ -5,6 +5,7 @@ #include "drake/systems/framework/basic_vector.h" #include "drake/systems/framework/event.h" #include "systems/vector_scope.h" +#include namespace dairlib { namespace systems { From ebc1f471174eedefed674ae249b95d58dc999455 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Jun 2022 16:43:45 -0400 Subject: [PATCH 227/758] working on fixing qp solver --- examples/Cassie/closed_loop_running_sim.cc | 1 + examples/Cassie/diagrams/cassie_sim_diagram.cc | 1 + examples/Cassie/multibody_sim.cc | 3 --- lcm/lcm_trajectory.h | 1 + .../osc/operational_space_control.cc | 6 +++--- .../osc/trans_space_tracking_data.cc | 17 +++++++++-------- 6 files changed, 15 insertions(+), 14 deletions(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index ca71363601..0f9419596c 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -1,5 +1,6 @@ #include #include +#include #include "dairlib/lcmt_pd_config.hpp" #include "dairlib/lcmt_robot_input.hpp" diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index e079265974..7798c1633e 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -3,6 +3,7 @@ #include #include +#include #include "dairlib/lcmt_cassie_out.hpp" #include "dairlib/lcmt_robot_input.hpp" diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 10685e3d9e..eea8cc14ff 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -215,9 +215,6 @@ int do_main(int argc, char* argv[]) { plant.SetPositions(&plant_context, q_init); plant.SetVelocities(&plant_context, VectorXd::Zero(plant.num_velocities())); VectorXd x = plant.GetPositionsAndVelocities(plant_context); - const static Eigen::IOFormat CSVFormat(Eigen::StreamPrecision, - Eigen::DontAlignCols, ", ", "\n"); - std::cout << "x_init: " << x.transpose().format(CSVFormat) << std::endl; diagram_context->SetTime(FLAGS_start_time); Simulator simulator(*diagram, std::move(diagram_context)); diff --git a/lcm/lcm_trajectory.h b/lcm/lcm_trajectory.h index bff1ab5fa9..d2cd1b8167 100644 --- a/lcm/lcm_trajectory.h +++ b/lcm/lcm_trajectory.h @@ -3,6 +3,7 @@ #include #include #include +#include #include diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index e1778c5777..54e7da6509 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -779,11 +779,11 @@ VectorXd OperationalSpaceControl::SolveQp( } // Solve the QP - const MathematicalProgramResult result = solver_->Solve(*prog_); // const MathematicalProgramResult result = solver_->Solve(*prog_); - auto osqp_solver = drake::solvers::OsqpSolver(); + const MathematicalProgramResult result = solver_->Solve(*prog_); +// auto osqp_solver = drake::solvers::OsqpSolver(); // osqp_solver->S - const MathematicalProgramResult result = osqp_solver.Solve(*prog_); +// const MathematicalProgramResult result = osqp_solver.Solve(*prog_); solve_time_ = result.get_solver_details().run_time; diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index 8443906321..ed0701fc9d 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -1,4 +1,5 @@ #include "trans_space_tracking_data.h" +#include using Eigen::MatrixXd; using Eigen::Vector3d; @@ -62,18 +63,18 @@ void TransTaskSpaceTrackingData::UpdateJ( context_wo_spr, JacobianWrtVariable::kV, *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); - if (fsm_state_ < 2) { +// if (fsm_state_ < 2) { // J_(2, 8) = 0; // J_(2, 16) = 0; - J_(2, 6) = 0; - J_(2, 14) = 0; - } - if (fsm_state_ >= 2) { - J_(2, 7) = 0; - J_(2, 15) = 0; // J_(2, 6) = 0; // J_(2, 14) = 0; - } +// } +// if (fsm_state_ >= 2) { +// J_(2, 7) = 0; +// J_(2, 15) = 0; +// J_(2, 6) = 0; +// J_(2, 14) = 0; +// } if (J_.hasNaN()) { std::cout << "Jacobian has NaNs" << std::endl; } From fac0abe0e83efc2a42ab958f1db4982045333cae Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Jun 2022 12:16:44 -0400 Subject: [PATCH 228/758] fixing osqp changes, think it's because sparsity is broken --- .../cassie/gym_envs/cassie_gym_test.py | 6 +- .../solver_settings/osqp_options_walking.yaml | 8 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- .../osc_run/osc_running_qp_settings.yaml | 6 +- solvers/fast_osqp_solver.cc | 115 ++++++++++++------ solvers/fast_osqp_solver.h | 3 + solvers/fast_osqp_solver_common.cc | 68 +++++++++-- solvers/osqp_options_default.yaml | 4 +- .../osc/operational_space_control.cc | 107 +++++++++------- .../osc/operational_space_control.h | 2 +- 10 files changed, 212 insertions(+), 109 deletions(-) diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index af8ab20d47..33be56a4c8 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -9,8 +9,8 @@ def main(): - # osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' - osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' + osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' + # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains_alip.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' @@ -30,7 +30,7 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - # gym_env = DrakeCassieGym(reward_func, visualize=True) + # gym_env = DrakeCassieGym(reward_func, visualize=False) gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) cumulative_reward = gym_env.advance_to(7.5) diff --git a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml index 50822be399..da90c7883c 100644 --- a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml +++ b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml @@ -8,9 +8,9 @@ eps_dual_inf: 1e-5 alpha: 1.6 linsys_solver: 0 delta: 1e-6 -polish: 1 -polish_refine_iter: 3 -verbose: 1 +polish: 0 +polish_refine_iter: 0 +verbose: 0 scaled_termination: 1 check_termination: 25 warm_start: 1 @@ -19,4 +19,4 @@ adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 -time_limit: 0.1 \ No newline at end of file +time_limit: 0.0 \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d0b69d5d08..55595b198a 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0000 w_input_reg: 0.1 w_accel: 0.0001 -w_soft_constraint: 100 +w_soft_constraint: 1 impact_threshold: 0.1 impact_tau: 0.05 mu: 0.6 diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 21759909aa..07c3ab49aa 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 50 +max_iter: 500 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -8,8 +8,8 @@ eps_dual_inf: 1e-5 alpha: 1.6 linsys_solver: 0 delta: 1e-6 -polish: 1 -polish_refine_iter: 1 +polish: 0 +polish_refine_iter: 0 verbose: 0 scaled_termination: 1 check_termination: 25 diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 1c8fdb699b..01f709494e 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -63,25 +63,25 @@ void ParseQuadraticCosts(const MathematicalProgram& prog, *constant_cost_term += quadratic_cost.evaluator()->c(); } -// // Scale the matrix P in the cost. -// // Note that the linear term is scaled in ParseLinearCosts(). -// const auto& scale_map = prog.GetVariableScaling(); -// if (!scale_map.empty()) { -// for (auto& triplet : P_triplets) { -// // Column -// const auto column = scale_map.find(triplet.col()); -// if (column != scale_map.end()) { -// triplet = Eigen::Triplet(triplet.row(), triplet.col(), -// triplet.value() * (column->second)); -// } -// // Row -// const auto row = scale_map.find(triplet.row()); -// if (row != scale_map.end()) { -// triplet = Eigen::Triplet(triplet.row(), triplet.col(), -// triplet.value() * (row->second)); -// } -// } -// } + // Scale the matrix P in the cost. + // Note that the linear term is scaled in ParseLinearCosts(). + const auto& scale_map = prog.GetVariableScaling(); + if (!scale_map.empty()) { + for (auto& triplet : P_triplets) { + // Column + const auto column = scale_map.find(triplet.col()); + if (column != scale_map.end()) { + triplet = Eigen::Triplet(triplet.row(), triplet.col(), + triplet.value() * (column->second)); + } + // Row + const auto row = scale_map.find(triplet.row()); + if (row != scale_map.end()) { + triplet = Eigen::Triplet(triplet.row(), triplet.col(), + triplet.value() * (row->second)); + } + } + } P->resize(prog.num_vars(), prog.num_vars()); P->setFromTriplets(P_triplets.begin(), P_triplets.end()); @@ -105,8 +105,17 @@ void ParseLinearCosts(const MathematicalProgram& prog, std::vector* q, // Add the constant cost term to constant_cost_term. *constant_cost_term += linear_cost.evaluator()->b(); } + + // Scale the vector q in the cost. + const auto& scale_map = prog.GetVariableScaling(); + if (!scale_map.empty()) { + for (const auto& [index, scale] : scale_map) { + q->at(index) *= scale; + } + } } + // OSQP defines its own infinity in osqp/include/glob_opts.h. c_float ConvertInfinity(double val) { if (std::isinf(val)) { @@ -196,6 +205,22 @@ void ParseAllLinearConstraints( l, u, &num_A_rows, constraint_start_row); ParseBoundingBoxConstraints(prog, &A_triplets, l, u, &num_A_rows, constraint_start_row); + + // Scale the matrix A. + // Note that we only scale the columns of A, because the constraint has the + // form l <= Ax <= u where the scaling of x enters the columns of A instead of + // rows of A. + const auto& scale_map = prog.GetVariableScaling(); + if (!scale_map.empty()) { + for (auto& triplet : A_triplets) { + auto column = scale_map.find(triplet.col()); + if (column != scale_map.end()) { + triplet = Eigen::Triplet(triplet.row(), triplet.col(), + triplet.value() * (column->second)); + } + } + } + A->resize(num_A_rows, prog.num_vars()); A->setFromTriplets(A_triplets.begin(), A_triplets.end()); } @@ -375,11 +400,6 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, const Eigen::VectorXd& initial_guess, const SolverOptions& merged_options, MathematicalProgramResult* result) const { - if (!prog.GetVariableScaling().empty()) { - static const drake::logging::Warn log_once( - "OsqpSolver doesn't support the feature of variable scaling."); - } - OsqpSolverDetails& solver_details = result->SetSolverDetailsType(); @@ -392,7 +412,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, Eigen::SparseMatrix P_sparse; std::vector q(prog.num_vars(), 0); double constant_cost_term{0}; - // + ParseQuadraticCosts(prog, &P_sparse, &q, &constant_cost_term); ParseLinearCosts(prog, &q, &constant_cost_term); @@ -405,19 +425,34 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, std::vector l, u; ParseAllLinearConstraints(prog, &A_sparse, &l, &u, &constraint_start_row); - csc* P_csc = EigenSparseToCSC(P_sparse); - csc* A_csc = EigenSparseToCSC(A_sparse); - osqp_update_lin_cost(workspace_, q.data()); - osqp_update_bounds(workspace_, l.data(), u.data()); - osqp_update_P_A(workspace_, P_csc->x, OSQP_NULL, P_csc->nzmax, A_csc->x, - OSQP_NULL, A_csc->nzmax); - SetFastOsqpSolverSettings(merged_options, osqp_settings_); + osqp_data_->n = prog.num_vars(); + osqp_data_->m = A_sparse.rows(); + osqp_data_->P = EigenSparseToCSC(P_sparse); + osqp_data_->q = q.data(); + osqp_data_->A = EigenSparseToCSC(A_sparse); + osqp_data_->l = l.data(); + osqp_data_->u = u.data(); + +// P_sparse.makeCompressed(); +// A_sparse.makeCompressed(); +// csc* P_csc = EigenSparseToCSC(P_sparse); +// csc* A_csc = EigenSparseToCSC(A_sparse); +// osqp_update_lin_cost(workspace_, q.data()); +// osqp_update_bounds(workspace_, l.data(), u.data()); +// osqp_update_P_A(workspace_, P_csc->x, OSQP_NULL, 0, A_csc->x, +// OSQP_NULL, 0); +// std::cout << success << std::endl; +// SetFastOsqpSolverSettings(merged_options, osqp_settings_); // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; // Solve problem. if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); + const c_int osqp_setup_err = osqp_setup(&workspace_, osqp_data_, osqp_settings_); + if (osqp_setup_err != 0) { + solution_result = SolutionResult::kInvalidInput; + } const c_int osqp_solve_err = osqp_solve(workspace_); if (osqp_solve_err != 0) { solution_result = SolutionResult::kInvalidInput; @@ -483,14 +518,14 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, // osqp_cleanup(workspace_); if (warm_start_) { - c_free(P_csc->x); - c_free(P_csc->i); - c_free(P_csc->p); - c_free(P_csc); - c_free(A_csc->x); - c_free(A_csc->i); - c_free(A_csc->p); - c_free(A_csc); + c_free(osqp_data_->P->x); + c_free(osqp_data_->P->i); + c_free(osqp_data_->P->p); + c_free(osqp_data_->P); + c_free(osqp_data_->A->x); + c_free(osqp_data_->A->i); + c_free(osqp_data_->A->p); + c_free(osqp_data_->A); } } diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index ee3e52a0ab..d6072883c1 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include "drake/common/drake_copyable.h" @@ -33,6 +34,8 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { static bool is_enabled(); static bool ProgramAttributesSatisfied( const drake::solvers::MathematicalProgram&); + static std::string UnsatisfiedProgramAttributes( + const drake::solvers::MathematicalProgram&); //@} void InitializeSolver(const drake::solvers::MathematicalProgram&, diff --git a/solvers/fast_osqp_solver_common.cc b/solvers/fast_osqp_solver_common.cc index a41329f6e3..98df44f9b5 100644 --- a/solvers/fast_osqp_solver_common.cc +++ b/solvers/fast_osqp_solver_common.cc @@ -3,22 +3,23 @@ /* clang-format on */ #include "drake/common/never_destroyed.h" +#include "drake/solvers/aggregate_costs_constraints.h" #include "drake/solvers/mathematical_program.h" // This file contains implementations that are common to both the available and // unavailable flavor of this class. using drake::solvers::MathematicalProgram; -using drake::solvers::ProgramAttributes; using drake::solvers::ProgramAttribute; +using drake::solvers::ProgramAttributes; using drake::solvers::SolverId; namespace dairlib { namespace solvers { FastOsqpSolver::FastOsqpSolver() - : SolverBase(&id, &is_available, &is_enabled, - &ProgramAttributesSatisfied) {} + : SolverBase(&id, &is_available, &is_enabled, &ProgramAttributesSatisfied) { +} FastOsqpSolver::~FastOsqpSolver() = default; @@ -29,17 +30,66 @@ SolverId FastOsqpSolver::id() { bool FastOsqpSolver::is_enabled() { return true; } -bool FastOsqpSolver::ProgramAttributesSatisfied(const drake::solvers::MathematicalProgram& prog) { +namespace { +bool CheckAttributes(const MathematicalProgram& prog, + std::string* explanation) { static const drake::never_destroyed solver_capabilities( std::initializer_list{ ProgramAttribute::kLinearCost, ProgramAttribute::kQuadraticCost, ProgramAttribute::kLinearConstraint, ProgramAttribute::kLinearEqualityConstraint}); - return AreRequiredAttributesSupported(prog.required_capabilities(), - solver_capabilities.access()) && - prog.required_capabilities().count(ProgramAttribute::kQuadraticCost) > - 0; + const ProgramAttributes& required_capabilities = prog.required_capabilities(); + const bool capabilities_match = AreRequiredAttributesSupported( + required_capabilities, solver_capabilities.access(), explanation); + if (!capabilities_match) { + if (explanation) { + *explanation = fmt::format("OsqpSolver is unable to solve because {}.", + *explanation); + } + return false; + } + if (required_capabilities.count(ProgramAttribute::kQuadraticCost) == 0) { + if (explanation) { + *explanation = + "OsqpSolver is unable to solve because a QuadraticCost is required" + " but has not been declared; OSQP works best with a quadratic cost." + " Please use a different solver such as CLP (for linear programming)" + " or IPOPT/SNOPT (for nonlinear programming) if you don't want to add" + " a quadratic cost to this program."; + } + return false; + } + const drake::solvers::Binding* + nonconvex_quadratic_cost = + FindNonconvexQuadraticCost(prog.quadratic_costs()); + if (nonconvex_quadratic_cost != nullptr) { + if (explanation) { + *explanation = + "OsqpSolver is unable to solve because the quadratic cost " + + nonconvex_quadratic_cost->to_string() + + " is non-convex. Either change this cost to a convex one, or switch " + "to a different solver like SNOPT/IPOPT/NLOPT."; + } + return false; + } + if (explanation) { + explanation->clear(); + } + return true; +} +} // namespace + +bool FastOsqpSolver::ProgramAttributesSatisfied( + const MathematicalProgram& prog) { + return CheckAttributes(prog, nullptr); +} + +std::string FastOsqpSolver::UnsatisfiedProgramAttributes( + const MathematicalProgram& prog) { + std::string explanation; + CheckAttributes(prog, &explanation); + return explanation; } } // namespace solvers -} // namespace drake +} // namespace dairlib diff --git a/solvers/osqp_options_default.yaml b/solvers/osqp_options_default.yaml index e87aadf35b..dd056b6662 100644 --- a/solvers/osqp_options_default.yaml +++ b/solvers/osqp_options_default.yaml @@ -10,7 +10,7 @@ linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 3 -verbose: 1 +verbose: 0 scaled_termination: 1 check_termination: 25 warm_start: 1 @@ -19,4 +19,4 @@ adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 -time_limit: 1.0 \ No newline at end of file +time_limit: 0.0 \ No newline at end of file diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 54e7da6509..e6ea33f0a5 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1,8 +1,9 @@ #include "systems/controllers/osc/operational_space_control.h" -#include #include +#include + #include "common/eigen_utils.h" #include "multibody/multibody_utils.h" @@ -40,8 +41,8 @@ namespace dairlib::systems::controllers { using multibody::CreateWithSpringsToWithoutSpringsMapPos; using multibody::CreateWithSpringsToWithoutSpringsMapVel; -using multibody::MakeNameToVelocitiesMap; using multibody::MakeNameToActuatorsMap; +using multibody::MakeNameToVelocitiesMap; using multibody::SetPositionsIfNew; using multibody::SetVelocitiesIfNew; using multibody::WorldPointEvaluator; @@ -51,8 +52,7 @@ OperationalSpaceControl::OperationalSpaceControl( const MultibodyPlant& plant_wo_spr, drake::systems::Context* context_w_spr, drake::systems::Context* context_wo_spr, - bool used_with_finite_state_machine, - double qp_time_limit) + bool used_with_finite_state_machine, double qp_time_limit) : plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), context_w_spr_(context_w_spr), @@ -390,8 +390,9 @@ void OperationalSpaceControl::Build() { // Add costs // 1. input cost if (W_input_.size() > 0) { - input_cost_ = prog_->AddQuadraticCost( - W_input_, VectorXd::Zero(n_u_), u_).evaluator().get(); + input_cost_ = prog_->AddQuadraticCost(W_input_, VectorXd::Zero(n_u_), u_) + .evaluator() + .get(); } // 2. acceleration cost if (W_joint_accel_.size() > 0) { @@ -458,16 +459,17 @@ void OperationalSpaceControl::Build() { .get(); /// Soft constraint version // DRAKE_DEMAND(w_blend_constraint_ > 0); - // prog_->AddQuadraticCost( - // w_blend_constraint_ * - // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), - // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); + // prog_->AddQuadraticCost( + // w_blend_constraint_ * + // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), + // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); /// hard constraint version prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); } - solver_ = std::make_unique(); - solver_->InitializeSolver(*prog_, solver_options_); + for (int i = -1; i < 5; ++i) { + solvers_[i] = std::make_unique(); + } } drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( @@ -628,8 +630,8 @@ VectorXd OperationalSpaceControl::SolveQp( weight(3, 3) *= 1e-3; weight(4, 4) *= 1e-3; A_c.block(0, n_v_, n_c_active_, n_c_active_) = weight; -// A_c.block(0, n_v_, n_c_active_, n_c_active_) = -// MatrixXd::Identity(n_c_active_, n_c_active_); + // A_c.block(0, n_v_, n_c_active_, n_c_active_) = + // MatrixXd::Identity(n_c_active_, n_c_active_); contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -692,13 +694,19 @@ VectorXd OperationalSpaceControl::SolveQp( const MatrixXd& W = tracking_data->GetWeight(); const MatrixXd& J_t = tracking_data->GetJ(); const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); - // The tracking cost is - // 0.5 * (J_*dv + JdotV - y_command)^T * W * (J_*dv + JdotV - y_command). - // We ignore the constant term - // 0.5 * (JdotV - y_command)^T * W * (JdotV - y_command), - // since it doesn't change the result of QP. + const VectorXd constant_term = (JdotV_t - ddy_t); + // tracking_cost_.at(i)->UpdateCoefficients( + // J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - + // ddy_t), 0.5 * constant_term.transpose() * W * constant_term, + // true); tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t)); + J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), + constant_term.transpose() * W * constant_term, true); + // tracking_cost_.at(i)->UpdateCoefficients( + // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * + // constant_term.transpose() * W * constant_term); + // tracking_cost_.at(i)->UpdateCoefficients( + // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_)); } else { tracking_cost_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), VectorXd::Zero(n_v_)); @@ -747,14 +755,13 @@ VectorXd OperationalSpaceControl::SolveQp( blend_constraint_->UpdateCoefficients(A, VectorXd::Zero(1)); } - // test joint-level input cost by fsm state if (!fsm_to_w_input_map_.empty()) { MatrixXd W = W_input_; if (fsm_to_w_input_map_.count(fsm_state)) { int j = fsm_to_w_input_map_.at(fsm_state).first; double w = fsm_to_w_input_map_.at(fsm_state).second; - W(j,j) += w; + W(j, j) += w; } input_cost_->UpdateCoefficients(W, VectorXd::Zero(n_u_)); } @@ -769,22 +776,23 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd::Zero(n_c_)); } - // if (!solver_->IsInitialized()) { - // solver_->InitializeSolver(*prog_); - // } + if (!solvers_.at(fsm_state)->IsInitialized()) { + solvers_.at(fsm_state)->InitializeSolver(*prog_, solver_options_); + } if (initial_guess_x_.count(fsm_state) > 0) { - solver_->WarmStart(initial_guess_x_.at(fsm_state), - initial_guess_y_.at(fsm_state)); + solvers_.at(fsm_state)->WarmStart(initial_guess_x_.at(fsm_state), + initial_guess_y_.at(fsm_state)); } // Solve the QP -// const MathematicalProgramResult result = solver_->Solve(*prog_); - const MathematicalProgramResult result = solver_->Solve(*prog_); -// auto osqp_solver = drake::solvers::OsqpSolver(); -// osqp_solver->S -// const MathematicalProgramResult result = osqp_solver.Solve(*prog_); - + MathematicalProgramResult result; + if (fsm_state == -1) { + auto osqp_solver = drake::solvers::OsqpSolver(); + result = osqp_solver.Solve(*prog_, std::nullopt, solver_options_); + } else { + result = solvers_.at(fsm_state)->Solve(*prog_); + } solve_time_ = result.get_solver_details().run_time; if (result.is_success()) { @@ -796,27 +804,35 @@ VectorXd OperationalSpaceControl::SolveQp( *epsilon_sol_ = result.GetSolution(epsilon_); double window = 0.01; double tau = 0.01; - if(fsm_state >= 2 && initial_guess_x_.size() == 4){ + if (fsm_state >= 2 && initial_guess_x_.size() == 4) { double clock_time; if (this->get_input_port(clock_port_).HasValue(context)) { auto clock = this->EvalVectorInput(context, clock_port_); clock_time = clock->get_value()(0); } - if(fsm_state == 2){ + if (fsm_state == 2) { double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); double blend_out = 1 - exp(-((clock_time - 0.2) + window) / tau); - u_sol_->row(6) = blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); - u_sol_->row(7) = blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); - u_sol_->row(0) = blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); - u_sol_->row(1) = blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); + u_sol_->row(6) = + blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); + u_sol_->row(7) = + blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); + u_sol_->row(0) = + blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); + u_sol_->row(1) = + blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); } - if(fsm_state == 3){ + if (fsm_state == 3) { double blend_in = 1 - exp(-((0.6 - clock_time) + window) / tau); double blend_out = 1 - exp(-((clock_time - 0.5) + window) / tau); - u_sol_->row(6) = blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); - u_sol_->row(7) = blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); - u_sol_->row(0) = blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); - u_sol_->row(1) = blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); + u_sol_->row(6) = + blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); + u_sol_->row(7) = + blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); + u_sol_->row(0) = + blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); + u_sol_->row(1) = + blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); } } u_prev_[fsm_state] = *u_sol_; @@ -827,7 +843,6 @@ VectorXd OperationalSpaceControl::SolveQp( u_prev_[fsm_state] = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } - for (auto& tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state)) { tracking_data->StoreYddotCommandSol(*dv_sol_); @@ -835,7 +850,7 @@ VectorXd OperationalSpaceControl::SolveQp( } return *u_sol_; -} +} // namespace dairlib::systems::controllers void OperationalSpaceControl::UpdateImpactInvariantProjection( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const Context& context, double t, double t_since_last_state_switch, diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 350e69035b..79b72892a7 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -315,7 +315,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { bool is_quaternion_; // Solver - std::unique_ptr solver_; + std::unordered_map> solvers_; drake::solvers::SolverOptions solver_options_ = drake::yaml::LoadYamlFile( FindResourceOrThrow("solvers/osqp_options_default.yaml")) From ad7d51efb75cad68f2b633df4ec7b511cf90738d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Jun 2022 13:44:01 -0400 Subject: [PATCH 229/758] finally works in both drake and mujoco --- examples/Cassie/osc_run/osc_running_qp_settings.yaml | 6 +++--- examples/Cassie/run_osc_running_controller.cc | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 07c3ab49aa..41753bee75 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 500 +max_iter: 75 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -12,9 +12,9 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 25 +check_termination: 15 warm_start: 1 -scaling: 10 +scaling: 1 adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index ca984dbaec..5c19de0a2c 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -501,8 +501,8 @@ int DoMain(int argc, char* argv[]) { "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); -// left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); -// right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), From 1b35e03b5fd9d1848aae0bb6e27b9bca17148d04 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Jun 2022 14:55:01 -0400 Subject: [PATCH 230/758] working on fixing input supervisor --- bindings/pydairlib/analysis/mbp_plotting_utils.py | 2 +- .../analysis/plot_configs/cassie_running_plot.yaml | 6 ++++-- examples/Cassie/systems/input_supervisor.cc | 6 +++--- examples/Cassie/systems/input_supervisor.h | 2 +- 4 files changed, 9 insertions(+), 7 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index a9b79584d9..04cde666ff 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -3,7 +3,7 @@ from matplotlib.patches import Patch from pydairlib.common import plot_styler, plotting_utils -from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost +from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost, osc_regularlization_tracking_cost from pydairlib.multibody import MakeNameToPositionsMap, \ MakeNameToVelocitiesMap, MakeNameToActuatorsMap, \ CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index ae1b86b56f..b930458e52 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) -#end_time: -1 -end_time: -1 +start_time: 0 +duration: 5 # Plant properties use_springs: true @@ -16,10 +16,12 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false plot_floating_base_velocities: false +plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true +plot_contact_forces: false special_positions_to_plot: [ ] special_velocities_to_plot: [] special_efforts_to_plot: [ ] diff --git a/examples/Cassie/systems/input_supervisor.cc b/examples/Cassie/systems/input_supervisor.cc index 103154b8e2..6ebddd4f40 100644 --- a/examples/Cassie/systems/input_supervisor.cc +++ b/examples/Cassie/systems/input_supervisor.cc @@ -105,8 +105,7 @@ InputSupervisor::InputSupervisor( K_ *= kEStopGain; // Create update for error flag - DeclarePeriodicDiscreteUpdateEvent(update_period, 0, - &InputSupervisor::UpdateErrorFlag); + DeclarePerStepDiscreteUpdateEvent(&InputSupervisor::UpdateErrorFlag); } void InputSupervisor::SetMotorTorques(const Context& context, @@ -212,7 +211,7 @@ void InputSupervisor::SetFailureStatus( output->error_name = ""; } -void InputSupervisor::UpdateErrorFlag( +drake::systems::EventStatus InputSupervisor::UpdateErrorFlag( const Context& context, DiscreteValues* discrete_state) const { const auto* controller_switch = @@ -278,6 +277,7 @@ void InputSupervisor::UpdateErrorFlag( blend_duration_) { discrete_state->get_mutable_value(prev_efforts_index_) = command->value(); } + return drake::systems::EventStatus::Succeeded(); } void InputSupervisor::CheckVelocities( diff --git a/examples/Cassie/systems/input_supervisor.h b/examples/Cassie/systems/input_supervisor.h index 2d19415a06..736da9dbc0 100644 --- a/examples/Cassie/systems/input_supervisor.h +++ b/examples/Cassie/systems/input_supervisor.h @@ -87,7 +87,7 @@ class InputSupervisor : public drake::systems::LeafSystem { void SetMotorTorques(const drake::systems::Context& context, systems::TimestampedVector* output) const; - void UpdateErrorFlag( + drake::systems::EventStatus UpdateErrorFlag( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; From 98a10af28d05daff46419da8719414cbe44a832d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Jun 2022 15:31:16 -0400 Subject: [PATCH 231/758] using lcm default url path --- .../plot_configs/cassie_running_plot.yaml | 2 +- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 23 ++++++++----------- examples/Cassie/run_controller_switch.cc | 18 ++++++--------- examples/Cassie/run_osc_running_controller.cc | 2 +- .../Cassie/run_osc_standing_controller.cc | 2 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- .../Cassie/run_osc_walking_controller_alip.cc | 2 +- 8 files changed, 23 insertions(+), 30 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index b930458e52..6cc9986343 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -7,7 +7,7 @@ channel_osc: "OSC_DEBUG_RUNNING" # Log time to stop at (seconds, -1 for whole log) start_time: 0 -duration: 5 +duration: 10 # Plant properties use_springs: true diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index a4247c66d8..77018011b9 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -67,7 +67,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index ec58764eb7..8cdee9137e 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -157,9 +157,9 @@ void setInitialEkfState(double t0, const cassie_out_t& cassie_output, int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; + auto lcm = builder.AddSystem(); + drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); // Build Cassie MBP drake::multibody::MultibodyPlant plant(0.0); @@ -229,7 +229,7 @@ int do_main(int argc, char* argv[]) { if (FLAGS_floating_base && FLAGS_test_with_ground_truth_state) { auto state_sub = builder.AddSystem( LcmSubscriberSystem::Make( - FLAGS_state_channel_name, &lcm_local)); + FLAGS_state_channel_name, lcm)); auto state_receiver = builder.AddSystem(plant); builder.Connect(state_sub->get_output_port(), @@ -247,14 +247,13 @@ int do_main(int argc, char* argv[]) { // Create and connect contact estimation publisher. auto contact_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_CONTACT_DISPATCHER", &lcm_local, {TriggerType::kForced})); + "CASSIE_CONTACT_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(state_estimator->get_contact_output_port(), contact_pub->get_input_port()); // TODO(yangwill): Consider filtering contact estimation auto gm_contact_pub = builder.AddSystem( LcmPublisherSystem::Make( - "CASSIE_GM_CONTACT_DISPATCHER", &lcm_local, - {TriggerType::kForced})); + "CASSIE_GM_CONTACT_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(state_estimator->get_gm_contact_output_port(), gm_contact_pub->get_input_port()); } @@ -293,7 +292,7 @@ int do_main(int argc, char* argv[]) { if (FLAGS_broadcast_robot_state) { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_DISPATCHER", &lcm_local, {TriggerType::kForced})); + "CASSIE_STATE_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(*robot_output_sender, *state_pub); auto net_state_pub = builder.AddSystem(LcmPublisherSystem::Make( @@ -304,7 +303,7 @@ int do_main(int argc, char* argv[]) { } else { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_DISPATCHER", &lcm_local, {TriggerType::kForced})); + "CASSIE_STATE_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(*robot_output_sender, *state_pub); // Create and connect RobotOutput publisher (low-rate for the network) @@ -328,10 +327,9 @@ int do_main(int argc, char* argv[]) { // Wait for the first message. drake::log()->info("Waiting for first lcmt_cassie_out"); - drake::lcm::Subscriber input_sub(&lcm_local, + drake::lcm::Subscriber input_sub(lcm, "CASSIE_OUTPUT"); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); // Initialize the context based on the first message. const double t0 = input_sub.message().utime * 1e-6; @@ -355,8 +353,7 @@ int do_main(int argc, char* argv[]) { while (true) { // Wait for an lcmt_cassie_out message. input_sub.clear(); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); // Write the lcmt_robot_input message into the context and advance. input_value.GetMutableData()->set_value(input_sub.message()); const double time = input_sub.message().utime * 1e-6; diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index c5647aa877..405bbc0ba3 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -1,6 +1,7 @@ -#include #include +#include +#include #include #include "dairlib/lcmt_controller_switch.hpp" @@ -78,15 +79,12 @@ int do_main(int argc, char* argv[]) { // offset has to be positive DRAKE_DEMAND(FLAGS_fsm_offset >= 0); - // Parameters - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - // Build the diagram drake::systems::DiagramBuilder builder; + auto lcm = builder.AddSystem(); auto name_pub = builder.AddSystem( LcmPublisherSystem::Make( - FLAGS_switch_channel, &lcm_local, - TriggerTypeSet({TriggerType::kForced}))); + FLAGS_switch_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); auto owned_diagram = builder.Build(); owned_diagram->set_name(("switch publisher")); @@ -96,13 +94,12 @@ int do_main(int argc, char* argv[]) { auto& diagram_context = simulator.get_mutable_context(); // Create subscriber for lcm driven loop - drake::lcm::Subscriber input_sub(&lcm_local, + drake::lcm::Subscriber input_sub(lcm, FLAGS_channel_x); // Wait for the first message and initialize the context time.. drake::log()->info("Waiting for first lcm input message"); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); const double t0 = input_sub.message().utime * 1e-6; diagram_context.SetTime(t0); @@ -124,8 +121,7 @@ int do_main(int argc, char* argv[]) { while (pub_count < FLAGS_n_publishes) { // Wait for input message. input_sub.clear(); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); // Get message time from the input channel double t_current = input_sub.message().utime * 1e-6; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 5c19de0a2c..aa135eab5f 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -169,7 +169,7 @@ int DoMain(int argc, char* argv[]) { plant, fsm_states, state_durations, 0.0, gains.impact_threshold, gains.impact_tau); /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm; auto state_receiver = builder.AddSystem(plant); auto command_pub = diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 9a6e72c266..7e3c154328 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -103,7 +103,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // auto osc_gains = // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); drake::yaml::LoadYamlOptions yaml_options; diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 10088e17b4..104a8f2ab4 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -113,7 +113,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index e9fc21d6c3..6a29665edf 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -124,7 +124,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both From 0e755b3b6ab25918ac941d8019e3cdb83d4d8be0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Jun 2022 15:59:29 -0400 Subject: [PATCH 232/758] using lcm env variable and fixing osqp solver --- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 23 ++-- examples/Cassie/run_controller_switch.cc | 18 +-- .../Cassie/run_osc_standing_controller.cc | 2 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- .../Cassie/run_osc_walking_controller_alip.cc | 2 +- solvers/fast_osqp_solver.cc | 129 ++++++++++++------ solvers/fast_osqp_solver.h | 24 +++- solvers/fast_osqp_solver_common.cc | 68 +++++++-- .../osc/operational_space_control.cc | 2 +- 10 files changed, 189 insertions(+), 83 deletions(-) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 304c2d7a56..2905f48df6 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -67,7 +67,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index d93f1c08af..33b2f2b5c2 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -157,9 +157,9 @@ void setInitialEkfState(double t0, const cassie_out_t& cassie_output, int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; + auto lcm = builder.AddSystem(); + drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); // Build Cassie MBP drake::multibody::MultibodyPlant plant(0.0); @@ -229,7 +229,7 @@ int do_main(int argc, char* argv[]) { if (FLAGS_floating_base && FLAGS_test_with_ground_truth_state) { auto state_sub = builder.AddSystem( LcmSubscriberSystem::Make( - FLAGS_state_channel_name, &lcm_local)); + FLAGS_state_channel_name, lcm)); auto state_receiver = builder.AddSystem(plant); builder.Connect(state_sub->get_output_port(), @@ -247,14 +247,13 @@ int do_main(int argc, char* argv[]) { // Create and connect contact estimation publisher. auto contact_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_CONTACT_DISPATCHER", &lcm_local, {TriggerType::kForced})); + "CASSIE_CONTACT_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(state_estimator->get_contact_output_port(), contact_pub->get_input_port()); // TODO(yangwill): Consider filtering contact estimation auto gm_contact_pub = builder.AddSystem( LcmPublisherSystem::Make( - "CASSIE_GM_CONTACT_DISPATCHER", &lcm_local, - {TriggerType::kForced})); + "CASSIE_GM_CONTACT_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(state_estimator->get_gm_contact_output_port(), gm_contact_pub->get_input_port()); } @@ -293,7 +292,7 @@ int do_main(int argc, char* argv[]) { if (FLAGS_broadcast_robot_state) { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_DISPATCHER", &lcm_local, {TriggerType::kForced})); + "CASSIE_STATE_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(*robot_output_sender, *state_pub); auto net_state_pub = builder.AddSystem(LcmPublisherSystem::Make( @@ -304,7 +303,7 @@ int do_main(int argc, char* argv[]) { } else { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_DISPATCHER", &lcm_local, {TriggerType::kForced})); + "CASSIE_STATE_DISPATCHER", lcm, {TriggerType::kForced})); builder.Connect(*robot_output_sender, *state_pub); // Create and connect RobotOutput publisher (low-rate for the network) @@ -328,10 +327,9 @@ int do_main(int argc, char* argv[]) { // Wait for the first message. drake::log()->info("Waiting for first lcmt_cassie_out"); - drake::lcm::Subscriber input_sub(&lcm_local, + drake::lcm::Subscriber input_sub(lcm, "CASSIE_OUTPUT"); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); // Initialize the context based on the first message. const double t0 = input_sub.message().utime * 1e-6; @@ -355,8 +353,7 @@ int do_main(int argc, char* argv[]) { while (true) { // Wait for an lcmt_cassie_out message. input_sub.clear(); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); // Write the lcmt_robot_input message into the context and advance. input_value.GetMutableData()->set_value(input_sub.message()); const double time = input_sub.message().utime * 1e-6; diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index c5647aa877..405bbc0ba3 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -1,6 +1,7 @@ -#include #include +#include +#include #include #include "dairlib/lcmt_controller_switch.hpp" @@ -78,15 +79,12 @@ int do_main(int argc, char* argv[]) { // offset has to be positive DRAKE_DEMAND(FLAGS_fsm_offset >= 0); - // Parameters - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - // Build the diagram drake::systems::DiagramBuilder builder; + auto lcm = builder.AddSystem(); auto name_pub = builder.AddSystem( LcmPublisherSystem::Make( - FLAGS_switch_channel, &lcm_local, - TriggerTypeSet({TriggerType::kForced}))); + FLAGS_switch_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); auto owned_diagram = builder.Build(); owned_diagram->set_name(("switch publisher")); @@ -96,13 +94,12 @@ int do_main(int argc, char* argv[]) { auto& diagram_context = simulator.get_mutable_context(); // Create subscriber for lcm driven loop - drake::lcm::Subscriber input_sub(&lcm_local, + drake::lcm::Subscriber input_sub(lcm, FLAGS_channel_x); // Wait for the first message and initialize the context time.. drake::log()->info("Waiting for first lcm input message"); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); const double t0 = input_sub.message().utime * 1e-6; diagram_context.SetTime(t0); @@ -124,8 +121,7 @@ int do_main(int argc, char* argv[]) { while (pub_count < FLAGS_n_publishes) { // Wait for input message. input_sub.clear(); - LcmHandleSubscriptionsUntil(&lcm_local, - [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); // Get message time from the input channel double t_current = input_sub.message().utime * 1e-6; diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index e8922a510d..bc92869397 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -134,7 +134,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); MatrixXd K_p_com = Eigen::Map< diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index db0105acc3..780e5ceda7 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -112,7 +112,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index e7e56d5be0..c773ca772d 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -117,7 +117,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 280c37f6e1..0e86963780 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -63,25 +63,25 @@ void ParseQuadraticCosts(const MathematicalProgram& prog, *constant_cost_term += quadratic_cost.evaluator()->c(); } -// // Scale the matrix P in the cost. -// // Note that the linear term is scaled in ParseLinearCosts(). -// const auto& scale_map = prog.GetVariableScaling(); -// if (!scale_map.empty()) { -// for (auto& triplet : P_triplets) { -// // Column -// const auto column = scale_map.find(triplet.col()); -// if (column != scale_map.end()) { -// triplet = Eigen::Triplet(triplet.row(), triplet.col(), -// triplet.value() * (column->second)); -// } -// // Row -// const auto row = scale_map.find(triplet.row()); -// if (row != scale_map.end()) { -// triplet = Eigen::Triplet(triplet.row(), triplet.col(), -// triplet.value() * (row->second)); -// } -// } -// } + // Scale the matrix P in the cost. + // Note that the linear term is scaled in ParseLinearCosts(). + const auto& scale_map = prog.GetVariableScaling(); + if (!scale_map.empty()) { + for (auto& triplet : P_triplets) { + // Column + const auto column = scale_map.find(triplet.col()); + if (column != scale_map.end()) { + triplet = Eigen::Triplet(triplet.row(), triplet.col(), + triplet.value() * (column->second)); + } + // Row + const auto row = scale_map.find(triplet.row()); + if (row != scale_map.end()) { + triplet = Eigen::Triplet(triplet.row(), triplet.col(), + triplet.value() * (row->second)); + } + } + } P->resize(prog.num_vars(), prog.num_vars()); P->setFromTriplets(P_triplets.begin(), P_triplets.end()); @@ -105,8 +105,17 @@ void ParseLinearCosts(const MathematicalProgram& prog, std::vector* q, // Add the constant cost term to constant_cost_term. *constant_cost_term += linear_cost.evaluator()->b(); } + + // Scale the vector q in the cost. + const auto& scale_map = prog.GetVariableScaling(); + if (!scale_map.empty()) { + for (const auto& [index, scale] : scale_map) { + q->at(index) *= scale; + } + } } + // OSQP defines its own infinity in osqp/include/glob_opts.h. c_float ConvertInfinity(double val) { if (std::isinf(val)) { @@ -196,6 +205,22 @@ void ParseAllLinearConstraints( l, u, &num_A_rows, constraint_start_row); ParseBoundingBoxConstraints(prog, &A_triplets, l, u, &num_A_rows, constraint_start_row); + + // Scale the matrix A. + // Note that we only scale the columns of A, because the constraint has the + // form l <= Ax <= u where the scaling of x enters the columns of A instead of + // rows of A. + const auto& scale_map = prog.GetVariableScaling(); + if (!scale_map.empty()) { + for (auto& triplet : A_triplets) { + auto column = scale_map.find(triplet.col()); + if (column != scale_map.end()) { + triplet = Eigen::Triplet(triplet.row(), triplet.col(), + triplet.value() * (column->second)); + } + } + } + A->resize(num_A_rows, prog.num_vars()); A->setFromTriplets(A_triplets.begin(), A_triplets.end()); } @@ -344,8 +369,6 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, osqp_data_->l = l.data(); osqp_data_->u = u.data(); - // Define Solver settings as default. - // Problem settings osqp_settings_ = static_cast(c_malloc(sizeof(OSQPSettings))); osqp_set_default_settings(osqp_settings_); SetFastOsqpSolverSettings(solver_options, osqp_settings_); @@ -355,18 +378,30 @@ void FastOsqpSolver::InitializeSolver(const MathematicalProgram& prog, const c_int osqp_setup_err = osqp_setup(&workspace_, osqp_data_, osqp_settings_); DRAKE_DEMAND(osqp_setup_err == 0); + + is_init_ = true; +} + +void FastOsqpSolver::WarmStart(const Eigen::VectorXd& primal, + const Eigen::VectorXd& dual) { + std::vector x, y; + x.reserve(primal.size()); + y.reserve(dual.size()); + for (int i = 0; i < primal.size(); ++i) { + x.push_back(ConvertInfinity(primal(i))); + } + for (int i = 0; i < dual.size(); ++i) { + y.push_back(ConvertInfinity(dual(i))); + } + osqp_warm_start(workspace_, x.data(), y.data()); } void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, const Eigen::VectorXd& initial_guess, const SolverOptions& merged_options, MathematicalProgramResult* result) const { - if (!prog.GetVariableScaling().empty()) { - static const drake::logging::Warn log_once( - "OsqpSolver doesn't support the feature of variable scaling."); - } - - OsqpSolverDetails& solver_details = result->SetSolverDetailsType(); + OsqpSolverDetails& solver_details = + result->SetSolverDetailsType(); // OSQP solves a convex quadratic programming problem // min 0.5 xᵀPx + qᵀx @@ -377,7 +412,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, Eigen::SparseMatrix P_sparse; std::vector q(prog.num_vars(), 0); double constant_cost_term{0}; - // + ParseQuadraticCosts(prog, &P_sparse, &q, &constant_cost_term); ParseLinearCosts(prog, &q, &constant_cost_term); @@ -390,19 +425,24 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, std::vector l, u; ParseAllLinearConstraints(prog, &A_sparse, &l, &u, &constraint_start_row); - csc* P_csc = EigenSparseToCSC(P_sparse); - csc* A_csc = EigenSparseToCSC(A_sparse); - osqp_update_lin_cost(workspace_, q.data()); - osqp_update_bounds(workspace_, l.data(), u.data()); - osqp_update_P_A(workspace_, P_csc->x, OSQP_NULL, P_csc->nzmax, A_csc->x, - OSQP_NULL, A_csc->nzmax); - SetFastOsqpSolverSettings(merged_options, osqp_settings_); + osqp_data_->n = prog.num_vars(); + osqp_data_->m = A_sparse.rows(); + osqp_data_->P = EigenSparseToCSC(P_sparse); + osqp_data_->q = q.data(); + osqp_data_->A = EigenSparseToCSC(A_sparse); + osqp_data_->l = l.data(); + osqp_data_->u = u.data(); + // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; // Solve problem. if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); + const c_int osqp_setup_err = osqp_setup(&workspace_, osqp_data_, osqp_settings_); + if (osqp_setup_err != 0) { + solution_result = SolutionResult::kInvalidInput; + } const c_int osqp_solve_err = osqp_solve(workspace_); if (osqp_solve_err != 0) { solution_result = SolutionResult::kInvalidInput; @@ -424,6 +464,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, switch (workspace_->info->status_val) { case OSQP_SOLVED: + this->EnableWarmStart(); case OSQP_SOLVED_INACCURATE: { const Eigen::Map> osqp_sol( workspace_->solution->x, prog.num_vars()); @@ -466,14 +507,16 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, result->set_solution_result(solution_result.value()); // osqp_cleanup(workspace_); - c_free(P_csc->x); - c_free(P_csc->i); - c_free(P_csc->p); - c_free(P_csc); - c_free(A_csc->x); - c_free(A_csc->i); - c_free(A_csc->p); - c_free(A_csc); + if (warm_start_) { + c_free(osqp_data_->P->x); + c_free(osqp_data_->P->i); + c_free(osqp_data_->P->p); + c_free(osqp_data_->P); + c_free(osqp_data_->A->x); + c_free(osqp_data_->A->i); + c_free(osqp_data_->A->p); + c_free(osqp_data_->A); + } } } // namespace solvers diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index ff56780f16..5e9059fb24 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -33,11 +33,29 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { static bool is_enabled(); static bool ProgramAttributesSatisfied( const drake::solvers::MathematicalProgram&); + static std::string UnsatisfiedProgramAttributes( + const drake::solvers::MathematicalProgram&); //@} void InitializeSolver(const drake::solvers::MathematicalProgram&, const drake::solvers::SolverOptions&); + /// Solver will automatically reenable warm starting after a successful solve + void DisableWarmStart() const { + osqp_settings_->warm_start = false; + warm_start_ = false; + is_init_ = false; + } + /// Solver will automatically reenable warm starting after a successful solve + void EnableWarmStart() const { + osqp_settings_->warm_start = true; + warm_start_ = true; + } + + void WarmStart(const Eigen::VectorXd& primal, const Eigen::VectorXd& dual); + + bool IsInitialized() const { return is_init_; } + // A using-declaration adds these methods into our class's Doxygen. using SolverBase::Solve; @@ -47,8 +65,10 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { drake::solvers::MathematicalProgramResult*) const final; OSQPData* osqp_data_; - OSQPSettings* osqp_settings_; - OSQPWorkspace* workspace_; + mutable OSQPSettings* osqp_settings_; + mutable OSQPWorkspace* workspace_; + mutable bool warm_start_ = true; + mutable bool is_init_ = false; }; } // namespace solvers } // namespace dairlib diff --git a/solvers/fast_osqp_solver_common.cc b/solvers/fast_osqp_solver_common.cc index a41329f6e3..98df44f9b5 100644 --- a/solvers/fast_osqp_solver_common.cc +++ b/solvers/fast_osqp_solver_common.cc @@ -3,22 +3,23 @@ /* clang-format on */ #include "drake/common/never_destroyed.h" +#include "drake/solvers/aggregate_costs_constraints.h" #include "drake/solvers/mathematical_program.h" // This file contains implementations that are common to both the available and // unavailable flavor of this class. using drake::solvers::MathematicalProgram; -using drake::solvers::ProgramAttributes; using drake::solvers::ProgramAttribute; +using drake::solvers::ProgramAttributes; using drake::solvers::SolverId; namespace dairlib { namespace solvers { FastOsqpSolver::FastOsqpSolver() - : SolverBase(&id, &is_available, &is_enabled, - &ProgramAttributesSatisfied) {} + : SolverBase(&id, &is_available, &is_enabled, &ProgramAttributesSatisfied) { +} FastOsqpSolver::~FastOsqpSolver() = default; @@ -29,17 +30,66 @@ SolverId FastOsqpSolver::id() { bool FastOsqpSolver::is_enabled() { return true; } -bool FastOsqpSolver::ProgramAttributesSatisfied(const drake::solvers::MathematicalProgram& prog) { +namespace { +bool CheckAttributes(const MathematicalProgram& prog, + std::string* explanation) { static const drake::never_destroyed solver_capabilities( std::initializer_list{ ProgramAttribute::kLinearCost, ProgramAttribute::kQuadraticCost, ProgramAttribute::kLinearConstraint, ProgramAttribute::kLinearEqualityConstraint}); - return AreRequiredAttributesSupported(prog.required_capabilities(), - solver_capabilities.access()) && - prog.required_capabilities().count(ProgramAttribute::kQuadraticCost) > - 0; + const ProgramAttributes& required_capabilities = prog.required_capabilities(); + const bool capabilities_match = AreRequiredAttributesSupported( + required_capabilities, solver_capabilities.access(), explanation); + if (!capabilities_match) { + if (explanation) { + *explanation = fmt::format("OsqpSolver is unable to solve because {}.", + *explanation); + } + return false; + } + if (required_capabilities.count(ProgramAttribute::kQuadraticCost) == 0) { + if (explanation) { + *explanation = + "OsqpSolver is unable to solve because a QuadraticCost is required" + " but has not been declared; OSQP works best with a quadratic cost." + " Please use a different solver such as CLP (for linear programming)" + " or IPOPT/SNOPT (for nonlinear programming) if you don't want to add" + " a quadratic cost to this program."; + } + return false; + } + const drake::solvers::Binding* + nonconvex_quadratic_cost = + FindNonconvexQuadraticCost(prog.quadratic_costs()); + if (nonconvex_quadratic_cost != nullptr) { + if (explanation) { + *explanation = + "OsqpSolver is unable to solve because the quadratic cost " + + nonconvex_quadratic_cost->to_string() + + " is non-convex. Either change this cost to a convex one, or switch " + "to a different solver like SNOPT/IPOPT/NLOPT."; + } + return false; + } + if (explanation) { + explanation->clear(); + } + return true; +} +} // namespace + +bool FastOsqpSolver::ProgramAttributesSatisfied( + const MathematicalProgram& prog) { + return CheckAttributes(prog, nullptr); +} + +std::string FastOsqpSolver::UnsatisfiedProgramAttributes( + const MathematicalProgram& prog) { + std::string explanation; + CheckAttributes(prog, &explanation); + return explanation; } } // namespace solvers -} // namespace drake +} // namespace dairlib diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 7dfda22aac..fcbea3c021 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -678,7 +678,7 @@ VectorXd OperationalSpaceControl::SolveQp( // 0.5 * (JdotV - y_command)^T * W * (JdotV - y_command), // since it doesn't change the result of QP. tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t)); + J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), 0, true); } else { tracking_cost_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), VectorXd::Zero(n_v_)); From a3037ef2b5425dbb9eaff21d6a0b03e87f54ae83 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 24 Jun 2022 15:58:31 -0400 Subject: [PATCH 233/758] fixing dircon jumping --- examples/Cassie/run_dircon_jumping.cc | 14 +++- examples/Cassie/systems/BUILD.bazel | 11 ++++ .../systems}/variable_time_fsm.cc | 65 ++++++------------- .../systems}/variable_time_fsm.h | 20 +++--- lcm/dircon_saved_trajectory.cc | 31 +++++---- lcm/lcm_trajectory.cc | 4 ++ 6 files changed, 77 insertions(+), 68 deletions(-) rename examples/{impact_invariant_control => Cassie/systems}/variable_time_fsm.cc (55%) rename examples/{impact_invariant_control => Cassie/systems}/variable_time_fsm.h (77%) diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index af04d73720..b38e9dcdac 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -332,7 +332,7 @@ void DoMain() { prog.SetSolverOption(id, "Solution", "No"); // target nonlinear constraint violation - prog.SetSolverOption(id, "Major optimality tolerance", 1e-4); + prog.SetSolverOption(id, "Major optimality tolerance", 1e-5 / FLAGS_cost_scaling); // target complementarity gap prog.SetSolverOption(id, "Major feasibility tolerance", tol); @@ -553,10 +553,18 @@ void SetKinematicConstraints(Dircon* trajopt, // actuator limits std::cout << "Actuator limit constraints: " << std::endl; + VectorXd u_min(n_u); + VectorXd u_max(n_u); + for (drake::multibody::JointActuatorIndex i(0); i < n_u; ++i) { + u_min(i) = -plant.get_joint_actuator(i).effort_limit(); + u_max(i) = plant.get_joint_actuator(i).effort_limit(); + } for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); - prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), - VectorXd::Constant(n_u, +175), ui); +// prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), +// VectorXd::Constant(n_u, +175), ui); + prog->AddBoundingBoxConstraint(u_min, + u_max, ui); } Vector3d pt_front_contact(-0.0457, 0.112, 0); diff --git a/examples/Cassie/systems/BUILD.bazel b/examples/Cassie/systems/BUILD.bazel index a07c5c468f..5999b6feca 100644 --- a/examples/Cassie/systems/BUILD.bazel +++ b/examples/Cassie/systems/BUILD.bazel @@ -49,6 +49,17 @@ cc_library( ], ) +cc_library( + name = "variable_time_fsm", + srcs = ["variable_time_fsm.cc"], + hdrs = ["variable_time_fsm.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "cassie_encoder", srcs = ["cassie_encoder.cc"], diff --git a/examples/impact_invariant_control/variable_time_fsm.cc b/examples/Cassie/systems/variable_time_fsm.cc similarity index 55% rename from examples/impact_invariant_control/variable_time_fsm.cc rename to examples/Cassie/systems/variable_time_fsm.cc index f9c07abc15..f336863313 100644 --- a/examples/impact_invariant_control/variable_time_fsm.cc +++ b/examples/Cassie/systems/variable_time_fsm.cc @@ -1,4 +1,6 @@ -#include "examples/impact_invariant_control/variable_time_fsm.h" +#include "examples/Cassie/systems/variable_time_fsm.h" + +#include using std::cout; using std::endl; @@ -10,50 +12,24 @@ using std::string; namespace dairlib { -using systems::OutputVector; using systems::ImpactInfoVector; +using systems::OutputVector; -VariableTimeFiniteStateMachine::VariableTimeFiniteStateMachine( +ContactScheduler::ContactScheduler( const drake::multibody::MultibodyPlant& plant, - const std::vector& states, const std::vector& state_durations, - double t0, double near_impact_threshold, double tau, BLEND_FUNC blend_func) - : ImpactTimeBasedFiniteStateMachine(plant, states, state_durations, t0), - states_(states), - state_durations_(state_durations), - t0_(t0), - near_impact_threshold_(near_impact_threshold), + double near_impact_threshold, double tau, BLEND_FUNC blend_func) + :near_impact_threshold_(near_impact_threshold), blend_func_(blend_func) { - - near_impact_port_ = - this->DeclareVectorOutputPort("near_impact", - ImpactInfoVector(0, 0, 0), - &VariableTimeFiniteStateMachine::CalcNearImpact) - .get_index(); - clock_port_ = this->DeclareVectorOutputPort("clock", - BasicVector(1), - &VariableTimeFiniteStateMachine::CalcClock) + impact_info_port_ = this->DeclareVectorOutputPort( + "near_impact", ImpactInfoVector(0, 0, 0), + &ContactScheduler::CalcNextImpactInfo) + .get_index(); + clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), + &ContactScheduler::CalcClock) + .get_index(); + clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), + &ContactScheduler::CalcClock) .get_index(); - - // Accumulate the durations to get timestamps - double sum = 0; - DRAKE_DEMAND(states.size() == state_durations.size()); - impact_times_.push_back(0); - impact_states_.push_back(states[0]); - for (int i = 0; i < states.size(); ++i) { - sum += state_durations[i]; - accu_state_durations_.push_back(sum); - if (states[i] >= 2) { - impact_times_.push_back(sum); - impact_states_.push_back(states[i+1]); - } - } - - // std::cout << "Impact times: " << std::endl; - // for(int i = 0; i < impact_times_.size(); ++i){ - // std::cout << impact_times_[i] << std::endl; - // } - - period_ = sum; } double alpha_sigmoid(double t, double tau, double near_impact_threshold) { @@ -65,8 +41,9 @@ double alpha_exp(double t, double tau, double near_impact_threshold) { return 1 - exp(-(t + near_impact_threshold) / tau); } -void VariableTimeFiniteStateMachine::CalcNearImpact( - const Context& context, ImpactInfoVector* near_impact) const { +void ContactScheduler::CalcNextImpactInfo( + const Context& context, + ImpactInfoVector* near_impact) const { // Read in lcm message time const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); @@ -101,8 +78,8 @@ void VariableTimeFiniteStateMachine::CalcNearImpact( } } -void VariableTimeFiniteStateMachine::CalcClock( - const Context& context, BasicVector* clock) const { +void ContactScheduler::CalcClock(const Context& context, + BasicVector* clock) const { // Read in lcm message time const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); diff --git a/examples/impact_invariant_control/variable_time_fsm.h b/examples/Cassie/systems/variable_time_fsm.h similarity index 77% rename from examples/impact_invariant_control/variable_time_fsm.h rename to examples/Cassie/systems/variable_time_fsm.h index e89bc01970..09c7a36b7b 100644 --- a/examples/impact_invariant_control/variable_time_fsm.h +++ b/examples/Cassie/systems/variable_time_fsm.h @@ -2,7 +2,6 @@ #include -#include "systems/controllers/time_based_fsm.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" @@ -13,13 +12,10 @@ namespace dairlib { enum BLEND_FUNC { SIGMOID, EXP }; -class VariableTimeFiniteStateMachine - : public systems::ImpactTimeBasedFiniteStateMachine { +class ContactScheduler : drake::systems::LeafSystem { public: - VariableTimeFiniteStateMachine( + ContactScheduler( const drake::multibody::MultibodyPlant& plant, - const std::vector& states, - const std::vector& state_durations, double t0 = 0, double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); const drake::systems::InputPort& get_input_port_state() const { @@ -31,18 +27,24 @@ class VariableTimeFiniteStateMachine const drake::systems::OutputPort& get_output_port_clock() const { return this->get_output_port(clock_port_); } + const drake::systems::OutputPort& get_output_port_contact_timing() const { + return this->get_output_port(contact_timing_); + } const drake::systems::OutputPort& get_output_port_impact() const { - return this->get_output_port(near_impact_port_); + return this->get_output_port(impact_info_port_); } private: - void CalcNearImpact(const drake::systems::Context& context, + void CalcNextImpactInfo(const drake::systems::Context& context, systems::ImpactInfoVector* near_impact) const; void CalcClock(const drake::systems::Context& context, drake::systems::BasicVector* clock) const; - int near_impact_port_; + int state_port_; + int fsm_port_; int clock_port_; + int contact_timing_; + int impact_info_port_; double t0_; std::vector states_; diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index aecada4a67..f9e7e2821e 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -32,7 +32,6 @@ DirconTrajectory::DirconTrajectory( LcmTrajectory::Trajectory state_traj; LcmTrajectory::Trajectory state_derivative_traj; LcmTrajectory::Trajectory force_traj; - LcmTrajectory::Trajectory impulse_traj; state_traj.traj_name = "state_traj" + std::to_string(mode); state_traj.datapoints = x[mode]; @@ -64,15 +63,6 @@ DirconTrajectory::DirconTrajectory( Eigen::Map(dircon.GetForceSamplesByMode(result, mode).data(), num_forces, force_traj.time_vector.size()); - // Impulse vars - if (mode > 0) { - impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); - impulse_traj.datatypes = impulse_names; - // Get start of mode to get time of impulse - impulse_traj.time_vector = state_breaks[mode].segment(0, 1); - impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode)); - } - // Collocation force vars if (state_breaks[mode].size() > 1) { LcmTrajectory::Trajectory collocation_force_traj; @@ -112,12 +102,29 @@ DirconTrajectory::DirconTrajectory( AddTrajectory(state_traj.traj_name, state_traj); AddTrajectory(state_derivative_traj.traj_name, state_derivative_traj); AddTrajectory(force_traj.traj_name, force_traj); - AddTrajectory(impulse_traj.traj_name, impulse_traj); x_.push_back(&state_traj); xdot_.push_back(&state_derivative_traj); lambda_.push_back(&force_traj); - impulse_.push_back(&impulse_traj); + // Impulse vars + LcmTrajectory::Trajectory impulse_traj; + if (mode > 0) { + impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); + // Check to make sure an impact occurs + if (dircon.impulse_vars(mode - 1).size() == 0){ + impulse_traj.datatypes = impulse_names;5 + // Get start of mode to get time of impulse + impulse_traj.time_vector = state_breaks[mode].segment(0, 1); + impulse_traj.datapoints = VectorXd::Zero(impulse_names.size()); + }else{ + impulse_traj.datatypes = impulse_names; + // Get start of mode to get time of impulse + impulse_traj.time_vector = state_breaks[mode].segment(0, 1); + impulse_traj.datapoints = result.GetSolution(dircon.impulse_vars(mode - 1)); + } + AddTrajectory(impulse_traj.traj_name, impulse_traj); + impulse_.push_back(&impulse_traj); + } } // Input trajectory diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index d2039689eb..c990a8bd38 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -101,7 +101,11 @@ lcmt_saved_traj LcmTrajectory::GenerateLcmObject() const { cpp_traj->time_vector.data(), cpp_traj->time_vector.data() + cpp_traj->time_vector.size()); traj_block.datatypes = vector(cpp_traj->datatypes); + std::cout << "memcpy: " << std::endl; + std::cout << traj_block.trajectory_name << std::endl; for (int i = 0; i < traj_block.num_datatypes; ++i) { +// std::cout << "num dtypes: " << traj_block.num_datatypes << std::endl; + // Temporary copy due to underlying data of Eigen::Matrix // being column major VectorXd tempRow = cpp_traj->datapoints.row(i); From cfa6286332943d20665efbc9acbddafd5b764e18 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 24 Jun 2022 15:59:28 -0400 Subject: [PATCH 234/758] removing couts and typos --- examples/Cassie/run_dircon_jumping.cc | 2 +- lcm/dircon_saved_trajectory.cc | 2 +- lcm/lcm_trajectory.cc | 4 ---- 3 files changed, 2 insertions(+), 6 deletions(-) diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index b38e9dcdac..25284a30b2 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -332,7 +332,7 @@ void DoMain() { prog.SetSolverOption(id, "Solution", "No"); // target nonlinear constraint violation - prog.SetSolverOption(id, "Major optimality tolerance", 1e-5 / FLAGS_cost_scaling); + prog.SetSolverOption(id, "Major optimality tolerance", 1e-7 / FLAGS_cost_scaling); // target complementarity gap prog.SetSolverOption(id, "Major feasibility tolerance", tol); diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index f9e7e2821e..4c2fc4167e 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -112,7 +112,7 @@ DirconTrajectory::DirconTrajectory( impulse_traj.traj_name = "impulse_vars" + std::to_string(mode); // Check to make sure an impact occurs if (dircon.impulse_vars(mode - 1).size() == 0){ - impulse_traj.datatypes = impulse_names;5 + impulse_traj.datatypes = impulse_names; // Get start of mode to get time of impulse impulse_traj.time_vector = state_breaks[mode].segment(0, 1); impulse_traj.datapoints = VectorXd::Zero(impulse_names.size()); diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index c990a8bd38..d2039689eb 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -101,11 +101,7 @@ lcmt_saved_traj LcmTrajectory::GenerateLcmObject() const { cpp_traj->time_vector.data(), cpp_traj->time_vector.data() + cpp_traj->time_vector.size()); traj_block.datatypes = vector(cpp_traj->datatypes); - std::cout << "memcpy: " << std::endl; - std::cout << traj_block.trajectory_name << std::endl; for (int i = 0; i < traj_block.num_datatypes; ++i) { -// std::cout << "num dtypes: " << traj_block.num_datatypes << std::endl; - // Temporary copy due to underlying data of Eigen::Matrix // being column major VectorXd tempRow = cpp_traj->datapoints.row(i); From 075b5640ebd8107fd5ae80e0fed05822db2052da Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 25 Jun 2022 22:12:44 -0400 Subject: [PATCH 235/758] addressing comments --- WORKSPACE | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/WORKSPACE b/WORKSPACE index e42f784543..14bc1615a9 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,9 +11,9 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "a6005354c97db4160d67ee735b1e01efcd633d9b" +DRAKE_COMMIT = "0b90deb0553a1a8cfa392371ef5c4c49ec024912" -DRAKE_CHECKSUM = "708cc2f868be1b07c87c730ffb423b87b0cd6120f7e9e7fe65b56139c832704a" +DRAKE_CHECKSUM = "b281c4c0c77819bdb9ff1be47a02e4ef0400b333693be6be24e5a9577753f416" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. # DRAKE_CHECKSUM = "0" * 64 From f595fe2b75cb92fcd916013b43d161e07f0e6d5a Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 25 Jun 2022 22:29:22 -0400 Subject: [PATCH 236/758] modifying cirrus file for compiler version --- .cirrus.yml | 2 ++ examples/Cassie/osc/solver_settings/osqp_options_walking.yaml | 2 +- solvers/osqp_options_default.yaml | 2 +- 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.cirrus.yml b/.cirrus.yml index a13aa2af2d..9caee7ec70 100644 --- a/.cirrus.yml +++ b/.cirrus.yml @@ -23,6 +23,8 @@ build_focal_task: cpu: 8 memory: 24 test_script: + - export CC=clang-12 + - export CXX=clang++-12 - bazel build --define=WITH_SNOPT=OFF --local_ram_resources=24000 diff --git a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml index 50822be399..d9ca698535 100644 --- a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml +++ b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml @@ -10,7 +10,7 @@ linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 3 -verbose: 1 +verbose: 0 scaled_termination: 1 check_termination: 25 warm_start: 1 diff --git a/solvers/osqp_options_default.yaml b/solvers/osqp_options_default.yaml index e87aadf35b..68b6ab24df 100644 --- a/solvers/osqp_options_default.yaml +++ b/solvers/osqp_options_default.yaml @@ -10,7 +10,7 @@ linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 3 -verbose: 1 +verbose: 0 scaled_termination: 1 check_termination: 25 warm_start: 1 From a92f2f2b07a7f9069ecca142f198acd554171aa2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 25 Jun 2022 22:37:09 -0400 Subject: [PATCH 237/758] adding clang-12 install to dockerfile --- install/focal/Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/install/focal/Dockerfile b/install/focal/Dockerfile index 1702e75456..c3c78e1928 100644 --- a/install/focal/Dockerfile +++ b/install/focal/Dockerfile @@ -2,7 +2,7 @@ FROM ros:noetic-ros-base-focal WORKDIR /dairlib ENV DAIRLIB_DOCKER_VERSION_25=25 COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python +RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python clang-12 RUN set -eux \ && apt-get install --no-install-recommends locales \ && locale-gen en_US.UTF-8 From 0a48cdf92399ddbcddc3d72038d21bc522716f97 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 27 Jun 2022 14:50:17 -0400 Subject: [PATCH 238/758] reoptimizing box jumping --- examples/Cassie/run_dircon_jumping.cc | 244 +++++++++++--------- examples/Cassie/systems/variable_time_fsm.h | 2 + 2 files changed, 139 insertions(+), 107 deletions(-) diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 25284a30b2..f6f881edef 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -1,7 +1,7 @@ #include +#include #include #include -#include #include #include @@ -256,12 +256,18 @@ void DoMain() { /**** * Mode duration constraints */ +// auto crouch_mode = DirconMode(double_stance_constraints, +// stance_knotpoints, 0.5, 0.75); +// auto flight_mode = DirconMode(flight_phase_constraints, +// flight_phase_knotpoints, 0.25, 0.5); +// auto land_mode = DirconMode(double_stance_constraints, +// stance_knotpoints, 0.4, 0.6); auto crouch_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.5, 0.75); + stance_knotpoints, 0.0, 1.0); auto flight_mode = DirconMode(flight_phase_constraints, - flight_phase_knotpoints, 0.25, 0.5); + flight_phase_knotpoints, 0.0, 1.0); auto land_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.4, 0.6); + stance_knotpoints, 0.0, 1.0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); @@ -332,7 +338,8 @@ void DoMain() { prog.SetSolverOption(id, "Solution", "No"); // target nonlinear constraint violation - prog.SetSolverOption(id, "Major optimality tolerance", 1e-7 / FLAGS_cost_scaling); + prog.SetSolverOption(id, "Major optimality tolerance", + 1e-5 / FLAGS_cost_scaling); // target complementarity gap prog.SetSolverOption(id, "Major feasibility tolerance", tol); @@ -403,7 +410,7 @@ void DoMain() { void SetKinematicConstraints(Dircon* trajopt, const MultibodyPlant& plant) { - auto *prog = &trajopt->prog(); + auto* prog = &trajopt->prog(); // Create maps for joints map pos_map = multibody::MakeNameToPositionsMap(plant); map vel_map = multibody::MakeNameToVelocitiesMap(plant); @@ -435,7 +442,7 @@ void SetKinematicConstraints(Dircon* trajopt, // position constraints prog->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, - x_0(pos_map.at("base_x"))); + x_0(pos_map.at("base_x"))); prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); @@ -449,10 +456,9 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); - prog->AddBoundingBoxConstraint(0.00, 0.1, - x_0(pos_map.at("hip_roll_left"))); + prog->AddBoundingBoxConstraint(0.00, 0.1, x_0(pos_map.at("hip_roll_left"))); prog->AddBoundingBoxConstraint(-0.1, -0.00, - x_0(pos_map.at("hip_roll_right"))); + x_0(pos_map.at("hip_roll_right"))); // hip yaw and roll constraints prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); @@ -465,20 +471,20 @@ void SetKinematicConstraints(Dircon* trajopt, // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, - x_0(pos_map.at("base_z"))); + x_0(pos_map.at("base_z"))); if (FLAGS_height < 0) { prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, - 0.5 * FLAGS_height + rest_height - eps, - x_top(pos_map.at("base_z"))); + 0.5 * FLAGS_height + rest_height - eps, + x_top(pos_map.at("base_z"))); } else { prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, - FLAGS_height + rest_height + eps, - x_top(pos_map.at("base_z"))); + FLAGS_height + rest_height + eps, + x_top(pos_map.at("base_z"))); } prog->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, - 0.8 * FLAGS_height + rest_height + eps, - x_f(pos_map.at("base_z"))); + 0.8 * FLAGS_height + rest_height + eps, + x_f(pos_map.at("base_z"))); // Zero starting and final velocities prog->AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); @@ -525,16 +531,17 @@ void SetKinematicConstraints(Dircon* trajopt, trajopt->AddConstraintToAllKnotPoints( x_0(pos_map[sym_joint_name + l_r_pair.first]) == x_0(pos_map[sym_joint_name + l_r_pair.second])); - prog->AddLinearConstraint( - x_f(pos_map[sym_joint_name + l_r_pair.first]) == - x_f(pos_map[sym_joint_name + l_r_pair.second])); + prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + l_r_pair.first]) == + x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle - trajopt->AddConstraintToAllKnotPoints( - u_0(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - u_0(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); - trajopt->AddConstraintToAllKnotPoints( - u_f(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) == - u_f(act_map.at(sym_joint_name + l_r_pair.second + "_motor"))); + // trajopt->AddConstraintToAllKnotPoints( + // u_0(act_map.at(sym_joint_name + l_r_pair.first + + // "_motor")) == u_0(act_map.at(sym_joint_name + + // l_r_pair.second + "_motor"))); + // trajopt->AddConstraintToAllKnotPoints( + // u_f(act_map.at(sym_joint_name + l_r_pair.first + + // "_motor")) == u_f(act_map.at(sym_joint_name + + // l_r_pair.second + "_motor"))); } } } @@ -556,15 +563,14 @@ void SetKinematicConstraints(Dircon* trajopt, VectorXd u_min(n_u); VectorXd u_max(n_u); for (drake::multibody::JointActuatorIndex i(0); i < n_u; ++i) { - u_min(i) = -plant.get_joint_actuator(i).effort_limit(); - u_max(i) = plant.get_joint_actuator(i).effort_limit(); + u_min(i) = 0.75 * -plant.get_joint_actuator(i).effort_limit(); + u_max(i) = 0.75 * plant.get_joint_actuator(i).effort_limit(); } for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); -// prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), -// VectorXd::Constant(n_u, +175), ui); - prog->AddBoundingBoxConstraint(u_min, - u_max, ui); + // prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), + // VectorXd::Constant(n_u, +175), ui); + prog->AddBoundingBoxConstraint(u_min, u_max, ui); } Vector3d pt_front_contact(-0.0457, 0.112, 0); @@ -711,6 +717,7 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, map act_map = multibody::MakeNameToActuatorsMap(plant); int n_v = plant.num_velocities(); + int n_q = plant.num_positions(); int n_u = plant.num_actuators(); // create joint/motor names @@ -739,83 +746,105 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, } l_r_pairs.pop_back(); - double w_symmetry_pos = FLAGS_cost_scaling * 1e5; - double w_symmetry_vel = FLAGS_cost_scaling * 1e2; - double w_symmetry_u = FLAGS_cost_scaling * 1e2; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& sym_joint_name : sym_joint_names) { - auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - - x(pos_map.at(sym_joint_name + l_r_pair.second)); - auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - - x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); - trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - if (sym_joint_name != "ankle_joint") { - auto act_diff = - u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); - trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } - } - } - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& asy_joint_name : asy_joint_names) { - auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + - x(pos_map.at(asy_joint_name + l_r_pair.second)); - auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + - x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); - trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - if (asy_joint_name != "ankle_joint") { - auto act_diff = - u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); - trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } - } - } + // double w_symmetry_pos = FLAGS_cost_scaling * 1e5; + // double w_symmetry_vel = FLAGS_cost_scaling * 1e2; + // double w_symmetry_u = FLAGS_cost_scaling * 1e2; + // for (const auto& l_r_pair : l_r_pairs) { + // for (const auto& sym_joint_name : sym_joint_names) { + // auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - + // x(pos_map.at(sym_joint_name + l_r_pair.second)); + // auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) + // - + // x(vel_map.at(sym_joint_name + l_r_pair.second + + // "dot")); + // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + // if (sym_joint_name != "ankle_joint") { + // auto act_diff = + // u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + // u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + // } + // } + // } + // for (const auto& l_r_pair : l_r_pairs) { + // for (const auto& asy_joint_name : asy_joint_names) { + // auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + + // x(pos_map.at(asy_joint_name + l_r_pair.second)); + // auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + // + + // x(vel_map.at(asy_joint_name + l_r_pair.second + + // "dot")); + // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + // if (asy_joint_name != "ankle_joint") { + // auto act_diff = + // u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + // u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + // } + // } + // } MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); - MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); - R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = - 5e-1; - R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) = - 5e-1; - R(act_map.at("hip_yaw_left_motor"), act_map.at("hip_yaw_left_motor")) = 5e-1; - R(act_map.at("hip_yaw_right_motor"), act_map.at("hip_yaw_right_motor")) = - 5e-1; - R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) = - 5e-5; - R(act_map.at("hip_pitch_right_motor"), act_map.at("hip_pitch_right_motor")) = - 5e-5; + // MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = + // 5e-1; + // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) + // = + // 5e-1; + // R(act_map.at("hip_yaw_left_motor"), act_map.at("hip_yaw_left_motor")) = + // 5e-1; R(act_map.at("hip_yaw_right_motor"), + // act_map.at("hip_yaw_right_motor")) = + // 5e-1; + // R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) + // = + // 5e-5; + // R(act_map.at("hip_pitch_right_motor"), + // act_map.at("hip_pitch_right_motor")) = + // 5e-5; Q *= FLAGS_cost_scaling; - R *= FLAGS_cost_scaling; + // R *= FLAGS_cost_scaling; trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); - trajopt->AddRunningCost(u.transpose() * R * u); + VectorXd q_f = VectorXd::Zero(n_q); + // VectorXd quat_identity(4); + // quat_identity << 1, 0, 0, 0; + // q_f.head(4) = quat_identity; + q_f(pos_map.at("hip_yaw_left")) = 0; + q_f(pos_map.at("hip_yaw_right")) = 0; + q_f(pos_map.at("hip_roll_left")) = 0; + q_f(pos_map.at("hip_roll_right")) = 0; + q_f(pos_map.at("base_z")) = 0.8 * FLAGS_height + FLAGS_start_height; + VectorXd q_f_target = q_f.segment(4, 9); - vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, - FLAGS_knot_points}; - MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); - W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; - W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; - W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; - W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; - W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; - W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; - W *= 2.0 * FLAGS_cost_scaling; - vector> joint_accel_costs; - for (int mode : {0, 1, 2}) { - joint_accel_costs.push_back(std::make_shared( - W, plant, &constraints->mode(mode).evaluators())); - for (int index = 0; index < mode_lengths[mode]; index++) { - // Assumes mode_lengths are the same across modes - auto x_i = trajopt->state_vars(mode, index); - auto u_i = trajopt->input_vars(mode, index); - auto l_i = trajopt->force_vars(mode, index); - trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - } - } + trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + trajopt->AddRunningCost((x.segment(4, 9) - q_f_target).transpose() * Q * + (x.segment(4, 9) - q_f_target)); + // trajopt->AddRunningCost(u.transpose() * R * u); + + // vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, + // FLAGS_knot_points}; + // MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + // W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; + // W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; + // W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; + // W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; + // W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + // W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + // W *= 2.0 * FLAGS_cost_scaling; + // vector> joint_accel_costs; + // for (int mode : {0, 1, 2}) { + // joint_accel_costs.push_back(std::make_shared( + // W, plant, &constraints->mode(mode).evaluators())); + // for (int index = 0; index < mode_lengths[mode]; index++) { + // // Assumes mode_lengths are the same across modes + // auto x_i = trajopt->state_vars(mode, index); + // auto u_i = trajopt->input_vars(mode, index); + // auto l_i = trajopt->force_vars(mode, index); + // trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + // } + // } } /****** @@ -935,10 +964,11 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); trajopt.SetInitialTrajectory(input_traj, state_traj); -// for (int mode = 0; mode < trajopt.num_modes(); ++mode) { -// trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], -// lambda_c_traj[mode], gamma_traj[mode]); -// } + // for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + // trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], + // lambda_c_traj[mode], + // gamma_traj[mode]); + // } } } // namespace dairlib diff --git a/examples/Cassie/systems/variable_time_fsm.h b/examples/Cassie/systems/variable_time_fsm.h index 09c7a36b7b..585bdb8ae9 100644 --- a/examples/Cassie/systems/variable_time_fsm.h +++ b/examples/Cassie/systems/variable_time_fsm.h @@ -46,6 +46,8 @@ class ContactScheduler : drake::systems::LeafSystem { int contact_timing_; int impact_info_port_; + const drake::multibody::MultibodyPlant& plant_; + double t0_; std::vector states_; std::vector state_durations_; From 9b0bfd75ae90e5b919f458efeba4a4c1e5aff08d Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 28 Jun 2022 14:37:04 -0400 Subject: [PATCH 239/758] working on contact scheduler --- bindings/pydairlib/analysis/BUILD.bazel | 1 + .../cassie/gym_envs/mujoco_cassie_gym.py | 15 ++- bindings/pydairlib/cassie/learn_osc_gains.py | 7 +- .../osc_run/learned_osc_running_gains.yaml | 38 +++--- examples/Cassie/run_dircon_jumping.cc | 126 +++++++++++------- examples/Cassie/run_osc_jumping_controller.cc | 2 +- examples/Cassie/systems/BUILD.bazel | 4 +- ...iable_time_fsm.cc => contact_scheduler.cc} | 2 +- ...ariable_time_fsm.h => contact_scheduler.h} | 2 +- .../osc/operational_space_control.cc | 9 +- .../trajectory_optimization/dircon/dircon.h | 2 +- 11 files changed, 124 insertions(+), 84 deletions(-) rename examples/Cassie/systems/{variable_time_fsm.cc => contact_scheduler.cc} (98%) rename examples/Cassie/systems/{variable_time_fsm.h => contact_scheduler.h} (96%) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 212995a207..56747fa6c9 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -93,6 +93,7 @@ py_binary( "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", + "//lcmtypes:lcmtypes_robot_archive_py", "//lcmtypes:lcmtypes_robot_py", ], ) diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 1023e033e5..e8e1d58178 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -200,21 +200,21 @@ def step(self, action=np.zeros(18)): u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) self.drake_sim.AdvanceTo(next_timestep) - self.reward_func.reset_clock_reward() + # self.reward_func.reset_clock_reward() while self.simulator.time() < next_timestep: self.simulator.step(cassie_in) foot_pos = self.simulator.foot_pos() - self.reward_func.update_clock_reward(self.simulator.get_foot_forces(), foot_pos, - self.simulator.xquat("left-foot"), self.simulator.xquat("right-foot")) + # self.reward_func.update_clock_reward(self.simulator.get_foot_forces(), foot_pos, + # self.simulator.xquat("left-foot"), self.simulator.xquat("right-foot")) if self.visualize: self.cassie_vis.draw(self.simulator) self.current_time = next_timestep t = self.simulator.time() - q = np.copy(self.simulator.qpos()) - v = np.copy(self.simulator.qvel()) - q, v = self.drake_to_mujoco_converter.convert_to_drake(q, v) + # q = np.copy() + # v = np.copy() + q, v = self.drake_to_mujoco_converter.convert_to_drake(self.simulator.qpos(), self.simulator.qvel()) self.current_time = t x = np.hstack((q, v)) x = reexpress_state_local_to_global_omega(x) @@ -394,7 +394,8 @@ def randomize_sim_params(self): def free_sim(self): del self.simulator - del self.cassie_vis + if self.visualize: + del self.cassie_vis def euler2quat(z=0, y=0, x=0): diff --git a/bindings/pydairlib/cassie/learn_osc_gains.py b/bindings/pydairlib/cassie/learn_osc_gains.py index f4aaaa82d1..9d38471355 100644 --- a/bindings/pydairlib/cassie/learn_osc_gains.py +++ b/bindings/pydairlib/cassie/learn_osc_gains.py @@ -80,7 +80,7 @@ def write_params(self, params): yaml_dump(new_gains, filename=self.osc_running_gains_filename) def get_batch_loss(self, params): - batch_size = 5 + batch_size = 10 batch_reward = 0 for i in range(batch_size): batch_reward += self.get_single_loss(params) @@ -108,6 +108,7 @@ def get_single_loss(self, params): state, reward = gym_env.step(np.zeros(18)) cumulative_reward += reward # print(-cumulative_reward) + gym_env.free_sim() return -cumulative_reward def learn_gains(self, batch=True): @@ -192,8 +193,8 @@ def learn_gains_apex(self): reward_function = RewardOSUDRL() optimizer = OSCGainsOptimizer(budget, reward_function, visualize=False) - # optimizer.learn_gains() - optimizer.learn_gains_apex() + optimizer.learn_gains() + # optimizer.learn_gains_apex() # optimal_params = optimizer.load_params('2022_06_09_15_500', optimizer.drake_params_folder).value # optimizer.write_params(optimal_params) diff --git a/examples/Cassie/osc_run/learned_osc_running_gains.yaml b/examples/Cassie/osc_run/learned_osc_running_gains.yaml index 4c4603c78b..dfc74fe8df 100644 --- a/examples/Cassie/osc_run/learned_osc_running_gains.yaml +++ b/examples/Cassie/osc_run/learned_osc_running_gains.yaml @@ -1,19 +1,19 @@ -FootstepKd: [0.24014605123137836, 0.0, 0.0, 0.0, 0.5215537630402741, 0.0, 0.0, 0.0, - 0.10406524421712957] +FootstepKd: [0.03177352249613004, 0.0, 0.0, 0.0, 0.4389937568136904, 0.0, 0.0, 0.0, + 0.12716547061955297] LiftoffSwingFootKd: [5, 0, 0, 0, 5, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, 0, 0, 35] LiftoffSwingFootW: [1, 0, 0, 0, 1, 0, 0, 0, 1] -PelvisKd: [3.313929750151991, 0.0, 0.0, 0.0, 7.291707347196438, 0.0, 0.0, 0.0, 9.813500192113974] -PelvisKp: [38.559293759237576, 0.0, 0.0, 0.0, 9.609034361274885, 0.0, 0.0, 0.0, 50.194944722723434] -PelvisRotKd: [12.210892635723313, 0.0, 0.0, 0.0, 5.513701361351321, 0.0, 0.0, 0.0, - 3.756526642513079] +PelvisKd: [0.5890737665487785, 0.0, 0.0, 0.0, 0.3065697740681626, 0.0, 0.0, 0.0, 3.575709536524337] +PelvisKp: [16.038541830836348, 0.0, 0.0, 0.0, 3.9843429704843962, 0.0, 0.0, 0.0, 51.84941416797943] +PelvisRotKd: [10.004676756212609, 0.0, 0.0, 0.0, 3.3726977593874716, 0.0, 0.0, 0.0, + 4.360440654654406] PelvisRotKp: [400.0, 0, 0, 0, 200.0, 0, 0, 0, 0.0] PelvisRotW: [5, 0, 0, 0, 1, 0, 0, 0, 5] PelvisW: [0, 0, 0, 0, 0, 0, 0, 0, 5] -SwingFootKd: [8.052187951590337, 0.0, 0.0, 0.0, 7.941424047902412, 0.0, 0.0, 0.0, - 4.740321014078774] -SwingFootKp: [119.02780136838098, 0.0, 0.0, 0.0, 86.4442874886555, 0.0, 0.0, 0.0, - 68.66666275104173] +SwingFootKd: [7.706143205070923, 0.0, 0.0, 0.0, 5.241286582894659, 0.0, 0.0, 0.0, + 1.127060223432193] +SwingFootKp: [145.14247825584522, 0.0, 0.0, 0.0, 79.71734912124174, 0.0, 0.0, 0.0, + 71.26378559542337] SwingFootW: [10, 0, 0, 0, 100, 0, 0, 0, 5] W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] @@ -22,17 +22,17 @@ W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] ekf_filter_tau: [0.05, 0.01, 0.01] flight_duration: 0.1 -footstep_lateral_offset: 0.006256616070335045 -footstep_sagital_offset: 0.08033678283597007 +footstep_lateral_offset: 0.011344974721002179 +footstep_sagital_offset: 0.006634618253487809 hip_yaw_kd: 1 -hip_yaw_kp: 49.45039358599729 +hip_yaw_kp: 34.98541652922292 impact_tau: 0.05 impact_threshold: 0.1 -mid_foot_height: 0.04698180774188275 -mu: 0.5968077063775069 +mid_foot_height: 0.05032695569729413 +mu: 0.4715404404999052 relative_feet: true relative_pelvis: true -rest_length: 0.965295603135476 +rest_length: 0.9560136356226284 stance_duration: 0.2 swing_toe_kd: 10 swing_toe_kp: 1500 @@ -40,8 +40,8 @@ vel_scale_rot: -0.5 vel_scale_trans_lateral: -0.15 vel_scale_trans_sagital: 0.25 w_accel: 0.0001 -w_hip_yaw: 1.6983797290405045 +w_hip_yaw: 5.41862598246515 w_input: 0.0 -w_input_reg: 0.00015457437376796958 -w_soft_constraint: 239.7104282566615 +w_input_reg: 0.00022359024445701495 +w_soft_constraint: 70.59455850641295 w_swing_toe: 1 diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index f6f881edef..1644c5403a 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -256,18 +256,18 @@ void DoMain() { /**** * Mode duration constraints */ -// auto crouch_mode = DirconMode(double_stance_constraints, -// stance_knotpoints, 0.5, 0.75); -// auto flight_mode = DirconMode(flight_phase_constraints, -// flight_phase_knotpoints, 0.25, 0.5); -// auto land_mode = DirconMode(double_stance_constraints, -// stance_knotpoints, 0.4, 0.6); + // auto crouch_mode = DirconMode(double_stance_constraints, + // stance_knotpoints, 0.5, 0.75); + // auto flight_mode = DirconMode(flight_phase_constraints, + // flight_phase_knotpoints, 0.25, 0.5); + // auto land_mode = DirconMode(double_stance_constraints, + // stance_knotpoints, 0.4, 0.6); auto crouch_mode = DirconMode(double_stance_constraints, stance_knotpoints, 0.0, 1.0); auto flight_mode = DirconMode(flight_phase_constraints, flight_phase_knotpoints, 0.0, 1.0); auto land_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.0, 1.0); + stance_knotpoints, 0.4, 1.0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); @@ -371,7 +371,9 @@ void DoMain() { } double alpha = .2; - int num_poses = std::min(FLAGS_knot_points, 5); +// int num_poses = std::min(FLAGS_knot_points + 1, 3); + int num_poses = std::max((int)(mode_lengths.size() + 1), FLAGS_knot_points); +// int num_poses = mode_lengths.size() * FLAGS_knot_points - 1; trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); cout << "\nChoose the best solver: " @@ -528,9 +530,11 @@ void SetKinematicConstraints(Dircon* trajopt, // Symmetry constraints for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { - trajopt->AddConstraintToAllKnotPoints( - x_0(pos_map[sym_joint_name + l_r_pair.first]) == - x_0(pos_map[sym_joint_name + l_r_pair.second])); + // trajopt->AddConstraintToAllKnotPoints( + // x_0(pos_map[sym_joint_name + l_r_pair.first]) == + // x_0(pos_map[sym_joint_name + l_r_pair.second])); + prog->AddLinearConstraint(x_0(pos_map[sym_joint_name + l_r_pair.first]) == + x_0(pos_map[sym_joint_name + l_r_pair.second])); prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + l_r_pair.first]) == x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle @@ -586,12 +590,23 @@ void SetKinematicConstraints(Dircon* trajopt, std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), -0.15 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + auto left_foot_z_ground_constraint = + std::make_shared>( + plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); + auto right_foot_z_ground_constraint = + std::make_shared>( + plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); + for (int mode : {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); prog->AddConstraint(left_foot_y_constraint, x_i.head(n_q)); prog->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); + prog->AddConstraint(left_foot_z_ground_constraint, x_i.head(n_q)); + prog->AddConstraint(right_foot_z_ground_constraint, x_i.head(n_q)); } } @@ -635,19 +650,21 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddConstraint(left_foot_x_constraint, x_f.head(n_q)); prog->AddConstraint(right_foot_x_constraint, x_f.head(n_q)); + // Foot ground clearance constraint + // Foot clearance constraint - auto left_foot_z_constraint = + auto left_foot_z_box_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); - auto right_foot_z_constraint = + auto right_foot_z_box_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); - prog->AddConstraint(left_foot_z_constraint, x_top.head(n_q)); - prog->AddConstraint(right_foot_z_constraint, x_top.head(n_q)); + prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); auto left_foot_rear_z_final_constraint = std::make_shared>( @@ -786,8 +803,9 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, // } // } - MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); - // MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); + MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); + MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = // 5e-1; // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) @@ -805,8 +823,8 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, // 5e-5; Q *= FLAGS_cost_scaling; - // R *= FLAGS_cost_scaling; - trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + R *= FLAGS_cost_scaling; + trajopt->AddRunningCost(x.tail(n_v - 3).transpose() * Q * x.tail(n_v - 3)); VectorXd q_f = VectorXd::Zero(n_q); // VectorXd quat_identity(4); // quat_identity << 1, 0, 0, 0; @@ -815,36 +833,48 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, q_f(pos_map.at("hip_yaw_right")) = 0; q_f(pos_map.at("hip_roll_left")) = 0; q_f(pos_map.at("hip_roll_right")) = 0; + std::cout << pos_map.at("hip_yaw_left") << std::endl; + std::cout << pos_map.at("hip_yaw_right") << std::endl; + std::cout << pos_map.at("hip_roll_left") << std::endl; + std::cout << pos_map.at("hip_roll_right") << std::endl; q_f(pos_map.at("base_z")) = 0.8 * FLAGS_height + FLAGS_start_height; - VectorXd q_f_target = q_f.segment(4, 9); - - trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); - trajopt->AddRunningCost((x.segment(4, 9) - q_f_target).transpose() * Q * - (x.segment(4, 9) - q_f_target)); - // trajopt->AddRunningCost(u.transpose() * R * u); - - // vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, - // FLAGS_knot_points}; - // MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); - // W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; - // W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; - // W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; - // W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; - // W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; - // W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; - // W *= 2.0 * FLAGS_cost_scaling; - // vector> joint_accel_costs; - // for (int mode : {0, 1, 2}) { - // joint_accel_costs.push_back(std::make_shared( - // W, plant, &constraints->mode(mode).evaluators())); - // for (int index = 0; index < mode_lengths[mode]; index++) { - // // Assumes mode_lengths are the same across modes - // auto x_i = trajopt->state_vars(mode, index); - // auto u_i = trajopt->input_vars(mode, index); - // auto l_i = trajopt->force_vars(mode, index); - // trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - // } - // } + VectorXd q_f_target_left = q_f.segment(4, 5); + VectorXd q_f_target_right = q_f.segment(13, 2); + + MatrixXd Q_left = 0.02 * MatrixXd::Identity(5, 5); + MatrixXd Q_right = 0.02 * MatrixXd::Identity(2, 2); + Q_left *= FLAGS_cost_scaling; + Q_right *= FLAGS_cost_scaling; + + // trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); +// trajopt->AddRunningCost((x.segment(4, 5) - q_f_target_left).transpose() * +// Q_left * (x.segment(4, 5) - q_f_target_left)); +// trajopt->AddRunningCost((x.segment(13, 2) - q_f_target_right).transpose() * +// Q_right * (x.segment(13, 2) - q_f_target_right)); +// trajopt->AddRunningCost(u.transpose() * R * u); +// +// vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, +// FLAGS_knot_points}; +// MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); +// W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; +// W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; +// W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; +// W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; +// W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; +// W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; +// W *= 2.0 * FLAGS_cost_scaling; +// vector> joint_accel_costs; +// for (int mode : {0, 1, 2}) { +// joint_accel_costs.push_back(std::make_shared( +// W, plant, &constraints->mode(mode).evaluators())); +// for (int index = 0; index < mode_lengths[mode]; index++) { +// // Assumes mode_lengths are the same across modes +// auto x_i = trajopt->state_vars(mode, index); +// auto u_i = trajopt->input_vars(mode, index); +// auto l_i = trajopt->force_vars(mode, index); +// trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); +// } +// } } /****** diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 9ee9700c7c..7ad5333261 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -239,7 +239,7 @@ int DoMain(int argc, char* argv[]) { pelvis_trans_traj = pelvis_trans_traj + offset_traj; /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm; auto state_receiver = builder.AddSystem(plant_w_spr); diff --git a/examples/Cassie/systems/BUILD.bazel b/examples/Cassie/systems/BUILD.bazel index 5999b6feca..4d24c8324a 100644 --- a/examples/Cassie/systems/BUILD.bazel +++ b/examples/Cassie/systems/BUILD.bazel @@ -51,8 +51,8 @@ cc_library( cc_library( name = "variable_time_fsm", - srcs = ["variable_time_fsm.cc"], - hdrs = ["variable_time_fsm.h"], + srcs = ["contact_scheduler.cc"], + hdrs = ["contact_scheduler.h"], deps = [ "//lcmtypes:lcmt_robot", "//systems/primitives", diff --git a/examples/Cassie/systems/variable_time_fsm.cc b/examples/Cassie/systems/contact_scheduler.cc similarity index 98% rename from examples/Cassie/systems/variable_time_fsm.cc rename to examples/Cassie/systems/contact_scheduler.cc index f336863313..1d7d6e7f85 100644 --- a/examples/Cassie/systems/variable_time_fsm.cc +++ b/examples/Cassie/systems/contact_scheduler.cc @@ -1,4 +1,4 @@ -#include "examples/Cassie/systems/variable_time_fsm.h" +#include "examples/Cassie/systems/contact_scheduler.h" #include diff --git a/examples/Cassie/systems/variable_time_fsm.h b/examples/Cassie/systems/contact_scheduler.h similarity index 96% rename from examples/Cassie/systems/variable_time_fsm.h rename to examples/Cassie/systems/contact_scheduler.h index 585bdb8ae9..28065498b6 100644 --- a/examples/Cassie/systems/variable_time_fsm.h +++ b/examples/Cassie/systems/contact_scheduler.h @@ -46,7 +46,7 @@ class ContactScheduler : drake::systems::LeafSystem { int contact_timing_; int impact_info_port_; - const drake::multibody::MultibodyPlant& plant_; +// const drake::multibody::MultibodyPlant& plant_; double t0_; std::vector states_; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index e6ea33f0a5..6cadb5ed02 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -699,8 +699,15 @@ VectorXd OperationalSpaceControl::SolveQp( // J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - // ddy_t), 0.5 * constant_term.transpose() * W * constant_term, // true); +// Eigen::EigenSolver b(J_t.transpose() * W * J_t,false); +// cout<<" Eigen values are: \n "< ldlt_solver; +// ldlt_solver.compute(J_t.transpose() * W * J_t); + // std::cout << J_t.rows() << ", " << J_t.cols() << std::endl; +// std::cout << W.rows() << ", " << W.cols() << std::endl; +// std::cout << ldlt_solver.isPositive() << std::endl; tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), + (J_t.transpose() * W) * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), constant_term.transpose() * W * constant_term, true); // tracking_cost_.at(i)->UpdateCoefficients( // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * diff --git a/systems/trajectory_optimization/dircon/dircon.h b/systems/trajectory_optimization/dircon/dircon.h index 6316b68680..6ac4ef9721 100644 --- a/systems/trajectory_optimization/dircon/dircon.h +++ b/systems/trajectory_optimization/dircon/dircon.h @@ -95,7 +95,7 @@ class Dircon /// /// Creates a callback using a single pose count parameter, num_poses /// Evenly divides the poses among the different modes, weighting by number - /// of frames in that mode. Since start/end poses per mdoe are required, must + /// of frames in that mode. Since start/end poses per mode are required, must /// have num_poses >= num_modes + 1 void CreateVisualizationCallback(std::string model_file, unsigned int num_poses, double alpha, From b75d24ba2f5a02c878e05e9f9f0c8c53432275c5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 28 Jun 2022 17:16:49 -0400 Subject: [PATCH 240/758] working on initial attempt at kinodynamic planning for contact scheduling --- examples/Cassie/contact_scheduler/BUILD.bazel | 40 + .../contact_scheduler.cc | 2 +- .../contact_scheduler.h | 0 .../contact_scheduler/kinodynamic_planner.cc | 728 ++++++++++++++++++ .../contact_scheduler/kinodynamic_planner.h | 211 +++++ .../contact_scheduler/kinodynamic_settings.h | 37 + .../kinodynamic_settings.yaml | 10 + examples/Cassie/systems/BUILD.bazel | 11 - 8 files changed, 1027 insertions(+), 12 deletions(-) create mode 100644 examples/Cassie/contact_scheduler/BUILD.bazel rename examples/Cassie/{systems => contact_scheduler}/contact_scheduler.cc (98%) rename examples/Cassie/{systems => contact_scheduler}/contact_scheduler.h (100%) create mode 100644 examples/Cassie/contact_scheduler/kinodynamic_planner.cc create mode 100644 examples/Cassie/contact_scheduler/kinodynamic_planner.h create mode 100644 examples/Cassie/contact_scheduler/kinodynamic_settings.h create mode 100644 examples/Cassie/contact_scheduler/kinodynamic_settings.yaml diff --git a/examples/Cassie/contact_scheduler/BUILD.bazel b/examples/Cassie/contact_scheduler/BUILD.bazel new file mode 100644 index 0000000000..3ac559dbd8 --- /dev/null +++ b/examples/Cassie/contact_scheduler/BUILD.bazel @@ -0,0 +1,40 @@ +# -*- mode: python -*- +# vi: set ft=python : + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "contact_scheduler", + srcs = ["contact_scheduler.cc"], + hdrs = ["contact_scheduler.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "kinodynamic_planner", + srcs = ["kinodynamic_planner.cc"], + hdrs = ["kinodynamic_planner.h"], + deps = [ + ":kinodynamic_settings", + "//lcmtypes:lcmt_robot", + "//multibody:multibody_solvers", + "//solvers:fast_osqp_solver", + "//systems/framework:vector", + "//lcm:lcm_trajectory_saver", + "//common", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "kinodynamic_settings", + hdrs = ["kinodynamic_settings.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/examples/Cassie/systems/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc similarity index 98% rename from examples/Cassie/systems/contact_scheduler.cc rename to examples/Cassie/contact_scheduler/contact_scheduler.cc index 1d7d6e7f85..589812ef03 100644 --- a/examples/Cassie/systems/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -1,4 +1,4 @@ -#include "examples/Cassie/systems/contact_scheduler.h" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include diff --git a/examples/Cassie/systems/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h similarity index 100% rename from examples/Cassie/systems/contact_scheduler.h rename to examples/Cassie/contact_scheduler/contact_scheduler.h diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc new file mode 100644 index 0000000000..ba982e54e6 --- /dev/null +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc @@ -0,0 +1,728 @@ +#include "kinodynamic_planner.h" + +using drake::AbstractValue; +using drake::multibody::BodyFrame; +using drake::multibody::JacobianWrtVariable; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; + +using drake::EigenPtr; + +using drake::solvers::MathematicalProgram; +using drake::solvers::MathematicalProgramResult; +using drake::solvers::OsqpSolver; +using drake::solvers::OsqpSolverDetails; +using drake::solvers::Solve; + +using Eigen::Matrix; +using Eigen::Matrix3d; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::LcmTrajectory; +using dairlib::multibody::MakeNameToPositionsMap; +using dairlib::multibody::MakeNameToVelocitiesMap; +using dairlib::multibody::SetPositionsAndVelocitiesIfNew; +using dairlib::systems::OutputVector; + +namespace dairlib { + +KinodynamicPlanner::KinodynamicPlanner( + const drake::multibody::MultibodyPlant& plant) + : plant_(plant), + n_q_(plant.num_positions()), + n_v_(plant.num_velocities()), + n_u_(plant.num_actuators()){ + // Create Ports + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector( + n_q_, n_v_, n_u_)) + .get_index(); + + traj_out_port_ = this->DeclareAbstractOutputPort( + "y(t)", &KinodynamicPlanner::GetMostRecentMotionPlan, + {this->all_state_ticket()}) + .get_index(); + + // Discrete update + DeclarePerStepDiscreteUpdateEvent( + &KinodynamicPlanner::DiscreteVariableUpdate); +// DeclarePeriodicDiscreteUpdateEvent(dt_, 0, +// &KinodynamicPlanner::PeriodicUpdate); + + x_des_ = VectorXd ::Zero(n_r_ + n_h_); +} + +void KinodynamicPlanner::AddMode(const LinearSrbdDynamics& dynamics, + BipedStance stance, const MatrixXd& reset, + int N) { + DRAKE_DEMAND(stance == nmodes_); + SrbdMode mode = {dynamics, reset, stance, N}; + for (int i = 0; i < N; i++) { + xx.push_back(prog_.NewContinuousVariables( + nx_, "x_" + std::to_string(stance) + std::to_string(i))); + uu.push_back(prog_.NewContinuousVariables( + nu_, "u_" + std::to_string(stance) + std::to_string(i))); + } + pp.push_back( + prog_.NewContinuousVariables(kLinearDim_, "p_" + std::to_string(stance))); + total_knots_ += N; + modes_.push_back(mode); + nmodes_++; +} + +void KinodynamicPlanner::FinalizeModeSequence() { + xx.push_back(prog_.NewContinuousVariables(nx_, "x_f")); + uu.push_back(prog_.NewContinuousVariables(nu_, "u_f")); + if (use_residuals_) { + residual_manager_ = std::make_unique( + total_knots_ + 1, modes_.front().dynamics.A, modes_.front().dynamics.B, + modes_.front().dynamics.b); + } +} + +void KinodynamicPlanner::SetReachabilityBoundingBox( + const Vector3d& bounds, + const std::vector& nominal_relative_pos) { + kin_bounds_ = bounds; + for (const auto& pos : nominal_relative_pos) { + nominal_foot_pos_.push_back(pos); + } +} + +void KinodynamicPlanner::CheckProblemDefinition() { + DRAKE_DEMAND(!modes_.empty()); + DRAKE_DEMAND(!nominal_foot_pos_.empty()); + DRAKE_DEMAND(plant_.mass() > 0); + DRAKE_DEMAND(mu_ > 0); + DRAKE_DEMAND(x_des_.rows() == nx_); + CheckSquareMatrixDimensions(Q_, nx_); + CheckSquareMatrixDimensions(Qf_, nx_); + CheckSquareMatrixDimensions(R_, nu_); + CheckSquareMatrixDimensions(Wp_, kLinearDim_); +} + +void KinodynamicPlanner::Build() { + CheckProblemDefinition(); + MakeDynamicsConstraints(); + MakeFrictionConeConstraints(); + MakeKinematicReachabilityConstraints(); + MakeInitialStateConstraint(); + MakeTerrainConstraints(); + MakeCost(); + + drake::solvers::SolverOptions solver_options; + solver_options.SetOption(OsqpSolver::id(), "verbose", 1); + solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-5); + solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); + solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-4); + solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-4); + solver_options.SetOption(OsqpSolver::id(), "polish", 1); + solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); + solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_fraction", 1.0); + solver_options.SetOption(OsqpSolver::id(), "max_iter", 20000); + prog_.SetSolverOptions(solver_options); +} + +void KinodynamicPlanner::MakeTerrainConstraints(const Vector3d& normal, + const Vector3d& origin) { + /// TODO: @Brian-Acosta add update function to adapt to terrain + MatrixXd TerrainNormal = normal.transpose(); + VectorXd TerrainPoint = normal.dot(origin) * VectorXd::Ones(1); + for (int i = 0; i < nmodes_; i++) { + terrain_angle_.push_back( + prog_.AddLinearEqualityConstraint(TerrainNormal, TerrainPoint, pp.at(i)) + .evaluator() + .get()); + } +} + +void KinodynamicPlanner::MakeDynamicsConstraints() { + for (int j = 0; j < nmodes_; j++) { + auto mode = modes_.at(j); + for (int i = 0; i < mode.N; i++) { + MatrixXd Aeq = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); + VectorXd beq = VectorXd::Zero(nx_); + Vector3d pos = Vector3d::Zero(); + pos(1) = nominal_foot_pos_.at(j)(1); + CopyCollocationDynamicsConstraint(mode.dynamics, false, pos, &Aeq, &beq); + dynamics_.push_back(prog_.AddLinearEqualityConstraint( + Aeq, beq, + {xx.at(j * mode.N + i), xx.at(j * mode.N + i + 1), + uu.at(j * mode.N + i), uu.at(j * mode.N + i + 1), + pp.at(mode.stance)})); + } + } + // for (auto& binding : dynamics_) { + // std::cout << binding.to_string() << std::endl; + // } +} + +void KinodynamicPlanner::UpdateKinematicConstraints(int n_until_stance, + int fsm_state) const { + for (auto& constraint : kinematic_constraint_) { + prog_.RemoveConstraint(constraint); + } + + kinematic_constraint_.clear(); + + MatrixXd A = MatrixXd::Zero(kLinearDim_, 2 * kLinearDim_); + A << Matrix3d::Identity(), -Matrix3d::Identity(); + auto curr_mode = modes_.at(fsm_state); + auto next_mode = modes_.at(1 - fsm_state); + + std::cout << "Next stance: "; + for (int i = n_until_stance; i <= n_until_stance + next_mode.N; i++) { + kinematic_constraint_.push_back(prog_.AddLinearConstraint( + A, nominal_foot_pos_.at(next_mode.stance) - kin_bounds_, + nominal_foot_pos_.at(next_mode.stance) + kin_bounds_, + {pp.at(next_mode.stance), xx.at(i).head(kLinearDim_)})); + std::cout << std::to_string(i) << " "; + } + std::cout << std::endl; + std::cout << "Next next stance: "; + for (int i = n_until_stance + next_mode.N; i <= total_knots_; i++) { + kinematic_constraint_.push_back(prog_.AddLinearConstraint( + A, nominal_foot_pos_.at(curr_mode.stance) - kin_bounds_, + nominal_foot_pos_.at(curr_mode.stance) + kin_bounds_, + {pp.at(curr_mode.stance), xx.at(i).head(kLinearDim_)})); + std::cout << std::to_string(i) << " "; + } + std::cout << std::endl; +} + +void KinodynamicPlanner::UpdateDynamicsConstraints(const Eigen::VectorXd& x, + int n_until_next_stance, + int fsm_state) const { + auto& mode = modes_.at(fsm_state); + Vector3d pos = plant_.CalcFootPosition(x, mode.stance); + + if (n_until_next_stance == mode.N) { + // make current stance dynamics and apply to mode + MatrixXd Aeq = MatrixXd::Zero(nx_, 2 * (nx_ + nu_)); + VectorXd beq = VectorXd::Zero(nx_); + CopyCollocationDynamicsConstraint(mode.dynamics, true, pos, &Aeq, &beq); + + for (int i = 0; i < (mode.N); i++) { + prog_.RemoveConstraint(dynamics_.at(i)); + dynamics_.at(i) = prog_.AddLinearEqualityConstraint( + Aeq, beq, {xx.at(i), xx.at(i + 1), uu.at(i), uu.at(i + 1)}); + } + + Aeq = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); + beq = VectorXd::Zero(nx_); + CopyCollocationDynamicsConstraint(modes_.at(1 - fsm_state).dynamics, false, + pos, &Aeq, &beq); + prog_.RemoveConstraint(dynamics_.at(mode.N)); + dynamics_.at(mode.N) = prog_.AddLinearEqualityConstraint( + Aeq, beq, + {xx.at(mode.N), xx.at(mode.N + 1), uu.at(mode.N), uu.at(mode.N + 1), + pp.at(1 - fsm_state)}); + } else { + int idx = n_until_next_stance; + MatrixXd Aeq1 = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); + MatrixXd Aeq2 = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); + VectorXd beq1 = VectorXd::Zero(nx_); + VectorXd beq2 = VectorXd::Zero(nx_); + CopyCollocationDynamicsConstraint(modes_.at(1 - fsm_state).dynamics, false, + pos, &Aeq1, &beq1); + + prog_.RemoveConstraint(dynamics_.at(idx)); + dynamics_.at(idx) = prog_.AddLinearEqualityConstraint( + Aeq1, beq1, + {xx.at(idx), xx.at(idx + 1), uu.at(idx), uu.at(idx + 1), + pp.at(1 - fsm_state)}); + + CopyCollocationDynamicsConstraint(mode.dynamics, false, pos, &Aeq2, &beq2); + prog_.RemoveConstraint(dynamics_.at(idx + mode.N)); + dynamics_.at(idx + mode.N) = prog_.AddLinearEqualityConstraint( + Aeq2, beq2, + {xx.at(idx + mode.N), xx.at(idx + mode.N + 1), uu.at(idx + mode.N), + uu.at(idx + mode.N + 1), pp.at(fsm_state)}); + } + std::cout << "\n"; +} + +// void KinodynamicPlanner::UpdateResidualDynamicsConstraints(const +// Eigen::VectorXd& x, +// int n_until_next_stance, int +// fsm_state) const { +// +// auto& mode = modes_.at(fsm_state); +// Vector3d pos = plant_.CalcFootPosition(x, mode.stance); +// +// if (n_until_next_stance == mode.N ) { +// // make current stance dynamics and apply to mode after +// // adding current residual estimate +// MatrixXd Aeq = MatrixXd::Zero(nx_, 2*(nx_ + nu_)); +// VectorXd beq = VectorXd::Zero(nx_); +// +// for (int i = 0; i < (mode.N); i++){ +// LinearSrbdDynamics dyn_i = {A_matrix_t::Zero(), B_matrix_t::Zero(), +// b_vector_t::Zero()}; +// residual_manager_->AddResidualToDynamics( +// residual_dynamics{mode.dynamics.A, mode.dynamics.B, +// mode.dynamics.b}, +// residual_manager_->GetAverageResidualForNextTwoKnots(i), +// &dyn_i.A, &dyn_i.B, &dyn_i.b); +// CopyCollocationDynamicsConstraint( +// dyn_i, true, pos, &Aeq, &beq); +// +// prog_.RemoveConstraint(dynamics_.at(i)); +// dynamics_.at(i) = prog_.AddLinearEqualityConstraint( +// Aeq, beq, +// {xx.at(i), xx.at(i+1), uu.at(i), uu.at(i+1)}); +// +// } +// +// Aeq = MatrixXd::Zero(nx_, 2*(nx_ + nu_) + kLinearDim_); +// beq = VectorXd::Zero(nx_); +// LinearSrbdDynamics dyn_f = {A_matrix_t::Zero(), B_matrix_t::Zero(), +// b_vector_t::Zero()}; residual_manager_->AddResidualToDynamics( +// residual_dynamics{modes_.at(1-fsm_state).dynamics.A, +// modes_.at(1-fsm_state).dynamics.B, +// modes_.at(1-fsm_state).dynamics.b}, +// residual_manager_->GetAverageResidualForNextTwoKnots(mode.N), +// &dyn_f.A, &dyn_f.B, &dyn_f.b); +// CopyCollocationDynamicsConstraint( +// dyn_f,false, pos, &Aeq, &beq); +// prog_.RemoveConstraint(dynamics_.at(mode.N)); +// dynamics_.at(mode.N) = prog_.AddLinearEqualityConstraint( +// Aeq, beq, +// {xx.at(mode.N), xx.at(mode.N+1), +// uu.at(mode.N), uu.at(mode.N+1), +// pp.at(1-fsm_state)}); +// } else { +// int idx = n_until_next_stance; +// +// LinearSrbdDynamics dyn_f = {A_matrix_t::Zero(), B_matrix_t::Zero(), +// b_vector_t::Zero()}; residual_manager_->AddResidualToDynamics( +// residual_dynamics{modes_.at(1-fsm_state).dynamics.A, +// modes_.at(1-fsm_state).dynamics.B, +// modes_.at(1-fsm_state).dynamics.b}, +// residual_manager_->GetAverageResidualForNextTwoKnots(mode.N), +// &dyn_f.A, &dyn_f.B, &dyn_f.b); +// +// MatrixXd Aeq = MatrixXd::Zero(nx_, 2*(nx_ + nu_) + kLinearDim_); +// VectorXd beq = VectorXd::Zero(nx_); +// CopyCollocationDynamicsConstraint( +// dyn_f, false, pos, &Aeq, &beq); +// +// prog_.RemoveConstraint(dynamics_.at(idx)); +// dynamics_.at(idx) = prog_.AddLinearEqualityConstraint( +// Aeq, beq, +// {xx.at(idx), xx.at(idx+1), +// uu.at(idx), uu.at(idx+1), pp.at(1-fsm_state)}); +// +// residual_manager_->AddResidualToDynamics( +// residual_dynamics{mode.dynamics.A, +// mode.dynamics.B, +// mode.dynamics.b}, +// residual_manager_->GetAverageResidualForNextTwoKnots(mode.N), +// &dyn_f.A, &dyn_f.B, &dyn_f.b); +// CopyCollocationDynamicsConstraint(dyn_f, false, pos, &Aeq, &beq); +// +// prog_.RemoveConstraint(dynamics_.at(idx + mode.N)); +// dynamics_.at(idx+mode.N) = prog_.AddLinearEqualityConstraint( +// Aeq, beq, +// {xx.at(idx+mode.N), xx.at(idx+mode.N+1), +// uu.at(idx+mode.N), uu.at(idx+mode.N+1), pp.at(fsm_state)}); +// } +// std::cout << "\n"; +//} + +void KinodynamicPlanner::UpdateFootPlacementCost( + int fsm_state, const Eigen::VectorXd& up_next_foot_target, + const Eigen::VectorXd& on_deck_foot_target) const { + foot_target_cost_.at(fsm_state)->UpdateCoefficients( + 2.0 * Wp_, -2.0 * Wp_ * on_deck_foot_target); + foot_target_cost_.at(1 - fsm_state) + ->UpdateCoefficients(2.0 * Wp_, -2.0 * Wp_ * up_next_foot_target); +} + +void KinodynamicPlanner::MakeInitialStateConstraint() { + initial_state_ = + prog_ + .AddLinearEqualityConstraint(MatrixXd::Identity(nx_, nx_), + VectorXd::Zero(nx_), xx.at(0)) + .evaluator() + .get(); +} + +void KinodynamicPlanner::MakeKinematicReachabilityConstraints() { + MatrixXd A = MatrixXd::Zero(kLinearDim_, 2 * kLinearDim_); + A << Matrix3d::Identity(), -Matrix3d::Identity(); + for (int j = 0; j < nmodes_; j++) { + auto mode = modes_.at(j); + for (int i = 0; i <= mode.N; i++) { + kinematic_constraint_.push_back(prog_.AddLinearConstraint( + A, nominal_foot_pos_.at(mode.stance) - kin_bounds_, + nominal_foot_pos_.at(mode.stance) + kin_bounds_, + {pp.at(mode.stance), xx.at(i + j * mode.N).head(kLinearDim_)})); + } + } +} + +void KinodynamicPlanner::MakeFrictionConeConstraints() { + for (int i = 0; i <= total_knots_; i++) { + friction_cone_.push_back( + prog_ + .AddConstraint(solvers::CreateLinearFrictionConstraint(mu_), + uu.at(i).head(kLinearDim_)) + .evaluator() + .get()); + } +} + +void KinodynamicPlanner::MakeCost() { + VectorXd unom = VectorXd::Zero(nu_); + unom(2) = 9.81 * plant_.mass(); + for (int i = 0; i <= total_knots_; i++) { + Matrix Q = (i == 0 || i == total_knots_) ? 0.5 * Q_ : Q_; + Matrix R = (i == 0 || i == total_knots_) ? 0.5 * R_ : R_; + tracking_cost_.push_back( + prog_.AddQuadraticErrorCost(Q, x_des_, xx.at(i)).evaluator().get()); + input_cost_.push_back( + prog_.AddQuadraticErrorCost(R, unom, uu.at(i)).evaluator().get()); + } + for (int i = 0; i < nmodes_; i++) { + foot_target_cost_.push_back( + prog_.AddQuadraticErrorCost(Wp_, nominal_foot_pos_.at(i), pp.at(i)) + .evaluator() + .get()); + } +} + +void KinodynamicPlanner::AddTrackingObjective(const VectorXd& xdes, + const MatrixXd& Q) { + Q_ = Q; + x_des_ = xdes; +} + +void KinodynamicPlanner::SetTerminalCost(const MatrixXd& Qf) { Qf_ = Qf; } + +void KinodynamicPlanner::AddInputRegularization(const Eigen::MatrixXd& R) { + R_ = R; +} + +void KinodynamicPlanner::AddFootPlacementRegularization( + const Eigen::MatrixXd& W) { + Wp_ = W; +} + +void KinodynamicPlanner::GetMostRecentMotionPlan( + const drake::systems::Context& context, + dairlib::lcmt_saved_traj* traj_msg) const { + *traj_msg = most_recent_sol_; +} + +EventStatus KinodynamicPlanner::DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { + const BasicVector* fsm_output = + (BasicVector*)this->EvalVectorInput(context, fsm_port_); + VectorXd fsm_state = fsm_output->get_value(); + + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + double timestamp = robot_output->get_timestamp(); + + VectorXd xdes = this->EvalVectorInput(context, x_des_port_)->get_value(); + + if (xdes != x_des_) { + UpdateTrackingObjective(xdes); + } + + if (use_fsm_) { + auto current_fsm_state = + discrete_state->get_mutable_vector(current_fsm_state_idx_) + .get_mutable_value(); + + if (fsm_state(0) != current_fsm_state(0)) { + current_fsm_state(0) = fsm_state(0); + discrete_state->get_mutable_vector(prev_event_time_idx_) + .get_mutable_value() + << timestamp; + } + } + return EventStatus::Succeeded(); +} + +EventStatus KinodynamicPlanner::PeriodicUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + + // const drake::AbstractValue* traj_value = + // this->EvalAbstractInput(context, srb_warmstart_port_); + // + // const auto& warmstart_traj = + // traj_value->get_value>(); + + VectorXd x = robot_output->GetState(); + + double timestamp = robot_output->get_timestamp(); + double time_since_last_event = timestamp; + int fsm_state = 0; + + if (use_fsm_) { + fsm_state = (int)(discrete_state->get_vector(current_fsm_state_idx_) + .get_value()(0)); + double last_event_time = + discrete_state->get_vector(prev_event_time_idx_).get_value()(0); + + time_since_last_event = + (last_event_time <= 0) ? timestamp : timestamp - last_event_time; + + if (use_residuals_) { + residual_dynamics res = + this->EvalAbstractInput(context, srbd_residual_port_) + ->get_value(); + DRAKE_DEMAND(res.A.cols() == nx_ + kLinearDim_); + DRAKE_DEMAND(res.B.cols() == nu_); + DRAKE_DEMAND(res.b.rows() == nx_); + residual_manager_->SetResidualForCurrentKnot(res); + } + + UpdateConstraints(plant_.CalcSRBStateFromPlantState(x), fsm_state, + time_since_last_event); + } else { + UpdateConstraints(plant_.CalcSRBStateFromPlantState(x), 0, 0); + } + + // VectorXd foot_target = + // this->EvalVectorInput(context, foot_target_port_)->get_value(); + UpdateFootPlacementCost(fsm_state, Vector3d::Zero(), Vector3d::Zero()); + // + // SetInitialGuess(fsm_state, timestamp, + // foot_target.head(kLinearDim_), + // foot_target.tail(kLinearDim_), + // warmstart_traj); + + // auto lin_con = prog_.GetAllLinearConstraints(); + // for (auto& binding : lin_con) { + // std::cout << "Next Binding:\n" << binding << std::endl; + // } + // print_constraint(lin_con); + + result_ = solver_.Solve(prog_); + + if (!result_.is_success()) { + std::cout << "result: " << result_.get_solution_result() << std::endl; + } + + most_recent_sol_ = MakeLcmTrajFromSol(result_, timestamp, + time_since_last_event, x, fsm_state); + return EventStatus::Succeeded(); +} + +void KinodynamicPlanner::UpdateTrackingObjective(const VectorXd& xdes) const { + x_des_ = xdes; + for (auto& cost : tracking_cost_) { + cost->UpdateCoefficients(2.0 * Q_, -2.0 * Q_ * xdes); + } +} + +void KinodynamicPlanner::UpdateConstraints( + const VectorXd& x0, const int fsm_state, + const double t_since_last_switch) const { + initial_state_->UpdateCoefficients(MatrixXd::Identity(nx_, nx_), x0); + + if (!use_fsm_) { + return; + } + std::cout << "Time since last switch: " << std::to_string(t_since_last_switch) + << std::endl; + int n_until_next_state = + modes_.at(fsm_state).N - std::floor(t_since_last_switch / dt_); + if (use_residuals_) { + UpdateResidualDynamicsConstraints(x0, n_until_next_state, fsm_state); + residual_manager_->CycleCurrentKnot(); + } else { + UpdateDynamicsConstraints(x0, n_until_next_state, fsm_state); + } + UpdateKinematicConstraints(n_until_next_state, fsm_state); +} + +void KinodynamicPlanner::SetInitialGuess( + int fsm_state, double timestamp, + const Eigen::VectorXd& up_next_stance_target, + const Eigen::VectorXd& on_deck_stance_target, + const drake::trajectories::Trajectory& srb_traj) const { + prog_.SetInitialGuess(pp.at(fsm_state), on_deck_stance_target); + prog_.SetInitialGuess(pp.at(1 - fsm_state), up_next_stance_target); + VectorXd srb_guess(nx_); + for (int i = 0; i < total_knots_; i++) { + double t = timestamp + i * dt_; + + Eigen::Vector4d u_guess(0, 0, plant_.mass() * 9.81, 0); + srb_guess.head(nx_ / 2) = srb_traj.value(t); + srb_guess.tail(nx_ / 2) = srb_traj.EvalDerivative(t, 1); + prog_.SetInitialGuess(xx.at(i), srb_guess); + prog_.SetInitialGuess(uu.at(i), u_guess); + } + double t = timestamp + total_knots_ * dt_; + srb_guess.head(nx_ / 2) = srb_traj.value(t); + srb_guess.tail(nx_ / 2) = srb_traj.EvalDerivative(t, 1); + prog_.SetInitialGuess(xx.back(), srb_guess); +} + +lcmt_saved_traj KinodynamicPlanner::MakeLcmTrajFromSol( + const drake::solvers::MathematicalProgramResult& result, double time, + double time_since_last_touchdown, const VectorXd& state, + int fsm_state) const { + DRAKE_DEMAND(result.is_success()); + + LcmTrajectory::Trajectory CoMTraj; + LcmTrajectory::Trajectory AngularTraj; + LcmTrajectory::Trajectory SwingFootTraj; + LcmTrajectory::Trajectory InputTraj; + + CoMTraj.traj_name = "com_traj"; + AngularTraj.traj_name = "orientation"; + SwingFootTraj.traj_name = "swing_foot_traj"; + InputTraj.traj_name = "input_traj"; + + /** need to set datatypes for LcmTrajectory to save properly **/ + for (int i = 0; i < 2 * kLinearDim_; i++) { + CoMTraj.datatypes.emplace_back("double"); + AngularTraj.datatypes.emplace_back("double"); + } + for (int i = 0; i < kLinearDim_; i++) { + SwingFootTraj.datatypes.emplace_back("double"); + InputTraj.datatypes.emplace_back("double"); + } + InputTraj.datatypes.emplace_back("double"); + + /** Allocate Eigen matrices for trajectory blocks **/ + MatrixXd com = MatrixXd::Zero(2 * kLinearDim_, total_knots_); + MatrixXd orientation = MatrixXd::Zero(2 * kAngularDim_, total_knots_); + MatrixXd input = MatrixXd::Zero(nu_, total_knots_); + VectorXd time_knots = VectorXd::Zero(total_knots_); + + for (int i = 0; i < total_knots_; i++) { + VectorXd ui = result.GetSolution(uu.at(i)); + VectorXd xi = result.GetSolution(xx.at(i)); + input.col(i) = ui; + com.block(0, i, 2 * kLinearDim_, 1) << xi.head(kLinearDim_), + xi.segment(kLinearDim_ + kAngularDim_, kLinearDim_); + orientation.block(0, i, 2 * kAngularDim_, 1) + << xi.segment(kLinearDim_, kAngularDim_), + xi.tail(kAngularDim_); + + time_knots(i) = time + dt_ * i; + } + + InputTraj.time_vector = time_knots; + InputTraj.datapoints = input; + CoMTraj.time_vector = time_knots; + CoMTraj.datapoints = com; + AngularTraj.time_vector = time_knots; + AngularTraj.datapoints = orientation; + + VectorXd swing_ft_traj_breaks = VectorXd::Ones(1) * time; + SwingFootTraj.time_vector = swing_ft_traj_breaks; + SwingFootTraj.datapoints = result.GetSolution(pp.at(1 - fsm_state)); + + LcmTrajectory lcm_traj; + lcm_traj.AddTrajectory(CoMTraj.traj_name, CoMTraj); + lcm_traj.AddTrajectory(AngularTraj.traj_name, AngularTraj); + lcm_traj.AddTrajectory(SwingFootTraj.traj_name, SwingFootTraj); + lcm_traj.AddTrajectory(InputTraj.traj_name, InputTraj); + + return lcm_traj.GenerateLcmObject(); +} + +void KinodynamicPlanner::print_constraint( + const std::vector& constraints) const { + for (auto& x0_const : constraints) { + std::cout << x0_const->get_description() << ":\n A:\n" + << x0_const->A() << "\nub:\n" + << x0_const->upper_bound() << "\nlb\n" + << x0_const->lower_bound() << std::endl; + } +} + +void KinodynamicPlanner::print_constraint( + const std::vector& constraints) + const { + for (auto& x0_const : constraints) { + std::cout << x0_const->get_description() << ":\n A:\n" + << x0_const->A() << "\nb:\n" + << x0_const->upper_bound() << std::endl; + } +} + +void KinodynamicPlanner::print_constraint( + const std::vector& constraints) const { + for (auto& constraint : constraints) { + auto constr = dynamic_cast(constraint); + std::cout << constr->get_description() << ":\n A:\n" + << constr->A() << "\nb:\n" + << constr->upper_bound() << std::endl; + } +} + +void KinodynamicPlanner::CopyDiscreteDynamicsConstraint( + const SrbdMode& mode, bool current_stance, const Vector3d& foot_pos, + const drake::EigenPtr& A, + const drake::EigenPtr& b) const { + DRAKE_DEMAND(A != nullptr && b != nullptr); + + if (!current_stance) { + A->block(0, 0, nx_, nx_ + kLinearDim_) = mode.dynamics.A; + A->block(0, nx_ + kLinearDim_, nx_, nu_) = mode.dynamics.B; + A->block(0, nx_ + nu_ + kLinearDim_, nx_, nx_) = + -MatrixXd::Identity(nx_, nx_); + *b = -mode.dynamics.b; + } else { + A->block(0, 0, nx_, nx_) = mode.dynamics.A.block(0, 0, nx_, nx_); + A->block(0, nx_, nx_, nu_) = mode.dynamics.B; + A->block(0, nx_ + nu_, nx_, nx_) = -MatrixXd::Identity(nx_, nx_); + *b = -(mode.dynamics.A.block(0, nx_, nx_, kLinearDim_) * foot_pos + + mode.dynamics.b); + } +} + +void KinodynamicPlanner::CopyCollocationDynamicsConstraint( + const LinearSrbdDynamics& dyn, bool current_stance, + const Eigen::Vector3d& foot_pos, const drake::EigenPtr& A, + const drake::EigenPtr& b) const { + DRAKE_DEMAND(A != nullptr && b != nullptr); + if (current_stance) { + DRAKE_DEMAND(A->cols() == 2 * (nx_ + nu_)); + } else { + DRAKE_DEMAND(A->cols() == 2 * (nx_ + nu_) + 3); + } + + Matrix Ax = dyn.A.block(0, 0, nx_, nx_); + Matrix Ap = dyn.A.block(0, nx_, nx_, nx_ + kLinearDim_); + double h = dt_; + A->block(0, 0, nx_, nx_) = (0.125 * h) * Ax * Ax - 0.75 * Ax - + (1.5 / h) * MatrixXd::Identity(nx_, nx_); + A->block(0, nx_, nx_, nx_) = -(0.125 * h) * Ax * Ax - 0.75 * Ax + + (1.5 / h) * MatrixXd::Identity(nx_, nx_); + A->block(0, 2 * nx_, nx_, nu_) = + (0.125 * h * Ax - 0.75 * MatrixXd::Identity(nx_, nx_)) * dyn.B; + A->block(0, 2 * nx_ + nu_, nx_, nu_) = + (-0.125 * h * Ax - 0.75 * MatrixXd::Identity(nx_, nx_)) * dyn.B; + if (current_stance) { + *b = 1.5 * dyn.b + 1.5 * Ap * foot_pos; + } else { + A->block(0, 2 * (nx_ + nu_), nx_, kLinearDim_) = -1.5 * Ap; + *b = 1.5 * dyn.b; + } +} + +void KinodynamicPlanner::CheckSquareMatrixDimensions(const MatrixXd& M, + const int n) const { + DRAKE_DEMAND(M.rows() == n); + DRAKE_DEMAND(M.cols() == n); +} + +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.h b/examples/Cassie/contact_scheduler/kinodynamic_planner.h new file mode 100644 index 0000000000..384aeac27d --- /dev/null +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.h @@ -0,0 +1,211 @@ +#pragma once + +#include +#include +#include +#include +#include + +#include + +#include "examples/Cassie/contact_scheduler/kinodynamic_settings.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/multibody_utils.h" +#include "solvers/constraint_factory.h" +#include "solvers/fast_osqp_solver.h" +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +//#include "drake/solvers/gurobi_solver.h" +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/osqp_solver.h" +#include "drake/solvers/solve.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +typedef struct LinearSrbdDynamics { + Eigen::MatrixXd A; + Eigen::MatrixXd B; + Eigen::VectorXd b; +} LinearSrbdDynamics; + +/// This kinodynamic planner is an implementation of the Dai 2014 paper +/// (Whole-body Motion Planning with Centroidal Dynamics and Full Kinematics) +/// This outputs: footstep timing +/// final footstep location +/// center of mass trajectory +/// swing foot trajectory (maybe)? + +/// TODOs: +/// + +/// Template borrowed from SrbdCMPC written by Brian Acosta in centroidal_models +/// branch + +class KinodynamicPlanner : public drake::systems::LeafSystem { + public: + KinodynamicPlanner(const drake::multibody::MultibodyPlant& plant); + + void SetMPCSettings(KinodynamicSettings& settings); + void SetTerminalCost(const Eigen::MatrixXd& Qf); + void AddInputRegularization(const Eigen::MatrixXd& R); + // void AddFootPlacementRegularization(const Eigen::MatrixXd& W); + void Build(); + void CheckProblemDefinition(); + + // Input ports + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_fsm_input_port() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_target_input_port() const { + return this->get_input_port(x_des_port_); + } + const drake::systems::InputPort& get_warmstart_input_port() const { + return this->get_input_port(srb_warmstart_port_); + } + // const drake::systems::InputPort& get_foot_target_input_port() + // const { + // return this->get_input_port(foot_target_port_); + // } + const drake::systems::OutputPort& get_traj_out_port() const { + return this->get_output_port(traj_out_port_); + } + + void SetKinematicConstraints(); + + void SetContactConstraints(); + + drake::solvers::MathematicalProgramResult solve_problem_as_is() { + return drake::solvers::Solve(prog_); + } + + void print_constraint( + const std::vector& constraint) const; + void print_constraint( + const std::vector& constraint) const; + void print_constraint( + const std::vector& constraint) + const; + + private: + void CheckSquareMatrixDimensions(const Eigen::MatrixXd& M, int n) const; + void GetMostRecentMotionPlan(const drake::systems::Context& context, + lcmt_saved_traj* traj_msg) const; + void MakeKinematicReachabilityConstraints(); + void MakeTerrainConstraints(const Eigen::Vector3d& normal = {0, 0, 1}, + const Eigen::Vector3d& origin = {0, 0, 0}); + void MakeDynamicsConstraints(); + void MakeFrictionConeConstraints(); + void MakeInitialStateConstraint(); + void MakeCost(); + + lcmt_saved_traj MakeLcmTrajFromSol( + const drake::solvers::MathematicalProgramResult& result, double time, + double time_since_last_touchdown, const Eigen::VectorXd& state, + int fsm_state) const; + + void UpdateConstraints(const Eigen::VectorXd& x0, int fsm_state, + double t_since_last_switch) const; + void UpdateTrackingObjective(const Eigen::VectorXd& xdes) const; + void UpdateDynamicsConstraints(const Eigen::VectorXd& x, + int n_until_next_stance, int fsm_state) const; + void UpdateKinematicConstraints(int n_until_stance, int fsm_state) const; + void SetInitialGuess( + int fsm_state, double timestamp, + const Eigen::VectorXd& up_next_stance_target, + const Eigen::VectorXd& on_deck_stance_target, + const drake::trajectories::Trajectory& srb_traj) const; +// void CopyDiscreteDynamicsConstraint( +// const SrbdMode& mode, bool current_stance, +// const Eigen::Vector3d& foot_pos, +// const drake::EigenPtr& A, +// const drake::EigenPtr& b) const; + void CopyCollocationDynamicsConstraint( + const LinearSrbdDynamics& dyn, bool current_stance, + const Eigen::Vector3d& foot_pos, + const drake::EigenPtr& A, + const drake::EigenPtr& b) const; + + // discrete update + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::EventStatus PeriodicUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + // plant + const drake::multibody::MultibodyPlant& plant_; + double mu_ = 0; + int n_q_; + int n_v_; + int n_u_; + + int n_r_ = 3; + int n_h_ = 3; + + + // parameters and constants + // const bool use_fsm_; + // const bool use_residuals_; + // const bool traj_tracking_; + // static constexpr int nx_ = 12; + // static constexpr int nu_ = 5; + static constexpr int kLinearDim_ = 3; + static constexpr int kAngularDim_ = 3; + // const double dt_; + int nmodes_ = 0; + + // port indices + int state_port_; + int fsm_port_; + int x_des_port_; + int srbd_residual_port_; + int traj_out_port_; + int foot_target_port_; + int srb_warmstart_port_; + + // discrete update indices + int current_fsm_state_idx_; + int prev_event_time_idx_; + + // Problem variables + Eigen::MatrixXd Q_; // For running cost x^TQx + Eigen::MatrixXd R_; // For running cost u^TRu + Eigen::MatrixXd Wp_; // regularizing cost on footstep location + Eigen::MatrixXd Qf_; // For terminal cost x_{T}^{T}Q_{f}x_{T} + Eigen::Vector3d kin_bounds_; + mutable Eigen::VectorXd x_des_; + mutable Eigen::MatrixXd x_des_mat_; + int total_knots_ = 0; + + // Solver + drake::solvers::OsqpSolver solver_; + mutable drake::solvers::MathematicalProgramResult result_; + mutable drake::solvers::MathematicalProgram prog_; + mutable lcmt_saved_traj most_recent_sol_; + + // Constraints + std::vector tracking_cost_; + std::vector input_cost_; + std::vector foot_target_cost_; + std::vector friction_cone_; + std::vector terrain_angle_; + drake::solvers::LinearEqualityConstraint* initial_state_; + mutable std::vector< + drake::solvers::Binding> + dynamics_; + mutable std::vector> + kinematic_constraint_; + + // Decision Variables + std::vector xx; + std::vector uu; + std::vector pp; +}; +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/kinodynamic_settings.h b/examples/Cassie/contact_scheduler/kinodynamic_settings.h new file mode 100644 index 0000000000..d0922d5398 --- /dev/null +++ b/examples/Cassie/contact_scheduler/kinodynamic_settings.h @@ -0,0 +1,37 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +namespace dairlib { + +struct KinodynamicSettings { + + int N; + int N_per_mode; + std::vector q_q; + std::vector q_v; + + MatrixXd Q_q; + MatrixXd Q_v; + + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(N)); + a->Visit(DRAKE_NVP(N_per_mode)); + a->Visit(DRAKE_NVP(q_q)); + a->Visit(DRAKE_NVP(q_v)); + + Q_q = Eigen::Map< + Eigen::Matrix>( + this->q_q.data(), 3, 3); + Q_v = Eigen::Map< + Eigen::Matrix>( + this->q_v.data(), 3, 3); + } +}; +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/kinodynamic_settings.yaml b/examples/Cassie/contact_scheduler/kinodynamic_settings.yaml new file mode 100644 index 0000000000..56d9dbc717 --- /dev/null +++ b/examples/Cassie/contact_scheduler/kinodynamic_settings.yaml @@ -0,0 +1,10 @@ +# hyperparameters for kinodynamic planner + +N: 15 +N_per_mode: 5 +Q_q: [1, 0, 0, + 0, 1, 0, + 0, 0, 1] +Q_v: [1, 0, 0, + 0, 1, 0, + 0, 0, 1] diff --git a/examples/Cassie/systems/BUILD.bazel b/examples/Cassie/systems/BUILD.bazel index 4d24c8324a..a07c5c468f 100644 --- a/examples/Cassie/systems/BUILD.bazel +++ b/examples/Cassie/systems/BUILD.bazel @@ -49,17 +49,6 @@ cc_library( ], ) -cc_library( - name = "variable_time_fsm", - srcs = ["contact_scheduler.cc"], - hdrs = ["contact_scheduler.h"], - deps = [ - "//lcmtypes:lcmt_robot", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) - cc_library( name = "cassie_encoder", srcs = ["cassie_encoder.cc"], From 7a4ee7185267f75c68fcaa35614d0c71f6eeeb41 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Jul 2022 15:52:05 -0400 Subject: [PATCH 241/758] committing progress --- bindings/pydairlib/analysis/BUILD.bazel | 13 + .../analysis/cassie_plotting_utils.py | 8 +- .../pydairlib/analysis/log_plotter_cassie.py | 16 +- .../plot_configs/cassie_running_plot.yaml | 18 +- .../pydairlib/analysis/spring_compensation.py | 82 ++ .../contact_scheduler/kinodynamic_planner.cc | 730 +++--------------- .../contact_scheduler/kinodynamic_planner.h | 53 +- .../osc/operational_space_control.cc | 8 +- 8 files changed, 263 insertions(+), 665 deletions(-) create mode 100644 bindings/pydairlib/analysis/spring_compensation.py diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 56747fa6c9..a070cc9479 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -47,6 +47,19 @@ py_library( deps = [], ) +py_library( + name = "spring_compensation", + srcs = ["spring_compensation.py"], + deps = [ + ":osc_debug_py", + "//bindings/pydairlib/common:plot_styler", + "//bindings/pydairlib/common:plotting_utils", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + ], +) + py_library( name = "mbp_plotting_utils", srcs = ["mbp_plotting_utils.py"], diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 672cb6574a..5167956024 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -5,7 +5,7 @@ # lcmtype imports import dairlib -import archive.dairlib +# import archive.dairlib import drake # dairlib python binding imports @@ -39,11 +39,7 @@ 'OSC_STANDING': dairlib.lcmt_robot_input, 'OSC_JUMPING': dairlib.lcmt_robot_input, 'OSC_RUNNING': dairlib.lcmt_robot_input, - 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, - 'OSC_DEBUG_STANDING': archive.dairlib.lcmt_osc_output, - 'OSC_DEBUG_WALKING': archive.dairlib.lcmt_osc_output, - 'OSC_DEBUG_JUMPING': archive.dairlib.lcmt_osc_output, - 'OSC_DEBUG_RUNNING': archive.dairlib.lcmt_osc_output} + 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out} cassie_contact_channels = \ {'CASSIE_CONTACT_DRAKE': drake.lcmt_contact_results_for_viz, diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 7a5ae53055..ed963da8c3 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -9,7 +9,7 @@ from cassie_plot_config import CassiePlotConfig import cassie_plotting_utils as cassie_plots import mbp_plotting_utils as mbp_plots - +from spring_compensation import SpringCompensation def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' @@ -58,6 +58,18 @@ def main(): t_x_slice = slice(robot_output['t_x'].size) t_osc_slice = slice(osc_debug['t_osc'].size) print('Log start time: ', robot_output['t_x'][0]) + # import time + # time_start = time.time() + # time.sleep(1) + # print(time.time() - time_start) + # spring_compensation = SpringCompensation() + # samples, t_samples = spring_compensation.sample_simulate_forward(robot_output['q'][0], robot_output['v'][0], robot_output['u'][0], 10) + # print(time.time() - time_start) + # plt.plot(t_samples, samples[:, :23]) + # plt.plot(t_samples, samples[:, -22:]) + # print(t_samples) + # plt.show() + # import pdb; pdb.set_trace() ''' Plot Positions ''' # Plot floating base positions if applicable @@ -85,7 +97,7 @@ def main(): robot_output, t_x_slice, plant, context, "pelvis") # Plot all joint velocities - if plot_config.plot_joint_positions: + if plot_config.plot_joint_velocities: plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 6 if use_floating_base else 0, t_x_slice) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 5a8732d77b..8b083e9f7c 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,23 +6,23 @@ use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) start_time: 0 -duration: 2 +duration: 5 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false +plot_floating_base_positions: true plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false -plot_joint_positions: false -plot_joint_velocities: false +plot_joint_positions: true +plot_joint_velocities: true plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -special_positions_to_plot: [ ] -special_velocities_to_plot: [] +special_positions_to_plot: [ 'hip_pitch_left'] +special_velocities_to_plot: ['hip_pitch_leftdot'] special_efforts_to_plot: [ ] # Finite State Machine Names @@ -31,14 +31,14 @@ fsm_state_names: ['Left Stance (LS)', 'Left Flight (LF)', 'Right Stance (RS)', ' # Foot position plots foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] -foot_xyz_to_plot: { 'right': [ 0, 2 ], 'left': [ 0, 2 ] } +foot_xyz_to_plot: { 'right': [0], 'left': [0 ] } #foot_xyz_to_plot: { } -pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' +pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: false plot_qp_solve_time: true -plot_qp_solutions: true +plot_qp_solutions: false plot_tracking_costs: false tracking_datas_to_plot: # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel' ] } diff --git a/bindings/pydairlib/analysis/spring_compensation.py b/bindings/pydairlib/analysis/spring_compensation.py new file mode 100644 index 0000000000..864ea1f3a1 --- /dev/null +++ b/bindings/pydairlib/analysis/spring_compensation.py @@ -0,0 +1,82 @@ +import numpy as np + +import dairlib +from pydrake.multibody.plant import * +from pydairlib.common import FindResourceOrThrow +from pydairlib.cassie.cassie_utils import * +from pydrake.multibody.tree import MultibodyForces +from pydairlib.multibody import * +import cassie_plotting_utils as cassie_plots +from scipy.spatial.transform import Rotation as R + +def quat_dot(quat, omega): + """ + Borrowed from quadrotor sim from MEAM 620 + Parameters: + quat, [i,j,k,w] + omega, angular velocity of body in body axes + + Returns + duat_dot, [i,j,k,w] + + """ + # Adapted from "Quaternions And Dynamics" by Basile Graf. + (q0, q1, q2, q3) = (quat[0], quat[1], quat[2], quat[3]) + G = np.array([[ q3, q2, -q1, -q0], + [-q2, q3, q0, -q1], + [ q1, -q0, q3, -q2]]) + quat_dot = 0.5 * G.T @ omega + # Augment to maintain unit quaternion. + quat_err = np.sum(quat**2) - 1 + quat_err_grad = 2 * quat + quat_dot = quat_dot - quat_err * quat_err_grad + return quat_dot + +class SpringCompensation(): + def __init__(self): + self.dt = 8e-5 + self.plant, self.context = cassie_plots.make_plant_and_context( + floating_base=True, springs=True) + self.nq = self.plant.num_positions() + self.nv = self.plant.num_velocities() + self.nx = self.nq + self.nv + self.B = self.plant.MakeActuationMatrix() + + def sample_simulate_forward(self, q, v, u, n_samples): + x = np.hstack((q, v)) + self.plant.SetPositionsAndVelocities(self.context, x) + + samples = np.zeros((n_samples, self.nx)) + # t_samples = np.zeros((n_samples, 1)) + t_samples = 0.01 * np.random.sample(n_samples) + t_samples = np.sort(t_samples) + M = self.plant.CalcMassMatrix(self.context) + c = self.plant.CalcBiasTerm(self.context) + f = MultibodyForces(self.plant) + self.plant.CalcForceElementsContribution(self.context, f) + g = self.plant.CalcGravityGeneralizedForces(self.context) + M_inv = np.linalg.inv(M) + vdot = M_inv @ (-c + f.generalized_forces() + g + self.B @ u) + # import pdb; pdb.set_trace() + # t = 0.01 * np.random.sample() + for i in range(n_samples): + x_next = self.simulate_forward(x, vdot, t_samples[i]) + samples[i] = x_next + # t_samples[i] = t + return samples, t_samples + + def simulate_forward(self, x, vdot, t): + t0 = 0 + q = np.copy(x[:self.nq]) + v = np.copy(x[-self.nv:]) + while t0 < t: + q[:4] = q[:4] + self.dt * quat_dot(q[:4], v[:3]) + q[4:] = q[4:] + self.dt * v[3:] + v = v + self.dt * vdot + t0 += self.dt + v[12] = 0 + v[20] = 0 + x_next = np.hstack((q, v)) + + return x_next + diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc index ba982e54e6..7f75690583 100644 --- a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc @@ -10,12 +10,15 @@ using drake::trajectories::PiecewisePolynomial; using drake::EigenPtr; +using drake::multibody::CentroidalMomentumConstraint; using drake::solvers::MathematicalProgram; using drake::solvers::MathematicalProgramResult; using drake::solvers::OsqpSolver; using drake::solvers::OsqpSolverDetails; using drake::solvers::Solve; +using drake::solvers::VectorXDecisionVariable; +using drake::AutoDiffXd; using Eigen::Matrix; using Eigen::Matrix3d; using Eigen::MatrixXd; @@ -32,15 +35,22 @@ using dairlib::systems::OutputVector; namespace dairlib { KinodynamicPlanner::KinodynamicPlanner( - const drake::multibody::MultibodyPlant& plant) + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context& context, + const drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context& context_ad) : plant_(plant), + context_(context), + plant_ad_(plant_ad), + context_ad_(context_ad), n_q_(plant.num_positions()), n_v_(plant.num_velocities()), - n_u_(plant.num_actuators()){ + n_u_(plant.num_actuators()), + m_(plant.CalcTotalMass(context)), + g_(plant.gravity_field().gravity_vector()) { // Create Ports state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector( - n_q_, n_v_, n_u_)) + "x, u, t", OutputVector(n_q_, n_v_, n_u_)) .get_index(); traj_out_port_ = this->DeclareAbstractOutputPort( @@ -51,672 +61,104 @@ KinodynamicPlanner::KinodynamicPlanner( // Discrete update DeclarePerStepDiscreteUpdateEvent( &KinodynamicPlanner::DiscreteVariableUpdate); -// DeclarePeriodicDiscreteUpdateEvent(dt_, 0, -// &KinodynamicPlanner::PeriodicUpdate); + // DeclarePeriodicDiscreteUpdateEvent(dt_, 0, + // &KinodynamicPlanner::PeriodicUpdate); x_des_ = VectorXd ::Zero(n_r_ + n_h_); } -void KinodynamicPlanner::AddMode(const LinearSrbdDynamics& dynamics, - BipedStance stance, const MatrixXd& reset, - int N) { - DRAKE_DEMAND(stance == nmodes_); - SrbdMode mode = {dynamics, reset, stance, N}; - for (int i = 0; i < N; i++) { - xx.push_back(prog_.NewContinuousVariables( - nx_, "x_" + std::to_string(stance) + std::to_string(i))); - uu.push_back(prog_.NewContinuousVariables( - nu_, "u_" + std::to_string(stance) + std::to_string(i))); - } - pp.push_back( - prog_.NewContinuousVariables(kLinearDim_, "p_" + std::to_string(stance))); - total_knots_ += N; - modes_.push_back(mode); - nmodes_++; -} - -void KinodynamicPlanner::FinalizeModeSequence() { - xx.push_back(prog_.NewContinuousVariables(nx_, "x_f")); - uu.push_back(prog_.NewContinuousVariables(nu_, "u_f")); - if (use_residuals_) { - residual_manager_ = std::make_unique( - total_knots_ + 1, modes_.front().dynamics.A, modes_.front().dynamics.B, - modes_.front().dynamics.b); - } -} - -void KinodynamicPlanner::SetReachabilityBoundingBox( - const Vector3d& bounds, - const std::vector& nominal_relative_pos) { - kin_bounds_ = bounds; - for (const auto& pos : nominal_relative_pos) { - nominal_foot_pos_.push_back(pos); - } -} - -void KinodynamicPlanner::CheckProblemDefinition() { - DRAKE_DEMAND(!modes_.empty()); - DRAKE_DEMAND(!nominal_foot_pos_.empty()); - DRAKE_DEMAND(plant_.mass() > 0); - DRAKE_DEMAND(mu_ > 0); - DRAKE_DEMAND(x_des_.rows() == nx_); - CheckSquareMatrixDimensions(Q_, nx_); - CheckSquareMatrixDimensions(Qf_, nx_); - CheckSquareMatrixDimensions(R_, nu_); - CheckSquareMatrixDimensions(Wp_, kLinearDim_); -} - -void KinodynamicPlanner::Build() { - CheckProblemDefinition(); - MakeDynamicsConstraints(); - MakeFrictionConeConstraints(); - MakeKinematicReachabilityConstraints(); - MakeInitialStateConstraint(); - MakeTerrainConstraints(); - MakeCost(); - - drake::solvers::SolverOptions solver_options; - solver_options.SetOption(OsqpSolver::id(), "verbose", 1); - solver_options.SetOption(OsqpSolver::id(), "eps_abs", 1e-5); - solver_options.SetOption(OsqpSolver::id(), "eps_rel", 1e-5); - solver_options.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-4); - solver_options.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-4); - solver_options.SetOption(OsqpSolver::id(), "polish", 1); - solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); - solver_options.SetOption(OsqpSolver::id(), "adaptive_rho_fraction", 1.0); - solver_options.SetOption(OsqpSolver::id(), "max_iter", 20000); - prog_.SetSolverOptions(solver_options); -} - -void KinodynamicPlanner::MakeTerrainConstraints(const Vector3d& normal, - const Vector3d& origin) { - /// TODO: @Brian-Acosta add update function to adapt to terrain - MatrixXd TerrainNormal = normal.transpose(); - VectorXd TerrainPoint = normal.dot(origin) * VectorXd::Ones(1); - for (int i = 0; i < nmodes_; i++) { - terrain_angle_.push_back( - prog_.AddLinearEqualityConstraint(TerrainNormal, TerrainPoint, pp.at(i)) - .evaluator() - .get()); - } -} - -void KinodynamicPlanner::MakeDynamicsConstraints() { - for (int j = 0; j < nmodes_; j++) { - auto mode = modes_.at(j); - for (int i = 0; i < mode.N; i++) { - MatrixXd Aeq = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); - VectorXd beq = VectorXd::Zero(nx_); - Vector3d pos = Vector3d::Zero(); - pos(1) = nominal_foot_pos_.at(j)(1); - CopyCollocationDynamicsConstraint(mode.dynamics, false, pos, &Aeq, &beq); - dynamics_.push_back(prog_.AddLinearEqualityConstraint( - Aeq, beq, - {xx.at(j * mode.N + i), xx.at(j * mode.N + i + 1), - uu.at(j * mode.N + i), uu.at(j * mode.N + i + 1), - pp.at(mode.stance)})); - } - } - // for (auto& binding : dynamics_) { - // std::cout << binding.to_string() << std::endl; - // } -} - -void KinodynamicPlanner::UpdateKinematicConstraints(int n_until_stance, - int fsm_state) const { - for (auto& constraint : kinematic_constraint_) { - prog_.RemoveConstraint(constraint); - } - - kinematic_constraint_.clear(); - - MatrixXd A = MatrixXd::Zero(kLinearDim_, 2 * kLinearDim_); - A << Matrix3d::Identity(), -Matrix3d::Identity(); - auto curr_mode = modes_.at(fsm_state); - auto next_mode = modes_.at(1 - fsm_state); - - std::cout << "Next stance: "; - for (int i = n_until_stance; i <= n_until_stance + next_mode.N; i++) { - kinematic_constraint_.push_back(prog_.AddLinearConstraint( - A, nominal_foot_pos_.at(next_mode.stance) - kin_bounds_, - nominal_foot_pos_.at(next_mode.stance) + kin_bounds_, - {pp.at(next_mode.stance), xx.at(i).head(kLinearDim_)})); - std::cout << std::to_string(i) << " "; - } - std::cout << std::endl; - std::cout << "Next next stance: "; - for (int i = n_until_stance + next_mode.N; i <= total_knots_; i++) { - kinematic_constraint_.push_back(prog_.AddLinearConstraint( - A, nominal_foot_pos_.at(curr_mode.stance) - kin_bounds_, - nominal_foot_pos_.at(curr_mode.stance) + kin_bounds_, - {pp.at(curr_mode.stance), xx.at(i).head(kLinearDim_)})); - std::cout << std::to_string(i) << " "; - } - std::cout << std::endl; -} - -void KinodynamicPlanner::UpdateDynamicsConstraints(const Eigen::VectorXd& x, - int n_until_next_stance, - int fsm_state) const { - auto& mode = modes_.at(fsm_state); - Vector3d pos = plant_.CalcFootPosition(x, mode.stance); - - if (n_until_next_stance == mode.N) { - // make current stance dynamics and apply to mode - MatrixXd Aeq = MatrixXd::Zero(nx_, 2 * (nx_ + nu_)); - VectorXd beq = VectorXd::Zero(nx_); - CopyCollocationDynamicsConstraint(mode.dynamics, true, pos, &Aeq, &beq); - - for (int i = 0; i < (mode.N); i++) { - prog_.RemoveConstraint(dynamics_.at(i)); - dynamics_.at(i) = prog_.AddLinearEqualityConstraint( - Aeq, beq, {xx.at(i), xx.at(i + 1), uu.at(i), uu.at(i + 1)}); - } - - Aeq = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); - beq = VectorXd::Zero(nx_); - CopyCollocationDynamicsConstraint(modes_.at(1 - fsm_state).dynamics, false, - pos, &Aeq, &beq); - prog_.RemoveConstraint(dynamics_.at(mode.N)); - dynamics_.at(mode.N) = prog_.AddLinearEqualityConstraint( - Aeq, beq, - {xx.at(mode.N), xx.at(mode.N + 1), uu.at(mode.N), uu.at(mode.N + 1), - pp.at(1 - fsm_state)}); - } else { - int idx = n_until_next_stance; - MatrixXd Aeq1 = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); - MatrixXd Aeq2 = MatrixXd::Zero(nx_, 2 * (nx_ + nu_) + kLinearDim_); - VectorXd beq1 = VectorXd::Zero(nx_); - VectorXd beq2 = VectorXd::Zero(nx_); - CopyCollocationDynamicsConstraint(modes_.at(1 - fsm_state).dynamics, false, - pos, &Aeq1, &beq1); - - prog_.RemoveConstraint(dynamics_.at(idx)); - dynamics_.at(idx) = prog_.AddLinearEqualityConstraint( - Aeq1, beq1, - {xx.at(idx), xx.at(idx + 1), uu.at(idx), uu.at(idx + 1), - pp.at(1 - fsm_state)}); - - CopyCollocationDynamicsConstraint(mode.dynamics, false, pos, &Aeq2, &beq2); - prog_.RemoveConstraint(dynamics_.at(idx + mode.N)); - dynamics_.at(idx + mode.N) = prog_.AddLinearEqualityConstraint( - Aeq2, beq2, - {xx.at(idx + mode.N), xx.at(idx + mode.N + 1), uu.at(idx + mode.N), - uu.at(idx + mode.N + 1), pp.at(fsm_state)}); - } - std::cout << "\n"; -} - -// void KinodynamicPlanner::UpdateResidualDynamicsConstraints(const -// Eigen::VectorXd& x, -// int n_until_next_stance, int -// fsm_state) const { -// -// auto& mode = modes_.at(fsm_state); -// Vector3d pos = plant_.CalcFootPosition(x, mode.stance); -// -// if (n_until_next_stance == mode.N ) { -// // make current stance dynamics and apply to mode after -// // adding current residual estimate -// MatrixXd Aeq = MatrixXd::Zero(nx_, 2*(nx_ + nu_)); -// VectorXd beq = VectorXd::Zero(nx_); -// -// for (int i = 0; i < (mode.N); i++){ -// LinearSrbdDynamics dyn_i = {A_matrix_t::Zero(), B_matrix_t::Zero(), -// b_vector_t::Zero()}; -// residual_manager_->AddResidualToDynamics( -// residual_dynamics{mode.dynamics.A, mode.dynamics.B, -// mode.dynamics.b}, -// residual_manager_->GetAverageResidualForNextTwoKnots(i), -// &dyn_i.A, &dyn_i.B, &dyn_i.b); -// CopyCollocationDynamicsConstraint( -// dyn_i, true, pos, &Aeq, &beq); -// -// prog_.RemoveConstraint(dynamics_.at(i)); -// dynamics_.at(i) = prog_.AddLinearEqualityConstraint( -// Aeq, beq, -// {xx.at(i), xx.at(i+1), uu.at(i), uu.at(i+1)}); -// -// } -// -// Aeq = MatrixXd::Zero(nx_, 2*(nx_ + nu_) + kLinearDim_); -// beq = VectorXd::Zero(nx_); -// LinearSrbdDynamics dyn_f = {A_matrix_t::Zero(), B_matrix_t::Zero(), -// b_vector_t::Zero()}; residual_manager_->AddResidualToDynamics( -// residual_dynamics{modes_.at(1-fsm_state).dynamics.A, -// modes_.at(1-fsm_state).dynamics.B, -// modes_.at(1-fsm_state).dynamics.b}, -// residual_manager_->GetAverageResidualForNextTwoKnots(mode.N), -// &dyn_f.A, &dyn_f.B, &dyn_f.b); -// CopyCollocationDynamicsConstraint( -// dyn_f,false, pos, &Aeq, &beq); -// prog_.RemoveConstraint(dynamics_.at(mode.N)); -// dynamics_.at(mode.N) = prog_.AddLinearEqualityConstraint( -// Aeq, beq, -// {xx.at(mode.N), xx.at(mode.N+1), -// uu.at(mode.N), uu.at(mode.N+1), -// pp.at(1-fsm_state)}); -// } else { -// int idx = n_until_next_stance; -// -// LinearSrbdDynamics dyn_f = {A_matrix_t::Zero(), B_matrix_t::Zero(), -// b_vector_t::Zero()}; residual_manager_->AddResidualToDynamics( -// residual_dynamics{modes_.at(1-fsm_state).dynamics.A, -// modes_.at(1-fsm_state).dynamics.B, -// modes_.at(1-fsm_state).dynamics.b}, -// residual_manager_->GetAverageResidualForNextTwoKnots(mode.N), -// &dyn_f.A, &dyn_f.B, &dyn_f.b); -// -// MatrixXd Aeq = MatrixXd::Zero(nx_, 2*(nx_ + nu_) + kLinearDim_); -// VectorXd beq = VectorXd::Zero(nx_); -// CopyCollocationDynamicsConstraint( -// dyn_f, false, pos, &Aeq, &beq); -// -// prog_.RemoveConstraint(dynamics_.at(idx)); -// dynamics_.at(idx) = prog_.AddLinearEqualityConstraint( -// Aeq, beq, -// {xx.at(idx), xx.at(idx+1), -// uu.at(idx), uu.at(idx+1), pp.at(1-fsm_state)}); +// void KinodynamicPlanner::print_constraint( +// const std::vector& constraints) const { +// for (auto& x0_const : constraints) { +// std::cout << x0_const->get_description() << ":\n A:\n" +// << x0_const->A() << "\nub:\n" +// << x0_const->upper_bound() << "\nlb\n" +// << x0_const->lower_bound() << std::endl; +// } +//} // -// residual_manager_->AddResidualToDynamics( -// residual_dynamics{mode.dynamics.A, -// mode.dynamics.B, -// mode.dynamics.b}, -// residual_manager_->GetAverageResidualForNextTwoKnots(mode.N), -// &dyn_f.A, &dyn_f.B, &dyn_f.b); -// CopyCollocationDynamicsConstraint(dyn_f, false, pos, &Aeq, &beq); +// void KinodynamicPlanner::print_constraint( +// const std::vector& constraints) +// const { +// for (auto& x0_const : constraints) { +// std::cout << x0_const->get_description() << ":\n A:\n" +// << x0_const->A() << "\nb:\n" +// << x0_const->upper_bound() << std::endl; +// } +//} // -// prog_.RemoveConstraint(dynamics_.at(idx + mode.N)); -// dynamics_.at(idx+mode.N) = prog_.AddLinearEqualityConstraint( -// Aeq, beq, -// {xx.at(idx+mode.N), xx.at(idx+mode.N+1), -// uu.at(idx+mode.N), uu.at(idx+mode.N+1), pp.at(fsm_state)}); +// void KinodynamicPlanner::print_constraint( +// const std::vector& constraints) const { +// for (auto& constraint : constraints) { +// auto constr = dynamic_cast(constraint); +// std::cout << constr->get_description() << ":\n A:\n" +// << constr->A() << "\nb:\n" +// << constr->upper_bound() << std::endl; // } -// std::cout << "\n"; //} -void KinodynamicPlanner::UpdateFootPlacementCost( - int fsm_state, const Eigen::VectorXd& up_next_foot_target, - const Eigen::VectorXd& on_deck_foot_target) const { - foot_target_cost_.at(fsm_state)->UpdateCoefficients( - 2.0 * Wp_, -2.0 * Wp_ * on_deck_foot_target); - foot_target_cost_.at(1 - fsm_state) - ->UpdateCoefficients(2.0 * Wp_, -2.0 * Wp_ * up_next_foot_target); -} - -void KinodynamicPlanner::MakeInitialStateConstraint() { - initial_state_ = - prog_ - .AddLinearEqualityConstraint(MatrixXd::Identity(nx_, nx_), - VectorXd::Zero(nx_), xx.at(0)) - .evaluator() - .get(); -} - -void KinodynamicPlanner::MakeKinematicReachabilityConstraints() { - MatrixXd A = MatrixXd::Zero(kLinearDim_, 2 * kLinearDim_); - A << Matrix3d::Identity(), -Matrix3d::Identity(); - for (int j = 0; j < nmodes_; j++) { - auto mode = modes_.at(j); - for (int i = 0; i <= mode.N; i++) { - kinematic_constraint_.push_back(prog_.AddLinearConstraint( - A, nominal_foot_pos_.at(mode.stance) - kin_bounds_, - nominal_foot_pos_.at(mode.stance) + kin_bounds_, - {pp.at(mode.stance), xx.at(i + j * mode.N).head(kLinearDim_)})); - } +void KinodynamicPlanner::AddCoMDynamicsConstraint() { + for (int i = 0; i < n_knot_points_; ++i) { + prog_.AddLinearEqualityConstraint( + m_ * ddr_[i] - F_[i][0] - F_[i][1] - F_[i][2] - F_[i][3], m_ * g_); } } -void KinodynamicPlanner::MakeFrictionConeConstraints() { - for (int i = 0; i <= total_knots_; i++) { - friction_cone_.push_back( - prog_ - .AddConstraint(solvers::CreateLinearFrictionConstraint(mu_), - uu.at(i).head(kLinearDim_)) - .evaluator() - .get()); +void KinodynamicPlanner::AddCentroidalMomentumConstraint() { + for (int i = 0; i < n_knot_points_; ++i) { + centroidal_momentum_constraints_.push_back( + std::make_shared(&plant_ad_, std::nullopt, + &context_ad_, true)); +// VectorXDecisionVariable x; + // constraint.ComposeVariable(q_.at(i).eval(), v_.at(i).eval(), + // h_.at(i).eval(), x); constraint.ComposeVariable(q_.at(i), v_.at(i), + // h_.at(i), &x); constraint.ComposeVariable(q_.at(i), v_.at(i), + // h_.at(i), &q_.at(i)); + prog_.AddConstraint(centroidal_momentum_constraints_[i], + {q_.at(i), v_.at(i), h_.at(i)}); } } -void KinodynamicPlanner::MakeCost() { - VectorXd unom = VectorXd::Zero(nu_); - unom(2) = 9.81 * plant_.mass(); - for (int i = 0; i <= total_knots_; i++) { - Matrix Q = (i == 0 || i == total_knots_) ? 0.5 * Q_ : Q_; - Matrix R = (i == 0 || i == total_knots_) ? 0.5 * R_ : R_; - tracking_cost_.push_back( - prog_.AddQuadraticErrorCost(Q, x_des_, xx.at(i)).evaluator().get()); - input_cost_.push_back( - prog_.AddQuadraticErrorCost(R, unom, uu.at(i)).evaluator().get()); - } - for (int i = 0; i < nmodes_; i++) { - foot_target_cost_.push_back( - prog_.AddQuadraticErrorCost(Wp_, nominal_foot_pos_.at(i), pp.at(i)) - .evaluator() - .get()); +void KinodynamicPlanner::AddAngularMomentumDynamicsConstraint() { + for (int i = 0; i < n_knot_points_; ++i) { + centroidal_momentum_constraints_.push_back( + std::make_shared(&plant_ad_, std::nullopt, + &context_ad_, true)); +// VectorXDecisionVariable x; + // constraint.ComposeVariable(q_.at(i).eval(), v_.at(i).eval(), + // h_.at(i).eval(), x); constraint.ComposeVariable(q_.at(i), v_.at(i), + // h_.at(i), &x); constraint.ComposeVariable(q_.at(i), v_.at(i), + // h_.at(i), &q_.at(i)); +// prog_.AddConstraint(dh_.at(i) == (c_[i][0] - r_[i][0]).cross(F_[i][0]), +// {q_.at(i), v_.at(i), h_.at(i)}); } } -void KinodynamicPlanner::AddTrackingObjective(const VectorXd& xdes, - const MatrixXd& Q) { - Q_ = Q; - x_des_ = xdes; -} - -void KinodynamicPlanner::SetTerminalCost(const MatrixXd& Qf) { Qf_ = Qf; } - -void KinodynamicPlanner::AddInputRegularization(const Eigen::MatrixXd& R) { - R_ = R; -} - -void KinodynamicPlanner::AddFootPlacementRegularization( - const Eigen::MatrixXd& W) { - Wp_ = W; -} - -void KinodynamicPlanner::GetMostRecentMotionPlan( - const drake::systems::Context& context, - dairlib::lcmt_saved_traj* traj_msg) const { - *traj_msg = most_recent_sol_; -} +void KinodynamicPlanner::AddIntegrationConstraints(){ + for (int i = 1; i < n_knot_points_; ++i) { + // eq 7d + prog_.AddLinearEqualityConstraint(q_[i] - q_[i-1] == v_[i] * dt_[i]); + // eq 7e + prog_.AddLinearEqualityConstraint(h_[i] - h_[i-1] == dh_[i] * dt_[i]); -EventStatus KinodynamicPlanner::DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const { - const BasicVector* fsm_output = - (BasicVector*)this->EvalVectorInput(context, fsm_port_); - VectorXd fsm_state = fsm_output->get_value(); + // eq 7f +// prog_.AddLinearEqualityConstraint(r_[i] - r_[i-1] == (dr_[i] + dr_[i-1])/2 * dt_[i]); + prog_.AddLinearEqualityConstraint(r_[i] - r_[i-1] == dr_[i] * dt_[i]); - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); - double timestamp = robot_output->get_timestamp(); - - VectorXd xdes = this->EvalVectorInput(context, x_des_port_)->get_value(); - - if (xdes != x_des_) { - UpdateTrackingObjective(xdes); - } - - if (use_fsm_) { - auto current_fsm_state = - discrete_state->get_mutable_vector(current_fsm_state_idx_) - .get_mutable_value(); - - if (fsm_state(0) != current_fsm_state(0)) { - current_fsm_state(0) = fsm_state(0); - discrete_state->get_mutable_vector(prev_event_time_idx_) - .get_mutable_value() - << timestamp; - } + // eq 7g + prog_.AddLinearEqualityConstraint(dr_[i] - dr_[i-1] == ddr_[i] * dt_[i]); } - return EventStatus::Succeeded(); } -EventStatus KinodynamicPlanner::PeriodicUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const { - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); - - // const drake::AbstractValue* traj_value = - // this->EvalAbstractInput(context, srb_warmstart_port_); - // - // const auto& warmstart_traj = - // traj_value->get_value>(); - - VectorXd x = robot_output->GetState(); - - double timestamp = robot_output->get_timestamp(); - double time_since_last_event = timestamp; - int fsm_state = 0; - - if (use_fsm_) { - fsm_state = (int)(discrete_state->get_vector(current_fsm_state_idx_) - .get_value()(0)); - double last_event_time = - discrete_state->get_vector(prev_event_time_idx_).get_value()(0); - - time_since_last_event = - (last_event_time <= 0) ? timestamp : timestamp - last_event_time; - - if (use_residuals_) { - residual_dynamics res = - this->EvalAbstractInput(context, srbd_residual_port_) - ->get_value(); - DRAKE_DEMAND(res.A.cols() == nx_ + kLinearDim_); - DRAKE_DEMAND(res.B.cols() == nu_); - DRAKE_DEMAND(res.b.rows() == nx_); - residual_manager_->SetResidualForCurrentKnot(res); - } - - UpdateConstraints(plant_.CalcSRBStateFromPlantState(x), fsm_state, - time_since_last_event); - } else { - UpdateConstraints(plant_.CalcSRBStateFromPlantState(x), 0, 0); - } - - // VectorXd foot_target = - // this->EvalVectorInput(context, foot_target_port_)->get_value(); - UpdateFootPlacementCost(fsm_state, Vector3d::Zero(), Vector3d::Zero()); - // - // SetInitialGuess(fsm_state, timestamp, - // foot_target.head(kLinearDim_), - // foot_target.tail(kLinearDim_), - // warmstart_traj); - - // auto lin_con = prog_.GetAllLinearConstraints(); - // for (auto& binding : lin_con) { - // std::cout << "Next Binding:\n" << binding << std::endl; - // } - // print_constraint(lin_con); - - result_ = solver_.Solve(prog_); - - if (!result_.is_success()) { - std::cout << "result: " << result_.get_solution_result() << std::endl; - } - - most_recent_sol_ = MakeLcmTrajFromSol(result_, timestamp, - time_since_last_event, x, fsm_state); - return EventStatus::Succeeded(); -} - -void KinodynamicPlanner::UpdateTrackingObjective(const VectorXd& xdes) const { - x_des_ = xdes; - for (auto& cost : tracking_cost_) { - cost->UpdateCoefficients(2.0 * Q_, -2.0 * Q_ * xdes); - } -} - -void KinodynamicPlanner::UpdateConstraints( - const VectorXd& x0, const int fsm_state, - const double t_since_last_switch) const { - initial_state_->UpdateCoefficients(MatrixXd::Identity(nx_, nx_), x0); - - if (!use_fsm_) { - return; - } - std::cout << "Time since last switch: " << std::to_string(t_since_last_switch) - << std::endl; - int n_until_next_state = - modes_.at(fsm_state).N - std::floor(t_since_last_switch / dt_); - if (use_residuals_) { - UpdateResidualDynamicsConstraints(x0, n_until_next_state, fsm_state); - residual_manager_->CycleCurrentKnot(); - } else { - UpdateDynamicsConstraints(x0, n_until_next_state, fsm_state); - } - UpdateKinematicConstraints(n_until_next_state, fsm_state); -} - -void KinodynamicPlanner::SetInitialGuess( - int fsm_state, double timestamp, - const Eigen::VectorXd& up_next_stance_target, - const Eigen::VectorXd& on_deck_stance_target, - const drake::trajectories::Trajectory& srb_traj) const { - prog_.SetInitialGuess(pp.at(fsm_state), on_deck_stance_target); - prog_.SetInitialGuess(pp.at(1 - fsm_state), up_next_stance_target); - VectorXd srb_guess(nx_); - for (int i = 0; i < total_knots_; i++) { - double t = timestamp + i * dt_; - - Eigen::Vector4d u_guess(0, 0, plant_.mass() * 9.81, 0); - srb_guess.head(nx_ / 2) = srb_traj.value(t); - srb_guess.tail(nx_ / 2) = srb_traj.EvalDerivative(t, 1); - prog_.SetInitialGuess(xx.at(i), srb_guess); - prog_.SetInitialGuess(uu.at(i), u_guess); - } - double t = timestamp + total_knots_ * dt_; - srb_guess.head(nx_ / 2) = srb_traj.value(t); - srb_guess.tail(nx_ / 2) = srb_traj.EvalDerivative(t, 1); - prog_.SetInitialGuess(xx.back(), srb_guess); +void KinodynamicPlanner::AddDynamicsConstraint() { + AddCoMDynamicsConstraint(); + AddCentroidalMomentumConstraint(); + AddIntegrationConstraints(); } -lcmt_saved_traj KinodynamicPlanner::MakeLcmTrajFromSol( - const drake::solvers::MathematicalProgramResult& result, double time, - double time_since_last_touchdown, const VectorXd& state, - int fsm_state) const { - DRAKE_DEMAND(result.is_success()); +void KinodynamicPlanner::AddKinematicConstraints(){ + // Linearize the kinematic constraints about current state - LcmTrajectory::Trajectory CoMTraj; - LcmTrajectory::Trajectory AngularTraj; - LcmTrajectory::Trajectory SwingFootTraj; - LcmTrajectory::Trajectory InputTraj; - - CoMTraj.traj_name = "com_traj"; - AngularTraj.traj_name = "orientation"; - SwingFootTraj.traj_name = "swing_foot_traj"; - InputTraj.traj_name = "input_traj"; - - /** need to set datatypes for LcmTrajectory to save properly **/ - for (int i = 0; i < 2 * kLinearDim_; i++) { - CoMTraj.datatypes.emplace_back("double"); - AngularTraj.datatypes.emplace_back("double"); - } - for (int i = 0; i < kLinearDim_; i++) { - SwingFootTraj.datatypes.emplace_back("double"); - InputTraj.datatypes.emplace_back("double"); - } - InputTraj.datatypes.emplace_back("double"); - - /** Allocate Eigen matrices for trajectory blocks **/ - MatrixXd com = MatrixXd::Zero(2 * kLinearDim_, total_knots_); - MatrixXd orientation = MatrixXd::Zero(2 * kAngularDim_, total_knots_); - MatrixXd input = MatrixXd::Zero(nu_, total_knots_); - VectorXd time_knots = VectorXd::Zero(total_knots_); - - for (int i = 0; i < total_knots_; i++) { - VectorXd ui = result.GetSolution(uu.at(i)); - VectorXd xi = result.GetSolution(xx.at(i)); - input.col(i) = ui; - com.block(0, i, 2 * kLinearDim_, 1) << xi.head(kLinearDim_), - xi.segment(kLinearDim_ + kAngularDim_, kLinearDim_); - orientation.block(0, i, 2 * kAngularDim_, 1) - << xi.segment(kLinearDim_, kAngularDim_), - xi.tail(kAngularDim_); - - time_knots(i) = time + dt_ * i; - } - - InputTraj.time_vector = time_knots; - InputTraj.datapoints = input; - CoMTraj.time_vector = time_knots; - CoMTraj.datapoints = com; - AngularTraj.time_vector = time_knots; - AngularTraj.datapoints = orientation; - - VectorXd swing_ft_traj_breaks = VectorXd::Ones(1) * time; - SwingFootTraj.time_vector = swing_ft_traj_breaks; - SwingFootTraj.datapoints = result.GetSolution(pp.at(1 - fsm_state)); - - LcmTrajectory lcm_traj; - lcm_traj.AddTrajectory(CoMTraj.traj_name, CoMTraj); - lcm_traj.AddTrajectory(AngularTraj.traj_name, AngularTraj); - lcm_traj.AddTrajectory(SwingFootTraj.traj_name, SwingFootTraj); - lcm_traj.AddTrajectory(InputTraj.traj_name, InputTraj); - - return lcm_traj.GenerateLcmObject(); -} - -void KinodynamicPlanner::print_constraint( - const std::vector& constraints) const { - for (auto& x0_const : constraints) { - std::cout << x0_const->get_description() << ":\n A:\n" - << x0_const->A() << "\nub:\n" - << x0_const->upper_bound() << "\nlb\n" - << x0_const->lower_bound() << std::endl; - } -} - -void KinodynamicPlanner::print_constraint( - const std::vector& constraints) - const { - for (auto& x0_const : constraints) { - std::cout << x0_const->get_description() << ":\n A:\n" - << x0_const->A() << "\nb:\n" - << x0_const->upper_bound() << std::endl; - } -} - -void KinodynamicPlanner::print_constraint( - const std::vector& constraints) const { - for (auto& constraint : constraints) { - auto constr = dynamic_cast(constraint); - std::cout << constr->get_description() << ":\n A:\n" - << constr->A() << "\nb:\n" - << constr->upper_bound() << std::endl; - } -} - -void KinodynamicPlanner::CopyDiscreteDynamicsConstraint( - const SrbdMode& mode, bool current_stance, const Vector3d& foot_pos, - const drake::EigenPtr& A, - const drake::EigenPtr& b) const { - DRAKE_DEMAND(A != nullptr && b != nullptr); - - if (!current_stance) { - A->block(0, 0, nx_, nx_ + kLinearDim_) = mode.dynamics.A; - A->block(0, nx_ + kLinearDim_, nx_, nu_) = mode.dynamics.B; - A->block(0, nx_ + nu_ + kLinearDim_, nx_, nx_) = - -MatrixXd::Identity(nx_, nx_); - *b = -mode.dynamics.b; - } else { - A->block(0, 0, nx_, nx_) = mode.dynamics.A.block(0, 0, nx_, nx_); - A->block(0, nx_, nx_, nu_) = mode.dynamics.B; - A->block(0, nx_ + nu_, nx_, nx_) = -MatrixXd::Identity(nx_, nx_); - *b = -(mode.dynamics.A.block(0, nx_, nx_, kLinearDim_) * foot_pos + - mode.dynamics.b); - } -} - -void KinodynamicPlanner::CopyCollocationDynamicsConstraint( - const LinearSrbdDynamics& dyn, bool current_stance, - const Eigen::Vector3d& foot_pos, const drake::EigenPtr& A, - const drake::EigenPtr& b) const { - DRAKE_DEMAND(A != nullptr && b != nullptr); - if (current_stance) { - DRAKE_DEMAND(A->cols() == 2 * (nx_ + nu_)); - } else { - DRAKE_DEMAND(A->cols() == 2 * (nx_ + nu_) + 3); - } - - Matrix Ax = dyn.A.block(0, 0, nx_, nx_); - Matrix Ap = dyn.A.block(0, nx_, nx_, nx_ + kLinearDim_); - double h = dt_; - A->block(0, 0, nx_, nx_) = (0.125 * h) * Ax * Ax - 0.75 * Ax - - (1.5 / h) * MatrixXd::Identity(nx_, nx_); - A->block(0, nx_, nx_, nx_) = -(0.125 * h) * Ax * Ax - 0.75 * Ax + - (1.5 / h) * MatrixXd::Identity(nx_, nx_); - A->block(0, 2 * nx_, nx_, nu_) = - (0.125 * h * Ax - 0.75 * MatrixXd::Identity(nx_, nx_)) * dyn.B; - A->block(0, 2 * nx_ + nu_, nx_, nu_) = - (-0.125 * h * Ax - 0.75 * MatrixXd::Identity(nx_, nx_)) * dyn.B; - if (current_stance) { - *b = 1.5 * dyn.b + 1.5 * Ap * foot_pos; - } else { - A->block(0, 2 * (nx_ + nu_), nx_, kLinearDim_) = -1.5 * Ap; - *b = 1.5 * dyn.b; - } } void KinodynamicPlanner::CheckSquareMatrixDimensions(const MatrixXd& M, diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.h b/examples/Cassie/contact_scheduler/kinodynamic_planner.h index 384aeac27d..63b6f7ee22 100644 --- a/examples/Cassie/contact_scheduler/kinodynamic_planner.h +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.h @@ -10,12 +10,14 @@ #include "examples/Cassie/contact_scheduler/kinodynamic_settings.h" #include "lcm/lcm_trajectory.h" + #include "multibody/multibody_utils.h" #include "solvers/constraint_factory.h" #include "solvers/fast_osqp_solver.h" #include "systems/framework/output_vector.h" - #include "drake/common/trajectories/piecewise_polynomial.h" + +#include "drake/multibody/optimization/centroidal_momentum_constraint.h" //#include "drake/solvers/gurobi_solver.h" #include "drake/solvers/mathematical_program.h" #include "drake/solvers/osqp_solver.h" @@ -45,11 +47,16 @@ typedef struct LinearSrbdDynamics { class KinodynamicPlanner : public drake::systems::LeafSystem { public: - KinodynamicPlanner(const drake::multibody::MultibodyPlant& plant); + KinodynamicPlanner(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context& context, + const drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context& context_ad); void SetMPCSettings(KinodynamicSettings& settings); void SetTerminalCost(const Eigen::MatrixXd& Qf); void AddInputRegularization(const Eigen::MatrixXd& R); + void AddTrackingObjective(const Eigen::VectorXd& xdes, + const Eigen::MatrixXd& Q); // void AddFootPlacementRegularization(const Eigen::MatrixXd& W); void Build(); void CheckProblemDefinition(); @@ -139,16 +146,41 @@ class KinodynamicPlanner : public drake::systems::LeafSystem { const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; + + void AddCentroidalMomentumConstraint(); + void AddAngularMomentumDynamicsConstraint(); + void AddCoMDynamicsConstraint(); + void AddDynamicsConstraint(); + void AddIntegrationConstraints(); + void AddKinematicConstraints(); + + // plant const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context& context_; + const drake::multibody::MultibodyPlant& plant_ad_; + drake::systems::Context& context_ad_; double mu_ = 0; int n_q_; int n_v_; int n_u_; + // centroidal optimization parameters + double m_; + Eigen::Vector3d g_; + int n_contacts_ = 4; int n_r_ = 3; int n_h_ = 3; + // mpc parameters + int n_knot_points_ = 4; + + + + + + + // parameters and constants // const bool use_fsm_; @@ -203,7 +235,24 @@ class KinodynamicPlanner : public drake::systems::LeafSystem { mutable std::vector> kinematic_constraint_; + + // Constraints + std::vector> centroidal_momentum_constraints_; + + // Decision Variables + std::vector q_; + std::vector v_; + std::vector dt_; + std::vector r_; + std::vector dr_; + std::vector ddr_; + std::vector> c_; + std::vector> F_; + std::vector> tau_; + std::vector h_; + std::vector dh_; + std::vector xx; std::vector uu; std::vector pp; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 6cadb5ed02..26ba467da7 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -120,8 +120,8 @@ OperationalSpaceControl::OperationalSpaceControl( VectorXd u_min(n_u_); VectorXd u_max(n_u_); for (JointActuatorIndex i(0); i < n_u_; ++i) { - u_min(i) = -plant_wo_spr_.get_joint_actuator(i).effort_limit(); - u_max(i) = plant_wo_spr_.get_joint_actuator(i).effort_limit(); + u_min[i] = -plant_wo_spr_.get_joint_actuator(i).effort_limit(); + u_max[i] = plant_wo_spr_.get_joint_actuator(i).effort_limit(); } u_min_ = u_min; u_max_ = u_max; @@ -547,9 +547,13 @@ VectorXd OperationalSpaceControl::SolveQp( bool near_impact = alpha != 0; VectorXd v_proj = VectorXd::Zero(n_v_); if (near_impact) { + auto start = std::chrono::high_resolution_clock::now(); UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, time_since_last_state_switch, fsm_state, next_fsm_state, M); + auto finish = std::chrono::high_resolution_clock::now(); + std::chrono::duration elapsed = finish - start; + cout << "Solve time:" << elapsed.count() << std::endl; // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; } From a6a91d3368cc2aded2cc2caa0ba5bc5c944e0ef6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Jul 2022 16:00:11 -0400 Subject: [PATCH 242/758] figuring out timing issue in dispatcherin --- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 26 +++++++++++-------- examples/Cassie/systems/input_supervisor.cc | 2 +- .../osc/operational_space_control.cc | 4 +-- 4 files changed, 19 insertions(+), 15 deletions(-) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 77018011b9..17d2124ee3 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -126,7 +126,7 @@ int do_main(int argc, char* argv[]) { int nu = plant.num_actuators(); VectorXd input_limit(nu); for (drake::multibody::JointActuatorIndex i(0); i < nu; ++i) { - input_limit(i) = plant.get_joint_actuator(i).effort_limit(); + input_limit[i] = plant.get_joint_actuator(i).effort_limit(); } auto input_supervisor = builder.AddSystem( diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 8cdee9137e..4323e3381e 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -1,4 +1,5 @@ #include +#include #include @@ -157,9 +158,9 @@ void setInitialEkfState(double t0, const cassie_out_t& cassie_output, int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - DiagramBuilder builder; - auto lcm = builder.AddSystem(); + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); + DiagramBuilder builder; // Build Cassie MBP drake::multibody::MultibodyPlant plant(0.0); @@ -229,7 +230,7 @@ int do_main(int argc, char* argv[]) { if (FLAGS_floating_base && FLAGS_test_with_ground_truth_state) { auto state_sub = builder.AddSystem( LcmSubscriberSystem::Make( - FLAGS_state_channel_name, lcm)); + FLAGS_state_channel_name, &lcm_local)); auto state_receiver = builder.AddSystem(plant); builder.Connect(state_sub->get_output_port(), @@ -247,13 +248,14 @@ int do_main(int argc, char* argv[]) { // Create and connect contact estimation publisher. auto contact_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_CONTACT_DISPATCHER", lcm, {TriggerType::kForced})); + "CASSIE_CONTACT_DISPATCHER", &lcm_local, {TriggerType::kForced})); builder.Connect(state_estimator->get_contact_output_port(), contact_pub->get_input_port()); // TODO(yangwill): Consider filtering contact estimation auto gm_contact_pub = builder.AddSystem( LcmPublisherSystem::Make( - "CASSIE_GM_CONTACT_DISPATCHER", lcm, {TriggerType::kForced})); + "CASSIE_GM_CONTACT_DISPATCHER", &lcm_local, + {TriggerType::kForced})); builder.Connect(state_estimator->get_gm_contact_output_port(), gm_contact_pub->get_input_port()); } @@ -292,7 +294,7 @@ int do_main(int argc, char* argv[]) { if (FLAGS_broadcast_robot_state) { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_DISPATCHER", lcm, {TriggerType::kForced})); + "CASSIE_STATE_DISPATCHER", &lcm_local, {TriggerType::kForced})); builder.Connect(*robot_output_sender, *state_pub); auto net_state_pub = builder.AddSystem(LcmPublisherSystem::Make( @@ -303,7 +305,7 @@ int do_main(int argc, char* argv[]) { } else { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_STATE_DISPATCHER", lcm, {TriggerType::kForced})); + "CASSIE_STATE_DISPATCHER", &lcm_local, {TriggerType::kForced})); builder.Connect(*robot_output_sender, *state_pub); // Create and connect RobotOutput publisher (low-rate for the network) @@ -327,9 +329,10 @@ int do_main(int argc, char* argv[]) { // Wait for the first message. drake::log()->info("Waiting for first lcmt_cassie_out"); - drake::lcm::Subscriber input_sub(lcm, + drake::lcm::Subscriber input_sub(&lcm_local, "CASSIE_OUTPUT"); - LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); // Initialize the context based on the first message. const double t0 = input_sub.message().utime * 1e-6; @@ -353,14 +356,15 @@ int do_main(int argc, char* argv[]) { while (true) { // Wait for an lcmt_cassie_out message. input_sub.clear(); - LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); // Write the lcmt_robot_input message into the context and advance. input_value.GetMutableData()->set_value(input_sub.message()); const double time = input_sub.message().utime * 1e-6; // Hacks -- for some reason, sometimes the lcm from Mujoco is not in order if (prev_time > time) { - std::cout << "time: " << time << std::endl; + std::cout << time << std::endl; continue; } diff --git a/examples/Cassie/systems/input_supervisor.cc b/examples/Cassie/systems/input_supervisor.cc index 6ebddd4f40..28f311dcb4 100644 --- a/examples/Cassie/systems/input_supervisor.cc +++ b/examples/Cassie/systems/input_supervisor.cc @@ -241,7 +241,7 @@ drake::systems::EventStatus InputSupervisor::UpdateErrorFlag( } if (command->get_data().array().isNaN().any()) { discrete_state->get_mutable_value( - error_indices_index_)[error_indices_.at("is_nan")] = 0; + error_indices_index_)[error_indices_.at("is_nan")] = 1; } if (context.get_discrete_state(n_fails_index_)[0] >= min_consecutive_failures_) { diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 6cadb5ed02..9d8afd4ec4 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -120,8 +120,8 @@ OperationalSpaceControl::OperationalSpaceControl( VectorXd u_min(n_u_); VectorXd u_max(n_u_); for (JointActuatorIndex i(0); i < n_u_; ++i) { - u_min(i) = -plant_wo_spr_.get_joint_actuator(i).effort_limit(); - u_max(i) = plant_wo_spr_.get_joint_actuator(i).effort_limit(); + u_min[i] = -plant_wo_spr_.get_joint_actuator(i).effort_limit(); + u_max[i] = plant_wo_spr_.get_joint_actuator(i).effort_limit(); } u_min_ = u_min; u_max_ = u_max; From 7a66a9f9aacfd106250571813e1dfca4692a707f Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Jul 2022 16:23:45 -0400 Subject: [PATCH 243/758] Revert "using lcm default url path" This reverts commit 98a10af2 --- .bazelrc | 2 +- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/run_controller_switch.cc | 20 +++++++++++-------- examples/Cassie/run_osc_running_controller.cc | 2 +- .../Cassie/run_osc_standing_controller.cc | 2 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- .../Cassie/run_osc_walking_controller_alip.cc | 2 +- 7 files changed, 18 insertions(+), 14 deletions(-) diff --git a/.bazelrc b/.bazelrc index 77f18fabcc..bc2090de3d 100644 --- a/.bazelrc +++ b/.bazelrc @@ -52,7 +52,7 @@ build --action_env=LD_LIBRARY_PATH= # customizations somehow. # build with snopt -build --define=WITH_SNOPT=ON +build --define=WITH_SNOPT=OFF # use python3 by default build --python_path=python3 diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 17d2124ee3..4e917cef52 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -67,7 +67,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index 405bbc0ba3..df85224517 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -1,7 +1,6 @@ #include #include -#include #include #include "dairlib/lcmt_controller_switch.hpp" @@ -79,12 +78,15 @@ int do_main(int argc, char* argv[]) { // offset has to be positive DRAKE_DEMAND(FLAGS_fsm_offset >= 0); + // Parameters + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + // Build the diagram drake::systems::DiagramBuilder builder; - auto lcm = builder.AddSystem(); auto name_pub = builder.AddSystem( LcmPublisherSystem::Make( - FLAGS_switch_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); + FLAGS_switch_channel, &lcm_local, + TriggerTypeSet({TriggerType::kForced}))); auto owned_diagram = builder.Build(); owned_diagram->set_name(("switch publisher")); @@ -94,12 +96,13 @@ int do_main(int argc, char* argv[]) { auto& diagram_context = simulator.get_mutable_context(); // Create subscriber for lcm driven loop - drake::lcm::Subscriber input_sub(lcm, + drake::lcm::Subscriber input_sub(&lcm_local, FLAGS_channel_x); // Wait for the first message and initialize the context time.. drake::log()->info("Waiting for first lcm input message"); - LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); const double t0 = input_sub.message().utime * 1e-6; diagram_context.SetTime(t0); @@ -107,8 +110,8 @@ int do_main(int argc, char* argv[]) { double t_threshold = t0; if (FLAGS_n_period_delay > 0) { t_threshold = (floor(t0 / FLAGS_fsm_period) + FLAGS_n_period_delay) * - FLAGS_fsm_period + - FLAGS_fsm_offset; + FLAGS_fsm_period + + FLAGS_fsm_offset; } // Create output message dairlib::lcmt_controller_switch msg; @@ -121,7 +124,8 @@ int do_main(int argc, char* argv[]) { while (pub_count < FLAGS_n_publishes) { // Wait for input message. input_sub.clear(); - LcmHandleSubscriptionsUntil(lcm, [&]() { return input_sub.count() > 0; }); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); // Get message time from the input channel double t_current = input_sub.message().utime * 1e-6; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index aa135eab5f..5c19de0a2c 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -169,7 +169,7 @@ int DoMain(int argc, char* argv[]) { plant, fsm_states, state_durations, 0.0, gains.impact_threshold, gains.impact_tau); /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm; + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant); auto command_pub = diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 7e3c154328..9a6e72c266 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -103,7 +103,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // auto osc_gains = // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); drake::yaml::LoadYamlOptions yaml_options; diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 104a8f2ab4..10088e17b4 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -113,7 +113,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 6a29665edf..e9fc21d6c3 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -124,7 +124,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both From 8d72073cdf5e0517b24dcd4a7f1ca3f280d1fc31 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 13 Jul 2022 11:58:43 -0400 Subject: [PATCH 244/758] fixing build issues after 22.04 --- WORKSPACE | 2 +- .../analysis/cassie_plotting_utils.py | 7 +--- .../pydairlib/analysis/process_lcm_log.py | 25 ++++++++------ examples/Cassie/run_dircon_jumping.cc | 4 +-- signalscope/BUILD.bazel | 34 +++++++++---------- 5 files changed, 35 insertions(+), 37 deletions(-) diff --git a/WORKSPACE b/WORKSPACE index e42f784543..653b25359b 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,7 +11,7 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "a6005354c97db4160d67ee735b1e01efcd633d9b" +DRAKE_COMMIT = "ade445d67e232077aa2d2c805022238f5682dbc6" DRAKE_CHECKSUM = "708cc2f868be1b07c87c730ffb423b87b0cd6120f7e9e7fe65b56139c832704a" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 672cb6574a..8c00056066 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -5,7 +5,6 @@ # lcmtype imports import dairlib -import archive.dairlib import drake # dairlib python binding imports @@ -39,11 +38,7 @@ 'OSC_STANDING': dairlib.lcmt_robot_input, 'OSC_JUMPING': dairlib.lcmt_robot_input, 'OSC_RUNNING': dairlib.lcmt_robot_input, - 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, - 'OSC_DEBUG_STANDING': archive.dairlib.lcmt_osc_output, - 'OSC_DEBUG_WALKING': archive.dairlib.lcmt_osc_output, - 'OSC_DEBUG_JUMPING': archive.dairlib.lcmt_osc_output, - 'OSC_DEBUG_RUNNING': archive.dairlib.lcmt_osc_output} + 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out} cassie_contact_channels = \ {'CASSIE_CONTACT_DRAKE': drake.lcmt_contact_results_for_viz, diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/analysis/process_lcm_log.py index cfb189a856..24dcb7171e 100644 --- a/bindings/pydairlib/analysis/process_lcm_log.py +++ b/bindings/pydairlib/analysis/process_lcm_log.py @@ -1,3 +1,5 @@ +import lcm + def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_callback, *args, **kwargs): """ @@ -43,6 +45,7 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca def get_log_summary(lcm_log): channel_names_and_msg_counts = {} + import pdb; pdb.set_trace() for event in lcm_log: if event.channel not in channel_names_and_msg_counts: channel_names_and_msg_counts[event.channel] = 1 @@ -63,14 +66,14 @@ def passthrough_callback(data, *args, **kwargs): return data -def main(): - import lcm - import sys - - logfile = sys.argv[1] - log = lcm.EventLog(logfile, "r") - print_log_summary(logfile, log) - - -if __name__ == "__main__": - main() +# def main(): +# import lcm +# import sys +# +# logfile = sys.argv[1] +# log = lcm.EventLog(logfile, "r") +# print_log_summary(logfile, log) +# +# +# if __name__ == "__main__": +# main() diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 1644c5403a..00e75aa268 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -567,8 +567,8 @@ void SetKinematicConstraints(Dircon* trajopt, VectorXd u_min(n_u); VectorXd u_max(n_u); for (drake::multibody::JointActuatorIndex i(0); i < n_u; ++i) { - u_min(i) = 0.75 * -plant.get_joint_actuator(i).effort_limit(); - u_max(i) = 0.75 * plant.get_joint_actuator(i).effort_limit(); + u_min[i] = 0.75 * -plant.get_joint_actuator(i).effort_limit(); + u_max[i] = 0.75 * plant.get_joint_actuator(i).effort_limit(); } for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); diff --git a/signalscope/BUILD.bazel b/signalscope/BUILD.bazel index a33d8a779a..ae657a022e 100644 --- a/signalscope/BUILD.bazel +++ b/signalscope/BUILD.bazel @@ -1,23 +1,23 @@ package(default_visibility = ["//visibility:public"]) -py_library( - name = "dairlib-signal-scope", - srcs = glob(["scripts/**"]) + [ - "startscope.py", - ], -) +#py_library( +# name = "dairlib-signal-scope", +# srcs = glob(["scripts/**"]) + [ +# "startscope.py", +# ], +#) -py_binary( - name = "signal-scope-py", - srcs = ["signal-scope.py"], - data = ["@signal_scope"], - main = "signal-scope.py", - deps = ["//lcmtypes:lcmtypes_robot_py"], -) +#py_binary( +# name = "signal-scope-py", +# srcs = ["signal-scope.py"], +# data = ["@signal_scope"], +# main = "signal-scope.py", +# deps = ["//lcmtypes:lcmtypes_robot_py"], +#) load("@drake//tools/skylark:drake_runfiles_binary.bzl", "drake_runfiles_binary") -drake_runfiles_binary( - name = "signal-scope", - target = ":signal-scope-py", -) +#drake_runfiles_binary( +# name = "signal-scope", +# target = ":signal-scope-py", +#) From 621da7dd872160eb7648d21abbefa94f9cdc9fb1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 14 Jul 2022 10:53:54 -0400 Subject: [PATCH 245/758] reverting gains to slower gait from May --- .../Cassie/osc_run/osc_running_gains.yaml | 44 +++++++++---------- .../osc/operational_space_control.cc | 8 ++-- 2 files changed, 26 insertions(+), 26 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 55595b198a..126a21a187 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ -w_input: 0.0000 +w_input: 0.0001 w_input_reg: 0.1 w_accel: 0.0001 -w_soft_constraint: 1 +w_soft_constraint: 100 impact_threshold: 0.1 impact_tau: 0.05 mu: 0.6 @@ -29,8 +29,8 @@ vel_scale_trans_sagital: 0.25 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 1.0 -stance_duration: 0.20 +rest_length: 0.87 +stance_duration: 0.30 flight_duration: 0.1 w_swing_toe: 1 @@ -42,12 +42,12 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.13 -footstep_lateral_offset: 0.045 # drake +footstep_sagital_offset: -0.05 +footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.3, 0, 0, - 0, 0.65, 0, + [ 0.25 0, 0, + 0, 0.6, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, @@ -56,22 +56,22 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 30] + 0, 0, 70] PelvisKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 4] + 0, 0, 5] PelvisRotW: - [5, 0, 0, - 0, 1, 0, - 0, 0, 5] + [1, 0, 0, + 0, 10, 0, + 0, 0, 0] PelvisRotKp: - [400., 0, 0, - 0, 200., 0, + [20., 0, 0, + 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [15., 0, 0, - 0, 10., 0, + [10., 0, 0, + 0, 5., 0, 0, 0, 1.] SwingFootW: [10, 0, 0, @@ -79,20 +79,20 @@ SwingFootW: 0, 0, 5] SwingFootKp: [50, 0, 0, - 0, 75, 0, - 0, 0, 45] + 0, 50, 0, + 0, 0, 50] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 2.] + 0, 0, 1.] LiftoffSwingFootW: [1, 0, 0, - 0, 1, 0, + 0, 100, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, - 0, 0, 35] + 0, 0, 50] LiftoffSwingFootKd: [ 5, 0, 0, 0, 5, 0, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 9d8afd4ec4..1bb129ee99 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -818,8 +818,8 @@ VectorXd OperationalSpaceControl::SolveQp( clock_time = clock->get_value()(0); } if (fsm_state == 2) { - double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); - double blend_out = 1 - exp(-((clock_time - 0.2) + window) / tau); + double blend_in = 1 - exp(-((0.4 - clock_time) + window) / tau); + double blend_out = 1 - exp(-((clock_time - 0.3) + window) / tau); u_sol_->row(6) = blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); u_sol_->row(7) = @@ -830,8 +830,8 @@ VectorXd OperationalSpaceControl::SolveQp( blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); } if (fsm_state == 3) { - double blend_in = 1 - exp(-((0.6 - clock_time) + window) / tau); - double blend_out = 1 - exp(-((clock_time - 0.5) + window) / tau); + double blend_in = 1 - exp(-((0.8 - clock_time) + window) / tau); + double blend_out = 1 - exp(-((clock_time - 0.7) + window) / tau); u_sol_->row(6) = blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); u_sol_->row(7) = From 3e2f9830c5c0ffd1bf5e32fab4b383020510e07a Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 14 Jul 2022 11:00:39 -0400 Subject: [PATCH 246/758] adding snopt back --- .bazelrc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.bazelrc b/.bazelrc index bc2090de3d..77f18fabcc 100644 --- a/.bazelrc +++ b/.bazelrc @@ -52,7 +52,7 @@ build --action_env=LD_LIBRARY_PATH= # customizations somehow. # build with snopt -build --define=WITH_SNOPT=OFF +build --define=WITH_SNOPT=ON # use python3 by default build --python_path=python3 From fce7d62cf831da66f2476bf64ea0718784a3ef23 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 14 Jul 2022 11:02:22 -0400 Subject: [PATCH 247/758] updating logging script to include running gains --- examples/Cassie/start_logging.py | 2 ++ 1 file changed, 2 insertions(+) diff --git a/examples/Cassie/start_logging.py b/examples/Cassie/start_logging.py index c4ed5dee2f..f513c95b89 100644 --- a/examples/Cassie/start_logging.py +++ b/examples/Cassie/start_logging.py @@ -18,6 +18,7 @@ def main(): standing_gains = current_dair_dir + "examples/Cassie/osc/osc_standing_gains.yaml" walking_gains = current_dair_dir + "examples/Cassie/osc/osc_walking_gains.yaml" alip_gains = current_dair_dir + "examples/Cassie/osc/osc_walking_gains_alip.yaml" + running_gains = current_dair_dir + "examples/Cassie/osc_run/osc_running_gains.yaml" if not os.path.isdir(logdir): os.mkdir(logdir) @@ -41,6 +42,7 @@ def main(): subprocess.run(['cp', standing_gains, 'standing_gains_%s.yaml' % log_num]) subprocess.run(['cp', walking_gains, 'walking_gains_%s.yaml' % log_num]) subprocess.run(['cp', alip_gains, 'walking_gains_alip%s.yaml' % log_num]) + subprocess.run(['cp', running_gains, 'running_gains_%s.yaml' % log_num]) subprocess.run(['lcm-logger', '-f', 'lcmlog-%s' % log_num]) From 6169276e28ce756b3feab3d6e4e7ac6b026c0320 Mon Sep 17 00:00:00 2001 From: Brian-Acosta Date: Thu, 14 Jul 2022 13:12:00 -0400 Subject: [PATCH 248/758] tuning on hardware --- examples/Cassie/osc_run/osc_running_gains.yaml | 16 ++++++++-------- .../Cassie/osc_run/osc_running_qp_settings.yaml | 2 +- .../controllers/osc/operational_space_control.cc | 2 +- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 126a21a187..fcbc3b2caf 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -42,12 +42,12 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.05 -footstep_lateral_offset: 0.04 # drake +footstep_sagital_offset: -0.1 +footstep_lateral_offset: 0.06 #drake mid_foot_height: 0.05 FootstepKd: - [ 0.25 0, 0, - 0, 0.6, 0, + [ 0.25, 0, 0, + 0, 0.7, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, @@ -58,19 +58,19 @@ PelvisKp: 0, 0, 0, 0, 0, 70] PelvisKd: - [ 0, 0, 0, + [ 0 , 0, 0, 0, 0, 0, 0, 0, 5] PelvisRotW: - [1, 0, 0, + [10, 0, 0, 0, 10, 0, 0, 0, 0] PelvisRotKp: - [20., 0, 0, + [10., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [10., 0, 0, + [2., 0, 0, 0, 5., 0, 0, 0, 1.] SwingFootW: diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 41753bee75..c83a270227 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 75 +max_iter: 100 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 1bb129ee99..a40469ca25 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -810,7 +810,7 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); double window = 0.01; - double tau = 0.01; + double tau = 0.02; if (fsm_state >= 2 && initial_guess_x_.size() == 4) { double clock_time; if (this->get_input_port(clock_port_).HasValue(context)) { From 3d107b9c0bb33fb85ff5c68963dca23a9c1049e4 Mon Sep 17 00:00:00 2001 From: dair Date: Fri, 15 Jul 2022 09:57:47 -0400 Subject: [PATCH 249/758] removing ignoring state in jacobian feature --- examples/Cassie/cassie_utils.cc | 8 +-- .../Cassie/osc/osc_walking_gains_alip.yaml | 6 +- .../solver_settings/osqp_options_walking.yaml | 12 ++-- .../Cassie/osc_run/osc_running_gains.yaml | 46 ++++++------ .../osc_run/osc_running_qp_settings.yaml | 2 +- .../osc_run/pelvis_trans_traj_generator.cc | 14 +++- .../Cassie/run_osc_walking_controller_alip.cc | 8 +-- .../osc/operational_space_control.cc | 70 +++++++++---------- .../controllers/osc/options_tracking_data.cc | 18 ----- .../controllers/osc/options_tracking_data.h | 5 -- 10 files changed, 86 insertions(+), 103 deletions(-) diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index 26e74cca4e..ba5a129df5 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -123,19 +123,19 @@ void AddCassieMultibody(MultibodyPlant* plant, plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("knee_joint_left")), - 0, 1500); + 0, 9000); plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("knee_joint_right")), - 0, 1500); + 0, 9000); plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("ankle_spring_joint_left")), - 0, 1250); + 0, 9000); plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("ankle_spring_joint_right")), - 0, 1250); + 0, 9000); } if (add_loop_closure) { diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index ae5ae78b46..4f085dbef2 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -3,8 +3,8 @@ w_input: 0.0000 w_input_reg: 0.0000 w_accel: 0.0001 w_soft_constraint: 100 -impact_threshold: 0.1 -impact_tau: 0.05 +impact_threshold: 0.05 +impact_tau: 0.025 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_input_reg: [1, 0.9, 0.5, 0.1, 5, @@ -74,7 +74,7 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 2.0 +w_hip_yaw: 0.5 hip_yaw_kp: 40 hip_yaw_kd: 1 diff --git a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml index da90c7883c..41753bee75 100644 --- a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml +++ b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml @@ -1,8 +1,8 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 500 -eps_abs: 1e-7 -eps_rel: 1e-7 +max_iter: 75 +eps_abs: 1e-5 +eps_rel: 1e-5 eps_prim_inf: 1e-5 eps_dual_inf: 1e-5 alpha: 1.6 @@ -12,11 +12,11 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 25 +check_termination: 15 warm_start: 1 -scaling: 10 +scaling: 1 adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 -time_limit: 0.0 \ No newline at end of file +time_limit: 0 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index fcbc3b2caf..83ad26d739 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,4 +1,4 @@ -w_input: 0.0001 +w_input: 0.0000 w_input_reg: 0.1 w_accel: 0.0001 w_soft_constraint: 100 @@ -16,7 +16,7 @@ W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, - 0.01, 0.02, 0.02] + 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 relative_feet: true @@ -29,8 +29,8 @@ vel_scale_trans_sagital: 0.25 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.87 -stance_duration: 0.30 +rest_length: 0.9 +stance_duration: 0.20 flight_duration: 0.1 w_swing_toe: 1 @@ -42,12 +42,12 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.1 -footstep_lateral_offset: 0.06 #drake +footstep_sagital_offset: -0.13 +footstep_lateral_offset: 0.045 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.25, 0, 0, - 0, 0.7, 0, + [ 0.3, 0, 0, + 0, 0.65, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, @@ -56,22 +56,22 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 70] + 0, 0, 40] PelvisKd: - [ 0 , 0, 0, + [ 0, 0, 0, 0, 0, 0, - 0, 0, 5] + 0, 0, 4] PelvisRotW: - [10, 0, 0, - 0, 10, 0, - 0, 0, 0] + [5, 0, 0, + 0, 1, 0, + 0, 0, 5] PelvisRotKp: - [10., 0, 0, - 0, 100., 0, + [100., 0, 0, + 0, 200., 0, 0, 0, 0.] PelvisRotKd: - [2., 0, 0, - 0, 5., 0, + [5., 0, 0, + 0, 10., 0, 0, 0, 1.] SwingFootW: [10, 0, 0, @@ -79,20 +79,20 @@ SwingFootW: 0, 0, 5] SwingFootKp: [50, 0, 0, - 0, 50, 0, - 0, 0, 50] + 0, 75, 0, + 0, 0, 45] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 1.] + 0, 0, 2.] LiftoffSwingFootW: [1, 0, 0, - 0, 100, 0, + 0, 1, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 35] LiftoffSwingFootKd: [ 5, 0, 0, 0, 5, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index c83a270227..41753bee75 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 100 +max_iter: 75 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index a4d6b6c18a..f6b602bcb0 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -107,7 +107,12 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( double dt = 1e-3; Eigen::Vector2d breaks; - breaks << t, t + dt; + if(t < 0.3){ + breaks << 0, 0.2; + } + else{ + breaks << 0.3, 0.5; + } MatrixXd samples(3, 2); MatrixXd samples_dot(3, 2); samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; @@ -127,7 +132,12 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( else if (fsm_state == 1){ y_dist_des = 0.15; } - return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); +// return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); + samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.05; +// samples << 0, y_dist_des, rest_length_, 0, y_dist_des, rest_length_ + 0.1; + return PiecewisePolynomial::FirstOrderHold(breaks, samples); +// return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( +// breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); } void PelvisTransTrajGenerator::CalcTraj( diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index e9fc21d6c3..45ca61d2e8 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -489,17 +489,13 @@ int DoMain(int argc, char* argv[]) { auto vel_map = MakeNameToVelocitiesMap(plant_w_spr); - swing_foot_data->AddJointAndStateToIgnoreInJacobian( - vel_map["hip_yaw_right"], left_stance_state); - swing_foot_data->AddJointAndStateToIgnoreInJacobian( - vel_map["hip_yaw_left"], right_stance_state); auto com_data = std::make_unique ("com_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); -// com_data->SetImpactInvariantProjection(true); + com_data->SetImpactInvariantProjection(true); auto swing_ft_traj_local = std::make_unique ( "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), @@ -543,7 +539,7 @@ int DoMain(int argc, char* argv[]) { "pelvis_heading_traj", osc_walking_gains.K_p_pelvis_heading, osc_walking_gains.K_d_pelvis_heading, osc_walking_gains.W_pelvis_heading, plant_w_spr, plant_w_spr); pelvis_heading_traj->AddFrameToTrack("pelvis"); - pelvis_heading_traj->SetImpactInvariantProjection(true); +// pelvis_heading_traj->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_heading_traj), osc_walking_gains.period_of_no_heading_control); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index a40469ca25..fe59032563 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -817,30 +817,30 @@ VectorXd OperationalSpaceControl::SolveQp( auto clock = this->EvalVectorInput(context, clock_port_); clock_time = clock->get_value()(0); } - if (fsm_state == 2) { - double blend_in = 1 - exp(-((0.4 - clock_time) + window) / tau); - double blend_out = 1 - exp(-((clock_time - 0.3) + window) / tau); - u_sol_->row(6) = - blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); - u_sol_->row(7) = - blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); - u_sol_->row(0) = - blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); - u_sol_->row(1) = - blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); - } - if (fsm_state == 3) { - double blend_in = 1 - exp(-((0.8 - clock_time) + window) / tau); - double blend_out = 1 - exp(-((clock_time - 0.7) + window) / tau); - u_sol_->row(6) = - blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); - u_sol_->row(7) = - blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); - u_sol_->row(0) = - blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); - u_sol_->row(1) = - blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); - } +// if (fsm_state == 2) { +// double blend_in = 1 - exp(-((0.4 - clock_time) + window) / tau); +// double blend_out = 1 - exp(-((clock_time - 0.3) + window) / tau); +// u_sol_->row(6) = +// blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); +// u_sol_->row(7) = +// blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); +// u_sol_->row(0) = +// blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); +// u_sol_->row(1) = +// blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); +// } +// if (fsm_state == 3) { +// double blend_in = 1 - exp(-((0.8 - clock_time) + window) / tau); +// double blend_out = 1 - exp(-((clock_time - 0.7) + window) / tau); +// u_sol_->row(6) = +// blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); +// u_sol_->row(7) = +// blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); +// u_sol_->row(0) = +// blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); +// u_sol_->row(1) = +// blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); +// } } u_prev_[fsm_state] = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); @@ -1137,17 +1137,17 @@ void OperationalSpaceControl::CalcOptimalInput( next_fsm_state = impact_info->GetCurrentContactMode(); } - if (fsm_state(0) == 0) { - x_wo_spr[19] = 0; - x_wo_spr[21] = 0; - x_wo_spr[33] = 0; - x_wo_spr[41] = 0; - } else if (fsm_state(0) == 1) { - x_wo_spr[11] = 0; - x_wo_spr[13] = 0; - x_wo_spr[33] = 0; - x_wo_spr[41] = 0; - } +// if (fsm_state(0) == 0) { +// x_wo_spr[19] = 0; +// x_wo_spr[21] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } else if (fsm_state(0) == 1) { +// x_wo_spr[11] = 0; +// x_wo_spr[13] = 0; +// x_wo_spr[33] = 0; +// x_wo_spr[41] = 0; +// } // else { // x_wo_spr[11] = 0; // x_wo_spr[13] = 0; diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index a82910bb65..f3a0d72bb2 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -37,12 +37,6 @@ void OptionsTrackingData::UpdateActual( JdotV_ = view_frame_rot_T_ * JdotV_; } - if (joint_idx_to_ignore_.count(fsm_state_)) { - for (int idx : joint_idx_to_ignore_[fsm_state_]) { - J_.col(idx) = VectorXd::Zero(J_.rows()); - } - } - UpdateFilters(t); } @@ -119,18 +113,6 @@ void OptionsTrackingData::SetLowPassFilter(double tau, } } -void OptionsTrackingData::AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, - int fsm_state) { - DRAKE_DEMAND(std::find(active_fsm_states_.begin(), - active_fsm_states_.end(), - fsm_state) != active_fsm_states_.end()); - if (joint_idx_to_ignore_.count(fsm_state)) { - joint_idx_to_ignore_[fsm_state].push_back(joint_vel_idx); - } else { - joint_idx_to_ignore_[fsm_state] = {joint_vel_idx}; - } -} - void OptionsTrackingData::SetTimeVaryingGains( const drake::trajectories::Trajectory& gain_multiplier) { DRAKE_DEMAND(gain_multiplier.cols() == n_ydot_); diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index a422b93528..4723bc2a93 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -43,10 +43,6 @@ class OptionsTrackingData : public OscTrackingData { idx_zero_feedforward_accel_ = indices; }; - // Ignore a joint to ignore in jacobian calculation. - // State must be added to the tracking data already - void AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, int fsm_state); - private: void UpdateActual( const Eigen::VectorXd& x_w_spr, @@ -68,7 +64,6 @@ class OptionsTrackingData : public OscTrackingData { Eigen::VectorXd filtered_ydot_; double tau_ = -1; std::set low_pass_filter_element_idx_; - std::unordered_map> joint_idx_to_ignore_; double last_timestamp_ = -1; }; From fd2aabe3b02188b97b37b1b3bdb7d2e0f5e22d5d Mon Sep 17 00:00:00 2001 From: dair Date: Fri, 15 Jul 2022 11:24:25 -0400 Subject: [PATCH 250/758] some more tuning --- .../plot_configs/cassie_running_plot.yaml | 3 +- examples/Cassie/cassie_utils.cc | 8 ++--- .../Cassie/osc_run/foot_traj_generator.cc | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 16 +++++----- .../osc_run/pelvis_trans_traj_generator.cc | 19 +++++------ examples/Cassie/run_osc_running_controller.cc | 4 +-- .../osc/operational_space_control.cc | 32 +++++++++++-------- 7 files changed, 45 insertions(+), 39 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 5a8732d77b..58c5c4d952 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -41,8 +41,7 @@ plot_qp_solve_time: true plot_qp_solutions: true plot_tracking_costs: false tracking_datas_to_plot: -# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel' ] } - # pelvis_trans_traj: {'dims': [0, 1, 2], 'derivs': ['accel']} + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] } # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # left_ft_traj: {'dims': [1], 'derivs': ['pos']} diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index ba5a129df5..26e74cca4e 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -123,19 +123,19 @@ void AddCassieMultibody(MultibodyPlant* plant, plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("knee_joint_left")), - 0, 9000); + 0, 1500); plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("knee_joint_right")), - 0, 9000); + 0, 1500); plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("ankle_spring_joint_left")), - 0, 9000); + 0, 1250); plant->AddForceElement( dynamic_cast&>( plant->GetJointByName("ankle_spring_joint_right")), - 0, 9000); + 0, 1250); } if (add_loop_closure) { diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index f0ac0fa71e..d8bedda5cf 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -252,7 +252,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[1] = start_pos + 0.85 * foot_end_pos_des; Y[1](2) = -rest_length_ + mid_foot_height_; Y[2] = foot_end_pos_des; - Y[2](2) = -rest_length_ + mid_foot_height_ / 2; + Y[2](2) = -rest_length_; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 83ad26d739..d99e6646fe 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -2,8 +2,8 @@ w_input: 0.0000 w_input_reg: 0.1 w_accel: 0.0001 w_soft_constraint: 100 -impact_threshold: 0.1 -impact_tau: 0.05 +impact_threshold: 0.05 +impact_tau: 0.025 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, @@ -47,20 +47,20 @@ footstep_lateral_offset: 0.045 # drake mid_foot_height: 0.05 FootstepKd: [ 0.3, 0, 0, - 0, 0.65, 0, + 0, 0.7, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, 0, 0, 0, - 0, 0, 5 ] + 0, 0, 10 ] PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 40] + 0, 0, 65] PelvisKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 4] + 0, 0, 5] PelvisRotW: [5, 0, 0, 0, 1, 0, @@ -86,8 +86,8 @@ SwingFootKd: 0, 5., 0, 0, 0, 2.] LiftoffSwingFootW: - [1, 0, 0, - 0, 1, 0, + [5, 0, 0, + 0, 5, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index f6b602bcb0..93e53a2476 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -106,17 +106,17 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( VectorXd rddot = f_g + f_leg; double dt = 1e-3; - Eigen::Vector2d breaks; - if(t < 0.3){ - breaks << 0, 0.2; + Eigen::Vector3d breaks; + if(t <= 0.3){ + breaks << 0, 0.2, 0.3; } else{ - breaks << 0.3, 0.5; + breaks << 0.3, 0.5, 0.6; } - MatrixXd samples(3, 2); - MatrixXd samples_dot(3, 2); - samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; - samples_dot << pelvis_vel, pelvis_vel + rddot * dt; + MatrixXd samples(3, 3); +// MatrixXd samples_dot(3, 2); +// samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; +// samples_dot << pelvis_vel, pelvis_vel + rddot * dt; // std::cout << "pelvis_pos: " << pelvis_pos.transpose() << std::endl; // std::cout << (pelvis_pos + 0.5 * rddot * dt * dt).transpose() << @@ -133,7 +133,8 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( y_dist_des = 0.15; } // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); - samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.05; +// samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.05, rest_length_; + samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.1, rest_length_; // samples << 0, y_dist_des, rest_length_, 0, y_dist_des, rest_length_ + 0.1; return PiecewisePolynomial::FirstOrderHold(breaks, samples); // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 5c19de0a2c..54bc8aaa3b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -419,8 +419,8 @@ int DoMain(int argc, char* argv[]) { // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); - left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); - right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); +// left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); +// right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index fe59032563..2e60a5dd57 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -809,17 +809,23 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); - double window = 0.01; - double tau = 0.02; - if (fsm_state >= 2 && initial_guess_x_.size() == 4) { - double clock_time; - if (this->get_input_port(clock_port_).HasValue(context)) { - auto clock = this->EvalVectorInput(context, clock_port_); - clock_time = clock->get_value()(0); - } +// double window = 0.01; +// double tau = 0.005; + double state_2_start = 0.2; + double state_2_end = 0.3; + double state_3_start = 0.5; + double state_3_end = 0.6; +// if (fsm_state >= 2 && initial_guess_x_.size() == 4) { +// double clock_time; +// if (this->get_input_port(clock_port_).HasValue(context)) { +// auto clock = this->EvalVectorInput(context, clock_port_); +// clock_time = clock->get_value()(0); +// } // if (fsm_state == 2) { -// double blend_in = 1 - exp(-((0.4 - clock_time) + window) / tau); -// double blend_out = 1 - exp(-((clock_time - 0.3) + window) / tau); +// double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); +// double blend_out = 1 - exp(-((clock_time - 0.2) + window) / tau); +// double blend_in = (state_2_end - clock_time) / (state_2_end - state_2_start); +// double blend_out = 1 - (state_2_end - clock_time) / (state_2_end - state_2_start); // u_sol_->row(6) = // blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); // u_sol_->row(7) = @@ -830,8 +836,8 @@ VectorXd OperationalSpaceControl::SolveQp( // blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); // } // if (fsm_state == 3) { -// double blend_in = 1 - exp(-((0.8 - clock_time) + window) / tau); -// double blend_out = 1 - exp(-((clock_time - 0.7) + window) / tau); +// double blend_in = (state_3_end - clock_time) / (state_3_end - state_3_start); +// double blend_out = 1 - (state_3_end - clock_time) / (state_3_end - state_3_start); // u_sol_->row(6) = // blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); // u_sol_->row(7) = @@ -841,7 +847,7 @@ VectorXd OperationalSpaceControl::SolveQp( // u_sol_->row(1) = // blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); // } - } +// } u_prev_[fsm_state] = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; From abf1d2c3bacf7d5ac7d3b1284a256efe7e6e77f7 Mon Sep 17 00:00:00 2001 From: dair Date: Fri, 15 Jul 2022 14:42:25 -0400 Subject: [PATCH 251/758] updating pelvis traj --- examples/Cassie/director_scripts/controller_status.py | 2 +- examples/Cassie/osc_run/pelvis_trans_traj_generator.cc | 5 +++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py index adc41dddfd..e27603ee0f 100644 --- a/examples/Cassie/director_scripts/controller_status.py +++ b/examples/Cassie/director_scripts/controller_status.py @@ -16,7 +16,7 @@ def __init__(self): self._current_channel_ = "" self.text_box = vis.TextItem('safety_info', 'safety_info', view) - self.text_box.setProperty('Position', [1200, 10]) + self.text_box.setProperty('Position', [10, 600]) self.text_box.setProperty('Font Size', 24) self.text_box.setProperty('Bold', True) diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 93e53a2476..b29b597b90 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -108,10 +108,10 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( double dt = 1e-3; Eigen::Vector3d breaks; if(t <= 0.3){ - breaks << 0, 0.2, 0.3; + breaks << 0, 0.15, 0.3; } else{ - breaks << 0.3, 0.5, 0.6; + breaks << 0.3, 0.45, 0.6; } MatrixXd samples(3, 3); // MatrixXd samples_dot(3, 2); @@ -137,6 +137,7 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.1, rest_length_; // samples << 0, y_dist_des, rest_length_, 0, y_dist_des, rest_length_ + 0.1; return PiecewisePolynomial::FirstOrderHold(breaks, samples); +// return PiecewisePolynomial::Cu(breaks, samples); // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( // breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); } From df8c613bdf5dccb861daa676a57a82d697ec489c Mon Sep 17 00:00:00 2001 From: dair Date: Fri, 15 Jul 2022 15:02:29 -0400 Subject: [PATCH 252/758] updating gains, mostly period --- examples/Cassie/osc_run/osc_running_gains.yaml | 14 +++++++------- .../Cassie/osc_run/pelvis_trans_traj_generator.cc | 4 ++-- examples/Cassie/urdf/cassie_v2.urdf | 4 ++-- 3 files changed, 11 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d99e6646fe..d7e7b4c9b5 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -29,8 +29,8 @@ vel_scale_trans_sagital: 0.25 vel_scale_trans_lateral: -0.15 # SLIP parameters -rest_length: 0.9 -stance_duration: 0.20 +rest_length: 0.85 +stance_duration: 0.3 flight_duration: 0.1 w_swing_toe: 1 @@ -43,7 +43,7 @@ hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.13 -footstep_lateral_offset: 0.045 # drake +footstep_lateral_offset: 0.06 # drake mid_foot_height: 0.05 FootstepKd: [ 0.3, 0, 0, @@ -56,7 +56,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 65] + 0, 0, 50] PelvisKd: [ 0, 0, 0, 0, 0, 0, @@ -66,7 +66,7 @@ PelvisRotW: 0, 1, 0, 0, 0, 5] PelvisRotKp: - [100., 0, 0, + [60., 0, 0, 0, 200., 0, 0, 0, 0.] PelvisRotKd: @@ -86,8 +86,8 @@ SwingFootKd: 0, 5., 0, 0, 0, 2.] LiftoffSwingFootW: - [5, 0, 0, - 0, 5, 0, + [3, 0, 0, + 0, 3, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index b29b597b90..5b733e1ccd 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -108,10 +108,10 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( double dt = 1e-3; Eigen::Vector3d breaks; if(t <= 0.3){ - breaks << 0, 0.15, 0.3; + breaks << 0, 0.3, 0.4; } else{ - breaks << 0.3, 0.45, 0.6; + breaks << 0.4, 0.7, 0.8; } MatrixXd samples(3, 3); // MatrixXd samples_dot(3, 2); diff --git a/examples/Cassie/urdf/cassie_v2.urdf b/examples/Cassie/urdf/cassie_v2.urdf index d7110db6ee..6597f1931b 100644 --- a/examples/Cassie/urdf/cassie_v2.urdf +++ b/examples/Cassie/urdf/cassie_v2.urdf @@ -615,7 +615,7 @@ - + @@ -624,7 +624,7 @@ - + From ca803e56ca1efa3f203cc56fa43f05f6941d127c Mon Sep 17 00:00:00 2001 From: dair Date: Fri, 15 Jul 2022 15:25:53 -0400 Subject: [PATCH 253/758] adding decelleration --- examples/Cassie/osc_run/pelvis_trans_traj_generator.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 5b733e1ccd..c80924b545 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -108,10 +108,10 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( double dt = 1e-3; Eigen::Vector3d breaks; if(t <= 0.3){ - breaks << 0, 0.3, 0.4; + breaks << 0, 0.25, 0.4; } else{ - breaks << 0.4, 0.7, 0.8; + breaks << 0.4, 0.65, 0.8; } MatrixXd samples(3, 3); // MatrixXd samples_dot(3, 2); From 3c77f53b39190aa7434542494adf15dde7ea252a Mon Sep 17 00:00:00 2001 From: dair Date: Mon, 18 Jul 2022 10:24:46 -0400 Subject: [PATCH 254/758] constraining maximum input acceleration --- WORKSPACE | 6 +- .../osc/operational_space_control.cc | 242 +++++++++--------- .../osc/operational_space_control.h | 5 +- 3 files changed, 131 insertions(+), 122 deletions(-) diff --git a/WORKSPACE b/WORKSPACE index 653b25359b..548396ba64 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,12 +11,12 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "ade445d67e232077aa2d2c805022238f5682dbc6" +DRAKE_COMMIT = "e80d001876a8c14dbd46e8a5f8c0d1eaf0e7de1a" -DRAKE_CHECKSUM = "708cc2f868be1b07c87c730ffb423b87b0cd6120f7e9e7fe65b56139c832704a" +DRAKE_CHECKSUM = "b277f8cd93ca219bb33d93a3bf7c111e3353df49aa48da19fcfbdb36addd3727" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. -# DRAKE_CHECKSUM = "0" * 64 +#DRAKE_CHECKSUM = "0" * 64 # Load an environment variable. load("//:environ.bzl", "environ_repository") diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index ea810fcd1f..3be54cf818 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -48,10 +48,10 @@ using multibody::SetVelocitiesIfNew; using multibody::WorldPointEvaluator; OperationalSpaceControl::OperationalSpaceControl( - const MultibodyPlant& plant_w_spr, - const MultibodyPlant& plant_wo_spr, - drake::systems::Context* context_w_spr, - drake::systems::Context* context_wo_spr, + const MultibodyPlant &plant_w_spr, + const MultibodyPlant &plant_wo_spr, + drake::systems::Context *context_w_spr, + drake::systems::Context *context_wo_spr, bool used_with_finite_state_machine, double qp_time_limit) : plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), @@ -80,7 +80,7 @@ OperationalSpaceControl::OperationalSpaceControl( fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); clock_port_ = this->DeclareVectorInputPort("clock", BasicVector(1)) - .get_index(); + .get_index(); impact_info_port_ = this->DeclareVectorInputPort("next_fsm, t_to_impact", ImpactInfoVector(0, 0, kSpaceDim)) @@ -94,20 +94,20 @@ OperationalSpaceControl::OperationalSpaceControl( } osc_output_port_ = this->DeclareVectorOutputPort( - "u, t", TimestampedVector(n_u_w_spr), - &OperationalSpaceControl::CalcOptimalInput) - .get_index(); + "u, t", TimestampedVector(n_u_w_spr), + &OperationalSpaceControl::CalcOptimalInput) + .get_index(); osc_debug_port_ = this->DeclareAbstractOutputPort( "lcmt_osc_debug", &OperationalSpaceControl::AssignOscLcmOutput) .get_index(); failure_port_ = this->DeclareVectorOutputPort( - "failure_signal", TimestampedVector(1), - &OperationalSpaceControl::CheckTracking) - .get_index(); + "failure_signal", TimestampedVector(1), + &OperationalSpaceControl::CheckTracking) + .get_index(); - const std::map& vel_map_wo_spr = + const std::map &vel_map_wo_spr = multibody::MakeNameToVelocitiesMap(plant_wo_spr); // Initialize the mapping from spring to no spring @@ -128,7 +128,7 @@ OperationalSpaceControl::OperationalSpaceControl( n_revolute_joints_ = 0; for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { - const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); + const drake::multibody::Joint &joint = plant_wo_spr_.get_joint(i); if (joint.type_name() == "revolute") { n_revolute_joints_ += 1; } @@ -137,7 +137,7 @@ OperationalSpaceControl::OperationalSpaceControl( VectorXd q_max(n_revolute_joints_); int floating_base_offset = n_v_ - n_revolute_joints_; for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { - const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); + const drake::multibody::Joint &joint = plant_wo_spr_.get_joint(i); if (joint.type_name() == "revolute") { q_min(vel_map_wo_spr.at(joint.name() + "dot") - floating_base_offset) = plant_wo_spr.get_joint(i).position_lower_limits()[0]; @@ -146,9 +146,9 @@ OperationalSpaceControl::OperationalSpaceControl( } if (joint.type_name() == "prismatic" && (joint.position_lower_limits()[0] != - -std::numeric_limits::infinity() || - (joint.position_upper_limits()[0] != - std::numeric_limits::infinity()))) { + -std::numeric_limits::infinity() || + (joint.position_upper_limits()[0] != + std::numeric_limits::infinity()))) { std::cerr << "Warning: joint limits have not been implemented for " "prismatic joints: " << std::endl; @@ -174,7 +174,7 @@ void OperationalSpaceControl::SetUpDoubleSupportPhaseBlending( } void OperationalSpaceControl::AddInputCostByJointAndFsmState( - const std::string& joint_u_name, int fsm, double w) { + const std::string &joint_u_name, int fsm, double w) { if (W_input_.size() == 0) { W_input_ = Eigen::MatrixXd::Zero(n_u_, n_u_); } @@ -184,13 +184,13 @@ void OperationalSpaceControl::AddInputCostByJointAndFsmState( // Constraint methods void OperationalSpaceControl::AddContactPoint( - const WorldPointEvaluator* evaluator) { + const WorldPointEvaluator *evaluator) { single_contact_mode_ = true; AddStateAndContactPoint(-1, evaluator); } void OperationalSpaceControl::AddStateAndContactPoint( - int state, const WorldPointEvaluator* evaluator) { + int state, const WorldPointEvaluator *evaluator) { DRAKE_DEMAND(&evaluator->plant() == &plant_wo_spr_); // Find the new contact in all_contacts_ @@ -214,7 +214,7 @@ void OperationalSpaceControl::AddStateAndContactPoint( } void OperationalSpaceControl::AddKinematicConstraint( - const multibody::KinematicEvaluatorSet* evaluators) { + const multibody::KinematicEvaluatorSet *evaluators) { DRAKE_DEMAND(&evaluators->plant() == &plant_wo_spr_); kinematic_evaluators_ = evaluators; } @@ -242,7 +242,7 @@ void OperationalSpaceControl::AddTrackingData( } } void OperationalSpaceControl::AddConstTrackingData( - std::unique_ptr tracking_data, const VectorXd& v, + std::unique_ptr tracking_data, const VectorXd &v, double t_lb, double t_ub) { tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(v); @@ -257,11 +257,11 @@ void OperationalSpaceControl::CheckCostSettings() { } if (W_input_smoothing_.size() != 0) { DRAKE_DEMAND((W_input_smoothing_.rows() == n_u_) && - (W_input_smoothing_.cols() == n_u_)); + (W_input_smoothing_.cols() == n_u_)); } if (W_joint_accel_.size() != 0) { DRAKE_DEMAND((W_joint_accel_.rows() == n_v_) && - (W_joint_accel_.cols() == n_v_)); + (W_joint_accel_.cols() == n_v_)); } } void OperationalSpaceControl::CheckConstraintSettings() { @@ -277,7 +277,7 @@ void OperationalSpaceControl::Build() { // Checker CheckCostSettings(); CheckConstraintSettings(); - for (auto& tracking_data : *tracking_data_vec_) { + for (auto &tracking_data : *tracking_data_vec_) { tracking_data->CheckOscTrackingData(); DRAKE_DEMAND(&tracking_data->plant_w_spr() == &plant_w_spr_); DRAKE_DEMAND(&tracking_data->plant_wo_spr() == &plant_wo_spr_); @@ -288,8 +288,8 @@ void OperationalSpaceControl::Build() { // Size of decision variable n_h_ = (kinematic_evaluators_ == nullptr) - ? 0 - : kinematic_evaluators_->count_full(); + ? 0 + : kinematic_evaluators_->count_full(); n_c_ = kSpaceDim * all_contacts_.size(); n_c_active_ = 0; for (auto evaluator : all_contacts_) { @@ -314,11 +314,13 @@ void OperationalSpaceControl::Build() { lambda_c_sol_ = std::make_unique(n_c_); lambda_h_sol_ = std::make_unique(n_h_); epsilon_sol_ = std::make_unique(n_c_active_); + u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); - epsilon_sol_->setZero(); + u_prev_->setZero(); + // Add decision variables dv_ = prog_->NewContinuousVariables(n_v_, "dv"); @@ -391,8 +393,8 @@ void OperationalSpaceControl::Build() { // 1. input cost if (W_input_.size() > 0) { input_cost_ = prog_->AddQuadraticCost(W_input_, VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); + .evaluator() + .get(); } // 2. acceleration cost if (W_joint_accel_.size() > 0) { @@ -426,6 +428,10 @@ void OperationalSpaceControl::Build() { .evaluator() .get(); } + input_smoothing_constraint_ = + prog_->AddBoundingBoxConstraint(VectorXd::Zero(n_u_), VectorXd::Zero(n_u_), u_) + .evaluator() + .get(); // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { tracking_cost_.push_back(prog_ @@ -473,17 +479,17 @@ void OperationalSpaceControl::Build() { } drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const { - const BasicVector* fsm_output = - (BasicVector*)this->EvalVectorInput(context, fsm_port_); + const drake::systems::Context &context, + drake::systems::DiscreteValues *discrete_state) const { + const BasicVector *fsm_output = + (BasicVector *) this->EvalVectorInput(context, fsm_port_); VectorXd fsm_state = fsm_output->get_value(); - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); double timestamp = robot_output->get_timestamp(); auto prev_fsm_state = discrete_state->get_mutable_vector(prev_fsm_state_idx_) - .get_mutable_value(); + .get_mutable_value(); if (fsm_state(0) != prev_fsm_state(0)) { prev_distinct_fsm_state_ = prev_fsm_state(0); prev_fsm_state(0) = fsm_state(0); @@ -495,8 +501,8 @@ drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( } VectorXd OperationalSpaceControl::SolveQp( - const VectorXd& x_w_spr, const VectorXd& x_wo_spr, - const drake::systems::Context& context, double t, int fsm_state, + const VectorXd &x_w_spr, const VectorXd &x_wo_spr, + const drake::systems::Context &context, double t, int fsm_state, double time_since_last_state_switch, double alpha, int next_fsm_state) const { // Get active contact indices @@ -508,10 +514,10 @@ VectorXd OperationalSpaceControl::SolveQp( if (map_iterator != contact_indices_map_.end()) { active_contact_set = map_iterator->second; } else { - static const drake::logging::Warn log_once(const_cast( - (std::to_string(fsm_state) + - " is not a valid finite state machine state in OSC.") - .c_str())); + static const drake::logging::Warn log_once(const_cast( + (std::to_string(fsm_state) + + " is not a valid finite state machine state in OSC.") + .c_str())); } } @@ -547,13 +553,13 @@ VectorXd OperationalSpaceControl::SolveQp( bool near_impact = alpha != 0; VectorXd v_proj = VectorXd::Zero(n_v_); if (near_impact) { - auto start = std::chrono::high_resolution_clock::now(); +// auto start = std::chrono::high_resolution_clock::now(); UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, time_since_last_state_switch, fsm_state, next_fsm_state, M); - auto finish = std::chrono::high_resolution_clock::now(); - std::chrono::duration elapsed = finish - start; - cout << "Solve time:" << elapsed.count() << std::endl; +// auto finish = std::chrono::high_resolution_clock::now(); +// std::chrono::duration elapsed = finish - start; +// cout << "Solve time:" << elapsed.count() << std::endl; // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; } @@ -681,12 +687,12 @@ VectorXd OperationalSpaceControl::SolveQp( time_since_last_state_switch, fsm_state, v_proj); } else { // Read in traj from input port - const string& traj_name = tracking_data->GetName(); + const string &traj_name = tracking_data->GetName(); int port_index = traj_name_to_port_index_map_.at(traj_name); - const drake::AbstractValue* input_traj = + const drake::AbstractValue *input_traj = this->EvalAbstractInput(context, port_index); DRAKE_DEMAND(input_traj != nullptr); - const auto& traj = + const auto &traj = input_traj->get_value>(); // Update tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, @@ -694,10 +700,10 @@ VectorXd OperationalSpaceControl::SolveQp( time_since_last_state_switch, fsm_state, v_proj); } - const VectorXd& ddy_t = tracking_data->GetYddotCommand(); - const MatrixXd& W = tracking_data->GetWeight(); - const MatrixXd& J_t = tracking_data->GetJ(); - const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); + const VectorXd &ddy_t = tracking_data->GetYddotCommand(); + const MatrixXd &W = tracking_data->GetWeight(); + const MatrixXd &J_t = tracking_data->GetJ(); + const VectorXd &JdotV_t = tracking_data->GetJdotTimesV(); const VectorXd constant_term = (JdotV_t - ddy_t); // tracking_cost_.at(i)->UpdateCoefficients( // J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - @@ -727,13 +733,13 @@ VectorXd OperationalSpaceControl::SolveQp( // Add joint limit constraints VectorXd w_joint_limit = K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_max_) - .cwiseMax(0) + - K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_min_) - .cwiseMin(0); + .tail(n_revolute_joints_) - + q_max_) + .cwiseMax(0) + + K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) + .tail(n_revolute_joints_) - + q_min_) + .cwiseMin(0); joint_limit_cost_.at(0)->UpdateCoefficients(w_joint_limit, 0); // (Testing) 6. blend contact forces during double support phase @@ -747,11 +753,11 @@ VectorXd OperationalSpaceControl::SolveQp( // We want left foot force to gradually increase alpha_left = -1; alpha_right = time_since_last_state_switch / - (ds_duration_ - time_since_last_state_switch); + (ds_duration_ - time_since_last_state_switch); } else if (prev_distinct_fsm_state_ == left_support_state_) { alpha_left = time_since_last_state_switch / - (ds_duration_ - time_since_last_state_switch); + (ds_duration_ - time_since_last_state_switch); alpha_right = -1; } A(0, 0) = alpha_left / 2; @@ -780,8 +786,10 @@ VectorXd OperationalSpaceControl::SolveQp( // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0 && initial_guess_x_.count(fsm_state) > 0) { input_smoothing_cost_->UpdateCoefficients( - W_input_smoothing_, -W_input_smoothing_ * u_prev_[fsm_state]); + W_input_smoothing_, -W_input_smoothing_ * *u_prev_); } + input_smoothing_constraint_->UpdateCoefficients( + MatrixXd::Identity(n_u_, n_u_), *u_prev_ - 1 * u_max_, *u_prev_ + 1 * u_max_); if (W_lambda_c_reg_.size() > 0) { lambda_c_smoothing_cost_->UpdateCoefficients(1000 * alpha * W_lambda_c_reg_, VectorXd::Zero(n_c_)); @@ -815,10 +823,10 @@ VectorXd OperationalSpaceControl::SolveQp( *epsilon_sol_ = result.GetSolution(epsilon_); // double window = 0.01; // double tau = 0.005; - double state_2_start = 0.2; - double state_2_end = 0.3; - double state_3_start = 0.5; - double state_3_end = 0.6; +// double state_2_start = 0.2; +// double state_2_end = 0.3; +// double state_3_start = 0.5; +// double state_3_end = 0.6; // if (fsm_state >= 2 && initial_guess_x_.size() == 4) { // double clock_time; // if (this->get_input_port(clock_port_).HasValue(context)) { @@ -852,15 +860,15 @@ VectorXd OperationalSpaceControl::SolveQp( // blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); // } // } - u_prev_[fsm_state] = *u_sol_; + *u_prev_ = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { // *u_prev_ = VectorXd::Zero(n_u_); - u_prev_[fsm_state] = 0.9 * *u_sol_ + VectorXd::Random(n_u_); + *u_prev_ = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } - for (auto& tracking_data : *tracking_data_vec_) { + for (auto &tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state)) { tracking_data->StoreYddotCommandSol(*dv_sol_); } @@ -869,9 +877,9 @@ VectorXd OperationalSpaceControl::SolveQp( return *u_sol_; } // namespace dairlib::systems::controllers void OperationalSpaceControl::UpdateImpactInvariantProjection( - const VectorXd& x_w_spr, const VectorXd& x_wo_spr, - const Context& context, double t, double t_since_last_state_switch, - int fsm_state, int next_fsm_state, const MatrixXd& M) const { + const VectorXd &x_w_spr, const VectorXd &x_wo_spr, + const Context &context, double t, double t_since_last_state_switch, + int fsm_state, int next_fsm_state, const MatrixXd &M) const { auto map_iterator = contact_indices_map_.find(next_fsm_state); if (map_iterator == contact_indices_map_.end()) { ii_lambda_sol_ = VectorXd::Zero(n_c_ + n_h_); @@ -913,11 +921,11 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( t_since_last_state_switch, fsm_state, v_proj); } else { // Read in traj from input port - const string& traj_name = tracking_data->GetName(); + const string &traj_name = tracking_data->GetName(); int port_index = traj_name_to_port_index_map_.at(traj_name); - const drake::AbstractValue* input_traj = + const drake::AbstractValue *input_traj = EvalAbstractInput(context, port_index); - const auto& traj = + const auto &traj = input_traj->get_value>(); tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, *context_wo_spr_, traj, t, @@ -929,7 +937,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( MatrixXd A = MatrixXd::Zero(active_tracking_data_dim, active_constraint_dim); VectorXd ydot_err_vec = VectorXd::Zero(active_tracking_data_dim); int start_row = 0; - for (auto& tracking_data : *tracking_data_vec_) { + for (auto &tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { A.block(start_row, 0, tracking_data->GetYdotDim(), @@ -957,58 +965,58 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( b_constrained << Ab, d; ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition() - .solve(b_constrained) - .head(active_constraint_dim); + .solve(b_constrained) + .head(active_constraint_dim); } void OperationalSpaceControl::AssignOscLcmOutput( - const Context& context, dairlib::lcmt_osc_output* output) const { + const Context &context, dairlib::lcmt_osc_output *output) const { auto state = - (OutputVector*)this->EvalVectorInput(context, state_port_); + (OutputVector *) this->EvalVectorInput(context, state_port_); total_cost_ = 0; int fsm_state = -1; if (used_with_finite_state_machine_) { auto fsm_output = - (BasicVector*)this->EvalVectorInput(context, fsm_port_); + (BasicVector *) this->EvalVectorInput(context, fsm_port_); fsm_state = fsm_output->get_value()(0); } double time_since_last_state_switch = used_with_finite_state_machine_ - ? state->get_timestamp() - - context.get_discrete_state(prev_event_time_idx_).get_value()(0) - : state->get_timestamp(); + ? state->get_timestamp() - + context.get_discrete_state(prev_event_time_idx_).get_value()(0) + : state->get_timestamp(); output->utime = state->get_timestamp() * 1e6; output->fsm_state = fsm_state; double input_cost = (W_input_.size() > 0) - ? (0.5 * (*u_sol_).transpose() * W_input_ * (*u_sol_))(0) - : 0; + ? (0.5 * (*u_sol_).transpose() * W_input_ * (*u_sol_))(0) + : 0; double acceleration_cost = (W_joint_accel_.size() > 0) - ? (0.5 * (*dv_sol_).transpose() * W_joint_accel_ * (*dv_sol_))(0) - : 0; + ? (0.5 * (*dv_sol_).transpose() * W_joint_accel_ * (*dv_sol_))(0) + : 0; double soft_constraint_cost = (w_soft_constraint_ > 0) - ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * - (*epsilon_sol_))(0) - : 0; + ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * + (*epsilon_sol_))(0) + : 0; double input_smoothing_cost = (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_ - u_prev_[fsm_state]).transpose() * - W_input_smoothing_ * (*u_sol_ - u_prev_[fsm_state]))(0) - : 0; + ? (0.5 * (*u_sol_ - *u_prev_).transpose() * + W_input_smoothing_ * (*u_sol_ - *u_prev_))(0) + : 0; double lambda_h_cost = (W_lambda_h_reg_.size() > 0) - ? (0.5 * (*lambda_h_sol_).transpose() * - W_lambda_h_reg_ * (*lambda_h_sol_))(0) - : 0; + ? (0.5 * (*lambda_h_sol_).transpose() * + W_lambda_h_reg_ * (*lambda_h_sol_))(0) + : 0; double lambda_c_cost = (W_lambda_c_reg_.size() > 0) - ? (0.5 * (*lambda_c_sol_).transpose() * - W_lambda_c_reg_ * (*lambda_c_sol_))(0) - : 0; + ? (0.5 * (*lambda_c_sol_).transpose() * + W_lambda_c_reg_ * (*lambda_c_sol_))(0) + : 0; total_cost_ += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost; + input_smoothing_cost + lambda_h_cost + lambda_c_cost; soft_constraint_cost_ = soft_constraint_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); @@ -1089,34 +1097,34 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command_sol = CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); - const VectorXd& ddy_t = tracking_data->GetYddotCommand(); - const MatrixXd& W = tracking_data->GetWeight(); - const MatrixXd& J_t = tracking_data->GetJ(); - const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); + const VectorXd &ddy_t = tracking_data->GetYddotCommand(); + const MatrixXd &W = tracking_data->GetWeight(); + const MatrixXd &J_t = tracking_data->GetJ(); + const VectorXd &JdotV_t = tracking_data->GetJdotTimesV(); output->tracking_costs[i] = (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * - (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); + (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); total_cost_ += output->tracking_costs[i]; } output->tracking_data[i] = osc_output; } // std::cout << total_cost_ << std::endl; - // *u_prev_ = *u_sol_; +// *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); } void OperationalSpaceControl::CalcOptimalInput( - const drake::systems::Context& context, - systems::TimestampedVector* control) const { + const drake::systems::Context &context, + systems::TimestampedVector *control) const { // Read in current state and time auto robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + (OutputVector *) this->EvalVectorInput(context, state_port_); VectorXd q_w_spr = robot_output->GetPositions(); VectorXd v_w_spr = robot_output->GetVelocities(); VectorXd x_w_spr(plant_w_spr_.num_positions() + - plant_w_spr_.num_velocities()); + plant_w_spr_.num_velocities()); x_w_spr << q_w_spr, v_w_spr; double timestamp = robot_output->get_timestamp(); @@ -1141,7 +1149,7 @@ void OperationalSpaceControl::CalcOptimalInput( double alpha = 0; int next_fsm_state = -1; if (this->get_near_impact_input_port().HasValue(context)) { - auto impact_info = (ImpactInfoVector*)this->EvalVectorInput( + auto impact_info = (ImpactInfoVector *) this->EvalVectorInput( context, impact_info_port_); alpha = impact_info->GetAlpha(); next_fsm_state = impact_info->GetCurrentContactMode(); @@ -1183,10 +1191,10 @@ void OperationalSpaceControl::CalcOptimalInput( } void OperationalSpaceControl::CheckTracking( - const drake::systems::Context& context, - TimestampedVector* output) const { + const drake::systems::Context &context, + TimestampedVector *output) const { auto robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + (OutputVector *) this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; if (soft_constraint_cost_ > 5e2 || isnan(soft_constraint_cost_)) { diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 79b72892a7..f8433d6ef8 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -334,6 +334,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::LinearEqualityConstraint* dynamics_constraint_; drake::solvers::LinearEqualityConstraint* holonomic_constraint_; drake::solvers::LinearEqualityConstraint* contact_constraints_; + drake::solvers::BoundingBoxConstraint* input_smoothing_constraint_; std::vector friction_constraints_; std::vector tracking_cost_; drake::solvers::QuadraticCost* input_cost_; @@ -347,7 +348,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::unique_ptr lambda_c_sol_; std::unique_ptr lambda_h_sol_; std::unique_ptr epsilon_sol_; -// std::unique_ptr u_prev_; + std::unique_ptr u_prev_; mutable double solve_time_; mutable Eigen::VectorXd ii_lambda_sol_; @@ -383,7 +384,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { mutable std::unordered_map initial_guess_x_ = {}; mutable std::unordered_map initial_guess_y_ = {}; - mutable std::unordered_map u_prev_ = {}; +// mutable std::unordered_map u_prev_ = {}; // OSC tracking data (stored as a pointer because of caching) std::unique_ptr>> From e907ae02ba0461f925c3d7c9ffb4045a94c803c2 Mon Sep 17 00:00:00 2001 From: dair Date: Tue, 19 Jul 2022 11:04:01 -0400 Subject: [PATCH 255/758] working on smoothing torques --- .../pydairlib/analysis/log_plotter_cassie.py | 11 +- .../plot_configs/cassie_default_plot.yaml | 9 +- .../plot_configs/cassie_running_plot.yaml | 19 +- .../Cassie/osc_run/osc_running_gains.yaml | 12 +- .../osc_run/pelvis_trans_traj_generator.cc | 86 +++++---- .../osc_run/pelvis_trans_traj_generator.h | 18 +- examples/Cassie/run_osc_running_controller.cc | 25 +-- .../impact_aware_time_based_fsm.cc | 37 ++++ .../impact_aware_time_based_fsm.h | 11 +- .../osc/operational_space_control.cc | 177 ++++++++++-------- .../osc/operational_space_control.h | 3 +- 11 files changed, 239 insertions(+), 169 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index ed963da8c3..242515dab6 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -122,14 +122,19 @@ def main(): mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, t_x_slice, act_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + ''' Plot OSC ''' if plot_config.plot_qp_costs: - mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) + plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_qp_solutions: - mbp_plots.plot_qp_solutions(osc_debug, t_osc_slice) + plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 6)) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_tracking_costs: - mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index 13bd2d6063..7b96b46d1f 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -1,13 +1,13 @@ # LCM channels to read data from channel_x: "CASSIE_STATE_DISPATCHER" -channel_u: "CASSIE_INPUT" +channel_u: "OSC_WALKING" channel_osc: "OSC_DEBUG_WALKING" -use_archived_lcmtypes: true +use_archived_lcmtypes: false # Approximate log time to start at relative to the first timestamp in the log -start_time: 0 +start_time: 5 # Duration of time to plot (seconds, -1 for whole log) -duration: 2 +duration: 10 # Plant properties use_springs: true @@ -37,6 +37,7 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_tracking_costs: true +plot_qp_solutions: true plot_qp_solve_time: true tracking_datas_to_plot: alip_com_traj: { 'dims': [ 0, 1 ], 'derivs': [ 'vel' ] } diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 8b9448cbda..f203de3feb 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,7 +6,7 @@ use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) start_time: 0 -duration: 5 +duration: -1 # Plant properties use_springs: true @@ -26,27 +26,28 @@ special_velocities_to_plot: ['hip_pitch_leftdot'] special_efforts_to_plot: [ ] # Finite State Machine Names -fsm_state_names: ['Left Stance (LS)', 'Left Flight (LF)', 'Right Stance (RS)', 'Right Flight (RF)'] +fsm_state_names: ['Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)'] # Foot position plots foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] -foot_xyz_to_plot: { 'right': [0], 'left': [0 ] } +foot_xyz_to_plot: { 'right': [0], 'left': [0] } #foot_xyz_to_plot: { } pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: false +plot_qp_costs: true plot_qp_solve_time: true -plot_qp_solutions: false -plot_tracking_costs: false -tracking_datas_to_plot: - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] } +plot_qp_solutions: true +plot_tracking_costs: true +tracking_datas_to_plot: { + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel', 'accel' ] }, + right_ft_traj: {'dims': [2], 'derivs': ['pos', 'vel', 'accel' ] } # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # left_ft_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_traj: {'dims': [2], 'derivs': ['vel']} # left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} # right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} +} \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d7e7b4c9b5..1d9c1571aa 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -30,7 +30,7 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.85 -stance_duration: 0.3 +stance_duration: 0.27 flight_duration: 0.1 w_swing_toe: 1 @@ -42,7 +42,7 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.13 +footstep_sagital_offset: -0.05 footstep_lateral_offset: 0.06 # drake mid_foot_height: 0.05 FootstepKd: @@ -56,7 +56,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 50] + 0, 0, 30] PelvisKd: [ 0, 0, 0, 0, 0, 0, @@ -66,7 +66,7 @@ PelvisRotW: 0, 1, 0, 0, 0, 5] PelvisRotKp: - [60., 0, 0, + [50., 0, 0, 0, 200., 0, 0, 0, 0.] PelvisRotKd: @@ -86,8 +86,8 @@ SwingFootKd: 0, 5., 0, 0, 0, 2.] LiftoffSwingFootW: - [3, 0, 0, - 0, 3, 0, + [5, 0, 0, + 0, 5, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index c80924b545..bd19380e0c 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -57,6 +57,9 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) .get_index(); + contact_scheduler_port_ = + this->DeclareVectorInputPort("t_mode", BasicVector(2)) + .get_index(); PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -79,9 +82,9 @@ PiecewisePolynomial PelvisTransTrajGenerator::GeneratePelvisTraj( } PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( - const VectorXd& x, double t, int fsm_state) const { + const VectorXd& x, double t_0, double t_f, int fsm_state) const { // fsm_state should be unused - if (fsm_state == 2) { + if (fsm_state >= 2) { // flight phase trajectory should be unused return PiecewisePolynomial(); } @@ -93,8 +96,9 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( plant_.CalcPointsPositions(*context_, feet_contact_points_.at(fsm_state)[0].second, Vector3d::Zero(), world_, &foot_pos); -// plant_.CalcPointsPositions(*context_, pelvis_frame_, Vector3d::Zero(), world_, -// &pelvis_pos); + // plant_.CalcPointsPositions(*context_, pelvis_frame_, Vector3d::Zero(), + // world_, + // &pelvis_pos); pelvis_pos = plant_.CalcCenterOfMassPositionInWorld(*context_); pelvis_vel = plant_.EvalBodySpatialVelocityInWorld(*context_, pelvis_).translational(); @@ -105,41 +109,42 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( k_leg_ * compression * leg_length.normalized() + b_leg_ * pelvis_vel; VectorXd rddot = f_g + f_leg; - double dt = 1e-3; - Eigen::Vector3d breaks; - if(t <= 0.3){ - breaks << 0, 0.25, 0.4; - } - else{ - breaks << 0.4, 0.65, 0.8; - } - MatrixXd samples(3, 3); -// MatrixXd samples_dot(3, 2); -// samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; -// samples_dot << pelvis_vel, pelvis_vel + rddot * dt; - - // std::cout << "pelvis_pos: " << pelvis_pos.transpose() << std::endl; - // std::cout << (pelvis_pos + 0.5 * rddot * dt * dt).transpose() << - // std::endl; std::cout << "pelvis_vel: " << pelvis_vel + rddot * dt << - // std::endl; std::cout << "pelvis_acc: " << rddot.transpose() << std::endl; - -// return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( -// breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); + // double dt = 1e-3; + Eigen::Vector2d breaks; + // if (t <= 0.3) { + // breaks << 0, 0.25, 0.4; + // } else { + // breaks << 0.4, 0.65, 0.8; + // } + breaks << t_0, t_f; + MatrixXd samples(3, 2); + MatrixXd samples_dot(3, 2); + // samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; + // samples_dot << pelvis_vel, pelvis_vel + rddot * dt; + + // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + // breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); double y_dist_des = 0; - if(fsm_state == 0){ + if (fsm_state == 0) { y_dist_des = -0.15; - } - else if (fsm_state == 1){ + } else if (fsm_state == 1) { y_dist_des = 0.15; } -// return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); -// samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.05, rest_length_; - samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.1, rest_length_; -// samples << 0, y_dist_des, rest_length_, 0, y_dist_des, rest_length_ + 0.1; - return PiecewisePolynomial::FirstOrderHold(breaks, samples); -// return PiecewisePolynomial::Cu(breaks, samples); -// return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( -// breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); + // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); + // samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, + // rest_length_ + 0.05, rest_length_; + samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.1; + // samples_dot << 0, 0, 0, 0, 0.25, 0.0; + // return PiecewisePolynomial::FirstOrderHold(breaks, samples); + // return PiecewisePolynomial::Cu(breaks, samples); + // return PiecewisePolynomial::CubicHermite( + // breaks, samples, samples_dot); + // return PiecewisePolynomial::CubicShapePreserving(breaks, samples); + + return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); + // return PiecewisePolynomial::CubicHermite( + // breaks, samples, samples_dot); } void PelvisTransTrajGenerator::CalcTraj( @@ -153,6 +158,13 @@ void PelvisTransTrajGenerator::CalcTraj( this->EvalVectorInput(context, fsm_port_)->get_value()(0); const auto& clock = this->EvalVectorInput(context, clock_port_)->get_value()(0); + const auto& mode_length = + this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); + + // std::cout << "fsm_state: " << fsm_state << std::endl; + // std::cout << "clock: " << clock << std::endl; + // std::cout << "mode_length start: " << mode_length[0] << std::endl; + // std::cout << "mode_length end: " << mode_length[1] << std::endl; auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( @@ -160,8 +172,8 @@ void PelvisTransTrajGenerator::CalcTraj( // const drake::VectorX& x = robot_output->GetState(); if (fsm_state == 0 || fsm_state == 1) { if (relative_pelvis_) { - *casted_traj = - GenerateSLIPTraj(robot_output->GetState(), clock, fsm_state); + *casted_traj = GenerateSLIPTraj(robot_output->GetState(), mode_length[0], + mode_length[1], fsm_state); } else { *casted_traj = GeneratePelvisTraj(robot_output->GetState(), clock, fsm_state); diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index 4038395f20..d76e309591 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -13,13 +13,13 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { public: PelvisTransTrajGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, + drake::systems::Context *context, drake::trajectories::PiecewisePolynomial& traj, const std::unordered_map< int, std::vector&>>>& - feet_contact_points, - bool relative_pelvis = false); + feet_contact_points, + bool relative_pelvis = false); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -30,6 +30,9 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const drake::systems::InputPort& get_clock_input_port() const { return this->get_input_port(clock_port_); } + const drake::systems::InputPort& get_contact_scheduler_input_port() const { + return this->get_input_port(contact_scheduler_port_); + } void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } @@ -38,17 +41,17 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const Eigen::VectorXd& x, double t, int fsm_state) const; drake::trajectories::PiecewisePolynomial GenerateSLIPTraj( - const Eigen::VectorXd& x, double t, int fsm_state) const; + const Eigen::VectorXd& x, double t_0, double t_f, int fsm_state) const; drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; + drake::systems::DiscreteValues *discrete_state) const; void CalcTraj(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; + drake::trajectories::Trajectory *traj) const; const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; + drake::systems::Context *context_; const drake::multibody::BodyFrame& world_; const drake::multibody::Body& pelvis_; const drake::multibody::BodyFrame& pelvis_frame_; @@ -68,6 +71,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex fsm_port_; drake::systems::InputPortIndex clock_port_; + drake::systems::InputPortIndex contact_scheduler_port_; // SLIP parameters double rest_length_ = 0.8; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 54bc8aaa3b..5aedbc5c86 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -160,7 +160,7 @@ int DoMain(int argc, char* argv[]) { std::cout << accumulated_state_durations.back() << std::endl; for (double state_duration : state_durations) { accumulated_state_durations.push_back(accumulated_state_durations.back() + - state_duration); + state_duration); std::cout << accumulated_state_durations.back() << std::endl; } accumulated_state_durations.pop_back(); @@ -200,9 +200,9 @@ int DoMain(int argc, char* argv[]) { osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight(1e-4 * - gains.W_lambda_c_regularization); + gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); + gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(gains.w_soft_constraint); @@ -393,14 +393,6 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); -// left_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// vel_map["hip_yaw_leftdot"], right_stance_state); -// left_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// vel_map["hip_yaw_leftdot"], right_touchdown_air_phase); -// right_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// vel_map["hip_yaw_rightdot"], left_stance_state); -// right_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// vel_map["hip_yaw_rightdot"], left_touchdown_air_phase); // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], left_stance_state); // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], right_stance_state); // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], left_stance_state); @@ -408,17 +400,10 @@ int DoMain(int argc, char* argv[]) { // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], left_stance_state); // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], right_stance_state); -// left_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// pos_map["hip_pitch_left"], right_stance_state); -// left_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// pos_map["hip_pitch_left"], right_touchdown_air_phase); -// right_foot_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// pos_map["hip_pitch_right"], left_stance_state); -// right_foot_yz_rel_tracking_data->AddJointAndStateToIgnoreInJacobian( -// pos_map["hip_pitch_right"], left_touchdown_air_phase); // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); + pelvis_trans_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); @@ -517,6 +502,8 @@ int DoMain(int argc, char* argv[]) { // OSC connections builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port_contact_scheduler(), + pelvis_trans_traj_generator->get_contact_scheduler_input_port()); builder.Connect(fsm->get_output_port_impact(), osc->get_near_impact_input_port()); builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 5ff004bc95..8eef515345 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -1,3 +1,4 @@ +#include #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" @@ -31,6 +32,15 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( BasicVector(1), &ImpactTimeBasedFiniteStateMachine::CalcClock) .get_index(); + radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + + contact_scheduler_port_ = this->DeclareVectorOutputPort("contact_scheduler", + BasicVector(2), + &ImpactTimeBasedFiniteStateMachine::CalcContactScheduler) + .get_index(); + // Accumulate the durations to get timestamps double sum = 0; @@ -110,4 +120,31 @@ void ImpactTimeBasedFiniteStateMachine::CalcClock( clock->get_mutable_value()(0) = remainder; } +void ImpactTimeBasedFiniteStateMachine::CalcContactScheduler( + const Context& context, BasicVector* contact_timing) const { + // Read in lcm message time + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + if (this->get_input_port(radio_port_).HasValue(context)) { + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + } + auto current_time = static_cast(robot_output->get_timestamp()); + double remainder = fmod(current_time, period_); + + for (unsigned int i = 0; i < accu_state_durations_.size(); i++) { + if (remainder < accu_state_durations_[i]) { + if(i == 0){ + contact_timing->get_mutable_value()(0) = 0 - 2e-3; + contact_timing->get_mutable_value()(1) = accu_state_durations_[i] + 2e-3; + } + else{ + contact_timing->get_mutable_value()(0) = accu_state_durations_[i-1] - 2e-3; + contact_timing->get_mutable_value()(1) = accu_state_durations_[i] + 2e-3; + } + break; + } + } +} + } // namespace dairlib diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index 3cad6c91b4..66d3421ff6 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -34,15 +34,22 @@ class ImpactTimeBasedFiniteStateMachine const drake::systems::OutputPort& get_output_port_impact() const { return this->get_output_port(near_impact_port_); } + const drake::systems::OutputPort& get_output_port_contact_scheduler() const { + return this->get_output_port(contact_scheduler_port_); + } private: void CalcNearImpact(const drake::systems::Context& context, - systems::ImpactInfoVector* near_impact) const; + systems::ImpactInfoVector *near_impact) const; void CalcClock(const drake::systems::Context& context, - drake::systems::BasicVector* clock) const; + drake::systems::BasicVector *clock) const; + void CalcContactScheduler(const drake::systems::Context& context, + drake::systems::BasicVector *clock) const; int near_impact_port_; int clock_port_; + int radio_port_; + int contact_scheduler_port_; double t0_; std::vector states_; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 3be54cf818..16584a6dda 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -48,8 +48,8 @@ using multibody::SetVelocitiesIfNew; using multibody::WorldPointEvaluator; OperationalSpaceControl::OperationalSpaceControl( - const MultibodyPlant &plant_w_spr, - const MultibodyPlant &plant_wo_spr, + const MultibodyPlant& plant_w_spr, + const MultibodyPlant& plant_wo_spr, drake::systems::Context *context_w_spr, drake::systems::Context *context_wo_spr, bool used_with_finite_state_machine, double qp_time_limit) @@ -107,7 +107,7 @@ OperationalSpaceControl::OperationalSpaceControl( &OperationalSpaceControl::CheckTracking) .get_index(); - const std::map &vel_map_wo_spr = + const std::map& vel_map_wo_spr = multibody::MakeNameToVelocitiesMap(plant_wo_spr); // Initialize the mapping from spring to no spring @@ -128,7 +128,7 @@ OperationalSpaceControl::OperationalSpaceControl( n_revolute_joints_ = 0; for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { - const drake::multibody::Joint &joint = plant_wo_spr_.get_joint(i); + const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); if (joint.type_name() == "revolute") { n_revolute_joints_ += 1; } @@ -137,7 +137,7 @@ OperationalSpaceControl::OperationalSpaceControl( VectorXd q_max(n_revolute_joints_); int floating_base_offset = n_v_ - n_revolute_joints_; for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { - const drake::multibody::Joint &joint = plant_wo_spr_.get_joint(i); + const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); if (joint.type_name() == "revolute") { q_min(vel_map_wo_spr.at(joint.name() + "dot") - floating_base_offset) = plant_wo_spr.get_joint(i).position_lower_limits()[0]; @@ -174,7 +174,7 @@ void OperationalSpaceControl::SetUpDoubleSupportPhaseBlending( } void OperationalSpaceControl::AddInputCostByJointAndFsmState( - const std::string &joint_u_name, int fsm, double w) { + const std::string& joint_u_name, int fsm, double w) { if (W_input_.size() == 0) { W_input_ = Eigen::MatrixXd::Zero(n_u_, n_u_); } @@ -242,7 +242,7 @@ void OperationalSpaceControl::AddTrackingData( } } void OperationalSpaceControl::AddConstTrackingData( - std::unique_ptr tracking_data, const VectorXd &v, + std::unique_ptr tracking_data, const VectorXd& v, double t_lb, double t_ub) { tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(v); @@ -277,7 +277,7 @@ void OperationalSpaceControl::Build() { // Checker CheckCostSettings(); CheckConstraintSettings(); - for (auto &tracking_data : *tracking_data_vec_) { + for (auto& tracking_data : *tracking_data_vec_) { tracking_data->CheckOscTrackingData(); DRAKE_DEMAND(&tracking_data->plant_w_spr() == &plant_w_spr_); DRAKE_DEMAND(&tracking_data->plant_wo_spr() == &plant_wo_spr_); @@ -450,28 +450,38 @@ void OperationalSpaceControl::Build() { .get()); // (Testing) 6. contact force blending - if (ds_duration_ > 0) { - epsilon_blend_ = - prog_->NewContinuousVariables(n_c_ / kSpaceDim, "epsilon_blend"); - blend_constraint_ = - prog_ - ->AddLinearEqualityConstraint( - MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim), VectorXd::Zero(1), - {lambda_c_.segment(kSpaceDim * 0 + 2, 1), - lambda_c_.segment(kSpaceDim * 1 + 2, 1), - lambda_c_.segment(kSpaceDim * 2 + 2, 1), - lambda_c_.segment(kSpaceDim * 3 + 2, 1), epsilon_blend_}) - .evaluator() - .get(); - /// Soft constraint version - // DRAKE_DEMAND(w_blend_constraint_ > 0); - // prog_->AddQuadraticCost( - // w_blend_constraint_ * - // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), - // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); - /// hard constraint version - prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); - } +// if (ds_duration_ > 0) { +// epsilon_blend_ = +// prog_->NewContinuousVariables(n_c_ / kSpaceDim, "epsilon_blend"); +// blend_constraint_ = +// prog_ +// ->AddLinearEqualityConstraint( +// MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim), VectorXd::Zero(1), +// {lambda_c_.segment(kSpaceDim * 0 + 2, 1), +// lambda_c_.segment(kSpaceDim * 1 + 2, 1), +// lambda_c_.segment(kSpaceDim * 2 + 2, 1), +// lambda_c_.segment(kSpaceDim * 3 + 2, 1), epsilon_blend_}) +// .evaluator() +// .get(); + /// Soft constraint version + // DRAKE_DEMAND(w_blend_constraint_ > 0); + // prog_->AddQuadraticCost( + // w_blend_constraint_ * + // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), + // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); + /// hard constraint version +// prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); +// } + blend_constraint_ = + prog_ + ->AddBoundingBoxConstraint( + VectorXd::Zero(4), VectorXd::Zero(4), + {lambda_c_.segment(kSpaceDim * 0 + 2, 1), + lambda_c_.segment(kSpaceDim * 1 + 2, 1), + lambda_c_.segment(kSpaceDim * 2 + 2, 1), + lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) + .evaluator() + .get(); for (int i = -1; i < 5; ++i) { solvers_[i] = std::make_unique(); @@ -479,7 +489,7 @@ void OperationalSpaceControl::Build() { } drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( - const drake::systems::Context &context, + const drake::systems::Context& context, drake::systems::DiscreteValues *discrete_state) const { const BasicVector *fsm_output = (BasicVector *) this->EvalVectorInput(context, fsm_port_); @@ -501,8 +511,8 @@ drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( } VectorXd OperationalSpaceControl::SolveQp( - const VectorXd &x_w_spr, const VectorXd &x_wo_spr, - const drake::systems::Context &context, double t, int fsm_state, + const VectorXd& x_w_spr, const VectorXd& x_wo_spr, + const drake::systems::Context& context, double t, int fsm_state, double time_since_last_state_switch, double alpha, int next_fsm_state) const { // Get active contact indices @@ -687,12 +697,12 @@ VectorXd OperationalSpaceControl::SolveQp( time_since_last_state_switch, fsm_state, v_proj); } else { // Read in traj from input port - const string &traj_name = tracking_data->GetName(); + const string& traj_name = tracking_data->GetName(); int port_index = traj_name_to_port_index_map_.at(traj_name); const drake::AbstractValue *input_traj = this->EvalAbstractInput(context, port_index); DRAKE_DEMAND(input_traj != nullptr); - const auto &traj = + const auto& traj = input_traj->get_value>(); // Update tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, @@ -700,10 +710,10 @@ VectorXd OperationalSpaceControl::SolveQp( time_since_last_state_switch, fsm_state, v_proj); } - const VectorXd &ddy_t = tracking_data->GetYddotCommand(); - const MatrixXd &W = tracking_data->GetWeight(); - const MatrixXd &J_t = tracking_data->GetJ(); - const VectorXd &JdotV_t = tracking_data->GetJdotTimesV(); + const VectorXd& ddy_t = tracking_data->GetYddotCommand(); + const MatrixXd& W = tracking_data->GetWeight(); + const MatrixXd& J_t = tracking_data->GetJ(); + const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); const VectorXd constant_term = (JdotV_t - ddy_t); // tracking_cost_.at(i)->UpdateCoefficients( // J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - @@ -743,34 +753,39 @@ VectorXd OperationalSpaceControl::SolveQp( joint_limit_cost_.at(0)->UpdateCoefficients(w_joint_limit, 0); // (Testing) 6. blend contact forces during double support phase - if (ds_duration_ > 0) { - MatrixXd A = MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim); - if (std::find(ds_states_.begin(), ds_states_.end(), fsm_state) != - ds_states_.end()) { - double alpha_left = 0; - double alpha_right = 0; - if (prev_distinct_fsm_state_ == right_support_state_) { - // We want left foot force to gradually increase - alpha_left = -1; - alpha_right = time_since_last_state_switch / - (ds_duration_ - time_since_last_state_switch); - - } else if (prev_distinct_fsm_state_ == left_support_state_) { - alpha_left = time_since_last_state_switch / - (ds_duration_ - time_since_last_state_switch); - alpha_right = -1; - } - A(0, 0) = alpha_left / 2; - A(0, 1) = alpha_left / 2; - A(0, 2) = alpha_right / 2; - A(0, 3) = alpha_right / 2; - A(0, 4) = 1; - A(0, 5) = 1; - A(0, 6) = 1; - A(0, 7) = 1; - } - blend_constraint_->UpdateCoefficients(A, VectorXd::Zero(1)); - } +// if (ds_duration_ > 0) { +// MatrixXd A = MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim); +// if (std::find(ds_states_.begin(), ds_states_.end(), fsm_state) != +// ds_states_.end()) { +// double alpha_left = 0; +// double alpha_right = 0; +// if (prev_distinct_fsm_state_ == right_support_state_) { +// // We want left foot force to gradually increase +// alpha_left = -1; +// alpha_right = time_since_last_state_switch / +// (ds_duration_ - time_since_last_state_switch); +// +// } else if (prev_distinct_fsm_state_ == left_support_state_) { +// alpha_left = time_since_last_state_switch / +// (ds_duration_ - time_since_last_state_switch); +// alpha_right = -1; +// } +// A(0, 0) = alpha_left / 2; +// A(0, 1) = alpha_left / 2; +// A(0, 2) = alpha_right / 2; +// A(0, 3) = alpha_right / 2; +// A(0, 4) = 1; +// A(0, 5) = 1; +// A(0, 6) = 1; +// A(0, 7) = 1; +// } + VectorXd normals = VectorXd(4); + normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), + lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), + lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), + lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); + blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 15 * VectorXd::Ones(4), normals + 15 * VectorXd::Ones(4)); +// } // test joint-level input cost by fsm state if (!fsm_to_w_input_map_.empty()) { @@ -868,7 +883,7 @@ VectorXd OperationalSpaceControl::SolveQp( *u_prev_ = 0.9 * *u_sol_ + VectorXd::Random(n_u_); } - for (auto &tracking_data : *tracking_data_vec_) { + for (auto& tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state)) { tracking_data->StoreYddotCommandSol(*dv_sol_); } @@ -877,9 +892,9 @@ VectorXd OperationalSpaceControl::SolveQp( return *u_sol_; } // namespace dairlib::systems::controllers void OperationalSpaceControl::UpdateImpactInvariantProjection( - const VectorXd &x_w_spr, const VectorXd &x_wo_spr, - const Context &context, double t, double t_since_last_state_switch, - int fsm_state, int next_fsm_state, const MatrixXd &M) const { + const VectorXd& x_w_spr, const VectorXd& x_wo_spr, + const Context& context, double t, double t_since_last_state_switch, + int fsm_state, int next_fsm_state, const MatrixXd& M) const { auto map_iterator = contact_indices_map_.find(next_fsm_state); if (map_iterator == contact_indices_map_.end()) { ii_lambda_sol_ = VectorXd::Zero(n_c_ + n_h_); @@ -921,11 +936,11 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( t_since_last_state_switch, fsm_state, v_proj); } else { // Read in traj from input port - const string &traj_name = tracking_data->GetName(); + const string& traj_name = tracking_data->GetName(); int port_index = traj_name_to_port_index_map_.at(traj_name); const drake::AbstractValue *input_traj = EvalAbstractInput(context, port_index); - const auto &traj = + const auto& traj = input_traj->get_value>(); tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, *context_wo_spr_, traj, t, @@ -937,7 +952,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( MatrixXd A = MatrixXd::Zero(active_tracking_data_dim, active_constraint_dim); VectorXd ydot_err_vec = VectorXd::Zero(active_tracking_data_dim); int start_row = 0; - for (auto &tracking_data : *tracking_data_vec_) { + for (auto& tracking_data : *tracking_data_vec_) { if (tracking_data->IsActive(fsm_state) && tracking_data->GetImpactInvariantProjection()) { A.block(start_row, 0, tracking_data->GetYdotDim(), @@ -970,7 +985,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } void OperationalSpaceControl::AssignOscLcmOutput( - const Context &context, dairlib::lcmt_osc_output *output) const { + const Context& context, dairlib::lcmt_osc_output *output) const { auto state = (OutputVector *) this->EvalVectorInput(context, state_port_); total_cost_ = 0; @@ -1097,10 +1112,10 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command_sol = CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); - const VectorXd &ddy_t = tracking_data->GetYddotCommand(); - const MatrixXd &W = tracking_data->GetWeight(); - const MatrixXd &J_t = tracking_data->GetJ(); - const VectorXd &JdotV_t = tracking_data->GetJdotTimesV(); + const VectorXd& ddy_t = tracking_data->GetYddotCommand(); + const MatrixXd& W = tracking_data->GetWeight(); + const MatrixXd& J_t = tracking_data->GetJ(); + const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); output->tracking_costs[i] = (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); @@ -1115,7 +1130,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( } void OperationalSpaceControl::CalcOptimalInput( - const drake::systems::Context &context, + const drake::systems::Context& context, systems::TimestampedVector *control) const { // Read in current state and time auto robot_output = @@ -1191,7 +1206,7 @@ void OperationalSpaceControl::CalcOptimalInput( } void OperationalSpaceControl::CheckTracking( - const drake::systems::Context &context, + const drake::systems::Context& context, TimestampedVector *output) const { auto robot_output = (OutputVector *) this->EvalVectorInput(context, state_port_); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index f8433d6ef8..1b5336540f 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -410,8 +410,9 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector ds_states_; double w_blend_constraint_ = 0.1; // for soft constraint mutable double prev_distinct_fsm_state_ = -1; - drake::solvers::LinearEqualityConstraint* blend_constraint_; + drake::solvers::BoundingBoxConstraint* blend_constraint_; drake::solvers::VectorXDecisionVariable epsilon_blend_; +// drake::solvers::BoundingBoxConstraint* contact_force_smoothing_constraint_; // Optional feature -- regularizing input mutable double total_cost_ = 0; From d9d78aea73602012bcfb76498cb3254e2cca6615 Mon Sep 17 00:00:00 2001 From: dair Date: Tue, 19 Jul 2022 11:45:23 -0400 Subject: [PATCH 256/758] updating rnning gains --- .../plot_configs/cassie_running_plot.yaml | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 20 +++++++------- .../osc_run/osc_running_qp_settings.yaml | 2 +- .../osc_run/pelvis_trans_traj_generator.cc | 26 ++++++++----------- 4 files changed, 23 insertions(+), 27 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index f203de3feb..4248a88dd1 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -31,7 +31,7 @@ fsm_state_names: ['Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', ' # Foot position plots foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] -foot_xyz_to_plot: { 'right': [0], 'left': [0] } +foot_xyz_to_plot: { 'right': [2], 'left': [2] } #foot_xyz_to_plot: { } pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 1d9c1571aa..4742a48ee2 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,6 +1,6 @@ w_input: 0.0000 w_input_reg: 0.1 -w_accel: 0.0001 +w_accel: 0.0000 w_soft_constraint: 100 impact_threshold: 0.05 impact_tau: 0.025 @@ -13,8 +13,8 @@ W_input_reg: [1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01] + 1, 0.001, 0.01, + 1, 0.001, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] #w_soft_constraint: 1000000 @@ -30,8 +30,8 @@ vel_scale_trans_lateral: -0.15 # SLIP parameters rest_length: 0.85 -stance_duration: 0.27 -flight_duration: 0.1 +stance_duration: 0.3 +flight_duration: 0.12 w_swing_toe: 1 swing_toe_kp: 1500 @@ -42,9 +42,9 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.05 -footstep_lateral_offset: 0.06 # drake -mid_foot_height: 0.05 +footstep_sagital_offset: -0.0 +footstep_lateral_offset: 0.03 # drake +mid_foot_height: 0.02 FootstepKd: [ 0.3, 0, 0, 0, 0.7, 0, @@ -56,7 +56,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 30] + 0, 0, 105] PelvisKd: [ 0, 0, 0, 0, 0, 0, @@ -76,7 +76,7 @@ PelvisRotKd: SwingFootW: [10, 0, 0, 0, 100, 0, - 0, 0, 5] + 0, 0, 100] SwingFootKp: [50, 0, 0, 0, 75, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 41753bee75..4238c8cf39 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 75 +max_iter: 150 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index bd19380e0c..2ebf9a3ed8 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -36,7 +36,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( const std::unordered_map< int, std::vector&>>>& - feet_contact_points, + feet_contact_points, bool relative_pelvis) : plant_(plant), context_(context), @@ -49,14 +49,14 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( this->set_name("pelvis_trans_traj_generator"); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); + "x, u, t", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) - .get_index(); + .get_index(); contact_scheduler_port_ = this->DeclareVectorInputPort("t_mode", BasicVector(2)) .get_index(); @@ -130,21 +130,17 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( } else if (fsm_state == 1) { y_dist_des = 0.15; } - // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); // samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, // rest_length_ + 0.05, rest_length_; - samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.1; +// samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.05; // samples_dot << 0, 0, 0, 0, 0.25, 0.0; + return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); // return PiecewisePolynomial::FirstOrderHold(breaks, samples); - // return PiecewisePolynomial::Cu(breaks, samples); // return PiecewisePolynomial::CubicHermite( // breaks, samples, samples_dot); // return PiecewisePolynomial::CubicShapePreserving(breaks, samples); - - return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); - // return PiecewisePolynomial::CubicHermite( - // breaks, samples, samples_dot); +// return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( +// breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); } void PelvisTransTrajGenerator::CalcTraj( @@ -167,7 +163,7 @@ void PelvisTransTrajGenerator::CalcTraj( // std::cout << "mode_length end: " << mode_length[1] << std::endl; auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( + (PiecewisePolynomial*) dynamic_cast*>( traj); // const drake::VectorX& x = robot_output->GetState(); if (fsm_state == 0 || fsm_state == 1) { From b81304a62ac8f980e61d5aeb3401c427c4d7f910 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 29 Jul 2022 15:41:01 -0400 Subject: [PATCH 257/758] working on variable step timing --- .../pydairlib/analysis/cassie_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_cassie.py | 6 +- .../pydairlib/analysis/mbp_plotting_utils.py | 36 +++ .../plot_configs/cassie_running_plot.yaml | 20 +- .../cassie/gym_envs/cassie_gym_test.py | 2 +- examples/Cassie/BUILD.bazel | 38 +-- .../osc_walking_controller_diagram.cc | 248 +++++++++++------- .../director_scripts/show_time_hardware.py | 7 +- .../solver_settings/osqp_options_walking.yaml | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 126 ++++----- examples/Cassie/osc_run/foot_traj_generator.h | 15 +- .../Cassie/osc_run/osc_running_gains.yaml | 84 +++--- .../osc_run/osc_running_qp_settings.yaml | 4 +- .../osc_run/pelvis_trans_traj_generator.cc | 2 +- examples/Cassie/run_osc_running_controller.cc | 4 + examples/Cassie/test/log_timing_test.cc | 2 +- .../impact_aware_time_based_fsm.cc | 84 +++--- .../osc/operational_space_control.cc | 64 ++--- .../controllers/osc/options_tracking_data.cc | 3 + 19 files changed, 429 insertions(+), 319 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index 884ef7cc2d..d258f348c2 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -49,5 +49,6 @@ def __init__(self, filename): self.plot_qp_solve_time = data['plot_qp_solve_time'] self.fsm_state_names = data['fsm_state_names'] self.plot_qp_solutions = data['plot_qp_solutions'] + self.plot_active_tracking_datas = data['plot_active_tracking_datas'] self.tracking_datas_to_plot = \ data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 242515dab6..6cff926648 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -89,8 +89,9 @@ def main(): ''' Plot Velocities ''' # Plot floating base velocities if applicable if use_floating_base and plot_config.plot_floating_base_velocities: - mbp_plots.plot_floating_base_velocities( + plot = mbp_plots.plot_floating_base_velocities( robot_output, vel_names, 6, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_floating_base_velocity_body_frame: mbp_plots.plot_floating_base_body_frame_velocities( @@ -162,6 +163,9 @@ def main(): if plot_config.plot_qp_solve_time: mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + if plot_config.plot_active_tracking_datas: + mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 70416af829..8111105eae 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -591,3 +591,39 @@ def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names): legend = ax.legend(handles=legend_elements, loc=4) # ax.add_artist(legend) ax.relim() + +def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_state_names): + ps = plot_styler.PlotStyler() + + ax = ps.fig.axes[0] + # ymin, ymax = ax.get_ylim() + ymin, ymax = 0, 1 + tracking_data_names = osc_debug['osc_debug_tracking_datas'].keys() + # import pdb; pdb.set_trace() + n_tracking_datas = len(tracking_data_names) + tracking_data_legend_elements = [] + + for i, tracking_data_name in enumerate(tracking_data_names): + # tracking_data_name = tracking_data_names[i] + tracking_data = osc_debug['osc_debug_tracking_datas'][ + tracking_data_name] + ax.fill_between(fsm_time, ymax - (i+0.25)/n_tracking_datas, ymax - + (i+0.75)/n_tracking_datas, + where=tracking_data.is_active.astype(bool)[ + :fsm_time.shape[0]], + color=ps.cmap(2 * i), alpha=0.5) + tracking_data_legend_elements.append(Patch(facecolor=ps.cmap(2 * i), + alpha=0.3, label=tracking_data_name)) + + # uses default color map + legend_elements = [] + for i in np.unique(fsm_signal): + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2 * i), alpha=0.2) + if fsm_state_names: + legend_elements.append(Patch(facecolor=ps.cmap(2 * i), alpha=0.3, label=fsm_state_names[i])) + + if len(legend_elements) > 0: + legend = ax.legend(handles=legend_elements, loc=4) + legend = ax.legend(handles=tracking_data_legend_elements, loc=1) + # ax.add_artist(legend) + ax.relim() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 4248a88dd1..45ed18914f 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,12 +1,13 @@ # LCM channels to read data from channel_x: "CASSIE_STATE_DISPATCHER" +#channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 0 -duration: -1 +start_time: 4 +duration: 6 # Plant properties use_springs: true @@ -14,7 +15,7 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: true -plot_floating_base_velocities: false +plot_floating_base_velocities: true plot_floating_base_velocity_body_frame: false plot_joint_positions: true plot_joint_velocities: true @@ -40,14 +41,15 @@ plot_qp_costs: true plot_qp_solve_time: true plot_qp_solutions: true plot_tracking_costs: true +plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel', 'accel' ] }, - right_ft_traj: {'dims': [2], 'derivs': ['pos', 'vel', 'accel' ] } + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} -# hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# left_ft_traj: {'dims': [1], 'derivs': ['pos']} -# left_ft_z_traj: {'dims': [1], 'derivs': ['pos']} -# right_ft_z_traj: {'dims': [1, 2], 'derivs': ['pos']} + # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} +# right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, + left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, + left_ft_z_traj: {'dims': [2], 'derivs': ['pos']}, +# right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} } \ No newline at end of file diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 33be56a4c8..825ce61520 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -11,7 +11,7 @@ def main(): osc_running_gains_filename = 'examples/Cassie/osc_run/osc_running_gains.yaml' # osc_running_gains_filename = 'examples/Cassie/osc_run/learned_osc_running_gains.yaml' - # osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains_alip.yaml' + osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains_alip.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' urdf = 'examples/Cassie/urdf/cassie_v2.urdf' diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 439b3d1c9c..9f3be203c8 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -298,25 +298,25 @@ cc_library( ], ) -cc_binary( - name = "log_timing_test", - srcs = ["test/log_timing_test.cc"], - deps = [ - "//lcmtypes:lcmt_robot", - "@drake//lcm", - "@gflags", - ], -) - -cc_binary( - name = "dispatcher_log_timing_test", - srcs = ["test/dispatcher_log_timing_test.cc"], - deps = [ - "//lcmtypes:lcmt_robot", - "@drake//lcm", - "@gflags", - ], -) +#cc_binary( +# name = "log_timing_test", +# srcs = ["test/log_timing_test.cc"], +# deps = [ +# "//lcmtypes:lcmt_robot", +# "@drake//lcm", +# "@gflags", +# ], +#) + +#cc_binary( +# name = "dispatcher_log_timing_test", +# srcs = ["test/dispatcher_log_timing_test.cc"], +# deps = [ +# "//lcmtypes:lcmt_robot", +# "@drake//lcm", +# "@gflags", +# ], +#) cc_test( name = "cassie_state_estimator_test", diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 122c4a61c9..d219796c24 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -30,6 +30,9 @@ #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" +#include "examples/Cassie/osc/osc_walking_gains_alip.h" +#include "systems/controllers/alip_swing_ft_traj_gen.h" +#include "systems/controllers/alip_traj_gen.h" namespace dairlib { @@ -65,8 +68,10 @@ namespace examples { namespace controllers { OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( - drake::multibody::MultibodyPlant& plant, bool has_double_stance, - const string& osc_walking_gains_filename, const string& osqp_settings_filename) + drake::multibody::MultibodyPlant &plant, + bool has_double_stance, + const string &osc_walking_gains_filename, + const string &osqp_settings_filename) : plant_(&plant), pos_map(multibody::MakeNameToPositionsMap(plant)), vel_map(multibody::MakeNameToVelocitiesMap(plant)), @@ -75,14 +80,16 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( left_heel(LeftToeRear(plant)), right_toe(RightToeFront(plant)), right_heel(RightToeRear(plant)), - left_toe_mid(std::pair&>( - (left_toe.first + left_heel.first) / 2, plant.GetFrameByName("toe_left"))), - right_toe_mid(std::pair&>( - (left_toe.first + left_heel.first) / 2, plant.GetFrameByName("toe_right"))), - left_toe_origin(std::pair&>( - Vector3d::Zero(), plant.GetFrameByName("toe_left"))), - right_toe_origin(std::pair&>( - Vector3d::Zero(), plant.GetFrameByName("toe_right"))), + left_toe_mid(std::pair &>( + (left_toe.first + left_heel.first) / 2, + plant.GetFrameByName("toe_left"))), + right_toe_mid(std::pair &>( + (left_toe.first + left_heel.first) / 2, + plant.GetFrameByName("toe_right"))), + left_toe_origin(std::pair &>( + Vector3d::Zero(), plant.GetFrameByName("toe_left"))), + right_toe_origin(std::pair &>( + Vector3d::Zero(), plant.GetFrameByName("toe_right"))), left_right_foot({left_toe_origin, right_toe_origin}), left_foot_points({left_heel, left_toe}), right_foot_points({right_heel, right_toe}), @@ -119,16 +126,20 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( DiagramBuilder builder; plant_context = plant.CreateDefaultContext(); feet_contact_points[0] = std::vector< - std::pair&>>( + std::pair &>>( {left_toe, left_heel}); feet_contact_points[1] = std::vector< - std::pair&>>( + std::pair &>>( {right_toe, right_heel}); - /**** OSC Gains ****/ - auto osc_walking_gains = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_walking_gains_filename)); + // Read-in the parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + OSCGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(osc_walking_gains_filename), {}, {}, yaml_options); + OSCWalkingGainsALIP osc_walking_gains = + drake::yaml::LoadYamlFile(osc_walking_gains_filename); + /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -173,8 +184,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( swing_ft_gain_multiplier_breaks = {0, left_support_duration / 2, left_support_duration}; swing_ft_gain_multiplier_samples = - std::vector < - drake::MatrixX>(3, drake::MatrixX::Identity(3, 3)); + std::vector< + drake::MatrixX>(3, drake::MatrixX::Identity(3, 3)); swing_ft_gain_multiplier_samples[2](2, 2) *= 0.3; swing_ft_gain_multiplier_gain_multiplier = PiecewisePolynomial::FirstOrderHold( @@ -183,8 +194,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( left_support_duration * 3 / 4, left_support_duration}; swing_ft_accel_gain_multiplier_samples = - std::vector < - drake::MatrixX>(4, drake::MatrixX::Identity(3, 3)); + std::vector< + drake::MatrixX>(4, drake::MatrixX::Identity(3, 3)); swing_ft_accel_gain_multiplier_samples[2](2, 2) *= 0; swing_ft_accel_gain_multiplier_samples[3](2, 2) *= 0; swing_ft_accel_gain_multiplier_gain_multiplier = @@ -216,7 +227,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( int n_u = plant.num_actuators(); MatrixXd Q_accel = osc_walking_gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingWeights(osc_walking_gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingWeights( + osc_walking_gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Soft constraint on contacts osc->SetSoftConstraintWeight(osc_walking_gains.w_soft_constraint); @@ -261,7 +273,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( std::cout << "Creating output trajectory leaf systems. " << std::endl; - cassie::osc::HighLevelCommand* high_level_command; + cassie::osc::HighLevelCommand *high_level_command; high_level_command = builder.AddSystem( plant, plant_context.get(), osc_walking_gains.vel_scale_rot, osc_walking_gains.vel_scale_trans_sagital, @@ -269,24 +281,35 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( auto head_traj_gen = builder.AddSystem( plant, plant_context.get()); auto lipm_traj_generator = builder.AddSystem( - plant, plant_context.get(), osc_walking_gains.lipm_height, unordered_fsm_states, - unordered_state_durations, contact_points_in_each_state); + plant, + plant_context.get(), + osc_walking_gains.lipm_height, + unordered_fsm_states, + unordered_state_durations, + contact_points_in_each_state); auto pelvis_traj_generator = builder.AddSystem( - plant, plant_context.get(), osc_walking_gains.lipm_height, unordered_fsm_states, - unordered_state_durations, contact_points_in_each_state, false); - auto walking_speed_control = - builder.AddSystem( - plant, plant_context.get(), osc_walking_gains.k_ff_lateral, osc_walking_gains.k_fb_lateral, - osc_walking_gains.k_ff_sagittal, osc_walking_gains.k_fb_sagittal, left_support_duration, 0, - osc_walking_gains.relative_swing_ft); + plant, + plant_context.get(), + osc_walking_gains.lipm_height, + unordered_fsm_states, + unordered_state_durations, + contact_points_in_each_state, + false); auto swing_ft_traj_generator = - builder.AddSystem( - plant, plant_context.get(), left_right_support_fsm_states, - left_right_support_state_durations, left_right_foot, "pelvis", - double_support_duration, osc_walking_gains.mid_foot_height, - osc_walking_gains.final_foot_height, osc_walking_gains.final_foot_velocity_z, - osc_walking_gains.max_CoM_to_footstep_dist, osc_walking_gains.footstep_offset, - osc_walking_gains.center_line_offset, osc_walking_gains.relative_swing_ft); + builder.AddSystem( + plant, + plant_context.get(), + left_right_support_fsm_states, + left_right_support_state_durations, + left_right_foot, + "pelvis", + double_support_duration, + osc_walking_gains.mid_foot_height, + osc_walking_gains.final_foot_height, + osc_walking_gains.final_foot_velocity_z, + osc_walking_gains.max_CoM_to_footstep_dist, + osc_walking_gains.footstep_offset, + osc_walking_gains.center_line_offset); auto left_toe_angle_traj_gen = builder.AddSystem( plant, plant_context.get(), pos_map["toe_left"], left_foot_points, @@ -296,88 +319,133 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( plant, plant_context.get(), pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); + auto alip_traj_generator = builder.AddSystem( + plant, + plant_context.get(), + osc_walking_gains.lipm_height, + unordered_fsm_states, + unordered_state_durations, + contact_points_in_each_state, + osc_walking_gains.Q_alip_kalman_filter.asDiagonal(), + osc_walking_gains.R_alip_kalman_filter.asDiagonal()); + + builder.Connect(fsm->get_output_port(0), + alip_traj_generator->get_input_port_fsm()); + builder.Connect(touchdown_event_time->get_output_port_event_time(), + alip_traj_generator->get_input_port_touchdown_time()); + builder.Connect(state_receiver->get_output_port(0), + alip_traj_generator->get_input_port_state()); + /**** Tracking Data *****/ std::cout << "Creating tracking data. " << std::endl; swing_foot_data = std::make_unique( - "swing_ft_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant, plant); + "swing_ft_data", + osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, + plant, + plant); swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); com_data = std::make_unique( - "com_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant, plant); + "com_data", + osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, + plant, + plant); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); swing_ft_traj_local = std::make_unique( - "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant, plant, swing_foot_data.get(), + "swing_ft_traj", + osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, + osc_walking_gains.W_swing_foot, + plant, + plant, + swing_foot_data.get(), com_data.get()); // WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); swing_ft_traj_local->SetViewFrame(view_frame); - swing_ft_traj_global = std::make_unique( - "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant, plant); swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); - if (osc_walking_gains.relative_swing_ft) { - swing_ft_traj_local->SetTimeVaryingGains( - swing_ft_gain_multiplier_gain_multiplier); - swing_ft_traj_local->SetFeedforwardAccelMultiplier( - swing_ft_accel_gain_multiplier_gain_multiplier); - osc->AddTrackingData(std::move(swing_ft_traj_local)); - } else { - swing_ft_traj_global->SetTimeVaryingGains( - swing_ft_gain_multiplier_gain_multiplier); - swing_ft_traj_global->SetFeedforwardAccelMultiplier( - swing_ft_accel_gain_multiplier_gain_multiplier); - osc->AddTrackingData(std::move(swing_ft_traj_global)); - } + swing_ft_traj_local->SetTimeVaryingGains( + swing_ft_gain_multiplier_gain_multiplier); + swing_ft_traj_local->SetFeedforwardAccelMultiplier( + swing_ft_accel_gain_multiplier_gain_multiplier); + osc->AddTrackingData(std::move(swing_ft_traj_local)); bool use_pelvis_for_lipm_tracking = true; pelvis_traj = std::make_unique( - "lipm_traj", osc_walking_gains.K_p_com, osc_walking_gains.K_d_com, osc_walking_gains.W_com, plant, + "lipm_traj", + osc_walking_gains.K_p_com, + osc_walking_gains.K_d_com, + osc_walking_gains.W_com, + plant, plant); pelvis_traj->AddPointToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_traj)); - - pelvis_balance_traj = std::make_unique ( - "pelvis_balance_traj", osc_walking_gains.K_p_pelvis_balance, osc_walking_gains.K_d_pelvis_balance, - osc_walking_gains.W_pelvis_balance, plant, plant); + + pelvis_balance_traj = std::make_unique( + "pelvis_balance_traj", + osc_walking_gains.K_p_pelvis_balance, + osc_walking_gains.K_d_pelvis_balance, + osc_walking_gains.W_pelvis_balance, + plant, + plant); pelvis_balance_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) - pelvis_heading_traj = std::make_unique ( - "pelvis_heading_traj", osc_walking_gains.K_p_pelvis_heading, osc_walking_gains.K_d_pelvis_heading, - osc_walking_gains.W_pelvis_heading, plant, plant); + pelvis_heading_traj = std::make_unique( + "pelvis_heading_traj", + osc_walking_gains.K_p_pelvis_heading, + osc_walking_gains.K_d_pelvis_heading, + osc_walking_gains.W_pelvis_heading, + plant, + plant); pelvis_heading_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_heading_traj), osc_walking_gains.period_of_no_heading_control); - - swing_toe_traj_left = std::make_unique ( - "left_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, - osc_walking_gains.W_swing_toe, plant, plant); - swing_toe_traj_right = std::make_unique ( - "right_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, - osc_walking_gains.W_swing_toe, plant, plant); + + swing_toe_traj_left = std::make_unique( + "left_toe_angle_traj", + osc_walking_gains.K_p_swing_toe, + osc_walking_gains.K_d_swing_toe, + osc_walking_gains.W_swing_toe, + plant, + plant); + swing_toe_traj_right = std::make_unique( + "right_toe_angle_traj", + osc_walking_gains.K_p_swing_toe, + osc_walking_gains.K_d_swing_toe, + osc_walking_gains.W_swing_toe, + plant, + plant); swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", "toe_leftdot"); swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", "toe_rightdot"); osc->AddTrackingData(std::move(swing_toe_traj_left)); osc->AddTrackingData(std::move(swing_toe_traj_right)); - - swing_hip_yaw_traj = std::make_unique ( - "swing_hip_yaw_traj", osc_walking_gains.K_p_hip_yaw, osc_walking_gains.K_d_hip_yaw, - osc_walking_gains.W_hip_yaw, plant, plant); - swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", + + swing_hip_yaw_traj = std::make_unique( + "swing_hip_yaw_traj", + osc_walking_gains.K_p_hip_yaw, + osc_walking_gains.K_d_hip_yaw, + osc_walking_gains.W_hip_yaw, + plant, + plant); + swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, + "hip_yaw_right", "hip_yaw_rightdot"); - swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", + swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, + "hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); - + /**** OSC settings ****/ @@ -426,24 +494,16 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( pelvis_traj_generator->get_input_port_touchdown_time()); builder.Connect(state_receiver->get_output_port(0), pelvis_traj_generator->get_input_port_state()); - builder.Connect(high_level_command->get_xy_output_port(), - walking_speed_control->get_input_port_des_hor_vel()); - builder.Connect(state_receiver->get_output_port(0), - walking_speed_control->get_input_port_state()); - builder.Connect(lipm_traj_generator->get_output_port_lipm_from_current(), - walking_speed_control->get_input_port_com()); - builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), - walking_speed_control->get_input_port_fsm_switch_time()); builder.Connect(fsm->get_output_port(0), swing_ft_traj_generator->get_input_port_fsm()); builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), swing_ft_traj_generator->get_input_port_fsm_switch_time()); builder.Connect(state_receiver->get_output_port(0), swing_ft_traj_generator->get_input_port_state()); - builder.Connect(lipm_traj_generator->get_output_port_lipm_from_current(), - swing_ft_traj_generator->get_input_port_com()); - builder.Connect(walking_speed_control->get_output_port(0), - swing_ft_traj_generator->get_input_port_sc()); + builder.Connect(alip_traj_generator->get_output_port_alip_state(), + swing_ft_traj_generator->get_input_port_alip_state()); + builder.Connect(high_level_command->get_xy_output_port(), + swing_ft_traj_generator->get_input_port_vdes()); builder.Connect(state_receiver->get_output_port(0), left_toe_angle_traj_gen->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/Cassie/director_scripts/show_time_hardware.py b/examples/Cassie/director_scripts/show_time_hardware.py index 5555f62c5b..bad7c4044c 100644 --- a/examples/Cassie/director_scripts/show_time_hardware.py +++ b/examples/Cassie/director_scripts/show_time_hardware.py @@ -61,6 +61,7 @@ def handle_message(self, msg): my_text = 'time: %.3f' % msg_time pelvis_height_text = 'pelvis height: %.3f' % pelvis_height pelvis_velocity_text = 'pelvis velocity: %.3f' % pelvis_velocity + realtime_text = '' if (len(self._real_time) >= self._num_msg_for_average): self._real_time.pop(0) @@ -70,10 +71,10 @@ def handle_message(self, msg): dt_real_time = self._real_time[-1] - self._real_time[0] rt_ratio = dt / dt_real_time + realtime_text = 'realtime rate: %.2f' % rt_ratio + # my_text = my_text + ', real time factor: %.2f' % rt_ratio - #my_text = my_text + ', real time factor: %.2f' % rt_ratio - - vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text, 'text') + vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text, 'text') # vis.updateText(my_text + '\n' + pelvis_velocity_text, 'text') diff --git a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml index 41753bee75..3e46b274fc 100644 --- a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml +++ b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 75 +max_iter: 500 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index d8bedda5cf..df22d765af 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -1,5 +1,7 @@ #include "foot_traj_generator.h" +#include + #include #include "dairlib/lcmt_radio_out.hpp" @@ -28,10 +30,10 @@ using drake::trajectories::Trajectory; namespace dairlib::examples::osc_run { -FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, - Context* context, - const string& foot_name, - const string& hip_name, bool relative_feet, +FootTrajGenerator::FootTrajGenerator(const MultibodyPlant &plant, + Context *context, + const string &foot_name, + const string &hip_name, bool relative_feet, const int stance_state, std::vector state_durations) : plant_(plant), @@ -43,7 +45,7 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, stance_state_(stance_state), state_durations_(state_durations) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); - Trajectory& traj_inst = empty_pp_traj; + Trajectory &traj_inst = empty_pp_traj; if (foot_name == "toe_left") { is_left_foot_ = true; @@ -59,23 +61,26 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); target_vel_port_ = this->DeclareVectorInputPort( - "v_des", BasicVector(VectorXd::Zero(2))) - .get_index(); + "v_des", BasicVector(VectorXd::Zero(2))) + .get_index(); fsm_port_ = this->DeclareVectorInputPort( - "fsm", BasicVector(VectorXd::Zero(1))) - .get_index(); + "fsm", BasicVector(VectorXd::Zero(1))) + .get_index(); clock_port_ = this->DeclareVectorInputPort( - "clock", BasicVector(VectorXd::Zero(1))) - .get_index(); + "clock", BasicVector(VectorXd::Zero(1))) + .get_index(); radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); + contact_scheduler_port_ = + this->DeclareVectorInputPort("t_mode", BasicVector(6)) + .get_index(); // The swing foot position in the beginning of the swing phase initial_foot_pos_idx_ = this->DeclareDiscreteState(3); @@ -90,11 +95,11 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, } EventStatus FootTrajGenerator::DiscreteVariableUpdate( - const Context& context, - DiscreteValues* discrete_state) const { + const Context &context, + DiscreteValues *discrete_state) const { // Read in current state - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); // Read in finite state machine VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); @@ -118,17 +123,17 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( // Only update the current foot position when in stance ( if (fsm_state(0) == stance_state_) { auto foot_pos = discrete_state->get_mutable_vector(initial_foot_pos_idx_) - .get_mutable_value(); + .get_mutable_value(); plant_.CalcPointsPositions(*context_, foot_frame_, Vector3d::Zero(), world_, &foot_pos); auto hip_pos = discrete_state->get_mutable_vector(initial_hip_pos_idx_) - .get_mutable_value(); + .get_mutable_value(); plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, &hip_pos); foot_pos = rot.transpose() * foot_pos; hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - .get_mutable_value(); + .get_mutable_value(); pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; @@ -141,17 +146,20 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( } PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( - const drake::systems::Context& context) const { + const drake::systems::Context &context) const { const auto robot_output = this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); double clock = this->EvalVectorInput(context, clock_port_)->get_value()(0); + const auto &mode_lengths = + this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); + // Offset between 0 and 2 double lateral_radio_tuning = 1.0; double sagital_radio_tuning = 1.0; if (this->get_input_port(radio_port_).HasValue(context)) { - const auto& radio_out = + const auto &radio_out = this->EvalInputValue(context, radio_port_); lateral_radio_tuning += radio_out->channel[4]; sagital_radio_tuning += radio_out->channel[5]; @@ -184,34 +192,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d pelvis_pos; plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, &pelvis_pos); - // double L_y_des = desired_pelvis_vel(0) * (pelvis_pos(2) - foot_pos(2)) * - // m_; double L_x_offset = - // -desired_pelvis_vel(1) * (pelvis_pos(2) - foot_pos(2)) * m_; - // Vector3d L = plant_.CalcSpatialMomentumInWorldAboutPoint(*context_, - // foot_pos) - // .rotational(); - // double H = pelvis_pos(2) - foot_pos(2); - // double omega = sqrt(9.81 / H); - // double T = state_durations_[4] - state_durations_[1]; - // Vector3d L_pred = m_ * H * omega * sinh(omega * (T - clock)) * pelvis_pos - // + - // cosh(omega * (T - clock)) * L; - // double L_x_n = 0.5 * m_ * H * lateral_offset_ * - // (omega * sinh(omega * T) / (1 + cosh(omega * T))); - // Vector2d L_i = multibody::ReExpressWorldVector2InBodyYawFrame( - // plant_, *context_, "pelvis", L_pred.head(2)); - // double p_x_ft_to_com = - // (L_y_des - cosh(omega * T) * L_i(1)) / (m_ * H * omega * sinh(omega * - // T)); - // double p_y_ft_to_com = -(L_x_offset + L_x_n - cosh(omega * T) * L_i(0)) / - // (m_ * H * omega * sinh(omega * T)); - // Vector2d foot_end_pos_xy = Vector2d(-p_x_ft_to_com, p_y_ft_to_com); - // - // Vector3d foot_end_pos_des = Vector3d::Zero(); - // foot_end_pos_des << foot_end_pos_xy, 0; - // /// ALIP - // VectorXd pelvis_vel = v.segment(3, 3); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; VectorXd foot_end_pos_des = Kd_ * (pelvis_vel_err); @@ -224,10 +205,19 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( foot_end_pos_des(0) += sagital_radio_tuning * sagital_offset_; foot_end_pos_des(2) = 0; + double pelvis_t0 = mode_lengths[0]; + double pelvis_tf = mode_lengths[1]; + double left_t0 = mode_lengths[2]; + double left_tf = mode_lengths[3]; + double right_t0 = mode_lengths[4]; + double right_tf = mode_lengths[5]; + std::vector T_waypoints; std::vector T_waypoints_0; std::vector T_waypoints_1; std::vector T_waypoints_2; + + // Storing old method for record keeping T_waypoints = {state_durations_[1], state_durations_[1] + 1.5 / 3.0 * (state_durations_[4] - state_durations_[1]), @@ -240,6 +230,15 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( T_waypoints_1 = {state_durations_[2], state_durations_[3]}; T_waypoints_2 = {state_durations_[3], state_durations_[4]}; +// T_waypoints = {left_t0, left_t0 + 0.5 * (left_tf - left_t0), left_tf}; +// T_waypoints_0 = { +// pelvis_t0, +// (state_durations_[3] - state_durations_[4]) + +// 1.5 / 3.0 * (0.1 + state_durations_[2] - pelvis_t0), +// state_durations_[2]}; +// T_waypoints_1 = {state_durations_[2], state_durations_[3]}; +// T_waypoints_2 = {state_durations_[3], state_durations_[4]}; + // auto foot_pos = // context.get_discrete_state(initial_foot_pos_idx_).get_value(); auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); @@ -265,13 +264,16 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -lateral_offset_); } - MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); - MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); - Y_dot_end(2) = -0.1; +// MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); +// MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); +// Y_dot_end(2) = -0.1; +// PiecewisePolynomial swing_foot_spline = +// PiecewisePolynomial::CubicWithContinuousSecondDerivatives( +// T_waypoints, Y, Y_dot_start, Y_dot_end); PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - T_waypoints, Y, Y_dot_start, Y_dot_end); + T_waypoints, Y, false); if (is_left_foot_) { return swing_foot_spline; @@ -300,17 +302,17 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); offset_swing_foot_spline.ConcatenateInTime( PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); - // for (auto t : offset_swing_foot_spline.get_segment_times()){ - // std::cout << t << std::endl; - // } +// for (auto t: offset_swing_foot_spline.get_segment_times()) { +// std::cout << t << std::endl; +// } return offset_swing_foot_spline; } // return swing_foot_spline; } void FootTrajGenerator::CalcTraj( - const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const { + const drake::systems::Context &context, + drake::trajectories::Trajectory *traj) const { // Read in current state // const auto robot_output = // this->template EvalVectorInput(context, state_port_); @@ -321,8 +323,8 @@ void FootTrajGenerator::CalcTraj( // const auto fsm_state = this->EvalVectorInput(context, // fsm_port_)->get_value(); - auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( + auto *casted_traj = + (PiecewisePolynomial *) dynamic_cast *>( traj); // if (fsm_state[0] == FLIGHT) { *casted_traj = GenerateFlightTraj(context); diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index e22329d831..fc617e51dd 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -32,6 +32,9 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::systems::InputPort& get_radio_input_port() const { return this->get_input_port(radio_port_); } + const drake::systems::InputPort& get_contact_scheduler_input_port() const { + return this->get_input_port(contact_scheduler_port_); + } void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; @@ -76,11 +79,13 @@ class FootTrajGenerator : public drake::systems::LeafSystem { bool relative_feet_; int stance_state_; - int state_port_; - int target_vel_port_; - int fsm_port_; - int clock_port_; - int radio_port_; + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex target_vel_port_; + drake::systems::InputPortIndex fsm_port_; + drake::systems::InputPortIndex clock_port_; + drake::systems::InputPortIndex radio_port_; + drake::systems::InputPortIndex contact_scheduler_port_; + int initial_foot_pos_idx_; int initial_hip_pos_idx_; int pelvis_yaw_idx_; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4742a48ee2..1b0221e382 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,37 +1,37 @@ -w_input: 0.0000 +w_input: 0.0001 w_input_reg: 0.1 -w_accel: 0.0000 +w_accel: 0.0001 w_soft_constraint: 100 -impact_threshold: 0.05 +impact_threshold: 0.025 impact_tau: 0.025 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe -W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5] -W_lambda_c_reg: [1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01] -W_lambda_h_reg: [0.01, 0.01, 0.01, - 0.01, 0.02, 0.02] +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] +W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01 ] +W_lambda_h_reg: [ 0.01, 0.01, 0.01, + 0.01, 0.02, 0.02 ] #w_soft_constraint: 1000000 relative_feet: true relative_pelvis: true -ekf_filter_tau: [0.05, 0.01, 0.01] +ekf_filter_tau: [ 0.05, 0.01, 0.01 ] # High level command gains (with radio) vel_scale_rot: -0.5 vel_scale_trans_sagital: 0.25 -vel_scale_trans_lateral: -0.15 +vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -stance_duration: 0.3 -flight_duration: 0.12 +stance_duration: 0.25 +flight_duration: 0.10 w_swing_toe: 1 swing_toe_kp: 1500 @@ -42,9 +42,9 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.0 +footstep_sagital_offset: -0.1 footstep_lateral_offset: 0.03 # drake -mid_foot_height: 0.02 +mid_foot_height: 0.05 FootstepKd: [ 0.3, 0, 0, 0, 0.7, 0, @@ -52,42 +52,42 @@ FootstepKd: PelvisW: [ 0, 0, 0, 0, 0, 0, - 0, 0, 10 ] + 0, 0, 5 ] PelvisKp: [ 0, 0, 0, 0, 0, 0, 0, 0, 105] PelvisKd: - [ 0, 0, 0, - 0, 0, 0, - 0, 0, 5] + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 4.5 ] PelvisRotW: - [5, 0, 0, - 0, 1, 0, - 0, 0, 5] + [ 1, 0, 0, + 0, 10, 0, + 0, 0, 1 ] PelvisRotKp: - [50., 0, 0, - 0, 200., 0, + [20., 0, 0, + 0, 100., 0, 0, 0, 0.] PelvisRotKd: [5., 0, 0, - 0, 10., 0, - 0, 0, 1.] + 0, 5., 0, + 0, 0, 3.] SwingFootW: - [10, 0, 0, - 0, 100, 0, - 0, 0, 100] + [ 10, 0, 0, + 0, 100, 0, + 0, 0, 5 ] SwingFootKp: - [50, 0, 0, - 0, 75, 0, - 0, 0, 45] + [ 50, 0, 0, + 0, 50, 0, + 0, 0, 50 ] SwingFootKd: - [5., 0, 0, - 0, 5., 0, - 0, 0, 2.] + [ 5., 0, 0, + 0, 5., 0, + 0, 0, 1. ] LiftoffSwingFootW: - [5, 0, 0, - 0, 5, 0, + [1, 0, 0, + 0, 1, 0, 0, 0, 1] LiftoffSwingFootKp: [50, 0, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 4238c8cf39..b446b78ecf 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 150 +max_iter: 100 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -12,7 +12,7 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 15 +check_termination: 25 warm_start: 1 scaling: 1 adaptive_rho: 1 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 2ebf9a3ed8..13cfec6ce5 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -58,7 +58,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) .get_index(); contact_scheduler_port_ = - this->DeclareVectorInputPort("t_mode", BasicVector(2)) + this->DeclareVectorInputPort("t_mode", BasicVector(6)) .get_index(); PiecewisePolynomial empty_pp_traj(VectorXd(0)); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 5aedbc5c86..2640eec277 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -504,6 +504,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); builder.Connect(fsm->get_output_port_contact_scheduler(), pelvis_trans_traj_generator->get_contact_scheduler_input_port()); + builder.Connect(fsm->get_output_port_contact_scheduler(), + l_foot_traj_generator->get_contact_scheduler_input_port()); + builder.Connect(fsm->get_output_port_contact_scheduler(), + r_foot_traj_generator->get_contact_scheduler_input_port()); builder.Connect(fsm->get_output_port_impact(), osc->get_near_impact_input_port()); builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); diff --git a/examples/Cassie/test/log_timing_test.cc b/examples/Cassie/test/log_timing_test.cc index be45d8857a..568870016a 100644 --- a/examples/Cassie/test/log_timing_test.cc +++ b/examples/Cassie/test/log_timing_test.cc @@ -1,7 +1,7 @@ #include #include #include -#include "lcm/lcm-cpp.hpp" +#include DEFINE_string(file, "", "Log file name."); DEFINE_int64(max_count, 5000, "Max number of messages to read."); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 8eef515345..95197b4f28 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -1,7 +1,6 @@ #include #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" - using drake::systems::BasicVector; using drake::systems::Context; using Eigen::VectorXd; @@ -13,8 +12,8 @@ using systems::OutputVector; using systems::ImpactInfoVector; ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( - const drake::multibody::MultibodyPlant& plant, - const std::vector& states, const std::vector& state_durations, + const drake::multibody::MultibodyPlant &plant, + const std::vector &states, const std::vector &state_durations, double t0, double near_impact_threshold, double tau, BLEND_FUNC blend_func) : TimeBasedFiniteStateMachine(plant, states, state_durations, t0), states_(states), @@ -25,21 +24,25 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( near_impact_port_ = this->DeclareVectorOutputPort("near_impact", - ImpactInfoVector(0, 0, 0), - &ImpactTimeBasedFiniteStateMachine::CalcNearImpact) + ImpactInfoVector(0, 0, 0), + &ImpactTimeBasedFiniteStateMachine::CalcNearImpact) .get_index(); clock_port_ = this->DeclareVectorOutputPort("clock", - BasicVector(1), - &ImpactTimeBasedFiniteStateMachine::CalcClock) - .get_index(); + BasicVector(1), + &ImpactTimeBasedFiniteStateMachine::CalcClock) + .get_index(); radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) - .get_index(); + drake::Value{}) + .get_index(); - contact_scheduler_port_ = this->DeclareVectorOutputPort("contact_scheduler", - BasicVector(2), - &ImpactTimeBasedFiniteStateMachine::CalcContactScheduler) - .get_index(); + contact_scheduler_port_ = this->DeclareVectorOutputPort("contact_scheduler " + "(pelvis_t0, " + "pelvis_tf, " + "left_t0, left_tf, " + "right_t0, right_t0", + BasicVector(6), + &ImpactTimeBasedFiniteStateMachine::CalcContactScheduler) + .get_index(); // Accumulate the durations to get timestamps @@ -52,15 +55,10 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( accu_state_durations_.push_back(sum); if (states[i] >= 2) { impact_times_.push_back(sum); - impact_states_.push_back(states[i+1]); + impact_states_.push_back(states[i + 1]); } } -// std::cout << "Impact times: " << std::endl; -// for(int i = 0; i < impact_times_.size(); ++i){ -// std::cout << impact_times_[i] << std::endl; -// } - period_ = sum; } @@ -74,10 +72,11 @@ double alpha_exp(double t, double tau, double near_impact_threshold) { } void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( - const Context& context, ImpactInfoVector* near_impact) const { + const Context &context, + ImpactInfoVector *near_impact) const { // Read in lcm message time - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); @@ -92,8 +91,8 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { double blend_window = blend_func_ == SIGMOID - ? 1.5 * near_impact_threshold_ - : near_impact_threshold_; + ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; if (abs(remainder - impact_times_[i]) < blend_window) { if (remainder < impact_times_[i]) { near_impact->SetAlpha(alpha_func(remainder - impact_times_[i], tau_, @@ -110,10 +109,10 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( } void ImpactTimeBasedFiniteStateMachine::CalcClock( - const Context& context, BasicVector* clock) const { + const Context &context, BasicVector *clock) const { // Read in lcm message time - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); @@ -121,12 +120,12 @@ void ImpactTimeBasedFiniteStateMachine::CalcClock( } void ImpactTimeBasedFiniteStateMachine::CalcContactScheduler( - const Context& context, BasicVector* contact_timing) const { + const Context &context, BasicVector *contact_timing) const { // Read in lcm message time - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); if (this->get_input_port(radio_port_).HasValue(context)) { - const auto& radio_out = + const auto &radio_out = this->EvalInputValue(context, radio_port_); } auto current_time = static_cast(robot_output->get_timestamp()); @@ -134,13 +133,20 @@ void ImpactTimeBasedFiniteStateMachine::CalcContactScheduler( for (unsigned int i = 0; i < accu_state_durations_.size(); i++) { if (remainder < accu_state_durations_[i]) { - if(i == 0){ - contact_timing->get_mutable_value()(0) = 0 - 2e-3; - contact_timing->get_mutable_value()(1) = accu_state_durations_[i] + 2e-3; - } - else{ - contact_timing->get_mutable_value()(0) = accu_state_durations_[i-1] - 2e-3; - contact_timing->get_mutable_value()(1) = accu_state_durations_[i] + 2e-3; + if (i == 0) { + contact_timing->get_mutable_value()(0) = 0; + contact_timing->get_mutable_value()(1) = accu_state_durations_[i]; + contact_timing->get_mutable_value()(2) = 0; + contact_timing->get_mutable_value()(3) = accu_state_durations_[i]; + contact_timing->get_mutable_value()(4) = 0; + contact_timing->get_mutable_value()(5) = accu_state_durations_[i]; + } else { + contact_timing->get_mutable_value()(0) = accu_state_durations_[i - 1]; + contact_timing->get_mutable_value()(1) = accu_state_durations_[i]; + contact_timing->get_mutable_value()(2) = accu_state_durations_[i - 1]; + contact_timing->get_mutable_value()(3) = accu_state_durations_[i]; + contact_timing->get_mutable_value()(4) = accu_state_durations_[i - 1]; + contact_timing->get_mutable_value()(5) = accu_state_durations_[i]; } break; } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 16584a6dda..71ec73e31d 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -428,10 +428,10 @@ void OperationalSpaceControl::Build() { .evaluator() .get(); } - input_smoothing_constraint_ = - prog_->AddBoundingBoxConstraint(VectorXd::Zero(n_u_), VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); +// input_smoothing_constraint_ = +// prog_->AddBoundingBoxConstraint(VectorXd::Zero(n_u_), VectorXd::Zero(n_u_), u_) +// .evaluator() +// .get(); // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { tracking_cost_.push_back(prog_ @@ -472,16 +472,16 @@ void OperationalSpaceControl::Build() { /// hard constraint version // prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); // } - blend_constraint_ = - prog_ - ->AddBoundingBoxConstraint( - VectorXd::Zero(4), VectorXd::Zero(4), - {lambda_c_.segment(kSpaceDim * 0 + 2, 1), - lambda_c_.segment(kSpaceDim * 1 + 2, 1), - lambda_c_.segment(kSpaceDim * 2 + 2, 1), - lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) - .evaluator() - .get(); +// blend_constraint_ = +// prog_ +// ->AddBoundingBoxConstraint( +// VectorXd::Zero(4), VectorXd::Zero(4), +// {lambda_c_.segment(kSpaceDim * 0 + 2, 1), +// lambda_c_.segment(kSpaceDim * 1 + 2, 1), +// lambda_c_.segment(kSpaceDim * 2 + 2, 1), +// lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) +// .evaluator() +// .get(); for (int i = -1; i < 5; ++i) { solvers_[i] = std::make_unique(); @@ -563,19 +563,12 @@ VectorXd OperationalSpaceControl::SolveQp( bool near_impact = alpha != 0; VectorXd v_proj = VectorXd::Zero(n_v_); if (near_impact) { -// auto start = std::chrono::high_resolution_clock::now(); UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, time_since_last_state_switch, fsm_state, next_fsm_state, M); -// auto finish = std::chrono::high_resolution_clock::now(); -// std::chrono::duration elapsed = finish - start; -// cout << "Solve time:" << elapsed.count() << std::endl; // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; } - // SetVelocitiesIfNew( - // plant_wo_spr_, x_wo_spr.tail(plant_wo_spr_.num_velocities()) + v_proj, - // context_wo_spr_); // Get J and JdotV for holonomic constraint MatrixXd J_h(n_h_, n_v_); @@ -640,18 +633,10 @@ VectorXd OperationalSpaceControl::SolveQp( /// JdotV_c_active + J_c_active*dv == -epsilon /// -> J_c_active*dv + I*epsilon == -JdotV_c_active /// -> [J_c_active, I]* [dv, epsilon]^T == -JdotV_c_active - MatrixXd A_c = MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_); - A_c.block(0, 0, n_c_active_, n_v_) = J_c_active; - MatrixXd weight = 0.001 * MatrixXd::Identity(n_c_active_, n_c_active_); - weight(0, 0) *= 1e-3; - weight(1, 1) *= 1e-3; - weight(3, 3) *= 1e-3; - weight(4, 4) *= 1e-3; - A_c.block(0, n_v_, n_c_active_, n_c_active_) = weight; - // A_c.block(0, n_v_, n_c_active_, n_c_active_) = - // MatrixXd::Identity(n_c_active_, n_c_active_); + A_c.block(0, n_v_, n_c_active_, n_c_active_) = + MatrixXd::Identity(n_c_active_, n_c_active_); contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); } } @@ -779,12 +764,12 @@ VectorXd OperationalSpaceControl::SolveQp( // A(0, 6) = 1; // A(0, 7) = 1; // } - VectorXd normals = VectorXd(4); - normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), - lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), - lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), - lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); - blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 15 * VectorXd::Ones(4), normals + 15 * VectorXd::Ones(4)); +// VectorXd normals = VectorXd(4); +// normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), +// lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), +// lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), +// lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); +// blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 15 * VectorXd::Ones(4), normals + 15 * VectorXd::Ones(4)); // } // test joint-level input cost by fsm state @@ -803,8 +788,9 @@ VectorXd OperationalSpaceControl::SolveQp( input_smoothing_cost_->UpdateCoefficients( W_input_smoothing_, -W_input_smoothing_ * *u_prev_); } - input_smoothing_constraint_->UpdateCoefficients( - MatrixXd::Identity(n_u_, n_u_), *u_prev_ - 1 * u_max_, *u_prev_ + 1 * u_max_); +// input_smoothing_constraint_->UpdateCoefficients( +// MatrixXd::Identity(n_u_, n_u_), *u_prev_ - 1 * u_max_, *u_prev_ + 1 * u_max_); + if (W_lambda_c_reg_.size() > 0) { lambda_c_smoothing_cost_->UpdateCoefficients(1000 * alpha * W_lambda_c_reg_, VectorXd::Zero(n_c_)); diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index f3a0d72bb2..c8b2cc6d9c 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -82,6 +82,9 @@ void OptionsTrackingData::UpdateYddotDes(double t, yddot_des_converted_ = ff_accel_multiplier_->value(t_since_state_switch) * yddot_des_converted_; } +// if(this->GetName() == "pelvis_trans_traj"){ +// yddot_des_converted_[2] -= 9.81; +// } } void OptionsTrackingData::UpdateYddotCmd(double t, From 4fa09298b15eb0baf9e7e3399cfd8b038eb2251c Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 2 Aug 2022 15:57:24 -0400 Subject: [PATCH 258/758] removed clock for variable footstep timing --- .../plot_configs/cassie_jumping_plot.yaml | 55 ++-- .../plot_configs/cassie_running_plot.yaml | 34 +-- bindings/pydairlib/lcm/BUILD.bazel | 2 + bindings/pydairlib/lcm/__init__.py | 2 +- .../lcm/dircon_trajectory_plotter.py | 18 +- .../Cassie/osc_run/foot_traj_generator.cc | 45 +++- examples/Cassie/osc_run/foot_traj_generator.h | 1 + .../Cassie/osc_run/osc_running_gains.yaml | 36 +-- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_dircon_jumping.cc | 242 +++++++++--------- .../impact_aware_time_based_fsm.cc | 37 ++- .../osc/operational_space_control.cc | 55 ++-- 12 files changed, 288 insertions(+), 241 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index b40798887d..532bc1a22f 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -1,29 +1,54 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_SIMULATION" -channel_u: "CASSIE_INPUT" +channel_x: "CASSIE_STATE_DISPATCHER" +#channel_x: "CASSIE_STATE_SIMULATION" +channel_u: "OSC_JUMPING" channel_osc: "OSC_DEBUG_JUMPING" +use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -end_time: -1 +start_time: 20 +duration: 5 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false -plot_floating_base_velocities: false -plot_joint_positions: false -plot_joint_velocities: false +plot_floating_base_positions: true +plot_floating_base_velocities: true +plot_floating_base_velocity_body_frame: false +plot_joint_positions: true +plot_joint_velocities: true plot_measured_efforts: true -special_positions_to_plot: [] -special_velocities_to_plot: [] -special_efforts_to_plot: [] +plot_commanded_efforts: true +plot_contact_forces: false +special_positions_to_plot: [ 'hip_pitch_left'] +special_velocities_to_plot: ['hip_pitch_leftdot'] +special_efforts_to_plot: [ ] + +# Finite State Machine Names +fsm_state_names: ['READY,', 'BALANCE', 'CROUCH', 'FLIGHT', 'LAND'] + +# Foot position plots +foot_positions_to_plot: [ 'right', 'left' ] +#foot_positions_to_plot: [] +foot_xyz_to_plot: { 'right': [2], 'left': [2] } +#foot_xyz_to_plot: { } +pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: false +plot_qp_costs: true +plot_qp_solve_time: true +plot_qp_solutions: true plot_tracking_costs: true -tracking_datas_to_plot: - left_ft_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} - right_ft_traj: {'dims': [0], 'derivs': ['pos', 'vel', 'accel']} -# swing_ft_traj: {'dims': [2], 'derivs': ['pos', 'accel']} +plot_active_tracking_datas: true +tracking_datas_to_plot: { + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel'] }, + # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} + # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, + left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, + # right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} + # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} + # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} +} \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 45ed18914f..aa8ff719e8 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,13 +1,13 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_DISPATCHER" -#channel_x: "CASSIE_STATE_SIMULATION" +#channel_x: "CASSIE_STATE_DISPATCHER" +channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 4 -duration: 6 +start_time: 0 +duration: -1 # Plant properties use_springs: true @@ -15,15 +15,15 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: true -plot_floating_base_velocities: true +plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false -plot_joint_positions: true -plot_joint_velocities: true +plot_joint_positions: false +plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -special_positions_to_plot: [ 'hip_pitch_left'] -special_velocities_to_plot: ['hip_pitch_leftdot'] +special_positions_to_plot: [] +special_velocities_to_plot: [] special_efforts_to_plot: [ ] # Finite State Machine Names @@ -37,19 +37,19 @@ foot_xyz_to_plot: { 'right': [2], 'left': [2] } pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: true -plot_qp_solve_time: true -plot_qp_solutions: true -plot_tracking_costs: true +plot_qp_costs: false +plot_qp_solve_time: false +plot_qp_solutions: false +plot_tracking_costs: false plot_active_tracking_datas: true tracking_datas_to_plot: { pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, - left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, - left_ft_z_traj: {'dims': [2], 'derivs': ['pos']}, -# right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} +# right_ft_traj: {'dims': [0, 2], 'derivs': ['pos'] }, +# left_ft_traj: {'dims': [0], 'derivs': ['pos']}, +# left_ft_z_traj: {'dims': [0], 'derivs': ['pos']}, +# right_ft_z_traj: {'dims': [0, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} } \ No newline at end of file diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index d40bcb5b64..126e076dd0 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -60,9 +60,11 @@ py_binary( srcs = [":dircon_trajectory_plotter.py"], deps = [ ":lcm_trajectory_py", + ":lcm_py", ":module_py", "//bindings/pydairlib/common", "//bindings/pydairlib/multibody:multibody_py", + "//bindings/pydairlib/cassie:cassie_utils_py", "//lcmtypes:lcmtypes_robot_py", ], ) diff --git a/bindings/pydairlib/lcm/__init__.py b/bindings/pydairlib/lcm/__init__.py index 718b93b986..d4f98f5d31 100644 --- a/bindings/pydairlib/lcm/__init__.py +++ b/bindings/pydairlib/lcm/__init__.py @@ -1,2 +1,2 @@ from .lcm_trajectory import * -from .lcm_py import * \ No newline at end of file +from .lcm_py import * diff --git a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py index fd1101bb5e..d70951ce65 100644 --- a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py @@ -5,15 +5,28 @@ from pydrake.trajectories import PiecewisePolynomial import numpy as np +from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph) +from pydairlib.cassie.cassie_utils import AddCassieMultibody def main(): + + builder = DiagramBuilder() + plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) + AddCassieMultibody(plant, scene_graph, + True, "examples/Cassie/urdf/cassie_v2.urdf", True, True) + + plant.Finalize() # Default filename for the example # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/walking_0.16.0") - filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/jumping_0.15h_0.3d") + # filename = FindResourceOrThrow("e?xamples/Cassie/saved_trajectories/jumping_0.15h_0.3d") + filename = FindResourceOrThrow( + "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_5") + # filename = FindResourceOrThrow( + # "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1") # filename = "/home/yangwill/Documents/research/projects/cassie/hardware/backup/dair/saved_trajectories/jumping_0.15h_0.3d" # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/" + sys.argv[1]) - dircon_traj = lcm_trajectory.DirconTrajectory(filename) + dircon_traj = lcm_trajectory.DirconTrajectory(plant, filename) # Reconstructing state and input trajectory as piecewise polynomials state_traj = dircon_traj.ReconstructStateTrajectory() @@ -27,7 +40,6 @@ def main(): force_datatypes = dircon_traj.GetTrajectory("force_vars1").datatypes collocation_force_points = dircon_traj.GetCollocationForceSamples(0) - import pdb; pdb.set_trace() # M = reflected_joints() # # mirror_traj = lcm_trajectory.Trajectory() diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index df22d765af..d0e9e2b186 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -87,6 +87,7 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant &plant, initial_hip_pos_idx_ = this->DeclareDiscreteState(3); pelvis_yaw_idx_ = this->DeclareDiscreteState(1); pelvis_vel_est_idx_ = this->DeclareDiscreteState(3); + last_stance_timestamp_idx_ = this->DeclareDiscreteState(1); // State variables inside this controller block DeclarePerStepDiscreteUpdateEvent(&FootTrajGenerator::DiscreteVariableUpdate); @@ -135,6 +136,9 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) .get_mutable_value(); pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; + auto last_stance_time = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) + .get_mutable_value(); + last_stance_time[0] = robot_output->get_timestamp(); // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; // pelvis_vel = Vector3d::Zero(); @@ -220,18 +224,37 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // Storing old method for record keeping T_waypoints = {state_durations_[1], state_durations_[1] + - 1.5 / 3.0 * (state_durations_[4] - state_durations_[1]), + 0.5 * (state_durations_[4] - state_durations_[1]), state_durations_[4]}; - T_waypoints_0 = { - state_durations_[0], - (state_durations_[3] - state_durations_[4]) + - 1.5 / 3.0 * (0.1 + state_durations_[2] - state_durations_[0]), - state_durations_[2]}; - T_waypoints_1 = {state_durations_[2], state_durations_[3]}; - T_waypoints_2 = {state_durations_[3], state_durations_[4]}; - -// T_waypoints = {left_t0, left_t0 + 0.5 * (left_tf - left_t0), left_tf}; + // T_waypoints_0 = { +// state_durations_[0], +// (state_durations_[3] - state_durations_[4]) + +// 0.5 * (0.1 + state_durations_[2] - state_durations_[0]), +// state_durations_[2]}; +// T_waypoints_1 = {state_durations_[2], state_durations_[3]}; +// T_waypoints_2 = {state_durations_[3], state_durations_[4]}; +// +// + + + if( is_left_foot_){ +// std::cout << "is left foot: " << is_left_foot_ << std::endl; + T_waypoints = {left_t0, left_t0 + 0.6 * (left_tf - left_t0), left_tf}; +// std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; +// std::cout << left_t0 << std::endl; +// std::cout << left_t0 + 0.6 * (left_tf - left_t0) << std::endl; +// std::cout << left_tf << std::endl; + } + else{ +// std::cout << "is left foot: " << is_left_foot_ << std::endl; + T_waypoints = {right_t0, right_t0 + 0.6 * (right_tf - right_t0), right_tf}; +// std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; +// std::cout << right_t0 << std::endl; +// std::cout << right_t0 + 0.6 * (right_tf - right_t0) << std::endl; +// std::cout << right_tf << std::endl; + } + // T_waypoints_0 = { // pelvis_t0, // (state_durations_[3] - state_durations_[4]) + // 1.5 / 3.0 * (0.1 + state_durations_[2] - pelvis_t0), @@ -274,6 +297,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, false); + return swing_foot_spline; + if (is_left_foot_) { return swing_foot_spline; diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index fc617e51dd..783fdee6a6 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -90,6 +90,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { int initial_hip_pos_idx_; int pelvis_yaw_idx_; int pelvis_vel_est_idx_; + int last_stance_timestamp_idx_; }; } // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 1b0221e382..3ca9265a05 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -2,8 +2,8 @@ w_input: 0.0001 w_input_reg: 0.1 w_accel: 0.0001 w_soft_constraint: 100 -impact_threshold: 0.025 -impact_tau: 0.025 +impact_threshold: 0.05 +impact_tau: 0.05 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, @@ -42,35 +42,35 @@ hip_yaw_kp: 40 hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.1 -footstep_lateral_offset: 0.03 # drake +footstep_sagital_offset: -0.08 +footstep_lateral_offset: 0.02 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.3, 0, 0, + [ 0.15, 0, 0, 0, 0.7, 0, 0, 0, 0 ] PelvisW: - [ 0, 0, 0, - 0, 0, 0, + [ 1, 0, 0, + 0, 1, 0, 0, 0, 5 ] PelvisKp: - [ 0, 0, 0, - 0, 0, 0, + [ -50, 0, 0, + 0, -50, 0, 0, 0, 105] PelvisKd: - [ 0, 0, 0, - 0, 0, 0, - 0, 0, 4.5 ] + [ 2, 0, 0, + 0, 2, 0, + 0, 0, 4 ] PelvisRotW: - [ 1, 0, 0, + [ 10, 0, 0, 0, 10, 0, 0, 0, 1 ] PelvisRotKp: - [20., 0, 0, + [30., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [5., 0, 0, + [10., 0, 0, 0, 5., 0, 0, 0, 3.] SwingFootW: @@ -79,18 +79,18 @@ SwingFootW: 0, 0, 5 ] SwingFootKp: [ 50, 0, 0, - 0, 50, 0, + 0, 100, 0, 0, 0, 50 ] SwingFootKd: [ 5., 0, 0, - 0, 5., 0, + 0, 10., 0, 0, 0, 1. ] LiftoffSwingFootW: [1, 0, 0, 0, 1, 0, 0, 0, 1] LiftoffSwingFootKp: - [50, 0, 0, + [25, 0, 0, 0, 50, 0, 0, 0, 35] LiftoffSwingFootKd: diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index b446b78ecf..cb7e1e289c 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 100 +max_iter: 200 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 00e75aa268..a63cc53c91 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -94,30 +94,30 @@ DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); namespace dairlib { -HybridDircon* createDircon(MultibodyPlant& plant); - -void SetKinematicConstraints(Dircon* trajopt, - const MultibodyPlant& plant); -void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, - DirconModeSequence*); -void AddCostsSprings(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence*); +HybridDircon *createDircon(MultibodyPlant &plant); + +void SetKinematicConstraints(Dircon *trajopt, + const MultibodyPlant &plant); +void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, + DirconModeSequence *); +void AddCostsSprings(Dircon *trajopt, + const MultibodyPlant &plant, + DirconModeSequence *); void SetInitialGuessFromTrajectory( - Dircon& trajopt, const MultibodyPlant& plant, - const string& filepath, bool same_knot_points = false, + Dircon &trajopt, const MultibodyPlant &plant, + const string &filepath, bool same_knot_points = false, Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); class JointAccelCost : public solvers::NonlinearCost { public: - JointAccelCost(const MatrixXd& W_Q, - const drake::multibody::MultibodyPlant& plant, - const KinematicEvaluatorSet* constraints, - const std::string& description = "") + JointAccelCost(const MatrixXd &W_Q, + const drake::multibody::MultibodyPlant &plant, + const KinematicEvaluatorSet *constraints, + const std::string &description = "") : solvers::NonlinearCost( - plant.num_positions() + plant.num_velocities() + - plant.num_actuators() + constraints->count_full(), - description), + plant.num_positions() + plant.num_velocities() + + plant.num_actuators() + constraints->count_full(), + description), plant_(plant), context_(plant_.CreateDefaultContext()), constraints_(constraints), @@ -125,11 +125,11 @@ class JointAccelCost : public solvers::NonlinearCost { n_x_(plant.num_positions() + plant.num_velocities()), n_u_(plant.num_actuators()), n_lambda_(constraints->count_full()), - W_Q_(W_Q){}; + W_Q_(W_Q) {}; private: - void EvaluateCost(const Eigen::Ref>& x, - drake::VectorX* y) const override { + void EvaluateCost(const Eigen::Ref> &x, + drake::VectorX *y) const override { DRAKE_ASSERT(x.size() == n_x_ + n_u_ + n_lambda_); // Extract our input variables: @@ -144,9 +144,9 @@ class JointAccelCost : public solvers::NonlinearCost { (*y) = xdot0.tail(n_v_).transpose() * W_Q_ * xdot0.tail(n_v_); }; - const drake::multibody::MultibodyPlant& plant_; + const drake::multibody::MultibodyPlant &plant_; std::unique_ptr> context_; - const KinematicEvaluatorSet* constraints_; + const KinematicEvaluatorSet *constraints_; int n_v_; int n_x_; @@ -159,7 +159,7 @@ class JointAccelCost : public solvers::NonlinearCost { void DoMain() { // Drake system initialization stuff drake::systems::DiagramBuilder builder; - SceneGraph& scene_graph = *builder.AddSystem(); + SceneGraph &scene_graph = *builder.AddSystem(); scene_graph.set_name("scene_graph"); MultibodyPlant plant(0.0); MultibodyPlant plant_vis(0.0); @@ -297,7 +297,7 @@ void DoMain() { all_modes.AddMode(&land_mode); auto trajopt = Dircon(all_modes); - auto& prog = trajopt.prog(); + auto &prog = trajopt.prog(); double tol = FLAGS_tol; if (FLAGS_ipopt) { @@ -347,6 +347,7 @@ void DoMain() { std::cout << "Adding kinematic constraints: " << std::endl; SetKinematicConstraints(&trajopt, plant); + std::cout << "Adding costs: " << std::endl; if (FLAGS_use_springs) { AddCostsSprings(&trajopt, plant, &all_modes); } else { @@ -372,7 +373,7 @@ void DoMain() { double alpha = .2; // int num_poses = std::min(FLAGS_knot_points + 1, 3); - int num_poses = std::max((int)(mode_lengths.size() + 1), FLAGS_knot_points); + int num_poses = std::max((int) (mode_lengths.size() + 1), FLAGS_knot_points); // int num_poses = mode_lengths.size() * FLAGS_knot_points - 1; trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); @@ -410,9 +411,9 @@ void DoMain() { } } -void SetKinematicConstraints(Dircon* trajopt, - const MultibodyPlant& plant) { - auto* prog = &trajopt->prog(); +void SetKinematicConstraints(Dircon *trajopt, + const MultibodyPlant &plant) { + auto *prog = &trajopt->prog(); // Create maps for joints map pos_map = multibody::MakeNameToPositionsMap(plant); map vel_map = multibody::MakeNameToVelocitiesMap(plant); @@ -470,20 +471,24 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_right"))); prog->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_left"))); prog->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_right"))); + trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_left"))); + trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_right"))); + trajopt->AddConstraintToAllKnotPoints(-1.1 >= x(pos_map.at("knee_left"))); + trajopt->AddConstraintToAllKnotPoints(-1.1 >= x(pos_map.at("knee_right"))); // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); - if (FLAGS_height < 0) { - prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, - 0.5 * FLAGS_height + rest_height - eps, - x_top(pos_map.at("base_z"))); - - } else { - prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, - FLAGS_height + rest_height + eps, - x_top(pos_map.at("base_z"))); - } +// if (FLAGS_height < 0) { +// prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, +// 0.5 * FLAGS_height + rest_height - eps, +// x_top(pos_map.at("base_z"))); +// +// } else { +// prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, +// FLAGS_height + rest_height + eps, +// x_top(pos_map.at("base_z"))); +// } prog->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, 0.8 * FLAGS_height + rest_height + eps, x_f(pos_map.at("base_z"))); @@ -508,19 +513,19 @@ void SetKinematicConstraints(Dircon* trajopt, vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& asy_joint_name : asy_joint_names) { + for (const auto &l_r_pair: l_r_pairs) { + for (const auto &asy_joint_name: asy_joint_names) { joint_names.push_back(asy_joint_name + l_r_pair.first); motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); } - for (const auto& sym_joint_name : sym_joint_names) { + for (const auto &sym_joint_name: sym_joint_names) { joint_names.push_back(sym_joint_name + l_r_pair.first); if (sym_joint_name != "ankle_joint") { motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); } } if (FLAGS_use_springs) { - for (const auto& spring_joint_name : spring_joint_names) { + for (const auto &spring_joint_name: spring_joint_names) { joint_names.push_back(spring_joint_name + l_r_pair.first); } } @@ -528,15 +533,15 @@ void SetKinematicConstraints(Dircon* trajopt, l_r_pairs.pop_back(); // Symmetry constraints - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& sym_joint_name : sym_joint_names) { + for (const auto &l_r_pair: l_r_pairs) { + for (const auto &sym_joint_name: sym_joint_names) { // trajopt->AddConstraintToAllKnotPoints( // x_0(pos_map[sym_joint_name + l_r_pair.first]) == // x_0(pos_map[sym_joint_name + l_r_pair.second])); - prog->AddLinearConstraint(x_0(pos_map[sym_joint_name + l_r_pair.first]) == - x_0(pos_map[sym_joint_name + l_r_pair.second])); - prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + l_r_pair.first]) == - x_f(pos_map[sym_joint_name + l_r_pair.second])); +// prog->AddLinearConstraint(x_0(pos_map[sym_joint_name + l_r_pair.first]) == +// x_0(pos_map[sym_joint_name + l_r_pair.second])); +// prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + l_r_pair.first]) == +// x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle // trajopt->AddConstraintToAllKnotPoints( // u_0(act_map.at(sym_joint_name + l_r_pair.first + @@ -552,16 +557,14 @@ void SetKinematicConstraints(Dircon* trajopt, // joint limits std::cout << "Joint limit constraints: " << std::endl; - - for (const auto& member : joint_names) { + for (const auto &member: joint_names) { trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) <= - plant.GetJointByName(member).position_upper_limits()(0)); + 0.9 * plant.GetJointByName(member).position_upper_limits()(0)); trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) >= - plant.GetJointByName(member).position_lower_limits()(0)); + 0.9 * plant.GetJointByName(member).position_lower_limits()(0)); } - // actuator limits std::cout << "Actuator limit constraints: " << std::endl; VectorXd u_min(n_u); @@ -575,6 +578,11 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), // VectorXd::Constant(n_u, +175), ui); prog->AddBoundingBoxConstraint(u_min, u_max, ui); + if (i < trajopt->N() - 1) { + auto uip1 = trajopt->input(i + 1); + prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); + prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); + } } Vector3d pt_front_contact(-0.0457, 0.112, 0); @@ -599,7 +607,7 @@ void SetKinematicConstraints(Dircon* trajopt, plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); - for (int mode : {0, 1, 2}) { + for (int mode: {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); @@ -656,13 +664,13 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_z_box_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), - (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); + (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), + (0.1 + FLAGS_height + eps) * VectorXd::Ones(1)); auto right_foot_z_box_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (1.25 * FLAGS_height - eps) * VectorXd::Ones(1), - (1.25 * FLAGS_height + eps) * VectorXd::Ones(1)); + (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), + (0.1 + FLAGS_height + eps) * VectorXd::Ones(1)); prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); @@ -724,8 +732,8 @@ void SetKinematicConstraints(Dircon* trajopt, /****** COSTS ******/ -void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, - DirconModeSequence* constraints) { +void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, + DirconModeSequence *constraints) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -749,12 +757,12 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& asy_joint_name : asy_joint_names) { + for (const auto &l_r_pair: l_r_pairs) { + for (const auto &asy_joint_name: asy_joint_names) { joint_names.push_back(asy_joint_name + l_r_pair.first); motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); } - for (const auto& sym_joint_name : sym_joint_names) { + for (const auto &sym_joint_name: sym_joint_names) { joint_names.push_back(sym_joint_name + l_r_pair.first); if (sym_joint_name != "ankle_joint") { motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); @@ -803,8 +811,8 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, // } // } - // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); - MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); + MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); +// MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = // 5e-1; @@ -833,56 +841,54 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, q_f(pos_map.at("hip_yaw_right")) = 0; q_f(pos_map.at("hip_roll_left")) = 0; q_f(pos_map.at("hip_roll_right")) = 0; - std::cout << pos_map.at("hip_yaw_left") << std::endl; - std::cout << pos_map.at("hip_yaw_right") << std::endl; - std::cout << pos_map.at("hip_roll_left") << std::endl; - std::cout << pos_map.at("hip_roll_right") << std::endl; + q_f(pos_map.at("hip_pitch_left")) = 0.67; + q_f(pos_map.at("hip_pitch_right")) = 0.67; q_f(pos_map.at("base_z")) = 0.8 * FLAGS_height + FLAGS_start_height; - VectorXd q_f_target_left = q_f.segment(4, 5); - VectorXd q_f_target_right = q_f.segment(13, 2); + VectorXd q_f_target_left = q_f.segment(6, 4); + VectorXd q_f_target_right = q_f.segment(13, 3); - MatrixXd Q_left = 0.02 * MatrixXd::Identity(5, 5); - MatrixXd Q_right = 0.02 * MatrixXd::Identity(2, 2); + MatrixXd Q_left = 1e1 * MatrixXd::Identity(4, 4); + MatrixXd Q_right = 1e1 * MatrixXd::Identity(3, 3); Q_left *= FLAGS_cost_scaling; Q_right *= FLAGS_cost_scaling; - // trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); -// trajopt->AddRunningCost((x.segment(4, 5) - q_f_target_left).transpose() * -// Q_left * (x.segment(4, 5) - q_f_target_left)); -// trajopt->AddRunningCost((x.segment(13, 2) - q_f_target_right).transpose() * -// Q_right * (x.segment(13, 2) - q_f_target_right)); -// trajopt->AddRunningCost(u.transpose() * R * u); -// -// vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, -// FLAGS_knot_points}; -// MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); -// W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; -// W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; -// W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; -// W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; -// W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; -// W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; -// W *= 2.0 * FLAGS_cost_scaling; -// vector> joint_accel_costs; -// for (int mode : {0, 1, 2}) { -// joint_accel_costs.push_back(std::make_shared( -// W, plant, &constraints->mode(mode).evaluators())); -// for (int index = 0; index < mode_lengths[mode]; index++) { -// // Assumes mode_lengths are the same across modes -// auto x_i = trajopt->state_vars(mode, index); -// auto u_i = trajopt->input_vars(mode, index); -// auto l_i = trajopt->force_vars(mode, index); -// trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); -// } -// } + trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); + trajopt->AddRunningCost((x.segment(6, 4) - q_f_target_left).transpose() * + Q_left * (x.segment(6, 4) - q_f_target_left)); + trajopt->AddRunningCost((x.segment(13, 3) - q_f_target_right).transpose() * + Q_right * (x.segment(13, 3) - q_f_target_right)); + trajopt->AddRunningCost(u.transpose() * R * u); + + vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, + FLAGS_knot_points}; + MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; + W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; + W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; + W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + W *= 2.0 * FLAGS_cost_scaling; + vector> joint_accel_costs; + for (int mode: {0, 1, 2}) { + joint_accel_costs.push_back(std::make_shared( + W, plant, &constraints->mode(mode).evaluators())); + for (int index = 0; index < mode_lengths[mode]; index++) { + // Assumes mode_lengths are the same across modes + auto x_i = trajopt->state_vars(mode, index); + auto u_i = trajopt->input_vars(mode, index); + auto l_i = trajopt->force_vars(mode, index); + trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + } + } } /****** COSTS ******/ -void AddCostsSprings(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence* constraints) { +void AddCostsSprings(Dircon *trajopt, + const MultibodyPlant &plant, + DirconModeSequence *constraints) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -905,12 +911,12 @@ void AddCostsSprings(Dircon* trajopt, vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& asy_joint_name : asy_joint_names) { + for (const auto &l_r_pair: l_r_pairs) { + for (const auto &asy_joint_name: asy_joint_names) { joint_names.push_back(asy_joint_name + l_r_pair.first); motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); } - for (const auto& sym_joint_name : sym_joint_names) { + for (const auto &sym_joint_name: sym_joint_names) { joint_names.push_back(sym_joint_name + l_r_pair.first); if (sym_joint_name != "ankle_joint") { motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); @@ -921,12 +927,12 @@ void AddCostsSprings(Dircon* trajopt, double w_symmetry_pos = 1e3; double w_symmetry_vel = 1e1; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& sym_joint_name : sym_joint_names) { + for (const auto &l_r_pair: l_r_pairs) { + for (const auto &sym_joint_name: sym_joint_names) { auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - - x(pos_map[sym_joint_name + l_r_pair.second]); + x(pos_map[sym_joint_name + l_r_pair.second]); auto vel_diff = x(vel_map[sym_joint_name + l_r_pair.first + "dot"]) - - x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); + x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); } @@ -957,7 +963,7 @@ void AddCostsSprings(Dircon* trajopt, vel_map["ankle_spring_joint_rightdot"]) = 0.0; W *= FLAGS_cost_scaling; vector> joint_accel_costs; - for (int mode : {0, 1, 2}) { + for (int mode: {0, 1, 2}) { joint_accel_costs.push_back(std::make_shared( W, plant, &constraints->mode(mode).evaluators())); for (int index = 0; index < mode_lengths[mode]; index++) { @@ -970,9 +976,9 @@ void AddCostsSprings(Dircon* trajopt, } } -void SetInitialGuessFromTrajectory(Dircon& trajopt, - const MultibodyPlant& plant, - const string& filepath, +void SetInitialGuessFromTrajectory(Dircon &trajopt, + const MultibodyPlant &plant, + const string &filepath, bool same_knot_points, Eigen::MatrixXd spr_map) { DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); @@ -1003,7 +1009,7 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, } // namespace dairlib -int main(int argc, char* argv[]) { +int main(int argc, char *argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); dairlib::DoMain(); } diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 95197b4f28..f32de7e3a8 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -50,6 +50,7 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( DRAKE_DEMAND(states.size() == state_durations.size()); impact_times_.push_back(0); impact_states_.push_back(states[0]); + accu_state_durations_.push_back(0); for (int i = 0; i < states.size(); ++i) { sum += state_durations[i]; accu_state_durations_.push_back(sum); @@ -116,7 +117,8 @@ void ImpactTimeBasedFiniteStateMachine::CalcClock( auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); - clock->get_mutable_value()(0) = remainder; +// clock->get_mutable_value()(0) = remainder; + clock->get_mutable_value()(0) = current_time; } void ImpactTimeBasedFiniteStateMachine::CalcContactScheduler( @@ -130,26 +132,23 @@ void ImpactTimeBasedFiniteStateMachine::CalcContactScheduler( } auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); + int n_periods = (int) (current_time / period_); for (unsigned int i = 0; i < accu_state_durations_.size(); i++) { - if (remainder < accu_state_durations_[i]) { - if (i == 0) { - contact_timing->get_mutable_value()(0) = 0; - contact_timing->get_mutable_value()(1) = accu_state_durations_[i]; - contact_timing->get_mutable_value()(2) = 0; - contact_timing->get_mutable_value()(3) = accu_state_durations_[i]; - contact_timing->get_mutable_value()(4) = 0; - contact_timing->get_mutable_value()(5) = accu_state_durations_[i]; - } else { - contact_timing->get_mutable_value()(0) = accu_state_durations_[i - 1]; - contact_timing->get_mutable_value()(1) = accu_state_durations_[i]; - contact_timing->get_mutable_value()(2) = accu_state_durations_[i - 1]; - contact_timing->get_mutable_value()(3) = accu_state_durations_[i]; - contact_timing->get_mutable_value()(4) = accu_state_durations_[i - 1]; - contact_timing->get_mutable_value()(5) = accu_state_durations_[i]; - } - break; - } + contact_timing->get_mutable_value()(0) = + n_periods * period_ + accu_state_durations_[i]; + contact_timing->get_mutable_value()(1) = + n_periods * period_ + accu_state_durations_[i]; + contact_timing->get_mutable_value()(2) = + n_periods * period_ + accu_state_durations_[1]; + contact_timing->get_mutable_value()(3) = + n_periods * period_ + accu_state_durations_[4]; + contact_timing->get_mutable_value()(4) = + (n_periods - 1) * period_ + accu_state_durations_[3]; + contact_timing->get_mutable_value()(5) = + (n_periods - 1) * period_ + accu_state_durations_[3] + + (accu_state_durations_[2] - accu_state_durations_[0]) + + (accu_state_durations_[4] - accu_state_durations_[3]); } } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 71ec73e31d..aed452f150 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -472,16 +472,16 @@ void OperationalSpaceControl::Build() { /// hard constraint version // prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); // } -// blend_constraint_ = -// prog_ -// ->AddBoundingBoxConstraint( -// VectorXd::Zero(4), VectorXd::Zero(4), -// {lambda_c_.segment(kSpaceDim * 0 + 2, 1), -// lambda_c_.segment(kSpaceDim * 1 + 2, 1), -// lambda_c_.segment(kSpaceDim * 2 + 2, 1), -// lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) -// .evaluator() -// .get(); + blend_constraint_ = + prog_ + ->AddBoundingBoxConstraint( + VectorXd::Zero(4), VectorXd::Zero(4), + {lambda_c_.segment(kSpaceDim * 0 + 2, 1), + lambda_c_.segment(kSpaceDim * 1 + 2, 1), + lambda_c_.segment(kSpaceDim * 2 + 2, 1), + lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) + .evaluator() + .get(); for (int i = -1; i < 5; ++i) { solvers_[i] = std::make_unique(); @@ -764,12 +764,12 @@ VectorXd OperationalSpaceControl::SolveQp( // A(0, 6) = 1; // A(0, 7) = 1; // } -// VectorXd normals = VectorXd(4); -// normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), -// lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), -// lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), -// lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); -// blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 15 * VectorXd::Ones(4), normals + 15 * VectorXd::Ones(4)); + VectorXd normals = VectorXd(4); + normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), + lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), + lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), + lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); + blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 25 * VectorXd::Ones(4), normals + 25 * VectorXd::Ones(4)); // } // test joint-level input cost by fsm state @@ -788,8 +788,6 @@ VectorXd OperationalSpaceControl::SolveQp( input_smoothing_cost_->UpdateCoefficients( W_input_smoothing_, -W_input_smoothing_ * *u_prev_); } -// input_smoothing_constraint_->UpdateCoefficients( -// MatrixXd::Identity(n_u_, n_u_), *u_prev_ - 1 * u_max_, *u_prev_ + 1 * u_max_); if (W_lambda_c_reg_.size() > 0) { lambda_c_smoothing_cost_->UpdateCoefficients(1000 * alpha * W_lambda_c_reg_, @@ -1155,27 +1153,6 @@ void OperationalSpaceControl::CalcOptimalInput( alpha = impact_info->GetAlpha(); next_fsm_state = impact_info->GetCurrentContactMode(); } - -// if (fsm_state(0) == 0) { -// x_wo_spr[19] = 0; -// x_wo_spr[21] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } else if (fsm_state(0) == 1) { -// x_wo_spr[11] = 0; -// x_wo_spr[13] = 0; -// x_wo_spr[33] = 0; -// x_wo_spr[41] = 0; -// } - // else { - // x_wo_spr[11] = 0; - // x_wo_spr[13] = 0; - // x_wo_spr[19] = 0; - // x_wo_spr[21] = 0; - // x_wo_spr[33] = 0; - // x_wo_spr[41] = 0; - // } - // Get discrete states const auto prev_event_time = context.get_discrete_state(prev_event_time_idx_).get_value(); From 645b9072b8a75bdeb6e1d3ba6b1472d5bc0ca330 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 4 Aug 2022 10:01:40 -0400 Subject: [PATCH 259/758] updating fsms to use variable timing --- .../contact_scheduler/contact_scheduler.cc | 72 +++++++++++++------ .../contact_scheduler/contact_scheduler.h | 20 +++--- systems/controllers/time_based_fsm.h | 4 +- 3 files changed, 66 insertions(+), 30 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 589812ef03..13c3e3eb5e 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -16,20 +16,22 @@ using systems::ImpactInfoVector; using systems::OutputVector; ContactScheduler::ContactScheduler( - const drake::multibody::MultibodyPlant& plant, + const drake::multibody::MultibodyPlant &plant, double near_impact_threshold, double tau, BLEND_FUNC blend_func) - :near_impact_threshold_(near_impact_threshold), + : near_impact_threshold_(near_impact_threshold), blend_func_(blend_func) { impact_info_port_ = this->DeclareVectorOutputPort( - "near_impact", ImpactInfoVector(0, 0, 0), - &ContactScheduler::CalcNextImpactInfo) - .get_index(); + "near_impact", ImpactInfoVector(0, 0, 0), + &ContactScheduler::CalcNextImpactInfo) + .get_index(); clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), &ContactScheduler::CalcClock) - .get_index(); - clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), - &ContactScheduler::CalcClock) - .get_index(); + .get_index(); + contact_scheduler_port_ = this->DeclareVectorOutputPort("contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, right_t0, right_t0", + BasicVector(6), + &ContactScheduler::CalcContactScheduler) + .get_index(); + } double alpha_sigmoid(double t, double tau, double near_impact_threshold) { @@ -42,11 +44,11 @@ double alpha_exp(double t, double tau, double near_impact_threshold) { } void ContactScheduler::CalcNextImpactInfo( - const Context& context, - ImpactInfoVector* near_impact) const { + const Context &context, + ImpactInfoVector *near_impact) const { // Read in lcm message time - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); @@ -61,8 +63,8 @@ void ContactScheduler::CalcNextImpactInfo( if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { double blend_window = blend_func_ == SIGMOID - ? 1.5 * near_impact_threshold_ - : near_impact_threshold_; + ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; if (abs(remainder - impact_times_[i]) < blend_window) { if (remainder < impact_times_[i]) { near_impact->SetAlpha(alpha_func(remainder - impact_times_[i], tau_, @@ -78,15 +80,45 @@ void ContactScheduler::CalcNextImpactInfo( } } -void ContactScheduler::CalcClock(const Context& context, - BasicVector* clock) const { +void ContactScheduler::CalcClock( + const Context &context, BasicVector *clock) const { // Read in lcm message time - const OutputVector* robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); + clock->get_mutable_value()(0) = current_time; +} + +void ContactScheduler::CalcContactScheduler( + const Context &context, BasicVector *contact_timing) const { + // Read in lcm message time + const OutputVector *robot_output = + (OutputVector *) this->EvalVectorInput(context, state_port_); +// if (this->get_input_port(radio_port_).HasValue(context)) { +// const auto &radio_out = +// this->EvalInputValue(context, radio_port_); +// } + auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); - clock->get_mutable_value()(0) = remainder; + int n_periods = (int) (current_time / period_); + + for (unsigned int i = 0; i < accu_state_durations_.size(); i++) { + contact_timing->get_mutable_value()(0) = + n_periods * period_ + accu_state_durations_[i]; + contact_timing->get_mutable_value()(1) = + n_periods * period_ + accu_state_durations_[i]; + contact_timing->get_mutable_value()(2) = + n_periods * period_ + accu_state_durations_[1]; + contact_timing->get_mutable_value()(3) = + n_periods * period_ + accu_state_durations_[4]; + contact_timing->get_mutable_value()(4) = + (n_periods - 1) * period_ + accu_state_durations_[3]; + contact_timing->get_mutable_value()(5) = + (n_periods - 1) * period_ + accu_state_durations_[3] + + (accu_state_durations_[2] - accu_state_durations_[0]) + + (accu_state_durations_[4] - accu_state_durations_[3]); + } } } // namespace dairlib diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 28065498b6..beb36d9768 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -27,24 +27,28 @@ class ContactScheduler : drake::systems::LeafSystem { const drake::systems::OutputPort& get_output_port_clock() const { return this->get_output_port(clock_port_); } - const drake::systems::OutputPort& get_output_port_contact_timing() const { - return this->get_output_port(contact_timing_); - } const drake::systems::OutputPort& get_output_port_impact() const { return this->get_output_port(impact_info_port_); } + const drake::systems::OutputPort& get_output_port_contact_scheduler() const { + return this->get_output_port(contact_scheduler_port_); + } private: void CalcNextImpactInfo(const drake::systems::Context& context, systems::ImpactInfoVector* near_impact) const; void CalcClock(const drake::systems::Context& context, drake::systems::BasicVector* clock) const; + void CalcContactScheduler(const drake::systems::Context& context, + drake::systems::BasicVector *clock) const; + + drake::systems::InputPortIndex state_port_; + drake::systems::OutputPortIndex fsm_port_; + drake::systems::OutputPortIndex clock_port_; +// drake::systems::OutputPortIndex contact_timing_; + drake::systems::OutputPortIndex impact_info_port_; + drake::systems::OutputPortIndex contact_scheduler_port_; - int state_port_; - int fsm_port_; - int clock_port_; - int contact_timing_; - int impact_info_port_; // const drake::multibody::MultibodyPlant& plant_; diff --git a/systems/controllers/time_based_fsm.h b/systems/controllers/time_based_fsm.h index e7da411315..cec1e1685d 100644 --- a/systems/controllers/time_based_fsm.h +++ b/systems/controllers/time_based_fsm.h @@ -50,8 +50,8 @@ class TimeBasedFiniteStateMachine : public drake::systems::LeafSystem { } protected: - int state_port_; - int fsm_port_; + drake::systems::InputPortIndex state_port_; + drake::systems::OutputPortIndex fsm_port_; private: void CalcFiniteState(const drake::systems::Context& context, From ec13036c92b06125ea33cdbd2c1042f97744a417 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 5 Aug 2022 17:05:49 -0400 Subject: [PATCH 260/758] adding contact scheduler for running --- .../pydairlib/analysis/log_plotter_cassie.py | 3 +- .../plot_configs/cassie_jumping_plot.yaml | 6 +- .../plot_configs/cassie_running_plot.yaml | 2 +- .../lcm/dircon_trajectory_plotter.py | 21 +- common/BUILD.bazel | 14 + common/blending_utils.cc | 11 + common/blending_utils.h | 7 + examples/Cassie/BUILD.bazel | 1 + examples/Cassie/contact_scheduler/BUILD.bazel | 10 + .../contact_scheduler/contact_scheduler.cc | 264 +++++++++++++----- .../contact_scheduler/contact_scheduler.h | 82 ++++-- .../osc_jump/jumping_event_based_fsm.cc | 8 +- .../Cassie/osc_jump/jumping_event_based_fsm.h | 6 +- .../osc_jump/pelvis_trans_traj_generator.cc | 2 +- .../osc_jump/pelvis_trans_traj_generator.h | 2 +- examples/Cassie/run_dircon_jumping.cc | 179 ++++++------ examples/Cassie/run_osc_jumping_controller.cc | 6 +- examples/Cassie/run_osc_running_controller.cc | 96 +++---- examples/impact_invariant_control/BUILD.bazel | 1 + .../impact_aware_time_based_fsm.cc | 12 +- .../impact_aware_time_based_fsm.h | 4 +- 21 files changed, 484 insertions(+), 253 deletions(-) create mode 100644 common/blending_utils.cc create mode 100644 common/blending_utils.h diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 6cff926648..fe837f4436 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -14,8 +14,7 @@ def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' - # config_file = \ - # 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 532bc1a22f..9a9c4a3b4d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_JUMPING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 20 -duration: 5 +start_time: 15 +duration: -1 # Plant properties use_springs: true @@ -43,7 +43,7 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel'] }, + pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index aa8ff719e8..3a8509de38 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -21,7 +21,7 @@ plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true -plot_contact_forces: false +plot_contact_forces: true special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [ ] diff --git a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py index d70951ce65..8b2dae5dd5 100644 --- a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py @@ -13,14 +13,14 @@ def main(): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) AddCassieMultibody(plant, scene_graph, - True, "examples/Cassie/urdf/cassie_v2.urdf", True, True) + True, "examples/Cassie/urdf/cassie_fixed_springs.urdf", False, True) plant.Finalize() # Default filename for the example # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/walking_0.16.0") - # filename = FindResourceOrThrow("e?xamples/Cassie/saved_trajectories/jumping_0.15h_0.3d") + # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/jumping_0.15h_0.3d") filename = FindResourceOrThrow( - "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_5") + "examples/Cassie/saved_trajectories/jumping_0.0h_1.0d_0") # filename = FindResourceOrThrow( # "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1") # filename = "/home/yangwill/Documents/research/projects/cassie/hardware/backup/dair/saved_trajectories/jumping_0.15h_0.3d" @@ -54,23 +54,34 @@ def main(): n_points = 500 t = np.linspace(state_traj.start_time(), state_traj.end_time(), n_points) state_samples = np.zeros((n_points, state_traj.value(0).shape[0])) + state_derivative_samples = np.zeros((n_points, state_traj.value(0).shape[0])) input_samples = np.zeros((n_points, input_traj.value(0).shape[0])) # force_samples = np.zeros((n_points, force_traj[0].value(0).shape[0])) for i in range(n_points): state_samples[i] = state_traj.value(t[i])[:, 0] + state_derivative_samples[i] = state_traj.EvalDerivative(t[i], 1)[:, 0] input_samples[i] = input_traj.value(t[i])[:, 0] # force_samples[i] = force_traj[0].value(t[i])[:, 0] # reflected_state_samples = state_samples @ M # Plotting reconstructed state trajectories plt.figure("state trajectory") - plt.plot(t, state_samples[:, 0:7]) + plt.plot(t, state_samples[:, 4:7]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 0:7]) # plt.plot(t, state_samples[:, -18:]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 7:13]) # plt.plot(t, state_samples[:, 25:31]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 25:31]) - plt.legend(state_datatypes[0:7]) + plt.legend(state_datatypes[4:7]) + + # Velocity Error + # plt.figure('velocity_error') + # import pdb; pdb.set_trace() + # plt.plot(t, (state_samples[:, (19 + 3):] - state_derivative_samples[:, 4:19])) + # plt.plot(t, (state_samples[:, -2:] - state_derivative_samples[:, 21:23])) + # plt.legend(state_datatypes[26:]) + # plt.plot(t, state_samples[:, (23 + 3):]) + plt.figure("input trajectory") plt.plot(t, input_samples[:, :]) diff --git a/common/BUILD.bazel b/common/BUILD.bazel index 3484c7d376..f6b0a826fe 100644 --- a/common/BUILD.bazel +++ b/common/BUILD.bazel @@ -6,6 +6,7 @@ cc_library( ":find_resource", ":eigen_utils", ":file_utils", + ":blending_utils", "@drake//:drake_shared_library", ], ) @@ -46,3 +47,16 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "blending_utils", + srcs = [ + "blending_utils.cc", + ], + hdrs = [ + "blending_utils.h", + ], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/common/blending_utils.cc b/common/blending_utils.cc new file mode 100644 index 0000000000..8e69630b26 --- /dev/null +++ b/common/blending_utils.cc @@ -0,0 +1,11 @@ +#include "blending_utils.h" +#include + +double blend_sigmoid(double t, double tau, double window) { + double x = (t + window) / tau; + return exp(x) / (1 + exp(x)); +} + +double blend_exp(double t, double tau, double window) { + return 1 - exp(-(t + window) / tau); +} \ No newline at end of file diff --git a/common/blending_utils.h b/common/blending_utils.h new file mode 100644 index 0000000000..fcb265c2ed --- /dev/null +++ b/common/blending_utils.h @@ -0,0 +1,7 @@ +#pragma once + +enum BLEND_FUNC { SIGMOID, EXP }; + +double blend_sigmoid(double t, double tau, double window); + +double blend_exp(double t, double tau, double window); \ No newline at end of file diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 9f3be203c8..24b96a1a22 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -357,6 +357,7 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//examples/Cassie/osc", + "//examples/Cassie/contact_scheduler:all", "//examples/Cassie/osc_jump", "//examples/Cassie/osc_run", "//lcm:trajectory_saver", diff --git a/examples/Cassie/contact_scheduler/BUILD.bazel b/examples/Cassie/contact_scheduler/BUILD.bazel index 3ac559dbd8..ce0982bafb 100644 --- a/examples/Cassie/contact_scheduler/BUILD.bazel +++ b/examples/Cassie/contact_scheduler/BUILD.bazel @@ -3,12 +3,22 @@ package(default_visibility = ["//visibility:public"]) +cc_library( + name="all", + deps = [ + ":contact_scheduler", + ":kinodynamic_planner", + ":kinodynamic_settings", + ] +) + cc_library( name = "contact_scheduler", srcs = ["contact_scheduler.cc"], hdrs = ["contact_scheduler.h"], deps = [ "//lcmtypes:lcmt_robot", + "//common", "//systems/primitives", "@drake//:drake_shared_library", ], diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 13c3e3eb5e..3696b30685 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -2,13 +2,17 @@ #include +using Eigen::VectorXd; using std::cout; using std::endl; +using std::string; using drake::systems::BasicVector; using drake::systems::Context; -using Eigen::VectorXd; -using std::string; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::systems::State; +using drake::systems::UnrestrictedUpdateEvent; namespace dairlib { @@ -17,9 +21,21 @@ using systems::OutputVector; ContactScheduler::ContactScheduler( const drake::multibody::MultibodyPlant &plant, - double near_impact_threshold, double tau, BLEND_FUNC blend_func) + std::set &impact_states, double near_impact_threshold, + double tau, BLEND_FUNC blend_func) : near_impact_threshold_(near_impact_threshold), - blend_func_(blend_func) { + tau_(tau), + blend_func_(blend_func), + impact_states_(impact_states) { + // Declare system ports + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); + fsm_port_ = this->DeclareVectorOutputPort("fsm", BasicVector(1), + &ContactScheduler::CalcFiniteState) + .get_index(); impact_info_port_ = this->DeclareVectorOutputPort( "near_impact", ImpactInfoVector(0, 0, 0), &ContactScheduler::CalcNextImpactInfo) @@ -27,20 +43,147 @@ ContactScheduler::ContactScheduler( clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), &ContactScheduler::CalcClock) .get_index(); - contact_scheduler_port_ = this->DeclareVectorOutputPort("contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, right_t0, right_t0", - BasicVector(6), - &ContactScheduler::CalcContactScheduler) - .get_index(); + contact_scheduler_port_ = + this->DeclareVectorOutputPort( + "contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, " + "right_t0, right_t0", + BasicVector(6), &ContactScheduler::CalcContactScheduler) + .get_index(); + // Declare discrete states and update + stored_robot_state_index_ = + DeclareDiscreteState(plant.num_positions() + plant.num_velocities()); + stored_fsm_state_index_ = DeclareDiscreteState(1); + stored_transition_time_index_ = DeclareDiscreteState(1); + nominal_state_durations_index_ = DeclareDiscreteState(2); + std::vector> + initial_state_transitions = {{0.1, LEFT_STANCE}, + {0.3, LEFT_FLIGHT}, + {0.4, RIGHT_STANCE}, + {0.6, RIGHT_FLIGHT}}; + upcoming_transitions_index_ = DeclareAbstractState( + drake::Value>>{ + initial_state_transitions}); + transition_times_index_ = DeclareAbstractState( + drake::Value>{{0.1, 0.3, 0.4, 0.6}}); + + DeclarePerStepUnrestrictedUpdateEvent( + &ContactScheduler::UpdateTransitionTimes); } -double alpha_sigmoid(double t, double tau, double near_impact_threshold) { - double x = (t + near_impact_threshold) / tau; - return exp(x) / (1 + exp(x)); +EventStatus ContactScheduler::UpdateTransitionTimes( + const Context &context, State *state) const { + const OutputVector *robot_output = + (OutputVector *) + this->EvalVectorInput(context, state_port_); + double current_time = robot_output->get_timestamp(); + + auto stored_fsm_state = (RUNNING_FSM_STATE) state->get_mutable_discrete_state( + stored_fsm_state_index_)[0]; + double stored_transition_time = + state->get_discrete_state(stored_transition_time_index_)[0]; + double nominal_stance_duration = + state->get_discrete_state(nominal_state_durations_index_)[0]; + double nominal_flight_duration = + state->get_discrete_state(nominal_state_durations_index_)[1]; + auto transition_times = + state->get_mutable_abstract_state>( + transition_times_index_); + std::vector> &upcoming_transitions = + state->get_mutable_abstract_state< + std::vector>>( + upcoming_transitions_index_); + + auto active_state = stored_fsm_state; + double transition_time = upcoming_transitions.at(1).first; + RUNNING_FSM_STATE transition_state = upcoming_transitions.at(1).second; + if (current_time > transition_time) { + active_state = transition_state; + } + + if (active_state != stored_fsm_state) { + state->get_mutable_discrete_state(stored_robot_state_index_) + .SetFromVector(robot_output->GetState()); + state->get_mutable_discrete_state(stored_transition_time_index_)[0] = + robot_output->get_timestamp(); + + double g = + drake::multibody::UniformGravityFieldElement::kDefaultStrength; + + // Compute relative to stance foot + double pelvis_z = robot_output->GetState()[6]; + double pelvis_zdot = robot_output->GetState()[23 + 5]; + + if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { + // TODO(yangwill): calculate end of stance duration + double next_transition_time = 0.3; + state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = + next_transition_time - stored_transition_time; + if (active_state == LEFT_STANCE) { + transition_times[LEFT_FLIGHT] = next_transition_time; + transition_times[RIGHT_STANCE] = + next_transition_time + nominal_flight_duration; + transition_times[RIGHT_FLIGHT] = next_transition_time + + nominal_flight_duration + + nominal_stance_duration; + upcoming_transitions = {{transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], + RIGHT_FLIGHT}}; + } else { + transition_times[LEFT_FLIGHT] = next_transition_time; + transition_times[RIGHT_STANCE] = + next_transition_time + nominal_flight_duration; + transition_times[RIGHT_FLIGHT] = next_transition_time + + nominal_flight_duration + + nominal_stance_duration; + upcoming_transitions = {{transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}}; + } + } else { + // TODO calculate end of flight duration + double next_transition_time = + stored_transition_time + + 1 / g * + (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - + 2 * g * (pelvis_z - rest_length_))); + if (active_state == LEFT_FLIGHT) { + transition_times[RIGHT_STANCE] = next_transition_time; + transition_times[RIGHT_FLIGHT] = + next_transition_time + nominal_stance_duration; + transition_times[LEFT_STANCE] = next_transition_time + + nominal_stance_duration + + nominal_flight_duration; + upcoming_transitions = {{transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}}; + } else { + transition_times[LEFT_STANCE] = next_transition_time; + transition_times[LEFT_FLIGHT] = + next_transition_time + nominal_stance_duration; + transition_times[RIGHT_STANCE] = next_transition_time + + nominal_stance_duration + + nominal_flight_duration; + upcoming_transitions = {{transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}}; + } + } + } + + stored_fsm_state << active_state; } -double alpha_exp(double t, double tau, double near_impact_threshold) { - return 1 - exp(-(t + near_impact_threshold) / tau); +void ContactScheduler::CalcFiniteState(const Context &context, + BasicVector *fsm_state) const { + // Assign fsm_state + fsm_state->SetFromVector( + context.get_discrete_state(stored_fsm_state_index_).value()); } void ContactScheduler::CalcNextImpactInfo( @@ -48,43 +191,49 @@ void ContactScheduler::CalcNextImpactInfo( ImpactInfoVector *near_impact) const { // Read in lcm message time const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + (OutputVector *) + this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); - - double remainder = fmod(current_time, period_); - + const std::vector> + &upcoming_transitions = + context.get_abstract_state< + std::vector>>( + upcoming_transitions_index_); // Assign the blending function ptr - auto alpha_func = blend_func_ == SIGMOID ? &alpha_sigmoid : &alpha_exp; + auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; near_impact->set_timestamp(current_time); - near_impact->SetCurrentContactMode(0); - near_impact->SetAlpha(0); + // near_impact->SetCurrentContactMode(0); + // near_impact->SetAlpha(0); + // Get current finite state - if (current_time >= t0_) { - for (int i = 0; i < impact_states_.size(); ++i) { - double blend_window = blend_func_ == SIGMOID - ? 1.5 * near_impact_threshold_ - : near_impact_threshold_; - if (abs(remainder - impact_times_[i]) < blend_window) { - if (remainder < impact_times_[i]) { - near_impact->SetAlpha(alpha_func(remainder - impact_times_[i], tau_, - near_impact_threshold_)); - } else { - near_impact->SetAlpha(alpha_func(impact_times_[i] - remainder, tau_, - near_impact_threshold_)); - } - near_impact->SetCurrentContactMode(impact_states_[i]); - break; + double transition_time = upcoming_transitions.at(1).first; + RUNNING_FSM_STATE transition_state = upcoming_transitions.at(1).second; + double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; + // Check if the upcoming state has an impact + if (impact_states_.count(transition_state) != 0) { + // Check if we're close to an impact event + if (abs(current_time - transition_time) < blend_window) { + // Apply the corresponding blending function + if (current_time < transition_time) { + near_impact->SetAlpha(alpha_func(current_time - transition_time, tau_, + near_impact_threshold_)); + } else { + near_impact->SetAlpha(alpha_func(transition_time - current_time, tau_, + near_impact_threshold_)); } + near_impact->SetCurrentContactMode(transition_state); } } } -void ContactScheduler::CalcClock( - const Context &context, BasicVector *clock) const { +void ContactScheduler::CalcClock(const Context &context, + BasicVector *clock) const { // Read in lcm message time const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + (OutputVector *) + this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); clock->get_mutable_value()(0) = current_time; @@ -93,32 +242,21 @@ void ContactScheduler::CalcClock( void ContactScheduler::CalcContactScheduler( const Context &context, BasicVector *contact_timing) const { // Read in lcm message time - const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); -// if (this->get_input_port(radio_port_).HasValue(context)) { -// const auto &radio_out = -// this->EvalInputValue(context, radio_port_); -// } - auto current_time = static_cast(robot_output->get_timestamp()); - double remainder = fmod(current_time, period_); - int n_periods = (int) (current_time / period_); - - for (unsigned int i = 0; i < accu_state_durations_.size(); i++) { - contact_timing->get_mutable_value()(0) = - n_periods * period_ + accu_state_durations_[i]; - contact_timing->get_mutable_value()(1) = - n_periods * period_ + accu_state_durations_[i]; - contact_timing->get_mutable_value()(2) = - n_periods * period_ + accu_state_durations_[1]; - contact_timing->get_mutable_value()(3) = - n_periods * period_ + accu_state_durations_[4]; - contact_timing->get_mutable_value()(4) = - (n_periods - 1) * period_ + accu_state_durations_[3]; - contact_timing->get_mutable_value()(5) = - (n_periods - 1) * period_ + accu_state_durations_[3] - + (accu_state_durations_[2] - accu_state_durations_[0]) - + (accu_state_durations_[4] - accu_state_durations_[3]); + RUNNING_FSM_STATE current_state_ = + (RUNNING_FSM_STATE) context.get_discrete_state(stored_fsm_state_index_)[0]; + auto transition_times = + context.get_abstract_state>(transition_times_index_); + if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_STANCE) { + contact_timing->get_mutable_value()(0) = transition_times[LEFT_STANCE]; + contact_timing->get_mutable_value()(1) = transition_times[LEFT_FLIGHT]; + } else { + contact_timing->get_mutable_value()(0) = transition_times[RIGHT_STANCE]; + contact_timing->get_mutable_value()(1) = transition_times[RIGHT_FLIGHT]; } + contact_timing->get_mutable_value()(2) = transition_times[LEFT_FLIGHT]; + contact_timing->get_mutable_value()(3) = transition_times[LEFT_STANCE]; + contact_timing->get_mutable_value()(4) = transition_times[RIGHT_FLIGHT]; + contact_timing->get_mutable_value()(5) = transition_times[RIGHT_STANCE]; } } // namespace dairlib diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index beb36d9768..a2012e7a63 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -1,6 +1,11 @@ #pragma once #include +#include +#include +#include + +#include "common/blending_utils.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" @@ -10,36 +15,49 @@ namespace dairlib { -enum BLEND_FUNC { SIGMOID, EXP }; +enum RUNNING_FSM_STATE { + LEFT_STANCE, RIGHT_STANCE, LEFT_FLIGHT, RIGHT_FLIGHT +}; -class ContactScheduler : drake::systems::LeafSystem { +class ContactScheduler : public drake::systems::LeafSystem { public: ContactScheduler( - const drake::multibody::MultibodyPlant& plant, - double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); + const drake::multibody::MultibodyPlant &plant, + std::set& impact_states, + double near_impact_threshold = 0, + double tau = 0.0025, + BLEND_FUNC blend_func = SIGMOID); - const drake::systems::InputPort& get_input_port_state() const { + void SetSLIPParams(double rest_length) { + rest_length_; + } + const drake::systems::InputPort &get_input_port_state() const { return this->get_input_port(state_port_); } - const drake::systems::OutputPort& get_output_port_fsm() const { + const drake::systems::OutputPort &get_output_port_fsm() const { return this->get_output_port(fsm_port_); } - const drake::systems::OutputPort& get_output_port_clock() const { + const drake::systems::OutputPort &get_output_port_clock() const { return this->get_output_port(clock_port_); } - const drake::systems::OutputPort& get_output_port_impact() const { + const drake::systems::OutputPort &get_output_port_impact() const { return this->get_output_port(impact_info_port_); } - const drake::systems::OutputPort& get_output_port_contact_scheduler() const { + const drake::systems::OutputPort &get_output_port_contact_scheduler() const { return this->get_output_port(contact_scheduler_port_); } private: - void CalcNextImpactInfo(const drake::systems::Context& context, - systems::ImpactInfoVector* near_impact) const; - void CalcClock(const drake::systems::Context& context, - drake::systems::BasicVector* clock) const; - void CalcContactScheduler(const drake::systems::Context& context, + drake::systems::EventStatus UpdateTransitionTimes( + const drake::systems::Context &context, + drake::systems::State* state) const; + void CalcNextImpactInfo(const drake::systems::Context &context, + systems::ImpactInfoVector *near_impact) const; + void CalcFiniteState(const drake::systems::Context &context, + drake::systems::BasicVector *fsm_state) const; + void CalcClock(const drake::systems::Context &context, + drake::systems::BasicVector *clock) const; + void CalcContactScheduler(const drake::systems::Context &context, drake::systems::BasicVector *clock) const; drake::systems::InputPortIndex state_port_; @@ -49,19 +67,35 @@ class ContactScheduler : drake::systems::LeafSystem { drake::systems::OutputPortIndex impact_info_port_; drake::systems::OutputPortIndex contact_scheduler_port_; + // For impact-invariant calculations + const std::set impact_states_; + double near_impact_threshold_; + double tau_; + const BLEND_FUNC blend_func_; + // const drake::multibody::MultibodyPlant& plant_; - double t0_; - std::vector states_; - std::vector state_durations_; - std::vector accu_state_durations_; - std::vector impact_states_; - std::vector impact_times_; - double period_; - double tau_ = 0.0025; - double near_impact_threshold_; - BLEND_FUNC blend_func_; + /// contains pairs (start of fsm, fsm_state) + /// the order of the vector goes: last transition, next upcoming three transitions +// mutable std::vector> upcoming_transitions_; // sorted by upcoming time +// mutable std::vector transition_times_; // fixed order by RUNNING_FSM_STATE + + int initial_state_ = 0; + + drake::systems::DiscreteStateIndex stored_fsm_state_index_; + drake::systems::DiscreteStateIndex stored_robot_state_index_; + drake::systems::DiscreteStateIndex stored_transition_time_index_; + // estimates of state durations for stance and flight in seconds + drake::systems::DiscreteStateIndex nominal_state_durations_index_; + + drake::systems::AbstractStateIndex transition_times_index_; + drake::systems::AbstractStateIndex upcoming_transitions_index_; + + /// SLIP parameters + double rest_length_; + + }; } // namespace dairlib diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc index 243ae9a8dc..ef52cb9017 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc @@ -23,7 +23,7 @@ namespace osc_jump { JumpingEventFsm::JumpingEventFsm(const MultibodyPlant& plant, const vector& transition_times, bool contact_based, double impact_threshold, - FSM_STATE init_state, BLEND_FUNC blend_func) + JUMPING_FSM_STATE init_state, BLEND_FUNC blend_func) : transition_times_(transition_times), contact_based_(contact_based), impact_threshold_(impact_threshold), @@ -104,7 +104,7 @@ EventStatus JumpingEventFsm::DiscreteVariableUpdate( fsm_state << CROUCH; std::cout << "Current time: " << timestamp << std::endl; std::cout << "Setting fsm to CROUCH" << std::endl; - std::cout << "fsm: " << (FSM_STATE)fsm_state(0) << std::endl; + std::cout << "fsm: " << (JUMPING_FSM_STATE)fsm_state(0) << std::endl; } } else if (fsm_state(0) == CROUCH) { if (contact_based_ ? num_contacts == 0 @@ -113,7 +113,7 @@ EventStatus JumpingEventFsm::DiscreteVariableUpdate( std::cout << "Current time: " << timestamp << std::endl; std::cout << "First detection time: " << state_trigger_time(0) << "\n"; std::cout << "Setting fsm to FLIGHT" << std::endl; - std::cout << "fsm: " << (FSM_STATE)fsm_state(0) << std::endl; + std::cout << "fsm: " << (JUMPING_FSM_STATE)fsm_state(0) << std::endl; } } else if (fsm_state(0) == FLIGHT) { if (contact_based_ ? num_contacts != 0 @@ -123,7 +123,7 @@ EventStatus JumpingEventFsm::DiscreteVariableUpdate( std::cout << "First detection time: " << state_trigger_time(0) << "\n"; std::cout << "Setting fsm to LAND" << "\n"; - std::cout << "fsm: " << (FSM_STATE)fsm_state(0) << "\n"; + std::cout << "fsm: " << (JUMPING_FSM_STATE)fsm_state(0) << "\n"; } } else if (fsm_state(0) == LAND) { // no more transitions diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.h b/examples/Cassie/osc_jump/jumping_event_based_fsm.h index 07a733e5ab..8b7f7054de 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.h +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.h @@ -11,7 +11,7 @@ namespace dairlib { namespace examples { namespace osc_jump { -enum FSM_STATE { READY, BALANCE, CROUCH, FLIGHT, LAND }; +enum JUMPING_FSM_STATE { READY, BALANCE, CROUCH, FLIGHT, LAND }; /// Event based FSM for jumping with option to change to a time-based FSM /// @param[plant] The MultibodyPlant that this FSM operates with @@ -26,7 +26,7 @@ class JumpingEventFsm : public drake::systems::LeafSystem { JumpingEventFsm(const drake::multibody::MultibodyPlant& plant, const std::vector& transition_times, bool contact_based = true, double impact_threshold = 0.0, - FSM_STATE init_state = BALANCE, + JUMPING_FSM_STATE init_state = BALANCE, BLEND_FUNC blend_func = SIGMOID); const drake::systems::InputPort& get_state_input_port() const { @@ -83,7 +83,7 @@ class JumpingEventFsm : public drake::systems::LeafSystem { int prev_time_idx_; int guard_trigger_time_idx_; - const FSM_STATE init_state_; + const JUMPING_FSM_STATE init_state_; BLEND_FUNC blend_func_; }; diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc index 87bfee2e7c..aa913a95a1 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc @@ -33,7 +33,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( const std::vector&>>& feet_contact_points, - double time_offset, FSM_STATE init_fsm_state) + double time_offset, JUMPING_FSM_STATE init_fsm_state) : plant_(plant), context_(context), world_(plant_.world_frame()), diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h index 3b2cb83ae6..56ab16efe7 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h @@ -19,7 +19,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const std::vector&>>& feet_contact_points, - double time_offset = 0.0, FSM_STATE init_fsm_state = BALANCE); + double time_offset = 0.0, JUMPING_FSM_STATE init_fsm_state = BALANCE); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index a63cc53c91..22a6760949 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -91,6 +91,9 @@ DEFINE_bool(same_knotpoints, false, "Set flag to true if seeding with a trajectory with the same " "number of knotpoints"); DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); +DEFINE_double(actuator_limit, + 1.0, + "Conservative estimate scaling factor for actuator limits, 1.0 is at the actual actuator limits."); namespace dairlib { @@ -467,15 +470,21 @@ void SetKinematicConstraints(Dircon *trajopt, prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_right"))); - prog->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_left"))); - prog->AddBoundingBoxConstraint(-2.1, -1.6, x_0(pos_map.at("toe_right"))); - prog->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_left"))); - prog->AddBoundingBoxConstraint(-2.1, -1.6, x_f(pos_map.at("toe_right"))); +// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_0(pos_map.at("toe_left"))); +// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_0(pos_map.at("toe_right"))); +// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_left"))); +// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_right"))); + trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_left"))); trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_right"))); trajopt->AddConstraintToAllKnotPoints(-1.1 >= x(pos_map.at("knee_left"))); trajopt->AddConstraintToAllKnotPoints(-1.1 >= x(pos_map.at("knee_right"))); + trajopt->AddConstraintToAllKnotPoints(-2.2 <= x(pos_map.at("toe_left"))); + trajopt->AddConstraintToAllKnotPoints(-2.2 <= x(pos_map.at("toe_right"))); + trajopt->AddConstraintToAllKnotPoints(-1.6 >= x(pos_map.at("toe_left"))); + trajopt->AddConstraintToAllKnotPoints(-1.6 >= x(pos_map.at("toe_right"))); + // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); @@ -543,14 +552,18 @@ void SetKinematicConstraints(Dircon *trajopt, // prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + l_r_pair.first]) == // x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle - // trajopt->AddConstraintToAllKnotPoints( - // u_0(act_map.at(sym_joint_name + l_r_pair.first + - // "_motor")) == u_0(act_map.at(sym_joint_name + - // l_r_pair.second + "_motor"))); - // trajopt->AddConstraintToAllKnotPoints( - // u_f(act_map.at(sym_joint_name + l_r_pair.first + - // "_motor")) == u_f(act_map.at(sym_joint_name + - // l_r_pair.second + "_motor"))); + trajopt->AddConstraintToAllKnotPoints( + u[act_map.at(sym_joint_name + l_r_pair.first + + "_motor")] - u[act_map.at(sym_joint_name + + l_r_pair.second + "_motor")] <= 10); + trajopt->AddConstraintToAllKnotPoints( + u[act_map.at(sym_joint_name + l_r_pair.first + + "_motor")] - u[act_map.at(sym_joint_name + + l_r_pair.second + "_motor")] >= -10); +// prog->AddConstraint( +// u_f(act_map.at(sym_joint_name + l_r_pair.first + +// "_motor")) == u_f(act_map.at(sym_joint_name + +// l_r_pair.second + "_motor"))); } } } @@ -570,8 +583,10 @@ void SetKinematicConstraints(Dircon *trajopt, VectorXd u_min(n_u); VectorXd u_max(n_u); for (drake::multibody::JointActuatorIndex i(0); i < n_u; ++i) { - u_min[i] = 0.75 * -plant.get_joint_actuator(i).effort_limit(); - u_max[i] = 0.75 * plant.get_joint_actuator(i).effort_limit(); + u_min[i] = + FLAGS_actuator_limit * -plant.get_joint_actuator(i).effort_limit(); + u_max[i] = + FLAGS_actuator_limit * plant.get_joint_actuator(i).effort_limit(); } for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); @@ -631,18 +646,20 @@ void SetKinematicConstraints(Dircon *trajopt, prog->AddConstraint(right_foot_x_start_constraint, x_0.head(n_q)); // Jumping distance constraint for platform clearance - auto left_foot_x_platform_constraint = - std::make_shared>( - plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), - 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); - auto right_foot_x_platform_constraint = - std::make_shared>( - plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), - 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); - prog->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); - prog->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); + if (FLAGS_height > 0.3) { + auto left_foot_x_platform_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), + 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); + auto right_foot_x_platform_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), + 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); + prog->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); + } // Jumping distance constraint auto left_foot_x_constraint = @@ -665,12 +682,12 @@ void SetKinematicConstraints(Dircon *trajopt, std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - (0.1 + FLAGS_height + eps) * VectorXd::Ones(1)); + (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); auto right_foot_z_box_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - (0.1 + FLAGS_height + eps) * VectorXd::Ones(1)); + (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); @@ -702,13 +719,13 @@ void SetKinematicConstraints(Dircon *trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - for (int index = 0; index < (mode_lengths[0] - 2); index++) { - auto lambda = trajopt->force_vars(0, index); - prog->AddLinearConstraint(lambda(2) >= 60); - prog->AddLinearConstraint(lambda(5) >= 60); - prog->AddLinearConstraint(lambda(8) >= 60); - prog->AddLinearConstraint(lambda(11) >= 60); - } +// for (int index = 0; index < (mode_lengths[0] - 2); index++) { +// auto lambda = trajopt->force_vars(0, index); +// prog->AddLinearConstraint(lambda(2) >= 60); +// prog->AddLinearConstraint(lambda(5) >= 60); +// prog->AddLinearConstraint(lambda(8) >= 60); +// prog->AddLinearConstraint(lambda(11) >= 60); +// } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); @@ -716,17 +733,11 @@ void SetKinematicConstraints(Dircon *trajopt, prog->AddLinearConstraint(lambda(5) <= 350); prog->AddLinearConstraint(lambda(8) <= 350); prog->AddLinearConstraint(lambda(11) <= 350); - prog->AddLinearConstraint(lambda(2) >= 50); - prog->AddLinearConstraint(lambda(5) >= 50); - prog->AddLinearConstraint(lambda(8) >= 50); - prog->AddLinearConstraint(lambda(11) >= 50); +// prog->AddLinearConstraint(lambda(2) >= 50); +// prog->AddLinearConstraint(lambda(5) >= 50); +// prog->AddLinearConstraint(lambda(8) >= 50); +// prog->AddLinearConstraint(lambda(11) >= 50); } - // Limit the ground impulses when landing - auto Lambda = trajopt->impulse_vars(1); - prog->AddLinearConstraint(Lambda(2) <= 2); - prog->AddLinearConstraint(Lambda(5) <= 2); - prog->AddLinearConstraint(Lambda(8) <= 2); - prog->AddLinearConstraint(Lambda(11) <= 2); } /****** @@ -771,45 +782,45 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, } l_r_pairs.pop_back(); - // double w_symmetry_pos = FLAGS_cost_scaling * 1e5; - // double w_symmetry_vel = FLAGS_cost_scaling * 1e2; - // double w_symmetry_u = FLAGS_cost_scaling * 1e2; - // for (const auto& l_r_pair : l_r_pairs) { - // for (const auto& sym_joint_name : sym_joint_names) { - // auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - - // x(pos_map.at(sym_joint_name + l_r_pair.second)); - // auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - // - - // x(vel_map.at(sym_joint_name + l_r_pair.second + - // "dot")); - // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - // if (sym_joint_name != "ankle_joint") { - // auto act_diff = - // u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - // u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); - // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - // } - // } - // } - // for (const auto& l_r_pair : l_r_pairs) { - // for (const auto& asy_joint_name : asy_joint_names) { - // auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + - // x(pos_map.at(asy_joint_name + l_r_pair.second)); - // auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) - // + - // x(vel_map.at(asy_joint_name + l_r_pair.second + - // "dot")); - // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - // if (asy_joint_name != "ankle_joint") { - // auto act_diff = - // u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - // u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); - // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - // } - // } - // } + double w_symmetry_pos = FLAGS_cost_scaling * 1e5; + double w_symmetry_vel = FLAGS_cost_scaling * 1e2; + double w_symmetry_u = FLAGS_cost_scaling * 1e2; + for (const auto &l_r_pair: l_r_pairs) { + for (const auto &sym_joint_name: sym_joint_names) { + auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - + x(pos_map.at(sym_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) + - + x(vel_map.at(sym_joint_name + l_r_pair.second + + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (sym_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + } + } + } + for (const auto& l_r_pair : l_r_pairs) { + for (const auto &asy_joint_name: asy_joint_names) { + auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + + x(pos_map.at(asy_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + + + x(vel_map.at(asy_joint_name + l_r_pair.second + + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (asy_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + } + } + } MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 7ad5333261..457c2acb38 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -260,7 +260,7 @@ int DoMain(int argc, char* argv[]) { pelvis_rot_trajectory, "pelvis_rot_tracking_data", FLAGS_delay_time); auto fsm = builder.AddSystem( plant_w_spr, transition_times, FLAGS_contact_based_fsm, - gains.impact_threshold, (osc_jump::FSM_STATE)FLAGS_init_fsm_state); + gains.impact_threshold, (osc_jump::JUMPING_FSM_STATE)FLAGS_init_fsm_state); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -326,8 +326,8 @@ int DoMain(int argc, char* argv[]) { auto right_heel_evaluator = multibody::WorldPointEvaluator( plant_w_spr, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - vector stance_modes = {osc_jump::BALANCE, - osc_jump::CROUCH, osc_jump::LAND}; + vector stance_modes = {osc_jump::BALANCE, + osc_jump::CROUCH, osc_jump::LAND}; for (auto mode : stance_modes) { osc->AddStateAndContactPoint(mode, &left_toe_evaluator); osc->AddStateAndContactPoint(mode, &left_heel_evaluator); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 2640eec277..fd98afd51b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -38,6 +38,7 @@ #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" namespace dairlib { @@ -143,14 +144,10 @@ int DoMain(int argc, char* argv[]) { // FindResourceOrThrow(FLAGS_osqp_settings)); /**** FSM and contact mode configuration ****/ - int left_stance_state = 0; - int right_stance_state = 1; - int right_touchdown_air_phase = 2; - int left_touchdown_air_phase = 3; - vector fsm_states = {left_stance_state, right_touchdown_air_phase, - right_stance_state, left_touchdown_air_phase, - left_stance_state}; + vector fsm_states = {RUNNING_FSM_STATE::LEFT_STANCE, RUNNING_FSM_STATE::LEFT_FLIGHT, + RUNNING_FSM_STATE::RIGHT_STANCE, RUNNING_FSM_STATE::RIGHT_FLIGHT, + RUNNING_FSM_STATE::LEFT_STANCE}; vector state_durations = { osc_gains.stance_duration, osc_gains.flight_duration, @@ -165,6 +162,9 @@ int DoMain(int argc, char* argv[]) { } accumulated_state_durations.pop_back(); + std::set impact_states = {LEFT_STANCE, RIGHT_STANCE}; + auto contact_scheduler = builder.AddSystem( + plant, impact_states, gains.impact_threshold, gains.impact_tau); auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, gains.impact_threshold, gains.impact_tau); @@ -225,10 +225,10 @@ int DoMain(int argc, char* argv[]) { plant, right_heel.first, right_heel.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); - osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_heel_evaluator); multibody::KinematicEvaluatorSet evaluators(plant); auto left_loop = LeftLoopClosureEvaluator(plant); @@ -255,10 +255,10 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); -// osc->AddStateAndContactPoint(left_stance_state, &left_fixed_knee_spring); -// osc->AddStateAndContactPoint(right_stance_state, &right_fixed_knee_spring); -// osc->AddStateAndContactPoint(left_stance_state, &left_fixed_ankle_spring); -// osc->AddStateAndContactPoint(right_stance_state, &right_fixed_ankle_spring); +// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_fixed_knee_spring); +// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_fixed_knee_spring); +// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_fixed_ankle_spring); +// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_fixed_ankle_spring); osc->AddKinematicConstraint(&evaluators); @@ -307,19 +307,19 @@ int DoMain(int argc, char* argv[]) { auto right_foot_tracking_data = std::make_unique( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - pelvis_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); - pelvis_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); - stance_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + stance_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "toe_left"); - stance_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, + stance_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, + left_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left"); - right_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, + right_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + left_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left"); - right_foot_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + right_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); auto left_foot_yz_tracking_data = @@ -330,9 +330,9 @@ int DoMain(int argc, char* argv[]) { std::make_unique( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_foot_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + left_foot_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); - right_foot_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + right_foot_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); auto left_hip_tracking_data = std::make_unique( @@ -341,11 +341,11 @@ int DoMain(int argc, char* argv[]) { auto right_hip_tracking_data = std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + left_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + left_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); auto left_hip_yz_tracking_data = std::make_unique( @@ -355,9 +355,9 @@ int DoMain(int argc, char* argv[]) { std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, + left_hip_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, + right_hip_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); auto left_foot_rel_tracking_data = @@ -393,12 +393,12 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], left_stance_state); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], right_stance_state); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], left_stance_state); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], right_stance_state); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], left_stance_state); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], right_stance_state); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], RUNNING_FSM_STATE::LEFT_STANCE); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], RUNNING_FSM_STATE::RIGHT_STANCE); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], RUNNING_FSM_STATE::LEFT_STANCE); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], RUNNING_FSM_STATE::RIGHT_STANCE); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], RUNNING_FSM_STATE::LEFT_STANCE); +// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], RUNNING_FSM_STATE::RIGHT_STANCE); // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); @@ -428,13 +428,13 @@ int DoMain(int argc, char* argv[]) { auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_touchdown_air_phase, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_touchdown_air_phase, + pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -459,17 +459,17 @@ int DoMain(int argc, char* argv[]) { "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); left_toe_angle_tracking_data->AddStateAndJointToTrack( - right_stance_state, "toe_left", "toe_leftdot"); + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data->AddStateAndJointToTrack( - right_touchdown_air_phase, "toe_left", "toe_leftdot"); + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data->AddStateAndJointToTrack( - left_touchdown_air_phase, "toe_left", "toe_leftdot"); + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left", "toe_leftdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - left_stance_state, "toe_right", "toe_rightdot"); + RUNNING_FSM_STATE::LEFT_STANCE, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - right_touchdown_air_phase, "toe_right", "toe_rightdot"); + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - left_touchdown_air_phase, "toe_right", "toe_rightdot"); + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right", "toe_rightdot"); left_toe_angle_tracking_data->SetImpactInvariantProjection(true); right_toe_angle_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); @@ -518,6 +518,8 @@ int DoMain(int argc, char* argv[]) { // FSM connections builder.Connect(state_receiver->get_output_port(0), fsm->get_input_port_state()); + builder.Connect(state_receiver->get_output_port(0), + contact_scheduler->get_input_port_state()); // Trajectory generator connections builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/impact_invariant_control/BUILD.bazel b/examples/impact_invariant_control/BUILD.bazel index 94839adef3..4230f9ead5 100644 --- a/examples/impact_invariant_control/BUILD.bazel +++ b/examples/impact_invariant_control/BUILD.bazel @@ -28,6 +28,7 @@ cc_library( hdrs = ["impact_aware_time_based_fsm.h"], deps = [ "//systems/controllers:time_based_fsm", + "//common", "@drake//:drake_shared_library", ], ) diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index f32de7e3a8..b5b6d6b1e1 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -20,6 +20,7 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( state_durations_(state_durations), t0_(t0), near_impact_threshold_(near_impact_threshold), + tau_(tau), blend_func_(blend_func) { near_impact_port_ = @@ -63,15 +64,6 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( period_ = sum; } -double alpha_sigmoid(double t, double tau, double near_impact_threshold) { - double x = (t + near_impact_threshold) / tau; - return exp(x) / (1 + exp(x)); -} - -double alpha_exp(double t, double tau, double near_impact_threshold) { - return 1 - exp(-(t + near_impact_threshold) / tau); -} - void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( const Context &context, ImpactInfoVector *near_impact) const { @@ -83,7 +75,7 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( double remainder = fmod(current_time, period_); // Assign the blending function ptr - auto alpha_func = blend_func_ == SIGMOID ? &alpha_sigmoid : &alpha_exp; + auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; near_impact->set_timestamp(current_time); near_impact->SetCurrentContactMode(0); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index 66d3421ff6..dea682c402 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -2,6 +2,7 @@ #include +#include "common/blending_utils.h" #include "systems/controllers/time_based_fsm.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" @@ -11,7 +12,6 @@ namespace dairlib { -enum BLEND_FUNC { SIGMOID, EXP }; class ImpactTimeBasedFiniteStateMachine : public systems::TimeBasedFiniteStateMachine { @@ -58,7 +58,7 @@ class ImpactTimeBasedFiniteStateMachine std::vector impact_states_; std::vector impact_times_; double period_; - double tau_ = 0.0025; + double tau_; double near_impact_threshold_; BLEND_FUNC blend_func_; }; From 878fdc1a1abb357c9c982e24faeb2065ddc2e025 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 8 Aug 2022 17:42:08 -0400 Subject: [PATCH 261/758] still working on replacing old fsm --- bindings/pydairlib/cassie/controllers_py.cc | 8 +- .../cassie/gym_envs/drake_cassie_gym.py | 2 +- bindings/pydairlib/cassie/simulators_py.cc | 2 +- .../lcm/dircon_trajectory_plotter.py | 14 +- .../contact_scheduler/contact_scheduler.cc | 222 +++++++++------ .../contact_scheduler/contact_scheduler.h | 78 +++--- .../osc_running_controller_diagram.cc | 48 ++-- .../osc_walking_controller_diagram.cc | 20 +- .../Cassie/osc/swing_toe_traj_generator.h | 2 +- examples/Cassie/osc_run/BUILD.bazel | 1 + .../Cassie/osc_run/foot_traj_generator.cc | 185 +++++++------ examples/Cassie/osc_run/foot_traj_generator.h | 12 +- .../Cassie/osc_run/osc_running_gains.yaml | 4 +- .../osc_run/pelvis_trans_traj_generator.cc | 22 +- examples/Cassie/run_dircon_jumping.cc | 11 +- examples/Cassie/run_osc_jumping_controller.cc | 18 +- examples/Cassie/run_osc_running_controller.cc | 255 +++++++++++------- .../Cassie/run_osc_standing_controller.cc | 4 +- examples/Cassie/run_osc_walking_controller.cc | 22 +- .../Cassie/run_osc_walking_controller_alip.cc | 28 +- .../impact_aware_time_based_fsm.cc | 2 +- .../impact_aware_time_based_fsm.h | 2 +- .../run_joint_space_walking_controller.cc | 10 +- lcmtypes/lcmt_contact_timing.lcm | 11 + .../osc/operational_space_control.cc | 2 +- .../osc/operational_space_control.h | 10 +- systems/controllers/time_based_fsm.h | 4 +- 27 files changed, 582 insertions(+), 417 deletions(-) create mode 100644 lcmtypes/lcmt_contact_timing.lcm diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index 0affd39263..d8623f9cb0 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -27,10 +27,10 @@ PYBIND11_MODULE(controllers, m) { py::arg("plant"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) .def("get_plant", &OSCRunningControllerDiagram::get_plant, py_rvp::reference_internal) - .def("get_state_input_port", + .def("get_input_port_state", &OSCRunningControllerDiagram::get_state_input_port, py_rvp::reference_internal) - .def("get_radio_input_port", + .def("get_input_port_radio", &OSCRunningControllerDiagram::get_radio_input_port, py_rvp::reference_internal) .def("get_control_output_port", @@ -49,10 +49,10 @@ PYBIND11_MODULE(controllers, m) { py::arg("plant"), py::arg("has_double_stance"), py::arg("osc_gains_filename"), py::arg("osqp_settings_filename")) .def("get_plant", &OSCWalkingControllerDiagram::get_plant, py_rvp::reference_internal) - .def("get_state_input_port", + .def("get_input_port_state", &OSCWalkingControllerDiagram::get_state_input_port, py_rvp::reference_internal) - .def("get_radio_input_port", + .def("get_input_port_radio", &OSCWalkingControllerDiagram::get_radio_input_port, py_rvp::reference_internal) .def("get_control_output_port", diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 5db61bc607..2bdb9c9ca9 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -50,7 +50,7 @@ def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) # self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), # self.controller.get_cassie_out_input_port()) - # self.builder.Connect(self.controller, self.simulator.get_radio_input_port()) + # self.builder.Connect(self.controller, self.simulator.get_input_port_radio()) self.diagram = self.builder.Build() self.sim = Simulator(self.diagram) diff --git a/bindings/pydairlib/cassie/simulators_py.cc b/bindings/pydairlib/cassie/simulators_py.cc index 2c7e0355bb..1b42c46989 100644 --- a/bindings/pydairlib/cassie/simulators_py.cc +++ b/bindings/pydairlib/cassie/simulators_py.cc @@ -29,7 +29,7 @@ PYBIND11_MODULE(simulators, m) { .def("get_actuation_input_port", &CassieSimDiagram::get_actuation_input_port, py_rvp::reference_internal) - .def("get_radio_input_port", &CassieSimDiagram::get_radio_input_port, + .def("get_input_port_radio", &CassieSimDiagram::get_radio_input_port, py_rvp::reference_internal) .def("get_state_output_port", &CassieSimDiagram::get_state_output_port, py_rvp::reference_internal) diff --git a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py index 8b2dae5dd5..109c47b7ab 100644 --- a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py @@ -20,7 +20,7 @@ def main(): # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/walking_0.16.0") # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/jumping_0.15h_0.3d") filename = FindResourceOrThrow( - "examples/Cassie/saved_trajectories/jumping_0.0h_1.0d_0") + "examples/Cassie/saved_trajectories/jumping_0.0h_1.0d_9") # filename = FindResourceOrThrow( # "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1") # filename = "/home/yangwill/Documents/research/projects/cassie/hardware/backup/dair/saved_trajectories/jumping_0.15h_0.3d" @@ -33,11 +33,11 @@ def main(): input_traj = dircon_traj.ReconstructInputTrajectory() state_datatypes = dircon_traj.GetTrajectory("state_traj0").datatypes input_datatypes = dircon_traj.GetTrajectory("input_traj").datatypes - force_samples = dircon_traj.GetTrajectory("force_vars0").datapoints + force_samples = dircon_traj.GetTrajectory("force_vars2").datapoints force_t_samples = dircon_traj.GetStateBreaks(0) force_traj = dircon_traj.ReconstructLambdaTrajectory() # force_datatypes = dircon_traj.GetTrajectory("force_vars0").datatypes - force_datatypes = dircon_traj.GetTrajectory("force_vars1").datatypes + force_datatypes = dircon_traj.GetTrajectory("force_vars2").datatypes collocation_force_points = dircon_traj.GetCollocationForceSamples(0) # M = reflected_joints() @@ -51,8 +51,15 @@ def main(): # dircon_traj.AddTrajectory('mirror_matrix', mirror_traj) # dircon_traj.WriteToFile(filename) + + plot_only_at_knotpoints = True + print(force_t_samples) + n_points = 500 t = np.linspace(state_traj.start_time(), state_traj.end_time(), n_points) + if plot_only_at_knotpoints: + n_points = force_t_samples.shape[0] + t = force_t_samples state_samples = np.zeros((n_points, state_traj.value(0).shape[0])) state_derivative_samples = np.zeros((n_points, state_traj.value(0).shape[0])) input_samples = np.zeros((n_points, input_traj.value(0).shape[0])) @@ -84,6 +91,7 @@ def main(): plt.figure("input trajectory") + print(np.diff(input_samples[:, 7])) plt.plot(t, input_samples[:, :]) plt.legend(input_datatypes[:]) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 3696b30685..3784f86dca 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -2,6 +2,8 @@ #include +#include "common/eigen_utils.h" + using Eigen::VectorXd; using std::cout; using std::endl; @@ -20,29 +22,30 @@ using systems::ImpactInfoVector; using systems::OutputVector; ContactScheduler::ContactScheduler( - const drake::multibody::MultibodyPlant &plant, - std::set &impact_states, double near_impact_threshold, + const drake::multibody::MultibodyPlant& plant, + std::set& impact_states, double near_impact_threshold, double tau, BLEND_FUNC blend_func) : near_impact_threshold_(near_impact_threshold), tau_(tau), blend_func_(blend_func), impact_states_(impact_states) { + this->set_name("ContactScheduler"); // Declare system ports state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector(plant.num_positions(), - plant.num_velocities(), - plant.num_actuators())) - .get_index(); + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorOutputPort("fsm", BasicVector(1), &ContactScheduler::CalcFiniteState) - .get_index(); + .get_index(); impact_info_port_ = this->DeclareVectorOutputPort( - "near_impact", ImpactInfoVector(0, 0, 0), - &ContactScheduler::CalcNextImpactInfo) - .get_index(); + "near_impact", ImpactInfoVector(0, 0, 0), + &ContactScheduler::CalcNextImpactInfo) + .get_index(); clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), &ContactScheduler::CalcClock) - .get_index(); + .get_index(); contact_scheduler_port_ = this->DeclareVectorOutputPort( "contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, " @@ -51,34 +54,43 @@ ContactScheduler::ContactScheduler( .get_index(); // Declare discrete states and update + stored_fsm_state_index_ = DeclareDiscreteState(1 * VectorXd::Ones(1)); stored_robot_state_index_ = DeclareDiscreteState(plant.num_positions() + plant.num_velocities()); - stored_fsm_state_index_ = DeclareDiscreteState(1); stored_transition_time_index_ = DeclareDiscreteState(1); - nominal_state_durations_index_ = DeclareDiscreteState(2); - std::vector> - initial_state_transitions = {{0.1, LEFT_STANCE}, - {0.3, LEFT_FLIGHT}, - {0.4, RIGHT_STANCE}, - {0.6, RIGHT_FLIGHT}}; + VectorXd nominal_state_durations = VectorXd::Zero(2); + nominal_state_durations << 0.25, 0.1; + nominal_state_durations_index_ = + DeclareDiscreteState(nominal_state_durations); + std::vector> initial_state_transitions = + {{-0.1, RIGHT_FLIGHT}, + {0.001, LEFT_STANCE}, + {0.25, LEFT_FLIGHT}, + {0.35, RIGHT_STANCE}}; + // transition_times_index_ = DeclareAbstractState( + // drake::Value>{{0.1, 0.3, 0.4, 0.6}}); + VectorXd initial_transition_times = VectorXd::Zero(4); + initial_transition_times << -0.1, 0.0, 0.25, 0.35; + transition_times_index_ = DeclareDiscreteState(initial_transition_times); + upcoming_transitions_index_ = DeclareAbstractState( drake::Value>>{ initial_state_transitions}); - transition_times_index_ = DeclareAbstractState( - drake::Value>{{0.1, 0.3, 0.4, 0.6}}); + debug_port_ = this->DeclareAbstractOutputPort( + "status", &ContactScheduler::OutputDebuggingInfo) + .get_index(); DeclarePerStepUnrestrictedUpdateEvent( &ContactScheduler::UpdateTransitionTimes); } EventStatus ContactScheduler::UpdateTransitionTimes( - const Context &context, State *state) const { - const OutputVector *robot_output = - (OutputVector *) - this->EvalVectorInput(context, state_port_); + const Context& context, State* state) const { + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); double current_time = robot_output->get_timestamp(); - auto stored_fsm_state = (RUNNING_FSM_STATE) state->get_mutable_discrete_state( + auto stored_fsm_state = (RUNNING_FSM_STATE)state->get_mutable_discrete_state( stored_fsm_state_index_)[0]; double stored_transition_time = state->get_discrete_state(stored_transition_time_index_)[0]; @@ -87,9 +99,9 @@ EventStatus ContactScheduler::UpdateTransitionTimes( double nominal_flight_duration = state->get_discrete_state(nominal_state_durations_index_)[1]; auto transition_times = - state->get_mutable_abstract_state>( - transition_times_index_); - std::vector> &upcoming_transitions = + state->get_mutable_discrete_state(transition_times_index_) + .get_mutable_value(); + std::vector>& upcoming_transitions = state->get_mutable_abstract_state< std::vector>>( upcoming_transitions_index_); @@ -98,6 +110,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( double transition_time = upcoming_transitions.at(1).first; RUNNING_FSM_STATE transition_state = upcoming_transitions.at(1).second; if (current_time > transition_time) { + std::cout << "transitioning to: " << transition_state << std::endl; + std::cout << "at: " << transition_time << std::endl; active_state = transition_state; } @@ -106,7 +120,10 @@ EventStatus ContactScheduler::UpdateTransitionTimes( .SetFromVector(robot_output->GetState()); state->get_mutable_discrete_state(stored_transition_time_index_)[0] = robot_output->get_timestamp(); - + double stored_transition_time = + state->get_discrete_state(stored_transition_time_index_)[0]; + std::cout << "stored_transition_time: " << stored_transition_time + << std::endl; double g = drake::multibody::UniformGravityFieldElement::kDefaultStrength; @@ -116,47 +133,53 @@ EventStatus ContactScheduler::UpdateTransitionTimes( if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { // TODO(yangwill): calculate end of stance duration - double next_transition_time = 0.3; + double next_transition_time = stored_transition_time + 0.25; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; + // nominal_state_durations[0] = + // next_transition_time - stored_transition_time; + // nominal_stance_duration = next_transition_time - + // stored_transition_time; if (active_state == LEFT_STANCE) { transition_times[LEFT_FLIGHT] = next_transition_time; transition_times[RIGHT_STANCE] = next_transition_time + nominal_flight_duration; transition_times[RIGHT_FLIGHT] = next_transition_time + - nominal_flight_duration + - nominal_stance_duration; + nominal_flight_duration + + nominal_stance_duration; upcoming_transitions = {{transition_times[LEFT_STANCE], LEFT_STANCE}, {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, {transition_times[RIGHT_STANCE], RIGHT_STANCE}, - {transition_times[RIGHT_FLIGHT], - RIGHT_FLIGHT}}; + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; } else { - transition_times[LEFT_FLIGHT] = next_transition_time; - transition_times[RIGHT_STANCE] = + transition_times[RIGHT_FLIGHT] = next_transition_time; + transition_times[LEFT_STANCE] = next_transition_time + nominal_flight_duration; - transition_times[RIGHT_FLIGHT] = next_transition_time + - nominal_flight_duration + - nominal_stance_duration; + transition_times[LEFT_FLIGHT] = next_transition_time + + nominal_flight_duration + + nominal_stance_duration; upcoming_transitions = {{transition_times[RIGHT_STANCE], RIGHT_STANCE}, {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, {transition_times[LEFT_STANCE], LEFT_STANCE}, {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}}; } } else { - // TODO calculate end of flight duration - double next_transition_time = - stored_transition_time + - 1 / g * - (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - - 2 * g * (pelvis_z - rest_length_))); + // double next_transition_time = + // stored_transition_time + + // 1 / g * + // (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - + // 2 * g * (pelvis_z - rest_length_))); + double next_transition_time = stored_transition_time + 0.1; + state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = + next_transition_time - stored_transition_time; + // nominal_flight_duration = 0.1; if (active_state == LEFT_FLIGHT) { transition_times[RIGHT_STANCE] = next_transition_time; transition_times[RIGHT_FLIGHT] = next_transition_time + nominal_stance_duration; transition_times[LEFT_STANCE] = next_transition_time + - nominal_stance_duration + - nominal_flight_duration; + nominal_stance_duration + + nominal_flight_duration; upcoming_transitions = {{transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, {transition_times[RIGHT_STANCE], RIGHT_STANCE}, {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, @@ -166,8 +189,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( transition_times[LEFT_FLIGHT] = next_transition_time + nominal_stance_duration; transition_times[RIGHT_STANCE] = next_transition_time + - nominal_stance_duration + - nominal_flight_duration; + nominal_stance_duration + + nominal_flight_duration; upcoming_transitions = {{transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, {transition_times[LEFT_STANCE], LEFT_STANCE}, {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, @@ -176,27 +199,27 @@ EventStatus ContactScheduler::UpdateTransitionTimes( } } - stored_fsm_state << active_state; + state->get_mutable_discrete_state(stored_fsm_state_index_).get_mutable_value() + << active_state; + return drake::systems::EventStatus::Succeeded(); } -void ContactScheduler::CalcFiniteState(const Context &context, - BasicVector *fsm_state) const { +void ContactScheduler::CalcFiniteState(const Context& context, + BasicVector* fsm_state) const { // Assign fsm_state - fsm_state->SetFromVector( - context.get_discrete_state(stored_fsm_state_index_).value()); + VectorXd current_finite_state = context.get_discrete_state(stored_fsm_state_index_).CopyToVector(); + fsm_state->get_mutable_value() = current_finite_state; } void ContactScheduler::CalcNextImpactInfo( - const Context &context, - ImpactInfoVector *near_impact) const { + const Context& context, + ImpactInfoVector* near_impact) const { // Read in lcm message time - const OutputVector *robot_output = - (OutputVector *) - this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); - const std::vector> - &upcoming_transitions = - context.get_abstract_state< + const std::vector>& + upcoming_transitions = context.get_abstract_state< std::vector>>( upcoming_transitions_index_); // Assign the blending function ptr @@ -209,43 +232,59 @@ void ContactScheduler::CalcNextImpactInfo( // Get current finite state double transition_time = upcoming_transitions.at(1).first; RUNNING_FSM_STATE transition_state = upcoming_transitions.at(1).second; + double previous_transition_time = upcoming_transitions.at(0).first; + RUNNING_FSM_STATE current_state = upcoming_transitions.at(0).second; double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ : near_impact_threshold_; + // Check if we're close to an impact event either upcoming or one that just + // happened + // Check if the upcoming state has an impact if (impact_states_.count(transition_state) != 0) { - // Check if we're close to an impact event if (abs(current_time - transition_time) < blend_window) { // Apply the corresponding blending function if (current_time < transition_time) { near_impact->SetAlpha(alpha_func(current_time - transition_time, tau_, near_impact_threshold_)); - } else { - near_impact->SetAlpha(alpha_func(transition_time - current_time, tau_, - near_impact_threshold_)); } near_impact->SetCurrentContactMode(transition_state); } } + // Check if current state that we just transitioned to has an impact + if (impact_states_.count(current_state) != 0) { + if (abs(current_time - previous_transition_time) < blend_window) { + // Apply the corresponding blending function + if (current_time > previous_transition_time) { + near_impact->SetAlpha( + alpha_func(previous_transition_time - current_time, tau_, + near_impact_threshold_)); + } + near_impact->SetCurrentContactMode(current_state); + } + } } -void ContactScheduler::CalcClock(const Context &context, - BasicVector *clock) const { +void ContactScheduler::CalcClock(const Context& context, + BasicVector* clock) const { // Read in lcm message time - const OutputVector *robot_output = - (OutputVector *) - this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); clock->get_mutable_value()(0) = current_time; } void ContactScheduler::CalcContactScheduler( - const Context &context, BasicVector *contact_timing) const { + const Context& context, BasicVector* contact_timing) const { // Read in lcm message time RUNNING_FSM_STATE current_state_ = - (RUNNING_FSM_STATE) context.get_discrete_state(stored_fsm_state_index_)[0]; + (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; + double nominal_stance_duration = + context.get_discrete_state(nominal_state_durations_index_)[0]; + double nominal_flight_duration = + context.get_discrete_state(nominal_state_durations_index_)[1]; auto transition_times = - context.get_abstract_state>(transition_times_index_); + context.get_discrete_state(transition_times_index_).value(); if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_STANCE) { contact_timing->get_mutable_value()(0) = transition_times[LEFT_STANCE]; contact_timing->get_mutable_value()(1) = transition_times[LEFT_FLIGHT]; @@ -254,9 +293,40 @@ void ContactScheduler::CalcContactScheduler( contact_timing->get_mutable_value()(1) = transition_times[RIGHT_FLIGHT]; } contact_timing->get_mutable_value()(2) = transition_times[LEFT_FLIGHT]; - contact_timing->get_mutable_value()(3) = transition_times[LEFT_STANCE]; + contact_timing->get_mutable_value()(3) = transition_times[LEFT_FLIGHT] + + 2 * nominal_flight_duration + + nominal_stance_duration; contact_timing->get_mutable_value()(4) = transition_times[RIGHT_FLIGHT]; - contact_timing->get_mutable_value()(5) = transition_times[RIGHT_STANCE]; + contact_timing->get_mutable_value()(5) = transition_times[RIGHT_FLIGHT] + + 2 * nominal_flight_duration + + nominal_stance_duration; +} + +void ContactScheduler::OutputDebuggingInfo( + const drake::systems::Context& context, + dairlib::lcmt_contact_timing* debug_info) const { + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto& upcoming_transitions = context.get_abstract_state< + std::vector>>( + upcoming_transitions_index_); + auto stored_fsm_state = + (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; + debug_info->utime = robot_output->get_timestamp() * 1e6; + + debug_info->n_transitions = 4; + debug_info->active_fsm_state = stored_fsm_state; + debug_info->transition_times.clear(); + debug_info->transition_times = std::vector(4); + debug_info->transition_states.clear(); + debug_info->transition_states = std::vector(4); + debug_info->fsm_state_names = {"LEFT_STANCE", "RIGHT_STANCE", "LEFT_FLIGHT", + "RIGHT_FLIGHT"}; + + for (int i = 0; i < debug_info->n_transitions; ++i) { + debug_info->transition_times.at(i) = upcoming_transitions[i].first; + debug_info->transition_states.at(i) = upcoming_transitions[i].second; + } } } // namespace dairlib diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index a2012e7a63..4dc4a7da56 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -1,71 +1,74 @@ #pragma once -#include #include +#include #include #include #include "common/blending_utils.h" - #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" +#include "dairlib/lcmt_contact_timing.hpp" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/leaf_system.h" namespace dairlib { -enum RUNNING_FSM_STATE { - LEFT_STANCE, RIGHT_STANCE, LEFT_FLIGHT, RIGHT_FLIGHT -}; +enum RUNNING_FSM_STATE { LEFT_STANCE, RIGHT_STANCE, LEFT_FLIGHT, RIGHT_FLIGHT }; class ContactScheduler : public drake::systems::LeafSystem { public: - ContactScheduler( - const drake::multibody::MultibodyPlant &plant, - std::set& impact_states, - double near_impact_threshold = 0, - double tau = 0.0025, - BLEND_FUNC blend_func = SIGMOID); - - void SetSLIPParams(double rest_length) { - rest_length_; - } - const drake::systems::InputPort &get_input_port_state() const { + ContactScheduler(const drake::multibody::MultibodyPlant& plant, + std::set& impact_states, + double near_impact_threshold = 0, double tau = 0.0025, + BLEND_FUNC blend_func = SIGMOID); + + void SetSLIPParams(double rest_length) { rest_length_; } + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } - const drake::systems::OutputPort &get_output_port_fsm() const { + const drake::systems::OutputPort& get_output_port_fsm() const { return this->get_output_port(fsm_port_); } - const drake::systems::OutputPort &get_output_port_clock() const { + const drake::systems::OutputPort& get_output_port_clock() const { return this->get_output_port(clock_port_); } - const drake::systems::OutputPort &get_output_port_impact() const { + const drake::systems::OutputPort& get_output_port_impact_info() const { return this->get_output_port(impact_info_port_); } - const drake::systems::OutputPort &get_output_port_contact_scheduler() const { + const drake::systems::OutputPort& get_output_port_contact_scheduler() + const { return this->get_output_port(contact_scheduler_port_); } + const drake::systems::OutputPort& get_output_port_debug_info() + const { + return this->get_output_port(debug_port_); + } private: drake::systems::EventStatus UpdateTransitionTimes( - const drake::systems::Context &context, + const drake::systems::Context& context, drake::systems::State* state) const; - void CalcNextImpactInfo(const drake::systems::Context &context, - systems::ImpactInfoVector *near_impact) const; - void CalcFiniteState(const drake::systems::Context &context, - drake::systems::BasicVector *fsm_state) const; - void CalcClock(const drake::systems::Context &context, - drake::systems::BasicVector *clock) const; - void CalcContactScheduler(const drake::systems::Context &context, - drake::systems::BasicVector *clock) const; + void CalcNextImpactInfo(const drake::systems::Context& context, + systems::ImpactInfoVector* near_impact) const; + void CalcFiniteState(const drake::systems::Context& context, + drake::systems::BasicVector* fsm_state) const; + void CalcClock(const drake::systems::Context& context, + drake::systems::BasicVector* clock) const; + void CalcContactScheduler( + const drake::systems::Context& context, + drake::systems::BasicVector* contact_timing) const; + void OutputDebuggingInfo(const drake::systems::Context& context, + dairlib::lcmt_contact_timing* debug_info) const; drake::systems::InputPortIndex state_port_; drake::systems::OutputPortIndex fsm_port_; drake::systems::OutputPortIndex clock_port_; -// drake::systems::OutputPortIndex contact_timing_; + // drake::systems::OutputPortIndex contact_timing_; drake::systems::OutputPortIndex impact_info_port_; drake::systems::OutputPortIndex contact_scheduler_port_; + drake::systems::OutputPortIndex debug_port_; // For impact-invariant calculations const std::set impact_states_; @@ -73,13 +76,14 @@ class ContactScheduler : public drake::systems::LeafSystem { double tau_; const BLEND_FUNC blend_func_; - -// const drake::multibody::MultibodyPlant& plant_; + // const drake::multibody::MultibodyPlant& plant_; /// contains pairs (start of fsm, fsm_state) - /// the order of the vector goes: last transition, next upcoming three transitions -// mutable std::vector> upcoming_transitions_; // sorted by upcoming time -// mutable std::vector transition_times_; // fixed order by RUNNING_FSM_STATE + /// the order of the vector goes: last transition, next upcoming three + /// transitions + // mutable std::vector> + // upcoming_transitions_; // sorted by upcoming time mutable + // std::vector transition_times_; // fixed order by RUNNING_FSM_STATE int initial_state_ = 0; @@ -88,14 +92,12 @@ class ContactScheduler : public drake::systems::LeafSystem { drake::systems::DiscreteStateIndex stored_transition_time_index_; // estimates of state durations for stance and flight in seconds drake::systems::DiscreteStateIndex nominal_state_durations_index_; + drake::systems::DiscreteStateIndex transition_times_index_; - drake::systems::AbstractStateIndex transition_times_index_; drake::systems::AbstractStateIndex upcoming_transitions_index_; /// SLIP parameters double rest_length_; - - }; } // namespace dairlib diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index b54bcf4b7c..bde4c19d08 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -439,62 +439,62 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /*****Connect ports*****/ // OSC connections - builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_impact(), - osc->get_near_impact_input_port()); - builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); + builder.Connect(fsm->get_fsm_output_port(), osc->get_input_port_fsm()); + builder.Connect(fsm->get_output_port_impact_info(), + osc->get_input_port_impact_info()); + builder.Connect(fsm->get_output_port_clock(), osc->get_input_port_clock()); builder.Connect(state_receiver->get_output_port(0), ekf_filter->get_input_port()); builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); // Trajectory generator connections builder.Connect(state_receiver->get_output_port(0), pelvis_trans_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(fsm->get_fsm_output_port(), pelvis_trans_traj_generator->get_fsm_input_port()); builder.Connect(fsm->get_output_port_clock(), pelvis_trans_traj_generator->get_clock_input_port()); builder.Connect(high_level_command->get_xy_output_port(), - l_foot_traj_generator->get_target_vel_input_port()); + l_foot_traj_generator->get_input_port_target_vel()); builder.Connect(high_level_command->get_xy_output_port(), - r_foot_traj_generator->get_target_vel_input_port()); + r_foot_traj_generator->get_input_port_target_vel()); builder.Connect(state_receiver->get_output_port(0), - l_foot_traj_generator->get_state_input_port()); + l_foot_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - r_foot_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - l_foot_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_fsm(), - r_foot_traj_generator->get_fsm_input_port()); + r_foot_traj_generator->get_input_port_state()); + builder.Connect(fsm->get_fsm_output_port(), + l_foot_traj_generator->get_input_port_fsm()); + builder.Connect(fsm->get_fsm_output_port(), + r_foot_traj_generator->get_input_port_fsm()); builder.Connect(state_receiver->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); // OSC connections builder.Connect(pelvis_trans_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_trans_traj")); + osc->get_input_port_tracking_data("pelvis_trans_traj")); builder.Connect(state_receiver->get_output_port(0), heading_traj_generator->get_state_input_port()); builder.Connect(high_level_command->get_yaw_output_port(), heading_traj_generator->get_yaw_input_port()); builder.Connect(heading_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_traj")); + osc->get_input_port_tracking_data("pelvis_rot_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_traj")); + osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_traj")); + osc->get_input_port_tracking_data("right_ft_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_z_traj")); + osc->get_input_port_tracking_data("left_ft_z_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_z_traj")); + osc->get_input_port_tracking_data("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); + osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); + osc->get_input_port_tracking_data("right_toe_angle_traj")); builder.Connect(osc->get_osc_output_port(), command_sender->get_input_port(0)); builder.Connect(radio_parser->get_output_port(), diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index d219796c24..7df5075b82 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -473,7 +473,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( builder.Connect(high_level_command->get_yaw_output_port(), head_traj_gen->get_yaw_input_port()); builder.Connect(state_receiver->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); builder.Connect(fsm->get_output_port(0), liftoff_event_time->get_input_port_fsm()); builder.Connect(state_receiver->get_output_port(0), @@ -505,25 +505,25 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( builder.Connect(high_level_command->get_xy_output_port(), swing_ft_traj_generator->get_input_port_vdes()); builder.Connect(state_receiver->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); - builder.Connect(fsm->get_output_port(0), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port(0), osc->get_input_port_fsm()); builder.Connect( pelvis_traj_generator->get_output_port_lipm_from_touchdown(), - osc->get_tracking_data_input_port("lipm_traj")); + osc->get_input_port_tracking_data("lipm_traj")); builder.Connect(swing_ft_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("swing_ft_traj")); + osc->get_input_port_tracking_data("swing_ft_traj")); builder.Connect(head_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_heading_traj")); + osc->get_input_port_tracking_data("pelvis_heading_traj")); builder.Connect(head_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_balance_traj")); + osc->get_input_port_tracking_data("pelvis_balance_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); + osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); + osc->get_input_port_tracking_data("right_toe_angle_traj")); builder.Connect(osc->get_output_port(0), command_sender->get_input_port(0)); builder.Connect(radio_parser->get_output_port(), high_level_command->get_radio_input_port()); diff --git a/examples/Cassie/osc/swing_toe_traj_generator.h b/examples/Cassie/osc/swing_toe_traj_generator.h index 5f47f5051a..245ac574fe 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.h +++ b/examples/Cassie/osc/swing_toe_traj_generator.h @@ -21,7 +21,7 @@ class SwingToeTrajGenerator : public drake::systems::LeafSystem { const std::string& traj_name); // Input/output ports - const drake::systems::InputPort& get_state_input_port() const { + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index d7b8d61814..85de595457 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -99,6 +99,7 @@ cc_library( "//multibody:utils", "//lcmtypes:lcmt_robot", "//systems/controllers/osc:osc_gains", + "//examples/Cassie/contact_scheduler:all", "//systems/primitives", "@drake//:drake_shared_library", ], diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index d0e9e2b186..5ad76a10c3 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -5,6 +5,7 @@ #include #include "dairlib/lcmt_radio_out.hpp" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include "multibody/multibody_utils.h" using Eigen::Map; @@ -30,10 +31,10 @@ using drake::trajectories::Trajectory; namespace dairlib::examples::osc_run { -FootTrajGenerator::FootTrajGenerator(const MultibodyPlant &plant, - Context *context, - const string &foot_name, - const string &hip_name, bool relative_feet, +FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, + Context* context, + const string& foot_name, + const string& hip_name, bool relative_feet, const int stance_state, std::vector state_durations) : plant_(plant), @@ -45,7 +46,7 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant &plant, stance_state_(stance_state), state_durations_(state_durations) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); - Trajectory &traj_inst = empty_pp_traj; + Trajectory& traj_inst = empty_pp_traj; if (foot_name == "toe_left") { is_left_foot_ = true; @@ -61,19 +62,19 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant &plant, // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); target_vel_port_ = this->DeclareVectorInputPort( - "v_des", BasicVector(VectorXd::Zero(2))) - .get_index(); + "v_des", BasicVector(VectorXd::Zero(2))) + .get_index(); fsm_port_ = this->DeclareVectorInputPort( - "fsm", BasicVector(VectorXd::Zero(1))) - .get_index(); + "fsm", BasicVector(VectorXd::Zero(1))) + .get_index(); clock_port_ = this->DeclareVectorInputPort( - "clock", BasicVector(VectorXd::Zero(1))) - .get_index(); + "clock", BasicVector(VectorXd::Zero(1))) + .get_index(); radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) @@ -96,11 +97,11 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant &plant, } EventStatus FootTrajGenerator::DiscreteVariableUpdate( - const Context &context, - DiscreteValues *discrete_state) const { + const Context& context, + DiscreteValues* discrete_state) const { // Read in current state - const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); // Read in finite state machine VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); @@ -124,20 +125,21 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( // Only update the current foot position when in stance ( if (fsm_state(0) == stance_state_) { auto foot_pos = discrete_state->get_mutable_vector(initial_foot_pos_idx_) - .get_mutable_value(); + .get_mutable_value(); plant_.CalcPointsPositions(*context_, foot_frame_, Vector3d::Zero(), world_, &foot_pos); auto hip_pos = discrete_state->get_mutable_vector(initial_hip_pos_idx_) - .get_mutable_value(); + .get_mutable_value(); plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, &hip_pos); foot_pos = rot.transpose() * foot_pos; hip_pos = rot.transpose() * hip_pos; auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - .get_mutable_value(); + .get_mutable_value(); pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; - auto last_stance_time = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - .get_mutable_value(); + auto last_stance_time = + discrete_state->get_mutable_vector(pelvis_vel_est_idx_) + .get_mutable_value(); last_stance_time[0] = robot_output->get_timestamp(); // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; @@ -150,20 +152,20 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( } PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( - const drake::systems::Context &context) const { + const drake::systems::Context& context) const { const auto robot_output = this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); double clock = this->EvalVectorInput(context, clock_port_)->get_value()(0); - const auto &mode_lengths = + const auto& mode_lengths = this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); // Offset between 0 and 2 double lateral_radio_tuning = 1.0; double sagital_radio_tuning = 1.0; if (this->get_input_port(radio_port_).HasValue(context)) { - const auto &radio_out = + const auto& radio_out = this->EvalInputValue(context, radio_port_); lateral_radio_tuning += radio_out->channel[4]; sagital_radio_tuning += radio_out->channel[5]; @@ -222,45 +224,44 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector T_waypoints_2; // Storing old method for record keeping - T_waypoints = {state_durations_[1], - state_durations_[1] + - 0.5 * (state_durations_[4] - state_durations_[1]), - state_durations_[4]}; - -// T_waypoints_0 = { -// state_durations_[0], -// (state_durations_[3] - state_durations_[4]) + -// 0.5 * (0.1 + state_durations_[2] - state_durations_[0]), -// state_durations_[2]}; -// T_waypoints_1 = {state_durations_[2], state_durations_[3]}; -// T_waypoints_2 = {state_durations_[3], state_durations_[4]}; -// -// - - - if( is_left_foot_){ -// std::cout << "is left foot: " << is_left_foot_ << std::endl; + T_waypoints = { + state_durations_[1], + state_durations_[1] + 0.5 * (state_durations_[4] - state_durations_[1]), + state_durations_[4]}; + + // T_waypoints_0 = { + // state_durations_[0], + // (state_durations_[3] - state_durations_[4]) + + // 0.5 * (0.1 + state_durations_[2] - state_durations_[0]), + // state_durations_[2]}; + // T_waypoints_1 = {state_durations_[2], state_durations_[3]}; + // T_waypoints_2 = {state_durations_[3], state_durations_[4]}; + // + // + + if (is_left_foot_) { + // std::cout << "is left foot: " << is_left_foot_ << std::endl; T_waypoints = {left_t0, left_t0 + 0.6 * (left_tf - left_t0), left_tf}; -// std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; -// std::cout << left_t0 << std::endl; -// std::cout << left_t0 + 0.6 * (left_tf - left_t0) << std::endl; -// std::cout << left_tf << std::endl; - } - else{ -// std::cout << "is left foot: " << is_left_foot_ << std::endl; + // std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; + // std::cout << left_t0 << std::endl; + // std::cout << left_t0 + 0.6 * (left_tf - left_t0) << std::endl; + // std::cout << left_tf << std::endl; + } else { + // std::cout << "is left foot: " << is_left_foot_ << std::endl; T_waypoints = {right_t0, right_t0 + 0.6 * (right_tf - right_t0), right_tf}; -// std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; -// std::cout << right_t0 << std::endl; -// std::cout << right_t0 + 0.6 * (right_tf - right_t0) << std::endl; -// std::cout << right_tf << std::endl; + // std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; + // std::cout << right_t0 << std::endl; + // std::cout << right_t0 + 0.6 * (right_tf - right_t0) << std::endl; + // std::cout << right_tf << std::endl; } - // T_waypoints_0 = { -// pelvis_t0, -// (state_durations_[3] - state_durations_[4]) + -// 1.5 / 3.0 * (0.1 + state_durations_[2] - pelvis_t0), -// state_durations_[2]}; -// T_waypoints_1 = {state_durations_[2], state_durations_[3]}; -// T_waypoints_2 = {state_durations_[3], state_durations_[4]}; +// std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; + // T_waypoints_0 = { + // pelvis_t0, + // (state_durations_[3] - state_durations_[4]) + + // 1.5 / 3.0 * (0.1 + state_durations_[2] - pelvis_t0), + // state_durations_[2]}; + // T_waypoints_1 = {state_durations_[2], state_durations_[3]}; + // T_waypoints_2 = {state_durations_[3], state_durations_[4]}; // auto foot_pos = // context.get_discrete_state(initial_foot_pos_idx_).get_value(); @@ -287,19 +288,22 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -lateral_offset_); } -// MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); -// MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); -// Y_dot_end(2) = -0.1; - -// PiecewisePolynomial swing_foot_spline = -// PiecewisePolynomial::CubicWithContinuousSecondDerivatives( -// T_waypoints, Y, Y_dot_start, Y_dot_end); + // MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); + // MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); + // Y_dot_end(2) = -0.1; + + // PiecewisePolynomial swing_foot_spline = + // PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + // T_waypoints, Y, Y_dot_start, Y_dot_end); +// std::cout << "is left foot: " << is_left_foot_ << std::endl; +// for (auto& t :T_waypoints){ +// std::cout << "t: " << t << std::endl; +// } PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, false); return swing_foot_spline; - if (is_left_foot_) { return swing_foot_spline; } else { @@ -327,17 +331,17 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); offset_swing_foot_spline.ConcatenateInTime( PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); -// for (auto t: offset_swing_foot_spline.get_segment_times()) { -// std::cout << t << std::endl; -// } + // for (auto t: offset_swing_foot_spline.get_segment_times()) { + // std::cout << t << std::endl; + // } return offset_swing_foot_spline; } // return swing_foot_spline; } void FootTrajGenerator::CalcTraj( - const drake::systems::Context &context, - drake::trajectories::Trajectory *traj) const { + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { // Read in current state // const auto robot_output = // this->template EvalVectorInput(context, state_port_); @@ -345,15 +349,30 @@ void FootTrajGenerator::CalcTraj( // double timestamp = robot_output->get_timestamp(); // // // Read in finite state machine - // const auto fsm_state = this->EvalVectorInput(context, - // fsm_port_)->get_value(); + const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value()[0]; - auto *casted_traj = - (PiecewisePolynomial *) dynamic_cast *>( + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( traj); - // if (fsm_state[0] == FLIGHT) { - *casted_traj = GenerateFlightTraj(context); - // } + if (is_left_foot_ ) { + if(fsm_state != LEFT_STANCE){ +// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); + *casted_traj = GenerateFlightTraj(context); + } +// else{ +// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); +// } + + } + else{ + if(fsm_state != RIGHT_STANCE){ + *casted_traj = GenerateFlightTraj(context); +// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); + } +// else{ +// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); +// } + } } } // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 783fdee6a6..7d110611e5 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -17,22 +17,22 @@ class FootTrajGenerator : public drake::systems::LeafSystem { bool relative_feet, int stance_state, std::vector state_durations); - const drake::systems::InputPort& get_state_input_port() const { + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } - const drake::systems::InputPort& get_fsm_input_port() const { + const drake::systems::InputPort& get_input_port_fsm() const { return this->get_input_port(fsm_port_); } - const drake::systems::InputPort& get_clock_input_port() const { + const drake::systems::InputPort& get_input_port_clock() const { return this->get_input_port(clock_port_); } - const drake::systems::InputPort& get_target_vel_input_port() const { + const drake::systems::InputPort& get_input_port_target_vel() const { return this->get_input_port(target_vel_port_); } - const drake::systems::InputPort& get_radio_input_port() const { + const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); } - const drake::systems::InputPort& get_contact_scheduler_input_port() const { + const drake::systems::InputPort& get_input_port_contact_scheduler() const { return this->get_input_port(contact_scheduler_port_); } diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 3ca9265a05..66fafe9e0f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -38,8 +38,8 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 2.5 -hip_yaw_kp: 40 -hip_yaw_kd: 1 +hip_yaw_kp: 100 +hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.08 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 13cfec6ce5..08d0e0d605 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -36,7 +36,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( const std::unordered_map< int, std::vector&>>>& - feet_contact_points, + feet_contact_points, bool relative_pelvis) : plant_(plant), context_(context), @@ -49,14 +49,14 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( this->set_name("pelvis_trans_traj_generator"); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); + "x, u, t", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) - .get_index(); + .get_index(); contact_scheduler_port_ = this->DeclareVectorInputPort("t_mode", BasicVector(6)) .get_index(); @@ -132,15 +132,15 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( } // samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, // rest_length_ + 0.05, rest_length_; -// samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + 0.05; - // samples_dot << 0, 0, 0, 0, 0.25, 0.0; + // samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + + // 0.05; samples_dot << 0, 0, 0, 0, 0.25, 0.0; return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); // return PiecewisePolynomial::FirstOrderHold(breaks, samples); // return PiecewisePolynomial::CubicHermite( // breaks, samples, samples_dot); // return PiecewisePolynomial::CubicShapePreserving(breaks, samples); -// return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( -// breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); + // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + // breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); } void PelvisTransTrajGenerator::CalcTraj( @@ -163,7 +163,7 @@ void PelvisTransTrajGenerator::CalcTraj( // std::cout << "mode_length end: " << mode_length[1] << std::endl; auto* casted_traj = - (PiecewisePolynomial*) dynamic_cast*>( + (PiecewisePolynomial*)dynamic_cast*>( traj); // const drake::VectorX& x = robot_output->GetState(); if (fsm_state == 0 || fsm_state == 1) { diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 22a6760949..91951b6b66 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -94,6 +94,9 @@ DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); DEFINE_double(actuator_limit, 1.0, "Conservative estimate scaling factor for actuator limits, 1.0 is at the actual actuator limits."); +DEFINE_double(input_delta, + 50.0, + "Maximum change in torques between knot points."); namespace dairlib { @@ -595,8 +598,10 @@ void SetKinematicConstraints(Dircon *trajopt, prog->AddBoundingBoxConstraint(u_min, u_max, ui); if (i < trajopt->N() - 1) { auto uip1 = trajopt->input(i + 1); - prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); - prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); +// prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); +// prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); + prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, FLAGS_input_delta)); + prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -FLAGS_input_delta)); } } @@ -824,7 +829,7 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); - MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); + MatrixXd R = 1e-1 * MatrixXd::Identity(n_u, n_u); // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = // 5e-1; // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 457c2acb38..7274d8811d 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -487,25 +487,25 @@ int DoMain(int argc, char* argv[]) { /*****Connect ports*****/ // OSC connections - builder.Connect(fsm->get_fsm_output_port(), osc->get_fsm_input_port()); - builder.Connect(fsm->get_clock_output_port(), osc->get_clock_input_port()); + builder.Connect(fsm->get_fsm_output_port(), osc->get_input_port_fsm()); + builder.Connect(fsm->get_clock_output_port(), osc->get_input_port_clock()); builder.Connect(fsm->get_impact_output_port(), - osc->get_near_impact_input_port()); + osc->get_input_port_impact_info()); builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); builder.Connect(pelvis_trans_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_trans_traj")); + osc->get_input_port_tracking_data("pelvis_trans_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_traj")); + osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_traj")); + osc->get_input_port_tracking_data("right_ft_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); + osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); + osc->get_input_port_tracking_data("right_toe_angle_traj")); builder.Connect( pelvis_rot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_tracking_data")); + osc->get_input_port_tracking_data("pelvis_rot_tracking_data")); // FSM connections builder.Connect(contact_results_sub->get_output_port(), diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index fd98afd51b..bc27e3c121 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -8,6 +8,7 @@ #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" @@ -38,7 +39,6 @@ #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" -#include "examples/Cassie/contact_scheduler/contact_scheduler.h" namespace dairlib { @@ -145,9 +145,10 @@ int DoMain(int argc, char* argv[]) { /**** FSM and contact mode configuration ****/ - vector fsm_states = {RUNNING_FSM_STATE::LEFT_STANCE, RUNNING_FSM_STATE::LEFT_FLIGHT, - RUNNING_FSM_STATE::RIGHT_STANCE, RUNNING_FSM_STATE::RIGHT_FLIGHT, - RUNNING_FSM_STATE::LEFT_STANCE}; + vector fsm_states = { + RUNNING_FSM_STATE::LEFT_STANCE, RUNNING_FSM_STATE::LEFT_FLIGHT, + RUNNING_FSM_STATE::RIGHT_STANCE, RUNNING_FSM_STATE::RIGHT_FLIGHT, + RUNNING_FSM_STATE::LEFT_STANCE}; vector state_durations = { osc_gains.stance_duration, osc_gains.flight_duration, @@ -157,7 +158,7 @@ int DoMain(int argc, char* argv[]) { std::cout << accumulated_state_durations.back() << std::endl; for (double state_duration : state_durations) { accumulated_state_durations.push_back(accumulated_state_durations.back() + - state_duration); + state_duration); std::cout << accumulated_state_durations.back() << std::endl; } accumulated_state_durations.pop_back(); @@ -166,7 +167,8 @@ int DoMain(int argc, char* argv[]) { auto contact_scheduler = builder.AddSystem( plant, impact_states, gains.impact_threshold, gains.impact_tau); auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, gains.impact_threshold, gains.impact_tau); + plant, fsm_states, state_durations, 0.0, gains.impact_threshold, + gains.impact_tau); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -184,11 +186,13 @@ int DoMain(int argc, char* argv[]) { auto failure_aggregator = builder.AddSystem(FLAGS_channel_u, 1); - auto cassie_out_to_radio = - builder.AddSystem(); + auto cassie_out_to_radio = builder.AddSystem(); auto controller_failure_pub = builder.AddSystem( LcmPublisherSystem::Make( "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto contact_scheduler_debug_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + "CONTACT_TIMING", &lcm, TriggerTypeSet({TriggerType::kForced}))); std::vector tau = {.05, .01, .01}; auto ekf_filter = builder.AddSystem(plant, tau); @@ -200,9 +204,9 @@ int DoMain(int argc, char* argv[]) { osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight(1e-4 * - gains.W_lambda_c_regularization); + gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); + gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(gains.w_soft_constraint); @@ -225,10 +229,14 @@ int DoMain(int argc, char* argv[]) { plant, right_heel.first, right_heel.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_toe_evaluator); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_heel_evaluator); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_toe_evaluator); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + &left_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + &left_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + &right_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + &right_heel_evaluator); multibody::KinematicEvaluatorSet evaluators(plant); auto left_loop = LeftLoopClosureEvaluator(plant); @@ -255,10 +263,14 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); -// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_fixed_knee_spring); -// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_fixed_knee_spring); -// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, &left_fixed_ankle_spring); -// osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_fixed_ankle_spring); + // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + // &left_fixed_knee_spring); + // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + // &right_fixed_knee_spring); + // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + // &left_fixed_ankle_spring); + // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + // &right_fixed_ankle_spring); osc->AddKinematicConstraint(&evaluators); @@ -307,20 +319,22 @@ int DoMain(int argc, char* argv[]) { auto right_foot_tracking_data = std::make_unique( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); - pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); - stance_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, - "toe_left"); - stance_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, - "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, - "toe_left"); - right_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, - "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, - "toe_left"); - right_foot_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, - "toe_right"); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, + "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, + "pelvis"); + stance_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_left"); + stance_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); auto left_foot_yz_tracking_data = std::make_unique( @@ -330,10 +344,10 @@ int DoMain(int argc, char* argv[]) { std::make_unique( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_foot_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, - "toe_left"); - right_foot_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, - "toe_right"); + left_foot_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + right_foot_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); auto left_hip_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -341,12 +355,14 @@ int DoMain(int argc, char* argv[]) { auto right_hip_tracking_data = std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, - "pelvis"); - left_hip_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, - "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); auto left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -355,10 +371,10 @@ int DoMain(int argc, char* argv[]) { std::make_unique( "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - left_hip_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, - "pelvis"); - right_hip_yz_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, - "pelvis"); + left_hip_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + right_hip_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); auto left_foot_rel_tracking_data = std::make_unique( @@ -393,21 +409,26 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], RUNNING_FSM_STATE::LEFT_STANCE); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], RUNNING_FSM_STATE::RIGHT_STANCE); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], RUNNING_FSM_STATE::LEFT_STANCE); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], RUNNING_FSM_STATE::RIGHT_STANCE); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], RUNNING_FSM_STATE::LEFT_STANCE); -// pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], RUNNING_FSM_STATE::RIGHT_STANCE); - - -// left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); -// right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); + // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], + // RUNNING_FSM_STATE::LEFT_STANCE); + // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], + // RUNNING_FSM_STATE::RIGHT_STANCE); + // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], + // RUNNING_FSM_STATE::LEFT_STANCE); + // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], + // RUNNING_FSM_STATE::RIGHT_STANCE); + // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], + // RUNNING_FSM_STATE::LEFT_STANCE); + // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], + // RUNNING_FSM_STATE::RIGHT_STANCE); + + // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); + // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); pelvis_trans_rel_tracking_data->DisableFeedforwardAccel({2}); -// left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); -// right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); -// left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); -// right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); + // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); + // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); @@ -428,14 +449,14 @@ int DoMain(int argc, char* argv[]) { auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::LEFT_STANCE, - "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, - "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::RIGHT_FLIGHT, - "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(RUNNING_FSM_STATE::LEFT_FLIGHT, - "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -501,79 +522,105 @@ int DoMain(int argc, char* argv[]) { /*****Connect ports*****/ // OSC connections - builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_contact_scheduler(), - pelvis_trans_traj_generator->get_contact_scheduler_input_port()); - builder.Connect(fsm->get_output_port_contact_scheduler(), - l_foot_traj_generator->get_contact_scheduler_input_port()); - builder.Connect(fsm->get_output_port_contact_scheduler(), - r_foot_traj_generator->get_contact_scheduler_input_port()); - builder.Connect(fsm->get_output_port_impact(), - osc->get_near_impact_input_port()); - builder.Connect(fsm->get_output_port_clock(), osc->get_clock_input_port()); + builder.Connect(fsm->get_output_port_fsm(), osc->get_input_port_fsm()); + builder.Connect(fsm->get_output_port_impact_info(), + osc->get_input_port_impact_info()); + builder.Connect(fsm->get_output_port_clock(), osc->get_input_port_clock()); + // builder.Connect(contact_scheduler->get_output_port_fsm(), + // osc->get_input_port_fsm()); + // builder.Connect(contact_scheduler->get_output_port_impact_info(), + // osc->get_input_port_impact_info()); + // builder.Connect(contact_scheduler->get_output_port_clock(), + // osc->get_input_port_clock()); + builder.Connect(state_receiver->get_output_port(0), ekf_filter->get_input_port()); builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); + // FSM connections builder.Connect(state_receiver->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), contact_scheduler->get_input_port_state()); // Trajectory generator connections + + // builder.Connect(contact_scheduler->get_output_port_fsm(), + // l_foot_traj_generator->get_input_port_fsm()); + // builder.Connect(contact_scheduler->get_output_port_fsm(), + // r_foot_traj_generator->get_input_port_fsm()); + // builder.Connect( + // contact_scheduler->get_output_port_contact_scheduler(), + // pelvis_trans_traj_generator->get_input_port_contact_scheduler()); + // builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + // l_foot_traj_generator->get_input_port_contact_scheduler()); + // builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + // r_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect( + contact_scheduler->get_output_port_contact_scheduler(), + pelvis_trans_traj_generator->get_contact_scheduler_input_port()); +// builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), +// l_foot_traj_generator->get_input_port_contact_scheduler()); +// builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), +// r_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(fsm->get_output_port_contact_scheduler(), + l_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(fsm->get_output_port_contact_scheduler(), + r_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(state_receiver->get_output_port(0), pelvis_trans_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(contact_scheduler->get_output_port_fsm(), pelvis_trans_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_clock(), + builder.Connect(contact_scheduler->get_output_port_clock(), pelvis_trans_traj_generator->get_clock_input_port()); builder.Connect(high_level_command->get_xy_output_port(), - l_foot_traj_generator->get_target_vel_input_port()); + l_foot_traj_generator->get_input_port_target_vel()); builder.Connect(high_level_command->get_xy_output_port(), - r_foot_traj_generator->get_target_vel_input_port()); + r_foot_traj_generator->get_input_port_target_vel()); builder.Connect(state_receiver->get_output_port(0), - l_foot_traj_generator->get_state_input_port()); + l_foot_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - r_foot_traj_generator->get_state_input_port()); + r_foot_traj_generator->get_input_port_state()); builder.Connect(cassie_out_to_radio->get_output_port(), - l_foot_traj_generator->get_radio_input_port()); + l_foot_traj_generator->get_input_port_radio()); builder.Connect(cassie_out_to_radio->get_output_port(), - r_foot_traj_generator->get_radio_input_port()); + r_foot_traj_generator->get_input_port_radio()); - builder.Connect(fsm->get_output_port_clock(), - l_foot_traj_generator->get_clock_input_port()); - builder.Connect(fsm->get_output_port_clock(), - r_foot_traj_generator->get_clock_input_port()); + builder.Connect(contact_scheduler->get_output_port_clock(), + l_foot_traj_generator->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_clock(), + r_foot_traj_generator->get_input_port_clock()); builder.Connect(fsm->get_output_port_fsm(), - l_foot_traj_generator->get_fsm_input_port()); + l_foot_traj_generator->get_input_port_fsm()); builder.Connect(fsm->get_output_port_fsm(), - r_foot_traj_generator->get_fsm_input_port()); + r_foot_traj_generator->get_input_port_fsm()); builder.Connect(state_receiver->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); // OSC connections builder.Connect(pelvis_trans_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_trans_traj")); + osc->get_input_port_tracking_data("pelvis_trans_traj")); builder.Connect(state_receiver->get_output_port(0), heading_traj_generator->get_state_input_port()); builder.Connect(high_level_command->get_yaw_output_port(), heading_traj_generator->get_yaw_input_port()); builder.Connect(heading_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_traj")); + osc->get_input_port_tracking_data("pelvis_rot_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_traj")); + osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_traj")); + osc->get_input_port_tracking_data("right_ft_traj")); builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("left_ft_z_traj")); + osc->get_input_port_tracking_data("left_ft_z_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("right_ft_z_traj")); + osc->get_input_port_tracking_data("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); + osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); + osc->get_input_port_tracking_data("right_toe_angle_traj")); // Publisher connections builder.Connect(cassie_out_receiver->get_output_port(), @@ -589,6 +636,8 @@ int DoMain(int argc, char* argv[]) { failure_aggregator->get_input_port(0)); builder.Connect(failure_aggregator->get_status_output_port(), controller_failure_pub->get_input_port()); + builder.Connect(contact_scheduler->get_output_port_debug_info(), + contact_scheduler_debug_publisher->get_input_port()); // Run lcm-driven simulation // Create the diagram diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 9a6e72c266..971e29cea2 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -279,9 +279,9 @@ int DoMain(int argc, char* argv[]) { command_sender->get_input_port(0)); builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); builder.Connect(com_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("com_traj")); + osc->get_input_port_tracking_data("com_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_rot_traj")); + osc->get_input_port_tracking_data("pelvis_rot_traj")); // Create the diagram auto owned_diagram = builder.Build(); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 10088e17b4..5c7933d7e1 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -221,7 +221,7 @@ int DoMain(int argc, char* argv[]) { auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); builder.Connect(state_receiver->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); // Create leafsystem that record the switching time of the FSM std::vector single_support_states = {left_stance_state, @@ -360,9 +360,9 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); builder.Connect(state_receiver->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); // Create Operational space control auto osc = builder.AddSystem( @@ -583,25 +583,25 @@ int DoMain(int argc, char* argv[]) { // Connect ports builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); - builder.Connect(fsm->get_output_port(0), osc->get_fsm_input_port()); + builder.Connect(fsm->get_output_port(0), osc->get_input_port_fsm()); if (use_pelvis_for_lipm_tracking) { builder.Connect( pelvis_traj_generator->get_output_port_lipm_from_touchdown(), - osc->get_tracking_data_input_port("lipm_traj")); + osc->get_input_port_tracking_data("lipm_traj")); } else { builder.Connect(lipm_traj_generator->get_output_port_lipm_from_touchdown(), - osc->get_tracking_data_input_port("lipm_traj")); + osc->get_input_port_tracking_data("lipm_traj")); } builder.Connect(swing_ft_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("swing_ft_traj")); + osc->get_input_port_tracking_data("swing_ft_traj")); builder.Connect(head_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_heading_traj")); + osc->get_input_port_tracking_data("pelvis_heading_traj")); builder.Connect(head_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_balance_traj")); + osc->get_input_port_tracking_data("pelvis_balance_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); + osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); + osc->get_input_port_tracking_data("right_toe_angle_traj")); builder.Connect(osc->get_output_port(0), command_sender->get_input_port(0)); if (FLAGS_publish_osc_data) { // Create osc debug sender. diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 45ca61d2e8..d71adb19e5 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -249,7 +249,7 @@ int DoMain(int argc, char* argv[]) { auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations, 0.0, osc_gains.impact_threshold); builder.Connect(simulator_drift->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); // Create leafsystem that record the switching time of the FSM std::vector single_support_states = {left_stance_state, @@ -258,7 +258,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, single_support_states); liftoff_event_time->set_name("liftoff_time"); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(fsm->get_fsm_output_port(), liftoff_event_time->get_input_port_fsm()); builder.Connect(simulator_drift->get_output_port(0), liftoff_event_time->get_input_port_state()); @@ -268,7 +268,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, double_support_states); touchdown_event_time->set_name("touchdown_time"); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(fsm->get_fsm_output_port(), touchdown_event_time->get_input_port_fsm()); builder.Connect(simulator_drift->get_output_port(0), touchdown_event_time->get_input_port_state()); @@ -358,9 +358,9 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); builder.Connect(pelvis_filt->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(pelvis_filt->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); // Create Operational space control auto osc = builder.AddSystem( @@ -573,7 +573,7 @@ int DoMain(int argc, char* argv[]) { if (FLAGS_use_radio) { builder.Connect(cassie_out_to_radio->get_output_port(), hip_yaw_traj_gen->get_radio_input_port()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(fsm->get_fsm_output_port(), hip_yaw_traj_gen->get_fsm_input_port()); osc->AddTrackingData(std::move(swing_hip_yaw_traj)); } else { @@ -594,22 +594,22 @@ int DoMain(int argc, char* argv[]) { // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_robot_output_input_port()); - builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); + builder.Connect(fsm->get_fsm_output_port(), osc->get_input_port_fsm()); builder.Connect(alip_traj_generator->get_output_port_com(), - osc->get_tracking_data_input_port("alip_com_traj")); + osc->get_input_port_tracking_data("alip_com_traj")); builder.Connect(swing_ft_traj_generator->get_output_port(0), - osc->get_tracking_data_input_port("swing_ft_traj")); + osc->get_input_port_tracking_data("swing_ft_traj")); builder.Connect(head_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_heading_traj")); + osc->get_input_port_tracking_data("pelvis_heading_traj")); builder.Connect(head_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("pelvis_balance_traj")); + osc->get_input_port_tracking_data("pelvis_balance_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("left_toe_angle_traj")); + osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), - osc->get_tracking_data_input_port("right_toe_angle_traj")); + osc->get_input_port_tracking_data("right_toe_angle_traj")); if (FLAGS_use_radio) { builder.Connect(hip_yaw_traj_gen->get_hip_yaw_output_port(), - osc->get_tracking_data_input_port("swing_hip_yaw_traj")); + osc->get_input_port_tracking_data("swing_hip_yaw_traj")); } builder.Connect(osc->get_output_port(0), command_sender->get_input_port(0)); if (FLAGS_publish_osc_data) { diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index b5b6d6b1e1..20b6c6e70b 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -22,7 +22,7 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( near_impact_threshold_(near_impact_threshold), tau_(tau), blend_func_(blend_func) { - + this->set_name("ImpactAwareTimeBasedFSM"); near_impact_port_ = this->DeclareVectorOutputPort("near_impact", ImpactInfoVector(0, 0, 0), diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index dea682c402..3e6f88f107 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -31,7 +31,7 @@ class ImpactTimeBasedFiniteStateMachine const drake::systems::OutputPort& get_output_port_clock() const { return this->get_output_port(clock_port_); } - const drake::systems::OutputPort& get_output_port_impact() const { + const drake::systems::OutputPort& get_output_port_impact_info() const { return this->get_output_port(near_impact_port_); } const drake::systems::OutputPort& get_output_port_contact_scheduler() const { diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 676e20e64d..fec6b4ffd7 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -177,7 +177,7 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(joint_tracking_data_vec[joint_idx])); builder.Connect(joint_trajs[joint_idx]->get_output_port(), - osc->get_tracking_data_input_port(joint_name + "_traj")); + osc->get_input_port_tracking_data(joint_name + "_traj")); } osc->SetOsqpSolverOptionsFromYaml( FLAGS_osqp_settings); @@ -188,14 +188,14 @@ int DoMain(int argc, char* argv[]) { /*****Connect ports*****/ // OSC connections - builder.Connect(fsm->get_output_port_fsm(), osc->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_impact(), - osc->get_near_impact_input_port()); + builder.Connect(fsm->get_fsm_output_port(), osc->get_input_port_fsm()); + builder.Connect(fsm->get_output_port_impact_info(), + osc->get_input_port_impact_info()); builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); // Publisher connections builder.Connect(osc->get_osc_output_port(), diff --git a/lcmtypes/lcmt_contact_timing.lcm b/lcmtypes/lcmt_contact_timing.lcm new file mode 100644 index 0000000000..4325b6d3db --- /dev/null +++ b/lcmtypes/lcmt_contact_timing.lcm @@ -0,0 +1,11 @@ +package dairlib; + +struct lcmt_contact_timing +{ + int64_t utime; + int16_t n_transitions; + int16_t active_fsm_state; + int16_t transition_states[n_transitions]; + double transition_times[n_transitions]; + string fsm_state_names[n_transitions]; +} diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index aed452f150..3b9334d37f 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1147,7 +1147,7 @@ void OperationalSpaceControl::CalcOptimalInput( double alpha = 0; int next_fsm_state = -1; - if (this->get_near_impact_input_port().HasValue(context)) { + if (this->get_input_port_impact_info().HasValue(context)) { auto impact_info = (ImpactInfoVector *) this->EvalVectorInput( context, impact_info_port_); alpha = impact_info->GetAlpha(); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 1b5336540f..b17754b252 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -85,7 +85,7 @@ namespace dairlib::systems::controllers { /// such as `PiecewisePolynomial` and `ExponentialPlusPiecewisePolynomial`. /// The users can connect the output ports of the desired trajectory blocks to /// the corresponding input ports of `OperationalSpaceControl` by using -/// the method get_tracking_data_input_port(). +/// the method get_input_port_tracking_data(). /// The procedure of setting up `OperationalSpaceControl`: /// 1. create an instance of `OperationalSpaceControl` @@ -118,16 +118,16 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const drake::systems::InputPort& get_robot_output_input_port() const { return this->get_input_port(state_port_); } - const drake::systems::InputPort& get_fsm_input_port() const { + const drake::systems::InputPort& get_input_port_fsm() const { return this->get_input_port(fsm_port_); } - const drake::systems::InputPort& get_clock_input_port() const { + const drake::systems::InputPort& get_input_port_clock() const { return this->get_input_port(clock_port_); } - const drake::systems::InputPort& get_near_impact_input_port() const { + const drake::systems::InputPort& get_input_port_impact_info() const { return this->get_input_port(impact_info_port_); } - const drake::systems::InputPort& get_tracking_data_input_port( + const drake::systems::InputPort& get_input_port_tracking_data( const std::string& name) const { try { return this->get_input_port(traj_name_to_port_index_map_.at(name)); diff --git a/systems/controllers/time_based_fsm.h b/systems/controllers/time_based_fsm.h index cec1e1685d..f22c596b68 100644 --- a/systems/controllers/time_based_fsm.h +++ b/systems/controllers/time_based_fsm.h @@ -41,11 +41,11 @@ class TimeBasedFiniteStateMachine : public drake::systems::LeafSystem { const std::vector& states, const std::vector& state_durations, double t0 = 0); - const drake::systems::InputPort& get_input_port_state() const { + const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); } - const drake::systems::OutputPort& get_output_port_fsm() const { + const drake::systems::OutputPort& get_fsm_output_port() const { return this->get_output_port(fsm_port_); } From 05f790b8c8bcf38131869983c851a8b5fdf0b5ab Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 9 Aug 2022 13:12:16 -0400 Subject: [PATCH 262/758] now implementing variable timings --- .../plot_configs/cassie_running_plot.yaml | 8 +- examples/Cassie/contact_scheduler/BUILD.bazel | 2 + .../contact_scheduler/contact_scheduler.cc | 163 ++++++++++-------- .../contact_scheduler/contact_scheduler.h | 13 +- .../Cassie/osc_run/osc_running_gains.yaml | 8 +- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 32 ++-- .../impact_aware_time_based_fsm.cc | 114 ++++++------ 8 files changed, 182 insertions(+), 160 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 3a8509de38..fc925fc748 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -14,14 +14,14 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true +plot_floating_base_positions: false plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true -plot_contact_forces: true +plot_contact_forces: false special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [ ] @@ -43,11 +43,11 @@ plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['pos', 'vel'] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['vel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [0, 2], 'derivs': ['pos'] }, -# left_ft_traj: {'dims': [0], 'derivs': ['pos']}, + left_ft_traj: {'dims': [2], 'derivs': ['vel']}, # left_ft_z_traj: {'dims': [0], 'derivs': ['pos']}, # right_ft_z_traj: {'dims': [0, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} diff --git a/examples/Cassie/contact_scheduler/BUILD.bazel b/examples/Cassie/contact_scheduler/BUILD.bazel index ce0982bafb..b2f603c7bf 100644 --- a/examples/Cassie/contact_scheduler/BUILD.bazel +++ b/examples/Cassie/contact_scheduler/BUILD.bazel @@ -19,6 +19,8 @@ cc_library( deps = [ "//lcmtypes:lcmt_robot", "//common", + "//multibody:utils", + "//examples/Cassie:cassie_utils", "//systems/primitives", "@drake//:drake_shared_library", ], diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 3784f86dca..803ba9c002 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -2,13 +2,17 @@ #include +#include + #include "common/eigen_utils.h" +#include "examples/Cassie/cassie_utils.h" +#include "multibody/multibody_utils.h" +using Eigen::Vector3d; using Eigen::VectorXd; -using std::cout; -using std::endl; using std::string; +using drake::multibody::Frame; using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteValues; @@ -18,14 +22,19 @@ using drake::systems::UnrestrictedUpdateEvent; namespace dairlib { +using drake::multibody::MultibodyPlant; +using drake::systems::Context; using systems::ImpactInfoVector; using systems::OutputVector; -ContactScheduler::ContactScheduler( - const drake::multibody::MultibodyPlant& plant, - std::set& impact_states, double near_impact_threshold, - double tau, BLEND_FUNC blend_func) - : near_impact_threshold_(near_impact_threshold), +ContactScheduler::ContactScheduler(const MultibodyPlant& plant, + Context* plant_context, + std::set& impact_states, + double near_impact_threshold, double tau, + BLEND_FUNC blend_func) + : plant_(plant), + plant_context_(plant_context), + near_impact_threshold_(near_impact_threshold), tau_(tau), blend_func_(blend_func), impact_states_(impact_states) { @@ -54,7 +63,7 @@ ContactScheduler::ContactScheduler( .get_index(); // Declare discrete states and update - stored_fsm_state_index_ = DeclareDiscreteState(1 * VectorXd::Ones(1)); + stored_fsm_state_index_ = DeclareDiscreteState(3 * VectorXd::Ones(1)); stored_robot_state_index_ = DeclareDiscreteState(plant.num_positions() + plant.num_velocities()); stored_transition_time_index_ = DeclareDiscreteState(1); @@ -64,7 +73,7 @@ ContactScheduler::ContactScheduler( DeclareDiscreteState(nominal_state_durations); std::vector> initial_state_transitions = {{-0.1, RIGHT_FLIGHT}, - {0.001, LEFT_STANCE}, + {0.00, LEFT_STANCE}, {0.25, LEFT_FLIGHT}, {0.35, RIGHT_STANCE}}; // transition_times_index_ = DeclareAbstractState( @@ -72,6 +81,7 @@ ContactScheduler::ContactScheduler( VectorXd initial_transition_times = VectorXd::Zero(4); initial_transition_times << -0.1, 0.0, 0.25, 0.35; transition_times_index_ = DeclareDiscreteState(initial_transition_times); + ground_height_index_ = DeclareDiscreteState(VectorXd::Zero(1)); upcoming_transitions_index_ = DeclareAbstractState( drake::Value>>{ @@ -107,13 +117,44 @@ EventStatus ContactScheduler::UpdateTransitionTimes( upcoming_transitions_index_); auto active_state = stored_fsm_state; - double transition_time = upcoming_transitions.at(1).first; - RUNNING_FSM_STATE transition_state = upcoming_transitions.at(1).second; + double transition_time = upcoming_transitions.at(3).first; + RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; if (current_time > transition_time) { - std::cout << "transitioning to: " << transition_state << std::endl; - std::cout << "at: " << transition_time << std::endl; + // std::cout << "transitioning to: " << transition_state << std::endl; + // std::cout << "at: " << transition_time << std::endl; active_state = transition_state; } + VectorXd q = robot_output->GetPositions(); + multibody::SetPositionsIfNew(plant_, q, plant_context_); + if (active_state == LEFT_STANCE) { + auto toe_front = LeftToeFront(plant_); + auto toe_rear = LeftToeRear(plant_); + Vector3d toe_front_pos; + Vector3d toe_rear_pos; + plant_.CalcPointsPositions(*plant_context_, toe_front.second, + toe_front.first, plant_.world_frame(), + &toe_front_pos); + plant_.CalcPointsPositions(*plant_context_, toe_rear.second, toe_rear.first, + plant_.world_frame(), &toe_rear_pos); + VectorXd height = + 0.5 * (toe_front_pos[2] + toe_rear_pos[2]) * VectorXd::Ones(1); + state->get_mutable_discrete_state(stored_robot_state_index_) + .SetFromVector(height); + } else if (active_state == RIGHT_STANCE) { + auto toe_front = RightToeFront(plant_); + auto toe_rear = RightToeRear(plant_); + Vector3d toe_front_pos; + Vector3d toe_rear_pos; + plant_.CalcPointsPositions(*plant_context_, toe_front.second, + toe_front.first, plant_.world_frame(), + &toe_front_pos); + plant_.CalcPointsPositions(*plant_context_, toe_rear.second, toe_rear.first, + plant_.world_frame(), &toe_rear_pos); + VectorXd height = + 0.5 * (toe_front_pos[2] + toe_rear_pos[2]) * VectorXd::Ones(1); + state->get_mutable_discrete_state(ground_height_index_) + .SetFromVector(height); + } if (active_state != stored_fsm_state) { state->get_mutable_discrete_state(stored_robot_state_index_) @@ -122,79 +163,56 @@ EventStatus ContactScheduler::UpdateTransitionTimes( robot_output->get_timestamp(); double stored_transition_time = state->get_discrete_state(stored_transition_time_index_)[0]; - std::cout << "stored_transition_time: " << stored_transition_time - << std::endl; double g = drake::multibody::UniformGravityFieldElement::kDefaultStrength; // Compute relative to stance foot - double pelvis_z = robot_output->GetState()[6]; - double pelvis_zdot = robot_output->GetState()[23 + 5]; + double pelvis_z = robot_output->GetPositionAtIndex(6) - + state->get_discrete_state(ground_height_index_)[0]; + double pelvis_zdot = robot_output->GetVelocityAtIndex(5); if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { + // Store the ground height of the stance foot + // TODO(yangwill): calculate end of stance duration double next_transition_time = stored_transition_time + 0.25; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; - // nominal_state_durations[0] = - // next_transition_time - stored_transition_time; - // nominal_stance_duration = next_transition_time - - // stored_transition_time; if (active_state == LEFT_STANCE) { transition_times[LEFT_FLIGHT] = next_transition_time; - transition_times[RIGHT_STANCE] = - next_transition_time + nominal_flight_duration; - transition_times[RIGHT_FLIGHT] = next_transition_time + - nominal_flight_duration + - nominal_stance_duration; - upcoming_transitions = {{transition_times[LEFT_STANCE], LEFT_STANCE}, - {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, - {transition_times[RIGHT_STANCE], RIGHT_STANCE}, - {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; - } else { - transition_times[RIGHT_FLIGHT] = next_transition_time; - transition_times[LEFT_STANCE] = - next_transition_time + nominal_flight_duration; - transition_times[LEFT_FLIGHT] = next_transition_time + - nominal_flight_duration + - nominal_stance_duration; upcoming_transitions = {{transition_times[RIGHT_STANCE], RIGHT_STANCE}, {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, {transition_times[LEFT_STANCE], LEFT_STANCE}, {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}}; + } else { + transition_times[RIGHT_FLIGHT] = next_transition_time; + upcoming_transitions = {{transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; } } else { - // double next_transition_time = - // stored_transition_time + - // 1 / g * - // (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - - // 2 * g * (pelvis_z - rest_length_))); - double next_transition_time = stored_transition_time + 0.1; + double time_to_touchdown = + 1 / g * + (pelvis_zdot + + sqrt(pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z))); + double next_transition_time = + stored_transition_time + + drake::math::saturate(time_to_touchdown, 0.07, 0.10); state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = next_transition_time - stored_transition_time; - // nominal_flight_duration = 0.1; if (active_state == LEFT_FLIGHT) { transition_times[RIGHT_STANCE] = next_transition_time; - transition_times[RIGHT_FLIGHT] = - next_transition_time + nominal_stance_duration; - transition_times[LEFT_STANCE] = next_transition_time + - nominal_stance_duration + - nominal_flight_duration; - upcoming_transitions = {{transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, - {transition_times[RIGHT_STANCE], RIGHT_STANCE}, - {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, - {transition_times[LEFT_STANCE], LEFT_STANCE}}; - } else { - transition_times[LEFT_STANCE] = next_transition_time; - transition_times[LEFT_FLIGHT] = - next_transition_time + nominal_stance_duration; - transition_times[RIGHT_STANCE] = next_transition_time + - nominal_stance_duration + - nominal_flight_duration; upcoming_transitions = {{transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, {transition_times[LEFT_STANCE], LEFT_STANCE}, {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, {transition_times[RIGHT_STANCE], RIGHT_STANCE}}; + } else { + transition_times[LEFT_STANCE] = next_transition_time; + upcoming_transitions = {{transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}}; } } } @@ -207,7 +225,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( void ContactScheduler::CalcFiniteState(const Context& context, BasicVector* fsm_state) const { // Assign fsm_state - VectorXd current_finite_state = context.get_discrete_state(stored_fsm_state_index_).CopyToVector(); + VectorXd current_finite_state = + context.get_discrete_state(stored_fsm_state_index_).CopyToVector(); fsm_state->get_mutable_value() = current_finite_state; } @@ -227,13 +246,13 @@ void ContactScheduler::CalcNextImpactInfo( near_impact->set_timestamp(current_time); // near_impact->SetCurrentContactMode(0); - // near_impact->SetAlpha(0); + near_impact->SetAlpha(0); // Get current finite state - double transition_time = upcoming_transitions.at(1).first; - RUNNING_FSM_STATE transition_state = upcoming_transitions.at(1).second; - double previous_transition_time = upcoming_transitions.at(0).first; - RUNNING_FSM_STATE current_state = upcoming_transitions.at(0).second; + double transition_time = upcoming_transitions.at(3).first; + RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; + double previous_transition_time = upcoming_transitions.at(2).first; + RUNNING_FSM_STATE current_state = upcoming_transitions.at(2).second; double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ : near_impact_threshold_; // Check if we're close to an impact event either upcoming or one that just @@ -243,7 +262,7 @@ void ContactScheduler::CalcNextImpactInfo( if (impact_states_.count(transition_state) != 0) { if (abs(current_time - transition_time) < blend_window) { // Apply the corresponding blending function - if (current_time < transition_time) { + if (current_time <= transition_time) { near_impact->SetAlpha(alpha_func(current_time - transition_time, tau_, near_impact_threshold_)); } @@ -254,7 +273,7 @@ void ContactScheduler::CalcNextImpactInfo( if (impact_states_.count(current_state) != 0) { if (abs(current_time - previous_transition_time) < blend_window) { // Apply the corresponding blending function - if (current_time > previous_transition_time) { + if (current_time >= previous_transition_time) { near_impact->SetAlpha( alpha_func(previous_transition_time - current_time, tau_, near_impact_threshold_)); @@ -300,6 +319,10 @@ void ContactScheduler::CalcContactScheduler( contact_timing->get_mutable_value()(5) = transition_times[RIGHT_FLIGHT] + 2 * nominal_flight_duration + nominal_stance_duration; + // std::cout << "contact_scheduler start: " + // << contact_timing->get_mutable_value()(2) << std::endl; + // std::cout << "contact_scheduler end: " + // << contact_timing->get_mutable_value()(3) << std::endl; } void ContactScheduler::OutputDebuggingInfo( @@ -320,8 +343,8 @@ void ContactScheduler::OutputDebuggingInfo( debug_info->transition_times = std::vector(4); debug_info->transition_states.clear(); debug_info->transition_states = std::vector(4); - debug_info->fsm_state_names = {"LEFT_STANCE", "RIGHT_STANCE", "LEFT_FLIGHT", - "RIGHT_FLIGHT"}; + debug_info->fsm_state_names = {"LEFT_STANCE (0)", "RIGHT_STANCE (1)", + "LEFT_FLIGHT (2)", "RIGHT_FLIGHT (3)"}; for (int i = 0; i < debug_info->n_transitions; ++i) { debug_info->transition_times.at(i) = upcoming_transitions[i].first; diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 4dc4a7da56..959ef9bbf8 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -6,9 +6,9 @@ #include #include "common/blending_utils.h" +#include "dairlib/lcmt_contact_timing.hpp" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" -#include "dairlib/lcmt_contact_timing.hpp" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/leaf_system.h" @@ -20,6 +20,7 @@ enum RUNNING_FSM_STATE { LEFT_STANCE, RIGHT_STANCE, LEFT_FLIGHT, RIGHT_FLIGHT }; class ContactScheduler : public drake::systems::LeafSystem { public: ContactScheduler(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* plant_context, std::set& impact_states, double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); @@ -34,15 +35,15 @@ class ContactScheduler : public drake::systems::LeafSystem { const drake::systems::OutputPort& get_output_port_clock() const { return this->get_output_port(clock_port_); } - const drake::systems::OutputPort& get_output_port_impact_info() const { + const drake::systems::OutputPort& get_output_port_impact_info() + const { return this->get_output_port(impact_info_port_); } const drake::systems::OutputPort& get_output_port_contact_scheduler() const { return this->get_output_port(contact_scheduler_port_); } - const drake::systems::OutputPort& get_output_port_debug_info() - const { + const drake::systems::OutputPort& get_output_port_debug_info() const { return this->get_output_port(debug_port_); } @@ -76,7 +77,8 @@ class ContactScheduler : public drake::systems::LeafSystem { double tau_; const BLEND_FUNC blend_func_; - // const drake::multibody::MultibodyPlant& plant_; + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* plant_context_; /// contains pairs (start of fsm, fsm_state) /// the order of the vector goes: last transition, next upcoming three @@ -93,6 +95,7 @@ class ContactScheduler : public drake::systems::LeafSystem { // estimates of state durations for stance and flight in seconds drake::systems::DiscreteStateIndex nominal_state_durations_index_; drake::systems::DiscreteStateIndex transition_times_index_; + drake::systems::DiscreteStateIndex ground_height_index_; drake::systems::AbstractStateIndex upcoming_transitions_index_; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 66fafe9e0f..d526beb85c 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -3,7 +3,7 @@ w_input_reg: 0.1 w_accel: 0.0001 w_soft_constraint: 100 impact_threshold: 0.05 -impact_tau: 0.05 +impact_tau: 0.005 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, @@ -43,7 +43,7 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.08 -footstep_lateral_offset: 0.02 # drake +footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.05 FootstepKd: [ 0.15, 0, 0, @@ -60,7 +60,7 @@ PelvisKp: PelvisKd: [ 2, 0, 0, 0, 2, 0, - 0, 0, 4 ] + 0, 0, 3.5 ] PelvisRotW: [ 10, 0, 0, 0, 10, 0, @@ -70,7 +70,7 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [10., 0, 0, + [5., 0, 0, 0, 5., 0, 0, 0, 3.] SwingFootW: diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index cb7e1e289c..b446b78ecf 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 200 +max_iter: 100 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index bc27e3c121..c47e6b2a60 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -165,7 +165,7 @@ int DoMain(int argc, char* argv[]) { std::set impact_states = {LEFT_STANCE, RIGHT_STANCE}; auto contact_scheduler = builder.AddSystem( - plant, impact_states, gains.impact_threshold, gains.impact_tau); + plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); auto fsm = builder.AddSystem( plant, fsm_states, state_durations, 0.0, gains.impact_threshold, gains.impact_tau); @@ -522,10 +522,11 @@ int DoMain(int argc, char* argv[]) { /*****Connect ports*****/ // OSC connections - builder.Connect(fsm->get_output_port_fsm(), osc->get_input_port_fsm()); - builder.Connect(fsm->get_output_port_impact_info(), +// builder.Connect(fsm->get_output_port_fsm(), osc->get_input_port_fsm()); + builder.Connect(contact_scheduler->get_output_port_fsm(), osc->get_input_port_fsm()); + builder.Connect(contact_scheduler->get_output_port_impact_info(), osc->get_input_port_impact_info()); - builder.Connect(fsm->get_output_port_clock(), osc->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); // builder.Connect(contact_scheduler->get_output_port_fsm(), // osc->get_input_port_fsm()); // builder.Connect(contact_scheduler->get_output_port_impact_info(), @@ -546,26 +547,15 @@ int DoMain(int argc, char* argv[]) { // Trajectory generator connections - // builder.Connect(contact_scheduler->get_output_port_fsm(), - // l_foot_traj_generator->get_input_port_fsm()); - // builder.Connect(contact_scheduler->get_output_port_fsm(), - // r_foot_traj_generator->get_input_port_fsm()); - // builder.Connect( - // contact_scheduler->get_output_port_contact_scheduler(), - // pelvis_trans_traj_generator->get_input_port_contact_scheduler()); - // builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), - // l_foot_traj_generator->get_input_port_contact_scheduler()); - // builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), - // r_foot_traj_generator->get_input_port_contact_scheduler()); builder.Connect( contact_scheduler->get_output_port_contact_scheduler(), pelvis_trans_traj_generator->get_contact_scheduler_input_port()); -// builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), -// l_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + l_foot_traj_generator->get_input_port_contact_scheduler()); // builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), // r_foot_traj_generator->get_input_port_contact_scheduler()); - builder.Connect(fsm->get_output_port_contact_scheduler(), - l_foot_traj_generator->get_input_port_contact_scheduler()); +// builder.Connect(fsm->get_output_port_contact_scheduler(), +// l_foot_traj_generator->get_input_port_contact_scheduler()); builder.Connect(fsm->get_output_port_contact_scheduler(), r_foot_traj_generator->get_input_port_contact_scheduler()); @@ -592,9 +582,9 @@ int DoMain(int argc, char* argv[]) { l_foot_traj_generator->get_input_port_clock()); builder.Connect(contact_scheduler->get_output_port_clock(), r_foot_traj_generator->get_input_port_clock()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(contact_scheduler->get_output_port_fsm(), l_foot_traj_generator->get_input_port_fsm()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(contact_scheduler->get_output_port_fsm(), r_foot_traj_generator->get_input_port_fsm()); builder.Connect(state_receiver->get_output_port(0), left_toe_angle_traj_gen->get_input_port_state()); diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index 20b6c6e70b..45535533ea 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -1,6 +1,8 @@ -#include #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" +#include +#include + using drake::systems::BasicVector; using drake::systems::Context; using Eigen::VectorXd; @@ -8,12 +10,12 @@ using std::string; namespace dairlib { -using systems::OutputVector; using systems::ImpactInfoVector; +using systems::OutputVector; ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( - const drake::multibody::MultibodyPlant &plant, - const std::vector &states, const std::vector &state_durations, + const drake::multibody::MultibodyPlant& plant, + const std::vector& states, const std::vector& state_durations, double t0, double near_impact_threshold, double tau, BLEND_FUNC blend_func) : TimeBasedFiniteStateMachine(plant, states, state_durations, t0), states_(states), @@ -24,27 +26,29 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( blend_func_(blend_func) { this->set_name("ImpactAwareTimeBasedFSM"); near_impact_port_ = - this->DeclareVectorOutputPort("near_impact", - ImpactInfoVector(0, 0, 0), - &ImpactTimeBasedFiniteStateMachine::CalcNearImpact) + this->DeclareVectorOutputPort( + "near_impact", ImpactInfoVector(0, 0, 0), + &ImpactTimeBasedFiniteStateMachine::CalcNearImpact) + .get_index(); + clock_port_ = this->DeclareVectorOutputPort( + "clock", BasicVector(1), + &ImpactTimeBasedFiniteStateMachine::CalcClock) + .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) .get_index(); - clock_port_ = this->DeclareVectorOutputPort("clock", - BasicVector(1), - &ImpactTimeBasedFiniteStateMachine::CalcClock) - .get_index(); - radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) - .get_index(); - - contact_scheduler_port_ = this->DeclareVectorOutputPort("contact_scheduler " - "(pelvis_t0, " - "pelvis_tf, " - "left_t0, left_tf, " - "right_t0, right_t0", - BasicVector(6), - &ImpactTimeBasedFiniteStateMachine::CalcContactScheduler) - .get_index(); + contact_scheduler_port_ = + this->DeclareVectorOutputPort( + "contact_scheduler " + "(pelvis_t0, " + "pelvis_tf, " + "left_t0, left_tf, " + "right_t0, right_t0", + BasicVector(6), + &ImpactTimeBasedFiniteStateMachine::CalcContactScheduler) + .get_index(); // Accumulate the durations to get timestamps double sum = 0; @@ -65,11 +69,11 @@ ImpactTimeBasedFiniteStateMachine::ImpactTimeBasedFiniteStateMachine( } void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( - const Context &context, - ImpactInfoVector *near_impact) const { + const Context& context, + ImpactInfoVector* near_impact) const { // Read in lcm message time - const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); @@ -84,8 +88,8 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { double blend_window = blend_func_ == SIGMOID - ? 1.5 * near_impact_threshold_ - : near_impact_threshold_; + ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; if (abs(remainder - impact_times_[i]) < blend_window) { if (remainder < impact_times_[i]) { near_impact->SetAlpha(alpha_func(remainder - impact_times_[i], tau_, @@ -102,46 +106,46 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( } void ImpactTimeBasedFiniteStateMachine::CalcClock( - const Context &context, BasicVector *clock) const { + const Context& context, BasicVector* clock) const { // Read in lcm message time - const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); -// clock->get_mutable_value()(0) = remainder; + // clock->get_mutable_value()(0) = remainder; clock->get_mutable_value()(0) = current_time; } void ImpactTimeBasedFiniteStateMachine::CalcContactScheduler( - const Context &context, BasicVector *contact_timing) const { + const Context& context, BasicVector* contact_timing) const { // Read in lcm message time - const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); if (this->get_input_port(radio_port_).HasValue(context)) { - const auto &radio_out = + const auto& radio_out = this->EvalInputValue(context, radio_port_); } auto current_time = static_cast(robot_output->get_timestamp()); double remainder = fmod(current_time, period_); - int n_periods = (int) (current_time / period_); - - for (unsigned int i = 0; i < accu_state_durations_.size(); i++) { - contact_timing->get_mutable_value()(0) = - n_periods * period_ + accu_state_durations_[i]; - contact_timing->get_mutable_value()(1) = - n_periods * period_ + accu_state_durations_[i]; - contact_timing->get_mutable_value()(2) = - n_periods * period_ + accu_state_durations_[1]; - contact_timing->get_mutable_value()(3) = - n_periods * period_ + accu_state_durations_[4]; - contact_timing->get_mutable_value()(4) = - (n_periods - 1) * period_ + accu_state_durations_[3]; - contact_timing->get_mutable_value()(5) = - (n_periods - 1) * period_ + accu_state_durations_[3] - + (accu_state_durations_[2] - accu_state_durations_[0]) - + (accu_state_durations_[4] - accu_state_durations_[3]); - } + int n_periods = (int)(current_time / period_); + + contact_timing->get_mutable_value()(0) = + n_periods * period_ + accu_state_durations_[0]; + contact_timing->get_mutable_value()(1) = + n_periods * period_ + accu_state_durations_[1]; + contact_timing->get_mutable_value()(2) = + n_periods * period_ + accu_state_durations_[1]; + contact_timing->get_mutable_value()(3) = + n_periods * period_ + accu_state_durations_[4]; + contact_timing->get_mutable_value()(4) = + (n_periods - 1) * period_ + accu_state_durations_[3]; + contact_timing->get_mutable_value()(5) = + (n_periods - 1) * period_ + accu_state_durations_[3] + + (accu_state_durations_[2] - accu_state_durations_[0]) + + (accu_state_durations_[4] - accu_state_durations_[3]); +// std::cout << "fsm start: " << contact_timing->get_mutable_value()(2) << std::endl; +// std::cout << "fsm end: " << contact_timing->get_mutable_value()(3) << std::endl; } } // namespace dairlib From 64c5cd9aa8cb2bfd2e5184f9f5d1b530c4c06e32 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 9 Aug 2022 15:23:32 -0400 Subject: [PATCH 263/758] running works with variable fsm --- .../plot_configs/cassie_running_plot.yaml | 4 +- .../contact_scheduler/contact_scheduler.cc | 17 ++- .../contact_scheduler/contact_scheduler.h | 8 +- .../director_scripts/show_time_hardware.py | 7 +- .../Cassie/osc_run/foot_traj_generator.cc | 121 +++++++++--------- examples/Cassie/osc_run/foot_traj_generator.h | 5 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 29 ++--- 8 files changed, 101 insertions(+), 92 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index fc925fc748..815a67fb06 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -14,8 +14,8 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false -plot_floating_base_velocities: false +plot_floating_base_positions: true +plot_floating_base_velocities: true plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 803ba9c002..0a51aad65d 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -34,10 +34,10 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, BLEND_FUNC blend_func) : plant_(plant), plant_context_(plant_context), + impact_states_(impact_states), near_impact_threshold_(near_impact_threshold), tau_(tau), - blend_func_(blend_func), - impact_states_(impact_states) { + blend_func_(blend_func) { this->set_name("ContactScheduler"); // Declare system ports state_port_ = this->DeclareVectorInputPort( @@ -138,7 +138,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( plant_.world_frame(), &toe_rear_pos); VectorXd height = 0.5 * (toe_front_pos[2] + toe_rear_pos[2]) * VectorXd::Ones(1); - state->get_mutable_discrete_state(stored_robot_state_index_) + state->get_mutable_discrete_state(ground_height_index_) .SetFromVector(height); } else if (active_state == RIGHT_STANCE) { auto toe_front = RightToeFront(plant_); @@ -192,10 +192,13 @@ EventStatus ContactScheduler::UpdateTransitionTimes( {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; } } else { - double time_to_touchdown = - 1 / g * - (pelvis_zdot + - sqrt(pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z))); + double time_to_touchdown = 0.1; + if (pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z) > 0) { + time_to_touchdown = + (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - + 2 * g * (rest_length_ - pelvis_z))) / + g; + } double next_transition_time = stored_transition_time + drake::math::saturate(time_to_touchdown, 0.07, 0.10); diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 959ef9bbf8..0ba8dbcdcc 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -66,20 +66,20 @@ class ContactScheduler : public drake::systems::LeafSystem { drake::systems::InputPortIndex state_port_; drake::systems::OutputPortIndex fsm_port_; drake::systems::OutputPortIndex clock_port_; - // drake::systems::OutputPortIndex contact_timing_; drake::systems::OutputPortIndex impact_info_port_; drake::systems::OutputPortIndex contact_scheduler_port_; drake::systems::OutputPortIndex debug_port_; + // Dynamics calculations + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* plant_context_; + // For impact-invariant calculations const std::set impact_states_; double near_impact_threshold_; double tau_; const BLEND_FUNC blend_func_; - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* plant_context_; - /// contains pairs (start of fsm, fsm_state) /// the order of the vector goes: last transition, next upcoming three /// transitions diff --git a/examples/Cassie/director_scripts/show_time_hardware.py b/examples/Cassie/director_scripts/show_time_hardware.py index bad7c4044c..f4d7c27f74 100644 --- a/examples/Cassie/director_scripts/show_time_hardware.py +++ b/examples/Cassie/director_scripts/show_time_hardware.py @@ -13,6 +13,7 @@ def __init__(self): self._name = "Time Visualizer" self._real_time = [] self._msg_time = [] + self._pelvis_velocity = [] self._subscriber = None # Number of messages used to average for real time factor. self._num_msg_for_average = 50 @@ -57,15 +58,19 @@ def handle_message(self, msg): pelvis_velocity = np.linalg.norm((msg.velocity)[3:5]) # convert from microseconds self._real_time.append(time.time()) self._msg_time.append(msg_time) + self._pelvis_velocity.append(pelvis_velocity) my_text = 'time: %.3f' % msg_time pelvis_height_text = 'pelvis height: %.3f' % pelvis_height - pelvis_velocity_text = 'pelvis velocity: %.3f' % pelvis_velocity + + pelvis_velocity_text = 'pelvis velocity: %.3f' % np.array(self._pelvis_velocity).mean() realtime_text = '' if (len(self._real_time) >= self._num_msg_for_average): self._real_time.pop(0) self._msg_time.pop(0) + self._pelvis_velocity.pop(0) + dt = self._msg_time[-1] - self._msg_time[0] dt_real_time = self._real_time[-1] - self._real_time[0] diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 5ad76a10c3..00607327f1 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -35,16 +35,14 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, Context* context, const string& foot_name, const string& hip_name, bool relative_feet, - const int stance_state, - std::vector state_durations) + const int stance_state) : plant_(plant), context_(context), world_(plant.world_frame()), foot_frame_(plant.GetFrameByName(foot_name)), hip_frame_(plant.GetFrameByName(hip_name)), relative_feet_(relative_feet), - stance_state_(stance_state), - state_durations_(state_durations) { + stance_state_(stance_state) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -224,10 +222,10 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector T_waypoints_2; // Storing old method for record keeping - T_waypoints = { - state_durations_[1], - state_durations_[1] + 0.5 * (state_durations_[4] - state_durations_[1]), - state_durations_[4]}; + // T_waypoints = { + // state_durations_[1], + // state_durations_[1] + 0.5 * (state_durations_[4] - + // state_durations_[1]), state_durations_[4]}; // T_waypoints_0 = { // state_durations_[0], @@ -254,7 +252,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // std::cout << right_t0 + 0.6 * (right_tf - right_t0) << std::endl; // std::cout << right_tf << std::endl; } -// std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; + // std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; // T_waypoints_0 = { // pelvis_t0, // (state_durations_[3] - state_durations_[4]) + @@ -295,47 +293,48 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // PiecewisePolynomial swing_foot_spline = // PiecewisePolynomial::CubicWithContinuousSecondDerivatives( // T_waypoints, Y, Y_dot_start, Y_dot_end); -// std::cout << "is left foot: " << is_left_foot_ << std::endl; -// for (auto& t :T_waypoints){ -// std::cout << "t: " << t << std::endl; -// } + // std::cout << "is left foot: " << is_left_foot_ << std::endl; + // for (auto& t :T_waypoints){ + // std::cout << "t: " << t << std::endl; + // } PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, false); return swing_foot_spline; - if (is_left_foot_) { - return swing_foot_spline; - } else { - // MatrixXd Y0 = MatrixXd::Zero(3, 3); - // MatrixXd Ydot0 = MatrixXd::Zero(3, 3); - // MatrixXd Y1 = MatrixXd::Zero(2, 3); - // MatrixXd Ydot1 = MatrixXd::Zero(2, 3); - std::vector Y0(T_waypoints_0.size(), VectorXd::Zero(3)); - std::vector Ydot0(T_waypoints_0.size(), VectorXd::Zero(3)); - std::vector Y2(T_waypoints_1.size(), VectorXd::Zero(3)); - std::vector Ydot2(T_waypoints_1.size(), VectorXd::Zero(3)); - Y0[0] = swing_foot_spline.value(state_durations_[2]); - Y0[1] = swing_foot_spline.value(T_waypoints[1]); - Y0[2] = swing_foot_spline.value(T_waypoints[2]); - Ydot0[0] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); - Ydot0[1] = swing_foot_spline.EvalDerivative(T_waypoints[1], 1); - Ydot0[2] = swing_foot_spline.EvalDerivative(T_waypoints[2], 1); - Y2[0] = swing_foot_spline.value(state_durations_[1]); - Y2[1] = swing_foot_spline.value(state_durations_[2]); - Ydot2[0] = swing_foot_spline.EvalDerivative(state_durations_[1], 1); - Ydot2[1] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); - PiecewisePolynomial offset_swing_foot_spline = - PiecewisePolynomial::CubicHermite(T_waypoints_0, Y0, Ydot0); - offset_swing_foot_spline.ConcatenateInTime( - PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); - offset_swing_foot_spline.ConcatenateInTime( - PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, Ydot2)); - // for (auto t: offset_swing_foot_spline.get_segment_times()) { - // std::cout << t << std::endl; - // } - return offset_swing_foot_spline; - } + // if (is_left_foot_) { + // return swing_foot_spline; + // } else { + // MatrixXd Y0 = MatrixXd::Zero(3, 3); + // MatrixXd Ydot0 = MatrixXd::Zero(3, 3); + // MatrixXd Y1 = MatrixXd::Zero(2, 3); + // MatrixXd Ydot1 = MatrixXd::Zero(2, 3); + // std::vector Y0(T_waypoints_0.size(), VectorXd::Zero(3)); + // std::vector Ydot0(T_waypoints_0.size(), VectorXd::Zero(3)); + // std::vector Y2(T_waypoints_1.size(), VectorXd::Zero(3)); + // std::vector Ydot2(T_waypoints_1.size(), VectorXd::Zero(3)); + // Y0[0] = swing_foot_spline.value(state_durations_[2]); + // Y0[1] = swing_foot_spline.value(T_waypoints[1]); + // Y0[2] = swing_foot_spline.value(T_waypoints[2]); + // Ydot0[0] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); + // Ydot0[1] = swing_foot_spline.EvalDerivative(T_waypoints[1], 1); + // Ydot0[2] = swing_foot_spline.EvalDerivative(T_waypoints[2], 1); + // Y2[0] = swing_foot_spline.value(state_durations_[1]); + // Y2[1] = swing_foot_spline.value(state_durations_[2]); + // Ydot2[0] = swing_foot_spline.EvalDerivative(state_durations_[1], 1); + // Ydot2[1] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); + // PiecewisePolynomial offset_swing_foot_spline = + // PiecewisePolynomial::CubicHermite(T_waypoints_0, Y0, Ydot0); + // offset_swing_foot_spline.ConcatenateInTime( + // PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); + // offset_swing_foot_spline.ConcatenateInTime( + // PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, + // Ydot2)); + // for (auto t: offset_swing_foot_spline.get_segment_times()) { + // std::cout << t << std::endl; + // } + // return offset_swing_foot_spline; + //} // return swing_foot_spline; } @@ -349,29 +348,33 @@ void FootTrajGenerator::CalcTraj( // double timestamp = robot_output->get_timestamp(); // // // Read in finite state machine - const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value()[0]; + const auto fsm_state = + this->EvalVectorInput(context, fsm_port_)->get_value()[0]; auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (is_left_foot_ ) { - if(fsm_state != LEFT_STANCE){ -// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); + if (is_left_foot_) { + if (fsm_state != LEFT_STANCE) { + // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, + // rest_length_}); *casted_traj = GenerateFlightTraj(context); } -// else{ -// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); -// } + // else{ + // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, + // rest_length_}); + // } - } - else{ - if(fsm_state != RIGHT_STANCE){ + } else { + if (fsm_state != RIGHT_STANCE) { *casted_traj = GenerateFlightTraj(context); -// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); + // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, + // rest_length_}); } -// else{ -// *casted_traj = PiecewisePolynomial(Vector3d{0, 0, rest_length_}); -// } + // else{ + // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, + // rest_length_}); + // } } } diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index 7d110611e5..e82f59e899 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -14,8 +14,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, const std::string& foot_name, const std::string& hip_name, - bool relative_feet, int stance_state, - std::vector state_durations); + bool relative_feet, int stance_state); const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); @@ -63,7 +62,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::Frame& hip_frame_; // Foot spline parameters - std::vector state_durations_; +// std::vector state_durations_; // Foot placement constants double rest_length_; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d526beb85c..f4dd76ae49 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -55,7 +55,7 @@ PelvisW: 0, 0, 5 ] PelvisKp: [ -50, 0, 0, - 0, -50, 0, + 0, 50, 0, 0, 0, 105] PelvisKd: [ 2, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c47e6b2a60..15ea21073f 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -165,10 +165,11 @@ int DoMain(int argc, char* argv[]) { std::set impact_states = {LEFT_STANCE, RIGHT_STANCE}; auto contact_scheduler = builder.AddSystem( - plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); - auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, gains.impact_threshold, + plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); +// auto fsm = builder.AddSystem( +// plant, fsm_states, state_durations, 0.0, gains.impact_threshold, +// gains.impact_tau); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -294,10 +295,10 @@ int DoMain(int argc, char* argv[]) { pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, - 0, accumulated_state_durations); + LEFT_STANCE); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", - osc_gains.relative_feet, 1, accumulated_state_durations); + osc_gains.relative_feet, RIGHT_STANCE); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( @@ -522,11 +523,13 @@ int DoMain(int argc, char* argv[]) { /*****Connect ports*****/ // OSC connections -// builder.Connect(fsm->get_output_port_fsm(), osc->get_input_port_fsm()); - builder.Connect(contact_scheduler->get_output_port_fsm(), osc->get_input_port_fsm()); + // builder.Connect(fsm->get_output_port_fsm(), osc->get_input_port_fsm()); + builder.Connect(contact_scheduler->get_output_port_fsm(), + osc->get_input_port_fsm()); builder.Connect(contact_scheduler->get_output_port_impact_info(), osc->get_input_port_impact_info()); - builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_clock(), + osc->get_input_port_clock()); // builder.Connect(contact_scheduler->get_output_port_fsm(), // osc->get_input_port_fsm()); // builder.Connect(contact_scheduler->get_output_port_impact_info(), @@ -540,8 +543,8 @@ int DoMain(int argc, char* argv[]) { osc->get_robot_output_input_port()); // FSM connections - builder.Connect(state_receiver->get_output_port(0), - fsm->get_state_input_port()); +// builder.Connect(state_receiver->get_output_port(0), +// fsm->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), contact_scheduler->get_input_port_state()); @@ -552,11 +555,7 @@ int DoMain(int argc, char* argv[]) { pelvis_trans_traj_generator->get_contact_scheduler_input_port()); builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), l_foot_traj_generator->get_input_port_contact_scheduler()); -// builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), -// r_foot_traj_generator->get_input_port_contact_scheduler()); -// builder.Connect(fsm->get_output_port_contact_scheduler(), -// l_foot_traj_generator->get_input_port_contact_scheduler()); - builder.Connect(fsm->get_output_port_contact_scheduler(), + builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), r_foot_traj_generator->get_input_port_contact_scheduler()); builder.Connect(state_receiver->get_output_port(0), From 898c2895de519bb09c0d1278eeae3b4decf78733 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 9 Aug 2022 16:00:19 -0400 Subject: [PATCH 264/758] refactoring port naming and fixing gym examples --- bindings/pydairlib/cassie/controllers_py.cc | 32 ++++++------- .../cassie/gym_envs/cassie_gym_test.py | 4 +- .../cassie/gym_envs/drake_cassie_gym.py | 12 ++--- .../cassie/gym_envs/mujoco_cassie_gym.py | 6 +-- bindings/pydairlib/cassie/simulators_py.cc | 12 ++--- examples/Cassie/closed_loop_running_sim.cc | 14 +++--- examples/Cassie/diagrams/BUILD.bazel | 1 + .../Cassie/diagrams/cassie_sim_diagram.cc | 8 +--- examples/Cassie/diagrams/cassie_sim_diagram.h | 26 +++++------ .../osc_running_controller_diagram.cc | 45 +++++++++++++------ .../diagrams/osc_running_controller_diagram.h | 41 +++++++++-------- .../diagrams/osc_walking_controller_diagram.h | 10 ++--- examples/Cassie/multibody_sim.cc | 2 +- .../Cassie/multibody_sim_w_ground_incline.cc | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 2 +- examples/Cassie/run_osc_running_controller.cc | 9 ---- examples/Cassie/test/min_deps_mbt_sim.cc | 2 +- 17 files changed, 118 insertions(+), 110 deletions(-) diff --git a/bindings/pydairlib/cassie/controllers_py.cc b/bindings/pydairlib/cassie/controllers_py.cc index d8623f9cb0..2620f903dd 100644 --- a/bindings/pydairlib/cassie/controllers_py.cc +++ b/bindings/pydairlib/cassie/controllers_py.cc @@ -28,19 +28,19 @@ PYBIND11_MODULE(controllers, m) { .def("get_plant", &OSCRunningControllerDiagram::get_plant, py_rvp::reference_internal) .def("get_input_port_state", - &OSCRunningControllerDiagram::get_state_input_port, + &OSCRunningControllerDiagram::get_input_port_state, py_rvp::reference_internal) .def("get_input_port_radio", - &OSCRunningControllerDiagram::get_radio_input_port, + &OSCRunningControllerDiagram::get_input_port_radio, py_rvp::reference_internal) - .def("get_control_output_port", - &OSCRunningControllerDiagram::get_control_output_port, + .def("get_output_port_robot_input", + &OSCRunningControllerDiagram::get_output_port_robot_input, py_rvp::reference_internal) - .def("get_torque_output_port", - &OSCRunningControllerDiagram::get_torque_output_port, + .def("get_output_port_torque", + &OSCRunningControllerDiagram::get_output_port_torque, py_rvp::reference_internal) - .def("get_controller_failure_output_port", - &OSCRunningControllerDiagram::get_controller_failure_output_port, + .def("get_output_port_controller_failure", + &OSCRunningControllerDiagram::get_output_port_controller_failure, py_rvp::reference_internal); py::class_>( @@ -50,19 +50,19 @@ PYBIND11_MODULE(controllers, m) { .def("get_plant", &OSCWalkingControllerDiagram::get_plant, py_rvp::reference_internal) .def("get_input_port_state", - &OSCWalkingControllerDiagram::get_state_input_port, + &OSCWalkingControllerDiagram::get_input_port_state, py_rvp::reference_internal) .def("get_input_port_radio", - &OSCWalkingControllerDiagram::get_radio_input_port, + &OSCWalkingControllerDiagram::get_input_port_radio, py_rvp::reference_internal) - .def("get_control_output_port", - &OSCWalkingControllerDiagram::get_control_output_port, + .def("get_output_port_robot_input", + &OSCWalkingControllerDiagram::get_output_port_robot_input, py_rvp::reference_internal) - .def("get_torque_output_port", - &OSCWalkingControllerDiagram::get_torque_output_port, + .def("get_output_port_torque", + &OSCWalkingControllerDiagram::get_output_port_torque, py_rvp::reference_internal) - .def("get_controller_failure_output_port", - &OSCWalkingControllerDiagram::get_controller_failure_output_port, + .def("get_output_port_controller_failure", + &OSCWalkingControllerDiagram::get_output_port_controller_failure, py_rvp::reference_internal); } } // namespace pydairlib diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 825ce61520..0eb8d739b6 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -30,8 +30,8 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - # gym_env = DrakeCassieGym(reward_func, visualize=False) - gym_env = MuJoCoCassieGym(reward_func, visualize=True) + gym_env = DrakeCassieGym(reward_func, visualize=True) + # gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) cumulative_reward = gym_env.advance_to(7.5) print(cumulative_reward) diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 2bdb9c9ca9..e39f56031c 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -46,9 +46,9 @@ def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.builder.AddSystem(self.controller) self.builder.AddSystem(self.simulator) - self.builder.Connect(self.controller.get_control_output_port(), self.simulator.get_actuation_input_port()) - self.builder.Connect(self.simulator.get_state_output_port(), self.controller.get_state_input_port()) - # self.builder.Connect(self.simulator.get_cassie_out_output_port_index(), + self.builder.Connect(self.controller.get_output_port_robot_input(), self.simulator.get_input_port_actuation()) + self.builder.Connect(self.simulator.get_output_port_state(), self.controller.get_input_port_state()) + # self.builder.Connect(self.simulator.get_output_port_cassie_out(), # self.controller.get_cassie_out_input_port()) # self.builder.Connect(self.controller, self.simulator.get_input_port_radio()) @@ -56,7 +56,7 @@ def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.sim = Simulator(self.diagram) self.simulator_context = self.diagram.GetMutableSubsystemContext(self.simulator, self.sim.get_mutable_context()) self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.sim.get_mutable_context()) - self.controller_output_port = self.controller.get_torque_output_port() + self.controller_output_port = self.controller.get_output_port_torque() self.sim.get_mutable_context().SetTime(self.start_time) self.reset() self.initialized = True @@ -90,8 +90,8 @@ def step(self, action=np.zeros(18)): print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.sim_dt action[2] = 1.0 - self.simulator.get_radio_input_port().FixValue(self.simulator_context, action) - self.controller.get_radio_input_port().FixValue(self.controller_context, action) + self.simulator.get_input_port_radio().FixValue(self.simulator_context, action) + self.controller.get_input_port_radio().FixValue(self.controller_context, action) self.sim.AdvanceTo(next_timestep) self.current_time = self.sim.get_context().get_time() diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index e8e1d58178..1672ca2037 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -129,7 +129,7 @@ def make(self, controller): self.robot_output_sender = RobotOutputSender(self.controller.get_plant(), False) self.builder.AddSystem(self.robot_output_sender) - self.builder.Connect(self.robot_output_sender.get_output_port(), self.controller.get_state_input_port()) + self.builder.Connect(self.robot_output_sender.get_output_port(), self.controller.get_input_port_state()) self.drake_to_mujoco_converter = DrakeToMujocoConverter(self.sim_dt) self.diagram = self.builder.Build() @@ -138,8 +138,8 @@ def make(self, controller): self.drake_sim.get_mutable_context()) self.controller_context = self.diagram.GetMutableSubsystemContext(self.controller, self.drake_sim.get_mutable_context()) - self.controller_output_port = self.controller.get_torque_output_port() - self.radio_input_port = self.controller.get_radio_input_port() + self.controller_output_port = self.controller.get_output_port_torque() + self.radio_input_port = self.controller.get_input_port_radio() self.drake_sim.get_mutable_context().SetTime(self.start_time) self.reset() self.initialized = True diff --git a/bindings/pydairlib/cassie/simulators_py.cc b/bindings/pydairlib/cassie/simulators_py.cc index 1b42c46989..4077eb241c 100644 --- a/bindings/pydairlib/cassie/simulators_py.cc +++ b/bindings/pydairlib/cassie/simulators_py.cc @@ -26,15 +26,15 @@ PYBIND11_MODULE(simulators, m) { py::arg("dissipation_rate")) .def("get_plant", &CassieSimDiagram::get_plant, py_rvp::reference_internal) - .def("get_actuation_input_port", - &CassieSimDiagram::get_actuation_input_port, + .def("get_input_port_actuation", + &CassieSimDiagram::get_input_port_actuation, py_rvp::reference_internal) - .def("get_input_port_radio", &CassieSimDiagram::get_radio_input_port, + .def("get_input_port_radio", &CassieSimDiagram::get_input_port_radio, py_rvp::reference_internal) - .def("get_state_output_port", &CassieSimDiagram::get_state_output_port, + .def("get_output_port_state", &CassieSimDiagram::get_output_port_state, py_rvp::reference_internal) - .def("get_cassie_out_output_port_index", - &CassieSimDiagram::get_cassie_out_output_port_index, + .def("get_output_port_cassie_out", + &CassieSimDiagram::get_output_port_cassie_out, py_rvp::reference_internal); } } // namespace pydairlib diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 0f9419596c..1844369d2a 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -55,11 +55,11 @@ int DoMain(int argc, char* argv[]) { // builder.AddSystem( // controller_plant, true, osc_walking_gains, osqp_settings); - builder.Connect(controller_diagram->get_control_output_port(), - sim_diagram->get_actuation_input_port()); - builder.Connect(sim_diagram->get_state_output_port(), - controller_diagram->get_state_input_port()); -// builder.Connect(sim_diagram->get_cassie_out_output_port_index(), + builder.Connect(controller_diagram->get_output_port_robot_input(), + sim_diagram->get_input_port_actuation()); + builder.Connect(sim_diagram->get_output_port_state(), + controller_diagram->get_input_port_state()); +// builder.Connect(sim_diagram->get_output_port_cassie_out(), // controller_diagram->get_cassie_out_input_port()); auto diagram = builder.Build(); @@ -80,8 +80,8 @@ int DoMain(int argc, char* argv[]) { Context& simulator_context = diagram->GetMutableSubsystemContext(*sim_diagram, &simulator.get_mutable_context()); Context& controller_context = diagram->GetMutableSubsystemContext(*controller_diagram, &simulator.get_mutable_context()); - sim_diagram->get_radio_input_port().FixValue(&simulator_context, Eigen::VectorXd::Zero(18)); - controller_diagram->get_radio_input_port().FixValue(&controller_context, Eigen::VectorXd::Zero(18)); + sim_diagram->get_input_port_radio().FixValue(&simulator_context, Eigen::VectorXd::Zero(18)); + controller_diagram->get_input_port_radio().FixValue(&controller_context, Eigen::VectorXd::Zero(18)); new_plant.SetPositionsAndVelocities(&plant_context, x_init); simulator.Initialize(); diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel index 120b0b2e8b..66e42dc00c 100644 --- a/examples/Cassie/diagrams/BUILD.bazel +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -40,6 +40,7 @@ cc_library( "//examples/Cassie:cassie_urdf", "//examples/Cassie:cassie_utils", "//examples/Cassie/osc_run:osc_run", + "//examples/Cassie/contact_scheduler:all", "//examples/Cassie/osc:osc", "//lcm:trajectory_saver", "//multibody:utils", diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 7798c1633e..c88682f624 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -5,13 +5,10 @@ #include #include -#include "dairlib/lcmt_cassie_out.hpp" -#include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_fixed_point_solver.h" #include "examples/Cassie/cassie_utils.h" #include "multibody/multibody_utils.h" -#include "systems/framework/geared_motor.h" #include "systems/primitives/radio_parser.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" @@ -19,12 +16,9 @@ #include "drake/geometry/drake_visualizer.h" #include "drake/lcm/drake_lcm.h" -#include "drake/lcmt_contact_results_for_viz.hpp" #include "drake/multibody/plant/contact_results_to_lcm.h" -#include "drake/systems/analysis/runge_kutta2_integrator.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/primitives/discrete_time_delay.h" @@ -81,7 +75,7 @@ CassieSimDiagram::CassieSimDiagram( sensor_aggregator_ = &AddImuAndAggregator(&builder, *plant_, constant_source->get_output_port()); - cassie_motor_ = &AddMotorModel(&builder, *plant); + cassie_motor_ = &AddMotorModel(&builder, *plant_); auto radio_parser = builder.AddSystem(); diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 005805e0ae..3d34ca2641 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -26,24 +26,24 @@ class CassieSimDiagram : public drake::systems::Diagram { double mu = 0.8, double stiffness = 1e4, double dissipation_rate = 1e2); /// @return the input port for the actuation command. - const drake::systems::InputPort& get_actuation_input_port() const { - return this->get_input_port(actuation_input_port_index_); + const drake::systems::InputPort& get_input_port_actuation() const { + return this->get_input_port(actuation_port_); } /// @return the input port for the radio struct. - const drake::systems::InputPort& get_radio_input_port() const { - return this->get_input_port(radio_input_port_index_); + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); } /// @return the output port for the plant state as an OutputVector. - const drake::systems::OutputPort& get_state_output_port() const { - return this->get_output_port(state_output_port_index_); + const drake::systems::OutputPort& get_output_port_state() const { + return this->get_output_port(state_port_); } - /// @return the output port for the failure status of the controller. - const drake::systems::OutputPort& get_cassie_out_output_port_index() + /// @return the output port for the lcmt_cassie_out_message + const drake::systems::OutputPort& get_output_port_cassie_out() const { - return this->get_output_port(cassie_out_output_port_index_); + return this->get_output_port(cassie_out_port_); } drake::multibody::MultibodyPlant& get_plant() { @@ -59,10 +59,10 @@ class CassieSimDiagram : public drake::systems::Diagram { const systems::GearedMotor* cassie_motor_; // const systems::RadioParser* radio_parser_; drake::geometry::SceneGraph* scene_graph_; - const int actuation_input_port_index_ = 0; - const int radio_input_port_index_ = 1; - const int state_output_port_index_ = 0; - const int cassie_out_output_port_index_ = 1; + const int actuation_port_ = 0; + const int radio_port_ = 1; + const int state_port_ = 0; + const int cassie_out_port_ = 1; const double actuator_delay = 5e-3; // 5ms const double actuator_update_rate = 1e-3; // 1ms const double dt_ = 8e-5; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index bde4c19d08..77aaa584fe 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -8,6 +8,7 @@ #include "common/find_resource.h" #include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" @@ -162,9 +163,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( } accumulated_state_durations.pop_back(); - auto fsm = builder.AddSystem( - plant, fsm_states, state_durations, 0.0, - osc_running_gains.impact_threshold, osc_running_gains.impact_tau); + std::set impact_states = {LEFT_STANCE, RIGHT_STANCE}; + auto contact_scheduler = builder.AddSystem( + plant, plant_context.get(), impact_states, gains.impact_threshold, + gains.impact_tau); auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); @@ -227,10 +229,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.rest_length); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", - osc_running_gains.relative_feet, 0, accumulated_state_durations); + osc_running_gains.relative_feet, LEFT_STANCE); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", - osc_running_gains.relative_feet, 1, accumulated_state_durations); + osc_running_gains.relative_feet, RIGHT_STANCE); l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( @@ -439,24 +441,36 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /*****Connect ports*****/ // OSC connections - builder.Connect(fsm->get_fsm_output_port(), osc->get_input_port_fsm()); - builder.Connect(fsm->get_output_port_impact_info(), + builder.Connect(contact_scheduler->get_output_port_fsm(), + osc->get_input_port_fsm()); + builder.Connect(contact_scheduler->get_output_port_impact_info(), osc->get_input_port_impact_info()); - builder.Connect(fsm->get_output_port_clock(), osc->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_clock(), + osc->get_input_port_clock()); + builder.Connect(state_receiver->get_output_port(0), ekf_filter->get_input_port()); builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), - fsm->get_state_input_port()); + contact_scheduler->get_input_port_state()); // Trajectory generator connections + + builder.Connect( + contact_scheduler->get_output_port_contact_scheduler(), + pelvis_trans_traj_generator->get_contact_scheduler_input_port()); + builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + l_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + r_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(state_receiver->get_output_port(0), pelvis_trans_traj_generator->get_state_input_port()); - builder.Connect(fsm->get_fsm_output_port(), + builder.Connect(contact_scheduler->get_output_port_fsm(), pelvis_trans_traj_generator->get_fsm_input_port()); - builder.Connect(fsm->get_output_port_clock(), + builder.Connect(contact_scheduler->get_output_port_clock(), pelvis_trans_traj_generator->get_clock_input_port()); builder.Connect(high_level_command->get_xy_output_port(), l_foot_traj_generator->get_input_port_target_vel()); @@ -466,9 +480,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( l_foot_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), r_foot_traj_generator->get_input_port_state()); - builder.Connect(fsm->get_fsm_output_port(), + + builder.Connect(contact_scheduler->get_output_port_clock(), + l_foot_traj_generator->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_clock(), + r_foot_traj_generator->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_fsm(), l_foot_traj_generator->get_input_port_fsm()); - builder.Connect(fsm->get_fsm_output_port(), + builder.Connect(contact_scheduler->get_output_port_fsm(), r_foot_traj_generator->get_input_port_fsm()); builder.Connect(state_receiver->get_output_port(0), left_toe_angle_traj_gen->get_input_port_state()); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index bbfabbb491..c3ae6377e9 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -43,35 +43,33 @@ class OSCRunningControllerDiagram final const std::string& osqp_settings_filename); /// @return the input port for the plant state. - const drake::systems::InputPort& get_state_input_port() const { - return this->get_input_port(state_input_port_index_); + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); } /// @return the input port for the cassie_out struct (containing radio /// commands). - const drake::systems::InputPort& get_radio_input_port() const { - return this->get_input_port(radio_input_port_index_); + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); } - /// @return the output port for the controller torques. - const drake::systems::OutputPort& get_control_output_port() const { - return this->get_output_port(control_output_port_index_); + /// @return the output port for the lcmt_robot_input message. + const drake::systems::OutputPort& get_output_port_robot_input() const { + return this->get_output_port(control_port_); } /// @return the output port for the controller torques. - const drake::systems::OutputPort& get_torque_output_port() const { - return this->get_output_port(torque_output_port_index_); + const drake::systems::OutputPort& get_output_port_torque() const { + return this->get_output_port(torque_port_); } /// @return the output port for the failure status of the controller. - const drake::systems::OutputPort& get_controller_failure_output_port() + const drake::systems::OutputPort& get_output_port_controller_failure() const { - return this->get_output_port(controller_failure_port_index_); + return this->get_output_port(controller_failure_port_); } - drake::multibody::MultibodyPlant& get_plant() { - return *plant_; - } + drake::multibody::MultibodyPlant& get_plant() { return *plant_; } private: drake::multibody::MultibodyPlant* plant_; @@ -139,11 +137,16 @@ class OSCRunningControllerDiagram final std::unique_ptr left_hip_yaw_tracking_data; std::unique_ptr right_hip_yaw_tracking_data; - const int state_input_port_index_ = 0; - const int radio_input_port_index_ = 1; - const int control_output_port_index_ = 0; - const int torque_output_port_index_ = 1; - const int controller_failure_port_index_ = 2; + const drake::systems::InputPortIndex + state_port_ = drake::systems::InputPortIndex(0); + const drake::systems::InputPortIndex + radio_port_ = drake::systems::InputPortIndex(1); + const drake::systems::OutputPortIndex control_port_ = + drake::systems::OutputPortIndex(0); + const drake::systems::OutputPortIndex torque_port_ = + drake::systems::OutputPortIndex(1); + const drake::systems::OutputPortIndex controller_failure_port_ = + drake::systems::OutputPortIndex(2); const std::string control_channel_name_ = "OSC_RUNNING"; }; diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.h b/examples/Cassie/diagrams/osc_walking_controller_diagram.h index b6155b8370..fdea148c70 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.h @@ -48,28 +48,28 @@ class OSCWalkingControllerDiagram final const std::string& osqp_settings_filename); /// @return the input port for the plant state. - const drake::systems::InputPort& get_state_input_port() const { + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_input_port_index_); } /// @return the input port for the cassie_out struct (containing radio /// commands). - const drake::systems::InputPort& get_radio_input_port() const { + const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_input_port_index_); } /// @return the output port for the controller torques. - const drake::systems::OutputPort& get_control_output_port() const { + const drake::systems::OutputPort& get_output_port_robot_input() const { return this->get_output_port(control_output_port_index_); } /// @return the output port for the controller torques. - const drake::systems::OutputPort& get_torque_output_port() const { + const drake::systems::OutputPort& get_output_port_torque() const { return this->get_output_port(torque_output_port_index_); } /// @return the output port for the failure status of the controller. - const drake::systems::OutputPort& get_controller_failure_output_port() + const drake::systems::OutputPort& get_output_port_controller_failure() const { return this->get_output_port(controller_failure_port_index_); } diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index eea8cc14ff..44df2eac6f 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -197,7 +197,7 @@ int do_main(int argc, char* argv[]) { double toe_spread = FLAGS_toe_spread; // Create a plant for CassieFixedPointSolver. // Note that we cannot use the plant from the above diagram, because after the - // diagram is built, plant.get_actuation_input_port().HasValue(*context) + // diagram is built, plant.get_input_port_actuation().HasValue(*context) // throws a segfault error drake::multibody::MultibodyPlant plant_for_solver(0.0); AddCassieMultibody(&plant_for_solver, nullptr, diff --git a/examples/Cassie/multibody_sim_w_ground_incline.cc b/examples/Cassie/multibody_sim_w_ground_incline.cc index 246a4a4a2d..83515db89e 100644 --- a/examples/Cassie/multibody_sim_w_ground_incline.cc +++ b/examples/Cassie/multibody_sim_w_ground_incline.cc @@ -254,7 +254,7 @@ int do_main(int argc, char* argv[]) { double toe_spread = .15; // Create a plant for CassieFixedPointSolver. // Note that we cannot use the plant from the above diagram, because after the - // diagram is built, plant.get_actuation_input_port().HasValue(*context) + // diagram is built, plant.get_input_port_actuation().HasValue(*context) // throws a segfault error drake::multibody::MultibodyPlant plant_for_solver(0.0); AddCassieMultibody(&plant_for_solver, nullptr, diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index e963e0eaeb..5b16d408ee 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -214,7 +214,7 @@ int do_main(int argc, char* argv[]) { double toe_spread = 0.1; // Create a plant for CassieFixedPointSolver. // Note that we cannot use the plant from the above diagram, because after the - // diagram is built, plant.get_actuation_input_port().HasValue(*context) + // diagram is built, plant.get_input_port_actuation().HasValue(*context) // throws a segfault error drake::multibody::MultibodyPlant plant_for_solver(0.0); AddCassieMultibody(&plant_for_solver, nullptr, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 15ea21073f..bae03cacee 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -523,19 +523,12 @@ int DoMain(int argc, char* argv[]) { /*****Connect ports*****/ // OSC connections - // builder.Connect(fsm->get_output_port_fsm(), osc->get_input_port_fsm()); builder.Connect(contact_scheduler->get_output_port_fsm(), osc->get_input_port_fsm()); builder.Connect(contact_scheduler->get_output_port_impact_info(), osc->get_input_port_impact_info()); builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); - // builder.Connect(contact_scheduler->get_output_port_fsm(), - // osc->get_input_port_fsm()); - // builder.Connect(contact_scheduler->get_output_port_impact_info(), - // osc->get_input_port_impact_info()); - // builder.Connect(contact_scheduler->get_output_port_clock(), - // osc->get_input_port_clock()); builder.Connect(state_receiver->get_output_port(0), ekf_filter->get_input_port()); @@ -543,8 +536,6 @@ int DoMain(int argc, char* argv[]) { osc->get_robot_output_input_port()); // FSM connections -// builder.Connect(state_receiver->get_output_port(0), -// fsm->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), contact_scheduler->get_input_port_state()); diff --git a/examples/Cassie/test/min_deps_mbt_sim.cc b/examples/Cassie/test/min_deps_mbt_sim.cc index 7a50899086..9c24a6cceb 100644 --- a/examples/Cassie/test/min_deps_mbt_sim.cc +++ b/examples/Cassie/test/min_deps_mbt_sim.cc @@ -60,7 +60,7 @@ int do_main(int argc, char* argv[]) { Eigen::VectorXd::Zero(plant.num_actuators())); builder.Connect(input_source->get_output_port(), - plant.get_actuation_input_port()); + plant.get_input_port_actuation()); builder.Connect( plant.get_geometry_poses_output_port(), From 4993cdb7773edad3a407f2fc2d5d0c47d8081412 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 9 Aug 2022 16:13:52 -0400 Subject: [PATCH 265/758] need to figure out why gym is failing --- examples/Cassie/contact_scheduler/contact_scheduler.cc | 5 +++-- examples/Cassie/contact_scheduler/contact_scheduler.h | 2 +- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 4 ++-- 3 files changed, 6 insertions(+), 5 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 0a51aad65d..8fe03fdb1d 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -1,6 +1,7 @@ #include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include +#include #include @@ -29,12 +30,12 @@ using systems::OutputVector; ContactScheduler::ContactScheduler(const MultibodyPlant& plant, Context* plant_context, - std::set& impact_states, + std::set impact_states, double near_impact_threshold, double tau, BLEND_FUNC blend_func) : plant_(plant), plant_context_(plant_context), - impact_states_(impact_states), + impact_states_(std::move(impact_states)), near_impact_threshold_(near_impact_threshold), tau_(tau), blend_func_(blend_func) { diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 0ba8dbcdcc..5688af3952 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -21,7 +21,7 @@ class ContactScheduler : public drake::systems::LeafSystem { public: ContactScheduler(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* plant_context, - std::set& impact_states, + std::set impact_states, double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 733e652bb5..ffde5cef33 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -14,7 +14,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.001 w_soft_constraint: 100 -x_offset: -0.02 +x_offset: 0.06 relative_feet: true mu: 0.4 @@ -29,7 +29,7 @@ hip_yaw_kd: 5 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.000 +landing_delay: 0.045 CoMW: [20, 0, 0, From df7acd011f10353ce02013ab33e5aa2b94307f61 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 9 Aug 2022 17:19:26 -0400 Subject: [PATCH 266/758] updating running gains to match toy examples --- examples/Cassie/osc_run/osc_running_gains.yaml | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index f4dd76ae49..aae6cd4518 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0001 w_input_reg: 0.1 w_accel: 0.0001 -w_soft_constraint: 100 +w_soft_constraint: 0 impact_threshold: 0.05 impact_tau: 0.005 mu: 0.6 @@ -43,7 +43,7 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.08 -footstep_lateral_offset: 0.04 # drake +footstep_lateral_offset: 0.03 # drake mid_foot_height: 0.05 FootstepKd: [ 0.15, 0, 0, @@ -56,11 +56,11 @@ PelvisW: PelvisKp: [ -50, 0, 0, 0, 50, 0, - 0, 0, 105] + 0, 0, 150] PelvisKd: [ 2, 0, 0, 0, 2, 0, - 0, 0, 3.5 ] + 0, 0, 4 ] PelvisRotW: [ 10, 0, 0, 0, 10, 0, From a4eed38440da130ddfd4d17fce17bb7aa3b2ea9e Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 10 Aug 2022 15:58:23 -0400 Subject: [PATCH 267/758] updating contact scheduler --- .../pydairlib/analysis/mbp_plotting_utils.py | 1 - .../plot_configs/cassie_default_plot.yaml | 5 +- .../plot_configs/cassie_running_plot.yaml | 10 +- .../contact_scheduler/contact_scheduler.cc | 2 +- .../state_based_controller_switch.cc | 125 ++++++++++++++++++ .../director_scripts/show_time_hardware.py | 6 +- .../Cassie/osc_run/osc_running_gains.yaml | 12 +- examples/Cassie/run_osc_running_controller.cc | 6 +- examples/Cassie/urdf/cassie_v2.urdf | 8 +- 9 files changed, 152 insertions(+), 23 deletions(-) create mode 100644 examples/Cassie/contact_scheduler/state_based_controller_switch.cc diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 8111105eae..6f3ba74fe9 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -443,7 +443,6 @@ def plot_tracking_costs(osc_debug, time_slice): data_dict = \ {key: val for key, val in osc_debug['tracking_cost'].items()} data_dict['t_osc'] = osc_debug['t_osc'] - plotting_utils.make_plot( data_dict, 't_osc', diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index 7b96b46d1f..f260a10bd8 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -22,7 +22,7 @@ plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -special_positions_to_plot: [ ] +special_positions_to_plot: ['knee_joint_left', 'knee_joint_right'] special_velocities_to_plot: [ ] special_efforts_to_plot: [ ] @@ -36,9 +36,10 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true -plot_tracking_costs: true +plot_tracking_costs: false plot_qp_solutions: true plot_qp_solve_time: true +plot_active_tracking_datas: false tracking_datas_to_plot: alip_com_traj: { 'dims': [ 0, 1 ], 'derivs': [ 'vel' ] } swing_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'accel' ] } diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 815a67fb06..c344ddfa5f 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,6 +1,6 @@ # LCM channels to read data from -#channel_x: "CASSIE_STATE_DISPATCHER" -channel_x: "CASSIE_STATE_SIMULATION" +channel_x: "CASSIE_STATE_DISPATCHER" +#channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false @@ -22,7 +22,7 @@ plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -special_positions_to_plot: [] +special_positions_to_plot: ['knee_joint_left', 'knee_joint_right'] special_velocities_to_plot: [] special_efforts_to_plot: [ ] @@ -43,11 +43,11 @@ plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': ['vel'] }, + pelvis_trans_traj: { 'dims': [2 ], 'derivs': ['pos', 'vel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [0, 2], 'derivs': ['pos'] }, - left_ft_traj: {'dims': [2], 'derivs': ['vel']}, + left_ft_traj: {'dims': [2], 'derivs': ['pos']}, # left_ft_z_traj: {'dims': [0], 'derivs': ['pos']}, # right_ft_z_traj: {'dims': [0, 2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 8fe03fdb1d..a509b78ff0 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -202,7 +202,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( } double next_transition_time = stored_transition_time + - drake::math::saturate(time_to_touchdown, 0.07, 0.10); + drake::math::saturate(time_to_touchdown, 0.05, 0.15); state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = next_transition_time - stored_transition_time; if (active_state == LEFT_FLIGHT) { diff --git a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc new file mode 100644 index 0000000000..e734df3bfd --- /dev/null +++ b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc @@ -0,0 +1,125 @@ +#include +#include + +#include + +#include "dairlib/lcmt_controller_switch.hpp" +#include "dairlib/lcmt_robot_output.hpp" + +#include "drake/lcm/drake_lcm.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/serializer.h" + +namespace dairlib { + +using drake::systems::TriggerType; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::TriggerTypeSet; + +DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", + "The name of the channel which receives state"); +DEFINE_string(switch_channel, "INPUT_SWITCH", + "The name of the channel which sends the channel name that " + "dispatcher_in listens to"); +DEFINE_string(new_channel, "PD_CONTROL", + "The name of the new lcm channel that dispatcher_in listens to " + "after switch"); +DEFINE_double(trigger_state, -1.0, " the period of TimeBasedFiniteStateMachine"); +DEFINE_double(blend_duration, 1.0, + "Duration to blend efforts between previous and current " + "controller command"); + +/// This program is a one-time-use switch that tells dispatcher_robot_in which +/// channel to listen to. It publishes the lcm message, +/// dairlib::lcmt_controller_switch, which contains a string of the channel +/// name. + +/// The program is extended so that it could be used with +/// new controller is still in a middle of a discrete state). This requires that +/// the users provide two (or three) more arguments to the constructors besides +/// `new_channel`: +/// @param trigger_state, the FSM state to switch on` +/// + + +int do_main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Parameters + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + + // Build the diagram + drake::systems::DiagramBuilder builder; + auto name_pub = builder.AddSystem( + LcmPublisherSystem::Make( + FLAGS_switch_channel, &lcm_local, + TriggerTypeSet({TriggerType::kForced}))); + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("switch publisher")); + + // Create simulator + drake::systems::Diagram* diagram_ptr = owned_diagram.get(); + drake::systems::Simulator simulator(std::move(owned_diagram)); + auto& diagram_context = simulator.get_mutable_context(); + + // Create subscriber for lcm driven loop + drake::lcm::Subscriber input_sub(&lcm_local, + FLAGS_channel_x); + + // Wait for the first message and initialize the context time.. + drake::log()->info("Waiting for first lcm input message"); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); + const double t0 = input_sub.message().utime * 1e-6; + diagram_context.SetTime(t0); + + // Set the threshold time + double t_threshold = t0; + if (FLAGS_n_period_delay > 0) { + t_threshold = (floor(t0 / FLAGS_fsm_period) + FLAGS_n_period_delay) * + FLAGS_fsm_period + + FLAGS_fsm_offset; + } + // Create output message + dairlib::lcmt_controller_switch msg; + msg.channel = FLAGS_new_channel; + msg.blend_duration = FLAGS_blend_duration; + + // Run the simulation until it publishes the channel name `n_publishes` times + drake::log()->info(diagram_ptr->get_name() + " started"); + int pub_count = 0; + while (pub_count < FLAGS_n_publishes) { + // Wait for input message. + input_sub.clear(); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); + + // Get message time from the input channel + double t_current = input_sub.message().utime * 1e-6; + if (t_current >= t_threshold) { + std::cout << "publish at t = " << t_current << std::endl; + + msg.utime = (int)input_sub.message().utime; + name_pub->get_input_port().FixValue( + &(diagram_ptr->GetMutableSubsystemContext(*name_pub, + &diagram_context)), + msg); + + // Force-publish via the diagram + /// We don't need AdvanceTo(time) because we manually force publish lcm + /// message, and there is nothing in the diagram that needs to be updated. + diagram_ptr->Publish(diagram_context); + + pub_count++; + } + } + drake::log()->info(diagram_ptr->get_name() + " ended"); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/Cassie/director_scripts/show_time_hardware.py b/examples/Cassie/director_scripts/show_time_hardware.py index f4d7c27f74..e123096cd9 100644 --- a/examples/Cassie/director_scripts/show_time_hardware.py +++ b/examples/Cassie/director_scripts/show_time_hardware.py @@ -16,7 +16,7 @@ def __init__(self): self._pelvis_velocity = [] self._subscriber = None # Number of messages used to average for real time factor. - self._num_msg_for_average = 50 + self._num_msg_for_average = 20 self.set_enabled(True) @@ -55,7 +55,9 @@ def set_enabled(self, enable): def handle_message(self, msg): msg_time = msg.utime * 1e-6 # convert from microseconds pelvis_height = (msg.position)[6] # convert from microseconds - pelvis_velocity = np.linalg.norm((msg.velocity)[3:5]) # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds + # pelvis_height = (msg.position)[2] # convert from microseconds + # pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds self._real_time.append(time.time()) self._msg_time.append(msg_time) self._pelvis_velocity.append(pelvis_velocity) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index aae6cd4518..eac0b46d74 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ w_input: 0.0001 w_input_reg: 0.1 w_accel: 0.0001 -w_soft_constraint: 0 +w_soft_constraint: 100 impact_threshold: 0.05 impact_tau: 0.005 mu: 0.6 @@ -21,11 +21,11 @@ W_lambda_h_reg: [ 0.01, 0.01, 0.01, relative_feet: true relative_pelvis: true -ekf_filter_tau: [ 0.05, 0.01, 0.01 ] +ekf_filter_tau: [ 0.001, 0.01, 0.001 ] # High level command gains (with radio) -vel_scale_rot: -0.5 -vel_scale_trans_sagital: 0.25 +vel_scale_rot: -2 +vel_scale_trans_sagital: 0.5 vel_scale_trans_lateral: -0.0 # SLIP parameters @@ -42,11 +42,11 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.08 +footstep_sagital_offset: -0.03 footstep_lateral_offset: 0.03 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.15, 0, 0, + [ 0.2, 0, 0, 0, 0.7, 0, 0, 0, 0 ] PelvisW: diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index bae03cacee..21c9339006 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -194,9 +194,9 @@ int DoMain(int argc, char* argv[]) { auto contact_scheduler_debug_publisher = builder.AddSystem(LcmPublisherSystem::Make( "CONTACT_TIMING", &lcm, TriggerTypeSet({TriggerType::kForced}))); - std::vector tau = {.05, .01, .01}; +// std::vector tau = {.05, .01, .01}; auto ekf_filter = - builder.AddSystem(plant, tau); + builder.AddSystem(plant, osc_gains.ekf_filter_tau); /**** OSC setup ****/ // Cost @@ -534,6 +534,8 @@ int DoMain(int argc, char* argv[]) { ekf_filter->get_input_port()); builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); +// builder.Connect(state_receiver->get_output_port(0), +// osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/Cassie/urdf/cassie_v2.urdf b/examples/Cassie/urdf/cassie_v2.urdf index 6597f1931b..bb0f7ca0b5 100644 --- a/examples/Cassie/urdf/cassie_v2.urdf +++ b/examples/Cassie/urdf/cassie_v2.urdf @@ -713,8 +713,8 @@ - - + + @@ -722,8 +722,8 @@ - - + + From dd4deb82a97b678c58ceb7ab1c80bd845f561976 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 10 Aug 2022 16:47:18 -0400 Subject: [PATCH 268/758] adding state based controller switch --- examples/Cassie/contact_scheduler/BUILD.bazel | 10 +++++ .../contact_scheduler/contact_scheduler.cc | 2 +- .../state_based_controller_switch.cc | 38 ++++++++++++------- .../Cassie/osc_run/osc_running_gains.yaml | 6 +-- 4 files changed, 39 insertions(+), 17 deletions(-) diff --git a/examples/Cassie/contact_scheduler/BUILD.bazel b/examples/Cassie/contact_scheduler/BUILD.bazel index b2f603c7bf..8f3ec0ca63 100644 --- a/examples/Cassie/contact_scheduler/BUILD.bazel +++ b/examples/Cassie/contact_scheduler/BUILD.bazel @@ -50,3 +50,13 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_binary( + name = "state_based_controller_switch", + srcs = ["state_based_controller_switch.cc"], + deps = [ + "@drake//:drake_shared_library", + "//lcmtypes:lcmt_robot", + "@gflags", + ], +) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index a509b78ff0..37238ee719 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -202,7 +202,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( } double next_transition_time = stored_transition_time + - drake::math::saturate(time_to_touchdown, 0.05, 0.15); + drake::math::saturate(time_to_touchdown, 0.08, 0.12); state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = next_transition_time - stored_transition_time; if (active_state == LEFT_FLIGHT) { diff --git a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc index e734df3bfd..2873fc7348 100644 --- a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc +++ b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc @@ -2,6 +2,7 @@ #include #include +#include #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" @@ -15,8 +16,8 @@ namespace dairlib { using drake::systems::TriggerType; -using drake::systems::lcm::LcmPublisherSystem; using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", "The name of the channel which receives state"); @@ -26,7 +27,13 @@ DEFINE_string(switch_channel, "INPUT_SWITCH", DEFINE_string(new_channel, "PD_CONTROL", "The name of the new lcm channel that dispatcher_in listens to " "after switch"); -DEFINE_double(trigger_state, -1.0, " the period of TimeBasedFiniteStateMachine"); +DEFINE_string(contact_schedule_channel, "CONTACT_TIMING", + "The name of the lcm channel that publishes contact timings"); +DEFINE_double(trigger_state, -1.0, + " the period of TimeBasedFiniteStateMachine"); +DEFINE_double(fsm_offset, 0.0, + "a constant that's used to determined the publish time see the " + "documentation below for details"); DEFINE_double(blend_duration, 1.0, "Duration to blend efforts between previous and current " "controller command"); @@ -43,7 +50,6 @@ DEFINE_double(blend_duration, 1.0, /// @param trigger_state, the FSM state to switch on` /// - int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -67,6 +73,8 @@ int do_main(int argc, char* argv[]) { // Create subscriber for lcm driven loop drake::lcm::Subscriber input_sub(&lcm_local, FLAGS_channel_x); + drake::lcm::Subscriber timing_sub(&lcm_local, + FLAGS_contact_schedule_channel); // Wait for the first message and initialize the context time.. drake::log()->info("Waiting for first lcm input message"); @@ -75,22 +83,26 @@ int do_main(int argc, char* argv[]) { const double t0 = input_sub.message().utime * 1e-6; diagram_context.SetTime(t0); - // Set the threshold time - double t_threshold = t0; - if (FLAGS_n_period_delay > 0) { - t_threshold = (floor(t0 / FLAGS_fsm_period) + FLAGS_n_period_delay) * - FLAGS_fsm_period + - FLAGS_fsm_offset; + drake::log()->info(diagram_ptr->get_name() + " started"); + + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return timing_sub.count() > 0; }); + while(timing_sub.message().transition_states.back() != FLAGS_trigger_state){ + timing_sub.clear(); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return timing_sub.count() > 0; }); } + const double transition_time = timing_sub.message().transition_times.back() + FLAGS_fsm_offset; + std::cout << "transition time: " << transition_time << std::endl; + // Create output message dairlib::lcmt_controller_switch msg; msg.channel = FLAGS_new_channel; msg.blend_duration = FLAGS_blend_duration; - // Run the simulation until it publishes the channel name `n_publishes` times - drake::log()->info(diagram_ptr->get_name() + " started"); + int pub_count = 0; - while (pub_count < FLAGS_n_publishes) { + while (pub_count < 1) { // Wait for input message. input_sub.clear(); LcmHandleSubscriptionsUntil(&lcm_local, @@ -98,7 +110,7 @@ int do_main(int argc, char* argv[]) { // Get message time from the input channel double t_current = input_sub.message().utime * 1e-6; - if (t_current >= t_threshold) { + if (t_current >= transition_time) { std::cout << "publish at t = " << t_current << std::endl; msg.utime = (int)input_sub.message().utime; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index eac0b46d74..2f7b3f1ae3 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -42,11 +42,11 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.03 -footstep_lateral_offset: 0.03 # drake +footstep_sagital_offset: -0.08 +footstep_lateral_offset: 0.01 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.2, 0, 0, + [ 0.18, 0, 0, 0, 0.7, 0, 0, 0, 0 ] PelvisW: From 307624bd89a58bf2c9405514c955bc41d61889ec Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 11 Aug 2022 16:47:04 -0400 Subject: [PATCH 269/758] optimizing long jumps --- examples/Cassie/run_dircon_jumping.cc | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 91951b6b66..101ab6639b 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -286,16 +286,16 @@ void DoMain() { land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); land_mode.MakeConstraintRelative(left_toe_eval_ind, 1); - land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); +// land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); land_mode.MakeConstraintRelative(left_heel_eval_ind, 0); land_mode.MakeConstraintRelative(left_heel_eval_ind, 1); - land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); +// land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); land_mode.MakeConstraintRelative(right_toe_eval_ind, 0); land_mode.MakeConstraintRelative(right_toe_eval_ind, 1); - land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); +// land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); land_mode.MakeConstraintRelative(right_heel_eval_ind, 0); land_mode.MakeConstraintRelative(right_heel_eval_ind, 1); - land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); +// land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); auto all_modes = DirconModeSequence(plant); all_modes.AddMode(&crouch_mode); @@ -346,6 +346,8 @@ void DoMain() { // target nonlinear constraint violation prog.SetSolverOption(id, "Major optimality tolerance", 1e-5 / FLAGS_cost_scaling); +// prog.SetSolverOption(id, "Major optimality tolerance", +// 1e-5); // target complementarity gap prog.SetSolverOption(id, "Major feasibility tolerance", tol); @@ -445,7 +447,7 @@ void SetKinematicConstraints(Dircon *trajopt, // Standing constraints double rest_height = FLAGS_start_height; - double eps = 1e-6; + double eps = 1e-4; double midpoint = 0.045; @@ -620,11 +622,11 @@ void SetKinematicConstraints(Dircon *trajopt, -0.15 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); auto left_foot_z_ground_constraint = std::make_shared>( - plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); auto right_foot_z_ground_constraint = std::make_shared>( - plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); for (int mode: {0, 1, 2}) { @@ -829,7 +831,7 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); - MatrixXd R = 1e-1 * MatrixXd::Identity(n_u, n_u); + MatrixXd R = 1e1 * MatrixXd::Identity(n_u, n_u); // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = // 5e-1; // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) From 5d39b36aca392b6e123f345194f29a0ddd972fd9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 15 Aug 2022 15:34:03 -0400 Subject: [PATCH 270/758] updating plot settings --- .../pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml | 4 ++-- .../pydairlib/analysis/plot_configs/cassie_running_plot.yaml | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 9a9c4a3b4d..871ad24b36 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_JUMPING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 15 -duration: -1 +start_time: 20 +duration: 5 # Plant properties use_springs: true diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index c344ddfa5f..bd23625d0d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,7 +6,7 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 0 +start_time: 5 duration: -1 # Plant properties From 48b02f19a96f6b72ea2a911d2cbc80f582bbba5e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 15 Aug 2022 16:21:57 -0400 Subject: [PATCH 271/758] addressing comments --- examples/Cassie/BUILD.bazel | 7 +++++-- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 2 +- examples/Cassie/run_controller_switch.cc | 2 +- examples/Cassie/run_osc_walking_controller.cc | 2 +- examples/Cassie/run_osc_walking_controller_alip.cc | 2 +- examples/Cassie/visualizer.cc | 2 +- solvers/fast_osqp_solver.cc | 5 ++--- solvers/fast_osqp_solver.h | 1 + 9 files changed, 14 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index e30e881b34..4ff6bb2020 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -241,6 +241,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/primitives:vector_aggregator", "@drake//:drake_shared_library", + "@lcm", ], ) @@ -294,22 +295,24 @@ cc_library( ], ) -cc_binary( +cc_test( name = "log_timing_test", srcs = ["test/log_timing_test.cc"], deps = [ "//lcmtypes:lcmt_robot", "@drake//lcm", + "@lcm", "@gflags", ], ) -cc_binary( +cc_test( name = "dispatcher_log_timing_test", srcs = ["test/dispatcher_log_timing_test.cc"], deps = [ "//lcmtypes:lcmt_robot", "@drake//lcm", + "@lcm", "@gflags", ], ) diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 2905f48df6..304c2d7a56 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -67,7 +67,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 33b2f2b5c2..f499cd1168 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -158,7 +158,7 @@ int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); DiagramBuilder builder; - auto lcm = builder.AddSystem(); + auto lcm = builder.AddSystem("udpm://239.255.76.67:7667?ttl=0"); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); // Build Cassie MBP diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index 405bbc0ba3..68032c1f44 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -81,7 +81,7 @@ int do_main(int argc, char* argv[]) { // Build the diagram drake::systems::DiagramBuilder builder; - auto lcm = builder.AddSystem(); + auto lcm = builder.AddSystem("udpm://239.255.76.67:7667?ttl=0"); auto name_pub = builder.AddSystem( LcmPublisherSystem::Make( FLAGS_switch_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index d0f0389688..8dbe0a030a 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -112,7 +112,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index d2f40c18a0..80d1cf536c 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -117,7 +117,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // Get contact frames and position (doesn't matter whether we use // plant_w_spr or plant_wospr because the contact frames exit in both diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index e78556114a..9609464ec7 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -109,7 +109,7 @@ int do_main(int argc, char* argv[]) { scene_graph.get_source_pose_port(ball_plant->get_source_id().value())); } - DrakeVisualizer::AddToBuilder(&builder, scene_graph); + DrakeVisualizer::AddToBuilder(&builder, scene_graph, lcm); // state_receiver->set_publish_period(1.0/30.0); // framerate diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 0e86963780..94e3e253d4 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -115,7 +115,6 @@ void ParseLinearCosts(const MathematicalProgram& prog, std::vector* q, } } - // OSQP defines its own infinity in osqp/include/glob_opts.h. c_float ConvertInfinity(double val) { if (std::isinf(val)) { @@ -432,14 +431,14 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, osqp_data_->A = EigenSparseToCSC(A_sparse); osqp_data_->l = l.data(); osqp_data_->u = u.data(); - // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; // Solve problem. if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); - const c_int osqp_setup_err = osqp_setup(&workspace_, osqp_data_, osqp_settings_); + const c_int osqp_setup_err = + osqp_setup(&workspace_, osqp_data_, osqp_settings_); if (osqp_setup_err != 0) { solution_result = SolutionResult::kInvalidInput; } diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index 5e9059fb24..d6072883c1 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -1,5 +1,6 @@ #pragma once +#include #include #include "drake/common/drake_copyable.h" From 2a0dc0a9e819e55ac34b946aa3bbd9b5ecde704c Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 15 Aug 2022 16:28:08 -0400 Subject: [PATCH 272/758] removing ubuntu bionic as it's no longer supported by drake --- .cirrus.yml | 20 +------------------- 1 file changed, 1 insertion(+), 19 deletions(-) diff --git a/.cirrus.yml b/.cirrus.yml index 9caee7ec70..ea7bb92db8 100644 --- a/.cirrus.yml +++ b/.cirrus.yml @@ -1,21 +1,3 @@ -build_task: - timeout_in: 120m - container: - dockerfile: install/bionic/Dockerfile - cpu: 8 - memory: 24 - test_script: - - bazel build - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - --jobs=8 - //... - - bazel test - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - //... build_focal_task: timeout_in: 120m container: @@ -63,7 +45,7 @@ build_with_ros_task: drake_master_build_task: timeout_in: 120m container: - dockerfile: install/bionic/ros/Dockerfile + dockerfile: install/focal/ros/Dockerfile cpu: 8 memory: 24 allow_failures: true From efc9ebc6708f88503f3e176f89040464f74a78fd Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 16 Aug 2022 11:42:17 -0400 Subject: [PATCH 273/758] updating dockerfile --- examples/Cassie/BUILD.bazel | 4 ++-- install/focal/Dockerfile | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 4ff6bb2020..2dcb370d82 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -295,7 +295,7 @@ cc_library( ], ) -cc_test( +cc_binary( name = "log_timing_test", srcs = ["test/log_timing_test.cc"], deps = [ @@ -306,7 +306,7 @@ cc_test( ], ) -cc_test( +cc_binary( name = "dispatcher_log_timing_test", srcs = ["test/dispatcher_log_timing_test.cc"], deps = [ diff --git a/install/focal/Dockerfile b/install/focal/Dockerfile index c3c78e1928..8033b6125f 100644 --- a/install/focal/Dockerfile +++ b/install/focal/Dockerfile @@ -2,7 +2,7 @@ FROM ros:noetic-ros-base-focal WORKDIR /dairlib ENV DAIRLIB_DOCKER_VERSION_25=25 COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python clang-12 +RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python clang-12 clang-format-12 RUN set -eux \ && apt-get install --no-install-recommends locales \ && locale-gen en_US.UTF-8 From 5d9a4f17403745f3575dbc6eeed3c58fd709aa36 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 16 Aug 2022 12:00:37 -0400 Subject: [PATCH 274/758] updating drake commit tag --- WORKSPACE | 4 +- .../Cassie/director_scripts/show_time_sim.py | 99 +++++++++++++++++++ 2 files changed, 101 insertions(+), 2 deletions(-) create mode 100644 examples/Cassie/director_scripts/show_time_sim.py diff --git a/WORKSPACE b/WORKSPACE index 14bc1615a9..e5dac2426f 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,9 +11,9 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "0b90deb0553a1a8cfa392371ef5c4c49ec024912" +DRAKE_COMMIT = "7ed177b58a6200b248928eb7519dd0eff4e04a14" -DRAKE_CHECKSUM = "b281c4c0c77819bdb9ff1be47a02e4ef0400b333693be6be24e5a9577753f416" +DRAKE_CHECKSUM = "a3ab84e9b2fa663158966b4b78b96dda5b2b6da96d24636245b645812270d98b" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. # DRAKE_CHECKSUM = "0" * 64 diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py new file mode 100644 index 0000000000..0ed188c336 --- /dev/null +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -0,0 +1,99 @@ +# Note that this script runs in the main context of drake-visulizer, +# where many modules and variables already exist in the global scope. +from director import lcmUtils +from director import applogic +import time +import dairlib.lcmt_robot_output + + +class TimeVisualizer(object): + + def __init__(self): + self._name = "Time Visualizer" + self._real_time = [] + self._msg_time = [] + self._pelvis_velocity = [] + self._subscriber = None + # Number of messages used to average for real time factor. + self._num_msg_for_average = 20 + + self.set_enabled(True) + + def add_subscriber(self): + if (self._subscriber is not None): + return + + if 'pd_panel_state_channel' in globals(): + channel = pd_panel_state_channel + else: + # channel = "NETWORK_CASSIE_STATE_DISPATCHER" + channel = "CASSIE_STATE_SIMULATION" + + self._subscriber = lcmUtils.addSubscriber( + channel, + messageClass=dairlib.lcmt_robot_output, + callback=self.handle_message) + + def remove_subscriber(self): + if (self._subscriber is None): + return + + lcmUtils.removeSubscriber(self._subscriber) + self._subscriber = None + vis.updateText('', 'text') + + def is_enabled(self): + return self._subscriber is not None + + def set_enabled(self, enable): + if enable: + self.add_subscriber() + else: + self.remove_subscriber() + + def handle_message(self, msg): + msg_time = msg.utime * 1e-6 # convert from microseconds + # Drake Sim + pelvis_height = (msg.position)[6] # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds + # pelvis_height = (msg.position)[2] # convert from microseconds + # pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds + self._real_time.append(time.time()) + self._msg_time.append(msg_time) + self._pelvis_velocity.append(pelvis_velocity) + + my_text = 'time: %.3f' % msg_time + pelvis_height_text = 'pelvis height: %.3f' % pelvis_height + + pelvis_velocity_text = 'pelvis velocity: %.3f' % np.array(self._pelvis_velocity).mean() + realtime_text = '' + + if (len(self._real_time) >= self._num_msg_for_average): + self._real_time.pop(0) + self._msg_time.pop(0) + self._pelvis_velocity.pop(0) + + + dt = self._msg_time[-1] - self._msg_time[0] + dt_real_time = self._real_time[-1] - self._real_time[0] + + rt_ratio = dt / dt_real_time + realtime_text = 'realtime rate: %.2f' % rt_ratio + # my_text = my_text + ', real time factor: %.2f' % rt_ratio + + vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text, 'text') + # vis.updateText(my_text + '\n' + pelvis_velocity_text, 'text') + + +def init_visualizer(): + time_viz = TimeVisualizer() + + # Adds to the "Tools" menu. + applogic.MenuActionToggleHelper( + 'Tools', time_viz._name, + time_viz.is_enabled, time_viz.set_enabled) + return time_viz + + +# Creates the visualizer when this script is executed. +time_viz = init_visualizer() From bedf944bfa7ee8ca01623ff14eb3ad6bb546cd1f Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 16 Aug 2022 12:01:37 -0400 Subject: [PATCH 275/758] updating ros dockerfile --- install/focal/ros/Dockerfile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/install/focal/ros/Dockerfile b/install/focal/ros/Dockerfile index 2020a9388b..57d8f7a8eb 100644 --- a/install/focal/ros/Dockerfile +++ b/install/focal/ros/Dockerfile @@ -4,7 +4,7 @@ ENV DAIRLIB_DOCKER_VERSION_26=26 ENV ROS_PYTHON_VERSION=3 COPY . . RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python -RUN apt-get install -y python3-rosinstall-generator python3-catkin-tools python3-vcstool python3-osrf-pycommon python3-vcstool python3-empy +RUN apt-get install -y python3-rosinstall-generator python3-catkin-tools python3-vcstool python3-osrf-pycommon python3-vcstool python3-empy clang-12 clang-format-12 RUN set -eux \ && apt-get install --no-install-recommends locales \ && locale-gen en_US.UTF-8 From 725112caa6f706de5099383acf33061be11d9875 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 16 Aug 2022 15:33:03 -0400 Subject: [PATCH 276/758] using common cost scaling --- .../plot_configs/cassie_running_plot.yaml | 8 +-- .../lcm/dircon_trajectory_plotter.py | 11 ++-- bindings/pydairlib/lcm/lcm_trajectory_py.cc | 1 + examples/Cassie/osc/osc_standing_gains.h | 38 ++++++++++- examples/Cassie/osc/osc_standing_gains.yaml | 5 +- .../Cassie/osc/osc_walking_gains_alip.yaml | 21 +++---- examples/Cassie/osc_run/osc_running_gains.h | 14 +++++ .../Cassie/osc_run/osc_running_gains.yaml | 14 +++-- examples/Cassie/run_dircon_jumping.cc | 8 +-- examples/Cassie/run_osc_running_controller.cc | 35 +++++------ .../Cassie/run_osc_standing_controller.cc | 63 ++++++------------- lcm/dircon_saved_trajectory.h | 16 ++--- .../osc/operational_space_control.cc | 8 ++- systems/controllers/osc/osc_gains.h | 6 +- 14 files changed, 139 insertions(+), 109 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index bd23625d0d..3bd47b7dbf 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -37,10 +37,10 @@ foot_xyz_to_plot: { 'right': [2], 'left': [2] } pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: false -plot_qp_solve_time: false -plot_qp_solutions: false -plot_tracking_costs: false +plot_qp_costs: true +plot_qp_solve_time: true +plot_qp_solutions: true +plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { pelvis_trans_traj: { 'dims': [2 ], 'derivs': ['pos', 'vel'] }, diff --git a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py index 109c47b7ab..93dd2917ad 100644 --- a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py @@ -20,7 +20,7 @@ def main(): # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/walking_0.16.0") # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/jumping_0.15h_0.3d") filename = FindResourceOrThrow( - "examples/Cassie/saved_trajectories/jumping_0.0h_1.0d_9") + "examples/Cassie/saved_trajectories/jumping_0.0h_0.6d_9") # filename = FindResourceOrThrow( # "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1") # filename = "/home/yangwill/Documents/research/projects/cassie/hardware/backup/dair/saved_trajectories/jumping_0.15h_0.3d" @@ -39,6 +39,7 @@ def main(): # force_datatypes = dircon_traj.GetTrajectory("force_vars0").datatypes force_datatypes = dircon_traj.GetTrajectory("force_vars2").datatypes + impulse_samples = dircon_traj.GetImpulseSamples(2) collocation_force_points = dircon_traj.GetCollocationForceSamples(0) # M = reflected_joints() # @@ -53,7 +54,6 @@ def main(): plot_only_at_knotpoints = True - print(force_t_samples) n_points = 500 t = np.linspace(state_traj.start_time(), state_traj.end_time(), n_points) @@ -70,16 +70,19 @@ def main(): input_samples[i] = input_traj.value(t[i])[:, 0] # force_samples[i] = force_traj[0].value(t[i])[:, 0] + import pdb; pdb.set_trace() # reflected_state_samples = state_samples @ M # Plotting reconstructed state trajectories plt.figure("state trajectory") - plt.plot(t, state_samples[:, 4:7]) + # plt.plot(t, state_samples[:, 4:7]) + plt.plot(t, state_samples[:, 22:25]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 0:7]) # plt.plot(t, state_samples[:, -18:]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 7:13]) # plt.plot(t, state_samples[:, 25:31]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 25:31]) - plt.legend(state_datatypes[4:7]) + # plt.legend(state_datatypes[4:7]) + plt.legend(state_datatypes[22:25]) # Velocity Error # plt.figure('velocity_error') diff --git a/bindings/pydairlib/lcm/lcm_trajectory_py.cc b/bindings/pydairlib/lcm/lcm_trajectory_py.cc index 088add2010..f6902b9343 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_py.cc +++ b/bindings/pydairlib/lcm/lcm_trajectory_py.cc @@ -66,6 +66,7 @@ PYBIND11_MODULE(lcm_trajectory, m) { .def("GetBreaks", &DirconTrajectory::GetBreaks) .def("GetForceSamples", &DirconTrajectory::GetForceSamples) .def("GetForceBreaks", &DirconTrajectory::GetForceBreaks) + .def("GetImpulseSamples", &DirconTrajectory::GetImpulseSamples) .def("GetCollocationForceSamples", &DirconTrajectory::GetCollocationForceSamples) .def("GetCollocationForceBreaks", diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h index af5a684553..75f9f5756c 100644 --- a/examples/Cassie/osc/osc_standing_gains.h +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -5,12 +5,15 @@ #include "drake/common/yaml/yaml_read_archive.h" -struct OSCStandingGains : OSCGains { +using Eigen::MatrixXd; + +struct OSCStandingGains : OSCGains { int rows; int cols; double HipYawKp; double HipYawKd; double HipYawW; + double center_of_mass_filter_tau; std::vector CoMKp; std::vector CoMKd; std::vector PelvisRotKp; @@ -18,6 +21,16 @@ struct OSCStandingGains : OSCGains { std::vector CoMW; std::vector PelvisW; + MatrixXd K_p_com; + MatrixXd K_d_com; + MatrixXd K_p_pelvis; + MatrixXd K_d_pelvis; + MatrixXd K_p_hip_yaw; + MatrixXd K_d_hip_yaw; + MatrixXd W_com; + MatrixXd W_pelvis; + MatrixXd W_hip_yaw; + template void Serialize(Archive* a) { OSCGains::Serialize(a); @@ -32,5 +45,28 @@ struct OSCStandingGains : OSCGains { a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(HipYawW)); + a->Visit(DRAKE_NVP(center_of_mass_filter_tau)); + + K_p_com = Eigen::Map< + Eigen::Matrix>( + CoMKp.data(), rows, cols); + K_d_com = Eigen::Map< + Eigen::Matrix>( + CoMKd.data(), rows, cols); + K_p_pelvis = Eigen::Map< + Eigen::Matrix>( + PelvisRotKp.data(), rows, cols); + K_d_pelvis = Eigen::Map< + Eigen::Matrix>( + PelvisRotKd.data(), rows, cols); + K_p_hip_yaw = HipYawKp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = HipYawKd * MatrixXd::Identity(1, 1); + W_com = Eigen::Map< + Eigen::Matrix>( + CoMW.data(), rows, cols); + W_pelvis = Eigen::Map< + Eigen::Matrix>( + PelvisW.data(), rows, cols); + W_hip_yaw = HipYawW * MatrixXd::Identity(1, 1); } }; diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index c1d5d96cd6..5fa77bfaf6 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -11,6 +11,7 @@ rows: 3 cols: 3 w_input: 0 w_accel: 0.00000001 +w_lambda: 0.00001 W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.001 ] @@ -20,11 +21,11 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] -W_lambda_h_reg: [ 0.01, 0.01, 0.01, - 0.01, 0.02, 0.02 ] +W_lambda_h_reg: [ 0.02, 0.02 ] w_soft_constraint: 100 w_input_reg: 0.001 impact_threshold: 0.00 +center_of_mass_filter_tau: 0.03 impact_tau: 0.00 mu: 0.6 HipYawKp: 10 diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 4f085dbef2..5e68756d5f 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -1,10 +1,10 @@ # OSC gains w_input: 0.0000 -w_input_reg: 0.0000 -w_accel: 0.0001 -w_soft_constraint: 100 -impact_threshold: 0.05 -impact_tau: 0.025 +w_input_reg: 0.000003 +w_accel: 0.00000001 +w_soft_constraint: 80 +impact_threshold: 0.00 +impact_tau: 0.00 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_input_reg: [1, 0.9, 0.5, 0.1, 5, @@ -52,7 +52,7 @@ ss_time: 0.3 ds_time: 0.1 # Distance of contact point from foot rear (0 is heel, 1 is toe) -contact_point_pos: 0.35 +contact_point_pos: 0.8 # Swing foot trajectory max_CoM_to_footstep_dist: 0.55 @@ -65,16 +65,11 @@ final_foot_velocity_z: 0.0 # LIPM trajectory lipm_height: 0.85 - - -#w_soft_constraint: 1000000 - - w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 0.5 +w_hip_yaw: 2.0 hip_yaw_kp: 40 hip_yaw_kd: 1 @@ -128,7 +123,7 @@ SwingFootKp: SwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 1] + 0, 0, 5] AlipKalmanQ: [.001, .001, .01, .01] diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 6026cd337f..6492bfa3fc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -8,6 +8,7 @@ using Eigen::MatrixXd; struct OSCRunningGains : OSCGains { + double weight_scaling; double w_swing_toe; double swing_toe_kp; double swing_toe_kd; @@ -77,6 +78,7 @@ struct OSCRunningGains : OSCGains { template void Serialize(Archive* a) { OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(weight_scaling)); a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); a->Visit(DRAKE_NVP(rest_length)); @@ -157,5 +159,17 @@ struct OSCRunningGains : OSCGains { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); + + w_accel *= weight_scaling; + w_input *= weight_scaling; + w_input_reg *= weight_scaling; + w_lambda *= weight_scaling; + w_soft_constraint *= weight_scaling; + W_pelvis *= weight_scaling; + W_pelvis_rot *= weight_scaling; + W_swing_foot *= weight_scaling; + W_liftoff_swing_foot *= weight_scaling; + W_swing_toe *= weight_scaling; + W_hip_yaw *= weight_scaling; } }; \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 2f7b3f1ae3..16129cacc2 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,10 +1,12 @@ -w_input: 0.0001 -w_input_reg: 0.1 +w_input: 0.00001 +w_input_reg: 0.0001 w_accel: 0.0001 w_soft_constraint: 100 +w_lambda: 0.0001 impact_threshold: 0.05 impact_tau: 0.005 mu: 0.6 +weight_scaling: 1.0 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, @@ -15,8 +17,8 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] -W_lambda_h_reg: [ 0.01, 0.01, 0.01, - 0.01, 0.02, 0.02 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.002, 0.002 ] #w_soft_constraint: 1000000 relative_feet: true @@ -50,8 +52,8 @@ FootstepKd: 0, 0.7, 0, 0, 0, 0 ] PelvisW: - [ 1, 0, 0, - 0, 1, 0, + [ 0.1, 0, 0, + 0, 0.1, 0, 0, 0, 5 ] PelvisKp: [ -50, 0, 0, diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 101ab6639b..f8b956958f 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -736,10 +736,10 @@ void SetKinematicConstraints(Dircon *trajopt, // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); - prog->AddLinearConstraint(lambda(2) <= 350); - prog->AddLinearConstraint(lambda(5) <= 350); - prog->AddLinearConstraint(lambda(8) <= 350); - prog->AddLinearConstraint(lambda(11) <= 350); + prog->AddLinearConstraint(lambda(2) <= FLAGS_input_delta * 350); + prog->AddLinearConstraint(lambda(5) <= FLAGS_input_delta * 350); + prog->AddLinearConstraint(lambda(8) <= FLAGS_input_delta * 350); + prog->AddLinearConstraint(lambda(11) <= FLAGS_input_delta * 350); // prog->AddLinearConstraint(lambda(2) >= 50); // prog->AddLinearConstraint(lambda(5) >= 50); // prog->AddLinearConstraint(lambda(8) >= 50); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 21c9339006..fdfa670558 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -155,11 +155,9 @@ int DoMain(int argc, char* argv[]) { osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; vector accumulated_state_durations; accumulated_state_durations.push_back(0); - std::cout << accumulated_state_durations.back() << std::endl; for (double state_duration : state_durations) { accumulated_state_durations.push_back(accumulated_state_durations.back() + state_duration); - std::cout << accumulated_state_durations.back() << std::endl; } accumulated_state_durations.pop_back(); @@ -167,9 +165,9 @@ int DoMain(int argc, char* argv[]) { auto contact_scheduler = builder.AddSystem( plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); -// auto fsm = builder.AddSystem( -// plant, fsm_states, state_durations, 0.0, gains.impact_threshold, -// gains.impact_tau); + // auto fsm = builder.AddSystem( + // plant, fsm_states, state_durations, 0.0, gains.impact_threshold, + // gains.impact_tau); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -194,26 +192,23 @@ int DoMain(int argc, char* argv[]) { auto contact_scheduler_debug_publisher = builder.AddSystem(LcmPublisherSystem::Make( "CONTACT_TIMING", &lcm, TriggerTypeSet({TriggerType::kForced}))); -// std::vector tau = {.05, .01, .01}; - auto ekf_filter = - builder.AddSystem(plant, osc_gains.ekf_filter_tau); + // std::vector tau = {.05, .01, .01}; + auto ekf_filter = builder.AddSystem( + plant, osc_gains.ekf_filter_tau); /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); - osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaContactRegularizationWeight(1e-4 * - gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); - + osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); + osc->SetInputSmoothingWeights(osc_gains.w_input_reg * osc_gains.W_input_regularization); + osc->SetInputCostWeights(osc_gains.w_input * osc_gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight(osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(osc_gains.w_lambda * osc_gains.W_lambda_h_regularization); // Soft constraint on contacts - osc->SetSoftConstraintWeight(gains.w_soft_constraint); + osc->SetSoftConstraintWeight(osc_gains.w_soft_constraint); // Contact information for OSC - osc->SetContactFriction(gains.mu); + osc->SetContactFriction(osc_gains.mu); const auto& pelvis = plant.GetBodyByName("pelvis"); multibody::WorldYawViewFrame view_frame(pelvis); @@ -534,8 +529,8 @@ int DoMain(int argc, char* argv[]) { ekf_filter->get_input_port()); builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); -// builder.Connect(state_receiver->get_output_port(0), -// osc->get_robot_output_input_port()); + // builder.Connect(state_receiver->get_output_port(0), + // osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 971e29cea2..7503dcb003 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -84,9 +84,10 @@ int DoMain(int argc, char* argv[]) { plant_w_springs.Finalize(); // Build fix-spring Cassie MBP drake::multibody::MultibodyPlant plant_wo_springs(0.0); - AddCassieMultibody(&plant_wo_springs, nullptr, true, - "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf", false, - false); + AddCassieMultibody( + &plant_wo_springs, nullptr, true, + "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf", false, + false); plant_wo_springs.Finalize(); auto context_w_spr = plant_w_springs.CreateDefaultContext(); @@ -113,28 +114,6 @@ int DoMain(int argc, char* argv[]) { OSCStandingGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_osc_gains_filename)); - MatrixXd K_p_com = Eigen::Map< - Eigen::Matrix>( - osc_gains.CoMKp.data(), osc_gains.rows, osc_gains.cols); - MatrixXd K_d_com = Eigen::Map< - Eigen::Matrix>( - osc_gains.CoMKd.data(), osc_gains.rows, osc_gains.cols); - MatrixXd K_p_pelvis = Eigen::Map< - Eigen::Matrix>( - osc_gains.PelvisRotKp.data(), osc_gains.rows, osc_gains.cols); - MatrixXd K_d_pelvis = Eigen::Map< - Eigen::Matrix>( - osc_gains.PelvisRotKd.data(), osc_gains.rows, osc_gains.cols); - MatrixXd K_p_hip_yaw = osc_gains.HipYawKp * MatrixXd::Identity(1, 1); - MatrixXd K_d_hip_yaw = osc_gains.HipYawKd * MatrixXd::Identity(1, 1); - MatrixXd W_com = Eigen::Map< - Eigen::Matrix>( - osc_gains.CoMW.data(), osc_gains.rows, osc_gains.cols); - MatrixXd W_pelvis = Eigen::Map< - Eigen::Matrix>( - osc_gains.PelvisW.data(), osc_gains.rows, osc_gains.cols); - MatrixXd W_hip_yaw = osc_gains.HipYawW * MatrixXd::Identity(1, 1); - // Create Lcm subsriber for lcmt_target_standing_height auto target_height_receiver = builder.AddSystem( LcmSubscriberSystem::Make( @@ -147,8 +126,7 @@ int DoMain(int argc, char* argv[]) { auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); - auto cassie_out_to_radio = - builder.AddSystem(); + auto cassie_out_to_radio = builder.AddSystem(); builder.Connect(*cassie_out_receiver, *cassie_out_to_radio); // Create command sender. @@ -224,10 +202,10 @@ int DoMain(int argc, char* argv[]) { int n_v = plant_wo_springs.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputSmoothingWeights(gains.w_input * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - // osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - // gains.W_lambda_h_regularization); + osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * + gains.W_lambda_h_regularization); // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing @@ -235,17 +213,19 @@ int DoMain(int argc, char* argv[]) { // W_com * FLAGS_cost_weight_multiplier, // plant_w_springs, plant_wo_springs); auto center_of_mass_traj = std::make_unique( - "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, - plant_w_springs, plant_wo_springs); + "com_traj", osc_gains.K_p_com, osc_gains.K_d_com, + osc_gains.W_com * FLAGS_cost_weight_multiplier, plant_w_springs, + plant_wo_springs); center_of_mass_traj->AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); - center_of_mass_traj->SetLowPassFilter(0.03, {1}); + center_of_mass_traj->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, + {1}); osc->AddTrackingData(std::move(center_of_mass_traj)); // Pelvis rotation tracking auto pelvis_rot_traj = std::make_unique( - "pelvis_rot_traj", K_p_pelvis, K_d_pelvis, - W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, + "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, plant_wo_springs); pelvis_rot_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_rot_traj)); @@ -254,17 +234,12 @@ int DoMain(int argc, char* argv[]) { // We use hip yaw joint tracking instead of pelvis yaw tracking because the // foot sometimes rotates about yaw, and we need hip yaw joint to go back to // 0. - double w_hip_yaw = 0.5; - double hip_yaw_kp = 40; - double hip_yaw_kd = 0.5; auto left_hip_yaw_traj = std::make_unique( - "left_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), - hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant_w_springs, plant_wo_springs); + "left_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, + osc_gains.W_hip_yaw, plant_w_springs, plant_wo_springs); auto right_hip_yaw_traj = std::make_unique( - "right_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), - hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), - plant_w_springs, plant_wo_springs); + "right_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, + osc_gains.W_hip_yaw, plant_w_springs, plant_wo_springs); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); diff --git a/lcm/dircon_saved_trajectory.h b/lcm/dircon_saved_trajectory.h index aeab7bd59c..0faf4818ef 100644 --- a/lcm/dircon_saved_trajectory.h +++ b/lcm/dircon_saved_trajectory.h @@ -87,36 +87,36 @@ class DirconTrajectory : public LcmTrajectory { Eigen::MatrixXd GetStateSamples(int mode) const { DRAKE_DEMAND(mode >= 0); DRAKE_DEMAND(mode < num_modes_); - return state_map_ * x_[mode]->datapoints; + return state_map_ * x_.at(mode)->datapoints; } Eigen::MatrixXd GetStateDerivativeSamples(int mode) const { DRAKE_DEMAND(mode >= 0); DRAKE_DEMAND(mode < num_modes_); - return state_map_ * xdot_[mode]->datapoints; + return state_map_ * xdot_.at(mode)->datapoints; } Eigen::MatrixXd GetStateBreaks(int mode) const { DRAKE_DEMAND(mode >= 0); DRAKE_DEMAND(mode < num_modes_); - return x_[mode]->time_vector; + return x_.at(mode)->time_vector; } Eigen::MatrixXd GetInputSamples() const { return actuator_map_ * u_->datapoints; } Eigen::MatrixXd GetBreaks() const { return u_->time_vector; } Eigen::MatrixXd GetForceSamples(int mode) const { - return lambda_[mode]->datapoints; + return lambda_.at(mode)->datapoints; } Eigen::MatrixXd GetForceBreaks(int mode) const { - return lambda_[mode]->time_vector; + return lambda_.at(mode)->time_vector; } Eigen::MatrixXd GetImpulseSamples(int mode) const { - return impulse_[mode - 1]->datapoints; + return impulse_.at(mode - 1)->datapoints; } Eigen::MatrixXd GetCollocationForceSamples(int mode) const { - return lambda_c_[mode]->datapoints; + return lambda_c_.at(mode)->datapoints; } Eigen::MatrixXd GetCollocationForceBreaks(int mode) const { - return lambda_c_[mode]->time_vector; + return lambda_c_.at(mode)->time_vector; } Eigen::VectorXd GetDecisionVariables() const { return decision_vars_->datapoints; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index d4756147b2..ea8c066996 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -702,7 +702,13 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd constant_term = (JdotV_t - ddy_t); tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), 0, true); + (J_t.transpose() * W) * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), + constant_term.transpose() * W * constant_term, true); + // tracking_cost_.at(i)->UpdateCoefficients( + // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * + // constant_term.transpose() * W * constant_term); + // tracking_cost_.at(i)->UpdateCoefficients( + // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_)); } else { tracking_cost_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), VectorXd::Zero(n_v_)); diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index ef91673570..efb837526c 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -9,8 +9,9 @@ using Eigen::MatrixXd; struct OSCGains { // costs double w_input; - double w_input_reg; double w_accel; + double w_lambda; + double w_input_reg; double w_soft_constraint; double impact_threshold; double impact_tau; @@ -28,8 +29,9 @@ struct OSCGains { template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(w_input)); - a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(w_accel)); + a->Visit(DRAKE_NVP(w_lambda)); + a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(w_soft_constraint)); a->Visit(DRAKE_NVP(impact_threshold)); a->Visit(DRAKE_NVP(impact_tau)); From 9a9f56303ac34c958d669075b60c78b682233141 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 16 Aug 2022 17:20:16 -0400 Subject: [PATCH 277/758] running updates --- .../Cassie/contact_scheduler/contact_scheduler.cc | 12 ++++++++---- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 1 + examples/Cassie/osc_run/osc_running_gains.yaml | 8 ++++---- examples/Cassie/osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 2 ++ 5 files changed, 16 insertions(+), 9 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 37238ee719..5241028f70 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -168,8 +168,11 @@ EventStatus ContactScheduler::UpdateTransitionTimes( drake::multibody::UniformGravityFieldElement::kDefaultStrength; // Compute relative to stance foot - double pelvis_z = robot_output->GetPositionAtIndex(6) - - state->get_discrete_state(ground_height_index_)[0]; + VectorXd pelvis_pos = Vector3d::Zero(); + plant_.CalcPointsPositions( + *plant_context_, plant_.GetBodyByName("pelvis").body_frame(), + Vector3d::Zero(), plant_.world_frame(), &pelvis_pos); + double pelvis_z = pelvis_pos[2]; double pelvis_zdot = robot_output->GetVelocityAtIndex(5); if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { @@ -200,9 +203,10 @@ EventStatus ContactScheduler::UpdateTransitionTimes( 2 * g * (rest_length_ - pelvis_z))) / g; } + double time_to_touchdown_saturated = + drake::math::saturate(time_to_touchdown, 0.05, 0.12); double next_transition_time = - stored_transition_time + - drake::math::saturate(time_to_touchdown, 0.08, 0.12); + stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = next_transition_time - stored_transition_time; if (active_state == LEFT_FLIGHT) { diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index ffde5cef33..1a5e2a84e6 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,4 +1,5 @@ w_input: 0.000 +w_lambda: 0.000 w_accel: 0.0000001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 16129cacc2..e59209fa36 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,7 +4,7 @@ w_accel: 0.0001 w_soft_constraint: 100 w_lambda: 0.0001 impact_threshold: 0.05 -impact_tau: 0.005 +impact_tau: 0.001 mu: 0.6 weight_scaling: 1.0 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe @@ -32,8 +32,8 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -stance_duration: 0.25 -flight_duration: 0.10 +stance_duration: 0.0 +flight_duration: 0.0 w_swing_toe: 1 swing_toe_kp: 1500 @@ -62,7 +62,7 @@ PelvisKp: PelvisKd: [ 2, 0, 0, 0, 2, 0, - 0, 0, 4 ] + 0, 0, 2 ] PelvisRotW: [ 10, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index b446b78ecf..d09c39daa5 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 100 +max_iter: 1000 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index fdfa670558..c49ac519d5 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -165,6 +165,7 @@ int DoMain(int argc, char* argv[]) { auto contact_scheduler = builder.AddSystem( plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); + contact_scheduler->SetSLIPParams(osc_gains.rest_length); // auto fsm = builder.AddSystem( // plant, fsm_states, state_durations, 0.0, gains.impact_threshold, // gains.impact_tau); @@ -288,6 +289,7 @@ int DoMain(int argc, char* argv[]) { plant, plant_context.get(), default_traj, feet_contact_points, osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, LEFT_STANCE); From 95b216119fdaee2055fd0f9c822c5509f0170ab5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Aug 2022 11:14:12 -0400 Subject: [PATCH 278/758] reverting running gains --- .../pydairlib/analysis/log_plotter_cassie.py | 4 +- .../plot_configs/cassie_running_plot.yaml | 2 +- .../plot_configs/cassie_standing_plot.yaml | 54 ++++++++++ .../osc_running_controller_diagram.cc | 2 +- .../osc_walking_controller_diagram.cc | 2 +- examples/Cassie/osc/osc_standing_gains.h | 12 +++ examples/Cassie/osc/osc_standing_gains.yaml | 36 ++++--- .../Cassie/osc_run/osc_running_gains.yaml | 56 +++++----- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_jumping_controller.cc | 1 - examples/Cassie/run_osc_running_controller.cc | 2 +- .../Cassie/run_osc_standing_controller.cc | 101 ++++++++++-------- examples/Cassie/run_osc_walking_controller.cc | 3 +- .../Cassie/run_osc_walking_controller_alip.cc | 3 +- examples/Cassie/start_logging.py | 2 + .../osc/operational_space_control.cc | 7 +- .../osc/operational_space_control.h | 5 +- 17 files changed, 191 insertions(+), 103 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index fe837f4436..fe3e35eb21 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -13,6 +13,7 @@ def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) @@ -160,7 +161,8 @@ def main(): mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_qp_solve_time: - mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_active_tracking_datas: mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 3bd47b7dbf..42fa0b186e 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,7 +6,7 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 5 +start_time: 0 duration: -1 # Plant properties diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml new file mode 100644 index 0000000000..32a22467b8 --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml @@ -0,0 +1,54 @@ +# LCM channels to read data from +channel_x: "CASSIE_STATE_DISPATCHER" +#channel_x: "CASSIE_STATE_SIMULATION" +channel_u: "OSC_STANDING" +channel_osc: "OSC_DEBUG_STANDING" +use_archived_lcmtypes: false + +# Log time to stop at (seconds, -1 for whole log) +start_time: 0 +duration: -1 + +# Plant properties +use_springs: true +use_floating_base: true + +# Desired RobotOutput plots +plot_floating_base_positions: true +plot_floating_base_velocities: true +plot_floating_base_velocity_body_frame: false +plot_joint_positions: true +plot_joint_velocities: true +plot_measured_efforts: true +plot_commanded_efforts: true +plot_contact_forces: false +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [ ] + +# Finite State Machine Names +fsm_state_names: [] + +# Foot position plots +foot_positions_to_plot: [ 'right', 'left' ] +#foot_positions_to_plot: [] +foot_xyz_to_plot: { 'right': [2], 'left': [2] } +#foot_xyz_to_plot: { } +pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' + +# Desired osc plots +plot_qp_costs: true +plot_qp_solve_time: true +plot_qp_solutions: true +plot_tracking_costs: true +plot_active_tracking_datas: true +tracking_datas_to_plot: { +# pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel'] }, + # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} + # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, +# left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, + # right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} + # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} + # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} +} \ No newline at end of file diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 77aaa584fe..fd78e56538 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -171,7 +171,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true, false); + plant, plant, plant_context.get(), plant_context.get(), true); auto radio_parser = builder.AddSystem(); auto failure_aggregator = builder.AddSystem( diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 7df5075b82..2a9c046544 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -208,7 +208,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true, false); + plant, plant, plant_context.get(), plant_context.get(), true); auto fsm = builder.AddSystem( plant, fsm_states, state_durations); auto liftoff_event_time = diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h index 75f9f5756c..ca5a711d7f 100644 --- a/examples/Cassie/osc/osc_standing_gains.h +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -8,6 +8,7 @@ using Eigen::MatrixXd; struct OSCStandingGains : OSCGains { + double weight_scaling; int rows; int cols; double HipYawKp; @@ -34,6 +35,7 @@ struct OSCStandingGains : OSCGains { template void Serialize(Archive* a) { OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(weight_scaling)); a->Visit(DRAKE_NVP(rows)); a->Visit(DRAKE_NVP(cols)); a->Visit(DRAKE_NVP(CoMKp)); @@ -68,5 +70,15 @@ struct OSCStandingGains : OSCGains { Eigen::Matrix>( PelvisW.data(), rows, cols); W_hip_yaw = HipYawW * MatrixXd::Identity(1, 1); + + + w_accel *= weight_scaling; + w_input *= weight_scaling; + w_input_reg *= weight_scaling; + w_lambda *= weight_scaling; + w_soft_constraint *= weight_scaling; + W_pelvis *= weight_scaling; + W_com *= weight_scaling; + W_hip_yaw *= weight_scaling; } }; diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 5fa77bfaf6..9838706af4 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -9,51 +9,57 @@ rows: 3 cols: 3 -w_input: 0 -w_accel: 0.00000001 +w_input: 0.00001 +w_accel: 0.0000001 w_lambda: 0.00001 +#W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, +# 1, 1, 1, 1, 0.01, 0.001, +# 1, 1, 1, 1, 0.01, 0.001 ] W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.001 ] + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] -W_lambda_h_reg: [ 0.02, 0.02 ] +#W_lambda_h_reg: [ 0.02, 0.02 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.002, 0.002 ] w_soft_constraint: 100 -w_input_reg: 0.001 +w_input_reg: 0.0000 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.03 +center_of_mass_filter_tau: 0.005 impact_tau: 0.00 mu: 0.6 +weight_scaling: 1.0 HipYawKp: 10 HipYawKd: 1 HipYawW: 0 CoMW: [ 20, 0, 0, 0, 20, 0, - 0, 0, 5 ] + 0, 0, 20 ] PelvisW: [ 2, 0, 0, 0, 2, 0, - 0, 0, 0 ] + 0, 0, 5 ] CoMKp: [ 20, 0, 0, 0, 20, 0, 0, 0, 20 ] CoMKd: - [ 0.5, 0, 0, - 0, 0.75, 0, + [ 5, 0, 0, + 0, 5, 0, 0, 0, 5] PelvisRotKp: [10, 0, 0, 0, 30, 0, - 0, 0, 10] + 0, 0, 5] PelvisRotKd: - [0.5, 0, 0, - 0, 0.5, 0, - 0, 0, 0.5] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e59209fa36..c0e3857e17 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,10 +1,10 @@ -w_input: 0.00001 +w_input: 0.00000 w_input_reg: 0.0001 -w_accel: 0.0001 +w_accel: 0.00001 w_soft_constraint: 100 -w_lambda: 0.0001 -impact_threshold: 0.05 -impact_tau: 0.001 +w_lambda: 0.00001 +impact_threshold: 0.025 +impact_tau: 0.005 mu: 0.6 weight_scaling: 1.0 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe @@ -23,7 +23,9 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true -ekf_filter_tau: [ 0.001, 0.01, 0.001 ] +#ekf_filter_tau: [ 0.001, 0.01, 0.001 ] +ekf_filter_tau: [0.05, 0.1, 0.01] + # High level command gains (with radio) vel_scale_rot: -2 @@ -40,8 +42,8 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 2.5 -hip_yaw_kp: 100 -hip_yaw_kd: 5 +hip_yaw_kp: 40 +hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.08 @@ -60,43 +62,43 @@ PelvisKp: 0, 50, 0, 0, 0, 150] PelvisKd: - [ 2, 0, 0, - 0, 2, 0, + [ 1, 0, 0, + 0, 1, 0, 0, 0, 2 ] PelvisRotW: [ 10, 0, 0, 0, 10, 0, 0, 0, 1 ] PelvisRotKp: - [30., 0, 0, + [50., 0, 0, 0, 100., 0, - 0, 0, 0.] + 0, 0, 1.] PelvisRotKd: - [5., 0, 0, + [4., 0, 0, 0, 5., 0, - 0, 0, 3.] + 0, 0, 1.] SwingFootW: [ 10, 0, 0, - 0, 100, 0, - 0, 0, 5 ] + 0, 10, 0, + 0, 0, 1 ] SwingFootKp: - [ 50, 0, 0, - 0, 100, 0, - 0, 0, 50 ] + [125, 0, 0, + 0, 100, 0, + 0, 0, 50] SwingFootKd: [ 5., 0, 0, - 0, 10., 0, + 0, 5., 0, 0, 0, 1. ] LiftoffSwingFootW: - [1, 0, 0, - 0, 1, 0, + [0.1, 0, 0, + 0, 10, 0, 0, 0, 1] LiftoffSwingFootKp: - [25, 0, 0, + [50, 0, 0, 0, 50, 0, - 0, 0, 35] + 0, 0, 50] LiftoffSwingFootKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 1] + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 0] diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index d09c39daa5..b446b78ecf 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 1000 +max_iter: 100 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 7274d8811d..749ad67580 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -362,7 +362,6 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_fixed_ankle_spring); osc->AddKinematicConstraint(&evaluators); - std::cout << " here: " << std::endl; /**** Tracking Data for OSC *****/ auto pelvis_tracking_data = std::make_unique( diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c49ac519d5..3ef608e599 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -179,7 +179,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true, false); + plant, plant, plant_context.get(), plant_context.get(), true); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 7503dcb003..e3916e8389 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -8,6 +8,7 @@ #include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "examples/Cassie/systems/cassie_out_to_radio.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" #include "systems/controllers/osc/com_tracking_data.h" @@ -42,6 +43,7 @@ using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; +using multibody::FixedJointEvaluator; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; @@ -65,7 +67,6 @@ DEFINE_string(osc_gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", "Filepath containing qp settings"); DEFINE_bool(use_radio, false, "use the radio to set height or not"); -DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); // Currently the controller runs at the rate between 500 Hz and 200 Hz, so the // publish rate of the robot state needs to be less than 500 Hz. Otherwise, the @@ -77,29 +78,29 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Build Cassie MBP - drake::multibody::MultibodyPlant plant_w_springs(0.0); - AddCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, + drake::multibody::MultibodyPlant plant(0.0); + AddCassieMultibody(&plant, nullptr, true /*floating base*/, "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); - plant_w_springs.Finalize(); + plant.Finalize(); // Build fix-spring Cassie MBP - drake::multibody::MultibodyPlant plant_wo_springs(0.0); - AddCassieMultibody( - &plant_wo_springs, nullptr, true, - "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf", false, - false); - plant_wo_springs.Finalize(); + // drake::multibody::MultibodyPlant plant(0.0); + // AddCassieMultibody( + // &plant, nullptr, true, + // "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf", false, + // false); + // plant.Finalize(); - auto context_w_spr = plant_w_springs.CreateDefaultContext(); - auto context_wo_spr = plant_wo_springs.CreateDefaultContext(); + auto context_w_spr = plant.CreateDefaultContext(); + // auto context_wo_spr = plant.CreateDefaultContext(); // Get contact frames and position (doesn't matter whether we use - // plant_w_springs or plant_wo_springs because the contact frames exit in both + // plant or plant because the contact frames exit in both // plants) - auto left_toe = LeftToeFront(plant_wo_springs); - auto left_heel = LeftToeRear(plant_wo_springs); - auto right_toe = RightToeFront(plant_wo_springs); - auto right_heel = RightToeRear(plant_wo_springs); + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); // Build the controller diagram DiagramBuilder builder; @@ -120,8 +121,7 @@ int DoMain(int argc, char* argv[]) { "TARGET_HEIGHT", &lcm_local)); // Create state receiver. - auto state_receiver = - builder.AddSystem(plant_w_springs); + auto state_receiver = builder.AddSystem(plant); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( @@ -133,8 +133,7 @@ int DoMain(int argc, char* argv[]) { auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); - auto command_sender = - builder.AddSystem(plant_w_springs); + auto command_sender = builder.AddSystem(plant); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -149,12 +148,11 @@ int DoMain(int argc, char* argv[]) { std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, + plant, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); auto pelvis_rot_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, - "pelvis_rot_traj"); + plant, context_w_spr.get(), feet_contact_points, "pelvis_rot_traj"); builder.Connect(state_receiver->get_output_port(0), com_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), @@ -168,38 +166,59 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_springs, plant_wo_springs, context_w_spr.get(), - context_wo_spr.get(), false, FLAGS_qp_time_limit); + plant, plant, context_w_spr.get(), context_w_spr.get(), false); // Distance constraint - multibody::KinematicEvaluatorSet evaluators(plant_wo_springs); - auto left_loop = LeftLoopClosureEvaluator(plant_wo_springs); - auto right_loop = RightLoopClosureEvaluator(plant_wo_springs); + multibody::KinematicEvaluatorSet evaluators(plant); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); + + // Fix the springs in the dynamics + auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); + auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + osc->AddKinematicConstraint(&evaluators); + // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), + plant, left_toe.first, left_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); osc->AddContactPoint(&left_toe_evaluator); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, left_heel.first, left_heel.second, Matrix3d::Identity(), + plant, left_heel.first, left_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); osc->AddContactPoint(&left_heel_evaluator); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, right_toe.first, right_toe.second, Matrix3d::Identity(), + plant, right_toe.first, right_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); osc->AddContactPoint(&right_toe_evaluator); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant_wo_springs, right_heel.first, right_heel.second, - Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + plant, right_heel.first, right_heel.second, Matrix3d::Identity(), + Vector3d::Zero(), {0, 1, 2}); osc->AddContactPoint(&right_heel_evaluator); // Cost - int n_v = plant_wo_springs.num_velocities(); + int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); osc->SetInputSmoothingWeights(gains.w_input * gains.W_input_regularization); @@ -211,11 +230,10 @@ int DoMain(int argc, char* argv[]) { // Weighting x-y higher than z, as they are more important to balancing // ComTrackingData center_of_mass_traj("com_traj", K_p_com, K_d_com, // W_com * FLAGS_cost_weight_multiplier, - // plant_w_springs, plant_wo_springs); + // plant, plant); auto center_of_mass_traj = std::make_unique( "com_traj", osc_gains.K_p_com, osc_gains.K_d_com, - osc_gains.W_com * FLAGS_cost_weight_multiplier, plant_w_springs, - plant_wo_springs); + osc_gains.W_com * FLAGS_cost_weight_multiplier, plant, plant); center_of_mass_traj->AddPointToTrack("pelvis"); // double cutoff_freq = 5; // in Hz // double tau = 1 / (2 * M_PI * cutoff_freq); @@ -225,8 +243,7 @@ int DoMain(int argc, char* argv[]) { // Pelvis rotation tracking auto pelvis_rot_traj = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, - plant_wo_springs); + osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); pelvis_rot_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_rot_traj)); @@ -236,10 +253,10 @@ int DoMain(int argc, char* argv[]) { // 0. auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, - osc_gains.W_hip_yaw, plant_w_springs, plant_wo_springs); + osc_gains.W_hip_yaw, plant, plant); auto right_hip_yaw_traj = std::make_unique( "right_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, - osc_gains.W_hip_yaw, plant_w_springs, plant_wo_springs); + osc_gains.W_hip_yaw, plant, plant); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 5c7933d7e1..9401e0f630 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -366,8 +366,7 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true, - FLAGS_qp_time_limit); + plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true); // Cost int n_v = plant_w_spr.num_velocities(); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index d71adb19e5..d35f8f14f5 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -364,8 +364,7 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true, - FLAGS_qp_time_limit); + plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true); // Cost int n_v = plant_w_spr.num_velocities(); diff --git a/examples/Cassie/start_logging.py b/examples/Cassie/start_logging.py index f513c95b89..88bdd39f2e 100644 --- a/examples/Cassie/start_logging.py +++ b/examples/Cassie/start_logging.py @@ -19,6 +19,7 @@ def main(): walking_gains = current_dair_dir + "examples/Cassie/osc/osc_walking_gains.yaml" alip_gains = current_dair_dir + "examples/Cassie/osc/osc_walking_gains_alip.yaml" running_gains = current_dair_dir + "examples/Cassie/osc_run/osc_running_gains.yaml" + jumping_gains = current_dair_dir + "examples/Cassie/osc_jump/osc_jumping_gains.yaml" if not os.path.isdir(logdir): os.mkdir(logdir) @@ -43,6 +44,7 @@ def main(): subprocess.run(['cp', walking_gains, 'walking_gains_%s.yaml' % log_num]) subprocess.run(['cp', alip_gains, 'walking_gains_alip%s.yaml' % log_num]) subprocess.run(['cp', running_gains, 'running_gains_%s.yaml' % log_num]) + subprocess.run(['cp', jumping_gains, 'jumping_gains_%s.yaml' % log_num]) subprocess.run(['lcm-logger', '-f', 'lcmlog-%s' % log_num]) diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index ea8c066996..9dc9e41e56 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -52,15 +52,14 @@ OperationalSpaceControl::OperationalSpaceControl( const MultibodyPlant& plant_wo_spr, drake::systems::Context *context_w_spr, drake::systems::Context *context_wo_spr, - bool used_with_finite_state_machine, double qp_time_limit) + bool used_with_finite_state_machine) : plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), context_w_spr_(context_w_spr), context_wo_spr_(context_wo_spr), world_w_spr_(plant_w_spr_.world_frame()), world_wo_spr_(plant_wo_spr_.world_frame()), - used_with_finite_state_machine_(used_with_finite_state_machine), - qp_time_limit_(qp_time_limit) { + used_with_finite_state_machine_(used_with_finite_state_machine){ this->set_name("OSC"); n_q_ = plant_wo_spr.num_positions(); @@ -1165,7 +1164,7 @@ void OperationalSpaceControl::CheckTracking( (OutputVector *) this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (soft_constraint_cost_ > 5e2 || isnan(soft_constraint_cost_)) { + if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { output->get_mutable_value()(0) = 1.0; } } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index b17754b252..af9439c25b 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -102,7 +102,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_wo_spr, drake::systems::Context* context_w_spr, drake::systems::Context* context_wo_spr, - bool used_with_finite_state_machine = true, double qp_time_limit = 0); + bool used_with_finite_state_machine = true); const drake::systems::OutputPort& get_osc_output_port() const { return this->get_output_port(osc_output_port_); @@ -400,9 +400,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector t_s_vec_; std::vector t_e_vec_; - // Maximum time limit for each QP solve - const double qp_time_limit_; - // Optional feature -- contact force blend double ds_duration_ = -1; int left_support_state_; From 02301849fb49b9cdba39a2dbab1556c46a084385 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Aug 2022 14:27:43 -0400 Subject: [PATCH 279/758] working on time varying weights --- .../plot_configs/cassie_running_plot.yaml | 28 ++++++----- .../contact_scheduler/contact_scheduler.cc | 15 ++++-- .../contact_scheduler/contact_scheduler.h | 2 +- .../osc_running_controller_diagram.cc | 9 ++-- .../Cassie/director_scripts/show_time_sim.py | 8 ++-- examples/Cassie/osc/osc_standing_gains.yaml | 2 +- .../Cassie/osc/osc_walking_gains_alip.yaml | 1 + .../Cassie/osc_run/foot_traj_generator.cc | 47 ------------------- examples/Cassie/osc_run/foot_traj_generator.h | 4 +- examples/Cassie/osc_run/osc_running_gains.h | 2 + .../Cassie/osc_run/osc_running_gains.yaml | 31 ++++++------ .../osc_run/osc_running_qp_settings.yaml | 4 +- .../osc_run/pelvis_trans_traj_generator.cc | 16 ++++--- .../osc_run/pelvis_trans_traj_generator.h | 21 +++++---- examples/Cassie/run_osc_running_controller.cc | 25 ++++++---- .../osc/operational_space_control.cc | 6 +-- .../controllers/osc/options_tracking_data.cc | 15 ++++-- .../controllers/osc/options_tracking_data.h | 18 ++++--- systems/controllers/osc/osc_tracking_data.h | 7 ++- 19 files changed, 131 insertions(+), 130 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 42fa0b186e..ee9cd105cd 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -22,17 +22,17 @@ plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -special_positions_to_plot: ['knee_joint_left', 'knee_joint_right'] -special_velocities_to_plot: [] +special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right' ] +special_velocities_to_plot: [ ] special_efforts_to_plot: [ ] # Finite State Machine Names -fsm_state_names: ['Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)'] +fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] # Foot position plots foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] -foot_xyz_to_plot: { 'right': [2], 'left': [2] } +foot_xyz_to_plot: { 'right': [ 2 ], 'left': [ 2 ] } #foot_xyz_to_plot: { } pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' @@ -43,13 +43,15 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [2 ], 'derivs': ['pos', 'vel'] }, -# pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} - # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} -# right_ft_traj: {'dims': [0, 2], 'derivs': ['pos'] }, - left_ft_traj: {'dims': [2], 'derivs': ['pos']}, -# left_ft_z_traj: {'dims': [0], 'derivs': ['pos']}, -# right_ft_z_traj: {'dims': [0, 2], 'derivs': ['pos']} -# left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} -# right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} + # pelvis_trans_traj: { 'dims': [2 ], 'derivs': ['pos', 'vel'] }, + pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'acel' ] }, + left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, } \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 5241028f70..db5753d98c 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -172,7 +172,9 @@ EventStatus ContactScheduler::UpdateTransitionTimes( plant_.CalcPointsPositions( *plant_context_, plant_.GetBodyByName("pelvis").body_frame(), Vector3d::Zero(), plant_.world_frame(), &pelvis_pos); - double pelvis_z = pelvis_pos[2]; + double pelvis_z = + pelvis_pos[2] - + state->get_discrete_state(ground_height_index_).value()[0]; double pelvis_zdot = robot_output->GetVelocityAtIndex(5); if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { @@ -203,8 +205,15 @@ EventStatus ContactScheduler::UpdateTransitionTimes( 2 * g * (rest_length_ - pelvis_z))) / g; } +// std::cout << "time_to_touchdown: " << time_to_touchdown << std::endl; +// std::cout << "rest_length_: " << rest_length_ << std::endl; +// std::cout << "pelvis_z: " << pelvis_pos[2] << std::endl; +// std::cout << "ground_height: " +// << state->get_discrete_state(ground_height_index_).value()[0] +// << std::endl; +// std::cout << "rest_length: " << pelvis_z << std::endl; double time_to_touchdown_saturated = - drake::math::saturate(time_to_touchdown, 0.05, 0.12); + drake::math::saturate(time_to_touchdown, 0.08, 0.12); double next_transition_time = stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = @@ -312,7 +321,7 @@ void ContactScheduler::CalcContactScheduler( context.get_discrete_state(nominal_state_durations_index_)[1]; auto transition_times = context.get_discrete_state(transition_times_index_).value(); - if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_STANCE) { + if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_FLIGHT) { contact_timing->get_mutable_value()(0) = transition_times[LEFT_STANCE]; contact_timing->get_mutable_value()(1) = transition_times[LEFT_FLIGHT]; } else { diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 5688af3952..d3dbe11663 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -25,7 +25,7 @@ class ContactScheduler : public drake::systems::LeafSystem { double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); - void SetSLIPParams(double rest_length) { rest_length_; } + void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index fd78e56538..49fe72cea5 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -226,7 +226,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_running_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_running_gains.rest_length); + pelvis_trans_traj_generator->SetSLIPParams( + osc_running_gains.rest_length, osc_running_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", osc_running_gains.relative_feet, LEFT_STANCE); @@ -236,11 +237,13 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.rest_length, osc_running_gains.footstep_lateral_offset, + osc_running_gains.rest_length, osc_running_gains.rest_length_offset, + osc_running_gains.footstep_lateral_offset, osc_running_gains.footstep_sagital_offset, osc_running_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( - osc_running_gains.rest_length, osc_running_gains.footstep_lateral_offset, + osc_running_gains.rest_length, osc_running_gains.rest_length_offset, + osc_running_gains.footstep_lateral_offset, osc_running_gains.footstep_sagital_offset, osc_running_gains.mid_foot_height); diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 0ed188c336..19d4db5ff4 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -54,10 +54,10 @@ def set_enabled(self, enable): def handle_message(self, msg): msg_time = msg.utime * 1e-6 # convert from microseconds # Drake Sim - pelvis_height = (msg.position)[6] # convert from microseconds - pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds - # pelvis_height = (msg.position)[2] # convert from microseconds - # pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds + # pelvis_height = (msg.position)[6] # convert from microseconds + # pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds + pelvis_height = (msg.position)[2] # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds self._real_time.append(time.time()) self._msg_time.append(msg_time) self._pelvis_velocity.append(pelvis_velocity) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 9838706af4..1d99370b8f 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -48,7 +48,7 @@ PelvisW: CoMKp: [ 20, 0, 0, 0, 20, 0, - 0, 0, 20 ] + 0, 0, 50 ] CoMKd: [ 5, 0, 0, 0, 5, 0, diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 5e68756d5f..1357af9b2f 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -2,6 +2,7 @@ w_input: 0.0000 w_input_reg: 0.000003 w_accel: 0.00000001 +w_lambda: 0.00000001 w_soft_constraint: 80 impact_threshold: 0.00 impact_tau: 0.00 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 00607327f1..efbb7238db 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -301,41 +301,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, false); return swing_foot_spline; - - // if (is_left_foot_) { - // return swing_foot_spline; - // } else { - // MatrixXd Y0 = MatrixXd::Zero(3, 3); - // MatrixXd Ydot0 = MatrixXd::Zero(3, 3); - // MatrixXd Y1 = MatrixXd::Zero(2, 3); - // MatrixXd Ydot1 = MatrixXd::Zero(2, 3); - // std::vector Y0(T_waypoints_0.size(), VectorXd::Zero(3)); - // std::vector Ydot0(T_waypoints_0.size(), VectorXd::Zero(3)); - // std::vector Y2(T_waypoints_1.size(), VectorXd::Zero(3)); - // std::vector Ydot2(T_waypoints_1.size(), VectorXd::Zero(3)); - // Y0[0] = swing_foot_spline.value(state_durations_[2]); - // Y0[1] = swing_foot_spline.value(T_waypoints[1]); - // Y0[2] = swing_foot_spline.value(T_waypoints[2]); - // Ydot0[0] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); - // Ydot0[1] = swing_foot_spline.EvalDerivative(T_waypoints[1], 1); - // Ydot0[2] = swing_foot_spline.EvalDerivative(T_waypoints[2], 1); - // Y2[0] = swing_foot_spline.value(state_durations_[1]); - // Y2[1] = swing_foot_spline.value(state_durations_[2]); - // Ydot2[0] = swing_foot_spline.EvalDerivative(state_durations_[1], 1); - // Ydot2[1] = swing_foot_spline.EvalDerivative(state_durations_[2], 1); - // PiecewisePolynomial offset_swing_foot_spline = - // PiecewisePolynomial::CubicHermite(T_waypoints_0, Y0, Ydot0); - // offset_swing_foot_spline.ConcatenateInTime( - // PiecewisePolynomial::ZeroOrderHold(T_waypoints_1, Y2)); - // offset_swing_foot_spline.ConcatenateInTime( - // PiecewisePolynomial::CubicHermite(T_waypoints_2, Y2, - // Ydot2)); - // for (auto t: offset_swing_foot_spline.get_segment_times()) { - // std::cout << t << std::endl; - // } - // return offset_swing_foot_spline; - //} - // return swing_foot_spline; } void FootTrajGenerator::CalcTraj( @@ -356,25 +321,13 @@ void FootTrajGenerator::CalcTraj( traj); if (is_left_foot_) { if (fsm_state != LEFT_STANCE) { - // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, - // rest_length_}); *casted_traj = GenerateFlightTraj(context); } - // else{ - // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, - // rest_length_}); - // } } else { if (fsm_state != RIGHT_STANCE) { *casted_traj = GenerateFlightTraj(context); - // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, - // rest_length_}); } - // else{ - // *casted_traj = PiecewisePolynomial(Vector3d{0, 0, - // rest_length_}); - // } } } diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index e82f59e899..a36efcc46e 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -37,9 +37,10 @@ class FootTrajGenerator : public drake::systems::LeafSystem { void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; - void SetFootPlacementOffsets(double rest_length, double center_line_offset, + void SetFootPlacementOffsets(double rest_length, double rest_length_offset, double center_line_offset, double footstep_offset, double mid_foot_height) { rest_length_ = rest_length; + rest_length_offset_ = rest_length_offset; lateral_offset_ = center_line_offset; sagital_offset_ = footstep_offset; mid_foot_height_ = mid_foot_height; @@ -66,6 +67,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { // Foot placement constants double rest_length_; + double rest_length_offset_; double lateral_offset_; double sagital_offset_; double mid_foot_height_; diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 6492bfa3fc..15795933a9 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -27,6 +27,7 @@ struct OSCRunningGains : OSCGains { bool relative_feet; bool relative_pelvis; double rest_length; + double rest_length_offset; double stance_duration; double flight_duration; @@ -82,6 +83,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); a->Visit(DRAKE_NVP(rest_length)); + a->Visit(DRAKE_NVP(rest_length_offset)); a->Visit(DRAKE_NVP(stance_duration)); a->Visit(DRAKE_NVP(flight_duration)); a->Visit(DRAKE_NVP(footstep_lateral_offset)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c0e3857e17..c99cde66e3 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,10 +1,10 @@ w_input: 0.00000 w_input_reg: 0.0001 -w_accel: 0.00001 +w_accel: 0.0000 w_soft_constraint: 100 -w_lambda: 0.00001 +w_lambda: 0.0001 impact_threshold: 0.025 -impact_tau: 0.005 +impact_tau: 0.01 mu: 0.6 weight_scaling: 1.0 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe @@ -34,6 +34,7 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 +rest_length_offset: 0.025 stance_duration: 0.0 flight_duration: 0.0 @@ -42,15 +43,15 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 2.5 -hip_yaw_kp: 40 -hip_yaw_kd: 1 +hip_yaw_kp: 100 +hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.08 -footstep_lateral_offset: 0.01 # drake +footstep_sagital_offset: -0.04 +footstep_lateral_offset: 0.02 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.18, 0, 0, + [ 0.2, 0, 0, 0, 0.7, 0, 0, 0, 0 ] PelvisW: @@ -60,7 +61,7 @@ PelvisW: PelvisKp: [ -50, 0, 0, 0, 50, 0, - 0, 0, 150] + 0, 0, 200] PelvisKd: [ 1, 0, 0, 0, 1, 0, @@ -70,20 +71,20 @@ PelvisRotW: 0, 10, 0, 0, 0, 1 ] PelvisRotKp: - [50., 0, 0, + [40., 0, 0, 0, 100., 0, 0, 0, 1.] PelvisRotKd: [4., 0, 0, 0, 5., 0, - 0, 0, 1.] + 0, 0, 0.] SwingFootW: [ 10, 0, 0, 0, 10, 0, 0, 0, 1 ] SwingFootKp: - [125, 0, 0, - 0, 100, 0, + [75, 0, 0, + 0, 50, 0, 0, 0, 50] SwingFootKd: [ 5., 0, 0, @@ -96,9 +97,9 @@ LiftoffSwingFootW: LiftoffSwingFootKp: [50, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 15] LiftoffSwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 0] + 0, 0, 1] diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index b446b78ecf..8f2ef65d49 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 100 +max_iter: 2000 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -12,7 +12,7 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 25 +check_termination: 15 warm_start: 1 scaling: 1 adaptive_rho: 1 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 08d0e0d605..21211be821 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -5,6 +5,7 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" +#include using std::string; using std::vector; @@ -82,7 +83,7 @@ PiecewisePolynomial PelvisTransTrajGenerator::GeneratePelvisTraj( } PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( - const VectorXd& x, double t_0, double t_f, int fsm_state) const { + const VectorXd& x, double t0, double tf, int fsm_state) const { // fsm_state should be unused if (fsm_state >= 2) { // flight phase trajectory should be unused @@ -116,9 +117,12 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( // } else { // breaks << 0.4, 0.65, 0.8; // } - breaks << t_0, t_f; + breaks << t0, tf; MatrixXd samples(3, 2); MatrixXd samples_dot(3, 2); + +// std::cout << "t0:" << t0 << std::endl; +// std::cout << "tf:" << tf << std::endl; // samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; // samples_dot << pelvis_vel, pelvis_vel + rddot * dt; @@ -132,10 +136,10 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( } // samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, // rest_length_ + 0.05, rest_length_; - // samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + - // 0.05; samples_dot << 0, 0, 0, 0, 0.25, 0.0; - return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); - // return PiecewisePolynomial::FirstOrderHold(breaks, samples); + samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + rest_length_offset_; +// samples_dot << 0, 0, 0, 0, 0.25, 0.0; + // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); + return PiecewisePolynomial::FirstOrderHold(breaks, samples); // return PiecewisePolynomial::CubicHermite( // breaks, samples, samples_dot); // return PiecewisePolynomial::CubicShapePreserving(breaks, samples); diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index d76e309591..3b1bc97c75 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -13,12 +13,12 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { public: PelvisTransTrajGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context *context, + drake::systems::Context* context, drake::trajectories::PiecewisePolynomial& traj, const std::unordered_map< int, std::vector&>>>& - feet_contact_points, + feet_contact_points, bool relative_pelvis = false); const drake::systems::InputPort& get_state_input_port() const { @@ -30,28 +30,32 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const drake::systems::InputPort& get_clock_input_port() const { return this->get_input_port(clock_port_); } - const drake::systems::InputPort& get_contact_scheduler_input_port() const { + const drake::systems::InputPort& get_contact_scheduler_input_port() + const { return this->get_input_port(contact_scheduler_port_); } - void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } + void SetSLIPParams(double rest_length, double rest_length_offset) { + rest_length_ = rest_length; + rest_length_offset_ = rest_length_offset; + } private: drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( const Eigen::VectorXd& x, double t, int fsm_state) const; drake::trajectories::PiecewisePolynomial GenerateSLIPTraj( - const Eigen::VectorXd& x, double t_0, double t_f, int fsm_state) const; + const Eigen::VectorXd& x, double t0, double tf, int fsm_state) const; drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, - drake::systems::DiscreteValues *discrete_state) const; + drake::systems::DiscreteValues* discrete_state) const; void CalcTraj(const drake::systems::Context& context, - drake::trajectories::Trajectory *traj) const; + drake::trajectories::Trajectory* traj) const; const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context *context_; + drake::systems::Context* context_; const drake::multibody::BodyFrame& world_; const drake::multibody::Body& pelvis_; const drake::multibody::BodyFrame& pelvis_frame_; @@ -75,6 +79,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { // SLIP parameters double rest_length_ = 0.8; + double rest_length_offset_ = 0.8; double k_leg_ = 100.0; double b_leg_ = 5.0; }; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 3ef608e599..8bdee8f5f3 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -201,10 +201,14 @@ int DoMain(int argc, char* argv[]) { // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); - osc->SetInputSmoothingWeights(osc_gains.w_input_reg * osc_gains.W_input_regularization); - osc->SetInputCostWeights(osc_gains.w_input * osc_gains.W_input_regularization); - osc->SetLambdaContactRegularizationWeight(osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(osc_gains.w_lambda * osc_gains.W_lambda_h_regularization); + osc->SetInputSmoothingWeights(osc_gains.w_input_reg * + osc_gains.W_input_regularization); + osc->SetInputCostWeights(osc_gains.w_input * + osc_gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight( + osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight( + osc_gains.w_lambda * osc_gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(osc_gains.w_soft_constraint); @@ -288,7 +292,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant, plant_context.get(), default_traj, feet_contact_points, osc_gains.relative_pelvis); - pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length, + osc_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, @@ -299,11 +304,13 @@ int DoMain(int argc, char* argv[]) { l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( - osc_gains.rest_length, osc_gains.footstep_lateral_offset, - osc_gains.footstep_sagital_offset, osc_gains.mid_foot_height); + osc_gains.rest_length, osc_gains.rest_length_offset, + osc_gains.footstep_lateral_offset, osc_gains.footstep_sagital_offset, + osc_gains.mid_foot_height); r_foot_traj_generator->SetFootPlacementOffsets( - osc_gains.rest_length, osc_gains.footstep_lateral_offset, - osc_gains.footstep_sagital_offset, osc_gains.mid_foot_height); + osc_gains.rest_length, osc_gains.rest_length_offset, + osc_gains.footstep_lateral_offset, osc_gains.footstep_sagital_offset, + osc_gains.mid_foot_height); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 9dc9e41e56..b3c7f75f5c 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1164,9 +1164,9 @@ void OperationalSpaceControl::CheckTracking( (OutputVector *) this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { - output->get_mutable_value()(0) = 1.0; - } +// if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { +// output->get_mutable_value()(0) = 1.0; +// } } } // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index c8b2cc6d9c..3f2bcfda33 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -37,6 +37,7 @@ void OptionsTrackingData::UpdateActual( JdotV_ = view_frame_rot_T_ * JdotV_; } + W_ = weight_trajectory_->value(t) * W_; UpdateFilters(t); } @@ -82,9 +83,9 @@ void OptionsTrackingData::UpdateYddotDes(double t, yddot_des_converted_ = ff_accel_multiplier_->value(t_since_state_switch) * yddot_des_converted_; } -// if(this->GetName() == "pelvis_trans_traj"){ -// yddot_des_converted_[2] -= 9.81; -// } + // if(this->GetName() == "pelvis_trans_traj"){ + // yddot_des_converted_[2] -= 9.81; + // } } void OptionsTrackingData::UpdateYddotCmd(double t, @@ -123,6 +124,14 @@ void OptionsTrackingData::SetTimeVaryingGains( DRAKE_DEMAND(gain_multiplier.start_time() == 0); gain_multiplier_ = &gain_multiplier; } + +void OptionsTrackingData::SetTimeVaryingWeights( + const drake::trajectories::Trajectory& weight_trajectory) { + DRAKE_DEMAND(weight_trajectory.cols() == n_ydot_); + DRAKE_DEMAND(weight_trajectory.rows() == n_ydot_); + DRAKE_DEMAND(weight_trajectory.start_time() == 0); + gain_multiplier_ = &weight_trajectory; +} void OptionsTrackingData::SetFeedforwardAccelMultiplier( const drake::trajectories::Trajectory& ff_accel_multiplier) { DRAKE_DEMAND(ff_accel_multiplier.cols() == n_ydot_); diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index 4723bc2a93..f4c1163fbc 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -24,7 +24,9 @@ class OptionsTrackingData : public OscTrackingData { // finite state void SetTimeVaryingGains( const drake::trajectories::Trajectory& gain_multiplier); - const drake::trajectories::Trajectory* gain_multiplier_ = nullptr; + void SetTimeVaryingWeights( + const drake::trajectories::Trajectory& weight_trajectory); + void SetFeedforwardAccelMultiplier( const drake::trajectories::Trajectory& ff_accel_multiplier); const drake::trajectories::Trajectory* ff_accel_multiplier_ = nullptr; @@ -44,12 +46,11 @@ class OptionsTrackingData : public OscTrackingData { }; private: - void UpdateActual( - const Eigen::VectorXd& x_w_spr, - const drake::systems::Context& context_w_spr, - const Eigen::VectorXd& x_wo_spr, - const drake::systems::Context& context_wo_spr, - double t) override; + void UpdateActual(const Eigen::VectorXd& x_w_spr, + const drake::systems::Context& context_w_spr, + const Eigen::VectorXd& x_wo_spr, + const drake::systems::Context& context_wo_spr, + double t) override; void UpdateFilters(double t); void UpdateYError() override; @@ -57,6 +58,9 @@ class OptionsTrackingData : public OscTrackingData { void UpdateYddotDes(double t, double t_since_state_switch) override; void UpdateYddotCmd(double t, double t_since_state_switch) override; + const drake::trajectories::Trajectory* gain_multiplier_ = nullptr; + const drake::trajectories::Trajectory* weight_trajectory_ = nullptr; + bool with_view_frame_ = false; // Members of low-pass filter diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index e1373d7424..9960a6b4b1 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -148,6 +148,9 @@ class OscTrackingData { // If `state_` is empty, then the tracking is always on. std::set active_fsm_states_; + // Cost weights + Eigen::MatrixXd W_; + /// OSC calculates feedback positions/velocities from `plant_w_spr_`, /// but in the optimization it uses `plant_wo_spr_`. The reason of using /// MultibodyPlant without springs is that the OSC cannot track desired @@ -160,7 +163,6 @@ class OscTrackingData { const drake::multibody::BodyFrame& world_wo_spr_; private: - void UpdateDesired(const drake::trajectories::Trajectory& traj, double t, double t_since_state_switch); // Update actual output methods @@ -188,9 +190,6 @@ class OscTrackingData { // Trajectory name std::string name_; - - // Cost weights - Eigen::MatrixXd W_; }; } // namespace controllers From 4314c75d3c0f6d1ac25ce5565dba156e971a8772 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Aug 2022 15:05:04 -0400 Subject: [PATCH 280/758] smoothly incresing foot tracking weights --- .../plot_configs/cassie_running_plot.yaml | 18 +++---- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- .../osc_run/osc_running_qp_settings.yaml | 4 +- examples/Cassie/run_osc_running_controller.cc | 47 +++++++++++-------- .../controllers/osc/options_tracking_data.cc | 22 +++++---- .../controllers/osc/options_tracking_data.h | 4 ++ systems/controllers/osc/osc_tracking_data.h | 2 +- 7 files changed, 59 insertions(+), 40 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index ee9cd105cd..6d3cc28fcf 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -44,14 +44,14 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [2 ], 'derivs': ['pos', 'vel'] }, - pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, +# pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, +# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, +# hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, +# hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'acel' ] }, - left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, +# left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, +# right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, +# left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, +# right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, } \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c99cde66e3..2fdca29551 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -81,7 +81,7 @@ PelvisRotKd: SwingFootW: [ 10, 0, 0, 0, 10, 0, - 0, 0, 1 ] + 0, 0, 5 ] SwingFootKp: [75, 0, 0, 0, 50, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 8f2ef65d49..7d134ca996 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 2000 +max_iter: 150 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -12,7 +12,7 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 15 +check_termination: 25 warm_start: 1 scaling: 1 adaptive_rho: 1 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 8bdee8f5f3..f2e384eb0f 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -341,6 +341,12 @@ int DoMain(int argc, char* argv[]) { right_foot_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); + + auto left_foot_yz_tracking_data = std::make_unique( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -369,6 +375,11 @@ int DoMain(int argc, char* argv[]) { left_hip_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + auto left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); @@ -414,22 +425,20 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); - // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_leftdot"], - // RUNNING_FSM_STATE::LEFT_STANCE); - // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_roll_rightdot"], - // RUNNING_FSM_STATE::RIGHT_STANCE); - // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_leftdot"], - // RUNNING_FSM_STATE::LEFT_STANCE); - // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["hip_pitch_rightdot"], - // RUNNING_FSM_STATE::RIGHT_STANCE); - // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_leftdot"], - // RUNNING_FSM_STATE::LEFT_STANCE); - // pelvis_trans_rel_tracking_data->AddJointAndStateToIgnoreInJacobian(vel_map["knee_joint_rightdot"], - // RUNNING_FSM_STATE::RIGHT_STANCE); + PiecewisePolynomial foot_traj_weight_trajectory = + PiecewisePolynomial::FirstOrderHold( + {0, 0.25 + 0.2}, {0.5 * VectorXd::Ones(1), VectorXd::Ones(1)}); + // PiecewisePolynomial foot_traj_weight_trajectory = + // PiecewisePolynomial::FirstOrderHold( + // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); + left_foot_rel_tracking_data->SetTimeVaryingWeights( + foot_traj_weight_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingWeights( + foot_traj_weight_trajectory); // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); - pelvis_trans_rel_tracking_data->DisableFeedforwardAccel({2}); + // pelvis_trans_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); @@ -444,8 +453,8 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); - osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); - osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); +// osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); +// osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); auto heading_traj_generator = builder.AddSystem(plant, @@ -599,10 +608,10 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("right_ft_traj")); - builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("left_ft_z_traj")); - builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("right_ft_z_traj")); +// builder.Connect(l_foot_traj_generator->get_output_port(0), +// osc->get_input_port_tracking_data("left_ft_z_traj")); +// builder.Connect(r_foot_traj_generator->get_output_port(0), +// osc->get_input_port_tracking_data("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index 3f2bcfda33..5cb2f5aaf5 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -37,7 +37,6 @@ void OptionsTrackingData::UpdateActual( JdotV_ = view_frame_rot_T_ * JdotV_; } - W_ = weight_trajectory_->value(t) * W_; UpdateFilters(t); } @@ -83,9 +82,6 @@ void OptionsTrackingData::UpdateYddotDes(double t, yddot_des_converted_ = ff_accel_multiplier_->value(t_since_state_switch) * yddot_des_converted_; } - // if(this->GetName() == "pelvis_trans_traj"){ - // yddot_des_converted_[2] -= 9.81; - // } } void OptionsTrackingData::UpdateYddotCmd(double t, @@ -100,6 +96,16 @@ void OptionsTrackingData::UpdateYddotCmd(double t, yddot_command_ = yddot_des_converted_ + gain_multiplier * (K_p_ * (error_y_) + K_d_ * (error_ydot_)); + UpdateW(t, t_since_state_switch); +} + +void OptionsTrackingData::UpdateW(double t, double t_since_state_switch) { + if(weight_trajectory_ != nullptr){ + time_varying_weight_ = weight_trajectory_->value(t - ).row(0)[0] * W_; + } + else{ + time_varying_weight_ = W_; + } } void OptionsTrackingData::SetLowPassFilter(double tau, @@ -127,10 +133,10 @@ void OptionsTrackingData::SetTimeVaryingGains( void OptionsTrackingData::SetTimeVaryingWeights( const drake::trajectories::Trajectory& weight_trajectory) { - DRAKE_DEMAND(weight_trajectory.cols() == n_ydot_); - DRAKE_DEMAND(weight_trajectory.rows() == n_ydot_); - DRAKE_DEMAND(weight_trajectory.start_time() == 0); - gain_multiplier_ = &weight_trajectory; +// DRAKE_DEMAND(weight_trajectory.cols() == n_ydot_); +// DRAKE_DEMAND(weight_trajectory.rows() == n_ydot_); +// DRAKE_DEMAND(weight_trajectory.start_time() == 0); + weight_trajectory_ = &weight_trajectory; } void OptionsTrackingData::SetFeedforwardAccelMultiplier( const drake::trajectories::Trajectory& ff_accel_multiplier) { diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index f4c1163fbc..2b94b9787d 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -31,6 +31,8 @@ class OptionsTrackingData : public OscTrackingData { const drake::trajectories::Trajectory& ff_accel_multiplier); const drake::trajectories::Trajectory* ff_accel_multiplier_ = nullptr; + const Eigen::MatrixXd& GetWeight() const override { return time_varying_weight_; } + // Additional feature -- ViewFrame const multibody::ViewFrame* view_frame_; Eigen::Matrix3d view_frame_rot_T_; @@ -57,6 +59,7 @@ class OptionsTrackingData : public OscTrackingData { void UpdateYdotError(const Eigen::VectorXd& v_proj) override; void UpdateYddotDes(double t, double t_since_state_switch) override; void UpdateYddotCmd(double t, double t_since_state_switch) override; + void UpdateW(double t, double t_since_state_switch); const drake::trajectories::Trajectory* gain_multiplier_ = nullptr; const drake::trajectories::Trajectory* weight_trajectory_ = nullptr; @@ -66,6 +69,7 @@ class OptionsTrackingData : public OscTrackingData { // Members of low-pass filter Eigen::VectorXd filtered_y_; Eigen::VectorXd filtered_ydot_; + Eigen::MatrixXd time_varying_weight_; double tau_ = -1; std::set low_pass_filter_element_idx_; double last_timestamp_ = -1; diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index 9960a6b4b1..0357029350 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -87,7 +87,7 @@ class OscTrackingData { const Eigen::MatrixXd& GetJ() const { return J_; } const Eigen::VectorXd& GetJdotTimesV() const { return JdotV_; } const Eigen::VectorXd& GetYddotCommand() const { return yddot_command_; } - const Eigen::MatrixXd& GetWeight() const { return W_; } + virtual const Eigen::MatrixXd& GetWeight() const { return W_; } // Getters const std::string& GetName() const { return name_; }; From 94bdce6317cefeec4bb6a58973fa581c31d5998b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Aug 2022 17:43:00 -0400 Subject: [PATCH 281/758] working on time varying weights' --- .../plot_configs/cassie_running_plot.yaml | 22 +++---- .../contact_scheduler/contact_scheduler.cc | 17 +++--- .../Cassie/osc_run/osc_running_gains.yaml | 52 ++++++++--------- .../osc_run/osc_running_qp_settings.yaml | 4 +- examples/Cassie/run_osc_running_controller.cc | 2 +- .../osc/operational_space_control.cc | 58 +++++++++---------- .../osc/operational_space_control.h | 2 +- .../controllers/osc/options_tracking_data.cc | 16 ++--- systems/controllers/osc/osc_tracking_data.cc | 3 +- systems/controllers/osc/osc_tracking_data.h | 2 + 10 files changed, 91 insertions(+), 87 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 6d3cc28fcf..1e32af6856 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -43,15 +43,15 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - # pelvis_trans_traj: { 'dims': [2 ], 'derivs': ['pos', 'vel'] }, -# pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, -# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, -# hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, -# hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, -# left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, -# right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, -# left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, -# right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] }, + # pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + # right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + # left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': ['pos', 'accel' ] }, + # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, } \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index db5753d98c..53b80db8ca 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -181,6 +181,11 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // Store the ground height of the stance foot // TODO(yangwill): calculate end of stance duration + double stance_scale = (0.016) / (pelvis_zdot * pelvis_zdot); + stance_scale = drake::math::saturate(stance_scale, 0.9, 1.2); + std::cout << "stance scale: " << stance_scale << std::endl; + // double next_transition_time = + // stored_transition_time + stance_scale * 0.25; double next_transition_time = stored_transition_time + 0.25; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; @@ -205,15 +210,9 @@ EventStatus ContactScheduler::UpdateTransitionTimes( 2 * g * (rest_length_ - pelvis_z))) / g; } -// std::cout << "time_to_touchdown: " << time_to_touchdown << std::endl; -// std::cout << "rest_length_: " << rest_length_ << std::endl; -// std::cout << "pelvis_z: " << pelvis_pos[2] << std::endl; -// std::cout << "ground_height: " -// << state->get_discrete_state(ground_height_index_).value()[0] -// << std::endl; -// std::cout << "rest_length: " << pelvis_z << std::endl; - double time_to_touchdown_saturated = - drake::math::saturate(time_to_touchdown, 0.08, 0.12); + // double time_to_touchdown_saturated = + // drake::math::saturate(time_to_touchdown, 0.08, 0.12); + double time_to_touchdown_saturated = 0.12; double next_transition_time = stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 2fdca29551..e03eb1c84c 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,6 +1,6 @@ w_input: 0.00000 -w_input_reg: 0.0001 -w_accel: 0.0000 +w_accel: 0.00001 +w_input_reg: 0.001 w_soft_constraint: 100 w_lambda: 0.0001 impact_threshold: 0.025 @@ -13,10 +13,10 @@ W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] -W_lambda_c_reg: [ 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01 ] +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] #w_soft_constraint: 1000000 @@ -34,7 +34,7 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.025 +rest_length_offset: 0.00 stance_duration: 0.0 flight_duration: 0.0 @@ -43,53 +43,53 @@ swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 2.5 -hip_yaw_kp: 100 -hip_yaw_kd: 5 +hip_yaw_kp: 40 +hip_yaw_kd: 1 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.04 -footstep_lateral_offset: 0.02 # drake +footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.2, 0, 0, + [ 0.15, 0, 0, 0, 0.7, 0, 0, 0, 0 ] PelvisW: - [ 0.1, 0, 0, + [ 0.0, 0, 0, 0, 0.1, 0, - 0, 0, 5 ] + 0, 0, 1 ] PelvisKp: - [ -50, 0, 0, - 0, 50, 0, - 0, 0, 200] + [ -25, 0, 0, + 0, 25, 0, + 0, 0, 150] PelvisKd: [ 1, 0, 0, 0, 1, 0, 0, 0, 2 ] PelvisRotW: [ 10, 0, 0, - 0, 10, 0, + 0, 2.5, 0, 0, 0, 1 ] PelvisRotKp: - [40., 0, 0, + [25., 0, 0, 0, 100., 0, 0, 0, 1.] PelvisRotKd: - [4., 0, 0, + [1., 0, 0, 0, 5., 0, 0, 0, 0.] SwingFootW: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 5 ] + [10, 0, 0, + 0, 10, 0, + 0, 0, 1] SwingFootKp: - [75, 0, 0, + [125, 0, 0, 0, 50, 0, 0, 0, 50] SwingFootKd: - [ 5., 0, 0, - 0, 5., 0, - 0, 0, 1. ] + [5., 0, 0, + 0, 5., 0, + 0, 0, 0.1] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 7d134ca996..41753bee75 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 150 +max_iter: 75 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -12,7 +12,7 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 25 +check_termination: 15 warm_start: 1 scaling: 1 adaptive_rho: 1 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index f2e384eb0f..7dcb3318fa 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -427,7 +427,7 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial foot_traj_weight_trajectory = PiecewisePolynomial::FirstOrderHold( - {0, 0.25 + 0.2}, {0.5 * VectorXd::Ones(1), VectorXd::Ones(1)}); + {0, 0.25 + 0.2}, {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)}); // PiecewisePolynomial foot_traj_weight_trajectory = // PiecewisePolynomial::FirstOrderHold( // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index b3c7f75f5c..1ad489f886 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -471,16 +471,16 @@ void OperationalSpaceControl::Build() { /// hard constraint version // prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); // } - blend_constraint_ = - prog_ - ->AddBoundingBoxConstraint( - VectorXd::Zero(4), VectorXd::Zero(4), - {lambda_c_.segment(kSpaceDim * 0 + 2, 1), - lambda_c_.segment(kSpaceDim * 1 + 2, 1), - lambda_c_.segment(kSpaceDim * 2 + 2, 1), - lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) - .evaluator() - .get(); +// blend_constraint_ = +// prog_ +// ->AddBoundingBoxConstraint( +// VectorXd::Zero(4), VectorXd::Zero(4), +// {lambda_c_.segment(kSpaceDim * 0 + 2, 1), +// lambda_c_.segment(kSpaceDim * 1 + 2, 1), +// lambda_c_.segment(kSpaceDim * 2 + 2, 1), +// lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) +// .evaluator() +// .get(); for (int i = -1; i < 5; ++i) { solvers_[i] = std::make_unique(); @@ -512,7 +512,7 @@ drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( VectorXd OperationalSpaceControl::SolveQp( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const drake::systems::Context& context, double t, int fsm_state, - double time_since_last_state_switch, double alpha, + double t_since_last_state_switch, double alpha, int next_fsm_state) const { // Get active contact indices std::set active_contact_set = {}; @@ -563,7 +563,7 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd v_proj = VectorXd::Zero(n_v_); if (near_impact) { UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, - time_since_last_state_switch, fsm_state, + t_since_last_state_switch, fsm_state, next_fsm_state, M); // Need to call Update before this to get the updated jacobian v_proj = alpha * M_Jt_ * ii_lambda_sol_; @@ -669,8 +669,8 @@ VectorXd OperationalSpaceControl::SolveQp( auto tracking_data = tracking_data_vec_->at(i).get(); if (tracking_data->IsActive(fsm_state) && - time_since_last_state_switch >= t_s_vec_.at(i) && - time_since_last_state_switch <= t_e_vec_.at(i)) { + t_since_last_state_switch >= t_s_vec_.at(i) && + t_since_last_state_switch <= t_e_vec_.at(i)) { // Check whether or not it is a constant trajectory, and update // TrackingData if (fixed_position_vec_.at(i).size() != 0) { @@ -678,7 +678,7 @@ VectorXd OperationalSpaceControl::SolveQp( tracking_data->Update( x_w_spr, *context_w_spr_, x_wo_spr, *context_wo_spr_, PiecewisePolynomial(fixed_position_vec_.at(i)), t, - time_since_last_state_switch, fsm_state, v_proj); + t_since_last_state_switch, fsm_state, v_proj); } else { // Read in traj from input port const string& traj_name = tracking_data->GetName(); @@ -691,7 +691,7 @@ VectorXd OperationalSpaceControl::SolveQp( // Update tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, *context_wo_spr_, traj, t, - time_since_last_state_switch, fsm_state, v_proj); + t_since_last_state_switch, fsm_state, v_proj); } const VectorXd& ddy_t = tracking_data->GetYddotCommand(); @@ -736,12 +736,12 @@ VectorXd OperationalSpaceControl::SolveQp( // if (prev_distinct_fsm_state_ == right_support_state_) { // // We want left foot force to gradually increase // alpha_left = -1; -// alpha_right = time_since_last_state_switch / -// (ds_duration_ - time_since_last_state_switch); +// alpha_right = t_since_last_state_switch / +// (ds_duration_ - t_since_last_state_switch); // // } else if (prev_distinct_fsm_state_ == left_support_state_) { -// alpha_left = time_since_last_state_switch / -// (ds_duration_ - time_since_last_state_switch); +// alpha_left = t_since_last_state_switch / +// (ds_duration_ - t_since_last_state_switch); // alpha_right = -1; // } // A(0, 0) = alpha_left / 2; @@ -753,12 +753,12 @@ VectorXd OperationalSpaceControl::SolveQp( // A(0, 6) = 1; // A(0, 7) = 1; // } - VectorXd normals = VectorXd(4); - normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), - lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), - lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), - lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); - blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 25 * VectorXd::Ones(4), normals + 25 * VectorXd::Ones(4)); +// VectorXd normals = VectorXd(4); +// normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), +// lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), +// lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), +// lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); +// blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 25 * VectorXd::Ones(4), normals + 25 * VectorXd::Ones(4)); // } // test joint-level input cost by fsm state @@ -1164,9 +1164,9 @@ void OperationalSpaceControl::CheckTracking( (OutputVector *) this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; -// if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { -// output->get_mutable_value()(0) = 1.0; -// } + if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { + output->get_mutable_value()(0) = 1.0; + } } } // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index af9439c25b..9c4f4c6b06 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -208,7 +208,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { const Eigen::VectorXd& x_wo_spr, const drake::systems::Context& context, double t, int fsm_state, - double time_since_last_state_switch, double alpha, + double t_since_last_state_switch, double alpha, int next_fsm_state) const; // Solves the optimization problem: diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index 5cb2f5aaf5..f4496cc6f6 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -1,5 +1,7 @@ #include "options_tracking_data.h" +#include + using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; @@ -100,10 +102,10 @@ void OptionsTrackingData::UpdateYddotCmd(double t, } void OptionsTrackingData::UpdateW(double t, double t_since_state_switch) { - if(weight_trajectory_ != nullptr){ - time_varying_weight_ = weight_trajectory_->value(t - ).row(0)[0] * W_; - } - else{ + if (weight_trajectory_ != nullptr) { + time_varying_weight_ = + weight_trajectory_->value(time_through_trajectory_).row(0)[0] * W_; + } else { time_varying_weight_ = W_; } } @@ -133,9 +135,9 @@ void OptionsTrackingData::SetTimeVaryingGains( void OptionsTrackingData::SetTimeVaryingWeights( const drake::trajectories::Trajectory& weight_trajectory) { -// DRAKE_DEMAND(weight_trajectory.cols() == n_ydot_); -// DRAKE_DEMAND(weight_trajectory.rows() == n_ydot_); -// DRAKE_DEMAND(weight_trajectory.start_time() == 0); + // DRAKE_DEMAND(weight_trajectory.cols() == n_ydot_); + // DRAKE_DEMAND(weight_trajectory.rows() == n_ydot_); + // DRAKE_DEMAND(weight_trajectory.start_time() == 0); weight_trajectory_ = &weight_trajectory; } void OptionsTrackingData::SetFeedforwardAccelMultiplier( diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index 464dde2b72..10417594b8 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -107,6 +107,7 @@ void OscTrackingData::UpdateDesired( yddot_des_ = traj.MakeDerivative(2)->value(t); } UpdateYddotDes(t, t_since_state_switch); + time_through_trajectory_ = t - traj.start_time(); } void OscTrackingData::UpdateYddotCmd(double t, double t_since_state_switch) { @@ -126,7 +127,7 @@ void OscTrackingData::AddFiniteStateToTrack(int state) { // Run this function in OSC constructor to make sure that users constructed // OscTrackingData correctly. void OscTrackingData::CheckOscTrackingData() { -// cout << "Checking " << name_ << endl; + // cout << "Checking " << name_ << endl; CheckDerivedOscTrackingData(); DRAKE_DEMAND((K_p_.rows() == n_ydot_) && (K_p_.cols() == n_ydot_)); diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index 0357029350..50d84f76d0 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -121,6 +121,8 @@ class OscTrackingData { bool use_springs_in_eval_ = true; bool impact_invariant_projection_ = false; + double time_through_trajectory_ = 0; + // Actual outputs, Jacobian and dJ/dt * v Eigen::VectorXd y_; Eigen::VectorXd error_y_; From 36574ca2ee705e6d92db2b369e0f714be94e3f86 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Aug 2022 20:15:07 -0400 Subject: [PATCH 282/758] time varying gains don't work --- .../pydairlib/analysis/log_plotter_cassie.py | 2 ++ .../contact_scheduler/contact_scheduler.cc | 2 +- .../Cassie/director_scripts/show_time_sim.py | 8 ++++---- .../Cassie/osc_run/osc_running_gains.yaml | 20 +++++++++---------- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 7 +++++++ .../osc/operational_space_control.cc | 14 ++++++------- 7 files changed, 32 insertions(+), 23 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index fe3e35eb21..70fa9c480f 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -136,6 +136,8 @@ def main(): if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.attach() + plt.ylim([0, 200]) if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 53b80db8ca..53df1ac56b 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -183,7 +183,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // TODO(yangwill): calculate end of stance duration double stance_scale = (0.016) / (pelvis_zdot * pelvis_zdot); stance_scale = drake::math::saturate(stance_scale, 0.9, 1.2); - std::cout << "stance scale: " << stance_scale << std::endl; + // std::cout << "stance scale: " << stance_scale << std::endl; // double next_transition_time = // stored_transition_time + stance_scale * 0.25; double next_transition_time = stored_transition_time + 0.25; diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 19d4db5ff4..0ed188c336 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -54,10 +54,10 @@ def set_enabled(self, enable): def handle_message(self, msg): msg_time = msg.utime * 1e-6 # convert from microseconds # Drake Sim - # pelvis_height = (msg.position)[6] # convert from microseconds - # pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds - pelvis_height = (msg.position)[2] # convert from microseconds - pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds + pelvis_height = (msg.position)[6] # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds + # pelvis_height = (msg.position)[2] # convert from microseconds + # pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds self._real_time.append(time.time()) self._msg_time.append(msg_time) self._pelvis_velocity.append(pelvis_velocity) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e03eb1c84c..00b210f257 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,5 +1,5 @@ w_input: 0.00000 -w_accel: 0.00001 +w_accel: 0.000001 w_input_reg: 0.001 w_soft_constraint: 100 w_lambda: 0.0001 @@ -23,8 +23,8 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true -#ekf_filter_tau: [ 0.001, 0.01, 0.001 ] -ekf_filter_tau: [0.05, 0.1, 0.01] +ekf_filter_tau: [ 0.001, 0.01, 0.001 ] +#ekf_filter_tau: [0.05, 0.1, 0.01] # High level command gains (with radio) @@ -34,7 +34,7 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.00 +rest_length_offset: 0.025 stance_duration: 0.0 flight_duration: 0.0 @@ -63,7 +63,7 @@ PelvisKp: 0, 25, 0, 0, 0, 150] PelvisKd: - [ 1, 0, 0, + [ 2, 0, 0, 0, 1, 0, 0, 0, 2 ] PelvisRotW: @@ -79,17 +79,17 @@ PelvisRotKd: 0, 5., 0, 0, 0, 0.] SwingFootW: - [10, 0, 0, - 0, 10, 0, + [1, 0, 0, + 0, 1, 0, 0, 0, 1] SwingFootKp: - [125, 0, 0, - 0, 50, 0, + [75, 0, 0, + 0, 75, 0, 0, 0, 50] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 0.1] + 0, 0, 1] LiftoffSwingFootW: [0.1, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 41753bee75..4238c8cf39 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 75 +max_iter: 150 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 7dcb3318fa..7e5b83ac89 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -428,6 +428,9 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial foot_traj_weight_trajectory = PiecewisePolynomial::FirstOrderHold( {0, 0.25 + 0.2}, {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)}); + PiecewisePolynomial foot_traj_gain_trajectory = + PiecewisePolynomial::FirstOrderHold( + {0, 0.25 + 0.2}, {0.5 * MatrixXd::Identity(3, 3), 2.0 * MatrixXd::Identity(3, 3)}); // PiecewisePolynomial foot_traj_weight_trajectory = // PiecewisePolynomial::FirstOrderHold( // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); @@ -435,6 +438,10 @@ int DoMain(int argc, char* argv[]) { foot_traj_weight_trajectory); right_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); + left_foot_rel_tracking_data->SetTimeVaryingGains( + foot_traj_gain_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingGains( + foot_traj_gain_trajectory); // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 1ad489f886..f3817b3a2e 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -701,8 +701,8 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd constant_term = (JdotV_t - ddy_t); tracking_cost_.at(i)->UpdateCoefficients( - (J_t.transpose() * W) * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), - constant_term.transpose() * W * constant_term, true); + J_t.transpose() * W * J_t + W_joint_accel_, J_t.transpose() * W * (JdotV_t - ddy_t), + constant_term.transpose() * W * constant_term); // tracking_cost_.at(i)->UpdateCoefficients( // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * // constant_term.transpose() * W * constant_term); @@ -783,12 +783,12 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd::Zero(n_c_)); } - if (!solvers_.at(fsm_state)->IsInitialized()) { - solvers_.at(fsm_state)->InitializeSolver(*prog_, solver_options_); + if (!solvers_.at(0)->IsInitialized()) { + solvers_.at(0)->InitializeSolver(*prog_, solver_options_); } if (initial_guess_x_.count(fsm_state) > 0) { - solvers_.at(fsm_state)->WarmStart(initial_guess_x_.at(fsm_state), + solvers_.at(0)->WarmStart(initial_guess_x_.at(fsm_state), initial_guess_y_.at(fsm_state)); } @@ -798,7 +798,7 @@ VectorXd OperationalSpaceControl::SolveQp( auto osqp_solver = drake::solvers::OsqpSolver(); result = osqp_solver.Solve(*prog_, std::nullopt, solver_options_); } else { - result = solvers_.at(fsm_state)->Solve(*prog_); + result = solvers_.at(0)->Solve(*prog_); } solve_time_ = result.get_solver_details().run_time; @@ -853,7 +853,7 @@ VectorXd OperationalSpaceControl::SolveQp( initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { // *u_prev_ = VectorXd::Zero(n_u_); - *u_prev_ = 0.9 * *u_sol_ + VectorXd::Random(n_u_); + *u_prev_ = 0.99 * *u_sol_ + VectorXd::Random(n_u_); } for (auto& tracking_data : *tracking_data_vec_) { From 018ca3668b2845d6e97a02b4c55fcf25ff4d84e6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Aug 2022 11:19:34 -0400 Subject: [PATCH 283/758] updating gains --- .../plot_configs/cassie_running_plot.yaml | 2 +- .../Cassie/osc/swing_toe_traj_generator.cc | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 98 +++++++++---------- 3 files changed, 50 insertions(+), 52 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1e32af6856..e1fc769454 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -52,6 +52,6 @@ tracking_datas_to_plot: { # left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': ['pos', 'accel' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, } \ No newline at end of file diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index 3f832fd066..05b3d23f92 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -63,7 +63,7 @@ void SwingToeTrajGenerator::CalcTraj( double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); - des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.05; + des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.02; // des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; auto* pp_traj = diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 00b210f257..7a5bf33896 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,31 +1,29 @@ -w_input: 0.00000 -w_accel: 0.000001 -w_input_reg: 0.001 +w_input: 0.0001 +w_input_reg: 0.1 +w_accel: 0.0001 w_soft_constraint: 100 w_lambda: 0.0001 -impact_threshold: 0.025 -impact_tau: 0.01 -mu: 0.6 +impact_threshold: 0.05 +impact_tau: 0.005 weight_scaling: 1.0 +mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] -W_lambda_c_reg: [1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01] -W_lambda_h_reg: [ 0.001, 0.001, 0.001, - 0.001, 0.002, 0.002 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01 ] +W_lambda_h_reg: [ 0.01, 0.01, 0.01, + 0.01, 0.02, 0.02 ] #w_soft_constraint: 1000000 relative_feet: true relative_pelvis: true ekf_filter_tau: [ 0.001, 0.01, 0.001 ] -#ekf_filter_tau: [0.05, 0.1, 0.01] - # High level command gains (with radio) vel_scale_rot: -2 @@ -34,72 +32,72 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.025 -stance_duration: 0.0 -flight_duration: 0.0 +rest_length_offset: 0.0 +stance_duration: 0.25 +flight_duration: 0.10 w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 2.5 -hip_yaw_kp: 40 -hip_yaw_kd: 1 +hip_yaw_kp: 100 +hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.04 -footstep_lateral_offset: 0.04 # drake +footstep_sagital_offset: -0.06 +footstep_lateral_offset: 0.01 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.15, 0, 0, + [ 0.18, 0, 0, 0, 0.7, 0, 0, 0, 0 ] PelvisW: - [ 0.0, 0, 0, - 0, 0.1, 0, - 0, 0, 1 ] + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 5 ] PelvisKp: - [ -25, 0, 0, - 0, 25, 0, - 0, 0, 150] + [ -50, 0, 0, + 0, 50, 0, + 0, 0, 145] PelvisKd: [ 2, 0, 0, - 0, 1, 0, - 0, 0, 2 ] + 0, 2, 0, + 0, 0, 4 ] PelvisRotW: [ 10, 0, 0, - 0, 2.5, 0, + 0, 10, 0, 0, 0, 1 ] PelvisRotKp: - [25., 0, 0, + [30., 0, 0, 0, 100., 0, - 0, 0, 1.] + 0, 0, 0.] PelvisRotKd: - [1., 0, 0, + [5., 0, 0, 0, 5., 0, - 0, 0, 0.] + 0, 0, 3.] SwingFootW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] + [ 10, 0, 0, + 0, 100, 0, + 0, 0, 5 ] SwingFootKp: - [75, 0, 0, - 0, 75, 0, - 0, 0, 50] + [ 50, 0, 0, + 0, 100, 0, + 0, 0, 50 ] SwingFootKd: - [5., 0, 0, - 0, 5., 0, - 0, 0, 1] + [ 5., 0, 0, + 0, 10., 0, + 0, 0, 1. ] LiftoffSwingFootW: - [0.1, 0, 0, - 0, 10, 0, + [1, 0, 0, + 0, 1, 0, 0, 0, 1] LiftoffSwingFootKp: - [50, 0, 0, + [25, 0, 0, 0, 50, 0, - 0, 0, 15] + 0, 0, 35] LiftoffSwingFootKd: - [ 1, 0, 0, - 0, 1, 0, + [ 5, 0, 0, + 0, 5, 0, 0, 0, 1] From 88731c1ff85ac442f0bae34d3038f7f3d33d144e Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Aug 2022 13:43:11 -0400 Subject: [PATCH 284/758] updating standing controller --- examples/Cassie/osc/osc_standing_gains.yaml | 22 +++++++-------- .../Cassie/osc_run/osc_running_gains.yaml | 8 +++--- .../Cassie/run_osc_standing_controller.cc | 3 ++- .../osc/operational_space_control.cc | 4 +-- .../controllers/osc/options_tracking_data.cc | 27 +++++++++++++++---- 5 files changed, 40 insertions(+), 24 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 1d99370b8f..e1673a7380 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -11,7 +11,7 @@ rows: 3 cols: 3 w_input: 0.00001 w_accel: 0.0000001 -w_lambda: 0.00001 +w_lambda: 0.000001 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, # 1, 1, 1, 1, 0.01, 0.001 ] @@ -28,7 +28,7 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] w_soft_constraint: 100 -w_input_reg: 0.0000 +w_input_reg: 0.01 impact_threshold: 0.00 center_of_mass_filter_tau: 0.005 impact_tau: 0.00 @@ -36,30 +36,30 @@ mu: 0.6 weight_scaling: 1.0 HipYawKp: 10 HipYawKd: 1 -HipYawW: 0 +HipYawW: 1 CoMW: [ 20, 0, 0, 0, 20, 0, 0, 0, 20 ] PelvisW: - [ 2, 0, 0, - 0, 2, 0, - 0, 0, 5 ] + [ 1, 0, 0, + 0, 0.1, 0, + 0, 0, 0.1 ] CoMKp: [ 20, 0, 0, 0, 20, 0, 0, 0, 50 ] CoMKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 5] + [ 1, 0, 0, + 0, 0.1, 0, + 0, 0, 4] PelvisRotKp: [10, 0, 0, 0, 30, 0, 0, 0, 5] PelvisRotKd: - [1, 0, 0, - 0, 1, 0, + [0.1, 0, 0, + 0, 0.1, 0, 0, 0, 1] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 7a5bf33896..913919a225 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,7 +1,7 @@ -w_input: 0.0001 +w_input: 0.000001 w_input_reg: 0.1 w_accel: 0.0001 -w_soft_constraint: 100 +w_soft_constraint: 0 w_lambda: 0.0001 impact_threshold: 0.05 impact_tau: 0.005 @@ -17,8 +17,8 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] -W_lambda_h_reg: [ 0.01, 0.01, 0.01, - 0.01, 0.02, 0.02 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.002, 0.002 ] #w_soft_constraint: 1000000 relative_feet: true diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index e3916e8389..9788cfd7db 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -221,7 +221,7 @@ int DoMain(int argc, char* argv[]) { int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingWeights(gains.w_input * gains.W_input_regularization); + osc->SetInputSmoothingWeights(gains.w_input_reg * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * gains.W_lambda_h_regularization); @@ -245,6 +245,7 @@ int DoMain(int argc, char* argv[]) { "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); pelvis_rot_traj->AddFrameToTrack("pelvis"); + pelvis_rot_traj->SetLowPassFilter(0.1, {0, 1, 2}); osc->AddTrackingData(std::move(pelvis_rot_traj)); // Hip yaw joint tracking diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f3817b3a2e..c1128fffdd 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -848,7 +848,6 @@ VectorXd OperationalSpaceControl::SolveQp( // blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); // } // } - *u_prev_ = *u_sol_; initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { @@ -1096,8 +1095,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( } output->tracking_data[i] = osc_output; } - // std::cout << total_cost_ << std::endl; -// *u_prev_ = *u_sol_; + *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); } diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index f4496cc6f6..be8d39d26f 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -2,7 +2,10 @@ #include +#include "drake/common/trajectories/piecewise_quaternion.h" + using Eigen::MatrixXd; +using Eigen::Quaterniond; using Eigen::Vector3d; using Eigen::VectorXd; using std::string; @@ -51,14 +54,28 @@ void OptionsTrackingData::UpdateFilters(double t) { } else if (t != last_timestamp_) { double dt = t - last_timestamp_; double alpha = dt / (dt + tau_); - filtered_y_ = alpha * y_ + (1 - alpha) * filtered_y_; + if (n_y_ == 4) { // quaternion + auto slerp = drake::trajectories::PiecewiseQuaternionSlerp( + {0, 1}, {Quaterniond(y_[0], y_[1], y_[2], y_[3]), + Quaterniond(filtered_y_[0], filtered_y_[1], filtered_y_[2], + filtered_y_[3])}); + filtered_y_ = slerp.value(1 - alpha); + } else { + filtered_y_ = alpha * y_ + (1 - alpha) * filtered_y_; + } filtered_ydot_ = alpha * ydot_ + (1 - alpha) * filtered_ydot_; } // Assign filtered values - for (auto idx : low_pass_filter_element_idx_) { - y_(idx) = filtered_y_(idx); - ydot_(idx) = filtered_ydot_(idx); + if (n_y_ == 4){ + y_ = filtered_y_; + ydot_ = filtered_ydot_; + } + else{ + for (auto idx : low_pass_filter_element_idx_) { + y_(idx) = filtered_y_(idx); + ydot_(idx) = filtered_ydot_(idx); + } } // Update timestamp last_timestamp_ = t; @@ -115,7 +132,7 @@ void OptionsTrackingData::SetLowPassFilter(double tau, DRAKE_DEMAND(tau > 0); tau_ = tau; - DRAKE_DEMAND(n_y_ == n_ydot_); // doesn't support quaternion yet +// DRAKE_DEMAND(n_y_ == n_ydot_); // doesn't support quaternion yet if (element_idx.empty()) { for (int i = 0; i < n_y_; i++) { low_pass_filter_element_idx_.insert(i); From da6a4cfc03da7a76f14d75f14235f9162596ccdd Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Aug 2022 13:55:07 -0400 Subject: [PATCH 285/758] more standing controller updates --- examples/Cassie/osc/osc_standing_gains.yaml | 6 +++--- examples/Cassie/run_osc_standing_controller.cc | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index e1673a7380..1d4ded8ccf 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -27,8 +27,8 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, #W_lambda_h_reg: [ 0.02, 0.02 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] -w_soft_constraint: 100 -w_input_reg: 0.01 +w_soft_constraint: 0 +w_input_reg: 0.0001 impact_threshold: 0.00 center_of_mass_filter_tau: 0.005 impact_tau: 0.00 @@ -42,7 +42,7 @@ CoMW: 0, 20, 0, 0, 0, 20 ] PelvisW: - [ 1, 0, 0, + [ 0.1, 0, 0, 0, 0.1, 0, 0, 0, 0.1 ] CoMKp: diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 9788cfd7db..e0e83a4045 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -245,7 +245,7 @@ int DoMain(int argc, char* argv[]) { "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); pelvis_rot_traj->AddFrameToTrack("pelvis"); - pelvis_rot_traj->SetLowPassFilter(0.1, {0, 1, 2}); + pelvis_rot_traj->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, {0, 1, 2}); osc->AddTrackingData(std::move(pelvis_rot_traj)); // Hip yaw joint tracking From 5278e20913c4e96fe97e14273ed7be0970ce2c68 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Aug 2022 14:31:10 -0400 Subject: [PATCH 286/758] running controller updates --- examples/Cassie/osc_run/osc_running_gains.h | 2 + .../Cassie/osc_run/osc_running_gains.yaml | 23 +- examples/Cassie/run_osc_running_controller.cc | 1 + .../osc/operational_space_control.cc | 394 +++++++++--------- .../osc/operational_space_control.h | 3 +- 5 files changed, 221 insertions(+), 202 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 15795933a9..4919db7851 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -36,6 +36,7 @@ struct OSCRunningGains : OSCGains { double mid_foot_height; std::vector ekf_filter_tau; + double rot_filter_tau; // swing foot tracking std::vector SwingFootW; @@ -90,6 +91,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(footstep_sagital_offset)); a->Visit(DRAKE_NVP(mid_foot_height)); a->Visit(DRAKE_NVP(ekf_filter_tau)); + a->Visit(DRAKE_NVP(rot_filter_tau)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 913919a225..89a36b3fc1 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,8 +1,8 @@ w_input: 0.000001 w_input_reg: 0.1 w_accel: 0.0001 -w_soft_constraint: 0 -w_lambda: 0.0001 +w_soft_constraint: 100 +w_lambda: 0.1 impact_threshold: 0.05 impact_tau: 0.005 weight_scaling: 1.0 @@ -15,14 +15,15 @@ W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01 ] -W_lambda_h_reg: [ 0.001, 0.001, 0.001, - 0.001, 0.002, 0.002 ] + 1, 0.001, 0.01, + 1, 0.001, 0.01 ] +W_lambda_h_reg: [ 0.01, 0.01, 0.01, + 0.01, 0.01, 0.01 ] #w_soft_constraint: 1000000 relative_feet: true relative_pelvis: true +rot_filter_tau: 0.005 ekf_filter_tau: [ 0.001, 0.01, 0.001 ] # High level command gains (with radio) @@ -37,8 +38,8 @@ stance_duration: 0.25 flight_duration: 0.10 w_swing_toe: 1 -swing_toe_kp: 1500 -swing_toe_kd: 10 +swing_toe_kp: 1000 +swing_toe_kd: 5 w_hip_yaw: 2.5 hip_yaw_kp: 100 @@ -46,11 +47,11 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.06 -footstep_lateral_offset: 0.01 # drake +footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.05 FootstepKd: [ 0.18, 0, 0, - 0, 0.7, 0, + 0, 0.4, 0, 0, 0, 0 ] PelvisW: [ 1, 0, 0, @@ -73,7 +74,7 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [5., 0, 0, + [2., 0, 0, 0, 5., 0, 0, 0, 3.] SwingFootW: diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 7e5b83ac89..85b9ca1bf6 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -478,6 +478,7 @@ int DoMain(int argc, char* argv[]) { RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {0, 1, 2}); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index c1128fffdd..0e4b200b4b 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -50,8 +50,8 @@ using multibody::WorldPointEvaluator; OperationalSpaceControl::OperationalSpaceControl( const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr, - drake::systems::Context *context_w_spr, - drake::systems::Context *context_wo_spr, + drake::systems::Context* context_w_spr, + drake::systems::Context* context_wo_spr, bool used_with_finite_state_machine) : plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), @@ -59,7 +59,7 @@ OperationalSpaceControl::OperationalSpaceControl( context_wo_spr_(context_wo_spr), world_w_spr_(plant_w_spr_.world_frame()), world_wo_spr_(plant_wo_spr_.world_frame()), - used_with_finite_state_machine_(used_with_finite_state_machine){ + used_with_finite_state_machine_(used_with_finite_state_machine) { this->set_name("OSC"); n_q_ = plant_wo_spr.num_positions(); @@ -79,7 +79,7 @@ OperationalSpaceControl::OperationalSpaceControl( fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); clock_port_ = this->DeclareVectorInputPort("clock", BasicVector(1)) - .get_index(); + .get_index(); impact_info_port_ = this->DeclareVectorInputPort("next_fsm, t_to_impact", ImpactInfoVector(0, 0, kSpaceDim)) @@ -93,18 +93,18 @@ OperationalSpaceControl::OperationalSpaceControl( } osc_output_port_ = this->DeclareVectorOutputPort( - "u, t", TimestampedVector(n_u_w_spr), - &OperationalSpaceControl::CalcOptimalInput) - .get_index(); + "u, t", TimestampedVector(n_u_w_spr), + &OperationalSpaceControl::CalcOptimalInput) + .get_index(); osc_debug_port_ = this->DeclareAbstractOutputPort( "lcmt_osc_debug", &OperationalSpaceControl::AssignOscLcmOutput) .get_index(); failure_port_ = this->DeclareVectorOutputPort( - "failure_signal", TimestampedVector(1), - &OperationalSpaceControl::CheckTracking) - .get_index(); + "failure_signal", TimestampedVector(1), + &OperationalSpaceControl::CheckTracking) + .get_index(); const std::map& vel_map_wo_spr = multibody::MakeNameToVelocitiesMap(plant_wo_spr); @@ -145,9 +145,9 @@ OperationalSpaceControl::OperationalSpaceControl( } if (joint.type_name() == "prismatic" && (joint.position_lower_limits()[0] != - -std::numeric_limits::infinity() || - (joint.position_upper_limits()[0] != - std::numeric_limits::infinity()))) { + -std::numeric_limits::infinity() || + (joint.position_upper_limits()[0] != + std::numeric_limits::infinity()))) { std::cerr << "Warning: joint limits have not been implemented for " "prismatic joints: " << std::endl; @@ -183,13 +183,13 @@ void OperationalSpaceControl::AddInputCostByJointAndFsmState( // Constraint methods void OperationalSpaceControl::AddContactPoint( - const WorldPointEvaluator *evaluator) { + const WorldPointEvaluator* evaluator) { single_contact_mode_ = true; AddStateAndContactPoint(-1, evaluator); } void OperationalSpaceControl::AddStateAndContactPoint( - int state, const WorldPointEvaluator *evaluator) { + int state, const WorldPointEvaluator* evaluator) { DRAKE_DEMAND(&evaluator->plant() == &plant_wo_spr_); // Find the new contact in all_contacts_ @@ -213,7 +213,7 @@ void OperationalSpaceControl::AddStateAndContactPoint( } void OperationalSpaceControl::AddKinematicConstraint( - const multibody::KinematicEvaluatorSet *evaluators) { + const multibody::KinematicEvaluatorSet* evaluators) { DRAKE_DEMAND(&evaluators->plant() == &plant_wo_spr_); kinematic_evaluators_ = evaluators; } @@ -256,11 +256,11 @@ void OperationalSpaceControl::CheckCostSettings() { } if (W_input_smoothing_.size() != 0) { DRAKE_DEMAND((W_input_smoothing_.rows() == n_u_) && - (W_input_smoothing_.cols() == n_u_)); + (W_input_smoothing_.cols() == n_u_)); } if (W_joint_accel_.size() != 0) { DRAKE_DEMAND((W_joint_accel_.rows() == n_v_) && - (W_joint_accel_.cols() == n_v_)); + (W_joint_accel_.cols() == n_v_)); } } void OperationalSpaceControl::CheckConstraintSettings() { @@ -287,8 +287,8 @@ void OperationalSpaceControl::Build() { // Size of decision variable n_h_ = (kinematic_evaluators_ == nullptr) - ? 0 - : kinematic_evaluators_->count_full(); + ? 0 + : kinematic_evaluators_->count_full(); n_c_ = kSpaceDim * all_contacts_.size(); n_c_active_ = 0; for (auto evaluator : all_contacts_) { @@ -320,7 +320,6 @@ void OperationalSpaceControl::Build() { lambda_h_sol_->setZero(); u_prev_->setZero(); - // Add decision variables dv_ = prog_->NewContinuousVariables(n_v_, "dv"); u_ = prog_->NewContinuousVariables(n_u_, "u"); @@ -392,8 +391,8 @@ void OperationalSpaceControl::Build() { // 1. input cost if (W_input_.size() > 0) { input_cost_ = prog_->AddQuadraticCost(W_input_, VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); + .evaluator() + .get(); } // 2. acceleration cost if (W_joint_accel_.size() > 0) { @@ -412,7 +411,11 @@ void OperationalSpaceControl::Build() { // 3. constraint force cost if (W_lambda_h_reg_.size() > 0) { DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); - prog_->AddQuadraticCost(W_lambda_h_reg_, VectorXd::Zero(n_h_), lambda_h_); + lambda_h_smoothing_cost_ = + prog_ + ->AddQuadraticCost(W_lambda_h_reg_, VectorXd::Zero(n_h_), lambda_h_) + .evaluator() + .get(); } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { @@ -427,10 +430,11 @@ void OperationalSpaceControl::Build() { .evaluator() .get(); } -// input_smoothing_constraint_ = -// prog_->AddBoundingBoxConstraint(VectorXd::Zero(n_u_), VectorXd::Zero(n_u_), u_) -// .evaluator() -// .get(); + // input_smoothing_constraint_ = + // prog_->AddBoundingBoxConstraint(VectorXd::Zero(n_u_), + // VectorXd::Zero(n_u_), u_) + // .evaluator() + // .get(); // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { tracking_cost_.push_back(prog_ @@ -449,38 +453,38 @@ void OperationalSpaceControl::Build() { .get()); // (Testing) 6. contact force blending -// if (ds_duration_ > 0) { -// epsilon_blend_ = -// prog_->NewContinuousVariables(n_c_ / kSpaceDim, "epsilon_blend"); -// blend_constraint_ = -// prog_ -// ->AddLinearEqualityConstraint( -// MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim), VectorXd::Zero(1), -// {lambda_c_.segment(kSpaceDim * 0 + 2, 1), -// lambda_c_.segment(kSpaceDim * 1 + 2, 1), -// lambda_c_.segment(kSpaceDim * 2 + 2, 1), -// lambda_c_.segment(kSpaceDim * 3 + 2, 1), epsilon_blend_}) -// .evaluator() -// .get(); - /// Soft constraint version - // DRAKE_DEMAND(w_blend_constraint_ > 0); - // prog_->AddQuadraticCost( - // w_blend_constraint_ * - // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), - // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); - /// hard constraint version -// prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); -// } -// blend_constraint_ = -// prog_ -// ->AddBoundingBoxConstraint( -// VectorXd::Zero(4), VectorXd::Zero(4), -// {lambda_c_.segment(kSpaceDim * 0 + 2, 1), -// lambda_c_.segment(kSpaceDim * 1 + 2, 1), -// lambda_c_.segment(kSpaceDim * 2 + 2, 1), -// lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) -// .evaluator() -// .get(); + if (ds_duration_ > 0) { + epsilon_blend_ = + prog_->NewContinuousVariables(n_c_ / kSpaceDim, "epsilon_blend"); + blend_constraint_ = + prog_ + ->AddLinearEqualityConstraint( + MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim), VectorXd::Zero(1), + {lambda_c_.segment(kSpaceDim * 0 + 2, 1), + lambda_c_.segment(kSpaceDim * 1 + 2, 1), + lambda_c_.segment(kSpaceDim * 2 + 2, 1), + lambda_c_.segment(kSpaceDim * 3 + 2, 1), epsilon_blend_}) + .evaluator() + .get(); + /// Soft constraint version + // DRAKE_DEMAND(w_blend_constraint_ > 0); + // prog_->AddQuadraticCost( + // w_blend_constraint_ * + // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), + // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); + /// hard constraint version + prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); + } + // blend_constraint_ = + // prog_ + // ->AddBoundingBoxConstraint( + // VectorXd::Zero(4), VectorXd::Zero(4), + // {lambda_c_.segment(kSpaceDim * 0 + 2, 1), + // lambda_c_.segment(kSpaceDim * 1 + 2, 1), + // lambda_c_.segment(kSpaceDim * 2 + 2, 1), + // lambda_c_.segment(kSpaceDim * 3 + 2, 1)}) + // .evaluator() + // .get(); for (int i = -1; i < 5; ++i) { solvers_[i] = std::make_unique(); @@ -489,16 +493,16 @@ void OperationalSpaceControl::Build() { drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( const drake::systems::Context& context, - drake::systems::DiscreteValues *discrete_state) const { - const BasicVector *fsm_output = - (BasicVector *) this->EvalVectorInput(context, fsm_port_); + drake::systems::DiscreteValues* discrete_state) const { + const BasicVector* fsm_output = + (BasicVector*)this->EvalVectorInput(context, fsm_port_); VectorXd fsm_state = fsm_output->get_value(); - const OutputVector *robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); double timestamp = robot_output->get_timestamp(); auto prev_fsm_state = discrete_state->get_mutable_vector(prev_fsm_state_idx_) - .get_mutable_value(); + .get_mutable_value(); if (fsm_state(0) != prev_fsm_state(0)) { prev_distinct_fsm_state_ = prev_fsm_state(0); prev_fsm_state(0) = fsm_state(0); @@ -512,8 +516,7 @@ drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( VectorXd OperationalSpaceControl::SolveQp( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const drake::systems::Context& context, double t, int fsm_state, - double t_since_last_state_switch, double alpha, - int next_fsm_state) const { + double t_since_last_state_switch, double alpha, int next_fsm_state) const { // Get active contact indices std::set active_contact_set = {}; if (single_contact_mode_) { @@ -523,10 +526,10 @@ VectorXd OperationalSpaceControl::SolveQp( if (map_iterator != contact_indices_map_.end()) { active_contact_set = map_iterator->second; } else { - static const drake::logging::Warn log_once(const_cast( - (std::to_string(fsm_state) + - " is not a valid finite state machine state in OSC.") - .c_str())); + static const drake::logging::Warn log_once(const_cast( + (std::to_string(fsm_state) + + " is not a valid finite state machine state in OSC.") + .c_str())); } } @@ -683,7 +686,7 @@ VectorXd OperationalSpaceControl::SolveQp( // Read in traj from input port const string& traj_name = tracking_data->GetName(); int port_index = traj_name_to_port_index_map_.at(traj_name); - const drake::AbstractValue *input_traj = + const drake::AbstractValue* input_traj = this->EvalAbstractInput(context, port_index); DRAKE_DEMAND(input_traj != nullptr); const auto& traj = @@ -701,7 +704,8 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd constant_term = (JdotV_t - ddy_t); tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t + W_joint_accel_, J_t.transpose() * W * (JdotV_t - ddy_t), + J_t.transpose() * W * J_t + W_joint_accel_, + J_t.transpose() * W * (JdotV_t - ddy_t), constant_term.transpose() * W * constant_term); // tracking_cost_.at(i)->UpdateCoefficients( // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * @@ -717,49 +721,44 @@ VectorXd OperationalSpaceControl::SolveQp( // Add joint limit constraints VectorXd w_joint_limit = K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_max_) - .cwiseMax(0) + - K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_min_) - .cwiseMin(0); + .tail(n_revolute_joints_) - + q_max_) + .cwiseMax(0) + + K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) + .tail(n_revolute_joints_) - + q_min_) + .cwiseMin(0); joint_limit_cost_.at(0)->UpdateCoefficients(w_joint_limit, 0); // (Testing) 6. blend contact forces during double support phase -// if (ds_duration_ > 0) { -// MatrixXd A = MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim); -// if (std::find(ds_states_.begin(), ds_states_.end(), fsm_state) != -// ds_states_.end()) { -// double alpha_left = 0; -// double alpha_right = 0; -// if (prev_distinct_fsm_state_ == right_support_state_) { -// // We want left foot force to gradually increase -// alpha_left = -1; -// alpha_right = t_since_last_state_switch / -// (ds_duration_ - t_since_last_state_switch); -// -// } else if (prev_distinct_fsm_state_ == left_support_state_) { -// alpha_left = t_since_last_state_switch / -// (ds_duration_ - t_since_last_state_switch); -// alpha_right = -1; -// } -// A(0, 0) = alpha_left / 2; -// A(0, 1) = alpha_left / 2; -// A(0, 2) = alpha_right / 2; -// A(0, 3) = alpha_right / 2; -// A(0, 4) = 1; -// A(0, 5) = 1; -// A(0, 6) = 1; -// A(0, 7) = 1; -// } -// VectorXd normals = VectorXd(4); -// normals << lambda_c_sol_->segment(kSpaceDim * 0 + 2, 1), -// lambda_c_sol_->segment(kSpaceDim * 1 + 2, 1), -// lambda_c_sol_->segment(kSpaceDim * 2 + 2, 1), -// lambda_c_sol_->segment(kSpaceDim * 3 + 2, 1); -// blend_constraint_->UpdateCoefficients(MatrixXd::Identity(4, 4), normals - 25 * VectorXd::Ones(4), normals + 25 * VectorXd::Ones(4)); -// } + if (ds_duration_ > 0) { + MatrixXd A = MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim); + if (std::find(ds_states_.begin(), ds_states_.end(), fsm_state) != + ds_states_.end()) { + double alpha_left = 0; + double alpha_right = 0; + if (prev_distinct_fsm_state_ == right_support_state_) { + // We want left foot force to gradually increase + alpha_left = -1; + alpha_right = t_since_last_state_switch / + (ds_duration_ - t_since_last_state_switch); + + } else if (prev_distinct_fsm_state_ == left_support_state_) { + alpha_left = t_since_last_state_switch / + (ds_duration_ - t_since_last_state_switch); + alpha_right = -1; + } + A(0, 0) = alpha_left / 2; + A(0, 1) = alpha_left / 2; + A(0, 2) = alpha_right / 2; + A(0, 3) = alpha_right / 2; + A(0, 4) = 1; + A(0, 5) = 1; + A(0, 6) = 1; + A(0, 7) = 1; + } + blend_constraint_->UpdateCoefficients(A, VectorXd::Zero(1)); + } // test joint-level input cost by fsm state if (!fsm_to_w_input_map_.empty()) { @@ -774,22 +773,27 @@ VectorXd OperationalSpaceControl::SolveQp( // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0 && initial_guess_x_.count(fsm_state) > 0) { - input_smoothing_cost_->UpdateCoefficients( - W_input_smoothing_, -W_input_smoothing_ * *u_prev_); + input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, + -W_input_smoothing_ * *u_prev_); } if (W_lambda_c_reg_.size() > 0) { - lambda_c_smoothing_cost_->UpdateCoefficients(1000 * alpha * W_lambda_c_reg_, + lambda_c_smoothing_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, VectorXd::Zero(n_c_)); } + if (W_lambda_h_reg_.size() > 0) { + lambda_h_smoothing_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, + VectorXd::Zero(n_h_)); + } + if (!solvers_.at(0)->IsInitialized()) { solvers_.at(0)->InitializeSolver(*prog_, solver_options_); } if (initial_guess_x_.count(fsm_state) > 0) { solvers_.at(0)->WarmStart(initial_guess_x_.at(fsm_state), - initial_guess_y_.at(fsm_state)); + initial_guess_y_.at(fsm_state)); } // Solve the QP @@ -809,45 +813,55 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); -// double window = 0.01; -// double tau = 0.005; -// double state_2_start = 0.2; -// double state_2_end = 0.3; -// double state_3_start = 0.5; -// double state_3_end = 0.6; -// if (fsm_state >= 2 && initial_guess_x_.size() == 4) { -// double clock_time; -// if (this->get_input_port(clock_port_).HasValue(context)) { -// auto clock = this->EvalVectorInput(context, clock_port_); -// clock_time = clock->get_value()(0); -// } -// if (fsm_state == 2) { -// double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); -// double blend_out = 1 - exp(-((clock_time - 0.2) + window) / tau); -// double blend_in = (state_2_end - clock_time) / (state_2_end - state_2_start); -// double blend_out = 1 - (state_2_end - clock_time) / (state_2_end - state_2_start); -// u_sol_->row(6) = -// blend_out * u_sol_->row(6) + (1 - blend_out) * u_prev_[0].row(6); -// u_sol_->row(7) = -// blend_in * u_sol_->row(7) + (1 - blend_in) * u_prev_[1].row(7); -// u_sol_->row(0) = -// blend_out * u_sol_->row(0) + (1 - blend_out) * u_prev_[0].row(0); -// u_sol_->row(1) = -// blend_in * u_sol_->row(1) + (1 - blend_in) * u_prev_[1].row(1); -// } -// if (fsm_state == 3) { -// double blend_in = (state_3_end - clock_time) / (state_3_end - state_3_start); -// double blend_out = 1 - (state_3_end - clock_time) / (state_3_end - state_3_start); -// u_sol_->row(6) = -// blend_in * u_sol_->row(6) + (1 - blend_in) * u_prev_[0].row(6); -// u_sol_->row(7) = -// blend_out * u_sol_->row(7) + (1 - blend_out) * u_prev_[1].row(7); -// u_sol_->row(0) = -// blend_in * u_sol_->row(0) + (1 - blend_in) * u_prev_[0].row(0); -// u_sol_->row(1) = -// blend_out * u_sol_->row(1) + (1 - blend_out) * u_prev_[1].row(1); -// } -// } + // double window = 0.01; + // double tau = 0.005; + // double state_2_start = 0.2; + // double state_2_end = 0.3; + // double state_3_start = 0.5; + // double state_3_end = 0.6; + // if (fsm_state >= 2 && initial_guess_x_.size() == 4) { + // double clock_time; + // if (this->get_input_port(clock_port_).HasValue(context)) { + // auto clock = this->EvalVectorInput(context, clock_port_); + // clock_time = clock->get_value()(0); + // } + // if (fsm_state == 2) { + // double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); + // double blend_out = 1 - exp(-((clock_time - 0.2) + window) / + // tau); double blend_in = (state_2_end - clock_time) / + // (state_2_end - state_2_start); double blend_out = 1 - + // (state_2_end - clock_time) / (state_2_end - state_2_start); + // u_sol_->row(6) = + // blend_out * u_sol_->row(6) + (1 - blend_out) * + // u_prev_[0].row(6); + // u_sol_->row(7) = + // blend_in * u_sol_->row(7) + (1 - blend_in) * + // u_prev_[1].row(7); + // u_sol_->row(0) = + // blend_out * u_sol_->row(0) + (1 - blend_out) * + // u_prev_[0].row(0); + // u_sol_->row(1) = + // blend_in * u_sol_->row(1) + (1 - blend_in) * + // u_prev_[1].row(1); + // } + // if (fsm_state == 3) { + // double blend_in = (state_3_end - clock_time) / (state_3_end - + // state_3_start); double blend_out = 1 - (state_3_end - + // clock_time) / (state_3_end - state_3_start); + // u_sol_->row(6) = + // blend_in * u_sol_->row(6) + (1 - blend_in) * + // u_prev_[0].row(6); + // u_sol_->row(7) = + // blend_out * u_sol_->row(7) + (1 - blend_out) * + // u_prev_[1].row(7); + // u_sol_->row(0) = + // blend_in * u_sol_->row(0) + (1 - blend_in) * + // u_prev_[0].row(0); + // u_sol_->row(1) = + // blend_out * u_sol_->row(1) + (1 - blend_out) * + // u_prev_[1].row(1); + // } + // } initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { @@ -910,7 +924,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( // Read in traj from input port const string& traj_name = tracking_data->GetName(); int port_index = traj_name_to_port_index_map_.at(traj_name); - const drake::AbstractValue *input_traj = + const drake::AbstractValue* input_traj = EvalAbstractInput(context, port_index); const auto& traj = input_traj->get_value>(); @@ -952,58 +966,58 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( b_constrained << Ab, d; ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition() - .solve(b_constrained) - .head(active_constraint_dim); + .solve(b_constrained) + .head(active_constraint_dim); } void OperationalSpaceControl::AssignOscLcmOutput( - const Context& context, dairlib::lcmt_osc_output *output) const { + const Context& context, dairlib::lcmt_osc_output* output) const { auto state = - (OutputVector *) this->EvalVectorInput(context, state_port_); + (OutputVector*)this->EvalVectorInput(context, state_port_); total_cost_ = 0; int fsm_state = -1; if (used_with_finite_state_machine_) { auto fsm_output = - (BasicVector *) this->EvalVectorInput(context, fsm_port_); + (BasicVector*)this->EvalVectorInput(context, fsm_port_); fsm_state = fsm_output->get_value()(0); } double time_since_last_state_switch = used_with_finite_state_machine_ - ? state->get_timestamp() - - context.get_discrete_state(prev_event_time_idx_).get_value()(0) - : state->get_timestamp(); + ? state->get_timestamp() - + context.get_discrete_state(prev_event_time_idx_).get_value()(0) + : state->get_timestamp(); output->utime = state->get_timestamp() * 1e6; output->fsm_state = fsm_state; double input_cost = (W_input_.size() > 0) - ? (0.5 * (*u_sol_).transpose() * W_input_ * (*u_sol_))(0) - : 0; + ? (0.5 * (*u_sol_).transpose() * W_input_ * (*u_sol_))(0) + : 0; double acceleration_cost = (W_joint_accel_.size() > 0) - ? (0.5 * (*dv_sol_).transpose() * W_joint_accel_ * (*dv_sol_))(0) - : 0; + ? (0.5 * (*dv_sol_).transpose() * W_joint_accel_ * (*dv_sol_))(0) + : 0; double soft_constraint_cost = (w_soft_constraint_ > 0) - ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * - (*epsilon_sol_))(0) - : 0; + ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * + (*epsilon_sol_))(0) + : 0; double input_smoothing_cost = (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_ - *u_prev_).transpose() * - W_input_smoothing_ * (*u_sol_ - *u_prev_))(0) - : 0; + ? (0.5 * (*u_sol_ - *u_prev_).transpose() * W_input_smoothing_ * + (*u_sol_ - *u_prev_))(0) + : 0; double lambda_h_cost = (W_lambda_h_reg_.size() > 0) - ? (0.5 * (*lambda_h_sol_).transpose() * - W_lambda_h_reg_ * (*lambda_h_sol_))(0) - : 0; + ? (0.5 * (*lambda_h_sol_).transpose() * + W_lambda_h_reg_ * (*lambda_h_sol_))(0) + : 0; double lambda_c_cost = (W_lambda_c_reg_.size() > 0) - ? (0.5 * (*lambda_c_sol_).transpose() * - W_lambda_c_reg_ * (*lambda_c_sol_))(0) - : 0; + ? (0.5 * (*lambda_c_sol_).transpose() * + W_lambda_c_reg_ * (*lambda_c_sol_))(0) + : 0; total_cost_ += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost; + input_smoothing_cost + lambda_h_cost + lambda_c_cost; soft_constraint_cost_ = soft_constraint_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); @@ -1090,7 +1104,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); output->tracking_costs[i] = (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * - (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); + (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); total_cost_ += output->tracking_costs[i]; } output->tracking_data[i] = osc_output; @@ -1102,15 +1116,15 @@ void OperationalSpaceControl::AssignOscLcmOutput( void OperationalSpaceControl::CalcOptimalInput( const drake::systems::Context& context, - systems::TimestampedVector *control) const { + systems::TimestampedVector* control) const { // Read in current state and time auto robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + (OutputVector*)this->EvalVectorInput(context, state_port_); VectorXd q_w_spr = robot_output->GetPositions(); VectorXd v_w_spr = robot_output->GetVelocities(); VectorXd x_w_spr(plant_w_spr_.num_positions() + - plant_w_spr_.num_velocities()); + plant_w_spr_.num_velocities()); x_w_spr << q_w_spr, v_w_spr; double timestamp = robot_output->get_timestamp(); @@ -1135,7 +1149,7 @@ void OperationalSpaceControl::CalcOptimalInput( double alpha = 0; int next_fsm_state = -1; if (this->get_input_port_impact_info().HasValue(context)) { - auto impact_info = (ImpactInfoVector *) this->EvalVectorInput( + auto impact_info = (ImpactInfoVector*)this->EvalVectorInput( context, impact_info_port_); alpha = impact_info->GetAlpha(); next_fsm_state = impact_info->GetCurrentContactMode(); @@ -1157,9 +1171,9 @@ void OperationalSpaceControl::CalcOptimalInput( void OperationalSpaceControl::CheckTracking( const drake::systems::Context& context, - TimestampedVector *output) const { + TimestampedVector* output) const { auto robot_output = - (OutputVector *) this->EvalVectorInput(context, state_port_); + (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 9c4f4c6b06..60e43360c6 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -341,6 +341,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector joint_limit_cost_; drake::solvers::QuadraticCost* input_smoothing_cost_; drake::solvers::QuadraticCost* lambda_c_smoothing_cost_; + drake::solvers::QuadraticCost* lambda_h_smoothing_cost_; // OSC solution std::unique_ptr dv_sol_; @@ -407,7 +408,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector ds_states_; double w_blend_constraint_ = 0.1; // for soft constraint mutable double prev_distinct_fsm_state_ = -1; - drake::solvers::BoundingBoxConstraint* blend_constraint_; + drake::solvers::LinearEqualityConstraint* blend_constraint_; drake::solvers::VectorXDecisionVariable epsilon_blend_; // drake::solvers::BoundingBoxConstraint* contact_force_smoothing_constraint_; From 0535221193de67aee370ea71045dedf38c34eccd Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 19 Aug 2022 15:02:17 -0400 Subject: [PATCH 287/758] outputting jump time --- examples/Cassie/osc/osc_walking_gains_alip.yaml | 12 ++++++------ examples/Cassie/osc_jump/jumping_event_based_fsm.cc | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 1357af9b2f..d4f97a0f39 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -1,11 +1,11 @@ # OSC gains w_input: 0.0000 -w_input_reg: 0.000003 +w_input_reg: 0.000001 w_accel: 0.00000001 w_lambda: 0.00000001 w_soft_constraint: 80 -impact_threshold: 0.00 -impact_tau: 0.00 +impact_threshold: 0.025 +impact_tau: 0.005 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_input_reg: [1, 0.9, 0.5, 0.1, 5, @@ -53,7 +53,7 @@ ss_time: 0.3 ds_time: 0.1 # Distance of contact point from foot rear (0 is heel, 1 is toe) -contact_point_pos: 0.8 +contact_point_pos: 0.35 # Swing foot trajectory max_CoM_to_footstep_dist: 0.55 @@ -70,7 +70,7 @@ w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 2.0 +w_hip_yaw: 0.1 hip_yaw_kp: 40 hip_yaw_kd: 1 @@ -124,7 +124,7 @@ SwingFootKp: SwingFootKd: [ 1, 0, 0, 0, 1, 0, - 0, 0, 5] + 0, 0, 1] AlipKalmanQ: [.001, .001, .01, .01] diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc index ef52cb9017..03d1496ddd 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc @@ -95,7 +95,7 @@ EventStatus JumpingEventFsm::DiscreteVariableUpdate( prev_time << timestamp; if (abs(transition_times_[BALANCE] - timestamp - - round(transition_times_[BALANCE] - timestamp)) < 1e-4) { + round(transition_times_[BALANCE] - timestamp)) < 1e-3) { std::cout << "Time until crouch: " << round(transition_times_[BALANCE] - timestamp) << std::endl; } From 40247298b6a32dd2b05a5cd65faf72e60a3bfb37 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Aug 2022 11:22:31 -0400 Subject: [PATCH 288/758] still tuning gains --- .../pydairlib/analysis/log_plotter_cassie.py | 2 + .../pydairlib/analysis/mbp_plotting_utils.py | 16 +++++ .../plot_configs/cassie_running_plot.yaml | 14 ++--- .../contact_scheduler/contact_scheduler.cc | 16 ++--- .../contact_scheduler/contact_scheduler.h | 6 ++ .../osc_running_controller_diagram.cc | 2 +- .../osc_walking_controller_diagram.cc | 2 +- examples/Cassie/osc_run/osc_running_gains.h | 3 + .../Cassie/osc_run/osc_running_gains.yaml | 63 ++++++++++--------- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_jumping_controller.cc | 2 +- examples/Cassie/run_osc_running_controller.cc | 35 +++++------ .../Cassie/run_osc_standing_controller.cc | 3 +- examples/Cassie/run_osc_walking_controller.cc | 3 +- .../Cassie/run_osc_walking_controller_alip.cc | 4 +- .../osc/operational_space_control.cc | 21 ++++--- .../osc/operational_space_control.h | 6 +- 17 files changed, 120 insertions(+), 80 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 70fa9c480f..65b45f9873 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -133,6 +133,8 @@ def main(): if plot_config.plot_qp_solutions: plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 6)) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 6f3ba74fe9..5fc2a6fdb2 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -559,6 +559,22 @@ def plot_lambda_c_sol(osc_debug, time_slice, lambda_slice): return ps +def plot_lambda_h_sol(osc_debug, time_slice, lambda_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + ['lambda_h_sol'], + {'lambda_h_sol': lambda_slice}, + {'lambda_h_sol': ['lambda_h_' + i for i in + plotting_utils.slice_to_string_list(lambda_slice)]}, + {'xlabel': 'time', + 'ylabel': 'lambda', + 'title': 'OSC constraint force solution'}, ps) + return ps + + def plot_epsilon_sol(osc_debug, time_slice, epsilon_slice): ps = plot_styler.PlotStyler() plotting_utils.make_plot( diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index e1fc769454..d9c8569072 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -14,8 +14,8 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true -plot_floating_base_velocities: true +plot_floating_base_positions: false +plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false @@ -43,15 +43,15 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] }, - # pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] }, + pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - # right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - # left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': ['pos', 'accel' ] }, + right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, + # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, } \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 53df1ac56b..605bbcb192 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -182,11 +182,11 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // TODO(yangwill): calculate end of stance duration double stance_scale = (0.016) / (pelvis_zdot * pelvis_zdot); - stance_scale = drake::math::saturate(stance_scale, 0.9, 1.2); + stance_scale = drake::math::saturate(stance_scale, 0.95, 1.05); // std::cout << "stance scale: " << stance_scale << std::endl; - // double next_transition_time = - // stored_transition_time + stance_scale * 0.25; - double next_transition_time = stored_transition_time + 0.25; + double next_transition_time = + stored_transition_time + stance_scale * stance_duration_; +// double next_transition_time = stored_transition_time + stance_duration_; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; if (active_state == LEFT_STANCE) { @@ -203,16 +203,16 @@ EventStatus ContactScheduler::UpdateTransitionTimes( {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; } } else { - double time_to_touchdown = 0.1; + double time_to_touchdown = flight_duration_; if (pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z) > 0) { time_to_touchdown = (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z))) / g; } - // double time_to_touchdown_saturated = - // drake::math::saturate(time_to_touchdown, 0.08, 0.12); - double time_to_touchdown_saturated = 0.12; + // double time_to_touchdown_saturated = ; + double time_to_touchdown_saturated = drake::math::saturate( + time_to_touchdown, 0.9 * flight_duration_, 1.1 * flight_duration_); double next_transition_time = stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index d3dbe11663..eb99f94fc4 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -26,6 +26,10 @@ class ContactScheduler : public drake::systems::LeafSystem { BLEND_FUNC blend_func = SIGMOID); void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } + void SetNominalStepTimings(double stance_duration, double flight_duration) { + stance_duration_ = stance_duration; + flight_duration_ = flight_duration; + } const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } @@ -101,6 +105,8 @@ class ContactScheduler : public drake::systems::LeafSystem { /// SLIP parameters double rest_length_; + double stance_duration_; + double flight_duration_; }; } // namespace dairlib diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 49fe72cea5..d53d4d2f64 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -184,7 +184,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight(1e-4 * gains.W_lambda_c_regularization); diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 2a9c046544..341688827f 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -227,7 +227,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( int n_u = plant.num_actuators(); MatrixXd Q_accel = osc_walking_gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingWeights( + osc->SetInputSmoothingCostWeights( osc_walking_gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Soft constraint on contacts osc->SetSoftConstraintWeight(osc_walking_gains.w_soft_constraint); diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 4919db7851..779025f6df 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -37,6 +37,7 @@ struct OSCRunningGains : OSCGains { std::vector ekf_filter_tau; double rot_filter_tau; + double w_input_accel; // swing foot tracking std::vector SwingFootW; @@ -92,6 +93,8 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(mid_foot_height)); a->Visit(DRAKE_NVP(ekf_filter_tau)); a->Visit(DRAKE_NVP(rot_filter_tau)); + a->Visit(DRAKE_NVP(w_input_accel)); + a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 89a36b3fc1..4e41771901 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,9 +1,10 @@ w_input: 0.000001 -w_input_reg: 0.1 +w_input_reg: 0.01 w_accel: 0.0001 -w_soft_constraint: 100 +w_soft_constraint: 1000 w_lambda: 0.1 -impact_threshold: 0.05 +w_input_accel: 0.1 +impact_threshold: 0.050 impact_tau: 0.005 weight_scaling: 1.0 mu: 0.6 @@ -17,8 +18,8 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.001, 0.01 ] -W_lambda_h_reg: [ 0.01, 0.01, 0.01, - 0.01, 0.01, 0.01 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.001, 0.001 ] #w_soft_constraint: 1000000 relative_feet: true @@ -33,20 +34,20 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.0 -stance_duration: 0.25 -flight_duration: 0.10 +rest_length_offset: 0.00 +stance_duration: 0.3 +flight_duration: 0.09 w_swing_toe: 1 -swing_toe_kp: 1000 -swing_toe_kd: 5 +swing_toe_kp: 1500 +swing_toe_kd: 10 w_hip_yaw: 2.5 hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.06 +footstep_sagital_offset: -0.04 footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.05 FootstepKd: @@ -54,41 +55,41 @@ FootstepKd: 0, 0.4, 0, 0, 0, 0 ] PelvisW: - [ 1, 0, 0, + [ 0, 0, 0, 0, 1, 0, 0, 0, 5 ] PelvisKp: - [ -50, 0, 0, + [ 0, 0, 0, 0, 50, 0, - 0, 0, 145] + 0, 0, 85] PelvisKd: - [ 2, 0, 0, + [ 0, 0, 0, 0, 2, 0, - 0, 0, 4 ] + 0, 0, 5 ] PelvisRotW: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 1 ] + [1, 0, 0, + 0, 2.5, 0, + 0, 0, 0.1] PelvisRotKp: - [30., 0, 0, + [50., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [2., 0, 0, + [8., 0, 0, 0, 5., 0, - 0, 0, 3.] + 0, 0, 1.] SwingFootW: - [ 10, 0, 0, - 0, 100, 0, - 0, 0, 5 ] + [10, 0, 0, + 0, 100, 0, + 0, 0, 10] SwingFootKp: - [ 50, 0, 0, - 0, 100, 0, - 0, 0, 50 ] + [125, 0, 0, + 0, 100, 0, + 0, 0, 40] SwingFootKd: - [ 5., 0, 0, - 0, 10., 0, - 0, 0, 1. ] + [5., 0, 0, + 0, 5., 0, + 0, 0, 2.] LiftoffSwingFootW: [1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 4238c8cf39..7d134ca996 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -12,7 +12,7 @@ polish: 0 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 -check_termination: 15 +check_termination: 25 warm_start: 1 scaling: 1 adaptive_rho: 1 diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 749ad67580..9a7ec046c6 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -306,7 +306,7 @@ int DoMain(int argc, char* argv[]) { osc->SetSoftConstraintWeight(gains.w_soft_constraint); // Soft constraint on contacts - osc->SetInputSmoothingWeights(1e-3 * gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 85b9ca1bf6..b1253715d7 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -166,9 +166,8 @@ int DoMain(int argc, char* argv[]) { plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); contact_scheduler->SetSLIPParams(osc_gains.rest_length); - // auto fsm = builder.AddSystem( - // plant, fsm_states, state_durations, 0.0, gains.impact_threshold, - // gains.impact_tau); + contact_scheduler->SetNominalStepTimings(osc_gains.stance_duration, + osc_gains.flight_duration); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -201,8 +200,9 @@ int DoMain(int argc, char* argv[]) { // Cost /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); - osc->SetInputSmoothingWeights(osc_gains.w_input_reg * - osc_gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * + osc_gains.W_input_regularization); + osc->SetInputSmoothingConstraintWeights(osc_gains.w_input_accel); osc->SetInputCostWeights(osc_gains.w_input * osc_gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight( @@ -346,7 +346,6 @@ int DoMain(int argc, char* argv[]) { right_foot_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); - auto left_foot_yz_tracking_data = std::make_unique( "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -430,7 +429,8 @@ int DoMain(int argc, char* argv[]) { {0, 0.25 + 0.2}, {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)}); PiecewisePolynomial foot_traj_gain_trajectory = PiecewisePolynomial::FirstOrderHold( - {0, 0.25 + 0.2}, {0.5 * MatrixXd::Identity(3, 3), 2.0 * MatrixXd::Identity(3, 3)}); + {0, 0.25 + 0.2}, + {0.5 * MatrixXd::Identity(3, 3), 2.0 * MatrixXd::Identity(3, 3)}); // PiecewisePolynomial foot_traj_weight_trajectory = // PiecewisePolynomial::FirstOrderHold( // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); @@ -438,10 +438,8 @@ int DoMain(int argc, char* argv[]) { foot_traj_weight_trajectory); right_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); - left_foot_rel_tracking_data->SetTimeVaryingGains( - foot_traj_gain_trajectory); - right_foot_rel_tracking_data->SetTimeVaryingGains( - foot_traj_gain_trajectory); + left_foot_rel_tracking_data->SetTimeVaryingGains(foot_traj_gain_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingGains(foot_traj_gain_trajectory); // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); @@ -460,8 +458,8 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); -// osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); -// osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); + // osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); + // osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); auto heading_traj_generator = builder.AddSystem(plant, @@ -478,7 +476,8 @@ int DoMain(int argc, char* argv[]) { RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {0, 1, 2}); + pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, + {0, 1, 2}); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -616,10 +615,10 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("right_ft_traj")); -// builder.Connect(l_foot_traj_generator->get_output_port(0), -// osc->get_input_port_tracking_data("left_ft_z_traj")); -// builder.Connect(r_foot_traj_generator->get_output_port(0), -// osc->get_input_port_tracking_data("right_ft_z_traj")); + // builder.Connect(l_foot_traj_generator->get_output_port(0), + // osc->get_input_port_tracking_data("left_ft_z_traj")); + // builder.Connect(r_foot_traj_generator->get_output_port(0), + // osc->get_input_port_tracking_data("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index e0e83a4045..c4ec7627bf 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -221,7 +221,8 @@ int DoMain(int argc, char* argv[]) { int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingWeights(gains.w_input_reg * gains.W_input_regularization); + osc->SetInputSmoothingCostWeights( + gains.w_input_reg * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * gains.W_lambda_h_regularization); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index 9401e0f630..33e70238c3 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -373,7 +373,8 @@ int DoMain(int argc, char* argv[]) { int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingWeights(gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingCostWeights( + gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index d35f8f14f5..a0d547a38a 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -375,8 +375,8 @@ int DoMain(int argc, char* argv[]) { osc_walking_gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * osc_walking_gains.W_lambda_h_regularization); - osc->SetInputSmoothingWeights(osc_walking_gains.w_input_reg * - MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingCostWeights(osc_walking_gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 0e4b200b4b..f2eff9d703 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -430,11 +430,12 @@ void OperationalSpaceControl::Build() { .evaluator() .get(); } - // input_smoothing_constraint_ = - // prog_->AddBoundingBoxConstraint(VectorXd::Zero(n_u_), - // VectorXd::Zero(n_u_), u_) - // .evaluator() - // .get(); + input_smoothing_constraint_ = + prog_ + ->AddBoundingBoxConstraint(u_min_, u_max_, + u_) + .evaluator() + .get(); // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { tracking_cost_.push_back(prog_ @@ -704,9 +705,9 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd constant_term = (JdotV_t - ddy_t); tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t + W_joint_accel_, + J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), - constant_term.transpose() * W * constant_term); + constant_term.transpose() * W * constant_term, true); // tracking_cost_.at(i)->UpdateCoefficients( // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * // constant_term.transpose() * W * constant_term); @@ -777,6 +778,12 @@ VectorXd OperationalSpaceControl::SolveQp( -W_input_smoothing_ * *u_prev_); } +// if (w_input_smoothing_constraint_ < 1){ +// input_smoothing_constraint_->UpdateCoefficients( +// MatrixXd::Identity(n_u_, n_u_), *u_prev_ - w_input_smoothing_constraint_ * u_max_, +// *u_prev_ + w_input_smoothing_constraint_ * u_max_); +// } + if (W_lambda_c_reg_.size() > 0) { lambda_c_smoothing_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, VectorXd::Zero(n_c_)); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 60e43360c6..59799e02fa 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -144,9 +144,12 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void SetAccelerationCostWeights(const Eigen::MatrixXd& W) { W_joint_accel_ = W; } - void SetInputSmoothingWeights(const Eigen::MatrixXd& W) { + void SetInputSmoothingCostWeights(const Eigen::MatrixXd& W) { W_input_smoothing_ = W; } + void SetInputSmoothingConstraintWeights(const double w) { + w_input_smoothing_constraint_ = w; + } void SetSoftConstraintWeight(double w_soft_constraint) { w_soft_constraint_ = w_soft_constraint; } @@ -364,6 +367,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::MatrixXd W_input_smoothing_; Eigen::MatrixXd W_lambda_c_reg_; Eigen::MatrixXd W_lambda_h_reg_; + double w_input_smoothing_constraint_ = 1; std::map> fsm_to_w_input_map_; // each pair is (joint index, weight) From e42278e507b69692171f29428e1caab9df3b9c2c Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Aug 2022 12:57:04 -0400 Subject: [PATCH 289/758] updating gains --- examples/Cassie/contact_scheduler/contact_scheduler.cc | 4 ++-- examples/Cassie/osc/swing_toe_traj_generator.cc | 2 +- examples/Cassie/osc_run/osc_running_gains.yaml | 6 +++--- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 605bbcb192..873d90442f 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -181,8 +181,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // Store the ground height of the stance foot // TODO(yangwill): calculate end of stance duration - double stance_scale = (0.016) / (pelvis_zdot * pelvis_zdot); - stance_scale = drake::math::saturate(stance_scale, 0.95, 1.05); + double stance_scale = (rest_length_) / (pelvis_z); + stance_scale = drake::math::saturate(stance_scale, 0.9, 1.2); // std::cout << "stance scale: " << stance_scale << std::endl; double next_transition_time = stored_transition_time + stance_scale * stance_duration_; diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index 05b3d23f92..58db05345c 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -63,7 +63,7 @@ void SwingToeTrajGenerator::CalcTraj( double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); - des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane + 0.02; + des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; // des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; auto* pp_traj = diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4e41771901..6f96f2bdf7 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -47,8 +47,8 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.04 -footstep_lateral_offset: 0.04 # drake +footstep_sagital_offset: -0.08 +footstep_lateral_offset: 0.03 # drake mid_foot_height: 0.05 FootstepKd: [ 0.18, 0, 0, @@ -61,7 +61,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 50, 0, - 0, 0, 85] + 0, 0, 105] PelvisKd: [ 0, 0, 0, 0, 2, 0, From a75b85e53b1ff322ed5229aa3ddc2e6931220fe4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Aug 2022 14:53:00 -0400 Subject: [PATCH 290/758] attempting a more grounded running gait to get it working first --- examples/Cassie/osc_run/foot_traj_generator.cc | 2 +- examples/Cassie/osc_run/osc_running_gains.yaml | 16 ++++++++-------- .../osc_run/pelvis_trans_traj_generator.cc | 5 ++--- examples/Cassie/run_osc_running_controller.cc | 2 +- 4 files changed, 12 insertions(+), 13 deletions(-) diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index efbb7238db..d4661e2301 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -273,7 +273,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[1] = start_pos + 0.85 * foot_end_pos_des; Y[1](2) = -rest_length_ + mid_foot_height_; Y[2] = foot_end_pos_des; - Y[2](2) = -rest_length_; + Y[2](2) = -rest_length_ - rest_length_offset_; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 6f96f2bdf7..fdbaf9eec4 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -34,7 +34,7 @@ vel_scale_trans_lateral: -0.0 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.00 +rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 @@ -47,8 +47,8 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.08 -footstep_lateral_offset: 0.03 # drake +footstep_sagital_offset: -0.06 +footstep_lateral_offset: 0.02 # drake mid_foot_height: 0.05 FootstepKd: [ 0.18, 0, 0, @@ -61,7 +61,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 50, 0, - 0, 0, 105] + 0, 0, 115] PelvisKd: [ 0, 0, 0, 0, 2, 0, @@ -85,15 +85,15 @@ SwingFootW: SwingFootKp: [125, 0, 0, 0, 100, 0, - 0, 0, 40] + 0, 0, 50] SwingFootKd: [5., 0, 0, 0, 5., 0, 0, 0, 2.] LiftoffSwingFootW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] + [0, 0, 0, + 0, 0, 0, + 0, 0, 0] LiftoffSwingFootKp: [25, 0, 0, 0, 50, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 21211be821..f2c067483e 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -134,9 +134,8 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( } else if (fsm_state == 1) { y_dist_des = 0.15; } - // samples << 0, 0, 0, y_dist_des, y_dist_des, y_dist_des, rest_length_, - // rest_length_ + 0.05, rest_length_; - samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + rest_length_offset_; +// samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + rest_length_offset_; + samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_; // samples_dot << 0, 0, 0, 0, 0.25, 0.0; // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); return PiecewisePolynomial::FirstOrderHold(breaks, samples); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index b1253715d7..1544842f9c 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -430,7 +430,7 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial foot_traj_gain_trajectory = PiecewisePolynomial::FirstOrderHold( {0, 0.25 + 0.2}, - {0.5 * MatrixXd::Identity(3, 3), 2.0 * MatrixXd::Identity(3, 3)}); + {0.5 * MatrixXd::Identity(3, 3), 3.0 * MatrixXd::Identity(3, 3)}); // PiecewisePolynomial foot_traj_weight_trajectory = // PiecewisePolynomial::FirstOrderHold( // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); From a8ea5c5e2dc70c72da06922b31c02b8de2a5fc42 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 23 Aug 2022 11:57:38 -0400 Subject: [PATCH 291/758] logging osc costs from the evaluator --- .../contact_scheduler/contact_scheduler.cc | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 3 +- examples/Cassie/osc_run/osc_running_gains.h | 3 + .../Cassie/osc_run/osc_running_gains.yaml | 24 +- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 1 + .../Cassie/run_osc_standing_controller.cc | 9 +- .../osc/operational_space_control.cc | 241 ++++++++---------- .../osc/operational_space_control.h | 50 ++-- 9 files changed, 155 insertions(+), 180 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 873d90442f..e47b7d5144 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -212,7 +212,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( } // double time_to_touchdown_saturated = ; double time_to_touchdown_saturated = drake::math::saturate( - time_to_touchdown, 0.9 * flight_duration_, 1.1 * flight_duration_); + time_to_touchdown, 0.75 * flight_duration_, 1.1 * flight_duration_); double next_transition_time = stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index d4661e2301..56e6812c51 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -268,8 +268,9 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; if (start_pos(2) == 0) { - Y[0](2) = -rest_length_; + Y[0](2) = -rest_length_ - rest_length_offset_; } + Y[0](2) -= rest_length_offset_; Y[1] = start_pos + 0.85 * foot_end_pos_des; Y[1](2) = -rest_length_ + mid_foot_height_; Y[2] = foot_end_pos_des; diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 779025f6df..07340c65b9 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -38,6 +38,7 @@ struct OSCRunningGains : OSCGains { std::vector ekf_filter_tau; double rot_filter_tau; double w_input_accel; + double w_joint_limit; // swing foot tracking std::vector SwingFootW; @@ -94,6 +95,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(ekf_filter_tau)); a->Visit(DRAKE_NVP(rot_filter_tau)); a->Visit(DRAKE_NVP(w_input_accel)); + a->Visit(DRAKE_NVP(w_joint_limit)); a->Visit(DRAKE_NVP(PelvisW)); @@ -172,6 +174,7 @@ struct OSCRunningGains : OSCGains { w_input_reg *= weight_scaling; w_lambda *= weight_scaling; w_soft_constraint *= weight_scaling; + w_joint_limit *= weight_scaling; W_pelvis *= weight_scaling; W_pelvis_rot *= weight_scaling; W_swing_foot *= weight_scaling; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index fdbaf9eec4..41661dbf47 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,6 +4,7 @@ w_accel: 0.0001 w_soft_constraint: 1000 w_lambda: 0.1 w_input_accel: 0.1 +w_joint_limit: 50 impact_threshold: 0.050 impact_tau: 0.005 weight_scaling: 1.0 @@ -38,7 +39,7 @@ rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 -w_swing_toe: 1 +w_swing_toe: 0.001 swing_toe_kp: 1500 swing_toe_kd: 10 @@ -47,11 +48,12 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.06 +#footstep_sagital_offset: -0.06 +footstep_sagital_offset: -0.05 footstep_lateral_offset: 0.02 # drake mid_foot_height: 0.05 FootstepKd: - [ 0.18, 0, 0, + [ 0.17, 0, 0, 0, 0.4, 0, 0, 0, 0 ] PelvisW: @@ -61,7 +63,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 50, 0, - 0, 0, 115] + 0, 0, 145] PelvisKd: [ 0, 0, 0, 0, 2, 0, @@ -75,17 +77,17 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [8., 0, 0, - 0, 5., 0, + [0.1, 0, 0, + 0, 2., 0, 0, 0, 1.] SwingFootW: - [10, 0, 0, - 0, 100, 0, - 0, 0, 10] + [1, 0, 0, + 0, 10, 0, + 0, 0, 1] SwingFootKp: - [125, 0, 0, + [100, 0, 0, 0, 100, 0, - 0, 0, 50] + 0, 0, 45] SwingFootKd: [5., 0, 0, 0, 5., 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 7d134ca996..97ab897cf1 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 150 +max_iter: 300 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1544842f9c..da8d609f4b 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -211,6 +211,7 @@ int DoMain(int argc, char* argv[]) { osc_gains.w_lambda * osc_gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetSoftConstraintWeight(osc_gains.w_soft_constraint); + osc->SetJointLimitWeight(osc_gains.w_joint_limit); // Contact information for OSC osc->SetContactFriction(osc_gains.mu); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index c4ec7627bf..c5afe230b7 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -197,7 +197,6 @@ int DoMain(int argc, char* argv[]) { osc->AddKinematicConstraint(&evaluators); - // Friction coefficient osc->SetContactFriction(gains.mu); // Add contact points @@ -221,11 +220,12 @@ int DoMain(int argc, char* argv[]) { int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingCostWeights( - gains.w_input_reg * gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.w_input_reg * + gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * gains.W_lambda_h_regularization); + osc->SetJointLimitWeight(1.0); // Center of mass tracking // Weighting x-y higher than z, as they are more important to balancing @@ -246,7 +246,8 @@ int DoMain(int argc, char* argv[]) { "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); pelvis_rot_traj->AddFrameToTrack("pelvis"); - pelvis_rot_traj->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, {0, 1, 2}); + pelvis_rot_traj->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, + {0, 1, 2}); osc->AddTrackingData(std::move(pelvis_rot_traj)); // Hip yaw joint tracking diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f2eff9d703..16d43cbade 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -397,12 +397,21 @@ void OperationalSpaceControl::Build() { // 2. acceleration cost if (W_joint_accel_.size() > 0) { DRAKE_DEMAND(W_joint_accel_.rows() == n_v_); - prog_->AddQuadraticCost(W_joint_accel_, VectorXd::Zero(n_v_), dv_); + accel_cost_ = + prog_->AddQuadraticCost(W_joint_accel_, VectorXd::Zero(n_v_), dv_) + .evaluator() + .get(); + } + if (W_input_smoothing_.size() > 0) { + input_smoothing_cost_ = + prog_->AddQuadraticCost(W_input_smoothing_, VectorXd::Zero(n_u_), u_) + .evaluator() + .get(); } // 3. contact force cost if (W_lambda_c_reg_.size() > 0) { DRAKE_DEMAND(W_lambda_c_reg_.rows() == n_c_); - lambda_c_smoothing_cost_ = + lambda_c_cost_ = prog_ ->AddQuadraticCost(W_lambda_c_reg_, VectorXd::Zero(n_c_), lambda_c_) .evaluator() @@ -411,7 +420,7 @@ void OperationalSpaceControl::Build() { // 3. constraint force cost if (W_lambda_h_reg_.size() > 0) { DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); - lambda_h_smoothing_cost_ = + lambda_h_cost_ = prog_ ->AddQuadraticCost(W_lambda_h_reg_, VectorXd::Zero(n_h_), lambda_h_) .evaluator() @@ -419,39 +428,32 @@ void OperationalSpaceControl::Build() { } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { - prog_->AddQuadraticCost( - w_soft_constraint_ * MatrixXd::Identity(n_c_active_, n_c_active_), - VectorXd::Zero(n_c_active_), epsilon_); - } - // (Testing) 7. Cost for staying close to the previous input - if (W_input_smoothing_.size() > 0) { - input_smoothing_cost_ = - prog_->AddQuadraticCost(W_input_smoothing_, VectorXd::Zero(n_u_), u_) + soft_constraint_cost_ = + prog_ + ->AddQuadraticCost(w_soft_constraint_ * + MatrixXd::Identity(n_c_active_, n_c_active_), + VectorXd::Zero(n_c_active_), epsilon_) .evaluator() .get(); } - input_smoothing_constraint_ = - prog_ - ->AddBoundingBoxConstraint(u_min_, u_max_, - u_) - .evaluator() - .get(); + // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { - tracking_cost_.push_back(prog_ - ->AddQuadraticCost(MatrixXd::Zero(n_v_, n_v_), - VectorXd::Zero(n_v_), dv_) - .evaluator() - .get()); + tracking_costs_.push_back(prog_ + ->AddQuadraticCost(MatrixXd::Zero(n_v_, n_v_), + VectorXd::Zero(n_v_), dv_) + .evaluator() + .get()); } // 5. Joint Limit cost - w_joint_limit_ = VectorXd::Zero(n_revolute_joints_); - K_joint_pos = 50 * MatrixXd::Identity(n_revolute_joints_, n_revolute_joints_); - joint_limit_cost_.push_back( - prog_->AddLinearCost(w_joint_limit_, 0, dv_.tail(n_revolute_joints_)) - .evaluator() - .get()); + K_joint_pos = w_joint_limit_ * W_joint_accel_.bottomRightCorner( + n_revolute_joints_, n_revolute_joints_); + joint_limit_cost_ = prog_ + ->AddLinearCost(VectorXd::Zero(n_revolute_joints_), 0, + dv_.tail(n_revolute_joints_)) + .evaluator() + .get(); // (Testing) 6. contact force blending if (ds_duration_ > 0) { @@ -704,18 +706,12 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); const VectorXd constant_term = (JdotV_t - ddy_t); - tracking_cost_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t, - J_t.transpose() * W * (JdotV_t - ddy_t), + tracking_costs_.at(i)->UpdateCoefficients( + J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), constant_term.transpose() * W * constant_term, true); - // tracking_cost_.at(i)->UpdateCoefficients( - // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_), 0.5 * - // constant_term.transpose() * W * constant_term); - // tracking_cost_.at(i)->UpdateCoefficients( - // J_t.transpose() * W * J_t, VectorXd::Zero(n_v_)); } else { - tracking_cost_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), - VectorXd::Zero(n_v_)); + tracking_costs_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), + VectorXd::Zero(n_v_)); } } @@ -729,7 +725,7 @@ VectorXd OperationalSpaceControl::SolveQp( .tail(n_revolute_joints_) - q_min_) .cwiseMin(0); - joint_limit_cost_.at(0)->UpdateCoefficients(w_joint_limit, 0); + joint_limit_cost_->UpdateCoefficients(w_joint_limit, 0); // (Testing) 6. blend contact forces during double support phase if (ds_duration_ > 0) { @@ -774,24 +770,19 @@ VectorXd OperationalSpaceControl::SolveQp( // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0 && initial_guess_x_.count(fsm_state) > 0) { - input_smoothing_cost_->UpdateCoefficients(W_input_smoothing_, - -W_input_smoothing_ * *u_prev_); + input_smoothing_cost_->UpdateCoefficients( + W_input_smoothing_, -W_input_smoothing_ * *u_prev_, + 0.5 * u_prev_->transpose() * W_input_smoothing_ * *u_prev_); } -// if (w_input_smoothing_constraint_ < 1){ -// input_smoothing_constraint_->UpdateCoefficients( -// MatrixXd::Identity(n_u_, n_u_), *u_prev_ - w_input_smoothing_constraint_ * u_max_, -// *u_prev_ + w_input_smoothing_constraint_ * u_max_); -// } - if (W_lambda_c_reg_.size() > 0) { - lambda_c_smoothing_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, - VectorXd::Zero(n_c_)); + lambda_c_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, + VectorXd::Zero(n_c_)); } if (W_lambda_h_reg_.size() > 0) { - lambda_h_smoothing_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, - VectorXd::Zero(n_h_)); + lambda_h_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, + VectorXd::Zero(n_h_)); } if (!solvers_.at(0)->IsInitialized()) { @@ -820,55 +811,6 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); - // double window = 0.01; - // double tau = 0.005; - // double state_2_start = 0.2; - // double state_2_end = 0.3; - // double state_3_start = 0.5; - // double state_3_end = 0.6; - // if (fsm_state >= 2 && initial_guess_x_.size() == 4) { - // double clock_time; - // if (this->get_input_port(clock_port_).HasValue(context)) { - // auto clock = this->EvalVectorInput(context, clock_port_); - // clock_time = clock->get_value()(0); - // } - // if (fsm_state == 2) { - // double blend_in = 1 - exp(-((0.3 - clock_time) + window) / tau); - // double blend_out = 1 - exp(-((clock_time - 0.2) + window) / - // tau); double blend_in = (state_2_end - clock_time) / - // (state_2_end - state_2_start); double blend_out = 1 - - // (state_2_end - clock_time) / (state_2_end - state_2_start); - // u_sol_->row(6) = - // blend_out * u_sol_->row(6) + (1 - blend_out) * - // u_prev_[0].row(6); - // u_sol_->row(7) = - // blend_in * u_sol_->row(7) + (1 - blend_in) * - // u_prev_[1].row(7); - // u_sol_->row(0) = - // blend_out * u_sol_->row(0) + (1 - blend_out) * - // u_prev_[0].row(0); - // u_sol_->row(1) = - // blend_in * u_sol_->row(1) + (1 - blend_in) * - // u_prev_[1].row(1); - // } - // if (fsm_state == 3) { - // double blend_in = (state_3_end - clock_time) / (state_3_end - - // state_3_start); double blend_out = 1 - (state_3_end - - // clock_time) / (state_3_end - state_3_start); - // u_sol_->row(6) = - // blend_in * u_sol_->row(6) + (1 - blend_in) * - // u_prev_[0].row(6); - // u_sol_->row(7) = - // blend_out * u_sol_->row(7) + (1 - blend_out) * - // u_prev_[1].row(7); - // u_sol_->row(0) = - // blend_in * u_sol_->row(0) + (1 - blend_in) * - // u_prev_[0].row(0); - // u_sol_->row(1) = - // blend_out * u_sol_->row(1) + (1 - blend_out) * - // u_prev_[1].row(1); - // } - // } initial_guess_x_[fsm_state] = result.GetSolution(); initial_guess_y_[fsm_state] = result.get_solver_details().y; } else { @@ -883,7 +825,8 @@ VectorXd OperationalSpaceControl::SolveQp( } return *u_sol_; -} // namespace dairlib::systems::controllers +} + void OperationalSpaceControl::UpdateImpactInvariantProjection( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const Context& context, double t, double t_since_last_state_switch, @@ -981,7 +924,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( const Context& context, dairlib::lcmt_osc_output* output) const { auto state = (OutputVector*)this->EvalVectorInput(context, state_port_); - total_cost_ = 0; + double total_cost = 0; int fsm_state = -1; if (used_with_finite_state_machine_) { auto fsm_output = @@ -997,39 +940,52 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->utime = state->get_timestamp() * 1e6; output->fsm_state = fsm_state; - double input_cost = - (W_input_.size() > 0) - ? (0.5 * (*u_sol_).transpose() * W_input_ * (*u_sol_))(0) - : 0; - double acceleration_cost = - (W_joint_accel_.size() > 0) - ? (0.5 * (*dv_sol_).transpose() * W_joint_accel_ * (*dv_sol_))(0) - : 0; - double soft_constraint_cost = - (w_soft_constraint_ > 0) - ? (0.5 * w_soft_constraint_ * (*epsilon_sol_).transpose() * - (*epsilon_sol_))(0) - : 0; + VectorXd y_accel_cost = VectorXd::Zero(1); + VectorXd y_input_cost = VectorXd::Zero(1); + VectorXd y_input_smoothing_cost = VectorXd::Zero(1); + VectorXd y_lambda_c_cost = VectorXd::Zero(1); + VectorXd y_lambda_h_cost = VectorXd::Zero(1); + VectorXd y_soft_constraint_cost = VectorXd::Zero(1); + VectorXd y_joint_limit_cost = VectorXd::Zero(1); + if (accel_cost_) { + accel_cost_->Eval(*dv_sol_, &y_accel_cost); + } + if (input_cost_) { + input_cost_->Eval(*u_sol_, &y_input_cost); + } + if (input_smoothing_cost_) { + input_smoothing_cost_->Eval(*u_sol_, &y_input_smoothing_cost); + } + if (lambda_c_cost_) { + lambda_c_cost_->Eval(*lambda_c_sol_, &y_lambda_c_cost); + } + if (lambda_h_cost_) { + lambda_h_cost_->Eval(*lambda_h_sol_, &y_lambda_h_cost); + } + if (soft_constraint_cost_) { + soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); + } + if (joint_limit_cost_) { + joint_limit_cost_->Eval(*dv_sol_, &y_joint_limit_cost); + } + double acceleration_cost = (accel_cost_ != nullptr) ? y_accel_cost[0] : 0; + double input_cost = (input_cost_ != nullptr) ? y_input_cost[0] : 0; double input_smoothing_cost = - (W_input_smoothing_.size() > 0) - ? (0.5 * (*u_sol_ - *u_prev_).transpose() * W_input_smoothing_ * - (*u_sol_ - *u_prev_))(0) - : 0; - double lambda_h_cost = (W_lambda_h_reg_.size() > 0) - ? (0.5 * (*lambda_h_sol_).transpose() * - W_lambda_h_reg_ * (*lambda_h_sol_))(0) - : 0; - double lambda_c_cost = (W_lambda_c_reg_.size() > 0) - ? (0.5 * (*lambda_c_sol_).transpose() * - W_lambda_c_reg_ * (*lambda_c_sol_))(0) - : 0; - total_cost_ += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost; - soft_constraint_cost_ = soft_constraint_cost; + (input_smoothing_cost_ != nullptr) ? y_input_smoothing_cost[0] : 0; + double soft_constraint_cost = + (soft_constraint_cost_ != nullptr) ? y_soft_constraint_cost[0] : 0; + double lambda_c_cost = (lambda_c_cost_ != nullptr) ? y_lambda_c_cost[0] : 0; + double lambda_h_cost = (lambda_h_cost_ != nullptr) ? y_lambda_h_cost[0] : 0; + double joint_limit_cost = + (joint_limit_cost_ != nullptr) ? y_joint_limit_cost[0] : 0; + + total_cost += input_cost + acceleration_cost + soft_constraint_cost + + input_smoothing_cost + lambda_h_cost + lambda_c_cost + + joint_limit_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); - output->regularization_costs.reserve(4); + // output->regularization_costs.reserve(4); output->regularization_costs.push_back(input_cost); output->regularization_cost_names.push_back("input_cost"); output->regularization_costs.push_back(acceleration_cost); @@ -1042,6 +998,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->regularization_cost_names.push_back("lambda_c_cost"); output->regularization_costs.push_back(lambda_h_cost); output->regularization_cost_names.push_back("lambda_h_cost"); + output->regularization_costs.push_back(joint_limit_cost); + output->regularization_cost_names.push_back("joint_limit_cost"); output->tracking_data_names.clear(); output->tracking_data.clear(); @@ -1105,17 +1063,16 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command_sol = CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); - const VectorXd& ddy_t = tracking_data->GetYddotCommand(); - const MatrixXd& W = tracking_data->GetWeight(); - const MatrixXd& J_t = tracking_data->GetJ(); - const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); - output->tracking_costs[i] = - (0.5 * (J_t * (*dv_sol_) + JdotV_t - ddy_t).transpose() * W * - (J_t * (*dv_sol_) + JdotV_t - ddy_t))(0); - total_cost_ += output->tracking_costs[i]; + VectorXd y_tracking_cost = VectorXd::Zero(1); + tracking_costs_[i]->Eval(*dv_sol_, &y_tracking_cost); + output->tracking_costs[i] = y_tracking_cost[0]; + total_cost += output->tracking_costs[i]; } output->tracking_data[i] = osc_output; } +// output->regularization_costs.push_back(total_cost); +// output->regularization_cost_names.push_back("total_cost"); + *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); output->num_regularization_costs = output->regularization_cost_names.size(); @@ -1183,7 +1140,11 @@ void OperationalSpaceControl::CheckTracking( (OutputVector*)this->EvalVectorInput(context, state_port_); output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; - if (soft_constraint_cost_ > 5e3 || isnan(soft_constraint_cost_)) { + VectorXd y_soft_constraint_cost = VectorXd::Zero(1); + if (soft_constraint_cost_ != nullptr) { + soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); + } + if (y_soft_constraint_cost[0] > 5e3 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 59799e02fa..d900132b5d 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -1,14 +1,15 @@ #pragma once +#include #include #include #include #include #include -#include #include +#include "common/find_resource.h" #include "dairlib/lcmt_osc_output.hpp" #include "dairlib/lcmt_osc_qp_output.hpp" #include "multibody/kinematic/kinematic_evaluator_set.h" @@ -19,7 +20,6 @@ #include "systems/controllers/osc/osc_tracking_data.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" -#include "common/find_resource.h" #include "drake/common/trajectories/exponential_plus_piecewise_polynomial.h" #include "drake/common/trajectories/piecewise_polynomial.h" @@ -138,8 +138,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { } // Regularization cost weights - void AddInputCostByJointAndFsmState( - const std::string& joint_u_name, int fsm, double w); + void AddInputCostByJointAndFsmState(const std::string& joint_u_name, int fsm, + double w); void SetInputCostWeights(const Eigen::MatrixXd& W) { W_input_ = W; } void SetAccelerationCostWeights(const Eigen::MatrixXd& W) { W_joint_accel_ = W; @@ -159,6 +159,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void SetLambdaHolonomicRegularizationWeight(const Eigen::MatrixXd& W) { W_lambda_h_reg_ = W; } + void SetJointLimitWeight(const double w) { w_joint_limit_ = w; } // Constraint methods void DisableAcutationConstraint() { with_input_constraints_ = false; } @@ -173,11 +174,12 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { /// The third argument is used to set a period in which OSC does not track the /// desired traj (the period starts when the finite state machine switches to /// a new state) - void AddTrackingData(std::unique_ptr tracking_data, double t_lb = 0, + void AddTrackingData(std::unique_ptr tracking_data, + double t_lb = 0, double t_ub = std::numeric_limits::infinity()); void AddConstTrackingData( - std::unique_ptr tracking_data, const Eigen::VectorXd& v, double t_lb = 0, - double t_ub = std::numeric_limits::infinity()); + std::unique_ptr tracking_data, const Eigen::VectorXd& v, + double t_lb = 0, double t_ub = std::numeric_limits::infinity()); std::vector>* GetAllTrackingData() { return tracking_data_vec_.get(); } @@ -196,7 +198,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void SetOsqpSolverOptionsFromYaml(const std::string& yaml_string) { SetOsqpSolverOptions( drake::yaml::LoadYamlFile( - FindResourceOrThrow(yaml_string)).osqp_options); + FindResourceOrThrow(yaml_string)) + .osqp_options); }; // OSC LeafSystem builder void Build(); @@ -337,14 +340,17 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::LinearEqualityConstraint* dynamics_constraint_; drake::solvers::LinearEqualityConstraint* holonomic_constraint_; drake::solvers::LinearEqualityConstraint* contact_constraints_; - drake::solvers::BoundingBoxConstraint* input_smoothing_constraint_; +// drake::solvers::BoundingBoxConstraint* input_smoothing_constraint_; std::vector friction_constraints_; - std::vector tracking_cost_; + + std::vector tracking_costs_; + drake::solvers::QuadraticCost* accel_cost_; + drake::solvers::LinearCost* joint_limit_cost_; drake::solvers::QuadraticCost* input_cost_; - std::vector joint_limit_cost_; drake::solvers::QuadraticCost* input_smoothing_cost_; - drake::solvers::QuadraticCost* lambda_c_smoothing_cost_; - drake::solvers::QuadraticCost* lambda_h_smoothing_cost_; + drake::solvers::QuadraticCost* lambda_c_cost_; + drake::solvers::QuadraticCost* lambda_h_cost_; + drake::solvers::QuadraticCost* soft_constraint_cost_; // OSC solution std::unique_ptr dv_sol_; @@ -368,8 +374,10 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::MatrixXd W_lambda_c_reg_; Eigen::MatrixXd W_lambda_h_reg_; double w_input_smoothing_constraint_ = 1; - std::map> fsm_to_w_input_map_; // each pair is (joint index, weight) - + // Joint limit penalty + double w_joint_limit_ = 0; + std::map> + fsm_to_w_input_map_; // each pair is (joint index, weight) // OSC constraint members bool with_input_constraints_ = true; @@ -377,9 +385,6 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { double mu_ = -1; // Friction coefficients double w_soft_constraint_ = -1; - // Joint limit penalty - Eigen::VectorXd w_joint_limit_; - // Map finite state machine state to its active contact indices std::map> contact_indices_map_ = {}; // All contacts (used in contact constraints) @@ -389,7 +394,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { mutable std::unordered_map initial_guess_x_ = {}; mutable std::unordered_map initial_guess_y_ = {}; -// mutable std::unordered_map u_prev_ = {}; + // mutable std::unordered_map u_prev_ = {}; // OSC tracking data (stored as a pointer because of caching) std::unique_ptr>> @@ -414,11 +419,12 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { mutable double prev_distinct_fsm_state_ = -1; drake::solvers::LinearEqualityConstraint* blend_constraint_; drake::solvers::VectorXDecisionVariable epsilon_blend_; -// drake::solvers::BoundingBoxConstraint* contact_force_smoothing_constraint_; + // drake::solvers::BoundingBoxConstraint* + // contact_force_smoothing_constraint_; // Optional feature -- regularizing input - mutable double total_cost_ = 0; - mutable double soft_constraint_cost_ = 0; +// mutable double total_cost_ = 0; +// mutable double soft_constraint_cost_ = 0; }; } // namespace dairlib::systems::controllers From b9175a3f4f90b5ccf5f8ba667e0da2f13ae04472 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 23 Aug 2022 16:08:23 -0400 Subject: [PATCH 292/758] long jumping still not converging well --- .../Cassie/osc_jump/osc_jumping_gains.yaml | 8 +- .../Cassie/osc_run/osc_running_gains.yaml | 14 +- examples/Cassie/run_dircon_jumping.cc | 384 +++++++++--------- 3 files changed, 200 insertions(+), 206 deletions(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 1a5e2a84e6..470ce07747 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -15,7 +15,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.001 w_soft_constraint: 100 -x_offset: 0.06 +x_offset: 0.0 relative_feet: true mu: 0.4 @@ -30,7 +30,7 @@ hip_yaw_kd: 5 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.045 +landing_delay: 0.0 CoMW: [20, 0, 0, @@ -55,11 +55,11 @@ CoMKd: PelvisRotKp: [25, 0, 0, 0, 50, 0, - 0, 0, 0] + 0, 0, 50] PelvisRotKd: [5, 0, 0, 0, 10, 0, - 0, 0, 0] + 0, 0, 1] FlightFootKp: [100, 0, 0, 0, 100, 0, diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 41661dbf47..f7eba2605d 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -30,8 +30,8 @@ ekf_filter_tau: [ 0.001, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -2 -vel_scale_trans_sagital: 0.5 -vel_scale_trans_lateral: -0.0 +vel_scale_trans_sagital: 0.2 +vel_scale_trans_lateral: -0.1 # SLIP parameters rest_length: 0.85 @@ -49,9 +49,9 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 #footstep_sagital_offset: -0.06 -footstep_sagital_offset: -0.05 +footstep_sagital_offset: -0.02 footstep_lateral_offset: 0.02 # drake -mid_foot_height: 0.05 +mid_foot_height: 0.15 FootstepKd: [ 0.17, 0, 0, 0, 0.4, 0, @@ -71,15 +71,15 @@ PelvisKd: PelvisRotW: [1, 0, 0, 0, 2.5, 0, - 0, 0, 0.1] + 0, 0, 1] PelvisRotKp: - [50., 0, 0, + [25., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: [0.1, 0, 0, 0, 2., 0, - 0, 0, 1.] + 0, 0, 5.] SwingFootW: [1, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index f8b956958f..922c7a7946 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -91,39 +91,38 @@ DEFINE_bool(same_knotpoints, false, "Set flag to true if seeding with a trajectory with the same " "number of knotpoints"); DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); -DEFINE_double(actuator_limit, - 1.0, - "Conservative estimate scaling factor for actuator limits, 1.0 is at the actual actuator limits."); -DEFINE_double(input_delta, - 50.0, +DEFINE_double(actuator_limit, 1.0, + "Conservative estimate scaling factor for actuator limits, 1.0 " + "is at the actual actuator limits."); +DEFINE_double(input_delta, 50.0, "Maximum change in torques between knot points."); namespace dairlib { -HybridDircon *createDircon(MultibodyPlant &plant); +HybridDircon* createDircon(MultibodyPlant& plant); -void SetKinematicConstraints(Dircon *trajopt, - const MultibodyPlant &plant); -void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, - DirconModeSequence *); -void AddCostsSprings(Dircon *trajopt, - const MultibodyPlant &plant, - DirconModeSequence *); +void SetKinematicConstraints(Dircon* trajopt, + const MultibodyPlant& plant); +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence*); +void AddCostsSprings(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence*); void SetInitialGuessFromTrajectory( - Dircon &trajopt, const MultibodyPlant &plant, - const string &filepath, bool same_knot_points = false, + Dircon& trajopt, const MultibodyPlant& plant, + const string& filepath, bool same_knot_points = false, Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); class JointAccelCost : public solvers::NonlinearCost { public: - JointAccelCost(const MatrixXd &W_Q, - const drake::multibody::MultibodyPlant &plant, - const KinematicEvaluatorSet *constraints, - const std::string &description = "") + JointAccelCost(const MatrixXd& W_Q, + const drake::multibody::MultibodyPlant& plant, + const KinematicEvaluatorSet* constraints, + const std::string& description = "") : solvers::NonlinearCost( - plant.num_positions() + plant.num_velocities() + - plant.num_actuators() + constraints->count_full(), - description), + plant.num_positions() + plant.num_velocities() + + plant.num_actuators() + constraints->count_full(), + description), plant_(plant), context_(plant_.CreateDefaultContext()), constraints_(constraints), @@ -131,11 +130,11 @@ class JointAccelCost : public solvers::NonlinearCost { n_x_(plant.num_positions() + plant.num_velocities()), n_u_(plant.num_actuators()), n_lambda_(constraints->count_full()), - W_Q_(W_Q) {}; + W_Q_(W_Q){}; private: - void EvaluateCost(const Eigen::Ref> &x, - drake::VectorX *y) const override { + void EvaluateCost(const Eigen::Ref>& x, + drake::VectorX* y) const override { DRAKE_ASSERT(x.size() == n_x_ + n_u_ + n_lambda_); // Extract our input variables: @@ -150,9 +149,9 @@ class JointAccelCost : public solvers::NonlinearCost { (*y) = xdot0.tail(n_v_).transpose() * W_Q_ * xdot0.tail(n_v_); }; - const drake::multibody::MultibodyPlant &plant_; + const drake::multibody::MultibodyPlant& plant_; std::unique_ptr> context_; - const KinematicEvaluatorSet *constraints_; + const KinematicEvaluatorSet* constraints_; int n_v_; int n_x_; @@ -165,7 +164,7 @@ class JointAccelCost : public solvers::NonlinearCost { void DoMain() { // Drake system initialization stuff drake::systems::DiagramBuilder builder; - SceneGraph &scene_graph = *builder.AddSystem(); + SceneGraph& scene_graph = *builder.AddSystem(); scene_graph.set_name("scene_graph"); MultibodyPlant plant(0.0); MultibodyPlant plant_vis(0.0); @@ -269,9 +268,9 @@ void DoMain() { // auto land_mode = DirconMode(double_stance_constraints, // stance_knotpoints, 0.4, 0.6); auto crouch_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.0, 1.0); + stance_knotpoints, 0.5, 1.0); auto flight_mode = DirconMode(flight_phase_constraints, - flight_phase_knotpoints, 0.0, 1.0); + flight_phase_knotpoints, 0.2, 2.0); auto land_mode = DirconMode(double_stance_constraints, stance_knotpoints, 0.4, 1.0); @@ -286,16 +285,16 @@ void DoMain() { land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); land_mode.MakeConstraintRelative(left_toe_eval_ind, 1); -// land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); + // land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); land_mode.MakeConstraintRelative(left_heel_eval_ind, 0); land_mode.MakeConstraintRelative(left_heel_eval_ind, 1); -// land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); + // land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); land_mode.MakeConstraintRelative(right_toe_eval_ind, 0); land_mode.MakeConstraintRelative(right_toe_eval_ind, 1); -// land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); + // land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); land_mode.MakeConstraintRelative(right_heel_eval_ind, 0); land_mode.MakeConstraintRelative(right_heel_eval_ind, 1); -// land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); + // land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); auto all_modes = DirconModeSequence(plant); all_modes.AddMode(&crouch_mode); @@ -303,7 +302,7 @@ void DoMain() { all_modes.AddMode(&land_mode); auto trajopt = Dircon(all_modes); - auto &prog = trajopt.prog(); + auto& prog = trajopt.prog(); double tol = FLAGS_tol; if (FLAGS_ipopt) { @@ -346,8 +345,8 @@ void DoMain() { // target nonlinear constraint violation prog.SetSolverOption(id, "Major optimality tolerance", 1e-5 / FLAGS_cost_scaling); -// prog.SetSolverOption(id, "Major optimality tolerance", -// 1e-5); + // prog.SetSolverOption(id, "Major optimality tolerance", + // 1e-5); // target complementarity gap prog.SetSolverOption(id, "Major feasibility tolerance", tol); @@ -356,11 +355,12 @@ void DoMain() { std::cout << "Adding kinematic constraints: " << std::endl; SetKinematicConstraints(&trajopt, plant); std::cout << "Adding costs: " << std::endl; - if (FLAGS_use_springs) { - AddCostsSprings(&trajopt, plant, &all_modes); - } else { - AddCosts(&trajopt, plant, &all_modes); - } +// if (FLAGS_use_springs) { +// AddCostsSprings(&trajopt, plant, &all_modes); +// } else { +// AddCosts(&trajopt, plant, &all_modes); +// } + AddCosts(&trajopt, plant, &all_modes); std::cout << "Setting initial conditions: " << std::endl; vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; @@ -380,9 +380,9 @@ void DoMain() { } double alpha = .2; -// int num_poses = std::min(FLAGS_knot_points + 1, 3); - int num_poses = std::max((int) (mode_lengths.size() + 1), FLAGS_knot_points); -// int num_poses = mode_lengths.size() * FLAGS_knot_points - 1; + // int num_poses = std::min(FLAGS_knot_points + 1, 3); + int num_poses = std::max((int)(mode_lengths.size() + 1), FLAGS_knot_points); + // int num_poses = mode_lengths.size() * FLAGS_knot_points - 1; trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); cout << "\nChoose the best solver: " @@ -419,9 +419,9 @@ void DoMain() { } } -void SetKinematicConstraints(Dircon *trajopt, - const MultibodyPlant &plant) { - auto *prog = &trajopt->prog(); +void SetKinematicConstraints(Dircon* trajopt, + const MultibodyPlant& plant) { + auto* prog = &trajopt->prog(); // Create maps for joints map pos_map = multibody::MakeNameToPositionsMap(plant); map vel_map = multibody::MakeNameToVelocitiesMap(plant); @@ -475,10 +475,10 @@ void SetKinematicConstraints(Dircon *trajopt, prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_right"))); -// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_0(pos_map.at("toe_left"))); -// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_0(pos_map.at("toe_right"))); -// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_left"))); -// prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_right"))); + // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_0(pos_map.at("toe_left"))); + // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_0(pos_map.at("toe_right"))); + // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_left"))); + // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_right"))); trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_left"))); trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_right"))); @@ -493,16 +493,16 @@ void SetKinematicConstraints(Dircon *trajopt, // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); -// if (FLAGS_height < 0) { -// prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, -// 0.5 * FLAGS_height + rest_height - eps, -// x_top(pos_map.at("base_z"))); -// -// } else { -// prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, -// FLAGS_height + rest_height + eps, -// x_top(pos_map.at("base_z"))); -// } + // if (FLAGS_height < 0) { + // prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, + // 0.5 * FLAGS_height + rest_height - eps, + // x_top(pos_map.at("base_z"))); + // + // } else { + // prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, + // FLAGS_height + rest_height + eps, + // x_top(pos_map.at("base_z"))); + // } prog->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, 0.8 * FLAGS_height + rest_height + eps, x_f(pos_map.at("base_z"))); @@ -527,19 +527,19 @@ void SetKinematicConstraints(Dircon *trajopt, vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; - for (const auto &l_r_pair: l_r_pairs) { - for (const auto &asy_joint_name: asy_joint_names) { + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { joint_names.push_back(asy_joint_name + l_r_pair.first); motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); } - for (const auto &sym_joint_name: sym_joint_names) { + for (const auto& sym_joint_name : sym_joint_names) { joint_names.push_back(sym_joint_name + l_r_pair.first); if (sym_joint_name != "ankle_joint") { motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); } } if (FLAGS_use_springs) { - for (const auto &spring_joint_name: spring_joint_names) { + for (const auto& spring_joint_name : spring_joint_names) { joint_names.push_back(spring_joint_name + l_r_pair.first); } } @@ -547,41 +547,43 @@ void SetKinematicConstraints(Dircon *trajopt, l_r_pairs.pop_back(); // Symmetry constraints - for (const auto &l_r_pair: l_r_pairs) { - for (const auto &sym_joint_name: sym_joint_names) { + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { // trajopt->AddConstraintToAllKnotPoints( // x_0(pos_map[sym_joint_name + l_r_pair.first]) == // x_0(pos_map[sym_joint_name + l_r_pair.second])); -// prog->AddLinearConstraint(x_0(pos_map[sym_joint_name + l_r_pair.first]) == -// x_0(pos_map[sym_joint_name + l_r_pair.second])); -// prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + l_r_pair.first]) == -// x_f(pos_map[sym_joint_name + l_r_pair.second])); + // prog->AddLinearConstraint(x_0(pos_map[sym_joint_name + + // l_r_pair.first]) == + // x_0(pos_map[sym_joint_name + l_r_pair.second])); + // prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + + // l_r_pair.first]) == + // x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle - trajopt->AddConstraintToAllKnotPoints( - u[act_map.at(sym_joint_name + l_r_pair.first + - "_motor")] - u[act_map.at(sym_joint_name + - l_r_pair.second + "_motor")] <= 10); - trajopt->AddConstraintToAllKnotPoints( - u[act_map.at(sym_joint_name + l_r_pair.first + - "_motor")] - u[act_map.at(sym_joint_name + - l_r_pair.second + "_motor")] >= -10); -// prog->AddConstraint( -// u_f(act_map.at(sym_joint_name + l_r_pair.first + -// "_motor")) == u_f(act_map.at(sym_joint_name + -// l_r_pair.second + "_motor"))); +// trajopt->AddConstraintToAllKnotPoints( +// u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] - +// u[act_map.at(sym_joint_name + l_r_pair.second + "_motor")] <= +// 10); +// trajopt->AddConstraintToAllKnotPoints( +// u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] - +// u[act_map.at(sym_joint_name + l_r_pair.second + "_motor")] >= +// -10); + // prog->AddConstraint( + // u_f(act_map.at(sym_joint_name + l_r_pair.first + + // "_motor")) == u_f(act_map.at(sym_joint_name + + // l_r_pair.second + "_motor"))); } } } // joint limits std::cout << "Joint limit constraints: " << std::endl; - for (const auto &member: joint_names) { + for (const auto& member : joint_names) { trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) <= - 0.9 * plant.GetJointByName(member).position_upper_limits()(0)); + plant.GetJointByName(member).position_upper_limits()(0)); trajopt->AddConstraintToAllKnotPoints( x(pos_map.at(member)) >= - 0.9 * plant.GetJointByName(member).position_lower_limits()(0)); + plant.GetJointByName(member).position_lower_limits()(0)); } // actuator limits std::cout << "Actuator limit constraints: " << std::endl; @@ -595,15 +597,15 @@ void SetKinematicConstraints(Dircon *trajopt, } for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); - // prog->AddBoundingBoxConstraint(VectorXd::Constant(n_u, -175), - // VectorXd::Constant(n_u, +175), ui); prog->AddBoundingBoxConstraint(u_min, u_max, ui); if (i < trajopt->N() - 1) { auto uip1 = trajopt->input(i + 1); -// prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); -// prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); - prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, FLAGS_input_delta)); - prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -FLAGS_input_delta)); + // prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); + // prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); + prog->AddConstraint(ui - uip1 <= + VectorXd::Constant(n_u, FLAGS_input_delta)); + prog->AddConstraint(ui - uip1 >= + VectorXd::Constant(n_u, -FLAGS_input_delta)); } } @@ -629,7 +631,7 @@ void SetKinematicConstraints(Dircon *trajopt, plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); - for (int mode: {0, 1, 2}) { + for (int mode : {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); @@ -726,13 +728,13 @@ void SetKinematicConstraints(Dircon *trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground -// for (int index = 0; index < (mode_lengths[0] - 2); index++) { -// auto lambda = trajopt->force_vars(0, index); -// prog->AddLinearConstraint(lambda(2) >= 60); -// prog->AddLinearConstraint(lambda(5) >= 60); -// prog->AddLinearConstraint(lambda(8) >= 60); -// prog->AddLinearConstraint(lambda(11) >= 60); -// } + // for (int index = 0; index < (mode_lengths[0] - 2); index++) { + // auto lambda = trajopt->force_vars(0, index); + // prog->AddLinearConstraint(lambda(2) >= 60); + // prog->AddLinearConstraint(lambda(5) >= 60); + // prog->AddLinearConstraint(lambda(8) >= 60); + // prog->AddLinearConstraint(lambda(11) >= 60); + // } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); @@ -740,18 +742,18 @@ void SetKinematicConstraints(Dircon *trajopt, prog->AddLinearConstraint(lambda(5) <= FLAGS_input_delta * 350); prog->AddLinearConstraint(lambda(8) <= FLAGS_input_delta * 350); prog->AddLinearConstraint(lambda(11) <= FLAGS_input_delta * 350); -// prog->AddLinearConstraint(lambda(2) >= 50); -// prog->AddLinearConstraint(lambda(5) >= 50); -// prog->AddLinearConstraint(lambda(8) >= 50); -// prog->AddLinearConstraint(lambda(11) >= 50); + // prog->AddLinearConstraint(lambda(2) >= 50); + // prog->AddLinearConstraint(lambda(5) >= 50); + // prog->AddLinearConstraint(lambda(8) >= 50); + // prog->AddLinearConstraint(lambda(11) >= 50); } } /****** COSTS ******/ -void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, - DirconModeSequence *constraints) { +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence* constraints) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -775,12 +777,12 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; - for (const auto &l_r_pair: l_r_pairs) { - for (const auto &asy_joint_name: asy_joint_names) { + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { joint_names.push_back(asy_joint_name + l_r_pair.first); motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); } - for (const auto &sym_joint_name: sym_joint_names) { + for (const auto& sym_joint_name : sym_joint_names) { joint_names.push_back(sym_joint_name + l_r_pair.first); if (sym_joint_name != "ankle_joint") { motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); @@ -789,49 +791,45 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, } l_r_pairs.pop_back(); - double w_symmetry_pos = FLAGS_cost_scaling * 1e5; - double w_symmetry_vel = FLAGS_cost_scaling * 1e2; - double w_symmetry_u = FLAGS_cost_scaling * 1e2; - for (const auto &l_r_pair: l_r_pairs) { - for (const auto &sym_joint_name: sym_joint_names) { - auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - - x(pos_map.at(sym_joint_name + l_r_pair.second)); - auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - - - x(vel_map.at(sym_joint_name + l_r_pair.second + - "dot")); - trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - if (sym_joint_name != "ankle_joint") { - auto act_diff = - u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); - trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } - } - } - for (const auto& l_r_pair : l_r_pairs) { - for (const auto &asy_joint_name: asy_joint_names) { - auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + - x(pos_map.at(asy_joint_name + l_r_pair.second)); - auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) - + - x(vel_map.at(asy_joint_name + l_r_pair.second + - "dot")); - trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - if (asy_joint_name != "ankle_joint") { - auto act_diff = - u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); - trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } - } - } +// double w_symmetry_pos = FLAGS_cost_scaling * 1e5; +// double w_symmetry_vel = FLAGS_cost_scaling * 1e2; +// double w_symmetry_u = FLAGS_cost_scaling * 1e2; +// for (const auto& l_r_pair : l_r_pairs) { +// for (const auto& sym_joint_name : sym_joint_names) { +// auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - +// x(pos_map.at(sym_joint_name + l_r_pair.second)); +// auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - +// x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); +// trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); +// trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); +// if (sym_joint_name != "ankle_joint") { +// auto act_diff = +// u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - +// u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); +// trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); +// } +// } +// } +// for (const auto& l_r_pair : l_r_pairs) { +// for (const auto& asy_joint_name : asy_joint_names) { +// auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + +// x(pos_map.at(asy_joint_name + l_r_pair.second)); +// auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + +// x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); +// trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); +// trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); +// if (asy_joint_name != "ankle_joint") { +// auto act_diff = +// u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + +// u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); +// trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); +// } +// } +// } - MatrixXd Q = 0.02 * MatrixXd::Identity(n_v, n_v); -// MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); - MatrixXd R = 1e1 * MatrixXd::Identity(n_u, n_u); + MatrixXd Q = FLAGS_cost_scaling * 0.02 * MatrixXd::Identity(n_v, n_v); + // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); + MatrixXd R = FLAGS_cost_scaling * 1e-1 * MatrixXd::Identity(n_u, n_u); // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = // 5e-1; // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) @@ -848,8 +846,6 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, // act_map.at("hip_pitch_right_motor")) = // 5e-5; - Q *= FLAGS_cost_scaling; - R *= FLAGS_cost_scaling; trajopt->AddRunningCost(x.tail(n_v - 3).transpose() * Q * x.tail(n_v - 3)); VectorXd q_f = VectorXd::Zero(n_q); // VectorXd quat_identity(4); @@ -865,48 +861,46 @@ void AddCosts(Dircon *trajopt, const MultibodyPlant &plant, VectorXd q_f_target_left = q_f.segment(6, 4); VectorXd q_f_target_right = q_f.segment(13, 3); - MatrixXd Q_left = 1e1 * MatrixXd::Identity(4, 4); - MatrixXd Q_right = 1e1 * MatrixXd::Identity(3, 3); - Q_left *= FLAGS_cost_scaling; - Q_right *= FLAGS_cost_scaling; + MatrixXd Q_left = FLAGS_cost_scaling * MatrixXd::Identity(4, 4); + MatrixXd Q_right = FLAGS_cost_scaling * MatrixXd::Identity(3, 3); trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); trajopt->AddRunningCost((x.segment(6, 4) - q_f_target_left).transpose() * - Q_left * (x.segment(6, 4) - q_f_target_left)); + Q_left * (x.segment(6, 4) - q_f_target_left)); trajopt->AddRunningCost((x.segment(13, 3) - q_f_target_right).transpose() * - Q_right * (x.segment(13, 3) - q_f_target_right)); + Q_right * (x.segment(13, 3) - q_f_target_right)); trajopt->AddRunningCost(u.transpose() * R * u); vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; - MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); - W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; - W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; - W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; - W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; - W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; - W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; - W *= 2.0 * FLAGS_cost_scaling; - vector> joint_accel_costs; - for (int mode: {0, 1, 2}) { - joint_accel_costs.push_back(std::make_shared( - W, plant, &constraints->mode(mode).evaluators())); - for (int index = 0; index < mode_lengths[mode]; index++) { - // Assumes mode_lengths are the same across modes - auto x_i = trajopt->state_vars(mode, index); - auto u_i = trajopt->input_vars(mode, index); - auto l_i = trajopt->force_vars(mode, index); - trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - } - } +// MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); +// W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; +// W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; +// W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; +// W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; +// W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; +// W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; +// W *= 2.0 * FLAGS_cost_scaling; +// vector> joint_accel_costs; +// for (int mode : {0, 1, 2}) { +// joint_accel_costs.push_back(std::make_shared( +// W, plant, &constraints->mode(mode).evaluators())); +// for (int index = 0; index < mode_lengths[mode]; index++) { +// // Assumes mode_lengths are the same across modes +// auto x_i = trajopt->state_vars(mode, index); +// auto u_i = trajopt->input_vars(mode, index); +// auto l_i = trajopt->force_vars(mode, index); +// trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); +// } +// } } /****** COSTS ******/ -void AddCostsSprings(Dircon *trajopt, - const MultibodyPlant &plant, - DirconModeSequence *constraints) { +void AddCostsSprings(Dircon* trajopt, + const MultibodyPlant& plant, + DirconModeSequence* constraints) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -929,12 +923,12 @@ void AddCostsSprings(Dircon *trajopt, vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; vector joint_names{}; vector motor_names{}; - for (const auto &l_r_pair: l_r_pairs) { - for (const auto &asy_joint_name: asy_joint_names) { + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { joint_names.push_back(asy_joint_name + l_r_pair.first); motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); } - for (const auto &sym_joint_name: sym_joint_names) { + for (const auto& sym_joint_name : sym_joint_names) { joint_names.push_back(sym_joint_name + l_r_pair.first); if (sym_joint_name != "ankle_joint") { motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); @@ -945,12 +939,12 @@ void AddCostsSprings(Dircon *trajopt, double w_symmetry_pos = 1e3; double w_symmetry_vel = 1e1; - for (const auto &l_r_pair: l_r_pairs) { - for (const auto &sym_joint_name: sym_joint_names) { + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - - x(pos_map[sym_joint_name + l_r_pair.second]); + x(pos_map[sym_joint_name + l_r_pair.second]); auto vel_diff = x(vel_map[sym_joint_name + l_r_pair.first + "dot"]) - - x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); + x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); } @@ -981,7 +975,7 @@ void AddCostsSprings(Dircon *trajopt, vel_map["ankle_spring_joint_rightdot"]) = 0.0; W *= FLAGS_cost_scaling; vector> joint_accel_costs; - for (int mode: {0, 1, 2}) { + for (int mode : {0, 1, 2}) { joint_accel_costs.push_back(std::make_shared( W, plant, &constraints->mode(mode).evaluators())); for (int index = 0; index < mode_lengths[mode]; index++) { @@ -994,9 +988,9 @@ void AddCostsSprings(Dircon *trajopt, } } -void SetInitialGuessFromTrajectory(Dircon &trajopt, - const MultibodyPlant &plant, - const string &filepath, +void SetInitialGuessFromTrajectory(Dircon& trajopt, + const MultibodyPlant& plant, + const string& filepath, bool same_knot_points, Eigen::MatrixXd spr_map) { DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); @@ -1027,7 +1021,7 @@ void SetInitialGuessFromTrajectory(Dircon &trajopt, } // namespace dairlib -int main(int argc, char *argv[]) { +int main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); dairlib::DoMain(); } From 0b7dc871ade8fd43131d8e9b406dfdb8a8cb860e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 25 Aug 2022 11:37:34 -0400 Subject: [PATCH 293/758] rewriting standing controller --- examples/Cassie/osc/osc_standing_gains.h | 56 ++-- examples/Cassie/osc/osc_standing_gains.yaml | 60 ++-- examples/Cassie/osc/standing_com_traj.cc | 100 ++++--- .../Cassie/osc_run/osc_running_gains.yaml | 34 ++- examples/Cassie/run_dircon_jumping.cc | 268 ++++++++++-------- .../Cassie/run_osc_standing_controller.cc | 59 ++-- .../Cassie/urdf/cassie_v2_conservative.urdf | 2 - .../osc/operational_space_control.cc | 16 +- 8 files changed, 319 insertions(+), 276 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h index ca5a711d7f..938d420a24 100644 --- a/examples/Cassie/osc/osc_standing_gains.h +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -15,21 +15,22 @@ struct OSCStandingGains : OSCGains { double HipYawKd; double HipYawW; double center_of_mass_filter_tau; - std::vector CoMKp; - std::vector CoMKd; + double rot_filter_tau; + std::vector PelvisW; + std::vector PelvisKp; + std::vector PelvisKd; + std::vector PelvisRotW; std::vector PelvisRotKp; std::vector PelvisRotKd; - std::vector CoMW; - std::vector PelvisW; - MatrixXd K_p_com; - MatrixXd K_d_com; + MatrixXd W_pelvis; MatrixXd K_p_pelvis; MatrixXd K_d_pelvis; + MatrixXd W_pelvis_rot; + MatrixXd K_p_pelvis_rot; + MatrixXd K_d_pelvis_rot; MatrixXd K_p_hip_yaw; MatrixXd K_d_hip_yaw; - MatrixXd W_com; - MatrixXd W_pelvis; MatrixXd W_hip_yaw; template @@ -38,37 +39,38 @@ struct OSCStandingGains : OSCGains { a->Visit(DRAKE_NVP(weight_scaling)); a->Visit(DRAKE_NVP(rows)); a->Visit(DRAKE_NVP(cols)); - a->Visit(DRAKE_NVP(CoMKp)); - a->Visit(DRAKE_NVP(CoMKd)); + a->Visit(DRAKE_NVP(PelvisW)); + a->Visit(DRAKE_NVP(PelvisKp)); + a->Visit(DRAKE_NVP(PelvisKd)); + a->Visit(DRAKE_NVP(PelvisRotW)); a->Visit(DRAKE_NVP(PelvisRotKp)); a->Visit(DRAKE_NVP(PelvisRotKd)); a->Visit(DRAKE_NVP(HipYawKp)); a->Visit(DRAKE_NVP(HipYawKd)); - a->Visit(DRAKE_NVP(CoMW)); - a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(HipYawW)); a->Visit(DRAKE_NVP(center_of_mass_filter_tau)); + a->Visit(DRAKE_NVP(rot_filter_tau)); - K_p_com = Eigen::Map< - Eigen::Matrix>( - CoMKp.data(), rows, cols); - K_d_com = Eigen::Map< + W_pelvis = Eigen::Map< Eigen::Matrix>( - CoMKd.data(), rows, cols); + this->PelvisW.data(), 3, 3); K_p_pelvis = Eigen::Map< Eigen::Matrix>( - PelvisRotKp.data(), rows, cols); + this->PelvisKp.data(), 3, 3); K_d_pelvis = Eigen::Map< Eigen::Matrix>( - PelvisRotKd.data(), rows, cols); - K_p_hip_yaw = HipYawKp * MatrixXd::Identity(1, 1); - K_d_hip_yaw = HipYawKd * MatrixXd::Identity(1, 1); - W_com = Eigen::Map< + this->PelvisKd.data(), 3, 3); + W_pelvis_rot = Eigen::Map< Eigen::Matrix>( - CoMW.data(), rows, cols); - W_pelvis = Eigen::Map< + this->PelvisRotW.data(), 3, 3); + K_p_pelvis_rot = Eigen::Map< Eigen::Matrix>( - PelvisW.data(), rows, cols); + this->PelvisRotKp.data(), 3, 3); + K_d_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKd.data(), 3, 3); + K_p_hip_yaw = HipYawKp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = HipYawKd * MatrixXd::Identity(1, 1); W_hip_yaw = HipYawW * MatrixXd::Identity(1, 1); @@ -77,8 +79,8 @@ struct OSCStandingGains : OSCGains { w_input_reg *= weight_scaling; w_lambda *= weight_scaling; w_soft_constraint *= weight_scaling; + W_pelvis_rot *= weight_scaling; W_pelvis *= weight_scaling; - W_com *= weight_scaling; - W_hip_yaw *= weight_scaling; + W_pelvis_rot *= weight_scaling; W_hip_yaw *= weight_scaling; } }; diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 1d4ded8ccf..4a7fb570c1 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -1,4 +1,3 @@ - # Set xy PD gains so they do not effect passive LIPM dynamics at capture # point, when x = sqrt(l/g) * xdot # Passive dynamics: xddot = g/l * x @@ -9,8 +8,8 @@ rows: 3 cols: 3 -w_input: 0.00001 -w_accel: 0.0000001 +w_input: 0.0 +w_accel: 0.1 w_lambda: 0.000001 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, @@ -18,7 +17,7 @@ w_lambda: 0.000001 W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] -W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, +W_input_reg: [ 1, 0.9, 0.6, 0.3, 5, 1, 0.9, 0.5, 0.1, 5 ] W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, @@ -27,39 +26,40 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, #W_lambda_h_reg: [ 0.02, 0.02 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] -w_soft_constraint: 0 -w_input_reg: 0.0001 +w_soft_constraint: 100 +w_input_reg: 0.00 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.005 +center_of_mass_filter_tau: 0.01 +rot_filter_tau: 0.01 impact_tau: 0.00 mu: 0.6 weight_scaling: 1.0 -HipYawKp: 10 -HipYawKd: 1 -HipYawW: 1 -CoMW: - [ 20, 0, 0, - 0, 20, 0, - 0, 0, 20 ] +HipYawKp: 40 +HipYawKd: 5 +HipYawW: 0 PelvisW: - [ 0.1, 0, 0, - 0, 0.1, 0, - 0, 0, 0.1 ] -CoMKp: - [ 20, 0, 0, - 0, 20, 0, - 0, 0, 50 ] -CoMKd: - [ 1, 0, 0, - 0, 0.1, 0, - 0, 0, 4] + [20, 0, 0, + 0, 2, 0, + 0, 0, 20] +PelvisKp: + [100, 0, 0, + 0, 50, 0, + 0, 0, 50] +PelvisKd: + [ 15, 0, 0, + 0, 5, 0, + 0, 0, 10] +PelvisRotW: + [5, 0, 0, + 0, 5, 0, + 0, 0, 1] PelvisRotKp: - [10, 0, 0, - 0, 30, 0, - 0, 0, 5] + [25, 0, 0, + 0, 50, 0, + 0, 0, 50] PelvisRotKd: - [0.1, 0, 0, - 0, 0.1, 0, + [0.1, 0, 0, + 0, 10, 0, 0, 0, 1] diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index 7a26b62f73..46db82130d 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -34,23 +34,21 @@ StandingComTraj::StandingComTraj( world_(plant_.world_frame()), feet_contact_points_(feet_contact_points), height_(height), - set_target_height_by_radio_(set_target_height_by_radio){ + set_target_height_by_radio_(set_target_height_by_radio) { // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); + .get_index(); target_height_port_ = this->DeclareAbstractInputPort( "lcmt_target_standing_height", drake::Value{}) .get_index(); - radio_port_ = - this->DeclareAbstractInputPort("radio_out", - drake::Value{}) - .get_index(); + radio_port_ = this->DeclareAbstractInputPort( + "radio_out", drake::Value{}) + .get_index(); // Provide an instance to allocate the memory first (for the output) PiecewisePolynomial pp(VectorXd(0)); drake::trajectories::Trajectory& traj_inst = pp; @@ -67,17 +65,20 @@ void StandingComTraj::CalcDesiredTraj( const auto& radio_out = this->EvalInputValue(context, radio_port_); - double target_height = height_; // Get target height from radio or lcm if (set_target_height_by_radio_) { - target_height = kTargetHeightMean + kTargetHeightScale * radio_out->channel[6]; + target_height = + kTargetHeightMean + kTargetHeightScale * radio_out->channel[6]; } else { if (this->EvalInputValue( - context, target_height_port_)->timestamp > 1e-3) { - target_height = this->EvalInputValue( - context, target_height_port_)->target_height; + context, target_height_port_) + ->timestamp > 1e-3) { + target_height = + this->EvalInputValue( + context, target_height_port_) + ->target_height; } } @@ -93,35 +94,56 @@ void StandingComTraj::CalcDesiredTraj( multibody::SetPositionsIfNew(plant_, q, context_); // Get center of left/right feet contact points positions - Vector3d contact_pos_sum = Vector3d::Zero(); - Vector3d position; - MatrixXd J(3, plant_.num_velocities()); - for (const auto& point_and_frame : feet_contact_points_) { - plant_.CalcPointsPositions(*context_, point_and_frame.second, - point_and_frame.first, world_, &position); - contact_pos_sum += position; - } - Vector3d feet_center_pos = contact_pos_sum / 4; + // Vector3d contact_pos_sum = Vector3d::Zero(); + Vector3d left_toe_position; + Vector3d left_heel_position; + Vector3d right_toe_position; + Vector3d right_heel_position; + // MatrixXd J(3, plant_.num_velocities()); + // for (const auto& point_and_frame : feet_contact_points_) { + // for (const auto& point_and_frame : feet_contact_points_) { + plant_.CalcPointsPositions(*context_, feet_contact_points_[0].second, + feet_contact_points_[0].first, world_, + &left_toe_position); + plant_.CalcPointsPositions(*context_, feet_contact_points_[1].second, + feet_contact_points_[1].first, world_, + &left_heel_position); + plant_.CalcPointsPositions(*context_, feet_contact_points_[2].second, + feet_contact_points_[2].first, world_, + &right_toe_position); + plant_.CalcPointsPositions(*context_, feet_contact_points_[3].second, + feet_contact_points_[3].first, world_, + &right_heel_position); + Vector3d contact_pos_sum = (left_toe_position + left_heel_position + + right_toe_position + right_heel_position) / + 4; + // } + double mid_point_x = ((left_toe_position[0] - left_heel_position[0]) + + (right_toe_position[0] - right_heel_position[0])) / + 2; + double mid_point_y = ((left_toe_position[1] - right_toe_position[1]) + + (left_heel_position[1] - right_heel_position[1])) / + 4; + // Vector3d feet_center_pos = contact_pos_sum / 4; // Testing -- filtering feet_center_pos - if (filtered_feet_center_pos_.norm() == 0) { - // Initialize - filtered_feet_center_pos_ = feet_center_pos; - } - if (robot_output->get_timestamp() != last_timestamp_) { - double dt = robot_output->get_timestamp() - last_timestamp_; - last_timestamp_ = robot_output->get_timestamp(); - double alpha = - 2 * M_PI * dt * cutoff_freq_ / (2 * M_PI * dt * cutoff_freq_ + 1); - filtered_feet_center_pos_ = - alpha * feet_center_pos + (1 - alpha) * filtered_feet_center_pos_; - } - feet_center_pos = filtered_feet_center_pos_; + // if (filtered_feet_center_pos_.norm() == 0) { + // // Initialize + // filtered_feet_center_pos_ = feet_center_pos; + // } + // if (robot_output->get_timestamp() != last_timestamp_) { + // double dt = robot_output->get_timestamp() - last_timestamp_; + // last_timestamp_ = robot_output->get_timestamp(); + // double alpha = + // 2 * M_PI * dt * cutoff_freq_ / (2 * M_PI * dt * cutoff_freq_ + 1); + // filtered_feet_center_pos_ = + // alpha * feet_center_pos + (1 - alpha) * filtered_feet_center_pos_; + // } + // feet_center_pos = filtered_feet_center_pos_; // Desired com pos - Vector3d desired_com_pos(feet_center_pos(0) + x_offset, - feet_center_pos(1) + y_offset, - feet_center_pos(2) + target_height); + Vector3d desired_com_pos(x_offset, -mid_point_y + y_offset, + contact_pos_sum(2) + target_height); // Assign traj PiecewisePolynomial* pp_traj = diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index f7eba2605d..740738f968 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -39,7 +39,7 @@ rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 -w_swing_toe: 0.001 +w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 @@ -48,13 +48,12 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -#footstep_sagital_offset: -0.06 -footstep_sagital_offset: -0.02 -footstep_lateral_offset: 0.02 # drake -mid_foot_height: 0.15 +footstep_sagital_offset: -0.045 +footstep_lateral_offset: 0.03 # drake +mid_foot_height: 0.05 FootstepKd: - [ 0.17, 0, 0, - 0, 0.4, 0, + [ 0.2, 0, 0, + 0, 0.45, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, @@ -63,7 +62,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 50, 0, - 0, 0, 145] + 0, 0, 115] PelvisKd: [ 0, 0, 0, 0, 2, 0, @@ -71,21 +70,21 @@ PelvisKd: PelvisRotW: [1, 0, 0, 0, 2.5, 0, - 0, 0, 1] + 0, 0, 0.1] PelvisRotKp: - [25., 0, 0, + [50., 0, 0, 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [0.1, 0, 0, - 0, 2., 0, - 0, 0, 5.] + [2., 0, 0, + 0, 5., 0, + 0, 0, 1.] SwingFootW: - [1, 0, 0, - 0, 10, 0, - 0, 0, 1] + [10, 0, 0, + 0, 100, 0, + 0, 0, 10] SwingFootKp: - [100, 0, 0, + [125, 0, 0, 0, 100, 0, 0, 0, 45] SwingFootKd: @@ -104,4 +103,3 @@ LiftoffSwingFootKd: [ 5, 0, 0, 0, 5, 0, 0, 0, 1] - diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 922c7a7946..d205292669 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -305,61 +305,64 @@ void DoMain() { auto& prog = trajopt.prog(); double tol = FLAGS_tol; + + drake::solvers::SolverOptions solver_options; if (FLAGS_ipopt) { // Ipopt settings adapted from CaSaDi and FROST auto id = drake::solvers::IpoptSolver::id(); - prog.SetSolverOption(id, "tol", tol); - prog.SetSolverOption(id, "dual_inf_tol", tol); - prog.SetSolverOption(id, "constr_viol_tol", tol); - prog.SetSolverOption(id, "compl_inf_tol", tol); - prog.SetSolverOption(id, "max_iter", 1e5); - prog.SetSolverOption(id, "nlp_lower_bound_inf", -1e6); - prog.SetSolverOption(id, "nlp_upper_bound_inf", 1e6); - prog.SetSolverOption(id, "print_timing_statistics", "yes"); - prog.SetSolverOption(id, "print_level", 5); - prog.SetSolverOption(id, "output_file", "../ipopt.out"); - - // Set to ignore overall tolerance/dual infeasibility, but terminate when - // primal feasible and objective fails to increase over 5 iterations. - prog.SetSolverOption(id, "acceptable_compl_inf_tol", tol); - prog.SetSolverOption(id, "acceptable_constr_viol_tol", tol); - prog.SetSolverOption(id, "acceptable_obj_change_tol", 1e-3); - prog.SetSolverOption(id, "acceptable_tol", 1e2); - prog.SetSolverOption(id, "acceptable_iter", 5); + solver_options.SetOption(id, "tol", tol); //NOLINT + solver_options.SetOption(id, "dual_inf_tol", tol); //NOLINT + solver_options.SetOption(id, "constr_viol_tol", tol); //NOLINT + solver_options.SetOption(id, "compl_inf_tol", tol); //NOLINT + solver_options.SetOption(id, "max_iter", 1e5); //NOLINT + solver_options.SetOption(id, "nlp_lower_bound_inf", -1e6); //NOLINT + solver_options.SetOption(id, "nlp_upper_bound_inf", 1e6); //NOLINT + solver_options.SetOption(id, "print_timing_statistics", "yes"); //NOLINT + solver_options.SetOption(id, "print_level", 5); //NOLINT + solver_options.SetOption(id, "output_file", "../ipopt.out"); //NOLINT + solver_options.SetOption(id, "acceptable_compl_inf_tol", tol); //NOLINT + solver_options.SetOption(id, "acceptable_constr_viol_tol", tol); //NOLINT + solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); //NOLINT + solver_options.SetOption(id, "acceptable_tol", 1e2); //NOLINT + solver_options.SetOption(id, "acceptable_iter", 5); //NOLINT + } else { // Snopt settings auto id = drake::solvers::SnoptSolver::id(); - if (FLAGS_use_springs) { - prog.SetSolverOption(id, "Print file", "../w_springs_snopt.out"); - } else { - prog.SetSolverOption(id, "Print file", "../snopt.out"); - } - prog.SetSolverOption(id, "Major iterations limit", 1e5); - prog.SetSolverOption(id, "Iterations limit", 100000); - prog.SetSolverOption(id, "Verify level", 0); + solver_options.SetOption(id, "Print file", "../snopt.out"); //NOLINT + solver_options.SetOption(id, "Major iterations limit", 1e5); //NOLINT + solver_options.SetOption(id, "Iterations limit", 100000); //NOLINT + solver_options.SetOption(id, "Verify level", 0); //NOLINT + solver_options.SetOption(id, "Major optimality tolerance", 1e-5); //NOLINT + solver_options.SetOption(id, "Solution", "No"); //NOLINT + solver_options.SetOption(id, "Major feasibility tolerance", tol); //NOLINT + +// prog.SetSolverOption(id, "Print file", "../snopt.out"); +// prog.SetSolverOption(id, "Major iterations limit", 1e5); +// prog.SetSolverOption(id, "Iterations limit", 100000); +// prog.SetSolverOption(id, "Verify level", 0); // snopt doc said try 2 if seeing snopta exit 40 - prog.SetSolverOption(id, "Scale option", 2); - prog.SetSolverOption(id, "Solution", "No"); + // prog.SetSolverOption(id, "Scale option", 2); +// prog.SetSolverOption(id, ); // target nonlinear constraint violation - prog.SetSolverOption(id, "Major optimality tolerance", - 1e-5 / FLAGS_cost_scaling); +// prog.SetSolverOption(id, "Major optimality tolerance", 1e-5); // prog.SetSolverOption(id, "Major optimality tolerance", // 1e-5); // target complementarity gap - prog.SetSolverOption(id, "Major feasibility tolerance", tol); +// prog.SetSolverOption(id, ); } std::cout << "Adding kinematic constraints: " << std::endl; SetKinematicConstraints(&trajopt, plant); std::cout << "Adding costs: " << std::endl; -// if (FLAGS_use_springs) { -// AddCostsSprings(&trajopt, plant, &all_modes); -// } else { -// AddCosts(&trajopt, plant, &all_modes); -// } + // if (FLAGS_use_springs) { + // AddCostsSprings(&trajopt, plant, &all_modes); + // } else { + // AddCosts(&trajopt, plant, &all_modes); + // } AddCosts(&trajopt, plant, &all_modes); std::cout << "Setting initial conditions: " << std::endl; vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, @@ -385,12 +388,21 @@ void DoMain() { // int num_poses = mode_lengths.size() * FLAGS_knot_points - 1; trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); - cout << "\nChoose the best solver: " - << drake::solvers::ChooseBestSolver(prog).name() << endl; + // cout << "\nChoose the best solver: " + // << drake::solvers::ChooseBestSolver(prog).name() << endl; cout << "Solving DIRCON\n\n"; + auto ipopt_solver = drake::solvers::IpoptSolver(); + auto snopt_solver = drake::solvers::SnoptSolver(); + MathematicalProgramResult result; + auto start = std::chrono::high_resolution_clock::now(); - const auto result = drake::solvers::Solve(prog, prog.initial_guess()); + if (FLAGS_ipopt) { + result = ipopt_solver.Solve(prog, prog.initial_guess(), solver_options); + } else { + result = snopt_solver.Solve(prog, prog.initial_guess(), solver_options); + } + auto finish = std::chrono::high_resolution_clock::now(); std::chrono::duration elapsed = finish - start; cout << "Solve time:" << elapsed.count() << std::endl; @@ -480,15 +492,15 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_left"))); // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_right"))); - trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_left"))); - trajopt->AddConstraintToAllKnotPoints(-2.1 <= x(pos_map.at("knee_right"))); - trajopt->AddConstraintToAllKnotPoints(-1.1 >= x(pos_map.at("knee_left"))); - trajopt->AddConstraintToAllKnotPoints(-1.1 >= x(pos_map.at("knee_right"))); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) >= -2.1); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) >= -2.1); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) <= -1.1); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) <= -1.1); - trajopt->AddConstraintToAllKnotPoints(-2.2 <= x(pos_map.at("toe_left"))); - trajopt->AddConstraintToAllKnotPoints(-2.2 <= x(pos_map.at("toe_right"))); - trajopt->AddConstraintToAllKnotPoints(-1.6 >= x(pos_map.at("toe_left"))); - trajopt->AddConstraintToAllKnotPoints(-1.6 >= x(pos_map.at("toe_right"))); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) >= -2.2); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) >= -2.2); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) <= -1.6); + trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) <= -1.6); // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, @@ -559,14 +571,18 @@ void SetKinematicConstraints(Dircon* trajopt, // l_r_pair.first]) == // x_f(pos_map[sym_joint_name + l_r_pair.second])); if (sym_joint_name != "ankle_joint") { // No actuator at ankle -// trajopt->AddConstraintToAllKnotPoints( -// u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] - -// u[act_map.at(sym_joint_name + l_r_pair.second + "_motor")] <= -// 10); -// trajopt->AddConstraintToAllKnotPoints( -// u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] - -// u[act_map.at(sym_joint_name + l_r_pair.second + "_motor")] >= -// -10); + // trajopt->AddConstraintToAllKnotPoints( + // u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] + // - + // u[act_map.at(sym_joint_name + l_r_pair.second + + // "_motor")] <= + // 10); + // trajopt->AddConstraintToAllKnotPoints( + // u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] + // - + // u[act_map.at(sym_joint_name + l_r_pair.second + + // "_motor")] >= + // -10); // prog->AddConstraint( // u_f(act_map.at(sym_joint_name + l_r_pair.first + // "_motor")) == u_f(act_map.at(sym_joint_name + @@ -625,11 +641,11 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_z_ground_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), - VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); + VectorXd::Zero(1), 0.5 * VectorXd::Ones(1)); auto right_foot_z_ground_constraint = std::make_shared>( plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), - VectorXd::Zero(1), 1.5 * VectorXd::Ones(1)); + VectorXd::Zero(1), 0.5 * VectorXd::Ones(1)); for (int mode : {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { @@ -687,18 +703,18 @@ void SetKinematicConstraints(Dircon* trajopt, // Foot ground clearance constraint // Foot clearance constraint - auto left_foot_z_box_constraint = - std::make_shared>( - plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); - auto right_foot_z_box_constraint = - std::make_shared>( - plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); - prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); - prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); + // auto left_foot_z_box_constraint = + // std::make_shared>( + // plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + // (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), + // (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); + // auto right_foot_z_box_constraint = + // std::make_shared>( + // plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + // (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), + // (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); + // prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); + // prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); auto left_foot_rear_z_final_constraint = std::make_shared>( @@ -791,41 +807,45 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, } l_r_pairs.pop_back(); -// double w_symmetry_pos = FLAGS_cost_scaling * 1e5; -// double w_symmetry_vel = FLAGS_cost_scaling * 1e2; -// double w_symmetry_u = FLAGS_cost_scaling * 1e2; -// for (const auto& l_r_pair : l_r_pairs) { -// for (const auto& sym_joint_name : sym_joint_names) { -// auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - -// x(pos_map.at(sym_joint_name + l_r_pair.second)); -// auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - -// x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); -// trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); -// trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); -// if (sym_joint_name != "ankle_joint") { -// auto act_diff = -// u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - -// u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); -// trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); -// } -// } -// } -// for (const auto& l_r_pair : l_r_pairs) { -// for (const auto& asy_joint_name : asy_joint_names) { -// auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + -// x(pos_map.at(asy_joint_name + l_r_pair.second)); -// auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + -// x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); -// trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); -// trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); -// if (asy_joint_name != "ankle_joint") { -// auto act_diff = -// u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + -// u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); -// trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); -// } -// } -// } + // double w_symmetry_pos = FLAGS_cost_scaling * 1e5; + // double w_symmetry_vel = FLAGS_cost_scaling * 1e2; + // double w_symmetry_u = FLAGS_cost_scaling * 1e2; + // for (const auto& l_r_pair : l_r_pairs) { + // for (const auto& sym_joint_name : sym_joint_names) { + // auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - + // x(pos_map.at(sym_joint_name + l_r_pair.second)); + // auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) + // - + // x(vel_map.at(sym_joint_name + l_r_pair.second + + // "dot")); + // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + // if (sym_joint_name != "ankle_joint") { + // auto act_diff = + // u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + // u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + // } + // } + // } + // for (const auto& l_r_pair : l_r_pairs) { + // for (const auto& asy_joint_name : asy_joint_names) { + // auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + + // x(pos_map.at(asy_joint_name + l_r_pair.second)); + // auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + // + + // x(vel_map.at(asy_joint_name + l_r_pair.second + + // "dot")); + // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + // if (asy_joint_name != "ankle_joint") { + // auto act_diff = + // u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + // u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + // } + // } + // } MatrixXd Q = FLAGS_cost_scaling * 0.02 * MatrixXd::Identity(n_v, n_v); // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); @@ -873,26 +893,26 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; -// MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); -// W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; -// W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; -// W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; -// W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; -// W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; -// W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; -// W *= 2.0 * FLAGS_cost_scaling; -// vector> joint_accel_costs; -// for (int mode : {0, 1, 2}) { -// joint_accel_costs.push_back(std::make_shared( -// W, plant, &constraints->mode(mode).evaluators())); -// for (int index = 0; index < mode_lengths[mode]; index++) { -// // Assumes mode_lengths are the same across modes -// auto x_i = trajopt->state_vars(mode, index); -// auto u_i = trajopt->input_vars(mode, index); -// auto l_i = trajopt->force_vars(mode, index); -// trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); -// } -// } + // MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); + // W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; + // W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; + // W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; + // W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; + // W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + // W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + // W *= 2.0 * FLAGS_cost_scaling; + // vector> joint_accel_costs; + // for (int mode : {0, 1, 2}) { + // joint_accel_costs.push_back(std::make_shared( + // W, plant, &constraints->mode(mode).evaluators())); + // for (int index = 0; index < mode_lengths[mode]; index++) { + // // Assumes mode_lengths are the same across modes + // auto x_i = trajopt->state_vars(mode, index); + // auto u_i = trajopt->input_vars(mode, index); + // auto l_i = trajopt->force_vars(mode, index); + // trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + // } + // } } /****** diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index c5afe230b7..25a1fe518a 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -16,6 +16,7 @@ #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/options_tracking_data.h" #include "systems/controllers/osc/osc_gains.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" @@ -49,6 +50,8 @@ using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; + DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "LCM channel for receiving state. " @@ -227,33 +230,33 @@ int DoMain(int argc, char* argv[]) { gains.W_lambda_h_regularization); osc->SetJointLimitWeight(1.0); - // Center of mass tracking - // Weighting x-y higher than z, as they are more important to balancing - // ComTrackingData center_of_mass_traj("com_traj", K_p_com, K_d_com, - // W_com * FLAGS_cost_weight_multiplier, - // plant, plant); - auto center_of_mass_traj = std::make_unique( - "com_traj", osc_gains.K_p_com, osc_gains.K_d_com, - osc_gains.W_com * FLAGS_cost_weight_multiplier, plant, plant); - center_of_mass_traj->AddPointToTrack("pelvis"); - // double cutoff_freq = 5; // in Hz - // double tau = 1 / (2 * M_PI * cutoff_freq); - center_of_mass_traj->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, - {1}); - osc->AddTrackingData(std::move(center_of_mass_traj)); - // Pelvis rotation tracking - auto pelvis_rot_traj = std::make_unique( - "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, - osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant, plant); - pelvis_rot_traj->AddFrameToTrack("pelvis"); - pelvis_rot_traj->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, - {0, 1, 2}); - osc->AddTrackingData(std::move(pelvis_rot_traj)); - - // Hip yaw joint tracking - // We use hip yaw joint tracking instead of pelvis yaw tracking because the - // foot sometimes rotates about yaw, and we need hip yaw joint to go back to - // 0. + + const auto& pelvis = plant.GetBodyByName("pelvis"); + multibody::WorldYawViewFrame view_frame(pelvis); + auto pelvis_tracking_data = std::make_unique( + "pelvis_trans_traj", MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), + MatrixXd::Zero(3, 3), plant, plant); + auto stance_foot_tracking_data = std::make_unique( + "stance_ft_traj", MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), + MatrixXd::Zero(3, 3), plant, plant); + pelvis_tracking_data->AddPointToTrack("pelvis"); + stance_foot_tracking_data->AddPointToTrack("toe_left"); + auto pelvis_trans_rel_tracking_data = + std::make_unique( + "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot, plant, plant, pelvis_tracking_data.get(), + stance_foot_tracking_data.get()); + pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); + auto pelvis_rot_tracking_data = std::make_unique( + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot, plant, plant); + pelvis_rot_tracking_data->AddFrameToTrack("pelvis"); + pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, + {0, 1, 2}); + osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); + + auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, osc_gains.W_hip_yaw, plant, plant); @@ -274,7 +277,7 @@ int DoMain(int argc, char* argv[]) { command_sender->get_input_port(0)); builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); builder.Connect(com_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("com_traj")); + osc->get_input_port_tracking_data("pelvis_trans_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("pelvis_rot_traj")); diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 23db5d2b58..b7120290d5 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -652,7 +652,6 @@ - @@ -662,7 +661,6 @@ - diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 16d43cbade..a2b425e69f 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -796,12 +796,12 @@ VectorXd OperationalSpaceControl::SolveQp( // Solve the QP MathematicalProgramResult result; - if (fsm_state == -1) { - auto osqp_solver = drake::solvers::OsqpSolver(); - result = osqp_solver.Solve(*prog_, std::nullopt, solver_options_); - } else { - result = solvers_.at(0)->Solve(*prog_); - } + // if (fsm_state == -1) { + // auto osqp_solver = drake::solvers::OsqpSolver(); + // result = osqp_solver.Solve(*prog_, std::nullopt, solver_options_); + // } else { + result = solvers_.at(0)->Solve(*prog_); + // } solve_time_ = result.get_solver_details().run_time; if (result.is_success()) { @@ -1070,8 +1070,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( } output->tracking_data[i] = osc_output; } -// output->regularization_costs.push_back(total_cost); -// output->regularization_cost_names.push_back("total_cost"); + // output->regularization_costs.push_back(total_cost); + // output->regularization_cost_names.push_back("total_cost"); *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); From 64b8acd081daeb040e03a72bc78ee6065bce8ea5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 25 Aug 2022 12:42:20 -0400 Subject: [PATCH 294/758] updating standing controller --- examples/Cassie/osc/osc_standing_gains.yaml | 6 ++-- examples/Cassie/osc/standing_com_traj.cc | 33 +++++++++++++------ examples/Cassie/osc/standing_com_traj.h | 1 + .../Cassie/run_osc_standing_controller.cc | 2 ++ 4 files changed, 29 insertions(+), 13 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 4a7fb570c1..67a96d3f2b 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -46,9 +46,9 @@ PelvisKp: 0, 50, 0, 0, 0, 50] PelvisKd: - [ 15, 0, 0, - 0, 5, 0, - 0, 0, 10] + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1] PelvisRotW: [5, 0, 0, 0, 5, 0, diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index 46db82130d..a87fbd9f8d 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -89,6 +89,8 @@ void StandingComTraj::CalcDesiredTraj( target_height = drake::math::saturate(target_height, kMinHeight, kMaxHeight); double x_offset = kCoMXScale * radio_out->channel[4]; double y_offset = kCoMYScale * radio_out->channel[5]; + Vector3d target_pos; + target_pos << x_offset, y_offset, target_height; VectorXd q = robot_output->GetPositions(); multibody::SetPositionsIfNew(plant_, q, context_); @@ -118,19 +120,16 @@ void StandingComTraj::CalcDesiredTraj( right_toe_position + right_heel_position) / 4; // } - double mid_point_x = ((left_toe_position[0] - left_heel_position[0]) + - (right_toe_position[0] - right_heel_position[0])) / - 2; + // double mid_point_x = ((left_toe_position[0] - left_heel_position[0]) + + // (right_toe_position[0] - right_heel_position[0])) / + // 2; double mid_point_y = ((left_toe_position[1] - right_toe_position[1]) + (left_heel_position[1] - right_heel_position[1])) / 4; // Vector3d feet_center_pos = contact_pos_sum / 4; // Testing -- filtering feet_center_pos - // if (filtered_feet_center_pos_.norm() == 0) { - // // Initialize - // filtered_feet_center_pos_ = feet_center_pos; - // } + // if (robot_output->get_timestamp() != last_timestamp_) { // double dt = robot_output->get_timestamp() - last_timestamp_; // last_timestamp_ = robot_output->get_timestamp(); @@ -142,14 +141,28 @@ void StandingComTraj::CalcDesiredTraj( // feet_center_pos = filtered_feet_center_pos_; // Desired com pos - Vector3d desired_com_pos(x_offset, -mid_point_y + y_offset, - contact_pos_sum(2) + target_height); + Vector3d desired_com_pos_offset; + desired_com_pos_offset << 0.05, -mid_point_y, contact_pos_sum(2); + Vector3d desired_com_pos = desired_com_pos_offset + target_pos; + + if (filtered_target_pos_.norm() == 0) { + // // Initialize + filtered_target_pos_ = desired_com_pos; + } + if (robot_output->get_timestamp() != last_timestamp_) { + double dt = robot_output->get_timestamp() - last_timestamp_; + last_timestamp_ = robot_output->get_timestamp(); + double alpha = + 2 * M_PI * dt * cutoff_freq_ / (2 * M_PI * dt * cutoff_freq_ + 1); + filtered_target_pos_ = + alpha * desired_com_pos + (1 - alpha) * filtered_target_pos_; + } // Assign traj PiecewisePolynomial* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - *pp_traj = PiecewisePolynomial(desired_com_pos); + *pp_traj = PiecewisePolynomial(filtered_target_pos_); } } // namespace osc diff --git a/examples/Cassie/osc/standing_com_traj.h b/examples/Cassie/osc/standing_com_traj.h index 4abbae4e18..6b32c9f177 100644 --- a/examples/Cassie/osc/standing_com_traj.h +++ b/examples/Cassie/osc/standing_com_traj.h @@ -71,6 +71,7 @@ class StandingComTraj : public drake::systems::LeafSystem { // Testing -- filtering for center of support polygon double cutoff_freq_ = 0.05; // in Hz. mutable Eigen::Vector3d filtered_feet_center_pos_ = Eigen::Vector3d::Zero(); + mutable Eigen::Vector3d filtered_target_pos_ = Eigen::Vector3d::Zero(); mutable double last_timestamp_ = 0; }; diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 25a1fe518a..524c21d4b0 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -246,6 +246,8 @@ int DoMain(int argc, char* argv[]) { "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); + pelvis_trans_rel_tracking_data->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, + {0, 1, 2}); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, From cd52e2e6f0f68244fbbb74d0165d7437c8e48f10 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 25 Aug 2022 14:36:41 -0400 Subject: [PATCH 295/758] updating standing controller --- common/BUILD.bazel | 14 +++++++ common/discrete_time_filter.cc | 30 +++++++++++++++ common/discrete_time_filter.h | 37 +++++++++++++++++++ examples/Cassie/osc/BUILD.bazel | 6 ++- examples/Cassie/osc/osc_standing_gains.h | 4 ++ examples/Cassie/osc/osc_standing_gains.yaml | 6 ++- examples/Cassie/osc/standing_com_traj.cc | 18 +++------ examples/Cassie/osc/standing_com_traj.h | 13 +++++-- .../osc/standing_pelvis_orientation_traj.cc | 27 +++++++------- .../osc/standing_pelvis_orientation_traj.h | 7 ++++ .../Cassie/run_osc_standing_controller.cc | 19 +++++----- 11 files changed, 139 insertions(+), 42 deletions(-) create mode 100644 common/discrete_time_filter.cc create mode 100644 common/discrete_time_filter.h diff --git a/common/BUILD.bazel b/common/BUILD.bazel index f6b0a826fe..2fe5887662 100644 --- a/common/BUILD.bazel +++ b/common/BUILD.bazel @@ -6,6 +6,7 @@ cc_library( ":find_resource", ":eigen_utils", ":file_utils", + ":discrete_time_filter", ":blending_utils", "@drake//:drake_shared_library", ], @@ -60,3 +61,16 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "discrete_time_filter", + srcs = [ + "discrete_time_filter.cc", + ], + hdrs = [ + "discrete_time_filter.h", + ], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/common/discrete_time_filter.cc b/common/discrete_time_filter.cc new file mode 100644 index 0000000000..b5b3b263d1 --- /dev/null +++ b/common/discrete_time_filter.cc @@ -0,0 +1,30 @@ +#include "discrete_time_filter.h" + +#include "drake/common/drake_assert.h" + +using Eigen::VectorXd; +namespace dairlib { + +void DiscreteTimeFilter::Update(Eigen::VectorXd value){ +} +void DiscreteTimeFilter::Reset(){ +} + +FirstOrderLowPassFilter::FirstOrderLowPassFilter(double alpha, int vector_size) + : alpha_(alpha) { + y_.resize(vector_size); + y_.setZero(); +} + +void FirstOrderLowPassFilter::Reset() { y_.setZero(); } + +void FirstOrderLowPassFilter::Update(VectorXd value) { + DRAKE_DEMAND(value.size() == y_.size()); + y_ = alpha_ * value + (1 - alpha_) * y_; +} + +void FirstOrderLowPassFilter::UpdateParameters(double alpha) { + alpha_ = alpha; +} + +} // namespace dairlib \ No newline at end of file diff --git a/common/discrete_time_filter.h b/common/discrete_time_filter.h new file mode 100644 index 0000000000..3035c47576 --- /dev/null +++ b/common/discrete_time_filter.h @@ -0,0 +1,37 @@ +#pragma once + +#include + +namespace dairlib { + +class DiscreteTimeFilter { + public: + DiscreteTimeFilter() = default; + virtual ~DiscreteTimeFilter() = default; + + virtual void Reset(); + virtual void Update(Eigen::VectorXd); + Eigen::VectorXd Value() const { + return y_; + } + + protected: + Eigen::VectorXd y_; + + private: +}; + +class FirstOrderLowPassFilter : public DiscreteTimeFilter { + public: + FirstOrderLowPassFilter(double alpha, int vector_size); + void Reset() override; + void Update(Eigen::VectorXd) override; + void UpdateParameters(double alpha); + + private: + double alpha_; +}; + +class ButterworthFilter : public DiscreteTimeFilter {}; + +} // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/osc/BUILD.bazel b/examples/Cassie/osc/BUILD.bazel index ff942be658..1e38fef6a3 100644 --- a/examples/Cassie/osc/BUILD.bazel +++ b/examples/Cassie/osc/BUILD.bazel @@ -12,7 +12,7 @@ cc_library( "//examples/Cassie/osc:osc_walking_gains_alip", "//examples/Cassie/osc:osc_standing_gains", "//examples/Cassie/osc:standing_com_traj", - "//examples/Cassie/osc:standing_pelvis_traj", + "//examples/Cassie/osc:standing_pelvis_orientation_traj", "//examples/Cassie/osc:swing_toe_traj", "//examples/Cassie/osc:walking_speed_control", "//systems/controllers:alip_swing_ft_traj_gen", @@ -78,6 +78,7 @@ cc_library( deps = [ "//lcmtypes:lcmt_robot", "//multibody:utils", + "//common:common", "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", @@ -85,13 +86,14 @@ cc_library( ) cc_library( - name = "standing_pelvis_traj", + name = "standing_pelvis_orientation_traj", srcs = ["standing_pelvis_orientation_traj.cc"], hdrs = ["standing_pelvis_orientation_traj.h"], deps = [ "//lcmtypes:lcmt_robot", "//systems/controllers:control_utils", "//systems/framework:vector", + "//common:common", "@drake//:drake_shared_library", ], ) diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h index 938d420a24..6a6f05ca35 100644 --- a/examples/Cassie/osc/osc_standing_gains.h +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -16,6 +16,8 @@ struct OSCStandingGains : OSCGains { double HipYawW; double center_of_mass_filter_tau; double rot_filter_tau; + double center_of_mass_command_filter_alpha; + double orientation_command_filter_alpha; std::vector PelvisW; std::vector PelvisKp; std::vector PelvisKd; @@ -50,6 +52,8 @@ struct OSCStandingGains : OSCGains { a->Visit(DRAKE_NVP(HipYawW)); a->Visit(DRAKE_NVP(center_of_mass_filter_tau)); a->Visit(DRAKE_NVP(rot_filter_tau)); + a->Visit(DRAKE_NVP(center_of_mass_command_filter_alpha)); + a->Visit(DRAKE_NVP(orientation_command_filter_alpha)); W_pelvis = Eigen::Map< Eigen::Matrix>( diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 67a96d3f2b..f352f0dce0 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -29,8 +29,10 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, w_soft_constraint: 100 w_input_reg: 0.00 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.01 +center_of_mass_filter_tau: 0.001 rot_filter_tau: 0.01 +center_of_mass_command_filter_alpha: 0.05 +orientation_command_filter_alpha: 0.0005 impact_tau: 0.00 mu: 0.6 weight_scaling: 1.0 @@ -40,7 +42,7 @@ HipYawW: 0 PelvisW: [20, 0, 0, 0, 2, 0, - 0, 0, 20] + 0, 0, 10] PelvisKp: [100, 0, 0, 0, 50, 0, diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index a87fbd9f8d..5d82a8691a 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -35,6 +35,8 @@ StandingComTraj::StandingComTraj( feet_contact_points_(feet_contact_points), height_(height), set_target_height_by_radio_(set_target_height_by_radio) { + + target_pos_filter_ = std::make_unique(1.0, 3); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( "x, u, t", OutputVector(plant.num_positions(), @@ -145,24 +147,14 @@ void StandingComTraj::CalcDesiredTraj( desired_com_pos_offset << 0.05, -mid_point_y, contact_pos_sum(2); Vector3d desired_com_pos = desired_com_pos_offset + target_pos; - if (filtered_target_pos_.norm() == 0) { - // // Initialize - filtered_target_pos_ = desired_com_pos; - } - if (robot_output->get_timestamp() != last_timestamp_) { - double dt = robot_output->get_timestamp() - last_timestamp_; - last_timestamp_ = robot_output->get_timestamp(); - double alpha = - 2 * M_PI * dt * cutoff_freq_ / (2 * M_PI * dt * cutoff_freq_ + 1); - filtered_target_pos_ = - alpha * desired_com_pos + (1 - alpha) * filtered_target_pos_; - } + target_pos_filter_->Update(desired_com_pos); + // Assign traj PiecewisePolynomial* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - *pp_traj = PiecewisePolynomial(filtered_target_pos_); + *pp_traj = PiecewisePolynomial(target_pos_filter_->Value()); } } // namespace osc diff --git a/examples/Cassie/osc/standing_com_traj.h b/examples/Cassie/osc/standing_com_traj.h index 6b32c9f177..438dc8e0e5 100644 --- a/examples/Cassie/osc/standing_com_traj.h +++ b/examples/Cassie/osc/standing_com_traj.h @@ -7,6 +7,7 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/framework/leaf_system.h" +#include "common/discrete_time_filter.h" namespace dairlib { namespace cassie { @@ -47,6 +48,10 @@ class StandingComTraj : public drake::systems::LeafSystem { return this->get_input_port(radio_port_); } + void SetCommandFilter(double alpha){ + target_pos_filter_->UpdateParameters(alpha); + } + private: void CalcDesiredTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -69,9 +74,11 @@ class StandingComTraj : public drake::systems::LeafSystem { // Testing -- filtering for center of support polygon - double cutoff_freq_ = 0.05; // in Hz. - mutable Eigen::Vector3d filtered_feet_center_pos_ = Eigen::Vector3d::Zero(); - mutable Eigen::Vector3d filtered_target_pos_ = Eigen::Vector3d::Zero(); + double cutoff_freq_ = 0.5; // in Hz. +// mutable Eigen::Vector3d filtered_feet_center_pos_ = Eigen::Vector3d::Zero(); +// mutable Eigen::Vector3d filtered_target_pos_ = Eigen::Vector3d::Zero(); + + std::unique_ptr target_pos_filter_; mutable double last_timestamp_ = 0; }; diff --git a/examples/Cassie/osc/standing_pelvis_orientation_traj.cc b/examples/Cassie/osc/standing_pelvis_orientation_traj.cc index 0717cb49fc..a9004e3308 100644 --- a/examples/Cassie/osc/standing_pelvis_orientation_traj.cc +++ b/examples/Cassie/osc/standing_pelvis_orientation_traj.cc @@ -28,17 +28,18 @@ StandingPelvisOrientationTraj::StandingPelvisOrientationTraj( context_(context), world_(plant_.world_frame()), feet_contact_points_(feet_contact_points) { + target_orientation_filter_ = + std::make_unique(1.0, 3); + // Input/Output setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); - radio_port_ = - this->DeclareAbstractInputPort("radio_out", - drake::Value{}) - .get_index(); + .get_index(); + radio_port_ = this->DeclareAbstractInputPort( + "radio_out", drake::Value{}) + .get_index(); PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; this->set_name(traj_name); @@ -77,15 +78,15 @@ void StandingPelvisOrientationTraj::CalcTraj( VectorXd r_foot = pt_2 - pt_3; // l_foot_proj = l_foot.dot() Vector3d rpy; - rpy << radio_out->channel[1], - radio_out->channel[2], + rpy << radio_out->channel[1], radio_out->channel[2], drake::math::wrap_to( 0.5 * (atan2(l_foot(1), l_foot(0)) + atan2(r_foot(1), r_foot(0))), - -M_PI, M_PI) + + -M_PI/4, M_PI/4) + radio_out->channel[3]; - auto rot_mat = - drake::math::RotationMatrix(drake::math::RollPitchYaw(rpy)); + target_orientation_filter_->Update(rpy); + auto rot_mat = drake::math::RotationMatrix(drake::math::RollPitchYaw( + static_cast(target_orientation_filter_->Value()))); *casted_traj = PiecewisePolynomial(rot_mat.ToQuaternionAsVector4()); } diff --git a/examples/Cassie/osc/standing_pelvis_orientation_traj.h b/examples/Cassie/osc/standing_pelvis_orientation_traj.h index abc12ac37d..c0ab3e1c2b 100644 --- a/examples/Cassie/osc/standing_pelvis_orientation_traj.h +++ b/examples/Cassie/osc/standing_pelvis_orientation_traj.h @@ -7,6 +7,7 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" +#include "common/discrete_time_filter.h" namespace dairlib::cassie::osc { @@ -26,6 +27,9 @@ class StandingPelvisOrientationTraj const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); } + void SetCommandFilter(double alpha){ + target_orientation_filter_->UpdateParameters(alpha); + } private: void CalcTraj(const drake::systems::Context& context, @@ -41,6 +45,9 @@ class StandingPelvisOrientationTraj feet_contact_points_; int state_port_; int radio_port_; + + std::unique_ptr target_orientation_filter_; + }; } // namespace dairlib::cassie::osc diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 524c21d4b0..a54a5910e3 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -48,10 +48,9 @@ using multibody::FixedJointEvaluator; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -using systems::controllers::RelativeTranslationTrackingData; - DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "LCM channel for receiving state. " @@ -153,9 +152,13 @@ int DoMain(int argc, char* argv[]) { auto com_traj_generator = builder.AddSystem( plant, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); + com_traj_generator->SetCommandFilter( + osc_gains.center_of_mass_command_filter_alpha); auto pelvis_rot_traj_generator = builder.AddSystem( plant, context_w_spr.get(), feet_contact_points, "pelvis_rot_traj"); + pelvis_rot_traj_generator->SetCommandFilter( + osc_gains.orientation_command_filter_alpha); builder.Connect(state_receiver->get_output_port(0), com_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), @@ -230,7 +233,6 @@ int DoMain(int argc, char* argv[]) { gains.W_lambda_h_regularization); osc->SetJointLimitWeight(1.0); - const auto& pelvis = plant.GetBodyByName("pelvis"); multibody::WorldYawViewFrame view_frame(pelvis); auto pelvis_tracking_data = std::make_unique( @@ -243,11 +245,11 @@ int DoMain(int argc, char* argv[]) { stance_foot_tracking_data->AddPointToTrack("toe_left"); auto pelvis_trans_rel_tracking_data = std::make_unique( - "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, - osc_gains.W_pelvis_rot, plant, plant, pelvis_tracking_data.get(), - stance_foot_tracking_data.get()); - pelvis_trans_rel_tracking_data->SetLowPassFilter(osc_gains.center_of_mass_filter_tau, - {0, 1, 2}); + "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, + osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant, + pelvis_tracking_data.get(), stance_foot_tracking_data.get()); + pelvis_trans_rel_tracking_data->SetLowPassFilter( + osc_gains.center_of_mass_filter_tau, {0, 1, 2}); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, @@ -258,7 +260,6 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); - auto left_hip_yaw_traj = std::make_unique( "left_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, osc_gains.W_hip_yaw, plant, plant); From 8c2b1a3412cbe17edb560357f0e4ce0167482ae7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Aug 2022 16:22:02 -0400 Subject: [PATCH 296/758] updating filter settings --- .../pydairlib/analysis/log_plotter_cassie.py | 21 ++++++++++++------- .../plot_configs/cassie_running_plot.yaml | 19 +++++++++-------- .../plot_configs/cassie_standing_plot.yaml | 4 ++-- .../cassie/gym_envs/drake_cassie_gym.py | 6 ++++-- .../cassie/gym_envs/mujoco_cassie_gym.py | 3 ++- .../lcm/dircon_trajectory_plotter.py | 21 +++++++++---------- examples/Cassie/osc/standing_com_traj.cc | 2 +- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 15 +++++++------ .../Cassie/run_osc_standing_controller.cc | 12 +++++++---- .../osc/operational_space_control.cc | 5 ----- 11 files changed, 61 insertions(+), 49 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 65b45f9873..6b441e6f4c 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -31,6 +31,7 @@ def main(): pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) + import pdb; pdb.set_trace() ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") @@ -58,6 +59,8 @@ def main(): t_x_slice = slice(robot_output['t_x'].size) t_osc_slice = slice(osc_debug['t_osc'].size) print('Log start time: ', robot_output['t_x'][0]) + + print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) # import time # time_start = time.time() # time.sleep(1) @@ -79,12 +82,16 @@ def main(): # Plot joint positions if plot_config.plot_joint_positions: - mbp_plots.plot_joint_positions(robot_output, pos_names, + plot = mbp_plots.plot_joint_positions(robot_output, pos_names, 7 if use_floating_base else 0, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + # Plot specific positions if plot_config.pos_names: - mbp_plots.plot_positions_by_name(robot_output, plot_config.pos_names, + plot = mbp_plots.plot_positions_by_name(robot_output, plot_config.pos_names, t_x_slice, pos_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + ''' Plot Velocities ''' # Plot floating base velocities if applicable @@ -127,6 +134,10 @@ def main(): ''' Plot OSC ''' + if plot_config.plot_tracking_costs: + plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plt.ylim([0, 400]) if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) @@ -135,11 +146,7 @@ def main(): mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - if plot_config.plot_tracking_costs: - plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plot.attach() - plt.ylim([0, 200]) + if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index d9c8569072..1340fbd5bb 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 0 -duration: -1 +start_time: 5 +duration: 5 # Plant properties use_springs: true @@ -22,8 +22,9 @@ plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right' ] -special_velocities_to_plot: [ ] +#special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right' ] +special_positions_to_plot: [ 'hip_roll_left', 'hip_roll_right' ] +special_velocities_to_plot: ['hip_roll_leftdot', 'hip_roll_rightdot' ] special_efforts_to_plot: [ ] # Finite State Machine Names @@ -43,13 +44,13 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] }, - pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] }, +# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' ] }, +# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, +# right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml index 32a22467b8..30c2ba6a0d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml @@ -43,8 +43,8 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { -# pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel'] }, - # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} + pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, + pelvis_rot_traj: {'dims': [0, 1, 2], 'derivs': ['vel', 'accel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, # left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index e39f56031c..6b34d0adf1 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -77,9 +77,11 @@ def reset(self): return def advance_to(self, time): + cumulative_reward = 0 while self.current_time < time and not self.terminated: - self.step() - return + _, reward = self.step() + cumulative_reward += reward + return cumulative_reward def check_termination(self): return self.cassie_state.get_fb_positions()[2] < 0.4 diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 1672ca2037..9f9bcebffd 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -184,6 +184,7 @@ def velocity_profile(self, timestep): return velocity_command def step(self, action=np.zeros(18)): + if not self.initialized: print("Call make() before calling step() or advance()") @@ -196,9 +197,9 @@ def step(self, action=np.zeros(18)): self.robot_output_sender.get_input_port_state().FixValue(self.robot_output_sender_context, self.cassie_state.x) action = self.velocity_profile(next_timestep) self.radio_input_port.FixValue(self.controller_context, action) - u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) + # import pdb; pdb.set_trace() self.drake_sim.AdvanceTo(next_timestep) # self.reward_func.reset_clock_reward() while self.simulator.time() < next_timestep: diff --git a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py index 93dd2917ad..fc67afa21a 100644 --- a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py +++ b/bindings/pydairlib/lcm/dircon_trajectory_plotter.py @@ -17,13 +17,13 @@ def main(): plant.Finalize() # Default filename for the example - # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/walking_0.16.0") # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/jumping_0.15h_0.3d") filename = FindResourceOrThrow( - "examples/Cassie/saved_trajectories/jumping_0.0h_0.6d_9") + "examples/Cassie/saved_trajectories/jumping_0.0h_0.6d_4") # filename = FindResourceOrThrow( # "examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1") - # filename = "/home/yangwill/Documents/research/projects/cassie/hardware/backup/dair/saved_trajectories/jumping_0.15h_0.3d" + # filename = FindResourceOrThrow( + # "examples/Cassie/saved_trajectories/jumping_box_0.4h_0.3d_5") # filename = FindResourceOrThrow("examples/Cassie/saved_trajectories/" + sys.argv[1]) dircon_traj = lcm_trajectory.DirconTrajectory(plant, filename) @@ -39,21 +39,21 @@ def main(): # force_datatypes = dircon_traj.GetTrajectory("force_vars0").datatypes force_datatypes = dircon_traj.GetTrajectory("force_vars2").datatypes - impulse_samples = dircon_traj.GetImpulseSamples(2) + # impulse_samples = dircon_traj.GetImpulseSamples(2) collocation_force_points = dircon_traj.GetCollocationForceSamples(0) # M = reflected_joints() # # mirror_traj = lcm_trajectory.Trajectory() # mirror_traj.traj_name = 'mirror_matrix' # mirror_traj.time_vector = np.zeros(M.shape[0]) - # mirror_traj.datapoints = M + # mirror_traj.datapoints = MCc # mirror_traj.datatypes = [''] * M.shape[0] # # dircon_traj.AddTrajectory('mirror_matrix', mirror_traj) # dircon_traj.WriteToFile(filename) - plot_only_at_knotpoints = True + plot_only_at_knotpoints = False n_points = 500 t = np.linspace(state_traj.start_time(), state_traj.end_time(), n_points) @@ -70,19 +70,18 @@ def main(): input_samples[i] = input_traj.value(t[i])[:, 0] # force_samples[i] = force_traj[0].value(t[i])[:, 0] - import pdb; pdb.set_trace() # reflected_state_samples = state_samples @ M # Plotting reconstructed state trajectories plt.figure("state trajectory") - # plt.plot(t, state_samples[:, 4:7]) - plt.plot(t, state_samples[:, 22:25]) + plt.plot(t, state_samples[:, 4:7]) + # plt.plot(t, state_samples[:, 22:25]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 0:7]) # plt.plot(t, state_samples[:, -18:]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 7:13]) # plt.plot(t, state_samples[:, 25:31]) # plt.plot(t + state_traj.end_time(), reflected_state_samples[:, 25:31]) - # plt.legend(state_datatypes[4:7]) - plt.legend(state_datatypes[22:25]) + plt.legend(state_datatypes[4:7]) + # plt.legend(state_datatypes[22:25]) # Velocity Error # plt.figure('velocity_error') diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index 5d82a8691a..545f187bff 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -144,7 +144,7 @@ void StandingComTraj::CalcDesiredTraj( // Desired com pos Vector3d desired_com_pos_offset; - desired_com_pos_offset << 0.05, -mid_point_y, contact_pos_sum(2); + desired_com_pos_offset << 0.04, -mid_point_y, contact_pos_sum(2); Vector3d desired_com_pos = desired_com_pos_offset + target_pos; target_pos_filter_->Update(desired_com_pos); diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 97ab897cf1..7d134ca996 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 300 +max_iter: 150 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index da8d609f4b..429d9319f8 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -551,12 +551,15 @@ int DoMain(int argc, char* argv[]) { builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); - builder.Connect(state_receiver->get_output_port(0), - ekf_filter->get_input_port()); - builder.Connect(ekf_filter->get_output_port(), - osc->get_robot_output_input_port()); - // builder.Connect(state_receiver->get_output_port(0), - // osc->get_robot_output_input_port()); + if (osc_gains.ekf_filter_tau[0] > 0){ + builder.Connect(state_receiver->get_output_port(0), + ekf_filter->get_input_port()); + builder.Connect(ekf_filter->get_output_port(), + osc->get_robot_output_input_port()); + }else{ + builder.Connect(state_receiver->get_output_port(0), + osc->get_robot_output_input_port()); + } // FSM connections builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index a54a5910e3..3c53fbf6ae 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -248,15 +248,19 @@ int DoMain(int argc, char* argv[]) { "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); - pelvis_trans_rel_tracking_data->SetLowPassFilter( - osc_gains.center_of_mass_filter_tau, {0, 1, 2}); + if (osc_gains.center_of_mass_filter_tau > 0) { + pelvis_trans_rel_tracking_data->SetLowPassFilter( + osc_gains.center_of_mass_filter_tau, {0, 1, 2}); + } pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); pelvis_rot_tracking_data->AddFrameToTrack("pelvis"); - pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, - {0, 1, 2}); + if (osc_gains.rot_filter_tau > 0) { + pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, + {0, 1, 2}); + } osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index a2b425e69f..bd6cc1918f 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -796,12 +796,7 @@ VectorXd OperationalSpaceControl::SolveQp( // Solve the QP MathematicalProgramResult result; - // if (fsm_state == -1) { - // auto osqp_solver = drake::solvers::OsqpSolver(); - // result = osqp_solver.Solve(*prog_, std::nullopt, solver_options_); - // } else { result = solvers_.at(0)->Solve(*prog_); - // } solve_time_ = result.get_solver_details().run_time; if (result.is_success()) { From a00028e7acf84d9cd843c4973463c0ba1fc1abcb Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 30 Aug 2022 11:53:40 -0400 Subject: [PATCH 297/758] updating foot traj --- examples/Cassie/osc/osc_standing_gains.yaml | 4 +- .../Cassie/osc_run/foot_traj_generator.cc | 107 +++++------------- .../Cassie/osc_run/osc_running_gains.yaml | 16 +-- examples/Cassie/run_osc_running_controller.cc | 7 +- 4 files changed, 43 insertions(+), 91 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index f352f0dce0..1a740a8955 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -9,7 +9,7 @@ rows: 3 cols: 3 w_input: 0.0 -w_accel: 0.1 +w_accel: 0.001 w_lambda: 0.000001 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, @@ -46,7 +46,7 @@ PelvisW: PelvisKp: [100, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 75] PelvisKd: [ 1, 0, 0, 0, 1, 0, diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 56e6812c51..c093c48059 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -132,13 +132,12 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( &hip_pos); foot_pos = rot.transpose() * foot_pos; hip_pos = rot.transpose() * hip_pos; - auto pelvis_vel = discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - .get_mutable_value(); - pelvis_vel = 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; - auto last_stance_time = - discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - .get_mutable_value(); - last_stance_time[0] = robot_output->get_timestamp(); + // auto pelvis_vel = + // discrete_state->get_mutable_value(pelvis_vel_est_idx_); pelvis_vel = + // 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; auto last_stance_time = + // discrete_state->get_mutable_vector(pelvis_vel_est_idx_) + // .get_mutable_value(); + // last_stance_time[0] = robot_output->get_timestamp(); // pelvis_vel = v.segment(3, 3); // std::cout << "stance state: " << stance_state_ << std::endl; // pelvis_vel = Vector3d::Zero(); @@ -159,6 +158,13 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( const auto& mode_lengths = this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); + double pelvis_t0 = mode_lengths[0]; + double pelvis_tf = mode_lengths[1]; + double left_t0 = mode_lengths[2]; + double left_tf = mode_lengths[3]; + double right_t0 = mode_lengths[4]; + double right_tf = mode_lengths[5]; + // Offset between 0 and 2 double lateral_radio_tuning = 1.0; double sagital_radio_tuning = 1.0; @@ -189,9 +195,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Vector3d desired_pelvis_vel; desired_pelvis_vel << desired_pelvis_vel_xy, 0; - /// ALIP - // x refers to sagital plane - // y refers to the lateral plane auto foot_pos = context.get_discrete_state(initial_foot_pos_idx_).get_value(); Vector3d pelvis_pos; plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, @@ -199,7 +202,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( VectorXd pelvis_vel = v.segment(3, 3); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; - VectorXd foot_end_pos_des = Kd_ * (pelvis_vel_err); + VectorXd foot_end_pos_des = 0.5 * (pelvis_tf - pelvis_t0) * rot.transpose() * pelvis_vel + Kd_ * (pelvis_vel_err); if (is_left_foot_) { foot_end_pos_des(1) += lateral_radio_tuning * lateral_offset_; @@ -207,97 +210,49 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( foot_end_pos_des(1) -= lateral_radio_tuning * lateral_offset_; } foot_end_pos_des(0) += sagital_radio_tuning * sagital_offset_; - foot_end_pos_des(2) = 0; + foot_end_pos_des(2) = -rest_length_ - rest_length_offset_; + - double pelvis_t0 = mode_lengths[0]; - double pelvis_tf = mode_lengths[1]; - double left_t0 = mode_lengths[2]; - double left_tf = mode_lengths[3]; - double right_t0 = mode_lengths[4]; - double right_tf = mode_lengths[5]; std::vector T_waypoints; std::vector T_waypoints_0; std::vector T_waypoints_1; std::vector T_waypoints_2; - // Storing old method for record keeping - // T_waypoints = { - // state_durations_[1], - // state_durations_[1] + 0.5 * (state_durations_[4] - - // state_durations_[1]), state_durations_[4]}; - - // T_waypoints_0 = { - // state_durations_[0], - // (state_durations_[3] - state_durations_[4]) + - // 0.5 * (0.1 + state_durations_[2] - state_durations_[0]), - // state_durations_[2]}; - // T_waypoints_1 = {state_durations_[2], state_durations_[3]}; - // T_waypoints_2 = {state_durations_[3], state_durations_[4]}; - // - // - if (is_left_foot_) { - // std::cout << "is left foot: " << is_left_foot_ << std::endl; T_waypoints = {left_t0, left_t0 + 0.6 * (left_tf - left_t0), left_tf}; - // std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; - // std::cout << left_t0 << std::endl; - // std::cout << left_t0 + 0.6 * (left_tf - left_t0) << std::endl; - // std::cout << left_tf << std::endl; } else { - // std::cout << "is left foot: " << is_left_foot_ << std::endl; T_waypoints = {right_t0, right_t0 + 0.6 * (right_tf - right_t0), right_tf}; - // std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; - // std::cout << right_t0 << std::endl; - // std::cout << right_t0 + 0.6 * (right_tf - right_t0) << std::endl; - // std::cout << right_tf << std::endl; } - // std::cout << T_waypoints.back() - T_waypoints.front() << std::endl; - // T_waypoints_0 = { - // pelvis_t0, - // (state_durations_[3] - state_durations_[4]) + - // 1.5 / 3.0 * (0.1 + state_durations_[2] - pelvis_t0), - // state_durations_[2]}; - // T_waypoints_1 = {state_durations_[2], state_durations_[3]}; - // T_waypoints_2 = {state_durations_[3], state_durations_[4]}; - - // auto foot_pos = - // context.get_discrete_state(initial_foot_pos_idx_).get_value(); + auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; Y[0] = start_pos; if (start_pos(2) == 0) { - Y[0](2) = -rest_length_ - rest_length_offset_; + Y[0](2) = -rest_length_; } - Y[0](2) -= rest_length_offset_; - Y[1] = start_pos + 0.85 * foot_end_pos_des; - Y[1](2) = -rest_length_ + mid_foot_height_; + // Y[0](2) -= rest_length_offset_; + // Y[1] = start_pos + 0.8 * foot_end_pos_des; + Y[1] = start_pos + 0.75 * (foot_end_pos_des - start_pos); + Y[1](2) += mid_foot_height_; Y[2] = foot_end_pos_des; - Y[2](2) = -rest_length_ - rest_length_offset_; +// Y[2](2) = -rest_length_ - rest_length_offset_; // corrections if (is_left_foot_) { - Y[1](1) -= 0.25 * lateral_offset_; + // Y[1](1) -= lateral_offset_; Y[1](1) = drake::math::saturate(Y[1](1), lateral_offset_, 0.2); Y[2](1) = drake::math::saturate(Y[2](1), lateral_offset_, 0.2); + } else { - Y[1](1) += 0.25 * lateral_offset_; + // Y[1](1) += lateral_offset_; Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -lateral_offset_); Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -lateral_offset_); } + Y[1](0) = drake::math::saturate(Y[1](0), -0.4, 0.4); + Y[2](0) = drake::math::saturate(Y[2](0), -0.4, 0.4); - // MatrixXd Y_dot_start = MatrixXd::Zero(3, 1); - // MatrixXd Y_dot_end = MatrixXd::Zero(3, 1); - // Y_dot_end(2) = -0.1; - - // PiecewisePolynomial swing_foot_spline = - // PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - // T_waypoints, Y, Y_dot_start, Y_dot_end); - // std::cout << "is left foot: " << is_left_foot_ << std::endl; - // for (auto& t :T_waypoints){ - // std::cout << "t: " << t << std::endl; - // } PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( T_waypoints, Y, false); @@ -307,12 +262,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( void FootTrajGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { - // Read in current state - // const auto robot_output = - // this->template EvalVectorInput(context, state_port_); - // VectorXd x = robot_output->GetState(); - // double timestamp = robot_output->get_timestamp(); - // // // Read in finite state machine const auto fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value()[0]; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 740738f968..df543dc84d 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -30,7 +30,7 @@ ekf_filter_tau: [ 0.001, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -2 -vel_scale_trans_sagital: 0.2 +vel_scale_trans_sagital: 0.5 vel_scale_trans_lateral: -0.1 # SLIP parameters @@ -49,11 +49,11 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.045 -footstep_lateral_offset: 0.03 # drake -mid_foot_height: 0.05 +footstep_lateral_offset: 0.07 # drake +mid_foot_height: 0.1 FootstepKd: - [ 0.2, 0, 0, - 0, 0.45, 0, + [ 0.13, 0, 0, + 0, 0.13, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, @@ -62,7 +62,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 50, 0, - 0, 0, 115] + 0, 0, 155] PelvisKd: [ 0, 0, 0, 0, 2, 0, @@ -76,9 +76,9 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [2., 0, 0, + [5., 0, 0, 0, 5., 0, - 0, 0, 1.] + 0, 0, 5.] SwingFootW: [10, 0, 0, 0, 100, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 429d9319f8..1f43ca0581 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -477,8 +477,11 @@ int DoMain(int argc, char* argv[]) { RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, - {0, 1, 2}); + + if(osc_gains.rot_filter_tau > 0){ + pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, + {0, 1, 2}); + } pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); From 348342b052a1530b22520d7c897ce8618df1c214 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 31 Aug 2022 15:05:54 -0400 Subject: [PATCH 298/758] updating lcm url only for local --- .../pydairlib/analysis/log_plotter_cassie.py | 1 - .../plot_configs/cassie_running_plot.yaml | 14 +- .../state_based_controller_switch.cc | 2 +- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 2 +- .../Cassie/osc_run/foot_traj_generator.cc | 5 +- .../Cassie/osc_run/osc_running_gains.yaml | 20 +- examples/Cassie/run_controller_switch.cc | 2 +- examples/Cassie/run_dircon_jumping.cc | 181 +++++++++--------- examples/Cassie/run_osc_running_controller.cc | 3 +- .../Cassie/run_osc_standing_controller.cc | 2 +- 11 files changed, 115 insertions(+), 119 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 6b441e6f4c..36dd677b5e 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -31,7 +31,6 @@ def main(): pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) - import pdb; pdb.set_trace() ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1340fbd5bb..bfa051e95b 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,16 +6,16 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 5 -duration: 5 +start_time: 1 +duration: 2 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false -plot_floating_base_velocities: false +plot_floating_base_positions: true +plot_floating_base_velocities: true plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false @@ -23,7 +23,7 @@ plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false #special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right' ] -special_positions_to_plot: [ 'hip_roll_left', 'hip_roll_right' ] +special_positions_to_plot: [ 'hip_pitch_left', 'hip_pitch_right', 'hip_roll_left', 'hip_roll_right' ] special_velocities_to_plot: ['hip_roll_leftdot', 'hip_roll_rightdot' ] special_efforts_to_plot: [ ] @@ -49,8 +49,8 @@ tracking_datas_to_plot: { # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, -# right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, -# left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, diff --git a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc index 2873fc7348..ced37ff3da 100644 --- a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc +++ b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc @@ -54,7 +54,7 @@ int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Parameters - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // Build the diagram drake::systems::DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 4e917cef52..17d2124ee3 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -67,7 +67,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 0975271983..2e1bc967d3 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -159,7 +159,7 @@ int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); DiagramBuilder builder; - auto lcm = builder.AddSystem("udpm://239.255.76.67:7667?ttl=0"); + auto lcm = builder.AddSystem(); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); // Build Cassie MBP diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index c093c48059..ffab5a16d3 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -202,7 +202,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( VectorXd pelvis_vel = v.segment(3, 3); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; - VectorXd foot_end_pos_des = 0.5 * (pelvis_tf - pelvis_t0) * rot.transpose() * pelvis_vel + Kd_ * (pelvis_vel_err); + VectorXd foot_end_pos_des = + 0.5 * (0.3) * rot.transpose() * pelvis_vel + Kd_ * (pelvis_vel_err); if (is_left_foot_) { foot_end_pos_des(1) += lateral_radio_tuning * lateral_offset_; @@ -212,8 +213,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( foot_end_pos_des(0) += sagital_radio_tuning * sagital_offset_; foot_end_pos_des(2) = -rest_length_ - rest_length_offset_; - - std::vector T_waypoints; std::vector T_waypoints_0; std::vector T_waypoints_1; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index df543dc84d..f72d21f231 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -35,12 +35,12 @@ vel_scale_trans_lateral: -0.1 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.025 +rest_length_offset: 0.05 stance_duration: 0.3 flight_duration: 0.09 w_swing_toe: 1 -swing_toe_kp: 1500 +swing_toe_kp: 1000 swing_toe_kd: 10 w_hip_yaw: 2.5 @@ -48,9 +48,9 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.045 +footstep_sagital_offset: -0.03 footstep_lateral_offset: 0.07 # drake -mid_foot_height: 0.1 +mid_foot_height: 0.15 FootstepKd: [ 0.13, 0, 0, 0, 0.13, 0, @@ -61,15 +61,15 @@ PelvisW: 0, 0, 5 ] PelvisKp: [ 0, 0, 0, - 0, 50, 0, + 0, 40, 0, 0, 0, 155] PelvisKd: [ 0, 0, 0, 0, 2, 0, 0, 0, 5 ] PelvisRotW: - [1, 0, 0, - 0, 2.5, 0, + [0.1, 0, 0, + 0, 5, 0, 0, 0, 0.1] PelvisRotKp: [50., 0, 0, @@ -85,12 +85,12 @@ SwingFootW: 0, 0, 10] SwingFootKp: [125, 0, 0, - 0, 100, 0, - 0, 0, 45] + 0, 75, 0, + 0, 0, 150] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 2.] + 0, 0, 5.] LiftoffSwingFootW: [0, 0, 0, 0, 0, 0, diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index d6bef0eecb..6b0cf9dae8 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -81,7 +81,7 @@ int do_main(int argc, char* argv[]) { // Build the diagram drake::systems::DiagramBuilder builder; - auto lcm = builder.AddSystem("udpm://239.255.76.67:7667?ttl=0"); + auto lcm = builder.AddSystem(); auto name_pub = builder.AddSystem( LcmPublisherSystem::Make( FLAGS_switch_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index d205292669..703969c835 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -310,49 +310,50 @@ void DoMain() { if (FLAGS_ipopt) { // Ipopt settings adapted from CaSaDi and FROST auto id = drake::solvers::IpoptSolver::id(); - solver_options.SetOption(id, "tol", tol); //NOLINT - solver_options.SetOption(id, "dual_inf_tol", tol); //NOLINT - solver_options.SetOption(id, "constr_viol_tol", tol); //NOLINT - solver_options.SetOption(id, "compl_inf_tol", tol); //NOLINT - solver_options.SetOption(id, "max_iter", 1e5); //NOLINT - solver_options.SetOption(id, "nlp_lower_bound_inf", -1e6); //NOLINT - solver_options.SetOption(id, "nlp_upper_bound_inf", 1e6); //NOLINT - solver_options.SetOption(id, "print_timing_statistics", "yes"); //NOLINT - solver_options.SetOption(id, "print_level", 5); //NOLINT - solver_options.SetOption(id, "output_file", "../ipopt.out"); //NOLINT - solver_options.SetOption(id, "acceptable_compl_inf_tol", tol); //NOLINT - solver_options.SetOption(id, "acceptable_constr_viol_tol", tol); //NOLINT - solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); //NOLINT - solver_options.SetOption(id, "acceptable_tol", 1e2); //NOLINT - solver_options.SetOption(id, "acceptable_iter", 5); //NOLINT + solver_options.SetOption(id, "tol", tol); // NOLINT + solver_options.SetOption(id, "dual_inf_tol", tol); // NOLINT + solver_options.SetOption(id, "constr_viol_tol", tol); // NOLINT + solver_options.SetOption(id, "compl_inf_tol", tol); // NOLINT + solver_options.SetOption(id, "max_iter", 1e5); // NOLINT + solver_options.SetOption(id, "nlp_lower_bound_inf", -1e6); // NOLINT + solver_options.SetOption(id, "nlp_upper_bound_inf", 1e6); // NOLINT + solver_options.SetOption(id, "print_timing_statistics", "yes"); // NOLINT + solver_options.SetOption(id, "print_level", 5); // NOLINT + solver_options.SetOption(id, "output_file", "../ipopt.out"); // NOLINT + solver_options.SetOption(id, "acceptable_compl_inf_tol", tol); // NOLINT + solver_options.SetOption(id, "acceptable_constr_viol_tol", tol); // NOLINT + solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); // NOLINT + solver_options.SetOption(id, "acceptable_tol", 1e2); // NOLINT + solver_options.SetOption(id, "acceptable_iter", 5); // NOLINT + solver_options.SetOption(id, "max_iter", 10000); // NOLINT } else { // Snopt settings auto id = drake::solvers::SnoptSolver::id(); - solver_options.SetOption(id, "Print file", "../snopt.out"); //NOLINT - solver_options.SetOption(id, "Major iterations limit", 1e5); //NOLINT - solver_options.SetOption(id, "Iterations limit", 100000); //NOLINT - solver_options.SetOption(id, "Verify level", 0); //NOLINT - solver_options.SetOption(id, "Major optimality tolerance", 1e-5); //NOLINT - solver_options.SetOption(id, "Solution", "No"); //NOLINT - solver_options.SetOption(id, "Major feasibility tolerance", tol); //NOLINT - -// prog.SetSolverOption(id, "Print file", "../snopt.out"); -// prog.SetSolverOption(id, "Major iterations limit", 1e5); -// prog.SetSolverOption(id, "Iterations limit", 100000); -// prog.SetSolverOption(id, "Verify level", 0); + solver_options.SetOption(id, "Print file", "../snopt.out"); // NOLINT + solver_options.SetOption(id, "Major iterations limit", 1e5); // NOLINT + solver_options.SetOption(id, "Iterations limit", 100000); // NOLINT + solver_options.SetOption(id, "Verify level", 0); // NOLINT + solver_options.SetOption(id, "Major optimality tolerance", 1e-5); // NOLINT + solver_options.SetOption(id, "Solution", "No"); // NOLINT + solver_options.SetOption(id, "Major feasibility tolerance", tol); // NOLINT + + // prog.SetSolverOption(id, "Print file", "../snopt.out"); + // prog.SetSolverOption(id, "Major iterations limit", 1e5); + // prog.SetSolverOption(id, "Iterations limit", 100000); + // prog.SetSolverOption(id, "Verify level", 0); // snopt doc said try 2 if seeing snopta exit 40 // prog.SetSolverOption(id, "Scale option", 2); -// prog.SetSolverOption(id, ); + // prog.SetSolverOption(id, ); // target nonlinear constraint violation -// prog.SetSolverOption(id, "Major optimality tolerance", 1e-5); + // prog.SetSolverOption(id, "Major optimality tolerance", 1e-5); // prog.SetSolverOption(id, "Major optimality tolerance", // 1e-5); // target complementarity gap -// prog.SetSolverOption(id, ); + // prog.SetSolverOption(id, ); } std::cout << "Adding kinematic constraints: " << std::endl; @@ -466,6 +467,9 @@ void SetKinematicConstraints(Dircon* trajopt, // position constraints prog->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, x_0(pos_map.at("base_x"))); + prog->AddBoundingBoxConstraint(FLAGS_distance + midpoint, + FLAGS_distance + midpoint, + x_f(pos_map.at("base_x"))); prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); @@ -744,24 +748,24 @@ void SetKinematicConstraints(Dircon* trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - // for (int index = 0; index < (mode_lengths[0] - 2); index++) { - // auto lambda = trajopt->force_vars(0, index); - // prog->AddLinearConstraint(lambda(2) >= 60); - // prog->AddLinearConstraint(lambda(5) >= 60); - // prog->AddLinearConstraint(lambda(8) >= 60); - // prog->AddLinearConstraint(lambda(11) >= 60); - // } + for (int index = 0; index < (mode_lengths[0] - 2); index++) { + auto lambda = trajopt->force_vars(0, index); + prog->AddLinearConstraint(lambda(2) >= 60); + prog->AddLinearConstraint(lambda(5) >= 60); + prog->AddLinearConstraint(lambda(8) >= 60); + prog->AddLinearConstraint(lambda(11) >= 60); + } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); - prog->AddLinearConstraint(lambda(2) <= FLAGS_input_delta * 350); - prog->AddLinearConstraint(lambda(5) <= FLAGS_input_delta * 350); - prog->AddLinearConstraint(lambda(8) <= FLAGS_input_delta * 350); - prog->AddLinearConstraint(lambda(11) <= FLAGS_input_delta * 350); - // prog->AddLinearConstraint(lambda(2) >= 50); - // prog->AddLinearConstraint(lambda(5) >= 50); - // prog->AddLinearConstraint(lambda(8) >= 50); - // prog->AddLinearConstraint(lambda(11) >= 50); + prog->AddLinearConstraint(lambda(2) <= 350); + prog->AddLinearConstraint(lambda(5) <= 350); + prog->AddLinearConstraint(lambda(8) <= 350); + prog->AddLinearConstraint(lambda(11) <= 350); + prog->AddLinearConstraint(lambda(2) >= 50); + prog->AddLinearConstraint(lambda(5) >= 50); + prog->AddLinearConstraint(lambda(8) >= 50); + prog->AddLinearConstraint(lambda(11) >= 50); } } @@ -807,45 +811,41 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, } l_r_pairs.pop_back(); - // double w_symmetry_pos = FLAGS_cost_scaling * 1e5; - // double w_symmetry_vel = FLAGS_cost_scaling * 1e2; - // double w_symmetry_u = FLAGS_cost_scaling * 1e2; - // for (const auto& l_r_pair : l_r_pairs) { - // for (const auto& sym_joint_name : sym_joint_names) { - // auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - - // x(pos_map.at(sym_joint_name + l_r_pair.second)); - // auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - // - - // x(vel_map.at(sym_joint_name + l_r_pair.second + - // "dot")); - // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - // if (sym_joint_name != "ankle_joint") { - // auto act_diff = - // u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - // u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); - // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - // } - // } - // } - // for (const auto& l_r_pair : l_r_pairs) { - // for (const auto& asy_joint_name : asy_joint_names) { - // auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + - // x(pos_map.at(asy_joint_name + l_r_pair.second)); - // auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) - // + - // x(vel_map.at(asy_joint_name + l_r_pair.second + - // "dot")); - // trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - // trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - // if (asy_joint_name != "ankle_joint") { - // auto act_diff = - // u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - // u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); - // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - // } - // } - // } + double w_symmetry_pos = FLAGS_cost_scaling * 1e5; + double w_symmetry_vel = FLAGS_cost_scaling * 1e2; + double w_symmetry_u = FLAGS_cost_scaling * 1e2; + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& sym_joint_name : sym_joint_names) { + auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - + x(pos_map.at(sym_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(sym_joint_name + l_r_pair.first + "dot")) - + x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (sym_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + } + } + } + for (const auto& l_r_pair : l_r_pairs) { + for (const auto& asy_joint_name : asy_joint_names) { + auto pos_diff = x(pos_map.at(asy_joint_name + l_r_pair.first)) + + x(pos_map.at(asy_joint_name + l_r_pair.second)); + auto vel_diff = x(vel_map.at(asy_joint_name + l_r_pair.first + "dot")) + + x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); + trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); + trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); + if (asy_joint_name != "ankle_joint") { + auto act_diff = + u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + } + } + } MatrixXd Q = FLAGS_cost_scaling * 0.02 * MatrixXd::Identity(n_v, n_v); // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); @@ -957,8 +957,8 @@ void AddCostsSprings(Dircon* trajopt, } l_r_pairs.pop_back(); - double w_symmetry_pos = 1e3; - double w_symmetry_vel = 1e1; + double w_symmetry_pos = FLAGS_cost_scaling * 1e3; + double w_symmetry_vel = FLAGS_cost_scaling * 1e1; for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - @@ -971,10 +971,8 @@ void AddCostsSprings(Dircon* trajopt, } std::cout << "n_v_: " << n_v << std::endl; - MatrixXd Q = 0.01 * MatrixXd::Identity(n_v, n_v); - MatrixXd R = 1e-4 * MatrixXd::Identity(n_u, n_u); - Q *= FLAGS_cost_scaling; - R *= FLAGS_cost_scaling; + MatrixXd Q = FLAGS_cost_scaling * 0.01 * MatrixXd::Identity(n_v, n_v); + MatrixXd R = FLAGS_cost_scaling * 1e-4 * MatrixXd::Identity(n_u, n_u); trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); trajopt->AddRunningCost(u.transpose() * R * u); @@ -993,11 +991,10 @@ void AddCostsSprings(Dircon* trajopt, vel_map["ankle_spring_joint_leftdot"]) = 0.0; W(vel_map["ankle_spring_joint_rightdot"], vel_map["ankle_spring_joint_rightdot"]) = 0.0; - W *= FLAGS_cost_scaling; vector> joint_accel_costs; for (int mode : {0, 1, 2}) { joint_accel_costs.push_back(std::make_shared( - W, plant, &constraints->mode(mode).evaluators())); + FLAGS_cost_scaling * W, plant, &constraints->mode(mode).evaluators())); for (int index = 0; index < mode_lengths[mode]; index++) { // Assumes mode_lengths are the same across modes auto x_i = trajopt->state_vars(mode, index); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1f43ca0581..4bf7ac8008 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -170,7 +170,8 @@ int DoMain(int argc, char* argv[]) { osc_gains.flight_duration); /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); +// drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm; auto state_receiver = builder.AddSystem(plant); auto command_pub = diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 3c53fbf6ae..e0e50947b3 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -107,7 +107,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_local; // auto osc_gains = // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); drake::yaml::LoadYamlOptions yaml_options; From 2ca75b1da2dc7cbbe2b4171f5c9ec8807e18f415 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Sep 2022 11:19:18 -0400 Subject: [PATCH 299/758] removing lambda weight on standing --- examples/Cassie/osc/osc_standing_gains.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 1a740a8955..41aa9a9437 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -10,7 +10,7 @@ rows: 3 cols: 3 w_input: 0.0 w_accel: 0.001 -w_lambda: 0.000001 +w_lambda: 0.000000 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, # 1, 1, 1, 1, 0.01, 0.001 ] From fce04e3f6f2c7ecf31b197c613b04921aebf0177 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Sep 2022 11:38:49 -0400 Subject: [PATCH 300/758] reverting lcm change again --- .../state_based_controller_switch.cc | 2 +- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 2 +- examples/Cassie/run_controller_switch.cc | 6 +++--- examples/Cassie/run_dircon_jumping.cc | 16 +++++++++++++++- examples/Cassie/run_osc_running_controller.cc | 3 +-- examples/Cassie/run_osc_standing_controller.cc | 2 +- 7 files changed, 23 insertions(+), 10 deletions(-) diff --git a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc index ced37ff3da..2873fc7348 100644 --- a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc +++ b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc @@ -54,7 +54,7 @@ int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Parameters - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // Build the diagram drake::systems::DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 17d2124ee3..4e917cef52 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -67,7 +67,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); DiagramBuilder builder; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 2e1bc967d3..0975271983 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -159,7 +159,7 @@ int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); DiagramBuilder builder; - auto lcm = builder.AddSystem(); + auto lcm = builder.AddSystem("udpm://239.255.76.67:7667?ttl=0"); drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); // Build Cassie MBP diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index 6b0cf9dae8..68032c1f44 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -81,7 +81,7 @@ int do_main(int argc, char* argv[]) { // Build the diagram drake::systems::DiagramBuilder builder; - auto lcm = builder.AddSystem(); + auto lcm = builder.AddSystem("udpm://239.255.76.67:7667?ttl=0"); auto name_pub = builder.AddSystem( LcmPublisherSystem::Make( FLAGS_switch_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -107,8 +107,8 @@ int do_main(int argc, char* argv[]) { double t_threshold = t0; if (FLAGS_n_period_delay > 0) { t_threshold = (floor(t0 / FLAGS_fsm_period) + FLAGS_n_period_delay) * - FLAGS_fsm_period + - FLAGS_fsm_offset; + FLAGS_fsm_period + + FLAGS_fsm_offset; } // Create output message dairlib::lcmt_controller_switch msg; diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 703969c835..2602024724 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -314,7 +314,6 @@ void DoMain() { solver_options.SetOption(id, "dual_inf_tol", tol); // NOLINT solver_options.SetOption(id, "constr_viol_tol", tol); // NOLINT solver_options.SetOption(id, "compl_inf_tol", tol); // NOLINT - solver_options.SetOption(id, "max_iter", 1e5); // NOLINT solver_options.SetOption(id, "nlp_lower_bound_inf", -1e6); // NOLINT solver_options.SetOption(id, "nlp_upper_bound_inf", 1e6); // NOLINT solver_options.SetOption(id, "print_timing_statistics", "yes"); // NOLINT @@ -464,6 +463,21 @@ void SetKinematicConstraints(Dircon* trajopt, double midpoint = 0.045; + // bounding box constraints on all decision variables + for (int i = 0; i < mode_lengths.size(); ++i) { + for (int j = 0; j < mode_lengths[i]; ++i) { + // auto state_vars_ij = trajopt->state_vars(i, j); + // auto input_vars_ij = trajopt->input_vars(i, j); + auto force_vars_ij = trajopt->force_vars(i, j); + prog->AddBoundingBoxConstraint(VectorXd::Constant(force_vars_ij.rows(), -200), + VectorXd::Constant(force_vars_ij.rows(), 200), + force_vars_ij); + prog->AddBoundingBoxConstraint(VectorXd::Constant(force_vars_ij.rows(), -200), + VectorXd::Constant(force_vars_ij.rows(), 200), + force_vars_ij); + } + } + // position constraints prog->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, x_0(pos_map.at("base_x"))); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 4bf7ac8008..1f43ca0581 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -170,8 +170,7 @@ int DoMain(int argc, char* argv[]) { osc_gains.flight_duration); /**** Initialize all the leaf systems ****/ -// drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - drake::lcm::DrakeLcm lcm; + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant); auto command_pub = diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index e0e50947b3..3c53fbf6ae 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -107,7 +107,7 @@ int DoMain(int argc, char* argv[]) { // Build the controller diagram DiagramBuilder builder; - drake::lcm::DrakeLcm lcm_local; + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); // auto osc_gains = // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); drake::yaml::LoadYamlOptions yaml_options; From e6a5dc12967029dd836096fe5bd56625524814ef Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Sep 2022 13:02:32 -0400 Subject: [PATCH 301/758] changing some scaling --- examples/Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 15 ++++++++------- examples/Cassie/urdf/cassie_v2_conservative.urdf | 4 ++-- .../controllers/osc/operational_space_control.cc | 6 +++--- .../controllers/osc/operational_space_control.h | 4 ++-- 5 files changed, 16 insertions(+), 15 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index f72d21f231..edcd6c8ca2 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -86,7 +86,7 @@ SwingFootW: SwingFootKp: [125, 0, 0, 0, 75, 0, - 0, 0, 150] + 0, 0, 75] SwingFootKd: [5., 0, 0, 0, 5., 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1f43ca0581..ef16553dea 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -201,7 +201,7 @@ int DoMain(int argc, char* argv[]) { /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * - osc_gains.W_input_regularization); + osc_gains.W_input_regularization); osc->SetInputSmoothingConstraintWeights(osc_gains.w_input_accel); osc->SetInputCostWeights(osc_gains.w_input * osc_gains.W_input_regularization); @@ -427,11 +427,12 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial foot_traj_weight_trajectory = PiecewisePolynomial::FirstOrderHold( - {0, 0.25 + 0.2}, {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)}); + {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, + {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)}); PiecewisePolynomial foot_traj_gain_trajectory = PiecewisePolynomial::FirstOrderHold( - {0, 0.25 + 0.2}, - {0.5 * MatrixXd::Identity(3, 3), 3.0 * MatrixXd::Identity(3, 3)}); + {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, + {0.5 * MatrixXd::Identity(3, 3), 2.0 * MatrixXd::Identity(3, 3)}); // PiecewisePolynomial foot_traj_weight_trajectory = // PiecewisePolynomial::FirstOrderHold( // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); @@ -478,7 +479,7 @@ int DoMain(int argc, char* argv[]) { pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - if(osc_gains.rot_filter_tau > 0){ + if (osc_gains.rot_filter_tau > 0) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {0, 1, 2}); } @@ -554,12 +555,12 @@ int DoMain(int argc, char* argv[]) { builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); - if (osc_gains.ekf_filter_tau[0] > 0){ + if (osc_gains.ekf_filter_tau[0] > 0) { builder.Connect(state_receiver->get_output_port(0), ekf_filter->get_input_port()); builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); - }else{ + } else { builder.Connect(state_receiver->get_output_port(0), osc->get_robot_output_input_port()); } diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index b7120290d5..86fc8e7e3a 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -784,7 +784,7 @@ - + @@ -793,7 +793,7 @@ - + diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index bd6cc1918f..dd6189c20f 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -447,7 +447,7 @@ void OperationalSpaceControl::Build() { } // 5. Joint Limit cost - K_joint_pos = w_joint_limit_ * W_joint_accel_.bottomRightCorner( + K_joint_pos_ = w_joint_limit_ * W_joint_accel_.bottomRightCorner( n_revolute_joints_, n_revolute_joints_); joint_limit_cost_ = prog_ ->AddLinearCost(VectorXd::Zero(n_revolute_joints_), 0, @@ -717,11 +717,11 @@ VectorXd OperationalSpaceControl::SolveQp( // Add joint limit constraints VectorXd w_joint_limit = - K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) + K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) .tail(n_revolute_joints_) - q_max_) .cwiseMax(0) + - K_joint_pos * (x_wo_spr.head(plant_wo_spr_.num_positions()) + K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) .tail(n_revolute_joints_) - q_min_) .cwiseMin(0); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index d900132b5d..66e680b492 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -311,8 +311,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::VectorXd q_max_; // robot joint limits - Eigen::MatrixXd K_joint_pos; - Eigen::MatrixXd K_joint_vel; + Eigen::MatrixXd K_joint_pos_; + Eigen::MatrixXd K_joint_vel_; // flag indicating whether using osc with finite state machine or not bool used_with_finite_state_machine_; From fbbf20595ade21685e9fd1f3d864b77599fa07b2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Sep 2022 13:21:51 -0400 Subject: [PATCH 302/758] updating gains --- examples/Cassie/osc/osc_standing_gains.yaml | 18 +++++++++--------- examples/Cassie/osc_run/foot_traj_generator.cc | 4 +--- examples/Cassie/osc_run/osc_running_gains.yaml | 10 +++++----- 3 files changed, 15 insertions(+), 17 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 41aa9a9437..ce723b453a 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -30,7 +30,7 @@ w_soft_constraint: 100 w_input_reg: 0.00 impact_threshold: 0.00 center_of_mass_filter_tau: 0.001 -rot_filter_tau: 0.01 +rot_filter_tau: 0.05 center_of_mass_command_filter_alpha: 0.05 orientation_command_filter_alpha: 0.0005 impact_tau: 0.00 @@ -40,16 +40,16 @@ HipYawKp: 40 HipYawKd: 5 HipYawW: 0 PelvisW: - [20, 0, 0, + [1, 0, 0, 0, 2, 0, 0, 0, 10] PelvisKp: - [100, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 75] PelvisKd: - [ 1, 0, 0, - 0, 1, 0, + [ 0.1, 0, 0, + 0, 0.1, 0, 0, 0, 1] PelvisRotW: [5, 0, 0, @@ -57,11 +57,11 @@ PelvisRotW: 0, 0, 1] PelvisRotKp: [25, 0, 0, - 0, 50, 0, + 0, 10, 0, 0, 0, 50] PelvisRotKd: - [0.1, 0, 0, - 0, 10, 0, - 0, 0, 1] + [0, 0, 0, + 0, 0.1, 0, + 0, 0, 0.1] diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index ffab5a16d3..d98d207e5b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -232,11 +232,9 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[0](2) = -rest_length_; } // Y[0](2) -= rest_length_offset_; - // Y[1] = start_pos + 0.8 * foot_end_pos_des; - Y[1] = start_pos + 0.75 * (foot_end_pos_des - start_pos); + Y[1] = start_pos + 0.8 * (foot_end_pos_des - start_pos); Y[1](2) += mid_foot_height_; Y[2] = foot_end_pos_des; -// Y[2](2) = -rest_length_ - rest_length_offset_; // corrections if (is_left_foot_) { diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index edcd6c8ca2..8c028b788e 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -49,7 +49,7 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.03 -footstep_lateral_offset: 0.07 # drake +footstep_lateral_offset: 0.1 # drake mid_foot_height: 0.15 FootstepKd: [ 0.13, 0, 0, @@ -68,7 +68,7 @@ PelvisKd: 0, 2, 0, 0, 0, 5 ] PelvisRotW: - [0.1, 0, 0, + [0.2, 0, 0, 0, 5, 0, 0, 0, 0.1] PelvisRotKp: @@ -76,8 +76,8 @@ PelvisRotKp: 0, 100., 0, 0, 0, 0.] PelvisRotKd: - [5., 0, 0, - 0, 5., 0, + [0.5, 0, 0, + 0, 2., 0, 0, 0, 5.] SwingFootW: [10, 0, 0, @@ -86,7 +86,7 @@ SwingFootW: SwingFootKp: [125, 0, 0, 0, 75, 0, - 0, 0, 75] + 0, 0, 150] SwingFootKd: [5., 0, 0, 0, 5., 0, From acc28e178f8ce1b52bd857d110854876e6771268 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 2 Sep 2022 09:44:33 -0400 Subject: [PATCH 303/758] drawing diagrams --- .../pydairlib/analysis/mbp_plotting_utils.py | 6 --- .../plot_configs/cassie_running_plot.yaml | 6 +-- examples/Cassie/BUILD.bazel | 3 ++ .../osc_running_controller_diagram.cc | 6 +-- examples/Cassie/dispatcher_robot_in.cc | 4 +- examples/Cassie/dispatcher_robot_out.cc | 3 ++ examples/Cassie/osc/osc_standing_gains.yaml | 42 +++++++++---------- .../Cassie/osc_run/osc_running_gains.yaml | 18 ++++---- examples/Cassie/run_osc_running_controller.cc | 22 +++++----- .../Cassie/run_osc_standing_controller.cc | 2 + 10 files changed, 57 insertions(+), 55 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 5fc2a6fdb2..22cb064b87 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -383,12 +383,6 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): ylabel='Efforts (Nm)', title='Select Joint Efforts') -def plot_commanded_efforts(robot_input, u_names, time_slice): - return plot_u_cmd(robot_input, 'u', u_names, slice(len(u_names)), - time_slice, ylabel='Efforts (Nm)', - title='Commanded Joint Efforts') - - def plot_points_positions(robot_output, time_slice, plant, context, frame_names, pts, dims): dim_map = ['_x', '_y', '_z'] diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index bfa051e95b..cec7eba206 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -7,7 +7,7 @@ use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) start_time: 1 -duration: 2 +duration: 7 # Plant properties use_springs: true @@ -49,8 +49,8 @@ tracking_datas_to_plot: { # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, - left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 6d17b03745..bec639c45d 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -261,6 +261,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -280,6 +281,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/controllers:linear_controller", "//systems/controllers:pd_config_lcm", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -440,6 +442,7 @@ cc_binary( "//systems/controllers/osc:osc_gains", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index d53d4d2f64..55497a2bc7 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -177,8 +177,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.AddSystem( control_channel_name_, 1); std::vector tau = {.05, .01, .01}; - auto ekf_filter = - builder.AddSystem(plant, tau); +// auto ekf_filter = +// builder.AddSystem(plant, tau); /**** OSC setup ****/ // Cost @@ -452,8 +452,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->get_input_port_clock()); builder.Connect(state_receiver->get_output_port(0), - ekf_filter->get_input_port()); - builder.Connect(ekf_filter->get_output_port(), osc->get_robot_output_input_port()); // FSM connections builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 4e917cef52..2b699691c9 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -15,6 +15,8 @@ #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + #include "drake/lcm/drake_lcm.h" #include "drake/systems/framework/diagram.h" @@ -222,7 +224,7 @@ int do_main(int argc, char* argv[]) { &(loop.get_diagram()->GetMutableSubsystemContext( *config_receiver, &loop.get_diagram_mutable_context())), msg); - + DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); return 0; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 0975271983..5b4f7b05d5 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -17,6 +17,7 @@ #include "systems/framework/output_vector.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/lcm/drake_lcm.h" #include "drake/solvers/choose_best_solver.h" @@ -318,7 +319,9 @@ int do_main(int argc, char* argv[]) { // Create the diagram, simulator, and context. auto owned_diagram = builder.Build(); + owned_diagram->set_name(("dispatcher_robot_out")); const auto& diagram = *owned_diagram; + DrawAndSaveDiagramGraph(diagram); drake::systems::Simulator simulator(std::move(owned_diagram)); auto& diagram_context = simulator.get_mutable_context(); diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index ce723b453a..fb5054344d 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -9,7 +9,7 @@ rows: 3 cols: 3 w_input: 0.0 -w_accel: 0.001 +w_accel: 0.000 w_lambda: 0.000000 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, @@ -29,8 +29,8 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, w_soft_constraint: 100 w_input_reg: 0.00 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.001 -rot_filter_tau: 0.05 +center_of_mass_filter_tau: 0.0001 +rot_filter_tau: 0.001 center_of_mass_command_filter_alpha: 0.05 orientation_command_filter_alpha: 0.0005 impact_tau: 0.00 @@ -40,28 +40,28 @@ HipYawKp: 40 HipYawKd: 5 HipYawW: 0 PelvisW: - [1, 0, 0, - 0, 2, 0, - 0, 0, 10] + [ 1, 0, 0, + 0, 2, 0, + 0, 0, 2 ] PelvisKp: - [50, 0, 0, - 0, 50, 0, - 0, 0, 75] + [ 50, 0, 0, + 0, 50, 0, + 0, 0, 75 ] PelvisKd: - [ 0.1, 0, 0, - 0, 0.1, 0, - 0, 0, 1] + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] PelvisRotW: - [5, 0, 0, - 0, 5, 0, - 0, 0, 1] + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 1 ] PelvisRotKp: - [25, 0, 0, - 0, 10, 0, - 0, 0, 50] + [ 25, 0, 0, + 0, 75, 0, + 0, 0, 50 ] PelvisRotKd: - [0, 0, 0, - 0, 0.1, 0, - 0, 0, 0.1] + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 8c028b788e..c70bda5f73 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -30,7 +30,7 @@ ekf_filter_tau: [ 0.001, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -2 -vel_scale_trans_sagital: 0.5 +vel_scale_trans_sagital: 1.0 vel_scale_trans_lateral: -0.1 # SLIP parameters @@ -49,15 +49,15 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.03 -footstep_lateral_offset: 0.1 # drake +footstep_lateral_offset: 0.07 # drake mid_foot_height: 0.15 FootstepKd: [ 0.13, 0, 0, - 0, 0.13, 0, + 0, 0.17, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, - 0, 1, 0, + 0, 0.1, 0, 0, 0, 5 ] PelvisKp: [ 0, 0, 0, @@ -68,16 +68,16 @@ PelvisKd: 0, 2, 0, 0, 0, 5 ] PelvisRotW: - [0.2, 0, 0, + [1, 0, 0, 0, 5, 0, 0, 0, 0.1] PelvisRotKp: - [50., 0, 0, - 0, 100., 0, + [150., 0, 0, + 0, 200., 0, 0, 0, 0.] PelvisRotKd: - [0.5, 0, 0, - 0, 2., 0, + [10, 0, 0, + 0, 10, 0, 0, 0, 5.] SwingFootW: [10, 0, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index ef16553dea..0880052a8f 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -193,8 +193,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( "CONTACT_TIMING", &lcm, TriggerTypeSet({TriggerType::kForced}))); // std::vector tau = {.05, .01, .01}; - auto ekf_filter = builder.AddSystem( - plant, osc_gains.ekf_filter_tau); +// auto ekf_filter = builder.AddSystem( +// plant, osc_gains.ekf_filter_tau); /**** OSC setup ****/ // Cost @@ -555,15 +555,15 @@ int DoMain(int argc, char* argv[]) { builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); - if (osc_gains.ekf_filter_tau[0] > 0) { - builder.Connect(state_receiver->get_output_port(0), - ekf_filter->get_input_port()); - builder.Connect(ekf_filter->get_output_port(), - osc->get_robot_output_input_port()); - } else { - builder.Connect(state_receiver->get_output_port(0), - osc->get_robot_output_input_port()); - } +// if (osc_gains.ekf_filter_tau[0] > 0) { +// builder.Connect(state_receiver->get_output_port(0), +// ekf_filter->get_input_port()); +// builder.Connect(ekf_filter->get_output_port(), +// osc->get_robot_output_input_port()); +// } else { + builder.Connect(state_receiver->get_output_port(0), + osc->get_robot_output_input_port()); +// } // FSM connections builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 3c53fbf6ae..686d04af64 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -21,6 +21,7 @@ #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" @@ -296,6 +297,7 @@ int DoMain(int argc, char* argv[]) { systems::LcmDrivenLoop loop( &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); From 99719d56498bd7a6743566f3d63d2807b6069213 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 2 Sep 2022 09:50:42 -0400 Subject: [PATCH 304/758] adding standing gains for sim --- examples/Cassie/osc/osc_standing_gains.yaml | 42 ++++++------ .../Cassie/osc/osc_standing_gains_sim.yaml | 67 +++++++++++++++++++ .../osc_run/osc_running_qp_settings.yaml | 2 +- 3 files changed, 89 insertions(+), 22 deletions(-) create mode 100644 examples/Cassie/osc/osc_standing_gains_sim.yaml diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index fb5054344d..ce723b453a 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -9,7 +9,7 @@ rows: 3 cols: 3 w_input: 0.0 -w_accel: 0.000 +w_accel: 0.001 w_lambda: 0.000000 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, @@ -29,8 +29,8 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, w_soft_constraint: 100 w_input_reg: 0.00 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.0001 -rot_filter_tau: 0.001 +center_of_mass_filter_tau: 0.001 +rot_filter_tau: 0.05 center_of_mass_command_filter_alpha: 0.05 orientation_command_filter_alpha: 0.0005 impact_tau: 0.00 @@ -40,28 +40,28 @@ HipYawKp: 40 HipYawKd: 5 HipYawW: 0 PelvisW: - [ 1, 0, 0, - 0, 2, 0, - 0, 0, 2 ] + [1, 0, 0, + 0, 2, 0, + 0, 0, 10] PelvisKp: - [ 50, 0, 0, - 0, 50, 0, - 0, 0, 75 ] + [50, 0, 0, + 0, 50, 0, + 0, 0, 75] PelvisKd: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 10 ] + [ 0.1, 0, 0, + 0, 0.1, 0, + 0, 0, 1] PelvisRotW: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 1 ] + [5, 0, 0, + 0, 5, 0, + 0, 0, 1] PelvisRotKp: - [ 25, 0, 0, - 0, 75, 0, - 0, 0, 50 ] + [25, 0, 0, + 0, 10, 0, + 0, 0, 50] PelvisRotKd: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 10 ] + [0, 0, 0, + 0, 0.1, 0, + 0, 0, 0.1] diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml new file mode 100644 index 0000000000..fb5054344d --- /dev/null +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -0,0 +1,67 @@ +# Set xy PD gains so they do not effect passive LIPM dynamics at capture +# point, when x = sqrt(l/g) * xdot +# Passive dynamics: xddot = g/l * x +# +# -Kp * x - Kd * xdot = +# -Kp * x + Kd * sqrt(g/l) * x = g/l * x +# Kp = sqrt(g/l) * Kd - g/l + +rows: 3 +cols: 3 +w_input: 0.0 +w_accel: 0.000 +w_lambda: 0.000000 +#W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, +# 1, 1, 1, 1, 0.01, 0.001, +# 1, 1, 1, 1, 0.01, 0.001 ] +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] +W_input_reg: [ 1, 0.9, 0.6, 0.3, 5, + 1, 0.9, 0.5, 0.1, 5 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01 ] +#W_lambda_h_reg: [ 0.02, 0.02 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.002, 0.002 ] +w_soft_constraint: 100 +w_input_reg: 0.00 +impact_threshold: 0.00 +center_of_mass_filter_tau: 0.0001 +rot_filter_tau: 0.001 +center_of_mass_command_filter_alpha: 0.05 +orientation_command_filter_alpha: 0.0005 +impact_tau: 0.00 +mu: 0.6 +weight_scaling: 1.0 +HipYawKp: 40 +HipYawKd: 5 +HipYawW: 0 +PelvisW: + [ 1, 0, 0, + 0, 2, 0, + 0, 0, 2 ] +PelvisKp: + [ 50, 0, 0, + 0, 50, 0, + 0, 0, 75 ] +PelvisKd: + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] +PelvisRotW: + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 1 ] +PelvisRotKp: + [ 25, 0, 0, + 0, 75, 0, + 0, 0, 50 ] +PelvisRotKd: + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] + + diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 7d134ca996..d9428063c2 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.0001 sigma: 1e-6 -max_iter: 150 +max_iter: 500 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 From 651fc07f170fd3b17e7c24977710a727d64e7649 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 2 Sep 2022 11:07:50 -0400 Subject: [PATCH 305/758] updating gains --- .../Cassie/osc_run/osc_running_gains.yaml | 22 +++++++++---------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c70bda5f73..a9c35e56ce 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -39,7 +39,7 @@ rest_length_offset: 0.05 stance_duration: 0.3 flight_duration: 0.09 -w_swing_toe: 1 +w_swing_toe: 0.001 swing_toe_kp: 1000 swing_toe_kd: 10 @@ -58,7 +58,7 @@ FootstepKd: PelvisW: [ 0, 0, 0, 0, 0.1, 0, - 0, 0, 5 ] + 0, 0, 5] PelvisKp: [ 0, 0, 0, 0, 40, 0, @@ -68,7 +68,7 @@ PelvisKd: 0, 2, 0, 0, 0, 5 ] PelvisRotW: - [1, 0, 0, + [10, 0, 0, 0, 5, 0, 0, 0, 0.1] PelvisRotKp: @@ -84,8 +84,8 @@ SwingFootW: 0, 100, 0, 0, 0, 10] SwingFootKp: - [125, 0, 0, - 0, 75, 0, + [125, 0, 0, + 0, 75, 0, 0, 0, 150] SwingFootKd: [5., 0, 0, @@ -96,10 +96,10 @@ LiftoffSwingFootW: 0, 0, 0, 0, 0, 0] LiftoffSwingFootKp: - [25, 0, 0, - 0, 50, 0, - 0, 0, 35] + [0, 0, 0, + 0, 0, 0, + 0, 0, 0] LiftoffSwingFootKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 1] + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 0] From 17b0916272b06a75550baa57ce5db3f1068369e9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 4 Sep 2022 19:28:55 -0400 Subject: [PATCH 306/758] relaxing toe actuator limits --- examples/Cassie/urdf/cassie_v2_conservative.urdf | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/Cassie/urdf/cassie_v2_conservative.urdf b/examples/Cassie/urdf/cassie_v2_conservative.urdf index 86fc8e7e3a..b7120290d5 100644 --- a/examples/Cassie/urdf/cassie_v2_conservative.urdf +++ b/examples/Cassie/urdf/cassie_v2_conservative.urdf @@ -784,7 +784,7 @@ - + @@ -793,7 +793,7 @@ - + From 0fa7ebdcc0d42565bd7211030d4512fd839aacb5 Mon Sep 17 00:00:00 2001 From: dair Date: Tue, 6 Sep 2022 13:06:19 -0400 Subject: [PATCH 307/758] add video logging script --- record_video.py | 36 ++++++++++++++++++++++++++++++++++++ 1 file changed, 36 insertions(+) create mode 100644 record_video.py diff --git a/record_video.py b/record_video.py new file mode 100644 index 0000000000..17dcc21091 --- /dev/null +++ b/record_video.py @@ -0,0 +1,36 @@ +import subprocess +import sys +import os +import glob +from datetime import date +def main(): + curr_date = date.today().strftime("%m_%d_%y") + year = date.today().strftime("%Y") + logdir = f"{os.getenv('HOME')}/Videos/cassie_experiments/{year}/{curr_date}/" + os.makedirs(logdir, exist_ok=True) + current_logs = sorted(glob.glob(logdir + 'log_*')) + if current_logs: + last_log = int(current_logs[-1].split('_')[-1].split('.')[0]) + log_num = f'{last_log+1:02}' + else: + log_num = '00' + print(log_num) + print(current_logs) + experiment_name = logdir + 'log_' + log_num + '.mp4' + cmd = 'v4l2-ctl --list-devices'.split(' ') + process = subprocess.check_output(cmd) + lines = process.decode("utf-8").split('\n') + dev_name = '' + for i, line in enumerate(lines): + if 'HD' in line: + dev_name = lines[i+1].split('\t')[1] + print(dev_name) + cmds = ('ffmpeg -y -f alsa -i default -i ' + dev_name + ' -vcodec libx264 -acodec aac -qp 0').split(' ') + cmds.append(experiment_name) + print(cmds) + print(' '.join(cmds)) + # import pdb; pdb.set_trace() + subprocess.run(cmds) + +if __name__ == '__main__': + main() From 56a9eba664f7bf9bc240bb63548172dbc3834a22 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 8 Sep 2022 11:21:18 -0400 Subject: [PATCH 308/758] adding command filter --- examples/Cassie/osc/osc_standing_gains_sim.yaml | 2 +- examples/Cassie/osc_run/foot_traj_generator.cc | 6 +++++- examples/Cassie/osc_run/foot_traj_generator.h | 8 ++++++++ examples/Cassie/osc_run/osc_running_gains.h | 2 ++ examples/Cassie/osc_run/osc_running_gains.yaml | 11 ++++++----- examples/Cassie/run_osc_running_controller.cc | 2 ++ 6 files changed, 24 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index fb5054344d..d6f17ec0a6 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -26,7 +26,7 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, #W_lambda_h_reg: [ 0.02, 0.02 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] -w_soft_constraint: 100 +w_soft_constraint: 0 w_input_reg: 0.00 impact_threshold: 0.00 center_of_mass_filter_tau: 0.0001 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index d98d207e5b..22c09ebc55 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -45,6 +45,8 @@ FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, stance_state_(stance_state) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; + target_vel_filter_ = + std::make_unique(1.0, 2); if (foot_name == "toe_left") { is_left_foot_ = true; @@ -194,7 +196,9 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // with OSU DRL Vector3d desired_pelvis_vel; - desired_pelvis_vel << desired_pelvis_vel_xy, 0; + target_vel_filter_->Update(desired_pelvis_vel_xy); + desired_pelvis_vel << target_vel_filter_->Value(), 0; + auto foot_pos = context.get_discrete_state(initial_foot_pos_idx_).get_value(); Vector3d pelvis_pos; plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index a36efcc46e..dd94a84218 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -6,6 +6,7 @@ #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" +#include "common/discrete_time_filter.h" namespace dairlib::examples::osc_run { @@ -35,6 +36,10 @@ class FootTrajGenerator : public drake::systems::LeafSystem { return this->get_input_port(contact_scheduler_port_); } + void SetCommandFilter(double alpha){ + target_vel_filter_->UpdateParameters(alpha); + } + void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; void SetFootPlacementOffsets(double rest_length, double rest_length_offset, double center_line_offset, @@ -92,6 +97,9 @@ class FootTrajGenerator : public drake::systems::LeafSystem { int pelvis_yaw_idx_; int pelvis_vel_est_idx_; int last_stance_timestamp_idx_; + + std::unique_ptr target_vel_filter_; + }; } // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 07340c65b9..8ed4b1e090 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -24,6 +24,7 @@ struct OSCRunningGains : OSCGains { double vel_scale_rot; double vel_scale_trans_sagital; double vel_scale_trans_lateral; + double target_vel_filter_alpha; bool relative_feet; bool relative_pelvis; double rest_length; @@ -121,6 +122,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(vel_scale_rot)); a->Visit(DRAKE_NVP(vel_scale_trans_sagital)); a->Visit(DRAKE_NVP(vel_scale_trans_lateral)); + a->Visit(DRAKE_NVP(target_vel_filter_alpha)); W_swing_foot = Eigen::Map< Eigen::Matrix>( diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index a9c35e56ce..3d774f126f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,7 +4,7 @@ w_accel: 0.0001 w_soft_constraint: 1000 w_lambda: 0.1 w_input_accel: 0.1 -w_joint_limit: 50 +w_joint_limit: 0 impact_threshold: 0.050 impact_tau: 0.005 weight_scaling: 1.0 @@ -32,15 +32,16 @@ ekf_filter_tau: [ 0.001, 0.01, 0.001 ] vel_scale_rot: -2 vel_scale_trans_sagital: 1.0 vel_scale_trans_lateral: -0.1 +target_vel_filter_alpha: 0.25 # SLIP parameters rest_length: 0.85 -rest_length_offset: 0.05 +rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 w_swing_toe: 0.001 -swing_toe_kp: 1000 +swing_toe_kp: 1500 swing_toe_kd: 10 w_hip_yaw: 2.5 @@ -70,7 +71,7 @@ PelvisKd: PelvisRotW: [10, 0, 0, 0, 5, 0, - 0, 0, 0.1] + 0, 0, 1] PelvisRotKp: [150., 0, 0, 0, 200., 0, @@ -86,7 +87,7 @@ SwingFootW: SwingFootKp: [125, 0, 0, 0, 75, 0, - 0, 0, 150] + 0, 0, 75] SwingFootKd: [5., 0, 0, 0, 5., 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 0880052a8f..7818b4a875 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -312,6 +312,8 @@ int DoMain(int argc, char* argv[]) { osc_gains.rest_length, osc_gains.rest_length_offset, osc_gains.footstep_lateral_offset, osc_gains.footstep_sagital_offset, osc_gains.mid_foot_height); + l_foot_traj_generator->SetCommandFilter(osc_gains.target_vel_filter_alpha); + r_foot_traj_generator->SetCommandFilter(osc_gains.target_vel_filter_alpha); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, From 10d518a09bd6049b4e487c95919298599700fd59 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 8 Sep 2022 14:07:06 -0400 Subject: [PATCH 309/758] updating filter to commands --- .../Cassie/osc_run/osc_running_gains.yaml | 6 +- .../osc_run/osc_running_qp_settings.yaml | 2 +- .../osc_run/pelvis_trans_traj_generator.cc | 4 +- .../osc/operational_space_control.cc | 81 ++++++++++--------- .../osc/operational_space_control.h | 16 ++-- 5 files changed, 58 insertions(+), 51 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 3d774f126f..ba10d79c8f 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -32,7 +32,7 @@ ekf_filter_tau: [ 0.001, 0.01, 0.001 ] vel_scale_rot: -2 vel_scale_trans_sagital: 1.0 vel_scale_trans_lateral: -0.1 -target_vel_filter_alpha: 0.25 +target_vel_filter_alpha: 0.001 # SLIP parameters rest_length: 0.85 @@ -54,11 +54,11 @@ footstep_lateral_offset: 0.07 # drake mid_foot_height: 0.15 FootstepKd: [ 0.13, 0, 0, - 0, 0.17, 0, + 0, 0.25, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, - 0, 0.1, 0, + 0, 1, 0, 0, 0, 5] PelvisKp: [ 0, 0, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index d9428063c2..b548c7d8b1 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -8,7 +8,7 @@ eps_dual_inf: 1e-5 alpha: 1.6 linsys_solver: 0 delta: 1e-6 -polish: 0 +polish: 1 polish_refine_iter: 0 verbose: 0 scaled_termination: 1 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index f2c067483e..6acc6ec391 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -130,9 +130,9 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( // breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); double y_dist_des = 0; if (fsm_state == 0) { - y_dist_des = -0.15; + y_dist_des = -0.1; } else if (fsm_state == 1) { - y_dist_des = 0.15; + y_dist_des = 0.1; } // samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + rest_length_offset_; samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index dd6189c20f..9fd10babbb 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -447,13 +447,15 @@ void OperationalSpaceControl::Build() { } // 5. Joint Limit cost - K_joint_pos_ = w_joint_limit_ * W_joint_accel_.bottomRightCorner( - n_revolute_joints_, n_revolute_joints_); - joint_limit_cost_ = prog_ - ->AddLinearCost(VectorXd::Zero(n_revolute_joints_), 0, - dv_.tail(n_revolute_joints_)) - .evaluator() - .get(); + if (w_joint_limit_ > 0) { + K_joint_pos_ = w_joint_limit_ * W_joint_accel_.bottomRightCorner( + n_revolute_joints_, n_revolute_joints_); + joint_limit_cost_ = prog_ + ->AddLinearCost(VectorXd::Zero(n_revolute_joints_), + 0, dv_.tail(n_revolute_joints_)) + .evaluator() + .get(); + } // (Testing) 6. contact force blending if (ds_duration_ > 0) { @@ -490,8 +492,10 @@ void OperationalSpaceControl::Build() { // .get(); for (int i = -1; i < 5; ++i) { - solvers_[i] = std::make_unique(); +// solvers_[i] = std::make_unique(); + solvers_[i] = std::make_unique(); } + prog_->SetSolverOptions(solver_options_); } drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( @@ -716,16 +720,18 @@ VectorXd OperationalSpaceControl::SolveQp( } // Add joint limit constraints - VectorXd w_joint_limit = - K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_max_) - .cwiseMax(0) + - K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_min_) - .cwiseMin(0); - joint_limit_cost_->UpdateCoefficients(w_joint_limit, 0); + if (w_joint_limit_ > 0) { + VectorXd w_joint_limit = + K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) + .tail(n_revolute_joints_) - + q_max_) + .cwiseMax(0) + + K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) + .tail(n_revolute_joints_) - + q_min_) + .cwiseMin(0); + joint_limit_cost_->UpdateCoefficients(w_joint_limit, 0); + } // (Testing) 6. blend contact forces during double support phase if (ds_duration_ > 0) { @@ -785,18 +791,20 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd::Zero(n_h_)); } - if (!solvers_.at(0)->IsInitialized()) { - solvers_.at(0)->InitializeSolver(*prog_, solver_options_); - } - - if (initial_guess_x_.count(fsm_state) > 0) { - solvers_.at(0)->WarmStart(initial_guess_x_.at(fsm_state), - initial_guess_y_.at(fsm_state)); - } +// if (!solvers_.at(0)->IsInitialized()) { +// solvers_.at(0)->InitializeSolver(*prog_, solver_options_); +// } +// +// if (initial_guess_x_.count(0) > 0) { +// solvers_.at(0)->WarmStart(initial_guess_x_.at(0), +// initial_guess_y_.at(0)); +// } // Solve the QP MathematicalProgramResult result; result = solvers_.at(0)->Solve(*prog_); + // auto osqp_solver = drake::solvers::OsqpSolver(); + // result = osqp_solver.Solve(*prog_, std::nullopt, solver_options_); solve_time_ = result.get_solver_details().run_time; if (result.is_success()) { @@ -806,8 +814,8 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); - initial_guess_x_[fsm_state] = result.GetSolution(); - initial_guess_y_[fsm_state] = result.get_solver_details().y; + initial_guess_x_[0] = result.GetSolution(); + initial_guess_y_[0] = result.get_solver_details().y; } else { // *u_prev_ = VectorXd::Zero(n_u_); *u_prev_ = 0.99 * *u_sol_ + VectorXd::Random(n_u_); @@ -960,9 +968,9 @@ void OperationalSpaceControl::AssignOscLcmOutput( if (soft_constraint_cost_) { soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); } - if (joint_limit_cost_) { - joint_limit_cost_->Eval(*dv_sol_, &y_joint_limit_cost); - } + // if (joint_limit_cost_) { + // joint_limit_cost_->Eval(*dv_sol_, &y_joint_limit_cost); + // } double acceleration_cost = (accel_cost_ != nullptr) ? y_accel_cost[0] : 0; double input_cost = (input_cost_ != nullptr) ? y_input_cost[0] : 0; double input_smoothing_cost = @@ -971,12 +979,11 @@ void OperationalSpaceControl::AssignOscLcmOutput( (soft_constraint_cost_ != nullptr) ? y_soft_constraint_cost[0] : 0; double lambda_c_cost = (lambda_c_cost_ != nullptr) ? y_lambda_c_cost[0] : 0; double lambda_h_cost = (lambda_h_cost_ != nullptr) ? y_lambda_h_cost[0] : 0; - double joint_limit_cost = - (joint_limit_cost_ != nullptr) ? y_joint_limit_cost[0] : 0; + // double joint_limit_cost = + // (joint_limit_cost_ != nullptr) ? y_joint_limit_cost[0] : 0; total_cost += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost + - joint_limit_cost; + input_smoothing_cost + lambda_h_cost + lambda_c_cost; output->regularization_costs.clear(); output->regularization_cost_names.clear(); @@ -993,8 +1000,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->regularization_cost_names.push_back("lambda_c_cost"); output->regularization_costs.push_back(lambda_h_cost); output->regularization_cost_names.push_back("lambda_h_cost"); - output->regularization_costs.push_back(joint_limit_cost); - output->regularization_cost_names.push_back("joint_limit_cost"); + // output->regularization_costs.push_back(joint_limit_cost); + // output->regularization_cost_names.push_back("joint_limit_cost"); output->tracking_data_names.clear(); output->tracking_data.clear(); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 66e680b492..b6c00e63cd 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -321,7 +321,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { bool is_quaternion_; // Solver - std::unordered_map> solvers_; + std::unordered_map> solvers_; drake::solvers::SolverOptions solver_options_ = drake::yaml::LoadYamlFile( FindResourceOrThrow("solvers/osqp_options_default.yaml")) @@ -344,13 +344,13 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::vector friction_constraints_; std::vector tracking_costs_; - drake::solvers::QuadraticCost* accel_cost_; - drake::solvers::LinearCost* joint_limit_cost_; - drake::solvers::QuadraticCost* input_cost_; - drake::solvers::QuadraticCost* input_smoothing_cost_; - drake::solvers::QuadraticCost* lambda_c_cost_; - drake::solvers::QuadraticCost* lambda_h_cost_; - drake::solvers::QuadraticCost* soft_constraint_cost_; + drake::solvers::QuadraticCost* accel_cost_ = nullptr; + drake::solvers::LinearCost* joint_limit_cost_ = nullptr; + drake::solvers::QuadraticCost* input_cost_ = nullptr; + drake::solvers::QuadraticCost* input_smoothing_cost_ = nullptr; + drake::solvers::QuadraticCost* lambda_c_cost_ = nullptr; + drake::solvers::QuadraticCost* lambda_h_cost_ = nullptr; + drake::solvers::QuadraticCost* soft_constraint_cost_ = nullptr; // OSC solution std::unique_ptr dv_sol_; From 541c8a996ecb2cf42b1b542e61759f95324e7835 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 8 Sep 2022 15:37:02 -0400 Subject: [PATCH 310/758] adding timing variation bounds in gains --- .../contact_scheduler/contact_scheduler.cc | 16 ++++++++-------- .../Cassie/contact_scheduler/contact_scheduler.h | 6 ++++++ examples/Cassie/osc_run/osc_running_gains.h | 4 ++++ examples/Cassie/osc_run/osc_running_gains.yaml | 3 +++ examples/Cassie/run_osc_running_controller.cc | 2 ++ 5 files changed, 23 insertions(+), 8 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index e47b7d5144..e8ae86ebda 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -121,8 +121,6 @@ EventStatus ContactScheduler::UpdateTransitionTimes( double transition_time = upcoming_transitions.at(3).first; RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; if (current_time > transition_time) { - // std::cout << "transitioning to: " << transition_state << std::endl; - // std::cout << "at: " << transition_time << std::endl; active_state = transition_state; } VectorXd q = robot_output->GetPositions(); @@ -182,11 +180,12 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // TODO(yangwill): calculate end of stance duration double stance_scale = (rest_length_) / (pelvis_z); - stance_scale = drake::math::saturate(stance_scale, 0.9, 1.2); - // std::cout << "stance scale: " << stance_scale << std::endl; + stance_scale = drake::math::saturate(stance_scale, 1 - stance_variance_, + 1 + stance_variance_); double next_transition_time = stored_transition_time + stance_scale * stance_duration_; -// double next_transition_time = stored_transition_time + stance_duration_; + // double next_transition_time = stored_transition_time + + // stance_duration_; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; if (active_state == LEFT_STANCE) { @@ -203,16 +202,17 @@ EventStatus ContactScheduler::UpdateTransitionTimes( {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; } } else { - double time_to_touchdown = flight_duration_; + // set default to minimum touchdown time in case pelvis is below rest length + double time_to_touchdown = (1 - flight_variance_) * flight_duration_; if (pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z) > 0) { time_to_touchdown = (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z))) / g; } - // double time_to_touchdown_saturated = ; double time_to_touchdown_saturated = drake::math::saturate( - time_to_touchdown, 0.75 * flight_duration_, 1.1 * flight_duration_); + time_to_touchdown, (1 - flight_variance_) * flight_duration_, + (1 + flight_variance_) * flight_duration_); double next_transition_time = stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index eb99f94fc4..2fc2d1dfe0 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -30,6 +30,10 @@ class ContactScheduler : public drake::systems::LeafSystem { stance_duration_ = stance_duration; flight_duration_ = flight_duration; } + void SetMaxStepTimingVariance(double stance_variance, double flight_variance) { + stance_variance_ = stance_variance; + flight_variance_ = flight_variance; + } const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } @@ -107,6 +111,8 @@ class ContactScheduler : public drake::systems::LeafSystem { double rest_length_; double stance_duration_; double flight_duration_; + double stance_variance_; + double flight_variance_; }; } // namespace dairlib diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 8ed4b1e090..0563775043 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -31,6 +31,8 @@ struct OSCRunningGains : OSCGains { double rest_length_offset; double stance_duration; double flight_duration; + double stance_variance; + double flight_variance; double footstep_lateral_offset; double footstep_sagital_offset; @@ -90,6 +92,8 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(rest_length_offset)); a->Visit(DRAKE_NVP(stance_duration)); a->Visit(DRAKE_NVP(flight_duration)); + a->Visit(DRAKE_NVP(stance_variance)); + a->Visit(DRAKE_NVP(flight_variance)); a->Visit(DRAKE_NVP(footstep_lateral_offset)); a->Visit(DRAKE_NVP(footstep_sagital_offset)); a->Visit(DRAKE_NVP(mid_foot_height)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index ba10d79c8f..44a6b34b07 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -39,6 +39,9 @@ rest_length: 0.85 rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 +# max percent variance +stance_variance: 0.1 +flight_variance: 0.3 w_swing_toe: 0.001 swing_toe_kp: 1500 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 7818b4a875..637add2b63 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -168,6 +168,8 @@ int DoMain(int argc, char* argv[]) { contact_scheduler->SetSLIPParams(osc_gains.rest_length); contact_scheduler->SetNominalStepTimings(osc_gains.stance_duration, osc_gains.flight_duration); + contact_scheduler->SetMaxStepTimingVariance(osc_gains.stance_variance, + osc_gains.flight_variance); /**** Initialize all the leaf systems ****/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); From 70fd2cdd7529778e5d535da86ce656760ca16470 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 12 Sep 2022 13:44:13 -0400 Subject: [PATCH 311/758] updating plots and lcm url for jumping controller --- bindings/pydairlib/analysis/log_plotter_cassie.py | 5 +++-- bindings/pydairlib/analysis/mbp_plotting_utils.py | 2 ++ .../analysis/plot_configs/cassie_running_plot.yaml | 10 +++++----- examples/Cassie/run_osc_jumping_controller.cc | 2 +- 4 files changed, 11 insertions(+), 8 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 36dd677b5e..0082faa7f8 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -154,6 +154,7 @@ def main(): plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') ''' Plot Foot Positions ''' if plot_config.foot_positions_to_plot: @@ -175,8 +176,8 @@ def main(): mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_active_tracking_datas: - mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - + plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.save_fig('active_tracking_datas.png') plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 22cb064b87..84f9a12178 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -636,3 +636,5 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_ legend = ax.legend(handles=tracking_data_legend_elements, loc=1) # ax.add_artist(legend) ax.relim() + + return ps \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index cec7eba206..1fb9f37f9d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 1 -duration: 7 +start_time: 3 +duration: 4 # Plant properties use_springs: true @@ -44,13 +44,13 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'vel' ] }, + pelvis_trans_traj: { 'dims': [1, 2 ], 'derivs': [ 'pos', 'vel' ] }, # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' ] }, # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, -# right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, -# left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + right_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, + left_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 9a7ec046c6..656c4ae6ec 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -239,7 +239,7 @@ int DoMain(int argc, char* argv[]) { pelvis_trans_traj = pelvis_trans_traj + offset_traj; /**** Initialize all the leaf systems ****/ - drake::lcm::DrakeLcm lcm; + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant_w_spr); From be56394b7745b863e1926b0897593c107a852727 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 15 Sep 2022 15:16:20 -0400 Subject: [PATCH 312/758] looking at toe weights --- .../pydairlib/analysis/log_plotter_cassie.py | 1 - .../plot_configs/cassie_running_plot.yaml | 10 +++++----- examples/Cassie/osc_run/osc_running_gains.yaml | 18 +++++++++--------- 3 files changed, 14 insertions(+), 15 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 0082faa7f8..fbb66f27cb 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -57,7 +57,6 @@ def main(): # Define x time slice t_x_slice = slice(robot_output['t_x'].size) t_osc_slice = slice(osc_debug['t_osc'].size) - print('Log start time: ', robot_output['t_x'][0]) print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) # import time diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1fb9f37f9d..f009ded63b 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,7 +6,7 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 3 +start_time: 0.5 duration: 4 # Plant properties @@ -49,10 +49,10 @@ tracking_datas_to_plot: { # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, - left_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, +# right_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, +# left_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, - # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, + left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel'] }, + right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel'] }, } \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 44a6b34b07..d4af03d841 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -11,8 +11,8 @@ weight_scaling: 1.0 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001 ] W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, 1, 0.9, 0.5, 0.1, 5 ] W_lambda_c_reg: [ 1, 0.001, 0.01, @@ -26,7 +26,7 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true rot_filter_tau: 0.005 -ekf_filter_tau: [ 0.001, 0.01, 0.001 ] +ekf_filter_tau: [ 0.05, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -2 @@ -40,10 +40,10 @@ rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 # max percent variance -stance_variance: 0.1 +stance_variance: 0.3 flight_variance: 0.3 -w_swing_toe: 0.001 +w_swing_toe: 0.01 swing_toe_kp: 1500 swing_toe_kd: 10 @@ -53,11 +53,11 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.03 -footstep_lateral_offset: 0.07 # drake +footstep_lateral_offset: 0.06 # drake mid_foot_height: 0.15 FootstepKd: - [ 0.13, 0, 0, - 0, 0.25, 0, + [ 0.01, 0, 0, + 0, 0.3, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, @@ -69,7 +69,7 @@ PelvisKp: 0, 0, 155] PelvisKd: [ 0, 0, 0, - 0, 2, 0, + 0, 10, 0, 0, 0, 5 ] PelvisRotW: [10, 0, 0, From 07425df36dbd399efdbcf1ddea196d6887ea6d69 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 15 Sep 2022 15:16:45 -0400 Subject: [PATCH 313/758] adding shells to visualization --- examples/Cassie/urdf/cassie_v2_shells.urdf | 909 + .../urdf/meshes/agility/achilles-rod.obj | 6460 + .../Cassie/urdf/meshes/agility/foot-crank.obj | 2288 + examples/Cassie/urdf/meshes/agility/foot.obj | 4048 + .../urdf/meshes/agility/heel-spring.obj | 3246 + .../Cassie/urdf/meshes/agility/hip-pitch.obj | 18176 +++ .../Cassie/urdf/meshes/agility/hip-roll.obj | 9385 ++ .../Cassie/urdf/meshes/agility/hip-yaw.obj | 4782 + .../urdf/meshes/agility/knee-spring.obj | 5643 + examples/Cassie/urdf/meshes/agility/knee.obj | 4543 + .../Cassie/urdf/meshes/agility/pelvis.obj | 98360 ++++++++-------- .../urdf/meshes/agility/plantar-rod.obj | 5035 + examples/Cassie/urdf/meshes/agility/shin.obj | 22185 ++++ .../Cassie/urdf/meshes/agility/tarsus.obj | 24843 ++++ examples/Cassie/visualizer.cc | 2 +- 15 files changed, 162912 insertions(+), 46993 deletions(-) create mode 100644 examples/Cassie/urdf/cassie_v2_shells.urdf create mode 100644 examples/Cassie/urdf/meshes/agility/achilles-rod.obj create mode 100644 examples/Cassie/urdf/meshes/agility/foot-crank.obj create mode 100644 examples/Cassie/urdf/meshes/agility/foot.obj create mode 100644 examples/Cassie/urdf/meshes/agility/heel-spring.obj create mode 100644 examples/Cassie/urdf/meshes/agility/hip-pitch.obj create mode 100644 examples/Cassie/urdf/meshes/agility/hip-roll.obj create mode 100644 examples/Cassie/urdf/meshes/agility/hip-yaw.obj create mode 100644 examples/Cassie/urdf/meshes/agility/knee-spring.obj create mode 100644 examples/Cassie/urdf/meshes/agility/knee.obj create mode 100644 examples/Cassie/urdf/meshes/agility/plantar-rod.obj create mode 100644 examples/Cassie/urdf/meshes/agility/shin.obj create mode 100644 examples/Cassie/urdf/meshes/agility/tarsus.obj diff --git a/examples/Cassie/urdf/cassie_v2_shells.urdf b/examples/Cassie/urdf/cassie_v2_shells.urdf new file mode 100644 index 0000000000..e92e03e89e --- /dev/null +++ b/examples/Cassie/urdf/cassie_v2_shells.urdf @@ -0,0 +1,909 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/Cassie/urdf/meshes/agility/achilles-rod.obj b/examples/Cassie/urdf/meshes/agility/achilles-rod.obj new file mode 100644 index 0000000000..bb9e5c8bcd --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/achilles-rod.obj @@ -0,0 +1,6460 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o achilles-rod +v 0.493264 0.000612 -0.005533 +v 0.495129 -0.001861 -0.007164 +v 0.493521 -0.001920 -0.005476 +v 0.494809 -0.003573 0.006126 +v 0.494500 -0.001991 0.006460 +v 0.493541 -0.001375 0.005639 +v 0.493349 0.002201 0.005103 +v 0.494816 0.003570 0.006131 +v 0.493210 0.003571 0.004174 +v 0.495032 0.002169 -0.006987 +v 0.494782 0.000144 -0.007076 +v 0.492357 -0.003566 0.003275 +v 0.493635 -0.003568 0.004674 +v 0.492735 -0.002468 0.004474 +v 0.489734 -0.003109 0.001830 +v 0.489910 -0.003568 0.000803 +v 0.491197 -0.003559 0.002174 +v 0.490964 -0.003570 -0.001946 +v 0.491383 -0.003026 -0.003089 +v 0.492900 -0.003566 -0.003858 +v 0.487927 0.003095 -0.001014 +v 0.486881 0.002895 -0.001396 +v 0.487444 0.003192 0.000359 +v 0.488422 0.003302 -0.000157 +v 0.489053 0.002956 -0.001766 +v 0.489455 -0.000296 0.003519 +v 0.487924 0.001241 0.002976 +v 0.487653 0.000187 0.003202 +v 0.489065 -0.001235 -0.003186 +v 0.487567 -0.001818 -0.002640 +v 0.489091 -0.000453 -0.003381 +v 0.487289 -0.000743 -0.003123 +v 0.489741 0.003572 -0.000571 +v 0.489883 0.003569 0.000763 +v 0.488465 0.003162 0.000969 +v 0.487888 -0.003192 0.000456 +v 0.489721 -0.003570 -0.000588 +v 0.487884 -0.003164 -0.000600 +v 0.490500 0.003567 -0.001485 +v 0.489687 0.003032 0.001906 +v 0.491120 0.003566 0.002083 +v 0.491032 -0.000071 0.004110 +v 0.489971 0.000760 0.003597 +v 0.487964 -0.002829 0.001550 +v 0.487889 -0.002818 -0.001557 +v 0.489928 -0.002959 -0.002177 +v 0.490300 0.002877 -0.002508 +v 0.488430 -0.001166 0.003120 +v 0.487123 -0.001107 0.003005 +v 0.491882 0.003566 -0.002809 +v 0.488256 0.002327 -0.002309 +v 0.488001 -0.002252 0.002315 +v 0.489698 0.000263 -0.003565 +v 0.487691 0.000771 -0.003128 +v 0.487272 0.001931 -0.002546 +v 0.492250 -0.000876 0.004697 +v 0.491144 -0.001727 0.003762 +v 0.490818 -0.002672 0.003037 +v 0.492829 0.003568 -0.003767 +v 0.490865 0.001896 -0.003577 +v 0.489633 0.001656 -0.003189 +v 0.489714 -0.001877 0.003093 +v 0.492696 0.000204 -0.005080 +v 0.492234 0.001876 -0.004404 +v 0.491265 0.000268 -0.004231 +v 0.493494 0.002468 -0.005130 +v 0.488465 0.001399 -0.002996 +v 0.493807 0.003566 -0.004873 +v 0.492458 -0.001545 -0.004691 +v 0.491601 -0.001890 -0.004004 +v 0.490853 -0.001248 -0.003793 +v 0.490260 -0.002012 -0.003194 +v 0.489078 -0.002139 -0.002671 +v 0.494807 0.003570 -0.006127 +v 0.492521 0.002389 0.004309 +v 0.492034 0.003557 0.002978 +v 0.489939 0.002174 0.002965 +v 0.487896 0.002770 0.001644 +v 0.491062 0.001662 0.003763 +v 0.492460 0.000577 0.004903 +v 0.493577 0.000637 0.005790 +v 0.487916 0.002096 0.002450 +v 0.494687 -0.003575 -0.005947 +v 0.487267 -0.002383 -0.002116 +v 0.510674 -0.000683 0.000948 +v 0.510693 -0.000370 -0.000840 +v 0.510729 0.000360 0.000168 +v 0.494718 -0.000854 0.006961 +v 0.502831 -0.002459 -0.009076 +v 0.504209 -0.003568 -0.008361 +v 0.501754 -0.003571 -0.008830 +v 0.510074 -0.002342 -0.002675 +v 0.509959 -0.003571 -0.001201 +v 0.509580 -0.003571 -0.002850 +v 0.510002 -0.003571 0.000908 +v 0.510328 -0.002762 -0.000280 +v 0.510323 -0.002579 0.001008 +v 0.509497 0.003572 -0.003093 +v 0.509943 0.003572 -0.001325 +v 0.510309 0.002571 -0.001352 +v 0.500774 0.003571 -0.008839 +v 0.500668 0.002450 -0.009214 +v 0.498989 0.003569 -0.008568 +v 0.495126 0.000374 0.007391 +v 0.495930 0.003571 -0.007101 +v 0.495170 0.002115 0.007120 +v 0.495989 0.003570 0.007152 +v 0.495646 -0.002096 0.007511 +v 0.496026 -0.003570 0.007181 +v 0.495475 -0.003565 -0.006775 +v 0.497124 0.003564 -0.007875 +v 0.497310 0.001760 -0.008572 +v 0.497504 0.002439 0.008486 +v 0.497689 0.003572 0.008119 +v 0.499754 0.003573 0.008752 +v 0.496804 -0.002586 0.008110 +v 0.497889 -0.003573 0.008211 +v 0.498170 -0.002152 0.008805 +v 0.500309 -0.003570 0.008828 +v 0.497030 -0.003570 -0.007803 +v 0.496998 -0.002030 -0.008335 +v 0.499544 -0.003572 -0.008727 +v 0.499070 -0.002058 -0.009098 +v 0.496421 0.001314 0.008172 +v 0.500052 0.002167 0.009256 +v 0.501998 0.003566 0.008836 +v 0.501775 0.000938 0.009503 +v 0.503437 0.003566 0.008578 +v 0.503448 0.000908 0.009241 +v 0.497734 0.000361 0.008899 +v 0.499434 0.001213 0.009305 +v 0.500642 -0.000373 0.009533 +v 0.496794 -0.000821 0.008435 +v 0.499315 -0.001143 0.009308 +v 0.501585 -0.001558 0.009436 +v 0.503392 -0.001587 0.009173 +v 0.502463 -0.003571 0.008764 +v 0.504005 -0.003558 0.008415 +v 0.504650 0.000574 0.008904 +v 0.504390 0.003553 0.008291 +v 0.505542 -0.003572 0.007711 +v 0.505208 -0.001965 0.008423 +v 0.506146 -0.000269 0.008169 +v 0.506133 0.001715 0.008019 +v 0.505973 0.003573 0.007452 +v 0.506427 -0.002083 0.007772 +v 0.497411 -0.000650 -0.008758 +v 0.495719 0.000536 -0.007815 +v 0.498486 0.000254 -0.009177 +v 0.499277 0.001523 -0.009237 +v 0.500642 0.000373 -0.009533 +v 0.504347 -0.000598 -0.009016 +v 0.502530 -0.000309 -0.009465 +v 0.502999 0.001563 -0.009264 +v 0.506142 -0.000265 -0.008168 +v 0.506021 0.001053 -0.008179 +v 0.505091 0.002114 -0.008485 +v 0.502676 0.003569 -0.008754 +v 0.506610 0.003562 -0.007040 +v 0.504867 0.003572 -0.008052 +v 0.506899 -0.003565 0.006797 +v 0.507762 0.001743 -0.006717 +v 0.507550 0.000080 -0.007139 +v 0.507330 -0.000250 0.007343 +v 0.507105 0.003563 0.006612 +v 0.507596 0.003573 -0.006123 +v 0.507982 -0.001508 0.006525 +v 0.508022 0.001934 0.006413 +v 0.508285 -0.003568 0.005327 +v 0.508499 -0.000114 0.006176 +v 0.508616 0.003569 0.004868 +v 0.508722 0.003571 -0.004658 +v 0.508819 0.002108 -0.005407 +v 0.508785 -0.000258 -0.005811 +v 0.509147 -0.001503 0.005062 +v 0.509061 0.001829 0.005134 +v 0.509678 0.000717 -0.004376 +v 0.509044 -0.003569 0.004102 +v 0.509364 -0.000247 0.004933 +v 0.509786 0.002018 -0.003722 +v 0.509782 -0.001486 0.003945 +v 0.509897 0.000942 0.003859 +v 0.509965 0.002140 0.003096 +v 0.509641 0.003568 0.002724 +v 0.508905 -0.003574 -0.004345 +v 0.509316 -0.002235 -0.004558 +v 0.507780 -0.003567 -0.005953 +v 0.509688 -0.003565 0.002556 +v 0.504412 -0.002417 -0.008656 +v 0.505692 -0.002074 -0.008187 +v 0.506590 -0.003565 -0.007045 +v 0.507152 -0.001625 -0.007265 +v 0.508150 -0.001947 -0.006280 +v 0.501204 -0.001628 -0.009422 +v 0.509936 -0.001019 -0.003757 +v 0.510372 -0.001850 0.001968 +v 0.510264 -0.000628 0.002917 +v 0.510437 0.001827 0.001601 +v 0.510040 0.003570 0.000617 +v 0.510426 0.000735 -0.002380 +v 0.510442 -0.001944 -0.001309 +v 0.510482 -0.000828 -0.002037 +v 0.510576 0.000380 0.001743 +v 0.510583 0.001657 0.000539 +v 0.510625 -0.001488 0.000085 +v 0.510636 0.001209 -0.000790 +v 0.507090 -0.003572 0.003098 +v 0.507884 -0.003572 -0.000073 +v 0.502770 -0.003572 -0.006498 +v 0.495023 -0.003572 -0.002411 +v 0.494530 -0.003572 0.000441 +v 0.495749 -0.003572 0.003868 +v 0.505486 -0.003572 0.005061 +v 0.505648 -0.003572 -0.004949 +v 0.500175 -0.003572 -0.006535 +v 0.498266 -0.003572 0.005973 +v 0.507158 -0.003572 -0.002913 +v 0.496141 -0.003572 -0.004286 +v 0.503610 -0.003572 0.006178 +v 0.501096 -0.003572 0.006654 +v 0.498124 -0.003572 -0.005902 +v 0.507252 0.003572 -0.002769 +v 0.507676 0.003572 0.001533 +v 0.507787 0.003572 -0.000611 +v 0.495599 0.003572 -0.003549 +v 0.497605 0.003572 -0.005636 +v 0.506402 0.003572 0.004149 +v 0.494749 0.003572 -0.001539 +v 0.500730 0.003572 -0.006638 +v 0.503266 0.003572 -0.006301 +v 0.505491 0.003572 -0.005085 +v 0.504437 0.003572 0.005788 +v 0.501679 0.003572 0.006667 +v 0.495881 0.003572 0.004048 +v 0.498455 0.003572 0.006062 +v 0.494624 0.003572 0.001017 +v 0.507706 -0.000168 -0.000760 +v 0.507731 0.000546 0.000092 +v 0.507736 -0.000204 0.000400 +v 0.505695 -0.004761 -0.000566 +v 0.506361 -0.004019 0.000511 +v 0.505553 -0.004760 0.001122 +v 0.499135 -0.003817 0.004945 +v 0.498693 -0.004761 0.003752 +v 0.500393 -0.004762 0.004456 +v 0.506042 0.004269 0.001151 +v 0.505735 0.004753 -0.000095 +v 0.505520 0.004762 0.001234 +v 0.494809 0.000083 0.001482 +v 0.494664 -0.000201 0.000415 +v 0.494844 -0.001024 0.001176 +v 0.494725 -0.000999 -0.000194 +v 0.494889 -0.001318 -0.001153 +v 0.495106 -0.002419 -0.000318 +v 0.494694 0.000751 -0.000172 +v 0.494722 0.000830 0.000531 +v 0.494798 0.001373 -0.000509 +v 0.495069 -0.001126 0.002095 +v 0.494688 -0.000034 -0.000763 +v 0.495070 0.002098 -0.001055 +v 0.495138 0.002403 0.000773 +v 0.495577 0.003380 -0.000276 +v 0.495274 0.000750 0.002747 +v 0.495428 -0.000944 0.002997 +v 0.495500 0.000347 0.003238 +v 0.495461 0.002762 -0.001601 +v 0.495928 -0.001132 0.003773 +v 0.496012 0.000987 0.003919 +v 0.495731 -0.003563 0.000788 +v 0.495667 -0.003433 -0.000818 +v 0.495040 -0.000767 -0.002111 +v 0.494951 0.000726 -0.001874 +v 0.495259 0.000318 -0.002768 +v 0.494835 -0.001524 0.000408 +v 0.495790 -0.001060 -0.003571 +v 0.495874 0.000270 -0.003835 +v 0.496235 0.003626 -0.002350 +v 0.496048 0.004009 -0.000607 +v 0.496837 0.004758 -0.001196 +v 0.495235 -0.002365 0.001413 +v 0.496665 -0.004757 -0.000285 +v 0.496731 -0.004757 0.000711 +v 0.495461 0.002998 0.000999 +v 0.496056 0.003883 0.001276 +v 0.496731 0.004759 0.000741 +v 0.495502 0.002399 0.002268 +v 0.495728 0.002914 0.002205 +v 0.497061 -0.004745 0.001886 +v 0.496032 -0.003828 -0.001426 +v 0.497187 -0.004746 -0.002145 +v 0.497483 0.004758 -0.002585 +v 0.496354 0.003944 0.001925 +v 0.494969 0.001637 0.001280 +v 0.497200 0.004751 0.002123 +v 0.496045 0.003288 0.002316 +v 0.496126 -0.003784 0.001751 +v 0.495224 -0.002197 -0.001721 +v 0.496354 -0.003845 -0.002116 +v 0.496465 0.003808 0.002411 +v 0.495015 0.001171 0.001825 +v 0.496045 0.003045 0.002627 +v 0.496750 0.003685 0.003155 +v 0.495776 -0.002581 0.002671 +v 0.496465 -0.003778 0.002459 +v 0.495762 -0.003223 0.001672 +v 0.495432 -0.002601 -0.001647 +v 0.495674 -0.002823 -0.001926 +v 0.497177 -0.002032 -0.004736 +v 0.496602 -0.001047 -0.004582 +v 0.497716 -0.001432 -0.005373 +v 0.495947 0.002686 0.002821 +v 0.497466 0.004754 0.002602 +v 0.495590 0.001936 0.002748 +v 0.495590 0.002225 0.002517 +v 0.495872 0.002060 0.003167 +v 0.496144 0.002822 0.003037 +v 0.497455 -0.004754 0.002585 +v 0.497160 -0.003963 -0.003319 +v 0.497866 -0.004759 -0.003032 +v 0.496329 -0.003433 -0.002728 +v 0.496021 -0.002874 -0.002877 +v 0.496565 -0.002670 -0.003817 +v 0.497177 -0.002374 -0.004574 +v 0.497566 -0.002444 -0.004856 +v 0.496692 0.003838 -0.002772 +v 0.496465 -0.003553 0.002773 +v 0.496808 -0.003819 -0.002981 +v 0.495286 -0.001778 -0.002234 +v 0.495590 -0.001692 -0.002903 +v 0.496144 -0.002045 -0.003609 +v 0.496808 -0.002388 -0.004215 +v 0.498382 -0.003172 -0.005019 +v 0.497131 0.004150 -0.003061 +v 0.497358 -0.003524 -0.004025 +v 0.497910 -0.003777 0.004269 +v 0.496929 -0.003788 0.003186 +v 0.498653 -0.004349 -0.004169 +v 0.498728 -0.004760 -0.003766 +v 0.498333 0.004755 -0.003519 +v 0.496808 0.003668 -0.003164 +v 0.495432 -0.001925 -0.002405 +v 0.495590 -0.002068 -0.002650 +v 0.496465 -0.002773 -0.003553 +v 0.497051 -0.003661 0.003485 +v 0.496465 -0.003302 0.003069 +v 0.499946 -0.004762 -0.004319 +v 0.498356 0.004752 0.003549 +v 0.496808 -0.003341 -0.003509 +v 0.499828 -0.003663 -0.005286 +v 0.496398 -0.002705 0.003512 +v 0.500270 0.004760 -0.004441 +v 0.498777 0.003811 -0.004749 +v 0.497704 0.003288 -0.004524 +v 0.496639 0.002670 -0.003907 +v 0.496354 0.003065 -0.003141 +v 0.496144 0.002860 -0.003004 +v 0.495676 0.002411 -0.002533 +v 0.498662 0.003761 0.004731 +v 0.497784 0.003975 0.003996 +v 0.497177 0.003598 0.003689 +v 0.496808 0.003509 0.003341 +v 0.501185 -0.004758 -0.004526 +v 0.495592 0.001591 -0.003037 +v 0.501163 -0.000607 0.006544 +v 0.499865 0.000727 0.006394 +v 0.499601 -0.000996 0.006298 +v 0.498869 0.000744 0.006089 +v 0.498573 -0.000513 0.006007 +v 0.497698 -0.000950 0.005479 +v 0.497271 0.000226 0.005251 +v 0.496611 -0.000393 0.004685 +v 0.501287 -0.001884 0.006296 +v 0.502795 -0.002023 0.006037 +v 0.502485 -0.000478 0.006419 +v 0.498048 -0.002108 0.005350 +v 0.496884 -0.002096 0.004498 +v 0.498511 -0.002554 0.005436 +v 0.499950 -0.002477 0.005942 +v 0.501677 -0.003021 0.005809 +v 0.500546 -0.003705 0.005384 +v 0.497566 -0.003130 0.004445 +v 0.497304 -0.003024 0.004294 +v 0.495735 -0.002228 0.002892 +v 0.502161 -0.003801 0.005266 +v 0.497051 -0.003301 0.003827 +v 0.502263 -0.004759 0.004405 +v 0.502498 -0.003855 -0.005155 +v 0.503088 -0.004762 -0.004118 +v 0.501452 -0.003774 -0.005356 +v 0.501067 -0.003032 -0.005827 +v 0.502811 -0.002638 -0.005804 +v 0.500008 -0.001952 -0.006160 +v 0.498929 -0.002075 -0.005806 +v 0.501471 -0.001793 -0.006310 +v 0.501710 -0.000878 -0.006496 +v 0.499516 -0.000720 -0.006319 +v 0.498110 0.000041 -0.005793 +v 0.497252 -0.000118 -0.005214 +v 0.500724 0.000297 -0.006544 +v 0.502366 -0.000025 -0.006462 +v 0.499759 0.001182 -0.006293 +v 0.498314 0.001085 -0.005811 +v 0.496951 0.000855 -0.004911 +v 0.502197 0.001230 -0.006366 +v 0.500832 0.001626 -0.006345 +v 0.496181 0.001268 -0.003992 +v 0.501885 0.002184 -0.006147 +v 0.499044 0.002388 -0.005733 +v 0.502799 0.002553 -0.005822 +v 0.497299 0.002443 -0.004702 +v 0.500089 0.002759 -0.005850 +v 0.498228 0.002705 -0.005175 +v 0.501479 0.003065 -0.005799 +v 0.496249 0.001730 -0.003903 +v 0.501540 0.003789 -0.005375 +v 0.499762 0.003901 -0.005069 +v 0.497746 0.002937 -0.004709 +v 0.495947 0.002544 -0.002949 +v 0.495288 0.001826 -0.002117 +v 0.502140 0.004762 -0.004421 +v 0.503262 0.003839 -0.004903 +v 0.503658 -0.003773 0.004780 +v 0.503340 -0.002911 0.005437 +v 0.503214 -0.001272 -0.006099 +v 0.503907 -0.001514 0.005798 +v 0.503377 -0.000118 0.006181 +v 0.503678 0.004745 -0.003817 +v 0.503474 0.001229 -0.006034 +v 0.503453 -0.000225 -0.006154 +v 0.503567 -0.003731 -0.004880 +v 0.503764 -0.004758 0.003731 +v 0.504108 0.002590 -0.005279 +v 0.504046 -0.001929 -0.005579 +v 0.504629 -0.002968 0.004784 +v 0.504467 -0.000894 0.005630 +v 0.504474 0.003693 -0.004295 +v 0.504693 0.001554 -0.005332 +v 0.504368 0.000485 -0.005728 +v 0.504579 -0.000636 -0.005593 +v 0.504551 -0.003143 -0.004724 +v 0.504929 -0.003708 -0.003922 +v 0.504447 -0.004751 -0.003183 +v 0.504626 -0.004750 0.002969 +v 0.504921 -0.003521 0.004147 +v 0.504655 0.004750 -0.002962 +v 0.504423 -0.001917 -0.005356 +v 0.504563 -0.002273 -0.005127 +v 0.504698 -0.002664 -0.004838 +v 0.505236 -0.002453 0.004530 +v 0.504959 0.003937 -0.003559 +v 0.505415 0.002113 -0.004559 +v 0.505376 -0.001183 -0.004921 +v 0.505060 -0.002094 -0.004817 +v 0.505044 0.004755 0.002416 +v 0.503877 0.004756 0.003671 +v 0.505453 0.004185 0.002792 +v 0.504834 0.003937 0.003749 +v 0.504719 0.003481 0.004321 +v 0.503304 0.003646 0.005071 +v 0.502221 0.004758 0.004423 +v 0.501474 0.003641 0.005472 +v 0.500063 0.004760 0.004397 +v 0.499785 0.004189 0.004852 +v 0.497051 0.003301 0.003827 +v 0.496692 0.003135 0.003548 +v 0.496354 0.002742 0.003426 +v 0.500203 0.003370 0.005548 +v 0.497246 0.002522 0.004606 +v 0.496575 0.002844 0.003645 +v 0.496808 0.002790 0.003961 +v 0.496144 0.002388 0.003391 +v 0.498505 0.002741 0.005332 +v 0.497566 0.002909 0.004593 +v 0.496465 0.002411 0.003808 +v 0.495762 0.001788 0.003157 +v 0.502750 0.002645 0.005811 +v 0.496929 0.002491 0.004277 +v 0.496462 0.001484 0.004296 +v 0.504316 0.002117 0.005383 +v 0.501195 0.002125 0.006212 +v 0.499943 0.001972 0.006127 +v 0.497817 0.001334 0.005477 +v 0.498677 0.002180 0.005678 +v 0.503237 0.001139 0.006130 +v 0.502085 0.001132 0.006407 +v 0.504263 0.000962 0.005725 +v 0.505213 0.001793 0.004901 +v 0.501008 0.000771 0.006509 +v 0.505144 0.000359 0.005230 +v 0.505223 0.003415 -0.003860 +v 0.505223 0.003121 -0.004101 +v 0.505487 0.000324 -0.004948 +v 0.505096 -0.003804 0.003621 +v 0.505096 -0.003231 0.004140 +v 0.505457 -0.001311 0.004833 +v 0.505349 0.003661 -0.003485 +v 0.505462 -0.002319 -0.004356 +v 0.505784 -0.002464 -0.003956 +v 0.505349 -0.003110 -0.003985 +v 0.506020 -0.003750 -0.002486 +v 0.505173 -0.004757 -0.002145 +v 0.505349 -0.003827 0.003301 +v 0.505471 -0.003094 0.003864 +v 0.505471 0.002598 0.004213 +v 0.505349 0.003110 0.003985 +v 0.505239 0.004750 -0.002079 +v 0.505592 0.003819 -0.002981 +v 0.505709 0.003509 -0.003180 +v 0.505592 0.003341 -0.003509 +v 0.505709 0.002957 -0.003697 +v 0.506169 0.001398 -0.004069 +v 0.505142 -0.004756 0.002226 +v 0.505592 -0.003819 0.002981 +v 0.505709 -0.003509 0.003180 +v 0.505592 -0.003341 0.003509 +v 0.505923 -0.000057 0.004550 +v 0.505592 0.002790 0.003961 +v 0.505592 0.003164 0.003669 +v 0.505709 0.003389 0.003305 +v 0.505595 0.004749 -0.001162 +v 0.505936 0.004026 -0.002026 +v 0.505943 0.003479 -0.002743 +v 0.505825 0.003188 -0.003348 +v 0.505825 0.002662 -0.003780 +v 0.506101 -0.001043 -0.004262 +v 0.505936 -0.002901 -0.003450 +v 0.505936 -0.003975 0.002218 +v 0.505936 -0.003553 0.002773 +v 0.505825 -0.003188 0.003349 +v 0.506087 -0.002831 0.003395 +v 0.505936 -0.002595 0.003685 +v 0.505936 -0.002222 0.003922 +v 0.505936 -0.001827 0.004121 +v 0.506317 -0.000930 0.004002 +v 0.506080 0.001315 0.004204 +v 0.505825 0.002662 0.003780 +v 0.505825 0.003020 0.003501 +v 0.505936 0.003413 0.002944 +v 0.506151 0.002284 0.003607 +v 0.506151 0.002627 0.003366 +v 0.506151 0.002944 0.003092 +v 0.506046 0.003845 0.002116 +v 0.506046 0.003288 -0.002907 +v 0.506165 0.002838 -0.003059 +v 0.506151 0.002458 -0.003491 +v 0.506494 0.000525 -0.003834 +v 0.506577 -0.003407 0.001603 +v 0.506046 -0.003180 0.003028 +v 0.506355 0.003106 0.002553 +v 0.506256 0.003391 0.002388 +v 0.506256 0.003632 0.001999 +v 0.506714 0.003361 -0.001133 +v 0.506271 0.003540 -0.002266 +v 0.506256 0.003141 -0.002709 +v 0.506671 -0.001907 -0.003122 +v 0.506256 -0.002219 -0.003504 +v 0.506256 -0.002591 -0.003237 +v 0.506268 -0.003632 -0.002084 +v 0.506773 -0.003485 -0.000278 +v 0.506256 -0.003419 0.002345 +v 0.506355 -0.003045 0.002627 +v 0.506256 -0.002822 0.003037 +v 0.506654 0.001054 0.003502 +v 0.506454 0.002433 0.003039 +v 0.506454 0.002821 0.002686 +v 0.506561 0.003357 0.001869 +v 0.506454 0.003498 0.001708 +v 0.506733 0.003529 0.000365 +v 0.506546 0.003077 -0.002167 +v 0.506454 0.002916 -0.002579 +v 0.506454 0.002433 -0.003039 +v 0.506454 0.002084 -0.003291 +v 0.506820 -0.000822 -0.003315 +v 0.506454 -0.002786 -0.002719 +v 0.506546 -0.002595 0.002726 +v 0.506454 -0.002357 0.003098 +v 0.506454 -0.001793 0.003456 +v 0.507002 0.001471 0.002716 +v 0.506638 0.002471 0.002660 +v 0.506638 0.002835 0.002269 +v 0.506638 0.002751 -0.002373 +v 0.506638 0.002471 -0.002660 +v 0.506638 0.002054 -0.002994 +v 0.506546 -0.003044 -0.002258 +v 0.507033 -0.002869 -0.000974 +v 0.506638 -0.002235 0.002864 +v 0.506638 -0.001828 0.003137 +v 0.506901 -0.001316 0.002978 +v 0.506810 0.002432 0.002315 +v 0.506810 0.002837 0.001796 +v 0.507092 0.002739 0.000948 +v 0.506810 0.002674 -0.002034 +v 0.506810 0.002315 -0.002432 +v 0.507015 0.001911 -0.002337 +v 0.507158 0.000539 -0.002710 +v 0.507142 -0.002048 -0.001947 +v 0.507027 -0.002655 0.001503 +v 0.506810 -0.002066 0.002647 +v 0.506904 -0.000001 0.003224 +v 0.507118 0.001678 0.002237 +v 0.507302 0.002083 0.001257 +v 0.506968 0.002427 -0.001894 +v 0.506968 0.002097 -0.002257 +v 0.507324 -0.001583 0.001788 +v 0.507329 -0.000181 0.002341 +v 0.507402 0.002110 -0.000452 +v 0.507133 0.002502 -0.000938 +v 0.507399 -0.000764 -0.002027 +v 0.507387 0.001518 -0.001503 +v 0.507466 -0.001915 0.000396 +v 0.507560 0.000683 0.001453 +v 0.507488 0.000473 -0.001794 +v 0.507576 -0.001337 -0.000826 +v 0.507575 -0.000401 0.001473 +v 0.507633 0.001198 0.000385 +v 0.507649 0.000795 -0.000872 +v 0.507638 -0.000935 0.000766 +v 0.507682 -0.000912 -0.000167 +v 0.504605 -0.004762 0.000889 +v 0.503717 -0.004762 0.002479 +v 0.500191 -0.004762 -0.003407 +v 0.503379 -0.004762 -0.002770 +v 0.502071 -0.004762 -0.003399 +v 0.497795 -0.004762 0.000941 +v 0.497751 -0.004762 -0.000664 +v 0.498883 -0.004762 0.002673 +v 0.502349 -0.004762 0.003319 +v 0.498419 -0.004762 -0.002188 +v 0.504595 -0.004762 -0.001088 +v 0.500697 -0.004762 0.003502 +v 0.504714 0.004762 0.000611 +v 0.502988 0.004762 -0.003095 +v 0.504406 0.004762 -0.001463 +v 0.503740 0.004762 0.002425 +v 0.500349 0.004762 -0.003470 +v 0.498193 0.004762 -0.001932 +v 0.502510 0.004762 0.003271 +v 0.498515 0.004762 0.002330 +v 0.500527 0.004762 0.003491 +v 0.497680 0.004762 0.000341 +v 0.501665 -0.004443 -0.003192 +v 0.500669 0.004442 -0.003146 +v 0.499957 -0.004446 -0.002952 +v 0.499392 0.004445 -0.002643 +v 0.498909 -0.004446 -0.002218 +v 0.498300 0.004444 -0.001388 +v 0.498271 -0.004444 -0.001268 +v 0.498017 -0.004444 -0.000160 +v 0.498008 0.004447 0.000178 +v 0.498173 -0.004442 0.001025 +v 0.498286 0.004446 0.001288 +v 0.498927 -0.004446 0.002241 +v 0.499158 0.004440 0.002483 +v 0.500270 -0.004446 0.003086 +v 0.500685 0.004444 0.003160 +v 0.502162 -0.004444 0.003068 +v 0.502038 0.004445 0.003079 +v 0.503423 0.004445 0.002330 +v 0.503556 -0.004441 0.002166 +v 0.504303 -0.004443 0.000768 +v 0.504283 0.004442 0.000826 +v 0.504338 0.004444 -0.000701 +v 0.504332 -0.004445 -0.000668 +v 0.503801 -0.004445 -0.001843 +v 0.503688 0.004446 -0.001994 +v 0.503072 -0.004447 -0.002579 +v 0.502843 0.004445 -0.002738 +v 0.501850 0.004445 -0.003117 +v 0.013985 0.003203 -0.000048 +v 0.013952 0.002860 -0.001418 +v 0.013374 0.003129 -0.000819 +v 0.010710 0.003571 -0.001502 +v 0.011614 0.003571 0.000195 +v 0.012088 0.003275 -0.001055 +v 0.012812 -0.003263 0.000598 +v 0.013585 -0.003111 -0.000812 +v 0.013951 -0.003190 0.000126 +v 0.011476 -0.000891 0.003465 +v 0.013570 -0.001164 0.002985 +v 0.013364 -0.000001 0.003243 +v 0.012748 0.003286 0.000543 +v 0.013920 0.002969 0.001169 +v 0.011504 -0.003564 -0.000469 +v 0.014277 0.000279 0.003192 +v 0.013063 0.000739 -0.003167 +v 0.013662 0.001724 -0.002702 +v 0.014312 0.000234 -0.003206 +v 0.011313 -0.003570 0.000763 +v 0.012117 -0.003200 0.001226 +v 0.011584 0.000264 0.003545 +v 0.012140 0.003084 0.001509 +v 0.012112 -0.002921 -0.001762 +v 0.010647 -0.003569 -0.001541 +v 0.012121 -0.002812 0.001919 +v 0.009957 -0.003568 0.002205 +v 0.010465 0.003564 0.001752 +v 0.012094 0.002844 -0.001868 +v 0.013865 -0.002340 -0.002205 +v 0.009834 -0.000003 0.004288 +v 0.010948 0.000930 0.003657 +v 0.010945 0.002904 0.002414 +v 0.012339 0.002504 0.002290 +v 0.013576 0.002317 0.002227 +v 0.011495 0.000807 -0.003507 +v 0.013061 -0.000221 -0.003245 +v 0.009369 -0.003569 -0.002752 +v 0.011251 -0.002584 -0.002595 +v 0.009846 0.002950 -0.003053 +v 0.009112 0.003571 -0.003002 +v 0.009316 0.000527 -0.004533 +v 0.010283 0.000791 -0.003982 +v 0.010902 -0.000395 -0.003743 +v 0.009471 -0.001169 -0.004319 +v 0.010374 -0.002338 -0.003265 +v 0.012731 -0.002167 -0.002492 +v 0.009277 0.001908 0.004151 +v 0.012130 0.001454 0.003104 +v 0.013561 0.001410 0.002886 +v 0.010459 0.002275 0.003246 +v 0.008947 -0.002524 -0.004067 +v 0.008195 0.003568 0.003932 +v 0.007823 -0.001315 -0.005485 +v 0.013300 -0.001248 -0.002971 +v 0.007458 -0.003565 -0.004807 +v 0.011278 -0.001521 -0.003336 +v 0.009469 -0.002749 0.003506 +v 0.007978 -0.003570 0.004182 +v 0.007932 0.003569 -0.004239 +v 0.007864 -0.001979 0.005243 +v 0.006353 -0.003565 0.006181 +v 0.006382 0.003569 0.006142 +v 0.007801 0.001957 0.005323 +v 0.005982 0.003570 -0.006574 +v 0.007686 0.002485 -0.005200 +v 0.006451 -0.000399 -0.007015 +v 0.007935 0.000670 -0.005497 +v 0.009789 0.001821 -0.003885 +v 0.010859 0.002137 -0.003167 +v 0.012147 0.002153 -0.002682 +v 0.006546 -0.003571 -0.005945 +v 0.006352 -0.002276 -0.006763 +v 0.013920 -0.002964 0.001181 +v 0.010964 -0.002253 0.003047 +v 0.009520 -0.001680 0.004093 +v 0.012159 -0.001930 0.002847 +v 0.007652 -0.000003 0.005800 +v 0.006262 -0.001392 0.007088 +v 0.013656 -0.002237 0.002310 +v 0.008687 -0.000777 0.004896 +v 0.008743 0.000444 0.004900 +v 0.006553 0.001561 0.006763 +v 0.008596 0.001973 -0.004623 +v 0.006297 0.001240 -0.007087 +v 0.006483 0.002741 -0.006431 +v 0.013969 0.002334 -0.002168 +v -0.009459 0.001033 0.000707 +v -0.009471 0.001159 -0.000209 +v -0.009520 -0.000610 -0.000284 +v -0.009467 -0.000409 0.001143 +v 0.006233 0.000245 0.007232 +v -0.001931 0.002589 -0.008985 +v -0.002360 0.003570 -0.008530 +v -0.000007 0.003572 -0.008864 +v -0.008936 0.002292 -0.002463 +v -0.008797 0.003571 -0.000940 +v -0.008379 0.003570 -0.002857 +v -0.009137 0.002660 -0.000671 +v -0.009134 0.002643 0.000741 +v -0.008748 0.003571 0.001321 +v -0.000007 -0.003572 0.008864 +v -0.001930 -0.002589 0.008985 +v -0.002360 -0.003570 0.008530 +v -0.004392 -0.003560 -0.007718 +v -0.005818 -0.003572 -0.006666 +v -0.005778 -0.002286 -0.007255 +v 0.005225 -0.003564 -0.007160 +v 0.004120 -0.002229 -0.008323 +v 0.003008 -0.003563 -0.008355 +v 0.005481 -0.003567 0.006954 +v 0.004338 -0.002288 0.008205 +v 0.004172 -0.003571 0.007802 +v 0.002658 -0.003562 0.008460 +v 0.001567 -0.002584 0.009052 +v 0.005226 0.003564 0.007160 +v 0.004118 0.002224 0.008323 +v 0.003008 0.003564 0.008355 +v 0.004539 0.001688 -0.008255 +v 0.004059 0.003568 -0.007872 +v 0.002658 0.003562 -0.008459 +v 0.001567 0.002583 -0.009052 +v -0.000346 -0.001686 0.009408 +v 0.004467 -0.000733 0.008428 +v 0.002056 -0.001443 0.009223 +v -0.001689 0.000090 0.009419 +v 0.002455 -0.000086 0.009222 +v 0.000531 -0.000312 0.009524 +v 0.005219 0.001277 0.007900 +v 0.003260 0.001179 0.008907 +v 0.001463 0.001537 0.009316 +v -0.000013 0.001623 0.009422 +v -0.002209 0.001487 0.009192 +v 0.000882 0.003571 0.008824 +v -0.001843 0.003573 0.008679 +v -0.003120 0.002506 0.008667 +v -0.003229 -0.000960 0.008945 +v -0.003308 -0.003562 0.008247 +v -0.004338 0.003571 0.007712 +v -0.004222 0.001183 0.008481 +v -0.005217 0.002329 0.007666 +v -0.004774 -0.000607 0.008245 +v -0.004769 -0.002080 0.008005 +v -0.005636 0.000186 0.007717 +v -0.005276 -0.003569 0.007114 +v 0.002117 0.000869 -0.009289 +v 0.002677 -0.000896 -0.009127 +v 0.001463 -0.001537 -0.009316 +v -0.000089 -0.000312 -0.009538 +v -0.001330 0.000930 -0.009419 +v -0.002254 -0.001005 -0.009232 +v -0.003295 0.000903 -0.008935 +v -0.004201 -0.000915 -0.008535 +v -0.000089 -0.001863 -0.009368 +v 0.005362 -0.001009 -0.007850 +v 0.004039 -0.000210 -0.008659 +v -0.002556 -0.002339 -0.008925 +v -0.005349 -0.000506 -0.007888 +v 0.000882 -0.003571 -0.008824 +v -0.001843 -0.003573 -0.008679 +v -0.005818 0.003572 0.006666 +v -0.006107 -0.001895 0.007098 +v -0.006817 -0.001487 -0.006538 +v -0.005675 0.000659 -0.007662 +v -0.006777 0.002575 0.006204 +v -0.006558 0.001136 0.006839 +v -0.006648 -0.003571 0.005852 +v -0.007144 -0.003570 -0.005235 +v -0.007495 -0.000042 -0.005947 +v -0.007186 0.003571 0.005161 +v -0.007234 -0.000265 0.006226 +v -0.007169 -0.001776 0.006050 +v -0.007720 0.001661 0.005401 +v -0.007954 -0.002009 -0.004885 +v -0.008084 -0.002167 0.004606 +v -0.007629 -0.003570 0.004488 +v -0.007982 -0.003565 -0.003830 +v -0.007982 0.003566 0.003830 +v -0.008279 -0.000330 0.004741 +v -0.008452 -0.000521 -0.004406 +v -0.008588 0.001569 0.003899 +v -0.008447 -0.003567 0.002692 +v -0.007652 0.003571 -0.004444 +v -0.008338 0.001792 -0.004328 +v -0.006532 0.003569 -0.005977 +v -0.007540 0.002231 -0.005440 +v -0.008499 -0.003566 -0.002511 +v -0.008678 -0.002007 -0.003403 +v -0.008499 0.003566 0.002511 +v -0.008727 -0.001535 0.003562 +v -0.005276 0.003569 -0.007114 +v -0.006331 0.002082 -0.006837 +v -0.003308 0.003562 -0.008248 +v -0.004772 0.002083 -0.008004 +v 0.000200 0.001640 -0.009421 +v -0.008993 0.000695 -0.003165 +v -0.009051 0.000402 0.003029 +v -0.009065 -0.000791 -0.002886 +v -0.009251 0.001489 0.001873 +v -0.009111 -0.001380 0.002474 +v -0.009246 -0.002022 0.001302 +v -0.008849 -0.003569 0.000548 +v -0.008748 -0.003571 -0.001321 +v -0.009190 -0.002072 -0.001585 +v -0.009305 0.001694 -0.001255 +v -0.009310 -0.002085 -0.000108 +v -0.009422 0.000031 -0.001564 +v -0.006425 0.003572 0.001735 +v -0.005289 0.003572 0.004001 +v -0.006550 0.003572 -0.001173 +v -0.000471 0.003572 -0.006638 +v 0.006654 0.003572 0.000079 +v 0.005984 0.003572 0.002911 +v -0.003396 0.003572 0.005723 +v -0.001001 0.003572 0.006556 +v -0.003259 0.003572 -0.005802 +v 0.005300 0.003572 -0.004025 +v 0.004169 0.003572 0.005187 +v -0.005423 0.003572 -0.003857 +v 0.002752 0.003572 -0.006092 +v 0.006294 0.003572 -0.002036 +v 0.001557 0.003572 0.006470 +v -0.006052 -0.003572 -0.002768 +v -0.006654 -0.003572 0.000079 +v -0.005984 -0.003572 0.002911 +v 0.003822 -0.003572 -0.005399 +v 0.005423 -0.003572 -0.003857 +v 0.006550 -0.003572 -0.001173 +v 0.001911 -0.003572 -0.006374 +v -0.004018 -0.003572 -0.005343 +v -0.000992 -0.003572 -0.006580 +v -0.003900 -0.003572 0.005429 +v -0.000836 -0.003572 0.006602 +v 0.006425 -0.003572 0.001735 +v 0.002412 -0.003572 0.006234 +v 0.005070 -0.003572 0.004311 +v -0.006514 -0.000532 -0.000438 +v -0.006522 -0.000511 0.000319 +v -0.006531 0.000610 0.000020 +v -0.003635 0.004763 0.002657 +v -0.004339 0.004755 0.001291 +v -0.004559 0.003957 0.002578 +v -0.005088 -0.004132 0.000428 +v -0.004512 -0.004762 -0.000368 +v -0.004285 -0.004762 0.001385 +v -0.004826 -0.004250 -0.001316 +v -0.004008 -0.004758 -0.002069 +v -0.001483 -0.003977 -0.005014 +v -0.000012 -0.004761 -0.004520 +v -0.002213 -0.004752 -0.004000 +v 0.006534 0.000396 0.000267 +v 0.006520 0.000107 -0.000631 +v 0.006473 0.000933 -0.000333 +v 0.006334 0.001692 0.000269 +v 0.006350 0.001224 -0.001068 +v 0.006058 0.002379 -0.000765 +v 0.005986 0.000243 0.002667 +v 0.006419 0.000394 0.001303 +v 0.006221 0.001164 0.001726 +v 0.006355 -0.001447 -0.000725 +v 0.006452 -0.000932 0.000719 +v 0.006191 -0.002125 0.000509 +v 0.006495 -0.000679 -0.000458 +v 0.006530 -0.000362 0.000314 +v 0.006016 -0.002576 -0.000344 +v 0.005932 0.002808 0.000208 +v 0.005263 -0.000367 0.003907 +v 0.005371 0.000615 0.003707 +v 0.006084 0.000877 -0.002280 +v 0.006381 -0.000060 -0.001532 +v 0.005947 -0.000406 -0.002749 +v 0.005482 -0.003453 -0.001063 +v 0.005508 -0.003576 -0.000046 +v 0.005542 0.000854 -0.003395 +v 0.005560 -0.000103 -0.003476 +v 0.004683 0.001171 -0.004445 +v 0.004725 -0.000161 -0.004553 +v 0.004762 -0.004076 -0.001944 +v 0.004431 -0.004758 -0.000868 +v 0.005489 0.003332 -0.001361 +v 0.005110 0.004064 -0.000620 +v 0.005478 0.003599 0.000454 +v 0.004505 0.004761 0.000452 +v 0.004257 0.004757 -0.001559 +v 0.005975 -0.002227 -0.001518 +v 0.004493 -0.004761 0.000510 +v 0.005570 -0.003212 0.001269 +v 0.006174 -0.001660 0.001429 +v 0.005047 -0.003961 0.001425 +v 0.005753 -0.002394 0.002050 +v 0.003871 0.004761 0.002319 +v 0.004850 0.004137 0.001557 +v 0.005849 0.002590 0.001504 +v 0.003911 -0.004761 -0.002262 +v 0.005087 -0.003291 0.002524 +v 0.003992 -0.004760 0.002098 +v 0.006203 -0.000771 0.001983 +v 0.005263 0.002114 -0.003304 +v 0.005397 -0.002316 0.002912 +v 0.004043 -0.004059 0.003202 +v 0.004931 0.003573 0.002445 +v 0.004527 0.003986 -0.002593 +v 0.005385 0.002993 -0.002251 +v 0.003499 0.004761 -0.002836 +v 0.006010 0.002037 -0.001642 +v 0.005780 0.001683 -0.002601 +v 0.005411 -0.002867 -0.002363 +v 0.005803 -0.001061 0.002865 +v 0.004100 0.004022 0.003125 +v 0.004529 0.002549 -0.004005 +v 0.003971 0.001738 -0.004929 +v 0.004358 -0.003834 -0.003074 +v 0.002679 0.004763 0.003637 +v 0.003521 0.003866 0.003972 +v 0.002793 -0.004757 -0.003569 +v 0.003390 0.002734 -0.004919 +v 0.004834 0.002840 0.003436 +v 0.003548 0.003873 -0.003930 +v 0.002557 0.004760 -0.003719 +v 0.004626 0.003299 -0.003272 +v 0.006091 -0.001414 -0.001996 +v 0.002931 -0.004023 0.004280 +v 0.002881 -0.004761 0.003495 +v 0.002539 0.003980 -0.004555 +v 0.002193 0.003084 -0.005366 +v 0.005723 0.002223 0.002298 +v 0.001318 0.004032 -0.005010 +v 0.003840 -0.003500 -0.004015 +v 0.004416 -0.003257 0.003590 +v 0.001588 0.004761 -0.004206 +v 0.001415 0.004749 0.004310 +v 0.002476 0.004086 0.004473 +v 0.000012 0.004761 -0.004520 +v 0.001432 -0.004761 -0.004268 +v 0.002429 -0.003792 -0.004772 +v 0.004902 -0.002455 -0.003623 +v 0.001440 -0.004760 0.004265 +v 0.004132 0.000279 -0.005080 +v -0.001124 0.001107 0.006383 +v -0.002061 -0.000758 0.006200 +v -0.000425 -0.000294 0.006553 +v 0.000491 0.000697 0.006501 +v 0.001148 -0.000650 0.006436 +v 0.002271 0.000736 0.006129 +v 0.002538 -0.000545 0.006029 +v 0.003775 0.000261 0.005360 +v 0.004621 0.000141 0.004662 +v 0.000297 0.002055 0.006237 +v 0.001629 0.001659 0.006129 +v 0.003837 0.001472 0.005125 +v 0.004807 0.001824 0.004084 +v -0.001025 0.002632 0.005922 +v -0.002063 0.001715 0.006004 +v 0.002547 0.002193 0.005636 +v 0.003764 0.002567 0.004729 +v 0.005678 0.001431 0.002955 +v 0.001126 0.003334 0.005560 +v 0.002455 0.003157 0.005219 +v -0.000057 0.003667 0.005447 +v -0.001526 0.003859 0.005086 +v 0.000028 0.004761 0.004521 +v -0.001440 0.004760 0.004265 +v -0.001393 0.003914 -0.005076 +v -0.001432 0.004761 -0.004268 +v 0.000000 0.003704 -0.005425 +v -0.001302 0.002542 -0.005916 +v 0.000837 0.002472 -0.006029 +v -0.000284 0.001946 -0.006278 +v 0.002023 0.001918 -0.005938 +v 0.002817 0.001365 -0.005769 +v -0.001616 0.000861 -0.006303 +v 0.000824 0.001022 -0.006429 +v 0.001847 0.000702 -0.006248 +v -0.000026 -0.000013 -0.006574 +v 0.003148 0.000426 -0.005741 +v -0.000962 -0.000161 -0.006486 +v 0.001282 -0.000399 -0.006419 +v 0.002465 -0.000533 -0.006061 +v 0.003736 -0.000742 -0.005336 +v -0.001184 -0.001489 -0.006294 +v -0.001954 -0.000617 -0.006234 +v 0.000296 -0.001639 -0.006350 +v 0.005061 -0.001187 -0.004003 +v 0.001888 -0.001895 -0.006000 +v 0.003017 -0.001618 -0.005596 +v 0.004057 -0.001600 -0.004896 +v 0.001028 -0.002630 -0.005922 +v -0.000392 -0.002948 -0.005857 +v 0.005471 -0.001728 -0.003182 +v -0.001720 -0.002867 -0.005640 +v 0.002404 -0.002893 -0.005386 +v 0.003668 -0.002813 -0.004660 +v 0.000047 -0.003743 -0.005396 +v 0.001393 -0.003914 -0.005076 +v -0.002405 0.002891 0.005385 +v -0.002397 0.002923 -0.005373 +v -0.002730 0.000157 0.005973 +v -0.002556 -0.002016 -0.005705 +v -0.002539 0.001731 -0.005806 +v -0.002433 0.003796 -0.004773 +v -0.002587 0.004762 0.003690 +v -0.002691 0.003748 0.004669 +v -0.002793 0.004756 -0.003569 +v -0.002884 -0.003162 -0.004968 +v -0.003067 -0.000020 -0.005816 +v -0.003494 0.001410 0.005386 +v -0.003649 0.004174 0.003511 +v -0.002498 -0.004760 -0.003753 +v -0.003748 -0.003777 -0.003850 +v -0.003534 -0.001352 -0.005349 +v -0.003808 0.001249 -0.005200 +v -0.003532 0.003320 -0.004420 +v -0.003770 0.003047 0.004440 +v -0.003370 -0.004761 -0.002980 +v -0.003787 -0.002548 -0.004727 +v -0.003822 0.000308 -0.005322 +v -0.003775 0.002169 -0.004903 +v -0.003594 -0.000660 0.005465 +v -0.004066 0.003891 -0.003374 +v -0.003944 0.004762 -0.002211 +v -0.003559 -0.004761 0.002770 +v -0.002595 -0.004762 0.003690 +v -0.003787 -0.003836 0.003748 +v -0.001415 -0.004749 0.004310 +v -0.002775 -0.003833 0.004548 +v 0.001468 -0.003883 0.005091 +v -0.000028 -0.004761 0.004521 +v -0.004042 -0.002722 0.004407 +v -0.001704 -0.003500 0.005295 +v -0.000330 -0.003598 0.005488 +v 0.003820 -0.002838 0.004514 +v 0.002372 -0.003081 0.005299 +v 0.004974 -0.001977 0.003812 +v 0.000411 -0.002780 0.005951 +v -0.003250 -0.002264 0.005246 +v -0.001780 -0.002366 0.005868 +v 0.003516 -0.002139 0.005114 +v -0.001315 -0.001804 0.006178 +v 0.001991 -0.001868 0.005967 +v 0.004550 -0.001324 0.004530 +v 0.000508 -0.001710 0.006324 +v 0.003384 -0.001165 0.005518 +v -0.004307 -0.001190 0.004815 +v -0.004587 -0.003820 -0.002737 +v -0.004435 -0.001024 -0.004734 +v -0.004818 0.002617 -0.003628 +v -0.004571 0.002761 0.003831 +v -0.004518 0.001491 0.004509 +v -0.004576 0.000192 0.004709 +v -0.004450 -0.004131 0.002482 +v -0.004712 -0.002519 -0.003813 +v -0.004827 0.000544 -0.004413 +v -0.004658 0.001871 -0.004213 +v -0.004645 0.003795 -0.002657 +v -0.004894 -0.002608 0.003511 +v -0.004431 0.004741 -0.001063 +v -0.004981 -0.003256 0.002758 +v -0.005235 -0.001196 0.003770 +v -0.005395 -0.003401 0.001570 +v -0.005047 -0.001057 -0.004070 +v -0.005227 0.003410 -0.002029 +v -0.005470 -0.000135 0.003628 +v -0.005325 -0.002893 -0.002520 +v -0.005489 0.001394 -0.003319 +v -0.005444 0.003649 -0.000393 +v -0.004517 0.004756 0.000226 +v -0.005584 0.003376 0.000752 +v -0.005436 0.003312 0.001606 +v -0.005345 0.002626 0.002758 +v -0.005227 0.001423 0.003711 +v -0.005565 -0.003385 -0.000839 +v -0.005656 -0.001802 -0.002794 +v -0.005510 -0.000395 -0.003555 +v -0.005716 -0.002001 0.002550 +v -0.005821 0.002161 -0.002135 +v -0.005810 -0.002948 0.000728 +v -0.005880 -0.002418 -0.001592 +v -0.005842 0.002772 -0.001105 +v -0.005882 0.002103 0.001987 +v -0.005796 0.001026 0.002900 +v -0.006103 -0.000721 0.002318 +v -0.005964 -0.000238 -0.002729 +v -0.006021 0.000802 -0.002466 +v -0.006141 -0.001807 0.001408 +v -0.006001 -0.002597 -0.000415 +v -0.006093 -0.001326 -0.002027 +v -0.006192 0.002168 -0.000137 +v -0.006214 0.001864 0.000988 +v -0.006114 0.001109 0.002078 +v -0.006298 -0.001807 0.000395 +v -0.006278 0.000311 0.001868 +v -0.006302 -0.001668 -0.000683 +v -0.006328 0.000534 -0.001641 +v -0.006328 0.001403 -0.000996 +v -0.006369 -0.000780 -0.001351 +v -0.006421 -0.000695 0.001119 +v -0.006463 0.000624 0.000923 +v -0.006505 0.000388 -0.000677 +v 0.003522 0.004762 -0.000336 +v -0.001157 0.004762 0.003344 +v -0.002508 0.004762 0.002454 +v -0.003373 0.004762 0.001050 +v -0.003360 0.004762 -0.001252 +v -0.001905 0.004762 -0.002964 +v 0.003274 0.004762 0.001262 +v 0.002198 0.004762 0.002794 +v 0.000500 0.004762 0.003476 +v 0.000000 0.004762 -0.003560 +v 0.001905 0.004762 -0.002964 +v 0.002955 0.004762 -0.001899 +v -0.002542 -0.004762 -0.002424 +v -0.001157 -0.004762 -0.003344 +v -0.003455 -0.004762 -0.000838 +v -0.003343 -0.004762 0.001102 +v -0.002198 -0.004762 0.002794 +v 0.001395 -0.004761 -0.003304 +v 0.003360 -0.004762 -0.001252 +v 0.003291 -0.004762 0.001388 +v -0.000335 -0.004762 0.003508 +v 0.001629 -0.004762 0.003160 +v 0.000877 0.004446 -0.003075 +v 0.001209 -0.004442 -0.002988 +v 0.001964 0.004444 -0.002510 +v 0.002576 -0.004445 -0.001904 +v 0.002667 0.004446 -0.001746 +v 0.003155 0.004444 -0.000547 +v 0.003053 -0.004445 -0.000891 +v 0.003190 -0.004445 0.000400 +v 0.003083 0.004442 0.000826 +v 0.002399 -0.004445 0.002147 +v 0.002526 0.004446 0.001945 +v 0.001607 0.004444 0.002764 +v 0.000815 -0.004445 0.003111 +v 0.000094 0.004445 0.003215 +v -0.000847 -0.004445 0.003089 +v -0.001300 0.004446 0.002910 +v -0.002272 -0.004445 0.002273 +v -0.002257 0.004442 0.002256 +v -0.002983 0.004446 0.001137 +v -0.003110 -0.004443 0.000742 +v -0.003195 0.004446 -0.000365 +v -0.003116 -0.004443 -0.000767 +v -0.002537 0.004446 -0.001965 +v -0.002359 -0.004444 -0.002166 +v -0.001337 0.004444 -0.002904 +v -0.000906 -0.004445 -0.003090 +v -0.000304 0.004444 -0.003168 +v 0.019999 0.004801 0.001159 +v 0.020000 0.003387 -0.003494 +v 0.020000 0.002933 0.003974 +v 0.020000 0.001159 -0.004801 +v 0.020000 0.000108 0.004895 +v 0.020000 -0.001776 -0.004563 +v 0.020000 -0.002731 0.004115 +v 0.020000 -0.004115 -0.002731 +v 0.020000 -0.004563 0.001776 +v 0.020000 0.004563 -0.001776 +v 0.020000 -0.004854 -0.000349 +v 0.022046 -0.001916 -0.002766 +v 0.022046 -0.001992 0.002774 +v 0.022046 -0.003301 0.000858 +v 0.022046 0.003250 -0.000866 +v 0.022046 0.003301 0.000858 +v 0.022046 0.002605 -0.002152 +v 0.022046 0.001992 0.002774 +v 0.022046 0.001423 -0.003048 +v 0.022046 -0.000000 0.003386 +v 0.022046 -0.000286 -0.003396 +v 0.022046 -0.003107 -0.001416 +v 0.480001 0.004908 0.000553 +v 0.480000 0.003404 0.003579 +v 0.480000 0.004294 -0.002354 +v 0.480001 -0.004527 0.001975 +v 0.480000 0.000553 -0.004908 +v 0.480000 0.002852 -0.003942 +v 0.480001 0.000307 0.004929 +v 0.480000 -0.002541 0.004186 +v 0.480000 -0.004802 -0.000956 +v 0.480000 -0.003681 -0.003229 +v 0.480000 -0.001988 -0.004442 +v 0.476574 -0.002759 -0.001920 +v 0.476574 -0.003333 -0.000589 +v 0.476574 -0.003248 0.000867 +v 0.476574 -0.001744 -0.002909 +v 0.476574 -0.002595 0.002174 +v 0.476574 0.002787 -0.001961 +v 0.476574 0.001441 0.003088 +v 0.476574 0.003081 0.001473 +v 0.476574 0.001423 -0.003048 +v 0.476574 -0.000848 0.003308 +v 0.476574 0.000000 -0.003381 +v 0.476574 0.003350 -0.000306 +v 0.028491 0.006314 -0.001117 +v 0.471509 0.006412 0.000004 +v 0.471509 0.005555 -0.003203 +v 0.028502 0.005220 -0.003658 +v 0.471498 0.003657 -0.005219 +v 0.028502 0.003654 -0.005222 +v 0.471498 0.001652 -0.006156 +v 0.028502 0.001647 -0.006157 +v 0.471498 -0.000553 -0.006349 +v 0.028491 -0.001117 -0.006314 +v 0.471498 -0.002691 -0.005777 +v 0.028502 -0.003658 -0.005220 +v 0.471498 -0.004505 -0.004509 +v 0.028502 -0.005222 -0.003654 +v 0.471509 -0.006024 -0.002197 +v 0.028491 -0.006315 -0.001110 +v 0.471498 -0.006349 0.000553 +v 0.028502 -0.006156 0.001652 +v 0.471498 -0.005777 0.002692 +v 0.028502 -0.005220 0.003657 +v 0.471498 -0.004508 0.004505 +v 0.028502 -0.003654 0.005222 +v 0.471498 -0.002696 0.005775 +v 0.028491 -0.001110 0.006315 +v 0.471498 -0.000558 0.006349 +v 0.471498 0.001647 0.006157 +v 0.028502 0.001652 0.006156 +v 0.471498 0.003654 0.005222 +v 0.028502 0.003658 0.005220 +v 0.471509 0.005551 0.003209 +v 0.028502 0.005222 0.003654 +v 0.028502 0.006157 0.001647 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vn -0.6721 0.0731 -0.7368 +vn -0.6284 -0.1880 -0.7548 +vn -0.6836 -0.2336 -0.6915 +vn -0.4448 -0.7885 0.4248 +vn -0.6946 -0.2329 0.6807 +vn -0.6816 -0.1818 0.7087 +vn -0.6700 0.2833 0.6862 +vn -0.4392 0.7925 0.4231 +vn -0.3861 0.8445 0.3712 +vn -0.6352 0.2261 -0.7385 +vn -0.6718 -0.0007 -0.7408 +vn -0.3037 -0.8830 0.3579 +vn -0.4089 -0.8281 0.3835 +vn -0.5913 -0.3867 0.7077 +vn -0.2762 -0.8119 0.5144 +vn -0.1456 -0.9783 0.1473 +vn -0.2392 -0.9291 0.2821 +vn -0.2159 -0.9441 -0.2490 +vn -0.4725 -0.6162 -0.6301 +vn -0.3414 -0.8577 -0.3845 +vn -0.0995 0.9507 -0.2936 +vn -0.0171 0.9070 -0.4209 +vn -0.0566 0.9940 0.0939 +vn -0.1677 0.9837 -0.0647 +vn -0.2439 0.8295 -0.5024 +vn -0.2690 -0.0895 0.9590 +vn -0.0994 0.3628 0.9266 +vn -0.0618 0.0520 0.9967 +vn -0.2121 -0.3212 -0.9229 +vn -0.0519 -0.5697 -0.8202 +vn -0.2166 -0.1472 -0.9651 +vn -0.0306 -0.2207 -0.9749 +vn -0.1697 0.9786 -0.1165 +vn -0.1563 0.9763 0.1494 +vn -0.1843 0.9419 0.2809 +vn -0.1005 -0.9841 0.1467 +vn -0.1499 -0.9796 -0.1340 +vn -0.0997 -0.9772 -0.1873 +vn -0.1835 0.9574 -0.2231 +vn -0.2711 0.8121 0.5168 +vn -0.2289 0.9351 0.2705 +vn -0.4315 -0.0173 0.9019 +vn -0.3099 0.2168 0.9257 +vn -0.1048 -0.8774 0.4681 +vn -0.0934 -0.8595 -0.5025 +vn -0.3213 -0.7697 -0.5516 +vn -0.3662 0.6872 -0.6274 +vn -0.1713 -0.3474 0.9219 +vn -0.0218 -0.3439 0.9387 +vn -0.2727 0.9071 -0.3207 +vn -0.1258 0.7125 -0.6903 +vn -0.1078 -0.6766 0.7284 +vn -0.2849 0.0822 -0.9550 +vn -0.0856 0.2242 -0.9708 +vn -0.0461 0.6081 -0.7925 +vn -0.5528 -0.1589 0.8180 +vn -0.4320 -0.3598 0.8270 +vn -0.4340 -0.6147 0.6587 +vn -0.3405 0.8709 -0.3543 +vn -0.4264 0.4174 -0.8025 +vn -0.2888 0.4394 -0.8506 +vn -0.2938 -0.5052 0.8114 +vn -0.5817 0.0074 -0.8133 +vn -0.5420 0.3108 -0.7808 +vn -0.4629 0.0449 -0.8853 +vn -0.6553 0.2925 -0.6965 +vn -0.1668 0.4274 -0.8886 +vn -0.4092 0.8344 -0.3693 +vn -0.5736 -0.2486 -0.7805 +vn -0.4846 -0.3487 -0.8023 +vn -0.3991 -0.2256 -0.8887 +vn -0.3704 -0.4853 -0.7920 +vn -0.2254 -0.6119 -0.7581 +vn -0.4410 0.7933 -0.4198 +vn -0.5693 0.3977 0.7196 +vn -0.2870 0.8862 0.3637 +vn -0.3044 0.5650 0.7669 +vn -0.1015 0.8604 0.4994 +vn -0.4295 0.3616 0.8275 +vn -0.5658 0.1142 0.8166 +vn -0.6735 0.1002 0.7323 +vn -0.1029 0.6541 0.7494 +vn -0.4374 -0.8044 -0.4020 +vn 0.0511 -0.7296 -0.6819 +vn 0.9925 -0.0709 0.0996 +vn 0.9952 -0.0391 -0.0895 +vn 0.9992 0.0350 0.0211 +vn -0.6747 -0.0910 0.7324 +vn 0.1711 -0.2532 -0.9521 +vn 0.2110 -0.7857 -0.5815 +vn 0.0329 -0.7893 -0.6131 +vn 0.9287 -0.2475 -0.2762 +vn 0.5983 -0.7968 -0.0845 +vn 0.5730 -0.7956 -0.1966 +vn 0.5983 -0.7989 0.0619 +vn 0.9536 -0.2994 -0.0319 +vn 0.9560 -0.2727 0.1077 +vn 0.5749 0.7908 -0.2100 +vn 0.5899 0.8026 -0.0889 +vn 0.9530 0.2667 -0.1440 +vn -0.0294 0.7953 -0.6056 +vn -0.0458 0.2469 -0.9679 +vn -0.1570 0.7854 -0.5987 +vn -0.6345 0.0397 0.7719 +vn -0.3566 0.7917 -0.4960 +vn -0.6377 0.2202 0.7381 +vn -0.3521 0.7902 0.5017 +vn -0.5919 -0.2097 0.7782 +vn -0.3556 -0.7999 0.4833 +vn -0.4007 -0.7827 -0.4762 +vn -0.2931 0.7790 -0.5543 +vn -0.4128 0.1908 -0.8906 +vn -0.3779 0.2509 0.8912 +vn -0.2375 0.8000 0.5509 +vn -0.1073 0.7873 0.6072 +vn -0.4537 -0.2757 0.8474 +vn -0.2121 -0.7978 0.5644 +vn -0.3026 -0.2230 0.9267 +vn -0.0664 -0.7756 0.6278 +vn -0.2854 -0.7863 -0.5480 +vn -0.4454 -0.2205 -0.8677 +vn -0.1209 -0.7795 -0.6146 +vn -0.2242 -0.2101 -0.9516 +vn -0.5009 0.1384 0.8544 +vn -0.1200 0.2248 0.9670 +vn 0.0623 0.7709 0.6339 +vn 0.0735 0.1071 0.9915 +vn 0.1503 0.7736 0.6155 +vn 0.2231 0.1114 0.9684 +vn -0.3494 0.0420 0.9360 +vn -0.2282 0.1479 0.9623 +vn -0.0609 -0.0278 0.9978 +vn -0.4626 -0.0778 0.8831 +vn -0.1997 -0.1240 0.9720 +vn 0.0446 -0.1653 0.9852 +vn 0.2345 -0.1543 0.9598 +vn 0.0814 -0.7840 0.6155 +vn 0.1998 -0.7792 0.5940 +vn 0.3613 0.0612 0.9304 +vn 0.2361 0.7659 0.5981 +vn 0.2855 -0.7990 0.5293 +vn 0.3967 -0.1944 0.8971 +vn 0.5010 -0.0260 0.8651 +vn 0.5149 0.1855 0.8369 +vn 0.3277 0.7911 0.5165 +vn 0.5484 -0.2172 0.8075 +vn -0.4138 -0.0699 -0.9077 +vn -0.5589 0.0483 -0.8278 +vn -0.2724 0.0154 -0.9621 +vn -0.1994 0.1757 -0.9640 +vn -0.0560 0.0352 -0.9978 +vn 0.3276 -0.0518 -0.9434 +vn 0.1402 -0.0306 -0.9897 +vn 0.1883 0.1651 -0.9681 +vn 0.5155 -0.0334 -0.8562 +vn 0.5087 0.1201 -0.8525 +vn 0.4008 0.2176 -0.8899 +vn 0.1086 0.7765 -0.6207 +vn 0.3788 0.7714 -0.5113 +vn 0.2486 0.7908 -0.5593 +vn 0.4126 -0.7826 0.4662 +vn 0.6772 0.1802 -0.7134 +vn 0.6650 0.0108 -0.7467 +vn 0.6437 -0.0117 0.7652 +vn 0.4178 0.7803 0.4655 +vn 0.4424 0.7913 -0.4221 +vn 0.7148 -0.1842 0.6746 +vn 0.7040 0.2019 0.6809 +vn 0.4984 -0.7776 0.3832 +vn 0.7654 -0.0058 0.6435 +vn 0.5226 0.7824 0.3387 +vn 0.5153 0.7962 -0.3169 +vn 0.7920 0.2167 -0.5708 +vn 0.7951 -0.0239 -0.6060 +vn 0.8196 -0.1801 0.5439 +vn 0.8250 0.1937 0.5309 +vn 0.8859 0.0600 -0.4600 +vn 0.5507 -0.7846 0.2849 +vn 0.8580 -0.0154 0.5133 +vn 0.9000 0.2204 -0.3761 +vn 0.8975 -0.1670 0.4082 +vn 0.9130 0.0954 0.3967 +vn 0.9160 0.2262 0.3312 +vn 0.5910 0.7827 0.1951 +vn 0.5234 -0.7978 -0.2992 +vn 0.8441 -0.2321 -0.4834 +vn 0.4617 -0.7832 -0.4165 +vn 0.5955 -0.7810 0.1883 +vn 0.3273 -0.2351 -0.9152 +vn 0.4767 -0.2204 -0.8510 +vn 0.3778 -0.7801 -0.4987 +vn 0.6203 -0.1751 -0.7646 +vn 0.7232 -0.2054 -0.6594 +vn -0.0112 -0.1740 -0.9847 +vn 0.9136 -0.0949 -0.3953 +vn 0.9569 -0.1965 0.2139 +vn 0.9504 -0.0522 0.3067 +vn 0.9633 0.1984 0.1809 +vn 0.6187 0.7843 0.0446 +vn 0.9646 0.0780 -0.2519 +vn 0.9691 -0.2058 -0.1361 +vn 0.9724 -0.0832 -0.2180 +vn 0.9796 0.0440 0.1962 +vn 0.9817 0.1840 0.0482 +vn 0.9879 -0.1553 0.0053 +vn 0.9881 0.1269 -0.0873 +vn -0.5847 -0.7552 -0.2962 +vn -0.6451 -0.7640 0.0042 +vn -0.1649 -0.7633 0.6247 +vn 0.6227 -0.7477 0.2306 +vn 0.6397 -0.7665 -0.0564 +vn 0.5226 -0.7699 -0.3663 +vn -0.4331 -0.7447 -0.5077 +vn -0.4292 -0.7595 0.4888 +vn 0.1002 -0.7432 0.6615 +vn 0.2916 -0.7611 -0.5794 +vn -0.5942 -0.7523 0.2847 +vn 0.5065 -0.7461 0.4322 +vn -0.2342 -0.7476 -0.6214 +vn 0.0184 -0.7550 -0.6555 +vn 0.3041 -0.7545 0.5816 +vn -0.5890 0.7569 0.2830 +vn -0.6399 0.7508 -0.1639 +vn -0.6692 0.7399 0.0692 +vn 0.5556 0.7470 0.3652 +vn 0.3396 0.7642 0.5483 +vn -0.5165 0.7539 -0.4059 +vn 0.6496 0.7456 0.1491 +vn 0.0571 0.7576 0.6503 +vn -0.2112 0.7499 0.6269 +vn -0.4270 0.7552 0.4973 +vn -0.3202 0.7495 -0.5795 +vn -0.0383 0.7633 -0.6449 +vn 0.5067 0.7693 -0.3892 +vn 0.2672 0.7622 -0.5896 +vn 0.6406 0.7599 -0.1104 +vn 0.9920 -0.0278 -0.1227 +vn 0.9966 0.0805 0.0162 +vn 0.9976 -0.0249 0.0642 +vn 0.4499 -0.8908 -0.0632 +vn 0.7812 -0.6175 0.0917 +vn 0.4198 -0.9018 0.1021 +vn -0.3059 -0.5823 0.7532 +vn -0.2408 -0.8999 0.3635 +vn -0.0753 -0.8930 0.4437 +vn 0.7406 0.6482 0.1772 +vn 0.4554 0.8901 -0.0142 +vn 0.3983 0.9095 0.1187 +vn -0.9723 0.0122 0.2335 +vn -0.9973 -0.0342 0.0651 +vn -0.9726 -0.1565 0.1717 +vn -0.9874 -0.1536 -0.0377 +vn -0.9677 -0.1896 -0.1661 +vn -0.9278 -0.3713 -0.0367 +vn -0.9946 0.0998 -0.0298 +vn -0.9866 0.1359 0.0900 +vn -0.9736 0.2158 -0.0744 +vn -0.9329 -0.1680 0.3184 +vn -0.9914 -0.0074 -0.1304 +vn -0.9354 0.3203 -0.1500 +vn -0.9274 0.3618 0.0946 +vn -0.8593 0.5101 -0.0376 +vn -0.9029 0.1140 0.4145 +vn -0.8828 -0.1398 0.4485 +vn -0.8610 0.0384 0.5071 +vn -0.8685 0.4314 -0.2442 +vn -0.7956 -0.1701 0.5815 +vn -0.7904 0.1382 0.5968 +vn -0.8316 -0.5458 0.1028 +vn -0.8487 -0.5195 -0.0986 +vn -0.9401 -0.1049 -0.3243 +vn -0.9548 0.1097 -0.2763 +vn -0.9043 0.0373 -0.4253 +vn -0.9685 -0.2397 0.0673 +vn -0.8270 -0.1630 -0.5381 +vn -0.8023 0.0394 -0.5956 +vn -0.7549 0.5582 -0.3443 +vn -0.7778 0.6216 -0.0931 +vn -0.4317 0.8943 -0.1176 +vn -0.9104 -0.3584 0.2068 +vn -0.4545 -0.8901 -0.0321 +vn -0.4438 -0.8924 0.0816 +vn -0.8699 0.4705 0.1479 +vn -0.7797 0.5987 0.1834 +vn -0.4427 0.8944 0.0643 +vn -0.8703 0.3471 0.3494 +vn -0.8194 0.4614 0.3401 +vn -0.4167 -0.8921 0.1747 +vn -0.7807 -0.5852 -0.2194 +vn -0.4068 -0.8902 -0.2049 +vn -0.3644 0.9007 -0.2364 +vn -0.7454 0.5946 0.3012 +vn -0.9533 0.2416 0.1812 +vn -0.3997 0.8983 0.1827 +vn -0.7627 0.5409 0.3547 +vn -0.7634 -0.5917 0.2590 +vn -0.8780 -0.3707 -0.3030 +vn -0.7094 -0.5912 -0.3836 +vn -0.7264 0.5916 0.3498 +vn -0.9445 0.1685 0.2819 +vn -0.7723 0.4759 0.4207 +vn -0.6685 0.5606 0.4887 +vn -0.8279 -0.3969 0.3962 +vn -0.7171 -0.5811 0.3848 +vn -0.8393 -0.4745 0.2653 +vn -0.8311 -0.4601 -0.3123 +vn -0.8399 -0.4372 -0.3215 +vn -0.6329 -0.2991 -0.7142 +vn -0.6989 -0.1518 -0.6990 +vn -0.5176 -0.2132 -0.8286 +vn -0.7964 0.4012 0.4525 +vn -0.3691 0.8916 0.2625 +vn -0.8548 0.2873 0.4323 +vn -0.8088 0.3153 0.4964 +vn -0.8057 0.3190 0.4990 +vn -0.7729 0.4289 0.4676 +vn -0.3685 -0.8907 0.2662 +vn -0.6121 -0.6173 -0.4942 +vn -0.3145 -0.9028 -0.2933 +vn -0.8635 -0.5039 -0.0220 +vn -0.7930 -0.4383 -0.4232 +vn -0.7062 -0.4087 -0.5782 +vn -0.6167 -0.3714 -0.6941 +vn -0.5417 -0.3970 -0.7409 +vn -0.6779 0.6062 -0.4159 +vn -0.7252 -0.5489 0.4157 +vn -0.6845 -0.5830 -0.4377 +vn -0.8967 -0.2601 -0.3582 +vn -0.8502 -0.2475 -0.4647 +vn -0.7594 -0.2669 -0.5933 +vn -0.6685 -0.3367 -0.6631 +vn -0.4242 -0.4838 -0.7655 +vn -0.6238 0.6247 -0.4698 +vn -0.5702 -0.5373 -0.6214 +vn -0.4999 -0.5807 0.6426 +vn -0.6471 -0.5898 0.4831 +vn -0.3903 -0.6495 -0.6525 +vn -0.2429 -0.9015 -0.3582 +vn -0.2761 0.8906 -0.3614 +vn -0.6730 0.5296 -0.5163 +vn -0.8337 -0.4474 -0.3237 +vn -0.8537 -0.3299 -0.4029 +vn -0.6495 -0.5719 -0.5010 +vn -0.6287 -0.5757 0.5227 +vn -0.7135 -0.4983 0.4927 +vn -0.1254 -0.8996 -0.4183 +vn -0.2759 0.8936 0.3541 +vn -0.6903 -0.5019 -0.5212 +vn -0.2121 -0.5587 -0.8018 +vn -0.7281 -0.4092 0.5500 +vn -0.0963 0.8919 -0.4419 +vn -0.3607 0.5908 -0.7217 +vn -0.5174 0.4786 -0.7094 +vn -0.6985 0.3998 -0.5934 +vn -0.6682 0.5422 -0.5094 +vn -0.7786 0.4317 -0.4554 +vn -0.8586 0.3598 -0.3650 +vn -0.3750 0.5769 0.7257 +vn -0.5395 0.6126 0.5777 +vn -0.6058 0.5577 0.5674 +vn -0.6090 0.4911 0.6229 +vn -0.0001 -0.8930 -0.4501 +vn -0.8531 0.2414 -0.4625 +vn -0.0102 -0.0848 0.9963 +vn -0.2002 0.1016 0.9745 +vn -0.2384 -0.1579 0.9583 +vn -0.3615 0.1070 0.9262 +vn -0.3956 -0.0769 0.9152 +vn -0.5355 -0.1530 0.8306 +vn -0.5964 0.0501 0.8011 +vn -0.7056 -0.0552 0.7065 +vn 0.0098 -0.2856 0.9583 +vn 0.2384 -0.3103 0.9202 +vn 0.1916 -0.0746 0.9786 +vn -0.4925 -0.3045 0.8153 +vn -0.6554 -0.3175 0.6854 +vn -0.3980 -0.3846 0.8329 +vn -0.1910 -0.3764 0.9066 +vn 0.0752 -0.4554 0.8871 +vn -0.0933 -0.5644 0.8202 +vn -0.5491 -0.4409 0.7100 +vn -0.6027 -0.4429 0.6638 +vn -0.7957 0.3619 -0.4857 +vn 0.1466 -0.5810 0.8006 +vn -0.6510 -0.4910 0.5788 +vn 0.1003 -0.8923 0.4402 +vn 0.1824 -0.5943 -0.7833 +vn 0.1867 -0.8954 -0.4042 +vn 0.0383 -0.5790 -0.8145 +vn -0.0189 -0.4582 -0.8886 +vn 0.2422 -0.3939 -0.8867 +vn -0.1662 -0.2974 -0.9402 +vn -0.3561 -0.3156 -0.8795 +vn 0.0444 -0.2724 -0.9612 +vn 0.0690 -0.1413 -0.9876 +vn -0.2572 -0.0999 -0.9612 +vn -0.4604 -0.0080 -0.8877 +vn -0.6140 -0.0166 -0.7891 +vn -0.0704 0.0351 -0.9969 +vn 0.1791 0.0037 -0.9838 +vn -0.2314 0.1699 -0.9579 +vn -0.4393 0.1650 -0.8830 +vn -0.6515 0.1343 -0.7467 +vn 0.1512 0.1800 -0.9720 +vn -0.0539 0.2518 -0.9663 +vn -0.7484 0.1956 -0.6337 +vn 0.1032 0.3303 -0.9382 +vn -0.3283 0.3665 -0.8706 +vn 0.2552 0.3971 -0.8816 +vn -0.6002 0.3572 -0.7157 +vn -0.1610 0.4261 -0.8902 +vn -0.4480 0.4117 -0.7936 +vn 0.0373 0.4549 -0.8897 +vn -0.6991 0.2625 -0.6651 +vn 0.0524 0.5840 -0.8100 +vn -0.2168 0.5883 -0.7791 +vn -0.5080 0.4323 -0.7450 +vn -0.8010 0.3849 -0.4585 +vn -0.9020 0.2837 -0.3253 +vn 0.0923 0.8960 -0.4344 +vn 0.3115 0.5786 -0.7538 +vn 0.3559 -0.5818 0.7314 +vn 0.3186 -0.4411 0.8390 +vn 0.2968 -0.2005 -0.9336 +vn 0.4121 -0.2450 0.8776 +vn 0.3371 -0.0155 0.9413 +vn 0.2484 0.8882 -0.3865 +vn 0.3403 0.1948 -0.9199 +vn 0.3415 -0.0352 -0.9392 +vn 0.3657 -0.5678 -0.7375 +vn 0.2481 -0.8944 0.3723 +vn 0.4428 0.4046 -0.8001 +vn 0.4251 -0.2967 -0.8551 +vn 0.5139 -0.4203 0.7479 +vn 0.5085 -0.1301 0.8512 +vn 0.5049 0.5571 -0.6594 +vn 0.5384 0.2355 -0.8091 +vn 0.4865 0.0750 -0.8704 +vn 0.5137 -0.1054 -0.8515 +vn 0.5081 -0.4652 -0.7249 +vn 0.5718 -0.5808 -0.5794 +vn 0.3264 -0.8874 -0.3255 +vn 0.3367 -0.8930 0.2986 +vn 0.5701 -0.5394 0.6196 +vn 0.3437 0.8878 -0.3059 +vn 0.5206 -0.2468 -0.8173 +vn 0.4986 -0.3679 -0.7849 +vn 0.5568 -0.3545 -0.7512 +vn 0.6209 -0.3479 0.7025 +vn 0.5467 0.6096 -0.5741 +vn 0.6316 0.3265 -0.7032 +vn 0.6287 -0.1869 -0.7548 +vn 0.6052 -0.3215 -0.7283 +vn 0.3662 0.9017 0.2297 +vn 0.2649 0.8906 0.3698 +vn 0.6461 0.6313 0.4290 +vn 0.5671 0.6039 0.5601 +vn 0.5295 0.5279 0.6641 +vn 0.3221 0.5562 0.7661 +vn 0.0966 0.8903 0.4451 +vn 0.0410 0.5608 0.8270 +vn -0.1037 0.8926 0.4388 +vn -0.2103 0.6294 0.7481 +vn -0.6067 0.5123 0.6078 +vn -0.6824 0.4765 0.5543 +vn -0.7419 0.4218 0.5212 +vn -0.1589 0.5082 0.8464 +vn -0.5998 0.3771 0.7057 +vn -0.7079 0.4364 0.5554 +vn -0.6688 0.4263 0.6090 +vn -0.7818 0.3466 0.5183 +vn -0.4019 0.4380 0.8042 +vn -0.5203 0.4785 0.7073 +vn -0.7274 0.3525 0.5888 +vn -0.8241 0.2635 0.5013 +vn 0.2328 0.3928 0.8897 +vn -0.6875 0.3578 0.6319 +vn -0.7096 0.2272 0.6670 +vn 0.4575 0.3392 0.8220 +vn 0.0015 0.3312 0.9436 +vn -0.1922 0.3085 0.9316 +vn -0.5255 0.1941 0.8284 +vn -0.3603 0.3382 0.8694 +vn 0.3051 0.1788 0.9354 +vn 0.1416 0.1686 0.9755 +vn 0.4646 0.1336 0.8754 +vn 0.6114 0.2755 0.7418 +vn -0.0267 0.1124 0.9933 +vn 0.5992 0.0475 0.7992 +vn 0.5116 0.5595 -0.6521 +vn 0.5884 0.4712 -0.6571 +vn 0.6577 0.0540 -0.7513 +vn 0.5828 -0.6218 0.5231 +vn 0.6433 -0.4012 0.6521 +vn 0.6299 -0.2095 0.7479 +vn 0.6121 0.5911 -0.5253 +vn -0.1334 -0.9508 -0.2795 +vn 0.6911 -0.3812 -0.6141 +vn 0.7915 -0.5398 -0.2865 +vn 0.7148 -0.5791 -0.3921 +vn 0.3877 -0.8993 -0.2021 +vn 0.6255 -0.6019 0.4964 +vn 0.6563 -0.4460 0.6086 +vn 0.6480 0.3845 0.6574 +vn 0.6281 0.4825 0.6104 +vn 0.4014 0.8911 -0.2119 +vn 0.6776 0.5884 -0.4412 +vn 0.6928 0.5578 -0.4571 +vn 0.6663 0.5095 -0.5445 +vn 0.6965 0.4448 -0.5630 +vn 0.7573 0.2099 -0.6185 +vn 0.3848 -0.8971 0.2173 +vn 0.6698 -0.6066 0.4282 +vn 0.6883 -0.5397 0.4847 +vn 0.6632 -0.5253 0.5332 +vn 0.7277 -0.0023 0.6859 +vn 0.6703 0.4241 0.6089 +vn 0.6551 0.5069 0.5602 +vn 0.6736 0.5264 0.5189 +vn 0.4464 0.8881 -0.1097 +vn 0.6985 0.6309 -0.3378 +vn 0.6935 0.6029 -0.3945 +vn 0.7423 0.4415 -0.5040 +vn 0.7008 0.4015 -0.5896 +vn 0.7413 -0.1556 -0.6529 +vn 0.4545 -0.6260 -0.6337 +vn 0.7090 -0.6160 0.3433 +vn 0.7194 -0.5511 0.4228 +vn 0.6930 -0.5433 0.4738 +vn 0.7433 -0.4305 0.5120 +vn 0.6459 -0.4058 0.6467 +vn 0.7290 -0.3238 0.6030 +vn 0.7267 -0.2893 0.6230 +vn 0.7846 -0.1322 0.6058 +vn 0.7405 0.1957 0.6429 +vn 0.7099 0.3882 0.5877 +vn 0.7119 0.4605 0.5303 +vn 0.7313 0.5152 0.4470 +vn 0.7625 0.3278 0.5579 +vn 0.7582 0.4001 0.5149 +vn 0.7570 0.4536 0.4703 +vn 0.7387 0.5885 0.3285 +vn 0.7434 0.5305 -0.4074 +vn 0.7534 0.4372 -0.4912 +vn 0.7523 0.4005 -0.5231 +vn 0.8077 0.0723 -0.5851 +vn 0.8163 -0.5294 0.2310 +vn 0.7427 -0.5095 0.4345 +vn 0.7778 0.4749 0.4117 +vn 0.7447 0.5380 0.3950 +vn 0.7395 0.6011 0.3030 +vn 0.8409 0.5177 -0.1575 +vn 0.7389 0.5631 -0.3701 +vn 0.7500 0.4574 -0.4779 +vn 0.8302 -0.2901 -0.4761 +vn 0.7451 -0.2581 -0.6150 +vn 0.7615 -0.4127 -0.4998 +vn 0.7811 -0.5642 -0.2673 +vn 0.8462 -0.5314 -0.0387 +vn 0.7817 -0.5050 0.3659 +vn 0.7983 -0.4622 0.3860 +vn 0.8014 -0.4370 0.4083 +vn 0.8302 0.1479 0.5375 +vn 0.8049 0.3531 0.4769 +vn 0.7997 0.4331 0.4158 +vn 0.7918 0.5471 0.2714 +vn 0.7316 0.6558 0.1863 +vn 0.8386 0.5437 0.0344 +vn 0.8403 0.4471 -0.3067 +vn 0.7939 0.4313 -0.4286 +vn 0.7813 0.4104 -0.4703 +vn 0.8060 0.2955 -0.5128 +vn 0.8598 -0.1113 -0.4984 +vn 0.8018 -0.4228 -0.4223 +vn 0.8251 -0.4036 0.3953 +vn 0.8116 -0.3518 0.4663 +vn 0.7754 -0.2800 0.5659 +vn 0.8845 0.2174 0.4127 +vn 0.8350 0.3673 0.4097 +vn 0.8388 0.4101 0.3581 +vn 0.8326 0.4195 -0.3617 +vn 0.8292 0.3783 -0.4114 +vn 0.8507 0.2549 -0.4597 +vn 0.8215 -0.4512 -0.3487 +vn 0.8907 -0.4309 -0.1447 +vn 0.8334 -0.3413 0.4347 +vn 0.8278 -0.2930 0.4784 +vn 0.8707 -0.1907 0.4533 +vn 0.8662 0.3637 0.3427 +vn 0.8787 0.3842 0.2834 +vn 0.9008 0.4146 0.1289 +vn 0.8600 0.4176 -0.2932 +vn 0.8554 0.3602 -0.3722 +vn 0.8931 0.2723 -0.3581 +vn 0.9014 0.0961 -0.4222 +vn 0.9044 -0.3081 -0.2950 +vn 0.8859 -0.4091 0.2185 +vn 0.8640 -0.3224 0.3868 +vn 0.8600 0.0041 0.5102 +vn 0.9148 0.2584 0.3105 +vn 0.9334 0.3037 0.1913 +vn 0.9091 0.3402 -0.2403 +vn 0.8702 0.3623 -0.3338 +vn 0.9325 -0.2358 0.2737 +vn 0.9318 -0.0203 0.3624 +vn 0.9404 0.3318 -0.0740 +vn 0.9043 0.3803 -0.1939 +vn 0.9438 -0.1132 -0.3105 +vn 0.9385 0.2526 -0.2353 +vn 0.9500 -0.3079 0.0528 +vn 0.9680 0.1096 0.2258 +vn 0.9591 0.0733 -0.2733 +vn 0.9687 -0.2128 -0.1279 +vn 0.9735 -0.0596 0.2209 +vn 0.9791 0.1943 0.0603 +vn 0.9830 0.1293 -0.1302 +vn 0.9817 -0.1494 0.1182 +vn 0.9905 -0.1367 -0.0175 +vn -0.3143 -0.9459 -0.0801 +vn -0.2189 -0.9498 -0.2237 +vn 0.0788 -0.9551 0.2855 +vn -0.1990 -0.9461 0.2554 +vn -0.1012 -0.9430 0.3171 +vn 0.3029 -0.9491 -0.0865 +vn 0.3234 -0.9441 0.0643 +vn 0.1936 -0.9524 -0.2356 +vn -0.1208 -0.9386 -0.3231 +vn 0.2403 -0.9496 0.2013 +vn -0.2818 -0.9550 0.0926 +vn 0.0294 -0.9533 -0.3005 +vn -0.2831 0.9576 -0.0543 +vn -0.1395 0.9565 0.2563 +vn -0.2786 0.9511 0.1332 +vn -0.2583 0.9420 -0.2143 +vn 0.0727 0.9562 0.2835 +vn 0.2359 0.9586 0.1593 +vn -0.1200 0.9493 -0.2906 +vn 0.2249 0.9558 -0.1894 +vn 0.0645 0.9527 -0.2971 +vn 0.3169 0.9482 -0.0243 +vn -0.1131 -0.3583 0.9267 +vn 0.1306 0.4231 0.8966 +vn 0.3833 -0.3821 0.8409 +vn 0.5598 0.2478 0.7907 +vn 0.6347 -0.3802 0.6727 +vn 0.8560 0.3750 0.3559 +vn 0.8550 -0.3647 0.3688 +vn 0.9252 -0.3780 0.0321 +vn 0.9130 0.4078 -0.0081 +vn 0.8549 -0.3931 -0.3385 +vn 0.8619 0.3261 -0.3884 +vn 0.6762 -0.3964 -0.6210 +vn 0.5608 0.3371 -0.7562 +vn 0.2863 -0.3606 -0.8877 +vn 0.1443 0.4269 -0.8927 +vn -0.2629 -0.4006 -0.8777 +vn -0.2218 0.3795 -0.8982 +vn -0.6426 0.3951 -0.6565 +vn -0.6822 -0.4109 -0.6048 +vn -0.8878 -0.4043 -0.2197 +vn -0.8665 0.4041 -0.2931 +vn -0.9258 0.3292 0.1858 +vn -0.9093 -0.3911 0.1420 +vn -0.7721 -0.3319 0.5419 +vn -0.7378 0.3273 0.5904 +vn -0.5023 -0.4061 0.7634 +vn -0.4682 0.4420 0.7651 +vn -0.1698 0.2545 0.9521 +vn 0.0359 0.9989 -0.0287 +vn 0.0518 0.9057 -0.4207 +vn 0.1180 0.9662 -0.2291 +vn 0.1860 0.9533 -0.2378 +vn 0.1736 0.9843 0.0315 +vn 0.2357 0.9308 -0.2794 +vn 0.1616 -0.9705 0.1788 +vn 0.0775 -0.9598 -0.2699 +vn 0.0239 -0.9989 0.0393 +vn 0.2919 -0.2482 0.9237 +vn 0.0922 -0.3523 0.9313 +vn 0.1345 0.0012 0.9909 +vn 0.1506 0.9741 0.1687 +vn 0.0367 0.9261 0.3756 +vn 0.1530 -0.9825 -0.1066 +vn -0.0009 0.0774 0.9970 +vn 0.1344 0.2579 -0.9568 +vn 0.0557 0.5106 -0.8580 +vn 0.0074 0.0861 -0.9963 +vn 0.1556 -0.9769 0.1462 +vn 0.2296 -0.8705 0.4354 +vn 0.2867 0.0699 0.9555 +vn 0.3373 0.8461 0.4128 +vn 0.2157 -0.8423 -0.4939 +vn 0.2033 -0.9503 -0.2359 +vn 0.2245 -0.8073 0.5458 +vn 0.2273 -0.9256 0.3026 +vn 0.1991 0.9399 0.2774 +vn 0.2313 0.8025 -0.5500 +vn 0.0394 -0.7364 -0.6754 +vn 0.4516 0.0056 0.8922 +vn 0.3528 0.2544 0.9004 +vn 0.2294 0.7478 0.6231 +vn 0.2260 0.7234 0.6524 +vn 0.0682 0.7227 0.6878 +vn 0.2851 0.2322 -0.9299 +vn 0.1481 -0.0881 -0.9850 +vn 0.2630 -0.9070 -0.3289 +vn 0.3227 -0.6738 -0.6647 +vn 0.4656 0.6111 -0.6401 +vn 0.2860 0.9157 -0.2822 +vn 0.5184 0.0950 -0.8498 +vn 0.4241 0.1947 -0.8844 +vn 0.3564 -0.0848 -0.9305 +vn 0.5006 -0.2214 -0.8369 +vn 0.4085 -0.5267 -0.7455 +vn 0.1626 -0.6370 -0.7535 +vn 0.5139 0.3301 0.7918 +vn 0.2290 0.4118 0.8820 +vn 0.0658 0.4247 0.9029 +vn 0.4049 0.5372 0.7399 +vn 0.5620 -0.4316 -0.7056 +vn 0.3391 0.8628 0.3750 +vn 0.6616 -0.1797 -0.7280 +vn 0.1088 -0.3814 -0.9180 +vn 0.4070 -0.8275 -0.3867 +vn 0.3137 -0.3977 -0.8622 +vn 0.5080 -0.5347 0.6753 +vn 0.3621 -0.8538 0.3740 +vn 0.3676 0.8515 -0.3739 +vn 0.6556 -0.2652 0.7070 +vn 0.4395 -0.7855 0.4356 +vn 0.4358 0.7880 0.4350 +vn 0.6709 0.2575 0.6954 +vn 0.4110 0.7789 -0.4738 +vn 0.6832 0.3083 -0.6619 +vn 0.6679 -0.0421 -0.7430 +vn 0.6553 0.0919 -0.7498 +vn 0.4701 0.3822 -0.7956 +vn 0.3629 0.4980 -0.7876 +vn 0.2217 0.6150 -0.7567 +vn 0.4492 -0.7954 -0.4068 +vn 0.6567 -0.2386 -0.7154 +vn 0.0501 -0.9203 0.3881 +vn 0.3575 -0.5571 0.7495 +vn 0.4957 -0.3200 0.8074 +vn 0.2022 -0.5591 0.8041 +vn 0.6795 -0.0029 0.7336 +vn 0.6454 -0.1560 0.7478 +vn 0.0739 -0.6996 0.7107 +vn 0.5725 -0.1267 0.8100 +vn 0.5782 0.0978 0.8100 +vn 0.6729 0.1791 0.7177 +vn 0.5811 0.3185 -0.7489 +vn 0.6421 0.1355 -0.7546 +vn 0.6833 0.2605 -0.6821 +vn 0.0261 0.7343 -0.6784 +vn -0.9918 0.1034 0.0758 +vn -0.9927 0.1185 -0.0236 +vn -0.9974 -0.0665 -0.0286 +vn -0.9915 -0.0408 0.1235 +vn 0.6453 0.0186 0.7637 +vn -0.1967 0.2656 -0.9438 +vn -0.1430 0.8018 -0.5803 +vn -0.0047 0.7845 -0.6201 +vn -0.9348 0.2421 -0.2597 +vn -0.6007 0.7968 -0.0660 +vn -0.5788 0.7904 -0.2007 +vn -0.9572 0.2821 -0.0653 +vn -0.9564 0.2819 0.0760 +vn -0.6057 0.7906 0.0900 +vn -0.0015 -0.7852 0.6192 +vn -0.1999 -0.2576 0.9454 +vn -0.1398 -0.8017 0.5812 +vn -0.3074 -0.7726 -0.5555 +vn -0.4108 -0.7918 -0.4521 +vn -0.5969 -0.2351 -0.7671 +vn 0.3618 -0.7817 -0.5080 +vn 0.4304 -0.2363 -0.8712 +vn 0.2088 -0.7754 -0.5959 +vn 0.3816 -0.7844 0.4890 +vn 0.4515 -0.2356 0.8606 +vn 0.2876 -0.7985 0.5288 +vn 0.1879 -0.7801 0.5968 +vn 0.1564 -0.2829 0.9463 +vn 0.3673 0.7791 0.5080 +vn 0.4350 0.2422 0.8673 +vn 0.2083 0.7767 0.5945 +vn 0.4707 0.1775 -0.8642 +vn 0.2897 0.7833 -0.5500 +vn 0.1896 0.7741 -0.6041 +vn 0.1782 0.2776 -0.9440 +vn -0.0403 -0.1762 0.9835 +vn 0.4638 -0.0714 0.8830 +vn 0.2252 -0.1533 0.9622 +vn -0.1748 -0.0032 0.9846 +vn 0.2598 -0.0110 0.9656 +vn 0.0559 -0.0269 0.9981 +vn 0.5443 0.1364 0.8277 +vn 0.3416 0.1254 0.9314 +vn 0.1634 0.1673 0.9723 +vn -0.0136 0.1789 0.9838 +vn -0.2305 0.1557 0.9605 +vn 0.0593 0.7796 0.6235 +vn -0.1175 0.7809 0.6135 +vn -0.3400 0.2756 0.8992 +vn -0.3339 -0.1017 0.9371 +vn -0.2446 -0.7725 0.5860 +vn -0.2900 0.7924 0.5366 +vn -0.4338 0.1172 0.8933 +vn -0.5465 0.2397 0.8024 +vn -0.4946 -0.0648 0.8667 +vn -0.4901 -0.2223 0.8428 +vn -0.5968 0.0174 0.8022 +vn -0.3641 -0.7890 0.4949 +vn 0.2278 0.0953 -0.9690 +vn 0.2803 -0.1050 -0.9542 +vn 0.1597 -0.1640 -0.9734 +vn -0.0042 -0.0310 -0.9995 +vn -0.1449 0.0932 -0.9850 +vn -0.2260 -0.0936 -0.9696 +vn -0.3513 0.0979 -0.9311 +vn -0.4396 -0.1007 -0.8925 +vn -0.0246 -0.2064 -0.9782 +vn 0.5614 -0.1015 -0.8213 +vn 0.4269 -0.0117 -0.9042 +vn -0.2743 -0.2481 -0.9291 +vn -0.5636 -0.0573 -0.8240 +vn 0.0622 -0.7805 -0.6220 +vn -0.1164 -0.7839 -0.6099 +vn -0.4005 0.7943 0.4569 +vn -0.6401 -0.1928 0.7437 +vn -0.7134 -0.1571 -0.6829 +vn -0.5971 0.0646 -0.7996 +vn -0.7041 0.2731 0.6555 +vn -0.6863 0.1203 0.7173 +vn -0.4640 -0.7863 0.4079 +vn -0.4944 -0.7847 -0.3739 +vn -0.7804 0.0065 -0.6252 +vn -0.4989 0.7919 0.3521 +vn -0.7561 -0.0268 0.6539 +vn -0.7553 -0.1893 0.6275 +vn -0.8097 0.1714 0.5612 +vn -0.8295 -0.2116 -0.5168 +vn -0.8428 -0.2309 0.4862 +vn -0.5282 -0.7908 0.3094 +vn -0.5529 -0.7890 -0.2679 +vn -0.5562 0.7853 0.2720 +vn -0.8656 -0.0314 0.4998 +vn -0.8828 -0.0477 -0.4673 +vn -0.8973 0.1742 0.4056 +vn -0.5950 -0.7809 0.1904 +vn -0.5287 0.7935 -0.3012 +vn -0.8737 0.1819 -0.4511 +vn -0.4503 0.7922 -0.4119 +vn -0.7841 0.2241 -0.5788 +vn -0.5906 -0.7866 -0.1802 +vn -0.9089 -0.2157 -0.3570 +vn -0.5988 0.7803 0.1807 +vn -0.9141 -0.1647 0.3707 +vn -0.3637 0.7883 -0.4963 +vn -0.6674 0.2076 -0.7151 +vn -0.2434 0.7738 -0.5848 +vn -0.4918 0.2158 -0.8435 +vn 0.0198 0.1714 -0.9850 +vn -0.9404 0.0760 -0.3313 +vn -0.9483 0.0317 0.3159 +vn -0.9497 -0.0897 -0.3001 +vn -0.9646 0.1662 0.2047 +vn -0.9547 -0.1459 0.2594 +vn -0.9660 -0.2167 0.1410 +vn -0.6161 -0.7868 0.0366 +vn -0.6052 -0.7926 -0.0738 +vn -0.9622 -0.2163 -0.1653 +vn -0.9747 0.1717 -0.1429 +vn -0.9737 -0.2270 -0.0186 +vn -0.9864 0.0028 -0.1642 +vn 0.6381 0.7520 -0.1656 +vn 0.5286 0.7467 -0.4037 +vn 0.6462 0.7543 0.1157 +vn 0.0411 0.7580 0.6509 +vn -0.6596 0.7514 -0.0184 +vn -0.5898 0.7548 -0.2872 +vn 0.3327 0.7532 -0.5674 +vn 0.1013 0.7498 -0.6539 +vn 0.3154 0.7573 0.5719 +vn -0.5135 0.7546 0.4085 +vn -0.4101 0.7560 -0.5102 +vn 0.5348 0.7547 0.3800 +vn -0.2664 0.7659 0.5852 +vn -0.6393 0.7393 0.2114 +vn -0.1555 0.7538 -0.6384 +vn 0.5919 -0.7577 0.2749 +vn 0.6562 -0.7546 -0.0075 +vn 0.5848 -0.7569 -0.2919 +vn -0.3924 -0.7407 0.5454 +vn -0.5425 -0.7536 0.3713 +vn -0.6438 -0.7565 0.1154 +vn -0.1754 -0.7527 0.6346 +vn 0.3895 -0.7648 0.5132 +vn 0.1023 -0.7578 0.6444 +vn 0.3773 -0.7629 -0.5250 +vn 0.0828 -0.7606 -0.6440 +vn -0.6341 -0.7542 -0.1707 +vn -0.2321 -0.7659 -0.5996 +vn -0.4936 -0.7574 -0.4274 +vn -0.9940 -0.0874 -0.0659 +vn -0.9956 -0.0808 0.0481 +vn -0.9945 0.1041 0.0072 +vn -0.3466 0.9059 0.2432 +vn -0.4369 0.8900 0.1306 +vn -0.6997 0.5985 0.3901 +vn -0.7744 -0.6292 0.0662 +vn -0.4405 -0.8971 -0.0345 +vn -0.4176 -0.8989 0.1330 +vn -0.7374 -0.6430 -0.2069 +vn -0.3857 -0.9008 -0.1995 +vn -0.2226 -0.6116 -0.7592 +vn -0.0081 -0.8962 -0.4437 +vn -0.2230 -0.8791 -0.4213 +vn 0.9963 0.0693 0.0501 +vn 0.9950 0.0187 -0.0984 +vn 0.9878 0.1475 -0.0500 +vn 0.9657 0.2546 0.0502 +vn 0.9679 0.1875 -0.1673 +vn 0.9238 0.3650 -0.1155 +vn 0.9127 0.0354 0.4072 +vn 0.9786 0.0564 0.1977 +vn 0.9474 0.1860 0.2605 +vn 0.9697 -0.2186 -0.1091 +vn 0.9835 -0.1434 0.1101 +vn 0.9408 -0.3297 0.0791 +vn 0.9912 -0.1107 -0.0730 +vn 0.9974 -0.0529 0.0492 +vn 0.9179 -0.3929 -0.0557 +vn 0.9039 0.4270 0.0232 +vn 0.8061 -0.0675 0.5879 +vn 0.8171 0.1019 0.5675 +vn 0.9300 0.1262 -0.3451 +vn 0.9714 -0.0139 -0.2372 +vn 0.9065 -0.0631 -0.4175 +vn 0.8305 -0.5313 -0.1674 +vn 0.8326 -0.5539 0.0014 +vn 0.8401 0.1282 -0.5270 +vn 0.8415 -0.0130 -0.5401 +vn 0.7250 0.1742 -0.6664 +vn 0.7259 -0.0267 -0.6873 +vn 0.7312 -0.6178 -0.2894 +vn 0.4385 -0.8951 -0.0802 +vn 0.8331 0.5153 -0.2010 +vn 0.7744 0.6248 -0.0996 +vn 0.8306 0.5523 0.0707 +vn 0.4410 0.8965 0.0421 +vn 0.4269 0.8920 -0.1488 +vn 0.9088 -0.3481 -0.2299 +vn 0.4423 -0.8958 0.0446 +vn 0.8596 -0.4767 0.1841 +vn 0.9386 -0.2567 0.2303 +vn 0.7597 -0.6120 0.2199 +vn 0.8830 -0.3568 0.3051 +vn 0.3761 0.8977 0.2296 +vn 0.7367 0.6337 0.2359 +vn 0.8884 0.3995 0.2262 +vn 0.3718 -0.9007 -0.2246 +vn 0.7666 -0.5134 0.3857 +vn 0.3936 -0.8960 0.2057 +vn 0.9467 -0.1183 0.2998 +vn 0.7997 0.3208 -0.5075 +vn 0.8228 -0.3487 0.4488 +vn 0.6153 -0.6250 0.4804 +vn 0.7547 0.5424 0.3691 +vn 0.6889 0.6117 -0.3890 +vn 0.8193 0.4551 -0.3488 +vn 0.3376 0.9007 -0.2734 +vn 0.9151 0.3132 -0.2540 +vn 0.8816 0.2607 -0.3935 +vn 0.8234 -0.4373 -0.3617 +vn 0.8820 -0.1667 0.4408 +vn 0.6186 0.6235 0.4781 +vn 0.6832 0.3909 -0.6168 +vn 0.5987 0.2586 -0.7581 +vn 0.6606 -0.5852 -0.4703 +vn 0.2661 0.8995 0.3464 +vn 0.5422 0.5858 0.6024 +vn 0.2837 -0.8903 -0.3562 +vn 0.5136 0.4184 -0.7491 +vn 0.7334 0.4340 0.5232 +vn 0.5484 0.5866 -0.5960 +vn 0.2492 0.9017 -0.3534 +vn 0.7016 0.5039 -0.5039 +vn 0.9278 -0.2123 -0.3069 +vn 0.4459 -0.6077 0.6571 +vn 0.2804 -0.8977 0.3397 +vn 0.3889 0.6039 -0.6958 +vn 0.3292 0.4638 -0.8225 +vn 0.8663 0.3432 0.3629 +vn 0.1923 0.6101 -0.7686 +vn 0.5766 -0.5433 -0.6103 +vn 0.6700 -0.4944 0.5537 +vn 0.1445 0.9060 -0.3979 +vn 0.1388 0.8864 0.4416 +vn 0.3631 0.6184 0.6970 +vn -0.0005 0.8963 -0.4434 +vn 0.1393 -0.9021 -0.4084 +vn 0.3805 -0.5878 -0.7140 +vn 0.7369 -0.3803 -0.5589 +vn 0.1416 -0.9007 0.4108 +vn 0.6210 0.0536 -0.7820 +vn -0.1670 0.1567 0.9734 +vn -0.3115 -0.1156 0.9432 +vn -0.0722 -0.0502 0.9961 +vn 0.0819 0.1073 0.9908 +vn 0.1779 -0.0888 0.9800 +vn 0.3483 0.1096 0.9310 +vn 0.3834 -0.0791 0.9202 +vn 0.5660 0.0354 0.8237 +vn 0.6990 0.0235 0.7147 +vn 0.0445 0.3151 0.9480 +vn 0.2355 0.2617 0.9360 +vn 0.5791 0.2170 0.7859 +vn 0.7333 0.2675 0.6251 +vn -0.1499 0.4059 0.9016 +vn -0.3230 0.2567 0.9109 +vn 0.3890 0.3237 0.8625 +vn 0.5713 0.4018 0.7157 +vn 0.8629 0.2217 0.4541 +vn 0.1748 0.5111 0.8416 +vn 0.3706 0.4910 0.7884 +vn -0.0130 0.5622 0.8269 +vn -0.2197 0.5925 0.7751 +vn 0.0060 0.8918 0.4524 +vn -0.1369 0.9001 0.4137 +vn -0.1971 0.5962 -0.7782 +vn -0.1365 0.9020 -0.4095 +vn -0.0026 0.5564 -0.8309 +vn -0.1912 0.3913 -0.9002 +vn 0.1299 0.3878 -0.9125 +vn -0.0493 0.2894 -0.9559 +vn 0.3058 0.2990 -0.9039 +vn 0.4371 0.2175 -0.8727 +vn -0.2419 0.1354 -0.9608 +vn 0.1222 0.1577 -0.9799 +vn 0.2835 0.1046 -0.9532 +vn -0.0048 0.0009 -1.0000 +vn 0.4843 0.0644 -0.8725 +vn -0.1447 -0.0197 -0.9893 +vn 0.1915 -0.0705 -0.9790 +vn 0.3739 -0.0815 -0.9239 +vn 0.5696 -0.1086 -0.8147 +vn -0.1727 -0.2349 -0.9566 +vn -0.3146 -0.0930 -0.9447 +vn 0.0456 -0.2420 -0.9692 +vn 0.7674 -0.1792 -0.6156 +vn 0.2801 -0.2772 -0.9191 +vn 0.4632 -0.2519 -0.8497 +vn 0.6267 -0.2502 -0.7380 +vn 0.1530 -0.4102 -0.8991 +vn -0.0663 -0.4395 -0.8958 +vn 0.8433 -0.2548 -0.4731 +vn -0.2583 -0.4373 -0.8614 +vn 0.3675 -0.4390 -0.8199 +vn 0.5578 -0.4191 -0.7164 +vn 0.0116 -0.5769 -0.8168 +vn 0.2010 -0.5954 -0.7779 +vn -0.3737 0.4303 0.8217 +vn -0.3711 0.4408 -0.8173 +vn -0.4141 0.0393 0.9094 +vn -0.3898 -0.2967 -0.8718 +vn -0.3902 0.2540 -0.8850 +vn -0.3764 0.5902 -0.7141 +vn -0.2456 0.8999 0.3604 +vn -0.4101 0.5817 0.7024 +vn -0.2798 0.8908 -0.3582 +vn -0.4313 -0.4973 -0.7528 +vn -0.4590 -0.0067 -0.8884 +vn -0.5332 0.2163 0.8179 +vn -0.5572 0.6294 0.5416 +vn -0.2633 -0.9118 -0.3152 +vn -0.5659 -0.5770 -0.5889 +vn -0.5336 -0.1966 -0.8226 +vn -0.5765 0.1913 -0.7944 +vn -0.5416 0.5071 -0.6704 +vn -0.5675 0.4556 0.6858 +vn -0.3240 -0.9016 -0.2865 +vn -0.5797 -0.3828 -0.7193 +vn -0.5927 0.0309 -0.8049 +vn -0.5704 0.3441 -0.7458 +vn -0.5379 -0.0961 0.8375 +vn -0.6070 0.5974 -0.5241 +vn -0.3829 0.8979 -0.2170 +vn -0.3406 -0.9016 0.2668 +vn -0.2510 -0.9001 0.3560 +vn -0.5801 -0.5842 0.5676 +vn -0.1398 -0.8892 0.4356 +vn -0.4213 -0.5767 0.6999 +vn 0.2127 -0.5926 0.7769 +vn 0.0009 -0.8929 0.4503 +vn -0.6189 -0.4113 0.6692 +vn -0.2604 -0.5351 0.8037 +vn -0.0544 -0.5514 0.8325 +vn 0.5830 -0.4397 0.6832 +vn 0.3588 -0.4629 0.8106 +vn 0.7549 -0.3012 0.5826 +vn 0.0630 -0.4252 0.9029 +vn -0.4815 -0.3437 0.8062 +vn -0.2759 -0.3678 0.8880 +vn 0.5324 -0.3296 0.7797 +vn -0.1722 -0.2746 0.9460 +vn 0.3019 -0.2928 0.9073 +vn 0.6859 -0.1974 0.7005 +vn 0.0664 -0.2563 0.9643 +vn 0.5196 -0.1727 0.8368 +vn -0.6669 -0.1919 0.7200 +vn -0.6996 -0.5803 -0.4169 +vn -0.6668 -0.1525 -0.7295 +vn -0.7339 0.4056 -0.5449 +vn -0.6990 0.4227 0.5769 +vn -0.6801 0.2321 0.6954 +vn -0.6944 0.0330 0.7188 +vn -0.6792 -0.6321 0.3729 +vn -0.7203 -0.3824 -0.5787 +vn -0.7376 0.0812 -0.6703 +vn -0.7070 0.2759 -0.6511 +vn -0.7133 0.5774 -0.3973 +vn -0.7421 -0.3891 0.5457 +vn -0.4571 0.8823 -0.1120 +vn -0.7584 -0.4974 0.4212 +vn -0.7941 -0.1907 0.5771 +vn -0.8201 -0.5175 0.2443 +vn -0.7686 -0.1713 -0.6163 +vn -0.7959 0.5226 -0.3057 +vn -0.8353 -0.0173 0.5496 +vn -0.8088 -0.4490 -0.3797 +vn -0.8362 0.2065 -0.5080 +vn -0.8250 0.5614 -0.0643 +vn -0.4489 0.8933 0.0239 +vn -0.8487 0.5175 0.1095 +vn -0.8224 0.5112 0.2497 +vn -0.8119 0.4007 0.4246 +vn -0.7962 0.2155 0.5654 +vn -0.8426 -0.5225 -0.1306 +vn -0.8574 -0.2716 -0.4372 +vn -0.8403 -0.0487 -0.5399 +vn -0.8691 -0.3073 0.3876 +vn -0.8842 0.3274 -0.3333 +vn -0.8873 -0.4484 0.1080 +vn -0.8963 -0.3705 -0.2437 +vn -0.8908 0.4231 -0.1659 +vn -0.8958 0.3245 0.3036 +vn -0.8834 0.1508 0.4437 +vn -0.9250 -0.1065 0.3648 +vn -0.9101 -0.0359 -0.4129 +vn -0.9149 0.1307 -0.3820 +vn -0.9325 -0.2851 0.2216 +vn -0.9148 -0.3997 -0.0587 +vn -0.9290 -0.2020 -0.3100 +vn -0.9430 0.3324 -0.0153 +vn -0.9463 0.2881 0.1464 +vn -0.9343 0.1760 0.3099 +vn -0.9603 -0.2724 0.0596 +vn -0.9550 0.0415 0.2937 +vn -0.9618 -0.2515 -0.1085 +vn -0.9640 0.0799 -0.2535 +vn -0.9624 0.2214 -0.1571 +vn -0.9712 -0.1113 -0.2108 +vn -0.9790 -0.1062 0.1740 +vn -0.9848 0.0988 0.1426 +vn -0.9923 0.0519 -0.1124 +vn -0.3174 0.9480 0.0246 +vn 0.1003 0.9503 -0.2947 +vn 0.2445 0.9415 -0.2319 +vn 0.2986 0.9504 -0.0871 +vn 0.2477 0.9641 0.0961 +vn 0.1746 0.9495 0.2606 +vn -0.3109 0.9417 -0.1290 +vn -0.1903 0.9526 -0.2375 +vn -0.0580 0.9445 -0.3234 +vn -0.0014 0.9532 0.3023 +vn -0.1727 0.9452 0.2772 +vn -0.2841 0.9416 0.1806 +vn 0.2420 -0.9417 0.2337 +vn 0.1010 -0.9497 0.2963 +vn 0.3007 -0.9510 0.0716 +vn 0.2986 -0.9478 -0.1115 +vn 0.1776 -0.9543 -0.2402 +vn -0.1095 -0.9580 0.2649 +vn -0.2684 -0.9583 0.0983 +vn -0.2460 -0.9636 -0.1047 +vn 0.0175 -0.9505 -0.3102 +vn -0.1372 -0.9588 -0.2488 +vn -0.2628 0.3412 0.9025 +vn -0.3037 -0.4384 0.8459 +vn -0.5768 0.3921 0.7167 +vn -0.7412 -0.2445 0.6252 +vn -0.7715 0.4058 0.4900 +vn -0.8988 0.4005 0.1780 +vn -0.8699 -0.4396 0.2236 +vn -0.9572 -0.2689 -0.1068 +vn -0.8953 0.3847 -0.2245 +vn -0.7113 -0.2851 -0.6424 +vn -0.7506 0.3551 -0.5573 +vn -0.4279 0.3839 -0.8182 +vn -0.2230 -0.3474 -0.9108 +vn -0.0173 0.3733 -0.9275 +vn 0.2674 -0.3576 -0.8948 +vn 0.3933 0.3996 -0.8280 +vn 0.6826 -0.3842 -0.6217 +vn 0.6559 0.3931 -0.6444 +vn 0.8468 0.4036 -0.3465 +vn 0.8984 -0.3894 -0.2031 +vn 0.9429 0.3231 0.0813 +vn 0.8782 -0.4229 0.2233 +vn 0.7437 0.3163 0.5889 +vn 0.6764 -0.4004 0.6182 +vn 0.3806 0.3610 0.8514 +vn 0.2076 -0.3954 0.8948 +vn 0.1009 0.4157 0.9039 +vn -0.7139 0.6783 0.1739 +vn -0.7292 0.4671 -0.5000 +vn -0.7136 0.4228 0.5585 +vn -0.7161 0.1573 -0.6800 +vn -0.7199 0.0169 0.6939 +vn -0.7199 -0.2532 -0.6463 +vn -0.7149 -0.3877 0.5819 +vn -0.7163 -0.5755 -0.3946 +vn -0.7221 -0.6382 0.2669 +vn -0.7234 0.6499 -0.2331 +vn -0.7286 -0.6827 -0.0546 +vn 0.6547 -0.4322 -0.6201 +vn 0.6368 -0.4576 0.6205 +vn 0.6355 -0.7466 0.1966 +vn 0.6571 0.7307 -0.1853 +vn 0.6402 0.7375 0.2150 +vn 0.6546 0.5816 -0.4830 +vn 0.6360 0.4560 0.6225 +vn 0.6558 0.3112 -0.6878 +vn 0.6425 0.0020 0.7663 +vn 0.6452 -0.0628 -0.7615 +vn 0.6398 -0.7063 -0.3031 +vn 0.7126 0.6965 0.0843 +vn 0.7118 0.4822 0.5108 +vn 0.7193 0.6176 -0.3181 +vn 0.7151 -0.6403 0.2805 +vn 0.7159 0.0787 -0.6937 +vn 0.7255 0.3971 -0.5621 +vn 0.7123 0.0501 0.7001 +vn 0.7180 -0.3598 0.5959 +vn 0.7215 -0.6808 -0.1265 +vn 0.7237 -0.5222 -0.4512 +vn 0.7271 -0.2711 -0.6307 +vn -0.6622 -0.6168 -0.4255 +vn -0.6557 -0.7436 -0.1312 +vn -0.6619 -0.7243 0.1931 +vn -0.6513 -0.3773 -0.6584 +vn -0.6501 -0.5668 0.5061 +vn -0.6457 0.6247 -0.4390 +vn -0.6386 0.3254 0.6974 +vn -0.6410 0.6844 0.3474 +vn -0.6583 0.3286 -0.6773 +vn -0.6381 -0.1842 0.7476 +vn -0.6535 -0.0128 -0.7568 +vn -0.6546 0.7529 -0.0680 +vn -0.0828 0.9815 -0.1728 +vn 0.0830 0.9966 -0.0017 +vn 0.0861 0.8701 -0.4853 +vn -0.0819 0.8240 -0.5606 +vn 0.0888 0.5819 -0.8084 +vn -0.0843 0.5710 -0.8166 +vn 0.0857 0.2626 -0.9611 +vn -0.0826 0.2441 -0.9662 +vn 0.0833 -0.0889 -0.9925 +vn -0.0829 -0.1728 -0.9815 +vn 0.0849 -0.4213 -0.9029 +vn -0.0833 -0.5610 -0.8236 +vn 0.0854 -0.7129 -0.6961 +vn -0.0827 -0.8245 -0.5598 +vn 0.0830 -0.9361 -0.3418 +vn -0.0841 -0.9815 -0.1722 +vn 0.0825 -0.9940 0.0723 +vn -0.0830 -0.9664 0.2434 +vn 0.0829 -0.9030 0.4215 +vn -0.0843 -0.8156 0.5725 +vn 0.0843 -0.7054 0.7038 +vn -0.0827 -0.5599 0.8244 +vn 0.0860 -0.4182 0.9043 +vn -0.0828 -0.1733 0.9814 +vn 0.0862 -0.0917 0.9920 +vn 0.0867 0.2618 0.9612 +vn -0.0832 0.2452 0.9659 +vn 0.0854 0.5792 0.8107 +vn -0.0828 0.5714 0.8165 +vn 0.0810 0.8702 0.4859 +vn -0.0849 0.8169 0.5705 +vn -0.0827 0.9662 0.2441 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/5 6/6/6 +f 7/7/7 8/8/8 9/9/9 +f 10/10/10 11/11/11 1/1/1 +f 12/12/12 13/13/13 14/14/14 +f 15/15/15 16/16/16 17/17/17 +f 18/18/18 19/19/19 20/20/20 +f 21/21/21 22/22/22 23/23/23 +f 24/24/24 21/21/21 23/23/23 +f 25/25/25 21/21/21 24/24/24 +f 26/26/26 27/27/27 28/28/28 +f 29/29/29 30/30/30 31/31/31 +f 31/31/31 30/30/30 32/32/32 +f 33/33/33 25/25/25 24/24/24 +f 33/33/33 24/24/24 34/34/34 +f 34/34/34 24/24/24 35/35/35 +f 16/16/16 36/36/36 37/37/37 +f 37/37/37 36/36/36 38/38/38 +f 39/39/39 25/25/25 33/33/33 +f 24/24/24 23/23/23 35/35/35 +f 34/34/34 40/40/40 41/41/41 +f 42/42/42 43/43/43 26/26/26 +f 16/16/16 15/15/15 44/44/44 +f 16/16/16 44/44/44 36/36/36 +f 38/38/38 45/45/45 37/37/37 +f 37/37/37 46/46/46 18/18/18 +f 39/39/39 47/47/47 25/25/25 +f 34/34/34 35/35/35 40/40/40 +f 48/48/48 26/26/26 28/28/28 +f 48/48/48 28/28/28 49/49/49 +f 50/50/50 47/47/47 39/39/39 +f 25/25/25 51/51/51 21/21/21 +f 21/21/21 51/51/51 22/22/22 +f 15/15/15 52/52/52 44/44/44 +f 37/37/37 45/45/45 46/46/46 +f 18/18/18 46/46/46 19/19/19 +f 53/53/53 31/31/31 54/54/54 +f 54/54/54 31/31/31 32/32/32 +f 51/51/51 55/55/55 22/22/22 +f 56/56/56 42/42/42 57/57/57 +f 57/57/57 42/42/42 26/26/26 +f 12/12/12 58/58/58 17/17/17 +f 50/50/50 59/59/59 60/60/60 +f 47/47/47 61/61/61 25/25/25 +f 25/25/25 61/61/61 51/51/51 +f 14/14/14 56/56/56 57/57/57 +f 57/57/57 26/26/26 62/62/62 +f 62/62/62 26/26/26 48/48/48 +f 17/17/17 62/62/62 15/15/15 +f 15/15/15 62/62/62 52/52/52 +f 1/1/1 63/63/63 64/64/64 +f 64/64/64 63/63/63 65/65/65 +f 50/50/50 60/60/60 47/47/47 +f 47/47/47 60/60/60 61/61/61 +f 58/58/58 62/62/62 17/17/17 +f 66/66/66 1/1/1 64/64/64 +f 60/60/60 65/65/65 53/53/53 +f 60/60/60 53/53/53 61/61/61 +f 61/61/61 53/53/53 67/67/67 +f 67/67/67 53/53/53 54/54/54 +f 12/12/12 14/14/14 57/57/57 +f 12/12/12 57/57/57 58/58/58 +f 58/58/58 57/57/57 62/62/62 +f 62/62/62 48/48/48 52/52/52 +f 52/52/52 48/48/48 49/49/49 +f 59/59/59 68/68/68 64/64/64 +f 59/59/59 64/64/64 60/60/60 +f 61/61/61 67/67/67 51/51/51 +f 51/51/51 67/67/67 55/55/55 +f 63/63/63 69/69/69 65/65/65 +f 65/65/65 69/69/69 70/70/70 +f 65/65/65 70/70/70 71/71/71 +f 29/29/29 72/72/72 73/73/73 +f 31/31/31 71/71/71 72/72/72 +f 31/31/31 72/72/72 29/29/29 +f 29/29/29 73/73/73 30/30/30 +f 53/53/53 65/65/65 71/71/71 +f 53/53/53 71/71/71 31/31/31 +f 60/60/60 64/64/64 65/65/65 +f 1/1/1 66/66/66 10/10/10 +f 54/54/54 55/55/55 67/67/67 +f 64/64/64 68/68/68 66/66/66 +f 66/66/66 74/74/74 10/10/10 +f 66/66/66 68/68/68 74/74/74 +f 7/7/7 9/9/9 75/75/75 +f 75/75/75 9/9/9 76/76/76 +f 77/77/77 76/76/76 41/41/41 +f 77/77/77 41/41/41 40/40/40 +f 78/78/78 40/40/40 35/35/35 +f 78/78/78 35/35/35 23/23/23 +f 79/79/79 75/75/75 76/76/76 +f 79/79/79 76/76/76 77/77/77 +f 80/80/80 81/81/81 7/7/7 +f 80/80/80 7/7/7 75/75/75 +f 77/77/77 40/40/40 82/82/82 +f 82/82/82 40/40/40 78/78/78 +f 80/80/80 75/75/75 79/79/79 +f 81/81/81 80/80/80 6/6/6 +f 42/42/42 80/80/80 79/79/79 +f 43/43/43 79/79/79 77/77/77 +f 56/56/56 6/6/6 80/80/80 +f 43/43/43 42/42/42 79/79/79 +f 43/43/43 77/77/77 27/27/27 +f 27/27/27 77/77/77 82/82/82 +f 56/56/56 80/80/80 42/42/42 +f 14/14/14 6/6/6 56/56/56 +f 13/13/13 4/4/4 6/6/6 +f 13/13/13 6/6/6 14/14/14 +f 26/26/26 43/43/43 27/27/27 +f 3/3/3 83/83/83 20/20/20 +f 70/70/70 20/20/20 19/19/19 +f 69/69/69 3/3/3 20/20/20 +f 69/69/69 20/20/20 70/70/70 +f 70/70/70 19/19/19 72/72/72 +f 72/72/72 19/19/19 46/46/46 +f 73/73/73 46/46/46 45/45/45 +f 72/72/72 46/46/46 73/73/73 +f 63/63/63 1/1/1 3/3/3 +f 63/63/63 3/3/3 69/69/69 +f 71/71/71 70/70/70 72/72/72 +f 30/30/30 73/73/73 45/45/45 +f 30/30/30 45/45/45 84/84/84 +f 85/85/85 86/86/86 87/87/87 +f 6/6/6 5/5/5 88/88/88 +f 89/89/89 90/90/90 91/91/91 +f 92/92/92 93/93/93 94/94/94 +f 95/95/95 93/93/93 96/96/96 +f 95/95/95 96/96/96 97/97/97 +f 98/98/98 99/99/99 100/100/100 +f 101/101/101 102/102/102 103/103/103 +f 81/81/81 104/104/104 7/7/7 +f 10/10/10 74/74/74 105/105/105 +f 8/8/8 7/7/7 106/106/106 +f 107/107/107 8/8/8 106/106/106 +f 108/108/108 4/4/4 109/109/109 +f 83/83/83 3/3/3 2/2/2 +f 83/83/83 2/2/2 110/110/110 +f 10/10/10 105/105/105 111/111/111 +f 112/112/112 111/111/111 103/103/103 +f 107/107/107 106/106/106 113/113/113 +f 107/107/107 113/113/113 114/114/114 +f 114/114/114 113/113/113 115/115/115 +f 108/108/108 5/5/5 4/4/4 +f 116/116/116 108/108/108 109/109/109 +f 116/116/116 109/109/109 117/117/117 +f 116/116/116 117/117/117 118/118/118 +f 118/118/118 117/117/117 119/119/119 +f 110/110/110 2/2/2 120/120/120 +f 120/120/120 2/2/2 121/121/121 +f 120/120/120 121/121/121 122/122/122 +f 122/122/122 121/121/121 123/123/123 +f 113/113/113 106/106/106 124/124/124 +f 115/115/115 113/113/113 125/125/125 +f 115/115/115 125/125/125 126/126/126 +f 106/106/106 7/7/7 104/104/104 +f 126/126/126 125/125/125 127/127/127 +f 126/126/126 127/127/127 128/128/128 +f 128/128/128 127/127/127 129/129/129 +f 124/124/124 130/130/130 113/113/113 +f 113/113/113 130/130/130 125/125/125 +f 125/125/125 130/130/130 131/131/131 +f 125/125/125 131/131/131 127/127/127 +f 106/106/106 104/104/104 124/124/124 +f 131/131/131 132/132/132 127/127/127 +f 104/104/104 81/81/81 88/88/88 +f 124/124/124 104/104/104 133/133/133 +f 124/124/124 133/133/133 130/130/130 +f 131/131/131 130/130/130 134/134/134 +f 131/131/131 134/134/134 132/132/132 +f 127/127/127 132/132/132 135/135/135 +f 127/127/127 135/135/135 129/129/129 +f 129/129/129 135/135/135 136/136/136 +f 81/81/81 6/6/6 88/88/88 +f 104/104/104 88/88/88 108/108/108 +f 104/104/104 108/108/108 133/133/133 +f 130/130/130 133/133/133 118/118/118 +f 130/130/130 118/118/118 134/134/134 +f 132/132/132 134/134/134 135/135/135 +f 133/133/133 108/108/108 116/116/116 +f 133/133/133 116/116/116 118/118/118 +f 134/134/134 119/119/119 135/135/135 +f 88/88/88 5/5/5 108/108/108 +f 134/134/134 118/118/118 119/119/119 +f 135/135/135 119/119/119 137/137/137 +f 135/135/135 137/137/137 136/136/136 +f 137/137/137 138/138/138 136/136/136 +f 136/136/136 139/139/139 129/129/129 +f 129/129/129 139/139/139 140/140/140 +f 129/129/129 140/140/140 128/128/128 +f 138/138/138 141/141/141 142/142/142 +f 138/138/138 142/142/142 136/136/136 +f 136/136/136 142/142/142 139/139/139 +f 142/142/142 143/143/143 139/139/139 +f 139/139/139 143/143/143 144/144/144 +f 139/139/139 144/144/144 140/140/140 +f 140/140/140 144/144/144 145/145/145 +f 141/141/141 146/146/146 142/142/142 +f 142/142/142 146/146/146 143/143/143 +f 147/147/147 148/148/148 112/112/112 +f 147/147/147 112/112/112 149/149/149 +f 149/149/149 150/150/150 151/151/151 +f 152/152/152 153/153/153 154/154/154 +f 155/155/155 152/152/152 156/156/156 +f 153/153/153 151/151/151 154/154/154 +f 152/152/152 154/154/154 157/157/157 +f 152/152/152 157/157/157 156/156/156 +f 149/149/149 112/112/112 150/150/150 +f 151/151/151 150/150/150 102/102/102 +f 151/151/151 102/102/102 154/154/154 +f 11/11/11 10/10/10 148/148/148 +f 148/148/148 10/10/10 112/112/112 +f 154/154/154 102/102/102 158/158/158 +f 156/156/156 157/157/157 159/159/159 +f 112/112/112 10/10/10 111/111/111 +f 150/150/150 112/112/112 103/103/103 +f 150/150/150 103/103/103 102/102/102 +f 102/102/102 101/101/101 158/158/158 +f 154/154/154 158/158/158 157/157/157 +f 157/157/157 158/158/158 160/160/160 +f 157/157/157 160/160/160 159/159/159 +f 141/141/141 161/161/161 146/146/146 +f 159/159/159 162/162/162 156/156/156 +f 156/156/156 162/162/162 163/163/163 +f 156/156/156 163/163/163 155/155/155 +f 146/146/146 164/164/164 143/143/143 +f 143/143/143 164/164/164 144/144/144 +f 144/144/144 165/165/165 145/145/145 +f 166/166/166 162/162/162 159/159/159 +f 161/161/161 167/167/167 146/146/146 +f 146/146/146 167/167/167 164/164/164 +f 164/164/164 168/168/168 144/144/144 +f 144/144/144 168/168/168 165/165/165 +f 161/161/161 169/169/169 167/167/167 +f 164/164/164 167/167/167 170/170/170 +f 164/164/164 170/170/170 168/168/168 +f 165/165/165 168/168/168 171/171/171 +f 172/172/172 173/173/173 166/166/166 +f 166/166/166 173/173/173 162/162/162 +f 162/162/162 174/174/174 163/163/163 +f 162/162/162 173/173/173 174/174/174 +f 169/169/169 175/175/175 167/167/167 +f 167/167/167 175/175/175 170/170/170 +f 170/170/170 176/176/176 168/168/168 +f 168/168/168 176/176/176 171/171/171 +f 173/173/173 177/177/177 174/174/174 +f 178/178/178 175/175/175 169/169/169 +f 170/170/170 175/175/175 179/179/179 +f 170/170/170 179/179/179 176/176/176 +f 172/172/172 98/98/98 180/180/180 +f 172/172/172 180/180/180 173/173/173 +f 173/173/173 180/180/180 177/177/177 +f 178/178/178 181/181/181 175/175/175 +f 179/179/179 182/182/182 176/176/176 +f 176/176/176 182/182/182 183/183/183 +f 176/176/176 183/183/183 171/171/171 +f 171/171/171 183/183/183 184/184/184 +f 94/94/94 185/185/185 186/186/186 +f 185/185/185 187/187/187 186/186/186 +f 178/178/178 188/188/188 181/181/181 +f 175/175/175 181/181/181 179/179/179 +f 179/179/179 181/181/181 182/182/182 +f 92/92/92 94/94/94 186/186/186 +f 90/90/90 89/89/89 189/189/189 +f 90/90/90 189/189/189 190/190/190 +f 90/90/90 190/190/190 191/191/191 +f 187/187/187 191/191/191 192/192/192 +f 187/187/187 192/192/192 193/193/193 +f 187/187/187 193/193/193 186/186/186 +f 122/122/122 194/194/194 91/91/91 +f 91/91/91 194/194/194 89/89/89 +f 191/191/191 190/190/190 192/192/192 +f 186/186/186 193/193/193 174/174/174 +f 121/121/121 147/147/147 123/123/123 +f 122/122/122 123/123/123 194/194/194 +f 189/189/189 89/89/89 152/152/152 +f 186/186/186 174/174/174 195/195/195 +f 194/194/194 153/153/153 89/89/89 +f 89/89/89 153/153/153 152/152/152 +f 189/189/189 152/152/152 190/190/190 +f 190/190/190 155/155/155 192/192/192 +f 193/193/193 192/192/192 163/163/163 +f 193/193/193 163/163/163 174/174/174 +f 2/2/2 1/1/1 11/11/11 +f 2/2/2 11/11/11 148/148/148 +f 2/2/2 148/148/148 121/121/121 +f 121/121/121 148/148/148 147/147/147 +f 123/123/123 147/147/147 149/149/149 +f 123/123/123 149/149/149 151/151/151 +f 123/123/123 151/151/151 194/194/194 +f 190/190/190 152/152/152 155/155/155 +f 192/192/192 155/155/155 163/163/163 +f 195/195/195 174/174/174 177/177/177 +f 194/194/194 151/151/151 153/153/153 +f 188/188/188 196/196/196 181/181/181 +f 181/181/181 197/197/197 182/182/182 +f 98/98/98 100/100/100 180/180/180 +f 195/195/195 92/92/92 186/186/186 +f 95/95/95 97/97/97 188/188/188 +f 188/188/188 97/97/97 196/196/196 +f 181/181/181 196/196/196 197/197/197 +f 184/184/184 183/183/183 198/198/198 +f 184/184/184 198/198/198 199/199/199 +f 199/199/199 100/100/100 99/99/99 +f 180/180/180 100/100/100 200/200/200 +f 180/180/180 200/200/200 177/177/177 +f 177/177/177 200/200/200 195/195/195 +f 92/92/92 201/201/201 93/93/93 +f 93/93/93 201/201/201 96/96/96 +f 195/195/195 200/200/200 202/202/202 +f 195/195/195 202/202/202 92/92/92 +f 92/92/92 202/202/202 201/201/201 +f 197/197/197 203/203/203 182/182/182 +f 182/182/182 203/203/203 183/183/183 +f 183/183/183 203/203/203 198/198/198 +f 199/199/199 198/198/198 204/204/204 +f 199/199/199 204/204/204 100/100/100 +f 201/201/201 205/205/205 96/96/96 +f 96/96/96 205/205/205 97/97/97 +f 97/97/97 205/205/205 196/196/196 +f 196/196/196 85/85/85 197/197/197 +f 197/197/197 85/85/85 203/203/203 +f 100/100/100 204/204/204 206/206/206 +f 100/100/100 206/206/206 200/200/200 +f 200/200/200 86/86/86 202/202/202 +f 202/202/202 86/86/86 201/201/201 +f 201/201/201 86/86/86 205/205/205 +f 196/196/196 205/205/205 85/85/85 +f 198/198/198 203/203/203 204/204/204 +f 200/200/200 206/206/206 86/86/86 +f 205/205/205 86/86/86 85/85/85 +f 85/85/85 87/87/87 203/203/203 +f 203/203/203 87/87/87 204/204/204 +f 204/204/204 87/87/87 206/206/206 +f 206/206/206 87/87/87 86/86/86 +f 207/207/207 188/188/188 178/178/178 +f 207/207/207 178/178/178 169/169/169 +f 208/208/208 93/93/93 95/95/95 +f 209/209/209 91/91/91 90/90/90 +f 18/18/18 210/210/210 211/211/211 +f 37/37/37 18/18/18 211/211/211 +f 17/17/17 16/16/16 211/211/211 +f 12/12/12 17/17/17 211/211/211 +f 13/13/13 12/12/12 212/212/212 +f 207/207/207 169/169/169 213/213/213 +f 213/213/213 169/169/169 161/161/161 +f 95/95/95 188/188/188 208/208/208 +f 208/208/208 188/188/188 207/207/207 +f 208/208/208 94/94/94 93/93/93 +f 90/90/90 214/214/214 209/209/209 +f 215/215/215 122/122/122 209/209/209 +f 210/210/210 18/18/18 20/20/20 +f 211/211/211 16/16/16 37/37/37 +f 212/212/212 12/12/12 211/211/211 +f 117/117/117 109/109/109 216/216/216 +f 217/217/217 94/94/94 208/208/208 +f 185/185/185 94/94/94 217/217/217 +f 214/214/214 187/187/187 217/217/217 +f 217/217/217 187/187/187 185/185/185 +f 187/187/187 214/214/214 191/191/191 +f 214/214/214 90/90/90 191/191/191 +f 122/122/122 91/91/91 209/209/209 +f 20/20/20 83/83/83 210/210/210 +f 210/210/210 83/83/83 218/218/218 +f 212/212/212 4/4/4 13/13/13 +f 216/216/216 109/109/109 212/212/212 +f 212/212/212 109/109/109 4/4/4 +f 219/219/219 141/141/141 138/138/138 +f 141/141/141 213/213/213 161/161/161 +f 220/220/220 119/119/119 216/216/216 +f 216/216/216 119/119/119 117/117/117 +f 220/220/220 137/137/137 119/119/119 +f 219/219/219 138/138/138 137/137/137 +f 219/219/219 137/137/137 220/220/220 +f 213/213/213 141/141/141 219/219/219 +f 221/221/221 120/120/120 122/122/122 +f 221/221/221 122/122/122 215/215/215 +f 110/110/110 221/221/221 218/218/218 +f 110/110/110 218/218/218 83/83/83 +f 110/110/110 120/120/120 221/221/221 +f 98/98/98 222/222/222 99/99/99 +f 223/223/223 199/199/199 224/224/224 +f 223/223/223 184/184/184 199/199/199 +f 68/68/68 59/59/59 225/225/225 +f 74/74/74 225/225/225 226/226/226 +f 226/226/226 105/105/105 74/74/74 +f 224/224/224 99/99/99 222/222/222 +f 224/224/224 199/199/199 99/99/99 +f 227/227/227 171/171/171 223/223/223 +f 223/223/223 171/171/171 184/184/184 +f 228/228/228 59/59/59 50/50/50 +f 111/111/111 105/105/105 226/226/226 +f 229/229/229 103/103/103 226/226/226 +f 230/230/230 160/160/160 158/158/158 +f 225/225/225 59/59/59 228/228/228 +f 225/225/225 74/74/74 68/68/68 +f 226/226/226 103/103/103 111/111/111 +f 103/103/103 229/229/229 101/101/101 +f 158/158/158 101/101/101 229/229/229 +f 159/159/159 160/160/160 231/231/231 +f 231/231/231 160/160/160 230/230/230 +f 222/222/222 98/98/98 172/172/172 +f 165/165/165 171/171/171 227/227/227 +f 128/128/128 232/232/232 233/233/233 +f 228/228/228 50/50/50 39/39/39 +f 230/230/230 158/158/158 229/229/229 +f 159/159/159 231/231/231 166/166/166 +f 234/234/234 9/9/9 8/8/8 +f 222/222/222 172/172/172 231/231/231 +f 128/128/128 140/140/140 232/232/232 +f 233/233/233 126/126/126 128/128/128 +f 235/235/235 107/107/107 114/114/114 +f 234/234/234 107/107/107 235/235/235 +f 234/234/234 8/8/8 107/107/107 +f 236/236/236 76/76/76 234/234/234 +f 234/234/234 76/76/76 9/9/9 +f 236/236/236 33/33/33 34/34/34 +f 228/228/228 39/39/39 236/236/236 +f 172/172/172 166/166/166 231/231/231 +f 232/232/232 145/145/145 165/165/165 +f 232/232/232 165/165/165 227/227/227 +f 236/236/236 39/39/39 33/33/33 +f 140/140/140 145/145/145 232/232/232 +f 233/233/233 115/115/115 126/126/126 +f 236/236/236 41/41/41 76/76/76 +f 236/236/236 34/34/34 41/41/41 +f 114/114/114 115/115/115 235/235/235 +f 235/235/235 115/115/115 233/233/233 +f 229/229/229 209/209/209 230/230/230 +f 230/230/230 209/209/209 231/231/231 +f 231/231/231 209/209/209 214/214/214 +f 231/231/231 214/214/214 222/222/222 +f 222/222/222 214/214/214 217/217/217 +f 222/222/222 217/217/217 208/208/208 +f 222/222/222 208/208/208 224/224/224 +f 224/224/224 208/208/208 223/223/223 +f 223/223/223 208/208/208 207/207/207 +f 223/223/223 207/207/207 227/227/227 +f 227/227/227 207/207/207 213/213/213 +f 227/227/227 213/213/213 232/232/232 +f 232/232/232 213/213/213 219/219/219 +f 232/232/232 219/219/219 233/233/233 +f 233/233/233 219/219/219 220/220/220 +f 233/233/233 220/220/220 235/235/235 +f 235/235/235 220/220/220 216/216/216 +f 235/235/235 216/216/216 234/234/234 +f 234/234/234 216/216/216 212/212/212 +f 234/234/234 212/212/212 236/236/236 +f 236/236/236 212/212/212 211/211/211 +f 236/236/236 211/211/211 228/228/228 +f 228/228/228 211/211/211 210/210/210 +f 228/228/228 210/210/210 225/225/225 +f 225/225/225 210/210/210 218/218/218 +f 225/225/225 218/218/218 226/226/226 +f 226/226/226 218/218/218 221/221/221 +f 226/226/226 221/221/221 229/229/229 +f 229/229/229 221/221/221 215/215/215 +f 229/229/229 215/215/215 209/209/209 +f 237/237/237 238/238/238 239/239/239 +f 240/240/240 241/241/241 242/242/242 +f 243/243/243 244/244/244 245/245/245 +f 246/246/246 247/247/247 248/248/248 +f 249/249/249 250/250/250 251/251/251 +f 252/252/252 253/253/253 254/254/254 +f 255/255/255 256/256/256 257/257/257 +f 249/249/249 251/251/251 258/258/258 +f 250/250/250 259/259/259 252/252/252 +f 260/260/260 257/257/257 261/261/261 +f 260/260/260 261/261/261 262/262/262 +f 249/249/249 258/258/258 263/263/263 +f 263/263/263 258/258/258 264/264/264 +f 263/263/263 264/264/264 265/265/265 +f 260/260/260 262/262/262 266/266/266 +f 265/265/265 267/267/267 268/268/268 +f 269/269/269 254/254/254 270/270/270 +f 271/271/271 259/259/259 272/272/272 +f 271/271/271 272/272/272 273/273/273 +f 274/274/274 252/252/252 254/254/254 +f 275/275/275 273/273/273 276/276/276 +f 277/277/277 278/278/278 279/279/279 +f 254/254/254 280/280/280 274/274/274 +f 281/281/281 282/282/282 269/269/269 +f 269/269/269 270/270/270 281/281/281 +f 271/271/271 273/273/273 275/275/275 +f 266/266/266 262/262/262 278/278/278 +f 261/261/261 283/283/283 262/262/262 +f 262/262/262 284/284/284 278/278/278 +f 278/278/278 285/285/285 279/279/279 +f 283/283/283 284/284/284 262/262/262 +f 278/278/278 284/284/284 285/285/285 +f 283/283/283 286/286/286 287/287/287 +f 283/283/283 287/287/287 284/284/284 +f 286/286/286 283/283/283 261/261/261 +f 282/282/282 288/288/288 269/269/269 +f 254/254/254 269/269/269 280/280/280 +f 289/289/289 281/281/281 270/270/270 +f 290/290/290 281/281/281 289/289/289 +f 277/277/277 266/266/266 278/278/278 +f 277/277/277 279/279/279 291/291/291 +f 284/284/284 292/292/292 285/285/285 +f 256/256/256 249/249/249 293/293/293 +f 261/261/261 293/293/293 286/286/286 +f 294/294/294 285/285/285 292/292/292 +f 295/295/295 284/284/284 287/287/287 +f 296/296/296 269/269/269 288/288/288 +f 297/297/297 270/270/270 254/254/254 +f 290/290/290 289/289/289 298/298/298 +f 284/284/284 295/295/295 299/299/299 +f 284/284/284 299/299/299 292/292/292 +f 292/292/292 299/299/299 294/294/294 +f 249/249/249 300/300/300 293/293/293 +f 287/287/287 286/286/286 301/301/301 +f 287/287/287 301/301/301 295/295/295 +f 302/302/302 299/299/299 295/295/295 +f 302/302/302 295/295/295 301/301/301 +f 286/286/286 293/293/293 300/300/300 +f 249/249/249 256/256/256 250/250/250 +f 250/250/250 252/252/252 274/274/274 +f 303/303/303 296/296/296 304/304/304 +f 304/304/304 296/296/296 288/288/288 +f 269/269/269 296/296/296 305/305/305 +f 269/269/269 305/305/305 280/280/280 +f 274/274/274 280/280/280 251/251/251 +f 306/306/306 289/289/289 270/270/270 +f 306/306/306 270/270/270 297/297/297 +f 307/307/307 289/289/289 306/306/306 +f 297/297/297 254/254/254 253/253/253 +f 308/308/308 309/309/309 310/310/310 +f 286/286/286 311/311/311 301/301/301 +f 299/299/299 302/302/302 312/312/312 +f 299/299/299 312/312/312 294/294/294 +f 286/286/286 313/313/313 314/314/314 +f 314/314/314 313/313/313 315/315/315 +f 314/314/314 315/315/315 286/286/286 +f 286/286/286 315/315/315 311/311/311 +f 311/311/311 316/316/316 301/301/301 +f 301/301/301 316/316/316 302/302/302 +f 261/261/261 257/257/257 293/293/293 +f 293/293/293 257/257/257 256/256/256 +f 256/256/256 255/255/255 250/250/250 +f 288/288/288 317/317/317 304/304/304 +f 305/305/305 296/296/296 303/303/303 +f 305/305/305 303/303/303 280/280/280 +f 318/318/318 319/319/319 290/290/290 +f 320/320/320 290/290/290 321/321/321 +f 321/321/321 290/290/290 298/298/298 +f 321/321/321 298/298/298 289/289/289 +f 321/321/321 289/289/289 307/307/307 +f 253/253/253 259/259/259 271/271/271 +f 322/322/322 275/275/275 309/309/309 +f 323/323/323 309/309/309 308/308/308 +f 324/324/324 308/308/308 310/310/310 +f 277/277/277 291/291/291 325/325/325 +f 304/304/304 317/317/317 326/326/326 +f 304/304/304 326/326/326 303/303/303 +f 274/274/274 251/251/251 250/250/250 +f 327/327/327 290/290/290 320/320/320 +f 328/328/328 271/271/271 329/329/329 +f 329/329/329 271/271/271 275/275/275 +f 330/330/330 275/275/275 322/322/322 +f 331/331/331 322/322/322 309/309/309 +f 331/331/331 309/309/309 323/323/323 +f 323/323/323 308/308/308 324/324/324 +f 332/332/332 324/324/324 310/310/310 +f 291/291/291 333/333/333 325/325/325 +f 334/334/334 331/331/331 323/323/323 +f 334/334/334 323/323/323 332/332/332 +f 332/332/332 323/323/323 324/324/324 +f 317/317/317 244/244/244 335/335/335 +f 317/317/317 336/336/336 326/326/326 +f 337/337/337 338/338/338 319/319/319 +f 334/334/334 319/319/319 318/318/318 +f 318/318/318 290/290/290 327/327/327 +f 328/328/328 307/307/307 306/306/306 +f 328/328/328 306/306/306 297/297/297 +f 328/328/328 297/297/297 253/253/253 +f 321/321/321 329/329/329 275/275/275 +f 321/321/321 275/275/275 330/330/330 +f 321/321/321 330/330/330 322/322/322 +f 322/322/322 331/331/331 334/334/334 +f 291/291/291 339/339/339 333/333/333 +f 325/325/325 333/333/333 340/340/340 +f 325/325/325 340/340/340 277/277/277 +f 341/341/341 328/328/328 342/342/342 +f 342/342/342 328/328/328 329/329/329 +f 342/342/342 329/329/329 321/321/321 +f 343/343/343 321/321/321 322/322/322 +f 317/317/317 335/335/335 336/336/336 +f 336/336/336 335/335/335 344/344/344 +f 326/326/326 336/336/336 345/345/345 +f 326/326/326 345/345/345 303/303/303 +f 280/280/280 258/258/258 251/251/251 +f 346/346/346 338/338/338 337/337/337 +f 334/334/334 337/337/337 319/319/319 +f 318/318/318 327/327/327 321/321/321 +f 321/321/321 327/327/327 320/320/320 +f 321/321/321 307/307/307 328/328/328 +f 252/252/252 259/259/259 253/253/253 +f 253/253/253 271/271/271 328/328/328 +f 334/334/334 343/343/343 322/322/322 +f 347/347/347 312/312/312 302/302/302 +f 321/321/321 341/341/341 342/342/342 +f 321/321/321 343/343/343 348/348/348 +f 348/348/348 343/343/343 334/334/334 +f 337/337/337 334/334/334 332/332/332 +f 337/337/337 332/332/332 349/349/349 +f 328/328/328 341/341/341 321/321/321 +f 318/318/318 348/348/348 334/334/334 +f 346/346/346 337/337/337 349/349/349 +f 244/244/244 243/243/243 335/335/335 +f 336/336/336 344/344/344 350/350/350 +f 336/336/336 350/350/350 345/345/345 +f 345/345/345 350/350/350 303/303/303 +f 280/280/280 303/303/303 258/258/258 +f 348/348/348 318/318/318 321/321/321 +f 309/309/309 275/275/275 276/276/276 +f 339/339/339 351/351/351 352/352/352 +f 339/339/339 353/353/353 333/333/333 +f 340/340/340 333/333/333 354/354/354 +f 340/340/340 354/354/354 277/277/277 +f 277/277/277 354/354/354 355/355/355 +f 277/277/277 355/355/355 356/356/356 +f 266/266/266 277/277/277 357/357/357 +f 257/257/257 260/260/260 272/272/272 +f 358/358/358 347/347/347 359/359/359 +f 360/360/360 347/347/347 302/302/302 +f 360/360/360 302/302/302 361/361/361 +f 362/362/362 346/346/346 349/349/349 +f 363/363/363 276/276/276 273/273/273 +f 272/272/272 259/259/259 257/257/257 +f 364/364/364 365/365/365 366/366/366 +f 366/366/366 367/367/367 368/368/368 +f 369/369/369 370/370/370 371/371/371 +f 372/372/372 364/364/364 366/366/366 +f 373/373/373 374/374/374 372/372/372 +f 372/372/372 374/374/374 364/364/364 +f 375/375/375 368/368/368 369/369/369 +f 376/376/376 369/369/369 371/371/371 +f 377/377/377 366/366/366 368/368/368 +f 377/377/377 368/368/368 375/375/375 +f 378/378/378 372/372/372 366/366/366 +f 377/377/377 378/378/378 366/366/366 +f 376/376/376 371/371/371 267/267/267 +f 375/375/375 369/369/369 376/376/376 +f 379/379/379 373/373/373 372/372/372 +f 379/379/379 372/372/372 378/378/378 +f 380/380/380 379/379/379 378/378/378 +f 243/243/243 378/378/378 377/377/377 +f 350/350/350 376/376/376 267/267/267 +f 380/380/380 378/378/378 243/243/243 +f 303/303/303 267/267/267 264/264/264 +f 243/243/243 377/377/377 335/335/335 +f 381/381/381 377/377/377 375/375/375 +f 381/381/381 375/375/375 382/382/382 +f 382/382/382 375/375/375 376/376/376 +f 303/303/303 350/350/350 383/383/383 +f 383/383/383 350/350/350 267/267/267 +f 383/383/383 267/267/267 303/303/303 +f 303/303/303 264/264/264 258/258/258 +f 384/384/384 379/379/379 380/380/380 +f 335/335/335 377/377/377 381/381/381 +f 335/335/335 381/381/381 382/382/382 +f 335/335/335 382/382/382 385/385/385 +f 385/385/385 382/382/382 376/376/376 +f 385/385/385 376/376/376 350/350/350 +f 380/380/380 243/243/243 245/245/245 +f 380/380/380 245/245/245 384/384/384 +f 384/384/384 245/245/245 386/386/386 +f 344/344/344 335/335/335 385/385/385 +f 344/344/344 385/385/385 350/350/350 +f 371/371/371 268/268/268 267/267/267 +f 267/267/267 265/265/265 264/264/264 +f 387/387/387 388/388/388 362/362/362 +f 389/389/389 387/387/387 362/362/362 +f 389/389/389 362/362/362 349/349/349 +f 390/390/390 389/389/389 349/349/349 +f 391/391/391 387/387/387 390/390/390 +f 390/390/390 387/387/387 389/389/389 +f 392/392/392 390/390/390 349/349/349 +f 393/393/393 349/349/349 332/332/332 +f 393/393/393 392/392/392 349/349/349 +f 394/394/394 391/391/391 390/390/390 +f 394/394/394 390/390/390 392/392/392 +f 395/395/395 391/391/391 394/394/394 +f 396/396/396 392/392/392 393/393/393 +f 396/396/396 393/393/393 310/310/310 +f 395/395/395 394/394/394 396/396/396 +f 396/396/396 394/394/394 392/392/392 +f 397/397/397 396/396/396 310/310/310 +f 398/398/398 310/310/310 309/309/309 +f 399/399/399 395/395/395 396/396/396 +f 398/398/398 397/397/397 310/310/310 +f 399/399/399 400/400/400 395/395/395 +f 401/401/401 399/399/399 396/396/396 +f 402/402/402 396/396/396 397/397/397 +f 403/403/403 398/398/398 309/309/309 +f 403/403/403 309/309/309 276/276/276 +f 401/401/401 396/396/396 402/402/402 +f 403/403/403 397/397/397 398/398/398 +f 404/404/404 400/400/400 399/399/399 +f 405/405/405 399/399/399 401/401/401 +f 406/406/406 403/403/403 276/276/276 +f 405/405/405 404/404/404 399/399/399 +f 402/402/402 397/397/397 403/403/403 +f 407/407/407 404/404/404 405/405/405 +f 408/408/408 401/401/401 402/402/402 +f 409/409/409 404/404/404 407/407/407 +f 410/410/410 402/402/402 403/403/403 +f 411/411/411 405/405/405 401/401/401 +f 411/411/411 401/401/401 408/408/408 +f 412/412/412 408/408/408 402/402/402 +f 354/354/354 403/403/403 406/406/406 +f 363/363/363 406/406/406 276/276/276 +f 413/413/413 407/407/407 405/405/405 +f 413/413/413 405/405/405 411/411/411 +f 412/412/412 402/402/402 410/410/410 +f 410/410/410 403/403/403 354/354/354 +f 414/414/414 354/354/354 406/406/406 +f 413/413/413 409/409/409 407/407/407 +f 354/354/354 414/414/414 363/363/363 +f 363/363/363 414/414/414 406/406/406 +f 363/363/363 273/273/273 272/272/272 +f 415/415/415 409/409/409 413/413/413 +f 415/415/415 413/413/413 411/411/411 +f 416/416/416 411/411/411 408/408/408 +f 352/352/352 408/408/408 412/412/412 +f 415/415/415 411/411/411 416/416/416 +f 352/352/352 416/416/416 408/408/408 +f 417/417/417 412/412/412 410/410/410 +f 352/352/352 412/412/412 417/417/417 +f 418/418/418 354/354/354 363/363/363 +f 419/419/419 363/363/363 272/272/272 +f 363/363/363 357/357/357 418/418/418 +f 354/354/354 418/418/418 356/356/356 +f 354/354/354 356/356/356 355/355/355 +f 410/410/410 354/354/354 417/417/417 +f 417/417/417 354/354/354 353/353/353 +f 417/417/417 353/353/353 352/352/352 +f 415/415/415 416/416/416 351/351/351 +f 415/415/415 351/351/351 420/420/420 +f 420/420/420 421/421/421 415/415/415 +f 351/351/351 416/416/416 352/352/352 +f 339/339/339 352/352/352 353/353/353 +f 333/333/333 353/353/353 354/354/354 +f 277/277/277 356/356/356 418/418/418 +f 277/277/277 418/418/418 357/357/357 +f 266/266/266 357/357/357 363/363/363 +f 266/266/266 363/363/363 419/419/419 +f 266/266/266 419/419/419 260/260/260 +f 260/260/260 419/419/419 272/272/272 +f 255/255/255 257/257/257 259/259/259 +f 255/255/255 259/259/259 250/250/250 +f 393/393/393 332/332/332 310/310/310 +f 386/386/386 422/422/422 384/384/384 +f 384/384/384 423/423/423 379/379/379 +f 379/379/379 423/423/423 373/373/373 +f 415/415/415 421/421/421 409/409/409 +f 400/400/400 424/424/424 395/395/395 +f 395/395/395 424/424/424 391/391/391 +f 384/384/384 422/422/422 423/423/423 +f 373/373/373 425/425/425 374/374/374 +f 374/374/374 425/425/425 426/426/426 +f 420/420/420 427/427/427 421/421/421 +f 409/409/409 428/428/428 404/404/404 +f 404/404/404 428/428/428 400/400/400 +f 400/400/400 428/428/428 429/429/429 +f 400/400/400 429/429/429 424/424/424 +f 391/391/391 430/430/430 387/387/387 +f 387/387/387 430/430/430 388/388/388 +f 386/386/386 431/431/431 422/422/422 +f 409/409/409 421/421/421 432/432/432 +f 409/409/409 432/432/432 428/428/428 +f 424/424/424 433/433/433 391/391/391 +f 373/373/373 423/423/423 425/425/425 +f 391/391/391 433/433/433 430/430/430 +f 422/422/422 434/434/434 423/423/423 +f 423/423/423 434/434/434 425/425/425 +f 425/425/425 435/435/435 426/426/426 +f 427/427/427 436/436/436 421/421/421 +f 432/432/432 437/437/437 428/428/428 +f 428/428/428 438/438/438 429/429/429 +f 429/429/429 438/438/438 439/439/439 +f 429/429/429 439/439/439 424/424/424 +f 424/424/424 439/439/439 433/433/433 +f 433/433/433 440/440/440 430/430/430 +f 421/421/421 436/436/436 432/432/432 +f 428/428/428 437/437/437 438/438/438 +f 430/430/430 440/440/440 441/441/441 +f 430/430/430 441/441/441 388/388/388 +f 388/388/388 441/441/441 442/442/442 +f 431/431/431 443/443/443 444/444/444 +f 431/431/431 444/444/444 422/422/422 +f 422/422/422 444/444/444 434/434/434 +f 445/445/445 436/436/436 427/427/427 +f 446/446/446 447/447/447 433/433/433 +f 433/433/433 447/447/447 448/448/448 +f 433/433/433 448/448/448 440/440/440 +f 434/434/434 449/449/449 425/425/425 +f 425/425/425 449/449/449 435/435/435 +f 436/436/436 445/445/445 450/450/450 +f 436/436/436 451/451/451 432/432/432 +f 439/439/439 452/452/452 433/433/433 +f 433/433/433 452/452/452 446/446/446 +f 446/446/446 452/452/452 453/453/453 +f 446/446/446 453/453/453 447/447/447 +f 447/447/447 453/453/453 448/448/448 +f 454/454/454 455/455/455 456/456/456 +f 456/456/456 455/455/455 457/457/457 +f 458/458/458 457/457/457 455/455/455 +f 459/459/459 455/455/455 460/460/460 +f 461/461/461 460/460/460 462/462/462 +f 358/358/358 463/463/463 462/462/462 +f 358/358/358 462/462/462 347/347/347 +f 359/359/359 347/347/347 360/360/360 +f 464/464/464 360/360/360 465/465/465 +f 465/465/465 360/360/360 361/361/361 +f 465/465/465 361/361/361 302/302/302 +f 465/465/465 302/302/302 466/466/466 +f 466/466/466 302/302/302 316/316/316 +f 458/458/458 455/455/455 459/459/459 +f 461/461/461 462/462/462 467/467/467 +f 467/467/467 462/462/462 463/463/463 +f 468/468/468 359/359/359 360/360/360 +f 468/468/468 360/360/360 464/464/464 +f 469/469/469 465/465/465 466/466/466 +f 459/459/459 460/460/460 461/461/461 +f 468/468/468 464/464/464 470/470/470 +f 470/470/470 464/464/464 465/465/465 +f 470/470/470 465/465/465 469/469/469 +f 471/471/471 466/466/466 316/316/316 +f 471/471/471 316/316/316 315/315/315 +f 467/467/467 463/463/463 358/358/358 +f 472/472/472 358/358/358 359/359/359 +f 472/472/472 359/359/359 473/473/473 +f 473/473/473 359/359/359 468/468/468 +f 474/474/474 470/470/470 469/469/469 +f 474/474/474 469/469/469 466/466/466 +f 474/474/474 466/466/466 471/471/471 +f 475/475/475 315/315/315 313/313/313 +f 476/476/476 459/459/459 461/461/461 +f 472/472/472 467/467/467 358/358/358 +f 477/477/477 468/468/468 470/470/470 +f 477/477/477 470/470/470 474/474/474 +f 478/478/478 474/474/474 471/471/471 +f 478/478/478 471/471/471 315/315/315 +f 263/263/263 475/475/475 313/313/313 +f 479/479/479 458/458/458 459/459/459 +f 468/468/468 472/472/472 473/473/473 +f 468/468/468 477/477/477 478/478/478 +f 478/478/478 477/477/477 474/474/474 +f 479/479/479 459/459/459 476/476/476 +f 480/480/480 461/461/461 467/467/467 +f 268/268/268 478/478/478 315/315/315 +f 268/268/268 315/315/315 475/475/475 +f 480/480/480 476/476/476 461/461/461 +f 480/480/480 467/467/467 481/481/481 +f 481/481/481 467/467/467 472/472/472 +f 482/482/482 472/472/472 468/468/468 +f 268/268/268 475/475/475 265/265/265 +f 265/265/265 475/475/475 263/263/263 +f 481/481/481 472/472/472 483/483/483 +f 482/482/482 483/483/483 472/472/472 +f 484/484/484 479/479/479 476/476/476 +f 485/485/485 476/476/476 480/480/480 +f 486/486/486 479/479/479 484/484/484 +f 484/484/484 476/476/476 485/485/485 +f 365/365/365 481/481/481 367/367/367 +f 367/367/367 481/481/481 483/483/483 +f 367/367/367 483/483/483 482/482/482 +f 482/482/482 468/468/468 478/478/478 +f 486/486/486 487/487/487 479/479/479 +f 488/488/488 480/480/480 481/481/481 +f 488/488/488 481/481/481 365/365/365 +f 370/370/370 482/482/482 478/478/478 +f 488/488/488 485/485/485 480/480/480 +f 368/368/368 367/367/367 482/482/482 +f 371/371/371 370/370/370 478/478/478 +f 371/371/371 478/478/478 268/268/268 +f 482/482/482 370/370/370 368/368/368 +f 485/485/485 374/374/374 484/484/484 +f 484/484/484 374/374/374 426/426/426 +f 484/484/484 426/426/426 486/486/486 +f 435/435/435 489/489/489 486/486/486 +f 435/435/435 486/486/486 426/426/426 +f 374/374/374 485/485/485 364/364/364 +f 364/364/364 485/485/485 488/488/488 +f 364/364/364 488/488/488 365/365/365 +f 366/366/366 365/365/365 367/367/367 +f 369/369/369 368/368/368 370/370/370 +f 450/450/450 490/490/490 491/491/491 +f 450/450/450 491/491/491 436/436/436 +f 436/436/436 491/491/491 451/451/451 +f 432/432/432 451/451/451 437/437/437 +f 437/437/437 492/492/492 438/438/438 +f 438/438/438 492/492/492 439/439/439 +f 448/448/448 453/453/453 440/440/440 +f 443/443/443 493/493/493 444/444/444 +f 444/444/444 494/494/494 434/434/434 +f 449/449/449 495/495/495 435/435/435 +f 435/435/435 495/495/495 489/489/489 +f 486/486/486 489/489/489 487/487/487 +f 479/479/479 487/487/487 458/458/458 +f 457/457/457 458/458/458 456/456/456 +f 445/445/445 496/496/496 450/450/450 +f 450/450/450 496/496/496 490/490/490 +f 437/437/437 451/451/451 492/492/492 +f 492/492/492 452/452/452 439/439/439 +f 453/453/453 452/452/452 497/497/497 +f 453/453/453 497/497/497 498/498/498 +f 453/453/453 498/498/498 440/440/440 +f 440/440/440 498/498/498 499/499/499 +f 440/440/440 499/499/499 441/441/441 +f 442/442/442 441/441/441 500/500/500 +f 442/442/442 500/500/500 501/501/501 +f 443/443/443 502/502/502 493/493/493 +f 493/493/493 502/502/502 444/444/444 +f 444/444/444 503/503/503 494/494/494 +f 494/494/494 503/503/503 434/434/434 +f 487/487/487 504/504/504 458/458/458 +f 458/458/458 504/504/504 505/505/505 +f 445/445/445 506/506/506 507/507/507 +f 445/445/445 507/507/507 508/508/508 +f 445/445/445 508/508/508 496/496/496 +f 496/496/496 508/508/508 509/509/509 +f 496/496/496 509/509/509 490/490/490 +f 490/490/490 509/509/509 510/510/510 +f 490/490/490 510/510/510 491/491/491 +f 491/491/491 510/510/510 451/451/451 +f 451/451/451 511/511/511 492/492/492 +f 499/499/499 498/498/498 441/441/441 +f 512/512/512 513/513/513 443/443/443 +f 443/443/443 513/513/513 502/502/502 +f 502/502/502 513/513/513 514/514/514 +f 502/502/502 514/514/514 515/515/515 +f 502/502/502 515/515/515 444/444/444 +f 444/444/444 515/515/515 503/503/503 +f 434/434/434 503/503/503 449/449/449 +f 495/495/495 516/516/516 489/489/489 +f 504/504/504 517/517/517 505/505/505 +f 505/505/505 517/517/517 518/518/518 +f 505/505/505 518/518/518 458/458/458 +f 458/458/458 518/518/518 519/519/519 +f 458/458/458 519/519/519 456/456/456 +f 506/506/506 520/520/520 521/521/521 +f 506/506/506 522/522/522 507/507/507 +f 507/507/507 522/522/522 508/508/508 +f 508/508/508 523/523/523 509/509/509 +f 509/509/509 523/523/523 510/510/510 +f 510/510/510 524/524/524 451/451/451 +f 452/452/452 492/492/492 525/525/525 +f 452/452/452 525/525/525 497/497/497 +f 497/497/497 525/525/525 498/498/498 +f 498/498/498 526/526/526 500/500/500 +f 498/498/498 500/500/500 441/441/441 +f 501/501/501 500/500/500 240/240/240 +f 242/242/242 527/527/527 512/512/512 +f 512/512/512 527/527/527 528/528/528 +f 512/512/512 528/528/528 513/513/513 +f 513/513/513 528/528/528 514/514/514 +f 514/514/514 529/529/529 515/515/515 +f 515/515/515 529/529/529 530/530/530 +f 515/515/515 530/530/530 503/503/503 +f 503/503/503 530/530/530 531/531/531 +f 503/503/503 531/531/531 449/449/449 +f 449/449/449 531/531/531 532/532/532 +f 449/449/449 532/532/532 495/495/495 +f 495/495/495 532/532/532 533/533/533 +f 495/495/495 533/533/533 534/534/534 +f 495/495/495 534/534/534 516/516/516 +f 489/489/489 516/516/516 535/535/535 +f 489/489/489 535/535/535 487/487/487 +f 487/487/487 535/535/535 504/504/504 +f 504/504/504 535/535/535 536/536/536 +f 504/504/504 536/536/536 517/517/517 +f 517/517/517 536/536/536 537/537/537 +f 517/517/517 537/537/537 518/518/518 +f 518/518/518 537/537/537 519/519/519 +f 519/519/519 538/538/538 456/456/456 +f 454/454/454 456/456/456 246/246/246 +f 454/454/454 246/246/246 248/248/248 +f 316/316/316 311/311/311 315/315/315 +f 313/313/313 286/286/286 263/263/263 +f 263/263/263 286/286/286 300/300/300 +f 263/263/263 300/300/300 249/249/249 +f 535/535/535 539/539/539 536/536/536 +f 536/536/536 539/539/539 540/540/540 +f 536/536/536 540/540/540 537/537/537 +f 537/537/537 540/540/540 541/541/541 +f 537/537/537 541/541/541 519/519/519 +f 519/519/519 541/541/541 538/538/538 +f 456/456/456 542/542/542 246/246/246 +f 521/521/521 522/522/522 506/506/506 +f 522/522/522 543/543/543 508/508/508 +f 508/508/508 543/543/543 523/523/523 +f 523/523/523 543/543/543 544/544/544 +f 523/523/523 544/544/544 510/510/510 +f 510/510/510 544/544/544 545/545/545 +f 510/510/510 545/545/545 524/524/524 +f 524/524/524 545/545/545 511/511/511 +f 524/524/524 511/511/511 451/451/451 +f 511/511/511 546/546/546 492/492/492 +f 492/492/492 546/546/546 525/525/525 +f 242/242/242 241/241/241 547/547/547 +f 242/242/242 547/547/547 527/527/527 +f 528/528/528 548/548/548 514/514/514 +f 514/514/514 548/548/548 529/529/529 +f 529/529/529 548/548/548 530/530/530 +f 541/541/541 549/549/549 538/538/538 +f 538/538/538 549/549/549 550/550/550 +f 538/538/538 550/550/550 456/456/456 +f 456/456/456 550/550/550 551/551/551 +f 456/456/456 551/551/551 542/542/542 +f 542/542/542 551/551/551 246/246/246 +f 520/520/520 552/552/552 553/553/553 +f 520/520/520 553/553/553 521/521/521 +f 521/521/521 553/553/553 522/522/522 +f 522/522/522 553/553/553 554/554/554 +f 522/522/522 554/554/554 543/543/543 +f 543/543/543 554/554/554 544/544/544 +f 525/525/525 555/555/555 498/498/498 +f 498/498/498 555/555/555 556/556/556 +f 498/498/498 556/556/556 557/557/557 +f 498/498/498 557/557/557 526/526/526 +f 526/526/526 557/557/557 500/500/500 +f 500/500/500 558/558/558 240/240/240 +f 240/240/240 558/558/558 559/559/559 +f 240/240/240 559/559/559 241/241/241 +f 527/527/527 547/547/547 560/560/560 +f 527/527/527 560/560/560 528/528/528 +f 528/528/528 560/560/560 561/561/561 +f 528/528/528 561/561/561 548/548/548 +f 548/548/548 561/561/561 562/562/562 +f 548/548/548 562/562/562 530/530/530 +f 531/531/531 530/530/530 532/532/532 +f 532/532/532 530/530/530 534/534/534 +f 532/532/532 534/534/534 533/533/533 +f 516/516/516 563/563/563 535/535/535 +f 535/535/535 563/563/563 539/539/539 +f 539/539/539 563/563/563 564/564/564 +f 539/539/539 564/564/564 540/540/540 +f 540/540/540 564/564/564 541/541/541 +f 541/541/541 564/564/564 565/565/565 +f 541/541/541 565/565/565 549/549/549 +f 550/550/550 549/549/549 566/566/566 +f 550/550/550 566/566/566 551/551/551 +f 551/551/551 566/566/566 567/567/567 +f 551/551/551 567/567/567 246/246/246 +f 246/246/246 567/567/567 568/568/568 +f 246/246/246 568/568/568 247/247/247 +f 247/247/247 568/568/568 552/552/552 +f 247/247/247 552/552/552 520/520/520 +f 553/553/553 552/552/552 569/569/569 +f 553/553/553 569/569/569 570/570/570 +f 553/553/553 570/570/570 554/554/554 +f 554/554/554 570/570/570 544/544/544 +f 544/544/544 570/570/570 571/571/571 +f 544/544/544 571/571/571 545/545/545 +f 545/545/545 571/571/571 572/572/572 +f 545/545/545 572/572/572 511/511/511 +f 525/525/525 546/546/546 573/573/573 +f 556/556/556 555/555/555 557/557/557 +f 557/557/557 555/555/555 574/574/574 +f 557/557/557 574/574/574 500/500/500 +f 500/500/500 574/574/574 558/558/558 +f 560/560/560 547/547/547 561/561/561 +f 561/561/561 575/575/575 562/562/562 +f 562/562/562 575/575/575 576/576/576 +f 562/562/562 576/576/576 530/530/530 +f 530/530/530 576/576/576 577/577/577 +f 530/530/530 577/577/577 534/534/534 +f 516/516/516 534/534/534 563/563/563 +f 563/563/563 578/578/578 564/564/564 +f 564/564/564 578/578/578 579/579/579 +f 564/564/564 579/579/579 565/565/565 +f 565/565/565 579/579/579 580/580/580 +f 565/565/565 580/580/580 549/549/549 +f 549/549/549 580/580/580 566/566/566 +f 567/567/567 566/566/566 568/568/568 +f 569/569/569 581/581/581 570/570/570 +f 570/570/570 581/581/581 582/582/582 +f 570/570/570 582/582/582 571/571/571 +f 571/571/571 582/582/582 583/583/583 +f 571/571/571 583/583/583 572/572/572 +f 572/572/572 583/583/583 511/511/511 +f 525/525/525 573/573/573 555/555/555 +f 555/555/555 584/584/584 574/574/574 +f 574/574/574 584/584/584 558/558/558 +f 558/558/558 585/585/585 559/559/559 +f 561/561/561 547/547/547 575/575/575 +f 575/575/575 586/586/586 576/576/576 +f 576/576/576 586/586/586 587/587/587 +f 576/576/576 587/587/587 577/577/577 +f 577/577/577 587/587/587 588/588/588 +f 577/577/577 588/588/588 534/534/534 +f 579/579/579 578/578/578 589/589/589 +f 579/579/579 589/589/589 580/580/580 +f 580/580/580 589/589/589 590/590/590 +f 580/580/580 590/590/590 566/566/566 +f 566/566/566 590/590/590 591/591/591 +f 566/566/566 591/591/591 568/568/568 +f 552/552/552 592/592/592 569/569/569 +f 569/569/569 592/592/592 581/581/581 +f 581/581/581 592/592/592 593/593/593 +f 581/581/581 593/593/593 582/582/582 +f 582/582/582 593/593/593 594/594/594 +f 582/582/582 594/594/594 583/583/583 +f 583/583/583 594/594/594 511/511/511 +f 511/511/511 594/594/594 595/595/595 +f 511/511/511 595/595/595 546/546/546 +f 584/584/584 555/555/555 596/596/596 +f 584/584/584 596/596/596 585/585/585 +f 584/584/584 585/585/585 558/558/558 +f 547/547/547 597/597/597 575/575/575 +f 575/575/575 597/597/597 598/598/598 +f 575/575/575 598/598/598 586/586/586 +f 586/586/586 598/598/598 587/587/587 +f 587/587/587 598/598/598 588/588/588 +f 534/534/534 588/588/588 599/599/599 +f 534/534/534 599/599/599 563/563/563 +f 578/578/578 600/600/600 589/589/589 +f 589/589/589 600/600/600 601/601/601 +f 589/589/589 601/601/601 590/590/590 +f 590/590/590 601/601/601 591/591/591 +f 552/552/552 602/602/602 592/592/592 +f 592/592/592 602/602/602 593/593/593 +f 593/593/593 602/602/602 603/603/603 +f 593/593/593 603/603/603 594/594/594 +f 546/546/546 595/595/595 573/573/573 +f 241/241/241 559/559/559 597/597/597 +f 241/241/241 597/597/597 547/547/547 +f 597/597/597 604/604/604 598/598/598 +f 598/598/598 604/604/604 588/588/588 +f 599/599/599 605/605/605 578/578/578 +f 599/599/599 578/578/578 563/563/563 +f 568/568/568 591/591/591 606/606/606 +f 568/568/568 606/606/606 552/552/552 +f 552/552/552 606/606/606 607/607/607 +f 552/552/552 607/607/607 602/602/602 +f 602/602/602 607/607/607 594/594/594 +f 602/602/602 594/594/594 603/603/603 +f 573/573/573 608/608/608 596/596/596 +f 573/573/573 596/596/596 555/555/555 +f 588/588/588 605/605/605 599/599/599 +f 607/607/607 606/606/606 609/609/609 +f 607/607/607 609/609/609 594/594/594 +f 594/594/594 609/609/609 595/595/595 +f 595/595/595 608/608/608 573/573/573 +f 559/559/559 585/585/585 610/610/610 +f 559/559/559 610/610/610 597/597/597 +f 588/588/588 604/604/604 605/605/605 +f 605/605/605 611/611/611 578/578/578 +f 578/578/578 611/611/611 600/600/600 +f 600/600/600 611/611/611 601/601/601 +f 591/591/591 601/601/601 606/606/606 +f 609/609/609 612/612/612 595/595/595 +f 596/596/596 613/613/613 585/585/585 +f 610/610/610 604/604/604 597/597/597 +f 595/595/595 612/612/612 608/608/608 +f 596/596/596 608/608/608 613/613/613 +f 585/585/585 613/613/613 610/610/610 +f 604/604/604 614/614/614 605/605/605 +f 605/605/605 614/614/614 611/611/611 +f 601/601/601 611/611/611 615/615/615 +f 601/601/601 615/615/615 606/606/606 +f 606/606/606 616/616/616 609/609/609 +f 609/609/609 616/616/616 612/612/612 +f 610/610/610 617/617/617 604/604/604 +f 604/604/604 617/617/617 614/614/614 +f 606/606/606 615/615/615 616/616/616 +f 612/612/612 616/616/616 237/237/237 +f 612/612/612 237/237/237 608/608/608 +f 608/608/608 237/237/237 613/613/613 +f 613/613/613 618/618/618 610/610/610 +f 614/614/614 239/239/239 611/611/611 +f 611/611/611 238/238/238 615/615/615 +f 610/610/610 618/618/618 617/617/617 +f 614/614/614 617/617/617 239/239/239 +f 611/611/611 239/239/239 238/238/238 +f 615/615/615 238/238/238 616/616/616 +f 616/616/616 238/238/238 237/237/237 +f 613/613/613 237/237/237 618/618/618 +f 617/617/617 618/618/618 239/239/239 +f 237/237/237 239/239/239 618/618/618 +f 512/512/512 619/619/619 242/242/242 +f 242/242/242 619/619/619 240/240/240 +f 443/443/443 620/620/620 512/512/512 +f 619/619/619 512/512/512 620/620/620 +f 362/362/362 621/621/621 346/346/346 +f 431/431/431 620/620/620 443/443/443 +f 388/388/388 622/622/622 623/623/623 +f 624/624/624 282/282/282 281/281/281 +f 624/624/624 281/281/281 625/625/625 +f 624/624/624 288/288/288 282/282/282 +f 626/626/626 317/317/317 288/288/288 +f 626/626/626 288/288/288 624/624/624 +f 386/386/386 627/627/627 431/431/431 +f 620/620/620 431/431/431 627/627/627 +f 625/625/625 290/290/290 628/628/628 +f 625/625/625 281/281/281 290/290/290 +f 629/629/629 240/240/240 619/619/619 +f 629/629/629 501/501/501 240/240/240 +f 501/501/501 629/629/629 442/442/442 +f 442/442/442 629/629/629 622/622/622 +f 622/622/622 388/388/388 442/442/442 +f 623/623/623 362/362/362 388/388/388 +f 621/621/621 362/362/362 623/623/623 +f 628/628/628 338/338/338 621/621/621 +f 628/628/628 290/290/290 319/319/319 +f 627/627/627 386/386/386 630/630/630 +f 621/621/621 338/338/338 346/346/346 +f 628/628/628 319/319/319 338/338/338 +f 244/244/244 626/626/626 245/245/245 +f 245/245/245 626/626/626 630/630/630 +f 630/630/630 386/386/386 245/245/245 +f 626/626/626 244/244/244 317/317/317 +f 247/247/247 520/520/520 631/631/631 +f 445/445/445 427/427/427 632/632/632 +f 633/633/633 520/520/520 506/506/506 +f 631/631/631 520/520/520 633/633/633 +f 634/634/634 454/454/454 631/631/631 +f 633/633/633 506/506/506 632/632/632 +f 632/632/632 506/506/506 445/445/445 +f 631/631/631 454/454/454 248/248/248 +f 420/420/420 635/635/635 632/632/632 +f 632/632/632 427/427/427 420/420/420 +f 631/631/631 248/248/248 247/247/247 +f 636/636/636 339/339/339 291/291/291 +f 634/634/634 455/455/455 454/454/454 +f 339/339/339 636/636/636 635/635/635 +f 455/455/455 634/634/634 637/637/637 +f 312/312/312 638/638/638 294/294/294 +f 339/339/339 635/635/635 351/351/351 +f 420/420/420 351/351/351 635/635/635 +f 460/460/460 455/455/455 637/637/637 +f 460/460/460 637/637/637 639/639/639 +f 460/460/460 639/639/639 462/462/462 +f 285/285/285 294/294/294 640/640/640 +f 640/640/640 294/294/294 638/638/638 +f 639/639/639 347/347/347 462/462/462 +f 638/638/638 347/347/347 639/639/639 +f 636/636/636 291/291/291 279/279/279 +f 638/638/638 312/312/312 347/347/347 +f 279/279/279 640/640/640 636/636/636 +f 640/640/640 279/279/279 285/285/285 +f 641/641/641 642/642/642 643/643/643 +f 643/643/643 642/642/642 644/644/644 +f 643/643/643 644/644/644 645/645/645 +f 645/645/645 644/644/644 646/646/646 +f 645/645/645 646/646/646 647/647/647 +f 647/647/647 646/646/646 648/648/648 +f 648/648/648 646/646/646 649/649/649 +f 648/648/648 649/649/649 650/650/650 +f 650/650/650 649/649/649 651/651/651 +f 650/650/650 651/651/651 652/652/652 +f 652/652/652 651/651/651 653/653/653 +f 652/652/652 653/653/653 654/654/654 +f 654/654/654 653/653/653 655/655/655 +f 654/654/654 655/655/655 656/656/656 +f 656/656/656 655/655/655 657/657/657 +f 656/656/656 657/657/657 658/658/658 +f 656/656/656 658/658/658 659/659/659 +f 659/659/659 658/658/658 660/660/660 +f 660/660/660 658/658/658 661/661/661 +f 660/660/660 661/661/661 662/662/662 +f 660/660/660 662/662/662 663/663/663 +f 663/663/663 662/662/662 664/664/664 +f 664/664/664 662/662/662 665/665/665 +f 664/664/664 665/665/665 666/666/666 +f 666/666/666 665/665/665 667/667/667 +f 666/666/666 667/667/667 641/641/641 +f 641/641/641 667/667/667 668/668/668 +f 641/641/641 668/668/668 642/642/642 +f 639/639/639 655/655/655 653/653/653 +f 639/639/639 653/653/653 638/638/638 +f 638/638/638 653/653/653 651/651/651 +f 638/638/638 651/651/651 640/640/640 +f 651/651/651 649/649/649 640/640/640 +f 640/640/640 649/649/649 646/646/646 +f 640/640/640 646/646/646 636/636/636 +f 636/636/636 646/646/646 644/644/644 +f 636/636/636 644/644/644 635/635/635 +f 635/635/635 644/644/644 642/642/642 +f 642/642/642 668/668/668 635/635/635 +f 635/635/635 668/668/668 632/632/632 +f 668/668/668 667/667/667 632/632/632 +f 667/667/667 665/665/665 632/632/632 +f 632/632/632 665/665/665 633/633/633 +f 633/633/633 665/665/665 662/662/662 +f 633/633/633 662/662/662 631/631/631 +f 631/631/631 662/662/662 661/661/661 +f 631/631/631 661/661/661 658/658/658 +f 631/631/631 658/658/658 634/634/634 +f 634/634/634 658/658/658 637/637/637 +f 637/637/637 658/658/658 657/657/657 +f 637/637/637 657/657/657 639/639/639 +f 639/639/639 657/657/657 655/655/655 +f 641/641/641 643/643/643 621/621/621 +f 621/621/621 643/643/643 628/628/628 +f 643/643/643 645/645/645 628/628/628 +f 628/628/628 645/645/645 647/647/647 +f 628/628/628 647/647/647 625/625/625 +f 625/625/625 647/647/647 648/648/648 +f 625/625/625 648/648/648 624/624/624 +f 648/648/648 650/650/650 624/624/624 +f 624/624/624 650/650/650 626/626/626 +f 650/650/650 652/652/652 626/626/626 +f 652/652/652 654/654/654 626/626/626 +f 626/626/626 654/654/654 630/630/630 +f 630/630/630 654/654/654 656/656/656 +f 630/630/630 656/656/656 627/627/627 +f 627/627/627 656/656/656 620/620/620 +f 620/620/620 656/656/656 659/659/659 +f 620/620/620 659/659/659 619/619/619 +f 659/659/659 660/660/660 619/619/619 +f 619/619/619 660/660/660 629/629/629 +f 629/629/629 660/660/660 663/663/663 +f 629/629/629 663/663/663 664/664/664 +f 629/629/629 664/664/664 622/622/622 +f 664/664/664 666/666/666 622/622/622 +f 622/622/622 666/666/666 641/641/641 +f 622/622/622 641/641/641 623/623/623 +f 623/623/623 641/641/641 621/621/621 +f 669/669/669 670/670/670 671/671/671 +f 672/672/672 673/673/673 674/674/674 +f 675/675/675 676/676/676 677/677/677 +f 678/678/678 679/679/679 680/680/680 +f 681/681/681 682/682/682 669/669/669 +f 681/681/681 669/669/669 671/671/671 +f 683/683/683 676/676/676 675/675/675 +f 680/680/680 679/679/679 684/684/684 +f 674/674/674 681/681/681 671/671/671 +f 685/685/685 686/686/686 687/687/687 +f 683/683/683 675/675/675 688/688/688 +f 688/688/688 675/675/675 689/689/689 +f 690/690/690 678/678/678 680/680/680 +f 673/673/673 691/691/691 681/681/681 +f 673/673/673 681/681/681 674/674/674 +f 683/683/683 692/692/692 676/676/676 +f 693/693/693 692/692/692 683/683/683 +f 688/688/688 689/689/689 694/694/694 +f 688/688/688 694/694/694 695/695/695 +f 696/696/696 691/691/691 673/673/673 +f 672/672/672 674/674/674 697/697/697 +f 692/692/692 698/698/698 676/676/676 +f 699/699/699 690/690/690 700/700/700 +f 696/696/696 701/701/701 691/691/691 +f 702/702/702 703/703/703 682/682/682 +f 691/691/691 702/702/702 681/681/681 +f 681/681/681 702/702/702 682/682/682 +f 704/704/704 685/685/685 705/705/705 +f 705/705/705 685/685/685 687/687/687 +f 706/706/706 707/707/707 693/693/693 +f 693/693/693 707/707/707 692/692/692 +f 672/672/672 697/697/697 708/708/708 +f 672/672/672 708/708/708 709/709/709 +f 710/710/710 711/711/711 712/712/712 +f 711/711/711 704/704/704 712/712/712 +f 712/712/712 704/704/704 705/705/705 +f 713/713/713 710/710/710 712/712/712 +f 706/706/706 714/714/714 707/707/707 +f 707/707/707 715/715/715 692/692/692 +f 692/692/692 715/715/715 698/698/698 +f 716/716/716 699/699/699 700/700/700 +f 700/700/700 690/690/690 717/717/717 +f 690/690/690 680/680/680 718/718/718 +f 718/718/718 680/680/680 684/684/684 +f 696/696/696 719/719/719 701/701/701 +f 701/701/701 702/702/702 691/691/691 +f 706/706/706 720/720/720 714/714/714 +f 717/717/717 690/690/690 718/718/718 +f 721/721/721 719/719/719 696/696/696 +f 722/722/722 710/710/710 713/713/713 +f 723/723/723 705/705/705 687/687/687 +f 724/724/724 720/720/720 706/706/706 +f 707/707/707 725/725/725 715/715/715 +f 726/726/726 727/727/727 695/695/695 +f 716/716/716 700/700/700 719/719/719 +f 719/719/719 700/700/700 717/717/717 +f 701/701/701 719/719/719 702/702/702 +f 709/709/709 708/708/708 728/728/728 +f 713/713/713 712/712/712 725/725/725 +f 725/725/725 712/712/712 705/705/705 +f 725/725/725 705/705/705 723/723/723 +f 721/721/721 716/716/716 719/719/719 +f 702/702/702 717/717/717 718/718/718 +f 702/702/702 718/718/718 703/703/703 +f 714/714/714 725/725/725 707/707/707 +f 725/725/725 723/723/723 715/715/715 +f 715/715/715 723/723/723 698/698/698 +f 729/729/729 730/730/730 727/727/727 +f 731/731/731 732/732/732 721/721/721 +f 721/721/721 732/732/732 716/716/716 +f 719/719/719 717/717/717 702/702/702 +f 733/733/733 728/728/728 734/734/734 +f 722/722/722 735/735/735 736/736/736 +f 711/711/711 737/737/737 738/738/738 +f 722/722/722 736/736/736 710/710/710 +f 711/711/711 710/710/710 737/737/737 +f 704/704/704 711/711/711 738/738/738 +f 704/704/704 738/738/738 739/739/739 +f 685/685/685 704/704/704 739/739/739 +f 685/685/685 739/739/739 686/686/686 +f 713/713/713 720/720/720 722/722/722 +f 725/725/725 714/714/714 713/713/713 +f 720/720/720 724/724/724 722/722/722 +f 722/722/722 724/724/724 740/740/740 +f 722/722/722 740/740/740 741/741/741 +f 714/714/714 720/720/720 713/713/713 +f 742/742/742 675/675/675 677/677/677 +f 729/729/729 727/727/727 726/726/726 +f 743/743/743 726/726/726 695/695/695 +f 743/743/743 695/695/695 694/694/694 +f 694/694/694 689/689/689 675/675/675 +f 694/694/694 675/675/675 742/742/742 +f 744/744/744 729/729/729 726/726/726 +f 745/745/745 743/743/743 694/694/694 +f 746/746/746 747/747/747 729/729/729 +f 748/748/748 694/694/694 742/742/742 +f 746/746/746 729/729/729 749/749/749 +f 749/749/749 729/729/729 744/744/744 +f 744/744/744 726/726/726 743/743/743 +f 745/745/745 694/694/694 748/748/748 +f 743/743/743 678/678/678 744/744/744 +f 744/744/744 699/699/699 749/749/749 +f 749/749/749 750/750/750 746/746/746 +f 732/732/732 751/751/751 746/746/746 +f 699/699/699 744/744/744 678/678/678 +f 678/678/678 743/743/743 745/745/745 +f 732/732/732 746/746/746 750/750/750 +f 750/750/750 749/749/749 699/699/699 +f 679/679/679 745/745/745 748/748/748 +f 716/716/716 732/732/732 750/750/750 +f 690/690/690 699/699/699 678/678/678 +f 678/678/678 745/745/745 679/679/679 +f 716/716/716 750/750/750 699/699/699 +f 734/734/734 728/728/728 752/752/752 +f 752/752/752 728/728/728 708/708/708 +f 753/753/753 754/754/754 734/734/734 +f 697/697/697 674/674/674 671/671/671 +f 736/736/736 753/753/753 734/734/734 +f 736/736/736 734/734/734 752/752/752 +f 752/752/752 708/708/708 737/737/737 +f 738/738/738 708/708/708 697/697/697 +f 738/738/738 697/697/697 739/739/739 +f 697/697/697 671/671/671 670/670/670 +f 737/737/737 708/708/708 738/738/738 +f 710/710/710 752/752/752 737/737/737 +f 735/735/735 753/753/753 736/736/736 +f 736/736/736 752/752/752 710/710/710 +f 686/686/686 739/739/739 697/697/697 +f 686/686/686 697/697/697 755/755/755 +f 755/755/755 697/697/697 670/670/670 +f 756/756/756 757/757/757 758/758/758 +f 759/759/759 756/756/756 758/758/758 +f 747/747/747 746/746/746 760/760/760 +f 761/761/761 762/762/762 763/763/763 +f 764/764/764 765/765/765 766/766/766 +f 765/765/765 767/767/767 768/768/768 +f 765/765/765 768/768/768 769/769/769 +f 770/770/770 771/771/771 772/772/772 +f 773/773/773 774/774/774 775/775/775 +f 741/741/741 740/740/740 776/776/776 +f 734/734/734 754/754/754 733/733/733 +f 751/751/751 732/732/732 731/731/731 +f 777/777/777 776/776/776 778/778/778 +f 730/730/730 747/747/747 779/779/779 +f 779/779/779 780/780/780 781/781/781 +f 781/781/781 780/780/780 782/782/782 +f 782/782/782 783/783/783 770/770/770 +f 751/751/751 731/731/731 784/784/784 +f 785/785/785 784/784/784 786/786/786 +f 754/754/754 753/753/753 733/733/733 +f 733/733/733 787/787/787 788/788/788 +f 789/789/789 790/790/790 763/763/763 +f 729/729/729 747/747/747 730/730/730 +f 779/779/779 747/747/747 780/780/780 +f 770/770/770 783/783/783 791/791/791 +f 770/770/770 791/791/791 771/771/771 +f 780/780/780 747/747/747 792/792/792 +f 782/782/782 780/780/780 793/793/793 +f 782/782/782 793/793/793 783/783/783 +f 783/783/783 793/793/793 791/791/791 +f 780/780/780 792/792/792 793/793/793 +f 771/771/771 791/791/791 794/794/794 +f 793/793/793 792/792/792 795/795/795 +f 793/793/793 796/796/796 791/791/791 +f 747/747/747 760/760/760 792/792/792 +f 793/793/793 795/795/795 796/796/796 +f 791/791/791 796/796/796 794/794/794 +f 792/792/792 760/760/760 797/797/797 +f 792/792/792 797/797/797 798/798/798 +f 792/792/792 798/798/798 795/795/795 +f 795/795/795 799/799/799 796/796/796 +f 796/796/796 799/799/799 800/800/800 +f 796/796/796 800/800/800 794/794/794 +f 746/746/746 751/751/751 760/760/760 +f 795/795/795 798/798/798 799/799/799 +f 760/760/760 751/751/751 797/797/797 +f 797/797/797 785/785/785 798/798/798 +f 794/794/794 800/800/800 801/801/801 +f 798/798/798 785/785/785 786/786/786 +f 798/798/798 786/786/786 799/799/799 +f 797/797/797 751/751/751 784/784/784 +f 797/797/797 784/784/784 785/785/785 +f 799/799/799 786/786/786 802/802/802 +f 799/799/799 802/802/802 800/800/800 +f 800/800/800 802/802/802 803/803/803 +f 800/800/800 803/803/803 801/801/801 +f 803/803/803 804/804/804 801/801/801 +f 794/794/794 805/805/805 771/771/771 +f 801/801/801 805/805/805 794/794/794 +f 805/805/805 806/806/806 771/771/771 +f 771/771/771 806/806/806 772/772/772 +f 803/803/803 807/807/807 804/804/804 +f 804/804/804 808/808/808 801/801/801 +f 801/801/801 808/808/808 805/805/805 +f 807/807/807 809/809/809 804/804/804 +f 804/804/804 809/809/809 808/808/808 +f 808/808/808 810/810/810 805/805/805 +f 805/805/805 810/810/810 811/811/811 +f 805/805/805 811/811/811 806/806/806 +f 808/808/808 812/812/812 810/810/810 +f 811/811/811 813/813/813 806/806/806 +f 814/814/814 815/815/815 816/816/816 +f 814/814/814 816/816/816 817/817/817 +f 818/818/818 817/817/817 819/819/819 +f 818/818/818 819/819/819 820/820/820 +f 820/820/820 819/819/819 821/821/821 +f 817/817/817 816/816/816 822/822/822 +f 817/817/817 822/822/822 819/819/819 +f 735/735/735 722/722/722 741/741/741 +f 735/735/735 741/741/741 823/823/823 +f 823/823/823 777/777/777 824/824/824 +f 824/824/824 777/777/777 815/815/815 +f 819/819/819 822/822/822 825/825/825 +f 819/819/819 825/825/825 821/821/821 +f 826/826/826 821/821/821 775/775/775 +f 815/815/815 777/777/777 778/778/778 +f 815/815/815 778/778/778 816/816/816 +f 821/821/821 825/825/825 773/773/773 +f 821/821/821 773/773/773 775/775/775 +f 823/823/823 741/741/741 776/776/776 +f 823/823/823 776/776/776 777/777/777 +f 816/816/816 778/778/778 827/827/827 +f 816/816/816 827/827/827 822/822/822 +f 822/822/822 827/827/827 828/828/828 +f 822/822/822 828/828/828 825/825/825 +f 825/825/825 828/828/828 773/773/773 +f 807/807/807 829/829/829 809/809/809 +f 808/808/808 809/809/809 812/812/812 +f 810/810/810 812/812/812 830/830/830 +f 810/810/810 830/830/830 811/811/811 +f 811/811/811 830/830/830 813/813/813 +f 775/775/775 831/831/831 826/826/826 +f 826/826/826 831/831/831 832/832/832 +f 829/829/829 833/833/833 809/809/809 +f 809/809/809 833/833/833 834/834/834 +f 809/809/809 834/834/834 812/812/812 +f 830/830/830 835/835/835 813/813/813 +f 774/774/774 836/836/836 831/831/831 +f 774/774/774 831/831/831 775/775/775 +f 831/831/831 837/837/837 832/832/832 +f 829/829/829 838/838/838 833/833/833 +f 834/834/834 839/839/839 812/812/812 +f 812/812/812 839/839/839 830/830/830 +f 830/830/830 839/839/839 840/840/840 +f 830/830/830 840/840/840 835/835/835 +f 833/833/833 841/841/841 834/834/834 +f 834/834/834 841/841/841 839/839/839 +f 836/836/836 842/842/842 831/831/831 +f 831/831/831 842/842/842 837/837/837 +f 838/838/838 841/841/841 833/833/833 +f 840/840/840 843/843/843 835/835/835 +f 835/835/835 843/843/843 844/844/844 +f 836/836/836 845/845/845 842/842/842 +f 838/838/838 846/846/846 841/841/841 +f 839/839/839 841/841/841 847/847/847 +f 839/839/839 847/847/847 840/840/840 +f 840/840/840 847/847/847 843/843/843 +f 842/842/842 848/848/848 837/837/837 +f 846/846/846 849/849/849 841/841/841 +f 841/841/841 849/849/849 847/847/847 +f 844/844/844 843/843/843 850/850/850 +f 766/766/766 851/851/851 852/852/852 +f 851/851/851 853/853/853 854/854/854 +f 851/851/851 854/854/854 852/852/852 +f 845/845/845 855/855/855 856/856/856 +f 845/845/845 856/856/856 842/842/842 +f 842/842/842 856/856/856 848/848/848 +f 846/846/846 857/857/857 849/849/849 +f 847/847/847 858/858/858 843/843/843 +f 843/843/843 858/858/858 850/850/850 +f 859/859/859 860/860/860 853/853/853 +f 762/762/762 761/761/761 861/861/861 +f 861/861/861 862/862/862 859/859/859 +f 853/853/853 860/860/860 854/854/854 +f 733/733/733 753/753/753 787/787/787 +f 788/788/788 787/787/787 789/789/789 +f 763/763/763 790/790/790 863/863/863 +f 763/763/763 863/863/863 761/761/761 +f 859/859/859 862/862/862 860/860/860 +f 789/789/789 787/787/787 814/814/814 +f 789/789/789 814/814/814 790/790/790 +f 863/863/863 818/818/818 761/761/761 +f 761/761/761 820/820/820 861/861/861 +f 861/861/861 820/820/820 862/862/862 +f 860/860/860 862/862/862 832/832/832 +f 790/790/790 814/814/814 863/863/863 +f 761/761/761 818/818/818 820/820/820 +f 862/862/862 820/820/820 832/832/832 +f 860/860/860 832/832/832 837/837/837 +f 860/860/860 837/837/837 854/854/854 +f 854/854/854 837/837/837 852/852/852 +f 787/787/787 824/824/824 814/814/814 +f 852/852/852 837/837/837 848/848/848 +f 852/852/852 848/848/848 864/864/864 +f 753/753/753 735/735/735 823/823/823 +f 753/753/753 823/823/823 787/787/787 +f 787/787/787 823/823/823 824/824/824 +f 814/814/814 824/824/824 815/815/815 +f 863/863/863 814/814/814 817/817/817 +f 863/863/863 817/817/817 818/818/818 +f 820/820/820 821/821/821 832/832/832 +f 832/832/832 821/821/821 826/826/826 +f 849/849/849 865/865/865 847/847/847 +f 847/847/847 865/865/865 858/858/858 +f 856/856/856 866/866/866 848/848/848 +f 848/848/848 866/866/866 864/864/864 +f 852/852/852 864/864/864 764/764/764 +f 852/852/852 764/764/764 766/766/766 +f 769/769/769 768/768/768 867/867/867 +f 769/769/769 867/867/867 857/857/857 +f 857/857/857 867/867/867 849/849/849 +f 849/849/849 867/867/867 865/865/865 +f 858/858/858 865/865/865 868/868/868 +f 858/858/858 868/868/868 850/850/850 +f 850/850/850 868/868/868 869/869/869 +f 850/850/850 869/869/869 870/870/870 +f 871/871/871 870/870/870 872/872/872 +f 871/871/871 872/872/872 855/855/855 +f 855/855/855 872/872/872 856/856/856 +f 856/856/856 872/872/872 866/866/866 +f 765/765/765 764/764/764 767/767/767 +f 764/764/764 864/864/864 873/873/873 +f 764/764/764 873/873/873 767/767/767 +f 870/870/870 869/869/869 874/874/874 +f 870/870/870 874/874/874 872/872/872 +f 864/864/864 875/875/875 873/873/873 +f 767/767/767 873/873/873 757/757/757 +f 767/767/767 757/757/757 768/768/768 +f 768/768/768 757/757/757 756/756/756 +f 768/768/768 756/756/756 867/867/867 +f 865/865/865 867/867/867 759/759/759 +f 865/865/865 759/759/759 868/868/868 +f 868/868/868 759/759/759 869/869/869 +f 872/872/872 875/875/875 866/866/866 +f 866/866/866 875/875/875 864/864/864 +f 875/875/875 757/757/757 873/873/873 +f 867/867/867 756/756/756 759/759/759 +f 869/869/869 759/759/759 874/874/874 +f 874/874/874 759/759/759 758/758/758 +f 874/874/874 758/758/758 872/872/872 +f 872/872/872 758/758/758 875/875/875 +f 875/875/875 758/758/758 757/757/757 +f 846/846/846 876/876/876 857/857/857 +f 876/876/876 846/846/846 877/877/877 +f 877/877/877 846/846/846 838/838/838 +f 878/878/878 765/765/765 769/769/769 +f 878/878/878 769/769/769 876/876/876 +f 769/769/769 857/857/857 876/876/876 +f 878/878/878 766/766/766 765/765/765 +f 879/879/879 763/763/763 762/762/762 +f 880/880/880 696/696/696 673/673/673 +f 881/881/881 721/721/721 696/696/696 +f 881/881/881 696/696/696 880/880/880 +f 882/882/882 803/803/803 883/883/883 +f 877/877/877 838/838/838 829/829/829 +f 829/829/829 882/882/882 877/877/877 +f 861/861/861 884/884/884 762/762/762 +f 879/879/879 762/762/762 884/884/884 +f 733/733/733 885/885/885 728/728/728 +f 731/731/731 881/881/881 886/886/886 +f 786/786/786 784/784/784 886/886/886 +f 851/851/851 766/766/766 887/887/887 +f 887/887/887 766/766/766 878/878/878 +f 887/887/887 853/853/853 851/851/851 +f 853/853/853 887/887/887 859/859/859 +f 859/859/859 887/887/887 884/884/884 +f 884/884/884 861/861/861 859/859/859 +f 888/888/888 789/789/789 763/763/763 +f 888/888/888 763/763/763 879/879/879 +f 889/889/889 709/709/709 885/885/885 +f 885/885/885 709/709/709 728/728/728 +f 880/880/880 672/672/672 889/889/889 +f 889/889/889 672/672/672 709/709/709 +f 673/673/673 672/672/672 880/880/880 +f 881/881/881 731/731/731 721/721/721 +f 886/886/886 784/784/784 731/731/731 +f 890/890/890 786/786/786 886/886/886 +f 802/802/802 890/890/890 883/883/883 +f 882/882/882 807/807/807 803/803/803 +f 807/807/807 882/882/882 829/829/829 +f 890/890/890 802/802/802 786/786/786 +f 883/883/883 803/803/803 802/802/802 +f 888/888/888 788/788/788 789/789/789 +f 733/733/733 888/888/888 885/885/885 +f 733/733/733 788/788/788 888/888/888 +f 855/855/855 891/891/891 871/871/871 +f 892/892/892 870/870/870 871/871/871 +f 892/892/892 850/850/850 870/870/870 +f 893/893/893 850/850/850 892/892/892 +f 894/894/894 776/776/776 895/895/895 +f 895/895/895 776/776/776 740/740/740 +f 892/892/892 871/871/871 891/891/891 +f 893/893/893 844/844/844 850/850/850 +f 895/895/895 724/724/724 896/896/896 +f 896/896/896 724/724/724 706/706/706 +f 778/778/778 776/776/776 894/894/894 +f 897/897/897 827/827/827 778/778/778 +f 898/898/898 828/828/828 899/899/899 +f 891/891/891 845/845/845 836/836/836 +f 895/895/895 740/740/740 724/724/724 +f 897/897/897 778/778/778 894/894/894 +f 828/828/828 827/827/827 899/899/899 +f 899/899/899 827/827/827 897/897/897 +f 898/898/898 773/773/773 828/828/828 +f 900/900/900 835/835/835 893/893/893 +f 893/893/893 835/835/835 844/844/844 +f 772/772/772 900/900/900 901/901/901 +f 688/688/688 902/902/902 896/896/896 +f 896/896/896 706/706/706 693/693/693 +f 782/782/782 770/770/770 903/903/903 +f 904/904/904 727/727/727 730/730/730 +f 902/902/902 727/727/727 904/904/904 +f 896/896/896 683/683/683 688/688/688 +f 898/898/898 774/774/774 773/773/773 +f 891/891/891 836/836/836 898/898/898 +f 891/891/891 855/855/855 845/845/845 +f 772/772/772 806/806/806 900/900/900 +f 901/901/901 770/770/770 772/772/772 +f 903/903/903 779/779/779 781/781/781 +f 904/904/904 779/779/779 903/903/903 +f 904/904/904 730/730/730 779/779/779 +f 902/902/902 695/695/695 727/727/727 +f 898/898/898 836/836/836 774/774/774 +f 900/900/900 813/813/813 835/835/835 +f 781/781/781 782/782/782 903/903/903 +f 896/896/896 693/693/693 683/683/683 +f 900/900/900 806/806/806 813/813/813 +f 903/903/903 770/770/770 901/901/901 +f 902/902/902 688/688/688 695/695/695 +f 899/899/899 879/879/879 884/884/884 +f 899/899/899 884/884/884 898/898/898 +f 898/898/898 884/884/884 887/887/887 +f 898/898/898 887/887/887 891/891/891 +f 891/891/891 887/887/887 878/878/878 +f 891/891/891 878/878/878 892/892/892 +f 892/892/892 878/878/878 876/876/876 +f 892/892/892 876/876/876 893/893/893 +f 893/893/893 876/876/876 877/877/877 +f 893/893/893 877/877/877 900/900/900 +f 900/900/900 877/877/877 882/882/882 +f 900/900/900 882/882/882 901/901/901 +f 901/901/901 882/882/882 883/883/883 +f 901/901/901 883/883/883 890/890/890 +f 901/901/901 890/890/890 903/903/903 +f 903/903/903 890/890/890 886/886/886 +f 903/903/903 886/886/886 904/904/904 +f 904/904/904 886/886/886 881/881/881 +f 904/904/904 881/881/881 902/902/902 +f 902/902/902 881/881/881 880/880/880 +f 902/902/902 880/880/880 896/896/896 +f 896/896/896 880/880/880 889/889/889 +f 896/896/896 889/889/889 895/895/895 +f 895/895/895 889/889/889 885/885/885 +f 895/895/895 885/885/885 894/894/894 +f 894/894/894 885/885/885 888/888/888 +f 894/894/894 888/888/888 897/897/897 +f 897/897/897 888/888/888 879/879/879 +f 897/897/897 879/879/879 899/899/899 +f 905/905/905 906/906/906 907/907/907 +f 908/908/908 909/909/909 910/910/910 +f 911/911/911 912/912/912 913/913/913 +f 912/912/912 914/914/914 915/915/915 +f 916/916/916 917/917/917 918/918/918 +f 919/919/919 920/920/920 921/921/921 +f 922/922/922 923/923/923 924/924/924 +f 925/925/925 926/926/926 927/927/927 +f 922/922/922 921/921/921 923/923/923 +f 928/928/928 929/929/929 930/930/930 +f 931/931/931 932/932/932 929/929/929 +f 931/931/931 929/929/929 928/928/928 +f 928/928/928 930/930/930 933/933/933 +f 932/932/932 919/919/919 926/926/926 +f 922/922/922 924/924/924 934/934/934 +f 935/935/935 925/925/925 936/936/936 +f 937/937/937 938/938/938 939/939/939 +f 940/940/940 933/933/933 941/941/941 +f 919/919/919 921/921/921 922/922/922 +f 937/937/937 939/939/939 942/942/942 +f 942/942/942 939/939/939 943/943/943 +f 942/942/942 943/943/943 944/944/944 +f 944/944/944 943/943/943 945/945/945 +f 946/946/946 940/940/940 947/947/947 +f 947/947/947 940/940/940 941/941/941 +f 941/941/941 933/933/933 930/930/930 +f 924/924/924 948/948/948 934/934/934 +f 934/934/934 948/948/948 949/949/949 +f 934/934/934 949/949/949 950/950/950 +f 950/950/950 949/949/949 951/951/951 +f 952/952/952 951/951/951 949/949/949 +f 953/953/953 928/928/928 933/933/933 +f 953/953/953 933/933/933 940/940/940 +f 941/941/941 954/954/954 947/947/947 +f 930/930/930 955/955/955 941/941/941 +f 929/929/929 956/956/956 930/930/930 +f 941/941/941 955/955/955 957/957/957 +f 941/941/941 957/957/957 954/954/954 +f 930/930/930 956/956/956 958/958/958 +f 930/930/930 958/958/958 955/955/955 +f 951/951/951 959/959/959 960/960/960 +f 950/950/950 960/960/960 961/961/961 +f 960/960/960 950/950/950 951/951/951 +f 952/952/952 949/949/949 948/948/948 +f 947/947/947 962/962/962 946/946/946 +f 955/955/955 958/958/958 963/963/963 +f 955/955/955 963/963/963 957/957/957 +f 957/957/957 964/964/964 954/954/954 +f 965/965/965 956/956/956 929/929/929 +f 950/950/950 961/961/961 934/934/934 +f 934/934/934 961/961/961 922/922/922 +f 966/966/966 942/942/942 944/944/944 +f 956/956/956 965/965/965 958/958/958 +f 958/958/958 967/967/967 963/963/963 +f 968/968/968 964/964/964 957/957/957 +f 968/968/968 957/957/957 963/963/963 +f 960/960/960 959/959/959 969/969/969 +f 960/960/960 969/969/969 961/961/961 +f 970/970/970 952/952/952 948/948/948 +f 970/970/970 948/948/948 971/971/971 +f 970/970/970 972/972/972 952/952/952 +f 973/973/973 948/948/948 924/924/924 +f 973/973/973 924/924/924 923/923/923 +f 974/974/974 937/937/937 942/942/942 +f 953/953/953 940/940/940 975/975/975 +f 940/940/940 946/946/946 975/975/975 +f 965/965/965 976/976/976 958/958/958 +f 932/932/932 926/926/926 929/929/929 +f 958/958/958 976/976/976 967/967/967 +f 959/959/959 977/977/977 969/969/969 +f 922/922/922 926/926/926 919/919/919 +f 966/966/966 974/974/974 942/942/942 +f 978/978/978 966/966/966 944/944/944 +f 978/978/978 944/944/944 979/979/979 +f 962/962/962 980/980/980 946/946/946 +f 946/946/946 980/980/980 975/975/975 +f 932/932/932 931/931/931 920/920/920 +f 932/932/932 920/920/920 919/919/919 +f 959/959/959 981/981/981 982/982/982 +f 959/959/959 982/982/982 977/977/977 +f 922/922/922 927/927/927 926/926/926 +f 971/971/971 948/948/948 973/973/973 +f 923/923/923 920/920/920 938/938/938 +f 923/923/923 938/938/938 937/937/937 +f 962/962/962 983/983/983 980/980/980 +f 978/978/978 979/979/979 984/984/984 +f 969/969/969 977/977/977 985/985/985 +f 961/961/961 927/927/927 922/922/922 +f 986/986/986 987/987/987 972/972/972 +f 986/986/986 972/972/972 970/970/970 +f 988/988/988 970/970/970 971/971/971 +f 953/953/953 989/989/989 928/928/928 +f 990/990/990 991/991/991 968/968/968 +f 992/992/992 984/984/984 993/993/993 +f 961/961/961 969/969/969 994/994/994 +f 961/961/961 994/994/994 927/927/927 +f 988/988/988 986/986/986 970/970/970 +f 973/973/973 923/923/923 937/937/937 +f 973/973/973 937/937/937 974/974/974 +f 988/988/988 966/966/966 978/978/978 +f 986/986/986 978/978/978 984/984/984 +f 986/986/986 984/984/984 992/992/992 +f 992/992/992 993/993/993 995/995/995 +f 980/980/980 983/983/983 996/996/996 +f 997/997/997 968/968/968 963/963/963 +f 988/988/988 978/978/978 986/986/986 +f 971/971/971 974/974/974 966/966/966 +f 998/998/998 992/992/992 995/995/995 +f 981/981/981 999/999/999 1000/1000/1000 +f 981/981/981 1000/1000/1000 982/982/982 +f 977/977/977 982/982/982 985/985/985 +f 969/969/969 985/985/985 994/994/994 +f 992/992/992 998/998/998 987/987/987 +f 992/992/992 987/987/987 986/986/986 +f 966/966/966 988/988/988 971/971/971 +f 974/974/974 971/971/971 973/973/973 +f 920/920/920 923/923/923 921/921/921 +f 1001/1001/1001 998/998/998 995/995/995 +f 989/989/989 939/939/939 938/938/938 +f 938/938/938 920/920/920 931/931/931 +f 983/983/983 1002/1002/1002 1003/1003/1003 +f 975/975/975 980/980/980 1004/1004/1004 +f 953/953/953 975/975/975 989/989/989 +f 990/990/990 1005/1005/1005 991/991/991 +f 1006/1006/1006 944/944/944 945/945/945 +f 1007/1007/1007 1008/1008/1008 1009/1009/1009 +f 1010/1010/1010 1009/1009/1009 1011/1011/1011 +f 1012/1012/1012 1013/1013/1013 1014/1014/1014 +f 1012/1012/1012 1010/1010/1010 1011/1011/1011 +f 1007/1007/1007 1009/1009/1009 1010/1010/1010 +f 936/936/936 1015/1015/1015 935/935/935 +f 1016/1016/1016 1007/1007/1007 1010/1010/1010 +f 1016/1016/1016 1010/1010/1010 1017/1017/1017 +f 1017/1017/1017 1010/1010/1010 1012/1012/1012 +f 1018/1018/1018 1012/1012/1012 1014/1014/1014 +f 1018/1018/1018 1014/1014/1014 1015/1015/1015 +f 1018/1018/1018 1015/1015/1015 1019/1019/1019 +f 1019/1019/1019 1015/1015/1015 936/936/936 +f 1020/1020/1020 1021/1021/1021 1007/1007/1007 +f 1022/1022/1022 1017/1017/1017 1012/1012/1012 +f 1022/1022/1022 1012/1012/1012 1018/1018/1018 +f 1020/1020/1020 1007/1007/1007 1016/1016/1016 +f 1023/1023/1023 1022/1022/1022 1018/1018/1018 +f 1019/1019/1019 936/936/936 1024/1024/1024 +f 1025/1025/1025 1016/1016/1016 1017/1017/1017 +f 1025/1025/1025 1017/1017/1017 1022/1022/1022 +f 1024/1024/1024 925/925/925 927/927/927 +f 1026/1026/1026 1025/1025/1025 1022/1022/1022 +f 1026/1026/1026 1022/1022/1022 1023/1023/1023 +f 1023/1023/1023 1018/1018/1018 1019/1019/1019 +f 1027/1027/1027 1020/1020/1020 1016/1016/1016 +f 1027/1027/1027 1016/1016/1016 1025/1025/1025 +f 985/985/985 1019/1019/1019 1024/1024/1024 +f 1028/1028/1028 1020/1020/1020 1027/1027/1027 +f 982/982/982 1026/1026/1026 1023/1023/1023 +f 985/985/985 1023/1023/1023 1019/1019/1019 +f 994/994/994 1024/1024/1024 927/927/927 +f 999/999/999 1025/1025/1025 1026/1026/1026 +f 999/999/999 1026/1026/1026 1000/1000/1000 +f 982/982/982 1023/1023/1023 985/985/985 +f 994/994/994 985/985/985 1024/1024/1024 +f 1026/1026/1026 982/982/982 1000/1000/1000 +f 1025/1025/1025 999/999/999 1029/1029/1029 +f 1025/1025/1025 1029/1029/1029 1027/1027/1027 +f 1027/1027/1027 1029/1029/1029 1028/1028/1028 +f 1030/1030/1030 1028/1028/1028 1029/1029/1029 +f 936/936/936 925/925/925 1024/1024/1024 +f 1031/1031/1031 1032/1032/1032 1001/1001/1001 +f 1033/1033/1033 1031/1031/1031 1001/1001/1001 +f 1033/1033/1033 1001/1001/1001 995/995/995 +f 1034/1034/1034 1031/1031/1031 1033/1033/1033 +f 1035/1035/1035 1033/1033/1033 995/995/995 +f 1035/1035/1035 995/995/995 993/993/993 +f 1036/1036/1036 1034/1034/1034 1033/1033/1033 +f 1036/1036/1036 1033/1033/1033 1035/1035/1035 +f 1037/1037/1037 1035/1035/1035 993/993/993 +f 1037/1037/1037 993/993/993 984/984/984 +f 1038/1038/1038 1037/1037/1037 984/984/984 +f 1039/1039/1039 1034/1034/1034 1036/1036/1036 +f 1040/1040/1040 1036/1036/1036 1035/1035/1035 +f 1040/1040/1040 1035/1035/1035 1037/1037/1037 +f 1041/1041/1041 1040/1040/1040 1037/1037/1037 +f 1042/1042/1042 1036/1036/1036 1040/1040/1040 +f 1041/1041/1041 1037/1037/1037 1038/1038/1038 +f 1043/1043/1043 1038/1038/1038 979/979/979 +f 1043/1043/1043 979/979/979 1006/1006/1006 +f 1042/1042/1042 1039/1039/1039 1036/1036/1036 +f 1041/1041/1041 1038/1038/1038 1043/1043/1043 +f 1044/1044/1044 1039/1039/1039 1042/1042/1042 +f 1045/1045/1045 1040/1040/1040 1041/1041/1041 +f 1042/1042/1042 1040/1040/1040 1045/1045/1045 +f 1045/1045/1045 1041/1041/1041 1046/1046/1046 +f 1046/1046/1046 1041/1041/1041 1043/1043/1043 +f 1046/1046/1046 1043/1043/1043 1047/1047/1047 +f 1047/1047/1047 1043/1043/1043 1006/1006/1006 +f 1047/1047/1047 1006/1006/1006 945/945/945 +f 1048/1048/1048 1049/1049/1049 1044/1044/1044 +f 1048/1048/1048 1044/1044/1044 1042/1042/1042 +f 1050/1050/1050 1042/1042/1042 1045/1045/1045 +f 1051/1051/1051 945/945/945 943/943/943 +f 1050/1050/1050 1048/1048/1048 1042/1042/1042 +f 1050/1050/1050 1045/1045/1045 1052/1052/1052 +f 1052/1052/1052 1045/1045/1045 1046/1046/1046 +f 1053/1053/1053 1046/1046/1046 1047/1047/1047 +f 1054/1054/1054 1047/1047/1047 945/945/945 +f 1052/1052/1052 1046/1046/1046 1053/1053/1053 +f 1054/1054/1054 945/945/945 1051/1051/1051 +f 939/939/939 1051/1051/1051 943/943/943 +f 1055/1055/1055 1050/1050/1050 1052/1052/1052 +f 1054/1054/1054 1053/1053/1053 1047/1047/1047 +f 1056/1056/1056 1048/1048/1048 1050/1050/1050 +f 1057/1057/1057 1051/1051/1051 939/939/939 +f 1058/1058/1058 1048/1048/1048 1056/1056/1056 +f 1056/1056/1056 1050/1050/1050 1055/1055/1055 +f 1059/1059/1059 1052/1052/1052 1053/1053/1053 +f 1057/1057/1057 939/939/939 989/989/989 +f 1059/1059/1059 1055/1055/1055 1052/1052/1052 +f 1059/1059/1059 1053/1053/1053 1060/1060/1060 +f 1060/1060/1060 1053/1053/1053 1054/1054/1054 +f 1060/1060/1060 1054/1054/1054 1004/1004/1004 +f 1004/1004/1004 1054/1054/1054 1051/1051/1051 +f 1061/1061/1061 1056/1056/1056 1055/1055/1055 +f 1057/1057/1057 1004/1004/1004 1051/1051/1051 +f 916/916/916 1058/1058/1058 1056/1056/1056 +f 1062/1062/1062 1055/1055/1055 1059/1059/1059 +f 1062/1062/1062 1061/1061/1061 1055/1055/1055 +f 1062/1062/1062 1059/1059/1059 1003/1003/1003 +f 1003/1003/1003 1059/1059/1059 1060/1060/1060 +f 1061/1061/1061 916/916/916 1056/1056/1056 +f 996/996/996 1060/1060/1060 1004/1004/1004 +f 928/928/928 989/989/989 938/938/938 +f 996/996/996 1003/1003/1003 1060/1060/1060 +f 975/975/975 1004/1004/1004 1057/1057/1057 +f 975/975/975 1057/1057/1057 989/989/989 +f 928/928/928 938/938/938 931/931/931 +f 1061/1061/1061 1062/1062/1062 917/917/917 +f 1061/1061/1061 917/917/917 916/916/916 +f 1002/1002/1002 917/917/917 1062/1062/1062 +f 1002/1002/1002 1062/1062/1062 1003/1003/1003 +f 983/983/983 1003/1003/1003 996/996/996 +f 980/980/980 996/996/996 1004/1004/1004 +f 1038/1038/1038 984/984/984 979/979/979 +f 979/979/979 944/944/944 1006/1006/1006 +f 1028/1028/1028 1063/1063/1063 1020/1020/1020 +f 1034/1034/1034 1064/1064/1064 1031/1031/1031 +f 1020/1020/1020 1063/1063/1063 1021/1021/1021 +f 1007/1007/1007 1065/1065/1065 1008/1008/1008 +f 1058/1058/1058 1066/1066/1066 1048/1048/1048 +f 1044/1044/1044 1049/1049/1049 1039/1039/1039 +f 1039/1039/1039 1067/1067/1067 1034/1034/1034 +f 1064/1064/1064 1068/1068/1068 1031/1031/1031 +f 1030/1030/1030 1069/1069/1069 1070/1070/1070 +f 1030/1030/1030 1070/1070/1070 1028/1028/1028 +f 1007/1007/1007 1021/1021/1021 1065/1065/1065 +f 1034/1034/1034 1067/1067/1067 1064/1064/1064 +f 1031/1031/1031 1068/1068/1068 1032/1032/1032 +f 1032/1032/1032 1068/1068/1068 1071/1071/1071 +f 1028/1028/1028 1070/1070/1070 1063/1063/1063 +f 918/918/918 1072/1072/1072 916/916/916 +f 916/916/916 1072/1072/1072 1058/1058/1058 +f 1058/1058/1058 1072/1072/1072 1066/1066/1066 +f 1048/1048/1048 1066/1066/1066 1049/1049/1049 +f 1049/1049/1049 1073/1073/1073 1039/1039/1039 +f 1039/1039/1039 1073/1073/1073 1067/1067/1067 +f 1021/1021/1021 1063/1063/1063 1074/1074/1074 +f 1066/1066/1066 1073/1073/1073 1049/1049/1049 +f 1069/1069/1069 1075/1075/1075 1070/1070/1070 +f 1021/1021/1021 1074/1074/1074 1065/1065/1065 +f 1076/1076/1076 1077/1077/1077 918/918/918 +f 918/918/918 1077/1077/1077 1072/1072/1072 +f 1066/1066/1066 1078/1078/1078 1073/1073/1073 +f 1073/1073/1073 1079/1079/1079 1067/1067/1067 +f 1064/1064/1064 1080/1080/1080 1068/1068/1068 +f 1068/1068/1068 1080/1080/1080 1071/1071/1071 +f 908/908/908 1075/1075/1075 1069/1069/1069 +f 1075/1075/1075 1081/1081/1081 1070/1070/1070 +f 1070/1070/1070 1081/1081/1081 1063/1063/1063 +f 1063/1063/1063 1081/1081/1081 1074/1074/1074 +f 1076/1076/1076 1082/1082/1082 1077/1077/1077 +f 1077/1077/1077 1083/1083/1083 1072/1072/1072 +f 1072/1072/1072 1083/1083/1083 1066/1066/1066 +f 1066/1066/1066 1083/1083/1083 1078/1078/1078 +f 1073/1073/1073 1084/1084/1084 1079/1079/1079 +f 1067/1067/1067 1079/1079/1079 1085/1085/1085 +f 1067/1067/1067 1085/1085/1085 1064/1064/1064 +f 1064/1064/1064 1085/1085/1085 1080/1080/1080 +f 1074/1074/1074 1086/1086/1086 1065/1065/1065 +f 1080/1080/1080 1087/1087/1087 1071/1071/1071 +f 1071/1071/1071 1087/1087/1087 1088/1088/1088 +f 1089/1089/1089 1090/1090/1090 1091/1091/1091 +f 1090/1090/1090 1092/1092/1092 1093/1093/1093 +f 1090/1090/1090 1093/1093/1093 1091/1091/1091 +f 1094/1094/1094 1095/1095/1095 1005/1005/1005 +f 1094/1094/1094 1005/1005/1005 990/990/990 +f 990/990/990 968/968/968 997/997/997 +f 1096/1096/1096 1091/1091/1091 1093/1093/1093 +f 1097/1097/1097 1092/1092/1092 1098/1098/1098 +f 1098/1098/1098 1092/1092/1092 1095/1095/1095 +f 1098/1098/1098 1095/1095/1095 1094/1094/1094 +f 1099/1099/1099 990/990/990 997/997/997 +f 1097/1097/1097 1093/1093/1093 1092/1092/1092 +f 1100/1100/1100 990/990/990 1099/1099/1099 +f 1101/1101/1101 997/997/997 967/967/967 +f 1102/1102/1102 1098/1098/1098 1094/1094/1094 +f 1100/1100/1100 1094/1094/1094 990/990/990 +f 1101/1101/1101 1099/1099/1099 997/997/997 +f 1103/1103/1103 1096/1096/1096 1093/1093/1093 +f 1103/1103/1103 1093/1093/1093 1097/1097/1097 +f 1104/1104/1104 1097/1097/1097 1098/1098/1098 +f 1102/1102/1102 1094/1094/1094 1100/1100/1100 +f 1105/1105/1105 1100/1100/1100 1099/1099/1099 +f 1101/1101/1101 967/967/967 976/976/976 +f 1104/1104/1104 1103/1103/1103 1097/1097/1097 +f 1106/1106/1106 1104/1104/1104 1098/1098/1098 +f 1106/1106/1106 1098/1098/1098 1102/1102/1102 +f 1107/1107/1107 1102/1102/1102 1100/1100/1100 +f 1107/1107/1107 1100/1100/1100 1105/1105/1105 +f 1105/1105/1105 1099/1099/1099 1108/1108/1108 +f 1108/1108/1108 1099/1099/1099 1101/1101/1101 +f 1109/1109/1109 1102/1102/1102 1107/1107/1107 +f 1110/1110/1110 1107/1107/1107 1105/1105/1105 +f 935/935/935 1101/1101/1101 976/976/976 +f 1111/1111/1111 1103/1103/1103 1086/1086/1086 +f 1086/1086/1086 1103/1103/1103 1008/1008/1008 +f 1008/1008/1008 1103/1103/1103 1104/1104/1104 +f 1008/1008/1008 1104/1104/1104 1106/1106/1106 +f 1109/1109/1109 1106/1106/1106 1102/1102/1102 +f 1011/1011/1011 1109/1109/1109 1107/1107/1107 +f 1110/1110/1110 1105/1105/1105 1108/1108/1108 +f 935/935/935 1108/1108/1108 1101/1101/1101 +f 1009/1009/1009 1106/1106/1106 1109/1109/1109 +f 1013/1013/1013 1107/1107/1107 1110/1110/1110 +f 926/926/926 965/965/965 929/929/929 +f 1008/1008/1008 1106/1106/1106 1009/1009/1009 +f 1011/1011/1011 1107/1107/1107 1013/1013/1013 +f 1110/1110/1110 1108/1108/1108 1015/1015/1015 +f 1015/1015/1015 1108/1108/1108 935/935/935 +f 1065/1065/1065 1086/1086/1086 1008/1008/1008 +f 1009/1009/1009 1109/1109/1109 1011/1011/1011 +f 935/935/935 976/976/976 925/925/925 +f 925/925/925 976/976/976 965/965/965 +f 965/965/965 926/926/926 925/925/925 +f 1110/1110/1110 1015/1015/1015 1014/1014/1014 +f 1110/1110/1110 1014/1014/1014 1013/1013/1013 +f 1012/1012/1012 1011/1011/1011 1013/1013/1013 +f 1082/1082/1082 915/915/915 1112/1112/1112 +f 1082/1082/1082 1112/1112/1112 1077/1077/1077 +f 1078/1078/1078 1113/1113/1113 1073/1073/1073 +f 1073/1073/1073 1113/1113/1113 1084/1084/1084 +f 1083/1083/1083 1113/1113/1113 1078/1078/1078 +f 1085/1085/1085 1114/1114/1114 1080/1080/1080 +f 1080/1080/1080 1114/1114/1114 1087/1087/1087 +f 908/908/908 910/910/910 1075/1075/1075 +f 1075/1075/1075 1115/1115/1115 1081/1081/1081 +f 1081/1081/1081 1116/1116/1116 1074/1074/1074 +f 1074/1074/1074 1116/1116/1116 1117/1117/1117 +f 1074/1074/1074 1117/1117/1117 1086/1086/1086 +f 1086/1086/1086 1117/1117/1117 1111/1111/1111 +f 1103/1103/1103 1111/1111/1111 1096/1096/1096 +f 1091/1091/1091 1118/1118/1118 1089/1089/1089 +f 1089/1089/1089 1118/1118/1118 913/913/913 +f 1077/1077/1077 1119/1119/1119 1083/1083/1083 +f 1083/1083/1083 1119/1119/1119 1113/1113/1113 +f 1084/1084/1084 1113/1113/1113 1120/1120/1120 +f 1084/1084/1084 1120/1120/1120 1079/1079/1079 +f 1079/1079/1079 1121/1121/1121 1085/1085/1085 +f 1085/1085/1085 1121/1121/1121 1114/1114/1114 +f 1087/1087/1087 1122/1122/1122 1088/1088/1088 +f 1075/1075/1075 910/910/910 1115/1115/1115 +f 1081/1081/1081 1115/1115/1115 1116/1116/1116 +f 1096/1096/1096 1123/1123/1123 1091/1091/1091 +f 915/915/915 914/914/914 1112/1112/1112 +f 1077/1077/1077 1112/1112/1112 1119/1119/1119 +f 1079/1079/1079 1120/1120/1120 1121/1121/1121 +f 1087/1087/1087 1114/1114/1114 1122/1122/1122 +f 1122/1122/1122 1124/1124/1124 1088/1088/1088 +f 1091/1091/1091 1123/1123/1123 1125/1125/1125 +f 1091/1091/1091 1125/1125/1125 1118/1118/1118 +f 991/991/991 964/964/964 968/968/968 +f 997/997/997 963/963/963 967/967/967 +f 1111/1111/1111 1126/1126/1126 1096/1096/1096 +f 1096/1096/1096 1126/1126/1126 1123/1123/1123 +f 1118/1118/1118 1127/1127/1127 913/913/913 +f 913/913/913 1127/1127/1127 911/911/911 +f 912/912/912 911/911/911 914/914/914 +f 1119/1119/1119 1128/1128/1128 1113/1113/1113 +f 1113/1113/1113 1128/1128/1128 1120/1120/1120 +f 1122/1122/1122 1129/1129/1129 1124/1124/1124 +f 1117/1117/1117 1130/1130/1130 1126/1126/1126 +f 1117/1117/1117 1126/1126/1126 1111/1111/1111 +f 1125/1125/1125 1127/1127/1127 1118/1118/1118 +f 1112/1112/1112 1131/1131/1131 1119/1119/1119 +f 1120/1120/1120 1132/1132/1132 1121/1121/1121 +f 1121/1121/1121 1132/1132/1132 1114/1114/1114 +f 1122/1122/1122 1114/1114/1114 1129/1129/1129 +f 1124/1124/1124 1133/1133/1133 1134/1134/1134 +f 1134/1134/1134 1135/1135/1135 909/909/909 +f 909/909/909 1135/1135/1135 1136/1136/1136 +f 909/909/909 1136/1136/1136 910/910/910 +f 910/910/910 1136/1136/1136 1137/1137/1137 +f 910/910/910 1137/1137/1137 1115/1115/1115 +f 1115/1115/1115 1137/1137/1137 1138/1138/1138 +f 1115/1115/1115 1138/1138/1138 1116/1116/1116 +f 1116/1116/1116 1138/1138/1138 1117/1117/1117 +f 1117/1117/1117 1138/1138/1138 1130/1130/1130 +f 911/911/911 1139/1139/1139 914/914/914 +f 914/914/914 1139/1139/1139 1131/1131/1131 +f 914/914/914 1131/1131/1131 1112/1112/1112 +f 1119/1119/1119 1131/1131/1131 1140/1140/1140 +f 1119/1119/1119 1140/1140/1140 1128/1128/1128 +f 1128/1128/1128 1141/1141/1141 1120/1120/1120 +f 1124/1124/1124 1129/1129/1129 1133/1133/1133 +f 1134/1134/1134 1133/1133/1133 1135/1135/1135 +f 1126/1126/1126 1142/1142/1142 1123/1123/1123 +f 1123/1123/1123 1142/1142/1142 1125/1125/1125 +f 1125/1125/1125 1142/1142/1142 1127/1127/1127 +f 1128/1128/1128 1140/1140/1140 1141/1141/1141 +f 1120/1120/1120 1141/1141/1141 1132/1132/1132 +f 1114/1114/1114 1132/1132/1132 1143/1143/1143 +f 1114/1114/1114 1143/1143/1143 1129/1129/1129 +f 1127/1127/1127 1144/1144/1144 911/911/911 +f 911/911/911 1144/1144/1144 1139/1139/1139 +f 1139/1139/1139 1145/1145/1145 1131/1131/1131 +f 1129/1129/1129 1143/1143/1143 1146/1146/1146 +f 1129/1129/1129 1146/1146/1146 1133/1133/1133 +f 1136/1136/1136 1147/1147/1147 1137/1137/1137 +f 1137/1137/1137 1148/1148/1148 1138/1138/1138 +f 1138/1138/1138 1148/1148/1148 1130/1130/1130 +f 1130/1130/1130 1149/1149/1149 1126/1126/1126 +f 1126/1126/1126 1149/1149/1149 1142/1142/1142 +f 1131/1131/1131 1145/1145/1145 1140/1140/1140 +f 1140/1140/1140 1150/1150/1150 1141/1141/1141 +f 1141/1141/1141 1150/1150/1150 1132/1132/1132 +f 1132/1132/1132 1150/1150/1150 1151/1151/1151 +f 1137/1137/1137 1147/1147/1147 1148/1148/1148 +f 1142/1142/1142 1152/1152/1152 1127/1127/1127 +f 1127/1127/1127 1152/1152/1152 1144/1144/1144 +f 1144/1144/1144 1153/1153/1153 1139/1139/1139 +f 1139/1139/1139 1153/1153/1153 1145/1145/1145 +f 1140/1140/1140 1154/1154/1154 1150/1150/1150 +f 1132/1132/1132 1151/1151/1151 1143/1143/1143 +f 1133/1133/1133 1146/1146/1146 1155/1155/1155 +f 1133/1133/1133 1155/1155/1155 1135/1135/1135 +f 1135/1135/1135 1156/1156/1156 1136/1136/1136 +f 1136/1136/1136 1156/1156/1156 1147/1147/1147 +f 1148/1148/1148 1147/1147/1147 1157/1157/1157 +f 1148/1148/1148 1149/1149/1149 1130/1130/1130 +f 1142/1142/1142 1149/1149/1149 1152/1152/1152 +f 1144/1144/1144 1152/1152/1152 1158/1158/1158 +f 1144/1144/1144 1158/1158/1158 1153/1153/1153 +f 1145/1145/1145 1154/1154/1154 1140/1140/1140 +f 1135/1135/1135 1155/1155/1155 1156/1156/1156 +f 1148/1148/1148 1157/1157/1157 1159/1159/1159 +f 1148/1148/1148 1159/1159/1159 1149/1149/1149 +f 1153/1153/1153 1158/1158/1158 1160/1160/1160 +f 1153/1153/1153 1160/1160/1160 1145/1145/1145 +f 1145/1145/1145 1160/1160/1160 1154/1154/1154 +f 1151/1151/1151 1161/1161/1161 1143/1143/1143 +f 1143/1143/1143 1161/1161/1161 1162/1162/1162 +f 1143/1143/1143 1162/1162/1162 1146/1146/1146 +f 1146/1146/1146 1162/1162/1162 1155/1155/1155 +f 1147/1147/1147 1156/1156/1156 1157/1157/1157 +f 1160/1160/1160 1163/1163/1163 1154/1154/1154 +f 1154/1154/1154 1163/1163/1163 1150/1150/1150 +f 1150/1150/1150 1163/1163/1163 1161/1161/1161 +f 1150/1150/1150 1161/1161/1161 1151/1151/1151 +f 1159/1159/1159 1164/1164/1164 1149/1149/1149 +f 1149/1149/1149 1164/1164/1164 1152/1152/1152 +f 1152/1152/1152 1164/1164/1164 1158/1158/1158 +f 1156/1156/1156 1165/1165/1165 1157/1157/1157 +f 1157/1157/1157 1165/1165/1165 1159/1159/1159 +f 1162/1162/1162 907/907/907 1155/1155/1155 +f 1155/1155/1155 907/907/907 1156/1156/1156 +f 1156/1156/1156 907/907/907 1165/1165/1165 +f 1159/1159/1159 1165/1165/1165 1164/1164/1164 +f 1164/1164/1164 906/906/906 1158/1158/1158 +f 1158/1158/1158 906/906/906 905/905/905 +f 1158/1158/1158 905/905/905 1160/1160/1160 +f 1160/1160/1160 905/905/905 1163/1163/1163 +f 1163/1163/1163 905/905/905 1166/1166/1166 +f 1163/1163/1163 1166/1166/1166 1161/1161/1161 +f 1161/1161/1161 1166/1166/1166 1162/1162/1162 +f 1162/1162/1162 1166/1166/1166 907/907/907 +f 1165/1165/1165 906/906/906 1164/1164/1164 +f 1166/1166/1166 905/905/905 907/907/907 +f 1165/1165/1165 907/907/907 906/906/906 +f 951/951/951 952/952/952 1167/1167/1167 +f 1029/1029/1029 1168/1168/1168 1030/1030/1030 +f 1169/1169/1169 1069/1069/1069 1168/1168/1168 +f 1169/1169/1169 908/908/908 1069/1069/1069 +f 909/909/909 1170/1170/1170 1134/1134/1134 +f 1168/1168/1168 1069/1069/1069 1030/1030/1030 +f 908/908/908 1169/1169/1169 1170/1170/1170 +f 1088/1088/1088 1171/1171/1171 1071/1071/1071 +f 1071/1071/1071 1171/1171/1171 1172/1172/1172 +f 1071/1071/1071 1172/1172/1172 1032/1032/1032 +f 1173/1173/1173 951/951/951 1167/1167/1167 +f 959/959/959 1173/1173/1173 1174/1174/1174 +f 999/999/999 981/981/981 1174/1174/1174 +f 999/999/999 1174/1174/1174 1175/1175/1175 +f 1175/1175/1175 1168/1168/1168 1029/1029/1029 +f 909/909/909 908/908/908 1170/1170/1170 +f 1171/1171/1171 1088/1088/1088 1124/1124/1124 +f 1032/1032/1032 1172/1172/1172 1176/1176/1176 +f 1176/1176/1176 1001/1001/1001 1032/1032/1032 +f 998/998/998 1176/1176/1176 1177/1177/1177 +f 1177/1177/1177 987/987/987 998/998/998 +f 1173/1173/1173 959/959/959 951/951/951 +f 1174/1174/1174 981/981/981 959/959/959 +f 1176/1176/1176 998/998/998 1001/1001/1001 +f 972/972/972 987/987/987 1177/1177/1177 +f 1167/1167/1167 952/952/952 1178/1178/1178 +f 1175/1175/1175 1029/1029/1029 999/999/999 +f 1171/1171/1171 1124/1124/1124 1134/1134/1134 +f 1171/1171/1171 1134/1134/1134 1170/1170/1170 +f 972/972/972 1177/1177/1177 1178/1178/1178 +f 952/952/952 972/972/972 1178/1178/1178 +f 1179/1179/1179 1076/1076/1076 1180/1180/1180 +f 915/915/915 1179/1179/1179 1181/1181/1181 +f 1181/1181/1181 912/912/912 915/915/915 +f 1089/1089/1089 913/913/913 1182/1182/1182 +f 1183/1183/1183 1089/1089/1089 1182/1182/1182 +f 1179/1179/1179 1082/1082/1082 1076/1076/1076 +f 1179/1179/1179 915/915/915 1082/1082/1082 +f 1180/1180/1180 1076/1076/1076 918/918/918 +f 912/912/912 1181/1181/1181 1182/1182/1182 +f 1182/1182/1182 913/913/913 912/912/912 +f 1180/1180/1180 917/917/917 1184/1184/1184 +f 962/962/962 1185/1185/1185 983/983/983 +f 983/983/983 1185/1185/1185 1184/1184/1184 +f 1180/1180/1180 918/918/918 917/917/917 +f 1183/1183/1183 1090/1090/1090 1089/1089/1089 +f 991/991/991 1186/1186/1186 964/964/964 +f 983/983/983 1184/1184/1184 1002/1002/1002 +f 1092/1092/1092 1090/1090/1090 1183/1183/1183 +f 1092/1092/1092 1183/1183/1183 1187/1187/1187 +f 991/991/991 1188/1188/1188 1186/1186/1186 +f 947/947/947 1185/1185/1185 962/962/962 +f 1002/1002/1002 1184/1184/1184 917/917/917 +f 954/954/954 964/964/964 1186/1186/1186 +f 1187/1187/1187 1095/1095/1095 1092/1092/1092 +f 1095/1095/1095 1187/1187/1187 1188/1188/1188 +f 1188/1188/1188 1005/1005/1005 1095/1095/1095 +f 1188/1188/1188 991/991/991 1005/1005/1005 +f 1185/1185/1185 947/947/947 954/954/954 +f 1185/1185/1185 954/954/954 1186/1186/1186 +f 1189/1189/1189 1190/1190/1190 1191/1191/1191 +f 1191/1191/1191 1190/1190/1190 1192/1192/1192 +f 1191/1191/1191 1192/1192/1192 1193/1193/1193 +f 1193/1193/1193 1192/1192/1192 1194/1194/1194 +f 1194/1194/1194 1192/1192/1192 1195/1195/1195 +f 1194/1194/1194 1195/1195/1195 1196/1196/1196 +f 1194/1194/1194 1196/1196/1196 1197/1197/1197 +f 1197/1197/1197 1196/1196/1196 1198/1198/1198 +f 1197/1197/1197 1198/1198/1198 1199/1199/1199 +f 1199/1199/1199 1198/1198/1198 1200/1200/1200 +f 1200/1200/1200 1198/1198/1198 1201/1201/1201 +f 1200/1200/1200 1201/1201/1201 1202/1202/1202 +f 1202/1202/1202 1201/1201/1201 1203/1203/1203 +f 1202/1202/1202 1203/1203/1203 1204/1204/1204 +f 1204/1204/1204 1203/1203/1203 1205/1205/1205 +f 1204/1204/1204 1205/1205/1205 1206/1206/1206 +f 1206/1206/1206 1205/1205/1205 1207/1207/1207 +f 1207/1207/1207 1205/1205/1205 1208/1208/1208 +f 1207/1207/1207 1208/1208/1208 1209/1209/1209 +f 1209/1209/1209 1208/1208/1208 1210/1210/1210 +f 1209/1209/1209 1210/1210/1210 1211/1211/1211 +f 1211/1211/1211 1210/1210/1210 1212/1212/1212 +f 1211/1211/1211 1212/1212/1212 1213/1213/1213 +f 1213/1213/1213 1212/1212/1212 1214/1214/1214 +f 1213/1213/1213 1214/1214/1214 1215/1215/1215 +f 1215/1215/1215 1214/1214/1214 1189/1189/1189 +f 1189/1189/1189 1214/1214/1214 1190/1190/1190 +f 1187/1187/1187 1201/1201/1201 1188/1188/1188 +f 1201/1201/1201 1198/1198/1198 1188/1188/1188 +f 1188/1188/1188 1198/1198/1198 1186/1186/1186 +f 1186/1186/1186 1198/1198/1198 1196/1196/1196 +f 1186/1186/1186 1196/1196/1196 1185/1185/1185 +f 1185/1185/1185 1196/1196/1196 1195/1195/1195 +f 1195/1195/1195 1192/1192/1192 1185/1185/1185 +f 1185/1185/1185 1192/1192/1192 1184/1184/1184 +f 1192/1192/1192 1190/1190/1190 1184/1184/1184 +f 1184/1184/1184 1190/1190/1190 1214/1214/1214 +f 1184/1184/1184 1214/1214/1214 1180/1180/1180 +f 1180/1180/1180 1214/1214/1214 1212/1212/1212 +f 1180/1180/1180 1212/1212/1212 1179/1179/1179 +f 1179/1179/1179 1212/1212/1212 1181/1181/1181 +f 1181/1181/1181 1212/1212/1212 1210/1210/1210 +f 1210/1210/1210 1208/1208/1208 1181/1181/1181 +f 1181/1181/1181 1208/1208/1208 1182/1182/1182 +f 1182/1182/1182 1208/1208/1208 1205/1205/1205 +f 1182/1182/1182 1205/1205/1205 1183/1183/1183 +f 1205/1205/1205 1203/1203/1203 1183/1183/1183 +f 1183/1183/1183 1203/1203/1203 1187/1187/1187 +f 1187/1187/1187 1203/1203/1203 1201/1201/1201 +f 1176/1176/1176 1189/1189/1189 1177/1177/1177 +f 1177/1177/1177 1189/1189/1189 1191/1191/1191 +f 1177/1177/1177 1191/1191/1191 1178/1178/1178 +f 1191/1191/1191 1193/1193/1193 1178/1178/1178 +f 1178/1178/1178 1193/1193/1193 1194/1194/1194 +f 1178/1178/1178 1194/1194/1194 1167/1167/1167 +f 1167/1167/1167 1194/1194/1194 1197/1197/1197 +f 1167/1167/1167 1197/1197/1197 1173/1173/1173 +f 1173/1173/1173 1197/1197/1197 1199/1199/1199 +f 1173/1173/1173 1199/1199/1199 1174/1174/1174 +f 1174/1174/1174 1199/1199/1199 1200/1200/1200 +f 1174/1174/1174 1200/1200/1200 1175/1175/1175 +f 1200/1200/1200 1202/1202/1202 1175/1175/1175 +f 1175/1175/1175 1202/1202/1202 1168/1168/1168 +f 1202/1202/1202 1204/1204/1204 1168/1168/1168 +f 1168/1168/1168 1204/1204/1204 1206/1206/1206 +f 1168/1168/1168 1206/1206/1206 1169/1169/1169 +f 1169/1169/1169 1206/1206/1206 1170/1170/1170 +f 1170/1170/1170 1206/1206/1206 1207/1207/1207 +f 1207/1207/1207 1209/1209/1209 1170/1170/1170 +f 1170/1170/1170 1209/1209/1209 1171/1171/1171 +f 1209/1209/1209 1211/1211/1211 1171/1171/1171 +f 1171/1171/1171 1211/1211/1211 1172/1172/1172 +f 1172/1172/1172 1211/1211/1211 1213/1213/1213 +f 1172/1172/1172 1213/1213/1213 1176/1176/1176 +f 1213/1213/1213 1215/1215/1215 1176/1176/1176 +f 1176/1176/1176 1215/1215/1215 1189/1189/1189 +f 1216/1216/1216 1217/1217/1217 1218/1218/1218 +f 1218/1218/1218 1217/1217/1217 1219/1219/1219 +f 1218/1218/1218 1219/1219/1219 1220/1220/1220 +f 1220/1220/1220 1219/1219/1219 1221/1221/1221 +f 1220/1220/1220 1221/1221/1221 1222/1222/1222 +f 1222/1222/1222 1223/1223/1223 1224/1224/1224 +f 1222/1222/1222 1221/1221/1221 1223/1223/1223 +f 1217/1217/1217 1216/1216/1216 1225/1225/1225 +f 1224/1224/1224 1223/1223/1223 1226/1226/1226 +f 1227/1227/1227 1228/1228/1228 1229/1229/1229 +f 1230/1230/1230 1231/1231/1231 1232/1232/1232 +f 1232/1232/1232 1231/1231/1231 1233/1233/1233 +f 1232/1232/1232 1233/1233/1233 1234/1234/1234 +f 1234/1234/1234 1235/1235/1235 1236/1236/1236 +f 1234/1234/1234 1233/1233/1233 1235/1235/1235 +f 1236/1236/1236 1235/1235/1235 1228/1228/1228 +f 1236/1236/1236 1228/1228/1228 1227/1227/1227 +f 1237/1237/1237 1227/1227/1227 1229/1229/1229 +f 1238/1238/1238 1239/1239/1239 1240/1240/1240 +f 1240/1240/1240 1239/1239/1239 1241/1241/1241 +f 1240/1240/1240 1242/1242/1242 1243/1243/1243 +f 1244/1244/1244 1245/1245/1245 1239/1239/1239 +f 1240/1240/1240 1241/1241/1241 1246/1246/1246 +f 1239/1239/1239 1245/1245/1245 1241/1241/1241 +f 1242/1242/1242 1240/1240/1240 1247/1247/1247 +f 1248/1248/1248 1242/1242/1242 1247/1247/1247 +f 1247/1247/1247 1240/1240/1240 1246/1246/1246 +f 1249/1249/1249 1250/1250/1250 1251/1251/1251 +f 1252/1252/1252 1249/1249/1249 1253/1253/1253 +f 1254/1254/1254 1255/1255/1255 1256/1256/1256 +f 1255/1255/1255 1257/1257/1257 1258/1258/1258 +f 1257/1257/1257 1259/1259/1259 1258/1258/1258 +f 1259/1259/1259 1252/1252/1252 1258/1258/1258 +f 1252/1252/1252 1253/1253/1253 1258/1258/1258 +f 1254/1254/1254 1257/1257/1257 1255/1255/1255 +f 1249/1249/1249 1251/1251/1251 1253/1253/1253 +f 1260/1260/1260 1254/1254/1254 1256/1256/1256 +f 1261/1261/1261 1262/1262/1262 1263/1263/1263 +f 1261/1261/1261 1263/1263/1263 1264/1264/1264 +f 1264/1264/1264 1263/1263/1263 1265/1265/1265 +f 1264/1264/1264 1265/1265/1265 1266/1266/1266 +f 1266/1266/1266 1265/1265/1265 1267/1267/1267 +f 1266/1266/1266 1267/1267/1267 1268/1268/1268 +f 1268/1268/1268 1267/1267/1267 1269/1269/1269 +f 1268/1268/1268 1269/1269/1269 1270/1270/1270 +f 1270/1270/1270 1269/1269/1269 1271/1271/1271 +f 1270/1270/1270 1271/1271/1271 1272/1272/1272 +f 1272/1272/1272 1271/1271/1271 1273/1273/1273 +f 1272/1272/1272 1273/1273/1273 1274/1274/1274 +f 1274/1274/1274 1273/1273/1273 1275/1275/1275 +f 1274/1274/1274 1275/1275/1275 1276/1276/1276 +f 1276/1276/1276 1275/1275/1275 1277/1277/1277 +f 1276/1276/1276 1277/1277/1277 1278/1278/1278 +f 1278/1278/1278 1277/1277/1277 1279/1279/1279 +f 1278/1278/1278 1279/1279/1279 1280/1280/1280 +f 1280/1280/1280 1279/1279/1279 1281/1281/1281 +f 1280/1280/1280 1281/1281/1281 1282/1282/1282 +f 1282/1282/1282 1281/1281/1281 1283/1283/1283 +f 1282/1282/1282 1283/1283/1283 1284/1284/1284 +f 1284/1284/1284 1283/1283/1283 1285/1285/1285 +f 1284/1284/1284 1285/1285/1285 1286/1286/1286 +f 1284/1284/1284 1286/1286/1286 1287/1287/1287 +f 1287/1287/1287 1286/1286/1286 1288/1288/1288 +f 1287/1287/1287 1288/1288/1288 1289/1289/1289 +f 1289/1289/1289 1288/1288/1288 1290/1290/1290 +f 1289/1289/1289 1290/1290/1290 1291/1291/1291 +f 1291/1291/1291 1290/1290/1290 1292/1292/1292 +f 1292/1292/1292 1290/1290/1290 1262/1262/1262 +f 1292/1292/1292 1262/1262/1262 1261/1261/1261 +f 1260/1260/1260 1256/1256/1256 23/23/23 +f 28/28/28 1255/1255/1255 1258/1258/1258 +f 1254/1254/1254 1260/1260/1260 22/22/22 +f 23/23/23 1256/1256/1256 78/78/78 +f 78/78/78 1256/1256/1256 82/82/82 +f 1254/1254/1254 22/22/22 55/55/55 +f 82/82/82 1256/1256/1256 1255/1255/1255 +f 1254/1254/1254 55/55/55 1257/1257/1257 +f 82/82/82 1255/1255/1255 27/27/27 +f 1257/1257/1257 55/55/55 54/54/54 +f 1257/1257/1257 54/54/54 1259/1259/1259 +f 27/27/27 1255/1255/1255 28/28/28 +f 1259/1259/1259 54/54/54 32/32/32 +f 28/28/28 1258/1258/1258 49/49/49 +f 1259/1259/1259 32/32/32 1252/1252/1252 +f 52/52/52 49/49/49 1258/1258/1258 +f 1252/1252/1252 32/32/32 30/30/30 +f 1251/1251/1251 36/36/36 44/44/44 +f 1260/1260/1260 23/23/23 22/22/22 +f 1252/1252/1252 84/84/84 1249/1249/1249 +f 45/45/45 1249/1249/1249 84/84/84 +f 30/30/30 84/84/84 1252/1252/1252 +f 52/52/52 1258/1258/1258 1253/1253/1253 +f 44/44/44 52/52/52 1253/1253/1253 +f 1253/1253/1253 1251/1251/1251 44/44/44 +f 38/38/38 1250/1250/1250 45/45/45 +f 1251/1251/1251 1250/1250/1250 36/36/36 +f 1250/1250/1250 1249/1249/1249 45/45/45 +f 1250/1250/1250 38/38/38 36/36/36 +f 686/686/686 1234/1234/1234 687/687/687 +f 1233/1233/1233 718/718/718 684/684/684 +f 687/687/687 1234/1234/1234 1236/1236/1236 +f 1233/1233/1233 684/684/684 1235/1235/1235 +f 1231/1231/1231 1230/1230/1230 669/669/669 +f 1235/1235/1235 684/684/684 679/679/679 +f 687/687/687 1236/1236/1236 723/723/723 +f 686/686/686 1232/1232/1232 1234/1234/1234 +f 698/698/698 1227/1227/1227 1237/1237/1237 +f 1235/1235/1235 679/679/679 1228/1228/1228 +f 723/723/723 1227/1227/1227 698/698/698 +f 1228/1228/1228 679/679/679 748/748/748 +f 1237/1237/1237 677/677/677 676/676/676 +f 676/676/676 698/698/698 1237/1237/1237 +f 1228/1228/1228 748/748/748 1229/1229/1229 +f 748/748/748 742/742/742 1229/1229/1229 +f 1237/1237/1237 1229/1229/1229 677/677/677 +f 1231/1231/1231 669/669/669 682/682/682 +f 1276/1276/1276 1226/1226/1226 1223/1223/1223 +f 1276/1276/1276 1223/1223/1223 1274/1274/1274 +f 1274/1274/1274 1223/1223/1223 1272/1272/1272 +f 1272/1272/1272 1223/1223/1223 1221/1221/1221 +f 1272/1272/1272 1221/1221/1221 1270/1270/1270 +f 1270/1270/1270 1221/1221/1221 1219/1219/1219 +f 1270/1270/1270 1219/1219/1219 1268/1268/1268 +f 1268/1268/1268 1219/1219/1219 1266/1266/1266 +f 1266/1266/1266 1219/1219/1219 1217/1217/1217 +f 1266/1266/1266 1217/1217/1217 1264/1264/1264 +f 1264/1264/1264 1217/1217/1217 1225/1225/1225 +f 1264/1264/1264 1225/1225/1225 1261/1261/1261 +f 1261/1261/1261 1225/1225/1225 1216/1216/1216 +f 1261/1261/1261 1216/1216/1216 1292/1292/1292 +f 1292/1292/1292 1216/1216/1216 1291/1291/1291 +f 1291/1291/1291 1216/1216/1216 1218/1218/1218 +f 1291/1291/1291 1218/1218/1218 1289/1289/1289 +f 1289/1289/1289 1218/1218/1218 1287/1287/1287 +f 1287/1287/1287 1218/1218/1218 1220/1220/1220 +f 1287/1287/1287 1220/1220/1220 1284/1284/1284 +f 1284/1284/1284 1220/1220/1220 1222/1222/1222 +f 1284/1284/1284 1222/1222/1222 1282/1282/1282 +f 1282/1282/1282 1222/1222/1222 1280/1280/1280 +f 1280/1280/1280 1222/1222/1222 1224/1224/1224 +f 1280/1280/1280 1224/1224/1224 1278/1278/1278 +f 1278/1278/1278 1224/1224/1224 1226/1226/1226 +f 1278/1278/1278 1226/1226/1226 1276/1276/1276 +f 1262/1262/1262 1238/1238/1238 1240/1240/1240 +f 1262/1262/1262 1240/1240/1240 1263/1263/1263 +f 1263/1263/1263 1240/1240/1240 1243/1243/1243 +f 1263/1263/1263 1243/1243/1243 1265/1265/1265 +f 1265/1265/1265 1243/1243/1243 1242/1242/1242 +f 1265/1265/1265 1242/1242/1242 1267/1267/1267 +f 1267/1267/1267 1242/1242/1242 1269/1269/1269 +f 1269/1269/1269 1242/1242/1242 1248/1248/1248 +f 1269/1269/1269 1248/1248/1248 1271/1271/1271 +f 1271/1271/1271 1248/1248/1248 1247/1247/1247 +f 1271/1271/1271 1247/1247/1247 1273/1273/1273 +f 1273/1273/1273 1247/1247/1247 1275/1275/1275 +f 1275/1275/1275 1247/1247/1247 1246/1246/1246 +f 1275/1275/1275 1246/1246/1246 1277/1277/1277 +f 1277/1277/1277 1246/1246/1246 1241/1241/1241 +f 1277/1277/1277 1241/1241/1241 1279/1279/1279 +f 1279/1279/1279 1241/1241/1241 1281/1281/1281 +f 1281/1281/1281 1241/1241/1241 1245/1245/1245 +f 1281/1281/1281 1245/1245/1245 1283/1283/1283 +f 1283/1283/1283 1245/1245/1245 1244/1244/1244 +f 1283/1283/1283 1244/1244/1244 1285/1285/1285 +f 1285/1285/1285 1244/1244/1244 1286/1286/1286 +f 1286/1286/1286 1244/1244/1244 1239/1239/1239 +f 1286/1286/1286 1239/1239/1239 1288/1288/1288 +f 1288/1288/1288 1239/1239/1239 1290/1290/1290 +f 1290/1290/1290 1239/1239/1239 1238/1238/1238 +f 1290/1290/1290 1238/1238/1238 1262/1262/1262 +f 677/677/677 1229/1229/1229 742/742/742 +f 1230/1230/1230 1232/1232/1232 670/670/670 +f 669/669/669 1230/1230/1230 670/670/670 +f 1231/1231/1231 682/682/682 703/703/703 +f 670/670/670 1232/1232/1232 755/755/755 +f 723/723/723 1236/1236/1236 1227/1227/1227 +f 1231/1231/1231 703/703/703 1233/1233/1233 +f 1233/1233/1233 703/703/703 718/718/718 +f 755/755/755 1232/1232/1232 686/686/686 diff --git a/examples/Cassie/urdf/meshes/agility/foot-crank.obj b/examples/Cassie/urdf/meshes/agility/foot-crank.obj new file mode 100644 index 0000000000..1f58845f18 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/foot-crank.obj @@ -0,0 +1,2288 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o foot-crank +v 0.010112 0.006500 -0.012100 +v 0.013631 0.006500 -0.010024 +v 0.015140 0.006500 -0.014033 +v 0.011655 0.006500 -0.015195 +v 0.045881 0.009829 0.004350 +v 0.058340 0.009674 0.003165 +v 0.058320 0.009776 -0.002873 +v 0.010199 0.009850 -0.012440 +v 0.011151 0.009850 -0.014928 +v 0.007261 0.009862 -0.017347 +v 0.014829 0.009853 -0.014520 +v 0.017547 0.009850 -0.007428 +v 0.014904 0.009850 -0.011291 +v 0.011854 0.009850 -0.010143 +v 0.007184 0.009819 0.018008 +v 0.014211 0.009850 0.015182 +v 0.010320 0.009850 0.013934 +v 0.014583 0.009850 0.010591 +v 0.018888 0.009850 0.007083 +v 0.014979 0.009850 0.005865 +v -0.014673 0.009850 -0.004259 +v 0.016142 0.009850 0.002145 +v 0.024922 0.009841 -0.002128 +v 0.019642 0.009850 0.003271 +v 0.023921 0.009850 0.008141 +v 0.014698 0.009850 -0.004818 +v 0.016975 0.009850 -0.001961 +v 0.023760 0.009728 -0.008461 +v 0.020101 0.009850 -0.004259 +v -0.012382 0.009695 -0.015353 +v -0.005558 0.009850 -0.014676 +v -0.006936 0.009509 -0.019030 +v -0.002146 0.009850 -0.016551 +v -0.010239 0.009850 -0.013483 +v 0.004741 0.009850 -0.014532 +v 0.002113 0.009960 -0.018665 +v -0.003226 0.009649 -0.019677 +v 0.025909 0.009713 -0.010863 +v 0.045679 0.009820 -0.004959 +v 0.025482 0.009812 0.010659 +v 0.010970 0.009850 0.010748 +v -0.010040 0.009850 0.012887 +v -0.011691 0.009850 0.010335 +v 0.002539 0.009850 0.015386 +v 0.006452 0.009850 0.015493 +v -0.007319 0.009934 0.017050 +v -0.003503 0.009850 0.014710 +v -0.017273 0.009901 0.007318 +v -0.014710 0.009905 0.010934 +v -0.012712 0.009585 0.015460 +v -0.002333 0.009877 0.018559 +v 0.002815 0.009809 0.019199 +v -0.017103 0.009926 -0.007334 +v -0.011892 0.009850 -0.009935 +v -0.015242 0.009763 -0.012038 +v 0.058395 -0.002886 0.001583 +v 0.060941 -0.003150 -0.001941 +v 0.059731 -0.003150 0.004084 +v 0.054124 -0.002906 0.003515 +v 0.053668 -0.003072 0.006377 +v 0.056665 -0.002911 -0.003360 +v 0.056736 -0.003188 -0.005845 +v 0.052146 -0.002946 -0.002382 +v 0.051788 -0.003124 -0.005201 +v 0.051412 -0.002875 0.000623 +v 0.048546 -0.003174 -0.000656 +v 0.042186 0.003939 0.010004 +v 0.008658 0.004352 0.019841 +v 0.016932 0.004350 0.013583 +v 0.021852 0.004350 0.001363 +v 0.036187 0.004177 0.001313 +v 0.018555 0.004350 -0.011265 +v 0.010044 0.004349 -0.019303 +v 0.039204 0.004232 -0.010872 +v 0.000796 0.008033 0.021628 +v 0.002963 0.000853 0.021900 +v 0.016317 0.000850 0.014316 +v 0.022128 0.000850 0.000586 +v 0.015864 0.000850 -0.015091 +v 0.002194 0.000851 -0.021767 +v 0.001657 0.007707 -0.021533 +v -0.009686 0.007857 0.019190 +v -0.014615 0.000850 0.016616 +v -0.014810 0.008777 0.015014 +v -0.019442 0.008196 0.009242 +v -0.021430 0.000850 0.003368 +v -0.021306 0.008222 0.001557 +v -0.019698 0.000850 -0.009627 +v -0.020572 0.008560 -0.005243 +v -0.017562 0.008172 -0.012271 +v -0.011650 0.007907 -0.018061 +v -0.010489 0.000850 -0.018978 +v -0.005737 0.007387 -0.020753 +v -0.017214 0.006500 0.007322 +v -0.019810 0.009057 0.005769 +v -0.019754 0.006500 0.005747 +v -0.019279 0.006500 0.002756 +v -0.019195 0.009787 0.002801 +v -0.014887 0.006500 0.005402 +v -0.014767 0.009850 0.005046 +v -0.015780 0.006500 0.002497 +v -0.016318 0.009850 0.002187 +v -0.013463 0.006500 0.015444 +v -0.015341 0.006500 0.012070 +v -0.009875 0.006500 0.012794 +v -0.012654 0.006500 0.010081 +v -0.002294 0.006500 0.018954 +v -0.005419 0.009001 0.020027 +v -0.006206 0.006500 0.019580 +v -0.007009 0.006500 0.015800 +v -0.003271 0.006500 0.015131 +v 0.006858 0.006500 0.018950 +v 0.004746 0.009058 0.020067 +v 0.003524 0.006500 0.019839 +v 0.002078 0.006500 0.017360 +v 0.006723 0.006500 0.015732 +v 0.003590 0.006500 0.014915 +v 0.011423 0.006500 0.010316 +v 0.010314 0.006500 0.014031 +v 0.014712 0.006500 0.014883 +v 0.014622 0.006500 0.010935 +v 0.018500 0.006500 0.007218 +v 0.019801 0.006500 0.003355 +v 0.015865 0.006500 0.002300 +v 0.015058 0.006500 0.005918 +v 0.016200 0.006500 -0.002233 +v 0.019548 0.006500 -0.003052 +v 0.018698 0.006500 -0.007254 +v 0.014806 0.006500 -0.005429 +v 0.002071 0.006500 -0.018026 +v 0.004514 0.006500 -0.020072 +v 0.005706 0.009038 -0.019846 +v 0.007253 0.006500 -0.018068 +v 0.004573 0.006500 -0.014413 +v -0.003886 0.006500 -0.020080 +v -0.007214 0.006500 -0.018211 +v -0.002078 0.006500 -0.017360 +v -0.004745 0.006500 -0.014413 +v -0.015369 0.006500 -0.012196 +v -0.014067 0.009230 -0.015061 +v -0.013412 0.006500 -0.015446 +v -0.010228 0.006500 -0.013622 +v -0.011829 0.006500 -0.010018 +v -0.019887 0.009471 -0.003604 +v -0.018124 0.006500 -0.002161 +v -0.020155 0.006500 -0.005107 +v -0.016022 0.006500 -0.007228 +v -0.017245 0.009872 -0.002028 +v -0.015225 0.006500 -0.003052 +v 0.057162 0.007571 0.005588 +v 0.048665 0.000661 0.007974 +v 0.046786 0.001933 -0.008632 +v 0.058501 0.007656 -0.005057 +v 0.060812 0.008242 -0.001021 +v 0.060024 0.007766 0.003425 +v 0.042021 0.002240 0.001512 +v 0.046524 -0.000719 -0.000820 +v 0.026055 0.007407 0.008351 +v 0.044269 0.007535 0.003459 +v 0.026593 0.007565 -0.000062 +v 0.025716 0.007448 -0.008216 +v 0.044273 0.007624 -0.004157 +v 0.044259 0.008502 0.005160 +v 0.045361 0.008609 -0.002678 +v 0.026228 0.008408 0.010209 +v 0.024386 0.008625 0.008167 +v 0.026370 0.007950 -0.009665 +v 0.005195 0.009005 0.019447 +v 0.006975 0.008933 0.017818 +v 0.005627 0.009018 0.015476 +v 0.003079 0.008919 0.015641 +v 0.002739 0.008997 0.018524 +v 0.006172 0.006409 0.017382 +v 0.006284 0.006520 0.015982 +v 0.006512 0.006543 0.018959 +v 0.004060 0.006413 0.018754 +v 0.002789 0.006543 0.018939 +v 0.003434 0.006426 0.016660 +v 0.003300 0.006551 0.015423 +v 0.004621 0.007500 0.018277 +v 0.004800 0.007500 0.016203 +v -0.015115 0.008922 0.012549 +v -0.013498 0.008936 0.014879 +v -0.013884 0.008786 0.013051 +v -0.010949 0.009009 0.014077 +v -0.013095 0.009002 0.010642 +v -0.010983 0.008922 0.011149 +v -0.012961 0.006377 0.014273 +v -0.011131 0.006528 0.014564 +v -0.014872 0.006526 0.013878 +v -0.013926 0.006424 0.011928 +v -0.014107 0.006497 0.011059 +v -0.011185 0.006556 0.010853 +v -0.011345 0.006424 0.012325 +v -0.011937 0.007500 0.012316 +v -0.006149 0.008933 0.019313 +v -0.003156 0.008911 0.019109 +v -0.006634 0.009023 0.016520 +v -0.002418 0.008963 0.017174 +v -0.003394 0.006422 0.018115 +v -0.003020 0.006532 0.019295 +v -0.005385 0.006426 0.018611 +v -0.006568 0.006536 0.018695 +v -0.005924 0.006422 0.016658 +v -0.006213 0.006568 0.015523 +v -0.003932 0.006426 0.016162 +v -0.003051 0.006548 0.015725 +v -0.004011 0.008994 0.015286 +v -0.003607 0.007500 0.016862 +v -0.005711 0.007500 0.017912 +v -0.015318 0.008932 0.005779 +v -0.015680 0.008923 0.003142 +v -0.016224 0.008735 0.004957 +v -0.017827 0.009002 0.002575 +v -0.019436 0.008934 0.003721 +v -0.019207 0.009010 0.005673 +v -0.017772 0.008936 0.006910 +v -0.015985 0.006408 0.005128 +v -0.017999 0.006560 0.006886 +v -0.018577 0.006385 0.005666 +v -0.019733 0.006568 0.004674 +v -0.017451 0.006407 0.003148 +v -0.018310 0.006542 0.002609 +v -0.016034 0.006570 0.002785 +v -0.015229 0.006551 0.005680 +v -0.018277 0.007500 0.004621 +v 0.012584 0.008937 0.015118 +v 0.015115 0.008922 0.012907 +v 0.012226 0.009000 0.013791 +v 0.013940 0.008972 0.010924 +v 0.010555 0.008934 0.013327 +v 0.011432 0.008990 0.010858 +v 0.013919 0.006385 0.011721 +v 0.014957 0.006571 0.012120 +v 0.013601 0.006528 0.014999 +v 0.012792 0.006407 0.014239 +v 0.010256 0.006513 0.012869 +v 0.011326 0.006408 0.012258 +v 0.012765 0.006566 0.010381 +v 0.013442 0.007500 0.011773 +v 0.012249 0.007500 0.013480 +v 0.019569 0.008922 0.005643 +v 0.018758 0.009017 0.003081 +v 0.017729 0.009019 0.006683 +v 0.015380 0.009021 0.004240 +v 0.015537 0.008915 0.006056 +v 0.016777 0.008942 0.002423 +v 0.018115 0.006422 0.003394 +v 0.019401 0.006544 0.003449 +v 0.018664 0.006427 0.005195 +v 0.018537 0.006526 0.006802 +v 0.017221 0.006424 0.006072 +v 0.014988 0.006544 0.005253 +v 0.015941 0.006407 0.004264 +v 0.016779 0.006571 0.002430 +v 0.018035 0.007500 0.003678 +v 0.016738 0.007500 0.005639 +v 0.015318 0.008932 -0.005779 +v 0.016031 0.009003 -0.002945 +v 0.016224 0.008735 -0.004957 +v 0.018812 0.008939 -0.002736 +v 0.019342 0.009012 -0.005390 +v 0.017924 0.008925 -0.006913 +v 0.016725 0.006413 -0.005996 +v 0.016124 0.006547 -0.006596 +v 0.019275 0.006554 -0.006186 +v 0.018769 0.006424 -0.005062 +v 0.018772 0.006563 -0.002716 +v 0.017790 0.006424 -0.003276 +v 0.015301 0.006528 -0.003405 +v 0.016136 0.006430 -0.004046 +v 0.018277 0.007500 -0.004621 +v 0.014243 0.009000 -0.010990 +v 0.014638 0.008929 -0.014044 +v 0.012778 0.009017 -0.014798 +v 0.010646 0.008919 -0.013828 +v 0.011117 0.008994 -0.011233 +v 0.011196 0.006377 -0.012419 +v 0.010501 0.006560 -0.013340 +v 0.012349 0.006563 -0.014972 +v 0.013582 0.006392 -0.014012 +v 0.014665 0.006547 -0.013990 +v 0.013580 0.006424 -0.011567 +v 0.014602 0.006570 -0.011376 +v 0.011707 0.006551 -0.010570 +v 0.013518 0.007500 -0.013140 +v 0.011632 0.007500 -0.012258 +v 0.002902 0.009010 -0.016096 +v 0.005119 0.008923 -0.015150 +v 0.006720 0.008980 -0.016668 +v 0.003276 0.006424 -0.016984 +v 0.003051 0.006517 -0.019323 +v 0.004256 0.006424 -0.018769 +v 0.006596 0.006547 -0.018649 +v 0.006041 0.006424 -0.017790 +v 0.006273 0.006544 -0.015626 +v 0.005062 0.006424 -0.016004 +v 0.003122 0.006566 -0.015613 +v 0.006289 0.008997 -0.018889 +v 0.003103 0.008982 -0.019145 +v 0.003607 0.007500 -0.016862 +v 0.005711 0.007500 -0.017912 +v -0.005671 0.008999 -0.019404 +v -0.006870 0.008945 -0.016572 +v -0.004485 0.008996 -0.015203 +v -0.002956 0.008998 -0.018704 +v -0.002492 0.008923 -0.016667 +v -0.005924 0.006422 -0.018115 +v -0.006640 0.006499 -0.016990 +v -0.005967 0.006536 -0.019296 +v -0.003859 0.006424 -0.018584 +v -0.002771 0.006554 -0.018914 +v -0.003579 0.006413 -0.016356 +v -0.002926 0.006563 -0.015911 +v -0.005271 0.006560 -0.015160 +v -0.004621 0.007500 -0.018277 +v -0.004800 0.007500 -0.016203 +v -0.010589 0.008999 -0.013104 +v -0.012584 0.008937 -0.015118 +v -0.014867 0.009008 -0.013178 +v -0.013828 0.008919 -0.010646 +v -0.011545 0.009010 -0.010977 +v -0.013919 0.006385 -0.011721 +v -0.013668 0.006548 -0.010532 +v -0.014971 0.006548 -0.013289 +v -0.012792 0.006407 -0.014239 +v -0.012507 0.006551 -0.015105 +v -0.011326 0.006408 -0.012258 +v -0.010334 0.006546 -0.012114 +v -0.013709 0.007500 -0.013377 +v -0.011747 0.007500 -0.012079 +v -0.019474 0.008989 -0.005331 +v -0.018391 0.008955 -0.002484 +v -0.016290 0.009007 -0.002784 +v -0.015303 0.009005 -0.005116 +v -0.017243 0.008939 -0.007048 +v -0.018769 0.006424 -0.004256 +v -0.019168 0.006497 -0.003353 +v -0.019260 0.006570 -0.006011 +v -0.017451 0.006407 -0.006170 +v -0.016774 0.006560 -0.006886 +v -0.015985 0.006408 -0.004189 +v -0.015040 0.006557 -0.004645 +v -0.016779 0.006571 -0.002430 +v -0.016213 0.007500 -0.004587 +v -0.018560 0.007500 -0.004730 +v 0.059855 -0.015745 0.000714 +v 0.056740 -0.015760 -0.000579 +v 0.057468 -0.015697 -0.004239 +v 0.051237 -0.015757 0.002934 +v 0.055407 -0.015749 0.001924 +v 0.055933 -0.015763 0.004819 +v 0.055444 -0.015801 -0.001806 +v 0.053155 -0.015743 -0.004352 +v 0.053620 -0.015815 -0.001255 +v 0.050382 -0.015747 -0.001445 +v 0.053260 -0.015761 0.000585 +v 0.050731 -0.012675 0.002687 +v 0.056517 -0.012675 0.004901 +v 0.060040 -0.012675 -0.000192 +v 0.056136 -0.012675 -0.005003 +v 0.050826 -0.012675 -0.002695 +v 0.057466 -0.012675 0.002558 +v 0.057462 -0.012675 -0.002375 +v 0.052534 -0.012675 -0.002558 +v 0.052539 -0.012675 0.002375 +v 0.052136 0.003073 0.001708 +v 0.055533 0.003118 0.003061 +v 0.057850 0.003065 0.001528 +v 0.057772 0.003060 -0.001413 +v 0.055501 0.003048 -0.003197 +v 0.052574 0.003103 -0.001978 +v 0.054255 -0.014263 -0.001752 +v 0.055745 -0.014263 0.001752 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn -0.0000 1.0000 0.0000 +vn 0.0133 0.9994 0.0323 +vn 0.0163 0.9995 0.0269 +vn 0.1023 0.9457 -0.3084 +vn 0.0003 1.0000 0.0007 +vn -0.0000 1.0000 0.0050 +vn 0.0585 0.9776 -0.2023 +vn 0.0029 1.0000 -0.0047 +vn 0.0106 0.9999 -0.0055 +vn -0.0008 1.0000 0.0006 +vn 0.0001 1.0000 -0.0000 +vn 0.0953 0.9421 0.3215 +vn 0.0134 0.9991 0.0410 +vn -0.0087 1.0000 0.0009 +vn 0.0034 0.9999 0.0095 +vn 0.0003 1.0000 -0.0002 +vn 0.0042 1.0000 -0.0068 +vn 0.0005 1.0000 -0.0008 +vn 0.0032 1.0000 0.0039 +vn 0.0006 1.0000 0.0003 +vn 0.0135 0.9999 -0.0064 +vn 0.0084 0.9999 -0.0087 +vn -0.0158 0.9975 -0.0689 +vn -0.0048 0.9997 -0.0219 +vn -0.0154 0.9972 -0.0732 +vn -0.0172 0.9998 -0.0096 +vn -0.0080 0.9995 -0.0314 +vn -0.0017 1.0000 0.0055 +vn -0.0206 0.9997 0.0104 +vn -0.0492 0.9977 -0.0472 +vn -0.1517 0.8571 0.4923 +vn 0.0113 0.9999 -0.0022 +vn 0.0113 0.9999 0.0039 +vn 0.0054 0.9999 -0.0117 +vn -0.0079 0.9996 -0.0281 +vn -0.0001 1.0000 0.0004 +vn -0.0211 0.9998 0.0044 +vn 0.0023 1.0000 0.0088 +vn 0.0028 1.0000 0.0012 +vn 0.0047 1.0000 0.0045 +vn -0.0995 0.9747 0.2003 +vn 0.0013 1.0000 -0.0058 +vn -0.2691 0.9495 0.1612 +vn -0.1872 0.9735 0.1316 +vn -0.2987 0.8284 0.4738 +vn -0.0227 0.9670 0.2539 +vn 0.0112 0.9126 0.4087 +vn 0.0010 1.0000 -0.0077 +vn -0.0009 0.9997 -0.0241 +vn -0.0034 0.9993 -0.0360 +vn -0.0652 -0.9975 -0.0275 +vn -0.0860 -0.9958 0.0326 +vn -0.0701 -0.9956 -0.0629 +vn 0.0028 -0.9990 -0.0451 +vn 0.0114 -0.9979 -0.0639 +vn -0.0338 -0.9972 0.0664 +vn -0.0334 -0.9934 0.1098 +vn 0.0476 -0.9979 0.0447 +vn 0.0383 -0.9969 0.0683 +vn 0.0763 -0.9968 -0.0246 +vn 0.1017 -0.9948 0.0089 +vn -0.2313 -0.9667 0.1093 +vn -0.0200 -0.9995 -0.0261 +vn -0.0192 -0.9996 -0.0206 +vn -0.0122 -0.9999 -0.0056 +vn -0.1251 -0.9921 0.0029 +vn -0.0058 -1.0000 0.0046 +vn -0.0058 -1.0000 0.0063 +vn -0.1416 -0.9889 -0.0454 +vn 0.3765 -0.0186 0.9262 +vn 0.2747 0.1182 0.9542 +vn 0.3395 0.0010 0.9406 +vn 0.5827 -0.0077 0.8126 +vn 0.6021 0.0609 0.7961 +vn 0.9195 -0.0705 0.3866 +vn 0.9180 -0.0799 0.3885 +vn 0.9262 -0.0226 0.3764 +vn 0.9276 -0.0098 0.3735 +vn 0.9592 0.1312 -0.2504 +vn 0.9605 0.0627 -0.2711 +vn 0.9045 -0.2489 -0.3462 +vn 0.8874 -0.2947 -0.3546 +vn 0.6634 0.2578 -0.7025 +vn 0.3374 -0.0959 -0.9364 +vn 0.4139 -0.3319 -0.8477 +vn 0.0944 -0.0426 -0.9946 +vn 0.0981 0.0697 -0.9927 +vn -0.2495 -0.0770 0.9653 +vn -0.2262 -0.0171 0.9739 +vn -0.3784 -0.0252 0.9253 +vn -0.6497 -0.0117 0.7601 +vn -0.7111 0.1224 0.6923 +vn -0.9037 0.0244 0.4276 +vn -0.9883 -0.0242 0.1506 +vn -0.9105 0.4111 0.0436 +vn -0.8985 0.0097 -0.4388 +vn -0.9761 0.0218 -0.2164 +vn -0.7879 0.0422 -0.6143 +vn -0.5292 0.3367 -0.7789 +vn -0.5002 -0.0301 -0.8654 +vn -0.2371 0.2434 -0.9405 +vn 0.5192 0.0080 -0.8546 +vn 0.5227 0.0129 -0.8524 +vn 0.5228 0.0131 -0.8524 +vn 0.5269 0.0189 -0.8497 +vn 0.9841 -0.0047 0.1774 +vn 0.9874 0.0203 0.1568 +vn 0.9839 -0.0063 0.1788 +vn 0.9802 -0.0277 0.1963 +vn -0.6364 -0.0119 -0.7713 +vn -0.6553 -0.0347 -0.7545 +vn -0.6541 -0.0331 -0.7557 +vn -0.6713 -0.0545 -0.7392 +vn -0.9538 0.0653 0.2932 +vn -0.9191 -0.0215 0.3935 +vn -0.9231 -0.0133 0.3844 +vn -0.8749 -0.0966 0.4746 +vn 0.0734 0.1036 0.9919 +vn 0.1394 0.0448 0.9892 +vn 0.1360 0.0479 0.9896 +vn 0.2091 -0.0187 0.9777 +vn 0.2261 -0.0500 -0.9728 +vn 0.8041 0.3912 -0.4476 +vn 0.9811 -0.1914 -0.0289 +vn -0.5876 0.1472 -0.7956 +vn -0.6337 0.0820 -0.7692 +vn -0.6494 0.0580 -0.7582 +vn -0.6928 -0.0141 -0.7210 +vn -0.7683 0.0518 0.6380 +vn -0.8383 -0.0563 0.5423 +vn -0.7674 0.0530 0.6390 +vn -0.6912 0.1450 0.7080 +vn 0.1907 -0.1286 0.9732 +vn 0.5877 0.1560 0.7939 +vn -0.4010 -0.1110 -0.9093 +vn -0.3060 0.0260 -0.9517 +vn -0.2675 0.0778 -0.9604 +vn -0.1541 0.2206 -0.9631 +vn 0.8103 -0.1539 -0.5654 +vn 0.9146 -0.0016 -0.4045 +vn 0.9325 0.0376 -0.3592 +vn 0.9653 0.1618 -0.2051 +vn -0.9624 -0.0033 0.2715 +vn -0.9566 0.0229 0.2906 +vn -0.9636 -0.0091 0.2673 +vn -0.9682 -0.0360 0.2474 +vn 0.1746 0.1347 0.9754 +vn 0.5013 -0.2557 0.8267 +vn -0.6069 -0.1613 -0.7782 +vn -0.2522 0.2048 -0.9458 +vn 0.3762 -0.0976 -0.9214 +vn 0.8605 0.0873 -0.5019 +vn -0.9931 0.1094 0.0417 +vn -0.9855 0.0215 0.1683 +vn -0.9890 0.0398 0.1423 +vn -0.9587 -0.0577 0.2783 +vn -0.2520 0.0486 0.9665 +vn -0.1374 -0.0533 0.9891 +vn -0.1322 -0.0578 0.9895 +vn -0.0270 -0.1475 0.9887 +vn 0.8351 0.1894 0.5164 +vn 0.9813 -0.1780 -0.0729 +vn -0.0690 -0.0168 0.9975 +vn -0.0712 -0.0147 0.9974 +vn 0.0431 -0.1220 0.9916 +vn 0.9541 0.0923 0.2848 +vn 0.9677 0.0522 0.2467 +vn 0.9686 0.0492 0.2438 +vn 0.9798 0.0040 0.1999 +vn 0.2553 0.0350 -0.9662 +vn 0.3053 -0.0281 -0.9518 +vn 0.2373 0.0571 -0.9698 +vn 0.1889 0.1153 -0.9752 +vn -0.9953 -0.0885 -0.0391 +vn -0.9869 -0.1404 -0.0800 +vn -0.9973 -0.0691 -0.0240 +vn -0.9997 -0.0093 0.0228 +vn -0.1891 0.0981 0.9771 +vn -0.9433 0.0965 -0.3177 +vn -0.9638 0.0319 -0.2647 +vn -0.9678 0.0158 -0.2513 +vn -0.9797 -0.0514 -0.1938 +vn -0.2838 0.0361 0.9582 +vn -0.3062 0.0093 0.9519 +vn -0.2795 0.0412 0.9593 +vn -0.2583 0.0660 0.9638 +vn 0.9648 -0.0237 0.2621 +vn 0.9524 -0.0650 0.2978 +vn 0.9666 -0.0164 0.2556 +vn 0.9757 0.0265 0.2176 +vn 0.3533 -0.0065 -0.9355 +vn 0.3269 -0.0377 -0.9443 +vn 0.3217 -0.0439 -0.9458 +vn 0.2967 -0.0727 -0.9522 +vn -0.2355 0.1327 -0.9628 +vn -0.4234 -0.0303 -0.9055 +vn -0.4329 -0.0392 -0.9006 +vn -0.5816 -0.1891 -0.7912 +vn -0.9545 0.2271 0.1931 +vn -0.7580 -0.2287 0.6109 +vn 0.4169 0.1894 0.8890 +vn 0.5377 0.0618 0.8409 +vn 0.5667 0.0277 0.8235 +vn 0.6713 -0.1120 0.7327 +vn 0.9118 0.1019 -0.3977 +vn 0.8576 -0.0123 -0.5142 +vn 0.8537 -0.0188 -0.5204 +vn 0.7755 -0.1292 -0.6180 +vn 0.8906 0.0986 0.4440 +vn 0.9138 0.0561 0.4022 +vn 0.9110 0.0618 0.4078 +vn 0.9339 0.0120 0.3573 +vn 0.6523 0.0997 -0.7514 +vn 0.8087 -0.0801 -0.5827 +vn 0.6615 0.0909 -0.7444 +vn 0.4942 0.2324 -0.8377 +vn -0.3440 -0.2150 -0.9140 +vn -0.9136 0.2171 -0.3439 +vn -0.9791 0.0829 -0.1855 +vn -0.9819 0.0737 -0.1745 +vn -0.9958 -0.0890 0.0230 +vn -0.3145 0.1078 0.9431 +vn -0.2198 0.0117 0.9755 +vn -0.2086 0.0006 0.9780 +vn -0.1097 -0.0954 0.9894 +vn 0.6364 0.1326 0.7599 +vn 0.2577 -0.2051 0.9442 +vn -0.7272 0.0369 0.6854 +vn -0.7208 0.0452 0.6916 +vn -0.5784 0.2013 0.7905 +vn -0.8256 -0.1164 0.5521 +vn 0.8167 -0.1144 -0.5656 +vn 0.8276 -0.0920 -0.5537 +vn 0.8322 -0.0822 -0.5484 +vn 0.8415 -0.0613 -0.5367 +vn -0.7728 0.0671 -0.6311 +vn -0.7450 0.0137 -0.6669 +vn -0.7798 0.0819 -0.6206 +vn -0.7998 0.1277 -0.5865 +vn 0.3182 -0.0083 0.9480 +vn 0.3560 0.0350 0.9338 +vn 0.4809 0.1886 0.8563 +vn 0.1755 -0.1611 0.9712 +vn -0.8951 0.0017 0.4458 +vn -0.8964 -0.0007 0.4432 +vn -0.8284 0.1032 0.5506 +vn 0.9177 -0.0360 -0.3957 +vn 0.9440 -0.1650 -0.2858 +vn 0.8916 0.0357 -0.4515 +vn 0.8278 0.1586 -0.5381 +vn -0.6089 -0.0334 -0.7925 +vn -0.4735 -0.1826 -0.8617 +vn -0.6327 -0.0033 -0.7744 +vn -0.7336 0.1454 -0.6639 +vn -0.9386 -0.0989 0.3306 +vn 0.8991 0.0296 0.4368 +vn 0.8909 0.0490 0.4515 +vn 0.9275 -0.0540 0.3700 +vn 0.8492 0.1316 0.5114 +vn 0.1944 -0.0911 0.9767 +vn -0.5722 0.0575 0.8181 +vn -0.5758 0.0538 0.8158 +vn -0.4926 0.1338 0.8599 +vn 0.5279 0.0251 -0.8490 +vn 0.5312 0.0203 -0.8470 +vn 0.5269 0.0264 -0.8495 +vn 0.5238 0.0309 -0.8513 +vn -0.9139 -0.0071 -0.4060 +vn -0.9106 0.0026 -0.4133 +vn -0.9098 0.0048 -0.4149 +vn -0.9064 0.0145 -0.4223 +vn -0.6557 -0.0334 0.7542 +vn 0.7407 0.0780 -0.6673 +vn 0.6910 0.0602 -0.7203 +vn 0.8331 0.1880 -0.5203 +vn 0.8804 0.1485 -0.4505 +vn 0.4562 0.1649 0.8745 +vn 0.4543 0.1587 0.8766 +vn 0.4514 0.1495 0.8797 +vn 0.4582 0.1715 0.8722 +vn 0.5210 -0.1024 -0.8474 +vn -0.2919 0.1135 -0.9497 +vn -0.5027 -0.0389 -0.8636 +vn -0.4773 -0.0192 -0.8785 +vn -0.6474 -0.1617 -0.7448 +vn -0.9574 0.2236 0.1827 +vn -0.7674 -0.2235 0.6009 +vn 0.2768 0.0299 0.9605 +vn 0.3881 0.3300 0.8605 +vn 0.2880 -0.0236 0.9573 +vn 0.3204 -0.0350 0.9466 +vn 0.2851 0.0151 -0.9584 +vn 0.2791 0.0551 -0.9587 +vn 0.5141 0.2917 -0.8066 +vn 0.5024 -0.0190 -0.8644 +vn 0.7324 -0.0307 -0.6801 +vn 0.8635 0.0503 -0.5018 +vn 0.9815 -0.0115 0.1911 +vn 0.9847 -0.0029 0.1742 +vn 0.9834 -0.0064 0.1811 +vn 0.9803 -0.0144 0.1969 +vn 0.4058 -0.0309 0.9134 +vn 0.5715 0.2570 0.7793 +vn -0.1083 -0.6293 -0.7696 +vn -0.4430 -0.8759 -0.1912 +vn -0.3918 -0.9181 0.0594 +vn -0.6235 -0.7129 -0.3209 +vn -0.6203 -0.7376 0.2668 +vn -0.4795 -0.8340 0.2730 +vn -0.6082 -0.7193 -0.3359 +vn -0.6619 -0.5771 -0.4785 +vn -0.6639 -0.6799 0.3113 +vn -0.4806 -0.7989 0.3616 +vn -0.0020 0.9998 0.0186 +vn -0.0062 0.9999 0.0081 +vn 0.0018 1.0000 -0.0003 +vn -0.0391 0.9874 0.1535 +vn -0.0149 0.9996 0.0250 +vn -0.7957 0.5853 -0.1557 +vn -0.7720 0.6199 -0.1402 +vn -0.6918 0.6260 -0.3599 +vn -0.8705 0.4746 0.1306 +vn -0.8440 0.5342 0.0483 +vn -0.7508 0.6496 0.1197 +vn -0.2695 0.1380 -0.9531 +vn -0.2883 -0.2169 -0.9327 +vn -0.2882 -0.2063 -0.9351 +vn -0.2668 0.1627 -0.9499 +vn -0.1335 0.8776 -0.4604 +vn -0.1374 0.8618 -0.4883 +vn -0.1337 0.8766 -0.4622 +vn -0.1377 0.8607 -0.4901 +vn 0.8133 0.2981 -0.4997 +vn 0.7077 0.4643 -0.5324 +vn 0.7935 0.5737 -0.2031 +vn 0.6271 0.5952 -0.5024 +vn 0.5924 0.7833 -0.1886 +vn -0.0739 0.9522 0.2965 +vn -0.2464 0.4998 0.8304 +vn -0.2543 0.4729 0.8436 +vn -0.2472 0.4969 0.8319 +vn -0.2547 0.4714 0.8443 +vn 0.8162 0.5762 -0.0416 +vn 0.9304 0.3551 0.0904 +vn 0.7583 0.6343 -0.1504 +vn 0.7807 0.6095 -0.1378 +vn 0.7696 0.6366 0.0496 +vn 0.6274 0.5432 0.5579 +vn 0.6307 0.5668 0.5301 +vn 0.6310 0.5696 0.5267 +vn 0.6336 0.5965 0.4926 +vn 0.3694 0.6031 0.7070 +vn 0.5173 0.8557 0.0127 +vn 0.6573 0.7416 0.1344 +vn 0.5757 0.8154 0.0610 +vn 0.7212 0.6636 0.1989 +vn 0.6895 0.5475 -0.4743 +vn 0.2418 0.4974 -0.8331 +vn 0.1443 0.8604 0.4888 +vn 0.2844 0.2937 0.9126 +vn 0.2742 0.3706 0.8874 +vn -0.6137 0.7879 0.0502 +vn -0.8169 0.5474 0.1816 +vn -0.0319 0.8553 0.5172 +vn -0.0883 0.5930 -0.8004 +vn -0.2835 0.5482 -0.7869 +vn -0.5806 0.4723 -0.6632 +vn -0.2265 0.1397 0.9639 +vn 0.0128 0.7440 -0.6680 +vn -0.5091 0.7918 -0.3375 +vn -0.5152 0.8126 -0.2725 +vn -0.5203 0.8018 -0.2940 +vn -0.0012 0.7865 -0.6176 +vn 0.0353 0.7832 -0.6208 +vn -0.3922 0.6711 0.6291 +vn -0.3239 0.7305 0.6012 +vn -0.0092 0.8108 0.5852 +vn 0.0348 0.7928 0.6085 +vn -0.4827 0.8385 -0.2530 +vn -0.4943 0.8326 -0.2498 +vn -0.7541 0.6549 -0.0488 +vn -0.7305 0.6820 -0.0358 +vn -0.4439 0.8577 0.2597 +vn -0.4407 0.8581 0.2636 +vn -0.3098 0.8088 -0.4998 +vn -0.1296 0.9910 -0.0349 +vn -0.0569 0.9984 -0.0054 +vn -0.0485 0.9988 -0.0111 +vn -0.3962 0.8819 0.2556 +vn -0.2483 0.8282 0.5024 +vn -0.0059 1.0000 0.0037 +vn 0.0020 1.0000 -0.0088 +vn 0.0482 0.9988 0.0085 +vn -0.0409 0.9987 -0.0318 +vn 0.3619 -0.9322 0.0012 +vn 0.4855 -0.8737 -0.0304 +vn 0.0899 -0.9913 0.0958 +vn 0.0064 -0.8774 0.4797 +vn -0.0030 -0.8278 0.5610 +vn -0.0984 -0.9949 0.0232 +vn -0.1278 -0.9917 0.0147 +vn -0.2213 -0.9733 -0.0606 +vn -0.0566 -0.9939 -0.0943 +vn 0.0087 -0.9948 -0.1015 +vn -0.1429 -0.0641 0.9877 +vn -0.1871 -0.0198 0.9821 +vn -0.0053 -0.1971 0.9804 +vn 0.6643 0.2133 0.7164 +vn 0.9721 -0.2230 -0.0727 +vn 0.8616 0.1271 -0.4913 +vn 0.0746 -0.0490 -0.9960 +vn 0.1806 -0.1494 -0.9721 +vn 0.0562 -0.0316 -0.9979 +vn -0.0677 0.0852 -0.9941 +vn -0.9890 -0.0640 -0.1330 +vn -0.9865 -0.0789 -0.1436 +vn -0.9901 -0.0571 -0.1282 +vn -0.9925 -0.0398 -0.1160 +vn -0.3483 0.1494 0.9254 +vn -0.9026 0.4195 -0.0968 +vn -0.8963 0.4350 -0.0862 +vn -0.8997 0.4267 -0.0919 +vn -0.8905 0.4484 -0.0769 +vn 0.3009 0.5111 -0.8051 +vn 0.7245 -0.0662 0.6861 +vn 0.6259 0.7780 0.0540 +vn 0.0956 0.9948 0.0350 +vn -0.0067 0.9967 -0.0804 +vn 0.0814 0.9961 -0.0328 +vn -0.0509 0.9962 -0.0710 +vn 0.0647 0.9918 0.1101 +vn 0.0451 0.9985 -0.0302 +vn -0.1733 0.2805 0.9441 +vn -0.0804 -0.9967 0.0131 +vn -0.0946 -0.9955 0.0062 +vn -0.1644 -0.9860 -0.0282 +vn -0.1927 -0.9803 -0.0422 +vn 0.0139 -0.9960 -0.0878 +vn 0.4621 -0.8868 -0.0030 +vn 0.5545 -0.8321 -0.0143 +vn 0.1098 -0.9933 0.0356 +vn 0.0760 -0.9963 0.0390 +vn -0.8009 0.2263 0.5544 +vn -0.1723 -0.2924 0.9406 +vn 0.2918 0.1636 0.9424 +vn 0.9968 -0.0789 -0.0129 +vn 0.9970 -0.0761 -0.0151 +vn 0.9967 -0.0804 -0.0118 +vn 0.9964 -0.0839 -0.0091 +vn 0.2358 0.1008 -0.9666 +vn 0.0710 -0.0305 -0.9970 +vn 0.0725 -0.0294 -0.9969 +vn -0.0669 -0.1375 -0.9882 +vn -0.6813 0.1562 -0.7151 +vn -0.9386 -0.2351 -0.2523 +vn -0.8463 -0.0631 0.5289 +vn 0.1918 0.6895 -0.6984 +vn 0.5990 0.7560 0.2640 +vn 0.0094 0.9995 0.0306 +vn 0.0095 0.9995 0.0305 +vn 0.1903 -0.9815 0.0232 +vn 0.0758 -0.9930 0.0904 +vn -0.0616 -0.9707 0.2321 +vn -0.1143 -0.9910 0.0699 +vn -0.1894 -0.9800 -0.0615 +vn -0.0882 -0.9887 -0.1211 +vn 0.0475 -0.9867 -0.1557 +vn 0.1026 -0.9894 -0.1030 +vn -0.0786 -0.1098 0.9908 +vn -0.1629 -0.2195 0.9619 +vn -0.0336 -0.0513 0.9981 +vn 0.0684 0.0816 0.9943 +vn 0.9305 0.0811 0.3571 +vn 0.9819 -0.1065 0.1566 +vn 0.9827 -0.1207 0.1406 +vn 0.9687 -0.2482 -0.0095 +vn 0.7530 0.1820 -0.6323 +vn 0.0620 -0.1527 -0.9863 +vn -0.4057 0.2833 -0.8690 +vn -0.9998 -0.0171 0.0108 +vn -0.9860 -0.1238 -0.1116 +vn -0.9991 0.0104 0.0422 +vn -0.9767 0.1260 0.1737 +vn -0.6857 0.4324 0.5856 +vn 0.1098 -0.6335 -0.7659 +vn -0.3906 0.4844 -0.7828 +vn 0.2976 0.7298 0.6155 +vn 0.3000 0.7332 0.6102 +vn 0.2995 0.7326 0.6113 +vn 0.3021 0.7364 0.6054 +vn -0.0757 0.9938 -0.0813 +vn -0.0462 0.9949 0.0892 +vn -0.0833 0.9931 -0.0828 +vn -0.0644 0.9974 -0.0313 +vn 0.0213 0.9986 -0.0474 +vn 0.0190 0.9991 0.0377 +vn 0.0087 0.9944 0.1056 +vn 0.1414 -0.9895 0.0301 +vn -0.0212 -0.9868 0.1606 +vn -0.2299 -0.9559 0.1829 +vn -0.1471 -0.9890 -0.0144 +vn 0.0003 -0.9857 -0.1687 +vn -0.0794 -0.9894 -0.1212 +vn 0.1044 -0.9883 -0.1109 +vn 0.1354 -0.9883 0.0706 +vn -0.9800 0.1667 0.1085 +vn -0.7263 -0.0179 0.6872 +vn -0.7845 -0.0825 0.6147 +vn -0.7338 -0.0257 0.6789 +vn -0.6503 0.0545 0.7577 +vn 0.4071 -0.0367 0.9127 +vn 0.3986 -0.0473 0.9159 +vn 0.4094 -0.0337 0.9118 +vn 0.4184 -0.0221 0.9080 +vn 0.9898 0.0427 -0.1360 +vn 0.9800 -0.0252 -0.1976 +vn 0.9763 -0.0414 -0.2122 +vn 0.9581 -0.1036 -0.2671 +vn 0.2575 0.1070 -0.9603 +vn 0.1617 0.0341 -0.9862 +vn 0.1725 0.0422 -0.9841 +vn 0.0774 -0.0290 -0.9966 +vn -0.5799 0.1027 -0.8082 +vn -0.7311 -0.0272 -0.6818 +vn -0.7094 -0.0063 -0.7048 +vn -0.8178 -0.1237 -0.5620 +vn -0.1590 0.4965 -0.8533 +vn 0.8800 0.2694 0.3913 +vn -0.5160 0.7407 0.4303 +vn 0.0056 0.9989 0.0459 +vn 0.0315 0.9994 0.0148 +vn -0.0145 0.9992 0.0375 +vn 0.0294 0.9995 0.0078 +vn -0.0452 0.9988 0.0206 +vn -0.0416 0.9991 0.0079 +vn 0.1915 -0.9619 -0.1953 +vn 0.1852 -0.9824 -0.0240 +vn 0.1143 -0.9920 0.0544 +vn 0.0989 -0.9937 0.0529 +vn -0.2385 -0.8970 0.3722 +vn -0.2618 -0.8703 0.4172 +vn -0.1179 -0.9930 0.0084 +vn -0.1582 -0.9773 -0.1409 +vn -0.0072 -0.9876 -0.1569 +vn 0.6404 0.2342 0.7315 +vn 0.8878 -0.1986 0.4152 +vn 0.8562 0.1113 -0.5045 +vn 0.7461 -0.0155 -0.6657 +vn 0.7504 -0.0114 -0.6609 +vn 0.6167 -0.1258 -0.7770 +vn 0.0272 0.2074 -0.9779 +vn -0.6813 -0.2385 -0.6921 +vn -0.9288 0.1764 -0.3259 +vn -0.6605 -0.0600 0.7484 +vn -0.5965 -0.1573 0.7870 +vn -0.5716 -0.1913 0.7979 +vn -0.5180 -0.2589 0.8153 +vn 0.4637 0.8246 0.3241 +vn -0.0191 0.5044 0.8633 +vn -0.8542 0.0930 -0.5116 +vn -0.8377 0.0144 -0.5459 +vn -0.8472 0.0557 -0.5284 +vn -0.8185 -0.0530 -0.5720 +vn 0.9629 0.0689 -0.2609 +vn 0.0624 0.9979 0.0173 +vn -0.0655 0.9958 0.0638 +vn -0.0186 0.9982 -0.0577 +vn 0.0723 -0.9803 -0.1840 +vn 0.1215 -0.9901 -0.0696 +vn 0.2468 -0.9670 0.0640 +vn 0.0851 -0.9941 0.0680 +vn 0.0414 -0.9970 0.0647 +vn -0.2462 -0.7946 0.5549 +vn -0.0769 -0.9950 0.0638 +vn -0.1316 -0.9912 0.0105 +vn -0.2565 -0.9551 -0.1483 +vn -0.0463 -0.9880 -0.1473 +vn 0.9286 -0.2850 0.2377 +vn 0.9361 0.2004 -0.2889 +vn 0.3406 -0.0255 -0.9399 +vn 0.3615 -0.0446 -0.9313 +vn 0.3410 -0.0258 -0.9397 +vn 0.3153 -0.0025 -0.9490 +vn -0.8240 -0.0513 -0.5643 +vn -0.8444 -0.0023 -0.5357 +vn -0.8207 -0.0585 -0.5684 +vn -0.7895 -0.1211 -0.6017 +vn -0.9764 0.1937 0.0957 +vn -0.3503 -0.1512 0.9244 +vn -0.3918 -0.2125 0.8952 +vn -0.3378 -0.1332 0.9318 +vn -0.2729 -0.0426 0.9611 +vn 0.4901 0.1994 0.8485 +vn 0.3173 0.2125 0.9242 +vn 0.5205 0.7814 0.3443 +vn -0.7502 0.5562 -0.3575 +vn -0.9075 0.3304 -0.2594 +vn -0.8391 0.4463 -0.3110 +vn -0.6128 0.6784 -0.4053 +vn 0.7208 0.0061 -0.6931 +vn 0.0824 0.9948 0.0601 +vn 0.4588 0.8855 -0.0739 +vn 0.2383 0.9696 0.0549 +vn 0.0206 0.9993 0.0316 +vn -0.0237 0.9989 0.0393 +vn -0.0158 0.9990 -0.0424 +vn -0.0504 -0.9875 -0.1494 +vn -0.0907 -0.9874 -0.1297 +vn 0.1066 -0.9905 -0.0874 +vn 0.2342 -0.9722 0.0065 +vn 0.0978 -0.9879 0.1203 +vn 0.0005 -0.9752 0.2212 +vn -0.0948 -0.9938 0.0585 +vn -0.0996 -0.9948 0.0223 +vn 0.9856 -0.0443 0.1629 +vn 0.9840 -0.0543 0.1696 +vn 0.9772 -0.0890 0.1927 +vn 0.7116 0.1988 -0.6739 +vn 0.1262 -0.2244 -0.9663 +vn -0.3923 0.1766 -0.9027 +vn -0.9410 -0.2344 -0.2441 +vn -0.9439 0.2354 0.2316 +vn -0.1481 -0.0738 0.9862 +vn -0.1920 -0.1243 0.9735 +vn -0.1295 -0.0526 0.9902 +vn -0.0747 0.0097 0.9972 +vn 0.9895 -0.0155 0.1435 +vn 0.0912 0.3997 0.9121 +vn -0.5940 0.0093 -0.8044 +vn 0.5220 0.8506 -0.0632 +vn 0.0538 0.9984 -0.0163 +vn -0.0545 0.9983 -0.0190 +vn -0.0883 -0.9898 -0.1120 +vn -0.1030 -0.9876 -0.1185 +vn -0.0420 -0.9895 -0.1381 +vn 0.0942 -0.9784 -0.1840 +vn 0.1422 -0.9879 -0.0616 +vn 0.0879 -0.9835 0.1579 +vn 0.1263 -0.9888 0.0800 +vn -0.0010 -0.9922 0.1245 +vn -0.0154 -0.9951 0.0979 +vn -0.5095 -0.8321 0.2191 +vn 0.3831 -0.0083 -0.9237 +vn 0.3902 -0.0164 -0.9206 +vn 0.3838 -0.0091 -0.9234 +vn 0.3757 0.0000 -0.9267 +vn -0.4154 0.1364 -0.8993 +vn -0.5487 0.0093 -0.8360 +vn -0.5452 0.0129 -0.8382 +vn -0.6576 -0.1137 -0.7448 +vn -0.9798 0.0964 0.1751 +vn -0.9586 -0.0039 0.2847 +vn -0.9525 -0.0219 0.3038 +vn -0.9112 -0.1125 0.3963 +vn -0.0756 0.2441 0.9668 +vn 0.0724 0.0953 0.9928 +vn 0.1183 0.0476 0.9918 +vn 0.2672 -0.1126 0.9570 +vn 0.9940 0.0817 0.0730 +vn 0.9895 0.1426 0.0226 +vn 0.9941 0.0693 0.0832 +vn 0.9917 0.0141 0.1279 +vn 0.6694 0.6722 0.3162 +vn 0.3826 -0.4294 0.8181 +vn -0.9316 -0.0630 0.3581 +vn 0.0621 0.5791 -0.8129 +vn -0.1000 0.7381 -0.6672 +vn -0.0730 0.7149 -0.6954 +vn -0.2346 0.8326 -0.5017 +vn 0.0160 0.9984 0.0544 +vn -0.0615 -0.9975 -0.0337 +vn -0.0368 -0.9955 -0.0871 +vn 0.0244 -0.9796 -0.1993 +vn 0.1160 -0.9896 -0.0848 +vn 0.1648 -0.9862 -0.0172 +vn 0.0901 -0.9913 0.0960 +vn 0.0138 -0.9782 0.2073 +vn -0.0466 -0.9906 0.1284 +vn -0.0532 -0.9939 0.0970 +vn -0.5663 -0.8239 0.0217 +vn 0.1468 -0.0186 -0.9890 +vn 0.1869 -0.0726 -0.9797 +vn 0.1250 0.0104 -0.9921 +vn 0.0796 0.0701 -0.9944 +vn -0.9975 0.0258 -0.0660 +vn -0.9993 -0.0227 -0.0286 +vn -0.9989 -0.0446 -0.0117 +vn -0.9961 -0.0857 0.0202 +vn -0.3834 0.1457 0.9120 +vn 0.0027 -0.1949 0.9808 +vn 0.6730 0.1831 0.7167 +vn 0.9992 -0.0277 -0.0285 +vn 0.9851 -0.1358 0.1051 +vn 0.9992 -0.0236 -0.0335 +vn 0.9765 0.1039 -0.1887 +vn 0.9154 0.3986 0.0567 +vn -0.0688 0.5637 0.8231 +vn 0.2443 0.8371 0.4895 +vn -0.8755 0.4511 0.1733 +vn -0.1328 0.3984 -0.9076 +vn -0.2437 0.6112 -0.7530 +vn -0.1903 0.5103 -0.8387 +vn -0.3070 0.7263 -0.6151 +vn -0.0260 0.9996 0.0081 +vn 0.0545 0.9982 0.0244 +vn -0.1613 -0.9829 -0.0890 +vn -0.2373 -0.9677 -0.0848 +vn -0.0548 -0.9920 -0.1141 +vn 0.0581 -0.9863 -0.1547 +vn 0.1101 -0.9910 -0.0765 +vn 0.1108 -0.9889 0.0994 +vn 0.1488 -0.9824 0.1128 +vn -0.0227 -0.9957 0.0902 +vn -0.0413 -0.9971 0.0641 +vn 0.1733 0.0082 -0.9848 +vn 0.1898 0.0284 -0.9814 +vn 0.1188 -0.0577 -0.9912 +vn -0.9411 0.0406 -0.3357 +vn -0.9553 0.1027 -0.2772 +vn -0.9389 0.0331 -0.3426 +vn -0.9206 -0.0199 -0.3901 +vn -0.7855 -0.1753 0.5935 +vn -0.4930 0.1741 0.8524 +vn 0.4582 0.0351 0.8882 +vn 0.3041 -0.0814 0.9492 +vn 0.4523 0.0305 0.8913 +vn 0.5891 0.1462 0.7947 +vn 0.9963 -0.0515 -0.0694 +vn 0.9850 -0.1647 0.0513 +vn 0.9962 -0.0479 -0.0731 +vn 0.9716 0.0923 -0.2179 +vn 0.2484 0.1016 -0.9633 +vn 0.8710 0.4255 -0.2456 +vn 0.9625 -0.2582 0.0831 +vn -0.2183 0.4841 0.8473 +vn -0.8325 0.4182 -0.3634 +vn -0.7663 0.6109 -0.1991 +vn -0.8024 0.5300 -0.2742 +vn -0.6759 0.7347 -0.0583 +vn 0.0027 0.9994 -0.0334 +vn -0.0328 0.9983 0.0485 +vn -0.2458 -0.9587 0.1434 +vn -0.0386 -0.9869 0.1569 +vn -0.1308 -0.9905 -0.0433 +vn -0.0158 -0.9888 -0.1484 +vn 0.0306 -0.9876 -0.1541 +vn 0.1219 -0.9907 0.0602 +vn 0.1336 -0.9906 0.0291 +vn -0.6164 0.0131 -0.7873 +vn -0.5931 -0.0235 -0.8048 +vn -0.6238 0.0252 -0.7812 +vn -0.6452 0.0616 -0.7615 +vn -0.9135 -0.0076 0.4069 +vn -0.9039 0.0189 0.4272 +vn -0.9158 -0.0147 0.4014 +vn -0.9248 -0.0442 0.3779 +vn 0.1410 0.0570 0.9884 +vn 0.2940 -0.0814 0.9523 +vn 0.3165 -0.1025 0.9430 +vn 0.4198 -0.2020 0.8849 +vn 0.8833 0.2515 0.3957 +vn 0.7713 -0.0891 -0.6302 +vn 0.7996 -0.1514 -0.5812 +vn 0.7559 -0.0592 -0.6521 +vn 0.7100 0.0191 -0.7039 +vn 0.4870 0.4710 -0.7355 +vn 0.4867 0.4714 -0.7355 +vn 0.4869 0.4712 -0.7355 +vn 0.4865 0.4716 -0.7354 +vn -0.0174 -0.1439 0.9894 +vn -0.3908 0.7059 0.5908 +vn -0.8395 0.3891 -0.3793 +vn -0.0218 0.9996 0.0202 +vn -0.0022 0.9995 -0.0319 +vn -0.1882 -0.9817 -0.0290 +vn -0.2216 -0.9749 -0.0191 +vn -0.1140 -0.9897 -0.0872 +vn -0.0266 -0.9812 -0.1909 +vn 0.0618 -0.9869 -0.1493 +vn 0.1586 -0.9841 0.0806 +vn 0.1489 -0.9887 -0.0145 +vn 0.0298 -0.9940 0.1056 +vn -0.0041 -0.9959 0.0904 +vn -0.9807 0.0327 0.1929 +vn -0.9948 -0.0969 0.0318 +vn -0.9758 0.0494 0.2131 +vn -0.9209 0.1666 0.3523 +vn -0.3463 -0.2135 0.9135 +vn 0.1376 0.1153 0.9837 +vn 0.8552 0.0441 0.5164 +vn 0.7845 -0.0679 0.6164 +vn 0.8607 0.0547 0.5061 +vn 0.9073 0.1713 0.3839 +vn 0.7532 0.0227 -0.6574 +vn 0.7904 -0.0328 -0.6117 +vn 0.7458 0.0329 -0.6653 +vn 0.7012 0.0901 -0.7072 +vn -0.4694 0.0132 -0.8829 +vn -0.3297 -0.1287 -0.9353 +vn -0.4877 0.0333 -0.8724 +vn -0.5990 0.1672 -0.7831 +vn -0.8491 0.3870 -0.3597 +vn 0.0390 0.7675 -0.6398 +vn 0.6230 0.0679 -0.7793 +vn -0.0494 0.3577 0.9325 +vn -0.0538 0.3496 0.9353 +vn -0.0511 0.3546 0.9336 +vn -0.0571 0.3433 0.9375 +vn 0.0049 -1.0000 -0.0051 +vn 0.0145 -0.9999 -0.0059 +vn 0.0184 -0.9996 -0.0216 +vn -0.0005 -1.0000 -0.0009 +vn 0.0010 -1.0000 -0.0015 +vn 0.0002 -1.0000 -0.0049 +vn 0.0198 -0.9996 -0.0212 +vn -0.0036 -0.9997 -0.0256 +vn -0.0138 -0.9999 -0.0059 +vn -0.0149 -0.9999 -0.0022 +vn -0.0061 -1.0000 0.0078 +vn -0.3669 0.0239 0.9299 +vn -0.3725 0.0132 0.9280 +vn -0.3615 0.0343 0.9317 +vn -0.3571 0.0427 0.9331 +vn 0.7546 -0.0694 0.6525 +vn 0.7148 -0.1533 0.6823 +vn 0.7954 0.0400 0.6048 +vn 0.8167 0.1175 0.5649 +vn 0.8639 -0.0668 -0.4992 +vn 0.8855 -0.1798 -0.4285 +vn 0.8142 0.0776 -0.5754 +vn 0.7638 0.1800 -0.6198 +vn 0.0280 -0.2334 -0.9720 +vn -0.3914 0.1892 -0.9005 +vn -0.7125 -0.1737 -0.6799 +vn -0.9905 0.1361 -0.0175 +vn -0.9977 0.0440 0.0516 +vn -0.9931 -0.0372 0.1115 +vn -0.9713 -0.1443 0.1893 +vn -0.3702 0.0299 0.9285 +vn -0.0851 -0.0271 0.9960 +vn -0.3117 0.0178 0.9500 +vn -0.0371 -0.0363 0.9987 +vn 0.5520 0.0410 0.8328 +vn 0.9996 -0.0193 -0.0216 +vn 0.9997 -0.0244 -0.0008 +vn 0.9997 -0.0237 -0.0039 +vn 0.9995 -0.0181 -0.0265 +vn 0.6172 0.0359 -0.7860 +vn -0.3117 0.0202 -0.9500 +vn 0.0371 -0.0476 -0.9982 +vn -0.0160 -0.0376 -0.9992 +vn -0.3837 0.0349 -0.9228 +vn -0.9930 0.0069 -0.1179 +vn -0.9996 -0.0207 -0.0168 +vn -0.9954 0.0007 -0.0955 +vn -0.9997 -0.0255 0.0010 +vn 0.0014 1.0000 -0.0012 +vn 0.0003 0.9994 -0.0341 +vn 0.0044 1.0000 -0.0073 +vn 0.0053 1.0000 -0.0009 +vn 0.0090 0.9999 -0.0064 +vn 0.0104 0.9997 -0.0200 +vn 0.5829 -0.7738 -0.2479 +vn -0.5831 -0.7736 0.2479 +vn -0.6051 -0.6796 0.4146 +vn -0.6023 -0.7021 0.3799 +vn 0.5178 -0.2137 -0.8284 +vn 0.9284 -0.3187 0.1910 +vn 0.2828 0.1856 0.9410 +vn -0.5943 -0.4820 0.6438 +vn -0.8731 0.1447 -0.4656 +s 1 +f 1/1/1 2/2/1 3/3/1 +f 1/1/1 3/3/1 4/4/1 +f 5/5/2 6/6/3 7/7/4 +f 8/8/5 9/9/6 10/10/7 +f 10/10/7 9/9/6 11/11/8 +f 12/12/9 13/13/10 14/14/11 +f 15/15/12 16/16/13 17/17/14 +f 18/18/1 19/19/1 20/20/1 +f 21/21/15 20/20/1 22/22/16 +f 23/23/17 24/24/18 25/25/19 +f 25/25/19 24/24/18 19/19/1 +f 21/21/15 26/26/1 14/14/11 +f 21/21/15 27/27/20 26/26/1 +f 14/14/11 26/26/1 12/12/9 +f 28/28/21 12/12/9 29/29/22 +f 28/28/21 29/29/22 23/23/17 +f 29/29/22 27/27/20 23/23/17 +f 30/30/23 31/31/24 32/32/25 +f 8/8/5 33/33/26 31/31/24 +f 8/8/5 31/31/24 34/34/27 +f 10/10/7 35/35/28 8/8/5 +f 35/35/28 33/33/26 8/8/5 +f 34/34/27 31/31/24 30/30/23 +f 33/33/26 35/35/28 36/36/29 +f 36/36/29 37/37/30 33/33/26 +f 11/11/31 38/38/31 39/39/31 +f 11/11/32 13/13/10 12/12/9 +f 11/11/32 12/12/9 28/28/21 +f 11/11/32 28/28/21 38/38/33 +f 7/7/4 39/39/34 5/5/2 +f 5/5/2 40/40/35 16/16/13 +f 18/18/1 16/16/13 19/19/1 +f 19/19/1 16/16/13 25/25/19 +f 25/25/19 16/16/13 40/40/35 +f 17/17/14 41/41/36 15/15/12 +f 42/42/37 41/41/36 43/43/38 +f 41/41/36 44/44/39 45/45/40 +f 41/41/36 45/45/40 15/15/12 +f 42/42/37 46/46/41 47/47/42 +f 48/48/43 49/49/44 43/43/38 +f 42/42/37 47/47/42 41/41/36 +f 47/47/42 44/44/39 41/41/36 +f 46/46/41 42/42/37 50/50/45 +f 44/44/39 47/47/42 51/51/46 +f 44/44/39 51/51/46 52/52/47 +f 43/43/38 41/41/36 48/48/43 +f 14/14/11 53/53/48 21/21/15 +f 34/34/27 54/54/49 14/14/11 +f 14/14/11 54/54/49 53/53/48 +f 53/53/48 54/54/49 55/55/50 +f 21/21/15 18/18/1 20/20/1 +f 8/8/5 34/34/27 14/14/11 +f 27/27/20 21/21/15 22/22/16 +f 27/27/20 22/22/16 23/23/17 +f 23/23/17 22/22/16 24/24/18 +f 56/56/51 57/57/52 58/58/53 +f 56/56/51 58/58/53 59/59/54 +f 59/59/54 58/58/53 60/60/55 +f 61/61/56 62/62/57 57/57/52 +f 61/61/56 57/57/52 56/56/51 +f 63/63/58 64/64/59 61/61/56 +f 61/61/56 64/64/59 62/62/57 +f 65/65/60 66/66/61 63/63/58 +f 63/63/58 66/66/61 64/64/59 +f 65/65/60 60/60/55 66/66/61 +f 59/59/54 60/60/55 65/65/60 +f 67/67/62 68/68/63 69/69/64 +f 67/67/62 70/70/65 71/71/66 +f 67/67/62 69/69/64 70/70/65 +f 72/72/67 73/73/68 74/74/69 +f 72/72/67 74/74/69 70/70/65 +f 70/70/65 74/74/69 71/71/66 +f 68/68/70 75/75/71 76/76/72 +f 68/68/70 76/76/72 77/77/73 +f 68/68/70 77/77/73 69/69/74 +f 69/69/75 77/77/76 78/78/77 +f 69/69/75 78/78/77 70/70/78 +f 70/70/79 78/78/80 72/72/81 +f 72/72/81 78/78/80 79/79/82 +f 72/72/83 79/79/83 73/73/83 +f 73/73/84 79/79/85 80/80/86 +f 80/80/86 81/81/87 73/73/84 +f 76/76/88 75/75/89 82/82/90 +f 76/76/88 82/82/90 83/83/91 +f 84/84/92 83/83/91 82/82/90 +f 85/85/93 83/83/91 84/84/92 +f 83/83/91 85/85/93 86/86/94 +f 87/87/95 86/86/94 85/85/93 +f 88/88/96 89/89/97 90/90/98 +f 88/88/96 90/90/98 91/91/99 +f 88/88/96 91/91/99 92/92/100 +f 93/93/101 92/92/100 91/91/99 +f 92/92/100 93/93/101 80/80/86 +f 80/80/86 93/93/101 81/81/87 +f 48/48/102 94/94/103 95/95/104 +f 95/95/104 94/94/103 96/96/105 +f 95/95/106 96/96/107 97/97/108 +f 95/95/106 97/97/108 98/98/109 +f 94/94/110 48/48/111 99/99/112 +f 99/99/112 48/48/111 100/100/113 +f 99/99/114 100/100/115 101/101/116 +f 101/101/116 100/100/115 102/102/117 +f 101/101/118 102/102/119 97/97/120 +f 97/97/120 102/102/119 98/98/121 +f 103/103/122 84/84/122 50/50/122 +f 84/84/123 103/103/123 104/104/123 +f 84/84/124 104/104/124 49/49/124 +f 103/103/125 50/50/126 105/105/127 +f 105/105/127 50/50/126 42/42/128 +f 105/105/129 42/42/130 43/43/131 +f 105/105/129 43/43/131 106/106/132 +f 106/106/133 43/43/133 49/49/133 +f 106/106/134 49/49/134 104/104/134 +f 51/51/135 107/107/136 108/108/137 +f 109/109/138 108/108/137 107/107/136 +f 108/108/139 109/109/140 46/46/141 +f 46/46/141 109/109/140 110/110/142 +f 107/107/143 51/51/144 47/47/145 +f 107/107/143 47/47/145 111/111/146 +f 111/111/147 47/47/147 110/110/147 +f 110/110/148 47/47/148 46/46/148 +f 15/15/149 112/112/149 113/113/149 +f 113/113/150 112/112/150 114/114/150 +f 114/114/151 52/52/151 113/113/151 +f 115/115/152 52/52/152 114/114/152 +f 112/112/153 15/15/154 116/116/155 +f 116/116/155 15/15/154 45/45/156 +f 116/116/157 45/45/158 117/117/159 +f 117/117/159 45/45/158 44/44/160 +f 117/117/161 44/44/161 115/115/161 +f 115/115/162 44/44/162 52/52/162 +f 118/118/163 18/18/164 41/41/165 +f 118/118/166 41/41/167 119/119/168 +f 119/119/168 41/41/167 17/17/169 +f 119/119/170 17/17/171 16/16/172 +f 119/119/170 16/16/172 120/120/173 +f 120/120/174 16/16/175 18/18/176 +f 120/120/174 18/18/176 121/121/177 +f 121/121/178 18/18/164 118/118/163 +f 122/122/179 19/19/180 123/123/181 +f 123/123/181 19/19/180 24/24/182 +f 123/123/183 24/24/184 22/22/185 +f 123/123/183 22/22/185 124/124/186 +f 124/124/187 22/22/188 20/20/189 +f 124/124/187 20/20/189 125/125/190 +f 125/125/191 20/20/192 122/122/193 +f 122/122/193 20/20/192 19/19/194 +f 126/126/195 27/27/196 127/127/197 +f 127/127/197 27/27/196 29/29/198 +f 127/127/199 29/29/199 128/128/199 +f 128/128/200 29/29/200 12/12/200 +f 128/128/201 12/12/202 129/129/203 +f 129/129/203 12/12/202 26/26/204 +f 129/129/205 26/26/206 126/126/207 +f 126/126/207 26/26/206 27/27/208 +f 4/4/209 9/9/210 1/1/211 +f 9/9/210 8/8/212 1/1/211 +f 1/1/213 8/8/214 14/14/215 +f 1/1/213 14/14/215 2/2/216 +f 2/2/217 14/14/217 13/13/217 +f 2/2/218 13/13/219 3/3/220 +f 13/13/219 11/11/221 3/3/220 +f 3/3/222 11/11/223 4/4/224 +f 4/4/224 11/11/223 9/9/225 +f 36/36/226 130/130/226 131/131/226 +f 36/36/227 131/131/227 132/132/227 +f 133/133/228 132/132/229 131/131/230 +f 133/133/228 10/10/231 132/132/229 +f 130/130/232 36/36/233 134/134/234 +f 134/134/234 36/36/233 35/35/235 +f 134/134/236 35/35/237 10/10/238 +f 134/134/236 10/10/238 133/133/239 +f 135/135/240 32/32/241 136/136/242 +f 37/37/243 32/32/241 135/135/240 +f 137/137/244 37/37/245 135/135/246 +f 136/136/247 32/32/248 31/31/249 +f 136/136/247 31/31/249 138/138/250 +f 138/138/251 31/31/252 33/33/253 +f 138/138/251 33/33/253 137/137/254 +f 137/137/244 33/33/255 37/37/245 +f 139/139/256 140/140/257 55/55/258 +f 141/141/259 140/140/257 139/139/256 +f 141/141/260 30/30/260 140/140/260 +f 142/142/261 30/30/262 141/141/263 +f 139/139/264 55/55/265 54/54/266 +f 139/139/264 54/54/266 143/143/267 +f 143/143/268 54/54/269 142/142/270 +f 142/142/270 54/54/269 34/34/271 +f 142/142/261 34/34/272 30/30/262 +f 134/134/1 133/133/1 130/130/1 +f 144/144/273 145/145/274 146/146/275 +f 144/144/273 146/146/275 89/89/276 +f 147/147/277 89/89/278 146/146/279 +f 147/147/277 53/53/280 89/89/278 +f 145/145/274 144/144/273 148/148/281 +f 145/145/282 148/148/283 149/149/284 +f 149/149/284 148/148/283 21/21/285 +f 149/149/286 21/21/286 147/147/286 +f 147/147/287 21/21/287 53/53/287 +f 67/67/288 150/150/289 75/75/71 +f 67/67/288 75/75/71 68/68/70 +f 150/150/289 67/67/288 151/151/290 +f 60/60/291 150/150/289 151/151/290 +f 152/152/292 74/74/293 153/153/294 +f 73/73/84 81/81/87 74/74/293 +f 74/74/293 81/81/87 153/153/294 +f 152/152/292 153/153/294 62/62/295 +f 62/62/295 153/153/294 57/57/296 +f 57/57/296 153/153/294 154/154/297 +f 57/57/298 154/154/299 155/155/300 +f 57/57/298 155/155/300 58/58/301 +f 58/58/302 155/155/303 150/150/289 +f 58/58/302 150/150/289 60/60/291 +f 152/152/304 62/62/304 64/64/304 +f 74/74/69 152/152/305 156/156/306 +f 74/74/69 156/156/306 71/71/66 +f 71/71/66 156/156/306 67/67/62 +f 152/152/305 157/157/307 156/156/306 +f 156/156/306 157/157/308 151/151/309 +f 156/156/306 151/151/309 67/67/62 +f 152/152/305 64/64/310 157/157/307 +f 64/64/310 66/66/311 157/157/307 +f 157/157/308 66/66/312 151/151/309 +f 151/151/309 66/66/312 60/60/313 +f 158/158/314 159/159/315 160/160/316 +f 160/160/316 159/159/315 161/161/317 +f 161/161/317 159/159/315 162/162/318 +f 5/5/319 159/159/320 163/163/321 +f 5/5/319 39/39/322 164/164/323 +f 5/5/319 164/164/323 159/159/320 +f 164/164/323 162/162/324 159/159/320 +f 40/40/325 5/5/326 163/163/327 +f 165/165/328 40/40/325 163/163/327 +f 165/165/329 163/163/330 158/158/331 +f 158/158/331 163/163/330 159/159/332 +f 39/39/322 162/162/324 164/164/323 +f 25/25/333 40/40/334 166/166/335 +f 40/40/334 165/165/336 166/166/335 +f 166/166/335 165/165/336 158/158/337 +f 161/161/317 162/162/318 167/167/338 +f 167/167/339 162/162/340 38/38/341 +f 38/38/341 162/162/340 39/39/342 +f 23/23/343 25/25/344 166/166/335 +f 28/28/345 23/23/343 161/161/346 +f 23/23/343 160/160/347 161/161/346 +f 23/23/343 166/166/335 160/160/347 +f 166/166/335 158/158/337 160/160/347 +f 38/38/348 28/28/349 167/167/350 +f 28/28/349 161/161/351 167/167/350 +f 104/104/1 103/103/1 105/105/1 +f 107/107/1 111/111/1 110/110/1 +f 110/110/1 109/109/1 107/107/1 +f 114/114/1 112/112/1 115/115/1 +f 115/115/1 112/112/1 116/116/1 +f 117/117/1 115/115/1 116/116/1 +f 120/120/1 118/118/1 119/119/1 +f 120/120/1 121/121/1 118/118/1 +f 125/125/1 122/122/1 123/123/1 +f 123/123/1 124/124/1 125/125/1 +f 129/129/1 127/127/1 128/128/1 +f 126/126/1 127/127/1 129/129/1 +f 56/56/51 65/65/60 61/61/56 +f 61/61/56 65/65/60 63/63/58 +f 59/59/54 65/65/60 56/56/51 +f 150/150/289 155/155/303 6/6/352 +f 7/7/353 6/6/354 154/154/355 +f 154/154/355 6/6/354 155/155/356 +f 154/154/357 153/153/357 7/7/357 +f 10/10/7 11/11/8 7/7/4 +f 11/11/8 39/39/34 7/7/4 +f 7/7/4 132/132/358 10/10/7 +f 132/132/358 7/7/4 153/153/294 +f 132/132/358 153/153/294 81/81/87 +f 6/6/3 15/15/12 113/113/359 +f 6/6/3 5/5/2 16/16/13 +f 6/6/3 16/16/13 15/15/12 +f 113/113/360 75/75/361 6/6/352 +f 6/6/352 75/75/361 150/150/289 +f 87/87/95 89/89/97 86/86/94 +f 88/88/96 86/86/94 89/89/97 +f 98/98/362 87/87/95 95/95/363 +f 52/52/47 51/51/46 108/108/364 +f 37/37/365 93/93/101 32/32/366 +f 91/91/99 90/90/98 140/140/367 +f 87/87/95 85/85/93 95/95/363 +f 82/82/90 75/75/89 108/108/368 +f 81/81/369 93/93/101 37/37/365 +f 93/93/101 91/91/99 32/32/366 +f 32/32/366 91/91/99 140/140/367 +f 140/140/370 90/90/371 55/55/372 +f 132/132/373 81/81/369 36/36/374 +f 84/84/375 82/82/376 50/50/45 +f 52/52/47 75/75/377 113/113/378 +f 90/90/371 89/89/379 53/53/380 +f 89/89/381 87/87/95 144/144/382 +f 144/144/382 87/87/95 98/98/362 +f 95/95/383 85/85/384 48/48/43 +f 81/81/369 37/37/365 36/36/374 +f 32/32/366 140/140/367 30/30/385 +f 55/55/372 90/90/371 53/53/380 +f 144/144/386 98/98/387 148/148/388 +f 48/48/43 85/85/384 84/84/389 +f 48/48/43 84/84/389 49/49/44 +f 82/82/376 108/108/390 50/50/45 +f 50/50/45 108/108/390 46/46/41 +f 108/108/364 75/75/377 52/52/47 +f 130/130/1 133/133/1 131/131/1 +f 138/138/1 137/137/1 136/136/1 +f 136/136/1 137/137/1 135/135/1 +f 143/143/1 142/142/1 139/139/1 +f 141/141/1 139/139/1 142/142/1 +f 146/146/1 149/149/1 147/147/1 +f 145/145/1 149/149/1 146/146/1 +f 96/96/1 94/94/1 99/99/1 +f 96/96/1 99/99/1 97/97/1 +f 99/99/1 101/101/1 97/97/1 +f 104/104/1 105/105/1 106/106/1 +f 21/21/15 102/102/391 100/100/392 +f 41/41/36 100/100/392 48/48/43 +f 18/18/1 21/21/15 41/41/36 +f 102/102/391 148/148/388 98/98/387 +f 148/148/388 102/102/391 21/21/15 +f 41/41/36 21/21/15 100/100/392 +f 168/168/393 169/169/393 170/170/393 +f 170/170/394 171/171/394 172/172/394 +f 173/173/395 174/174/396 175/175/397 +f 173/173/395 175/175/397 176/176/398 +f 176/176/398 175/175/397 177/177/399 +f 176/176/400 177/177/401 178/178/402 +f 178/178/402 177/177/401 179/179/403 +f 178/178/402 179/179/403 174/174/404 +f 168/168/405 177/177/406 175/175/407 +f 168/168/408 175/175/408 169/169/408 +f 169/169/409 175/175/409 174/174/409 +f 169/169/410 174/174/410 170/170/410 +f 170/170/411 174/174/412 179/179/413 +f 170/170/411 179/179/413 171/171/414 +f 171/171/415 179/179/416 177/177/417 +f 171/171/415 177/177/417 172/172/418 +f 172/172/419 177/177/406 168/168/405 +f 168/168/420 170/170/421 180/180/422 +f 180/180/422 170/170/421 181/181/423 +f 172/172/424 168/168/424 180/180/424 +f 170/170/425 172/172/425 181/181/425 +f 181/181/426 172/172/426 180/180/426 +f 182/182/427 183/183/428 184/184/429 +f 184/184/429 183/183/428 185/185/430 +f 184/184/429 186/186/431 182/182/427 +f 185/185/432 187/187/432 186/186/432 +f 188/188/433 189/189/433 190/190/433 +f 188/188/434 190/190/435 191/191/436 +f 191/191/436 190/190/435 192/192/437 +f 192/192/438 193/193/438 194/194/438 +f 194/194/439 193/193/440 189/189/441 +f 194/194/439 189/189/441 188/188/442 +f 182/182/443 190/190/443 183/183/443 +f 183/183/444 190/190/444 189/189/444 +f 183/183/445 189/189/445 185/185/445 +f 185/185/446 189/189/447 193/193/448 +f 185/185/446 193/193/448 187/187/449 +f 187/187/450 193/193/451 186/186/452 +f 186/186/452 193/193/451 192/192/453 +f 186/186/454 192/192/454 182/182/454 +f 182/182/455 192/192/455 190/190/455 +f 185/185/456 186/186/456 195/195/456 +f 184/184/457 185/185/457 195/195/457 +f 186/186/458 184/184/458 195/195/458 +f 196/196/459 197/197/460 198/198/460 +f 198/198/460 197/197/460 199/199/460 +f 200/200/461 201/201/462 202/202/463 +f 202/202/463 201/201/462 203/203/464 +f 202/202/463 203/203/464 204/204/465 +f 204/204/465 203/203/464 205/205/466 +f 204/204/465 205/205/466 206/206/467 +f 206/206/467 205/205/466 207/207/468 +f 206/206/467 207/207/468 200/200/461 +f 200/200/461 207/207/468 201/201/462 +f 196/196/469 203/203/470 201/201/471 +f 196/196/469 201/201/471 197/197/472 +f 197/197/473 201/201/474 199/199/475 +f 199/199/475 201/201/474 207/207/476 +f 199/199/477 207/207/477 208/208/477 +f 208/208/478 207/207/478 205/205/478 +f 208/208/479 205/205/479 198/198/479 +f 198/198/480 205/205/481 203/203/482 +f 198/198/480 203/203/482 196/196/483 +f 199/199/484 208/208/484 209/209/484 +f 198/198/485 199/199/485 210/210/485 +f 210/210/486 199/199/486 209/209/486 +f 208/208/487 198/198/488 209/209/489 +f 209/209/489 198/198/488 210/210/490 +f 211/211/491 212/212/492 213/213/493 +f 214/214/494 215/215/494 216/216/494 +f 216/216/495 217/217/496 211/211/491 +f 216/216/495 211/211/491 213/213/493 +f 213/213/493 212/212/492 214/214/497 +f 218/218/498 219/219/499 220/220/500 +f 220/220/500 219/219/499 221/221/501 +f 220/220/500 221/221/501 222/222/502 +f 222/222/502 221/221/501 223/223/503 +f 222/222/502 223/223/503 224/224/504 +f 222/222/502 224/224/504 218/218/498 +f 218/218/498 224/224/504 225/225/505 +f 218/218/498 225/225/505 219/219/499 +f 215/215/506 221/221/506 216/216/506 +f 216/216/507 221/221/508 219/219/509 +f 216/216/507 219/219/509 217/217/510 +f 217/217/511 219/219/512 225/225/513 +f 217/217/511 225/225/513 211/211/514 +f 211/211/515 225/225/516 212/212/517 +f 212/212/517 225/225/516 224/224/518 +f 212/212/519 224/224/520 214/214/521 +f 214/214/521 224/224/520 223/223/522 +f 214/214/523 223/223/524 215/215/525 +f 215/215/525 223/223/524 221/221/526 +f 216/216/527 213/213/527 226/226/527 +f 214/214/528 216/216/528 226/226/528 +f 213/213/529 214/214/529 226/226/529 +f 227/227/530 228/228/531 229/229/532 +f 229/229/532 228/228/531 230/230/533 +f 229/229/532 231/231/534 227/227/530 +f 229/229/532 232/232/535 231/231/534 +f 233/233/536 234/234/537 235/235/538 +f 233/233/536 235/235/538 236/236/539 +f 236/236/540 235/235/541 237/237/542 +f 236/236/540 237/237/542 238/238/543 +f 238/238/543 237/237/542 239/239/544 +f 238/238/543 239/239/544 233/233/536 +f 233/233/536 239/239/544 234/234/537 +f 227/227/545 235/235/545 228/228/545 +f 228/228/546 235/235/546 234/234/546 +f 228/228/547 234/234/548 230/230/549 +f 230/230/549 234/234/548 239/239/550 +f 230/230/551 239/239/551 232/232/551 +f 232/232/552 239/239/552 237/237/552 +f 232/232/553 237/237/553 231/231/553 +f 231/231/554 237/237/555 227/227/556 +f 227/227/556 237/237/555 235/235/557 +f 240/240/558 232/232/558 241/241/558 +f 230/230/559 232/232/559 240/240/559 +f 229/229/560 230/230/561 241/241/562 +f 241/241/562 230/230/561 240/240/563 +f 232/232/564 229/229/564 241/241/564 +f 242/242/565 243/243/565 244/244/565 +f 245/245/566 246/246/566 244/244/566 +f 243/243/567 247/247/567 245/245/567 +f 248/248/568 249/249/569 250/250/570 +f 250/250/570 249/249/569 251/251/571 +f 250/250/570 251/251/571 252/252/572 +f 252/252/573 251/251/573 253/253/573 +f 252/252/574 253/253/575 254/254/576 +f 254/254/576 253/253/575 255/255/577 +f 254/254/576 255/255/577 248/248/568 +f 248/248/568 255/255/577 249/249/569 +f 242/242/578 251/251/578 249/249/578 +f 242/242/579 249/249/579 243/243/579 +f 243/243/580 249/249/581 255/255/582 +f 243/243/580 255/255/582 247/247/583 +f 247/247/584 255/255/585 253/253/586 +f 247/247/584 253/253/586 245/245/587 +f 245/245/588 253/253/588 246/246/588 +f 246/246/589 253/253/590 251/251/591 +f 246/246/589 251/251/591 244/244/592 +f 244/244/593 251/251/593 242/242/593 +f 243/243/594 245/245/594 256/256/594 +f 256/256/595 245/245/595 257/257/595 +f 244/244/596 243/243/597 256/256/598 +f 257/257/599 244/244/596 256/256/598 +f 245/245/600 244/244/600 257/257/600 +f 258/258/601 259/259/602 260/260/603 +f 259/259/604 261/261/604 262/262/604 +f 262/262/605 263/263/606 258/258/601 +f 262/262/605 258/258/601 260/260/603 +f 264/264/607 265/265/608 266/266/609 +f 264/264/607 266/266/609 267/267/610 +f 267/267/610 266/266/609 268/268/611 +f 267/267/610 268/268/611 269/269/612 +f 269/269/612 268/268/611 270/270/613 +f 269/269/612 270/270/613 271/271/614 +f 271/271/614 270/270/613 264/264/607 +f 264/264/607 270/270/613 265/265/608 +f 261/261/615 266/266/616 262/262/617 +f 262/262/618 266/266/618 263/263/618 +f 263/263/619 266/266/619 265/265/619 +f 263/263/620 265/265/620 258/258/620 +f 258/258/621 265/265/621 270/270/621 +f 258/258/622 270/270/622 259/259/622 +f 259/259/623 270/270/624 268/268/625 +f 259/259/623 268/268/625 261/261/626 +f 261/261/615 268/268/627 266/266/616 +f 262/262/628 260/260/628 272/272/628 +f 259/259/629 262/262/629 272/272/629 +f 260/260/603 259/259/602 272/272/630 +f 273/273/631 274/274/631 275/275/631 +f 275/275/632 276/276/632 277/277/632 +f 278/278/633 279/279/634 280/280/635 +f 278/278/633 280/280/635 281/281/636 +f 281/281/636 280/280/635 282/282/637 +f 281/281/636 282/282/637 283/283/638 +f 283/283/638 282/282/637 284/284/639 +f 283/283/638 284/284/639 285/285/640 +f 283/283/638 285/285/640 278/278/641 +f 278/278/642 285/285/642 279/279/642 +f 274/274/643 282/282/644 280/280/645 +f 274/274/643 280/280/645 275/275/646 +f 275/275/647 280/280/648 276/276/649 +f 276/276/649 280/280/648 279/279/650 +f 276/276/651 279/279/652 277/277/653 +f 277/277/653 279/279/652 285/285/654 +f 277/277/655 285/285/656 273/273/657 +f 273/273/657 285/285/656 284/284/658 +f 273/273/659 284/284/660 282/282/661 +f 273/273/659 282/282/661 274/274/662 +f 275/275/663 277/277/663 286/286/663 +f 286/286/664 277/277/664 287/287/664 +f 273/273/665 275/275/665 286/286/665 +f 277/277/666 273/273/667 287/287/668 +f 287/287/668 273/273/667 286/286/669 +f 288/288/670 289/289/670 290/290/670 +f 291/291/671 292/292/672 293/293/673 +f 293/293/673 292/292/672 294/294/674 +f 293/293/673 294/294/674 295/295/675 +f 295/295/675 294/294/674 296/296/676 +f 295/295/675 296/296/676 297/297/677 +f 297/297/677 296/296/676 298/298/678 +f 297/297/677 298/298/678 291/291/679 +f 291/291/680 298/298/680 292/292/680 +f 299/299/681 294/294/682 292/292/683 +f 299/299/681 292/292/683 300/300/684 +f 300/300/685 292/292/686 288/288/687 +f 288/288/687 292/292/686 298/298/688 +f 288/288/689 298/298/689 289/289/689 +f 289/289/690 298/298/690 296/296/690 +f 289/289/691 296/296/691 290/290/691 +f 290/290/692 296/296/693 294/294/694 +f 290/290/692 294/294/694 299/299/695 +f 300/300/696 288/288/696 301/301/696 +f 299/299/697 300/300/697 302/302/697 +f 302/302/698 300/300/698 301/301/698 +f 290/290/699 299/299/699 302/302/699 +f 288/288/700 290/290/701 301/301/702 +f 301/301/702 290/290/701 302/302/703 +f 303/303/704 304/304/704 305/305/704 +f 306/306/705 305/305/705 307/307/705 +f 308/308/706 309/309/707 310/310/708 +f 308/308/706 310/310/708 311/311/709 +f 311/311/709 310/310/708 312/312/710 +f 311/311/709 312/312/710 313/313/711 +f 313/313/711 312/312/710 314/314/712 +f 313/313/711 314/314/712 315/315/713 +f 313/313/711 315/315/713 309/309/714 +f 303/303/715 312/312/716 310/310/717 +f 303/303/718 310/310/719 309/309/720 +f 303/303/718 309/309/720 304/304/721 +f 304/304/722 309/309/722 315/315/722 +f 304/304/723 315/315/723 305/305/723 +f 305/305/724 315/315/725 314/314/726 +f 305/305/724 314/314/726 307/307/727 +f 307/307/728 314/314/729 312/312/730 +f 307/307/728 312/312/730 306/306/731 +f 306/306/732 312/312/716 303/303/715 +f 303/303/733 305/305/733 316/316/733 +f 316/316/734 305/305/734 317/317/734 +f 306/306/735 303/303/735 316/316/735 +f 305/305/736 306/306/737 317/317/738 +f 317/317/738 306/306/737 316/316/739 +f 318/318/740 319/319/740 320/320/740 +f 320/320/741 321/321/741 322/322/741 +f 323/323/742 324/324/743 325/325/744 +f 323/323/742 325/325/744 326/326/745 +f 326/326/745 325/325/744 327/327/746 +f 326/326/745 327/327/746 328/328/747 +f 328/328/747 327/327/746 329/329/748 +f 328/328/747 329/329/748 324/324/743 +f 328/328/747 324/324/743 323/323/742 +f 319/319/749 327/327/750 325/325/751 +f 319/319/749 325/325/751 320/320/752 +f 320/320/753 325/325/754 324/324/755 +f 320/320/753 324/324/755 321/321/756 +f 321/321/757 324/324/758 322/322/759 +f 322/322/759 324/324/758 329/329/760 +f 322/322/761 329/329/761 318/318/761 +f 318/318/762 329/329/763 327/327/764 +f 318/318/762 327/327/764 319/319/765 +f 320/320/766 322/322/767 330/330/768 +f 330/330/768 322/322/767 331/331/769 +f 318/318/770 320/320/770 330/330/770 +f 331/331/771 318/318/771 330/330/771 +f 322/322/772 318/318/772 331/331/772 +f 332/332/773 333/333/773 334/334/773 +f 335/335/774 336/336/774 332/332/774 +f 337/337/775 338/338/776 339/339/777 +f 337/337/775 339/339/777 340/340/778 +f 340/340/778 339/339/777 341/341/779 +f 340/340/778 341/341/779 342/342/780 +f 342/342/780 341/341/779 343/343/781 +f 342/342/780 343/343/781 344/344/782 +f 342/342/780 344/344/782 338/338/783 +f 332/332/784 339/339/785 338/338/786 +f 332/332/784 338/338/786 333/333/787 +f 333/333/788 338/338/788 344/344/788 +f 333/333/789 344/344/789 334/334/789 +f 334/334/790 344/344/791 343/343/792 +f 334/334/790 343/343/792 335/335/793 +f 335/335/794 343/343/795 341/341/796 +f 335/335/794 341/341/796 336/336/797 +f 336/336/798 341/341/799 339/339/800 +f 336/336/798 339/339/800 332/332/801 +f 334/334/802 335/335/802 345/345/802 +f 346/346/803 334/334/803 345/345/803 +f 332/332/804 334/334/804 346/346/804 +f 335/335/805 332/332/806 345/345/807 +f 345/345/807 332/332/806 346/346/808 +f 347/347/809 348/348/810 349/349/811 +f 350/350/812 351/351/813 352/352/814 +f 352/352/814 351/351/813 347/347/809 +f 347/347/809 351/351/813 348/348/810 +f 348/348/810 353/353/815 349/349/811 +f 349/349/811 353/353/815 354/354/816 +f 353/353/815 355/355/817 354/354/816 +f 354/354/816 355/355/817 356/356/818 +f 355/355/817 357/357/819 356/356/818 +f 356/356/818 357/357/819 350/350/812 +f 350/350/812 357/357/819 351/351/813 +f 358/358/820 350/350/821 352/352/822 +f 358/358/820 352/352/822 359/359/823 +f 359/359/824 352/352/825 347/347/826 +f 359/359/824 347/347/826 360/360/827 +f 360/360/828 347/347/829 349/349/830 +f 360/360/828 349/349/830 361/361/831 +f 361/361/832 349/349/832 354/354/832 +f 361/361/833 354/354/833 362/362/833 +f 362/362/834 354/354/834 356/356/834 +f 362/362/835 356/356/836 358/358/837 +f 358/358/837 356/356/836 350/350/838 +f 363/363/1 359/359/1 360/360/1 +f 363/363/1 360/360/1 364/364/1 +f 364/364/1 360/360/1 361/361/1 +f 364/364/1 361/361/1 365/365/1 +f 365/365/1 361/361/1 362/362/1 +f 365/365/1 362/362/1 358/358/1 +f 365/365/1 358/358/1 366/366/1 +f 366/366/1 358/358/1 359/359/1 +f 366/366/1 359/359/1 363/363/1 +f 367/367/839 366/366/840 368/368/841 +f 368/368/841 366/366/840 363/363/842 +f 368/368/843 363/363/843 369/369/843 +f 369/369/844 363/363/845 364/364/846 +f 369/369/844 364/364/846 370/370/847 +f 370/370/848 364/364/848 371/371/848 +f 371/371/849 364/364/850 365/365/851 +f 371/371/849 365/365/851 372/372/852 +f 372/372/853 365/365/854 367/367/855 +f 367/367/855 365/365/854 366/366/856 +f 367/367/857 368/368/858 369/369/859 +f 367/367/857 369/369/859 372/372/860 +f 369/369/859 370/370/861 372/372/860 +f 372/372/860 370/370/861 371/371/862 +f 357/357/863 373/373/863 374/374/863 +f 374/374/864 373/373/865 348/348/866 +f 374/374/867 351/351/867 357/357/867 +f 357/357/868 355/355/868 373/373/868 +f 355/355/869 353/353/869 373/373/869 +f 373/373/865 353/353/870 348/348/866 +f 348/348/871 351/351/871 374/374/871 diff --git a/examples/Cassie/urdf/meshes/agility/foot.obj b/examples/Cassie/urdf/meshes/agility/foot.obj new file mode 100644 index 0000000000..88dc821034 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/foot.obj @@ -0,0 +1,4048 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o foot +v 0.076973 -0.009653 0.006310 +v 0.056887 -0.010000 0.001162 +v 0.055851 -0.010000 -0.002144 +v 0.053448 -0.009982 -0.009669 +v 0.053841 -0.010000 -0.006651 +v 0.053221 -0.009913 0.004400 +v 0.046939 -0.010004 0.002206 +v 0.052755 -0.010000 -0.000261 +v 0.054399 -0.010000 0.002019 +v 0.072184 -0.009754 0.010842 +v 0.048795 -0.010000 0.000387 +v 0.049932 -0.009999 -0.003414 +v 0.036423 -0.007706 0.004716 +v 0.037835 0.003321 0.004721 +v 0.036219 0.007583 0.004754 +v 0.044717 -0.007794 0.005000 +v 0.052229 0.003001 0.006258 +v 0.056765 -0.007796 0.007503 +v 0.072604 -0.007892 0.012781 +v 0.078209 0.003132 0.014036 +v 0.077885 -0.002818 0.014118 +v 0.029832 -0.008017 0.005400 +v 0.029983 0.007876 0.005398 +v 0.049823 0.010108 -0.010290 +v 0.052811 0.004962 -0.011050 +v 0.057414 0.009316 -0.011194 +v 0.057757 0.005145 -0.010877 +v 0.061343 0.005393 -0.009298 +v 0.062714 0.009116 -0.008229 +v 0.063626 0.004424 -0.006933 +v 0.065854 0.009379 -0.003650 +v 0.065810 0.004542 -0.002583 +v 0.066174 0.005278 0.001567 +v 0.066158 0.010021 0.001513 +v 0.047711 0.004849 -0.008544 +v 0.058084 0.003820 -0.010108 +v 0.051717 0.003836 -0.009980 +v 0.064419 0.003175 0.002173 +v 0.049887 0.003071 -0.007810 +v 0.057756 0.003055 -0.008840 +v 0.063843 0.003073 -0.003134 +v -0.008802 0.010000 -0.010016 +v -0.008599 0.009994 -0.006675 +v -0.003234 0.010000 -0.012625 +v -0.010973 0.009897 0.001490 +v -0.011774 0.010004 -0.011091 +v 0.009669 0.010000 -0.008745 +v 0.007873 0.009999 -0.007220 +v 0.012775 0.010000 -0.003311 +v 0.010680 0.009997 -0.001419 +v 0.008976 0.010005 0.006046 +v 0.014873 0.010004 0.006018 +v 0.012749 0.010000 0.003457 +v -0.001396 0.009997 -0.010683 +v 0.001812 0.010000 -0.013469 +v -0.037755 0.009871 -0.073892 +v -0.037733 0.010000 -0.078233 +v -0.052346 0.009825 -0.096591 +v -0.026572 0.010040 -0.056860 +v -0.050279 0.009664 -0.100339 +v -0.036464 0.010000 -0.081600 +v -0.033233 0.010000 -0.081758 +v 0.044941 0.010007 -0.014985 +v 0.045273 0.010000 -0.011932 +v 0.033700 0.010001 0.001774 +v 0.037698 0.009771 0.003116 +v 0.002700 0.009918 -0.010104 +v 0.008695 0.010007 -0.037001 +v -0.024841 0.010006 -0.074799 +v 0.005551 0.010000 -0.012434 +v 0.010955 0.010000 -0.031986 +v 0.013788 0.010014 -0.033107 +v 0.075688 -0.008095 0.012227 +v 0.080764 -0.006420 0.009146 +v 0.077500 -0.005919 0.013344 +v 0.082661 -0.004623 0.008631 +v 0.079492 -0.002976 0.013446 +v 0.084229 -0.003981 0.007234 +v 0.086223 -0.002592 0.005676 +v 0.079914 0.000937 0.013625 +v 0.086460 0.001999 0.005617 +v 0.084813 0.003877 0.006623 +v 0.079137 0.005287 0.012437 +v 0.082502 0.004673 0.008819 +v 0.080284 0.006973 0.008855 +v 0.077570 0.009420 0.006748 +v 0.074364 0.009911 0.008343 +v 0.057282 -0.004000 0.000335 +v 0.055313 -0.004000 -0.002116 +v 0.052897 -0.004000 -0.000698 +v 0.054302 -0.004000 0.002103 +v 0.009053 -0.009998 0.005872 +v 0.015565 -0.010002 0.006029 +v 0.003959 -0.009911 0.010178 +v 0.012841 -0.010000 0.004175 +v 0.005580 -0.010000 -0.012390 +v 0.010482 -0.009888 -0.001259 +v 0.007277 -0.009997 -0.007945 +v 0.012775 -0.010000 -0.003311 +v -0.009595 -0.010007 -0.004768 +v -0.011572 -0.010004 -0.010731 +v -0.006695 -0.009822 -0.007823 +v -0.008384 -0.010000 -0.010162 +v 0.009669 -0.010000 -0.008745 +v -0.003785 -0.010000 -0.012533 +v -0.002958 -0.009729 -0.009894 +v 0.001892 -0.010000 -0.013522 +v 0.001706 -0.009881 -0.010173 +v -0.025283 -0.010001 -0.054127 +v -0.015693 -0.010016 -0.028788 +v -0.032603 -0.009883 -0.064449 +v -0.050935 -0.009996 -0.096707 +v -0.037925 -0.010000 -0.079069 +v 0.008669 -0.010007 -0.037047 +v 0.013895 -0.010015 -0.033103 +v 0.010928 -0.010000 -0.031960 +v -0.034616 -0.010000 -0.082256 +v -0.024864 -0.010007 -0.074829 +v -0.024880 0.009451 -0.079249 +v 0.063035 0.008898 -0.009576 +v 0.064431 0.008925 -0.008204 +v 0.065596 0.009005 -0.006631 +v 0.066501 0.009137 -0.004896 +v 0.067124 0.009317 -0.003041 +v 0.067653 0.009435 -0.001721 +v 0.051724 0.009451 -0.014971 +v 0.054457 0.009436 -0.012785 +v 0.061442 0.008925 -0.010712 +v 0.059691 0.009005 -0.011587 +v 0.057825 0.009137 -0.012177 +v 0.055890 0.009317 -0.012468 +v -0.024880 -0.009451 -0.079249 +v -0.050375 -0.009451 -0.100642 +v 0.051724 -0.009451 -0.014971 +v 0.048880 -0.009985 -0.013541 +v -0.053854 0.008750 -0.096312 +v -0.056238 0.006762 -0.097906 +v -0.043950 0.008471 -0.081064 +v -0.022746 0.000273 -0.037725 +v -0.019818 0.008144 -0.031827 +v -0.026109 0.008155 -0.047371 +v -0.034799 -0.008264 -0.064849 +v -0.023935 -0.008209 -0.042521 +v -0.017822 -0.007733 -0.025635 +v -0.047616 0.001127 -0.083186 +v -0.058707 -0.001606 -0.099146 +v -0.056626 -0.006174 -0.097986 +v -0.058198 0.003430 -0.098791 +v -0.031531 0.002513 -0.056065 +v -0.041421 -0.002445 -0.073641 +v -0.035073 0.008142 -0.065261 +v -0.043994 -0.008647 -0.081340 +v -0.054464 -0.008394 -0.096846 +v -0.017240 0.008334 -0.023868 +v 0.001939 -0.008370 0.012667 +v 0.000879 0.008281 0.012886 +v -0.012316 0.008265 0.003658 +v -0.012432 -0.007776 0.003653 +v -0.010716 -0.008268 0.007138 +v -0.010696 0.008268 0.007169 +v -0.007368 -0.008393 0.010537 +v -0.007779 0.008268 0.010261 +v -0.002906 -0.008188 0.012636 +v -0.004015 0.008268 0.012234 +v 0.049065 0.009451 -0.016900 +v 0.046162 0.009451 -0.018438 +v 0.028200 0.010016 -0.023777 +v 0.032046 0.009452 -0.025490 +v 0.015477 0.009445 -0.036420 +v -0.010086 0.010007 -0.054946 +v 0.001322 0.009450 -0.048410 +v -0.011348 0.009447 -0.062008 +v -0.020500 0.009451 -0.074374 +v -0.022518 0.009451 -0.076966 +v 0.049065 -0.009451 -0.016900 +v 0.046162 -0.009451 -0.018438 +v -0.010014 -0.010011 -0.054866 +v -0.020500 -0.009451 -0.074374 +v -0.019430 -0.009210 -0.072529 +v -0.002498 -0.009450 -0.052089 +v 0.014495 -0.009443 -0.037124 +v 0.030518 -0.010019 -0.022415 +v 0.031639 -0.009453 -0.025697 +v -0.022518 -0.009451 -0.076966 +v -0.012132 0.003454 -0.011873 +v -0.015349 0.010006 -0.028083 +v -0.014492 0.003297 -0.024830 +v -0.033159 0.003700 -0.081687 +v -0.025042 0.002730 -0.074690 +v -0.019150 0.002780 -0.066248 +v -0.008003 0.003128 -0.052833 +v 0.008020 0.003371 -0.037812 +v 0.002348 0.002978 -0.014414 +v 0.008668 0.003594 -0.036138 +v 0.000714 0.003201 -0.013191 +v -0.004038 0.003263 -0.012562 +v -0.008634 0.003264 -0.010124 +v -0.018301 0.003292 -0.037006 +v -0.020888 0.002401 -0.044533 +v -0.037423 0.003259 -0.077686 +v -0.029864 0.002923 -0.063884 +v 0.000684 0.001240 -0.014916 +v -0.009067 0.001075 -0.050413 +v -0.009604 0.001075 -0.012409 +v 0.006710 0.001167 -0.036222 +v -0.015257 0.001062 -0.036265 +v -0.026472 0.001146 -0.073457 +v -0.034894 0.000977 -0.079580 +v 0.028378 0.003340 0.002712 +v 0.015746 0.002849 0.005859 +v 0.012767 0.003539 0.002889 +v 0.013202 0.002796 -0.001399 +v 0.011837 0.002778 -0.005883 +v 0.009318 0.003279 -0.009223 +v 0.006487 0.002787 -0.011597 +v 0.010682 0.003010 -0.031219 +v 0.005717 0.003248 -0.014166 +v 0.014319 0.003124 -0.032837 +v 0.027103 0.002717 -0.024254 +v 0.043984 0.003520 -0.015612 +v 0.033960 0.003094 0.001475 +v 0.045249 0.003346 -0.011992 +v 0.033132 0.003179 0.001876 +v 0.032738 0.001068 -0.000578 +v 0.014549 0.001083 -0.005207 +v 0.014679 0.001197 0.003339 +v 0.013159 0.001081 -0.030816 +v 0.007834 0.001114 -0.013067 +v 0.027889 0.001062 -0.021064 +v 0.010510 0.001224 -0.010339 +v 0.043105 0.001065 -0.013187 +v -0.014544 -0.003393 -0.025001 +v -0.012088 -0.003383 -0.011755 +v -0.008565 -0.003420 -0.010137 +v -0.008076 -0.002554 -0.010746 +v -0.003516 -0.002747 -0.012792 +v 0.001231 -0.003458 -0.013280 +v 0.002384 -0.002907 -0.014557 +v 0.008652 -0.003751 -0.035903 +v 0.008176 -0.003455 -0.037703 +v -0.000145 -0.002762 -0.044897 +v -0.010134 -0.002477 -0.055029 +v -0.019096 -0.002734 -0.066151 +v -0.024932 -0.003174 -0.074745 +v -0.033244 -0.002844 -0.081586 +v -0.030363 -0.002838 -0.064936 +v -0.037591 -0.003545 -0.077982 +v -0.025331 -0.003395 -0.054090 +v -0.018290 -0.003377 -0.036952 +v 0.006255 -0.001082 -0.036107 +v 0.000743 -0.001171 -0.015283 +v -0.013755 -0.001054 -0.055805 +v -0.009830 -0.001070 -0.012498 +v -0.026135 -0.001278 -0.073734 +v -0.028003 -0.001090 -0.064933 +v -0.035696 -0.001125 -0.078692 +v -0.013760 -0.001083 -0.031531 +v 0.037229 -0.003104 -0.018796 +v 0.048872 -0.003334 -0.013450 +v 0.024127 -0.003294 -0.026259 +v 0.014001 -0.003323 -0.032995 +v 0.010613 -0.003240 -0.031196 +v 0.005625 -0.003274 -0.013756 +v 0.006160 -0.003236 -0.011766 +v 0.009310 -0.002790 -0.009371 +v 0.012128 -0.002821 -0.005317 +v 0.013177 -0.002860 -0.000729 +v 0.012750 -0.003745 0.002710 +v 0.015901 -0.003268 0.005939 +v 0.033818 -0.010033 0.001749 +v 0.030983 -0.003355 0.002140 +v 0.036861 -0.003014 0.001574 +v 0.046570 -0.003334 0.002172 +v 0.047566 -0.001057 -0.011406 +v 0.051438 -0.001040 -0.007819 +v 0.048291 -0.001059 -0.005296 +v 0.028762 -0.001215 -0.021317 +v 0.011592 -0.001096 -0.010055 +v 0.007822 -0.001113 -0.013074 +v 0.012736 -0.001110 -0.030755 +v 0.015206 -0.001086 -0.002782 +v 0.036726 -0.001150 -0.000362 +v 0.015194 -0.001077 0.003528 +v 0.046710 -0.001124 -0.000164 +v -0.058572 0.001692 -0.101225 +v -0.051155 0.000297 -0.110348 +v -0.058115 -0.003521 -0.100902 +v -0.051645 -0.003788 -0.108453 +v -0.053632 -0.004631 -0.105490 +v -0.057515 -0.005257 -0.100171 +v -0.053011 -0.007527 -0.102818 +v -0.055001 -0.008102 -0.099121 +v -0.052539 -0.009716 -0.096504 +v -0.051722 0.003819 -0.108328 +v -0.053517 0.004528 -0.105688 +v -0.057237 0.005483 -0.100292 +v -0.053469 0.006782 -0.103394 +v -0.055268 0.007878 -0.099271 +v 0.053054 -0.003169 -0.009950 +v 0.053002 -0.003637 -0.005862 +v 0.053852 -0.003528 -0.007453 +v 0.053706 -0.003025 -0.008766 +v 0.050226 -0.003453 -0.003891 +v 0.048897 -0.003387 -0.000196 +v 0.008356 -0.002573 -0.036155 +v 0.007638 -0.001691 -0.036752 +v 0.000411 -0.002046 -0.013831 +v -0.009333 -0.001557 -0.011191 +v -0.010562 -0.003268 -0.010405 +v -0.011379 -0.001904 -0.012335 +v -0.035692 -0.003129 -0.081774 +v -0.037525 -0.003252 -0.079754 +v -0.034169 -0.001287 -0.080250 +v -0.013647 -0.001874 -0.024933 +v -0.036038 -0.001561 -0.080052 +v -0.036893 -0.002213 -0.077947 +v -0.018257 -0.001904 -0.039313 +v 0.011691 -0.003429 -0.032485 +v 0.014333 -0.001782 -0.031872 +v 0.048554 -0.001971 -0.012785 +v 0.052611 -0.001484 -0.008360 +v 0.011754 -0.001841 -0.031470 +v 0.052656 -0.002121 -0.006440 +v 0.006670 -0.001637 -0.012807 +v 0.049257 -0.001892 -0.003946 +v 0.048146 -0.001970 -0.000519 +v 0.047997 -0.002875 0.001272 +v 0.046154 -0.001713 0.001136 +v 0.014061 -0.003469 0.005374 +v 0.013013 -0.002757 0.003579 +v 0.013965 -0.001729 0.003874 +v 0.030387 -0.001704 0.001228 +v 0.015862 -0.001790 0.004988 +v 0.005687 0.003472 -0.012809 +v 0.006520 0.001821 -0.013497 +v 0.012967 0.002836 0.003726 +v 0.014138 0.002962 0.005285 +v 0.012010 0.003120 -0.032661 +v 0.011876 0.001709 -0.031344 +v 0.015912 0.001288 0.004263 +v 0.013759 0.001786 -0.032035 +v 0.033282 0.001623 0.000582 +v 0.045127 0.003383 -0.014356 +v 0.043848 0.001864 -0.014719 +v 0.034592 0.001785 -0.019110 +v 0.044440 0.001753 -0.012594 +v -0.033541 0.002272 -0.081343 +v -0.037677 0.003513 -0.078960 +v -0.036762 0.002848 -0.080897 +v -0.035641 0.003494 -0.081839 +v -0.036680 0.001635 -0.078903 +v 0.007364 0.002060 -0.037488 +v -0.008366 0.001618 -0.051603 +v -0.013871 0.001848 -0.026150 +v 0.008243 0.002425 -0.036174 +v -0.011401 0.001781 -0.012583 +v -0.010830 0.002815 -0.010606 +v -0.008569 0.002018 -0.010859 +v -0.004396 0.001933 -0.013337 +v 0.051809 0.003000 -0.001062 +v 0.057873 0.003000 0.001559 +v 0.055094 0.003000 0.003361 +v 0.052399 0.003000 0.001920 +v 0.054347 0.003000 -0.003203 +v 0.057745 0.003000 -0.002040 +v 0.056062 -0.004000 0.003191 +v 0.058361 -0.004000 0.000094 +v 0.055702 -0.004000 -0.003412 +v 0.051723 -0.004000 -0.000978 +v 0.052833 -0.004000 0.002448 +v 0.061442 0.008925 -0.010712 +v 0.054016 0.007888 -0.023865 +v 0.059691 0.009005 -0.011587 +v 0.063035 0.008898 -0.009576 +v 0.046162 0.009451 -0.018438 +v 0.025493 0.009439 -0.029209 +v 0.049065 0.009451 -0.016900 +v 0.051724 0.009451 -0.014971 +v 0.066501 0.009137 -0.004896 +v 0.077814 0.009301 0.006912 +v 0.084156 0.007927 0.001609 +v 0.067124 0.009317 -0.003041 +v 0.067634 0.009428 -0.001761 +v 0.057825 0.009137 -0.012177 +v 0.055890 0.009317 -0.012468 +v 0.054450 0.009439 -0.012801 +v 0.065596 0.009005 -0.006631 +v 0.064431 0.008925 -0.008204 +v 0.038538 -0.009226 0.003706 +v 0.029709 -0.009683 0.004000 +v 0.053696 -0.008934 0.005968 +v -0.001052 -0.009910 0.010984 +v -0.005290 -0.009908 0.009615 +v -0.009375 -0.009910 0.005966 +v -0.011570 -0.009326 0.003160 +v -0.010854 -0.009914 0.000462 +v -0.017026 -0.009310 -0.026474 +v -0.023928 -0.009416 -0.044785 +v -0.030611 0.009514 -0.059236 +v -0.016889 0.009723 -0.028644 +v -0.007926 0.009917 0.007782 +v -0.001465 0.009908 0.011018 +v 0.003931 0.009933 0.010200 +v 0.029534 0.009672 0.004073 +v 0.002698 -0.008914 0.009832 +v 0.008328 -0.008984 0.005827 +v 0.009481 -0.008991 -0.003433 +v 0.005889 -0.008983 -0.008290 +v -0.009455 -0.009008 -0.003512 +v -0.009992 -0.008892 0.001574 +v -0.008029 -0.008914 0.005998 +v -0.004351 -0.008901 0.009175 +v -0.009979 0.008916 0.001146 +v -0.009641 0.009039 -0.003090 +v 0.003724 0.008905 0.009386 +v 0.007867 0.009006 0.006319 +v -0.007238 0.009007 -0.006949 +v -0.003574 0.009007 -0.009441 +v 0.004924 0.009007 -0.008812 +v 0.009177 0.009000 -0.004406 +v 0.009968 0.009007 0.001597 +v -0.000885 0.008921 0.009995 +v -0.005036 0.008886 0.008719 +v -0.008570 0.008919 0.005329 +v 0.084316 -0.007840 0.001304 +v 0.053863 -0.007660 -0.024699 +v 0.086881 -0.005033 0.000152 +v 0.055708 -0.003830 -0.026481 +v 0.055897 0.000712 -0.026951 +v 0.088481 -0.000226 0.000235 +v 0.055273 0.005476 -0.025966 +v 0.087642 0.004468 0.000730 +v 0.085302 0.006798 0.000405 +v -0.046675 0.007893 -0.108377 +v -0.016024 0.007891 -0.082480 +v -0.015333 0.007089 -0.083518 +v -0.046363 0.006476 -0.110259 +v -0.014564 0.004476 -0.085131 +v -0.046576 0.004073 -0.112070 +v -0.046187 -0.000480 -0.112820 +v -0.013871 -0.000708 -0.085617 +v -0.014594 -0.005242 -0.084663 +v -0.046301 -0.004077 -0.111908 +v -0.046145 -0.007319 -0.109282 +v -0.015438 -0.007049 -0.083628 +v -0.016245 -0.007901 -0.082639 +v -0.047417 -0.007954 -0.108140 +v -0.020500 -0.009451 -0.074374 +v -0.022518 -0.009451 -0.076966 +v -0.000801 -0.007881 -0.062591 +v -0.003474 -0.005564 -0.069340 +v -0.002477 -0.000114 -0.070149 +v -0.005533 0.005434 -0.072157 +v 0.003362 0.005429 -0.061768 +v -0.002981 0.007873 -0.064976 +v 0.012501 -0.006494 -0.051550 +v 0.011113 -0.003603 -0.054977 +v 0.013885 0.000819 -0.052936 +v 0.034519 -0.007899 -0.033569 +v 0.014186 -0.007883 -0.048095 +v 0.034318 -0.005641 -0.036466 +v 0.023563 -0.003506 -0.044848 +v 0.030165 0.000828 -0.040728 +v 0.026094 0.005412 -0.042066 +v 0.014269 0.007862 -0.048078 +v 0.031145 0.007862 -0.035834 +v 0.039974 -0.003652 -0.034290 +v 0.038005 0.006389 -0.033717 +v 0.041767 0.002648 -0.033726 +v 0.013186 0.005430 -0.052253 +v 0.088833 -0.001352 0.001475 +v 0.088455 -0.002287 0.002996 +v 0.087145 -0.005550 0.002197 +v 0.085493 0.007019 0.002673 +v 0.088405 0.002381 0.003214 +v 0.088629 0.002251 0.001630 +v 0.084958 -0.007358 0.002677 +v -0.048392 -0.004621 -0.111591 +v -0.047477 0.000596 -0.113017 +v -0.048992 -0.001154 -0.112518 +v -0.049108 0.002051 -0.112238 +v -0.048470 0.005411 -0.110890 +v -0.048385 -0.006852 -0.109301 +v -0.047906 0.007567 -0.108607 +v 0.009332 -0.010000 0.004200 +v 0.011880 -0.010000 0.003136 +v 0.009378 -0.010000 -0.004442 +v 0.010703 -0.010000 -0.006036 +v 0.001672 -0.010000 -0.010241 +v 0.004084 -0.010000 -0.011506 +v 0.004705 -0.010000 0.008964 +v 0.001884 -0.010000 0.012063 +v 0.007830 -0.010000 0.009210 +v -0.008241 -0.010000 0.005913 +v -0.010780 -0.010000 0.006083 +v -0.002270 -0.010000 0.010034 +v -0.004682 -0.010000 0.011145 +v -0.007479 -0.010000 -0.007194 +v -0.008326 -0.010000 -0.008765 +v -0.011804 -0.010000 -0.003120 +v -0.010141 -0.010000 0.000185 +v -0.003176 -0.010000 -0.011720 +v -0.012177 -0.012000 -0.000882 +v -0.008656 -0.012000 -0.008721 +v -0.001468 -0.012000 -0.012054 +v 0.006329 -0.012000 -0.010532 +v 0.011880 -0.012000 -0.003136 +v 0.011545 -0.012000 0.003438 +v 0.008163 -0.012000 0.009184 +v 0.000802 -0.012000 0.012116 +v -0.005029 -0.012000 0.010993 +v -0.010151 -0.012000 0.006784 +v -0.001392 -0.012000 0.008254 +v -0.007005 -0.012000 0.004149 +v -0.008071 -0.012000 -0.000540 +v 0.006569 -0.012000 0.005188 +v 0.007825 -0.012000 -0.002717 +v -0.001345 -0.012000 -0.007976 +v 0.003427 -0.012000 -0.007386 +v -0.006087 -0.012000 -0.005505 +v -0.009845 0.010000 -0.003279 +v -0.011880 0.010000 0.003136 +v -0.011545 0.010000 -0.003438 +v -0.008163 0.010000 -0.009184 +v -0.004549 0.010000 -0.009066 +v -0.001406 0.010000 0.010045 +v -0.006329 0.010000 0.010532 +v -0.008291 0.010000 0.006240 +v 0.008241 0.010000 0.005913 +v 0.008656 0.010000 0.008721 +v 0.003982 0.010000 0.009270 +v 0.001468 0.010000 0.012054 +v 0.006446 0.010000 -0.007917 +v 0.010151 0.010000 -0.006784 +v 0.010234 0.010000 -0.001044 +v 0.012177 0.010000 0.000882 +v -0.000802 0.010000 -0.012116 +v 0.000782 0.010000 -0.010058 +v 0.005029 0.010000 -0.010993 +v 0.011804 0.012000 0.003120 +v 0.011580 0.012000 -0.003471 +v 0.007153 0.012000 -0.010101 +v -0.001884 0.012000 -0.012063 +v -0.007830 0.012000 -0.009210 +v -0.011880 0.012000 -0.003136 +v -0.010703 0.012000 0.006036 +v -0.004084 0.012000 0.011506 +v 0.003176 0.012000 0.011720 +v 0.008326 0.012000 0.008765 +v 0.006669 0.012000 0.004578 +v 0.008209 0.012000 -0.001104 +v 0.001392 0.012000 0.008254 +v -0.005257 0.012000 0.006218 +v -0.008265 0.012000 0.000553 +v -0.000810 0.012000 -0.008048 +v -0.005705 0.012000 -0.005899 +v 0.004416 0.012000 -0.006918 +v 0.053019 -0.004926 0.000021 +v 0.052950 -0.005225 0.000997 +v 0.054221 -0.005130 0.001919 +v 0.053273 -0.005266 -0.001445 +v 0.056145 -0.004970 -0.001596 +v 0.054882 -0.005382 -0.002492 +v 0.057068 -0.005470 -0.001328 +v 0.057479 -0.005483 0.000279 +v 0.054060 -0.009123 -0.002376 +v 0.054176 -0.009600 -0.001763 +v 0.052591 -0.009096 -0.000605 +v 0.055748 -0.009701 -0.001750 +v 0.053442 -0.009555 0.001335 +v 0.055204 -0.009441 0.002139 +v 0.053901 -0.009386 0.001609 +v 0.056927 -0.009730 0.000396 +v 0.056913 -0.009342 0.001201 +v 0.056985 -0.009233 -0.001409 +v 0.050332 0.015653 0.000133 +v 0.053327 0.015686 -0.000862 +v 0.051533 0.015548 -0.003416 +v 0.054936 0.015614 -0.001836 +v 0.054880 0.015575 -0.004671 +v 0.058372 0.015552 -0.003512 +v 0.056555 0.015666 -0.001021 +v 0.059744 0.015624 0.000342 +v 0.056677 0.015651 0.000804 +v 0.057859 0.015576 0.003788 +v 0.054995 0.015594 0.001851 +v 0.054831 0.015617 0.004662 +v 0.053356 0.015656 0.000909 +v 0.051581 0.015494 0.003496 +v 0.055271 0.012525 0.004826 +v 0.052040 0.012525 0.003876 +v 0.050077 0.012525 0.000266 +v 0.051396 0.012525 -0.003221 +v 0.055525 0.012525 -0.005035 +v 0.059951 0.012525 -0.001057 +v 0.058366 0.012525 0.003530 +v 0.055507 0.012525 -0.003447 +v 0.058361 0.012525 -0.000094 +v 0.055702 0.012525 0.003412 +v 0.052213 0.012525 0.001709 +v 0.051961 0.012525 -0.001317 +v 0.055970 -0.003256 0.003075 +v 0.052764 -0.003261 0.002212 +v 0.051813 -0.003151 -0.000911 +v 0.053706 -0.003294 -0.002788 +v 0.056868 -0.003268 -0.002638 +v 0.058182 -0.003198 0.000334 +v 0.054684 -0.003492 -0.002008 +v 0.053286 -0.003481 -0.001079 +v 0.052998 -0.003494 0.000318 +v 0.053899 -0.003481 0.001707 +v 0.056229 -0.003500 0.001585 +v 0.056989 -0.003482 0.000425 +v 0.056622 -0.003466 -0.001235 +v 0.055943 -0.003744 -0.001671 +v 0.055322 -0.003675 0.001906 +v 0.056254 -0.005141 0.001523 +v 0.055050 -0.005222 0.001980 +v 0.056993 -0.004995 -0.000252 +v 0.053065 -0.009545 -0.000500 +v 0.053021 -0.008663 -0.000127 +v 0.054318 -0.008828 -0.001843 +v 0.054256 -0.006422 -0.001760 +v 0.055503 -0.006497 -0.001853 +v 0.054618 -0.006852 -0.002451 +v 0.056929 -0.005894 0.000168 +v 0.056120 -0.006009 0.001571 +v 0.057459 -0.006305 0.000649 +v 0.057336 -0.008710 0.001158 +v 0.056994 -0.008582 -0.001565 +v 0.056988 -0.008274 0.000128 +v 0.053023 -0.008338 -0.001588 +v 0.052642 -0.008237 0.001000 +v 0.053151 -0.007910 -0.000532 +v 0.055108 -0.008066 0.002584 +v 0.057276 -0.007928 0.001093 +v 0.056828 -0.007507 0.000768 +v 0.057246 -0.007809 -0.001038 +v 0.054275 -0.007643 -0.002363 +v 0.052811 -0.007547 -0.001228 +v 0.054280 -0.007241 -0.001848 +v 0.052765 -0.007436 0.001298 +v 0.053079 -0.007107 -0.000312 +v 0.055166 -0.007267 0.002508 +v 0.056831 -0.007170 0.001681 +v 0.056576 -0.006752 0.001116 +v 0.052896 -0.006775 -0.001382 +v 0.052469 -0.005928 -0.000378 +v 0.053704 -0.005774 0.002239 +v 0.053459 -0.005411 0.001156 +v 0.056031 -0.008932 -0.001627 +v 0.056927 -0.009051 -0.000293 +v 0.056519 -0.009125 0.001162 +v 0.055351 -0.009221 0.001896 +v 0.053835 -0.005589 -0.001518 +v 0.053837 -0.005998 -0.002196 +v 0.055330 -0.005697 -0.001915 +v 0.055686 -0.006103 -0.002389 +v 0.056546 -0.005799 -0.001109 +v 0.057025 -0.006200 -0.001408 +v 0.054283 -0.006499 0.002365 +v 0.056012 -0.006427 0.002264 +v 0.054733 -0.006089 0.001895 +v 0.053483 -0.006194 0.001191 +v 0.052677 -0.006638 0.001048 +v 0.056851 -0.006614 -0.000703 +v 0.056265 -0.006929 -0.002145 +v 0.054962 -0.006876 0.001967 +v 0.053483 -0.006999 0.001178 +v 0.056036 -0.007727 -0.002249 +v 0.056417 -0.007376 -0.001394 +v 0.053503 -0.007776 0.001310 +v 0.054288 -0.008012 -0.001846 +v 0.055691 -0.008417 0.001838 +v 0.052971 -0.008966 0.001517 +v 0.056411 -0.005575 0.002100 +v 0.053095 -0.005503 -0.000283 +v 0.053120 -0.006324 -0.000594 +v 0.057523 -0.007059 -0.000317 +v 0.055357 -0.007643 0.001898 +v 0.055007 -0.008456 -0.002503 +v 0.056078 -0.008137 -0.001604 +v 0.054939 -0.008860 0.002515 +v 0.053917 -0.008533 0.001606 +v 0.056588 0.014113 0.000917 +v 0.053413 0.014113 0.000917 +v 0.056588 0.014113 -0.000917 +v 0.053413 0.014113 -0.000917 +v -0.006303 -0.009439 -0.055889 +v 0.013834 -0.009452 -0.037575 +v -0.024880 -0.009451 -0.079249 +v 0.051724 -0.009451 -0.014971 +v 0.049065 -0.009451 -0.016900 +v 0.046162 -0.009451 -0.018438 +v -0.051001 -0.009274 -0.101176 +v 0.077649 -0.009333 0.006775 +v -0.054864 -0.004292 -0.104409 +v -0.055392 0.001869 -0.104852 +v -0.053531 0.006837 -0.103291 +v -0.050804 0.009329 -0.101009 +v 0.081685 0.004301 0.010169 +v 0.082209 -0.001878 0.010609 +v 0.080350 -0.006862 0.009048 +v 0.032189 -0.009452 -0.025375 +v -0.024880 0.009451 -0.079249 +v -0.022518 0.009451 -0.076966 +v -0.020500 0.009451 -0.074374 +v -0.011242 0.009452 -0.061817 +v 0.003958 0.009452 -0.045860 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vn 0.2403 -0.9557 0.1698 +vn 0.0108 -0.9999 0.0112 +vn 0.0128 -0.9999 -0.0053 +vn 0.0874 -0.9905 -0.1063 +vn 0.0129 -0.9999 -0.0058 +vn -0.0526 -0.9575 0.2835 +vn 0.0021 -0.9995 0.0311 +vn -0.0012 -1.0000 0.0068 +vn -0.0059 -0.9994 0.0336 +vn 0.0065 -0.9105 0.4134 +vn -0.0003 -1.0000 -0.0019 +vn -0.0001 -1.0000 -0.0001 +vn 0.0602 -0.2412 0.9686 +vn -0.0212 -0.0103 0.9997 +vn 0.0873 -0.0012 0.9962 +vn -0.1134 -0.0058 0.9935 +vn -0.2115 -0.0035 0.9774 +vn -0.2829 -0.2174 0.9342 +vn -0.1412 -0.4045 0.9036 +vn 0.2243 0.1703 0.9595 +vn 0.0716 -0.1015 0.9923 +vn 0.1668 -0.3443 0.9239 +vn 0.1784 -0.0007 0.9840 +vn 0.4660 -0.0134 0.8847 +vn 0.1563 0.3197 0.9346 +vn -0.1879 -0.0097 0.9821 +vn -0.2172 0.2568 0.9417 +vn -0.5355 0.2559 0.8048 +vn -0.6893 -0.0138 0.7244 +vn -0.8124 0.0513 0.5809 +vn -0.9496 0.0337 0.3117 +vn -0.9646 0.0647 0.2558 +vn -0.9974 0.0118 0.0705 +vn -0.9982 -0.0027 0.0591 +vn 0.6064 0.3760 0.7007 +vn -0.2248 0.6800 0.6979 +vn -0.4002 0.8274 0.3941 +vn 0.2210 0.7175 0.6605 +vn -0.7733 0.6325 -0.0444 +vn -0.6530 0.7488 0.1136 +vn -0.7227 0.6910 -0.0128 +vn 0.2261 0.9216 0.3157 +vn -0.1062 0.9489 0.2973 +vn -0.3571 0.9239 0.1377 +vn -0.0022 1.0000 0.0049 +vn -0.0203 0.9998 0.0030 +vn 0.0003 1.0000 0.0014 +vn -0.0360 0.9993 0.0106 +vn -0.0416 0.9991 0.0111 +vn -0.0061 1.0000 -0.0001 +vn -0.0052 1.0000 -0.0054 +vn -0.0009 1.0000 0.0004 +vn -0.0009 1.0000 0.0001 +vn 0.0003 0.9999 0.0110 +vn 0.0069 0.9995 0.0311 +vn 0.0002 1.0000 -0.0012 +vn 0.0039 1.0000 0.0055 +vn 0.0307 0.9994 0.0133 +vn -0.2813 0.9477 0.1508 +vn -0.0399 0.9990 0.0212 +vn -0.3299 0.9426 0.0512 +vn -0.1683 0.9830 0.0734 +vn -0.2108 0.9562 -0.2030 +vn -0.0033 0.9999 -0.0114 +vn 0.0458 0.9971 -0.0601 +vn 0.0683 0.9920 -0.1059 +vn -0.0220 0.9997 -0.0049 +vn 0.0436 0.9971 -0.0630 +vn 0.0169 0.9921 0.1246 +vn 0.0318 0.9966 0.0762 +vn 0.0011 0.9999 0.0103 +vn 0.0648 0.9954 -0.0706 +vn 0.1243 0.9859 -0.1123 +vn -0.0282 0.9996 0.0007 +vn -0.0040 1.0000 0.0025 +vn 0.0648 0.9935 -0.0933 +vn 0.2934 -0.7473 0.5962 +vn 0.5863 -0.6451 0.4901 +vn 0.3437 -0.4773 0.8087 +vn 0.6814 -0.4337 0.5896 +vn 0.5785 -0.2503 0.7763 +vn 0.7129 -0.3598 0.6019 +vn 0.7651 -0.1210 0.6325 +vn 0.5673 0.0727 0.8203 +vn 0.7641 0.0981 0.6376 +vn 0.7191 0.3009 0.6263 +vn 0.6082 0.5097 0.6085 +vn 0.6806 0.4829 0.5509 +vn 0.4712 0.7303 0.4946 +vn 0.3571 0.7997 0.4827 +vn 0.3613 0.7988 0.4810 +vn -0.9491 0.1035 0.2974 +vn -0.8490 -0.0157 0.5281 +vn -0.9136 0.0512 0.4034 +vn -0.7775 -0.0726 0.6246 +vn 0.5153 0.0475 0.8557 +vn 0.5057 0.0413 0.8617 +vn 0.5103 0.0443 0.8589 +vn 0.5190 0.0499 0.8533 +vn 0.8384 -0.0014 -0.5450 +vn 0.8926 -0.0537 -0.4477 +vn 0.8726 -0.0329 -0.4874 +vn 0.8109 0.0213 -0.5847 +vn -0.3257 0.0080 -0.9455 +vn -0.4626 -0.0606 -0.8845 +vn -0.3871 -0.0222 -0.9218 +vn -0.5084 -0.0846 -0.8569 +vn -0.0030 -1.0000 0.0075 +vn 0.0075 -0.9992 0.0401 +vn 0.1232 -0.8322 0.5406 +vn -0.0082 -0.9999 -0.0066 +vn -0.0281 -0.9996 -0.0012 +vn -0.0334 -0.9994 0.0029 +vn 0.1194 -0.9918 -0.0449 +vn -0.0375 -0.9992 0.0126 +vn -0.0087 -1.0000 0.0024 +vn -0.0264 -0.9996 0.0127 +vn 0.0368 -0.9987 0.0348 +vn 0.0019 -0.9972 0.0745 +vn -0.0173 -0.9997 0.0168 +vn 0.0349 -0.9959 0.0840 +vn 0.0351 -0.9963 0.0786 +vn 0.0980 -0.9941 0.0474 +vn -0.0191 -0.9996 0.0192 +vn -0.0339 -0.9993 0.0126 +vn -0.0328 -0.9994 0.0118 +vn -0.0531 -0.9982 0.0269 +vn -0.0775 -0.9963 -0.0369 +vn -0.0158 -0.9998 0.0111 +vn 0.0675 -0.9950 -0.0741 +vn 0.0641 -0.9934 -0.0954 +vn -0.0054 -1.0000 0.0029 +vn -0.0025 -1.0000 0.0025 +vn 0.1223 -0.9861 -0.1126 +vn 0.1134 0.9858 -0.1239 +vn 0.1115 0.9848 -0.1328 +vn 0.1115 0.9848 -0.1329 +vn 0.1116 0.9848 -0.1330 +vn 0.1117 0.9848 -0.1331 +vn 0.1110 0.9850 -0.1323 +vn 0.1118 0.9848 -0.1332 +vn 0.1118 0.9848 -0.1329 +vn 0.1087 0.9857 -0.1288 +vn 0.0821 0.9910 -0.1057 +vn 0.0922 0.9906 -0.1013 +vn 0.1084 0.9860 -0.1268 +vn 0.1115 0.9848 -0.1330 +vn 0.1115 0.9848 -0.1331 +vn 0.1116 0.9848 -0.1332 +vn 0.1116 0.9848 -0.1331 +vn 0.1083 0.9862 -0.1249 +vn 0.1024 0.9887 -0.1096 +vn 0.0995 0.9896 -0.1037 +vn 0.1086 -0.9863 -0.1245 +vn -0.2277 -0.9491 -0.2176 +vn 0.1113 -0.9838 -0.1406 +vn 0.1004 -0.9843 -0.1453 +vn -0.6534 0.6998 0.2886 +vn -0.7998 0.5267 0.2880 +vn -0.7320 0.5068 0.4554 +vn -0.9239 0.0031 0.3826 +vn -0.9402 0.1076 0.3232 +vn -0.8919 0.1444 0.4286 +vn -0.8512 -0.2505 0.4613 +vn -0.8607 -0.3543 0.3655 +vn -0.9255 -0.2801 0.2551 +vn -0.8359 0.0939 0.5408 +vn -0.9667 -0.1179 0.2272 +vn -0.8266 -0.4620 0.3215 +vn -0.9268 0.2591 0.2718 +vn -0.8765 0.1737 0.4490 +vn -0.8477 -0.1751 0.5007 +vn -0.7972 0.4005 0.4518 +vn -0.7833 -0.3426 0.5187 +vn -0.6830 -0.6780 0.2717 +vn -0.9659 0.0257 0.2575 +vn 0.1291 -0.0057 0.9916 +vn 0.0627 0.0069 0.9980 +vn -0.9528 0.0056 0.3035 +vn -0.9475 0.0068 0.3197 +vn -0.8116 0.0024 0.5842 +vn -0.8273 -0.0026 0.5617 +vn -0.5775 0.0016 0.8164 +vn -0.6034 -0.0069 0.7974 +vn -0.2270 -0.0034 0.9739 +vn -0.3102 0.0023 0.9507 +vn 0.0619 0.9925 -0.1057 +vn 0.0748 0.9891 -0.1265 +vn 0.0826 0.9871 -0.1375 +vn 0.0792 0.9861 -0.1463 +vn 0.0893 0.9886 -0.1212 +vn 0.1103 0.9888 -0.1006 +vn 0.1424 0.9759 -0.1653 +vn 0.1321 0.9860 -0.1017 +vn 0.1360 0.9855 -0.1018 +vn 0.1279 0.9851 -0.1151 +vn 0.0901 -0.9843 -0.1515 +vn 0.0760 -0.9858 -0.1497 +vn 0.1361 -0.9855 -0.1015 +vn 0.1363 -0.9853 -0.1028 +vn 0.1125 -0.9881 -0.1048 +vn 0.1236 -0.9829 -0.1363 +vn 0.1129 -0.9877 -0.1082 +vn 0.0914 -0.9882 -0.1227 +vn 0.0803 -0.9866 -0.1419 +vn 0.0833 -0.9864 -0.1419 +vn 0.1283 -0.9850 -0.1154 +vn 0.9782 -0.0289 -0.2058 +vn 0.9114 0.2969 -0.2849 +vn 0.9619 0.0097 -0.2733 +vn 0.9361 0.2823 -0.2098 +vn -0.6330 0.1622 0.7570 +vn -0.7352 0.0396 0.6767 +vn -0.6473 0.0116 0.7621 +vn -0.7318 0.0388 0.6804 +vn -0.8005 0.0497 0.5973 +vn -0.7446 -0.0032 0.6676 +vn -0.7171 -0.0031 0.6969 +vn -0.7971 0.2398 0.5542 +vn -0.7400 -0.0069 0.6725 +vn -0.9592 -0.0355 -0.2806 +vn -0.9593 -0.0340 -0.2802 +vn -0.9001 0.3461 -0.2647 +vn -0.9518 0.1399 -0.2729 +vn -0.2316 0.0099 -0.9728 +vn -0.3598 0.0200 -0.9328 +vn -0.2967 0.2865 -0.9110 +vn -0.2877 0.0254 -0.9574 +vn -0.4429 0.0255 -0.8962 +vn -0.2968 0.3168 -0.9008 +vn 0.9261 0.1552 -0.3438 +vn 0.9071 0.0256 -0.4201 +vn 0.9275 0.1285 -0.3511 +vn 0.8963 0.3040 -0.3227 +vn 0.8958 0.0159 -0.4442 +vn 0.8902 0.0288 -0.4547 +vn -0.0125 0.9999 -0.0012 +vn -0.0051 1.0000 -0.0001 +vn -0.0139 0.9999 -0.0002 +vn -0.0022 1.0000 -0.0040 +vn -0.0024 1.0000 -0.0001 +vn -0.2933 0.9186 0.2650 +vn -0.2414 0.9195 0.3101 +vn -0.5099 0.0120 -0.8601 +vn -0.2210 0.2343 -0.9467 +vn -0.2348 0.0064 -0.9720 +vn -0.2241 0.3218 -0.9199 +vn 0.9920 0.1222 -0.0310 +vn 0.9117 0.4040 -0.0745 +vn 0.9466 0.0196 -0.3218 +vn 0.9661 0.0468 -0.2540 +vn 0.8909 0.0095 -0.4541 +vn 0.7690 0.0317 -0.6385 +vn 0.7258 0.0027 -0.6879 +vn 0.7275 0.0148 -0.6859 +vn 0.6862 0.0152 -0.7273 +vn 0.7489 -0.0169 0.6625 +vn 0.9692 -0.0306 0.2445 +vn 0.8383 0.3188 0.4423 +vn 0.9517 0.2687 0.1484 +vn -0.5434 -0.0090 0.8394 +vn -0.5468 0.0006 0.8373 +vn -0.5013 0.0111 0.8652 +vn -0.5127 0.0210 0.8583 +vn -0.5669 0.2266 0.7920 +vn -0.5113 -0.0076 0.8594 +vn -0.7659 0.0063 -0.6430 +vn -0.6232 0.0116 -0.7820 +vn -0.7664 0.0086 -0.6423 +vn -0.3048 0.0111 -0.9524 +vn -0.1369 0.9699 -0.2014 +vn 0.0080 1.0000 0.0002 +vn -0.0016 0.9992 -0.0404 +vn 0.0845 0.9543 0.2867 +vn 0.1895 0.9808 0.0463 +vn -0.1313 0.9605 0.2455 +vn 0.0026 0.9999 -0.0109 +vn -0.2802 0.9582 0.0574 +vn 0.9580 -0.0258 -0.2857 +vn 0.9360 -0.2615 -0.2357 +vn 0.9807 0.0210 -0.1945 +vn 0.9821 0.0484 -0.1821 +vn -0.4806 -0.0488 -0.8756 +vn -0.7665 -0.0186 -0.6420 +vn -0.5361 -0.0276 -0.8437 +vn -0.3007 -0.0206 -0.9535 +vn -0.2572 -0.0689 -0.9639 +vn -0.2723 -0.3056 -0.9124 +vn -0.1721 0.0191 -0.9849 +vn -0.7959 -0.3829 -0.4690 +vn -0.9918 -0.1180 -0.0483 +vn -0.9381 0.0181 -0.3460 +vn -0.9598 0.0480 -0.2765 +vn -0.6525 0.0267 0.7573 +vn -0.6876 -0.0330 0.7253 +vn -0.6672 -0.0046 0.7449 +vn -0.7463 -0.0179 0.6653 +vn -0.7469 0.0025 0.6649 +vn -0.8023 -0.0527 0.5946 +vn -0.7392 -0.0156 0.6733 +vn -0.7282 -0.0167 0.6852 +vn -0.6053 0.0416 0.7949 +vn -0.6154 0.0233 0.7879 +vn 0.8021 -0.4371 -0.4069 +vn 0.9151 -0.0097 -0.4031 +vn 0.8794 0.0107 -0.4760 +vn 0.9452 -0.2111 -0.2491 +vn 0.9103 -0.0459 -0.4114 +vn 0.9086 -0.2669 -0.3212 +vn -0.2513 -0.9654 0.0701 +vn -0.3726 -0.9058 -0.2018 +vn 0.0149 -0.9999 -0.0014 +vn 0.2955 -0.9348 -0.1970 +vn -0.0225 -0.9996 0.0169 +vn -0.0312 -0.9994 0.0147 +vn 0.0345 -0.9917 0.1238 +vn 0.1933 -0.9794 -0.0590 +vn -0.4141 -0.3115 0.8553 +vn -0.4922 -0.0054 0.8705 +vn -0.5378 -0.0164 0.8429 +vn -0.5160 -0.2419 0.8217 +vn -0.5194 -0.3081 0.7971 +vn -0.5439 -0.1849 0.8185 +vn -0.5496 -0.0139 0.8353 +vn 0.8568 -0.2856 0.4293 +vn 0.9632 0.0406 0.2656 +vn 0.7422 0.0244 0.6698 +vn 0.9636 0.0470 0.2633 +vn 0.6031 0.0218 -0.7973 +vn 0.7305 -0.0051 -0.6829 +vn 0.6459 -0.0145 -0.7633 +vn 0.7716 -0.0370 -0.6350 +vn 0.9095 -0.0081 -0.4156 +vn 0.9652 -0.0413 -0.2582 +vn 0.8974 -0.4396 -0.0383 +vn 0.9949 -0.0966 -0.0277 +vn 0.8945 0.0005 -0.4471 +vn -0.2283 -0.0016 -0.9736 +vn 0.0339 -0.2864 -0.9575 +vn -0.0965 -0.0196 -0.9951 +vn -0.1613 -0.2758 -0.9476 +vn -0.0077 -0.4007 -0.9162 +vn -0.0654 -0.3584 -0.9313 +vn 0.0348 -0.0032 -0.9994 +vn -0.1372 -0.9665 0.2170 +vn -0.1357 -0.9792 0.1511 +vn 0.0033 -1.0000 -0.0038 +vn -0.2068 -0.9093 0.3612 +vn 0.2221 -0.9564 -0.1895 +vn 0.2623 -0.9600 -0.0981 +vn 0.1681 -0.9390 0.3001 +vn 0.2840 -0.9573 -0.0544 +vn -0.0126 -0.9343 -0.3561 +vn 0.2724 -0.9622 0.0019 +vn -0.2566 -0.9246 -0.2816 +vn -0.9267 0.1448 -0.3467 +vn -0.7645 0.0081 -0.6446 +vn -0.8871 -0.2948 -0.3553 +vn -0.7429 -0.2305 -0.6284 +vn -0.6791 -0.4647 -0.5683 +vn -0.8296 -0.5279 -0.1819 +vn -0.5217 -0.7440 -0.4174 +vn -0.5722 -0.7998 -0.1817 +vn -0.4029 -0.9116 0.0811 +vn -0.7323 0.2693 -0.6255 +vn -0.7066 0.4104 -0.5765 +vn -0.8058 0.5315 -0.2614 +vn -0.5562 0.6789 -0.4793 +vn -0.5954 0.7814 -0.1869 +vn -0.8746 0.0048 0.4848 +vn -0.7181 -0.3197 0.6181 +vn -0.6708 -0.0192 -0.7414 +vn -0.7218 -0.1937 -0.6645 +vn -0.8672 -0.3654 -0.3384 +vn -0.9916 0.0195 0.1277 +vn -0.9931 0.0160 0.1162 +vn -0.9514 -0.0067 0.3079 +vn -0.5910 -0.2180 -0.7767 +vn -0.6376 -0.0275 -0.7699 +vn -0.9526 -0.0011 -0.3042 +vn -0.8928 -0.2407 -0.3807 +vn -0.9407 0.0176 -0.3387 +vn -0.8594 -0.0029 -0.5113 +vn -0.9676 -0.0480 0.2480 +vn -0.8437 -0.3273 0.4254 +vn -0.8885 -0.4588 0.0077 +vn -0.4867 -0.8732 0.0249 +vn -0.7308 -0.0487 -0.6808 +vn -0.7029 -0.4917 0.5141 +vn -0.3537 -0.5632 -0.7468 +vn -0.5824 -0.6982 0.4163 +vn -0.5595 -0.6469 0.5181 +vn -0.5673 -0.6378 0.5210 +vn -0.5844 -0.5159 0.6263 +vn -0.4193 -0.8303 0.3671 +vn -0.4129 -0.8173 0.4020 +vn -0.5389 -0.6634 0.5191 +vn -0.2973 -0.8383 -0.4570 +vn -0.2315 -0.6247 -0.7457 +vn 0.0365 -0.7903 -0.6116 +vn -0.0608 -0.7933 -0.6058 +vn 0.0174 -0.8581 -0.5131 +vn -0.1800 -0.6626 -0.7270 +vn -0.2594 -0.9331 -0.2490 +vn -0.2029 -0.6328 -0.7472 +vn 0.6639 -0.0635 -0.7451 +vn 0.6446 -0.3001 -0.7031 +vn 0.3928 -0.2937 -0.8715 +vn 0.1676 0.0124 -0.9858 +vn 0.0713 -0.2593 -0.9632 +vn 0.1757 0.0086 -0.9844 +vn 0.6339 -0.6939 -0.3415 +vn -0.0670 -0.0803 0.9945 +vn 0.6925 0.0580 0.7190 +vn 0.7225 0.0370 0.6904 +vn 0.7044 0.0498 0.7080 +vn 0.7396 0.0244 0.6726 +vn 0.9980 -0.0563 0.0279 +vn 0.9206 -0.3889 0.0347 +vn -0.2438 -0.7034 0.6677 +vn -0.0868 -0.8794 0.4681 +vn 0.7191 -0.6766 -0.1585 +vn 0.8642 -0.4770 -0.1599 +vn 0.1771 -0.8532 0.4906 +vn 0.0899 -0.6779 0.7296 +vn 0.6538 -0.7494 -0.1045 +vn 0.7556 -0.6299 -0.1795 +vn 0.7527 -0.6580 0.0212 +vn 0.6632 -0.4820 0.5726 +vn 0.5710 -0.7745 -0.2722 +vn 0.8016 -0.5090 -0.3136 +vn 0.5434 -0.8077 -0.2286 +vn 0.3288 0.0214 0.9442 +vn 0.2161 -0.0193 0.9762 +vn 0.4807 -0.2480 0.8411 +vn -0.4953 -0.4502 0.7430 +vn -0.0205 -0.8283 0.5598 +vn -0.3909 -0.6940 0.6046 +vn -0.4500 -0.7833 0.4289 +vn 0.4868 -0.6958 0.5281 +vn 0.1641 -0.5756 0.8011 +vn -0.6699 -0.7092 -0.2196 +vn -0.6247 -0.6357 -0.4534 +vn -0.3718 -0.8610 -0.3471 +vn -0.6720 -0.5940 0.4423 +vn -0.8124 -0.5640 -0.1479 +vn 0.9643 -0.0589 -0.2581 +vn 0.9102 -0.4118 -0.0449 +vn 0.9421 -0.2247 -0.2490 +vn 0.6428 -0.7384 -0.2040 +vn -0.5645 -0.3766 -0.7345 +vn -0.6683 -0.6812 -0.2990 +vn -0.8142 -0.5098 -0.2780 +vn -0.5631 -0.7845 -0.2596 +vn -0.3844 -0.8785 -0.2838 +vn -0.6764 0.0039 -0.7365 +vn -0.5255 -0.0334 -0.8502 +vn -0.6506 -0.3906 -0.6513 +vn -0.1414 -0.7459 -0.6509 +vn 0.5182 0.0336 -0.8546 +vn 0.5725 -0.2491 -0.7812 +vn 0.8761 -0.4045 -0.2624 +vn 0.4515 -0.7494 -0.4842 +vn 0.5461 -0.5724 -0.6117 +vn 0.6245 -0.7800 0.0411 +vn 0.6103 -0.7380 -0.2879 +vn -0.1447 -0.5830 -0.7995 +vn 0.0612 -0.7248 -0.6862 +vn 0.4766 -0.6191 -0.6241 +vn 0.1037 -0.8702 -0.4817 +vn 0.8459 0.0481 -0.5312 +vn 0.9502 0.2994 -0.0863 +vn 0.4784 0.7646 -0.4319 +vn 0.6868 0.7247 -0.0560 +vn 0.5996 0.6767 -0.4274 +vn 0.5434 0.6696 -0.5064 +vn 0.8535 0.4082 -0.3241 +vn 0.5914 0.7434 -0.3124 +vn 0.5650 0.6221 -0.5420 +vn 0.5782 0.7411 -0.3412 +vn 0.6048 0.7651 -0.2212 +vn 0.3394 0.0623 -0.9386 +vn 0.7752 -0.0041 -0.6317 +vn 0.8002 -0.0211 -0.5993 +vn 0.4088 0.2969 0.8630 +vn 0.3115 -0.0189 0.9501 +vn 0.0732 0.2495 0.9656 +vn 0.4753 0.7596 0.4439 +vn 0.4113 0.6726 -0.6151 +vn 0.3144 0.7274 -0.6100 +vn 0.3864 0.7341 -0.5584 +vn -0.1076 0.7292 0.6758 +vn -0.3320 0.7666 -0.5497 +vn -0.0836 0.9206 -0.3815 +vn -0.8959 0.2527 0.3654 +vn -0.9954 -0.0031 0.0955 +vn -0.9800 0.1887 0.0626 +vn -0.9941 0.0026 0.1081 +vn -0.5123 0.6958 0.5034 +vn -0.2974 0.7685 0.5665 +vn -0.4371 0.5899 0.6790 +vn -0.3246 0.7942 0.5136 +vn -0.1880 0.6172 -0.7640 +vn -0.6811 0.7181 -0.1428 +vn -0.4646 0.6039 -0.6477 +vn -0.6526 0.5344 -0.5371 +vn -0.5920 0.3346 0.7332 +vn -0.3248 0.8510 0.4126 +vn -0.4808 0.7661 0.4266 +vn 0.9722 0.2031 0.1161 +vn 0.9353 -0.0314 0.3525 +vn 0.9040 -0.0145 0.4273 +vn 0.8457 0.1559 0.5104 +vn 0.6253 0.0505 0.7787 +vn 0.0488 -0.0305 0.9983 +vn -0.0435 0.0697 0.9966 +vn 0.0232 -0.0210 0.9995 +vn -0.0708 0.1165 0.9907 +vn -0.0805 0.2534 0.9640 +vn 0.2962 0.7191 0.6286 +vn 0.2188 0.6877 0.6922 +vn 0.2178 0.6645 0.7149 +vn 0.3210 0.7385 0.5930 +vn 0.8366 0.5419 -0.0801 +vn 0.4536 0.7697 0.4493 +vn -0.9260 0.1735 0.3353 +vn -0.2815 0.9181 0.2790 +vn -0.5596 0.8215 0.1095 +vn -0.5989 0.6643 0.4472 +vn -0.5807 0.6853 0.4394 +vn -0.6037 0.5857 0.5409 +vn -0.5856 0.5892 0.5566 +vn -0.2639 0.9269 0.2669 +vn -0.6377 0.5728 0.5150 +vn 0.7064 0.6021 -0.3722 +vn 0.8150 0.5358 -0.2208 +vn 0.5820 0.8011 -0.1396 +vn 0.4221 0.8963 -0.1355 +vn 0.5066 0.8363 -0.2096 +vn 0.6314 0.7190 -0.2904 +vn 0.3100 0.9263 -0.2142 +vn 0.2698 0.9413 -0.2031 +vn 0.1919 0.8978 -0.3964 +vn -0.8300 0.5563 0.0402 +vn 0.6170 0.7346 -0.2824 +vn 0.3156 -0.0112 -0.9488 +vn 0.2103 0.0209 -0.9774 +vn 0.4565 0.0256 -0.8894 +vn 0.4024 -0.0089 -0.9154 +vn 0.7081 0.0454 -0.7047 +vn -0.5925 0.0629 -0.8031 +vn -0.6745 0.7105 -0.2003 +vn 0.3900 0.6773 -0.6239 +vn -0.1379 0.7005 -0.7002 +vn -0.4243 0.6017 -0.6767 +vn -0.2537 0.6253 -0.7380 +vn -0.2524 0.6271 -0.7369 +vn -0.2477 0.4819 -0.8405 +vn -0.2176 0.8916 -0.3971 +vn -0.2237 0.3929 -0.8920 +vn -0.0142 0.9999 0.0008 +vn 0.0053 1.0000 -0.0001 +vn -0.0094 0.9999 0.0145 +vn 0.0187 0.9998 0.0024 +vn 0.0230 0.9997 0.0009 +vn -0.0248 0.9995 -0.0209 +vn -0.0151 0.9997 -0.0166 +vn 0.0157 0.9999 -0.0015 +vn 0.0028 1.0000 0.0094 +vn -0.0127 0.9999 0.0021 +vn -0.0000 1.0000 -0.0000 +vn -0.3225 -0.0906 0.9422 +vn -0.7916 0.1134 0.6004 +vn -0.9964 -0.0769 0.0354 +vn -0.6303 -0.0179 -0.7761 +vn -0.8011 0.0686 -0.5946 +vn -0.7419 0.0358 -0.6696 +vn -0.5432 -0.0548 -0.8378 +vn 0.4074 -0.0125 -0.9132 +vn 0.2239 0.0546 -0.9731 +vn 0.2890 0.0315 -0.9568 +vn 0.4712 -0.0369 -0.8812 +vn 0.9736 0.0004 -0.2282 +vn 0.9507 0.0357 -0.3080 +vn 0.9601 0.0227 -0.2788 +vn 0.9809 -0.0144 -0.1941 +vn 0.6450 0.0009 0.7642 +vn 0.5570 0.0546 0.8287 +vn 0.6018 0.0281 0.7981 +vn 0.5203 0.0753 0.8506 +vn -0.5106 0.6090 0.6069 +vn -0.4973 0.6448 0.5804 +vn -0.4987 0.6413 0.5831 +vn -0.5125 0.6037 0.6107 +vn -0.6420 0.0137 0.7666 +vn -0.6397 0.0066 0.7686 +vn -0.6404 0.0088 0.7680 +vn -0.6425 0.0152 0.7662 +vn 0.7528 -0.0268 0.6578 +vn 0.7631 0.1504 0.6285 +vn 0.4741 0.7622 0.4408 +vn 0.7539 0.2813 0.5937 +vn 0.1196 0.9822 -0.1450 +vn 0.2625 0.8783 -0.3996 +vn 0.1160 0.9829 -0.1430 +vn 0.1224 0.9816 -0.1463 +vn 0.0842 0.9833 -0.1613 +vn 0.0971 0.9833 -0.1537 +vn 0.0949 0.9836 -0.1533 +vn 0.1131 0.9831 -0.1436 +vn 0.1187 0.9838 -0.1345 +vn 0.2924 0.9453 0.1445 +vn 0.3900 0.9154 -0.0998 +vn 0.1308 0.9816 -0.1389 +vn 0.1284 0.9823 -0.1364 +vn 0.1140 0.9833 -0.1422 +vn 0.1141 0.9833 -0.1421 +vn 0.1167 0.9829 -0.1424 +vn 0.1182 0.9834 -0.1375 +vn 0.1199 0.9827 -0.1410 +vn -0.0100 -0.5486 0.8360 +vn 0.1047 -0.8443 0.5256 +vn -0.0483 -0.8763 0.4793 +vn 0.0450 -0.9601 0.2762 +vn -0.1300 -0.3177 0.9392 +vn -0.1599 -0.7122 0.6835 +vn 0.0817 -0.7803 0.6201 +vn -0.1674 -0.7704 0.6152 +vn -0.0682 -0.7585 0.6481 +vn -0.3539 -0.7813 0.5141 +vn -0.2825 -0.7508 0.5970 +vn -0.5839 -0.7090 0.3954 +vn -0.5195 -0.7738 0.3624 +vn -0.8155 -0.5282 0.2366 +vn -0.6416 -0.7444 0.1848 +vn -0.3920 -0.9170 0.0738 +vn -0.3174 -0.9423 0.1062 +vn -0.3520 -0.9324 0.0817 +vn -0.8083 -0.5370 0.2415 +vn -0.5470 -0.7753 0.3158 +vn -0.5993 -0.7404 0.3045 +vn -0.6007 -0.7289 0.3284 +vn -0.6558 -0.6900 0.3062 +vn -0.4440 0.8660 0.2301 +vn -0.8008 0.4810 0.3569 +vn -0.2047 0.9763 0.0706 +vn -0.1931 0.9800 0.0471 +vn -0.6422 0.7424 0.1910 +vn -0.6592 0.7071 0.2558 +vn -0.7269 0.6719 0.1420 +vn -0.6350 0.7533 0.1712 +vn -0.5938 0.7747 0.2173 +vn -0.5387 0.7786 0.3218 +vn -0.4559 0.7686 0.4487 +vn -0.3594 0.7670 0.5315 +vn -0.2255 0.7774 0.5872 +vn -0.0984 0.7599 0.6426 +vn 0.0574 0.7636 0.6431 +vn 0.1319 0.8086 0.5734 +vn 0.1167 0.8342 0.5390 +vn 0.1541 0.6112 0.7763 +vn 0.0900 0.5572 0.8255 +vn 0.0931 0.5652 0.8197 +vn -0.1998 -0.6119 -0.7653 +vn -0.5663 -0.4790 -0.6707 +vn -0.3574 -0.6500 -0.6706 +vn -0.5821 -0.4464 -0.6796 +vn -0.7980 -0.5786 -0.1688 +vn -0.9156 -0.0568 0.3981 +vn -0.8942 -0.0020 0.4477 +vn -0.9013 0.0398 0.4314 +vn -0.5983 -0.6688 0.4414 +vn -0.3678 -0.1940 0.9095 +vn -0.5181 -0.0774 0.8518 +vn -0.4138 -0.0219 0.9101 +vn 0.6548 -0.6254 0.4244 +vn 0.5502 -0.6826 0.4810 +vn 0.8113 -0.5139 0.2786 +vn 0.7785 -0.6273 0.0214 +vn 0.8039 -0.5758 -0.1488 +vn 0.5871 -0.7220 -0.3661 +vn 0.5327 -0.7048 -0.4686 +vn 0.3149 -0.6623 -0.6799 +vn 0.4072 -0.6570 -0.6345 +vn 0.0550 -0.7798 -0.6236 +vn 0.6908 0.7206 -0.0589 +vn 0.7137 0.6961 0.0772 +vn 0.7017 0.7025 -0.1188 +vn -0.3795 0.3424 -0.8595 +vn -0.6514 0.6183 -0.4398 +vn -0.7144 0.2756 -0.6432 +vn 0.9602 0.0008 0.2792 +vn 0.5935 0.7179 0.3638 +vn 0.6566 0.2978 0.6930 +vn 0.5862 0.6430 0.4929 +vn 0.4087 0.0161 0.9125 +vn 0.4860 0.0266 0.8735 +vn -0.0622 0.8307 0.5532 +vn -0.4937 0.0275 0.8692 +vn -0.5497 0.0221 0.8351 +vn -0.4870 0.0476 0.8721 +vn -0.5030 0.7143 0.4867 +vn -0.8990 0.0516 0.4349 +vn -0.6646 0.7421 0.0867 +vn -0.9747 0.0233 -0.2222 +vn -0.6781 0.6703 -0.3015 +vn 0.0963 0.7073 -0.7003 +vn -0.3111 0.6277 -0.7136 +vn 0.0211 0.7254 -0.6880 +vn 0.3866 0.4542 -0.8026 +vn 0.7940 0.4784 -0.3751 +vn 0.8066 0.4423 -0.3921 +vn 0.4246 0.7940 -0.4350 +vn 0.4097 0.4060 -0.8169 +vn 0.4277 -0.8788 -0.2117 +vn 0.4451 -0.5524 -0.7048 +vn 0.7206 -0.4758 -0.5043 +vn 0.5126 -0.3281 -0.7935 +vn 0.5411 0.0581 -0.8390 +vn 0.8299 -0.0048 -0.5580 +vn 0.4802 0.4855 -0.7305 +vn 0.6653 0.2841 -0.6904 +vn 0.5874 0.6928 -0.4184 +vn 0.1034 0.9025 -0.4181 +vn 0.3021 0.9178 -0.2578 +vn 0.5308 0.6979 -0.4808 +vn 0.5216 0.5795 -0.6262 +vn 0.6771 0.3515 -0.6465 +vn 0.2259 0.3963 -0.8899 +vn 0.5743 0.0329 -0.8180 +vn 0.7287 -0.0474 -0.6832 +vn 0.6613 -0.4230 -0.6195 +vn 0.6055 -0.3315 -0.7235 +vn 0.4245 -0.7470 -0.5117 +vn 0.5133 -0.7174 -0.4709 +vn 0.2966 -0.9181 -0.2630 +vn 0.1682 -0.9645 -0.2036 +vn 0.1437 -0.9834 -0.1105 +vn 0.1341 -0.9836 -0.1205 +vn 0.4732 -0.7571 -0.4505 +vn 0.6818 -0.4731 -0.5580 +vn 0.7680 -0.0086 -0.6404 +vn 0.7021 0.4724 -0.5329 +vn 0.6264 0.4811 -0.6134 +vn 0.5217 0.7246 -0.4504 +vn 0.5277 -0.6105 -0.5906 +vn 0.6761 -0.2826 -0.6804 +vn 0.6562 0.0756 -0.7508 +vn 0.2159 -0.9003 -0.3780 +vn 0.2501 -0.9134 -0.3212 +vn 0.4271 -0.6064 -0.6707 +vn 0.5720 -0.2222 -0.7896 +vn 0.5357 0.0761 -0.8410 +vn 0.5072 0.4809 -0.7152 +vn 0.4485 0.7116 -0.5407 +vn 0.3526 0.7310 -0.5842 +vn 0.4759 -0.2411 -0.8458 +vn 0.3995 0.5794 -0.7104 +vn 0.4603 0.1845 -0.8684 +vn 0.5908 0.4689 -0.6566 +vn 0.9791 -0.1602 -0.1256 +vn 0.8935 -0.2483 0.3741 +vn 0.7905 -0.5812 -0.1933 +vn 0.6534 0.7197 0.2348 +vn 0.8822 0.2535 0.3969 +vn 0.8193 0.5626 0.1107 +vn 0.9662 0.2291 -0.1180 +vn 0.5585 -0.7919 0.2472 +vn -0.1058 -0.7234 -0.6823 +vn -0.0408 -0.4982 -0.8661 +vn -0.0189 -0.4204 -0.9071 +vn -0.0457 0.0696 -0.9965 +vn -0.4744 -0.1594 -0.8658 +vn -0.5280 0.2389 -0.8150 +vn -0.4187 0.5626 -0.7129 +vn -0.3398 -0.8071 -0.4828 +vn -0.4059 -0.7153 -0.5688 +vn -0.1263 0.7066 -0.6963 +vn -0.3143 0.8147 -0.4873 +vn -0.0466 -0.2404 -0.9696 +vn -0.8765 -0.2771 -0.3937 +vn -0.8813 -0.2274 -0.4141 +vn -0.7129 0.0315 -0.7006 +vn -0.6774 0.0957 -0.7293 +vn -0.4255 -0.1675 -0.8893 +vn -0.4119 -0.2034 -0.8883 +vn 0.0543 0.1209 -0.9912 +vn 0.0289 0.1886 -0.9816 +vn 0.1649 -0.1928 -0.9673 +vn 0.1853 -0.2543 -0.9492 +vn 0.6032 0.3216 -0.7299 +vn 0.7427 -0.3707 -0.5576 +vn 0.9212 0.3707 -0.1182 +vn 0.9862 -0.1576 0.0503 +vn 0.9527 -0.0970 0.2879 +vn 0.9431 -0.1106 0.3135 +vn 0.8331 0.0979 0.5444 +vn 0.8249 0.1302 0.5500 +vn 0.4202 0.0133 0.9073 +vn 0.4318 0.0602 0.9000 +vn 0.3751 -0.1411 0.9162 +vn 0.3645 -0.1729 0.9150 +vn -0.1466 0.0769 0.9862 +vn -0.1378 0.1006 0.9853 +vn -0.3951 0.0160 0.9185 +vn -0.4535 0.0126 0.8912 +vn -0.6343 0.0667 0.7702 +vn -0.6333 0.0709 0.7707 +vn -0.9453 -0.2097 0.2498 +vn -0.9495 0.2953 0.1057 +vn 0.0000 -1.0000 0.0000 +vn 0.9752 0.2190 -0.0331 +vn 0.9340 -0.2581 -0.2469 +vn 0.7908 0.3097 -0.5280 +vn 0.6030 -0.3131 -0.7338 +vn 0.1928 0.2009 -0.9605 +vn 0.1841 0.2304 -0.9555 +vn 0.2071 0.1503 -0.9667 +vn 0.2101 0.1393 -0.9677 +vn -0.3751 -0.1411 -0.9162 +vn -0.3645 -0.1729 -0.9150 +vn -0.4202 0.0133 -0.9073 +vn -0.4318 0.0602 -0.9000 +vn -0.8249 0.1302 -0.5500 +vn -0.8331 0.0979 -0.5444 +vn -0.9527 -0.0970 -0.2879 +vn -0.9431 -0.1106 -0.3135 +vn -0.9862 -0.1576 -0.0503 +vn -0.9210 0.3711 0.1183 +vn -0.7427 -0.3707 0.5576 +vn -0.6032 0.3216 0.7299 +vn -0.1649 -0.1928 0.9673 +vn -0.1853 -0.2543 0.9492 +vn -0.0543 0.1209 0.9912 +vn -0.0289 0.1886 0.9816 +vn 0.4255 -0.1675 0.8893 +vn 0.4119 -0.2034 0.8883 +vn 0.7129 0.0315 0.7006 +vn 0.6774 0.0961 0.7293 +vn 0.8813 -0.2274 0.4141 +vn 0.8765 -0.2771 0.3937 +vn -0.2934 -0.0351 -0.9553 +vn -0.4729 0.0147 -0.8810 +vn -0.1829 0.0009 -0.9831 +vn 0.5587 -0.0371 -0.8286 +vn 0.3539 0.0243 -0.9350 +vn 0.6499 0.0229 -0.7596 +vn 0.8962 -0.0395 -0.4419 +vn 0.9939 0.0279 -0.1068 +vn 0.9227 -0.0263 0.3847 +vn 0.8268 0.0166 0.5622 +vn 0.4553 -0.0132 0.8902 +vn 0.3892 0.0014 0.9212 +vn 0.1500 -0.0091 0.9886 +vn 0.1424 -0.0067 0.9898 +vn -0.5486 -0.0066 0.8361 +vn -0.4836 0.0204 0.8751 +vn -0.5027 0.0126 0.8644 +vn -0.9998 -0.0176 -0.0008 +vn -0.9812 0.0332 0.1902 +vn -0.9579 0.0359 -0.2849 +vn -0.6975 -0.0359 -0.7157 +vn -0.2004 -0.0084 0.9797 +vn -0.1349 0.0035 0.9909 +vn -0.2116 -0.0103 0.9773 +vn 0.4104 -0.0044 0.9119 +vn 0.4539 0.0054 0.8910 +vn 0.4020 -0.0062 0.9156 +vn 0.9293 -0.0088 0.3691 +vn 0.9287 -0.0093 0.3707 +vn 0.9295 -0.0087 0.3688 +vn 0.6386 -0.0255 -0.7691 +vn 0.8370 0.0196 -0.5468 +vn 0.8978 -0.0188 -0.4401 +vn 0.2926 -0.0339 -0.9556 +vn 0.5437 0.0164 -0.8391 +vn -0.5715 -0.0185 -0.8204 +vn -0.3958 0.0319 -0.9178 +vn -0.5298 -0.0059 -0.8481 +vn -0.9706 0.0032 -0.2409 +vn -0.9846 0.0219 -0.1732 +vn -0.9652 -0.0026 -0.2616 +vn -0.8213 -0.0168 0.5703 +vn -0.7487 0.0097 0.6628 +vn -0.8373 -0.0233 0.5462 +vn -0.2621 0.9278 0.2657 +vn -0.9857 0.0201 -0.1671 +vn -0.9884 -0.0799 -0.1294 +vn -0.9839 -0.0897 -0.1545 +vn -0.1129 0.9537 -0.2788 +vn 0.4448 0.3898 -0.8063 +vn 0.4995 0.8578 -0.1206 +vn -0.5499 -0.7067 -0.4452 +vn -0.5508 -0.7048 -0.4471 +vn -0.5540 -0.6972 -0.4549 +vn -0.0459 -0.7929 -0.6077 +vn -0.3605 -0.3930 0.8459 +vn 0.2803 -0.8631 0.4200 +vn 0.9994 -0.0206 0.0266 +vn 0.9985 0.0456 0.0294 +vn 0.9995 0.0125 0.0280 +vn 0.3987 -0.8875 -0.2311 +vn 0.3069 -0.1250 -0.9435 +vn 0.3144 0.0226 -0.9490 +vn 0.3153 0.0657 -0.9467 +vn -0.0158 0.9998 0.0105 +vn -0.0055 0.9995 -0.0298 +vn -0.0124 0.9993 -0.0343 +vn 0.0001 0.9995 -0.0328 +vn -0.0010 0.9999 -0.0137 +vn 0.0133 0.9995 -0.0279 +vn 0.0079 0.9996 -0.0279 +vn 0.0161 0.9999 0.0001 +vn 0.0025 0.9998 0.0193 +vn 0.0049 0.9999 0.0127 +vn 0.0186 0.9998 0.0038 +vn -0.0037 1.0000 0.0053 +vn -0.0106 0.9996 0.0266 +vn -0.0342 0.9987 0.0387 +vn -0.3123 0.0371 0.9493 +vn -0.3378 0.0019 0.9412 +vn -0.3087 0.0419 0.9502 +vn -0.2812 0.0789 0.9564 +vn -0.8761 -0.0745 0.4764 +vn -0.9043 -0.0063 0.4268 +vn -0.9126 0.0181 0.4083 +vn -0.9321 0.0909 0.3505 +vn -0.9409 0.0444 -0.3357 +vn -0.9448 0.0631 -0.3214 +vn -0.9398 0.0392 -0.3395 +vn -0.9351 0.0196 -0.3537 +vn -0.4019 -0.0408 -0.9148 +vn -0.3832 -0.0113 -0.9236 +vn -0.3748 0.0015 -0.9271 +vn -0.3511 0.0374 -0.9356 +vn 0.3111 0.1772 -0.9337 +vn 0.6478 -0.2466 -0.7208 +vn 0.9196 0.2110 -0.3313 +vn 0.9418 -0.0840 0.3254 +vn 0.9232 -0.0155 0.3840 +vn 0.9087 0.0245 0.4166 +vn 0.8719 0.1044 0.4784 +vn 0.3864 -0.0141 0.9222 +vn 0.3351 0.0361 0.9415 +vn 0.3319 0.0391 0.9425 +vn 0.2770 0.0903 0.9566 +vn -0.2598 -0.0250 0.9653 +vn -0.4160 0.0083 0.9093 +vn -0.2874 -0.0193 0.9576 +vn -0.4386 0.0133 0.8986 +vn -0.9566 -0.0241 0.2904 +vn -0.9939 0.0070 0.1099 +vn -0.9636 -0.0200 0.2666 +vn -0.9965 0.0116 0.0830 +vn -0.6743 0.0396 -0.7374 +vn -0.5148 -0.0173 -0.8571 +vn -0.5375 -0.0098 -0.8432 +vn -0.7013 0.0502 -0.7111 +vn 0.0477 -0.0470 -0.9978 +vn 0.8941 -0.0124 -0.4476 +vn 0.7611 0.0324 -0.6478 +vn 0.7845 0.0256 -0.6196 +vn 0.9146 -0.0214 -0.4039 +vn 0.7814 0.0011 0.6240 +vn 0.7967 0.0074 0.6043 +vn 0.7942 0.0063 0.6077 +vn 0.7782 -0.0002 0.6280 +vn -0.0974 -0.9792 -0.1782 +vn -0.0078 -0.9788 -0.2048 +vn -0.2020 -0.9749 -0.0933 +vn -0.2220 -0.9745 -0.0327 +vn -0.2151 -0.9761 0.0311 +vn -0.8333 0.5268 -0.1675 +vn -0.1448 -0.9841 0.1032 +vn -0.0846 -0.9774 0.1939 +vn -0.1140 -0.9790 0.1690 +vn 0.0638 -0.9802 0.1872 +vn 0.2305 -0.9531 0.1960 +vn 0.2466 -0.9668 0.0675 +vn 0.2333 -0.9721 0.0246 +vn 0.1153 -0.9837 -0.1376 +vn 0.2323 -0.9679 -0.0959 +vn 0.3159 0.4971 -0.8081 +vn 0.0358 0.8320 0.5535 +vn 0.3497 -0.0223 0.9366 +vn 0.1393 0.0175 0.9901 +vn 0.1117 0.0451 0.9927 +vn 0.3393 -0.0299 0.9402 +vn 0.8857 -0.1036 0.4526 +vn 0.8857 -0.1031 0.4527 +vn 0.9232 -0.0005 0.3843 +vn 0.8145 -0.2348 0.5305 +vn 0.9718 0.0985 -0.2144 +vn 0.6015 -0.3236 -0.7304 +vn 0.8418 0.1063 -0.5292 +vn 0.8251 0.2293 -0.5164 +vn 0.8404 0.1226 -0.5280 +vn 0.0925 -0.1815 -0.9790 +vn 0.0608 -0.2118 -0.9754 +vn 0.2552 -0.0174 -0.9667 +vn -0.0210 -0.2876 -0.9575 +vn -0.5446 0.1722 -0.8208 +vn -0.9809 0.0356 -0.1913 +vn -0.9790 0.0270 -0.2022 +vn -0.8455 -0.0976 0.5250 +vn -0.8407 -0.1077 0.5307 +vn -0.8388 -0.1114 0.5330 +vn -0.8316 -0.1251 0.5411 +vn -0.1075 0.0841 0.9906 +vn -0.0601 0.1157 0.9915 +vn -0.0549 -0.9980 0.0314 +vn -0.0173 -0.9978 0.0643 +vn -0.0014 -0.9989 0.0462 +vn -0.1153 -0.9921 0.0501 +vn -0.0569 -0.9984 0.0024 +vn -0.0640 -0.9979 -0.0128 +vn -0.4095 0.8379 -0.3608 +vn -0.1068 0.8907 -0.4418 +vn -0.1671 0.8878 -0.4289 +vn -0.2513 0.7839 -0.5677 +vn 0.1923 0.8109 -0.5527 +vn -0.0566 0.8027 -0.5937 +vn 0.3987 0.8663 0.3009 +vn 0.3601 0.7911 0.4944 +vn 0.4227 0.8381 0.3448 +vn 0.8685 0.4882 -0.0859 +vn -0.7986 0.5853 -0.1404 +vn -0.5400 0.8417 0.0003 +vn -0.7499 0.6523 -0.1099 +vn 0.3622 0.7373 0.5702 +vn 0.3279 0.7698 0.5477 +vn 0.3344 0.7638 0.5521 +vn 0.6731 0.7389 0.0320 +vn 0.5095 0.8601 -0.0259 +vn 0.6351 0.7722 0.0177 +vn -0.1138 0.7837 -0.6106 +vn -0.3383 0.8628 -0.3756 +vn -0.1799 0.8153 -0.5503 +vn -0.8136 0.5801 -0.0399 +vn -0.5799 0.8130 0.0530 +vn -0.7685 0.6396 -0.0190 +vn 0.2102 0.8281 0.5197 +vn 0.3680 0.8190 0.4402 +vn 0.4666 0.8107 0.3535 +vn -0.3391 0.8277 -0.4472 +vn -0.5884 0.7983 -0.1284 +vn -0.7962 0.4959 0.3467 +vn -0.7753 0.5469 0.3160 +vn 0.3076 0.3267 -0.8937 +vn 0.9924 0.1185 0.0322 +vn 0.4309 0.8296 0.3551 +vn 0.3927 0.7962 0.4603 +vn 0.3691 0.5770 0.7286 +vn 0.3719 0.5639 0.7374 +vn -0.2053 0.7831 0.5871 +vn -0.3839 0.7969 -0.4665 +vn -0.2230 0.8193 -0.5282 +vn 0.1193 0.8140 -0.5685 +vn 0.2275 0.8140 -0.5345 +vn 0.6888 0.7085 -0.1537 +vn 0.6539 0.7462 -0.1248 +vn 0.5051 0.8132 -0.2891 +vn 0.5130 0.8151 -0.2692 +vn -0.2364 0.8099 0.5368 +vn 0.1903 0.8094 0.5556 +vn -0.0983 0.8152 0.5707 +vn -0.4738 0.8027 0.3622 +vn -0.5459 0.8232 0.1556 +vn 0.6039 0.6912 -0.3970 +vn 0.3554 0.8207 -0.4474 +vn -0.3667 0.6823 0.6324 +vn -0.3662 0.6900 0.6243 +vn -0.3631 0.7265 0.5835 +vn -0.3606 0.7462 0.5596 +vn 0.2307 0.8431 -0.4857 +vn 0.4751 0.8791 -0.0370 +vn -0.5052 0.4471 0.7382 +vn -0.4796 0.8770 0.0279 +vn -0.3112 0.6867 -0.6569 +vn -0.3059 0.8559 -0.4169 +vn -0.2979 0.8967 -0.3273 +vn 0.2835 0.9136 0.2914 +vn -0.7577 0.6455 0.0962 +vn -0.4862 0.8618 0.1445 +vn -0.6966 0.7090 0.1097 +vn 0.8192 0.2583 -0.5121 +vn 0.4748 0.8200 0.3197 +vn 0.5107 0.7968 0.3229 +vn 0.5954 0.7334 0.3282 +vn 0.6584 0.6766 0.3298 +vn 0.1601 0.8095 0.5649 +vn 0.0189 0.3865 0.9221 +vn -0.2932 0.8844 0.3632 +vn -0.5438 0.8295 -0.1273 +vn -0.7567 0.6488 -0.0802 +vn -0.8049 0.5840 -0.1055 +vn -0.3322 0.8562 -0.3956 +vn 0.6553 0.6370 -0.4060 +vn 0.4899 0.8606 0.1393 +vn 0.5188 0.8392 0.1629 +vn 0.2107 0.8278 0.5200 +vn -0.5091 0.8573 0.0759 +vn -0.3239 0.8865 -0.3306 +vn 0.4351 0.7482 -0.5009 +vn 0.5601 0.6483 -0.5157 +vn 0.3806 0.7188 0.5819 +vn -0.2075 0.8643 0.4582 +vn -0.3056 0.5993 -0.7399 +vn 0.1235 0.8797 -0.4593 +vn 0.3049 0.7235 -0.6194 +vn 0.1693 0.8478 -0.5025 +vn 0.3520 0.6677 -0.6560 +vn 0.4366 0.8854 -0.1599 +vn 0.4062 0.4889 0.7720 +vn -0.1173 0.8851 0.4503 +vn -0.3130 0.7255 0.6129 +vn -0.1677 0.8525 0.4951 +vn -0.3656 0.6658 0.6504 +vn -0.4231 0.8932 0.1521 +vn -0.4264 0.8270 -0.3664 +vn 0.1173 0.8438 -0.5238 +vn 0.3267 0.9353 -0.1356 +vn 0.4618 0.8698 0.1737 +vn -0.3884 0.9176 0.0845 +vn 0.3832 -0.7884 0.4813 +vn 0.0847 -0.5945 0.7996 +vn 0.0993 -0.6302 0.7701 +vn 0.4165 -0.8391 -0.3500 +vn 0.5759 -0.8167 0.0372 +vn 0.3663 -0.8363 -0.4081 +vn -0.4353 -0.7478 -0.5013 +vn -0.5008 -0.7907 -0.3521 +vn -0.2125 -0.8841 -0.4163 +vn -0.9868 0.0940 -0.1321 +vn -0.4311 -0.6174 0.6580 +vn -0.3983 -0.6573 0.6398 +vn -0.1605 -0.8637 0.4778 +vn -0.1302 -0.8814 0.4540 +vn -0.3814 -0.9114 0.1547 +vn -0.5068 -0.8262 -0.2461 +vn -0.1646 -0.9139 -0.3711 +vn 0.3769 -0.6581 -0.6519 +vn 0.3263 -0.7220 -0.6102 +vn -0.7064 -0.6138 0.3525 +vn -0.7352 -0.5613 0.3800 +vn -0.5213 -0.8305 0.1962 +vn -0.3628 -0.5344 0.7634 +vn -0.2779 -0.8351 0.4747 +vn -0.3217 -0.7216 0.6130 +vn -0.4266 -0.8864 0.1799 +vn -0.4298 -0.6289 -0.6479 +vn -0.4276 -0.7087 -0.5611 +vn -0.3935 -0.8694 -0.2987 +vn 0.6417 -0.5952 -0.4836 +vn 0.1583 -0.8392 0.5203 +vn 0.4297 -0.8312 0.3528 +vn 0.0555 -0.8228 0.5656 +vn -0.2810 -0.6788 0.6785 +vn -0.6145 -0.7864 -0.0629 +vn -0.4163 -0.8977 0.1447 +vn -0.4801 -0.8685 0.1237 +vn -0.5118 -0.8269 -0.2329 +vn -0.2478 -0.8158 -0.5225 +vn -0.1966 -0.8001 -0.5667 +vn 0.3768 -0.9021 0.2105 +vn 0.4858 -0.5819 0.6522 +vn -0.3246 -0.9158 0.2364 +vn -0.3811 -0.9024 -0.2013 +vn 0.2611 -0.7758 -0.5744 +vn 0.0083 -0.8745 -0.4850 +vn 0.0643 -0.8434 -0.5334 +vn 0.3335 -0.8428 -0.4224 +vn 0.3424 -0.8873 -0.3091 +vn 0.4464 -0.8574 0.2562 +vn 0.4205 -0.8250 0.3775 +vn 0.4517 -0.8884 0.0815 +vn 0.2744 -0.7472 0.6053 +vn 0.0613 -0.7906 0.6092 +vn -0.2744 -0.6612 0.6983 +vn -0.3391 -0.5912 0.7317 +vn -0.4184 -0.8781 0.2321 +vn -0.4700 -0.8541 0.2228 +vn -0.6375 -0.7480 0.1846 +vn -0.5555 -0.6937 -0.4585 +vn 0.5969 -0.8002 0.0574 +vn 0.3948 -0.8086 0.4362 +vn -0.1459 -0.9073 0.3944 +vn -0.4734 -0.8663 0.1592 +vn -0.5328 -0.7303 -0.4276 +vn -0.2696 -0.7976 -0.5396 +vn -0.5651 -0.6605 -0.4944 +vn -0.3341 -0.8183 -0.4676 +vn 0.1236 -0.8162 -0.5644 +vn 0.1101 -0.8250 -0.5543 +vn 0.2604 -0.8593 -0.4403 +vn 0.2825 -0.8462 -0.4518 +vn 0.5112 -0.8588 -0.0336 +vn 0.6915 -0.7067 -0.1495 +vn 0.7470 -0.6371 -0.1901 +vn 0.4519 -0.8921 0.0006 +vn 0.5842 -0.6591 0.4736 +vn 0.2911 -0.8280 0.4793 +vn 0.5169 -0.7231 0.4583 +vn 0.1311 -0.7418 0.6577 +vn 0.0712 -0.6607 0.7473 +vn -0.2532 -0.8801 0.4017 +vn -0.8142 -0.5791 -0.0407 +vn -0.3761 -0.9011 -0.2156 +vn 0.0560 -0.8531 -0.5188 +vn 0.0560 -0.8530 -0.5189 +vn 0.0564 -0.8530 -0.5188 +vn 0.0566 -0.8526 -0.5194 +vn 0.3874 -0.9128 -0.1291 +vn 0.6416 -0.7201 0.2642 +vn 0.7529 -0.6180 0.2262 +vn -0.3079 -0.6435 0.7008 +vn 0.1605 -0.8241 -0.5433 +vn 0.2931 -0.8244 -0.4842 +vn 0.3960 -0.8610 -0.3192 +vn 0.3791 -0.8853 -0.2692 +vn 0.8238 -0.5653 -0.0432 +vn 0.0034 -0.9042 0.4272 +vn -0.4666 -0.4298 0.7730 +vn -0.8679 -0.4847 -0.1089 +vn -0.3657 -0.5934 -0.7171 +vn 0.8674 -0.4799 -0.1315 +vn -0.6969 -0.6974 0.1674 +vn -0.0000 0.5332 -0.8460 +vn 0.0000 0.5222 0.8528 +vn 0.4986 0.0139 -0.8667 +vn -0.5274 -0.0319 -0.8490 +vn -0.9983 0.0578 0.0000 +vn -0.9993 0.0245 0.0297 +vn -0.9992 0.0164 0.0370 +vn -0.9977 -0.0165 0.0664 +vn -0.4505 0.0504 0.8914 +vn 0.5178 -0.0016 0.8555 +vn 0.9990 0.0447 -0.0069 +vn 0.9993 0.0369 0.0000 +vn 0.9989 0.0468 -0.0084 +vn 0.9984 0.0545 -0.0152 +vn 0.1335 -0.9836 -0.1216 +vn 0.1099 -0.9833 -0.1448 +vn 0.1348 -0.9838 -0.1181 +vn 0.1207 -0.9825 -0.1418 +vn 0.1068 -0.9813 -0.1601 +vn 0.1248 -0.9803 -0.1530 +vn 0.1016 -0.9814 -0.1629 +vn 0.0888 -0.9816 -0.1690 +vn 0.1098 -0.9850 -0.1328 +vn 0.2565 -0.9636 0.0750 +vn -0.7169 -0.4268 -0.5512 +vn -0.5632 -0.7248 -0.3969 +vn -0.6896 -0.4008 -0.6031 +vn -0.7713 0.1726 -0.6126 +vn -0.5900 0.6541 -0.4733 +vn -0.1224 0.9635 -0.2381 +vn 0.6632 0.4292 0.6131 +vn 0.7382 -0.1799 0.6501 +vn 0.5751 -0.6503 0.4964 +vn 0.6692 -0.4842 0.5637 +vn 0.9384 0.0031 0.3457 +vn 0.9497 -0.0006 0.3131 +vn 0.9931 -0.0035 -0.1175 +vn 0.9882 0.0084 -0.1527 +vn 0.0908 -0.9829 -0.1605 +vn 0.1215 0.9825 -0.1414 +vn 0.1339 0.9836 -0.1206 +vn 0.1450 0.9834 -0.1092 +vn 0.8419 0.0000 -0.5397 +vn 0.1393 0.9828 -0.1214 +vn 0.1431 0.9828 -0.1171 +vn -0.9877 -0.0166 0.1552 +vn -0.9018 -0.0109 0.4321 +vn 0.2779 -0.0074 0.9606 +vn 0.0999 -0.0181 0.9948 +vn 0.6747 -0.0046 0.7381 +vn 0.4023 0.0088 -0.9155 +vn 0.5126 -0.0023 -0.8587 +vn 0.0843 -0.0100 -0.9964 +vn -0.2653 0.0180 -0.9640 +vn -0.8180 0.0133 -0.5751 +vn -0.9246 -0.0052 -0.3808 +vn -0.5680 -0.0149 0.8229 +vn -0.9491 -0.0075 0.3148 +vn -0.1227 0.0057 0.9924 +vn 0.4621 0.0072 0.8868 +vn 0.9286 -0.0094 0.3711 +vn 0.9750 0.0180 -0.2216 +vn -0.3591 0.0417 -0.9324 +vn -0.9873 0.0263 -0.1569 +vn -0.7278 0.0166 0.6856 +vn 0.7992 0.0017 -0.6010 +vn 0.1246 0.9830 -0.1348 +vn 0.1186 0.9825 -0.1437 +vn 0.0935 0.9836 -0.1544 +vn -0.9560 0.0183 -0.2929 +vn 0.0595 -0.0065 0.9982 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 1/1/1 3/3/3 4/4/4 +f 4/4/4 3/3/3 5/5/5 +f 6/6/6 7/7/7 8/8/8 +f 6/6/6 9/9/9 2/2/2 +f 9/9/9 6/6/6 8/8/8 +f 1/1/1 10/10/10 2/2/2 +f 2/2/2 10/10/10 6/6/6 +f 11/11/11 12/12/12 8/8/8 +f 8/8/8 12/12/12 3/3/3 +f 3/3/3 12/12/12 5/5/5 +f 8/8/8 7/7/7 11/11/11 +f 13/13/13 14/14/14 15/15/15 +f 13/13/13 16/16/16 14/14/14 +f 14/14/14 16/16/16 17/17/17 +f 18/18/18 17/17/17 16/16/16 +f 17/17/17 18/18/18 19/19/19 +f 17/17/17 19/19/19 20/20/20 +f 19/19/19 21/21/21 20/20/20 +f 13/13/13 15/15/15 22/22/22 +f 22/22/22 15/15/15 23/23/23 +f 24/24/24 25/25/25 26/26/26 +f 25/25/25 27/27/27 26/26/26 +f 27/27/27 28/28/28 26/26/26 +f 26/26/26 28/28/28 29/29/29 +f 28/28/28 30/30/30 29/29/29 +f 29/29/29 30/30/30 31/31/31 +f 30/30/30 32/32/32 31/31/31 +f 32/32/32 33/33/33 31/31/31 +f 31/31/31 33/33/33 34/34/34 +f 24/24/24 35/35/35 25/25/25 +f 28/28/28 27/27/27 36/36/36 +f 28/28/28 36/36/36 30/30/37 +f 35/35/35 37/37/38 25/25/25 +f 25/25/25 37/37/38 36/36/36 +f 25/25/25 36/36/36 27/27/27 +f 33/33/39 32/32/40 38/38/41 +f 35/35/35 39/39/42 37/37/38 +f 36/36/36 37/37/38 40/40/43 +f 30/30/37 41/41/44 32/32/40 +f 32/32/40 41/41/44 38/38/41 +f 37/37/38 39/39/42 40/40/43 +f 36/36/36 40/40/43 30/30/37 +f 30/30/37 40/40/43 41/41/44 +f 42/42/45 43/43/46 44/44/47 +f 43/43/46 42/42/45 45/45/48 +f 45/45/48 42/42/45 46/46/49 +f 47/47/50 48/48/51 49/49/52 +f 49/49/52 48/48/51 50/50/53 +f 51/51/54 52/52/55 53/53/56 +f 44/44/47 43/43/46 54/54/57 +f 44/44/47 54/54/57 55/55/58 +f 51/51/54 53/53/56 50/50/53 +f 50/50/53 53/53/56 49/49/52 +f 56/56/59 57/57/60 58/58/61 +f 56/56/59 59/59/62 57/57/60 +f 60/60/63 61/61/64 62/62/65 +f 57/57/60 61/61/64 58/58/61 +f 63/63/66 64/64/67 24/24/68 +f 65/65/69 66/66/70 24/24/68 +f 58/58/61 61/61/64 60/60/63 +f 67/67/71 68/68/72 55/55/58 +f 55/55/58 54/54/57 67/67/71 +f 24/24/68 64/64/67 65/65/69 +f 60/60/63 62/62/65 69/69/73 +f 47/47/50 67/67/71 48/48/51 +f 47/47/50 70/70/74 67/67/71 +f 68/68/72 71/71/75 72/72/76 +f 67/67/71 70/70/74 71/71/75 +f 67/67/71 71/71/75 68/68/72 +f 10/10/10 1/1/1 73/73/77 +f 73/73/77 1/1/1 74/74/78 +f 73/73/77 74/74/78 75/75/79 +f 74/74/78 76/76/80 75/75/79 +f 75/75/79 76/76/80 77/77/81 +f 77/77/81 76/76/80 78/78/82 +f 78/78/82 79/79/83 77/77/81 +f 77/77/81 79/79/83 80/80/84 +f 81/81/85 80/80/84 79/79/83 +f 80/80/84 81/81/85 82/82/86 +f 80/80/84 82/82/86 83/83/87 +f 83/83/87 82/82/86 84/84/88 +f 83/83/87 84/84/88 85/85/89 +f 83/83/87 85/85/89 86/86/90 +f 83/83/87 86/86/90 87/87/91 +f 2/2/92 88/88/93 3/3/94 +f 3/3/94 88/88/93 89/89/95 +f 3/3/96 89/89/97 90/90/98 +f 3/3/96 90/90/98 8/8/99 +f 8/8/100 90/90/101 91/91/102 +f 8/8/100 91/91/102 9/9/103 +f 9/9/104 91/91/105 2/2/106 +f 2/2/106 91/91/105 88/88/107 +f 92/92/108 93/93/109 94/94/110 +f 95/95/111 93/93/109 92/92/108 +f 96/96/112 97/97/113 98/98/114 +f 97/97/113 99/99/115 95/95/111 +f 97/97/113 95/95/111 92/92/108 +f 100/100/116 101/101/117 102/102/118 +f 102/102/118 101/101/117 103/103/119 +f 97/97/113 96/96/112 104/104/120 +f 97/97/113 104/104/120 99/99/115 +f 102/102/118 103/103/119 105/105/121 +f 102/102/118 105/105/121 106/106/122 +f 106/106/122 105/105/121 107/107/123 +f 106/106/122 107/107/123 108/108/124 +f 109/109/125 110/110/126 111/111/127 +f 112/112/128 113/113/129 111/111/127 +f 111/111/127 113/113/129 109/109/125 +f 114/114/130 115/115/131 116/116/132 +f 114/114/130 116/116/132 108/108/124 +f 116/116/132 96/96/112 108/108/124 +f 108/108/124 96/96/112 98/98/114 +f 112/112/128 117/117/133 113/113/129 +f 108/108/124 107/107/123 114/114/130 +f 118/118/134 117/117/133 112/112/128 +f 69/69/73 119/119/135 60/60/63 +f 120/120/136 29/29/137 121/121/138 +f 121/121/138 29/29/137 122/122/139 +f 122/122/139 29/29/137 31/31/140 +f 122/122/139 31/31/140 123/123/141 +f 123/123/141 31/31/140 124/124/142 +f 124/124/142 31/31/140 125/125/143 +f 126/126/144 24/24/68 127/127/145 +f 127/127/145 24/24/68 26/26/146 +f 29/29/137 120/120/136 26/26/146 +f 26/26/146 120/120/136 128/128/147 +f 26/26/146 128/128/147 129/129/148 +f 26/26/146 129/129/148 130/130/149 +f 26/26/146 130/130/149 131/131/150 +f 26/26/146 131/131/150 127/127/145 +f 125/125/143 31/31/140 34/34/151 +f 125/125/143 34/34/151 86/86/152 +f 86/86/152 34/34/151 87/87/153 +f 132/132/154 118/118/134 133/133/155 +f 133/133/155 118/118/134 112/112/128 +f 4/4/4 134/134/156 1/1/1 +f 134/134/156 4/4/4 135/135/157 +f 136/136/158 137/137/159 138/138/160 +f 139/139/161 140/140/162 141/141/163 +f 142/142/164 143/143/165 139/139/161 +f 139/139/161 143/143/165 144/144/166 +f 145/145/167 146/146/168 147/147/169 +f 145/145/167 148/148/170 146/146/168 +f 137/137/159 148/148/170 145/145/167 +f 149/149/171 145/145/167 150/150/172 +f 139/139/161 141/141/163 149/149/171 +f 149/149/171 141/141/163 151/151/173 +f 152/152/174 142/142/164 150/150/172 +f 153/153/175 152/152/174 147/147/169 +f 147/147/169 152/152/174 150/150/172 +f 147/147/169 150/150/172 145/145/167 +f 138/138/160 137/137/159 145/145/167 +f 138/138/160 145/145/167 151/151/173 +f 151/151/173 145/145/167 149/149/171 +f 150/150/172 142/142/164 139/139/161 +f 150/150/172 139/139/161 149/149/171 +f 139/139/161 144/144/166 154/154/176 +f 139/139/161 154/154/176 140/140/162 +f 22/22/22 23/23/23 155/155/177 +f 155/155/177 23/23/23 156/156/178 +f 157/157/179 158/158/180 159/159/181 +f 157/157/179 159/159/181 160/160/182 +f 160/160/182 159/159/181 161/161/183 +f 160/160/182 161/161/183 162/162/184 +f 162/162/184 161/161/183 163/163/185 +f 162/162/184 163/163/185 164/164/186 +f 164/164/186 163/163/185 156/156/178 +f 156/156/178 163/163/185 155/155/177 +f 157/157/179 154/154/176 144/144/166 +f 157/157/179 144/144/166 158/158/180 +f 24/24/68 126/126/144 165/165/187 +f 24/24/68 165/165/187 166/166/188 +f 24/24/68 166/166/188 63/63/66 +f 167/167/189 63/63/66 166/166/188 +f 166/166/188 168/168/190 167/167/189 +f 167/167/189 168/168/190 72/72/76 +f 168/168/190 169/169/191 72/72/76 +f 72/72/76 169/169/191 68/68/72 +f 68/68/72 169/169/191 170/170/192 +f 170/170/192 169/169/191 171/171/193 +f 170/170/192 171/171/193 172/172/194 +f 173/173/195 69/69/73 172/172/194 +f 172/172/194 69/69/73 170/170/192 +f 69/69/73 173/173/195 174/174/196 +f 69/69/73 174/174/196 119/119/135 +f 134/134/156 135/135/157 175/175/197 +f 175/175/197 135/135/157 176/176/198 +f 177/177/199 118/118/134 178/178/200 +f 179/179/201 180/180/202 177/177/203 +f 177/177/203 180/180/202 181/181/204 +f 177/177/203 181/181/204 114/114/130 +f 114/114/130 181/181/204 115/115/131 +f 115/115/131 181/181/204 182/182/205 +f 182/182/205 181/181/204 183/183/206 +f 176/176/198 135/135/157 183/183/206 +f 183/183/206 135/135/157 182/182/205 +f 118/118/134 132/132/154 184/184/207 +f 118/118/134 184/184/207 178/178/200 +f 46/46/208 185/185/209 186/186/210 +f 186/186/210 185/185/209 187/187/211 +f 188/188/212 189/189/213 62/62/214 +f 62/62/214 189/189/213 69/69/215 +f 189/189/213 190/190/216 69/69/215 +f 69/69/215 190/190/216 170/170/217 +f 191/191/218 170/170/217 190/190/216 +f 192/192/219 68/68/220 170/170/217 +f 192/192/219 170/170/217 191/191/218 +f 55/55/221 68/68/222 193/193/223 +f 193/193/223 68/68/222 194/194/224 +f 55/55/225 195/195/226 196/196/227 +f 55/55/225 196/196/227 44/44/228 +f 44/44/228 196/196/227 42/42/229 +f 42/42/229 196/196/227 197/197/230 +f 198/198/231 59/59/232 186/186/210 +f 186/186/210 187/187/211 198/198/231 +f 198/198/231 199/199/233 59/59/232 +f 200/200/234 57/57/235 201/201/236 +f 201/201/236 57/57/235 59/59/232 +f 201/201/236 59/59/232 199/199/233 +f 202/202/237 203/203/238 204/204/239 +f 202/202/237 205/205/240 203/203/238 +f 203/203/238 206/206/241 204/204/239 +f 207/207/242 208/208/243 203/203/238 +f 203/203/238 208/208/243 206/206/241 +f 65/65/244 209/209/245 52/52/246 +f 52/52/246 209/209/245 210/210/247 +f 211/211/248 212/212/249 53/53/250 +f 53/53/250 212/212/249 49/49/251 +f 49/49/251 212/212/249 213/213/252 +f 49/49/251 213/213/252 47/47/253 +f 213/213/252 214/214/254 47/47/253 +f 215/215/255 70/70/256 214/214/254 +f 214/214/254 70/70/256 47/47/253 +f 71/71/257 70/70/258 216/216/259 +f 216/216/259 70/70/258 217/217/260 +f 72/72/261 218/218/262 167/167/263 +f 167/167/263 218/218/262 219/219/264 +f 220/220/265 63/63/266 167/167/263 +f 220/220/265 167/167/263 219/219/264 +f 65/65/244 64/64/267 221/221/268 +f 221/221/268 64/64/267 222/222/269 +f 209/209/245 65/65/244 223/223/270 +f 224/224/271 225/225/272 226/226/273 +f 227/227/274 228/228/275 229/229/276 +f 229/229/276 228/228/275 230/230/277 +f 229/229/276 230/230/277 225/225/272 +f 229/229/276 225/225/272 231/231/278 +f 231/231/278 225/225/272 224/224/271 +f 110/110/279 232/232/280 101/101/281 +f 101/101/281 232/232/280 233/233/282 +f 103/103/283 234/234/284 235/235/285 +f 103/103/283 235/235/285 105/105/286 +f 105/105/286 235/235/285 236/236/287 +f 105/105/286 236/236/287 237/237/288 +f 105/105/286 237/237/288 107/107/289 +f 238/238/290 239/239/291 107/107/292 +f 107/107/292 239/239/291 114/114/293 +f 240/240/294 241/241/295 114/114/296 +f 114/114/296 241/241/295 177/177/297 +f 242/242/298 177/177/297 241/241/295 +f 177/177/297 242/242/298 243/243/299 +f 244/244/300 118/118/301 243/243/299 +f 243/243/299 118/118/301 177/177/297 +f 117/117/302 118/118/301 245/245/303 +f 245/245/303 118/118/301 244/244/300 +f 246/246/304 109/109/305 113/113/306 +f 246/246/304 113/113/306 247/247/307 +f 109/109/305 246/246/304 248/248/308 +f 109/109/305 248/248/308 249/249/309 +f 249/249/309 110/110/279 109/109/305 +f 232/232/280 110/110/279 249/249/309 +f 250/250/310 251/251/311 252/252/312 +f 252/252/312 251/251/311 253/253/313 +f 254/254/314 255/255/315 256/256/316 +f 253/253/313 257/257/317 252/252/312 +f 252/252/312 257/257/317 254/254/314 +f 254/254/314 257/257/317 255/255/315 +f 258/258/318 182/182/319 135/135/320 +f 258/258/318 135/135/320 259/259/321 +f 182/182/319 258/258/318 260/260/322 +f 261/261/323 115/115/324 260/260/322 +f 260/260/322 115/115/324 182/182/319 +f 262/262/325 263/263/326 116/116/327 +f 116/116/327 263/263/326 96/96/328 +f 264/264/329 265/265/330 96/96/331 +f 96/96/331 265/265/330 104/104/332 +f 104/104/332 265/265/330 266/266/333 +f 104/104/332 266/266/333 99/99/334 +f 266/266/333 267/267/335 99/99/334 +f 268/268/336 95/95/337 267/267/335 +f 267/267/335 95/95/337 99/99/334 +f 93/93/338 269/269/339 270/270/340 +f 270/270/340 269/269/339 271/271/341 +f 270/270/340 271/271/341 272/272/342 +f 270/270/340 272/272/342 273/273/343 +f 270/270/340 273/273/343 7/7/344 +f 274/274/345 275/275/346 276/276/347 +f 276/276/347 277/277/348 274/274/345 +f 276/276/347 278/278/349 279/279/350 +f 276/276/347 279/279/350 280/280/351 +f 276/276/347 280/280/351 277/277/348 +f 281/281/352 278/278/349 276/276/347 +f 282/282/353 283/283/354 281/281/352 +f 276/276/347 284/284/355 282/282/353 +f 276/276/347 282/282/353 281/281/352 +f 285/285/356 286/286/357 287/287/358 +f 287/287/358 286/286/357 288/288/359 +f 287/287/358 288/288/359 289/289/360 +f 289/289/360 290/290/361 287/287/358 +f 289/289/360 291/291/362 290/290/361 +f 290/290/361 291/291/362 292/292/363 +f 133/133/155 293/293/364 291/291/362 +f 291/291/362 293/293/364 292/292/363 +f 133/133/155 112/112/128 293/293/364 +f 285/285/356 294/294/365 286/286/357 +f 285/285/356 295/295/366 294/294/365 +f 296/296/367 297/297/368 295/295/366 +f 296/296/367 295/295/366 285/285/356 +f 298/298/369 60/60/63 297/297/368 +f 298/298/369 297/297/368 296/296/367 +f 58/58/61 60/60/63 298/298/369 +f 4/4/370 299/299/371 135/135/320 +f 135/135/320 299/299/371 259/259/321 +f 5/5/372 300/300/373 301/301/374 +f 5/5/375 301/301/376 302/302/377 +f 5/5/375 302/302/377 4/4/370 +f 4/4/370 302/302/377 299/299/371 +f 300/300/373 5/5/372 303/303/378 +f 303/303/378 5/5/372 12/12/379 +f 12/12/380 304/304/381 303/303/382 +f 304/304/381 12/12/380 11/11/383 +f 114/114/384 239/239/291 240/240/385 +f 239/239/291 238/238/290 305/305/386 +f 305/305/386 238/238/290 306/306/387 +f 251/251/311 250/250/310 306/306/387 +f 251/251/311 306/306/387 238/238/290 +f 107/107/292 237/237/388 238/238/290 +f 305/305/386 240/240/385 239/239/291 +f 305/305/386 306/306/389 240/240/385 +f 238/238/290 237/237/288 307/307/390 +f 238/238/290 307/307/390 251/251/311 +f 243/243/391 254/254/392 244/244/393 +f 240/240/385 306/306/389 241/241/394 +f 252/252/395 254/254/392 243/243/391 +f 242/242/396 252/252/395 243/243/391 +f 250/250/310 252/252/395 242/242/396 +f 241/241/397 306/306/387 250/250/310 +f 242/242/396 241/241/397 250/250/310 +f 236/236/287 307/307/390 237/237/288 +f 236/236/398 235/235/399 308/308/400 +f 251/251/401 307/307/402 236/236/403 +f 236/236/398 308/308/400 253/253/404 +f 236/236/403 253/253/405 251/251/401 +f 101/101/406 233/233/407 309/309/408 +f 101/101/409 309/309/408 234/234/410 +f 101/101/409 234/234/410 103/103/411 +f 308/308/400 235/235/399 234/234/410 +f 308/308/400 234/234/410 309/309/408 +f 253/253/313 308/308/400 310/310/412 +f 310/310/412 308/308/400 309/309/408 +f 310/310/412 309/309/408 233/233/407 +f 117/117/413 245/245/413 311/311/413 +f 117/117/414 311/311/415 113/113/416 +f 311/311/415 312/312/417 113/113/416 +f 113/113/418 312/312/419 247/247/307 +f 245/245/420 244/244/393 254/254/392 +f 245/245/420 254/254/392 313/313/421 +f 313/313/421 254/254/314 256/256/316 +f 314/314/422 310/310/412 232/232/280 +f 232/232/280 310/310/412 233/233/423 +f 310/310/412 314/314/422 257/257/317 +f 310/310/412 257/257/317 253/253/313 +f 313/313/421 256/256/316 315/315/424 +f 245/245/420 313/313/421 311/311/425 +f 313/313/421 315/315/424 311/311/425 +f 256/256/426 316/316/427 312/312/419 +f 256/256/426 312/312/419 315/315/428 +f 315/315/429 312/312/429 311/311/429 +f 316/316/427 247/247/307 312/312/419 +f 246/246/304 247/247/307 316/316/427 +f 255/255/430 316/316/427 256/256/426 +f 317/317/431 249/249/309 248/248/308 +f 317/317/431 248/248/308 246/246/304 +f 255/255/430 246/246/304 316/316/427 +f 246/246/304 255/255/430 317/317/432 +f 317/317/432 257/257/317 314/314/422 +f 255/255/430 257/257/317 317/317/432 +f 249/249/309 317/317/431 314/314/422 +f 249/249/309 314/314/422 232/232/280 +f 115/115/433 261/261/434 318/318/435 +f 115/115/433 318/318/435 116/116/327 +f 116/116/327 318/318/435 262/262/325 +f 261/261/323 260/260/322 319/319/436 +f 319/319/436 260/260/322 277/277/348 +f 319/319/437 277/277/348 280/280/351 +f 260/260/322 258/258/318 277/277/348 +f 258/258/318 259/259/321 320/320/438 +f 258/258/318 320/320/438 277/277/348 +f 277/277/348 320/320/438 274/274/345 +f 320/320/438 321/321/439 274/274/345 +f 274/274/345 321/321/439 275/275/346 +f 320/320/438 299/299/371 321/321/439 +f 259/259/321 299/299/371 320/320/438 +f 280/280/351 322/322/440 319/319/437 +f 262/262/325 318/318/435 322/322/440 +f 322/322/440 318/318/435 261/261/441 +f 322/322/440 261/261/441 319/319/437 +f 321/321/442 323/323/443 275/275/444 +f 321/321/439 299/299/371 302/302/445 +f 321/321/442 302/302/446 323/323/443 +f 300/300/373 323/323/443 301/301/374 +f 301/301/374 323/323/443 302/302/446 +f 96/96/447 263/263/448 264/264/449 +f 324/324/450 263/263/448 262/262/325 +f 262/262/325 322/322/440 324/324/450 +f 324/324/450 322/322/440 280/280/351 +f 324/324/450 280/280/351 279/279/350 +f 323/323/443 300/300/373 303/303/378 +f 303/303/378 325/325/451 323/323/443 +f 304/304/381 326/326/452 303/303/453 +f 303/303/453 326/326/452 325/325/454 +f 326/326/452 284/284/355 325/325/454 +f 325/325/454 276/276/455 323/323/443 +f 323/323/443 276/276/455 275/275/444 +f 325/325/454 284/284/355 276/276/455 +f 7/7/456 273/273/457 327/327/458 +f 7/7/456 327/327/458 11/11/383 +f 11/11/383 327/327/458 304/304/381 +f 263/263/448 324/324/450 264/264/449 +f 304/304/381 327/327/458 326/326/452 +f 326/326/452 327/327/458 284/284/355 +f 327/327/458 273/273/343 328/328/459 +f 327/327/458 328/328/459 284/284/355 +f 93/93/460 95/95/337 329/329/461 +f 95/95/337 268/268/336 330/330/462 +f 95/95/337 330/330/462 329/329/461 +f 93/93/460 329/329/461 269/269/339 +f 267/267/335 330/330/462 268/268/336 +f 265/265/463 264/264/464 324/324/450 +f 281/281/352 331/331/465 330/330/462 +f 265/265/463 324/324/450 278/278/349 +f 278/278/349 324/324/450 279/279/350 +f 281/281/352 283/283/354 331/331/465 +f 330/330/462 267/267/335 281/281/352 +f 267/267/335 266/266/466 281/281/352 +f 266/266/466 278/278/349 281/281/352 +f 266/266/466 265/265/463 278/278/349 +f 272/272/342 282/282/353 328/328/459 +f 272/272/342 328/328/459 273/273/343 +f 332/332/467 282/282/353 272/272/342 +f 282/282/353 284/284/355 328/328/459 +f 269/269/339 329/329/461 333/333/468 +f 333/333/468 329/329/461 331/331/469 +f 333/333/468 331/331/469 283/283/470 +f 329/329/461 330/330/462 331/331/469 +f 283/283/470 282/282/353 332/332/467 +f 272/272/342 271/271/341 332/332/467 +f 271/271/341 269/269/339 332/332/467 +f 332/332/467 269/269/339 333/333/468 +f 283/283/470 332/332/467 333/333/468 +f 215/215/255 334/334/471 70/70/256 +f 217/217/260 70/70/258 334/334/472 +f 228/228/473 335/335/474 215/215/475 +f 215/215/475 335/335/474 334/334/472 +f 335/335/474 217/217/260 334/334/472 +f 228/228/473 215/215/475 230/230/476 +f 336/336/477 226/226/478 212/212/249 +f 212/212/249 211/211/248 336/336/477 +f 214/214/479 213/213/480 230/230/476 +f 214/214/479 230/230/476 215/215/475 +f 212/212/249 226/226/478 225/225/481 +f 212/212/249 225/225/481 213/213/480 +f 213/213/480 225/225/481 230/230/476 +f 210/210/482 337/337/482 52/52/482 +f 52/52/483 337/337/484 336/336/477 +f 52/52/483 336/336/477 53/53/250 +f 53/53/250 336/336/477 211/211/248 +f 71/71/257 216/216/259 338/338/485 +f 71/71/257 338/338/485 72/72/486 +f 72/72/486 338/338/485 218/218/487 +f 217/217/260 335/335/474 216/216/259 +f 335/335/474 339/339/488 216/216/259 +f 228/228/275 227/227/274 335/335/474 +f 335/335/474 227/227/274 339/339/488 +f 340/340/489 226/226/478 210/210/490 +f 210/210/490 226/226/478 337/337/491 +f 226/226/478 336/336/477 337/337/491 +f 341/341/492 218/218/487 338/338/485 +f 339/339/488 341/341/492 338/338/485 +f 339/339/488 338/338/485 216/216/259 +f 227/227/274 341/341/492 339/339/488 +f 210/210/247 209/209/245 342/342/493 +f 210/210/247 342/342/493 340/340/494 +f 224/224/271 340/340/494 342/342/493 +f 224/224/271 226/226/273 340/340/494 +f 220/220/265 343/343/495 63/63/266 +f 63/63/496 343/343/495 222/222/497 +f 63/63/496 222/222/497 64/64/498 +f 344/344/499 220/220/265 345/345/500 +f 218/218/501 341/341/492 219/219/502 +f 229/229/276 344/344/499 345/345/500 +f 341/341/492 229/229/276 219/219/502 +f 229/229/276 231/231/278 344/344/499 +f 220/220/265 219/219/502 345/345/500 +f 345/345/500 219/219/502 229/229/276 +f 341/341/492 227/227/274 229/229/276 +f 209/209/245 223/223/503 342/342/493 +f 65/65/244 221/221/268 223/223/270 +f 220/220/265 344/344/499 343/343/495 +f 343/343/495 344/344/499 346/346/504 +f 344/344/499 231/231/278 346/346/504 +f 343/343/495 346/346/504 222/222/497 +f 221/221/505 342/342/493 223/223/503 +f 221/221/505 222/222/506 346/346/504 +f 221/221/505 346/346/504 342/342/493 +f 342/342/493 346/346/504 224/224/271 +f 231/231/278 224/224/271 346/346/504 +f 189/189/213 188/188/212 347/347/507 +f 347/347/508 207/207/242 189/189/509 +f 207/207/242 347/347/508 208/208/243 +f 57/57/235 200/200/234 348/348/510 +f 57/57/511 348/348/510 61/61/512 +f 61/61/512 348/348/510 349/349/513 +f 61/61/512 349/349/513 350/350/514 +f 61/61/515 350/350/516 62/62/517 +f 350/350/516 188/188/518 62/62/517 +f 347/347/519 188/188/518 350/350/516 +f 349/349/520 347/347/521 350/350/522 +f 347/347/521 349/349/520 208/208/523 +f 348/348/510 200/200/234 351/351/524 +f 348/348/510 351/351/524 349/349/513 +f 351/351/525 208/208/523 349/349/520 +f 192/192/219 194/194/526 68/68/220 +f 203/203/527 205/205/528 352/352/529 +f 190/190/530 189/189/509 207/207/242 +f 192/192/219 191/191/531 353/353/532 +f 192/192/219 353/353/532 352/352/529 +f 352/352/529 353/353/533 203/203/527 +f 191/191/531 190/190/534 353/353/532 +f 353/353/533 190/190/530 203/203/527 +f 190/190/530 207/207/242 203/203/527 +f 200/200/234 201/201/535 351/351/524 +f 187/187/211 354/354/536 198/198/231 +f 198/198/231 354/354/536 199/199/233 +f 354/354/537 206/206/538 199/199/539 +f 201/201/540 199/199/539 206/206/538 +f 201/201/540 206/206/538 208/208/541 +f 201/201/540 208/208/541 351/351/542 +f 354/354/537 204/204/543 206/206/538 +f 192/192/219 352/352/529 355/355/544 +f 355/355/544 352/352/529 205/205/528 +f 194/194/526 192/192/219 355/355/544 +f 356/356/545 187/187/211 185/185/209 +f 187/187/211 356/356/545 354/354/536 +f 354/354/537 356/356/545 204/204/543 +f 42/42/546 197/197/547 357/357/548 +f 42/42/546 357/357/548 46/46/549 +f 46/46/549 357/357/548 185/185/550 +f 193/193/551 195/195/226 55/55/225 +f 193/193/223 194/194/224 355/355/544 +f 193/193/223 355/355/544 202/202/552 +f 202/202/552 355/355/544 205/205/528 +f 356/356/545 357/357/553 204/204/543 +f 357/357/553 197/197/230 358/358/554 +f 356/356/545 185/185/209 357/357/553 +f 357/357/553 358/358/554 204/204/543 +f 193/193/555 202/202/556 195/195/557 +f 358/358/554 196/196/227 359/359/558 +f 196/196/227 195/195/557 359/359/558 +f 359/359/558 195/195/557 202/202/556 +f 196/196/227 358/358/554 197/197/230 +f 358/358/554 359/359/559 204/204/543 +f 202/202/556 204/204/560 359/359/558 +f 38/38/561 17/17/562 20/20/563 +f 360/360/564 39/39/42 14/14/565 +f 361/361/566 362/362/567 38/38/561 +f 38/38/561 362/362/567 17/17/562 +f 17/17/562 362/362/567 363/363/568 +f 17/17/562 363/363/568 14/14/565 +f 14/14/565 363/363/568 360/360/564 +f 39/39/42 360/360/564 364/364/569 +f 39/39/42 364/364/569 40/40/43 +f 40/40/43 364/364/569 365/365/570 +f 40/40/43 365/365/570 41/41/44 +f 41/41/44 365/365/570 38/38/561 +f 38/38/561 365/365/570 361/361/566 +f 91/91/571 366/366/571 88/88/571 +f 88/88/571 366/366/571 367/367/571 +f 88/88/571 367/367/571 368/368/571 +f 88/88/571 368/368/571 89/89/571 +f 89/89/571 368/368/571 90/90/571 +f 90/90/571 368/368/571 369/369/571 +f 90/90/571 369/369/571 91/91/571 +f 91/91/571 369/369/571 370/370/571 +f 91/91/571 370/370/571 366/366/571 +f 364/364/572 368/368/572 365/365/572 +f 365/365/573 368/368/573 367/367/573 +f 365/365/574 367/367/574 361/361/574 +f 361/361/575 367/367/576 366/366/577 +f 361/361/575 366/366/577 362/362/578 +f 362/362/579 366/366/580 370/370/581 +f 362/362/579 370/370/581 363/363/582 +f 363/363/583 370/370/584 369/369/585 +f 363/363/583 369/369/585 360/360/586 +f 360/360/587 369/369/588 364/364/589 +f 364/364/589 369/369/588 368/368/590 +f 38/38/591 20/20/592 83/83/593 +f 38/38/591 83/83/593 33/33/594 +f 87/87/595 34/34/596 33/33/597 +f 33/33/597 83/83/598 87/87/595 +f 35/35/35 24/24/24 66/66/599 +f 35/35/35 66/66/599 15/15/600 +f 14/14/601 39/39/42 35/35/35 +f 14/14/602 35/35/35 15/15/600 +f 371/371/603 372/372/604 373/373/605 +f 374/374/606 372/372/604 371/371/603 +f 375/375/607 372/372/604 376/376/608 +f 372/372/604 375/375/607 377/377/609 +f 378/378/610 372/372/604 377/377/609 +f 379/379/611 380/380/612 381/381/613 +f 380/380/612 382/382/614 383/383/615 +f 372/372/604 384/384/616 373/373/605 +f 372/372/604 385/385/617 384/384/616 +f 378/378/610 386/386/618 372/372/604 +f 381/381/613 387/387/619 379/379/611 +f 388/388/620 387/387/619 381/381/613 +f 83/83/87 20/20/20 80/80/84 +f 77/77/81 21/21/21 75/75/79 +f 73/73/77 19/19/19 10/10/10 +f 80/80/84 21/21/21 77/77/81 +f 75/75/79 19/19/19 73/73/77 +f 75/75/79 21/21/21 19/19/19 +f 20/20/20 21/21/21 80/80/84 +f 13/13/13 22/22/22 389/389/621 +f 389/389/621 22/22/22 390/390/622 +f 389/389/623 390/390/622 270/270/624 +f 16/16/625 13/13/13 389/389/621 +f 16/16/625 389/389/621 391/391/626 +f 391/391/626 389/389/623 6/6/6 +f 6/6/6 389/389/623 270/270/624 +f 6/6/6 270/270/624 7/7/7 +f 18/18/18 16/16/625 391/391/626 +f 19/19/19 18/18/18 391/391/626 +f 19/19/19 391/391/626 10/10/10 +f 10/10/10 391/391/626 6/6/6 +f 94/94/110 270/270/624 390/390/622 +f 94/94/110 93/93/109 270/270/624 +f 22/22/22 155/155/627 390/390/622 +f 390/390/622 155/155/627 94/94/110 +f 155/155/627 163/163/628 392/392/629 +f 155/155/627 392/392/629 94/94/110 +f 163/163/628 161/161/630 392/392/629 +f 161/161/630 393/393/631 392/392/629 +f 161/161/630 159/159/632 394/394/633 +f 161/161/630 394/394/633 393/393/631 +f 158/158/634 395/395/635 159/159/632 +f 159/159/632 395/395/635 394/394/633 +f 394/394/633 395/395/635 396/396/636 +f 101/101/117 100/100/116 396/396/636 +f 110/110/637 396/396/636 395/395/635 +f 110/110/637 395/395/635 397/397/638 +f 110/110/637 101/101/117 396/396/636 +f 397/397/639 395/395/635 158/158/634 +f 397/397/639 158/158/634 144/144/166 +f 152/152/174 153/153/175 293/293/364 +f 152/152/640 111/111/641 142/142/642 +f 143/143/165 398/398/643 397/397/639 +f 143/143/165 397/397/639 144/144/166 +f 397/397/638 398/398/643 110/110/637 +f 110/110/637 398/398/643 111/111/641 +f 398/398/643 142/142/642 111/111/641 +f 111/111/641 152/152/640 112/112/128 +f 112/112/128 152/152/640 293/293/364 +f 398/398/643 143/143/165 142/142/642 +f 285/285/356 287/287/358 146/146/168 +f 146/146/168 290/290/361 147/147/169 +f 287/287/358 290/290/361 146/146/168 +f 290/290/361 292/292/363 147/147/169 +f 153/153/175 292/292/363 293/293/364 +f 147/147/169 292/292/363 153/153/175 +f 137/137/159 136/136/158 298/298/369 +f 298/298/369 136/136/158 58/58/61 +f 298/298/369 296/296/367 137/137/159 +f 137/137/159 296/296/367 148/148/170 +f 296/296/367 285/285/356 148/148/170 +f 146/146/168 148/148/170 285/285/356 +f 138/138/160 58/58/61 136/136/158 +f 138/138/160 151/151/173 399/399/644 +f 399/399/644 151/151/173 141/141/645 +f 399/399/644 400/400/646 186/186/647 +f 56/56/59 399/399/644 59/59/62 +f 59/59/62 399/399/644 186/186/647 +f 58/58/61 138/138/160 56/56/59 +f 56/56/59 138/138/160 399/399/644 +f 399/399/644 141/141/645 400/400/648 +f 400/400/648 141/141/645 140/140/649 +f 400/400/648 140/140/649 154/154/650 +f 45/45/48 46/46/49 186/186/647 +f 45/45/48 186/186/647 400/400/646 +f 45/45/651 400/400/648 157/157/652 +f 157/157/652 400/400/648 154/154/650 +f 157/157/652 160/160/653 45/45/651 +f 45/45/651 160/160/653 401/401/654 +f 160/160/653 162/162/655 401/401/654 +f 162/162/655 164/164/656 401/401/654 +f 164/164/656 402/402/657 401/401/654 +f 164/164/656 156/156/658 402/402/657 +f 156/156/658 403/403/659 402/402/657 +f 52/52/55 51/51/54 403/403/659 +f 403/403/659 404/404/660 65/65/69 +f 65/65/69 52/52/55 403/403/659 +f 404/404/660 403/403/659 156/156/658 +f 404/404/660 156/156/658 23/23/661 +f 65/65/69 404/404/660 66/66/70 +f 66/66/662 404/404/660 15/15/663 +f 15/15/663 404/404/660 23/23/661 +f 405/405/664 406/406/665 94/94/666 +f 94/94/666 406/406/665 92/92/667 +f 92/92/668 406/406/668 97/97/668 +f 97/97/669 407/407/670 98/98/671 +f 98/98/672 407/407/672 408/408/672 +f 98/98/673 408/408/674 108/108/675 +f 100/100/676 102/102/677 409/409/678 +f 396/396/679 100/100/676 409/409/678 +f 409/409/678 410/410/680 396/396/679 +f 396/396/679 410/410/680 394/394/681 +f 394/394/681 410/410/680 411/411/682 +f 394/394/681 411/411/682 412/412/683 +f 394/394/681 412/412/683 393/393/684 +f 393/393/684 412/412/683 392/392/685 +f 392/392/685 412/412/683 405/405/664 +f 392/392/685 405/405/664 94/94/666 +f 413/413/686 414/414/687 45/45/688 +f 415/415/689 51/51/690 416/416/691 +f 43/43/692 45/45/692 414/414/692 +f 414/414/693 417/417/694 43/43/695 +f 417/417/694 418/418/696 43/43/695 +f 43/43/695 418/418/696 54/54/697 +f 418/418/698 67/67/698 54/54/698 +f 67/67/699 419/419/700 48/48/701 +f 419/419/702 420/420/702 48/48/702 +f 48/48/703 420/420/703 50/50/703 +f 420/420/704 421/421/704 50/50/704 +f 50/50/705 421/421/705 51/51/705 +f 421/421/706 416/416/691 51/51/690 +f 402/402/707 403/403/708 415/415/689 +f 402/402/707 415/415/689 422/422/709 +f 402/402/707 422/422/709 423/423/710 +f 413/413/686 45/45/688 424/424/711 +f 424/424/711 45/45/688 401/401/712 +f 424/424/713 401/401/713 423/423/713 +f 423/423/710 401/401/714 402/402/707 +f 415/415/689 403/403/708 51/51/690 +f 425/425/715 426/426/716 427/427/717 +f 427/427/717 426/426/716 428/428/718 +f 429/429/719 430/430/720 428/428/718 +f 428/428/718 430/430/720 427/427/717 +f 431/431/721 432/432/722 429/429/719 +f 429/429/719 432/432/722 430/430/720 +f 433/433/723 432/432/722 431/431/721 +f 372/372/604 433/433/723 431/431/721 +f 372/372/604 381/381/613 433/433/723 +f 434/434/724 435/435/725 436/436/726 +f 434/434/724 436/436/726 437/437/727 +f 437/437/727 436/436/726 438/438/728 +f 438/438/728 439/439/729 437/437/727 +f 438/438/728 440/440/730 439/439/729 +f 438/438/728 441/441/731 440/440/730 +f 442/442/732 443/443/733 441/441/731 +f 441/441/731 443/443/733 440/440/730 +f 442/442/732 444/444/734 443/443/733 +f 445/445/735 444/444/734 442/442/732 +f 446/446/736 444/444/734 445/445/735 +f 444/444/734 446/446/736 447/447/737 +f 446/446/736 448/448/738 449/449/739 +f 450/450/740 446/446/736 451/451/741 +f 452/452/742 453/453/743 454/454/744 +f 454/454/744 453/453/743 455/455/745 +f 450/450/740 451/451/741 456/456/746 +f 456/456/746 451/451/741 457/457/747 +f 457/457/747 451/451/741 452/452/742 +f 457/457/747 452/452/742 458/458/748 +f 458/458/748 452/452/742 454/454/744 +f 459/459/749 460/460/750 456/456/746 +f 459/459/749 456/456/746 461/461/751 +f 461/461/751 456/456/746 462/462/752 +f 462/462/752 458/458/748 463/463/753 +f 463/463/753 458/458/748 464/464/754 +f 464/464/754 465/465/755 466/466/756 +f 461/461/751 462/462/752 467/467/757 +f 467/467/757 462/462/752 463/463/753 +f 468/468/758 464/464/754 466/466/756 +f 467/467/757 463/463/753 469/469/759 +f 469/469/759 463/463/753 464/464/754 +f 469/469/759 464/464/754 468/468/758 +f 435/435/725 455/455/745 453/453/743 +f 435/435/725 453/453/743 436/436/726 +f 436/436/726 453/453/743 438/438/728 +f 438/438/728 453/453/743 452/452/742 +f 438/438/728 452/452/742 441/441/731 +f 441/441/731 452/452/742 451/451/741 +f 441/441/731 451/451/741 442/442/732 +f 442/442/732 451/451/741 445/445/735 +f 445/445/735 451/451/741 446/446/736 +f 460/460/750 450/450/740 456/456/746 +f 458/458/748 454/454/744 470/470/760 +f 470/470/760 454/454/744 455/455/745 +f 470/470/760 455/455/745 465/465/755 +f 465/465/755 464/464/754 470/470/760 +f 470/470/760 464/464/754 458/458/748 +f 458/458/748 462/462/752 457/457/747 +f 457/457/747 462/462/752 456/456/746 +f 468/468/758 466/466/756 372/372/604 +f 459/459/749 461/461/751 426/426/716 +f 426/426/716 461/461/751 467/467/757 +f 426/426/716 467/467/757 428/428/718 +f 428/428/718 467/467/757 469/469/759 +f 428/428/718 469/469/759 429/429/719 +f 429/429/719 469/469/759 431/431/721 +f 431/431/721 469/469/759 468/468/758 +f 431/431/721 468/468/758 372/372/604 +f 471/471/761 472/472/762 473/473/763 +f 474/474/764 475/475/765 432/432/766 +f 432/432/766 475/475/765 476/476/767 +f 471/471/761 475/475/765 472/472/762 +f 477/477/768 425/425/715 473/473/763 +f 471/471/761 476/476/767 475/475/765 +f 381/381/613 474/474/764 433/433/723 +f 433/433/723 474/474/764 432/432/766 +f 430/430/720 476/476/767 471/471/761 +f 471/471/761 473/473/763 427/427/717 +f 425/425/715 427/427/717 473/473/763 +f 471/471/761 427/427/717 430/430/720 +f 476/476/767 430/430/720 432/432/722 +f 444/444/769 478/478/770 443/443/771 +f 440/440/730 479/479/772 439/439/729 +f 479/479/772 480/480/773 481/481/774 +f 439/439/729 481/481/774 482/482/775 +f 447/447/776 483/483/777 444/444/769 +f 444/444/769 483/483/777 478/478/770 +f 479/479/772 481/481/774 439/439/729 +f 439/439/729 482/482/775 437/437/778 +f 437/437/778 482/482/775 484/484/779 +f 484/484/779 434/434/724 437/437/778 +f 479/479/772 440/440/780 480/480/773 +f 480/480/773 440/440/780 443/443/771 +f 480/480/773 443/443/771 478/478/770 +f 485/485/571 486/486/571 487/487/571 +f 487/487/571 486/486/571 488/488/571 +f 487/487/571 488/488/571 489/489/571 +f 489/489/571 488/488/571 490/490/571 +f 491/491/571 492/492/571 493/493/571 +f 491/491/571 493/493/571 485/485/571 +f 485/485/571 493/493/571 486/486/571 +f 494/494/571 495/495/571 496/496/571 +f 496/496/571 495/495/571 497/497/571 +f 496/496/571 497/497/571 492/492/571 +f 496/496/571 492/492/571 491/491/571 +f 498/498/571 499/499/571 500/500/571 +f 498/498/571 500/500/571 501/501/571 +f 501/501/571 500/500/571 495/495/571 +f 501/501/571 495/495/571 494/494/571 +f 489/489/571 490/490/571 502/502/571 +f 489/489/571 502/502/571 498/498/571 +f 498/498/571 502/502/571 499/499/571 +f 503/503/781 500/500/782 504/504/783 +f 504/504/783 500/500/782 499/499/784 +f 504/504/783 499/499/784 502/502/785 +f 504/504/783 502/502/785 505/505/786 +f 505/505/787 502/502/788 490/490/789 +f 505/505/787 490/490/789 506/506/790 +f 506/506/791 490/490/791 488/488/791 +f 506/506/792 488/488/792 507/507/792 +f 507/507/793 488/488/793 486/486/793 +f 507/507/794 486/486/795 508/508/796 +f 508/508/796 486/486/795 509/509/797 +f 509/509/797 486/486/795 493/493/798 +f 509/509/799 493/493/800 492/492/801 +f 509/509/799 492/492/801 510/510/802 +f 510/510/803 492/492/804 497/497/805 +f 510/510/803 497/497/805 511/511/806 +f 511/511/806 497/497/805 495/495/807 +f 511/511/806 495/495/807 512/512/808 +f 512/512/809 495/495/809 503/503/809 +f 503/503/810 495/495/810 500/500/810 +f 513/513/811 510/510/811 511/511/811 +f 514/514/811 512/512/811 503/503/811 +f 514/514/811 503/503/811 515/515/811 +f 513/513/811 511/511/811 512/512/811 +f 513/513/811 512/512/811 514/514/811 +f 516/516/811 509/509/811 513/513/811 +f 513/513/811 509/509/811 510/510/811 +f 516/516/811 508/508/811 509/509/811 +f 517/517/811 507/507/811 516/516/811 +f 516/516/811 507/507/811 508/508/811 +f 518/518/811 505/505/811 519/519/811 +f 519/519/811 505/505/811 506/506/811 +f 519/519/811 506/506/811 517/517/811 +f 517/517/811 506/506/811 507/507/811 +f 520/520/811 504/504/811 518/518/811 +f 518/518/811 504/504/811 505/505/811 +f 515/515/811 503/503/811 520/520/811 +f 520/520/811 503/503/811 504/504/811 +f 521/521/811 522/522/811 523/523/811 +f 521/521/811 523/523/811 524/524/811 +f 521/521/811 524/524/811 525/525/811 +f 526/526/811 527/527/811 528/528/811 +f 528/528/811 527/527/811 522/522/811 +f 528/528/811 522/522/811 521/521/811 +f 529/529/811 530/530/811 531/531/811 +f 531/531/811 530/530/811 532/532/811 +f 531/531/811 532/532/811 526/526/811 +f 526/526/811 532/532/811 527/527/811 +f 533/533/811 534/534/811 535/535/811 +f 535/535/811 534/534/811 536/536/811 +f 535/535/811 536/536/811 529/529/811 +f 529/529/811 536/536/811 530/530/811 +f 525/525/811 524/524/811 537/537/811 +f 525/525/811 537/537/811 538/538/811 +f 538/538/811 537/537/811 539/539/811 +f 538/538/811 539/539/811 533/533/811 +f 533/533/811 539/539/811 534/534/811 +f 540/540/812 536/536/812 541/541/812 +f 541/541/813 536/536/813 534/534/813 +f 541/541/814 534/534/814 542/542/814 +f 542/542/815 534/534/815 539/539/815 +f 542/542/816 539/539/817 537/537/818 +f 542/542/816 537/537/818 543/543/819 +f 543/543/820 537/537/821 524/524/822 +f 543/543/820 524/524/822 544/544/823 +f 544/544/824 524/524/825 545/545/826 +f 545/545/826 524/524/825 523/523/827 +f 545/545/826 523/523/827 522/522/828 +f 545/545/829 522/522/829 546/546/829 +f 546/546/830 522/522/830 527/527/830 +f 546/546/831 527/527/831 547/547/831 +f 547/547/832 527/527/833 532/532/834 +f 547/547/832 532/532/834 548/548/835 +f 548/548/836 532/532/837 530/530/838 +f 548/548/836 530/530/838 549/549/839 +f 549/549/839 530/530/838 540/540/840 +f 540/540/840 530/530/838 536/536/841 +f 550/550/571 540/540/571 551/551/571 +f 551/551/571 540/540/571 541/541/571 +f 552/552/571 548/548/571 549/549/571 +f 552/552/571 549/549/571 550/550/571 +f 550/550/571 549/549/571 540/540/571 +f 553/553/571 547/547/571 552/552/571 +f 552/552/571 547/547/571 548/548/571 +f 554/554/571 546/546/571 553/553/571 +f 553/553/571 546/546/571 547/547/571 +f 554/554/571 545/545/571 546/546/571 +f 555/555/571 543/543/571 556/556/571 +f 543/543/571 544/544/571 556/556/571 +f 556/556/571 544/544/571 545/545/571 +f 556/556/571 545/545/571 554/554/571 +f 557/557/571 542/542/571 555/555/571 +f 555/555/571 542/542/571 543/543/571 +f 551/551/571 541/541/571 542/542/571 +f 551/551/571 542/542/571 557/557/571 +f 489/489/842 525/525/843 538/538/844 +f 489/489/845 538/538/846 533/533/847 +f 487/487/848 533/533/847 535/535/849 +f 485/485/850 535/535/849 529/529/851 +f 491/491/852 529/529/851 531/531/853 +f 496/496/854 531/531/853 526/526/855 +f 496/496/856 526/526/857 528/528/858 +f 501/501/859 528/528/860 521/521/861 +f 498/498/862 521/521/861 525/525/843 +f 555/555/863 519/519/864 557/557/865 +f 556/556/866 518/518/867 555/555/868 +f 554/554/869 520/520/870 556/556/871 +f 553/553/872 514/514/873 554/554/874 +f 552/552/875 513/513/876 553/553/872 +f 550/550/877 516/516/878 552/552/879 +f 551/551/880 516/516/881 550/550/882 +f 557/557/883 517/517/884 551/551/885 +f 558/558/886 559/559/886 560/560/886 +f 561/561/887 559/559/888 558/558/889 +f 562/562/890 563/563/890 561/561/890 +f 563/563/891 562/562/891 564/564/891 +f 562/562/892 565/565/892 564/564/892 +f 566/566/893 567/567/894 568/568/895 +f 567/567/896 566/566/896 569/569/896 +f 570/570/897 571/571/897 572/572/897 +f 573/573/898 574/574/898 571/571/898 +f 573/573/899 575/575/900 574/574/901 +f 569/569/902 575/575/902 573/573/902 +f 569/569/903 566/566/904 575/575/905 +f 576/576/906 577/577/907 578/578/908 +f 578/578/908 577/577/907 579/579/909 +f 578/578/908 579/579/909 580/580/910 +f 580/580/910 579/579/909 581/581/911 +f 581/581/911 579/579/909 582/582/912 +f 581/581/911 582/582/912 583/583/913 +f 582/582/912 584/584/914 583/583/913 +f 583/583/913 584/584/914 585/585/915 +f 585/585/915 584/584/914 586/586/916 +f 585/585/915 586/586/916 587/587/917 +f 587/587/917 586/586/916 588/588/918 +f 587/587/917 588/588/918 589/589/919 +f 589/589/919 588/588/918 576/576/906 +f 576/576/906 588/588/918 577/577/907 +f 590/590/920 587/587/921 589/589/922 +f 590/590/920 589/589/922 591/591/923 +f 591/591/924 589/589/925 592/592/926 +f 592/592/926 589/589/925 576/576/927 +f 592/592/928 576/576/929 578/578/930 +f 592/592/928 578/578/930 593/593/931 +f 593/593/932 578/578/933 594/594/934 +f 594/594/934 578/578/933 580/580/935 +f 594/594/936 580/580/936 581/581/936 +f 594/594/937 581/581/937 595/595/937 +f 595/595/938 581/581/938 583/583/938 +f 595/595/939 583/583/940 596/596/941 +f 596/596/941 583/583/940 585/585/942 +f 596/596/943 585/585/944 590/590/945 +f 590/590/945 585/585/944 587/587/946 +f 597/597/811 595/595/811 598/598/811 +f 598/598/811 595/595/811 596/596/811 +f 598/598/811 596/596/811 599/599/811 +f 599/599/811 596/596/811 590/590/811 +f 599/599/811 590/590/811 591/591/811 +f 599/599/811 591/591/811 600/600/811 +f 601/601/811 593/593/811 597/597/811 +f 597/597/811 593/593/811 594/594/811 +f 597/597/811 594/594/811 595/595/811 +f 600/600/811 591/591/811 592/592/811 +f 600/600/811 592/592/811 601/601/811 +f 601/601/811 592/592/811 593/593/811 +f 602/602/947 599/599/948 603/603/949 +f 603/603/949 599/599/948 600/600/950 +f 603/603/951 600/600/952 604/604/953 +f 604/604/953 600/600/952 601/601/954 +f 604/604/955 601/601/956 597/597/957 +f 604/604/955 597/597/957 605/605/958 +f 605/605/959 597/597/959 606/606/959 +f 606/606/960 597/597/961 598/598/962 +f 606/606/960 598/598/962 607/607/963 +f 607/607/964 598/598/965 599/599/966 +f 607/607/964 599/599/966 602/602/967 +f 605/605/968 608/608/969 609/609/970 +f 605/605/968 609/609/970 604/604/971 +f 604/604/971 609/609/970 603/603/972 +f 603/603/973 609/609/973 610/610/973 +f 610/610/974 611/611/975 603/603/976 +f 603/603/976 611/611/975 602/602/977 +f 602/602/977 611/611/975 612/612/978 +f 602/602/977 612/612/978 613/613/979 +f 602/602/977 613/613/979 607/607/980 +f 607/607/980 613/613/979 606/606/981 +f 613/613/979 614/614/982 606/606/981 +f 606/606/981 614/614/982 608/608/969 +f 606/606/981 608/608/969 605/605/968 +f 615/615/983 608/608/983 614/614/983 +f 616/616/984 612/612/984 611/611/984 +f 617/617/985 616/616/986 618/618/987 +f 617/617/985 612/612/988 616/616/986 +f 619/619/989 612/612/990 617/617/991 +f 619/619/989 613/613/992 612/612/990 +f 613/613/993 619/619/993 614/614/993 +f 614/614/994 619/619/994 615/615/994 +f 615/615/995 619/619/996 562/562/997 +f 562/562/998 608/608/999 615/615/1000 +f 561/561/1001 608/608/999 562/562/998 +f 561/561/1002 609/609/1002 608/608/1002 +f 609/609/1003 561/561/887 558/558/889 +f 609/609/1003 558/558/889 610/610/1004 +f 560/560/1005 611/611/1006 558/558/1007 +f 558/558/1007 611/611/1006 610/610/1008 +f 618/618/987 616/616/986 611/611/1009 +f 618/618/987 611/611/1009 560/560/1010 +f 569/569/1011 571/571/1012 570/570/1013 +f 569/569/1011 573/573/1014 571/571/1012 +f 620/620/1015 567/567/1016 569/569/1011 +f 569/569/1011 570/570/1013 620/620/1015 +f 621/621/1017 622/622/1018 566/566/1019 +f 623/623/1020 624/624/1021 625/625/1022 +f 626/626/1023 627/627/1024 628/628/1025 +f 629/629/1026 630/630/1026 631/631/1026 +f 632/632/1027 633/633/1028 634/634/1029 +f 635/635/1030 636/636/1031 637/637/1032 +f 636/636/1033 638/638/1034 637/637/1035 +f 639/639/1036 640/640/1037 641/641/1038 +f 640/640/1039 642/642/1040 643/643/1041 +f 644/644/1042 645/645/1043 646/646/1044 +f 625/625/1022 647/647/1045 623/623/1020 +f 648/648/1046 649/649/1047 650/650/1048 +f 575/575/905 566/566/904 651/651/1049 +f 652/652/1050 574/574/901 575/575/900 +f 574/574/1051 653/653/1052 654/654/1053 +f 654/654/1053 571/571/1054 574/574/1051 +f 572/572/1055 571/571/1055 654/654/1055 +f 655/655/1056 656/656/1057 648/648/1046 +f 657/657/1058 658/658/1059 656/656/1057 +f 626/626/1060 628/628/1061 659/659/1062 +f 659/659/1062 628/628/1061 660/660/1063 +f 661/661/1064 662/662/1065 663/663/1066 +f 664/664/1067 665/665/1068 661/661/1064 +f 666/666/1069 667/667/1070 624/624/1021 +f 644/644/1071 668/668/1072 642/642/1073 +f 642/642/1073 668/668/1072 669/669/1074 +f 670/670/1075 639/639/1036 641/641/1038 +f 637/637/1035 638/638/1034 671/671/1076 +f 672/672/1077 633/633/1077 635/635/1077 +f 634/634/1029 633/633/1028 672/672/1078 +f 673/673/1079 632/632/1080 634/634/1081 +f 629/629/1082 631/631/1082 674/674/1082 +f 568/568/1083 675/675/1084 621/621/1085 +f 565/565/1086 562/562/997 619/619/996 +f 565/565/1087 619/619/1088 676/676/1089 +f 676/676/1089 619/619/1088 617/617/1090 +f 676/676/1091 617/617/1091 618/618/1091 +f 676/676/1092 618/618/1092 649/649/1092 +f 649/649/1093 618/618/1093 650/650/1093 +f 650/650/1048 677/677/1094 648/648/1046 +f 648/648/1046 677/677/1094 655/655/1056 +f 656/656/1057 655/655/1056 657/657/1058 +f 658/658/1059 657/657/1058 659/659/1062 +f 658/658/1059 659/659/1062 660/660/1063 +f 628/628/1025 627/627/1024 662/662/1065 +f 662/662/1065 627/627/1024 663/663/1066 +f 661/661/1064 663/663/1066 664/664/1067 +f 665/665/1068 664/664/1067 678/678/1095 +f 665/665/1068 678/678/1095 647/647/1096 +f 678/678/1097 623/623/1020 647/647/1045 +f 625/625/1022 624/624/1021 667/667/1070 +f 666/666/1069 679/679/1098 667/667/1070 +f 666/666/1099 646/646/1044 679/679/1100 +f 679/679/1100 646/646/1044 645/645/1043 +f 646/646/1044 668/668/1101 644/644/1042 +f 642/642/1040 669/669/1102 643/643/1041 +f 640/640/1037 643/643/1103 641/641/1038 +f 641/641/1038 671/671/1104 670/670/1075 +f 670/670/1075 671/671/1104 638/638/1105 +f 637/637/1032 680/680/1106 635/635/1030 +f 680/680/1107 672/672/1107 635/635/1107 +f 632/632/1080 673/673/1079 681/681/1108 +f 673/673/1109 682/682/1110 681/681/1111 +f 681/681/1111 682/682/1110 630/630/1112 +f 682/682/1113 631/631/1113 630/630/1113 +f 629/629/1114 674/674/1114 683/683/1114 +f 674/674/1115 684/684/1116 683/683/1117 +f 683/683/1117 684/684/1116 675/675/1118 +f 684/684/1119 621/621/1085 675/675/1084 +f 621/621/1017 566/566/1019 568/568/1120 +f 622/622/1018 651/651/1121 566/566/1019 +f 651/651/1122 652/652/1122 575/575/1122 +f 652/652/1123 653/653/1052 574/574/1051 +f 572/572/1124 620/620/1124 570/570/1124 +f 676/676/1125 649/649/1126 663/663/1127 +f 564/564/1128 626/626/1129 659/659/1130 +f 655/655/1131 561/561/1132 563/563/1133 +f 559/559/888 561/561/887 677/677/1134 +f 559/559/1135 650/650/1136 560/560/1137 +f 560/560/1137 650/650/1136 618/618/1138 +f 559/559/1139 677/677/1139 650/650/1139 +f 655/655/1131 677/677/1140 561/561/1132 +f 657/657/1141 655/655/1131 563/563/1133 +f 659/659/1130 657/657/1142 563/563/1143 +f 659/659/1130 563/563/1143 564/564/1128 +f 664/664/1144 649/649/1145 648/648/1146 +f 669/669/1147 668/668/1148 665/665/1149 +f 669/669/1150 665/665/1150 643/643/1150 +f 625/625/1151 641/641/1152 647/647/1153 +f 671/671/1154 667/667/1154 679/679/1154 +f 680/680/1155 645/645/1156 644/644/1157 +f 680/680/1155 644/644/1157 672/672/1158 +f 634/634/1159 672/672/1160 642/642/1161 +f 640/640/1162 634/634/1159 642/642/1161 +f 634/634/1159 640/640/1162 673/673/1163 +f 673/673/1163 640/640/1162 639/639/1164 +f 631/631/1165 636/636/1165 674/674/1165 +f 674/674/1166 636/636/1166 635/635/1166 +f 621/621/1167 684/684/1167 633/633/1167 +f 632/632/1168 622/622/1168 621/621/1168 +f 651/651/1169 622/622/1170 681/681/1171 +f 651/651/1169 630/630/1172 652/652/1173 +f 629/629/1174 653/653/1175 652/652/1176 +f 654/654/1177 683/683/1178 572/572/1179 +f 675/675/1180 572/572/1179 683/683/1178 +f 572/572/1181 675/675/1182 620/620/1183 +f 568/568/895 567/567/894 620/620/1184 +f 565/565/1185 626/626/1129 564/564/1128 +f 676/676/1125 627/627/1186 565/565/1185 +f 565/565/1185 627/627/1186 626/626/1129 +f 627/627/1186 676/676/1125 663/663/1127 +f 663/663/1187 649/649/1187 664/664/1187 +f 664/664/1144 648/648/1146 678/678/1188 +f 648/648/1189 623/623/1190 678/678/1191 +f 648/648/1189 656/656/1192 623/623/1190 +f 623/623/1190 656/656/1192 624/624/1193 +f 656/656/1192 658/658/1194 624/624/1193 +f 660/660/1195 666/666/1196 658/658/1194 +f 658/658/1194 666/666/1196 624/624/1193 +f 628/628/1197 666/666/1198 660/660/1199 +f 666/666/1198 628/628/1197 646/646/1200 +f 628/628/1201 662/662/1202 646/646/1203 +f 646/646/1203 662/662/1202 668/668/1204 +f 661/661/1205 668/668/1204 662/662/1202 +f 661/661/1206 665/665/1149 668/668/1148 +f 665/665/1207 647/647/1207 643/643/1207 +f 643/643/1208 647/647/1153 641/641/1152 +f 667/667/1209 671/671/1210 625/625/1211 +f 625/625/1211 671/671/1210 641/641/1212 +f 671/671/1213 679/679/1213 637/637/1213 +f 637/637/1214 679/679/1215 645/645/1156 +f 637/637/1214 645/645/1156 680/680/1155 +f 644/644/1157 642/642/1216 672/672/1158 +f 670/670/1217 673/673/1163 639/639/1164 +f 673/673/1163 670/670/1217 682/682/1218 +f 670/670/1217 638/638/1219 682/682/1218 +f 682/682/1218 638/638/1219 631/631/1220 +f 636/636/1221 631/631/1221 638/638/1221 +f 674/674/1222 635/635/1222 684/684/1222 +f 635/635/1223 633/633/1223 684/684/1223 +f 632/632/1224 621/621/1224 633/633/1224 +f 632/632/1225 681/681/1225 622/622/1225 +f 630/630/1172 651/651/1169 681/681/1171 +f 630/630/1226 629/629/1226 652/652/1226 +f 653/653/1175 629/629/1174 654/654/1177 +f 629/629/1174 683/683/1178 654/654/1177 +f 620/620/1183 675/675/1182 568/568/1227 +f 586/586/1228 685/685/1228 686/686/1228 +f 686/686/571 685/685/571 687/687/571 +f 686/686/571 687/687/571 688/688/571 +f 688/688/1229 687/687/1229 579/579/1229 +f 588/588/1230 586/586/1230 686/686/1230 +f 586/586/1231 584/584/1231 685/685/1231 +f 685/685/1232 584/584/1233 687/687/1234 +f 687/687/1234 584/584/1233 582/582/1235 +f 687/687/1236 582/582/1236 579/579/1236 +f 579/579/1237 577/577/1237 688/688/1237 +f 588/588/1238 686/686/1239 688/688/1240 +f 688/688/1240 577/577/1241 588/588/1238 +f 689/689/1242 460/460/750 690/690/1243 +f 689/689/1242 450/450/1244 460/460/750 +f 691/691/1245 446/446/736 449/449/739 +f 689/689/1242 446/446/736 450/450/1244 +f 448/448/738 446/446/736 689/689/1242 +f 426/426/1246 692/692/1247 693/693/1248 +f 694/694/1249 426/426/1246 693/693/1248 +f 695/695/1250 446/446/736 691/691/1245 +f 447/447/737 446/446/736 695/695/1250 +f 696/696/1251 426/426/1246 425/425/715 +f 696/696/1251 692/692/1247 426/426/1246 +f 697/697/1252 483/483/777 695/695/1253 +f 483/483/777 697/697/1252 478/478/1254 +f 478/478/1254 697/697/1252 480/480/773 +f 698/698/1255 480/480/773 697/697/1252 +f 698/698/1255 481/481/774 480/480/773 +f 699/699/1256 482/482/775 698/698/1255 +f 698/698/1255 482/482/775 481/481/774 +f 699/699/1256 484/484/779 482/482/775 +f 699/699/1256 700/700/1257 484/484/779 +f 701/701/1258 474/474/764 380/380/612 +f 701/701/1258 475/475/765 474/474/764 +f 702/702/1259 475/475/765 701/701/1258 +f 702/702/1259 472/472/762 475/475/765 +f 703/703/1260 473/473/1261 702/702/1259 +f 702/702/1259 473/473/1261 472/472/762 +f 703/703/1260 477/477/768 473/473/1261 +f 703/703/1260 696/696/1251 477/477/768 +f 425/425/715 477/477/768 696/696/1251 +f 381/381/613 380/380/612 474/474/764 +f 434/434/724 484/484/779 700/700/1257 +f 447/447/776 695/695/1253 483/483/777 +f 409/409/1262 417/417/694 414/414/1263 +f 413/413/1264 410/410/1265 414/414/1263 +f 459/459/749 694/694/1249 704/704/1266 +f 426/426/1246 694/694/1249 459/459/749 +f 690/690/1243 459/459/749 704/704/1266 +f 690/690/1243 460/460/750 459/459/749 +f 435/435/725 705/705/1267 706/706/1268 +f 707/707/1269 435/435/725 706/706/1268 +f 424/424/1270 410/410/1265 413/413/1264 +f 455/455/1271 707/707/1269 708/708/1272 +f 407/407/670 421/421/1273 420/420/1274 +f 408/408/674 420/420/1274 419/419/700 +f 108/108/675 419/419/700 67/67/699 +f 106/106/1275 67/67/1276 418/418/696 +f 102/102/1277 418/418/696 417/417/694 +f 412/412/1278 424/424/1270 423/423/1279 +f 422/422/1280 412/412/1278 423/423/1279 +f 405/405/1281 422/422/1280 415/415/689 +f 406/406/1282 415/415/689 416/416/691 +f 406/406/1282 416/416/691 421/421/1283 +f 435/435/725 707/707/1269 455/455/1271 +f 487/487/848 489/489/845 533/533/847 +f 485/485/850 487/487/848 535/535/849 +f 529/529/851 491/491/852 485/485/850 +f 496/496/854 491/491/852 531/531/853 +f 494/494/1284 496/496/856 528/528/858 +f 501/501/859 494/494/1285 528/528/860 +f 498/498/862 501/501/859 521/521/861 +f 489/489/842 498/498/862 525/525/843 +f 555/555/863 518/518/1286 519/519/864 +f 556/556/866 520/520/1287 518/518/867 +f 554/554/869 515/515/1288 520/520/870 +f 554/554/874 514/514/873 515/515/1289 +f 553/553/872 513/513/876 514/514/873 +f 552/552/879 516/516/878 513/513/1290 +f 551/551/880 517/517/1291 516/516/881 +f 557/557/883 519/519/1292 517/517/884 +f 409/409/1262 102/102/1277 417/417/694 +f 411/411/1293 410/410/1265 424/424/1270 +f 414/414/1263 410/410/1265 409/409/1262 +f 709/709/1294 455/455/1271 708/708/1272 +f 709/709/1294 465/465/1295 455/455/1271 +f 376/376/608 465/465/1295 709/709/1294 +f 376/376/608 466/466/1296 465/465/1295 +f 700/700/1257 435/435/725 434/434/724 +f 700/700/1257 705/705/1267 435/435/725 +f 97/97/1297 406/406/1282 421/421/1283 +f 407/407/670 97/97/669 421/421/1273 +f 408/408/674 407/407/670 420/420/1274 +f 108/108/675 408/408/674 419/419/700 +f 106/106/1275 108/108/1298 67/67/1276 +f 102/102/1277 106/106/1275 418/418/696 +f 412/412/1278 411/411/1293 424/424/1270 +f 405/405/1281 412/412/1278 422/422/1280 +f 406/406/1282 405/405/1281 415/415/689 +f 374/374/606 381/381/613 372/372/604 +f 388/388/620 381/381/613 374/374/606 +f 376/376/608 372/372/604 466/466/1296 +f 379/379/611 382/382/614 380/380/612 +f 385/385/617 372/372/604 386/386/618 diff --git a/examples/Cassie/urdf/meshes/agility/heel-spring.obj b/examples/Cassie/urdf/meshes/agility/heel-spring.obj new file mode 100644 index 0000000000..7fe1a97321 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/heel-spring.obj @@ -0,0 +1,3246 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o heel-spring +v 0.124673 -0.024882 -0.010098 +v 0.124657 -0.024899 -0.007598 +v 0.112896 -0.024910 -0.010098 +v 0.112875 -0.024891 -0.007598 +v 0.112886 0.024904 -0.007598 +v 0.112869 0.024885 -0.010098 +v 0.124647 0.024922 -0.010098 +v 0.124667 0.024900 -0.007598 +v 0.119162 -0.006220 -0.013398 +v 0.119425 -0.005466 -0.013396 +v 0.120908 -0.006304 -0.013393 +v 0.116995 -0.007020 -0.013398 +v 0.116516 -0.006415 -0.013393 +v 0.117837 -0.005567 -0.013385 +v 0.120546 -0.009973 -0.013398 +v 0.121622 -0.009686 -0.013395 +v 0.120139 -0.011245 -0.013391 +v 0.120937 -0.007697 -0.013398 +v 0.121769 -0.007774 -0.013395 +v 0.115805 -0.007591 -0.013376 +v 0.116490 -0.010572 -0.013389 +v 0.115763 -0.008986 -0.013397 +v 0.116604 -0.009296 -0.013398 +v 0.118101 -0.011543 -0.013396 +v 0.118380 -0.010773 -0.013398 +v 0.121396 -0.009874 0.005817 +v 0.121759 -0.008307 0.005818 +v 0.121147 -0.006782 0.005885 +v 0.120151 -0.011174 0.005818 +v 0.117893 -0.011378 0.005818 +v 0.116455 -0.010348 0.005817 +v 0.115764 -0.008685 0.005818 +v 0.116307 -0.006824 0.005817 +v 0.117548 -0.005782 0.005817 +v 0.118998 -0.005532 0.005805 +v 0.120194 -0.005901 0.005829 +v 0.120077 -0.005691 -0.010098 +v 0.121698 -0.007564 -0.010098 +v 0.121391 -0.010190 -0.010098 +v 0.119614 -0.011399 -0.010098 +v 0.117789 -0.011407 -0.010098 +v 0.116240 -0.010173 -0.010098 +v 0.115706 -0.007913 -0.010098 +v 0.117436 -0.005705 -0.010098 +v 0.114123 -0.011016 -0.010098 +v 0.115721 -0.012838 -0.010098 +v 0.113447 -0.008452 -0.010098 +v 0.122656 -0.012166 -0.010098 +v 0.121256 -0.003764 -0.010098 +v 0.118032 -0.003224 -0.010098 +v 0.123291 -0.005752 -0.010098 +v 0.114155 -0.005917 -0.010098 +v 0.123974 -0.007629 -0.010098 +v 0.120394 -0.013516 -0.010098 +v 0.115596 -0.004268 -0.010098 +v 0.123936 -0.009625 -0.010098 +v 0.118219 -0.013770 -0.010098 +v 0.122240 -0.004572 -0.010945 +v 0.120703 -0.003607 -0.010806 +v 0.119028 -0.003223 -0.010811 +v 0.117131 -0.003486 -0.010767 +v 0.115479 -0.004364 -0.010797 +v 0.114041 -0.006140 -0.010770 +v 0.113564 -0.007737 -0.010767 +v 0.113585 -0.009430 -0.010787 +v 0.114111 -0.010954 -0.010803 +v 0.115177 -0.012330 -0.010835 +v 0.116638 -0.013323 -0.010829 +v 0.118632 -0.013777 -0.010778 +v 0.120827 -0.013360 -0.010794 +v 0.122480 -0.012163 -0.011001 +v 0.123284 -0.011222 -0.010771 +v 0.124013 -0.009204 -0.010834 +v 0.123804 -0.006937 -0.010796 +v 0.123019 -0.005371 -0.010772 +v 0.113925 -0.008770 -0.011591 +v 0.116384 -0.011688 -0.012697 +v 0.116722 -0.012632 -0.011989 +v 0.118342 -0.012294 -0.012816 +v 0.118893 -0.013345 -0.011624 +v 0.119699 -0.012437 -0.012603 +v 0.120641 -0.012686 -0.011968 +v 0.121460 -0.011469 -0.012660 +v 0.122309 -0.009946 -0.012824 +v 0.123174 -0.010161 -0.011866 +v 0.123117 -0.008151 -0.012298 +v 0.122799 -0.006803 -0.012290 +v 0.122200 -0.006098 -0.012447 +v 0.121330 -0.004996 -0.012308 +v 0.120113 -0.004509 -0.012478 +v 0.118749 -0.004218 -0.012399 +v 0.117270 -0.004236 -0.012100 +v 0.116392 -0.005437 -0.012755 +v 0.115464 -0.005029 -0.011727 +v 0.114984 -0.006284 -0.012260 +v 0.114169 -0.007326 -0.011729 +v 0.114715 -0.008228 -0.012583 +v 0.114869 -0.009838 -0.012556 +v 0.114849 -0.011126 -0.011799 +v 0.119162 -0.006220 -0.011098 +v 0.120937 -0.007697 -0.011098 +v 0.116995 -0.007020 -0.011098 +v 0.116604 -0.009296 -0.011098 +v 0.118380 -0.010773 -0.011098 +v 0.120546 -0.009973 -0.011098 +v 0.120974 0.007812 -0.013398 +v 0.121705 0.007535 -0.013387 +v 0.120495 0.005977 -0.013392 +v 0.119274 0.006250 -0.013398 +v 0.119225 0.005444 -0.013384 +v 0.117527 0.005720 -0.013393 +v 0.115670 0.008789 -0.013396 +v 0.116535 0.010641 -0.013384 +v 0.116567 0.009195 -0.013398 +v 0.118268 0.010757 -0.013398 +v 0.116210 0.006764 -0.013391 +v 0.117070 0.006941 -0.013398 +v 0.120558 0.011049 -0.013371 +v 0.120471 0.010066 -0.013398 +v 0.119590 0.011492 -0.013379 +v 0.121724 0.009493 -0.013399 +v 0.118177 0.011505 -0.013393 +v 0.115856 0.009114 0.005817 +v 0.115984 0.007463 0.005828 +v 0.121469 0.009596 0.005893 +v 0.116503 0.010413 0.005817 +v 0.117718 0.011286 0.005828 +v 0.119479 0.011417 0.005808 +v 0.120989 0.010490 0.005817 +v 0.121135 0.006702 0.005805 +v 0.121750 0.008211 0.005818 +v 0.120175 0.005898 0.005829 +v 0.118391 0.005515 0.005818 +v 0.116779 0.006296 0.005805 +v 0.115700 0.008560 -0.010098 +v 0.116316 0.010266 -0.010098 +v 0.117747 0.011400 -0.010098 +v 0.119561 0.011421 -0.010098 +v 0.121124 0.010478 -0.010098 +v 0.121780 0.008786 -0.010098 +v 0.121376 0.006835 -0.010098 +v 0.119784 0.005656 -0.010098 +v 0.117962 0.005540 -0.010098 +v 0.116343 0.006681 -0.010098 +v 0.113850 0.006468 -0.010098 +v 0.123990 0.007658 -0.010098 +v 0.123919 0.009651 -0.010098 +v 0.122848 0.005049 -0.010098 +v 0.120993 0.013364 -0.010098 +v 0.117746 0.013728 -0.010098 +v 0.115462 0.004379 -0.010098 +v 0.117416 0.003393 -0.010098 +v 0.113516 0.009093 -0.010098 +v 0.120066 0.003340 -0.010098 +v 0.114206 0.011171 -0.010098 +v 0.115530 0.012665 -0.010098 +v 0.123135 0.011488 -0.010098 +v 0.113932 0.006418 -0.010769 +v 0.114957 0.004848 -0.010787 +v 0.116254 0.003898 -0.010842 +v 0.117759 0.003330 -0.010798 +v 0.120107 0.003379 -0.010797 +v 0.122233 0.004514 -0.010789 +v 0.123442 0.006064 -0.010785 +v 0.124003 0.007764 -0.010786 +v 0.123849 0.009930 -0.010764 +v 0.123219 0.011301 -0.010810 +v 0.121936 0.012753 -0.010756 +v 0.119677 0.013708 -0.010780 +v 0.117878 0.013689 -0.010787 +v 0.116449 0.013228 -0.010822 +v 0.114985 0.012175 -0.010780 +v 0.113949 0.010611 -0.010873 +v 0.113485 0.008427 -0.010790 +v 0.120841 0.012618 -0.012006 +v 0.122815 0.009228 -0.012556 +v 0.122038 0.010761 -0.012694 +v 0.122993 0.010312 -0.011992 +v 0.122157 0.011833 -0.011718 +v 0.119186 0.012588 -0.012548 +v 0.118577 0.013184 -0.011859 +v 0.117307 0.012136 -0.012751 +v 0.116867 0.012823 -0.011765 +v 0.115640 0.011843 -0.012013 +v 0.115322 0.010756 -0.012539 +v 0.114307 0.009277 -0.012103 +v 0.114591 0.008261 -0.012458 +v 0.114384 0.006975 -0.011946 +v 0.115284 0.005964 -0.012330 +v 0.115927 0.005189 -0.012304 +v 0.117142 0.004403 -0.012214 +v 0.118162 0.004805 -0.012876 +v 0.118637 0.003891 -0.011952 +v 0.119962 0.004288 -0.012256 +v 0.121409 0.004879 -0.012154 +v 0.121607 0.005951 -0.012827 +v 0.122763 0.006417 -0.012131 +v 0.123008 0.008033 -0.012382 +v 0.123684 0.008488 -0.011490 +v 0.117070 0.006941 -0.011098 +v 0.116567 0.009195 -0.011098 +v 0.119274 0.006250 -0.011098 +v 0.120974 0.007812 -0.011098 +v 0.120471 0.010066 -0.011098 +v 0.118268 0.010757 -0.011098 +v 0.120648 0.017061 -0.013394 +v 0.120947 0.018729 -0.013398 +v 0.121692 0.018694 -0.013397 +v 0.115751 0.019929 -0.013394 +v 0.116300 0.021334 -0.013392 +v 0.116595 0.020278 -0.013398 +v 0.119188 0.017232 -0.013398 +v 0.119176 0.016468 -0.013393 +v 0.117554 0.016713 -0.013395 +v 0.118354 0.021775 -0.013398 +v 0.117473 0.022291 -0.013389 +v 0.118888 0.022574 -0.013392 +v 0.117012 0.018006 -0.013398 +v 0.116150 0.017907 -0.013398 +v 0.120529 0.021001 -0.013398 +v 0.120497 0.022032 -0.013395 +v 0.121725 0.020590 -0.013370 +v 0.121594 0.020400 0.005230 +v 0.115947 0.020390 0.005179 +v 0.115896 0.018601 0.005169 +v 0.116681 0.021634 0.005158 +v 0.118437 0.022498 0.005169 +v 0.120472 0.021967 0.005168 +v 0.120617 0.017181 0.005172 +v 0.121582 0.018460 0.005159 +v 0.119148 0.016535 0.005179 +v 0.117208 0.016950 0.005168 +v 0.115776 0.019005 -0.010098 +v 0.116137 0.021128 -0.010098 +v 0.118185 0.022519 -0.010098 +v 0.120299 0.022146 -0.010098 +v 0.121516 0.020798 -0.010098 +v 0.121788 0.019169 -0.010098 +v 0.120750 0.017092 -0.010098 +v 0.118349 0.016480 -0.010098 +v 0.116581 0.017377 -0.010098 +v 0.113831 0.017462 -0.010098 +v 0.123954 0.018460 -0.010098 +v 0.123959 0.020456 -0.010098 +v 0.122715 0.015897 -0.010098 +v 0.118783 0.024791 -0.010098 +v 0.115464 0.015394 -0.010098 +v 0.117224 0.014448 -0.010098 +v 0.113543 0.020292 -0.010098 +v 0.119869 0.014294 -0.010098 +v 0.114310 0.022342 -0.010098 +v 0.121341 0.024166 -0.010098 +v 0.116216 0.024176 -0.010098 +v 0.123245 0.022321 -0.010098 +v 0.113896 0.017464 -0.010792 +v 0.115006 0.015815 -0.010776 +v 0.116245 0.014892 -0.010799 +v 0.117947 0.014283 -0.010783 +v 0.120001 0.014374 -0.010839 +v 0.121907 0.015272 -0.010805 +v 0.123281 0.016728 -0.010798 +v 0.124009 0.018904 -0.010767 +v 0.123918 0.020635 -0.010792 +v 0.123343 0.022091 -0.010827 +v 0.122213 0.023512 -0.010766 +v 0.120231 0.024563 -0.010878 +v 0.118037 0.024741 -0.010772 +v 0.116128 0.024049 -0.010835 +v 0.114799 0.022970 -0.010841 +v 0.114061 0.021799 -0.010933 +v 0.113495 0.019743 -0.010755 +v 0.123277 0.017469 -0.011466 +v 0.122646 0.019662 -0.012769 +v 0.123240 0.021056 -0.011827 +v 0.121868 0.022031 -0.012652 +v 0.122014 0.023228 -0.011510 +v 0.120803 0.022953 -0.012666 +v 0.119919 0.023658 -0.012327 +v 0.118422 0.023895 -0.012247 +v 0.117187 0.023634 -0.012223 +v 0.115953 0.022784 -0.012320 +v 0.114954 0.021388 -0.012391 +v 0.115008 0.020314 -0.012789 +v 0.113967 0.020250 -0.011578 +v 0.115040 0.018966 -0.012859 +v 0.114075 0.018897 -0.011771 +v 0.114702 0.017803 -0.012223 +v 0.115044 0.016684 -0.011883 +v 0.116207 0.016664 -0.012814 +v 0.116099 0.015492 -0.011631 +v 0.117238 0.015289 -0.012141 +v 0.118339 0.015344 -0.012500 +v 0.119941 0.015253 -0.012237 +v 0.121013 0.015690 -0.012221 +v 0.122112 0.016695 -0.012268 +v 0.122333 0.017855 -0.012741 +v 0.123395 0.019156 -0.011921 +v 0.117012 0.018006 -0.011098 +v 0.116595 0.020278 -0.011098 +v 0.119188 0.017232 -0.011098 +v 0.120947 0.018729 -0.011098 +v 0.120529 0.021001 -0.011098 +v 0.118354 0.021775 -0.011098 +v 0.121845 -0.019120 -0.013385 +v 0.121524 -0.020970 -0.013378 +v 0.120952 -0.020255 -0.013398 +v 0.116589 -0.018738 -0.013398 +v 0.115746 -0.018905 -0.013395 +v 0.116882 -0.017096 -0.013395 +v 0.118659 -0.016439 -0.013397 +v 0.118337 -0.017228 -0.013398 +v 0.117023 -0.021007 -0.013398 +v 0.116631 -0.021710 -0.013388 +v 0.115874 -0.020504 -0.013390 +v 0.119205 -0.021765 -0.013398 +v 0.118211 -0.022573 -0.013390 +v 0.120340 -0.022107 -0.013394 +v 0.120207 -0.016750 -0.013373 +v 0.121257 -0.017672 -0.013390 +v 0.120518 -0.017986 -0.013398 +v 0.121169 -0.021206 0.004521 +v 0.118646 -0.022467 0.004476 +v 0.120059 -0.022176 0.004444 +v 0.116802 -0.021786 0.004437 +v 0.115859 -0.020133 0.004460 +v 0.115961 -0.018519 0.004467 +v 0.117162 -0.016945 0.004449 +v 0.118866 -0.016538 0.004468 +v 0.120454 -0.017015 0.004448 +v 0.121532 -0.018388 0.004467 +v 0.121713 -0.019863 0.004456 +v 0.120853 -0.021728 -0.010098 +v 0.119043 -0.022537 -0.010098 +v 0.116818 -0.021897 -0.010098 +v 0.115780 -0.020017 -0.010098 +v 0.116060 -0.018051 -0.010098 +v 0.117682 -0.016645 -0.010098 +v 0.119495 -0.016548 -0.010098 +v 0.120932 -0.017364 -0.010098 +v 0.121890 -0.019478 -0.010098 +v 0.123341 -0.022155 -0.010098 +v 0.117046 -0.014498 -0.010098 +v 0.115323 -0.015504 -0.010098 +v 0.119884 -0.014269 -0.010098 +v 0.113437 -0.019840 -0.010098 +v 0.114316 -0.022321 -0.010098 +v 0.124093 -0.019631 -0.010098 +v 0.121344 -0.024181 -0.010098 +v 0.122211 -0.015498 -0.010098 +v 0.118131 -0.024782 -0.010098 +v 0.123461 -0.017057 -0.010098 +v 0.115676 -0.023784 -0.010098 +v 0.114075 -0.017065 -0.010098 +v 0.122348 -0.023386 -0.010802 +v 0.123539 -0.021743 -0.010778 +v 0.123956 -0.020000 -0.011025 +v 0.123994 -0.018790 -0.010791 +v 0.123368 -0.016891 -0.010775 +v 0.122555 -0.015866 -0.010861 +v 0.121004 -0.014713 -0.010821 +v 0.119230 -0.014270 -0.010854 +v 0.117683 -0.014332 -0.010788 +v 0.115736 -0.015176 -0.010838 +v 0.114319 -0.016670 -0.010760 +v 0.113572 -0.018557 -0.010771 +v 0.113617 -0.020666 -0.010775 +v 0.114485 -0.022480 -0.010971 +v 0.115006 -0.023181 -0.010784 +v 0.116243 -0.024114 -0.010768 +v 0.118167 -0.024759 -0.010791 +v 0.120501 -0.024490 -0.010760 +v 0.115029 -0.016741 -0.011909 +v 0.116122 -0.015946 -0.012196 +v 0.115802 -0.017256 -0.012903 +v 0.114513 -0.017959 -0.012102 +v 0.114281 -0.019310 -0.012135 +v 0.114524 -0.020804 -0.012213 +v 0.115323 -0.021735 -0.012532 +v 0.116123 -0.023525 -0.011674 +v 0.116170 -0.022712 -0.012505 +v 0.117321 -0.023549 -0.012322 +v 0.118305 -0.024163 -0.011856 +v 0.118854 -0.023341 -0.012797 +v 0.119646 -0.024208 -0.011674 +v 0.120261 -0.023138 -0.012715 +v 0.121208 -0.023602 -0.011731 +v 0.121617 -0.022371 -0.012609 +v 0.122607 -0.022316 -0.011716 +v 0.122750 -0.021260 -0.012279 +v 0.122800 -0.019900 -0.012599 +v 0.123236 -0.018487 -0.012004 +v 0.122746 -0.017573 -0.012224 +v 0.121504 -0.016319 -0.012472 +v 0.121291 -0.015463 -0.011745 +v 0.119841 -0.015459 -0.012503 +v 0.118533 -0.015034 -0.012159 +v 0.117386 -0.015577 -0.012523 +v 0.120952 -0.020255 -0.011098 +v 0.119205 -0.021765 -0.011098 +v 0.120518 -0.017986 -0.011098 +v 0.118337 -0.017228 -0.011098 +v 0.116589 -0.018738 -0.011098 +v 0.117023 -0.021007 -0.011098 +v 0.119629 -0.013568 0.015979 +v 0.117687 -0.013744 0.015910 +v 0.116157 -0.015145 0.015432 +v 0.121761 -0.015469 0.015234 +v 0.118121 -0.015759 0.015006 +v 0.114615 -0.016492 0.014359 +v 0.120262 -0.016017 0.014802 +v 0.123099 -0.016634 0.014182 +v 0.122386 -0.017072 0.013584 +v 0.115535 -0.016823 0.013949 +v 0.124771 -0.024894 0.002054 +v 0.118220 -0.022957 0.004919 +v 0.112771 -0.024877 0.002080 +v 0.121049 -0.022553 0.005512 +v 0.115489 -0.022103 0.006172 +v 0.122669 -0.021665 0.006814 +v 0.112977 -0.018161 0.011954 +v 0.114236 -0.020971 0.007832 +v 0.124611 -0.018291 0.011763 +v 0.123733 -0.020179 0.008995 +v 0.113729 -0.019597 0.009848 +v 0.114075 -0.018279 0.011782 +v 0.123628 -0.018606 0.011302 +v 0.124771 -0.024997 0.000002 +v 0.112771 -0.024997 0.000002 +v 0.112771 -0.004759 0.000002 +v 0.112858 -0.004759 0.011327 +v 0.116228 -0.011744 0.014338 +v 0.118297 -0.011744 0.015038 +v 0.120826 -0.011745 0.014614 +v 0.122513 -0.011744 0.013350 +v 0.114618 -0.011744 0.012880 +v 0.123619 -0.011745 0.011463 +v 0.123618 -0.011744 0.008461 +v 0.119431 -0.011744 0.004992 +v 0.117362 -0.011744 0.005183 +v 0.121884 -0.011744 0.006009 +v 0.115609 -0.011744 0.006072 +v 0.123810 -0.004759 0.013388 +v 0.124722 -0.004759 0.010931 +v 0.121330 -0.004759 0.015517 +v 0.118203 -0.004759 0.016027 +v 0.115893 -0.004759 0.015296 +v 0.114132 -0.004759 0.013880 +v 0.120337 0.014193 0.015823 +v 0.114996 0.016165 0.014748 +v 0.117684 0.013754 0.015961 +v 0.122129 0.015800 0.015004 +v 0.123298 0.016804 0.013959 +v 0.112771 0.024904 0.002035 +v 0.119250 0.022058 0.006248 +v 0.124771 0.024887 0.002066 +v 0.118825 0.016920 0.013785 +v 0.112930 0.018299 0.011763 +v 0.117414 0.021636 0.006867 +v 0.117146 0.017574 0.012826 +v 0.120885 0.018013 0.012182 +v 0.121206 0.020450 0.008607 +v 0.116443 0.020529 0.008492 +v 0.116312 0.018816 0.011003 +v 0.124631 0.018367 0.011662 +v 0.112926 0.004766 0.011685 +v 0.112771 0.004766 0.000002 +v 0.112771 0.025003 0.000002 +v 0.124771 0.025003 0.000002 +v 0.124771 0.004766 0.000002 +v 0.124771 -0.004759 0.000002 +v 0.114368 0.004766 0.014113 +v 0.116218 0.004766 0.015477 +v 0.118312 0.004766 0.016002 +v 0.120968 0.004766 0.015676 +v 0.123581 0.004766 0.013704 +v 0.124704 0.004766 0.011118 +v 0.116960 0.018485 0.008917 +v 0.117431 0.010994 0.008345 +v 0.116729 0.010910 0.009415 +v 0.117324 0.018906 0.010571 +v 0.118012 0.018900 0.011336 +v 0.117443 0.018942 0.009181 +v 0.120313 -0.016473 0.011036 +v 0.120349 -0.016524 0.014292 +v 0.118655 -0.016483 0.011854 +v 0.120438 -0.016425 0.009798 +v 0.123341 -0.016442 0.008940 +v 0.122731 -0.016522 0.012103 +v 0.120369 -0.016502 0.009036 +v 0.120659 -0.016522 0.005908 +v 0.122657 -0.016522 0.007766 +v 0.117257 -0.016418 0.014436 +v 0.114433 -0.016524 0.008562 +v 0.117192 -0.016524 0.005713 +v 0.117133 -0.016503 0.009107 +v 0.118727 -0.016502 0.008137 +v 0.117117 -0.016463 0.010821 +v 0.114836 -0.016523 0.012261 +v 0.119338 -0.011759 0.005155 +v 0.119178 -0.016192 0.005171 +v 0.116566 -0.016190 0.005740 +v 0.115984 -0.011759 0.006035 +v 0.114935 -0.016190 0.007118 +v 0.114349 -0.011759 0.008139 +v 0.114063 -0.016190 0.009069 +v 0.113987 -0.011759 0.010792 +v 0.114125 -0.016190 0.011203 +v 0.115268 -0.016190 0.013315 +v 0.115344 -0.011759 0.013393 +v 0.117937 -0.011759 0.014778 +v 0.119713 -0.016191 0.014730 +v 0.120840 -0.011759 0.014357 +v 0.122294 -0.016192 0.013332 +v 0.122668 -0.011759 0.012803 +v 0.123545 -0.016191 0.010675 +v 0.123497 -0.011759 0.010835 +v 0.123390 -0.011759 0.008702 +v 0.122101 -0.016192 0.006479 +v 0.122198 -0.011759 0.006611 +v 0.119554 -0.011759 0.006888 +v 0.117611 -0.011759 0.006985 +v 0.120734 -0.011759 0.012644 +v 0.122027 -0.011759 0.010143 +v 0.121226 -0.011759 0.007898 +v 0.116445 -0.011759 0.012286 +v 0.118419 -0.011759 0.013194 +v 0.115539 -0.011759 0.010085 +v 0.116099 -0.011759 0.008221 +v 0.118051 0.010377 0.006974 +v 0.116616 0.010135 0.007622 +v 0.115493 0.010141 0.009730 +v 0.116249 0.010135 0.011990 +v 0.117852 0.010136 0.013101 +v 0.119799 0.010134 0.013044 +v 0.121230 0.010134 0.012067 +v 0.122029 0.010138 0.010050 +v 0.121166 0.010136 0.007832 +v 0.119495 0.010403 0.007030 +v 0.118237 0.010519 0.007958 +v 0.119616 0.010497 0.007978 +v 0.121499 0.010469 0.008817 +v 0.120879 0.010503 0.009306 +v 0.115906 0.010469 0.009199 +v 0.117204 0.010514 0.008591 +v 0.121078 0.010469 0.011880 +v 0.120555 0.010500 0.011342 +v 0.119562 0.010504 0.011972 +v 0.118767 0.010466 0.012895 +v 0.118490 0.010509 0.012133 +v 0.116619 0.010468 0.012010 +v 0.116883 0.010491 0.011227 +v 0.116625 0.010498 0.009616 +v 0.118480 0.010980 0.007908 +v 0.117382 0.010804 0.011639 +v 0.118058 0.010977 0.011969 +v 0.119041 0.010958 0.012079 +v 0.119972 0.010969 0.011736 +v 0.120610 0.010886 0.011063 +v 0.120932 0.010862 0.009932 +v 0.120516 0.010950 0.008775 +v 0.119614 0.010898 0.008018 +v 0.116728 0.010894 0.010584 +v 0.119437 0.018553 0.007955 +v 0.120838 0.018507 0.009579 +v 0.120477 0.018487 0.011307 +v 0.118910 0.018491 0.012092 +v 0.117727 0.018490 0.011794 +v 0.116794 0.018476 0.010749 +v 0.118294 0.018587 0.007886 +v 0.120291 0.018933 0.009727 +v 0.118007 -0.016259 0.008610 +v 0.119594 -0.016258 0.008645 +v 0.118811 -0.014140 0.008169 +v 0.120378 -0.014140 0.009121 +v 0.117204 -0.014140 0.009051 +v 0.120338 -0.014140 0.010953 +v 0.117163 -0.014140 0.010883 +v 0.118730 -0.014140 0.011835 +v 0.000001 -0.024997 -0.007598 +v 0.000001 0.025003 -0.007598 +v 0.124771 0.025003 -0.007598 +v 0.124771 -0.024997 -0.007598 +v 0.000001 -0.024997 0.000002 +v 0.124771 -0.024997 0.000002 +v 0.120450 0.021505 0.003789 +v 0.116222 0.019867 0.003789 +v 0.117006 0.021304 0.003789 +v 0.118299 0.022013 0.003789 +v 0.118290 0.016949 0.003789 +v 0.114247 -0.011744 0.007792 +v 0.113704 -0.011744 0.010275 +v 0.116687 0.018044 0.003789 +v 0.121324 0.019476 0.003789 +v 0.120578 0.017676 0.003789 +v 0.124771 0.025003 0.000002 +v 0.000001 0.025003 0.000002 +v 0.118848 0.018908 0.011552 +v 0.120031 0.018915 0.010964 +v 0.119181 0.018978 0.008445 +v 0.118463 0.018938 0.008391 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn 0.0024 -1.0000 -0.0068 +vn 0.0020 -1.0000 -0.0049 +vn -0.0003 -1.0000 0.0057 +vn -0.0007 -1.0000 0.0076 +vn -1.0000 0.0002 0.0068 +vn -1.0000 0.0002 0.0063 +vn -1.0000 -0.0005 -0.0079 +vn -1.0000 -0.0005 -0.0084 +vn -0.0031 1.0000 -0.0076 +vn -0.0027 1.0000 -0.0054 +vn -0.0001 1.0000 0.0066 +vn 0.0003 1.0000 0.0088 +vn 1.0000 -0.0002 0.0059 +vn 1.0000 0.0005 -0.0080 +vn 1.0000 0.0005 -0.0075 +vn 1.0000 -0.0002 0.0064 +vn -0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.0020 0.0051 -1.0000 +vn -0.0017 0.0033 -1.0000 +vn 0.0032 0.0033 -1.0000 +vn -0.0104 0.0037 -0.9999 +vn -0.0071 0.0027 -1.0000 +vn -0.0040 0.0097 -0.9999 +vn 0.0037 -0.0050 -1.0000 +vn 0.0033 -0.0017 -1.0000 +vn 0.0028 -0.0060 -1.0000 +vn 0.0036 0.0020 -1.0000 +vn 0.0036 0.0011 -1.0000 +vn -0.0149 0.0037 -0.9999 +vn -0.0050 -0.0056 -1.0000 +vn 0.0020 0.0086 -1.0000 +vn -0.0050 -0.0012 -1.0000 +vn -0.0014 -0.0021 -1.0000 +vn -0.0008 -0.0036 -1.0000 +vn 0.0274 -0.0198 0.9994 +vn 0.0682 -0.0164 0.9975 +vn 0.0048 0.0051 1.0000 +vn 0.0060 -0.0166 0.9998 +vn -0.0043 -0.0116 0.9999 +vn -0.0091 -0.0072 0.9999 +vn -0.0120 -0.0013 0.9999 +vn -0.0141 0.0080 0.9999 +vn -0.0122 0.0242 0.9996 +vn -0.0020 0.0604 0.9982 +vn -0.0007 0.0627 0.9980 +vn 0.4145 0.9100 -0.0081 +vn 0.8220 0.5694 0.0087 +vn 0.9554 0.2951 -0.0075 +vn 0.9969 0.0777 0.0086 +vn 0.9923 -0.1232 -0.0084 +vn 0.9742 -0.2257 0.0042 +vn 0.5747 -0.8183 -0.0058 +vn 0.7222 -0.6916 0.0135 +vn 0.4329 -0.9014 0.0122 +vn 0.2936 -0.9559 -0.0023 +vn 0.0838 -0.9964 0.0104 +vn 0.0044 -1.0000 0.0018 +vn -0.6203 -0.7844 0.0002 +vn -0.5823 -0.8130 0.0053 +vn -0.7823 -0.6229 0.0068 +vn -0.8433 -0.5375 -0.0036 +vn -0.9983 -0.0577 0.0125 +vn -0.9770 0.2131 -0.0099 +vn -0.8359 0.5487 0.0118 +vn -0.7788 0.6271 -0.0112 +vn -0.6430 0.7658 0.0082 +vn -0.0150 0.9998 -0.0094 +vn -0.1699 0.9855 0.0060 +vn 0.0636 0.9980 0.0075 +vn 0.5045 0.8634 0.0077 +vn 0.6424 0.7170 -0.2706 +vn 0.3239 0.9032 -0.2816 +vn 0.4703 0.8807 -0.0566 +vn 0.0790 0.9758 -0.2037 +vn -0.1325 0.9905 -0.0365 +vn -0.3242 0.9221 -0.2111 +vn -0.5938 0.8045 0.0167 +vn -0.6099 0.7542 -0.2432 +vn -0.8648 0.5020 -0.0063 +vn -0.8757 0.4253 -0.2286 +vn -0.9990 0.0118 -0.0437 +vn -0.9633 0.1811 -0.1982 +vn -0.9552 -0.2081 -0.2103 +vn -0.8761 -0.4820 0.0141 +vn -0.8585 -0.4395 -0.2642 +vn -0.6759 -0.6916 -0.2547 +vn -0.5752 -0.8177 -0.0243 +vn -0.3697 -0.9040 -0.2146 +vn -0.1281 -0.9916 -0.0149 +vn -0.0114 -0.9723 -0.2336 +vn 0.2854 -0.9584 -0.0099 +vn 0.3941 -0.8907 -0.2267 +vn 0.7126 -0.6997 -0.0507 +vn 0.6428 -0.6711 -0.3694 +vn 0.8597 -0.4760 -0.1853 +vn 0.9681 -0.2505 0.0022 +vn 0.9609 -0.1086 -0.2546 +vn 0.9887 0.1412 -0.0504 +vn 0.9267 0.2848 -0.2452 +vn 0.8528 0.5222 -0.0013 +vn 0.7705 0.5925 -0.2351 +vn -0.8446 -0.0575 -0.5324 +vn -0.4689 -0.3971 -0.7889 +vn -0.1308 -0.5971 -0.7914 +vn -0.4329 -0.5510 -0.7134 +vn -0.3485 -0.7240 -0.5953 +vn -0.0796 -0.6839 -0.7252 +vn 0.0175 -0.8425 -0.5385 +vn 0.1640 -0.6817 -0.7130 +vn 0.2669 -0.5352 -0.8015 +vn 0.3387 -0.7317 -0.5915 +vn 0.4791 -0.5185 -0.7082 +vn 0.5517 -0.2196 -0.8046 +vn 0.6272 -0.2472 -0.7386 +vn 0.7609 -0.2994 -0.5756 +vn 0.7613 0.0444 -0.6469 +vn 0.6039 0.1361 -0.7854 +vn 0.7049 0.3092 -0.6384 +vn 0.5998 0.4371 -0.6703 +vn 0.4338 0.4436 -0.7843 +vn 0.4464 0.6240 -0.6413 +vn 0.2519 0.7046 -0.6634 +vn 0.1365 0.5972 -0.7904 +vn -0.0135 0.7548 -0.6558 +vn -0.2652 0.7465 -0.6102 +vn -0.1896 0.5968 -0.7797 +vn -0.4115 0.5425 -0.7324 +vn -0.4595 0.4137 -0.7860 +vn -0.5776 0.6052 -0.5478 +vn -0.6597 0.3760 -0.6507 +vn -0.6048 0.1925 -0.7728 +vn -0.8039 0.2084 -0.5571 +vn -0.7060 0.0567 -0.7059 +vn -0.5928 -0.1072 -0.7982 +vn -0.6812 -0.2457 -0.6896 +vn -0.6736 -0.4616 -0.5773 +vn -0.6396 -0.7687 0.0000 +vn 0.3463 -0.9381 -0.0000 +vn 0.9856 -0.1693 0.0000 +vn 0.6394 0.7689 0.0000 +vn -0.3465 0.9381 0.0000 +vn -0.9856 0.1693 0.0000 +vn 0.0094 -0.0052 -0.9999 +vn 0.0126 -0.0064 -0.9999 +vn 0.0046 -0.0077 -1.0000 +vn 0.0018 -0.0126 -0.9999 +vn 0.0018 -0.0175 -0.9998 +vn -0.0019 -0.0073 -1.0000 +vn -0.0042 0.0018 -1.0000 +vn -0.0083 0.0089 -0.9999 +vn -0.0055 0.0063 -1.0000 +vn -0.0006 0.0090 -1.0000 +vn -0.0071 -0.0052 -1.0000 +vn -0.0053 -0.0050 -1.0000 +vn 0.0176 0.0259 -0.9995 +vn 0.0089 0.0188 -0.9998 +vn 0.0093 0.0169 -0.9998 +vn 0.0038 0.0041 -1.0000 +vn 0.0016 0.0069 -1.0000 +vn -0.0141 0.0062 0.9999 +vn -0.0085 -0.0085 0.9999 +vn 0.0157 0.0105 0.9998 +vn -0.0141 0.0071 0.9999 +vn -0.0100 0.0162 0.9998 +vn 0.0119 0.0596 0.9981 +vn 0.0683 0.1209 0.9903 +vn 0.0577 -0.0370 0.9977 +vn 0.0743 -0.0389 0.9965 +vn 0.0092 -0.0205 0.9997 +vn -0.0096 -0.0111 0.9999 +vn -0.0070 -0.0167 0.9998 +vn -1.0000 0.0093 -0.0037 +vn -0.9434 -0.3316 0.0104 +vn -0.9812 0.1925 0.0094 +vn -0.8113 0.5846 -0.0011 +vn -0.7609 0.6488 0.0056 +vn -0.6189 0.7855 0.0003 +vn -0.5835 0.8121 0.0048 +vn -0.0160 0.9999 0.0007 +vn -0.0741 0.9972 0.0070 +vn -0.0696 0.9976 0.0065 +vn -0.0116 0.9999 0.0002 +vn 0.5166 0.8562 0.0029 +vn 0.5227 0.8525 0.0037 +vn 0.5171 0.8559 0.0029 +vn 0.5232 0.8522 0.0038 +vn 0.9306 0.3661 0.0001 +vn 0.8808 0.4735 0.0071 +vn 0.9407 0.3392 0.0078 +vn 0.9964 0.0844 -0.0026 +vn 0.9961 -0.0872 0.0097 +vn 0.8420 -0.5394 -0.0035 +vn 0.8059 -0.5920 0.0073 +vn 0.4398 -0.8981 0.0064 +vn 0.3436 -0.9391 -0.0025 +vn -0.1180 -0.9930 0.0101 +vn -0.2715 -0.9624 -0.0033 +vn -0.6542 -0.7563 0.0094 +vn -0.7998 -0.6002 -0.0045 +vn -0.8779 -0.3893 -0.2789 +vn -0.7270 -0.6506 -0.2197 +vn -0.9265 -0.3750 -0.0308 +vn -0.6203 -0.7843 0.0031 +vn -0.4570 -0.8531 -0.2517 +vn -0.2543 -0.9671 0.0035 +vn -0.1525 -0.9584 -0.2411 +vn 0.2442 -0.9697 -0.0074 +vn 0.2537 -0.9301 -0.2656 +vn 0.6039 -0.7684 -0.2118 +vn 0.5139 -0.8365 0.1903 +vn 0.8758 -0.4388 -0.2008 +vn 0.8149 -0.5649 -0.1300 +vn 0.9853 -0.1695 0.0232 +vn 0.9579 -0.1349 -0.2534 +vn 0.9818 0.1896 -0.0108 +vn 0.9365 0.2617 -0.2334 +vn 0.8165 0.5773 -0.0049 +vn 0.8161 0.5128 -0.2665 +vn 0.6002 0.7808 -0.1734 +vn 0.6398 0.7305 0.2386 +vn 0.1626 0.9720 -0.1697 +vn 0.3763 0.8830 -0.2807 +vn -0.1835 0.9830 -0.0098 +vn 0.1071 0.9554 0.2752 +vn -0.1494 0.9475 -0.2828 +vn -0.4365 0.8723 -0.2205 +vn -0.6011 0.7991 -0.0068 +vn -0.7064 0.6687 -0.2322 +vn -0.8602 0.5093 -0.0264 +vn -0.8860 0.3748 -0.2732 +vn -0.9902 0.1352 -0.0340 +vn -0.9746 -0.0366 -0.2210 +vn 0.3524 0.7183 -0.5999 +vn 0.7057 0.1158 -0.6990 +vn 0.5557 0.4154 -0.7201 +vn 0.7458 0.3185 -0.5851 +vn 0.5824 0.1798 -0.7928 +vn 0.5963 0.5755 -0.5597 +vn 0.3800 0.5250 -0.7616 +vn 0.1691 0.6185 -0.7674 +vn 0.0822 0.7151 -0.6941 +vn -0.0330 0.8190 -0.5728 +vn -0.1156 0.5927 -0.7971 +vn -0.2593 0.6329 -0.7296 +vn -0.3276 0.7580 -0.5640 +vn -0.5484 0.5830 -0.5994 +vn -0.4447 0.4230 -0.7895 +vn -0.6135 0.3811 -0.6916 +vn -0.6236 0.0451 -0.7804 +vn -0.7791 0.1443 -0.6100 +vn -0.7237 -0.0881 -0.6844 +vn -0.7598 -0.2606 -0.5957 +vn -0.5323 -0.3305 -0.7794 +vn -0.6310 -0.4249 -0.6490 +vn -0.4839 -0.5849 -0.6509 +vn -0.2661 -0.5462 -0.7942 +vn -0.2870 -0.7198 -0.6321 +vn -0.0929 -0.6490 -0.7551 +vn -0.0191 -0.8110 -0.5848 +vn 0.1018 -0.6224 -0.7760 +vn 0.2113 -0.7291 -0.6510 +vn 0.4590 -0.6430 -0.6131 +vn 0.3365 -0.5118 -0.7905 +vn 0.4941 -0.4345 -0.7530 +vn 0.7028 -0.3638 -0.6113 +vn 0.5859 -0.1848 -0.7890 +vn 0.7368 -0.1033 -0.6682 +vn 0.8634 0.0042 -0.5046 +vn 0.9760 0.2178 0.0000 +vn 0.2992 0.9542 0.0000 +vn -0.6766 0.7364 0.0000 +vn -0.9760 -0.2178 0.0000 +vn -0.2993 -0.9542 0.0000 +vn 0.6764 -0.7366 0.0000 +vn 0.0021 -0.0035 -1.0000 +vn 0.0049 0.0032 -1.0000 +vn 0.0017 0.0074 -1.0000 +vn -0.0055 0.0019 -1.0000 +vn -0.0047 0.0052 -1.0000 +vn -0.0048 0.0031 -1.0000 +vn 0.0011 -0.0052 -1.0000 +vn 0.0010 -0.0066 -1.0000 +vn -0.0005 -0.0033 -1.0000 +vn -0.0027 0.0080 -1.0000 +vn -0.0047 0.0094 -0.9999 +vn -0.0009 0.0081 -1.0000 +vn -0.0001 -0.0015 -1.0000 +vn -0.0007 -0.0006 -1.0000 +vn 0.0180 0.0037 -0.9998 +vn 0.0071 0.0039 -1.0000 +vn 0.0213 0.0059 -0.9998 +vn 0.0049 0.0013 1.0000 +vn -0.0090 0.0055 0.9999 +vn -0.0087 -0.0063 0.9999 +vn -0.0098 0.0192 0.9998 +vn -0.0084 0.0164 0.9998 +vn 0.0133 0.0490 0.9987 +vn 0.0210 -0.0244 0.9995 +vn 0.0623 -0.0369 0.9974 +vn -0.0023 -0.0118 0.9999 +vn -0.0081 -0.0077 0.9999 +vn -0.9895 -0.1447 -0.0041 +vn -0.9495 -0.3135 0.0117 +vn -0.9614 0.2748 0.0109 +vn -0.8417 0.5398 -0.0056 +vn -0.6791 0.7340 0.0107 +vn -0.5525 0.8335 -0.0061 +vn -0.4415 0.8972 0.0085 +vn 0.1738 0.9848 -0.0015 +vn 0.2456 0.9693 0.0076 +vn 0.1806 0.9836 -0.0006 +vn 0.2525 0.9676 0.0085 +vn 0.7422 0.6701 -0.0006 +vn 0.8080 0.5891 0.0101 +vn 0.9005 0.4350 -0.0002 +vn 0.9527 0.3038 0.0122 +vn 0.9893 -0.1459 -0.0042 +vn 0.9478 -0.3187 0.0114 +vn 0.6278 -0.7784 -0.0086 +vn 0.6193 -0.7851 0.0100 +vn 0.1035 -0.9946 0.0111 +vn -0.1107 -0.9938 -0.0074 +vn -0.5264 -0.8501 0.0146 +vn -0.7111 -0.7031 -0.0049 +vn -0.8886 -0.3631 -0.2801 +vn -0.7191 -0.6645 -0.2034 +vn -0.9278 -0.3707 -0.0412 +vn -0.6287 -0.7776 0.0109 +vn -0.4571 -0.8605 -0.2250 +vn -0.2979 -0.9545 -0.0112 +vn -0.1214 -0.9682 -0.2188 +vn 0.2111 -0.9774 -0.0128 +vn 0.2335 -0.9279 -0.2906 +vn 0.5521 -0.8088 -0.2024 +vn 0.6701 -0.7328 -0.1181 +vn 0.8443 -0.4993 -0.1948 +vn 0.9720 -0.2336 -0.0251 +vn 0.8809 -0.4258 0.2067 +vn 0.9677 -0.1015 -0.2306 +vn 0.9845 0.1751 0.0054 +vn 0.9488 0.2062 -0.2391 +vn 0.8411 0.5408 -0.0106 +vn 0.8374 0.4742 -0.2718 +vn 0.6484 0.7436 -0.1631 +vn 0.4763 0.8755 -0.0811 +vn 0.2584 0.9329 -0.2510 +vn 0.0269 0.9993 -0.0255 +vn -0.1515 0.9661 -0.2091 +vn -0.4718 0.8810 -0.0348 +vn -0.4795 0.8243 -0.3011 +vn -0.7151 0.6544 -0.2456 +vn -0.8465 0.5324 0.0074 +vn -0.8674 0.4008 -0.2948 +vn -0.9848 0.1714 -0.0278 +vn -0.9823 0.0098 -0.1870 +vn 0.7972 -0.3317 -0.5044 +vn 0.6750 0.0279 -0.7373 +vn 0.5848 0.2199 -0.7808 +vn 0.7650 0.2757 -0.5820 +vn 0.5597 0.4322 -0.7070 +vn 0.5566 0.6442 -0.5246 +vn 0.3290 0.4917 -0.8062 +vn 0.3487 0.6133 -0.7087 +vn 0.2031 0.7320 -0.6503 +vn 0.0277 0.6267 -0.7787 +vn -0.0474 0.7675 -0.6393 +vn -0.2826 0.7188 -0.6352 +vn -0.2661 0.5747 -0.7739 +vn -0.5035 0.5663 -0.6526 +vn -0.4986 0.3775 -0.7803 +vn -0.6654 0.3510 -0.6589 +vn -0.6695 0.1362 -0.7302 +vn -0.8327 0.1392 -0.5360 +vn -0.5687 0.0731 -0.8193 +vn -0.6494 -0.0917 -0.7549 +vn -0.8270 -0.1017 -0.5530 +vn -0.5168 -0.3059 -0.7996 +vn -0.7031 -0.2975 -0.6458 +vn -0.6475 -0.4971 -0.5776 +vn -0.4451 -0.5002 -0.7428 +vn -0.4737 -0.6911 -0.5459 +vn -0.2392 -0.5563 -0.7958 +vn -0.2747 -0.7328 -0.6225 +vn -0.0613 -0.7305 -0.6801 +vn 0.0908 -0.6102 -0.7870 +vn 0.1884 -0.7448 -0.6402 +vn 0.3973 -0.6627 -0.6349 +vn 0.3771 -0.4922 -0.7846 +vn 0.5792 -0.5042 -0.6405 +vn 0.6185 -0.2807 -0.7339 +vn 0.5563 -0.1564 -0.8161 +vn 0.8101 -0.0617 -0.5831 +vn 0.9836 0.1805 0.0000 +vn 0.3351 0.9422 0.0000 +vn -0.6481 0.7615 0.0000 +vn -0.9835 -0.1809 0.0000 +vn -0.3353 -0.9421 0.0000 +vn 0.6481 -0.7615 0.0000 +vn 0.0140 -0.0000 -0.9999 +vn 0.0235 -0.0092 -0.9997 +vn 0.0188 -0.0057 -0.9998 +vn -0.0039 0.0005 -1.0000 +vn -0.0033 -0.0014 -1.0000 +vn -0.0022 0.0022 -1.0000 +vn 0.0035 0.0061 -1.0000 +vn -0.0011 0.0017 -1.0000 +vn -0.0077 -0.0071 -0.9999 +vn -0.0084 -0.0095 -0.9999 +vn -0.0075 -0.0033 -1.0000 +vn 0.0002 -0.0078 -1.0000 +vn -0.0027 -0.0082 -1.0000 +vn 0.0060 -0.0057 -1.0000 +vn 0.0163 0.0243 -0.9996 +vn 0.0069 0.0092 -0.9999 +vn 0.0085 0.0115 -0.9999 +vn 0.0102 -0.0087 0.9999 +vn -0.0126 -0.0104 0.9999 +vn 0.0505 -0.1363 0.9894 +vn -0.0169 -0.0178 0.9997 +vn -0.0135 -0.0101 0.9999 +vn -0.0073 0.0060 1.0000 +vn -0.0071 0.0102 0.9999 +vn -0.0026 0.0101 0.9999 +vn 0.0162 0.0202 0.9997 +vn 0.0155 0.0172 0.9997 +vn 0.1052 0.0055 0.9944 +vn 0.7033 -0.7109 -0.0050 +vn 0.4458 -0.8951 0.0111 +vn 0.0691 -0.9976 -0.0041 +vn -0.0765 -0.9970 0.0083 +vn -0.2825 -0.9593 -0.0021 +vn -0.3466 -0.9380 0.0068 +vn -0.8749 -0.4844 0.0011 +vn -0.8686 -0.4955 0.0028 +vn -0.8692 -0.4944 0.0026 +vn -0.8754 -0.4834 0.0009 +vn -0.9908 0.1356 -0.0016 +vn -0.9980 0.0631 0.0059 +vn -0.9378 0.3470 0.0100 +vn -0.8789 0.4770 -0.0044 +vn -0.5445 0.8387 0.0126 +vn -0.3730 0.9278 -0.0051 +vn 0.0286 0.9995 0.0116 +vn 0.2289 0.9734 -0.0034 +vn 0.5635 0.8261 0.0113 +vn 0.7377 0.6751 -0.0062 +vn 0.9230 0.3847 0.0125 +vn 1.0000 -0.0044 -0.0062 +vn 0.9903 -0.1384 0.0084 +vn 0.8169 -0.5767 0.0067 +vn 0.6757 -0.7116 -0.1926 +vn 0.8572 -0.5149 -0.0022 +vn 0.6951 -0.6852 0.2176 +vn 0.8931 -0.3884 -0.2270 +vn 0.9986 -0.0440 -0.0289 +vn 0.9290 -0.1254 -0.3482 +vn 0.9610 0.1814 -0.2087 +vn 0.8972 0.4415 0.0117 +vn 0.8424 0.4785 -0.2478 +vn 0.6412 0.7671 -0.0214 +vn 0.7001 0.6591 -0.2748 +vn 0.4179 0.8821 -0.2174 +vn 0.2043 0.9769 -0.0632 +vn 0.0677 0.9567 -0.2832 +vn -0.1906 0.9570 -0.2187 +vn -0.3331 0.9425 -0.0264 +vn -0.5424 0.7994 -0.2583 +vn -0.6734 0.7391 -0.0162 +vn -0.8146 0.5320 -0.2311 +vn -0.9008 0.4341 -0.0129 +vn -0.9649 0.1885 -0.1828 +vn -0.9494 0.2183 0.2257 +vn -0.9450 -0.2429 -0.2189 +vn -0.9853 -0.1034 -0.1359 +vn -0.8613 -0.5078 -0.0174 +vn -0.7860 -0.5189 -0.3360 +vn -0.6909 -0.6888 -0.2198 +vn -0.5777 -0.8162 -0.0022 +vn -0.4246 -0.8815 -0.2067 +vn -0.1112 -0.9938 0.0033 +vn -0.1096 -0.9594 -0.2600 +vn 0.2784 -0.9448 -0.1726 +vn 0.1794 -0.9590 0.2192 +vn 0.4942 -0.8358 -0.2391 +vn -0.6550 0.4939 -0.5718 +vn -0.4559 0.6284 -0.6304 +vn -0.5160 0.3773 -0.7690 +vn -0.6131 0.1105 -0.7822 +vn -0.3540 0.4701 -0.8085 +vn -0.7418 0.2688 -0.6144 +vn -0.7784 0.0195 -0.6275 +vn -0.7317 -0.2255 -0.6433 +vn -0.6142 -0.2150 -0.7593 +vn -0.5954 -0.3702 -0.7130 +vn -0.4352 -0.4476 -0.7812 +vn -0.4584 -0.7058 -0.5401 +vn -0.4571 -0.5565 -0.6939 +vn -0.2585 -0.7131 -0.6517 +vn -0.1164 -0.6013 -0.7905 +vn -0.0986 -0.8139 -0.5726 +vn 0.0337 -0.6676 -0.7438 +vn 0.1539 -0.8288 -0.5380 +vn 0.2488 -0.6361 -0.7304 +vn 0.2893 -0.5110 -0.8094 +vn 0.4284 -0.7178 -0.5489 +vn 0.4975 -0.5036 -0.7063 +vn 0.5496 -0.2875 -0.7844 +vn 0.6727 -0.5018 -0.5437 +vn 0.7038 -0.2989 -0.6444 +vn 0.7085 -0.0682 -0.7024 +vn 0.6244 0.0850 -0.7764 +vn 0.7816 0.1669 -0.6011 +vn 0.6828 0.3485 -0.6421 +vn 0.5194 0.3618 -0.7742 +vn 0.4892 0.5451 -0.6809 +vn 0.4405 0.7063 -0.5541 +vn 0.2826 0.5509 -0.7853 +vn 0.1901 0.7088 -0.6793 +vn -0.0338 0.6072 -0.7938 +vn -0.0406 0.7826 -0.6211 +vn -0.2486 0.6852 -0.6847 +vn -0.6539 0.7566 0.0000 +vn -0.9822 -0.1879 0.0000 +vn -0.3283 -0.9446 0.0000 +vn 0.6537 -0.7567 0.0000 +vn 0.9822 0.1879 0.0000 +vn 0.3282 0.9446 0.0000 +vn 0.1144 -0.1366 0.9840 +vn -0.1263 -0.1294 0.9835 +vn -0.2710 -0.2905 0.9177 +vn 0.3055 -0.3181 0.8975 +vn -0.0044 -0.5995 0.8004 +vn -0.0120 -0.7580 0.6521 +vn 0.0012 -0.6444 0.7647 +vn -0.0001 -0.7778 0.6286 +vn -0.0070 -0.8049 0.5934 +vn 0.0070 -0.7748 0.6322 +vn 0.0013 -0.8276 0.5612 +vn -0.0002 -0.8280 0.5607 +vn -0.0013 -0.8276 0.5613 +vn 0.0011 -0.8275 0.5614 +vn -0.0018 -0.8272 0.5619 +vn 0.0024 -0.8271 0.5621 +vn -0.0049 -0.8258 0.5639 +vn -0.0035 -0.8269 0.5624 +vn 0.0048 -0.8268 0.5625 +vn 0.0042 -0.8268 0.5625 +vn -0.0022 -0.8266 0.5628 +vn -0.0012 -0.8280 0.5607 +vn 0.0018 -0.8274 0.5616 +vn 0.0000 -0.9987 0.0501 +vn -0.0001 -0.9987 0.0510 +vn -0.0012 -0.9984 0.0568 +vn -0.0013 -0.9983 0.0577 +vn -1.0000 0.0007 0.0072 +vn -1.0000 -0.0000 0.0000 +vn -1.0000 -0.0014 0.0070 +vn -0.9777 -0.0074 0.2099 +vn -0.9734 0.0055 0.2292 +vn 0.1571 0.0132 -0.9875 +vn 0.6804 0.0181 -0.7326 +vn 0.4982 -0.0143 -0.8670 +vn 0.0841 -0.0094 -0.9964 +vn -0.3942 -0.0145 -0.9189 +vn -0.7499 -0.0112 -0.6615 +vn -0.7670 0.0095 -0.6416 +vn 0.9492 0.0127 -0.3143 +vn 0.8348 -0.0210 -0.5501 +vn -0.9641 -0.0049 -0.2656 +vn -0.9532 -0.0138 0.3019 +vn -0.9590 0.0086 0.2832 +vn -0.3233 0.0142 -0.9462 +vn -0.1511 -0.0125 0.9884 +vn 0.2862 -0.0007 0.9582 +vn 0.0986 0.0095 0.9951 +vn -0.3906 0.0128 0.9205 +vn -0.7394 0.0107 0.6731 +vn -0.6230 -0.0140 0.7821 +vn 0.6287 0.0046 0.7776 +vn 0.8202 0.0111 0.5720 +vn 0.9823 -0.0044 0.1872 +vn 0.9851 0.0025 0.1722 +vn 0.7784 -0.0075 0.6277 +vn 0.4243 0.0139 0.9054 +vn -0.0773 0.0111 0.9969 +vn -0.4719 0.0050 0.8816 +vn -0.7527 -0.0079 0.6583 +vn -0.7773 0.0081 0.6291 +vn 0.1588 0.1955 0.9678 +vn -0.0113 0.7253 0.6884 +vn -0.1411 0.1609 0.9768 +vn 0.0060 0.6503 0.7596 +vn 0.0027 0.7974 0.6034 +vn -0.0013 0.8279 0.5609 +vn 0.0004 0.8278 0.5611 +vn 0.0008 0.8277 0.5611 +vn -0.0039 0.8033 0.5955 +vn -0.0035 0.8224 0.5689 +vn -0.0019 0.8275 0.5615 +vn 0.0001 0.8263 0.5633 +vn -0.0002 0.8265 0.5630 +vn 0.0015 0.8269 0.5623 +vn -0.0018 0.8270 0.5621 +vn 0.0003 0.8263 0.5633 +vn 0.0005 0.8267 0.5627 +vn -0.9628 -0.0013 0.2703 +vn -0.9797 0.0027 0.2006 +vn -0.9999 -0.0005 0.0132 +vn -1.0000 -0.0006 0.0063 +vn 0.0000 0.9988 0.0486 +vn 0.0001 0.9988 0.0495 +vn 0.0011 0.9985 0.0553 +vn 0.0013 0.9984 0.0561 +vn -0.7434 -0.0059 0.6688 +vn -0.7164 0.0124 0.6976 +vn -0.4264 -0.0099 0.9045 +vn -0.0536 0.0008 0.9986 +vn 0.3670 -0.0021 0.9302 +vn 0.5996 0.0018 0.8003 +vn 0.7864 -0.0112 0.6176 +vn 0.8056 0.0064 0.5925 +vn 0.9844 0.0024 0.1758 +vn 0.9795 -0.0028 0.2013 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn -0.8722 0.0232 -0.4885 +vn -0.6270 -0.0304 -0.7784 +vn -0.9497 0.0490 -0.3094 +vn -0.0183 0.9995 0.0243 +vn -0.0074 0.9999 0.0156 +vn -0.3697 0.9135 -0.1696 +vn -0.0099 -0.9997 -0.0236 +vn 0.0210 -0.9991 0.0357 +vn -0.0051 -1.0000 -0.0010 +vn -0.0009 -0.9999 0.0168 +vn 0.0676 -0.9973 0.0276 +vn 0.0978 -0.9940 0.0487 +vn 0.0088 -0.9989 0.0456 +vn 0.0016 -0.9979 -0.0649 +vn 0.0098 -0.9994 0.0335 +vn -0.0069 -0.9997 0.0214 +vn -0.1936 -0.9804 -0.0359 +vn -0.0985 -0.9822 -0.1597 +vn 0.0116 -0.9999 0.0070 +vn 0.0006 -1.0000 0.0071 +vn 0.0249 -0.9997 -0.0022 +vn -0.0788 -0.9967 0.0177 +vn -0.2396 0.0217 -0.9706 +vn -0.2128 -0.0254 -0.9768 +vn -0.4011 -0.0507 -0.9146 +vn -0.5497 0.0248 -0.8350 +vn -0.8082 -0.0426 -0.5873 +vn -0.9216 0.0276 -0.3873 +vn -0.9722 -0.0681 -0.2240 +vn -0.9836 0.0148 0.1795 +vn -0.9567 -0.0325 0.2894 +vn -0.8809 -0.0442 0.4713 +vn -0.8866 0.0071 0.4625 +vn -0.4771 0.0009 0.8789 +vn -0.4916 -0.0069 0.8708 +vn -0.3242 -0.0273 0.9456 +vn -0.1844 0.0105 0.9828 +vn 0.2180 -0.0585 0.9742 +vn 0.4152 0.0245 0.9094 +vn 0.7349 -0.0612 0.6754 +vn 0.8143 0.0103 0.5804 +vn 0.9858 -0.0362 0.1637 +vn 0.9839 0.0042 0.1786 +vn 0.9583 -0.0046 -0.2857 +vn 0.9543 -0.0434 -0.2956 +vn 0.8830 -0.0544 -0.4662 +vn 0.8687 -0.0043 -0.4952 +vn 0.4536 0.0166 -0.8910 +vn 0.4243 -0.0275 -0.9051 +vn 0.4359 0.0029 -0.9000 +vn 0.4081 -0.0393 -0.9121 +vn -0.1786 0.0071 -0.9839 +vn -0.3574 -0.0027 -0.9340 +vn -0.6865 0.0273 -0.7267 +vn -0.8316 -0.0062 -0.5554 +vn -0.8834 0.0835 -0.4612 +vn -0.9577 -0.0067 -0.2877 +vn -0.9468 -0.0036 0.3217 +vn -0.9247 0.0042 0.3806 +vn -0.9265 0.0036 0.3763 +vn -0.9483 -0.0042 0.3172 +vn -0.5591 0.1926 0.8065 +vn -0.4267 -0.0062 0.9044 +vn -0.2711 0.4136 0.8691 +vn -0.0991 -0.0075 0.9951 +vn 0.2824 0.0564 0.9576 +vn 0.6158 -0.0083 0.7879 +vn 0.7826 0.0050 0.6225 +vn 0.8911 -0.0074 0.4537 +vn 0.9297 0.0015 0.3683 +vn 0.9324 0.0199 -0.3610 +vn 0.9418 -0.0015 -0.3360 +vn 0.9412 -0.0013 -0.3379 +vn 0.9317 0.0244 -0.3625 +vn 0.4380 0.0065 -0.8989 +vn 0.5171 -0.0012 -0.8560 +vn 0.2438 0.0000 -0.9698 +vn 0.2326 0.0069 -0.9726 +vn -0.0833 0.9826 -0.1662 +vn -0.0438 0.9910 -0.1266 +vn 0.0588 0.9871 -0.1487 +vn 0.0426 0.9944 -0.0970 +vn 0.1667 0.9827 -0.0802 +vn 0.0476 0.9988 -0.0082 +vn -0.2142 0.9767 -0.0119 +vn -0.0849 0.9901 -0.1116 +vn 0.4277 0.8443 0.3228 +vn 0.0387 0.9991 0.0200 +vn 0.0238 0.9981 0.0574 +vn -0.0009 0.9761 0.2172 +vn -0.0119 0.9984 0.0556 +vn -0.3728 0.8527 0.3660 +vn -0.0401 0.9991 0.0157 +vn -0.0431 0.9991 0.0048 +vn -0.1125 -0.0340 -0.9931 +vn -0.4174 0.0316 -0.9082 +vn -0.5126 -0.1870 -0.8380 +vn -0.8426 0.0929 -0.5304 +vn -0.5765 -0.1589 0.8015 +vn -0.1407 0.0719 0.9874 +vn -0.3144 0.0063 0.9493 +vn 0.1307 0.0312 0.9909 +vn 0.3507 0.0654 0.9342 +vn 0.5398 0.0389 0.8409 +vn 0.6699 0.2435 0.7014 +vn 0.8921 0.0851 0.4438 +vn 0.9681 -0.0639 0.2424 +vn 0.9562 -0.2114 0.2027 +vn 0.7885 -0.0974 -0.6073 +vn 0.6659 -0.2059 -0.7171 +vn 0.7163 0.0154 -0.6976 +vn 0.0601 0.0243 -0.9979 +vn 0.0674 -0.0876 -0.9939 +vn -0.8704 -0.0203 -0.4920 +vn -0.9840 0.1749 0.0332 +vn -0.9958 -0.0397 0.0828 +vn -0.9795 -0.1273 0.1563 +vn 0.9377 0.1133 -0.3285 +vn 0.8817 0.3732 -0.2886 +vn -0.7159 0.5009 0.4865 +vn 0.9110 -0.3863 0.1444 +vn 0.7226 0.0721 -0.6875 +vn 0.0160 0.0993 -0.9949 +vn -0.4575 -0.3479 0.8184 +vn 0.7185 0.0270 -0.6950 +vn 0.7462 0.0241 -0.6653 +vn 0.7928 0.0214 0.6090 +vn 0.9786 0.0215 0.2047 +vn 0.1056 0.0159 0.9943 +vn -0.5147 0.0162 0.8572 +vn -0.9964 0.0229 -0.0813 +vn -0.7574 0.0177 0.6527 +vn -0.8501 -0.0041 0.5266 +vn -0.2826 0.0066 -0.9592 +vn -0.0026 0.9997 0.0225 +vn 0.0601 -0.0068 -0.9982 +vn -0.6588 0.7187 0.2223 +vn -0.5237 0.8406 0.1381 +vn -0.8331 0.3289 -0.4447 +vn -0.2978 0.8979 -0.3243 +vn 0.3288 0.8553 -0.4003 +vn 0.9228 0.1396 -0.3592 +vn 0.4270 0.9023 0.0587 +vn 0.7870 0.5317 0.3128 +vn 0.6273 0.5767 0.5233 +vn 0.2338 0.8354 0.4974 +vn 0.0262 0.4760 0.8790 +vn -0.2029 -0.3051 -0.9304 +vn -0.4239 -0.7540 -0.5018 +vn -0.3384 -0.8796 -0.3344 +vn -0.8500 -0.3649 -0.3799 +vn -0.6554 -0.7550 0.0190 +vn -0.5010 -0.8640 0.0508 +vn -0.8260 -0.3433 0.4470 +vn -0.3255 -0.8551 0.4036 +vn 0.0010 -0.7954 0.6061 +vn 0.4623 -0.2399 0.8537 +vn 0.3232 -0.8789 0.3509 +vn 0.8436 -0.3616 0.3970 +vn 0.4790 -0.8750 0.0703 +vn 0.8114 -0.3765 -0.4471 +vn 0.3440 -0.8631 -0.3699 +vn 0.4001 -0.2012 -0.8941 +vn 0.0259 -0.8919 -0.4514 +vn 0.5375 -0.0465 0.8420 +vn 0.5132 -0.0566 0.8564 +vn 0.4972 -0.0141 0.8675 +vn -0.4614 -0.0456 0.8860 +vn -0.4856 -0.0553 0.8724 +vn -0.5027 -0.0133 0.8643 +vn 0.9995 -0.0204 0.0224 +vn 0.9995 -0.0259 0.0152 +vn 0.9996 -0.0242 0.0174 +vn 0.9995 -0.0298 0.0100 +vn 0.4845 0.0015 0.8748 +vn 0.4964 -0.0077 0.8680 +vn -0.5158 0.0018 0.8567 +vn -0.5041 -0.0075 0.8636 +vn -1.0000 -0.0049 -0.0019 +vn -0.9987 -0.0202 -0.0465 +vn -0.9997 -0.0260 0.0008 +vn -0.9949 0.0071 -0.1002 +vn -0.9959 0.0005 0.0901 +vn -0.4808 -0.0260 -0.8765 +vn -0.4588 -0.0070 -0.8885 +vn -0.4646 -0.0120 -0.8854 +vn -0.4425 0.0069 -0.8968 +vn 0.5191 -0.0235 -0.8544 +vn 0.5415 -0.0036 -0.8407 +vn 0.5357 -0.0088 -0.8444 +vn 0.5576 0.0111 -0.8300 +vn 1.0000 -0.0037 0.0085 +vn 1.0000 0.0007 0.0064 +vn 1.0000 0.0000 0.0000 +vn 1.0000 0.0023 0.0086 +vn 1.0000 -0.0006 0.0056 +vn -0.5646 -0.8203 -0.0910 +vn -0.2343 -0.9712 -0.0438 +vn -0.3716 -0.9280 0.0274 +vn 0.9921 -0.1238 0.0214 +vn 0.7088 -0.7051 0.0232 +vn 0.9663 -0.2563 -0.0237 +vn 0.5842 -0.8112 -0.0277 +vn 0.1569 -0.9867 0.0430 +vn 0.5076 0.8614 -0.0146 +vn 0.3714 0.9283 -0.0172 +vn 0.5425 0.8400 0.0106 +vn 0.9932 0.0030 0.1163 +vn 0.8693 0.0011 0.4943 +vn 0.9029 -0.0049 0.4297 +vn 0.9983 -0.0131 -0.0567 +vn 0.5747 0.0028 0.8184 +vn -0.9821 0.0031 -0.1883 +vn 0.8174 0.5758 0.0181 +vn 0.9018 0.4320 -0.0139 +vn -0.9169 -0.3950 0.0574 +vn -0.9995 0.0054 0.0308 +vn -0.9997 -0.0018 -0.0241 +vn -0.9236 0.3828 0.0184 +vn -0.9827 0.1843 -0.0193 +vn -0.4396 0.8981 -0.0092 +vn -0.4793 0.8775 -0.0177 +vn -0.3296 0.9440 0.0136 +vn -0.3028 0.9529 0.0190 +vn -0.0007 -1.0000 -0.0017 +vn -0.0001 -1.0000 0.0001 +vn 0.0002 -1.0000 0.0005 +vn -0.0001 -1.0000 -0.0001 +vn -0.0002 -1.0000 -0.0001 +vn -0.3201 0.7918 0.5202 +vn -0.5807 0.7919 0.1891 +vn -0.5795 0.7927 0.1895 +vn 0.0609 0.7952 0.6033 +vn -0.3141 0.7961 0.5172 +vn -0.1689 0.8258 -0.5381 +vn -0.5726 0.7728 -0.2737 +vn 0.0654 0.7919 0.6072 +vn 0.2876 0.7667 0.5740 +vn 0.4932 0.7709 -0.4030 +vn 0.4968 0.7681 -0.4041 +vn 0.4984 0.7667 -0.4046 +vn -0.1157 0.9222 -0.3690 +vn 0.0312 0.7828 -0.6215 +vn 0.6304 0.7630 0.1426 +vn 0.6284 0.7650 0.1408 +vn 0.6274 0.7660 0.1399 +vn -0.0086 0.9999 0.0069 +vn 0.0015 0.9999 0.0149 +vn -0.0136 0.9998 0.0168 +vn 0.2905 0.7642 0.5759 +vn 0.4921 0.7718 -0.4027 +vn 0.0069 0.7572 -0.6531 +vn 0.6320 0.7615 0.1439 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 5/5/5 6/6/6 4/4/7 +f 4/4/7 6/6/6 3/3/8 +f 6/6/9 5/5/10 7/7/11 +f 7/7/11 5/5/10 8/8/12 +f 1/1/13 7/7/14 8/8/15 +f 2/2/16 1/1/13 8/8/15 +f 5/5/17 2/2/17 8/8/17 +f 5/5/17 4/4/17 2/2/17 +f 6/6/18 7/7/18 1/1/18 +f 3/3/18 6/6/18 1/1/18 +f 9/9/19 10/10/20 11/11/21 +f 12/12/22 13/13/23 14/14/24 +f 14/14/24 10/10/20 9/9/19 +f 15/15/25 16/16/26 17/17/27 +f 18/18/28 19/19/29 15/15/25 +f 15/15/25 19/19/29 16/16/26 +f 9/9/19 11/11/21 18/18/28 +f 18/18/28 11/11/21 19/19/29 +f 20/20/30 13/13/23 12/12/22 +f 21/21/31 22/22/32 23/23/33 +f 24/24/34 25/25/35 17/17/27 +f 12/12/22 14/14/24 9/9/19 +f 23/23/33 22/22/32 20/20/30 +f 23/23/33 20/20/30 12/12/22 +f 24/24/34 21/21/31 25/25/35 +f 25/25/35 21/21/31 23/23/33 +f 15/15/25 17/17/27 25/25/35 +f 26/26/36 27/27/37 28/28/38 +f 28/28/38 29/29/39 26/26/36 +f 28/28/38 30/30/40 29/29/39 +f 31/31/41 30/30/40 28/28/38 +f 28/28/38 32/32/42 31/31/41 +f 28/28/38 33/33/43 32/32/42 +f 28/28/38 34/34/44 33/33/43 +f 35/35/45 34/34/44 28/28/38 +f 36/36/46 35/35/45 28/28/38 +f 37/37/47 28/28/48 38/38/49 +f 38/38/49 28/28/48 27/27/50 +f 38/38/49 27/27/50 39/39/51 +f 39/39/51 27/27/50 26/26/52 +f 39/39/53 26/26/54 29/29/55 +f 39/39/53 29/29/55 40/40/56 +f 40/40/56 29/29/55 30/30/57 +f 40/40/56 30/30/57 41/41/58 +f 41/41/59 30/30/60 31/31/61 +f 41/41/59 31/31/61 42/42/62 +f 42/42/62 31/31/61 32/32/63 +f 42/42/62 32/32/63 43/43/64 +f 43/43/64 32/32/63 33/33/65 +f 43/43/64 33/33/65 44/44/66 +f 44/44/66 33/33/65 34/34/67 +f 44/44/68 34/34/69 35/35/70 +f 44/44/68 35/35/70 37/37/47 +f 37/37/47 35/35/70 36/36/71 +f 37/37/47 36/36/71 28/28/48 +f 42/42/17 45/45/17 46/46/17 +f 42/42/17 46/46/17 41/41/17 +f 43/43/17 47/47/17 45/45/17 +f 43/43/17 45/45/17 42/42/17 +f 40/40/17 48/48/17 39/39/17 +f 37/37/17 49/49/17 50/50/17 +f 37/37/17 50/50/17 44/44/17 +f 38/38/17 51/51/17 37/37/17 +f 37/37/17 51/51/17 49/49/17 +f 43/43/17 52/52/17 47/47/17 +f 44/44/17 52/52/17 43/43/17 +f 38/38/17 53/53/17 51/51/17 +f 40/40/17 54/54/17 48/48/17 +f 50/50/17 55/55/17 44/44/17 +f 44/44/17 55/55/17 52/52/17 +f 39/39/17 56/56/17 38/38/17 +f 38/38/17 56/56/17 53/53/17 +f 39/39/17 48/48/17 56/56/17 +f 41/41/17 57/57/17 40/40/17 +f 40/40/17 57/57/17 54/54/17 +f 41/41/17 46/46/17 57/57/17 +f 58/58/72 59/59/73 49/49/74 +f 59/59/73 60/60/75 49/49/74 +f 60/60/75 50/50/76 49/49/74 +f 60/60/75 61/61/77 50/50/76 +f 61/61/77 55/55/78 50/50/76 +f 61/61/77 62/62/79 55/55/78 +f 55/55/78 62/62/79 52/52/80 +f 63/63/81 52/52/80 62/62/79 +f 63/63/81 47/47/82 52/52/80 +f 63/63/81 64/64/83 47/47/82 +f 64/64/83 65/65/84 47/47/82 +f 65/65/84 45/45/85 47/47/82 +f 65/65/84 66/66/86 45/45/85 +f 67/67/87 46/46/88 45/45/85 +f 67/67/87 45/45/85 66/66/86 +f 67/67/87 68/68/89 46/46/88 +f 46/46/88 68/68/89 57/57/90 +f 68/68/89 69/69/91 57/57/90 +f 57/57/90 69/69/91 54/54/92 +f 70/70/93 54/54/92 69/69/91 +f 54/54/92 70/70/93 48/48/94 +f 70/70/93 71/71/95 48/48/94 +f 71/71/95 72/72/96 48/48/94 +f 72/72/96 56/56/97 48/48/94 +f 72/72/96 73/73/98 56/56/97 +f 73/73/98 53/53/99 56/56/97 +f 74/74/100 53/53/99 73/73/98 +f 53/53/99 74/74/100 51/51/101 +f 74/74/100 75/75/102 51/51/101 +f 51/51/101 75/75/102 49/49/74 +f 49/49/74 75/75/102 58/58/72 +f 65/65/84 64/64/83 76/76/103 +f 21/21/104 24/24/105 77/77/106 +f 67/67/87 78/78/107 68/68/89 +f 79/79/108 78/78/107 77/77/106 +f 79/79/108 77/77/106 24/24/105 +f 78/78/107 79/79/108 80/80/109 +f 78/78/107 80/80/109 68/68/89 +f 68/68/89 80/80/109 69/69/91 +f 81/81/110 80/80/109 79/79/108 +f 81/81/110 79/79/108 24/24/105 +f 70/70/93 69/69/91 80/80/109 +f 24/24/105 17/17/111 81/81/110 +f 81/81/110 82/82/112 80/80/109 +f 80/80/109 82/82/112 70/70/93 +f 83/83/113 82/82/112 81/81/110 +f 83/83/113 81/81/110 17/17/111 +f 71/71/95 70/70/93 82/82/112 +f 82/82/112 83/83/113 71/71/95 +f 16/16/114 83/83/113 17/17/111 +f 84/84/115 83/83/113 16/16/114 +f 85/85/116 72/72/96 71/71/95 +f 85/85/116 71/71/95 83/83/113 +f 85/85/116 83/83/113 84/84/115 +f 73/73/98 72/72/96 85/85/116 +f 84/84/115 86/86/117 85/85/116 +f 86/86/117 84/84/115 16/16/114 +f 86/86/117 73/73/98 85/85/116 +f 86/86/117 16/16/114 19/19/118 +f 74/74/100 73/73/98 86/86/117 +f 87/87/119 86/86/117 19/19/118 +f 86/86/117 87/87/119 74/74/100 +f 87/87/119 19/19/118 88/88/120 +f 74/74/100 87/87/119 75/75/102 +f 88/88/120 19/19/118 11/11/121 +f 58/58/72 75/75/102 87/87/119 +f 58/58/72 87/87/119 88/88/120 +f 89/89/122 88/88/120 11/11/121 +f 89/89/122 58/58/72 88/88/120 +f 90/90/123 89/89/122 11/11/121 +f 10/10/124 90/90/123 11/11/121 +f 89/89/122 90/90/123 58/58/72 +f 58/58/72 90/90/123 59/59/73 +f 60/60/75 59/59/73 90/90/123 +f 91/91/125 60/60/75 90/90/123 +f 91/91/125 90/90/123 10/10/124 +f 61/61/77 60/60/75 92/92/126 +f 92/92/126 60/60/75 91/91/125 +f 14/14/127 91/91/125 10/10/124 +f 14/14/127 92/92/126 91/91/125 +f 62/62/79 61/61/77 92/92/126 +f 93/93/128 92/92/126 14/14/127 +f 14/14/127 13/13/129 93/93/128 +f 92/92/126 93/93/128 94/94/130 +f 92/92/126 94/94/130 62/62/79 +f 95/95/131 94/94/130 93/93/128 +f 63/63/81 62/62/79 94/94/130 +f 95/95/131 93/93/128 13/13/129 +f 63/63/81 94/94/130 95/95/131 +f 20/20/132 95/95/131 13/13/129 +f 96/96/133 63/63/81 95/95/131 +f 64/64/83 63/63/81 96/96/133 +f 97/97/134 96/96/133 95/95/131 +f 97/97/134 95/95/131 20/20/132 +f 76/76/103 64/64/83 96/96/133 +f 76/76/103 96/96/133 97/97/134 +f 20/20/132 22/22/135 97/97/134 +f 98/98/136 97/97/134 22/22/135 +f 98/98/136 76/76/103 97/97/134 +f 98/98/136 65/65/84 76/76/103 +f 66/66/86 65/65/84 98/98/136 +f 98/98/136 99/99/137 66/66/86 +f 21/21/104 98/98/136 22/22/135 +f 77/77/106 99/99/137 98/98/136 +f 77/77/106 98/98/136 21/21/104 +f 67/67/87 66/66/86 99/99/137 +f 99/99/137 77/77/106 78/78/107 +f 99/99/137 78/78/107 67/67/87 +f 9/9/138 18/18/138 100/100/138 +f 100/100/138 18/18/138 101/101/138 +f 12/12/139 9/9/139 102/102/139 +f 102/102/139 9/9/139 100/100/139 +f 23/23/140 12/12/140 103/103/140 +f 103/103/140 12/12/140 102/102/140 +f 25/25/141 23/23/141 104/104/141 +f 104/104/141 23/23/141 103/103/141 +f 15/15/142 25/25/142 105/105/142 +f 105/105/142 25/25/142 104/104/142 +f 18/18/143 15/15/143 101/101/143 +f 101/101/143 15/15/143 105/105/143 +f 105/105/18 104/104/18 101/101/18 +f 101/101/18 104/104/18 103/103/18 +f 101/101/18 103/103/18 100/100/18 +f 100/100/18 103/103/18 102/102/18 +f 106/106/144 107/107/145 108/108/146 +f 109/109/147 110/110/148 111/111/149 +f 112/112/150 113/113/151 114/114/152 +f 114/114/152 113/113/151 115/115/153 +f 116/116/154 112/112/150 117/117/155 +f 117/117/155 112/112/150 114/114/152 +f 117/117/155 111/111/149 116/116/154 +f 109/109/147 108/108/146 110/110/148 +f 118/118/156 119/119/157 120/120/158 +f 119/119/157 118/118/156 121/121/159 +f 115/115/153 113/113/151 122/122/160 +f 109/109/147 111/111/149 117/117/155 +f 106/106/144 108/108/146 109/109/147 +f 119/119/157 121/121/159 106/106/144 +f 106/106/144 121/121/159 107/107/145 +f 122/122/160 120/120/158 115/115/153 +f 115/115/153 120/120/158 119/119/157 +f 123/123/161 124/124/162 125/125/163 +f 125/125/163 126/126/164 123/123/161 +f 127/127/165 126/126/164 125/125/163 +f 128/128/166 127/127/165 125/125/163 +f 125/125/163 129/129/167 128/128/166 +f 130/130/168 131/131/169 125/125/163 +f 132/132/170 130/130/168 125/125/163 +f 125/125/163 133/133/171 132/132/170 +f 134/134/172 133/133/171 125/125/163 +f 124/124/162 134/134/172 125/125/163 +f 135/135/173 124/124/174 123/123/175 +f 135/135/173 123/123/175 136/136/176 +f 136/136/176 123/123/175 126/126/177 +f 136/136/176 126/126/177 137/137/178 +f 137/137/178 126/126/177 127/127/179 +f 137/137/180 127/127/181 128/128/182 +f 137/137/180 128/128/182 138/138/183 +f 138/138/184 128/128/185 139/139/186 +f 139/139/186 128/128/185 129/129/187 +f 139/139/188 129/129/189 125/125/190 +f 139/139/188 125/125/190 140/140/191 +f 140/140/191 125/125/190 131/131/192 +f 140/140/191 131/131/192 141/141/193 +f 141/141/193 131/131/192 130/130/194 +f 141/141/193 130/130/194 132/132/195 +f 141/141/193 132/132/195 142/142/196 +f 142/142/196 132/132/195 133/133/197 +f 142/142/196 133/133/197 143/143/198 +f 143/143/198 133/133/197 134/134/199 +f 143/143/198 134/134/199 144/144/200 +f 144/144/200 134/134/199 124/124/174 +f 144/144/200 124/124/174 135/135/173 +f 135/135/17 145/145/17 144/144/17 +f 140/140/17 146/146/17 147/147/17 +f 140/140/17 147/147/17 139/139/17 +f 141/141/17 148/148/17 146/146/17 +f 141/141/17 146/146/17 140/140/17 +f 138/138/17 149/149/17 150/150/17 +f 138/138/17 150/150/17 137/137/17 +f 143/143/17 151/151/17 152/152/17 +f 144/144/17 145/145/17 151/151/17 +f 144/144/17 151/151/17 143/143/17 +f 135/135/17 153/153/17 145/145/17 +f 142/142/17 148/148/17 141/141/17 +f 142/142/17 154/154/17 148/148/17 +f 136/136/17 155/155/17 135/135/17 +f 135/135/17 155/155/17 153/153/17 +f 139/139/17 149/149/17 138/138/17 +f 143/143/17 152/152/17 154/154/17 +f 143/143/17 154/154/17 142/142/17 +f 137/137/17 156/156/17 136/136/17 +f 136/136/17 156/156/17 155/155/17 +f 137/137/17 150/150/17 156/156/17 +f 139/139/17 157/157/17 149/149/17 +f 139/139/17 147/147/17 157/157/17 +f 158/158/201 159/159/202 145/145/203 +f 145/145/203 159/159/202 151/151/204 +f 159/159/202 160/160/205 151/151/204 +f 151/151/204 160/160/205 152/152/206 +f 161/161/207 152/152/206 160/160/205 +f 161/161/207 154/154/208 152/152/206 +f 161/161/207 162/162/209 154/154/208 +f 162/162/209 163/163/210 154/154/208 +f 154/154/208 163/163/210 148/148/211 +f 163/163/210 164/164/212 148/148/213 +f 164/164/212 146/146/214 148/148/213 +f 164/164/212 165/165/215 146/146/214 +f 165/165/215 147/147/216 146/146/214 +f 165/165/215 166/166/217 147/147/216 +f 147/147/216 166/166/217 157/157/218 +f 167/167/219 157/157/218 166/166/217 +f 167/167/219 168/168/220 157/157/218 +f 168/168/220 149/149/221 157/157/218 +f 169/169/222 149/149/223 168/168/220 +f 169/169/222 150/150/224 149/149/225 +f 170/170/226 150/150/224 169/169/222 +f 171/171/227 150/150/224 170/170/226 +f 171/171/227 156/156/228 150/150/224 +f 172/172/229 156/156/228 171/171/227 +f 156/156/228 172/172/229 155/155/230 +f 155/155/230 172/172/229 173/173/231 +f 155/155/230 173/173/231 153/153/232 +f 173/173/231 174/174/233 153/153/232 +f 153/153/232 174/174/233 145/145/203 +f 145/145/203 174/174/233 158/158/201 +f 169/169/222 168/168/220 175/175/234 +f 176/176/235 177/177/236 178/178/237 +f 177/177/236 176/176/235 121/121/238 +f 167/167/219 166/166/217 178/178/237 +f 179/179/239 167/167/219 178/178/237 +f 179/179/239 178/178/237 177/177/236 +f 177/177/236 121/121/238 118/118/240 +f 167/167/219 179/179/239 168/168/220 +f 175/175/234 179/179/239 177/177/236 +f 175/175/234 177/177/236 118/118/240 +f 179/179/239 175/175/234 168/168/220 +f 118/118/240 120/120/241 175/175/234 +f 180/180/242 175/175/234 120/120/241 +f 181/181/243 169/169/222 175/175/234 +f 181/181/243 175/175/234 180/180/242 +f 120/120/241 122/122/244 180/180/242 +f 170/170/226 169/169/222 181/181/243 +f 182/182/245 181/181/243 180/180/242 +f 180/180/242 122/122/244 182/182/245 +f 171/171/227 170/170/226 183/183/246 +f 183/183/246 170/170/226 181/181/243 +f 183/183/246 181/181/243 182/182/245 +f 184/184/247 183/183/246 182/182/245 +f 113/113/248 182/182/245 122/122/244 +f 183/183/246 184/184/247 171/171/227 +f 172/172/229 171/171/227 184/184/247 +f 184/184/247 182/182/245 113/113/248 +f 113/113/248 185/185/249 184/184/247 +f 173/173/231 172/172/229 184/184/247 +f 184/184/247 185/185/249 173/173/231 +f 112/112/250 185/185/249 113/113/248 +f 186/186/251 173/173/231 185/185/249 +f 186/186/251 185/185/249 112/112/250 +f 174/174/233 173/173/231 186/186/251 +f 187/187/252 186/186/251 112/112/250 +f 188/188/253 174/174/233 186/186/251 +f 188/188/253 186/186/251 187/187/252 +f 187/187/252 112/112/250 188/188/253 +f 174/174/233 188/188/253 158/158/201 +f 116/116/254 188/188/253 112/112/250 +f 188/188/253 116/116/254 189/189/255 +f 159/159/202 158/158/201 188/188/253 +f 188/188/253 189/189/255 159/159/202 +f 190/190/256 159/159/202 189/189/255 +f 190/190/256 189/189/255 116/116/254 +f 160/160/205 159/159/202 190/190/256 +f 111/111/257 190/190/256 116/116/254 +f 190/190/256 191/191/258 160/160/205 +f 191/191/258 190/190/256 111/111/257 +f 161/161/207 160/160/205 191/191/258 +f 111/111/257 192/192/259 191/191/258 +f 193/193/260 161/161/207 191/191/258 +f 193/193/260 191/191/258 192/192/259 +f 111/111/257 110/110/261 192/192/259 +f 162/162/209 161/161/207 193/193/260 +f 193/193/260 192/192/259 110/110/261 +f 162/162/209 193/193/260 194/194/262 +f 194/194/262 193/193/260 110/110/261 +f 195/195/263 162/162/209 194/194/262 +f 108/108/264 194/194/262 110/110/261 +f 194/194/262 108/108/264 195/195/263 +f 163/163/210 162/162/209 195/195/263 +f 196/196/265 195/195/263 108/108/264 +f 195/195/263 197/197/266 163/163/210 +f 164/164/212 163/163/210 197/197/266 +f 197/197/266 195/195/263 196/196/265 +f 107/107/267 196/196/265 108/108/264 +f 197/197/266 196/196/265 107/107/267 +f 165/165/215 164/164/212 197/197/266 +f 197/197/266 107/107/267 198/198/268 +f 199/199/269 165/165/215 197/197/266 +f 199/199/269 197/197/266 198/198/268 +f 121/121/238 198/198/268 107/107/267 +f 176/176/235 199/199/269 198/198/268 +f 176/176/235 198/198/268 121/121/238 +f 166/166/217 165/165/215 199/199/269 +f 178/178/237 166/166/217 199/199/269 +f 178/178/237 199/199/269 176/176/235 +f 117/117/270 114/114/270 200/200/270 +f 200/200/270 114/114/270 201/201/270 +f 109/109/271 117/117/271 202/202/271 +f 202/202/271 117/117/271 200/200/271 +f 106/106/272 109/109/272 203/203/272 +f 203/203/272 109/109/272 202/202/272 +f 119/119/273 106/106/273 204/204/273 +f 204/204/273 106/106/273 203/203/273 +f 115/115/274 119/119/274 205/205/274 +f 205/205/274 119/119/274 204/204/274 +f 114/114/275 115/115/275 201/201/275 +f 201/201/275 115/115/275 205/205/275 +f 205/205/18 204/204/18 201/201/18 +f 201/201/18 204/204/18 203/203/18 +f 201/201/18 203/203/18 200/200/18 +f 200/200/18 203/203/18 202/202/18 +f 206/206/276 207/207/277 208/208/278 +f 209/209/279 210/210/280 211/211/281 +f 212/212/282 213/213/283 214/214/284 +f 211/211/281 210/210/280 215/215/285 +f 215/215/285 210/210/280 216/216/286 +f 215/215/285 216/216/286 217/217/287 +f 218/218/288 219/219/289 211/211/281 +f 211/211/281 219/219/289 209/209/279 +f 218/218/288 214/214/284 219/219/289 +f 212/212/282 206/206/276 213/213/283 +f 220/220/290 221/221/291 222/222/292 +f 212/212/282 214/214/284 218/218/288 +f 207/207/277 206/206/276 212/212/282 +f 220/220/290 222/222/292 207/207/277 +f 207/207/277 222/222/292 208/208/278 +f 215/215/285 217/217/287 221/221/291 +f 215/215/285 221/221/291 220/220/290 +f 223/223/293 224/224/294 225/225/295 +f 226/226/296 224/224/294 223/223/293 +f 223/223/293 227/227/297 226/226/296 +f 223/223/293 228/228/298 227/227/297 +f 223/223/293 229/229/299 230/230/300 +f 223/223/293 231/231/301 229/229/299 +f 232/232/302 231/231/301 223/223/293 +f 225/225/295 232/232/302 223/223/293 +f 233/233/303 225/225/304 224/224/305 +f 233/233/303 224/224/305 234/234/306 +f 234/234/306 224/224/305 226/226/307 +f 234/234/306 226/226/307 235/235/308 +f 235/235/308 226/226/307 227/227/309 +f 235/235/310 227/227/311 236/236/312 +f 236/236/312 227/227/311 228/228/313 +f 236/236/314 228/228/315 237/237/316 +f 237/237/316 228/228/315 223/223/317 +f 237/237/316 223/223/317 238/238/318 +f 238/238/318 223/223/317 230/230/319 +f 238/238/318 230/230/319 239/239/320 +f 239/239/320 230/230/319 229/229/321 +f 239/239/320 229/229/321 231/231/322 +f 239/239/320 231/231/322 240/240/323 +f 240/240/323 231/231/322 232/232/324 +f 240/240/323 232/232/324 241/241/325 +f 241/241/325 232/232/324 225/225/304 +f 241/241/325 225/225/304 233/233/303 +f 233/233/17 242/242/17 241/241/17 +f 238/238/17 243/243/17 244/244/17 +f 238/238/17 244/244/17 237/237/17 +f 239/239/17 245/245/17 243/243/17 +f 239/239/17 243/243/17 238/238/17 +f 236/236/17 246/246/17 235/235/17 +f 241/241/17 247/247/17 248/248/17 +f 241/241/17 248/248/17 240/240/17 +f 241/241/17 242/242/17 247/247/17 +f 233/233/17 249/249/17 242/242/17 +f 234/234/17 249/249/17 233/233/17 +f 240/240/17 250/250/17 239/239/17 +f 239/239/17 250/250/17 245/245/17 +f 234/234/17 251/251/17 249/249/17 +f 236/236/17 252/252/17 246/246/17 +f 240/240/17 248/248/17 250/250/17 +f 235/235/17 253/253/17 234/234/17 +f 234/234/17 253/253/17 251/251/17 +f 235/235/17 246/246/17 253/253/17 +f 237/237/17 254/254/17 236/236/17 +f 236/236/17 254/254/17 252/252/17 +f 237/237/17 244/244/17 254/254/17 +f 255/255/326 256/256/327 242/242/328 +f 256/256/327 247/247/329 242/242/328 +f 256/256/327 257/257/330 247/247/329 +f 247/247/329 257/257/330 248/248/331 +f 258/258/332 248/248/331 257/257/330 +f 258/258/332 250/250/333 248/248/331 +f 258/258/332 259/259/334 250/250/333 +f 259/259/334 260/260/335 250/250/333 +f 250/250/333 260/260/335 245/245/336 +f 260/260/335 261/261/337 245/245/336 +f 261/261/337 243/243/338 245/245/339 +f 261/261/337 262/262/340 243/243/338 +f 262/262/340 244/244/341 243/243/338 +f 262/262/340 263/263/342 244/244/341 +f 244/244/341 263/263/342 254/254/343 +f 264/264/344 254/254/343 263/263/342 +f 264/264/344 265/265/345 254/254/343 +f 265/265/345 252/252/346 254/254/343 +f 266/266/347 252/252/346 265/265/345 +f 252/252/346 266/266/347 246/246/348 +f 266/266/347 267/267/349 246/246/348 +f 246/246/348 267/267/349 253/253/350 +f 253/253/350 267/267/349 268/268/351 +f 268/268/351 269/269/352 253/253/350 +f 253/253/350 269/269/352 251/251/353 +f 269/269/352 270/270/354 251/251/353 +f 251/251/353 270/270/354 249/249/355 +f 270/270/354 271/271/356 249/249/355 +f 249/249/355 271/271/356 242/242/328 +f 242/242/328 271/271/356 255/255/326 +f 262/262/340 261/261/337 272/272/357 +f 273/273/358 222/222/359 274/274/360 +f 264/264/344 263/263/342 274/274/360 +f 222/222/359 275/275/361 274/274/360 +f 265/265/345 264/264/344 276/276/362 +f 276/276/362 264/264/344 274/274/360 +f 276/276/362 274/274/360 275/275/361 +f 222/222/359 221/221/363 275/275/361 +f 277/277/364 276/276/362 275/275/361 +f 275/275/361 221/221/363 277/277/364 +f 266/266/347 265/265/345 276/276/362 +f 277/277/364 278/278/365 276/276/362 +f 276/276/362 278/278/365 266/266/347 +f 221/221/363 217/217/366 277/277/364 +f 277/277/364 217/217/366 278/278/365 +f 279/279/367 266/266/347 278/278/365 +f 279/279/367 278/278/365 217/217/366 +f 266/266/347 279/279/367 267/267/349 +f 280/280/368 267/267/349 279/279/367 +f 216/216/369 279/279/367 217/217/366 +f 280/280/368 279/279/367 216/216/369 +f 280/280/368 268/268/351 267/267/349 +f 280/280/368 281/281/370 268/268/351 +f 281/281/370 280/280/368 216/216/369 +f 269/269/352 268/268/351 281/281/370 +f 210/210/371 281/281/370 216/216/369 +f 282/282/372 281/281/370 210/210/371 +f 281/281/370 282/282/372 270/270/354 +f 281/281/370 270/270/354 269/269/352 +f 210/210/371 283/283/373 282/282/372 +f 284/284/374 270/270/354 282/282/372 +f 209/209/375 283/283/373 210/210/371 +f 271/271/356 270/270/354 284/284/374 +f 282/282/372 283/283/373 284/284/374 +f 283/283/373 209/209/375 285/285/376 +f 283/283/373 285/285/376 284/284/374 +f 284/284/374 285/285/376 286/286/377 +f 286/286/377 271/271/356 284/284/374 +f 209/209/375 219/219/378 285/285/376 +f 271/271/356 286/286/377 255/255/326 +f 285/285/376 287/287/379 286/286/377 +f 287/287/379 255/255/326 286/286/377 +f 285/285/376 219/219/378 287/287/379 +f 288/288/380 255/255/326 287/287/379 +f 287/287/379 219/219/378 289/289/381 +f 287/287/379 289/289/381 288/288/380 +f 256/256/327 255/255/326 288/288/380 +f 288/288/380 290/290/382 256/256/327 +f 290/290/382 288/288/380 289/289/381 +f 257/257/330 256/256/327 290/290/382 +f 214/214/383 289/289/381 219/219/378 +f 291/291/384 290/290/382 289/289/381 +f 214/214/383 291/291/384 289/289/381 +f 291/291/384 257/257/330 290/290/382 +f 291/291/384 214/214/383 292/292/385 +f 257/257/330 291/291/384 258/258/332 +f 214/214/383 213/213/386 292/292/385 +f 291/291/384 292/292/385 258/258/332 +f 258/258/332 292/292/385 259/259/334 +f 259/259/334 292/292/385 293/293/387 +f 293/293/387 292/292/385 213/213/386 +f 294/294/388 259/259/334 293/293/387 +f 206/206/389 293/293/387 213/213/386 +f 260/260/335 259/259/334 294/294/388 +f 294/294/388 293/293/387 206/206/389 +f 295/295/390 260/260/335 294/294/388 +f 261/261/337 260/260/335 295/295/390 +f 295/295/390 294/294/388 206/206/389 +f 272/272/357 261/261/337 295/295/390 +f 296/296/391 295/295/390 206/206/389 +f 272/272/357 295/295/390 296/296/391 +f 206/206/389 208/208/392 296/296/391 +f 297/297/393 272/272/357 296/296/391 +f 297/297/393 262/262/340 272/272/357 +f 273/273/358 297/297/393 296/296/391 +f 296/296/391 208/208/392 273/273/358 +f 222/222/359 273/273/358 208/208/392 +f 263/263/342 262/262/340 297/297/393 +f 297/297/393 273/273/358 274/274/360 +f 297/297/393 274/274/360 263/263/342 +f 218/218/394 211/211/394 298/298/394 +f 298/298/394 211/211/394 299/299/394 +f 212/212/395 218/218/395 300/300/395 +f 300/300/395 218/218/395 298/298/395 +f 207/207/396 212/212/396 301/301/396 +f 301/301/396 212/212/396 300/300/396 +f 220/220/397 207/207/397 302/302/397 +f 302/302/397 207/207/397 301/301/397 +f 215/215/398 220/220/398 303/303/398 +f 303/303/398 220/220/398 302/302/398 +f 211/211/399 215/215/399 299/299/399 +f 299/299/399 215/215/399 303/303/399 +f 303/303/18 302/302/18 299/299/18 +f 299/299/18 302/302/18 301/301/18 +f 299/299/18 301/301/18 298/298/18 +f 298/298/18 301/301/18 300/300/18 +f 304/304/400 305/305/401 306/306/402 +f 307/307/403 308/308/404 309/309/405 +f 309/309/405 310/310/406 311/311/407 +f 312/312/408 313/313/409 314/314/410 +f 315/315/411 316/316/412 312/312/408 +f 306/306/402 305/305/401 317/317/413 +f 306/306/402 317/317/413 315/315/411 +f 315/315/411 317/317/413 316/316/412 +f 318/318/414 319/319/415 320/320/416 +f 312/312/408 316/316/412 313/313/409 +f 319/319/415 304/304/400 320/320/416 +f 320/320/416 304/304/400 306/306/402 +f 311/311/407 310/310/406 320/320/416 +f 320/320/416 310/310/406 318/318/414 +f 307/307/403 309/309/405 311/311/407 +f 312/312/408 314/314/410 307/307/403 +f 307/307/403 314/314/410 308/308/404 +f 321/321/417 322/322/418 323/323/419 +f 324/324/420 322/322/418 321/321/417 +f 321/321/417 325/325/421 324/324/420 +f 321/321/417 326/326/422 325/325/421 +f 321/321/417 327/327/423 326/326/422 +f 321/321/417 328/328/424 327/327/423 +f 329/329/425 328/328/424 321/321/417 +f 321/321/417 330/330/426 329/329/425 +f 321/321/417 331/331/427 330/330/426 +f 332/332/428 323/323/429 333/333/430 +f 333/333/430 323/323/429 322/322/431 +f 333/333/430 322/322/431 334/334/432 +f 334/334/432 322/322/431 324/324/433 +f 334/334/434 324/324/435 325/325/436 +f 334/334/434 325/325/436 335/335/437 +f 335/335/438 325/325/439 326/326/440 +f 335/335/438 326/326/440 336/336/441 +f 336/336/441 326/326/440 327/327/442 +f 336/336/441 327/327/442 337/337/443 +f 337/337/443 327/327/442 328/328/444 +f 337/337/443 328/328/444 338/338/445 +f 338/338/445 328/328/444 329/329/446 +f 338/338/445 329/329/446 339/339/447 +f 339/339/447 329/329/446 330/330/448 +f 339/339/447 330/330/448 340/340/449 +f 340/340/449 330/330/448 331/331/450 +f 340/340/449 331/331/450 321/321/451 +f 340/340/449 321/321/451 332/332/428 +f 332/332/428 321/321/451 323/323/429 +f 332/332/17 341/341/17 340/340/17 +f 337/337/17 342/342/17 343/343/17 +f 337/337/17 343/343/17 336/336/17 +f 338/338/17 344/344/17 337/337/17 +f 337/337/17 344/344/17 342/342/17 +f 335/335/17 345/345/17 346/346/17 +f 335/335/17 346/346/17 334/334/17 +f 340/340/17 341/341/17 347/347/17 +f 332/332/17 348/348/17 341/341/17 +f 333/333/17 348/348/17 332/332/17 +f 339/339/17 344/344/17 338/338/17 +f 339/339/17 349/349/17 344/344/17 +f 333/333/17 350/350/17 348/348/17 +f 347/347/17 351/351/17 340/340/17 +f 340/340/17 351/351/17 339/339/17 +f 339/339/17 351/351/17 349/349/17 +f 334/334/17 352/352/17 350/350/17 +f 334/334/17 350/350/17 333/333/17 +f 334/334/17 346/346/17 352/352/17 +f 336/336/17 353/353/17 345/345/17 +f 336/336/17 345/345/17 335/335/17 +f 336/336/17 343/343/17 353/353/17 +f 354/354/452 341/341/453 348/348/454 +f 355/355/455 341/341/453 354/354/452 +f 355/355/455 347/347/456 341/341/453 +f 355/355/455 356/356/457 347/347/456 +f 356/356/457 357/357/458 347/347/456 +f 357/357/458 351/351/459 347/347/456 +f 357/357/458 358/358/460 351/351/459 +f 351/351/459 358/358/460 349/349/461 +f 359/359/462 349/349/461 358/358/460 +f 360/360/463 349/349/461 359/359/462 +f 349/349/461 360/360/463 344/344/464 +f 360/360/463 361/361/465 344/344/464 +f 362/362/466 344/344/464 361/361/465 +f 362/362/466 342/342/467 344/344/464 +f 363/363/468 342/342/467 362/362/466 +f 363/363/468 343/343/469 342/342/467 +f 363/363/468 364/364/470 343/343/469 +f 343/343/469 364/364/470 353/353/471 +f 364/364/470 365/365/472 353/353/471 +f 365/365/472 345/345/473 353/353/471 +f 366/366/474 345/345/475 365/365/472 +f 366/366/474 346/346/476 345/345/475 +f 366/366/474 367/367/477 346/346/476 +f 367/367/477 368/368/478 346/346/476 +f 346/346/476 368/368/478 352/352/479 +f 369/369/480 352/352/479 368/368/478 +f 369/369/480 350/350/481 352/352/479 +f 369/369/480 370/370/482 350/350/481 +f 370/370/482 371/371/483 350/350/481 +f 350/350/481 371/371/483 348/348/484 +f 371/371/483 354/354/452 348/348/485 +f 372/372/486 373/373/487 374/374/488 +f 363/363/468 373/373/487 372/372/486 +f 364/364/470 363/363/468 372/372/486 +f 308/308/489 374/374/488 309/309/490 +f 372/372/486 374/374/488 375/375/491 +f 375/375/491 364/364/470 372/372/486 +f 365/365/472 364/364/470 375/375/491 +f 374/374/488 308/308/489 375/375/491 +f 365/365/472 375/375/491 376/376/492 +f 375/375/491 308/308/489 376/376/492 +f 366/366/474 365/365/472 376/376/492 +f 376/376/492 308/308/489 377/377/493 +f 377/377/493 366/366/474 376/376/492 +f 314/314/494 377/377/493 308/308/489 +f 367/367/477 366/366/474 377/377/493 +f 377/377/493 378/378/495 367/367/477 +f 378/378/495 377/377/493 313/313/496 +f 313/313/496 377/377/493 314/314/494 +f 379/379/497 367/367/477 380/380/498 +f 380/380/498 367/367/477 378/378/495 +f 379/379/497 368/368/478 367/367/477 +f 380/380/498 378/378/495 313/313/496 +f 369/369/480 368/368/478 379/379/497 +f 379/379/497 380/380/498 381/381/499 +f 313/313/496 316/316/500 380/380/498 +f 380/380/498 316/316/500 381/381/499 +f 370/370/482 369/369/480 379/379/497 +f 379/379/497 381/381/499 382/382/501 +f 379/379/497 382/382/501 370/370/482 +f 383/383/502 381/381/499 316/316/500 +f 382/382/501 381/381/499 383/383/502 +f 384/384/503 370/370/482 382/382/501 +f 371/371/483 370/370/482 384/384/503 +f 384/384/503 382/382/501 383/383/502 +f 385/385/504 384/384/503 383/383/502 +f 385/385/504 383/383/502 316/316/500 +f 385/385/504 316/316/500 317/317/505 +f 384/384/503 385/385/504 386/386/506 +f 384/384/503 386/386/506 371/371/483 +f 371/371/483 386/386/506 354/354/452 +f 387/387/507 386/386/506 385/385/504 +f 387/387/507 385/385/504 317/317/505 +f 317/317/505 305/305/508 387/387/507 +f 386/386/506 387/387/507 388/388/509 +f 386/386/506 388/388/509 354/354/452 +f 387/387/507 305/305/508 389/389/510 +f 387/387/507 389/389/510 388/388/509 +f 355/355/455 354/354/452 388/388/509 +f 388/388/509 389/389/510 355/355/455 +f 356/356/457 355/355/455 389/389/510 +f 305/305/508 390/390/511 389/389/510 +f 389/389/510 390/390/511 356/356/457 +f 304/304/512 390/390/511 305/305/508 +f 391/391/513 356/356/457 390/390/511 +f 391/391/513 390/390/511 304/304/512 +f 391/391/513 357/357/458 356/356/457 +f 392/392/514 391/391/513 304/304/512 +f 358/358/460 357/357/458 391/391/513 +f 391/391/513 392/392/514 358/358/460 +f 319/319/515 392/392/514 304/304/512 +f 359/359/462 358/358/460 392/392/514 +f 359/359/462 392/392/514 393/393/516 +f 393/393/516 392/392/514 319/319/515 +f 394/394/517 359/359/462 393/393/516 +f 360/360/463 359/359/462 394/394/517 +f 318/318/518 393/393/516 319/319/515 +f 395/395/519 394/394/517 393/393/516 +f 395/395/519 393/393/516 318/318/518 +f 394/394/517 395/395/519 360/360/463 +f 310/310/520 395/395/519 318/318/518 +f 360/360/463 395/395/519 361/361/465 +f 361/361/465 395/395/519 396/396/521 +f 396/396/521 395/395/519 310/310/520 +f 361/361/465 396/396/521 362/362/466 +f 397/397/522 396/396/521 310/310/520 +f 397/397/522 362/362/466 396/396/521 +f 310/310/520 309/309/490 397/397/522 +f 362/362/466 397/397/522 363/363/468 +f 373/373/487 363/363/468 397/397/522 +f 309/309/490 373/373/487 397/397/522 +f 374/374/488 373/373/487 309/309/490 +f 306/306/523 315/315/523 398/398/523 +f 398/398/523 315/315/523 399/399/523 +f 320/320/524 306/306/524 400/400/524 +f 400/400/524 306/306/524 398/398/524 +f 311/311/525 320/320/525 401/401/525 +f 401/401/525 320/320/525 400/400/525 +f 307/307/526 311/311/526 402/402/526 +f 402/402/526 311/311/526 401/401/526 +f 312/312/527 307/307/527 403/403/527 +f 403/403/527 307/307/527 402/402/527 +f 315/315/528 312/312/528 399/399/528 +f 399/399/528 312/312/528 403/403/528 +f 403/403/18 402/402/18 399/399/18 +f 399/399/18 402/402/18 401/401/18 +f 399/399/18 401/401/18 398/398/18 +f 398/398/18 401/401/18 400/400/18 +f 404/404/529 405/405/530 406/406/531 +f 406/406/531 407/407/532 404/404/529 +f 408/408/533 406/406/531 409/409/534 +f 406/406/531 408/408/533 407/407/532 +f 407/407/532 408/408/533 410/410/535 +f 410/410/535 411/411/536 407/407/532 +f 410/410/535 412/412/537 411/411/536 +f 409/409/534 413/413/538 408/408/533 +f 414/414/539 415/415/540 416/416/541 +f 414/414/539 417/417/542 415/415/540 +f 416/416/541 415/415/540 418/418/543 +f 414/414/539 419/419/544 417/417/542 +f 413/413/538 409/409/534 420/420/545 +f 418/418/543 421/421/546 416/416/541 +f 411/411/536 412/412/537 422/422/547 +f 414/414/539 423/423/548 419/419/544 +f 416/416/541 421/421/546 420/420/545 +f 420/420/545 421/421/546 424/424/549 +f 423/423/548 414/414/539 422/422/547 +f 413/413/538 420/420/545 425/425/550 +f 425/425/550 420/420/545 424/424/549 +f 422/422/547 412/412/537 426/426/551 +f 422/422/547 426/426/551 423/423/548 +f 427/427/552 414/414/553 428/428/554 +f 428/428/554 414/414/553 416/416/555 +f 429/429/556 428/428/557 416/416/558 +f 420/420/559 430/430/560 416/416/558 +f 416/416/558 430/430/560 429/429/556 +f 408/408/561 413/413/562 431/431/563 +f 431/431/563 432/432/564 408/408/561 +f 433/433/565 434/434/566 412/412/567 +f 413/413/562 425/425/568 435/435/569 +f 436/436/570 437/437/571 423/423/572 +f 435/435/569 431/431/563 413/413/562 +f 410/410/573 408/408/561 432/432/564 +f 438/438/574 439/439/575 415/415/576 +f 434/434/566 436/436/570 412/412/567 +f 417/417/577 419/419/578 440/440/579 +f 412/412/567 410/410/573 433/433/565 +f 439/439/575 441/441/580 415/415/576 +f 442/442/581 422/422/582 443/443/583 +f 442/442/581 411/411/584 422/422/582 +f 407/407/532 411/411/584 444/444/585 +f 444/444/585 411/411/584 442/442/581 +f 404/404/529 407/407/532 444/444/585 +f 445/445/586 404/404/529 444/444/585 +f 405/405/530 404/404/529 445/445/586 +f 406/406/531 405/405/530 445/445/586 +f 446/446/587 406/406/531 445/445/586 +f 409/409/588 406/406/531 446/446/587 +f 447/447/589 409/409/588 446/446/587 +f 409/409/588 447/447/589 420/420/559 +f 420/420/559 447/447/589 430/430/560 +f 448/448/590 449/449/591 450/450/592 +f 451/451/593 449/449/591 448/448/590 +f 449/449/591 451/451/593 452/452/594 +f 453/453/595 454/454/596 455/455/597 +f 452/452/594 456/456/598 449/449/591 +f 456/456/598 457/457/599 449/449/591 +f 453/453/595 458/458/600 454/454/596 +f 459/459/601 457/457/599 456/456/598 +f 452/452/594 460/460/602 456/456/598 +f 455/455/597 454/454/596 461/461/603 +f 453/453/595 462/462/604 458/458/600 +f 459/459/601 463/463/605 457/457/599 +f 455/455/597 461/461/603 464/464/606 +f 460/460/602 452/452/594 464/464/606 +f 457/457/599 462/462/604 453/453/595 +f 460/460/602 464/464/606 461/461/603 +f 457/457/599 463/463/605 462/462/604 +f 465/465/607 457/457/608 466/466/609 +f 466/466/609 457/457/608 453/453/610 +f 466/466/609 453/453/610 467/467/557 +f 467/467/611 453/453/612 468/468/613 +f 468/468/613 453/453/612 455/455/614 +f 468/468/18 469/469/18 466/466/18 +f 470/470/18 427/427/18 428/428/18 +f 467/467/18 468/468/18 466/466/18 +f 429/429/18 470/470/18 428/428/18 +f 465/465/607 471/471/615 457/457/608 +f 471/471/615 449/449/616 457/457/608 +f 472/472/617 449/449/616 471/471/615 +f 450/450/592 449/449/616 472/472/617 +f 473/473/618 450/450/592 472/472/617 +f 448/448/590 450/450/592 474/474/619 +f 474/474/619 450/450/592 473/473/618 +f 451/451/620 448/448/590 474/474/619 +f 475/475/621 451/451/620 474/474/619 +f 452/452/622 451/451/620 475/475/621 +f 452/452/622 475/475/621 464/464/623 +f 464/464/623 475/475/621 476/476/624 +f 442/442/625 443/443/625 446/446/625 +f 445/445/625 444/444/625 442/442/625 +f 445/445/625 442/442/625 446/446/625 +f 443/443/625 447/447/625 446/446/625 +f 443/443/625 430/430/625 447/447/625 +f 443/443/625 470/470/625 430/430/625 +f 476/476/626 465/465/626 466/466/626 +f 470/470/625 429/429/625 430/430/625 +f 475/475/626 474/474/626 473/473/626 +f 475/475/626 473/473/626 476/476/626 +f 473/473/626 472/472/626 476/476/626 +f 472/472/626 471/471/626 476/476/626 +f 471/471/626 465/465/626 476/476/626 +f 469/469/626 476/476/626 466/466/626 +f 477/477/627 478/478/628 479/479/629 +f 480/480/630 481/481/631 482/482/632 +f 483/483/633 484/484/634 485/485/635 +f 486/486/636 487/487/637 483/483/633 +f 483/483/633 487/487/637 488/488/638 +f 489/489/639 490/490/640 491/491/641 +f 485/485/635 484/484/634 492/492/642 +f 489/489/639 491/491/641 487/487/637 +f 489/489/639 487/487/637 486/486/636 +f 493/493/643 494/494/644 495/495/645 +f 495/495/645 494/494/644 496/496/646 +f 497/497/647 498/498/648 495/495/645 +f 495/495/645 498/498/648 493/493/643 +f 485/485/635 492/492/642 498/498/648 +f 485/485/635 498/498/648 497/497/647 +f 483/483/633 488/488/638 484/484/634 +f 496/496/646 490/490/640 489/489/639 +f 496/496/646 494/494/644 490/490/640 +f 499/499/649 500/500/650 501/501/651 +f 499/499/649 501/501/651 502/502/652 +f 502/502/652 501/501/651 503/503/653 +f 502/502/652 503/503/653 504/504/654 +f 504/504/654 503/503/653 505/505/655 +f 504/504/654 505/505/655 506/506/656 +f 506/506/656 505/505/655 507/507/657 +f 506/506/656 507/507/657 508/508/658 +f 506/506/656 508/508/658 509/509/659 +f 509/509/660 508/508/661 492/492/662 +f 509/509/660 492/492/662 510/510/663 +f 510/510/663 492/492/662 511/511/664 +f 510/510/663 511/511/664 512/512/665 +f 512/512/665 511/511/664 513/513/666 +f 512/512/665 513/513/666 514/514/667 +f 514/514/667 513/513/666 515/515/668 +f 514/514/667 515/515/668 516/516/669 +f 516/516/669 515/515/668 517/517/670 +f 517/517/670 515/515/668 487/487/671 +f 517/517/670 487/487/671 518/518/672 +f 517/517/670 518/518/672 519/519/673 +f 519/519/674 518/518/675 499/499/676 +f 499/499/676 518/518/675 500/500/677 +f 520/520/625 499/499/625 521/521/625 +f 522/522/625 514/514/625 523/523/625 +f 523/523/625 514/514/625 516/516/625 +f 524/524/625 519/519/625 520/520/625 +f 520/520/625 519/519/625 499/499/625 +f 525/525/625 510/510/625 526/526/625 +f 526/526/625 510/510/625 522/522/625 +f 523/523/625 516/516/625 517/517/625 +f 523/523/625 517/517/625 524/524/625 +f 524/524/625 517/517/625 519/519/625 +f 525/525/625 509/509/625 510/510/625 +f 510/510/625 512/512/625 522/522/625 +f 522/522/625 512/512/625 514/514/625 +f 527/527/625 506/506/625 525/525/625 +f 525/525/625 506/506/625 509/509/625 +f 528/528/625 502/502/625 504/504/625 +f 528/528/625 504/504/625 527/527/625 +f 527/527/625 504/504/625 506/506/625 +f 521/521/625 499/499/625 502/502/625 +f 521/521/625 502/502/625 528/528/625 +f 529/529/678 521/521/679 530/530/680 +f 530/530/680 521/521/679 528/528/681 +f 530/530/680 528/528/681 531/531/682 +f 531/531/682 528/528/681 527/527/683 +f 531/531/684 527/527/685 525/525/686 +f 531/531/684 525/525/686 532/532/687 +f 532/532/688 525/525/689 533/533/690 +f 533/533/690 525/525/689 526/526/691 +f 533/533/690 526/526/691 534/534/692 +f 534/534/692 526/526/691 522/522/693 +f 534/534/692 522/522/693 535/535/694 +f 535/535/694 522/522/693 523/523/695 +f 535/535/694 523/523/695 536/536/696 +f 536/536/697 523/523/698 524/524/699 +f 536/536/697 524/524/699 537/537/700 +f 537/537/701 524/524/702 520/520/703 +f 537/537/701 520/520/703 538/538/704 +f 538/538/704 520/520/703 529/529/678 +f 529/529/678 520/520/703 521/521/679 +f 529/529/705 539/539/706 538/538/707 +f 538/538/707 539/539/706 540/540/708 +f 538/538/707 540/540/708 541/541/709 +f 541/541/709 540/540/708 542/542/710 +f 543/543/711 544/544/712 529/529/705 +f 529/529/705 544/544/712 539/539/706 +f 545/545/713 546/546/714 547/547/715 +f 545/545/713 547/547/715 548/548/716 +f 548/548/716 549/549/717 550/550/718 +f 550/550/718 549/549/717 551/551/719 +f 548/548/716 547/547/715 549/549/717 +f 541/541/709 542/542/710 545/545/713 +f 545/545/713 542/542/710 546/546/714 +f 550/550/718 551/551/719 543/543/711 +f 543/543/711 551/551/719 552/552/720 +f 543/543/711 552/552/720 544/544/712 +f 553/553/721 539/539/722 478/478/628 +f 478/478/628 539/539/722 544/544/723 +f 478/478/628 544/544/724 479/479/629 +f 554/554/725 549/549/726 555/555/727 +f 555/555/727 549/549/726 556/556/728 +f 556/556/728 547/547/729 557/557/730 +f 557/557/730 547/547/729 546/546/731 +f 557/557/730 546/546/731 558/558/732 +f 558/558/732 546/546/733 559/559/734 +f 560/560/735 542/542/736 561/561/737 +f 553/553/721 561/561/738 539/539/739 +f 479/479/629 544/544/724 552/552/740 +f 479/479/629 552/552/741 562/562/742 +f 562/562/742 552/552/741 551/551/743 +f 556/556/728 549/549/726 547/547/729 +f 560/560/735 559/559/744 542/542/745 +f 562/562/746 551/551/746 554/554/746 +f 546/546/733 542/542/747 559/559/734 +f 561/561/737 542/542/736 540/540/748 +f 561/561/738 540/540/749 539/539/739 +f 554/554/725 551/551/750 549/549/726 +f 561/561/737 563/563/751 564/564/752 560/560/735 +f 565/565/753 559/559/734 564/564/754 +f 564/564/752 559/559/744 560/560/735 +f 565/565/753 558/558/732 559/559/734 +f 565/565/753 557/557/730 558/558/732 +f 566/566/755 555/555/727 556/556/728 +f 566/566/755 557/557/730 565/565/753 +f 566/566/755 556/556/728 557/557/730 +f 567/567/756 555/555/727 566/566/755 +f 568/568/757 479/479/629 562/562/742 +f 568/568/758 562/562/759 554/554/725 +f 569/569/760 553/553/721 478/478/628 +f 567/567/756 554/554/725 555/555/727 +f 477/477/627 479/479/629 568/568/757 +f 570/570/761 482/482/632 481/481/631 +f 563/563/762 561/561/738 569/569/760 +f 569/569/760 561/561/738 553/553/721 +f 568/568/758 554/554/725 567/567/756 +f 533/533/690 548/548/716 550/550/718 +f 533/533/690 550/550/718 532/532/688 +f 532/532/763 550/550/718 531/531/764 +f 531/531/764 550/550/718 543/543/711 +f 531/531/682 543/543/765 530/530/680 +f 530/530/766 543/543/711 529/529/705 +f 537/537/767 538/538/707 541/541/709 +f 537/537/700 541/541/768 536/536/697 +f 536/536/769 541/541/709 545/545/713 +f 536/536/770 545/545/713 535/535/771 +f 535/535/771 545/545/713 534/534/772 +f 534/534/772 545/545/713 548/548/716 +f 534/534/692 548/548/773 533/533/690 +f 500/500/650 494/494/774 501/501/651 +f 501/501/775 494/494/644 503/503/776 +f 503/503/776 494/494/644 493/493/643 +f 503/503/653 493/493/777 505/505/655 +f 505/505/778 493/493/643 507/507/779 +f 507/507/779 493/493/643 498/498/648 +f 507/507/657 498/498/780 508/508/658 +f 508/508/781 498/498/781 492/492/781 +f 492/492/782 484/484/782 511/511/782 +f 511/511/664 484/484/783 513/513/666 +f 513/513/784 484/484/634 488/488/638 +f 513/513/666 488/488/785 515/515/668 +f 515/515/786 488/488/638 487/487/637 +f 487/487/671 491/491/787 518/518/672 +f 518/518/788 491/491/788 490/490/788 +f 518/518/675 490/490/789 500/500/677 +f 500/500/790 490/490/640 494/494/644 +f 496/496/791 571/571/792 495/495/793 +f 489/489/794 572/572/795 496/496/796 +f 573/573/626 574/574/626 575/575/626 +f 575/575/626 574/574/626 576/576/626 +f 575/575/626 576/576/626 577/577/626 +f 577/577/626 576/576/626 578/578/626 +f 577/577/797 497/497/798 575/575/799 +f 575/575/799 497/497/798 495/495/800 +f 495/495/793 571/571/792 575/575/801 +f 575/575/801 571/571/792 573/573/802 +f 573/573/802 571/571/792 496/496/791 +f 496/496/796 572/572/795 573/573/803 +f 573/573/803 572/572/795 574/574/804 +f 574/574/804 572/572/795 489/489/794 +f 486/486/805 576/576/806 574/574/807 +f 486/486/805 483/483/808 576/576/806 +f 574/574/807 489/489/809 486/486/805 +f 576/576/810 483/483/811 578/578/812 +f 578/578/812 483/483/811 485/485/813 +f 578/578/814 485/485/815 577/577/816 +f 485/485/815 497/497/817 577/577/816 +f 579/579/18 580/580/18 581/581/18 +f 581/581/18 582/582/18 579/579/18 +f 583/583/626 579/579/626 582/582/626 +f 582/582/626 584/584/626 583/583/626 +f 470/470/818 414/414/819 427/427/820 +f 470/470/818 422/422/582 414/414/819 +f 470/470/818 443/443/583 422/422/582 +f 469/469/821 468/468/820 455/455/822 +f 464/464/623 469/469/821 455/455/822 +f 464/464/623 476/476/624 469/469/821 +f 461/461/823 454/454/824 585/585/825 +f 586/586/826 587/587/827 462/462/828 +f 454/454/824 458/458/829 588/588/830 +f 459/459/831 456/456/832 589/589/833 +f 587/587/827 588/588/830 458/458/829 +f 424/424/834 421/421/835 590/590/836 +f 590/590/836 591/591/837 424/424/834 +f 418/418/838 415/415/576 441/441/580 +f 441/441/580 590/590/836 418/418/838 +f 419/419/578 423/423/572 437/437/571 +f 426/426/839 412/412/567 436/436/570 +f 425/425/568 424/424/834 591/591/837 +f 423/423/572 426/426/839 436/436/570 +f 421/421/835 418/418/838 590/590/836 +f 591/591/837 435/435/569 425/425/568 +f 415/415/576 417/417/577 438/438/574 +f 432/432/564 433/433/565 410/410/573 +f 437/437/571 440/440/579 419/419/578 +f 440/440/579 438/438/574 417/417/577 +f 588/588/830 585/585/825 454/454/824 +f 592/592/840 586/586/826 463/463/841 +f 585/585/842 593/593/843 461/461/844 +f 458/458/829 462/462/828 587/587/827 +f 463/463/841 459/459/831 592/592/840 +f 593/593/843 594/594/845 460/460/846 +f 462/462/828 463/463/841 586/586/826 +f 460/460/846 461/461/844 593/593/843 +f 589/589/833 592/592/840 459/459/831 +f 456/456/847 460/460/848 594/594/849 +f 594/594/849 589/589/850 456/456/847 +f 594/594/17 592/592/17 589/589/17 +f 594/594/17 593/593/17 592/592/17 +f 587/587/17 586/586/17 585/585/17 +f 593/593/17 585/585/17 586/586/17 +f 585/585/17 588/588/17 587/587/17 +f 593/593/17 586/586/17 592/592/17 +f 438/438/626 590/590/626 439/439/626 +f 591/591/626 438/438/626 440/440/626 +f 433/433/851 432/432/852 434/434/853 +f 435/435/626 440/440/626 437/437/854 +f 590/590/626 441/441/626 439/439/626 +f 435/435/626 591/591/626 440/440/626 +f 431/431/626 437/437/854 436/436/855 +f 591/591/626 590/590/626 438/438/626 +f 432/432/852 431/431/626 436/436/855 +f 432/432/852 436/436/855 434/434/853 +f 437/437/854 431/431/626 435/435/626 +f 584/584/820 582/582/820 581/581/820 +f 584/584/820 581/581/820 595/595/820 +f 580/580/625 596/596/625 595/595/625 +f 595/595/625 581/581/625 580/580/625 +f 596/596/17 583/583/17 584/584/17 +f 584/584/17 595/595/17 596/596/17 +f 583/583/557 596/596/557 579/579/557 +f 596/596/557 580/580/557 579/579/557 +f 567/567/856 480/480/857 568/568/858 +f 567/567/856 597/597/859 481/481/860 +f 482/482/632 569/569/861 477/477/862 +f 477/477/862 480/480/857 482/482/632 +f 566/566/863 598/598/864 597/597/859 +f 570/570/865 563/563/866 599/599/867 +f 600/600/868 563/563/869 569/569/861 +f 564/564/870 598/598/871 565/565/872 +f 569/569/760 478/478/628 477/477/627 +f 481/481/631 597/597/873 570/570/761 +f 597/597/873 598/598/874 570/570/761 +f 570/570/761 599/599/875 482/482/632 +f 599/599/875 600/600/868 482/482/632 +f 567/567/856 481/481/860 480/480/857 +f 567/567/856 566/566/863 597/597/859 +f 482/482/632 600/600/868 569/569/861 +f 477/477/862 568/568/858 480/480/857 +f 566/566/863 565/565/876 598/598/864 +f 570/570/865 564/564/877 563/563/866 +f 600/600/868 599/599/878 563/563/869 +f 564/564/870 570/570/879 598/598/871 diff --git a/examples/Cassie/urdf/meshes/agility/hip-pitch.obj b/examples/Cassie/urdf/meshes/agility/hip-pitch.obj new file mode 100644 index 0000000000..b3fd9672bf --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/hip-pitch.obj @@ -0,0 +1,18176 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o hip-pitch +v 0.082607 -0.059250 0.062126 +v 0.081991 -0.064250 0.062463 +v 0.046863 -0.059250 0.062499 +v 0.046805 -0.064250 0.062414 +v 0.064382 -0.064250 0.018673 +v 0.056584 -0.064250 0.018172 +v 0.063337 -0.064250 0.026502 +v 0.062765 -0.064250 0.032530 +v 0.045193 -0.064250 0.038703 +v 0.046774 -0.064250 0.045680 +v 0.041802 -0.059250 -0.051531 +v 0.046947 -0.059250 -0.045597 +v 0.040599 -0.064250 -0.054106 +v 0.046914 -0.064250 -0.045560 +v 0.081788 -0.064250 -0.062496 +v 0.081998 -0.059250 -0.062451 +v 0.046857 -0.064250 -0.062490 +v 0.046882 -0.059250 -0.062516 +v -0.056495 -0.059250 -0.034365 +v -0.045679 -0.059250 -0.038139 +v -0.041276 -0.059250 -0.051917 +v 0.044782 -0.059250 -0.039770 +v 0.075262 -0.059250 -0.039797 +v 0.096815 -0.059250 -0.054827 +v 0.073058 -0.059250 -0.045870 +v 0.025752 -0.059250 -0.053852 +v 0.172680 -0.059250 -0.040533 +v 0.150609 -0.059250 -0.058941 +v 0.159381 -0.059250 -0.045418 +v 0.035000 -0.059250 0.066000 +v 0.084049 -0.059250 -0.056096 +v 0.129198 -0.059250 -0.058966 +v 0.129243 -0.059250 -0.065556 +v -0.026873 -0.059250 -0.052757 +v -0.004663 -0.059250 -0.059349 +v -0.013329 -0.059250 -0.065383 +v 0.010933 -0.059250 0.058559 +v -0.013447 -0.059250 0.065213 +v 0.041714 -0.059250 -0.056764 +v 0.134600 -0.059250 0.064941 +v 0.101953 -0.058450 0.056350 +v 0.056798 -0.064250 -0.017929 +v 0.063418 -0.064250 -0.018174 +v 0.075153 -0.064250 -0.039545 +v 0.044814 -0.064250 -0.039800 +v 0.073053 -0.064250 -0.045610 +v 0.084231 -0.064250 -0.056350 +v 0.084137 -0.064250 0.056674 +v 0.080864 -0.064250 0.045526 +v 0.069991 -0.064250 0.032510 +v 0.079840 -0.064250 0.051890 +v 0.040637 -0.064250 0.054030 +v 0.073103 -0.049250 -0.045658 +v 0.073040 -0.047250 -0.045878 +v 0.086013 -0.049250 -0.056835 +v 0.096392 -0.047250 -0.062364 +v 0.111651 -0.049250 -0.066159 +v 0.133476 -0.047250 -0.065631 +v 0.141888 -0.049250 -0.062714 +v 0.161411 -0.048393 -0.051682 +v 0.175132 -0.047250 -0.037512 +v 0.177774 -0.049250 -0.032776 +v 0.185104 -0.047250 -0.012118 +v 0.185394 -0.049250 -0.010437 +v 0.185424 -0.047250 0.011482 +v 0.185480 -0.049250 0.009887 +v 0.177937 -0.049250 0.032488 +v 0.173683 -0.047250 0.039558 +v 0.160141 -0.049250 0.052923 +v 0.150240 -0.047250 0.059141 +v 0.135665 -0.049250 0.064550 +v 0.117354 -0.047250 0.066948 +v 0.108581 -0.049250 0.065435 +v 0.090288 -0.048250 0.059031 +v 0.079801 -0.047250 0.051764 +v 0.079825 -0.049250 0.051707 +v 0.073052 -0.045250 -0.045624 +v 0.073040 -0.043250 -0.045878 +v 0.091980 -0.045250 -0.060511 +v 0.096392 -0.043250 -0.062364 +v 0.118318 -0.045250 -0.066201 +v 0.126710 -0.043250 -0.066084 +v 0.141888 -0.045250 -0.062714 +v 0.155563 -0.043250 -0.056409 +v 0.167783 -0.045250 -0.046513 +v 0.176793 -0.043250 -0.034448 +v 0.185576 -0.045250 -0.013740 +v 0.185825 -0.043250 -0.008899 +v 0.184526 -0.043250 0.014891 +v 0.181455 -0.045250 0.026690 +v 0.175393 -0.043250 0.036656 +v 0.159745 -0.044393 0.053115 +v 0.137541 -0.043250 0.064066 +v 0.135664 -0.045250 0.064550 +v 0.103754 -0.043250 0.065001 +v 0.105123 -0.045250 0.065002 +v 0.079864 -0.045250 0.052091 +v 0.079801 -0.043250 0.051764 +v 0.073052 -0.041250 -0.045624 +v 0.073040 -0.039250 -0.045878 +v 0.086013 -0.041250 -0.056835 +v 0.096392 -0.039250 -0.062364 +v 0.111651 -0.041250 -0.066159 +v 0.133476 -0.039250 -0.065631 +v 0.141887 -0.041250 -0.062714 +v 0.161681 -0.040191 -0.051471 +v 0.176793 -0.039250 -0.034448 +v 0.181395 -0.041250 -0.026827 +v 0.185825 -0.039250 -0.008899 +v 0.186077 -0.041250 -0.000528 +v 0.184338 -0.040250 0.015723 +v 0.175394 -0.039250 0.036656 +v 0.174300 -0.041250 0.038257 +v 0.158057 -0.040250 0.054205 +v 0.137541 -0.039250 0.064066 +v 0.139782 -0.041250 0.061274 +v 0.129277 -0.041250 0.065425 +v 0.103754 -0.039250 0.065001 +v 0.105123 -0.041250 0.065002 +v 0.079864 -0.041250 0.052091 +v 0.079801 -0.039250 0.051764 +v 0.073052 -0.037250 -0.045624 +v 0.073299 -0.034750 -0.045942 +v 0.085339 -0.036000 -0.056301 +v 0.108244 -0.037250 -0.065961 +v 0.109609 -0.034750 -0.065869 +v 0.140048 -0.034750 -0.063326 +v 0.141888 -0.037250 -0.062714 +v 0.161008 -0.034750 -0.051997 +v 0.167782 -0.037250 -0.046513 +v 0.176793 -0.034750 -0.034448 +v 0.185576 -0.037250 -0.013740 +v 0.185825 -0.034750 -0.008900 +v 0.184526 -0.034750 0.014891 +v 0.184121 -0.037250 0.016549 +v 0.175394 -0.034750 0.036655 +v 0.176082 -0.037250 0.035217 +v 0.160141 -0.037250 0.052923 +v 0.153417 -0.034750 0.057706 +v 0.139782 -0.037250 0.061274 +v 0.127367 -0.034750 0.065811 +v 0.129277 -0.037250 0.065425 +v 0.105123 -0.037250 0.065002 +v 0.100499 -0.034750 0.063768 +v 0.079864 -0.037250 0.052091 +v 0.079801 -0.034750 0.051764 +v 0.073052 -0.053250 -0.045624 +v 0.073040 -0.051250 -0.045878 +v 0.086013 -0.053250 -0.056835 +v 0.096392 -0.051250 -0.062364 +v 0.111651 -0.053250 -0.066159 +v 0.126710 -0.051250 -0.066084 +v 0.141887 -0.053250 -0.062714 +v 0.155563 -0.051250 -0.056409 +v 0.162334 -0.053250 -0.050922 +v 0.176793 -0.051250 -0.034448 +v 0.181395 -0.053250 -0.026827 +v 0.185825 -0.051250 -0.008900 +v 0.184333 -0.053250 0.000017 +v 0.184338 -0.052250 0.015723 +v 0.175394 -0.051250 0.036655 +v 0.174300 -0.053250 0.038257 +v 0.158058 -0.052250 0.054205 +v 0.137541 -0.051250 0.064066 +v 0.135664 -0.053250 0.064550 +v 0.103754 -0.051250 0.065001 +v 0.105123 -0.053250 0.065002 +v 0.079864 -0.053250 0.052091 +v 0.079801 -0.051250 0.051764 +v 0.073052 -0.057250 -0.045624 +v 0.073040 -0.055250 -0.045878 +v 0.086013 -0.057250 -0.056835 +v 0.096392 -0.055250 -0.062364 +v 0.111651 -0.057250 -0.066159 +v 0.133476 -0.055250 -0.065631 +v 0.148531 -0.057250 -0.060622 +v 0.168931 -0.055250 -0.045769 +v 0.174109 -0.057250 -0.038527 +v 0.185525 -0.055250 -0.012372 +v 0.184993 -0.057250 -0.013711 +v 0.185061 -0.057250 0.013387 +v 0.184526 -0.055250 0.014891 +v 0.175394 -0.055250 0.036656 +v 0.176082 -0.057250 0.035216 +v 0.159746 -0.056393 0.053115 +v 0.134342 -0.055250 0.065123 +v 0.139989 -0.057250 0.061198 +v 0.129277 -0.057250 0.065425 +v 0.105123 -0.057250 0.065002 +v 0.100499 -0.055250 0.063768 +v 0.079864 -0.057250 0.052091 +v 0.079801 -0.055250 0.051764 +v 0.067738 -0.028904 -0.027824 +v 0.078625 -0.028874 -0.042186 +v 0.074718 -0.034751 -0.037907 +v 0.086538 -0.034750 -0.049101 +v 0.096429 -0.028902 -0.054463 +v 0.110189 -0.034750 -0.058604 +v 0.118273 -0.028931 -0.059137 +v 0.137666 -0.034750 -0.056623 +v 0.137166 -0.028883 -0.056588 +v 0.156959 -0.028895 -0.046426 +v 0.167597 -0.034750 -0.036513 +v 0.174587 -0.028874 -0.023887 +v 0.180160 -0.034750 -0.001831 +v 0.179105 -0.028887 0.007606 +v 0.179471 -0.034750 0.001041 +v 0.171174 -0.034750 0.030197 +v 0.166766 -0.028878 0.036927 +v 0.156364 -0.034750 0.046740 +v 0.143957 -0.028926 0.054309 +v 0.137869 -0.034750 0.056479 +v 0.125298 -0.028871 0.058746 +v 0.107782 -0.034750 0.058412 +v 0.106300 -0.028909 0.057746 +v 0.083273 -0.028889 0.046621 +v 0.080802 -0.034750 0.044707 +v 0.061878 -0.034750 -0.012963 +v 0.061864 -0.028906 -0.012806 +v 0.062625 -0.034750 -0.017285 +v 0.070066 -0.028895 0.032411 +v 0.047011 -0.049250 0.046598 +v 0.046961 -0.047250 0.046484 +v 0.022856 -0.048210 0.062155 +v 0.000829 -0.047250 0.066406 +v -0.001081 -0.049250 0.066403 +v -0.028524 -0.047250 0.060253 +v -0.030347 -0.049250 0.059356 +v -0.049728 -0.047250 0.043723 +v -0.055316 -0.049250 0.037204 +v -0.061950 -0.047250 0.023932 +v -0.065785 -0.049250 0.009100 +v -0.066368 -0.047250 -0.002406 +v -0.064689 -0.049250 -0.014136 +v -0.060055 -0.047250 -0.028354 +v -0.055873 -0.049250 -0.035898 +v -0.041661 -0.047250 -0.052042 +v -0.037215 -0.049250 -0.055005 +v -0.019508 -0.047250 -0.061412 +v -0.019312 -0.049250 -0.063192 +v 0.005592 -0.047250 -0.066738 +v 0.000829 -0.049250 -0.066406 +v 0.029117 -0.048488 -0.059727 +v 0.047017 -0.049250 -0.046371 +v 0.046897 -0.047250 -0.045658 +v 0.046948 -0.045250 0.045623 +v 0.046914 -0.043250 0.045575 +v 0.035170 -0.044481 0.056108 +v 0.023640 -0.043250 0.061852 +v 0.005592 -0.045250 0.066738 +v 0.000829 -0.043250 0.066406 +v -0.028524 -0.043250 0.060253 +v -0.030347 -0.045250 0.059356 +v -0.054157 -0.043250 0.038872 +v -0.055316 -0.045250 0.037204 +v -0.065496 -0.043250 0.010987 +v -0.065785 -0.045250 0.009100 +v -0.064529 -0.043250 -0.015700 +v -0.064689 -0.045250 -0.014136 +v -0.054157 -0.045250 -0.038872 +v -0.053127 -0.043250 -0.039849 +v -0.030347 -0.043250 -0.059356 +v -0.028524 -0.045250 -0.060253 +v -0.001081 -0.043250 -0.066403 +v 0.000829 -0.045250 -0.066406 +v 0.022856 -0.044290 -0.062155 +v 0.047008 -0.043250 -0.046636 +v 0.047017 -0.045250 -0.046371 +v 0.046948 -0.041250 0.045623 +v 0.046961 -0.039250 0.046484 +v 0.028295 -0.041250 0.060361 +v 0.023640 -0.039250 0.061852 +v 0.000829 -0.039250 0.066406 +v -0.001081 -0.041250 0.066403 +v -0.022298 -0.039250 0.062348 +v -0.019834 -0.041250 0.061211 +v -0.036135 -0.040500 0.055422 +v -0.051960 -0.039250 0.041360 +v -0.053127 -0.041250 0.039849 +v -0.062930 -0.039250 0.020600 +v -0.065499 -0.041250 0.012407 +v -0.066352 -0.039250 -0.009086 +v -0.064051 -0.041250 -0.017549 +v -0.053127 -0.039250 -0.039849 +v -0.053891 -0.041250 -0.038474 +v -0.037215 -0.041250 -0.055005 +v -0.030347 -0.039250 -0.059356 +v -0.019766 -0.041250 -0.061231 +v -0.001081 -0.039250 -0.066403 +v 0.000829 -0.041250 -0.066406 +v 0.022062 -0.039250 -0.062432 +v 0.029070 -0.040694 -0.059852 +v 0.047017 -0.041250 -0.046371 +v 0.046948 -0.039250 -0.045623 +v 0.046948 -0.037250 0.045623 +v 0.046859 -0.034750 0.045938 +v 0.034164 -0.037250 0.056722 +v 0.020908 -0.034750 0.063624 +v 0.005592 -0.037250 0.066738 +v -0.006212 -0.034750 0.065784 +v -0.022298 -0.034750 0.062348 +v -0.030347 -0.037250 0.059356 +v -0.037323 -0.034750 0.054526 +v -0.051960 -0.034750 0.041361 +v -0.053128 -0.037250 0.039849 +v -0.062930 -0.034750 0.020600 +v -0.065499 -0.037250 0.012407 +v -0.066352 -0.034750 -0.009086 +v -0.064051 -0.037250 -0.017549 +v -0.053127 -0.034750 -0.039849 +v -0.053891 -0.037250 -0.038474 +v -0.031652 -0.037250 -0.059020 +v -0.030347 -0.034750 -0.059356 +v 0.005591 -0.034750 -0.066738 +v -0.006212 -0.037250 -0.065784 +v 0.020908 -0.037250 -0.063624 +v 0.034164 -0.034750 -0.056721 +v 0.046960 -0.037250 -0.045874 +v 0.046948 -0.034750 -0.045623 +v 0.045188 -0.034751 0.038112 +v 0.044783 -0.045250 0.039777 +v 0.044806 -0.048000 0.039739 +v 0.044968 -0.052375 0.039539 +v 0.044739 -0.043250 0.039804 +v 0.044783 -0.041250 0.039777 +v 0.044739 -0.039250 0.039804 +v 0.044783 -0.037250 0.039777 +v 0.046914 -0.059250 0.045560 +v 0.044803 -0.059250 0.040524 +v 0.044777 -0.057250 0.039749 +v 0.046961 -0.055250 0.046484 +v 0.046948 -0.057250 0.045623 +v 0.044739 -0.055250 0.039804 +v 0.045529 -0.051250 0.041523 +v 0.046897 -0.053250 0.045658 +v 0.047017 -0.053250 -0.046371 +v 0.047011 -0.051250 -0.046598 +v 0.044948 -0.054250 -0.039548 +v 0.044972 -0.050393 -0.039800 +v 0.047017 -0.057250 -0.046371 +v 0.046897 -0.055250 -0.045658 +v 0.044948 -0.057250 -0.039541 +v 0.045209 -0.034750 -0.038107 +v 0.044831 -0.038500 -0.039688 +v 0.044831 -0.042500 -0.039688 +v 0.044601 -0.034750 -0.039444 +v 0.044954 -0.045865 -0.039593 +v -0.059167 -0.034750 -0.000569 +v -0.059188 -0.037250 -0.000353 +v -0.060861 -0.034750 0.002150 +v -0.062892 -0.037250 0.002257 +v -0.063783 -0.034750 0.000906 +v -0.062454 -0.037250 -0.002209 +v -0.062162 -0.034750 -0.002219 +v -0.016709 -0.034750 -0.057349 +v -0.016745 -0.037250 -0.057423 +v -0.019129 -0.037250 -0.056206 +v -0.020924 -0.034750 -0.056625 +v -0.021407 -0.037250 -0.058349 +v -0.019075 -0.034750 -0.060945 +v -0.018726 -0.037250 -0.060880 +v -0.016594 -0.034750 0.058858 +v -0.016831 -0.037250 0.056977 +v -0.019075 -0.037250 0.060945 +v -0.021407 -0.034750 0.059697 +v -0.021287 -0.037250 0.057584 +v -0.018261 -0.034750 0.056203 +v 0.045717 -0.051250 0.048159 +v 0.034164 -0.053250 0.056722 +v 0.023640 -0.051250 0.061852 +v 0.005592 -0.053250 0.066738 +v 0.000829 -0.051250 0.066406 +v -0.028524 -0.051250 0.060253 +v -0.019508 -0.053250 0.061412 +v -0.035804 -0.053250 0.055701 +v -0.049728 -0.051250 0.043723 +v -0.055316 -0.053250 0.037204 +v -0.061950 -0.051250 0.023931 +v -0.065785 -0.053250 0.009100 +v -0.066368 -0.051250 -0.002406 +v -0.064170 -0.052662 -0.016568 +v -0.054157 -0.053250 -0.038872 +v -0.053127 -0.051250 -0.039849 +v -0.035099 -0.052298 -0.056158 +v -0.020441 -0.051250 -0.062836 +v -0.005844 -0.053250 -0.066716 +v -0.001081 -0.051250 -0.066403 +v 0.022856 -0.052290 -0.062155 +v -0.059289 -0.051250 0.001334 +v -0.059740 -0.053250 -0.002044 +v -0.060379 -0.053250 0.002076 +v -0.063509 -0.051250 0.001237 +v -0.064031 -0.053250 0.000371 +v -0.062219 -0.051250 -0.002402 +v -0.017460 -0.051250 -0.056446 +v -0.016995 -0.053250 -0.059813 +v -0.017540 -0.053250 -0.056707 +v -0.020288 -0.053250 -0.056523 +v -0.021224 -0.051250 -0.057828 +v -0.020840 -0.053250 -0.060122 +v -0.018853 -0.051250 -0.061093 +v -0.016664 -0.051250 0.057180 +v -0.017074 -0.053250 0.059926 +v -0.019146 -0.051250 0.060892 +v -0.021306 -0.051250 0.057496 +v -0.021287 -0.053250 0.057584 +v -0.017886 -0.053250 0.056554 +v 0.028295 -0.057250 0.060361 +v 0.023640 -0.055250 0.061852 +v 0.000829 -0.055250 0.066406 +v -0.001081 -0.057250 0.066403 +v -0.028524 -0.055250 0.060253 +v -0.030347 -0.057250 0.059356 +v -0.054157 -0.055250 0.038873 +v -0.055316 -0.057250 0.037204 +v -0.065496 -0.055250 0.010987 +v -0.065785 -0.057250 0.009100 +v -0.064529 -0.055250 -0.015701 +v -0.064689 -0.057250 -0.014136 +v -0.055873 -0.057250 -0.035898 +v -0.053127 -0.055250 -0.039849 +v -0.036817 -0.056380 -0.055174 +v -0.014409 -0.055250 -0.064830 +v -0.005844 -0.057250 -0.066716 +v 0.012292 -0.055250 -0.065264 +v 0.023640 -0.057250 -0.061852 +v 0.034164 -0.055250 -0.056722 +v -0.007812 -0.066007 0.065615 +v -0.029707 -0.066151 0.059183 +v -0.042516 -0.059250 0.051165 +v -0.052679 -0.065996 0.040758 +v -0.062251 -0.059250 0.023846 +v -0.064088 -0.066045 0.016056 +v -0.066251 -0.059250 -0.007786 +v -0.065867 -0.066117 -0.008073 +v -0.059082 -0.066011 -0.029606 +v -0.047941 -0.066016 -0.045530 +v -0.029222 -0.066108 -0.059487 +v -0.007269 -0.066062 -0.065622 +v -0.059118 -0.055250 0.000394 +v -0.059096 -0.057250 -0.000137 +v -0.060372 -0.057250 0.002251 +v -0.063481 -0.055250 0.001763 +v -0.063955 -0.057250 -0.000071 +v -0.061778 -0.055250 -0.002390 +v -0.061437 -0.057250 -0.002276 +v -0.016674 -0.055250 -0.059660 +v -0.017242 -0.057250 -0.060471 +v -0.018402 -0.057250 -0.056237 +v -0.018926 -0.055250 -0.056127 +v -0.021459 -0.057250 -0.058561 +v -0.021433 -0.055250 -0.059295 +v -0.016646 -0.055250 0.058423 +v -0.017940 -0.057250 0.060959 +v -0.020263 -0.055250 0.060824 +v -0.021287 -0.057250 0.057584 +v -0.019655 -0.055250 0.056019 +v -0.017786 -0.057250 0.056478 +v 0.040569 -0.059250 0.054052 +v 0.063097 -0.034750 0.017818 +v 0.056447 -0.034750 0.018322 +v 0.056096 -0.034750 -0.018891 +v 0.133876 -0.066074 0.064978 +v 0.131170 -0.066166 -0.065243 +v 0.051444 -0.028924 -0.029782 +v 0.035887 -0.028898 -0.047015 +v 0.026200 -0.034750 -0.053113 +v 0.012728 -0.028891 -0.058231 +v 0.004677 -0.034750 -0.059242 +v -0.016099 -0.028889 -0.057118 +v -0.034254 -0.028845 -0.048046 +v -0.039937 -0.034750 -0.043732 +v -0.047598 -0.028933 -0.035472 +v -0.053478 -0.034750 -0.025915 +v -0.056043 -0.028863 -0.018385 +v -0.059347 -0.028901 0.000660 +v -0.056569 -0.034750 0.018204 +v -0.054672 -0.028908 0.022581 +v -0.041557 -0.034750 0.042843 +v -0.042436 -0.028873 0.041471 +v -0.023924 -0.028898 0.054092 +v -0.002051 -0.028909 0.059320 +v 0.015604 -0.034750 0.057341 +v 0.016906 -0.028880 0.056517 +v 0.034443 -0.028901 0.048335 +v 0.035784 -0.034750 0.047190 +v 0.051384 -0.028876 0.029636 +v 0.057852 -0.028895 -0.013152 +v 0.057860 -0.034750 -0.013252 +v 0.058311 -0.034750 0.012769 +v 0.057724 -0.028895 0.013306 +v 0.062283 -0.034750 0.013460 +v 0.061790 -0.028900 0.012741 +v -0.035949 -0.057250 0.047133 +v -0.036928 -0.057250 -0.046874 +v 0.030451 -0.057250 -0.050769 +v 0.009174 -0.057250 -0.058789 +v -0.004378 -0.057250 0.059358 +v -0.055804 -0.057250 -0.021085 +v 0.024971 -0.057250 0.054168 +v -0.050571 -0.057250 0.031188 +v -0.057696 -0.059250 -0.013656 +v -0.057016 -0.059250 0.018214 +v -0.037157 -0.059250 0.046616 +v -0.014856 -0.059250 0.057303 +v -0.056059 -0.053250 0.019684 +v 0.025069 -0.053250 0.054147 +v 0.031835 -0.053250 -0.049766 +v 0.011051 -0.053250 -0.058636 +v -0.000739 -0.054309 0.059221 +v -0.046307 -0.053250 -0.037629 +v -0.057300 -0.053250 -0.014948 +v -0.042755 -0.053250 0.041256 +v 0.023303 -0.055250 0.054930 +v 0.025069 -0.055250 -0.054147 +v 0.000060 -0.055250 -0.059217 +v -0.055135 -0.055250 -0.022814 +v -0.038083 -0.055250 -0.045605 +v -0.034466 -0.055250 0.048397 +v -0.053268 -0.055250 0.026886 +v -0.020991 -0.045250 0.056881 +v -0.019075 -0.045250 0.060945 +v -0.017079 -0.045250 -0.060014 +v -0.020935 -0.045250 -0.059926 +v -0.063719 -0.045250 -0.000662 +v -0.061791 -0.045250 0.002490 +v -0.020288 -0.045250 -0.056523 +v -0.056059 -0.045250 0.019684 +v -0.059165 -0.045250 -0.000127 +v -0.016824 -0.045250 0.056965 +v -0.060733 -0.045250 -0.002290 +v 0.026157 -0.045250 -0.053347 +v -0.017540 -0.045250 -0.056707 +v 0.006438 -0.046650 -0.059159 +v 0.005501 -0.046309 0.059193 +v -0.046307 -0.045250 -0.037629 +v 0.025069 -0.045250 0.054147 +v -0.043387 -0.046250 0.040605 +v -0.016746 -0.047250 0.057455 +v -0.018934 -0.047250 0.060945 +v -0.017074 -0.047250 -0.059926 +v 0.028981 -0.047250 0.051641 +v 0.031188 -0.047250 -0.050297 +v -0.018114 -0.047250 -0.056250 +v -0.021335 -0.047250 0.057717 +v -0.063345 -0.047250 0.001956 +v -0.061177 -0.047250 -0.002530 +v -0.056634 -0.047250 0.017963 +v -0.059205 -0.047250 0.000496 +v -0.021167 -0.047250 -0.057444 +v -0.046933 -0.047250 -0.036433 +v -0.019655 -0.047250 0.056217 +v -0.034746 -0.038380 0.048094 +v 0.026157 -0.037250 -0.053347 +v 0.002444 -0.038393 -0.059203 +v 0.005502 -0.038309 0.059193 +v -0.039458 -0.037250 -0.044420 +v -0.054017 -0.038197 -0.024766 +v 0.025069 -0.037250 0.054147 +v -0.052369 -0.037250 0.028597 +v -0.017798 -0.039250 0.060892 +v -0.016827 -0.039250 -0.059833 +v -0.021306 -0.039250 -0.059483 +v -0.021306 -0.039250 0.057496 +v -0.017648 -0.039250 0.056611 +v 0.028980 -0.039250 0.051641 +v -0.018928 -0.039250 -0.056045 +v 0.025069 -0.039250 -0.054147 +v -0.063651 -0.039250 0.001079 +v -0.062693 -0.039250 -0.001940 +v -0.059313 -0.039250 -0.001146 +v -0.060662 -0.039250 0.002117 +v -0.053268 -0.039250 0.026886 +v -0.035687 -0.039250 -0.047820 +v -0.017159 -0.043250 0.056534 +v -0.018934 -0.043250 0.060945 +v -0.021339 -0.043250 0.058147 +v -0.021310 -0.041250 0.057801 +v -0.061429 -0.041250 -0.002455 +v -0.063776 -0.041250 -0.000063 +v -0.021346 -0.041250 -0.057934 +v -0.016603 -0.041250 0.059209 +v -0.061571 -0.041250 0.002455 +v -0.018546 -0.041250 0.056253 +v -0.040610 -0.041250 0.043717 +v -0.056059 -0.041250 0.019684 +v -0.059190 -0.041250 0.000059 +v -0.054931 -0.041250 -0.024082 +v -0.034465 -0.041250 -0.048397 +v -0.018250 -0.041250 -0.056241 +v -0.016605 -0.041250 -0.059036 +v 0.023303 -0.041250 -0.054930 +v -0.000739 -0.042309 0.059221 +v 0.025069 -0.041250 0.054147 +v -0.019075 -0.043250 -0.060945 +v -0.016709 -0.043250 -0.057338 +v 0.023303 -0.043250 0.054930 +v 0.006621 -0.043250 -0.059300 +v 0.030363 -0.043250 -0.050841 +v -0.063955 -0.043250 0.000071 +v -0.054931 -0.043250 0.024082 +v -0.059171 -0.043250 -0.000253 +v -0.061024 -0.043250 0.002311 +v -0.061363 -0.043250 -0.002312 +v -0.055135 -0.043250 -0.022814 +v -0.020974 -0.043250 -0.056713 +v -0.034466 -0.043250 0.048397 +v -0.038083 -0.043250 -0.045605 +v -0.016674 -0.049250 0.059660 +v -0.021306 -0.049250 0.059483 +v -0.019290 -0.049250 0.056135 +v 0.030410 -0.049250 -0.050761 +v 0.026313 -0.051250 -0.053669 +v -0.063783 -0.049250 -0.000906 +v -0.021339 -0.049250 -0.058147 +v -0.019348 -0.049250 -0.060824 +v -0.061778 -0.049250 0.002390 +v -0.056059 -0.049250 0.019684 +v -0.059242 -0.049250 0.000480 +v -0.016500 -0.049250 -0.057778 +v -0.060459 -0.049250 -0.002176 +v 0.030363 -0.049250 0.050841 +v 0.005501 -0.050191 -0.059193 +v 0.006621 -0.049250 0.059300 +v -0.046307 -0.049250 -0.037629 +v -0.019685 -0.049250 -0.056303 +v -0.042755 -0.049250 0.041257 +v -0.034466 -0.051250 0.048396 +v 0.011051 -0.051250 0.058636 +v -0.055135 -0.051250 -0.022814 +v -0.038083 -0.051250 -0.045605 +v -0.051500 -0.051250 0.029629 +v 0.075169 -0.046033 -0.039688 +v 0.075169 -0.042033 -0.039688 +v 0.075177 -0.039250 -0.040549 +v 0.075218 -0.037250 -0.039770 +v 0.075169 -0.056467 -0.039688 +v 0.075218 -0.053250 -0.039770 +v 0.075047 -0.050250 -0.039546 +v 0.179294 -0.037250 -0.001159 +v 0.183830 -0.034750 -0.001170 +v 0.183067 -0.037250 -0.001763 +v 0.182334 -0.037250 0.002517 +v 0.181567 -0.034750 0.002358 +v 0.136707 -0.037250 -0.057388 +v 0.138257 -0.034750 -0.060988 +v 0.139075 -0.037250 -0.060945 +v 0.141346 -0.034750 -0.057934 +v 0.140895 -0.037250 -0.056565 +v 0.137169 -0.034750 0.060122 +v 0.136843 -0.037250 0.059656 +v 0.138245 -0.037250 0.056359 +v 0.141629 -0.034750 0.058874 +v 0.141346 -0.037250 0.057934 +v 0.179313 -0.051250 0.001146 +v 0.179433 -0.053250 0.001027 +v 0.181143 -0.053250 -0.002430 +v 0.181222 -0.051250 -0.002390 +v 0.183894 -0.051250 0.001033 +v 0.181833 -0.053250 0.002253 +v 0.136995 -0.051250 -0.059813 +v 0.137169 -0.053250 -0.060122 +v 0.141469 -0.051250 -0.059469 +v 0.141014 -0.053250 -0.059813 +v 0.138954 -0.053250 -0.055900 +v 0.138420 -0.051250 -0.056358 +v 0.137169 -0.051250 0.060122 +v 0.137618 -0.053250 0.056516 +v 0.138811 -0.051250 0.056140 +v 0.141346 -0.053250 0.057934 +v 0.141166 -0.051250 0.059656 +v 0.138257 -0.053250 0.060988 +v 0.157425 -0.065975 -0.055124 +v 0.176581 -0.066088 -0.034209 +v 0.183820 -0.059250 -0.017406 +v 0.185363 -0.066112 -0.011155 +v 0.185906 -0.059250 0.009250 +v 0.184769 -0.065903 0.013998 +v 0.176510 -0.059250 0.034429 +v 0.174745 -0.066115 0.037408 +v 0.162165 -0.059250 0.051334 +v 0.157314 -0.066050 0.054513 +v 0.179279 -0.055250 0.001383 +v 0.179441 -0.057250 0.000902 +v 0.179909 -0.057250 -0.001683 +v 0.181857 -0.055250 -0.002430 +v 0.183067 -0.057250 -0.001763 +v 0.183709 -0.055250 0.000954 +v 0.182533 -0.057250 0.002394 +v 0.137304 -0.055250 -0.060401 +v 0.136627 -0.057250 -0.059434 +v 0.141399 -0.057250 -0.059523 +v 0.141562 -0.055250 -0.058564 +v 0.138922 -0.057250 -0.056120 +v 0.138089 -0.055250 -0.056315 +v 0.136692 -0.055250 0.057598 +v 0.137290 -0.057250 0.056793 +v 0.140587 -0.055250 0.056209 +v 0.140678 -0.057250 0.056574 +v 0.141495 -0.055250 0.058199 +v 0.138661 -0.055250 0.060824 +v 0.137321 -0.057250 0.060081 +v 0.083829 -0.059250 0.056021 +v 0.079819 -0.059250 0.051830 +v 0.065425 -0.028887 0.023316 +v 0.124873 -0.057250 0.059176 +v 0.116615 -0.057250 -0.059314 +v 0.177197 -0.057250 -0.016860 +v 0.080879 -0.057250 0.044901 +v 0.092957 -0.057250 -0.052927 +v 0.174602 -0.058139 0.022796 +v 0.160672 -0.057250 -0.043673 +v 0.163916 -0.057250 0.039991 +v 0.080778 -0.059250 0.044703 +v 0.124925 -0.059250 0.059293 +v 0.145304 -0.059250 0.053423 +v 0.162715 -0.059250 0.041288 +v 0.178883 -0.059250 0.007202 +v 0.176550 -0.059250 -0.018121 +v 0.120739 -0.054450 -0.059221 +v 0.177847 -0.053250 -0.013558 +v 0.108949 -0.053250 0.058636 +v 0.080880 -0.053250 0.044907 +v 0.094931 -0.053250 -0.054147 +v 0.169438 -0.054393 0.033311 +v 0.153535 -0.054083 -0.048646 +v 0.159457 -0.053250 0.044420 +v 0.166934 -0.053250 -0.036433 +v 0.172031 -0.055250 -0.029835 +v 0.096697 -0.055250 -0.054930 +v 0.113588 -0.055250 0.058869 +v 0.177847 -0.055250 0.013558 +v 0.092226 -0.055250 0.052523 +v 0.080728 -0.055250 0.044544 +v 0.138257 -0.045250 0.060988 +v 0.141290 -0.045250 0.057711 +v 0.141014 -0.045250 -0.059813 +v 0.137169 -0.045250 -0.060122 +v 0.138954 -0.045250 -0.055900 +v 0.116245 -0.046150 -0.059213 +v 0.137651 -0.045250 0.056444 +v 0.112105 -0.045250 0.059456 +v 0.080880 -0.045250 0.044907 +v 0.183359 -0.045250 0.001381 +v 0.092226 -0.045250 -0.052523 +v 0.182444 -0.045250 -0.002378 +v 0.181031 -0.045250 0.002291 +v 0.168024 -0.045250 0.034982 +v 0.158083 -0.045250 -0.045605 +v 0.179464 -0.045250 -0.000812 +v 0.172578 -0.046050 -0.027252 +v 0.140592 -0.047250 -0.060497 +v 0.139889 -0.047250 -0.056168 +v 0.141174 -0.047250 0.057401 +v 0.137940 -0.047250 0.060959 +v 0.183359 -0.047250 -0.001381 +v 0.136404 -0.047250 -0.057982 +v 0.182444 -0.047250 0.002378 +v 0.179831 -0.047250 -0.001855 +v 0.162004 -0.047250 -0.042379 +v 0.093843 -0.047250 -0.053347 +v 0.179275 -0.047250 0.000402 +v 0.171005 -0.047250 0.031558 +v 0.113379 -0.047250 0.059300 +v 0.137935 -0.047250 0.056365 +v 0.080958 -0.047250 0.045270 +v 0.119940 -0.037250 -0.059217 +v 0.108949 -0.037250 0.058636 +v 0.080879 -0.037250 0.044916 +v 0.094931 -0.037250 -0.054147 +v 0.177777 -0.037250 0.014906 +v 0.153536 -0.038083 -0.048645 +v 0.162004 -0.037250 0.042379 +v 0.176041 -0.038450 -0.018721 +v 0.167492 -0.038250 -0.035717 +v 0.141469 -0.039250 -0.059469 +v 0.136995 -0.039250 -0.059813 +v 0.141014 -0.039250 0.059813 +v 0.138954 -0.039250 0.056015 +v 0.137169 -0.039250 0.060122 +v 0.181433 -0.039250 -0.002358 +v 0.183858 -0.039250 -0.000067 +v 0.180406 -0.039250 0.002372 +v 0.138240 -0.039250 -0.056285 +v 0.107057 -0.039250 0.058248 +v 0.172049 -0.039250 0.028240 +v 0.158083 -0.039250 0.045605 +v 0.179177 -0.039250 0.000018 +v 0.108949 -0.039250 -0.058636 +v 0.080777 -0.039250 0.044686 +v 0.137169 -0.043250 0.060122 +v 0.138954 -0.043250 0.056015 +v 0.141014 -0.043250 0.059813 +v 0.141174 -0.041250 -0.057401 +v 0.139075 -0.041250 -0.060945 +v 0.136915 -0.041250 -0.056893 +v 0.117551 -0.042513 -0.059316 +v 0.136995 -0.041250 0.059813 +v 0.141346 -0.041250 0.057934 +v 0.138033 -0.041250 0.056400 +v 0.115178 -0.041250 0.059021 +v 0.093843 -0.041250 0.053347 +v 0.080807 -0.041250 0.044618 +v 0.183830 -0.041250 0.001170 +v 0.180323 -0.041250 -0.002364 +v 0.092226 -0.041250 -0.052523 +v 0.179650 -0.041250 0.001517 +v 0.172578 -0.042450 0.027252 +v 0.162004 -0.041250 0.042379 +v 0.169000 -0.041250 -0.034049 +v 0.141290 -0.043250 -0.057711 +v 0.137798 -0.043250 -0.060892 +v 0.180781 -0.043250 -0.002402 +v 0.183858 -0.043250 -0.000067 +v 0.181359 -0.043250 0.002402 +v 0.172031 -0.043250 -0.029835 +v 0.096697 -0.043250 -0.054930 +v 0.107057 -0.043250 0.058248 +v 0.158082 -0.043250 0.045605 +v 0.179633 -0.043250 0.001643 +v 0.138089 -0.043250 -0.056315 +v 0.080800 -0.043250 0.044991 +v 0.079604 -0.043250 0.043083 +v 0.137079 -0.049250 0.060014 +v 0.137649 -0.049250 0.056592 +v 0.140543 -0.049250 0.056529 +v 0.140595 -0.049250 0.060173 +v 0.112105 -0.049250 0.059456 +v 0.140243 -0.049250 -0.056209 +v 0.139317 -0.049250 -0.061160 +v 0.136935 -0.049250 -0.057337 +v 0.114702 -0.050173 -0.058984 +v 0.080880 -0.049250 0.044907 +v 0.092226 -0.049250 -0.052523 +v 0.179294 -0.049250 -0.001398 +v 0.182079 -0.049250 0.002439 +v 0.174017 -0.050107 0.024766 +v 0.183576 -0.049250 -0.001121 +v 0.161006 -0.050173 0.042735 +v 0.174017 -0.050361 -0.024766 +v 0.161007 -0.050250 -0.042734 +v 0.096697 -0.051250 -0.054930 +v 0.107057 -0.051250 0.058248 +v 0.080777 -0.051250 0.044686 +v 0.064445 -0.028816 0.032641 +v 0.061854 -0.028793 0.029098 +v 0.068099 -0.028750 0.028947 +v 0.067681 -0.026048 0.030538 +v 0.064837 -0.026060 0.031721 +v 0.062884 -0.026056 0.029827 +v 0.064149 -0.028706 0.026662 +v 0.064058 -0.026067 0.027270 +v 0.066651 -0.026115 0.027095 +v 0.008971 -0.090721 -0.018593 +v 0.007398 -0.090656 -0.022301 +v 0.009565 -0.090664 -0.020561 +v 0.006823 -0.090725 -0.017861 +v 0.005111 -0.090632 -0.019097 +v 0.005497 -0.090723 -0.021312 +v 0.006109 -0.080305 -0.019960 +v 0.007471 -0.080469 -0.018720 +v 0.008394 -0.080330 -0.020310 +v 0.005798 -0.088079 -0.019384 +v 0.008729 -0.088122 -0.019583 +v 0.006480 -0.088227 -0.021697 +v 0.006731 -0.080721 -0.021311 +v 0.007794 -0.088317 -0.017703 +v 0.009577 -0.088271 -0.021075 +v 0.004888 -0.088306 -0.019369 +v 0.007250 -0.089250 -0.020000 +v -0.018703 -0.090722 0.005414 +v -0.020872 -0.090640 0.005776 +v -0.022161 -0.090716 0.003827 +v -0.021035 -0.090646 0.001508 +v -0.017760 -0.090742 0.002614 +v -0.021123 -0.080286 0.003531 +v -0.019732 -0.080403 0.004890 +v -0.018851 -0.080414 0.003200 +v -0.021355 -0.088130 0.003038 +v -0.020061 -0.088250 0.005481 +v -0.018638 -0.088135 0.004178 +v -0.018872 -0.088227 0.002267 +v -0.020481 -0.080721 0.002319 +v -0.017662 -0.088310 0.004367 +v -0.022329 -0.088306 0.003953 +v -0.020739 -0.088328 0.001428 +v -0.019962 -0.089250 0.003631 +v -0.054435 -0.070714 -0.022881 +v -0.057137 -0.070648 -0.022997 +v -0.057949 -0.070694 -0.025633 +v -0.055502 -0.070716 -0.027039 +v -0.053533 -0.070656 -0.025523 +v -0.054688 -0.060363 -0.025566 +v -0.057111 -0.060393 -0.024820 +v -0.055072 -0.060404 -0.023824 +v -0.057570 -0.068265 -0.025697 +v -0.055348 -0.068115 -0.023334 +v -0.054214 -0.068241 -0.025730 +v -0.056423 -0.068151 -0.026046 +v -0.054163 -0.068291 -0.022854 +v -0.055833 -0.068320 -0.027144 +v -0.057585 -0.068333 -0.023393 +v -0.055726 -0.069250 -0.024811 +v -0.031630 -0.070731 -0.049474 +v -0.034343 -0.070648 -0.049153 +v -0.035459 -0.070722 -0.051151 +v -0.031454 -0.070700 -0.052742 +v -0.034307 -0.070633 -0.053204 +v -0.032868 -0.060341 -0.050014 +v -0.032221 -0.060396 -0.052042 +v -0.034539 -0.060412 -0.051231 +v -0.033345 -0.068067 -0.052700 +v -0.034254 -0.068144 -0.050085 +v -0.031977 -0.068154 -0.050437 +v -0.030895 -0.068308 -0.051369 +v -0.033436 -0.068289 -0.053626 +v -0.032513 -0.068320 -0.048879 +v -0.035565 -0.068314 -0.050464 +v -0.033223 -0.069250 -0.051159 +v 0.002407 -0.070722 -0.060894 +v -0.000070 -0.070648 -0.058644 +v -0.001842 -0.070674 -0.059911 +v -0.001973 -0.070711 -0.062014 +v 0.000091 -0.070686 -0.063349 +v 0.001214 -0.060364 -0.060491 +v -0.000121 -0.060341 -0.062168 +v -0.001353 -0.060452 -0.060658 +v -0.001142 -0.068155 -0.061789 +v -0.000937 -0.068154 -0.059896 +v -0.000100 -0.068198 -0.058955 +v 0.001023 -0.068130 -0.062081 +v 0.000318 -0.068319 -0.063339 +v -0.002457 -0.068309 -0.061287 +v 0.002411 -0.068258 -0.060128 +v 0.000746 -0.069250 -0.061489 +v 0.009107 -0.090726 -0.053887 +v 0.007356 -0.090656 -0.052661 +v 0.004887 -0.090711 -0.054617 +v 0.006097 -0.080377 -0.055428 +v 0.007159 -0.080448 -0.053728 +v 0.008349 -0.080367 -0.055776 +v 0.006670 -0.088135 -0.053619 +v 0.008717 -0.088139 -0.055076 +v 0.006503 -0.088122 -0.056321 +v 0.007768 -0.088308 -0.052696 +v 0.009587 -0.088283 -0.056051 +v 0.006224 -0.088307 -0.057048 +v 0.004889 -0.088325 -0.054373 +v 0.009138 -0.090677 -0.056422 +v 0.006404 -0.090720 -0.057069 +v 0.007250 -0.089250 -0.055000 +v -0.052377 -0.090713 0.013465 +v -0.050612 -0.090687 0.014916 +v -0.051289 -0.090687 0.017174 +v -0.052364 -0.080342 0.016836 +v -0.052095 -0.080370 0.014656 +v -0.054093 -0.080512 0.015101 +v -0.053968 -0.088160 0.016445 +v -0.052025 -0.088156 0.016795 +v -0.051915 -0.088115 0.014463 +v -0.053885 -0.088151 0.014669 +v -0.055207 -0.088314 0.016251 +v -0.052307 -0.088317 0.017898 +v -0.050466 -0.088303 0.014841 +v -0.053652 -0.088302 0.013406 +v -0.055030 -0.090713 0.014537 +v -0.053659 -0.090720 0.017795 +v -0.052851 -0.089250 0.015601 +v -0.062440 -0.070726 0.009755 +v -0.060739 -0.070698 0.007102 +v -0.057880 -0.070700 0.009471 +v -0.059787 -0.060406 0.010822 +v -0.059387 -0.060379 0.008690 +v -0.061409 -0.060372 0.009028 +v -0.061747 -0.068117 0.009298 +v -0.059838 -0.068114 0.010960 +v -0.059200 -0.068134 0.008463 +v -0.062036 -0.068294 0.007746 +v -0.061854 -0.068321 0.011207 +v -0.059125 -0.068308 0.011619 +v -0.058079 -0.068306 0.008416 +v -0.060462 -0.070719 0.011955 +v -0.060249 -0.069250 0.009543 +v 0.041279 -0.073220 -0.064267 +v 0.044267 -0.073148 -0.063134 +v 0.044367 -0.073220 -0.059820 +v 0.040978 -0.073220 -0.058980 +v 0.039133 -0.073167 -0.061312 +v 0.042915 -0.060350 -0.060321 +v 0.041744 -0.060332 -0.062938 +v 0.040623 -0.060405 -0.060808 +v 0.042818 -0.070150 -0.063026 +v 0.040210 -0.070092 -0.061492 +v 0.043071 -0.070106 -0.060015 +v 0.043232 -0.060711 -0.062594 +v 0.043184 -0.070312 -0.064256 +v 0.039453 -0.070299 -0.062823 +v 0.039871 -0.070329 -0.059622 +v 0.042974 -0.070319 -0.058804 +v 0.044761 -0.070325 -0.061114 +v 0.043443 -0.071250 -0.061128 +v 0.040945 -0.071250 -0.061859 +v -0.031121 -0.073214 0.055972 +v -0.033644 -0.073195 0.053743 +v -0.032055 -0.073179 0.050829 +v -0.030146 -0.060270 0.051861 +v -0.032267 -0.060499 0.053241 +v -0.030023 -0.060422 0.054778 +v -0.032499 -0.070105 0.052829 +v -0.031006 -0.070164 0.054868 +v -0.029206 -0.070157 0.053927 +v -0.029883 -0.070161 0.051825 +v -0.029180 -0.070305 0.050954 +v -0.032012 -0.070321 0.050719 +v -0.031089 -0.070284 0.056317 +v -0.027895 -0.070336 0.053527 +v -0.033561 -0.070323 0.053191 +v -0.027888 -0.073231 0.054038 +v -0.029561 -0.073231 0.050823 +v -0.029307 -0.071250 0.053633 +v -0.031805 -0.071250 0.052901 +v 0.041552 -0.073221 0.064249 +v 0.039071 -0.073152 0.061685 +v 0.041045 -0.073225 0.058932 +v 0.043663 -0.073162 0.059267 +v 0.044768 -0.073217 0.062341 +v 0.042478 -0.060418 0.062849 +v 0.043536 -0.060521 0.061048 +v 0.041485 -0.060339 0.060158 +v 0.040577 -0.060465 0.062131 +v 0.041396 -0.070156 0.059908 +v 0.040380 -0.070129 0.062113 +v 0.042540 -0.070163 0.063066 +v 0.043668 -0.070142 0.061003 +v 0.041161 -0.070306 0.064276 +v 0.044858 -0.070301 0.062416 +v 0.039180 -0.070285 0.060190 +v 0.043243 -0.070323 0.058948 +v 0.043055 -0.071250 0.061859 +v 0.040557 -0.071250 0.061128 +v 0.069197 -0.090673 0.061053 +v 0.068449 -0.090726 0.057826 +v 0.071907 -0.090712 0.060690 +v 0.071345 -0.090645 0.056851 +v 0.072691 -0.090692 0.058763 +v 0.069710 -0.080324 0.058093 +v 0.071075 -0.080337 0.060027 +v 0.071429 -0.080438 0.058242 +v 0.069518 -0.088161 0.060028 +v 0.071625 -0.088253 0.060430 +v 0.069359 -0.080717 0.059880 +v 0.071657 -0.088146 0.058230 +v 0.069512 -0.088142 0.057883 +v 0.072600 -0.088292 0.057938 +v 0.068178 -0.088347 0.058406 +v 0.069243 -0.088283 0.061010 +v 0.070156 -0.088325 0.056736 +v 0.070464 -0.089250 0.059011 +v 0.077815 -0.070722 0.060450 +v 0.080053 -0.070657 0.058631 +v 0.082022 -0.070694 0.060094 +v 0.081646 -0.070706 0.062747 +v 0.078563 -0.070656 0.062812 +v 0.080336 -0.062356 0.062159 +v 0.081066 -0.062439 0.060276 +v 0.078680 -0.062438 0.060631 +v 0.079273 -0.068159 0.059783 +v 0.079248 -0.068091 0.062375 +v 0.081472 -0.068135 0.060651 +v 0.081638 -0.068318 0.062673 +v 0.081892 -0.068313 0.059458 +v 0.078431 -0.068305 0.059196 +v 0.078285 -0.068297 0.062777 +v 0.080000 -0.069250 0.061000 +v 0.105770 -0.090715 0.022647 +v 0.102870 -0.090687 0.020809 +v 0.104064 -0.090696 0.018515 +v 0.105820 -0.090719 0.018251 +v 0.107614 -0.090661 0.020019 +v 0.105544 -0.080305 0.021618 +v 0.105940 -0.080481 0.019139 +v 0.104090 -0.080346 0.020437 +v 0.103744 -0.088233 0.019437 +v 0.104790 -0.088139 0.021762 +v 0.107113 -0.088211 0.019690 +v 0.106116 -0.088157 0.019249 +v 0.103311 -0.088319 0.021657 +v 0.105369 -0.088325 0.018009 +v 0.106695 -0.088290 0.022419 +v 0.105258 -0.089250 0.020367 +v 0.141566 -0.090722 0.002296 +v 0.139651 -0.090640 0.003112 +v 0.137645 -0.090749 0.000954 +v 0.139467 -0.090652 -0.001445 +v 0.142096 -0.090712 -0.000291 +v 0.140643 -0.080346 0.001854 +v 0.139558 -0.080329 -0.000295 +v 0.138921 -0.080453 0.001363 +v 0.138770 -0.088113 0.001756 +v 0.141335 -0.088141 0.001357 +v 0.141069 -0.080726 -0.000076 +v 0.140073 -0.088122 -0.000710 +v 0.139230 -0.088325 0.003034 +v 0.142017 -0.088327 0.002030 +v 0.137703 -0.088278 -0.000198 +v 0.141435 -0.088301 -0.001142 +v 0.140000 -0.089250 0.000803 +v 0.119044 -0.070734 0.059048 +v 0.121275 -0.070655 0.059018 +v 0.122129 -0.070687 0.062098 +v 0.121119 -0.060381 0.060450 +v 0.118828 -0.060501 0.060307 +v 0.120009 -0.060320 0.062258 +v 0.120162 -0.068098 0.059439 +v 0.118761 -0.068134 0.061872 +v 0.121185 -0.068152 0.061847 +v 0.117560 -0.068295 0.060827 +v 0.119823 -0.068330 0.058694 +v 0.120525 -0.068278 0.063449 +v 0.122245 -0.068323 0.060187 +v 0.117676 -0.070696 0.061160 +v 0.119440 -0.070711 0.063159 +v 0.120000 -0.069250 0.061000 +v 0.159769 -0.070679 0.048017 +v 0.158709 -0.070669 0.050090 +v 0.155864 -0.070700 0.049664 +v 0.155664 -0.070671 0.046666 +v 0.158329 -0.070710 0.045935 +v 0.156237 -0.060445 0.048086 +v 0.158213 -0.060390 0.049179 +v 0.158142 -0.060354 0.046970 +v 0.156401 -0.068144 0.047203 +v 0.156795 -0.068153 0.049281 +v 0.158586 -0.068243 0.049559 +v 0.158495 -0.068150 0.046963 +v 0.159733 -0.068303 0.046835 +v 0.155730 -0.068250 0.046393 +v 0.156174 -0.068322 0.050015 +v 0.157555 -0.069250 0.048069 +v 0.178645 -0.070719 0.012599 +v 0.181604 -0.070694 0.014046 +v 0.179395 -0.070714 0.017121 +v 0.178929 -0.060496 0.013472 +v 0.178348 -0.060322 0.015767 +v 0.180392 -0.060359 0.014821 +v 0.178483 -0.068235 0.013084 +v 0.178255 -0.068238 0.016500 +v 0.179524 -0.068153 0.016165 +v 0.180521 -0.068142 0.014080 +v 0.181222 -0.068301 0.013453 +v 0.180613 -0.068316 0.016640 +v 0.176831 -0.068326 0.014628 +v 0.176837 -0.070711 0.014828 +v 0.179188 -0.069250 0.014757 +v 0.151990 -0.073232 -0.055849 +v 0.153533 -0.073149 -0.052812 +v 0.151768 -0.073186 -0.050674 +v 0.149297 -0.060347 -0.053310 +v 0.151471 -0.060401 -0.051758 +v 0.151266 -0.060425 -0.054773 +v 0.149264 -0.070117 -0.054292 +v 0.150297 -0.070151 -0.051612 +v 0.152551 -0.070092 -0.053663 +v 0.151382 -0.070321 -0.056027 +v 0.153586 -0.070319 -0.053679 +v 0.147773 -0.070284 -0.054031 +v 0.151112 -0.070284 -0.050207 +v 0.148246 -0.073196 -0.054682 +v 0.148882 -0.073219 -0.051206 +v 0.150966 -0.071250 -0.052167 +v 0.150351 -0.071250 -0.054696 +v 0.173909 -0.090722 0.002673 +v 0.172668 -0.090637 0.001148 +v 0.174523 -0.090730 -0.001532 +v 0.177197 -0.090661 0.000063 +v 0.176325 -0.090724 0.002684 +v 0.173755 -0.080363 0.001103 +v 0.175651 -0.080433 0.001849 +v 0.175648 -0.080369 -0.000368 +v 0.173656 -0.088140 0.001215 +v 0.175562 -0.088143 0.002172 +v 0.176252 -0.088158 0.000164 +v 0.174278 -0.088135 -0.000439 +v 0.176755 -0.088311 0.002344 +v 0.173684 -0.088320 0.002828 +v 0.172908 -0.088317 -0.000290 +v 0.176481 -0.088282 -0.001254 +v 0.175000 -0.089250 0.000803 +v 0.060211 -0.028750 -0.031385 +v 0.059856 -0.032750 -0.031195 +v 0.056296 -0.028750 -0.033051 +v 0.070396 -0.032792 -0.033484 +v 0.078065 -0.032587 -0.041977 +v 0.071451 -0.028750 -0.034335 +v 0.089082 -0.028750 -0.050733 +v 0.095180 -0.032494 -0.054176 +v 0.115773 -0.028750 -0.059509 +v 0.114896 -0.032544 -0.058992 +v 0.127229 -0.032735 -0.059098 +v 0.143455 -0.028750 -0.054587 +v 0.147325 -0.032712 -0.053241 +v 0.161507 -0.028750 -0.042240 +v 0.161962 -0.032816 -0.042759 +v 0.174161 -0.028750 -0.024422 +v 0.174505 -0.032823 -0.024880 +v 0.179246 -0.032720 -0.008978 +v 0.179505 -0.028761 0.002770 +v 0.176138 -0.032666 0.020839 +v 0.171894 -0.028754 0.028890 +v 0.162857 -0.032568 0.041071 +v 0.155443 -0.028753 0.047661 +v 0.149195 -0.032720 0.051862 +v 0.132731 -0.028753 0.058017 +v 0.132934 -0.032613 0.058155 +v 0.107768 -0.028752 0.058126 +v 0.107815 -0.032727 0.058604 +v 0.084963 -0.028752 0.047967 +v 0.083240 -0.032495 0.046984 +v 0.071409 -0.028750 0.034253 +v 0.071466 -0.032723 0.034339 +v 0.062144 -0.028572 -0.029650 +v 0.064502 -0.026000 -0.026080 +v 0.063261 -0.028713 -0.026533 +v 0.067477 -0.028681 -0.026904 +v 0.068571 -0.028546 -0.029630 +v 0.068251 -0.026000 -0.030811 +v 0.065600 -0.028570 -0.032705 +v 0.063143 -0.026000 -0.031457 +v 0.056206 -0.028750 0.033152 +v 0.059788 -0.032750 0.031194 +v 0.060201 -0.028750 0.031414 +v 0.008144 -0.026798 -0.059821 +v 0.008774 -0.032750 -0.060194 +v -0.008056 -0.032755 -0.059115 +v -0.012057 -0.028088 -0.059968 +v -0.012154 -0.028029 0.059936 +v -0.006293 -0.032629 0.059306 +v 0.008290 -0.032750 0.060349 +v 0.008426 -0.026738 0.059667 +v -0.025391 -0.028029 -0.055641 +v -0.028267 -0.032730 -0.052679 +v -0.037511 -0.032793 -0.046598 +v -0.039506 -0.027935 -0.046030 +v -0.049168 -0.032829 -0.034728 +v -0.054160 -0.027946 -0.028093 +v -0.054617 -0.032717 -0.024163 +v -0.058998 -0.032745 -0.009986 +v -0.060741 -0.028081 -0.007080 +v -0.060746 -0.028024 0.006975 +v -0.058595 -0.032768 0.011316 +v -0.054603 -0.032844 0.024733 +v -0.055276 -0.026849 0.023609 +v -0.043988 -0.028094 0.042384 +v -0.041945 -0.032773 0.043399 +v -0.028306 -0.032736 0.052689 +v -0.025361 -0.028061 0.055692 +v 0.058360 -0.028750 0.014890 +v 0.057071 -0.032685 0.016308 +v 0.050041 -0.028750 0.032027 +v 0.050946 -0.032628 0.031117 +v 0.032393 -0.028750 0.049802 +v 0.037342 -0.032587 0.046058 +v 0.019862 -0.032525 0.056120 +v 0.008986 -0.028750 0.058724 +v -0.016019 -0.028750 0.057204 +v -0.038175 -0.028750 0.045511 +v -0.036548 -0.032564 0.046774 +v -0.055035 -0.028750 0.022993 +v -0.059196 -0.028751 -0.006224 +v -0.050511 -0.028750 -0.031255 +v -0.033134 -0.028750 -0.049303 +v -0.009864 -0.028750 -0.058581 +v 0.007669 -0.032545 -0.059044 +v 0.015161 -0.028750 -0.057441 +v 0.028283 -0.032512 -0.052158 +v 0.037192 -0.028752 -0.046289 +v 0.047683 -0.032648 -0.036139 +v 0.050899 -0.028752 -0.030255 +v 0.058113 -0.028750 -0.015040 +v 0.057577 -0.032743 -0.015600 +v -0.065341 -0.032750 0.000054 +v -0.065314 -0.027898 -0.000013 +v -0.020328 -0.032750 -0.062122 +v -0.020195 -0.027922 -0.062131 +v -0.020283 -0.032750 0.062156 +v -0.020186 -0.027908 0.062118 +v 0.066086 -0.032750 0.034822 +v 0.070834 -0.032750 0.043497 +v 0.111710 -0.032750 -0.060349 +v 0.049496 -0.032750 0.042422 +v 0.165610 -0.032750 0.040918 +v 0.060564 -0.032750 0.027379 +v 0.078957 -0.032750 -0.051212 +v 0.070732 -0.032750 -0.044962 +v 0.064833 -0.032480 0.021382 +v 0.061842 -0.032829 0.015285 +v 0.044324 -0.028122 0.050497 +v 0.045078 -0.032750 0.050409 +v 0.079389 -0.028064 0.051284 +v 0.081212 -0.032750 0.051607 +v 0.111870 -0.026694 0.059773 +v 0.070732 -0.028750 0.044962 +v 0.068437 -0.032750 0.046137 +v 0.050906 -0.028750 0.046005 +v 0.050574 -0.032750 0.045882 +v 0.049369 -0.028750 0.042718 +v 0.111577 -0.026702 -0.059650 +v 0.078716 -0.026457 -0.050287 +v 0.045070 -0.028130 -0.050412 +v 0.042671 -0.032750 -0.050744 +v 0.049661 -0.032750 -0.042155 +v 0.049230 -0.028750 -0.043097 +v 0.050188 -0.032750 -0.045724 +v 0.051316 -0.028750 -0.046117 +v 0.068437 -0.028750 -0.046137 +v 0.132154 -0.028029 -0.059936 +v 0.132026 -0.032750 0.060175 +v 0.132057 -0.028088 0.059968 +v 0.180746 -0.028024 -0.006976 +v 0.174326 -0.026985 -0.026311 +v 0.160478 -0.026375 -0.044315 +v 0.145361 -0.028060 -0.055692 +v 0.145391 -0.028029 0.055641 +v 0.166192 -0.028023 0.040262 +v 0.176836 -0.026666 0.018892 +v 0.180654 -0.032750 0.007175 +v 0.180741 -0.028080 0.007080 +v 0.185314 -0.027898 0.000013 +v 0.185341 -0.032750 -0.000054 +v 0.064427 -0.032830 -0.022458 +v 0.063217 -0.032519 -0.016467 +v 0.060572 -0.032750 -0.027336 +v 0.140283 -0.032750 -0.062156 +v 0.140186 -0.027908 -0.062118 +v 0.140328 -0.032750 0.062122 +v 0.140194 -0.027922 0.062131 +v 0.066032 -0.028750 0.034939 +v 0.066007 -0.032750 -0.035541 +v 0.070834 -0.028750 -0.043497 +v 0.066085 -0.028750 -0.034822 +v 0.062184 -0.028578 0.030081 +v 0.062619 -0.026000 0.028262 +v 0.063951 -0.026000 0.032001 +v 0.065358 -0.028572 0.032603 +v 0.067651 -0.026000 0.031192 +v 0.068622 -0.028669 0.030029 +v 0.067139 -0.026000 0.026699 +v 0.067515 -0.028538 0.026936 +v 0.063257 -0.028718 0.026543 +v 0.060656 -0.028750 0.027216 +v 0.064070 -0.028750 0.017966 +v 0.060647 -0.028750 -0.027258 +v 0.063986 -0.028750 -0.017662 +v -0.061094 -0.025985 0.000258 +v -0.041569 -0.025998 0.041749 +v -0.018692 -0.025984 0.058208 +v -0.019534 -0.026161 0.060225 +v -0.063327 -0.026159 0.000007 +v -0.019095 -0.025984 -0.058078 +v -0.047028 -0.025993 -0.036393 +v 0.038358 -0.026000 0.049653 +v 0.074417 -0.026001 0.048312 +v -0.019554 -0.026161 -0.060218 +v 0.139095 -0.025984 0.058077 +v 0.139606 -0.026137 0.060246 +v 0.047194 -0.026001 -0.048060 +v 0.162837 -0.025998 0.040447 +v 0.181355 -0.025973 0.000756 +v 0.138236 -0.025980 -0.058447 +v 0.183339 -0.026164 0.000001 +v 0.139532 -0.026166 -0.060236 +v 0.047040 0.027001 0.001808 +v 0.046559 0.032830 0.003160 +v 0.045657 0.025499 0.009752 +v 0.046905 0.027001 -0.001883 +v 0.045181 0.025508 -0.012831 +v 0.046541 0.032569 -0.003060 +v 0.045355 0.030366 -0.012372 +v 0.040821 0.026997 -0.025453 +v 0.036311 0.027000 -0.030885 +v 0.036370 0.025500 -0.030979 +v 0.036382 0.025499 0.030983 +v 0.042508 0.027032 0.019404 +v 0.036370 0.027000 0.030979 +v 0.045575 0.030234 0.009859 +v 0.083629 0.025499 -0.030918 +v 0.077638 0.027009 -0.019717 +v 0.083664 0.027000 -0.030868 +v 0.074343 0.025498 -0.009752 +v 0.074818 0.030061 -0.012768 +v 0.073413 0.033047 -0.003369 +v 0.072960 0.027001 -0.001808 +v 0.073095 0.027001 0.001883 +v 0.074666 0.025503 0.012636 +v 0.073356 0.032729 0.002751 +v 0.074363 0.030874 0.011077 +v 0.078243 0.027042 0.021804 +v 0.083689 0.027000 0.030885 +v 0.083664 0.025500 0.030868 +v 0.117211 0.036880 -0.017588 +v 0.087470 0.036885 -0.002833 +v 0.090924 0.036899 0.000113 +v 0.136687 0.036927 0.007161 +v 0.136852 0.036850 -0.007189 +v 0.089457 0.036969 0.002499 +v 0.127004 0.036844 0.017140 +v 0.061172 0.037087 0.002414 +v 0.085435 0.036915 0.001333 +v 0.127349 0.036833 -0.016837 +v 0.116487 0.036813 0.017511 +v 0.009850 0.037295 0.001553 +v 0.046627 0.036799 -0.003570 +v 0.005177 0.037260 -0.008983 +v 0.034019 0.036866 0.006385 +v -0.011855 0.037051 0.006081 +v -0.017832 0.036877 -0.000578 +v -0.008315 0.036931 0.016090 +v -0.008769 0.037127 -0.006726 +v -0.007083 0.036901 -0.016871 +v -0.001029 0.037131 -0.010997 +v 0.003559 0.036821 -0.017512 +v 0.005904 0.037370 0.007811 +v 0.002937 0.036836 0.017711 +v 0.077249 0.025498 0.033727 +v 0.076994 0.026462 0.033767 +v 0.046136 0.026288 0.033384 +v 0.109814 0.025500 0.045989 +v 0.109982 0.026494 0.045965 +v 0.032503 0.025500 0.036841 +v 0.011504 0.026484 0.045294 +v 0.012727 0.025501 0.045037 +v -0.003380 0.026349 0.046545 +v -0.043804 0.026264 0.016708 +v -0.046207 0.026502 0.005341 +v -0.046561 0.026191 -0.005586 +v -0.032864 0.031464 -0.001306 +v -0.037014 0.029513 -0.003078 +v -0.032549 0.029000 0.000000 +v -0.034733 0.030738 0.002950 +v -0.037025 0.029394 0.003102 +v 0.022891 0.032353 0.023226 +v 0.027922 0.031724 0.023306 +v 0.027343 0.029568 0.028237 +v 0.023965 0.030438 0.028448 +v -0.039229 0.029098 -0.000134 +v -0.022232 0.031161 0.025331 +v -0.024678 0.029585 0.028540 +v -0.027638 0.026303 0.037655 +v -0.036751 0.026323 0.028881 +v -0.028243 0.029092 0.027251 +v -0.024694 0.031307 0.022349 +v -0.016758 0.036548 0.009125 +v -0.028130 0.029477 0.023670 +v 0.000674 0.031483 0.032822 +v 0.003172 0.029725 0.036913 +v -0.000545 0.029101 0.039262 +v -0.003156 0.030623 0.035038 +v -0.016938 0.026153 0.043583 +v -0.022627 0.028997 0.027183 +v -0.023627 0.029000 0.022798 +v 0.023060 0.029000 0.027516 +v 0.022788 0.029000 0.023631 +v 0.028064 0.028995 0.023046 +v -0.003297 0.029000 0.036000 +v -0.000009 0.028999 0.032710 +v 0.003064 0.028999 0.035331 +v 0.063564 0.026470 0.028838 +v 0.059976 0.026998 0.024604 +v 0.048142 0.034500 0.004366 +v 0.071895 0.034518 0.004174 +v 0.046551 0.031439 0.012649 +v 0.041339 0.027025 0.026117 +v 0.077977 0.027039 0.026405 +v 0.087496 0.025500 -0.036841 +v 0.108496 0.026484 -0.045294 +v 0.107273 0.025501 -0.045037 +v 0.072327 0.026276 -0.033087 +v 0.025328 0.025500 -0.039623 +v 0.009629 0.026392 -0.046085 +v 0.043852 0.026271 -0.033733 +v 0.026517 0.029542 -0.028685 +v 0.028248 0.030379 -0.027091 +v 0.027888 0.031654 -0.023524 +v 0.024325 0.032461 -0.022386 +v 0.022312 0.031408 -0.026233 +v -0.025279 0.029381 -0.028800 +v -0.022231 0.031162 -0.025331 +v -0.030117 0.026299 -0.035891 +v -0.028860 0.029256 -0.025421 +v -0.025069 0.031244 -0.022197 +v -0.040860 0.026366 -0.022791 +v -0.016647 0.036542 -0.009317 +v 0.002933 0.029379 -0.037758 +v 0.000959 0.031482 -0.032826 +v -0.002162 0.029196 -0.038608 +v -0.007087 0.026388 -0.046093 +v -0.003065 0.030677 -0.034893 +v -0.018810 0.026002 -0.042797 +v -0.022457 0.029000 -0.024392 +v -0.025449 0.029000 -0.022281 +v -0.023860 0.029000 -0.028340 +v 0.028001 0.028999 -0.022999 +v 0.022592 0.029000 -0.023834 +v 0.023338 0.029000 -0.027743 +v 0.001992 0.029000 -0.033622 +v -0.001666 0.029000 -0.033182 +v 0.061532 0.026561 -0.028677 +v 0.059995 0.026998 -0.024604 +v 0.048027 0.034502 -0.004170 +v 0.045470 0.029920 -0.017474 +v 0.078659 0.027029 -0.026042 +v 0.123362 0.026330 -0.046553 +v 0.161870 0.025984 0.020763 +v 0.155403 0.026471 0.030457 +v 0.152330 0.025500 0.033692 +v 0.141891 0.026383 0.041480 +v 0.127087 0.026388 0.046093 +v 0.154697 0.029000 -0.002967 +v 0.152864 0.031464 0.001306 +v 0.153088 0.029000 0.001920 +v 0.154733 0.030738 -0.002950 +v 0.158603 0.029204 -0.001883 +v 0.158424 0.029297 0.002341 +v 0.094983 0.030272 0.028540 +v 0.091752 0.030379 0.027091 +v 0.092112 0.031654 0.023524 +v 0.095675 0.032461 0.022386 +v 0.083113 0.036610 0.006611 +v 0.097688 0.031408 0.026233 +v 0.145627 0.029341 0.028633 +v 0.142704 0.030612 0.026903 +v 0.144054 0.031512 0.022252 +v 0.148798 0.029240 0.025754 +v 0.118500 0.029191 0.038911 +v 0.117076 0.030769 0.034653 +v 0.120103 0.031456 0.032894 +v 0.122582 0.029251 0.037990 +v 0.123065 0.030677 0.034893 +v 0.166063 0.026440 0.007656 +v 0.143619 0.029000 0.022805 +v 0.142699 0.029000 0.027381 +v 0.147319 0.028999 0.022937 +v 0.091436 0.029000 0.026333 +v 0.093196 0.029000 0.022505 +v 0.097408 0.029000 0.023834 +v 0.095650 0.029000 0.028678 +v 0.116600 0.028998 0.035028 +v 0.121666 0.029000 0.033182 +v 0.097109 0.032353 -0.023226 +v 0.086003 0.036551 -0.007548 +v 0.092078 0.031724 -0.023306 +v 0.092062 0.030307 -0.027406 +v 0.096035 0.030438 -0.028448 +v 0.166568 0.026236 -0.003351 +v 0.142232 0.031161 -0.025331 +v 0.144902 0.029489 -0.028630 +v 0.147627 0.026324 -0.037654 +v 0.156751 0.026323 -0.028881 +v 0.145639 0.031129 -0.022038 +v 0.148598 0.029139 -0.026566 +v 0.119932 0.031468 -0.032865 +v 0.116748 0.030461 -0.035461 +v 0.116712 0.029290 -0.037172 +v 0.120887 0.029137 -0.039110 +v 0.123156 0.030623 -0.035038 +v 0.136973 0.026196 -0.043561 +v 0.163179 0.026320 -0.018039 +v 0.142627 0.028997 -0.027183 +v 0.147255 0.029000 -0.022900 +v 0.143627 0.029000 -0.022798 +v 0.093227 0.029000 -0.028493 +v 0.091557 0.028998 -0.024005 +v 0.097923 0.029000 -0.026103 +v 0.095346 0.029000 -0.022423 +v 0.123297 0.029000 -0.036000 +v 0.120009 0.028999 -0.032710 +v 0.071298 0.034653 -0.003938 +v 0.071313 0.033056 0.001545 +v 0.048198 0.033325 0.001665 +v 0.048397 0.032995 -0.001518 +v 0.071830 0.032823 -0.001518 +v -0.006788 0.040275 0.002935 +v -0.007839 0.038068 0.004711 +v -0.001065 0.037948 0.009115 +v 0.002480 0.040266 0.007046 +v 0.007253 0.040239 -0.000461 +v 0.007940 0.038016 -0.003788 +v 0.002020 0.040025 -0.007046 +v -0.005494 0.039983 -0.004725 +v 0.000853 0.052779 0.001589 +v 0.004720 0.052829 0.000929 +v 0.001820 0.052860 0.000096 +v -0.000882 0.052768 -0.001569 +v -0.000966 0.052836 -0.004814 +v -0.004547 0.052836 -0.001469 +v -0.001833 0.052856 -0.000042 +v 0.000982 0.052812 -0.001558 +v 0.003566 0.052805 -0.003171 +v -0.000956 0.052818 0.001549 +v -0.003987 0.052784 0.002791 +v 0.001139 0.052805 0.004827 +v 0.001347 0.049762 0.004860 +v -0.002741 0.049763 0.003040 +v -0.005022 0.049762 -0.000464 +v -0.001886 0.049763 -0.004568 +v 0.002963 0.049762 -0.004015 +v 0.004932 0.049763 0.000757 +v 0.003507 0.049762 -0.000977 +v 0.000899 0.049762 0.003234 +v -0.001933 0.049762 -0.003010 +v 0.002124 0.034039 0.002589 +v -0.000638 0.033959 0.003115 +v -0.003204 0.033957 0.000391 +v -0.000809 0.033968 -0.003267 +v 0.002910 0.034037 -0.001410 +v -0.000509 0.032011 0.038575 +v 0.002389 0.031926 0.037696 +v 0.001708 0.031960 0.033648 +v -0.001492 0.032005 0.033815 +v -0.002854 0.031920 0.036510 +v -0.001389 0.021070 0.036008 +v 0.000075 0.021230 0.034378 +v 0.001406 0.021138 0.035748 +v -0.000026 0.021217 0.037630 +v -0.000592 0.028880 0.034314 +v 0.001670 0.028905 0.035818 +v 0.000806 0.028912 0.037437 +v -0.001383 0.028899 0.037018 +v 0.002722 0.029054 0.035196 +v 0.001146 0.029052 0.038760 +v -0.001070 0.029011 0.033101 +v -0.002569 0.029060 0.037270 +v -0.001449 0.030000 0.036349 +v 0.001061 0.030000 0.035658 +v 0.027685 0.031994 0.023934 +v 0.024032 0.032014 0.028029 +v 0.028163 0.031925 0.026577 +v 0.024729 0.031988 0.022831 +v 0.022799 0.031921 0.024660 +v 0.025470 0.021096 0.026843 +v 0.023860 0.021284 0.025791 +v 0.025245 0.021086 0.024074 +v 0.027093 0.021252 0.025391 +v 0.024641 0.028886 0.023868 +v 0.026794 0.028915 0.024556 +v 0.026603 0.028888 0.026793 +v 0.024074 0.028908 0.026423 +v 0.027033 0.029066 0.023156 +v 0.028259 0.029047 0.026398 +v 0.024494 0.029043 0.028221 +v 0.022691 0.029069 0.025536 +v 0.024016 0.029069 0.022981 +v 0.026569 0.030000 0.025400 +v 0.023966 0.030000 0.025418 +v 0.022852 0.032005 -0.025454 +v 0.023816 0.031917 -0.023100 +v 0.026757 0.032004 -0.023162 +v 0.028256 0.031922 -0.025144 +v 0.026682 0.031932 -0.028083 +v 0.024119 0.031993 -0.027789 +v 0.024929 0.021096 -0.026805 +v 0.026906 0.021022 -0.025628 +v 0.024063 0.021136 -0.025084 +v 0.023829 0.028909 -0.024884 +v 0.022908 0.028958 -0.025781 +v 0.027044 0.028854 -0.026348 +v 0.025931 0.021416 -0.023778 +v 0.025827 0.028911 -0.023837 +v 0.024636 0.029063 -0.022650 +v 0.028300 0.029038 -0.024637 +v 0.025493 0.029025 -0.028545 +v 0.025400 0.030000 -0.026569 +v 0.025418 0.030000 -0.023966 +v -0.002771 0.031974 -0.035183 +v 0.000184 0.031931 -0.033188 +v 0.002421 0.031987 -0.034770 +v 0.001390 0.021060 -0.036177 +v -0.000075 0.021230 -0.034378 +v -0.001406 0.021138 -0.035748 +v 0.000036 0.021222 -0.037647 +v -0.001140 0.028905 -0.034736 +v -0.001164 0.028890 -0.037306 +v 0.000999 0.028938 -0.037777 +v 0.001258 0.028901 -0.034848 +v 0.000198 0.029063 -0.033083 +v 0.002925 0.029054 -0.036011 +v -0.001821 0.029057 -0.038327 +v -0.002574 0.029059 -0.034929 +v 0.001645 0.031983 -0.038407 +v -0.001555 0.031996 -0.038127 +v 0.001449 0.030000 -0.036349 +v -0.001061 0.030000 -0.035658 +v -0.024209 0.031989 -0.027928 +v -0.026839 0.031921 -0.027818 +v -0.028322 0.031966 -0.025511 +v -0.025102 0.021084 -0.024076 +v -0.026077 0.021199 -0.026834 +v -0.023927 0.021262 -0.025884 +v -0.026846 0.021236 -0.024878 +v -0.024347 0.028917 -0.024244 +v -0.026711 0.028893 -0.024227 +v -0.026555 0.028911 -0.026690 +v -0.024126 0.028888 -0.026623 +v -0.024725 0.029055 -0.022713 +v -0.022516 0.029047 -0.025778 +v -0.025296 0.029062 -0.028289 +v -0.027871 0.029056 -0.026855 +v -0.027844 0.029076 -0.023874 +v -0.026146 0.031986 -0.022768 +v -0.022699 0.031965 -0.024526 +v -0.024678 0.030000 -0.026727 +v -0.025964 0.030000 -0.024464 +v -0.037119 0.032009 -0.002710 +v -0.038313 0.031986 0.002005 +v -0.034749 0.031992 0.002344 +v -0.034500 0.021144 -0.000281 +v -0.036353 0.021106 0.001515 +v -0.037133 0.021117 -0.001165 +v -0.034173 0.028844 0.000343 +v -0.037544 0.028821 0.000972 +v -0.036375 0.028904 -0.001661 +v -0.033650 0.029069 -0.001636 +v -0.033636 0.029064 0.001523 +v -0.036769 0.029038 0.002795 +v -0.038778 0.029064 0.000253 +v -0.037214 0.029062 -0.002660 +v -0.033228 0.031992 -0.000679 +v -0.034593 0.030000 -0.000426 +v -0.037407 0.030000 0.000426 +v -0.023265 0.031994 0.023969 +v -0.025541 0.031923 0.022639 +v -0.028342 0.032003 0.025038 +v -0.026048 0.031988 0.028115 +v -0.022930 0.031932 0.026883 +v -0.026636 0.021058 0.026482 +v -0.025288 0.021202 0.023790 +v -0.024185 0.021209 0.026245 +v -0.023670 0.028850 0.024915 +v -0.025975 0.028872 0.027154 +v -0.026830 0.028891 0.024338 +v -0.023526 0.029055 0.027537 +v -0.027586 0.029034 0.027602 +v -0.023334 0.029011 0.023209 +v -0.027589 0.029072 0.023586 +v -0.026392 0.030000 0.026061 +v -0.024147 0.030000 0.024744 +v 0.121549 0.031989 0.038177 +v 0.122815 0.031932 0.035300 +v 0.121055 0.031959 0.033516 +v 0.119439 0.021096 0.034622 +v 0.121564 0.021161 0.035704 +v 0.119170 0.021113 0.037405 +v 0.120386 0.028887 0.037744 +v 0.118275 0.028900 0.035940 +v 0.117857 0.028971 0.034675 +v 0.121517 0.028898 0.035150 +v 0.122625 0.029055 0.037080 +v 0.117528 0.029051 0.037451 +v 0.120250 0.029075 0.038777 +v 0.121434 0.029052 0.033378 +v 0.117835 0.032008 0.034096 +v 0.118264 0.031961 0.038347 +v 0.119874 0.030000 0.034536 +v 0.120126 0.030000 0.037464 +v 0.095252 0.032001 0.022870 +v 0.092291 0.031947 0.023579 +v 0.092511 0.031989 0.027313 +v 0.096231 0.031954 0.027893 +v 0.097083 0.031994 0.024736 +v 0.094493 0.021085 0.023899 +v 0.095948 0.021172 0.026240 +v 0.093135 0.021098 0.026095 +v 0.094308 0.028903 0.027186 +v 0.092989 0.028862 0.024516 +v 0.096284 0.028853 0.024859 +v 0.092361 0.029066 0.027191 +v 0.095552 0.029052 0.028202 +v 0.097364 0.029069 0.024959 +v 0.092142 0.029047 0.023731 +v 0.095392 0.029060 0.022823 +v 0.094043 0.030000 0.024074 +v 0.095045 0.030000 0.026838 +v 0.095084 0.031946 -0.024114 +v 0.097389 0.031929 -0.025833 +v 0.095337 0.031955 -0.027996 +v 0.092697 0.031933 -0.027583 +v 0.091871 0.031989 -0.025168 +v 0.094780 0.031971 -0.022404 +v 0.095878 0.021089 -0.024912 +v 0.093674 0.021178 -0.024131 +v 0.094939 0.021090 -0.026866 +v 0.093177 0.028854 -0.024257 +v 0.094793 0.028839 -0.027271 +v 0.093317 0.021489 -0.026526 +v 0.096020 0.028910 -0.024643 +v 0.097246 0.029069 -0.024865 +v 0.095343 0.029069 -0.022706 +v 0.092623 0.029062 -0.027659 +v 0.096364 0.029052 -0.027671 +v 0.092112 0.029052 -0.023938 +v 0.094544 0.030000 -0.025456 +v 0.122620 0.031995 -0.036763 +v 0.119892 0.031948 -0.038930 +v 0.117261 0.031986 -0.036318 +v 0.119432 0.031952 -0.033059 +v 0.121849 0.032004 -0.034196 +v 0.121293 0.021104 -0.035241 +v 0.119168 0.021222 -0.034735 +v 0.118663 0.021124 -0.036451 +v 0.120354 0.021274 -0.037580 +v 0.119569 0.028917 -0.037600 +v 0.121769 0.028883 -0.036314 +v 0.120234 0.028896 -0.034360 +v 0.118309 0.028880 -0.035660 +v 0.118300 0.029066 -0.033790 +v 0.117203 0.029059 -0.036620 +v 0.120514 0.029031 -0.038949 +v 0.122757 0.029075 -0.036242 +v 0.121490 0.029057 -0.033518 +v 0.120126 0.030000 -0.034536 +v 0.119874 0.030000 -0.037464 +v 0.143131 0.032000 -0.026706 +v 0.143483 0.031971 -0.023076 +v 0.147518 0.031994 -0.023701 +v 0.147890 0.031995 -0.026555 +v 0.145738 0.031937 -0.028314 +v 0.144090 0.021197 -0.026270 +v 0.146846 0.021111 -0.026159 +v 0.145471 0.021115 -0.023876 +v 0.144868 0.028837 -0.027122 +v 0.147121 0.028912 -0.025643 +v 0.145739 0.028903 -0.023766 +v 0.143899 0.028895 -0.024942 +v 0.148146 0.029063 -0.024557 +v 0.146422 0.029024 -0.028357 +v 0.144657 0.029034 -0.022539 +v 0.142694 0.029060 -0.026214 +v 0.145281 0.030000 -0.024355 +v 0.145801 0.030000 -0.026906 +v 0.154352 0.032008 -0.002419 +v 0.153910 0.031939 0.002143 +v 0.158126 0.031990 0.001942 +v 0.155202 0.021059 0.001231 +v 0.156702 0.021093 -0.001360 +v 0.157112 0.021161 0.000953 +v 0.156916 0.028912 -0.001343 +v 0.157507 0.028897 0.000862 +v 0.155219 0.028908 0.001464 +v 0.154515 0.028888 -0.001027 +v 0.154469 0.021482 -0.000621 +v 0.152941 0.028979 -0.000082 +v 0.158844 0.029066 -0.000530 +v 0.156632 0.029066 0.002920 +v 0.156265 0.029053 -0.002826 +v 0.158127 0.031993 -0.001680 +v 0.154536 0.030000 0.000126 +v 0.157464 0.030000 -0.000126 +v 0.145724 0.031995 0.022678 +v 0.142661 0.031932 0.024680 +v 0.143797 0.031992 0.027557 +v 0.147100 0.031937 0.027883 +v 0.148108 0.031986 0.024978 +v 0.145087 0.021135 0.023897 +v 0.146905 0.021114 0.025615 +v 0.144208 0.021083 0.026151 +v 0.147142 0.028905 0.025298 +v 0.145988 0.021469 0.027005 +v 0.145454 0.028897 0.027197 +v 0.143800 0.028913 0.025436 +v 0.145279 0.028902 0.023744 +v 0.142600 0.029060 0.025219 +v 0.145535 0.029040 0.022466 +v 0.146978 0.029062 0.027851 +v 0.144070 0.029066 0.027876 +v 0.148244 0.029064 0.025087 +v 0.145029 0.030000 0.024028 +v 0.145855 0.030000 0.026497 +v 0.001489 -0.068250 -0.058434 +v 0.002242 -0.074831 -0.059217 +v -0.002003 -0.074667 -0.059123 +v -0.002971 -0.068250 -0.061812 +v -0.002085 -0.072067 -0.062618 +v 0.000975 -0.071029 -0.063501 +v 0.001703 -0.068250 -0.063148 +v 0.001421 -0.076294 -0.055453 +v 0.005204 -0.075469 -0.060945 +v 0.006662 -0.070763 -0.064167 +v 0.003598 -0.078455 -0.055313 +v 0.000260 -0.075688 -0.028942 +v 0.003599 -0.078757 -0.021820 +v -0.054423 -0.076166 0.009377 +v -0.017243 -0.075731 -0.005441 +v -0.053919 -0.077436 0.011390 +v -0.009026 -0.078590 -0.004304 +v -0.055712 -0.078300 0.012993 +v -0.059185 -0.073999 0.014171 +v -0.057497 -0.075225 0.009440 +v -0.061867 -0.070095 0.018710 +v -0.059837 -0.073480 0.012272 +v -0.006514 -0.069594 -0.064414 +v 0.009066 -0.066566 -0.065980 +v -0.053981 -0.076063 -0.014781 +v -0.053097 -0.075076 -0.025916 +v -0.035626 -0.076147 -0.042331 +v -0.019252 -0.073008 -0.059071 +v -0.012325 -0.076012 -0.054920 +v -0.030348 -0.074138 -0.052013 +v -0.033236 -0.074856 -0.048444 +v -0.053471 -0.075069 -0.023194 +v -0.060717 -0.073686 -0.005406 +v -0.041806 -0.073382 -0.044885 +v -0.035950 -0.072141 -0.051271 +v -0.060341 -0.073779 0.006642 +v -0.056788 -0.073576 -0.022417 +v -0.050790 -0.070517 -0.039449 +v -0.056686 -0.071831 -0.027336 +v -0.064070 -0.070035 -0.008365 +v -0.034922 -0.070807 -0.053554 +v -0.062951 -0.070854 0.009988 +v -0.058618 -0.070934 -0.025336 +v -0.065510 -0.066269 0.010120 +v -0.021380 -0.066299 -0.062708 +v -0.040839 -0.066259 -0.052357 +v -0.057483 -0.066254 -0.033108 +v -0.065568 -0.066249 -0.009918 +v -0.002311 -0.090025 0.065724 +v -0.013593 -0.089326 0.064482 +v -0.011428 -0.092022 0.062946 +v -0.027790 -0.088880 0.059996 +v -0.029461 -0.091954 0.056521 +v -0.044161 -0.088920 0.049089 +v -0.033843 -0.091132 0.054956 +v -0.056775 -0.088803 0.034021 +v -0.045389 -0.091787 0.044946 +v -0.062307 -0.088941 0.020904 +v -0.059825 -0.091668 0.021406 +v -0.055337 -0.091824 0.031245 +v -0.032177 -0.093062 0.049727 +v 0.172227 -0.094335 0.000668 +v 0.142624 -0.099522 0.001288 +v 0.141394 -0.100160 -0.001408 +v 0.139006 -0.098601 0.003454 +v 0.175181 -0.090885 0.003845 +v 0.128607 -0.098590 0.004205 +v 0.128461 -0.101599 0.001563 +v 0.137825 -0.100656 -0.000919 +v 0.041925 -0.091193 0.064926 +v 0.064938 -0.089735 0.065573 +v 0.038182 -0.093304 0.061590 +v 0.045331 -0.092902 0.062498 +v 0.063824 -0.091972 0.064198 +v 0.119964 -0.102761 0.005122 +v 0.122074 -0.099709 0.006836 +v 0.092321 -0.097828 0.039791 +v 0.105059 -0.102296 0.023261 +v 0.088369 -0.099978 0.041384 +v 0.073046 -0.090842 0.061180 +v 0.073213 -0.094363 0.058498 +v 0.107868 -0.102711 0.019396 +v 0.095113 -0.102223 0.031317 +v 0.102972 -0.103557 0.018494 +v 0.070579 -0.092576 0.061663 +v 0.067810 -0.094171 0.059682 +v 0.008688 -0.088988 -0.065751 +v 0.009711 -0.086250 -0.065964 +v 0.010172 -0.086250 -0.066000 +v 0.009261 -0.086250 -0.065858 +v 0.008833 -0.086250 -0.065685 +v 0.008436 -0.086250 -0.065447 +v 0.008081 -0.086250 -0.065152 +v 0.007775 -0.086250 -0.064805 +v -0.062099 -0.086250 0.019873 +v -0.061880 -0.086250 0.019471 +v -0.062253 -0.086250 0.020304 +v -0.062341 -0.086250 0.020753 +v -0.062359 -0.086250 0.021210 +v -0.062308 -0.086250 0.021664 +v -0.062188 -0.086250 0.022106 +v -0.060222 -0.089661 0.017684 +v -0.060612 -0.086250 0.017726 +v 0.004783 -0.086250 -0.059116 +v 0.003978 -0.091244 -0.056651 +v 0.005574 -0.086250 -0.061116 +v 0.003866 -0.086250 -0.054919 +v 0.003750 -0.086250 -0.052771 +v 0.004211 -0.086250 -0.057042 +v 0.006575 -0.086250 -0.063020 +v 0.122990 -0.102474 -0.008793 +v 0.102669 -0.102455 -0.029108 +v 0.146751 -0.098724 -0.018030 +v 0.085388 -0.105924 -0.003550 +v -0.018881 -0.099117 0.026703 +v -0.050219 -0.094293 0.016886 +v 0.059751 -0.099144 -0.046865 +v 0.056573 -0.105136 -0.021697 +v 0.147847 -0.093346 -0.051444 +v 0.151154 -0.093368 -0.049831 +v 0.123421 -0.097099 -0.047062 +v 0.168323 -0.091802 -0.042077 +v 0.179255 -0.091805 -0.023112 +v 0.007500 -0.102336 -0.022796 +v 0.007289 -0.099911 -0.037273 +v 0.027624 -0.105135 -0.010254 +v 0.058372 -0.101477 0.039189 +v 0.056222 -0.106156 0.013236 +v 0.174969 -0.093809 -0.001866 +v 0.183368 -0.091882 -0.002674 +v 0.125328 -0.091796 -0.064056 +v 0.139191 -0.091826 -0.061072 +v 0.045493 -0.093006 -0.062440 +v 0.006828 -0.096124 -0.052258 +v 0.009979 -0.095380 -0.054942 +v -0.000643 -0.102815 -0.003099 +v 0.007003 -0.102737 -0.017336 +v -0.000076 -0.102726 0.012861 +v 0.008707 -0.100331 0.037045 +v -0.027327 -0.093182 0.052386 +v -0.054460 -0.093288 0.017690 +v 0.043029 -0.094790 0.057937 +v 0.069740 -0.095456 0.056336 +v -0.034149 -0.097682 0.008335 +v 0.009803 -0.102883 -0.019262 +v 0.009234 -0.091767 -0.064020 +v 0.007733 -0.094300 -0.057603 +v 0.038402 -0.093605 -0.060751 +v 0.042786 -0.094699 -0.058098 +v 0.148804 -0.092009 -0.056386 +v 0.154435 -0.091459 -0.054314 +v 0.177886 -0.092878 0.001107 +v -0.019648 -0.100216 0.006306 +v -0.022677 -0.099599 0.004094 +v -0.017215 -0.100677 0.003135 +v 0.010750 -0.086250 -0.066000 +v 0.122783 -0.088719 -0.065955 +v 0.131373 -0.066250 -0.065433 +v 0.010750 -0.066250 -0.066000 +v -0.055711 -0.066250 0.036165 +v -0.036231 -0.066250 0.055716 +v -0.011721 -0.066250 0.065343 +v 0.183730 -0.066250 -0.018630 +v 0.184869 -0.089500 -0.011053 +v 0.182660 -0.088681 -0.020911 +v 0.175836 -0.088938 -0.035145 +v 0.173343 -0.066250 -0.039220 +v 0.165297 -0.089606 -0.047798 +v 0.156239 -0.066250 -0.055711 +v 0.150956 -0.088947 -0.058342 +v 0.135936 -0.088971 -0.064082 +v 0.061346 -0.066260 0.066000 +v -0.062467 -0.066464 0.021196 +v -0.004457 -0.074748 -0.004953 +v -0.009738 -0.074750 -0.034314 +v -0.009114 -0.076250 -0.033965 +v -0.021897 -0.076250 -0.030060 +v -0.021291 -0.074750 -0.030008 +v -0.025925 -0.074750 -0.020830 +v -0.025810 -0.076250 -0.015160 +v -0.023576 -0.074750 -0.010820 +v 0.003848 -0.099692 -0.016755 +v 0.002195 -0.100272 -0.011698 +v 0.004368 -0.100581 -0.019809 +v 0.004119 -0.074748 -0.017765 +v -0.002645 -0.100210 -0.006269 +v 0.061341 -0.086250 0.066000 +v 0.137857 -0.076250 0.032348 +v 0.145518 -0.075700 0.023527 +v 0.138550 -0.076147 0.052950 +v 0.175211 -0.076169 0.006855 +v 0.144917 -0.075400 0.013390 +v 0.139693 -0.075959 0.006893 +v 0.166341 -0.076125 0.030850 +v 0.082014 -0.076284 0.054924 +v 0.116741 -0.077162 0.014039 +v 0.116128 -0.075249 0.022497 +v 0.125433 -0.076250 0.033440 +v 0.118355 -0.074749 0.010957 +v 0.126141 -0.074750 0.033694 +v 0.140529 -0.074750 0.030951 +v 0.128314 -0.074749 0.004124 +v 0.133100 -0.079159 0.004408 +v 0.080855 -0.070822 0.063803 +v 0.069355 -0.070486 0.064103 +v 0.077247 -0.073704 0.060599 +v 0.116932 -0.073470 0.061245 +v 0.121973 -0.071583 0.063250 +v 0.062738 -0.066375 0.066005 +v 0.131534 -0.066265 0.065414 +v 0.082325 -0.074321 0.059721 +v 0.121000 -0.075032 0.058404 +v 0.079262 -0.075006 0.058368 +v 0.152706 -0.070763 0.055054 +v 0.159300 -0.070866 0.050044 +v 0.164419 -0.066526 0.049183 +v 0.178769 -0.073438 0.017660 +v 0.181904 -0.071125 0.014157 +v 0.180429 -0.069757 0.023017 +v 0.178496 -0.074322 0.012171 +v 0.176483 -0.075241 0.014551 +v 0.184207 -0.070718 0.001194 +v 0.185929 -0.066651 -0.000959 +v 0.184833 -0.066255 0.013468 +v 0.176111 -0.066257 0.035601 +v 0.171824 -0.070339 0.038024 +v 0.148982 -0.066329 0.059603 +v 0.136191 -0.071272 0.061449 +v 0.159971 -0.073068 0.046898 +v 0.170145 -0.073614 0.035364 +v 0.155762 -0.073069 0.050193 +v 0.139567 -0.074380 0.056814 +v 0.181249 -0.073395 0.004070 +v 0.155899 -0.075162 0.045706 +v 0.178681 -0.076464 0.003853 +v 0.173999 -0.077975 0.004687 +v 0.081917 -0.078626 0.051837 +v 0.073446 -0.074596 0.061288 +v 0.122380 -0.068250 0.059619 +v 0.120476 -0.068250 0.063895 +v 0.117573 -0.068250 0.059168 +v 0.155123 -0.068250 0.049710 +v 0.160558 -0.068250 0.048759 +v 0.156623 -0.068250 0.045485 +v 0.181406 -0.068250 0.013203 +v 0.180451 -0.068250 0.017423 +v 0.178223 -0.068250 0.012300 +v 0.176488 -0.068250 0.015179 +v 0.077262 -0.068250 0.059894 +v 0.079542 -0.068250 0.063606 +v 0.082543 -0.068250 0.061997 +v 0.081322 -0.068250 0.058707 +v 0.185963 -0.086250 -0.002195 +v 0.185941 -0.086250 -0.001716 +v 0.185842 -0.086250 -0.001246 +v 0.185670 -0.086250 -0.000799 +v 0.185429 -0.086250 -0.000384 +v 0.185124 -0.086250 -0.000013 +v 0.184765 -0.086250 0.000305 +v 0.061591 -0.086250 0.065990 +v 0.180297 -0.086250 0.002831 +v 0.182612 -0.086250 0.001712 +v 0.177858 -0.086250 0.003644 +v 0.175334 -0.086250 0.004137 +v 0.172768 -0.086250 0.004303 +v 0.131000 -0.086250 0.004303 +v 0.120372 -0.086250 0.008824 +v 0.122058 -0.086250 0.007322 +v 0.123954 -0.086250 0.006095 +v 0.126014 -0.086250 0.005171 +v 0.128192 -0.086250 0.004572 +v 0.130435 -0.086250 0.004313 +v 0.120039 -0.086250 0.009183 +v 0.074785 -0.086250 0.059442 +v 0.072990 -0.086250 0.061200 +v 0.070989 -0.086250 0.062719 +v 0.068813 -0.086250 0.063975 +v 0.064076 -0.086250 0.065623 +v 0.066496 -0.086250 0.064948 +v 0.185945 -0.086250 -0.002697 +v 0.185945 -0.066250 -0.002697 +v 0.061936 -0.086250 0.052394 +v 0.158285 -0.086250 -0.001649 +v 0.151777 -0.086250 0.002696 +v 0.109062 -0.086250 0.003609 +v 0.158208 -0.066250 -0.001495 +v 0.058683 -0.066253 0.052568 +v 0.109255 -0.066250 0.003522 +v 0.152261 -0.066250 0.002571 +v 0.066974 -0.066250 0.049338 +v -0.036171 -0.068250 -0.050390 +v -0.031757 -0.068250 -0.053792 +v -0.031462 -0.068250 -0.049052 +v -0.053555 -0.068250 -0.022743 +v -0.058688 -0.068250 -0.024897 +v -0.054753 -0.068250 -0.027373 +v -0.057299 -0.068250 0.009994 +v -0.062793 -0.068250 0.011140 +v -0.060700 -0.068250 0.006836 +v -0.061991 -0.086250 0.022652 +v -0.061991 -0.066250 0.022652 +v -0.001919 -0.086250 -0.007429 +v -0.000390 -0.086250 -0.008806 +v 0.011069 -0.086250 -0.008360 +v 0.003750 -0.086250 -0.019053 +v 0.003714 -0.086250 -0.018024 +v -0.005955 -0.086250 -0.005192 +v -0.005475 -0.086250 -0.005377 +v -0.003625 -0.086250 -0.006279 +v 0.000933 -0.086250 -0.010383 +v 0.002023 -0.086250 -0.012128 +v 0.002860 -0.086250 -0.014008 +v 0.003428 -0.086250 -0.015986 +v -0.051928 -0.086250 0.011541 +v -0.053912 -0.086250 0.012387 +v -0.055794 -0.086250 0.013442 +v -0.057552 -0.086250 0.014693 +v -0.059164 -0.086250 0.016127 +v -0.034648 -0.086250 0.009852 +v 0.017080 -0.086250 -0.053387 +v 0.012836 -0.086250 -0.047389 +v -0.040720 -0.086250 0.016308 +v 0.016246 -0.066250 -0.053132 +v -0.040625 -0.066250 0.016718 +v 0.010892 -0.066250 -0.008120 +v -0.036475 -0.066250 0.010861 +v 0.012514 -0.066250 -0.045333 +v 0.185740 -0.088920 -0.000985 +v 0.181925 -0.088939 0.002055 +v -0.055421 -0.089709 0.013033 +v -0.052033 -0.092654 0.013095 +v -0.055367 -0.091858 0.014532 +v -0.020413 -0.098202 0.000922 +v 0.041754 -0.091174 -0.064986 +v 0.004583 -0.092695 -0.055740 +v 0.150243 -0.070250 -0.049452 +v 0.147499 -0.070250 -0.054870 +v 0.154200 -0.070250 -0.053418 +v 0.151824 -0.070250 -0.056516 +v -0.029778 -0.070250 0.056737 +v -0.034504 -0.070250 0.053095 +v -0.027356 -0.070250 0.052708 +v -0.030080 -0.070250 0.049863 +v 0.045524 -0.070250 -0.061255 +v 0.041597 -0.070250 -0.057897 +v 0.038479 -0.070250 -0.062680 +v 0.043155 -0.070250 -0.064732 +v 0.041434 -0.070250 0.065024 +v 0.038522 -0.070250 0.061516 +v 0.045525 -0.070250 0.061985 +v 0.042081 -0.070250 0.057782 +v 0.106911 -0.088250 0.017938 +v 0.102233 -0.088250 0.020649 +v 0.106843 -0.088250 0.022695 +v 0.139733 -0.088250 -0.001976 +v 0.137349 -0.088250 0.000877 +v 0.140397 -0.088250 0.003695 +v 0.142601 -0.088250 0.000295 +v 0.176747 -0.088250 -0.001676 +v 0.175761 -0.088250 0.003621 +v 0.172238 -0.088250 0.000491 +v 0.067814 -0.088250 0.060254 +v 0.072204 -0.088250 0.061139 +v 0.072579 -0.088250 0.057282 +v 0.069359 -0.088250 0.056638 +v 0.008216 -0.088250 -0.017138 +v 0.004524 -0.088250 -0.019939 +v 0.008514 -0.088250 -0.022715 +v -0.019199 -0.088250 0.006351 +v -0.022745 -0.088250 0.003828 +v -0.017365 -0.088250 0.003056 +v -0.020015 -0.088250 0.000904 +v -0.050373 -0.088250 0.014670 +v -0.054977 -0.088250 0.017331 +v -0.054098 -0.088250 0.012987 +v -0.051340 -0.088250 0.017827 +v 0.008545 -0.088250 -0.057450 +v 0.009295 -0.088250 -0.052871 +v 0.004194 -0.088250 -0.054953 +v 0.063411 -0.086250 0.052393 +v 0.018312 -0.086250 -0.053261 +v -0.034647 -0.086250 0.010631 +v 0.012535 -0.086250 -0.008337 +v 0.014302 -0.086250 -0.047366 +v -0.039173 -0.086250 0.016659 +v 0.159750 -0.086250 -0.001625 +v 0.153242 -0.086250 0.002719 +v 0.110527 -0.086250 0.003632 +v 0.017902 -0.066250 -0.053242 +v 0.159673 -0.066250 -0.001472 +v -0.039250 -0.066250 0.016445 +v 0.060126 -0.066248 0.052587 +v 0.013980 -0.066250 -0.045310 +v 0.012357 -0.066250 -0.008097 +v 0.153726 -0.066250 0.002594 +v 0.068439 -0.066250 0.049361 +v 0.110720 -0.066250 0.003545 +v -0.033517 -0.066250 0.010062 +v -0.060606 -0.065730 0.004181 +v -0.065400 -0.065742 0.001951 +v -0.062715 -0.065575 0.000880 +v -0.060130 -0.065634 0.000612 +v -0.057055 -0.065742 -0.000047 +v -0.061655 -0.065675 -0.001492 +v -0.060307 -0.065774 -0.004041 +v -0.064471 -0.065751 -0.003020 +v -0.062407 -0.025972 -0.001838 +v -0.062582 -0.025858 0.001800 +v -0.059354 -0.026072 -0.000108 +v -0.063882 -0.063545 0.000405 +v -0.060123 -0.063539 -0.001946 +v -0.060277 -0.063562 0.001828 +v -0.014778 -0.065747 -0.059253 +v -0.016376 -0.065776 -0.055258 +v -0.017537 -0.065575 -0.058181 +v -0.020006 -0.065684 -0.057373 +v -0.023507 -0.065726 -0.058743 +v -0.019471 -0.065622 -0.059916 +v -0.019964 -0.065735 -0.054380 +v -0.018758 -0.065746 -0.062845 +v -0.020751 -0.025936 -0.057694 +v -0.018502 -0.026129 -0.056456 +v -0.017250 -0.025981 -0.059684 +v -0.020333 -0.026044 -0.059932 +v -0.017667 -0.063562 -0.056743 +v -0.021290 -0.063539 -0.057812 +v -0.017852 -0.063545 -0.060613 +v -0.018354 -0.065730 0.054264 +v -0.015212 -0.065756 0.056831 +v -0.017934 -0.065575 0.057522 +v -0.018702 -0.065675 0.059901 +v -0.015551 -0.065768 0.061102 +v -0.019964 -0.065735 0.062600 +v -0.022597 -0.065771 0.056185 +v -0.020378 -0.065634 0.058047 +v -0.022797 -0.065756 0.060149 +v -0.020862 -0.025922 0.058576 +v -0.017079 -0.026000 0.058008 +v -0.019315 -0.026101 0.056426 +v -0.019229 -0.026058 0.060664 +v -0.021323 -0.063523 0.057669 +v -0.016783 -0.063551 0.057652 +v -0.018768 -0.063563 0.060639 +v 0.140079 -0.065618 0.059454 +v 0.141102 -0.065756 0.054540 +v 0.143017 -0.065725 0.060139 +v 0.139410 -0.065756 0.062610 +v 0.135585 -0.065747 0.061089 +v 0.137930 -0.065634 0.057526 +v 0.135475 -0.065752 0.056040 +v 0.137357 -0.025970 0.057054 +v 0.138172 -0.025991 0.060294 +v 0.141117 -0.025886 0.058391 +v 0.137040 -0.063555 0.059743 +v 0.137739 -0.063565 0.056852 +v 0.140562 -0.063558 0.056818 +v 0.140459 -0.063563 0.060089 +v 0.181869 -0.065545 -0.001425 +v 0.185745 -0.065735 0.001276 +v 0.181177 -0.065675 0.001236 +v 0.177936 -0.065751 0.002289 +v 0.178296 -0.065739 -0.003065 +v 0.181586 -0.065754 0.004183 +v 0.183636 -0.065751 -0.003658 +v 0.180233 -0.026122 -0.001753 +v 0.180046 -0.025995 0.001294 +v 0.182700 -0.025970 0.001616 +v 0.183055 -0.026007 -0.001184 +v 0.180511 -0.063563 0.001922 +v 0.179726 -0.063551 -0.001578 +v 0.183959 -0.063523 0.000064 +v 0.137999 -0.065622 -0.059603 +v 0.135151 -0.065749 -0.059998 +v 0.137928 -0.065756 -0.062588 +v 0.143234 -0.065751 -0.058247 +v 0.140420 -0.065752 -0.054434 +v 0.140471 -0.065587 -0.058805 +v 0.138544 -0.065675 -0.057062 +v 0.135585 -0.065747 -0.055891 +v 0.141630 -0.065749 -0.061689 +v 0.140954 -0.025920 -0.059132 +v 0.136996 -0.025947 -0.058447 +v 0.139257 -0.026052 -0.056517 +v 0.140295 -0.063561 -0.056658 +v 0.137562 -0.063569 -0.056981 +v 0.137211 -0.063549 -0.059925 +v 0.138352 -0.026349 -0.060536 +v 0.140690 -0.063562 -0.059903 +v -0.042808 0.026348 -0.017732 +v -0.016044 0.026348 -0.043108 +v -0.019137 -0.027731 -0.041827 +v -0.042235 -0.027731 -0.017494 +v 0.019137 0.026348 -0.041827 +v 0.008829 -0.027731 -0.044389 +v 0.031320 -0.027731 -0.033686 +v 0.043108 0.026348 -0.016044 +v 0.045966 -0.027731 -0.001673 +v 0.044389 0.026348 0.008829 +v 0.031320 0.026348 0.033686 +v 0.033686 -0.027731 0.031320 +v 0.008829 0.026348 0.044389 +v 0.001673 -0.027731 0.045966 +v -0.019137 0.026348 0.041827 +v -0.031320 -0.027731 0.033686 +v -0.042235 0.026348 0.017494 +v -0.044389 -0.027731 0.008829 +v 0.075611 0.026348 -0.008829 +v 0.088680 0.026348 -0.033686 +v 0.077765 -0.027731 -0.017494 +v 0.100863 -0.027731 -0.041827 +v 0.121674 0.026348 -0.045966 +v 0.136045 -0.027731 -0.043108 +v 0.145144 0.026348 -0.037631 +v 0.163108 0.026348 -0.016045 +v 0.161827 -0.027731 -0.019137 +v 0.164389 0.026348 0.008829 +v 0.163108 -0.027731 0.016044 +v 0.151320 0.026348 0.033686 +v 0.139137 -0.027731 0.041827 +v 0.118327 0.026348 0.045966 +v 0.111171 -0.027731 0.044389 +v 0.094856 0.026348 0.037631 +v 0.088680 -0.027731 0.033686 +v 0.077765 0.026348 0.017494 +v 0.075611 -0.027731 0.008829 +v 0.145509 -0.097494 0.063490 +v 0.120459 -0.097134 0.068046 +v 0.124388 -0.097184 0.067418 +v 0.104887 -0.097134 0.069884 +v 0.096885 -0.097134 0.070469 +v 0.080609 -0.097134 0.071658 +v 0.072304 -0.097111 0.071965 +v 0.069074 -0.096663 0.072079 +v 0.066356 -0.095775 0.072200 +v 0.064003 -0.094478 0.072335 +v 0.060116 -0.088857 0.072797 +v 0.060815 -0.090946 0.072635 +v 0.062179 -0.092898 0.072475 +v 0.056485 -0.069124 0.074058 +v 0.056484 -0.069126 0.074093 +v 0.051572 -0.065082 0.074227 +v 0.051572 -0.065083 0.074248 +v -0.032244 -0.065083 0.064805 +v -0.040827 -0.065091 0.062012 +v -0.048641 -0.065094 0.057404 +v -0.055279 -0.065093 0.051195 +v -0.062745 -0.065083 0.038467 +v -0.060396 -0.065088 0.043711 +v -0.063557 -0.065083 0.036180 +v -0.064826 -0.068785 0.031509 +v -0.064834 -0.068786 0.031511 +v -0.064784 -0.092177 0.025544 +v -0.064730 -0.093532 0.024779 +v -0.064685 -0.094660 0.024141 +v -0.064372 -0.096779 0.022208 +v -0.064256 -0.097353 0.021352 +v -0.064059 -0.098326 0.019900 +v -0.064030 -0.099902 0.013892 +v -0.063902 -0.099368 0.017149 +v -0.065100 -0.099929 0.002424 +v -0.065033 -0.099933 -0.002799 +v -0.065016 -0.099934 -0.004068 +v -0.062671 -0.099991 -0.020942 +v -0.057991 -0.100071 -0.035731 +v -0.052221 -0.100095 -0.045787 +v -0.055220 -0.100094 -0.041299 +v -0.048728 -0.100077 -0.049868 +v -0.040561 -0.099994 -0.056499 +v -0.044830 -0.100043 -0.053448 +v -0.031431 -0.099861 -0.060741 +v -0.036050 -0.099932 -0.058940 +v -0.023523 -0.099709 -0.063032 +v 0.006317 -0.097685 -0.068866 +v 0.003637 -0.098836 -0.068370 +v 0.000771 -0.099353 -0.067857 +v 0.008237 -0.096493 -0.069195 +v 0.009872 -0.094931 -0.069512 +v 0.011751 -0.090861 -0.070048 +v 0.011083 -0.093041 -0.069801 +v 0.015328 -0.069183 -0.071858 +v 0.015481 -0.069103 -0.070309 +v 0.015325 -0.069185 -0.071887 +v 0.020205 -0.065082 -0.072556 +v 0.067722 -0.065083 -0.074261 +v 0.152244 -0.065083 -0.064805 +v 0.160827 -0.065091 -0.062012 +v 0.168641 -0.065094 -0.057404 +v 0.175279 -0.065093 -0.051195 +v 0.182745 -0.065083 -0.038467 +v 0.180396 -0.065088 -0.043711 +v 0.188977 -0.065083 -0.011634 +v 0.187788 -0.065083 -0.019949 +v 0.188018 -0.088857 -0.002896 +v 0.189156 -0.069081 -0.006726 +v 0.189164 -0.069081 -0.006727 +v 0.187882 -0.090802 -0.002246 +v 0.187718 -0.093111 -0.000597 +v 0.186821 -0.096597 0.003993 +v 0.187356 -0.095127 0.001527 +v 0.186557 -0.097043 0.005342 +v 0.186357 -0.097381 0.006362 +v 0.185956 -0.097701 0.009315 +v 0.182239 -0.097770 0.028558 +v 0.160682 -0.097736 0.058138 +v 0.178454 -0.097830 0.038885 +v 0.175840 -0.097842 0.043646 +v 0.172757 -0.097838 0.047926 +v 0.169116 -0.097818 0.051866 +v 0.165098 -0.097784 0.055261 +v 0.156032 -0.097676 0.060397 +v 0.178360 -0.104484 -0.011156 +v 0.077166 -0.117738 -0.043103 +v 0.115291 -0.112196 -0.050148 +v 0.121479 -0.111859 -0.048487 +v 0.142353 -0.112717 -0.030512 +v 0.146838 -0.109847 -0.038587 +v 0.142839 -0.115204 -0.021214 +v 0.147181 -0.111993 -0.028523 +v 0.144213 -0.114905 -0.020776 +v 0.177798 -0.104545 -0.013419 +v 0.177952 -0.104501 -0.013215 +v 0.124204 -0.108964 0.057666 +v 0.125690 -0.110774 0.050488 +v 0.137916 -0.107425 0.055530 +v 0.066719 -0.111712 0.062187 +v 0.123881 -0.111714 0.047775 +v 0.115006 -0.112211 0.050219 +v 0.172896 -0.103691 0.034190 +v 0.171547 -0.103544 0.037379 +v 0.163430 -0.103811 0.047389 +v 0.155144 -0.104798 0.051995 +v -0.059439 -0.104467 0.004070 +v 0.002277 -0.115505 0.037832 +v 0.004709 -0.112196 0.050148 +v 0.000429 -0.119291 0.026603 +v -0.003439 -0.114972 0.036489 +v -0.001479 -0.111859 0.048487 +v -0.030948 -0.105468 -0.053150 +v -0.004204 -0.108964 -0.057666 +v -0.005690 -0.110774 -0.050488 +v 0.053281 -0.111712 -0.062187 +v -0.003881 -0.111714 -0.047775 +v 0.004994 -0.112211 -0.050219 +v -0.056682 -0.104307 -0.020676 +v -0.054868 -0.104018 -0.028022 +v -0.048292 -0.103511 -0.042522 +v -0.043430 -0.103811 -0.047389 +v -0.038292 -0.104367 -0.050653 +v 0.154385 -0.108249 -0.038164 +v 0.171241 -0.103526 -0.037980 +v 0.175182 -0.104069 -0.026902 +v 0.153740 -0.105545 -0.050488 +v 0.103301 -0.110550 -0.060151 +v 0.131035 -0.108255 -0.056651 +v 0.157459 -0.104475 -0.051051 +v 0.154270 -0.104929 -0.052292 +v 0.162731 -0.103875 -0.047925 +v -0.056919 -0.104343 0.019507 +v -0.051241 -0.103526 0.037980 +v 0.016699 -0.110550 0.060151 +v -0.011035 -0.108255 0.056651 +v -0.034270 -0.104929 0.052292 +v -0.042731 -0.103875 0.047925 +v -0.047345 -0.103546 0.043662 +v -0.024547 -0.114832 -0.020668 +v -0.024225 -0.114945 -0.020671 +v -0.042899 -0.110650 -0.010950 +v -0.043088 -0.111147 -0.005806 +v -0.059472 -0.104511 -0.002800 +v -0.024560 -0.116041 -0.015932 +v -0.005892 -0.119905 -0.020671 +v -0.022057 -0.115367 -0.021448 +v 0.011730 -0.120764 -0.028274 +v 0.006159 -0.120077 -0.027514 +v 0.125892 -0.119905 -0.020671 +v 0.179472 -0.104511 0.002800 +v 0.179439 -0.104467 0.004070 +v 0.175759 -0.105923 0.006554 +v 0.069416 -0.124986 0.027668 +v -0.024987 -0.117433 0.004619 +v -0.025024 -0.117555 -0.000586 +v -0.024965 -0.117361 -0.005806 +v 0.144987 -0.117433 0.004619 +v 0.144965 -0.117361 -0.005806 +v -0.006213 -0.121267 0.014643 +v -0.006488 -0.122438 0.004619 +v 0.126213 -0.121267 0.014643 +v 0.126488 -0.122438 0.004619 +v 0.126471 -0.122364 -0.005806 +v 0.126155 -0.121020 -0.015932 +v 0.012668 -0.124004 0.019311 +v 0.012498 -0.125024 0.014643 +v 0.012300 -0.126210 0.004619 +v 0.012312 -0.126136 -0.005806 +v 0.012539 -0.124774 -0.015932 +v 0.107502 -0.125024 0.014643 +v 0.107700 -0.126210 0.004619 +v 0.107688 -0.126136 -0.005806 +v 0.031518 -0.126509 0.019311 +v 0.031645 -0.125233 0.023668 +v 0.050458 -0.128797 0.014643 +v 0.050418 -0.130000 0.004619 +v 0.050421 -0.129924 -0.005806 +v 0.050466 -0.128545 -0.015932 +v 0.050551 -0.125986 -0.025097 +v 0.069466 -0.126483 0.023668 +v 0.069508 -0.127764 0.019311 +v 0.069582 -0.130000 0.004619 +v 0.069579 -0.129924 -0.005806 +v 0.069562 -0.129393 -0.010950 +v 0.069534 -0.128545 -0.015932 +v 0.088482 -0.126509 0.019311 +v 0.088584 -0.127538 0.014643 +v 0.088703 -0.128735 0.004619 +v 0.088696 -0.128660 -0.005806 +v 0.088643 -0.128131 -0.010950 +v 0.088559 -0.127286 -0.015932 +v -0.050678 -0.071331 0.055258 +v -0.057698 -0.071243 0.047429 +v -0.062534 -0.070983 0.038095 +v -0.056817 -0.091591 0.045973 +v -0.056856 -0.091590 0.045921 +v -0.059315 -0.091589 0.041783 +v -0.060892 -0.091637 0.038357 +v -0.047453 -0.091978 0.055777 +v -0.051134 -0.091778 0.052673 +v -0.053906 -0.091664 0.049770 +v -0.043401 -0.092247 0.058447 +v -0.030771 -0.093352 0.063188 +v -0.035499 -0.092896 0.061960 +v -0.040020 -0.092506 0.060196 +v 0.066755 -0.099534 0.071874 +v 0.053369 -0.065417 0.074261 +v 0.054813 -0.066273 0.074234 +v 0.055892 -0.067557 0.074175 +v 0.016517 -0.098361 0.069917 +v 0.112678 -0.097760 0.068980 +v 0.104872 -0.098233 0.069727 +v 0.097585 -0.098676 0.070425 +v -0.064705 -0.067272 0.032235 +v -0.064474 -0.066174 0.033193 +v -0.064431 -0.066088 0.033343 +v -0.064068 -0.065363 0.034606 +v -0.064736 -0.067422 0.032104 +v 0.060000 -0.099562 -0.071923 +v 0.016938 -0.066312 -0.072204 +v 0.018360 -0.065438 -0.072384 +v 0.019994 -0.065088 -0.072551 +v 0.015887 -0.067609 -0.072031 +v 0.150771 -0.093352 -0.063188 +v 0.103483 -0.098361 -0.069917 +v 0.053245 -0.099534 -0.071874 +v 0.170678 -0.071331 -0.055258 +v 0.176817 -0.091591 -0.045973 +v 0.176856 -0.091590 -0.045921 +v 0.182534 -0.070983 -0.038095 +v 0.179315 -0.091589 -0.041783 +v 0.180892 -0.091637 -0.038357 +v 0.167453 -0.091978 -0.055777 +v 0.171134 -0.091778 -0.052673 +v 0.177698 -0.071243 -0.047429 +v 0.173906 -0.091664 -0.049770 +v 0.163401 -0.092247 -0.058447 +v 0.155499 -0.092896 -0.061960 +v 0.160020 -0.092506 -0.060196 +v 0.187134 -0.092540 -0.011778 +v 0.189202 -0.066174 -0.008518 +v 0.189214 -0.067422 -0.007398 +v 0.189123 -0.065363 -0.009986 +v 0.189195 -0.066099 -0.008654 +v 0.185795 -0.092331 -0.020805 +v 0.183992 -0.092055 -0.028691 +v 0.163415 -0.108928 0.019883 +v 0.155558 -0.110552 0.024488 +v 0.125706 -0.114743 0.035903 +v 0.117440 -0.115530 0.037894 +v 0.053204 -0.117915 -0.043493 +v 0.020616 -0.116833 -0.041035 +v 0.138369 -0.104794 0.060363 +v 0.138384 -0.100519 0.063858 +v 0.066777 -0.104779 0.070355 +v 0.066764 -0.109052 0.066956 +v 0.097663 -0.108209 0.065465 +v 0.097723 -0.103931 0.068886 +v 0.151312 -0.098481 0.061371 +v -0.031360 -0.098591 0.061523 +v 0.016349 -0.103620 0.068371 +v 0.016413 -0.107899 0.064942 +v 0.175926 -0.100406 0.039398 +v 0.172056 -0.100393 0.045521 +v 0.166297 -0.100721 0.051349 +v 0.160199 -0.101309 0.055307 +v 0.156453 -0.101762 0.056966 +v 0.153605 -0.102149 0.057902 +v 0.177113 -0.100976 0.035483 +v -0.035765 -0.098060 0.060303 +v -0.060205 -0.096733 0.036291 +v -0.057161 -0.100931 0.035496 +v -0.059520 -0.096674 0.038062 +v -0.055201 -0.100772 0.039937 +v -0.058020 -0.096603 0.041265 +v -0.055699 -0.096591 0.045137 +v -0.052929 -0.096664 0.048744 +v -0.050638 -0.100813 0.046611 +v -0.046899 -0.097010 0.054396 +v -0.041880 -0.101489 0.053907 +v -0.045248 -0.101168 0.051652 +v -0.043122 -0.097316 0.056927 +v -0.035334 -0.102280 0.056912 +v 0.179147 -0.101302 0.029082 +v -0.062598 -0.097108 0.028555 +v -0.061307 -0.101580 0.020252 +v 0.183754 -0.101250 0.006295 +v 0.183863 -0.101190 0.004081 +v 0.186407 -0.097580 0.004019 +v -0.062580 -0.102514 0.004093 +v 0.183575 -0.101690 0.002814 +v 0.186407 -0.097580 -0.004019 +v 0.183540 -0.101648 -0.004089 +v -0.062614 -0.102557 -0.002816 +v 0.185774 -0.097536 -0.011762 +v 0.182367 -0.101736 -0.013719 +v 0.180205 -0.096733 -0.036291 +v 0.181307 -0.101580 -0.020252 +v 0.184409 -0.097382 -0.020706 +v 0.182598 -0.097108 -0.028555 +v 0.177161 -0.100931 -0.035496 +v -0.058138 -0.102156 -0.028843 +v -0.059994 -0.102444 -0.021281 +v -0.056668 -0.101378 -0.035353 +v 0.155765 -0.098060 -0.060303 +v 0.179520 -0.096674 -0.038062 +v 0.175201 -0.100772 -0.039937 +v 0.178020 -0.096604 -0.041265 +v 0.175699 -0.096591 -0.045137 +v 0.172929 -0.096664 -0.048744 +v 0.170638 -0.100813 -0.046611 +v 0.166899 -0.097010 -0.054396 +v 0.161880 -0.101489 -0.053907 +v 0.165248 -0.101168 -0.051652 +v 0.163122 -0.097316 -0.056926 +v 0.155334 -0.102280 -0.056912 +v 0.151360 -0.098591 -0.061523 +v -0.033482 -0.102971 -0.056913 +v -0.051348 -0.101216 -0.044952 +v -0.045768 -0.101542 -0.050591 +v -0.043308 -0.101762 -0.052394 +v -0.039863 -0.102129 -0.054414 +v -0.031423 -0.102849 -0.057996 +v 0.103651 -0.103620 -0.068371 +v 0.103587 -0.107899 -0.064942 +v 0.007104 -0.103023 -0.067419 +v -0.004658 -0.102042 -0.065946 +v 0.053236 -0.109052 -0.066956 +v 0.053223 -0.104779 -0.070355 +v -0.004603 -0.106323 -0.062482 +v 0.015522 -0.068895 -0.070325 +v 0.015584 -0.068741 -0.070340 +v 0.189160 -0.067065 -0.007724 +v 0.053792 -0.065600 0.074219 +v 0.055551 -0.067047 0.074159 +v 0.018020 -0.065670 -0.072282 +v 0.016232 -0.067079 -0.072058 +v -0.064793 -0.067990 0.031799 +v -0.064574 -0.066913 0.032537 +v 0.144829 -0.097503 0.062983 +v 0.119984 -0.097146 0.067502 +v 0.123881 -0.097195 0.066879 +v 0.104540 -0.097146 0.069325 +v 0.096604 -0.097146 0.069905 +v 0.080461 -0.097146 0.071085 +v 0.072224 -0.097123 0.071388 +v 0.069021 -0.096679 0.071502 +v 0.066325 -0.095798 0.071622 +v 0.063992 -0.094512 0.071755 +v 0.060136 -0.088937 0.072214 +v 0.060829 -0.091009 0.072053 +v 0.062182 -0.092944 0.071895 +v 0.056535 -0.069366 0.073464 +v 0.056534 -0.069368 0.073499 +v 0.051662 -0.065357 0.073633 +v 0.051662 -0.065358 0.073653 +v -0.031467 -0.065358 0.064288 +v -0.039979 -0.065365 0.061518 +v -0.047729 -0.065369 0.056947 +v -0.054313 -0.065368 0.050789 +v -0.061718 -0.065358 0.038166 +v -0.059388 -0.065363 0.043366 +v -0.062523 -0.065358 0.035897 +v -0.063782 -0.069030 0.031264 +v -0.063790 -0.069030 0.031266 +v -0.063740 -0.092230 0.025349 +v -0.063686 -0.093573 0.024589 +v -0.063641 -0.094692 0.023957 +v -0.063332 -0.096794 0.022040 +v -0.063216 -0.097363 0.021191 +v -0.063021 -0.098328 0.019751 +v -0.062993 -0.099892 0.013792 +v -0.062865 -0.099362 0.017022 +v -0.064054 -0.099918 0.002418 +v -0.063987 -0.099922 -0.002763 +v -0.063970 -0.099923 -0.004021 +v -0.061645 -0.099980 -0.020756 +v -0.057002 -0.100059 -0.035424 +v -0.051280 -0.100082 -0.045398 +v -0.054255 -0.100082 -0.040947 +v -0.047815 -0.100065 -0.049446 +v -0.039715 -0.099982 -0.056022 +v -0.043949 -0.100031 -0.052996 +v -0.030660 -0.099851 -0.060229 +v -0.035242 -0.099921 -0.058443 +v -0.022817 -0.099700 -0.062502 +v 0.006778 -0.097693 -0.068288 +v 0.004120 -0.098834 -0.067796 +v 0.001277 -0.099346 -0.067287 +v 0.008683 -0.096510 -0.068614 +v 0.010304 -0.094961 -0.068928 +v 0.012168 -0.090924 -0.069460 +v 0.011505 -0.093086 -0.069215 +v 0.015715 -0.069424 -0.071256 +v 0.015712 -0.069426 -0.071284 +v 0.020553 -0.065357 -0.071947 +v 0.067679 -0.065358 -0.073638 +v 0.151509 -0.065358 -0.064260 +v 0.160022 -0.065365 -0.061490 +v 0.167771 -0.065369 -0.056920 +v 0.174355 -0.065368 -0.050762 +v 0.181760 -0.065358 -0.038139 +v 0.179430 -0.065363 -0.043339 +v 0.187941 -0.065358 -0.011525 +v 0.186761 -0.065358 -0.019772 +v 0.186989 -0.088937 -0.002859 +v 0.188119 -0.069323 -0.006658 +v 0.188127 -0.069323 -0.006658 +v 0.186855 -0.090866 -0.002214 +v 0.186692 -0.093156 -0.000578 +v 0.185803 -0.096613 0.003974 +v 0.186333 -0.095156 0.001528 +v 0.185540 -0.097056 0.005312 +v 0.185342 -0.097391 0.006323 +v 0.184945 -0.097709 0.009252 +v 0.181258 -0.097777 0.028337 +v 0.159878 -0.097743 0.057675 +v 0.177504 -0.097837 0.038580 +v 0.174912 -0.097848 0.043301 +v 0.171854 -0.097845 0.047547 +v 0.168243 -0.097825 0.051454 +v 0.164257 -0.097791 0.054822 +v 0.155265 -0.097684 0.059916 +v 0.177410 -0.104436 -0.011051 +v 0.077046 -0.117581 -0.042736 +v 0.114859 -0.112085 -0.049723 +v 0.120996 -0.111750 -0.048076 +v 0.141699 -0.112601 -0.030249 +v 0.146147 -0.109755 -0.038257 +v 0.142181 -0.115068 -0.021027 +v 0.146487 -0.111884 -0.028276 +v 0.143544 -0.114772 -0.020592 +v 0.176853 -0.104496 -0.013295 +v 0.177006 -0.104452 -0.013093 +v 0.123698 -0.108879 0.057207 +v 0.125173 -0.110674 0.050088 +v 0.137299 -0.107353 0.055089 +v 0.066685 -0.111604 0.061691 +v 0.123378 -0.111607 0.047397 +v 0.114576 -0.112099 0.049820 +v 0.171992 -0.103650 0.033923 +v 0.170654 -0.103503 0.037087 +v 0.162604 -0.103768 0.047014 +v 0.154385 -0.104747 0.051582 +v -0.058439 -0.104419 0.004050 +v 0.002771 -0.115367 0.037536 +v 0.005184 -0.112085 0.049750 +v 0.000938 -0.119121 0.026399 +v -0.002898 -0.114838 0.036204 +v -0.000954 -0.111750 0.048103 +v -0.030181 -0.105412 -0.052700 +v -0.003656 -0.108879 -0.057180 +v -0.005131 -0.110674 -0.050061 +v 0.053358 -0.111604 -0.061664 +v -0.003336 -0.111607 -0.047370 +v 0.005466 -0.112099 -0.049793 +v -0.055705 -0.104260 -0.020493 +v -0.053905 -0.103974 -0.027779 +v -0.047383 -0.103471 -0.042160 +v -0.042561 -0.103768 -0.046987 +v -0.037465 -0.104319 -0.050224 +v 0.153632 -0.108170 -0.037838 +v 0.170350 -0.103486 -0.037655 +v 0.174259 -0.104024 -0.026668 +v 0.152993 -0.105488 -0.050061 +v 0.102967 -0.110452 -0.059644 +v 0.130474 -0.108176 -0.056173 +v 0.156681 -0.104426 -0.050619 +v 0.153519 -0.104877 -0.051850 +v 0.161910 -0.103831 -0.047519 +v -0.055939 -0.104296 0.019361 +v -0.050308 -0.103486 0.037682 +v 0.017075 -0.110452 0.059671 +v -0.010432 -0.108176 0.056200 +v -0.033476 -0.104877 0.051877 +v -0.041868 -0.103831 0.047546 +v -0.046444 -0.103505 0.043317 +v -0.023833 -0.114699 -0.020485 +v -0.023513 -0.114811 -0.020488 +v -0.042034 -0.110552 -0.010847 +v -0.042222 -0.111044 -0.005744 +v -0.058471 -0.104462 -0.002764 +v -0.023846 -0.115898 -0.015788 +v -0.005331 -0.119731 -0.020488 +v -0.021364 -0.115230 -0.021259 +v 0.012147 -0.120583 -0.028029 +v 0.006621 -0.119901 -0.027275 +v 0.125373 -0.119731 -0.020488 +v 0.178513 -0.104462 0.002791 +v 0.178481 -0.104419 0.004050 +v 0.174831 -0.105863 0.006514 +v 0.069360 -0.124770 0.027455 +v -0.024269 -0.117278 0.004595 +v -0.024306 -0.117399 -0.000568 +v -0.024247 -0.117207 -0.005744 +v 0.144311 -0.117278 0.004595 +v 0.144289 -0.117207 -0.005744 +v -0.005649 -0.121081 0.014537 +v -0.005922 -0.122242 0.004595 +v 0.125691 -0.121081 0.014537 +v 0.125964 -0.122242 0.004595 +v 0.125947 -0.122169 -0.005744 +v 0.125634 -0.120837 -0.015788 +v 0.013077 -0.123796 0.019166 +v 0.012908 -0.124807 0.014537 +v 0.012712 -0.125984 0.004595 +v 0.012724 -0.125910 -0.005744 +v 0.012949 -0.124560 -0.015788 +v 0.107134 -0.124807 0.014537 +v 0.107330 -0.125984 0.004595 +v 0.107318 -0.125910 -0.005744 +v 0.031772 -0.126280 0.019166 +v 0.031898 -0.125015 0.023487 +v 0.050557 -0.128550 0.014537 +v 0.050518 -0.129742 0.004595 +v 0.050520 -0.129668 -0.005744 +v 0.050566 -0.128299 -0.015788 +v 0.050649 -0.125762 -0.024877 +v 0.069409 -0.126254 0.023487 +v 0.069451 -0.127525 0.019166 +v 0.069524 -0.129742 0.004595 +v 0.069522 -0.129668 -0.005744 +v 0.069504 -0.129141 -0.010847 +v 0.069477 -0.128299 -0.015788 +v 0.088270 -0.126280 0.019166 +v 0.088371 -0.127300 0.014537 +v 0.088489 -0.128488 0.004595 +v 0.088482 -0.128413 -0.005744 +v 0.088430 -0.127889 -0.010847 +v 0.088346 -0.127051 -0.015788 +v -0.049750 -0.071555 0.054819 +v -0.056712 -0.071467 0.047054 +v -0.061508 -0.071209 0.037796 +v -0.055838 -0.091649 0.045609 +v -0.055877 -0.091648 0.045558 +v -0.058316 -0.091646 0.041454 +v -0.059880 -0.091694 0.038056 +v -0.046551 -0.092032 0.055333 +v -0.050202 -0.091834 0.052255 +v -0.052951 -0.091720 0.049376 +v -0.042532 -0.092299 0.057982 +v -0.030006 -0.093395 0.062684 +v -0.034695 -0.092942 0.061465 +v -0.039179 -0.092556 0.059716 +v 0.066720 -0.099527 0.071299 +v 0.053444 -0.065688 0.073665 +v 0.054876 -0.066538 0.073639 +v 0.055947 -0.067812 0.073581 +v 0.016894 -0.098363 0.069358 +v 0.112267 -0.097767 0.068428 +v 0.104525 -0.098236 0.069169 +v 0.097298 -0.098675 0.069861 +v -0.063661 -0.067529 0.031985 +v -0.063432 -0.066439 0.032935 +v -0.063390 -0.066354 0.033083 +v -0.063030 -0.065636 0.034336 +v -0.063693 -0.067678 0.031855 +v 0.060021 -0.099554 -0.071319 +v 0.017312 -0.066576 -0.071598 +v 0.018723 -0.065710 -0.071777 +v 0.020343 -0.065362 -0.071943 +v 0.016270 -0.067863 -0.071427 +v 0.150048 -0.093395 -0.062656 +v 0.103148 -0.098363 -0.069331 +v 0.053322 -0.099527 -0.071271 +v 0.169792 -0.071555 -0.054792 +v 0.175880 -0.091649 -0.045582 +v 0.175919 -0.091648 -0.045531 +v 0.181550 -0.071209 -0.037769 +v 0.178358 -0.091646 -0.041427 +v 0.179922 -0.091694 -0.038029 +v 0.166594 -0.092032 -0.055306 +v 0.170244 -0.091834 -0.052227 +v 0.176755 -0.071467 -0.047027 +v 0.172993 -0.091720 -0.049348 +v 0.162575 -0.092299 -0.057955 +v 0.154737 -0.092942 -0.061438 +v 0.159221 -0.092556 -0.059689 +v 0.186113 -0.092589 -0.011668 +v 0.188164 -0.066439 -0.008435 +v 0.188176 -0.067678 -0.007323 +v 0.188085 -0.065636 -0.009890 +v 0.188157 -0.066365 -0.008569 +v 0.184785 -0.092382 -0.020621 +v 0.182997 -0.092109 -0.028442 +v 0.162588 -0.108843 0.019734 +v 0.154795 -0.110454 0.024301 +v 0.125189 -0.114611 0.035623 +v 0.116990 -0.115391 0.037597 +v 0.053281 -0.117757 -0.043123 +v 0.020960 -0.116684 -0.040685 +v 0.137747 -0.104743 0.059882 +v 0.137763 -0.100503 0.063348 +v 0.066743 -0.104728 0.069792 +v 0.066730 -0.108966 0.066421 +v 0.097375 -0.108130 0.064942 +v 0.097435 -0.103887 0.068335 +v 0.150585 -0.098482 0.060881 +v -0.030590 -0.098591 0.061032 +v 0.016728 -0.103579 0.067824 +v 0.016792 -0.107823 0.064424 +v 0.174997 -0.100391 0.039089 +v 0.171158 -0.100378 0.045161 +v 0.165447 -0.100704 0.050942 +v 0.159399 -0.101287 0.054867 +v 0.155684 -0.101736 0.056512 +v 0.152858 -0.102120 0.057441 +v 0.176174 -0.100956 0.035205 +v -0.034959 -0.098065 0.059822 +v -0.059199 -0.096749 0.036007 +v -0.056179 -0.100912 0.035219 +v -0.058519 -0.096689 0.037764 +v -0.054235 -0.100754 0.039624 +v -0.057032 -0.096620 0.040941 +v -0.054730 -0.096607 0.044781 +v -0.051982 -0.096680 0.048358 +v -0.049710 -0.100795 0.046243 +v -0.046001 -0.097023 0.053963 +v -0.041024 -0.101465 0.053479 +v -0.044364 -0.101147 0.051242 +v -0.042256 -0.097326 0.056473 +v -0.034531 -0.102250 0.056459 +v 0.178192 -0.101280 0.028858 +v -0.061572 -0.097121 0.028335 +v -0.060291 -0.101555 0.020100 +v 0.182761 -0.101228 0.006257 +v 0.182869 -0.101169 0.004061 +v 0.185392 -0.097588 0.004000 +v -0.061554 -0.102482 0.004073 +v 0.182583 -0.101665 0.002804 +v 0.185392 -0.097588 -0.003973 +v 0.182549 -0.101623 -0.004042 +v -0.061588 -0.102524 -0.002780 +v 0.184764 -0.097544 -0.011652 +v 0.181385 -0.101710 -0.013593 +v 0.179241 -0.096749 -0.035980 +v 0.180333 -0.101555 -0.020072 +v 0.183410 -0.097392 -0.020522 +v 0.181614 -0.097121 -0.028308 +v 0.176221 -0.100912 -0.035192 +v -0.057148 -0.102127 -0.028593 +v -0.058989 -0.102412 -0.021093 +v -0.055691 -0.101355 -0.035050 +v 0.155001 -0.098065 -0.059795 +v 0.178561 -0.096689 -0.037737 +v 0.174277 -0.100754 -0.039596 +v 0.177074 -0.096620 -0.040914 +v 0.174772 -0.096607 -0.044754 +v 0.172024 -0.096680 -0.048331 +v 0.169752 -0.100795 -0.046215 +v 0.166043 -0.097023 -0.053936 +v 0.161066 -0.101465 -0.053452 +v 0.164406 -0.101147 -0.051215 +v 0.162298 -0.097326 -0.056446 +v 0.154573 -0.102250 -0.056432 +v 0.150633 -0.098591 -0.061005 +v -0.032695 -0.102935 -0.056433 +v -0.050414 -0.101194 -0.044570 +v -0.044880 -0.101517 -0.050163 +v -0.042440 -0.101736 -0.051950 +v -0.039024 -0.102100 -0.053955 +v -0.030652 -0.102814 -0.057506 +v 0.103314 -0.103579 -0.067797 +v 0.103250 -0.107823 -0.064396 +v 0.007559 -0.102986 -0.066853 +v -0.004106 -0.102014 -0.065392 +v 0.053312 -0.108966 -0.066393 +v 0.053300 -0.104728 -0.069765 +v -0.004052 -0.106259 -0.061956 +v 0.188122 -0.067323 -0.007647 +v 0.053864 -0.065870 0.073625 +v 0.055609 -0.067306 0.073564 +v 0.018385 -0.065939 -0.071676 +v 0.016612 -0.067338 -0.071454 +v -0.063749 -0.068241 0.031552 +v -0.063531 -0.067172 0.032284 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vn -0.0104 -0.0660 -0.9978 +vn -0.0094 -0.0591 -0.9982 +vn 0.0003 0.0096 -1.0000 +vn 0.0014 0.0170 -0.9999 +vn -0.0000 1.0000 0.0000 +vn 0.7466 0.1537 -0.6473 +vn 0.7906 0.0366 -0.6113 +vn 0.7734 0.0868 -0.6280 +vn 0.8042 -0.0097 -0.5943 +vn 0.0002 -0.0090 1.0000 +vn -0.0000 -0.0077 1.0000 +vn -0.0017 0.0039 1.0000 +vn -0.0019 0.0052 1.0000 +vn -0.0111 0.9999 0.0068 +vn 0.0040 1.0000 0.0012 +vn -0.0130 0.9964 0.0841 +vn -0.6510 -0.1032 -0.7520 +vn -0.4648 0.5920 -0.6584 +vn -0.2637 -0.6361 -0.7252 +vn -0.0556 0.7736 -0.6313 +vn -0.0380 0.9965 -0.0745 +vn 0.0355 0.9962 -0.0793 +vn 0.0811 -0.6974 -0.7121 +vn 0.3870 0.5649 -0.7288 +vn 0.6351 -0.5178 -0.5732 +vn 0.8799 0.3279 -0.3439 +vn 0.8747 0.3421 -0.3435 +vn 0.9697 -0.0454 -0.2401 +vn 0.9934 0.0565 -0.1003 +vn 0.9648 -0.1450 0.2194 +vn 0.9951 -0.0431 0.0890 +vn 0.9253 -0.2204 0.3088 +vn 0.7916 0.5135 0.3311 +vn 0.6127 -0.5830 0.5336 +vn 0.5036 0.6188 0.6029 +vn 0.3541 -0.5646 0.7455 +vn 0.1676 0.6880 0.7061 +vn 0.0243 -0.6687 0.7431 +vn -0.2583 0.5140 0.8180 +vn -0.5713 -0.0302 0.8202 +vn -0.6149 -0.1033 -0.7818 +vn -0.5127 0.4581 -0.7262 +vn -0.1933 -0.4026 -0.8947 +vn -0.1058 0.4946 -0.8627 +vn 0.1279 -0.4861 -0.8645 +vn 0.2464 0.6318 -0.7349 +vn 0.3838 -0.6903 -0.6134 +vn 0.5202 0.6902 -0.5029 +vn 0.5968 -0.7340 -0.3240 +vn 0.7762 0.5676 -0.2744 +vn 0.9341 -0.3520 0.0588 +vn 0.9674 -0.2478 0.0528 +vn 0.7368 -0.6720 0.0740 +vn 0.7287 -0.6808 0.0743 +vn 0.6971 0.6546 0.2924 +vn 0.5462 -0.6925 0.4712 +vn 0.4268 -0.1864 0.8849 +vn 0.0267 0.2061 0.9782 +vn 0.0270 0.2111 0.9771 +vn 0.0156 0.0239 0.9996 +vn 0.0148 0.0111 0.9998 +vn -0.4347 -0.2966 0.8503 +vn -0.4376 -0.2826 0.8536 +vn -0.4796 0.1078 0.8708 +vn -0.4798 0.1268 0.8682 +vn -0.6510 -0.0995 -0.7526 +vn -0.2637 -0.6361 -0.7251 +vn 0.3872 0.5576 -0.7343 +vn 0.6323 -0.5650 -0.5301 +vn 0.7010 0.6687 -0.2478 +vn 0.8407 -0.5205 -0.1497 +vn 0.9074 0.4141 0.0716 +vn 0.9018 -0.1777 0.3938 +vn 0.8711 -0.0899 0.4829 +vn 0.7668 0.0894 0.6357 +vn 0.6950 0.1776 0.6967 +vn 0.3076 -0.6392 0.7048 +vn 0.2825 -0.6579 0.6981 +vn 0.3002 -0.6449 0.7029 +vn 0.2750 -0.6634 0.6959 +vn 0.0241 0.4919 0.8703 +vn -0.0175 -0.0110 0.9998 +vn -0.6538 -0.0316 -0.7560 +vn -0.3670 0.2335 -0.9004 +vn 0.0842 -0.0208 -0.9962 +vn 0.0833 -0.0088 -0.9965 +vn 0.2108 -0.0789 -0.9743 +vn 0.3655 0.0413 -0.9299 +vn 0.4712 0.1334 -0.8719 +vn 0.4886 -0.3891 -0.7809 +vn 0.6521 0.4803 -0.5866 +vn 0.6647 -0.6542 -0.3609 +vn 0.8256 0.4829 -0.2919 +vn 0.9808 -0.1879 0.0524 +vn 0.9782 -0.2005 0.0534 +vn 0.9860 -0.0585 0.1560 +vn 0.9580 0.0305 0.2850 +vn 0.8074 -0.1084 0.5799 +vn 0.8715 -0.0418 0.4886 +vn 0.7314 -0.1775 0.6585 +vn 0.6239 0.4319 0.6513 +vn 0.3037 -0.5997 0.7404 +vn 0.3041 -0.5792 0.7563 +vn 0.2963 -0.2533 0.9209 +vn 0.0906 -0.0840 0.9923 +vn 0.2583 0.0484 0.9648 +vn -0.0695 0.3121 0.9475 +vn -0.0715 0.3320 0.9406 +vn -0.4222 -0.3732 0.8261 +vn -0.4273 -0.3557 0.8312 +vn -0.4976 0.0683 0.8647 +vn -0.4992 0.1000 0.8607 +vn -0.0881 0.6903 -0.7181 +vn 0.0877 -0.6318 -0.7701 +vn 0.2464 0.6318 -0.7350 +vn 0.4122 -0.5650 -0.7147 +vn 0.6359 0.4667 -0.6147 +vn 0.6844 -0.4883 -0.5414 +vn 0.6281 -0.7751 -0.0687 +vn 0.6483 -0.7589 -0.0617 +vn 0.8436 -0.5366 0.0208 +vn 0.8638 -0.5029 0.0317 +vn 0.9018 -0.1778 0.3938 +vn 0.8711 -0.0897 0.4829 +vn 0.7667 0.0897 0.6356 +vn 0.6950 0.1779 0.6967 +vn 0.4193 -0.1775 0.8903 +vn 0.0267 0.2058 0.9782 +vn -0.4346 -0.2971 0.8502 +vn -0.4376 -0.2829 0.8535 +vn 0.0880 -0.8055 -0.5861 +vn 0.2719 0.8310 -0.4853 +vn 0.4513 -0.7234 -0.5225 +vn 0.7311 0.5775 -0.3633 +vn 0.9155 0.0253 -0.4015 +vn 0.9788 -0.1657 -0.1205 +vn 0.9566 -0.0640 -0.2844 +vn 0.9795 0.1459 0.1391 +vn 0.9564 0.0377 0.2896 +vn 0.7913 -0.1557 0.5913 +vn 0.8819 -0.0352 0.4702 +vn 0.7131 -0.2308 0.6619 +vn 0.3366 -0.5498 0.7644 +vn 0.2938 -0.6119 0.7344 +vn 0.3311 -0.5582 0.7608 +vn 0.2881 -0.6195 0.7302 +vn -0.0172 0.1917 0.9813 +vn -0.0209 0.2472 0.9687 +vn -0.0350 0.4576 0.8885 +vn -0.0354 0.4641 0.8850 +vn -0.4066 -0.4493 0.7955 +vn -0.4978 0.1246 0.8583 +vn -0.8677 0.0331 -0.4959 +vn -0.6993 0.0144 -0.7147 +vn -0.8160 0.0329 -0.5772 +vn -0.5578 0.0928 -0.8248 +vn -0.3830 -0.1006 -0.9183 +vn -0.1738 0.0688 -0.9824 +vn 0.0209 -0.0924 -0.9955 +vn 0.3114 -0.0249 -0.9499 +vn 0.2913 0.0309 -0.9561 +vn 0.5173 -0.3280 -0.7905 +vn 0.5192 -0.3650 -0.7728 +vn 0.7343 0.3613 -0.5747 +vn 0.8769 -0.3606 -0.3177 +vn 0.9170 0.3765 -0.1314 +vn 0.9432 -0.2434 0.2263 +vn 0.9415 -0.1920 0.2768 +vn 0.9469 -0.2196 0.2350 +vn 0.9086 0.1947 0.3695 +vn 0.8947 0.2402 0.3765 +vn 0.7299 -0.2010 0.6534 +vn 0.7184 -0.1309 0.6832 +vn 0.6022 0.1445 0.7852 +vn 0.4308 -0.0407 0.9015 +vn 0.2660 0.0039 0.9640 +vn 0.0746 -0.1575 0.9847 +vn -0.2059 0.0131 0.9785 +vn -0.2811 0.0380 0.9589 +vn -0.4492 -0.0903 0.8889 +vn -0.4506 -0.0997 0.8871 +vn -0.7461 0.4689 -0.4727 +vn -0.9854 0.0022 -0.1703 +vn -0.9539 0.0942 -0.2850 +vn -0.9310 0.0548 -0.3608 +vn -0.8807 -0.0215 -0.4731 +vn -0.8711 -0.0146 -0.4909 +vn -0.7325 0.0035 0.6808 +vn 0.5423 0.0618 0.8379 +vn 0.1794 -0.1732 0.9684 +vn -0.2028 0.1780 0.9629 +vn -0.2014 0.1904 0.9608 +vn -0.2282 -0.2052 0.9517 +vn -0.2285 -0.2173 0.9490 +vn -0.6022 0.2021 0.7723 +vn -0.5732 -0.5039 0.6462 +vn -0.7086 0.5535 0.4376 +vn -0.7347 -0.6208 0.2737 +vn -0.8215 0.5533 0.1378 +vn -0.8707 -0.4901 -0.0411 +vn -0.8437 0.4960 -0.2053 +vn -0.8217 -0.4626 -0.3329 +vn -0.6586 0.5519 -0.5114 +vn -0.6255 -0.4856 -0.6108 +vn -0.3480 0.4544 -0.8200 +vn -0.3486 0.4461 -0.8243 +vn -0.2601 0.6223 -0.7383 +vn -0.2300 0.6244 -0.7465 +vn -0.1587 0.3216 -0.9335 +vn -0.1542 0.2071 -0.9661 +vn 0.1988 -0.6019 -0.7734 +vn 0.5779 0.3046 -0.7571 +vn 0.6657 0.0289 0.7457 +vn 0.2582 -0.6981 0.6678 +vn 0.1659 0.5321 0.8303 +vn -0.1951 -0.3013 0.9334 +vn -0.1951 -0.3101 0.9305 +vn -0.1949 -0.2496 0.9485 +vn -0.1949 -0.2479 0.9490 +vn -0.6254 0.2205 0.7485 +vn -0.6229 0.2329 0.7468 +vn -0.6467 -0.2203 0.7302 +vn -0.6454 -0.2327 0.7275 +vn -0.9070 0.2052 0.3678 +vn -0.9042 0.2173 0.3677 +vn -0.9218 -0.1780 0.3444 +vn -0.9200 -0.1904 0.3427 +vn -0.9846 0.1712 -0.0361 +vn -0.9838 0.1758 -0.0356 +vn -0.9470 -0.1353 -0.2913 +vn -0.9881 -0.0375 -0.1491 +vn -0.8314 0.1487 -0.5355 +vn -0.7413 0.0545 -0.6690 +vn -0.6240 -0.2276 -0.7475 +vn -0.6229 -0.2329 -0.7468 +vn -0.2282 0.2052 -0.9517 +vn -0.2285 0.2178 -0.9489 +vn -0.2028 -0.1782 -0.9629 +vn -0.2014 -0.1909 -0.9607 +vn 0.1794 0.1732 -0.9684 +vn 0.5407 -0.1081 -0.8342 +vn 0.5868 -0.3230 0.7425 +vn 0.4596 0.5498 0.6975 +vn 0.1905 -0.2521 0.9488 +vn 0.1888 -0.2655 0.9454 +vn 0.1037 -0.1025 0.9893 +vn -0.0726 0.0678 0.9951 +vn -0.1706 0.1610 0.9721 +vn -0.2006 -0.6592 0.7247 +vn -0.2484 -0.6916 0.6782 +vn -0.2202 -0.6728 0.7063 +vn -0.2665 -0.7031 0.6593 +vn -0.6623 -0.1655 0.7307 +vn -0.7347 -0.0797 0.6737 +vn -0.8358 0.0770 0.5436 +vn -0.8726 0.1608 0.4611 +vn -0.8112 -0.4562 0.3657 +vn -0.7731 0.6280 0.0891 +vn -0.7260 -0.6868 -0.0351 +vn -0.7888 0.5117 -0.3405 +vn -0.7830 0.5231 -0.3365 +vn -0.7677 -0.1247 -0.6285 +vn -0.8523 -0.0333 -0.5220 +vn -0.6877 -0.2142 -0.6937 +vn -0.5624 0.5025 -0.6567 +vn -0.2504 -0.6669 -0.7018 +vn -0.2499 -0.6456 -0.7216 +vn -0.2267 -0.3379 -0.9135 +vn -0.2368 -0.2294 -0.9441 +vn -0.2375 -0.2249 -0.9450 +vn 0.1669 0.1609 -0.9728 +vn 0.2045 -0.5054 -0.8383 +vn 0.5783 0.3032 -0.7574 +vn 0.6539 -0.0716 0.7532 +vn 0.4603 0.5761 0.6755 +vn 0.2519 -0.6486 0.7183 +vn 0.0635 0.6023 0.7957 +vn -0.1782 -0.4989 0.8482 +vn -0.1781 -0.5227 0.8337 +vn -0.1782 -0.4667 0.8663 +vn -0.1782 -0.4645 0.8675 +vn -0.4250 0.3913 0.8163 +vn -0.6269 -0.3262 0.7076 +vn -0.6144 -0.3947 0.6831 +vn -0.7288 -0.0793 0.6801 +vn -0.8281 0.0262 0.5599 +vn -0.8493 -0.3604 0.3857 +vn -0.8435 -0.3794 0.3802 +vn -0.8346 0.5424 0.0962 +vn -0.7968 -0.6030 -0.0385 +vn -0.8297 0.4279 -0.3585 +vn -0.8245 0.4410 -0.3545 +vn -0.7597 -0.0945 -0.6433 +vn -0.8400 -0.0408 -0.5410 +vn -0.6367 0.2132 -0.7410 +vn -0.6328 0.2310 -0.7390 +vn -0.2011 -0.0266 -0.9792 +vn -0.1963 0.6451 -0.7384 +vn 0.0634 -0.6027 -0.7955 +vn 0.2519 0.6483 -0.7185 +vn 0.4602 -0.5759 -0.6757 +vn 0.6535 0.0787 -0.7528 +vn 0.8671 0.0249 0.4976 +vn 0.9639 0.0051 0.2664 +vn 0.9625 0.0056 0.2712 +vn 0.8054 0.0568 -0.5900 +vn 0.9357 0.0074 -0.3527 +vn 0.9361 0.0110 -0.3516 +vn 0.9372 0.0222 -0.3480 +vn 0.9375 0.0253 -0.3472 +vn 0.9459 0.0145 0.3243 +vn 0.9846 -0.0167 0.1740 +vn 0.9570 0.0133 0.2896 +vn 0.9390 0.0459 -0.3407 +vn 0.9412 0.1123 -0.3187 +vn 0.9410 0.1286 -0.3130 +vn 0.9496 -0.0172 -0.3130 +vn 0.9350 0.0769 -0.3463 +vn 0.9934 -0.1137 0.0144 +vn 0.9217 -0.0351 -0.3864 +vn 0.9494 0.0557 -0.3090 +vn 0.9950 0.0625 -0.0775 +vn 0.9807 0.1334 -0.1426 +vn 0.9594 0.0149 0.2818 +vn 0.9412 0.1126 -0.3186 +vn 0.9391 0.0473 -0.3402 +vn 0.9376 0.0273 -0.3465 +vn 0.7759 -0.0065 0.6308 +vn 0.6268 0.0216 0.7789 +vn 0.9546 0.0437 -0.2947 +vn 0.8691 -0.0199 0.4943 +vn 0.9523 0.0069 -0.3050 +vn 0.9549 0.0360 0.2948 +vn 0.9560 0.0288 0.2920 +vn 0.9987 0.0037 0.0502 +vn 0.9983 -0.0018 0.0583 +vn 0.9560 -0.0459 0.2896 +vn 0.9555 -0.0356 0.2928 +vn 0.9611 -0.0214 0.2754 +vn 0.8721 -0.1277 -0.4724 +vn 0.9395 -0.0037 0.3425 +vn 0.9386 -0.0004 0.3450 +vn 0.9383 0.0006 0.3458 +vn 0.9374 0.0039 0.3483 +vn 0.9414 -0.0590 0.3322 +vn 0.9335 -0.0969 0.3452 +vn 0.9482 -0.0171 0.3172 +vn 0.9504 0.0000 0.3109 +vn 0.9410 0.0230 -0.3378 +vn 0.9670 0.0098 -0.2544 +vn 0.9101 -0.0212 -0.4139 +vn 0.9412 0.0204 0.3374 +vn 0.9427 0.0362 0.3318 +vn 0.9376 -0.0093 0.3476 +vn 0.9344 -0.0311 0.3549 +vn 0.9547 0.0433 0.2945 +vn 0.9547 0.0432 0.2945 +vn 0.9561 -0.0459 0.2896 +vn 0.9548 -0.0344 0.2953 +vn 0.9527 -0.0178 0.3035 +vn 0.9516 -0.0103 0.3072 +vn 0.9554 0.0175 -0.2949 +vn 0.7127 0.0212 -0.7011 +vn 0.6081 0.0263 -0.7934 +vn 0.7717 0.0088 -0.6359 +vn 0.9620 -0.0285 0.2714 +vn -0.8481 -0.0385 -0.5284 +vn -0.5286 0.3973 -0.7502 +vn 0.3688 -0.3367 -0.8664 +vn 0.9217 0.3773 0.0904 +vn 0.8831 -0.1013 0.4581 +vn -0.4817 0.0598 0.8743 +vn -0.4861 0.0676 0.8713 +vn -0.4885 0.0718 0.8696 +vn -0.4925 0.0790 0.8667 +vn -0.1953 -0.0055 -0.9807 +vn -0.2888 -0.2728 -0.9177 +vn -0.3765 -0.1383 -0.9160 +vn -0.3318 0.0687 -0.9409 +vn 0.6429 0.3469 -0.6829 +vn 0.8388 -0.4093 0.3591 +vn 0.6820 0.1140 0.7224 +vn -0.8311 -0.1018 0.5468 +vn -0.8444 -0.0689 0.5312 +vn -0.8558 -0.0381 0.5159 +vn -0.8676 -0.0022 0.4972 +vn -0.7929 0.4126 -0.4484 +vn -0.1439 -0.5461 -0.8252 +vn 0.7457 0.4506 -0.4908 +vn 0.6563 -0.4682 0.5916 +vn 0.1260 0.3585 0.9250 +vn -0.8068 -0.3048 0.5061 +vn 0.5729 -0.4870 0.6593 +vn 0.4532 0.5105 0.7307 +vn 0.2736 -0.5622 0.7804 +vn 0.1657 0.5324 0.8301 +vn -0.1950 -0.3153 0.9287 +vn -0.2383 -0.6618 0.7108 +vn -0.2005 -0.3806 0.9027 +vn -0.2405 -0.6865 0.6862 +vn -0.5621 0.4050 0.7211 +vn -0.6289 -0.4053 0.6635 +vn -0.7347 -0.6207 0.2737 +vn -0.7973 -0.6001 -0.0639 +vn -0.8372 0.1781 -0.5172 +vn -0.8792 0.2567 -0.4015 +vn -0.7539 0.0691 -0.6533 +vn -0.6713 -0.0163 -0.7410 +vn -0.0795 -0.9854 -0.1507 +vn -0.2775 -0.6467 -0.7105 +vn 0.0057 -1.0000 -0.0067 +vn -0.1564 0.5052 -0.8487 +vn 0.1602 -0.2314 -0.9596 +vn 0.5419 -0.0935 -0.8352 +vn 0.8476 0.5301 -0.0240 +vn -0.8903 0.4340 -0.1381 +vn 0.0215 -0.3580 -0.9335 +vn 0.4072 0.2714 -0.8721 +vn 0.8778 -0.3642 0.3112 +vn 0.3898 0.6071 0.6925 +vn -0.5952 -0.6542 0.4668 +vn -0.9831 0.0618 -0.1725 +vn -0.0662 0.1317 -0.9891 +vn -0.1086 -0.0819 -0.9907 +vn -0.2742 -0.2985 -0.9142 +vn 0.3142 -0.4113 -0.8557 +vn 0.9288 0.3420 -0.1423 +vn 0.7183 -0.4604 0.5216 +vn -0.0698 0.4909 0.8684 +vn -0.7825 -0.5768 0.2346 +vn -0.7151 -0.5099 -0.4781 +vn -0.5169 -0.1266 -0.8466 +vn 0.8099 -0.2805 -0.5151 +vn 0.8475 -0.2005 -0.4915 +vn 0.8868 -0.0902 -0.4533 +vn 0.9068 -0.0099 -0.4214 +vn 0.2175 -0.0860 0.9723 +vn 0.2896 0.0445 0.9561 +vn 0.1230 -0.2428 0.9622 +vn 0.0640 -0.3335 0.9406 +vn -0.8623 0.4619 0.2076 +vn 0.1887 -0.2655 0.9454 +vn 0.1975 -0.1927 0.9612 +vn 0.1978 -0.1903 0.9616 +vn -0.2028 0.1785 0.9628 +vn -0.2014 0.1906 0.9608 +vn -0.6254 0.2204 0.7485 +vn -0.6229 0.2328 0.7468 +vn -0.6467 -0.2202 0.7302 +vn -0.9069 0.2056 0.3678 +vn -0.9042 0.2172 0.3677 +vn -0.9218 -0.1784 0.3442 +vn -0.9199 -0.1907 0.3427 +vn -0.9515 -0.1363 -0.2759 +vn -0.9890 -0.0336 -0.1440 +vn -0.9053 -0.2145 -0.3667 +vn -0.8401 0.3699 -0.3967 +vn -0.6401 -0.4076 -0.6512 +vn -0.3013 -0.5683 -0.7657 +vn -0.0122 0.6578 -0.7531 +vn 0.1296 -0.6049 -0.7857 +vn 0.3286 0.4291 -0.8414 +vn 0.4382 -0.6085 -0.6616 +vn 0.6268 0.2948 -0.7213 +vn -0.0903 -0.0235 0.9956 +vn -0.2267 -0.0634 0.9719 +vn -0.4073 0.1768 0.8960 +vn -0.4232 0.2320 0.8758 +vn -0.6069 -0.2498 0.7545 +vn -0.7726 0.3026 0.5581 +vn -0.8834 -0.2295 0.4085 +vn -0.9285 -0.1423 0.3430 +vn -0.9816 0.0267 0.1890 +vn -0.9938 -0.0198 -0.1095 +vn -0.9914 -0.0504 -0.1211 +vn -0.9116 0.0429 -0.4087 +vn -0.8518 0.0002 -0.5239 +vn -0.7358 0.0351 -0.6762 +vn -0.6103 -0.0496 -0.7906 +vn -0.4363 0.1183 -0.8920 +vn -0.2165 -0.0858 -0.9725 +vn -0.0712 -0.0283 -0.9971 +vn -0.8763 0.1144 -0.4681 +vn -0.2455 -0.5725 -0.7823 +vn 0.4579 0.5394 -0.7066 +vn 0.8050 -0.4931 0.3300 +vn 0.6510 0.1534 0.7434 +vn -0.6882 -0.1160 0.7162 +vn -0.6728 -0.0727 0.7363 +vn -0.7003 -0.1541 0.6970 +vn -0.7101 -0.1880 0.6785 +vn -0.9012 0.3561 -0.2469 +vn -0.8282 -0.1880 -0.5279 +vn 0.6625 0.0688 -0.7459 +vn 0.5932 0.1983 -0.7803 +vn 0.7325 -0.1101 -0.6718 +vn 0.7629 -0.2315 -0.6037 +vn 0.3919 0.3125 0.8653 +vn 0.0704 -0.3919 0.9173 +vn -0.4534 -0.5727 -0.6830 +vn 0.5606 0.6137 -0.5560 +vn 0.8084 -0.5796 0.1023 +vn 0.2694 0.4475 0.8528 +vn -0.5787 -0.3746 0.7244 +vn -0.8558 0.5164 -0.0294 +vn 0.8011 -0.0081 0.5985 +vn 0.8044 0.0036 0.5940 +vn 0.8024 -0.0035 0.5968 +vn 0.8057 0.0084 0.5922 +vn -0.0641 0.0261 0.9976 +vn 0.0530 0.0003 0.9986 +vn -0.0444 0.0218 0.9988 +vn 0.0756 -0.0047 0.9971 +vn 0.0018 0.0215 -0.9998 +vn 0.2388 -0.0260 -0.9707 +vn 0.2014 -0.0184 -0.9793 +vn -0.0370 0.0291 -0.9989 +vn 0.2002 -0.0179 0.9796 +vn 0.2300 -0.0065 0.9732 +vn 0.0035 -0.0765 0.9971 +vn 0.1229 -0.0107 -0.9924 +vn 0.1816 -0.0156 -0.9832 +vn 0.7222 0.2320 -0.6516 +vn 0.7081 0.1666 -0.6862 +vn 0.5969 -0.0365 -0.8015 +vn 0.4398 0.1059 -0.8918 +vn 0.2970 -0.1419 -0.9443 +vn 0.2680 -0.2059 -0.9412 +vn -0.0376 0.2199 -0.9748 +vn -0.0432 0.2014 -0.9786 +vn -0.2017 0.1351 -0.9701 +vn -0.5777 0.0186 -0.8161 +vn -0.6782 0.0375 -0.7340 +vn -0.7958 -0.0828 -0.5998 +vn -0.9034 0.0542 -0.4253 +vn -0.9632 -0.0641 -0.2609 +vn -0.9984 -0.0381 -0.0424 +vn -0.9999 -0.0088 0.0104 +vn -0.9539 0.0608 0.2938 +vn -0.8985 -0.0265 0.4383 +vn -0.6882 0.0314 0.7248 +vn -0.7376 0.0469 0.6736 +vn -0.4399 -0.0712 0.8952 +vn -0.3083 0.0444 0.9502 +vn -0.2306 0.1250 0.9650 +vn -0.3689 0.9002 0.2316 +vn 0.0581 -0.1585 0.9857 +vn 0.0462 -0.1925 0.9802 +vn 0.2584 0.0358 0.9654 +vn 0.3088 0.0647 0.9489 +vn 0.5601 -0.0055 0.8284 +vn 0.6010 -0.0186 0.7990 +vn 0.8596 0.0434 0.5091 +vn 0.8838 0.0060 -0.4679 +vn 0.9331 0.0074 -0.3596 +vn 0.9367 0.0467 -0.3471 +vn 0.9344 0.1174 -0.3363 +vn 0.9460 0.0657 0.3175 +vn 0.9368 0.0861 0.3390 +vn 0.9261 0.0543 0.3733 +vn 0.8831 -0.0221 0.4687 +vn 0.8866 -0.0206 -0.4620 +vn 0.8631 -0.0188 -0.5047 +vn -0.0000 1.0000 -0.0001 +vn 0.0772 0.0232 -0.9967 +vn 0.0860 0.0171 -0.9962 +vn 0.0805 0.0209 -0.9965 +vn 0.0717 0.0270 -0.9971 +vn -0.1704 0.1060 0.9796 +vn 0.0215 -0.0080 0.9997 +vn -0.0541 0.0369 0.9979 +vn 0.1368 -0.0770 0.9876 +vn -0.0000 -1.0000 -0.0000 +vn -0.0047 -0.9999 -0.0089 +vn -0.0592 -0.9921 -0.1109 +vn -0.0848 -0.9878 -0.1308 +vn -0.0065 -0.9999 -0.0098 +vn 0.6008 -0.1541 -0.7844 +vn 0.5980 -0.2148 -0.7722 +vn 0.3006 0.5231 -0.7975 +vn 0.1286 -0.6906 -0.7117 +vn -0.0679 0.6756 -0.7341 +vn -0.2582 -0.4201 -0.8700 +vn -0.4247 0.3367 -0.8404 +vn -0.4879 -0.6066 -0.6277 +vn -0.5847 0.6892 -0.4280 +vn -0.7053 -0.6187 -0.3462 +vn -0.1653 -0.9823 -0.0883 +vn -0.7640 -0.6450 0.0163 +vn -0.9301 0.3369 -0.1462 +vn -0.6795 0.6967 0.2301 +vn -0.5578 -0.7326 0.3900 +vn -0.7115 0.2611 0.6524 +vn -0.6394 0.1841 0.7465 +vn -0.5505 0.1189 0.8263 +vn -0.3856 -0.1813 0.9047 +vn -0.2551 0.0250 0.9666 +vn -0.2091 0.0952 0.9733 +vn -0.0385 -0.6108 0.7908 +vn 0.1269 0.6848 0.7176 +vn 0.2783 -0.8059 0.5226 +vn 0.5604 0.3059 0.7696 +vn 0.0119 -0.9999 0.0060 +vn -0.1215 -0.9657 -0.2296 +vn -0.0832 -0.9964 -0.0161 +vn -0.0942 -0.9952 -0.0251 +vn -0.0083 -1.0000 -0.0017 +vn -0.0300 -0.9993 0.0205 +vn 0.0257 -0.9945 0.1011 +vn -0.0600 -0.9980 -0.0219 +vn -0.0151 -0.9998 -0.0135 +vn 0.0375 -0.9936 -0.1070 +vn -0.0327 -0.9990 -0.0298 +vn 0.0026 -1.0000 0.0003 +vn -0.0491 -0.9908 -0.1262 +vn -0.0406 -0.9937 -0.1044 +vn 0.0262 -0.9946 -0.1009 +vn 0.0285 -0.9914 -0.1274 +vn 0.0304 -0.9903 -0.1359 +vn 0.0219 -0.9997 -0.0136 +vn -0.0089 -0.9567 -0.2910 +vn -0.0212 -0.9889 0.1470 +vn -0.0640 -0.9978 0.0154 +vn -0.0105 0.9999 -0.0134 +vn -0.0637 0.9945 -0.0834 +vn -0.0628 0.9949 0.0786 +vn 0.0156 0.9999 -0.0008 +vn 0.0224 0.9997 -0.0011 +vn 0.0388 0.9992 -0.0019 +vn -0.0731 0.5073 0.8587 +vn 0.0559 0.9880 -0.1439 +vn 0.0463 0.9918 -0.1190 +vn 0.0042 0.9999 -0.0107 +vn -0.1256 0.9712 -0.2027 +vn -0.0096 0.9998 -0.0157 +vn 0.5784 -0.2724 -0.7689 +vn 0.3236 0.5661 -0.7582 +vn 0.1546 -0.6281 -0.7626 +vn -0.0562 0.5507 -0.8328 +vn -0.1582 -0.1723 -0.9723 +vn -0.2255 -0.2992 -0.9271 +vn -0.4304 -0.4479 -0.7836 +vn -0.4564 0.6298 -0.6285 +vn -0.5942 -0.6703 -0.4445 +vn -0.7229 0.5955 -0.3504 +vn -0.9125 -0.3777 -0.1574 +vn -0.9147 -0.3724 -0.1570 +vn -0.9745 -0.2054 0.0908 +vn -0.9132 -0.3969 -0.0926 +vn -0.8501 -0.4927 0.1859 +vn -0.8424 -0.5057 0.1860 +vn -0.6965 0.5748 0.4295 +vn -0.5964 -0.6105 0.5213 +vn -0.3954 0.6562 0.6427 +vn -0.2353 -0.0512 0.9706 +vn -0.4514 0.1649 0.8770 +vn -0.3838 0.0937 0.9186 +vn -0.1599 -0.1204 0.9798 +vn 0.1797 0.2169 0.9595 +vn 0.5683 -0.1755 0.8039 +vn 0.5665 -0.1859 0.8028 +vn -0.0068 -0.9999 0.0119 +vn 0.0104 -0.9999 0.0059 +vn 0.0129 -0.9923 0.1235 +vn -0.0121 -0.9999 0.0005 +vn 0.0268 -0.9968 0.0751 +vn 0.0272 -0.9978 0.0603 +vn -0.0096 -0.9997 0.0221 +vn 0.0596 -0.9901 -0.1270 +vn 0.0294 -0.9957 -0.0878 +vn 0.0274 -0.9963 -0.0820 +vn 0.0242 -0.9997 0.0034 +vn -0.1035 -0.2049 -0.9733 +vn -0.1158 -0.3664 -0.9232 +vn -0.1157 -0.3617 -0.9251 +vn 0.0168 -0.9902 0.1388 +vn -0.0754 -0.9967 0.0291 +vn 0.1139 -0.9822 -0.1497 +vn 0.0944 -0.9852 -0.1428 +vn 0.0555 -0.9940 0.0942 +vn 0.0519 -0.9912 0.1215 +vn -0.1435 -0.9650 0.2195 +vn 0.0093 -0.9997 0.0239 +vn 0.0055 0.9999 -0.0109 +vn 0.0285 0.9980 -0.0560 +vn 0.0315 0.9976 -0.0619 +vn -0.0120 0.9999 -0.0085 +vn 0.0227 0.9966 -0.0790 +vn -0.0291 0.9944 -0.1013 +vn 0.0363 0.9950 0.0934 +vn -0.0193 0.9975 -0.0674 +vn -0.2565 0.1765 0.9503 +vn -0.0884 0.5188 0.8503 +vn -0.0884 0.5106 0.8553 +vn 0.0535 0.9875 -0.1483 +vn 0.0602 0.9771 -0.2039 +vn 0.0564 0.9800 -0.1910 +vn 0.0337 0.9957 -0.0859 +vn -0.0253 0.9997 -0.0071 +vn 0.0843 0.9867 0.1392 +vn 0.0739 0.9883 0.1333 +vn 0.0677 0.9882 -0.1377 +vn -0.0106 0.9999 0.0028 +vn -0.0901 0.9934 0.0710 +vn -0.0991 0.9884 0.1154 +vn -0.0104 0.9996 0.0249 +vn 0.5749 0.2661 -0.7738 +vn 0.2739 -0.5325 -0.8009 +vn -0.0896 -0.1973 -0.9762 +vn -0.0661 -0.1421 -0.9876 +vn 0.3520 0.2598 -0.8992 +vn 0.3641 -0.0236 -0.9310 +vn 0.3643 0.0322 -0.9307 +vn -0.4970 0.5336 -0.6844 +vn -0.6108 -0.2571 -0.7489 +vn -0.9201 0.0672 -0.3860 +vn -0.9204 0.0568 -0.3867 +vn -0.8992 0.2373 -0.3675 +vn -0.8980 0.2433 -0.3666 +vn -0.7844 0.0151 0.6200 +vn -0.8373 -0.0340 0.5457 +vn -0.9253 0.0494 0.3759 +vn -0.8746 0.1108 0.4720 +vn -0.9663 0.0588 0.2506 +vn -0.9034 -0.0993 0.4172 +vn -0.8438 -0.1894 0.5021 +vn -0.4761 -0.5467 0.6888 +vn -0.0191 -0.3265 0.9450 +vn -0.2149 0.2250 0.9504 +vn -0.3919 -0.0134 0.9199 +vn 0.2369 -0.5446 0.8045 +vn 0.5964 0.1355 0.7912 +vn 0.5961 0.1877 0.7807 +vn 0.5899 0.0034 0.8075 +vn 0.5890 -0.0062 0.8081 +vn -0.0141 -0.9999 0.0099 +vn 0.0078 -0.9933 0.1153 +vn 0.0135 -0.9950 0.0993 +vn -0.0004 -0.9929 0.1188 +vn -0.2523 -0.8517 0.4593 +vn -0.0447 -0.9975 -0.0550 +vn 0.0186 -0.9996 -0.0214 +vn 0.0548 -0.9868 -0.1526 +vn 0.0635 -0.9822 -0.1766 +vn -0.1045 -0.7660 -0.6343 +vn -0.1049 -0.7573 -0.6446 +vn -0.0475 -0.9989 -0.0032 +vn -0.0044 -0.9999 -0.0106 +vn -0.2343 -0.9700 -0.0648 +vn 0.0551 -0.9981 -0.0281 +vn 0.0431 -0.9988 -0.0220 +vn -0.0197 -0.9992 0.0346 +vn 0.0082 -0.9999 0.0127 +vn -0.0131 -0.9999 -0.0009 +vn -0.0596 -0.9982 -0.0040 +vn -0.2649 -0.8389 0.4755 +vn -0.0375 0.9993 -0.0077 +vn -0.0174 0.9997 -0.0177 +vn 0.0924 0.9945 -0.0484 +vn -0.1568 0.9445 0.2889 +vn -0.0284 0.9984 0.0482 +vn 0.0166 0.9975 0.0686 +vn 0.0108 0.9999 0.0056 +vn -0.3230 -0.0345 0.9458 +vn -0.1179 0.3519 0.9286 +vn -0.1179 0.3392 0.9333 +vn -0.0208 0.9369 -0.3489 +vn -0.0436 0.9988 -0.0242 +vn 0.0481 0.9985 0.0252 +vn 0.0380 0.9991 0.0199 +vn 0.1064 0.9884 -0.1083 +vn 0.1478 0.9785 -0.1440 +vn 0.0429 0.9930 -0.1102 +vn 0.0482 0.9911 -0.1238 +vn -0.0090 1.0000 0.0008 +vn -0.1084 0.9765 0.1864 +vn -0.0560 0.9977 0.0373 +vn -0.0288 0.9976 -0.0630 +vn -0.5669 0.8188 -0.0906 +vn -0.0327 0.9969 -0.0715 +vn -0.0043 0.9999 -0.0094 +vn 0.5904 0.0016 -0.8071 +vn 0.3444 0.1811 -0.9212 +vn 0.4845 0.0847 -0.8707 +vn 0.2200 0.2567 -0.9411 +vn -0.3754 -0.2032 -0.9043 +vn -0.4376 -0.1158 -0.8917 +vn -0.4441 0.4648 -0.7660 +vn -0.7206 -0.4171 -0.5539 +vn -0.9670 0.1439 -0.2104 +vn -0.9955 0.0814 -0.0484 +vn -0.9974 0.0473 0.0540 +vn -0.9481 0.2269 0.2227 +vn -0.9462 0.2346 0.2229 +vn -0.7293 -0.2250 0.6462 +vn -0.2319 -0.0826 0.9692 +vn -0.4451 0.0180 0.8953 +vn 0.2369 -0.5447 0.8045 +vn 0.5927 0.1361 0.7938 +vn 0.5918 0.1704 0.7879 +vn 0.5896 0.0064 0.8077 +vn 0.5890 -0.0025 0.8081 +vn -0.9029 -0.2295 -0.3633 +vn -0.9032 -0.1588 -0.3987 +vn -0.8868 -0.0163 -0.4619 +vn -0.8688 0.0612 -0.4914 +vn 0.7573 -0.0534 -0.6509 +vn 0.8318 0.3929 -0.3921 +vn 0.3186 -0.4665 0.8252 +vn -0.0194 0.2075 0.9780 +vn -0.0690 -0.9907 0.1174 +vn -0.0306 -0.9993 0.0205 +vn -0.0543 -0.9982 0.0235 +vn 0.0023 -1.0000 -0.0002 +vn 0.0120 -0.9995 0.0283 +vn 0.0225 -0.9970 -0.0747 +vn 0.0193 -0.9949 -0.0990 +vn 0.0546 -0.9870 -0.1513 +vn 0.0594 -0.9845 -0.1647 +vn -0.0240 -0.3487 0.9369 +vn -0.0666 -0.9968 0.0438 +vn -0.0059 -0.9999 0.0104 +vn 0.0161 -0.9998 -0.0084 +vn 0.0372 -0.9991 -0.0193 +vn 0.0193 -0.9998 -0.0100 +vn 0.0297 0.9982 0.0512 +vn 0.0066 0.9999 0.0114 +vn 0.0332 0.9978 0.0572 +vn 0.0679 0.9974 0.0250 +vn 0.0151 0.9992 0.0381 +vn 0.0680 0.9977 -0.0033 +vn -0.1120 -0.4998 0.8589 +vn 0.0857 0.9828 0.1638 +vn 0.0378 0.9908 -0.1301 +vn -0.0481 0.8190 -0.5718 +vn -0.0354 0.8574 -0.5134 +vn 0.0302 0.9934 -0.1103 +vn 0.0256 0.9945 -0.1013 +vn 0.0251 0.9947 -0.0995 +vn 0.5411 0.4176 -0.7300 +vn 0.2696 -0.5954 -0.7568 +vn 0.0618 0.7971 -0.6007 +vn -0.0641 -0.6439 -0.7624 +vn -0.8190 -0.3111 -0.4821 +vn -0.8040 -0.3600 -0.4732 +vn -0.8311 -0.2891 -0.4751 +vn -0.2100 0.4859 -0.8484 +vn -0.1332 0.3958 -0.9086 +vn -0.2924 0.5780 -0.7619 +vn -0.3391 0.6273 -0.7010 +vn -0.5354 -0.1827 -0.8246 +vn -0.6884 0.4364 -0.5794 +vn -0.7673 -0.2857 -0.5741 +vn -0.9844 -0.0088 -0.1759 +vn -0.9843 -0.0116 -0.1761 +vn -0.9998 -0.0074 -0.0182 +vn -0.9997 -0.0166 0.0155 +vn -0.9721 -0.1735 0.1579 +vn -0.9663 -0.2060 0.1542 +vn -0.6844 0.5814 0.4399 +vn -0.5848 -0.6448 0.4922 +vn -0.4388 0.4592 0.7724 +vn -0.3456 -0.1087 0.9320 +vn -0.4196 -0.1656 0.8925 +vn -0.2465 -0.0349 0.9685 +vn -0.1629 0.0256 0.9863 +vn 0.5676 -0.1795 0.8035 +vn 0.5884 -0.0117 0.8085 +vn -0.7213 -0.5246 -0.4522 +vn 0.0315 0.5652 -0.8243 +vn 0.7132 -0.4581 -0.5305 +vn 0.7566 0.3258 0.5670 +vn 0.7758 0.4241 0.4672 +vn 0.7380 0.2632 0.6213 +vn 0.6633 0.0906 0.7429 +vn -0.3895 -0.1083 0.9146 +vn -0.6800 0.5319 0.5047 +vn 0.5972 -0.0606 -0.7998 +vn 0.0020 -1.0000 0.0003 +vn 0.0288 -0.9974 -0.0666 +vn 0.0034 -1.0000 0.0067 +vn 0.0162 -0.9993 0.0326 +vn 0.0183 -0.9992 0.0367 +vn 0.0378 -0.9932 0.1101 +vn 0.0225 -0.9966 0.0793 +vn -0.0423 -0.9852 -0.1660 +vn -0.0300 -0.9926 -0.1178 +vn 0.0401 -0.9944 -0.0981 +vn 0.0382 -0.9888 -0.1444 +vn 0.0419 -0.9865 -0.1585 +vn -0.0458 0.3405 -0.9391 +vn 0.0102 -0.9605 0.2780 +vn 0.0695 -0.9931 -0.0944 +vn 0.0548 -0.9942 -0.0924 +vn -0.0262 0.9996 -0.0041 +vn 0.0292 0.9984 0.0480 +vn 0.0079 0.9999 0.0130 +vn 0.0336 0.9979 0.0552 +vn 0.0589 0.9880 -0.1430 +vn 0.0388 0.9928 -0.1135 +vn 0.0400 0.9923 -0.1171 +vn -0.1269 0.2898 -0.9486 +vn 0.0807 0.9848 -0.1536 +vn 0.0920 0.9832 -0.1579 +vn 0.0000 0.9988 -0.0499 +vn -0.0185 0.9993 -0.0315 +vn -0.0925 0.9843 -0.1505 +vn -0.0360 0.9992 -0.0179 +vn -0.2278 0.9715 -0.0655 +vn -0.0272 0.9995 -0.0185 +vn 0.2308 0.6189 -0.7508 +vn -0.1845 -0.4819 -0.8566 +vn -0.0770 -0.5268 -0.8465 +vn -0.2984 -0.4410 -0.8464 +vn -0.4148 -0.4031 -0.8157 +vn -0.4236 -0.4137 -0.8059 +vn -0.4261 0.6704 -0.6075 +vn -0.5519 0.8042 -0.2203 +vn -0.7420 -0.6581 -0.1276 +vn -0.8715 -0.0640 0.4862 +vn -0.9649 0.1220 0.2326 +vn -0.9292 0.1091 0.3530 +vn -0.9823 0.0926 0.1628 +vn -0.7245 -0.6598 0.1994 +vn -0.7072 0.5565 0.4361 +vn -0.6152 -0.5565 0.5584 +vn -0.4191 0.6224 0.6610 +vn -0.4397 -0.1117 0.8912 +vn -0.1141 0.3383 0.9341 +vn -0.0479 -0.4087 0.9114 +vn 0.3083 0.3955 0.8652 +vn 0.3469 -0.6256 0.6988 +vn -0.1618 0.8774 -0.4517 +vn 0.6101 -0.0136 0.7922 +vn -0.8349 -0.2688 -0.4804 +vn -0.8486 -0.2416 -0.4707 +vn 0.4655 0.2416 -0.8514 +vn 0.7480 -0.4157 -0.5174 +vn 0.8597 0.3019 0.4120 +vn 0.0605 -0.6301 0.7742 +vn -0.5515 0.2553 0.7942 +vn -0.9295 0.3453 -0.1296 +vn -0.1406 -0.2443 -0.9595 +vn -0.0987 -0.1724 -0.9801 +vn 0.9359 0.3041 -0.1779 +vn 0.7685 -0.5390 0.3448 +vn 0.0205 0.4387 0.8984 +vn -0.7236 -0.5012 0.4746 +vn -0.8365 -0.4942 -0.2367 +vn -0.3961 0.3338 -0.8554 +vn 0.3524 -0.2529 -0.9010 +vn 0.7338 0.1683 -0.6582 +vn 0.9020 -0.2101 0.3771 +vn 0.8914 -0.0913 0.4439 +vn 0.8496 0.0745 0.5221 +vn 0.7805 0.2327 0.5802 +vn -0.5100 0.2048 0.8354 +vn -0.5781 0.3203 0.7505 +vn -0.6124 0.3868 0.6894 +vn -0.6470 0.4640 0.6050 +vn -0.8883 -0.2759 -0.3672 +vn -0.6951 0.1992 -0.6908 +vn 0.3138 -0.2946 -0.9026 +vn 0.7146 0.3127 -0.6258 +vn 0.9284 -0.2263 0.2946 +vn 0.6890 0.2610 0.6761 +vn -0.2127 -0.3675 0.9054 +vn -0.7038 0.3344 0.6268 +vn -0.8099 -0.0393 -0.5853 +vn -0.7745 0.0490 -0.6307 +vn -0.7345 0.1294 -0.6662 +vn -0.6913 0.2027 -0.6936 +vn 0.5810 -0.2908 -0.7602 +vn 0.8189 0.2802 -0.5009 +vn 0.6649 -0.1866 0.7232 +vn 0.6141 -0.0752 0.7856 +vn 0.5485 0.0428 0.8350 +vn 0.4726 0.1584 0.8669 +vn -0.6703 -0.2033 0.7137 +vn -0.7602 -0.0646 0.6464 +vn -0.6015 0.0175 -0.7987 +vn -0.3015 -0.4218 -0.8551 +vn 0.7465 0.4863 -0.4541 +vn 0.6963 -0.6340 0.3365 +vn 0.3427 0.2813 0.8964 +vn -0.4889 0.3719 -0.7891 +vn 0.5371 -0.6353 -0.5549 +vn 0.9160 -0.0618 -0.3964 +vn 0.4010 -0.0159 0.9159 +vn 0.4844 0.1309 0.8650 +vn 0.3139 -0.1500 0.9375 +vn 0.2265 -0.2692 0.9361 +vn -0.8053 0.2668 0.5294 +vn -0.8691 -0.4937 -0.0305 +vn -0.9420 0.0241 0.3348 +vn -0.9397 0.0376 0.3401 +vn -0.9446 0.0072 0.3281 +vn -0.9456 0.0000 0.3252 +vn -0.9966 0.0217 -0.0789 +vn -0.9424 0.0151 -0.3342 +vn -0.9732 0.1345 -0.1865 +vn -0.9354 0.0598 0.3486 +vn -0.9523 0.0205 0.3044 +vn -0.9293 0.1351 0.3438 +vn -0.9508 -0.2368 0.1997 +vn -0.9361 -0.3105 0.1653 +vn -0.7537 0.2519 -0.6070 +vn -0.9398 0.0187 0.3411 +vn -0.9418 0.0264 0.3352 +vn -0.9425 0.0293 0.3329 +vn -0.9443 0.0371 0.3270 +vn -0.7744 -0.0078 -0.6326 +vn -0.8506 -0.0079 -0.5258 +vn -0.6096 0.0107 -0.7927 +vn -0.9428 0.0364 0.3314 +vn 0.4770 0.0151 0.8788 +vn -0.8341 -0.0064 -0.5516 +vn -0.9888 -0.0065 -0.1491 +vn -0.9461 -0.0560 0.3190 +vn -0.9468 -0.0773 0.3123 +vn -0.9413 0.0059 0.3376 +vn -0.9373 0.0380 0.3466 +vn -0.9505 0.0379 0.3085 +vn -0.9497 0.0317 0.3116 +vn -0.9476 0.0168 0.3189 +vn -0.9460 0.0059 0.3242 +vn 0.9378 -0.2644 0.2250 +vn -0.1684 0.3096 0.9358 +vn 0.1521 -0.2718 0.9502 +vn -0.9329 0.3226 -0.1598 +vn -0.8079 -0.2808 -0.5182 +vn 0.5289 0.1087 -0.8417 +vn 0.6333 0.3054 -0.7111 +vn 0.6518 0.3489 -0.6733 +vn 0.6875 0.4517 -0.5686 +vn 0.9131 -0.3885 0.1235 +vn 0.8012 0.2713 0.5334 +vn -0.6870 -0.2128 0.6948 +vn -0.8642 0.3525 0.3591 +vn -0.3054 -0.4144 -0.8573 +vn 0.1881 0.2207 -0.9570 +vn 0.9693 -0.1611 0.1859 +vn 0.9622 -0.0565 0.2663 +vn 0.9492 0.0100 0.3144 +vn 0.9137 0.1192 0.3884 +vn -0.5336 -0.1205 0.8371 +vn -0.5029 -0.1716 0.8472 +vn -0.4782 -0.2104 0.8527 +vn -0.4356 -0.2732 0.8577 +vn -0.8761 0.2534 -0.4102 +vn -0.2181 -0.5872 -0.7795 +vn 0.4799 0.0999 -0.8716 +vn 0.8914 0.0055 0.4533 +vn 0.8960 0.0279 0.4432 +vn 0.8846 -0.0229 0.4657 +vn 0.8791 -0.0442 0.4746 +vn -0.7880 0.0184 0.6154 +vn -0.5363 -0.4729 0.6991 +vn -0.6493 0.2268 -0.7260 +vn -0.0213 -0.5046 -0.8631 +vn 0.4535 0.0800 -0.8877 +vn -0.0757 -0.1587 0.9844 +vn -0.0766 -0.1568 0.9847 +vn -0.0780 -0.1538 0.9850 +vn -0.0792 -0.1515 0.9853 +vn -0.8518 0.2709 -0.4484 +vn -0.6739 -0.3312 -0.6605 +vn 0.9129 0.1580 -0.3765 +vn 0.9127 0.1515 -0.3796 +vn 0.9124 0.1437 -0.3833 +vn 0.9121 0.1389 -0.3856 +vn 0.8335 -0.4326 0.3437 +vn -0.3315 0.3616 0.8714 +vn -0.7268 -0.4845 0.4868 +vn -0.6163 0.4812 -0.6234 +vn -0.1039 -0.4422 -0.8909 +vn 0.8935 0.4304 -0.1277 +vn -0.6811 0.0124 -0.7321 +vn -0.6836 0.0021 -0.7298 +vn -0.6903 -0.0271 -0.7230 +vn -0.6924 -0.0368 -0.7206 +vn 0.4219 -0.0561 -0.9049 +vn 0.5896 0.0838 -0.8033 +vn 0.7715 -0.0865 -0.6303 +vn 0.8734 0.0110 -0.4870 +vn 0.9555 -0.0182 -0.2946 +vn 0.9885 0.0516 -0.1421 +vn 0.9923 -0.0482 0.1138 +vn 0.9659 0.0013 0.2588 +vn 0.8751 0.0019 0.4839 +vn 0.8203 0.0038 0.5718 +vn 0.6412 -0.0626 0.7648 +vn 0.5166 0.0166 0.8560 +vn 0.9833 0.0368 0.1780 +vn 0.7111 -0.5130 0.4808 +vn 0.0241 0.3290 0.9440 +vn -0.8225 -0.3475 0.4502 +vn -0.8902 0.4411 -0.1143 +vn -0.0804 -0.5508 -0.8307 +vn 0.4214 0.2442 -0.8734 +vn 0.0168 0.4306 0.9024 +vn -0.3668 -0.3778 0.8502 +vn -0.7636 0.3287 -0.5558 +vn -0.5194 -0.2946 -0.8021 +vn 0.7902 0.2758 -0.5473 +vn 0.9042 -0.3901 -0.1737 +vn 0.3236 -0.2685 0.9073 +vn 0.0632 0.1824 0.9812 +vn -0.9092 0.0343 0.4149 +vn -0.8762 0.4640 -0.1306 +vn -0.5857 -0.5071 -0.6323 +vn 0.3848 0.0836 -0.9192 +vn 0.7983 -0.3539 -0.4873 +vn 0.9570 0.2898 -0.0090 +vn -0.9337 0.0917 -0.3461 +vn -0.9591 0.0149 -0.2828 +vn -0.9649 -0.0093 -0.2623 +vn -0.9769 -0.0857 -0.1955 +vn -0.7433 0.0414 0.6677 +vn -0.7348 0.0262 0.6778 +vn -0.7322 0.0216 0.6808 +vn -0.7225 0.0053 0.6913 +vn -0.9429 -0.0151 0.3327 +vn -0.9505 -0.0502 0.3068 +vn -0.9390 0.0003 0.3439 +vn -0.9287 0.0357 0.3691 +vn -0.9491 0.0952 0.3004 +vn -0.9096 -0.0276 0.4146 +vn -0.9397 0.0132 0.3417 +vn -0.9584 0.0381 0.2829 +vn -0.9449 -0.0397 0.3249 +vn -0.0106 0.9998 -0.0146 +vn -0.0090 0.9993 -0.0376 +vn 0.0000 1.0000 0.0001 +vn -0.0534 0.9907 -0.1250 +vn -0.0845 0.9840 -0.1568 +vn -0.0447 -0.9893 0.1390 +vn 0.0044 -0.9999 0.0148 +vn -0.0018 -0.9925 0.1226 +vn 0.0461 -0.9989 0.0069 +vn 0.0474 -0.9986 0.0221 +vn 0.0624 -0.9932 0.0981 +vn 0.0494 -0.9969 0.0605 +vn -0.0579 -0.9981 0.0189 +vn -0.0528 -0.9986 -0.0075 +vn 0.0035 -0.9999 0.0096 +vn 0.0346 -0.9949 0.0943 +vn 0.0177 -0.9992 -0.0367 +vn 0.0138 -0.9999 -0.0105 +vn 0.1748 -0.9836 0.0449 +vn 0.0425 -0.9924 0.1158 +vn 0.0049 -0.9999 0.0124 +vn -0.6677 -0.0068 0.7444 +vn -0.6803 -0.0037 0.7329 +vn -0.4792 -0.0625 0.8755 +vn -0.1250 0.0547 0.9906 +vn 0.0279 0.0591 0.9979 +vn 0.0322 0.0592 0.9977 +vn 0.1881 0.0622 0.9802 +vn 0.1533 -0.6459 0.7479 +vn 0.0371 -0.8182 0.5738 +vn 0.2228 -0.5086 0.8317 +vn 0.2466 -0.4544 0.8560 +vn 0.5727 0.0622 0.8174 +vn 0.5715 0.0300 0.8200 +vn 0.6574 0.0867 0.7485 +vn 0.7819 -0.0676 0.6198 +vn 0.8348 -0.1595 0.5270 +vn 0.8816 0.4218 0.2120 +vn 0.9627 -0.2555 -0.0887 +vn 0.9586 -0.2702 -0.0896 +vn 0.8657 -0.4902 -0.1014 +vn 0.8236 -0.5576 -0.1041 +vn 0.8456 0.0522 -0.5312 +vn 0.8449 0.0617 -0.5314 +vn 0.8482 -0.0793 -0.5236 +vn 0.8477 -0.0914 -0.5225 +vn 0.4552 0.4002 -0.7954 +vn 0.3366 -0.5695 -0.7499 +vn 0.1151 0.5840 -0.8035 +vn -0.0910 -0.6964 -0.7119 +vn -0.2408 0.3828 -0.8919 +vn -0.5478 -0.2942 -0.7831 +vn -0.5441 -0.3084 -0.7803 +vn 0.0418 -0.9983 0.0407 +vn 0.0116 -0.9999 0.0100 +vn 0.0295 -0.9993 -0.0249 +vn -0.0350 -0.9943 -0.1007 +vn 0.0292 -0.9810 -0.1920 +vn 0.0712 -0.9970 -0.0301 +vn 0.0924 -0.9843 0.1501 +vn 0.1186 -0.9883 0.0954 +vn 0.1759 -0.9836 0.0403 +vn 0.0445 -0.9984 0.0344 +vn 0.0567 -0.9964 0.0634 +vn -0.0056 -0.9999 0.0084 +vn -0.0077 -0.9999 -0.0107 +vn 0.0240 -0.9997 0.0033 +vn 0.1560 -0.9826 0.1009 +vn 0.1959 0.9380 -0.2861 +vn 0.1593 -0.9685 0.1916 +vn -0.1362 -0.9692 0.2050 +vn -0.1599 -0.9573 0.2407 +vn 0.0293 0.9985 -0.0454 +vn -0.0090 0.9993 -0.0362 +vn 0.0725 0.9966 -0.0384 +vn 0.0108 0.9999 0.0112 +vn 0.0600 0.9960 0.0660 +vn 0.1078 0.9801 0.1668 +vn 0.0926 0.9934 0.0682 +vn 0.0239 0.9997 -0.0093 +vn 0.1032 0.9735 -0.2042 +vn -0.0426 0.9969 -0.0658 +vn 0.0125 0.9999 -0.0024 +vn -0.0086 0.9999 0.0127 +vn 0.0567 0.9873 0.1481 +vn 0.0654 0.9831 0.1708 +vn 0.2663 0.9592 0.0946 +vn 0.1162 0.9900 0.0795 +vn 0.0476 0.9988 -0.0091 +vn -0.0041 0.9935 -0.1138 +vn -0.0188 0.9998 -0.0118 +vn 0.0063 0.9999 0.0112 +vn -0.6916 -0.0363 0.7213 +vn -0.6915 -0.0490 0.7207 +vn -0.5670 -0.1052 0.8170 +vn -0.3220 0.6803 0.6584 +vn -0.2496 -0.4811 0.8403 +vn 0.0559 0.2785 0.9588 +vn 0.0534 0.2368 0.9701 +vn 0.1533 0.4091 0.8995 +vn 0.2547 0.4164 0.8728 +vn 0.3985 0.4708 0.7871 +vn 0.4182 0.5049 0.7551 +vn 0.3335 -0.8592 0.3880 +vn 0.5503 0.8109 0.1991 +vn 0.9967 -0.0794 -0.0147 +vn 0.9916 -0.0556 0.1166 +vn 0.9971 -0.0733 0.0224 +vn 0.9896 -0.0954 -0.1076 +vn 0.6915 -0.7043 -0.1606 +vn 0.6777 0.6605 -0.3233 +vn 0.5933 -0.5187 -0.6156 +vn 0.4451 -0.0070 -0.8954 +vn 0.2694 0.0826 -0.9595 +vn 0.3518 0.0416 -0.9352 +vn 0.1696 0.1290 -0.9770 +vn -0.1785 0.2180 -0.9595 +vn -0.5636 -0.1704 -0.8083 +vn -0.5616 -0.1797 -0.8076 +vn -0.5881 -0.0213 -0.8085 +vn -0.5892 -0.0116 -0.8079 +vn 0.0576 -0.9970 0.0518 +vn 0.0094 -0.9999 0.0078 +vn -0.0028 -0.9996 -0.0294 +vn 0.0055 -0.7708 -0.6370 +vn 0.0422 -0.9990 -0.0178 +vn 0.0674 -0.9941 0.0852 +vn 0.0060 -1.0000 0.0078 +vn -0.0228 -0.9997 0.0007 +vn -0.0371 -0.9993 0.0011 +vn -0.0176 -0.9998 -0.0095 +vn -0.0347 -0.9947 -0.0965 +vn -0.0011 -0.9999 -0.0114 +vn -0.0417 -0.9924 -0.1160 +vn 0.9575 -0.1527 -0.2447 +vn 0.9245 0.2881 -0.2495 +vn 0.9590 -0.1418 -0.2454 +vn -0.0038 -0.9992 -0.0406 +vn 0.0829 0.9920 -0.0952 +vn 0.0848 0.9848 -0.1513 +vn 0.0546 0.9984 -0.0168 +vn 0.0758 0.9931 -0.0894 +vn 0.0251 0.9996 -0.0096 +vn -0.0134 0.9999 0.0070 +vn 0.0228 0.9997 -0.0030 +vn 0.0068 0.9998 -0.0183 +vn -0.0208 0.9996 -0.0187 +vn -0.0529 0.9877 -0.1473 +vn -0.0618 0.9831 -0.1720 +vn 0.2322 0.9711 -0.0558 +vn -0.0293 0.9993 0.0238 +vn -0.0143 0.9851 -0.1713 +vn -0.0273 0.9962 0.0832 +vn 0.0301 0.9982 0.0522 +vn 0.0846 0.9963 0.0151 +vn -0.7099 0.0686 0.7010 +vn -0.6622 0.0732 0.7458 +vn -0.3800 -0.2965 0.8762 +vn -0.3776 -0.3092 0.8728 +vn 0.2363 0.4217 -0.8754 +vn 0.0816 0.6669 -0.7406 +vn 0.3725 0.4045 -0.8352 +vn 0.4524 0.2417 -0.8584 +vn 0.4488 0.3212 -0.8339 +vn 0.5022 -0.3146 -0.8055 +vn 0.6869 0.5073 -0.5204 +vn 0.9211 0.2994 -0.2489 +vn 0.9673 -0.0873 0.2383 +vn 0.9695 0.0535 0.2393 +vn 0.9690 -0.0639 0.2387 +vn 0.8404 -0.3370 -0.4244 +vn 0.6531 -0.7372 0.1734 +vn 0.7426 0.6010 0.2955 +vn 0.6183 -0.3022 0.7256 +vn 0.6135 -0.3210 0.7216 +vn 0.6462 -0.1593 0.7464 +vn 0.6470 -0.1533 0.7469 +vn -0.3088 -0.1927 0.9314 +vn -0.3286 0.0341 0.9438 +vn -0.1435 0.0602 0.9878 +vn -0.1476 -0.1017 0.9838 +vn 0.1186 -0.0034 0.9929 +vn 0.1187 -0.0018 0.9929 +vn -0.2574 0.1828 -0.9488 +vn -0.3529 0.0981 -0.9305 +vn -0.5142 -0.0633 -0.8553 +vn -0.5900 -0.1502 -0.7933 +vn 0.0078 -0.9998 -0.0208 +vn 0.0782 -0.9922 -0.0969 +vn -0.0128 -0.9998 -0.0145 +vn -0.0767 -0.9914 -0.1061 +vn -0.0856 -0.9787 -0.1869 +vn -0.0147 -0.9992 -0.0377 +vn 0.0901 -0.9708 -0.2224 +vn 0.6949 0.6971 -0.1764 +vn 0.1311 -0.9875 -0.0879 +vn 0.1503 -0.9848 -0.0872 +vn 0.0071 0.9999 -0.0092 +vn 0.0887 0.9892 -0.1171 +vn 0.1035 0.9839 -0.1457 +vn 0.1219 0.9899 -0.0725 +vn 0.0571 0.9981 0.0235 +vn 0.0129 0.9999 0.0105 +vn 0.0629 0.9925 0.1048 +vn 0.0529 0.9986 0.0100 +vn 0.0229 0.9996 0.0155 +vn 0.0145 0.9999 0.0032 +vn 0.0265 0.9995 0.0145 +vn 0.1523 0.9873 0.0445 +vn 0.1588 0.9869 0.0289 +vn 0.0625 0.9967 0.0512 +vn 0.2969 0.8597 -0.4157 +vn -0.0505 0.9974 -0.0512 +vn 0.1197 0.9879 -0.0986 +vn 0.2248 0.9738 -0.0350 +vn 0.0382 0.9986 0.0362 +vn -0.4568 -0.0656 0.8871 +vn -0.4572 -0.0786 0.8859 +vn -0.4284 0.2255 0.8750 +vn -0.4269 0.2344 0.8734 +vn 0.0679 -0.2481 0.9663 +vn 0.0676 -0.2513 0.9656 +vn 0.3308 -0.0473 0.9425 +vn 0.2376 -0.0715 0.9687 +vn 0.4727 0.3576 0.8054 +vn 0.4715 0.3682 0.8013 +vn 0.6923 -0.4591 0.5568 +vn 0.6654 0.6413 0.3820 +vn 0.7884 -0.5599 0.2547 +vn 0.2117 0.9711 -0.1105 +vn 0.9955 -0.0034 0.0942 +vn 0.9984 -0.0561 0.0045 +vn 0.9911 -0.1059 -0.0809 +vn 0.9730 -0.1567 -0.1695 +vn 0.3898 -0.6136 -0.6867 +vn 0.2079 -0.4551 -0.8658 +vn 0.3441 -0.5621 -0.7520 +vn 0.1219 -0.4061 -0.9057 +vn 0.0661 -0.5828 -0.8099 +vn 0.0646 -0.5892 -0.8054 +vn -0.1546 0.6281 -0.7626 +vn -0.2837 -0.7994 -0.5297 +vn -0.5601 0.3106 -0.7680 +vn 0.8163 -0.4557 0.3548 +vn -0.3035 0.3847 0.8717 +vn -0.7462 -0.5282 0.4052 +vn -0.6258 0.5224 -0.5792 +vn -0.0724 -0.4292 -0.9003 +vn 0.8931 0.4339 -0.1191 +vn 0.0215 -0.9998 0.0029 +vn 0.0414 -0.9991 -0.0103 +vn 0.0798 -0.9919 -0.0989 +vn 0.0078 -0.9999 -0.0102 +vn -0.0312 -0.9921 -0.1217 +vn 0.0116 -0.9994 -0.0316 +vn 0.0394 -0.9760 -0.2141 +vn 0.0666 -0.9973 0.0312 +vn 0.0379 -0.9990 0.0255 +vn 0.0925 -0.9843 0.1505 +vn 0.0833 -0.9928 0.0861 +vn 0.1276 -0.9914 0.0283 +vn 0.0219 -0.9987 0.0462 +vn 0.0144 -0.9997 0.0191 +vn -0.0116 -0.9997 -0.0213 +vn -0.0339 -0.9950 -0.0941 +vn 0.0627 -0.9965 0.0560 +vn 0.2741 -0.9597 0.0617 +vn 0.0062 -0.9998 0.0185 +vn 0.0131 0.9999 -0.0069 +vn 0.0606 0.9978 0.0262 +vn 0.0136 0.9998 0.0111 +vn 0.0725 0.9897 0.1236 +vn 0.0559 0.9984 0.0098 +vn 0.0624 0.9959 0.0662 +vn 0.0208 0.9969 -0.0758 +vn -0.0185 0.9998 -0.0117 +vn -0.0567 0.9873 -0.1481 +vn -0.0654 0.9831 -0.1708 +vn 0.1552 0.9872 0.0375 +vn 0.0046 1.0000 0.0088 +vn 0.0210 0.9998 0.0025 +vn 0.0362 0.9993 -0.0023 +vn -0.0070 0.9951 -0.0983 +vn -0.0199 0.9997 -0.0123 +vn -0.7333 0.0638 0.6770 +vn -0.7680 0.0015 0.6404 +vn -0.7620 0.0670 0.6441 +vn -0.5497 0.1550 0.8209 +vn -0.3536 -0.6200 0.7004 +vn -0.2135 0.5567 0.8028 +vn 0.0598 -0.5453 0.8361 +vn 0.0580 -0.5561 0.8291 +vn 0.3535 -0.0309 0.9349 +vn 0.2486 -0.0620 0.9666 +vn 0.4695 0.3634 0.8047 +vn 0.4684 0.3732 0.8008 +vn 0.6868 -0.5075 0.5203 +vn 0.9641 0.0085 0.2653 +vn 0.9736 0.0061 0.2282 +vn 0.9749 0.0873 0.2046 +vn 0.9635 0.2089 0.1671 +vn 0.7569 -0.6274 -0.1828 +vn 0.7649 0.5833 -0.2733 +vn 0.5904 -0.4771 -0.6511 +vn 0.6352 0.1541 -0.7568 +vn -0.3970 0.1181 -0.9102 +vn -0.3997 -0.0225 -0.9164 +vn -0.3912 -0.2074 -0.8966 +vn -0.1116 -0.3358 -0.9353 +vn -0.0124 -0.2843 -0.9586 +vn 0.0494 -0.2504 -0.9669 +vn 0.1345 -0.2014 -0.9702 +vn -0.1903 0.5518 -0.8120 +vn -0.5577 -0.3305 -0.7614 +vn 0.9187 -0.3950 -0.0010 +vn 0.9436 -0.3284 0.0418 +vn 0.9691 -0.2234 0.1050 +vn 0.9791 -0.1215 0.1631 +vn 0.0216 0.1097 0.9937 +vn 0.0628 -0.0871 0.9942 +vn 0.0217 -0.0725 0.9971 +vn -0.2902 -0.3036 0.9075 +vn -0.9553 0.2954 0.0136 +vn -0.6011 -0.5832 -0.5464 +vn 0.0412 0.4123 -0.9101 +vn -0.0159 -0.9999 0.0045 +vn 0.0183 -0.9998 0.0046 +vn 0.0587 -0.9945 -0.0863 +vn 0.0347 -0.9994 -0.0084 +vn 0.0612 -0.9933 -0.0980 +vn -0.0188 -0.9951 -0.0967 +vn 0.0067 -0.9998 -0.0192 +vn 0.0018 -0.9917 -0.1283 +vn -0.0288 -0.9994 -0.0170 +vn -0.0092 -0.9992 0.0383 +vn -0.0111 -0.9997 -0.0220 +vn -0.0424 -0.9921 -0.1182 +vn 0.0353 -0.9990 -0.0256 +vn 0.0214 -0.9997 -0.0096 +vn 0.1403 -0.9895 0.0337 +vn -0.0485 -0.9828 0.1782 +vn 0.1050 -0.9933 0.0485 +vn -0.0521 -0.9880 -0.1451 +vn 0.0925 -0.9937 0.0633 +vn 0.0250 -0.9997 -0.0012 +vn 0.2144 -0.9761 -0.0348 +vn 0.1284 -0.9898 -0.0611 +vn 0.4859 -0.3978 -0.7782 +vn 0.4859 -0.3976 -0.7783 +vn 0.4420 -0.2373 -0.8651 +vn 0.1100 -0.9902 -0.0858 +vn 0.4672 -0.5036 0.7267 +vn 0.4675 -0.5027 0.7271 +vn 0.4563 -0.5329 0.7126 +vn 0.0335 0.9967 -0.0738 +vn 0.0571 0.9981 0.0211 +vn 0.0129 0.9999 0.0106 +vn 0.0632 0.9924 0.1051 +vn 0.0635 0.9975 0.0316 +vn 0.1273 0.9627 0.2389 +vn 0.0145 0.9999 0.0028 +vn 0.0283 0.9995 0.0103 +vn 0.1718 0.9845 0.0340 +vn 0.2466 0.9674 0.0584 +vn 0.1087 0.9927 -0.0522 +vn 0.4192 0.5341 -0.7342 +vn 0.0963 0.9933 -0.0636 +vn 0.1770 0.9835 -0.0364 +vn -0.0271 0.9996 -0.0091 +vn -0.0463 0.9916 -0.1209 +vn -0.0533 0.9888 -0.1393 +vn 0.1428 0.9871 0.0729 +vn 0.0259 0.9997 0.0029 +vn 0.3335 0.9413 0.0519 +vn 0.1091 0.9906 0.0826 +vn 0.0460 0.9986 0.0249 +vn 0.0285 0.9990 -0.0343 +vn -0.0133 0.9896 -0.1429 +vn -0.0328 0.9992 -0.0208 +vn 0.2870 0.7921 0.5388 +vn -0.6191 -0.0856 0.7806 +vn -0.6625 -0.0351 0.7483 +vn -0.4573 -0.0744 0.8862 +vn -0.3749 0.4603 0.8047 +vn 0.0543 -0.5992 0.7987 +vn 0.0525 -0.6103 0.7904 +vn 0.0603 -0.2049 0.9769 +vn 0.4561 -0.5335 0.7123 +vn 0.9443 0.2621 0.1990 +vn 0.9474 -0.2481 -0.2021 +vn 0.3037 -0.3179 -0.8982 +vn 0.2165 -0.2935 -0.9311 +vn 0.0841 -0.3870 -0.9182 +vn -0.2177 0.5128 -0.8304 +vn -0.5573 -0.3276 -0.7630 +vn 0.7394 0.5459 0.3941 +vn -0.0645 -0.5415 0.8382 +vn -0.7201 0.5472 0.4265 +vn -0.5932 -0.5350 -0.6016 +vn -0.1107 0.3555 -0.9281 +vn 0.8354 -0.4638 -0.2948 +vn -0.0741 0.3785 0.9226 +vn -0.5558 -0.5646 0.6102 +vn -0.7548 0.5218 -0.3974 +vn -0.3758 -0.3413 -0.8616 +vn 0.9206 0.3860 -0.0585 +vn 0.8432 -0.4024 -0.3565 +vn 0.7891 0.3681 0.4917 +vn 0.4390 -0.5225 0.7309 +vn -0.8556 0.4924 0.1600 +vn -0.9729 -0.1690 -0.1580 +vn 0.9267 0.3396 0.1607 +vn 0.6723 -0.3750 0.6383 +vn -0.6422 0.3544 0.6797 +vn -0.6450 0.3756 0.6655 +vn -0.6469 0.3945 0.6526 +vn -0.6484 0.4070 0.6434 +vn -0.5167 -0.4451 -0.7313 +vn -0.0753 0.4155 -0.9065 +vn 0.8782 -0.1360 -0.4585 +vn 0.8881 -0.3844 0.2520 +vn 0.4323 0.3693 0.8226 +vn -0.5422 -0.4422 0.7145 +vn -0.8978 0.3825 0.2183 +vn -0.6655 -0.3216 -0.6736 +vn -0.3618 0.1107 -0.9256 +vn 0.4025 -0.0152 -0.9153 +vn 0.8054 0.4312 -0.4067 +vn 0.9510 -0.2018 0.2343 +vn -0.1288 0.2536 0.9587 +vn -0.1067 0.2086 0.9722 +vn -0.0823 0.1589 0.9839 +vn -0.0641 0.1218 0.9905 +vn -0.9627 -0.1349 -0.2343 +vn -0.9581 -0.0481 -0.2825 +vn -0.9372 0.0679 -0.3420 +vn -0.9107 0.1545 -0.3830 +vn 0.5252 -0.1215 -0.8423 +vn 0.7132 0.4727 -0.5176 +vn 0.9081 -0.1400 0.3947 +vn 0.9097 -0.2018 0.3630 +vn 0.9049 -0.2837 0.3173 +vn 0.8930 -0.3589 0.2716 +vn -0.3946 0.3454 0.8515 +vn -0.7558 -0.5106 0.4099 +vn -0.8790 0.2408 -0.4116 +vn -0.0663 -0.5616 -0.8247 +vn 0.4622 0.0957 -0.8816 +vn 0.0408 -0.0051 0.9992 +vn 0.0067 0.0020 1.0000 +vn 0.0360 -0.0041 0.9993 +vn 0.0028 0.0028 1.0000 +vn -0.8778 0.0087 -0.4789 +vn -0.9901 0.0466 -0.1322 +vn -0.9903 0.0055 -0.1390 +vn -0.8742 -0.0010 -0.4855 +vn -0.9949 -0.0347 -0.0944 +vn -0.7814 0.1075 0.6148 +vn -0.8065 0.0364 0.5901 +vn -0.7961 0.1617 0.5832 +vn 0.6831 -0.2892 0.6706 +vn 0.3714 0.2460 0.8953 +vn -0.7499 0.2201 0.6239 +vn -0.6944 0.0706 0.7161 +vn -0.6693 0.4159 -0.6157 +vn -0.7923 0.2733 -0.5455 +vn -0.8037 0.2572 -0.5365 +vn -0.9068 0.0647 -0.4166 +vn -0.0618 0.2224 -0.9730 +vn 0.4720 -0.3184 -0.8221 +vn 0.9108 0.3048 -0.2784 +vn -0.0023 1.0000 0.0045 +vn 0.0001 0.9999 -0.0120 +vn 0.0048 1.0000 -0.0054 +vn 0.0188 0.9998 0.0043 +vn 0.0069 0.9999 -0.0126 +vn -0.7546 0.0258 0.6556 +vn -0.7387 -0.0246 0.6735 +vn -0.9892 -0.0432 -0.1399 +vn -0.9892 -0.0427 -0.1400 +vn -0.9892 -0.0424 -0.1402 +vn -0.9892 -0.0422 -0.1403 +vn -0.9253 0.0035 0.3792 +vn -0.8958 0.0012 -0.4445 +vn -0.8104 0.0073 -0.5859 +vn -0.9897 -0.0175 -0.1419 +vn -0.9909 -0.0448 -0.1269 +vn -0.9908 -0.0511 -0.1251 +vn -0.9887 -0.0534 -0.1399 +vn -0.9887 -0.0507 -0.1408 +vn -0.9888 -0.0372 -0.1447 +vn -0.9887 -0.0334 -0.1458 +vn -0.9821 0.0701 -0.1750 +vn -0.9838 0.0545 -0.1707 +vn -0.9875 0.0070 -0.1574 +vn -0.9881 -0.0070 -0.1534 +vn -0.9887 -0.0535 -0.1399 +vn -0.9887 -0.0556 -0.1393 +vn -0.9885 -0.0640 -0.1369 +vn -0.9885 -0.0664 -0.1361 +vn -0.9872 -0.0974 -0.1265 +vn -0.9876 -0.0902 -0.1288 +vn -0.9886 -0.0610 -0.1375 +vn -0.9888 -0.0536 -0.1396 +vn -0.9873 -0.0061 -0.1589 +vn -0.9888 -0.0199 -0.1481 +vn -0.9894 -0.0263 -0.1431 +vn -0.9903 -0.0390 -0.1333 +vn -0.7642 0.0919 0.6384 +vn -0.1576 0.9810 -0.1133 +vn -0.0836 0.9928 -0.0857 +vn -0.0022 0.9985 -0.0549 +vn 0.7646 0.0507 0.6425 +vn 0.7820 0.0998 0.6153 +vn 0.7937 0.1375 0.5926 +vn 0.9740 -0.2259 -0.0164 +vn 0.7439 -0.0002 0.6683 +vn 0.8054 0.0136 -0.5925 +vn 0.8044 0.0099 -0.5940 +vn 0.8029 0.0044 -0.5961 +vn 0.8019 0.0009 -0.5975 +vn 0.0179 -0.9995 -0.0250 +vn 0.0198 -0.9995 -0.0257 +vn 0.0157 -0.9996 -0.0242 +vn -0.0744 -0.9968 0.0280 +vn 0.0214 -0.9994 -0.0266 +vn -0.0070 0.9929 -0.1188 +vn 0.0269 0.9944 0.1025 +vn -0.0018 0.9965 -0.0831 +vn -0.6656 0.0816 0.7419 +vn 0.0659 -0.1011 0.9927 +vn 0.8586 0.0841 0.5058 +vn 0.5593 0.0100 -0.8289 +vn 0.6853 -0.0384 -0.7272 +vn 0.6600 -0.0281 -0.7507 +vn 0.5108 0.0271 -0.8593 +vn -0.9176 0.0123 -0.3974 +vn -0.9574 0.0467 -0.2849 +vn -0.9521 0.0414 -0.3029 +vn -0.9077 0.0052 -0.4195 +vn -0.1599 0.9330 0.3224 +vn -0.0091 0.9885 0.1508 +vn 0.0223 0.9932 0.1141 +vn 0.8538 0.2531 0.4549 +vn 0.9029 0.1769 0.3918 +vn 0.8430 0.2950 0.4498 +vn 0.0306 0.9962 -0.0821 +vn -0.2170 0.8971 0.3849 +vn -0.2417 0.9612 -0.1326 +vn -0.5347 0.0957 0.8396 +vn -0.5835 0.0389 0.8112 +vn -0.5291 0.1019 0.8424 +vn -0.4916 0.1421 0.8591 +vn 0.3171 -0.1888 0.9294 +vn 0.8995 0.1803 0.3980 +vn 0.9553 0.0575 0.2900 +vn 0.6168 -0.1683 -0.7689 +vn 0.1917 0.3045 -0.9330 +vn -0.4623 0.0455 -0.8856 +vn -0.8063 0.2337 -0.5434 +vn -0.9796 -0.1133 -0.1661 +vn -0.6160 0.0321 0.7871 +vn 0.7320 -0.6203 -0.2816 +vn -0.1972 -0.7882 -0.5829 +vn -0.0370 0.9501 -0.3096 +vn -0.0282 -0.9980 0.0572 +vn -0.0164 -0.9992 -0.0376 +vn 0.0320 0.9863 -0.1619 +vn 0.0598 0.9979 0.0247 +vn 0.0373 0.9911 -0.1275 +vn -0.7403 0.0651 0.6691 +vn -0.8838 -0.0033 0.4679 +vn -0.8595 0.0105 0.5110 +vn -0.6928 0.0830 0.7163 +vn 0.8596 0.0751 0.5054 +vn 0.6739 0.0274 0.7383 +vn 0.7093 0.0355 0.7040 +vn 0.8838 0.0827 0.4606 +vn 0.9924 0.0119 -0.1221 +vn 0.4576 0.1042 -0.8830 +vn -0.2981 -0.0573 -0.9528 +vn -0.8738 0.0562 -0.4830 +vn 0.1659 0.9845 0.0567 +vn 0.1895 0.9793 -0.0707 +vn 0.1588 0.9832 0.0905 +vn 0.1293 0.9653 0.2267 +vn -0.2505 0.9574 -0.1438 +vn -0.1472 0.9886 0.0329 +vn -0.0886 0.9915 0.0954 +vn 0.0010 0.9926 -0.1217 +vn -0.0517 0.9886 -0.1412 +vn -0.8294 -0.0867 0.5519 +vn -0.5409 0.2814 0.7926 +vn 0.3110 0.1454 0.9392 +vn 0.1662 0.0647 0.9840 +vn 0.2912 0.1343 0.9472 +vn 0.4165 0.2048 0.8858 +vn 0.9145 -0.2599 0.3100 +vn 0.8309 0.3030 -0.4668 +vn 0.4069 0.0541 -0.9119 +vn 0.3581 -0.0168 -0.9335 +vn 0.3544 -0.0220 -0.9349 +vn 0.3172 -0.0731 -0.9455 +vn -0.8425 0.0892 -0.5313 +vn -0.8697 0.0337 -0.4925 +vn -0.8753 0.0208 -0.4832 +vn -0.8984 -0.0398 -0.4374 +vn -0.6113 -0.7656 -0.2004 +vn 0.2551 -0.2581 0.9318 +vn 0.3335 -0.5978 -0.7290 +vn 0.0041 0.9419 -0.3359 +vn -0.0255 -0.9994 0.0253 +vn 0.0375 -0.9993 -0.0091 +vn -0.0055 0.9997 0.0223 +vn -0.7270 -0.0340 0.6858 +vn -0.6828 -0.0153 0.7305 +vn -0.5139 0.0475 0.8565 +vn -0.4374 0.0726 0.8963 +vn 0.9764 -0.0213 0.2147 +vn 0.9171 0.0363 0.3971 +vn 0.9656 -0.0074 0.2600 +vn 0.9039 0.0455 0.4254 +vn 0.1427 0.0292 -0.9893 +vn -0.1130 0.0851 -0.9899 +vn -0.2221 0.1092 -0.9689 +vn -0.2945 0.1237 -0.9476 +vn -0.3000 0.1229 -0.9460 +vn 0.1411 0.9899 0.0147 +vn 0.0581 0.9909 -0.1216 +vn 0.0066 0.9888 -0.1490 +vn -0.0909 0.9757 -0.1992 +vn -0.1675 0.9568 -0.2376 +vn -0.0954 0.8356 0.5410 +vn -0.0977 0.9948 0.0287 +vn -0.9880 0.1544 -0.0022 +vn -0.9885 0.0091 0.1510 +vn -0.9872 0.0008 0.1595 +vn -0.9465 -0.1332 0.2940 +vn -0.1558 0.1372 0.9782 +vn -0.1128 0.0822 0.9902 +vn -0.0950 0.0596 0.9937 +vn -0.0433 -0.0059 0.9990 +vn 0.9415 -0.1089 0.3189 +vn 0.9846 0.1039 0.1404 +vn 0.9829 0.0694 0.1705 +vn 0.9627 0.2704 -0.0124 +vn 0.6304 0.0803 -0.7721 +vn 0.6052 0.1029 -0.7894 +vn 0.6283 0.0822 -0.7737 +vn 0.6551 0.0575 -0.7533 +vn -0.4961 -0.1063 -0.8617 +vn -0.5676 -0.0172 -0.8231 +vn -0.5643 -0.0223 -0.8253 +vn -0.6366 0.0791 -0.7672 +vn -0.8572 -0.4656 0.2202 +vn 0.3059 -0.7809 0.5446 +vn 0.5504 -0.4455 -0.7061 +vn -0.0245 -0.9984 0.0507 +vn -0.0151 -0.9986 -0.0514 +vn -0.0184 0.9993 -0.0333 +vn -0.9407 -0.0834 -0.3290 +vn -0.5886 0.0973 0.8025 +vn 0.1525 -0.0361 0.9876 +vn 0.9494 0.0920 0.3004 +vn 0.8516 -0.0804 -0.5179 +vn -0.3286 0.1284 -0.9357 +vn 0.2059 0.9567 -0.2057 +vn 0.1659 0.9859 -0.0202 +vn 0.2273 0.9418 -0.2478 +vn 0.1964 0.9729 0.1218 +vn -0.1936 0.8914 0.4099 +vn 0.0431 0.9857 0.1630 +vn -0.2483 0.8407 0.4813 +vn -0.2713 0.9484 -0.1643 +vn -0.2998 0.9340 -0.1945 +vn -0.1532 0.9873 -0.0431 +vn -0.1246 0.9921 -0.0141 +vn -0.8128 0.2038 -0.5457 +vn -0.8350 0.1666 -0.5244 +vn -0.8424 0.1533 -0.5165 +vn -0.8696 0.0997 -0.4836 +vn -0.8566 -0.1761 0.4850 +vn -0.4459 0.2494 0.8596 +vn 0.1091 -0.2003 0.9736 +vn 0.8260 0.1698 0.5375 +vn 0.9659 -0.2542 0.0496 +vn 0.6417 0.2635 -0.7203 +vn 0.1504 -0.2290 -0.9617 +vn -0.6558 -0.7537 -0.0425 +vn 0.3245 -0.4885 0.8100 +vn 0.3411 -0.5223 -0.7816 +vn -0.0049 -0.9996 0.0279 +vn 0.0016 -0.9999 -0.0162 +vn -0.0370 0.9984 0.0432 +vn -0.7754 0.0709 -0.6275 +vn -0.9933 -0.0430 0.1071 +vn -0.0679 0.0946 0.9932 +vn -0.6108 0.5501 0.5695 +vn -0.6796 0.2196 0.7000 +vn -0.7177 0.2480 0.6506 +vn 0.9378 -0.0916 0.3349 +vn 0.7786 0.1074 -0.6183 +vn -0.1333 -0.0306 -0.9906 +vn -0.0293 0.9908 -0.1324 +vn -0.0558 0.9860 -0.1569 +vn -0.1679 0.9661 -0.1963 +vn -0.1376 0.9889 -0.0570 +vn 0.0409 0.9985 0.0364 +vn 0.7200 0.5025 -0.4786 +vn 0.8214 0.1868 -0.5389 +vn 0.7759 0.0632 -0.6276 +vn -0.6876 0.2453 0.6833 +vn -0.1119 0.9936 0.0116 +vn -0.5933 0.0603 -0.8027 +vn -0.5729 0.0924 -0.8144 +vn -0.5670 0.1013 -0.8175 +vn -0.5388 0.1427 -0.8303 +vn -0.9743 -0.2157 0.0648 +vn -0.6468 0.1676 0.7440 +vn -0.5799 0.0956 0.8091 +vn 0.4226 0.1192 0.8985 +vn 0.5438 -0.0441 0.8381 +vn 0.5728 -0.0886 0.8149 +vn 0.6511 -0.2260 0.7246 +vn 0.7975 0.0857 -0.5972 +vn 0.7253 -0.0667 -0.6852 +vn -0.1944 -0.5482 -0.8135 +vn -0.2459 0.1117 0.9628 +vn 0.4754 -0.8797 -0.0141 +vn -0.0108 -0.9991 0.0417 +vn 0.0018 0.9992 0.0406 +vn -0.8962 0.0369 0.4422 +vn -0.9895 -0.0407 0.1388 +vn -0.8451 0.0613 0.5311 +vn 0.8184 0.0657 0.5709 +vn 0.5797 -0.0253 0.8145 +vn 0.6413 -0.0046 0.7673 +vn 0.8599 0.0860 0.5031 +vn 0.4891 -0.0552 -0.8705 +vn -0.1523 0.1053 -0.9827 +vn -0.9964 -0.0593 0.0613 +vn 0.0727 0.9924 0.0995 +vn 0.1037 0.9883 0.1119 +vn 0.2481 0.9635 0.1000 +vn 0.1268 0.9899 -0.0631 +vn -0.0945 0.9817 -0.1651 +vn -0.0973 0.9729 -0.2097 +vn -0.3013 0.8059 0.5096 +vn -0.1380 0.9904 -0.0115 +vn -0.1105 0.9938 0.0116 +vn -0.5740 -0.0060 0.8189 +vn -0.6179 -0.0795 0.7822 +vn -0.5505 0.0301 0.8343 +vn -0.5012 0.1008 0.8594 +vn 0.5690 -0.0877 0.8177 +vn 0.8519 0.2434 0.4637 +vn 0.9826 -0.1856 0.0084 +vn 0.2274 0.1073 -0.9679 +vn 0.2627 0.0592 -0.9631 +vn 0.2536 0.0716 -0.9647 +vn 0.2839 0.0295 -0.9584 +vn -0.8709 -0.0125 -0.4914 +vn -0.8490 -0.0588 -0.5251 +vn -0.8766 0.0010 -0.4812 +vn -0.8939 0.0463 -0.4458 +vn -0.6137 -0.7892 -0.0228 +vn -0.1319 -0.7818 0.6094 +vn 0.5343 -0.7768 0.3334 +vn 0.1489 -0.4691 -0.8705 +vn 0.0121 -0.9999 0.0034 +vn -0.0758 0.9969 -0.0222 +vn -0.7094 0.1107 0.6961 +vn -0.1772 -0.0129 0.9841 +vn 0.9979 0.0430 0.0478 +vn 0.9974 0.0390 0.0608 +vn 0.9938 0.0244 0.1083 +vn 0.9923 0.0200 0.1222 +vn -0.2017 0.0448 -0.9784 +vn -0.1041 0.0223 -0.9943 +vn -0.1235 0.0268 -0.9920 +vn -0.2208 0.0492 -0.9741 +vn -0.9986 -0.0245 -0.0468 +vn -0.1349 0.9746 0.1788 +vn -0.1599 0.9861 0.0458 +vn 0.0337 0.9835 0.1777 +vn 0.2169 0.9604 0.1752 +vn -0.2119 0.9680 -0.1348 +vn 0.1511 0.9874 0.0462 +vn 0.1227 0.9922 0.0232 +vn -0.0955 0.9861 -0.1360 +vn -0.0312 0.9917 -0.1249 +vn 0.2466 0.8001 -0.5469 +vn -0.8717 -0.3259 0.3661 +vn -0.4800 0.2338 0.8456 +vn 0.2516 -0.1823 0.9505 +vn 0.8380 0.2055 0.5056 +vn 0.8973 0.1085 0.4278 +vn 0.9108 0.0817 0.4047 +vn 0.9567 -0.0496 0.2868 +vn 0.5222 0.0712 -0.8499 +vn 0.6343 -0.0631 -0.7705 +vn 0.5026 0.0922 -0.8596 +vn 0.4031 0.1913 -0.8949 +vn -0.3658 -0.2156 -0.9054 +vn -0.8461 0.2672 -0.4613 +vn -0.7745 -0.5887 0.2313 +vn 0.2361 -0.7765 0.5842 +vn 0.6232 -0.7363 -0.2638 +vn -0.1426 -0.7972 -0.5866 +vn 0.0053 -1.0000 -0.0072 +vn 0.0058 0.9999 0.0137 +vn -0.7401 0.0557 0.6702 +vn -0.6736 0.0252 0.7387 +vn -0.7245 0.0486 0.6875 +vn -0.6565 0.0178 0.7541 +vn 0.9689 -0.0020 0.2476 +vn 0.9716 0.0016 0.2365 +vn 0.9802 0.0142 0.1974 +vn 0.9827 0.0183 0.1843 +vn -0.1647 0.0249 -0.9860 +vn -0.2876 -0.0121 -0.9577 +vn -0.1957 0.0157 -0.9805 +vn -0.3116 -0.0195 -0.9500 +vn -0.6723 0.7391 0.0412 +vn -0.0891 0.9909 0.1006 +vn -0.0836 0.9864 0.1418 +vn 0.0402 0.9809 0.1902 +vn 0.1142 0.9797 0.1648 +vn -0.0289 0.9938 -0.1076 +vn 0.1003 0.8098 -0.5780 +vn 0.1653 0.9854 0.0399 +vn 0.1529 0.9878 0.0311 +vn -0.7255 -0.2175 0.6530 +vn -0.1467 0.2155 0.9654 +vn 0.6678 -0.2739 0.6921 +vn 0.9292 0.2105 0.3038 +vn 0.6133 -0.2753 -0.7404 +vn 0.1583 0.3346 -0.9290 +vn -0.8031 -0.2945 -0.5180 +vn -0.9771 0.2061 0.0530 +vn 0.0618 0.0515 0.9968 +vn 0.4767 -0.7689 -0.4262 +vn -0.4662 -0.7367 -0.4899 +vn 0.0327 -0.9992 -0.0227 +vn -0.0268 -0.9996 -0.0015 +vn 0.0867 0.9957 -0.0319 +vn 0.1257 0.9908 -0.0494 +vn -0.0281 0.9994 0.0195 +vn -0.5072 -0.0478 -0.8605 +vn -0.8837 0.0703 -0.4627 +vn -0.2590 0.0136 0.9658 +vn -0.4585 -0.0431 0.8877 +vn -0.4224 -0.0326 0.9058 +vn -0.2081 0.0273 0.9777 +vn 0.9907 0.0199 0.1347 +vn 0.9983 -0.0308 -0.0498 +vn 0.9953 0.0095 0.0966 +vn 0.9958 -0.0398 -0.0828 +vn 0.2334 0.0342 -0.9718 +vn 0.0518 0.9931 -0.1052 +vn 0.0446 0.9924 -0.1144 +vn -0.1903 0.9816 0.0183 +vn -0.1161 0.9893 -0.0884 +vn -0.0881 0.9901 0.1095 +vn 0.0293 0.9864 0.1618 +vn 0.0968 0.9857 0.1376 +vn 0.1455 0.9894 0.0033 +vn -0.3481 0.2315 -0.9084 +vn -0.7923 -0.2132 -0.5717 +vn -0.9757 0.1769 0.1291 +vn -0.7757 -0.1616 0.6100 +vn -0.2535 0.1162 0.9603 +vn 0.2347 -0.2190 0.9471 +vn 0.7805 0.1635 0.6034 +vn 0.9882 -0.1493 -0.0331 +vn 0.8822 0.1620 -0.4421 +vn 0.3501 -0.2259 -0.9090 +vn -0.1918 -0.6033 -0.7741 +vn -0.0122 -0.7299 -0.6834 +vn -0.0152 -0.7282 -0.6852 +vn 0.1634 -0.8133 -0.5584 +vn -0.6300 -0.6416 0.4375 +vn -0.2507 0.4511 0.8565 +vn 0.9934 0.0993 0.0566 +vn 0.2699 0.9561 -0.1142 +vn -0.0018 -1.0000 -0.0065 +vn -0.0718 0.9959 0.0549 +vn -0.5152 0.0390 -0.8562 +vn -0.3898 0.0026 -0.9209 +vn -0.5484 0.0490 -0.8348 +vn -0.5645 -0.0218 0.8252 +vn -0.7683 0.0683 0.6365 +vn -0.6102 -0.0034 0.7923 +vn -0.8026 0.0864 0.5902 +vn 0.4631 -0.0385 0.8855 +vn 0.9955 0.0868 -0.0375 +vn 0.9649 0.0374 -0.2601 +vn 0.9940 0.0785 -0.0764 +vn 0.9515 0.0264 -0.3065 +vn -0.3584 -0.0061 -0.9335 +vn 0.0589 0.9931 -0.1011 +vn 0.0764 0.9917 -0.1031 +vn -0.0534 0.9907 -0.1252 +vn -0.1678 0.9848 -0.0456 +vn -0.0178 0.9966 0.0810 +vn -0.0098 0.9945 0.1044 +vn 0.1553 0.9820 0.1071 +vn 0.1428 0.9897 0.0137 +vn -0.1954 0.9806 0.0174 +vn -0.8638 -0.0381 -0.5024 +vn -0.8777 -0.0055 -0.4791 +vn -0.8623 -0.0414 -0.5047 +vn -0.8448 -0.0773 -0.5294 +vn -0.7773 0.1408 0.6131 +vn -0.7375 0.0519 0.6734 +vn -0.7207 0.0204 0.6930 +vn -0.6603 -0.0807 0.7467 +vn 0.5101 -0.1057 0.8536 +vn 0.6047 0.0418 0.7953 +vn 0.5769 -0.0051 0.8168 +vn 0.6532 0.1331 0.7454 +vn 0.8916 -0.0766 -0.4462 +vn 0.8873 -0.0857 -0.4531 +vn 0.8868 -0.0865 -0.4541 +vn 0.8831 -0.0940 -0.4597 +vn 0.0828 0.0341 -0.9960 +vn 0.0392 -0.0027 -0.9992 +vn 0.0441 0.0014 -0.9990 +vn -0.0032 -0.0384 -0.9993 +vn -0.4527 -0.4782 -0.7526 +vn 0.1629 -0.8143 -0.5572 +vn -0.7802 -0.4759 0.4060 +vn -0.1075 -0.7750 0.6227 +vn -0.0852 -0.7655 0.6378 +vn -0.1691 -0.7982 0.5782 +vn -0.0136 -0.7310 0.6822 +vn 0.9820 0.0638 -0.1779 +vn -0.0312 -0.9995 0.0037 +vn 0.0274 -0.9992 -0.0276 +vn 0.0255 0.9995 0.0199 +vn 0.0901 0.9959 -0.0040 +vn 0.0253 0.9995 0.0200 +vn -0.0415 0.9981 0.0446 +vn -0.9087 0.0189 -0.4170 +vn -0.9082 0.0192 -0.4181 +vn -0.9086 0.0189 -0.4172 +vn -0.9080 0.0193 -0.4186 +vn -0.3612 0.0168 0.9324 +vn -0.4036 0.0065 0.9149 +vn -0.3970 0.0081 0.9178 +vn -0.3537 0.0186 0.9352 +vn 0.8625 0.0167 0.5057 +vn 0.8753 0.0108 0.4834 +vn 0.8648 0.0157 0.5020 +vn 0.8773 0.0098 0.4798 +vn 0.4341 0.0102 -0.9008 +vn 0.4290 0.0116 -0.9032 +vn 0.4049 0.0182 -0.9142 +vn 0.3995 0.0197 -0.9165 +vn 0.0829 0.9795 0.1838 +vn 0.0040 0.9925 0.1218 +vn 0.1203 0.9918 0.0433 +vn 0.1930 0.9774 -0.0868 +vn -0.0241 0.9957 0.0898 +vn -0.0646 0.9692 -0.2375 +vn -0.0687 0.9940 -0.0849 +vn -0.0633 0.9971 -0.0414 +vn 0.0614 0.9892 -0.1330 +vn -0.5083 0.8239 0.2507 +vn -0.7878 -0.2610 -0.5579 +vn -0.8699 0.2537 0.4230 +vn -0.8349 0.1253 0.5359 +vn -0.8061 0.0557 0.5891 +vn -0.7162 -0.1025 0.6903 +vn 0.4485 0.0519 0.8923 +vn 0.4732 0.0171 0.8808 +vn 0.4848 0.0001 0.8746 +vn 0.5099 -0.0378 0.8594 +vn 0.9257 0.0289 -0.3772 +vn 0.9407 -0.0203 -0.3385 +vn 0.9207 0.0424 -0.3879 +vn 0.9030 0.0865 -0.4208 +vn 0.1282 -0.0919 -0.9875 +vn -0.2833 0.2197 -0.9335 +vn -0.4264 -0.5477 -0.7198 +vn -0.6249 -0.3771 0.6836 +vn -0.1855 -0.7508 0.6340 +vn 0.9390 0.3319 -0.0898 +vn 0.1650 -0.8093 -0.5637 +vn -0.0118 -0.9997 0.0192 +vn 0.0159 -0.9992 -0.0358 +vn -0.0760 0.9953 0.0603 +vn -0.0866 0.9939 0.0678 +vn 0.0698 0.9967 -0.0426 +vn -0.1862 0.0158 0.9824 +vn -0.1727 0.0199 0.9848 +vn -0.1093 0.0396 0.9932 +vn -0.0949 0.0440 0.9945 +vn 0.9974 0.0702 0.0179 +vn 0.9970 0.0645 0.0427 +vn 0.9861 0.0362 0.1622 +vn 0.9808 0.0287 0.1929 +vn 0.0999 0.0215 -0.9948 +vn 0.1597 0.0063 -0.9871 +vn 0.1496 0.0089 -0.9887 +vn 0.0883 0.0245 -0.9958 +vn -0.9820 0.0299 -0.1863 +vn -0.9996 -0.0134 -0.0266 +vn -0.9873 0.0219 -0.1571 +vn -0.9998 -0.0213 0.0026 +vn 0.1688 0.9843 0.0507 +vn 0.1326 0.9888 -0.0679 +vn 0.1136 0.9893 -0.0920 +vn -0.1626 0.9709 -0.1760 +vn -0.1620 0.9864 -0.0275 +vn -0.0709 0.9935 0.0890 +vn -0.2350 0.9705 0.0540 +vn 0.0189 0.9916 0.1279 +vn -0.0186 0.9828 -0.1837 +vn -0.9603 -0.1643 0.2253 +vn -0.9483 -0.0608 0.3116 +vn -0.9534 -0.0900 0.2880 +vn -0.9255 0.0246 0.3779 +vn 0.2363 0.0132 0.9716 +vn 0.1852 0.0666 0.9804 +vn 0.1811 0.0708 0.9809 +vn 0.1335 0.1193 0.9838 +vn 0.9185 0.1519 0.3651 +vn 0.9160 0.1446 0.3742 +vn 0.9183 0.1514 0.3657 +vn 0.9204 0.1578 0.3576 +vn 0.8045 -0.1656 -0.5704 +vn 0.4324 0.1778 -0.8840 +vn -0.3073 -0.2036 -0.9296 +vn -0.4955 -0.0416 -0.8676 +vn -0.4685 -0.0669 -0.8809 +vn -0.6417 0.1123 -0.7586 +vn -0.5468 -0.8048 -0.2308 +vn -0.1897 -0.4441 0.8756 +vn 0.6189 -0.2459 -0.7460 +vn -0.2263 0.9597 0.1663 +vn 0.0039 -0.9995 -0.0310 +vn -0.0155 -0.9993 0.0328 +vn -0.0065 0.9989 -0.0466 +vn -0.1459 0.1302 -0.9807 +vn -0.9948 -0.1021 -0.0069 +vn -0.6741 0.1551 0.7222 +vn 0.6091 -0.0860 0.7884 +vn 0.9299 0.0898 0.3566 +vn 0.3673 -0.0350 -0.9295 +vn 0.2848 0.9586 -0.0032 +vn 0.1221 0.9848 0.1231 +vn 0.1227 0.9850 -0.1217 +vn -0.0509 0.9866 -0.1550 +vn 0.0363 0.9137 0.4048 +vn -0.1034 0.9883 -0.1119 +vn 0.0208 0.8687 0.4949 +vn -0.2057 0.9785 -0.0133 +vn -0.2138 0.9768 -0.0110 +vn 0.0731 0.2803 -0.9571 +vn -0.6085 -0.2377 -0.7571 +vn -0.9730 0.2271 -0.0402 +vn -0.9904 0.1002 0.0956 +vn -0.9889 0.0621 0.1350 +vn -0.9470 -0.1071 0.3029 +vn 0.0255 0.0232 0.9994 +vn 0.0214 0.0173 0.9996 +vn 0.0273 0.0257 0.9993 +vn 0.0312 0.0311 0.9990 +vn 0.9969 0.0058 0.0788 +vn 0.9937 0.0409 0.1041 +vn 0.9925 0.0507 0.1111 +vn 0.9859 0.0913 0.1401 +vn 0.5845 -0.1794 -0.7913 +vn 0.4710 -0.4067 -0.7828 +vn -0.6050 -0.7912 -0.0893 +vn 0.0783 -0.4486 0.8903 +vn -0.0088 -1.0000 -0.0010 +vn 0.0311 -0.9995 0.0013 +vn 0.0261 0.9975 -0.0663 +vn -0.6937 0.0597 0.7178 +vn -0.9117 -0.0121 0.4107 +vn -0.8832 0.0004 0.4690 +vn -0.6300 0.0748 0.7730 +vn 0.6639 -0.0502 0.7461 +vn 0.9767 0.1585 0.1448 +vn 0.4048 -0.0038 -0.9144 +vn 0.1735 -0.0100 -0.9848 +vn 0.0767 -0.0125 -0.9970 +vn -0.0788 -0.0161 -0.9968 +vn -0.5633 0.1282 -0.8162 +vn -0.1218 0.9924 0.0147 +vn 0.0920 0.9780 -0.1874 +vn -0.0097 0.9917 -0.1282 +vn -0.0405 0.9931 -0.1097 +vn 0.1497 0.9639 -0.2204 +vn 0.0656 0.9971 0.0389 +vn -0.1386 0.7986 0.5856 +vn -0.4162 -0.0520 0.9078 +vn -0.5261 -0.1982 0.8270 +vn -0.3493 0.0285 0.9366 +vn -0.2178 0.1734 0.9605 +vn 0.7950 -0.2508 0.5524 +vn 0.9638 0.2178 0.1539 +vn 0.6917 0.0450 -0.7208 +vn 0.6958 0.0523 -0.7163 +vn 0.6958 0.0523 -0.7164 +vn 0.6993 0.0600 -0.7123 +vn -0.1491 -0.1269 -0.9806 +vn -0.6413 0.1945 -0.7423 +vn -0.8012 0.1157 -0.5872 +vn -0.8487 0.1748 -0.4992 +vn -0.9309 0.1437 -0.3359 +vn -0.9543 0.2410 -0.1768 +vn -0.9388 -0.3442 -0.0104 +vn 0.0769 -0.8093 0.5823 +vn 0.8913 -0.2631 -0.3692 +vn -0.0152 -0.9978 0.0646 +vn -0.0038 -0.9991 -0.0433 +vn 0.0855 0.9957 -0.0353 +vn 0.1132 0.9924 -0.0487 +vn -0.0749 0.9961 0.0457 +vn -0.2769 0.0547 0.9593 +vn 0.0925 -0.0349 0.9951 +vn -0.1922 0.0340 0.9808 +vn 0.1530 -0.0493 0.9870 +vn 0.9768 0.0741 0.2008 +vn 0.8511 -0.0700 -0.5203 +vn 0.1593 0.0630 -0.9852 +vn -0.9235 -0.0075 -0.3835 +vn -0.8837 -0.0335 -0.4668 +vn -0.8918 -0.0287 -0.4516 +vn -0.9334 -0.0000 -0.3590 +vn 0.0344 0.9879 0.1515 +vn 0.0423 0.9860 0.1613 +vn 0.1808 0.9821 0.0530 +vn 0.1584 0.9812 0.1107 +vn -0.7491 0.5550 0.3617 +vn -0.8753 0.2452 0.4169 +vn -0.8204 0.0861 0.5653 +vn -0.0749 0.9963 -0.0432 +vn -0.2173 0.4435 -0.8695 +vn -0.2297 0.3291 -0.9159 +vn -0.2302 0.3233 -0.9179 +vn 0.1432 0.9880 -0.0571 +vn 0.1116 0.9920 -0.0590 +vn -0.8424 0.0959 0.5302 +vn -0.7253 -0.1090 0.6797 +vn 0.3375 0.0929 0.9367 +vn 0.3619 0.0648 0.9300 +vn 0.3635 0.0630 0.9295 +vn 0.3929 0.0281 0.9192 +vn 0.9671 -0.1602 0.1975 +vn 0.9635 0.2023 -0.1751 +vn 0.3889 -0.2100 -0.8970 +vn -0.2312 0.3123 -0.9214 +vn -0.7644 -0.2576 -0.5910 +vn -0.6112 -0.7810 -0.1286 +vn 0.2581 -0.3133 0.9139 +vn 0.2797 -0.5206 -0.8067 +vn 0.2694 0.9544 -0.1285 +vn 0.0348 -0.9992 -0.0201 +vn -0.0483 0.9968 -0.0633 +vn 0.0548 0.1229 -0.9909 +vn -0.8621 -0.0945 -0.4978 +vn -0.8547 0.1115 0.5070 +vn 0.0099 -0.0509 0.9987 +vn 0.8494 0.1004 0.5181 +vn 0.9181 -0.0626 -0.3914 +vn 0.0533 0.9676 -0.2469 +vn -0.1144 0.9907 -0.0738 +vn -0.0973 0.9944 -0.0413 +vn -0.0445 0.9594 -0.2785 +vn -0.6604 0.0845 0.7461 +vn -0.7014 0.1239 0.7019 +vn -0.6503 0.1965 0.7338 +vn 0.1352 0.9875 -0.0810 +vn 0.1171 0.9927 -0.0275 +vn 0.0082 0.9966 0.0821 +vn 0.5951 0.7442 0.3035 +vn 0.8232 0.3720 0.4289 +vn 0.8264 0.3625 0.4308 +vn -0.0082 -0.1431 -0.9897 +vn -0.6805 0.1139 -0.7238 +vn -0.7567 0.0163 -0.6536 +vn -0.7700 -0.0031 -0.6381 +vn -0.8347 -0.1150 -0.5386 +vn -0.7485 0.0560 0.6608 +vn -0.6868 0.1522 0.7108 +vn 0.3559 -0.2655 0.8960 +vn 0.8416 0.3139 0.4394 +vn 0.9308 -0.2562 -0.2606 +vn 0.5132 0.2044 -0.8336 +vn -0.2240 -0.7792 -0.5854 +vn -0.6282 -0.4395 0.6420 +vn 0.5127 -0.7857 0.3462 +vn 0.4604 -0.7862 -0.4122 +vn 0.0094 -0.9999 0.0097 +vn -0.0171 -0.9998 -0.0088 +vn -0.0378 0.9991 0.0170 +vn -0.4465 0.0731 -0.8918 +vn -0.1837 0.0117 -0.9829 +vn -0.5066 0.0876 -0.8577 +vn -0.9817 -0.0422 0.1859 +vn -0.4837 0.0998 0.8695 +vn -0.2085 0.0509 0.9767 +vn -0.4400 0.0921 0.8933 +vn -0.1516 0.0406 0.9876 +vn 0.9985 0.0454 -0.0318 +vn 0.9984 0.0458 -0.0334 +vn 0.9984 0.0457 -0.0330 +vn 0.9985 0.0453 -0.0317 +vn -0.1139 -0.0043 -0.9935 +vn 0.1261 0.9915 0.0312 +vn 0.1168 0.9914 -0.0592 +vn 0.0819 0.9577 -0.2758 +vn -0.0906 0.9929 -0.0777 +vn -0.1198 0.9923 -0.0306 +vn -0.1044 0.9849 0.1382 +vn -0.1114 0.9849 0.1325 +vn 0.0125 0.9721 0.2343 +vn -0.9971 0.0352 0.0668 +vn -0.9913 0.0826 0.1025 +vn -0.9935 0.0676 0.0914 +vn -0.9862 0.1104 0.1231 +vn -0.1456 -0.1259 0.9813 +vn 0.0173 0.0511 0.9985 +vn -0.0003 0.0316 0.9995 +vn 0.1743 0.2190 0.9600 +vn 0.8945 0.1735 0.4121 +vn 0.8815 0.1432 0.4500 +vn 0.8949 0.1746 0.4107 +vn 0.9044 0.2010 0.3764 +vn 0.7960 -0.2602 -0.5465 +vn 0.1088 0.2919 -0.9503 +vn -0.2645 -0.1009 -0.9591 +vn -0.3358 -0.4919 -0.8032 +vn -0.5004 -0.7884 0.3578 +vn 0.7832 -0.3429 0.5187 +vn 0.0086 -1.0000 -0.0003 +vn -0.0192 0.9966 -0.0804 +vn -0.9658 0.0682 -0.2500 +vn -0.9947 0.0173 -0.1011 +vn -0.9780 0.0519 -0.2023 +vn -0.9978 0.0056 -0.0666 +vn 0.4022 0.1066 0.9093 +vn 0.2489 0.0864 0.9647 +vn 0.2766 0.0902 0.9568 +vn 0.4191 0.1088 0.9014 +vn 0.9019 -0.0261 0.4311 +vn 0.6715 0.0813 -0.7365 +vn 0.4771 0.0295 -0.8784 +vn 0.6359 0.0713 -0.7685 +vn 0.4383 0.0198 -0.8986 +vn 0.1637 0.9854 -0.0473 +vn 0.1464 0.9855 -0.0855 +vn 0.0496 0.9801 -0.1923 +vn 0.0557 0.9767 0.2074 +vn 0.0140 0.9552 0.2956 +vn 0.1190 0.9865 0.1123 +vn -0.0578 0.9983 -0.0030 +vn -0.7961 0.0486 0.6033 +vn -0.7328 -0.0391 0.6793 +vn -0.7225 -0.0519 0.6894 +vn -0.6628 -0.1197 0.7392 +vn -0.0505 0.2210 0.9740 +vn 0.7795 -0.2837 0.5584 +vn 0.9623 0.1994 0.1852 +vn 0.4353 -0.1505 -0.8876 +vn 0.2808 0.0394 -0.9590 +vn 0.3189 -0.0052 -0.9478 +vn 0.1356 0.1984 -0.9707 +vn -0.7358 0.0123 -0.6771 +vn -0.7746 0.0725 -0.6283 +vn -0.7335 0.0089 -0.6797 +vn -0.6796 -0.0630 -0.7309 +vn -0.9789 0.1239 0.1623 +vn 0.4921 -0.7724 0.4014 +vn 0.4465 -0.7427 -0.4990 +vn 0.0332 -0.9994 0.0101 +vn 0.0321 0.9994 -0.0101 +vn -0.5923 0.0826 -0.8015 +vn -0.9327 -0.0329 0.3591 +vn -0.5777 0.0817 0.8121 +vn 0.6724 -0.0699 0.7369 +vn 0.9900 0.1237 -0.0683 +vn 0.1879 -0.0874 -0.9783 +vn 0.1643 0.9859 -0.0326 +vn 0.0267 0.9898 -0.1396 +vn -0.1126 0.9818 -0.1526 +vn 0.2139 0.9767 -0.0174 +vn -0.1322 0.9909 -0.0243 +vn -0.1646 0.9701 0.1785 +vn 0.0177 0.9933 0.1142 +vn -0.9648 -0.1959 0.1752 +vn -0.7113 0.3290 0.6211 +vn -0.1757 -0.1947 0.9650 +vn 0.7686 0.0714 0.6357 +vn 0.7922 0.1266 0.5970 +vn 0.7886 0.1177 0.6035 +vn 0.8047 0.1601 0.5718 +vn 0.8828 -0.1527 -0.4443 +vn 0.8139 -0.0133 -0.5808 +vn 0.8261 -0.0336 -0.5625 +vn 0.7247 0.1098 -0.6803 +vn -0.3754 -0.0240 -0.9266 +vn -0.2965 -0.1199 -0.9475 +vn -0.4126 0.0240 -0.9106 +vn -0.4798 0.1165 -0.8696 +vn 0.1562 -0.5621 -0.8122 +vn -0.8177 -0.5701 0.0795 +vn -0.9135 -0.4053 -0.0356 +vn -0.8678 -0.4963 0.0258 +vn -0.7077 -0.6853 0.1721 +vn 0.2815 -0.2979 0.9122 +vn 0.6505 -0.7492 -0.1245 +vn 0.6591 -0.7385 -0.1421 +vn 0.6589 -0.7390 -0.1408 +vn 0.6690 -0.7251 -0.1630 +vn -0.0599 -0.9982 -0.0069 +vn 0.0335 -0.9994 -0.0129 +vn 0.0256 0.9993 0.0288 +vn -0.4486 0.0186 0.8935 +vn -0.4351 0.0226 0.9001 +vn -0.3793 0.0389 0.9245 +vn -0.3644 0.0432 0.9302 +vn 0.9999 -0.0116 -0.0017 +vn 0.9603 0.0769 0.2682 +vn 0.9984 0.0073 0.0560 +vn 0.9417 0.0951 0.3229 +vn 0.2914 -0.0427 -0.9556 +vn -0.6093 0.1147 -0.7846 +vn -0.9358 0.0069 -0.3524 +vn 0.0661 0.9610 0.2686 +vn 0.1458 0.9831 0.1112 +vn 0.2460 0.9687 -0.0326 +vn -0.2915 0.9531 0.0817 +vn -0.0976 0.9837 0.1508 +vn -0.1367 0.9894 -0.0484 +vn -0.1869 0.9821 -0.0226 +vn -0.1691 0.7831 -0.5984 +vn 0.1030 0.9922 -0.0704 +vn 0.0364 0.9960 -0.0812 +vn -0.9413 0.2427 0.2345 +vn -0.7738 -0.1127 0.6234 +vn 0.0759 0.0236 0.9968 +vn -0.0044 -0.0646 0.9979 +vn 0.0883 0.0374 0.9954 +vn 0.1544 0.1108 0.9818 +vn 0.9424 -0.1242 0.3106 +vn 0.9653 0.2512 -0.0713 +vn 0.4940 -0.3026 -0.8151 +vn -0.2509 0.3050 -0.9187 +vn -0.7992 -0.2547 -0.5444 +vn -0.8745 -0.3085 0.3742 +vn 0.8675 -0.4809 0.1276 +vn 0.0022 -0.7864 -0.6178 +vn 0.3904 -0.0782 -0.9173 +vn 0.7418 -0.0529 0.6685 +vn 0.6658 -0.2095 0.7161 +vn 0.7279 -0.0971 0.6788 +vn 0.5844 0.1442 0.7985 +vn 0.5690 0.1913 0.7998 +vn 0.2934 -0.3428 0.8924 +vn 0.2913 -0.3161 0.9029 +vn 0.1241 0.0798 0.9890 +vn 0.1410 0.1016 0.9848 +vn 0.0106 0.1326 0.9911 +vn -0.1624 -0.3728 0.9136 +vn -0.1736 -0.3396 0.9244 +vn -0.3453 -0.0613 0.9365 +vn -0.4902 -0.1800 0.8528 +vn -0.6978 -0.1738 0.6949 +vn -0.6988 -0.1652 0.6960 +vn -0.8948 -0.1551 0.4186 +vn -0.8901 -0.1245 0.4385 +vn -0.8868 -0.4243 0.1829 +vn -0.8751 -0.4525 0.1718 +vn -0.9313 0.3509 -0.0977 +vn -0.8702 -0.4225 -0.2535 +vn -0.8152 0.2191 -0.5362 +vn -0.7156 -0.3074 -0.6272 +vn -0.7120 -0.2509 -0.6558 +vn -0.6079 0.0204 -0.7938 +vn -0.4354 -0.2142 -0.8744 +vn -0.1844 -0.0631 -0.9808 +vn -0.1914 -0.0494 -0.9803 +vn 0.2038 -0.1104 -0.9728 +vn 0.1945 -0.1078 -0.9750 +vn 0.5323 -0.0308 -0.8460 +vn 0.6209 -0.0695 -0.7808 +vn 0.7289 -0.0233 -0.6842 +vn 0.7319 -0.0042 -0.6814 +vn 0.8615 -0.4413 -0.2511 +vn 0.8682 -0.4118 -0.2768 +vn 0.8780 -0.3462 -0.3305 +vn -0.0874 0.2028 -0.9753 +vn -0.2425 -0.9638 -0.1108 +vn -0.7224 -0.5211 -0.4546 +vn -0.4577 -0.8476 -0.2685 +vn -0.7310 -0.3606 -0.5793 +vn -0.7015 0.2254 0.6760 +vn -0.1075 -0.5156 0.8501 +vn 0.6394 0.2600 0.7235 +vn 0.8500 -0.4811 -0.2148 +vn 0.3973 -0.0912 0.9132 +vn 0.1011 0.0446 -0.9939 +vn 0.1137 0.0741 -0.9907 +vn 0.0724 -0.0902 -0.9933 +vn 0.1905 -0.0161 -0.9815 +vn 0.1551 0.0516 0.9866 +vn -0.0138 -0.1532 0.9881 +vn 0.1215 0.0817 0.9892 +vn 0.1329 0.1084 0.9852 +vn -0.7163 -0.0082 -0.6977 +vn -0.6091 -0.1212 -0.7838 +vn -0.6135 -0.1677 -0.7717 +vn -0.6651 -0.1377 -0.7340 +vn -0.7905 -0.0205 -0.6121 +vn -0.8775 -0.1687 -0.4490 +vn -0.9225 -0.1890 -0.3367 +vn -0.9209 -0.1124 -0.3732 +vn -0.8800 -0.0337 -0.4737 +vn -0.8852 0.0153 0.4650 +vn -0.9333 -0.1106 0.3416 +vn -0.9005 -0.0476 0.4323 +vn -0.9144 -0.0269 0.4039 +vn -0.7380 -0.1622 0.6550 +vn -0.6642 -0.1303 0.7361 +vn -0.6302 -0.0897 0.7712 +vn -0.7218 -0.0015 0.6921 +vn -0.8912 0.1360 -0.4326 +vn -0.8973 0.1073 -0.4282 +vn -0.8075 -0.0325 -0.5889 +vn -0.8510 -0.0905 -0.5173 +vn -0.7150 -0.2145 -0.6654 +vn -0.7091 -0.2854 -0.6448 +vn -0.4884 0.1991 -0.8496 +vn -0.3328 -0.3565 -0.8730 +vn -0.1160 0.3155 -0.9418 +vn 0.0566 -0.3623 -0.9303 +vn 0.2814 0.1969 -0.9392 +vn 0.4277 -0.4004 -0.8104 +vn 0.4480 -0.3624 -0.8173 +vn 0.6009 -0.1765 -0.7796 +vn 0.5650 -0.0320 -0.8245 +vn 0.7071 -0.3101 -0.6355 +vn 0.9170 -0.1295 -0.3772 +vn 0.8817 -0.1027 -0.4605 +vn 0.9259 -0.3514 -0.1386 +vn 0.9965 -0.0604 0.0572 +vn 0.9659 -0.1506 0.2107 +vn 0.8896 -0.3173 0.3286 +vn 0.8420 -0.2073 0.4981 +vn 0.7447 -0.2707 0.6100 +vn 0.5496 -0.1525 0.8214 +vn 0.6607 -0.2392 0.7116 +vn 0.3909 -0.2448 0.8873 +vn 0.1959 -0.0787 0.9775 +vn 0.1101 -0.0824 0.9905 +vn -0.0398 -0.3000 0.9531 +vn -0.0432 -0.3152 0.9480 +vn -0.3094 0.2200 0.9251 +vn -0.4299 -0.3069 0.8491 +vn -0.6086 0.2877 0.7395 +vn -0.7166 -0.3336 0.6126 +vn -0.7653 -0.2596 0.5891 +vn -0.8834 0.0223 0.4681 +vn -0.8993 0.0645 0.4326 +vn -0.8992 0.0599 0.4334 +vn -0.8454 -0.0027 -0.5341 +vn -0.8440 0.0039 -0.5364 +vn -0.8369 0.0122 0.5473 +vn -0.8434 0.0349 0.5361 +vn 0.2380 -0.0084 -0.9712 +vn 0.2424 0.0033 -0.9702 +vn -0.7753 0.0342 -0.6306 +vn -0.7806 0.0203 -0.6247 +vn -0.7733 0.0352 0.6330 +vn -0.7789 0.0205 0.6268 +vn 0.2414 0.0403 0.9696 +vn 0.2622 0.0023 0.9650 +vn 0.0048 -1.0000 -0.0026 +vn 0.0107 -0.9999 -0.0022 +vn 0.0120 -0.9999 -0.0046 +vn 0.0223 -0.9990 -0.0384 +vn 0.0184 -0.9936 0.1113 +vn -0.0069 -0.9861 0.1658 +vn 0.0411 -0.9890 0.1420 +vn -0.0121 -0.9999 -0.0104 +vn -0.0137 -0.9999 -0.0059 +vn -0.0149 -0.9999 -0.0066 +vn -0.0705 -0.9937 -0.0869 +vn -0.0681 -0.9969 -0.0399 +vn -0.0690 -0.9962 -0.0532 +vn -0.0338 -0.9979 -0.0544 +vn 0.0152 -0.9997 0.0196 +vn 0.0190 -0.9998 0.0111 +vn 0.0078 -1.0000 0.0028 +vn 0.0247 -0.9995 0.0200 +vn 0.0086 -0.9998 0.0186 +vn -0.0327 -0.9994 -0.0096 +vn 0.1360 0.0075 0.9907 +vn 0.1053 0.0018 0.9944 +vn -0.1184 0.0188 0.9928 +vn -0.1695 0.0029 0.9855 +vn -0.1186 -0.0950 0.9884 +vn -0.1966 -0.0575 0.9788 +vn -0.0508 -0.2545 -0.9657 +vn -0.0440 -0.2248 -0.9734 +vn 0.0052 -0.0102 -0.9999 +vn 0.0143 0.0295 -0.9995 +vn 0.8134 -0.0172 0.5814 +vn 0.7978 0.0536 0.6006 +vn 0.7225 0.2666 0.6380 +vn 0.7002 0.3128 0.6418 +vn 0.9041 -0.0620 -0.4228 +vn 0.9340 -0.0012 -0.3572 +vn 0.9308 -0.0087 -0.3655 +vn 0.9535 0.0525 -0.2968 +vn -0.1415 0.1256 -0.9820 +vn -0.1310 0.0849 -0.9877 +vn -0.1334 0.1377 -0.9815 +vn -0.1414 0.1358 -0.9806 +vn 0.0784 0.0352 -0.9963 +vn 0.1578 -0.0025 -0.9875 +vn 0.7196 0.2661 -0.6414 +vn 0.6941 0.3182 -0.6457 +vn 0.8027 0.0247 -0.5959 +vn 0.8170 -0.0473 -0.5747 +vn 0.9796 0.1396 0.1446 +vn 0.8103 -0.1735 0.5597 +vn 0.0012 0.0975 0.9952 +vn -0.0052 0.1261 0.9920 +vn -0.0320 0.2458 0.9688 +vn -0.0358 0.2627 0.9642 +vn -0.0818 0.2617 -0.9617 +vn 0.0036 -0.1790 -0.9839 +vn -0.1336 0.0180 0.9909 +vn -0.1312 0.0445 0.9904 +vn 0.8811 -0.0628 -0.4687 +vn 0.9144 -0.1284 -0.3839 +vn 0.8995 -0.0885 -0.4278 +vn 0.8771 -0.0735 -0.4747 +vn 0.7193 -0.0168 -0.6945 +vn 0.6770 -0.0322 -0.7353 +vn 0.6646 -0.0949 -0.7411 +vn 0.7310 -0.0465 -0.6808 +vn 0.7210 0.0202 0.6926 +vn 0.5993 -0.1479 0.7868 +vn 0.7400 -0.0140 0.6725 +vn 0.7793 -0.0014 0.6266 +vn 0.9177 0.0158 0.3970 +vn 0.9312 0.0345 0.3630 +vn 0.9024 -0.0074 0.4309 +vn 0.9136 0.2022 0.3528 +vn 0.8369 0.0122 -0.5472 +vn 0.8333 0.0006 -0.5528 +vn 0.8391 -0.0028 0.5440 +vn 0.8392 -0.0034 0.5438 +vn -0.0192 -0.9998 -0.0002 +vn -0.0070 -1.0000 -0.0012 +vn -0.0159 -0.9999 -0.0005 +vn -0.0009 -1.0000 -0.0011 +vn 0.0138 -0.9987 -0.0490 +vn 0.0184 -0.9992 -0.0367 +vn -0.0025 -1.0000 -0.0016 +vn 0.0094 -0.9998 0.0195 +vn 0.0006 -0.9999 0.0133 +vn 0.0491 -0.9969 0.0617 +vn -0.0098 -1.0000 -0.0012 +vn -0.0131 -0.9999 0.0089 +vn -0.0098 -0.9999 0.0035 +vn -0.2509 0.0230 -0.9677 +vn -0.2622 0.0023 -0.9650 +vn 0.7808 0.0153 -0.6245 +vn 0.7789 0.0205 -0.6268 +vn 0.7722 0.0421 0.6339 +vn 0.7806 0.0205 0.6247 +vn -0.2283 -0.0082 0.9736 +vn -0.2377 0.0086 0.9713 +vn -0.0722 -0.9974 -0.0068 +vn 0.0040 -1.0000 -0.0035 +vn -0.0047 -1.0000 0.0034 +vn -0.0128 -0.9998 0.0140 +vn -0.0001 -1.0000 0.0044 +vn -0.0245 -0.9966 0.0789 +vn -0.0278 -0.9888 0.1469 +vn -0.0060 -0.9854 0.1704 +vn -0.0714 -0.9920 -0.1043 +vn -0.0137 -0.9833 0.1814 +vn 0.0123 -0.9823 0.1869 +vn -0.0008 -1.0000 0.0015 +vn -0.8769 -0.0259 0.4800 +vn -0.8903 -0.1448 0.4318 +vn -0.8826 -0.0630 0.4658 +vn -0.8913 -0.1758 0.4179 +vn -0.7219 0.2217 -0.6555 +vn -0.8786 0.1838 -0.4407 +vn -0.8746 0.1224 -0.4691 +vn -0.8779 0.1662 -0.4491 +vn -0.8725 0.1029 -0.4776 +vn -0.7219 -0.2217 0.6555 +vn 0.8759 -0.3680 -0.3120 +vn 0.6144 0.1550 -0.7736 +vn -0.2019 -0.3266 -0.9234 +vn -0.6128 0.1176 -0.7815 +vn -0.9419 -0.2795 0.1863 +vn -0.9190 -0.3800 0.1047 +vn -0.9437 -0.2381 0.2295 +vn -0.9219 0.1893 0.3379 +vn -0.0949 0.0786 0.9924 +vn 0.2898 -0.4621 0.8382 +vn 0.9566 0.0421 0.2884 +vn 0.9296 -0.0317 0.3672 +vn 0.9475 -0.0088 0.3195 +vn 0.9862 -0.0643 0.1524 +vn 0.9738 -0.1114 0.1981 +vn -0.1044 -0.0025 -0.9945 +vn -0.0893 -0.0228 -0.9957 +vn -0.1116 0.0071 -0.9937 +vn -0.1265 0.0273 -0.9916 +vn 0.9565 0.2777 0.0896 +vn 0.1683 -0.7714 0.6137 +vn 0.8146 0.0049 0.5801 +vn 0.9787 -0.0955 -0.1816 +vn 0.9881 -0.0556 -0.1431 +vn 0.9882 -0.0553 -0.1428 +vn 0.9943 -0.0166 -0.1050 +vn 0.9951 -0.0085 0.0988 +vn 0.9945 0.1049 0.0022 +vn 0.9769 0.1985 -0.0790 +vn 0.9701 -0.1336 0.2029 +vn 0.7264 -0.3685 -0.5801 +vn 0.2671 0.0138 -0.9636 +vn -0.2324 0.0732 0.9699 +vn -0.0880 0.2272 0.9699 +vn -0.2802 0.0189 0.9598 +vn -0.4206 -0.1526 0.8943 +vn 0.2534 -0.0231 0.9671 +vn 0.3213 0.0778 0.9438 +vn 0.3993 0.2021 0.8943 +vn 0.1562 -0.1577 0.9751 +vn 0.8832 -0.2054 -0.4215 +vn -0.2097 -0.2700 -0.9398 +vn 0.4518 0.3044 -0.8386 +vn -0.7846 0.5808 0.2170 +vn -0.5473 0.7464 0.3786 +vn -0.5068 0.7258 0.4652 +vn -0.4774 0.7079 0.5205 +vn -0.4355 0.6667 0.6049 +vn -0.4358 0.6662 0.6052 +vn -0.5700 0.6923 0.4426 +vn -0.2851 0.9579 -0.0350 +vn -0.6039 0.6853 0.4071 +vn -0.1067 0.9499 0.2939 +vn 0.2007 0.6845 0.7008 +vn 0.2479 0.9506 0.1869 +vn -0.5996 0.6898 -0.4059 +vn -0.0437 0.9601 -0.2763 +vn -0.0267 0.5939 0.8041 +vn -0.4148 0.6921 -0.5907 +vn -0.4509 0.5917 -0.6682 +vn -0.3392 0.8315 -0.4399 +vn -0.3338 0.8391 -0.4296 +vn -0.7670 0.1383 -0.6265 +vn -0.0449 0.9988 -0.0187 +vn -0.4488 0.8772 -0.1704 +vn -0.1042 0.9942 -0.0250 +vn -0.7220 0.6553 -0.2219 +vn 0.1684 0.7348 0.6571 +vn 0.1863 0.7676 0.6133 +vn 0.0551 0.5169 0.8543 +vn -0.0435 0.7762 0.6290 +vn -0.1913 0.6267 0.7555 +vn -0.2293 0.5767 0.7841 +vn -0.5700 0.6908 -0.4449 +vn -0.3129 0.9497 -0.0114 +vn 0.0339 0.6029 0.7971 +vn -0.2015 0.6791 0.7059 +vn -0.2526 0.9592 0.1272 +vn 0.1998 0.6866 -0.6990 +vn 0.2509 0.9588 -0.1331 +vn -0.0328 0.6049 -0.7956 +vn 0.5827 0.6730 0.4555 +vn 0.3071 0.9517 -0.0052 +vn 0.1434 0.6661 -0.7320 +vn 0.0319 0.7268 -0.6861 +vn -0.0352 0.7565 -0.6530 +vn 0.2147 0.6197 -0.7549 +vn 0.4463 0.6610 0.6032 +vn 0.4480 0.6571 0.6062 +vn 0.4921 0.7789 0.3888 +vn 0.2707 0.9151 0.2990 +vn 0.1866 0.9782 0.0909 +vn 0.8645 0.4457 0.2324 +vn 0.0232 0.5416 -0.8403 +vn 0.4749 0.7898 0.3881 +vn 0.4398 0.8131 0.3815 +vn 0.6013 0.6877 0.4068 +vn 0.2132 0.9205 0.3274 +vn -0.2289 0.8229 -0.5200 +vn -0.2237 0.7954 -0.5633 +vn -0.2010 0.6831 -0.7021 +vn -0.2459 0.9295 -0.2748 +vn 0.6040 0.6851 -0.4071 +vn -0.0044 0.9666 -0.2561 +vn 0.5700 0.6922 -0.4426 +vn 0.2503 0.9648 0.0814 +vn 0.7638 0.6064 -0.2210 +vn 0.4346 0.6051 -0.6671 +vn 0.9831 0.0397 0.1787 +vn 0.9850 0.0313 0.1696 +vn 0.9715 0.0180 0.2365 +vn 0.6677 -0.7440 -0.0244 +vn 0.6952 -0.7185 -0.0182 +vn 0.7055 -0.7086 -0.0158 +vn 0.7080 -0.7060 -0.0152 +vn 0.9867 0.0308 -0.1596 +vn 0.9709 -0.0035 -0.2394 +vn 0.9886 0.0170 -0.1499 +vn 0.9791 -0.0159 -0.2029 +vn 0.9451 -0.0030 -0.3268 +vn 0.1086 -0.9940 -0.0163 +vn 0.2306 -0.9539 -0.1921 +vn 0.0412 -0.9985 -0.0347 +vn 0.8978 0.0626 -0.4359 +vn 0.8834 0.0086 0.4685 +vn 0.7725 -0.5380 0.3375 +vn 0.9511 0.0100 0.3088 +vn 0.9766 0.0121 0.2149 +vn -0.8792 0.0358 -0.4751 +vn -0.9739 -0.0575 -0.2197 +vn -0.9513 -0.2142 -0.2215 +vn -0.8372 -0.4852 -0.2523 +vn -0.7668 -0.5467 -0.3364 +vn -0.9858 0.0194 -0.1666 +vn -0.9839 0.0281 -0.1766 +vn -0.6682 -0.7436 0.0244 +vn -0.7083 -0.7057 0.0152 +vn -0.7236 -0.6901 0.0115 +vn -0.7273 -0.6863 0.0106 +vn -0.9888 0.0227 0.1476 +vn -0.9635 0.0291 0.2662 +vn -0.9903 0.0104 0.1388 +vn -0.9813 0.0006 0.1927 +vn -0.9333 0.0506 0.3556 +vn -0.5946 -0.7223 0.3532 +vn -0.8967 0.0103 0.4425 +vn -0.0262 0.9823 -0.1853 +vn -0.0071 0.9995 -0.0323 +vn 0.0025 0.9999 -0.0118 +vn 0.1818 0.9804 0.0757 +vn 0.1835 0.9799 -0.0780 +vn -0.0056 0.9999 0.0089 +vn 0.0771 0.9796 0.1855 +vn -0.0002 0.9911 0.1333 +vn 0.0041 0.9995 -0.0322 +vn 0.0833 0.9799 -0.1814 +vn -0.0344 0.9810 0.1909 +vn 0.0142 0.9999 -0.0033 +vn 0.0205 0.9830 -0.1827 +vn 0.0107 0.9991 -0.0419 +vn 0.0412 0.9799 0.1954 +vn -0.0940 0.9950 0.0328 +vn -0.1996 0.9799 -0.0075 +vn -0.0938 0.9780 0.1865 +vn -0.2769 0.9586 -0.0668 +vn -0.0831 0.9778 -0.1925 +vn -0.0042 0.9992 -0.0399 +vn 0.0350 0.9774 -0.2086 +vn 0.0107 0.9992 0.0393 +vn 0.0284 0.9762 0.2149 +vn -0.2086 -0.0942 0.9735 +vn -0.1552 -0.0825 0.9844 +vn -0.0121 -0.0451 0.9989 +vn -0.2030 0.0579 0.9775 +vn -0.1651 0.0493 0.9850 +vn 0.3727 0.2286 0.8993 +vn 0.1469 -0.0751 0.9863 +vn 0.3205 0.1544 0.9346 +vn 0.1896 -0.8034 0.5644 +vn 0.0841 -0.1527 0.9847 +vn -0.0174 -0.9998 0.0068 +vn -0.2659 -0.9633 0.0360 +vn -0.0170 -0.9999 -0.0023 +vn -0.5030 0.3537 0.7886 +vn -0.8410 -0.3334 -0.4262 +vn -0.4032 0.6105 -0.6817 +vn -0.4087 0.6213 -0.6686 +vn -0.3654 0.5369 -0.7604 +vn 0.1193 0.9383 0.3245 +vn 0.0936 0.9345 0.3436 +vn 0.0461 0.9445 0.3252 +vn 0.1068 0.9333 0.3428 +vn 0.0788 0.9425 0.3246 +vn 0.1871 0.9160 0.3549 +vn -0.3522 0.5117 -0.7836 +vn -0.3353 0.9419 0.0192 +vn -0.1131 0.9935 -0.0139 +vn -0.2153 0.9765 0.0040 +vn -0.3416 0.9379 -0.0602 +vn -0.3283 0.9322 -0.1525 +vn -0.3393 0.9406 0.0115 +vn -0.1913 0.9358 0.2962 +vn -0.2244 0.9357 0.2721 +vn -0.2026 0.9365 0.2863 +vn -0.2707 0.9394 0.2105 +vn -0.1813 0.9702 0.1606 +vn -0.3547 0.9222 0.1538 +vn -0.2125 0.9706 0.1128 +vn -0.1296 0.9703 0.2045 +vn 0.0344 0.9414 0.3355 +vn 0.0030 0.9859 0.1672 +vn -0.0258 0.9608 0.2760 +vn -0.0380 0.9361 0.3498 +vn -0.0844 0.9371 0.3386 +vn -0.1235 0.9364 0.3284 +vn 0.2212 -0.0492 0.9740 +vn -0.3315 0.9396 0.0855 +vn -0.3206 0.9384 0.1293 +vn -0.5768 -0.4678 -0.6697 +vn 0.2110 0.2799 0.9366 +vn -0.7559 -0.2303 0.6128 +vn -0.9148 0.3457 0.2089 +vn 0.0771 0.5076 -0.8581 +vn 0.8822 -0.3536 -0.3111 +vn 0.9342 -0.2622 -0.2417 +vn 0.9796 -0.1379 -0.1463 +vn 0.9968 -0.0389 -0.0702 +vn 0.0244 -0.0159 0.9996 +vn 0.0681 0.0516 0.9963 +vn 0.1096 0.1159 0.9872 +vn -0.0279 -0.0962 0.9950 +vn -0.9903 -0.0388 -0.1333 +vn 0.7046 -0.4061 -0.5819 +vn 0.6661 0.3366 0.6656 +vn 0.5227 -0.1813 0.8330 +vn -0.6423 0.1427 0.7531 +vn -0.8182 -0.4993 0.2850 +vn -0.0786 -0.0033 -0.9969 +vn 0.1009 0.0093 -0.9949 +vn -0.0045 -0.9739 -0.2269 +vn -0.0018 -0.9380 -0.3466 +vn 0.0133 -0.9408 -0.3386 +vn -0.0105 -0.9412 -0.3378 +vn -0.0040 -0.9980 -0.0635 +vn 0.0166 -0.9994 -0.0298 +vn 0.0179 -0.9955 -0.0930 +vn -0.0060 -1.0000 -0.0010 +vn 0.0048 -1.0000 -0.0002 +vn -0.0046 -0.9997 -0.0224 +vn 0.0048 -0.9928 -0.1196 +vn -0.3727 0.2286 -0.8993 +vn -0.1476 -0.0742 -0.9863 +vn -0.3205 0.1544 -0.9346 +vn -0.1729 -0.8324 -0.5266 +vn 0.2508 -0.6672 -0.7014 +vn 0.1121 0.9288 -0.3533 +vn 0.0694 0.9131 -0.4018 +vn 0.0589 0.9431 -0.3272 +vn 0.1038 0.9365 -0.3349 +vn 0.1137 0.9342 -0.3381 +vn 0.1479 0.9317 -0.3318 +vn 0.0663 0.9432 -0.3257 +vn -0.0498 0.9413 -0.3338 +vn -0.2633 0.9553 0.1342 +vn -0.2287 0.9396 -0.2546 +vn -0.1922 0.9370 -0.2917 +vn -0.2192 0.9368 -0.2728 +vn -0.2721 0.9322 -0.2387 +vn -0.2605 0.9399 -0.2206 +vn -0.3079 0.9372 -0.1636 +vn -0.2089 0.9707 -0.1189 +vn -0.0014 0.9703 -0.2420 +vn 0.0607 0.9388 -0.3391 +vn 0.0068 0.9637 -0.2667 +vn -0.0623 0.9367 -0.3445 +vn -0.0383 0.9399 -0.3392 +vn -0.1471 0.9338 -0.3260 +vn -0.7278 -0.2078 -0.6536 +vn -0.6922 -0.1077 -0.7136 +vn -0.6372 0.0121 -0.7706 +vn -0.5718 0.1272 -0.8105 +vn 0.6713 -0.0856 -0.7362 +vn -0.3874 -0.6364 0.6670 +vn -0.9155 0.2370 0.3250 +vn -0.9951 -0.0581 -0.0797 +vn -0.3384 -0.1964 -0.9203 +vn 0.1446 0.3194 -0.9365 +vn 0.8799 -0.2800 -0.3838 +vn 0.9405 0.2885 0.1796 +vn 0.3224 -0.4005 0.8577 +vn -0.5855 0.7782 0.2271 +vn -0.2827 0.9451 0.1640 +vn -0.1965 0.9750 0.1036 +vn -0.9214 -0.3072 -0.2378 +vn -0.1153 0.2595 -0.9588 +vn 0.4810 -0.3965 -0.7819 +vn 0.7916 0.6090 -0.0504 +vn 0.0991 -0.0354 0.9944 +vn -0.0882 -0.0658 0.9939 +vn 0.0021 -0.9733 0.2295 +vn -0.0091 -0.9404 0.3400 +vn 0.2030 -0.9505 0.2350 +vn 0.0123 -0.9997 0.0187 +vn 0.0097 -0.9969 0.0785 +vn 0.0043 -0.9954 0.0962 +vn -0.0105 -0.9999 -0.0049 +vn -0.0850 -0.1517 -0.9848 +vn 0.6818 -0.5498 0.4825 +vn 0.5413 0.5111 0.6676 +vn -0.0072 0.0248 0.9997 +vn 0.9256 0.0350 0.3769 +vn 0.9358 0.1244 0.3297 +vn 0.9373 0.1621 0.3086 +vn 0.9139 -0.0232 0.4054 +vn -0.2668 -0.0039 0.9638 +vn 0.0894 -0.2332 -0.9683 +vn -0.1176 0.9440 0.3084 +vn -0.1057 0.9418 0.3190 +vn -0.0634 0.9438 0.3243 +vn -0.1030 0.9387 0.3291 +vn -0.1150 0.9366 0.3310 +vn -0.0385 0.9777 0.2065 +vn -0.1247 0.9406 0.3158 +vn -0.0623 0.9424 0.3286 +vn 0.2512 0.9679 0.0072 +vn 0.3371 0.9406 0.0414 +vn 0.1417 0.9776 0.1556 +vn 0.2130 0.9382 0.2729 +vn 0.1621 0.9371 0.3091 +vn 0.2472 0.9430 0.2229 +vn 0.2263 0.9379 0.2628 +vn 0.1007 0.9914 0.0831 +vn -0.4368 0.3590 0.8248 +vn 0.0277 0.9576 0.2868 +vn -0.0270 0.9413 0.3364 +vn 0.0020 0.9432 0.3321 +vn -0.0579 0.9608 0.2710 +vn 0.0479 0.9394 0.3395 +vn 0.0268 0.9385 0.3443 +vn 0.3398 0.9381 0.0664 +vn 0.3092 0.9354 0.1714 +vn 0.3238 0.9339 0.1518 +vn 0.9727 -0.1251 0.1957 +vn 0.9727 -0.0782 0.2187 +vn 0.9653 0.0119 0.2609 +vn -0.0347 0.2206 0.9747 +vn -0.6128 -0.6923 0.3810 +vn 0.4049 -0.2614 -0.8762 +vn 0.9525 0.0838 0.2927 +vn 0.9727 -0.2314 0.0155 +vn 0.8890 0.2062 0.4088 +vn 0.3407 -0.2125 0.9159 +vn -0.2920 0.2410 0.9255 +vn -0.8799 -0.2800 0.3838 +vn -0.8575 0.4097 -0.3112 +vn -0.5159 -0.3548 -0.7797 +vn 0.4266 0.1877 -0.8847 +vn 0.4510 0.3131 -0.8358 +vn 0.4095 0.1171 -0.9047 +vn 0.4562 0.3461 -0.8198 +vn 0.4230 0.1700 0.8901 +vn 0.3596 0.2644 0.8949 +vn 0.4928 0.0519 0.8686 +vn 0.3252 0.3117 0.8928 +vn -0.5866 -0.2844 0.7583 +vn -0.8218 0.5554 0.1276 +vn 0.8581 -0.3166 -0.4043 +vn -0.1181 0.9376 -0.3269 +vn -0.0450 0.9796 -0.1960 +vn -0.1038 0.9392 -0.3274 +vn -0.1040 0.9446 -0.3114 +vn -0.0646 0.9440 -0.3235 +vn -0.1174 0.9435 -0.3099 +vn 0.3481 0.9367 -0.0378 +vn 0.3433 0.9352 -0.0868 +vn 0.2421 0.9701 0.0139 +vn 0.1871 0.9363 -0.2973 +vn 0.2230 0.9372 -0.2683 +vn 0.2029 0.9373 -0.2834 +vn 0.2748 0.9369 -0.2159 +vn 0.2641 0.9415 -0.2095 +vn 0.2482 0.9330 -0.2608 +vn 0.0035 0.9430 -0.3328 +vn 0.2300 0.8774 -0.4210 +vn 0.1881 0.9090 -0.3720 +vn 0.0234 0.9403 -0.3396 +vn -0.0371 0.9625 -0.2689 +vn 0.0837 0.9361 -0.3416 +vn 0.1233 0.9365 -0.3284 +vn 0.3229 0.9379 -0.1267 +vn 0.5412 -0.4875 0.6851 +vn -0.8129 -0.4890 -0.3163 +vn -0.0259 0.3580 -0.9334 +vn 0.6440 -0.3695 -0.6699 +vn 0.9148 0.3457 -0.2089 +vn 0.8228 0.4786 0.3064 +vn 0.2364 -0.4880 0.8402 +vn -0.3443 0.6511 0.6764 +vn -0.8009 -0.4899 0.3444 +vn -0.7860 0.2815 -0.5504 +vn 0.0474 -0.2561 -0.9655 +vn 0.3802 0.1609 -0.9108 +vn 0.9768 -0.2034 0.0666 +vn -0.7356 -0.3915 0.5528 +vn -0.6524 0.2282 -0.7227 +vn -0.6661 0.3366 -0.6656 +vn -0.6071 0.0388 -0.7936 +vn -0.5700 -0.0692 -0.8187 +vn 0.6371 -0.0285 -0.7703 +vn 0.6489 0.6214 -0.4390 +vn 0.0129 -0.9399 0.3411 +vn 0.0042 0.0508 0.9987 +vn 0.0059 0.0575 0.9983 +vn -0.0017 0.0278 0.9996 +vn -0.0029 0.0231 0.9997 +vn 0.0029 0.0601 -0.9982 +vn 0.0026 0.0588 -0.9983 +vn 0.0008 0.0516 -0.9987 +vn 0.0004 0.0498 -0.9988 +vn -0.3455 0.7268 0.5936 +vn -0.2689 0.9231 0.2747 +vn -0.2472 0.8260 0.5065 +vn -0.2312 0.8204 0.5230 +vn 0.5623 0.7497 0.3489 +vn 0.5642 0.7462 0.3534 +vn 0.5657 0.7433 0.3570 +vn 0.6903 0.6593 -0.2980 +vn 0.8000 0.5621 -0.2100 +vn 0.5803 0.7331 -0.3549 +vn 0.2013 0.8176 -0.5394 +vn 0.2000 0.4643 0.8628 +vn 0.5603 0.7534 0.3443 +vn 0.3693 0.7780 -0.5083 +vn -0.2627 0.7941 -0.5481 +vn -0.0848 0.8065 -0.5851 +vn -0.3145 0.7596 -0.5693 +vn -0.6044 0.7856 -0.1321 +vn -0.6887 0.7190 -0.0931 +vn -0.8493 0.5280 0.0021 +vn -0.8910 0.4526 0.0352 +vn -0.0156 -0.9424 0.3342 +vn 0.7954 -0.4941 -0.3511 +vn -0.5179 -0.1050 0.8489 +vn -0.7482 -0.1130 -0.6538 +vn 0.6504 -0.1162 -0.7507 +vn 0.6877 -0.1097 0.7176 +vn -0.7065 -0.7076 -0.0105 +vn -0.8039 -0.5942 -0.0262 +vn -0.8942 -0.4377 0.0942 +vn -0.6472 -0.7614 -0.0379 +vn -0.7896 -0.6123 -0.0409 +vn -0.4212 -0.7498 0.5102 +vn -0.1606 -0.8471 0.5066 +vn -0.1557 -0.8506 0.5022 +vn -0.0075 -0.9138 0.4061 +vn -0.0086 -0.9172 0.3984 +vn 0.5448 -0.7648 0.3440 +vn 0.8291 -0.5402 0.1438 +vn 0.8226 -0.5533 0.1314 +vn 0.7836 -0.6212 0.0115 +vn 0.7790 -0.6165 -0.1147 +vn 0.8006 -0.5980 -0.0370 +vn 0.7652 -0.6302 -0.1318 +vn 0.7359 -0.6732 0.0727 +vn 0.7991 -0.5997 0.0421 +vn 0.8028 -0.5950 0.0385 +vn 0.5489 -0.6916 -0.4696 +vn -0.1872 -0.8070 -0.5602 +vn -0.0064 -0.8698 -0.4934 +vn -0.0048 -0.8640 -0.5035 +vn -0.1441 -0.8043 -0.5765 +vn -0.4477 -0.7578 -0.4746 +vn -0.6232 -0.7674 0.1506 +vn -0.8847 -0.4395 -0.1556 +vn -0.9198 -0.3447 -0.1874 +vn -0.0181 0.9986 -0.0487 +vn -0.0205 0.9988 -0.0440 +vn -0.0517 0.9976 -0.0465 +vn -0.0291 0.9991 -0.0303 +vn 0.0032 0.9962 -0.0867 +vn -0.0508 0.9985 -0.0204 +vn -0.0478 0.9987 -0.0157 +vn -0.0333 0.9951 0.0930 +vn -0.0220 0.9969 0.0757 +vn -0.0490 0.9667 0.2513 +vn -0.0154 0.9997 0.0166 +vn 0.0011 0.9993 0.0383 +vn 0.0373 0.9986 0.0376 +vn 0.0393 0.9989 0.0263 +vn -0.0004 1.0000 -0.0003 +vn -0.0003 1.0000 0.0001 +vn -0.0002 1.0000 0.0004 +vn -0.0690 0.9953 0.0680 +vn 0.0002 1.0000 0.0000 +vn 0.0043 0.9994 0.0357 +vn -0.0213 0.9981 0.0570 +vn 0.0325 0.9984 0.0461 +vn 0.0382 0.9992 0.0106 +vn 0.0610 0.9970 0.0473 +vn 0.0969 0.9922 0.0789 +vn 0.1826 0.9562 0.2288 +vn 0.0143 0.9997 0.0189 +vn 0.0110 0.9236 -0.3832 +vn 0.0499 0.9940 -0.0974 +vn 0.1010 0.9946 -0.0224 +vn -0.0290 0.9604 -0.2770 +vn -0.0606 0.9975 -0.0356 +vn 0.0001 1.0000 -0.0002 +vn -0.1330 0.9911 0.0093 +vn -0.0609 0.9962 -0.0627 +vn -0.0653 0.9962 -0.0583 +vn -0.0114 0.9937 -0.1113 +vn -0.0017 -0.9913 -0.1319 +vn -0.0115 -0.9999 0.0040 +vn 0.0003 -0.9934 -0.1148 +vn -0.0157 -0.9998 -0.0102 +vn -0.0318 -0.9772 0.2101 +vn -0.0233 -0.9994 0.0274 +vn 0.0497 -0.9858 0.1606 +vn 0.0054 -0.9998 0.0179 +vn 0.0524 -0.9822 0.1806 +vn -0.0132 -0.9999 0.0069 +vn 0.0234 -0.9995 0.0226 +vn 0.0079 -1.0000 -0.0043 +vn -0.0493 -0.9975 -0.0506 +vn -0.0206 -0.9997 -0.0152 +vn -0.0029 -0.9993 0.0364 +vn 0.0156 -0.9998 0.0105 +vn 0.0441 -0.9937 0.1035 +vn -0.0208 -0.9936 -0.1113 +vn -0.0017 -0.9999 -0.0111 +vn -0.0289 -0.9969 -0.0729 +vn -0.0139 -0.9999 -0.0093 +vn 0.0127 -0.9999 0.0022 +vn -0.0116 -0.9999 0.0111 +vn -0.0081 -1.0000 -0.0013 +vn 0.0128 -0.9998 -0.0150 +vn 0.0070 -1.0000 -0.0020 +vn 0.0171 -0.9998 -0.0059 +vn 0.1909 -0.9812 0.0269 +vn -0.0087 -1.0000 0.0010 +vn 0.0091 -1.0000 0.0010 +vn 0.0086 -0.9999 -0.0068 +vn 0.0117 -0.9999 -0.0055 +vn -0.0029 -1.0000 -0.0095 +vn -0.0095 -0.9999 -0.0091 +vn 0.0270 -0.9987 -0.0434 +vn 0.0528 -0.9927 -0.1087 +vn -0.0120 -0.9999 0.0011 +vn 0.0251 -0.9993 -0.0259 +vn 0.0250 -0.9992 -0.0326 +vn 0.0325 -0.9809 -0.1917 +vn 0.0020 1.0000 -0.0023 +vn -0.0050 0.9998 -0.0193 +vn -0.0037 0.9997 -0.0260 +vn -0.0086 0.9994 -0.0341 +vn -0.0125 0.9997 -0.0225 +vn -0.0029 1.0000 0.0012 +vn -0.0023 1.0000 0.0011 +vn -0.0170 0.9999 0.0029 +vn 0.0052 1.0000 0.0024 +vn 0.0037 0.9999 0.0153 +vn 0.0039 1.0000 0.0020 +vn -0.0125 0.9999 0.0032 +vn 0.0017 1.0000 -0.0016 +vn 0.0123 0.9999 0.0015 +vn -0.0087 0.9999 0.0148 +vn -0.0031 1.0000 -0.0025 +vn -0.4067 -0.0179 0.9134 +vn -0.3922 -0.0396 0.9190 +vn -0.3803 -0.0572 0.9231 +vn -0.3678 -0.0753 0.9268 +vn -0.8025 -0.2877 0.5227 +vn -0.9726 0.1928 0.1302 +vn -0.7923 -0.0755 -0.6054 +vn -0.7590 -0.0006 -0.6511 +vn -0.7231 0.0671 -0.6875 +vn -0.6755 0.1443 -0.7231 +vn 0.1126 -0.1127 -0.9872 +vn 0.1956 -0.0049 -0.9807 +vn 0.2598 0.0820 -0.9622 +vn 0.3358 0.1894 -0.9227 +vn 0.9217 -0.0772 -0.3803 +vn 0.9384 -0.0237 -0.3447 +vn 0.9488 0.0190 -0.3153 +vn 0.9593 0.0815 -0.2705 +vn 0.7418 0.0284 0.6701 +vn 0.7363 0.0130 0.6765 +vn 0.7469 0.0436 0.6635 +vn 0.7517 0.0585 0.6569 +vn -0.0000 -1.0000 0.0001 +vn -0.0001 -1.0000 0.0000 +vn 0.0001 -1.0000 -0.0001 +vn -0.0001 -1.0000 -0.0001 +vn 0.0001 -1.0000 0.0001 +vn 0.0001 -1.0000 0.0002 +vn 0.1877 -0.0257 0.9819 +vn -0.0274 -0.0049 0.9996 +vn 0.1553 -0.0225 0.9876 +vn -0.0532 -0.0023 0.9986 +vn -0.7247 -0.0932 0.6827 +vn -0.8853 -0.0287 -0.4641 +vn -0.9899 0.0512 -0.1322 +vn -0.9782 0.0346 -0.2049 +vn -0.8355 -0.0506 -0.5472 +vn 0.4255 0.0149 -0.9048 +vn 0.3498 0.0401 -0.9360 +vn 0.3662 0.0348 -0.9299 +vn 0.4466 0.0077 -0.8947 +vn 0.9803 -0.0425 0.1927 +vn 0.8783 0.0309 0.4770 +vn 0.9657 -0.0264 0.2582 +vn 0.8493 0.0446 0.5260 +vn 0.0145 -0.9999 0.0047 +vn 0.0173 -0.9998 -0.0014 +vn 0.0151 -0.9999 0.0069 +vn 0.0247 -0.9994 -0.0225 +vn 0.0172 -0.9998 -0.0044 +vn 0.0303 0.9995 0.0033 +vn -0.0457 0.9989 0.0081 +vn 0.0244 -0.9997 0.0004 +vn 0.0165 -0.9964 -0.0830 +vn 0.0232 -0.9997 -0.0119 +vn 0.0304 -0.9974 0.0646 +vn 0.5529 0.0412 -0.8322 +vn 0.5806 0.0320 -0.8136 +vn 0.6857 -0.0059 -0.7279 +vn 0.7165 -0.0181 -0.6973 +vn 0.7947 -0.0325 0.6061 +vn 0.8650 -0.0738 0.4964 +vn 0.8089 -0.0402 0.5866 +vn 0.8790 -0.0833 0.4695 +vn -0.1879 0.0445 0.9812 +vn -0.7593 -0.0827 0.6455 +vn -0.8014 -0.0475 -0.5962 +vn -0.9591 0.0368 -0.2805 +vn -0.9356 0.0190 -0.3527 +vn -0.7387 -0.0700 -0.6704 +vn -0.0375 -0.9952 -0.0903 +vn 0.1194 -0.9922 -0.0357 +vn 0.1519 -0.9882 0.0190 +vn 0.0779 -0.9931 0.0879 +vn 0.0439 -0.9934 0.1061 +vn -0.1066 -0.9897 0.0954 +vn -0.0366 -0.9952 -0.0910 +vn -0.1230 -0.9909 0.0543 +vn -0.0473 0.2253 -0.9731 +vn -0.8921 -0.0181 -0.4514 +vn -0.9139 -0.0994 -0.3935 +vn -0.9180 -0.1198 -0.3781 +vn -0.9263 -0.1802 -0.3309 +vn -0.6580 0.1315 0.7414 +vn -0.5283 -0.0066 0.8490 +vn -0.5033 -0.0306 0.8636 +vn -0.3684 -0.1487 0.9177 +vn 0.2890 0.2199 0.9317 +vn 0.8882 -0.2388 0.3926 +vn 0.9555 0.2489 -0.1586 +vn 0.4662 -0.2837 -0.8380 +vn -0.1707 0.7659 -0.6199 +vn 0.9536 -0.2281 -0.1966 +vn 0.1087 0.7442 0.6590 +vn 0.1043 0.7418 0.6625 +vn 0.1679 0.7745 0.6099 +vn 0.0467 0.7074 0.7053 +vn -0.9060 -0.1178 -0.4065 +vn 0.0289 0.9994 0.0209 +vn -0.0451 0.9989 -0.0111 +vn -0.0158 -0.9999 0.0049 +vn -0.1251 -0.9921 0.0140 +vn -0.0091 -0.9999 0.0044 +vn 0.0922 -0.9957 -0.0039 +vn 0.5788 0.0233 -0.8151 +vn 0.3583 -0.0706 -0.9309 +vn 0.5338 0.0028 -0.8456 +vn 0.3042 -0.0914 -0.9482 +vn 0.9952 0.0482 0.0856 +vn 0.6688 -0.0925 0.7376 +vn -0.4769 -0.0380 0.8782 +vn -0.1445 0.0274 0.9891 +vn -0.2088 0.0155 0.9778 +vn -0.5506 -0.0536 0.8331 +vn -0.9752 0.0453 -0.2168 +vn -0.9559 0.0241 -0.2929 +vn -0.8322 -0.0541 -0.5518 +vn -0.7804 -0.0768 -0.6206 +vn 0.1235 -0.9898 -0.0706 +vn 0.0761 -0.9907 -0.1124 +vn 0.1229 -0.9919 0.0333 +vn -0.0617 -0.9900 -0.1270 +vn 0.1242 -0.9673 0.2209 +vn -0.0386 -0.9928 0.1134 +vn -0.1256 -0.9893 0.0742 +vn -0.1343 -0.9909 -0.0017 +vn -0.0858 -0.9861 -0.1424 +vn -0.6844 0.1303 -0.7174 +vn -0.8071 0.0032 -0.5904 +vn -0.7958 0.0168 -0.6054 +vn -0.8826 -0.1072 -0.4577 +vn -0.9312 0.1388 0.3370 +vn -0.8974 0.0364 0.4398 +vn -0.8882 0.0156 0.4593 +vn -0.8270 -0.0928 0.5545 +vn 0.3943 0.0581 0.9171 +vn 0.4323 0.1249 0.8930 +vn 0.3714 0.0188 0.9283 +vn 0.3303 -0.0476 0.9427 +vn 0.9833 0.0438 -0.1767 +vn 0.9615 -0.0399 -0.2717 +vn 0.9605 -0.0427 -0.2748 +vn 0.9291 -0.1134 -0.3520 +vn 0.3446 0.1686 -0.9235 +vn 0.2081 0.0554 -0.9765 +vn 0.2057 0.0535 -0.9771 +vn 0.0577 -0.0653 -0.9962 +vn -0.7445 -0.0713 -0.6638 +vn -0.0042 0.7919 -0.6107 +vn 0.9706 -0.2020 0.1308 +vn -0.1254 0.7392 0.6618 +vn -0.1352 0.7344 0.6651 +vn 0.0042 0.7923 0.6101 +vn -0.2630 0.6627 0.7012 +vn -0.0285 0.9984 0.0490 +vn 0.0292 0.9995 -0.0151 +vn 0.0346 0.9993 -0.0151 +vn 0.0251 0.9996 -0.0150 +vn 0.0221 0.9996 -0.0150 +vn -0.0394 -0.9992 0.0034 +vn -0.0172 -0.9929 0.1181 +vn -0.0206 -0.9947 0.1006 +vn -0.8935 -0.0154 -0.4489 +vn -0.6801 -0.2639 0.6839 +vn -0.1329 0.0943 -0.9866 +vn 0.5072 -0.0878 -0.8574 +vn 0.8865 0.0269 0.4619 +vn 0.8976 0.0179 0.4405 +vn 0.8895 0.0246 0.4564 +vn 0.8999 0.0159 0.4358 +vn -0.4642 0.0005 0.8858 +vn -0.4845 -0.0068 0.8748 +vn -0.5512 -0.0316 0.8337 +vn -0.5687 -0.0383 0.8216 +vn 0.0744 -0.9816 0.1760 +vn -0.0245 -0.9922 0.1218 +vn -0.1519 -0.9807 0.1227 +vn -0.1817 -0.9743 0.1329 +vn 0.0778 -0.9935 0.0829 +vn 0.0693 -0.9960 0.0562 +vn -0.0326 -0.9980 -0.0547 +vn 0.8067 -0.1179 -0.5791 +vn 0.7913 -0.2275 -0.5676 +vn 0.8401 -0.1459 -0.5224 +vn -0.8925 -0.1200 0.4348 +vn -0.8929 -0.1193 0.4341 +vn -0.8601 -0.1714 0.4804 +vn 0.0161 0.1602 0.9869 +vn 0.4674 -0.1866 0.8641 +vn 0.7944 0.1169 0.5960 +vn 0.8793 -0.0694 -0.4712 +vn 0.8249 -0.1778 -0.5366 +vn -0.1072 0.1982 -0.9743 +vn -0.8018 -0.0726 -0.5932 +vn -0.7189 -0.1606 -0.6763 +vn -0.8017 -0.0726 -0.5933 +vn -0.8783 0.0350 -0.4768 +vn -0.9246 -0.0574 0.3765 +vn -0.8416 -0.2469 0.4804 +vn -0.8325 0.5540 0.0058 +vn 0.5062 0.0078 -0.8624 +vn 0.6508 0.7447 0.1481 +vn 0.6577 0.7279 0.1940 +vn 0.6172 0.7868 -0.0043 +vn 0.6691 0.6503 0.3597 +vn 0.0010 -0.9779 0.2093 +vn -0.0048 0.9996 0.0286 +vn -0.0290 -0.9996 -0.0071 +vn -0.0153 -0.9965 0.0817 +vn -0.0260 -0.9996 0.0123 +vn -0.0395 -0.9965 -0.0738 +vn -0.7134 -0.0665 0.6976 +vn -0.9994 0.0330 0.0091 +vn -0.7906 -0.0968 -0.6046 +vn -0.2130 0.0101 -0.9770 +vn 0.7257 -0.1021 -0.6804 +vn 0.9957 0.0316 -0.0876 +vn 0.7675 -0.0945 0.6340 +vn 0.0467 0.0530 0.9975 +vn 0.1628 -0.9749 0.1518 +vn 0.0106 -0.9914 0.1308 +vn -0.0977 -0.9879 0.1203 +vn 0.1034 -0.9945 0.0174 +vn -0.0992 -0.9902 -0.0987 +vn -0.0115 -0.9879 -0.1550 +vn -0.1026 -0.9912 -0.0842 +vn -0.1268 -0.9909 0.0449 +vn 0.0779 -0.9968 -0.0195 +vn 0.5765 0.0324 0.8164 +vn 0.6594 -0.0701 0.7486 +vn 0.6692 -0.0827 0.7385 +vn 0.7220 -0.1607 0.6730 +vn 0.9473 0.2484 -0.2024 +vn 0.6573 -0.2839 -0.6982 +vn 0.0433 -0.0785 -0.9960 +vn 0.1765 -0.2352 -0.9558 +vn 0.0446 -0.0800 -0.9958 +vn -0.0866 0.0754 -0.9934 +vn -0.9190 0.1090 -0.3788 +vn -0.9525 0.0175 -0.3041 +vn -0.9567 0.0021 -0.2910 +vn -0.9728 -0.0845 -0.2155 +vn -0.5566 0.0315 0.8302 +vn -0.5540 0.0350 0.8318 +vn -0.5568 0.0309 0.8300 +vn -0.5591 0.0276 0.8287 +vn 0.0634 0.7156 0.6956 +vn 0.1120 0.7496 0.6523 +vn 0.1151 0.7517 0.6494 +vn 0.1651 0.7829 0.5999 +vn -0.9334 0.2986 0.1988 +vn -0.1977 0.6673 -0.7181 +vn 0.0751 0.2943 -0.9528 +vn 0.7535 0.5768 0.3155 +vn -0.0274 0.9989 -0.0371 +vn -0.0077 -0.9992 -0.0390 +vn -0.0078 -0.9992 -0.0386 +vn 0.0564 -0.9965 -0.0615 +vn -0.0809 -0.9966 -0.0130 +vn -0.3469 -0.0534 0.9364 +vn 0.0070 0.0208 0.9998 +vn -0.0582 0.0073 0.9983 +vn -0.4218 -0.0694 0.9040 +vn -0.9500 -0.0372 -0.3099 +vn -0.9977 0.0230 -0.0634 +vn -0.9934 0.0106 -0.1146 +vn -0.9298 -0.0508 -0.3646 +vn 0.3366 -0.0596 -0.9397 +vn 0.0278 0.0204 -0.9994 +vn 0.0984 0.0023 -0.9951 +vn 0.4048 -0.0777 -0.9111 +vn 0.8821 -0.0519 0.4683 +vn 0.9952 0.0349 0.0917 +vn 0.9851 0.0174 0.1711 +vn 0.8396 -0.0694 0.5388 +vn 0.1163 -0.9879 0.1024 +vn 0.0304 -0.9920 0.1223 +vn -0.0983 -0.9885 0.1151 +vn 0.1247 -0.9922 -0.0067 +vn 0.1490 -0.9758 -0.1598 +vn -0.0790 -0.9920 -0.0983 +vn 0.0055 -0.9911 -0.1330 +vn -0.1117 -0.9922 -0.0555 +vn -0.1341 -0.9876 0.0814 +vn 0.4432 0.2311 0.8661 +vn 0.7952 -0.1963 0.5737 +vn 0.8912 0.2249 -0.3940 +vn 0.6617 -0.1553 -0.7335 +vn -0.0450 0.1387 -0.9893 +vn -0.4829 -0.1177 -0.8677 +vn -0.8341 0.1194 -0.5385 +vn -0.9874 -0.1577 0.0100 +vn -0.7656 0.2165 0.6058 +vn -0.3458 -0.1503 0.9262 +vn 0.4685 0.3731 0.8008 +vn 0.5285 0.7941 0.3001 +vn -0.4990 0.8363 0.2274 +vn -0.8658 -0.0924 -0.4918 +vn -0.3657 0.5848 -0.7241 +vn 0.6683 0.5175 -0.5343 +vn -0.0021 1.0000 0.0043 +vn 0.0129 -0.9999 -0.0079 +vn 0.6942 -0.0874 0.7144 +vn 0.1819 0.0970 0.9785 +vn -0.9525 -0.1276 0.2767 +vn -0.9129 0.0632 -0.4033 +vn 0.3178 -0.0910 -0.9438 +vn 0.6057 0.0049 -0.7957 +vn 0.4038 -0.0647 -0.9126 +vn 0.6732 0.0313 -0.7388 +vn 0.2099 -0.9774 0.0261 +vn 0.1109 -0.9888 -0.0996 +vn 0.1436 -0.9826 0.1178 +vn -0.1858 -0.9748 0.1233 +vn -0.0191 -0.9901 0.1393 +vn -0.1860 -0.9825 -0.0135 +vn -0.0563 -0.9911 -0.1203 +vn -0.0031 -0.9905 -0.1377 +vn 0.9899 -0.1414 -0.0046 +vn 0.4524 0.2178 -0.8648 +vn 0.3908 0.1281 -0.9115 +vn 0.3566 0.0804 -0.9308 +vn 0.2760 -0.0255 -0.9608 +vn -0.9187 0.1500 -0.3653 +vn -0.8809 0.0204 -0.4729 +vn -0.9257 0.1958 -0.3237 +vn -0.9287 0.2877 -0.2340 +vn -0.7633 -0.2389 0.6003 +vn -0.0929 0.2120 0.9728 +vn 0.3745 -0.1156 0.9200 +vn 0.8736 0.2088 0.4395 +vn -0.4239 0.3941 0.8155 +vn 0.1643 0.8237 0.5428 +vn -0.7811 0.4853 -0.3930 +vn -0.1760 0.7945 -0.5812 +vn 0.7076 -0.6227 -0.3339 +vn -0.0070 0.9991 -0.0411 +vn 0.0252 0.9995 0.0184 +vn 0.0589 -0.9980 -0.0235 +vn 0.9044 -0.1316 -0.4059 +vn 0.6950 0.0776 0.7148 +vn 0.1015 -0.0938 0.9904 +vn -0.9553 0.0558 0.2904 +vn -0.8816 -0.1448 -0.4492 +vn 0.1799 0.1058 -0.9780 +vn 0.0627 -0.9953 0.0744 +vn 0.0568 -0.9922 0.1108 +vn -0.0113 -0.9760 0.2174 +vn -0.0961 -0.9922 0.0794 +vn 0.5641 -0.8250 0.0334 +vn -0.1140 -0.9893 -0.0914 +vn -0.1245 -0.9859 -0.1116 +vn -0.0023 -0.9936 -0.1128 +vn 0.0042 -0.9957 -0.0928 +vn 0.4891 0.2047 -0.8479 +vn -0.0890 -0.2558 -0.9626 +vn -0.6331 0.2066 -0.7460 +vn -0.9687 -0.2481 -0.0016 +vn -0.7646 0.2987 0.5711 +vn 0.1672 -0.0503 0.9846 +vn 0.0167 -0.1795 0.9836 +vn 0.2078 -0.0140 0.9781 +vn 0.3663 0.1335 0.9209 +vn 0.9929 -0.1176 -0.0157 +vn 0.9802 -0.1927 0.0454 +vn 0.9948 -0.0958 -0.0333 +vn 0.9935 0.0061 -0.1141 +vn 0.7246 0.4309 -0.5378 +vn 0.1984 0.2776 0.9400 +vn 0.3699 0.6822 0.6306 +vn -0.6746 0.5837 -0.4520 +vn -0.5029 -0.1107 -0.8572 +vn 0.0245 0.9997 -0.0090 +vn 0.0262 -0.9996 0.0086 +vn -0.6479 0.0683 0.7587 +vn -0.9868 -0.1312 -0.0946 +vn -0.9569 -0.1811 0.2270 +vn -0.9889 -0.1386 -0.0528 +vn -0.9354 -0.1899 0.2984 +vn 0.1293 0.0326 -0.9911 +vn 0.1910 0.0156 -0.9815 +vn 0.3728 -0.0366 -0.9272 +vn 0.4544 -0.0609 -0.8887 +vn 0.9161 0.0342 0.3996 +vn 0.5763 -0.1254 0.8076 +vn 0.1770 -0.9817 -0.0704 +vn 0.1188 -0.9918 0.0468 +vn 0.0361 -0.9890 0.1437 +vn -0.0881 -0.9932 0.0758 +vn -0.1423 -0.9894 0.0285 +vn 0.0079 -0.9836 0.1801 +vn 0.0478 -0.9949 -0.0890 +vn -0.1859 -0.9825 0.0063 +vn -0.0087 -0.9962 -0.0862 +vn 0.5785 -0.0909 0.8106 +vn 0.9011 0.1836 0.3929 +vn 0.9231 -0.2446 -0.2968 +vn 0.7072 0.1252 -0.6958 +vn -0.1769 0.0236 -0.9839 +vn -0.2542 -0.0753 -0.9642 +vn -0.2698 -0.0957 -0.9581 +vn -0.3318 -0.1790 -0.9262 +vn -0.9950 0.0998 -0.0031 +vn -0.9928 -0.0292 -0.1166 +vn -0.9927 0.1196 0.0146 +vn -0.9715 0.2148 0.1004 +vn -0.4310 -0.1640 0.8873 +vn 0.0493 0.1803 0.9824 +vn 0.1700 0.3725 0.9123 +vn -0.8244 0.5598 0.0838 +vn -0.8313 0.5504 0.0775 +vn -0.8281 0.5548 0.0804 +vn -0.8372 0.5422 0.0721 +vn -0.0512 0.3689 -0.9280 +vn 0.7072 0.7042 -0.0636 +vn 0.7086 0.7029 -0.0623 +vn 0.7082 0.7032 -0.0627 +vn 0.7097 0.7018 -0.0615 +vn -0.0206 0.9997 -0.0100 +vn 0.0070 0.9999 0.0143 +vn 0.0249 -0.9995 0.0219 +vn -0.8948 0.0728 0.4405 +vn -0.8445 -0.1219 -0.5215 +vn 0.1033 0.0985 -0.9898 +vn 0.8442 -0.1304 -0.5199 +vn 0.7605 0.0825 0.6440 +vn -0.0476 -0.1313 0.9902 +vn -0.0385 -0.9880 0.1498 +vn -0.1059 -0.9911 0.0811 +vn -0.1177 -0.9912 -0.0607 +vn 0.0510 -0.9922 0.1141 +vn 0.1496 -0.9871 -0.0564 +vn 0.1974 -0.9802 -0.0146 +vn -0.1270 -0.9873 -0.0956 +vn 0.0329 -0.9907 -0.1323 +vn -0.2345 0.0511 0.9708 +vn -0.2160 0.0711 0.9738 +vn -0.1513 0.1396 0.9786 +vn 0.9186 -0.0391 0.3932 +vn 0.8633 -0.1507 0.4816 +vn 0.9293 -0.0104 0.3691 +vn 0.9590 0.1120 0.2602 +vn 0.7139 0.0152 -0.7000 +vn 0.7247 0.0317 -0.6883 +vn 0.7239 0.0304 -0.6892 +vn 0.7339 0.0458 -0.6777 +vn -0.2524 -0.0162 -0.9675 +vn -0.2691 0.0026 -0.9631 +vn -0.2503 -0.0186 -0.9680 +vn -0.2320 -0.0390 -0.9719 +vn -0.9968 0.0543 0.0581 +vn -0.9968 0.0518 0.0601 +vn -0.9968 0.0514 0.0609 +vn -0.9968 0.0485 0.0628 +vn -0.3020 -0.0243 0.9530 +vn -0.5644 0.7371 0.3717 +vn -0.5419 0.6488 0.5342 +vn -0.5660 0.7474 0.3478 +vn -0.5677 0.7971 0.2058 +vn -0.4529 -0.3849 -0.8042 +vn 0.8350 -0.1949 0.5146 +vn 0.5790 0.7878 -0.2099 +vn 0.0056 0.9999 -0.0109 +vn 0.0074 1.0000 -0.0000 +vn 0.0096 0.9999 0.0029 +vn -0.0126 0.9995 -0.0275 +vn 0.0103 0.9999 -0.0128 +vn 0.0168 0.9998 -0.0112 +vn -0.0346 -0.9993 0.0161 +vn -0.1304 -0.9911 -0.0284 +vn -0.1498 -0.9880 -0.0375 +vn -0.8738 0.1275 -0.4693 +vn -0.2178 -0.0550 -0.9744 +vn 0.9012 -0.0057 -0.4334 +vn 0.9053 -0.0026 -0.4248 +vn 0.9023 -0.0048 -0.4312 +vn 0.9061 -0.0019 -0.4230 +vn 0.3324 -0.0384 0.9424 +vn 0.1723 0.0130 0.9850 +vn 0.2906 -0.0248 0.9565 +vn 0.1340 0.0249 0.9907 +vn -0.9884 -0.0617 0.1390 +vn 0.1154 -0.9913 0.0640 +vn 0.1322 -0.9910 0.0205 +vn 0.0384 -0.9912 0.1264 +vn -0.1103 -0.9876 0.1116 +vn -0.1019 -0.9902 -0.0954 +vn 0.0089 -0.9629 -0.2698 +vn 0.1082 -0.9891 -0.1000 +vn -0.1586 -0.9839 0.0825 +vn -0.9454 0.0330 -0.3241 +vn -0.9730 -0.0606 -0.2225 +vn -0.9738 -0.0647 -0.2179 +vn -0.9813 -0.1375 -0.1349 +vn -0.6679 0.2402 0.7045 +vn -0.3507 -0.1640 0.9220 +vn 0.7687 0.1205 0.6282 +vn 0.7478 0.0763 0.6595 +vn 0.7730 0.1303 0.6209 +vn 0.7862 0.1625 0.5962 +vn 0.9438 -0.1473 -0.2958 +vn 0.7151 0.1773 -0.6762 +vn -0.0682 -0.0521 -0.9963 +vn -0.0035 -0.1125 -0.9936 +vn -0.0751 -0.0457 -0.9961 +vn -0.1547 0.0301 -0.9875 +vn 0.2773 0.4921 -0.8252 +vn 0.5108 0.5968 0.6188 +vn -0.9501 0.3059 -0.0612 +vn -0.2547 -0.9631 -0.0868 +vn -0.0032 0.9998 -0.0177 +vn -0.0126 0.9997 0.0189 +vn -0.0014 -0.9999 -0.0134 +vn -0.0387 -0.9969 0.0684 +vn -0.0006 -0.9999 -0.0152 +vn 0.0316 -0.9959 -0.0850 +vn 0.5046 0.0496 -0.8619 +vn 0.9198 -0.1083 -0.3771 +vn 0.7860 0.0370 0.6172 +vn 0.2268 -0.0789 0.9707 +vn -0.5595 0.0373 0.8280 +vn -0.9556 -0.0727 0.2854 +vn -0.6111 -0.0455 -0.7902 +vn -0.8389 0.0172 -0.5440 +vn -0.8020 0.0052 -0.5973 +vn -0.5507 -0.0587 -0.8326 +vn -0.1572 -0.9866 0.0427 +vn -0.0860 -0.9890 0.1207 +vn -0.1379 -0.9895 -0.0433 +vn 0.1593 -0.9865 -0.0382 +vn 0.0180 -0.9945 -0.1034 +vn 0.1912 -0.9815 -0.0129 +vn 0.0046 -0.9890 0.1481 +vn 0.0721 -0.9911 0.1117 +vn -0.0765 -0.9888 -0.1280 +vn -0.6286 -0.0360 -0.7769 +vn -0.5721 -0.1167 -0.8119 +vn -0.6519 0.0004 -0.7583 +vn -0.7012 0.0869 -0.7076 +vn -0.8855 0.0810 0.4575 +vn -0.9324 -0.0191 0.3610 +vn -0.8751 0.0988 0.4738 +vn -0.8174 0.1822 0.5464 +vn -0.0833 -0.2134 0.9734 +vn 0.4178 0.1554 0.8952 +vn 0.9340 0.0418 0.3547 +vn 0.9067 -0.0134 0.4216 +vn 0.9322 0.0374 0.3601 +vn 0.9534 0.0958 0.2860 +vn 0.7078 0.0178 -0.7061 +vn 0.7683 -0.0773 -0.6354 +vn 0.6910 0.0411 -0.7216 +vn 0.6148 0.1361 -0.7769 +vn 0.4117 -0.2032 -0.8884 +vn 0.5901 0.8057 -0.0508 +vn 0.0756 -0.4222 0.9034 +vn -0.7215 0.6569 -0.2191 +vn -0.6651 0.7425 -0.0796 +vn -0.6577 0.7506 -0.0641 +vn -0.5955 0.8017 0.0513 +vn -0.0044 1.0000 0.0084 +vn 0.0022 0.9994 -0.0356 +vn -0.0305 -0.9994 -0.0166 +vn 0.5476 0.0360 -0.8360 +vn 0.8548 -0.0642 0.5149 +vn 0.8158 -0.0419 0.5768 +vn 0.8462 -0.0590 0.5296 +vn 0.8051 -0.0363 0.5921 +vn -0.5385 0.0066 0.8426 +vn -0.6183 -0.0173 0.7858 +vn -0.8211 -0.0887 0.5638 +vn -0.8627 -0.1066 0.4944 +vn -0.9125 0.0476 -0.4063 +vn 0.0364 -0.1144 -0.9928 +vn 0.1766 -0.9830 -0.0504 +vn 0.1268 -0.9908 0.0464 +vn 0.0769 -0.9847 0.1565 +vn 0.0727 -0.9955 -0.0601 +vn 0.0973 -0.9931 -0.0662 +vn -0.2020 -0.9753 0.0898 +vn -0.0330 -0.9929 0.1143 +vn -0.1445 -0.9895 0.0085 +vn -0.1116 -0.9935 -0.0232 +vn -0.2892 -0.8228 -0.4893 +vn -0.5237 -0.1105 -0.8447 +vn -0.5109 -0.0908 -0.8548 +vn -0.5076 -0.0857 -0.8573 +vn -0.4976 -0.0707 -0.8645 +vn -0.9820 0.1622 0.0962 +vn -0.8530 -0.2580 0.4538 +vn 0.1475 0.2346 0.9608 +vn 0.4964 -0.1437 0.8561 +vn 0.9768 0.1721 0.1274 +vn 0.8936 -0.1969 -0.4034 +vn 0.6224 0.1575 -0.7667 +vn 0.5309 -0.3412 -0.7757 +vn -0.0315 -0.1411 0.9895 +vn 0.6009 0.7899 0.1225 +vn -0.6492 0.7560 -0.0844 +vn -0.6598 0.7437 -0.1081 +vn -0.6611 0.7421 -0.1110 +vn -0.6720 0.7278 -0.1370 +vn -0.0114 0.9998 0.0140 +vn -0.0808 -0.9949 -0.0598 +vn -0.0838 -0.9946 -0.0616 +vn 0.0561 -0.9982 0.0194 +vn 0.9655 -0.0259 -0.2590 +vn 0.9694 -0.0307 -0.2435 +vn 0.9809 -0.0474 -0.1888 +vn 0.9836 -0.0523 -0.1728 +vn 0.1438 0.0043 0.9896 +vn 0.2372 -0.0240 0.9712 +vn 0.1653 -0.0022 0.9862 +vn 0.2542 -0.0292 0.9667 +vn -0.9365 0.0188 0.3501 +vn -0.9623 -0.0060 0.2720 +vn -0.9575 -0.0009 0.2883 +vn -0.9274 0.0262 0.3731 +vn -0.3212 -0.0498 -0.9457 +vn -0.1664 -0.0046 -0.9861 +vn -0.2823 -0.0382 -0.9586 +vn -0.1305 0.0057 -0.9914 +vn -0.1767 -0.9508 0.2546 +vn -0.0861 -0.9963 0.0041 +vn -0.1628 -0.9653 -0.2040 +vn 0.2317 -0.9622 0.1435 +vn 0.1348 -0.9906 -0.0247 +vn 0.0341 -0.9906 0.1323 +vn 0.0178 -0.9919 -0.1260 +vn 0.0927 -0.9892 -0.1140 +vn 0.6597 -0.1293 -0.7403 +vn 0.1869 0.2518 -0.9496 +vn -0.6054 -0.2899 -0.7412 +vn -0.9265 0.3666 -0.0842 +vn -0.5844 -0.3566 0.7289 +vn 0.0419 0.2976 0.9538 +vn 0.8168 -0.2422 0.5237 +vn 0.9712 0.2381 0.0005 +vn 0.6001 -0.6063 -0.5218 +vn -0.1455 0.6380 0.7562 +vn -0.0392 0.7248 0.6878 +vn -0.0585 0.7103 0.7015 +vn 0.0534 0.7859 0.6161 +vn -0.9490 0.3154 0.0002 +vn -0.0590 0.7287 -0.6822 +vn -0.2134 -0.9675 -0.1360 +vn -0.0272 0.9996 -0.0101 +vn 0.0142 0.9997 0.0219 +vn 0.0075 -0.9998 -0.0201 +vn 0.0365 -0.9916 0.1240 +vn 0.0322 -0.9940 0.1043 +vn 0.8344 -0.0030 0.5512 +vn 0.7605 0.0309 0.6486 +vn 0.8198 0.0042 0.5726 +vn 0.7466 0.0366 0.6642 +vn -0.4224 -0.0538 0.9048 +vn -0.6881 0.0128 0.7255 +vn -0.4915 -0.0381 0.8701 +vn -0.7286 0.0245 0.6845 +vn -0.9279 -0.0816 -0.3637 +vn -0.7935 -0.0109 -0.6085 +vn -0.9057 -0.0671 -0.4185 +vn -0.7529 0.0056 -0.6581 +vn 0.6403 -0.0309 -0.7675 +vn 0.6495 -0.0348 -0.7596 +vn 0.6772 -0.0467 -0.7343 +vn 0.6857 -0.0504 -0.7262 +vn -0.1154 -0.9933 0.0014 +vn -0.1243 -0.9922 -0.0132 +vn -0.0369 -0.9931 -0.1114 +vn 0.0050 -0.9936 -0.1126 +vn 0.1254 -0.9920 -0.0167 +vn 0.0770 -0.9915 0.1046 +vn -0.0019 -0.9884 0.1520 +vn -0.0766 -0.9909 0.1110 +vn 0.1385 -0.9901 -0.0227 +vn 0.9274 0.0053 0.3740 +vn 0.9286 0.0086 0.3711 +vn 0.9430 0.0561 0.3281 +vn 0.6949 0.0063 -0.7191 +vn 0.6953 0.0056 -0.7187 +vn 0.6948 0.0065 -0.7192 +vn 0.6943 0.0072 -0.7196 +vn -0.5460 0.0946 -0.8324 +vn -0.6086 0.0027 -0.7935 +vn -0.6315 -0.0352 -0.7745 +vn -0.6795 -0.1214 -0.7236 +vn -0.9271 0.0881 0.3642 +vn -0.9051 0.0315 0.4239 +vn -0.9037 0.0282 0.4273 +vn -0.8747 -0.0286 0.4838 +vn -0.0964 0.0990 0.9904 +vn -0.0486 0.0489 0.9976 +vn -0.0442 0.0442 0.9980 +vn 0.0086 -0.0115 0.9999 +vn 0.9083 -0.0432 0.4160 +vn 0.9275 -0.0749 0.3663 +vn 0.6227 0.7542 -0.2083 +vn -0.4143 0.8008 0.4325 +vn -0.8329 0.4784 0.2784 +vn -0.5121 -0.0736 -0.8558 +vn 0.0684 -0.9549 0.2890 +vn -0.0297 0.9995 0.0080 +vn -0.0388 0.9992 0.0016 +vn 0.0085 0.9995 -0.0292 +vn 0.0304 0.9993 -0.0199 +vn 0.1278 0.9903 0.0539 +vn 0.0622 0.9955 0.0710 +vn 0.0067 0.9999 0.0134 +vn 0.0343 0.9977 -0.0588 +vn -0.0005 -1.0000 0.0010 +vn -0.0001 -1.0000 0.0019 +vn -0.0067 -1.0000 -0.0025 +vn -0.0006 -1.0000 -0.0017 +vn 0.0002 -1.0000 -0.0032 +vn 0.0019 -1.0000 0.0046 +vn -0.0000 -1.0000 -0.0001 +vn 0.0000 -1.0000 -0.0002 +vn -0.0006 -1.0000 0.0006 +vn 0.0305 -0.9994 -0.0163 +vn 0.0060 -0.9993 -0.0377 +vn 0.0066 -0.9990 0.0433 +vn 0.0008 -0.9997 0.0229 +vn -0.0006 -1.0000 -0.0000 +vn 0.0227 -0.9970 0.0738 +vn 0.0323 -0.9993 0.0167 +vn -0.8769 0.3508 0.3286 +vn 0.0648 -0.9979 0.0041 +vn 0.0541 -0.9977 -0.0404 +vn 0.0043 -1.0000 -0.0085 +vn 0.0358 -0.9982 -0.0486 +vn 0.0296 -0.9980 -0.0557 +vn -0.0007 -1.0000 -0.0001 +vn 0.0370 -0.9967 -0.0724 +vn 0.0135 -0.9999 -0.0005 +vn 0.0072 -1.0000 -0.0048 +vn 0.0132 -0.9999 -0.0001 +vn -0.0008 -1.0000 -0.0002 +vn 0.0002 -1.0000 0.0000 +vn 0.0603 -0.9980 -0.0187 +vn 0.0415 -0.9991 0.0077 +vn 0.0458 -0.9983 0.0355 +vn 0.0244 -0.9986 0.0469 +vn -0.0008 -1.0000 -0.0009 +vn -0.0004 1.0000 0.0010 +vn -0.0010 0.9999 -0.0111 +vn 0.0001 1.0000 -0.0023 +vn 0.0001 1.0000 -0.0008 +vn 0.0007 1.0000 -0.0012 +vn 0.0006 1.0000 0.0059 +vn 0.0000 1.0000 0.0016 +vn -0.0002 1.0000 0.0008 +vn -0.0002 1.0000 0.0001 +vn 0.0002 1.0000 -0.0010 +vn 0.0002 1.0000 -0.0003 +vn -0.0002 1.0000 0.0007 +vn -0.0002 1.0000 0.0000 +vn 0.0010 1.0000 -0.0005 +vn 0.0009 1.0000 -0.0001 +vn -0.0000 1.0000 0.0010 +vn 0.0004 1.0000 -0.0004 +vn 0.0002 1.0000 0.0002 +vn 0.0005 1.0000 -0.0004 +vn -0.0000 1.0000 -0.0005 +vn 0.0001 1.0000 -0.0004 +vn -0.0002 1.0000 -0.0009 +vn -0.0003 1.0000 -0.0003 +vn 0.0347 0.9986 -0.0408 +vn 0.0154 0.9993 0.0331 +vn 0.5562 0.7813 -0.2831 +vn 0.0003 1.0000 0.0010 +vn 0.0001 1.0000 0.0008 +vn -0.0001 1.0000 -0.0051 +vn 0.0052 0.9999 0.0096 +vn 0.0003 1.0000 -0.0007 +vn -0.0006 1.0000 0.0030 +vn -0.0024 1.0000 0.0067 +vn -0.0008 1.0000 0.0053 +vn 0.0326 0.9986 0.0423 +vn 0.0004 1.0000 0.0042 +vn -0.1630 0.9836 0.0770 +vn 0.0015 1.0000 0.0008 +vn 0.0008 1.0000 -0.0000 +vn -0.0006 1.0000 -0.0062 +vn -0.0015 1.0000 -0.0050 +vn 0.0044 1.0000 -0.0081 +vn 0.0077 0.9999 -0.0103 +vn 0.0041 0.9998 -0.0205 +vn -0.0067 1.0000 -0.0042 +vn 0.0001 1.0000 0.0000 +vn 0.0130 0.9999 -0.0043 +vn 0.0093 1.0000 -0.0007 +vn -0.0001 1.0000 0.0044 +vn -0.0138 0.9999 -0.0004 +vn 0.0133 0.9999 -0.0027 +vn 0.1382 0.9877 -0.0728 +vn -0.0304 0.9967 0.0757 +vn 0.0301 0.9986 -0.0426 +vn -0.0285 0.9988 -0.0392 +vn -0.0132 -0.9998 -0.0134 +vn -0.0055 -1.0000 -0.0012 +vn -0.0104 -0.9998 -0.0143 +vn 0.3487 -0.7870 -0.5090 +vn -0.0473 -0.9833 -0.1756 +vn -0.0053 -0.9977 -0.0677 +vn 0.0071 -0.9999 -0.0075 +vn -0.0116 -0.9998 -0.0129 +vn -0.0083 -0.9998 -0.0191 +vn 0.0044 -0.9987 -0.0509 +vn -0.0077 -1.0000 -0.0039 +vn 0.0033 -0.9978 -0.0662 +vn 0.0079 -0.9979 -0.0641 +vn -0.0037 -0.9980 -0.0634 +vn 0.0002 -1.0000 0.0006 +vn 0.0008 -1.0000 0.0002 +vn 0.0012 -1.0000 -0.0009 +vn 0.0000 -1.0000 0.0010 +vn 0.0025 -1.0000 0.0011 +vn -0.0132 -0.9999 0.0081 +vn -0.0076 -1.0000 0.0038 +vn 0.0000 -1.0000 -0.0012 +vn -0.0027 -1.0000 -0.0007 +vn 0.0071 -1.0000 -0.0015 +vn 0.0017 -1.0000 -0.0002 +vn -0.0118 -0.9999 -0.0086 +vn -0.0055 -1.0000 0.0065 +vn -0.0098 -0.9999 -0.0065 +vn 0.0042 -1.0000 -0.0037 +vn 0.0145 -0.9997 -0.0186 +vn 0.0027 -1.0000 0.0004 +vn -0.0175 0.1162 -0.9931 +vn 0.5867 -0.2361 -0.7746 +vn 0.9719 0.1991 0.1253 +vn 0.3142 -0.1258 0.9410 +vn 0.2891 -0.1629 0.9433 +vn 0.2944 -0.1551 0.9430 +vn 0.2696 -0.1908 0.9439 +vn -0.8891 0.1789 0.4214 +vn -0.9931 -0.1083 -0.0451 +vn -0.3507 -0.9023 -0.2507 +vn -0.2720 -0.8742 -0.4021 +vn -0.5013 -0.7355 -0.4558 +vn -0.5266 -0.3631 -0.7686 +vn -0.6726 -0.6976 -0.2469 +vn -0.6709 -0.7415 -0.0069 +vn -0.6689 -0.7433 -0.0067 +vn -0.3902 -0.8196 -0.4194 +vn -0.2088 -0.8169 -0.5377 +vn -0.3429 -0.7720 -0.5352 +vn -0.2113 -0.8116 -0.5446 +vn -0.2491 -0.7084 -0.6604 +vn -0.1954 -0.9803 0.0277 +vn -0.6948 -0.7128 0.0961 +vn -0.3452 -0.9369 0.0558 +vn -0.6270 -0.7201 -0.2973 +vn -0.5751 -0.2511 -0.7786 +vn -0.8620 -0.4666 0.1981 +vn -0.7599 -0.6418 0.1030 +vn -0.6318 -0.7752 0.0051 +vn -0.1126 -0.3662 -0.9237 +vn -0.0343 -0.3141 -0.9488 +vn -0.0267 -0.5231 -0.8518 +vn -0.0435 -0.7098 -0.7031 +vn -0.0416 -0.7534 -0.6563 +vn -0.2419 -0.9685 -0.0598 +vn -0.3149 -0.9252 -0.2118 +vn -0.1449 -0.9761 -0.1619 +vn -0.2203 -0.7449 -0.6297 +vn -0.0699 -0.9633 -0.2592 +vn -0.0435 -0.9732 -0.2257 +vn -0.1472 -0.9436 -0.2966 +vn -0.8385 -0.5329 -0.1138 +vn -0.5724 -0.8190 -0.0397 +vn -0.0594 -0.8788 -0.4735 +vn -0.4369 -0.7768 -0.4536 +vn -0.4574 -0.6952 -0.5545 +vn -0.6060 -0.7954 0.0115 +vn -0.5811 -0.7984 -0.1577 +vn -0.4323 -0.8921 -0.1316 +vn -0.0557 -0.6951 -0.7168 +vn -0.6513 -0.5457 -0.5273 +vn -0.6432 -0.6619 -0.3849 +vn -0.8234 -0.5582 -0.1023 +vn -0.4509 -0.5059 -0.7354 +vn -0.3180 -0.7213 -0.6153 +vn -0.8186 -0.5682 0.0839 +vn -0.8285 -0.4659 -0.3108 +vn -0.8831 -0.4586 0.0996 +vn -0.3002 -0.5083 -0.8071 +vn -0.5525 -0.4890 -0.6750 +vn -0.7799 -0.4433 -0.4418 +vn -0.9011 -0.4039 -0.1578 +vn -0.1065 0.0340 -0.9937 +vn -0.0351 -0.4383 0.8982 +vn -0.2123 -0.6069 0.7659 +vn -0.1228 -0.8154 0.5658 +vn -0.3845 -0.3216 0.8653 +vn -0.3300 -0.6228 0.7094 +vn -0.6341 -0.3156 0.7059 +vn -0.4443 -0.5852 0.6784 +vn -0.7991 -0.3441 0.4930 +vn -0.4342 -0.8099 0.3943 +vn -0.9625 -0.2707 0.0162 +vn -0.7274 -0.6099 0.3144 +vn -0.6689 -0.6499 0.3608 +vn -0.1581 -0.9647 0.2108 +vn 0.1772 -0.9261 0.3330 +vn 0.1660 -0.8986 0.4061 +vn 0.1622 -0.9867 0.0122 +vn 0.1098 -0.5893 0.8004 +vn 0.1775 -0.3074 0.9349 +vn 0.2284 -0.3547 0.9067 +vn 0.1867 -0.9132 0.3623 +vn 0.1516 -0.9814 0.1178 +vn -0.0009 -0.5971 0.8022 +vn 0.2195 -0.2836 0.9335 +vn -0.0132 -0.8919 0.4521 +vn 0.0001 -0.8780 0.4787 +vn 0.0685 -0.7350 0.6745 +vn 0.4897 -0.6591 0.5708 +vn 0.5509 -0.3806 0.7427 +vn 0.6759 -0.3147 0.6664 +vn 0.5077 -0.7018 0.4997 +vn 0.3138 -0.8126 0.4912 +vn 0.5886 -0.2415 0.7715 +vn 0.5556 -0.4870 0.6739 +vn 0.5690 -0.6642 0.4848 +vn 0.1729 -0.9442 0.2805 +vn 0.1046 -0.9943 0.0203 +vn 0.1461 -0.9811 0.1272 +vn 0.0900 -0.9903 0.1056 +vn 0.3647 -0.5439 0.7558 +vn 0.0376 -0.9021 0.4298 +vn -0.4610 -0.2886 -0.8392 +vn -0.1358 -0.0263 -0.9904 +vn -0.0276 -0.0752 -0.9968 +vn -0.2937 0.0241 -0.9556 +vn -0.4441 0.0453 -0.8948 +vn -0.5835 0.0364 -0.8113 +vn -0.7072 -0.0021 -0.7070 +vn -0.8013 -0.0616 -0.5951 +vn -0.9014 -0.0924 -0.4231 +vn -0.8441 -0.1147 -0.5238 +vn -0.9603 -0.0424 -0.2756 +vn -0.9927 -0.0192 -0.1188 +vn -0.9988 -0.0240 0.0416 +vn -0.9781 -0.0568 0.2004 +vn -0.9327 -0.1279 0.3372 +vn -0.7295 -0.4331 -0.5293 +vn -0.7754 -0.0809 -0.6262 +vn -0.9153 -0.0905 -0.3924 +vn -0.9155 -0.2815 -0.2874 +vn -0.8572 -0.3722 -0.3560 +vn -0.9953 0.0106 -0.0960 +vn -0.9993 -0.0335 -0.0156 +vn -0.9759 0.0286 -0.2163 +vn -0.8586 -0.1863 -0.4776 +vn 0.1098 -0.9927 -0.0492 +vn 0.0627 -0.9839 -0.1672 +vn 0.1559 -0.9838 -0.0881 +vn 0.0465 -0.9987 -0.0199 +vn -0.1924 -0.9751 0.1103 +vn -0.1388 -0.9829 0.1206 +vn -0.2348 -0.9719 -0.0148 +vn 0.0002 -0.9553 -0.2956 +vn -0.0074 -0.9904 -0.1382 +vn 0.1047 -0.9658 -0.2374 +vn 0.1518 -0.9700 -0.1898 +vn 0.0772 -0.9708 -0.2272 +vn 0.4624 -0.8043 -0.3733 +vn 0.5099 -0.8341 -0.2106 +vn -0.0558 -0.9873 -0.1487 +vn -0.0362 -0.9764 -0.2130 +vn -0.0555 -0.9971 -0.0514 +vn -0.0011 -0.9676 0.2523 +vn -0.0102 -0.9967 0.0805 +vn 0.2052 -0.9786 -0.0157 +vn 0.5211 -0.8527 -0.0364 +vn 0.0724 -0.7632 -0.6420 +vn 0.0891 -0.9614 -0.2603 +vn 0.0009 -0.8735 -0.4869 +vn -0.0264 -0.9650 -0.2608 +vn -0.0196 -0.9433 -0.3315 +vn -0.0977 -0.9952 -0.0052 +vn -0.0954 -0.9937 -0.0587 +vn -0.0971 -0.9930 0.0667 +vn -0.0625 -0.9776 0.2009 +vn -0.0893 -0.9665 0.2408 +vn -0.1042 -0.9711 0.2148 +vn -0.4571 -0.8782 -0.1410 +vn -0.3128 -0.9486 -0.0485 +vn -0.0094 -0.9388 0.3444 +vn 0.0509 -0.9492 0.3106 +vn 0.0882 -0.9551 0.2829 +vn -0.2855 -0.9106 -0.2990 +vn -0.0814 -0.9929 -0.0871 +vn -0.0157 -0.7710 -0.6367 +vn -0.0096 -0.9293 -0.3691 +vn -0.0084 -0.9071 -0.4209 +vn -0.0103 -0.9344 -0.3562 +vn 0.0995 -0.9652 -0.2419 +vn 0.4101 -0.6847 -0.6025 +vn 0.2301 -0.9700 0.0780 +vn -0.1564 -0.9859 0.0598 +vn -0.1765 -0.9838 -0.0327 +vn -0.1343 -0.9906 0.0279 +vn 0.0001 -0.0121 -0.9999 +vn 0.0492 -0.2549 -0.9657 +vn 0.1869 0.0117 -0.9823 +vn 0.0009 0.0027 -1.0000 +vn -0.8257 0.0068 0.5640 +vn -0.5483 0.0174 0.8361 +vn -0.1836 0.0105 0.9829 +vn -0.2098 -0.0195 0.9776 +vn 0.9557 0.0033 -0.2945 +vn 0.9867 -0.0218 -0.1613 +vn 0.9426 -0.0110 -0.3336 +vn 0.7938 -0.3664 -0.4854 +vn 0.8057 0.0100 -0.5923 +vn 0.6278 -0.3798 -0.6794 +vn 0.5400 0.0085 -0.8416 +vn 0.4312 -0.3182 -0.8443 +vn 0.2406 -0.3019 -0.9225 +vn -0.0054 0.0028 1.0000 +vn -0.9151 -0.3195 0.2458 +vn -0.4712 -0.0756 -0.8788 +vn -0.1576 -0.0748 -0.9847 +vn 0.0547 -0.2292 -0.9718 +vn -0.4727 0.0084 0.8812 +vn 0.2826 0.2963 0.9123 +vn 0.3412 -0.1229 0.9319 +vn 0.2763 0.3253 0.9043 +vn 0.3441 -0.1707 0.9233 +vn 0.8355 -0.3522 0.4218 +vn 0.6723 0.7189 0.1766 +vn 0.7643 -0.6194 -0.1794 +vn 0.5365 0.6733 -0.5088 +vn -0.9139 -0.3691 -0.1687 +vn -0.7173 -0.6769 -0.1650 +vn -0.7013 -0.5979 -0.3881 +vn -0.8434 -0.5356 -0.0420 +vn -0.4072 -0.7938 -0.4517 +vn -0.9163 -0.2198 0.3348 +vn -0.9871 -0.0711 0.1435 +vn -0.9845 -0.0916 -0.1498 +vn -0.3688 -0.8187 -0.4402 +vn 0.0053 -0.9999 0.0107 +vn -0.0037 -1.0000 -0.0058 +vn 0.0244 -0.9992 0.0319 +vn 0.0063 -0.0716 0.9974 +vn 0.0144 -0.9999 0.0042 +vn 0.0465 -0.9986 0.0249 +vn 0.0458 -0.9989 0.0035 +vn -0.0071 -1.0000 -0.0015 +vn 0.0797 -0.9735 0.2145 +vn 0.2504 -0.9674 0.0374 +vn -0.0225 -0.9994 0.0262 +vn -0.1141 -0.9778 0.1759 +vn 0.1848 -0.9760 0.1154 +vn 0.2019 -0.8786 0.4328 +vn 0.2766 -0.9266 0.2548 +vn 0.1420 -0.9828 0.1180 +vn -0.0089 -0.9998 -0.0182 +vn 0.9018 -0.4029 0.1565 +vn 0.7296 -0.2357 -0.6420 +vn -0.0857 0.2055 -0.9749 +vn -0.1619 -0.5025 -0.8493 +vn -0.6074 0.6265 -0.4885 +vn 0.2133 -0.0743 0.9742 +vn -0.1044 -0.0736 0.9918 +vn -0.2523 -0.2131 0.9439 +vn -0.0062 -0.7592 0.6509 +vn 0.1962 -0.2668 0.9436 +vn 0.1757 -0.7162 0.6754 +vn -0.0028 -0.8038 0.5949 +vn 0.0425 -0.5902 0.8061 +vn 0.0878 -0.0763 0.9932 +vn 0.1417 -0.4891 0.8606 +vn -0.0025 -0.8475 0.5309 +vn 0.0246 -0.9351 0.3536 +vn 0.0094 -0.9250 0.3799 +vn 0.4085 -0.5900 0.6965 +vn 0.5397 -0.5562 0.6320 +vn 0.5788 -0.5291 0.6205 +vn 0.5802 -0.7803 0.2335 +vn 0.7270 -0.6500 0.2214 +vn 0.8146 -0.4768 0.3301 +vn 0.5202 -0.8509 0.0728 +vn 0.3203 -0.9412 0.1074 +vn 0.9832 -0.0595 0.1728 +vn 0.9325 -0.3522 0.0805 +vn 0.8446 -0.5047 0.1788 +vn 0.9144 -0.3932 0.0963 +vn 0.7554 -0.4725 0.4539 +vn 0.6593 -0.5548 0.5074 +vn 0.3632 -0.4820 0.7974 +vn 0.1998 -0.6256 0.7541 +vn 0.4826 -0.7380 0.4716 +vn 0.4947 -0.8002 0.3391 +vn 0.3350 -0.7866 0.5187 +vn 0.1885 -0.8282 0.5277 +vn 0.6920 -0.7100 0.1303 +vn 0.7302 -0.6715 0.1261 +vn 0.6604 -0.7406 0.1238 +vn 0.2022 -0.9451 0.2568 +vn 0.7487 -0.6393 0.1752 +vn 0.5013 -0.5856 0.6370 +vn 0.2550 -0.7630 0.5940 +vn 0.1249 -0.7911 0.5988 +vn 0.5415 -0.5009 0.6752 +vn 0.0124 -0.6345 0.7728 +vn 0.0129 -0.6298 0.7767 +vn 0.4912 -0.7011 0.5169 +vn -0.7858 -0.3817 -0.4866 +vn 0.4709 -0.2514 0.8456 +vn -0.8671 -0.3147 -0.3861 +vn -0.9801 0.1882 0.0629 +vn -0.0922 -0.1574 0.9832 +vn 0.6145 0.2254 0.7560 +vn 0.8133 -0.2986 -0.4994 +vn 0.2565 0.2934 -0.9209 +vn -0.1711 -0.1207 -0.9778 +vn 0.2982 -0.5325 -0.7921 +vn -0.8961 0.2506 -0.3662 +vn -0.5017 -0.0965 0.8597 +vn -0.4485 -0.0500 0.8924 +vn -0.6251 -0.2141 0.7506 +vn -0.3103 0.0628 0.9486 +vn 0.9793 -0.0072 0.2022 +vn 0.9881 0.0228 0.1522 +vn 0.9387 -0.0877 0.3333 +vn 0.9913 0.1285 -0.0297 +vn -0.9479 -0.2354 -0.2145 +vn -0.6022 0.1555 0.7830 +vn -0.4172 0.0457 0.9077 +vn -0.4344 0.0554 0.8990 +vn -0.2728 -0.0327 0.9615 +vn 0.7595 0.0203 0.6502 +vn 0.8325 -0.0291 0.5532 +vn 0.7949 -0.0025 0.6068 +vn 0.8556 -0.0469 0.5156 +vn 0.6172 -0.1017 -0.7802 +vn 0.6975 -0.0356 -0.7157 +vn 0.7891 0.0544 -0.6118 +vn 0.4832 -0.1956 -0.8534 +vn -0.7960 0.2325 -0.5588 +vn 0.7627 0.0808 0.6417 +vn 0.7017 -0.0932 -0.7063 +vn 0.7925 0.3673 -0.4868 +vn -0.4515 -0.2950 -0.8421 +vn -0.8466 0.2132 -0.4876 +vn -0.9332 -0.0963 0.3463 +vn -0.4180 0.0821 0.9047 +vn 0.2781 -0.1325 0.9514 +vn -0.0129 -0.9999 -0.0031 +vn -0.0206 -0.9989 -0.0426 +vn -0.0376 -0.9993 -0.0029 +vn -0.0134 -0.9952 0.0973 +vn 0.0073 -0.9992 0.0380 +vn 1.0000 0.0015 0.0034 +vn 0.9856 -0.0006 0.1694 +vn 0.9922 -0.0042 0.1244 +vn 0.9593 -0.0084 0.2824 +vn 0.9013 -0.0084 0.4331 +vn 0.8206 -0.0054 0.5714 +vn 0.7103 -0.0068 0.7039 +vn 0.7233 -0.0109 0.6904 +vn 0.6082 -0.0236 0.7934 +vn 0.0395 -0.0031 0.9992 +vn -0.0036 0.0000 1.0000 +vn 0.0918 -0.0061 0.9958 +vn 0.3857 -0.0295 0.9222 +vn 0.3557 -0.0271 0.9342 +vn 0.4883 -0.0210 0.8724 +vn 0.2505 -0.0407 0.9673 +vn 0.0999 -0.0407 0.9942 +vn 0.1350 -0.0440 0.9899 +vn 0.0293 -0.0507 0.9983 +vn 0.0090 -0.0194 0.9998 +vn 0.7121 -0.0360 0.7011 +vn 0.7327 -0.0092 0.6805 +vn 0.7989 -0.0235 0.6010 +vn 0.5957 -0.0524 0.8015 +vn 0.4940 -0.0384 0.8686 +vn 0.3480 0.0157 0.9373 +vn 0.1912 0.0362 0.9809 +vn 0.0490 0.0098 0.9987 +vn 0.7322 -0.0947 0.6744 +vn 0.7218 -0.0282 0.6915 +vn 0.7368 -0.0150 0.6759 +vn 0.6524 -0.0312 0.7572 +vn 0.5453 -0.0121 0.8381 +vn 0.4287 0.0377 0.9027 +vn 0.2115 -0.0032 0.9774 +vn 0.3415 0.0133 0.9398 +vn 0.9994 0.0039 -0.0344 +vn 1.0000 0.0000 0.0092 +vn -0.0400 0.0030 -0.9992 +vn -0.0379 0.0000 -0.9993 +vn -0.0411 0.0045 -0.9991 +vn -0.0433 0.0075 -0.9990 +vn -0.9938 -0.1005 0.0470 +vn -0.9809 0.0002 0.1945 +vn -0.9926 -0.0614 0.1050 +vn -0.9862 -0.1600 -0.0431 +vn -0.0219 -0.0053 -0.9997 +vn -0.0214 -0.0041 -0.9998 +vn -0.0216 -0.0046 -0.9998 +vn -0.0221 -0.0057 -0.9997 +vn -0.3625 -0.0509 -0.9306 +vn -0.5876 0.0165 -0.8090 +vn -0.6400 0.0440 -0.7671 +vn -0.5573 0.0073 -0.8303 +vn -0.5552 0.0082 -0.8316 +vn -0.5622 0.0051 -0.8270 +vn -0.5644 0.0042 -0.8255 +vn -0.7317 0.0181 -0.6814 +vn -0.7349 0.0041 -0.6782 +vn 0.0073 0.9999 0.0069 +vn 0.0824 0.9965 -0.0158 +vn 0.0334 0.9994 -0.0020 +vn 0.0001 1.0000 0.0002 +vn 0.0001 1.0000 0.0053 +vn 0.0013 1.0000 0.0013 +vn 0.0032 1.0000 0.0007 +vn 0.0060 0.9999 -0.0104 +vn 0.0124 0.9947 0.1019 +vn 0.0003 1.0000 0.0014 +vn 0.0074 1.0000 0.0018 +vn 0.0053 1.0000 0.0045 +vn 0.0097 0.9743 0.2249 +vn -0.0079 1.0000 0.0059 +vn 0.7896 0.1778 -0.5873 +vn 0.2698 -0.1598 -0.9496 +vn -0.7830 0.1548 -0.6024 +vn -0.9747 -0.2149 0.0607 +vn -0.1354 0.2567 0.9569 +vn 0.5044 -0.5634 0.6544 +vn 0.9191 -0.0367 0.3924 +vn 0.8809 0.0987 -0.4629 +vn 0.3715 -0.2797 -0.8853 +vn -0.2010 0.0622 -0.9776 +vn -0.9779 -0.1384 0.1566 +vn -0.9976 -0.0693 0.0052 +vn -0.9907 -0.0032 -0.1361 +vn -0.9526 -0.1785 0.2465 +vn -0.2490 0.1441 0.9577 +vn 0.5771 -0.2142 0.7881 +vn 0.5130 -0.2685 0.8153 +vn 0.5895 -0.2030 0.7819 +vn 0.6932 -0.0987 0.7139 +vn 0.0108 -0.9993 -0.0348 +vn 0.0841 -0.9581 -0.2738 +vn 0.0142 -0.9988 -0.0461 +vn -0.0045 -0.9990 0.0446 +vn -0.0154 -0.9999 0.0073 +vn -0.0417 -0.9985 -0.0352 +vn -0.0192 -0.9992 0.0360 +vn -0.0382 -0.9940 -0.1025 +vn 0.7016 0.2523 -0.6665 +vn -0.1941 -0.3111 -0.9304 +vn -0.7460 0.0737 -0.6618 +vn -0.6917 -0.0559 0.7200 +vn -0.6989 -0.0481 0.7136 +vn -0.7100 -0.0357 0.7033 +vn -0.6788 -0.0697 0.7310 +vn 0.8985 0.0430 0.4369 +vn 0.5519 -0.3652 0.7497 +vn -0.9534 0.0003 0.3018 +vn -0.9413 0.0022 0.3375 +vn -0.9852 -0.0004 0.1717 +vn -0.9505 -0.0000 0.3107 +vn -0.0117 0.0003 -0.9999 +vn -0.0379 -0.0016 -0.9993 +vn -0.1734 -0.0013 -0.9849 +vn -0.9994 -0.0280 -0.0214 +vn -0.9977 0.0124 -0.0661 +vn -0.3521 -0.0327 -0.9354 +vn -0.3692 0.0304 -0.9288 +vn -0.5037 0.0628 -0.8616 +vn -0.6257 0.0297 -0.7795 +vn -0.7328 -0.0314 -0.6797 +vn -0.8181 -0.1177 -0.5629 +vn -0.8631 -0.0975 -0.4956 +vn -0.9345 -0.0140 -0.3556 +vn -0.9763 0.0254 -0.2150 +vn -0.3629 -0.0045 -0.9318 +vn -0.5637 -0.0068 -0.8259 +vn -0.4339 -0.0296 -0.9005 +vn -0.5358 -0.0421 -0.8433 +vn -0.6312 -0.0197 -0.7754 +vn -0.7160 0.0361 -0.6972 +vn -0.7614 0.0007 -0.6483 +vn -0.9312 -0.0041 -0.3645 +vn -0.8462 -0.0244 -0.5323 +vn -0.6746 -0.0142 -0.7380 +vn -0.7965 -0.0181 -0.6043 +vn -0.9078 -0.0311 -0.4182 +vn -0.8547 -0.0088 -0.5190 +vn -0.9081 -0.0245 -0.4179 +vn -0.9491 -0.0195 -0.3143 +vn -0.9874 -0.0183 -0.1572 +vn -0.9749 -0.0276 -0.2211 +vn -0.9936 -0.0395 -0.1057 +vn -0.9994 -0.0266 -0.0216 +vn -0.9137 -0.0162 -0.4060 +vn -0.9653 -0.0027 -0.2611 +vn -0.9929 -0.0007 -0.1193 +vn -0.9993 -0.0054 0.0363 +vn -0.9820 -0.0034 0.1889 +vn -0.1519 -0.0058 -0.9884 +vn -0.3032 -0.0089 -0.9529 +vn -0.4522 0.0004 -0.8919 +vn -0.5728 0.0021 -0.8197 +vn -0.6927 -0.0176 -0.7210 +vn 0.9096 0.0264 -0.4146 +vn 0.9188 0.0433 -0.3924 +vn 0.9041 0.0169 -0.4270 +vn 0.8938 0.0000 -0.4485 +vn 0.2773 -0.0098 0.9607 +vn 0.2858 -0.0000 0.9583 +vn 0.2761 -0.0112 0.9611 +vn 0.2675 -0.0210 0.9633 +vn 0.0000 0.0000 -1.0000 +vn 0.5514 0.0089 0.8342 +vn 0.3701 -0.0079 0.9290 +vn 0.3705 -0.0091 0.9288 +vn 0.6189 -0.0081 0.7854 +vn 0.9472 0.0124 0.3204 +vn 0.8160 0.0267 0.5774 +vn 0.8851 -0.0174 0.4651 +vn 0.9731 -0.0085 0.2303 +vn 0.7486 0.0216 0.6627 +vn 0.8158 -0.0157 0.5781 +vn 0.9990 0.0093 0.0441 +vn 0.9990 0.0083 0.0435 +vn -0.0001 1.0000 -0.0001 +vn -0.0023 1.0000 -0.0066 +vn 0.0000 1.0000 -0.0008 +vn -0.0026 1.0000 0.0075 +vn -0.0026 1.0000 -0.0005 +vn -0.0003 1.0000 -0.0000 +vn -0.1830 0.9800 0.0781 +vn -0.0639 0.9978 0.0176 +vn -0.0312 0.9995 -0.0071 +vn -0.0001 1.0000 0.0002 +vn -0.0206 0.9984 -0.0528 +vn -0.0371 0.9904 -0.1335 +vn 0.0017 1.0000 -0.0061 +vn 0.4548 -0.6872 0.5665 +vn 0.4757 -0.3430 0.8100 +vn 0.4802 -0.6715 0.5644 +vn 0.4173 -0.5935 0.6882 +vn -0.6805 -0.6728 -0.2902 +vn -0.5268 -0.2421 -0.8148 +vn -0.3957 -0.6411 -0.6576 +vn -0.5343 -0.6173 -0.5775 +vn -0.7033 -0.0873 -0.7055 +vn -0.9013 -0.2408 0.3601 +vn -0.9069 0.0000 0.4214 +vn 0.3179 -0.6589 -0.6817 +vn 0.6353 -0.7628 -0.1206 +vn 0.7892 -0.6132 -0.0329 +vn 0.7379 -0.6251 -0.2545 +vn 0.2784 -0.5466 -0.7898 +vn -0.3813 -0.4611 -0.8013 +vn -0.3360 -0.7498 -0.5700 +vn -0.5697 -0.0222 -0.8216 +vn -0.2921 -0.8193 -0.4933 +vn -0.2923 -0.8191 -0.4936 +vn -0.0006 -0.5425 -0.8400 +vn -0.5743 -0.8087 -0.1271 +vn -0.7166 -0.6820 -0.1460 +vn -0.7521 -0.6428 -0.1453 +vn -0.7992 -0.5489 -0.2450 +vn -0.5951 -0.6902 -0.4116 +vn -0.7173 -0.5034 -0.4817 +vn -0.7930 -0.0345 0.6082 +vn -0.3495 0.0541 0.9354 +vn 0.3553 -0.0437 0.9337 +vn 0.9785 0.0446 0.2016 +vn 0.8908 -0.0535 -0.4512 +vn 0.4383 0.0320 -0.8982 +vn -0.7247 0.0147 -0.6889 +vn -0.7904 -0.0159 -0.6123 +vn -0.8023 -0.0218 -0.5965 +vn -0.7080 0.0220 -0.7059 +vn 0.5756 -0.0424 -0.8166 +vn 0.3833 0.0042 -0.9236 +vn 0.6096 -0.0512 -0.7910 +vn 0.3387 0.0143 -0.9408 +vn -0.8570 0.0062 -0.5152 +vn -0.8848 -0.0062 -0.4658 +vn -0.8614 0.0043 -0.5079 +vn -0.8896 -0.0084 -0.4566 +vn -0.6911 -0.0034 0.7228 +vn -0.5084 0.0336 0.8604 +vn -0.7223 -0.0106 0.6915 +vn -0.4796 0.0389 0.8766 +vn 0.5889 -0.0589 0.8061 +vn 0.9571 0.0556 0.2844 +vn -0.6001 0.0189 0.7997 +vn -0.8261 -0.0282 0.5628 +vn -0.7988 -0.0215 0.6012 +vn -0.5536 0.0270 0.8324 +vn 0.4639 -0.0250 0.8855 +vn 0.7341 0.0402 0.6778 +vn 0.4016 -0.0380 0.9150 +vn 0.7689 0.0501 0.6374 +vn 0.8041 -0.0375 -0.5933 +vn 0.5710 0.0222 -0.8206 +vn 0.8368 -0.0478 -0.5455 +vn 0.5234 0.0325 -0.8515 +vn -0.6802 -0.0185 -0.7328 +vn -0.8259 0.0197 -0.5635 +vn -0.6497 -0.0253 -0.7598 +vn -0.8532 0.0283 -0.5209 +vn 0.7555 -0.0090 -0.6551 +vn 0.6789 0.0136 -0.7341 +vn 0.7694 -0.0134 -0.6387 +vn 0.6592 0.0190 -0.7517 +vn -0.5963 -0.0131 -0.8027 +vn -0.5861 -0.0105 -0.8102 +vn -0.5948 -0.0127 -0.8038 +vn -0.5837 -0.0099 -0.8119 +vn -0.8774 0.0101 0.4797 +vn -0.8955 0.0177 0.4446 +vn -0.7915 -0.0202 0.6108 +vn -0.7732 -0.0259 0.6336 +vn 0.7063 -0.0025 0.7079 +vn 0.6223 0.0240 0.7824 +vn 0.6072 0.0285 0.7941 +vn 0.7238 -0.0085 0.6899 +vn -0.1948 0.0856 0.9771 +vn 0.4990 -0.0971 0.8611 +vn 0.9009 0.1029 -0.4216 +vn 0.4041 -0.0880 -0.9105 +vn -0.8025 0.0781 -0.5916 +vn -0.9976 -0.0675 -0.0143 +vn 0.7658 -0.0633 0.6399 +vn 0.9524 0.0792 -0.2944 +vn 0.6770 -0.0739 -0.7323 +vn -0.7775 -0.0194 -0.6286 +vn -0.5925 0.0546 -0.8038 +vn -0.4954 0.0867 -0.8643 +vn -0.8381 -0.0496 -0.5433 +vn -0.9123 0.0341 0.4081 +vn -0.6746 -0.0371 0.7373 +vn -0.8693 0.0175 0.4940 +vn -0.6200 -0.0491 0.7830 +vn 0.1266 0.0649 0.9898 +vn 0.3480 -0.0817 -0.9339 +vn 0.4186 -0.0281 -0.9077 +vn 0.5491 0.0800 -0.8319 +vn 0.1940 -0.1895 -0.9625 +vn -0.7033 0.1809 -0.6875 +vn -0.9879 -0.1216 -0.0961 +vn -0.5496 0.1078 0.8284 +vn -0.3174 0.0006 0.9483 +vn -0.4454 0.0582 0.8934 +vn -0.1959 -0.0514 0.9793 +vn 0.8848 -0.0167 0.4657 +vn 0.9191 0.0321 0.3927 +vn 0.9022 0.0067 0.4312 +vn 0.8569 -0.0498 0.5131 +vn -0.6764 0.0867 -0.7314 +vn -0.9273 -0.3320 -0.1726 +vn -0.7299 0.2113 0.6500 +vn 0.5267 -0.0992 0.8443 +vn 0.5807 -0.0590 0.8120 +vn 0.4271 -0.1670 0.8887 +vn 0.6765 0.0202 0.7362 +vn 0.7350 -0.1015 -0.6705 +vn 0.8234 -0.2255 -0.5207 +vn 0.7182 -0.0817 -0.6911 +vn 0.6640 -0.0229 -0.7474 +vn -0.5637 0.0585 -0.8239 +vn -0.9936 -0.1000 -0.0531 +vn -0.8322 0.0568 0.5515 +vn 0.5711 0.0014 0.8209 +vn 0.6549 -0.0424 0.7545 +vn 0.5949 -0.0106 0.8037 +vn 0.6736 -0.0527 0.7372 +vn 0.6539 -0.0404 -0.7555 +vn 0.6043 -0.0160 -0.7966 +vn 0.6161 -0.0217 -0.7874 +vn 0.6636 -0.0454 -0.7467 +vn -0.5564 0.0238 0.8306 +vn -0.5768 0.0166 0.8167 +vn -0.6164 0.0025 0.7874 +vn -0.6304 -0.0027 0.7763 +vn 0.7505 -0.0171 0.6607 +vn 0.7953 0.0094 0.6062 +vn 0.7307 -0.0280 0.6822 +vn 0.8099 0.0186 0.5863 +vn 0.5812 -0.0163 -0.8136 +vn 0.5856 -0.0183 -0.8104 +vn 0.5797 -0.0156 -0.8147 +vn 0.5871 -0.0190 -0.8093 +vn -0.7907 0.0320 -0.6113 +vn -0.8590 -0.0047 -0.5120 +vn -0.8091 0.0228 -0.5872 +vn -0.8737 -0.0136 -0.4863 +vn 0.4304 0.2235 0.8745 +vn 0.9486 -0.2515 0.1920 +vn 0.9672 0.0825 -0.2402 +vn -0.0567 0.0622 -0.9964 +vn 0.1346 -0.0565 -0.9893 +vn 0.0119 0.0198 -0.9997 +vn -0.1565 0.1236 -0.9799 +vn -0.9480 -0.1306 -0.2904 +vn -0.8637 0.1540 0.4799 +vn -0.4059 -0.1683 0.8983 +vn -0.6611 0.1500 -0.7351 +vn -0.9771 -0.1402 0.1600 +vn -0.7446 0.0832 0.6623 +vn 0.4814 -0.0998 0.8708 +vn 0.4958 -0.0884 0.8639 +vn 0.4846 -0.0973 0.8693 +vn 0.4615 -0.1154 0.8796 +vn 0.8924 0.1532 -0.4244 +vn 0.3712 -0.1871 -0.9095 +vn -0.3605 -0.0338 -0.9322 +vn -0.6406 -0.0264 -0.7674 +vn -0.5394 0.0409 -0.8411 +vn -0.4275 0.0177 -0.9038 +vn -0.9998 -0.0120 -0.0182 +vn -0.8028 -0.0104 -0.5961 +vn -0.8832 -0.0252 -0.4684 +vn -0.8634 -0.0075 -0.5044 +vn -0.9405 -0.0175 -0.3393 +vn -0.9774 -0.0185 -0.2107 +vn -0.9963 -0.0179 -0.0840 +vn -0.7267 -0.0074 -0.6869 +vn -0.6185 -0.0331 -0.7851 +vn -0.3934 -0.0210 -0.9191 +vn -0.4975 -0.0355 -0.8668 +vn -0.3489 -0.0104 -0.9371 +vn 0.9908 0.0028 -0.1355 +vn 0.9936 -0.0686 -0.0898 +vn 0.9172 -0.1168 0.3809 +vn 0.0684 -0.0534 0.9962 +vn 0.1983 0.0350 0.9795 +vn 0.7262 -0.0125 0.6874 +vn 0.6531 0.0047 0.7573 +vn 0.5191 -0.0673 0.8521 +vn 0.4717 -0.1242 0.8730 +vn 0.3454 0.0139 0.9383 +vn 0.1291 -0.0666 0.9894 +vn 0.0224 -0.0868 0.9960 +vn 0.2609 -0.0986 0.9603 +vn 0.3536 -0.0554 0.9338 +vn 0.5019 -0.0179 0.8647 +vn 0.6163 -0.1137 0.7793 +vn 0.7029 -0.0945 0.7050 +vn 0.8136 -0.0356 0.5804 +vn 0.9000 -0.0067 0.4358 +vn 0.9606 -0.0095 0.2779 +vn 0.9963 -0.0862 -0.0065 +vn 0.9927 -0.0440 0.1124 +vn 0.7379 -0.0066 0.6748 +vn 0.0132 -0.0135 0.9998 +vn 0.7034 -0.0160 0.7106 +vn 0.4655 -0.0082 0.8850 +vn 0.0625 -0.0180 0.9979 +vn 0.6071 -0.0278 0.7942 +vn 0.1923 -0.0227 0.9811 +vn 0.3483 -0.0002 0.9374 +vn 0.0001 1.0000 0.0009 +vn -0.9491 -0.0078 -0.3148 +vn -0.8825 0.0208 -0.4698 +vn -0.8267 -0.0164 -0.5624 +vn -0.7996 -0.0095 -0.6004 +vn -0.7572 0.0156 -0.6531 +vn -0.6065 -0.0018 -0.7951 +vn -0.9990 -0.0093 -0.0441 +vn -0.9717 0.0092 -0.2362 +vn -0.3718 0.0046 -0.9283 +vn -0.3730 0.0078 -0.9278 +vn 0.5572 -0.0073 0.8303 +vn 0.5622 -0.0051 0.8270 +vn 0.5552 -0.0082 0.8317 +vn 0.7317 -0.0182 0.6814 +vn 0.5870 -0.0169 0.8094 +vn 0.6395 -0.0444 0.7675 +vn 0.0219 0.0053 0.9997 +vn 0.0216 0.0046 0.9998 +vn 0.0214 0.0041 0.9998 +vn 0.0432 -0.0031 0.9991 +vn 0.0442 -0.0044 0.9990 +vn 0.0409 -0.0000 0.9992 +vn 0.0466 -0.0075 0.9989 +vn 0.9761 0.1589 0.1485 +vn 0.9981 0.0613 0.0010 +vn 0.9931 0.1005 0.0600 +vn 0.9959 -0.0002 -0.0906 +vn -0.8598 -0.0181 0.5104 +vn -0.8673 -0.0074 0.4977 +vn -0.8649 -0.0108 0.5018 +vn -0.2633 0.0000 -0.9647 +vn -0.2582 -0.0063 -0.9661 +vn -0.2592 -0.0051 -0.9658 +vn -0.8723 -0.0000 0.4890 +vn -0.2540 -0.0113 -0.9671 +vn 0.0001 1.0000 -0.0001 +vn -0.5637 0.0083 -0.8260 +vn -0.9990 -0.0084 -0.0436 +vn 0.5644 -0.0041 0.8255 +vn 0.7349 -0.0041 0.6782 +vn 0.3613 0.0503 0.9311 +vn 0.0221 0.0057 0.9997 +vn -0.0123 -0.9990 -0.0433 +vn 0.0530 -0.9983 -0.0228 +vn 0.0188 -0.9998 -0.0097 +vn -0.0300 -0.9995 0.0015 +vn -0.0312 -0.9995 0.0080 +vn -0.0090 -0.9993 0.0371 +vn -0.0114 -0.9994 0.0328 +vn 0.0235 -0.9992 0.0339 +vn 0.0494 0.9984 -0.0289 +vn -0.9981 0.0362 -0.0491 +vn -0.5300 -0.0298 -0.8475 +vn 0.4936 0.0325 -0.8691 +vn 0.9989 -0.0225 0.0406 +vn 0.5101 0.0318 0.8595 +vn -0.3672 -0.0218 0.9299 +vn -0.8615 0.4813 -0.1619 +vn -0.2522 0.7762 -0.5779 +vn -0.3010 0.8244 -0.4792 +vn -0.2343 0.7568 -0.6102 +vn -0.1708 0.6813 -0.7118 +vn 0.6832 0.4687 -0.5600 +vn 0.5714 0.8202 0.0283 +vn 0.6629 0.5021 0.5553 +vn -0.2750 0.7093 0.6490 +vn -0.2482 0.7295 0.6374 +vn -0.2896 0.6978 0.6551 +vn -0.3102 0.6811 0.6633 +vn -0.0578 -0.9983 0.0113 +vn -0.0263 -0.9988 -0.0422 +vn -0.0189 -0.9997 -0.0171 +vn 0.0168 -0.9995 -0.0256 +vn 0.0252 -0.9997 0.0002 +vn 0.0198 -0.9995 0.0242 +vn -0.0042 -0.9998 -0.0170 +vn -0.0033 -0.9989 0.0471 +vn 0.0194 0.9997 0.0116 +vn 0.0498 0.9966 0.0650 +vn 0.0190 0.9998 0.0109 +vn -0.0163 0.9986 -0.0512 +vn 0.9996 -0.0130 -0.0241 +vn 0.9414 0.0159 0.3369 +vn 0.9319 0.0180 0.3623 +vn -0.2831 -0.0137 0.9590 +vn -0.4710 0.0031 0.8822 +vn -0.2924 -0.0129 0.9562 +vn -0.4820 0.0042 0.8762 +vn -0.9828 0.0147 -0.1843 +vn -0.6314 -0.0277 -0.7749 +vn 0.0797 0.0234 -0.9965 +vn 0.9987 -0.0148 -0.0478 +vn 0.6596 0.7432 0.1123 +vn 0.6766 0.7205 0.1516 +vn 0.7260 0.6212 0.2949 +vn 0.1929 0.6217 0.7592 +vn 0.0079 0.7322 0.6810 +vn -0.0021 0.7371 0.6758 +vn -0.1649 0.8006 0.5760 +vn -0.6889 0.4598 0.5604 +vn -0.4524 0.7064 -0.5444 +vn -0.4527 0.6961 -0.5572 +vn -0.4520 0.7133 -0.5356 +vn -0.4519 0.7201 -0.5266 +vn 0.6048 0.4305 -0.6700 +vn 0.5893 0.8075 -0.0246 +vn -0.0005 -0.9989 0.0464 +vn -0.0616 -0.9979 0.0186 +vn -0.0158 -0.9998 0.0096 +vn 0.0007 -0.9994 -0.0337 +vn -0.0331 -0.9991 -0.0278 +vn 0.0050 -0.9998 -0.0196 +vn 0.0409 -0.9988 0.0253 +vn 0.0304 -0.9995 0.0005 +vn 0.0319 -0.9994 -0.0133 +vn 0.0194 0.9998 -0.0080 +vn 0.0180 0.9997 -0.0174 +vn 0.0091 0.9970 -0.0765 +vn 0.0272 0.9987 0.0438 +vn -0.0039 -0.0330 -0.9994 +vn 0.5772 0.0123 -0.8165 +vn 0.8298 0.0093 0.5580 +vn 0.7775 0.0003 0.6288 +vn 0.7808 0.0007 0.6248 +vn 0.8328 0.0099 0.5535 +vn -0.7581 -0.0098 0.6520 +vn -0.7860 -0.0055 0.6182 +vn -0.7595 -0.0095 0.6504 +vn -0.7879 -0.0052 0.6158 +vn -0.8105 0.0241 -0.5852 +vn -0.3214 0.6418 -0.6963 +vn -0.1793 0.7468 -0.6404 +vn -0.1234 0.7802 -0.6133 +vn 0.0032 0.8404 -0.5420 +vn 0.5114 0.5952 -0.6199 +vn 0.8241 0.5625 0.0668 +vn 0.6969 0.6903 0.1947 +vn 0.6574 0.7185 0.2270 +vn 0.4994 0.7990 0.3351 +vn 0.2701 0.5593 0.7837 +vn -0.4716 0.7487 0.4658 +vn -0.5287 0.7105 0.4644 +vn -0.4629 0.7541 0.4659 +vn -0.4081 0.7857 0.4649 +vn -0.8560 0.5149 -0.0451 +vn -0.0129 -0.9998 -0.0124 +vn -0.0146 -0.9994 0.0325 +vn -0.0338 -0.9994 -0.0113 +vn 0.0002 -0.9990 -0.0436 +vn 0.0272 -0.9994 -0.0205 +vn 0.0175 -0.9997 0.0185 +vn 0.0330 -0.9991 0.0248 +vn -0.0271 0.9995 0.0133 +vn -0.9778 -0.0067 -0.2095 +vn -0.9749 0.0240 0.2212 +vn -0.9720 -0.0086 -0.2350 +vn -0.0121 0.0053 -0.9999 +vn 0.3187 0.0331 -0.9473 +vn 0.0110 0.0072 -0.9999 +vn 0.3342 0.0344 -0.9419 +vn 0.9994 -0.0160 0.0314 +vn 0.5418 0.0284 0.8400 +vn -0.1007 -0.0116 0.9948 +vn -0.9694 0.0256 0.2440 +vn -0.7446 0.6629 -0.0786 +vn -0.7747 0.6306 -0.0467 +vn -0.6552 0.7381 -0.1610 +vn -0.2181 0.5300 -0.8195 +vn -0.1541 0.5954 -0.7885 +vn -0.1110 0.6357 -0.7639 +vn -0.0102 0.7184 -0.6956 +vn 0.8210 0.4956 -0.2835 +vn 0.7809 0.5955 -0.1887 +vn 0.7374 0.6664 -0.1103 +vn 0.6451 0.7638 0.0215 +vn 0.4634 0.5640 0.6835 +vn -0.1636 0.7126 0.6823 +vn -0.0630 0.7658 0.6400 +vn -0.1886 0.6975 0.6914 +vn -0.2851 0.6318 0.7208 +vn -0.8280 0.5604 0.0175 +vn 0.0016 -0.9998 0.0180 +vn -0.0317 -0.9994 -0.0155 +vn 0.0115 -0.9996 -0.0273 +vn 0.0196 -0.9997 -0.0119 +vn 0.0330 -0.9992 0.0206 +vn -0.0004 -0.9996 -0.0267 +vn -0.0382 -0.9974 0.0618 +vn -0.0213 0.9993 -0.0295 +vn -0.0043 0.9991 -0.0419 +vn -0.0201 0.9993 -0.0304 +vn -0.0371 0.9992 -0.0179 +vn -0.9758 -0.0083 0.2183 +vn -0.9989 0.0119 -0.0443 +vn -0.9788 -0.0073 0.2048 +vn -0.9980 0.0132 -0.0618 +vn 0.3617 -0.0093 -0.9323 +vn 0.2110 -0.0264 -0.9771 +vn 0.3538 -0.0102 -0.9353 +vn 0.1987 -0.0278 -0.9797 +vn 0.9917 0.0281 0.1254 +vn 0.4745 -0.0205 0.8800 +vn -0.1206 0.0151 0.9926 +vn -0.7169 0.6943 0.0632 +vn -0.6288 0.7642 0.1437 +vn -0.7620 0.6474 0.0156 +vn -0.8187 0.5716 -0.0538 +vn -0.0871 0.5983 -0.7965 +vn 0.0268 0.7115 -0.7022 +vn 0.0938 0.7669 -0.6348 +vn 0.1947 0.8341 -0.5162 +vn 0.8133 0.4654 -0.3492 +vn 0.4215 0.6732 0.6075 +vn 0.3806 0.7034 0.6003 +vn 0.3552 0.7209 0.5951 +vn 0.3058 0.7523 0.5836 +vn -0.3787 0.5682 0.7306 +vn 0.0223 -0.9996 0.0154 +vn 0.0425 -0.9990 0.0150 +vn 0.0113 -0.9988 0.0469 +vn -0.0575 -0.9983 -0.0073 +vn -0.0094 -0.9993 -0.0371 +vn -0.0222 -0.9998 0.0017 +vn 0.0138 -0.9994 -0.0315 +vn 0.0237 -0.9995 -0.0214 +vn -0.0306 -0.9986 0.0438 +vn -0.0189 0.9974 -0.0698 +vn -0.0206 0.9966 -0.0797 +vn 0.0022 0.9987 0.0518 +vn -0.1177 -0.0070 0.9930 +vn -0.6486 0.0199 0.7609 +vn -0.9929 -0.0103 0.1183 +vn -0.8372 0.0167 -0.5467 +vn 0.0063 -0.0166 -0.9998 +vn 0.4506 0.0131 -0.8926 +vn 0.0298 -0.0151 -0.9994 +vn 0.4729 0.0147 -0.8810 +vn 0.9926 -0.0094 0.1208 +vn 0.8514 0.0195 0.5241 +vn 0.9896 -0.0079 0.1437 +vn 0.8382 0.0211 0.5450 +vn -0.1586 0.6547 0.7391 +vn -0.0850 0.7074 0.7017 +vn -0.1805 0.6375 0.7490 +vn -0.2313 0.5951 0.7696 +vn -0.7221 0.6868 0.0831 +vn -0.7149 0.6934 0.0897 +vn -0.7234 0.6856 0.0820 +vn -0.7291 0.6801 0.0767 +vn -0.5680 0.5521 -0.6105 +vn 0.0832 0.7280 -0.6805 +vn 0.0069 0.7708 -0.6370 +vn 0.0965 0.7198 -0.6874 +vn 0.1747 0.6668 -0.7245 +vn 0.7307 0.5919 -0.3402 +vn 0.6950 0.7064 -0.1340 +vn 0.7209 0.6900 0.0643 +vn 0.6721 0.6639 0.3280 +vn 0.6749 0.5443 0.4982 +vn -0.0441 0.9753 -0.2163 +vn -0.7014 0.0105 -0.7127 +vn -0.6879 0.0222 -0.7255 +vn -0.7114 0.0017 -0.7028 +vn -0.7252 -0.0107 -0.6884 +vn -0.0020 0.0228 -0.9997 +vn 0.4096 0.0408 -0.9113 +vn 0.1681 -0.0164 -0.9856 +vn -0.0912 -0.0184 -0.9957 +vn 0.7076 -0.0292 -0.7060 +vn 0.9230 0.0292 -0.3836 +vn 0.9987 -0.0408 -0.0297 +vn 0.9749 0.0164 0.2219 +vn 0.8850 0.0184 0.4653 +vn 0.9229 -0.0228 0.3844 +vn 0.4246 -0.0273 0.9050 +vn 0.4295 -0.0305 0.9025 +vn 0.4198 -0.0241 0.9073 +vn 0.4159 -0.0216 0.9091 +vn -0.0912 0.0411 0.9950 +vn -0.4300 0.0298 0.9023 +vn -0.2749 -0.0323 0.9609 +vn -0.6661 -0.0318 0.7452 +vn -0.9275 0.0358 0.3722 +vn -0.9817 -0.0148 0.1901 +vn -0.9997 0.0233 -0.0120 +vn -0.9966 -0.0109 -0.0816 +vn -0.9804 0.0251 -0.1954 +vn -0.6660 0.0318 -0.7452 +vn -0.9163 -0.0305 -0.3993 +vn -0.4109 -0.0387 -0.9108 +vn -0.0011 0.0292 -0.9996 +vn 0.3548 -0.0408 -0.9341 +vn 0.5781 0.0164 -0.8158 +vn 0.7685 0.0184 -0.6396 +vn 0.7083 -0.0228 -0.7055 +vn 0.9986 -0.0273 -0.0459 +vn 0.9982 -0.0305 -0.0514 +vn 0.9989 -0.0241 -0.0406 +vn 0.9991 -0.0216 -0.0364 +vn 0.8844 0.0411 0.4650 +vn 0.6658 0.0311 0.7455 +vn 0.7826 -0.0322 0.6217 +vn 0.4339 -0.0310 0.9004 +vn 0.2749 0.0323 0.9609 +vn 0.0912 -0.0411 0.9950 +vn -0.3616 -0.0134 0.9322 +vn -0.3345 -0.0305 0.9419 +vn -0.4035 0.0134 0.9149 +vn -0.4295 0.0305 0.9025 +vn -0.7618 0.0398 0.6466 +vn -0.9249 0.0221 0.3794 +vn -0.8550 -0.0174 0.5184 +vn -0.9804 -0.0251 0.1954 +vn 0.4564 -0.7363 -0.4996 +vn 0.5715 -0.4462 -0.6887 +vn 0.6765 -0.4441 -0.5875 +vn -0.2068 -0.1699 0.9635 +vn -0.1095 -0.4602 0.8810 +vn -0.1035 -0.1620 0.9813 +vn 0.0909 -0.8035 0.5883 +vn 0.0044 -0.7611 0.6486 +vn 0.0123 -0.9070 0.4210 +vn 0.5974 -0.7322 0.3271 +vn 0.5298 -0.7456 0.4043 +vn 0.3744 -0.8975 0.2330 +vn -0.2366 -0.9146 0.3281 +vn -0.2852 -0.7494 0.5976 +vn -0.3857 -0.7441 0.5455 +vn 0.8249 0.4226 0.3755 +vn 0.6151 -0.7453 0.2574 +vn 0.4199 0.5300 0.7367 +vn 0.0030 -0.1933 0.9811 +vn 0.3012 0.6088 0.7340 +vn -0.0212 -0.9331 -0.3589 +vn -0.0337 -0.9415 -0.3354 +vn -0.0779 -0.9337 -0.3495 +vn 0.9169 -0.1625 -0.3645 +vn 0.9507 -0.1625 -0.2642 +vn 0.8465 -0.4328 -0.3101 +vn -0.4812 -0.8017 -0.3545 +vn -0.7453 0.3490 -0.5681 +vn -0.6904 0.3383 -0.6394 +vn 0.1031 -0.9850 -0.1381 +vn 0.0320 -0.9903 -0.1354 +vn 0.0395 -0.9658 -0.2562 +vn 0.0258 -0.9342 0.3559 +vn 0.0231 -0.9468 0.3210 +vn 0.1004 -0.9542 0.2817 +vn -0.5796 -0.7901 -0.1993 +vn -0.5380 -0.8050 -0.2500 +vn -0.3826 -0.9087 -0.1670 +vn 0.2449 -0.9111 0.3314 +vn 0.2616 -0.7336 0.6272 +vn 0.1921 -0.9181 0.3467 +vn 0.1137 -0.9470 -0.3005 +vn 0.1514 -0.9487 -0.2776 +vn 0.0994 -0.9619 -0.2547 +vn -0.0503 -0.9778 -0.2034 +vn -0.2129 -0.9116 -0.3516 +vn -0.1321 -0.9158 -0.3792 +vn -0.1554 -0.9565 -0.2469 +vn 0.6729 -0.7323 -0.1044 +vn 0.6539 -0.7401 -0.1573 +vn 0.8815 -0.4360 -0.1814 +vn 0.3883 -0.7411 -0.5477 +vn 0.4712 -0.4488 -0.7593 +vn 0.3933 -0.9023 0.1766 +vn 0.2619 -0.9462 0.1900 +vn 0.3189 -0.9384 0.1329 +vn -0.8875 0.1370 -0.4400 +vn -0.9193 -0.1612 0.3590 +vn -0.9235 -0.0742 0.3764 +vn 0.0945 -0.4640 0.8808 +vn 0.1877 -0.4758 0.8593 +vn 0.1967 -0.7563 0.6239 +vn 0.1055 -0.9452 0.3091 +vn 0.1367 -0.9552 0.2624 +vn 0.1300 -0.9031 0.4092 +vn 0.6576 0.1079 0.7456 +vn 0.0466 0.8224 0.5670 +vn 0.2846 -0.7488 -0.5985 +vn 0.2310 -0.9055 -0.3559 +vn 0.1714 -0.8824 -0.4382 +vn 0.4487 0.4427 0.7763 +vn 0.3454 0.4521 0.8224 +vn 0.3209 -0.7313 0.6019 +vn -0.0195 -0.9122 -0.4092 +vn -0.0979 -0.9428 -0.3187 +vn 0.1643 -0.9821 -0.0917 +vn -0.0816 -0.9445 0.3183 +vn -0.3524 -0.9034 -0.2443 +vn 0.3175 -0.9006 0.2969 +vn 0.2229 -0.4797 -0.8486 +vn 0.3433 -0.4512 -0.8238 +vn 0.0274 -0.9799 0.1975 +vn -0.0381 -0.9789 0.2005 +vn -0.0494 -0.9972 0.0560 +vn 0.0329 -0.9965 0.0771 +vn 0.9690 -0.1629 -0.1856 +vn 0.6431 0.7560 -0.1220 +vn 0.7307 0.1788 0.6589 +vn 0.3168 -0.1692 -0.9333 +vn -0.4712 -0.4488 0.7593 +vn 0.6192 -0.7643 0.1801 +vn 0.8788 0.4168 0.2324 +vn 0.2171 -0.9576 -0.1897 +vn 0.2001 -0.9433 -0.2650 +vn 0.2976 -0.9332 -0.2016 +vn 0.9057 -0.4213 -0.0476 +vn 0.9806 -0.1607 -0.1120 +vn 0.7869 0.3256 0.5241 +vn -0.6424 -0.0723 0.7629 +vn -0.6795 -0.1816 0.7108 +vn -0.5941 -0.1718 0.7858 +vn 0.1896 -0.9436 0.2714 +vn 0.2261 -0.9525 0.2040 +vn 0.6240 -0.7378 -0.2575 +vn 0.5909 -0.7336 -0.3356 +vn 0.8223 -0.4378 -0.3635 +vn -0.2824 -0.9416 -0.1832 +vn -0.3009 -0.9037 -0.3046 +vn -0.2587 -0.9403 -0.2211 +vn -0.1191 0.9676 -0.2228 +vn -0.0359 -0.1739 -0.9841 +vn -0.8750 0.1571 -0.4579 +vn -0.1490 -0.9489 -0.2781 +vn -0.9904 0.0867 -0.1076 +vn -0.8451 0.1823 -0.5026 +vn 0.7497 -0.1716 -0.6392 +vn 0.7932 -0.1580 -0.5881 +vn 0.5442 0.4284 0.7213 +vn 0.3776 -0.7371 0.5604 +vn -0.2109 -0.9561 -0.2032 +vn -0.8534 -0.4499 0.2634 +vn -0.8481 -0.4309 0.3085 +vn 0.3040 -0.9491 -0.0820 +vn 0.3615 -0.9270 -0.1001 +vn 0.4456 -0.8934 -0.0574 +vn -0.9229 0.3752 -0.0860 +vn -0.9158 0.3542 -0.1896 +vn -0.5840 -0.8006 -0.1344 +vn 0.6914 -0.7212 -0.0423 +vn 0.8947 -0.4327 -0.1104 +vn -0.3433 -0.4512 0.8238 +vn -0.3168 -0.1692 0.9333 +vn -0.4247 -0.1724 0.8887 +vn 0.0415 0.6357 0.7708 +vn 0.0839 -0.1404 0.9865 +vn 0.1626 -0.9638 0.2113 +vn 0.1599 -0.9428 0.2925 +vn -0.3001 -0.9283 -0.2195 +vn -0.3375 -0.9335 -0.1211 +vn 0.0131 0.8043 -0.5941 +vn 0.0252 -0.2006 -0.9794 +vn -0.1717 -0.8792 0.4444 +vn 0.7749 0.2332 0.5875 +vn -0.1528 -0.9748 0.1627 +vn -0.2278 -0.9543 0.1933 +vn -0.2284 -0.9729 0.0355 +vn 0.0988 -0.9936 -0.0550 +vn 0.1641 -0.9848 0.0560 +vn 0.0988 -0.9935 0.0560 +vn 0.5828 0.7482 -0.3171 +vn 0.6153 0.7562 -0.2228 +vn 0.9319 -0.0652 -0.3568 +vn -0.4460 -0.8940 0.0436 +vn -0.4253 -0.8968 0.1218 +vn -0.6436 -0.7472 0.1661 +vn 0.5009 -0.1570 -0.8512 +vn 0.5941 -0.1718 -0.7858 +vn -0.1509 -0.9666 -0.2072 +vn -0.0512 -0.9962 -0.0698 +vn 0.8809 0.4060 0.2433 +vn 0.8870 0.4174 0.1976 +vn 0.7098 -0.6993 0.0844 +vn 0.1113 -0.4611 -0.8803 +vn 0.1018 -0.7589 -0.6432 +vn -0.0174 -0.7623 -0.6470 +vn -0.1682 -0.9398 -0.2975 +vn -0.4931 0.3644 -0.7899 +vn -0.3815 -0.7957 -0.4704 +vn -0.5883 0.3612 -0.7235 +vn 0.1285 -0.1671 0.9775 +vn 0.0986 -0.2051 0.9738 +vn 0.5187 -0.7416 -0.4255 +vn 0.3684 -0.9039 -0.2175 +vn -0.5715 -0.4462 0.6887 +vn -0.4564 -0.7363 0.4996 +vn 0.7422 -0.4436 -0.5022 +vn -0.2705 -0.9095 -0.3156 +vn -0.5439 0.5863 -0.6004 +vn -0.6847 0.4851 -0.5439 +vn 0.8704 -0.4896 0.0513 +vn 0.7017 -0.7121 0.0236 +vn -0.2034 -0.9291 0.3089 +vn -0.1580 -0.9397 0.3032 +vn 0.4983 0.7485 -0.4376 +vn 0.8225 -0.0723 -0.5641 +vn -0.0898 -0.9087 0.4077 +vn 0.4374 -0.8950 -0.0877 +vn -0.1224 -0.9404 -0.3174 +vn 0.4854 -0.8714 0.0704 +vn -0.1520 -0.7685 -0.6215 +vn -0.1760 -0.4742 -0.8627 +vn -0.0937 -0.5125 -0.8536 +vn 0.3149 -0.9027 -0.2933 +vn 0.2752 -0.9041 -0.3270 +vn 0.4580 -0.8889 -0.0001 +vn -0.4150 -0.9032 -0.1094 +vn -0.4502 -0.8924 -0.0298 +vn -0.0217 -0.4655 -0.8848 +vn -0.8219 0.3066 -0.4800 +vn -0.3398 -0.7918 -0.5075 +vn -0.2709 -0.7924 -0.5465 +vn -0.8223 -0.4378 0.3635 +vn -0.8716 -0.1589 0.4638 +vn -0.1805 -0.9405 0.2879 +vn -0.3797 -0.9000 0.2143 +vn -0.3012 -0.9497 0.0854 +vn 0.8716 -0.1589 -0.4638 +vn 0.3794 -0.9232 0.0610 +vn -0.2968 -0.9549 -0.0052 +vn 0.4010 -0.9044 -0.1461 +vn -0.7919 -0.4372 0.4264 +vn -0.7422 -0.4436 0.5022 +vn -0.8157 -0.1376 0.5618 +vn -0.4232 -0.7951 -0.4344 +vn -0.1583 -0.9845 -0.0759 +vn -0.1479 -0.9874 0.0560 +vn -0.6319 -0.7734 0.0499 +vn -0.6330 -0.7731 -0.0403 +vn -0.2690 0.7616 0.5896 +vn -0.4082 0.3747 -0.8324 +vn -0.3035 0.3977 -0.8658 +vn -0.6550 0.7523 -0.0704 +vn -0.7289 0.6278 -0.2731 +vn 0.7564 0.1173 0.6435 +vn 0.1784 0.6492 0.7394 +vn -0.1567 -0.9474 0.2790 +vn 0.0559 0.7148 0.6971 +vn -0.2229 -0.4797 0.8486 +vn 0.2068 -0.1699 -0.9635 +vn 0.8569 -0.4504 -0.2505 +vn 0.4247 -0.1724 -0.8887 +vn 0.0749 0.6552 0.7517 +vn -0.8616 0.3558 -0.3621 +vn 0.2700 0.7612 -0.5897 +vn 0.6424 -0.0723 -0.7629 +vn -0.3101 -0.9068 -0.2856 +vn -0.5417 0.4945 -0.6797 +vn 0.6073 0.2307 0.7602 +vn 0.8282 -0.5593 0.0345 +vn 0.2461 -0.5034 0.8283 +vn 0.0458 -0.9369 -0.3465 +vn -0.6189 -0.7446 0.2502 +vn 0.2225 -0.9409 -0.2553 +vn 0.2602 -0.9416 -0.2135 +vn -0.1268 0.7859 0.6052 +vn 0.1056 -0.1602 -0.9814 +vn -0.0921 -0.9760 0.1975 +vn -0.6765 -0.4441 0.5875 +vn -0.7931 -0.1580 0.5882 +vn 0.2286 -0.9709 -0.0712 +vn -0.6515 0.7490 -0.1206 +vn -0.9208 0.3808 -0.0851 +vn -0.7889 0.5983 -0.1400 +vn 0.6795 -0.1816 -0.7108 +vn -0.2769 -0.9569 -0.0878 +vn 0.0047 -0.4594 0.8882 +vn -0.8922 0.2045 -0.4027 +vn -0.2663 0.9409 -0.2092 +vn 0.1339 0.5730 0.8085 +vn -0.1018 -0.7589 0.6432 +vn 0.6399 0.4207 0.6431 +vn 0.4572 -0.7382 0.4960 +vn -0.9002 0.2168 -0.3777 +vn -0.9011 0.2590 -0.3479 +vn -0.3381 -0.9027 0.2662 +vn -0.3860 0.7878 0.4800 +vn 0.7675 0.4172 0.4868 +vn 0.6948 0.4177 0.5856 +vn 0.6618 0.6186 0.4236 +vn 0.6456 0.7635 -0.0188 +vn 0.6363 0.7436 0.2051 +vn 0.2161 0.9441 0.2489 +vn 0.7039 0.1734 0.6888 +vn -0.3014 0.8456 -0.4406 +vn -0.0553 0.6371 -0.7688 +vn 0.2460 -0.9499 -0.1928 +vn 0.2096 -0.9472 -0.2426 +vn -0.1331 -0.9461 0.2951 +vn -0.5909 -0.7336 0.3356 +vn -0.8076 0.3142 -0.4991 +vn 0.2288 -0.9719 0.0560 +vn -0.1296 -0.9531 0.2736 +vn 0.0853 -0.9182 -0.3868 +vn -0.5996 0.7628 0.2422 +vn -0.6072 0.7832 0.1339 +vn 0.8158 -0.1377 -0.5617 +vn -0.5247 -0.7340 0.4312 +vn 0.8912 0.3971 0.2193 +vn 0.7227 0.5967 0.3488 +vn 0.6241 0.7548 0.2019 +vn 0.3719 0.7452 -0.5535 +vn 0.2688 -0.9400 -0.2099 +vn -0.2962 -0.9120 0.2836 +vn -0.5009 -0.1570 0.8512 +vn -0.4990 0.7472 0.4389 +vn -0.3718 0.7447 0.5543 +vn -0.9179 0.3966 -0.0122 +vn -0.8225 -0.0723 0.5641 +vn -0.5844 0.7464 0.3184 +vn -0.8641 0.2147 -0.4552 +vn 0.1392 0.5670 0.8119 +vn 0.1219 -0.9571 0.2629 +vn 0.2426 0.4049 0.8816 +vn 0.0666 0.6589 0.7493 +vn 0.7919 -0.4372 -0.4264 +vn 0.5204 0.3991 0.7549 +vn -0.7497 -0.1716 0.6392 +vn -0.2593 0.4178 -0.8708 +vn -0.2380 -0.7596 -0.6052 +vn 0.0330 -0.9979 -0.0550 +vn -0.9436 0.3301 0.0264 +vn 0.1739 0.8483 0.5001 +vn -0.1314 0.6235 0.7707 +vn -0.8922 0.1972 -0.4063 +vn 0.1949 -0.9541 -0.2274 +vn 0.1284 0.7840 -0.6074 +vn 0.3015 -0.9507 0.0724 +vn 0.0937 -0.9814 0.1674 +vn -0.6543 -0.3948 0.6450 +vn -0.3583 -0.9335 -0.0131 +vn 0.8082 0.3564 0.4688 +vn -0.4350 0.5965 -0.6745 +vn 0.2288 0.5333 0.8144 +vn -0.9239 0.3812 0.0317 +vn -0.1835 0.5537 -0.8123 +vn -0.2882 0.5892 -0.7548 +vn 0.8283 0.4326 0.3560 +vn 0.4287 0.8593 0.2790 +vn 0.8296 0.4244 0.3629 +vn -0.9377 0.3260 -0.1200 +vn -0.9407 0.2553 -0.2234 +vn -0.6140 0.7108 -0.3431 +vn -0.3398 0.6773 -0.6526 +vn 0.8348 -0.3574 -0.4187 +vn -0.0942 -0.0575 -0.9939 +vn 0.6456 0.6484 0.4036 +vn -0.7932 0.4312 -0.4300 +vn -0.1218 0.4788 -0.8695 +vn -0.1428 0.6675 -0.7308 +vn 0.9987 -0.0214 -0.0454 +vn 0.6723 0.7003 0.2399 +vn -0.4564 0.7363 0.4996 +vn -0.6765 0.4441 0.5875 +vn -0.5715 0.4462 0.6887 +vn 0.2068 0.1699 -0.9635 +vn 0.1035 0.1620 -0.9813 +vn 0.1095 0.4602 -0.8810 +vn -0.0909 0.8035 -0.5883 +vn -0.0123 0.9070 -0.4210 +vn -0.0044 0.7611 -0.6486 +vn -0.5974 0.7322 -0.3271 +vn -0.3744 0.8975 -0.2330 +vn -0.5298 0.7456 -0.4043 +vn 0.2366 0.9146 -0.3281 +vn 0.3857 0.7441 -0.5455 +vn 0.2852 0.7494 -0.5976 +vn -0.3866 0.9062 -0.1713 +vn -0.6151 0.7453 -0.2574 +vn 0.3607 0.5881 -0.7239 +vn 0.2449 0.6472 -0.7219 +vn -0.0030 0.1933 -0.9811 +vn 0.0212 0.9331 0.3589 +vn 0.0779 0.9337 0.3495 +vn 0.0337 0.9415 0.3354 +vn -0.9169 0.1625 0.3645 +vn -0.8465 0.4328 0.3101 +vn -0.9507 0.1625 0.2642 +vn 0.4812 0.8017 0.3545 +vn 0.2450 0.9409 0.2337 +vn 0.2765 0.9371 0.2130 +vn -0.1031 0.9850 0.1381 +vn -0.0395 0.9658 0.2562 +vn -0.0320 0.9903 0.1354 +vn -0.0258 0.9342 -0.3559 +vn -0.1004 0.9542 -0.2817 +vn -0.0231 0.9468 -0.3210 +vn 0.5796 0.7901 0.1993 +vn 0.3826 0.9087 0.1670 +vn 0.5380 0.8050 0.2500 +vn -0.2449 0.9111 -0.3314 +vn -0.1921 0.9181 -0.3467 +vn -0.2616 0.7336 -0.6272 +vn -0.1137 0.9470 0.3005 +vn -0.0994 0.9619 0.2547 +vn -0.1514 0.9487 0.2776 +vn 0.0503 0.9778 0.2034 +vn 0.2129 0.9116 0.3516 +vn 0.1554 0.9565 0.2469 +vn 0.1321 0.9158 0.3792 +vn -0.6729 0.7323 0.1044 +vn -0.8815 0.4360 0.1814 +vn -0.6539 0.7401 0.1573 +vn -0.3883 0.7411 0.5477 +vn -0.4712 0.4488 0.7593 +vn -0.3933 0.9023 -0.1766 +vn -0.3189 0.9384 -0.1329 +vn -0.2619 0.9462 -0.1900 +vn 0.5343 0.3404 -0.7738 +vn 0.9235 0.0742 -0.3764 +vn 0.9193 0.1612 -0.3590 +vn -0.0945 0.4640 -0.8808 +vn -0.1877 0.4758 -0.8593 +vn -0.1967 0.7563 -0.6239 +vn -0.1055 0.9452 -0.3091 +vn -0.1300 0.9031 -0.4092 +vn -0.1367 0.9552 -0.2624 +vn 0.6784 0.2329 -0.6968 +vn 0.1007 0.5930 -0.7988 +vn -0.2846 0.7488 0.5985 +vn -0.1714 0.8824 0.4382 +vn -0.2310 0.9055 0.3559 +vn -0.2118 0.8962 -0.3899 +vn -0.3209 0.7313 -0.6019 +vn -0.1607 0.8905 -0.4256 +vn 0.0979 0.9428 0.3187 +vn 0.0195 0.9122 0.4092 +vn -0.1643 0.9821 0.0917 +vn 0.0816 0.9445 -0.3183 +vn 0.3524 0.9034 0.2443 +vn -0.3175 0.9006 -0.2969 +vn -0.2229 0.4797 0.8486 +vn -0.3433 0.4512 0.8238 +vn -0.0274 0.9799 -0.1975 +vn 0.0381 0.9789 -0.2005 +vn -0.0329 0.9965 -0.0771 +vn 0.0494 0.9972 -0.0560 +vn -0.9690 0.1629 0.1856 +vn -0.6348 0.2319 0.7370 +vn -0.7474 0.6479 0.1470 +vn -0.3168 0.1692 0.9333 +vn 0.4712 0.4488 -0.7593 +vn -0.4028 0.9097 -0.1015 +vn -0.6192 0.7643 -0.1801 +vn -0.2171 0.9576 0.1897 +vn -0.2976 0.9332 0.2016 +vn -0.2001 0.9433 0.2650 +vn -0.9057 0.4213 0.0476 +vn -0.6539 0.5547 0.5145 +vn -0.9806 0.1607 0.1120 +vn 0.6424 0.0723 -0.7629 +vn 0.5941 0.1718 -0.7858 +vn 0.6795 0.1816 -0.7108 +vn -0.1896 0.9436 -0.2714 +vn -0.2261 0.9525 -0.2040 +vn -0.6240 0.7378 0.2575 +vn -0.8223 0.4378 0.3635 +vn -0.5909 0.7336 0.3356 +vn 0.2824 0.9416 0.1832 +vn 0.2587 0.9403 0.2211 +vn 0.3009 0.9037 0.3045 +vn 0.2093 -0.9605 0.1835 +vn -0.3926 0.1828 0.9014 +vn 0.0359 0.1739 0.9841 +vn 0.1490 0.9489 0.2780 +vn 0.6818 0.2206 -0.6975 +vn 0.5040 0.2375 -0.8304 +vn -0.7931 0.1580 0.5882 +vn -0.7497 0.1716 0.6392 +vn -0.2515 0.9031 -0.3480 +vn -0.3776 0.7371 -0.5604 +vn 0.2109 0.9561 0.2032 +vn 0.8534 0.4499 -0.2634 +vn 0.8481 0.4309 -0.3085 +vn -0.3040 0.9491 0.0820 +vn -0.4456 0.8934 0.0574 +vn -0.3614 0.9270 0.1000 +vn 0.3719 0.9277 0.0326 +vn 0.5840 0.8006 0.1344 +vn 0.3457 0.9360 0.0667 +vn -0.8947 0.4327 0.1104 +vn -0.6914 0.7212 0.0423 +vn 0.3433 0.4512 -0.8238 +vn 0.4247 0.1724 -0.8887 +vn 0.3168 0.1692 -0.9333 +vn -0.0325 0.7712 -0.6358 +vn -0.0839 0.1404 -0.9865 +vn -0.1599 0.9428 -0.2925 +vn -0.1626 0.9638 -0.2113 +vn 0.3001 0.9283 0.2194 +vn 0.3375 0.9335 0.1211 +vn -0.0253 0.5797 0.8144 +vn -0.0252 0.2006 0.9794 +vn 0.1717 0.8792 -0.4444 +vn -0.7037 0.3696 0.6068 +vn 0.1528 0.9748 -0.1627 +vn 0.2284 0.9729 -0.0355 +vn 0.2278 0.9543 -0.1933 +vn -0.0988 0.9936 0.0550 +vn -0.0988 0.9935 -0.0560 +vn -0.1641 0.9848 -0.0560 +vn -0.6635 0.6533 0.3647 +vn -0.9319 0.0652 0.3568 +vn -0.7181 0.6463 0.2582 +vn 0.4460 0.8940 -0.0436 +vn 0.6436 0.7472 -0.1661 +vn 0.4253 0.8968 -0.1218 +vn -0.5941 0.1718 0.7859 +vn -0.5009 0.1570 0.8512 +vn 0.1509 0.9666 0.2072 +vn 0.0512 0.9962 0.0698 +vn -0.5031 0.8587 0.0981 +vn -0.7098 0.6993 -0.0844 +vn -0.4492 0.8926 -0.0378 +vn -0.1113 0.4611 0.8803 +vn 0.0174 0.7623 0.6470 +vn -0.1018 0.7589 0.6432 +vn 0.1682 0.9398 0.2975 +vn 0.1831 0.9312 0.3151 +vn 0.2212 0.9324 0.2856 +vn 0.3815 0.7957 0.4704 +vn -0.1285 0.1672 -0.9775 +vn -0.0986 0.2051 -0.9738 +vn -0.5187 0.7416 0.4255 +vn -0.3684 0.9039 0.2175 +vn 0.4564 0.7363 -0.4996 +vn 0.5715 0.4462 -0.6887 +vn -0.7422 0.4436 0.5022 +vn 0.2705 0.9095 0.3156 +vn -0.3018 0.3932 0.8685 +vn -0.2465 0.5002 0.8301 +vn -0.7017 0.7121 -0.0236 +vn -0.8704 0.4896 -0.0513 +vn 0.2034 0.9291 -0.3089 +vn 0.1580 0.9397 -0.3032 +vn -0.5733 0.6495 0.4995 +vn -0.8225 0.0723 0.5641 +vn 0.0898 0.9087 -0.4077 +vn -0.4374 0.8950 0.0877 +vn 0.1224 0.9404 0.3174 +vn -0.4854 0.8714 -0.0704 +vn 0.1520 0.7685 0.6215 +vn 0.0937 0.5125 0.8536 +vn 0.1760 0.4742 0.8627 +vn -0.2752 0.9041 0.3270 +vn -0.3149 0.9027 0.2933 +vn -0.4580 0.8889 0.0001 +vn 0.4150 0.9032 0.1094 +vn 0.4502 0.8924 0.0298 +vn 0.0217 0.4655 0.8848 +vn 0.2662 0.9517 0.1532 +vn 0.3398 0.7918 0.5075 +vn 0.2709 0.7924 0.5465 +vn 0.8716 0.1589 -0.4638 +vn 0.8223 0.4378 -0.3635 +vn 0.1805 0.9405 -0.2879 +vn 0.3797 0.9000 -0.2143 +vn 0.3012 0.9497 -0.0854 +vn -0.8716 0.1589 0.4638 +vn -0.3794 0.9232 -0.0610 +vn 0.2968 0.9549 0.0052 +vn -0.4010 0.9044 0.1461 +vn 0.7919 0.4372 -0.4264 +vn 0.8157 0.1377 -0.5618 +vn 0.7422 0.4436 -0.5022 +vn 0.4232 0.7951 0.4344 +vn 0.1583 0.9845 0.0759 +vn 0.1479 0.9874 -0.0560 +vn 0.6319 0.7734 -0.0499 +vn 0.6330 0.7731 0.0403 +vn 0.3188 0.6265 -0.7113 +vn 0.1522 0.9271 0.3425 +vn 0.1150 0.9168 0.3823 +vn 0.6371 0.6387 -0.4315 +vn 0.5855 0.5484 -0.5971 +vn -0.6833 0.2293 0.6932 +vn 0.1310 0.6872 -0.7146 +vn 0.1567 0.9474 -0.2790 +vn -0.0570 0.6994 -0.7125 +vn 0.2229 0.4797 -0.8486 +vn -0.2068 0.1699 0.9635 +vn -0.8569 0.4504 0.2505 +vn -0.4247 0.1724 0.8887 +vn 0.0244 0.7221 -0.6914 +vn 0.3289 0.9349 0.1332 +vn -0.6424 0.0723 0.7629 +vn -0.3189 0.6284 0.7095 +vn 0.3101 0.9068 0.2856 +vn 0.5417 -0.4945 0.6797 +vn 0.5923 0.3682 -0.7167 +vn -0.8283 0.5593 -0.0345 +vn -0.2461 0.5034 -0.8283 +vn -0.0458 0.9369 0.3465 +vn 0.6189 0.7446 -0.2502 +vn -0.2225 0.9409 0.2553 +vn -0.2602 0.9416 0.2136 +vn 0.1647 0.5879 -0.7920 +vn -0.1056 0.1602 0.9814 +vn 0.0921 0.9760 -0.1975 +vn 0.7931 0.1580 -0.5882 +vn 0.6765 0.4441 -0.5875 +vn -0.2286 0.9709 0.0712 +vn 0.6514 -0.7490 0.1206 +vn -0.1507 0.2210 0.9636 +vn 0.9085 -0.4097 0.0827 +vn -0.6795 0.1816 0.7108 +vn 0.2769 0.9569 0.0878 +vn -0.0047 0.4594 -0.8882 +vn -0.4144 0.1796 0.8922 +vn 0.2663 -0.9409 0.2092 +vn -0.0849 0.8224 -0.5626 +vn 0.1018 0.7589 -0.6432 +vn -0.2929 0.9070 -0.3027 +vn -0.4572 0.7382 -0.4960 +vn 0.4793 0.7162 -0.5072 +vn 0.4025 0.7967 -0.4507 +vn 0.3381 0.9027 -0.2662 +vn 0.7075 -0.0385 0.7057 +vn -0.3533 0.9085 -0.2231 +vn -0.3182 0.9084 -0.2713 +vn -0.6868 0.5551 0.4692 +vn -0.7036 0.6505 0.2859 +vn -0.7232 0.6749 0.1467 +vn -0.2287 -0.9407 -0.2507 +vn 0.7027 0.2185 -0.6771 +vn 0.3016 -0.8452 0.4412 +vn 0.2131 -0.7672 -0.6050 +vn -0.2460 0.9499 0.1928 +vn -0.2096 0.9472 0.2426 +vn 0.1331 0.9461 -0.2951 +vn 0.5909 0.7336 -0.3356 +vn -0.3469 0.2760 0.8964 +vn -0.2288 0.9719 -0.0560 +vn 0.1296 0.9531 -0.2736 +vn -0.0853 0.9182 0.3868 +vn 0.6986 0.6527 -0.2932 +vn 0.7112 0.6423 -0.2858 +vn -0.8157 0.1377 0.5618 +vn 0.5247 0.7340 -0.4312 +vn -0.8894 -0.4022 -0.2170 +vn -0.6240 -0.7549 -0.2019 +vn 0.4144 0.2544 -0.8738 +vn -0.4361 0.6509 0.6214 +vn -0.2688 0.9400 0.2099 +vn 0.2962 0.9120 -0.2836 +vn 0.5009 0.1570 -0.8512 +vn 0.5722 0.6508 -0.4991 +vn 0.4356 0.6509 -0.6217 +vn 0.3966 0.9180 0.0043 +vn 0.8225 0.0723 -0.5641 +vn 0.6617 0.6554 -0.3641 +vn 0.5014 0.4455 -0.7417 +vn -0.0799 0.8239 -0.5610 +vn -0.1219 0.9571 -0.2629 +vn -0.2422 -0.4066 -0.8809 +vn -0.0585 0.7521 -0.6565 +vn -0.7919 0.4372 0.4264 +vn 0.4869 0.5040 -0.7133 +vn 0.7497 0.1716 -0.6392 +vn 0.1014 0.9093 0.4036 +vn 0.2380 0.7596 0.6052 +vn -0.0330 0.9979 0.0550 +vn 0.3766 0.9212 -0.0976 +vn -0.1740 -0.8484 -0.4999 +vn 0.6005 -0.6465 0.4705 +vn 0.5060 0.5440 -0.6693 +vn -0.1949 0.9541 0.2274 +vn -0.1648 0.5931 0.7881 +vn -0.3015 0.9507 -0.0724 +vn -0.0937 0.9814 -0.1674 +vn -0.9522 0.0507 -0.3013 +vn 0.3583 0.9335 0.0131 +vn -0.6161 0.6928 0.3747 +vn -0.1874 0.6238 0.7588 +vn -0.1256 0.8458 -0.5185 +vn 0.3806 0.9246 -0.0147 +vn -0.0970 0.7004 0.7071 +vn 0.0242 0.7864 0.6173 +vn -0.5072 0.8483 0.1521 +vn 0.1760 0.3651 -0.9142 +vn -0.5872 0.7748 0.2342 +vn 0.4100 0.8845 -0.2228 +vn 0.4029 0.8288 -0.3883 +vn 0.4626 0.8150 -0.3489 +vn -0.3166 0.8445 0.4319 +vn 0.8175 0.0714 0.5715 +vn 0.0430 0.8882 -0.4575 +vn 0.5352 0.4152 -0.7357 +vn 0.0761 0.6462 -0.7593 +vn -0.0524 0.4762 -0.8778 +vn -0.5878 -0.2584 0.7666 +vn -0.3850 0.8172 0.4290 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 5/5/5 6/6/5 7/7/5 +f 8/8/5 9/9/5 10/10/5 +f 11/11/6 12/12/7 13/13/8 +f 13/13/8 12/12/7 14/14/9 +f 15/15/10 16/16/11 17/17/12 +f 17/17/12 16/16/11 18/18/13 +f 19/19/5 20/20/5 21/21/5 +f 12/12/5 11/11/5 22/22/5 +f 23/23/5 24/24/5 25/25/5 +f 11/11/5 26/26/5 22/22/5 +f 27/27/5 28/28/5 29/29/5 +f 1/1/14 3/3/5 30/30/5 +f 25/25/5 24/24/5 31/31/5 +f 32/32/5 28/28/5 33/33/5 +f 34/34/5 35/35/5 36/36/5 +f 30/30/5 37/37/5 38/38/5 +f 16/16/5 31/31/5 24/24/5 +f 18/18/5 36/36/5 39/39/5 +f 21/21/5 34/34/5 36/36/5 +f 1/1/14 40/40/15 41/41/16 +f 36/36/5 35/35/5 26/26/5 +f 33/33/5 16/16/5 24/24/5 +f 42/42/5 43/43/5 44/44/5 +f 42/42/5 44/44/5 45/45/5 +f 44/44/5 46/46/5 45/45/5 +f 45/45/5 46/46/5 14/14/5 +f 18/18/5 16/16/5 36/36/5 +f 47/47/5 17/17/5 46/46/5 +f 14/14/5 17/17/5 13/13/5 +f 46/46/5 17/17/5 14/14/5 +f 15/15/5 17/17/5 47/47/5 +f 6/6/5 9/9/5 7/7/5 +f 4/4/5 2/2/5 48/48/5 +f 49/49/5 50/50/5 51/51/5 +f 4/4/5 48/48/5 51/51/5 +f 51/51/5 10/10/5 4/4/5 +f 4/4/5 10/10/5 52/52/5 +f 51/51/5 50/50/5 10/10/5 +f 8/8/5 10/10/5 50/50/5 +f 53/53/17 54/54/17 55/55/17 +f 55/55/18 54/54/18 56/56/18 +f 55/55/19 56/56/19 57/57/19 +f 57/57/20 56/56/21 58/58/22 +f 57/57/23 58/58/23 59/59/23 +f 59/59/24 58/58/24 60/60/24 +f 60/60/25 61/61/25 62/62/25 +f 62/62/26 61/61/27 63/63/28 +f 62/62/26 63/63/28 64/64/29 +f 64/64/29 63/63/28 65/65/30 +f 64/64/29 65/65/30 66/66/31 +f 66/66/31 65/65/30 67/67/32 +f 67/67/33 65/65/33 68/68/33 +f 67/67/34 68/68/34 69/69/34 +f 69/69/35 68/68/35 70/70/35 +f 69/69/36 70/70/36 71/71/36 +f 71/71/37 70/70/37 72/72/37 +f 71/71/38 72/72/38 73/73/38 +f 73/73/39 72/72/39 74/74/39 +f 74/74/40 75/75/40 76/76/40 +f 77/77/41 78/78/41 79/79/41 +f 79/79/42 78/78/42 80/80/42 +f 79/79/43 80/80/43 81/81/43 +f 81/81/44 80/80/44 82/82/44 +f 81/81/45 82/82/45 83/83/45 +f 83/83/46 82/82/46 84/84/46 +f 83/83/47 84/84/47 85/85/47 +f 85/85/48 84/84/48 86/86/48 +f 85/85/49 86/86/49 87/87/49 +f 87/87/50 86/86/50 88/88/50 +f 87/87/51 88/88/52 89/89/53 +f 87/87/51 89/89/53 90/90/54 +f 90/90/55 89/89/55 91/91/55 +f 90/90/56 91/91/56 92/92/56 +f 92/92/57 93/93/57 94/94/57 +f 94/94/58 93/93/59 95/95/60 +f 94/94/58 95/95/60 96/96/61 +f 96/96/62 95/95/63 97/97/64 +f 97/97/64 95/95/63 98/98/65 +f 99/99/66 100/100/66 101/101/66 +f 101/101/18 100/100/18 102/102/18 +f 101/101/67 102/102/67 103/103/67 +f 103/103/20 102/102/20 104/104/20 +f 103/103/23 104/104/23 105/105/23 +f 105/105/68 104/104/68 106/106/68 +f 106/106/69 107/107/69 108/108/69 +f 108/108/70 107/107/70 109/109/70 +f 108/108/71 109/109/71 110/110/71 +f 110/110/72 109/109/72 111/111/72 +f 111/111/73 112/112/74 113/113/75 +f 113/113/75 112/112/74 114/114/76 +f 114/114/77 115/115/78 116/116/79 +f 116/116/79 115/115/78 117/117/80 +f 117/117/81 115/115/81 118/118/81 +f 117/117/82 118/118/82 119/119/82 +f 119/119/62 118/118/63 120/120/64 +f 120/120/64 118/118/63 121/121/65 +f 122/122/83 123/123/83 124/124/83 +f 125/125/84 124/124/84 126/126/84 +f 125/125/85 126/126/86 127/127/87 +f 125/125/85 127/127/87 128/128/88 +f 128/128/88 127/127/87 129/129/89 +f 128/128/90 129/129/90 130/130/90 +f 130/130/91 129/129/91 131/131/91 +f 130/130/92 131/131/92 132/132/92 +f 132/132/93 131/131/93 133/133/93 +f 132/132/94 133/133/95 134/134/96 +f 132/132/94 134/134/96 135/135/97 +f 135/135/97 134/134/96 136/136/98 +f 135/135/97 136/136/98 137/137/99 +f 137/137/99 136/136/98 138/138/100 +f 138/138/101 136/136/101 139/139/101 +f 138/138/102 139/139/103 140/140/104 +f 140/140/104 139/139/103 141/141/105 +f 140/140/104 141/141/105 142/142/106 +f 142/142/106 141/141/105 143/143/107 +f 143/143/107 141/141/105 144/144/108 +f 143/143/109 144/144/110 145/145/111 +f 145/145/111 144/144/110 146/146/112 +f 147/147/66 148/148/66 149/149/66 +f 149/149/18 148/148/18 150/150/18 +f 149/149/67 150/150/67 151/151/67 +f 151/151/113 150/150/113 152/152/113 +f 151/151/114 152/152/114 153/153/114 +f 153/153/115 152/152/115 154/154/115 +f 153/153/116 154/154/116 155/155/116 +f 155/155/117 154/154/117 156/156/117 +f 155/155/118 156/156/118 157/157/118 +f 157/157/70 156/156/70 158/158/70 +f 157/157/119 158/158/120 159/159/121 +f 159/159/121 158/158/120 160/160/122 +f 160/160/123 161/161/124 162/162/125 +f 162/162/125 161/161/124 163/163/126 +f 163/163/127 164/164/127 165/165/127 +f 165/165/128 164/164/59 166/166/60 +f 165/165/128 166/166/60 167/167/61 +f 167/167/129 166/166/130 168/168/64 +f 168/168/64 166/166/130 169/169/65 +f 170/170/66 171/171/66 172/172/66 +f 172/172/18 171/171/18 173/173/18 +f 172/172/67 173/173/67 174/174/67 +f 174/174/20 173/173/20 175/175/20 +f 174/174/131 175/175/131 176/176/131 +f 176/176/132 175/175/132 177/177/132 +f 176/176/133 177/177/133 178/178/133 +f 178/178/134 177/177/134 179/179/134 +f 178/178/135 179/179/136 180/180/137 +f 180/180/137 179/179/136 181/181/138 +f 181/181/138 179/179/136 182/182/139 +f 181/181/138 182/182/139 183/183/140 +f 181/181/138 183/183/140 184/184/141 +f 184/184/141 183/183/140 185/185/142 +f 185/185/143 186/186/144 187/187/145 +f 187/187/145 186/186/144 188/188/146 +f 188/188/147 186/186/148 189/189/149 +f 189/189/149 186/186/148 190/190/150 +f 189/189/151 190/190/151 191/191/151 +f 191/191/152 190/190/152 192/192/152 +f 193/193/153 194/194/154 195/195/155 +f 195/195/155 194/194/154 196/196/156 +f 196/196/156 194/194/154 197/197/157 +f 196/196/156 197/197/157 198/198/158 +f 198/198/158 197/197/157 199/199/159 +f 198/198/158 199/199/159 200/200/160 +f 200/200/160 199/199/159 201/201/161 +f 200/200/160 201/201/161 202/202/162 +f 200/200/160 202/202/162 203/203/163 +f 203/203/164 202/202/164 204/204/164 +f 203/203/165 204/204/165 205/205/165 +f 205/205/166 204/204/166 206/206/166 +f 205/205/167 206/206/168 207/207/169 +f 207/207/169 206/206/168 208/208/170 +f 208/208/170 206/206/168 209/209/171 +f 208/208/172 209/209/173 210/210/174 +f 210/210/174 209/209/173 211/211/175 +f 210/210/174 211/211/175 212/212/176 +f 212/212/176 211/211/175 213/213/177 +f 212/212/176 213/213/177 214/214/178 +f 214/214/178 213/213/177 215/215/179 +f 214/214/178 215/215/179 216/216/180 +f 214/214/178 216/216/180 217/217/181 +f 217/217/182 216/216/182 50/50/182 +f 218/218/183 219/219/184 220/220/185 +f 220/220/185 219/219/184 193/193/153 +f 220/220/185 193/193/153 43/43/186 +f 43/43/186 193/193/153 44/44/187 +f 44/44/187 193/193/153 195/195/155 +f 50/50/188 216/216/188 221/221/188 +f 222/222/189 223/223/189 224/224/189 +f 224/224/190 225/225/190 226/226/190 +f 226/226/191 225/225/192 227/227/193 +f 226/226/191 227/227/193 228/228/194 +f 228/228/195 227/227/195 229/229/195 +f 228/228/196 229/229/196 230/230/196 +f 230/230/197 229/229/197 231/231/197 +f 230/230/198 231/231/198 232/232/198 +f 232/232/199 231/231/199 233/233/199 +f 232/232/200 233/233/200 234/234/200 +f 234/234/201 233/233/201 235/235/201 +f 234/234/202 235/235/202 236/236/202 +f 236/236/203 235/235/203 237/237/203 +f 236/236/204 237/237/204 238/238/204 +f 238/238/205 237/237/206 239/239/207 +f 238/238/205 239/239/207 240/240/208 +f 240/240/208 239/239/207 241/241/209 +f 240/240/208 241/241/209 242/242/210 +f 242/242/211 241/241/211 243/243/211 +f 244/244/212 243/243/212 245/245/212 +f 246/246/213 247/247/213 248/248/213 +f 248/248/214 249/249/214 250/250/214 +f 250/250/215 249/249/215 251/251/215 +f 250/250/216 251/251/217 252/252/218 +f 250/250/216 252/252/218 253/253/219 +f 253/253/220 252/252/221 254/254/222 +f 253/253/220 254/254/222 255/255/223 +f 255/255/224 254/254/225 256/256/226 +f 255/255/224 256/256/226 257/257/227 +f 257/257/228 256/256/229 258/258/230 +f 257/257/228 258/258/230 259/259/231 +f 259/259/231 258/258/230 260/260/232 +f 260/260/232 258/258/230 261/261/233 +f 260/260/232 261/261/233 262/262/234 +f 260/260/232 262/262/234 263/263/235 +f 263/263/236 262/262/237 264/264/238 +f 263/263/236 264/264/238 265/265/239 +f 265/265/240 264/264/240 266/266/240 +f 266/266/241 267/267/241 268/268/241 +f 269/269/242 270/270/242 271/271/242 +f 271/271/243 270/270/243 272/272/243 +f 271/271/244 272/272/245 273/273/246 +f 271/271/244 273/273/246 274/274/247 +f 274/274/247 273/273/246 275/275/248 +f 274/274/249 275/275/250 276/276/251 +f 276/276/251 275/275/250 277/277/252 +f 277/277/253 278/278/254 279/279/255 +f 279/279/255 278/278/254 280/280/256 +f 279/279/257 280/280/257 281/281/257 +f 281/281/258 280/280/258 282/282/258 +f 281/281/259 282/282/259 283/283/259 +f 283/283/260 282/282/261 284/284/262 +f 283/283/260 284/284/262 285/285/263 +f 285/285/263 284/284/262 286/286/264 +f 286/286/265 284/284/265 287/287/265 +f 286/286/266 287/287/267 288/288/268 +f 288/288/268 287/287/267 289/289/269 +f 288/288/268 289/289/269 290/290/270 +f 290/290/271 289/289/271 291/291/271 +f 290/290/272 291/291/272 292/292/272 +f 293/293/273 292/292/273 294/294/273 +f 295/295/274 296/296/274 297/297/274 +f 297/297/275 296/296/275 298/298/275 +f 297/297/276 298/298/276 299/299/276 +f 299/299/277 298/298/277 300/300/277 +f 299/299/278 300/300/279 301/301/280 +f 299/299/278 301/301/280 302/302/281 +f 302/302/282 301/301/282 303/303/282 +f 302/302/283 303/303/284 304/304/285 +f 302/302/283 304/304/285 305/305/286 +f 305/305/286 304/304/285 306/306/287 +f 305/305/286 306/306/287 307/307/288 +f 307/307/289 306/306/289 308/308/289 +f 307/307/290 308/308/290 309/309/290 +f 309/309/291 308/308/292 310/310/293 +f 309/309/291 310/310/293 311/311/294 +f 311/311/294 310/310/293 312/312/295 +f 312/312/295 310/310/293 313/313/296 +f 312/312/297 313/313/297 314/314/297 +f 312/312/298 314/314/298 315/315/298 +f 315/315/299 314/314/299 316/316/299 +f 316/316/300 314/314/300 317/317/300 +f 316/316/301 317/317/301 318/318/301 +f 318/318/302 317/317/302 319/319/302 +f 320/320/303 321/321/304 322/322/305 +f 322/322/306 323/323/306 9/9/306 +f 247/247/307 246/246/308 324/324/309 +f 324/324/309 246/246/308 321/321/310 +f 324/324/311 321/321/304 320/320/303 +f 324/324/311 320/320/303 325/325/312 +f 325/325/312 320/320/303 326/326/313 +f 325/325/310 326/326/314 269/269/315 +f 269/269/315 326/326/314 270/270/316 +f 296/296/317 295/295/318 327/327/319 +f 296/296/317 327/327/319 320/320/303 +f 320/320/303 327/327/319 326/326/313 +f 328/328/320 10/10/321 329/329/322 +f 329/329/322 10/10/321 9/9/323 +f 329/329/322 9/9/323 330/330/324 +f 331/331/316 332/332/325 333/333/326 +f 333/333/326 332/332/325 330/330/327 +f 333/333/328 330/330/324 9/9/323 +f 333/333/328 9/9/323 323/323/329 +f 323/323/330 334/334/330 335/335/330 +f 9/9/331 320/320/303 322/322/305 +f 222/222/332 322/322/332 223/223/332 +f 336/336/333 337/337/334 338/338/335 +f 338/338/335 337/337/334 339/339/336 +f 340/340/337 341/341/338 342/342/339 +f 342/342/339 341/341/338 338/338/335 +f 342/342/339 338/338/335 343/343/340 +f 343/343/340 338/338/335 339/339/336 +f 14/14/341 12/12/342 45/45/343 +f 45/45/343 12/12/342 22/22/344 +f 293/293/345 294/294/346 344/344/347 +f 293/293/345 344/344/347 345/345/348 +f 345/345/349 344/344/350 343/343/340 +f 343/343/340 344/344/350 346/346/351 +f 346/346/352 344/344/353 318/318/354 +f 346/346/352 318/318/354 319/319/355 +f 268/268/356 267/267/356 345/345/357 +f 268/268/356 345/345/357 347/347/357 +f 244/244/358 245/245/359 339/339/360 +f 339/339/360 245/245/359 347/347/361 +f 339/339/336 347/347/362 343/343/340 +f 343/343/340 347/347/362 345/345/349 +f 22/22/363 342/342/364 45/45/365 +f 45/45/366 342/342/339 343/343/340 +f 348/348/367 349/349/367 350/350/367 +f 350/350/368 349/349/368 351/351/368 +f 350/350/369 351/351/369 352/352/369 +f 352/352/370 351/351/370 353/353/370 +f 352/352/371 353/353/371 354/354/371 +f 354/354/372 353/353/373 348/348/374 +f 348/348/374 353/353/373 349/349/375 +f 355/355/376 356/356/377 357/357/378 +f 355/355/376 357/357/378 358/358/379 +f 358/358/380 357/357/380 359/359/380 +f 358/358/381 359/359/381 360/360/381 +f 360/360/382 359/359/382 361/361/382 +f 360/360/383 361/361/384 355/355/385 +f 355/355/385 361/361/384 356/356/386 +f 362/362/387 363/363/387 364/364/387 +f 362/362/388 364/364/388 365/365/388 +f 365/365/389 364/364/389 366/366/389 +f 365/365/390 366/366/390 367/367/390 +f 367/367/391 366/366/391 363/363/391 +f 367/367/392 363/363/392 362/362/392 +f 335/335/393 368/368/393 369/369/393 +f 369/369/394 368/368/394 370/370/394 +f 369/369/395 370/370/395 371/371/395 +f 371/371/396 370/370/396 372/372/396 +f 371/371/397 372/372/217 373/373/398 +f 371/371/397 373/373/398 374/374/399 +f 374/374/399 373/373/398 375/375/400 +f 375/375/401 373/373/401 376/376/401 +f 375/375/402 376/376/402 377/377/402 +f 377/377/197 376/376/197 378/378/197 +f 377/377/403 378/378/403 379/379/403 +f 379/379/199 378/378/199 380/380/199 +f 379/379/404 380/380/404 381/381/404 +f 382/382/405 381/381/406 383/383/407 +f 382/382/405 383/383/407 384/384/408 +f 384/384/409 385/385/410 386/386/411 +f 386/386/412 385/385/412 387/387/412 +f 386/386/413 387/387/413 388/388/413 +f 388/388/414 337/337/414 336/336/414 +f 335/335/415 334/334/415 368/368/415 +f 389/389/416 390/390/416 391/391/416 +f 389/389/417 391/391/417 392/392/417 +f 392/392/418 391/391/418 393/393/418 +f 392/392/419 393/393/419 394/394/419 +f 394/394/420 393/393/420 390/390/420 +f 394/394/421 390/390/421 389/389/421 +f 395/395/422 396/396/422 397/397/422 +f 395/395/423 397/397/424 398/398/425 +f 395/395/426 398/398/426 399/399/426 +f 399/399/427 398/398/427 400/400/427 +f 399/399/428 400/400/428 401/401/428 +f 401/401/429 400/400/429 396/396/429 +f 401/401/430 396/396/430 395/395/430 +f 402/402/431 403/403/431 404/404/431 +f 404/404/432 403/403/432 374/374/432 +f 404/404/433 374/374/434 405/405/435 +f 405/405/435 374/374/434 406/406/436 +f 405/405/437 406/406/438 407/407/439 +f 405/405/437 407/407/439 402/402/440 +f 402/402/441 407/407/441 403/403/441 +f 332/332/242 331/331/242 408/408/242 +f 408/408/243 331/331/243 409/409/243 +f 408/408/244 409/409/442 410/410/443 +f 408/408/244 410/410/443 411/411/444 +f 411/411/445 410/410/446 412/412/193 +f 411/411/445 412/412/193 413/413/194 +f 413/413/447 412/412/448 414/414/449 +f 413/413/447 414/414/449 415/415/223 +f 415/415/450 414/414/451 416/416/452 +f 415/415/450 416/416/452 417/417/453 +f 417/417/228 416/416/229 418/418/454 +f 417/417/228 418/418/454 419/419/455 +f 419/419/455 418/418/454 420/420/456 +f 420/420/457 418/418/457 421/421/457 +f 420/420/458 421/421/458 422/422/458 +f 422/422/459 423/423/459 424/424/459 +f 424/424/460 423/423/460 425/425/460 +f 424/424/461 425/425/461 426/426/461 +f 426/426/462 425/425/462 427/427/462 +f 426/426/463 427/427/463 340/340/463 +f 340/340/464 427/427/464 341/341/464 +f 428/428/465 38/38/466 429/429/467 +f 429/429/467 38/38/466 430/430/468 +f 429/429/469 430/430/469 431/431/469 +f 431/431/470 430/430/470 432/432/470 +f 431/431/471 432/432/472 433/433/473 +f 433/433/473 432/432/472 434/434/474 +f 433/433/473 434/434/474 435/435/475 +f 435/435/475 434/434/474 436/436/476 +f 436/436/476 434/434/474 19/19/477 +f 436/436/476 19/19/477 437/437/478 +f 437/437/478 19/19/477 21/21/479 +f 437/437/478 21/21/479 438/438/480 +f 438/438/480 21/21/479 36/36/481 +f 438/438/480 36/36/481 439/439/482 +f 440/440/483 441/441/483 442/442/483 +f 440/440/484 442/442/484 443/443/484 +f 443/443/485 442/442/485 444/444/485 +f 443/443/486 444/444/486 445/445/486 +f 445/445/487 444/444/487 446/446/487 +f 445/445/488 446/446/489 441/441/490 +f 445/445/488 441/441/490 440/440/491 +f 447/447/492 448/448/492 449/449/492 +f 447/447/493 449/449/493 450/450/493 +f 450/450/494 449/449/495 451/451/496 +f 450/450/494 451/451/496 452/452/497 +f 452/452/498 451/451/498 448/448/498 +f 452/452/499 448/448/499 447/447/499 +f 453/453/500 454/454/500 455/455/500 +f 455/455/501 454/454/501 456/456/501 +f 455/455/502 456/456/502 457/457/502 +f 457/457/503 456/456/503 458/458/503 +f 457/457/504 458/458/504 453/453/504 +f 453/453/505 458/458/505 454/454/505 +f 328/328/506 459/459/507 10/10/508 +f 10/10/508 459/459/507 52/52/509 +f 5/5/510 460/460/511 6/6/512 +f 6/6/512 460/460/511 461/461/513 +f 42/42/514 462/462/515 220/220/516 +f 42/42/514 220/220/516 43/43/517 +f 463/463/518 40/40/519 30/30/520 +f 463/463/518 30/30/520 428/428/465 +f 428/428/465 30/30/520 38/38/466 +f 33/33/521 464/464/522 36/36/481 +f 36/36/481 464/464/522 439/439/482 +f 465/465/523 346/346/524 466/466/525 +f 466/466/525 346/346/524 467/467/526 +f 466/466/525 467/467/526 468/468/527 +f 468/468/527 467/467/526 469/469/528 +f 468/468/529 469/469/530 470/470/531 +f 470/470/531 469/469/530 355/355/376 +f 470/470/531 355/355/376 358/358/379 +f 470/470/531 358/358/379 471/471/532 +f 471/471/532 358/358/379 472/472/533 +f 471/471/532 472/472/533 473/473/534 +f 473/473/534 472/472/533 474/474/535 +f 473/473/534 474/474/535 475/475/536 +f 475/475/536 474/474/535 348/348/537 +f 475/475/536 348/348/537 476/476/538 +f 476/476/538 348/348/537 477/477/539 +f 476/476/538 477/477/539 478/478/540 +f 478/478/540 477/477/539 479/479/541 +f 478/478/540 479/479/541 480/480/542 +f 480/480/542 479/479/541 481/481/543 +f 481/481/543 479/479/541 367/367/544 +f 481/481/543 367/367/544 482/482/545 +f 482/482/546 367/367/546 362/362/546 +f 482/482/547 362/362/548 483/483/549 +f 482/482/547 483/483/549 484/484/550 +f 484/484/550 483/483/549 485/485/551 +f 485/485/551 483/483/549 486/486/552 +f 485/485/551 486/486/552 320/320/303 +f 485/485/551 320/320/303 487/487/553 +f 465/465/554 343/343/340 346/346/351 +f 488/488/555 489/489/556 465/465/554 +f 465/465/554 489/489/556 462/462/557 +f 490/490/558 491/491/559 461/461/560 +f 461/461/560 491/491/559 487/487/553 +f 461/461/560 487/487/553 6/6/561 +f 6/6/561 487/487/553 9/9/331 +f 9/9/331 487/487/553 320/320/303 +f 462/462/557 42/42/562 465/465/554 +f 465/465/554 42/42/562 45/45/563 +f 465/465/554 45/45/563 343/343/340 +f 7/7/5 9/9/5 8/8/5 +f 301/301/5 362/362/5 365/365/5 +f 298/298/5 362/362/5 300/300/5 +f 300/300/5 362/362/5 301/301/5 +f 486/486/5 483/483/5 298/298/5 +f 313/313/5 360/360/5 314/314/5 +f 486/486/5 296/296/564 320/320/564 +f 298/298/5 483/483/5 362/362/5 +f 477/477/5 348/348/5 350/350/5 +f 486/486/5 298/298/5 296/296/564 +f 308/308/5 352/352/5 354/354/5 +f 314/314/5 360/360/5 355/355/5 +f 314/314/5 355/355/5 469/469/5 +f 306/306/5 350/350/5 352/352/5 +f 306/306/5 352/352/5 308/308/5 +f 301/301/5 365/365/5 303/303/5 +f 303/303/5 365/365/5 304/304/5 +f 313/313/5 358/358/5 360/360/5 +f 314/314/5 469/469/5 467/467/5 +f 314/314/5 467/467/5 317/317/5 +f 317/317/5 467/467/5 319/319/5 +f 358/358/5 313/313/5 310/310/5 +f 350/350/5 306/306/5 304/304/5 +f 308/308/5 354/354/5 310/310/5 +f 479/479/5 477/477/5 304/304/5 +f 350/350/5 304/304/5 477/477/5 +f 354/354/5 348/348/5 474/474/5 +f 354/354/5 474/474/5 310/310/5 +f 310/310/5 474/474/5 472/472/5 +f 358/358/5 310/310/5 472/472/5 +f 467/467/5 346/346/5 319/319/5 +f 365/365/5 367/367/5 479/479/5 +f 365/365/5 479/479/5 304/304/5 +f 220/220/5 489/489/5 218/218/5 +f 462/462/5 489/489/5 220/220/5 +f 489/489/565 488/488/566 219/219/567 +f 489/489/565 219/219/567 218/218/568 +f 460/460/5 492/492/5 490/490/5 +f 460/460/5 490/490/5 461/461/5 +f 492/492/569 493/493/570 490/490/571 +f 490/490/571 493/493/570 491/491/572 +f 413/413/573 456/456/573 454/454/573 +f 424/424/574 448/448/573 451/451/575 +f 419/419/573 444/444/573 417/417/573 +f 451/451/575 422/422/576 424/424/574 +f 413/413/573 454/454/573 411/411/573 +f 458/458/573 456/456/573 494/494/573 +f 451/451/575 449/449/573 495/495/573 +f 448/448/573 424/424/574 426/426/573 +f 411/411/573 454/454/573 408/408/573 +f 419/419/573 446/446/573 444/444/573 +f 417/417/573 444/444/573 442/442/573 +f 446/446/573 419/419/573 420/420/577 +f 422/422/576 451/451/575 420/420/577 +f 496/496/573 340/340/573 342/342/573 +f 449/449/573 448/448/573 426/426/573 +f 449/449/573 426/426/573 497/497/573 +f 408/408/573 454/454/573 498/498/573 +f 498/498/573 454/454/573 458/458/573 +f 417/417/573 442/442/573 415/415/573 +f 420/420/577 495/495/573 499/499/573 +f 456/456/573 413/413/573 415/415/573 +f 495/495/573 420/420/577 451/451/575 +f 497/497/573 426/426/573 496/496/573 +f 446/446/573 420/420/577 499/499/573 +f 446/446/573 499/499/573 441/441/573 +f 426/426/573 340/340/573 496/496/573 +f 408/408/573 498/498/573 500/500/573 +f 415/415/573 442/442/573 501/501/573 +f 415/415/573 501/501/573 494/494/573 +f 494/494/573 456/456/573 415/415/573 +f 330/330/573 332/332/573 500/500/573 +f 500/500/573 332/332/573 408/408/573 +f 22/22/363 26/26/578 342/342/364 +f 342/342/364 26/26/578 496/496/579 +f 496/496/580 26/26/580 497/497/580 +f 497/497/581 26/26/581 35/35/581 +f 497/497/582 35/35/582 449/449/582 +f 34/34/583 449/449/583 35/35/583 +f 449/449/584 34/34/584 495/495/584 +f 34/34/585 20/20/585 495/495/585 +f 495/495/586 20/20/586 499/499/586 +f 499/499/587 20/20/587 502/502/587 +f 503/503/588 442/442/588 441/441/588 +f 503/503/589 441/441/589 502/502/589 +f 502/502/590 441/441/590 499/499/590 +f 442/442/591 503/503/591 501/501/591 +f 501/501/592 503/503/592 504/504/592 +f 501/501/593 504/504/594 494/494/595 +f 494/494/595 504/504/594 458/458/596 +f 458/458/596 504/504/594 505/505/597 +f 458/458/596 505/505/597 498/498/598 +f 498/498/599 505/505/599 37/37/599 +f 498/498/600 37/37/600 500/500/600 +f 500/500/601 37/37/601 329/329/601 +f 329/329/602 330/330/602 500/500/602 +f 375/375/573 406/406/573 374/374/573 +f 396/396/603 400/400/604 386/386/411 +f 381/381/605 393/393/606 379/379/607 +f 400/400/604 384/384/409 386/386/411 +f 374/374/573 403/403/608 371/371/609 +f 384/384/409 400/400/604 398/398/610 +f 384/384/409 398/398/610 382/382/611 +f 506/506/573 391/391/573 390/390/573 +f 396/396/603 386/386/411 388/388/612 +f 381/381/605 390/390/613 393/393/606 +f 390/390/613 381/381/605 382/382/611 +f 507/507/614 323/323/615 335/335/616 +f 508/508/617 336/336/618 338/338/619 +f 397/397/620 396/396/603 388/388/612 +f 397/397/620 388/388/612 509/509/621 +f 371/371/609 403/403/608 510/510/622 +f 510/510/622 403/403/608 407/407/623 +f 379/379/607 393/393/606 391/391/573 +f 379/379/607 391/391/573 377/377/573 +f 406/406/573 375/375/573 377/377/573 +f 511/511/573 382/382/611 398/398/610 +f 382/382/611 511/511/573 512/512/573 +f 509/509/621 388/388/612 508/508/617 +f 390/390/613 382/382/611 512/512/573 +f 388/388/612 336/336/618 508/508/617 +f 371/371/609 510/510/622 507/507/614 +f 371/371/609 507/507/614 369/369/573 +f 391/391/573 506/506/573 377/377/573 +f 506/506/573 513/513/573 377/377/573 +f 407/407/573 406/406/573 377/377/573 +f 407/407/573 377/377/573 513/513/573 +f 507/507/614 335/335/616 369/369/573 +f 453/453/5 410/410/5 409/409/5 +f 410/410/5 453/453/5 455/455/5 +f 410/410/5 455/455/5 412/412/5 +f 423/423/624 452/452/625 447/447/5 +f 453/453/626 510/510/626 457/457/626 +f 423/423/624 447/447/5 425/425/5 +f 333/333/5 514/514/627 331/331/5 +f 409/409/628 514/514/627 510/510/629 +f 510/510/630 453/453/630 409/409/630 +f 338/338/631 341/341/632 515/515/633 +f 425/425/5 447/447/5 516/516/5 +f 516/516/5 447/447/5 450/450/5 +f 514/514/627 409/409/628 331/331/5 +f 425/425/5 516/516/5 515/515/633 +f 425/425/5 515/515/633 427/427/5 +f 416/416/5 443/443/5 418/418/5 +f 418/418/5 443/443/5 445/445/5 +f 445/445/5 440/440/5 517/517/5 +f 422/422/634 452/452/625 423/423/624 +f 412/412/5 455/455/5 457/457/5 +f 412/412/5 457/457/5 414/414/5 +f 450/450/5 452/452/625 518/518/5 +f 418/418/5 445/445/5 421/421/635 +f 515/515/633 341/341/632 427/427/5 +f 452/452/625 422/422/634 421/421/635 +f 445/445/5 517/517/5 421/421/635 +f 519/519/5 520/520/5 414/414/5 +f 440/440/5 443/443/5 520/520/5 +f 520/520/5 443/443/5 414/414/5 +f 443/443/5 416/416/5 414/414/5 +f 421/421/635 517/517/5 518/518/5 +f 457/457/5 519/519/5 414/414/5 +f 518/518/5 452/452/625 421/421/635 +f 338/338/636 515/515/636 508/508/636 +f 508/508/637 515/515/637 509/509/637 +f 509/509/638 515/515/638 516/516/638 +f 509/509/639 516/516/639 397/397/639 +f 397/397/424 516/516/640 450/450/641 +f 397/397/424 450/450/641 398/398/425 +f 398/398/425 450/450/641 518/518/642 +f 398/398/643 518/518/643 511/511/643 +f 511/511/644 518/518/644 517/517/644 +f 511/511/645 517/517/645 512/512/645 +f 512/512/646 517/517/647 440/440/648 +f 512/512/646 440/440/648 390/390/649 +f 390/390/649 440/440/648 506/506/650 +f 506/506/650 440/440/648 520/520/651 +f 506/506/652 520/520/652 513/513/652 +f 513/513/653 520/520/653 519/519/653 +f 513/513/654 519/519/654 407/407/654 +f 407/407/655 519/519/656 457/457/657 +f 407/407/655 457/457/657 510/510/658 +f 510/510/659 514/514/659 507/507/659 +f 507/507/660 514/514/661 333/333/328 +f 507/507/660 333/333/328 323/323/329 +f 253/253/573 521/521/662 522/522/573 +f 263/263/573 523/523/663 524/524/573 +f 259/259/573 525/525/573 257/257/573 +f 253/253/573 522/522/573 250/250/664 +f 257/257/573 525/525/573 526/526/573 +f 263/263/573 524/524/573 527/527/573 +f 263/263/573 527/527/573 260/260/573 +f 528/528/665 526/526/573 529/529/573 +f 523/523/663 265/265/666 266/266/667 +f 265/265/666 523/523/663 263/263/573 +f 250/250/664 522/522/573 530/530/668 +f 259/259/573 531/531/573 525/525/573 +f 531/531/573 259/259/573 260/260/573 +f 532/532/669 268/268/670 347/347/671 +f 533/533/672 523/523/663 266/266/667 +f 533/533/673 266/266/674 534/534/675 +f 250/250/664 530/530/668 535/535/676 +f 257/257/573 526/526/573 255/255/677 +f 521/521/662 253/253/573 255/255/677 +f 536/536/573 260/260/573 527/527/573 +f 260/260/573 536/536/573 531/531/573 +f 534/534/678 266/266/679 532/532/669 +f 266/266/679 268/268/670 532/532/669 +f 250/250/664 535/535/676 537/537/680 +f 250/250/664 537/537/680 248/248/681 +f 526/526/573 528/528/665 255/255/677 +f 528/528/665 538/538/682 255/255/677 +f 521/521/662 255/255/677 538/538/682 +f 321/321/573 246/246/683 537/537/680 +f 537/537/680 246/246/683 248/248/681 +f 539/539/684 225/225/685 224/224/686 +f 539/539/684 540/540/5 225/225/685 +f 225/225/685 540/540/5 227/227/5 +f 239/239/5 541/541/687 241/241/688 +f 322/322/689 542/542/690 223/223/691 +f 539/539/692 224/224/693 535/535/694 +f 543/543/695 347/347/696 245/245/697 +f 241/241/688 541/541/687 534/534/698 +f 534/534/698 541/541/687 544/544/699 +f 535/535/700 224/224/701 542/542/690 +f 542/542/690 224/224/701 223/223/691 +f 241/241/688 534/534/698 243/243/702 +f 243/243/702 534/534/698 543/543/695 +f 545/545/5 227/227/5 540/540/5 +f 233/233/5 546/546/5 547/547/5 +f 548/548/703 549/549/5 546/546/5 +f 237/237/5 550/550/5 239/239/5 +f 227/227/5 545/545/5 229/229/704 +f 233/233/5 547/547/5 235/235/5 +f 543/543/695 245/245/697 243/243/702 +f 550/550/5 237/237/5 235/235/5 +f 231/231/5 546/546/5 233/233/5 +f 235/235/5 547/547/5 551/551/5 +f 548/548/703 546/546/5 229/229/704 +f 546/546/5 231/231/5 229/229/704 +f 538/538/705 548/548/703 229/229/704 +f 545/545/5 552/552/706 229/229/704 +f 229/229/704 552/552/706 538/538/705 +f 550/550/5 235/235/5 551/551/5 +f 347/347/707 543/543/707 532/532/707 +f 532/532/708 543/543/708 534/534/708 +f 533/533/673 534/534/675 544/544/709 +f 533/533/673 544/544/709 527/527/710 +f 527/527/711 544/544/712 550/550/713 +f 527/527/714 550/550/714 536/536/714 +f 536/536/715 550/550/715 551/551/715 +f 536/536/716 551/551/717 547/547/718 +f 536/536/716 547/547/718 531/531/719 +f 531/531/720 547/547/721 549/549/722 +f 531/531/720 549/549/722 529/529/723 +f 529/529/723 549/549/722 548/548/724 +f 529/529/723 548/548/724 528/528/725 +f 528/528/725 548/548/724 538/538/726 +f 538/538/727 552/552/727 521/521/727 +f 521/521/728 552/552/728 530/530/728 +f 530/530/729 552/552/730 539/539/692 +f 530/530/729 539/539/692 535/535/694 +f 537/537/731 535/535/731 542/542/731 +f 537/537/732 542/542/733 322/322/734 +f 537/537/732 322/322/734 321/321/735 +f 302/302/573 366/366/573 364/364/573 +f 309/309/573 353/353/736 307/307/573 +f 307/307/573 353/353/736 351/351/573 +f 359/359/573 312/312/573 361/361/573 +f 302/302/573 364/364/573 299/299/737 +f 363/363/738 366/366/739 553/553/740 +f 356/356/573 315/315/573 316/316/573 +f 356/356/573 361/361/573 315/315/573 +f 315/315/573 361/361/573 312/312/573 +f 299/299/737 364/364/573 363/363/668 +f 353/353/736 309/309/573 311/311/741 +f 312/312/573 359/359/573 311/311/741 +f 554/554/742 318/318/743 344/344/744 +f 356/356/377 316/316/745 555/555/746 +f 299/299/737 363/363/668 556/556/676 +f 307/307/573 351/351/573 305/305/747 +f 311/311/741 557/557/748 558/558/749 +f 366/366/573 302/302/573 305/305/573 +f 557/557/748 311/311/741 359/359/573 +f 557/557/748 359/359/573 357/357/573 +f 555/555/750 316/316/751 554/554/742 +f 353/353/736 311/311/741 558/558/749 +f 353/353/736 558/558/749 349/349/752 +f 554/554/742 316/316/751 318/318/743 +f 299/299/737 556/556/676 559/559/753 +f 299/299/737 559/559/753 297/297/573 +f 351/351/573 349/349/573 560/560/754 +f 351/351/573 560/560/754 305/305/747 +f 305/305/747 560/560/754 553/553/755 +f 553/553/740 366/366/739 305/305/756 +f 327/327/573 295/295/573 559/559/753 +f 559/559/753 295/295/573 297/297/573 +f 561/561/5 273/273/5 272/272/5 +f 273/273/5 561/561/5 275/275/757 +f 287/287/5 562/562/758 289/289/5 +f 287/287/5 563/563/5 562/562/758 +f 289/289/5 562/562/758 291/291/759 +f 553/553/760 564/564/761 565/565/762 +f 326/326/5 566/566/763 270/270/5 +f 565/565/5 561/561/5 272/272/5 +f 565/565/764 272/272/765 556/556/766 +f 291/291/759 562/562/758 555/555/767 +f 555/555/767 562/562/758 567/567/768 +f 556/556/769 272/272/770 566/566/763 +f 566/566/763 272/272/770 270/270/5 +f 291/291/759 555/555/767 568/568/771 +f 291/291/759 568/568/771 292/292/772 +f 568/568/771 344/344/773 294/294/774 +f 564/564/761 275/275/757 561/561/5 +f 282/282/5 569/569/5 570/570/5 +f 571/571/5 572/572/5 573/573/775 +f 275/275/757 564/564/761 277/277/776 +f 277/277/776 564/564/761 278/278/777 +f 282/282/5 570/570/5 284/284/5 +f 284/284/5 570/570/5 571/571/5 +f 568/568/771 294/294/774 292/292/772 +f 563/563/5 287/287/5 284/284/778 +f 280/280/5 572/572/5 569/569/5 +f 280/280/5 569/569/5 282/282/5 +f 571/571/779 558/558/779 284/284/779 +f 553/553/760 573/573/775 278/278/777 +f 573/573/775 572/572/5 278/278/777 +f 572/572/5 280/280/5 278/278/777 +f 284/284/778 558/558/780 574/574/781 +f 564/564/761 553/553/760 278/278/777 +f 567/567/5 563/563/5 574/574/781 +f 574/574/781 563/563/5 284/284/778 +f 344/344/782 568/568/783 554/554/784 +f 554/554/784 568/568/783 555/555/785 +f 356/356/377 555/555/746 567/567/786 +f 356/356/377 567/567/786 357/357/378 +f 357/357/378 567/567/786 574/574/787 +f 357/357/788 574/574/788 557/557/788 +f 557/557/789 574/574/789 558/558/789 +f 558/558/790 571/571/791 349/349/792 +f 349/349/792 571/571/791 573/573/793 +f 349/349/792 573/573/793 560/560/794 +f 560/560/795 573/573/795 553/553/795 +f 363/363/796 553/553/797 565/565/764 +f 363/363/796 565/565/764 556/556/766 +f 559/559/798 556/556/798 566/566/798 +f 559/559/799 566/566/800 326/326/801 +f 559/559/799 326/326/801 327/327/802 +f 575/575/803 530/530/804 576/576/805 +f 576/576/805 530/530/804 522/522/806 +f 576/576/807 522/522/807 577/577/807 +f 577/577/808 522/522/808 521/521/808 +f 577/577/809 521/521/809 575/575/809 +f 575/575/810 521/521/810 530/530/810 +f 277/277/811 578/578/812 276/276/813 +f 283/283/573 579/579/573 580/580/573 +f 283/283/573 580/580/573 281/281/573 +f 581/581/573 286/286/573 288/288/573 +f 276/276/573 582/582/573 274/274/573 +f 281/281/573 580/580/573 583/583/573 +f 584/584/573 578/578/812 585/585/573 +f 586/586/573 583/583/573 587/587/573 +f 588/588/573 587/587/573 579/579/573 +f 589/589/573 581/581/573 590/590/573 +f 591/591/814 290/290/815 292/292/816 +f 290/290/815 591/591/814 288/288/573 +f 274/274/573 582/582/573 271/271/573 +f 592/592/817 591/591/814 292/292/816 +f 579/579/573 283/283/573 285/285/573 +f 286/286/573 581/581/573 285/285/573 +f 592/592/817 293/293/818 345/345/819 +f 271/271/820 582/582/820 593/593/820 +f 593/593/821 582/582/821 584/584/821 +f 281/281/573 583/583/573 279/279/822 +f 285/285/573 589/589/573 588/588/573 +f 578/578/812 277/277/811 279/279/822 +f 589/589/573 285/285/573 581/581/573 +f 579/579/573 285/285/573 588/588/573 +f 292/292/816 293/293/818 592/592/817 +f 271/271/823 593/593/824 594/594/825 +f 583/583/573 586/586/573 279/279/822 +f 586/586/573 585/585/573 279/279/822 +f 585/585/573 578/578/812 279/279/822 +f 325/325/573 269/269/573 594/594/825 +f 594/594/825 269/269/573 271/271/823 +f 575/575/5 251/251/5 249/249/5 +f 575/575/5 576/576/5 251/251/5 +f 251/251/5 576/576/5 252/252/5 +f 262/262/5 595/595/5 264/264/826 +f 264/264/826 595/595/5 596/596/827 +f 264/264/826 596/596/827 266/266/828 +f 324/324/5 597/597/829 247/247/830 +f 249/249/831 597/597/829 593/593/629 +f 593/593/832 575/575/832 249/249/832 +f 247/247/830 597/597/829 248/248/833 +f 266/266/834 596/596/835 598/598/836 +f 597/597/829 249/249/831 248/248/833 +f 266/266/834 598/598/836 599/599/837 +f 266/266/834 599/599/837 267/267/838 +f 599/599/837 345/345/839 267/267/838 +f 577/577/5 252/252/5 576/576/5 +f 256/256/5 600/600/5 258/258/5 +f 601/601/5 602/602/5 603/603/5 +f 604/604/5 602/602/5 605/605/5 +f 262/262/5 606/606/5 595/595/5 +f 252/252/5 577/577/5 254/254/5 +f 607/607/5 577/577/5 575/575/5 +f 258/258/5 600/600/5 604/604/5 +f 258/258/5 604/604/5 261/261/5 +f 606/606/5 262/262/5 261/261/5 +f 256/256/5 603/603/5 600/600/5 +f 604/604/5 605/605/5 261/261/5 +f 607/607/5 601/601/5 254/254/5 +f 601/601/5 603/603/5 254/254/5 +f 603/603/5 256/256/5 254/254/5 +f 261/261/5 605/605/5 608/608/5 +f 577/577/5 607/607/5 254/254/5 +f 608/608/5 606/606/5 261/261/5 +f 345/345/840 599/599/840 592/592/840 +f 592/592/841 599/599/841 598/598/841 +f 592/592/842 598/598/842 591/591/842 +f 591/591/843 598/598/843 596/596/843 +f 591/591/844 596/596/845 590/590/846 +f 590/590/847 596/596/848 606/606/849 +f 590/590/847 606/606/849 589/589/850 +f 589/589/851 606/606/851 608/608/851 +f 589/589/852 608/608/852 588/588/852 +f 588/588/853 608/608/853 605/605/853 +f 588/588/854 605/605/855 602/602/856 +f 588/588/854 602/602/856 587/587/857 +f 587/587/857 602/602/856 601/601/858 +f 587/587/857 601/601/858 586/586/859 +f 586/586/860 601/601/860 585/585/860 +f 585/585/861 601/601/861 607/607/861 +f 585/585/862 607/607/862 584/584/862 +f 584/584/863 607/607/864 575/575/865 +f 584/584/863 575/575/865 593/593/866 +f 593/593/659 597/597/659 594/594/659 +f 594/594/867 597/597/661 324/324/868 +f 594/594/867 324/324/868 325/325/802 +f 539/539/869 609/609/869 540/540/869 +f 540/540/870 609/609/870 610/610/870 +f 540/540/871 610/610/871 545/545/871 +f 545/545/872 610/610/873 611/611/874 +f 545/545/872 611/611/874 552/552/875 +f 552/552/730 611/611/876 539/539/692 +f 539/539/877 611/611/877 609/609/877 +f 612/612/878 339/339/878 613/613/878 +f 228/228/573 610/610/573 609/609/879 +f 234/234/573 614/614/573 232/232/573 +f 615/615/573 238/238/573 240/240/573 +f 615/615/573 240/240/573 616/616/573 +f 228/228/573 609/609/879 226/226/880 +f 232/232/573 614/614/573 617/617/573 +f 618/618/573 617/617/573 619/619/573 +f 620/620/881 242/242/882 243/243/883 +f 242/242/882 620/620/881 240/240/573 +f 240/240/573 620/620/881 616/616/573 +f 226/226/880 609/609/879 224/224/884 +f 234/234/573 621/621/573 614/614/573 +f 621/621/573 234/234/573 236/236/573 +f 622/622/885 322/322/886 222/222/887 +f 238/238/573 615/615/573 236/236/573 +f 612/612/888 244/244/889 339/339/890 +f 620/620/891 243/243/891 623/623/891 +f 224/224/884 609/609/879 624/624/892 +f 624/624/892 609/609/879 611/611/573 +f 232/232/573 617/617/573 230/230/573 +f 610/610/573 228/228/573 230/230/573 +f 625/625/573 236/236/573 626/626/573 +f 626/626/573 236/236/573 615/615/573 +f 236/236/573 625/625/573 621/621/573 +f 623/623/893 243/243/894 612/612/888 +f 243/243/894 244/244/889 612/612/888 +f 224/224/884 624/624/892 622/622/885 +f 224/224/884 622/622/885 222/222/887 +f 617/617/573 618/618/573 230/230/573 +f 618/618/573 627/627/573 230/230/573 +f 611/611/573 610/610/573 230/230/573 +f 611/611/573 230/230/573 627/627/573 +f 402/402/5 372/372/5 370/370/5 +f 372/372/5 402/402/5 404/404/5 +f 372/372/5 404/404/5 373/373/5 +f 385/385/895 401/401/5 387/387/896 +f 387/387/896 401/401/5 395/395/897 +f 387/387/896 395/395/897 388/388/898 +f 628/628/5 405/405/5 402/402/5 +f 402/402/5 370/370/5 629/629/5 +f 613/613/899 339/339/900 337/337/901 +f 388/388/902 395/395/902 623/623/902 +f 629/629/5 370/370/5 334/334/5 +f 334/334/5 370/370/5 368/368/5 +f 388/388/903 623/623/904 613/613/899 +f 388/388/903 613/613/899 337/337/901 +f 405/405/5 373/373/5 404/404/5 +f 380/380/905 392/392/5 394/394/906 +f 394/394/906 389/389/5 630/630/5 +f 384/384/907 399/399/908 385/385/895 +f 385/385/895 399/399/908 401/401/5 +f 373/373/5 405/405/5 376/376/5 +f 380/380/905 394/394/906 381/381/909 +f 381/381/909 394/394/906 383/383/910 +f 631/631/5 395/395/5 399/399/908 +f 399/399/908 384/384/907 383/383/910 +f 378/378/5 389/389/5 392/392/5 +f 378/378/5 392/392/5 380/380/905 +f 394/394/906 630/630/5 383/383/910 +f 628/628/5 632/632/5 376/376/5 +f 389/389/5 378/378/5 376/376/5 +f 383/383/910 630/630/5 631/631/5 +f 376/376/5 632/632/5 389/389/5 +f 405/405/5 628/628/5 376/376/5 +f 631/631/5 399/399/908 383/383/910 +f 612/612/911 613/613/911 623/623/911 +f 620/620/912 623/623/913 395/395/914 +f 620/620/912 395/395/914 626/626/915 +f 626/626/915 395/395/914 631/631/916 +f 626/626/917 631/631/917 625/625/917 +f 625/625/644 631/631/644 630/630/644 +f 625/625/918 630/630/918 621/621/918 +f 621/621/919 630/630/919 389/389/919 +f 621/621/920 389/389/921 619/619/922 +f 619/619/922 389/389/921 618/618/923 +f 618/618/924 389/389/924 632/632/924 +f 618/618/925 632/632/925 627/627/925 +f 627/627/926 632/632/926 628/628/926 +f 627/627/927 628/628/927 611/611/927 +f 611/611/928 628/628/928 402/402/928 +f 611/611/929 402/402/929 624/624/929 +f 624/624/930 402/402/930 629/629/930 +f 624/624/931 629/629/931 622/622/931 +f 622/622/932 629/629/932 334/334/932 +f 622/622/933 334/334/933 323/323/933 +f 622/622/934 323/323/934 322/322/934 +f 562/562/935 591/591/844 590/590/846 +f 562/562/935 590/590/846 567/567/936 +f 567/567/937 590/590/937 581/581/937 +f 567/567/938 581/581/938 563/563/938 +f 563/563/939 581/581/939 288/288/939 +f 563/563/940 288/288/940 562/562/940 +f 562/562/941 288/288/941 591/591/941 +f 596/596/942 523/523/942 533/533/942 +f 596/596/943 533/533/673 606/606/944 +f 606/606/944 533/533/673 527/527/710 +f 606/606/945 527/527/945 524/524/945 +f 606/606/946 524/524/946 595/595/946 +f 595/595/947 524/524/947 523/523/947 +f 595/595/948 523/523/948 596/596/948 +f 541/541/949 620/620/949 544/544/949 +f 544/544/950 620/620/950 626/626/950 +f 544/544/712 626/626/951 550/550/713 +f 550/550/952 626/626/952 615/615/952 +f 550/550/953 615/615/954 239/239/955 +f 239/239/955 615/615/954 616/616/956 +f 239/239/957 616/616/958 541/541/959 +f 541/541/959 616/616/958 620/620/960 +f 571/571/961 587/587/961 572/572/961 +f 572/572/962 587/587/962 583/583/962 +f 572/572/963 583/583/963 569/569/963 +f 569/569/964 583/583/964 580/580/964 +f 569/569/965 580/580/965 570/570/965 +f 570/570/966 580/580/966 579/579/966 +f 570/570/967 579/579/967 571/571/967 +f 571/571/968 579/579/968 587/587/968 +f 602/602/969 529/529/970 603/603/971 +f 603/603/971 529/529/970 526/526/972 +f 603/603/973 526/526/973 600/600/973 +f 600/600/974 526/526/974 525/525/974 +f 600/600/975 525/525/976 604/604/977 +f 604/604/977 525/525/976 531/531/978 +f 604/604/979 531/531/720 602/602/980 +f 602/602/980 531/531/720 529/529/723 +f 549/549/981 619/619/981 617/617/981 +f 549/549/982 617/617/982 546/546/982 +f 546/546/983 617/617/983 614/614/983 +f 546/546/984 614/614/984 547/547/984 +f 547/547/985 614/614/985 621/621/985 +f 547/547/721 621/621/920 549/549/722 +f 549/549/722 621/621/920 619/619/922 +f 561/561/986 582/582/986 276/276/986 +f 561/561/987 276/276/987 564/564/987 +f 564/564/988 276/276/988 578/578/988 +f 564/564/989 578/578/990 584/584/991 +f 564/564/989 584/584/991 565/565/992 +f 565/565/993 584/584/993 582/582/993 +f 565/565/994 582/582/994 561/561/994 +f 78/78/995 77/77/996 633/633/997 +f 78/78/995 633/633/997 634/634/998 +f 634/634/999 633/633/1000 195/195/155 +f 634/634/999 195/195/155 635/635/1001 +f 634/634/999 635/635/1001 100/100/1002 +f 634/634/999 100/100/1002 99/99/996 +f 123/123/1003 122/122/1004 636/636/1005 +f 123/123/1003 636/636/1005 195/195/1006 +f 195/195/155 636/636/1007 635/635/1001 +f 25/25/1008 46/46/1009 23/23/1010 +f 23/23/1010 46/46/1009 44/44/1011 +f 23/23/1012 44/44/1013 637/637/1014 +f 171/171/1015 170/170/1015 637/637/1015 +f 637/637/1016 44/44/1016 638/638/1016 +f 638/638/1017 44/44/187 639/639/1018 +f 638/638/1019 639/639/1020 148/148/1021 +f 638/638/1019 148/148/1021 147/147/1022 +f 44/44/187 195/195/155 639/639/1018 +f 639/639/1018 195/195/155 633/633/1000 +f 639/639/1023 633/633/1024 53/53/1025 +f 53/53/1025 633/633/1024 54/54/1026 +f 207/207/169 640/640/1027 205/205/167 +f 205/205/1028 640/640/1028 641/641/1028 +f 641/641/1029 640/640/1029 642/642/1029 +f 641/641/1030 642/642/1030 643/643/1030 +f 641/641/1031 643/643/1031 644/644/1031 +f 644/644/1032 643/643/1033 207/207/1034 +f 207/207/1034 643/643/1033 640/640/1035 +f 200/200/1036 645/645/1036 646/646/1036 +f 646/646/1037 645/645/1037 647/647/1037 +f 646/646/1038 647/647/1038 648/648/1038 +f 648/648/1039 647/647/1039 649/649/1039 +f 648/648/1040 649/649/1040 200/200/1040 +f 200/200/1041 649/649/1041 645/645/1041 +f 650/650/1042 651/651/1043 212/212/1044 +f 212/212/1044 651/651/1043 652/652/1045 +f 212/212/1046 652/652/1047 653/653/1048 +f 653/653/1048 652/652/1047 654/654/1049 +f 653/653/1050 654/654/1050 140/140/1050 +f 653/653/1051 140/140/1051 650/650/1051 +f 650/650/1052 140/140/1052 651/651/1052 +f 655/655/1053 656/656/1054 657/657/1055 +f 655/655/1053 657/657/1055 658/658/1056 +f 658/658/1057 657/657/1057 659/659/1057 +f 659/659/1058 657/657/1058 159/159/1058 +f 659/659/1059 159/159/1059 660/660/1059 +f 659/659/1060 660/660/1060 655/655/1060 +f 655/655/1061 660/660/1061 656/656/1061 +f 661/661/1062 662/662/1063 663/663/1064 +f 663/663/1064 662/662/1063 664/664/1065 +f 663/663/1066 664/664/1066 665/665/1066 +f 663/663/1067 665/665/1067 666/666/1067 +f 666/666/1068 665/665/1069 661/661/1070 +f 661/661/1070 665/665/1069 662/662/1071 +f 667/667/1072 668/668/1072 669/669/1072 +f 669/669/1073 668/668/1073 670/670/1073 +f 669/669/1074 670/670/1074 671/671/1074 +f 671/671/1075 670/670/1075 672/672/1075 +f 671/671/1076 672/672/1076 667/667/1076 +f 667/667/1077 672/672/1077 668/668/1077 +f 31/31/1078 47/47/1079 25/25/1080 +f 25/25/1080 47/47/1079 46/46/1081 +f 33/33/521 28/28/1082 464/464/522 +f 464/464/522 28/28/1082 673/673/1083 +f 28/28/1082 27/27/1084 673/673/1083 +f 673/673/1083 27/27/1084 674/674/1085 +f 674/674/1085 27/27/1084 675/675/1086 +f 674/674/1085 675/675/1086 676/676/1087 +f 676/676/1087 675/675/1086 677/677/1088 +f 676/676/1087 677/677/1088 678/678/1089 +f 678/678/1089 677/677/1088 679/679/1090 +f 678/678/1089 679/679/1090 680/680/1091 +f 680/680/1091 679/679/1090 681/681/1092 +f 681/681/1092 682/682/1093 680/680/1091 +f 682/682/1093 681/681/1092 40/40/519 +f 682/682/1093 40/40/519 463/463/518 +f 683/683/1094 684/684/1094 685/685/1094 +f 683/683/1095 685/685/1095 686/686/1095 +f 686/686/1096 685/685/1096 687/687/1096 +f 686/686/1097 687/687/1097 688/688/1097 +f 688/688/1098 687/687/1098 689/689/1098 +f 688/688/1099 689/689/1099 683/683/1099 +f 683/683/1100 689/689/1100 684/684/1100 +f 690/690/1101 691/691/1101 692/692/1101 +f 690/690/1102 692/692/1102 693/693/1102 +f 693/693/1103 692/692/1103 694/694/1103 +f 693/693/1104 694/694/1104 695/695/1104 +f 695/695/1105 694/694/1105 691/691/1105 +f 695/695/1106 691/691/1106 690/690/1106 +f 696/696/1107 697/697/1107 698/698/1107 +f 698/698/1108 697/697/1108 699/699/1108 +f 698/698/1109 699/699/1109 700/700/1109 +f 700/700/1110 699/699/1110 187/187/1110 +f 700/700/1111 187/187/1111 701/701/1111 +f 701/701/1112 187/187/1112 702/702/1112 +f 701/701/1113 702/702/1113 696/696/1113 +f 696/696/1114 702/702/1114 697/697/1114 +f 2/2/1115 1/1/1116 48/48/1117 +f 48/48/1117 1/1/1116 703/703/1118 +f 48/48/1119 703/703/1120 51/51/1121 +f 51/51/1121 703/703/1120 704/704/1122 +f 47/47/1123 31/31/1124 16/16/1125 +f 47/47/1123 16/16/1125 15/15/1126 +f 460/460/1127 5/5/1128 705/705/1129 +f 460/460/1127 705/705/1129 492/492/1130 +f 492/492/1130 705/705/1129 493/493/1131 +f 127/127/5 648/648/5 129/129/5 +f 129/129/5 648/648/5 131/131/5 +f 646/646/5 648/648/5 127/127/5 +f 653/653/5 139/139/5 136/136/5 +f 653/653/5 650/650/5 139/139/5 +f 139/139/5 650/650/5 141/141/5 +f 646/646/5 126/126/1132 200/200/5 +f 126/126/1132 646/646/5 127/127/5 +f 653/653/5 210/210/5 212/212/5 +f 133/133/5 641/641/5 134/134/5 +f 134/134/5 641/641/5 644/644/5 +f 131/131/5 205/205/5 641/641/5 +f 131/131/5 641/641/5 133/133/5 +f 123/123/1133 195/195/1134 196/196/1135 +f 134/134/5 644/644/5 136/136/5 +f 141/141/5 650/650/5 144/144/5 +f 144/144/5 650/650/5 212/212/5 +f 144/144/5 212/212/5 214/214/5 +f 208/208/5 136/136/5 207/207/5 +f 207/207/5 136/136/5 644/644/5 +f 203/203/5 131/131/5 200/200/5 +f 200/200/5 131/131/5 648/648/5 +f 131/131/5 203/203/5 205/205/5 +f 136/136/5 208/208/5 210/210/5 +f 210/210/5 653/653/5 136/136/5 +f 200/200/5 126/126/1132 198/198/5 +f 198/198/5 126/126/1132 196/196/1135 +f 196/196/1135 126/126/1132 124/124/1136 +f 144/144/5 214/214/5 146/146/5 +f 196/196/1135 124/124/1136 123/123/1133 +f 214/214/5 217/217/5 146/146/5 +f 176/176/573 692/692/573 691/691/573 +f 692/692/573 176/176/573 178/178/573 +f 176/176/573 691/691/573 174/174/573 +f 188/188/573 702/702/573 187/187/573 +f 41/41/1137 706/706/1138 189/189/1139 +f 702/702/573 188/188/573 189/189/1139 +f 174/174/573 691/691/573 707/707/573 +f 707/707/573 691/691/573 694/694/573 +f 187/187/1140 699/699/1141 185/185/1142 +f 185/185/1142 699/699/1141 184/184/1143 +f 708/708/573 685/685/573 684/684/573 +f 697/697/573 702/702/573 706/706/1138 +f 706/706/1138 702/702/573 189/189/1139 +f 41/41/1137 191/191/1144 709/709/1145 +f 174/174/573 707/707/573 710/710/1146 +f 174/174/573 710/710/1146 172/172/573 +f 172/172/573 710/710/1146 170/170/1147 +f 684/684/1148 689/689/1149 711/711/1150 +f 181/181/573 689/689/1149 180/180/573 +f 180/180/573 689/689/1149 687/687/573 +f 41/41/1137 189/189/1139 191/191/1144 +f 689/689/1149 181/181/573 184/184/1143 +f 711/711/1150 689/689/1149 184/184/1143 +f 692/692/573 178/178/573 712/712/573 +f 692/692/573 712/712/573 694/694/573 +f 710/710/1146 637/637/1151 170/170/1147 +f 184/184/1143 713/713/1152 711/711/1150 +f 180/180/573 687/687/573 178/178/573 +f 178/178/573 687/687/573 685/685/573 +f 178/178/573 685/685/573 708/708/573 +f 178/178/573 708/708/573 712/712/573 +f 713/713/1152 184/184/1143 699/699/1141 +f 709/709/1153 714/714/1154 41/41/1155 +f 41/41/1156 715/715/1157 706/706/1158 +f 706/706/1158 715/715/1157 697/697/1159 +f 716/716/1160 699/699/1161 697/697/1162 +f 716/716/1160 697/697/1162 715/715/1163 +f 699/699/1164 716/716/1165 717/717/1166 +f 699/699/1164 717/717/1166 713/713/1167 +f 713/713/1167 717/717/1166 711/711/1168 +f 711/711/1169 718/718/1169 684/684/1169 +f 719/719/1170 708/708/1171 718/718/1172 +f 718/718/1172 708/708/1171 684/684/1173 +f 708/708/1174 719/719/1175 29/29/1176 +f 708/708/1174 29/29/1176 712/712/1177 +f 29/29/1178 694/694/1178 712/712/1178 +f 694/694/1179 29/29/1179 32/32/1179 +f 694/694/1180 32/32/1180 707/707/1180 +f 707/707/1181 32/32/1181 24/24/1181 +f 707/707/1182 24/24/1182 710/710/1182 +f 710/710/1183 24/24/1184 23/23/1012 +f 710/710/1183 23/23/1012 637/637/1014 +f 672/672/573 670/670/1185 165/165/1186 +f 153/153/573 155/155/573 664/664/573 +f 664/664/573 662/662/1187 153/153/573 +f 664/664/573 155/155/573 665/665/573 +f 665/665/573 155/155/573 157/157/573 +f 153/153/573 662/662/1187 151/151/1188 +f 672/672/573 165/165/1186 167/167/573 +f 151/151/1188 662/662/1187 720/720/1189 +f 720/720/1189 662/662/1187 665/665/1190 +f 165/165/1186 670/670/1185 163/163/1191 +f 163/163/1191 670/670/1185 162/162/1192 +f 657/657/573 656/656/573 721/721/573 +f 668/668/573 672/672/573 167/167/573 +f 668/668/573 167/167/573 722/722/573 +f 722/722/573 168/168/573 723/723/573 +f 160/160/1193 660/660/1194 159/159/1195 +f 159/159/573 657/657/573 157/157/1196 +f 151/151/1188 720/720/1189 724/724/1197 +f 151/151/1188 724/724/1197 149/149/573 +f 149/149/573 724/724/1197 147/147/573 +f 722/722/573 167/167/573 168/168/573 +f 660/660/1194 160/160/1193 162/162/1192 +f 656/656/1198 660/660/1194 162/162/1192 +f 656/656/1198 162/162/1192 725/725/1199 +f 665/665/1200 157/157/1200 726/726/1200 +f 724/724/1197 638/638/573 147/147/573 +f 162/162/1192 727/727/1201 725/725/1199 +f 157/157/1196 728/728/1202 726/726/1203 +f 157/157/1196 657/657/573 721/721/573 +f 721/721/573 728/728/1202 157/157/1196 +f 727/727/1201 162/162/1192 670/670/1185 +f 727/727/1201 670/670/1185 668/668/573 +f 175/175/1204 693/693/1205 177/177/1206 +f 186/186/1207 700/700/1208 701/701/5 +f 686/686/5 688/688/5 179/179/5 +f 700/700/1208 186/186/1207 185/185/1209 +f 700/700/1208 185/185/1209 183/183/1210 +f 175/175/1204 690/690/1211 693/693/1205 +f 186/186/1207 701/701/5 696/696/5 +f 186/186/1207 696/696/5 190/190/5 +f 179/179/5 688/688/5 182/182/5 +f 177/177/1206 686/686/5 179/179/5 +f 726/726/1212 177/177/1206 693/693/1205 +f 726/726/1212 693/693/1205 695/695/1213 +f 726/726/1212 729/729/1214 177/177/1206 +f 730/730/1215 171/171/1216 637/637/1217 +f 696/696/5 731/731/5 190/190/5 +f 182/182/5 688/688/5 683/683/5 +f 182/182/5 683/683/5 183/183/1210 +f 683/683/5 732/732/1218 183/183/1210 +f 183/183/1210 732/732/1218 725/725/1219 +f 686/686/5 177/177/1206 729/729/1214 +f 686/686/5 729/729/1214 683/683/5 +f 695/695/1220 690/690/1211 720/720/1221 +f 720/720/1221 690/690/1211 175/175/1204 +f 720/720/1221 175/175/1204 173/173/1222 +f 720/720/1221 173/173/1222 730/730/1215 +f 730/730/1215 173/173/1222 171/171/1216 +f 698/698/1223 700/700/1208 183/183/1210 +f 698/698/1223 183/183/1210 725/725/1219 +f 190/190/5 731/731/5 733/733/5 +f 190/190/5 733/733/5 192/192/5 +f 733/733/5 734/734/5 192/192/5 +f 723/723/1224 734/734/1225 733/733/1226 +f 723/723/1227 733/733/1227 722/722/1227 +f 722/722/1228 733/733/1228 731/731/1228 +f 722/722/1229 731/731/1230 696/696/1231 +f 722/722/1229 696/696/1231 668/668/1232 +f 668/668/1232 696/696/1231 698/698/1233 +f 668/668/1232 698/698/1233 727/727/1234 +f 727/727/1201 698/698/1235 725/725/1199 +f 725/725/1219 732/732/1218 656/656/1236 +f 656/656/1237 732/732/1238 683/683/1239 +f 656/656/1237 683/683/1239 721/721/1240 +f 721/721/1241 683/683/1241 729/729/1241 +f 721/721/1242 729/729/1242 728/728/1242 +f 728/728/1243 729/729/1243 726/726/1243 +f 726/726/1244 695/695/1245 665/665/1246 +f 665/665/1246 695/695/1245 720/720/1247 +f 720/720/1248 730/730/1248 724/724/1248 +f 724/724/1249 730/730/1250 637/637/1251 +f 724/724/1249 637/637/1251 638/638/1252 +f 735/735/573 736/736/1253 94/94/1254 +f 83/83/573 85/85/1255 737/737/573 +f 737/737/573 738/738/573 83/83/573 +f 737/737/573 85/85/1255 739/739/573 +f 83/83/573 738/738/573 81/81/573 +f 81/81/573 738/738/573 79/79/573 +f 735/735/573 94/94/1254 96/96/573 +f 79/79/1256 738/738/1256 740/740/1256 +f 740/740/1257 738/738/1257 739/739/1257 +f 94/94/1254 736/736/1253 92/92/1258 +f 92/92/1258 736/736/1253 90/90/1259 +f 741/741/573 735/735/573 742/742/573 +f 742/742/573 735/735/573 96/96/573 +f 742/742/573 97/97/573 743/743/573 +f 90/90/1259 744/744/573 87/87/573 +f 79/79/1260 740/740/1261 745/745/1262 +f 79/79/1260 745/745/1262 77/77/1263 +f 87/87/573 744/744/573 746/746/573 +f 742/742/573 96/96/573 97/97/573 +f 744/744/573 90/90/1259 747/747/573 +f 747/747/573 90/90/1259 748/748/573 +f 739/739/573 85/85/1255 749/749/1264 +f 745/745/1262 633/633/1265 77/77/1263 +f 736/736/1253 748/748/573 90/90/1259 +f 85/85/1266 750/750/1267 751/751/1268 +f 87/87/573 746/746/573 85/85/573 +f 85/85/573 746/746/573 750/750/573 +f 85/85/1255 751/751/1269 749/749/1264 +f 58/58/22 752/752/1270 60/60/1271 +f 60/60/1271 752/752/1270 753/753/1272 +f 60/60/1271 753/753/1272 61/61/1273 +f 754/754/5 755/755/5 70/70/5 +f 63/63/5 756/756/5 65/65/5 +f 754/754/5 70/70/5 68/68/5 +f 58/58/22 757/757/1274 752/752/1270 +f 70/70/5 755/755/5 72/72/1275 +f 65/65/5 756/756/5 758/758/5 +f 61/61/1273 759/759/1276 63/63/5 +f 63/63/5 759/759/1276 756/756/5 +f 760/760/1277 61/61/1273 753/753/1272 +f 761/761/1278 54/54/1279 633/633/1280 +f 65/65/5 758/758/5 68/68/5 +f 758/758/5 762/762/5 763/763/5 +f 758/758/5 763/763/5 68/68/5 +f 760/760/1277 751/751/1281 61/61/1273 +f 61/61/1273 751/751/1281 759/759/1276 +f 72/72/1275 755/755/5 764/764/1282 +f 764/764/1282 755/755/5 765/765/5 +f 757/757/1274 58/58/22 740/740/1283 +f 740/740/1283 58/58/22 56/56/21 +f 740/740/1283 56/56/21 761/761/1278 +f 761/761/1278 56/56/21 54/54/1279 +f 754/754/5 68/68/5 763/763/5 +f 72/72/1275 764/764/1282 74/74/1284 +f 74/74/1284 764/764/1282 766/766/1285 +f 74/74/1284 766/766/1285 75/75/1286 +f 743/743/1287 766/766/1288 742/742/1289 +f 742/742/1289 766/766/1288 764/764/1290 +f 757/757/1291 740/740/1292 739/739/1293 +f 757/757/1291 739/739/1293 753/753/1294 +f 753/753/1294 739/739/1293 749/749/1295 +f 753/753/1296 749/749/1296 760/760/1296 +f 760/760/1297 749/749/1297 751/751/1297 +f 751/751/1268 750/750/1267 759/759/1298 +f 759/759/1299 750/750/1300 762/762/1301 +f 762/762/1302 750/750/1302 747/747/1302 +f 762/762/1303 747/747/1303 763/763/1303 +f 763/763/1304 747/747/1304 748/748/1304 +f 763/763/1305 748/748/1306 736/736/1307 +f 763/763/1305 736/736/1307 754/754/1308 +f 754/754/1309 736/736/1310 741/741/1311 +f 754/754/1309 741/741/1311 765/765/1312 +f 765/765/1312 741/741/1311 742/742/1313 +f 765/765/1312 742/742/1313 764/764/1314 +f 740/740/1315 761/761/1316 745/745/1317 +f 745/745/1317 761/761/1316 633/633/1318 +f 128/128/573 649/649/1319 647/647/573 +f 128/128/573 130/130/1320 649/649/1319 +f 128/128/573 647/647/573 125/125/1321 +f 125/125/1321 647/647/573 645/645/573 +f 142/142/573 651/651/573 140/140/573 +f 651/651/573 142/142/573 143/143/573 +f 125/125/1321 645/645/573 767/767/573 +f 140/140/573 654/654/573 138/138/573 +f 138/138/573 654/654/573 137/137/573 +f 652/652/573 651/651/573 143/143/573 +f 652/652/573 143/143/573 768/768/573 +f 768/768/573 145/145/573 769/769/573 +f 135/135/573 643/643/573 132/132/573 +f 125/125/1321 767/767/573 770/770/1322 +f 125/125/1321 770/770/1322 124/124/1323 +f 124/124/1323 770/770/1322 122/122/1324 +f 640/640/573 643/643/573 771/771/573 +f 132/132/573 643/643/573 642/642/573 +f 768/768/573 143/143/573 145/145/573 +f 643/643/573 135/135/573 137/137/573 +f 771/771/573 643/643/573 137/137/573 +f 649/649/1319 130/130/1320 772/772/1325 +f 770/770/1322 636/636/573 122/122/1324 +f 137/137/573 773/773/573 771/771/573 +f 640/640/1326 774/774/1326 130/130/1326 +f 130/130/1320 775/775/1327 772/772/1325 +f 132/132/573 642/642/573 640/640/573 +f 132/132/573 640/640/573 130/130/573 +f 774/774/1328 775/775/1327 130/130/1320 +f 773/773/573 137/137/573 654/654/573 +f 773/773/573 654/654/573 652/652/573 +f 104/104/1329 776/776/1330 106/106/1331 +f 106/106/1331 776/776/1330 107/107/1332 +f 776/776/1330 104/104/1329 777/777/5 +f 778/778/1333 115/115/1334 114/114/1335 +f 778/778/1333 114/114/1335 779/779/1336 +f 779/779/1336 114/114/1335 112/112/1337 +f 778/778/1333 780/780/5 115/115/1334 +f 115/115/1334 780/780/5 118/118/5 +f 109/109/1338 781/781/1339 782/782/1340 +f 109/109/1338 782/782/1340 111/111/1341 +f 111/111/1341 782/782/1340 783/783/1342 +f 107/107/1332 781/781/1339 109/109/1338 +f 772/772/1343 107/107/1332 776/776/1330 +f 772/772/1344 776/776/1344 784/784/1344 +f 772/772/1343 775/775/1345 107/107/1332 +f 779/779/5 785/785/5 118/118/5 +f 111/111/1341 783/783/1342 112/112/1337 +f 112/112/1337 786/786/5 787/787/5 +f 112/112/1337 783/783/1342 786/786/5 +f 107/107/1332 775/775/1345 774/774/1346 +f 118/118/5 780/780/5 779/779/5 +f 781/781/1339 107/107/1332 774/774/1346 +f 781/781/1339 774/774/1346 788/788/1347 +f 784/784/5 777/777/5 104/104/1329 +f 784/784/5 104/104/1329 789/789/5 +f 789/789/5 104/104/1329 102/102/5 +f 789/789/5 102/102/5 635/635/5 +f 635/635/5 102/102/5 100/100/5 +f 787/787/5 779/779/1336 112/112/1337 +f 118/118/5 785/785/5 121/121/5 +f 785/785/5 790/790/5 121/121/5 +f 769/769/1348 790/790/1349 785/785/1350 +f 769/769/1348 785/785/1350 768/768/1351 +f 768/768/1352 785/785/1353 779/779/1354 +f 768/768/1352 779/779/1354 652/652/1355 +f 652/652/1355 779/779/1354 787/787/1356 +f 652/652/1355 787/787/1356 773/773/1357 +f 773/773/1358 787/787/1358 786/786/1358 +f 773/773/1359 786/786/1359 771/771/1359 +f 771/771/1360 786/786/1360 783/783/1360 +f 771/771/1361 783/783/1361 788/788/1361 +f 771/771/1362 788/788/1363 640/640/1364 +f 640/640/1364 788/788/1363 774/774/1365 +f 772/772/1366 784/784/1367 649/649/1368 +f 649/649/1368 784/784/1367 645/645/1369 +f 645/645/1369 784/784/1367 767/767/1370 +f 767/767/1370 784/784/1367 789/789/1371 +f 767/767/1372 789/789/1372 770/770/1372 +f 770/770/1373 789/789/1373 635/635/1373 +f 770/770/1374 635/635/1001 636/636/1007 +f 791/791/1375 741/741/1375 792/792/1375 +f 792/792/1376 741/741/1311 736/736/1310 +f 792/792/1377 736/736/1377 793/793/1377 +f 793/793/1378 736/736/1378 735/735/1378 +f 793/793/1379 735/735/1379 791/791/1379 +f 791/791/1380 735/735/1380 741/741/1380 +f 105/105/1381 794/794/1382 795/795/573 +f 105/105/1381 106/106/1383 794/794/1382 +f 794/794/1382 106/106/1383 108/108/1384 +f 105/105/1381 795/795/573 103/103/1385 +f 103/103/1385 795/795/573 796/796/1386 +f 796/796/1386 797/797/1387 103/103/1385 +f 117/117/573 798/798/573 116/116/573 +f 798/798/573 117/117/573 119/119/573 +f 116/116/1388 799/799/1389 114/114/1390 +f 114/114/1390 799/799/1389 113/113/1391 +f 800/800/573 798/798/573 119/119/573 +f 800/800/573 119/119/573 801/801/573 +f 802/802/573 120/120/573 803/803/573 +f 801/801/573 119/119/573 802/802/573 +f 111/111/1392 804/804/1393 110/110/1394 +f 110/110/1394 804/804/1393 805/805/573 +f 110/110/1394 805/805/573 108/108/1384 +f 103/103/1385 797/797/1387 806/806/1395 +f 103/103/1385 806/806/1395 101/101/573 +f 101/101/573 806/806/1395 99/99/1396 +f 802/802/573 119/119/573 120/120/573 +f 804/804/1393 111/111/1392 807/807/1397 +f 807/807/1397 111/111/1392 113/113/1391 +f 807/807/1397 113/113/1391 808/808/1398 +f 806/806/1395 634/634/1265 99/99/1396 +f 113/113/1391 809/809/1399 808/808/1398 +f 108/108/1384 805/805/573 810/810/573 +f 108/108/1384 810/810/573 794/794/1382 +f 809/809/1399 113/113/1391 799/799/1389 +f 809/809/1399 799/799/1389 800/800/573 +f 84/84/5 811/811/5 86/86/5 +f 812/812/1400 811/811/5 84/84/5 +f 793/793/1401 93/93/1402 92/92/1403 +f 793/793/1401 92/92/1403 792/792/1404 +f 792/792/1404 92/92/1403 91/91/1405 +f 82/82/1406 812/812/1400 84/84/5 +f 793/793/1401 791/791/5 93/93/1402 +f 93/93/1402 791/791/5 95/95/5 +f 88/88/5 813/813/5 814/814/5 +f 88/88/5 814/814/5 89/89/5 +f 89/89/5 814/814/5 815/815/5 +f 86/86/5 813/813/5 88/88/5 +f 811/811/5 816/816/5 86/86/5 +f 817/817/1407 78/78/1408 634/634/1409 +f 792/792/5 818/818/5 95/95/5 +f 89/89/5 815/815/5 91/91/1405 +f 91/91/1405 808/808/1410 819/819/1411 +f 815/815/5 820/820/1412 91/91/1405 +f 91/91/1405 820/820/1412 808/808/1410 +f 95/95/5 791/791/5 792/792/5 +f 813/813/5 86/86/5 816/816/5 +f 813/813/5 816/816/5 820/820/5 +f 821/821/1413 812/812/1400 797/797/1414 +f 797/797/1414 812/812/1400 82/82/1406 +f 797/797/1414 82/82/1406 80/80/1415 +f 797/797/1414 80/80/1415 817/817/1407 +f 817/817/1407 80/80/1415 78/78/1408 +f 819/819/1411 792/792/1404 91/91/1405 +f 95/95/5 818/818/5 98/98/5 +f 818/818/5 822/822/5 98/98/5 +f 803/803/1416 823/823/1417 822/822/1418 +f 803/803/1416 822/822/1418 802/802/1419 +f 802/802/1420 822/822/1420 818/818/1420 +f 802/802/1421 818/818/1421 801/801/1421 +f 801/801/1422 818/818/1423 792/792/1424 +f 801/801/1422 792/792/1424 800/800/1425 +f 800/800/1425 792/792/1424 819/819/1426 +f 800/800/1425 819/819/1426 809/809/1427 +f 809/809/1428 819/819/1428 808/808/1428 +f 808/808/1429 820/820/1430 807/807/1431 +f 807/807/1431 820/820/1430 805/805/1432 +f 805/805/1433 820/820/1433 816/816/1433 +f 805/805/1434 816/816/1434 810/810/1434 +f 810/810/1435 816/816/1435 811/811/1435 +f 810/810/1436 811/811/1436 794/794/1436 +f 794/794/1437 811/811/1438 821/821/1439 +f 794/794/1440 821/821/1441 796/796/1442 +f 796/796/1442 821/821/1441 797/797/1443 +f 797/797/1444 817/817/1444 806/806/1444 +f 806/806/1445 817/817/1445 634/634/1445 +f 755/755/1446 824/824/1447 765/765/1448 +f 765/765/1448 824/824/1447 825/825/1449 +f 765/765/1450 825/825/1451 826/826/1452 +f 765/765/1312 826/826/1453 754/754/1309 +f 754/754/1454 826/826/1454 827/827/1454 +f 754/754/1455 827/827/1455 755/755/1455 +f 755/755/1456 827/827/1456 824/824/1456 +f 71/71/573 824/824/573 827/827/573 +f 824/824/573 828/828/1457 825/825/573 +f 59/59/1458 60/60/1459 829/829/1460 +f 829/829/1460 60/60/1459 62/62/1461 +f 59/59/1458 829/829/1460 830/830/573 +f 59/59/1458 830/830/573 57/57/1462 +f 57/57/1462 830/830/573 831/831/1463 +f 831/831/1463 832/832/1464 57/57/1462 +f 824/824/573 71/71/573 73/73/1465 +f 71/71/573 827/827/573 69/69/573 +f 69/69/573 827/827/573 826/826/573 +f 69/69/573 826/826/573 67/67/573 +f 828/828/1457 824/824/573 73/73/1465 +f 828/828/1457 76/76/1466 833/833/573 +f 57/57/1462 832/832/1464 834/834/1467 +f 57/57/1462 834/834/1467 55/55/573 +f 55/55/573 834/834/1467 53/53/1468 +f 835/835/1469 836/836/1470 837/837/1471 +f 836/836/1470 838/838/573 66/66/573 +f 66/66/573 838/838/573 64/64/573 +f 73/73/1465 74/74/1472 828/828/1457 +f 828/828/1457 74/74/1472 76/76/1466 +f 836/836/1470 66/66/573 67/67/1473 +f 837/837/1471 836/836/1470 67/67/1473 +f 639/639/1474 53/53/1468 834/834/1467 +f 67/67/1473 839/839/1475 837/837/1471 +f 835/835/1476 840/840/1477 62/62/1478 +f 62/62/1479 841/841/1480 829/829/1481 +f 64/64/573 838/838/573 835/835/1476 +f 64/64/573 835/835/1476 62/62/1478 +f 62/62/1478 840/840/1477 841/841/1482 +f 839/839/1483 67/67/1484 826/826/1485 +f 154/154/5 663/663/5 156/156/5 +f 663/663/5 152/152/1486 661/661/5 +f 671/671/1487 164/164/1488 163/163/1489 +f 671/671/1487 163/163/1489 669/669/1490 +f 669/669/1490 163/163/1489 161/161/1491 +f 152/152/1486 663/663/5 154/154/5 +f 671/671/1487 667/667/5 164/164/1488 +f 164/164/1488 667/667/5 166/166/5 +f 158/158/1492 658/658/1493 659/659/1494 +f 158/158/1492 659/659/1494 160/160/1495 +f 156/156/1496 658/658/1493 158/158/1492 +f 841/841/1497 156/156/1497 666/666/1497 +f 666/666/5 156/156/5 663/663/5 +f 156/156/1496 841/841/1498 840/840/1499 +f 842/842/1500 148/148/1501 639/639/1502 +f 669/669/5 843/843/5 166/166/5 +f 160/160/1495 659/659/1494 161/161/1503 +f 161/161/1503 659/659/1494 655/655/1504 +f 161/161/1503 837/837/1505 839/839/1506 +f 655/655/1504 837/837/1505 161/161/1503 +f 166/166/5 667/667/5 669/669/5 +f 658/658/1493 156/156/1496 840/840/1499 +f 658/658/1493 840/840/1499 655/655/1507 +f 666/666/1508 661/661/5 152/152/1486 +f 666/666/1508 152/152/1486 832/832/1509 +f 832/832/1509 152/152/1486 150/150/1510 +f 832/832/1509 150/150/1510 842/842/1500 +f 842/842/1500 150/150/1510 148/148/1501 +f 669/669/1490 161/161/1491 839/839/1511 +f 166/166/5 843/843/5 169/169/5 +f 843/843/5 844/844/5 169/169/5 +f 833/833/1512 844/844/1513 843/843/1514 +f 833/833/1515 843/843/1515 828/828/1515 +f 828/828/1516 843/843/1517 669/669/1518 +f 828/828/1516 669/669/1518 825/825/1451 +f 825/825/1451 669/669/1518 826/826/1452 +f 826/826/1485 669/669/1519 839/839/1483 +f 837/837/1520 655/655/1520 835/835/1520 +f 835/835/1521 655/655/1521 840/840/1521 +f 841/841/1480 666/666/1522 829/829/1481 +f 829/829/1481 666/666/1522 831/831/1523 +f 831/831/1523 666/666/1522 832/832/1524 +f 832/832/1525 842/842/1525 834/834/1525 +f 834/834/1526 842/842/1526 639/639/1526 +f 777/777/1527 796/796/1527 795/795/1527 +f 777/777/1528 795/795/1528 776/776/1528 +f 776/776/1529 795/795/1529 794/794/1529 +f 776/776/1530 794/794/1530 784/784/1530 +f 784/784/1531 794/794/1531 796/796/1531 +f 784/784/1532 796/796/1532 777/777/1532 +f 812/812/1533 738/738/1533 737/737/1533 +f 812/812/1534 737/737/1534 811/811/1534 +f 811/811/1535 737/737/1535 739/739/1535 +f 811/811/1438 739/739/1536 821/821/1439 +f 821/821/1537 739/739/1537 812/812/1537 +f 812/812/1538 739/739/1538 738/738/1538 +f 757/757/1539 831/831/1539 830/830/1539 +f 757/757/1540 830/830/1540 752/752/1540 +f 752/752/1541 830/830/1541 829/829/1541 +f 752/752/1542 829/829/1542 753/753/1542 +f 753/753/1294 829/829/1481 757/757/1291 +f 757/757/1291 829/829/1481 831/831/1523 +f 788/788/1543 807/807/1431 805/805/1432 +f 788/788/1544 805/805/1544 781/781/1544 +f 781/781/1545 805/805/1546 782/782/1547 +f 782/782/1547 805/805/1546 804/804/1548 +f 782/782/1549 804/804/1549 783/783/1549 +f 783/783/1550 804/804/1550 807/807/1550 +f 783/783/1551 807/807/1551 788/788/1551 +f 820/820/1552 750/750/1552 813/813/1552 +f 813/813/1553 750/750/1553 746/746/1553 +f 813/813/1554 746/746/1554 814/814/1554 +f 814/814/1555 746/746/1555 744/744/1555 +f 814/814/1556 744/744/1556 815/815/1556 +f 815/815/1557 744/744/1557 747/747/1557 +f 815/815/1558 747/747/1558 820/820/1558 +f 820/820/1559 747/747/1559 750/750/1559 +f 762/762/1301 835/835/1560 759/759/1299 +f 759/759/1561 835/835/1562 756/756/1563 +f 756/756/1563 835/835/1562 838/838/1564 +f 756/756/1565 838/838/1566 758/758/1567 +f 758/758/1567 838/838/1566 836/836/1568 +f 758/758/1569 836/836/1569 762/762/1569 +f 762/762/1570 836/836/1570 835/835/1570 +f 780/780/1571 798/798/1572 779/779/1573 +f 779/779/1573 798/798/1572 800/800/1574 +f 779/779/1575 800/800/1575 799/799/1575 +f 779/779/1576 799/799/1576 778/778/1576 +f 778/778/1577 799/799/1577 116/116/1577 +f 778/778/1578 116/116/1578 780/780/1578 +f 780/780/1579 116/116/1579 798/798/1579 +f 845/845/1580 8/8/1581 221/221/1582 +f 221/221/1582 8/8/1581 50/50/1583 +f 705/705/1584 5/5/1585 7/7/1586 +f 705/705/1584 7/7/1586 846/846/1587 +f 846/846/1587 7/7/1586 8/8/1588 +f 846/846/1589 8/8/1590 845/845/1591 +f 847/847/1592 848/848/1592 845/845/1592 +f 845/845/1593 848/848/1593 849/849/1593 +f 845/845/1591 849/849/1594 846/846/1589 +f 846/846/1589 849/849/1594 850/850/1595 +f 846/846/1596 850/850/1597 851/851/1598 +f 851/851/1598 850/850/1597 852/852/1599 +f 851/851/1600 852/852/1600 853/853/1600 +f 851/851/1601 853/853/1601 847/847/1601 +f 847/847/1602 853/853/1602 848/848/1602 +f 849/849/1603 848/848/1604 850/850/1605 +f 852/852/1606 850/850/1605 853/853/1607 +f 850/850/1605 848/848/1604 853/853/1607 +f 50/50/1608 844/844/1513 833/833/1512 +f 803/803/1416 217/217/1609 823/823/1417 +f 823/823/1417 217/217/1609 50/50/1608 +f 145/145/1610 146/146/1611 769/769/1612 +f 769/769/1612 146/146/1611 217/217/1613 +f 769/769/1614 217/217/1614 790/790/1614 +f 790/790/1615 217/217/1616 803/803/1617 +f 790/790/1615 803/803/1617 121/121/1618 +f 121/121/1618 803/803/1617 120/120/1619 +f 97/97/1620 98/98/1621 743/743/1622 +f 743/743/1622 98/98/1621 822/822/1623 +f 743/743/1287 822/822/1418 823/823/1417 +f 743/743/1287 823/823/1417 50/50/1608 +f 743/743/1287 50/50/1608 766/766/1288 +f 766/766/1288 50/50/1608 833/833/1512 +f 766/766/1624 833/833/1625 75/75/1626 +f 75/75/1626 833/833/1625 76/76/1627 +f 168/168/1628 169/169/1629 723/723/1630 +f 723/723/1630 169/169/1629 844/844/1631 +f 723/723/1224 844/844/1513 50/50/1608 +f 723/723/1224 50/50/1608 734/734/1225 +f 734/734/1225 50/50/1608 709/709/1153 +f 734/734/1632 709/709/1633 192/192/1634 +f 192/192/1634 709/709/1633 191/191/1635 +f 51/51/1636 704/704/1637 49/49/1638 +f 49/49/1638 704/704/1637 714/714/1639 +f 49/49/1640 714/714/1154 50/50/1608 +f 50/50/1608 714/714/1154 709/709/1153 +f 846/846/1641 851/851/1642 705/705/1643 +f 17/17/1644 39/39/1645 13/13/1646 +f 13/13/1647 39/39/1647 11/11/1647 +f 17/17/1644 18/18/1648 39/39/1645 +f 52/52/1649 459/459/1650 4/4/1651 +f 4/4/1651 459/459/1650 3/3/1652 +f 854/854/1653 855/855/1654 856/856/1655 +f 857/857/1656 858/858/1656 859/859/1656 +f 859/859/1657 855/855/1654 854/854/1653 +f 860/860/1658 861/861/1659 862/862/1660 +f 860/860/1661 863/863/1661 861/861/1661 +f 861/861/1662 863/863/1662 864/864/1662 +f 861/861/1663 864/864/1663 862/862/1663 +f 862/862/1664 864/864/1665 865/865/1666 +f 862/862/1664 865/865/1666 866/866/1667 +f 866/866/1668 865/865/1669 863/863/1670 +f 866/866/1668 863/863/1670 860/860/1671 +f 863/863/1672 867/867/1673 864/864/1674 +f 867/867/1675 868/868/1676 864/864/1677 +f 864/864/1678 868/868/1678 865/865/1678 +f 863/863/1672 869/869/1679 867/867/1673 +f 863/863/1680 865/865/1680 869/869/1680 +f 869/869/1681 858/858/1682 857/857/1683 +f 869/869/1681 857/857/1683 867/867/1684 +f 857/857/1685 854/854/1685 867/867/1685 +f 867/867/1675 854/854/1686 868/868/1676 +f 868/868/1676 854/854/1686 856/856/1687 +f 856/856/1688 855/855/1688 868/868/1688 +f 868/868/1689 855/855/1689 865/865/1689 +f 865/865/1690 855/855/1690 859/859/1690 +f 865/865/1691 859/859/1691 869/869/1691 +f 869/869/1692 859/859/1692 858/858/1692 +f 859/859/1693 854/854/1693 870/870/1693 +f 857/857/1694 859/859/1694 870/870/1694 +f 854/854/1695 857/857/1695 870/870/1695 +f 866/866/1696 860/860/1658 862/862/1660 +f 871/871/1697 872/872/1697 873/873/1697 +f 873/873/1698 874/874/1698 875/875/1698 +f 876/876/1699 877/877/1700 878/878/1701 +f 876/876/1702 879/879/1703 880/880/1704 +f 876/876/1702 880/880/1704 877/877/1705 +f 877/877/1706 880/880/1707 881/881/1708 +f 877/877/1706 881/881/1708 878/878/1709 +f 881/881/1710 882/882/1710 878/878/1710 +f 878/878/1711 882/882/1711 883/883/1711 +f 883/883/1712 882/882/1712 879/879/1712 +f 883/883/1713 879/879/1713 876/876/1713 +f 884/884/1714 882/882/1715 881/881/1716 +f 881/881/1716 880/880/1717 884/884/1714 +f 879/879/1718 885/885/1719 880/880/1720 +f 882/882/1721 886/886/1722 879/879/1718 +f 879/879/1718 886/886/1722 885/885/1719 +f 873/873/1723 872/872/1723 885/885/1723 +f 885/885/1724 872/872/1724 880/880/1724 +f 880/880/1725 872/872/1726 871/871/1727 +f 880/880/1725 871/871/1727 884/884/1728 +f 871/871/1729 875/875/1729 884/884/1729 +f 884/884/1730 875/875/1730 882/882/1730 +f 882/882/1731 875/875/1732 886/886/1733 +f 875/875/1732 874/874/1734 886/886/1733 +f 886/886/1735 874/874/1736 885/885/1737 +f 885/885/1737 874/874/1736 873/873/1738 +f 875/875/1739 871/871/1739 887/887/1739 +f 873/873/1740 875/875/1740 887/887/1740 +f 871/871/1741 873/873/1741 887/887/1741 +f 883/883/1742 876/876/1699 878/878/1701 +f 888/888/1743 889/889/1743 890/890/1743 +f 891/891/1744 892/892/1744 888/888/1744 +f 893/893/1745 894/894/1745 895/895/1745 +f 896/896/1746 897/897/1747 894/894/1748 +f 894/894/1748 897/897/1747 895/895/1749 +f 895/895/1750 897/897/1751 893/893/1752 +f 897/897/1751 898/898/1753 893/893/1752 +f 898/898/1754 899/899/1755 893/893/1756 +f 893/893/1756 899/899/1755 894/894/1757 +f 894/894/1757 899/899/1755 896/896/1758 +f 897/897/1759 900/900/1759 898/898/1759 +f 898/898/1760 901/901/1761 899/899/1762 +f 899/899/1762 901/901/1761 896/896/1763 +f 897/897/1764 902/902/1764 900/900/1764 +f 896/896/1765 902/902/1765 897/897/1765 +f 896/896/1766 890/890/1767 902/902/1768 +f 890/890/1767 889/889/1769 902/902/1768 +f 902/902/1770 889/889/1771 900/900/1772 +f 889/889/1771 888/888/1773 900/900/1772 +f 888/888/1774 892/892/1775 900/900/1776 +f 900/900/1776 892/892/1775 898/898/1777 +f 898/898/1778 892/892/1779 891/891/1780 +f 898/898/1778 891/891/1780 901/901/1781 +f 891/891/1782 890/890/1783 901/901/1784 +f 901/901/1784 890/890/1783 896/896/1785 +f 891/891/1786 888/888/1786 903/903/1786 +f 890/890/1787 891/891/1787 903/903/1787 +f 888/888/1788 890/890/1788 903/903/1788 +f 904/904/1789 905/905/1789 906/906/1789 +f 907/907/1790 906/906/1790 908/908/1790 +f 909/909/1791 910/910/1791 911/911/1791 +f 911/911/1792 912/912/1792 913/913/1792 +f 911/911/1793 913/913/1793 909/909/1793 +f 909/909/1794 913/913/1794 914/914/1794 +f 909/909/1795 914/914/1795 910/910/1795 +f 910/910/1796 914/914/1796 912/912/1796 +f 910/910/1797 912/912/1797 911/911/1797 +f 912/912/1798 915/915/1799 916/916/1800 +f 914/914/1801 915/915/1799 912/912/1798 +f 913/913/1802 917/917/1803 914/914/1801 +f 913/913/1802 918/918/1804 917/917/1803 +f 912/912/1805 916/916/1806 918/918/1807 +f 912/912/1805 918/918/1807 913/913/1808 +f 914/914/1801 917/917/1803 915/915/1799 +f 916/916/1809 908/908/1810 918/918/1811 +f 908/908/1810 906/906/1812 918/918/1811 +f 918/918/1813 906/906/1813 905/905/1813 +f 918/918/1814 905/905/1814 917/917/1814 +f 917/917/1815 905/905/1815 904/904/1815 +f 917/917/1816 904/904/1816 915/915/1816 +f 904/904/1817 907/907/1817 915/915/1817 +f 915/915/1818 907/907/1818 916/916/1818 +f 916/916/1819 907/907/1819 908/908/1819 +f 907/907/1820 904/904/1820 919/919/1820 +f 906/906/1821 907/907/1821 919/919/1821 +f 904/904/1822 906/906/1822 919/919/1822 +f 920/920/1823 921/921/1823 922/922/1823 +f 923/923/1824 924/924/1824 920/920/1824 +f 925/925/1825 926/926/1825 927/927/1825 +f 926/926/1826 928/928/1826 927/927/1826 +f 927/927/1827 928/928/1827 929/929/1827 +f 927/927/1828 929/929/1828 925/925/1828 +f 929/929/1829 930/930/1830 925/925/1831 +f 925/925/1832 930/930/1832 931/931/1832 +f 925/925/1833 931/931/1833 926/926/1833 +f 926/926/1834 931/931/1834 928/928/1834 +f 931/931/1835 932/932/1836 928/928/1837 +f 928/928/1837 932/932/1836 933/933/1838 +f 930/930/1839 934/934/1839 931/931/1839 +f 931/931/1840 934/934/1841 932/932/1842 +f 929/929/1829 933/933/1843 930/930/1830 +f 928/928/1837 933/933/1838 929/929/1844 +f 932/932/1845 924/924/1846 933/933/1847 +f 933/933/1847 924/924/1846 923/923/1848 +f 933/933/1849 923/923/1849 922/922/1849 +f 933/933/1843 922/922/1850 930/930/1830 +f 930/930/1830 922/922/1850 921/921/1851 +f 930/930/1852 921/921/1853 934/934/1854 +f 921/921/1853 920/920/1855 934/934/1854 +f 934/934/1841 920/920/1856 932/932/1842 +f 920/920/1856 924/924/1857 932/932/1842 +f 920/920/1858 922/922/1858 935/935/1858 +f 923/923/1859 920/920/1859 935/935/1859 +f 922/922/1860 923/923/1860 935/935/1860 +f 936/936/1861 937/937/1861 938/938/1861 +f 939/939/1862 940/940/1862 941/941/1862 +f 939/939/1863 942/942/1864 940/940/1865 +f 940/940/1866 942/942/1867 943/943/1868 +f 940/940/1866 943/943/1868 941/941/1869 +f 941/941/1870 943/943/1870 944/944/1870 +f 941/941/1871 944/944/1871 939/939/1871 +f 939/939/1863 944/944/1872 942/942/1864 +f 942/942/1873 945/945/1874 943/943/1875 +f 943/943/1875 945/945/1874 946/946/1876 +f 943/943/1875 946/946/1876 944/944/1877 +f 944/944/1877 946/946/1876 947/947/1878 +f 942/942/1879 948/948/1879 945/945/1879 +f 944/944/1877 948/948/1880 942/942/1881 +f 944/944/1877 947/947/1878 948/948/1880 +f 948/948/1882 938/938/1883 937/937/1884 +f 948/948/1882 937/937/1884 945/945/1885 +f 945/945/1886 937/937/1886 936/936/1886 +f 945/945/1887 936/936/1887 946/946/1887 +f 946/946/1888 936/936/1888 949/949/1888 +f 949/949/1889 950/950/1890 946/946/1891 +f 946/946/1891 950/950/1890 947/947/1892 +f 947/947/1893 950/950/1894 938/938/1895 +f 947/947/1893 938/938/1895 948/948/1896 +f 949/949/1897 936/936/1897 951/951/1897 +f 950/950/1898 949/949/1898 951/951/1898 +f 938/938/1899 950/950/1899 951/951/1899 +f 936/936/1900 938/938/1900 951/951/1900 +f 952/952/1901 953/953/1901 954/954/1901 +f 955/955/1902 956/956/1902 957/957/1902 +f 957/957/1903 958/958/1903 955/955/1903 +f 958/958/1904 959/959/1904 955/955/1904 +f 959/959/1905 960/960/1906 955/955/1907 +f 955/955/1907 960/960/1906 956/956/1908 +f 956/956/1909 960/960/1910 961/961/1911 +f 956/956/1909 961/961/1911 957/957/1912 +f 957/957/1913 961/961/1913 958/958/1913 +f 958/958/1914 962/962/1915 963/963/1916 +f 958/958/1914 963/963/1916 959/959/1917 +f 961/961/1918 962/962/1915 958/958/1914 +f 959/959/1917 964/964/1919 960/960/1920 +f 959/959/1917 963/963/1916 964/964/1919 +f 961/961/1918 965/965/1921 962/962/1915 +f 960/960/1922 965/965/1921 961/961/1918 +f 960/960/1923 964/964/1923 965/965/1923 +f 966/966/1924 967/967/1924 962/962/1924 +f 962/962/1925 967/967/1925 963/963/1925 +f 963/963/1926 967/967/1926 954/954/1926 +f 963/963/1927 954/954/1928 964/964/1929 +f 964/964/1929 954/954/1928 953/953/1930 +f 964/964/1931 953/953/1932 952/952/1933 +f 964/964/1931 952/952/1933 965/965/1934 +f 965/965/1935 952/952/1935 966/966/1935 +f 965/965/1936 966/966/1936 962/962/1936 +f 952/952/1937 954/954/1937 968/968/1937 +f 966/966/1938 952/952/1938 968/968/1938 +f 967/967/1939 966/966/1939 968/968/1939 +f 954/954/1940 967/967/1940 968/968/1940 +f 969/969/1941 970/970/1941 971/971/1941 +f 972/972/1942 973/973/1942 974/974/1942 +f 974/974/1943 975/975/1944 972/972/1945 +f 975/975/1944 976/976/1946 972/972/1945 +f 976/976/1947 977/977/1948 972/972/1949 +f 972/972/1949 977/977/1948 973/973/1950 +f 973/973/1951 977/977/1952 974/974/1953 +f 977/977/1952 975/975/1954 974/974/1953 +f 975/975/1955 978/978/1955 979/979/1955 +f 975/975/1956 979/979/1957 976/976/1958 +f 976/976/1958 979/979/1957 980/980/1959 +f 977/977/1960 978/978/1960 975/975/1960 +f 977/977/1961 981/981/1961 978/978/1961 +f 980/980/1959 981/981/1962 976/976/1958 +f 976/976/1958 981/981/1962 977/977/1963 +f 969/969/1964 982/982/1964 979/979/1964 +f 979/979/1965 982/982/1965 980/980/1965 +f 982/982/1966 971/971/1966 980/980/1966 +f 980/980/1967 971/971/1967 981/981/1967 +f 981/981/1968 971/971/1968 970/970/1968 +f 981/981/1969 970/970/1969 978/978/1969 +f 970/970/1970 969/969/1970 978/978/1970 +f 978/978/1971 969/969/1971 979/979/1971 +f 969/969/1972 971/971/1972 983/983/1972 +f 982/982/1973 969/969/1973 983/983/1973 +f 971/971/1974 982/982/1974 983/983/1974 +f 984/984/1975 985/985/1975 986/986/1975 +f 987/987/1976 988/988/1976 984/984/1976 +f 989/989/1977 990/990/1978 991/991/1979 +f 992/992/1980 993/993/1980 990/990/1980 +f 990/990/1981 993/993/1981 991/991/1981 +f 991/991/1982 993/993/1983 994/994/1984 +f 991/991/1982 994/994/1984 989/989/1985 +f 989/989/1986 994/994/1987 995/995/1988 +f 995/995/1988 994/994/1987 992/992/1989 +f 995/995/1990 992/992/1990 990/990/1990 +f 992/992/1991 996/996/1992 993/993/1993 +f 993/993/1993 996/996/1992 997/997/1994 +f 993/993/1993 998/998/1995 999/999/1996 +f 993/993/1993 999/999/1996 994/994/1997 +f 994/994/1997 1000/1000/1998 992/992/1991 +f 992/992/1991 1000/1000/1998 996/996/1992 +f 994/994/1997 999/999/1996 1000/1000/1998 +f 993/993/1993 997/997/1994 998/998/1995 +f 984/984/1999 997/997/1999 996/996/1999 +f 997/997/2000 984/984/2000 988/988/2000 +f 997/997/2001 988/988/2001 998/998/2001 +f 998/998/2002 988/988/2002 987/987/2002 +f 998/998/2003 987/987/2003 999/999/2003 +f 999/999/2004 987/987/2004 986/986/2004 +f 999/999/2005 986/986/2005 1000/1000/2005 +f 1000/1000/2006 986/986/2006 985/985/2006 +f 1000/1000/2007 985/985/2007 996/996/2007 +f 996/996/2008 985/985/2008 984/984/2008 +f 986/986/2009 987/987/2010 1001/1001/2011 +f 1001/1001/2011 987/987/2010 1002/1002/2012 +f 984/984/2013 986/986/2013 1002/1002/2013 +f 1002/1002/2014 986/986/2014 1001/1001/2014 +f 987/987/2015 984/984/2015 1002/1002/2015 +f 995/995/2016 990/990/1978 989/989/1977 +f 1003/1003/2017 1004/1004/2017 1005/1005/2017 +f 1006/1006/2018 1007/1007/2018 1008/1008/2018 +f 1006/1006/2019 1009/1009/2020 1007/1007/2021 +f 1007/1007/2022 1009/1009/2023 1008/1008/2024 +f 1008/1008/2024 1009/1009/2023 1010/1010/2025 +f 1008/1008/2026 1010/1010/2026 1011/1011/2026 +f 1008/1008/2027 1011/1011/2028 1006/1006/2029 +f 1006/1006/2029 1011/1011/2028 1012/1012/2030 +f 1006/1006/2019 1012/1012/2031 1009/1009/2020 +f 1012/1012/2032 1013/1013/2033 1014/1014/2034 +f 1012/1012/2032 1014/1014/2034 1009/1009/2035 +f 1010/1010/2036 1015/1015/2037 1011/1011/2038 +f 1011/1011/2038 1015/1015/2037 1016/1016/2039 +f 1009/1009/2035 1015/1015/2037 1010/1010/2036 +f 1009/1009/2035 1017/1017/2040 1015/1015/2037 +f 1014/1014/2034 1017/1017/2040 1009/1009/2035 +f 1011/1011/2038 1016/1016/2039 1012/1012/2032 +f 1012/1012/2032 1016/1016/2039 1013/1013/2033 +f 1014/1014/2041 1005/1005/2042 1004/1004/2043 +f 1014/1014/2041 1004/1004/2043 1017/1017/2044 +f 1017/1017/2045 1004/1004/2046 1015/1015/2047 +f 1015/1015/2047 1004/1004/2046 1003/1003/2048 +f 1003/1003/2049 1018/1018/2050 1015/1015/2051 +f 1015/1015/2051 1018/1018/2050 1016/1016/2052 +f 1016/1016/2053 1018/1018/2054 1013/1013/2055 +f 1013/1013/2055 1018/1018/2054 1019/1019/2056 +f 1013/1013/2057 1019/1019/2058 1014/1014/2059 +f 1019/1019/2058 1005/1005/2060 1014/1014/2059 +f 1018/1018/2061 1003/1003/2061 1020/1020/2061 +f 1020/1020/2062 1003/1003/2062 1021/1021/2062 +f 1019/1019/2063 1018/1018/2063 1020/1020/2063 +f 1021/1021/2064 1019/1019/2065 1020/1020/2066 +f 1005/1005/2067 1019/1019/2065 1021/1021/2064 +f 1003/1003/2068 1005/1005/2068 1021/1021/2068 +f 1022/1022/2069 1023/1023/2069 1024/1024/2069 +f 1024/1024/2070 1025/1025/2070 1026/1026/2070 +f 1027/1027/2071 1028/1028/2072 1029/1029/2073 +f 1029/1029/2073 1030/1030/2074 1027/1027/2071 +f 1029/1029/2075 1031/1031/2076 1030/1030/2077 +f 1031/1031/2076 1032/1032/2078 1030/1030/2077 +f 1030/1030/2079 1032/1032/2080 1033/1033/2081 +f 1030/1030/2079 1033/1033/2081 1027/1027/2082 +f 1027/1027/2083 1033/1033/2084 1028/1028/2085 +f 1033/1033/2084 1034/1034/2086 1028/1028/2085 +f 1034/1034/2087 1031/1031/2088 1028/1028/2089 +f 1028/1028/2089 1031/1031/2088 1029/1029/2090 +f 1033/1033/2091 1035/1035/2092 1036/1036/2093 +f 1033/1033/2091 1036/1036/2093 1034/1034/2094 +f 1032/1032/2095 1035/1035/2092 1033/1033/2091 +f 1031/1031/2096 1037/1037/2097 1032/1032/2098 +f 1034/1034/2094 1038/1038/2099 1031/1031/2096 +f 1031/1031/2096 1038/1038/2099 1037/1037/2097 +f 1037/1037/2100 1035/1035/2100 1032/1032/2100 +f 1034/1034/2094 1036/1036/2093 1038/1038/2099 +f 1037/1037/2101 1024/1024/2101 1023/1023/2101 +f 1037/1037/2102 1023/1023/2103 1035/1035/2104 +f 1035/1035/2104 1023/1023/2103 1022/1022/2105 +f 1035/1035/2106 1022/1022/2107 1036/1036/2108 +f 1036/1036/2108 1022/1022/2107 1026/1026/2109 +f 1036/1036/2110 1026/1026/2111 1025/1025/2112 +f 1036/1036/2110 1025/1025/2112 1038/1038/2113 +f 1025/1025/2114 1024/1024/2114 1038/1038/2114 +f 1038/1038/2115 1024/1024/2115 1037/1037/2115 +f 1026/1026/2116 1022/1022/2116 1039/1039/2116 +f 1024/1024/2117 1026/1026/2117 1039/1039/2117 +f 1040/1040/2118 1024/1024/2118 1039/1039/2118 +f 1022/1022/2119 1024/1024/2119 1040/1040/2119 +f 1039/1039/2120 1022/1022/2120 1040/1040/2120 +f 1041/1041/2121 1042/1042/2121 1043/1043/2121 +f 1042/1042/2122 1044/1044/2122 1045/1045/2122 +f 1046/1046/2123 1047/1047/2124 1048/1048/2125 +f 1049/1049/2126 1050/1050/2127 1051/1051/2128 +f 1051/1051/2128 1050/1050/2127 1047/1047/2129 +f 1050/1050/2130 1052/1052/2131 1047/1047/2132 +f 1047/1047/2132 1052/1052/2131 1048/1048/2133 +f 1048/1048/2134 1052/1052/2135 1053/1053/2136 +f 1048/1048/2134 1053/1053/2136 1046/1046/2137 +f 1046/1046/2138 1053/1053/2139 1051/1051/2140 +f 1051/1051/2140 1053/1053/2139 1049/1049/2141 +f 1050/1050/2142 1054/1054/2143 1052/1052/2144 +f 1053/1053/2145 1055/1055/2146 1056/1056/2147 +f 1053/1053/2145 1056/1056/2147 1049/1049/2148 +f 1049/1049/2148 1056/1056/2147 1050/1050/2149 +f 1053/1053/2145 1057/1057/2150 1055/1055/2146 +f 1052/1052/2144 1054/1054/2143 1057/1057/2150 +f 1052/1052/2144 1057/1057/2150 1053/1053/2145 +f 1042/1042/2151 1041/1041/2152 1055/1055/2153 +f 1055/1055/2153 1041/1041/2152 1056/1056/2154 +f 1056/1056/2155 1041/1041/2156 1050/1050/2157 +f 1050/1050/2157 1041/1041/2156 1043/1043/2158 +f 1050/1050/2159 1043/1043/2160 1045/1045/2161 +f 1050/1050/2159 1045/1045/2161 1054/1054/2162 +f 1054/1054/2163 1045/1045/2163 1044/1044/2163 +f 1054/1054/2164 1044/1044/2164 1057/1057/2164 +f 1044/1044/2165 1042/1042/2166 1057/1057/2167 +f 1057/1057/2167 1042/1042/2166 1055/1055/2168 +f 1045/1045/2169 1043/1043/2169 1058/1058/2169 +f 1042/1042/2170 1045/1045/2170 1058/1058/2170 +f 1043/1043/2171 1042/1042/2171 1058/1058/2171 +f 1051/1051/2172 1047/1047/2124 1046/1046/2123 +f 1059/1059/2173 1060/1060/2173 1061/1061/2173 +f 1062/1062/2174 1063/1063/2174 1059/1059/2174 +f 1064/1064/2175 1065/1065/2175 1066/1066/2175 +f 1065/1065/2176 1067/1067/2176 1066/1066/2176 +f 1067/1067/2177 1068/1068/2177 1066/1066/2177 +f 1066/1066/2178 1068/1068/2178 1064/1064/2178 +f 1068/1068/2179 1069/1069/2179 1064/1064/2179 +f 1064/1064/2180 1069/1069/2180 1065/1065/2180 +f 1065/1065/2181 1069/1069/2181 1067/1067/2181 +f 1069/1069/2182 1070/1070/2183 1071/1071/2184 +f 1069/1069/2182 1071/1071/2184 1067/1067/2185 +f 1068/1068/2186 1070/1070/2183 1069/1069/2182 +f 1071/1071/2184 1072/1072/2187 1067/1067/2185 +f 1068/1068/2186 1073/1073/2188 1070/1070/2183 +f 1067/1067/2185 1072/1072/2187 1068/1068/2189 +f 1068/1068/2189 1072/1072/2187 1073/1073/2190 +f 1071/1071/2191 1060/1060/2191 1072/1072/2191 +f 1072/1072/2192 1060/1060/2192 1059/1059/2192 +f 1072/1072/2193 1059/1059/2194 1073/1073/2195 +f 1059/1059/2194 1063/1063/2196 1073/1073/2195 +f 1073/1073/2197 1063/1063/2198 1062/1062/2199 +f 1073/1073/2197 1062/1062/2199 1070/1070/2200 +f 1070/1070/2201 1062/1062/2202 1071/1071/2203 +f 1062/1062/2202 1061/1061/2204 1071/1071/2203 +f 1071/1071/2205 1061/1061/2205 1060/1060/2205 +f 1062/1062/2206 1059/1059/2206 1074/1074/2206 +f 1061/1061/2207 1062/1062/2207 1074/1074/2207 +f 1059/1059/2208 1061/1061/2208 1074/1074/2208 +f 1075/1075/2209 1076/1076/2209 1077/1077/2209 +f 1078/1078/2210 1079/1079/2210 1075/1075/2210 +f 1080/1080/2211 1081/1081/2211 1082/1082/2211 +f 1082/1082/2212 1083/1083/2213 1084/1084/2214 +f 1082/1082/2212 1084/1084/2214 1080/1080/2215 +f 1080/1080/2216 1084/1084/2216 1085/1085/2216 +f 1080/1080/2217 1085/1085/2217 1081/1081/2217 +f 1085/1085/2218 1086/1086/2219 1081/1081/2220 +f 1081/1081/2220 1086/1086/2219 1083/1083/2221 +f 1081/1081/2222 1083/1083/2222 1082/1082/2222 +f 1083/1083/2223 1087/1087/2223 1084/1084/2223 +f 1086/1086/2224 1088/1088/2225 1083/1083/2226 +f 1086/1086/2224 1085/1085/2227 1088/1088/2225 +f 1084/1084/2228 1089/1089/2228 1085/1085/2228 +f 1084/1084/2229 1087/1087/2229 1089/1089/2229 +f 1087/1087/2230 1076/1076/2231 1075/1075/2232 +f 1087/1087/2230 1075/1075/2232 1089/1089/2233 +f 1089/1089/2234 1075/1075/2234 1079/1079/2234 +f 1089/1089/2235 1079/1079/2235 1085/1085/2235 +f 1085/1085/2236 1079/1079/2237 1088/1088/2238 +f 1079/1079/2237 1078/1078/2239 1088/1088/2238 +f 1078/1078/2240 1077/1077/2240 1088/1088/2240 +f 1088/1088/2241 1077/1077/2242 1083/1083/2243 +f 1077/1077/2242 1076/1076/2244 1083/1083/2243 +f 1083/1083/2243 1076/1076/2244 1087/1087/2245 +f 1078/1078/2246 1075/1075/2246 1090/1090/2246 +f 1077/1077/2247 1078/1078/2247 1090/1090/2247 +f 1075/1075/2248 1077/1077/2248 1090/1090/2248 +f 1091/1091/2249 1092/1092/2249 1093/1093/2249 +f 1093/1093/2250 1094/1094/2250 1095/1095/2250 +f 1096/1096/2251 1097/1097/2252 1098/1098/2253 +f 1098/1098/2254 1099/1099/2255 1096/1096/2256 +f 1096/1096/2256 1099/1099/2255 1100/1100/2257 +f 1096/1096/2258 1100/1100/2258 1101/1101/2258 +f 1101/1101/2259 1100/1100/2259 1102/1102/2259 +f 1101/1101/2260 1102/1102/2260 1097/1097/2260 +f 1097/1097/2261 1102/1102/2262 1099/1099/2263 +f 1097/1097/2261 1099/1099/2263 1098/1098/2264 +f 1099/1099/2265 1103/1103/2266 1100/1100/2267 +f 1100/1100/2267 1103/1103/2266 1104/1104/2268 +f 1099/1099/2269 1105/1105/2270 1103/1103/2271 +f 1102/1102/2272 1105/1105/2272 1099/1099/2272 +f 1102/1102/2273 1106/1106/2274 1105/1105/2275 +f 1100/1100/2267 1104/1104/2268 1106/1106/2276 +f 1100/1100/2267 1106/1106/2276 1102/1102/2277 +f 1105/1105/2270 1093/1093/2278 1103/1103/2271 +f 1093/1093/2278 1092/1092/2279 1103/1103/2271 +f 1103/1103/2280 1092/1092/2281 1104/1104/2282 +f 1104/1104/2282 1092/1092/2281 1091/1091/2283 +f 1104/1104/2284 1091/1091/2284 1095/1095/2284 +f 1104/1104/2285 1095/1095/2285 1106/1106/2285 +f 1106/1106/2286 1095/1095/2286 1094/1094/2286 +f 1106/1106/2274 1094/1094/2287 1105/1105/2275 +f 1094/1094/2288 1093/1093/2288 1105/1105/2288 +f 1095/1095/2289 1091/1091/2289 1107/1107/2289 +f 1093/1093/2290 1095/1095/2290 1107/1107/2290 +f 1091/1091/2291 1093/1093/2291 1107/1107/2291 +f 1101/1101/2292 1097/1097/2252 1096/1096/2251 +f 1108/1108/2293 1109/1109/2293 1110/1110/2293 +f 1111/1111/2294 1112/1112/2294 1113/1113/2294 +f 1111/1111/2295 1114/1114/2295 1112/1112/2295 +f 1114/1114/2296 1115/1115/2296 1112/1112/2296 +f 1112/1112/2297 1115/1115/2297 1113/1113/2297 +f 1115/1115/2298 1116/1116/2298 1113/1113/2298 +f 1113/1113/2299 1116/1116/2299 1111/1111/2299 +f 1116/1116/2300 1114/1114/2300 1111/1111/2300 +f 1114/1114/2301 1117/1117/2302 1115/1115/2303 +f 1114/1114/2301 1118/1118/2304 1117/1117/2302 +f 1115/1115/2305 1117/1117/2306 1119/1119/2307 +f 1114/1114/2301 1120/1120/2308 1118/1118/2304 +f 1116/1116/2309 1120/1120/2308 1114/1114/2301 +f 1115/1115/2310 1119/1119/2310 1116/1116/2310 +f 1116/1116/2311 1119/1119/2312 1120/1120/2313 +f 1109/1109/2314 1108/1108/2314 1118/1118/2314 +f 1118/1118/2315 1108/1108/2316 1117/1117/2317 +f 1108/1108/2316 1121/1121/2318 1117/1117/2317 +f 1117/1117/2306 1121/1121/2319 1122/1122/2320 +f 1117/1117/2306 1122/1122/2320 1119/1119/2307 +f 1122/1122/2321 1110/1110/2321 1119/1119/2321 +f 1119/1119/2312 1110/1110/2322 1120/1120/2313 +f 1120/1120/2323 1110/1110/2323 1109/1109/2323 +f 1120/1120/2324 1109/1109/2324 1118/1118/2324 +f 1110/1110/2325 1122/1122/2325 1123/1123/2325 +f 1108/1108/2326 1110/1110/2326 1123/1123/2326 +f 1121/1121/2327 1108/1108/2327 1123/1123/2327 +f 1122/1122/2328 1121/1121/2328 1123/1123/2328 +f 1124/1124/2329 1125/1125/2329 1126/1126/2329 +f 1126/1126/2330 1127/1127/2330 1128/1128/2330 +f 1129/1129/2331 1130/1130/2331 1131/1131/2331 +f 1131/1131/2332 1132/1132/2333 1129/1129/2334 +f 1132/1132/2335 1133/1133/2335 1129/1129/2335 +f 1129/1129/2336 1133/1133/2337 1130/1130/2338 +f 1130/1130/2338 1133/1133/2337 1134/1134/2339 +f 1130/1130/2340 1134/1134/2341 1135/1135/2342 +f 1130/1130/2340 1135/1135/2342 1131/1131/2343 +f 1131/1131/2332 1135/1135/2344 1132/1132/2333 +f 1134/1134/2345 1136/1136/2346 1135/1135/2347 +f 1135/1135/2347 1136/1136/2346 1137/1137/2348 +f 1135/1135/2347 1137/1137/2348 1132/1132/2349 +f 1132/1132/2349 1137/1137/2348 1133/1133/2350 +f 1133/1133/2350 1137/1137/2348 1138/1138/2351 +f 1133/1133/2350 1138/1138/2351 1134/1134/2352 +f 1127/1127/2353 1126/1126/2354 1137/1137/2355 +f 1137/1137/2355 1126/1126/2354 1138/1138/2356 +f 1126/1126/2357 1125/1125/2358 1138/1138/2359 +f 1138/1138/2359 1125/1125/2358 1134/1134/2360 +f 1134/1134/2361 1125/1125/2362 1124/1124/2363 +f 1134/1134/2361 1124/1124/2363 1136/1136/2364 +f 1136/1136/2365 1124/1124/2365 1128/1128/2365 +f 1136/1136/2366 1128/1128/2366 1137/1137/2366 +f 1137/1137/2367 1128/1128/2367 1127/1127/2367 +f 1124/1124/2368 1126/1126/2368 1139/1139/2368 +f 1128/1128/2369 1124/1124/2369 1139/1139/2369 +f 1126/1126/2370 1128/1128/2370 1139/1139/2370 +f 1140/1140/2371 1141/1141/2371 1142/1142/2371 +f 1143/1143/2372 1144/1144/2372 1145/1145/2372 +f 1143/1143/2373 1146/1146/2374 1144/1144/2375 +f 1146/1146/2374 1147/1147/2376 1144/1144/2375 +f 1144/1144/2377 1147/1147/2378 1148/1148/2379 +f 1144/1144/2377 1148/1148/2379 1145/1145/2380 +f 1148/1148/2381 1149/1149/2381 1145/1145/2381 +f 1145/1145/2382 1149/1149/2383 1143/1143/2384 +f 1149/1149/2383 1146/1146/2385 1143/1143/2384 +f 1149/1149/2386 1150/1150/2387 1146/1146/2388 +f 1148/1148/2389 1147/1147/2390 1151/1151/2391 +f 1146/1146/2392 1152/1152/2392 1147/1147/2392 +f 1148/1148/2389 1151/1151/2391 1149/1149/2386 +f 1149/1149/2386 1151/1151/2391 1150/1150/2387 +f 1152/1152/2393 1153/1153/2394 1147/1147/2395 +f 1153/1153/2394 1142/1142/2396 1147/1147/2395 +f 1147/1147/2397 1142/1142/2397 1151/1151/2397 +f 1151/1151/2398 1142/1142/2398 1141/1141/2398 +f 1151/1151/2399 1141/1141/2399 1150/1150/2399 +f 1141/1141/2400 1140/1140/2401 1150/1150/2402 +f 1150/1150/2402 1140/1140/2401 1146/1146/2403 +f 1146/1146/2404 1140/1140/2405 1153/1153/2406 +f 1146/1146/2404 1153/1153/2406 1152/1152/2407 +f 1140/1140/2408 1142/1142/2408 1154/1154/2408 +f 1153/1153/2409 1140/1140/2409 1154/1154/2409 +f 1142/1142/2410 1153/1153/2410 1154/1154/2410 +f 1155/1155/2411 1156/1156/2411 1157/1157/2411 +f 1158/1158/2412 1159/1159/2412 1160/1160/2412 +f 1160/1160/2413 1161/1161/2413 1158/1158/2413 +f 1161/1161/2414 1162/1162/2414 1158/1158/2414 +f 1158/1158/2415 1162/1162/2415 1159/1159/2415 +f 1159/1159/2416 1162/1162/2416 1163/1163/2416 +f 1159/1159/2417 1163/1163/2417 1160/1160/2417 +f 1160/1160/2418 1163/1163/2418 1161/1161/2418 +f 1163/1163/2419 1164/1164/2420 1161/1161/2421 +f 1163/1163/2419 1165/1165/2422 1164/1164/2420 +f 1161/1161/2421 1164/1164/2420 1166/1166/2423 +f 1161/1161/2421 1166/1166/2423 1162/1162/2424 +f 1163/1163/2419 1167/1167/2425 1165/1165/2422 +f 1162/1162/2424 1166/1166/2423 1167/1167/2425 +f 1162/1162/2424 1167/1167/2425 1163/1163/2419 +f 1166/1166/2426 1168/1168/2426 1169/1169/2426 +f 1166/1166/2427 1169/1169/2427 1167/1167/2427 +f 1169/1169/2428 1157/1157/2428 1167/1167/2428 +f 1157/1157/2429 1156/1156/2430 1167/1167/2431 +f 1167/1167/2431 1156/1156/2430 1165/1165/2432 +f 1156/1156/2433 1155/1155/2434 1165/1165/2435 +f 1165/1165/2435 1155/1155/2434 1164/1164/2436 +f 1164/1164/2437 1155/1155/2438 1168/1168/2439 +f 1164/1164/2437 1168/1168/2439 1166/1166/2440 +f 1157/1157/2441 1169/1169/2441 1170/1170/2441 +f 1155/1155/2442 1157/1157/2443 1170/1170/2444 +f 1171/1171/2445 1155/1155/2442 1170/1170/2444 +f 1168/1168/2446 1155/1155/2446 1171/1171/2446 +f 1169/1169/2447 1168/1168/2448 1170/1170/2449 +f 1170/1170/2449 1168/1168/2448 1171/1171/2450 +f 1172/1172/2451 1173/1173/2451 1174/1174/2451 +f 1174/1174/2452 1175/1175/2452 1176/1176/2452 +f 1177/1177/2453 1178/1178/2453 1179/1179/2453 +f 1180/1180/2454 1181/1181/2455 1177/1177/2456 +f 1177/1177/2456 1181/1181/2455 1178/1178/2457 +f 1178/1178/2458 1181/1181/2459 1179/1179/2460 +f 1181/1181/2459 1182/1182/2461 1179/1179/2460 +f 1179/1179/2462 1182/1182/2462 1183/1183/2462 +f 1179/1179/2463 1183/1183/2463 1177/1177/2463 +f 1177/1177/2464 1183/1183/2464 1180/1180/2464 +f 1181/1181/2465 1184/1184/2466 1182/1182/2467 +f 1180/1180/2468 1185/1185/2469 1181/1181/2465 +f 1183/1183/2470 1186/1186/2471 1180/1180/2468 +f 1180/1180/2468 1186/1186/2471 1185/1185/2469 +f 1181/1181/2465 1185/1185/2469 1184/1184/2466 +f 1183/1183/2472 1187/1187/2472 1186/1186/2472 +f 1182/1182/2467 1187/1187/2473 1183/1183/2474 +f 1184/1184/2466 1187/1187/2473 1182/1182/2467 +f 1185/1185/2475 1186/1186/2475 1173/1173/2475 +f 1173/1173/2476 1172/1172/2476 1185/1185/2476 +f 1185/1185/2477 1172/1172/2478 1176/1176/2479 +f 1185/1185/2477 1176/1176/2479 1184/1184/2480 +f 1184/1184/2481 1176/1176/2481 1175/1175/2481 +f 1184/1184/2482 1175/1175/2482 1187/1187/2482 +f 1187/1187/2483 1175/1175/2483 1174/1174/2483 +f 1187/1187/2484 1174/1174/2484 1186/1186/2484 +f 1186/1186/2485 1174/1174/2485 1173/1173/2485 +f 1174/1174/2486 1176/1176/2486 1188/1188/2486 +f 1172/1172/2487 1174/1174/2487 1188/1188/2487 +f 1176/1176/2488 1172/1172/2488 1188/1188/2488 +f 1189/1189/2489 1190/1190/2489 1191/1191/2489 +f 1192/1192/2490 1193/1193/2491 1194/1194/2492 +f 1194/1194/2492 1193/1193/2491 1195/1195/2493 +f 1193/1193/2491 1196/1196/2494 1195/1195/2493 +f 1195/1195/2495 1196/1196/2496 1197/1197/2497 +f 1196/1196/2496 1198/1198/2498 1197/1197/2497 +f 1198/1198/2498 1199/1199/2499 1197/1197/2497 +f 1197/1197/2500 1199/1199/2501 1200/1200/2502 +f 1199/1199/2501 1201/1201/2503 1200/1200/2502 +f 1200/1200/2502 1201/1201/2503 1202/1202/2504 +f 1201/1201/2503 1203/1203/2505 1202/1202/2504 +f 1202/1202/2504 1203/1203/2505 1204/1204/2506 +f 1203/1203/2505 1205/1205/2507 1204/1204/2506 +f 1205/1205/2507 1206/1206/2508 1204/1204/2506 +f 1204/1204/2506 1206/1206/2508 1207/1207/2509 +f 1206/1206/2510 1208/1208/2510 1207/1207/2510 +f 1207/1207/2511 1208/1208/2511 1209/1209/2511 +f 1208/1208/2512 1210/1210/2512 1209/1209/2512 +f 1209/1209/2513 1210/1210/2514 1211/1211/2515 +f 1210/1210/2514 1212/1212/2516 1211/1211/2515 +f 1211/1211/2515 1212/1212/2516 1213/1213/2517 +f 1212/1212/2516 1214/1214/2518 1213/1213/2517 +f 1213/1213/2517 1214/1214/2518 1215/1215/2519 +f 1214/1214/2518 1216/1216/2520 1215/1215/2519 +f 1215/1215/2519 1216/1216/2520 1217/1217/2521 +f 1216/1216/2520 1218/1218/2522 1217/1217/2521 +f 1217/1217/2521 1218/1218/2522 1219/1219/2523 +f 1219/1219/2523 1218/1218/2522 1220/1220/2524 +f 1221/1221/2525 1222/1222/2526 1223/1223/2527 +f 1223/1223/2528 1222/1222/2528 1224/1224/2528 +f 1224/1224/2529 1222/1222/2530 1225/1225/2531 +f 1225/1225/2531 1222/1222/2530 1226/1226/2532 +f 1225/1225/2533 1226/1226/2533 1227/1227/2533 +f 1227/1227/2534 1226/1226/2534 1228/1228/2534 +f 1227/1227/2535 1228/1228/2535 1221/1221/2535 +f 1221/1221/2525 1228/1228/2536 1222/1222/2526 +f 1229/1229/2537 1230/1230/2537 1231/1231/2537 +f 1232/1232/2538 1233/1233/2539 1234/1234/2540 +f 1232/1232/2538 1234/1234/2540 1235/1235/2541 +f 1236/1236/2542 1237/1237/2543 1238/1238/2544 +f 1236/1236/2542 1238/1238/2544 1239/1239/2545 +f 1240/1240/2546 1241/1241/2547 1242/1242/2548 +f 1240/1240/2546 1242/1242/2548 1243/1243/2549 +f 1242/1242/2548 1244/1244/2550 1243/1243/2549 +f 1243/1243/2549 1244/1244/2550 1245/1245/2551 +f 1245/1245/2551 1244/1244/2550 1246/1246/2552 +f 1245/1245/2551 1246/1246/2552 1247/1247/2553 +f 1245/1245/2551 1247/1247/2553 1248/1248/2554 +f 1249/1249/2555 1250/1250/2556 1251/1251/2557 +f 1249/1249/2555 1251/1251/2557 1252/1252/2558 +f 1252/1252/2558 1251/1251/2557 1253/1253/2559 +f 1253/1253/2559 1251/1251/2557 1254/1254/2560 +f 1253/1253/2559 1254/1254/2560 1255/1255/2561 +f 1253/1253/2559 1255/1255/2561 1256/1256/2562 +f 1257/1257/2563 1258/1258/2564 1259/1259/2565 +f 1258/1258/2564 1260/1260/2566 1259/1259/2565 +f 1259/1259/2565 1260/1260/2566 1261/1261/2567 +f 1260/1260/2566 1262/1262/2568 1261/1261/2567 +f 1262/1262/2569 1263/1263/2569 1261/1261/2569 +f 1261/1261/2570 1263/1263/2570 1264/1264/2570 +f 1263/1263/2571 1237/1237/2571 1264/1264/2571 +f 1264/1264/2572 1237/1237/2572 1265/1265/2572 +f 1237/1237/2573 1255/1255/2573 1265/1265/2573 +f 1265/1265/2574 1255/1255/2575 1266/1266/2576 +f 1255/1255/2575 1267/1267/2577 1266/1266/2576 +f 1267/1267/2577 1254/1254/2578 1266/1266/2576 +f 1266/1266/2576 1254/1254/2578 1268/1268/2579 +f 1254/1254/2578 1251/1251/2580 1268/1268/2579 +f 1250/1250/2581 1269/1269/2582 1268/1268/2579 +f 1250/1250/2581 1268/1268/2579 1251/1251/2580 +f 1269/1269/2582 1250/1250/2581 1247/1247/2583 +f 1269/1269/2582 1247/1247/2583 1246/1246/2584 +f 1269/1269/2582 1246/1246/2584 1270/1270/2585 +f 1270/1270/2585 1246/1246/2584 1244/1244/2586 +f 1270/1270/2585 1244/1244/2586 1271/1271/2587 +f 1271/1271/2587 1244/1244/2586 1242/1242/2588 +f 1271/1271/2587 1242/1242/2588 1241/1241/2589 +f 1271/1271/2587 1241/1241/2589 1272/1272/2590 +f 1272/1272/2590 1241/1241/2589 1234/1234/2591 +f 1272/1272/2590 1234/1234/2591 1273/1273/2592 +f 1272/1272/2590 1273/1273/2592 1274/1274/2593 +f 1274/1274/2594 1273/1273/2594 1275/1275/2594 +f 1274/1274/2595 1275/1275/2595 1276/1276/2595 +f 1276/1276/2596 1275/1275/2596 1277/1277/2596 +f 1276/1276/2597 1277/1277/2598 1278/1278/2599 +f 1278/1278/2599 1277/1277/2598 1279/1279/2600 +f 1279/1279/2600 1277/1277/2598 1280/1280/2601 +f 1281/1281/2602 1282/1282/2603 1247/1247/2553 +f 1247/1247/2553 1282/1282/2603 1248/1248/2554 +f 1282/1282/2604 1281/1281/2605 1249/1249/2555 +f 1249/1249/2555 1281/1281/2605 1250/1250/2556 +f 1283/1283/2606 1284/1284/2607 1234/1234/2540 +f 1234/1234/2540 1284/1284/2607 1235/1235/2541 +f 1241/1241/2547 1240/1240/2546 1283/1283/2608 +f 1283/1283/2608 1240/1240/2546 1284/1284/2609 +f 1285/1285/2610 1286/1286/2611 1256/1256/2562 +f 1256/1256/2562 1255/1255/2561 1285/1285/2610 +f 1237/1237/2543 1236/1236/2542 1285/1285/2612 +f 1285/1285/2612 1236/1236/2542 1286/1286/2613 +f 1287/1287/2614 1220/1220/2615 1288/1288/2616 +f 1220/1220/2615 1218/1218/2617 1288/1288/2616 +f 1289/1289/2618 1198/1198/2619 1196/1196/2620 +f 1260/1260/2621 1230/1230/2622 1290/1290/2623 +f 1210/1210/2624 1208/1208/2625 1291/1291/2626 +f 1292/1292/2627 1230/1230/2622 1260/1260/2621 +f 1293/1293/2628 1193/1193/2629 1294/1294/2630 +f 1260/1260/2621 1295/1295/2631 1292/1292/2627 +f 1260/1260/2621 1296/1296/2632 1295/1295/2631 +f 1260/1260/2621 1258/1258/2633 1296/1296/2632 +f 1239/1239/2545 1238/1238/2544 1297/1297/2634 +f 1297/1297/2634 1238/1238/2544 1298/1298/2635 +f 1297/1297/2634 1298/1298/2635 1299/1299/2636 +f 1299/1299/2636 1298/1298/2635 1300/1300/2637 +f 1299/1299/2636 1300/1300/2637 1301/1301/2638 +f 1301/1301/2638 1300/1300/2637 1216/1216/2639 +f 1302/1302/2640 1303/1303/2641 1304/1304/2642 +f 1304/1304/2642 1303/1303/2641 1305/1305/2643 +f 1306/1306/2644 1290/1290/2645 1229/1229/2646 +f 1229/1229/2646 1290/1290/2645 1230/1230/2647 +f 1304/1304/2648 1305/1305/2649 1306/1306/2650 +f 1306/1306/2650 1305/1305/2649 1290/1290/2651 +f 1307/1307/2652 1289/1289/2653 1308/1308/2654 +f 1308/1308/2654 1289/1289/2653 1293/1293/2655 +f 1308/1308/2654 1293/1293/2655 1309/1309/2656 +f 1309/1309/2656 1293/1293/2655 1310/1310/2657 +f 1309/1309/2656 1310/1310/2657 1232/1232/2538 +f 1232/1232/2538 1310/1310/2657 1233/1233/2539 +f 1191/1191/2658 1190/1190/2659 1311/1311/2660 +f 1191/1191/2658 1311/1311/2660 1312/1312/2661 +f 1312/1312/2662 1311/1311/2662 1313/1313/2662 +f 1312/1312/2663 1313/1313/2663 1314/1314/2663 +f 1314/1314/2664 1313/1313/2665 1315/1315/2666 +f 1315/1315/2666 1313/1313/2665 1294/1294/2667 +f 1316/1316/2668 1199/1199/2669 1289/1289/2653 +f 1316/1316/2668 1289/1289/2653 1307/1307/2652 +f 1216/1216/2639 1317/1317/2670 1301/1301/2638 +f 1301/1301/2638 1317/1317/2670 1318/1318/2671 +f 1319/1319/2672 1206/1206/2673 1205/1205/2674 +f 1319/1319/2672 1205/1205/2674 1320/1320/2675 +f 1320/1320/2675 1205/1205/2674 1203/1203/2676 +f 1320/1320/2675 1203/1203/2676 1321/1321/2677 +f 1321/1321/2677 1203/1203/2676 1201/1201/2678 +f 1321/1321/2677 1201/1201/2678 1322/1322/2679 +f 1323/1323/2680 1212/1212/2681 1291/1291/2682 +f 1323/1323/2680 1291/1291/2682 1324/1324/2683 +f 1324/1324/2683 1291/1291/2682 1208/1208/2684 +f 1324/1324/2683 1208/1208/2684 1325/1325/2685 +f 1325/1325/2685 1208/1208/2684 1326/1326/2686 +f 1325/1325/2685 1326/1326/2686 1327/1327/2687 +f 1328/1328/2688 1329/1329/2689 1319/1319/2672 +f 1319/1319/2672 1329/1329/2689 1206/1206/2673 +f 1329/1329/2690 1328/1328/2691 1326/1326/2686 +f 1326/1326/2686 1328/1328/2691 1327/1327/2687 +f 1208/1208/2692 1206/1206/2693 1326/1326/2694 +f 1250/1250/2695 1281/1281/2695 1247/1247/2695 +f 1216/1216/2696 1300/1300/2697 1218/1218/2617 +f 1206/1206/2693 1329/1329/2698 1326/1326/2694 +f 1280/1280/2699 1330/1330/2700 1331/1331/2701 +f 1280/1280/2699 1332/1332/2702 1330/1330/2700 +f 1280/1280/2699 1277/1277/2703 1332/1332/2702 +f 1277/1277/2703 1190/1190/2704 1332/1332/2702 +f 1199/1199/2669 1316/1316/2668 1333/1333/2705 +f 1333/1333/2705 1316/1316/2668 1334/1334/2706 +f 1333/1333/2707 1334/1334/2708 1322/1322/2679 +f 1322/1322/2679 1201/1201/2678 1333/1333/2707 +f 1212/1212/2681 1323/1323/2680 1335/1335/2709 +f 1335/1335/2709 1323/1323/2680 1336/1336/2710 +f 1335/1335/2711 1336/1336/2712 1317/1317/2670 +f 1317/1317/2670 1336/1336/2712 1318/1318/2671 +f 1190/1190/2704 1277/1277/2703 1311/1311/2713 +f 1193/1193/2629 1192/1192/2714 1294/1294/2630 +f 1277/1277/2703 1313/1313/2715 1311/1311/2713 +f 1277/1277/2703 1310/1310/2716 1313/1313/2715 +f 1313/1313/2715 1310/1310/2716 1294/1294/2630 +f 1201/1201/2717 1199/1199/2717 1333/1333/2717 +f 1310/1310/2716 1293/1293/2628 1294/1294/2630 +f 1293/1293/2628 1196/1196/2620 1193/1193/2629 +f 1275/1275/2718 1233/1233/2719 1310/1310/2716 +f 1275/1275/2718 1273/1273/2720 1233/1233/2719 +f 1291/1291/2626 1212/1212/2721 1210/1210/2624 +f 1199/1199/2722 1198/1198/2619 1289/1289/2618 +f 1273/1273/2720 1234/1234/2723 1233/1233/2719 +f 1234/1234/2724 1241/1241/2724 1283/1283/2724 +f 1287/1287/2725 1288/1288/2726 1337/1337/2727 +f 1337/1337/2727 1288/1288/2726 1302/1302/2728 +f 1302/1302/2729 1288/1288/2729 1303/1303/2729 +f 1294/1294/2730 1338/1338/2731 1339/1339/2732 +f 1339/1339/2732 1338/1338/2731 1340/1340/2733 +f 1315/1315/2734 1294/1294/2734 1339/1339/2734 +f 1341/1341/2735 1342/1342/2735 1343/1343/2735 +f 1341/1341/2736 1343/1343/2736 1344/1344/2736 +f 1343/1343/2737 1345/1345/2737 1344/1344/2737 +f 1344/1344/2738 1345/1345/2738 1346/1346/2738 +f 1346/1346/2739 1345/1345/2740 1347/1347/2741 +f 1346/1346/2739 1347/1347/2741 1348/1348/2742 +f 1348/1348/2743 1347/1347/2743 1349/1349/2743 +f 1349/1349/2744 1347/1347/2744 1342/1342/2744 +f 1349/1349/2745 1342/1342/2745 1341/1341/2745 +f 1292/1292/2746 1350/1350/2747 1231/1231/2748 +f 1292/1292/2746 1231/1231/2748 1230/1230/2749 +f 1219/1219/2750 1220/1220/2751 1287/1287/2752 +f 1219/1219/2750 1287/1287/2752 1337/1337/2753 +f 1295/1295/2754 1351/1351/2754 1349/1349/2754 +f 1295/1295/2755 1349/1349/2755 1350/1350/2755 +f 1295/1295/2756 1350/1350/2747 1292/1292/2746 +f 1190/1190/2757 1189/1189/2758 1332/1332/2759 +f 1332/1332/2759 1189/1189/2758 1352/1352/2760 +f 1353/1353/2761 1330/1330/2762 1223/1223/2763 +f 1353/1353/2761 1331/1331/2764 1330/1330/2762 +f 1223/1223/2765 1330/1330/2765 1332/1332/2765 +f 1223/1223/2766 1332/1332/2766 1352/1352/2766 +f 1192/1192/2767 1194/1194/2768 1340/1340/2769 +f 1192/1192/2767 1340/1340/2769 1338/1338/2770 +f 1279/1279/2771 1331/1331/2772 1353/1353/2773 +f 1279/1279/2771 1280/1280/2774 1331/1331/2772 +f 1351/1351/2775 1295/1295/2775 1296/1296/2775 +f 1257/1257/2776 1296/1296/2776 1258/1258/2776 +f 1351/1351/2777 1296/1296/2777 1257/1257/2777 +f 1354/1354/2778 1249/1249/2778 1252/1252/2778 +f 1252/1252/2779 1253/1253/2780 1355/1355/2781 +f 1355/1355/2781 1253/1253/2780 1256/1256/2782 +f 1355/1355/2781 1256/1256/2782 1356/1356/2783 +f 1286/1286/2784 1357/1357/2784 1256/1256/2784 +f 1256/1256/2785 1357/1357/2785 1356/1356/2785 +f 1249/1249/2786 1358/1358/2786 1282/1282/2786 +f 1249/1249/2787 1354/1354/2787 1358/1358/2787 +f 1236/1236/2788 1357/1357/2788 1286/1286/2788 +f 1236/1236/2789 1356/1356/2789 1357/1357/2789 +f 1358/1358/2790 1248/1248/2790 1282/1282/2790 +f 1248/1248/2791 1358/1358/2791 1354/1354/2791 +f 1356/1356/2792 1236/1236/2792 1239/1239/2792 +f 1359/1359/2793 1240/1240/2794 1243/1243/2795 +f 1359/1359/2793 1243/1243/2795 1360/1360/2796 +f 1360/1360/2797 1243/1243/2549 1245/1245/2551 +f 1360/1360/2798 1245/1245/2799 1354/1354/2800 +f 1354/1354/2800 1245/1245/2799 1248/1248/2801 +f 1361/1361/2802 1239/1239/2803 1297/1297/2804 +f 1297/1297/2804 1362/1362/2805 1361/1361/2802 +f 1299/1299/2806 1362/1362/2805 1297/1297/2804 +f 1299/1299/2806 1301/1301/2807 1362/1362/2805 +f 1240/1240/2808 1363/1363/2808 1284/1284/2808 +f 1240/1240/2809 1359/1359/2809 1363/1363/2809 +f 1301/1301/2810 1318/1318/2810 1364/1364/2810 +f 1336/1336/2811 1365/1365/2811 1318/1318/2811 +f 1318/1318/2812 1365/1365/2812 1364/1364/2812 +f 1284/1284/2813 1363/1363/2813 1235/1235/2813 +f 1235/1235/2814 1363/1363/2814 1359/1359/2814 +f 1232/1232/2815 1235/1235/2815 1359/1359/2815 +f 1323/1323/2816 1365/1365/2816 1336/1336/2816 +f 1323/1323/2817 1364/1364/2817 1365/1365/2817 +f 1309/1309/2818 1366/1366/2819 1308/1308/2820 +f 1309/1309/2818 1232/1232/2821 1366/1366/2819 +f 1364/1364/2822 1323/1323/2823 1324/1324/2824 +f 1364/1364/2822 1324/1324/2824 1367/1367/2825 +f 1367/1367/2825 1324/1324/2824 1325/1325/2826 +f 1325/1325/2685 1327/1327/2687 1368/1368/2827 +f 1369/1369/2828 1316/1316/2668 1307/1307/2652 +f 1370/1370/2829 1327/1327/2830 1328/1328/2831 +f 1327/1327/2830 1370/1370/2829 1368/1368/2832 +f 1316/1316/2833 1371/1371/2834 1334/1334/2835 +f 1316/1316/2833 1369/1369/2836 1371/1371/2834 +f 1319/1319/2837 1370/1370/2837 1328/1328/2837 +f 1319/1319/2838 1368/1368/2838 1370/1370/2838 +f 1334/1334/2839 1371/1371/2839 1322/1322/2839 +f 1322/1322/2840 1371/1371/2840 1369/1369/2840 +f 1368/1368/2841 1319/1319/2841 1320/1320/2841 +f 1321/1321/2842 1322/1322/2842 1369/1369/2842 +f 1372/1372/2843 1373/1373/2844 1374/1374/2845 +f 1372/1372/2846 1374/1374/2847 1375/1375/2848 +f 1375/1375/2848 1374/1374/2847 1376/1376/2849 +f 1375/1375/2850 1376/1376/2851 1377/1377/2852 +f 1377/1377/2852 1376/1376/2851 1378/1378/2853 +f 1376/1376/2851 1379/1379/2854 1378/1378/2853 +f 1379/1379/2855 1376/1376/2856 1380/1380/2857 +f 1380/1380/2858 1376/1376/2858 1381/1381/2858 +f 1382/1382/2859 1383/1383/2859 1384/1384/2859 +f 1374/1374/2860 1383/1383/2860 1382/1382/2860 +f 1383/1383/2861 1374/1374/2845 1385/1385/2862 +f 1373/1373/2844 1385/1385/2862 1374/1374/2845 +f 1386/1386/2863 1387/1387/2863 1388/1388/2863 +f 1389/1389/2864 1390/1390/2865 1387/1387/2866 +f 1389/1389/2864 1387/1387/2866 1386/1386/2867 +f 1391/1391/2868 1390/1390/2865 1389/1389/2864 +f 1392/1392/2869 1391/1391/2868 1389/1389/2864 +f 1392/1392/2870 1389/1389/2871 1393/1393/2872 +f 1393/1393/2872 1389/1389/2871 1394/1394/2873 +f 1393/1393/2874 1394/1394/2875 1395/1395/2876 +f 1395/1395/2876 1394/1394/2875 1396/1396/2877 +f 1394/1394/2875 1397/1397/2878 1396/1396/2877 +f 1397/1397/2879 1394/1394/2879 1398/1398/2879 +f 1398/1398/2880 1394/1394/2880 1399/1399/2880 +f 1400/1400/2881 1401/1401/2882 1402/1402/2883 +f 1403/1403/2884 1404/1404/2885 1402/1402/2883 +f 1402/1402/2883 1405/1405/2886 1406/1406/2887 +f 1401/1401/2882 1407/1407/2888 1408/1408/2889 +f 1402/1402/2883 1406/1406/2887 1403/1403/2884 +f 1402/1402/2883 1404/1404/2885 1409/1409/2890 +f 1409/1409/2890 1400/1400/2881 1402/1402/2883 +f 1406/1406/2887 1405/1405/2886 1410/1410/2891 +f 1411/1411/2892 1412/1412/2893 1413/1413/2894 +f 1414/1414/2895 1407/1407/2888 1411/1411/2892 +f 1415/1415/2896 1416/1416/2897 1417/1417/2898 +f 1418/1418/2899 1419/1419/2900 1415/1415/2896 +f 1420/1420/2901 1421/1421/2902 1419/1419/2900 +f 1413/1413/2894 1412/1412/2893 1421/1421/2902 +f 1413/1413/2894 1421/1421/2902 1420/1420/2901 +f 1407/1407/2888 1412/1412/2893 1411/1411/2892 +f 1405/1405/2886 1408/1408/2889 1407/1407/2888 +f 1422/1422/2903 1423/1423/2904 1414/1414/2895 +f 1417/1417/2898 1422/1422/2903 1415/1415/2896 +f 1420/1420/2901 1419/1419/2900 1418/1418/2899 +f 1422/1422/2903 1414/1414/2895 1411/1411/2892 +f 1417/1417/2898 1423/1423/2904 1422/1422/2903 +f 1424/1424/2905 1425/1425/2906 1426/1426/2907 +f 1427/1427/2908 1428/1428/2909 1424/1424/2905 +f 1424/1424/2905 1428/1428/2909 1425/1425/2906 +f 1429/1429/2910 1430/1430/2911 1431/1431/2912 +f 1429/1429/2913 1426/1426/2913 1430/1430/2913 +f 1431/1431/2912 1430/1430/2911 1432/1432/2914 +f 1433/1433/2915 1434/1434/2916 1435/1435/2917 +f 1436/1436/2918 1437/1437/2918 1438/1438/2918 +f 1438/1438/2919 1439/1439/2919 1436/1436/2919 +f 1439/1439/2920 1438/1438/2921 1440/1440/2922 +f 1441/1441/2923 1442/1442/2924 1414/1414/2895 +f 1423/1423/2904 1441/1441/2923 1414/1414/2895 +f 1426/1426/2925 1442/1442/2924 1443/1443/2926 +f 1426/1426/2925 1443/1443/2926 1430/1430/2927 +f 1444/1444/2928 1430/1430/2927 1443/1443/2926 +f 1444/1444/2928 1441/1441/2923 1423/1423/2904 +f 1407/1407/2888 1414/1414/2895 1426/1426/2925 +f 1414/1414/2895 1442/1442/2924 1426/1426/2925 +f 1430/1430/2927 1444/1444/2928 1423/1423/2904 +f 1434/1434/2929 1439/1439/2920 1440/1440/2922 +f 1434/1434/2930 1440/1440/2931 1445/1445/2932 +f 1434/1434/2930 1445/1445/2932 1435/1435/2933 +f 1416/1416/2897 1436/1436/2934 1439/1439/2935 +f 1417/1417/2898 1446/1446/2936 1447/1447/2937 +f 1417/1417/2898 1447/1447/2937 1448/1448/2938 +f 1448/1448/2938 1447/1447/2937 1449/1449/2939 +f 1449/1449/2939 1447/1447/2937 1450/1450/2940 +f 1451/1451/2941 1446/1446/2936 1417/1417/2898 +f 1452/1452/2942 1451/1451/2941 1417/1417/2898 +f 1449/1449/2939 1450/1450/2940 1453/1453/2943 +f 1452/1452/2942 1453/1453/2943 1451/1451/2941 +f 1423/1423/2904 1454/1454/2944 1455/1455/2945 +f 1423/1423/2904 1455/1455/2945 1430/1430/2927 +f 1430/1430/2927 1455/1455/2945 1456/1456/2946 +f 1456/1456/2946 1432/1432/2947 1430/1430/2927 +f 1456/1456/2946 1457/1457/2948 1432/1432/2947 +f 1417/1417/2898 1457/1457/2948 1454/1454/2944 +f 1417/1417/2898 1454/1454/2944 1423/1423/2904 +f 1458/1458/2949 1417/1417/2898 1448/1448/2938 +f 1432/1432/2947 1457/1457/2948 1417/1417/2898 +f 1432/1432/2947 1417/1417/2898 1458/1458/2949 +f 1416/1416/2950 1439/1439/2950 1434/1434/2950 +f 1416/1416/2897 1434/1434/2951 1452/1452/2942 +f 1452/1452/2942 1434/1434/2951 1433/1433/2952 +f 1449/1449/2939 1453/1453/2943 1452/1452/2942 +f 1449/1449/2939 1452/1452/2942 1433/1433/2952 +f 1416/1416/2897 1452/1452/2942 1417/1417/2898 +f 1446/1446/2953 1459/1459/2953 1447/1447/2953 +f 1451/1451/2954 1453/1453/2954 1460/1460/2954 +f 1460/1460/2955 1446/1446/2955 1451/1451/2955 +f 1459/1459/2956 1446/1446/2956 1460/1460/2956 +f 1461/1461/2957 1444/1444/2957 1443/1443/2957 +f 1444/1444/2958 1461/1461/2959 1441/1441/2960 +f 1441/1441/2960 1461/1461/2959 1462/1462/2961 +f 1463/1463/2962 1441/1441/2963 1462/1462/2964 +f 1441/1441/2963 1463/1463/2962 1442/1442/2965 +f 1463/1463/2966 1443/1443/2966 1442/1442/2966 +f 1464/1464/2967 1457/1457/2967 1456/1456/2967 +f 1457/1457/2968 1464/1464/2968 1465/1465/2968 +f 1465/1465/2969 1454/1454/2969 1457/1457/2969 +f 1454/1454/2970 1465/1465/2970 1466/1466/2970 +f 1454/1454/2971 1466/1466/2971 1455/1455/2971 +f 1382/1382/2972 1384/1384/2972 1467/1467/2972 +f 1467/1467/2973 1398/1398/2973 1399/1399/2973 +f 1468/1468/2974 1469/1469/2975 1470/1470/2976 +f 1469/1469/2975 1468/1468/2974 1471/1471/2977 +f 1468/1468/2974 1472/1472/2978 1471/1471/2977 +f 1398/1398/2979 1473/1473/2980 1397/1397/2981 +f 1383/1383/2982 1472/1472/2978 1384/1384/2983 +f 1467/1467/2984 1473/1473/2980 1398/1398/2979 +f 1467/1467/2984 1468/1468/2974 1473/1473/2980 +f 1384/1384/2983 1472/1472/2978 1468/1468/2974 +f 1384/1384/2983 1468/1468/2974 1467/1467/2984 +f 1474/1474/2985 1475/1475/2986 1476/1476/2987 +f 1474/1474/2988 1477/1477/2988 1475/1475/2988 +f 1478/1478/2989 1479/1479/2989 1480/1480/2989 +f 1481/1481/2990 1482/1482/2991 1480/1480/2992 +f 1483/1483/2993 1484/1484/2994 1412/1412/2893 +f 1412/1412/2893 1484/1484/2994 1421/1421/2902 +f 1484/1484/2994 1485/1485/2995 1421/1421/2902 +f 1479/1479/2996 1485/1485/2995 1481/1481/2990 +f 1479/1479/2996 1481/1481/2990 1480/1480/2992 +f 1479/1479/2996 1421/1421/2902 1485/1485/2995 +f 1482/1482/2991 1483/1483/2993 1480/1480/2992 +f 1480/1480/2992 1483/1483/2993 1412/1412/2893 +f 1480/1480/2992 1412/1412/2893 1477/1477/2997 +f 1435/1435/2933 1445/1445/2932 1437/1437/2998 +f 1437/1437/2998 1436/1436/2934 1416/1416/2897 +f 1486/1486/2999 1487/1487/3000 1419/1419/2900 +f 1488/1488/3001 1489/1489/3002 1486/1486/2999 +f 1490/1490/3003 1489/1489/3002 1491/1491/3004 +f 1491/1491/3004 1489/1489/3002 1488/1488/3001 +f 1487/1487/3000 1490/1490/3003 1419/1419/2900 +f 1419/1419/2900 1490/1490/3003 1492/1492/3005 +f 1421/1421/2902 1493/1493/3006 1494/1494/3007 +f 1494/1494/3007 1419/1419/2900 1421/1421/2902 +f 1495/1495/3008 1493/1493/3006 1479/1479/2996 +f 1496/1496/3009 1497/1497/3010 1495/1495/3008 +f 1496/1496/3009 1495/1495/3008 1479/1479/2996 +f 1419/1419/2900 1494/1494/3007 1497/1497/3010 +f 1419/1419/2900 1497/1497/3010 1496/1496/3009 +f 1479/1479/2996 1493/1493/3006 1421/1421/2902 +f 1416/1416/2897 1435/1435/2933 1437/1437/2998 +f 1492/1492/3005 1490/1490/3003 1491/1491/3004 +f 1492/1492/3005 1491/1491/3004 1435/1435/2933 +f 1492/1492/3005 1435/1435/2933 1416/1416/2897 +f 1496/1496/3009 1498/1498/3011 1419/1419/2900 +f 1419/1419/2900 1498/1498/3011 1488/1488/3001 +f 1419/1419/2900 1488/1488/3001 1486/1486/2999 +f 1416/1416/2897 1415/1415/2896 1419/1419/2900 +f 1419/1419/2900 1492/1492/3005 1416/1416/2897 +f 1487/1487/3012 1499/1499/3013 1490/1490/3014 +f 1500/1500/3015 1490/1490/3014 1499/1499/3013 +f 1489/1489/3016 1490/1490/3016 1500/1500/3016 +f 1486/1486/3017 1501/1501/3017 1487/1487/3017 +f 1499/1499/3018 1487/1487/3018 1501/1501/3018 +f 1502/1502/3019 1483/1483/3019 1482/1482/3019 +f 1502/1502/3020 1484/1484/3020 1483/1483/3020 +f 1503/1503/3021 1484/1484/3021 1502/1502/3021 +f 1503/1503/3022 1485/1485/3022 1484/1484/3022 +f 1485/1485/3023 1503/1503/3023 1504/1504/3023 +f 1504/1504/3024 1481/1481/3024 1485/1485/3024 +f 1482/1482/3025 1481/1481/3026 1502/1502/3027 +f 1493/1493/3028 1505/1505/3028 1494/1494/3028 +f 1494/1494/3029 1505/1505/3029 1506/1506/3029 +f 1506/1506/3030 1497/1497/3030 1494/1494/3030 +f 1497/1497/3031 1506/1506/3031 1495/1495/3031 +f 1386/1386/3032 1388/1388/3032 1507/1507/3032 +f 1381/1381/3033 1507/1507/3033 1380/1380/3033 +f 1508/1508/3034 1509/1509/3035 1510/1510/3036 +f 1508/1508/3034 1510/1510/3036 1379/1379/2855 +f 1388/1388/3037 1511/1511/3038 1507/1507/3039 +f 1387/1387/3040 1511/1511/3038 1388/1388/3037 +f 1379/1379/2855 1380/1380/2857 1507/1507/3039 +f 1379/1379/2855 1507/1507/3039 1508/1508/3034 +f 1507/1507/3039 1511/1511/3038 1508/1508/3034 +f 1476/1476/2987 1475/1475/2986 1512/1512/3041 +f 1513/1513/3042 1514/1514/3042 1515/1515/3042 +f 1515/1515/3043 1514/1514/3043 1516/1516/3043 +f 1427/1427/2908 1517/1517/3044 1428/1428/2909 +f 1518/1518/3045 1519/1519/3046 1520/1520/3047 +f 1518/1518/3045 1521/1521/3048 1519/1519/3046 +f 1522/1522/3049 1521/1521/3049 1518/1518/3049 +f 1520/1520/3050 1519/1519/3050 1523/1523/3050 +f 1524/1524/3051 1525/1525/3052 1425/1425/3053 +f 1526/1526/3054 1527/1527/3055 1528/1528/3056 +f 1528/1528/3056 1527/1527/3055 1410/1410/2891 +f 1527/1527/3055 1529/1529/3057 1410/1410/2891 +f 1428/1428/3058 1529/1529/3057 1524/1524/3051 +f 1428/1428/3058 1524/1524/3051 1425/1425/3053 +f 1407/1407/2888 1426/1426/2925 1425/1425/3053 +f 1428/1428/3058 1410/1410/2891 1529/1529/3057 +f 1525/1525/3052 1526/1526/3054 1425/1425/3053 +f 1425/1425/3053 1526/1526/3054 1528/1528/3056 +f 1425/1425/3053 1528/1528/3056 1407/1407/2888 +f 1410/1410/2891 1405/1405/2886 1528/1528/3056 +f 1528/1528/3056 1405/1405/2886 1407/1407/2888 +f 1523/1523/3059 1519/1519/3060 1403/1403/2884 +f 1530/1530/3061 1531/1531/3062 1516/1516/3063 +f 1406/1406/2887 1531/1531/3062 1532/1532/3064 +f 1514/1514/3065 1533/1533/3066 1530/1530/3061 +f 1514/1514/3065 1530/1530/3061 1516/1516/3063 +f 1532/1532/3067 1533/1533/3067 1514/1514/3067 +f 1406/1406/2887 1532/1532/3064 1403/1403/2884 +f 1534/1534/3068 1535/1535/3069 1428/1428/3058 +f 1536/1536/3070 1406/1406/2887 1410/1410/2891 +f 1536/1536/3070 1410/1410/2891 1535/1535/3069 +f 1428/1428/3058 1537/1537/3071 1534/1534/3068 +f 1517/1517/3072 1538/1538/3073 1537/1537/3071 +f 1517/1517/3072 1537/1537/3071 1428/1428/3058 +f 1406/1406/2887 1536/1536/3070 1538/1538/3073 +f 1406/1406/2887 1538/1538/3073 1517/1517/3072 +f 1428/1428/3058 1535/1535/3069 1410/1410/2891 +f 1403/1403/2884 1539/1539/3074 1523/1523/3059 +f 1403/1403/2884 1532/1532/3064 1514/1514/3075 +f 1514/1514/3075 1513/1513/3076 1403/1403/2884 +f 1403/1403/2884 1513/1513/3076 1539/1539/3074 +f 1517/1517/3072 1516/1516/3063 1406/1406/2887 +f 1406/1406/2887 1516/1516/3063 1531/1531/3062 +f 1540/1540/3077 1532/1532/3078 1541/1541/3079 +f 1542/1542/3080 1532/1532/3080 1540/1540/3080 +f 1542/1542/3081 1533/1533/3081 1532/1532/3081 +f 1530/1530/3082 1541/1541/3082 1531/1531/3082 +f 1532/1532/3078 1531/1531/3083 1541/1541/3079 +f 1543/1543/3084 1526/1526/3084 1525/1525/3084 +f 1544/1544/3085 1526/1526/3085 1543/1543/3085 +f 1544/1544/3086 1527/1527/3086 1526/1526/3086 +f 1545/1545/3087 1527/1527/3087 1544/1544/3087 +f 1545/1545/3088 1529/1529/3088 1527/1527/3088 +f 1529/1529/3089 1545/1545/3089 1546/1546/3089 +f 1546/1546/3090 1524/1524/3090 1529/1529/3090 +f 1546/1546/3091 1525/1525/3092 1524/1524/3093 +f 1525/1525/3092 1546/1546/3091 1543/1543/3094 +f 1547/1547/3095 1536/1536/3096 1535/1535/3097 +f 1536/1536/3096 1547/1547/3095 1548/1548/3098 +f 1548/1548/3099 1538/1538/3099 1536/1536/3099 +f 1538/1538/3100 1548/1548/3100 1537/1537/3100 +f 1547/1547/3101 1535/1535/3101 1534/1534/3101 +f 1468/1468/2974 1470/1470/2976 1473/1473/2980 +f 1400/1400/2881 1549/1549/3102 1550/1550/3103 +f 1549/1549/3102 1551/1551/3104 1550/1550/3103 +f 1550/1550/3103 1551/1551/3104 1477/1477/2997 +f 1477/1477/2997 1551/1551/3104 1552/1552/3105 +f 1477/1477/2997 1552/1552/3105 1475/1475/3106 +f 1553/1553/3107 1475/1475/3106 1552/1552/3105 +f 1553/1553/3107 1549/1549/3102 1400/1400/2881 +f 1412/1412/2893 1550/1550/3103 1477/1477/2997 +f 1475/1475/3106 1553/1553/3107 1400/1400/2881 +f 1401/1401/2882 1400/1400/2881 1550/1550/3103 +f 1401/1401/2882 1550/1550/3103 1407/1407/2888 +f 1407/1407/2888 1550/1550/3103 1412/1412/2893 +f 1554/1554/3108 1521/1521/3109 1522/1522/3110 +f 1554/1554/3108 1522/1522/3110 1523/1523/3059 +f 1554/1554/3108 1523/1523/3059 1539/1539/3074 +f 1403/1403/2884 1519/1519/3060 1404/1404/2885 +f 1404/1404/2885 1519/1519/3060 1521/1521/3109 +f 1409/1409/2890 1555/1555/3111 1556/1556/3112 +f 1409/1409/2890 1556/1556/3112 1557/1557/3113 +f 1557/1557/3113 1556/1556/3112 1558/1558/3114 +f 1559/1559/3115 1555/1555/3111 1409/1409/2890 +f 1404/1404/2885 1559/1559/3115 1409/1409/2890 +f 1558/1558/3114 1560/1560/3116 1559/1559/3115 +f 1558/1558/3114 1556/1556/3112 1560/1560/3116 +f 1561/1561/3117 1562/1562/3118 1400/1400/2881 +f 1400/1400/2881 1562/1562/3118 1475/1475/3106 +f 1562/1562/3118 1563/1563/3119 1475/1475/3106 +f 1563/1563/3119 1512/1512/3120 1475/1475/3106 +f 1564/1564/3121 1565/1565/3122 1512/1512/3120 +f 1409/1409/2890 1565/1565/3122 1561/1561/3117 +f 1409/1409/2890 1561/1561/3117 1400/1400/2881 +f 1563/1563/3119 1564/1564/3121 1512/1512/3120 +f 1566/1566/3123 1409/1409/2890 1557/1557/3113 +f 1512/1512/3120 1565/1565/3122 1409/1409/2890 +f 1512/1512/3120 1409/1409/2890 1566/1566/3123 +f 1404/1404/2885 1521/1521/3109 1554/1554/3108 +f 1404/1404/2885 1554/1554/3108 1567/1567/3124 +f 1558/1558/3114 1559/1559/3115 1404/1404/2885 +f 1558/1558/3114 1404/1404/2885 1567/1567/3124 +f 1555/1555/3125 1568/1568/3125 1556/1556/3125 +f 1569/1569/3126 1559/1559/3126 1560/1560/3126 +f 1559/1559/3127 1569/1569/3127 1570/1570/3127 +f 1570/1570/3128 1555/1555/3128 1559/1559/3128 +f 1568/1568/3129 1555/1555/3129 1570/1570/3129 +f 1571/1571/3130 1552/1552/3130 1572/1572/3130 +f 1571/1571/3131 1553/1553/3131 1552/1552/3131 +f 1573/1573/3132 1553/1553/3132 1571/1571/3132 +f 1553/1553/3133 1573/1573/3133 1549/1549/3133 +f 1549/1549/3134 1573/1573/3134 1574/1574/3134 +f 1549/1549/3135 1574/1574/3135 1551/1551/3135 +f 1551/1551/3136 1574/1574/3136 1572/1572/3136 +f 1572/1572/3137 1552/1552/3137 1551/1551/3137 +f 1575/1575/3138 1565/1565/3138 1564/1564/3138 +f 1565/1565/3139 1575/1575/3140 1576/1576/3141 +f 1576/1576/3141 1561/1561/3142 1565/1565/3139 +f 1562/1562/3143 1561/1561/3143 1576/1576/3143 +f 1562/1562/3118 1576/1576/3144 1563/1563/3119 +f 1508/1508/3034 1577/1577/3145 1509/1509/3035 +f 1508/1508/3034 1511/1511/3038 1577/1577/3145 +f 1393/1393/3146 1578/1578/3147 1579/1579/3148 +f 1393/1393/3146 1579/1579/3148 1372/1372/3149 +f 1375/1375/3150 1580/1580/3151 1392/1392/3152 +f 1392/1392/3152 1580/1580/3151 1581/1581/3153 +f 1372/1372/573 1375/1375/573 1393/1393/573 +f 1393/1393/573 1375/1375/573 1392/1392/573 +f 1582/1582/3154 1583/1583/3155 1584/1584/3156 +f 1582/1582/3154 1584/1584/3156 1585/1585/3157 +f 1585/1585/3158 1411/1411/3159 1586/1586/3160 +f 1586/1586/3161 1411/1411/3162 1587/1587/3163 +f 1586/1586/3161 1587/1587/3163 1588/1588/3164 +f 1585/1585/3165 1584/1584/3165 1422/1422/3165 +f 1585/1585/3158 1422/1422/3166 1411/1411/3159 +f 1588/1588/3164 1587/1587/3163 1413/1413/3167 +f 1589/1589/3168 1588/1588/3164 1420/1420/3169 +f 1588/1588/3164 1413/1413/3167 1420/1420/3169 +f 1589/1589/3168 1420/1420/3169 1418/1418/3170 +f 1589/1589/3171 1418/1418/3172 1582/1582/3173 +f 1582/1582/3173 1418/1418/3172 1583/1583/3174 +f 1584/1584/3156 1583/1583/3155 1415/1415/2896 +f 1584/1584/3175 1415/1415/3175 1422/1422/3175 +f 1587/1587/3176 1411/1411/3176 1413/1413/3176 +f 1418/1418/2899 1415/1415/2896 1583/1583/3155 +f 1402/1402/2883 1401/1401/2882 1408/1408/2889 +f 1408/1408/2889 1405/1405/2886 1402/1402/2883 +f 1393/1393/3177 1395/1395/3177 1578/1578/3177 +f 1391/1391/3178 1392/1392/3178 1581/1581/3178 +f 1375/1375/3179 1377/1377/3179 1580/1580/3179 +f 1373/1373/3180 1372/1372/3180 1579/1579/3180 +f 1473/1473/3181 1470/1470/3182 1396/1396/3183 +f 1396/1396/3183 1397/1397/3184 1473/1473/3181 +f 1396/1396/3183 1470/1470/3182 1395/1395/3185 +f 1395/1395/3186 1470/1470/3187 1578/1578/3188 +f 1469/1469/3189 1578/1578/3188 1470/1470/3187 +f 1579/1579/3190 1578/1578/3188 1469/1469/3189 +f 1373/1373/3191 1579/1579/3191 1469/1469/3191 +f 1472/1472/3192 1383/1383/3193 1471/1471/3194 +f 1469/1469/3195 1385/1385/3196 1373/1373/3197 +f 1385/1385/3196 1469/1469/3195 1471/1471/3194 +f 1471/1471/3194 1383/1383/3193 1385/1385/3196 +f 1378/1378/3198 1379/1379/2855 1510/1510/3036 +f 1378/1378/3198 1510/1510/3036 1509/1509/3199 +f 1378/1378/3198 1509/1509/3199 1377/1377/3200 +f 1509/1509/3201 1580/1580/3201 1377/1377/3201 +f 1581/1581/3202 1580/1580/3203 1509/1509/3204 +f 1509/1509/3204 1577/1577/3205 1581/1581/3202 +f 1577/1577/3205 1391/1391/3206 1581/1581/3202 +f 1391/1391/3207 1577/1577/3207 1390/1390/3207 +f 1511/1511/3208 1387/1387/2866 1390/1390/2865 +f 1511/1511/3208 1390/1390/2865 1577/1577/3209 +f 1543/1543/5 1546/1546/5 1545/1545/5 +f 1544/1544/5 1543/1543/5 1545/1545/5 +f 1537/1537/3071 1548/1548/3210 1547/1547/3211 +f 1547/1547/3211 1534/1534/3068 1537/1537/3071 +f 1530/1530/3061 1533/1533/3066 1541/1541/3212 +f 1533/1533/3066 1540/1540/3213 1541/1541/3212 +f 1533/1533/3066 1542/1542/3214 1540/1540/3213 +f 1520/1520/3215 1523/1523/3059 1522/1522/3110 +f 1518/1518/3216 1520/1520/3215 1522/1522/3110 +f 1568/1568/3217 1560/1560/3218 1556/1556/3219 +f 1570/1570/3220 1569/1569/3221 1560/1560/3218 +f 1570/1570/3220 1560/1560/3218 1568/1568/3217 +f 1563/1563/3119 1576/1576/3222 1575/1575/3223 +f 1563/1563/3119 1575/1575/3223 1564/1564/3121 +f 1574/1574/3224 1573/1573/3225 1572/1572/3225 +f 1572/1572/3225 1573/1573/3225 1571/1571/3226 +f 1502/1502/3027 1504/1504/3227 1503/1503/3228 +f 1502/1502/3027 1481/1481/3026 1504/1504/3227 +f 1506/1506/3229 1505/1505/3230 1495/1495/3008 +f 1505/1505/3230 1493/1493/3006 1495/1495/3008 +f 1500/1500/3231 1499/1499/3232 1489/1489/3233 +f 1499/1499/3232 1501/1501/3234 1489/1489/3233 +f 1489/1489/3233 1501/1501/3234 1486/1486/3235 +f 1445/1445/2932 1440/1440/2931 1438/1438/3236 +f 1445/1445/2932 1438/1438/3236 1437/1437/2998 +f 1447/1447/3237 1459/1459/3238 1450/1450/2940 +f 1450/1450/2940 1459/1459/3238 1453/1453/2943 +f 1459/1459/3238 1460/1460/3239 1453/1453/2943 +f 1455/1455/2945 1466/1466/3240 1464/1464/3241 +f 1456/1456/2946 1455/1455/2945 1464/1464/3241 +f 1466/1466/3240 1465/1465/3242 1464/1464/3241 +f 1461/1461/3243 1443/1443/3244 1462/1462/3245 +f 1443/1443/3244 1463/1463/3246 1462/1462/3245 +f 1479/1479/3247 1498/1498/3248 1496/1496/3249 +f 1431/1431/3250 1432/1432/3251 1458/1458/3252 +f 1517/1517/3253 1427/1427/3254 1516/1516/3255 +f 1431/1431/3250 1458/1458/3252 1448/1448/3256 +f 1448/1448/3256 1382/1382/3257 1431/1431/3250 +f 1516/1516/3255 1427/1427/3254 1515/1515/3258 +f 1477/1477/3259 1386/1386/3260 1507/1507/3261 +f 1429/1429/3262 1431/1431/3250 1382/1382/3257 +f 1382/1382/3257 1426/1426/3263 1429/1429/3262 +f 1426/1426/3263 1382/1382/3257 1467/1467/3264 +f 1399/1399/3265 1424/1424/3266 1467/1467/3264 +f 1427/1427/3254 1424/1424/3266 1399/1399/3265 +f 1424/1424/3266 1426/1426/3263 1467/1467/3264 +f 1474/1474/3267 1476/1476/3268 1386/1386/3260 +f 1399/1399/3265 1515/1515/3258 1427/1427/3254 +f 1382/1382/3257 1448/1448/3256 1449/1449/3269 +f 1382/1382/3257 1433/1433/2915 1374/1374/3270 +f 1433/1433/2915 1382/1382/3257 1449/1449/3269 +f 1513/1513/3271 1394/1394/3272 1554/1554/3273 +f 1374/1374/3270 1433/1433/2915 1435/1435/2917 +f 1539/1539/3274 1513/1513/3271 1554/1554/3273 +f 1435/1435/2917 1376/1376/3275 1374/1374/3270 +f 1554/1554/3273 1394/1394/3272 1389/1389/3276 +f 1389/1389/3276 1567/1567/3277 1554/1554/3273 +f 1399/1399/3265 1394/1394/3272 1513/1513/3271 +f 1386/1386/3260 1558/1558/3278 1389/1389/3276 +f 1478/1478/3279 1498/1498/3248 1479/1479/3247 +f 1376/1376/3275 1491/1491/3280 1381/1381/3281 +f 1558/1558/3278 1567/1567/3277 1389/1389/3276 +f 1376/1376/3275 1435/1435/2917 1491/1491/3280 +f 1381/1381/3281 1480/1480/3282 1507/1507/3261 +f 1480/1480/3282 1477/1477/3259 1507/1507/3261 +f 1515/1515/3258 1399/1399/3265 1513/1513/3271 +f 1478/1478/3279 1381/1381/3281 1488/1488/3283 +f 1386/1386/3260 1477/1477/3259 1474/1474/3267 +f 1558/1558/3278 1386/1386/3260 1476/1476/3268 +f 1480/1480/3282 1381/1381/3281 1478/1478/3279 +f 1488/1488/3283 1381/1381/3281 1491/1491/3280 +f 1558/1558/3278 1476/1476/3268 1557/1557/3284 +f 1498/1498/3248 1478/1478/3279 1488/1488/3283 +f 1476/1476/3268 1566/1566/3285 1557/1557/3284 +f 1476/1476/3268 1512/1512/3286 1566/1566/3285 +f 1585/1585/3287 1586/1586/3288 1582/1582/3289 +f 1589/1589/3290 1582/1582/3289 1586/1586/3288 +f 1589/1589/3290 1586/1586/3288 1588/1588/3291 +f 1590/1590/3292 1591/1591/3293 1592/1592/3294 +f 1593/1593/3295 1594/1594/3296 1595/1595/3297 +f 1593/1593/3295 1595/1595/3297 1596/1596/1211 +f 1597/1597/3298 1598/1598/3299 1594/1594/3296 +f 1599/1599/3300 1600/1600/3301 1601/1601/3302 +f 1596/1596/1211 1600/1600/3301 1599/1599/3300 +f 1599/1599/3300 1601/1601/3302 1590/1590/3292 +f 1590/1590/3292 1601/1601/3302 1591/1591/3293 +f 1596/1596/1211 1595/1595/3297 1600/1600/3301 +f 1597/1597/3298 1594/1594/3296 1593/1593/3295 +f 1592/1592/3294 1591/1591/3293 1597/1597/3298 +f 1597/1597/3298 1591/1591/3293 1598/1598/3299 +f 1602/1602/3303 1601/1601/3304 1603/1603/3305 +f 1603/1603/3305 1601/1601/3304 1600/1600/3306 +f 1603/1603/3307 1600/1600/3307 1604/1604/3307 +f 1604/1604/3308 1600/1600/3308 1595/1595/3308 +f 1604/1604/3309 1595/1595/3310 1605/1605/3311 +f 1605/1605/3311 1595/1595/3310 1594/1594/3312 +f 1605/1605/3313 1594/1594/3314 1606/1606/3315 +f 1606/1606/3315 1594/1594/3314 1598/1598/3316 +f 1606/1606/3317 1598/1598/3318 1607/1607/3319 +f 1607/1607/3319 1598/1598/3318 1591/1591/3320 +f 1607/1607/3321 1591/1591/3322 1601/1601/3323 +f 1607/1607/3321 1601/1601/3323 1602/1602/3324 +f 1608/1608/573 1602/1602/3325 1609/1609/3326 +f 1608/1608/573 1607/1607/3326 1602/1602/3325 +f 1608/1608/573 1606/1606/3327 1607/1607/3326 +f 1603/1603/3328 1604/1604/3329 1610/1610/3329 +f 1610/1610/3329 1605/1605/3330 1606/1606/3327 +f 1610/1610/3329 1606/1606/3327 1608/1608/573 +f 1610/1610/3329 1604/1604/3329 1605/1605/3330 +f 1609/1609/3326 1602/1602/3325 1603/1603/573 +f 1611/1611/3331 1609/1609/3332 1612/1612/3333 +f 1612/1612/3333 1609/1609/3332 1603/1603/3334 +f 1612/1612/3335 1603/1603/3335 1613/1613/3335 +f 1613/1613/3336 1603/1603/3337 1610/1610/3338 +f 1613/1613/3336 1610/1610/3338 1614/1614/3339 +f 1614/1614/3340 1610/1610/3341 1608/1608/3342 +f 1614/1614/3340 1608/1608/3342 1615/1615/3343 +f 1615/1615/3344 1608/1608/3345 1611/1611/3346 +f 1611/1611/3346 1608/1608/3345 1609/1609/3347 +f 1615/1615/3348 1613/1613/3349 1614/1614/3350 +f 1612/1612/3351 1613/1613/3349 1611/1611/3352 +f 1615/1615/3348 1611/1611/3352 1613/1613/3349 +f 1596/1596/1211 1599/1599/3300 1593/1593/3295 +f 1593/1593/3295 1599/1599/3300 1590/1590/3292 +f 1593/1593/3295 1590/1590/3292 1597/1597/3298 +f 1597/1597/3298 1590/1590/3292 1592/1592/3294 +f 1616/1616/3353 1617/1617/3353 1618/1618/3353 +f 1619/1619/3354 1620/1620/3354 1616/1616/3354 +f 1621/1621/3355 1622/1622/3356 1623/1623/3357 +f 1623/1623/3357 1624/1624/3358 1621/1621/3355 +f 1625/1625/3359 1626/1626/3360 1622/1622/3361 +f 1622/1622/3361 1626/1626/3360 1623/1623/3362 +f 1623/1623/3363 1626/1626/3364 1624/1624/3365 +f 1624/1624/3365 1626/1626/3364 1627/1627/3366 +f 1624/1624/3367 1627/1627/3367 1628/1628/3367 +f 1624/1624/3368 1628/1628/3368 1621/1621/3368 +f 1621/1621/3369 1628/1628/3370 1625/1625/3371 +f 1621/1621/3369 1625/1625/3371 1622/1622/3372 +f 1625/1625/3373 1629/1629/3374 1626/1626/3375 +f 1627/1627/3376 1630/1630/3377 1628/1628/3378 +f 1626/1626/3375 1629/1629/3374 1627/1627/3376 +f 1627/1627/3376 1629/1629/3374 1630/1630/3377 +f 1625/1625/3373 1631/1631/3379 1629/1629/3374 +f 1628/1628/3378 1630/1630/3377 1632/1632/3380 +f 1628/1628/3378 1632/1632/3380 1631/1631/3379 +f 1628/1628/3378 1631/1631/3379 1625/1625/3373 +f 1618/1618/3381 1631/1631/3381 1619/1619/3381 +f 1619/1619/3382 1631/1631/3383 1620/1620/3384 +f 1620/1620/3384 1631/1631/3383 1632/1632/3385 +f 1620/1620/3386 1632/1632/3387 1616/1616/3388 +f 1616/1616/3388 1632/1632/3387 1630/1630/3389 +f 1616/1616/3390 1630/1630/3390 1617/1617/3390 +f 1617/1617/3391 1630/1630/3391 1629/1629/3391 +f 1617/1617/3392 1629/1629/3392 1618/1618/3392 +f 1618/1618/3393 1629/1629/3393 1631/1631/3393 +f 1633/1633/3394 1616/1616/3394 1634/1634/3394 +f 1619/1619/3395 1616/1616/3395 1633/1633/3395 +f 1634/1634/3396 1619/1619/3397 1633/1633/3398 +f 1618/1618/3399 1619/1619/3397 1634/1634/3396 +f 1616/1616/3400 1618/1618/3400 1634/1634/3400 +f 1635/1635/3401 1636/1636/3401 1637/1637/3401 +f 1638/1638/3402 1639/1639/3402 1636/1636/3402 +f 1640/1640/3403 1641/1641/3404 1642/1642/3405 +f 1643/1643/3406 1640/1640/3403 1642/1642/3405 +f 1642/1642/3407 1644/1644/3408 1643/1643/3409 +f 1644/1644/3408 1645/1645/3410 1643/1643/3409 +f 1643/1643/3411 1645/1645/3411 1646/1646/3411 +f 1643/1643/3412 1646/1646/3412 1640/1640/3412 +f 1640/1640/3413 1646/1646/3414 1647/1647/3415 +f 1640/1640/3413 1647/1647/3415 1641/1641/3416 +f 1647/1647/3417 1644/1644/3418 1641/1641/3419 +f 1641/1641/3419 1644/1644/3418 1642/1642/3420 +f 1645/1645/3421 1648/1648/3422 1649/1649/3423 +f 1644/1644/3424 1648/1648/3422 1645/1645/3421 +f 1646/1646/3425 1650/1650/3426 1647/1647/3427 +f 1647/1647/3427 1650/1650/3426 1651/1651/3428 +f 1645/1645/3421 1649/1649/3423 1646/1646/3425 +f 1644/1644/3424 1652/1652/3429 1648/1648/3422 +f 1647/1647/3427 1651/1651/3428 1644/1644/3424 +f 1646/1646/3425 1649/1649/3423 1650/1650/3426 +f 1644/1644/3424 1651/1651/3428 1652/1652/3429 +f 1638/1638/3430 1652/1652/3431 1639/1639/3432 +f 1639/1639/3432 1652/1652/3431 1651/1651/3433 +f 1639/1639/3434 1651/1651/3435 1636/1636/3436 +f 1636/1636/3436 1651/1651/3435 1650/1650/3437 +f 1636/1636/3438 1650/1650/3439 1649/1649/3440 +f 1636/1636/3438 1649/1649/3440 1637/1637/3441 +f 1637/1637/3442 1649/1649/3443 1635/1635/3444 +f 1635/1635/3444 1649/1649/3443 1648/1648/3445 +f 1635/1635/3446 1648/1648/3447 1638/1638/3448 +f 1638/1638/3448 1648/1648/3447 1652/1652/3449 +f 1636/1636/3450 1635/1635/3450 1653/1653/3450 +f 1654/1654/3451 1636/1636/3451 1653/1653/3451 +f 1638/1638/3452 1636/1636/3452 1654/1654/3452 +f 1653/1653/3453 1638/1638/3454 1654/1654/3455 +f 1635/1635/3456 1638/1638/3454 1653/1653/3453 +f 1655/1655/3457 1656/1656/3457 1657/1657/3457 +f 1657/1657/3458 1658/1658/3459 1659/1659/3460 +f 1657/1657/3458 1659/1659/3460 1660/1660/3461 +f 1661/1661/3462 1662/1662/3463 1663/1663/3464 +f 1663/1663/3465 1664/1664/3465 1661/1661/3465 +f 1664/1664/3466 1665/1665/3466 1661/1661/3466 +f 1661/1661/3467 1665/1665/3467 1666/1666/3467 +f 1661/1661/3468 1666/1666/3468 1662/1662/3468 +f 1662/1662/3469 1666/1666/3470 1667/1667/3471 +f 1667/1667/3471 1666/1666/3470 1668/1668/3472 +f 1668/1668/3473 1664/1664/3474 1667/1667/3475 +f 1667/1667/3475 1664/1664/3474 1663/1663/3476 +f 1668/1668/3477 1669/1669/3478 1664/1664/3479 +f 1664/1664/3479 1669/1669/3478 1665/1665/3480 +f 1668/1668/3477 1670/1670/3481 1669/1669/3478 +f 1666/1666/3482 1670/1670/3481 1668/1668/3477 +f 1665/1665/3483 1671/1671/3483 1666/1666/3483 +f 1666/1666/3484 1671/1671/3485 1670/1670/3486 +f 1656/1656/3487 1665/1665/3488 1669/1669/3489 +f 1656/1656/3490 1669/1669/3490 1657/1657/3490 +f 1657/1657/3491 1669/1669/3491 1670/1670/3491 +f 1657/1657/3492 1670/1670/3492 1658/1658/3492 +f 1658/1658/3493 1670/1670/3486 1659/1659/3494 +f 1659/1659/3494 1670/1670/3486 1671/1671/3485 +f 1659/1659/3495 1671/1671/3495 1660/1660/3495 +f 1660/1660/3496 1671/1671/3497 1665/1665/3498 +f 1660/1660/3496 1665/1665/3498 1655/1655/3499 +f 1655/1655/3500 1665/1665/3488 1656/1656/3487 +f 1657/1657/3501 1660/1660/3501 1672/1672/3501 +f 1673/1673/3502 1657/1657/3502 1672/1672/3502 +f 1655/1655/3503 1657/1657/3503 1673/1673/3503 +f 1672/1672/3504 1655/1655/3505 1673/1673/3506 +f 1660/1660/3507 1655/1655/3505 1672/1672/3504 +f 1667/1667/3508 1663/1663/3464 1662/1662/3463 +f 1674/1674/3509 1675/1675/3509 1676/1676/3509 +f 1677/1677/3510 1678/1678/3511 1679/1679/3512 +f 1679/1679/3512 1680/1680/3513 1677/1677/3510 +f 1678/1678/3514 1681/1681/3514 1679/1679/3514 +f 1679/1679/3515 1681/1681/3515 1682/1682/3515 +f 1679/1679/3516 1682/1682/3516 1680/1680/3516 +f 1680/1680/3517 1682/1682/3517 1683/1683/3517 +f 1680/1680/3518 1683/1683/3518 1677/1677/3518 +f 1683/1683/3519 1684/1684/3519 1677/1677/3519 +f 1677/1677/3520 1684/1684/3520 1678/1678/3520 +f 1678/1678/3521 1684/1684/3521 1681/1681/3521 +f 1684/1684/3522 1685/1685/3523 1681/1681/3524 +f 1684/1684/3522 1686/1686/3525 1685/1685/3523 +f 1687/1687/3526 1683/1683/3527 1682/1682/3528 +f 1681/1681/3524 1688/1688/3529 1682/1682/3528 +f 1682/1682/3528 1688/1688/3529 1687/1687/3526 +f 1683/1683/3530 1686/1686/3525 1684/1684/3522 +f 1681/1681/3524 1685/1685/3523 1688/1688/3529 +f 1675/1675/3531 1685/1685/3532 1676/1676/3533 +f 1676/1676/3533 1685/1685/3532 1686/1686/3534 +f 1676/1676/3535 1686/1686/3535 1689/1689/3535 +f 1689/1689/3536 1686/1686/3536 1683/1683/3536 +f 1689/1689/3537 1683/1683/3538 1687/1687/3539 +f 1689/1689/3537 1687/1687/3539 1690/1690/3540 +f 1690/1690/3541 1687/1687/3542 1674/1674/3543 +f 1674/1674/3543 1687/1687/3542 1688/1688/3544 +f 1674/1674/3545 1688/1688/3546 1685/1685/3547 +f 1674/1674/3545 1685/1685/3547 1675/1675/3548 +f 1689/1689/3549 1690/1690/3550 1691/1691/3551 +f 1691/1691/3551 1690/1690/3550 1692/1692/3552 +f 1676/1676/3553 1689/1689/3553 1691/1691/3553 +f 1692/1692/3554 1676/1676/3554 1691/1691/3554 +f 1674/1674/3555 1676/1676/3555 1692/1692/3555 +f 1690/1690/3556 1674/1674/3556 1692/1692/3556 +f 1693/1693/3557 1694/1694/3557 1695/1695/3557 +f 1696/1696/3558 1697/1697/3559 1698/1698/3560 +f 1696/1696/3558 1699/1699/3561 1697/1697/3559 +f 1696/1696/3562 1700/1700/3563 1701/1701/3564 +f 1696/1696/3562 1701/1701/3564 1699/1699/3565 +f 1699/1699/3566 1701/1701/3567 1702/1702/3568 +f 1699/1699/3566 1702/1702/3568 1697/1697/3569 +f 1697/1697/3570 1702/1702/3571 1703/1703/3572 +f 1697/1697/3570 1703/1703/3572 1698/1698/3573 +f 1698/1698/3574 1703/1703/3575 1700/1700/3576 +f 1698/1698/3574 1700/1700/3576 1696/1696/3577 +f 1700/1700/3578 1704/1704/3579 1701/1701/3580 +f 1700/1700/3578 1705/1705/3581 1704/1704/3579 +f 1703/1703/3582 1705/1705/3581 1700/1700/3578 +f 1702/1702/3583 1706/1706/3584 1703/1703/3582 +f 1703/1703/3582 1706/1706/3584 1705/1705/3581 +f 1702/1702/3583 1707/1707/3585 1706/1706/3584 +f 1701/1701/3580 1704/1704/3579 1708/1708/3586 +f 1701/1701/3580 1708/1708/3586 1707/1707/3585 +f 1701/1701/3580 1707/1707/3585 1702/1702/3583 +f 1709/1709/3587 1704/1704/3587 1710/1710/3587 +f 1710/1710/3588 1704/1704/3588 1705/1705/3588 +f 1710/1710/3589 1705/1705/3589 1693/1693/3589 +f 1693/1693/3590 1705/1705/3590 1706/1706/3590 +f 1693/1693/3591 1706/1706/3591 1694/1694/3591 +f 1694/1694/3592 1706/1706/3592 1707/1707/3592 +f 1694/1694/3593 1707/1707/3593 1695/1695/3593 +f 1695/1695/3594 1707/1707/3594 1708/1708/3594 +f 1695/1695/3595 1708/1708/3595 1709/1709/3595 +f 1709/1709/3596 1708/1708/3596 1704/1704/3596 +f 1693/1693/3597 1695/1695/3597 1711/1711/3597 +f 1711/1711/3598 1695/1695/3598 1712/1712/3598 +f 1710/1710/3599 1693/1693/3599 1712/1712/3599 +f 1712/1712/3600 1693/1693/3600 1711/1711/3600 +f 1709/1709/3601 1710/1710/3601 1712/1712/3601 +f 1695/1695/3602 1709/1709/3602 1712/1712/3602 +f 1713/1713/3603 1714/1714/3603 1715/1715/3603 +f 1716/1716/3604 1717/1717/3604 1718/1718/3604 +f 1716/1716/3605 1719/1719/3605 1717/1717/3605 +f 1719/1719/3606 1720/1720/3606 1717/1717/3606 +f 1717/1717/3607 1720/1720/3607 1718/1718/3607 +f 1718/1718/3608 1720/1720/3608 1721/1721/3608 +f 1718/1718/3609 1721/1721/3610 1716/1716/3611 +f 1716/1716/3611 1721/1721/3610 1719/1719/3612 +f 1719/1719/3613 1722/1722/3614 1723/1723/3615 +f 1720/1720/3616 1724/1724/3617 1725/1725/3618 +f 1723/1723/3615 1724/1724/3617 1719/1719/3613 +f 1719/1719/3613 1724/1724/3617 1720/1720/3616 +f 1725/1725/3618 1726/1726/3619 1720/1720/3616 +f 1720/1720/3616 1726/1726/3619 1721/1721/3620 +f 1721/1721/3620 1726/1726/3619 1722/1722/3614 +f 1721/1721/3620 1722/1722/3614 1719/1719/3613 +f 1727/1727/3621 1723/1723/3621 1722/1722/3621 +f 1727/1727/3622 1722/1722/3623 1713/1713/3624 +f 1713/1713/3624 1722/1722/3623 1726/1726/3625 +f 1713/1713/3626 1726/1726/3627 1725/1725/3628 +f 1713/1713/3626 1725/1725/3628 1714/1714/3629 +f 1714/1714/3630 1725/1725/3630 1724/1724/3630 +f 1714/1714/3631 1724/1724/3631 1715/1715/3631 +f 1715/1715/3632 1724/1724/3632 1723/1723/3632 +f 1715/1715/3633 1723/1723/3633 1727/1727/3633 +f 1727/1727/3634 1713/1713/3634 1728/1728/3634 +f 1728/1728/3635 1713/1713/3635 1729/1729/3635 +f 1715/1715/3636 1727/1727/3636 1728/1728/3636 +f 1729/1729/3637 1715/1715/3637 1728/1728/3637 +f 1713/1713/3638 1715/1715/3638 1729/1729/3638 +f 1730/1730/3639 1731/1731/3639 1732/1732/3639 +f 1733/1733/3640 1734/1734/3640 1730/1730/3640 +f 1735/1735/3641 1736/1736/3641 1737/1737/3641 +f 1736/1736/3642 1738/1738/3642 1737/1737/3642 +f 1737/1737/3643 1738/1738/3643 1739/1739/3643 +f 1737/1737/3644 1739/1739/3644 1735/1735/3644 +f 1735/1735/3645 1739/1739/3645 1740/1740/3645 +f 1735/1735/3646 1740/1740/3646 1736/1736/3646 +f 1736/1736/3647 1740/1740/3647 1738/1738/3647 +f 1738/1738/3648 1741/1741/3649 1739/1739/3650 +f 1739/1739/3650 1741/1741/3649 1742/1742/3651 +f 1738/1738/3652 1743/1743/3652 1741/1741/3652 +f 1740/1740/3653 1744/1744/3654 1743/1743/3655 +f 1740/1740/3653 1742/1742/3651 1744/1744/3654 +f 1739/1739/3650 1742/1742/3651 1740/1740/3653 +f 1740/1740/3653 1743/1743/3655 1738/1738/3656 +f 1730/1730/3657 1743/1743/3657 1731/1731/3657 +f 1731/1731/3658 1743/1743/3658 1744/1744/3658 +f 1731/1731/3659 1744/1744/3659 1732/1732/3659 +f 1732/1732/3660 1744/1744/3660 1742/1742/3660 +f 1732/1732/3661 1742/1742/3661 1733/1733/3661 +f 1733/1733/3662 1742/1742/3663 1741/1741/3664 +f 1733/1733/3662 1741/1741/3664 1734/1734/3665 +f 1734/1734/3666 1741/1741/3667 1743/1743/3668 +f 1734/1734/3666 1743/1743/3668 1730/1730/3669 +f 1732/1732/3670 1733/1733/3670 1745/1745/3670 +f 1730/1730/3671 1732/1732/3671 1746/1746/3671 +f 1746/1746/3672 1732/1732/3672 1745/1745/3672 +f 1733/1733/3673 1730/1730/3673 1745/1745/3673 +f 1745/1745/3674 1730/1730/3674 1746/1746/3674 +f 1747/1747/3675 1748/1748/3675 1749/1749/3675 +f 1750/1750/3676 1751/1751/3676 1752/1752/3676 +f 1752/1752/3677 1753/1753/3677 1754/1754/3677 +f 1752/1752/3678 1754/1754/3679 1750/1750/3680 +f 1750/1750/3680 1754/1754/3679 1755/1755/3681 +f 1755/1755/3682 1756/1756/3683 1750/1750/3684 +f 1750/1750/3684 1756/1756/3683 1751/1751/3685 +f 1756/1756/3686 1753/1753/3686 1751/1751/3686 +f 1751/1751/3687 1753/1753/3687 1752/1752/3687 +f 1756/1756/3688 1757/1757/3689 1753/1753/3690 +f 1753/1753/3690 1758/1758/3691 1754/1754/3692 +f 1753/1753/3690 1759/1759/3693 1758/1758/3691 +f 1756/1756/3688 1760/1760/3694 1757/1757/3689 +f 1754/1754/3692 1758/1758/3691 1755/1755/3695 +f 1753/1753/3690 1757/1757/3689 1759/1759/3693 +f 1755/1755/3696 1760/1760/3694 1756/1756/3688 +f 1747/1747/3697 1759/1759/3697 1757/1757/3697 +f 1747/1747/3698 1757/1757/3698 1748/1748/3698 +f 1748/1748/3699 1757/1757/3699 1760/1760/3699 +f 1748/1748/3700 1760/1760/3700 1749/1749/3700 +f 1749/1749/3701 1760/1760/3702 1761/1761/3703 +f 1761/1761/3703 1760/1760/3702 1755/1755/3704 +f 1761/1761/3705 1755/1755/3706 1758/1758/3707 +f 1761/1761/3705 1758/1758/3707 1762/1762/3708 +f 1762/1762/3709 1758/1758/3709 1759/1759/3709 +f 1762/1762/3710 1759/1759/3710 1747/1747/3710 +f 1749/1749/3711 1761/1761/3711 1763/1763/3711 +f 1747/1747/3712 1749/1749/3713 1764/1764/3714 +f 1764/1764/3714 1749/1749/3713 1763/1763/3715 +f 1762/1762/3716 1747/1747/3716 1764/1764/3716 +f 1761/1761/3717 1762/1762/3718 1763/1763/3719 +f 1763/1763/3719 1762/1762/3718 1764/1764/3720 +f 1765/1765/3721 1766/1766/3721 1767/1767/3721 +f 1767/1767/3722 1768/1768/3722 1769/1769/3722 +f 1770/1770/3723 1771/1771/3723 1772/1772/3723 +f 1772/1772/3724 1773/1773/3724 1774/1774/3724 +f 1772/1772/3725 1774/1774/3725 1770/1770/3725 +f 1770/1770/3726 1774/1774/3726 1775/1775/3726 +f 1770/1770/3727 1775/1775/3727 1771/1771/3727 +f 1771/1771/3728 1775/1775/3728 1773/1773/3728 +f 1771/1771/3729 1773/1773/3729 1772/1772/3729 +f 1773/1773/3730 1776/1776/3731 1774/1774/3732 +f 1773/1773/3730 1777/1777/3733 1776/1776/3731 +f 1775/1775/3734 1777/1777/3733 1773/1773/3730 +f 1775/1775/3734 1778/1778/3735 1777/1777/3733 +f 1774/1774/3732 1776/1776/3731 1779/1779/3736 +f 1775/1775/3734 1780/1780/3737 1778/1778/3735 +f 1774/1774/3732 1780/1780/3737 1775/1775/3734 +f 1774/1774/3732 1779/1779/3736 1780/1780/3737 +f 1767/1767/3738 1777/1777/3739 1768/1768/3740 +f 1768/1768/3741 1777/1777/3742 1778/1778/3743 +f 1768/1768/3741 1778/1778/3743 1769/1769/3744 +f 1769/1769/3745 1778/1778/3746 1765/1765/3747 +f 1765/1765/3747 1778/1778/3746 1780/1780/3748 +f 1765/1765/3749 1780/1780/3750 1779/1779/3751 +f 1765/1765/3749 1779/1779/3751 1766/1766/3752 +f 1766/1766/3753 1779/1779/3754 1767/1767/3755 +f 1767/1767/3755 1779/1779/3754 1776/1776/3756 +f 1767/1767/3738 1776/1776/3757 1777/1777/3739 +f 1769/1769/3758 1765/1765/3759 1781/1781/3760 +f 1782/1782/3761 1769/1769/3758 1781/1781/3760 +f 1767/1767/3762 1769/1769/3762 1782/1782/3762 +f 1765/1765/3763 1767/1767/3763 1781/1781/3763 +f 1781/1781/3764 1767/1767/3764 1782/1782/3764 +f 1783/1783/3765 1784/1784/3766 1785/1785/3767 +f 1785/1785/3768 1786/1786/3768 1787/1787/3768 +f 1783/1783/3765 1788/1788/3769 1784/1784/3766 +f 1783/1783/3765 1787/1787/3770 1788/1788/3769 +f 1789/1789/3771 1790/1790/3772 1791/1791/3773 +f 1792/1792/3774 1793/1793/3774 1794/1794/3774 +f 1794/1794/3775 1793/1793/3775 1791/1791/3775 +f 1791/1791/3776 1793/1793/3777 1789/1789/3778 +f 1789/1789/3778 1793/1793/3777 1795/1795/3779 +f 1789/1789/3780 1795/1795/3781 1790/1790/3782 +f 1790/1790/3782 1795/1795/3781 1792/1792/3783 +f 1790/1790/3784 1792/1792/3784 1794/1794/3784 +f 1795/1795/3785 1796/1796/3786 1797/1797/3787 +f 1792/1792/3788 1798/1798/3789 1793/1793/3790 +f 1795/1795/3785 1797/1797/3787 1792/1792/3788 +f 1793/1793/3790 1799/1799/3791 1795/1795/3785 +f 1795/1795/3785 1799/1799/3791 1796/1796/3786 +f 1792/1792/3788 1800/1800/3792 1798/1798/3789 +f 1792/1792/3788 1797/1797/3787 1800/1800/3792 +f 1793/1793/3790 1798/1798/3789 1799/1799/3791 +f 1786/1786/3793 1798/1798/3794 1787/1787/3795 +f 1787/1787/3795 1798/1798/3794 1800/1800/3796 +f 1787/1787/3797 1800/1800/3797 1788/1788/3797 +f 1788/1788/3798 1800/1800/3798 1797/1797/3798 +f 1788/1788/3799 1797/1797/3800 1796/1796/3801 +f 1788/1788/3799 1796/1796/3801 1784/1784/3802 +f 1784/1784/3803 1796/1796/3803 1799/1799/3803 +f 1784/1784/3804 1799/1799/3804 1785/1785/3804 +f 1785/1785/3805 1799/1799/3806 1798/1798/3807 +f 1785/1785/3805 1798/1798/3807 1786/1786/3808 +f 1787/1787/3809 1783/1783/3809 1801/1801/3809 +f 1785/1785/3810 1787/1787/3810 1801/1801/3810 +f 1783/1783/3811 1785/1785/3811 1801/1801/3811 +f 1794/1794/3812 1791/1791/3773 1790/1790/3772 +f 1802/1802/3813 1803/1803/3813 1804/1804/3813 +f 1804/1804/3814 1805/1805/3814 1806/1806/3814 +f 1807/1807/3815 1808/1808/3816 1809/1809/3817 +f 1809/1809/3817 1810/1810/3818 1807/1807/3815 +f 1810/1810/3819 1811/1811/3819 1812/1812/3819 +f 1810/1810/3820 1812/1812/3820 1807/1807/3820 +f 1812/1812/3821 1813/1813/3821 1807/1807/3821 +f 1807/1807/3822 1813/1813/3822 1808/1808/3822 +f 1808/1808/3823 1813/1813/3823 1814/1814/3823 +f 1808/1808/3824 1814/1814/3824 1809/1809/3824 +f 1809/1809/3825 1814/1814/3826 1811/1811/3827 +f 1809/1809/3825 1811/1811/3827 1810/1810/3828 +f 1814/1814/3829 1815/1815/3830 1816/1816/3831 +f 1812/1812/3832 1817/1817/3833 1818/1818/3834 +f 1813/1813/3835 1819/1819/3836 1815/1815/3830 +f 1813/1813/3835 1815/1815/3830 1814/1814/3829 +f 1818/1818/3834 1819/1819/3836 1812/1812/3832 +f 1812/1812/3832 1819/1819/3836 1813/1813/3835 +f 1814/1814/3829 1816/1816/3831 1811/1811/3837 +f 1811/1811/3837 1817/1817/3833 1812/1812/3832 +f 1816/1816/3831 1817/1817/3833 1811/1811/3837 +f 1803/1803/3838 1817/1817/3839 1816/1816/3840 +f 1803/1803/3838 1816/1816/3840 1804/1804/3841 +f 1804/1804/3842 1816/1816/3843 1815/1815/3844 +f 1804/1804/3842 1815/1815/3844 1805/1805/3845 +f 1805/1805/3846 1815/1815/3846 1819/1819/3846 +f 1805/1805/3847 1819/1819/3847 1806/1806/3847 +f 1806/1806/3848 1819/1819/3849 1818/1818/3850 +f 1806/1806/3848 1818/1818/3850 1802/1802/3851 +f 1802/1802/3852 1818/1818/3853 1817/1817/3854 +f 1802/1802/3852 1817/1817/3854 1803/1803/3855 +f 1804/1804/3856 1806/1806/3856 1820/1820/3856 +f 1821/1821/3857 1804/1804/3857 1820/1820/3857 +f 1802/1802/3858 1804/1804/3858 1821/1821/3858 +f 1806/1806/3859 1802/1802/3860 1820/1820/3861 +f 1820/1820/3861 1802/1802/3860 1821/1821/3862 +f 1822/1822/3863 1823/1823/3863 1824/1824/3863 +f 1825/1825/3864 1826/1826/3864 1822/1822/3864 +f 1827/1827/3865 1828/1828/3865 1829/1829/3865 +f 1828/1828/3866 1830/1830/3866 1831/1831/3866 +f 1828/1828/3867 1831/1831/3868 1829/1829/3869 +f 1829/1829/3869 1831/1831/3868 1832/1832/3870 +f 1832/1832/3871 1833/1833/3872 1829/1829/3873 +f 1829/1829/3873 1833/1833/3872 1827/1827/3874 +f 1833/1833/3875 1830/1830/3875 1827/1827/3875 +f 1827/1827/3876 1830/1830/3876 1828/1828/3876 +f 1831/1831/3877 1834/1834/3878 1832/1832/3879 +f 1830/1830/3880 1835/1835/3881 1831/1831/3877 +f 1831/1831/3877 1835/1835/3881 1834/1834/3878 +f 1833/1833/3882 1836/1836/3883 1837/1837/3884 +f 1833/1833/3882 1837/1837/3884 1830/1830/3885 +f 1830/1830/3886 1837/1837/3886 1835/1835/3886 +f 1832/1832/3879 1836/1836/3883 1833/1833/3882 +f 1832/1832/3879 1834/1834/3878 1836/1836/3883 +f 1826/1826/3887 1835/1835/3888 1822/1822/3889 +f 1822/1822/3889 1835/1835/3888 1837/1837/3890 +f 1822/1822/3891 1837/1837/3891 1823/1823/3891 +f 1823/1823/3892 1837/1837/3892 1836/1836/3892 +f 1823/1823/3893 1836/1836/3893 1824/1824/3893 +f 1824/1824/3894 1836/1836/3894 1834/1834/3894 +f 1824/1824/3895 1834/1834/3895 1825/1825/3895 +f 1825/1825/3896 1834/1834/3896 1835/1835/3896 +f 1825/1825/3897 1835/1835/3897 1826/1826/3897 +f 1822/1822/3898 1824/1824/3898 1838/1838/3898 +f 1825/1825/3899 1822/1822/3899 1839/1839/3899 +f 1839/1839/3900 1822/1822/3900 1838/1838/3900 +f 1824/1824/3901 1825/1825/3902 1838/1838/3903 +f 1838/1838/3903 1825/1825/3902 1839/1839/3904 +f 1840/1840/3905 1841/1841/3905 1842/1842/3905 +f 1843/1843/3906 1844/1844/3907 1845/1845/3908 +f 1846/1846/3909 1847/1847/3910 1844/1844/3911 +f 1844/1844/3911 1847/1847/3910 1845/1845/3912 +f 1845/1845/3913 1847/1847/3914 1843/1843/3915 +f 1843/1843/3915 1847/1847/3914 1848/1848/3916 +f 1843/1843/3917 1848/1848/3918 1849/1849/3919 +f 1843/1843/3917 1849/1849/3919 1850/1850/3920 +f 1850/1850/3921 1849/1849/3922 1844/1844/3923 +f 1849/1849/3922 1846/1846/3924 1844/1844/3923 +f 1848/1848/3925 1851/1851/3926 1849/1849/3927 +f 1847/1847/3928 1852/1852/3929 1853/1853/3930 +f 1854/1854/3931 1852/1852/3929 1846/1846/3932 +f 1846/1846/3932 1852/1852/3929 1847/1847/3928 +f 1849/1849/3927 1854/1854/3931 1846/1846/3932 +f 1849/1849/3927 1851/1851/3926 1854/1854/3931 +f 1847/1847/3928 1853/1853/3930 1848/1848/3925 +f 1848/1848/3925 1853/1853/3930 1851/1851/3926 +f 1855/1855/3933 1852/1852/3933 1854/1854/3933 +f 1855/1855/3934 1854/1854/3934 1840/1840/3934 +f 1840/1840/3935 1854/1854/3935 1851/1851/3935 +f 1840/1840/3936 1851/1851/3936 1841/1841/3936 +f 1841/1841/3937 1851/1851/3937 1853/1853/3937 +f 1841/1841/3938 1853/1853/3938 1842/1842/3938 +f 1842/1842/3939 1853/1853/3939 1852/1852/3939 +f 1842/1842/3940 1852/1852/3940 1855/1855/3940 +f 1840/1840/3941 1842/1842/3941 1856/1856/3941 +f 1855/1855/3942 1840/1840/3943 1857/1857/3944 +f 1857/1857/3944 1840/1840/3943 1856/1856/3945 +f 1842/1842/3946 1855/1855/3946 1857/1857/3946 +f 1856/1856/3947 1842/1842/3947 1857/1857/3947 +f 1850/1850/3948 1844/1844/3907 1843/1843/3906 +f 1858/1858/3949 1859/1859/3949 1860/1860/3949 +f 1860/1860/3950 1861/1861/3950 1862/1862/3950 +f 1863/1863/3951 1864/1864/3952 1865/1865/3953 +f 1864/1864/3954 1866/1866/3955 1867/1867/3956 +f 1866/1866/3955 1868/1868/3957 1867/1867/3956 +f 1867/1867/3958 1868/1868/3959 1865/1865/3960 +f 1865/1865/3960 1868/1868/3959 1869/1869/3961 +f 1865/1865/3962 1869/1869/3963 1863/1863/3964 +f 1869/1869/3963 1870/1870/3965 1863/1863/3964 +f 1870/1870/3966 1866/1866/3967 1863/1863/3968 +f 1863/1863/3968 1866/1866/3967 1864/1864/3969 +f 1869/1869/3970 1871/1871/3971 1870/1870/3972 +f 1870/1870/3972 1871/1871/3971 1872/1872/3973 +f 1866/1866/3974 1873/1873/3975 1868/1868/3976 +f 1868/1868/3976 1874/1874/3977 1869/1869/3970 +f 1869/1869/3970 1874/1874/3977 1871/1871/3971 +f 1873/1873/3975 1874/1874/3977 1868/1868/3976 +f 1866/1866/3974 1875/1875/3978 1873/1873/3975 +f 1870/1870/3972 1872/1872/3973 1866/1866/3974 +f 1866/1866/3974 1872/1872/3973 1875/1875/3978 +f 1861/1861/3979 1875/1875/3980 1862/1862/3981 +f 1862/1862/3982 1875/1875/3983 1872/1872/3984 +f 1862/1862/3982 1872/1872/3984 1858/1858/3985 +f 1858/1858/3986 1872/1872/3987 1859/1859/3988 +f 1859/1859/3988 1872/1872/3987 1871/1871/3989 +f 1859/1859/3990 1871/1871/3991 1860/1860/3992 +f 1860/1860/3992 1871/1871/3991 1874/1874/3993 +f 1860/1860/3994 1874/1874/3995 1861/1861/3996 +f 1861/1861/3996 1874/1874/3995 1873/1873/3997 +f 1861/1861/3979 1873/1873/3998 1875/1875/3980 +f 1858/1858/3999 1860/1860/3999 1876/1876/3999 +f 1876/1876/4000 1860/1860/4000 1877/1877/4000 +f 1862/1862/4001 1858/1858/4001 1877/1877/4001 +f 1877/1877/4002 1858/1858/4002 1876/1876/4002 +f 1860/1860/4003 1862/1862/4003 1877/1877/4003 +f 1867/1867/4004 1865/1865/3953 1864/1864/3952 +f 505/505/5 504/504/5 38/38/5 +f 27/27/5 29/29/5 719/719/5 +f 434/434/5 502/502/5 19/19/5 +f 719/719/5 675/675/5 27/27/5 +f 41/41/16 714/714/4005 703/703/4006 +f 719/719/5 718/718/4007 675/675/5 +f 503/503/5 502/502/5 434/434/5 +f 26/26/5 11/11/5 39/39/5 +f 434/434/5 432/432/5 503/503/5 +f 718/718/4007 677/677/4008 675/675/5 +f 711/711/4009 677/677/4008 718/718/4007 +f 677/677/4008 711/711/4009 679/679/4010 +f 502/502/5 20/20/5 19/19/5 +f 28/28/5 32/32/5 29/29/5 +f 711/711/4009 717/717/4011 679/679/4010 +f 432/432/5 430/430/5 503/503/5 +f 681/681/5 679/679/4010 717/717/4011 +f 716/716/5 681/681/5 717/717/4011 +f 459/459/5 328/328/5 329/329/5 +f 34/34/5 21/21/5 20/20/5 +f 329/329/5 30/30/5 459/459/5 +f 33/33/5 24/24/5 32/32/5 +f 704/704/5 703/703/4006 714/714/4005 +f 26/26/5 39/39/5 36/36/5 +f 37/37/5 30/30/5 329/329/5 +f 504/504/5 430/430/5 38/38/5 +f 715/715/4012 40/40/15 716/716/5 +f 681/681/5 716/716/5 40/40/15 +f 430/430/5 504/504/5 503/503/5 +f 30/30/5 3/3/5 459/459/5 +f 40/40/15 715/715/4012 41/41/16 +f 703/703/4006 1/1/14 41/41/16 +f 38/38/5 37/37/5 505/505/5 +f 40/40/15 1/1/14 30/30/5 +f 16/16/5 33/33/5 36/36/5 +f 1200/1200/4013 1224/1224/2529 1197/1197/4014 +f 1346/1346/4015 1213/1213/4016 1215/1215/4017 +f 1197/1197/4014 1224/1224/2529 1195/1195/4018 +f 1276/1276/573 1272/1272/4019 1274/1274/4020 +f 1271/1271/573 1272/1272/4019 1276/1276/573 +f 1202/1202/4021 1224/1224/2529 1200/1200/4013 +f 1229/1229/573 1231/1231/4022 1337/1337/4023 +f 1314/1314/573 1315/1315/573 1312/1312/573 +f 1276/1276/573 1278/1278/3325 1270/1270/573 +f 1315/1315/573 1339/1339/573 1340/1340/4024 +f 1195/1195/4018 1224/1224/2529 1194/1194/4025 +f 1271/1271/573 1276/1276/573 1270/1270/573 +f 1312/1312/573 1315/1315/573 1191/1191/573 +f 1204/1204/4026 1224/1224/2529 1202/1202/4021 +f 1191/1191/573 1315/1315/573 1340/1340/4024 +f 1302/1302/573 1304/1304/573 1337/1337/4023 +f 1340/1340/4024 1194/1194/4025 1227/1227/4027 +f 1189/1189/4028 1340/1340/4024 1227/1227/4027 +f 1346/1346/2739 1348/1348/2742 1351/1351/4029 +f 1221/1221/4030 1189/1189/4028 1227/1227/4027 +f 1352/1352/4031 1189/1189/4028 1221/1221/4030 +f 1346/1346/4015 1217/1217/4032 1219/1219/4033 +f 1223/1223/4034 1352/1352/4031 1221/1221/4030 +f 1224/1224/2529 1204/1204/4026 1207/1207/4035 +f 1219/1219/4033 1344/1344/4036 1346/1346/4015 +f 1270/1270/573 1278/1278/3325 1279/1279/573 +f 1270/1270/573 1257/1257/573 1268/1268/573 +f 1224/1224/2529 1353/1353/4037 1223/1223/4038 +f 1346/1346/4015 1224/1224/2529 1207/1207/4035 +f 1353/1353/4037 1257/1257/573 1279/1279/573 +f 1351/1351/4039 1257/1257/573 1353/1353/4037 +f 1209/1209/4040 1346/1346/4015 1207/1207/4035 +f 1269/1269/4041 1270/1270/573 1268/1268/573 +f 1337/1337/4023 1231/1231/4022 1341/1341/4042 +f 1268/1268/573 1257/1257/573 1259/1259/573 +f 1270/1270/573 1279/1279/573 1257/1257/573 +f 1349/1349/4043 1351/1351/4043 1348/1348/4043 +f 1225/1225/2531 1227/1227/4027 1194/1194/4025 +f 1350/1350/4044 1349/1349/4045 1341/1341/4042 +f 1346/1346/4015 1209/1209/4040 1211/1211/4046 +f 1231/1231/4022 1350/1350/4044 1341/1341/4042 +f 1224/1224/2529 1225/1225/2531 1194/1194/4025 +f 1337/1337/4023 1341/1341/4042 1344/1344/4036 +f 1219/1219/4033 1337/1337/4023 1344/1344/4036 +f 1224/1224/2529 1346/1346/4015 1351/1351/4039 +f 1189/1189/4028 1191/1191/573 1340/1340/4024 +f 1229/1229/573 1337/1337/4023 1304/1304/573 +f 1261/1261/573 1265/1265/573 1266/1266/573 +f 1266/1266/573 1268/1268/573 1261/1261/573 +f 1353/1353/4037 1224/1224/2529 1351/1351/4039 +f 1346/1346/4015 1211/1211/4046 1213/1213/4016 +f 1304/1304/573 1306/1306/573 1229/1229/573 +f 1268/1268/573 1259/1259/573 1261/1261/573 +f 1264/1264/573 1265/1265/573 1261/1261/573 +f 1346/1346/4015 1215/1215/4017 1217/1217/4032 +f 201/201/4047 199/199/4048 197/197/4049 +f 201/201/4047 197/197/4049 202/202/4050 +f 468/468/4051 471/471/4052 466/466/4053 +f 194/194/4054 204/204/4055 202/202/4050 +f 466/466/4053 471/471/4052 473/473/4056 +f 465/465/4056 466/466/4053 473/473/4056 +f 473/473/4056 475/475/4057 465/465/4056 +f 204/204/4055 194/194/4054 193/193/4058 +f 193/193/4058 206/206/4059 204/204/4055 +f 488/488/4060 465/465/4056 475/475/4057 +f 219/219/4061 206/206/4059 193/193/4058 +f 194/194/4054 202/202/4050 197/197/4049 +f 488/488/4060 476/476/4062 491/491/4063 +f 209/209/4064 206/206/4059 493/493/4065 +f 491/491/4063 493/493/4065 488/488/4060 +f 219/219/4061 493/493/4065 206/206/4059 +f 705/705/4066 209/209/4064 493/493/4065 +f 491/491/4063 476/476/4062 487/487/4067 +f 480/480/4068 487/487/4067 478/478/4069 +f 705/705/1643 851/851/1642 847/847/4070 +f 476/476/4062 488/488/4060 475/475/4057 +f 847/847/4071 845/845/4071 221/221/4071 +f 219/219/4061 488/488/4060 493/493/4065 +f 847/847/4072 221/221/4072 705/705/4072 +f 209/209/4064 705/705/4066 221/221/4058 +f 209/209/4064 221/221/4058 216/216/3225 +f 485/485/4073 487/487/4067 480/480/4068 +f 476/476/4062 478/478/4069 487/487/4067 +f 216/216/3225 213/213/4074 209/209/4064 +f 471/471/4052 468/468/4051 470/470/4075 +f 213/213/4074 211/211/4076 209/209/4064 +f 484/484/4077 485/485/4073 480/480/4068 +f 484/484/4077 480/480/4068 481/481/4078 +f 213/213/4074 216/216/3225 215/215/4079 +f 481/481/4078 482/482/4080 484/484/4077 +f 1359/1359/4081 1360/1360/2798 1232/1232/4082 +f 1354/1354/2800 1252/1252/4083 1355/1355/4084 +f 1321/1321/4085 1301/1301/4086 1367/1367/2825 +f 1232/1232/4082 1360/1360/2798 1239/1239/4087 +f 1228/1228/4088 1226/1226/4089 1308/1308/4090 +f 1366/1366/4091 1228/1228/4088 1308/1308/4090 +f 1345/1345/4092 1343/1343/5 1362/1362/4093 +f 1226/1226/4089 1222/1222/5 1347/1347/4094 +f 1307/1307/4095 1301/1301/4086 1321/1321/4085 +f 1343/1343/5 1361/1361/4096 1362/1362/4093 +f 1239/1239/4087 1361/1361/4096 1232/1232/4082 +f 1361/1361/4096 1343/1343/5 1342/1342/5 +f 1307/1307/4095 1308/1308/4090 1226/1226/4089 +f 1228/1228/4088 1366/1366/4091 1222/1222/5 +f 1226/1226/4089 1301/1301/4086 1307/1307/4095 +f 1360/1360/2798 1354/1354/2800 1355/1355/4084 +f 1222/1222/5 1366/1366/4091 1342/1342/5 +f 1368/1368/4097 1321/1321/4085 1367/1367/2825 +f 1222/1222/5 1342/1342/5 1347/1347/4094 +f 1301/1301/4086 1226/1226/4089 1347/1347/4094 +f 1320/1320/4098 1321/1321/4085 1368/1368/4097 +f 1321/1321/4085 1369/1369/4099 1307/1307/4095 +f 1361/1361/4096 1366/1366/4091 1232/1232/4082 +f 1361/1361/4096 1342/1342/5 1366/1366/4091 +f 1345/1345/4092 1362/1362/4093 1347/1347/4094 +f 1362/1362/4093 1301/1301/4086 1347/1347/4094 +f 1360/1360/2798 1355/1355/4084 1239/1239/4087 +f 1325/1325/2826 1368/1368/4097 1367/1367/2825 +f 1355/1355/4084 1356/1356/4100 1239/1239/4087 +f 1364/1364/4101 1367/1367/2825 1301/1301/4086 +f 1262/1262/4102 1260/1260/2621 1290/1290/2623 +f 1305/1305/4103 1298/1298/4104 1262/1262/4102 +f 1300/1300/2697 1288/1288/2616 1218/1218/2617 +f 1262/1262/4102 1290/1290/2623 1305/1305/4103 +f 1298/1298/4104 1305/1305/4103 1303/1303/573 +f 1277/1277/2703 1275/1275/2718 1310/1310/2716 +f 1255/1255/4105 1254/1254/4105 1267/1267/4105 +f 1300/1300/2697 1298/1298/4104 1303/1303/573 +f 1263/1263/4106 1262/1262/4102 1298/1298/4104 +f 1263/1263/4106 1298/1298/4104 1238/1238/4107 +f 1196/1196/2620 1293/1293/2628 1289/1289/2618 +f 1237/1237/4108 1285/1285/4108 1255/1255/4108 +f 1212/1212/4109 1335/1335/4110 1214/1214/4111 +f 1192/1192/2714 1338/1338/4112 1294/1294/2630 +f 1216/1216/4113 1214/1214/4111 1317/1317/4114 +f 1238/1238/4107 1237/1237/4115 1263/1263/4106 +f 1300/1300/2697 1303/1303/573 1288/1288/2616 +f 1317/1317/4114 1214/1214/4111 1335/1335/4110 +f 463/463/4116 439/439/4117 464/464/4118 +f 464/464/4118 682/682/4119 463/463/4116 +f 429/429/4120 431/431/4121 433/433/4122 +f 438/438/4123 429/429/4120 435/435/4124 +f 429/429/4120 433/433/4122 435/435/4124 +f 464/464/4118 678/678/4125 680/680/4126 +f 436/436/4127 438/438/4123 435/435/4124 +f 464/464/4118 676/676/4128 678/678/4125 +f 437/437/4129 438/438/4123 436/436/4127 +f 429/429/4120 438/438/4123 439/439/4117 +f 464/464/4118 674/674/4130 676/676/4128 +f 464/464/4118 680/680/4126 682/682/4119 +f 464/464/4118 673/673/4131 674/674/4130 +f 428/428/4132 429/429/4120 439/439/4117 +f 463/463/4116 428/428/4132 439/439/4117 +f 1878/1878/4133 1879/1879/4133 1880/1880/4133 +f 1878/1878/4134 1880/1880/4134 1881/1881/4134 +f 1882/1882/4135 1881/1881/4135 1880/1880/4135 +f 1882/1882/4136 1883/1883/4137 1881/1881/4138 +f 1881/1881/4138 1883/1883/4137 1884/1884/4139 +f 1884/1884/4140 1883/1883/4140 1879/1879/4140 +f 1884/1884/4141 1879/1879/4141 1878/1878/4141 +f 1878/1878/573 1881/1881/573 1884/1884/573 +f 1885/1885/4142 1879/1879/4143 1886/1886/4144 +f 1879/1879/4145 1887/1887/4145 1886/1886/4145 +f 1886/1886/4144 1888/1888/4146 1885/1885/4142 +f 1888/1888/4146 1889/1889/4147 1885/1885/4142 +f 1888/1888/4146 1890/1890/4148 1889/1889/4147 +f 1891/1891/4149 1892/1892/4150 1893/1893/4151 +f 1892/1892/4150 1894/1894/4152 1893/1893/4151 +f 1894/1894/4152 1895/1895/4153 1893/1893/4151 +f 1891/1891/4154 1896/1896/4155 1897/1897/4156 +f 1891/1891/4149 1893/1893/4151 1896/1896/4157 +f 1893/1893/4158 1895/1895/4158 1896/1896/4158 +f 1898/1898/4159 1896/1896/4155 1895/1895/4160 +f 1899/1899/4161 1897/1897/4156 1896/1896/4155 +f 1900/1900/4162 1901/1901/4163 1887/1887/4164 +f 1900/1900/4162 1887/1887/4164 1883/1883/4165 +f 1887/1887/4164 1879/1879/4166 1883/1883/4165 +f 1897/1897/4156 1902/1902/4167 1891/1891/4154 +f 1903/1903/4168 1904/1904/4169 1902/1902/4167 +f 1904/1904/4169 1905/1905/4170 1906/1906/4171 +f 1904/1904/4169 1907/1907/4172 1905/1905/4170 +f 1904/1904/4169 1908/1908/4173 1907/1907/4172 +f 1902/1902/4174 1909/1909/4174 1903/1903/4174 +f 1897/1897/4156 1910/1910/4175 1902/1902/4167 +f 1879/1879/4143 1906/1906/4171 1880/1880/4176 +f 1911/1911/4177 1904/1904/4169 1903/1903/4168 +f 1911/1911/4177 1908/1908/4173 1904/1904/4169 +f 1880/1880/4176 1906/1906/4171 1905/1905/4170 +f 1912/1912/4178 1908/1908/4173 1911/1911/4177 +f 1910/1910/4175 1897/1897/4156 1913/1913/4179 +f 1914/1914/4180 1902/1902/4167 1910/1910/4175 +f 1914/1914/4180 1909/1909/4181 1902/1902/4167 +f 1882/1882/4182 1880/1880/4176 1905/1905/4170 +f 1915/1915/4183 1903/1903/4168 1916/1916/4184 +f 1911/1911/4177 1903/1903/4168 1915/1915/4183 +f 1882/1882/4182 1905/1905/4170 1900/1900/4162 +f 1917/1917/4185 1914/1914/4180 1910/1910/4175 +f 1918/1918/4186 1905/1905/4170 1907/1907/4187 +f 1918/1918/4186 1912/1912/4178 1911/1911/4177 +f 1917/1917/4185 1913/1913/4179 1919/1919/4188 +f 1917/1917/4185 1910/1910/4175 1913/1913/4179 +f 1920/1920/4189 1914/1914/4180 1917/1917/4185 +f 1918/1918/4186 1911/1911/4177 1915/1915/4183 +f 1898/1898/4159 1919/1919/4188 1896/1896/4155 +f 1898/1898/4159 1921/1921/4190 1919/1919/4188 +f 1918/1918/4186 1922/1922/4191 1905/1905/4170 +f 1915/1915/4183 1923/1923/4192 1918/1918/4186 +f 1916/1916/4184 1920/1920/4189 1915/1915/4183 +f 1919/1919/4188 1921/1921/4190 1917/1917/4185 +f 1905/1905/4170 1922/1922/4191 1900/1900/4162 +f 1920/1920/4189 1924/1924/4193 1915/1915/4183 +f 1925/1925/4194 1917/1917/4185 1921/1921/4190 +f 1925/1925/4194 1920/1920/4189 1917/1917/4185 +f 1924/1924/4193 1920/1920/4189 1925/1925/4194 +f 1923/1923/4192 1915/1915/4183 1924/1924/4193 +f 1922/1922/4191 1918/1918/4186 1923/1923/4192 +f 1901/1901/4163 1900/1900/4162 1922/1922/4195 +f 1926/1926/4196 1927/1927/4197 1928/1928/4198 +f 1928/1928/4198 1927/1927/4197 1929/1929/4199 +f 1930/1930/4200 1928/1928/4198 1929/1929/4199 +f 1931/1931/4201 1932/1932/4202 1929/1929/4199 +f 1929/1929/4199 1932/1932/4202 1930/1930/4200 +f 1933/1933/4203 1934/1934/4204 1931/1931/4201 +f 1935/1935/4205 1936/1936/4206 1933/1933/4203 +f 1937/1937/4207 1933/1933/4203 1936/1936/4206 +f 1934/1934/4204 1933/1933/4203 1937/1937/4207 +f 1932/1932/4202 1931/1931/4201 1934/1934/4204 +f 1938/1938/4208 1932/1932/4202 1934/1934/4204 +f 1939/1939/4209 1940/1940/4210 1941/1941/4211 +f 1939/1939/4209 1942/1942/4212 1940/1940/4210 +f 1943/1943/4213 1944/1944/4214 1942/1942/4212 +f 1939/1939/4209 1943/1943/4213 1942/1942/4212 +f 1945/1945/4215 1946/1946/4216 1942/1942/4212 +f 1945/1945/4215 1942/1942/4212 1944/1944/4214 +f 1926/1926/4196 1947/1947/4217 1948/1948/4218 +f 1928/1928/4198 1949/1949/4219 1926/1926/4196 +f 1926/1926/4196 1949/1949/4219 1947/1947/4217 +f 1947/1947/4217 1950/1950/4220 1951/1951/4221 +f 1951/1951/4221 1948/1948/4218 1947/1947/4217 +f 1952/1952/4222 1945/1945/4215 1953/1953/4223 +f 1953/1953/4223 1945/1945/4215 1944/1944/4214 +f 1954/1954/4224 1955/1955/4225 1953/1953/4223 +f 1956/1956/4226 1957/1957/4227 1958/1958/4228 +f 1956/1956/4226 1954/1954/4224 1957/1957/4227 +f 1955/1955/4225 1954/1954/4224 1956/1956/4226 +f 1959/1959/4229 1953/1953/4223 1955/1955/4225 +f 1955/1955/4225 1956/1956/4226 1960/1960/4230 +f 1953/1953/4223 1959/1959/4229 1952/1952/4222 +f 1952/1952/4231 1959/1959/4232 1961/1961/4233 +f 1957/1957/4227 1948/1948/4218 1962/1962/4234 +f 1962/1962/4234 1951/1951/4221 1963/1963/4235 +f 1962/1962/4234 1948/1948/4218 1951/1951/4221 +f 1957/1957/4227 1962/1962/4234 1958/1958/4228 +f 1964/1964/4236 1965/1965/4237 1966/1966/4238 +f 1964/1964/4236 1967/1967/4239 1965/1965/4237 +f 1964/1964/4236 1968/1968/4240 1967/1967/4239 +f 1964/1964/4236 1969/1969/4241 1968/1968/4240 +f 1964/1964/4236 1970/1970/4242 1969/1969/4241 +f 1964/1964/4236 1971/1971/4243 1970/1970/4242 +f 1935/1935/4205 1972/1972/4244 1973/1973/4245 +f 1935/1935/4205 1974/1974/4246 1972/1972/4244 +f 1935/1935/4205 1975/1975/4247 1974/1974/4246 +f 1935/1935/4205 1976/1976/4248 1975/1975/4247 +f 1935/1935/4205 1977/1977/4249 1976/1976/4248 +f 1935/1935/4205 1978/1978/4250 1977/1977/4249 +f 1973/1973/4245 1979/1979/4251 1935/1935/4205 +f 1973/1973/4245 1980/1980/4252 1979/1979/4251 +f 1981/1981/4253 1964/1964/4236 1982/1982/4254 +f 1981/1981/4253 1983/1983/4255 1964/1964/4236 +f 1984/1984/4256 1982/1982/4254 1985/1985/4257 +f 1981/1981/4253 1982/1982/4254 1986/1986/4258 +f 1964/1964/4236 1983/1983/4255 1987/1987/4259 +f 1988/1988/4260 1989/1989/4261 1990/1990/4262 +f 1988/1988/4260 1991/1991/4263 1989/1989/4261 +f 1937/1937/4264 1992/1992/4265 1934/1934/4204 +f 1937/1937/4264 1993/1993/4266 1992/1992/4265 +f 1994/1994/4267 1989/1989/4261 1995/1995/4268 +f 1996/1996/4269 1997/1997/4270 1998/1998/4271 +f 1999/1999/4272 1990/1990/4262 1997/1997/4270 +f 2000/2000/4273 1990/1990/4262 1999/1999/4272 +f 1995/1995/4268 1989/1989/4261 1991/1991/4263 +f 1995/1995/4268 2001/2001/4274 2002/2002/4275 +f 2003/2003/4276 2001/2001/4274 1995/1995/4268 +f 2004/2004/4277 2005/2005/4278 1960/1960/4230 +f 2005/2005/4278 1961/1961/4233 1960/1960/4230 +f 2005/2005/4278 1991/1991/4263 1961/1961/4233 +f 1941/1941/4211 1988/1988/4260 1990/1990/4262 +f 1998/1998/4271 1990/1990/4262 1989/1989/4261 +f 1939/1939/4209 1990/1990/4262 2006/2006/4279 +f 1939/1939/4209 1941/1941/4211 1990/1990/4262 +f 2006/2006/4279 2000/2000/4273 2007/2007/4280 +f 1990/1990/4262 2000/2000/4273 2006/2006/4279 +f 1997/1997/4270 1990/1990/4262 1998/1998/4271 +f 1994/1994/4267 2008/2008/4281 1998/1998/4271 +f 1989/1989/4261 1994/1994/4267 1998/1998/4271 +f 1996/1996/4269 1998/1998/4271 2009/2009/4282 +f 2008/2008/4281 1994/1994/4267 2010/2010/4283 +f 1994/1994/4267 2011/2011/4284 2012/2012/4285 +f 2003/2003/4276 2013/2013/4286 2014/2014/4287 +f 2015/2015/4288 2013/2013/4286 2003/2003/4276 +f 2016/2016/4289 2005/2005/4278 2004/2004/4277 +f 2005/2005/4278 1995/1995/4268 1991/1991/4263 +f 2005/2005/4278 2003/2003/4276 1995/1995/4268 +f 2011/2011/4284 1995/1995/4268 2002/2002/4275 +f 1994/1994/4267 1995/1995/4268 2011/2011/4284 +f 1956/1956/4226 2004/2004/4277 1960/1960/4230 +f 1928/1928/4198 2016/2016/4289 2004/2004/4277 +f 1930/1930/4290 2016/2016/4289 1928/1928/4198 +f 2017/2017/4291 2016/2016/4289 1930/1930/4290 +f 2017/2017/4291 1992/1992/4265 2016/2016/4289 +f 1938/1938/4208 1992/1992/4265 2017/2017/4291 +f 1934/1934/4204 1992/1992/4265 1938/1938/4208 +f 1936/1936/4292 2018/2018/4293 1937/1937/4264 +f 2019/2019/4294 1949/1949/4219 1928/1928/4198 +f 2004/2004/4277 2019/2019/4294 1928/1928/4198 +f 1956/1956/4226 1958/1958/4295 2004/2004/4277 +f 2004/2004/4277 2020/2020/4296 2019/2019/4294 +f 2004/2004/4277 1958/1958/4295 2020/2020/4296 +f 2021/2021/4297 1992/1992/4265 1993/1993/4266 +f 2015/2015/4288 1992/1992/4265 2021/2021/4297 +f 2005/2005/4278 2016/2016/4289 2015/2015/4288 +f 2016/2016/4289 1992/1992/4265 2015/2015/4288 +f 2005/2005/4278 2015/2015/4288 2003/2003/4276 +f 1988/1988/4260 1952/1952/4231 1991/1991/4263 +f 1988/1988/4260 1945/1945/4215 1952/1952/4231 +f 1961/1961/4233 1991/1991/4263 1952/1952/4231 +f 2003/2003/4276 2022/2022/4298 2001/2001/4274 +f 2014/2014/4287 2022/2022/4298 2003/2003/4276 +f 2023/2023/4299 2012/2012/4285 2024/2024/4300 +f 2023/2023/4299 2025/2025/4301 2012/2012/4285 +f 1994/1994/4267 2026/2026/4302 2010/2010/4283 +f 2012/2012/4285 2026/2026/4302 1994/1994/4267 +f 2025/2025/4301 2026/2026/4302 2012/2012/4285 +f 2008/2008/4281 2009/2009/4282 1998/1998/4271 +f 2009/2009/4282 2027/2027/4303 1996/1996/4269 +f 1999/1999/4272 1997/1997/4270 2028/2028/4304 +f 2029/2029/4305 2006/2006/4279 2007/2007/4280 +f 1946/1946/4216 1945/1945/4215 1988/1988/4260 +f 1941/1941/4211 1946/1946/4216 1988/1988/4260 +f 1961/1961/4233 1955/1955/4225 1960/1960/4230 +f 2019/2019/4294 1963/1963/4235 1951/1951/4221 +f 2020/2020/4296 1963/1963/4235 2019/2019/4294 +f 1951/1951/4221 1950/1950/4220 2019/2019/4294 +f 2018/2018/4293 1993/1993/4266 1937/1937/4264 +f 2021/2021/4297 2030/2030/4306 2015/2015/4288 +f 2031/2031/4307 2030/2030/4306 2021/2021/4297 +f 2015/2015/4288 2030/2030/4306 2032/2032/4308 +f 2032/2032/4308 2013/2013/4286 2015/2015/4288 +f 1966/1966/4238 2033/2033/4309 2034/2034/4310 +f 2034/2034/4310 1964/1964/4236 1966/1966/4238 +f 2035/2035/4311 2034/2034/4310 2036/2036/4312 +f 1978/1978/4250 1935/1935/4205 1933/1933/4203 +f 2037/2037/4313 1931/1931/4201 2038/2038/4314 +f 1933/1933/4203 1931/1931/4201 2037/2037/4313 +f 2038/2038/4314 1931/1931/4201 1929/1929/4199 +f 2038/2038/4314 1929/1929/4199 2039/2039/4315 +f 2039/2039/4315 1929/1929/4199 1927/1927/4316 +f 1927/1927/4316 1926/1926/4196 2039/2039/4315 +f 2040/2040/4317 2041/2041/4318 2042/2042/4319 +f 2040/2040/4317 2043/2043/4320 2044/2044/4321 +f 2040/2040/4317 2042/2042/4319 2043/2043/4320 +f 2045/2045/4322 2044/2044/4321 2043/2043/4320 +f 2044/2044/4321 2045/2045/4322 2046/2046/4323 +f 2046/2046/4323 2045/2045/4322 2047/2047/4324 +f 2035/2035/4311 2047/2047/4324 2048/2048/4325 +f 2046/2046/4323 2047/2047/4324 2035/2035/4311 +f 2048/2048/4325 2034/2034/4310 2035/2035/4311 +f 2039/2039/4315 1926/1926/4196 2049/2049/4326 +f 1900/1900/4162 1883/1883/4165 1882/1882/4182 +f 1906/1906/4171 1879/1879/4143 1885/1885/4142 +f 1919/1919/4188 1899/1899/4161 1896/1896/4155 +f 1898/1898/4159 2050/2050/4327 1921/1921/4190 +f 2051/2051/4328 1894/1894/4329 1892/1892/4330 +f 2052/2052/4331 2053/2053/4331 1889/1889/4331 +f 2052/2052/4332 2054/2054/4333 2053/2053/4334 +f 2055/2055/4335 2054/2054/4333 2052/2052/4332 +f 2056/2056/4336 2054/2054/4336 2055/2055/4336 +f 2056/2056/4337 2057/2057/4337 2054/2054/4337 +f 2058/2058/4338 2057/2057/4338 2056/2056/4338 +f 2058/2058/4339 1892/1892/4339 2057/2057/4339 +f 2059/2059/4340 2014/2014/4341 2060/2060/4342 +f 2059/2059/4340 2061/2061/4343 2014/2014/4341 +f 2060/2060/4342 2014/2014/4341 2013/2013/4344 +f 1889/1889/4345 1890/1890/4346 2062/2062/4347 +f 2013/2013/4344 2063/2063/4348 2060/2060/4342 +f 2057/2057/4349 1891/1891/4154 1902/1902/4167 +f 2054/2054/4350 1902/1902/4167 1904/1904/4169 +f 2057/2057/4349 1902/1902/4167 2054/2054/4350 +f 2057/2057/4349 1892/1892/4351 1891/1891/4154 +f 1971/1971/4243 1964/1964/4236 1987/1987/4259 +f 1948/1948/4218 2064/2064/4352 1926/1926/4196 +f 2049/2049/4326 1926/1926/4196 2064/2064/4352 +f 2054/2054/4350 1906/1906/4171 2053/2053/4353 +f 1904/1904/4169 1906/1906/4171 2054/2054/4350 +f 1885/1885/4142 2053/2053/4353 1906/1906/4171 +f 1885/1885/4142 1889/1889/4354 2053/2053/4353 +f 2065/2065/4355 2066/2066/4356 2067/2067/4357 +f 2068/2068/4358 2069/2069/4359 2070/2070/4360 +f 2067/2067/4357 2066/2066/4356 2071/2071/4361 +f 2071/2071/4361 2066/2066/4356 2069/2069/4359 +f 2072/2072/4362 2073/2073/4363 2074/2074/4364 +f 2069/2069/4359 2068/2068/4358 2071/2071/4361 +f 2074/2074/4364 2075/2075/4365 2072/2072/4362 +f 2072/2072/4362 2075/2075/4365 2067/2067/4357 +f 2065/2065/4355 2067/2067/4357 2075/2075/4365 +f 2074/2074/4366 2073/2073/4366 2076/2076/4366 +f 2075/2075/4367 2074/2074/4367 2077/2077/4367 +f 2075/2075/4368 2077/2077/4368 2065/2065/4368 +f 2065/2065/4369 2077/2077/4369 2078/2078/4369 +f 2065/2065/4370 2078/2078/4370 2066/2066/4370 +f 2079/2079/4371 2080/2080/4372 2070/2070/4373 +f 2081/2081/4374 2082/2082/4375 2083/2083/4376 +f 2081/2081/4374 2084/2084/4377 2085/2085/4378 +f 2086/2086/4379 2082/2082/4375 2085/2085/4378 +f 2082/2082/4375 2081/2081/4374 2085/2085/4378 +f 2086/2086/4379 2085/2085/4378 2087/2087/4380 +f 2088/2088/4381 2084/2084/4377 2081/2081/4374 +f 2089/2089/4382 2084/2084/4377 2090/2090/4383 +f 2084/2084/4377 2088/2088/4381 2090/2090/4383 +f 2089/2089/4382 2090/2090/4383 2067/2067/4357 +f 2067/2067/4357 2090/2090/4383 2072/2072/4362 +f 2091/2091/4384 2092/2092/4385 2093/2093/4386 +f 2094/2094/4387 2095/2095/4388 2096/2096/4389 +f 2068/2068/4358 2097/2097/4390 2098/2098/4391 +f 2096/2096/4392 2095/2095/4392 2099/2099/4392 +f 2100/2100/4393 2101/2101/4394 2099/2099/4395 +f 2102/2102/4396 2096/2096/4389 2101/2101/4394 +f 2099/2099/4395 2101/2101/4394 2096/2096/4389 +f 2096/2096/4389 2102/2102/4396 2103/2103/4397 +f 2103/2103/4397 2102/2102/4396 2093/2093/4386 +f 2091/2091/4384 2093/2093/4386 2104/2104/4398 +f 2104/2104/4398 2087/2087/4380 2105/2105/4399 +f 2091/2091/4384 2104/2104/4398 2105/2105/4399 +f 2105/2105/4399 2087/2087/4380 2085/2085/4378 +f 2092/2092/4385 2106/2106/4400 2093/2093/4386 +f 2093/2093/4386 2106/2106/4400 2103/2103/4397 +f 2103/2103/4397 2107/2107/4401 2096/2096/4389 +f 2091/2091/4384 2108/2108/4402 2092/2092/4385 +f 2106/2106/4400 2107/2107/4401 2103/2103/4397 +f 2107/2107/4401 2094/2094/4387 2096/2096/4389 +f 2085/2085/4378 2109/2109/4403 2105/2105/4399 +f 2105/2105/4399 2109/2109/4403 2091/2091/4384 +f 2091/2091/4384 2109/2109/4403 2108/2108/4402 +f 2085/2085/4378 2089/2089/4382 2109/2109/4403 +f 2110/2110/4404 2099/2099/4405 2095/2095/4406 +f 2110/2110/4404 2095/2095/4406 2097/2097/4390 +f 2110/2110/4404 2097/2097/4390 2068/2068/4358 +f 2106/2106/4400 2111/2111/4407 2107/2107/4401 +f 2107/2107/4401 2071/2071/4361 2094/2094/4387 +f 2109/2109/4403 2111/2111/4407 2108/2108/4402 +f 2089/2089/4382 2067/2067/4357 2109/2109/4403 +f 2109/2109/4403 2067/2067/4357 2111/2111/4407 +f 2111/2111/4407 2071/2071/4361 2107/2107/4401 +f 2071/2071/4361 2098/2098/4391 2094/2094/4387 +f 2071/2071/4361 2111/2111/4407 2067/2067/4357 +f 2071/2071/4361 2068/2068/4358 2098/2098/4391 +f 2112/2112/4408 2099/2099/4405 2110/2110/4404 +f 2112/2112/4409 2068/2068/4410 2113/2113/4411 +f 2068/2068/4410 2112/2112/4409 2110/2110/4412 +f 2113/2113/4411 2070/2070/4413 2080/2080/4414 +f 2068/2068/4410 2070/2070/4413 2113/2113/4411 +f 2114/2114/4415 2073/2073/4363 2072/2072/4362 +f 2090/2090/4416 2083/2083/4416 2072/2072/4416 +f 2072/2072/4362 2083/2083/4376 2115/2115/4417 +f 2114/2114/4415 2072/2072/4362 2115/2115/4417 +f 2082/2082/4375 2115/2115/4417 2083/2083/4376 +f 2116/2116/4418 2085/2085/4418 2117/2117/4418 +f 2116/2116/4419 2089/2089/4419 2085/2085/4419 +f 2118/2118/4420 2089/2089/4420 2116/2116/4420 +f 2118/2118/4421 2084/2084/4421 2089/2089/4421 +f 2084/2084/4422 2118/2118/4422 2117/2117/4422 +f 2117/2117/4423 2085/2085/4423 2084/2084/4423 +f 2108/2108/4424 2119/2119/4424 2120/2120/4424 +f 2108/2108/4425 2120/2120/4425 2092/2092/4425 +f 2120/2120/4426 2106/2106/4426 2092/2092/4426 +f 2121/2121/4427 2106/2106/4428 2120/2120/4429 +f 2121/2121/4427 2111/2111/4430 2106/2106/4428 +f 2119/2119/4431 2111/2111/4432 2121/2121/4433 +f 2119/2119/4431 2108/2108/4434 2111/2111/4432 +f 2122/2122/4435 2095/2095/4435 2123/2123/4435 +f 2095/2095/4436 2122/2122/4437 2097/2097/4438 +f 2097/2097/4438 2122/2122/4437 2124/2124/4439 +f 2097/2097/4440 2124/2124/4441 2098/2098/4442 +f 2098/2098/4442 2124/2124/4441 2125/2125/4443 +f 2125/2125/4444 2094/2094/4445 2098/2098/4446 +f 2123/2123/4447 2094/2094/4445 2125/2125/4444 +f 2123/2123/4448 2095/2095/4448 2094/2094/4448 +f 2126/2126/4449 2083/2083/4449 2090/2090/4449 +f 2083/2083/4450 2126/2126/4450 2081/2081/4450 +f 2081/2081/4451 2126/2126/4451 2127/2127/4451 +f 2128/2128/4452 2081/2081/4452 2127/2127/4452 +f 2128/2128/4453 2088/2088/4453 2081/2081/4453 +f 2129/2129/4454 2088/2088/4454 2128/2128/4454 +f 2129/2129/4455 2090/2090/4455 2088/2088/4455 +f 2126/2126/4456 2090/2090/4456 2129/2129/4456 +f 2118/2118/573 2116/2116/573 2117/2117/573 +f 2074/2074/4457 2069/2069/4359 2066/2066/4356 +f 2069/2069/4359 2076/2076/4458 2079/2079/4459 +f 2074/2074/4457 2078/2078/4460 2077/2077/4461 +f 2066/2066/4356 2078/2078/4460 2074/2074/4457 +f 2074/2074/4457 2076/2076/4458 2069/2069/4359 +f 2079/2079/4459 2070/2070/4360 2069/2069/4359 +f 2120/2120/573 2119/2119/573 2121/2121/573 +f 2122/2122/573 2123/2123/573 2125/2125/573 +f 2125/2125/573 2124/2124/573 2122/2122/573 +f 2127/2127/573 2126/2126/573 2128/2128/573 +f 2128/2128/573 2126/2126/573 2129/2129/573 +f 2130/2130/4462 2100/2100/4463 2131/2131/4464 +f 2131/2131/4464 2100/2100/4463 2132/2132/4465 +f 2100/2100/4463 2133/2133/4466 2132/2132/4465 +f 2133/2133/4466 2100/2100/4463 2134/2134/4467 +f 2099/2099/4468 2134/2134/4467 2100/2100/4463 +f 2099/2099/4468 2135/2135/4469 2134/2134/4467 +f 2099/2099/4468 2136/2136/4470 2135/2135/4469 +f 2064/2064/4471 2086/2086/4379 2049/2049/4472 +f 2064/2064/4471 2137/2137/4473 2086/2086/4379 +f 2138/2138/4474 2099/2099/4468 2112/2112/4475 +f 2139/2139/4476 2099/2099/4468 2138/2138/4474 +f 2136/2136/4470 2099/2099/4468 2139/2139/4476 +f 2138/2138/4474 2112/2112/4475 2140/2140/4477 +f 2140/2140/4477 2113/2113/4478 2141/2141/4479 +f 2140/2140/4477 2112/2112/4475 2113/2113/4478 +f 2113/2113/4478 2142/2142/4480 2141/2141/4479 +f 2113/2113/4478 2143/2143/4481 2142/2142/4480 +f 2080/2080/4372 2143/2143/4481 2113/2113/4478 +f 2144/2144/4482 2076/2076/4483 2073/2073/4484 +f 2145/2145/4485 2076/2076/4483 2144/2144/4482 +f 2145/2145/4485 2079/2079/4371 2076/2076/4483 +f 2146/2146/4486 2079/2079/4371 2145/2145/4485 +f 2147/2147/4487 2079/2079/4371 2146/2146/4486 +f 2148/2148/4488 2079/2079/4371 2147/2147/4487 +f 2149/2149/4489 2079/2079/4371 2148/2148/4488 +f 2149/2149/4489 2080/2080/4372 2079/2079/4371 +f 2143/2143/4481 2080/2080/4372 2149/2149/4489 +f 2073/2073/4484 2150/2150/4490 2144/2144/4482 +f 2151/2151/4491 2073/2073/4484 2114/2114/4492 +f 2150/2150/4490 2073/2073/4484 2151/2151/4491 +f 2151/2151/4491 2114/2114/4492 2115/2115/4417 +f 2152/2152/4493 2115/2115/4417 2153/2153/4494 +f 2151/2151/4491 2115/2115/4417 2152/2152/4493 +f 2153/2153/4494 2115/2115/4417 2154/2154/4495 +f 2155/2155/4496 2082/2082/4375 2086/2086/4379 +f 2156/2156/4497 2082/2082/4375 2155/2155/4496 +f 2156/2156/4497 2115/2115/4417 2082/2082/4375 +f 2154/2154/4495 2115/2115/4417 2156/2156/4497 +f 2155/2155/4496 2086/2086/4379 2137/2137/4473 +f 2100/2100/4463 2157/2157/4498 2158/2158/4499 +f 2130/2130/4462 2157/2157/4498 2100/2100/4463 +f 2156/2156/573 2155/2155/573 2159/2159/573 +f 2133/2133/573 2134/2134/573 2160/2160/573 +f 2132/2132/573 2133/2133/573 2160/2160/573 +f 2131/2131/573 2132/2132/573 2160/2160/573 +f 2136/2136/573 2139/2139/573 2161/2161/573 +f 2161/2161/573 2160/2160/573 2136/2136/573 +f 2147/2147/573 2146/2146/573 2162/2162/573 +f 2140/2140/573 2141/2141/573 2161/2161/573 +f 2152/2152/573 2153/2153/573 2159/2159/573 +f 2137/2137/573 2064/2064/573 2159/2159/573 +f 2158/2158/4500 2157/2157/4501 2160/2160/4502 +f 2160/2160/4502 2163/2163/4503 2158/2158/4500 +f 2130/2130/573 2131/2131/573 2160/2160/573 +f 2155/2155/573 2137/2137/573 2159/2159/573 +f 2143/2143/573 2149/2149/573 2162/2162/573 +f 2064/2064/4504 2049/2049/4505 2164/2164/4506 +f 2164/2164/4506 2159/2159/4507 2064/2064/4504 +f 2139/2139/573 2138/2138/573 2161/2161/573 +f 2151/2151/573 2152/2152/573 2159/2159/573 +f 2150/2150/573 2151/2151/573 2159/2159/573 +f 2159/2159/573 2162/2162/573 2150/2150/573 +f 2144/2144/573 2150/2150/573 2162/2162/573 +f 2141/2141/573 2142/2142/573 2161/2161/573 +f 2154/2154/573 2156/2156/573 2159/2159/573 +f 2157/2157/573 2130/2130/573 2160/2160/573 +f 2135/2135/573 2136/2136/573 2160/2160/573 +f 2146/2146/573 2145/2145/573 2162/2162/573 +f 2153/2153/573 2154/2154/573 2159/2159/573 +f 2149/2149/573 2148/2148/573 2162/2162/573 +f 2148/2148/573 2147/2147/573 2162/2162/573 +f 2145/2145/573 2144/2144/573 2162/2162/573 +f 2142/2142/573 2143/2143/573 2162/2162/573 +f 2162/2162/573 2161/2161/573 2142/2142/573 +f 2134/2134/573 2135/2135/573 2160/2160/573 +f 2138/2138/573 2140/2140/573 2161/2161/573 +f 2161/2161/4508 2162/2162/4509 2165/2165/4510 +f 2165/2165/4510 2166/2166/4511 2161/2161/4508 +f 2164/2164/4512 2167/2167/4513 2159/2159/4514 +f 2160/2160/4515 2161/2161/4516 2166/2166/4517 +f 2166/2166/4517 2163/2163/4518 2160/2160/4515 +f 2162/2162/4519 2159/2159/4514 2167/2167/4513 +f 2167/2167/4513 2165/2165/4520 2162/2162/4519 +f 2164/2164/4521 2049/2049/4522 2086/2086/4523 +f 2165/2165/4524 2167/2167/4525 2087/2087/4526 +f 2086/2086/4523 2087/2087/4526 2167/2167/4525 +f 2163/2163/4527 2101/2101/4528 2100/2100/4529 +f 2166/2166/4530 2165/2165/4524 2087/2087/4526 +f 2166/2166/4530 2087/2087/4526 2104/2104/4531 +f 2104/2104/4531 2093/2093/4532 2166/2166/4530 +f 2100/2100/4529 2158/2158/4533 2163/2163/4527 +f 2102/2102/4534 2101/2101/4528 2166/2166/4530 +f 2101/2101/4528 2163/2163/4527 2166/2166/4530 +f 2166/2166/4530 2093/2093/4532 2102/2102/4534 +f 2167/2167/4525 2164/2164/4521 2086/2086/4523 +f 2168/2168/573 2169/2169/573 2170/2170/573 +f 2168/2168/4535 1908/1908/4535 1912/1912/4535 +f 2170/2170/4536 1908/1908/4536 2168/2168/4536 +f 1908/1908/4537 2170/2170/4537 1907/1907/4537 +f 2169/2169/4538 1907/1907/4538 2170/2170/4538 +f 2169/2169/4539 1918/1918/4539 1907/1907/4539 +f 1918/1918/4540 2169/2169/4540 2168/2168/4540 +f 1918/1918/4541 2168/2168/4541 1912/1912/4541 +f 2171/2171/573 2172/2172/573 2173/2173/573 +f 2172/2172/4542 1914/1914/4542 1920/1920/4542 +f 2171/2171/4543 1914/1914/4543 2172/2172/4543 +f 2171/2171/4544 1909/1909/4544 1914/1914/4544 +f 2171/2171/4545 1903/1903/4546 1909/1909/4547 +f 1903/1903/4546 2171/2171/4545 2173/2173/4548 +f 2173/2173/4549 1916/1916/4549 1903/1903/4549 +f 1916/1916/4550 2173/2173/4551 2172/2172/4552 +f 2172/2172/4552 1920/1920/4553 1916/1916/4550 +f 2051/2051/4554 1892/1892/4555 2058/2058/4556 +f 2051/2051/4554 2058/2058/4556 2062/2062/4557 +f 2056/2056/4558 2055/2055/4559 1889/1889/4560 +f 2062/2062/4557 2058/2058/4556 2056/2056/4558 +f 2062/2062/4557 2056/2056/4558 1889/1889/4560 +f 2055/2055/4559 2052/2052/4561 1889/1889/4560 +f 2174/2174/573 2175/2175/573 2176/2176/573 +f 1919/1919/4562 2175/2175/4562 1899/1899/4562 +f 1899/1899/4563 2175/2175/4563 2174/2174/4563 +f 1899/1899/4564 2174/2174/4564 1897/1897/4564 +f 2174/2174/4565 1913/1913/4566 1897/1897/4567 +f 1913/1913/4566 2174/2174/4565 2176/2176/4568 +f 1913/1913/4569 2176/2176/4569 2175/2175/4569 +f 1913/1913/4570 2175/2175/4570 1919/1919/4570 +f 1978/1978/4571 2177/2177/4572 2050/2050/4573 +f 2050/2050/4573 2177/2177/4572 2178/2178/4574 +f 2179/2179/573 2180/2180/573 2181/2181/573 +f 2036/2036/4575 1966/1966/4576 1901/1901/4577 +f 1890/1890/4346 2182/2182/4578 2183/2183/4579 +f 2184/2184/4580 1894/1894/4329 2185/2185/4581 +f 2185/2185/4581 1894/1894/4329 2051/2051/4328 +f 2185/2185/4581 2051/2051/4328 2186/2186/4582 +f 2186/2186/4582 2051/2051/4328 2179/2179/4583 +f 2179/2179/4583 2051/2051/4328 2180/2180/4584 +f 2180/2180/4584 2051/2051/4328 2187/2187/4585 +f 2187/2187/4585 2051/2051/4328 2188/2188/4586 +f 2188/2188/4586 2051/2051/4328 2062/2062/4347 +f 2188/2188/4586 2062/2062/4347 2189/2189/4587 +f 2189/2189/4587 2062/2062/4347 2190/2190/4588 +f 2190/2190/4588 2062/2062/4347 2183/2183/4579 +f 2183/2183/4579 2062/2062/4347 1890/1890/4346 +f 1894/1894/4329 2184/2184/4580 2191/2191/4589 +f 1894/1894/4329 2191/2191/4589 1895/1895/4590 +f 1895/1895/4590 2191/2191/4589 2192/2192/4591 +f 2193/2193/4592 1895/1895/4590 2192/2192/4591 +f 2194/2194/4593 1895/1895/4590 2193/2193/4592 +f 2195/2195/4594 1895/1895/4590 2194/2194/4593 +f 1980/1980/4595 1898/1898/4596 1895/1895/4590 +f 1980/1980/4595 1895/1895/4590 2195/2195/4594 +f 1973/1973/4597 1898/1898/4596 1980/1980/4595 +f 1887/1887/4598 1971/1971/4599 1886/1886/4600 +f 1987/1987/4601 1886/1886/4600 1971/1971/4599 +f 1983/1983/4602 1886/1886/4600 1987/1987/4601 +f 1981/1981/4603 1888/1888/4604 1886/1886/4600 +f 1981/1981/4603 1886/1886/4600 1983/1983/4602 +f 1986/1986/4605 1888/1888/4604 1981/1981/4603 +f 1888/1888/4604 1984/1984/4606 1985/1985/4607 +f 1984/1984/4606 1888/1888/4604 1986/1986/4605 +f 2182/2182/4578 1890/1890/4346 1985/1985/4607 +f 1985/1985/4607 1890/1890/4346 1888/1888/4604 +f 1898/1898/4596 1973/1973/4597 1972/1972/4608 +f 1898/1898/4596 1972/1972/4608 1974/1974/4609 +f 2050/2050/4573 1898/1898/4596 1975/1975/4610 +f 1975/1975/4610 1898/1898/4596 1974/1974/4609 +f 2050/2050/4573 1975/1975/4610 1976/1976/4611 +f 1977/1977/4612 2050/2050/4573 1976/1976/4611 +f 1978/1978/4571 2050/2050/4573 1977/1977/4612 +f 1965/1965/4613 1901/1901/4577 1966/1966/4576 +f 1967/1967/4614 1901/1901/4577 1965/1965/4613 +f 1887/1887/4598 1968/1968/4615 1969/1969/4616 +f 1968/1968/4615 1887/1887/4598 1901/1901/4577 +f 1968/1968/4615 1901/1901/4577 1967/1967/4614 +f 1970/1970/4617 1971/1971/4599 1887/1887/4598 +f 1970/1970/4617 1887/1887/4598 1969/1969/4616 +f 2192/2192/573 2191/2191/573 2196/2196/573 +f 1987/1987/573 1971/1971/573 2197/2197/573 +f 2197/2197/573 2198/2198/573 1987/1987/573 +f 1971/1971/573 1970/1970/573 2197/2197/573 +f 2190/2190/573 2183/2183/573 2181/2181/573 +f 1984/1984/573 1986/1986/573 2198/2198/573 +f 1985/1985/573 1984/1984/573 2198/2198/573 +f 1973/1973/573 1980/1980/573 2199/2199/573 +f 2182/2182/573 1985/1985/573 2198/2198/573 +f 2198/2198/573 2181/2181/573 2182/2182/573 +f 1980/1980/573 2195/2195/573 2199/2199/573 +f 1972/1972/573 1973/1973/573 2199/2199/573 +f 2180/2180/573 2187/2187/573 2181/2181/573 +f 1970/1970/573 1969/1969/573 2197/2197/573 +f 2183/2183/573 2182/2182/573 2181/2181/573 +f 1976/1976/573 1975/1975/573 2199/2199/573 +f 1975/1975/573 1974/1974/573 2199/2199/573 +f 1977/1977/573 1976/1976/573 2199/2199/573 +f 1974/1974/573 1972/1972/573 2199/2199/573 +f 1978/1978/573 1977/1977/573 2199/2199/573 +f 2194/2194/573 2193/2193/573 2196/2196/573 +f 2186/2186/573 2179/2179/573 2181/2181/573 +f 2193/2193/573 2192/2192/573 2196/2196/573 +f 2197/2197/573 1966/1966/573 2033/2033/573 +f 2185/2185/573 2186/2186/573 2181/2181/573 +f 2195/2195/573 2194/2194/573 2196/2196/573 +f 2196/2196/573 2199/2199/573 2195/2195/573 +f 2036/2036/4618 2200/2200/4619 2197/2197/4620 +f 2197/2197/4620 2033/2033/4621 2036/2036/4618 +f 1967/1967/573 1965/1965/573 2197/2197/573 +f 1986/1986/573 1981/1981/573 2198/2198/573 +f 1968/1968/573 1967/1967/573 2197/2197/573 +f 2191/2191/573 2184/2184/573 2181/2181/573 +f 2181/2181/573 2196/2196/573 2191/2191/573 +f 1983/1983/573 1987/1987/573 2198/2198/573 +f 2187/2187/573 2188/2188/573 2181/2181/573 +f 1965/1965/573 1966/1966/573 2197/2197/573 +f 2188/2188/573 2189/2189/573 2181/2181/573 +f 1981/1981/573 1983/1983/573 2198/2198/573 +f 2189/2189/573 2190/2190/573 2181/2181/573 +f 1969/1969/573 1968/1968/573 2197/2197/573 +f 2184/2184/573 2185/2185/573 2181/2181/573 +f 2178/2178/4622 2177/2177/4623 2199/2199/4624 +f 2199/2199/4624 2201/2201/4625 2178/2178/4622 +f 2177/2177/573 1978/1978/573 2199/2199/573 +f 1966/1966/4576 2036/2036/4575 2033/2033/4626 +f 2196/2196/4627 2181/2181/4628 2202/2202/4629 +f 2202/2202/4629 2203/2203/4630 2196/2196/4627 +f 2198/2198/4631 2197/2197/4632 2200/2200/4633 +f 2200/2200/4633 2204/2204/4634 2198/2198/4631 +f 2199/2199/4635 2196/2196/4627 2203/2203/4630 +f 2203/2203/4630 2201/2201/4636 2199/2199/4635 +f 2181/2181/4637 2198/2198/4631 2204/2204/4634 +f 2204/2204/4634 2202/2202/4638 2181/2181/4637 +f 2202/2202/4639 2204/2204/4640 1923/1923/4641 +f 1921/1921/4642 2201/2201/4643 2203/2203/4644 +f 2036/2036/4645 1901/1901/4646 2200/2200/4647 +f 1925/1925/4648 1921/1921/4642 2203/2203/4644 +f 2202/2202/4639 1923/1923/4641 2203/2203/4644 +f 1925/1925/4648 2203/2203/4644 1924/1924/3242 +f 1923/1923/4641 1924/1924/3242 2203/2203/4644 +f 2201/2201/4643 2050/2050/4649 2178/2178/4650 +f 1922/1922/4651 2204/2204/4640 1901/1901/4646 +f 1922/1922/4651 1923/1923/4641 2204/2204/4640 +f 2200/2200/4647 1901/1901/4646 2204/2204/4640 +f 1921/1921/4642 2050/2050/4649 2201/2201/4643 +f 2205/2205/4652 2206/2206/4653 2007/2007/4654 +f 2029/2029/4655 2007/2007/4654 2206/2206/4653 +f 2206/2206/4653 1943/1943/4213 2029/2029/4655 +f 1936/1936/4292 1935/1935/4656 1979/1979/4251 +f 2207/2207/4657 2208/2208/4658 2209/2209/4659 +f 1979/1979/4251 2195/2195/4660 2207/2207/4657 +f 1933/1933/4203 2037/2037/4313 2177/2177/4661 +f 2209/2209/4659 1936/1936/4292 1979/1979/4251 +f 2209/2209/4659 2018/2018/4293 1936/1936/4292 +f 2177/2177/4661 2037/2037/4313 2178/2178/4662 +f 1979/1979/4251 2207/2207/4657 2209/2209/4659 +f 2028/2028/4304 2027/2027/4663 2047/2047/4324 +f 1999/1999/4272 2028/2028/4304 2045/2045/4322 +f 2000/2000/4273 2041/2041/4664 2007/2007/4280 +f 1999/1999/4272 2043/2043/4320 2000/2000/4273 +f 2205/2205/4665 2007/2007/4280 2041/2041/4664 +f 2041/2041/4664 2000/2000/4273 2042/2042/4666 +f 2042/2042/4666 2000/2000/4273 2043/2043/4320 +f 2043/2043/4320 1999/1999/4272 2045/2045/4322 +f 2045/2045/4322 2028/2028/4304 2047/2047/4324 +f 2027/2027/4663 2009/2009/4667 2047/2047/4324 +f 2047/2047/4324 2009/2009/4667 2048/2048/4325 +f 2008/2008/4281 2048/2048/4325 2009/2009/4667 +f 2034/2034/4310 2048/2048/4325 2008/2008/4281 +f 1993/1993/4266 2208/2208/4658 2021/2021/4297 +f 2021/2021/4297 2208/2208/4658 2210/2210/4668 +f 2210/2210/4668 2208/2208/4658 2207/2207/4657 +f 2031/2031/4669 2021/2021/4297 2210/2210/4668 +f 2210/2210/4668 2207/2207/4657 2063/2063/4670 +f 2013/2013/4344 2032/2032/4671 2063/2063/4348 +f 2063/2063/4348 2032/2032/4671 2210/2210/4672 +f 2025/2025/4301 2023/2023/4299 2211/2211/4673 +f 2023/2023/4299 1964/1964/4236 2211/2211/4673 +f 1964/1964/4236 2034/2034/4310 2211/2211/4673 +f 2211/2211/4673 2008/2008/4281 2010/2010/4283 +f 2008/2008/4281 2211/2211/4673 2034/2034/4310 +f 2001/2001/4674 2061/2061/4343 2002/2002/4675 +f 2061/2061/4343 2011/2011/4676 2002/2002/4675 +f 2061/2061/4343 2059/2059/4340 1982/1982/4254 +f 2061/2061/4343 1982/1982/4254 2212/2212/4677 +f 2011/2011/4676 2061/2061/4343 2212/2212/4677 +f 2024/2024/4678 2212/2212/4677 2023/2023/4679 +f 1982/1982/4254 1964/1964/4236 2023/2023/4679 +f 2212/2212/4677 1982/1982/4254 2023/2023/4679 +f 2213/2213/573 2214/2214/573 2215/2215/573 +f 2214/2214/573 2216/2216/573 2215/2215/573 +f 2216/2216/4680 2028/2028/4680 2215/2215/4680 +f 2027/2027/4681 2028/2028/4681 2216/2216/4681 +f 2027/2027/4682 2216/2216/4682 2214/2214/4682 +f 2027/2027/4683 2214/2214/4683 1996/1996/4683 +f 2213/2213/4684 1996/1996/4684 2214/2214/4684 +f 2213/2213/4685 1997/1997/4685 1996/1996/4685 +f 2213/2213/4686 2028/2028/4687 1997/1997/4688 +f 2215/2215/4689 2028/2028/4687 2213/2213/4686 +f 2217/2217/573 2218/2218/573 2219/2219/573 +f 2220/2220/573 2219/2219/573 2218/2218/573 +f 2217/2217/4690 1932/1932/4691 2218/2218/4692 +f 1932/1932/4691 2217/2217/4690 1930/1930/4693 +f 2219/2219/4694 2017/2017/4695 2217/2217/4696 +f 2217/2217/4696 2017/2017/4695 1930/1930/4697 +f 2220/2220/4698 2017/2017/4699 2219/2219/4700 +f 2017/2017/4699 2220/2220/4698 1938/1938/4701 +f 2218/2218/4702 1938/1938/4702 2220/2220/4702 +f 2218/2218/4703 1932/1932/4703 1938/1938/4703 +f 2221/2221/573 2222/2222/573 2223/2223/573 +f 2221/2221/573 2223/2223/573 2224/2224/573 +f 2010/2010/4704 2221/2221/4705 2224/2224/4706 +f 2224/2224/4706 2211/2211/4707 2010/2010/4704 +f 2223/2223/4708 2211/2211/4709 2224/2224/4710 +f 2211/2211/4709 2223/2223/4708 2025/2025/4711 +f 2222/2222/4712 2025/2025/4713 2223/2223/4714 +f 2222/2222/4712 2026/2026/4715 2025/2025/4713 +f 2221/2221/4716 2026/2026/4717 2222/2222/4718 +f 2221/2221/4716 2010/2010/4719 2026/2026/4717 +f 2225/2225/4720 1949/1949/4721 2226/2226/4722 +f 2225/2225/4720 1947/1947/4723 1949/1949/4721 +f 2227/2227/4724 1950/1950/4725 2225/2225/4726 +f 2225/2225/4726 1950/1950/4725 1947/1947/4727 +f 2019/2019/4728 1950/1950/4729 2227/2227/4730 +f 2228/2228/4731 2019/2019/4728 2227/2227/4730 +f 2228/2228/4732 1949/1949/4733 2019/2019/4734 +f 2226/2226/4735 1949/1949/4733 2228/2228/4732 +f 2229/2229/4736 1961/1961/4736 1959/1959/4736 +f 1961/1961/4737 2229/2229/4737 2230/2230/4737 +f 2230/2230/4738 1955/1955/4738 1961/1961/4738 +f 2231/2231/4739 1955/1955/4739 2230/2230/4739 +f 1959/1959/4740 1955/1955/4740 2231/2231/4740 +f 2229/2229/4741 1959/1959/4741 2231/2231/4741 +f 1946/1946/4742 2232/2232/4742 2233/2233/4742 +f 2233/2233/4743 1942/1942/4743 1946/1946/4743 +f 2234/2234/4744 1942/1942/4744 2233/2233/4744 +f 2234/2234/4745 1940/1940/4746 1942/1942/4747 +f 2235/2235/4748 1940/1940/4746 2234/2234/4745 +f 1940/1940/4749 2235/2235/4750 1941/1941/4751 +f 1941/1941/4751 2235/2235/4750 2232/2232/4752 +f 2232/2232/4753 1946/1946/4753 1941/1941/4753 +f 2236/2236/573 2237/2237/573 2238/2238/573 +f 2235/2235/573 2233/2233/573 2232/2232/573 +f 2234/2234/573 2233/2233/573 2235/2235/573 +f 2239/2239/4754 1962/1962/4755 1963/1963/4756 +f 2240/2240/4757 1962/1962/4755 2239/2239/4754 +f 2240/2240/4758 1958/1958/4758 1962/1962/4758 +f 2241/2241/4759 1958/1958/4759 2240/2240/4759 +f 1958/1958/4760 2241/2241/4761 2020/2020/4762 +f 2242/2242/4763 2020/2020/4762 2241/2241/4761 +f 2020/2020/4764 2242/2242/4765 2239/2239/4766 +f 2020/2020/4764 2239/2239/4766 1963/1963/4767 +f 2230/2230/573 2229/2229/573 2231/2231/573 +f 2241/2241/573 2239/2239/573 2242/2242/573 +f 2240/2240/573 2239/2239/573 2241/2241/573 +f 2227/2227/573 2225/2225/573 2226/2226/573 +f 2227/2227/573 2226/2226/573 2228/2228/573 +f 2237/2237/4768 2029/2029/4768 1943/1943/4768 +f 2029/2029/4769 2237/2237/4769 2236/2236/4769 +f 2236/2236/4770 2006/2006/4770 2029/2029/4770 +f 2238/2238/4771 2006/2006/4772 2236/2236/4773 +f 2238/2238/4771 1939/1939/4774 2006/2006/4772 +f 2237/2237/4775 1943/1943/4776 1939/1939/4777 +f 2237/2237/4775 1939/1939/4777 2238/2238/4778 +f 2243/2243/573 2244/2244/573 2245/2245/573 +f 2014/2014/4779 2243/2243/4779 2022/2022/4779 +f 2245/2245/4780 2022/2022/4780 2243/2243/4780 +f 2245/2245/4781 2001/2001/4781 2022/2022/4781 +f 2244/2244/4782 2061/2061/4783 2245/2245/4784 +f 2245/2245/4784 2061/2061/4783 2001/2001/4785 +f 2061/2061/4786 2244/2244/4787 2243/2243/4788 +f 2243/2243/4788 2014/2014/4789 2061/2061/4786 +f 2246/2246/573 2247/2247/573 2248/2248/573 +f 2248/2248/573 2247/2247/573 2249/2249/573 +f 2210/2210/4790 2032/2032/4791 2249/2249/4792 +f 2249/2249/4792 2032/2032/4791 2248/2248/4793 +f 2247/2247/4794 2210/2210/4795 2249/2249/4796 +f 2210/2210/4795 2247/2247/4794 2031/2031/4797 +f 2246/2246/4798 2031/2031/4799 2247/2247/4800 +f 2246/2246/4798 2030/2030/4801 2031/2031/4799 +f 2030/2030/4802 2246/2246/4803 2032/2032/4804 +f 2248/2248/4805 2032/2032/4804 2246/2246/4803 +f 2250/2250/573 2251/2251/573 2252/2252/573 +f 2253/2253/573 2251/2251/573 2250/2250/573 +f 2252/2252/4806 2209/2209/4806 2208/2208/4806 +f 2251/2251/4807 2209/2209/4807 2252/2252/4807 +f 2251/2251/4808 2018/2018/4808 2209/2209/4808 +f 2018/2018/4809 2251/2251/4810 2253/2253/4811 +f 2018/2018/4809 2253/2253/4811 1993/1993/4812 +f 1993/1993/4813 2253/2253/4813 2250/2250/4813 +f 2250/2250/4814 2208/2208/4814 1993/1993/4814 +f 2252/2252/4815 2208/2208/4815 2250/2250/4815 +f 2254/2254/573 2255/2255/573 2256/2256/573 +f 2011/2011/4816 2255/2255/4816 2012/2012/4816 +f 2254/2254/4817 2012/2012/4817 2255/2255/4817 +f 2254/2254/4818 2024/2024/4818 2012/2012/4818 +f 2024/2024/4819 2254/2254/4820 2256/2256/4821 +f 2256/2256/4821 2212/2212/4822 2024/2024/4819 +f 2256/2256/4823 2011/2011/4823 2212/2212/4823 +f 2255/2255/4824 2011/2011/4824 2256/2256/4824 +f 2063/2063/4670 2207/2207/4657 2191/2191/4825 +f 2207/2207/4657 2195/2195/4660 2194/2194/4826 +f 2194/2194/4826 2193/2193/4827 2207/2207/4657 +f 2177/2177/4661 1978/1978/4250 1933/1933/4203 +f 2207/2207/4657 2192/2192/4828 2191/2191/4825 +f 2182/2182/4829 1985/1985/4257 1982/1982/4254 +f 2187/2187/4830 2188/2188/4831 2060/2060/4832 +f 2059/2059/4340 2060/2060/4832 2189/2189/4833 +f 2189/2189/4833 2190/2190/4834 2059/2059/4340 +f 2187/2187/4830 2060/2060/4832 2063/2063/4670 +f 2190/2190/4834 2183/2183/4835 2059/2059/4340 +f 2183/2183/4835 2182/2182/4829 2059/2059/4340 +f 2180/2180/4836 2187/2187/4830 2063/2063/4670 +f 2063/2063/4670 2179/2179/4837 2180/2180/4836 +f 2063/2063/4670 2185/2185/4838 2186/2186/4839 +f 2063/2063/4670 2184/2184/4840 2185/2185/4838 +f 2063/2063/4670 2186/2186/4839 2179/2179/4837 +f 1979/1979/4251 1980/1980/4252 2195/2195/4660 +f 2193/2193/4827 2192/2192/4828 2207/2207/4657 +f 2040/2040/4317 2158/2158/4841 2041/2041/4318 +f 2158/2158/4841 2157/2157/4842 2041/2041/4318 +f 1984/1984/4256 1986/1986/4258 1982/1982/4254 +f 2041/2041/4318 2157/2157/4842 2205/2205/4843 +f 2036/2036/4312 2034/2034/4310 2033/2033/4309 +f 2189/2189/4833 2060/2060/4832 2188/2188/4831 +f 2184/2184/4840 2063/2063/4670 2191/2191/4825 +f 1982/1982/4254 2059/2059/4340 2182/2182/4829 +f 2137/2137/4844 1948/1948/4218 2155/2155/4845 +f 1957/1957/4227 2151/2151/4846 2152/2152/4847 +f 1957/1957/4227 2152/2152/4847 2153/2153/4848 +f 1957/1957/4227 2153/2153/4848 1948/1948/4218 +f 1948/1948/4218 2153/2153/4848 2154/2154/4849 +f 1948/1948/4218 2154/2154/4849 2156/2156/4850 +f 2137/2137/4844 2064/2064/4352 1948/1948/4218 +f 2156/2156/4850 2155/2155/4845 1948/1948/4218 +f 2141/2141/4851 2142/2142/4852 1943/1943/4213 +f 2140/2140/4853 2141/2141/4851 1943/1943/4213 +f 2138/2138/4854 2140/2140/4853 2206/2206/4653 +f 2139/2139/4855 2138/2138/4854 2206/2206/4653 +f 2140/2140/4853 1943/1943/4213 2206/2206/4653 +f 2136/2136/4856 2139/2139/4855 2206/2206/4653 +f 2135/2135/4857 2136/2136/4856 2205/2205/4843 +f 2134/2134/4858 2135/2135/4857 2205/2205/4843 +f 2133/2133/4859 2134/2134/4858 2205/2205/4843 +f 2136/2136/4856 2206/2206/4653 2205/2205/4843 +f 2132/2132/4860 2133/2133/4859 2205/2205/4843 +f 2205/2205/4843 2157/2157/4842 2130/2130/4861 +f 2131/2131/4862 2132/2132/4860 2205/2205/4843 +f 2205/2205/4843 2130/2130/4861 2131/2131/4862 +f 2150/2150/4863 2151/2151/4846 1954/1954/4224 +f 1954/1954/4224 1953/1953/4223 2150/2150/4863 +f 1957/1957/4227 1954/1954/4224 2151/2151/4846 +f 2142/2142/4852 2143/2143/4864 1943/1943/4213 +f 1944/1944/4214 1943/1943/4213 2143/2143/4864 +f 2144/2144/4865 2150/2150/4863 1953/1953/4223 +f 1953/1953/4223 1944/1944/4214 2146/2146/4866 +f 1944/1944/4214 2143/2143/4864 2149/2149/4867 +f 2145/2145/4868 2144/2144/4865 1953/1953/4223 +f 2146/2146/4866 2145/2145/4868 1953/1953/4223 +f 1944/1944/4214 2149/2149/4867 2148/2148/4869 +f 2146/2146/4866 1944/1944/4214 2147/2147/4870 +f 1944/1944/4214 2148/2148/4869 2147/2147/4870 +f 2152/2152/5 2257/2257/5 2153/2153/5 +f 1970/1970/5 2258/2258/5 1969/1969/5 +f 2153/2153/5 2257/2257/5 2154/2154/5 +f 2184/2184/5 2259/2259/5 2260/2260/5 +f 2183/2183/5 2260/2260/5 2182/2182/5 +f 2182/2182/5 2261/2261/5 1985/1985/5 +f 1983/1983/5 2261/2261/5 1987/1987/5 +f 1985/1985/5 2261/2261/5 1984/1984/5 +f 1980/1980/5 2262/2262/5 2259/2259/5 +f 1981/1981/5 2261/2261/5 1983/1983/5 +f 2155/2155/5 2257/2257/5 2137/2137/5 +f 1978/1978/5 2262/2262/5 1977/1977/5 +f 2157/2157/5 2263/2263/5 2130/2130/5 +f 2139/2139/5 2263/2263/5 2264/2264/5 +f 1987/1987/5 2258/2258/5 1971/1971/5 +f 1984/1984/5 2261/2261/5 1986/1986/5 +f 2190/2190/5 2260/2260/5 2183/2183/5 +f 2143/2143/5 2264/2264/5 2265/2265/5 +f 1971/1971/5 2258/2258/5 1970/1970/5 +f 1986/1986/5 2261/2261/5 1981/1981/5 +f 2177/2177/5 2262/2262/5 1978/1978/5 +f 2151/2151/5 2265/2265/5 2257/2257/5 +f 2156/2156/5 2257/2257/5 2155/2155/5 +f 2154/2154/5 2257/2257/5 2156/2156/5 +f 2151/2151/5 2257/2257/5 2152/2152/5 +f 2036/2036/5 2266/2266/5 2035/2035/5 +f 2267/2267/5 2158/2158/5 2040/2040/5 +f 2044/2044/5 2046/2046/5 2267/2267/5 +f 2266/2266/5 2267/2267/5 2035/2035/5 +f 2046/2046/5 2035/2035/5 2267/2267/5 +f 2267/2267/5 2040/2040/5 2044/2044/5 +f 2037/2037/5 2038/2038/5 2268/2268/5 +f 2049/2049/4871 2269/2269/4524 2039/2039/1134 +f 2268/2268/5 2178/2178/5 2037/2037/5 +f 2269/2269/4524 2268/2268/5 2039/2039/1134 +f 2039/2039/1134 2268/2268/5 2038/2038/5 +f 2261/2261/4872 2266/2266/4873 2258/2258/4874 +f 2262/2262/4875 2268/2268/4876 2259/2259/4877 +f 2260/2260/4878 2270/2270/4879 2261/2261/4872 +f 2259/2259/4877 2271/2271/4880 2260/2260/4881 +f 2263/2263/4882 2272/2272/4883 2264/2264/4884 +f 2265/2265/4885 2273/2273/4886 2257/2257/4887 +f 2264/2264/4888 2274/2274/4889 2265/2265/4890 +f 2158/2158/4891 2263/2263/4892 2157/2157/4893 +f 2158/2158/4891 2267/2267/4894 2263/2263/4892 +f 2257/2257/4895 2269/2269/4896 2064/2064/4897 +f 2269/2269/4896 2049/2049/4898 2064/2064/4897 +f 2258/2258/4899 2266/2266/4900 2033/2033/4901 +f 2178/2178/4902 2268/2268/4903 2177/2177/4904 +f 2266/2266/4900 2036/2036/4905 2033/2033/4901 +f 2269/2269/4524 2271/2271/5 2268/2268/5 +f 2268/2268/4903 2262/2262/4906 2177/2177/4904 +f 2271/2271/5 2275/2275/5 2268/2268/5 +f 2273/2273/4907 2274/2274/5 2271/2271/5 +f 2274/2274/5 2266/2266/5 2271/2271/5 +f 2266/2266/5 2270/2270/5 2271/2271/5 +f 2271/2271/5 2269/2269/4524 2273/2273/4907 +f 2274/2274/5 2267/2267/5 2266/2266/5 +f 2274/2274/5 2272/2272/5 2267/2267/5 +f 1974/1974/5 1975/1975/5 2262/2262/5 +f 1967/1967/5 1968/1968/5 2258/2258/5 +f 1972/1972/5 1974/1974/5 2262/2262/5 +f 1976/1976/5 1977/1977/5 2262/2262/5 +f 2134/2134/5 2133/2133/5 2263/2263/5 +f 2133/2133/5 2132/2132/5 2263/2263/5 +f 2185/2185/5 2184/2184/5 2260/2260/5 +f 2184/2184/5 2191/2191/5 2259/2259/5 +f 2179/2179/5 2186/2186/5 2260/2260/5 +f 2182/2182/5 2260/2260/5 2261/2261/5 +f 1966/1966/5 1965/1965/5 2258/2258/5 +f 2180/2180/5 2179/2179/5 2260/2260/5 +f 2187/2187/5 2180/2180/5 2260/2260/5 +f 2195/2195/5 1980/1980/5 2259/2259/5 +f 2064/2064/5 2137/2137/5 2257/2257/5 +f 1980/1980/5 1973/1973/5 2262/2262/5 +f 2193/2193/5 2194/2194/5 2259/2259/5 +f 2033/2033/5 1966/1966/5 2258/2258/5 +f 2261/2261/4872 2270/2270/4879 2266/2266/4873 +f 2192/2192/5 2193/2193/5 2259/2259/5 +f 2131/2131/5 2130/2130/5 2263/2263/5 +f 2132/2132/5 2131/2131/5 2263/2263/5 +f 2194/2194/5 2195/2195/5 2259/2259/5 +f 2139/2139/5 2136/2136/5 2263/2263/5 +f 2188/2188/5 2187/2187/5 2260/2260/5 +f 1987/1987/5 2261/2261/5 2258/2258/5 +f 2136/2136/5 2135/2135/5 2263/2263/5 +f 2138/2138/5 2139/2139/5 2264/2264/5 +f 2142/2142/5 2141/2141/5 2264/2264/5 +f 2189/2189/5 2188/2188/5 2260/2260/5 +f 2186/2186/5 2185/2185/5 2260/2260/5 +f 2143/2143/5 2142/2142/5 2264/2264/5 +f 2190/2190/5 2189/2189/5 2260/2260/5 +f 2141/2141/5 2140/2140/5 2264/2264/5 +f 2148/2148/5 2149/2149/5 2265/2265/5 +f 2149/2149/5 2143/2143/5 2265/2265/5 +f 2147/2147/5 2148/2148/5 2265/2265/5 +f 2146/2146/5 2147/2147/5 2265/2265/5 +f 2145/2145/5 2146/2146/5 2265/2265/5 +f 2144/2144/5 2145/2145/5 2265/2265/5 +f 2140/2140/5 2138/2138/5 2264/2264/5 +f 2191/2191/5 2192/2192/5 2259/2259/5 +f 2150/2150/5 2144/2144/5 2265/2265/5 +f 2151/2151/5 2150/2150/5 2265/2265/5 +f 2135/2135/5 2134/2134/5 2263/2263/5 +f 1973/1973/5 1972/1972/5 2262/2262/5 +f 1965/1965/5 1967/1967/5 2258/2258/5 +f 1975/1975/5 1976/1976/5 2262/2262/5 +f 1968/1968/5 1969/1969/5 2258/2258/5 +f 2259/2259/4877 2268/2268/4876 2275/2275/4908 +f 2260/2260/4878 2271/2271/4909 2270/2270/4879 +f 2259/2259/4877 2275/2275/4908 2271/2271/4880 +f 2263/2263/4882 2267/2267/4910 2272/2272/4883 +f 2265/2265/4885 2274/2274/4911 2273/2273/4886 +f 2257/2257/4887 2273/2273/4886 2269/2269/4912 +f 2264/2264/4888 2272/2272/4913 2274/2274/4889 +f 2276/2276/4914 2277/2277/4915 2278/2278/4916 +f 2279/2279/4917 2276/2276/4914 2278/2278/4916 +f 2276/2276/4914 2279/2279/4917 2280/2280/4918 +f 2281/2281/4919 2282/2282/4920 2280/2280/4918 +f 2281/2281/4919 2280/2280/4918 2279/2279/4917 +f 2277/2277/4915 2283/2283/4921 2278/2278/4916 +f 2278/2278/4916 2283/2283/4921 2281/2281/4919 +f 2281/2281/4919 2283/2283/4921 2282/2282/4920 +f 2284/2284/4922 2285/2285/4922 2286/2286/4922 +f 2287/2287/4923 2285/2285/4923 2284/2284/4923 +f 2287/2287/4924 2284/2284/4924 2288/2288/4924 +f 2288/2288/4925 2284/2284/4925 2286/2286/4925 +f 2288/2288/4926 2286/2286/4926 2289/2289/4926 +f 2289/2289/4927 2286/2286/4927 2285/2285/4927 +f 2289/2289/4928 2285/2285/4928 2287/2287/4928 +f 2277/2277/4929 2287/2287/4929 2283/2283/4929 +f 2283/2283/4930 2287/2287/4931 2288/2288/4932 +f 2283/2283/4930 2288/2288/4932 2282/2282/4933 +f 2282/2282/4934 2288/2288/4934 2280/2280/4934 +f 2280/2280/4935 2288/2288/4935 2289/2289/4935 +f 2280/2280/4936 2289/2289/4936 2276/2276/4936 +f 2276/2276/4937 2289/2289/4938 2287/2287/4939 +f 2276/2276/4937 2287/2287/4939 2277/2277/4940 +f 2279/2279/4917 2278/2278/4916 2281/2281/4919 +f 2290/2290/4941 2291/2291/4942 2292/2292/4943 +f 2293/2293/4944 2294/2294/4945 2295/2295/4946 +f 2292/2292/4943 2291/2291/4942 2293/2293/4944 +f 2293/2293/4944 2291/2291/4942 2296/2296/4947 +f 2293/2293/4944 2296/2296/4947 2294/2294/4945 +f 2295/2295/4946 2297/2297/4948 2292/2292/4943 +f 2292/2292/4943 2297/2297/4948 2290/2290/4941 +f 2294/2294/4945 2297/2297/4948 2295/2295/4946 +f 2298/2298/4949 2299/2299/4950 2300/2300/4951 +f 2298/2298/4949 2300/2300/4951 2301/2301/4952 +f 2302/2302/4953 2300/2300/4954 2299/2299/4955 +f 2302/2302/4956 2299/2299/4957 2303/2303/4958 +f 2303/2303/4958 2299/2299/4957 2298/2298/4959 +f 2303/2303/4960 2298/2298/4960 2301/2301/4960 +f 2303/2303/4961 2301/2301/4961 2304/2304/4961 +f 2304/2304/4962 2301/2301/4962 2300/2300/4962 +f 2304/2304/4963 2300/2300/4954 2302/2302/4953 +f 2290/2290/4964 2302/2302/4965 2291/2291/4966 +f 2291/2291/4967 2302/2302/4968 2296/2296/4969 +f 2296/2296/4969 2302/2302/4968 2303/2303/4970 +f 2296/2296/4971 2303/2303/4971 2294/2294/4971 +f 2294/2294/4972 2303/2303/4973 2304/2304/4974 +f 2294/2294/4972 2304/2304/4974 2297/2297/4975 +f 2297/2297/4976 2304/2304/4976 2290/2290/4976 +f 2290/2290/4964 2304/2304/4977 2302/2302/4965 +f 2295/2295/4946 2292/2292/4943 2293/2293/4944 +f 2305/2305/4978 2306/2306/4979 2307/2307/4980 +f 2308/2308/4981 2309/2309/4982 2310/2310/4983 +f 2311/2311/4984 2305/2305/4978 2312/2312/4985 +f 2308/2308/4981 2310/2310/4983 2313/2313/4986 +f 2307/2307/4980 2309/2309/4982 2308/2308/4981 +f 2307/2307/4980 2306/2306/4979 2309/2309/4982 +f 2312/2312/4985 2305/2305/4978 2307/2307/4980 +f 2308/2308/4981 2313/2313/4986 2312/2312/4985 +f 2312/2312/4985 2313/2313/4986 2311/2311/4984 +f 2314/2314/4987 2315/2315/4988 2316/2316/4989 +f 2317/2317/4990 2315/2315/4988 2314/2314/4987 +f 2318/2318/4991 2316/2316/4991 2319/2319/4991 +f 2319/2319/4992 2316/2316/4992 2315/2315/4992 +f 2319/2319/4993 2315/2315/4994 2317/2317/4995 +f 2319/2319/4993 2317/2317/4995 2320/2320/4996 +f 2320/2320/4997 2317/2317/4998 2318/2318/4999 +f 2318/2318/4999 2317/2317/4998 2314/2314/5000 +f 2318/2318/5001 2314/2314/5001 2316/2316/5001 +f 2311/2311/5002 2318/2318/5003 2305/2305/5004 +f 2305/2305/5004 2318/2318/5003 2319/2319/5005 +f 2305/2305/5006 2319/2319/5006 2306/2306/5006 +f 2306/2306/5007 2319/2319/5008 2309/2309/5009 +f 2309/2309/5009 2319/2319/5008 2320/2320/5010 +f 2309/2309/5011 2320/2320/5011 2310/2310/5011 +f 2310/2310/5012 2320/2320/5013 2318/2318/5014 +f 2310/2310/5012 2318/2318/5014 2313/2313/5015 +f 2313/2313/5016 2318/2318/5016 2311/2311/5016 +f 2312/2312/4985 2307/2307/4980 2308/2308/4981 +f 2321/2321/5017 2322/2322/5018 2323/2323/5019 +f 2321/2321/5017 2324/2324/5020 2325/2325/5021 +f 2321/2321/5017 2323/2323/5019 2324/2324/5020 +f 2326/2326/5022 2322/2322/5018 2321/2321/5017 +f 2325/2325/5021 2327/2327/5023 2326/2326/5022 +f 2321/2321/5017 2325/2325/5021 2326/2326/5022 +f 2326/2326/5022 2327/2327/5023 2322/2322/5018 +f 2328/2328/5024 2329/2329/5024 2330/2330/5024 +f 2331/2331/5025 2328/2328/5026 2332/2332/5027 +f 2332/2332/5028 2328/2328/5029 2333/2333/5030 +f 2333/2333/5030 2328/2328/5029 2330/2330/5031 +f 2333/2333/5032 2330/2330/5032 2334/2334/5032 +f 2334/2334/5033 2330/2330/5033 2329/2329/5033 +f 2334/2334/5034 2329/2329/5034 2331/2331/5034 +f 2331/2331/5025 2329/2329/5035 2328/2328/5026 +f 2327/2327/5036 2331/2331/5037 2332/2332/5038 +f 2327/2327/5039 2332/2332/5040 2322/2322/5041 +f 2322/2322/5041 2332/2332/5040 2333/2333/5042 +f 2322/2322/5043 2333/2333/5044 2323/2323/5045 +f 2323/2323/5045 2333/2333/5044 2334/2334/5046 +f 2323/2323/5047 2334/2334/5047 2324/2324/5047 +f 2324/2324/5048 2334/2334/5049 2331/2331/5050 +f 2324/2324/5048 2331/2331/5050 2325/2325/5051 +f 2325/2325/5052 2331/2331/5037 2327/2327/5036 +f 2335/2335/5053 2336/2336/5054 2337/2337/5055 +f 2337/2337/5055 2338/2338/5056 2339/2339/5057 +f 2337/2337/5055 2336/2336/5054 2340/2340/5058 +f 2341/2341/5059 2335/2335/5053 2339/2339/5057 +f 2337/2337/5055 2340/2340/5058 2338/2338/5056 +f 2335/2335/5053 2341/2341/5059 2336/2336/5054 +f 2337/2337/5055 2339/2339/5057 2335/2335/5053 +f 2342/2342/5060 2343/2343/5061 2344/2344/5062 +f 2344/2344/5062 2345/2345/5063 2342/2342/5060 +f 2346/2346/5064 2343/2343/5065 2347/2347/5066 +f 2347/2347/5066 2343/2343/5065 2342/2342/5067 +f 2347/2347/5068 2342/2342/5069 2348/2348/5070 +f 2348/2348/5070 2342/2342/5069 2345/2345/5071 +f 2348/2348/5072 2345/2345/5072 2344/2344/5072 +f 2348/2348/5073 2344/2344/5073 2346/2346/5073 +f 2346/2346/5074 2344/2344/5074 2343/2343/5074 +f 2338/2338/5075 2346/2346/5076 2347/2347/5077 +f 2338/2338/5075 2347/2347/5077 2339/2339/5078 +f 2339/2339/5079 2347/2347/5080 2341/2341/5081 +f 2341/2341/5081 2347/2347/5080 2348/2348/5082 +f 2341/2341/5083 2348/2348/5083 2336/2336/5083 +f 2336/2336/5084 2348/2348/5085 2340/2340/5086 +f 2340/2340/5086 2348/2348/5085 2346/2346/5087 +f 2340/2340/5088 2346/2346/5088 2338/2338/5088 +f 2349/2349/5089 2350/2350/5090 2351/2351/5091 +f 2352/2352/5092 2353/2353/5093 2354/2354/5094 +f 2354/2354/5094 2353/2353/5093 2355/2355/5095 +f 2355/2355/5095 2356/2356/5096 2349/2349/5089 +f 2349/2349/5089 2356/2356/5096 2350/2350/5090 +f 2357/2357/5097 2352/2352/5092 2354/2354/5094 +f 2355/2355/5095 2353/2353/5093 2356/2356/5096 +f 2349/2349/5089 2351/2351/5091 2354/2354/5094 +f 2354/2354/5094 2351/2351/5091 2357/2357/5097 +f 2358/2358/5098 2359/2359/5099 2360/2360/5100 +f 2361/2361/5101 2360/2360/5101 2362/2362/5101 +f 2362/2362/5102 2360/2360/5102 2359/2359/5102 +f 2362/2362/5103 2359/2359/5103 2363/2363/5103 +f 2363/2363/5104 2359/2359/5104 2364/2364/5104 +f 2363/2363/5105 2364/2364/5106 2365/2365/5107 +f 2365/2365/5107 2364/2364/5106 2358/2358/5108 +f 2365/2365/5109 2358/2358/5110 2361/2361/5111 +f 2361/2361/5111 2358/2358/5110 2360/2360/5112 +f 2353/2353/5113 2361/2361/5114 2362/2362/5115 +f 2353/2353/5113 2362/2362/5115 2356/2356/5116 +f 2356/2356/5117 2362/2362/5118 2363/2363/5119 +f 2356/2356/5117 2363/2363/5119 2350/2350/5120 +f 2350/2350/5121 2363/2363/5121 2351/2351/5121 +f 2351/2351/5122 2363/2363/5123 2365/2365/5124 +f 2351/2351/5122 2365/2365/5124 2357/2357/5125 +f 2357/2357/5126 2365/2365/5127 2352/2352/5128 +f 2352/2352/5128 2365/2365/5127 2361/2361/5129 +f 2352/2352/5128 2361/2361/5129 2353/2353/5130 +f 2354/2354/5094 2355/2355/5095 2349/2349/5089 +f 2364/2364/5131 2359/2359/5099 2358/2358/5098 +f 2366/2366/5132 2367/2367/5133 2368/2368/5134 +f 2368/2368/5134 2369/2369/5135 2366/2366/5132 +f 2367/2367/5136 2370/2370/5137 2371/2371/5138 +f 2371/2371/5138 2368/2368/5139 2367/2367/5136 +f 2372/2372/5140 2371/2371/5138 2370/2370/5137 +f 2370/2370/5137 2373/2373/5141 2372/2372/5140 +f 2374/2374/5142 2372/2372/5140 2373/2373/5141 +f 2373/2373/5141 2375/2375/5143 2374/2374/5142 +f 2375/2375/5143 2376/2376/5144 2377/2377/5145 +f 2377/2377/5145 2374/2374/5142 2375/2375/5143 +f 2376/2376/5146 2378/2378/5147 2379/2379/5148 +f 2379/2379/5148 2377/2377/5149 2376/2376/5146 +f 2378/2378/5150 2380/2380/5151 2379/2379/5152 +f 2381/2381/5153 2379/2379/5152 2380/2380/5151 +f 2380/2380/5151 2382/2382/5154 2381/2381/5153 +f 2383/2383/5155 2381/2381/5153 2382/2382/5154 +f 2376/2376/5 2375/2375/5 2373/2373/5 +f 2366/2366/5 2382/2382/5 2380/2380/5 +f 2380/2380/5 2378/2378/5 2376/2376/5 +f 2376/2376/5 2373/2373/5 2370/2370/5 +f 2370/2370/5 2367/2367/5 2366/2366/5 +f 2366/2366/5 2380/2380/5 2376/2376/5 +f 2376/2376/5 2370/2370/5 2366/2366/5 +f 2368/2368/573 2371/2371/573 2372/2372/573 +f 2383/2383/573 2369/2369/573 2368/2368/573 +f 2368/2368/573 2372/2372/573 2374/2374/573 +f 2374/2374/573 2377/2377/573 2379/2379/573 +f 2379/2379/573 2381/2381/573 2383/2383/573 +f 2383/2383/573 2368/2368/573 2374/2374/573 +f 2374/2374/573 2379/2379/573 2383/2383/573 +f 2383/2383/5155 2382/2382/5154 2366/2366/5156 +f 2366/2366/5156 2369/2369/5157 2383/2383/5155 +f 2384/2384/5158 2385/2385/5159 2386/2386/5160 +f 2387/2387/5161 2386/2386/5160 2385/2385/5159 +f 2385/2385/5159 2388/2388/5162 2387/2387/5161 +f 2389/2389/5163 2387/2387/5161 2388/2388/5162 +f 2388/2388/5162 2390/2390/5164 2389/2389/5163 +f 2390/2390/5164 2391/2391/5165 2392/2392/5166 +f 2392/2392/5166 2389/2389/5163 2390/2390/5164 +f 2391/2391/5167 2393/2393/5168 2394/2394/5169 +f 2394/2394/5169 2392/2392/5170 2391/2391/5167 +f 2393/2393/5171 2395/2395/5172 2394/2394/5173 +f 2396/2396/5174 2394/2394/5173 2395/2395/5172 +f 2395/2395/5172 2397/2397/5175 2396/2396/5174 +f 2398/2398/5176 2396/2396/5174 2397/2397/5175 +f 2397/2397/5177 2399/2399/5178 2400/2400/5179 +f 2400/2400/5179 2398/2398/5180 2397/2397/5177 +f 2399/2399/5181 2401/2401/5182 2400/2400/5183 +f 2402/2402/5184 2400/2400/5183 2401/2401/5182 +f 2385/2385/5 2384/2384/5 2401/2401/5 +f 2395/2395/5 2393/2393/5 2391/2391/5 +f 2385/2385/5 2401/2401/5 2399/2399/5 +f 2399/2399/5 2397/2397/5 2395/2395/5 +f 2395/2395/5 2391/2391/5 2390/2390/5 +f 2390/2390/5 2388/2388/5 2385/2385/5 +f 2385/2385/5 2399/2399/5 2395/2395/5 +f 2395/2395/5 2390/2390/5 2385/2385/5 +f 2396/2396/573 2398/2398/573 2400/2400/573 +f 2402/2402/573 2386/2386/573 2387/2387/573 +f 2387/2387/573 2389/2389/573 2392/2392/573 +f 2392/2392/573 2394/2394/573 2396/2396/573 +f 2396/2396/573 2400/2400/573 2402/2402/573 +f 2402/2402/573 2387/2387/573 2392/2392/573 +f 2392/2392/573 2396/2396/573 2402/2402/573 +f 2402/2402/5184 2401/2401/5182 2384/2384/5158 +f 2384/2384/5158 2386/2386/5160 2402/2402/5184 +f 2717/2403/5185 2715/2404/5186 2713/2405/5187 +f 2606/2406/5188 2664/2407/5189 2613/2408/5190 +f 2660/2409/5191 2659/2410/5192 2502/2411/5193 +f 2666/2412/5194 2667/2413/5195 2506/2414/5196 +f 2539/2415/5197 2686/2416/5198 2683/2417/5199 +f 2482/2418/5200 2666/2412/5194 2672/2419/5201 +f 2412/2420/5202 2609/2421/5203 2411/2422/5204 +f 2654/2423/5205 2582/2424/5206 2655/2425/5207 +f 2635/2426/5208 2649/2427/5209 2700/2428/5210 +f 2722/2429/5211 2442/2430/5212 2444/2431/5213 +f 2593/2432/5214 2587/2433/5215 2588/2434/5216 +f 2556/2435/5217 2583/2436/5218 2589/2437/5219 +f 2705/2438/5220 2707/2439/5221 2522/2440/5222 +f 2508/2441/5223 2671/2442/5224 2501/2443/5225 +f 2490/2444/5226 2491/2445/5227 2594/2446/5228 +f 2581/2447/5229 2582/2424/5206 2588/2434/5216 +f 2515/2448/5230 2516/2449/5231 2517/2450/5232 +f 2699/2451/5233 2701/2452/5234 2702/2453/5235 +f 2716/2454/5236 2718/2455/5237 2715/2404/5186 +f 2505/2456/5238 2651/2457/5239 2650/2458/5240 +f 2429/2459/5241 2601/2460/5242 2597/2461/5243 +f 2661/2462/5244 2660/2409/5191 2657/2463/5245 +f 2671/2442/5224 2656/2464/5246 2501/2443/5225 +f 2504/2465/5247 2500/2466/5248 2499/2467/5249 +f 2413/2468/5250 2419/2469/5251 2613/2408/5190 +f 2719/2470/5252 2533/2471/5253 2531/2472/5254 +f 2481/2473/5255 2487/2474/5256 2670/2475/5257 +f 2516/2449/5231 2518/2476/5258 2520/2477/5259 +f 2575/2478/5260 2593/2432/5214 2594/2446/5228 +f 2577/2479/5261 2583/2436/5218 2556/2435/5217 +f 2522/2440/5222 2707/2439/5221 2523/2480/5262 +f 2507/2481/5263 2508/2441/5223 2651/2457/5239 +f 2720/2482/5264 2708/2483/5265 2719/2470/5252 +f 2583/2436/5218 2584/2484/5266 2589/2437/5219 +f 2578/2485/5267 2579/2486/5268 2585/2487/5269 +f 2648/2488/5270 2469/2489/5271 2472/2490/5272 +f 2641/2491/5273 2708/2483/5265 2720/2482/5264 +f 2686/2416/5198 2685/2492/5274 2683/2417/5199 +f 2672/2419/5201 2687/2493/5275 2480/2494/5276 +f 2567/2495/5277 2552/2496/5278 2496/2497/5279 +f 2695/2498/5280 2643/2499/5281 2474/2500/5282 +f 2595/2501/5283 2603/2502/5284 2602/2503/5285 +f 2652/2504/5286 2564/2505/5287 2651/2457/5239 +f 2704/2506/5288 2710/2507/5289 2709/2508/5290 +f 2547/2509/5291 2543/2510/5292 2549/2511/5293 +f 2625/2512/5294 2629/2513/5295 2455/2514/5296 +f 2517/2450/5232 2519/2515/5297 2515/2448/5230 +f 2741/2516/5298 2428/2517/5299 2597/2461/5243 +f 2713/2405/5187 2639/2518/5300 2631/2519/5301 +f 2486/2520/5302 2481/2473/5255 2669/2521/5303 +f 2548/2522/5304 2547/2509/5291 2549/2511/5293 +f 2688/2523/5305 2674/2524/5306 2601/2460/5242 +f 2561/2525/5307 2497/2526/5308 2488/2527/5309 +f 2439/2528/5310 2440/2529/5311 2706/2530/5312 +f 2695/2498/5280 2696/2531/5313 2698/2532/5314 +f 2673/2533/5315 2607/2534/5316 2608/2535/5317 +f 2408/2536/5318 2609/2421/5203 2616/2537/5319 +f 2594/2446/5228 2491/2445/5227 2552/2496/5278 +f 2589/2437/5219 2573/2538/5320 2653/2539/5321 +f 2542/2540/5322 2547/2509/5291 2544/2541/5323 +f 2461/2542/5324 2622/2543/5325 2629/2513/5295 +f 2686/2416/5198 2539/2415/5197 2538/2544/5326 +f 2473/2545/5327 2474/2500/5282 2643/2499/5281 +f 2569/2546/5328 2562/2547/5329 2563/2548/5330 +f 2592/2549/5331 2574/2550/5332 2591/2551/5333 +f 2467/2552/5334 2466/2553/5335 2633/2554/5336 +f 2509/2555/5337 2535/2556/5338 2689/2557/5339 +f 2718/2455/5237 2640/2558/5340 2636/2559/5341 +f 2572/2560/5342 2581/2447/5229 2580/2561/5343 +f 2478/2562/5344 2479/2563/5345 2690/2564/5346 +f 2727/2565/5347 2728/2566/5348 2731/2567/5349 +f 2519/2515/5297 2551/2568/5350 2548/2522/5304 +f 2445/2569/5351 2724/2570/5352 2446/2571/5353 +f 2614/2572/5354 2615/2573/5355 2661/2462/5244 +f 2714/2574/5356 2710/2507/5289 2527/2575/5357 +f 2683/2417/5199 2682/2576/5358 2684/2577/5359 +f 2714/2574/5356 2713/2405/5187 2712/2578/5360 +f 2525/2579/5361 2549/2511/5293 2542/2540/5322 +f 2629/2513/5295 2453/2580/5362 2454/2581/5363 +f 2695/2498/5280 2692/2582/5364 2694/2583/5365 +f 2512/2584/5366 2577/2479/5261 2510/2585/5367 +f 2465/2586/5368 2467/2552/5334 2638/2587/5369 +f 2502/2411/5193 2537/2588/5370 2577/2479/5261 +f 2701/2452/5234 2699/2451/5233 2498/2589/5371 +f 2572/2560/5342 2551/2568/5350 2550/2590/5372 +f 2694/2583/5365 2690/2564/5346 2554/2591/5373 +f 2733/2592/5374 2730/2593/5375 2729/2594/5376 +f 2716/2454/5236 2534/2595/5377 2532/2596/5378 +f 2554/2591/5373 2553/2597/5379 2694/2583/5365 +f 2521/2598/5380 2546/2599/5381 2706/2530/5312 +f 2727/2565/5347 2731/2567/5349 2732/2600/5382 +f 2443/2601/5383 2442/2430/5212 2722/2429/5211 +f 2725/2602/5384 2721/2603/5385 2525/2579/5361 +f 2601/2460/5242 2676/2604/5386 2600/2605/5387 +f 2510/2585/5367 2513/2606/5388 2512/2584/5366 +f 2536/2607/5389 2535/2556/5338 2557/2608/5390 +f 2550/2590/5372 2519/2515/5297 2520/2477/5259 +f 2542/2540/5322 2543/2510/5292 2547/2509/5291 +f 2553/2597/5379 2488/2527/5309 2696/2531/5313 +f 2635/2426/5208 2709/2508/5290 2634/2609/5391 +f 2488/2527/5309 2553/2597/5379 2555/2610/5392 +f 2563/2548/5330 2557/2608/5390 2558/2611/5393 +f 2528/2612/5394 2498/2589/5371 2497/2526/5308 +f 2678/2613/5395 2679/2614/5396 2599/2615/5397 +f 2446/2571/5353 2724/2570/5352 2723/2616/5398 +f 2571/2617/5399 2570/2618/5400 2563/2548/5330 +f 2728/2566/5348 2719/2470/5252 2531/2472/5254 +f 2693/2619/5401 2697/2620/5402 2546/2599/5381 +f 2608/2535/5317 2421/2621/5403 2595/2501/5283 +f 2448/2622/5404 2447/2623/5405 2721/2603/5385 +f 2620/2624/5406 2619/2625/5407 2597/2461/5243 +f 2472/2490/5272 2470/2626/5408 2643/2499/5281 +f 2615/2573/5355 2616/2537/5319 2661/2462/5244 +f 2527/2575/5357 2710/2507/5289 2704/2506/5288 +f 2609/2421/5203 2410/2627/5409 2411/2422/5204 +f 2487/2474/5256 2671/2442/5224 2670/2475/5257 +f 2507/2481/5263 2506/2414/5196 2667/2413/5195 +f 2650/2458/5240 2555/2610/5392 2505/2456/5238 +f 2568/2628/5410 2577/2479/5261 2512/2584/5366 +f 2555/2610/5392 2561/2525/5307 2488/2527/5309 +f 2407/2629/5411 2616/2537/5319 2615/2573/5355 +f 2732/2600/5382 2729/2594/5376 2629/2513/5295 +f 2575/2478/5260 2592/2549/5331 2593/2432/5214 +f 2663/2630/5412 2673/2533/5315 2686/2416/5198 +f 2627/2631/5413 2720/2482/5264 2727/2565/5347 +f 2727/2565/5347 2720/2482/5264 2728/2566/5348 +f 2548/2522/5304 2525/2579/5361 2515/2448/5230 +f 2702/2453/5235 2703/2632/5414 2649/2427/5209 +f 2708/2483/5265 2641/2491/5273 2642/2633/5415 +f 2609/2421/5203 2409/2634/5416 2410/2627/5409 +f 2633/2554/5336 2638/2587/5369 2467/2552/5334 +f 2441/2635/5417 2707/2439/5221 2705/2438/5220 +f 2674/2524/5306 2676/2604/5386 2601/2460/5242 +f 2642/2633/5415 2463/2636/5418 2630/2637/5419 +f 2524/2638/5420 2723/2616/5398 2724/2570/5352 +f 2729/2594/5376 2732/2600/5382 2731/2567/5349 +f 2617/2639/5421 2741/2516/5298 2597/2461/5243 +f 2556/2435/5217 2589/2437/5219 2504/2465/5247 +f 2687/2493/5275 2690/2564/5346 2479/2563/5345 +f 2587/2433/5215 2593/2432/5214 2592/2549/5331 +f 2414/2640/5422 2413/2468/5250 2613/2408/5190 +f 2573/2538/5320 2652/2504/5286 2653/2539/5321 +f 2691/2641/5423 2694/2583/5365 2692/2582/5364 +f 2652/2504/5286 2573/2538/5320 2564/2505/5287 +f 2671/2442/5224 2487/2474/5256 2662/2642/5424 +f 2480/2494/5276 2482/2418/5200 2672/2419/5201 +f 2686/2416/5198 2673/2533/5315 2685/2492/5274 +f 2582/2424/5206 2489/2643/5425 2588/2434/5216 +f 2682/2576/5358 2602/2503/5285 2603/2502/5284 +f 2674/2524/5306 2675/2644/5426 2676/2604/5386 +f 2492/2645/5427 2494/2646/5428 2552/2496/5278 +f 2420/2647/5429 2421/2621/5403 2607/2534/5316 +f 2550/2590/5372 2582/2424/5206 2572/2560/5342 +f 2643/2499/5281 2698/2532/5314 2648/2488/5270 +f 2499/2467/5249 2502/2411/5193 2504/2465/5247 +f 2583/2436/5218 2577/2479/5261 2578/2485/5267 +f 2719/2470/5252 2716/2454/5236 2532/2596/5378 +f 2627/2631/5413 2727/2565/5347 2628/2648/5430 +f 2576/2649/5431 2568/2628/5410 2569/2546/5328 +f 2679/2614/5396 2680/2650/5432 2598/2651/5433 +f 2574/2550/5332 2575/2478/5260 2566/2652/5434 +f 2580/2561/5343 2581/2447/5229 2587/2433/5215 +f 2506/2414/5196 2505/2456/5238 2672/2419/5201 +f 2535/2556/5338 2536/2607/5389 2675/2644/5426 +f 2623/2653/5435 2626/2654/5436 2740/2655/5437 +f 2630/2637/5419 2637/2656/5438 2636/2559/5341 +f 2558/2611/5393 2559/2657/5439 2563/2548/5330 +f 2658/2658/5440 2661/2462/5244 2616/2537/5319 +f 2459/2659/5441 2626/2654/5436 2624/2660/5442 +f 2607/2534/5316 2673/2533/5315 2663/2630/5412 +f 2700/2428/5210 2709/2508/5290 2635/2426/5208 +f 2656/2464/5246 2660/2409/5191 2499/2467/5249 +f 2661/2462/5244 2657/2463/5245 2404/2661/5443 +f 2625/2512/5294 2461/2542/5324 2629/2513/5295 +f 2557/2608/5390 2563/2548/5330 2562/2547/5329 +f 2607/2534/5316 2606/2406/5188 2420/2647/5429 +f 2665/2662/5444 2502/2411/5193 2659/2410/5192 +f 2485/2663/5445 2668/2664/5446 2667/2413/5195 +f 2704/2506/5288 2701/2452/5234 2528/2612/5394 +f 2674/2524/5306 2688/2523/5305 2675/2644/5426 +f 2654/2423/5205 2489/2643/5425 2582/2424/5206 +f 2697/2620/5402 2439/2528/5310 2706/2530/5312 +f 2552/2496/5278 2494/2646/5428 2496/2497/5279 +f 2638/2587/5369 2631/2519/5301 2639/2518/5300 +f 2432/2665/5447 2433/2666/5448 2688/2523/5305 +f 2445/2569/5351 2725/2602/5384 2724/2570/5352 +f 2541/2667/5449 2562/2547/5329 2513/2606/5388 +f 2739/2668/5450 2624/2660/5442 2623/2653/5435 +f 2483/2669/5451 2484/2670/5452 2667/2413/5195 +f 2732/2600/5382 2629/2513/5295 2622/2543/5325 +f 2541/2667/5449 2536/2607/5389 2557/2608/5390 +f 2647/2671/5453 2468/2672/5454 2646/2673/5455 +f 2505/2456/5238 2506/2414/5196 2651/2457/5239 +f 2731/2567/5349 2733/2592/5374 2729/2594/5376 +f 2727/2565/5347 2732/2600/5382 2622/2543/5325 +f 2680/2650/5432 2682/2576/5358 2603/2502/5284 +f 2610/2674/5456 2419/2469/5251 2417/2675/5457 +f 2618/2676/5458 2742/2677/5459 2617/2639/5421 +f 2526/2678/5460 2529/2679/5461 2532/2596/5378 +f 2522/2440/5222 2523/2480/5262 2542/2540/5322 +f 2684/2577/5359 2682/2576/5358 2680/2650/5432 +f 2537/2588/5370 2538/2544/5326 2511/2680/5462 +f 2675/2644/5426 2677/2681/5463 2676/2604/5386 +f 2629/2513/5295 2454/2581/5363 2456/2682/5464 +f 2565/2683/5465 2574/2550/5332 2566/2652/5434 +f 2703/2632/5414 2701/2452/5234 2704/2506/5288 +f 2642/2633/5415 2640/2558/5340 2718/2455/5237 +f 2514/2684/5466 2538/2544/5326 2513/2606/5388 +f 2664/2407/5189 2663/2630/5412 2665/2662/5444 +f 2712/2578/5360 2713/2405/5187 2631/2519/5301 +f 2556/2435/5217 2502/2411/5193 2577/2479/5261 +f 2530/2685/5467 2531/2472/5254 2490/2444/5226 +f 2597/2461/5243 2424/2686/5468 2426/2687/5469 +f 2628/2648/5430 2727/2565/5347 2622/2543/5325 +f 2700/2428/5210 2704/2506/5288 2709/2508/5290 +f 2613/2408/5190 2658/2658/5440 2609/2421/5203 +f 2404/2661/5443 2614/2572/5354 2661/2462/5244 +f 2594/2446/5228 2567/2495/5277 2575/2478/5260 +f 2672/2419/5201 2666/2412/5194 2506/2414/5196 +f 2444/2431/5213 2446/2571/5353 2723/2616/5398 +f 2632/2688/5470 2712/2578/5360 2631/2519/5301 +f 2684/2577/5359 2680/2650/5432 2681/2689/5471 +f 2678/2613/5395 2677/2681/5463 2679/2614/5396 +f 2612/2690/5472 2738/2691/5473 2611/2692/5474 +f 2428/2517/5299 2429/2459/5241 2597/2461/5243 +f 2536/2607/5389 2677/2681/5463 2675/2644/5426 +f 2465/2586/5368 2630/2637/5419 2464/2693/5475 +f 2496/2497/5279 2495/2694/5476 2497/2526/5308 +f 2565/2683/5465 2564/2505/5287 2573/2538/5320 +f 2557/2608/5390 2509/2555/5337 2558/2611/5393 +f 2541/2667/5449 2540/2695/5477 2681/2689/5471 +f 2629/2513/5295 2456/2682/5464 2455/2514/5296 +f 2606/2406/5188 2613/2408/5190 2420/2647/5429 +f 2499/2467/5249 2501/2443/5225 2656/2464/5246 +f 2676/2604/5386 2678/2613/5395 2600/2605/5387 +f 2608/2535/5317 2605/2696/5478 2685/2492/5274 +f 2423/2697/5479 2595/2501/5283 2422/2698/5480 +f 2626/2654/5436 2623/2653/5435 2624/2660/5442 +f 2521/2598/5380 2522/2440/5222 2544/2541/5323 +f 2667/2413/5195 2668/2664/5446 2507/2481/5263 +f 2438/2699/5481 2439/2528/5310 2697/2620/5402 +f 2659/2410/5192 2661/2462/5244 2658/2658/5440 +f 2596/2700/5482 2423/2697/5479 2425/2701/5483 +f 2707/2439/5221 2722/2429/5211 2523/2480/5262 +f 2597/2461/5243 2599/2615/5397 2598/2651/5433 +f 2599/2615/5397 2597/2461/5243 2600/2605/5387 +f 2597/2461/5243 2601/2460/5242 2600/2605/5387 +f 2669/2521/5303 2508/2441/5223 2507/2481/5263 +f 2648/2488/5270 2649/2427/5209 2469/2489/5271 +f 2705/2438/5220 2522/2440/5222 2521/2598/5380 +f 2507/2481/5263 2668/2664/5446 2669/2521/5303 +f 2541/2667/5449 2557/2608/5390 2562/2547/5329 +f 2683/2417/5199 2684/2577/5359 2540/2695/5477 +f 2633/2554/5336 2631/2519/5301 2638/2587/5369 +f 2429/2459/5241 2430/2702/5484 2601/2460/5242 +f 2657/2463/5245 2405/2703/5485 2404/2661/5443 +f 2500/2466/5248 2504/2465/5247 2503/2704/5486 +f 2690/2564/5346 2687/2493/5275 2554/2591/5373 +f 2534/2595/5377 2527/2575/5357 2526/2678/5460 +f 2579/2486/5268 2570/2618/5400 2580/2561/5343 +f 2728/2566/5348 2720/2482/5264 2719/2470/5252 +f 2517/2450/5232 2520/2477/5259 2519/2515/5297 +f 2645/2705/5487 2472/2490/5272 2647/2671/5453 +f 2404/2661/5443 2406/2706/5488 2614/2572/5354 +f 2612/2690/5472 2611/2692/5474 2610/2674/5456 +f 2711/2707/5489 2710/2507/5289 2712/2578/5360 +f 2613/2408/5190 2609/2421/5203 2415/2708/5490 +f 2492/2645/5427 2552/2496/5278 2491/2445/5227 +f 2599/2615/5397 2600/2605/5387 2678/2613/5395 +f 2597/2461/5243 2426/2687/5469 2620/2624/5406 +f 2596/2700/5482 2598/2651/5433 2604/2709/5491 +f 2695/2498/5280 2698/2532/5314 2643/2499/5281 +f 2559/2657/5439 2571/2617/5399 2563/2548/5330 +f 2723/2616/5398 2524/2638/5420 2523/2480/5262 +f 2563/2548/5330 2570/2618/5400 2569/2546/5328 +f 2570/2618/5400 2571/2617/5399 2580/2561/5343 +f 2528/2612/5394 2527/2575/5357 2704/2506/5288 +f 2449/2710/5492 2730/2593/5375 2733/2592/5374 +f 2726/2711/5493 2449/2710/5492 2733/2592/5374 +f 2655/2425/5207 2550/2590/5372 2520/2477/5259 +f 2728/2566/5348 2530/2685/5467 2518/2476/5258 +f 2559/2657/5439 2544/2541/5323 2547/2509/5291 +f 2519/2515/5297 2550/2590/5372 2551/2568/5350 +f 2591/2551/5333 2585/2487/5269 2586/2712/5494 +f 2595/2501/5283 2423/2697/5479 2596/2700/5482 +f 2549/2511/5293 2543/2510/5292 2542/2540/5322 +f 2631/2519/5301 2633/2554/5336 2632/2688/5470 +f 2632/2688/5470 2633/2554/5336 2634/2609/5391 +f 2633/2554/5336 2635/2426/5208 2634/2609/5391 +f 2424/2686/5468 2597/2461/5243 2425/2701/5483 +f 2693/2619/5401 2689/2557/5339 2435/2713/5495 +f 2604/2709/5491 2595/2501/5283 2596/2700/5482 +f 2644/2714/5496 2736/2715/5497 2645/2705/5487 +f 2532/2596/5378 2534/2595/5377 2526/2678/5460 +f 2421/2621/5403 2608/2535/5317 2607/2534/5316 +f 2511/2680/5462 2538/2544/5326 2514/2684/5466 +f 2497/2526/5308 2498/2589/5371 2488/2527/5309 +f 2533/2471/5253 2532/2596/5378 2529/2679/5461 +f 2430/2702/5484 2431/2716/5498 2688/2523/5305 +f 2601/2460/5242 2430/2702/5484 2688/2523/5305 +f 2492/2645/5427 2493/2717/5499 2495/2694/5476 +f 2687/2493/5275 2505/2456/5238 2554/2591/5373 +f 2425/2701/5483 2597/2461/5243 2596/2700/5482 +f 2499/2467/5249 2660/2409/5191 2502/2411/5193 +f 2669/2521/5303 2670/2475/5257 2508/2441/5223 +f 2461/2542/5324 2462/2718/5500 2628/2648/5430 +f 2518/2476/5258 2654/2423/5205 2655/2425/5207 +f 2567/2495/5277 2566/2652/5434 2575/2478/5260 +f 2527/2575/5357 2528/2612/5394 2526/2678/5460 +f 2733/2592/5374 2518/2476/5258 2516/2449/5231 +f 2666/2412/5194 2482/2418/5200 2483/2669/5451 +f 2639/2518/5300 2637/2656/5438 2630/2637/5419 +f 2697/2620/5402 2706/2530/5312 2546/2599/5381 +f 2665/2662/5444 2663/2630/5412 2686/2416/5198 +f 2650/2458/5240 2564/2505/5287 2560/2719/5501 +f 2502/2411/5193 2556/2435/5217 2504/2465/5247 +f 2447/2623/5405 2726/2711/5493 2721/2603/5385 +f 2406/2706/5488 2615/2573/5355 2614/2572/5354 +f 2606/2406/5188 2663/2630/5412 2664/2407/5189 +f 2580/2561/5343 2585/2487/5269 2579/2486/5268 +f 2589/2437/5219 2590/2720/5502 2573/2538/5320 +f 2649/2427/5209 2635/2426/5208 2633/2554/5336 +f 2413/2468/5250 2417/2675/5457 2419/2469/5251 +f 2529/2679/5461 2493/2717/5499 2531/2472/5254 +f 2677/2681/5463 2678/2613/5395 2676/2604/5386 +f 2733/2592/5374 2731/2567/5349 2518/2476/5258 +f 2613/2408/5190 2664/2407/5189 2658/2658/5440 +f 2665/2662/5444 2686/2416/5198 2538/2544/5326 +f 2713/2405/5187 2715/2404/5186 2637/2656/5438 +f 2724/2570/5352 2725/2602/5384 2525/2579/5361 +f 2625/2512/5294 2739/2668/5450 2460/2721/5503 +f 2497/2526/5308 2561/2525/5307 2496/2497/5279 +f 2586/2712/5494 2580/2561/5343 2587/2433/5215 +f 2528/2612/5394 2701/2452/5234 2498/2589/5371 +f 2572/2560/5342 2547/2509/5291 2548/2522/5304 +f 2527/2575/5357 2534/2595/5377 2714/2574/5356 +f 2651/2457/5239 2506/2414/5196 2507/2481/5263 +f 2578/2485/5267 2590/2720/5502 2584/2484/5266 +f 2683/2417/5199 2685/2492/5274 2682/2576/5358 +f 2490/2444/5226 2531/2472/5254 2491/2445/5227 +f 2560/2719/5501 2565/2683/5465 2566/2652/5434 +f 2718/2455/5237 2636/2559/5341 2715/2404/5186 +f 2540/2695/5477 2684/2577/5359 2681/2689/5471 +f 2681/2689/5471 2677/2681/5463 2536/2607/5389 +f 2705/2438/5220 2706/2530/5312 2440/2529/5311 +f 2545/2722/5504 2559/2657/5439 2558/2611/5393 +f 2592/2549/5331 2575/2478/5260 2574/2550/5332 +f 2546/2599/5381 2521/2598/5380 2544/2541/5323 +f 2571/2617/5399 2559/2657/5439 2547/2509/5291 +f 2704/2506/5288 2700/2428/5210 2703/2632/5414 +f 2619/2625/5407 2618/2676/5458 2617/2639/5421 +f 2531/2472/5254 2530/2685/5467 2728/2566/5348 +f 2624/2660/5442 2625/2512/5294 2459/2659/5441 +f 2710/2507/5289 2714/2574/5356 2712/2578/5360 +f 2688/2523/5305 2431/2716/5498 2432/2665/5447 +f 2591/2551/5333 2574/2550/5332 2573/2538/5320 +f 2590/2720/5502 2589/2437/5219 2584/2484/5266 +f 2630/2637/5419 2465/2586/5368 2638/2587/5369 +f 2688/2523/5305 2689/2557/5339 2675/2644/5426 +f 2719/2470/5252 2708/2483/5265 2718/2455/5237 +f 2585/2487/5269 2590/2720/5502 2578/2485/5267 +f 2723/2616/5398 2722/2429/5211 2444/2431/5213 +f 2406/2706/5488 2407/2629/5411 2615/2573/5355 +f 2692/2582/5364 2695/2498/5280 2476/2723/5505 +f 2447/2623/5405 2449/2710/5492 2726/2711/5493 +f 2625/2512/5294 2624/2660/5442 2739/2668/5450 +f 2647/2671/5453 2644/2714/5496 2645/2705/5487 +f 2450/2724/5506 2629/2513/5295 2729/2594/5376 +f 2630/2637/5419 2636/2559/5341 2640/2558/5340 +f 2711/2707/5489 2712/2578/5360 2632/2688/5470 +f 2523/2480/5262 2524/2638/5420 2542/2540/5322 +f 2662/2642/5424 2403/2725/5507 2657/2463/5245 +f 2496/2497/5279 2494/2646/5428 2495/2694/5476 +f 2685/2492/5274 2605/2696/5478 2602/2503/5285 +f 2493/2717/5499 2492/2645/5427 2491/2445/5227 +f 2548/2522/5304 2515/2448/5230 2519/2515/5297 +f 2437/2726/5508 2438/2699/5481 2697/2620/5402 +f 2520/2477/5259 2517/2450/5232 2516/2449/5231 +f 2539/2415/5197 2540/2695/5477 2513/2606/5388 +f 2613/2408/5190 2415/2708/5490 2414/2640/5422 +f 2696/2531/5313 2694/2583/5365 2553/2597/5379 +f 2664/2407/5189 2665/2662/5444 2659/2410/5192 +f 2544/2541/5323 2522/2440/5222 2542/2540/5322 +f 2649/2427/5209 2633/2554/5336 2469/2489/5271 +f 2513/2606/5388 2510/2585/5367 2514/2684/5466 +f 2698/2532/5314 2702/2453/5235 2648/2488/5270 +f 2687/2493/5275 2479/2563/5345 2480/2494/5276 +f 2619/2625/5407 2617/2639/5421 2597/2461/5243 +f 2591/2551/5333 2586/2712/5494 2592/2549/5331 +f 2604/2709/5491 2680/2650/5432 2603/2502/5284 +f 2529/2679/5461 2526/2678/5460 2493/2717/5499 +f 2721/2603/5385 2515/2448/5230 2525/2579/5361 +f 2516/2449/5231 2515/2448/5230 2726/2711/5493 +f 2640/2558/5340 2642/2633/5415 2630/2637/5419 +f 2525/2579/5361 2548/2522/5304 2549/2511/5293 +f 2566/2652/5434 2561/2525/5307 2560/2719/5501 +f 2510/2585/5367 2577/2479/5261 2511/2680/5462 +f 2693/2619/5401 2509/2555/5337 2689/2557/5339 +f 2683/2417/5199 2540/2695/5477 2539/2415/5197 +f 2729/2594/5376 2452/2727/5509 2451/2728/5510 +f 2599/2615/5397 2679/2614/5396 2598/2651/5433 +f 2655/2425/5207 2582/2424/5206 2550/2590/5372 +f 2665/2662/5444 2537/2588/5370 2502/2411/5193 +f 2568/2628/5410 2576/2649/5431 2577/2479/5261 +f 2687/2493/5275 2672/2419/5201 2505/2456/5238 +f 2500/2466/5248 2503/2704/5486 2652/2504/5286 +f 2562/2547/5329 2568/2628/5410 2512/2584/5366 +f 2485/2663/5445 2486/2520/5302 2668/2664/5446 +f 2608/2535/5317 2685/2492/5274 2673/2533/5315 +f 2493/2717/5499 2526/2678/5460 2495/2694/5476 +f 2560/2719/5501 2555/2610/5392 2650/2458/5240 +f 2567/2495/5277 2594/2446/5228 2552/2496/5278 +f 2501/2443/5225 2499/2467/5249 2500/2466/5248 +f 2562/2547/5329 2512/2584/5366 2513/2606/5388 +f 2709/2508/5290 2711/2707/5489 2634/2609/5391 +f 2690/2564/5346 2694/2583/5365 2691/2641/5423 +f 2642/2633/5415 2718/2455/5237 2708/2483/5265 +f 2407/2629/5411 2408/2536/5318 2616/2537/5319 +f 2658/2658/5440 2664/2407/5189 2659/2410/5192 +f 2616/2537/5319 2609/2421/5203 2658/2658/5440 +f 2716/2454/5236 2715/2404/5186 2717/2403/5185 +f 2528/2612/5394 2497/2526/5308 2495/2694/5476 +f 2592/2549/5331 2586/2712/5494 2587/2433/5215 +f 2641/2491/5273 2720/2482/5264 2627/2631/5413 +f 2577/2479/5261 2576/2649/5431 2578/2485/5267 +f 2656/2464/5246 2671/2442/5224 2662/2642/5424 +f 2524/2638/5420 2525/2579/5361 2542/2540/5322 +f 2580/2561/5343 2586/2712/5494 2585/2487/5269 +f 2582/2424/5206 2581/2447/5229 2572/2560/5342 +f 2562/2547/5329 2569/2546/5328 2568/2628/5410 +f 2509/2555/5337 2546/2599/5381 2558/2611/5393 +f 2703/2632/5414 2702/2453/5235 2701/2452/5234 +f 2656/2464/5246 2662/2642/5424 2657/2463/5245 +f 2504/2465/5247 2589/2437/5219 2653/2539/5321 +f 2462/2718/5500 2627/2631/5413 2628/2648/5430 +f 2538/2544/5326 2537/2588/5370 2665/2662/5444 +f 2581/2447/5229 2588/2434/5216 2587/2433/5215 +f 2483/2669/5451 2667/2413/5195 2666/2412/5194 +f 2546/2599/5381 2545/2722/5504 2558/2611/5393 +f 2546/2599/5381 2509/2555/5337 2693/2619/5401 +f 2540/2695/5477 2541/2667/5449 2513/2606/5388 +f 2691/2641/5423 2692/2582/5364 2477/2729/5511 +f 2503/2704/5486 2653/2539/5321 2652/2504/5286 +f 2417/2675/5457 2612/2690/5472 2610/2674/5456 +f 2702/2453/5235 2698/2532/5314 2699/2451/5233 +f 2726/2711/5493 2733/2592/5374 2516/2449/5231 +f 2533/2471/5253 2719/2470/5252 2532/2596/5378 +f 2546/2599/5381 2544/2541/5323 2545/2722/5504 +f 2469/2489/5271 2468/2672/5454 2472/2490/5272 +f 2572/2560/5342 2580/2561/5343 2571/2617/5399 +f 2681/2689/5471 2536/2607/5389 2541/2667/5449 +f 2515/2448/5230 2721/2603/5385 2726/2711/5493 +f 2579/2486/5268 2578/2485/5267 2569/2546/5328 +f 2610/2674/5456 2611/2692/5474 2737/2730/5512 +f 2594/2446/5228 2588/2434/5216 2489/2643/5425 +f 2707/2439/5221 2441/2635/5417 2443/2601/5383 +f 2496/2497/5279 2561/2525/5307 2567/2495/5277 +f 2559/2657/5439 2545/2722/5504 2544/2541/5323 +f 2670/2475/5257 2669/2521/5303 2481/2473/5255 +f 2629/2513/5295 2450/2724/5506 2453/2580/5362 +f 2699/2451/5233 2488/2527/5309 2498/2589/5371 +f 2535/2556/5338 2509/2555/5337 2557/2608/5390 +f 2632/2688/5470 2634/2609/5391 2711/2707/5489 +f 2639/2518/5300 2713/2405/5187 2637/2656/5438 +f 2462/2718/5500 2463/2636/5418 2641/2491/5273 +f 2530/2685/5467 2490/2444/5226 2489/2643/5425 +f 2421/2621/5403 2422/2698/5480 2595/2501/5283 +f 2405/2703/5485 2657/2463/5245 2403/2725/5507 +f 2455/2514/5296 2459/2659/5441 2625/2512/5294 +f 2531/2472/5254 2533/2471/5253 2529/2679/5461 +f 2551/2568/5350 2572/2560/5342 2548/2522/5304 +f 2538/2544/5326 2539/2415/5197 2513/2606/5388 +f 2647/2671/5453 2472/2490/5272 2468/2672/5454 +f 2489/2643/5425 2654/2423/5205 2518/2476/5258 +f 2564/2505/5287 2565/2683/5465 2560/2719/5501 +f 2470/2626/5408 2473/2545/5327 2643/2499/5281 +f 2435/2713/5495 2437/2726/5508 2693/2619/5401 +f 2706/2530/5312 2705/2438/5220 2521/2598/5380 +f 2605/2696/5478 2608/2535/5317 2595/2501/5283 +f 2561/2525/5307 2566/2652/5434 2567/2495/5277 +f 2555/2610/5392 2554/2591/5373 2505/2456/5238 +f 2595/2501/5283 2602/2503/5285 2605/2696/5478 +f 2607/2534/5316 2663/2630/5412 2606/2406/5188 +f 2408/2536/5318 2409/2634/5416 2609/2421/5203 +f 2696/2531/5313 2699/2451/5233 2698/2532/5314 +f 2639/2518/5300 2630/2637/5419 2638/2587/5369 +f 2570/2618/5400 2579/2486/5268 2569/2546/5328 +f 2716/2454/5236 2717/2403/5185 2534/2595/5377 +f 2508/2441/5223 2501/2443/5225 2651/2457/5239 +f 2569/2546/5328 2578/2485/5267 2576/2649/5431 +f 2633/2554/5336 2466/2553/5335 2469/2489/5271 +f 2685/2492/5274 2602/2503/5285 2682/2576/5358 +f 2643/2499/5281 2648/2488/5270 2472/2490/5272 +f 2501/2443/5225 2500/2466/5248 2652/2504/5286 +f 2604/2709/5491 2603/2502/5284 2595/2501/5283 +f 2622/2543/5325 2461/2542/5324 2628/2648/5430 +f 2719/2470/5252 2718/2455/5237 2716/2454/5236 +f 2475/2731/5513 2477/2729/5511 2692/2582/5364 +f 2451/2728/5510 2450/2724/5506 2729/2594/5376 +f 2528/2612/5394 2495/2694/5476 2526/2678/5460 +f 2547/2509/5291 2572/2560/5342 2571/2617/5399 +f 2653/2539/5321 2503/2704/5486 2504/2465/5247 +f 2574/2550/5332 2565/2683/5465 2573/2538/5320 +f 2518/2476/5258 2655/2425/5207 2520/2477/5259 +f 2537/2588/5370 2511/2680/5462 2577/2479/5261 +f 2488/2527/5309 2699/2451/5233 2696/2531/5313 +f 2722/2429/5211 2707/2439/5221 2443/2601/5383 +f 2492/2645/5427 2495/2694/5476 2494/2646/5428 +f 2721/2603/5385 2725/2602/5384 2448/2622/5404 +f 2651/2457/5239 2501/2443/5225 2652/2504/5286 +f 2588/2434/5216 2594/2446/5228 2593/2432/5214 +f 2691/2641/5423 2477/2729/5511 2478/2562/5344 +f 2487/2474/5256 2403/2725/5507 2662/2642/5424 +f 2490/2444/5226 2594/2446/5228 2489/2643/5425 +f 2723/2616/5398 2523/2480/5262 2722/2429/5211 +f 2420/2647/5429 2613/2408/5190 2419/2469/5251 +f 2668/2664/5446 2486/2520/5302 2669/2521/5303 +f 2725/2602/5384 2445/2569/5351 2448/2622/5404 +f 2485/2663/5445 2667/2413/5195 2484/2670/5452 +f 2597/2461/5243 2598/2651/5433 2596/2700/5482 +f 2694/2583/5365 2696/2531/5313 2695/2498/5280 +f 2463/2636/5418 2464/2693/5475 2630/2637/5419 +f 2670/2475/5257 2671/2442/5224 2508/2441/5223 +f 2690/2564/5346 2691/2641/5423 2478/2562/5344 +f 2688/2523/5305 2433/2666/5448 2689/2557/5339 +f 2525/2579/5361 2524/2638/5420 2724/2570/5352 +f 2463/2636/5418 2642/2633/5415 2641/2491/5273 +f 2715/2404/5186 2636/2559/5341 2637/2656/5438 +f 2680/2650/5432 2604/2709/5491 2598/2651/5433 +f 2452/2727/5509 2729/2594/5376 2730/2593/5375 +f 2677/2681/5463 2681/2689/5471 2679/2614/5396 +f 2689/2557/5339 2436/2732/5514 2435/2713/5495 +f 2641/2491/5273 2627/2631/5413 2462/2718/5500 +f 2476/2723/5505 2475/2731/5513 2692/2582/5364 +f 2649/2427/5209 2703/2632/5414 2700/2428/5210 +f 2584/2484/5266 2583/2436/5218 2578/2485/5267 +f 2659/2410/5192 2660/2409/5191 2661/2462/5244 +f 2440/2529/5311 2441/2635/5417 2705/2438/5220 +f 2491/2445/5227 2531/2472/5254 2493/2717/5499 +f 2564/2505/5287 2650/2458/5240 2651/2457/5239 +f 2710/2507/5289 2711/2707/5489 2709/2508/5290 +f 2675/2644/5426 2689/2557/5339 2535/2556/5338 +f 2693/2619/5401 2437/2726/5508 2697/2620/5402 +f 2474/2500/5282 2476/2723/5505 2695/2498/5280 +f 2717/2403/5185 2713/2405/5187 2714/2574/5356 +f 2609/2421/5203 2412/2420/5202 2415/2708/5490 +f 2434/2733/5515 2436/2732/5514 2689/2557/5339 +f 2511/2680/5462 2514/2684/5466 2510/2585/5367 +f 2585/2487/5269 2591/2551/5333 2590/2720/5502 +f 2660/2409/5191 2656/2464/5246 2657/2463/5245 +f 2681/2689/5471 2680/2650/5432 2679/2614/5396 +f 2452/2727/5509 2730/2593/5375 2449/2710/5492 +f 2728/2566/5348 2518/2476/5258 2731/2567/5349 +f 2645/2705/5487 2736/2715/5497 2471/2734/5516 +f 2736/2715/5497 2644/2714/5496 2647/2671/5453 +f 2518/2476/5258 2530/2685/5467 2489/2643/5425 +f 2738/2691/5473 2612/2690/5472 2416/2735/5517 +f 2611/2692/5474 2738/2691/5473 2737/2730/5512 +f 2573/2538/5320 2590/2720/5502 2591/2551/5333 +f 2418/2736/5518 2610/2674/5456 2737/2730/5512 +f 2555/2610/5392 2560/2719/5501 2561/2525/5307 +f 2553/2597/5379 2554/2591/5373 2555/2610/5392 +f 2433/2666/5448 2434/2733/5515 2689/2557/5339 +f 2734/2737/5519 2735/2738/5519 2458/2739/5519 +f 2740/2655/5437 2626/2654/5436 2457/2740/5520 +f 2623/2653/5435 2740/2655/5437 2739/2668/5450 +f 2621/2741/5521 2741/2516/5522 2617/2639/5523 +f 2617/2639/5421 2742/2677/5459 2741/2516/5524 +f 2649/2427/5209 2648/2488/5270 2702/2453/5235 +f 2534/2595/5377 2717/2403/5185 2714/2574/5356 +f 2741/2516/5524 2742/2677/5459 2427/2742/5525 +f 2742/2677/5459 2618/2676/5458 2619/2625/5407 +f 3056/2743/5526 3052/2744/5527 3054/2745/5528 +f 2945/2746/5529 2952/2747/5530 3003/2748/5531 +f 2999/2749/5532 2841/2750/5533 2998/2751/5534 +f 3005/2752/5535 2845/2753/5536 3006/2754/5537 +f 2878/2755/5538 3022/2756/5539 3025/2757/5540 +f 2821/2758/5541 3011/2759/5542 3005/2752/5535 +f 2752/2760/5543 2751/2761/5544 2948/2762/5545 +f 2993/2763/5546 2994/2764/5547 2921/2765/5548 +f 2974/2766/5549 3039/2767/5550 2988/2768/5551 +f 3061/2769/5552 2784/2770/5553 2782/2771/5554 +f 2932/2772/5555 2927/2773/5556 2926/2774/5557 +f 2895/2775/5558 2928/2776/5559 2922/2777/5560 +f 3044/2778/5561 2861/2779/5562 3046/2780/5563 +f 2847/2781/5564 2840/2782/5565 3010/2783/5566 +f 2829/2784/5567 2933/2785/5568 2830/2786/5569 +f 2920/2787/5570 2927/2773/5556 2921/2765/5548 +f 2854/2788/5571 2856/2789/5572 2855/2790/5573 +f 3038/2791/5574 3041/2792/5575 3040/2793/5576 +f 3055/2794/5577 3054/2745/5528 3057/2795/5578 +f 2844/2796/5579 2989/2797/5580 2990/2798/5581 +f 2769/2799/5582 2936/2800/5583 2940/2801/5584 +f 3000/2802/5585 2996/2803/5586 2999/2749/5532 +f 3010/2783/5566 2840/2782/5565 2995/2804/5587 +f 2843/2805/5588 2838/2806/5589 2839/2807/5590 +f 2753/2808/5591 2952/2747/5530 2759/2809/5592 +f 3058/2810/5593 2870/2811/5594 2872/2812/5595 +f 2820/2813/5596 3009/2814/5597 2826/2815/5598 +f 2855/2790/5573 2859/2816/5599 2857/2817/5600 +f 2914/2818/5601 2933/2785/5568 2932/2772/5555 +f 2916/2819/5602 2895/2775/5558 2922/2777/5560 +f 2861/2779/5562 2862/2820/5603 3046/2780/5563 +f 2846/2821/5604 2990/2798/5581 2847/2781/5564 +f 3059/2822/5605 3058/2810/5593 3047/2823/5606 +f 2922/2777/5560 2928/2776/5559 2923/2824/5607 +f 2917/2825/5608 2924/2826/5609 2918/2827/5610 +f 2987/2828/5611 2811/2829/5612 2808/2830/5613 +f 2980/2831/5614 3059/2822/5605 3047/2823/5606 +f 3025/2757/5540 3022/2756/5539 3024/2832/5615 +f 3011/2759/5542 2819/2833/5616 3026/2834/5617 +f 2906/2835/5618 2835/2836/5619 2891/2837/5620 +f 3034/2838/5621 2813/2839/5622 2982/2840/5623 +f 2934/2841/5624 2941/2842/5625 2942/2843/5626 +f 2991/2844/5627 2990/2798/5581 2903/2845/5628 +f 3043/2846/5629 3048/2847/5630 3049/2848/5631 +f 2886/2849/5632 2888/2850/5633 2882/2851/5634 +f 2964/2852/5635 2795/2853/5636 2968/2854/5637 +f 2856/2789/5572 2854/2788/5571 2858/2855/5638 +f 3078/2856/5639 2936/2800/5583 2768/2857/5640 +f 3052/2744/5527 2970/2858/5641 2978/2859/5642 +f 2825/2860/5643 3008/2861/5644 2820/2813/5596 +f 2887/2862/5645 2888/2850/5633 2886/2849/5632 +f 3027/2863/5646 2940/2801/5584 3013/2864/5647 +f 2900/2865/5648 2827/2866/5649 2836/2867/5650 +f 2779/2868/5651 3045/2869/5652 2780/2870/5653 +f 3034/2838/5621 3037/2871/5654 3035/2872/5655 +f 3012/2873/5656 2947/2874/5657 2946/2875/5658 +f 2748/2876/5659 2955/2877/5660 2948/2762/5545 +f 2933/2785/5568 2891/2837/5620 2830/2786/5569 +f 2928/2776/5559 2992/2878/5661 2912/2879/5662 +f 2881/2880/5663 2883/2881/5664 2886/2849/5632 +f 2800/2882/5665 2968/2854/5637 2961/2883/5666 +f 3025/2757/5540 2877/2884/5667 2878/2755/5538 +f 2812/2885/5668 2982/2840/5623 2813/2839/5622 +f 2908/2886/5669 2902/2887/5670 2901/2888/5671 +f 2931/2889/5672 2930/2890/5673 2913/2891/5674 +f 2806/2892/5675 2972/2893/5676 2805/2894/5677 +f 2848/2895/5678 3028/2896/5679 2874/2897/5680 +f 3057/2795/5578 2975/2898/5681 2979/2899/5682 +f 2911/2900/5683 2919/2901/5684 2920/2787/5570 +f 2817/2902/5685 3029/2903/5686 2818/2904/5687 +f 3066/2905/5688 3070/2906/5689 3067/2907/5690 +f 2858/2855/5638 2887/2862/5645 2890/2908/5691 +f 2785/2909/5692 2786/2910/5693 3063/2911/5694 +f 2953/2912/5695 3000/2802/5585 2954/2913/5696 +f 3053/2914/5697 2866/2915/5698 3049/2848/5631 +f 3022/2756/5539 3023/2916/5699 3021/2917/5700 +f 3053/2914/5697 3051/2918/5701 3052/2744/5527 +f 2864/2919/5702 2881/2880/5663 2888/2850/5633 +f 2968/2854/5637 2794/2920/5703 2793/2921/5704 +f 3034/2838/5621 3033/2922/5705 3031/2923/5706 +f 2851/2924/5707 2849/2925/5708 2916/2819/5602 +f 2804/2926/5709 2977/2927/5710 2806/2892/5675 +f 2841/2750/5533 2916/2819/5602 2876/2928/5711 +f 3040/2793/5576 2837/2929/5712 3038/2791/5574 +f 2911/2900/5683 2889/2930/5713 2890/2908/5691 +f 3033/2922/5705 2893/2931/5714 3029/2903/5686 +f 3072/2932/5715 3068/2933/5716 3069/2934/5717 +f 3055/2794/5577 2871/2935/5718 2873/2936/5719 +f 2893/2931/5714 3033/2922/5705 2892/2937/5720 +f 2860/2938/5721 3045/2869/5652 2885/2939/5722 +f 3066/2905/5688 3071/2940/5723 3070/2906/5689 +f 2783/2941/5724 3061/2769/5552 2782/2771/5554 +f 3064/2942/5725 2864/2919/5702 3060/2943/5726 +f 2940/2801/5584 2939/2944/5727 3015/2945/5728 +f 2849/2925/5708 2851/2924/5707 2852/2946/5729 +f 2875/2947/5730 2896/2948/5731 2874/2897/5680 +f 2889/2930/5713 2859/2816/5599 2858/2855/5638 +f 2881/2880/5663 2886/2849/5632 2882/2851/5634 +f 2892/2937/5720 3035/2872/5655 2827/2866/5649 +f 2974/2766/5549 2973/2949/5732 3048/2847/5630 +f 2827/2866/5649 2894/2950/5733 2892/2937/5720 +f 2902/2887/5670 2897/2951/5734 2896/2948/5731 +f 2867/2952/5735 2836/2867/5650 2837/2929/5712 +f 3017/2953/5736 2938/2954/5737 3018/2955/5738 +f 2786/2910/5693 3062/2956/5739 3063/2911/5694 +f 2910/2957/5740 2902/2887/5670 2909/2958/5741 +f 3067/2907/5690 2870/2811/5594 3058/2810/5593 +f 3032/2959/5742 2885/2939/5722 3036/2960/5743 +f 2947/2874/5657 2934/2841/5624 2761/2961/5744 +f 2788/2962/5745 3060/2943/5726 2787/2963/5746 +f 2959/2964/5747 2936/2800/5583 2958/2965/5748 +f 2811/2829/5612 2982/2840/5623 2809/2966/5749 +f 2954/2913/5696 3000/2802/5585 2955/2877/5660 +f 2866/2915/5698 3043/2846/5629 3049/2848/5631 +f 2948/2762/5545 2751/2761/5544 2750/2967/5750 +f 2826/2815/5598 3009/2814/5597 3010/2783/5566 +f 2846/2821/5604 3006/2754/5537 2845/2753/5536 +f 2989/2797/5580 2844/2796/5579 2894/2950/5733 +f 2907/2968/5751 2851/2924/5707 2916/2819/5602 +f 2894/2950/5733 2827/2866/5649 2900/2865/5648 +f 2747/2969/5752 2954/2913/5696 2955/2877/5660 +f 3071/2940/5723 2968/2854/5637 3068/2933/5716 +f 2914/2818/5601 2932/2772/5555 2931/2889/5672 +f 3002/2970/5753 3025/2757/5540 3012/2873/5656 +f 2966/2971/5754 3066/2905/5688 3059/2822/5605 +f 3066/2905/5688 3067/2907/5690 3059/2822/5605 +f 2887/2862/5645 2854/2788/5571 2864/2919/5702 +f 3041/2792/5575 2988/2768/5551 3042/2972/5755 +f 3047/2823/5606 2981/2973/5756 2980/2831/5614 +f 2948/2762/5545 2750/2967/5750 2749/2974/5757 +f 2972/2893/5676 2806/2892/5675 2977/2927/5710 +f 2781/2975/5758 3044/2778/5561 3046/2780/5563 +f 3013/2864/5647 2940/2801/5584 3015/2945/5728 +f 2981/2973/5756 2969/2976/5759 2802/2977/5760 +f 2863/2978/5761 3063/2911/5694 3062/2956/5739 +f 3068/2933/5716 3070/2906/5689 3071/2940/5723 +f 2956/2979/5762 2936/2800/5583 3078/2856/5639 +f 2895/2775/5558 2843/2805/5588 2928/2776/5559 +f 3026/2834/5617 2818/2904/5687 3029/2903/5686 +f 2926/2774/5557 2931/2889/5672 2932/2772/5555 +f 2754/2980/5763 2952/2747/5530 2753/2808/5591 +f 2912/2879/5662 2992/2878/5661 2991/2844/5627 +f 3030/2981/5764 3031/2923/5706 3033/2922/5705 +f 2991/2844/5627 2903/2845/5628 2912/2879/5662 +f 3010/2783/5566 3001/2982/5765 2826/2815/5598 +f 2819/2833/5616 3011/2759/5542 2821/2758/5541 +f 3025/2757/5540 3024/2832/5615 3012/2873/5656 +f 2921/2765/5548 2927/2773/5556 2828/2983/5766 +f 3021/2917/5700 2942/2843/5626 2941/2842/5625 +f 3013/2864/5647 3015/2945/5728 3014/2984/5767 +f 2831/2985/5768 2891/2837/5620 2833/2986/5769 +f 2760/2987/5770 2946/2875/5658 2761/2961/5744 +f 2889/2930/5713 2911/2900/5683 2921/2765/5548 +f 2982/2840/5623 2987/2828/5611 3037/2871/5654 +f 2838/2806/5589 2843/2805/5588 2841/2750/5533 +f 2922/2777/5560 2917/2825/5608 2916/2819/5602 +f 3058/2810/5593 2871/2935/5718 3055/2794/5577 +f 2966/2971/5754 2967/2988/5771 3066/2905/5688 +f 2915/2989/5772 2908/2886/5669 2907/2968/5751 +f 3018/2955/5738 2937/2990/5773 3019/2991/5774 +f 2913/2891/5674 2905/2992/5775 2914/2818/5601 +f 2919/2901/5684 2926/2774/5557 2920/2787/5570 +f 2845/2753/5536 3011/2759/5542 2844/2796/5579 +f 2874/2897/5680 3014/2984/5767 2875/2947/5730 +f 2962/2993/5776 3077/2994/5777 2965/2995/5778 +f 2969/2976/5759 2975/2898/5681 2976/2996/5779 +f 2897/2951/5734 2902/2887/5670 2898/2997/5780 +f 2997/2998/5781 2955/2877/5660 3000/2802/5585 +f 2798/2999/5782 2963/3000/5783 2965/2995/5778 +f 2946/2875/5658 3002/2970/5753 3012/2873/5656 +f 3039/2767/5550 2974/2766/5549 3048/2847/5630 +f 2995/2804/5587 2838/2806/5589 2999/2749/5532 +f 3000/2802/5585 2744/3001/5784 2996/2803/5586 +f 2964/2852/5635 2968/2854/5637 2800/2882/5665 +f 2896/2948/5731 2901/2888/5671 2902/2887/5670 +f 2946/2875/5658 2760/2987/5770 2945/2746/5529 +f 3004/3002/5785 2998/2751/5534 2841/2750/5533 +f 2824/3003/5786 3006/2754/5537 3007/3004/5787 +f 3043/2846/5629 2867/2952/5735 3040/2793/5576 +f 3013/2864/5647 3014/2984/5767 3027/2863/5646 +f 2993/2763/5546 2921/2765/5548 2828/2983/5766 +f 3036/2960/5743 3045/2869/5652 2779/2868/5651 +f 2891/2837/5620 2835/2836/5619 2833/2986/5769 +f 2977/2927/5710 2978/2859/5642 2970/2858/5641 +f 2772/3005/5788 3027/2863/5646 2773/3006/5789 +f 2785/2909/5692 3063/2911/5694 3064/2942/5725 +f 2880/3007/5790 2852/2946/5729 2901/2888/5671 +f 3076/3008/5791 2962/2993/5776 2963/3000/5783 +f 2822/3009/5792 3006/2754/5537 2823/3010/5793 +f 3071/2940/5723 2961/2883/5666 2968/2854/5637 +f 2880/3007/5790 2896/2948/5731 2875/2947/5730 +f 2986/3011/5794 2985/3012/5795 2807/3013/5796 +f 2844/2796/5579 2990/2798/5581 2845/2753/5536 +f 3070/2906/5689 3068/2933/5716 3072/2932/5715 +f 3066/2905/5688 2961/2883/5666 3071/2940/5723 +f 3019/2991/5774 2942/2843/5626 3021/2917/5700 +f 2949/3014/5797 2757/3015/5798 2759/2809/5592 +f 2957/3016/5799 2956/2979/5762 3079/3017/5800 +f 2865/3018/5801 2871/2935/5718 2868/3019/5802 +f 2861/2779/5562 2881/2880/5663 2862/2820/5603 +f 3023/2916/5699 3019/2991/5774 3021/2917/5700 +f 2876/2928/5711 2850/3020/5803 2877/2884/5667 +f 3014/2984/5767 3015/2945/5728 3016/3021/5804 +f 2968/2854/5637 2796/3022/5805 2794/2920/5703 +f 2904/3023/5806 2905/2992/5775 2913/2891/5674 +f 3042/2972/5755 3043/2846/5629 3040/2793/5576 +f 2981/2973/5756 3057/2795/5578 2979/2899/5682 +f 2853/3024/5807 2852/2946/5729 2877/2884/5667 +f 3003/2748/5531 3004/3002/5785 3002/2970/5753 +f 3051/2918/5701 2970/2858/5641 3052/2744/5527 +f 2895/2775/5558 2916/2819/5602 2841/2750/5533 +f 2869/3025/5808 2829/2784/5567 2870/2811/5594 +f 2936/2800/5583 2766/3026/5809 2764/3027/5810 +f 2967/2988/5771 2961/2883/5666 3066/2905/5688 +f 3039/2767/5550 3048/2847/5630 3043/2846/5629 +f 2952/2747/5530 2948/2762/5545 2997/2998/5781 +f 2744/3001/5784 3000/2802/5585 2953/2912/5695 +f 2933/2785/5568 2914/2818/5601 2906/2835/5618 +f 3011/2759/5542 2845/2753/5536 3005/2752/5535 +f 2784/2770/5553 3062/2956/5739 2786/2910/5693 +f 2971/3028/5811 2970/2858/5641 3051/2918/5701 +f 3023/2916/5699 3020/3029/5812 3019/2991/5774 +f 3017/2953/5736 3018/2955/5738 3016/3021/5804 +f 2951/3030/5813 2950/3031/5814 3075/3032/5815 +f 2768/2857/5640 2936/2800/5583 2769/2799/5582 +f 2875/2947/5730 3014/2984/5767 3016/3021/5804 +f 2804/2926/5709 2803/3033/5816 2969/2976/5759 +f 2835/2836/5619 2836/2867/5650 2834/3034/5817 +f 2904/3023/5806 2912/2879/5662 2903/2845/5628 +f 2896/2948/5731 2897/2951/5734 2848/2895/5678 +f 2880/3007/5790 3020/3029/5812 2879/3035/5818 +f 2968/2854/5637 2795/2853/5636 2796/3022/5805 +f 2945/2746/5529 2760/2987/5770 2952/2747/5530 +f 2838/2806/5589 2995/2804/5587 2840/2782/5565 +f 3015/2945/5728 2939/2944/5727 3017/2953/5736 +f 2947/2874/5657 3024/2832/5615 2944/3036/5819 +f 2763/3037/5820 2762/3038/5821 2934/2841/5624 +f 2965/2995/5778 2963/3000/5783 2962/2993/5776 +f 2860/2938/5721 2883/2881/5664 2861/2779/5562 +f 3006/2754/5537 2846/2821/5604 3007/3004/5787 +f 2778/3039/5822 3036/2960/5743 2779/2868/5651 +f 2998/2751/5534 2997/2998/5781 3000/2802/5585 +f 2935/3040/5823 2765/3041/5824 2763/3037/5820 +f 3046/2780/5563 2862/2820/5603 3061/2769/5552 +f 2936/2800/5583 2937/2990/5773 2938/2954/5737 +f 2938/2954/5737 2939/2944/5727 2936/2800/5583 +f 2936/2800/5583 2939/2944/5727 2940/2801/5584 +f 3008/2861/5644 2846/2821/5604 2847/2781/5564 +f 2987/2828/5611 2808/2830/5613 2988/2768/5551 +f 3044/2778/5561 2860/2938/5721 2861/2779/5562 +f 2846/2821/5604 3008/2861/5644 3007/3004/5787 +f 2880/3007/5790 2901/2888/5671 2896/2948/5731 +f 3022/2756/5539 2879/3035/5818 3023/2916/5699 +f 2972/2893/5676 2977/2927/5710 2970/2858/5641 +f 2769/2799/5582 2940/2801/5584 2770/3042/5825 +f 2996/2803/5586 2744/3001/5784 2745/3043/5826 +f 2839/2807/5590 2842/3044/5827 2843/2805/5588 +f 3029/2903/5686 2893/2931/5714 3026/2834/5617 +f 2873/2936/5719 2865/3018/5801 2866/2915/5698 +f 2918/2827/5610 2919/2901/5684 2909/2958/5741 +f 3067/2907/5690 3058/2810/5593 3059/2822/5605 +f 2856/2789/5572 2858/2855/5638 2859/2816/5599 +f 2984/3045/5828 2986/3011/5794 2811/2829/5612 +f 2744/3001/5784 2953/2912/5695 2746/3046/5829 +f 2951/3030/5813 2949/3014/5797 2950/3031/5814 +f 3050/3047/5830 3051/2918/5701 3049/2848/5631 +f 2952/2747/5530 2755/3048/5831 2948/2762/5545 +f 2831/2985/5768 2830/2786/5569 2891/2837/5620 +f 2938/2954/5737 3017/2953/5736 2939/2944/5727 +f 2936/2800/5583 2959/2964/5747 2766/3026/5809 +f 2935/3040/5823 2943/3049/5832 2937/2990/5773 +f 3034/2838/5621 2982/2840/5623 3037/2871/5654 +f 2898/2997/5780 2902/2887/5670 2910/2957/5740 +f 3062/2956/5739 2862/2820/5603 2863/2978/5761 +f 2902/2887/5670 2908/2886/5669 2909/2958/5741 +f 2909/2958/5741 2919/2901/5684 2910/2957/5740 +f 2867/2952/5735 3043/2846/5629 2866/2915/5698 +f 2789/3050/5833 3072/2932/5715 3069/2934/5717 +f 3065/3051/5834 3072/2932/5715 2789/3050/5833 +f 2994/2764/5547 2859/2816/5599 2889/2930/5713 +f 3067/2907/5690 2857/2817/5600 2869/3025/5808 +f 2898/2997/5780 2886/2849/5632 2883/2881/5664 +f 2858/2855/5638 2890/2908/5691 2889/2930/5713 +f 2930/2890/5673 2925/3052/5835 2924/2826/5609 +f 2934/2841/5624 2935/3040/5823 2763/3037/5820 +f 2888/2850/5633 2881/2880/5663 2882/2851/5634 +f 2970/2858/5641 2971/3028/5811 2972/2893/5676 +f 2971/3028/5811 2973/2949/5732 2972/2893/5676 +f 2972/2893/5676 2973/2949/5732 2974/2766/5549 +f 2764/3027/5810 2765/3041/5824 2936/2800/5583 +f 3032/2959/5742 2775/3053/5836 3028/2896/5679 +f 2943/3049/5832 2935/3040/5823 2934/2841/5624 +f 2983/3054/5837 2984/3045/5828 3073/3055/5838 +f 2871/2935/5718 2865/3018/5801 2873/2936/5719 +f 2761/2961/5744 2946/2875/5658 2947/2874/5657 +f 2850/3020/5803 2853/3024/5807 2877/2884/5667 +f 2836/2867/5650 2827/2866/5649 2837/2929/5712 +f 2872/2812/5595 2868/3019/5802 2871/2935/5718 +f 2770/3042/5825 3027/2863/5646 2771/3056/5839 +f 2940/2801/5584 3027/2863/5646 2770/3042/5825 +f 2831/2985/5768 2834/3034/5817 2832/3057/5840 +f 3026/2834/5617 2893/2931/5714 2844/2796/5579 +f 2765/3041/5824 2935/3040/5823 2936/2800/5583 +f 2838/2806/5589 2841/2750/5533 2999/2749/5532 +f 3008/2861/5644 2847/2781/5564 3009/2814/5597 +f 2800/2882/5665 2967/2988/5771 2801/3058/5841 +f 2857/2817/5600 2994/2764/5547 2993/2763/5546 +f 2906/2835/5618 2914/2818/5601 2905/2992/5775 +f 2866/2915/5698 2865/3018/5801 2867/2952/5735 +f 3072/2932/5715 2855/2790/5573 2857/2817/5600 +f 3005/2752/5535 2822/3009/5792 2821/2758/5541 +f 2978/2859/5642 2969/2976/5759 2976/2996/5779 +f 3036/2960/5743 2885/2939/5722 3045/2869/5652 +f 3004/3002/5785 3025/2757/5540 3002/2970/5753 +f 2989/2797/5580 2899/3059/5842 2903/2845/5628 +f 2841/2750/5533 2843/2805/5588 2895/2775/5558 +f 2787/2963/5746 3060/2943/5726 3065/3051/5834 +f 2746/3046/5829 2953/2912/5695 2954/2913/5696 +f 2945/2746/5529 3003/2748/5531 3002/2970/5753 +f 2919/2901/5684 2918/2827/5610 2924/2826/5609 +f 2928/2776/5559 2912/2879/5662 2929/3060/5843 +f 2988/2768/5551 2972/2893/5676 2974/2766/5549 +f 2753/2808/5591 2759/2809/5592 2757/3015/5798 +f 2868/3019/5802 2870/2811/5594 2832/3057/5840 +f 3016/3021/5804 3015/2945/5728 3017/2953/5736 +f 3072/2932/5715 2857/2817/5600 3070/2906/5689 +f 2952/2747/5530 2997/2998/5781 3003/2748/5531 +f 3004/3002/5785 2877/2884/5667 3025/2757/5540 +f 3052/2744/5527 2976/2996/5779 3054/2745/5528 +f 3063/2911/5694 2864/2919/5702 3064/2942/5725 +f 2964/2852/5635 2799/3061/5844 3076/3008/5791 +f 2836/2867/5650 2835/2836/5619 2900/2865/5648 +f 2925/3052/5835 2926/2774/5557 2919/2901/5684 +f 2867/2952/5735 2837/2929/5712 3040/2793/5576 +f 2911/2900/5683 2887/2862/5645 2886/2849/5632 +f 2866/2915/5698 3053/2914/5697 2873/2936/5719 +f 2990/2798/5581 2846/2821/5604 2845/2753/5536 +f 2917/2825/5608 2923/2824/5607 2929/3060/5843 +f 3022/2756/5539 3021/2917/5700 3024/2832/5615 +f 2829/2784/5567 2830/2786/5569 2870/2811/5594 +f 2899/3059/5842 2905/2992/5775 2904/3023/5806 +f 3057/2795/5578 3054/2745/5528 2975/2898/5681 +f 2879/3035/5818 3020/3029/5812 3023/2916/5699 +f 3020/3029/5812 2875/2947/5730 3016/3021/5804 +f 3044/2778/5561 2780/2870/5653 3045/2869/5652 +f 2884/3062/5845 2897/2951/5734 2898/2997/5780 +f 2931/2889/5672 2913/2891/5674 2914/2818/5601 +f 2885/2939/5722 2883/2881/5664 2860/2938/5721 +f 2910/2957/5740 2886/2849/5632 2898/2997/5780 +f 3043/2846/5629 3042/2972/5755 3039/2767/5550 +f 2958/2965/5748 2956/2979/5762 2957/3016/5799 +f 2870/2811/5594 3067/2907/5690 2869/3025/5808 +f 2963/3000/5783 2798/2999/5782 2964/2852/5635 +f 3049/2848/5631 3051/2918/5701 3053/2914/5697 +f 3027/2863/5646 2772/3005/5788 2771/3056/5839 +f 2930/2890/5673 2912/2879/5662 2913/2891/5674 +f 2929/3060/5843 2923/2824/5607 2928/2776/5559 +f 2969/2976/5759 2977/2927/5710 2804/2926/5709 +f 3027/2863/5646 3014/2984/5767 3028/2896/5679 +f 3058/2810/5593 3057/2795/5578 3047/2823/5606 +f 2924/2826/5609 2917/2825/5608 2929/3060/5843 +f 3062/2956/5739 2784/2770/5553 3061/2769/5552 +f 2746/3046/5829 2954/2913/5696 2747/2969/5752 +f 3031/2923/5706 2815/3063/5846 3034/2838/5621 +f 2787/2963/5746 3065/3051/5834 2789/3050/5833 +f 2964/2852/5635 3076/3008/5791 2963/3000/5783 +f 2986/3011/5794 2984/3045/5828 2983/3054/5837 +f 2790/3064/5847 3068/2933/5716 2968/2854/5637 +f 2969/2976/5759 2979/2899/5682 2975/2898/5681 +f 3050/3047/5830 2971/3028/5811 3051/2918/5701 +f 2862/2820/5603 2881/2880/5663 2863/2978/5761 +f 3001/2982/5765 2996/2803/5586 2743/3065/5848 +f 2835/2836/5619 2834/3034/5817 2833/2986/5769 +f 3024/2832/5615 2941/2842/5625 2944/3036/5819 +f 2832/3057/5840 2830/2786/5569 2831/2985/5768 +f 2887/2862/5645 2858/2855/5638 2854/2788/5571 +f 2777/3066/5849 3036/2960/5743 2778/3039/5822 +f 2859/2816/5599 2855/2790/5573 2856/2789/5572 +f 2878/2755/5538 2852/2946/5729 2879/3035/5818 +f 2952/2747/5530 2754/2980/5763 2755/3048/5831 +f 3035/2872/5655 2892/2937/5720 3033/2922/5705 +f 3003/2748/5531 2998/2751/5534 3004/3002/5785 +f 2883/2881/5664 2881/2880/5663 2861/2779/5562 +f 2988/2768/5551 2808/2830/5613 2972/2893/5676 +f 2852/2946/5729 2853/3024/5807 2849/2925/5708 +f 3037/2871/5654 2987/2828/5611 3041/2792/5575 +f 3026/2834/5617 2819/2833/5616 2818/2904/5687 +f 2958/2965/5748 2936/2800/5583 2956/2979/5762 +f 2930/2890/5673 2931/2889/5672 2925/3052/5835 +f 2943/3049/5832 2942/2843/5626 3019/2991/5774 +f 2868/3019/5802 2832/3057/5840 2865/3018/5801 +f 3060/2943/5726 2864/2919/5702 2854/2788/5571 +f 2855/2790/5573 3065/3051/5834 2854/2788/5571 +f 2979/2899/5682 2969/2976/5759 2981/2973/5756 +f 2864/2919/5702 2888/2850/5633 2887/2862/5645 +f 2905/2992/5775 2899/3059/5842 2900/2865/5648 +f 2849/2925/5708 2850/3020/5803 2916/2819/5602 +f 3032/2959/5742 3028/2896/5679 2848/2895/5678 +f 3022/2756/5539 2878/2755/5538 2879/3035/5818 +f 3068/2933/5716 2791/3067/5850 2792/3068/5851 +f 2938/2954/5737 2937/2990/5773 3018/2955/5738 +f 2994/2764/5547 2889/2930/5713 2921/2765/5548 +f 3004/3002/5785 2841/2750/5533 2876/2928/5711 +f 2907/2968/5751 2916/2819/5602 2915/2989/5772 +f 3026/2834/5617 2844/2796/5579 3011/2759/5542 +f 2839/2807/5590 2991/2844/5627 2842/3044/5827 +f 2901/2888/5671 2851/2924/5707 2907/2968/5751 +f 2824/3003/5786 3007/3004/5787 2825/2860/5643 +f 2947/2874/5657 3012/2873/5656 3024/2832/5615 +f 2832/3057/5840 2834/3034/5817 2865/3018/5801 +f 2899/3059/5842 2989/2797/5580 2894/2950/5733 +f 2906/2835/5618 2891/2837/5620 2933/2785/5568 +f 2840/2782/5565 2839/2807/5590 2838/2806/5589 +f 2901/2888/5671 2852/2946/5729 2851/2924/5707 +f 3048/2847/5630 2973/2949/5732 3050/3047/5830 +f 3029/2903/5686 3030/2981/5764 3033/2922/5705 +f 2981/2973/5756 3047/2823/5606 3057/2795/5578 +f 2747/2969/5752 2955/2877/5660 2748/2876/5659 +f 2997/2998/5781 2998/2751/5534 3003/2748/5531 +f 2955/2877/5660 2997/2998/5781 2948/2762/5545 +f 3055/2794/5577 3056/2743/5526 3054/2745/5528 +f 2867/2952/5735 2834/3034/5817 2836/2867/5650 +f 2931/2889/5672 2926/2774/5557 2925/3052/5835 +f 2980/2831/5614 2966/2971/5754 3059/2822/5605 +f 2916/2819/5602 2917/2825/5608 2915/2989/5772 +f 2995/2804/5587 3001/2982/5765 3010/2783/5566 +f 2863/2978/5761 2881/2880/5663 2864/2919/5702 +f 2919/2901/5684 2924/2826/5609 2925/3052/5835 +f 2921/2765/5548 2911/2900/5683 2920/2787/5570 +f 2901/2888/5671 2907/2968/5751 2908/2886/5669 +f 2848/2895/5678 2897/2951/5734 2885/2939/5722 +f 3042/2972/5755 3040/2793/5576 3041/2792/5575 +f 2995/2804/5587 2996/2803/5586 3001/2982/5765 +f 2843/2805/5588 2992/2878/5661 2928/2776/5559 +f 2801/3058/5841 2967/2988/5771 2966/2971/5754 +f 2877/2884/5667 3004/3002/5785 2876/2928/5711 +f 2920/2787/5570 2926/2774/5557 2927/2773/5556 +f 2822/3009/5792 3005/2752/5535 3006/2754/5537 +f 2885/2939/5722 2897/2951/5734 2884/3062/5845 +f 2885/2939/5722 3032/2959/5742 2848/2895/5678 +f 2879/3035/5818 2852/2946/5729 2880/3007/5790 +f 3030/2981/5764 2816/3069/5852 3031/2923/5706 +f 2842/3044/5827 2991/2844/5627 2992/2878/5661 +f 2757/3015/5798 2949/3014/5797 2951/3030/5813 +f 3041/2792/5575 3038/2791/5574 3037/2871/5654 +f 3065/3051/5834 2855/2790/5573 3072/2932/5715 +f 2872/2812/5595 2871/2935/5718 3058/2810/5593 +f 2885/2939/5722 2884/3062/5845 2883/2881/5664 +f 2808/2830/5613 2811/2829/5612 2807/3013/5796 +f 2911/2900/5683 2910/2957/5740 2919/2901/5684 +f 3020/3029/5812 2880/3007/5790 2875/2947/5730 +f 2854/2788/5571 3065/3051/5834 3060/2943/5726 +f 2918/2827/5610 2908/2886/5669 2917/2825/5608 +f 2949/3014/5797 3074/3070/5853 2950/3031/5814 +f 2933/2785/5568 2828/2983/5766 2927/2773/5556 +f 3046/2780/5563 2783/2941/5724 2781/2975/5758 +f 2835/2836/5619 2906/2835/5618 2900/2865/5648 +f 2898/2997/5780 2883/2881/5664 2884/3062/5845 +f 3009/2814/5597 2820/2813/5596 3008/2861/5644 +f 2968/2854/5637 2793/2921/5704 2790/3064/5847 +f 3038/2791/5574 2837/2929/5712 2827/2866/5649 +f 2874/2897/5680 2896/2948/5731 2848/2895/5678 +f 2971/3028/5811 3050/3047/5830 2973/2949/5732 +f 2978/2859/5642 2976/2996/5779 3052/2744/5527 +f 2801/3058/5841 2980/2831/5614 2802/2977/5760 +f 2869/3025/5808 2828/2983/5766 2829/2784/5567 +f 2761/2961/5744 2934/2841/5624 2762/3038/5821 +f 2745/3043/5826 2743/3065/5848 2996/2803/5586 +f 2795/2853/5636 2964/2852/5635 2798/2999/5782 +f 2870/2811/5594 2868/3019/5802 2872/2812/5595 +f 2890/2908/5691 2887/2862/5645 2911/2900/5683 +f 2877/2884/5667 2852/2946/5729 2878/2755/5538 +f 2986/3011/5794 2807/3013/5796 2811/2829/5612 +f 2828/2983/5766 2857/2817/5600 2993/2763/5546 +f 2903/2845/5628 2899/3059/5842 2904/3023/5806 +f 2809/2966/5749 2982/2840/5623 2812/2885/5668 +f 2775/3053/5836 3032/2959/5742 2777/3066/5849 +f 3045/2869/5652 2860/2938/5721 3044/2778/5561 +f 2944/3036/5819 2934/2841/5624 2947/2874/5657 +f 2900/2865/5648 2906/2835/5618 2905/2992/5775 +f 2894/2950/5733 2844/2796/5579 2893/2931/5714 +f 2934/2841/5624 2944/3036/5819 2941/2842/5625 +f 2946/2875/5658 2945/2746/5529 3002/2970/5753 +f 2748/2876/5659 2948/2762/5545 2749/2974/5757 +f 3035/2872/5655 3037/2871/5654 3038/2791/5574 +f 2978/2859/5642 2977/2927/5710 2969/2976/5759 +f 2909/2958/5741 2908/2886/5669 2918/2827/5610 +f 3055/2794/5577 2873/2936/5719 3056/2743/5526 +f 2847/2781/5564 2990/2798/5581 2840/2782/5565 +f 2908/2886/5669 2915/2989/5772 2917/2825/5608 +f 2972/2893/5676 2808/2830/5613 2805/2894/5677 +f 3024/2832/5615 3021/2917/5700 2941/2842/5625 +f 2982/2840/5623 2811/2829/5612 2987/2828/5611 +f 2840/2782/5565 2991/2844/5627 2839/2807/5590 +f 2943/3049/5832 2934/2841/5624 2942/2843/5626 +f 2961/2883/5666 2967/2988/5771 2800/2882/5665 +f 3058/2810/5593 3055/2794/5577 3057/2795/5578 +f 2814/3071/5854 3031/2923/5706 2816/3069/5852 +f 2791/3067/5850 3068/2933/5716 2790/3064/5847 +f 2867/2952/5735 2865/3018/5801 2834/3034/5817 +f 2886/2849/5632 2910/2957/5740 2911/2900/5683 +f 2992/2878/5661 2843/2805/5588 2842/3044/5827 +f 2913/2891/5674 2912/2879/5662 2904/3023/5806 +f 2857/2817/5600 2859/2816/5599 2994/2764/5547 +f 2876/2928/5711 2916/2819/5602 2850/3020/5803 +f 2827/2866/5649 3035/2872/5655 3038/2791/5574 +f 3061/2769/5552 2783/2941/5724 3046/2780/5563 +f 2831/2985/5768 2833/2986/5769 2834/3034/5817 +f 3060/2943/5726 2788/2962/5745 3064/2942/5725 +f 2990/2798/5581 2991/2844/5627 2840/2782/5565 +f 2927/2773/5556 2932/2772/5555 2933/2785/5568 +f 3030/2981/5764 2817/2902/5685 2816/3069/5852 +f 2826/2815/5598 3001/2982/5765 2743/3065/5848 +f 2829/2784/5567 2828/2983/5766 2933/2785/5568 +f 3062/2956/5739 3061/2769/5552 2862/2820/5603 +f 2760/2987/5770 2759/2809/5592 2952/2747/5530 +f 3007/3004/5787 3008/2861/5644 2825/2860/5643 +f 3064/2942/5725 2788/2962/5745 2785/2909/5692 +f 2824/3003/5786 2823/3010/5793 3006/2754/5537 +f 2936/2800/5583 2935/3040/5823 2937/2990/5773 +f 3033/2922/5705 3034/2838/5621 3035/2872/5655 +f 2802/2977/5760 2969/2976/5759 2803/3033/5816 +f 3009/2814/5597 2847/2781/5564 3010/2783/5566 +f 3029/2903/5686 2817/2902/5685 3030/2981/5764 +f 3027/2863/5646 3028/2896/5679 2773/3006/5789 +f 2864/2919/5702 3063/2911/5694 2863/2978/5761 +f 2802/2977/5760 2980/2831/5614 2981/2973/5756 +f 3054/2745/5528 2976/2996/5779 2975/2898/5681 +f 3019/2991/5774 2937/2990/5773 2943/3049/5832 +f 2792/3068/5851 3069/2934/5717 3068/2933/5716 +f 3016/3021/5804 3018/2955/5738 3020/3029/5812 +f 3028/2896/5679 2775/3053/5836 2776/3072/5855 +f 2980/2831/5614 2801/3058/5841 2966/2971/5754 +f 2815/3063/5846 3031/2923/5706 2814/3071/5854 +f 2988/2768/5551 3039/2767/5550 3042/2972/5755 +f 2923/2824/5607 2917/2825/5608 2922/2777/5560 +f 2998/2751/5534 3000/2802/5585 2999/2749/5532 +f 2780/2870/5653 3044/2778/5561 2781/2975/5758 +f 2830/2786/5569 2832/3057/5840 2870/2811/5594 +f 2903/2845/5628 2990/2798/5581 2989/2797/5580 +f 3049/2848/5631 3048/2847/5630 3050/3047/5830 +f 3014/2984/5767 2874/2897/5680 3028/2896/5679 +f 3032/2959/5742 3036/2960/5743 2777/3066/5849 +f 2813/2839/5622 3034/2838/5621 2815/3063/5846 +f 3056/2743/5526 3053/2914/5697 3052/2744/5527 +f 2948/2762/5545 2755/3048/5831 2752/2760/5543 +f 2774/3073/5856 3028/2896/5679 2776/3072/5855 +f 2850/3020/5803 2849/2925/5708 2853/3024/5807 +f 2924/2826/5609 2929/3060/5843 2930/2890/5673 +f 2999/2749/5532 2996/2803/5586 2995/2804/5587 +f 3020/3029/5812 3018/2955/5738 3019/2991/5774 +f 2792/3068/5851 2789/3050/5833 3069/2934/5717 +f 3067/2907/5690 3070/2906/5689 2857/2817/5600 +f 2984/3045/5828 2810/3074/5857 3073/3055/5838 +f 3073/3055/5838 2986/3011/5794 2983/3054/5837 +f 2857/2817/5600 2828/2983/5766 2869/3025/5808 +f 3075/3032/5815 2756/3075/5858 2951/3030/5813 +f 2950/3031/5814 3074/3070/5853 3075/3032/5815 +f 2912/2879/5662 2930/2890/5673 2929/3060/5843 +f 2758/3076/5859 3074/3070/5853 2949/3014/5797 +f 2894/2950/5733 2900/2865/5648 2899/3059/5842 +f 2892/2937/5720 2894/2950/5733 2893/2931/5714 +f 2773/3006/5789 3028/2896/5679 2774/3073/5856 +f 3077/2994/5777 2797/3077/5860 2965/2995/5778 +f 2962/2993/5776 3076/3008/5791 3077/2994/5777 +f 2960/3078/5861 2956/2979/5862 3078/2856/5863 +f 2956/2979/5762 3078/2856/5864 3079/3017/5800 +f 2988/2768/5551 3041/2792/5575 2987/2828/5611 +f 2873/2936/5719 3053/2914/5697 3056/2743/5526 +f 3078/2856/5864 2767/3079/5865 3079/3017/5800 +f 3079/3017/5800 2958/2965/5748 2957/3016/5799 +f 2485/2663/5445 2824/3003/5786 2825/2860/5643 2486/2520/5302 +f 2742/2677/5459 3079/3017/5800 2767/3079/5865 2427/2742/5525 +f 2740/2655/5437 3077/2994/5777 3076/3008/5791 2739/2668/5450 +f 2415/2708/5490 2755/3048/5831 2754/2980/5763 2414/2640/5422 +f 2434/2733/5515 2774/3073/5856 2776/3072/5855 2436/2732/5514 +f 2626/2654/5436 2965/2995/5778 2797/3077/5860 2457/2740/5520 +f 2427/2742/5525 2767/3079/5865 3078/2856/5864 2741/2516/5524 +f 2469/2489/5271 2808/2830/5613 2807/3013/5796 2468/2672/5454 +f 2407/2629/5411 2747/2969/5752 2748/2876/5659 2408/2536/5318 +f 2464/2693/5475 2803/3033/5816 2804/2926/5709 2465/2586/5368 +f 2455/2514/5296 2795/2853/5636 2798/2999/5782 2459/2659/5441 +f 2451/2728/5510 2791/3067/5850 2790/3064/5847 2450/2724/5506 +f 2436/2732/5514 2776/3072/5855 2775/3053/5836 2435/2713/5495 +f 2741/2516/5522 2621/2741/5521 2960/3078/5861 3078/2856/5863 +f 2470/2626/5408 2809/2966/5749 2812/2885/5668 2473/2545/5327 +f 2418/2736/5518 2758/3076/5859 2949/3014/5797 2610/2674/5456 +f 2472/2490/5272 2811/2829/5612 2809/2966/5749 2470/2626/5408 +f 2439/2528/5310 2779/2868/5651 2780/2870/5653 2440/2529/5311 +f 2431/2716/5498 2771/3056/5839 2772/3005/5788 2432/2665/5447 +f 2441/2635/5417 2781/2975/5758 2783/2941/5724 2443/2601/5383 +f 2421/2621/5403 2761/2961/5744 2762/3038/5821 2422/2698/5480 +f 2403/2725/5507 2743/3065/5848 2745/3043/5826 2405/2703/5485 +f 2416/2735/5517 2756/3075/5858 3075/3032/5815 2738/2691/5473 +f 2429/2459/5241 2769/2799/5582 2770/3042/5825 2430/2702/5484 +f 2459/2659/5441 2798/2999/5782 2965/2995/5778 2626/2654/5436 +f 2406/2706/5488 2746/3046/5829 2747/2969/5752 2407/2629/5411 +f 2409/2634/5416 2749/2974/5757 2750/2967/5750 2410/2627/5409 +f 2625/2512/5294 2964/2852/5635 2800/2882/5665 2461/2542/5324 +f 2467/2552/5334 2806/2892/5675 2805/2894/5677 2466/2553/5335 +f 2739/2668/5450 3076/3008/5791 2799/3061/5844 2460/2721/5503 +f 2612/2690/5472 2951/3030/5813 2756/3075/5858 2416/2735/5517 +f 2466/2553/5335 2805/2894/5677 2808/2830/5613 2469/2489/5271 +f 2619/2625/5407 2958/2965/5748 3079/3017/5800 2742/2677/5459 +f 2476/2723/5505 2815/3063/5846 2814/3071/5854 2475/2731/5513 +f 2741/2516/5298 3078/2856/5639 2768/2857/5640 2428/2517/5299 +f 2474/2500/5282 2813/2839/5622 2815/3063/5846 2476/2723/5505 +f 2738/2691/5473 3075/3032/5815 3074/3070/5853 2737/2730/5512 +f 2450/2724/5506 2790/3064/5847 2793/2921/5704 2453/2580/5362 +f 2477/2729/5511 2816/3069/5852 2817/2902/5685 2478/2562/5344 +f 2424/2686/5468 2764/3027/5810 2766/3026/5809 2426/2687/5469 +f 2483/2669/5451 2822/3009/5792 2823/3010/5793 2484/2670/5452 +f 2438/2699/5481 2778/3039/5822 2779/2868/5651 2439/2528/5310 +f 2426/2687/5469 2766/3026/5809 2959/2964/5747 2620/2624/5406 +f 2443/2601/5383 2783/2941/5724 2782/2771/5554 2442/2430/5212 +f 2620/2624/5406 2959/2964/5747 2958/2965/5748 2619/2625/5407 +f 2435/2713/5495 2775/3053/5836 2777/3066/5849 2437/2726/5508 +f 2465/2586/5368 2804/2926/5709 2806/2892/5675 2467/2552/5334 +f 2461/2542/5324 2800/2882/5665 2801/3058/5841 2462/2718/5500 +f 2460/2721/5503 2799/3061/5844 2964/2852/5635 2625/2512/5294 +f 2475/2731/5513 2814/3071/5854 2816/3069/5852 2477/2729/5511 +f 2417/2675/5457 2757/3015/5798 2951/3030/5813 2612/2690/5472 +f 2437/2726/5508 2777/3066/5849 2778/3039/5822 2438/2699/5481 +f 2420/2647/5429 2760/2987/5770 2761/2961/5744 2421/2621/5403 +f 2448/2622/5404 2788/2962/5745 2787/2963/5746 2447/2623/5405 +f 2411/2422/5204 2751/2761/5544 2752/2760/5543 2412/2420/5202 +f 2456/2682/5464 2796/3022/5805 2795/2853/5636 2455/2514/5296 +f 2457/2740/5520 2797/3077/5860 3077/2994/5777 2740/2655/5437 +f 2610/2674/5456 2949/3014/5797 2759/2809/5592 2419/2469/5251 +f 2484/2670/5452 2823/3010/5793 2824/3003/5786 2485/2663/5445 +f 2478/2562/5344 2817/2902/5685 2818/2904/5687 2479/2563/5345 +f 2487/2474/5256 2826/2815/5598 2743/3065/5848 2403/2725/5507 +f 2482/2418/5200 2821/2758/5541 2822/3009/5792 2483/2669/5451 +f 2480/2494/5276 2819/2833/5616 2821/2758/5541 2482/2418/5200 +f 2468/2672/5454 2807/3013/5796 2985/3012/5795 2646/2673/5455 +f 2447/2623/5405 2787/2963/5746 2789/3050/5833 2449/2710/5492 +f 2647/2671/5453 2986/3011/5794 3073/3055/5838 2736/2715/5497 +f 2423/2697/5479 2763/3037/5820 2765/3041/5824 2425/2701/5483 +f 2432/2665/5447 2772/3005/5788 2773/3006/5789 2433/2666/5448 +f 2404/2661/5443 2744/3001/5784 2746/3046/5829 2406/2706/5488 +f 2471/2734/5516 2810/3074/5857 2984/3045/5828 2645/2705/5487 +f 2444/2431/5213 2784/2770/5553 2786/2910/5693 2446/2571/5353 +f 2440/2529/5311 2780/2870/5653 2781/2975/5758 2441/2635/5417 +f 2413/2468/5250 2753/2808/5591 2757/3015/5798 2417/2675/5457 +f 2646/2673/5455 2985/3012/5795 2986/3011/5794 2647/2671/5453 +f 2449/2710/5492 2789/3050/5833 2792/3068/5851 2452/2727/5509 +f 2414/2640/5422 2754/2980/5763 2753/2808/5591 2413/2468/5250 +f 2408/2536/5318 2748/2876/5659 2749/2974/5757 2409/2634/5416 +f 2621/2741/5521 2617/2639/5523 2956/2979/5862 2960/3078/5861 +f 2445/2569/5351 2785/2909/5692 2788/2962/5745 2448/2622/5404 +f 2479/2563/5345 2818/2904/5687 2819/2833/5616 2480/2494/5276 +f 2422/2698/5480 2762/3038/5821 2763/3037/5820 2423/2697/5479 +f 2433/2666/5448 2773/3006/5789 2774/3073/5856 2434/2733/5515 +f 2473/2545/5327 2812/2885/5668 2813/2839/5622 2474/2500/5282 +f 2453/2580/5362 2793/2921/5704 2794/2920/5703 2454/2581/5363 +f 2486/2520/5302 2825/2860/5643 2820/2813/5596 2481/2473/5255 +f 2425/2701/5483 2765/3041/5824 2764/3027/5810 2424/2686/5468 +f 2454/2581/5363 2794/2920/5703 2796/3022/5805 2456/2682/5464 +f 2410/2627/5409 2750/2967/5750 2751/2761/5544 2411/2422/5204 +f 2463/2636/5418 2802/2977/5760 2803/3033/5816 2464/2693/5475 +f 2419/2469/5251 2759/2809/5592 2760/2987/5770 2420/2647/5429 +f 2645/2705/5487 2984/3045/5828 2811/2829/5612 2472/2490/5272 +f 2737/2730/5512 3074/3070/5853 2758/3076/5859 2418/2736/5518 +f 2430/2702/5484 2770/3042/5825 2771/3056/5839 2431/2716/5498 +f 2452/2727/5509 2792/3068/5851 2791/3067/5850 2451/2728/5510 +f 2405/2703/5485 2745/3043/5826 2744/3001/5784 2404/2661/5443 +f 2428/2517/5299 2768/2857/5640 2769/2799/5582 2429/2459/5241 +f 2446/2571/5353 2786/2910/5693 2785/2909/5692 2445/2569/5351 +f 2736/2715/5497 3073/3055/5838 2810/3074/5857 2471/2734/5516 +f 2412/2420/5202 2752/2760/5543 2755/3048/5831 2415/2708/5490 +f 2442/2430/5212 2782/2771/5554 2784/2770/5553 2444/2431/5213 +f 2481/2473/5255 2820/2813/5596 2826/2815/5598 2487/2474/5256 +f 2462/2718/5500 2801/3058/5841 2802/2977/5760 2463/2636/5418 diff --git a/examples/Cassie/urdf/meshes/agility/hip-roll.obj b/examples/Cassie/urdf/meshes/agility/hip-roll.obj new file mode 100644 index 0000000000..bc12f3761e --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/hip-roll.obj @@ -0,0 +1,9385 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o hip-roll +v -0.054937 -0.105193 0.030586 +v -0.054830 -0.106841 0.033716 +v -0.054900 -0.104405 0.034586 +v -0.054849 -0.103392 0.036990 +v -0.054900 -0.101478 0.033572 +v -0.054825 -0.099811 0.034305 +v -0.054848 -0.101219 0.030060 +v -0.020979 -0.105103 0.032460 +v -0.021035 -0.102271 0.034909 +v -0.021029 -0.104448 0.034682 +v -0.021011 -0.102451 0.031443 +v -0.050811 -0.105058 0.031831 +v -0.050824 -0.104591 0.034994 +v -0.050801 -0.101259 0.034494 +v -0.021367 -0.101063 0.033002 +v -0.050828 -0.102053 0.031394 +v -0.050961 -0.104414 0.036613 +v -0.050957 -0.106847 0.033600 +v -0.050965 -0.105511 0.030581 +v -0.050957 -0.102342 0.029714 +v -0.050957 -0.099621 0.032868 +v -0.050963 -0.101171 0.036103 +v -0.051900 -0.104010 0.034845 +v -0.051900 -0.101451 0.033100 +v -0.051900 -0.104242 0.031756 +v -0.054946 -0.100509 -0.034940 +v -0.054837 -0.103402 -0.036927 +v -0.054938 -0.106254 -0.034548 +v -0.054837 -0.105956 -0.030732 +v -0.054935 -0.102414 -0.030031 +v -0.054825 -0.099811 -0.032163 +v -0.021054 -0.101145 -0.032945 +v -0.021087 -0.103308 -0.031290 +v -0.021008 -0.105273 -0.033033 +v -0.020985 -0.102985 -0.035198 +v -0.050830 -0.103690 -0.035340 +v -0.050801 -0.105557 -0.032930 +v -0.050824 -0.102758 -0.031064 +v -0.050801 -0.101000 -0.033937 +v -0.050957 -0.106755 -0.034126 +v -0.050963 -0.104191 -0.036636 +v -0.050957 -0.100701 -0.035837 +v -0.050951 -0.100013 -0.031433 +v -0.050942 -0.104773 -0.029809 +v -0.051900 -0.104310 -0.034632 +v -0.051900 -0.102158 -0.031836 +v -0.059700 -0.070852 -0.059778 +v -0.059619 -0.068050 -0.058881 +v -0.059698 -0.067471 -0.061819 +v -0.059671 -0.071851 -0.058734 +v -0.059633 -0.069868 -0.063879 +v -0.059697 -0.072344 -0.062299 +v -0.044806 -0.070921 -0.059838 +v -0.044816 -0.070979 -0.062021 +v -0.044779 -0.068632 -0.060523 +v -0.056605 -0.068597 -0.059898 +v -0.045175 -0.069234 -0.062447 +v -0.056626 -0.069231 -0.062534 +v -0.056634 -0.071217 -0.062091 +v -0.056623 -0.071385 -0.059949 +v -0.056756 -0.072216 -0.059227 +v -0.056759 -0.072529 -0.062210 +v -0.056731 -0.067222 -0.060235 +v -0.056761 -0.069575 -0.058260 +v -0.056764 -0.069217 -0.063897 +v -0.057700 -0.069497 -0.062403 +v -0.057700 -0.070295 -0.059925 +v -0.049700 -0.038615 0.034665 +v -0.050900 -0.039591 0.033437 +v -0.050900 -0.034724 0.036236 +v -0.049700 -0.035210 0.035121 +v -0.050900 -0.034606 0.034459 +v -0.049700 -0.034775 0.032043 +v -0.050900 -0.036228 0.030771 +v -0.049700 -0.037691 0.030969 +v -0.050580 -0.039037 0.032933 +v -0.050300 -0.040278 0.033232 +v -0.050900 -0.039683 0.031045 +v -0.049700 -0.038622 0.029733 +v -0.050900 -0.035872 0.029595 +v -0.049700 -0.033449 0.031490 +v -0.050900 -0.033167 0.032647 +v -0.049700 -0.034503 0.036321 +v -0.050900 -0.039004 0.036152 +v -0.049700 -0.039789 0.035412 +v -0.049700 -0.104119 0.031119 +v -0.050900 -0.105073 0.031695 +v -0.049700 -0.105552 0.034125 +v -0.050900 -0.104746 0.034993 +v -0.049700 -0.101375 0.035052 +v -0.050900 -0.101222 0.034817 +v -0.049700 -0.102255 0.031115 +v -0.050900 -0.102151 0.031185 +v -0.049700 -0.101961 0.029817 +v -0.050900 -0.103064 0.029613 +v -0.050900 -0.100071 0.031419 +v -0.049700 -0.099523 0.033309 +v -0.050900 -0.100333 0.035667 +v -0.049700 -0.101703 0.036544 +v -0.050900 -0.105941 0.036128 +v -0.049700 -0.105240 0.036280 +v -0.049700 -0.106866 0.031770 +v -0.050900 -0.106152 0.030996 +v -0.050300 -0.103556 0.029715 +v -0.054900 -0.035010 -0.032896 +v -0.054830 -0.034078 -0.030781 +v -0.054849 -0.033787 -0.035527 +v -0.054944 -0.037847 -0.036327 +v -0.054900 -0.037937 -0.031882 +v -0.054825 -0.037837 -0.029811 +v -0.054848 -0.040523 -0.033392 +v -0.021066 -0.037849 -0.034986 +v -0.021131 -0.034932 -0.034135 +v -0.020969 -0.035514 -0.031847 +v -0.021096 -0.038217 -0.031711 +v -0.050801 -0.034426 -0.033130 +v -0.050824 -0.036858 -0.035454 +v -0.050827 -0.038855 -0.033809 +v -0.050806 -0.037623 -0.031063 +v -0.050961 -0.037434 -0.036751 +v -0.050929 -0.033193 -0.034592 +v -0.050957 -0.035187 -0.029964 +v -0.050951 -0.039560 -0.030823 +v -0.050963 -0.039987 -0.034688 +v -0.051900 -0.037773 -0.034712 +v -0.051900 -0.037542 -0.031623 +v -0.051900 -0.034983 -0.033368 +v -0.049700 -0.035691 -0.031197 +v -0.050900 -0.036444 -0.030249 +v -0.050900 -0.034514 -0.032373 +v -0.049700 -0.034630 -0.034574 +v -0.050900 -0.035284 -0.034957 +v -0.050900 -0.038558 -0.035063 +v -0.049700 -0.038515 -0.034944 +v -0.049700 -0.038125 -0.031308 +v -0.050900 -0.038030 -0.031268 +v -0.049700 -0.037793 -0.029749 +v -0.050900 -0.037458 -0.029623 +v -0.050900 -0.040257 -0.032280 +v -0.049700 -0.040465 -0.032933 +v -0.050900 -0.039353 -0.035895 +v -0.049700 -0.038767 -0.036249 +v -0.050900 -0.034790 -0.036464 +v -0.049700 -0.034501 -0.036319 +v -0.050900 -0.033279 -0.031759 +v -0.049700 -0.033289 -0.032230 +v -0.049700 -0.035971 -0.029654 +v -0.049700 -0.100441 -0.033405 +v -0.050900 -0.101115 -0.034202 +v -0.049700 -0.102894 -0.035503 +v -0.050900 -0.103579 -0.035502 +v -0.049700 -0.105225 -0.034478 +v -0.050900 -0.105625 -0.033544 +v -0.049700 -0.104980 -0.031664 +v -0.050900 -0.103742 -0.030911 +v -0.049700 -0.101540 -0.031536 +v -0.050900 -0.101111 -0.032340 +v -0.049700 -0.099988 -0.031489 +v -0.050900 -0.099623 -0.032542 +v -0.050900 -0.102995 -0.029494 +v -0.049700 -0.104056 -0.029615 +v -0.050900 -0.106975 -0.032426 +v -0.049700 -0.106970 -0.032943 +v -0.050900 -0.104559 -0.036739 +v -0.049700 -0.105068 -0.036354 +v -0.049700 -0.101161 -0.036356 +v -0.050900 -0.100152 -0.035255 +v -0.059675 -0.110136 0.008622 +v -0.059616 -0.108081 0.005763 +v -0.059676 -0.110101 0.003454 +v -0.059682 -0.113652 0.006218 +v -0.059601 -0.112700 0.008177 +v -0.059598 -0.112916 0.003904 +v -0.048784 -0.111392 0.004633 +v -0.048895 -0.109822 0.007000 +v -0.048944 -0.112437 0.006786 +v -0.048876 -0.109846 0.005161 +v -0.056591 -0.109425 0.005254 +v -0.056595 -0.110642 0.007706 +v -0.056607 -0.112654 0.006267 +v -0.056613 -0.111623 0.004471 +v -0.056770 -0.111927 0.008816 +v -0.056753 -0.109839 0.003354 +v -0.056767 -0.108171 0.006887 +v -0.056735 -0.113755 0.004787 +v -0.057700 -0.111556 0.006966 +v -0.057700 -0.110162 0.004768 +v -0.030200 -0.080032 -0.042923 +v -0.030200 -0.086925 -0.043915 +v -0.030200 -0.100164 -0.032641 +v -0.030200 -0.100521 -0.034930 +v -0.028000 -0.100526 -0.034943 +v -0.028000 -0.086658 -0.043911 +v -0.028001 -0.100056 -0.033059 +v -0.028000 -0.079730 -0.042927 +v -0.032200 -0.080032 -0.042923 +v -0.031717 -0.085532 -0.043786 +v -0.031700 -0.093419 -0.040315 +v -0.032200 -0.100164 -0.032641 +v -0.032200 -0.100521 -0.034930 +v -0.031200 -0.100526 -0.034943 +v -0.031200 -0.100090 -0.032984 +v -0.031200 -0.077443 -0.043510 +v -0.034200 -0.080032 -0.042923 +v -0.033717 -0.085532 -0.043786 +v -0.033700 -0.093419 -0.040315 +v -0.034200 -0.100164 -0.032641 +v -0.034200 -0.100521 -0.034930 +v -0.033200 -0.100526 -0.034943 +v -0.033200 -0.100090 -0.032984 +v -0.033200 -0.077443 -0.043510 +v -0.036200 -0.080032 -0.042923 +v -0.035717 -0.085532 -0.043786 +v -0.035700 -0.093419 -0.040315 +v -0.036200 -0.100164 -0.032641 +v -0.036200 -0.100521 -0.034930 +v -0.035200 -0.100526 -0.034943 +v -0.035200 -0.100090 -0.032984 +v -0.035200 -0.077443 -0.043510 +v -0.038200 -0.080032 -0.042923 +v -0.037717 -0.085532 -0.043786 +v -0.037700 -0.093419 -0.040315 +v -0.038200 -0.100164 -0.032641 +v -0.038200 -0.100521 -0.034930 +v -0.037200 -0.100526 -0.034943 +v -0.037200 -0.100090 -0.032984 +v -0.037200 -0.077443 -0.043510 +v -0.040200 -0.080032 -0.042923 +v -0.039717 -0.085532 -0.043786 +v -0.039700 -0.093420 -0.040315 +v -0.040200 -0.100164 -0.032641 +v -0.040200 -0.100521 -0.034930 +v -0.039200 -0.100526 -0.034943 +v -0.039200 -0.100090 -0.032984 +v -0.039200 -0.077443 -0.043510 +v -0.042571 -0.084509 -0.041689 +v -0.042201 -0.078516 -0.043079 +v -0.041717 -0.085532 -0.043786 +v -0.041700 -0.093420 -0.040315 +v -0.042199 -0.100165 -0.032609 +v -0.042200 -0.100521 -0.034930 +v -0.041200 -0.100526 -0.034943 +v -0.041200 -0.100090 -0.032984 +v -0.041200 -0.077443 -0.043510 +v -0.030477 -0.063259 -0.043571 +v -0.030200 -0.073031 -0.046356 +v -0.030200 -0.067053 -0.046431 +v -0.030685 -0.108989 0.021100 +v -0.030200 -0.104931 0.030521 +v -0.030200 -0.101435 0.030488 +v -0.030200 -0.110920 0.022452 +v -0.030200 -0.116474 0.005788 +v -0.030700 -0.113909 0.004860 +v -0.030200 -0.104949 -0.030520 +v -0.030200 -0.113965 -0.016718 +v -0.030644 -0.112660 -0.012063 +v -0.030200 -0.102092 -0.030319 +v -0.028001 -0.062988 -0.043540 +v -0.028000 -0.072884 -0.046425 +v -0.028000 -0.066944 -0.046362 +v -0.027999 -0.110471 -0.018624 +v -0.028000 -0.104931 -0.030521 +v -0.028001 -0.102205 -0.030204 +v -0.027999 -0.108894 0.021251 +v -0.028000 -0.113965 0.016718 +v -0.027998 -0.114224 0.002886 +v -0.028000 -0.101773 0.030440 +v -0.028000 -0.104949 0.030520 +v -0.028000 -0.116474 -0.005788 +v -0.028000 -0.110920 -0.022452 +v -0.032477 -0.063259 -0.043571 +v -0.031717 -0.072969 -0.046405 +v -0.031719 -0.067018 -0.046408 +v -0.032658 -0.111373 0.015723 +v -0.032200 -0.104931 0.030521 +v -0.032200 -0.101505 0.030487 +v -0.032200 -0.110920 0.022452 +v -0.032200 -0.116474 0.005788 +v -0.032700 -0.114265 -0.002442 +v -0.032200 -0.104949 -0.030520 +v -0.032200 -0.113965 -0.016718 +v -0.032700 -0.108989 -0.021100 +v -0.032686 -0.102010 -0.030291 +v -0.031200 -0.113965 0.016718 +v -0.031200 -0.101771 0.030440 +v -0.031200 -0.104949 0.030520 +v -0.031200 -0.116474 -0.005788 +v -0.031200 -0.110920 -0.022452 +v -0.031200 -0.102512 -0.030126 +v -0.031200 -0.104931 -0.030521 +v -0.034477 -0.063259 -0.043571 +v -0.033717 -0.072969 -0.046405 +v -0.033719 -0.067018 -0.046408 +v -0.034685 -0.108989 0.021100 +v -0.034200 -0.104931 0.030521 +v -0.034200 -0.101435 0.030488 +v -0.034200 -0.110920 0.022452 +v -0.034200 -0.116474 0.005788 +v -0.034575 -0.113749 0.005770 +v -0.034200 -0.104949 -0.030520 +v -0.034200 -0.113965 -0.016718 +v -0.034700 -0.108989 -0.021100 +v -0.034825 -0.113749 -0.005770 +v -0.034686 -0.102010 -0.030291 +v -0.033200 -0.104931 -0.030521 +v -0.033200 -0.113965 0.016718 +v -0.033200 -0.102092 0.030319 +v -0.033200 -0.104949 0.030520 +v -0.033200 -0.116474 -0.005788 +v -0.033200 -0.110920 -0.022452 +v -0.036477 -0.063259 -0.043571 +v -0.035717 -0.072969 -0.046405 +v -0.035719 -0.067018 -0.046408 +v -0.036593 -0.110155 0.018832 +v -0.036200 -0.104931 0.030521 +v -0.036200 -0.101435 0.030488 +v -0.035729 -0.111228 0.021896 +v -0.035700 -0.115476 0.010025 +v -0.036700 -0.114132 0.002435 +v -0.035700 -0.116565 -0.005072 +v -0.036200 -0.104949 -0.030520 +v -0.035671 -0.111228 -0.021896 +v -0.036664 -0.111950 -0.014402 +v -0.036200 -0.102092 -0.030319 +v -0.035200 -0.104931 -0.030521 +v -0.035200 -0.101771 0.030440 +v -0.035200 -0.104949 0.030520 +v -0.038200 -0.063356 -0.043616 +v -0.037717 -0.072969 -0.046405 +v -0.037719 -0.067018 -0.046408 +v -0.038200 -0.110920 0.022452 +v -0.038200 -0.104931 0.030521 +v -0.038200 -0.102512 0.030126 +v -0.038200 -0.111972 0.013763 +v -0.038200 -0.116474 0.005788 +v -0.038700 -0.114220 0.002440 +v -0.038200 -0.104949 -0.030520 +v -0.038200 -0.113965 -0.016718 +v -0.038200 -0.111575 -0.014919 +v -0.038200 -0.102092 -0.030319 +v -0.037200 -0.104931 -0.030521 +v -0.037200 -0.102237 -0.030195 +v -0.037200 -0.113965 0.016718 +v -0.037200 -0.102092 0.030319 +v -0.037200 -0.104949 0.030520 +v -0.037200 -0.116474 -0.005788 +v -0.037200 -0.110920 -0.022452 +v -0.039923 -0.063259 -0.043571 +v -0.039717 -0.072969 -0.046405 +v -0.039719 -0.067018 -0.046408 +v -0.040200 -0.109309 0.020483 +v -0.040200 -0.104931 0.030521 +v -0.040200 -0.101435 0.030488 +v -0.040200 -0.110920 0.022452 +v -0.040200 -0.116474 0.005788 +v -0.040200 -0.114291 0.001748 +v -0.040200 -0.104949 -0.030520 +v -0.040200 -0.113965 -0.016718 +v -0.040700 -0.112535 -0.012404 +v -0.040200 -0.102092 -0.030319 +v -0.039200 -0.112346 -0.013756 +v -0.039200 -0.104931 -0.030521 +v -0.039200 -0.102237 -0.030195 +v -0.039200 -0.108648 0.021705 +v -0.039200 -0.113965 0.016718 +v -0.039200 -0.101771 0.030440 +v -0.039200 -0.104949 0.030520 +v -0.039200 -0.116474 -0.005788 +v -0.039200 -0.110920 -0.022452 +v -0.042200 -0.063861 -0.043800 +v -0.041717 -0.072969 -0.046405 +v -0.041719 -0.067018 -0.046408 +v -0.042200 -0.107895 0.022656 +v -0.042200 -0.104931 0.030521 +v -0.042200 -0.101440 0.030504 +v -0.042200 -0.110920 0.022452 +v -0.042200 -0.113830 0.006610 +v -0.042200 -0.116474 0.005788 +v -0.042200 -0.104949 -0.030520 +v -0.042200 -0.113965 -0.016718 +v -0.042575 -0.112732 -0.011707 +v -0.042200 -0.102247 -0.030259 +v -0.041200 -0.063091 -0.043491 +v -0.041200 -0.102092 0.030319 +v -0.041200 -0.104949 0.030520 +v -0.041200 -0.113279 0.010457 +v -0.041200 -0.113965 0.016718 +v -0.041200 -0.116474 -0.005788 +v -0.041200 -0.110920 -0.022452 +v -0.041200 -0.102512 -0.030126 +v -0.041200 -0.104931 -0.030521 +v -0.043316 -0.114328 -0.014293 +v -0.049718 -0.113759 -0.015604 +v -0.043389 -0.107168 -0.029276 +v -0.049785 -0.107387 -0.027486 +v -0.043365 -0.102038 -0.038878 +v -0.049775 -0.100882 -0.039984 +v -0.043309 -0.089651 -0.061669 +v -0.049700 -0.088789 -0.062784 +v -0.030200 -0.039498 0.034940 +v -0.030200 -0.039376 0.031542 +v -0.030200 -0.050608 0.039858 +v -0.030546 -0.087466 0.040719 +v -0.030200 -0.091329 0.041516 +v -0.030200 -0.074353 0.046630 +v -0.030700 -0.068778 0.044315 +v -0.030200 -0.051854 0.043395 +v -0.030200 -0.100488 0.034971 +v -0.028000 -0.039474 0.034945 +v -0.028000 -0.049798 0.039450 +v -0.028001 -0.039748 0.032104 +v -0.028000 -0.053282 0.043965 +v -0.027241 -0.064999 0.044128 +v -0.028000 -0.075788 0.046474 +v -0.027998 -0.083512 0.042210 +v -0.028000 -0.092452 0.040920 +v -0.028000 -0.100166 0.032591 +v -0.028000 -0.100521 0.034931 +v -0.031679 -0.039488 0.034945 +v -0.032200 -0.038708 0.030596 +v -0.032200 -0.050608 0.039858 +v -0.032546 -0.087466 0.040719 +v -0.031671 -0.091896 0.041228 +v -0.031700 -0.075072 0.046565 +v -0.032700 -0.068778 0.044315 +v -0.031700 -0.059975 0.045476 +v -0.031700 -0.048104 0.041228 +v -0.032200 -0.100488 0.034971 +v -0.031200 -0.049369 0.039231 +v -0.031200 -0.039750 0.032122 +v -0.031200 -0.100164 0.032641 +v -0.031200 -0.100521 0.034931 +v -0.034200 -0.039498 0.034940 +v -0.034200 -0.039376 0.031542 +v -0.034200 -0.050608 0.039858 +v -0.034546 -0.087466 0.040719 +v -0.033671 -0.091896 0.041228 +v -0.033700 -0.075072 0.046565 +v -0.034700 -0.068778 0.044315 +v -0.033700 -0.059975 0.045476 +v -0.033700 -0.048104 0.041228 +v -0.034200 -0.100488 0.034971 +v -0.033200 -0.039474 0.034945 +v -0.033200 -0.049369 0.039231 +v -0.033200 -0.039750 0.032122 +v -0.033200 -0.100164 0.032641 +v -0.033200 -0.100521 0.034931 +v -0.036200 -0.039498 0.034940 +v -0.036200 -0.038708 0.030596 +v -0.036200 -0.050608 0.039858 +v -0.036546 -0.087466 0.040719 +v -0.035671 -0.091896 0.041228 +v -0.035700 -0.075072 0.046565 +v -0.036700 -0.068778 0.044315 +v -0.035700 -0.059975 0.045476 +v -0.035700 -0.048104 0.041228 +v -0.036200 -0.100488 0.034971 +v -0.035200 -0.039474 0.034945 +v -0.035200 -0.049369 0.039231 +v -0.035200 -0.039750 0.032122 +v -0.035200 -0.100164 0.032641 +v -0.035200 -0.100521 0.034931 +v -0.038200 -0.039498 0.034940 +v -0.038200 -0.038708 0.030596 +v -0.038200 -0.050608 0.039858 +v -0.038546 -0.087466 0.040719 +v -0.037671 -0.091896 0.041228 +v -0.037700 -0.075072 0.046565 +v -0.038700 -0.068778 0.044315 +v -0.037700 -0.059975 0.045476 +v -0.037700 -0.048104 0.041228 +v -0.038839 -0.100199 0.032514 +v -0.038200 -0.100488 0.034971 +v -0.037200 -0.039474 0.034945 +v -0.037200 -0.049369 0.039231 +v -0.037200 -0.039750 0.032122 +v -0.037200 -0.100164 0.032641 +v -0.037200 -0.100521 0.034931 +v -0.040200 -0.039498 0.034940 +v -0.040200 -0.039236 0.031307 +v -0.040200 -0.050608 0.039858 +v -0.040546 -0.087466 0.040719 +v -0.039671 -0.091896 0.041228 +v -0.039700 -0.075072 0.046565 +v -0.040700 -0.068778 0.044315 +v -0.039700 -0.059975 0.045476 +v -0.039700 -0.048104 0.041228 +v -0.040200 -0.100488 0.034971 +v -0.039200 -0.039474 0.034945 +v -0.039200 -0.049369 0.039231 +v -0.039200 -0.039750 0.032122 +v -0.039200 -0.100521 0.034931 +v -0.041679 -0.039488 0.034945 +v -0.042200 -0.039376 0.031540 +v -0.042200 -0.050652 0.039845 +v -0.042200 -0.100503 0.034197 +v -0.041671 -0.091896 0.041228 +v -0.042200 -0.077886 0.043603 +v -0.041700 -0.075072 0.046565 +v -0.042867 -0.067481 0.044059 +v -0.041700 -0.059975 0.045476 +v -0.041700 -0.048104 0.041228 +v -0.041200 -0.049369 0.039231 +v -0.041200 -0.039750 0.032122 +v -0.041200 -0.100164 0.032641 +v -0.041200 -0.100521 0.034931 +v -0.049711 -0.116611 0.000189 +v -0.043358 -0.116421 0.004490 +v -0.049708 -0.113467 0.016356 +v -0.043322 -0.112458 0.018656 +v -0.049745 -0.107267 0.027492 +v -0.043391 -0.107085 0.028611 +v -0.043199 -0.101390 0.031522 +v -0.043200 -0.113172 0.011240 +v -0.043200 -0.083147 0.042264 +v -0.043200 -0.054545 0.041476 +v -0.043197 -0.038644 0.031475 +v -0.042200 -0.026031 0.005587 +v -0.043200 -0.027222 0.012096 +v -0.042200 -0.031448 0.021558 +v -0.043200 -0.026266 -0.006774 +v -0.042199 -0.037511 -0.030172 +v -0.043200 -0.031448 -0.021558 +v -0.042200 -0.027856 -0.013734 +v -0.042199 -0.039885 -0.032635 +v -0.043200 -0.041841 -0.034139 +v -0.042507 -0.057966 -0.042722 +v -0.043201 -0.068436 -0.044218 +v -0.043200 -0.093110 -0.037661 +v -0.043201 -0.106291 -0.025550 +v -0.040845 -0.037586 0.030186 +v -0.041200 -0.028476 0.016067 +v -0.040200 -0.028307 0.015047 +v -0.040700 -0.025937 -0.004877 +v -0.040800 -0.030148 -0.018807 +v -0.040200 -0.037510 -0.030173 +v -0.041200 -0.037610 -0.030213 +v -0.041200 -0.039814 -0.032289 +v -0.040200 -0.039839 -0.032448 +v -0.041200 -0.057513 -0.042810 +v -0.040200 -0.058226 -0.042740 +v -0.039200 -0.037675 0.030198 +v -0.038640 -0.031147 0.021026 +v -0.039200 -0.037610 -0.030213 +v -0.038575 -0.029702 -0.018266 +v -0.038200 -0.039412 -0.031796 +v -0.039200 -0.039814 -0.032289 +v -0.039200 -0.057513 -0.042810 +v -0.038200 -0.058226 -0.042740 +v -0.037200 -0.037675 0.030198 +v -0.036640 -0.031147 0.021026 +v -0.036700 -0.031147 -0.021026 +v -0.036200 -0.039412 -0.031796 +v -0.037200 -0.037671 -0.030227 +v -0.037200 -0.039814 -0.032289 +v -0.037200 -0.057513 -0.042810 +v -0.036200 -0.058226 -0.042740 +v -0.035200 -0.037675 0.030198 +v -0.034640 -0.031147 0.021026 +v -0.034700 -0.031147 -0.021026 +v -0.034200 -0.039412 -0.031796 +v -0.035200 -0.037671 -0.030227 +v -0.035200 -0.039814 -0.032289 +v -0.035200 -0.057513 -0.042810 +v -0.034200 -0.058226 -0.042740 +v -0.033200 -0.037675 0.030198 +v -0.032640 -0.031147 0.021026 +v -0.032867 -0.031034 -0.020808 +v -0.032200 -0.037510 -0.030173 +v -0.033200 -0.037671 -0.030227 +v -0.033200 -0.039814 -0.032289 +v -0.032200 -0.039839 -0.032448 +v -0.033200 -0.057513 -0.042810 +v -0.032200 -0.058226 -0.042740 +v -0.031200 -0.037675 0.030198 +v -0.030200 -0.031448 0.021558 +v -0.031200 -0.028476 0.016067 +v -0.030200 -0.026026 0.005566 +v -0.031200 -0.025935 -0.003043 +v -0.030200 -0.028476 -0.016067 +v -0.031200 -0.030216 -0.019543 +v -0.030200 -0.039412 -0.031796 +v -0.031200 -0.039524 -0.031535 +v -0.031200 -0.057513 -0.042810 +v -0.030200 -0.058226 -0.042740 +v -0.028000 -0.026002 0.005322 +v -0.028000 -0.031238 0.021180 +v -0.026816 -0.029166 0.017256 +v -0.026904 -0.103550 -0.028963 +v -0.049757 -0.097512 0.037175 +v -0.043381 -0.098460 0.037115 +v -0.043350 -0.087445 0.043120 +v -0.049689 -0.086187 0.043567 +v -0.043327 -0.071712 0.046597 +v -0.049680 -0.072713 0.046420 +v -0.049706 -0.055268 0.044189 +v -0.043279 -0.054180 0.043761 +v -0.043377 -0.041486 0.037090 +v -0.049760 -0.042455 0.037175 +v -0.043329 -0.055827 -0.065142 +v -0.043322 -0.085064 -0.065038 +v -0.049705 -0.055046 -0.065063 +v -0.049700 -0.083677 -0.065215 +v -0.043445 -0.104193 0.037090 +v -0.049602 -0.104321 0.036977 +v -0.049493 -0.106979 0.034803 +v -0.043371 -0.106930 0.034847 +v -0.043384 -0.106864 -0.035109 +v -0.049554 -0.106812 -0.035166 +v -0.026789 -0.074071 0.044098 +v -0.026803 -0.091118 -0.039118 +v -0.026761 -0.026080 0.005817 +v -0.026784 -0.026368 -0.007656 +v -0.028000 -0.036962 -0.030059 +v -0.028000 -0.027334 -0.011406 +v -0.026801 -0.030054 -0.018923 +v -0.026880 -0.035860 0.028243 +v -0.026816 -0.076266 -0.043811 +v -0.028000 -0.037683 0.030199 +v -0.028000 -0.039795 -0.032191 +v -0.026902 -0.034949 -0.026997 +v -0.026846 -0.043028 -0.035160 +v -0.026884 -0.102659 0.030147 +v -0.026763 -0.114180 0.004255 +v -0.026779 -0.113439 -0.008382 +v -0.026801 -0.053396 0.041013 +v -0.026854 -0.043977 0.035762 +v -0.028000 -0.047793 -0.038183 +v -0.026755 -0.087616 0.040764 +v -0.026780 -0.059049 -0.043180 +v -0.026811 -0.109405 -0.020161 +v -0.026785 -0.110488 0.017966 +v -0.049904 -0.100783 -0.030040 +v -0.030200 -0.039590 -0.035393 +v -0.030200 -0.054345 -0.043826 +v -0.028000 -0.053075 -0.043915 +v -0.028000 -0.039479 -0.034930 +v -0.032200 -0.039519 -0.035383 +v -0.031756 -0.054412 -0.043821 +v -0.031200 -0.039589 -0.035694 +v -0.033662 -0.045919 -0.039883 +v -0.033756 -0.054412 -0.043821 +v -0.033781 -0.039530 -0.034954 +v -0.035662 -0.045919 -0.039883 +v -0.035756 -0.054412 -0.043821 +v -0.035781 -0.039530 -0.034954 +v -0.037662 -0.045919 -0.039883 +v -0.037756 -0.054412 -0.043821 +v -0.037781 -0.039530 -0.034954 +v -0.040200 -0.039519 -0.035383 +v -0.039756 -0.054412 -0.043821 +v -0.039200 -0.039589 -0.035694 +v -0.042200 -0.039519 -0.035383 +v -0.041756 -0.054412 -0.043821 +v -0.041200 -0.039589 -0.035694 +v -0.030200 -0.035133 0.030380 +v -0.030200 -0.035130 -0.030401 +v -0.030200 -0.026035 0.016718 +v -0.030200 -0.023526 -0.005788 +v -0.030200 -0.029080 -0.022452 +v -0.028000 -0.035069 0.030521 +v -0.028000 -0.028484 -0.021329 +v -0.028000 -0.023370 -0.004353 +v -0.028000 -0.026605 0.018146 +v -0.028000 -0.035055 -0.030526 +v -0.032200 -0.035055 0.030526 +v -0.032200 -0.026035 0.016718 +v -0.032700 -0.027000 0.009637 +v -0.032700 -0.025937 -0.004877 +v -0.032200 -0.023526 -0.005788 +v -0.032200 -0.029080 -0.022452 +v -0.032200 -0.035069 -0.030521 +v -0.031200 -0.035069 0.030521 +v -0.031200 -0.035029 -0.030488 +v -0.031200 -0.026035 -0.016718 +v -0.031200 -0.023526 0.005788 +v -0.031200 -0.029080 0.022452 +v -0.034200 -0.035133 0.030380 +v -0.034200 -0.035130 -0.030401 +v -0.033671 -0.028772 0.021896 +v -0.034700 -0.027000 0.009636 +v -0.033700 -0.024524 0.010025 +v -0.034700 -0.025937 -0.004877 +v -0.033700 -0.023435 -0.005072 +v -0.033729 -0.028772 -0.021895 +v -0.033200 -0.035069 0.030521 +v -0.033200 -0.035055 -0.030526 +v -0.036200 -0.035130 -0.030401 +v -0.036200 -0.035055 0.030526 +v -0.035671 -0.028772 0.021896 +v -0.036700 -0.027000 0.009637 +v -0.035700 -0.024524 0.010025 +v -0.036700 -0.025937 -0.004877 +v -0.035700 -0.023435 -0.005072 +v -0.035729 -0.028772 -0.021896 +v -0.035200 -0.035069 0.030521 +v -0.035200 -0.035055 -0.030526 +v -0.038200 -0.035130 -0.030401 +v -0.038200 -0.035055 0.030526 +v -0.037671 -0.028772 0.021896 +v -0.038600 -0.026635 0.008171 +v -0.037700 -0.024524 0.010025 +v -0.037700 -0.023435 -0.005072 +v -0.038867 -0.026104 -0.005542 +v -0.037729 -0.028772 -0.021896 +v -0.037200 -0.035069 0.030521 +v -0.037200 -0.035055 -0.030526 +v -0.040200 -0.035055 0.030526 +v -0.040200 -0.026035 0.016718 +v -0.040200 -0.023526 -0.005788 +v -0.040200 -0.029080 -0.022452 +v -0.040200 -0.035069 -0.030521 +v -0.039200 -0.035069 0.030521 +v -0.039200 -0.035055 -0.030526 +v -0.039200 -0.026035 -0.016718 +v -0.039200 -0.023526 0.005788 +v -0.039200 -0.029080 0.022452 +v -0.042200 -0.035133 0.030380 +v -0.042200 -0.026035 0.016718 +v -0.042200 -0.023526 -0.005788 +v -0.042200 -0.029080 -0.022452 +v -0.042200 -0.035069 -0.030521 +v -0.041200 -0.035069 0.030521 +v -0.041200 -0.035055 -0.030526 +v -0.041200 -0.026035 -0.016718 +v -0.041200 -0.023526 0.005788 +v -0.041200 -0.029080 0.022452 +v -0.049687 -0.026135 -0.015124 +v -0.043384 -0.024653 -0.011788 +v -0.049192 -0.032667 -0.029280 +v -0.043401 -0.032839 -0.029323 +v -0.049779 -0.039136 -0.039985 +v -0.043335 -0.038036 -0.038875 +v -0.049706 -0.050690 -0.062097 +v -0.043359 -0.051170 -0.062789 +v -0.049779 -0.032738 0.027448 +v -0.043408 -0.032837 0.028457 +v -0.043363 -0.026827 0.017290 +v -0.049659 -0.027762 0.019156 +v -0.049698 -0.024539 0.009020 +v -0.043322 -0.023927 0.005287 +v -0.049687 -0.023641 -0.003281 +v -0.043436 -0.033084 0.035162 +v -0.049562 -0.033011 0.033817 +v -0.049554 -0.034872 0.036866 +v -0.043282 -0.035450 0.036926 +v -0.043396 -0.033163 -0.035177 +v -0.049554 -0.033152 -0.035099 +v -0.049902 -0.099192 -0.032580 +v -0.049811 -0.032588 -0.027506 +v -0.081684 -0.097345 0.013028 +v -0.075900 -0.106239 0.026385 +v -0.077598 -0.098548 0.029880 +v -0.076964 -0.110692 0.009089 +v -0.075622 -0.114118 0.006876 +v -0.075442 -0.111594 0.017986 +v -0.079273 -0.105536 -0.004879 +v -0.077915 -0.109060 0.003697 +v -0.078312 -0.107989 0.006552 +v -0.076519 -0.112359 0.003209 +v -0.075029 -0.115381 -0.001796 +v -0.075028 -0.112000 -0.016445 +v -0.069096 -0.093980 -0.050187 +v -0.068173 -0.079046 -0.056391 +v -0.062112 -0.087948 -0.062371 +v -0.062831 -0.070084 -0.064310 +v -0.060627 -0.085268 -0.064719 +v -0.065078 -0.073158 -0.061100 +v -0.065212 -0.066843 -0.060916 +v -0.061400 -0.057619 -0.064703 +v -0.068439 -0.060413 -0.055756 +v -0.062173 -0.052155 -0.062354 +v -0.079961 -0.051847 -0.028160 +v -0.075192 -0.033709 -0.025965 +v -0.075941 -0.038800 -0.028647 +v -0.075739 -0.042904 -0.033643 +v -0.078472 -0.032927 -0.007827 +v -0.078067 -0.031263 0.003717 +v -0.075148 -0.024797 -0.002777 +v -0.075756 -0.026087 0.004522 +v -0.075556 -0.027460 0.015092 +v -0.076130 -0.027352 0.008615 +v -0.077890 -0.031332 0.008103 +v -0.075988 -0.044381 0.037219 +v -0.076888 -0.042742 0.033434 +v -0.080180 -0.049831 0.029029 +v -0.076115 -0.065230 0.045250 +v -0.076194 -0.053443 0.041953 +v -0.079431 -0.064700 0.037447 +v -0.076252 -0.079081 0.044314 +v -0.080332 -0.085800 0.031786 +v -0.076004 -0.091130 0.040176 +v -0.076186 -0.096685 0.035861 +v -0.067444 -0.070062 -0.057832 +v -0.067488 -0.046889 -0.052910 +v -0.073726 -0.052407 -0.044315 +v -0.076638 -0.080071 -0.040535 +v -0.076766 -0.066855 -0.041504 +v -0.072046 -0.041325 -0.041452 +v -0.072262 -0.098729 -0.040938 +v -0.079424 -0.087391 -0.030577 +v -0.075996 -0.097208 -0.032831 +v -0.083775 -0.074851 -0.019855 +v -0.077299 -0.039662 0.028799 +v -0.083738 -0.068531 0.023423 +v -0.076300 -0.101668 -0.027750 +v -0.080538 -0.097227 -0.016968 +v -0.082480 -0.049978 -0.016492 +v -0.074566 -0.107199 -0.026239 +v -0.074854 -0.028396 -0.017834 +v -0.084163 -0.088491 -0.003389 +v -0.086030 -0.069694 -0.002006 +v -0.084074 -0.052271 0.010181 +v -0.083043 -0.046851 -0.004958 +v -0.080804 -0.039780 0.011976 +v -0.084297 -0.082884 0.014147 +v -0.075856 -0.034054 0.026788 +v -0.072580 -0.108303 -0.026478 +v -0.073280 -0.112395 -0.018808 +v -0.060710 -0.089424 -0.062251 +v -0.070044 -0.100105 -0.042233 +v -0.072966 -0.115059 -0.011507 +v -0.073058 -0.116517 -0.000588 +v -0.073356 -0.115396 0.010042 +v -0.073360 -0.112586 0.018583 +v -0.073625 -0.108771 0.025554 +v -0.073879 -0.096504 0.038058 +v -0.074103 -0.089171 0.042388 +v -0.074153 -0.079370 0.045519 +v -0.074225 -0.070692 0.046470 +v -0.074012 -0.057919 0.045046 +v -0.074130 -0.044199 0.038730 +v -0.059879 -0.082062 -0.065473 +v -0.059694 -0.055838 -0.065335 +v -0.056700 -0.111123 0.009362 +v -0.056700 -0.107926 0.006000 +v -0.056700 -0.114053 0.005946 +v -0.056700 -0.110971 0.002656 +v -0.056700 -0.032074 0.006000 +v -0.056700 -0.029790 0.009026 +v -0.056700 -0.025761 0.006495 +v -0.056700 -0.029350 0.002762 +v -0.056700 -0.073061 -0.060919 +v -0.056700 -0.070451 -0.057872 +v -0.056700 -0.070796 -0.064015 +v -0.056700 -0.066614 -0.061350 +v -0.074812 -0.101669 0.029708 +v -0.049931 -0.100332 0.030342 +v -0.075085 -0.099838 0.031291 +v -0.074583 -0.099519 -0.031576 +v -0.073234 -0.099241 -0.033423 +v -0.074317 -0.101601 -0.029635 +v -0.074087 -0.105519 0.028467 +v -0.074325 -0.098782 0.034857 +v -0.071477 -0.100436 -0.037869 +v -0.073204 -0.104719 -0.028868 +v -0.076418 -0.099981 0.030023 +v -0.073452 -0.025908 -0.014774 +v -0.073199 -0.031298 -0.025733 +v -0.060955 -0.050357 -0.062003 +v -0.069872 -0.039994 -0.042411 +v -0.074245 -0.031979 0.026351 +v -0.073355 -0.027008 0.017893 +v -0.073300 -0.023943 0.006468 +v -0.072943 -0.023676 -0.003920 +v -0.049932 -0.039667 0.030344 +v -0.074999 -0.038347 0.029678 +v -0.075277 -0.040235 0.031354 +v -0.049960 -0.039618 -0.030315 +v -0.074478 -0.040480 -0.031775 +v -0.073922 -0.038814 -0.029889 +v -0.049847 -0.040835 -0.032910 +v -0.073359 -0.040738 -0.034271 +v -0.073924 -0.035306 0.028863 +v -0.074551 -0.041256 0.034863 +v -0.071257 -0.039433 -0.038143 +v -0.073701 -0.034353 -0.028304 +v -0.043129 -0.058174 -0.045261 +v -0.043129 -0.056026 -0.044960 +v -0.043129 -0.058104 -0.046297 +v -0.043129 -0.059054 -0.042872 +v -0.043129 -0.063920 -0.046613 +v -0.043129 -0.063216 -0.043941 +v -0.043129 -0.062091 -0.045394 +v -0.043129 -0.057159 -0.043738 +v -0.043129 -0.059591 -0.042903 +v -0.043129 -0.061426 -0.043949 +v -0.043129 -0.060297 -0.045583 +v -0.043129 -0.052443 -0.050807 +v -0.042629 -0.055427 -0.043691 +v -0.043129 -0.067450 -0.051172 +v -0.043129 -0.063131 -0.047739 +v -0.043129 -0.050986 -0.050018 +v -0.043129 -0.050927 -0.058289 +v -0.043129 -0.053039 -0.057693 +v -0.043129 -0.066278 -0.053885 +v -0.043129 -0.061037 -0.060582 +v -0.043129 -0.058362 -0.062829 +v -0.043129 -0.066361 -0.059362 +v -0.042129 -0.054519 -0.046266 +v -0.042129 -0.056612 -0.045531 +v -0.042129 -0.062544 -0.044881 +v -0.042129 -0.061252 -0.043785 +v -0.042129 -0.063090 -0.043735 +v -0.042129 -0.056404 -0.046959 +v -0.042129 -0.058293 -0.045125 +v -0.042129 -0.059977 -0.046346 +v -0.042129 -0.060634 -0.045679 +v -0.042129 -0.057572 -0.043579 +v -0.042129 -0.049953 -0.052844 +v -0.042129 -0.052129 -0.051302 +v -0.042129 -0.052920 -0.056957 +v -0.042129 -0.052971 -0.060528 +v -0.042129 -0.057759 -0.060682 +v -0.042129 -0.061394 -0.062755 +v -0.042129 -0.064864 -0.057702 +v -0.042129 -0.067351 -0.050525 +v -0.042129 -0.065637 -0.050846 +v -0.042129 -0.067103 -0.057402 +v -0.047521 -0.056304 -0.046007 +v -0.046565 -0.058150 -0.045579 +v -0.046935 -0.054693 -0.046595 +v -0.047392 -0.066581 -0.056127 +v -0.046903 -0.067115 -0.052729 +v -0.047541 -0.066820 -0.053036 +v -0.046581 -0.053317 -0.058881 +v -0.046749 -0.052134 -0.055405 +v -0.046648 -0.054160 -0.058957 +v -0.047266 -0.064634 -0.059269 +v -0.046536 -0.063697 -0.059620 +v -0.046542 -0.066226 -0.056507 +v -0.047545 -0.059020 -0.045724 +v -0.047484 -0.061523 -0.045975 +v -0.047309 -0.052258 -0.049115 +v -0.046563 -0.051618 -0.050608 +v -0.046961 -0.062762 -0.046303 +v -0.046999 -0.065743 -0.055318 +v -0.047119 -0.064732 -0.057499 +v -0.046535 -0.065973 -0.050005 +v -0.046941 -0.065815 -0.051758 +v -0.046716 -0.064056 -0.048476 +v -0.047367 -0.062399 -0.047213 +v -0.047165 -0.059589 -0.046553 +v -0.047257 -0.057516 -0.060371 +v -0.047536 -0.059125 -0.061375 +v -0.047399 -0.061920 -0.060086 +v -0.047573 -0.064004 -0.059461 +v -0.047532 -0.065920 -0.050707 +v -0.046988 -0.052359 -0.051184 +v -0.047392 -0.052027 -0.055303 +v -0.047350 -0.065433 -0.048643 +v -0.047537 -0.051376 -0.055754 +v -0.046748 -0.057148 -0.046580 +v -0.047345 -0.056311 -0.046899 +v -0.046571 -0.056742 -0.061117 +v -0.046529 -0.064151 -0.047986 +v -0.047435 -0.054555 -0.059112 +v -0.047350 -0.054474 -0.060132 +v -0.046879 -0.057909 -0.061496 +v -0.047551 -0.052669 -0.049623 +v -0.047361 -0.051002 -0.052789 +v -0.046640 -0.051096 -0.054853 +v -0.046857 -0.061728 -0.061131 +v -0.046866 -0.054177 -0.048401 +v -0.047135 -0.051733 -0.057128 +v -0.046845 -0.058755 -0.060552 +v -0.046807 -0.062876 -0.059471 +v -0.059685 -0.030454 0.008228 +v -0.059618 -0.027797 0.008593 +v -0.059679 -0.026323 0.006132 +v -0.059611 -0.027313 0.003734 +v -0.059687 -0.029832 0.003503 +v -0.059616 -0.031872 0.005427 +v -0.048771 -0.029357 0.004610 +v -0.048867 -0.027419 0.005868 +v -0.048808 -0.030384 0.006502 +v -0.056620 -0.027588 0.006807 +v -0.049183 -0.029113 0.007605 +v -0.056573 -0.029984 0.007517 +v -0.056602 -0.030121 0.004736 +v -0.056597 -0.027803 0.004790 +v -0.056767 -0.027887 0.008664 +v -0.056761 -0.028557 0.003027 +v -0.056773 -0.026181 0.005921 +v -0.056753 -0.031838 0.005454 +v -0.056774 -0.030726 0.008161 +v -0.057700 -0.027594 0.005505 +v -0.057700 -0.030020 0.006449 +v -0.054951 -0.037105 0.036422 +v -0.054830 -0.034078 0.035687 +v -0.054944 -0.033673 0.032153 +v -0.054948 -0.038878 0.030734 +v -0.054848 -0.040350 0.034370 +v -0.054825 -0.035695 0.029811 +v -0.020993 -0.038354 0.031997 +v -0.021092 -0.034997 0.034307 +v -0.021136 -0.037916 0.034921 +v -0.021025 -0.035653 0.031637 +v -0.050790 -0.038400 0.034922 +v -0.050824 -0.035006 0.034591 +v -0.050829 -0.035006 0.031951 +v -0.050809 -0.037906 0.031234 +v -0.050957 -0.033271 0.032247 +v -0.050963 -0.034236 0.035702 +v -0.050961 -0.037341 0.036767 +v -0.050961 -0.040113 0.034502 +v -0.050951 -0.039177 0.030440 +v -0.050965 -0.035607 0.029936 +v -0.051900 -0.035288 0.032227 +v -0.051900 -0.038377 0.032458 +v -0.051900 -0.036632 0.035017 +v -0.043129 -0.079718 -0.045190 +v -0.043129 -0.080601 -0.046510 +v -0.042641 -0.080382 -0.042895 +v -0.043129 -0.085481 -0.046266 +v -0.042629 -0.084573 -0.043691 +v -0.043129 -0.083519 -0.044398 +v -0.043129 -0.078084 -0.044074 +v -0.043129 -0.081891 -0.044090 +v -0.042688 -0.080929 -0.046512 +v -0.043129 -0.082728 -0.045781 +v -0.043129 -0.080870 -0.042887 +v -0.043129 -0.079017 -0.046152 +v -0.043129 -0.076063 -0.046684 +v -0.042629 -0.076770 -0.043956 +v -0.043129 -0.072649 -0.050525 +v -0.043129 -0.089186 -0.050647 +v -0.043129 -0.086806 -0.048962 +v -0.043129 -0.074275 -0.051258 +v -0.043129 -0.074645 -0.056524 +v -0.042646 -0.072554 -0.056382 +v -0.043129 -0.076122 -0.061324 +v -0.043129 -0.078882 -0.060327 +v -0.043129 -0.083351 -0.062610 +v -0.042550 -0.084554 -0.059594 +v -0.043129 -0.089458 -0.057066 +v -0.043129 -0.087534 -0.056249 +v -0.042129 -0.078652 -0.043878 +v -0.042129 -0.077477 -0.044822 +v -0.042129 -0.079332 -0.046545 +v -0.042129 -0.079480 -0.045630 +v -0.042129 -0.081939 -0.045504 +v -0.042129 -0.086313 -0.048620 +v -0.042129 -0.083855 -0.044708 +v -0.042129 -0.082457 -0.043588 +v -0.042129 -0.073033 -0.049843 +v -0.042129 -0.073995 -0.051773 +v -0.042129 -0.076945 -0.059758 +v -0.042129 -0.075462 -0.060921 +v -0.042129 -0.082102 -0.062724 +v -0.042129 -0.088103 -0.059364 +v -0.042129 -0.089721 -0.051273 +v -0.042129 -0.087948 -0.054907 +v -0.046603 -0.076047 -0.047285 +v -0.046687 -0.076192 -0.048161 +v -0.046531 -0.073607 -0.052194 +v -0.047471 -0.073507 -0.051022 +v -0.047589 -0.075835 -0.047705 +v -0.046793 -0.074116 -0.049339 +v -0.047576 -0.086804 -0.048485 +v -0.047231 -0.085499 -0.046704 +v -0.047578 -0.080982 -0.045819 +v -0.046487 -0.074383 -0.057292 +v -0.047257 -0.074411 -0.056021 +v -0.047332 -0.076836 -0.059306 +v -0.047599 -0.076508 -0.059730 +v -0.047576 -0.083126 -0.061021 +v -0.047117 -0.080382 -0.061598 +v -0.046481 -0.081542 -0.061137 +v -0.046707 -0.084589 -0.060673 +v -0.046536 -0.088094 -0.056724 +v -0.046767 -0.085697 -0.058888 +v -0.047049 -0.087764 -0.055170 +v -0.046538 -0.080353 -0.045965 +v -0.046645 -0.076717 -0.060278 +v -0.046814 -0.079116 -0.060312 +v -0.047633 -0.088161 -0.051200 +v -0.047098 -0.087721 -0.049027 +v -0.047325 -0.076499 -0.047953 +v -0.046698 -0.076115 -0.058752 +v -0.046626 -0.088475 -0.050781 +v -0.047179 -0.085542 -0.048092 +v -0.046539 -0.084793 -0.046655 +v -0.046953 -0.073861 -0.057443 +v -0.046817 -0.072943 -0.052740 +v -0.047529 -0.073956 -0.056948 +v -0.047575 -0.078754 -0.060572 +v -0.046870 -0.087789 -0.051539 +v -0.046984 -0.082249 -0.045475 +v -0.047140 -0.078358 -0.045813 +v -0.047533 -0.088381 -0.056326 +v -0.047269 -0.089054 -0.053219 +v -0.047078 -0.080884 -0.046491 +v -0.047455 -0.078974 -0.046625 +v -0.047338 -0.086261 -0.058371 +v -0.047073 -0.074051 -0.052272 +v -0.047581 -0.073227 -0.053518 +v -0.047135 -0.082529 -0.060329 +v -0.047329 -0.087118 -0.058812 +v -0.046569 -0.088817 -0.053949 +v -0.046718 -0.084388 -0.047181 +v 0.010328 -0.042294 0.034111 +v 0.012488 -0.041852 0.032290 +v 0.009890 -0.040615 0.033527 +v 0.010399 -0.039105 0.037300 +v 0.010378 -0.038031 0.036111 +v 0.014086 -0.037189 0.036953 +v 0.013494 -0.038331 0.038074 +v 0.016134 -0.039708 0.036697 +v 0.016329 -0.039265 0.034877 +v 0.014771 -0.042792 0.033613 +v 0.014634 -0.041690 0.032452 +v 0.013798 -0.044256 0.032149 +v 0.012706 -0.043068 0.031074 +v 0.017364 -0.041809 0.032333 +v 0.017436 -0.042384 0.034021 +v 0.017758 -0.039189 0.037216 +v 0.017147 -0.037376 0.036766 +v 0.012386 -0.036914 0.039491 +v 0.011496 -0.035910 0.038232 +v 0.007987 -0.039819 0.036586 +v 0.007854 -0.039300 0.034843 +v 0.009178 -0.043083 0.033322 +v 0.010505 -0.042735 0.031407 +v 0.012249 -0.044165 0.032240 +v 0.009959 -0.041929 0.042816 +v 0.008006 -0.044382 0.040372 +v 0.011257 -0.043208 0.041682 +v 0.013599 -0.041325 0.043423 +v 0.011778 -0.046840 0.038050 +v 0.009414 -0.047560 0.037201 +v 0.014356 -0.048314 0.036441 +v 0.015965 -0.044706 0.040185 +v 0.017979 -0.045960 0.038803 +v 0.016841 -0.042468 0.042277 +v 0.015941 -0.027552 0.020886 +v 0.012293 -0.028626 0.019649 +v 0.009901 -0.026902 0.021369 +v 0.014618 -0.024886 0.023459 +v 0.011855 -0.024759 0.023648 +v 0.010016 -0.041785 0.034485 +v 0.014323 -0.042723 0.033583 +v 0.016198 -0.040667 0.035640 +v 0.014177 -0.038442 0.037853 +v 0.010811 -0.039019 0.037293 +v 0.008631 -0.042520 0.033990 +v 0.008162 -0.039472 0.037031 +v 0.012137 -0.044316 0.032186 +v 0.016788 -0.038255 0.038248 +v 0.011992 -0.037152 0.039353 +v 0.015973 -0.043578 0.032928 +v 0.017991 -0.041460 0.035047 +v 0.012532 -0.043464 0.034355 +v 0.015783 -0.040628 0.037191 +v 0.010685 -0.040055 0.037764 +v -0.015981 -0.044912 0.039978 +v -0.017646 -0.046229 0.038526 +v -0.014291 -0.048430 0.036333 +v -0.010261 -0.047800 0.036940 +v -0.011518 -0.046747 0.038144 +v -0.008135 -0.045938 0.038807 +v -0.008553 -0.043147 0.041601 +v -0.012730 -0.041128 0.043648 +v -0.011502 -0.043096 0.041794 +v -0.017636 -0.043254 0.041501 +v -0.011704 -0.024617 0.023611 +v -0.015700 -0.027331 0.020951 +v -0.015530 -0.025509 0.022955 +v -0.013452 -0.028918 0.019621 +v -0.010168 -0.027477 0.020857 +v -0.011522 -0.042603 0.033709 +v -0.009673 -0.040057 0.036213 +v -0.013168 -0.038368 0.037940 +v -0.015676 -0.039442 0.036869 +v -0.015491 -0.042261 0.034009 +v -0.007852 -0.040874 0.035629 +v -0.009931 -0.043565 0.032945 +v -0.018070 -0.041104 0.035402 +v -0.016421 -0.038000 0.038503 +v -0.014910 -0.044201 0.032287 +v -0.010735 -0.037342 0.039148 +v -0.015108 -0.039892 0.037927 +v -0.010121 -0.040837 0.036982 +v -0.013771 -0.043418 0.034401 +v 0.015783 -0.044164 -0.040726 +v 0.014940 -0.041492 -0.043268 +v 0.018185 -0.044436 -0.040327 +v 0.010685 -0.043591 -0.041299 +v 0.010615 -0.041677 -0.043065 +v 0.012532 -0.047000 -0.037891 +v 0.016133 -0.047696 -0.037054 +v 0.012521 -0.048386 -0.036355 +v 0.009262 -0.047285 -0.037465 +v 0.007925 -0.044202 -0.040553 +v 0.012805 -0.028780 -0.019501 +v 0.015456 -0.025254 -0.023022 +v 0.010229 -0.027105 -0.021103 +v 0.011125 -0.024949 -0.023442 +v 0.016159 -0.041528 -0.034742 +v 0.015678 -0.028020 -0.020791 +v 0.012609 -0.042845 -0.033466 +v 0.010170 -0.041681 -0.034627 +v 0.010188 -0.039611 -0.036701 +v 0.013733 -0.038249 -0.038022 +v 0.016722 -0.043371 -0.033119 +v 0.017690 -0.039109 -0.037388 +v 0.009648 -0.037958 -0.038545 +v 0.007927 -0.041574 -0.034922 +v 0.013846 -0.037207 -0.039303 +v 0.011423 -0.044154 -0.032353 +v 0.011778 -0.043305 -0.034514 +v 0.011257 -0.039673 -0.038146 +v 0.015965 -0.041170 -0.036649 +v -0.015879 -0.045464 -0.039426 +v -0.014989 -0.048215 -0.036540 +v -0.017612 -0.046219 -0.038536 +v -0.010892 -0.046408 -0.038482 +v -0.010658 -0.048015 -0.036733 +v -0.008266 -0.043448 -0.041311 +v -0.008375 -0.046246 -0.038485 +v -0.017844 -0.043657 -0.041083 +v -0.015118 -0.041618 -0.043137 +v -0.012229 -0.042882 -0.042008 +v -0.011516 -0.041413 -0.043329 +v -0.010594 -0.025244 -0.023010 +v -0.013946 -0.024713 -0.023704 +v -0.015869 -0.026113 -0.022263 +v -0.012565 -0.028836 -0.019631 +v -0.010322 -0.027372 -0.020876 +v -0.015311 -0.028002 -0.020450 +v -0.015679 -0.039109 -0.037161 +v -0.010956 -0.038790 -0.037504 +v -0.010095 -0.041728 -0.034570 +v -0.014623 -0.042734 -0.033536 +v -0.012977 -0.037122 -0.039385 +v -0.017688 -0.038994 -0.037495 +v -0.009348 -0.038261 -0.038249 +v -0.011889 -0.044324 -0.032172 +v -0.016976 -0.043044 -0.033462 +v -0.007876 -0.041408 -0.035089 +v -0.010707 -0.040142 -0.037677 +v -0.011518 -0.043211 -0.034608 +v -0.014482 -0.039554 -0.038265 +v -0.015293 -0.042623 -0.035196 +v -0.013522 -0.037154 -0.036988 +v -0.014896 -0.038726 -0.037678 +v -0.011004 -0.038600 -0.037805 +v -0.009674 -0.038766 -0.035377 +v -0.009893 -0.041820 -0.034585 +v -0.011322 -0.041718 -0.032424 +v -0.014720 -0.042954 -0.033451 +v -0.016223 -0.040760 -0.033382 +v -0.016026 -0.039580 -0.036825 +v -0.015243 -0.037789 -0.036353 +v -0.016687 -0.037054 -0.037089 +v -0.016271 -0.038009 -0.038396 +v -0.018360 -0.041211 -0.035194 +v -0.018038 -0.039800 -0.034342 +v -0.015870 -0.042612 -0.031531 +v -0.013570 -0.044331 -0.032074 +v -0.011367 -0.042924 -0.031218 +v -0.009360 -0.043151 -0.033253 +v -0.008074 -0.040725 -0.033417 +v -0.007855 -0.040134 -0.036270 +v -0.009854 -0.036480 -0.037662 +v -0.010753 -0.037452 -0.038953 +v -0.015326 -0.037455 -0.038950 +v -0.015801 -0.036508 -0.037634 +v 0.010769 -0.041402 -0.032740 +v 0.011422 -0.042836 -0.033569 +v 0.009732 -0.039783 -0.036622 +v 0.010377 -0.037747 -0.036395 +v 0.012783 -0.038310 -0.038095 +v 0.015833 -0.037974 -0.036168 +v 0.015777 -0.039264 -0.037141 +v 0.015370 -0.042555 -0.033850 +v 0.014771 -0.041660 -0.032482 +v 0.012706 -0.043721 -0.031741 +v 0.015978 -0.042522 -0.031620 +v 0.017151 -0.043068 -0.033337 +v 0.018170 -0.038557 -0.035585 +v 0.017334 -0.038642 -0.037763 +v 0.013710 -0.035960 -0.038182 +v 0.011496 -0.037041 -0.039364 +v 0.008603 -0.037451 -0.036691 +v 0.008070 -0.039900 -0.036505 +v 0.008786 -0.041700 -0.032442 +v 0.008875 -0.042865 -0.033540 +v 0.012240 -0.043603 -0.031671 +v -0.012961 -0.038215 0.038190 +v -0.013710 -0.037160 0.036982 +v -0.009857 -0.038591 0.035551 +v -0.009356 -0.041160 0.035245 +v -0.010347 -0.041029 0.033113 +v -0.013674 -0.043075 0.033330 +v -0.014263 -0.041890 0.032252 +v -0.016203 -0.041375 0.035030 +v -0.016290 -0.038816 0.035326 +v -0.015479 -0.039017 0.037388 +v -0.017321 -0.038708 0.037696 +v -0.016874 -0.037106 0.037036 +v -0.017528 -0.041492 0.032650 +v -0.017239 -0.042865 0.033540 +v -0.010903 -0.043073 0.031069 +v -0.012091 -0.044265 0.032139 +v -0.008345 -0.042180 0.034225 +v -0.007855 -0.039003 0.035139 +v -0.008566 -0.038812 0.037593 +v -0.010753 -0.036321 0.037822 +v -0.011891 -0.037211 0.039194 +v -0.015326 -0.036323 0.037819 +v -0.015801 -0.037639 0.038765 +v -0.021000 -0.106771 0.028745 +v -0.027000 -0.106482 0.029439 +v -0.021000 -0.112863 0.018445 +v -0.027000 -0.116524 0.008160 +v -0.021000 -0.116778 0.001757 +v -0.027000 -0.113938 -0.016148 +v -0.021000 -0.113437 -0.017450 +v -0.027000 -0.106424 -0.029507 +v -0.021000 -0.106470 -0.029442 +v -0.021074 -0.048371 0.041318 +v -0.027000 -0.055524 0.044453 +v -0.021000 -0.070080 0.046751 +v -0.027000 -0.073482 0.046625 +v -0.021000 -0.085787 0.043892 +v -0.027000 -0.088990 0.042604 +v -0.021000 -0.099423 0.036481 +v -0.027000 -0.099502 0.036424 +v -0.027000 -0.043919 0.038707 +v -0.016811 -0.038499 0.020936 +v 0.016818 -0.038496 0.020905 +v -0.016994 -0.034596 0.013084 +v 0.017000 -0.034573 0.013025 +v -0.016971 -0.032446 0.002856 +v 0.016972 -0.032448 0.002871 +v -0.016951 -0.033060 -0.007687 +v 0.016958 -0.033064 -0.007707 +v -0.016975 -0.038236 -0.020394 +v 0.016962 -0.035931 -0.015934 +v 0.016760 -0.038502 -0.020886 +v 0.020884 -0.077248 0.037017 +v -0.018565 -0.076248 0.037285 +v -0.018188 -0.087289 0.033561 +v 0.020758 -0.093232 0.029699 +v -0.018202 -0.094118 0.028900 +v -0.018018 -0.100453 0.022240 +v 0.020773 -0.104926 0.014629 +v -0.018125 -0.104762 0.014371 +v -0.018960 -0.107459 0.005824 +v 0.020916 -0.107433 -0.002195 +v -0.017937 -0.107380 -0.004347 +v -0.018273 -0.105358 -0.013027 +v 0.020928 -0.103859 -0.016621 +v -0.017986 -0.100511 -0.022140 +v 0.020722 -0.093218 -0.029732 +v -0.019173 -0.095630 -0.027966 +v -0.018438 -0.088511 -0.032878 +v -0.018584 -0.077599 -0.037137 +v 0.020888 -0.076966 -0.037102 +v -0.021115 -0.030672 -0.026570 +v -0.026999 -0.030696 -0.026633 +v -0.027000 -0.024144 -0.010168 +v -0.021000 -0.024541 -0.011088 +v -0.021000 -0.023857 0.007760 +v -0.027000 -0.024541 0.011088 +v -0.021111 -0.030689 0.026605 +v -0.027000 -0.030731 0.026539 +v -0.021000 -0.098739 -0.036772 +v -0.027000 -0.099423 -0.036481 +v -0.021000 -0.082491 -0.045468 +v -0.027000 -0.085787 -0.043892 +v -0.027000 -0.070104 -0.046729 +v -0.021000 -0.061047 -0.045903 +v -0.027000 -0.053843 -0.043781 +v -0.020683 -0.046981 -0.040428 +v -0.027000 -0.043855 -0.038680 +v -0.020790 -0.035473 0.022960 +v -0.020897 -0.031269 0.015391 +v -0.020893 -0.028446 0.002826 +v -0.020890 -0.029457 -0.009464 +v -0.020825 -0.035351 -0.023093 +v -0.018626 -0.042773 -0.038646 +v -0.027000 -0.035373 -0.038822 +v -0.016181 -0.050244 -0.038203 +v -0.009616 -0.049765 -0.038293 +v 0.020774 -0.035554 -0.038754 +v 0.018661 -0.043273 -0.038539 +v 0.015620 -0.036052 -0.038428 +v 0.012163 -0.035569 -0.038759 +v 0.008755 -0.048972 -0.038323 +v 0.015539 -0.050702 -0.038258 +v -0.013839 -0.035599 -0.038787 +v 0.007629 -0.041031 -0.038624 +v -0.007368 -0.040523 -0.038641 +v 0.020793 -0.028682 0.031712 +v 0.020807 -0.035559 0.038750 +v 0.020783 -0.028671 -0.031731 +v -0.027000 -0.028530 -0.031770 +v 0.020353 -0.035979 0.023570 +v 0.020684 -0.031152 0.013620 +v 0.020405 -0.035997 -0.023580 +v 0.020521 -0.029009 0.004346 +v 0.020721 -0.029990 -0.010454 +v 0.016243 -0.043027 -0.031115 +v 0.018601 -0.038953 -0.035189 +v 0.009235 -0.042703 -0.031439 +v 0.007576 -0.038051 -0.036090 +v -0.018236 -0.041224 -0.032917 +v -0.017536 -0.036907 -0.037233 +v -0.014450 -0.043372 -0.030771 +v -0.009380 -0.042756 -0.031386 +v -0.007784 -0.037286 -0.036851 +v -0.019694 -0.029179 -0.030718 +v -0.019751 -0.035880 -0.023948 +v -0.016688 -0.038305 -0.021438 +v -0.018536 -0.043320 0.038676 +v -0.027000 -0.035387 0.038822 +v -0.015620 -0.036052 0.038428 +v 0.010461 -0.050702 0.038258 +v -0.014170 -0.050952 0.038248 +v -0.009757 -0.049857 0.038290 +v 0.017245 -0.048972 0.038323 +v -0.007339 -0.043682 0.038523 +v -0.009470 -0.037384 0.038761 +v 0.010453 -0.035967 0.038435 +v 0.013838 -0.035583 0.038772 +v -0.012708 -0.035578 0.038732 +v 0.018371 -0.041031 0.038624 +v 0.007339 -0.043273 0.038539 +v -0.017875 -0.047527 0.038430 +v 0.020986 -0.036603 0.023575 +v 0.020984 -0.036600 -0.023630 +v -0.018837 -0.040406 0.033737 +v -0.013000 -0.043666 0.030476 +v -0.008376 -0.041796 0.032346 +v -0.019760 -0.035886 0.023936 +v -0.019671 -0.029176 0.030725 +v 0.016765 -0.042703 0.031439 +v 0.018424 -0.038052 0.036090 +v -0.027000 -0.028523 0.031792 +v 0.009757 -0.043027 0.031115 +v 0.007399 -0.038953 0.035189 +v -0.007576 -0.038052 0.036090 +v -0.027000 -0.104608 0.036703 +v -0.021000 -0.103762 0.036789 +v -0.027000 -0.106789 0.033762 +v -0.021000 -0.106685 0.034591 +v -0.020743 -0.097684 0.028538 +v -0.020820 -0.079753 0.039090 +v -0.020808 -0.091421 -0.033925 +v -0.021000 -0.104591 -0.036685 +v -0.027000 -0.106778 -0.033705 +v -0.021000 -0.106789 -0.033762 +v -0.027000 -0.104668 -0.036715 +v -0.020863 -0.108333 0.013338 +v -0.020953 -0.110144 -0.009676 +v -0.020737 -0.102232 -0.023012 +v -0.020795 -0.077944 -0.039287 +v -0.020202 -0.089892 0.033599 +v -0.020210 -0.105622 0.016490 +v -0.020094 -0.108691 -0.004823 +v -0.020129 -0.105403 -0.016192 +v 0.007333 -0.033478 -0.008646 +v -0.006295 -0.033848 -0.010484 +v 0.005056 -0.034292 -0.011741 +v 0.008645 -0.032447 0.003007 +v 0.008464 -0.032623 -0.003994 +v 0.015732 -0.032564 0.002171 +v 0.016745 -0.032336 -0.001228 +v 0.005463 -0.033131 0.007718 +v -0.005228 -0.034262 0.011582 +v -0.006595 -0.032986 0.006868 +v -0.008503 -0.032469 -0.002808 +v -0.015669 -0.032296 0.000055 +v -0.016534 -0.035222 0.014058 +v -0.005594 -0.037565 0.019028 +v -0.016927 -0.037681 0.019670 +v 0.005654 -0.035119 0.013835 +v 0.016810 -0.035383 0.014690 +v 0.016915 -0.037813 0.019995 +v 0.005602 -0.037575 0.019031 +v 0.015701 -0.035574 -0.014848 +v 0.016900 -0.037795 -0.019917 +v 0.005592 -0.037572 -0.019045 +v -0.016950 -0.037670 -0.019670 +v -0.005530 -0.037866 -0.019999 +v -0.016693 -0.034992 -0.013720 +v 0.001702 -0.037208 0.022443 +v -0.016988 -0.037289 0.022469 +v -0.002023 -0.037262 0.022323 +v 0.016974 -0.036810 0.023142 +v -0.020670 -0.034008 -0.020733 +v -0.020568 -0.029942 -0.009411 +v -0.020624 -0.028897 0.005399 +v -0.017342 -0.031858 0.000080 +v -0.020671 -0.034009 0.020733 +v -0.017018 -0.037250 -0.022521 +v 0.001317 -0.037149 -0.022620 +v 0.016985 -0.036837 -0.023110 +v 0.020593 -0.029173 0.005761 +v 0.020684 -0.033921 0.020816 +v 0.020495 -0.029767 -0.008363 +v 0.018038 -0.034256 -0.014263 +v 0.020621 -0.034083 -0.020708 +v 0.017356 -0.029373 0.030277 +v 0.016736 -0.022963 0.030746 +v 0.001686 -0.027361 0.030682 +v 0.021339 -0.027878 0.020974 +v 0.021273 -0.023341 0.027841 +v 0.021361 -0.023096 -0.027747 +v 0.021342 -0.027873 -0.020917 +v 0.020981 -0.025226 -0.015078 +v 0.021000 -0.022820 0.004411 +v 0.028520 -0.022353 -0.020650 +v 0.032421 -0.023832 -0.010006 +v 0.034300 -0.022338 -0.007948 +v 0.034759 -0.022779 0.001682 +v 0.033206 -0.022346 0.011384 +v 0.030468 -0.024601 0.012509 +v 0.028168 -0.022325 0.020992 +v 0.006160 -0.022340 0.034655 +v 0.004288 -0.026086 0.031146 +v -0.006786 -0.022377 0.034466 +v -0.010575 -0.025169 0.030751 +v -0.016792 -0.022783 0.030743 +v 0.009089 -0.020337 0.034053 +v 0.020929 -0.020338 0.028315 +v -0.007542 -0.020337 0.034558 +v -0.017387 -0.029305 0.030283 +v -0.018965 -0.020336 0.029516 +v -0.027129 -0.020337 0.022535 +v -0.021290 -0.023367 0.027828 +v -0.030318 -0.022346 0.018182 +v -0.034522 -0.020337 0.007649 +v -0.034918 -0.022698 0.002390 +v -0.034206 -0.020337 -0.008411 +v -0.034196 -0.023043 -0.005752 +v -0.029762 -0.022332 -0.019072 +v -0.028075 -0.020337 -0.021271 +v -0.019907 -0.020337 -0.028856 +v -0.021297 -0.023292 -0.027798 +v -0.017303 -0.029376 -0.030332 +v -0.011169 -0.020337 -0.033387 +v -0.016789 -0.022964 -0.030719 +v -0.008757 -0.022324 -0.034004 +v 0.005206 -0.020338 -0.035022 +v 0.005023 -0.022334 -0.034986 +v 0.017776 -0.020338 -0.030198 +v 0.016603 -0.023068 -0.030778 +v 0.017407 -0.029241 -0.030306 +v 0.026004 -0.020337 -0.023808 +v 0.034078 -0.020339 -0.009428 +v 0.034596 -0.020338 0.006625 +v 0.030240 -0.020338 0.017816 +v -0.021304 -0.027886 -0.020972 +v -0.021358 -0.027864 0.020901 +v -0.020980 -0.025203 0.015025 +v -0.021000 -0.022818 -0.004428 +v -0.030365 -0.024635 0.012622 +v -0.027401 -0.025739 -0.015925 +v -0.001806 -0.028148 -0.030532 +v 0.000596 -0.026787 -0.031008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vn -0.9993 -0.0344 0.0160 +vn -0.9991 -0.0363 0.0213 +vn -0.9993 -0.0259 0.0276 +vn -0.9996 0.0006 0.0267 +vn -0.9995 0.0325 0.0063 +vn -0.9992 0.0390 0.0128 +vn -0.9995 0.0272 -0.0128 +vn -0.9997 0.0206 -0.0133 +vn 0.9999 0.0096 0.0118 +vn 0.9963 0.0853 0.0071 +vn 0.9998 0.0008 0.0220 +vn 0.9949 0.1006 0.0017 +vn -0.0046 -0.9893 0.1460 +vn 0.0067 -0.9619 0.2734 +vn -0.0040 -0.9882 0.1529 +vn 0.0076 -0.9591 0.2829 +vn -0.0078 0.1368 0.9906 +vn 0.0109 -0.1037 0.9946 +vn 0.0096 -0.0862 0.9962 +vn -0.0087 0.1485 0.9889 +vn 0.0213 0.8464 0.5321 +vn -0.0190 0.9686 -0.2479 +vn 0.0093 0.7664 -0.6423 +vn -0.0177 0.9633 -0.2679 +vn 0.0111 0.7481 -0.6635 +vn -0.0003 -0.1439 -0.9896 +vn 0.0179 -0.3447 -0.9385 +vn 0.0009 -0.1570 -0.9876 +vn 0.0191 -0.3578 -0.9336 +vn 0.9922 0.1056 0.0658 +vn 0.9956 -0.0259 0.0901 +vn 0.9948 -0.0664 0.0770 +vn 0.9958 -0.0904 0.0126 +vn 0.9943 -0.0853 -0.0638 +vn 0.9928 -0.0719 -0.0959 +vn 0.9960 0.0203 -0.0874 +vn 0.9950 0.0644 -0.0770 +vn 0.9953 0.0954 -0.0171 +vn 0.9937 0.0551 0.0974 +vn -0.0468 -0.7340 0.6775 +vn 0.0176 -0.7779 0.6282 +vn -0.0542 -0.7286 0.6828 +vn -0.1101 -0.6846 0.7206 +vn 0.1354 0.1540 0.9788 +vn -0.1587 0.5930 0.7894 +vn 0.1155 0.8957 0.4294 +vn -0.1612 0.9370 -0.3099 +vn -0.0106 0.8753 -0.4835 +vn 0.0019 0.8680 -0.4966 +vn 0.1584 0.7476 -0.6450 +vn -0.1243 -0.1275 -0.9840 +vn -0.0728 -0.1974 -0.9776 +vn -0.0797 -0.1881 -0.9789 +vn -0.0223 -0.2638 -0.9643 +vn -0.0416 -0.8980 -0.4379 +vn -0.0735 -0.9121 -0.4034 +vn -0.0467 -0.9004 -0.4325 +vn -0.0156 -0.8850 -0.4654 +vn 0.1237 -0.3248 -0.9376 +vn -0.0014 -0.4509 -0.8926 +vn 0.0015 -0.4477 -0.8942 +vn -0.1240 -0.5590 -0.8198 +vn -0.2276 0.9558 -0.1862 +vn -0.1765 0.9756 -0.1309 +vn -0.1845 0.9729 -0.1395 +vn -0.1239 0.9895 -0.0743 +vn 0.1271 -0.6222 0.7725 +vn -0.0344 -0.5380 0.8423 +vn 0.0058 -0.5609 0.8279 +vn -0.2067 -0.4245 0.8815 +vn -1.0000 0.0000 0.0000 +vn 0.9668 0.2553 -0.0066 +vn -0.9988 -0.0047 -0.0480 +vn -0.9990 -0.0334 0.0290 +vn -0.9975 0.0645 0.0273 +vn 0.9996 0.0106 0.0270 +vn 0.9994 0.0107 0.0335 +vn 0.9996 0.0109 0.0274 +vn 0.9997 0.0107 0.0219 +vn 0.0064 -0.7842 -0.6205 +vn 0.0197 -0.6873 -0.7261 +vn 0.0188 -0.6944 -0.7193 +vn 0.0054 -0.7905 -0.6125 +vn -0.0032 -0.5611 0.8277 +vn 0.0089 -0.6634 0.7483 +vn 0.0080 -0.6562 0.7546 +vn -0.0039 -0.5547 0.8320 +vn -0.0115 0.8418 0.5396 +vn 0.0173 0.6078 0.7939 +vn 0.0152 0.6277 0.7783 +vn -0.0132 0.8530 0.5218 +vn -0.0048 0.4838 -0.8752 +vn 0.0248 0.7747 -0.6319 +vn 0.0229 0.7583 -0.6516 +vn -0.0067 0.4625 -0.8866 +vn 0.9880 -0.1481 0.0437 +vn 0.9946 -0.0982 -0.0347 +vn 0.9959 -0.0190 -0.0881 +vn 0.9954 -0.0277 -0.0915 +vn 0.9948 0.0645 -0.0782 +vn 0.9874 0.1543 -0.0346 +vn 0.9956 0.0799 0.0487 +vn 0.9891 0.0453 0.1400 +vn 0.9962 -0.0352 0.0795 +vn -0.0405 -0.6678 -0.7433 +vn -0.0885 -0.6969 -0.7117 +vn -0.0454 -0.6709 -0.7402 +vn 0.0008 -0.6406 -0.7679 +vn -0.1326 -0.9879 0.0809 +vn 0.0255 -0.9662 0.2566 +vn 0.0350 -0.9631 0.2667 +vn 0.1746 -0.8951 0.4103 +vn -0.1689 -0.1960 0.9659 +vn 0.0241 0.4740 0.8802 +vn 0.1370 0.3201 0.9374 +vn 0.0291 0.4676 0.8835 +vn -0.1115 0.6325 0.7665 +vn 0.0389 0.9798 -0.1964 +vn 0.0804 0.9848 -0.1540 +vn 0.0445 0.9806 -0.1907 +vn -0.0081 0.9699 -0.2434 +vn -0.1570 0.5551 -0.8168 +vn -0.0083 0.3844 -0.9231 +vn -0.0329 0.4143 -0.9095 +vn 0.1178 0.2214 -0.9680 +vn -0.4512 0.6801 -0.5779 +vn -0.4238 0.7042 -0.5697 +vn -0.4334 0.6959 -0.5727 +vn -0.3951 0.7278 -0.5605 +vn -0.0160 0.0680 0.9976 +vn -0.7243 -0.5464 0.4205 +vn -0.1351 -0.9238 -0.3582 +vn -0.9996 0.0027 0.0276 +vn -0.9993 0.0187 0.0329 +vn -0.9993 0.0191 0.0306 +vn -0.9997 -0.0030 0.0249 +vn -0.9994 0.0033 -0.0353 +vn -0.9998 -0.0187 0.0099 +vn 0.9999 -0.0129 -0.0045 +vn 0.9918 0.0573 -0.1142 +vn 0.9919 0.0566 -0.1136 +vn 0.0003 0.9705 -0.2410 +vn -0.0128 0.9550 -0.2962 +vn -0.0109 0.9576 -0.2881 +vn 0.0020 0.9722 -0.2342 +vn 0.0100 -0.2190 -0.9757 +vn 0.0073 -0.2362 -0.9717 +vn 0.0075 -0.2338 -0.9722 +vn 0.0102 -0.2177 -0.9760 +vn 0.0206 -0.9968 -0.0778 +vn 0.0369 -0.9992 0.0145 +vn 0.0227 -0.9976 -0.0659 +vn 0.0390 -0.9989 0.0264 +vn -0.0087 -0.0182 0.9998 +vn 0.0431 0.2436 0.9689 +vn -0.0011 0.0203 0.9998 +vn 0.0514 0.2858 0.9569 +vn 0.9944 -0.0841 0.0639 +vn 0.9927 -0.0939 0.0757 +vn 0.9937 -0.1001 -0.0505 +vn 0.9919 -0.0788 -0.0999 +vn 0.9919 0.0876 0.0917 +vn 0.9941 0.1076 0.0156 +vn 0.9938 0.0074 0.1112 +vn 0.9936 0.0257 -0.1101 +vn 0.9923 0.0828 -0.0921 +vn -0.1846 0.9634 0.1946 +vn 0.0468 0.7963 -0.6030 +vn 0.1799 0.8631 -0.4719 +vn 0.0103 0.7727 -0.6347 +vn -0.1504 0.6420 -0.7518 +vn 0.0522 -0.4896 -0.8704 +vn 0.0965 -0.4519 -0.8868 +vn 0.0438 -0.4964 -0.8670 +vn -0.0083 -0.5378 -0.8431 +vn -0.0827 -0.9893 0.1204 +vn -0.0656 -0.9924 0.1042 +vn -0.0851 -0.9888 0.1227 +vn -0.1002 -0.9855 0.1370 +vn -0.0456 -0.1475 0.9880 +vn 0.1150 -0.3414 0.9329 +vn -0.0573 -0.1328 0.9895 +vn -0.1914 0.0405 0.9807 +vn 0.1730 0.6319 0.7555 +vn -0.8017 0.5690 0.1832 +vn 0.1881 -0.0959 0.9775 +vn -0.7257 -0.6549 -0.2109 +vn 0.0808 -0.5151 -0.8533 +vn -0.2673 0.8292 -0.4909 +vn 0.9605 0.1387 -0.2411 +vn 0.4339 0.4492 -0.7810 +vn -0.6549 0.1005 -0.7490 +vn -0.4063 -0.9090 -0.0928 +vn -0.4221 -0.9045 -0.0601 +vn -0.4023 -0.9099 -0.1011 +vn -0.3882 -0.9125 -0.1290 +vn 0.5632 -0.7564 0.3327 +vn -0.4997 -0.2994 0.8128 +vn 0.5603 0.5445 0.6241 +vn 0.3870 -0.8574 -0.3394 +vn -0.5775 -0.2903 -0.7630 +vn 0.6458 0.2455 -0.7229 +vn -0.4206 0.6789 -0.6017 +vn 0.3990 0.8959 0.1955 +vn -0.1934 0.9001 0.3905 +vn -0.0671 -0.0196 0.9976 +vn 0.4450 -0.1518 0.8826 +vn -0.4535 -0.8712 0.1881 +vn 0.7926 -0.3273 -0.5144 +vn 1.0000 0.0000 0.0000 +vn 0.9878 -0.1245 0.0938 +vn 0.9771 -0.1698 0.1279 +vn 0.9171 0.2759 0.2878 +vn 0.9317 -0.2902 0.2186 +vn -0.9618 -0.1642 0.2192 +vn -0.9772 -0.0850 0.1947 +vn -0.9868 -0.0365 0.1577 +vn -0.9998 0.0015 0.0192 +vn -0.4146 0.7920 0.4481 +vn -0.4377 0.7992 0.4119 +vn -0.4551 0.8038 0.3832 +vn 0.5126 0.8544 -0.0847 +vn -0.4893 0.1889 -0.8514 +vn 0.1854 -0.0490 -0.9814 +vn -0.1649 -0.9626 0.2152 +vn -0.1482 -0.9640 0.2209 +vn -0.0718 -0.9333 0.3519 +vn -0.0589 -0.9266 0.3713 +vn 0.6826 -0.7128 -0.1614 +vn -0.0457 -0.8637 0.5020 +vn -0.3128 0.4907 -0.8132 +vn 0.4663 0.7253 -0.5064 +vn -0.4835 0.8737 0.0539 +vn 0.4740 0.7302 0.4921 +vn -0.4883 0.0528 0.8711 +vn -0.5360 0.0692 0.8414 +vn -0.2247 -0.0320 0.9739 +vn -0.0825 -0.0742 0.9938 +vn 0.4519 -0.8392 0.3026 +vn -0.5275 -0.8488 0.0349 +vn 0.2602 -0.4750 -0.8406 +vn -0.3919 0.7838 0.4818 +vn 0.9493 -0.0725 -0.3060 +vn 0.9962 -0.0201 -0.0848 +vn 0.8997 -0.1007 -0.4248 +vn -0.9950 0.0544 -0.0839 +vn -0.9923 0.0671 -0.1036 +vn -0.9721 0.1275 -0.1969 +vn -0.9993 0.0349 0.0110 +vn -0.9994 0.0215 0.0254 +vn -0.9995 0.0322 -0.0044 +vn -0.9997 0.0249 -0.0078 +vn -0.9993 -0.0202 0.0304 +vn -0.9993 -0.0074 0.0365 +vn -0.9994 -0.0294 0.0156 +vn -0.9996 -0.0256 0.0094 +vn 0.9996 -0.0066 -0.0260 +vn 0.9974 0.0399 -0.0605 +vn 0.9996 -0.0056 -0.0267 +vn 0.9989 -0.0467 0.0039 +vn -0.0127 0.6909 -0.7229 +vn 0.0220 0.3112 -0.9501 +vn -0.0104 0.6691 -0.7431 +vn 0.0244 0.2805 -0.9595 +vn -0.0090 -0.6358 -0.7718 +vn 0.0292 -0.9934 -0.1110 +vn -0.0093 -0.9123 0.4094 +vn 0.0229 0.0495 0.9985 +vn -0.0163 0.5429 0.8396 +vn 0.0248 0.9693 0.2448 +vn 0.9949 0.0081 -0.1001 +vn 0.9952 -0.0211 -0.0954 +vn 0.9964 0.0770 -0.0362 +vn 0.9893 0.1378 0.0475 +vn 0.9954 0.0435 0.0852 +vn 0.9893 -0.0349 0.1416 +vn 0.9953 -0.0774 0.0580 +vn 0.9954 -0.0932 -0.0212 +vn 0.9953 -0.0871 -0.0427 +vn 0.0232 0.3403 -0.9400 +vn 0.1426 0.4482 -0.8825 +vn 0.0065 0.3239 -0.9461 +vn -0.1238 0.1946 -0.9730 +vn -0.0763 -0.6918 -0.7180 +vn -0.0176 -0.6284 -0.7777 +vn -0.0677 -0.6830 -0.7273 +vn -0.1209 -0.7355 -0.6666 +vn 0.1710 -0.9794 0.1077 +vn -0.1948 -0.7841 0.5893 +vn 0.1683 -0.1898 0.9673 +vn -0.1316 0.2475 0.9599 +vn 0.0312 0.9661 0.2562 +vn 0.1763 0.9037 0.3901 +vn -0.0133 0.9769 0.2131 +vn -0.1638 0.9846 0.0610 +vn -0.0350 0.9992 0.0202 +vn -0.0802 0.9964 -0.0273 +vn -0.0706 0.9974 -0.0171 +vn -0.1238 0.9895 -0.0743 +vn 0.1065 -0.7670 0.6328 +vn -0.4235 -0.3932 0.8162 +vn -0.0013 -0.4510 -0.8925 +vn -0.0667 -0.7384 -0.6710 +vn -0.5402 -0.8028 -0.2522 +vn 0.3959 -0.8800 0.2622 +vn -0.2357 -0.0489 0.9706 +vn -0.2880 -0.0312 0.9571 +vn -0.1341 -0.0820 0.9876 +vn -0.0952 -0.0943 0.9910 +vn -0.0250 0.9940 -0.1066 +vn -0.0039 0.9936 -0.1132 +vn 0.0944 0.9743 -0.2044 +vn 0.0688 0.9691 -0.2368 +vn 0.2436 0.9486 -0.2020 +vn 0.1691 0.9517 -0.2563 +vn -0.0562 -0.7019 0.7100 +vn -0.1153 -0.6839 0.7204 +vn 0.1605 -0.7442 0.6484 +vn 0.2118 -0.7486 0.6283 +vn -0.2875 -0.9292 -0.2324 +vn 0.2875 -0.8525 -0.4365 +vn -0.1773 -0.1063 -0.9784 +vn -0.2267 -0.1205 -0.9665 +vn 0.0659 -0.0339 -0.9973 +vn 0.1235 -0.0161 -0.9922 +vn -0.1770 0.9380 -0.2979 +vn -0.1889 0.9350 -0.3003 +vn -0.1210 0.9504 -0.2865 +vn -0.1027 0.9537 -0.2826 +vn 0.2775 0.6655 0.6929 +vn -0.5252 0.3664 0.7680 +vn 0.4301 -0.8883 -0.1612 +vn -0.1383 -0.6437 0.7526 +vn -0.0496 -0.6111 0.7900 +vn 0.1618 -0.5091 0.8454 +vn 0.2577 -0.4511 0.8544 +vn -0.2232 0.3924 0.8923 +vn 0.3150 0.6562 0.6857 +vn -0.3711 0.9251 -0.0805 +vn 0.4280 0.7351 -0.5258 +vn -0.5073 0.0320 -0.8612 +vn 0.4969 -0.2665 -0.8259 +vn 0.3858 -0.4403 -0.8107 +vn 0.4828 -0.2320 -0.8444 +vn 0.6633 0.0227 -0.7480 +vn 0.6004 -0.0432 -0.7985 +vn -0.4081 0.6122 0.6773 +vn 0.4190 0.3799 0.8247 +vn -0.4052 -0.5422 0.7361 +vn 0.2758 -0.7232 0.6332 +vn -0.2036 -0.8543 -0.4782 +vn -0.2029 -0.8544 -0.4784 +vn -0.2074 -0.8542 -0.4769 +vn -0.2090 -0.8541 -0.4763 +vn 0.3057 -0.0006 -0.9521 +vn -0.5152 0.2735 -0.8122 +vn 0.5141 0.8333 -0.2033 +vn -0.6532 0.5587 0.5110 +vn -0.9996 0.0289 0.0004 +vn -0.9974 -0.0390 0.0601 +vn -0.9983 -0.0353 -0.0474 +vn 0.9991 0.0072 0.0421 +vn 0.9978 -0.0238 0.0626 +vn 0.9984 0.0560 0.0099 +vn 0.0543 0.9984 -0.0125 +vn -0.0390 0.9234 0.3818 +vn 0.0326 0.9960 0.0827 +vn -0.0546 0.8944 0.4438 +vn 0.0998 -0.0830 0.9915 +vn -0.0386 -0.5811 0.8129 +vn 0.0393 -0.8948 -0.4447 +vn 0.0582 -0.8657 -0.4972 +vn 0.0538 -0.8727 -0.4852 +vn 0.0358 -0.9000 -0.4344 +vn 0.0069 0.3258 -0.9454 +vn 0.0096 0.3355 -0.9420 +vn 0.0091 0.3342 -0.9425 +vn 0.0062 0.3235 -0.9462 +vn 0.9675 0.0993 0.2324 +vn 0.9895 -0.0489 0.1361 +vn 0.9727 -0.2132 0.0922 +vn 0.9734 0.2088 -0.0940 +vn 0.9911 0.0513 -0.1232 +vn 0.9904 0.1294 0.0486 +vn 0.9795 -0.0657 -0.1902 +vn 0.9935 -0.1053 -0.0444 +vn 0.0478 0.8331 -0.5511 +vn 0.0772 0.8468 -0.5262 +vn 0.1931 0.8876 -0.4183 +vn -0.1994 0.7976 0.5692 +vn 0.2169 0.4458 0.8684 +vn -0.1716 -0.1733 0.9698 +vn 0.1471 -0.8920 0.4274 +vn 0.1599 -0.8955 0.4154 +vn 0.1592 -0.8953 0.4160 +vn 0.1670 -0.8973 0.4086 +vn -0.1803 -0.9354 -0.3041 +vn 0.1859 -0.3369 -0.9230 +vn 0.1053 -0.2688 -0.9574 +vn 0.0854 -0.2513 -0.9641 +vn -0.0199 -0.1582 -0.9872 +vn -0.0897 0.7508 -0.6545 +vn -0.2748 0.5431 -0.7934 +vn -0.4511 0.5487 0.7039 +vn -0.6225 0.5744 0.5316 +vn -0.5657 0.5692 0.5967 +vn -0.7387 0.5693 0.3609 +vn -0.5867 -0.8098 -0.0054 +vn 0.3134 -0.8019 -0.5086 +vn 1.0000 0.0003 0.0005 +vn 1.0000 0.0000 0.0001 +vn 1.0000 0.0002 0.0004 +vn -0.9894 -0.0624 -0.1308 +vn -0.9878 -0.0645 -0.1417 +vn -0.9924 -0.0518 -0.1118 +vn -0.9988 0.0258 -0.0424 +vn -0.9980 0.0628 -0.0098 +vn 0.9981 0.0601 -0.0134 +vn 0.9925 -0.0475 -0.1122 +vn 0.9987 0.0264 -0.0441 +vn 0.9902 -0.0565 -0.1274 +vn 0.9887 -0.0585 -0.1378 +vn -0.9878 -0.0645 -0.1418 +vn -0.9421 -0.0799 -0.3257 +vn -0.9304 -0.0273 -0.3656 +vn -0.9374 -0.0964 -0.3347 +vn -0.9786 -0.1110 -0.1730 +vn -0.9985 0.0121 -0.0540 +vn -0.9980 0.0632 -0.0093 +vn 0.0614 -0.5427 -0.8377 +vn 0.0673 -0.5418 -0.8378 +vn 0.0001 -0.5506 -0.8347 +vn -0.0062 -0.5513 -0.8343 +vn -0.0134 -0.6035 -0.7972 +vn -0.0129 -0.6036 -0.7972 +vn -0.0131 -0.6036 -0.7972 +vn -0.0134 -0.6036 -0.7972 +vn -0.9976 -0.0089 -0.0680 +vn -0.9990 -0.0161 -0.0428 +vn -0.9992 -0.0179 -0.0365 +vn -0.9955 -0.0012 -0.0948 +vn -0.9820 -0.1684 0.0856 +vn -0.9981 -0.0170 0.0587 +vn -0.9987 0.0005 0.0512 +vn -0.9792 -0.1789 0.0957 +vn -0.9825 -0.1849 0.0228 +vn -0.9819 -0.1889 0.0105 +vn -0.9996 -0.0075 -0.0272 +vn -0.9908 -0.1214 -0.0598 +vn -0.9762 -0.2149 -0.0302 +vn -0.9997 0.0016 -0.0234 +vn 1.0000 0.0000 0.0002 +vn 1.0000 0.0001 0.0001 +vn 1.0000 -0.0000 0.0004 +vn 1.0000 -0.0005 -0.0002 +vn 1.0000 0.0003 0.0001 +vn 1.0000 0.0004 0.0001 +vn 1.0000 -0.0004 0.0003 +vn 1.0000 -0.0004 0.0002 +vn 1.0000 -0.0013 0.0001 +vn 1.0000 -0.0005 -0.0001 +vn 1.0000 -0.0003 -0.0002 +vn -0.9748 -0.0112 -0.2230 +vn -0.9812 -0.0208 -0.1918 +vn -0.9827 -0.0233 -0.1836 +vn -0.9663 -0.0005 -0.2576 +vn -0.9746 -0.2113 0.0740 +vn -0.9993 -0.0102 0.0354 +vn -0.9995 0.0003 0.0308 +vn -0.9841 -0.1551 0.0865 +vn -0.9792 -0.2010 0.0279 +vn -0.9472 -0.3189 -0.0325 +vn -0.9798 -0.1596 -0.1205 +vn -0.9832 -0.1757 -0.0506 +vn -0.9699 -0.2070 -0.1284 +vn -0.9812 -0.1531 -0.1177 +vn 0.9658 -0.0237 -0.2582 +vn 0.9844 0.0000 -0.1757 +vn 0.9441 -0.0438 -0.3266 +vn 0.9373 -0.0493 -0.3451 +vn 0.9709 -0.2023 0.1282 +vn 0.9817 -0.1825 0.0538 +vn 0.9508 -0.3079 0.0342 +vn 0.9985 0.0014 0.0540 +vn 0.9979 -0.0186 0.0625 +vn 0.9746 -0.2232 -0.0194 +vn 0.9610 -0.2627 -0.0859 +vn 0.9909 -0.1125 -0.0735 +vn 0.9998 -0.0151 -0.0165 +vn -0.9823 -0.1667 0.0849 +vn -0.9902 -0.1395 0.0097 +vn -0.9906 -0.1362 0.0122 +vn -0.9858 -0.1554 -0.0640 +vn -0.9689 -0.2097 -0.1315 +vn -0.9878 -0.1464 -0.0535 +vn -0.2437 -0.9698 0.0053 +vn -0.9905 -0.1364 -0.0152 +vn 0.9784 -0.1847 -0.0924 +vn 0.9790 -0.1631 -0.1222 +vn 0.9791 -0.1627 -0.1220 +vn 0.9830 -0.1719 0.0647 +vn 0.9764 -0.2046 0.0689 +vn 0.9721 -0.2344 0.0114 +vn 0.9994 0.0025 0.0355 +vn 0.9991 -0.0113 0.0415 +vn 0.9793 -0.2005 -0.0275 +vn 0.9779 -0.1842 -0.0986 +vn -0.9377 -0.3234 0.1269 +vn -0.9985 -0.0296 0.0468 +vn -0.9994 0.0003 0.0335 +vn -0.9371 -0.3129 0.1547 +vn -0.9478 -0.3097 0.0756 +vn -0.9064 -0.4214 0.0295 +vn -0.9494 -0.3116 -0.0391 +vn -0.9987 -0.0298 -0.0417 +vn -0.9384 -0.3092 -0.1541 +vn -0.8839 -0.4448 -0.1443 +vn -0.9996 0.0020 -0.0279 +vn 0.9312 -0.3323 -0.1498 +vn 0.9746 -0.1820 -0.1301 +vn 0.9261 -0.3434 0.1565 +vn 0.9170 -0.3657 0.1593 +vn 0.8484 -0.5292 0.0114 +vn 0.9314 -0.3509 0.0964 +vn 0.9467 -0.3185 -0.0483 +vn 0.9967 -0.0386 0.0711 +vn 0.9525 -0.3038 -0.0221 +vn 0.9256 -0.3479 -0.1490 +vn -0.9871 -0.0031 -0.1601 +vn -0.9884 -0.0056 -0.1519 +vn -0.9887 -0.0062 -0.1498 +vn -0.9855 -0.0003 -0.1697 +vn -0.9999 -0.0110 0.0062 +vn -0.9862 -0.1609 0.0400 +vn -0.9765 -0.2154 -0.0067 +vn -0.9993 -0.0345 -0.0133 +vn -0.9998 0.0113 -0.0151 +vn 0.9604 -0.2638 -0.0895 +vn 0.9993 -0.0084 -0.0369 +vn 0.9995 0.0038 -0.0316 +vn 0.9696 -0.2118 0.1224 +vn 0.9742 -0.2175 0.0599 +vn 0.9534 -0.3003 0.0306 +vn 0.9987 0.0035 0.0503 +vn 0.9981 -0.0159 0.0589 +vn 0.9761 -0.2160 -0.0240 +vn 0.9823 -0.1627 -0.0925 +vn -0.9958 0.0055 -0.0912 +vn -0.9940 0.0107 -0.1089 +vn -0.9935 0.0120 -0.1134 +vn -0.9974 -0.0003 -0.0715 +vn -0.9676 -0.2521 -0.0167 +vn -0.9995 -0.0086 -0.0312 +vn -0.9882 -0.1391 -0.0644 +vn -0.9620 -0.2723 -0.0213 +vn -0.9996 0.0019 -0.0268 +vn 0.9955 0.0239 -0.0922 +vn 0.9989 0.0454 -0.0151 +vn 0.9987 0.0509 0.0043 +vn 1.0000 -0.0078 -0.0040 +vn 1.0000 -0.0051 0.0054 +vn 0.9968 -0.0721 0.0347 +vn 0.9539 -0.2987 0.0304 +vn 0.9929 -0.1157 -0.0278 +vn -0.9854 -0.0036 -0.1701 +vn -0.9872 -0.0068 -0.1591 +vn -0.9877 -0.0076 -0.1564 +vn -0.9835 -0.0004 -0.1809 +vn -1.0000 -0.0057 0.0000 +vn -0.9997 -0.0059 -0.0224 +vn -0.9940 -0.0991 -0.0467 +vn -0.9681 -0.2504 -0.0089 +vn -0.9998 0.0019 -0.0192 +vn 0.9845 0.0002 -0.1755 +vn 0.9844 0.0000 -0.1759 +vn 1.0000 -0.0059 0.0012 +vn 0.9911 -0.1332 -0.0014 +vn 0.9705 -0.2296 -0.0734 +vn 0.9918 -0.1076 -0.0691 +vn 0.9998 -0.0138 -0.0151 +vn -0.0311 -0.8075 -0.5891 +vn 0.0063 -0.8030 -0.5960 +vn -0.2379 -0.8106 -0.5351 +vn -0.2576 -0.8089 -0.5284 +vn 0.4393 -0.8523 -0.2841 +vn -0.5036 -0.8586 -0.0957 +vn 0.5036 -0.8586 0.0957 +vn -0.4393 -0.8523 0.2841 +vn 0.2374 -0.8107 0.5351 +vn 0.2573 -0.8090 0.5285 +vn 0.0311 -0.8075 0.5891 +vn -0.0063 -0.8030 0.5960 +vn 0.0139 -0.8029 -0.5959 +vn -0.5054 -0.7224 -0.4719 +vn 0.7324 -0.6459 -0.2153 +vn -0.7886 -0.6111 -0.0681 +vn 0.7886 -0.6111 0.0681 +vn -0.7324 -0.6459 0.2153 +vn 0.5055 -0.7224 0.4719 +vn -0.0139 -0.8029 0.5959 +vn -0.5052 -0.7225 -0.4720 +vn 0.5056 -0.7223 0.4719 +vn 0.0140 -0.8079 -0.5891 +vn -0.0140 -0.8079 0.5891 +vn 0.0143 -0.8031 -0.5957 +vn 0.7326 -0.6457 -0.2152 +vn 0.5055 -0.7223 0.4719 +vn -0.5056 -0.7223 -0.4719 +vn 0.5054 -0.7224 0.4719 +vn -0.5055 -0.7224 -0.4719 +vn 0.5057 -0.7223 0.4718 +vn 0.0172 0.0054 -0.9998 +vn 0.0305 0.0107 -0.9995 +vn -0.0038 -0.2210 -0.9753 +vn -0.0143 -0.2419 -0.9702 +vn -0.0053 -0.9597 -0.2809 +vn -0.0080 -0.9435 -0.3313 +vn -0.0174 -0.9739 -0.2264 +vn -0.0244 -0.8376 -0.5457 +vn -0.0257 -0.7462 -0.6653 +vn -0.0144 -0.9220 -0.3869 +vn 0.0020 -0.7759 -0.6308 +vn -0.0008 -0.6925 -0.7215 +vn -1.0000 0.0084 0.0030 +vn -0.9877 -0.0526 0.1475 +vn -0.9917 -0.0661 0.1104 +vn -0.9879 -0.0270 0.1526 +vn -0.9626 0.0314 0.2690 +vn -0.9995 0.0236 0.0186 +vn -0.9996 -0.0293 0.0062 +vn -0.9994 -0.0327 0.0140 +vn 0.9999 0.0116 0.0089 +vn 1.0000 -0.0001 -0.0003 +vn 0.9974 0.0568 0.0438 +vn 0.9966 0.0653 0.0504 +vn 0.8573 0.0511 0.5123 +vn 0.8315 0.0615 0.5521 +vn 0.9934 -0.0420 0.1068 +vn 0.9999 -0.0060 0.0113 +vn 1.0000 -0.0003 0.0003 +vn 1.0000 -0.0001 0.0001 +vn 1.0000 -0.0002 0.0002 +vn -0.0055 -0.5940 0.8044 +vn 0.0057 -0.5960 0.8030 +vn -0.0132 -0.4985 0.8668 +vn 0.0289 -0.4079 0.9126 +vn -0.0275 -0.1651 0.9859 +vn 0.0493 -0.0161 0.9987 +vn -0.1476 0.1393 0.9792 +vn -0.1619 0.1404 0.9768 +vn 0.1271 0.5437 0.8296 +vn 0.1368 0.5418 0.8293 +vn 0.0061 0.5631 0.8264 +vn -0.0076 0.5647 0.8252 +vn -0.9845 0.1073 0.1385 +vn -0.9848 0.1067 0.1371 +vn -0.9770 0.0887 0.1938 +vn -0.9254 -0.1241 0.3581 +vn -0.9387 -0.1499 0.3103 +vn -0.9534 -0.0524 0.2972 +vn -0.9043 0.0256 0.4262 +vn -0.9669 0.0774 0.2432 +vn -0.9800 0.1023 0.1707 +vn -0.9995 -0.0295 0.0067 +vn -0.9986 -0.0412 0.0332 +vn 0.9808 0.1157 0.1572 +vn 0.9780 0.0948 0.1857 +vn 0.9811 0.1151 0.1558 +vn 0.9782 0.0973 0.1833 +vn 0.9681 0.0777 0.2381 +vn 0.9031 0.0275 0.4285 +vn 0.9445 -0.0452 0.3253 +vn 0.8804 -0.1679 0.4436 +vn 0.9402 -0.1875 0.2845 +vn 0.8533 -0.2912 0.4326 +vn 0.9988 0.0490 0.0076 +vn 0.0129 -0.5891 0.8079 +vn -0.9998 0.0085 0.0193 +vn -0.9774 0.0753 0.1977 +vn -0.9255 -0.1240 0.3578 +vn -0.9389 -0.1498 0.3100 +vn -0.9757 0.0841 0.2024 +vn -0.9986 -0.0410 0.0329 +vn 0.9997 0.0089 0.0206 +vn 0.9800 0.0725 0.1853 +vn 0.9776 0.0776 0.1956 +vn 0.8802 -0.1680 0.4439 +vn 0.8108 -0.3492 0.4697 +vn -0.0175 0.5892 0.8078 +vn -0.9998 0.0080 0.0181 +vn -0.9777 0.0748 0.1964 +vn 0.0129 -0.5892 0.8079 +vn -0.0182 0.5892 0.8078 +vn -0.9188 -0.1298 0.3729 +vn -0.9633 -0.1295 0.2353 +vn -0.9614 -0.1321 0.2413 +vn 0.6430 -0.5151 0.5667 +vn -0.0177 0.5892 0.8078 +vn -0.9998 0.0084 0.0190 +vn -0.9775 0.0751 0.1973 +vn 0.8812 -0.1605 0.4447 +vn 0.9303 -0.1882 0.3148 +vn 0.9812 -0.0839 0.1736 +vn 0.9888 -0.0491 0.1411 +vn -0.9816 0.1132 0.1535 +vn -0.9816 0.1134 0.1539 +vn -0.9765 0.0899 0.1961 +vn -0.9865 -0.0629 0.1512 +vn -0.9858 -0.0636 0.1557 +vn -0.9703 -0.0748 0.2299 +vn -0.9628 -0.0623 0.2630 +vn -0.8920 0.0337 0.4508 +vn -0.9559 0.0935 0.2785 +vn -0.9805 0.1010 0.1684 +vn 0.8193 -0.3433 0.4593 +vn -0.5096 -0.5253 0.6814 +vn 0.0194 -0.9998 -0.0101 +vn -0.0122 -0.9939 0.1098 +vn 0.0073 -0.9386 0.3449 +vn -0.0057 -0.9148 0.4040 +vn -0.0045 -0.8434 0.5373 +vn -0.0179 -0.9716 0.2358 +vn 0.4632 -0.8590 0.2180 +vn 0.1981 -0.9501 0.2411 +vn 0.3484 -0.9086 0.2304 +vn 0.5199 -0.6597 0.5426 +vn -0.7607 -0.5612 0.3261 +vn -0.8804 -0.2406 0.4086 +vn 0.6169 -0.3022 0.7267 +vn -0.6364 -0.0744 0.7678 +vn 0.6040 0.1710 0.7784 +vn -0.5693 0.4378 0.6959 +vn 0.4360 0.6500 0.6224 +vn 0.3570 0.5540 0.7521 +vn 0.4007 0.6074 0.6859 +vn 0.6936 0.6822 0.2314 +vn -0.7589 0.5610 0.3307 +vn 0.4709 0.6908 0.5487 +vn -0.6521 0.7572 0.0384 +vn 0.6542 0.6522 -0.3830 +vn -0.6255 0.7363 -0.2581 +vn 0.6808 0.7293 -0.0689 +vn -0.1854 0.6991 -0.6906 +vn -0.4883 0.6482 -0.5842 +vn -0.4196 0.6804 -0.6008 +vn -0.6294 0.5991 -0.4949 +vn 0.3509 0.4516 -0.8203 +vn -0.0781 0.0074 -0.9969 +vn -0.2075 0.1519 -0.9664 +vn -0.3162 0.1547 -0.9360 +vn -0.5878 -0.1482 -0.7953 +vn 0.5402 -0.0414 -0.8405 +vn 0.7101 -0.3405 -0.6162 +vn -0.1079 -0.7487 -0.6540 +vn -0.0958 -0.7450 -0.6602 +vn -0.1850 -0.7355 -0.6518 +vn -0.7247 -0.4662 -0.5074 +vn 0.7032 -0.6668 0.2466 +vn -0.6490 -0.7601 -0.0322 +vn 0.9456 -0.3173 -0.0712 +vn 0.9482 -0.2801 -0.1500 +vn 0.8028 -0.5259 -0.2810 +vn 0.3767 -0.7225 0.5798 +vn 0.4369 -0.6778 0.5914 +vn -0.2898 0.2355 0.9276 +vn 0.2397 0.5833 0.7761 +vn 0.2366 0.5839 0.7766 +vn 0.0806 0.6340 0.7691 +vn 0.1926 0.6157 0.7641 +vn 0.0425 0.6072 0.7934 +vn 0.3737 0.7836 0.4962 +vn -0.0461 0.9918 0.1191 +vn -0.0613 0.8363 -0.5449 +vn -0.0253 0.7488 -0.6623 +vn -0.0074 0.7455 -0.6665 +vn 0.0086 0.6413 -0.7672 +vn -0.0430 0.6298 -0.7755 +vn 0.1554 0.1305 -0.9792 +vn 0.0627 0.2066 -0.9764 +vn 0.0650 0.1000 -0.9929 +vn -0.0297 0.0778 -0.9965 +vn 0.4080 -0.0407 -0.9121 +vn 0.4222 -0.0419 -0.9056 +vn -0.4879 -0.3679 -0.7916 +vn 0.1085 -0.6436 -0.7576 +vn 0.2628 -0.4389 -0.8593 +vn 0.0753 -0.6936 -0.7164 +vn 0.1304 -0.8049 -0.5788 +vn 0.1213 -0.7957 -0.5934 +vn 0.3808 -0.7266 0.5719 +vn -0.8252 -0.4921 0.2772 +vn 0.7833 -0.6007 0.1598 +vn -0.8475 -0.5296 -0.0358 +vn 0.2590 -0.8376 -0.4810 +vn -0.0900 -0.7568 0.6474 +vn -0.3089 -0.7360 0.6024 +vn -0.1974 -0.7387 0.6445 +vn 0.2665 0.5914 0.7610 +vn 0.2572 0.5935 0.7626 +vn 0.4345 0.6291 0.6446 +vn 0.4966 0.5302 0.6872 +vn 0.4726 0.6756 0.5659 +vn 0.5041 0.6888 0.5210 +vn 0.3126 0.7256 -0.6130 +vn 0.4959 0.7120 -0.4972 +vn 0.1878 0.6392 -0.7458 +vn 0.1464 0.6072 -0.7810 +vn 0.2095 0.3155 -0.9255 +vn 0.0542 0.2143 -0.9753 +vn -0.0099 0.2295 -0.9733 +vn 0.4135 -0.0362 -0.9098 +vn 0.4316 -0.0374 -0.9013 +vn 0.1155 -0.6622 -0.7404 +vn 0.0610 -0.7049 -0.7067 +vn 0.0285 -0.8110 -0.5844 +vn 0.0067 -0.8010 -0.5986 +vn -0.3617 -0.7325 0.5767 +vn 0.7391 -0.5831 0.3371 +vn -0.7817 -0.6043 0.1545 +vn 0.5201 -0.8465 -0.1140 +vn 0.0467 -0.8506 -0.5238 +vn 0.0476 -0.8506 -0.5237 +vn 0.2799 -0.7335 0.6194 +vn 0.4425 -0.6829 0.5813 +vn 0.4963 0.5304 0.6873 +vn 0.4219 0.7286 -0.5395 +vn 0.1715 0.6427 -0.7467 +vn 0.3296 0.7344 -0.5932 +vn 0.1106 0.6013 -0.7913 +vn 0.2067 0.3277 -0.9219 +vn 0.0707 0.2294 -0.9708 +vn 0.0020 0.3599 -0.9330 +vn 0.4528 -0.0270 -0.8912 +vn 0.2626 -0.4389 -0.8593 +vn 0.0282 -0.8103 -0.5853 +vn 0.0338 -0.8049 -0.5925 +vn 0.3958 -0.7417 0.5415 +vn 0.0586 -0.8495 -0.5244 +vn 0.2279 -0.7643 0.6032 +vn 0.2322 -0.7751 0.5876 +vn 0.0923 -0.7954 0.5990 +vn 0.0000 -0.8076 0.5897 +vn 0.7186 -0.3993 0.5694 +vn 0.2276 0.5794 0.7826 +vn 0.2272 0.5795 0.7827 +vn 0.2377 0.6516 0.7203 +vn 0.2158 0.6079 0.7641 +vn 0.4399 0.7016 0.5606 +vn 0.4815 0.6999 0.5275 +vn 0.1711 0.6427 -0.7468 +vn 0.3297 0.7344 -0.5932 +vn 0.1103 0.6016 -0.7912 +vn 0.2070 0.3280 -0.9217 +vn 0.0001 0.3637 -0.9315 +vn -0.4882 -0.3679 -0.7914 +vn 0.1175 -0.6669 -0.7358 +vn 0.0567 -0.7095 -0.7024 +vn 0.0260 -0.8069 -0.5902 +vn 0.3549 -0.7603 0.5441 +vn 0.4088 -0.7068 0.5773 +vn -0.0999 0.8150 -0.5707 +vn -0.0308 0.7573 -0.6523 +vn -0.0844 0.7440 -0.6628 +vn -0.0996 0.6319 -0.7686 +vn 0.0103 0.6233 -0.7819 +vn 0.1986 0.3217 -0.9258 +vn 0.0686 0.2264 -0.9716 +vn 0.1169 -0.6695 -0.7336 +vn -0.0756 -0.7867 -0.6127 +vn 0.3710 -0.7773 0.5081 +vn 0.0295 -0.8073 0.5894 +vn 0.1055 -0.7944 0.5981 +vn 0.2337 0.6512 0.7221 +vn 0.2155 0.6080 0.7642 +vn 0.4067 0.7015 0.5852 +vn 0.4441 0.7017 0.5571 +vn -0.4508 0.7481 0.4870 +vn 0.7246 0.6526 0.2213 +vn -0.7223 0.6855 0.0912 +vn 0.7271 0.6821 -0.0773 +vn -0.6300 0.7517 -0.1950 +vn 0.4857 0.7177 -0.4990 +vn -0.2412 0.7666 -0.5951 +vn -0.2604 0.6398 -0.7231 +vn -0.2586 0.6553 -0.7097 +vn -0.2702 0.5113 -0.8158 +vn 0.2069 0.3257 -0.9226 +vn 0.3865 0.4637 -0.7972 +vn -0.0229 0.1493 -0.9885 +vn -0.0113 0.3814 -0.9243 +vn 0.1087 -0.6497 -0.7524 +vn 0.1089 -0.6898 -0.7158 +vn 0.1125 -0.8076 -0.5788 +vn 0.1341 -0.7951 -0.5914 +vn 0.2597 -0.8385 -0.4791 +vn 0.0085 0.9958 0.0912 +vn -0.5286 0.8061 0.2662 +vn -0.5136 0.8154 0.2671 +vn -0.2037 -0.7840 -0.5864 +vn -0.3072 -0.7735 -0.5544 +vn 0.3192 -0.8786 -0.3552 +vn -0.0106 -0.5334 0.8458 +vn -0.0247 -0.2279 0.9734 +vn -0.0135 -0.3733 0.9276 +vn 0.0059 -0.3461 0.9382 +vn -0.0111 -0.0211 0.9997 +vn -0.0012 -0.0492 0.9988 +vn 0.0063 0.3034 0.9528 +vn 0.0063 0.3337 0.9426 +vn -0.0226 0.2406 0.9704 +vn -0.0091 0.5359 0.8442 +vn 0.0139 0.2120 -0.9772 +vn 0.0117 -0.3043 -0.9525 +vn 0.0030 0.2945 -0.9557 +vn 0.0037 -0.2033 -0.9791 +vn -0.0007 -0.6336 0.7736 +vn -0.0010 -0.6331 0.7740 +vn -0.0009 -0.6334 0.7738 +vn -0.0005 -0.6339 0.7734 +vn 0.0954 -0.9835 -0.1535 +vn 0.5799 -0.7897 0.2003 +vn -0.3577 -0.7185 0.5965 +vn 0.2247 0.0685 0.9720 +vn 0.1641 0.0513 0.9851 +vn 0.0421 0.0165 0.9990 +vn 0.0011 0.0049 1.0000 +vn -0.0378 -0.9898 -0.1376 +vn 0.5023 -0.8460 0.1787 +vn -0.2250 -0.7573 0.6131 +vn 0.0571 0.0253 0.9980 +vn 0.0441 0.0216 0.9988 +vn 0.0110 0.0122 0.9999 +vn 0.0009 0.0092 1.0000 +vn -0.0387 -0.9873 -0.1539 +vn -0.0133 -0.9896 -0.1433 +vn 0.0138 -0.9912 -0.1319 +vn 0.0308 -0.9917 -0.1247 +vn -0.2160 0.0687 0.9740 +vn -0.1730 0.0876 0.9810 +vn -0.0521 0.1385 0.9890 +vn 0.0039 0.1612 0.9869 +vn 0.6240 -0.7645 0.1615 +vn -0.2362 -0.7848 0.5730 +vn -0.3694 -0.7149 0.5936 +vn 0.2109 0.0688 0.9751 +vn 0.1536 0.0526 0.9867 +vn 0.0393 0.0203 0.9990 +vn 0.6393 -0.7499 0.1701 +vn -0.1839 -0.7939 0.5796 +vn 0.0546 0.0253 0.9982 +vn 0.0430 0.0220 0.9988 +vn 0.0107 0.0127 0.9999 +vn 0.0008 0.0096 1.0000 +vn -0.0176 -0.9885 -0.1500 +vn 0.1677 -0.9856 0.0216 +vn 0.2337 -0.9686 0.0850 +vn 0.3444 -0.9186 0.1940 +vn -0.2148 -0.7824 0.5845 +vn -0.1094 -0.7963 0.5949 +vn -0.3313 -0.7537 0.5675 +vn 0.0260 0.0252 0.9993 +vn 0.0158 0.0190 0.9997 +vn 0.0095 0.0151 0.9998 +vn 0.0005 0.0091 1.0000 +vn -0.0039 0.1612 -0.9869 +vn 0.0362 0.1445 -0.9888 +vn 0.1222 0.1093 -0.9865 +vn 0.1559 0.0950 -0.9832 +vn 0.1530 -0.9646 0.2147 +vn 0.1027 -0.9755 0.1948 +vn 0.0376 -0.9849 0.1689 +vn -0.0030 -0.9884 0.1516 +vn -0.0032 0.1201 -0.9928 +vn 0.0278 0.1088 -0.9937 +vn 0.1045 0.0802 -0.9913 +vn 0.1321 0.0698 -0.9888 +vn 0.1446 -0.9658 0.2150 +vn 0.0976 -0.9757 0.1961 +vn 0.0362 -0.9846 0.1710 +vn -0.0027 -0.9880 0.1546 +vn 0.1043 0.0803 -0.9913 +vn 0.1322 0.0698 -0.9888 +vn -0.0024 0.0789 -0.9969 +vn 0.0028 0.0762 -0.9971 +vn 0.0108 0.0721 -0.9973 +vn 0.0146 0.0702 -0.9974 +vn 0.1447 -0.9658 0.2150 +vn 0.0978 -0.9757 0.1959 +vn 0.0360 -0.9847 0.1705 +vn -0.0029 -0.9881 0.1541 +vn -0.0015 0.0785 -0.9969 +vn -0.0005 0.0779 -0.9970 +vn 0.0000 0.0777 -0.9970 +vn 0.1449 -0.9658 0.2150 +vn -0.0028 -0.9880 0.1544 +vn 0.0436 0.1420 -0.9889 +vn 0.1133 0.1131 -0.9871 +vn 0.1429 0.1005 -0.9846 +vn -0.0014 0.1155 -0.9933 +vn 0.0232 0.0960 -0.9951 +vn 0.0320 0.0890 -0.9955 +vn 0.0557 0.0701 -0.9960 +vn -0.0840 -0.7812 -0.6186 +vn 0.0930 -0.9661 0.2409 +vn 0.0421 -0.9800 0.1943 +vn 0.0446 -0.9795 0.1967 +vn -0.0013 -0.9880 0.1546 +vn -0.4471 0.0590 -0.8925 +vn 0.1951 -0.5168 -0.8336 +vn -0.6274 0.0666 -0.7758 +vn 0.5919 -0.3886 -0.7061 +vn 0.5917 -0.3887 -0.7063 +vn -0.6277 0.0666 -0.7756 +vn -0.0157 0.1406 -0.9899 +vn -0.0165 0.1410 -0.9899 +vn -0.0201 0.1420 -0.9897 +vn -0.0214 0.1424 -0.9896 +vn 0.0607 -0.4542 -0.8888 +vn 0.0497 -0.4517 -0.8908 +vn -0.0177 -0.0295 0.9994 +vn -0.0050 -0.0175 0.9998 +vn 0.0149 -0.9994 0.0318 +vn 0.0078 -0.9997 0.0248 +vn 0.0021 -0.6155 -0.7881 +vn 0.0114 -0.6230 -0.7821 +vn 0.0043 -0.9979 -0.0648 +vn -0.0077 -0.9972 -0.0749 +vn -0.7414 -0.0391 0.6699 +vn -0.7908 -0.2673 -0.5507 +vn 0.0006 0.9879 0.1551 +vn 0.0718 0.9972 -0.0213 +vn -0.6519 0.6738 -0.3478 +vn 0.2281 0.8309 0.5076 +vn -0.5384 -0.0309 -0.8421 +vn 0.0776 0.6913 0.7184 +vn 0.0942 0.6762 0.7307 +vn -0.2355 0.7744 0.5872 +vn -0.2951 0.7774 0.5555 +vn 0.1818 0.6995 -0.6911 +vn -0.4229 -0.7163 0.5550 +vn -0.4252 -0.7179 0.5512 +vn -0.4502 -0.8614 0.2352 +vn 0.0088 -0.9997 0.0242 +vn -0.1888 -0.9625 0.1949 +vn -0.6903 -0.7128 -0.1243 +vn -0.3950 0.2521 0.8834 +vn 0.3115 0.4640 0.8292 +vn 0.1660 0.6705 0.7231 +vn -0.3552 0.5605 -0.7482 +vn 0.4408 -0.5201 0.7316 +vn -0.6219 0.2604 -0.7385 +vn 0.4367 0.4041 -0.8037 +vn 0.1749 0.0357 -0.9839 +vn 0.1675 -0.2969 -0.9401 +vn 0.6481 -0.4849 -0.5872 +vn 0.1035 -0.8528 -0.5119 +vn 0.3935 -0.8694 -0.2988 +vn 0.0996 -0.9933 -0.0582 +vn -0.4932 -0.8402 0.2255 +vn 0.3432 -0.7888 0.5098 +vn -0.3707 0.5480 0.7498 +vn 0.2009 0.9309 -0.3049 +vn 0.3248 -0.2253 0.9186 +vn -0.4800 0.8745 -0.0696 +vn -0.5417 -0.4203 0.7279 +vn -0.1250 0.8491 -0.5133 +vn 0.7481 0.3989 -0.5303 +vn -0.9991 -0.0371 -0.0202 +vn -0.9990 -0.0307 -0.0321 +vn -0.9990 -0.0344 -0.0277 +vn -0.9999 0.0048 -0.0122 +vn -0.9885 0.0553 -0.1406 +vn -0.9833 0.0665 -0.1692 +vn 0.9785 0.0761 -0.1918 +vn 0.9999 0.0058 -0.0147 +vn 0.9662 0.0951 -0.2396 +vn -0.9882 0.0803 -0.1304 +vn -0.9894 0.0733 -0.1257 +vn -0.9883 0.0742 -0.1335 +vn -0.9874 0.0755 -0.1392 +vn -0.9873 0.0851 -0.1342 +vn 0.9771 0.0879 -0.1939 +vn 0.9884 0.0788 -0.1298 +vn 0.9761 0.1364 -0.1691 +vn 0.9675 0.0974 -0.2332 +vn 0.9669 0.1669 -0.1930 +vn -0.9873 0.0849 -0.1340 +vn -0.9873 0.0755 -0.1396 +vn 0.9773 0.0782 -0.1969 +vn 0.9999 0.0061 -0.0153 +vn -0.9999 0.0157 0.0024 +vn -0.9996 0.0234 -0.0170 +vn -0.9692 0.1048 -0.2229 +vn -0.9571 0.1208 -0.2635 +vn 0.1094 0.5437 -0.8321 +vn 0.1462 0.5454 -0.8253 +vn -0.2766 0.4807 -0.8321 +vn -0.3061 0.4724 -0.8265 +vn -0.2313 0.4743 -0.8494 +vn -0.2310 0.4744 -0.8495 +vn 1.0000 -0.0003 0.0000 +vn 1.0000 0.0003 -0.0001 +vn -0.9809 0.1633 0.1055 +vn -0.9989 0.0009 0.0466 +vn -0.9984 0.0174 0.0534 +vn -0.9829 0.1745 0.0583 +vn -0.9558 0.2928 0.0276 +vn -0.9793 0.2025 -0.0078 +vn -0.9701 0.2414 -0.0259 +vn -0.9677 0.2172 -0.1281 +vn -0.9625 0.2324 -0.1398 +vn -0.9986 0.0359 -0.0392 +vn -0.9985 0.0146 0.0532 +vn -0.9967 0.0458 0.0664 +vn -0.9420 0.3025 0.1457 +vn -0.9412 0.3076 -0.1397 +vn -0.9960 0.0501 -0.0744 +vn -0.9979 0.0201 -0.0618 +vn -0.9329 0.3274 0.1501 +vn -0.9291 0.3613 0.0795 +vn -0.9286 0.3632 0.0764 +vn -0.9289 0.3675 -0.0464 +vn -0.9293 0.3669 -0.0424 +vn -0.9334 0.3297 -0.1418 +vn 0.9967 0.0350 0.0732 +vn 0.9984 -0.0069 0.0560 +vn 0.9346 0.3216 0.1522 +vn 0.9521 0.2799 -0.1229 +vn 0.9995 -0.0037 -0.0327 +vn 0.9984 0.0312 -0.0471 +vn 0.9447 0.3010 -0.1300 +vn 0.9297 0.3654 -0.0456 +vn 0.9289 0.3678 -0.0426 +vn 0.9286 0.3631 0.0772 +vn 0.9286 0.3636 0.0740 +vn 0.9257 0.3450 0.1552 +vn -0.9411 0.3078 -0.1399 +vn -0.9428 0.3013 0.1427 +vn -0.9974 0.0373 0.0615 +vn -0.9329 0.3281 0.1481 +vn -0.9335 0.3293 -0.1418 +vn 0.9349 0.3242 -0.1445 +vn 0.9987 -0.0057 -0.0502 +vn 0.9971 0.0361 -0.0673 +vn 0.9261 0.3472 -0.1479 +vn 0.9289 0.3676 -0.0461 +vn 0.9286 0.3630 0.0771 +vn -0.9332 0.3384 -0.1214 +vn -0.9983 0.0359 -0.0469 +vn -0.9993 0.0118 -0.0361 +vn -0.9431 0.3028 0.1376 +vn -0.9345 0.3266 0.1418 +vn -0.9341 0.3524 0.0574 +vn -0.9412 0.3274 0.0837 +vn -0.9151 0.4017 -0.0357 +vn -0.9099 0.4095 -0.0664 +vn -0.9444 0.2952 -0.1445 +vn 0.9348 0.3245 -0.1447 +vn -0.9998 -0.0006 0.0175 +vn -0.9672 0.2328 0.1015 +vn -0.9724 0.2139 0.0933 +vn -0.9993 0.0343 0.0122 +vn -0.9811 0.1932 -0.0072 +vn -0.9701 0.2414 -0.0260 +vn -0.9720 0.2156 -0.0937 +vn -0.9766 0.1790 -0.1191 +vn -0.9992 0.0266 -0.0290 +vn 0.9978 0.0150 0.0651 +vn 0.9780 0.1861 0.0946 +vn 0.9728 0.2031 -0.1118 +vn 0.9988 -0.0059 -0.0483 +vn 0.9983 0.0139 -0.0570 +vn 0.9748 0.2160 -0.0564 +vn 0.9716 0.2350 -0.0263 +vn 0.9706 0.2401 0.0153 +vn 0.9691 0.2377 0.0662 +vn 0.9670 0.2287 0.1125 +vn -1.0000 -0.0001 0.0000 +vn -1.0000 -0.0003 0.0002 +vn -1.0000 -0.0004 0.0003 +vn 0.9915 0.1183 0.0540 +vn 0.9895 0.1316 0.0600 +vn 0.9999 0.0114 0.0054 +vn 0.9885 0.1297 -0.0784 +vn 0.9995 -0.0040 -0.0324 +vn 0.9992 0.0094 -0.0381 +vn 0.9857 0.1597 -0.0541 +vn 0.9436 0.3292 -0.0353 +vn 0.9943 0.1041 0.0226 +vn -0.0680 0.8241 0.5623 +vn -0.0601 0.8239 0.5635 +vn -0.1371 0.8240 0.5497 +vn -0.1427 0.8238 0.5486 +vn 0.1476 0.9792 0.1393 +vn 0.1619 0.9768 0.1404 +vn -0.0493 0.9987 -0.0161 +vn 0.0276 0.9859 -0.1651 +vn -0.0290 0.9126 -0.4079 +vn 0.0093 0.8664 -0.4992 +vn -0.0422 0.7976 -0.6017 +vn -0.0614 0.7942 -0.6045 +vn 0.0139 0.8029 0.5959 +vn -0.5057 0.7222 0.4718 +vn 0.7324 0.6459 0.2153 +vn -0.7886 0.6111 0.0681 +vn 0.7886 0.6111 -0.0681 +vn -0.7324 0.6459 -0.2153 +vn 0.5057 0.7223 -0.4718 +vn -0.0125 0.8029 -0.5959 +vn -0.1344 0.7969 0.5890 +vn -0.1338 0.7972 -0.5886 +vn 0.0136 0.8080 0.5891 +vn -0.1337 0.7973 -0.5886 +vn -0.1334 0.7973 -0.5886 +vn 0.0137 0.8029 0.5959 +vn 0.5057 0.7222 -0.4718 +vn -0.0137 0.8030 -0.5959 +vn -0.1644 0.7939 0.5854 +vn -0.1342 0.7957 0.5906 +vn -0.5287 0.7055 0.4719 +vn -0.5413 0.6998 0.4660 +vn -0.0158 0.9390 -0.3436 +vn -0.0307 0.9686 -0.2468 +vn -0.0299 0.9841 -0.1750 +vn 0.0194 0.9684 -0.2488 +vn -0.0139 0.9235 -0.3833 +vn -0.0048 0.7415 -0.6710 +vn -0.0025 0.7492 -0.6623 +vn 0.0090 0.6989 -0.7152 +vn -0.0063 0.8400 0.5426 +vn -0.0231 0.9703 0.2408 +vn -0.0153 0.9291 0.3696 +vn 0.0007 0.9054 0.4245 +vn 0.0029 0.9811 0.1932 +vn 0.0107 0.9946 0.1033 +vn 0.0172 0.9980 -0.0616 +vn 0.0032 0.8876 0.4606 +vn -0.0447 0.9657 0.2559 +vn -0.0629 0.7929 0.6061 +vn 0.0476 0.5990 0.7993 +vn -0.1287 -0.1487 0.9805 +vn 0.5246 0.2246 0.8212 +vn -0.1680 0.6724 0.7208 +vn 0.3629 0.9315 -0.0249 +vn 0.0029 -0.1229 0.9924 +vn -0.0027 -0.1252 0.9921 +vn -0.0104 -0.1279 0.9917 +vn -0.0142 -0.1296 0.9915 +vn -0.0566 0.6021 0.7964 +vn -0.2412 0.6599 0.7116 +vn 0.3510 0.9355 0.0409 +vn 0.4134 0.9082 0.0655 +vn 0.0797 0.9950 -0.0607 +vn -0.0237 0.9950 -0.0972 +vn 0.0901 -0.0895 0.9919 +vn 0.3018 -0.0041 0.9534 +vn 0.3537 0.0179 0.9352 +vn -0.3798 0.6290 0.6784 +vn 0.6011 0.7863 0.1430 +vn -0.0234 0.9950 -0.0973 +vn 0.0905 -0.0896 0.9919 +vn 0.3016 -0.0039 0.9534 +vn 0.3535 0.0182 0.9352 +vn -0.1313 -0.1219 0.9838 +vn 0.6463 0.2016 0.7360 +vn -0.1686 0.6702 0.7228 +vn 0.2769 0.9608 0.0126 +vn 0.3328 0.9424 0.0338 +vn 0.0578 0.9960 -0.0686 +vn 0.6842 0.7277 0.0486 +vn -0.0599 -0.1220 0.9907 +vn 0.3597 0.2465 0.8999 +vn -0.0729 0.6763 0.7330 +vn 0.0973 0.9952 -0.0123 +vn 0.1579 0.9868 0.0354 +vn 0.0605 0.9974 -0.0404 +vn -0.0106 0.9953 -0.0960 +vn 0.0900 0.9938 0.0657 +vn 0.0557 0.9955 0.0769 +vn -0.0643 0.9912 0.1153 +vn -0.1151 0.9847 0.1310 +vn -0.0527 -0.1214 -0.9912 +vn -0.0413 -0.1261 -0.9912 +vn -0.0152 -0.1366 -0.9905 +vn -0.0025 -0.1413 -0.9900 +vn 0.0680 0.9950 0.0729 +vn -0.0130 0.9950 0.0991 +vn -0.0414 0.9933 0.1080 +vn -0.0519 -0.1211 -0.9913 +vn -0.0406 -0.1260 -0.9912 +vn -0.0150 -0.1363 -0.9906 +vn -0.0026 -0.1411 -0.9900 +vn 0.3796 0.9250 0.0158 +vn -0.0766 0.6913 -0.7185 +vn 0.6897 0.2243 -0.6885 +vn -0.1152 -0.1127 -0.9869 +vn -0.0763 0.6913 -0.7185 +vn -0.1149 -0.1128 -0.9870 +vn -0.1151 -0.1126 -0.9869 +vn -0.1151 -0.1126 -0.9870 +vn 0.0650 0.9978 -0.0156 +vn 0.0001 1.0000 0.0013 +vn -0.2560 0.9643 0.0678 +vn -0.3807 0.9193 0.1001 +vn 0.3974 0.6412 -0.6565 +vn -0.6562 0.1712 -0.7349 +vn 0.0383 -0.1410 -0.9893 +vn -0.0740 0.9907 0.1143 +vn 0.0307 0.9986 0.0425 +vn 0.0818 0.9966 0.0076 +vn 0.1628 0.9855 -0.0488 +vn -0.0387 0.6009 -0.7984 +vn 0.3756 0.2872 -0.8812 +vn -0.0470 -0.2376 -0.9702 +vn -0.2248 0.6000 -0.7678 +vn 0.0409 -0.3031 -0.9521 +vn 0.1367 -0.2848 -0.9488 +vn -0.0133 0.6052 -0.7960 +vn 0.0000 0.6024 -0.7982 +vn 0.1370 -0.2848 -0.9487 +vn -0.0032 0.5807 -0.8141 +vn -0.0190 0.5863 -0.8099 +vn -0.0847 0.3483 -0.9335 +vn -0.4068 -0.0345 -0.9129 +vn 0.1158 -0.2677 -0.9565 +vn 0.0003 0.0341 0.9994 +vn -0.0071 0.0273 0.9996 +vn 0.0102 0.6204 -0.7842 +vn -0.0087 0.6326 -0.7744 +vn 0.0011 0.9985 -0.0553 +vn 0.0085 0.9975 -0.0704 +vn -0.9991 -0.0399 -0.0169 +vn -0.9990 -0.0432 -0.0073 +vn -0.7637 0.5755 -0.2923 +vn -0.0929 0.9927 -0.0769 +vn -0.9577 -0.2658 0.1099 +vn -0.7455 -0.4984 0.4425 +vn -0.8750 -0.3650 0.3179 +vn -0.9140 -0.3895 0.1140 +vn -0.7108 -0.6970 0.0941 +vn -0.7355 -0.6267 0.2574 +vn -0.9377 -0.3416 -0.0630 +vn -0.9294 -0.3690 -0.0044 +vn -0.9396 -0.3381 0.0536 +vn -0.9070 -0.4210 -0.0099 +vn -0.7170 -0.6948 -0.0559 +vn -0.7716 -0.5935 -0.2290 +vn -0.7186 -0.4324 -0.5447 +vn -0.8352 -0.0901 -0.5426 +vn -0.6434 -0.3583 -0.6765 +vn -0.4734 -0.0222 -0.8805 +vn -0.7446 -0.0982 -0.6602 +vn -0.7820 -0.0830 -0.6177 +vn -0.8021 0.0621 -0.5939 +vn -0.6023 0.1012 -0.7919 +vn -0.7837 0.0705 -0.6171 +vn -0.8402 0.0924 -0.5344 +vn -0.6264 0.3365 -0.7032 +vn -0.9445 0.1647 -0.2841 +vn -0.8050 0.4479 -0.3891 +vn -0.8435 0.3101 -0.4387 +vn -0.8471 0.4098 -0.3383 +vn -0.9299 0.3552 -0.0956 +vn -0.9387 0.3448 -0.0024 +vn -0.7256 0.6865 -0.0475 +vn -0.9129 0.4082 -0.0039 +vn -0.7443 0.6347 0.2078 +vn -0.8761 0.4745 0.0854 +vn -0.9291 0.3622 0.0752 +vn -0.7460 0.4341 0.5051 +vn -0.8093 0.4635 0.3607 +vn -0.9494 0.1898 0.2501 +vn -0.6809 0.0777 0.7283 +vn -0.7269 0.2729 0.6302 +vn -0.9409 0.0467 0.3355 +vn -0.7570 -0.1335 0.6396 +vn -0.9484 -0.1472 0.2807 +vn -0.7213 -0.3378 0.6047 +vn -0.7376 -0.4895 0.4650 +vn -0.8673 0.0036 -0.4978 +vn -0.6736 0.4712 -0.5694 +vn -0.8864 0.1709 -0.4302 +vn -0.9110 -0.1011 -0.3998 +vn -0.9164 0.0314 -0.3990 +vn -0.7621 0.5179 -0.3885 +vn -0.7822 -0.5017 -0.3694 +vn -0.9378 -0.1705 -0.3025 +vn -0.9159 -0.2421 -0.3201 +vn -0.9779 -0.0381 -0.2055 +vn -0.9354 0.2889 0.2040 +vn -0.9799 0.0171 0.1988 +vn -0.9252 -0.2905 -0.2440 +vn -0.9492 -0.2611 -0.1757 +vn -0.9671 0.1881 -0.1712 +vn -0.6871 -0.5350 -0.4916 +vn -0.7586 0.5889 -0.2789 +vn -0.9827 -0.1785 -0.0483 +vn -0.9995 0.0103 -0.0294 +vn -0.9837 0.1595 0.0834 +vn -0.9736 0.2220 -0.0527 +vn -0.9495 0.2959 0.1042 +vn -0.9864 -0.1167 0.1160 +vn -0.7562 0.4543 0.4709 +vn -0.2087 -0.7390 -0.6405 +vn -0.3241 -0.8575 -0.3997 +vn 0.0240 -0.8841 -0.4667 +vn -0.0094 -0.9682 -0.2500 +vn -0.3285 -0.9183 -0.2210 +vn -0.2557 -0.9667 -0.0045 +vn -0.3245 -0.9251 0.1973 +vn -0.2413 -0.8900 0.3868 +vn -0.2844 -0.7716 0.5691 +vn -0.2581 -0.6413 0.7226 +vn -0.2851 -0.3823 0.8789 +vn -0.2604 -0.2022 0.9441 +vn -0.3034 -0.0136 0.9528 +vn -0.2926 0.2535 0.9220 +vn -0.2816 0.5876 0.7586 +vn -0.2588 -0.0873 -0.9620 +vn -0.2254 0.2514 -0.9413 +vn -0.0582 -0.3981 -0.9155 +vn -0.3325 -0.5525 -0.7644 +vn 0.0053 0.7595 -0.6505 +vn 0.0200 0.7399 -0.6724 +vn 0.0111 0.7519 -0.6592 +vn 0.0241 0.7344 -0.6783 +vn 0.0208 0.7467 0.6648 +vn -0.0221 0.8069 0.5903 +vn 0.0001 0.7769 0.6296 +vn 0.0479 0.7043 0.7083 +vn -0.0381 -0.6087 0.7925 +vn 0.0025 -0.6515 0.7586 +vn -0.1024 -0.5346 0.8389 +vn 0.0551 -0.7025 0.7095 +vn -0.0271 -0.6714 -0.7406 +vn -0.0221 -0.6795 -0.7334 +vn -0.0250 -0.6747 -0.7376 +vn -0.0187 -0.6849 -0.7284 +vn -0.0320 0.7294 0.6833 +vn 0.0101 0.8813 0.4724 +vn -0.0258 0.7556 0.6545 +vn 0.0180 0.9032 0.4289 +vn 0.0368 -0.1310 0.9907 +vn 0.0064 -0.9193 0.3935 +vn -0.0335 -0.7390 0.6729 +vn -0.0297 -0.7610 0.6481 +vn 0.0117 -0.9356 0.3530 +vn -0.0066 -0.6924 -0.7215 +vn -0.0155 -0.7246 -0.6890 +vn -0.0143 -0.7205 -0.6933 +vn -0.0048 -0.6856 -0.7279 +vn 0.0229 0.5488 -0.8357 +vn -0.0270 0.7340 -0.6787 +vn 0.0160 0.5770 -0.8166 +vn -0.0346 0.7586 -0.6507 +vn -0.0738 -0.4255 0.9019 +vn 0.0084 -0.3900 0.9208 +vn 0.0158 -0.6526 0.7575 +vn -0.0084 -0.9866 -0.1632 +vn -0.3430 -0.7376 -0.5817 +vn 0.0057 -1.0000 0.0006 +vn 0.0015 -0.6293 -0.7771 +vn -0.3382 -0.5398 -0.7709 +vn -0.2678 -0.5087 0.8182 +vn -0.2598 -0.8502 0.4578 +vn 0.0099 -0.9282 0.3721 +vn -0.1334 -0.9422 0.3074 +vn -0.0069 -0.9904 0.1378 +vn -0.2824 -0.4204 -0.8623 +vn -0.5981 -0.5491 0.5837 +vn -0.5147 -0.6034 0.6091 +vn -0.5964 -0.4787 -0.6444 +vn -0.5473 -0.6298 -0.5512 +vn -0.5767 -0.6330 -0.5165 +vn -0.6724 -0.7157 -0.1889 +vn -0.6243 -0.6405 -0.4472 +vn -0.6456 -0.7579 -0.0935 +vn -0.5951 -0.8034 -0.0191 +vn 0.0080 0.9446 -0.3281 +vn 0.0005 0.6717 -0.7408 +vn -0.0027 0.7915 -0.6112 +vn -0.2385 0.6809 -0.6924 +vn -0.3129 0.8663 -0.3894 +vn -0.3504 0.7249 0.5931 +vn -0.2825 0.8820 0.3771 +vn -0.3663 0.9218 0.1270 +vn -0.2419 0.9657 -0.0947 +vn 0.0465 -0.9556 -0.2911 +vn -0.0488 -0.5313 -0.8458 +vn 0.0351 0.1122 -0.9931 +vn -0.0318 0.7978 -0.6021 +vn 0.0364 0.9992 0.0143 +vn -0.0397 0.7646 0.6432 +vn 0.0600 -0.1795 0.9819 +vn -0.0593 -0.7196 0.6918 +vn 0.0112 0.3940 0.9190 +vn 0.0032 0.4977 0.8673 +vn 0.0150 0.6626 0.7489 +vn -0.0030 0.3971 -0.9178 +vn -0.3882 0.7219 -0.5729 +vn -0.1185 0.6539 -0.7472 +vn 0.0282 0.9055 -0.4234 +vn -0.0246 0.9906 -0.1349 +vn 0.0244 0.9148 -0.4032 +vn -0.0280 0.9929 -0.1152 +vn -0.2378 0.4406 0.8656 +vn -0.0120 0.9003 0.4350 +vn 0.0077 0.9295 0.3687 +vn -0.0103 0.9596 0.2813 +vn -0.0165 0.9889 0.1475 +vn 0.0040 0.9699 0.2436 +vn -0.0142 0.9498 0.3124 +vn -0.0063 0.4812 -0.8766 +vn -0.6283 0.6580 0.4151 +vn -0.5304 0.6879 0.4955 +vn -0.5229 0.5601 0.6426 +vn -0.5425 0.4770 0.6915 +vn -0.4139 0.9017 0.1249 +vn -0.8486 0.5224 0.0839 +vn -0.7129 0.6727 -0.1979 +vn -0.6654 0.6135 -0.4253 +vn -0.6583 0.4420 -0.6093 +vn -0.4962 0.3124 -0.8101 +vn -0.3825 0.7275 -0.5696 +vn -0.6876 0.6946 -0.2114 +vn -0.6875 0.6927 -0.2179 +vn -0.8948 0.3992 0.1999 +vn -0.8809 0.4543 0.1327 +vn -0.8671 0.2385 0.4373 +vn -0.8360 0.2279 0.4991 +vn 0.9981 0.0202 0.0575 +vn 0.9738 0.1594 0.1620 +vn 0.9951 0.0637 0.0759 +vn 0.9607 -0.2507 -0.1195 +vn 0.9814 -0.1732 -0.0825 +vn 0.9920 0.1127 0.0561 +vn 0.9662 0.2312 0.1137 +vn 0.9009 0.3885 0.1934 +vn -0.6256 0.4724 -0.6208 +vn -0.6323 0.4719 -0.6145 +vn -0.6533 0.4695 -0.5940 +vn -0.6574 0.4689 -0.5898 +vn 0.6315 0.6901 -0.3534 +vn -0.6990 0.7106 0.0801 +vn 0.7781 0.4946 0.3871 +vn -0.7617 0.2506 0.5975 +vn 0.7702 -0.2167 0.5998 +vn -0.4551 -0.5431 0.7057 +vn 0.0719 -0.9890 0.1296 +vn 0.0154 -0.9902 0.1386 +vn 0.3114 -0.9464 0.0860 +vn 0.3350 -0.9387 0.0812 +vn -0.1881 -0.6120 -0.7682 +vn 0.5832 -0.5689 -0.5799 +vn 0.5985 -0.5709 -0.5620 +vn 0.5948 -0.5703 -0.5666 +vn 0.5788 -0.5680 -0.5851 +vn 0.7782 -0.6052 -0.1679 +vn -0.5542 -0.7545 0.3516 +vn 0.4194 0.1446 0.8962 +vn -0.8132 0.5801 0.0466 +vn -0.1447 0.7009 0.6984 +vn 0.6065 0.6531 0.4534 +vn -0.7116 0.7026 0.0050 +vn 0.7350 0.6311 -0.2479 +vn -0.6460 0.3978 -0.6515 +vn 0.6461 0.1951 -0.7379 +vn -0.7511 -0.2625 -0.6057 +vn 0.6780 -0.5028 -0.5362 +vn -0.5571 -0.8299 -0.0299 +vn 0.1804 -0.9750 -0.1296 +vn -0.3029 -0.7535 0.5835 +vn -0.2825 -0.7558 0.5907 +vn -0.0921 -0.7602 0.6432 +vn -0.0753 -0.7591 0.6466 +vn 0.0695 -0.9647 0.2541 +vn 0.8933 -0.4058 -0.1934 +vn -0.1612 -0.2717 0.9488 +vn 0.6798 0.0199 0.7332 +vn -0.4499 0.8636 -0.2275 +vn 0.8829 0.4204 0.2093 +vn -0.6331 -0.5676 -0.5263 +vn -0.5209 -0.6909 -0.5013 +vn -0.4102 -0.7832 -0.4674 +vn -0.2883 -0.8592 -0.4227 +vn 0.3269 0.8334 -0.4456 +vn 0.4043 0.8290 -0.3864 +vn 0.2526 0.8303 -0.4968 +vn 0.1718 0.8198 -0.5463 +vn -0.1037 0.2335 0.9668 +vn 0.4352 -0.1248 0.8917 +vn -0.3309 -0.8972 -0.2926 +vn 0.2300 -0.8007 -0.5532 +vn -0.0895 0.9048 -0.4163 +vn 0.5647 0.5339 -0.6294 +vn -0.1710 0.3009 0.9382 +vn -0.2862 0.3694 0.8841 +vn -0.0063 0.1961 0.9806 +vn 0.1299 0.1037 0.9861 +vn 0.0780 0.2636 0.9615 +vn -0.1267 0.0711 0.9894 +vn 0.1428 0.2931 0.9454 +vn -0.3822 -0.9197 -0.0895 +vn -0.4728 -0.8686 0.1487 +vn -0.4522 -0.8899 0.0590 +vn 0.9916 -0.0917 0.0914 +vn 0.9860 -0.1547 0.0623 +vn 0.9877 -0.0902 0.1277 +vn 0.4919 -0.6513 -0.5778 +vn 0.3911 -0.5745 -0.7190 +vn 0.2242 -0.8772 -0.4245 +vn -0.1067 -0.0454 0.9933 +vn 0.1778 -0.1624 0.9706 +vn 0.5346 0.6460 0.5448 +vn 0.2045 -0.1689 0.9642 +vn -0.0235 0.9064 0.4218 +vn -0.2518 0.8855 0.3905 +vn -0.1262 0.9031 0.4105 +vn 0.9459 0.2521 -0.2043 +vn 0.9488 0.2467 -0.1974 +vn 0.8926 0.3718 -0.2550 +vn -0.9765 0.0417 -0.2113 +vn -0.9360 -0.0172 -0.3515 +vn -0.8790 0.0946 -0.4673 +vn -0.9787 0.0445 0.2006 +vn -0.9750 0.0519 0.2161 +vn -0.8100 0.2209 0.5432 +vn -0.9402 0.1675 0.2966 +vn 0.4879 0.8722 -0.0344 +vn 0.8276 0.5307 0.1826 +vn 0.5010 0.8648 -0.0327 +vn -0.8429 0.3983 -0.3616 +vn -0.9964 -0.0160 -0.0829 +vn -0.1734 -0.9829 -0.0622 +vn -0.9873 -0.1111 0.1133 +vn -0.8846 -0.4304 0.1797 +vn -0.9767 -0.1712 0.1292 +vn -0.9834 -0.1608 0.0837 +vn -0.9865 -0.1383 0.0882 +vn -0.9836 -0.1546 0.0931 +vn -0.9876 -0.1455 -0.0589 +vn -0.8691 -0.4130 -0.2721 +vn -0.9839 -0.1631 -0.0726 +vn 0.3850 -0.0759 -0.9198 +vn 0.9849 -0.0929 0.1462 +vn -0.3410 0.2381 -0.9094 +vn -0.9770 0.0377 -0.2097 +vn 0.2703 -0.8067 0.5256 +vn -0.0656 -0.8676 0.4929 +vn -0.0148 -0.8649 0.5017 +vn 0.2966 -0.7972 0.5258 +vn -0.5750 0.2326 -0.7844 +vn -0.3920 0.2926 -0.8722 +vn -0.5250 0.2509 -0.8132 +vn 0.0287 -0.9232 0.3832 +vn 0.9286 -0.1634 -0.3333 +vn 0.9291 -0.1624 -0.3324 +vn 0.9249 -0.1706 -0.3398 +vn -0.9358 0.3050 0.1766 +vn -0.9222 0.3085 0.2333 +vn -0.9805 0.1920 0.0422 +vn 0.2452 -0.9186 -0.3098 +vn 0.9617 0.1670 0.2173 +vn -0.9463 0.1628 0.2794 +vn 0.8676 0.4314 -0.2475 +vn 0.4146 0.9041 0.1037 +vn 0.9944 -0.1054 0.0012 +vn -0.4639 -0.4247 -0.7775 +vn -0.7062 -0.2608 -0.6582 +vn -0.4215 -0.4465 -0.7893 +vn -0.1364 0.9904 0.0223 +vn -0.6584 -0.4395 0.6111 +vn 0.4730 0.4826 -0.7371 +vn -0.9577 0.2698 -0.1003 +vn -0.2800 -0.5097 -0.8135 +vn -0.0780 0.9714 -0.2241 +vn -0.1923 0.9750 -0.1116 +vn -0.1597 0.9765 -0.1445 +vn -0.0384 0.9644 -0.2616 +vn 0.7177 0.6142 -0.3281 +vn -0.8011 -0.4938 -0.3382 +vn 0.8375 0.4989 -0.2229 +vn -0.7756 0.4097 0.4802 +vn -0.1577 0.9337 0.3214 +vn -0.9965 0.0451 -0.0699 +vn -0.9952 0.0580 -0.0783 +vn 0.9563 -0.0540 -0.2872 +vn 0.8400 -0.0466 -0.5406 +vn 0.8951 -0.0500 -0.4431 +vn -0.5258 -0.5188 -0.6741 +vn -0.8157 0.4552 -0.3569 +vn 0.9849 -0.0930 0.1463 +vn -0.6099 -0.3408 0.7155 +vn 0.3233 -0.5424 -0.7754 +vn 0.9431 -0.3323 0.0119 +vn 0.3520 0.6509 -0.6726 +vn 0.9167 -0.3752 -0.1372 +vn 0.8933 -0.4396 -0.0936 +vn 0.8773 0.2898 0.3825 +vn 0.9027 0.2331 0.3617 +vn 0.7497 0.5232 0.4053 +vn -0.6936 -0.6167 -0.3724 +vn 0.9600 -0.0543 -0.2747 +vn 0.4632 -0.6212 0.6321 +vn 0.5170 -0.6291 0.5805 +vn 0.4776 -0.6236 0.6189 +vn 0.9272 -0.1346 0.3496 +vn -0.9775 0.0826 -0.1940 +vn -0.9808 0.0165 -0.1944 +vn -0.2809 -0.6780 -0.6793 +vn -0.0490 -0.3802 0.9236 +vn -0.4208 -0.2863 0.8608 +vn -0.4535 -0.2748 0.8478 +vn 0.5004 0.0398 0.8649 +vn 0.0143 -0.3904 0.9206 +vn -0.7203 -0.2486 -0.6476 +vn -0.6740 0.6693 -0.3126 +vn 0.7751 0.6305 0.0423 +vn 0.9237 -0.1729 -0.3419 +vn -0.0169 0.7392 -0.6733 +vn 0.4126 0.1937 0.8901 +vn -0.9831 0.1798 0.0357 +vn 0.9110 -0.3259 -0.2529 +vn 0.3577 0.6514 0.6691 +vn -0.2623 0.8833 0.3885 +vn 0.5298 -0.6305 0.5673 +vn 0.5175 0.3213 -0.7931 +vn -0.0339 -0.9779 -0.2063 +vn -0.1698 0.1723 0.9703 +vn 0.8850 0.3485 -0.3088 +vn -0.7044 0.4552 0.5446 +vn -0.9951 0.0607 -0.0781 +vn -0.0075 -0.0951 -0.9954 +vn -0.1670 0.3440 -0.9240 +vn 0.3041 -0.9334 -0.1906 +vn -0.9991 0.0201 0.0368 +vn -0.9985 0.0342 -0.0419 +vn -0.9992 -0.0392 -0.0047 +vn 0.9990 0.0272 0.0343 +vn 0.9908 0.0469 0.1270 +vn 0.9881 0.0507 0.1454 +vn 0.0694 0.7075 0.7033 +vn -0.0232 0.3725 0.9278 +vn 0.0497 0.6427 0.7645 +vn -0.0448 0.2830 0.9581 +vn 0.0667 -0.6427 0.7632 +vn -0.0449 -0.9978 0.0496 +vn 0.0779 -0.8768 -0.4744 +vn -0.0184 0.0233 -0.9996 +vn 0.0891 0.5454 -0.8334 +vn -0.0345 0.9937 -0.1063 +vn 0.9893 0.1253 0.0746 +vn 0.9914 0.0560 0.1182 +vn 0.9871 -0.0835 0.1367 +vn 0.9796 0.1533 -0.1302 +vn 0.9910 0.0186 -0.1328 +vn 0.9896 0.1435 -0.0035 +vn 0.9920 -0.1240 -0.0245 +vn 0.9766 -0.1333 -0.1688 +vn 0.9792 -0.1307 0.1550 +vn -0.0292 -0.1352 0.9904 +vn -0.0112 -0.1550 0.9878 +vn -0.0104 -0.1560 0.9877 +vn 0.0064 -0.1745 0.9846 +vn -0.0351 -0.9082 0.4172 +vn -0.0729 -0.8905 0.4490 +vn -0.0327 -0.9092 0.4151 +vn 0.0074 -0.9250 0.3800 +vn 0.0146 -0.5946 -0.8039 +vn 0.0800 -0.6288 -0.7734 +vn 0.0915 -0.6345 -0.7675 +vn 0.1759 -0.6722 -0.7192 +vn -0.2002 0.0955 -0.9751 +vn 0.1774 0.7610 -0.6240 +vn 0.0686 0.8469 -0.5274 +vn 0.0625 0.8509 -0.5215 +vn -0.0729 0.9212 -0.3821 +vn -0.0035 0.8492 0.5280 +vn 0.0044 0.8533 0.5213 +vn 0.0055 0.8536 0.5209 +vn 0.0143 0.8580 0.5135 +vn -0.1302 -0.5943 0.7936 +vn -0.8030 0.2161 0.5554 +vn -0.5739 -0.3699 -0.7306 +vn -0.5223 -0.3464 -0.7792 +vn -0.5448 -0.3567 -0.7589 +vn -0.4670 -0.3207 -0.8241 +vn -0.0993 0.9865 0.1299 +vn 0.9668 0.0718 0.2454 +vn -0.9981 0.0491 0.0378 +vn -0.9992 -0.0394 0.0118 +vn -0.9976 0.0191 -0.0667 +vn 0.9993 0.0045 0.0363 +vn 0.9988 -0.0050 0.0497 +vn 0.9997 0.0148 0.0212 +vn 0.0087 0.1045 0.9945 +vn -0.0033 0.2059 0.9786 +vn -0.0024 0.1980 0.9802 +vn 0.0095 0.0972 0.9952 +vn -0.0003 1.0000 0.0000 +vn 0.0176 0.9741 -0.2253 +vn 0.0008 0.9999 -0.0136 +vn 0.0186 0.9711 -0.2381 +vn -0.0050 0.2400 -0.9708 +vn 0.0217 -0.1091 -0.9938 +vn -0.0034 0.2195 -0.9756 +vn 0.0234 -0.1318 -0.9910 +vn -0.0115 -0.9911 -0.1327 +vn 0.0140 -0.9918 0.1267 +vn -0.0098 -0.9933 -0.1153 +vn 0.0161 -0.9887 0.1489 +vn 0.9957 0.0696 -0.0605 +vn 0.9959 0.0877 -0.0221 +vn 0.9955 0.0754 0.0576 +vn 0.9946 0.0719 0.0746 +vn 0.9949 -0.0059 0.1010 +vn 0.9915 -0.0901 0.0939 +vn 0.9942 -0.1049 0.0230 +vn 0.9954 -0.0689 -0.0662 +vn 0.9955 -0.0448 -0.0836 +vn 0.9952 0.0326 -0.0918 +vn -0.0697 0.2380 0.9688 +vn -0.0248 0.2875 0.9575 +vn -0.0351 0.2762 0.9605 +vn 0.0096 0.3244 0.9459 +vn -0.0371 0.9814 0.1886 +vn 0.0383 0.9624 0.2689 +vn -0.0284 0.9797 0.1982 +vn -0.1023 0.9879 0.1168 +vn -0.0606 0.7540 -0.6541 +vn -0.0223 0.7261 -0.6872 +vn -0.0311 0.7328 -0.6798 +vn 0.0065 0.7033 -0.7109 +vn -0.0324 -0.2125 -0.9766 +vn 0.0352 -0.1396 -0.9896 +vn -0.0220 -0.2013 -0.9793 +vn -0.0909 -0.2741 -0.9574 +vn -0.0964 -0.9235 -0.3712 +vn -0.0152 -0.9539 -0.2998 +vn -0.0129 -0.9546 -0.2977 +vn 0.0669 -0.9723 -0.2239 +vn -0.0503 -0.5817 0.8118 +vn 0.0123 -0.6327 0.7743 +vn -0.0456 -0.5857 0.8092 +vn -0.1043 -0.5335 0.8393 +vn -0.1608 -0.2595 0.9523 +vn -0.3397 -0.1005 0.9351 +vn -0.2934 -0.1439 0.9451 +vn -0.4993 0.0646 0.8640 +vn -0.1655 -0.7685 -0.6181 +vn -0.2972 -0.8041 -0.5149 +vn -0.2585 -0.7959 -0.5475 +vn -0.4235 -0.8162 -0.3932 +vn 0.0114 0.9546 -0.2976 +vn -0.1779 0.8889 -0.4221 +vn -0.1100 0.9187 -0.3794 +vn -0.3613 0.7704 -0.5253 +vn -0.9842 -0.1345 0.1152 +vn -0.9941 -0.0903 0.0604 +vn -0.9752 -0.1476 0.1647 +vn -0.9986 -0.0370 0.0388 +vn -0.9237 -0.2355 0.3021 +vn -0.9643 -0.1523 0.2168 +vn -0.9777 -0.1186 0.1736 +vn -0.9943 0.0869 -0.0625 +vn -0.9747 0.1710 -0.1438 +vn -0.9872 0.1185 -0.1072 +vn -0.9994 0.0254 0.0231 +vn -0.8732 0.1946 0.4468 +vn -0.9988 0.0395 0.0306 +vn -0.8815 0.3029 0.3623 +vn -0.6980 0.2040 0.6864 +vn -0.9994 0.0327 -0.0109 +vn -0.9999 0.0102 -0.0131 +vn -0.9813 0.1833 -0.0581 +vn -0.9705 0.2292 -0.0742 +vn -0.9994 0.0324 -0.0100 +vn -0.9996 -0.0122 0.0239 +vn -0.9864 0.0018 0.1646 +vn -0.9670 0.1440 0.2101 +vn -0.9986 0.0520 -0.0139 +vn -0.9979 0.0253 -0.0596 +vn 0.8746 0.4202 0.2419 +vn 0.6692 0.2074 0.7135 +vn 0.7359 0.2220 0.6396 +vn 0.8881 0.4300 0.1621 +vn 0.7690 -0.6349 -0.0748 +vn 0.6632 -0.7388 -0.1195 +vn 0.7701 -0.6336 -0.0742 +vn 0.9683 -0.2259 0.1068 +vn 0.9293 0.2142 -0.3007 +vn 0.9716 0.1373 -0.1927 +vn 0.9997 0.0138 -0.0194 +vn 0.7867 0.5959 0.1612 +vn 0.8341 0.5380 0.1217 +vn 0.8499 0.5159 0.1071 +vn 0.9002 -0.4069 0.1553 +vn 0.9026 -0.3987 0.1622 +vn 0.9277 -0.2334 0.2913 +vn 0.9995 0.0297 -0.0148 +vn 0.9938 0.1008 -0.0470 +vn 0.9884 0.1456 -0.0419 +vn 0.9991 0.0323 0.0265 +vn 0.9983 0.0363 0.0463 +vn 0.9942 -0.0160 0.1066 +vn 0.9847 0.0875 0.1507 +vn 0.9931 0.1086 0.0437 +vn 0.9998 0.0194 -0.0007 +vn 0.1302 0.3732 -0.9186 +vn -0.3642 0.9013 -0.2344 +vn 0.4785 0.8737 -0.0873 +vn -0.4471 0.7049 0.5506 +vn -0.5639 0.0490 0.8244 +vn 0.6565 -0.5038 0.5613 +vn -0.7197 -0.6512 0.2406 +vn 0.3005 -0.9514 0.0669 +vn -0.1438 -0.7251 -0.6734 +vn -0.1868 -0.7159 -0.6728 +vn -0.4230 -0.6370 -0.6444 +vn -0.4481 -0.6256 -0.6386 +vn -0.2995 0.2108 -0.9305 +vn 0.7827 -0.6187 -0.0682 +vn 0.8165 0.5774 0.0000 +vn -0.1719 0.7376 0.6530 +vn -0.1726 0.7376 0.6528 +vn -0.1644 0.7374 0.6551 +vn -0.1634 0.7374 0.6554 +vn 0.3326 0.9421 0.0427 +vn -0.3022 0.7866 -0.5384 +vn 0.2111 0.2561 -0.9433 +vn -0.3138 0.1663 -0.9348 +vn 0.4548 -0.4351 -0.7771 +vn -0.6202 -0.5272 -0.5808 +vn 0.6598 -0.7368 -0.1473 +vn -0.4529 -0.8907 0.0377 +vn -0.0036 -0.7636 0.6457 +vn 0.0269 -0.7603 0.6491 +vn 0.1621 -0.7368 0.6563 +vn 0.1718 -0.7346 0.6564 +vn 0.8389 -0.5435 0.0287 +vn 0.4090 -0.1405 0.9016 +vn 0.8608 0.4997 0.0966 +vn -0.1991 -0.6136 -0.7641 +vn 0.4346 0.5081 -0.7436 +vn -0.3739 0.8385 -0.3963 +vn 0.0666 0.8064 0.5876 +vn -0.5493 -0.3126 0.7750 +vn 0.6523 -0.6914 0.3105 +vn -0.3839 -0.8913 -0.2413 +vn 0.5135 0.1595 -0.8431 +vn -0.0318 0.6249 -0.7800 +vn 0.4064 0.7930 0.4538 +vn -0.4876 0.3350 0.8063 +vn 0.5045 -0.7738 0.3830 +vn 0.9979 -0.0215 -0.0618 +vn 0.9907 -0.1129 -0.0763 +vn 0.8975 0.4297 0.0991 +vn -0.5408 0.6974 0.4702 +vn -0.2156 0.6707 0.7097 +vn -0.4886 0.7093 0.5082 +vn -0.9522 -0.1274 0.2775 +vn -0.9414 -0.1329 0.3100 +vn -0.8292 -0.1680 0.5330 +vn 0.2767 -0.9497 0.1469 +vn 0.6158 -0.7846 -0.0720 +vn 0.3022 -0.9428 0.1406 +vn -0.8951 -0.2719 0.3534 +vn -0.9314 -0.3460 0.1133 +vn -0.9024 -0.2545 0.3476 +vn 0.1474 -0.1736 -0.9737 +vn 0.2450 -0.2385 -0.9397 +vn 0.2202 -0.2222 -0.9498 +vn 0.1247 -0.1584 -0.9795 +vn 0.9229 0.3032 0.2374 +vn 0.9577 0.2281 0.1754 +vn 0.9216 0.3053 0.2397 +vn 0.9956 -0.0135 -0.0932 +vn 0.8421 -0.0668 0.5351 +vn 0.9902 -0.0893 0.1074 +vn 0.8777 -0.0684 0.4744 +vn -0.6042 -0.6147 0.5071 +vn -0.4403 -0.8462 0.3002 +vn -0.6800 -0.6473 0.3445 +vn -0.0686 -0.4684 -0.8809 +vn -0.0629 -0.4676 -0.8817 +vn -0.0615 -0.4674 -0.8819 +vn 0.8195 -0.4681 0.3306 +vn 0.5431 0.6208 -0.5654 +vn 0.7556 0.5925 -0.2794 +vn 0.9103 0.4140 -0.0026 +vn 0.7634 0.5709 -0.3020 +vn -0.9567 -0.2428 0.1606 +vn -0.4999 0.3430 -0.7953 +vn -0.3818 0.4536 -0.8053 +vn -0.5155 0.3484 -0.7829 +vn 0.9987 -0.0508 0.0021 +vn 0.9970 -0.0760 -0.0137 +vn -0.5240 0.8392 -0.1454 +vn -0.5244 0.8240 -0.2147 +vn -0.8420 0.4254 -0.3317 +vn -0.8699 0.3738 -0.3217 +vn 0.5272 0.0944 0.8445 +vn 0.5723 0.1105 0.8126 +vn 0.7621 0.1822 0.6213 +vn -0.3434 0.5466 -0.7638 +vn -0.5720 0.6117 -0.5466 +vn -0.5341 0.6235 -0.5710 +vn -0.9277 -0.3734 -0.0021 +vn 0.6085 -0.5951 0.5249 +vn 0.7654 -0.4601 0.4500 +vn 0.5852 -0.6110 0.5331 +vn -0.7937 -0.0791 -0.6031 +vn -0.7945 -0.0745 -0.6027 +vn -0.7726 -0.1951 -0.6041 +vn 0.7855 -0.4520 0.4227 +vn 0.6820 -0.5496 0.4825 +vn -0.4195 0.8065 0.4166 +vn 0.8670 -0.0767 0.4923 +vn -0.9005 -0.4264 0.0851 +vn -0.9021 -0.4233 0.0837 +vn 0.7380 0.1425 -0.6596 +vn 0.6280 0.1226 -0.7685 +vn 0.5977 0.1686 -0.7838 +vn 0.6559 0.0768 -0.7509 +vn -0.0722 -0.4688 -0.8804 +vn -0.4502 0.8849 0.1191 +vn -0.3792 0.9246 0.0352 +vn -0.2545 0.9609 -0.1092 +vn -0.8644 0.0598 0.4993 +vn -0.8997 0.1243 0.4185 +vn -0.9981 0.0372 0.0494 +vn -0.8949 -0.2068 -0.3955 +vn -0.8812 -0.1869 -0.4341 +vn -0.9040 -0.2216 -0.3655 +vn -0.4412 -0.3847 0.8108 +vn -0.2846 -0.4404 0.8515 +vn -0.4626 -0.4089 0.7867 +vn -0.4556 -0.4524 -0.7667 +vn 0.9586 0.2519 0.1329 +vn 0.3764 -0.7495 0.5447 +vn -0.8876 -0.1700 0.4281 +vn -0.7982 0.6014 0.0340 +vn 0.7859 0.1919 0.5878 +vn 0.2271 -0.8239 -0.5193 +vn -0.9242 0.3566 0.1368 +vn -0.4452 -0.3425 0.8273 +vn 0.6417 0.1842 0.7445 +vn 0.6904 0.1260 0.7124 +vn 0.4639 0.3552 0.8116 +vn 0.3309 -0.9436 0.0114 +vn 0.1347 -0.9390 -0.3164 +vn 0.1931 -0.9707 -0.1433 +vn 0.4150 -0.9037 0.1050 +vn 0.9430 -0.0149 -0.3324 +vn 0.9249 -0.0753 -0.3727 +vn 0.9440 -0.0110 -0.3297 +vn 0.0784 -0.8914 -0.4464 +vn 0.1184 -0.9221 -0.3683 +vn 0.3464 0.4215 0.8381 +vn -0.3982 -0.8633 0.3100 +vn -0.3923 -0.8735 0.2882 +vn 0.8584 -0.3453 0.3794 +vn 0.9558 0.0449 -0.2906 +vn -0.9997 0.0024 -0.0237 +vn -0.8039 0.0346 -0.5938 +vn -0.9530 0.1219 0.2773 +vn -0.9509 0.1020 0.2921 +vn -0.9464 0.0683 0.3158 +vn 0.6385 -0.7646 -0.0874 +vn -0.5514 -0.6184 0.5599 +vn -0.9127 -0.2373 -0.3327 +vn 0.6371 -0.7396 -0.2169 +vn -0.9894 0.1328 0.0583 +vn -0.2966 0.9342 -0.1983 +vn 0.5648 0.2149 -0.7968 +vn 0.0410 0.9447 0.3254 +vn -0.2549 -0.4382 0.8620 +vn 0.9826 0.1797 0.0461 +vn 0.9853 0.1620 0.0539 +vn 0.9593 0.2805 -0.0335 +vn -0.3955 0.0639 0.9162 +vn -0.1898 0.6221 0.7596 +vn -0.8812 0.0485 -0.4703 +vn 0.6724 -0.5389 -0.5074 +vn 0.3018 -0.3572 0.8839 +vn -0.4285 -0.8242 -0.3704 +vn -0.3268 0.9234 -0.2014 +vn 0.7287 0.5204 -0.4452 +vn 0.4637 0.4274 -0.7761 +vn -0.9549 0.1589 0.2507 +vn -0.8182 -0.0586 0.5719 +vn -0.3896 0.3833 -0.8374 +vn 0.4991 0.8663 -0.0187 +vn -0.7538 -0.1816 0.6315 +vn 0.3434 0.4216 0.8392 +vn 0.9588 0.2782 -0.0573 +vn 0.9637 0.2547 -0.0797 +vn -0.2199 0.5599 0.7988 +vn 0.5979 0.2350 0.7663 +vn 0.6347 0.0690 0.7696 +vn 0.5421 0.3987 0.7397 +vn 0.9625 0.1808 -0.2022 +vn 0.9750 0.1271 -0.1824 +vn 0.9917 -0.0158 -0.1275 +vn 0.9911 -0.0892 -0.0984 +vn 0.3120 -0.7139 -0.6268 +vn 0.3055 -0.7039 -0.6412 +vn 0.3232 -0.7308 -0.6012 +vn 0.3313 -0.7428 -0.5818 +vn -0.5789 -0.3983 -0.7115 +vn -0.7667 -0.6001 -0.2282 +vn -0.9148 0.4040 0.0003 +vn -0.9217 0.3811 0.0728 +vn -0.8498 0.3726 0.3729 +vn -0.8087 0.3763 0.4521 +vn -0.7627 -0.1272 0.6341 +vn -0.7102 0.4668 0.5269 +vn 0.3429 -0.4372 -0.8314 +vn 0.5516 -0.7821 -0.2899 +vn 0.9974 -0.0432 -0.0573 +vn 0.9939 0.0415 -0.1025 +vn 0.9553 0.2215 -0.1959 +vn 0.9401 0.2630 -0.2170 +vn 0.4892 0.3614 0.7938 +vn 0.4892 0.3613 0.7938 +vn 0.3301 0.8378 0.4348 +vn -0.6543 0.2943 0.6966 +vn -0.7704 0.5925 0.2352 +vn -0.9465 -0.3218 -0.0236 +vn -0.8163 -0.0546 -0.5751 +vn -0.4328 -0.7856 -0.4423 +vn 0.6519 -0.0839 0.7536 +vn 0.4153 -0.0233 -0.9094 +vn 0.0000 -0.7071 0.7071 +vn 0.0000 0.7071 -0.7071 +vn -0.0001 0.7071 -0.7071 +vn -0.0003 0.7071 -0.7071 +vn -0.0283 -0.6791 0.7335 +vn -0.0333 -0.7048 0.7086 +vn -0.0185 -0.6879 0.7256 +vn 0.0071 -0.6828 0.7306 +vn -0.0117 -0.7283 0.6852 +vn -0.0270 -0.7240 0.6893 +vn 0.0117 -0.7291 0.6843 +vn 0.0339 -0.7025 0.7108 +vn 0.0326 -0.7160 0.6973 +vn 0.0253 -0.6879 0.7253 +vn 0.0195 0.7066 -0.7074 +vn 0.0223 0.7214 -0.6921 +vn 0.0118 0.7163 -0.6977 +vn 0.0083 0.7103 -0.7039 +vn -0.0127 0.7339 -0.6792 +vn -0.3381 -0.6777 -0.6530 +vn -0.7128 -0.4668 -0.5234 +vn -0.6654 -0.5048 -0.5499 +vn -0.2892 -0.6937 -0.6597 +vn 0.4096 -0.6108 -0.6776 +vn 0.8400 -0.3982 -0.3685 +vn 0.8555 0.3673 0.3649 +vn 0.9414 0.2600 0.2147 +vn 0.9322 0.2750 0.2354 +vn 0.8407 0.3811 0.3846 +vn -0.2057 0.6878 0.6961 +vn 0.0801 0.7244 0.6847 +vn 0.0472 0.7233 0.6890 +vn -0.2323 0.6813 0.6942 +vn -0.9713 0.1592 0.1767 +vn -0.8471 0.3985 0.3516 +vn -0.8701 0.3670 0.3290 +vn -0.9801 0.1269 0.1525 +vn -0.0724 0.6759 -0.7334 +vn -0.0890 0.6663 -0.7403 +vn -0.0676 0.7242 -0.6863 +vn 0.0290 0.6596 -0.7511 +vn -0.0120 0.6567 -0.7541 +vn 0.0292 0.7614 -0.6477 +vn 0.0564 0.7392 -0.6712 +vn 0.0719 0.7063 -0.7043 +vn -0.0518 0.7447 -0.6653 +vn -0.0167 0.7566 -0.6537 +vn 0.0479 0.6641 -0.7461 +vn 0.0699 0.6939 -0.7167 +vn -0.9930 -0.0432 -0.1099 +vn -0.9821 -0.1316 -0.1346 +vn -0.9742 -0.1725 -0.1457 +vn -0.8688 0.2971 0.3961 +vn -0.6029 0.5437 0.5839 +vn -0.7413 0.5033 0.4440 +vn -0.5213 0.6351 0.5700 +vn -0.2284 0.6333 0.7395 +vn 0.3087 0.7224 0.6188 +vn 0.3878 0.6680 0.6352 +vn 0.3585 0.6891 0.6297 +vn 0.4466 0.6213 0.6438 +vn 0.9701 0.1629 0.1798 +vn 0.9743 0.1619 0.1565 +vn 0.9710 0.1627 0.1750 +vn 0.9662 0.1637 0.1992 +vn 0.8284 -0.3602 -0.4289 +vn 0.7342 -0.5039 -0.4550 +vn 0.5897 -0.5519 -0.5896 +vn 0.2707 -0.7257 -0.6325 +vn -0.1725 -0.6701 -0.7220 +vn -0.3642 -0.6792 -0.6371 +vn -0.5847 -0.4986 -0.6400 +vn -0.9524 -0.2547 -0.1676 +vn -0.5803 0.6567 0.4816 +vn -0.6881 0.5119 0.5142 +vn -0.6856 0.5159 0.5136 +vn -0.7709 0.3543 0.5294 +vn 0.9872 0.1583 -0.0167 +vn 0.9725 0.1636 0.1659 +vn 0.9733 0.1636 0.1612 +vn 0.9266 0.1635 0.3385 +vn -0.4071 -0.5523 -0.7275 +vn -0.2845 -0.6790 -0.6768 +vn -0.2878 -0.6760 -0.6784 +vn -0.1558 -0.7805 -0.6054 +vn -0.0322 -0.7057 0.7077 +vn -0.0357 -0.7195 0.6935 +vn -0.0092 -0.7284 0.6850 +vn 0.0296 -0.7369 0.6754 +vn 0.0185 -0.7269 0.6865 +vn 0.0326 -0.7115 0.7020 +vn 0.0335 -0.6983 0.7150 +vn -0.0021 -0.6864 0.7272 +vn 0.0189 -0.6884 0.7251 +vn -0.0291 -0.6931 0.7202 +vn -0.0162 0.6985 -0.7154 +vn 0.0050 0.6962 -0.7178 +vn -0.0581 0.7411 -0.6689 +vn 0.0107 0.6777 -0.7352 +vn -0.0272 0.6858 -0.7273 +vn 0.8879 -0.3415 -0.3084 +vn 0.9314 0.2958 0.2123 +vn 0.5685 0.5638 0.5991 +vn -0.4897 0.6220 0.6110 +vn -0.2765 0.7073 0.6506 +vn -0.2993 0.7003 0.6481 +vn -0.5175 0.6074 0.6028 +vn -0.9989 -0.0272 -0.0378 +vn -0.9987 0.0259 0.0428 +vn -0.9993 -0.0218 -0.0295 +vn -0.9980 0.0335 0.0542 +vn -0.6733 -0.4921 -0.5519 +vn -0.1138 -0.7204 -0.6842 +vn 0.4983 -0.5868 -0.6382 +vn 0.0916 0.7256 -0.6820 +vn 0.0848 0.6975 -0.7115 +vn 0.0460 0.6646 -0.7457 +vn 0.0322 0.6600 -0.7506 +vn -0.0780 0.6604 -0.7468 +vn -0.0771 0.7022 -0.7078 +vn -0.0641 0.7284 -0.6822 +vn -0.0481 0.7444 -0.6660 +vn -0.0211 0.6553 -0.7551 +vn -0.0099 0.7631 -0.6462 +vn 0.0288 0.7501 -0.6607 +vn 0.1930 -0.6713 -0.7156 +vn 0.2120 -0.6793 -0.7026 +vn 0.1979 -0.6734 -0.7123 +vn 0.1807 -0.6660 -0.7238 +vn -0.7600 -0.4417 -0.4768 +vn -0.6785 -0.5573 -0.4787 +vn -0.7444 -0.4663 -0.4780 +vn -0.8091 -0.3532 -0.4696 +vn -0.9973 -0.0500 0.0533 +vn -0.9894 0.0995 0.1055 +vn -0.9742 0.1821 0.1335 +vn -0.9316 0.3170 0.1780 +vn -0.5207 0.5108 0.6841 +vn -0.3587 0.6609 0.6592 +vn -0.3393 0.6758 0.6543 +vn -0.1586 0.7890 0.5935 +vn 0.5632 0.4922 0.6638 +vn 0.8654 0.3279 0.3789 +vn 0.7561 0.4746 0.4506 +vn 0.9297 0.2946 0.2213 +vn 0.9919 0.0232 0.1252 +vn 0.8753 -0.2912 -0.3861 +vn 0.8201 -0.3971 -0.4120 +vn 0.8470 -0.3492 -0.4009 +vn 0.7782 -0.4620 -0.4254 +vn 0.4793 -0.4021 -0.7801 +vn -0.2494 -0.8471 -0.4693 +vn -0.9636 0.1910 -0.1869 +vn -0.6814 0.2929 0.6707 +vn 0.4844 0.7779 0.4003 +vn 0.9307 -0.0125 0.3655 +vn 0.0294 -0.6980 -0.7155 +vn 0.0099 -0.6847 -0.7288 +vn 0.0375 -0.7059 -0.7073 +vn -0.0270 -0.6913 -0.7221 +vn -0.0181 -0.6784 -0.7345 +vn -0.0057 -0.7301 -0.6833 +vn 0.0223 -0.7251 -0.6883 +vn -0.0040 -0.7424 -0.6699 +vn -0.0273 -0.7211 -0.6922 +vn -0.0348 -0.7049 -0.7084 +vn 0.0652 0.6801 0.7302 +vn 0.0561 0.6933 0.7184 +vn 0.0023 0.7166 0.6975 +vn -0.0135 0.7378 0.6749 +vn 0.9060 0.2725 -0.3240 +vn 0.9915 0.1014 -0.0813 +vn 0.9979 0.0606 -0.0242 +vn 0.4580 -0.6297 0.6275 +vn 0.4501 -0.6337 0.6291 +vn 0.4513 -0.6331 0.6289 +vn 0.4586 -0.6294 0.6273 +vn -0.5589 -0.5803 0.5923 +vn -0.6585 -0.5121 0.5515 +vn -0.5714 -0.5726 0.5879 +vn -0.6681 -0.5046 0.5468 +vn -1.0000 0.0065 -0.0026 +vn -0.9682 0.1963 -0.1548 +vn -0.9994 0.0277 -0.0196 +vn -0.9617 0.2152 -0.1700 +vn -0.4716 0.6078 -0.6388 +vn 0.1162 0.7440 -0.6579 +vn 0.8852 0.2964 -0.3585 +vn 0.1016 0.6854 0.7210 +vn 0.0494 0.6641 0.7460 +vn 0.0645 0.7274 0.6831 +vn 0.0204 0.7614 0.6480 +vn -0.0708 0.7278 0.6821 +vn -0.0478 0.7435 0.6670 +vn -0.0688 0.6945 0.7162 +vn -0.0599 0.6761 0.7344 +vn 0.0160 0.7753 0.6314 +vn -0.0022 0.6532 0.7572 +vn -0.0234 0.6550 0.7552 +vn 0.6780 0.5140 -0.5254 +vn 0.7837 0.3543 -0.5101 +vn 0.7059 0.4772 -0.5235 +vn 0.5729 0.6307 -0.5235 +vn -0.0634 0.6690 -0.7405 +vn -0.1360 0.6936 -0.7074 +vn -0.1749 0.7049 -0.6874 +vn -0.2459 0.7220 -0.6467 +vn -0.8979 0.3383 -0.2817 +vn -0.7957 0.3730 -0.4772 +vn -0.8765 0.3486 -0.3319 +vn -0.9415 0.3055 -0.1423 +vn -0.8341 -0.3751 0.4045 +vn -0.9508 -0.2807 0.1314 +vn -0.7478 -0.4944 0.4430 +vn -0.6321 -0.5125 0.5811 +vn -0.4318 -0.6764 0.5968 +vn 0.2018 -0.6448 0.7372 +vn 0.2342 -0.6580 0.7157 +vn 0.2242 -0.6540 0.7225 +vn 0.2624 -0.6687 0.6957 +vn 0.9616 -0.1649 0.2195 +vn 0.9114 -0.3378 0.2349 +vn 0.9583 -0.1807 0.2212 +vn 0.9792 -0.0203 0.2018 +vn 0.9266 0.3386 -0.1635 +vn 0.9733 0.1613 -0.1636 +vn 0.9725 0.1659 -0.1636 +vn 0.9872 -0.0167 -0.1583 +vn -0.7708 0.5294 -0.3544 +vn -0.6856 0.5136 -0.5159 +vn -0.6881 0.5143 -0.5119 +vn -0.5804 0.4817 -0.6566 +vn -0.1558 -0.6054 0.7805 +vn -0.2877 -0.6783 0.6761 +vn -0.2844 -0.6767 0.6791 +vn -0.4070 -0.7275 0.5524 +vn 0.0000 -0.7071 -0.7071 +vn 0.1752 0.6266 0.7594 +vn -0.0314 -0.7115 -0.7020 +vn -0.0108 -0.7284 -0.6851 +vn -0.0427 -0.7193 -0.6934 +vn 0.0253 -0.7235 -0.6898 +vn 0.0189 -0.7350 -0.6778 +vn 0.0314 -0.6988 -0.7146 +vn 0.0454 -0.7178 -0.6947 +vn -0.0342 -0.6954 -0.7178 +vn -0.0175 -0.6860 -0.7274 +vn 0.0085 -0.6840 -0.7295 +vn 0.0159 -0.6728 -0.7396 +vn -0.0269 0.7035 0.7102 +vn -0.0246 0.7332 0.6796 +vn -0.0150 0.7026 0.7114 +vn -0.0218 0.6913 0.7222 +vn -0.0651 0.7024 0.7088 +vn -0.0096 0.6891 0.7246 +vn -0.0990 0.6859 -0.7209 +vn 0.2016 0.7072 -0.6777 +vn -0.0610 0.6921 -0.7192 +vn 0.2492 0.7044 -0.6646 +vn 0.9791 0.1358 -0.1514 +vn 0.9945 0.0788 -0.0695 +vn 0.9813 0.1295 -0.1422 +vn 0.9959 0.0701 -0.0570 +vn 0.3382 -0.6841 0.6463 +vn 0.6482 -0.5202 0.5561 +vn 0.6059 -0.5500 0.5748 +vn 0.3033 -0.6960 0.6508 +vn -0.3912 -0.6213 0.6789 +vn -0.9790 -0.1595 0.1270 +vn -0.9779 -0.1626 0.1316 +vn -0.9781 -0.1620 0.1307 +vn -0.9792 -0.1590 0.1262 +vn -0.7215 0.5172 -0.4604 +vn -0.0587 0.7412 0.6687 +vn -0.0009 0.7571 0.6533 +vn -0.0706 0.7249 0.6853 +vn 0.0452 0.7456 0.6649 +vn 0.0641 0.7431 0.6661 +vn -0.0443 0.6435 0.7642 +vn 0.0186 0.6559 0.7546 +vn 0.0658 0.6723 0.7373 +vn -0.0659 0.6757 0.7342 +vn 0.0704 0.6983 0.7123 +vn -0.4318 0.6231 -0.6522 +vn -0.7263 0.4343 -0.5328 +vn -0.5855 0.5996 -0.5456 +vn -0.9927 -0.0274 0.1174 +vn -0.9973 -0.0206 0.0701 +vn -0.9941 -0.0257 0.1058 +vn -0.9892 -0.0311 0.1434 +vn -0.7304 -0.5341 0.4258 +vn -0.3724 -0.6763 0.6355 +vn -0.4863 -0.5773 0.6559 +vn -0.1839 -0.6655 0.7234 +vn 0.0639 -0.7673 0.6381 +vn 0.7146 -0.4368 0.5464 +vn 0.7256 -0.4377 0.5310 +vn 0.7218 -0.4374 0.5363 +vn 0.7358 -0.4383 0.5163 +vn 0.9811 0.1569 -0.1129 +vn 0.9964 -0.0765 -0.0374 +vn 0.9936 0.0732 -0.0863 +vn 0.9453 0.2879 -0.1536 +vn 0.6596 0.4793 -0.5789 +vn 0.3154 0.6409 -0.6998 +vn 0.5077 0.6181 -0.6002 +vn -0.0375 0.7475 -0.6632 +vn -0.9402 -0.0160 0.3402 +vn -0.9777 0.0550 -0.2029 +vn -0.2126 -0.7903 0.5747 +vn 0.6816 -0.2928 0.6706 +vn 0.9719 -0.2342 0.0226 +vn 0.2566 0.7654 -0.5902 +vn 0.2382 0.7791 -0.5799 +vn 0.2347 0.7816 -0.5779 +vn 0.2122 0.7974 -0.5649 +vn -0.0969 -0.3282 0.9396 +vn -0.1576 -0.2785 0.9474 +vn 0.0434 -0.4331 0.9003 +vn -0.4439 -0.8772 0.1831 +vn -0.8563 0.1863 0.4818 +vn -0.8331 -0.0821 -0.5470 +vn -0.2723 0.9357 -0.2241 +vn 0.2229 0.1828 -0.9575 +vn 0.8060 0.5442 0.2329 +vn 0.9209 -0.3820 -0.0782 +vn 0.9142 -0.3427 -0.2161 +vn 0.9089 -0.3305 -0.2544 +vn 0.5629 0.7422 -0.3637 +vn 0.8707 -0.2729 -0.4092 +vn -0.9092 0.1992 -0.3657 +vn -0.8950 0.1728 -0.4111 +vn -0.9352 0.2741 -0.2242 +vn -0.9389 0.3075 -0.1544 +vn -0.8421 -0.1244 0.5248 +vn -0.5830 -0.8077 0.0874 +vn -0.0915 -0.4091 0.9079 +vn 0.3547 -0.8241 0.4417 +vn 0.6611 -0.3041 0.6859 +vn 0.8823 -0.4697 -0.0296 +vn 0.8351 0.5225 0.1723 +vn 0.7473 0.1635 -0.6440 +vn -0.0024 0.8023 -0.5969 +vn -0.0009 0.7992 -0.6011 +vn -0.0057 0.8088 -0.5880 +vn -0.0066 0.8105 -0.5856 +vn -0.3075 -0.1441 0.9406 +vn -0.9245 -0.3760 -0.0631 +vn -0.0001 0.7070 0.7072 +vn 0.0000 0.7072 0.7071 +vn -0.0001 0.7069 0.7073 +vn -0.0004 0.7072 0.7070 +vn -0.0002 0.7072 0.7070 +vn -0.0001 0.7071 0.7071 +vn 0.0000 0.7071 0.7071 +vn -0.0005 0.7070 0.7072 +vn 0.0001 -0.7071 -0.7071 +vn 0.0004 -0.7073 -0.7069 +vn 0.0003 -0.7071 -0.7071 +vn -0.0002 -0.7074 -0.7068 +vn -0.0001 -0.7073 -0.7069 +vn 0.8831 0.4588 -0.0980 +vn 0.8750 0.4685 -0.1219 +vn 0.8963 0.4400 -0.0557 +vn 0.9053 -0.2477 -0.3451 +vn 0.5175 -0.2550 0.8168 +vn -0.0506 -0.9671 0.2492 +vn -0.4067 -0.5388 0.7377 +vn -0.9923 0.0412 -0.1171 +vn -0.9959 0.0779 -0.0452 +vn -0.9516 -0.0567 -0.3021 +vn -0.9319 -0.0844 -0.3528 +vn -0.6665 0.4557 -0.5900 +vn 0.2896 -0.8371 0.4641 +vn 0.8349 0.0826 0.5441 +vn 0.8761 -0.3585 -0.3223 +vn 0.5939 0.7622 -0.2577 +vn 0.3287 0.3044 -0.8940 +vn -0.3317 0.9178 -0.2182 +vn -0.6828 0.0936 -0.7246 +vn -0.9379 0.2242 0.2646 +vn -0.9560 0.1660 0.2420 +vn -0.9872 -0.0759 0.1403 +vn -0.9809 -0.1678 0.0985 +vn -0.4803 -0.6207 0.6197 +vn 0.8555 0.4885 -0.1716 +vn 0.0619 0.4692 0.8809 +vn 0.0331 0.5880 0.8082 +vn 0.0216 0.6315 0.7751 +vn -0.0944 0.6347 0.7669 +vn -0.1059 0.6251 0.7734 +vn -0.2204 0.5180 0.8265 +vn -0.0781 -0.8274 -0.5561 +vn -0.0409 -0.7739 -0.6320 +vn -0.0298 -0.7566 -0.6532 +vn 0.0039 -0.8581 -0.5134 +vn 0.0063 -0.9262 -0.3770 +vn 0.0015 -0.7710 -0.6368 +vn -0.3725 -0.8010 -0.4686 +vn -0.3568 -0.8019 -0.4791 +vn -0.4483 -0.7921 -0.4142 +vn -0.6499 -0.0363 -0.7592 +vn -0.8897 -0.2207 0.3997 +vn -0.4899 0.8261 0.2785 +vn -0.2934 0.5594 0.7752 +vn 0.6730 0.6521 0.3491 +vn 0.8158 -0.0390 0.5770 +vn 0.9305 0.0731 -0.3589 +vn 0.9053 0.2674 -0.3300 +vn 0.8835 0.3480 -0.3136 +vn 0.2085 0.3226 0.9233 +vn 0.8017 0.5368 -0.2630 +vn -0.9814 0.1824 -0.0604 +vn -0.9684 0.2332 -0.0889 +vn -0.9938 -0.0748 0.0821 +vn -0.9845 -0.1334 0.1140 +vn -0.3206 -0.5427 -0.7763 +vn -0.3164 -0.5623 -0.7640 +vn -0.3369 -0.4521 -0.8259 +vn -0.3423 -0.4154 -0.8428 +vn 0.5709 -0.7850 -0.2406 +vn 0.7660 0.0658 -0.6395 +vn 0.9308 -0.2262 0.2873 +vn 0.7485 0.6418 0.1669 +vn 0.5492 0.4155 0.7251 +vn -0.0315 0.8019 0.5966 +vn -0.0007 0.8392 0.5438 +vn -0.1178 0.6738 0.7295 +vn -0.1519 0.6129 0.7754 +vn -0.2705 -0.8019 -0.5327 +vn -0.5645 -0.3380 -0.7531 +vn -0.0002 -0.7071 0.7072 +vn -0.0001 -0.7071 0.7071 +vn 0.0000 -0.7073 0.7069 +vn -0.0003 -0.7070 0.7072 +vn -0.0004 -0.7071 0.7072 +vn -0.0001 -0.7072 0.7071 +vn 0.0001 -0.7073 0.7069 +vn -0.0001 -0.7070 0.7072 +vn -0.0002 -0.7070 0.7072 +vn 0.0001 0.7072 -0.7070 +vn 0.0000 0.7072 -0.7071 +vn 0.0001 0.7073 -0.7069 +vn 0.0002 0.7073 -0.7070 +vn -0.0125 -0.9568 0.2904 +vn -0.0254 -0.9761 0.2158 +vn -0.0894 -0.9094 0.4062 +vn 0.0531 -0.9819 0.1816 +vn -0.0478 -0.9984 -0.0315 +vn -0.0092 -0.9520 -0.3060 +vn 0.0044 -0.9328 -0.3604 +vn -0.0096 -0.8664 -0.4992 +vn -0.0012 -0.8647 -0.5023 +vn 0.0013 0.4199 0.9076 +vn 0.1207 0.2698 0.9553 +vn 0.0064 0.0345 0.9994 +vn 0.0016 -0.0893 0.9960 +vn -0.0049 -0.3192 0.9477 +vn 0.0095 -0.4088 0.9126 +vn 0.0182 -0.4983 0.8668 +vn -0.0015 -0.5068 0.8621 +vn -0.0228 0.2399 0.9705 +vn 0.0003 0.8955 0.4451 +vn 0.0002 0.8952 0.4456 +vn -0.0000 0.9448 0.3275 +vn 0.0000 0.9450 0.3272 +vn -0.0001 0.9972 0.0745 +vn 0.0000 0.9972 0.0742 +vn -0.0000 0.9754 -0.2206 +vn -0.0079 0.9794 -0.2017 +vn 0.0014 0.9706 -0.2409 +vn -0.0115 0.9212 -0.3890 +vn 0.0004 0.8911 -0.4539 +vn 0.0149 -0.2281 0.9735 +vn 0.0019 -0.1786 0.9839 +vn 0.0012 -0.4439 0.8961 +vn 0.0245 -0.6200 0.7842 +vn -0.0008 -0.6489 0.7609 +vn 0.0025 -0.8057 0.5924 +vn 0.0253 -0.9193 0.3927 +vn -0.0065 -0.9210 0.3896 +vn 0.0014 -0.9891 0.1474 +vn 0.0205 -0.9984 -0.0527 +vn 0.0053 -0.9928 -0.1199 +vn 0.0021 -0.9384 -0.3456 +vn 0.0168 -0.8962 -0.4432 +vn 0.0067 -0.8215 -0.5702 +vn 0.0215 -0.6113 -0.7911 +vn 0.0081 -0.6749 -0.7379 +vn 0.0049 -0.4686 -0.8834 +vn 0.0046 -0.2062 -0.9785 +vn 0.0119 -0.2251 -0.9743 +vn 0.0012 0.9293 -0.3694 +vn 0.0002 0.9291 -0.3697 +vn 0.0184 0.9830 -0.1827 +vn 0.0304 0.9746 -0.2220 +vn -0.0242 0.9921 0.1234 +vn 0.0094 0.9711 0.2385 +vn 0.0096 0.9309 0.3652 +vn -0.0108 0.9282 0.3719 +vn -0.0161 -0.2682 -0.9632 +vn -0.0041 -0.2175 -0.9761 +vn -0.0520 -0.2572 -0.9650 +vn -0.0318 -0.3834 -0.9230 +vn 0.0638 -0.0057 -0.9979 +vn -0.0251 0.1832 -0.9828 +vn 0.0246 0.3437 -0.9388 +vn -0.0094 0.4187 -0.9081 +vn -0.0147 0.2349 -0.9719 +vn 0.9987 0.0474 0.0166 +vn 0.9984 0.0546 0.0162 +vn 0.9993 0.0334 0.0152 +vn 0.9997 0.0220 0.0051 +vn 0.9997 0.0224 0.0006 +vn 0.9997 0.0245 -0.0056 +vn 0.9998 0.0214 -0.0029 +vn 0.9990 0.0395 -0.0210 +vn 0.9987 0.0436 -0.0247 +vn -0.0130 0.1161 -0.9932 +vn 0.0044 -0.0194 -0.9998 +vn 0.0257 -0.0412 -0.9988 +vn -0.0025 -0.0399 -0.9992 +vn -0.0428 -0.0161 -0.9990 +vn 0.0217 -0.0351 -0.9991 +vn -0.0621 -0.0108 -0.9980 +vn 0.0014 -0.5417 -0.8406 +vn -0.0062 -0.6366 -0.7712 +vn -0.0078 -0.3631 -0.9317 +vn -0.0003 -0.0417 -0.9991 +vn 0.0048 -0.0430 -0.9991 +vn 0.0013 -0.0618 -0.9981 +vn 0.0005 -0.0312 -0.9995 +vn 0.0001 -0.0329 -0.9995 +vn 1.0000 -0.0008 0.0015 +vn 0.9999 0.0031 0.0112 +vn 1.0000 0.0019 -0.0002 +vn 0.0037 0.7142 -0.6999 +vn 0.0028 0.7172 -0.6968 +vn 0.0036 0.7146 -0.6995 +vn 0.0027 0.7177 -0.6964 +vn -0.6921 0.6582 0.2963 +vn -0.6840 0.6896 0.2380 +vn -0.6870 0.6610 0.3018 +vn -0.6712 0.6742 -0.3081 +vn -0.6841 0.6585 -0.3138 +vn -0.6727 0.6806 -0.2902 +vn -0.6853 0.6848 0.2476 +vn -0.6997 0.7111 0.0693 +vn -0.7035 0.7096 0.0383 +vn -0.6837 0.7070 -0.1807 +vn -0.6845 0.7184 -0.1240 +vn 0.6483 0.7517 -0.1212 +vn 0.7041 0.6928 0.1556 +vn 0.7058 0.6913 -0.1546 +vn 0.7074 0.7051 0.0492 +vn 0.7126 0.6992 0.0574 +vn 0.7068 0.6842 -0.1795 +vn 0.7014 0.6739 0.2321 +vn 0.7102 0.6561 0.2554 +vn 0.6885 0.6496 0.3223 +vn 0.6710 0.6700 0.3174 +vn -0.8835 0.3600 -0.2997 +vn -0.9047 0.2978 -0.3045 +vn -0.9013 0.3089 -0.3038 +vn -0.9239 0.2263 -0.3084 +vn -0.8244 -0.3540 0.4417 +vn 0.9689 0.1455 -0.2001 +vn 0.9727 0.1425 -0.1831 +vn 0.9737 0.1416 -0.1786 +vn 0.9815 0.1340 -0.1370 +vn 0.6215 -0.5010 0.6022 +vn 0.0652 0.6766 -0.7334 +vn 0.1384 0.7034 -0.6972 +vn 0.1116 0.6942 -0.7111 +vn 0.1898 0.7193 -0.6683 +vn 0.9999 -0.0120 0.0103 +vn 1.0000 -0.0007 0.0012 +vn 0.9999 -0.0127 0.0106 +vn 0.9966 0.0307 -0.0760 +vn 0.9875 0.1220 -0.1002 +vn 0.9838 -0.1783 -0.0188 +vn 0.9428 0.2999 -0.1453 +vn 0.6238 0.4961 -0.6040 +vn -0.0950 0.7160 -0.6916 +vn -0.1688 0.7430 -0.6477 +vn -0.1295 0.7293 -0.6719 +vn -0.0609 0.7016 -0.7099 +vn -0.9546 0.2248 -0.1955 +vn -0.9624 0.1644 -0.2163 +vn -0.9657 0.1172 -0.2317 +vn -0.9650 0.0205 -0.2613 +vn -0.3859 -0.4839 0.7854 +vn 0.4558 -0.2876 0.8423 +vn -0.0002 0.7366 0.6764 +vn -0.0177 0.7440 0.6679 +vn 0.0036 0.7428 0.6695 +vn 0.0019 0.8466 0.5322 +vn 0.0234 0.9153 0.4020 +vn 0.0144 0.9287 0.3706 +vn -0.0074 0.9417 0.3364 +vn 0.8350 0.3606 0.4156 +vn 0.7950 0.4085 0.4485 +vn 0.6193 0.7081 0.3392 +vn 0.5497 0.8287 0.1050 +vn 0.0069 0.9979 -0.0641 +vn 0.0045 0.1750 0.9846 +vn 0.0189 0.0018 0.9998 +vn 0.0357 0.0198 0.9992 +vn 0.0022 -0.0422 0.9991 +vn 0.0062 -0.0391 0.9992 +vn -0.0000 -0.0379 0.9993 +vn 0.0252 -0.0430 0.9988 +vn -0.0000 -0.0378 0.9993 +vn 0.0723 -0.9373 0.3410 +vn 0.0405 -0.8608 0.5073 +vn 0.0183 -0.7265 0.6869 +vn 0.0127 -0.5626 0.8266 +vn -0.0002 -0.4374 0.8993 +vn -0.0016 -0.5173 0.8558 +vn 0.0134 -0.0294 0.9995 +vn 0.0362 -0.0391 0.9986 +vn -0.0008 0.7882 0.6155 +vn -0.0015 0.0134 0.9999 +vn 0.0032 -0.0245 0.9997 +vn 0.0158 0.0075 0.9998 +vn 0.0049 -0.0237 0.9997 +vn 0.0066 -0.0190 0.9998 +vn 0.0821 -0.0417 0.9958 +vn 0.0090 -0.6179 0.7862 +vn 0.9999 -0.0064 -0.0119 +vn 1.0000 -0.0014 -0.0024 +vn 1.0000 -0.0038 0.0042 +vn 1.0000 0.0051 0.0062 +vn 0.9998 -0.0139 -0.0142 +vn 0.0058 -0.7188 -0.6952 +vn -0.0241 -0.7111 -0.7027 +vn -0.0073 -0.7147 -0.6994 +vn 0.0502 -0.7206 -0.6916 +vn -0.0137 0.7107 0.7034 +vn -0.0087 0.7116 0.7026 +vn -0.0041 -0.7602 -0.6496 +vn -0.0006 -0.7176 -0.6964 +vn -0.0010 -0.7209 -0.6930 +vn -0.0210 -0.7256 0.6878 +vn 0.0017 -0.7184 0.6956 +vn 0.0100 -0.7130 0.7011 +vn 0.0002 -0.7069 -0.7073 +vn 0.0000 -0.7069 -0.7073 +vn -0.0169 0.7216 -0.6921 +vn -0.0836 0.7093 -0.6999 +vn 0.0010 0.8483 -0.5295 +vn 1.0000 0.0071 -0.0064 +vn 0.0101 -0.7169 0.6971 +vn 0.0273 -0.7117 0.7019 +vn 0.0035 0.7152 0.6989 +vn 0.0036 0.7155 0.6986 +vn 0.0036 0.7153 0.6988 +vn 0.8835 0.3600 0.2997 +vn 0.9047 0.2978 0.3045 +vn 0.9013 0.3089 0.3038 +vn 0.9239 0.2263 0.3084 +vn 0.8215 -0.3565 -0.4450 +vn -0.9689 0.1455 0.2001 +vn -0.9727 0.1425 0.1831 +vn -0.9737 0.1416 0.1786 +vn -0.9815 0.1340 0.1370 +vn -0.6218 -0.5010 -0.6020 +vn -0.0652 0.6766 0.7334 +vn -0.1384 0.7034 0.6972 +vn -0.1116 0.6942 0.7111 +vn -0.1898 0.7193 0.6683 +vn 0.0021 0.7426 -0.6698 +vn -0.0283 0.7452 -0.6663 +vn -0.0015 0.7381 -0.6747 +vn -0.0003 -0.7070 -0.7072 +vn 0.9877 0.1534 0.0303 +vn 0.8903 -0.3664 -0.2704 +vn -0.9645 0.1594 0.2106 +vn -0.9034 0.3440 0.2562 +vn -0.9414 0.2442 0.2326 +vn -0.9839 0.0348 0.1753 +vn -0.8175 -0.2571 -0.5154 +vn -0.4820 -0.8672 -0.1251 +vn -0.4210 0.6178 0.6642 +vn -0.2742 0.6951 0.6645 +vn -0.4955 0.5689 0.6564 +vn -0.1875 0.7305 0.6566 +vn 0.6174 0.4893 0.6159 +vn 0.5763 0.5386 0.6147 +vn 0.5965 0.5150 0.6156 +vn 0.5524 0.5650 0.6128 +vn 0.9999 0.0037 -0.0133 +vn 0.9995 0.0293 0.0081 +vn 1.0000 0.0026 -0.0038 +vn -0.0082 -0.7194 0.6946 +vn -0.0378 -0.7175 0.6956 +vn 0.0209 -0.7092 0.7047 +vn 0.0232 0.9158 -0.4009 +vn -0.0028 0.9390 -0.3438 +vn 0.0159 0.9279 -0.3726 +vn 0.7920 0.4290 -0.4344 +vn 0.7213 0.4555 -0.5218 +vn 0.7837 0.4326 -0.4457 +vn 0.7007 0.4616 -0.5441 +vn 0.5247 0.8265 -0.2040 +vn -0.0220 0.0545 0.9983 +vn -0.0155 0.0636 0.9979 +vn -0.0172 0.0607 0.9980 +vn -0.0101 0.0705 0.9975 +vn -0.0682 -0.8014 0.5943 +vn 0.0254 -0.6757 0.7367 +vn -0.0205 -0.7414 0.6708 +vn 0.0731 -0.5994 0.7971 +vn -0.0171 -0.9997 -0.0195 +vn 0.0271 -0.9971 -0.0708 +vn 0.9996 -0.0111 0.0271 +vn 0.9996 -0.0189 0.0195 +vn 0.9996 -0.0096 0.0270 +vn 0.9997 -0.0050 0.0259 +vn 0.9998 0.0048 0.0175 +vn 0.9999 0.0071 0.0146 +vn 0.9998 -0.0156 0.0118 +vn 0.9996 -0.0127 -0.0265 +vn 0.9997 -0.0144 -0.0179 +vn 0.9984 -0.0044 -0.0561 +vn 0.9996 -0.0269 0.0067 +vn -0.0010 -0.9965 0.0840 +vn -0.0056 -0.9970 0.0777 +vn -0.0040 -0.9968 0.0799 +vn -0.0084 -0.9972 0.0736 +vn 0.0001 -0.8121 -0.5835 +vn 0.0133 -0.7992 -0.6010 +vn 0.0065 -0.8061 -0.5917 +vn -0.0070 -0.8188 -0.5740 +vn -0.0234 0.0123 -0.9997 +vn 0.0044 0.0446 -0.9990 +vn 0.9998 -0.0201 0.0090 +vn 0.9999 -0.0136 -0.0015 +vn 0.9998 -0.0214 0.0063 +vn 0.9999 -0.0134 -0.0007 +vn 0.9998 -0.0218 -0.0025 +vn 0.9996 -0.0263 -0.0139 +vn 0.9992 -0.0372 -0.0128 +vn 0.9996 -0.0079 -0.0283 +vn 0.9995 -0.0050 -0.0309 +vn 0.9990 -0.0052 -0.0444 +vn 0.9991 -0.0047 -0.0429 +vn -0.9921 0.0144 0.1245 +vn -0.9992 0.0129 -0.0383 +vn -0.9972 -0.0253 -0.0710 +vn -0.9941 0.0421 -0.0995 +vn -0.9978 -0.0168 -0.0643 +vn -0.9966 -0.0056 -0.0826 +vn -0.9956 0.0158 0.0926 +vn -0.9974 0.0219 0.0683 +vn -0.9946 0.0496 0.0913 +vn -0.9985 -0.0185 -0.0513 +vn -0.9944 0.0365 -0.0997 +vn -0.9992 0.0238 -0.0327 +vn -0.9996 0.0232 -0.0175 +vn -0.9999 0.0068 -0.0157 +vn -0.9997 0.0212 -0.0079 +vn -0.9999 -0.0146 -0.0037 +vn -0.9998 -0.0180 -0.0094 +vn -0.9998 -0.0105 -0.0163 +vn -0.9992 -0.0145 -0.0368 +vn -0.9991 0.0370 -0.0191 +vn -0.9995 -0.0300 -0.0114 +vn -0.9998 -0.0106 0.0152 +vn -0.9994 -0.0124 0.0335 +vn -0.9998 -0.0178 0.0102 +vn -0.9988 -0.0156 0.0474 +vn -0.9970 -0.0334 0.0692 +vn -0.9887 0.1359 -0.0641 +vn -0.9966 0.0807 -0.0171 +vn -0.9965 -0.0777 -0.0320 +vn -0.9964 -0.0812 -0.0228 +vn -0.9947 0.1030 0.0015 +vn -0.9914 -0.1307 -0.0059 +vn -0.9975 0.0004 0.0700 +vn -0.9967 -0.0783 0.0193 +vn -0.9884 0.1509 0.0179 +vn -0.9963 -0.0856 0.0099 +vn -0.9971 0.0719 0.0266 +vn -0.9963 0.0755 0.0419 +vn -0.9969 -0.0728 0.0311 +vn -0.9996 -0.0279 0.0104 +vn -0.9993 0.0339 0.0143 +vn -0.9996 0.0228 0.0164 +vn -0.9999 -0.0124 0.0038 +vn -0.9998 0.0187 0.0075 +vn -0.9999 0.0048 0.0117 +vn -0.9993 0.0245 0.0293 +vn -0.9922 -0.0252 0.1221 +vn 0.6979 -0.1521 -0.6999 +vn 0.6901 -0.0303 -0.7230 +vn 0.6897 -0.0305 -0.7235 +vn 0.7010 -0.1466 -0.6979 +vn 0.0489 -0.0432 -0.9979 +vn 0.5698 -0.3818 0.7277 +vn 0.5722 -0.4387 0.6929 +vn 0.6034 -0.4891 0.6299 +vn 0.5432 -0.8145 0.2039 +vn 0.5815 -0.7712 0.2592 +vn 0.5733 -0.7095 0.4098 +vn 0.5300 -0.8446 -0.0757 +vn 0.5392 -0.8412 0.0399 +vn 0.7004 -0.7129 -0.0337 +vn 0.4959 -0.8251 -0.2708 +vn 0.6785 -0.6561 -0.3304 +vn 0.5727 -0.6536 -0.4948 +vn 0.5800 -0.6551 -0.4842 +vn 0.6165 -0.5509 -0.5626 +vn 0.6849 -0.3228 -0.6532 +vn 0.7116 -0.3925 -0.5827 +vn 0.6156 -0.5527 0.5617 +vn 0.4879 -0.7142 0.5019 +vn 0.7030 -0.0841 0.7062 +vn 0.7262 -0.1655 0.6672 +vn 0.8903 -0.4198 0.1766 +vn 0.6049 -0.7952 0.0413 +vn -0.5802 -0.4149 0.7008 +vn 0.5499 -0.6861 0.4763 +vn 0.9378 -0.3366 -0.0849 +vn 0.7477 -0.0287 0.6634 +vn 0.7444 -0.0295 0.6671 +vn 0.1021 -0.0421 0.9939 +vn 0.6314 0.5620 0.5344 +vn 0.5844 0.5883 -0.5589 +vn 0.6686 0.6700 -0.3227 +vn 0.9946 0.1040 0.0065 +vn 0.6575 0.6691 0.3465 +vn -0.0090 -0.9819 0.1892 +vn 0.0269 -0.9658 0.2581 +vn -0.0352 -0.9534 0.2995 +vn 0.0792 -0.9957 -0.0480 +vn 0.1795 -0.9791 0.0952 +vn -0.1735 -0.9756 -0.1346 +vn -0.0337 -0.9986 0.0406 +vn 0.0049 -0.9854 -0.1700 +vn 0.0243 -0.9526 -0.3033 +vn 0.0030 -0.9883 -0.1524 +vn -0.0116 -0.9972 0.0745 +vn -0.1088 -0.9941 -0.0024 +vn 0.0066 -0.9449 -0.3273 +vn 0.2252 -0.8949 -0.3853 +vn -0.0134 -0.9155 -0.4021 +vn -0.0352 -0.9425 -0.3324 +vn -0.0202 -0.9407 -0.3387 +vn 0.0112 -0.9984 -0.0548 +vn -0.1635 -0.9582 -0.2348 +vn 0.1763 -0.9203 0.3494 +vn 0.3571 -0.9315 0.0698 +vn -0.1419 -0.9672 0.2107 +vn -0.0038 -0.9118 0.4106 +vn 0.1339 -0.9076 0.3980 +vn 0.0023 -0.9482 0.3176 +vn 0.0003 -0.9311 0.3646 +vn 0.0069 -0.8924 0.4511 +vn 0.0042 -0.9676 0.2525 +vn 0.0030 -0.8440 0.5364 +vn 0.0180 -0.9901 0.1391 +vn 0.0042 -0.9956 0.0935 +vn -0.6836 -0.6891 0.2405 +vn -0.8750 -0.4750 -0.0930 +vn -0.7143 -0.6870 0.1331 +vn -0.7010 -0.6984 0.1444 +vn -0.7108 -0.6965 -0.0978 +vn -0.6791 -0.7337 0.0213 +vn -0.7134 -0.6863 -0.1417 +vn -0.8754 -0.4746 0.0917 +vn -0.6657 -0.7042 -0.2468 +vn -0.0110 -0.8878 -0.4601 +vn 0.0017 -0.9696 -0.2447 +vn -0.0212 -0.9892 -0.1452 +vn -0.0008 -0.9112 -0.4120 +vn 0.0060 -0.8475 -0.5308 +vn 0.6827 -0.6922 -0.2342 +vn 0.7130 -0.6921 -0.1121 +vn 0.6849 -0.6760 -0.2718 +vn 0.6609 -0.7500 0.0279 +vn 0.7157 -0.6813 0.1537 +vn 0.5860 -0.7685 0.2569 +vn 0.8731 -0.4771 -0.1001 +vn 0.5313 -0.2421 0.8118 +vn 0.3646 0.0239 0.9309 +vn 0.0009 -0.1764 0.9843 +vn 0.8979 -0.3631 0.2487 +vn 0.9941 -0.1052 0.0260 +vn 0.7266 -0.1141 0.6775 +vn 0.8899 -0.2870 -0.3545 +vn 0.9947 -0.1016 -0.0166 +vn 0.9951 -0.0974 0.0140 +vn 0.9983 -0.0296 0.0497 +vn 0.9969 -0.0757 -0.0230 +vn 0.9977 -0.0666 -0.0126 +vn 0.8276 -0.2779 -0.4876 +vn 0.5633 -0.7122 -0.4190 +vn 0.5462 -0.6871 -0.4791 +vn 0.7461 -0.5922 -0.3044 +vn 0.9190 -0.3634 -0.1529 +vn 0.6641 -0.7447 -0.0658 +vn 0.6630 -0.7356 0.1390 +vn 0.8973 -0.3136 0.3107 +vn 0.6587 -0.6885 0.3036 +vn 0.7660 -0.2718 0.5826 +vn 0.5719 -0.7047 0.4199 +vn 0.5592 -0.6892 0.4607 +vn 0.1364 -0.6922 0.7087 +vn 0.2096 -0.6915 0.6913 +vn 0.2007 -0.7141 0.6706 +vn -0.1256 -0.6870 0.7157 +vn 0.0324 -0.6657 0.7455 +vn -0.2064 -0.6694 0.7136 +vn -0.2457 -0.6378 0.7300 +vn 0.3437 -0.1636 0.9247 +vn 0.6086 0.0130 0.7933 +vn 0.3288 -0.2037 0.9222 +vn 0.0269 0.2311 0.9726 +vn 0.0294 0.2480 0.9683 +vn -0.2180 -0.0879 0.9720 +vn -0.1467 -0.0984 0.9843 +vn -0.2059 -0.0661 0.9763 +vn -0.3633 0.0098 0.9316 +vn -0.5376 0.0330 0.8425 +vn -0.7148 -0.2149 0.6655 +vn -0.6401 -0.1372 0.7560 +vn -0.6520 -0.6532 0.3850 +vn -0.8142 0.4166 0.4044 +vn -0.8614 -0.4360 0.2606 +vn -0.8374 -0.4836 0.2547 +vn -0.9395 -0.2329 -0.2514 +vn -0.9833 0.1801 -0.0255 +vn -0.9782 0.2069 -0.0192 +vn -0.9641 -0.2114 -0.1610 +vn -0.6350 -0.6870 -0.3532 +vn -0.8672 0.2776 -0.4134 +vn -0.5764 0.0261 -0.8168 +vn -0.6290 0.0038 -0.7774 +vn -0.7152 -0.1191 -0.6887 +vn -0.7182 -0.1433 -0.6809 +vn -0.5405 -0.0183 -0.8412 +vn -0.3234 -0.0516 -0.9449 +vn -0.4813 0.0227 -0.8763 +vn -0.1620 0.0977 -0.9819 +vn 0.1484 -0.0156 -0.9888 +vn 0.1294 -0.0297 -0.9912 +vn 0.4867 0.0279 -0.8731 +vn 0.3180 -0.0668 -0.9457 +vn 0.2029 -0.0575 -0.9775 +vn 0.6022 0.0284 -0.7978 +vn 0.6907 -0.1535 -0.7066 +vn 0.7002 -0.1998 -0.6854 +vn 0.9469 -0.0894 -0.3089 +vn 0.8302 0.3060 -0.4661 +vn 0.9747 -0.1527 0.1630 +vn 0.9974 0.0726 -0.0051 +vn 0.8699 -0.0732 0.4877 +vn 0.0288 -0.9959 -0.0859 +vn 0.0245 -0.9700 -0.2419 +vn 0.0709 -0.9536 -0.2927 +vn -0.0005 -0.9998 -0.0175 +vn 0.0308 -0.9877 0.1535 +vn -0.0197 -0.9518 0.3060 +vn -0.0701 -0.9102 0.4083 +vn -0.0000 1.0000 -0.0000 +vn 0.0001 1.0000 0.0000 +vn -0.0001 1.0000 0.0000 +vn 0.0002 1.0000 -0.0000 +vn -0.0001 1.0000 -0.0001 +vn 0.7158 -0.6294 -0.3025 +vn 0.7035 -0.6104 0.3639 +vn 0.6795 -0.7026 0.2112 +vn -0.0156 -0.0869 0.9961 +vn -0.9945 -0.1028 -0.0187 +vn -0.8882 -0.2880 -0.3580 +vn -0.8875 -0.2902 0.3578 +vn -0.9938 -0.1108 -0.0096 +vn -0.9973 -0.0643 -0.0359 +vn -0.9977 -0.0670 -0.0087 +vn -0.9974 -0.0710 0.0105 +vn -0.9957 -0.0859 0.0345 +vn -0.5567 -0.6889 -0.4642 +vn -0.5599 -0.7023 -0.4397 +vn -0.5648 -0.7096 0.4213 +vn -0.7269 -0.6328 0.2667 +vn -0.6173 -0.7202 -0.3166 +vn -0.0396 -0.9953 0.0887 +vn -0.0613 -0.9587 0.2777 +vn -0.0924 -0.9516 0.2932 +vn 0.0039 -0.9915 0.1299 +vn -0.0281 -0.9974 -0.0666 +vn 0.0082 -0.9542 -0.2990 +vn -0.0014 -0.9744 -0.2248 +vn 0.0497 -0.9110 -0.4094 +vn -0.0039 -0.6937 0.7203 +vn -0.0012 -0.6995 0.7146 +vn -0.7093 -0.6390 0.2976 +vn -0.7924 -0.3933 0.4662 +vn -0.2284 -0.6850 -0.6918 +vn -0.1697 -0.6600 -0.7318 +vn 0.0104 -0.3051 -0.9523 +vn 0.0811 -0.5776 -0.8122 +vn 0.1089 -0.7203 -0.6851 +vn -0.0077 -0.0657 -0.9978 +vn -0.0024 -0.7012 -0.7130 +vn 0.0032 -0.6878 -0.7259 +vn 0.7027 -0.6136 -0.3602 +vn 0.7995 -0.3843 -0.4616 +vn -0.0082 -0.0596 -0.9982 +vn -0.7113 -0.6351 -0.3012 +vn -0.7934 -0.3907 -0.4668 +vn 0.9993 -0.0244 0.0274 +vn 0.9987 -0.0235 0.0448 +vn 0.9992 -0.0085 0.0401 +vn 0.9995 -0.0051 -0.0296 +vn 0.9997 0.0011 -0.0228 +vn 1.0000 0.0046 -0.0034 +vn 0.9993 -0.0284 -0.0243 +vn 0.9998 0.0094 -0.0198 +vn 0.9994 0.0334 -0.0104 +vn 0.9991 -0.0061 -0.0417 +vn 0.9992 -0.0288 -0.0262 +vn 0.9993 -0.0354 -0.0123 +vn 0.9905 -0.0243 0.1354 +vn 0.9985 -0.0252 0.0496 +vn 0.9969 -0.0216 0.0751 +vn 0.9994 0.0332 -0.0041 +vn 0.9991 0.0158 0.0394 +vn 0.9991 0.0276 0.0313 +vn 0.9995 0.0265 0.0182 +vn 0.9996 -0.0246 -0.0172 +vn 0.9998 -0.0167 -0.0129 +vn 0.9997 0.0221 -0.0041 +vn 0.9967 0.0804 -0.0089 +vn 0.9963 0.0770 -0.0383 +vn 0.9979 0.0611 -0.0190 +vn 0.9990 0.0383 -0.0241 +vn 0.9879 -0.1544 -0.0135 +vn 0.9631 -0.2449 -0.1117 +vn 0.9934 -0.1127 0.0225 +vn 0.9952 -0.0946 0.0254 +vn 0.9989 0.0474 0.0033 +vn 0.9969 0.0757 0.0228 +vn 0.9984 0.0492 0.0276 +vn 0.9990 -0.0395 0.0212 +vn 0.9986 0.0476 0.0230 +vn 0.9989 0.0466 -0.0060 +vn 0.9996 -0.0185 0.0209 +vn 0.9997 0.0244 0.0013 +vn 0.9988 0.0284 0.0404 +vn 0.9987 -0.0457 0.0236 +vn 0.9789 0.0218 0.2033 +vn -0.9985 -0.0416 0.0361 +vn -0.9985 -0.0485 0.0256 +vn -0.9988 -0.0370 0.0321 +vn -0.9988 -0.0413 0.0249 +vn -0.9991 -0.0238 0.0353 +vn -0.9988 0.0341 0.0346 +vn -0.9987 0.0393 0.0311 +vn -0.9987 0.0369 0.0356 +vn -0.9989 0.0354 0.0318 +vn -0.9989 0.0286 0.0368 +vn -0.9991 0.0292 -0.0311 +vn -0.9991 0.0346 -0.0243 +vn -0.9993 0.0380 -0.0005 +vn -0.9985 0.0282 -0.0466 +vn -0.9987 0.0357 -0.0365 +vn -0.2530 -0.9674 -0.0057 +vn -0.0338 -0.9396 0.3406 +vn -0.0886 -0.9520 -0.2931 +vn 0.1183 -0.9467 -0.2997 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 4/4/4 5/5/5 +f 5/5/5 4/4/4 6/6/6 +f 3/3/3 2/2/2 4/4/4 +f 5/5/5 7/7/7 1/1/8 +f 5/5/5 6/6/6 7/7/7 +f 8/8/9 9/9/10 10/10/11 +f 8/8/9 11/11/12 9/9/10 +f 12/12/13 8/8/14 13/13/15 +f 13/13/15 8/8/14 10/10/16 +f 13/13/17 10/10/18 9/9/19 +f 13/13/17 9/9/19 14/14/20 +f 14/14/21 9/9/21 15/15/21 +f 14/14/22 15/15/23 16/16/24 +f 16/16/24 15/15/23 11/11/25 +f 16/16/26 11/11/27 12/12/28 +f 12/12/28 11/11/27 8/8/29 +f 14/14/30 17/17/31 13/13/32 +f 13/13/32 17/17/31 18/18/33 +f 13/13/32 18/18/33 12/12/34 +f 12/12/34 18/18/33 19/19/35 +f 12/12/34 19/19/35 20/20/36 +f 12/12/34 20/20/36 16/16/37 +f 16/16/37 20/20/36 21/21/38 +f 16/16/37 21/21/38 14/14/30 +f 14/14/30 21/21/38 22/22/39 +f 14/14/30 22/22/39 17/17/31 +f 2/2/40 18/18/41 17/17/42 +f 2/2/40 17/17/42 4/4/43 +f 4/4/44 17/17/44 22/22/44 +f 4/4/45 22/22/45 6/6/45 +f 6/6/46 22/22/46 21/21/46 +f 6/6/47 21/21/48 7/7/49 +f 7/7/49 21/21/48 20/20/50 +f 7/7/51 20/20/52 1/1/53 +f 1/1/53 20/20/52 19/19/54 +f 1/1/55 19/19/56 18/18/57 +f 1/1/55 18/18/57 2/2/58 +f 3/3/59 5/5/60 23/23/61 +f 23/23/61 5/5/60 24/24/62 +f 1/1/63 3/3/64 25/25/65 +f 25/25/65 3/3/64 23/23/66 +f 5/5/67 1/1/68 24/24/69 +f 24/24/69 1/1/68 25/25/70 +f 24/24/71 25/25/71 23/23/71 +f 15/15/72 9/9/10 11/11/12 +f 26/26/73 27/27/73 28/28/73 +f 28/28/74 29/29/74 30/30/74 +f 30/30/75 31/31/75 26/26/75 +f 32/32/76 33/33/77 34/34/78 +f 35/35/79 32/32/76 34/34/78 +f 36/36/80 35/35/81 34/34/82 +f 36/36/80 34/34/82 37/37/83 +f 37/37/84 34/34/85 33/33/86 +f 37/37/84 33/33/86 38/38/87 +f 38/38/88 33/33/89 32/32/90 +f 38/38/88 32/32/90 39/39/91 +f 39/39/92 32/32/93 35/35/94 +f 39/39/92 35/35/94 36/36/95 +f 37/37/96 40/40/97 36/36/98 +f 36/36/98 40/40/97 41/41/99 +f 36/36/98 41/41/99 42/42/100 +f 36/36/98 42/42/100 39/39/101 +f 39/39/101 42/42/100 43/43/102 +f 39/39/101 43/43/102 38/38/103 +f 38/38/103 43/43/102 44/44/104 +f 38/38/103 44/44/104 37/37/96 +f 37/37/96 44/44/104 40/40/97 +f 27/27/105 41/41/106 40/40/107 +f 27/27/105 40/40/107 28/28/108 +f 28/28/109 40/40/110 29/29/111 +f 29/29/111 40/40/110 44/44/112 +f 29/29/113 44/44/113 30/30/113 +f 30/30/114 44/44/115 43/43/116 +f 30/30/114 43/43/116 31/31/117 +f 31/31/118 43/43/119 42/42/120 +f 31/31/118 42/42/120 26/26/121 +f 26/26/122 42/42/123 27/27/124 +f 27/27/124 42/42/123 41/41/125 +f 28/28/126 30/30/127 45/45/128 +f 45/45/128 30/30/127 46/46/129 +f 26/26/130 28/28/130 45/45/130 +f 46/46/131 26/26/131 45/45/131 +f 30/30/132 26/26/132 46/46/132 +f 47/47/133 48/48/134 49/49/135 +f 47/47/133 50/50/136 48/48/134 +f 49/49/137 51/51/137 52/52/137 +f 52/52/138 50/50/136 47/47/133 +f 53/53/139 54/54/140 55/55/141 +f 56/56/142 55/55/143 57/57/144 +f 56/56/142 57/57/144 58/58/145 +f 58/58/146 57/57/147 54/54/148 +f 58/58/146 54/54/148 59/59/149 +f 59/59/150 54/54/151 60/60/152 +f 60/60/152 54/54/151 53/53/153 +f 60/60/154 53/53/155 56/56/156 +f 56/56/156 53/53/155 55/55/157 +f 60/60/158 61/61/159 62/62/160 +f 60/60/158 62/62/160 59/59/161 +f 56/56/162 63/63/163 64/64/164 +f 59/59/161 62/62/160 65/65/165 +f 59/59/161 65/65/165 58/58/166 +f 56/56/162 64/64/164 60/60/158 +f 60/60/158 64/64/164 61/61/159 +f 58/58/166 63/63/163 56/56/162 +f 58/58/166 65/65/165 63/63/163 +f 48/48/167 63/63/167 49/49/167 +f 49/49/168 63/63/169 65/65/170 +f 49/49/168 65/65/170 51/51/171 +f 51/51/172 65/65/173 62/62/174 +f 51/51/172 62/62/174 52/52/175 +f 52/52/176 62/62/177 61/61/178 +f 52/52/176 61/61/178 50/50/179 +f 50/50/180 61/61/181 64/64/182 +f 50/50/180 64/64/182 48/48/183 +f 48/48/184 64/64/184 63/63/184 +f 66/66/185 52/52/185 67/67/185 +f 49/49/186 52/52/186 66/66/186 +f 67/67/187 49/49/187 66/66/187 +f 47/47/188 49/49/188 67/67/188 +f 52/52/189 47/47/189 67/67/189 +f 57/57/190 55/55/141 54/54/140 +f 68/68/191 69/69/191 70/70/191 +f 68/68/192 70/70/192 71/71/192 +f 71/71/193 70/70/194 72/72/195 +f 71/71/193 72/72/195 73/73/196 +f 73/73/197 72/72/197 74/74/197 +f 73/73/198 74/74/198 75/75/198 +f 75/75/199 74/74/199 76/76/199 +f 77/77/200 78/78/200 79/79/200 +f 79/79/201 78/78/201 80/80/201 +f 79/79/202 80/80/202 81/81/202 +f 81/81/203 80/80/203 82/82/203 +f 81/81/204 82/82/204 83/83/204 +f 83/83/205 82/82/205 70/70/205 +f 83/83/206 70/70/206 84/84/206 +f 83/83/207 84/84/207 85/85/207 +f 85/85/208 84/84/208 69/69/208 +f 68/68/209 85/85/209 69/69/209 +f 73/73/210 81/81/210 71/71/210 +f 71/71/210 81/81/210 83/83/210 +f 75/75/211 79/79/212 73/73/210 +f 73/73/210 79/79/212 81/81/210 +f 76/76/213 77/77/213 79/79/213 +f 76/76/214 79/79/212 75/75/211 +f 71/71/210 83/83/210 68/68/210 +f 68/68/210 83/83/210 85/85/210 +f 77/77/215 76/76/216 78/78/217 +f 74/74/218 82/82/71 80/80/71 +f 72/72/71 70/70/71 82/82/71 +f 72/72/71 82/82/71 74/74/218 +f 74/74/218 80/80/71 78/78/217 +f 74/74/218 78/78/217 76/76/216 +f 69/69/71 84/84/71 70/70/71 +f 86/86/219 87/87/220 88/88/221 +f 88/88/222 87/87/222 89/89/222 +f 88/88/223 89/89/223 90/90/223 +f 90/90/224 89/89/224 91/91/224 +f 90/90/225 91/91/226 92/92/227 +f 92/92/227 91/91/226 93/93/228 +f 94/94/229 92/92/229 95/95/229 +f 95/95/230 92/92/227 93/93/228 +f 94/94/231 95/95/231 96/96/231 +f 94/94/232 96/96/232 97/97/232 +f 97/97/233 96/96/233 98/98/233 +f 97/97/234 98/98/234 99/99/234 +f 99/99/235 98/98/236 100/100/237 +f 99/99/235 100/100/237 101/101/238 +f 101/101/239 100/100/239 102/102/239 +f 102/102/240 100/100/240 103/103/240 +f 102/102/241 103/103/241 104/104/241 +f 86/86/219 104/104/242 87/87/220 +f 90/90/210 99/99/210 101/101/210 +f 90/90/210 101/101/210 88/88/210 +f 90/90/210 97/97/210 99/99/210 +f 86/86/243 102/102/244 104/104/245 +f 88/88/210 102/102/244 86/86/243 +f 92/92/210 97/97/210 90/90/210 +f 92/92/210 94/94/210 97/97/210 +f 88/88/210 101/101/210 102/102/244 +f 89/89/71 100/100/71 91/91/71 +f 91/91/71 98/98/71 96/96/71 +f 91/91/71 100/100/71 98/98/71 +f 93/93/71 96/96/71 95/95/71 +f 91/91/71 96/96/71 93/93/71 +f 87/87/246 100/100/71 89/89/71 +f 87/87/246 103/103/247 100/100/71 +f 87/87/246 104/104/248 103/103/247 +f 105/105/249 106/106/250 107/107/251 +f 105/105/249 107/107/251 108/108/252 +f 109/109/253 110/110/254 106/106/250 +f 109/109/253 106/106/250 105/105/249 +f 109/109/253 111/111/255 110/110/254 +f 108/108/256 111/111/255 109/109/253 +f 112/112/257 113/113/258 114/114/259 +f 114/114/259 115/115/260 112/112/257 +f 116/116/261 113/113/262 117/117/263 +f 117/117/263 113/113/262 112/112/264 +f 117/117/265 112/112/265 118/118/265 +f 118/118/266 112/112/266 115/115/266 +f 118/118/267 115/115/267 119/119/267 +f 119/119/268 115/115/268 114/114/268 +f 119/119/269 114/114/269 116/116/269 +f 116/116/270 114/114/270 113/113/270 +f 117/117/271 120/120/272 121/121/273 +f 117/117/271 121/121/273 116/116/274 +f 116/116/274 121/121/273 122/122/275 +f 116/116/274 122/122/275 119/119/276 +f 119/119/276 122/122/275 123/123/277 +f 119/119/276 123/123/277 118/118/278 +f 118/118/278 123/123/277 124/124/279 +f 118/118/278 124/124/279 117/117/271 +f 117/117/271 124/124/279 120/120/272 +f 107/107/280 121/121/281 120/120/282 +f 107/107/280 120/120/282 108/108/283 +f 108/108/284 120/120/285 124/124/286 +f 108/108/284 124/124/286 111/111/287 +f 111/111/288 124/124/288 123/123/288 +f 111/111/289 123/123/289 110/110/289 +f 110/110/290 123/123/290 122/122/290 +f 110/110/291 122/122/291 106/106/291 +f 106/106/292 122/122/293 121/121/294 +f 106/106/292 121/121/294 107/107/295 +f 108/108/296 109/109/297 125/125/298 +f 125/125/298 109/109/297 126/126/299 +f 105/105/300 108/108/300 127/127/300 +f 127/127/301 108/108/301 125/125/301 +f 109/109/59 105/105/302 126/126/61 +f 126/126/61 105/105/302 127/127/62 +f 126/126/71 127/127/71 125/125/71 +f 128/128/303 129/129/303 130/130/303 +f 128/128/304 130/130/304 131/131/304 +f 131/131/305 130/130/305 132/132/305 +f 131/131/306 132/132/307 133/133/308 +f 131/131/306 133/133/308 134/134/309 +f 134/134/310 133/133/311 135/135/312 +f 135/135/312 133/133/311 136/136/313 +f 137/137/314 135/135/312 138/138/315 +f 138/138/315 135/135/312 136/136/313 +f 137/137/316 138/138/317 139/139/318 +f 137/137/316 139/139/318 140/140/319 +f 140/140/320 139/139/320 141/141/320 +f 140/140/321 141/141/321 142/142/321 +f 142/142/322 141/141/323 143/143/324 +f 142/142/322 143/143/324 144/144/325 +f 144/144/326 143/143/327 145/145/328 +f 144/144/326 145/145/328 146/146/329 +f 146/146/330 145/145/330 147/147/330 +f 147/147/331 145/145/331 129/129/331 +f 128/128/332 147/147/332 129/129/332 +f 134/134/210 144/144/210 131/131/210 +f 134/134/210 142/142/210 144/144/210 +f 134/134/210 140/140/210 142/142/210 +f 131/131/210 146/146/210 128/128/210 +f 128/128/210 146/146/210 147/147/210 +f 135/135/210 140/140/210 134/134/210 +f 135/135/210 137/137/210 140/140/210 +f 131/131/210 144/144/210 146/146/210 +f 132/132/71 143/143/71 133/133/71 +f 133/133/71 139/139/71 136/136/71 +f 133/133/71 141/141/71 139/139/71 +f 133/133/71 143/143/71 141/141/71 +f 136/136/71 139/139/71 138/138/71 +f 130/130/71 145/145/71 143/143/71 +f 130/130/71 143/143/71 132/132/71 +f 130/130/71 129/129/71 145/145/71 +f 148/148/333 149/149/334 150/150/335 +f 150/150/335 149/149/334 151/151/336 +f 150/150/337 151/151/337 152/152/337 +f 152/152/338 151/151/338 153/153/338 +f 152/152/339 153/153/339 154/154/339 +f 154/154/340 153/153/340 155/155/340 +f 154/154/341 155/155/341 156/156/341 +f 156/156/342 155/155/343 157/157/344 +f 158/158/345 156/156/342 159/159/346 +f 159/159/346 156/156/342 157/157/344 +f 158/158/347 159/159/347 160/160/347 +f 158/158/348 160/160/348 161/161/348 +f 161/161/349 160/160/349 162/162/349 +f 161/161/350 162/162/350 163/163/350 +f 163/163/351 162/162/352 164/164/353 +f 163/163/351 164/164/353 165/165/354 +f 165/165/355 164/164/355 166/166/355 +f 166/166/356 164/164/356 167/167/356 +f 166/166/357 167/167/357 148/148/357 +f 149/149/358 148/148/358 167/167/358 +f 152/152/210 163/163/210 165/165/210 +f 154/154/210 163/163/210 152/152/210 +f 154/154/210 161/161/210 163/163/210 +f 156/156/210 161/161/210 154/154/210 +f 150/150/210 166/166/210 148/148/210 +f 156/156/210 158/158/210 161/161/210 +f 150/150/210 165/165/210 166/166/210 +f 152/152/210 165/165/210 150/150/210 +f 153/153/71 162/162/71 155/155/71 +f 155/155/71 162/162/71 160/160/71 +f 151/151/71 164/164/71 153/153/71 +f 153/153/71 164/164/71 162/162/71 +f 155/155/71 160/160/71 157/157/71 +f 157/157/71 160/160/71 159/159/71 +f 149/149/71 167/167/71 151/151/71 +f 151/151/71 167/167/71 164/164/71 +f 168/168/359 169/169/359 170/170/359 +f 171/171/360 172/172/360 168/168/360 +f 170/170/361 173/173/361 171/171/361 +f 174/174/362 175/175/362 176/176/363 +f 174/174/362 177/177/364 175/175/362 +f 177/177/365 178/178/366 175/175/367 +f 175/175/367 178/178/366 179/179/368 +f 175/175/369 179/179/369 176/176/369 +f 179/179/370 180/180/370 176/176/370 +f 176/176/371 180/180/372 181/181/373 +f 176/176/371 181/181/373 174/174/374 +f 174/174/375 181/181/376 178/178/377 +f 174/174/375 178/178/377 177/177/378 +f 179/179/379 182/182/380 180/180/381 +f 178/178/382 183/183/383 184/184/384 +f 181/181/385 185/185/386 183/183/383 +f 181/181/385 183/183/383 178/178/382 +f 180/180/381 182/182/380 185/185/386 +f 180/180/381 185/185/386 181/181/385 +f 179/179/379 184/184/384 182/182/380 +f 178/178/382 184/184/384 179/179/379 +f 183/183/387 169/169/388 184/184/389 +f 184/184/390 169/169/390 168/168/390 +f 184/184/391 168/168/391 182/182/391 +f 182/182/392 168/168/392 172/172/392 +f 172/172/393 171/171/394 182/182/395 +f 182/182/395 171/171/394 185/185/396 +f 171/171/397 173/173/397 185/185/397 +f 185/185/398 173/173/399 183/183/400 +f 183/183/400 173/173/399 170/170/401 +f 183/183/387 170/170/402 169/169/388 +f 171/171/403 168/168/403 186/186/403 +f 170/170/404 171/171/405 187/187/406 +f 187/187/406 171/171/405 186/186/407 +f 168/168/408 170/170/408 186/186/408 +f 186/186/409 170/170/409 187/187/409 +f 188/188/71 189/189/71 190/190/71 +f 190/190/71 189/189/71 191/191/71 +f 192/192/410 193/193/411 194/194/412 +f 194/194/412 193/193/411 195/195/411 +f 196/196/413 197/197/414 198/198/415 +f 196/196/413 198/198/415 199/199/416 +f 199/199/416 198/198/415 200/200/417 +f 201/201/418 198/198/419 202/202/420 +f 202/202/420 198/198/419 203/203/421 +f 198/198/419 197/197/422 203/203/421 +f 204/204/413 205/205/414 206/206/415 +f 204/204/413 206/206/415 207/207/416 +f 207/207/416 206/206/415 208/208/417 +f 209/209/418 206/206/419 210/210/420 +f 210/210/420 206/206/419 211/211/421 +f 206/206/419 205/205/422 211/211/421 +f 212/212/413 213/213/414 214/214/415 +f 212/212/413 214/214/415 215/215/416 +f 215/215/416 214/214/415 216/216/417 +f 217/217/418 214/214/419 218/218/420 +f 218/218/420 214/214/419 219/219/421 +f 214/214/419 213/213/422 219/219/421 +f 220/220/413 221/221/414 222/222/415 +f 220/220/413 222/222/415 223/223/416 +f 223/223/416 222/222/415 224/224/417 +f 225/225/418 222/222/419 226/226/420 +f 226/226/420 222/222/419 227/227/421 +f 222/222/419 221/221/422 227/227/421 +f 228/228/413 229/229/423 230/230/415 +f 228/228/413 230/230/415 231/231/416 +f 231/231/416 230/230/415 232/232/417 +f 233/233/418 230/230/419 234/234/420 +f 234/234/420 230/230/419 235/235/421 +f 230/230/419 229/229/422 235/235/421 +f 236/236/424 237/237/425 238/238/426 +f 236/236/424 238/238/426 239/239/427 +f 236/236/424 239/239/427 240/240/428 +f 240/240/428 239/239/427 241/241/429 +f 242/242/418 239/239/419 243/243/420 +f 243/243/420 239/239/419 244/244/421 +f 239/239/419 238/238/422 244/244/421 +f 189/189/430 193/193/431 192/192/432 +f 189/189/430 192/192/432 191/191/433 +f 198/198/434 201/201/434 200/200/434 +f 206/206/435 209/209/435 208/208/435 +f 214/214/436 217/217/436 216/216/436 +f 222/222/435 225/225/435 224/224/435 +f 230/230/437 233/233/437 232/232/437 +f 239/239/436 242/242/436 241/241/436 +f 245/245/438 246/246/439 188/188/440 +f 247/247/441 246/246/439 245/245/438 +f 248/248/442 249/249/443 250/250/444 +f 251/251/445 249/249/443 248/248/442 +f 251/251/445 248/248/442 252/252/446 +f 252/252/446 248/248/442 253/253/447 +f 254/254/448 255/255/449 256/256/450 +f 256/256/450 255/255/449 253/253/447 +f 253/253/447 255/255/449 252/252/446 +f 257/257/451 254/254/448 256/256/450 +f 258/258/452 195/195/453 259/259/453 +f 258/258/452 259/259/453 260/260/454 +f 261/261/455 262/262/456 263/263/457 +f 264/264/458 265/265/459 266/266/460 +f 264/264/458 267/267/411 268/268/411 +f 264/264/458 268/268/411 265/265/459 +f 265/265/459 269/269/461 266/266/460 +f 266/266/460 269/269/461 261/261/455 +f 261/261/455 269/269/461 270/270/462 +f 261/261/455 270/270/462 262/262/456 +f 271/271/463 272/272/464 196/196/465 +f 273/273/466 272/272/464 271/271/463 +f 274/274/467 275/275/468 276/276/469 +f 277/277/470 275/275/468 274/274/467 +f 277/277/470 274/274/467 278/278/471 +f 278/278/471 274/274/467 279/279/472 +f 280/280/473 281/281/474 282/282/475 +f 282/282/475 281/281/474 279/279/472 +f 279/279/472 281/281/474 278/278/471 +f 282/282/475 283/283/476 280/280/473 +f 203/203/477 272/272/478 273/273/479 +f 203/203/477 273/273/479 245/245/480 +f 248/248/481 284/284/482 253/253/483 +f 248/248/481 285/285/484 286/286/485 +f 248/248/481 286/286/485 284/284/482 +f 284/284/482 287/287/486 253/253/483 +f 253/253/483 287/287/486 256/256/487 +f 256/256/487 287/287/486 288/288/488 +f 256/256/487 288/288/488 289/289/489 +f 289/289/489 288/288/488 290/290/210 +f 291/291/463 292/292/464 204/204/465 +f 293/293/466 292/292/464 291/291/463 +f 294/294/490 295/295/443 296/296/444 +f 297/297/445 295/295/443 294/294/490 +f 297/297/445 294/294/490 298/298/491 +f 298/298/491 294/294/490 299/299/492 +f 300/300/473 301/301/493 302/302/494 +f 302/302/494 301/301/493 303/303/495 +f 303/303/496 301/301/496 299/299/496 +f 299/299/492 301/301/497 298/298/491 +f 302/302/494 304/304/476 300/300/473 +f 211/211/477 292/292/478 293/293/479 +f 211/211/477 293/293/479 271/271/480 +f 282/282/498 305/305/499 283/283/500 +f 274/274/501 306/306/502 279/279/503 +f 307/307/504 308/308/505 274/274/501 +f 274/274/501 308/308/505 306/306/502 +f 306/306/502 309/309/506 279/279/503 +f 279/279/503 309/309/506 282/282/498 +f 282/282/498 309/309/506 310/310/507 +f 282/282/498 310/310/507 305/305/499 +f 311/311/463 312/312/464 212/212/465 +f 313/313/466 312/312/464 311/311/463 +f 314/314/508 315/315/509 316/316/510 +f 317/317/511 315/315/509 314/314/508 +f 317/317/511 314/314/508 318/318/512 +f 318/318/512 314/314/508 319/319/513 +f 318/318/512 319/319/513 320/320/514 +f 321/321/515 322/322/516 323/323/517 +f 323/323/517 322/322/516 320/320/514 +f 323/323/517 320/320/514 319/319/513 +f 324/324/518 321/321/515 323/323/517 +f 219/219/477 312/312/478 313/313/479 +f 219/219/477 313/313/479 291/291/480 +f 302/302/519 325/325/520 304/304/500 +f 294/294/521 317/317/522 299/299/523 +f 299/299/523 317/317/522 318/318/524 +f 299/299/523 318/318/524 303/303/525 +f 294/294/521 326/326/484 327/327/526 +f 294/294/521 327/327/526 317/317/522 +f 318/318/524 320/320/527 303/303/525 +f 303/303/525 320/320/527 302/302/519 +f 302/302/519 320/320/527 322/322/528 +f 302/302/519 322/322/528 325/325/520 +f 328/328/529 329/329/530 220/220/531 +f 330/330/532 329/329/530 328/328/529 +f 331/331/71 332/332/71 333/333/71 +f 331/331/71 333/333/71 334/334/533 +f 331/331/71 334/334/533 335/335/534 +f 335/335/534 334/334/533 336/336/535 +f 337/337/71 338/338/536 339/339/537 +f 339/339/537 338/338/536 336/336/535 +f 336/336/535 338/338/536 335/335/534 +f 340/340/71 337/337/71 339/339/537 +f 227/227/477 329/329/478 330/330/479 +f 227/227/477 330/330/479 311/311/480 +f 323/323/538 341/341/539 342/342/540 +f 314/314/541 343/343/542 319/319/543 +f 344/344/544 345/345/545 314/314/541 +f 314/314/541 345/345/545 343/343/542 +f 343/343/542 346/346/546 319/319/543 +f 319/319/543 346/346/546 323/323/538 +f 323/323/538 346/346/546 347/347/547 +f 323/323/538 347/347/547 341/341/539 +f 348/348/548 349/349/549 228/228/550 +f 350/350/551 349/349/549 348/348/548 +f 351/351/71 352/352/71 353/353/71 +f 354/354/71 352/352/71 351/351/71 +f 354/354/71 351/351/71 355/355/71 +f 355/355/71 351/351/71 356/356/552 +f 357/357/553 358/358/554 359/359/555 +f 359/359/555 358/358/554 356/356/552 +f 356/356/552 358/358/554 355/355/71 +f 360/360/556 357/357/553 359/359/555 +f 235/235/557 349/349/478 350/350/558 +f 235/235/557 350/350/558 348/348/559 +f 361/361/560 362/362/210 363/363/210 +f 364/364/561 365/365/562 336/336/563 +f 364/364/561 366/366/210 367/367/210 +f 364/364/561 367/367/210 365/365/562 +f 365/365/562 368/368/564 336/336/563 +f 336/336/563 368/368/564 361/361/560 +f 361/361/560 368/368/564 369/369/210 +f 361/361/560 369/369/210 362/362/210 +f 370/370/565 371/371/566 237/237/567 +f 372/372/568 371/371/566 370/370/565 +f 373/373/71 374/374/71 375/375/71 +f 376/376/71 374/374/71 373/373/71 +f 376/376/71 373/373/71 377/377/569 +f 376/376/71 377/377/569 378/378/71 +f 379/379/570 380/380/571 381/381/572 +f 381/381/572 380/380/571 377/377/569 +f 377/377/569 380/380/571 378/378/71 +f 382/382/573 379/379/570 381/381/572 +f 244/244/574 371/371/575 372/372/574 +f 244/244/574 372/372/574 383/383/574 +f 384/384/210 385/385/210 386/386/576 +f 386/386/576 385/385/210 387/387/210 +f 387/387/210 388/388/577 386/386/576 +f 386/386/576 388/388/577 359/359/578 +f 359/359/578 388/388/577 389/389/579 +f 359/359/578 389/389/579 390/390/580 +f 390/390/580 389/389/579 391/391/210 +f 254/254/581 262/262/582 270/270/583 +f 254/254/581 270/270/583 255/255/584 +f 255/255/585 270/270/585 269/269/585 +f 255/255/586 269/269/586 252/252/586 +f 252/252/587 269/269/587 265/265/587 +f 252/252/588 265/265/588 251/251/588 +f 251/251/589 265/265/590 268/268/591 +f 251/251/589 268/268/591 249/249/592 +f 280/280/593 290/290/593 288/288/593 +f 280/280/594 288/288/594 281/281/594 +f 281/281/595 288/288/488 287/287/486 +f 281/281/474 287/287/596 278/278/471 +f 278/278/597 287/287/486 284/284/482 +f 278/278/471 284/284/598 277/277/470 +f 277/277/599 284/284/599 286/286/599 +f 277/277/600 286/286/600 275/275/600 +f 300/300/593 305/305/593 310/310/593 +f 300/300/601 310/310/601 301/301/601 +f 301/301/595 310/310/595 309/309/595 +f 301/301/596 309/309/596 298/298/596 +f 298/298/597 309/309/506 306/306/502 +f 298/298/598 306/306/598 297/297/598 +f 297/297/602 306/306/602 308/308/602 +f 297/297/600 308/308/600 295/295/600 +f 321/321/603 325/325/603 322/322/603 +f 317/317/604 327/327/604 315/315/604 +f 337/337/605 341/341/605 347/347/605 +f 337/337/594 347/347/594 338/338/594 +f 338/338/606 347/347/547 346/346/546 +f 338/338/536 346/346/596 335/335/534 +f 335/335/597 346/346/546 343/343/542 +f 335/335/598 343/343/598 331/331/598 +f 331/331/607 343/343/607 345/345/607 +f 331/331/600 345/345/600 332/332/600 +f 357/357/593 362/362/593 369/369/593 +f 357/357/608 369/369/608 358/358/608 +f 358/358/595 369/369/595 368/368/595 +f 358/358/596 368/368/596 355/355/596 +f 355/355/597 368/368/564 365/365/562 +f 355/355/598 365/365/598 354/354/598 +f 354/354/609 365/365/609 367/367/609 +f 354/354/600 367/367/600 352/352/600 +f 379/379/593 391/391/593 389/389/593 +f 379/379/610 389/389/610 380/380/610 +f 380/380/595 389/389/579 388/388/577 +f 380/380/596 388/388/596 378/378/596 +f 378/378/597 388/388/597 387/387/597 +f 378/378/598 387/387/598 376/376/598 +f 376/376/611 387/387/611 385/385/611 +f 376/376/600 385/385/600 374/374/600 +f 247/247/612 260/260/613 259/259/614 +f 247/247/612 259/259/614 246/246/615 +f 392/392/616 393/393/617 394/394/618 +f 394/394/618 393/393/617 395/395/619 +f 396/396/620 397/397/621 398/398/622 +f 398/398/622 397/397/621 399/399/623 +f 400/400/71 401/401/71 402/402/624 +f 403/403/625 404/404/626 405/405/627 +f 403/403/625 405/405/627 406/406/628 +f 406/406/628 405/405/627 407/407/629 +f 406/406/628 407/407/629 402/402/624 +f 402/402/624 407/407/629 400/400/71 +f 250/250/630 408/408/631 403/403/625 +f 403/403/625 408/408/631 404/404/626 +f 409/409/210 410/410/632 411/411/633 +f 410/410/632 412/412/634 413/413/635 +f 413/413/636 412/412/637 414/414/638 +f 413/413/636 414/414/638 415/415/639 +f 415/415/639 414/414/638 416/416/640 +f 415/415/639 416/416/640 417/417/641 +f 417/417/641 416/416/640 418/418/642 +f 410/410/632 409/409/210 412/412/634 +f 408/408/643 418/418/644 416/416/645 +f 408/408/643 416/416/645 404/404/646 +f 404/404/646 416/416/645 414/414/647 +f 404/404/646 414/414/647 405/405/648 +f 405/405/648 414/414/647 412/412/649 +f 405/405/648 412/412/649 407/407/650 +f 407/407/651 412/412/652 409/409/653 +f 407/407/651 409/409/653 400/400/654 +f 419/419/655 420/420/656 421/421/657 +f 422/422/658 423/423/659 424/424/660 +f 422/422/658 424/424/660 425/425/661 +f 425/425/661 424/424/660 426/426/662 +f 425/425/661 426/426/662 421/421/657 +f 421/421/657 426/426/662 427/427/663 +f 421/421/657 427/427/663 419/419/655 +f 276/276/664 428/428/665 422/422/658 +f 422/422/658 428/428/665 423/423/659 +f 419/419/666 429/429/667 430/430/668 +f 429/429/667 427/427/669 426/426/670 +f 429/429/667 426/426/670 406/406/671 +f 406/406/671 426/426/670 424/424/672 +f 406/406/671 424/424/672 403/403/673 +f 403/403/673 424/424/672 423/423/674 +f 403/403/673 423/423/674 431/431/675 +f 431/431/675 423/423/674 432/432/676 +f 429/429/667 419/419/666 427/427/669 +f 428/428/677 432/432/677 423/423/677 +f 433/433/678 434/434/71 435/435/679 +f 436/436/680 437/437/681 438/438/660 +f 436/436/680 438/438/660 439/439/661 +f 439/439/661 438/438/660 440/440/662 +f 439/439/661 440/440/662 435/435/679 +f 435/435/679 440/440/662 441/441/682 +f 435/435/679 441/441/682 433/433/678 +f 296/296/630 442/442/683 436/436/680 +f 436/436/680 442/442/683 437/437/681 +f 443/443/684 444/444/685 445/445/210 +f 444/444/685 441/441/686 440/440/670 +f 444/444/685 440/440/670 425/425/671 +f 425/425/671 440/440/670 438/438/672 +f 425/425/671 438/438/672 422/422/687 +f 422/422/687 438/438/672 437/437/674 +f 422/422/687 437/437/674 446/446/688 +f 446/446/688 437/437/674 447/447/676 +f 444/444/685 443/443/684 441/441/686 +f 442/442/677 447/447/677 437/437/677 +f 441/441/689 443/443/689 433/433/689 +f 448/448/690 449/449/71 450/450/691 +f 451/451/680 452/452/659 453/453/660 +f 451/451/680 453/453/660 454/454/661 +f 454/454/661 453/453/660 455/455/662 +f 454/454/661 455/455/662 450/450/691 +f 450/450/691 455/455/662 456/456/682 +f 450/450/691 456/456/682 448/448/690 +f 316/316/630 457/457/683 451/451/680 +f 451/451/680 457/457/683 452/452/659 +f 458/458/684 459/459/685 460/460/210 +f 459/459/685 456/456/686 455/455/670 +f 459/459/685 455/455/670 439/439/671 +f 439/439/671 455/455/670 453/453/672 +f 439/439/671 453/453/672 436/436/673 +f 436/436/673 453/453/672 452/452/674 +f 436/436/673 452/452/674 461/461/675 +f 461/461/675 452/452/674 462/462/676 +f 459/459/685 458/458/684 456/456/686 +f 457/457/692 462/462/692 452/452/692 +f 456/456/693 458/458/693 448/448/693 +f 463/463/690 464/464/71 465/465/691 +f 466/466/694 467/467/681 468/468/660 +f 466/466/694 468/468/660 469/469/661 +f 469/469/661 468/468/660 470/470/662 +f 469/469/661 470/470/662 465/465/691 +f 465/465/691 470/470/662 471/471/682 +f 465/465/691 471/471/682 463/463/690 +f 472/472/695 473/473/696 466/466/694 +f 466/466/694 473/473/696 467/467/681 +f 474/474/684 475/475/685 476/476/210 +f 475/475/685 471/471/686 470/470/670 +f 475/475/685 470/470/670 454/454/671 +f 454/454/671 470/470/670 468/468/672 +f 454/454/671 468/468/672 451/451/673 +f 451/451/673 468/468/672 467/467/674 +f 451/451/673 467/467/674 477/477/697 +f 477/477/697 467/467/674 478/478/676 +f 475/475/685 474/474/684 471/471/686 +f 473/473/677 478/478/677 467/467/677 +f 471/471/698 474/474/698 463/463/698 +f 479/479/699 480/480/71 481/481/700 +f 482/482/680 483/483/681 484/484/660 +f 482/482/680 484/484/660 485/485/661 +f 485/485/661 484/484/660 486/486/662 +f 485/485/661 486/486/662 481/481/700 +f 481/481/700 486/486/662 487/487/682 +f 481/481/700 487/487/682 479/479/699 +f 353/353/630 488/488/683 482/482/680 +f 482/482/680 488/488/683 483/483/681 +f 489/489/684 490/490/685 491/491/210 +f 490/490/685 487/487/686 486/486/670 +f 490/490/685 486/486/670 469/469/671 +f 469/469/671 486/486/670 484/484/672 +f 469/469/671 484/484/672 466/466/701 +f 466/466/701 484/484/672 483/483/702 +f 466/466/701 483/483/702 472/472/703 +f 472/472/703 483/483/702 492/492/704 +f 490/490/685 489/489/684 487/487/686 +f 488/488/692 492/492/692 483/483/692 +f 487/487/698 489/489/698 479/479/698 +f 493/493/705 494/494/706 495/495/707 +f 496/496/708 497/497/709 498/498/710 +f 498/498/710 497/497/709 499/499/711 +f 498/498/710 499/499/711 500/500/712 +f 500/500/712 499/499/711 501/501/713 +f 500/500/712 501/501/713 495/495/707 +f 495/495/707 501/501/713 502/502/714 +f 495/495/707 502/502/714 493/493/705 +f 493/493/666 503/503/667 504/504/668 +f 503/503/667 502/502/669 501/501/670 +f 503/503/667 501/501/670 485/485/671 +f 485/485/671 501/501/670 499/499/672 +f 485/485/671 499/499/672 482/482/673 +f 482/482/673 499/499/672 497/497/674 +f 482/482/673 497/497/674 505/505/715 +f 505/505/715 497/497/674 506/506/676 +f 503/503/667 493/493/666 502/502/669 +f 496/496/716 506/506/716 497/497/716 +f 393/393/617 392/392/616 507/507/717 +f 507/507/717 392/392/616 508/508/718 +f 507/507/717 508/508/718 509/509/719 +f 509/509/719 508/508/718 510/510/720 +f 509/509/719 510/510/720 511/511/721 +f 511/511/721 510/510/720 512/512/722 +f 496/496/723 513/513/724 375/375/725 +f 375/375/726 513/513/726 373/373/726 +f 373/373/727 513/513/727 514/514/727 +f 496/496/728 515/515/728 513/513/728 +f 498/498/729 515/515/729 496/496/729 +f 498/498/730 500/500/730 515/515/730 +f 495/495/731 516/516/731 500/500/731 +f 516/516/732 495/495/732 517/517/732 +f 517/517/733 495/495/734 494/494/735 +f 518/518/736 519/519/736 520/520/736 +f 520/520/737 519/519/737 517/517/737 +f 520/520/738 517/517/733 494/494/735 +f 518/518/739 521/521/739 519/519/739 +f 522/522/740 523/523/740 524/524/740 +f 524/524/741 523/523/741 521/521/741 +f 524/524/742 521/521/742 518/518/742 +f 525/525/743 526/526/744 522/522/745 +f 522/522/745 526/526/744 523/523/746 +f 526/526/747 525/525/747 527/527/747 +f 527/527/748 370/370/749 528/528/750 +f 237/237/751 236/236/751 528/528/751 +f 237/237/752 528/528/752 370/370/752 +f 529/529/753 236/236/753 240/240/753 +f 382/382/754 530/530/755 240/240/756 +f 240/240/757 530/530/757 529/529/757 +f 373/373/758 514/514/758 377/377/758 +f 377/377/759 514/514/759 381/381/759 +f 381/381/760 530/530/761 382/382/762 +f 505/505/715 384/384/763 353/353/764 +f 505/505/715 353/353/764 482/482/673 +f 485/485/765 481/481/765 503/503/765 +f 503/503/766 481/481/767 480/480/768 +f 503/503/766 480/480/768 504/504/769 +f 504/504/769 480/480/768 531/531/770 +f 532/532/771 531/531/771 533/533/771 +f 532/532/772 533/533/772 534/534/772 +f 535/535/773 536/536/774 537/537/775 +f 537/537/775 536/536/774 538/538/776 +f 538/538/776 536/536/774 539/539/777 +f 538/538/776 539/539/777 540/540/778 +f 540/540/778 539/539/777 541/541/779 +f 540/540/778 541/541/779 383/383/780 +f 383/383/780 541/541/779 348/348/781 +f 383/383/780 348/348/781 244/244/782 +f 244/244/782 348/348/781 228/228/783 +f 244/244/784 228/228/784 243/243/784 +f 243/243/785 228/228/786 231/231/787 +f 243/243/785 231/231/787 390/390/788 +f 390/390/788 231/231/787 360/360/789 +f 353/353/764 384/384/763 351/351/790 +f 351/351/791 384/384/791 386/386/791 +f 351/351/792 386/386/792 356/356/792 +f 356/356/552 386/386/793 359/359/555 +f 359/359/794 390/390/788 360/360/789 +f 472/472/795 366/366/796 333/333/797 +f 469/469/765 465/465/765 490/490/765 +f 490/490/798 465/465/799 464/464/800 +f 490/490/798 464/464/800 491/491/801 +f 491/491/801 464/464/800 542/542/802 +f 542/542/802 464/464/800 543/543/803 +f 544/544/804 545/545/805 546/546/806 +f 544/544/804 546/546/806 547/547/807 +f 547/547/807 546/546/806 548/548/808 +f 548/548/808 546/546/806 549/549/809 +f 548/548/808 549/549/809 348/348/781 +f 348/348/781 549/549/809 328/328/810 +f 348/348/781 328/328/810 235/235/811 +f 235/235/811 328/328/810 220/220/812 +f 235/235/784 220/220/784 234/234/784 +f 234/234/813 220/220/786 223/223/814 +f 234/234/813 223/223/814 363/363/815 +f 363/363/815 223/223/814 340/340/816 +f 333/333/797 366/366/796 364/364/817 +f 333/333/818 364/364/818 334/334/818 +f 334/334/819 364/364/819 336/336/819 +f 336/336/820 361/361/820 339/339/820 +f 339/339/821 361/361/822 340/340/816 +f 340/340/816 361/361/822 363/363/815 +f 477/477/697 344/344/823 316/316/824 +f 477/477/697 316/316/824 451/451/673 +f 454/454/765 450/450/765 475/475/765 +f 475/475/798 450/450/799 449/449/800 +f 475/475/798 449/449/800 476/476/825 +f 476/476/825 449/449/800 550/550/802 +f 550/550/802 449/449/800 551/551/803 +f 552/552/826 553/553/827 554/554/828 +f 554/554/828 553/553/827 555/555/829 +f 555/555/829 553/553/827 556/556/830 +f 556/556/830 553/553/827 557/557/831 +f 556/556/830 557/557/831 311/311/832 +f 227/227/833 311/311/833 212/212/833 +f 227/227/784 212/212/784 226/226/784 +f 226/226/813 212/212/834 215/215/814 +f 226/226/813 215/215/814 342/342/835 +f 342/342/835 215/215/814 324/324/836 +f 316/316/824 344/344/823 314/314/837 +f 324/324/836 323/323/838 342/342/835 +f 294/294/839 296/296/840 326/326/841 +f 326/326/841 296/296/840 461/461/842 +f 461/461/675 296/296/843 436/436/673 +f 439/439/765 435/435/765 459/459/765 +f 459/459/844 435/435/845 434/434/846 +f 459/459/844 434/434/846 460/460/847 +f 460/460/847 434/434/846 558/558/848 +f 558/558/848 434/434/846 559/559/849 +f 560/560/826 561/561/850 562/562/851 +f 562/562/851 561/561/850 563/563/852 +f 563/563/852 561/561/850 564/564/853 +f 564/564/853 561/561/850 565/565/831 +f 564/564/853 565/565/831 291/291/854 +f 219/219/833 291/291/833 204/204/833 +f 219/219/855 204/204/855 218/218/855 +f 218/218/856 204/204/834 207/207/857 +f 218/218/856 207/207/857 304/304/858 +f 446/446/688 307/307/859 276/276/860 +f 446/446/688 276/276/860 422/422/687 +f 425/425/765 421/421/765 444/444/765 +f 444/444/798 421/421/799 420/420/800 +f 444/444/798 420/420/800 445/445/825 +f 445/445/825 420/420/800 566/566/802 +f 566/566/802 420/420/800 567/567/803 +f 568/568/861 569/569/862 570/570/863 +f 570/570/863 569/569/862 571/571/864 +f 571/571/864 569/569/862 572/572/865 +f 571/571/864 572/572/865 573/573/866 +f 573/573/866 572/572/865 574/574/867 +f 573/573/866 574/574/867 271/271/854 +f 211/211/833 271/271/833 196/196/833 +f 211/211/855 196/196/855 210/210/855 +f 210/210/868 196/196/834 199/199/857 +f 210/210/868 199/199/857 283/283/869 +f 276/276/860 307/307/859 274/274/870 +f 431/431/871 285/285/872 250/250/840 +f 431/431/675 250/250/843 403/403/673 +f 406/406/765 402/402/765 429/429/765 +f 429/429/844 402/402/845 401/401/873 +f 429/429/844 401/401/873 430/430/874 +f 430/430/874 401/401/873 575/575/875 +f 575/575/875 401/401/873 576/576/876 +f 575/575/877 576/576/877 577/577/877 +f 577/577/878 576/576/878 578/578/878 +f 577/577/879 578/578/879 579/579/879 +f 579/579/880 578/578/880 580/580/880 +f 579/579/881 580/580/881 581/581/881 +f 581/581/882 580/580/882 582/582/882 +f 581/581/883 582/582/884 583/583/885 +f 583/583/885 582/582/884 584/584/886 +f 584/584/887 582/582/888 585/585/889 +f 584/584/887 585/585/889 245/245/890 +f 203/203/833 245/245/833 188/188/833 +f 203/203/855 188/188/855 202/202/855 +f 202/202/891 188/188/786 190/190/892 +f 202/202/891 190/190/892 289/289/893 +f 289/289/893 190/190/892 257/257/894 +f 250/250/840 285/285/872 248/248/839 +f 256/256/895 289/289/893 257/257/894 +f 586/586/896 587/587/897 588/588/898 +f 263/263/899 589/589/900 261/261/901 +f 590/590/902 591/591/903 592/592/904 +f 590/590/902 592/592/904 593/593/905 +f 593/593/905 592/592/904 594/594/906 +f 593/593/905 594/594/906 595/595/907 +f 595/595/907 594/594/906 596/596/908 +f 596/596/908 594/594/906 597/597/909 +f 596/596/908 597/597/909 598/598/910 +f 596/596/908 598/598/910 599/599/911 +f 600/600/912 601/601/913 602/602/914 +f 602/602/914 601/601/913 603/603/915 +f 604/604/916 605/605/917 606/606/918 +f 604/604/916 606/606/918 607/607/919 +f 506/506/920 496/496/920 505/505/920 +f 505/505/921 496/496/723 375/375/725 +f 505/505/922 375/375/922 384/384/922 +f 384/384/923 375/375/924 385/385/925 +f 385/385/925 375/375/924 374/374/926 +f 492/492/927 488/488/927 472/472/927 +f 472/472/928 488/488/928 353/353/928 +f 472/472/795 353/353/929 366/366/796 +f 366/366/930 353/353/931 367/367/932 +f 367/367/932 353/353/931 352/352/933 +f 478/478/934 473/473/935 477/477/936 +f 477/477/936 473/473/935 472/472/937 +f 477/477/697 472/472/795 344/344/823 +f 344/344/823 472/472/795 333/333/797 +f 344/344/938 333/333/939 345/345/940 +f 345/345/940 333/333/939 332/332/941 +f 462/462/934 457/457/934 461/461/934 +f 461/461/942 457/457/942 316/316/942 +f 461/461/842 316/316/943 326/326/841 +f 326/326/930 316/316/931 327/327/932 +f 327/327/932 316/316/931 315/315/933 +f 447/447/934 442/442/934 446/446/934 +f 446/446/942 442/442/942 296/296/942 +f 446/446/944 296/296/944 307/307/944 +f 307/307/945 296/296/946 308/308/947 +f 308/308/947 296/296/946 295/295/933 +f 432/432/934 428/428/934 431/431/934 +f 431/431/948 428/428/948 276/276/948 +f 431/431/871 276/276/949 285/285/872 +f 285/285/950 276/276/951 286/286/952 +f 286/286/952 276/276/951 275/275/953 +f 418/418/954 408/408/955 417/417/956 +f 417/417/956 408/408/955 250/250/957 +f 417/417/958 250/250/959 267/267/960 +f 267/267/961 250/250/962 268/268/963 +f 268/268/963 250/250/962 249/249/964 +f 391/391/965 379/379/966 390/390/967 +f 390/390/967 379/379/966 382/382/968 +f 390/390/788 382/382/754 243/243/785 +f 243/243/785 382/382/754 240/240/756 +f 243/243/969 240/240/970 242/242/971 +f 242/242/971 240/240/970 241/241/972 +f 362/362/973 357/357/974 363/363/975 +f 363/363/975 357/357/974 360/360/976 +f 363/363/815 360/360/789 234/234/813 +f 234/234/813 360/360/789 231/231/787 +f 234/234/977 231/231/978 233/233/979 +f 233/233/979 231/231/978 232/232/980 +f 341/341/973 337/337/974 342/342/981 +f 342/342/981 337/337/974 340/340/982 +f 342/342/835 340/340/816 226/226/813 +f 226/226/813 340/340/816 223/223/814 +f 226/226/977 223/223/978 225/225/979 +f 225/225/979 223/223/978 224/224/980 +f 325/325/983 321/321/984 304/304/985 +f 304/304/985 321/321/984 324/324/986 +f 304/304/858 324/324/836 218/218/856 +f 218/218/856 324/324/836 215/215/814 +f 218/218/987 215/215/988 217/217/989 +f 217/217/989 215/215/988 216/216/990 +f 305/305/983 300/300/991 283/283/992 +f 283/283/992 300/300/991 304/304/993 +f 283/283/869 304/304/858 210/210/868 +f 210/210/868 304/304/858 207/207/857 +f 210/210/994 207/207/978 209/209/989 +f 209/209/989 207/207/978 208/208/995 +f 290/290/965 280/280/996 289/289/997 +f 289/289/997 280/280/996 283/283/998 +f 289/289/893 283/283/869 202/202/891 +f 202/202/891 283/283/869 199/199/857 +f 202/202/977 199/199/988 201/201/989 +f 201/201/989 199/199/988 200/200/995 +f 262/262/999 254/254/1000 263/263/1001 +f 263/263/1001 254/254/1000 257/257/1002 +f 263/263/899 257/257/894 194/194/1003 +f 194/194/1003 257/257/894 190/190/892 +f 194/194/1004 190/190/1005 192/192/1006 +f 192/192/1006 190/190/1005 191/191/1007 +f 244/244/1008 238/238/1008 237/237/1008 +f 244/244/1009 237/237/1009 371/371/1009 +f 235/235/1010 229/229/1010 228/228/1010 +f 235/235/1011 228/228/1011 349/349/1011 +f 227/227/1010 221/221/1010 220/220/1010 +f 227/227/1012 220/220/1012 329/329/1012 +f 219/219/1013 213/213/1013 212/212/1013 +f 219/219/1012 212/212/1012 312/312/1012 +f 211/211/1013 205/205/1013 204/204/1013 +f 211/211/1012 204/204/1012 292/292/1012 +f 203/203/1013 197/197/1013 196/196/1013 +f 203/203/1012 196/196/1012 272/272/1012 +f 193/193/1014 189/189/1015 195/195/1016 +f 195/195/1016 189/189/1015 188/188/1017 +f 195/195/1018 188/188/1019 259/259/614 +f 259/259/614 188/188/1019 246/246/615 +f 605/605/1020 604/604/1021 590/590/902 +f 590/590/902 604/604/1021 591/591/903 +f 511/511/721 512/512/722 606/606/1022 +f 606/606/1022 512/512/722 607/607/1023 +f 608/608/1024 609/609/1025 396/396/620 +f 396/396/620 609/609/1025 397/397/621 +f 394/394/618 395/395/619 608/608/1026 +f 608/608/1026 395/395/619 609/609/1027 +f 398/398/622 399/399/623 601/601/913 +f 601/601/913 399/399/623 603/603/915 +f 413/413/1028 415/415/1028 610/610/1028 +f 194/194/1029 195/195/1029 611/611/1029 +f 586/586/896 612/612/1030 613/613/1031 +f 614/614/1032 615/615/1032 616/616/1032 +f 587/587/1033 617/617/1033 588/588/1033 +f 195/195/1034 258/258/1034 618/618/1034 +f 619/619/1035 411/411/1036 617/617/1037 +f 587/587/1038 619/619/1035 617/617/1037 +f 620/620/1039 621/621/1039 622/622/1039 +f 267/267/960 264/264/1040 623/623/1041 +f 264/264/1042 266/266/1043 624/624/1044 +f 266/266/1045 261/261/1045 625/625/1045 +f 410/410/1046 413/413/1046 626/626/1046 +f 410/410/1047 626/626/1047 627/627/1047 +f 263/263/899 194/194/1003 589/589/900 +f 627/627/1048 617/617/1037 411/411/1036 +f 628/628/1049 620/620/1049 622/622/1049 +f 623/623/1050 629/629/1050 417/417/1050 +f 258/258/1051 628/628/1051 630/630/1051 +f 628/628/1052 622/622/1052 630/630/1052 +f 618/618/1053 258/258/1053 630/630/1053 +f 611/611/1054 195/195/1054 618/618/1054 +f 589/589/1055 194/194/1055 611/611/1055 +f 631/631/1056 261/261/901 589/589/900 +f 625/625/1057 261/261/901 631/631/1056 +f 624/624/1044 266/266/1043 625/625/1058 +f 632/632/1059 264/264/1042 624/624/1044 +f 623/623/1060 264/264/1060 632/632/1060 +f 411/411/1061 410/410/1061 627/627/1061 +f 615/615/1062 613/613/1062 616/616/1062 +f 610/610/1063 415/415/1063 629/629/1063 +f 267/267/960 623/623/1041 417/417/958 +f 615/615/1064 586/586/1064 613/613/1064 +f 586/586/896 588/588/898 612/612/1030 +f 415/415/1065 417/417/1065 629/629/1065 +f 614/614/1066 616/616/1066 621/621/1066 +f 621/621/1067 620/620/1067 614/614/1067 +f 609/609/1068 395/395/1069 633/633/1070 +f 582/582/71 634/634/71 585/585/71 +f 585/585/71 634/634/71 635/635/71 +f 628/628/210 258/258/641 636/636/641 +f 636/636/641 637/637/210 628/628/210 +f 628/628/210 637/637/210 620/620/210 +f 572/572/71 638/638/1071 574/574/1072 +f 574/574/1072 638/638/1071 639/639/1073 +f 584/584/1074 640/640/1075 583/583/210 +f 584/584/1074 639/639/1076 640/640/1075 +f 561/561/1077 641/641/1078 565/565/1079 +f 565/565/1079 641/641/1078 642/642/1080 +f 561/561/1077 643/643/1081 641/641/1078 +f 573/573/1082 641/641/1083 571/571/1084 +f 573/573/1082 642/642/1085 641/641/1083 +f 641/641/1083 643/643/1086 571/571/1084 +f 553/553/1077 644/644/1078 557/557/1079 +f 557/557/1079 644/644/1078 645/645/1080 +f 553/553/1077 646/646/1087 644/644/1078 +f 564/564/1082 644/644/1083 563/563/1084 +f 564/564/1082 645/645/1085 644/644/1083 +f 644/644/1083 646/646/1086 563/563/1084 +f 546/546/1077 647/647/1078 549/549/1079 +f 549/549/1079 647/647/1078 648/648/1088 +f 546/546/1077 649/649/1081 647/647/1078 +f 556/556/1082 647/647/1083 555/555/1084 +f 556/556/1082 648/648/1085 647/647/1083 +f 647/647/1083 649/649/1086 555/555/1084 +f 539/539/71 650/650/1071 541/541/1072 +f 541/541/1072 650/650/1071 651/651/1073 +f 548/548/1089 652/652/1090 547/547/210 +f 548/548/1089 651/651/1076 652/652/1090 +f 525/525/1091 653/653/1092 527/527/1093 +f 527/527/1093 653/653/1092 654/654/1094 +f 540/540/1089 655/655/1090 538/538/210 +f 540/540/1089 654/654/1076 655/655/1090 +f 634/634/1095 637/637/1096 636/636/1097 +f 634/634/1095 636/636/1097 635/635/1098 +f 638/638/1099 640/640/1099 639/639/1099 +f 650/650/1100 652/652/1100 651/651/1100 +f 653/653/1100 655/655/1100 654/654/1100 +f 401/401/71 656/656/71 576/576/71 +f 580/580/71 657/657/71 582/582/71 +f 656/656/71 658/658/71 576/576/71 +f 576/576/71 658/658/71 578/578/71 +f 578/578/71 658/658/71 659/659/71 +f 578/578/71 659/659/71 580/580/71 +f 580/580/71 659/659/71 660/660/71 +f 580/580/71 660/660/71 657/657/71 +f 661/661/210 619/619/462 587/587/210 +f 614/614/210 662/662/210 615/615/210 +f 615/615/210 662/662/210 663/663/1101 +f 615/615/210 663/663/1101 586/586/210 +f 586/586/210 663/663/1101 664/664/210 +f 586/586/210 664/664/210 587/587/210 +f 587/587/210 664/664/210 661/661/210 +f 614/614/210 665/665/1102 662/662/210 +f 567/567/1103 420/420/1104 666/666/1105 +f 666/666/1105 667/667/1106 567/567/1103 +f 567/567/1103 667/667/1106 668/668/1107 +f 668/668/1107 667/667/1106 669/669/1108 +f 669/669/1108 667/667/1106 670/670/1109 +f 669/669/1108 670/670/1109 568/568/1110 +f 568/568/1110 670/670/1109 671/671/1111 +f 568/568/1110 671/671/1111 569/569/1112 +f 569/569/1112 671/671/1111 672/672/71 +f 673/673/210 575/575/210 577/577/210 +f 583/583/210 674/674/210 581/581/210 +f 581/581/210 675/675/210 579/579/210 +f 579/579/210 675/675/210 676/676/210 +f 579/579/210 676/676/210 577/577/210 +f 577/577/210 676/676/210 677/677/210 +f 577/577/210 677/677/210 673/673/210 +f 581/581/210 674/674/210 675/675/210 +f 434/434/1113 678/678/1114 559/559/1115 +f 560/560/1116 679/679/1117 561/561/1118 +f 678/678/1114 680/680/1119 559/559/1115 +f 559/559/1115 680/680/1119 681/681/1120 +f 681/681/1120 680/680/1119 682/682/1121 +f 681/681/1120 682/682/1121 683/683/1122 +f 683/683/1122 682/682/1121 684/684/1123 +f 683/683/1122 684/684/1123 560/560/1116 +f 560/560/1116 684/684/1123 685/685/1124 +f 560/560/1116 685/685/1124 679/679/1117 +f 686/686/1125 566/566/1126 567/567/1127 +f 568/568/1128 570/570/1129 687/687/1130 +f 568/568/1128 685/685/1131 669/669/1132 +f 669/669/1132 685/685/1131 684/684/1133 +f 669/669/1132 684/684/1133 668/668/1134 +f 668/668/1134 684/684/1133 682/682/1135 +f 668/668/1134 682/682/1135 567/567/1127 +f 567/567/1127 682/682/1135 680/680/1136 +f 567/567/1127 680/680/1136 686/686/1125 +f 568/568/1128 687/687/1130 685/685/1131 +f 552/552/1137 688/688/1117 553/553/1118 +f 551/551/1138 449/449/1104 689/689/1139 +f 689/689/1139 690/690/1140 551/551/1138 +f 551/551/1138 690/690/1140 691/691/1120 +f 691/691/1120 690/690/1140 692/692/1121 +f 691/691/1120 692/692/1121 693/693/1122 +f 693/693/1122 692/692/1121 694/694/1123 +f 693/693/1122 694/694/1123 552/552/1137 +f 552/552/1137 694/694/1123 695/695/1141 +f 552/552/1137 695/695/1141 688/688/1117 +f 696/696/1125 558/558/1126 559/559/1127 +f 560/560/1142 562/562/1143 697/697/1144 +f 560/560/1142 695/695/1145 683/683/1146 +f 683/683/1146 695/695/1145 694/694/1133 +f 683/683/1146 694/694/1133 681/681/1147 +f 681/681/1147 694/694/1133 692/692/1135 +f 681/681/1147 692/692/1135 559/559/1127 +f 559/559/1127 692/692/1135 690/690/1136 +f 559/559/1127 690/690/1136 696/696/1125 +f 560/560/1142 697/697/1144 695/695/1145 +f 545/545/1148 698/698/1149 546/546/1150 +f 543/543/1151 464/464/1104 699/699/1139 +f 699/699/1139 700/700/1152 543/543/1151 +f 543/543/1151 700/700/1152 701/701/1153 +f 701/701/1153 700/700/1152 702/702/1154 +f 701/701/1153 702/702/1154 703/703/1155 +f 701/701/1153 703/703/1155 704/704/1156 +f 704/704/1156 703/703/1155 545/545/1148 +f 545/545/1148 703/703/1155 705/705/1157 +f 545/545/1148 705/705/1157 698/698/1149 +f 706/706/1125 550/550/1126 551/551/1127 +f 552/552/1158 554/554/1143 707/707/1144 +f 552/552/1158 705/705/1145 693/693/1146 +f 693/693/1146 705/705/1145 703/703/1133 +f 693/693/1146 703/703/1133 691/691/1134 +f 691/691/1134 703/703/1133 702/702/1135 +f 691/691/1134 702/702/1135 551/551/1127 +f 551/551/1127 702/702/1135 700/700/1136 +f 551/551/1127 700/700/1136 706/706/1125 +f 552/552/1158 707/707/1144 705/705/1145 +f 533/533/1159 531/531/1160 708/708/1161 +f 708/708/1161 709/709/1162 533/533/1159 +f 533/533/1159 709/709/1162 534/534/1163 +f 534/534/1163 709/709/1162 710/710/1164 +f 534/534/1163 710/710/1164 535/535/1165 +f 535/535/1165 710/710/1164 711/711/1166 +f 535/535/1165 711/711/1166 536/536/1167 +f 536/536/1167 711/711/1166 712/712/71 +f 713/713/1168 542/542/1126 543/543/1169 +f 545/545/1170 544/544/1171 714/714/1172 +f 545/545/1170 715/715/1173 704/704/1174 +f 704/704/1174 715/715/1173 716/716/1175 +f 704/704/1174 716/716/1175 701/701/1176 +f 701/701/1176 716/716/1175 543/543/1169 +f 543/543/1169 716/716/1175 717/717/1177 +f 543/543/1169 717/717/1177 713/713/1168 +f 545/545/1170 714/714/1172 715/715/1173 +f 494/494/71 718/718/71 520/520/71 +f 718/718/71 719/719/71 520/520/71 +f 520/520/71 719/719/71 518/518/71 +f 518/518/71 719/719/71 720/720/71 +f 518/518/71 720/720/71 524/524/71 +f 524/524/71 720/720/71 721/721/1178 +f 524/524/71 721/721/1178 522/522/1179 +f 522/522/1179 721/721/1178 722/722/1180 +f 723/723/1181 531/531/1182 532/532/1183 +f 535/535/1184 537/537/1185 724/724/1186 +f 535/535/1184 725/725/1187 534/534/1188 +f 534/534/1188 725/725/1187 726/726/1189 +f 534/534/1188 726/726/1189 532/532/1183 +f 532/532/1183 726/726/1189 727/727/210 +f 532/532/1183 727/727/210 723/723/1181 +f 535/535/1184 724/724/1186 725/725/1187 +f 656/656/1190 661/661/1191 664/664/1192 +f 656/656/1190 664/664/1192 658/658/1193 +f 658/658/1194 664/664/1195 663/663/1196 +f 658/658/1194 663/663/1196 659/659/1197 +f 659/659/1197 663/663/1196 662/662/1198 +f 659/659/1197 662/662/1198 660/660/1199 +f 660/660/1199 662/662/1198 665/665/1200 +f 660/660/1199 665/665/1200 657/657/1201 +f 666/666/1202 673/673/1202 677/677/1202 +f 666/666/1203 677/677/1203 667/667/1203 +f 667/667/1204 677/677/1204 676/676/1204 +f 667/667/1106 676/676/1205 670/670/1109 +f 670/670/1206 676/676/1206 675/675/1206 +f 670/670/1109 675/675/1207 671/671/1111 +f 671/671/1208 675/675/1208 674/674/1208 +f 671/671/1209 674/674/1209 672/672/1209 +f 678/678/1210 686/686/1210 680/680/1210 +f 685/685/1211 687/687/1211 679/679/1211 +f 689/689/1212 696/696/1212 690/690/1212 +f 695/695/1213 697/697/1213 688/688/1213 +f 699/699/1212 706/706/1212 700/700/1212 +f 705/705/1214 707/707/1214 698/698/1214 +f 708/708/1215 713/713/1215 717/717/1215 +f 708/708/1203 717/717/1203 709/709/1203 +f 709/709/1204 717/717/1177 716/716/1175 +f 709/709/1162 716/716/1205 710/710/1164 +f 710/710/1206 716/716/1175 715/715/1173 +f 710/710/1164 715/715/1207 711/711/1166 +f 711/711/1216 715/715/1216 714/714/1216 +f 711/711/1217 714/714/1217 712/712/1217 +f 718/718/1218 723/723/1219 727/727/1220 +f 718/718/1218 727/727/1220 719/719/1221 +f 719/719/1204 727/727/1204 726/726/1204 +f 719/719/1205 726/726/1205 720/720/1205 +f 720/720/1206 726/726/1189 725/725/1187 +f 720/720/1207 725/725/1207 721/721/1207 +f 721/721/1216 725/725/1216 724/724/1216 +f 721/721/1217 724/724/1217 722/722/1217 +f 728/728/1222 729/729/1223 730/730/1224 +f 730/730/1224 729/729/1223 731/731/1225 +f 732/732/1226 733/733/1227 734/734/1228 +f 734/734/1228 733/733/1227 735/735/1229 +f 736/736/1230 737/737/1231 738/738/1232 +f 736/736/1230 738/738/1232 739/739/1233 +f 739/739/1233 738/738/1232 740/740/1234 +f 740/740/1234 738/738/1232 741/741/1235 +f 740/740/1234 741/741/1235 742/742/1236 +f 742/742/1236 741/741/1235 729/729/1223 +f 742/742/1236 729/729/1223 728/728/1222 +f 743/743/1237 744/744/1238 745/745/1239 +f 743/743/1237 745/745/1239 746/746/1240 +f 723/723/1241 718/718/1241 531/531/1241 +f 531/531/1242 718/718/1242 494/494/1242 +f 531/531/770 494/494/1243 504/504/769 +f 504/504/1244 494/494/1244 493/493/1244 +f 713/713/1245 708/708/1246 542/542/1247 +f 542/542/1247 708/708/1246 531/531/1248 +f 542/542/1249 531/531/770 480/480/768 +f 542/542/1249 480/480/768 491/491/1250 +f 491/491/1251 480/480/1252 479/479/1253 +f 491/491/1251 479/479/1253 489/489/1254 +f 706/706/1245 699/699/1255 550/550/1256 +f 550/550/1256 699/699/1255 464/464/1257 +f 550/550/1258 464/464/1258 476/476/1258 +f 476/476/1259 464/464/1259 463/463/1259 +f 476/476/1260 463/463/1260 474/474/1260 +f 696/696/1245 689/689/1261 558/558/1262 +f 558/558/1262 689/689/1261 449/449/1263 +f 558/558/1258 449/449/1258 460/460/1258 +f 460/460/1259 449/449/1259 448/448/1259 +f 460/460/1260 448/448/1260 458/458/1260 +f 686/686/1264 678/678/1264 566/566/1264 +f 566/566/1265 678/678/1265 434/434/1265 +f 566/566/1266 434/434/1266 445/445/1266 +f 445/445/1267 434/434/1268 433/433/1269 +f 445/445/1267 433/433/1269 443/443/1254 +f 673/673/1245 666/666/1255 575/575/1262 +f 575/575/1262 666/666/1255 420/420/1257 +f 575/575/1258 420/420/1258 430/430/1258 +f 430/430/1270 420/420/1270 419/419/1270 +f 661/661/1271 656/656/1271 619/619/1271 +f 619/619/1272 656/656/1272 401/401/1272 +f 619/619/1035 401/401/1273 411/411/1036 +f 411/411/1274 401/401/1275 400/400/1276 +f 411/411/1274 400/400/1276 409/409/1277 +f 655/655/1278 653/653/1279 538/538/1280 +f 538/538/1280 653/653/1279 525/525/1281 +f 538/538/776 525/525/743 537/537/775 +f 537/537/775 525/525/743 522/522/745 +f 537/537/1282 522/522/1283 724/724/1284 +f 724/724/1284 522/522/1283 722/722/1285 +f 652/652/1278 650/650/1286 547/547/1287 +f 547/547/1287 650/650/1286 539/539/1288 +f 547/547/807 539/539/777 544/544/804 +f 544/544/804 539/539/777 536/536/774 +f 544/544/1289 536/536/1290 714/714/1291 +f 714/714/1291 536/536/1290 712/712/1292 +f 555/555/1293 649/649/1293 546/546/1293 +f 555/555/829 546/546/1294 554/554/828 +f 554/554/1295 546/546/1295 698/698/1295 +f 554/554/1296 698/698/1296 707/707/1296 +f 563/563/1293 646/646/1293 553/553/1293 +f 563/563/852 553/553/1297 562/562/851 +f 562/562/1295 553/553/1295 688/688/1295 +f 562/562/1298 688/688/1298 697/697/1298 +f 571/571/1293 643/643/1293 561/561/1293 +f 571/571/864 561/561/1297 570/570/863 +f 570/570/1295 561/561/1295 679/679/1295 +f 570/570/1299 679/679/1300 687/687/1300 +f 640/640/1301 638/638/1302 583/583/1303 +f 583/583/1303 638/638/1302 572/572/1304 +f 583/583/1305 572/572/865 569/569/862 +f 583/583/1306 569/569/1306 674/674/1306 +f 674/674/1307 569/569/1307 672/672/1307 +f 637/637/1308 634/634/1309 620/620/1310 +f 620/620/1310 634/634/1309 582/582/1311 +f 620/620/1312 582/582/1312 614/614/1312 +f 614/614/1313 582/582/1313 657/657/1313 +f 614/614/1314 657/657/1314 665/665/1314 +f 383/383/1315 372/372/1315 370/370/1315 +f 383/383/780 370/370/749 540/540/778 +f 540/540/778 370/370/749 527/527/748 +f 540/540/778 527/527/748 654/654/1316 +f 548/548/808 348/348/781 541/541/779 +f 548/548/1317 541/541/1317 651/651/1317 +f 311/311/832 330/330/1318 328/328/810 +f 311/311/832 328/328/810 556/556/830 +f 556/556/830 328/328/810 549/549/809 +f 556/556/1317 549/549/1317 648/648/1317 +f 291/291/854 313/313/1319 311/311/832 +f 291/291/854 311/311/832 564/564/853 +f 564/564/853 311/311/832 557/557/831 +f 564/564/1320 557/557/1320 645/645/1320 +f 271/271/854 293/293/1319 291/291/854 +f 271/271/854 291/291/854 573/573/866 +f 573/573/866 291/291/854 565/565/831 +f 573/573/1320 565/565/1320 642/642/1320 +f 245/245/890 273/273/1319 271/271/854 +f 245/245/890 271/271/854 584/584/887 +f 584/584/887 271/271/854 574/574/867 +f 584/584/1320 574/574/1320 639/639/1320 +f 260/260/1321 247/247/1322 258/258/1323 +f 258/258/1323 247/247/1322 245/245/890 +f 258/258/1323 245/245/890 585/585/889 +f 258/258/1323 585/585/889 636/636/1324 +f 636/636/1325 585/585/1325 635/635/1325 +f 599/599/911 598/598/910 745/745/1326 +f 745/745/1326 598/598/910 746/746/1327 +f 744/744/1238 743/743/1237 736/736/1230 +f 736/736/1230 743/743/1237 737/737/1231 +f 733/733/1227 732/732/1226 747/747/1328 +f 747/747/1328 732/732/1226 748/748/1329 +f 747/747/1330 748/748/1331 731/731/1225 +f 731/731/1225 748/748/1331 730/730/1224 +f 600/600/912 602/602/914 735/735/1229 +f 735/735/1229 602/602/914 734/734/1228 +f 633/633/1070 749/749/1332 609/609/1068 +f 609/609/1068 749/749/1332 397/397/1333 +f 730/730/1334 750/750/1334 728/728/1334 +f 730/730/1224 748/748/1331 750/750/1335 +f 751/751/1336 752/752/1337 753/753/1338 +f 754/754/1339 755/755/1340 756/756/1341 +f 751/751/1336 754/754/1339 756/756/1341 +f 757/757/1342 758/758/1343 759/759/1344 +f 757/757/1342 760/760/1345 758/758/1343 +f 761/761/1346 760/760/1345 757/757/1342 +f 762/762/1347 761/761/1346 757/757/1342 +f 763/763/1348 764/764/1349 765/765/1350 +f 764/764/1349 766/766/1351 767/767/1352 +f 764/764/1349 767/767/1352 765/765/1350 +f 766/766/1351 764/764/1349 768/768/1353 +f 769/769/1354 770/770/1355 766/766/1356 +f 771/771/1357 770/770/1355 769/769/1354 +f 772/772/1358 770/770/1355 771/771/1357 +f 773/773/1359 774/774/1360 775/775/1361 +f 773/773/1359 775/775/1361 776/776/1362 +f 777/777/1363 778/778/1364 779/779/1365 +f 778/778/1364 780/780/1366 779/779/1365 +f 781/781/1367 782/782/1368 783/783/1369 +f 784/784/1370 785/785/1371 786/786/1372 +f 787/787/1373 788/788/1374 789/789/1375 +f 787/787/1373 789/789/1375 790/790/1376 +f 791/791/1377 792/792/1378 790/790/1376 +f 791/791/1377 793/793/1379 792/792/1378 +f 769/769/1354 794/794/1380 771/771/1357 +f 764/764/1349 794/794/1380 768/768/1353 +f 772/772/1358 771/771/1357 795/795/1381 +f 791/791/1377 790/790/1376 789/789/1375 +f 786/786/1372 789/789/1375 788/788/1374 +f 786/786/1372 788/788/1374 784/784/1370 +f 794/794/1380 764/764/1349 771/771/1357 +f 771/771/1357 796/796/1382 795/795/1381 +f 763/763/1348 797/797/1383 764/764/1349 +f 764/764/1349 797/797/1383 798/798/1384 +f 764/764/1349 798/798/1384 771/771/1357 +f 771/771/1357 798/798/1384 796/796/1382 +f 795/795/1381 796/796/1382 799/799/1385 +f 800/800/1386 801/801/1387 763/763/1348 +f 763/763/1348 801/801/1387 797/797/1383 +f 799/799/1385 796/796/1382 776/776/1362 +f 800/800/1386 802/802/1388 801/801/1387 +f 798/798/1384 773/773/1359 796/796/1382 +f 796/796/1382 773/773/1359 776/776/1362 +f 797/797/1383 801/801/1387 803/803/1389 +f 797/797/1383 803/803/1389 798/798/1384 +f 798/798/1384 803/803/1389 773/773/1359 +f 751/751/1336 753/753/1338 791/791/1377 +f 786/786/1372 785/785/1371 804/804/1390 +f 791/791/1377 753/753/1338 793/793/1379 +f 805/805/1391 791/791/1377 789/789/1375 +f 805/805/1391 789/789/1375 786/786/1372 +f 802/802/1388 806/806/1392 807/807/1393 +f 802/802/1388 807/807/1393 801/801/1387 +f 773/773/1359 803/803/1389 808/808/1394 +f 773/773/1359 808/808/1394 774/774/1360 +f 809/809/1395 762/762/1347 807/807/1393 +f 809/809/1395 807/807/1393 806/806/1392 +f 801/801/1387 807/807/1393 803/803/1389 +f 774/774/1360 808/808/1394 777/777/1363 +f 774/774/1360 777/777/1363 810/810/1396 +f 757/757/1342 759/759/1344 751/751/1336 +f 757/757/1342 751/751/1336 811/811/1397 +f 812/812/1398 813/813/1399 814/814/1400 +f 814/814/1400 813/813/1399 815/815/1401 +f 814/814/1400 815/815/1401 777/777/1363 +f 777/777/1363 815/815/1401 778/778/1364 +f 811/811/1397 751/751/1336 816/816/1402 +f 811/811/1397 816/816/1402 812/812/1398 +f 778/778/1364 815/815/1401 783/783/1369 +f 759/759/1344 754/754/1339 751/751/1336 +f 812/812/1398 816/816/1402 805/805/1391 +f 812/812/1398 805/805/1391 813/813/1399 +f 815/815/1401 781/781/1367 783/783/1369 +f 751/751/1336 756/756/1341 752/752/1337 +f 751/751/1336 791/791/1377 816/816/1402 +f 816/816/1402 791/791/1377 805/805/1391 +f 813/813/1399 805/805/1391 786/786/1372 +f 813/813/1399 786/786/1372 815/815/1401 +f 815/815/1401 786/786/1372 804/804/1390 +f 815/815/1401 804/804/1390 781/781/1367 +f 781/781/1367 804/804/1390 817/817/1403 +f 807/807/1393 762/762/1347 757/757/1342 +f 803/803/1389 812/812/1398 808/808/1394 +f 810/810/1396 777/777/1363 779/779/1365 +f 807/807/1393 757/757/1342 811/811/1397 +f 807/807/1393 811/811/1397 803/803/1389 +f 803/803/1389 811/811/1397 812/812/1398 +f 808/808/1394 812/812/1398 814/814/1400 +f 808/808/1394 814/814/1400 777/777/1363 +f 818/818/1404 395/395/619 819/819/1405 +f 819/819/1405 395/395/619 393/393/617 +f 820/820/1406 399/399/623 397/397/621 +f 820/820/1406 397/397/621 821/821/1407 +f 393/393/617 822/822/1408 819/819/1405 +f 507/507/717 822/822/1408 393/393/617 +f 822/822/1408 507/507/717 823/823/1409 +f 823/823/1409 507/507/717 824/824/1410 +f 509/509/719 824/824/1410 507/507/717 +f 824/824/1410 509/509/719 825/825/1411 +f 825/825/1411 509/509/719 826/826/1412 +f 826/826/1412 509/509/719 511/511/721 +f 827/827/1413 590/590/902 828/828/1414 +f 828/828/1414 590/590/902 593/593/905 +f 593/593/905 829/829/1415 828/828/1414 +f 595/595/907 829/829/1415 593/593/905 +f 829/829/1415 595/595/907 830/830/1416 +f 831/831/1417 830/830/1416 595/595/907 +f 831/831/1417 595/595/907 596/596/908 +f 831/831/1417 596/596/908 832/832/1418 +f 599/599/911 832/832/1418 596/596/908 +f 833/833/1419 834/834/1420 602/602/914 +f 833/833/1419 602/602/914 603/603/915 +f 833/833/1419 603/603/915 767/767/1421 +f 399/399/623 767/767/1421 603/603/915 +f 399/399/623 820/820/1422 767/767/1421 +f 835/835/71 836/836/71 837/837/71 +f 837/837/71 836/836/71 838/838/71 +f 839/839/71 840/840/71 841/841/71 +f 839/839/71 841/841/71 842/842/71 +f 843/843/1423 768/768/1424 844/844/1425 +f 844/844/1425 768/768/1424 794/794/1426 +f 768/768/1427 843/843/1428 845/845/1429 +f 768/768/1427 845/845/1429 766/766/1430 +f 846/846/1431 766/766/1432 845/845/1433 +f 846/846/1431 769/769/1434 766/766/1432 +f 844/844/1435 794/794/1436 846/846/1437 +f 846/846/1437 794/794/1436 769/769/1438 +f 838/838/1439 760/760/1440 837/837/1441 +f 837/837/1441 760/760/1440 755/755/1442 +f 760/760/1443 838/838/1443 758/758/1443 +f 758/758/1444 838/838/1445 836/836/1446 +f 758/758/1444 836/836/1446 759/759/1447 +f 759/759/1448 836/836/1449 835/835/1450 +f 759/759/1448 835/835/1450 754/754/1451 +f 754/754/1452 835/835/1453 755/755/1454 +f 837/837/1455 755/755/1454 835/835/1453 +f 847/847/1456 848/848/1457 849/849/1458 +f 749/749/1459 850/850/1460 851/851/1461 +f 633/633/1462 852/852/1463 850/850/1460 +f 633/633/1462 850/850/1460 749/749/1459 +f 511/511/721 853/853/1464 826/826/1412 +f 853/853/1464 511/511/721 848/848/1457 +f 853/853/1464 848/848/1457 847/847/1456 +f 590/590/902 854/854/1465 848/848/1466 +f 848/848/1466 854/854/1465 849/849/1467 +f 590/590/902 827/827/1413 854/854/1465 +f 397/397/621 855/855/1468 821/821/1407 +f 855/855/1468 397/397/621 851/851/1461 +f 851/851/1461 397/397/621 749/749/1459 +f 395/395/619 856/856/1469 633/633/1462 +f 633/633/1462 856/856/1469 852/852/1463 +f 395/395/619 818/818/1404 856/856/1469 +f 832/832/1418 788/788/1374 831/831/1417 +f 831/831/1417 788/788/1374 787/787/1373 +f 787/787/1373 790/790/1376 830/830/1416 +f 830/830/1416 790/790/1376 829/829/1415 +f 828/828/1414 790/790/1376 792/792/1378 +f 831/831/1417 787/787/1373 830/830/1416 +f 788/788/1374 832/832/1418 784/784/1370 +f 828/828/1414 792/792/1378 827/827/1413 +f 828/828/1414 829/829/1415 790/790/1376 +f 793/793/1379 854/854/1465 827/827/1413 +f 793/793/1379 827/827/1413 792/792/1378 +f 793/793/1379 857/857/1470 854/854/1465 +f 854/854/1465 857/857/1470 849/849/1467 +f 753/753/1338 857/857/1470 793/793/1379 +f 847/847/1471 849/849/1471 857/857/1471 +f 857/857/1470 753/753/1338 752/752/1337 +f 853/853/1464 847/847/1456 857/857/1470 +f 853/853/1464 857/857/1470 752/752/1337 +f 853/853/1464 752/752/1337 826/826/1412 +f 755/755/1340 760/760/1345 761/761/1346 +f 819/819/1405 822/822/1408 762/762/1347 +f 761/761/1346 822/822/1408 823/823/1409 +f 761/761/1346 823/823/1409 824/824/1410 +f 755/755/1340 824/824/1410 756/756/1341 +f 826/826/1412 756/756/1341 825/825/1411 +f 825/825/1411 756/756/1341 824/824/1410 +f 756/756/1341 826/826/1412 752/752/1337 +f 755/755/1340 761/761/1346 824/824/1410 +f 761/761/1346 762/762/1347 822/822/1408 +f 818/818/1404 819/819/1405 809/809/1395 +f 819/819/1405 762/762/1347 809/809/1395 +f 809/809/1395 806/806/1472 852/852/1463 +f 852/852/1463 856/856/1469 809/809/1395 +f 818/818/1404 809/809/1395 856/856/1469 +f 802/802/1473 852/852/1463 806/806/1472 +f 850/850/1460 852/852/1463 802/802/1473 +f 851/851/1474 850/850/1460 802/802/1473 +f 855/855/1475 800/800/1386 821/821/1476 +f 802/802/1477 800/800/1386 855/855/1475 +f 802/802/1477 855/855/1475 851/851/1478 +f 765/765/1350 820/820/1422 763/763/1348 +f 821/821/1476 763/763/1348 820/820/1422 +f 821/821/1476 800/800/1386 763/763/1348 +f 767/767/1421 820/820/1422 765/765/1350 +f 770/770/1355 834/834/1420 766/766/1351 +f 833/833/1419 766/766/1351 834/834/1420 +f 766/766/1351 833/833/1419 767/767/1352 +f 858/858/1479 750/750/1480 859/859/1481 +f 734/734/1228 860/860/1482 732/732/1226 +f 860/860/1482 861/861/1483 732/732/1226 +f 862/862/1484 736/736/1230 863/863/1485 +f 863/863/1485 736/736/1230 739/739/1233 +f 740/740/1234 864/864/1486 863/863/1485 +f 740/740/1234 863/863/1485 739/739/1233 +f 742/742/1236 864/864/1486 740/740/1234 +f 865/865/1487 864/864/1486 742/742/1236 +f 858/858/1479 865/865/1487 742/742/1236 +f 858/858/1479 742/742/1236 728/728/1222 +f 858/858/1479 728/728/1222 750/750/1480 +f 860/860/1482 734/734/1228 602/602/914 +f 602/602/914 834/834/1420 860/860/1482 +f 780/780/1488 841/841/1488 782/782/1488 +f 782/782/1489 841/841/1489 840/840/1489 +f 782/782/1490 840/840/1490 783/783/1490 +f 783/783/1491 840/840/1491 839/839/1491 +f 783/783/1492 839/839/1492 778/778/1492 +f 778/778/1493 839/839/1493 842/842/1493 +f 778/778/1494 842/842/1494 780/780/1494 +f 780/780/1495 842/842/1495 841/841/1495 +f 866/866/1496 867/867/1497 868/868/1498 +f 869/869/1499 870/870/1500 871/871/1501 +f 872/872/1502 873/873/1503 869/869/1504 +f 869/869/1504 873/873/1503 870/870/1505 +f 736/736/1230 874/874/1506 866/866/1496 +f 866/866/1496 874/874/1506 867/867/1497 +f 862/862/1484 874/874/1506 736/736/1230 +f 599/599/911 875/875/1507 832/832/1418 +f 875/875/1507 599/599/911 866/866/1508 +f 875/875/1507 866/866/1508 868/868/1509 +f 732/732/1226 876/876/1510 872/872/1511 +f 872/872/1511 876/876/1510 873/873/1512 +f 861/861/1483 876/876/1510 732/732/1226 +f 859/859/1481 750/750/1480 877/877/1513 +f 877/877/1513 750/750/1480 871/871/1501 +f 871/871/1501 750/750/1480 869/869/1499 +f 875/875/1514 868/868/1515 785/785/1371 +f 832/832/1418 875/875/1514 784/784/1370 +f 784/784/1370 875/875/1514 785/785/1371 +f 804/804/1516 785/785/1371 868/868/1515 +f 868/868/1515 867/867/1517 804/804/1516 +f 817/817/1403 804/804/1516 867/867/1517 +f 862/862/1484 817/817/1403 874/874/1506 +f 867/867/1517 874/874/1506 817/817/1403 +f 779/779/1365 780/780/1518 781/781/1367 +f 781/781/1367 780/780/1519 782/782/1368 +f 858/858/1520 779/779/1365 865/865/1487 +f 865/865/1487 779/779/1365 864/864/1486 +f 864/864/1486 781/781/1367 863/863/1485 +f 863/863/1485 781/781/1367 862/862/1484 +f 817/817/1403 862/862/1484 781/781/1367 +f 781/781/1367 864/864/1486 779/779/1365 +f 779/779/1365 858/858/1520 810/810/1396 +f 774/774/1360 810/810/1396 859/859/1521 +f 858/858/1520 859/859/1521 810/810/1396 +f 775/775/1361 774/774/1360 877/877/1522 +f 775/775/1361 877/877/1522 871/871/1523 +f 859/859/1521 877/877/1522 774/774/1360 +f 776/776/1362 775/775/1524 870/870/1500 +f 870/870/1500 775/775/1524 871/871/1501 +f 870/870/1500 873/873/1525 776/776/1362 +f 876/876/1526 861/861/1483 799/799/1385 +f 873/873/1525 876/876/1526 776/776/1362 +f 776/776/1362 876/876/1526 799/799/1385 +f 860/860/1482 772/772/1358 795/795/1381 +f 795/795/1381 799/799/1385 861/861/1483 +f 861/861/1483 860/860/1482 795/795/1381 +f 860/860/1482 834/834/1420 772/772/1358 +f 772/772/1358 834/834/1420 770/770/1355 +f 846/846/71 843/843/71 844/844/71 +f 846/846/71 845/845/71 843/843/71 +f 878/878/71 879/879/71 880/880/71 +f 878/878/71 880/880/71 881/881/71 +f 882/882/71 883/883/71 884/884/71 +f 881/881/71 885/885/71 878/878/71 +f 883/883/71 886/886/71 887/887/71 +f 886/886/71 888/888/71 887/887/71 +f 880/880/71 879/879/71 889/889/71 +f 884/884/71 883/883/71 887/887/71 +f 890/890/1527 879/879/1528 885/885/1529 +f 890/890/1527 885/885/1529 881/881/1530 +f 891/891/71 882/882/71 884/884/71 +f 884/884/71 888/888/71 892/892/71 +f 889/889/71 879/879/71 893/893/71 +f 889/889/71 893/893/71 894/894/71 +f 889/889/71 894/894/71 895/895/71 +f 892/892/71 891/891/71 884/884/71 +f 892/892/71 896/896/71 891/891/71 +f 897/897/71 898/898/71 899/899/71 +f 895/895/71 894/894/71 898/898/71 +f 895/895/71 898/898/71 897/897/71 +f 897/897/71 899/899/71 896/896/71 +f 891/891/71 896/896/71 899/899/71 +f 900/900/1531 890/890/1532 901/901/1533 +f 902/902/1534 903/903/210 904/904/1535 +f 905/905/210 901/901/1533 906/906/210 +f 907/907/1536 908/908/210 902/902/210 +f 901/901/1533 890/890/1532 909/909/1537 +f 908/908/210 907/907/1536 903/903/1538 +f 901/901/1533 910/910/210 900/900/1531 +f 901/901/1533 905/905/210 911/911/210 +f 901/901/1533 911/911/210 910/910/210 +f 910/910/210 911/911/210 912/912/210 +f 910/910/210 912/912/210 913/913/210 +f 913/913/210 912/912/210 914/914/210 +f 913/913/210 914/914/210 915/915/210 +f 915/915/210 914/914/210 916/916/210 +f 902/902/210 917/917/210 918/918/210 +f 902/902/210 918/918/210 907/907/1536 +f 915/915/210 916/916/210 919/919/210 +f 919/919/210 916/916/210 917/917/210 +f 917/917/210 916/916/210 918/918/210 +f 888/888/1539 907/907/1540 892/892/1541 +f 892/892/1541 907/907/1540 918/918/1542 +f 892/892/1543 918/918/1543 896/896/1543 +f 896/896/1544 918/918/1544 916/916/1544 +f 896/896/1545 916/916/1545 897/897/1545 +f 897/897/1546 916/916/1546 914/914/1546 +f 897/897/1547 914/914/1547 895/895/1547 +f 895/895/1548 914/914/1548 912/912/1548 +f 895/895/1549 912/912/1550 911/911/1551 +f 895/895/1549 911/911/1551 889/889/1552 +f 889/889/1553 911/911/1553 880/880/1553 +f 880/880/1554 911/911/1555 905/905/1556 +f 880/880/1554 905/905/1556 906/906/1557 +f 881/881/1558 880/880/1558 909/909/1558 +f 909/909/1559 880/880/1559 906/906/1559 +f 881/881/1560 909/909/1560 890/890/1560 +f 879/879/1528 890/890/1527 900/900/1561 +f 879/879/1562 900/900/1562 893/893/1562 +f 893/893/1563 900/900/1563 910/910/1563 +f 893/893/1564 910/910/1564 894/894/1564 +f 894/894/1565 910/910/1565 913/913/1565 +f 894/894/1566 913/913/1566 898/898/1566 +f 898/898/1567 913/913/1567 915/915/1567 +f 898/898/1568 915/915/1568 899/899/1568 +f 899/899/1569 915/915/1569 919/919/1569 +f 899/899/1570 919/919/1570 917/917/1570 +f 899/899/1571 917/917/1571 891/891/1571 +f 891/891/1572 917/917/1573 882/882/1574 +f 882/882/1574 917/917/1573 902/902/1575 +f 883/883/1576 882/882/1576 904/904/1576 +f 904/904/1535 882/882/1577 902/902/1534 +f 883/883/1578 904/904/1578 886/886/1578 +f 886/886/1579 904/904/1579 903/903/1579 +f 888/888/1580 886/886/1580 907/907/1580 +f 907/907/1536 886/886/1581 903/903/1538 +f 879/879/1582 901/901/1583 885/885/1584 +f 885/885/1584 901/901/1583 909/909/1585 +f 885/885/1586 909/909/1587 906/906/1588 +f 885/885/1586 906/906/1588 878/878/1589 +f 878/878/1590 906/906/1590 901/901/1590 +f 878/878/1591 901/901/1591 879/879/1591 +f 888/888/1592 908/908/1592 903/903/1592 +f 888/888/1593 903/903/1593 887/887/1593 +f 887/887/1594 903/903/1594 884/884/1594 +f 884/884/1595 903/903/1595 902/902/1595 +f 884/884/1596 902/902/1597 908/908/1598 +f 884/884/1596 908/908/1598 888/888/1599 +f 920/920/1600 921/921/1601 922/922/1602 +f 923/923/1603 924/924/1604 925/925/1605 +f 926/926/1606 927/927/1607 928/928/1608 +f 929/929/1609 930/930/1610 931/931/1611 +f 932/932/1612 933/933/1613 921/921/1601 +f 934/934/1614 922/922/1614 935/935/1614 +f 933/933/1613 936/936/1615 921/921/1601 +f 937/937/1616 938/938/1617 925/925/1618 +f 939/939/1619 940/940/1620 941/941/1621 +f 942/942/1622 932/932/1623 943/943/1624 +f 944/944/1625 945/945/1626 946/946/1627 +f 946/946/1627 945/945/1626 947/947/1628 +f 939/939/1629 931/931/1630 940/940/1631 +f 948/948/1632 933/933/1632 942/942/1632 +f 942/942/1622 933/933/1633 932/932/1623 +f 932/932/1612 921/921/1601 920/920/1600 +f 949/949/1634 950/950/1634 927/927/1634 +f 933/933/1635 948/948/1636 951/951/1637 +f 949/949/1638 952/952/1639 950/950/1640 +f 925/925/1641 947/947/1642 923/923/1643 +f 953/953/1644 943/943/1644 954/954/1644 +f 955/955/1645 926/926/1606 928/928/1608 +f 956/956/1646 942/942/1646 943/943/1646 +f 954/954/1647 943/943/1624 932/932/1623 +f 928/928/1648 927/927/1649 950/950/1650 +f 928/928/1648 950/950/1650 957/957/1651 +f 945/945/1652 958/958/1653 959/959/1654 +f 925/925/1605 924/924/1604 951/951/1637 +f 951/951/1655 924/924/1655 939/939/1655 +f 921/921/1656 943/943/1657 953/953/1658 +f 960/960/1659 934/934/1660 961/961/1661 +f 923/923/1662 929/929/1609 931/931/1611 +f 922/922/1663 921/921/1663 935/935/1663 +f 938/938/1664 946/946/1627 947/947/1628 +f 956/956/1665 939/939/1619 941/941/1621 +f 961/961/1666 935/935/1666 962/962/1666 +f 962/962/1667 927/927/1607 926/926/1606 +f 947/947/1668 963/963/1669 929/929/1670 +f 940/940/1671 937/937/1671 948/948/1671 +f 933/933/1672 951/951/1672 936/936/1672 +f 958/958/1673 926/926/1673 955/955/1673 +f 937/937/1674 925/925/1674 948/948/1674 +f 948/948/1636 925/925/1605 951/951/1637 +f 964/964/1675 953/953/1675 954/954/1675 +f 952/952/1676 961/961/1677 962/962/1678 +f 952/952/1676 962/962/1678 965/965/1679 +f 965/965/1680 962/962/1680 926/926/1680 +f 947/947/1642 929/929/1681 923/923/1643 +f 956/956/1665 941/941/1621 942/942/1682 +f 960/960/1659 920/920/1683 934/934/1660 +f 961/961/1684 934/934/1684 935/935/1684 +f 957/957/1685 952/952/1639 958/958/1686 +f 963/963/1687 959/959/1688 955/955/1689 +f 935/935/1690 921/921/1690 964/964/1690 +f 952/952/1691 965/965/1691 958/958/1691 +f 955/955/1645 928/928/1608 966/966/1692 +f 944/944/1693 957/957/1693 945/945/1693 +f 929/929/1609 963/963/1694 930/930/1610 +f 924/924/1695 931/931/1695 939/939/1695 +f 941/941/1696 948/948/1696 942/942/1696 +f 935/935/1697 949/949/1698 927/927/1607 +f 930/930/1699 967/967/1700 938/938/1701 +f 964/964/1702 960/960/1702 949/949/1702 +f 963/963/1687 955/955/1689 930/930/1703 +f 936/936/1704 951/951/1705 956/956/1706 +f 936/936/1707 956/956/1707 921/921/1707 +f 964/964/1708 954/954/1647 920/920/1709 +f 964/964/1710 920/920/1710 960/960/1710 +f 928/928/1711 944/944/1712 966/966/1713 +f 966/966/1714 944/944/1714 946/946/1714 +f 928/928/1711 957/957/1715 944/944/1712 +f 947/947/1668 945/945/1716 963/963/1669 +f 940/940/1717 948/948/1717 941/941/1717 +f 931/931/1630 937/937/1718 940/940/1631 +f 921/921/1656 953/953/1658 964/964/1719 +f 958/958/1720 965/965/1720 926/926/1720 +f 955/955/1721 966/966/1721 930/930/1721 +f 952/952/1722 960/960/1659 961/961/1661 +f 950/950/1640 952/952/1639 957/957/1685 +f 935/935/1697 964/964/1723 949/949/1698 +f 967/967/1724 946/946/1724 938/938/1724 +f 938/938/1617 947/947/1725 925/925/1618 +f 951/951/1705 939/939/1726 956/956/1706 +f 921/921/1727 956/956/1727 943/943/1727 +f 949/949/1728 960/960/1728 952/952/1728 +f 930/930/1729 966/966/1729 946/946/1729 +f 930/930/1730 946/946/1730 967/967/1730 +f 954/954/1647 932/932/1623 920/920/1709 +f 920/920/1683 922/922/1731 934/934/1660 +f 962/962/1667 935/935/1697 927/927/1607 +f 957/957/1685 958/958/1686 945/945/1732 +f 945/945/1733 959/959/1733 963/963/1733 +f 931/931/1630 930/930/1699 938/938/1701 +f 931/931/1630 938/938/1701 937/937/1718 +f 958/958/1653 955/955/1734 959/959/1654 +f 923/923/1662 931/931/1611 924/924/1735 +f 968/968/1736 969/969/1736 970/970/1736 +f 971/971/1737 972/972/1737 970/970/1737 +f 972/972/1738 973/973/1738 968/968/1738 +f 974/974/1739 975/975/1740 976/976/1741 +f 975/975/1742 977/977/1743 978/978/1744 +f 977/977/1743 979/979/1745 978/978/1744 +f 978/978/1746 979/979/1746 976/976/1746 +f 979/979/1747 980/980/1747 976/976/1747 +f 976/976/1748 980/980/1748 974/974/1748 +f 980/980/1749 981/981/1749 974/974/1749 +f 974/974/1750 981/981/1750 975/975/1750 +f 975/975/1751 981/981/1751 977/977/1751 +f 977/977/1752 982/982/1753 979/979/1754 +f 981/981/1755 983/983/1756 984/984/1757 +f 981/981/1755 984/984/1757 977/977/1752 +f 985/985/1758 983/983/1756 980/980/1759 +f 980/980/1759 983/983/1756 981/981/1755 +f 979/979/1754 985/985/1758 980/980/1759 +f 977/977/1752 984/984/1757 982/982/1753 +f 979/979/1754 986/986/1760 985/985/1758 +f 979/979/1754 982/982/1753 986/986/1760 +f 969/969/1761 968/968/1762 982/982/1763 +f 982/982/1763 968/968/1762 986/986/1764 +f 986/986/1765 968/968/1766 973/973/1767 +f 986/986/1765 973/973/1767 985/985/1768 +f 985/985/1769 973/973/1770 983/983/1771 +f 983/983/1771 973/973/1770 972/972/1772 +f 972/972/1773 971/971/1773 983/983/1773 +f 983/983/1774 971/971/1775 984/984/1776 +f 971/971/1775 970/970/1777 984/984/1776 +f 984/984/1778 970/970/1779 982/982/1780 +f 970/970/1779 969/969/1781 982/982/1780 +f 970/970/1782 972/972/1782 987/987/1782 +f 987/987/1783 972/972/1783 988/988/1783 +f 968/968/1784 970/970/1785 988/988/1786 +f 988/988/1786 970/970/1785 987/987/1787 +f 972/972/1788 968/968/1788 988/988/1788 +f 978/978/1789 976/976/1741 975/975/1740 +f 989/989/1790 990/990/1790 991/991/1790 +f 992/992/1791 993/993/1791 989/989/1791 +f 991/991/1792 994/994/1792 992/992/1792 +f 995/995/1793 996/996/1793 997/997/1794 +f 995/995/1793 998/998/1795 996/996/1793 +f 999/999/1796 997/997/1797 996/996/1798 +f 999/999/1796 996/996/1798 1000/1000/1799 +f 1000/1000/1800 996/996/1801 1001/1001/1802 +f 1001/1001/1802 996/996/1801 998/998/1803 +f 1001/1001/1804 998/998/1805 1002/1002/1806 +f 1002/1002/1806 998/998/1805 995/995/1807 +f 1002/1002/1808 995/995/1809 999/999/1810 +f 999/999/1810 995/995/1809 997/997/1811 +f 1001/1001/1812 1003/1003/1813 1000/1000/1814 +f 1000/1000/1814 1003/1003/1813 1004/1004/1815 +f 1000/1000/1814 1004/1004/1815 1005/1005/1816 +f 1000/1000/1814 1005/1005/1816 999/999/1817 +f 999/999/1817 1005/1005/1816 1006/1006/1818 +f 999/999/1817 1006/1006/1818 1007/1007/1819 +f 999/999/1817 1007/1007/1819 1002/1002/1820 +f 1002/1002/1820 1007/1007/1819 1008/1008/1821 +f 1002/1002/1820 1008/1008/1821 1001/1001/1812 +f 1001/1001/1812 1008/1008/1821 1003/1003/1813 +f 989/989/1822 1005/1005/1823 990/990/1824 +f 990/990/1824 1005/1005/1823 1004/1004/1825 +f 990/990/1826 1004/1004/1827 1003/1003/1828 +f 990/990/1826 1003/1003/1828 991/991/1829 +f 991/991/1830 1003/1003/1831 994/994/1832 +f 994/994/1832 1003/1003/1831 1008/1008/1833 +f 994/994/1834 1008/1008/1835 1007/1007/1836 +f 994/994/1834 1007/1007/1836 992/992/1837 +f 992/992/1838 1007/1007/1839 993/993/1840 +f 993/993/1840 1007/1007/1839 1006/1006/1841 +f 993/993/1842 1006/1006/1843 1005/1005/1844 +f 993/993/1842 1005/1005/1844 989/989/1845 +f 991/991/1846 992/992/1847 1009/1009/1848 +f 1009/1009/1848 992/992/1847 1010/1010/1849 +f 989/989/1850 991/991/1851 1011/1011/1852 +f 1011/1011/1852 991/991/1851 1009/1009/1853 +f 992/992/1854 989/989/1855 1010/1010/1856 +f 1010/1010/1856 989/989/1855 1011/1011/1857 +f 1010/1010/71 1011/1011/71 1009/1009/71 +f 1012/1012/1858 1013/1013/1859 1014/1014/1860 +f 1015/1015/1861 1016/1016/1862 1017/1017/1863 +f 1018/1018/1864 1012/1012/1858 1014/1014/1860 +f 1019/1019/1865 1020/1020/1866 1021/1021/1867 +f 1016/1016/1862 1022/1022/1868 1017/1017/1863 +f 1013/1013/1859 1012/1012/1858 1023/1023/71 +f 1022/1022/1868 1019/1019/1865 1017/1017/1863 +f 1020/1020/1866 1019/1019/1865 1022/1022/1868 +f 1023/1023/71 1018/1018/1869 1024/1024/1870 +f 1024/1024/1870 1018/1018/1869 1025/1025/1871 +f 1015/1015/1861 1017/1017/1863 1021/1021/1867 +f 1025/1025/1871 1018/1018/1869 1014/1014/1872 +f 1023/1023/71 1024/1024/1870 1026/1026/1873 +f 1027/1027/71 1015/1015/1861 1021/1021/1867 +f 1021/1021/1867 1020/1020/1866 1028/1028/1874 +f 1029/1029/71 1023/1023/71 1026/1026/1873 +f 1029/1029/71 1026/1026/1873 1030/1030/1875 +f 1030/1030/1875 1026/1026/1873 1031/1031/1876 +f 1030/1030/1875 1031/1031/1876 1032/1032/1877 +f 1030/1030/1875 1032/1032/1877 1033/1033/1878 +f 1028/1028/1874 1027/1027/71 1021/1021/1867 +f 1033/1033/1878 1034/1034/1879 1035/1035/1880 +f 1033/1033/1878 1032/1032/1877 1034/1034/1879 +f 1035/1035/1880 1034/1034/1879 1036/1036/1881 +f 1035/1035/1880 1036/1036/1881 1037/1037/1882 +f 1027/1027/71 1028/1028/1874 1036/1036/1881 +f 1036/1036/1881 1028/1028/1874 1037/1037/1882 +f 1025/1025/1883 1014/1014/1884 1038/1038/1885 +f 1025/1025/1883 1038/1038/1885 1039/1039/1886 +f 1040/1040/1887 1041/1041/1888 1014/1014/1889 +f 1014/1014/1890 1041/1041/1890 1038/1038/1890 +f 1020/1020/1891 1042/1042/1892 1043/1043/1893 +f 1043/1043/1893 1042/1042/1892 1044/1044/210 +f 1042/1042/1894 1020/1020/1895 1045/1045/1896 +f 1016/1016/1897 1044/1044/1898 1045/1045/1899 +f 1041/1041/210 1040/1040/210 1039/1039/210 +f 1046/1046/1900 1047/1047/1901 1031/1031/1902 +f 1039/1039/210 1040/1040/210 1047/1047/1901 +f 1039/1039/210 1047/1047/1901 1046/1046/1900 +f 1031/1031/1902 1047/1047/1901 1048/1048/1903 +f 1031/1031/1902 1048/1048/1903 1049/1049/1904 +f 1049/1049/1904 1048/1048/1903 1050/1050/1905 +f 1050/1050/1905 1048/1048/1903 1035/1035/1906 +f 1050/1050/1905 1035/1035/1906 1051/1051/1907 +f 1044/1044/210 1052/1052/210 1043/1043/1893 +f 1051/1051/1907 1035/1035/1906 1053/1053/1908 +f 1051/1051/1907 1053/1053/1908 1052/1052/210 +f 1052/1052/210 1053/1053/1908 1043/1043/1893 +f 1028/1028/1909 1020/1020/1909 1043/1043/1909 +f 1028/1028/1910 1043/1043/1910 1053/1053/1910 +f 1028/1028/1911 1053/1053/1911 1037/1037/1911 +f 1037/1037/1912 1053/1053/1912 1035/1035/1912 +f 1033/1033/1913 1035/1035/1913 1048/1048/1913 +f 1033/1033/1914 1048/1048/1914 1030/1030/1914 +f 1030/1030/1915 1048/1048/1915 1047/1047/1915 +f 1030/1030/1916 1047/1047/1916 1029/1029/1916 +f 1029/1029/1917 1047/1047/1918 1023/1023/1919 +f 1023/1023/1919 1047/1047/1918 1040/1040/1920 +f 1023/1023/1921 1040/1040/1921 1013/1013/1921 +f 1014/1014/1889 1013/1013/1922 1040/1040/1887 +f 1024/1024/1923 1025/1025/1883 1039/1039/1886 +f 1024/1024/1924 1039/1039/1925 1046/1046/1926 +f 1024/1024/1924 1046/1046/1926 1026/1026/1927 +f 1026/1026/1928 1046/1046/1928 1031/1031/1928 +f 1031/1031/1929 1049/1049/1929 1032/1032/1929 +f 1032/1032/1930 1049/1049/1930 1050/1050/1930 +f 1032/1032/1931 1050/1050/1931 1034/1034/1931 +f 1034/1034/1932 1050/1050/1932 1051/1051/1932 +f 1034/1034/1933 1051/1051/1933 1036/1036/1933 +f 1036/1036/1934 1051/1051/1934 1052/1052/1934 +f 1036/1036/1935 1052/1052/1935 1027/1027/1935 +f 1027/1027/1936 1052/1052/1937 1015/1015/1938 +f 1015/1015/1938 1052/1052/1937 1044/1044/1939 +f 1016/1016/1897 1015/1015/1940 1044/1044/1898 +f 1016/1016/1941 1045/1045/1941 1022/1022/1941 +f 1020/1020/1895 1022/1022/1942 1045/1045/1896 +f 1018/1018/1943 1039/1039/1943 1038/1038/1943 +f 1018/1018/1944 1038/1038/1944 1012/1012/1944 +f 1012/1012/1945 1038/1038/1945 1041/1041/1945 +f 1012/1012/1946 1041/1041/1946 1023/1023/1946 +f 1023/1023/1947 1041/1041/1947 1039/1039/1947 +f 1023/1023/1948 1039/1039/1948 1018/1018/1948 +f 1019/1019/1949 1042/1042/1949 1045/1045/1949 +f 1019/1019/1950 1045/1045/1950 1017/1017/1950 +f 1017/1017/1951 1045/1045/1951 1044/1044/1951 +f 1017/1017/1952 1044/1044/1952 1021/1021/1952 +f 1021/1021/1953 1044/1044/1953 1042/1042/1953 +f 1021/1021/1954 1042/1042/1954 1019/1019/1954 +f 1054/1054/1955 1055/1055/1956 1056/1056/1957 +f 1057/1057/1958 1058/1058/1959 1059/1059/1960 +f 1060/1060/1961 1061/1061/1962 1062/1062/1963 +f 1063/1063/1964 1056/1056/1965 1064/1064/1966 +f 1065/1065/1967 1064/1064/1968 1066/1066/1969 +f 1067/1067/1970 1068/1068/1971 1069/1069/1972 +f 1067/1067/1970 1069/1069/1972 1070/1070/1973 +f 1071/1071/1974 1072/1072/1975 1073/1073/1976 +f 1054/1054/1955 1074/1074/1977 1055/1055/1956 +f 1069/1069/1978 1075/1075/1979 1076/1076/1980 +f 1060/1060/1981 1077/1077/1982 1078/1078/1983 +f 1074/1074/1984 1079/1079/1985 1055/1055/1986 +f 1075/1075/1979 1080/1080/1987 1076/1076/1980 +f 1081/1081/1988 1082/1082/1988 1083/1083/1988 +f 1084/1084/1989 1085/1085/1990 1063/1063/1991 +f 1064/1064/1968 1086/1086/1992 1066/1066/1969 +f 1087/1087/1993 1075/1075/1994 1068/1068/1995 +f 1070/1070/1996 1069/1069/1997 1072/1072/1975 +f 1088/1088/1998 1077/1077/1999 1060/1060/2000 +f 1088/1088/1998 1060/1060/2000 1082/1082/2001 +f 1089/1089/2002 1074/1074/2003 1090/1090/2004 +f 1066/1066/2005 1086/1086/2006 1084/1084/2007 +f 1066/1066/2005 1084/1084/2007 1075/1075/1994 +f 1091/1091/2008 1092/1092/2008 1077/1077/2008 +f 1061/1061/2009 1081/1081/2010 1083/1083/2011 +f 1093/1093/2012 1062/1062/2013 1094/1094/2014 +f 1063/1063/2015 1064/1064/2016 1080/1080/1987 +f 1073/1073/2017 1072/1072/2017 1095/1095/2017 +f 1089/1089/2018 1083/1083/2018 1074/1074/2018 +f 1096/1096/2019 1097/1097/2020 1064/1064/1968 +f 1064/1064/1968 1097/1097/2020 1086/1086/1992 +f 1068/1068/2021 1075/1075/2021 1069/1069/2021 +f 1074/1074/2022 1093/1093/2023 1094/1094/2024 +f 1074/1074/1984 1094/1094/2025 1079/1079/1985 +f 1057/1057/2026 1085/1085/2027 1097/1097/2028 +f 1098/1098/2029 1067/1067/2030 1095/1095/2031 +f 1079/1079/2032 1094/1094/2033 1058/1058/2034 +f 1076/1076/2035 1065/1065/2036 1087/1087/2037 +f 1067/1067/2038 1070/1070/2038 1099/1099/2038 +f 1085/1085/1990 1059/1059/2039 1056/1056/1957 +f 1080/1080/1987 1064/1064/2016 1065/1065/2040 +f 1065/1065/1967 1066/1066/1969 1087/1087/2041 +f 1088/1088/1998 1073/1073/2042 1077/1077/1999 +f 1090/1090/2004 1074/1074/2003 1054/1054/2043 +f 1055/1055/2044 1079/1079/2044 1056/1056/2044 +f 1077/1077/1999 1073/1073/2042 1091/1091/2045 +f 1069/1069/2046 1076/1076/2035 1087/1087/2037 +f 1069/1069/2047 1087/1087/2048 1098/1098/2049 +f 1092/1092/2050 1091/1091/2051 1100/1100/2052 +f 1092/1092/2050 1100/1100/2052 1081/1081/2053 +f 1083/1083/2054 1082/1082/2055 1101/1101/2056 +f 1091/1091/2051 1099/1099/2057 1071/1071/2058 +f 1059/1059/2039 1054/1054/1955 1056/1056/1957 +f 1069/1069/2047 1098/1098/2049 1072/1072/2059 +f 1073/1073/2042 1095/1095/2031 1091/1091/2045 +f 1077/1077/1982 1092/1092/2060 1081/1081/2061 +f 1078/1078/2062 1081/1081/2010 1061/1061/2009 +f 1083/1083/2054 1101/1101/2056 1074/1074/2063 +f 1095/1095/2031 1099/1099/2064 1091/1091/2045 +f 1101/1101/2065 1062/1062/2013 1093/1093/2012 +f 1094/1094/2066 1090/1090/2067 1058/1058/2068 +f 1056/1056/1965 1096/1096/2069 1064/1064/1966 +f 1060/1060/1981 1078/1078/1983 1061/1061/2070 +f 1056/1056/2071 1079/1079/2032 1058/1058/2034 +f 1056/1056/1965 1058/1058/2072 1096/1096/2069 +f 1097/1097/2073 1058/1058/2073 1057/1057/2073 +f 1097/1097/2028 1085/1085/2027 1084/1084/2074 +f 1095/1095/2031 1067/1067/2030 1099/1099/2064 +f 1074/1074/2022 1101/1101/2075 1093/1093/2023 +f 1057/1057/2076 1059/1059/2076 1085/1085/2076 +f 1080/1080/2077 1065/1065/2036 1076/1076/2035 +f 1100/1100/2078 1071/1071/2079 1088/1088/2080 +f 1062/1062/2081 1089/1089/2081 1090/1090/2081 +f 1058/1058/1959 1054/1054/2082 1059/1059/1960 +f 1087/1087/2083 1068/1068/2083 1067/1067/2083 +f 1099/1099/2084 1070/1070/2084 1071/1071/2084 +f 1089/1089/2085 1061/1061/2085 1083/1083/2085 +f 1096/1096/2086 1058/1058/2086 1097/1097/2086 +f 1086/1086/2087 1097/1097/2028 1084/1084/2074 +f 1075/1075/2088 1084/1084/1989 1063/1063/1991 +f 1101/1101/2089 1082/1082/2089 1062/1062/2089 +f 1094/1094/2066 1062/1062/2090 1090/1090/2067 +f 1098/1098/2029 1087/1087/2091 1067/1067/2030 +f 1082/1082/2092 1060/1060/2092 1062/1062/2092 +f 1087/1087/1993 1066/1066/2005 1075/1075/1994 +f 1070/1070/1996 1072/1072/1975 1071/1071/1974 +f 1071/1071/2093 1073/1073/2093 1088/1088/2093 +f 1062/1062/1963 1061/1061/1962 1089/1089/2094 +f 1077/1077/1982 1081/1081/2061 1078/1078/1983 +f 1072/1072/2059 1098/1098/2049 1095/1095/2095 +f 1085/1085/1990 1056/1056/1957 1063/1063/1991 +f 1081/1081/2096 1100/1100/2078 1088/1088/2080 +f 1081/1081/2096 1088/1088/2080 1082/1082/2097 +f 1058/1058/1959 1090/1090/2098 1054/1054/2082 +f 1075/1075/1979 1063/1063/2015 1080/1080/1987 +f 1091/1091/2051 1071/1071/2058 1100/1100/2052 +f 1102/1102/2099 1103/1103/2100 1104/1104/2101 +f 1102/1102/2102 1104/1104/2103 1105/1105/2104 +f 1105/1105/2104 1104/1104/2103 1106/1106/2105 +f 1105/1105/2106 1106/1106/2107 1107/1107/2108 +f 1105/1105/2106 1107/1107/2108 1108/1108/2109 +f 1108/1108/2110 1107/1107/2110 1109/1109/2110 +f 1109/1109/2111 1107/1107/2111 1110/1110/2111 +f 1109/1109/2112 1110/1110/2113 1111/1111/2114 +f 1111/1111/2114 1110/1110/2113 1112/1112/2115 +f 1113/1113/2116 1111/1111/2116 1114/1114/2116 +f 1114/1114/2117 1111/1111/2114 1112/1112/2115 +f 1113/1113/2118 1114/1114/2118 1115/1115/2118 +f 1113/1113/2119 1115/1115/2119 1116/1116/2119 +f 1116/1116/2120 1115/1115/2121 1117/1117/2122 +f 1117/1117/2122 1115/1115/2121 1118/1118/2123 +f 1117/1117/2124 1118/1118/2125 1119/1119/2124 +f 1119/1119/2126 1118/1118/2126 1120/1120/2126 +f 1119/1119/2127 1120/1120/2127 1121/1121/2127 +f 1121/1121/2128 1120/1120/2128 1122/1122/2128 +f 1121/1121/2129 1122/1122/2129 1123/1123/2129 +f 1123/1123/2130 1122/1122/2130 1124/1124/2130 +f 1123/1123/2131 1124/1124/2131 1125/1125/2131 +f 1102/1102/2099 1125/1125/2132 1103/1103/2100 +f 1103/1103/2133 1125/1125/2133 1124/1124/2133 +f 1125/1125/2134 1102/1102/2134 1123/1123/2134 +f 1111/1111/2134 1116/1116/2134 1109/1109/2134 +f 1109/1109/2134 1116/1116/2134 1117/1117/2134 +f 1111/1111/2134 1113/1113/2134 1116/1116/2134 +f 1105/1105/2134 1119/1119/2134 1121/1121/2134 +f 1109/1109/2134 1117/1117/2134 1108/1108/2134 +f 1108/1108/2134 1117/1117/2134 1119/1119/2134 +f 1102/1102/2134 1121/1121/2134 1123/1123/2134 +f 1105/1105/2134 1121/1121/2134 1102/1102/2134 +f 1108/1108/2134 1119/1119/2134 1105/1105/2134 +f 1114/1114/2135 1112/1112/2135 1115/1115/2135 +f 1110/1110/2135 1115/1115/2135 1112/1112/2135 +f 1110/1110/2135 1118/1118/2135 1115/1115/2135 +f 1107/1107/2135 1118/1118/2135 1110/1110/2135 +f 1107/1107/2135 1120/1120/2136 1118/1118/2135 +f 1106/1106/2135 1120/1120/2136 1107/1107/2135 +f 1106/1106/2135 1122/1122/2137 1120/1120/2136 +f 1103/1103/2135 1124/1124/2136 1104/1104/2135 +f 1104/1104/2135 1122/1122/2137 1106/1106/2135 +f 1104/1104/2135 1124/1124/2136 1122/1122/2137 +f 1126/1126/2138 1127/1127/2139 1128/1128/2140 +f 1128/1128/2140 1129/1129/2141 1126/1126/2138 +f 1128/1128/2140 1127/1127/2139 1130/1130/2142 +f 1127/1127/2139 1131/1131/2143 1130/1130/2142 +f 1130/1130/2142 1132/1132/2144 1133/1133/2145 +f 1133/1133/2145 1132/1132/2144 1134/1134/2146 +f 1130/1130/2142 1131/1131/2143 1132/1132/2144 +f 1133/1133/2145 1135/1135/2147 1129/1129/2141 +f 1133/1133/2145 1129/1129/2141 1128/1128/2140 +f 1133/1133/2145 1134/1134/2146 1135/1135/2147 +f 1136/1136/2148 1137/1137/2149 1138/1138/2150 +f 1138/1138/2150 1139/1139/2151 1136/1136/2148 +f 1138/1138/2150 1140/1140/2152 1139/1139/2151 +f 1141/1141/2153 1138/1138/2154 1137/1137/2155 +f 1141/1141/2153 1137/1137/2155 1142/1142/2156 +f 1142/1142/2157 1137/1137/2157 1136/1136/2157 +f 1142/1142/2158 1136/1136/2158 1143/1143/2158 +f 1143/1143/2159 1136/1136/2160 1139/1139/2161 +f 1143/1143/2159 1139/1139/2161 1144/1144/2162 +f 1144/1144/2163 1139/1139/2164 1140/1140/2165 +f 1144/1144/2163 1140/1140/2165 1145/1145/2166 +f 1145/1145/2167 1140/1140/2168 1138/1138/2169 +f 1145/1145/2167 1138/1138/2169 1141/1141/2170 +f 1141/1141/2171 1146/1146/2172 1147/1147/2173 +f 1142/1142/2174 1148/1148/2175 1141/1141/2171 +f 1141/1141/2171 1148/1148/2175 1146/1146/2172 +f 1144/1144/2176 1149/1149/2177 1143/1143/2178 +f 1145/1145/2179 1150/1150/2180 1144/1144/2176 +f 1144/1144/2176 1150/1150/2180 1149/1149/2177 +f 1141/1141/2171 1147/1147/2173 1145/1145/2179 +f 1145/1145/2179 1147/1147/2173 1150/1150/2180 +f 1142/1142/2174 1151/1151/2181 1148/1148/2175 +f 1143/1143/2178 1149/1149/2177 1152/1152/2182 +f 1143/1143/2178 1152/1152/2182 1142/1142/2174 +f 1142/1142/2174 1152/1152/2182 1151/1151/2181 +f 1147/1147/2183 1146/1146/2184 1127/1127/2185 +f 1127/1127/2186 1126/1126/2187 1147/1147/2188 +f 1147/1147/2188 1126/1126/2187 1150/1150/2189 +f 1150/1150/2189 1126/1126/2187 1129/1129/2190 +f 1150/1150/2191 1129/1129/2192 1149/1149/2193 +f 1149/1149/2193 1129/1129/2192 1135/1135/2194 +f 1149/1149/2195 1135/1135/2196 1134/1134/2197 +f 1149/1149/2195 1134/1134/2197 1152/1152/2198 +f 1152/1152/2199 1134/1134/2200 1151/1151/2201 +f 1151/1151/2201 1134/1134/2200 1132/1132/2202 +f 1151/1151/2201 1132/1132/2202 1148/1148/2203 +f 1132/1132/2202 1131/1131/2204 1148/1148/2203 +f 1148/1148/2203 1131/1131/2204 1146/1146/2205 +f 1146/1146/2184 1131/1131/2206 1127/1127/2185 +f 1130/1130/2207 1133/1133/2208 1153/1153/2209 +f 1153/1153/2209 1133/1133/2208 1154/1154/2210 +f 1128/1128/2211 1130/1130/2212 1155/1155/2213 +f 1155/1155/2213 1130/1130/2212 1153/1153/2214 +f 1133/1133/2215 1128/1128/2216 1154/1154/2217 +f 1154/1154/2217 1128/1128/2216 1155/1155/2218 +f 1155/1155/2134 1153/1153/2134 1154/1154/2134 +f 1156/1156/2219 1157/1157/2220 1158/1158/2221 +f 1158/1158/2221 1159/1159/2222 1160/1160/2223 +f 1160/1160/2223 1159/1159/2222 1161/1161/2224 +f 1162/1162/2225 1163/1163/2226 1164/1164/2227 +f 1160/1160/2223 1161/1161/2224 1162/1162/2225 +f 1160/1160/2223 1162/1162/2225 1164/1164/2227 +f 1156/1156/2219 1165/1165/2228 1157/1157/2220 +f 1164/1164/2227 1163/1163/2226 1165/1165/2228 +f 1164/1164/2227 1165/1165/2228 1156/1156/2219 +f 1156/1156/2219 1158/1158/2221 1160/1160/2223 +f 1166/1166/2229 1167/1167/2230 1168/1168/2231 +f 1166/1166/2229 1169/1169/2232 1167/1167/2230 +f 1166/1166/2229 1170/1170/2233 1169/1169/2232 +f 1171/1171/2234 1170/1170/2234 1172/1172/2234 +f 1172/1172/2235 1170/1170/2235 1166/1166/2235 +f 1172/1172/2236 1166/1166/2236 1173/1173/2236 +f 1173/1173/2237 1166/1166/2238 1168/1168/2239 +f 1173/1173/2237 1168/1168/2239 1174/1174/2240 +f 1174/1174/2241 1168/1168/2242 1175/1175/2243 +f 1175/1175/2243 1168/1168/2242 1167/1167/2244 +f 1175/1175/2245 1167/1167/2245 1169/1169/2245 +f 1175/1175/2246 1169/1169/2246 1171/1171/2246 +f 1171/1171/2247 1169/1169/2247 1170/1170/2247 +f 1172/1172/2248 1176/1176/2249 1177/1177/2250 +f 1172/1172/2248 1177/1177/2250 1171/1171/2251 +f 1175/1175/2252 1178/1178/2253 1174/1174/2254 +f 1174/1174/2254 1178/1178/2253 1179/1179/2255 +f 1175/1175/2252 1180/1180/2256 1178/1178/2253 +f 1171/1171/2251 1177/1177/2250 1180/1180/2256 +f 1171/1171/2251 1180/1180/2256 1175/1175/2252 +f 1173/1173/2257 1181/1181/2258 1172/1172/2248 +f 1172/1172/2248 1181/1181/2258 1176/1176/2249 +f 1174/1174/2254 1179/1179/2255 1173/1173/2257 +f 1173/1173/2257 1179/1179/2255 1181/1181/2258 +f 1177/1177/2259 1159/1159/2260 1158/1158/2261 +f 1177/1177/2259 1158/1158/2261 1180/1180/2262 +f 1180/1180/2263 1158/1158/2264 1157/1157/2265 +f 1180/1180/2263 1157/1157/2265 1178/1178/2266 +f 1157/1157/2267 1165/1165/2268 1178/1178/2269 +f 1178/1178/2269 1165/1165/2268 1179/1179/2270 +f 1165/1165/2271 1163/1163/2272 1179/1179/2273 +f 1179/1179/2273 1163/1163/2272 1181/1181/2274 +f 1163/1163/2275 1162/1162/2276 1181/1181/2277 +f 1181/1181/2277 1162/1162/2276 1176/1176/2278 +f 1162/1162/2276 1161/1161/2279 1176/1176/2278 +f 1176/1176/2280 1161/1161/2281 1177/1177/2282 +f 1161/1161/2281 1159/1159/2283 1177/1177/2282 +f 1164/1164/2284 1156/1156/2284 1182/1182/2284 +f 1183/1183/2285 1164/1164/2285 1182/1182/2285 +f 1160/1160/2286 1164/1164/2286 1183/1183/2286 +f 1184/1184/2287 1160/1160/2287 1183/1183/2287 +f 1156/1156/2288 1160/1160/2288 1184/1184/2288 +f 1182/1182/2289 1156/1156/2289 1184/1184/2289 +f 1184/1184/2134 1183/1183/2134 1182/1182/2134 +f 1185/1185/2290 1186/1186/2291 1187/1187/2292 +f 1188/1188/2293 1189/1189/2294 1186/1186/2291 +f 1190/1190/2295 1191/1191/2296 1192/1192/2297 +f 1185/1185/2290 1187/1187/2292 1191/1191/2296 +f 1190/1190/2295 1192/1192/2297 1193/1193/2298 +f 1185/1185/2290 1191/1191/2296 1190/1190/2295 +f 1188/1188/2293 1194/1194/2299 1189/1189/2294 +f 1190/1190/2295 1193/1193/2298 1194/1194/2299 +f 1190/1190/2295 1194/1194/2299 1188/1188/2293 +f 1188/1188/2293 1186/1186/2291 1185/1185/2290 +f 1195/1195/2300 1196/1196/2301 1197/1197/2302 +f 1197/1197/2302 1196/1196/2301 1198/1198/2303 +f 1199/1199/2304 1196/1196/2305 1200/1200/2306 +f 1199/1199/2307 1200/1200/2308 1195/1195/2309 +f 1199/1199/2307 1195/1195/2309 1201/1201/2310 +f 1201/1201/2311 1195/1195/2312 1202/1202/2313 +f 1202/1202/2313 1195/1195/2312 1197/1197/2314 +f 1202/1202/2315 1197/1197/2316 1203/1203/2317 +f 1203/1203/2317 1197/1197/2316 1198/1198/2318 +f 1203/1203/2319 1198/1198/2319 1204/1204/2319 +f 1204/1204/2320 1198/1198/2320 1196/1196/2320 +f 1204/1204/2321 1196/1196/2305 1199/1199/2304 +f 1199/1199/2322 1205/1205/2323 1206/1206/2324 +f 1199/1199/2322 1206/1206/2324 1204/1204/2325 +f 1203/1203/2326 1207/1207/2327 1208/1208/2328 +f 1203/1203/2326 1208/1208/2328 1202/1202/2329 +f 1204/1204/2325 1209/1209/2330 1207/1207/2327 +f 1204/1204/2325 1207/1207/2327 1203/1203/2326 +f 1204/1204/2325 1206/1206/2324 1209/1209/2330 +f 1201/1201/2331 1210/1210/2332 1205/1205/2323 +f 1201/1201/2331 1205/1205/2323 1199/1199/2322 +f 1202/1202/2329 1208/1208/2328 1210/1210/2332 +f 1202/1202/2329 1210/1210/2332 1201/1201/2331 +f 1206/1206/2333 1187/1187/2334 1186/1186/2335 +f 1206/1206/2333 1186/1186/2335 1209/1209/2336 +f 1186/1186/2337 1189/1189/2338 1209/1209/2339 +f 1209/1209/2339 1189/1189/2338 1207/1207/2340 +f 1207/1207/2341 1189/1189/2342 1194/1194/2343 +f 1207/1207/2341 1194/1194/2343 1208/1208/2344 +f 1208/1208/2345 1194/1194/2346 1193/1193/2347 +f 1208/1208/2345 1193/1193/2347 1210/1210/2348 +f 1193/1193/2347 1192/1192/2349 1210/1210/2348 +f 1210/1210/2350 1192/1192/2351 1205/1205/2352 +f 1205/1205/2352 1192/1192/2351 1191/1191/2353 +f 1205/1205/2354 1191/1191/2355 1187/1187/2356 +f 1205/1205/2354 1187/1187/2356 1206/1206/2357 +f 1190/1190/2358 1188/1188/2359 1211/1211/2360 +f 1211/1211/2360 1188/1188/2359 1212/1212/2361 +f 1185/1185/2362 1190/1190/2363 1213/1213/2364 +f 1213/1213/2364 1190/1190/2363 1211/1211/2365 +f 1188/1188/2366 1185/1185/2367 1212/1212/2368 +f 1212/1212/2368 1185/1185/2367 1213/1213/2369 +f 1212/1212/2370 1213/1213/2370 1211/1211/2370 +f 1200/1200/2371 1196/1196/2301 1195/1195/2300 +f 1214/1214/2372 1215/1215/2373 1216/1216/2374 +f 1217/1217/2375 1218/1218/2376 1215/1215/2373 +f 1219/1219/2377 1220/1220/2378 1217/1217/2375 +f 1214/1214/2372 1221/1221/2379 1222/1222/2380 +f 1214/1214/2372 1222/1222/2380 1223/1223/2381 +f 1223/1223/2381 1222/1222/2380 1224/1224/2382 +f 1223/1223/2381 1219/1219/2377 1217/1217/2375 +f 1223/1223/2381 1224/1224/2382 1219/1219/2377 +f 1217/1217/2375 1215/1215/2373 1214/1214/2372 +f 1220/1220/2378 1218/1218/2376 1217/1217/2375 +f 1214/1214/2372 1216/1216/2374 1221/1221/2379 +f 1225/1225/2383 1226/1226/2384 1227/1227/2385 +f 1228/1228/2386 1229/1229/2387 1225/1225/2383 +f 1225/1225/2383 1230/1230/2388 1228/1228/2386 +f 1227/1227/2385 1230/1230/2388 1225/1225/2383 +f 1231/1231/2389 1226/1226/2390 1232/1232/2391 +f 1232/1232/2391 1226/1226/2390 1225/1225/2392 +f 1232/1232/2393 1225/1225/2394 1233/1233/2395 +f 1233/1233/2395 1225/1225/2394 1229/1229/2396 +f 1233/1233/2397 1229/1229/2398 1228/1228/2399 +f 1233/1233/2397 1228/1228/2399 1234/1234/2400 +f 1234/1234/2401 1228/1228/2401 1230/1230/2401 +f 1234/1234/2402 1230/1230/2403 1227/1227/2404 +f 1234/1234/2402 1227/1227/2404 1231/1231/2405 +f 1231/1231/2406 1227/1227/2406 1226/1226/2406 +f 1231/1231/2407 1235/1235/2408 1236/1236/2409 +f 1232/1232/2410 1237/1237/2411 1235/1235/2408 +f 1232/1232/2410 1235/1235/2408 1231/1231/2407 +f 1234/1234/2412 1238/1238/2413 1233/1233/2414 +f 1234/1234/2412 1239/1239/2415 1238/1238/2413 +f 1231/1231/2407 1236/1236/2409 1234/1234/2412 +f 1234/1234/2412 1236/1236/2409 1239/1239/2415 +f 1233/1233/2414 1240/1240/2416 1232/1232/2410 +f 1232/1232/2410 1240/1240/2416 1237/1237/2411 +f 1233/1233/2414 1238/1238/2413 1240/1240/2416 +f 1222/1222/2417 1221/1221/2418 1236/1236/2419 +f 1236/1236/2420 1221/1221/2421 1216/1216/2422 +f 1236/1236/2420 1216/1216/2422 1239/1239/2423 +f 1216/1216/2424 1215/1215/2425 1239/1239/2426 +f 1239/1239/2426 1215/1215/2425 1238/1238/2427 +f 1215/1215/2425 1218/1218/2428 1238/1238/2427 +f 1238/1238/2429 1218/1218/2430 1240/1240/2431 +f 1218/1218/2430 1220/1220/2432 1240/1240/2431 +f 1240/1240/2433 1220/1220/2434 1219/1219/2435 +f 1240/1240/2433 1219/1219/2435 1237/1237/2436 +f 1219/1219/2437 1224/1224/2438 1237/1237/2439 +f 1237/1237/2439 1224/1224/2438 1235/1235/2440 +f 1235/1235/2440 1224/1224/2438 1222/1222/2417 +f 1235/1235/2440 1222/1222/2417 1236/1236/2419 +f 1223/1223/2441 1217/1217/2441 1241/1241/2441 +f 1241/1241/2442 1217/1217/2442 1242/1242/2442 +f 1243/1243/2443 1223/1223/2443 1241/1241/2443 +f 1214/1214/2444 1223/1223/2444 1243/1243/2444 +f 1244/1244/2445 1214/1214/2445 1243/1243/2445 +f 1217/1217/2446 1214/1214/2447 1242/1242/2448 +f 1242/1242/2448 1214/1214/2447 1244/1244/2449 +f 1244/1244/2370 1243/1243/2370 1241/1241/2370 +f 1244/1244/2370 1241/1241/2370 1242/1242/2370 +f 1245/1245/2450 1246/1246/2451 1247/1247/2452 +f 1245/1245/2453 1247/1247/2453 1248/1248/2453 +f 1248/1248/2454 1247/1247/2454 1249/1249/2454 +f 1248/1248/2455 1249/1249/2455 1250/1250/2455 +f 1250/1250/2456 1249/1249/2456 1251/1251/2456 +f 1250/1250/2457 1251/1251/2457 1252/1252/2457 +f 1252/1252/2458 1251/1251/2458 1253/1253/2458 +f 1252/1252/2459 1253/1253/2460 1254/1254/2461 +f 1255/1255/2462 1254/1254/2462 1256/1256/2462 +f 1256/1256/2463 1254/1254/2461 1253/1253/2460 +f 1255/1255/2464 1256/1256/2465 1257/1257/2466 +f 1255/1255/2464 1257/1257/2466 1258/1258/2467 +f 1258/1258/2468 1257/1257/2468 1259/1259/2468 +f 1259/1259/2469 1257/1257/2469 1260/1260/2469 +f 1259/1259/2470 1260/1260/2470 1261/1261/2470 +f 1261/1261/2471 1260/1260/2471 1262/1262/2471 +f 1261/1261/2472 1262/1262/2472 1263/1263/2472 +f 1263/1263/2473 1262/1262/2473 1264/1264/2473 +f 1263/1263/2474 1264/1264/2474 1265/1265/2474 +f 1265/1265/2475 1264/1264/2475 1266/1266/2475 +f 1265/1265/2476 1266/1266/2477 1267/1267/2478 +f 1265/1265/2476 1267/1267/2478 1268/1268/2479 +f 1245/1245/2450 1268/1268/2480 1246/1246/2451 +f 1246/1246/2481 1268/1268/2481 1267/1267/2481 +f 1252/1252/2482 1258/1258/2483 1259/1259/2484 +f 1254/1254/2485 1255/1255/2486 1252/1252/2482 +f 1252/1252/2482 1255/1255/2486 1258/1258/2483 +f 1250/1250/2487 1259/1259/2484 1261/1261/2487 +f 1252/1252/2482 1259/1259/2484 1250/1250/2487 +f 1245/1245/2488 1265/1265/2482 1268/1268/2488 +f 1248/1248/2489 1265/1265/2482 1245/1245/2488 +f 1263/1263/2486 1265/1265/2482 1248/1248/2489 +f 1250/1250/2487 1263/1263/2486 1248/1248/2489 +f 1250/1250/2487 1261/1261/2487 1263/1263/2486 +f 1256/1256/2370 1253/1253/2370 1257/1257/2370 +f 1251/1251/2370 1257/1257/2370 1253/1253/2370 +f 1251/1251/2370 1260/1260/2490 1257/1257/2370 +f 1249/1249/2370 1260/1260/2490 1251/1251/2370 +f 1249/1249/2370 1262/1262/2491 1260/1260/2490 +f 1249/1249/2370 1264/1264/2492 1262/1262/2491 +f 1247/1247/2490 1264/1264/2492 1249/1249/2370 +f 1246/1246/2493 1267/1267/2494 1247/1247/2490 +f 1247/1247/2490 1266/1266/2490 1264/1264/2492 +f 1267/1267/2494 1266/1266/2490 1247/1247/2490 +f 1269/1269/2495 1270/1270/2496 1271/1271/2497 +f 1269/1269/2498 1271/1271/2498 1272/1272/2498 +f 1272/1272/2499 1271/1271/2499 1273/1273/2499 +f 1272/1272/2500 1273/1273/2500 1274/1274/2500 +f 1274/1274/2501 1273/1273/2501 1275/1275/2501 +f 1274/1274/2502 1275/1275/2503 1276/1276/2504 +f 1274/1274/2502 1276/1276/2504 1277/1277/2505 +f 1278/1278/2506 1277/1277/2506 1276/1276/2506 +f 1279/1279/2507 1278/1278/2507 1280/1280/2507 +f 1279/1279/2508 1280/1280/2508 1281/1281/2508 +f 1281/1281/2509 1280/1280/2509 1282/1282/2509 +f 1281/1281/2510 1282/1282/2510 1283/1283/2510 +f 1283/1283/2511 1282/1282/2511 1284/1284/2511 +f 1283/1283/2512 1284/1284/2512 1285/1285/2512 +f 1285/1285/2513 1284/1284/2513 1286/1286/2513 +f 1285/1285/2514 1286/1286/2515 1287/1287/2516 +f 1287/1287/2516 1286/1286/2515 1288/1288/2517 +f 1287/1287/2518 1288/1288/2518 1289/1289/2518 +f 1269/1269/2495 1289/1289/2519 1270/1270/2496 +f 1289/1289/2520 1269/1269/2521 1287/1287/2522 +f 1277/1277/2523 1281/1281/2488 1274/1274/2488 +f 1277/1277/2523 1279/1279/2524 1281/1281/2488 +f 1278/1278/2525 1279/1279/2524 1277/1277/2523 +f 1274/1274/2488 1281/1281/2488 1283/1283/2488 +f 1272/1272/2488 1287/1287/2522 1269/1269/2521 +f 1272/1272/2488 1285/1285/2488 1287/1287/2522 +f 1272/1272/2488 1283/1283/2488 1285/1285/2488 +f 1274/1274/2488 1283/1283/2488 1272/1272/2488 +f 1278/1278/2526 1276/1276/2527 1280/1280/2528 +f 1275/1275/2370 1282/1282/2370 1276/1276/2527 +f 1276/1276/2527 1282/1282/2370 1280/1280/2528 +f 1273/1273/2370 1284/1284/2370 1275/1275/2370 +f 1275/1275/2370 1284/1284/2370 1282/1282/2370 +f 1271/1271/2370 1284/1284/2370 1273/1273/2370 +f 1271/1271/2370 1286/1286/2370 1284/1284/2370 +f 1270/1270/2529 1289/1289/2530 1288/1288/2531 +f 1270/1270/2529 1288/1288/2531 1271/1271/2370 +f 1271/1271/2370 1288/1288/2531 1286/1286/2370 +f 1290/1290/2532 1291/1291/2533 1292/1292/2534 +f 1290/1290/2535 1292/1292/2535 1293/1293/2535 +f 1293/1293/2536 1292/1292/2536 1294/1294/2536 +f 1293/1293/2537 1294/1294/2537 1295/1295/2537 +f 1295/1295/2538 1294/1294/2538 1296/1296/2538 +f 1295/1295/2539 1296/1296/2539 1297/1297/2539 +f 1297/1297/2540 1296/1296/2540 1298/1298/2540 +f 1297/1297/2541 1298/1298/2542 1299/1299/2543 +f 1300/1300/2544 1299/1299/2544 1301/1301/2544 +f 1301/1301/2545 1299/1299/2543 1298/1298/2542 +f 1300/1300/2546 1301/1301/2547 1302/1302/2548 +f 1300/1300/2546 1302/1302/2548 1303/1303/2549 +f 1303/1303/2550 1302/1302/2551 1304/1304/2552 +f 1303/1303/2550 1304/1304/2552 1305/1305/2553 +f 1305/1305/2554 1304/1304/2554 1306/1306/2554 +f 1306/1306/2555 1304/1304/2555 1307/1307/2555 +f 1306/1306/2556 1307/1307/2556 1308/1308/2556 +f 1308/1308/2557 1307/1307/2557 1309/1309/2557 +f 1308/1308/2558 1309/1309/2558 1310/1310/2558 +f 1310/1310/2559 1309/1309/2560 1311/1311/2561 +f 1310/1310/2559 1311/1311/2561 1312/1312/2562 +f 1290/1290/2532 1312/1312/2563 1291/1291/2533 +f 1291/1291/2564 1312/1312/2564 1311/1311/2564 +f 1297/1297/2565 1303/1303/2566 1295/1295/2567 +f 1297/1297/2565 1300/1300/2568 1303/1303/2566 +f 1299/1299/2569 1300/1300/2568 1297/1297/2565 +f 1293/1293/2134 1306/1306/2570 1308/1308/2134 +f 1295/1295/2567 1303/1303/2566 1305/1305/2571 +f 1290/1290/2572 1310/1310/2566 1312/1312/2573 +f 1290/1290/2572 1308/1308/2134 1310/1310/2566 +f 1293/1293/2134 1308/1308/2134 1290/1290/2572 +f 1295/1295/2567 1305/1305/2571 1293/1293/2134 +f 1293/1293/2134 1305/1305/2571 1306/1306/2570 +f 1296/1296/2135 1302/1302/2135 1298/1298/2135 +f 1298/1298/2135 1302/1302/2135 1301/1301/2135 +f 1296/1296/2135 1304/1304/2135 1302/1302/2135 +f 1294/1294/2135 1304/1304/2135 1296/1296/2135 +f 1292/1292/2574 1307/1307/2575 1294/1294/2135 +f 1294/1294/2135 1307/1307/2575 1304/1304/2135 +f 1292/1292/2574 1309/1309/2576 1307/1307/2575 +f 1311/1311/2577 1309/1309/2576 1291/1291/2576 +f 1291/1291/2576 1309/1309/2576 1292/1292/2574 +f 1313/1313/2578 1314/1314/2579 1315/1315/2580 +f 1315/1315/2580 1314/1314/2579 1316/1316/2581 +f 1315/1315/2580 1316/1316/2581 1317/1317/2582 +f 1317/1317/2582 1316/1316/2581 1318/1318/2583 +f 1317/1317/2582 1318/1318/2583 1319/1319/2584 +f 1319/1319/2584 1318/1318/2583 1320/1320/2585 +f 1319/1319/2584 1320/1320/2585 1321/1321/2586 +f 1322/1322/2587 1323/1323/2588 1324/1324/2589 +f 1324/1324/2589 1323/1323/2588 1325/1325/2590 +f 1324/1324/2589 1325/1325/2590 1326/1326/2591 +f 1326/1326/2591 1325/1325/2590 1327/1327/2592 +f 1326/1326/2591 1327/1327/2592 1328/1328/2593 +f 1328/1328/2593 1327/1327/2592 1329/1329/2594 +f 1323/1323/2588 1322/1322/2587 1330/1330/2595 +f 1331/1331/2596 1332/1332/2597 1333/1333/2598 +f 1333/1333/2598 1332/1332/2597 1334/1334/2599 +f 1333/1333/2598 1334/1334/2599 1335/1335/2600 +f 1335/1335/2600 1334/1334/2599 1336/1336/2601 +f 1335/1335/2600 1336/1336/2601 1337/1337/2602 +f 1337/1337/2602 1336/1336/2601 1338/1338/2603 +f 1337/1337/2602 1338/1338/2603 1339/1339/2604 +f 1339/1339/2604 1338/1338/2603 1340/1340/2605 +f 1339/1339/2604 1340/1340/2605 1341/1341/2606 +f 1342/1342/2607 1343/1343/2608 1344/1344/2609 +f 1344/1344/2609 1345/1345/2610 1342/1342/2607 +f 1346/1346/2611 1345/1345/2610 1344/1344/2609 +f 1345/1345/2610 1346/1346/2611 1347/1347/2612 +f 1345/1345/2610 1347/1347/2612 1348/1348/2613 +f 1348/1348/2613 1347/1347/2612 1349/1349/2614 +f 1350/1350/2615 1348/1348/2613 1349/1349/2614 +f 1350/1350/2615 1351/1351/2616 1348/1348/2613 +f 1351/1351/2616 1350/1350/2615 1352/1352/2617 +f 1351/1351/2616 1352/1352/2617 1353/1353/2618 +f 1351/1351/2616 1353/1353/2618 1354/1354/2619 +f 1353/1353/2618 1355/1355/2620 1354/1354/2619 +f 1355/1355/2620 1356/1356/2621 1354/1354/2619 +f 1356/1356/2621 1355/1355/2620 1357/1357/2622 +f 1358/1358/2623 1356/1356/2621 1357/1357/2622 +f 1359/1359/2624 1360/1360/2625 1358/1358/2623 +f 1358/1358/2623 1360/1360/2625 1356/1356/2621 +f 1361/1361/2626 1362/1362/2627 1363/1363/2628 +f 1361/1361/2626 1363/1363/2628 1364/1364/2629 +f 1364/1364/2629 1363/1363/2628 1365/1365/2630 +f 1365/1365/2630 1363/1363/2628 1366/1366/2631 +f 1365/1365/2630 1366/1366/2631 1367/1367/2632 +f 1367/1367/2632 1366/1366/2631 1368/1368/2633 +f 1369/1369/2634 1370/1370/2635 1371/1371/2636 +f 1371/1371/2636 1370/1370/2635 1372/1372/2637 +f 1371/1371/2636 1372/1372/2637 1373/1373/2638 +f 1371/1371/2636 1373/1373/2638 1374/1374/2639 +f 1375/1375/2640 1374/1374/2639 1373/1373/2638 +f 1375/1375/2640 1376/1376/2641 1374/1374/2639 +f 1377/1377/2642 1376/1376/2641 1375/1375/2640 +f 1367/1367/2643 1378/1378/2644 1379/1379/2645 +f 1367/1367/2643 1379/1379/2645 1365/1365/2646 +f 1365/1365/2646 1379/1379/2645 1380/1380/2647 +f 1365/1365/2646 1380/1380/2647 1364/1364/2648 +f 1364/1364/2648 1380/1380/2647 1381/1381/2649 +f 1382/1382/2650 1361/1361/2651 1364/1364/2648 +f 1382/1382/2650 1364/1364/2648 1381/1381/2649 +f 1383/1383/2652 1377/1377/2642 1384/1384/2653 +f 1385/1385/2654 1386/1386/2655 1359/1359/2624 +f 1359/1359/2624 1386/1386/2655 1360/1360/2625 +f 1387/1387/2656 1388/1388/2657 1389/1389/2658 +f 1387/1387/2659 1389/1389/2660 1390/1390/2661 +f 1390/1390/2661 1384/1384/2653 1387/1387/2659 +f 1360/1360/2625 1391/1391/2662 1392/1392/2663 +f 1393/1393/2664 1384/1384/2653 1390/1390/2661 +f 1394/1394/2665 1395/1395/2666 1393/1393/2664 +f 1392/1392/2663 1388/1388/2657 1360/1360/2625 +f 1360/1360/2625 1388/1388/2657 1387/1387/2656 +f 1384/1384/2653 1393/1393/2664 1383/1383/2652 +f 1393/1393/2664 1390/1390/2661 1394/1394/2665 +f 1391/1391/2662 1386/1386/2655 1395/1395/2666 +f 1386/1386/2655 1391/1391/2662 1360/1360/2625 +f 1395/1395/2666 1394/1394/2665 1391/1391/2662 +f 1342/1342/2667 1396/1396/2668 1397/1397/2669 +f 1387/1387/2670 1384/1384/2671 1398/1398/2672 +f 1398/1398/2672 1384/1384/2671 1399/1399/2673 +f 1400/1400/2674 1401/1401/2675 1332/1332/2676 +f 1402/1402/2677 1341/1341/2678 1340/1340/2679 +f 1401/1401/2675 1334/1334/2680 1332/1332/2676 +f 1403/1403/2681 1336/1336/2682 1334/1334/2680 +f 1403/1403/2681 1334/1334/2680 1401/1401/2675 +f 1404/1404/2683 1338/1338/2684 1403/1403/2681 +f 1403/1403/2681 1338/1338/2684 1336/1336/2682 +f 1402/1402/2677 1340/1340/2679 1404/1404/2683 +f 1404/1404/2683 1340/1340/2679 1338/1338/2684 +f 1339/1339/2685 1382/1382/2686 1337/1337/2687 +f 1380/1380/2688 1335/1335/2689 1337/1337/2687 +f 1380/1380/2688 1337/1337/2687 1381/1381/2690 +f 1381/1381/2690 1337/1337/2687 1382/1382/2686 +f 1335/1335/2689 1380/1380/2688 1333/1333/2691 +f 1333/1333/2691 1380/1380/2688 1379/1379/2692 +f 1333/1333/2691 1379/1379/2692 1378/1378/2693 +f 1333/1333/2691 1378/1378/2693 1331/1331/2694 +f 1392/1392/2695 1405/1405/2696 1388/1388/2697 +f 1388/1388/2697 1405/1405/2696 1406/1406/2698 +f 1388/1388/2699 1406/1406/2699 1389/1389/2699 +f 1407/1407/2700 1391/1391/2701 1408/1408/2702 +f 1408/1408/2702 1391/1391/2701 1394/1394/2703 +f 1408/1408/2704 1394/1394/2704 1390/1390/2704 +f 1405/1405/2705 1392/1392/2706 1407/1407/2707 +f 1407/1407/2707 1392/1392/2706 1391/1391/2708 +f 1348/1348/2709 1351/1351/2710 1345/1345/2711 +f 1345/1345/2711 1351/1351/2710 1342/1342/2667 +f 1409/1409/2712 1383/1383/2713 1410/1410/2714 +f 1383/1383/2713 1409/1409/2712 1385/1385/2715 +f 1385/1385/2716 1409/1409/2716 1411/1411/2716 +f 1385/1385/2717 1411/1411/2718 1412/1412/2719 +f 1385/1385/2717 1412/1412/2719 1386/1386/2720 +f 1386/1386/2721 1412/1412/2722 1395/1395/2723 +f 1395/1395/2723 1412/1412/2722 1413/1413/2724 +f 1413/1413/2725 1393/1393/2725 1395/1395/2725 +f 1410/1410/2726 1383/1383/2726 1393/1393/2726 +f 1341/1341/2727 1402/1402/2728 1398/1398/2729 +f 1414/1414/2730 1398/1398/2729 1399/1399/2731 +f 1362/1362/2732 1414/1414/2730 1399/1399/2731 +f 1362/1362/2732 1361/1361/2733 1414/1414/2730 +f 1361/1361/2734 1382/1382/2686 1414/1414/2735 +f 1382/1382/2686 1415/1415/2736 1414/1414/2735 +f 1416/1416/2737 1415/1415/2736 1382/1382/2686 +f 1416/1416/2737 1382/1382/2686 1339/1339/2685 +f 1339/1339/2604 1341/1341/2606 1416/1416/2738 +f 1330/1330/2595 1417/1417/2739 1418/1418/2740 +f 1418/1418/2740 1417/1417/2739 1419/1419/2741 +f 1342/1342/2607 1420/1420/2742 1343/1343/2608 +f 1421/1421/2743 1343/1343/2608 1422/1422/2744 +f 1342/1342/2607 1423/1423/2745 1420/1420/2742 +f 1422/1422/2744 1420/1420/2742 1424/1424/2746 +f 1425/1425/2747 1426/1426/2748 1427/1427/2749 +f 1428/1428/2750 1397/1397/2751 1418/1418/2752 +f 1397/1397/2753 1429/1429/2754 1423/1423/2745 +f 1397/1397/2753 1423/1423/2745 1342/1342/2607 +f 1427/1427/2755 1397/1397/2755 1428/1428/2755 +f 1427/1427/2756 1428/1428/2756 1425/1425/2756 +f 1397/1397/2753 1427/1427/2757 1429/1429/2754 +f 1426/1426/2758 1425/1425/2759 1430/1430/2760 +f 1430/1430/2760 1425/1425/2759 1424/1424/2746 +f 1420/1420/2742 1422/1422/2744 1343/1343/2608 +f 1421/1421/2743 1431/1431/2761 1343/1343/2608 +f 1418/1418/2752 1419/1419/2762 1428/1428/2750 +f 1420/1420/2742 1430/1430/2760 1424/1424/2746 +f 1396/1396/2668 1342/1342/2667 1432/1432/2763 +f 1360/1360/2764 1433/1433/2765 1404/1404/2766 +f 1351/1351/2710 1356/1356/2767 1360/1360/2764 +f 1405/1405/2768 1390/1390/2661 1389/1389/2660 +f 1408/1408/2769 1390/1390/2661 1407/1407/2770 +f 1406/1406/2771 1405/1405/2768 1389/1389/2660 +f 1414/1414/2730 1415/1415/2772 1416/1416/2773 +f 1393/1393/2774 1413/1413/2775 1410/1410/2776 +f 1398/1398/2729 1414/1414/2730 1341/1341/2727 +f 1419/1419/2762 1434/1434/2777 1435/1435/2778 +f 1428/1428/2750 1435/1435/2778 1436/1436/2779 +f 1412/1412/2780 1411/1411/2781 1410/1410/2776 +f 1416/1416/2773 1341/1341/2727 1414/1414/2730 +f 1331/1331/2782 1437/1437/2783 1438/1438/2784 +f 1432/1432/2763 1342/1342/2667 1401/1401/2785 +f 1428/1428/2750 1419/1419/2762 1435/1435/2778 +f 1410/1410/2776 1413/1413/2775 1412/1412/2780 +f 1439/1439/2786 1440/1440/2787 1427/1427/2749 +f 1426/1426/2748 1439/1439/2786 1427/1427/2749 +f 1396/1396/2788 1441/1441/2789 1397/1397/2790 +f 1397/1397/2790 1441/1441/2789 1418/1418/2789 +f 1420/1420/2791 1442/1442/2792 1430/1430/2793 +f 1430/1430/2793 1442/1442/2792 1443/1443/2794 +f 1430/1430/2795 1443/1443/2795 1426/1426/2795 +f 1439/1439/2796 1423/1423/2797 1440/1440/2798 +f 1440/1440/2798 1423/1423/2797 1429/1429/2799 +f 1440/1440/2800 1429/1429/2800 1427/1427/2800 +f 1442/1442/2801 1420/1420/2802 1439/1439/2803 +f 1439/1439/2803 1420/1420/2802 1423/1423/2804 +f 1396/1396/2805 1400/1400/2806 1332/1332/2807 +f 1411/1411/2781 1409/1409/2808 1410/1410/2776 +f 1434/1434/2809 1417/1417/2809 1431/1431/2809 +f 1417/1417/2810 1434/1434/2810 1419/1419/2810 +f 1436/1436/2811 1422/1422/2812 1424/1424/2813 +f 1436/1436/2811 1424/1424/2813 1444/1444/2814 +f 1444/1444/2815 1424/1424/2815 1425/1425/2815 +f 1444/1444/2816 1425/1425/2816 1428/1428/2816 +f 1435/1435/2817 1422/1422/2818 1436/1436/2819 +f 1435/1435/2817 1421/1421/2820 1422/1422/2818 +f 1434/1434/2821 1431/1431/2822 1435/1435/2823 +f 1435/1435/2823 1431/1431/2822 1421/1421/2824 +f 1401/1401/2785 1342/1342/2667 1404/1404/2766 +f 1360/1360/2764 1342/1342/2667 1351/1351/2710 +f 1342/1342/2667 1360/1360/2764 1404/1404/2766 +f 1360/1360/2764 1398/1398/2825 1433/1433/2765 +f 1351/1351/2710 1354/1354/2826 1356/1356/2767 +f 1390/1390/2661 1405/1405/2768 1407/1407/2770 +f 1360/1360/2764 1387/1387/2827 1398/1398/2825 +f 1396/1396/2805 1332/1332/2807 1438/1438/2784 +f 1332/1332/2807 1331/1331/2782 1438/1438/2784 +f 1426/1426/2748 1442/1442/2828 1439/1439/2786 +f 1442/1442/2828 1426/1426/2748 1443/1443/2829 +f 1428/1428/2750 1436/1436/2779 1444/1444/2830 +f 1438/1438/2784 1441/1441/2831 1396/1396/2805 +f 1367/1367/2832 1368/1368/2833 1438/1438/2784 +f 1441/1441/2831 1438/1438/2784 1368/1368/2833 +f 1438/1438/2834 1437/1437/2835 1367/1367/2836 +f 1437/1437/2835 1378/1378/2837 1367/1367/2836 +f 1437/1437/2838 1331/1331/2838 1378/1378/2838 +f 1445/1445/2839 1446/1446/2840 1329/1329/2841 +f 1329/1329/2841 1446/1446/2840 1328/1328/2842 +f 1447/1447/2843 1448/1448/2844 1445/1445/2845 +f 1445/1445/2845 1448/1448/2844 1446/1446/2846 +f 1314/1314/2579 1313/1313/2578 1448/1448/2847 +f 1314/1314/2579 1448/1448/2847 1447/1447/2848 +f 1328/1328/2849 1449/1449/2850 1326/1326/2851 +f 1326/1326/2851 1450/1450/2852 1324/1324/2853 +f 1450/1450/2852 1322/1322/2854 1324/1324/2853 +f 1449/1449/2850 1450/1450/2852 1326/1326/2851 +f 1328/1328/2849 1446/1446/210 1448/1448/2855 +f 1451/1451/2856 1452/1452/2857 1369/1369/2858 +f 1313/1313/2859 1449/1449/2850 1448/1448/2855 +f 1453/1453/2860 1454/1454/2861 1320/1320/2862 +f 1320/1320/2862 1454/1454/2861 1321/1321/2863 +f 1455/1455/2864 1452/1452/2865 1454/1454/2866 +f 1455/1455/2864 1454/1454/2866 1453/1453/2867 +f 1370/1370/2635 1369/1369/2634 1452/1452/2868 +f 1370/1370/2635 1452/1452/2868 1455/1455/2869 +f 1315/1315/2870 1317/1317/2871 1456/1456/2872 +f 1317/1317/2871 1457/1457/2873 1456/1456/2872 +f 1317/1317/2871 1319/1319/2874 1457/1457/2873 +f 1458/1458/2875 1319/1319/2874 1321/1321/2876 +f 1319/1319/2874 1458/1458/2875 1457/1457/2873 +f 1313/1313/2859 1315/1315/2870 1456/1456/2872 +f 1456/1456/2872 1449/1449/2850 1313/1313/2859 +f 1321/1321/2876 1452/1452/2857 1458/1458/2875 +f 1454/1454/210 1452/1452/2857 1321/1321/2876 +f 1452/1452/2857 1451/1451/2856 1458/1458/2875 +f 1451/1451/2856 1369/1369/2858 1371/1371/2877 +f 1328/1328/2849 1448/1448/2855 1449/1449/2850 +f 1371/1371/2877 1459/1459/2878 1451/1451/2856 +f 1376/1376/2879 1459/1459/2878 1374/1374/2880 +f 413/413/2881 1323/1323/2882 626/626/2883 +f 1327/1327/2884 1325/1325/2885 610/610/2886 +f 618/618/2887 1372/1372/2888 611/611/2889 +f 413/413/2881 610/610/2886 1325/1325/2885 +f 626/626/2883 1323/1323/2882 1330/1330/2890 +f 629/629/2891 1329/1329/2892 1327/1327/2884 +f 629/629/2891 623/623/2893 1329/1329/2892 +f 1329/1329/2892 623/623/2893 1445/1445/2894 +f 623/623/2893 1447/1447/2895 1445/1445/2894 +f 1441/1441/2896 617/617/2897 1418/1418/2898 +f 617/617/2897 627/627/2899 1418/1418/2898 +f 1314/1314/2900 1447/1447/2895 623/623/2893 +f 1374/1374/2880 1459/1459/2878 1371/1371/2877 +f 617/617/2897 1441/1441/2896 1368/1368/2901 +f 1384/1384/2902 622/622/2903 621/621/2904 +f 622/622/2903 1377/1377/2905 1375/1375/2906 +f 1314/1314/2900 623/623/2893 632/632/2907 +f 1314/1314/2900 632/632/2907 1316/1316/2908 +f 588/588/2909 1368/1368/2901 1366/1366/2910 +f 1316/1316/2908 632/632/2907 624/624/2911 +f 588/588/2909 1366/1366/2910 612/612/2912 +f 1373/1373/2913 1372/1372/2888 618/618/2887 +f 612/612/2912 1366/1366/2910 1363/1363/2914 +f 1316/1316/2908 624/624/2911 625/625/2915 +f 612/612/2912 1363/1363/2914 613/613/2916 +f 1316/1316/2908 625/625/2915 1318/1318/2917 +f 1318/1318/2917 625/625/2915 631/631/2918 +f 613/613/2916 1363/1363/2914 616/616/2919 +f 616/616/2919 1363/1363/2914 1362/1362/2920 +f 1320/1320/2921 631/631/2918 589/589/2922 +f 616/616/2919 1362/1362/2920 621/621/2904 +f 1318/1318/2917 631/631/2918 1320/1320/2921 +f 621/621/2904 1362/1362/2920 1399/1399/2923 +f 1320/1320/2921 589/589/2922 1453/1453/2924 +f 1399/1399/2923 1384/1384/2902 621/621/2904 +f 1453/1453/2924 589/589/2922 1455/1455/2925 +f 627/627/2899 626/626/2883 1330/1330/2890 +f 589/589/2922 1370/1370/2926 1455/1455/2925 +f 627/627/2899 1330/1330/2890 1418/1418/2898 +f 1325/1325/2885 1323/1323/2882 413/413/2881 +f 1377/1377/2905 622/622/2903 1384/1384/2902 +f 589/589/2922 611/611/2889 1370/1370/2926 +f 630/630/2927 622/622/2903 1375/1375/2906 +f 1370/1370/2926 611/611/2889 1372/1372/2888 +f 1327/1327/2884 610/610/2886 629/629/2891 +f 588/588/2909 617/617/2897 1368/1368/2901 +f 1375/1375/2906 1373/1373/2913 630/630/2927 +f 1373/1373/2913 618/618/2887 630/630/2927 +f 1359/1359/2928 1376/1376/2929 1383/1383/2930 +f 1376/1376/2929 1359/1359/2928 1459/1459/2931 +f 1383/1383/2932 1385/1385/2654 1359/1359/2624 +f 1344/1344/2933 1460/1460/2934 1346/1346/2935 +f 1350/1350/2936 1349/1349/2937 1461/1461/2938 +f 1352/1352/2939 1350/1350/2940 1462/1462/2941 +f 1353/1353/2942 1463/1463/2943 1355/1355/2944 +f 1355/1355/2944 1458/1458/2945 1357/1357/2946 +f 1359/1359/2928 1358/1358/2947 1451/1451/2948 +f 1346/1346/2935 1449/1449/2949 1347/1347/2950 +f 1347/1347/2950 1449/1449/2949 1461/1461/2938 +f 1347/1347/2950 1461/1461/2938 1349/1349/2937 +f 1352/1352/2939 1462/1462/2941 1353/1353/2942 +f 1355/1355/2944 1463/1463/2943 1458/1458/2945 +f 1359/1359/2928 1451/1451/2948 1459/1459/2931 +f 1343/1343/2951 1450/1450/2952 1344/1344/2933 +f 1344/1344/2933 1450/1450/2952 1460/1460/2934 +f 1346/1346/2935 1460/1460/2934 1449/1449/2949 +f 1353/1353/2942 1462/1462/2941 1463/1463/2943 +f 1358/1358/2947 1357/1357/2946 1451/1451/2948 +f 1461/1461/2953 1456/1456/2953 1350/1350/2953 +f 1350/1350/2940 1456/1456/2954 1462/1462/2941 +f 1357/1357/2946 1458/1458/2945 1451/1451/2948 +f 1460/1460/2955 1450/1450/2955 1449/1449/2955 +f 1449/1449/2949 1456/1456/2956 1461/1461/2938 +f 1462/1462/2941 1456/1456/2954 1457/1457/2957 +f 1462/1462/2941 1457/1457/2957 1463/1463/2943 +f 1463/1463/2943 1457/1457/2957 1458/1458/2945 +f 1343/1343/2951 1417/1417/2958 1322/1322/2959 +f 1343/1343/2608 1431/1431/2761 1417/1417/2960 +f 1343/1343/2951 1322/1322/2959 1450/1450/2952 +f 1417/1417/2739 1330/1330/2595 1322/1322/2587 +f 1377/1377/2642 1383/1383/2652 1376/1376/2641 +f 1433/1433/2961 1398/1398/2961 1402/1402/2961 +f 1400/1400/2962 1396/1396/2962 1432/1432/2962 +f 1433/1433/2963 1402/1402/2963 1404/1404/2963 +f 1404/1404/2766 1403/1403/2964 1401/1401/2785 +f 1400/1400/2965 1432/1432/2965 1401/1401/2965 +f 1464/1464/2966 1465/1465/2967 1466/1466/2968 +f 1467/1467/2969 1468/1468/2970 1469/1469/2971 +f 1469/1469/2971 1468/1468/2970 1470/1470/2972 +f 1471/1471/2973 1472/1472/2974 1473/1473/2975 +f 1474/1474/2976 1473/1473/2975 1475/1475/2977 +f 1465/1465/2967 1464/1464/2966 1474/1474/2976 +f 1473/1473/2975 1472/1472/2974 1476/1476/2978 +f 1476/1476/2978 1472/1472/2974 1477/1477/2979 +f 1476/1476/2978 1477/1477/2979 1478/1478/2980 +f 1471/1471/2973 1479/1479/2981 1472/1472/2974 +f 1479/1479/2981 1471/1471/2973 1480/1480/2982 +f 1481/1481/2983 1482/1482/2984 1480/1480/2982 +f 1480/1480/2982 1482/1482/2984 1479/1479/2981 +f 1464/1464/2966 1466/1466/2968 1483/1483/2985 +f 1483/1483/2985 1466/1466/2968 1484/1484/2986 +f 1484/1484/2986 1466/1466/2968 1485/1485/2987 +f 1486/1486/2988 1487/1487/2989 1488/1488/2990 +f 1488/1488/2990 1487/1487/2989 1465/1465/2967 +f 1481/1481/2983 1489/1489/2991 1482/1482/2984 +f 1490/1490/2992 1491/1491/2993 1489/1489/2991 +f 1492/1492/2994 1489/1489/2991 1481/1481/2983 +f 1478/1478/2995 1477/1477/2996 1490/1490/2992 +f 1490/1490/2992 1477/1477/2996 1491/1491/2993 +f 1489/1489/2991 1492/1492/2994 1490/1490/2992 +f 1488/1488/2997 1493/1493/2998 1486/1486/2999 +f 1493/1493/2998 1488/1488/2997 1494/1494/3000 +f 1495/1495/3001 1494/1494/3000 1496/1496/3002 +f 1478/1478/3003 1497/1497/3004 1476/1476/3005 +f 1476/1476/3005 1497/1497/3004 1495/1495/3001 +f 1498/1498/3006 1487/1487/3007 1486/1486/3008 +f 1499/1499/3009 1487/1487/3007 1498/1498/3006 +f 1484/1484/2986 1499/1499/3009 1500/1500/3010 +f 1484/1484/2986 1485/1485/2987 1499/1499/3009 +f 1499/1499/3009 1498/1498/3006 1500/1500/3010 +f 1480/1480/3011 1501/1501/3012 1502/1502/3013 +f 1501/1501/3012 1470/1470/3014 1503/1503/3015 +f 1504/1504/3016 1505/1505/3017 1503/1503/3015 +f 1484/1484/2986 1504/1504/3016 1483/1483/2985 +f 1506/1506/3018 1507/1507/3019 1508/1508/3020 +f 1502/1502/3021 1509/1509/3022 1510/1510/3023 +f 1511/1511/3024 1512/1512/3025 1505/1505/3017 +f 1505/1505/3017 1512/1512/3025 1503/1503/3026 +f 1503/1503/3026 1512/1512/3025 1513/1513/3027 +f 1503/1503/3026 1513/1513/3027 1501/1501/3028 +f 1501/1501/3028 1513/1513/3027 1514/1514/3029 +f 1501/1501/3028 1514/1514/3029 1509/1509/3022 +f 1501/1501/3028 1509/1509/3022 1502/1502/3021 +f 1515/1515/3030 1512/1512/3031 1511/1511/3032 +f 1515/1515/3030 1516/1516/3033 1512/1512/3031 +f 1517/1517/3034 1516/1516/3033 1515/1515/3030 +f 1516/1516/3033 1517/1517/3034 1518/1518/3035 +f 1518/1518/3036 1519/1519/3037 1520/1520/3038 +f 1520/1520/3038 1519/1519/3037 1521/1521/3039 +f 1520/1520/3038 1521/1521/3039 1509/1509/3040 +f 1521/1521/3039 1510/1510/3041 1509/1509/3040 +f 1522/1522/3042 1523/1523/3043 1507/1507/3044 +f 1524/1524/3045 1508/1508/3046 1522/1522/3042 +f 1522/1522/3042 1508/1508/3046 1523/1523/3043 +f 1524/1524/3045 1525/1525/3047 1508/1508/3046 +f 1525/1525/3047 1524/1524/3045 1526/1526/3048 +f 1527/1527/3049 1507/1507/3019 1528/1528/3050 +f 1507/1507/3019 1527/1527/3049 1522/1522/3051 +f 1522/1522/3052 1527/1527/3053 1529/1529/3054 +f 1529/1529/3054 1524/1524/3055 1522/1522/3052 +f 1530/1530/3056 1526/1526/3057 1531/1531/3058 +f 1526/1526/3057 1529/1529/3054 1531/1531/3058 +f 1529/1529/3054 1526/1526/3057 1524/1524/3055 +f 1532/1532/3059 1533/1533/3060 1531/1531/3058 +f 1531/1531/3058 1533/1533/3060 1530/1530/3056 +f 1532/1532/3059 1534/1534/3061 1533/1533/3060 +f 1535/1535/3062 1534/1534/3062 1532/1532/3062 +f 1535/1535/3063 1536/1536/3064 1534/1534/3061 +f 1537/1537/3065 1536/1536/3066 1535/1535/3067 +f 1537/1537/3065 1538/1538/3068 1536/1536/3066 +f 1537/1537/3065 1539/1539/3069 1538/1538/3068 +f 1540/1540/3070 1539/1539/3070 1537/1537/3070 +f 1541/1541/3071 1542/1542/3072 1540/1540/3073 +f 1540/1540/3073 1542/1542/3072 1539/1539/3074 +f 1543/1543/3075 1542/1542/3072 1541/1541/3071 +f 1544/1544/3076 1545/1545/3077 1541/1541/3071 +f 1541/1541/3071 1545/1545/3077 1543/1543/3075 +f 1544/1544/3076 1546/1546/3078 1545/1545/3077 +f 1546/1546/3078 1544/1544/3076 1547/1547/3079 +f 1546/1546/3078 1547/1547/3079 1548/1548/3080 +f 1549/1549/3081 1550/1550/3082 1547/1547/3079 +f 1547/1547/3079 1550/1550/3082 1548/1548/3080 +f 1549/1549/3081 1551/1551/3083 1550/1550/3082 +f 1549/1549/3081 1511/1511/3084 1551/1551/3083 +f 1552/1552/3085 1515/1515/3086 1511/1511/3084 +f 1552/1552/3085 1511/1511/3084 1549/1549/3081 +f 1517/1517/3034 1515/1515/3030 1553/1553/3087 +f 1553/1553/3087 1515/1515/3030 1552/1552/3088 +f 1553/1553/3087 1554/1554/3089 1518/1518/3090 +f 1518/1518/3090 1517/1517/3034 1553/1553/3087 +f 1519/1519/3037 1518/1518/3090 1554/1554/3089 +f 1554/1554/3089 1555/1555/3091 1519/1519/3037 +f 1555/1555/3091 1521/1521/3039 1519/1519/3037 +f 1528/1528/3050 1521/1521/3039 1555/1555/3091 +f 1528/1528/3050 1510/1510/3023 1521/1521/3039 +f 1510/1510/3023 1528/1528/3050 1506/1506/3018 +f 1506/1506/3018 1528/1528/3050 1507/1507/3019 +f 1514/1514/3092 1520/1520/3093 1509/1509/3094 +f 1514/1514/3092 1518/1518/3095 1520/1520/3093 +f 1514/1514/3092 1516/1516/3096 1518/1518/3095 +f 1513/1513/3097 1516/1516/3096 1514/1514/3092 +f 1512/1512/3098 1516/1516/3096 1513/1513/3097 +f 1508/1508/3046 1507/1507/3044 1523/1523/3043 +f 1506/1506/3018 1508/1508/3020 1530/1530/3056 +f 1549/1549/3099 1528/1528/3100 1552/1552/3101 +f 1555/1555/3099 1552/1552/3101 1528/1528/3100 +f 1555/1555/3099 1553/1553/3102 1552/1552/3101 +f 1553/1553/3102 1555/1555/3099 1554/1554/3103 +f 1480/1480/3011 1502/1502/3013 1481/1481/3104 +f 1502/1502/3021 1492/1492/3105 1481/1481/3106 +f 1502/1502/3021 1510/1510/3023 1506/1506/3018 +f 1502/1502/3021 1506/1506/3018 1492/1492/3105 +f 1532/1532/3101 1537/1537/3099 1535/1535/3099 +f 1540/1540/3099 1537/1537/3099 1532/1532/3101 +f 1540/1540/3099 1532/1532/3101 1541/1541/3099 +f 1541/1541/3099 1532/1532/3101 1531/1531/3099 +f 1531/1531/3099 1544/1544/3099 1541/1541/3099 +f 1544/1544/3099 1531/1531/3099 1529/1529/3099 +f 1544/1544/3099 1529/1529/3099 1547/1547/3099 +f 1547/1547/3099 1529/1529/3099 1527/1527/3099 +f 1527/1527/3099 1549/1549/3099 1547/1547/3099 +f 1549/1549/3099 1527/1527/3099 1528/1528/3100 +f 1508/1508/3020 1525/1525/3107 1530/1530/3056 +f 1530/1530/3056 1525/1525/3107 1526/1526/3057 +f 1493/1493/2998 1556/1556/3108 1542/1542/3109 +f 1533/1533/3110 1557/1557/3111 1497/1497/3004 +f 1497/1497/3004 1557/1557/3111 1558/1558/3112 +f 1497/1497/3004 1558/1558/3112 1495/1495/3113 +f 1495/1495/3113 1558/1558/3112 1559/1559/3114 +f 1495/1495/3113 1559/1559/3114 1494/1494/3115 +f 1494/1494/3115 1559/1559/3114 1556/1556/3108 +f 1494/1494/3115 1556/1556/3108 1493/1493/2998 +f 1539/1539/3069 1542/1542/3116 1556/1556/3117 +f 1557/1557/3118 1533/1533/3060 1534/1534/3061 +f 1557/1557/3118 1534/1534/3061 1560/1560/3119 +f 1536/1536/3064 1560/1560/3119 1534/1534/3061 +f 1539/1539/3069 1561/1561/3120 1538/1538/3068 +f 1539/1539/3069 1556/1556/3117 1561/1561/3120 +f 1559/1559/3121 1561/1561/3122 1556/1556/3123 +f 1559/1559/3121 1538/1538/3124 1561/1561/3122 +f 1559/1559/3121 1536/1536/3125 1538/1538/3124 +f 1558/1558/3126 1536/1536/3125 1559/1559/3121 +f 1558/1558/3126 1560/1560/3127 1536/1536/3125 +f 1557/1557/3128 1560/1560/3127 1558/1558/3126 +f 1490/1490/2992 1492/1492/2994 1506/1506/3129 +f 1490/1490/2992 1506/1506/3129 1530/1530/3130 +f 1497/1497/3004 1478/1478/3003 1490/1490/3131 +f 1497/1497/3004 1490/1490/3131 1530/1530/3132 +f 1533/1533/3110 1497/1497/3004 1530/1530/3132 +f 1545/1545/3133 1546/1546/3134 1562/1562/3135 +f 1546/1546/3134 1563/1563/3136 1562/1562/3135 +f 1548/1548/3137 1563/1563/3136 1546/1546/3134 +f 1548/1548/3137 1550/1550/3082 1563/1563/3136 +f 1563/1563/3136 1550/1550/3082 1562/1562/3135 +f 1543/1543/3138 1562/1562/3135 1551/1551/3083 +f 1500/1500/3010 1498/1498/3006 1543/1543/3139 +f 1551/1551/3140 1500/1500/3010 1543/1543/3139 +f 1562/1562/3135 1550/1550/3082 1551/1551/3083 +f 1505/1505/3017 1504/1504/3016 1484/1484/2986 +f 1505/1505/3017 1484/1484/2986 1500/1500/3141 +f 1505/1505/3017 1500/1500/3141 1551/1551/3142 +f 1505/1505/3017 1551/1551/3142 1511/1511/3024 +f 1562/1562/3135 1543/1543/3138 1545/1545/3143 +f 1486/1486/2999 1493/1493/2998 1498/1498/3144 +f 1543/1543/3145 1493/1493/2998 1542/1542/3109 +f 1498/1498/3144 1493/1493/2998 1543/1543/3145 +f 513/513/3146 591/591/3147 604/604/3148 +f 528/528/3149 601/601/3150 600/600/3151 +f 601/601/3150 528/528/3149 236/236/3152 +f 528/528/3149 600/600/3151 735/735/3153 +f 733/733/3154 527/527/3155 735/735/3153 +f 398/398/3156 236/236/3152 529/529/3157 +f 398/398/3156 601/601/3150 236/236/3152 +f 594/594/3158 592/592/3159 515/515/3160 +f 526/526/3161 527/527/3155 733/733/3154 +f 598/598/3162 516/516/3163 517/517/3164 +f 529/529/3157 608/608/3165 396/396/3166 +f 733/733/3154 747/747/3167 526/526/3161 +f 529/529/3157 530/530/761 608/608/3165 +f 521/521/3168 523/523/3169 729/729/3170 +f 731/731/3171 526/526/3161 747/747/3167 +f 530/530/761 394/394/3172 608/608/3165 +f 731/731/3171 523/523/3169 526/526/3161 +f 729/729/3170 523/523/3169 731/731/3171 +f 530/530/761 392/392/3173 394/394/3172 +f 381/381/760 392/392/3173 530/530/761 +f 381/381/760 508/508/3174 392/392/3173 +f 514/514/3175 508/508/3174 381/381/760 +f 741/741/3176 521/521/3168 729/729/3170 +f 741/741/3176 519/519/3177 521/521/3168 +f 738/738/3178 519/519/3177 741/741/3176 +f 514/514/3175 510/510/3179 508/508/3174 +f 513/513/3146 510/510/3179 514/514/3175 +f 738/738/3178 737/737/3180 519/519/3177 +f 737/737/3180 517/517/3164 519/519/3177 +f 737/737/3180 743/743/3181 517/517/3164 +f 527/527/3155 528/528/3149 735/735/3153 +f 529/529/3157 396/396/3166 398/398/3156 +f 607/607/3182 513/513/3146 604/604/3148 +f 746/746/3183 517/517/3164 743/743/3181 +f 598/598/3162 517/517/3164 746/746/3183 +f 513/513/3146 515/515/3160 592/592/3159 +f 516/516/3163 598/598/3162 597/597/3184 +f 591/591/3147 513/513/3146 592/592/3159 +f 512/512/3185 510/510/3179 513/513/3146 +f 500/500/3186 594/594/3158 515/515/3160 +f 500/500/3186 597/597/3184 594/594/3158 +f 597/597/3184 500/500/3186 516/516/3163 +f 607/607/3182 512/512/3185 513/513/3146 +f 511/511/3187 606/606/3188 848/848/3189 +f 606/606/3188 605/605/3190 848/848/3189 +f 848/848/3189 605/605/3190 590/590/3191 +f 866/866/3192 744/744/3193 736/736/3194 +f 745/745/3195 744/744/3193 866/866/3192 +f 745/745/3195 866/866/3192 599/599/3196 +f 872/872/3197 748/748/3198 732/732/3199 +f 748/748/3198 872/872/3197 869/869/3200 +f 750/750/3201 748/748/3198 869/869/3200 +f 1465/1465/2967 1474/1474/2976 1475/1475/2977 +f 1496/1496/3202 1488/1488/2990 1475/1475/2977 +f 1488/1488/2997 1496/1496/3002 1494/1494/3000 +f 1475/1475/2977 1488/1488/2990 1465/1465/2967 +f 1476/1476/2978 1475/1475/2977 1473/1473/2975 +f 1496/1496/3002 1476/1476/3005 1495/1495/3001 +f 1476/1476/2978 1496/1496/3202 1475/1475/2977 +f 1471/1471/2973 1464/1464/2966 1468/1468/2970 +f 1464/1464/2966 1471/1471/2973 1473/1473/2975 +f 1474/1474/2976 1464/1464/2966 1473/1473/2975 +f 1471/1471/2973 1468/1468/2970 1467/1467/2969 +f 1499/1499/3203 1466/1466/2968 1465/1465/2967 +f 1465/1465/2967 1487/1487/2989 1499/1499/3203 +f 1485/1485/2987 1466/1466/2968 1499/1499/3203 +f 1479/1479/2981 1482/1482/2984 1489/1489/3204 +f 1489/1489/3204 1472/1472/2974 1479/1479/2981 +f 1489/1489/3204 1491/1491/3205 1472/1472/2974 +f 1477/1477/2979 1472/1472/2974 1491/1491/3205 +f 1470/1470/3014 1504/1504/3016 1503/1503/3015 +f 1468/1468/2970 1464/1464/2966 1470/1470/2972 +f 1470/1470/3014 1483/1483/2985 1504/1504/3016 +f 1483/1483/2985 1470/1470/2972 1464/1464/2966 +f 1471/1471/2973 1467/1467/2969 1469/1469/2971 +f 1469/1469/2971 1480/1480/2982 1471/1471/2973 +f 1469/1469/2971 1470/1470/2972 1480/1480/2982 +f 1501/1501/3012 1480/1480/3011 1470/1470/3014 diff --git a/examples/Cassie/urdf/meshes/agility/hip-yaw.obj b/examples/Cassie/urdf/meshes/agility/hip-yaw.obj new file mode 100644 index 0000000000..d1f54f21c7 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/hip-yaw.obj @@ -0,0 +1,4782 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o hip-yaw +v 0.009840 -0.037390 -0.008288 +v 0.008183 -0.037125 0.001224 +v 0.004829 -0.036659 -0.007895 +v 0.004415 -0.036610 0.007760 +v 0.010947 -0.037598 0.008391 +v -0.000082 -0.036465 0.008233 +v 0.001837 -0.036526 0.014639 +v -0.000074 -0.036534 0.019923 +v 0.008661 -0.037147 0.020085 +v -0.005368 -0.036756 0.019961 +v -0.001959 -0.036516 0.012938 +v -0.007581 -0.037018 0.003753 +v -0.007974 -0.037028 -0.007445 +v -0.006595 -0.036891 -0.005051 +v -0.010276 -0.037461 0.008161 +v 0.000474 -0.036455 -0.008319 +v -0.002184 -0.036546 -0.014127 +v 0.000001 -0.036534 -0.019925 +v -0.005039 -0.036722 -0.019953 +v 0.005858 -0.036807 -0.019959 +v 0.001923 -0.036532 -0.014363 +v 0.013900 -0.038314 0.019905 +v 0.013469 -0.038156 0.005431 +v 0.011557 -0.037759 -0.003599 +v 0.014265 -0.038432 -0.005559 +v 0.014230 -0.038420 -0.012609 +v 0.011706 -0.037766 -0.019978 +v 0.014330 -0.038483 -0.019952 +v -0.013955 -0.038350 -0.012087 +v -0.014192 -0.038401 -0.005547 +v -0.013869 -0.038303 -0.019930 +v -0.010085 -0.037432 0.001124 +v -0.014263 -0.038431 0.005558 +v -0.014340 -0.038494 0.019920 +v -0.018863 -0.039901 -0.020074 +v -0.019385 -0.040047 -0.005436 +v -0.019308 -0.040033 0.005457 +v -0.020073 -0.040081 0.020847 +v 0.018991 -0.039939 0.020096 +v 0.019844 -0.040151 0.005390 +v 0.019303 -0.040027 -0.005449 +v 0.018772 -0.039875 -0.020053 +v -0.020460 -0.040048 -0.021081 +v -0.022043 -0.039560 0.002517 +v -0.022501 -0.039364 0.021033 +v -0.022580 -0.039294 -0.001194 +v -0.023030 -0.038945 -0.021001 +v -0.011575 -0.036956 -0.021702 +v -0.002341 -0.035767 -0.021721 +v 0.010548 -0.036724 -0.021669 +v 0.020521 -0.040074 -0.021074 +v -0.010635 -0.037551 -0.019983 +v 0.021876 -0.039628 -0.002806 +v 0.022508 -0.039376 0.020997 +v 0.022537 -0.039274 0.000440 +v 0.023110 -0.038867 -0.020995 +v 0.020173 -0.039929 0.021157 +v 0.002083 -0.035773 0.021713 +v 0.011016 -0.036895 0.021707 +v -0.016475 -0.038254 0.021845 +v -0.011450 -0.037713 0.019961 +v -0.007386 -0.036286 0.021664 +v -0.030550 -0.027836 0.002076 +v -0.030547 -0.026737 -0.009064 +v -0.030493 -0.029920 -0.017182 +v -0.030456 -0.030481 0.017254 +v -0.030782 -0.022719 0.016726 +v -0.030566 -0.025418 0.012580 +v -0.030586 -0.023414 -0.017021 +v 0.001586 -0.031101 0.024998 +v -0.005236 -0.023153 0.025000 +v -0.021083 -0.035499 0.024949 +v -0.015518 -0.024765 0.024993 +v -0.020985 -0.026371 0.025045 +v -0.024559 -0.031789 0.024997 +v -0.024402 -0.023859 0.025093 +v 0.005474 -0.023165 0.025000 +v 0.015725 -0.024826 0.024993 +v 0.021039 -0.035298 0.025000 +v 0.020508 -0.026212 0.025103 +v 0.024558 -0.031796 0.024993 +v 0.024429 -0.024050 0.025065 +v 0.023450 -0.022490 0.026000 +v 0.018160 -0.022345 0.029968 +v 0.018264 -0.025531 0.026115 +v 0.011722 -0.022328 0.033023 +v 0.012555 -0.024147 0.030851 +v 0.004960 -0.022335 0.034689 +v 0.002316 -0.022945 0.034508 +v -0.004010 -0.022333 0.034885 +v -0.012419 -0.022326 0.032766 +v -0.007474 -0.023397 0.033152 +v -0.018707 -0.022332 0.029627 +v -0.018778 -0.025673 0.025714 +v -0.013819 -0.024413 0.029951 +v -0.023520 -0.022538 0.025933 +v -0.031213 -0.024120 0.011689 +v -0.033702 -0.022335 0.009580 +v -0.031160 -0.025646 0.006360 +v -0.034913 -0.022335 0.002936 +v -0.031098 -0.026348 0.000754 +v -0.034834 -0.022350 -0.003450 +v -0.031138 -0.026034 -0.004030 +v -0.033759 -0.022344 -0.009361 +v -0.031170 -0.024803 -0.009800 +v -0.031428 -0.022409 -0.015447 +v -0.028325 -0.033892 0.020671 +v -0.029710 -0.020337 0.018525 +v -0.032828 -0.020337 0.012281 +v -0.034644 -0.020337 0.005265 +v -0.034977 -0.020338 -0.002097 +v -0.033378 -0.020338 -0.010901 +v -0.030460 -0.020338 -0.017239 +v -0.027601 -0.020336 -0.021722 +v -0.029842 -0.032053 -0.018332 +v -0.023444 -0.022479 -0.026025 +v -0.024429 -0.024050 -0.025065 +v -0.024603 -0.031760 -0.024986 +v -0.028004 -0.033992 -0.021005 +v -0.022168 -0.020338 -0.027122 +v -0.016211 -0.020338 -0.031066 +v -0.015942 -0.022339 -0.031198 +v -0.009546 -0.020338 -0.033717 +v -0.009420 -0.022341 -0.033743 +v -0.000585 -0.020338 -0.035113 +v -0.000798 -0.022338 -0.035095 +v 0.011294 -0.020338 -0.033328 +v 0.008152 -0.022337 -0.034071 +v 0.016523 -0.022339 -0.030998 +v 0.020991 -0.020337 -0.028078 +v 0.027768 -0.020334 -0.021721 +v 0.024385 -0.023767 -0.025110 +v 0.023488 -0.022507 -0.025968 +v 0.029704 -0.032231 -0.018527 +v 0.028000 -0.033999 -0.021001 +v 0.024565 -0.031786 -0.024995 +v 0.032196 -0.020338 -0.013821 +v 0.031715 -0.022345 -0.014854 +v 0.030890 -0.022795 -0.016458 +v 0.030532 -0.023955 -0.017109 +v 0.030485 -0.030118 -0.017197 +v 0.034226 -0.020338 -0.007442 +v 0.034338 -0.022331 -0.006989 +v 0.035071 -0.020338 -0.000000 +v 0.035065 -0.022329 0.000001 +v 0.033860 -0.020337 0.009283 +v 0.034043 -0.022325 0.008568 +v 0.030687 -0.020339 0.016852 +v 0.031249 -0.022500 0.015786 +v 0.030571 -0.023554 0.017045 +v 0.029900 -0.031989 0.018225 +v 0.030497 -0.029812 0.017175 +v 0.028006 -0.033993 0.021001 +v 0.026282 -0.020337 0.023239 +v 0.020916 -0.020337 0.028129 +v 0.012789 -0.020337 0.032704 +v 0.002327 -0.020337 0.035041 +v -0.006517 -0.020337 0.034432 +v -0.016726 -0.020337 0.030998 +v -0.024708 -0.020338 0.024804 +v 0.020263 -0.036640 0.024406 +v 0.009795 -0.034039 0.024285 +v -0.000336 -0.033155 0.024283 +v -0.010152 -0.034083 0.024295 +v -0.019905 -0.036676 0.024334 +v 0.010996 -0.032333 -0.024999 +v 0.005239 -0.023153 -0.025000 +v 0.015539 -0.024771 -0.024993 +v 0.020901 -0.035679 -0.024910 +v 0.020339 -0.026157 -0.025133 +v -0.006489 -0.031700 -0.024999 +v -0.005445 -0.023174 -0.025000 +v -0.015659 -0.024807 -0.024993 +v -0.021032 -0.035303 -0.025000 +v -0.020496 -0.026208 -0.025105 +v -0.011619 -0.023944 -0.031479 +v -0.018261 -0.025531 -0.026117 +v -0.000916 -0.022950 -0.034489 +v 0.009196 -0.023583 -0.032598 +v 0.018192 -0.025498 -0.026225 +v -0.020252 -0.036642 -0.024411 +v -0.013522 -0.034801 -0.024293 +v -0.004887 -0.033383 -0.024290 +v 0.006598 -0.033460 -0.024279 +v 0.019841 -0.036695 -0.024320 +v 0.030565 -0.027231 -0.005942 +v 0.030550 -0.027844 0.001937 +v 0.030552 -0.025588 0.012373 +v 0.031076 -0.025147 -0.009106 +v 0.031102 -0.026358 -0.001324 +v 0.031141 -0.026011 0.004175 +v 0.031185 -0.024926 0.009246 +v 0.046227 -0.104876 -0.025000 +v -0.000559 -0.138526 -0.025000 +v 0.048610 -0.092476 -0.025000 +v 0.047452 -0.079601 -0.025000 +v 0.042075 -0.114247 -0.025000 +v 0.028415 -0.129380 -0.025000 +v 0.036048 -0.122538 -0.025000 +v 0.038675 -0.048955 -0.024740 +v 0.023141 -0.037704 -0.025031 +v 0.019516 -0.134467 -0.025000 +v 0.000361 -0.032811 -0.025006 +v 0.014182 -0.034664 -0.024761 +v 0.009748 -0.137573 -0.025000 +v -0.039865 -0.053105 -0.024973 +v -0.047346 -0.079207 -0.025000 +v -0.010637 -0.137382 -0.025000 +v -0.014269 -0.034683 -0.024750 +v -0.036651 -0.121858 -0.025000 +v -0.020346 -0.134094 -0.025000 +v -0.022671 -0.037463 -0.024780 +v -0.029148 -0.128841 -0.025000 +v -0.024455 -0.037222 -0.024975 +v -0.046497 -0.104008 -0.025000 +v -0.048658 -0.091186 -0.025000 +v -0.042522 -0.113455 -0.025000 +v 0.010637 -0.137382 0.025000 +v 0.020346 -0.134094 0.025000 +v -0.009748 -0.137573 0.025000 +v 0.047347 -0.079206 0.025000 +v 0.036651 -0.121858 0.025000 +v 0.048658 -0.091186 0.025000 +v 0.042521 -0.113455 0.025000 +v 0.046498 -0.104007 0.025000 +v 0.029148 -0.128841 0.025000 +v 0.038869 -0.049629 0.024857 +v 0.022671 -0.037463 0.024780 +v 0.014275 -0.034677 0.024776 +v -0.047452 -0.079600 0.025000 +v -0.048610 -0.092476 0.025000 +v -0.042075 -0.114247 0.025000 +v 0.023747 -0.037357 0.024962 +v 0.007011 -0.033358 0.024762 +v -0.000922 -0.032874 0.024820 +v -0.036048 -0.122538 0.025000 +v -0.028416 -0.129380 0.025000 +v 0.000515 -0.138540 0.025000 +v -0.014181 -0.034656 0.024786 +v -0.019517 -0.134467 0.025000 +v -0.022876 -0.037560 0.024777 +v -0.038877 -0.049660 0.024859 +v -0.023372 -0.037440 0.024932 +v -0.046227 -0.104876 0.025000 +v -0.030843 -0.031157 -0.017813 +v -0.027808 -0.034192 -0.015078 +v -0.027568 -0.034432 -0.017839 +v -0.028091 -0.033909 -0.023311 +v -0.023202 -0.038798 -0.016094 +v -0.024230 -0.037770 -0.013378 +v -0.022633 -0.039321 0.021568 +v -0.030821 -0.031179 0.017768 +v -0.026355 -0.035645 -0.012784 +v -0.026044 -0.035956 -0.019169 +v -0.022335 -0.039550 -0.021468 +v -0.024487 -0.037513 -0.018896 +v -0.028303 -0.033697 0.023077 +v -0.027342 -0.034658 0.018184 +v -0.023928 -0.038072 0.018246 +v -0.023269 -0.038731 0.015913 +v -0.025105 -0.036839 0.024865 +v -0.025536 -0.036464 0.019293 +v -0.027902 -0.034098 0.015514 +v -0.024458 -0.037542 0.013019 +v -0.026816 -0.035184 0.013191 +v -0.034564 -0.034633 0.016358 +v -0.035891 -0.039256 0.014321 +v -0.035750 -0.038765 0.016946 +v -0.041882 -0.060125 0.017694 +v -0.042024 -0.060620 0.015105 +v -0.035652 -0.038424 0.021262 +v -0.042024 -0.060620 -0.016895 +v -0.041134 -0.057519 -0.019993 +v -0.035750 -0.038765 -0.015054 +v -0.034693 -0.035083 -0.018104 +v -0.035891 -0.039256 -0.017680 +v -0.036649 -0.041897 -0.019968 +v -0.041882 -0.060125 -0.014305 +v -0.041127 -0.057493 0.019965 +v -0.038972 -0.049988 0.021661 +v -0.037130 -0.043573 -0.023619 +v -0.036692 -0.042048 0.020069 +v -0.038801 -0.049393 -0.021661 +v -0.041126 -0.057493 -0.012034 +v -0.041134 -0.057519 0.012007 +v -0.036649 -0.041897 0.012031 +v -0.036693 -0.042048 -0.011931 +v -0.038801 -0.049393 0.010339 +v -0.038972 -0.049988 -0.010339 +v -0.021800 -0.039735 0.021635 +v -0.020282 -0.039867 0.021533 +v -0.020424 -0.039891 -0.021555 +v 0.034693 -0.035083 0.018104 +v 0.034564 -0.034634 -0.016358 +v 0.030843 -0.031157 0.017813 +v 0.030821 -0.031179 -0.017768 +v 0.041882 -0.060125 -0.017694 +v 0.042024 -0.060620 -0.015105 +v 0.041882 -0.060125 0.014306 +v 0.042024 -0.060620 0.016895 +v 0.035891 -0.039256 -0.014320 +v 0.035750 -0.038765 -0.016946 +v 0.035652 -0.038423 -0.021262 +v 0.041126 -0.057493 -0.019966 +v 0.038972 -0.049988 -0.021661 +v 0.041134 -0.057519 0.019993 +v 0.035750 -0.038765 0.015054 +v 0.035891 -0.039256 0.017680 +v 0.036649 -0.041897 0.019969 +v 0.036692 -0.042048 -0.020069 +v 0.036389 -0.040989 0.022444 +v 0.041126 -0.057493 0.012035 +v 0.041134 -0.057519 -0.012007 +v 0.036649 -0.041897 -0.012032 +v 0.036692 -0.042049 0.011931 +v 0.038801 -0.049393 0.021661 +v 0.038801 -0.049393 -0.010339 +v 0.038972 -0.049988 0.010339 +v 0.023806 -0.038194 0.018250 +v 0.023358 -0.038642 0.015235 +v 0.022373 -0.039529 0.021505 +v 0.022583 -0.039349 -0.021560 +v 0.024230 -0.037770 -0.018622 +v 0.025091 -0.036850 -0.024867 +v 0.023294 -0.038706 -0.016486 +v 0.025741 -0.036259 -0.019252 +v 0.028303 -0.033697 -0.023077 +v 0.027494 -0.034506 -0.017989 +v 0.025077 -0.036856 0.024867 +v 0.026480 -0.035520 -0.012849 +v 0.027838 -0.034162 -0.015235 +v 0.027808 -0.034192 0.015078 +v 0.026355 -0.035645 0.012784 +v 0.023975 -0.038025 -0.013576 +v 0.027568 -0.034432 0.017839 +v 0.028091 -0.033909 0.023311 +v 0.024230 -0.037770 0.013378 +v 0.025856 -0.036144 0.019238 +v 0.019599 -0.040119 0.020584 +v 0.020548 -0.040143 -0.020822 +v 0.019294 -0.040043 -0.020585 +v 0.021010 -0.040066 0.020888 +v 0.021798 -0.039736 -0.021634 +v 0.015389 -0.038669 0.020976 +v 0.013546 -0.038120 -0.020964 +v 0.010187 -0.037355 0.020976 +v 0.005759 -0.036686 0.020931 +v 0.005767 -0.036676 -0.020989 +v -0.000280 -0.036424 0.020929 +v 0.000280 -0.036424 -0.020929 +v -0.005767 -0.036676 0.020989 +v -0.005759 -0.036687 -0.020931 +v -0.013545 -0.038120 0.020964 +v -0.010188 -0.037355 -0.020976 +v -0.015392 -0.038669 -0.020978 +v -0.019315 -0.040045 0.020610 +v -0.019599 -0.040119 -0.020584 +v 0.034531 -0.037369 0.015894 +v 0.026714 -0.045185 0.017501 +v 0.028283 -0.043617 0.020574 +v 0.030147 -0.041752 0.021490 +v 0.032131 -0.039768 0.021134 +v 0.033763 -0.038136 0.019137 +v 0.033184 -0.038715 0.011742 +v 0.028296 -0.043604 0.011376 +v 0.030634 -0.041265 0.010448 +v 0.026856 -0.045043 0.014100 +v 0.032848 -0.039052 0.015797 +v 0.032402 -0.039498 0.017935 +v 0.030689 -0.041210 0.019332 +v 0.028578 -0.043322 0.017839 +v 0.028338 -0.043562 0.015078 +v 0.029609 -0.042290 0.012937 +v 0.031954 -0.039946 0.013319 +v 0.034483 -0.037417 -0.015595 +v 0.026609 -0.045290 -0.016997 +v 0.027033 -0.044866 -0.013594 +v 0.028283 -0.043617 -0.011426 +v 0.030794 -0.041105 -0.010410 +v 0.033395 -0.038505 -0.012071 +v 0.034086 -0.037814 -0.018333 +v 0.028296 -0.043604 -0.020624 +v 0.030634 -0.041265 -0.021552 +v 0.032872 -0.039028 -0.020530 +v 0.032893 -0.039007 -0.015618 +v 0.031304 -0.040595 -0.012784 +v 0.028670 -0.043230 -0.013895 +v 0.028338 -0.043562 -0.016922 +v 0.029437 -0.042463 -0.018896 +v 0.031803 -0.040096 -0.018887 +v -0.021010 -0.040066 -0.020888 +v -0.020548 -0.040143 0.020822 +v -0.028440 -0.043460 0.014388 +v -0.028484 -0.043415 0.017451 +v -0.029809 -0.042090 0.019125 +v -0.031573 -0.040326 0.018918 +v -0.032757 -0.039142 0.017044 +v -0.032611 -0.039288 0.014549 +v -0.030898 -0.041002 0.012647 +v -0.031138 -0.040761 0.010399 +v -0.028283 -0.043617 0.011426 +v -0.026613 -0.045286 0.014885 +v -0.027314 -0.044585 0.019247 +v -0.029957 -0.041942 0.021601 +v -0.032872 -0.039028 0.020530 +v -0.034086 -0.037814 0.018333 +v -0.034483 -0.037417 0.015595 +v -0.033588 -0.038312 0.012463 +v -0.028248 -0.043652 -0.016203 +v -0.028925 -0.042975 -0.013576 +v -0.030806 -0.041094 -0.012762 +v -0.032656 -0.039244 -0.014388 +v -0.032534 -0.039366 -0.017722 +v -0.031088 -0.040811 -0.019168 +v -0.029142 -0.042758 -0.018681 +v -0.026856 -0.045043 -0.014100 +v -0.028296 -0.043604 -0.011376 +v -0.030634 -0.041265 -0.010448 +v -0.033184 -0.038715 -0.011742 +v -0.034531 -0.037369 -0.015894 +v -0.033588 -0.038312 -0.019537 +v -0.031477 -0.040423 -0.021445 +v -0.028553 -0.043346 -0.020885 +v -0.026714 -0.045185 -0.017501 +v 0.020424 -0.039891 0.021555 +v -0.007898 -0.033557 0.024481 +v -0.005268 -0.033226 -0.024499 +v 0.004021 -0.033036 -0.024696 +v 0.023117 -0.037487 -0.024864 +v 0.020262 -0.039881 -0.021509 +v -0.030752 -0.041147 -0.012750 +v -0.032130 -0.042032 -0.012647 +v -0.031815 -0.040084 -0.013228 +v -0.033990 -0.040172 -0.015124 +v -0.032951 -0.038949 -0.015614 +v -0.033589 -0.040573 -0.017938 +v -0.032124 -0.039776 -0.018467 +v -0.031829 -0.042334 -0.019377 +v -0.030191 -0.041709 -0.019346 +v -0.029844 -0.044319 -0.018121 +v -0.028273 -0.043626 -0.017161 +v -0.029369 -0.044793 -0.015119 +v -0.028762 -0.043137 -0.013747 +v -0.030587 -0.043575 -0.013082 +v -0.030532 -0.041368 -0.012696 +v -0.031676 -0.042487 -0.012738 +v -0.030523 -0.041377 -0.010998 +v -0.031671 -0.042492 -0.011008 +v -0.029844 -0.044318 -0.011699 +v -0.028618 -0.043282 -0.011783 +v -0.028434 -0.045729 -0.013958 +v -0.027346 -0.044553 -0.013878 +v -0.027029 -0.044871 -0.016865 +v -0.028171 -0.045991 -0.016451 +v -0.028742 -0.045420 -0.018825 +v -0.028281 -0.043619 -0.019903 +v -0.030577 -0.043585 -0.020804 +v -0.031000 -0.040900 -0.021078 +v -0.033061 -0.041101 -0.020657 +v -0.033426 -0.038473 -0.018989 +v -0.034669 -0.039494 -0.018670 +v -0.035209 -0.038953 -0.016277 +v -0.034109 -0.037791 -0.015086 +v -0.034792 -0.039371 -0.013579 +v -0.032641 -0.039259 -0.011941 +v -0.033546 -0.040616 -0.011776 +v -0.032013 -0.042150 -0.011020 +v -0.030864 -0.041036 -0.011028 +v -0.034154 -0.048494 -0.017443 +v -0.033516 -0.048989 -0.019777 +v -0.032467 -0.050045 -0.017441 +v -0.035922 -0.046726 -0.018887 +v -0.036736 -0.045751 -0.020840 +v -0.035128 -0.047368 -0.020885 +v -0.039344 -0.043154 -0.016728 +v -0.038507 -0.044005 -0.019362 +v -0.037690 -0.044958 -0.017443 +v -0.037688 -0.044809 -0.011733 +v -0.039078 -0.043428 -0.013861 +v -0.037690 -0.044958 -0.014557 +v -0.034154 -0.048494 -0.014557 +v -0.032389 -0.050098 -0.014912 +v -0.034471 -0.048042 -0.011396 +v -0.036153 -0.046342 -0.011030 +v -0.035922 -0.046726 -0.013113 +v -0.033102 -0.049394 -0.012863 +v -0.015703 -0.030172 -0.016532 +v -0.017959 -0.027918 -0.013526 +v -0.016437 -0.029435 -0.013909 +v -0.019268 -0.026600 -0.015028 +v -0.018659 -0.027202 -0.018151 +v -0.016817 -0.029060 -0.018333 +v -0.029436 -0.044633 -0.015425 +v -0.015682 -0.030887 -0.016302 +v -0.016597 -0.029972 -0.013456 +v -0.030532 -0.043537 -0.013251 +v -0.018614 -0.027962 -0.013089 +v -0.032011 -0.042057 -0.012949 +v -0.033043 -0.041032 -0.013623 +v -0.019838 -0.026742 -0.014685 +v -0.033835 -0.040234 -0.015478 +v -0.019944 -0.026632 -0.017029 +v -0.033331 -0.040738 -0.018051 +v -0.018651 -0.027924 -0.018891 +v -0.031613 -0.042456 -0.019159 +v -0.016812 -0.029764 -0.018688 +v -0.029909 -0.044160 -0.018010 +v -0.028456 -0.045809 -0.014229 +v -0.028198 -0.046072 -0.016366 +v -0.031603 -0.042666 -0.010991 +v -0.029447 -0.044820 -0.012118 +v -0.033365 -0.040903 -0.020492 +v -0.034942 -0.039328 -0.018128 +v -0.031345 -0.042919 -0.020950 +v -0.028673 -0.045592 -0.018427 +v -0.029671 -0.044599 -0.020077 +v -0.034558 -0.039709 -0.012913 +v -0.033102 -0.041163 -0.011436 +v -0.035242 -0.039022 -0.015636 +v -0.034154 -0.041423 -0.014557 +v -0.034154 -0.041423 -0.017443 +v -0.032386 -0.043190 -0.013113 +v -0.030618 -0.044958 -0.014557 +v -0.030618 -0.044958 -0.017443 +v -0.032386 -0.043190 -0.018887 +v 0.037690 -0.044958 -0.017443 +v 0.038486 -0.044019 -0.019340 +v 0.039210 -0.043272 -0.017434 +v 0.035922 -0.046726 -0.018887 +v 0.035286 -0.047210 -0.020957 +v 0.037064 -0.045443 -0.020681 +v 0.034154 -0.048494 -0.017443 +v 0.032619 -0.049877 -0.018017 +v 0.033586 -0.048912 -0.019842 +v 0.034237 -0.048276 -0.011552 +v 0.032738 -0.049752 -0.013536 +v 0.034154 -0.048494 -0.014557 +v 0.039354 -0.043159 -0.015272 +v 0.037690 -0.044958 -0.014557 +v 0.038686 -0.043810 -0.013039 +v 0.036149 -0.046348 -0.010999 +v 0.035922 -0.046726 -0.013113 +v 0.037679 -0.044819 -0.011755 +v 0.032339 -0.050177 -0.016000 +v 0.015705 -0.030172 -0.015702 +v 0.017243 -0.028608 -0.013307 +v 0.019303 -0.026565 -0.015167 +v 0.018800 -0.027072 -0.017891 +v 0.016679 -0.029182 -0.018396 +v 0.033829 -0.040240 -0.015425 +v 0.020041 -0.026538 -0.015760 +v 0.019428 -0.027151 -0.013858 +v 0.032733 -0.041336 -0.013251 +v 0.017906 -0.028670 -0.012913 +v 0.030851 -0.043218 -0.013041 +v 0.016373 -0.030206 -0.013822 +v 0.029624 -0.044442 -0.014695 +v 0.015678 -0.030890 -0.016243 +v 0.029540 -0.044529 -0.017106 +v 0.016777 -0.029799 -0.018660 +v 0.030361 -0.043717 -0.018499 +v 0.031652 -0.042417 -0.019159 +v 0.018245 -0.028337 -0.018987 +v 0.019545 -0.027030 -0.018006 +v 0.033356 -0.040713 -0.018010 +v 0.034673 -0.039600 -0.013251 +v 0.035264 -0.039000 -0.015634 +v 0.033128 -0.041139 -0.011351 +v 0.029488 -0.044777 -0.019811 +v 0.028396 -0.045871 -0.017804 +v 0.032367 -0.041898 -0.020876 +v 0.030836 -0.043433 -0.020849 +v 0.034924 -0.039348 -0.018115 +v 0.033795 -0.040475 -0.020077 +v 0.029253 -0.045014 -0.012364 +v 0.031091 -0.043174 -0.011103 +v 0.028293 -0.045972 -0.014917 +v 0.030618 -0.044958 -0.014557 +v 0.030618 -0.044958 -0.017443 +v 0.032386 -0.043190 -0.013113 +v 0.034154 -0.041423 -0.014557 +v 0.034154 -0.041423 -0.017443 +v 0.032386 -0.043190 -0.018887 +v 0.031903 -0.042259 -0.012726 +v 0.030882 -0.041018 -0.012649 +v 0.033422 -0.040741 -0.013728 +v 0.032593 -0.039307 -0.014361 +v 0.034023 -0.040139 -0.016257 +v 0.032807 -0.039092 -0.017012 +v 0.033155 -0.041008 -0.018623 +v 0.031680 -0.040220 -0.018887 +v 0.031178 -0.042985 -0.019276 +v 0.030104 -0.041795 -0.019265 +v 0.028442 -0.043457 -0.017608 +v 0.029750 -0.044412 -0.017858 +v 0.029339 -0.044823 -0.015467 +v 0.028306 -0.043594 -0.015153 +v 0.029077 -0.042822 -0.013406 +v 0.030374 -0.043788 -0.013235 +v 0.030527 -0.041373 -0.012710 +v 0.031676 -0.042486 -0.012730 +v 0.031654 -0.042508 -0.010998 +v 0.030517 -0.041383 -0.010966 +v 0.029749 -0.044413 -0.011783 +v 0.028110 -0.043790 -0.012266 +v 0.028159 -0.046004 -0.014814 +v 0.026983 -0.044916 -0.015680 +v 0.028536 -0.045626 -0.018291 +v 0.027452 -0.044448 -0.018375 +v 0.028932 -0.042967 -0.020540 +v 0.030015 -0.044147 -0.020469 +v 0.032663 -0.041499 -0.020888 +v 0.031589 -0.040311 -0.020831 +v 0.033330 -0.038569 -0.019085 +v 0.034865 -0.039297 -0.018351 +v 0.034080 -0.037820 -0.016535 +v 0.035173 -0.038989 -0.015370 +v 0.033660 -0.038239 -0.013579 +v 0.034229 -0.039933 -0.012368 +v 0.032270 -0.039629 -0.011633 +v 0.031995 -0.042167 -0.011028 +v 0.030858 -0.041041 -0.011050 +v -0.037838 -0.044669 0.020119 +v -0.039066 -0.043423 0.018137 +v -0.037690 -0.044958 0.017443 +v -0.034154 -0.048494 0.017443 +v -0.032686 -0.049810 0.018218 +v -0.033857 -0.048648 0.020150 +v -0.034083 -0.048424 0.011687 +v -0.033053 -0.049430 0.012957 +v -0.034154 -0.048494 0.014557 +v -0.032302 -0.050204 0.015390 +v -0.039331 -0.043181 0.014905 +v -0.037690 -0.044958 0.014557 +v -0.038296 -0.044190 0.012399 +v -0.035922 -0.046726 0.013113 +v -0.035721 -0.046784 0.010999 +v -0.037167 -0.045344 0.011399 +v -0.035922 -0.046726 0.018887 +v -0.035981 -0.046525 0.021037 +v -0.018959 -0.026916 0.014400 +v -0.019299 -0.026573 0.016742 +v -0.015769 -0.030107 0.015257 +v -0.017259 -0.028609 0.013388 +v -0.018112 -0.027763 0.018439 +v -0.016293 -0.029575 0.017974 +v -0.033835 -0.040234 0.016522 +v -0.019853 -0.026726 0.014733 +v -0.033331 -0.040738 0.013949 +v -0.018817 -0.027762 0.013242 +v -0.031613 -0.042456 0.012841 +v -0.017158 -0.029418 0.013089 +v -0.029909 -0.044160 0.013990 +v -0.016042 -0.030540 0.014466 +v -0.015732 -0.030843 0.016508 +v -0.029443 -0.044631 0.015997 +v -0.029934 -0.044135 0.018051 +v -0.016500 -0.030082 0.018306 +v -0.017866 -0.028710 0.019087 +v -0.031652 -0.042417 0.019159 +v -0.019253 -0.027328 0.018335 +v -0.033039 -0.041029 0.018374 +v -0.019969 -0.026610 0.016816 +v -0.035188 -0.039076 0.014911 +v -0.035043 -0.039226 0.017791 +v -0.032377 -0.041893 0.011071 +v -0.034193 -0.040077 0.012392 +v -0.029091 -0.045173 0.019344 +v -0.028226 -0.046043 0.016730 +v -0.032877 -0.041392 0.020744 +v -0.030836 -0.043433 0.020849 +v -0.034164 -0.040101 0.019570 +v -0.030099 -0.044169 0.011508 +v -0.028522 -0.045742 0.013873 +v -0.030618 -0.044958 0.014557 +v -0.030618 -0.044958 0.017443 +v -0.032386 -0.043190 0.013113 +v -0.034154 -0.041423 0.014557 +v -0.034154 -0.041423 0.017443 +v -0.032386 -0.043190 0.018887 +v 0.030752 -0.041147 0.012750 +v 0.031883 -0.042279 0.012743 +v 0.032074 -0.039826 0.013435 +v 0.033522 -0.040640 0.013786 +v 0.032918 -0.038982 0.016046 +v 0.033939 -0.040224 0.017012 +v 0.031916 -0.039983 0.018776 +v 0.032556 -0.041607 0.019114 +v 0.029758 -0.042142 0.019161 +v 0.030388 -0.043774 0.018849 +v 0.028391 -0.043509 0.017322 +v 0.029344 -0.044818 0.016387 +v 0.028472 -0.043428 0.014246 +v 0.030052 -0.044110 0.013470 +v 0.030495 -0.041405 0.012655 +v 0.031676 -0.042487 0.012738 +v 0.030543 -0.041356 0.011030 +v 0.031671 -0.042492 0.011008 +v 0.028930 -0.042969 0.011528 +v 0.029682 -0.044480 0.011813 +v 0.027411 -0.044488 0.013643 +v 0.028109 -0.046053 0.015158 +v 0.027021 -0.044879 0.016348 +v 0.028926 -0.045236 0.019267 +v 0.027675 -0.044224 0.018955 +v 0.029388 -0.042511 0.020748 +v 0.031110 -0.043053 0.020958 +v 0.031157 -0.040742 0.020906 +v 0.033723 -0.040439 0.020224 +v 0.032790 -0.039110 0.019896 +v 0.034138 -0.037761 0.016639 +v 0.035206 -0.038956 0.016793 +v 0.034792 -0.039371 0.013579 +v 0.033405 -0.038494 0.013016 +v 0.033546 -0.040616 0.011777 +v 0.031032 -0.040867 0.010919 +v 0.032013 -0.042150 0.011020 +v 0.034012 -0.048501 0.020270 +v 0.032903 -0.049579 0.018747 +v 0.034154 -0.048494 0.017443 +v 0.032355 -0.050158 0.016728 +v 0.035922 -0.046726 0.018887 +v 0.036814 -0.045682 0.020798 +v 0.035454 -0.047028 0.020948 +v 0.037690 -0.044958 0.017443 +v 0.039127 -0.043355 0.017778 +v 0.038309 -0.044204 0.019601 +v 0.037690 -0.044958 0.014557 +v 0.037635 -0.044870 0.011619 +v 0.039006 -0.043490 0.013782 +v 0.034154 -0.048494 0.014557 +v 0.032685 -0.049814 0.013637 +v 0.035638 -0.046857 0.011019 +v 0.035922 -0.046726 0.013113 +v 0.034169 -0.048337 0.011618 +v 0.039376 -0.043131 0.015888 +v 0.016521 -0.029356 0.018176 +v 0.017805 -0.028063 0.013388 +v 0.015697 -0.030154 0.015142 +v 0.019148 -0.026729 0.014867 +v 0.019470 -0.026621 0.017226 +v 0.018203 -0.027673 0.018392 +v 0.029436 -0.044633 0.015425 +v 0.015734 -0.030845 0.015760 +v 0.016467 -0.030108 0.013653 +v 0.030532 -0.043537 0.013251 +v 0.018058 -0.028522 0.012955 +v 0.032414 -0.041655 0.013041 +v 0.019402 -0.027177 0.013822 +v 0.033638 -0.040428 0.014695 +v 0.020038 -0.026542 0.015708 +v 0.033725 -0.040344 0.017106 +v 0.018817 -0.027762 0.018758 +v 0.032378 -0.041691 0.018977 +v 0.017158 -0.029418 0.018911 +v 0.030499 -0.043570 0.018722 +v 0.016042 -0.030540 0.017534 +v 0.029675 -0.044403 0.017344 +v 0.028796 -0.045477 0.013251 +v 0.028160 -0.046107 0.016000 +v 0.030110 -0.044154 0.011544 +v 0.034000 -0.040270 0.019853 +v 0.035218 -0.039050 0.017098 +v 0.030112 -0.044157 0.020458 +v 0.032117 -0.042147 0.020981 +v 0.028793 -0.045471 0.018748 +v 0.034000 -0.040270 0.012147 +v 0.032120 -0.042149 0.011018 +v 0.035019 -0.039245 0.014221 +v 0.034154 -0.041423 0.014557 +v 0.034154 -0.041423 0.017443 +v 0.032386 -0.043190 0.013113 +v 0.030618 -0.044958 0.014557 +v 0.030618 -0.044958 0.017443 +v 0.032386 -0.043190 0.018887 +v -0.031903 -0.042259 0.012726 +v -0.030752 -0.041147 0.012743 +v -0.032019 -0.039881 0.013407 +v -0.033184 -0.040979 0.013476 +v -0.034069 -0.040093 0.015832 +v -0.032962 -0.038937 0.016186 +v -0.032935 -0.041228 0.018923 +v -0.031814 -0.040085 0.018801 +v -0.030104 -0.041795 0.019265 +v -0.030471 -0.043691 0.018921 +v -0.028442 -0.043457 0.017608 +v -0.029357 -0.044805 0.016516 +v -0.028306 -0.043594 0.015153 +v -0.029743 -0.044420 0.014115 +v -0.029077 -0.042822 0.013406 +v -0.031553 -0.042610 0.012620 +v -0.030527 -0.041373 0.012710 +v -0.031654 -0.042508 0.010998 +v -0.030539 -0.041360 0.011008 +v -0.028231 -0.043668 0.012068 +v -0.030079 -0.044083 0.011562 +v -0.028400 -0.045762 0.013834 +v -0.026931 -0.044968 0.016194 +v -0.028464 -0.045698 0.018350 +v -0.028449 -0.043451 0.020169 +v -0.031033 -0.043129 0.021036 +v -0.031056 -0.040843 0.020972 +v -0.033630 -0.040532 0.020197 +v -0.033119 -0.038781 0.019506 +v -0.034799 -0.039363 0.018312 +v -0.034080 -0.037820 0.016535 +v -0.035230 -0.038932 0.015867 +v -0.033419 -0.038481 0.012884 +v -0.034537 -0.039626 0.013016 +v -0.032164 -0.041998 0.010919 +v -0.030939 -0.040961 0.010990 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn -0.1801 -0.9833 0.0261 +vn -0.1010 -0.9949 0.0018 +vn -0.0804 -0.9967 -0.0108 +vn -0.0747 -0.9970 0.0197 +vn -0.1796 -0.9837 -0.0126 +vn 0.0045 -0.9980 0.0629 +vn -0.0669 -0.9977 -0.0096 +vn 0.0026 -0.9832 0.1825 +vn -0.1552 -0.9588 0.2380 +vn 0.0944 -0.9776 0.1880 +vn 0.0688 -0.9976 -0.0032 +vn 0.0907 -0.9959 0.0035 +vn 0.1471 -0.9889 0.0207 +vn 0.0577 -0.9983 -0.0111 +vn 0.1814 -0.9833 -0.0152 +vn -0.0048 -0.9968 -0.0800 +vn 0.0750 -0.9972 0.0013 +vn -0.0157 -0.9839 -0.1782 +vn 0.1082 -0.9756 -0.1910 +vn -0.1034 -0.9818 -0.1594 +vn -0.0717 -0.9974 0.0065 +vn -0.2580 -0.9542 0.1514 +vn -0.2261 -0.9736 -0.0301 +vn -0.2017 -0.9793 0.0165 +vn -0.2351 -0.9700 0.0619 +vn -0.3375 -0.9413 0.0045 +vn -0.2074 -0.9530 -0.2209 +vn -0.2874 -0.9459 -0.1506 +vn 0.1234 -0.9923 0.0057 +vn 0.2245 -0.9733 0.0471 +vn 0.2596 -0.9489 -0.1793 +vn 0.1885 -0.9821 -0.0015 +vn 0.2346 -0.9709 -0.0490 +vn 0.2497 -0.9471 0.2015 +vn 0.2353 -0.9612 -0.1441 +vn 0.0975 -0.9851 0.1420 +vn 0.1248 -0.9796 -0.1577 +vn 0.0020 -0.9372 0.3487 +vn -0.1980 -0.9704 0.1384 +vn -0.0417 -0.9931 -0.1100 +vn -0.1341 -0.9777 0.1614 +vn -0.2373 -0.9622 -0.1335 +vn -0.0930 -0.9163 -0.3895 +vn -0.3855 -0.9227 -0.0028 +vn -0.5022 -0.8647 -0.0016 +vn -0.5410 -0.8410 0.0014 +vn -0.5636 -0.8261 -0.0003 +vn 0.1700 -0.8116 -0.5589 +vn 0.0261 -0.8277 -0.5605 +vn -0.1640 -0.8168 -0.5531 +vn 0.1091 -0.9151 -0.3881 +vn 0.1854 -0.9446 -0.2709 +vn 0.4767 -0.8789 -0.0139 +vn 0.4838 -0.8752 0.0011 +vn 0.4614 -0.8872 -0.0044 +vn 0.5751 -0.8181 -0.0006 +vn 0.0289 -0.9129 0.4071 +vn -0.0426 -0.8162 0.5762 +vn -0.1709 -0.8144 0.5546 +vn 0.2278 -0.7819 0.5803 +vn 0.2196 -0.9466 0.2361 +vn 0.1126 -0.8243 0.5549 +vn -0.9843 -0.1765 0.0105 +vn -0.9848 -0.1693 -0.0378 +vn -0.9682 -0.0981 -0.2302 +vn -0.9415 -0.3369 0.0012 +vn -0.9616 -0.2622 0.0811 +vn -0.9814 -0.1822 0.0601 +vn -0.9287 -0.0768 -0.3627 +vn -0.0004 -0.0006 1.0000 +vn -0.0010 -0.0017 1.0000 +vn 0.0033 -0.0073 1.0000 +vn 0.0034 -0.0058 1.0000 +vn -0.0631 -0.1283 0.9897 +vn 0.0032 -0.0109 0.9999 +vn -0.1716 -0.2516 0.9525 +vn 0.0004 -0.0004 1.0000 +vn -0.0071 -0.0032 1.0000 +vn -0.0002 -0.0064 1.0000 +vn 0.0933 -0.1634 0.9821 +vn 0.0131 -0.0102 0.9999 +vn 0.1411 -0.2389 0.9607 +vn 0.3047 -0.5104 0.8041 +vn 0.3600 -0.7057 0.6102 +vn 0.3546 -0.6349 0.6864 +vn 0.2071 -0.7121 0.6708 +vn 0.2763 -0.6961 0.6626 +vn 0.1445 -0.7994 0.5832 +vn 0.1490 -0.7661 0.6252 +vn -0.0940 0.0499 0.9943 +vn 0.0203 -0.3641 0.9311 +vn 0.1690 0.0241 0.9853 +vn -0.2425 -0.7072 0.6641 +vn -0.1795 -0.6595 0.7299 +vn -0.0619 -0.7907 0.6091 +vn -0.0436 -0.8102 0.5845 +vn -0.3702 -0.6954 0.6159 +vn -0.3902 -0.6967 0.6019 +vn -0.3071 -0.6974 0.6476 +vn -0.4252 -0.6845 0.5922 +vn -0.8191 -0.5431 0.1847 +vn -0.6963 -0.6934 0.1852 +vn -0.8168 -0.5659 0.1121 +vn -0.7176 -0.6938 0.0604 +vn -0.8502 -0.5265 0.0065 +vn -0.7159 -0.6947 -0.0698 +vn -0.8220 -0.5655 -0.0666 +vn -0.6974 -0.6923 -0.1855 +vn -0.8431 -0.5180 -0.1446 +vn -0.8478 -0.4935 -0.1940 +vn -0.8509 -0.0033 0.5254 +vn -0.7952 0.0045 0.6063 +vn -0.8367 0.0254 0.5470 +vn -0.9319 -0.0390 0.3607 +vn -0.8800 0.0168 0.4747 +vn -0.9633 0.0248 0.2672 +vn -0.9871 -0.0190 0.1591 +vn -0.9972 0.0286 0.0686 +vn -0.9983 -0.0102 -0.0574 +vn -0.9917 0.0152 -0.1274 +vn -0.9487 -0.0342 -0.3143 +vn -0.9729 0.0074 -0.2312 +vn -0.8699 0.0163 -0.4930 +vn -0.9018 0.0242 -0.4316 +vn -0.7851 0.0086 -0.6194 +vn -0.8368 0.0016 -0.5476 +vn -0.6787 0.0141 -0.7343 +vn -0.7177 0.0137 -0.6962 +vn -0.7499 -0.0078 -0.6615 +vn -0.7924 -0.0086 -0.6100 +vn -0.6070 -0.0383 -0.7938 +vn -0.4698 -0.0069 -0.8828 +vn -0.4533 -0.0077 -0.8913 +vn -0.2682 -0.0041 -0.9634 +vn -0.2590 -0.0018 -0.9659 +vn -0.0088 0.0033 -1.0000 +vn -0.0295 -0.0062 -0.9995 +vn 0.3239 -0.0889 -0.9419 +vn 0.1718 -0.3438 -0.9232 +vn 0.4394 -0.3236 -0.8380 +vn 0.5911 -0.0423 -0.8055 +vn 0.7889 0.0154 -0.6144 +vn 0.7031 0.0091 -0.7110 +vn 0.6751 0.0304 -0.7371 +vn 0.8397 -0.0091 -0.5429 +vn 0.7913 -0.0188 -0.6112 +vn 0.7427 -0.0163 -0.6694 +vn 0.9268 -0.0243 -0.3747 +vn 0.9003 0.0165 -0.4351 +vn 0.9255 -0.1001 -0.3654 +vn 0.9420 -0.0545 -0.3312 +vn 0.8597 0.0026 -0.5107 +vn 0.9748 0.0041 -0.2229 +vn 0.9807 0.0035 -0.1955 +vn 1.0000 0.0034 0.0075 +vn 1.0000 -0.0027 0.0076 +vn 0.9614 -0.0005 0.2751 +vn 0.9754 0.0067 0.2205 +vn 0.8721 0.0212 0.4889 +vn 0.9056 0.0185 0.4237 +vn 0.9375 -0.0759 0.3395 +vn 0.8298 0.0092 0.5581 +vn 0.9709 -0.0915 0.2211 +vn 0.7933 0.0004 0.6089 +vn 0.7589 0.0146 0.6511 +vn 0.6710 0.0219 0.7411 +vn 0.5947 -0.0232 0.8036 +vn 0.6965 0.0053 0.7176 +vn 0.7470 -0.0106 0.6647 +vn 0.5036 0.0657 0.8614 +vn 0.3710 -0.0185 0.9284 +vn 0.3047 -0.0107 0.9524 +vn 0.0538 -0.0647 0.9965 +vn -0.2152 -0.0147 0.9765 +vn -0.4678 -0.0762 0.8806 +vn -0.3272 0.0856 0.9411 +vn -0.5765 0.0110 0.8170 +vn -0.7127 0.0295 0.7009 +vn -0.6475 0.0397 0.7611 +vn -0.7526 0.0013 0.6585 +vn -0.6670 0.0030 0.7451 +vn -0.2265 -0.9740 -0.0015 +vn -0.2788 -0.9600 0.0274 +vn -0.2718 -0.9623 0.0105 +vn 0.2224 -0.9749 -0.0007 +vn 0.2775 -0.9596 0.0462 +vn 0.2818 -0.9570 0.0695 +vn 0.1744 -0.9846 0.0082 +vn 0.0778 -0.9969 0.0074 +vn 0.0993 -0.9951 -0.0025 +vn -0.0286 -0.9996 -0.0024 +vn -0.0827 -0.9965 0.0083 +vn -0.1598 -0.9871 0.0036 +vn -0.2438 -0.3690 0.8969 +vn -0.1762 -0.3313 0.9269 +vn -0.8079 -0.5893 0.0040 +vn -0.7446 -0.6675 -0.0025 +vn 0.0800 -0.5736 0.8152 +vn -0.1118 -0.5985 0.7933 +vn 0.0138 -0.5282 0.8490 +vn 0.1307 -0.6761 0.7251 +vn -0.0033 -0.5944 0.8041 +vn -0.3389 -0.6175 0.7098 +vn -0.3073 -0.5353 0.7868 +vn -0.5157 -0.5030 0.6935 +vn -0.5196 -0.5025 0.6910 +vn -0.0139 -0.3416 0.9397 +vn -0.1002 -0.3702 0.9235 +vn -0.0320 -0.1536 -0.9876 +vn 0.0002 0.0000 -1.0000 +vn -0.0073 -0.0082 -0.9999 +vn 0.1849 -0.3774 -0.9074 +vn 0.0985 -0.1784 -0.9790 +vn 0.0048 -0.0209 -0.9998 +vn 0.1574 -0.2571 -0.9535 +vn 0.0200 -0.1709 -0.9851 +vn -0.0003 -0.0001 -1.0000 +vn 0.0071 -0.0032 -1.0000 +vn 0.0428 -0.1450 -0.9885 +vn -0.0938 -0.1657 -0.9817 +vn -0.0148 -0.0105 -0.9998 +vn -0.1429 -0.2426 -0.9596 +vn -0.1471 -0.7320 -0.6652 +vn -0.2592 -0.6822 -0.6837 +vn -0.3316 -0.7061 -0.6256 +vn -0.3560 -0.6238 -0.6958 +vn -0.2999 -0.5044 -0.8097 +vn -0.0034 -0.7053 -0.7089 +vn -0.0227 -0.7066 -0.7072 +vn 0.2186 -0.6820 -0.6979 +vn 0.3530 -0.6453 -0.6774 +vn 0.3152 -0.5146 -0.7974 +vn 0.2273 -0.9738 0.0033 +vn 0.2787 -0.9600 -0.0268 +vn 0.2716 -0.9624 -0.0088 +vn -0.2228 -0.9747 0.0191 +vn -0.2672 -0.9636 -0.0070 +vn -0.2783 -0.9599 -0.0330 +vn -0.1223 -0.9925 0.0042 +vn -0.0757 -0.9971 -0.0085 +vn 0.0121 -0.9999 0.0055 +vn 0.0795 -0.9968 -0.0075 +vn 0.1470 -0.9891 -0.0029 +vn -0.0750 -0.5727 -0.8163 +vn 0.1394 -0.5713 -0.8088 +vn 0.0394 -0.5450 -0.8375 +vn -0.0474 -0.5714 -0.8193 +vn -0.0197 -0.5986 -0.8008 +vn -0.4111 -0.5768 -0.7059 +vn -0.4719 -0.5216 -0.7108 +vn -0.4992 -0.5013 -0.7067 +vn -0.4987 -0.5013 -0.7071 +vn 0.9851 -0.1695 -0.0277 +vn 0.9846 -0.1746 0.0093 +vn 0.9787 -0.2052 -0.0034 +vn 0.9855 -0.1593 0.0591 +vn 0.7095 -0.6906 -0.1404 +vn 0.8312 -0.5352 -0.1508 +vn 0.7490 -0.6246 -0.2212 +vn 0.8388 -0.5436 -0.0298 +vn 0.7216 -0.6923 0.0042 +vn 0.8388 -0.5393 0.0750 +vn 0.6996 -0.6946 0.1675 +vn 0.8153 -0.5597 0.1486 +vn 0.8659 -0.4717 0.1664 +vn 0.8135 -0.5816 -0.0049 +vn 0.7934 -0.6087 0.0033 +vn 0.3680 -0.6018 0.7088 +vn 0.4735 -0.5220 0.7094 +vn 0.4988 -0.5053 0.7041 +vn 0.4996 -0.5006 0.7070 +vn 0.4150 -0.5766 -0.7037 +vn 0.5055 -0.5001 -0.7031 +vn 0.5064 -0.4918 -0.7083 +vn -0.0000 1.0000 -0.0000 +vn -0.0000 1.0000 -0.0002 +vn 0.0001 1.0000 -0.0007 +vn -0.0000 1.0000 -0.0003 +vn -0.0000 1.0000 0.0003 +vn -0.0000 1.0000 0.0002 +vn 0.0000 1.0000 -0.0001 +vn 0.0000 1.0000 0.0001 +vn -0.7053 -0.7083 0.0288 +vn 0.7054 -0.7085 0.0205 +vn 0.6991 -0.7140 -0.0385 +vn 0.0000 0.0000 -1.0000 +vn 0.0025 0.0013 -1.0000 +vn 0.1018 0.0857 -0.9911 +vn 0.0096 0.2624 -0.9649 +vn 0.0012 0.0340 -0.9994 +vn 0.0497 0.2362 -0.9704 +vn -0.0318 0.0325 -0.9990 +vn 0.0000 0.0005 -1.0000 +vn -0.0208 0.0410 -0.9989 +vn 0.0227 -0.0127 -0.9997 +vn -0.0329 0.0392 -0.9987 +vn 0.0000 0.0000 1.0000 +vn 0.0001 0.0020 1.0000 +vn 0.0617 0.0624 0.9961 +vn -0.0287 -0.0319 0.9991 +vn -0.0008 0.0047 1.0000 +vn -0.0002 0.0020 1.0000 +vn -0.0866 -0.1151 0.9896 +vn 0.0060 0.0105 0.9999 +vn 0.0011 0.0067 1.0000 +vn -0.0033 0.0076 1.0000 +vn 0.0508 -0.0604 0.9969 +vn -0.0714 0.0694 0.9950 +vn 0.1458 -0.1908 0.9707 +vn 0.7071 0.7071 0.0000 +vn 0.6933 0.7205 0.0134 +vn 0.6703 0.7421 0.0024 +vn 0.7062 0.7080 -0.0005 +vn 0.5522 0.8257 -0.1151 +vn 0.7003 0.7135 0.0190 +vn 0.6952 0.7180 0.0337 +vn 0.4423 0.8715 0.2119 +vn 0.7002 0.7136 0.0207 +vn 0.7051 0.7091 -0.0029 +vn 0.7017 0.7125 -0.0053 +vn 0.6770 0.7360 0.0013 +vn 0.6103 0.7799 -0.1387 +vn 0.7050 0.7092 -0.0047 +vn -0.8337 0.5422 0.1048 +vn -0.9612 0.2759 0.0000 +vn -0.8845 0.4567 -0.0958 +vn -0.9187 0.3941 -0.0250 +vn -0.9829 0.1840 0.0015 +vn -0.9812 0.1932 -0.0007 +vn -0.9185 0.3947 -0.0242 +vn -0.9613 0.2756 -0.0006 +vn -0.9612 0.2760 0.0000 +vn -0.8853 0.4649 -0.0028 +vn -0.8848 0.4561 -0.0956 +vn -0.9612 0.2759 0.0004 +vn -0.9613 0.2754 0.0010 +vn -0.9612 0.2758 -0.0005 +vn -0.9612 0.2760 0.0002 +vn -0.9612 0.2759 -0.0001 +vn -0.9611 0.2762 0.0000 +vn -0.9612 0.2759 -0.0003 +vn -0.6572 0.6973 0.2862 +vn -0.7106 0.7036 -0.0058 +vn 0.2314 0.8463 -0.4798 +vn 0.2576 0.9209 -0.2926 +vn -0.1214 0.8492 -0.5139 +vn -0.0702 0.8686 0.4905 +vn -0.0548 0.7788 0.6248 +vn 0.0864 0.8322 0.5477 +vn 0.8868 0.4621 0.0027 +vn 0.8337 0.5422 -0.1047 +vn 0.7106 0.7036 0.0058 +vn 0.6573 0.6972 -0.2861 +vn 0.9614 0.2752 -0.0006 +vn 0.9614 0.2752 -0.0001 +vn 0.9830 0.1839 -0.0015 +vn 0.9812 0.1930 0.0007 +vn 0.8848 0.4561 0.0957 +vn 0.9185 0.3947 0.0242 +vn 0.9612 0.2759 -0.0000 +vn 0.9612 0.2758 0.0001 +vn 0.9613 0.2754 -0.0010 +vn 0.9612 0.2759 -0.0001 +vn 0.9612 0.2758 -0.0003 +vn 0.9613 0.2756 0.0005 +vn 0.9612 0.2759 -0.0002 +vn 0.9612 0.2758 -0.0002 +vn 0.9612 0.2760 -0.0000 +vn 0.9612 0.2758 0.0000 +vn -0.0106 -0.9999 -0.0018 +vn -0.1995 -0.9799 0.0015 +vn -0.2180 -0.9759 -0.0016 +vn -0.4019 -0.9157 0.0015 +vn -0.4190 -0.9080 -0.0015 +vn -0.5852 -0.8109 0.0015 +vn -0.6002 -0.7998 -0.0015 +vn -0.7423 -0.6700 0.0015 +vn -0.7547 -0.6560 -0.0015 +vn -0.8664 -0.4993 0.0015 +vn -0.8756 -0.4830 -0.0015 +vn -0.9543 -0.2989 0.0017 +vn -0.9602 -0.2793 -0.0021 +vn -0.9987 -0.0505 0.0022 +vn -0.9996 -0.0282 -0.0019 +vn 0.0100 -0.9999 0.0015 +vn 0.1988 -0.9800 -0.0018 +vn 0.2185 -0.9758 0.0015 +vn 0.4019 -0.9157 -0.0015 +vn 0.4190 -0.9080 0.0015 +vn 0.5851 -0.8109 -0.0015 +vn 0.6002 -0.7998 0.0015 +vn 0.7423 -0.6701 -0.0015 +vn 0.7548 -0.6560 0.0015 +vn 0.8664 -0.4993 -0.0015 +vn 0.8756 -0.4830 0.0015 +vn 0.9543 -0.2989 -0.0017 +vn 0.9602 -0.2794 0.0021 +vn 0.9987 -0.0505 -0.0022 +vn 0.9996 -0.0283 0.0019 +vn -0.6937 0.7202 -0.0073 +vn -0.6718 0.7407 0.0008 +vn -0.4354 0.8747 -0.2130 +vn -0.5497 0.8275 0.1145 +vn -0.7010 0.7132 0.0075 +vn -0.6051 0.7827 0.1458 +vn -0.6784 0.7347 0.0011 +vn -0.7053 0.7089 0.0046 +vn -0.7049 0.7093 0.0030 +vn -0.7071 0.7071 0.0000 +vn -0.7004 0.7137 -0.0084 +vn -0.7044 0.7098 -0.0011 +vn -0.7040 0.7102 -0.0034 +vn -0.7050 0.7092 -0.0048 +vn 0.1710 0.9697 -0.1744 +vn -0.0737 0.9856 0.1524 +vn 0.2185 0.9578 0.1865 +vn -0.1784 0.9709 -0.1594 +vn -0.2564 0.9205 0.2950 +vn 0.2707 0.8911 -0.3642 +vn 0.2316 0.8998 0.3697 +vn 0.1951 0.9808 -0.0023 +vn 0.0987 0.9951 -0.0025 +vn 0.1145 0.9934 0.0004 +vn -0.0017 1.0000 -0.0002 +vn 0.0016 1.0000 0.0002 +vn -0.1145 0.9934 -0.0004 +vn -0.0986 0.9951 0.0025 +vn -0.2323 0.9003 -0.3680 +vn -0.1952 0.9808 0.0023 +vn -0.2707 0.8906 0.3654 +vn -0.2176 0.9567 -0.1936 +vn -0.1711 0.9697 0.1743 +vn -0.7733 -0.6294 -0.0762 +vn -0.6651 -0.6610 -0.3476 +vn -0.7040 -0.6849 -0.1876 +vn 0.5882 0.5721 -0.5716 +vn 0.6196 0.6297 -0.4686 +vn 0.6224 0.6353 -0.4571 +vn 0.5831 0.5635 -0.5852 +vn 0.2399 0.2608 -0.9351 +vn 0.2302 0.2417 -0.9427 +vn 0.1503 0.1724 -0.9735 +vn 0.0854 0.0745 -0.9936 +vn -0.2700 -0.2977 -0.9157 +vn -0.4402 -0.4018 -0.8030 +vn -0.5535 -0.6127 -0.5641 +vn -0.5999 -0.6581 0.4549 +vn -0.5807 -0.6852 0.4396 +vn -0.5479 -0.7272 0.4135 +vn 0.2127 0.2003 0.9564 +vn 0.2589 0.2830 0.9235 +vn 0.2530 0.2723 0.9284 +vn 0.2015 0.1806 0.9627 +vn -0.2382 -0.2394 0.9412 +vn -0.2662 -0.2525 0.9303 +vn -0.2540 -0.2468 0.9352 +vn -0.3068 -0.2711 0.9124 +vn -0.6207 -0.6264 0.4715 +vn 0.6700 0.6590 0.3417 +vn 0.6049 0.6081 0.5141 +vn 0.5741 0.5587 0.5986 +vn 0.7099 0.7018 0.0589 +vn -0.6799 -0.7231 -0.1220 +vn -0.6904 -0.6803 -0.2461 +vn -0.6837 -0.7134 -0.1537 +vn -0.6912 -0.6649 -0.2829 +vn -0.3537 -0.3536 -0.8659 +vn -0.3532 -0.3534 -0.8662 +vn -0.3534 -0.3535 -0.8661 +vn -0.3539 -0.3537 -0.8658 +vn 0.2424 0.2137 -0.9463 +vn 0.2783 0.3090 -0.9094 +vn 0.2563 0.2500 -0.9337 +vn 0.2903 0.3417 -0.8938 +vn 0.7082 0.6755 -0.2056 +vn 0.6994 0.7001 -0.1441 +vn 0.7057 0.6838 -0.1857 +vn 0.6956 0.7079 -0.1223 +vn 0.5944 0.5839 0.5529 +vn 0.5374 0.5649 0.6261 +vn 0.5783 0.5789 0.5749 +vn 0.5230 0.5596 0.6429 +vn 0.1687 0.1052 0.9800 +vn -0.0499 -0.0014 0.9988 +vn 0.0903 0.0671 0.9937 +vn -0.1238 -0.0378 0.9916 +vn -0.4932 -0.5591 0.6665 +vn -0.6156 -0.5998 0.5111 +vn -0.5331 -0.5742 0.6214 +vn -0.6512 -0.6081 0.4540 +vn 0.7072 -0.7071 0.0002 +vn 0.7073 -0.7070 0.0003 +vn 0.7071 -0.7071 0.0001 +vn 0.7072 -0.7070 0.0000 +vn 0.7072 -0.7071 0.0000 +vn 0.7070 -0.7072 0.0000 +vn 0.7069 -0.7073 -0.0000 +vn 0.7069 -0.7073 -0.0002 +vn 0.7070 -0.7072 -0.0001 +vn 0.7071 -0.7071 0.0000 +vn 0.7072 -0.7070 0.0003 +vn 0.7071 -0.7071 -0.0001 +vn 0.7072 -0.7070 -0.0002 +vn -0.7005 -0.6806 0.2149 +vn -0.6514 -0.6653 -0.3648 +vn -0.6757 -0.7295 -0.1061 +vn 0.6950 0.7083 -0.1233 +vn 0.7015 0.6836 0.2017 +vn 0.6505 0.6351 -0.4164 +vn 0.6184 0.6303 -0.4693 +vn 0.5559 0.5403 -0.6318 +vn 0.2102 0.2028 -0.9564 +vn 0.2355 0.2521 -0.9386 +vn 0.2020 0.1869 -0.9614 +vn -0.2916 -0.2898 -0.9116 +vn -0.2921 -0.2900 -0.9114 +vn -0.2918 -0.2899 -0.9115 +vn -0.2904 -0.2893 -0.9121 +vn -0.6035 -0.6583 -0.4500 +vn -0.6255 -0.6057 -0.4919 +vn -0.6192 -0.6527 0.4367 +vn 0.2124 0.1999 0.9565 +vn 0.2589 0.2829 0.9236 +vn 0.2529 0.2722 0.9284 +vn -0.2162 -0.2185 0.9516 +vn -0.2698 -0.2462 0.9309 +vn -0.3910 -0.4070 0.8255 +vn -0.4229 -0.3799 0.8227 +vn 0.6133 0.6065 0.5059 +vn 0.6006 0.5809 0.5494 +vn 0.6822 0.6911 0.2386 +vn -0.5633 -0.5382 -0.6269 +vn -0.5639 -0.5425 -0.6227 +vn -0.5635 -0.5400 -0.6252 +vn -0.5640 -0.5441 -0.6211 +vn 0.1522 0.1321 -0.9795 +vn 0.1728 0.1954 -0.9654 +vn 0.1617 0.1611 -0.9736 +vn 0.1815 0.2224 -0.9579 +vn 0.6953 0.6465 -0.3140 +vn 0.6849 0.7020 -0.1953 +vn 0.6931 0.6670 -0.2733 +vn 0.6785 0.7185 -0.1532 +vn 0.6127 0.5892 0.5267 +vn 0.5592 0.5726 0.5995 +vn 0.5986 0.5851 0.5470 +vn 0.5438 0.5672 0.6185 +vn 0.2161 0.1837 0.9589 +vn 0.0104 0.0635 0.9979 +vn -0.0383 -0.0772 0.9963 +vn -0.0948 -0.0552 0.9940 +vn -0.2813 -0.3597 0.8897 +vn -0.6823 -0.6875 0.2485 +vn -0.6824 -0.5944 0.4255 +vn -0.6854 -0.6281 0.3684 +vn -0.6745 -0.7175 0.1739 +vn 0.7069 -0.7073 -0.0001 +vn 0.7072 -0.7071 -0.0001 +vn 0.7069 -0.7073 0.0002 +vn 0.1772 0.9710 0.1604 +vn 0.0733 0.9853 -0.1546 +vn -0.6854 0.6680 -0.2897 +vn -0.6714 0.7408 -0.0205 +vn -0.6160 0.6649 -0.4224 +vn -0.5327 0.4932 -0.6877 +vn -0.2057 0.2450 -0.9474 +vn -0.0302 -0.0138 -0.9994 +vn 0.3351 -0.2938 -0.8952 +vn 0.5035 -0.5530 -0.6638 +vn 0.6912 -0.6493 -0.3171 +vn 0.6749 -0.7226 0.1497 +vn 0.6478 -0.5985 0.4713 +vn 0.5465 -0.5681 0.6153 +vn 0.4694 -0.4028 0.7858 +vn -0.0120 -0.0847 0.9963 +vn -0.2540 0.3769 0.8907 +vn -0.6598 0.5599 0.5011 +vn -0.7071 -0.7071 -0.0001 +vn -0.7071 -0.7071 -0.0003 +vn -0.7070 -0.7072 0.0001 +vn -0.7071 -0.7071 0.0000 +vn -0.7070 -0.7072 -0.0002 +vn -0.7069 -0.7073 -0.0002 +vn -0.7069 -0.7073 -0.0001 +vn -0.7069 -0.7073 0.0000 +vn -0.7070 -0.7072 0.0002 +vn 0.7005 -0.6805 -0.2148 +vn 0.6634 -0.6588 0.3547 +vn 0.6805 -0.7263 0.0969 +vn -0.5986 0.5807 0.5518 +vn -0.6222 0.6289 0.4661 +vn -0.6246 0.6343 0.4555 +vn -0.5947 0.5733 0.5637 +vn -0.2399 0.2608 0.9351 +vn -0.1994 0.1819 0.9629 +vn -0.2332 0.2477 0.9404 +vn -0.1882 0.1603 0.9690 +vn 0.3268 -0.2964 0.8974 +vn 0.3316 -0.3498 0.8762 +vn 0.3293 -0.3224 0.8875 +vn 0.3344 -0.3890 0.8584 +vn 0.6173 -0.6585 0.4305 +vn 0.6363 -0.6015 0.4831 +vn 0.6193 -0.6524 -0.4368 +vn -0.5873 0.5664 -0.5781 +vn -0.5551 0.5677 -0.6079 +vn -0.3688 0.3552 -0.8590 +vn -0.2587 0.2830 -0.9236 +vn 0.1643 -0.1913 -0.9677 +vn 0.2332 -0.2273 -0.9455 +vn 0.3717 -0.3983 -0.8386 +vn 0.4229 -0.3799 -0.8227 +vn -0.7009 0.6811 -0.2120 +vn -0.6476 0.6211 -0.4414 +vn -0.6475 0.6808 -0.3423 +vn -0.6485 0.6614 -0.3768 +vn -0.6458 0.6004 -0.4717 +vn -0.1245 0.1496 -0.9809 +vn -0.2021 0.1750 -0.9636 +vn -0.1506 0.1582 -0.9759 +vn -0.2298 0.1838 -0.9557 +vn 0.4732 -0.5081 -0.7196 +vn 0.4083 -0.3374 -0.8482 +vn 0.4333 -0.3982 -0.8085 +vn 0.4904 -0.5616 -0.6664 +vn 0.7244 -0.6785 0.1219 +vn 0.7098 -0.7010 0.0690 +vn 0.7192 -0.6873 0.1020 +vn 0.7045 -0.7078 0.0517 +vn 0.3759 -0.3832 0.8437 +vn 0.4166 -0.4000 0.8163 +vn 0.4053 -0.3954 0.8243 +vn 0.3640 -0.3783 0.8511 +vn -0.0852 0.0888 0.9924 +vn -0.1043 0.1274 0.9863 +vn -0.0909 0.1003 0.9908 +vn -0.1091 0.1372 0.9845 +vn -0.6165 0.5694 0.5438 +vn -0.6217 0.6189 0.4800 +vn -0.6187 0.5865 0.5228 +vn -0.6226 0.6370 0.4545 +vn -0.7070 -0.7072 -0.0000 +vn -0.7072 -0.7070 0.0002 +vn -0.7072 -0.7070 0.0003 +vn -0.7071 -0.7071 0.0001 +vn -0.7070 -0.7072 -0.0001 +vn -0.7072 -0.7071 0.0002 +vn -0.7071 -0.7071 0.0002 +vn 0.7733 -0.6294 0.0762 +vn 0.6523 -0.6700 0.3544 +vn 0.6952 -0.6904 0.2001 +vn -0.5800 0.5582 0.5933 +vn -0.6186 0.6278 0.4725 +vn -0.6224 0.6353 0.4571 +vn -0.5736 0.5475 0.6093 +vn -0.2229 0.2570 0.9404 +vn -0.1391 0.1096 0.9842 +vn -0.2096 0.2333 0.9496 +vn -0.1176 0.0721 0.9904 +vn 0.3399 -0.2990 0.8917 +vn 0.3501 -0.3634 0.8633 +vn 0.4165 -0.3942 0.8193 +vn 0.5137 -0.5726 0.6389 +vn 0.5998 -0.6583 -0.4548 +vn 0.5807 -0.6853 -0.4395 +vn 0.5479 -0.7272 -0.4135 +vn -0.2127 0.2003 -0.9564 +vn -0.2589 0.2829 -0.9236 +vn -0.2529 0.2722 -0.9284 +vn -0.2015 0.1806 -0.9627 +vn 0.2382 -0.2394 -0.9412 +vn 0.2661 -0.2524 -0.9303 +vn 0.2540 -0.2468 -0.9352 +vn 0.3065 -0.2709 -0.9125 +vn 0.6206 -0.6266 -0.4714 +vn -0.6701 0.6590 -0.3417 +vn -0.6049 0.6080 -0.5141 +vn -0.5741 0.5587 -0.5986 +vn -0.7099 0.7018 -0.0589 +vn -0.0612 0.7904 -0.6095 +vn 0.1001 0.7599 -0.6422 +vn 0.0705 0.8690 -0.4898 +vn 0.1877 0.7129 -0.6757 +vn 0.1432 0.7246 -0.6741 +vn 0.0884 0.7405 -0.6662 +vn 0.0730 0.7393 -0.6694 +vn -0.0038 0.7398 -0.6729 +vn -0.0009 0.7383 -0.6745 +vn -0.1097 0.7075 -0.6982 +vn -0.0817 0.7226 -0.6864 +vn -0.1861 0.7069 -0.6824 +vn -0.1063 0.7792 0.6177 +vn -0.1891 0.7106 0.6777 +vn -0.1450 0.7207 0.6779 +vn -0.0556 0.7255 0.6860 +vn -0.0685 0.7267 0.6836 +vn 0.0522 0.7364 0.6745 +vn -0.0111 0.7489 0.6626 +vn 0.0933 0.7292 0.6779 +vn 0.1781 0.7150 0.6760 +vn -0.0880 0.8173 0.5695 +vn 0.1239 0.8497 0.5126 +vn -0.1124 0.7967 -0.5938 +vn -0.0034 0.7911 0.6116 +vn 0.1035 0.6754 -0.7302 +vn 0.0063 0.6103 -0.7921 +vn -0.2455 0.8518 -0.4628 +vn -0.3484 0.8498 -0.3955 +vn -0.1902 0.5852 -0.7883 +vn 0.1431 0.1504 -0.9782 +vn 0.4171 0.4542 -0.7872 +vn 0.5240 0.4921 -0.6951 +vn 0.4190 0.4373 0.7958 +vn 0.5620 0.5901 0.5796 +vn 0.5610 0.5930 0.5776 +vn 0.4406 0.4191 0.7939 +vn 0.1314 0.1411 0.9812 +vn -0.5690 0.5697 -0.5930 +vn -0.5610 0.5930 -0.5776 +vn -0.5682 0.5721 -0.5914 +vn -0.5735 0.5556 -0.6019 +vn -0.2026 0.1996 -0.9587 +vn -0.2191 0.2351 -0.9469 +vn -0.1258 0.1346 0.9829 +vn -0.4182 0.4531 0.7873 +vn -0.5223 0.4876 0.6996 +vn 0.1232 -0.3019 -0.9453 +vn 0.6082 -0.4119 -0.6786 +vn 0.6311 -0.3136 -0.7094 +vn 0.5592 -0.5552 -0.6157 +vn 0.5107 -0.6563 -0.5554 +vn 0.7168 -0.6484 0.2563 +vn 0.7847 -0.5882 0.1956 +vn 0.6239 -0.7106 0.3253 +vn 0.5438 -0.7506 0.3752 +vn 0.3418 -0.2800 0.8971 +vn 0.4476 -0.2535 0.8576 +vn 0.2187 -0.3046 0.9270 +vn 0.1053 -0.3225 0.9407 +vn -0.3038 0.3714 0.8774 +vn -0.1697 0.4001 0.9006 +vn -0.4823 0.3188 0.8159 +vn -0.5873 0.2786 0.7599 +vn -0.4998 0.8398 0.2117 +vn -0.8600 0.4731 -0.1910 +vn -0.3910 0.6679 -0.6332 +vn -0.3730 0.1689 -0.9123 +vn -0.2881 0.1723 -0.9420 +vn -0.2575 0.1727 -0.9507 +vn -0.1348 0.1742 -0.9754 +vn -0.6965 0.7175 0.0075 +vn -0.6981 0.7160 0.0057 +vn -0.6980 0.7161 0.0059 +vn -0.6991 0.7150 0.0042 +vn 0.1899 -0.1859 0.9640 +vn 0.1758 -0.1897 0.9660 +vn 0.2035 -0.1823 0.9620 +vn 0.2168 -0.1787 0.9597 +vn 0.5174 -0.5464 0.6585 +vn 0.5099 -0.5498 0.6616 +vn 0.5262 -0.5425 0.6549 +vn 0.5344 -0.5387 0.6513 +vn 0.7208 -0.6770 0.1486 +vn 0.7203 -0.6776 0.1482 +vn 0.7073 -0.6868 -0.1676 +vn 0.6896 -0.7223 -0.0520 +vn 0.6026 -0.5708 -0.5578 +vn 0.4630 -0.5395 -0.7033 +vn 0.2992 -0.5453 -0.7830 +vn 0.3646 -0.0375 -0.9304 +vn -0.1864 -0.1288 -0.9740 +vn -0.2195 0.5008 -0.8373 +vn -0.2956 0.4823 -0.8246 +vn -0.4358 0.4383 -0.7861 +vn -0.5244 0.4031 -0.7500 +vn -0.6219 0.7315 -0.2794 +vn -0.6501 0.6964 -0.3041 +vn -0.5914 0.7656 -0.2533 +vn -0.5723 0.7850 -0.2373 +vn -0.7002 0.6275 0.3406 +vn -0.8084 0.5499 0.2101 +vn -0.5801 0.6387 0.5055 +vn -0.4052 0.4377 0.8026 +vn -0.3690 0.3508 0.8607 +vn -0.2261 0.2507 0.9413 +vn -0.2344 0.2485 0.9398 +vn 0.5429 -0.8350 0.0891 +vn 0.6233 -0.7820 -0.0063 +vn 0.6196 -0.7849 -0.0017 +vn 0.6924 -0.7144 -0.1016 +vn 0.7070 0.7072 0.0004 +vn 0.7069 0.7073 0.0002 +vn 0.7071 0.7071 0.0002 +vn 0.7072 0.7070 0.0001 +vn 0.7073 0.7069 -0.0002 +vn 0.7074 0.7068 -0.0002 +vn 0.7071 0.7071 0.0003 +vn 0.7071 0.7071 0.0001 +vn 0.7073 0.7069 0.0001 +vn 0.7073 0.7069 0.0002 +vn 0.7072 0.7071 -0.0002 +vn 0.7071 0.7071 -0.0001 +vn 0.7072 0.7071 0.0000 +vn -0.7072 -0.7070 -0.0001 +vn -0.7074 -0.7068 -0.0002 +vn -0.7069 -0.7074 -0.0002 +vn -0.7072 -0.7071 -0.0003 +vn -0.7072 -0.7071 -0.0002 +vn -0.7069 -0.7073 0.0003 +vn -0.7072 -0.7070 -0.0002 +vn -0.7068 -0.7074 -0.0002 +vn -0.6818 -0.7313 -0.0204 +vn -0.6869 -0.7259 -0.0358 +vn -0.6755 -0.7373 -0.0097 +vn -0.7069 -0.7059 -0.0446 +vn -0.7158 -0.6965 -0.0494 +vn -0.6995 -0.7130 -0.0489 +vn -0.7390 -0.6737 -0.0049 +vn -0.7288 -0.6840 -0.0316 +vn -0.7322 -0.6808 -0.0197 +vn -0.7232 -0.6894 0.0404 +vn -0.7362 -0.6765 0.0189 +vn -0.7323 -0.6806 0.0212 +vn -0.6789 -0.7340 0.0207 +vn -0.6713 -0.7411 0.0113 +vn -0.6937 -0.7191 0.0405 +vn -0.7111 -0.7013 0.0501 +vn -0.7078 -0.7052 0.0420 +vn -0.6772 -0.7352 0.0299 +vn 0.7081 0.7061 -0.0002 +vn 0.7076 0.7066 0.0013 +vn 0.7059 0.7083 -0.0014 +vn 0.6355 0.7717 -0.0248 +vn 0.6213 0.7829 -0.0310 +vn 0.7099 0.7043 -0.0040 +vn 0.5817 -0.5853 0.5649 +vn 0.6566 -0.6306 0.4138 +vn 0.6503 -0.6271 0.4288 +vn 0.5723 -0.5792 0.5805 +vn 0.1075 -0.0926 0.9899 +vn 0.0966 -0.0842 0.9918 +vn 0.0974 -0.0848 0.9916 +vn 0.1086 -0.0934 0.9897 +vn -0.3002 0.2944 0.9073 +vn -0.4626 0.4802 0.7452 +vn -0.4744 0.4683 0.7454 +vn -0.6274 0.6484 0.4312 +vn -0.7059 0.6946 0.1389 +vn -0.6227 0.6830 -0.3817 +vn -0.5455 0.5301 -0.6492 +vn -0.2465 0.3335 -0.9100 +vn -0.0017 -0.0137 -0.9999 +vn 0.0877 -0.0655 -0.9940 +vn 0.2964 -0.3122 -0.9026 +vn 0.6727 -0.6851 -0.2794 +vn 0.6020 -0.5739 -0.5552 +vn 0.6110 -0.5865 -0.5317 +vn 0.6763 -0.6927 -0.2505 +vn 0.7530 0.6579 0.0128 +vn 0.7532 0.6572 0.0291 +vn 0.7563 0.6542 -0.0077 +vn 0.7429 0.6680 -0.0434 +vn 0.7305 0.6801 0.0622 +vn 0.7088 0.7014 0.0753 +vn 0.7383 0.6722 0.0552 +vn 0.6669 0.7438 -0.0456 +vn 0.6811 0.7293 -0.0650 +vn 0.6577 0.7526 -0.0311 +vn 0.6565 0.7543 0.0102 +vn 0.7063 0.7045 -0.0691 +vn 0.7119 0.6983 -0.0743 +vn 0.7517 0.6587 -0.0340 +vn 0.7336 0.6768 -0.0609 +vn 0.6736 0.7372 0.0524 +vn 0.6649 0.7456 0.0437 +vn 0.6838 0.7265 0.0681 +vn 0.6972 0.7135 0.0691 +vn 0.6524 0.7579 0.0042 +vn 0.7167 -0.6936 -0.0726 +vn 0.6596 -0.6895 -0.2994 +vn 0.6257 -0.6059 -0.4914 +vn 0.4578 -0.4811 -0.7476 +vn 0.4132 -0.3950 -0.8205 +vn 0.1432 -0.1586 -0.9769 +vn 0.0849 -0.0570 -0.9948 +vn -0.2013 0.1747 -0.9638 +vn -0.3083 0.3473 -0.8856 +vn -0.5444 0.5104 -0.6656 +vn -0.6150 0.6536 -0.4412 +vn -0.7169 0.6822 -0.1440 +vn -0.6877 0.7212 0.0834 +vn -0.6580 0.6244 0.4209 +vn -0.5480 0.5782 0.6045 +vn -0.3905 0.3637 0.8457 +vn -0.2709 0.2944 0.9165 +vn -0.0695 0.0486 0.9964 +vn 0.0615 -0.0315 0.9976 +vn 0.2619 -0.2860 0.9217 +vn 0.4583 -0.4253 0.7804 +vn 0.5367 -0.5621 0.6292 +vn 0.6700 -0.6438 0.3695 +vn 0.6796 -0.7022 0.2122 +vn 0.3536 -0.3536 -0.8660 +vn 0.3536 -0.3537 -0.8659 +vn 0.3536 -0.3535 -0.8661 +vn -0.3536 0.3536 -0.8660 +vn -0.3536 0.3536 0.8660 +vn 0.3536 -0.3537 0.8660 +vn 0.3536 -0.3537 0.8659 +vn 0.3537 -0.3537 0.8659 +vn 0.3535 -0.3535 0.8661 +vn 0.9640 0.0875 0.2511 +vn 0.9649 0.1060 0.2405 +vn 0.9530 -0.0038 0.3030 +vn 0.9499 -0.0200 0.3118 +vn 0.5706 0.4028 0.7157 +vn 0.5868 0.4128 0.6966 +vn 0.5125 0.3663 0.7766 +vn 0.5012 0.3591 0.7873 +vn 0.2454 0.8303 0.5004 +vn 0.2714 0.8282 0.4902 +vn 0.1510 0.8322 0.5336 +vn 0.1199 0.8310 0.5433 +vn -0.2096 0.9762 0.0555 +vn 0.3126 0.9422 -0.1207 +vn -0.2820 0.6853 -0.6715 +vn 0.5426 0.5755 -0.6119 +vn 0.5490 0.6012 -0.5806 +vn 0.4976 0.4346 -0.7507 +vn 0.4833 0.3969 -0.7803 +vn 0.8895 0.1645 -0.4264 +vn 0.8844 0.2151 -0.4142 +vn 0.8802 -0.0797 -0.4678 +vn 0.8722 -0.1264 -0.4726 +vn 0.7331 -0.6798 -0.0213 +vn 0.7318 -0.6809 -0.0300 +vn 0.7427 -0.6695 -0.0165 +vn 0.7055 -0.7074 -0.0426 +vn 0.6989 -0.7136 -0.0479 +vn 0.7175 -0.6952 -0.0420 +vn 0.6811 -0.7318 -0.0229 +vn 0.6740 -0.7384 -0.0233 +vn 0.6858 -0.7268 -0.0370 +vn 0.6914 -0.7215 0.0393 +vn 0.6746 -0.7377 0.0266 +vn 0.6804 -0.7325 0.0218 +vn 0.7382 -0.6745 0.0041 +vn 0.7315 -0.6815 0.0225 +vn 0.7340 -0.6784 0.0314 +vn 0.7105 -0.7020 0.0492 +vn 0.7077 -0.7053 0.0423 +vn 0.7232 -0.6895 0.0400 +vn 0.6753 -0.7376 0.0005 +vn -0.7607 0.6451 0.0723 +vn -0.6438 0.7128 0.2782 +vn -0.6419 0.7568 0.1236 +vn -0.7071 0.7071 0.0009 +vn -0.7059 0.7083 0.0051 +vn 0.5858 0.5762 0.5700 +vn 0.5405 0.7342 0.4108 +vn 0.5691 0.7039 0.4249 +vn 0.5814 0.5701 0.5805 +vn 0.0795 0.0665 0.9946 +vn 0.2734 0.2956 0.9154 +vn -0.1163 0.0145 0.9931 +vn -0.2310 -0.2441 0.9418 +vn -0.5625 -0.4376 0.7015 +vn -0.6366 -0.6487 0.4171 +vn -0.7683 -0.5346 0.3520 +vn -0.6989 -0.7135 0.0501 +vn -0.5531 -0.5456 -0.6296 +vn -0.6072 -0.5830 -0.5398 +vn -0.6041 -0.5810 -0.5455 +vn -0.5476 -0.5417 -0.6378 +vn -0.2369 -0.2420 -0.9409 +vn -0.1267 -0.1103 -0.9858 +vn -0.2293 -0.2330 -0.9450 +vn -0.1191 -0.1013 -0.9877 +vn 0.3050 0.3075 -0.9013 +vn 0.3348 0.3296 -0.8828 +vn 0.3320 0.3275 -0.8846 +vn 0.3028 0.3059 -0.9026 +vn 0.6845 0.6833 -0.2541 +vn 0.6720 0.6784 -0.2970 +vn 0.6734 0.6789 -0.2926 +vn 0.6855 0.6836 -0.2505 +vn -0.6572 0.7537 0.0117 +vn -0.6616 0.7486 0.0424 +vn -0.6541 0.7564 0.0029 +vn -0.6666 0.7442 -0.0437 +vn -0.6810 0.7298 0.0605 +vn -0.6858 0.7246 0.0674 +vn -0.7335 0.6774 -0.0566 +vn -0.7377 0.6728 -0.0552 +vn -0.7521 0.6586 -0.0235 +vn -0.7541 0.6562 -0.0258 +vn -0.7039 0.7070 -0.0689 +vn -0.6938 0.7165 -0.0724 +vn -0.7196 0.6908 -0.0703 +vn -0.6572 0.7532 -0.0290 +vn -0.6756 0.7348 -0.0600 +vn -0.7212 0.6895 0.0664 +vn -0.7414 0.6689 0.0533 +vn -0.7128 0.6976 0.0728 +vn -0.7569 0.6533 0.0147 +vn -0.7505 0.6603 0.0286 +vn 0.7040 0.6925 0.1576 +vn 0.6853 0.6698 -0.2860 +vn 0.6956 0.7145 0.0751 +vn 0.6268 0.6550 -0.4221 +vn 0.5345 0.5113 -0.6730 +vn 0.4038 0.4293 -0.8079 +vn 0.2526 0.2267 -0.9406 +vn 0.1177 0.1379 -0.9834 +vn -0.1039 -0.1239 -0.9868 +vn -0.1877 -0.1753 -0.9665 +vn -0.4448 -0.4518 -0.7733 +vn -0.4642 -0.4543 -0.7603 +vn -0.6707 -0.6531 -0.3517 +vn -0.6372 -0.6500 -0.4142 +vn -0.6971 -0.7168 0.0138 +vn -0.7096 -0.6713 0.2140 +vn -0.5984 -0.6303 0.4947 +vn -0.5079 -0.4713 0.7210 +vn -0.3046 -0.3405 0.8895 +vn -0.1484 -0.1100 0.9828 +vn 0.0612 0.0336 0.9976 +vn 0.2677 0.2943 0.9174 +vn 0.3728 0.3674 0.8521 +vn 0.5700 0.5770 0.5850 +vn 0.5778 0.5919 0.5620 +vn 0.3536 0.3536 -0.8660 +vn -0.3536 -0.3537 -0.8660 +vn -0.3536 -0.3537 -0.8659 +vn -0.3537 -0.3537 -0.8659 +vn -0.3535 -0.3535 -0.8661 +vn -0.3536 -0.3536 0.8660 +vn -0.3536 -0.3537 0.8659 +vn -0.3537 -0.3537 0.8659 +vn -0.3537 -0.3538 0.8659 +vn 0.3536 0.3536 0.8660 +vn 0.2683 0.8882 0.3729 +vn -0.4211 0.7963 0.4342 +vn -0.3113 0.7070 0.6351 +vn -0.5108 0.0010 0.8597 +vn -0.8722 0.3726 0.3169 +vn -0.9226 -0.2094 0.3240 +vn -0.9395 0.2023 -0.2763 +vn -0.9395 0.2277 -0.2561 +vn -0.9233 0.0638 -0.3787 +vn -0.9146 0.0274 -0.4035 +vn -0.4687 0.2832 -0.8367 +vn -0.4951 0.6828 -0.5373 +vn -0.5498 0.6718 -0.4964 +vn -0.2535 0.6946 -0.6733 +vn -0.1488 0.6840 -0.7141 +vn -0.0985 0.9807 -0.1690 +vn -0.0813 0.9825 -0.1678 +vn -0.1517 0.9732 -0.1726 +vn -0.1741 0.9693 -0.1738 +vn -0.3576 -0.2382 -0.9030 +vn -0.3339 -0.3492 -0.8756 +vn -0.3110 -0.4367 -0.8442 +vn -0.2850 -0.5205 -0.8049 +vn -0.7543 -0.5754 -0.3160 +vn -0.7117 -0.6570 -0.2485 +vn -0.6665 -0.7220 -0.1859 +vn -0.6072 -0.7865 -0.1128 +vn -0.7265 -0.5147 0.4553 +vn -0.6384 -0.5598 0.5282 +vn -0.5583 -0.5910 0.5822 +vn -0.4473 -0.6218 0.6429 +vn -0.2244 -0.0958 0.9698 +vn -0.1913 -0.1028 0.9761 +vn -0.1611 -0.1089 0.9809 +vn -0.1195 -0.1170 0.9859 +vn 0.4324 0.3813 0.8171 +vn 0.4322 0.3821 0.8169 +vn 0.4329 0.3801 0.8174 +vn 0.4331 0.3791 0.8177 +vn 0.6021 0.7632 0.2347 +vn 0.6699 0.7205 0.1790 +vn 0.7166 0.6841 0.1362 +vn 0.7729 0.6297 0.0780 +vn 0.5642 0.6269 -0.5373 +vn 0.5779 0.6210 -0.5295 +vn 0.5563 0.6304 -0.5413 +vn 0.5451 0.6351 -0.5473 +vn 0.2293 0.1929 -0.9541 +vn 0.2652 0.1887 -0.9455 +vn 0.2156 0.1944 -0.9569 +vn 0.1755 0.1985 -0.9643 +vn 0.7036 0.7104 0.0182 +vn 0.6993 0.7147 0.0132 +vn 0.6999 0.7142 0.0133 +vn 0.6958 0.7182 0.0081 +vn -0.1831 -0.2124 0.9599 +vn -0.2345 -0.1972 0.9519 +vn -0.2982 -0.1770 0.9380 +vn -0.3360 -0.1649 0.9273 +vn -0.4330 -0.6845 0.5865 +vn -0.5233 -0.6482 0.5532 +vn -0.6934 -0.5504 0.4650 +vn -0.7635 -0.4947 0.4152 +vn -0.6093 -0.7785 -0.1507 +vn -0.6365 -0.7513 -0.1743 +vn -0.6759 -0.7064 -0.2101 +vn -0.7061 -0.6667 -0.2387 +vn -0.5057 -0.5120 -0.6944 +vn -0.5036 -0.5130 -0.6952 +vn -0.5081 -0.5109 -0.6934 +vn -0.5101 -0.5099 -0.6927 +vn -0.0508 -0.1064 -0.9930 +vn -0.0588 -0.0863 -0.9945 +vn -0.0743 -0.0473 -0.9961 +vn -0.0823 -0.0270 -0.9962 +vn 0.4499 0.3917 -0.8026 +vn 0.4090 0.4089 -0.8158 +vn 0.5067 0.3652 -0.7810 +vn 0.5340 0.3519 -0.7688 +vn 0.6349 0.7107 -0.3030 +vn 0.5383 0.7525 -0.3794 +vn 0.7014 0.7061 -0.0977 +vn 0.7163 0.6827 0.1442 +vn 0.6294 0.6327 0.4511 +vn 0.4905 0.4996 0.7140 +vn 0.3378 0.3161 0.8865 +vn 0.2654 0.1963 0.9439 +vn 0.1879 0.2084 0.9598 +vn -0.7680 -0.6359 0.0766 +vn -0.7373 -0.6749 0.0279 +vn -0.7385 -0.6736 0.0296 +vn -0.7033 -0.7106 -0.0208 +vn 0.7071 -0.7071 0.0002 +vn 0.7072 -0.7070 0.0001 +vn 0.7073 -0.7069 -0.0001 +vn 0.7070 -0.7072 0.0001 +vn 0.7073 -0.7070 -0.0000 +vn 0.7070 -0.7072 -0.0002 +vn 0.7072 -0.7070 -0.0001 +vn 0.7072 -0.7070 -0.0004 +vn -0.7070 0.7072 0.0002 +vn -0.7069 0.7073 0.0000 +vn -0.7073 0.7069 0.0002 +vn -0.7070 0.7072 0.0001 +vn -0.7071 0.7071 -0.0001 +vn -0.7072 0.7070 -0.0001 +vn -0.7074 0.7068 -0.0002 +vn -0.7070 0.7072 -0.0001 +vn -0.7072 0.7070 -0.0000 +vn -0.7072 0.7070 -0.0004 +vn -0.7073 0.7070 -0.0003 +vn -0.7071 0.7071 0.0001 +vn -0.7072 0.7070 -0.0002 +vn -0.7073 0.7069 -0.0003 +vn -0.7250 -0.6877 0.0370 +vn -0.7398 -0.6725 0.0206 +vn -0.7336 -0.6793 0.0213 +vn -0.6800 -0.7329 0.0211 +vn -0.6737 -0.7387 0.0217 +vn -0.6883 -0.7244 0.0377 +vn -0.6887 -0.7241 -0.0383 +vn -0.6740 -0.7380 -0.0321 +vn -0.6796 -0.7332 -0.0226 +vn -0.6741 -0.7386 -0.0061 +vn -0.7378 -0.6750 -0.0091 +vn -0.7322 -0.6807 -0.0228 +vn -0.7329 -0.6793 -0.0359 +vn -0.7063 -0.7068 -0.0405 +vn -0.7040 -0.7086 -0.0475 +vn -0.7203 -0.6925 -0.0400 +vn -0.7063 -0.7067 0.0414 +vn -0.7073 -0.7054 0.0465 +vn 0.7072 0.7070 0.0004 +vn 0.7075 0.7067 -0.0002 +vn 0.7067 0.7075 0.0002 +vn 0.7067 0.7075 0.0036 +vn 0.7070 0.7072 -0.0004 +vn 0.7052 0.7090 -0.0032 +vn -0.6886 0.6790 -0.2545 +vn -0.6351 0.6523 -0.4137 +vn -0.5444 0.5318 -0.6488 +vn -0.2318 0.3157 -0.9201 +vn -0.0014 -0.0130 -0.9999 +vn 0.2523 -0.1064 -0.9618 +vn 0.3094 -0.3223 -0.8947 +vn 0.4730 -0.4552 -0.7543 +vn 0.6801 -0.6661 -0.3063 +vn 0.7841 -0.5854 -0.2059 +vn 0.7580 -0.6166 -0.2129 +vn 0.6791 -0.6637 -0.3135 +vn 0.6654 -0.6736 0.3217 +vn 0.6192 -0.6033 0.5025 +vn 0.6631 -0.6694 0.3350 +vn 0.6148 -0.5971 0.5153 +vn 0.2927 -0.2902 0.9111 +vn 0.2621 -0.2674 0.9273 +vn 0.2648 -0.2693 0.9259 +vn 0.2949 -0.2919 0.9099 +vn -0.2596 0.2640 0.9289 +vn -0.2506 0.2569 0.9334 +vn -0.2511 0.2573 0.9332 +vn -0.2605 0.2648 0.9285 +vn -0.6035 0.6033 0.5214 +vn -0.5855 0.5907 0.5552 +vn -0.5869 0.5917 0.5527 +vn -0.6046 0.6041 0.5192 +vn -0.6978 0.7119 -0.0785 +vn 0.6684 0.7423 -0.0466 +vn 0.6550 0.7555 -0.0165 +vn 0.6563 0.7544 0.0110 +vn 0.6557 0.7545 0.0272 +vn 0.7053 0.7054 -0.0711 +vn 0.6942 0.7160 -0.0732 +vn 0.6693 0.7409 -0.0560 +vn 0.7425 0.6683 0.0459 +vn 0.7440 0.6663 0.0498 +vn 0.7564 0.6540 0.0110 +vn 0.7548 0.6560 -0.0001 +vn 0.7061 0.7045 0.0715 +vn 0.6886 0.7216 0.0715 +vn 0.7194 0.6910 0.0712 +vn 0.6730 0.7377 0.0532 +vn 0.6682 0.7421 0.0528 +vn 0.7432 0.6675 -0.0459 +vn 0.7286 0.6818 -0.0661 +vn 0.7530 0.6573 -0.0307 +vn -0.6622 0.6728 0.3300 +vn -0.7021 0.7084 0.0722 +vn -0.7099 0.6973 0.0991 +vn -0.6562 0.6374 0.4038 +vn -0.4818 0.5011 0.7189 +vn -0.4120 0.3819 0.8273 +vn -0.2008 0.2317 0.9518 +vn -0.0369 0.0005 0.9993 +vn 0.1991 -0.1613 0.9666 +vn 0.3693 -0.4036 0.8371 +vn 0.5459 -0.5082 0.6661 +vn 0.6206 -0.6521 0.4355 +vn 0.7188 -0.6790 0.1492 +vn 0.6876 -0.7172 -0.1134 +vn 0.6563 -0.6140 -0.4385 +vn 0.5605 -0.5720 -0.5989 +vn 0.3424 -0.3057 -0.8884 +vn 0.3383 -0.3534 -0.8721 +vn 0.0261 -0.0434 -0.9987 +vn -0.1043 0.1407 -0.9845 +vn -0.2684 0.2574 -0.9283 +vn -0.4862 0.5022 -0.7152 +vn -0.5089 0.5065 -0.6961 +vn -0.6137 0.6139 -0.4964 +vn -0.6135 0.6200 -0.4891 +vn 0.3537 -0.3537 -0.8659 +vn 0.3537 -0.3538 -0.8659 +vn -0.0340 0.9832 0.1795 +vn 0.0356 0.9805 0.1931 +vn 0.1274 0.9857 -0.1102 +vn 0.1632 0.9793 -0.1195 +vn -0.0508 0.8031 -0.5937 +vn 0.0795 0.8093 -0.5820 +vn 0.3664 0.7719 -0.5196 +vn 0.4511 0.7459 -0.4900 +vn 0.2808 0.3634 -0.8883 +vn 0.8467 0.2765 -0.4546 +vn 0.8470 0.2741 -0.4555 +vn 0.8457 0.2845 -0.4514 +vn 0.8452 0.2890 -0.4496 +vn 0.9473 -0.2632 -0.1829 +vn 0.9593 0.2219 0.1746 +vn 0.9538 0.2706 0.1310 +vn 0.8315 0.1473 0.5356 +vn 0.7894 0.0754 0.6092 +vn 0.6668 0.4903 0.5613 +vn 0.6641 0.5323 0.5249 +vn 0.1502 0.5846 0.7973 +vn 0.1938 0.6791 0.7080 +vn 0.2312 0.8403 0.4903 +vn -0.2401 -0.2463 0.9390 +vn -0.2879 -0.2392 0.9273 +vn -0.3107 -0.2358 0.9208 +vn -0.3491 -0.2291 0.9086 +vn -0.5204 -0.7489 0.4103 +vn -0.6314 -0.6960 0.3419 +vn -0.7505 -0.6123 0.2486 +vn -0.8232 -0.5398 0.1760 +vn -0.4836 -0.7494 -0.4523 +vn -0.5412 -0.6515 -0.5316 +vn -0.5965 -0.5177 -0.6133 +vn -0.6314 -0.3885 -0.6711 +vn 0.0213 -0.1961 -0.9803 +vn 0.0002 -0.0868 -0.9962 +vn -0.0278 0.0592 -0.9979 +vn -0.0486 0.1690 -0.9844 +vn 0.5954 0.3665 -0.7150 +vn 0.5675 0.4979 -0.6558 +vn 0.5307 0.6103 -0.5881 +vn 0.4827 0.7138 -0.5074 +vn 0.8202 0.5709 0.0366 +vn 0.7401 0.6603 0.1272 +vn 0.6168 0.7508 0.2363 +vn 0.5029 0.8041 0.3172 +vn 0.4940 0.1756 0.8515 +vn 0.4060 0.2020 0.8912 +vn 0.2972 0.2305 0.9266 +vn 0.1701 0.2586 0.9509 +vn 0.7094 0.7036 0.0422 +vn 0.6921 0.7216 0.0179 +vn 0.6931 0.7206 0.0196 +vn 0.6757 0.7372 -0.0041 +vn -0.1608 -0.1408 -0.9769 +vn -0.1525 -0.1828 -0.9713 +vn -0.1454 -0.2155 -0.9656 +vn -0.1384 -0.2496 -0.9584 +vn -0.5694 -0.4170 -0.7084 +vn -0.5357 -0.5177 -0.6671 +vn -0.4745 -0.6518 -0.5916 +vn -0.4344 -0.7192 -0.5423 +vn -0.8105 -0.5518 -0.1966 +vn -0.5762 -0.7671 0.2822 +vn -0.5563 -0.7869 0.2671 +vn -0.6132 -0.7260 0.3114 +vn -0.6417 -0.6902 0.3344 +vn -0.4849 -0.3527 0.8003 +vn -0.4140 -0.3796 0.8273 +vn -0.2471 -0.2684 0.9311 +vn -0.0702 -0.1416 0.9874 +vn 0.1562 0.0925 0.9834 +vn 0.2223 0.2425 0.9443 +vn 0.1990 0.3639 0.9099 +vn 0.6430 0.5760 0.5047 +vn 0.6319 0.5839 0.5096 +vn 0.6122 0.5979 0.5175 +vn 0.6017 0.6049 0.5216 +vn 0.7042 0.6791 -0.2070 +vn 0.7449 0.6427 -0.1789 +vn 0.6310 0.7339 -0.2513 +vn 0.5909 0.7591 -0.2731 +vn 0.4494 0.4725 -0.7581 +vn 0.5636 0.4441 -0.6965 +vn 0.3309 0.4266 -0.8417 +vn 0.2816 0.2974 -0.9123 +vn 0.3046 0.1590 -0.9391 +vn -0.6918 -0.6904 -0.2117 +vn -0.7438 -0.6500 -0.1561 +vn -0.7370 -0.6557 -0.1638 +vn -0.7863 -0.6090 -0.1046 +vn -0.7069 0.7074 0.0001 +vn -0.7072 0.7070 0.0003 +vn -0.7072 0.7071 -0.0001 +vn -0.7069 0.7073 0.0003 +vn -0.7070 0.7072 -0.0000 +vn -0.7070 0.7072 -0.0002 +vn -0.7070 0.7072 0.0004 +vn -0.7070 0.7072 0.0003 +vn -0.7073 0.7069 -0.0000 +vn -0.7074 0.7069 -0.0001 +vn -0.7069 0.7073 -0.0003 +vn -0.7070 0.7072 -0.0004 +vn 0.7071 -0.7072 -0.0001 +vn 0.7072 -0.7070 0.0002 +vn 0.7074 -0.7068 0.0000 +vn 0.7073 -0.7069 0.0000 +vn 0.7070 -0.7072 0.0004 +vn 0.7071 -0.7072 0.0000 +vn 0.6895 -0.7232 0.0393 +vn 0.6734 -0.7387 0.0306 +vn 0.6804 -0.7325 0.0217 +vn 0.6749 -0.7378 0.0075 +vn 0.7068 -0.7060 0.0444 +vn 0.7142 -0.6983 0.0481 +vn 0.7029 -0.7091 0.0554 +vn 0.7331 -0.6798 0.0205 +vn 0.7424 -0.6696 0.0196 +vn 0.7286 -0.6842 0.0319 +vn 0.7326 -0.6803 -0.0215 +vn 0.7225 -0.6902 -0.0397 +vn 0.7380 -0.6744 -0.0237 +vn 0.6807 -0.7322 -0.0214 +vn 0.6760 -0.7365 -0.0227 +vn 0.7050 -0.7074 -0.0510 +vn 0.7065 -0.7065 -0.0429 +vn 0.6909 -0.7219 -0.0400 +vn 0.7390 -0.6737 0.0009 +vn -0.6951 0.7189 -0.0026 +vn -0.7447 0.5873 -0.3169 +vn -0.7465 0.6552 -0.1161 +vn -0.6911 0.7223 0.0248 +vn -0.6755 0.7370 0.0250 +vn -0.6952 0.7095 -0.1152 +vn -0.5768 -0.5846 -0.5705 +vn -0.6902 -0.5737 -0.4410 +vn -0.6667 -0.5927 -0.4520 +vn -0.5709 -0.5806 -0.5805 +vn -0.0629 -0.0719 -0.9954 +vn -0.2191 -0.2009 -0.9548 +vn 0.0346 0.0539 -0.9979 +vn 0.2427 0.2316 -0.9420 +vn 0.4863 0.5056 -0.7127 +vn 0.6482 0.6375 -0.4164 +vn 0.6954 0.7166 -0.0543 +vn 0.6610 0.6555 0.3653 +vn 0.6119 0.6314 0.4764 +vn 0.5333 0.5471 0.6452 +vn 0.4966 0.4947 0.7132 +vn -0.0550 -0.0629 0.9965 +vn 0.0387 0.0534 0.9978 +vn 0.0301 0.0427 0.9986 +vn -0.0627 -0.0724 0.9954 +vn -0.5347 -0.5335 0.6554 +vn -0.5704 -0.3466 0.7447 +vn -0.6403 -0.5416 0.5447 +vn -0.6406 -0.6402 0.4240 +vn -0.6915 -0.6838 0.2332 +vn -0.6969 -0.6967 0.1700 +vn -0.7539 0.6568 -0.0151 +vn -0.7493 0.6609 -0.0409 +vn -0.7572 0.6532 0.0008 +vn -0.7503 0.6605 0.0282 +vn -0.7293 0.6815 -0.0601 +vn -0.7286 0.6818 -0.0663 +vn -0.6888 0.7220 0.0650 +vn -0.6704 0.7399 0.0562 +vn -0.6588 0.7519 0.0262 +vn -0.6540 0.7563 0.0158 +vn -0.7294 0.6813 0.0617 +vn -0.7284 0.6818 0.0682 +vn -0.7009 0.7096 0.0728 +vn -0.7485 0.6620 0.0389 +vn -0.6884 0.7222 -0.0667 +vn -0.6712 0.7390 -0.0577 +vn -0.7005 0.7099 -0.0737 +vn -0.6598 0.7509 -0.0286 +vn -0.6553 0.7549 -0.0252 +vn -0.7188 -0.6952 0.0025 +vn -0.6919 -0.7116 0.1223 +vn -0.6033 -0.5837 0.5434 +vn -0.5895 -0.5899 0.5518 +vn -0.3673 -0.3746 0.8514 +vn -0.3302 -0.3067 0.8927 +vn -0.0790 -0.0936 0.9925 +vn 0.0613 0.0941 0.9937 +vn 0.2174 0.2013 0.9551 +vn 0.4487 0.4721 0.7588 +vn 0.4890 0.4941 0.7188 +vn 0.6742 0.7009 0.2330 +vn 0.6538 0.6538 0.3808 +vn 0.7154 0.6977 -0.0375 +vn 0.6489 0.6764 -0.3485 +vn 0.6366 0.6162 -0.4637 +vn 0.4349 0.4639 -0.7718 +vn 0.3675 0.3407 -0.8654 +vn 0.0587 0.0911 -0.9941 +vn -0.0206 -0.0394 -0.9990 +vn -0.3264 -0.3186 -0.8899 +vn -0.3530 -0.3578 -0.8645 +vn -0.6169 -0.6317 -0.4695 +vn -0.5952 -0.5829 -0.5531 +vn -0.3536 -0.3535 0.8661 +vn -0.7986 -0.4248 -0.4264 +vn -0.7773 0.4519 -0.4377 +vn -0.6302 0.3206 -0.7071 +vn -0.1467 0.6355 -0.7580 +vn -0.1932 0.6899 -0.6977 +vn -0.2250 0.8498 -0.4767 +vn -0.0335 0.9446 -0.3266 +vn -0.1224 0.9884 -0.0903 +vn -0.1881 0.9820 -0.0193 +vn -0.1952 0.8244 0.5313 +vn -0.3556 0.6367 0.6842 +vn -0.2917 0.6912 0.6612 +vn -0.5837 0.5317 0.6137 +vn -0.6136 0.5388 0.5772 +vn -0.7568 -0.0473 0.6519 +vn -0.9504 0.2549 0.1782 +vn -0.9420 0.2822 0.1816 +vn -0.9727 0.1615 0.1665 +vn -0.9841 0.0855 0.1559 +vn 0.2595 -0.2542 0.9317 +vn 0.2345 -0.2570 0.9375 +vn 0.2663 -0.2533 0.9300 +vn 0.2911 -0.2503 0.9234 +vn 0.6202 -0.6285 0.4693 +vn 0.6073 -0.6502 0.4566 +vn 0.5936 -0.6718 0.4431 +vn 0.5820 -0.6891 0.4318 +vn 0.7081 -0.5380 -0.4573 +vn 0.6754 -0.5622 -0.4773 +vn 0.6204 -0.5984 -0.5070 +vn 0.5776 -0.6231 -0.5273 +vn 0.1076 -0.0613 -0.9923 +vn 0.0814 -0.1844 -0.9795 +vn 0.1313 0.0584 -0.9896 +vn 0.1479 0.1488 -0.9777 +vn -0.5461 0.2507 -0.7993 +vn -0.4305 0.7263 -0.5358 +vn -0.7303 0.6818 0.0426 +vn -0.7948 0.6019 -0.0776 +vn -0.7036 0.6688 0.2402 +vn -0.6550 0.6452 0.3933 +vn -0.6764 0.5154 0.5262 +vn -0.2295 0.4731 0.8506 +vn -0.2502 0.3800 0.8905 +vn -0.2659 0.2962 0.9174 +vn -0.2852 0.1679 0.9437 +vn -0.7149 0.6936 0.0881 +vn -0.7447 0.6657 0.0474 +vn -0.7434 0.6670 0.0496 +vn -0.7700 0.6379 0.0103 +vn 0.2407 -0.1709 -0.9554 +vn 0.2260 -0.2108 -0.9511 +vn 0.2546 -0.1325 -0.9579 +vn 0.2771 -0.0665 -0.9585 +vn 0.3336 -0.6234 -0.7072 +vn 0.8340 -0.3935 -0.3868 +vn 0.4516 -0.8920 0.0190 +vn 0.8116 -0.3709 0.4515 +vn 0.1791 -0.6197 0.7641 +vn 0.3210 0.0299 0.9466 +vn -0.2852 0.0240 0.9582 +vn -0.2711 0.1321 0.9534 +vn -0.3680 0.3535 0.8600 +vn -0.4935 0.5315 0.6884 +vn -0.6233 0.6402 0.4490 +vn -0.6777 0.6685 0.3063 +vn -0.7434 0.6240 0.2410 +vn -0.6218 0.7365 -0.2662 +vn -0.5960 0.7643 -0.2463 +vn -0.6659 0.6826 -0.3011 +vn -0.6951 0.6412 -0.3251 +vn -0.4274 0.3199 -0.8456 +vn -0.3925 0.3379 -0.8554 +vn -0.3162 0.3741 -0.8718 +vn -0.2796 0.3903 -0.8772 +vn 0.6823 -0.7032 -0.2001 +vn 0.6624 -0.7289 -0.1727 +vn 0.6653 -0.7253 -0.1766 +vn 0.6440 -0.7505 -0.1483 +vn -0.7072 -0.7070 0.0000 +vn -0.7071 -0.7072 -0.0000 +vn -0.7070 -0.7072 -0.0004 +vn -0.7073 -0.7069 0.0004 +vn -0.7073 -0.7070 0.0000 +vn -0.7072 -0.7071 0.0001 +vn 0.7070 0.7072 0.0002 +vn 0.7070 0.7072 0.0001 +vn 0.7069 0.7073 0.0001 +vn 0.7070 0.7072 -0.0000 +vn 0.7073 0.7070 0.0003 +vn 0.7072 0.7070 0.0002 +vn 0.7069 0.7074 0.0000 +vn 0.7068 0.7074 0.0000 +vn 0.7070 0.7072 -0.0001 +vn 0.7069 0.7073 -0.0002 +vn 0.7071 0.7072 -0.0001 +vn -0.2000 -0.9794 -0.0285 +vn -0.2224 -0.9542 0.2002 +vn 0.2023 -0.9663 -0.1589 +vn 0.1897 -0.9806 0.0499 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 2/2/2 5/5/5 +f 6/6/6 4/4/4 7/7/7 +f 6/6/6 7/7/7 8/8/8 +f 8/8/8 7/7/7 9/9/9 +f 8/8/8 10/10/10 11/11/11 +f 8/8/8 11/11/11 6/6/6 +f 6/6/6 11/11/11 12/12/12 +f 13/13/13 14/14/14 12/12/12 +f 12/12/12 11/11/11 15/15/15 +f 13/13/13 12/12/12 15/15/15 +f 14/14/14 13/13/13 16/16/16 +f 16/16/16 13/13/13 17/17/17 +f 16/16/16 17/17/17 18/18/18 +f 18/18/18 17/17/17 19/19/19 +f 18/18/18 20/20/20 21/21/21 +f 21/21/21 16/16/16 18/18/18 +f 16/16/16 21/21/21 3/3/3 +f 22/22/22 5/5/5 23/23/23 +f 1/1/1 24/24/24 23/23/23 +f 5/5/5 2/2/2 1/1/1 +f 5/5/5 1/1/1 23/23/23 +f 25/25/25 24/24/24 1/1/1 +f 25/25/25 1/1/1 26/26/26 +f 26/26/26 27/27/27 28/28/28 +f 29/29/29 30/30/30 31/31/31 +f 30/30/30 29/29/29 13/13/13 +f 15/15/15 32/32/32 13/13/13 +f 13/13/13 32/32/32 30/30/30 +f 33/33/33 32/32/32 15/15/15 +f 15/15/15 34/34/34 33/33/33 +f 31/31/31 30/30/30 35/35/35 +f 35/35/35 30/30/30 36/36/36 +f 33/33/33 34/34/34 37/37/37 +f 37/37/37 34/34/34 38/38/38 +f 22/22/22 23/23/23 39/39/39 +f 39/39/39 23/23/23 40/40/40 +f 25/25/25 26/26/26 28/28/28 +f 25/25/25 28/28/28 41/41/41 +f 41/41/41 28/28/28 42/42/42 +f 43/43/43 35/35/35 36/36/36 +f 37/37/37 38/38/38 44/44/44 +f 44/44/44 38/38/38 45/45/45 +f 45/45/45 46/46/46 44/44/44 +f 43/43/43 46/46/46 47/47/47 +f 43/43/43 36/36/36 46/46/46 +f 46/46/46 45/45/45 47/47/47 +f 19/19/19 48/48/48 49/49/49 +f 27/27/27 20/20/20 50/50/50 +f 51/51/51 42/42/42 50/50/50 +f 50/50/50 42/42/42 28/28/28 +f 50/50/50 28/28/28 27/27/27 +f 50/50/50 20/20/20 49/49/49 +f 49/49/49 20/20/20 18/18/18 +f 49/49/49 18/18/18 19/19/19 +f 48/48/48 52/52/52 31/31/31 +f 48/48/48 31/31/31 43/43/43 +f 43/43/43 31/31/31 35/35/35 +f 41/41/41 42/42/42 51/51/51 +f 41/41/41 51/51/51 53/53/53 +f 54/54/54 55/55/55 56/56/56 +f 56/56/56 55/55/55 51/51/51 +f 51/51/51 55/55/55 53/53/53 +f 40/40/40 55/55/55 54/54/54 +f 39/39/39 40/40/40 57/57/57 +f 57/57/57 40/40/40 54/54/54 +f 58/58/58 9/9/9 59/59/59 +f 60/60/60 38/38/38 34/34/34 +f 60/60/60 34/34/34 61/61/61 +f 60/60/60 61/61/61 62/62/62 +f 62/62/62 10/10/10 58/58/58 +f 58/58/58 10/10/10 8/8/8 +f 58/58/58 8/8/8 9/9/9 +f 59/59/59 9/9/9 22/22/22 +f 59/59/59 22/22/22 57/57/57 +f 57/57/57 22/22/22 39/39/39 +f 63/63/63 64/64/64 65/65/65 +f 66/66/66 63/63/63 65/65/65 +f 67/67/67 68/68/68 66/66/66 +f 66/66/66 68/68/68 63/63/63 +f 65/65/65 64/64/64 69/69/69 +f 70/70/70 71/71/71 72/72/72 +f 72/72/72 71/71/71 73/73/73 +f 72/72/72 73/73/73 74/74/74 +f 72/72/72 74/74/74 75/75/75 +f 75/75/75 74/74/74 76/76/76 +f 71/71/71 70/70/70 77/77/77 +f 77/77/77 70/70/70 78/78/78 +f 78/78/78 70/70/70 79/79/79 +f 78/78/78 79/79/79 80/80/80 +f 80/80/80 79/79/79 81/81/81 +f 80/80/80 81/81/81 82/82/82 +f 83/83/83 84/84/84 85/85/85 +f 86/86/86 87/87/87 84/84/84 +f 84/84/84 87/87/87 85/85/85 +f 88/88/88 89/89/89 86/86/86 +f 86/86/86 89/89/89 87/87/87 +f 90/90/90 89/89/91 88/88/92 +f 91/91/93 92/92/94 90/90/95 +f 90/90/95 92/92/94 89/89/96 +f 93/93/97 94/94/98 95/95/99 +f 93/93/97 95/95/99 91/91/93 +f 91/91/93 95/95/99 92/92/94 +f 93/93/97 96/96/100 94/94/98 +f 97/97/101 67/67/67 98/98/102 +f 98/98/102 99/99/103 97/97/101 +f 100/100/104 99/99/103 98/98/102 +f 100/100/104 101/101/105 99/99/103 +f 102/102/106 101/101/105 100/100/104 +f 102/102/106 103/103/107 101/101/105 +f 104/104/108 103/103/107 102/102/106 +f 104/104/108 105/105/109 103/103/107 +f 105/105/109 104/104/108 106/106/110 +f 66/66/111 107/107/112 108/108/113 +f 109/109/114 67/67/115 108/108/113 +f 67/67/115 109/109/114 98/98/116 +f 98/98/116 109/109/114 110/110/117 +f 98/98/116 110/110/117 100/100/118 +f 100/100/118 110/110/117 111/111/119 +f 111/111/119 102/102/120 100/100/118 +f 112/112/121 104/104/122 111/111/119 +f 111/111/119 104/104/122 102/102/120 +f 113/113/123 69/69/69 106/106/124 +f 106/106/124 112/112/121 113/113/123 +f 112/112/121 106/106/124 104/104/122 +f 114/114/125 115/115/126 65/65/65 +f 114/114/125 65/65/65 113/113/123 +f 113/113/123 65/65/65 69/69/69 +f 114/114/125 116/116/127 117/117/128 +f 114/114/125 117/117/128 118/118/129 +f 119/119/130 115/115/126 114/114/125 +f 119/119/130 114/114/125 118/118/129 +f 120/120/131 116/116/127 114/114/125 +f 121/121/132 122/122/133 120/120/131 +f 120/120/131 122/122/133 116/116/127 +f 123/123/134 124/124/135 121/121/132 +f 121/121/132 124/124/135 122/122/133 +f 125/125/136 126/126/137 123/123/134 +f 123/123/134 126/126/137 124/124/135 +f 125/125/136 127/127/138 128/128/139 +f 128/128/139 126/126/137 125/125/136 +f 129/129/140 128/128/139 127/127/138 +f 130/130/141 129/129/140 127/127/138 +f 131/131/142 132/132/143 133/133/144 +f 131/131/142 133/133/144 130/130/141 +f 130/130/141 133/133/144 129/129/140 +f 134/134/145 135/135/146 131/131/142 +f 136/136/147 132/132/143 131/131/142 +f 136/136/147 131/131/142 135/135/146 +f 137/137/148 138/138/149 131/131/142 +f 131/131/142 138/138/149 139/139/150 +f 139/139/150 140/140/151 131/131/142 +f 131/131/142 140/140/151 141/141/152 +f 141/141/152 134/134/145 131/131/142 +f 142/142/153 143/143/154 137/137/148 +f 143/143/154 138/138/149 137/137/148 +f 143/143/154 142/142/153 144/144/155 +f 143/143/154 144/144/155 145/145/156 +f 146/146/157 147/147/158 144/144/155 +f 144/144/155 147/147/158 145/145/156 +f 148/148/159 149/149/160 146/146/157 +f 146/146/157 149/149/160 147/147/158 +f 150/150/161 148/148/159 151/151/162 +f 150/150/161 151/151/162 152/152/163 +f 148/148/159 150/150/161 149/149/160 +f 153/153/164 151/151/162 154/154/165 +f 154/154/165 151/151/162 148/148/159 +f 83/83/166 154/154/165 155/155/167 +f 83/83/166 82/82/168 154/154/165 +f 154/154/165 82/82/168 81/81/169 +f 154/154/165 81/81/169 153/153/164 +f 155/155/167 84/84/170 83/83/166 +f 156/156/171 84/84/170 155/155/167 +f 156/156/171 86/86/172 84/84/170 +f 157/157/173 88/88/92 156/156/171 +f 156/156/171 88/88/92 86/86/172 +f 157/157/173 90/90/90 88/88/92 +f 158/158/174 90/90/90 157/157/173 +f 159/159/175 91/91/176 158/158/174 +f 158/158/174 91/91/176 90/90/90 +f 159/159/175 93/93/177 91/91/176 +f 160/160/178 96/96/179 159/159/175 +f 159/159/175 96/96/179 93/93/177 +f 75/75/180 76/76/181 160/160/178 +f 160/160/178 76/76/181 96/96/179 +f 108/108/113 107/107/112 160/160/178 +f 160/160/178 107/107/112 75/75/180 +f 78/78/182 80/80/183 85/85/184 +f 73/73/185 94/94/186 74/74/187 +f 73/73/185 95/95/188 94/94/186 +f 71/71/189 92/92/190 95/95/188 +f 71/71/189 95/95/188 73/73/185 +f 89/89/191 92/92/190 71/71/189 +f 77/77/192 89/89/191 71/71/189 +f 77/77/192 87/87/193 89/89/191 +f 78/78/182 87/87/193 77/77/192 +f 78/78/182 85/85/184 87/87/193 +f 76/76/76 74/74/74 96/96/194 +f 74/74/74 94/94/195 96/96/194 +f 69/69/69 64/64/64 106/106/110 +f 68/68/68 67/67/67 97/97/101 +f 63/63/63 68/68/68 99/99/103 +f 64/64/64 63/63/63 103/103/107 +f 64/64/64 103/103/107 105/105/109 +f 68/68/68 97/97/101 99/99/103 +f 63/63/63 99/99/103 101/101/105 +f 63/63/63 101/101/105 103/103/107 +f 64/64/64 105/105/109 106/106/110 +f 65/65/65 115/115/196 66/66/66 +f 66/66/66 115/115/196 107/107/197 +f 57/57/57 161/161/198 59/59/59 +f 59/59/59 161/161/198 162/162/199 +f 59/59/59 162/162/199 58/58/58 +f 58/58/58 162/162/199 163/163/200 +f 58/58/58 163/163/200 62/62/62 +f 62/62/62 163/163/200 164/164/201 +f 62/62/62 164/164/201 60/60/60 +f 60/60/60 164/164/201 165/165/202 +f 60/60/60 165/165/202 38/38/38 +f 38/38/38 165/165/202 45/45/203 +f 45/45/203 165/165/202 72/72/204 +f 107/107/205 45/45/203 75/75/206 +f 75/75/206 45/45/203 72/72/204 +f 165/165/202 164/164/201 72/72/204 +f 72/72/204 164/164/201 70/70/207 +f 164/164/201 163/163/200 70/70/207 +f 163/163/200 162/162/199 70/70/207 +f 70/70/207 162/162/199 79/79/208 +f 162/162/199 161/161/198 79/79/208 +f 166/166/209 167/167/210 168/168/211 +f 166/166/209 168/168/211 169/169/212 +f 169/169/212 168/168/211 170/170/213 +f 169/169/212 170/170/213 136/136/214 +f 136/136/214 170/170/213 132/132/215 +f 167/167/210 166/166/209 171/171/216 +f 167/167/210 171/171/216 172/172/217 +f 172/172/217 171/171/216 173/173/218 +f 173/173/218 171/171/216 174/174/219 +f 173/173/218 174/174/219 175/175/220 +f 175/175/220 174/174/219 118/118/221 +f 175/175/220 118/118/221 117/117/222 +f 124/124/223 176/176/224 122/122/225 +f 122/122/225 176/176/224 177/177/226 +f 122/122/225 177/177/226 116/116/227 +f 126/126/228 178/178/229 124/124/223 +f 124/124/223 178/178/229 176/176/224 +f 178/178/229 126/126/228 179/179/230 +f 179/179/230 126/126/228 128/128/139 +f 179/179/230 128/128/139 129/129/140 +f 179/179/230 129/129/140 180/180/231 +f 180/180/231 129/129/140 133/133/232 +f 173/173/233 175/175/234 177/177/235 +f 168/168/236 180/180/237 170/170/238 +f 179/179/239 180/180/237 168/168/236 +f 167/167/240 179/179/239 168/168/236 +f 178/178/241 179/179/239 167/167/240 +f 178/178/241 167/167/240 172/172/242 +f 172/172/242 176/176/243 178/178/241 +f 173/173/233 177/177/235 176/176/243 +f 173/173/233 176/176/243 172/172/242 +f 175/175/220 117/117/222 116/116/227 +f 116/116/227 177/177/226 175/175/220 +f 43/43/43 181/181/244 48/48/48 +f 48/48/48 181/181/244 182/182/245 +f 48/48/48 182/182/245 183/183/246 +f 48/48/48 183/183/246 49/49/49 +f 49/49/49 183/183/246 184/184/247 +f 49/49/49 184/184/247 50/50/50 +f 50/50/50 184/184/247 185/185/248 +f 50/50/50 185/185/248 51/51/51 +f 181/181/244 43/43/43 47/47/249 +f 174/174/250 181/181/244 47/47/249 +f 118/118/251 174/174/250 47/47/249 +f 118/118/251 47/47/249 119/119/252 +f 169/169/212 185/185/248 166/166/209 +f 185/185/248 184/184/247 166/166/209 +f 166/166/209 184/184/247 171/171/216 +f 184/184/247 183/183/246 171/171/216 +f 183/183/246 182/182/245 171/171/216 +f 171/171/216 182/182/245 174/174/219 +f 174/174/219 182/182/245 181/181/244 +f 186/186/253 187/187/254 141/141/255 +f 141/141/255 187/187/254 152/152/163 +f 141/141/255 140/140/151 186/186/253 +f 187/187/254 188/188/256 152/152/163 +f 152/152/163 188/188/256 150/150/161 +f 143/143/257 189/189/258 138/138/259 +f 190/190/260 189/189/258 143/143/257 +f 145/145/261 190/190/260 143/143/257 +f 190/190/260 145/145/261 191/191/262 +f 191/191/262 145/145/261 147/147/263 +f 147/147/263 192/192/264 191/191/262 +f 147/147/263 149/149/265 192/192/264 +f 80/80/80 82/82/82 83/83/83 +f 83/83/83 85/85/85 80/80/80 +f 189/189/258 139/139/150 138/138/259 +f 149/149/265 150/150/161 192/192/264 +f 192/192/264 150/150/161 188/188/256 +f 192/192/264 188/188/256 187/187/254 +f 192/192/264 187/187/254 191/191/262 +f 191/191/262 187/187/254 190/190/260 +f 190/190/260 187/187/254 186/186/253 +f 190/190/260 186/186/253 189/189/258 +f 189/189/258 186/186/253 140/140/151 +f 189/189/258 140/140/151 139/139/150 +f 151/151/266 141/141/255 152/152/163 +f 151/151/266 134/134/267 141/141/255 +f 161/161/198 57/57/57 54/54/268 +f 161/161/198 54/54/268 79/79/269 +f 79/79/269 54/54/268 153/153/270 +f 79/79/269 153/153/270 81/81/271 +f 133/133/232 132/132/215 170/170/213 +f 133/133/232 170/170/213 180/180/231 +f 169/169/212 56/56/272 51/51/51 +f 51/51/51 185/185/248 169/169/212 +f 56/56/272 169/169/212 135/135/273 +f 135/135/273 169/169/212 136/136/274 +f 155/155/275 158/158/275 156/156/275 +f 127/127/276 121/121/275 130/130/277 +f 130/130/277 121/121/275 120/120/278 +f 120/120/278 131/131/279 130/130/277 +f 131/131/279 114/114/280 113/113/280 +f 131/131/279 113/113/280 137/137/280 +f 137/137/280 113/113/280 112/112/275 +f 120/120/278 114/114/280 131/131/279 +f 142/142/275 137/137/280 112/112/275 +f 123/123/275 127/127/276 125/125/275 +f 142/142/275 112/112/275 144/144/281 +f 111/111/275 146/146/275 144/144/281 +f 146/146/275 109/109/275 108/108/275 +f 110/110/275 109/109/275 111/111/275 +f 127/127/276 123/123/275 121/121/275 +f 146/146/275 108/108/275 148/148/282 +f 109/109/275 146/146/275 111/111/275 +f 148/148/282 108/108/275 154/154/276 +f 154/154/276 108/108/275 160/160/282 +f 154/154/276 160/160/282 155/155/275 +f 155/155/275 160/160/282 159/159/281 +f 159/159/281 158/158/275 155/155/275 +f 112/112/275 111/111/275 144/144/281 +f 157/157/275 156/156/275 158/158/275 +f 47/47/47 115/115/196 119/119/283 +f 47/47/47 45/45/45 115/115/196 +f 45/45/45 107/107/197 115/115/196 +f 135/135/284 134/134/267 56/56/56 +f 56/56/56 134/134/267 54/54/54 +f 54/54/54 134/134/267 151/151/266 +f 151/151/266 153/153/285 54/54/54 +f 193/193/286 194/194/286 195/195/286 +f 194/194/286 196/196/287 195/195/286 +f 197/197/286 194/194/286 193/193/286 +f 198/198/286 194/194/286 199/199/286 +f 200/200/288 196/196/287 201/201/289 +f 202/202/286 194/194/286 198/198/286 +f 203/203/290 204/204/291 201/201/289 +f 205/205/286 194/194/286 202/202/286 +f 196/196/287 206/206/292 201/201/289 +f 194/194/286 207/207/293 196/196/287 +f 206/206/292 203/203/290 201/201/289 +f 208/208/286 207/207/293 194/194/286 +f 209/209/294 203/203/290 206/206/292 +f 196/196/287 207/207/293 206/206/292 +f 210/210/286 208/208/286 211/211/286 +f 206/206/292 212/212/295 209/209/294 +f 213/213/286 210/210/286 211/211/286 +f 206/206/292 214/214/296 212/212/295 +f 215/215/286 216/216/286 210/210/286 +f 210/210/286 207/207/293 208/208/286 +f 217/217/286 215/215/286 210/210/286 +f 199/199/286 194/194/286 197/197/286 +f 216/216/286 207/207/293 210/210/286 +f 218/218/297 219/219/297 220/220/297 +f 221/221/298 222/222/297 223/223/297 +f 222/222/297 224/224/297 225/225/297 +f 222/222/297 221/221/298 226/226/297 +f 221/221/298 219/219/297 226/226/297 +f 227/227/299 228/228/300 229/229/301 +f 230/230/302 231/231/297 232/232/297 +f 221/221/298 227/227/299 229/229/301 +f 227/227/299 233/233/303 228/228/300 +f 221/221/298 234/234/304 235/235/305 +f 232/232/297 236/236/297 237/237/297 +f 230/230/302 221/221/298 235/235/305 +f 222/222/297 225/225/297 223/223/297 +f 238/238/297 218/218/297 220/220/297 +f 239/239/306 230/230/302 235/235/305 +f 240/240/297 219/219/297 221/221/298 +f 219/219/297 240/240/297 220/220/297 +f 241/241/307 242/242/308 239/239/306 +f 230/230/302 240/240/297 221/221/298 +f 243/243/309 242/242/308 241/241/307 +f 242/242/308 230/230/302 239/239/306 +f 221/221/298 229/229/301 234/234/304 +f 230/230/302 237/237/297 240/240/297 +f 230/230/302 232/232/297 237/237/297 +f 244/244/297 232/232/297 231/231/297 +f 245/245/310 246/246/310 247/247/310 +f 245/245/310 247/247/310 248/248/311 +f 249/249/312 250/250/313 251/251/314 +f 252/252/310 253/253/310 245/245/310 +f 245/245/310 253/253/310 246/246/310 +f 248/248/311 247/247/310 254/254/315 +f 248/248/311 254/254/315 214/214/316 +f 214/214/316 254/254/315 255/255/317 +f 254/254/315 256/256/318 255/255/317 +f 255/255/317 256/256/318 249/249/312 +f 257/257/319 258/258/310 252/252/310 +f 259/259/320 251/251/314 260/260/321 +f 251/251/314 259/259/320 261/261/322 +f 259/259/320 262/262/323 261/261/322 +f 261/261/322 262/262/323 257/257/319 +f 257/257/319 262/262/323 258/258/310 +f 258/258/310 263/263/310 252/252/310 +f 255/255/317 249/249/312 251/251/314 +f 264/264/310 260/260/321 253/253/310 +f 253/253/310 260/260/321 250/250/313 +f 250/250/313 260/260/321 251/251/314 +f 252/252/310 263/263/310 253/253/310 +f 253/253/310 263/263/310 265/265/310 +f 253/253/310 265/265/310 264/264/310 +f 266/266/324 267/267/325 268/268/325 +f 269/269/326 270/270/327 230/230/328 +f 230/230/328 270/270/327 207/207/329 +f 266/266/324 268/268/325 271/271/325 +f 207/207/329 272/272/330 273/273/331 +f 274/274/332 275/275/333 276/276/325 +f 276/276/325 275/275/333 277/277/325 +f 207/207/329 278/278/334 272/272/330 +f 242/242/335 279/279/336 230/230/328 +f 273/273/331 206/206/337 207/207/329 +f 230/230/328 279/279/336 269/269/326 +f 207/207/329 270/270/327 278/278/334 +f 242/242/335 280/280/338 279/279/336 +f 277/277/325 275/275/333 281/281/339 +f 271/271/325 268/268/325 282/282/340 +f 271/271/325 282/282/340 242/242/335 +f 242/242/335 282/282/340 280/280/338 +f 206/206/337 273/273/331 283/283/341 +f 277/277/325 281/281/339 283/283/341 +f 283/283/341 281/281/339 206/206/337 +f 275/275/333 274/274/332 266/266/324 +f 266/266/324 274/274/332 267/267/325 +f 270/270/327 284/284/332 278/278/334 +f 284/284/332 270/270/327 285/285/325 +f 274/274/332 286/286/325 267/267/325 +f 274/274/332 287/287/332 286/286/325 +f 286/286/325 287/287/332 288/288/325 +f 287/287/332 289/289/325 288/288/325 +f 288/288/325 289/289/325 285/285/325 +f 285/285/325 289/289/325 284/284/332 +f 252/252/342 245/245/343 266/266/324 +f 266/266/324 245/245/343 275/275/333 +f 243/243/344 290/290/345 261/261/322 +f 251/251/314 261/261/322 290/290/345 +f 290/290/345 243/243/344 291/291/346 +f 292/292/347 212/212/348 214/214/349 +f 292/292/347 214/214/349 255/255/317 +f 293/293/350 294/294/351 295/295/352 +f 295/295/352 294/294/351 296/296/353 +f 297/297/354 298/298/355 196/196/356 +f 196/196/356 298/298/355 221/221/357 +f 299/299/358 300/300/359 221/221/357 +f 301/301/360 294/294/351 293/293/350 +f 294/294/351 301/301/360 302/302/360 +f 294/294/351 302/302/360 303/303/361 +f 196/196/356 304/304/362 297/297/354 +f 221/221/357 298/298/355 299/299/358 +f 305/305/363 304/304/362 200/200/364 +f 200/200/364 304/304/362 196/196/356 +f 221/221/357 300/300/359 306/306/365 +f 307/307/360 293/293/350 308/308/360 +f 308/308/360 293/293/350 309/309/366 +f 306/306/365 227/227/360 221/221/357 +f 303/303/361 302/302/360 310/310/361 +f 303/303/361 310/310/361 200/200/364 +f 200/200/364 310/310/361 305/305/363 +f 309/309/366 293/293/350 311/311/367 +f 298/298/355 312/312/368 299/299/358 +f 312/312/368 298/298/355 313/313/360 +f 293/293/350 314/314/360 301/301/360 +f 314/314/360 307/307/360 315/315/369 +f 307/307/360 314/314/360 293/293/350 +f 227/227/360 306/306/365 316/316/363 +f 309/309/366 311/311/367 227/227/360 +f 309/309/366 227/227/360 316/316/363 +f 312/312/368 313/313/360 317/317/360 +f 312/312/368 317/317/360 318/318/360 +f 318/318/360 317/317/360 315/315/369 +f 315/315/369 317/317/360 314/314/360 +f 194/194/370 220/220/371 208/208/372 +f 208/208/372 220/220/371 240/240/373 +f 208/208/372 240/240/373 211/211/374 +f 211/211/374 240/240/373 237/237/375 +f 211/211/374 237/237/375 213/213/376 +f 213/213/376 237/237/375 236/236/377 +f 213/213/376 236/236/377 210/210/378 +f 210/210/378 236/236/377 232/232/379 +f 210/210/378 232/232/379 217/217/380 +f 217/217/380 232/232/379 244/244/381 +f 217/217/380 244/244/381 215/215/382 +f 215/215/382 244/244/381 231/231/383 +f 215/215/382 231/231/383 216/216/384 +f 216/216/384 231/231/383 230/230/328 +f 216/216/384 230/230/328 207/207/329 +f 194/194/370 238/238/385 220/220/371 +f 238/238/385 194/194/370 205/205/386 +f 238/238/385 205/205/386 218/218/387 +f 218/218/387 205/205/386 202/202/388 +f 218/218/387 202/202/388 219/219/389 +f 219/219/389 202/202/388 198/198/390 +f 219/219/389 198/198/390 226/226/391 +f 226/226/391 198/198/390 199/199/392 +f 226/226/391 199/199/392 222/222/393 +f 222/222/393 199/199/392 197/197/394 +f 222/222/393 197/197/394 224/224/395 +f 224/224/395 197/197/394 193/193/396 +f 224/224/395 193/193/396 225/225/397 +f 225/225/397 193/193/396 195/195/398 +f 225/225/397 195/195/398 223/223/399 +f 223/223/399 195/195/398 196/196/356 +f 223/223/399 196/196/356 221/221/357 +f 319/319/400 320/320/401 321/321/402 +f 322/322/403 323/323/404 324/324/405 +f 322/322/403 325/325/406 323/323/404 +f 324/324/405 323/323/404 326/326/407 +f 324/324/405 326/326/407 327/327/408 +f 327/327/408 326/326/407 328/328/409 +f 329/329/410 319/319/400 321/321/402 +f 330/330/409 295/295/409 331/331/409 +f 331/331/409 295/295/409 296/296/409 +f 332/332/409 295/295/409 333/333/409 +f 333/333/409 295/295/409 330/330/409 +f 327/327/408 328/328/409 296/296/409 +f 296/296/409 328/328/409 331/331/409 +f 320/320/401 330/330/409 334/334/411 +f 320/320/401 334/334/411 321/321/402 +f 295/295/409 332/332/409 335/335/409 +f 295/295/409 335/335/409 336/336/412 +f 330/330/409 320/320/401 337/337/409 +f 330/330/409 337/337/409 333/333/409 +f 334/334/411 325/325/406 321/321/402 +f 321/321/402 325/325/406 322/322/403 +f 336/336/412 335/335/409 338/338/413 +f 336/336/412 338/338/413 329/329/410 +f 329/329/410 338/338/413 319/319/400 +f 339/339/414 340/340/415 341/341/416 +f 340/340/415 339/339/414 342/342/417 +f 340/340/415 342/342/417 343/343/418 +f 343/343/418 342/342/417 321/321/402 +f 343/343/418 321/321/402 322/322/403 +f 339/339/414 341/341/416 344/344/419 +f 344/344/419 341/341/416 345/345/420 +f 344/344/419 345/345/420 346/346/421 +f 346/346/421 345/345/420 347/347/422 +f 347/347/422 345/345/420 348/348/423 +f 347/347/422 348/348/423 349/349/424 +f 349/349/424 348/348/423 350/350/425 +f 349/349/424 350/350/425 351/351/426 +f 351/351/426 350/350/425 352/352/427 +f 351/351/426 352/352/427 353/353/428 +f 353/353/428 352/352/427 354/354/429 +f 353/353/428 354/354/429 355/355/430 +f 353/353/428 355/355/430 356/356/431 +f 356/356/431 355/355/430 357/357/432 +f 307/307/433 308/308/434 358/358/435 +f 359/359/436 306/306/437 300/300/438 +f 359/359/436 360/360/439 306/306/437 +f 306/306/440 360/360/441 316/316/442 +f 316/316/442 360/360/441 361/361/443 +f 316/316/442 361/361/443 362/362/444 +f 316/316/442 362/362/444 309/309/445 +f 309/309/445 362/362/444 363/363/446 +f 358/358/435 308/308/434 363/363/446 +f 363/363/446 308/308/434 309/309/445 +f 364/364/447 307/307/448 358/358/449 +f 365/365/450 312/312/451 318/318/452 +f 365/365/450 318/318/452 366/366/453 +f 366/366/454 318/318/455 364/364/456 +f 364/364/456 318/318/455 315/315/457 +f 364/364/447 315/315/458 307/307/448 +f 367/367/459 312/312/460 365/365/461 +f 367/367/459 299/299/358 312/312/460 +f 359/359/462 300/300/359 367/367/459 +f 367/367/459 300/300/359 299/299/358 +f 332/332/463 368/368/464 335/335/465 +f 335/335/465 368/368/464 369/369/466 +f 335/335/467 369/369/468 370/370/469 +f 335/335/467 370/370/469 338/338/470 +f 338/338/471 370/370/472 319/319/473 +f 319/319/473 370/370/472 371/371/474 +f 319/319/475 371/371/476 320/320/477 +f 320/320/477 371/371/476 372/372/478 +f 320/320/479 372/372/480 337/337/481 +f 337/337/481 372/372/480 373/373/482 +f 337/337/483 373/373/484 333/333/485 +f 333/333/485 373/373/484 374/374/486 +f 333/333/487 374/374/488 332/332/489 +f 332/332/489 374/374/488 368/368/490 +f 369/369/491 363/363/492 362/362/493 +f 369/369/491 362/362/493 370/370/493 +f 370/370/493 362/362/493 361/361/494 +f 370/370/493 361/361/494 360/360/495 +f 370/370/493 360/360/495 371/371/496 +f 371/371/496 360/360/495 359/359/497 +f 371/371/496 359/359/497 372/372/498 +f 372/372/498 359/359/497 367/367/499 +f 372/372/498 367/367/499 373/373/500 +f 373/373/500 367/367/499 365/365/501 +f 373/373/500 365/365/501 366/366/502 +f 373/373/500 366/366/502 374/374/503 +f 374/374/503 366/366/502 364/364/503 +f 374/374/503 364/364/503 368/368/502 +f 368/368/502 364/364/503 358/358/500 +f 368/368/502 358/358/500 369/369/491 +f 369/369/491 358/358/500 363/363/492 +f 302/302/504 301/301/505 375/375/506 +f 298/298/507 376/376/508 377/377/509 +f 377/377/509 313/313/510 298/298/507 +f 377/377/509 378/378/511 313/313/510 +f 313/313/440 378/378/512 317/317/513 +f 317/317/513 378/378/512 379/379/514 +f 317/317/515 379/379/516 380/380/517 +f 317/317/515 380/380/517 314/314/518 +f 375/375/506 301/301/505 380/380/519 +f 380/380/519 301/301/505 314/314/520 +f 381/381/521 302/302/504 375/375/506 +f 382/382/522 304/304/523 305/305/524 +f 382/382/522 305/305/524 383/383/453 +f 383/383/525 305/305/526 384/384/527 +f 384/384/527 305/305/526 310/310/528 +f 384/384/527 310/310/528 381/381/521 +f 381/381/521 310/310/528 302/302/504 +f 376/376/508 304/304/529 382/382/530 +f 376/376/508 297/297/531 304/304/529 +f 376/376/508 298/298/507 297/297/531 +f 331/331/532 385/385/533 330/330/534 +f 330/330/534 385/385/533 386/386/535 +f 330/330/536 386/386/537 334/334/538 +f 334/334/538 386/386/537 387/387/539 +f 334/334/540 387/387/541 325/325/542 +f 325/325/542 387/387/541 388/388/543 +f 325/325/544 388/388/545 323/323/546 +f 323/323/546 388/388/545 389/389/547 +f 323/323/548 389/389/549 326/326/550 +f 326/326/550 389/389/549 390/390/551 +f 326/326/550 390/390/551 328/328/552 +f 328/328/553 390/390/554 385/385/555 +f 328/328/553 385/385/555 331/331/556 +f 388/388/557 376/376/497 389/389/502 +f 389/389/502 376/376/497 382/382/500 +f 389/389/502 382/382/500 383/383/558 +f 389/389/502 383/383/558 390/390/496 +f 390/390/496 383/383/558 384/384/559 +f 390/390/496 384/384/559 381/381/496 +f 390/390/496 381/381/496 385/385/496 +f 385/385/496 381/381/496 375/375/500 +f 385/385/496 375/375/500 380/380/496 +f 385/385/496 380/380/496 386/386/496 +f 386/386/496 380/380/496 379/379/500 +f 386/386/496 379/379/500 387/387/496 +f 387/387/496 379/379/500 378/378/500 +f 387/387/496 378/378/500 377/377/497 +f 387/387/496 377/377/497 376/376/497 +f 387/387/496 376/376/497 388/388/557 +f 255/255/317 251/251/314 290/290/345 +f 290/290/345 391/391/560 255/255/317 +f 391/391/560 290/290/345 392/392/561 +f 391/391/560 392/392/561 357/357/432 +f 357/357/432 392/392/561 356/356/431 +f 260/260/562 393/393/563 394/394/564 +f 260/260/562 394/394/564 259/259/565 +f 259/259/565 394/394/564 395/395/566 +f 259/259/565 395/395/566 262/262/567 +f 262/262/567 395/395/566 396/396/568 +f 262/262/567 396/396/568 258/258/569 +f 258/258/569 396/396/568 397/397/570 +f 258/258/569 397/397/570 263/263/571 +f 263/263/571 397/397/570 398/398/572 +f 263/263/571 398/398/572 265/265/573 +f 265/265/573 398/398/572 399/399/574 +f 265/265/575 399/399/575 264/264/575 +f 264/264/576 399/399/576 393/393/576 +f 264/264/577 393/393/577 260/260/577 +f 399/399/578 400/400/579 401/401/578 +f 399/399/578 401/401/578 393/393/580 +f 393/393/580 401/401/578 402/402/580 +f 393/393/580 402/402/580 394/394/581 +f 394/394/581 402/402/580 403/403/581 +f 394/394/581 403/403/581 395/395/581 +f 395/395/581 403/403/581 404/404/581 +f 395/395/581 404/404/581 396/396/582 +f 396/396/582 404/404/581 405/405/583 +f 396/396/582 405/405/583 397/397/584 +f 397/397/584 405/405/583 406/406/584 +f 397/397/584 406/406/584 407/407/585 +f 397/397/584 407/407/585 398/398/586 +f 398/398/586 407/407/585 408/408/580 +f 398/398/586 408/408/580 399/399/578 +f 399/399/578 408/408/580 400/400/579 +f 268/268/587 267/267/588 407/407/589 +f 402/402/590 285/285/591 270/270/592 +f 402/402/590 401/401/593 285/285/591 +f 285/285/594 401/401/595 288/288/596 +f 288/288/596 401/401/595 400/400/597 +f 288/288/598 400/400/599 286/286/600 +f 286/286/600 400/400/599 408/408/601 +f 407/407/589 267/267/588 408/408/602 +f 408/408/602 267/267/588 286/286/603 +f 406/406/604 268/268/587 407/407/589 +f 403/403/605 279/279/606 404/404/607 +f 404/404/607 279/279/606 280/280/608 +f 404/404/609 280/280/610 405/405/611 +f 405/405/611 280/280/610 282/282/612 +f 405/405/611 282/282/612 406/406/604 +f 406/406/604 282/282/612 268/268/587 +f 403/403/605 269/269/326 279/279/606 +f 402/402/613 269/269/326 403/403/605 +f 402/402/613 270/270/327 269/269/326 +f 249/249/614 409/409/615 410/410/616 +f 249/249/614 410/410/616 250/250/617 +f 250/250/618 410/410/619 253/253/620 +f 253/253/620 410/410/619 411/411/621 +f 253/253/622 411/411/623 412/412/624 +f 253/253/622 412/412/624 246/246/625 +f 246/246/626 412/412/627 247/247/628 +f 247/247/628 412/412/627 413/413/629 +f 247/247/630 413/413/631 414/414/632 +f 247/247/630 414/414/632 254/254/633 +f 254/254/634 414/414/635 256/256/636 +f 256/256/636 414/414/635 415/415/637 +f 256/256/638 415/415/639 249/249/640 +f 249/249/640 415/415/639 409/409/641 +f 410/410/642 416/416/585 417/417/581 +f 410/410/642 417/417/581 411/411/643 +f 411/411/643 417/417/581 418/418/644 +f 411/411/643 418/418/644 419/419/644 +f 411/411/643 419/419/644 412/412/643 +f 412/412/643 419/419/644 420/420/645 +f 412/412/643 420/420/645 413/413/646 +f 413/413/646 420/420/645 421/421/642 +f 413/413/646 421/421/642 414/414/647 +f 414/414/647 421/421/642 422/422/648 +f 414/414/647 422/422/648 415/415/646 +f 415/415/646 422/422/648 423/423/583 +f 415/415/646 423/423/583 424/424/584 +f 415/415/646 424/424/584 409/409/585 +f 409/409/585 424/424/584 416/416/585 +f 409/409/585 416/416/585 410/410/642 +f 274/274/649 276/276/650 420/420/651 +f 424/424/652 273/273/653 272/272/654 +f 424/424/652 423/423/655 273/273/653 +f 273/273/656 423/423/657 283/283/658 +f 283/283/658 423/423/657 422/422/659 +f 283/283/660 422/422/661 277/277/662 +f 277/277/662 422/422/661 421/421/663 +f 420/420/651 276/276/650 421/421/663 +f 421/421/663 276/276/650 277/277/662 +f 419/419/664 274/274/665 420/420/666 +f 417/417/667 284/284/668 289/289/669 +f 417/417/667 289/289/669 418/418/670 +f 418/418/671 289/289/672 419/419/673 +f 419/419/673 289/289/672 287/287/674 +f 419/419/664 287/287/675 274/274/665 +f 416/416/676 284/284/677 417/417/678 +f 416/416/676 278/278/334 284/284/677 +f 424/424/679 272/272/330 416/416/676 +f 416/416/676 272/272/330 278/278/334 +f 241/241/680 291/291/346 243/243/344 +f 228/228/681 425/425/682 229/229/683 +f 229/229/683 425/425/682 344/344/419 +f 344/344/419 346/346/684 229/229/683 +f 229/229/683 346/346/684 234/234/685 +f 234/234/685 346/346/684 347/347/686 +f 234/234/685 347/347/686 235/235/687 +f 235/235/687 347/347/686 349/349/688 +f 235/235/687 349/349/688 426/426/689 +f 426/426/689 351/351/690 239/239/691 +f 239/239/691 351/351/690 353/353/428 +f 239/239/691 353/353/428 241/241/680 +f 241/241/680 353/353/428 291/291/346 +f 426/426/692 239/239/692 235/235/692 +f 212/212/348 292/292/347 209/209/693 +f 209/209/693 292/292/347 355/355/430 +f 355/355/430 354/354/694 209/209/693 +f 209/209/693 354/354/694 427/427/695 +f 427/427/695 354/354/694 352/352/696 +f 427/427/695 352/352/696 428/428/697 +f 428/428/697 352/352/696 350/350/698 +f 428/428/697 348/348/699 204/204/700 +f 204/204/700 348/348/699 345/345/420 +f 204/204/700 345/345/420 429/429/701 +f 429/429/701 345/345/420 430/430/702 +f 209/209/703 427/427/703 203/203/703 +f 203/203/704 427/427/695 428/428/697 +f 203/203/290 428/428/705 204/204/291 +f 429/429/706 201/201/289 204/204/291 +f 290/290/345 291/291/346 392/392/561 +f 392/392/561 291/291/346 356/356/431 +f 353/353/428 356/356/431 291/291/346 +f 349/349/688 351/351/690 426/426/689 +f 344/344/419 425/425/682 339/339/414 +f 339/339/414 425/425/682 342/342/417 +f 342/342/417 425/425/682 321/321/402 +f 425/425/682 228/228/681 233/233/707 +f 425/425/682 233/233/707 321/321/402 +f 321/321/402 233/233/707 329/329/708 +f 357/357/432 292/292/347 391/391/560 +f 391/391/560 292/292/347 255/255/317 +f 355/355/430 292/292/347 357/357/432 +f 341/341/416 430/430/702 345/345/420 +f 350/350/698 348/348/699 428/428/697 +f 343/343/418 430/430/702 340/340/415 +f 341/341/416 340/340/415 430/430/702 +f 343/343/418 324/324/405 429/429/701 +f 322/322/403 324/324/405 343/343/418 +f 343/343/418 429/429/701 430/430/702 +f 201/201/289 429/429/706 324/324/709 +f 201/201/289 324/324/710 200/200/288 +f 324/324/710 327/327/711 200/200/288 +f 327/327/711 303/303/712 200/200/288 +f 327/327/711 296/296/353 303/303/712 +f 296/296/353 294/294/351 303/303/712 +f 336/336/713 293/293/714 295/295/715 +f 336/336/713 311/311/716 293/293/714 +f 336/336/713 227/227/299 311/311/716 +f 329/329/717 227/227/299 336/336/713 +f 233/233/303 227/227/299 329/329/717 +f 275/275/718 245/245/719 248/248/720 +f 275/275/718 248/248/720 281/281/721 +f 281/281/722 248/248/723 214/214/296 +f 281/281/722 214/214/296 206/206/292 +f 242/242/308 243/243/309 261/261/724 +f 261/261/724 257/257/725 242/242/308 +f 257/257/725 271/271/726 242/242/308 +f 257/257/725 252/252/342 271/271/726 +f 252/252/342 266/266/324 271/271/726 +f 431/431/727 432/432/727 433/433/727 +f 433/433/728 432/432/729 434/434/730 +f 433/433/728 434/434/730 435/435/731 +f 435/435/732 434/434/733 436/436/734 +f 435/435/732 436/436/734 437/437/735 +f 437/437/736 436/436/737 438/438/738 +f 437/437/736 438/438/738 439/439/739 +f 439/439/740 438/438/741 440/440/742 +f 439/439/740 440/440/742 441/441/743 +f 441/441/744 440/440/744 442/442/744 +f 441/441/745 442/442/745 443/443/745 +f 443/443/746 442/442/746 444/444/746 +f 443/443/747 444/444/748 445/445/749 +f 445/445/749 444/444/748 446/446/750 +f 447/447/751 445/445/752 448/448/753 +f 448/448/753 445/445/752 446/446/754 +f 447/447/755 448/448/756 449/449/757 +f 447/447/755 449/449/757 450/450/758 +f 450/450/759 449/449/760 451/451/761 +f 450/450/759 451/451/761 452/452/762 +f 452/452/763 451/451/764 453/453/765 +f 453/453/765 451/451/764 454/454/766 +f 453/453/765 454/454/766 455/455/767 +f 453/453/765 455/455/767 456/456/768 +f 456/456/768 455/455/767 457/457/769 +f 456/456/770 457/457/770 458/458/770 +f 458/458/771 457/457/771 459/459/771 +f 458/458/772 459/459/773 460/460/774 +f 460/460/774 459/459/773 461/461/775 +f 460/460/776 461/461/777 462/462/778 +f 460/460/776 462/462/778 463/463/779 +f 463/463/780 462/462/781 464/464/782 +f 463/463/780 464/464/782 465/465/783 +f 465/465/783 464/464/782 466/466/784 +f 465/465/783 466/466/784 467/467/785 +f 465/465/783 467/467/785 468/468/786 +f 431/431/787 468/468/788 432/432/789 +f 432/432/789 468/468/788 467/467/790 +f 468/468/791 431/431/791 433/433/792 +f 468/468/791 433/433/792 465/465/310 +f 443/443/793 452/452/794 441/441/795 +f 441/441/795 452/452/794 453/453/796 +f 443/443/793 450/450/797 452/452/794 +f 445/445/798 447/447/310 450/450/797 +f 445/445/798 450/450/797 443/443/793 +f 437/437/799 460/460/800 435/435/798 +f 441/441/795 456/456/801 439/439/802 +f 441/441/795 453/453/796 456/456/801 +f 435/435/798 465/465/310 433/433/792 +f 435/435/798 463/463/798 465/465/310 +f 435/435/798 460/460/800 463/463/798 +f 439/439/802 458/458/803 437/437/799 +f 437/437/799 458/458/803 460/460/800 +f 439/439/802 456/456/801 458/458/803 +f 448/448/584 446/446/642 444/444/646 +f 448/448/584 444/444/646 449/449/578 +f 440/440/581 454/454/642 442/442/804 +f 442/442/804 454/454/642 451/451/805 +f 442/442/804 451/451/805 449/449/578 +f 442/442/804 449/449/578 444/444/646 +f 440/440/581 455/455/806 454/454/642 +f 438/438/807 457/457/578 440/440/581 +f 440/440/581 457/457/578 455/455/806 +f 438/438/807 459/459/808 457/457/578 +f 436/436/580 459/459/808 438/438/807 +f 436/436/580 461/461/809 459/459/808 +f 432/432/810 467/467/578 466/466/578 +f 432/432/810 466/466/578 434/434/646 +f 434/434/646 462/462/642 436/436/580 +f 436/436/580 462/462/642 461/461/809 +f 466/466/578 464/464/811 434/434/646 +f 434/434/646 464/464/811 462/462/642 +f 469/469/812 470/470/813 471/471/814 +f 472/472/815 473/473/816 474/474/817 +f 475/475/818 476/476/819 477/477/820 +f 478/478/821 479/479/822 480/480/823 +f 469/469/812 471/471/814 481/481/824 +f 471/471/814 482/482/825 481/481/824 +f 483/483/826 484/484/827 485/485/828 +f 482/482/825 486/486/829 481/481/824 +f 485/485/828 484/484/827 478/478/821 +f 485/485/828 478/478/821 480/480/823 +f 486/486/829 483/483/826 481/481/824 +f 481/481/824 483/483/826 485/485/828 +f 477/477/820 476/476/819 472/472/815 +f 472/472/815 476/476/819 473/473/816 +f 480/480/823 479/479/822 475/475/818 +f 480/480/823 475/475/818 477/477/820 +f 472/472/815 474/474/817 470/470/813 +f 472/472/815 470/470/813 469/469/812 +f 487/487/830 488/488/831 489/489/832 +f 487/487/830 490/490/833 488/488/831 +f 491/491/834 490/490/833 487/487/830 +f 487/487/830 492/492/835 491/491/834 +f 493/493/836 494/494/837 495/495/838 +f 493/493/836 495/495/838 496/496/839 +f 496/496/840 495/495/841 497/497/842 +f 496/496/840 497/497/842 498/498/843 +f 498/498/844 497/497/845 499/499/846 +f 499/499/846 497/497/845 500/500/847 +f 499/499/846 500/500/847 501/501/848 +f 501/501/848 500/500/847 502/502/849 +f 501/501/848 502/502/849 503/503/850 +f 503/503/850 502/502/849 504/504/851 +f 503/503/850 504/504/851 505/505/852 +f 505/505/852 504/504/851 506/506/853 +f 505/505/852 506/506/853 507/507/854 +f 507/507/855 506/506/856 494/494/857 +f 507/507/855 494/494/857 493/493/858 +f 493/493/859 508/508/860 509/509/861 +f 493/493/859 509/509/861 507/507/862 +f 496/496/863 510/510/864 511/511/865 +f 496/496/863 511/511/865 493/493/859 +f 493/493/859 511/511/865 508/508/860 +f 503/503/866 512/512/867 513/513/868 +f 503/503/866 513/513/868 501/501/869 +f 505/505/870 514/514/871 512/512/867 +f 505/505/870 512/512/867 503/503/866 +f 507/507/862 509/509/861 515/515/872 +f 507/507/862 515/515/872 516/516/873 +f 507/507/862 516/516/873 505/505/870 +f 505/505/870 516/516/873 514/514/871 +f 499/499/874 517/517/875 518/518/876 +f 499/499/874 518/518/876 498/498/877 +f 498/498/877 518/518/876 510/510/864 +f 498/498/877 510/510/864 496/496/863 +f 501/501/869 513/513/868 519/519/878 +f 501/501/869 519/519/878 517/517/875 +f 501/501/869 517/517/875 499/499/874 +f 509/509/879 471/471/880 515/515/881 +f 471/471/880 470/470/882 515/515/881 +f 515/515/881 470/470/882 516/516/883 +f 470/470/882 474/474/884 516/516/883 +f 516/516/883 474/474/884 514/514/885 +f 474/474/884 473/473/886 514/514/885 +f 514/514/885 473/473/886 512/512/887 +f 512/512/887 473/473/886 476/476/888 +f 512/512/887 476/476/888 513/513/889 +f 476/476/888 475/475/890 513/513/889 +f 513/513/889 475/475/890 519/519/891 +f 519/519/891 475/475/890 479/479/892 +f 519/519/891 479/479/892 517/517/893 +f 479/479/892 478/478/894 517/517/893 +f 517/517/893 478/478/894 518/518/895 +f 518/518/895 478/478/894 484/484/896 +f 518/518/895 484/484/896 510/510/897 +f 510/510/897 484/484/896 483/483/898 +f 510/510/897 483/483/898 511/511/899 +f 483/483/898 486/486/900 511/511/899 +f 511/511/899 486/486/900 508/508/901 +f 486/486/900 482/482/902 508/508/901 +f 508/508/901 482/482/902 509/509/879 +f 509/509/879 482/482/902 471/471/880 +f 480/480/496 477/477/496 520/520/496 +f 520/520/496 477/477/496 521/521/496 +f 485/485/903 480/480/904 522/522/904 +f 522/522/904 480/480/904 520/520/905 +f 481/481/906 485/485/906 523/523/906 +f 523/523/906 485/485/906 522/522/906 +f 469/469/409 481/481/409 524/524/409 +f 524/524/409 481/481/409 523/523/409 +f 472/472/907 469/469/907 525/525/907 +f 525/525/907 469/469/907 524/524/907 +f 477/477/908 472/472/909 521/521/910 +f 521/521/910 472/472/909 525/525/911 +f 524/524/581 523/523/581 525/525/642 +f 525/525/642 523/523/581 522/522/642 +f 525/525/642 522/522/642 521/521/585 +f 521/521/585 522/522/642 520/520/585 +f 494/494/912 487/487/913 489/489/914 +f 494/494/912 489/489/914 495/495/915 +f 495/495/916 489/489/917 488/488/918 +f 495/495/916 488/488/918 497/497/919 +f 497/497/920 488/488/921 490/490/922 +f 497/497/920 490/490/922 500/500/923 +f 500/500/924 490/490/924 502/502/924 +f 502/502/925 490/490/833 491/491/834 +f 502/502/849 491/491/926 504/504/851 +f 504/504/927 491/491/928 492/492/929 +f 504/504/927 492/492/929 506/506/930 +f 506/506/931 492/492/932 487/487/933 +f 506/506/931 487/487/933 494/494/934 +f 526/526/935 527/527/936 528/528/937 +f 529/529/938 530/530/939 531/531/940 +f 532/532/941 533/533/942 534/534/943 +f 535/535/944 536/536/945 537/537/946 +f 526/526/935 528/528/937 538/538/947 +f 526/526/935 538/538/947 539/539/948 +f 538/538/947 540/540/949 539/539/948 +f 541/541/950 535/535/944 542/542/951 +f 542/542/951 535/535/944 537/537/946 +f 540/540/949 543/543/952 539/539/948 +f 539/539/948 543/543/952 542/542/951 +f 542/542/951 543/543/952 541/541/950 +f 532/532/941 534/534/943 529/529/938 +f 529/529/938 534/534/943 530/530/939 +f 536/536/945 544/544/953 537/537/946 +f 537/537/946 544/544/953 532/532/941 +f 532/532/941 544/544/953 533/533/942 +f 529/529/938 531/531/940 526/526/935 +f 526/526/935 531/531/940 527/527/936 +f 545/545/954 546/546/955 547/547/956 +f 548/548/957 549/549/958 545/545/954 +f 547/547/956 548/548/957 545/545/954 +f 550/550/959 551/551/960 552/552/961 +f 550/550/959 552/552/961 553/553/962 +f 553/553/963 552/552/964 554/554/965 +f 553/553/963 554/554/965 555/555/966 +f 555/555/966 554/554/965 556/556/967 +f 555/555/966 556/556/967 557/557/968 +f 557/557/968 556/556/967 558/558/969 +f 557/557/968 558/558/969 559/559/970 +f 559/559/971 558/558/972 560/560/973 +f 559/559/971 560/560/973 561/561/974 +f 561/561/975 560/560/976 562/562/977 +f 562/562/977 560/560/976 563/563/978 +f 562/562/979 563/563/980 564/564/981 +f 562/562/979 564/564/981 565/565/982 +f 565/565/983 564/564/984 551/551/985 +f 565/565/983 551/551/985 550/550/986 +f 550/550/987 566/566/988 567/567/989 +f 550/550/987 567/567/989 565/565/990 +f 553/553/991 568/568/992 566/566/988 +f 553/553/991 566/566/988 550/550/987 +f 561/561/993 569/569/994 559/559/995 +f 559/559/995 569/569/994 570/570/996 +f 562/562/997 571/571/998 572/572/999 +f 562/562/997 572/572/999 561/561/993 +f 561/561/993 572/572/999 569/569/994 +f 567/567/989 573/573/1000 565/565/990 +f 565/565/990 573/573/1000 574/574/1001 +f 565/565/990 574/574/1001 562/562/997 +f 562/562/997 574/574/1001 571/571/998 +f 555/555/1002 575/575/1003 576/576/1004 +f 555/555/1002 576/576/1004 553/553/991 +f 553/553/991 576/576/1004 568/568/992 +f 559/559/995 570/570/996 577/577/1005 +f 559/559/995 577/577/1005 557/557/1006 +f 557/557/1006 577/577/1005 575/575/1003 +f 557/557/1006 575/575/1003 555/555/1002 +f 538/538/1007 528/528/1008 567/567/1009 +f 567/567/1009 528/528/1008 573/573/1010 +f 573/573/1010 528/528/1008 527/527/1011 +f 573/573/1010 527/527/1011 574/574/1012 +f 527/527/1011 531/531/1013 574/574/1012 +f 574/574/1012 531/531/1013 571/571/1014 +f 531/531/1013 530/530/1015 571/571/1014 +f 571/571/1014 530/530/1015 572/572/1016 +f 530/530/1015 534/534/1017 572/572/1016 +f 572/572/1016 534/534/1017 569/569/1018 +f 569/569/1018 534/534/1017 570/570/1019 +f 570/570/1019 534/534/1017 533/533/1020 +f 570/570/1019 533/533/1020 544/544/1021 +f 570/570/1019 544/544/1021 577/577/1022 +f 544/544/1021 536/536/1023 577/577/1022 +f 577/577/1022 536/536/1023 575/575/1024 +f 575/575/1024 536/536/1023 535/535/1025 +f 575/575/1024 535/535/1025 576/576/1026 +f 535/535/1025 541/541/1027 576/576/1026 +f 576/576/1026 541/541/1027 568/568/1028 +f 541/541/1027 543/543/1029 568/568/1028 +f 568/568/1028 543/543/1029 540/540/1030 +f 568/568/1028 540/540/1030 566/566/1031 +f 566/566/1031 540/540/1030 538/538/1007 +f 566/566/1031 538/538/1007 567/567/1009 +f 537/537/310 532/532/310 578/578/310 +f 578/578/310 532/532/310 579/579/310 +f 542/542/1032 537/537/1032 580/580/1032 +f 580/580/1032 537/537/1032 578/578/1032 +f 539/539/1033 542/542/1034 581/581/1035 +f 581/581/1035 542/542/1034 580/580/1036 +f 526/526/642 539/539/642 582/582/642 +f 582/582/642 539/539/642 581/581/642 +f 529/529/1037 526/526/1038 583/583/1039 +f 583/583/1039 526/526/1038 582/582/1040 +f 532/532/1041 529/529/1041 579/579/1041 +f 579/579/1041 529/529/1041 583/583/1041 +f 582/582/497 581/581/497 583/583/496 +f 583/583/496 581/581/497 580/580/496 +f 583/583/496 580/580/496 579/579/500 +f 579/579/500 580/580/496 578/578/500 +f 551/551/960 547/547/1042 552/552/961 +f 552/552/1043 547/547/956 546/546/955 +f 552/552/1043 546/546/955 554/554/1044 +f 554/554/965 546/546/1045 556/556/967 +f 556/556/1046 546/546/955 545/545/954 +f 556/556/967 545/545/1047 558/558/969 +f 558/558/1048 545/545/1049 549/549/1050 +f 558/558/1048 549/549/1050 560/560/1051 +f 560/560/1052 549/549/1052 563/563/1052 +f 563/563/1053 549/549/1054 548/548/1055 +f 563/563/1053 548/548/1055 564/564/1056 +f 564/564/1057 548/548/1058 547/547/1059 +f 564/564/1057 547/547/1059 551/551/1060 +f 584/584/1061 585/585/1062 586/586/1063 +f 586/586/1063 585/585/1062 587/587/1064 +f 586/586/1065 587/587/1066 588/588/1067 +f 588/588/1067 587/587/1066 589/589/1068 +f 588/588/1069 589/589/1070 590/590/1071 +f 590/590/1071 589/589/1070 591/591/1072 +f 590/590/1073 591/591/1074 592/592/1075 +f 592/592/1075 591/591/1074 593/593/1076 +f 592/592/1077 593/593/1078 594/594/1079 +f 592/592/1077 594/594/1079 595/595/1080 +f 595/595/1081 594/594/1082 596/596/1083 +f 596/596/1083 594/594/1082 597/597/1084 +f 596/596/1085 597/597/1086 598/598/1087 +f 596/596/1085 598/598/1087 599/599/1088 +f 599/599/1089 598/598/1090 600/600/1091 +f 599/599/1089 600/600/1091 601/601/1092 +f 602/602/1093 601/601/1094 603/603/1095 +f 603/603/1095 601/601/1094 600/600/1096 +f 602/602/1097 603/603/1098 604/604/1099 +f 604/604/1099 603/603/1098 605/605/1100 +f 604/604/1101 605/605/1102 606/606/1103 +f 606/606/1103 605/605/1102 607/607/1104 +f 606/606/1105 607/607/1106 608/608/1107 +f 608/608/1107 607/607/1106 609/609/1108 +f 608/608/1109 609/609/1110 610/610/1111 +f 608/608/1109 610/610/1111 611/611/1112 +f 611/611/1113 610/610/1114 612/612/1115 +f 612/612/1115 610/610/1114 613/613/1116 +f 612/612/1117 613/613/1118 614/614/1119 +f 612/612/1117 614/614/1119 615/615/1120 +f 615/615/1121 614/614/1122 616/616/1123 +f 615/615/1121 616/616/1123 617/617/1124 +f 617/617/1124 616/616/1123 618/618/1125 +f 617/617/1124 618/618/1125 619/619/1126 +f 619/619/1126 618/618/1125 620/620/1127 +f 619/619/1126 620/620/1127 621/621/1128 +f 621/621/1128 620/620/1127 622/622/1129 +f 584/584/1130 621/621/1131 585/585/1132 +f 585/585/1132 621/621/1131 622/622/1133 +f 601/601/500 602/602/500 599/599/494 +f 621/621/500 584/584/1134 619/619/501 +f 619/619/501 584/584/1134 586/586/501 +f 599/599/494 604/604/1135 606/606/1136 +f 599/599/494 606/606/1136 596/596/1137 +f 599/599/494 602/602/500 604/604/1135 +f 590/590/500 615/615/1138 588/588/494 +f 595/595/496 611/611/1139 592/592/500 +f 596/596/1137 606/606/1136 608/608/495 +f 596/596/1137 608/608/495 595/595/496 +f 595/595/496 608/608/495 611/611/1139 +f 588/588/494 617/617/1140 586/586/501 +f 586/586/501 617/617/1140 619/619/501 +f 588/588/494 615/615/1138 617/617/1140 +f 592/592/500 612/612/1141 590/590/500 +f 590/590/500 612/612/1141 615/615/1138 +f 592/592/500 611/611/1139 612/612/1141 +f 603/603/1142 600/600/1143 598/598/1144 +f 597/597/1145 607/607/1145 605/605/1146 +f 597/597/1145 605/605/1146 598/598/1144 +f 594/594/1147 607/607/1145 597/597/1145 +f 598/598/1144 605/605/1146 603/603/1142 +f 594/594/1147 610/610/1146 609/609/1148 +f 594/594/1147 609/609/1148 607/607/1145 +f 593/593/1149 610/610/1146 594/594/1147 +f 591/591/1150 613/613/1146 593/593/1149 +f 593/593/1149 613/613/1146 610/610/1146 +f 591/591/1150 614/614/1150 613/613/1146 +f 589/589/1145 616/616/1145 614/614/1150 +f 589/589/1145 614/614/1150 591/591/1150 +f 622/622/1151 620/620/1152 585/585/1153 +f 585/585/1153 620/620/1152 587/587/1154 +f 587/587/1154 616/616/1145 589/589/1145 +f 620/620/1152 618/618/1155 587/587/1154 +f 587/587/1154 618/618/1155 616/616/1145 +f 623/623/1156 624/624/1157 625/625/1158 +f 626/626/1159 627/627/1160 628/628/1161 +f 629/629/1162 630/630/1163 631/631/1164 +f 631/631/1164 630/630/1163 632/632/1165 +f 625/625/1158 624/624/1157 633/633/1166 +f 625/625/1158 633/633/1166 634/634/1167 +f 634/634/1167 633/633/1166 635/635/1168 +f 636/636/1169 637/637/1170 629/629/1162 +f 636/636/1169 629/629/1162 631/631/1164 +f 634/634/1167 635/635/1168 638/638/1171 +f 634/634/1167 638/638/1171 636/636/1169 +f 636/636/1169 638/638/1171 637/637/1170 +f 626/626/1159 628/628/1161 639/639/1172 +f 639/639/1172 628/628/1161 640/640/1173 +f 631/631/1164 632/632/1165 626/626/1159 +f 626/626/1159 632/632/1165 627/627/1160 +f 639/639/1172 640/640/1173 623/623/1156 +f 639/639/1172 623/623/1156 625/625/1158 +f 641/641/1174 642/642/1175 643/643/1176 +f 643/643/1176 644/644/1177 641/641/1174 +f 643/643/1176 645/645/1178 646/646/1179 +f 642/642/1175 645/645/1178 643/643/1176 +f 647/647/1180 648/648/1181 649/649/1182 +f 649/649/1182 648/648/1181 650/650/1183 +f 649/649/1182 650/650/1183 651/651/1184 +f 651/651/1184 650/650/1183 652/652/1185 +f 651/651/1184 652/652/1185 653/653/1186 +f 653/653/1186 652/652/1185 654/654/1187 +f 653/653/1188 654/654/1189 655/655/1190 +f 653/653/1188 655/655/1190 656/656/1191 +f 656/656/1192 655/655/1193 657/657/1194 +f 657/657/1194 655/655/1193 658/658/1195 +f 657/657/1196 658/658/1197 659/659/1198 +f 657/657/1196 659/659/1198 660/660/1199 +f 660/660/1200 659/659/1201 661/661/1202 +f 660/660/1200 661/661/1202 662/662/1203 +f 662/662/1204 661/661/1205 663/663/1206 +f 662/662/1204 663/663/1206 647/647/1207 +f 647/647/1180 663/663/1208 648/648/1181 +f 649/649/1209 664/664/1210 647/647/1211 +f 647/647/1211 664/664/1210 665/665/1212 +f 651/651/1213 666/666/1214 649/649/1209 +f 649/649/1209 666/666/1214 667/667/1215 +f 649/649/1209 667/667/1215 664/664/1210 +f 657/657/1216 668/668/1217 669/669/1218 +f 657/657/1216 669/669/1218 656/656/1219 +f 660/660/1220 670/670/1221 671/671/1222 +f 660/660/1220 671/671/1222 657/657/1216 +f 657/657/1216 671/671/1222 668/668/1217 +f 647/647/1211 665/665/1212 662/662/1223 +f 662/662/1223 665/665/1212 672/672/1224 +f 662/662/1223 672/672/1224 670/670/1221 +f 662/662/1223 670/670/1221 660/660/1220 +f 653/653/1225 673/673/1226 651/651/1213 +f 651/651/1213 673/673/1226 666/666/1214 +f 656/656/1219 669/669/1218 674/674/1227 +f 656/656/1219 674/674/1227 653/653/1225 +f 653/653/1225 674/674/1227 673/673/1226 +f 665/665/1228 664/664/1229 633/633/1230 +f 633/633/1230 624/624/1231 665/665/1228 +f 665/665/1228 624/624/1231 672/672/1232 +f 672/672/1232 624/624/1231 623/623/1233 +f 672/672/1232 623/623/1233 670/670/1234 +f 670/670/1234 623/623/1233 640/640/1235 +f 670/670/1234 640/640/1235 671/671/1236 +f 640/640/1235 628/628/1237 671/671/1236 +f 671/671/1236 628/628/1237 668/668/1238 +f 628/628/1237 627/627/1239 668/668/1238 +f 668/668/1238 627/627/1239 669/669/1240 +f 627/627/1239 632/632/1241 669/669/1240 +f 669/669/1240 632/632/1241 674/674/1242 +f 632/632/1241 630/630/1243 674/674/1242 +f 674/674/1242 630/630/1243 673/673/1244 +f 673/673/1244 630/630/1243 629/629/1245 +f 673/673/1244 629/629/1245 637/637/1246 +f 673/673/1244 637/637/1246 666/666/1247 +f 637/637/1246 638/638/1248 666/666/1247 +f 666/666/1247 638/638/1248 667/667/1249 +f 638/638/1248 635/635/1250 667/667/1249 +f 667/667/1249 635/635/1250 633/633/1251 +f 667/667/1249 633/633/1251 664/664/1252 +f 631/631/409 626/626/409 675/675/409 +f 675/675/409 626/626/409 676/676/409 +f 636/636/907 631/631/907 677/677/907 +f 677/677/907 631/631/907 675/675/907 +f 634/634/908 636/636/909 678/678/910 +f 678/678/910 636/636/909 677/677/911 +f 625/625/496 634/634/496 679/679/496 +f 679/679/496 634/634/496 678/678/496 +f 639/639/903 625/625/904 680/680/1253 +f 680/680/1253 625/625/904 679/679/1254 +f 626/626/906 639/639/906 676/676/906 +f 676/676/906 639/639/906 680/680/906 +f 679/679/585 678/678/585 680/680/642 +f 680/680/642 678/678/585 677/677/642 +f 680/680/642 677/677/642 676/676/581 +f 676/676/581 677/677/642 675/675/581 +f 663/663/1255 642/642/1256 648/648/1257 +f 648/648/1257 642/642/1256 641/641/1258 +f 648/648/1259 641/641/1260 650/650/1261 +f 650/650/1261 641/641/1260 644/644/1262 +f 650/650/1183 644/644/1263 652/652/1185 +f 652/652/1264 644/644/1265 643/643/1266 +f 652/652/1264 643/643/1266 654/654/1267 +f 654/654/1189 643/643/1268 655/655/1190 +f 655/655/1269 643/643/1270 646/646/1271 +f 655/655/1269 646/646/1271 658/658/1272 +f 658/658/1272 646/646/1271 659/659/1273 +f 659/659/1273 646/646/1271 645/645/1274 +f 659/659/1275 645/645/1276 661/661/1277 +f 661/661/1277 645/645/1276 642/642/1256 +f 661/661/1277 642/642/1256 663/663/1255 +f 681/681/1278 682/682/1279 683/683/1280 +f 683/683/1280 682/682/1279 684/684/1281 +f 683/683/1282 684/684/1283 685/685/1284 +f 685/685/1284 684/684/1283 686/686/1285 +f 685/685/1286 686/686/1287 687/687/1288 +f 687/687/1288 686/686/1287 688/688/1289 +f 687/687/1290 688/688/1291 689/689/1292 +f 689/689/1292 688/688/1291 690/690/1293 +f 689/689/1294 690/690/1295 691/691/1296 +f 691/691/1296 690/690/1295 692/692/1297 +f 691/691/1298 692/692/1299 693/693/1300 +f 693/693/1300 692/692/1299 694/694/1301 +f 693/693/1302 694/694/1303 695/695/1304 +f 695/695/1304 694/694/1303 696/696/1305 +f 697/697/1306 695/695/1307 698/698/1308 +f 698/698/1308 695/695/1307 696/696/1309 +f 697/697/1310 698/698/1311 699/699/1312 +f 699/699/1312 698/698/1311 700/700/1313 +f 699/699/1314 700/700/1315 701/701/1316 +f 701/701/1316 700/700/1315 702/702/1317 +f 701/701/1318 702/702/1318 703/703/1318 +f 703/703/1319 702/702/1320 704/704/1321 +f 703/703/1319 704/704/1321 705/705/1322 +f 705/705/1323 704/704/1324 706/706/1325 +f 706/706/1325 704/704/1324 707/707/1326 +f 706/706/1325 707/707/1326 708/708/1327 +f 708/708/1327 707/707/1326 709/709/1328 +f 708/708/1327 709/709/1328 710/710/1329 +f 710/710/1330 709/709/1331 711/711/1332 +f 711/711/1332 709/709/1331 712/712/1333 +f 711/711/1334 712/712/1335 713/713/1336 +f 711/711/1334 713/713/1336 714/714/1337 +f 714/714/1338 713/713/1339 715/715/1340 +f 714/714/1338 715/715/1340 716/716/1341 +f 716/716/1341 715/715/1340 717/717/1342 +f 681/681/1343 716/716/1344 682/682/1345 +f 682/682/1345 716/716/1344 717/717/1346 +f 716/716/1142 681/681/1347 683/683/1348 +f 693/693/1349 701/701/1350 703/703/1351 +f 693/693/1349 703/703/1351 691/691/1352 +f 697/697/1353 699/699/1354 695/695/1353 +f 695/695/1353 699/699/1354 693/693/1349 +f 693/693/1349 699/699/1354 701/701/1350 +f 687/687/1145 710/710/1350 711/711/1355 +f 687/687/1145 711/711/1355 685/685/1356 +f 691/691/1352 705/705/1357 689/689/409 +f 689/689/409 705/705/1357 706/706/1358 +f 691/691/1352 703/703/1351 705/705/1357 +f 683/683/1348 714/714/1144 716/716/1142 +f 685/685/1356 711/711/1355 714/714/1144 +f 685/685/1356 714/714/1144 683/683/1348 +f 687/687/1145 708/708/1146 710/710/1350 +f 689/689/409 706/706/1358 708/708/1146 +f 689/689/409 708/708/1146 687/687/1145 +f 698/698/497 696/696/497 694/694/496 +f 698/698/497 694/694/496 700/700/496 +f 692/692/500 702/702/500 694/694/496 +f 702/702/500 700/700/496 694/694/496 +f 690/690/1139 704/704/502 692/692/500 +f 692/692/500 704/704/502 702/702/500 +f 690/690/1139 707/707/1359 704/704/502 +f 688/688/1360 709/709/1359 707/707/1359 +f 688/688/1360 707/707/1359 690/690/1139 +f 686/686/1361 712/712/1362 709/709/1359 +f 686/686/1361 709/709/1359 688/688/1360 +f 682/682/1363 717/717/1134 684/684/1137 +f 684/684/1137 717/717/1134 715/715/494 +f 684/684/1137 712/712/1362 686/686/1361 +f 715/715/494 713/713/1364 684/684/1137 +f 684/684/1137 713/713/1364 712/712/1362 +f 718/718/1365 719/719/1366 720/720/1367 +f 720/720/1367 719/719/1366 721/721/1368 +f 722/722/1369 723/723/1370 724/724/1371 +f 725/725/1372 726/726/1373 727/727/1374 +f 728/728/1375 729/729/1376 730/730/1377 +f 720/720/1367 721/721/1368 731/731/1378 +f 731/731/1378 721/721/1368 732/732/1379 +f 733/733/1380 729/729/1376 734/734/1381 +f 734/734/1381 729/729/1376 728/728/1375 +f 732/732/1379 735/735/1382 731/731/1378 +f 731/731/1378 735/735/1382 734/734/1381 +f 734/734/1381 735/735/1382 733/733/1380 +f 725/725/1372 727/727/1374 722/722/1369 +f 722/722/1369 727/727/1374 723/723/1370 +f 730/730/1377 736/736/1383 728/728/1375 +f 728/728/1375 736/736/1383 725/725/1372 +f 725/725/1372 736/736/1383 726/726/1373 +f 724/724/1371 718/718/1365 722/722/1369 +f 722/722/1369 718/718/1365 720/720/1367 +f 737/737/1384 738/738/1385 739/739/1386 +f 740/740/1387 738/738/1385 737/737/1384 +f 737/737/1384 741/741/1388 740/740/1387 +f 742/742/1389 741/741/1388 737/737/1384 +f 743/743/1390 744/744/1391 745/745/1392 +f 743/743/1390 745/745/1392 746/746/1393 +f 746/746/1394 745/745/1395 747/747/1396 +f 746/746/1394 747/747/1396 748/748/1397 +f 748/748/1397 747/747/1396 749/749/1398 +f 748/748/1397 749/749/1398 750/750/1399 +f 750/750/1399 749/749/1398 751/751/1400 +f 750/750/1399 751/751/1400 752/752/1401 +f 752/752/1401 751/751/1400 741/741/1402 +f 752/752/1401 741/741/1402 753/753/1403 +f 752/752/1401 753/753/1403 754/754/1404 +f 754/754/1405 753/753/1406 755/755/1407 +f 754/754/1405 755/755/1407 756/756/1408 +f 756/756/1409 755/755/1410 757/757/1411 +f 756/756/1409 757/757/1411 758/758/1412 +f 758/758/1412 757/757/1411 744/744/1413 +f 758/758/1412 744/744/1413 743/743/1414 +f 743/743/1415 759/759/1416 760/760/1417 +f 743/743/1415 760/760/1417 758/758/1418 +f 746/746/1419 761/761/1420 759/759/1416 +f 746/746/1419 759/759/1416 743/743/1415 +f 754/754/1421 762/762/1422 752/752/1423 +f 752/752/1423 762/762/1422 763/763/1424 +f 756/756/1425 764/764/1426 765/765/1427 +f 756/756/1425 765/765/1427 754/754/1421 +f 754/754/1421 765/765/1427 762/762/1422 +f 758/758/1418 760/760/1417 766/766/1428 +f 758/758/1418 766/766/1428 756/756/1425 +f 756/756/1425 766/766/1428 764/764/1426 +f 748/748/1429 767/767/1430 768/768/1431 +f 748/748/1429 768/768/1431 746/746/1419 +f 746/746/1419 768/768/1431 761/761/1420 +f 752/752/1423 763/763/1424 750/750/1432 +f 750/750/1432 763/763/1424 769/769/1433 +f 750/750/1432 769/769/1433 767/767/1430 +f 750/750/1432 767/767/1430 748/748/1429 +f 760/760/1434 721/721/1435 766/766/1436 +f 721/721/1435 719/719/1437 766/766/1436 +f 766/766/1436 719/719/1437 718/718/1438 +f 766/766/1436 718/718/1438 764/764/1439 +f 718/718/1438 724/724/1440 764/764/1439 +f 764/764/1439 724/724/1440 765/765/1441 +f 765/765/1441 724/724/1440 723/723/1442 +f 765/765/1441 723/723/1442 762/762/1443 +f 762/762/1443 723/723/1442 727/727/1444 +f 762/762/1443 727/727/1444 763/763/1445 +f 727/727/1444 726/726/1446 763/763/1445 +f 763/763/1445 726/726/1446 736/736/1447 +f 763/763/1445 736/736/1447 769/769/1448 +f 769/769/1448 736/736/1447 730/730/1449 +f 769/769/1448 730/730/1449 767/767/1450 +f 767/767/1450 730/730/1449 729/729/1451 +f 767/767/1450 729/729/1451 768/768/1452 +f 768/768/1452 729/729/1451 733/733/1453 +f 768/768/1452 733/733/1453 761/761/1454 +f 761/761/1454 733/733/1453 735/735/1455 +f 761/761/1454 735/735/1455 732/732/1456 +f 761/761/1454 732/732/1456 759/759/1457 +f 759/759/1457 732/732/1456 760/760/1434 +f 760/760/1434 732/732/1456 721/721/1435 +f 728/728/642 725/725/642 770/770/642 +f 770/770/642 725/725/642 771/771/642 +f 734/734/1037 728/728/1038 772/772/1039 +f 772/772/1039 728/728/1038 770/770/1458 +f 731/731/1041 734/734/1041 773/773/1041 +f 773/773/1041 734/734/1041 772/772/1041 +f 720/720/310 731/731/310 774/774/310 +f 774/774/310 731/731/310 773/773/310 +f 722/722/1032 720/720/1032 775/775/1032 +f 775/775/1032 720/720/1032 774/774/1032 +f 725/725/1033 722/722/1034 771/771/1035 +f 771/771/1035 722/722/1034 775/775/1036 +f 774/774/500 773/773/500 775/775/496 +f 775/775/496 773/773/500 772/772/496 +f 775/775/496 772/772/496 771/771/497 +f 771/771/497 772/772/496 770/770/497 +f 744/744/1391 739/739/1459 745/745/1392 +f 745/745/1460 739/739/1386 738/738/1385 +f 745/745/1460 738/738/1385 747/747/1461 +f 747/747/1462 738/738/1463 749/749/1464 +f 749/749/1464 738/738/1463 740/740/1465 +f 749/749/1464 740/740/1465 751/751/1466 +f 751/751/1466 740/740/1465 741/741/1467 +f 741/741/1468 742/742/1469 753/753/1470 +f 753/753/1470 742/742/1469 755/755/1471 +f 755/755/1471 742/742/1469 737/737/1472 +f 755/755/1410 737/737/1473 757/757/1411 +f 757/757/1474 737/737/1475 739/739/1476 +f 757/757/1474 739/739/1476 744/744/1477 +f 776/776/1478 777/777/1479 778/778/1480 +f 776/776/1478 778/778/1480 779/779/1481 +f 779/779/1482 778/778/1483 780/780/1484 +f 780/780/1484 778/778/1483 781/781/1485 +f 780/780/1486 781/781/1487 782/782/1488 +f 782/782/1488 781/781/1487 783/783/1489 +f 782/782/1490 783/783/1491 784/784/1492 +f 782/782/1490 784/784/1492 785/785/1493 +f 785/785/1494 784/784/1494 786/786/1494 +f 785/785/1495 786/786/1495 787/787/1495 +f 787/787/1496 786/786/1497 788/788/1498 +f 787/787/1496 788/788/1498 789/789/1499 +f 789/789/1499 788/788/1498 790/790/1500 +f 789/789/1501 790/790/1502 791/791/1503 +f 791/791/1503 790/790/1502 792/792/1504 +f 793/793/1505 791/791/1506 794/794/1507 +f 794/794/1507 791/791/1506 792/792/1508 +f 793/793/1509 794/794/1510 795/795/1511 +f 793/793/1509 795/795/1511 796/796/1512 +f 796/796/1513 795/795/1513 797/797/1513 +f 797/797/1514 795/795/1514 798/798/1514 +f 797/797/1515 798/798/1515 799/799/1515 +f 799/799/1516 798/798/1516 800/800/1516 +f 799/799/1517 800/800/1517 801/801/1517 +f 801/801/1518 800/800/1518 802/802/1518 +f 801/801/1519 802/802/1520 803/803/1521 +f 803/803/1521 802/802/1520 804/804/1522 +f 803/803/1521 804/804/1522 805/805/1523 +f 805/805/1523 804/804/1522 806/806/1524 +f 805/805/1523 806/806/1524 807/807/1525 +f 807/807/1526 806/806/1527 808/808/1528 +f 807/807/1526 808/808/1528 809/809/1529 +f 809/809/1530 808/808/1531 810/810/1532 +f 810/810/1532 808/808/1531 811/811/1533 +f 776/776/1534 810/810/1535 777/777/1536 +f 777/777/1536 810/810/1535 811/811/1537 +f 810/810/584 776/776/1538 779/779/1539 +f 789/789/584 797/797/584 787/787/1539 +f 787/787/1539 797/797/584 799/799/581 +f 791/791/1540 793/793/581 796/796/578 +f 791/791/1540 796/796/578 789/789/584 +f 789/789/584 796/796/578 797/797/584 +f 782/782/643 803/803/1541 805/805/1542 +f 782/782/643 805/805/1542 780/780/1543 +f 785/785/581 799/799/581 801/801/580 +f 787/787/1539 799/799/581 785/785/581 +f 779/779/1539 809/809/645 810/810/584 +f 780/780/1543 807/807/645 809/809/645 +f 780/780/1543 809/809/645 779/779/1539 +f 780/780/1543 805/805/1542 807/807/645 +f 782/782/643 801/801/580 803/803/1541 +f 785/785/581 801/801/580 782/782/643 +f 794/794/310 792/792/1544 795/795/1545 +f 795/795/1545 792/792/1544 790/790/310 +f 788/788/1546 798/798/1547 795/795/1545 +f 788/788/1546 795/795/1545 790/790/310 +f 786/786/794 798/798/1547 788/788/1546 +f 786/786/794 800/800/1548 798/798/1547 +f 784/784/1549 800/800/1548 786/786/794 +f 783/783/1546 802/802/798 784/784/1549 +f 784/784/1549 802/802/798 800/800/1548 +f 783/783/1546 804/804/792 802/802/798 +f 781/781/1550 806/806/1551 804/804/792 +f 781/781/1550 804/804/792 783/783/1546 +f 777/777/1552 811/811/1553 778/778/1554 +f 778/778/1554 811/811/1553 808/808/1554 +f 778/778/1554 808/808/1554 781/781/1550 +f 781/781/1550 808/808/1554 806/806/1551 +f 108/108/113 67/67/115 66/66/111 +f 5/5/5 22/22/22 7/7/7 +f 7/7/7 22/22/22 9/9/9 +f 4/4/4 5/5/5 7/7/7 +f 55/55/1555 40/40/40 23/23/23 +f 55/55/1555 23/23/23 24/24/24 +f 55/55/1555 24/24/24 25/25/25 +f 53/53/1556 55/55/1555 25/25/25 +f 25/25/25 41/41/41 53/53/1556 +f 1/1/1 3/3/3 21/21/21 +f 21/21/21 27/27/27 26/26/26 +f 21/21/21 26/26/26 1/1/1 +f 20/20/20 27/27/27 21/21/21 +f 4/4/4 6/6/6 12/12/12 +f 2/2/2 12/12/12 14/14/14 +f 3/3/3 2/2/2 14/14/14 +f 16/16/16 3/3/3 14/14/14 +f 12/12/12 2/2/2 4/4/4 +f 29/29/29 17/17/17 13/13/13 +f 52/52/52 48/48/48 19/19/19 +f 31/31/31 17/17/17 29/29/29 +f 17/17/17 31/31/31 52/52/52 +f 52/52/52 19/19/19 17/17/17 +f 10/10/10 62/62/62 61/61/61 +f 10/10/10 61/61/61 11/11/11 +f 34/34/34 11/11/11 61/61/61 +f 11/11/11 34/34/34 15/15/15 +f 33/33/33 37/37/37 44/44/1557 +f 32/32/32 46/46/1558 30/30/30 +f 46/46/1558 32/32/32 33/33/33 +f 44/44/1557 46/46/1558 33/33/33 +f 36/36/36 30/30/30 46/46/1558 diff --git a/examples/Cassie/urdf/meshes/agility/knee-spring.obj b/examples/Cassie/urdf/meshes/agility/knee-spring.obj new file mode 100644 index 0000000000..c5704d9a2a --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/knee-spring.obj @@ -0,0 +1,5643 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o knee-spring +v -0.000003 0.025000 0.000004 +v -0.000003 -0.025000 0.000004 +v 0.137997 -0.025000 0.000004 +v 0.137997 0.025000 0.000004 +v -0.000003 -0.025000 -0.008496 +v -0.000003 0.025000 -0.008496 +v 0.137997 0.025000 -0.008496 +v 0.137997 -0.025000 -0.008496 +v 0.129997 -0.018345 -0.014296 +v 0.128969 -0.018944 -0.014291 +v 0.129917 -0.017252 -0.014291 +v 0.129997 -0.020655 -0.014296 +v 0.129421 -0.021147 -0.014297 +v 0.133133 -0.022397 -0.014287 +v 0.131192 -0.022481 -0.014289 +v 0.131997 -0.021809 -0.014296 +v 0.131240 -0.016438 -0.014261 +v 0.131997 -0.017191 -0.014296 +v 0.133021 -0.016611 -0.014295 +v 0.133997 -0.020655 -0.014296 +v 0.134600 -0.021162 -0.014293 +v 0.133997 -0.018345 -0.014296 +v 0.134579 -0.017816 -0.014291 +v 0.135078 -0.019581 -0.014281 +v 0.129555 -0.021172 0.004983 +v 0.129565 -0.017787 0.004919 +v 0.129010 -0.019382 0.004919 +v 0.130461 -0.016978 0.004919 +v 0.131643 -0.016547 0.004919 +v 0.133166 -0.016765 0.004919 +v 0.134482 -0.017840 0.004919 +v 0.134984 -0.019618 0.004919 +v 0.134429 -0.021213 0.004919 +v 0.133104 -0.022276 0.004919 +v 0.131108 -0.022375 0.004912 +v 0.128987 -0.019136 -0.010996 +v 0.129660 -0.017544 -0.010996 +v 0.131256 -0.016544 -0.010996 +v 0.132979 -0.016631 -0.010996 +v 0.134506 -0.017740 -0.010996 +v 0.135036 -0.020034 -0.010996 +v 0.133757 -0.022009 -0.010996 +v 0.131299 -0.022529 -0.010996 +v 0.129318 -0.020988 -0.010996 +v 0.126969 -0.017876 -0.010996 +v 0.126731 -0.019924 -0.010996 +v 0.135758 -0.023260 -0.010996 +v 0.137227 -0.020540 -0.010996 +v 0.128868 -0.023793 -0.010996 +v 0.127294 -0.021907 -0.010996 +v 0.133621 -0.024528 -0.010996 +v 0.131387 -0.024761 -0.010996 +v 0.128496 -0.015444 -0.010996 +v 0.137024 -0.017876 -0.010996 +v 0.131387 -0.014239 -0.010996 +v 0.133621 -0.014472 -0.010996 +v 0.135757 -0.015740 -0.010996 +v 0.126804 -0.020439 -0.011659 +v 0.127339 -0.021941 -0.011699 +v 0.128659 -0.023624 -0.011672 +v 0.130038 -0.024354 -0.011801 +v 0.131483 -0.024732 -0.011696 +v 0.133001 -0.024673 -0.011691 +v 0.134287 -0.024184 -0.011823 +v 0.135273 -0.023629 -0.011707 +v 0.136398 -0.022401 -0.011673 +v 0.137200 -0.020406 -0.011685 +v 0.137173 -0.018507 -0.011687 +v 0.136480 -0.016750 -0.011767 +v 0.134958 -0.015128 -0.011697 +v 0.132590 -0.014227 -0.011685 +v 0.130255 -0.014533 -0.011755 +v 0.128610 -0.015476 -0.011686 +v 0.127626 -0.016552 -0.011666 +v 0.126798 -0.018620 -0.011724 +v 0.136399 -0.019725 -0.013129 +v 0.136494 -0.018349 -0.012800 +v 0.135639 -0.018173 -0.013670 +v 0.135448 -0.016700 -0.013069 +v 0.134068 -0.016415 -0.013779 +v 0.134573 -0.015720 -0.012896 +v 0.133319 -0.014899 -0.012604 +v 0.132675 -0.015470 -0.013458 +v 0.131368 -0.014946 -0.012894 +v 0.129600 -0.015518 -0.012820 +v 0.129210 -0.016644 -0.013557 +v 0.128047 -0.016764 -0.012620 +v 0.128375 -0.017807 -0.013567 +v 0.127547 -0.018498 -0.012936 +v 0.128218 -0.020001 -0.013732 +v 0.127492 -0.020594 -0.012847 +v 0.128705 -0.021430 -0.013676 +v 0.128147 -0.022265 -0.012667 +v 0.129883 -0.022476 -0.013871 +v 0.129254 -0.022982 -0.013072 +v 0.131135 -0.023876 -0.013097 +v 0.131782 -0.023447 -0.013601 +v 0.133201 -0.023736 -0.013139 +v 0.134541 -0.023095 -0.013075 +v 0.135412 -0.022254 -0.013167 +v 0.135686 -0.020955 -0.013580 +v 0.136469 -0.021333 -0.012528 +v 0.129997 -0.020655 -0.011996 +v 0.129997 -0.018345 -0.011996 +v 0.131997 -0.021809 -0.011996 +v 0.133997 -0.020655 -0.011996 +v 0.133997 -0.018345 -0.011996 +v 0.131997 -0.017191 -0.011996 +v 0.135201 -0.030040 0.009184 +v 0.135944 -0.030324 0.008132 +v 0.136767 -0.030025 0.007502 +v 0.134904 -0.030375 0.009104 +v 0.136626 -0.030260 0.007015 +v 0.137305 -0.030025 0.005323 +v 0.137014 -0.030317 0.005537 +v 0.136969 -0.030280 0.004189 +v 0.137134 -0.030026 0.003498 +v 0.136534 -0.030321 0.002802 +v 0.134557 -0.030024 0.000320 +v 0.135737 -0.030311 0.001637 +v 0.134743 -0.030277 0.000772 +v 0.132135 -0.030307 -0.000040 +v 0.132299 -0.030031 -0.000336 +v 0.133686 -0.030282 0.000249 +v 0.132028 -0.029000 0.000906 +v 0.133804 -0.029000 -0.002335 +v 0.129796 -0.029000 -0.002293 +v 0.129012 -0.029000 0.002163 +v 0.126791 -0.029000 -0.000436 +v 0.127995 -0.029000 0.004537 +v 0.124449 -0.029000 0.004604 +v 0.128315 -0.029000 0.006756 +v 0.125243 -0.029000 0.001646 +v 0.134600 -0.029000 0.001891 +v 0.136561 -0.029000 -0.001001 +v 0.138868 -0.030000 0.001853 +v 0.138584 -0.029000 0.001297 +v 0.139499 -0.029000 0.004221 +v 0.139538 -0.030000 0.004841 +v 0.137040 -0.030000 -0.000605 +v 0.134184 -0.030000 -0.002251 +v 0.130290 0.019097 0.010848 +v 0.127374 0.015073 0.008917 +v 0.136155 0.016205 0.009407 +v 0.133547 0.019116 0.010863 +v 0.129018 -0.017987 0.010268 +v 0.134213 -0.018675 0.010626 +v 0.136636 -0.015032 0.008898 +v 0.126178 -0.006365 0.006487 +v 0.137915 -0.002342 0.006008 +v 0.126066 0.001029 0.005931 +v 0.137860 0.005372 0.006312 +v 0.134256 -0.030000 0.012186 +v 0.132307 -0.029000 0.012540 +v 0.131447 -0.030000 0.012543 +v 0.135504 -0.029000 0.011720 +v 0.137141 -0.030000 0.010595 +v 0.138002 -0.029000 0.009568 +v 0.139068 -0.030000 0.007628 +v 0.139260 -0.029000 0.007037 +v 0.125997 -0.029000 0.000004 +v 0.137997 0.029000 0.000004 +v 0.137997 -0.029000 0.000004 +v 0.125997 0.029000 0.000004 +v 0.137686 -0.008852 0.006957 +v 0.126867 -0.013334 0.008234 +v 0.137402 0.011398 0.007642 +v 0.131623 -0.019430 0.011039 +v 0.126317 0.008971 0.006981 +v 0.132311 0.029000 0.011068 +v 0.135720 0.029000 0.009835 +v 0.126811 0.029000 0.008273 +v 0.126016 0.029000 0.005591 +v 0.126025 -0.029000 0.005651 +v 0.137892 -0.029000 0.006299 +v 0.137968 0.029000 0.005651 +v 0.129604 -0.029000 0.010536 +v 0.137554 0.029000 0.007343 +v 0.129483 0.029000 0.010487 +v 0.126440 -0.029000 0.007342 +v 0.127691 -0.029000 0.009220 +v 0.132454 -0.029000 0.011062 +v 0.136150 -0.029000 0.009534 +v 0.135939 -0.030032 0.001453 +v 0.136511 -0.033500 0.007221 +v 0.137053 -0.033504 0.004980 +v 0.124586 -0.030000 0.006582 +v 0.124742 -0.030000 0.002817 +v 0.126693 -0.030000 -0.000408 +v 0.130182 -0.030000 -0.002374 +v 0.128607 -0.029000 0.011830 +v 0.128075 -0.030000 0.011487 +v 0.125242 -0.029000 0.008533 +v 0.125864 -0.030000 0.009372 +v 0.135366 -0.033505 0.001233 +v 0.132955 -0.033497 0.000035 +v 0.136575 -0.033500 0.002949 +v 0.132378 -0.034000 0.009045 +v 0.134557 -0.034001 0.009067 +v 0.131201 -0.034001 0.009762 +v 0.134744 -0.034000 0.008017 +v 0.129860 -0.034000 0.008476 +v 0.127997 -0.034002 0.007743 +v 0.128067 -0.034000 0.006165 +v 0.127260 -0.034001 0.004212 +v 0.136309 -0.034000 0.006999 +v 0.136024 -0.034000 0.005541 +v 0.129530 -0.034000 0.001782 +v 0.130794 -0.034000 0.000421 +v 0.131444 -0.034000 0.001013 +v 0.128723 -0.034000 0.001517 +v 0.128210 -0.034000 0.003589 +v 0.136752 -0.034001 0.004330 +v 0.135793 -0.034000 0.003516 +v 0.134919 -0.033502 0.009156 +v 0.133921 -0.030254 0.009678 +v 0.132499 -0.030257 0.010038 +v 0.132195 -0.033504 0.010057 +v 0.130947 -0.030366 0.009919 +v 0.129580 -0.033498 0.009450 +v 0.129697 -0.030301 0.009484 +v 0.128335 -0.030316 0.008476 +v 0.127879 -0.033503 0.007889 +v 0.127429 -0.030311 0.007131 +v 0.127106 -0.033502 0.006170 +v 0.127002 -0.030333 0.005694 +v 0.127044 -0.030033 0.006878 +v 0.126720 -0.030036 0.005334 +v 0.134413 -0.029000 0.008265 +v 0.131966 -0.029000 0.009081 +v 0.135973 -0.029000 0.005995 +v 0.135772 -0.029000 0.003595 +v 0.129829 -0.029000 0.008400 +v 0.135356 -0.034000 0.001599 +v 0.133837 -0.034000 0.001343 +v 0.132961 -0.034000 0.000337 +v 0.130185 -0.030029 0.010044 +v 0.132913 -0.030018 0.010318 +v 0.128177 -0.030037 0.008677 +v 0.127464 -0.030021 0.002141 +v 0.126860 -0.030048 0.003930 +v 0.129231 -0.030019 0.000372 +v 0.127073 -0.033506 0.003859 +v 0.127036 -0.030343 0.004201 +v 0.127394 -0.030291 0.002958 +v 0.128138 -0.030271 0.001737 +v 0.128229 -0.033501 0.001653 +v 0.129461 -0.030271 0.000627 +v 0.130280 -0.033504 0.000248 +v 0.130856 -0.030263 0.000092 +v 0.126120 0.024918 -0.010996 +v 0.126100 0.024897 -0.008496 +v 0.137882 0.024900 -0.008496 +v 0.137899 0.024881 -0.010996 +v 0.137893 -0.024894 -0.008496 +v 0.137872 -0.024914 -0.010996 +v 0.126111 -0.024903 -0.008496 +v 0.126094 -0.024886 -0.010996 +v 0.128831 -0.008560 -0.014259 +v 0.129554 -0.006568 -0.014293 +v 0.129997 -0.007345 -0.014296 +v 0.135025 -0.009104 -0.014280 +v 0.134281 -0.010558 -0.014299 +v 0.133997 -0.009655 -0.014296 +v 0.131997 -0.010809 -0.014296 +v 0.131742 -0.011586 -0.014298 +v 0.129934 -0.010767 -0.014287 +v 0.129997 -0.009655 -0.014296 +v 0.129047 -0.009311 -0.014295 +v 0.131333 -0.005533 -0.014296 +v 0.132997 -0.005625 -0.014292 +v 0.131997 -0.006191 -0.014296 +v 0.134429 -0.006626 -0.014292 +v 0.135070 -0.007797 -0.014247 +v 0.133997 -0.007345 -0.014296 +v 0.130066 -0.010714 0.004990 +v 0.129549 -0.006750 0.004911 +v 0.129021 -0.008521 0.004922 +v 0.131337 -0.005567 0.004920 +v 0.133167 -0.005765 0.004919 +v 0.134145 -0.006472 0.004919 +v 0.134812 -0.007540 0.004919 +v 0.134931 -0.008911 0.004919 +v 0.134429 -0.010213 0.004919 +v 0.133074 -0.011286 0.004929 +v 0.131399 -0.011415 0.004922 +v 0.129362 -0.009904 0.004902 +v 0.128987 -0.008136 -0.010996 +v 0.129660 -0.006544 -0.010996 +v 0.131256 -0.005544 -0.010996 +v 0.133444 -0.005775 -0.010996 +v 0.134859 -0.007454 -0.010996 +v 0.134953 -0.009177 -0.010996 +v 0.133659 -0.011157 -0.010996 +v 0.131160 -0.011430 -0.010996 +v 0.129382 -0.010137 -0.010996 +v 0.126969 -0.006876 -0.010996 +v 0.126766 -0.009540 -0.010996 +v 0.136700 -0.010906 -0.010996 +v 0.135421 -0.012524 -0.010996 +v 0.128496 -0.012556 -0.010996 +v 0.137315 -0.008500 -0.010996 +v 0.133621 -0.013528 -0.010996 +v 0.131387 -0.013761 -0.010996 +v 0.128496 -0.004444 -0.010996 +v 0.136700 -0.006094 -0.010996 +v 0.131387 -0.003239 -0.010996 +v 0.133621 -0.003472 -0.010996 +v 0.135422 -0.004477 -0.010996 +v 0.126758 -0.008930 -0.011736 +v 0.127269 -0.010887 -0.011723 +v 0.128463 -0.012395 -0.011738 +v 0.129836 -0.013283 -0.011799 +v 0.131511 -0.013735 -0.011696 +v 0.133523 -0.013582 -0.011692 +v 0.135720 -0.012248 -0.011695 +v 0.136709 -0.010807 -0.011771 +v 0.137279 -0.008884 -0.011664 +v 0.137023 -0.006961 -0.011716 +v 0.136372 -0.005638 -0.011865 +v 0.135375 -0.004496 -0.011763 +v 0.133962 -0.003581 -0.011666 +v 0.131766 -0.003223 -0.011675 +v 0.129817 -0.003746 -0.011852 +v 0.128410 -0.004621 -0.011654 +v 0.127626 -0.005608 -0.011783 +v 0.126859 -0.007350 -0.011701 +v 0.136173 -0.009547 -0.013244 +v 0.136246 -0.007431 -0.013153 +v 0.136796 -0.008978 -0.012575 +v 0.135332 -0.006038 -0.013398 +v 0.134508 -0.004542 -0.012771 +v 0.134142 -0.005356 -0.013732 +v 0.133349 -0.004217 -0.013055 +v 0.132124 -0.004781 -0.013802 +v 0.131356 -0.003943 -0.012888 +v 0.130376 -0.004847 -0.013557 +v 0.129057 -0.005654 -0.013474 +v 0.128778 -0.005125 -0.012746 +v 0.127777 -0.006853 -0.012983 +v 0.127573 -0.008025 -0.013057 +v 0.127589 -0.009284 -0.013006 +v 0.128569 -0.010148 -0.013745 +v 0.128070 -0.011014 -0.012826 +v 0.129443 -0.011872 -0.013303 +v 0.130915 -0.012071 -0.013804 +v 0.130643 -0.012884 -0.012865 +v 0.132112 -0.012913 -0.013119 +v 0.133321 -0.012080 -0.013722 +v 0.133413 -0.012906 -0.012803 +v 0.134665 -0.012457 -0.012614 +v 0.134418 -0.011554 -0.013650 +v 0.135512 -0.010860 -0.013338 +v 0.129997 -0.009655 -0.011996 +v 0.129997 -0.007345 -0.011996 +v 0.131997 -0.010809 -0.011996 +v 0.133997 -0.009655 -0.011996 +v 0.133997 -0.007345 -0.011996 +v 0.131997 -0.006191 -0.011996 +v 0.132640 -0.024499 0.007202 +v 0.134122 -0.024499 0.005999 +v 0.130812 -0.024497 0.007020 +v 0.129706 -0.024498 0.005301 +v 0.130438 -0.024494 0.003230 +v 0.132943 -0.024494 0.002840 +v 0.134144 -0.024500 0.004257 +v 0.131754 -0.025251 0.008040 +v 0.130245 -0.025248 0.007468 +v 0.131362 -0.034500 0.008044 +v 0.129371 -0.034500 0.006581 +v 0.129135 -0.025249 0.006092 +v 0.128974 -0.034500 0.004770 +v 0.129195 -0.025251 0.003692 +v 0.129645 -0.034500 0.003042 +v 0.130645 -0.025248 0.002300 +v 0.131526 -0.034500 0.001977 +v 0.132382 -0.025249 0.001966 +v 0.133641 -0.034500 0.002419 +v 0.134472 -0.025251 0.003147 +v 0.134732 -0.034500 0.003724 +v 0.135032 -0.034500 0.005403 +v 0.135018 -0.025247 0.005083 +v 0.134532 -0.025253 0.006710 +v 0.133910 -0.034500 0.007422 +v 0.133265 -0.025250 0.007744 +v 0.129757 -0.034500 0.011535 +v 0.133933 -0.034500 0.011632 +v 0.127222 -0.034500 0.009872 +v 0.125328 -0.034500 0.003215 +v 0.125517 -0.034500 0.007388 +v 0.132392 -0.034500 -0.001890 +v 0.138321 -0.034500 0.007670 +v 0.136711 -0.034500 0.009948 +v 0.136295 -0.034500 -0.000400 +v 0.138438 -0.034500 0.002636 +v 0.128991 -0.034500 -0.001147 +v 0.126957 -0.034500 0.000393 +v 0.138814 -0.034500 0.005171 +v 0.134151 -0.035325 -0.001533 +v 0.132091 -0.035329 -0.000176 +v 0.130207 -0.035325 -0.001665 +v 0.137857 -0.035325 0.008657 +v 0.137154 -0.035328 0.005289 +v 0.138859 -0.035325 0.005078 +v 0.136494 -0.035326 0.002404 +v 0.138365 -0.035325 0.002564 +v 0.137063 -0.035325 0.000375 +v 0.134640 -0.035327 0.000585 +v 0.130074 -0.035325 0.011592 +v 0.129861 -0.035329 0.009679 +v 0.131178 -0.035343 0.010092 +v 0.132629 -0.035325 0.011794 +v 0.129107 -0.035327 0.000741 +v 0.126899 -0.035325 0.009661 +v 0.135088 -0.035325 0.011131 +v 0.133143 -0.035328 0.010011 +v 0.134867 -0.035325 0.009268 +v 0.136511 -0.035327 0.007487 +v 0.125263 -0.035325 0.006328 +v 0.127821 -0.035336 0.008064 +v 0.127208 -0.035325 0.000112 +v 0.125460 -0.035325 0.002850 +v 0.127501 -0.035327 0.002464 +v 0.126861 -0.035326 0.005297 +v 0.132827 -0.037794 0.007959 +v 0.131997 -0.037794 0.007323 +v 0.133164 -0.037800 0.007026 +v 0.130460 -0.037791 0.007669 +v 0.130829 -0.037800 0.007026 +v 0.134985 -0.037786 0.005836 +v 0.134077 -0.037776 0.003926 +v 0.134875 -0.037790 0.003825 +v 0.131498 -0.037778 0.008057 +v 0.134081 -0.037789 0.007264 +v 0.134017 -0.037792 0.006154 +v 0.132110 -0.037778 0.002660 +v 0.133551 -0.037797 0.002350 +v 0.130829 -0.037800 0.002982 +v 0.130531 -0.037798 0.002313 +v 0.129977 -0.037792 0.003854 +v 0.131893 -0.037797 0.001971 +v 0.129342 -0.037797 0.003536 +v 0.129917 -0.037775 0.006075 +v 0.128934 -0.037799 0.005018 +v 0.129245 -0.037788 0.006450 +v 0.128183 -0.037123 0.004144 +v 0.129426 -0.037328 0.002377 +v 0.132753 -0.037238 0.001317 +v 0.134918 -0.037012 0.002246 +v 0.135664 -0.037289 0.004407 +v 0.135481 -0.036974 0.007058 +v 0.133391 -0.036891 0.008919 +v 0.130769 -0.037179 0.001376 +v 0.133684 -0.036687 0.001021 +v 0.132049 -0.036710 0.009296 +v 0.130586 -0.036833 0.008938 +v 0.129144 -0.036582 0.008377 +v 0.127748 -0.036733 0.005415 +v 0.128210 -0.036738 0.003021 +v 0.131882 -0.036676 0.000677 +v 0.136336 -0.036613 0.005420 +v 0.135216 -0.036402 0.008216 +v 0.127881 -0.036479 0.006809 +v 0.135837 -0.036278 0.002468 +v 0.136300 -0.036511 0.003835 +v 0.130108 -0.036361 0.000843 +v 0.134770 -0.036265 0.001292 +v 0.134053 -0.036255 0.009148 +v 0.128760 -0.036313 0.001757 +v 0.136397 -0.036102 0.006702 +v 0.127327 -0.036015 0.004059 +v 0.133997 -0.037473 0.005153 +v 0.132960 -0.037457 0.006757 +v 0.131034 -0.037457 0.006757 +v 0.129997 -0.037473 0.004855 +v 0.130942 -0.037468 0.003304 +v 0.133088 -0.037466 0.003325 +v 0.133997 -0.035490 0.006159 +v 0.131997 -0.035490 0.007313 +v 0.133997 -0.035490 0.003849 +v 0.129997 -0.035490 0.006159 +v 0.131997 -0.035490 0.002695 +v 0.129997 -0.035490 0.003849 +v 0.124558 0.030000 0.003662 +v 0.124536 0.029000 0.006111 +v 0.124742 0.030000 0.007191 +v 0.125365 0.029000 0.008569 +v 0.126388 0.030000 0.010047 +v 0.126954 0.029000 0.010613 +v 0.129058 0.030000 0.011988 +v 0.129809 0.029000 0.012259 +v 0.132307 0.030000 0.012540 +v 0.133104 0.029000 0.012465 +v 0.134835 0.030000 0.011978 +v 0.136192 0.029000 0.011313 +v 0.137226 0.030000 0.010462 +v 0.138451 0.029000 0.008907 +v 0.138839 0.030000 0.008145 +v 0.139486 0.029000 0.006026 +v 0.139612 0.030000 0.004687 +v 0.139260 0.029000 0.002970 +v 0.138452 0.030000 0.001101 +v 0.138002 0.029000 0.000439 +v 0.136379 0.030000 -0.001155 +v 0.135704 0.029000 -0.001583 +v 0.133570 0.030000 -0.002373 +v 0.132074 0.029000 -0.002594 +v 0.129796 0.030000 -0.002293 +v 0.127778 0.029000 -0.001343 +v 0.126094 0.030000 0.000220 +v 0.124853 0.029000 0.002349 +v 0.132828 0.029000 0.001048 +v 0.134950 0.029000 0.002193 +v 0.130935 0.029000 0.001117 +v 0.129272 0.029000 0.002018 +v 0.135762 0.029000 0.006406 +v 0.134732 0.029000 0.008003 +v 0.136028 0.029000 0.004536 +v 0.132891 0.029000 0.008933 +v 0.130996 0.029000 0.008921 +v 0.128234 0.029000 0.006481 +v 0.128026 0.029000 0.004079 +v 0.129331 0.029000 0.008025 +v 0.128059 0.034000 0.005920 +v 0.129369 0.034000 0.008148 +v 0.131965 0.034000 0.009063 +v 0.134271 0.034000 0.008366 +v 0.135515 0.034000 0.006946 +v 0.136088 0.034000 0.004771 +v 0.135084 0.034000 0.002394 +v 0.133392 0.034000 0.001210 +v 0.130986 0.034000 0.001054 +v 0.129213 0.034000 0.002106 +v 0.128158 0.034000 0.003686 +v 0.130484 0.034001 0.000424 +v 0.128184 0.034000 0.002169 +v 0.133730 0.034000 0.000546 +v 0.127322 0.034000 0.004155 +v 0.127680 0.034002 0.007209 +v 0.136650 0.034000 0.006033 +v 0.136314 0.034002 0.002799 +v 0.130599 0.034001 0.009621 +v 0.135687 0.034000 0.007976 +v 0.133839 0.034000 0.009418 +v 0.127139 0.033507 0.003664 +v 0.126962 0.030298 0.005101 +v 0.127102 0.033510 0.006333 +v 0.127079 0.030274 0.003892 +v 0.127512 0.030374 0.002743 +v 0.127994 0.033501 0.001978 +v 0.128438 0.030278 0.001411 +v 0.129912 0.033499 0.000350 +v 0.129770 0.030293 0.000480 +v 0.130892 0.030281 0.000088 +v 0.132088 0.030242 -0.000048 +v 0.132966 0.033504 0.000041 +v 0.133396 0.030354 0.000178 +v 0.134472 0.030251 0.000607 +v 0.135686 0.033498 0.001483 +v 0.135567 0.030265 0.001425 +v 0.136628 0.030365 0.002984 +v 0.136996 0.033508 0.004255 +v 0.137043 0.030261 0.004854 +v 0.136946 0.030263 0.005965 +v 0.136836 0.033500 0.006334 +v 0.136446 0.030262 0.007436 +v 0.135673 0.033508 0.008532 +v 0.135325 0.030286 0.008790 +v 0.134133 0.030280 0.009578 +v 0.133157 0.033501 0.009912 +v 0.132842 0.030316 0.009962 +v 0.131027 0.033497 0.009940 +v 0.131510 0.030266 0.010027 +v 0.130391 0.030328 0.009773 +v 0.128742 0.033501 0.008901 +v 0.129126 0.030268 0.009152 +v 0.128080 0.030261 0.008188 +v 0.127232 0.030321 0.006695 +v 0.128567 0.030049 0.001026 +v 0.129970 0.030030 0.000084 +v 0.127279 0.030042 0.002616 +v 0.126664 0.030017 0.004434 +v 0.132027 0.030026 -0.000341 +v 0.134330 0.030023 0.000180 +v 0.135989 0.030019 0.001400 +v 0.136971 0.030045 0.003294 +v 0.137399 0.030017 0.005489 +v 0.126930 0.030031 0.006693 +v 0.133461 0.030045 0.010079 +v 0.131502 0.030034 0.010276 +v 0.130064 0.030037 0.009916 +v 0.136781 0.030028 0.007318 +v 0.135626 0.030040 0.008845 +v 0.128397 0.030046 0.008843 +v 0.133556 0.024494 0.003230 +v 0.134285 0.024497 0.005421 +v 0.132724 0.024498 0.007277 +v 0.131409 0.024498 0.002770 +v 0.129890 0.024497 0.004018 +v 0.130092 0.024492 0.006433 +v 0.132703 0.025248 0.007984 +v 0.134328 0.025247 0.006949 +v 0.132941 0.034500 0.007963 +v 0.134686 0.034500 0.006436 +v 0.134974 0.025253 0.005547 +v 0.135016 0.034500 0.004926 +v 0.134864 0.025247 0.004006 +v 0.134538 0.034500 0.003294 +v 0.133713 0.025249 0.002468 +v 0.132777 0.034500 0.002042 +v 0.131997 0.025253 0.001978 +v 0.131079 0.034500 0.002127 +v 0.130501 0.025247 0.002362 +v 0.129531 0.034500 0.003153 +v 0.129403 0.025253 0.003446 +v 0.128941 0.025247 0.005171 +v 0.128969 0.034500 0.005084 +v 0.129398 0.034500 0.006565 +v 0.129665 0.025247 0.006949 +v 0.130635 0.034500 0.007729 +v 0.130929 0.025253 0.007836 +v 0.132629 0.034500 0.011905 +v 0.128132 0.034500 0.010756 +v 0.136270 0.034500 0.010374 +v 0.138838 0.034500 0.005546 +v 0.138030 0.034500 0.008209 +v 0.132071 0.034500 -0.001858 +v 0.125673 0.034500 0.007670 +v 0.136917 0.034500 0.000191 +v 0.138457 0.034500 0.002783 +v 0.129122 0.034500 -0.001209 +v 0.134560 0.034500 -0.001315 +v 0.126400 0.034500 0.000960 +v 0.125156 0.034500 0.004462 +v 0.128951 0.035325 -0.001221 +v 0.132508 0.035326 -0.000121 +v 0.132164 0.035325 -0.001813 +v 0.125134 0.035325 0.005078 +v 0.126885 0.035326 0.005437 +v 0.127059 0.035330 0.003494 +v 0.126245 0.035325 0.008869 +v 0.127660 0.035327 0.007803 +v 0.125961 0.035325 0.001697 +v 0.128358 0.035335 0.001318 +v 0.130417 0.035328 0.000120 +v 0.134576 0.035325 0.011346 +v 0.132512 0.035328 0.010117 +v 0.132067 0.035325 0.011835 +v 0.135106 0.035325 -0.001162 +v 0.134278 0.035328 0.000414 +v 0.137681 0.035325 0.001189 +v 0.136452 0.035329 0.002468 +v 0.138880 0.035325 0.004457 +v 0.137063 0.035357 0.004007 +v 0.136711 0.035325 0.009948 +v 0.135080 0.035326 0.009169 +v 0.138210 0.035325 0.007878 +v 0.136662 0.035330 0.007148 +v 0.129331 0.035325 0.011328 +v 0.129993 0.035326 0.009775 +v 0.135561 0.035329 0.001290 +v 0.137069 0.035327 0.005799 +v 0.130895 0.037788 0.007890 +v 0.132001 0.037790 0.007325 +v 0.130829 0.037800 0.007026 +v 0.132879 0.037801 0.007968 +v 0.133164 0.037800 0.007026 +v 0.132594 0.037803 0.001951 +v 0.130829 0.037800 0.002982 +v 0.131997 0.037790 0.002683 +v 0.129423 0.037794 0.006669 +v 0.129987 0.037787 0.006167 +v 0.133165 0.037800 0.002982 +v 0.134857 0.037801 0.003830 +v 0.134007 0.037792 0.003846 +v 0.129662 0.037800 0.005004 +v 0.128920 0.037802 0.004621 +v 0.129989 0.037792 0.003842 +v 0.130181 0.037800 0.002548 +v 0.134332 0.037800 0.005004 +v 0.134005 0.037794 0.006163 +v 0.134999 0.037794 0.005740 +v 0.134339 0.037772 0.007043 +v 0.129622 0.037359 0.007749 +v 0.130743 0.037095 0.008780 +v 0.134136 0.037150 0.008236 +v 0.134068 0.037333 0.001992 +v 0.130709 0.036973 0.001136 +v 0.128979 0.037136 0.002509 +v 0.128185 0.037218 0.004889 +v 0.128302 0.037053 0.006441 +v 0.132503 0.037256 0.001266 +v 0.127819 0.036621 0.003695 +v 0.132698 0.036973 0.009016 +v 0.135533 0.037132 0.006678 +v 0.136254 0.036759 0.005163 +v 0.135208 0.037197 0.002992 +v 0.128425 0.036563 0.007612 +v 0.135979 0.036674 0.003291 +v 0.129349 0.036335 0.001273 +v 0.135190 0.036350 0.001770 +v 0.133557 0.036469 0.000779 +v 0.131843 0.036303 0.000413 +v 0.127442 0.036298 0.005785 +v 0.129219 0.036109 0.008823 +v 0.134981 0.036325 0.008490 +v 0.131056 0.036077 0.009669 +v 0.133826 0.036140 0.009318 +v 0.135995 0.036355 0.007235 +v 0.129997 0.037466 0.004898 +v 0.131126 0.037473 0.006810 +v 0.133126 0.037473 0.006662 +v 0.133997 0.037466 0.005110 +v 0.133089 0.037466 0.003325 +v 0.130997 0.037473 0.003272 +v 0.129997 0.035490 0.006159 +v 0.131997 0.035490 0.007313 +v 0.129997 0.035490 0.003849 +v 0.133997 0.035490 0.006159 +v 0.131997 0.035490 0.002695 +v 0.133997 0.035490 0.003849 +v 0.133949 0.021881 -0.014286 +v 0.134955 0.020225 -0.014296 +v 0.133997 0.020655 -0.014296 +v 0.131997 0.021809 -0.014296 +v 0.132035 0.022573 -0.014291 +v 0.129997 0.020655 -0.014296 +v 0.129058 0.020310 -0.014292 +v 0.130228 0.022005 -0.014297 +v 0.132899 0.016561 -0.014287 +v 0.131997 0.017191 -0.014296 +v 0.133997 0.018345 -0.014296 +v 0.134749 0.018075 -0.014296 +v 0.131726 0.016449 -0.014288 +v 0.129895 0.017248 -0.014295 +v 0.129997 0.018345 -0.014296 +v 0.129059 0.018710 -0.014294 +v 0.129615 0.021263 0.004989 +v 0.134784 0.018489 0.004923 +v 0.134954 0.019710 0.004923 +v 0.134027 0.017318 0.004909 +v 0.132651 0.016592 0.004909 +v 0.131151 0.016651 0.004930 +v 0.129699 0.017589 0.004919 +v 0.129082 0.019002 0.004930 +v 0.132097 0.022463 0.004923 +v 0.130903 0.022248 0.004930 +v 0.133445 0.022105 0.004909 +v 0.134561 0.021001 0.004929 +v 0.134927 0.020399 -0.010996 +v 0.134902 0.018675 -0.010996 +v 0.134010 0.017189 -0.010996 +v 0.132425 0.016510 -0.010996 +v 0.130397 0.016835 -0.010996 +v 0.128989 0.018913 -0.010996 +v 0.129100 0.020220 0.004902 +v 0.129247 0.020777 -0.010996 +v 0.130509 0.022179 -0.010996 +v 0.133170 0.022406 -0.010996 +v 0.137025 0.017876 -0.010996 +v 0.137263 0.019923 -0.010996 +v 0.128867 0.023793 -0.010996 +v 0.127084 0.021535 -0.010996 +v 0.136700 0.021907 -0.010996 +v 0.126731 0.019076 -0.010996 +v 0.135422 0.023523 -0.010996 +v 0.133621 0.024528 -0.010996 +v 0.136020 0.016076 -0.010996 +v 0.127294 0.017093 -0.010996 +v 0.131387 0.024761 -0.010996 +v 0.134404 0.014797 -0.010996 +v 0.131812 0.014167 -0.010996 +v 0.128868 0.015207 -0.010996 +v 0.137186 0.020380 -0.011729 +v 0.136693 0.021883 -0.011670 +v 0.135800 0.023148 -0.011694 +v 0.134767 0.023958 -0.011725 +v 0.133458 0.024545 -0.011724 +v 0.131497 0.024781 -0.011686 +v 0.128950 0.023815 -0.011696 +v 0.127498 0.022251 -0.011687 +v 0.126875 0.020741 -0.011676 +v 0.126754 0.018792 -0.011725 +v 0.127728 0.016408 -0.011704 +v 0.129212 0.015037 -0.011752 +v 0.130626 0.014427 -0.011742 +v 0.132829 0.014276 -0.011714 +v 0.135104 0.015226 -0.011676 +v 0.136473 0.016726 -0.011713 +v 0.137171 0.018496 -0.011677 +v 0.128191 0.018912 -0.013707 +v 0.127343 0.018714 -0.012690 +v 0.127490 0.019869 -0.012956 +v 0.128533 0.017802 -0.013677 +v 0.128030 0.016828 -0.012655 +v 0.129404 0.016532 -0.013591 +v 0.129755 0.015522 -0.012908 +v 0.130796 0.015795 -0.013662 +v 0.131449 0.014791 -0.012654 +v 0.132438 0.015380 -0.013403 +v 0.133723 0.015053 -0.012607 +v 0.134272 0.015930 -0.013342 +v 0.134753 0.017272 -0.013976 +v 0.135550 0.016498 -0.012777 +v 0.136300 0.017789 -0.012833 +v 0.135612 0.018864 -0.013847 +v 0.136561 0.019543 -0.012940 +v 0.135829 0.020275 -0.013627 +v 0.136292 0.021443 -0.012705 +v 0.135231 0.021444 -0.013746 +v 0.135147 0.022543 -0.013165 +v 0.134377 0.023450 -0.012854 +v 0.133224 0.022962 -0.013830 +v 0.132858 0.023880 -0.013044 +v 0.131467 0.023870 -0.013139 +v 0.130235 0.024009 -0.012485 +v 0.130412 0.023068 -0.013634 +v 0.129284 0.023058 -0.013044 +v 0.129147 0.021647 -0.013915 +v 0.128313 0.022343 -0.012783 +v 0.127932 0.020946 -0.013250 +v 0.133997 0.020655 -0.011996 +v 0.133997 0.018345 -0.011996 +v 0.131997 0.021809 -0.011996 +v 0.129997 0.020655 -0.011996 +v 0.129997 0.018345 -0.011996 +v 0.131997 0.017191 -0.011996 +v 0.133941 0.010841 -0.014296 +v 0.134860 0.009601 -0.014285 +v 0.133997 0.009655 -0.014296 +v 0.133997 0.007345 -0.014296 +v 0.135051 0.008024 -0.014289 +v 0.134342 0.006411 -0.014270 +v 0.131997 0.010809 -0.014296 +v 0.132626 0.011479 -0.014293 +v 0.131350 0.011515 -0.014286 +v 0.132548 0.005520 -0.014296 +v 0.130694 0.005728 -0.014293 +v 0.131997 0.006191 -0.014296 +v 0.129997 0.009655 -0.014296 +v 0.129470 0.010358 -0.014276 +v 0.129997 0.007345 -0.014296 +v 0.129402 0.006845 -0.014294 +v 0.128915 0.008356 -0.014284 +v 0.133935 0.010713 0.004986 +v 0.134874 0.007760 0.004907 +v 0.134880 0.009307 0.004910 +v 0.134341 0.006696 0.004930 +v 0.133106 0.005720 0.004911 +v 0.131108 0.005630 0.004939 +v 0.129614 0.006709 0.004909 +v 0.129123 0.007819 0.004919 +v 0.129087 0.009101 0.004929 +v 0.129658 0.010323 0.004923 +v 0.130741 0.011203 0.004909 +v 0.132426 0.011458 0.004919 +v 0.134857 0.009716 -0.010996 +v 0.134902 0.007675 -0.010996 +v 0.133898 0.006070 -0.010996 +v 0.131788 0.005460 -0.010996 +v 0.129528 0.006570 -0.010996 +v 0.129031 0.009348 -0.010996 +v 0.130379 0.011082 -0.010996 +v 0.132695 0.011529 -0.010996 +v 0.137025 0.006876 -0.010996 +v 0.137263 0.008923 -0.010996 +v 0.127973 0.011924 -0.010996 +v 0.126969 0.010124 -0.010996 +v 0.136431 0.011463 -0.010996 +v 0.134403 0.013203 -0.010996 +v 0.126731 0.008076 -0.010996 +v 0.129962 0.013413 -0.010996 +v 0.135758 0.004740 -0.010996 +v 0.127293 0.006094 -0.010996 +v 0.133621 0.003472 -0.010996 +v 0.132421 0.013766 -0.010996 +v 0.131387 0.003239 -0.010996 +v 0.128868 0.004207 -0.010996 +v 0.137267 0.008744 -0.011698 +v 0.136751 0.010862 -0.011682 +v 0.135070 0.012783 -0.011669 +v 0.133750 0.013453 -0.011714 +v 0.132156 0.013777 -0.011685 +v 0.130612 0.013566 -0.011709 +v 0.129027 0.012862 -0.011685 +v 0.127655 0.011502 -0.011654 +v 0.126812 0.009512 -0.011659 +v 0.126809 0.007540 -0.011697 +v 0.127399 0.006021 -0.011822 +v 0.128387 0.004643 -0.011657 +v 0.129740 0.003772 -0.011757 +v 0.130985 0.003327 -0.011673 +v 0.132720 0.003274 -0.011715 +v 0.135409 0.004423 -0.011657 +v 0.136859 0.006435 -0.011748 +v 0.127752 0.007295 -0.013130 +v 0.127474 0.008601 -0.012976 +v 0.128602 0.006078 -0.013365 +v 0.128674 0.005085 -0.012618 +v 0.129688 0.004855 -0.013236 +v 0.130890 0.004685 -0.013570 +v 0.131286 0.003892 -0.012782 +v 0.132238 0.004745 -0.013773 +v 0.132829 0.003992 -0.012862 +v 0.133699 0.004925 -0.013600 +v 0.134265 0.004180 -0.012459 +v 0.135267 0.005394 -0.012991 +v 0.135889 0.006535 -0.013160 +v 0.136349 0.007480 -0.013081 +v 0.136569 0.008796 -0.012860 +v 0.135790 0.009712 -0.013586 +v 0.136342 0.010229 -0.012763 +v 0.134873 0.010939 -0.013770 +v 0.135546 0.011629 -0.012682 +v 0.134294 0.012167 -0.013238 +v 0.132590 0.012285 -0.013726 +v 0.133205 0.012913 -0.012887 +v 0.131612 0.013225 -0.012672 +v 0.130348 0.012635 -0.013093 +v 0.129884 0.011844 -0.013593 +v 0.128523 0.011725 -0.012687 +v 0.127818 0.010465 -0.012861 +v 0.127877 0.009372 -0.013353 +v 0.133997 0.009655 -0.011996 +v 0.133997 0.007345 -0.011996 +v 0.131997 0.010809 -0.011996 +v 0.129997 0.009655 -0.011996 +v 0.129997 0.007345 -0.011996 +v 0.131997 0.006191 -0.011996 +v 0.128242 -0.034000 0.003369 +v 0.124650 -0.034000 0.002993 +v 0.128085 -0.034000 0.006079 +v 0.132287 -0.034000 0.000939 +v 0.130523 -0.034000 -0.002469 +v 0.129979 -0.034000 0.001502 +v 0.126839 -0.034000 -0.000543 +v 0.134494 -0.034000 0.001827 +v 0.136842 -0.034000 -0.000758 +v 0.134439 -0.034000 -0.002147 +v 0.135646 -0.034000 0.003298 +v 0.138864 -0.034000 0.001761 +v 0.125375 -0.034000 0.008643 +v 0.129125 -0.034000 0.007828 +v 0.127152 -0.034000 0.010766 +v 0.132560 -0.034000 0.008993 +v 0.133471 -0.034000 0.012477 +v 0.134887 -0.034000 0.007937 +v 0.137338 -0.034000 0.010403 +v 0.138945 -0.034000 0.007873 +v 0.130701 -0.034000 0.008832 +v 0.129555 -0.034000 0.012155 +v 0.139543 -0.034000 0.005396 +v 0.124579 -0.034000 0.006222 +v 0.128025 -0.034500 0.004092 +v 0.128182 -0.034500 0.006297 +v 0.129394 -0.034500 0.008139 +v 0.131434 -0.034500 0.008993 +v 0.133459 -0.034500 0.008789 +v 0.135098 -0.034500 0.007575 +v 0.136031 -0.034500 0.005577 +v 0.135341 -0.034500 0.002602 +v 0.132905 -0.034500 0.001050 +v 0.130701 -0.034500 0.001176 +v 0.129124 -0.034500 0.002180 +v 0.139261 -0.034500 0.007149 +v 0.137229 -0.034500 0.010508 +v 0.132533 -0.034500 -0.002518 +v 0.134995 -0.034500 -0.001901 +v 0.139343 -0.034500 0.002993 +v 0.137310 -0.034500 -0.000370 +v 0.129780 -0.034500 -0.002204 +v 0.126582 -0.034500 -0.000353 +v 0.134214 -0.034500 0.012212 +v 0.124614 -0.034500 0.003311 +v 0.131461 -0.034500 0.012526 +v 0.128998 -0.034500 0.011909 +v 0.126863 -0.034500 0.010528 +v 0.124788 -0.034500 0.007463 +v 0.136044 0.034000 0.004714 +v 0.139191 0.034000 0.002789 +v 0.139534 0.034000 0.005543 +v 0.135363 0.034000 0.002791 +v 0.138058 0.034000 0.000518 +v 0.131537 0.034000 0.001002 +v 0.132773 0.034000 -0.002550 +v 0.133726 0.034000 0.001314 +v 0.136028 0.034000 -0.001369 +v 0.129481 0.034000 0.001799 +v 0.129561 0.034000 -0.002119 +v 0.127326 0.034000 -0.000916 +v 0.128025 0.034000 0.004091 +v 0.125375 0.034000 0.001365 +v 0.129690 0.034000 0.008322 +v 0.126163 0.034000 0.009901 +v 0.128278 0.034000 0.006625 +v 0.134096 0.034000 0.008520 +v 0.138413 0.034000 0.009066 +v 0.136097 0.034000 0.011318 +v 0.135646 0.034000 0.006710 +v 0.131601 0.034000 0.009026 +v 0.129846 0.034000 0.012287 +v 0.133541 0.034000 0.012401 +v 0.124535 0.034000 0.004010 +v 0.124615 0.034000 0.006547 +v 0.135986 0.034500 0.004265 +v 0.135716 0.034500 0.006625 +v 0.134032 0.034500 0.008534 +v 0.131363 0.034500 0.009029 +v 0.129106 0.034500 0.007850 +v 0.128112 0.034500 0.006069 +v 0.128117 0.034500 0.003693 +v 0.130103 0.034500 0.001373 +v 0.132627 0.034500 0.001012 +v 0.134776 0.034500 0.002024 +v 0.130523 0.034500 -0.002469 +v 0.125374 0.034500 0.008643 +v 0.126839 0.034500 -0.000543 +v 0.124495 0.034500 0.005772 +v 0.124829 0.034500 0.002557 +v 0.134887 0.034500 -0.002019 +v 0.127682 0.034500 0.011229 +v 0.130911 0.034500 0.012482 +v 0.137513 0.034500 -0.000119 +v 0.139016 0.034500 0.002206 +v 0.133906 0.034500 0.012299 +v 0.139542 0.034500 0.005862 +v 0.136213 0.034500 0.011241 +v 0.138206 0.034500 0.009310 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.0054 0.0031 -1.0000 +vn -0.0048 0.0013 -1.0000 +vn -0.0038 0.0119 -0.9999 +vn -0.0005 -0.0005 -1.0000 +vn -0.3090 -0.1923 -0.9314 +vn 0.0030 -0.0080 -1.0000 +vn -0.0991 -0.3610 -0.9273 +vn 0.0006 -0.0098 -1.0000 +vn -0.0071 0.0396 -0.9992 +vn -0.0080 0.0223 -0.9997 +vn -0.0027 0.0082 -1.0000 +vn 0.0065 -0.0010 -1.0000 +vn 0.0044 -0.0007 -1.0000 +vn 0.0083 0.0003 -1.0000 +vn 0.0075 0.0005 -1.0000 +vn 0.0124 0.0005 -0.9999 +vn -0.0031 -0.0029 1.0000 +vn -0.0218 0.0190 0.9996 +vn -0.0540 0.0191 0.9984 +vn -0.0090 0.0174 0.9998 +vn -0.0005 0.0141 0.9999 +vn 0.0050 0.0104 0.9999 +vn 0.0090 0.0059 0.9999 +vn 0.0117 0.0002 0.9999 +vn 0.0131 -0.0076 0.9999 +vn 0.0111 -0.0223 0.9997 +vn -0.0009 -0.0606 0.9982 +vn -0.9937 0.1119 -0.0002 +vn -0.9998 0.0177 0.0087 +vn -0.8335 0.5525 0.0069 +vn -0.7618 0.6478 -0.0013 +vn -0.5162 0.8564 0.0076 +vn -0.2512 0.9679 -0.0020 +vn -0.1030 0.9947 0.0075 +vn 0.3331 0.9429 -0.0003 +vn 0.4021 0.9156 0.0062 +vn 0.5907 0.8069 0.0003 +vn 0.6326 0.7744 0.0058 +vn 0.9735 0.2286 -0.0023 +vn 0.9624 0.2717 0.0032 +vn 0.9636 0.2674 0.0026 +vn 0.9743 0.2251 -0.0027 +vn 0.8478 -0.5302 -0.0069 +vn 0.9444 -0.3286 0.0117 +vn 0.8170 -0.5765 0.0116 +vn 0.5664 -0.8241 -0.0080 +vn 0.3545 -0.9350 0.0110 +vn 0.1947 -0.9808 -0.0065 +vn 0.0495 -0.9987 0.0103 +vn -0.6139 -0.7894 0.0000 +vn -0.6124 -0.7906 0.0003 +vn -0.6125 -0.7904 0.0003 +vn -0.6140 -0.7893 0.0000 +vn -0.9828 -0.1845 -0.0004 +vn -0.9567 -0.2909 0.0108 +vn -0.9979 -0.0647 -0.0082 +vn -0.9574 -0.1790 -0.2266 +vn -0.8822 -0.4709 -0.0041 +vn -0.8492 -0.4622 -0.2553 +vn -0.6337 -0.7350 -0.2411 +vn -0.5778 -0.8160 0.0195 +vn -0.3602 -0.8981 -0.2521 +vn -0.1281 -0.9918 -0.0027 +vn -0.0794 -0.9567 -0.2799 +vn 0.1570 -0.9578 -0.2410 +vn 0.3255 -0.9455 -0.0059 +vn 0.4261 -0.8569 -0.2902 +vn 0.5861 -0.7721 -0.2456 +vn 0.7132 -0.7008 -0.0149 +vn 0.8358 -0.5201 -0.1757 +vn 0.9774 -0.2103 -0.0231 +vn 0.9491 -0.1531 -0.2752 +vn 0.9640 0.1557 -0.2157 +vn 0.9485 0.3167 -0.0100 +vn 0.8243 0.5056 -0.2548 +vn 0.7127 0.6969 -0.0806 +vn 0.5366 0.8152 -0.2181 +vn 0.3318 0.9407 -0.0713 +vn 0.1077 0.9722 -0.2080 +vn -0.1357 0.9892 -0.0547 +vn -0.3323 0.9218 -0.1996 +vn -0.6421 0.7652 -0.0460 +vn -0.5984 0.7405 -0.3058 +vn -0.8353 0.5248 -0.1637 +vn -0.9407 0.3362 -0.0446 +vn -0.9556 0.1574 -0.2489 +vn 0.7710 -0.0361 -0.6358 +vn 0.7831 0.2240 -0.5801 +vn 0.6436 0.2359 -0.7281 +vn 0.6147 -0.0122 -0.7887 +vn 0.4983 0.3419 -0.7967 +vn 0.6177 0.4804 -0.6227 +vn 0.3649 0.5415 -0.7574 +vn 0.4476 0.6620 -0.6012 +vn 0.2019 0.5697 -0.7966 +vn 0.2449 0.8042 -0.5416 +vn 0.1190 0.6983 -0.7059 +vn -0.1141 0.7892 -0.6035 +vn -0.1644 0.6318 -0.7575 +vn -0.4083 0.6901 -0.5976 +vn -0.4692 0.5111 -0.7202 +vn -0.4114 0.4448 -0.7955 +vn -0.6939 0.4731 -0.5428 +vn -0.6207 0.2868 -0.7297 +vn -0.5843 0.1043 -0.8048 +vn -0.7843 0.1614 -0.5990 +vn -0.6507 -0.0836 -0.7547 +vn -0.7881 -0.1861 -0.5867 +vn -0.5907 -0.3487 -0.7276 +vn -0.6724 -0.4800 -0.5635 +vn -0.3667 -0.5140 -0.7754 +vn -0.4731 -0.6174 -0.6285 +vn -0.1575 -0.7691 -0.6194 +vn -0.0111 -0.6796 -0.7335 +vn 0.2483 -0.5780 -0.7774 +vn 0.2074 -0.7436 -0.6356 +vn 0.4354 -0.6272 -0.6458 +vn 0.5815 -0.4927 -0.6474 +vn 0.5032 -0.3549 -0.7879 +vn 0.6473 -0.2410 -0.7232 +vn 0.7900 -0.3197 -0.5232 +vn 1.0000 0.0000 0.0000 +vn 0.4998 0.8662 0.0000 +vn 0.5002 0.8659 0.0000 +vn -0.4998 0.8662 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4998 -0.8662 0.0000 +vn 0.4998 -0.8662 0.0000 +vn 0.5032 -0.5801 0.6406 +vn 0.6147 -0.5694 0.5458 +vn 0.5612 -0.7802 0.2761 +vn 0.4489 -0.5645 0.6927 +vn 0.6261 -0.7554 0.1935 +vn 0.7110 -0.7027 0.0248 +vn 0.7529 -0.6450 0.1309 +vn 0.7469 -0.6617 -0.0655 +vn 0.6347 -0.7520 -0.1776 +vn 0.7224 -0.5648 -0.3990 +vn 0.3196 -0.7407 -0.5909 +vn 0.5243 -0.7002 -0.4846 +vn 0.4262 -0.7035 -0.5687 +vn -0.0068 -0.7302 -0.6832 +vn 0.0472 -0.7153 -0.6972 +vn 0.2317 -0.6176 -0.7516 +vn 0.0000 1.0000 -0.0000 +vn 0.9203 0.0121 -0.3911 +vn 0.8572 -0.0111 -0.5149 +vn 0.9912 -0.0114 -0.1319 +vn 1.0000 0.0052 -0.0031 +vn 0.6842 0.0073 -0.7293 +vn 0.5812 -0.0163 -0.8136 +vn 0.2938 0.0050 -0.9559 +vn 0.1869 0.0021 -0.9824 +vn -0.2272 -0.1729 0.9584 +vn 0.0053 -0.3539 0.9353 +vn -0.0035 -0.3830 0.9237 +vn 0.1910 -0.1801 0.9649 +vn 0.0042 0.4213 0.9069 +vn 0.2696 0.1918 0.9437 +vn -0.0064 0.3534 0.9355 +vn 0.0099 0.1577 0.9874 +vn -0.0080 0.0547 0.9985 +vn 0.0089 -0.0275 0.9996 +vn -0.0078 -0.1281 0.9917 +vn 0.2806 0.0347 0.9592 +vn 0.0581 0.0064 0.9983 +vn -0.1139 0.0545 0.9920 +vn 0.4632 -0.0626 0.8841 +vn 0.6714 0.0750 0.7372 +vn 0.8136 -0.0497 0.5793 +vn 0.9281 -0.0026 0.3723 +vn 0.9686 -0.0071 0.2486 +vn -0.0056 0.2180 0.9759 +vn 0.0061 0.3125 0.9499 +vn -0.0057 -0.2763 0.9610 +vn -0.0499 0.1879 0.9809 +vn 0.0090 -0.2150 0.9766 +vn -1.0000 0.0000 0.0034 +vn -1.0000 -0.0001 0.0049 +vn -0.9895 0.0009 0.1447 +vn -0.9925 -0.0012 0.1218 +vn 0.9999 0.0000 0.0167 +vn 1.0000 -0.0012 0.0059 +vn 0.9999 -0.0001 0.0160 +vn 1.0000 -0.0013 0.0051 +vn -0.5692 0.0093 0.8222 +vn -0.3834 -0.0101 0.9235 +vn 0.9715 0.0022 0.2370 +vn 0.9835 0.0001 0.1810 +vn 0.9854 0.0003 0.1702 +vn 0.9066 0.0046 0.4219 +vn 0.9297 -0.0018 0.3683 +vn 0.6023 0.0128 0.7982 +vn 0.7591 -0.0004 0.6509 +vn 0.0708 0.0174 0.9973 +vn -0.4353 0.0126 0.9002 +vn -0.8108 -0.0104 0.5852 +vn -0.8359 0.0054 0.5488 +vn -0.9906 0.0157 0.1358 +vn -0.9787 -0.0002 0.2051 +vn -0.9886 0.0003 0.1504 +vn -0.9163 -0.0053 0.4005 +vn -0.8965 0.0042 0.4430 +vn -0.7126 -0.0081 0.7015 +vn 0.1006 -0.0173 0.9948 +vn 0.6746 -0.0137 0.7381 +vn 0.8495 -0.0055 0.5276 +vn 0.8837 -0.0062 0.4680 +vn 0.9624 0.0007 0.2716 +vn 0.9692 0.0019 0.2463 +vn 0.4972 0.0090 0.8676 +vn 0.0043 -0.9999 -0.0119 +vn 0.0056 -0.9999 -0.0110 +vn 0.0004 -0.9999 -0.0123 +vn 0.0117 -0.9999 -0.0001 +vn 0.0117 -0.9999 -0.0025 +vn 0.0120 -0.9999 -0.0049 +vn 0.0082 -0.9999 -0.0104 +vn 0.0091 -0.9999 -0.0092 +vn 0.8603 -0.2602 0.4383 +vn 0.9923 -0.0044 0.1238 +vn 0.9228 -0.0083 0.3852 +vn 0.9568 -0.2890 0.0320 +vn 0.7795 -0.0040 0.6265 +vn -0.9761 -0.2137 -0.0404 +vn -0.9866 -0.1404 -0.0832 +vn -0.9585 0.0382 -0.2826 +vn -0.6899 0.0042 -0.7239 +vn -0.6671 0.0449 -0.7436 +vn -0.4935 -0.0975 -0.8642 +vn -0.4876 -0.1176 -0.8651 +vn -0.8776 -0.0713 -0.4741 +vn -0.2798 -0.1150 0.9532 +vn -0.6928 0.1317 0.7090 +vn -0.6942 0.1263 0.7086 +vn -0.6852 0.1586 0.7108 +vn -0.2946 -0.1657 0.9412 +vn -0.6809 0.1732 0.7116 +vn -0.8886 -0.2112 0.4071 +vn -0.9200 -0.1225 0.3722 +vn -0.9570 0.1714 0.2340 +vn -0.9494 0.2489 0.1916 +vn -0.0047 0.0561 -0.9984 +vn -0.0107 0.0771 -0.9970 +vn 0.3366 -0.0143 -0.9415 +vn 0.6175 -0.2632 -0.7412 +vn 0.1832 -0.2623 -0.9474 +vn 0.5378 -0.0166 -0.8429 +vn 0.7552 -0.0048 -0.6555 +vn 0.8969 -0.0118 -0.4421 +vn 0.8563 -0.3256 -0.4009 +vn 0.9848 0.0008 -0.1739 +vn -0.0003 -1.0000 -0.0018 +vn -0.0004 -1.0000 -0.0008 +vn 0.0003 -1.0000 -0.0014 +vn -0.0005 -1.0000 -0.0009 +vn 0.0019 -1.0000 -0.0026 +vn 0.0019 -1.0000 -0.0013 +vn 0.0027 -1.0000 -0.0008 +vn 0.0010 -1.0000 0.0001 +vn -0.0002 -1.0000 -0.0001 +vn -0.0009 -1.0000 0.0002 +vn 0.0003 -1.0000 0.0003 +vn 0.0000 -1.0000 0.0000 +vn 0.0005 -1.0000 0.0004 +vn 0.0011 -1.0000 0.0002 +vn -0.0012 -1.0000 0.0002 +vn -0.0011 -1.0000 0.0002 +vn 0.5641 -0.2626 0.7829 +vn 0.5961 0.0162 0.8028 +vn 0.3460 -0.0443 0.9372 +vn 0.0523 -0.4377 0.8976 +vn 0.0794 -0.3221 0.9434 +vn -0.1495 -0.2584 0.9544 +vn -0.4626 -0.0579 0.8847 +vn -0.4656 0.0076 0.8849 +vn -0.7215 0.0029 0.6924 +vn -0.7945 -0.1837 0.5788 +vn -0.9048 0.0054 0.4258 +vn -0.9108 -0.3614 0.1993 +vn -0.9919 -0.0045 0.1267 +vn -0.7792 -0.6157 0.1174 +vn -0.6892 -0.6767 0.2591 +vn -0.7222 -0.6917 -0.0049 +vn -0.0003 -1.0000 0.0003 +vn -0.0003 -1.0000 0.0005 +vn -0.9958 -0.0092 0.0910 +vn -0.9190 0.0059 0.3941 +vn -0.9933 -0.0204 0.1133 +vn -0.9424 -0.0092 0.3342 +vn -0.6278 -0.0194 0.7782 +vn -0.4667 0.0253 0.8841 +vn 0.0192 -0.0281 0.9994 +vn 0.1413 0.0047 0.9900 +vn 0.3770 -0.0261 0.9259 +vn 0.3845 -0.0305 0.9226 +vn 0.8947 -0.0162 0.4464 +vn 0.9419 0.0250 0.3350 +vn 0.8069 0.0387 0.5894 +vn 0.9914 -0.0239 0.1290 +vn 0.9546 0.0252 -0.2967 +vn 0.8991 -0.0115 -0.4375 +vn 0.5346 0.0199 -0.8449 +vn 0.5394 -0.0095 -0.8420 +vn 0.2791 -0.0014 -0.9603 +vn 0.2203 0.0252 -0.9751 +vn -0.3410 -0.0078 -0.9400 +vn -0.3744 0.0077 -0.9272 +vn -0.3163 -0.0192 -0.9485 +vn -0.3984 0.0191 -0.9170 +vn -0.8459 -0.0077 -0.5332 +vn -0.8695 0.0140 -0.4938 +vn -0.8239 -0.0265 -0.5662 +vn -0.8878 0.0326 -0.4590 +vn 0.0116 -0.9999 0.0106 +vn 0.0119 -0.9999 0.0051 +vn 0.0109 -0.9999 0.0040 +vn 0.0003 -0.9999 0.0108 +vn -0.0025 -0.9999 0.0125 +vn -0.0001 -0.9999 0.0105 +vn -0.0070 -0.9999 0.0132 +vn -0.0134 -0.9999 0.0089 +vn -0.0141 -0.9999 0.0060 +vn -0.0108 -0.9999 0.0106 +vn -0.0160 -0.9999 0.0044 +vn 0.0090 -0.9999 0.0111 +vn -0.0131 -0.9999 0.0064 +vn 0.0112 -0.9999 0.0011 +vn 0.0017 -0.9999 0.0120 +vn -0.0156 -0.9999 -0.0073 +vn -0.0090 -0.9999 -0.0097 +vn -0.0164 -0.9998 -0.0071 +vn -0.0061 -1.0000 -0.0070 +vn -0.0053 -1.0000 -0.0081 +vn -0.0038 -0.9999 -0.0108 +vn -0.9318 -0.2583 -0.2552 +vn -0.9897 0.0043 -0.1434 +vn -0.9040 -0.0293 -0.4266 +vn -0.7690 -0.0202 -0.6389 +vn -0.7444 -0.2742 -0.6088 +vn -0.5123 -0.0024 -0.8588 +vn -0.3308 -0.2883 -0.8986 +vn -0.2192 -0.0080 -0.9757 +vn 0.0225 -0.0107 -0.9997 +vn -0.2025 -0.3932 -0.8969 +vn -0.2109 -0.3616 -0.9082 +vn -0.2930 -0.7993 -0.5247 +vn -0.3303 -0.7906 -0.5156 +vn -0.2181 -0.7857 -0.5789 +vn -0.5418 -0.6629 -0.5167 +vn -0.5424 -0.7663 -0.3442 +vn -0.7132 -0.6466 -0.2707 +vn -0.7602 -0.6263 -0.1728 +vn -0.8175 -0.5694 -0.0866 +vn -0.5363 -0.6603 0.5258 +vn -0.6879 -0.6185 0.3798 +vn -0.5407 -0.6711 0.5072 +vn -0.4206 -0.6204 0.6619 +vn -0.2478 -0.7082 0.6611 +vn 0.3608 -0.5358 0.7633 +vn 0.1071 -0.7951 0.5969 +vn 0.5358 -0.6879 -0.4896 +vn -0.5917 -0.4444 -0.6726 +vn -0.8684 -0.4820 -0.1167 +vn -0.1628 -0.4833 -0.8602 +vn 0.1990 -0.5082 -0.8379 +vn 0.6188 -0.5045 -0.6021 +vn 0.8997 -0.3607 -0.2458 +vn 0.7854 -0.5043 0.3590 +vn 0.7651 -0.6312 0.1270 +vn 0.6344 -0.5556 0.5375 +vn 0.2763 -0.4143 0.8672 +vn 0.1443 -0.7024 0.6970 +vn -0.2245 -0.1252 0.9664 +vn -0.3424 -0.7662 0.5438 +vn -0.7677 -0.3410 0.5426 +vn -0.6569 -0.7414 0.1370 +vn 0.0002 1.0000 0.0063 +vn -0.0003 1.0000 0.0087 +vn 0.0027 1.0000 -0.0055 +vn 0.0031 1.0000 -0.0076 +vn 1.0000 -0.0005 -0.0079 +vn 1.0000 -0.0005 -0.0084 +vn 1.0000 0.0002 0.0063 +vn 1.0000 0.0002 0.0068 +vn 0.0003 -1.0000 0.0060 +vn 0.0008 -1.0000 0.0080 +vn -0.0020 -1.0000 -0.0048 +vn -0.0024 -1.0000 -0.0068 +vn -1.0000 0.0005 -0.0080 +vn -1.0000 -0.0002 0.0063 +vn -1.0000 0.0005 -0.0075 +vn -1.0000 -0.0002 0.0068 +vn -0.0560 0.0234 -0.9982 +vn -0.0089 -0.0019 -1.0000 +vn -0.0154 -0.0006 -0.9999 +vn 0.0233 0.0062 -0.9997 +vn 0.2681 -0.2442 -0.9319 +vn 0.0084 0.0039 -1.0000 +vn -0.0027 0.0024 -1.0000 +vn -0.0153 -0.3721 -0.9281 +vn -0.0042 -0.0057 -1.0000 +vn -0.0031 -0.0053 -1.0000 +vn -0.0174 0.0057 -0.9998 +vn 0.0023 0.0034 -1.0000 +vn 0.0012 0.0020 -1.0000 +vn 0.0166 -0.0039 -0.9999 +vn 0.0506 0.0126 -0.9986 +vn 0.0245 -0.0009 -0.9997 +vn -0.0187 -0.0109 0.9998 +vn -0.0194 0.0174 0.9997 +vn -0.0449 0.0096 0.9989 +vn -0.0037 0.0145 0.9999 +vn 0.0049 0.0113 0.9999 +vn 0.0088 0.0083 0.9999 +vn 0.0120 0.0044 0.9999 +vn 0.0150 -0.0012 0.9999 +vn 0.0172 -0.0080 0.9998 +vn 0.0162 -0.0213 0.9996 +vn 0.0028 -0.0917 0.9958 +vn -0.1942 -0.0621 0.9790 +vn -0.9947 0.1027 -0.0017 +vn -0.9997 0.0226 0.0056 +vn -0.9561 0.2929 0.0083 +vn -0.9209 0.3898 -0.0014 +vn -0.5327 0.8463 0.0042 +vn -0.5518 0.8339 0.0069 +vn -0.5502 0.8350 0.0067 +vn -0.5309 0.8474 0.0039 +vn 0.1050 0.9945 0.0009 +vn 0.1073 0.9942 0.0012 +vn 0.4669 0.8843 -0.0021 +vn 0.3561 0.9344 0.0056 +vn 0.7315 0.6818 0.0071 +vn 0.9303 0.3667 -0.0023 +vn 0.9487 0.3163 0.0045 +vn 0.9903 -0.1390 0.0054 +vn 0.9664 -0.2569 -0.0036 +vn 0.8068 -0.5908 0.0113 +vn 0.8251 -0.5649 -0.0064 +vn 0.6208 -0.7838 0.0165 +vn 0.1064 -0.9943 -0.0010 +vn 0.0768 -0.9970 -0.0053 +vn 0.0803 -0.9968 -0.0048 +vn 0.1089 -0.9940 -0.0007 +vn -0.5812 -0.8138 -0.0033 +vn -0.4654 -0.8851 0.0078 +vn -0.6189 -0.7855 0.0078 +vn -0.8430 -0.5379 -0.0031 +vn -0.8861 -0.4634 0.0058 +vn -0.9630 -0.0533 -0.2641 +vn -0.8795 -0.4497 -0.1559 +vn -0.9836 -0.1462 -0.1056 +vn -0.6518 -0.7578 -0.0312 +vn -0.8257 -0.4737 0.3063 +vn -0.6413 -0.6958 -0.3236 +vn -0.3955 -0.8903 -0.2257 +vn -0.1261 -0.9920 -0.0067 +vn -0.0727 -0.9599 -0.2709 +vn 0.2753 -0.9323 -0.2346 +vn 0.3207 -0.9468 0.0287 +vn 0.6134 -0.7890 -0.0355 +vn 0.6874 -0.6833 -0.2462 +vn 0.8950 -0.4457 -0.0155 +vn 0.8634 -0.4118 -0.2914 +vn 0.9701 -0.0933 -0.2239 +vn 0.9997 0.0186 -0.0183 +vn 0.9359 0.2643 -0.2330 +vn 0.8889 0.4578 -0.0153 +vn 0.7859 0.5329 -0.3136 +vn 0.6547 0.7555 -0.0243 +vn 0.6260 0.7249 -0.2875 +vn 0.3570 0.9073 -0.2223 +vn 0.2716 0.9624 0.0031 +vn -0.0140 0.9704 -0.2411 +vn -0.1524 0.9883 -0.0067 +vn -0.3942 0.8820 -0.2583 +vn -0.6404 0.7674 -0.0313 +vn -0.6508 0.7029 -0.2869 +vn -0.8204 0.5190 -0.2399 +vn -0.9458 0.3248 -0.0084 +vn -0.9544 0.1918 -0.2289 +vn 0.7200 -0.1787 -0.6706 +vn 0.6423 0.1374 -0.7540 +vn 0.7423 0.1840 -0.6442 +vn 0.8344 -0.0721 -0.5465 +vn 0.5992 0.4305 -0.6750 +vn 0.4839 0.3730 -0.7916 +vn 0.4646 0.6760 -0.5721 +vn 0.3717 0.5428 -0.7531 +vn 0.2096 0.7561 -0.6200 +vn 0.1934 0.5563 -0.8082 +vn 0.0223 0.6500 -0.7596 +vn -0.1089 0.7979 -0.5929 +vn -0.1443 0.5651 -0.8123 +vn -0.3008 0.6386 -0.7083 +vn -0.4920 0.3696 -0.7882 +vn -0.5178 0.5066 -0.6894 +vn -0.5432 0.6029 -0.5843 +vn -0.7222 0.2969 -0.6247 +vn -0.6533 0.0214 -0.7568 +vn -0.7689 0.0777 -0.6346 +vn -0.7740 -0.1449 -0.6164 +vn -0.5751 -0.1938 -0.7948 +vn -0.5926 -0.3028 -0.7464 +vn -0.6712 -0.4413 -0.5957 +vn -0.4136 -0.4529 -0.7898 +vn -0.4552 -0.5880 -0.6686 +vn -0.2061 -0.6211 -0.7561 +vn -0.2423 -0.7703 -0.5898 +vn 0.0195 -0.7776 -0.6285 +vn 0.2214 -0.6043 -0.7653 +vn 0.2486 -0.7703 -0.5872 +vn 0.4742 -0.6968 -0.5381 +vn 0.4181 -0.5446 -0.7271 +vn 0.6236 -0.4135 -0.6634 +vn 0.6284 -0.1276 -0.7673 +vn 0.0012 1.0000 0.0017 +vn 0.0012 1.0000 0.0007 +vn 0.0005 1.0000 -0.0005 +vn 0.0001 1.0000 0.0009 +vn 0.0000 1.0000 0.0017 +vn 0.0011 1.0000 0.0012 +vn 0.0053 1.0000 -0.0004 +vn -0.3544 0.0154 0.9350 +vn -0.5874 0.0117 0.8092 +vn -0.5684 -0.0174 0.8225 +vn -0.8396 -0.0165 0.5429 +vn -0.9461 0.0160 0.3235 +vn -0.9971 -0.0142 -0.0752 +vn -0.9143 0.0177 -0.4047 +vn -0.7556 -0.0167 -0.6549 +vn -0.4592 0.0148 -0.8882 +vn -0.1551 -0.0173 -0.9878 +vn 0.1588 0.0183 -0.9871 +vn 0.5147 -0.0165 -0.8572 +vn 0.7926 0.0084 -0.6097 +vn 0.9109 -0.0001 -0.4127 +vn 0.9819 0.0133 -0.1892 +vn 0.9623 -0.0080 -0.2717 +vn 0.8856 -0.0177 0.4641 +vn 0.9581 0.0113 0.2862 +vn 0.8330 0.0120 0.5532 +vn 0.6052 -0.0188 0.7958 +vn 0.4181 0.0033 0.9084 +vn 0.2323 -0.0163 0.9725 +vn 0.1922 -0.0077 0.9813 +vn -0.0957 0.7828 -0.6148 +vn -0.1029 0.7765 -0.6217 +vn -0.4365 0.7278 -0.5289 +vn -0.2692 0.7179 -0.6420 +vn -0.6341 0.7252 -0.2684 +vn -0.6910 0.7195 0.0698 +vn -0.6476 0.7181 0.2549 +vn -0.3580 0.7282 0.5845 +vn -0.4447 0.6821 0.5805 +vn -0.0558 0.7183 0.6935 +vn 0.2056 0.7367 0.6442 +vn 0.3224 0.7147 0.6207 +vn 0.6219 0.7230 0.3007 +vn 0.5668 0.7070 0.4229 +vn 0.7106 0.7036 0.0037 +vn 0.6490 0.7303 -0.2131 +vn 0.5583 0.7129 -0.4244 +vn 0.4396 0.6270 -0.6431 +vn 0.4144 0.5403 -0.7324 +vn 0.0008 -1.0000 -0.0016 +vn 0.0000 -1.0000 -0.0020 +vn -0.0007 -1.0000 -0.0016 +vn 0.0007 -1.0000 0.0008 +vn 0.0016 -1.0000 -0.0002 +vn 0.0015 -1.0000 -0.0002 +vn 0.0008 -1.0000 -0.0004 +vn 0.0006 -1.0000 -0.0002 +vn 0.0009 -1.0000 -0.0008 +vn 0.0009 -1.0000 -0.0009 +vn -0.0041 -1.0000 0.0060 +vn -0.0048 -1.0000 0.0034 +vn -0.0025 -1.0000 0.0066 +vn 0.0027 -1.0000 0.0052 +vn -0.0008 -1.0000 -0.0011 +vn -0.0033 -1.0000 0.0042 +vn 0.0007 -1.0000 0.0005 +vn 0.0034 -1.0000 0.0020 +vn 0.0006 -1.0000 0.0002 +vn 0.0006 -1.0000 0.0010 +vn -0.0026 -1.0000 -0.0006 +vn -0.0038 -1.0000 0.0033 +vn -0.0008 -1.0000 -0.0009 +vn -0.0009 -1.0000 -0.0002 +vn -0.0010 -1.0000 -0.0005 +vn -0.0013 -1.0000 -0.0010 +vn -0.9762 -0.0240 -0.2157 +vn -0.9785 0.2033 0.0335 +vn -0.9694 0.2416 0.0438 +vn -0.8666 -0.2250 0.4453 +vn -0.8622 -0.2786 0.4231 +vn -0.7423 0.0567 0.6676 +vn -0.6591 0.0658 0.7492 +vn -0.3557 -0.0447 0.9335 +vn -0.2548 -0.0319 0.9665 +vn -0.0288 0.2068 0.9780 +vn -0.0226 0.2269 0.9736 +vn 0.3201 -0.1223 0.9394 +vn 0.2541 -0.2166 0.9426 +vn 0.4917 0.0691 0.8680 +vn 0.6688 -0.1150 0.7345 +vn 0.7837 0.1427 0.6045 +vn 0.7958 0.2247 0.5623 +vn 0.9490 -0.1846 0.2557 +vn 0.9407 -0.2140 0.2634 +vn 0.9998 0.0139 0.0143 +vn 0.9981 0.0504 0.0361 +vn 0.9372 -0.0136 -0.3484 +vn 0.9284 -0.0500 -0.3682 +vn 0.8085 0.1844 -0.5589 +vn 0.7981 0.2137 -0.5633 +vn 0.5284 -0.2656 -0.8064 +vn 0.3360 0.3355 -0.8801 +vn 0.0315 -0.3394 -0.9401 +vn -0.2045 0.2868 -0.9359 +vn -0.5164 -0.1655 -0.8402 +vn -0.4988 -0.2062 -0.8419 +vn -0.6920 -0.0057 -0.7219 +vn -0.7691 -0.0004 -0.6392 +vn -0.9363 -0.0110 -0.3511 +vn -0.0019 -1.0000 0.0094 +vn -0.0047 -0.9999 0.0147 +vn 0.0068 -1.0000 0.0066 +vn -0.0039 -0.9999 0.0135 +vn -0.0029 -1.0000 0.0068 +vn 0.0015 -1.0000 -0.0030 +vn -0.0127 -0.9999 0.0106 +vn -0.0164 -0.9998 0.0090 +vn -0.0015 -0.9998 0.0220 +vn 0.0098 -0.9999 0.0044 +vn 0.0069 -1.0000 -0.0007 +vn -0.0011 -0.9998 0.0218 +vn -0.0100 -0.9998 0.0191 +vn 0.0028 -1.0000 -0.0046 +vn 0.0049 -1.0000 0.0022 +vn 0.0068 -1.0000 0.0039 +vn 0.0017 -0.9996 0.0275 +vn 0.0066 -1.0000 0.0032 +vn 0.0117 -0.9999 -0.0109 +vn 0.0154 -0.9999 0.0058 +vn 0.0097 -0.9999 -0.0068 +vn -0.6257 -0.7799 0.0138 +vn -0.6812 -0.7165 -0.1501 +vn -0.5268 -0.7996 -0.2883 +vn -0.4585 -0.7502 -0.4764 +vn -0.2921 -0.7945 -0.5324 +vn -0.0195 -0.7936 -0.6081 +vn 0.1284 -0.7465 -0.6529 +vn 0.3185 -0.7879 -0.5270 +vn 0.5230 -0.7091 -0.4728 +vn 0.5759 -0.7762 -0.2568 +vn 0.6553 -0.7495 -0.0934 +vn 0.6128 -0.7722 0.1677 +vn 0.6242 -0.6935 0.3599 +vn 0.4351 -0.7623 0.4791 +vn 0.2503 -0.6785 0.6906 +vn 0.1708 -0.7741 0.6096 +vn -0.2202 -0.7285 -0.6487 +vn 0.2896 -0.6209 -0.7284 +vn 0.0062 -0.6345 0.7729 +vn -0.0903 -0.7619 0.6414 +vn -0.2542 -0.6565 0.7101 +vn -0.3491 -0.7627 0.5445 +vn -0.5126 -0.6143 0.5999 +vn -0.5796 -0.7506 0.3172 +vn -0.7604 -0.6444 0.0806 +vn -0.6775 -0.6424 -0.3582 +vn -0.0233 -0.6250 -0.7803 +vn 0.7714 -0.6312 0.0812 +vn 0.5776 -0.5817 0.5727 +vn -0.7432 -0.5863 0.3223 +vn 0.6724 -0.5868 -0.4510 +vn 0.7822 -0.5846 -0.2153 +vn -0.3272 -0.5496 -0.7687 +vn 0.5189 -0.5463 -0.6575 +vn 0.3718 -0.5502 0.7477 +vn -0.5832 -0.5617 -0.5868 +vn 0.7908 -0.5354 0.2967 +vn -0.1247 -0.5268 0.8408 +vn -0.7080 -0.4837 0.5145 +vn -0.8680 -0.4632 -0.1792 +vn -0.3807 -0.5089 0.7721 +vn 0.0143 -0.4932 -0.8698 +vn 0.4386 -0.4613 -0.7713 +vn 0.7645 -0.4779 -0.4326 +vn 0.8758 -0.4818 0.0290 +vn 0.7638 -0.4741 0.4381 +vn 0.1817 -0.4983 0.8478 +vn -0.8864 -0.4585 0.0646 +vn -0.7712 -0.4707 -0.4286 +vn -0.4850 -0.4546 -0.7470 +vn 0.5088 -0.4564 0.7299 +vn -0.9973 -0.0707 -0.0186 +vn -0.9972 -0.0546 -0.0519 +vn -0.9993 -0.0360 0.0085 +vn -0.3443 -0.6983 -0.6275 +vn -0.5086 -0.6985 -0.5034 +vn -0.3638 -0.6998 -0.6147 +vn -0.1851 -0.6731 -0.7160 +vn 0.3460 -0.6986 -0.6263 +vn 0.1850 -0.6732 -0.7159 +vn 0.3623 -0.6998 -0.6157 +vn 0.5069 -0.6991 -0.5043 +vn 0.9973 -0.0712 0.0188 +vn 0.9971 -0.0549 0.0522 +vn 0.9993 -0.0360 -0.0085 +vn 0.3711 -0.7085 0.6003 +vn 0.5225 -0.6783 0.5166 +vn 0.3424 -0.7116 0.6135 +vn 0.1818 -0.7158 0.6742 +vn -0.5310 -0.0457 0.8461 +vn -0.5509 -0.0490 0.8331 +vn -0.5211 -0.0077 0.8535 +vn -1.0000 -0.0023 0.0053 +vn -0.9997 -0.0131 -0.0200 +vn -0.4988 -0.0008 -0.8667 +vn -0.5007 -0.0022 -0.8656 +vn -0.5021 -0.0011 -0.8648 +vn -0.4961 -0.0024 -0.8683 +vn -0.5057 -0.0037 -0.8627 +vn 0.5020 -0.0011 -0.8649 +vn 0.5084 0.0032 -0.8611 +vn 0.5066 0.0050 -0.8622 +vn 0.5057 -0.0037 -0.8627 +vn 0.5183 0.0133 -0.8551 +vn 0.9997 -0.0132 0.0200 +vn 1.0000 -0.0026 -0.0051 +vn 0.4987 -0.0008 0.8667 +vn 0.4933 0.0027 0.8699 +vn 0.4943 0.0040 0.8693 +vn 0.4958 -0.0024 0.8684 +vn 0.4850 0.0106 0.8745 +vn -0.5186 -0.0138 0.8549 +vn -0.5054 0.0037 0.8629 +vn -0.9896 -0.1296 -0.0620 +vn -0.9943 0.0373 0.0996 +vn -0.9558 -0.0227 0.2932 +vn -0.8724 0.0518 0.4860 +vn -0.7525 0.0054 0.6586 +vn -0.6413 0.0284 0.7668 +vn -0.4202 -0.0273 0.9070 +vn -0.2545 0.0274 0.9667 +vn 0.0053 -0.0279 0.9996 +vn 0.1600 -0.0051 0.9871 +vn 0.3644 -0.0487 0.9300 +vn 0.5458 0.0369 0.8371 +vn 0.7070 -0.0578 0.7049 +vn 0.8486 0.0119 0.5290 +vn 0.9208 -0.0078 0.3899 +vn 0.9832 0.0501 0.1755 +vn 0.9960 -0.0720 -0.0530 +vn 0.9539 0.0786 -0.2896 +vn 0.8677 0.0005 -0.4971 +vn 0.7796 0.0200 -0.6259 +vn 0.6021 -0.0207 -0.7982 +vn 0.4622 0.0110 -0.8867 +vn 0.2319 -0.0630 -0.9707 +vn 0.0430 0.1539 -0.9872 +vn -0.0205 0.2450 -0.9693 +vn -0.2641 -0.3286 -0.9068 +vn -0.5305 0.3282 -0.7816 +vn -0.7400 -0.3298 -0.5862 +vn -0.8826 0.2568 -0.3938 +vn -0.9802 -0.1802 -0.0826 +vn 0.9735 0.0159 0.2283 +vn 0.9707 -0.0182 -0.2394 +vn 0.9365 0.0109 -0.3504 +vn 0.6382 -0.0230 -0.7695 +vn 0.6643 0.0133 -0.7474 +vn 0.2506 0.0129 -0.9680 +vn 0.0199 -0.0271 -0.9994 +vn -0.2301 0.0176 -0.9730 +vn -0.5432 -0.0194 -0.8394 +vn -0.6705 0.0158 -0.7417 +vn -0.8830 -0.0167 -0.4691 +vn -0.9368 0.0127 -0.3496 +vn -0.9733 -0.0115 -0.2292 +vn -0.9899 0.0185 -0.1408 +vn -0.9084 -0.0087 0.4180 +vn -0.9174 0.0036 0.3980 +vn -0.9124 -0.0033 0.4092 +vn -0.9212 0.0090 0.3891 +vn -0.4997 0.0146 0.8661 +vn -0.5732 -0.0176 0.8192 +vn -0.3340 -0.0152 0.9425 +vn -0.2228 0.0131 0.9748 +vn 0.2379 -0.0115 0.9712 +vn 0.2652 0.0094 0.9642 +vn 0.6875 0.0083 0.7262 +vn 0.6901 -0.0046 0.7237 +vn 0.9479 -0.0085 0.3184 +vn 0.0004 1.0000 0.0012 +vn 0.0004 1.0000 0.0011 +vn 0.0001 1.0000 0.0005 +vn 0.0000 1.0000 0.0001 +vn -0.0002 1.0000 0.0005 +vn -0.0002 1.0000 0.0006 +vn 0.0002 1.0000 -0.0001 +vn 0.0018 1.0000 -0.0008 +vn 0.0019 1.0000 -0.0012 +vn -0.0015 1.0000 0.0007 +vn -0.0002 1.0000 0.0001 +vn -0.0019 1.0000 0.0009 +vn -0.0019 1.0000 0.0013 +vn 0.0024 1.0000 -0.0025 +vn 0.0005 1.0000 -0.0012 +vn -0.0002 1.0000 -0.0004 +vn -0.0003 1.0000 -0.0001 +vn 0.0001 1.0000 -0.0013 +vn -0.0002 1.0000 -0.0007 +vn -0.9264 0.2772 -0.2550 +vn -0.9997 0.0086 0.0241 +vn -0.9220 0.3149 0.2254 +vn -0.9759 0.0027 -0.2181 +vn -0.8863 -0.0036 -0.4630 +vn -0.7597 0.2508 -0.5999 +vn -0.7042 0.0026 -0.7100 +vn -0.4105 0.2841 -0.8665 +vn -0.4601 -0.0156 -0.8878 +vn -0.1995 0.0190 -0.9797 +vn 0.0065 0.0223 -0.9997 +vn 0.1537 0.3195 -0.9350 +vn 0.2820 -0.0032 -0.9594 +vn 0.4873 0.0191 -0.8730 +vn 0.7287 0.0466 -0.6832 +vn 0.7174 -0.0140 -0.6966 +vn 0.9168 0.0018 -0.3993 +vn 0.9282 0.3437 -0.1429 +vn 0.9989 0.0063 -0.0454 +vn 0.9807 0.0134 0.1951 +vn 0.9243 0.2545 0.2843 +vn 0.8772 -0.0015 0.4802 +vn 0.6775 0.3041 0.6698 +vn 0.5907 0.3569 0.7237 +vn 0.4861 0.1047 0.8676 +vn 0.2823 0.0589 0.9575 +vn 0.1600 -0.0003 0.9871 +vn -0.2454 0.0672 0.9671 +vn -0.0806 0.0066 0.9967 +vn -0.3407 0.0107 0.9401 +vn -0.6506 0.0472 0.7579 +vn -0.5564 -0.0016 0.8309 +vn -0.7908 0.0118 0.6120 +vn -0.9370 0.0015 0.3494 +vn -0.0145 0.9998 -0.0128 +vn -0.0116 0.9996 -0.0246 +vn -0.0052 0.9999 -0.0156 +vn -0.0036 0.9999 -0.0125 +vn -0.0163 0.9999 -0.0041 +vn -0.0122 0.9999 0.0004 +vn -0.0111 0.9999 0.0035 +vn 0.0009 0.9999 -0.0120 +vn 0.0061 1.0000 -0.0078 +vn 0.0051 0.9999 -0.0089 +vn 0.0066 0.9999 -0.0098 +vn 0.0111 0.9999 -0.0097 +vn 0.0026 0.9999 -0.0111 +vn 0.0135 0.9999 -0.0053 +vn 0.0130 0.9999 0.0021 +vn 0.0109 0.9999 0.0045 +vn -0.0122 0.9999 0.0023 +vn -0.0152 0.9999 0.0016 +vn 0.0124 0.9999 0.0110 +vn 0.0045 0.9998 0.0172 +vn 0.0079 0.9998 0.0180 +vn -0.0007 0.9998 0.0176 +vn -0.0030 0.9999 0.0164 +vn -0.0057 0.9999 0.0161 +vn -0.0032 0.9999 0.0158 +vn 0.0109 0.9999 0.0038 +vn 0.0138 0.9999 0.0035 +vn 0.0144 0.9998 0.0104 +vn -0.0134 0.9998 0.0119 +vn -0.0147 0.9998 0.0112 +vn -0.1565 0.6470 -0.7463 +vn -0.0045 0.7694 -0.6388 +vn -0.2600 0.7226 -0.6405 +vn 0.0016 0.8048 -0.5936 +vn -0.3907 0.6636 -0.6380 +vn 0.0995 0.6016 0.7926 +vn 0.1852 0.7144 0.6748 +vn 0.2083 0.7479 0.6302 +vn -0.0729 0.7183 0.6919 +vn 0.6586 0.7479 -0.0827 +vn 0.6059 0.7756 0.1770 +vn 0.5709 0.8194 0.0509 +vn 0.7607 0.6162 -0.2039 +vn 0.4674 0.7751 -0.4251 +vn 0.7666 0.5379 -0.3507 +vn 0.3043 0.7590 -0.5756 +vn 0.3616 0.7669 -0.5303 +vn 0.1939 0.5935 -0.7811 +vn -0.6014 0.5823 -0.5470 +vn -0.6945 0.6227 -0.3604 +vn -0.6952 0.6235 -0.3577 +vn -0.6507 0.7558 -0.0739 +vn -0.6968 0.6882 -0.2019 +vn 0.4851 0.4017 0.7767 +vn 0.4938 0.7012 0.5143 +vn 0.6101 0.6946 0.3813 +vn 0.6122 0.7423 0.2726 +vn 0.4177 0.7676 -0.4861 +vn -0.4351 0.7019 -0.5640 +vn -0.7441 0.6653 0.0605 +vn -0.6899 0.6867 0.2290 +vn -0.6674 0.6936 0.2712 +vn -0.7030 0.5076 0.4982 +vn -0.4790 0.7176 0.5055 +vn -0.4520 0.5677 0.6881 +vn -0.2960 0.6608 0.6898 +vn -0.2142 0.6137 0.7599 +vn -0.0823 0.7204 0.6886 +vn 0.8575 0.4817 0.1807 +vn 0.7163 0.5127 0.4733 +vn 0.4639 0.6568 0.5945 +vn 0.4701 0.2056 0.8584 +vn 0.0431 0.6577 0.7521 +vn 0.0465 0.6692 0.7416 +vn 0.0200 0.5771 0.8164 +vn 0.0105 0.5422 0.8402 +vn -0.4036 0.2206 0.8879 +vn -0.3969 0.7820 0.4806 +vn -0.8423 0.0311 0.5382 +vn -0.7163 0.6928 0.0835 +vn -0.8767 0.4708 -0.0988 +vn -0.6849 0.4993 -0.5307 +vn -0.4707 0.6277 -0.6200 +vn -0.0851 0.3057 -0.9483 +vn 0.0274 0.6919 -0.7215 +vn 0.4615 0.1747 -0.8698 +vn 0.4306 0.7552 -0.4943 +vn 0.9042 -0.0108 -0.4270 +vn 0.6796 0.7302 -0.0705 +vn -0.0013 -1.0000 0.0007 +vn 0.0007 -1.0000 0.0011 +vn -0.0007 -1.0000 0.0002 +vn 0.0013 -1.0000 -0.0008 +vn 0.0031 -1.0000 -0.0026 +vn 0.5372 -0.0119 0.8434 +vn 0.7533 -0.0099 0.6576 +vn 0.6436 0.0126 0.7652 +vn 0.8620 0.0124 0.5068 +vn 0.9839 -0.0098 0.1785 +vn 0.9994 0.0103 -0.0342 +vn 0.9378 -0.0126 -0.3470 +vn 0.8161 0.0151 -0.5777 +vn 0.5672 -0.0151 -0.8235 +vn 0.2771 0.0148 -0.9607 +vn 0.0109 -0.0118 -0.9999 +vn -0.3116 0.0115 -0.9501 +vn -0.4916 -0.0097 -0.8708 +vn -0.5690 0.0107 -0.8223 +vn -0.7023 -0.0128 -0.7118 +vn -0.9660 0.0052 -0.2584 +vn -0.9652 0.0045 -0.2615 +vn -0.9609 0.0009 -0.2769 +vn -0.9602 0.0003 -0.2794 +vn -0.9605 0.0055 0.2782 +vn -0.9302 -0.0093 0.3670 +vn -0.8539 0.0071 0.5203 +vn -0.7818 -0.0091 0.6235 +vn -0.4145 0.0088 0.9100 +vn -0.3367 -0.0018 0.9416 +vn -0.0988 0.0078 0.9951 +vn -0.0831 0.0044 0.9965 +vn -0.1587 -0.7433 -0.6499 +vn 0.0393 -0.7253 -0.6874 +vn 0.4515 -0.7328 -0.5091 +vn 0.3776 -0.6958 -0.6110 +vn 0.6354 -0.7393 -0.2227 +vn 0.6480 -0.7520 0.1205 +vn 0.7217 -0.6796 0.1316 +vn 0.5083 -0.7462 0.4299 +vn 0.2014 -0.7445 0.6365 +vn 0.1527 -0.6754 0.7215 +vn -0.2100 -0.7682 0.6047 +vn -0.5339 -0.7433 0.4031 +vn -0.5786 -0.6569 0.4833 +vn -0.6651 -0.7457 0.0402 +vn -0.6125 -0.7398 -0.2784 +vn -0.6147 -0.6883 -0.3852 +vn -0.3625 -0.7220 -0.5892 +vn -0.0005 1.0000 -0.0033 +vn 0.0000 1.0000 -0.0012 +vn -0.0000 1.0000 -0.0006 +vn -0.0014 1.0000 0.0006 +vn -0.0009 1.0000 0.0009 +vn -0.0030 1.0000 -0.0000 +vn -0.0011 1.0000 0.0007 +vn -0.0010 1.0000 0.0006 +vn -0.0041 1.0000 -0.0016 +vn -0.0034 1.0000 -0.0036 +vn 0.0009 1.0000 -0.0032 +vn 0.0007 1.0000 0.0010 +vn -0.0000 1.0000 0.0014 +vn -0.0003 1.0000 0.0014 +vn 0.0004 1.0000 -0.0016 +vn -0.0001 1.0000 -0.0019 +vn 0.0020 1.0000 -0.0013 +vn 0.0054 1.0000 -0.0051 +vn 0.0096 1.0000 0.0008 +vn 0.0207 0.9997 -0.0111 +vn 0.0006 1.0000 0.0013 +vn 0.0003 1.0000 0.0010 +vn 0.0024 1.0000 0.0007 +vn 0.0026 1.0000 0.0004 +vn -0.0003 1.0000 0.0009 +vn -0.0004 1.0000 0.0008 +vn 0.0015 1.0000 -0.0017 +vn 0.0052 1.0000 0.0044 +vn 0.9658 0.1615 0.2029 +vn 0.9615 0.2001 0.1883 +vn 0.9190 -0.0063 0.3943 +vn 0.8716 -0.0137 0.4901 +vn 0.7194 -0.0039 0.6946 +vn 0.6040 0.0156 0.7968 +vn 0.4027 -0.2192 0.8887 +vn 0.3723 -0.2780 0.8855 +vn 0.0508 0.0984 0.9939 +vn 0.1871 0.2089 0.9599 +vn -0.0668 0.0394 0.9970 +vn -0.2319 -0.2742 0.9333 +vn -0.2363 -0.2978 0.9249 +vn -0.5857 0.3416 0.7350 +vn -0.7349 -0.3419 0.5857 +vn -0.9436 0.2036 0.2610 +vn -0.9297 0.2483 0.2721 +vn -0.9985 -0.0165 0.0530 +vn -0.9911 0.0319 -0.1293 +vn -0.9345 -0.1577 -0.3191 +vn -0.9236 -0.1984 -0.3281 +vn -0.6740 0.2189 -0.7056 +vn -0.6747 0.2586 -0.6913 +vn -0.4563 -0.0628 -0.8876 +vn -0.4045 -0.0971 -0.9094 +vn 0.0006 0.0440 -0.9990 +vn 0.0320 0.0512 -0.9982 +vn 0.4582 -0.0719 -0.8859 +vn 0.3184 -0.0340 -0.9473 +vn 0.6430 0.1983 -0.7398 +vn 0.6509 0.2598 -0.7134 +vn 0.8464 -0.1755 -0.5029 +vn 0.8704 -0.1091 -0.4802 +vn 0.9361 0.0962 -0.3382 +vn 0.9738 -0.1466 -0.1738 +vn 0.9653 -0.2249 -0.1331 +vn -0.0014 1.0000 0.0093 +vn -0.0048 1.0000 -0.0031 +vn -0.0025 0.9999 0.0098 +vn 0.0005 1.0000 -0.0022 +vn 0.0141 0.9999 0.0057 +vn 0.0717 0.9254 -0.3722 +vn -0.0010 1.0000 0.0052 +vn 0.0083 0.9996 0.0257 +vn 0.0042 1.0000 -0.0025 +vn 0.0055 1.0000 -0.0050 +vn -0.0058 1.0000 0.0076 +vn 0.3585 0.9223 -0.1444 +vn -0.0107 0.9999 0.0110 +vn 0.0001 1.0000 0.0052 +vn 0.0064 1.0000 0.0016 +vn 0.0104 0.9999 0.0055 +vn 0.0002 1.0000 0.0045 +vn 0.0016 1.0000 0.0026 +vn 0.0120 0.9998 0.0160 +vn 0.0054 0.9999 0.0094 +vn 0.0190 0.9997 0.0156 +vn -0.5154 0.7980 0.3124 +vn -0.4290 0.7559 0.4945 +vn -0.1922 0.8069 0.5586 +vn -0.2178 0.7022 0.6779 +vn 0.1562 0.7886 0.5947 +vn 0.3919 0.7190 0.5739 +vn 0.4733 0.7727 0.4230 +vn 0.3709 0.7749 -0.5117 +vn -0.2292 0.6954 -0.6810 +vn -0.3419 0.8065 -0.4824 +vn -0.5499 0.7125 -0.4358 +vn -0.5907 0.8020 -0.0885 +vn -0.6911 0.7227 -0.0068 +vn -0.6557 0.7118 0.2518 +vn 0.0797 0.7289 -0.6800 +vn -0.7491 0.6132 -0.2508 +vn 0.1105 0.6785 0.7262 +vn 0.6335 0.7110 0.3052 +vn 0.6131 0.7816 0.1148 +vn 0.7617 0.6474 0.0254 +vn 0.5520 0.7348 -0.3942 +vn -0.6414 0.6111 0.4638 +vn 0.7175 0.6285 -0.3004 +vn -0.4644 0.5726 -0.6756 +vn 0.5652 0.5847 -0.5819 +vn 0.2920 0.5916 -0.7515 +vn -0.0393 0.5625 -0.8258 +vn -0.8231 0.5495 0.1434 +vn -0.5201 0.4960 0.6953 +vn 0.5487 0.5796 0.6024 +vn -0.1504 0.5091 0.8475 +vn 0.3158 0.5129 0.7982 +vn 0.7195 0.5624 0.4075 +vn -0.6212 0.5139 -0.5916 +vn 0.8344 0.5281 -0.1579 +vn 0.5859 0.5127 -0.6275 +vn -0.2729 0.4916 -0.8269 +vn -0.8140 0.5199 -0.2592 +vn -0.8755 0.4790 0.0634 +vn -0.7448 0.4696 0.4741 +vn 0.0963 0.4783 0.8729 +vn 0.5306 0.4648 0.7088 +vn 0.7910 0.4828 0.3758 +vn 0.8401 0.5250 0.1365 +vn 0.7440 0.5101 -0.4317 +vn 0.3990 0.4989 -0.7693 +vn 0.0861 0.4796 -0.8732 +vn -0.3555 0.4689 0.8086 +vn 0.7110 0.7022 0.0379 +vn 0.7221 0.6627 0.1985 +vn 0.7022 0.7117 -0.0200 +vn 0.6653 0.7249 -0.1786 +vn 0.4734 0.7422 -0.4743 +vn 0.3703 0.7218 -0.5847 +vn 0.3093 0.7035 -0.6398 +vn 0.1918 0.6562 -0.7298 +vn -0.1726 0.7424 -0.6473 +vn -0.3218 0.7216 -0.6129 +vn -0.4007 0.7028 -0.5877 +vn -0.5394 0.6546 -0.5297 +vn -0.7109 0.7023 -0.0380 +vn -0.7223 0.6619 -0.2005 +vn -0.7020 0.7118 0.0208 +vn -0.6646 0.7249 0.1814 +vn -0.3881 0.7021 0.5970 +vn -0.5334 0.6622 0.5263 +vn -0.3332 0.7117 0.6185 +vn -0.1769 0.7248 0.6659 +vn 0.1820 0.7034 0.6871 +vn 0.3498 0.7161 0.6040 +vn 0.3495 0.7161 0.6042 +vn 0.5049 0.7036 0.5000 +vn 1.0000 0.0028 -0.0001 +vn 1.0000 0.0016 0.0025 +vn 1.0000 0.0011 -0.0020 +vn 1.0000 0.0036 -0.0068 +vn 1.0000 0.0041 0.0065 +vn 0.4976 0.0020 -0.8674 +vn 0.4999 0.0031 -0.8661 +vn 0.5017 0.0010 -0.8650 +vn 0.4931 0.0051 -0.8700 +vn 0.5057 0.0033 -0.8627 +vn -0.5023 0.0021 -0.8647 +vn -0.5001 0.0031 -0.8660 +vn -0.4982 0.0011 -0.8671 +vn -0.5070 0.0053 -0.8619 +vn -0.4937 0.0036 -0.8696 +vn -1.0000 0.0011 0.0020 +vn -1.0000 0.0028 0.0001 +vn -1.0000 0.0016 -0.0025 +vn -1.0000 0.0036 0.0068 +vn -1.0000 0.0045 -0.0073 +vn -0.4981 0.0010 0.8671 +vn -0.4998 0.0028 0.8661 +vn -0.5020 0.0017 0.8649 +vn -0.4938 0.0037 0.8696 +vn -0.5058 0.0045 0.8626 +vn 0.5023 0.0014 0.8647 +vn 0.4998 0.0032 0.8661 +vn 0.4976 0.0015 0.8674 +vn 0.5064 0.0045 0.8623 +vn 0.4933 0.0044 0.8699 +vn 0.0046 0.0080 -1.0000 +vn 0.3412 0.0839 -0.9362 +vn 0.0028 0.0058 -1.0000 +vn 0.0029 0.0056 -1.0000 +vn 0.0031 0.0070 -1.0000 +vn -0.0027 -0.0002 -1.0000 +vn -0.3568 0.0949 -0.9294 +vn -0.2110 0.3017 -0.9298 +vn 0.1232 -0.3565 -0.9261 +vn 0.0015 -0.0089 -1.0000 +vn 0.0002 -0.0029 -1.0000 +vn 0.3384 -0.1650 -0.9264 +vn 0.0005 -0.0106 -0.9999 +vn -0.0010 -0.0023 -1.0000 +vn -0.0018 -0.0005 -1.0000 +vn -0.0026 0.0000 -1.0000 +vn -0.0169 0.0049 0.9998 +vn 0.0081 -0.0087 0.9999 +vn 0.0120 -0.0014 0.9999 +vn 0.0056 -0.0140 0.9999 +vn 0.0089 -0.0111 0.9999 +vn 0.0049 -0.0112 0.9999 +vn -0.0207 -0.0193 0.9996 +vn -0.0427 -0.0160 0.9990 +vn 0.0139 0.0263 0.9996 +vn -0.0058 0.0668 0.9977 +vn 0.0142 0.0302 0.9994 +vn 0.0124 0.0078 0.9999 +vn 0.9392 0.3435 -0.0048 +vn 0.9970 0.0771 0.0082 +vn 0.9615 -0.2748 -0.0008 +vn 0.9372 -0.3486 0.0046 +vn 0.6574 -0.7535 0.0001 +vn 0.6763 -0.7366 0.0051 +vn 0.2198 -0.9755 0.0061 +vn 0.1236 -0.9923 -0.0022 +vn -0.2991 -0.9542 0.0107 +vn -0.5356 -0.8444 -0.0065 +vn -0.7637 -0.6455 0.0112 +vn -0.9743 -0.2253 -0.0067 +vn -0.9803 -0.1976 0.0068 +vn -0.9714 0.2373 0.0063 +vn -0.9066 0.4219 -0.0037 +vn -0.7714 0.6363 0.0091 +vn -0.4470 0.8945 -0.0059 +vn -0.4031 0.9151 0.0060 +vn 0.0353 0.9994 0.0063 +vn 0.3745 0.9272 -0.0084 +vn 0.5004 0.8658 0.0077 +vn 0.8548 0.5189 0.0057 +vn 0.9975 0.0667 -0.0227 +vn 0.9518 0.1714 -0.2545 +vn 0.8914 0.4532 0.0038 +vn 0.8620 0.4413 -0.2493 +vn 0.7165 0.6530 -0.2454 +vn 0.6426 0.7662 0.0068 +vn 0.5004 0.8313 -0.2419 +vn 0.2996 0.9540 -0.0106 +vn 0.2457 0.9306 -0.2713 +vn -0.0967 0.9668 -0.2365 +vn -0.1546 0.9880 0.0040 +vn -0.5791 0.8150 -0.0182 +vn -0.5417 0.8021 -0.2515 +vn -0.8158 0.5384 -0.2112 +vn -0.9218 0.3871 -0.0198 +vn -0.9524 0.2048 -0.2257 +vn -0.9982 -0.0567 0.0181 +vn -0.9572 -0.1493 -0.2480 +vn -0.8989 -0.4301 -0.0839 +vn -0.7884 -0.5775 -0.2117 +vn -0.5944 -0.8038 -0.0255 +vn -0.5039 -0.8183 -0.2765 +vn -0.2720 -0.9408 -0.2023 +vn -0.0539 -0.9955 -0.0780 +vn 0.1755 -0.9597 -0.2196 +vn 0.4231 -0.9040 -0.0605 +vn 0.5745 -0.7865 -0.2267 +vn 0.7559 -0.6534 -0.0399 +vn 0.8289 -0.5073 -0.2358 +vn 0.9463 -0.3221 -0.0288 +vn 0.9574 -0.1725 -0.2317 +vn -0.6697 -0.0940 -0.7366 +vn -0.8041 -0.1703 -0.5696 +vn -0.7933 0.0714 -0.6046 +vn -0.5481 -0.1484 -0.8231 +vn -0.6191 -0.3049 -0.7237 +vn -0.6941 -0.4579 -0.5555 +vn -0.4020 -0.4387 -0.8037 +vn -0.4647 -0.5253 -0.7128 +vn -0.4006 -0.6962 -0.5957 +vn -0.2074 -0.6454 -0.7352 +vn -0.0942 -0.8257 -0.5562 +vn -0.0639 -0.5981 -0.7989 +vn 0.0832 -0.7230 -0.6858 +vn 0.3032 -0.7886 -0.5349 +vn 0.3923 -0.6226 -0.6770 +vn 0.4709 -0.3971 -0.7877 +vn 0.6215 -0.5313 -0.5757 +vn 0.7496 -0.2958 -0.5921 +vn 0.6275 -0.1147 -0.7701 +vn 0.8026 0.0057 -0.5965 +vn 0.6739 0.1430 -0.7248 +vn 0.7498 0.3409 -0.5671 +vn 0.5614 0.3345 -0.7569 +vn 0.3790 0.4675 -0.7986 +vn 0.5503 0.5326 -0.6431 +vn 0.4076 0.6912 -0.5967 +vn 0.2211 0.6003 -0.7686 +vn 0.1488 0.7709 -0.6193 +vn 0.0001 0.6059 -0.7955 +vn -0.0858 0.7584 -0.6462 +vn -0.3144 0.8081 -0.4981 +vn -0.2663 0.6222 -0.7361 +vn -0.4754 0.6178 -0.6263 +vn -0.4972 0.3726 -0.7836 +vn -0.6505 0.4986 -0.5729 +vn -0.7099 0.2536 -0.6571 +vn -0.2168 0.0256 0.9759 +vn 0.0028 0.0009 -1.0000 +vn 0.0129 0.0029 -0.9999 +vn 0.0089 0.0012 -1.0000 +vn 0.0145 -0.0164 -0.9998 +vn 0.0107 -0.0039 -0.9999 +vn 0.0146 -0.0170 -0.9997 +vn -0.0050 0.0073 -1.0000 +vn -0.0017 0.0056 -1.0000 +vn -0.0078 0.0070 -0.9999 +vn 0.0067 0.0055 -1.0000 +vn -0.0015 -0.0020 -1.0000 +vn 0.0026 -0.0012 -1.0000 +vn -0.0167 0.0126 -0.9998 +vn -0.0158 0.0141 -0.9998 +vn -0.0052 0.0004 -1.0000 +vn -0.0043 0.0004 -1.0000 +vn -0.0124 0.0026 -0.9999 +vn 0.0061 0.0055 1.0000 +vn 0.0610 -0.0073 0.9981 +vn 0.0769 -0.0022 0.9970 +vn 0.0087 -0.0129 0.9999 +vn 0.0090 -0.0165 0.9998 +vn -0.0048 -0.0065 1.0000 +vn -0.0132 -0.0050 0.9999 +vn -0.0076 -0.0105 0.9999 +vn -0.0111 -0.0019 0.9999 +vn -0.0164 0.0180 0.9997 +vn -0.0178 0.0400 0.9990 +vn -0.0149 0.0584 0.9982 +vn 0.9998 0.0201 0.0013 +vn 0.9728 -0.2315 0.0014 +vn 0.9645 -0.2639 -0.0004 +vn 0.7771 -0.6293 0.0086 +vn 0.6036 -0.7972 -0.0047 +vn 0.3489 -0.9371 0.0128 +vn -0.0868 -0.9962 -0.0080 +vn -0.2871 -0.9578 0.0110 +vn -0.4519 -0.8920 -0.0078 +vn -0.5856 -0.8105 0.0102 +vn -0.9822 -0.1878 -0.0103 +vn -0.9145 -0.4045 0.0085 +vn -0.9760 -0.2178 0.0049 +vn -0.9705 0.2410 -0.0088 +vn -0.9795 0.2013 0.0066 +vn -0.7888 0.6146 0.0088 +vn -0.5221 0.8529 -0.0047 +vn -0.4027 0.9153 0.0051 +vn -0.1868 0.9824 -0.0028 +vn -0.1496 0.9887 0.0019 +vn 0.6304 0.7763 -0.0093 +vn 0.4422 0.8968 0.0115 +vn 0.6578 0.7531 0.0113 +vn 0.6564 0.7544 -0.0092 +vn 0.8302 0.5573 0.0131 +vn 1.0000 -0.0033 -0.0015 +vn 0.9670 0.0325 -0.2527 +vn 0.8858 0.4127 -0.2123 +vn 0.9952 0.0978 0.0069 +vn 0.9368 0.3070 0.1678 +vn 0.5945 0.7770 -0.2070 +vn 0.7275 0.6660 -0.1649 +vn 0.4584 0.8887 0.0064 +vn 0.3143 0.9163 -0.2483 +vn 0.0801 0.9967 0.0127 +vn 0.0151 0.9730 -0.2304 +vn -0.3768 0.9252 -0.0445 +vn -0.2361 0.9430 -0.2348 +vn -0.5583 0.8014 -0.2147 +vn -0.7461 0.6657 -0.0079 +vn -0.8161 0.5357 -0.2168 +vn -0.9417 0.3343 -0.0385 +vn -0.9572 0.1792 -0.2273 +vn -0.9979 -0.0625 -0.0175 +vn -0.9534 -0.1838 -0.2394 +vn -0.8868 -0.4615 -0.0250 +vn -0.8323 -0.4577 -0.3125 +vn -0.6874 -0.6955 -0.2092 +vn -0.5718 -0.8201 -0.0208 +vn -0.3984 -0.8861 -0.2368 +vn -0.2177 -0.9505 -0.2215 +vn -0.1205 -0.9927 -0.0039 +vn 0.1433 -0.9630 -0.2284 +vn 0.3460 -0.9305 -0.1207 +vn 0.6090 -0.7622 -0.2193 +vn 0.7365 -0.6759 -0.0267 +vn 0.8842 -0.3958 -0.2481 +vn 0.9598 -0.2795 -0.0263 +vn -0.7327 -0.2169 -0.6451 +vn -0.7979 0.0123 -0.6026 +vn -0.6220 -0.0262 -0.7826 +vn -0.5255 -0.3438 -0.7783 +vn -0.5929 -0.4217 -0.6860 +vn -0.5867 -0.5962 -0.5480 +vn -0.4017 -0.6360 -0.6589 +vn -0.2657 -0.5379 -0.8000 +vn -0.1908 -0.6658 -0.7213 +vn -0.1283 -0.8083 -0.5746 +vn 0.0323 -0.6558 -0.7543 +vn 0.1070 -0.5505 -0.8279 +vn 0.1449 -0.7925 -0.5924 +vn 0.3041 -0.6154 -0.7272 +vn 0.3900 -0.7819 -0.4863 +vn 0.4768 -0.4123 -0.7763 +vn 0.5780 -0.5394 -0.6123 +vn 0.6611 -0.3501 -0.6635 +vn 0.6346 -0.1062 -0.7655 +vn 0.7543 -0.1616 -0.6363 +vn 0.7964 0.0522 -0.6025 +vn 0.6630 0.1991 -0.7216 +vn 0.5515 0.2039 -0.8089 +vn 0.7608 0.3017 -0.5746 +vn 0.5145 0.4220 -0.7465 +vn 0.6333 0.5512 -0.5431 +vn 0.3563 0.4745 -0.8049 +vn 0.3944 0.6447 -0.6549 +vn 0.0960 0.6632 -0.7423 +vn 0.1602 0.5731 -0.8037 +vn 0.2118 0.7836 -0.5840 +vn -0.0629 0.8156 -0.5752 +vn -0.1446 0.6056 -0.7825 +vn -0.2832 0.7247 -0.6282 +vn -0.3816 0.5624 -0.7336 +vn -0.5103 0.3687 -0.7770 +vn -0.5940 0.5647 -0.5729 +vn -0.7296 0.3456 -0.5901 +vn -0.7049 0.1581 -0.6914 +vn 0.9577 -0.2844 0.0427 +vn 0.9937 0.0977 -0.0546 +vn 0.9846 0.1604 -0.0701 +vn 0.8328 -0.0778 -0.5481 +vn 0.8392 -0.0378 -0.5425 +vn 0.8505 0.0943 -0.5175 +vn 0.8507 0.1441 -0.5055 +vn 0.5088 -0.1574 -0.8464 +vn 0.5230 -0.2293 -0.8209 +vn 0.3985 0.1984 -0.8954 +vn 0.3729 0.2598 -0.8907 +vn 0.0547 -0.1232 -0.9909 +vn 0.0846 -0.1904 -0.9780 +vn -0.0691 0.1557 -0.9854 +vn -0.0978 0.2202 -0.9705 +vn -0.3873 -0.3479 -0.8538 +vn -0.5647 0.3141 -0.7631 +vn -0.9035 -0.0761 -0.4219 +vn -0.9033 -0.0692 -0.4233 +vn -0.9027 -0.0472 -0.4276 +vn -0.9026 -0.0435 -0.4283 +vn -0.9741 0.0015 0.2260 +vn -0.9748 0.0383 0.2199 +vn -0.9498 0.2581 0.1768 +vn -0.9248 0.3472 0.1558 +vn -0.7367 -0.3538 0.5763 +vn -0.4994 0.3690 0.7839 +vn -0.3614 -0.2477 0.8989 +vn 0.0548 0.2796 0.9585 +vn 0.2274 -0.2799 0.9327 +vn 0.5240 0.2196 0.8229 +vn 0.6954 -0.3123 0.6472 +vn 0.8198 0.3255 0.4712 +vn 0.9424 -0.3300 0.0546 +vn -0.9034 -0.4282 -0.0201 +vn -0.8887 0.3532 0.2922 +vn -0.7861 -0.2982 0.5414 +vn -0.7812 -0.3315 0.5289 +vn -0.7108 0.0390 0.7023 +vn -0.6126 -0.0036 0.7904 +vn -0.4493 0.0411 0.8925 +vn -0.3056 -0.1240 0.9440 +vn -0.2380 -0.2023 0.9500 +vn -0.0752 0.3932 0.9164 +vn 0.1067 -0.3372 0.9354 +vn 0.4755 0.2250 0.8504 +vn 0.4750 0.2602 0.8407 +vn 0.4718 0.0943 0.8767 +vn 0.4710 0.0824 0.8783 +vn 0.8515 -0.0885 0.5169 +vn 0.8531 -0.0768 0.5160 +vn 0.8295 -0.2009 0.5211 +vn 0.8201 -0.2365 0.5211 +vn 0.9375 0.2644 0.2263 +vn 0.8961 -0.4434 0.0177 +vn 0.8828 0.4398 -0.1650 +vn 0.7790 -0.4141 -0.4709 +vn 0.7576 0.2372 -0.6081 +vn 0.7226 0.1539 -0.6740 +vn 0.6036 -0.0289 -0.7968 +vn 0.4501 0.0378 -0.8922 +vn 0.3058 -0.1244 -0.9439 +vn 0.2380 -0.2026 -0.9499 +vn 0.0754 0.3928 -0.9165 +vn -0.1067 -0.3372 -0.9354 +vn -0.4831 0.2062 -0.8509 +vn -0.4817 0.2747 -0.8322 +vn -0.4668 -0.0559 -0.8826 +vn -0.4611 -0.0981 -0.8819 +vn -0.8273 0.2306 -0.5122 +vn -0.8345 0.2032 -0.5121 +vn -0.8608 -0.2029 -0.4667 +vn -0.8571 -0.2311 -0.4604 +vn -0.9943 0.0981 0.0417 +vn -0.9710 -0.2118 -0.1111 +vn -0.9766 -0.1778 -0.1210 +vn -0.9155 0.0266 -0.4014 +vn -0.8830 0.0441 -0.4673 +vn -0.7493 -0.0686 -0.6587 +vn -0.7478 -0.0767 -0.6595 +vn -0.1824 0.0042 -0.9832 +vn -0.1845 -0.0076 -0.9828 +vn -0.1956 -0.0736 -0.9779 +vn -0.1979 -0.0881 -0.9763 +vn 0.3599 0.1061 -0.9269 +vn 0.3406 0.1682 -0.9250 +vn 0.4375 -0.2374 -0.8673 +vn 0.4438 -0.2841 -0.8499 +vn 0.7375 0.2821 -0.6136 +vn 0.8467 -0.2444 -0.4726 +vn 0.9807 0.1749 -0.0874 +vn 0.9718 0.2148 -0.0970 +vn 0.9908 -0.1352 -0.0090 +vn 0.9839 -0.1789 0.0022 +vn 0.8147 0.2624 0.5172 +vn 0.7073 -0.3649 0.6054 +vn 0.3417 0.3255 0.8816 +vn 0.1345 -0.3121 0.9405 +vn -0.1356 0.2766 0.9514 +vn -0.3969 -0.3633 0.8429 +vn -0.6317 0.3329 0.7001 +vn -0.8419 -0.2906 0.4546 +vn -0.8631 -0.2376 0.4456 +vn -0.9283 0.1237 0.3505 +vn -0.9259 0.1881 0.3276 +vn 0.9996 -0.0259 0.0143 +vn 0.9811 -0.0960 0.1680 +vn 0.8696 0.1029 0.4828 +vn 0.7878 0.0258 0.6154 +vn 0.5890 -0.0128 0.8080 +vn 0.5391 -0.0052 0.8422 +vn 0.2980 -0.0125 0.9545 +vn 0.1554 0.0533 0.9864 +vn -0.0231 -0.2769 0.9606 +vn -0.0292 -0.3079 0.9510 +vn -0.3351 0.3770 0.8635 +vn -0.4709 -0.5000 0.7268 +vn -0.6678 0.4458 0.5960 +vn -0.8492 -0.3539 0.3919 +vn -0.9607 0.1401 0.2396 +vn -0.9331 0.2184 0.2857 +vn -0.9951 -0.0721 0.0679 +vn -0.9694 0.2297 -0.0872 +vn -0.9567 0.2737 -0.0994 +vn -0.9081 -0.3038 -0.2884 +vn -0.7839 0.3566 -0.5083 +vn -0.7365 -0.2465 -0.6300 +vn -0.4535 0.2105 -0.8660 +vn -0.4534 0.2060 -0.8672 +vn -0.4544 0.2603 -0.8519 +vn -0.4544 0.2837 -0.8444 +vn -0.1220 -0.4003 -0.9082 +vn 0.0870 0.5296 -0.8438 +vn 0.3119 -0.4048 -0.8596 +vn 0.5792 0.2329 -0.7812 +vn 0.5638 0.2736 -0.7793 +vn 0.7024 -0.0798 -0.7072 +vn 0.8153 0.1152 -0.5675 +vn 0.9174 -0.0856 -0.3886 +vn 0.9736 0.0887 -0.2105 +s 1 +f 1/1/1 2/2/1 3/3/1 +f 3/3/1 4/4/1 1/1/1 +f 5/5/2 6/6/2 7/7/2 +f 7/7/2 8/8/2 5/5/2 +f 9/9/3 10/10/4 11/11/5 +f 12/12/6 13/13/7 10/10/4 +f 14/14/8 15/15/9 16/16/10 +f 16/16/10 15/15/9 12/12/6 +f 15/15/9 13/13/7 12/12/6 +f 17/17/11 18/18/12 11/11/5 +f 11/11/5 18/18/12 9/9/3 +f 18/18/12 17/17/11 19/19/13 +f 12/12/6 10/10/4 9/9/3 +f 20/20/14 21/21/15 14/14/8 +f 20/20/14 14/14/8 16/16/10 +f 22/22/16 23/23/17 24/24/18 +f 24/24/18 21/21/15 20/20/14 +f 19/19/13 22/22/16 18/18/12 +f 22/22/16 19/19/13 23/23/17 +f 22/22/16 24/24/18 20/20/14 +f 25/25/19 26/26/20 27/27/21 +f 25/25/19 28/28/22 26/26/20 +f 25/25/19 29/29/23 28/28/22 +f 30/30/24 29/29/23 25/25/19 +f 25/25/19 31/31/25 30/30/24 +f 25/25/19 32/32/26 31/31/25 +f 25/25/19 33/33/27 32/32/26 +f 25/25/19 34/34/28 33/33/27 +f 25/25/19 35/35/29 34/34/28 +f 36/36/30 27/27/31 26/26/32 +f 36/36/30 26/26/32 37/37/33 +f 37/37/33 26/26/32 28/28/34 +f 37/37/33 28/28/34 38/38/35 +f 38/38/35 28/28/34 29/29/36 +f 38/38/35 29/29/36 39/39/37 +f 39/39/37 29/29/36 30/30/38 +f 39/39/37 30/30/38 40/40/39 +f 40/40/39 30/30/38 31/31/40 +f 40/40/41 31/31/42 32/32/43 +f 40/40/41 32/32/43 41/41/44 +f 41/41/45 32/32/46 33/33/47 +f 41/41/45 33/33/47 42/42/48 +f 42/42/48 33/33/47 34/34/49 +f 42/42/48 34/34/49 43/43/50 +f 43/43/50 34/34/49 35/35/51 +f 43/43/52 35/35/53 25/25/54 +f 43/43/52 25/25/54 44/44/55 +f 44/44/56 25/25/57 27/27/31 +f 44/44/56 27/27/31 36/36/30 +f 36/36/1 45/45/1 46/46/1 +f 42/42/1 47/47/1 41/41/1 +f 41/41/1 47/47/1 48/48/1 +f 44/44/1 49/49/1 43/43/1 +f 36/36/1 46/46/1 44/44/1 +f 44/44/1 46/46/1 50/50/1 +f 42/42/1 51/51/1 47/47/1 +f 44/44/1 50/50/1 49/49/1 +f 43/43/1 49/49/1 52/52/1 +f 37/37/1 53/53/1 45/45/1 +f 37/37/1 45/45/1 36/36/1 +f 41/41/1 48/48/1 54/54/1 +f 41/41/1 54/54/1 40/40/1 +f 43/43/1 51/51/1 42/42/1 +f 38/38/1 53/53/1 37/37/1 +f 38/38/1 55/55/1 53/53/1 +f 43/43/1 52/52/1 51/51/1 +f 39/39/1 56/56/1 55/55/1 +f 39/39/1 55/55/1 38/38/1 +f 40/40/1 54/54/1 57/57/1 +f 40/40/1 57/57/1 39/39/1 +f 39/39/1 57/57/1 56/56/1 +f 46/46/58 58/58/59 50/50/60 +f 58/58/59 59/59/61 50/50/60 +f 59/59/61 60/60/62 50/50/60 +f 50/50/60 60/60/62 49/49/63 +f 60/60/62 61/61/64 49/49/63 +f 49/49/63 61/61/64 52/52/65 +f 61/61/64 62/62/66 52/52/65 +f 52/52/65 62/62/66 63/63/67 +f 63/63/67 51/51/68 52/52/65 +f 63/63/67 64/64/69 51/51/68 +f 65/65/70 47/47/71 51/51/68 +f 65/65/70 51/51/68 64/64/69 +f 47/47/71 65/65/70 66/66/72 +f 47/47/71 66/66/72 48/48/73 +f 66/66/72 67/67/74 48/48/73 +f 48/48/73 67/67/74 68/68/75 +f 68/68/75 54/54/76 48/48/73 +f 68/68/75 69/69/77 54/54/76 +f 69/69/77 57/57/78 54/54/76 +f 69/69/77 70/70/79 57/57/78 +f 57/57/78 70/70/79 56/56/80 +f 56/56/80 70/70/79 71/71/81 +f 56/56/80 71/71/81 55/55/82 +f 71/71/81 72/72/83 55/55/82 +f 55/55/82 72/72/83 53/53/84 +f 72/72/83 73/73/85 53/53/84 +f 53/53/84 73/73/85 74/74/86 +f 53/53/84 74/74/86 45/45/87 +f 74/74/86 75/75/88 45/45/87 +f 45/45/87 75/75/88 46/46/58 +f 46/46/58 75/75/88 58/58/59 +f 67/67/74 76/76/89 68/68/75 +f 77/77/90 68/68/75 76/76/89 +f 78/78/91 76/76/89 24/24/92 +f 24/24/92 23/23/93 78/78/91 +f 76/76/89 78/78/91 77/77/90 +f 77/77/90 69/69/77 68/68/75 +f 77/77/90 78/78/91 69/69/77 +f 79/79/94 69/69/77 78/78/91 +f 78/78/91 23/23/93 79/79/94 +f 23/23/93 80/80/95 79/79/94 +f 69/69/77 79/79/94 70/70/79 +f 79/79/94 81/81/96 70/70/79 +f 81/81/96 79/79/94 80/80/95 +f 19/19/97 80/80/95 23/23/93 +f 82/82/98 70/70/79 81/81/96 +f 80/80/95 19/19/97 83/83/99 +f 80/80/95 83/83/99 81/81/96 +f 81/81/96 83/83/99 82/82/98 +f 82/82/98 71/71/81 70/70/79 +f 71/71/81 82/82/98 84/84/100 +f 84/84/100 82/82/98 83/83/99 +f 17/17/101 83/83/99 19/19/97 +f 83/83/99 17/17/101 84/84/100 +f 72/72/83 71/71/81 84/84/100 +f 84/84/100 17/17/101 85/85/102 +f 84/84/100 85/85/102 72/72/83 +f 73/73/85 72/72/83 85/85/102 +f 86/86/103 85/85/102 17/17/101 +f 86/86/103 17/17/101 11/11/104 +f 87/87/105 85/85/102 86/86/103 +f 85/85/102 87/87/105 73/73/85 +f 73/73/85 87/87/105 74/74/86 +f 88/88/106 87/87/105 86/86/103 +f 11/11/104 88/88/106 86/86/103 +f 10/10/107 88/88/106 11/11/104 +f 74/74/86 87/87/105 75/75/88 +f 87/87/105 88/88/106 89/89/108 +f 87/87/105 89/89/108 75/75/88 +f 89/89/108 88/88/106 10/10/107 +f 90/90/109 89/89/108 10/10/107 +f 89/89/108 91/91/110 75/75/88 +f 89/89/108 90/90/109 91/91/110 +f 75/75/88 91/91/110 58/58/59 +f 10/10/107 13/13/7 90/90/109 +f 59/59/61 58/58/59 91/91/110 +f 90/90/109 13/13/7 92/92/111 +f 90/90/109 92/92/111 91/91/110 +f 93/93/112 59/59/61 91/91/110 +f 93/93/112 91/91/110 92/92/111 +f 60/60/62 59/59/61 93/93/112 +f 94/94/113 92/92/111 13/13/7 +f 95/95/114 93/93/112 92/92/111 +f 95/95/114 92/92/111 94/94/113 +f 93/93/112 95/95/114 60/60/62 +f 15/15/9 94/94/113 13/13/7 +f 61/61/64 60/60/62 95/95/114 +f 61/61/64 95/95/114 96/96/115 +f 96/96/115 95/95/114 94/94/113 +f 97/97/116 96/96/115 15/15/9 +f 15/15/9 96/96/115 94/94/113 +f 61/61/64 96/96/115 62/62/66 +f 15/15/9 14/14/117 97/97/116 +f 96/96/115 97/97/116 98/98/118 +f 62/62/66 96/96/115 63/63/67 +f 98/98/118 63/63/67 96/96/115 +f 97/97/116 14/14/117 98/98/118 +f 64/64/69 63/63/67 98/98/118 +f 99/99/119 64/64/69 98/98/118 +f 99/99/119 98/98/118 14/14/117 +f 64/64/69 99/99/119 65/65/70 +f 100/100/120 99/99/119 14/14/117 +f 100/100/120 14/14/117 21/21/121 +f 99/99/119 100/100/120 65/65/70 +f 66/66/72 65/65/70 100/100/120 +f 100/100/120 21/21/121 101/101/122 +f 102/102/123 66/66/72 100/100/120 +f 102/102/123 100/100/120 101/101/122 +f 66/66/72 102/102/123 67/67/74 +f 67/67/74 102/102/123 76/76/89 +f 76/76/89 102/102/123 101/101/122 +f 24/24/92 101/101/122 21/21/121 +f 76/76/89 101/101/122 24/24/92 +f 12/12/124 9/9/124 103/103/124 +f 103/103/124 9/9/124 104/104/124 +f 16/16/125 12/12/125 105/105/125 +f 105/105/125 12/12/125 103/103/126 +f 20/20/127 16/16/127 106/106/127 +f 106/106/127 16/16/127 105/105/127 +f 22/22/128 20/20/128 107/107/128 +f 107/107/128 20/20/128 106/106/128 +f 18/18/129 22/22/129 108/108/129 +f 108/108/129 22/22/129 107/107/129 +f 9/9/130 18/18/130 104/104/130 +f 104/104/130 18/18/130 108/108/130 +f 108/108/2 107/107/2 104/104/2 +f 104/104/2 107/107/2 106/106/2 +f 104/104/2 106/106/2 103/103/2 +f 103/103/2 106/106/2 105/105/2 +f 109/109/131 110/110/132 111/111/133 +f 112/112/134 110/110/132 109/109/131 +f 113/113/135 111/111/133 110/110/132 +f 114/114/136 113/113/135 115/115/137 +f 115/115/137 116/116/138 117/117/139 +f 118/118/140 117/117/139 116/116/138 +f 119/119/141 120/120/142 121/121/143 +f 122/122/144 123/123/145 124/124/146 +f 125/125/147 126/126/147 127/127/147 +f 128/128/147 127/127/147 129/129/147 +f 130/130/147 131/131/147 132/132/147 +f 128/128/147 129/129/147 133/133/147 +f 134/134/147 126/126/147 125/125/147 +f 134/134/147 135/135/147 126/126/147 +f 125/125/147 127/127/147 128/128/147 +f 136/136/148 137/137/149 138/138/150 +f 136/136/148 138/138/150 139/139/151 +f 140/140/152 137/137/149 136/136/148 +f 140/140/152 135/135/153 137/137/149 +f 141/141/154 135/135/153 140/140/152 +f 141/141/154 126/126/155 135/135/153 +f 142/142/156 143/143/157 144/144/158 +f 142/142/156 144/144/158 145/145/159 +f 146/146/160 147/147/161 148/148/162 +f 149/149/163 150/150/164 151/151/165 +f 151/151/165 150/150/164 152/152/166 +f 153/153/167 154/154/168 155/155/169 +f 153/153/167 156/156/170 154/154/168 +f 157/157/171 158/158/172 156/156/170 +f 159/159/173 160/160/174 158/158/172 +f 159/159/173 158/158/172 157/157/171 +f 139/139/151 160/160/174 159/159/173 +f 161/161/2 162/162/2 163/163/2 +f 139/139/151 138/138/150 160/160/174 +f 161/161/2 164/164/2 162/162/2 +f 165/165/175 150/150/164 149/149/163 +f 149/149/163 166/166/176 165/165/175 +f 143/143/157 167/167/177 144/144/158 +f 148/148/162 166/166/176 146/146/160 +f 146/146/160 168/168/178 147/147/161 +f 148/148/162 165/165/175 166/166/176 +f 167/167/177 143/143/157 169/169/179 +f 169/169/179 151/151/165 152/152/166 +f 167/167/177 169/169/179 152/152/166 +f 170/170/147 171/171/147 172/172/147 +f 164/164/180 161/161/181 173/173/182 +f 161/161/181 174/174/183 173/173/182 +f 163/163/184 162/162/185 175/175/186 +f 175/175/186 162/162/185 176/176/187 +f 168/168/178 146/146/188 177/177/189 +f 176/176/190 152/152/191 150/150/192 +f 178/178/193 152/152/191 176/176/190 +f 178/178/193 167/167/194 152/152/191 +f 171/171/195 144/144/196 178/178/193 +f 178/178/193 144/144/196 167/167/194 +f 171/171/195 145/145/159 144/144/196 +f 170/170/197 145/145/159 171/171/195 +f 142/142/156 145/145/159 170/170/197 +f 179/179/198 142/142/156 170/170/197 +f 142/142/156 179/179/198 143/143/199 +f 143/143/199 179/179/198 172/172/200 +f 172/172/200 169/169/201 143/143/199 +f 174/174/183 149/149/202 151/151/203 +f 173/173/182 151/151/203 172/172/200 +f 172/172/200 151/151/203 169/169/201 +f 180/180/204 149/149/202 174/174/183 +f 180/180/204 166/166/205 149/149/202 +f 181/181/206 166/166/205 180/180/204 +f 177/177/189 146/146/188 181/181/206 +f 181/181/206 146/146/188 166/166/205 +f 182/182/207 168/168/178 177/177/189 +f 182/182/207 147/147/161 168/168/178 +f 147/147/161 182/182/207 183/183/208 +f 147/147/161 183/183/208 148/148/209 +f 175/175/210 165/165/211 183/183/208 +f 183/183/208 165/165/211 148/148/209 +f 175/175/210 150/150/212 165/165/211 +f 151/151/203 173/173/182 174/174/183 +f 150/150/213 175/175/213 176/176/213 +f 141/141/214 119/119/215 123/123/216 +f 139/139/217 117/117/218 136/136/219 +f 140/140/220 119/119/215 141/141/214 +f 136/136/219 184/184/221 140/140/220 +f 136/136/219 117/117/218 184/184/221 +f 140/140/220 184/184/221 119/119/215 +f 185/185/222 115/115/223 113/113/224 +f 186/186/225 115/115/223 185/185/222 +f 110/110/226 185/185/222 113/113/224 +f 187/187/227 131/131/228 188/188/229 +f 189/189/230 129/129/231 127/127/232 +f 189/189/230 127/127/232 190/190/233 +f 188/188/229 131/131/228 133/133/234 +f 157/157/171 156/156/170 153/153/167 +f 155/155/169 154/154/168 191/191/235 +f 192/192/236 191/191/237 193/193/238 +f 155/155/169 191/191/235 192/192/239 +f 192/192/236 193/193/238 194/194/240 +f 194/194/241 193/193/242 187/187/243 +f 188/188/229 133/133/234 189/189/230 +f 187/187/243 193/193/242 131/131/244 +f 190/190/245 127/127/246 126/126/155 +f 190/190/245 126/126/155 141/141/154 +f 189/189/230 133/133/234 129/129/231 +f 124/124/247 195/195/248 196/196/249 +f 121/121/250 195/195/248 124/124/247 +f 195/195/248 121/121/250 120/120/251 +f 195/195/248 120/120/251 118/118/252 +f 195/195/248 118/118/252 197/197/253 +f 197/197/253 118/118/252 116/116/254 +f 197/197/253 116/116/254 186/186/225 +f 115/115/223 186/186/225 116/116/254 +f 198/198/255 199/199/256 200/200/257 +f 201/201/258 199/199/256 198/198/255 +f 202/202/259 200/200/257 203/203/260 +f 198/198/255 200/200/257 202/202/259 +f 204/204/261 203/203/260 205/205/262 +f 202/202/259 203/203/260 204/204/261 +f 201/201/258 206/206/263 199/199/256 +f 207/207/264 206/206/263 201/201/258 +f 208/208/265 209/209/266 210/210/266 +f 208/208/265 211/211/267 209/209/266 +f 212/212/268 211/211/267 208/208/265 +f 212/212/268 205/205/262 211/211/267 +f 204/204/261 205/205/262 212/212/268 +f 207/207/264 213/213/269 206/206/263 +f 214/214/270 213/213/269 207/207/264 +f 185/185/222 110/110/226 215/215/271 +f 112/112/272 215/215/271 110/110/226 +f 216/216/273 215/215/271 112/112/272 +f 215/215/271 217/217/274 218/218/275 +f 215/215/271 216/216/273 217/217/274 +f 218/218/275 217/217/274 219/219/276 +f 219/219/276 220/220/277 218/218/275 +f 220/220/277 219/219/276 221/221/278 +f 220/220/277 221/221/278 222/222/279 +f 222/222/279 223/223/280 220/220/277 +f 223/223/280 222/222/279 224/224/281 +f 224/224/281 225/225/282 223/223/280 +f 225/225/282 224/224/281 226/226/283 +f 182/182/266 177/177/266 183/183/266 +f 181/181/266 175/175/266 183/183/266 +f 172/172/147 179/179/147 170/170/147 +f 164/164/147 173/173/147 176/176/147 +f 183/183/266 177/177/266 181/181/266 +f 181/181/266 180/180/266 174/174/266 +f 174/174/266 161/161/266 175/175/266 +f 171/171/147 178/178/147 173/173/147 +f 173/173/147 172/172/147 171/171/147 +f 161/161/266 163/163/266 175/175/266 +f 178/178/147 176/176/147 173/173/147 +f 176/176/147 162/162/147 164/164/147 +f 174/174/266 175/175/266 181/181/266 +f 226/226/284 227/227/285 228/228/286 +f 131/131/147 193/193/147 132/132/147 +f 229/229/147 156/156/147 158/158/147 +f 230/230/147 156/156/147 229/229/147 +f 231/231/147 138/138/147 232/232/147 +f 233/233/147 191/191/147 230/230/147 +f 134/134/147 137/137/147 135/135/147 +f 231/231/147 158/158/147 160/160/147 +f 130/130/147 133/133/147 131/131/147 +f 230/230/147 191/191/147 154/154/147 +f 233/233/147 193/193/147 191/191/147 +f 132/132/147 193/193/147 233/233/147 +f 231/231/147 160/160/147 138/138/147 +f 230/230/147 154/154/147 156/156/147 +f 232/232/147 137/137/147 134/134/147 +f 229/229/147 158/158/147 231/231/147 +f 128/128/147 133/133/147 130/130/147 +f 234/234/287 213/213/269 214/214/270 +f 235/235/288 236/236/266 234/234/287 +f 210/210/266 236/236/266 235/235/288 +f 210/210/266 209/209/266 236/236/266 +f 235/235/288 234/234/287 214/214/270 +f 231/231/289 214/214/290 207/207/291 +f 232/232/292 214/214/290 231/231/289 +f 134/134/293 214/214/290 232/232/292 +f 134/134/293 235/235/294 214/214/290 +f 125/125/295 235/235/294 134/134/293 +f 125/125/295 210/210/296 235/235/294 +f 125/125/295 208/208/297 210/210/296 +f 128/128/298 208/208/297 125/125/295 +f 128/128/299 212/212/300 208/208/301 +f 130/130/302 212/212/300 128/128/299 +f 130/130/302 204/204/303 212/212/300 +f 132/132/304 204/204/303 130/130/302 +f 132/132/304 202/202/305 204/204/303 +f 233/233/306 202/202/305 132/132/304 +f 230/230/307 202/202/305 233/233/306 +f 230/230/307 198/198/308 202/202/305 +f 229/229/309 198/198/310 230/230/311 +f 229/229/309 201/201/312 198/198/310 +f 231/231/313 201/201/314 229/229/315 +f 231/231/313 207/207/316 201/201/314 +f 232/232/147 138/138/147 137/137/147 +f 157/157/317 111/111/318 159/159/319 +f 155/155/320 237/237/321 238/238/322 +f 192/192/323 237/237/321 155/155/320 +f 194/194/324 227/227/325 239/239/326 +f 187/187/327 227/227/325 194/194/324 +f 157/157/317 109/109/328 111/111/318 +f 192/192/323 239/239/326 237/237/321 +f 194/194/324 239/239/326 192/192/323 +f 187/187/327 228/228/329 227/227/325 +f 159/159/319 114/114/330 139/139/217 +f 159/159/319 111/111/318 114/114/330 +f 155/155/320 238/238/322 153/153/331 +f 139/139/217 114/114/330 117/117/218 +f 153/153/331 109/109/328 157/157/317 +f 153/153/331 238/238/322 109/109/328 +f 188/188/332 240/240/333 241/241/334 +f 189/189/335 240/240/333 188/188/332 +f 242/242/336 240/240/333 189/189/335 +f 190/190/337 123/123/216 242/242/336 +f 190/190/337 242/242/336 189/189/335 +f 187/187/327 241/241/334 228/228/329 +f 188/188/332 241/241/334 187/187/327 +f 141/141/214 123/123/216 190/190/337 +f 226/226/283 243/243/338 225/225/282 +f 244/244/339 243/243/338 226/226/283 +f 243/243/338 244/244/339 245/245/340 +f 246/246/341 243/243/338 245/245/340 +f 246/246/341 247/247/342 243/243/338 +f 248/248/343 247/247/342 246/246/341 +f 247/247/342 248/248/343 249/249/344 +f 249/249/344 248/248/343 250/250/345 +f 122/122/346 249/249/344 250/250/345 +f 122/122/346 196/196/249 249/249/344 +f 124/124/247 196/196/249 122/122/346 +f 250/250/347 123/123/145 122/122/144 +f 123/123/145 250/250/347 242/242/348 +f 248/248/349 242/242/350 250/250/351 +f 246/246/352 242/242/350 248/248/349 +f 242/242/350 246/246/352 240/240/353 +f 240/240/353 246/246/352 245/245/354 +f 226/226/284 228/228/286 241/241/355 +f 226/226/284 241/241/355 244/244/356 +f 239/239/357 224/224/358 222/222/359 +f 221/221/360 237/237/361 239/239/357 +f 216/216/362 238/238/363 217/217/274 +f 112/112/134 109/109/131 216/216/362 +f 114/114/136 111/111/133 113/113/135 +f 117/117/139 114/114/136 115/115/137 +f 184/184/364 117/117/139 118/118/140 +f 120/120/142 184/184/364 118/118/140 +f 119/119/141 184/184/364 120/120/142 +f 124/124/146 119/119/141 121/121/143 +f 124/124/146 123/123/145 119/119/141 +f 241/241/355 240/240/353 245/245/354 +f 245/245/354 244/244/356 241/241/355 +f 217/217/274 238/238/363 237/237/361 +f 247/247/342 211/211/365 205/205/366 +f 249/249/344 211/211/365 247/247/342 +f 247/247/342 205/205/366 243/243/338 +f 249/249/344 209/209/367 211/211/365 +f 237/237/361 219/219/276 217/217/274 +f 238/238/363 216/216/362 109/109/131 +f 196/196/249 209/209/367 249/249/344 +f 196/196/249 236/236/368 209/209/367 +f 195/195/248 236/236/368 196/196/249 +f 195/195/248 234/234/369 236/236/368 +f 197/197/253 234/234/369 195/195/248 +f 197/197/253 213/213/370 234/234/369 +f 186/186/225 213/213/370 197/197/253 +f 186/186/225 206/206/371 213/213/372 +f 185/185/222 206/206/371 186/186/225 +f 215/215/271 206/206/371 185/185/222 +f 215/215/271 199/199/373 206/206/371 +f 218/218/275 199/199/374 215/215/271 +f 226/226/284 224/224/358 227/227/285 +f 224/224/358 239/239/357 227/227/285 +f 221/221/360 239/239/357 222/222/359 +f 219/219/276 237/237/361 221/221/360 +f 218/218/275 200/200/375 199/199/374 +f 220/220/277 200/200/376 218/218/275 +f 220/220/377 203/203/377 200/200/377 +f 223/223/280 203/203/378 220/220/277 +f 225/225/282 203/203/378 223/223/280 +f 225/225/282 205/205/366 203/203/379 +f 243/243/338 205/205/366 225/225/282 +f 251/251/380 252/252/381 253/253/382 +f 251/251/380 253/253/382 254/254/383 +f 255/255/384 256/256/385 254/254/386 +f 255/255/384 254/254/386 253/253/387 +f 256/256/388 255/255/389 257/257/390 +f 256/256/388 257/257/390 258/258/391 +f 251/251/392 258/258/393 252/252/394 +f 252/252/394 258/258/393 257/257/395 +f 253/253/1 252/252/1 255/255/1 +f 255/255/1 252/252/1 257/257/1 +f 251/251/2 254/254/2 258/258/2 +f 258/258/2 254/254/2 256/256/2 +f 259/259/396 260/260/397 261/261/398 +f 262/262/399 263/263/400 264/264/401 +f 265/265/402 266/266/403 267/267/404 +f 265/265/402 267/267/404 268/268/405 +f 268/268/405 267/267/404 269/269/406 +f 263/263/400 266/266/403 265/265/402 +f 270/270/2 271/271/407 272/272/408 +f 260/260/397 272/272/408 261/261/398 +f 268/268/405 269/269/406 261/261/398 +f 261/261/398 269/269/406 259/259/396 +f 260/260/397 270/270/2 272/272/408 +f 264/264/401 263/263/400 265/265/402 +f 273/273/409 274/274/410 275/275/411 +f 273/273/409 275/275/411 271/271/407 +f 271/271/407 275/275/411 272/272/408 +f 275/275/411 274/274/410 262/262/399 +f 275/275/411 262/262/399 264/264/401 +f 276/276/412 277/277/413 278/278/414 +f 276/276/412 279/279/415 277/277/413 +f 280/280/416 279/279/415 276/276/412 +f 276/276/412 281/281/417 280/280/416 +f 276/276/412 282/282/418 281/281/417 +f 276/276/412 283/283/419 282/282/418 +f 276/276/412 284/284/420 283/283/419 +f 276/276/412 285/285/421 284/284/420 +f 276/276/412 286/286/422 285/285/421 +f 278/278/414 287/287/423 276/276/412 +f 288/288/424 278/278/425 277/277/426 +f 288/288/424 277/277/426 289/289/427 +f 289/289/428 277/277/429 279/279/430 +f 289/289/428 279/279/430 290/290/431 +f 290/290/432 279/279/433 291/291/434 +f 291/291/434 279/279/433 280/280/435 +f 291/291/434 280/280/435 281/281/436 +f 291/291/434 281/281/436 292/292/437 +f 292/292/437 281/281/436 282/282/438 +f 292/292/437 282/282/438 283/283/439 +f 292/292/437 283/283/439 293/293/440 +f 293/293/440 283/283/439 284/284/441 +f 293/293/440 284/284/441 294/294/442 +f 294/294/442 284/284/441 285/285/443 +f 294/294/444 285/285/445 286/286/446 +f 294/294/444 286/286/446 295/295/447 +f 295/295/448 286/286/449 276/276/450 +f 295/295/448 276/276/450 296/296/451 +f 296/296/451 276/276/450 287/287/452 +f 296/296/451 287/287/452 278/278/425 +f 296/296/451 278/278/425 288/288/424 +f 288/288/1 297/297/1 298/298/1 +f 294/294/1 299/299/1 293/293/1 +f 294/294/1 300/300/1 299/299/1 +f 296/296/1 301/301/1 295/295/1 +f 288/288/1 298/298/1 296/296/1 +f 299/299/1 302/302/1 293/293/1 +f 293/293/1 302/302/1 292/292/1 +f 294/294/1 303/303/1 300/300/1 +f 296/296/1 298/298/1 301/301/1 +f 295/295/1 301/301/1 304/304/1 +f 289/289/1 305/305/1 297/297/1 +f 289/289/1 297/297/1 288/288/1 +f 292/292/1 302/302/1 306/306/1 +f 290/290/1 305/305/1 289/289/1 +f 290/290/1 307/307/1 305/305/1 +f 295/295/1 304/304/1 294/294/1 +f 294/294/1 304/304/1 303/303/1 +f 291/291/1 308/308/1 307/307/1 +f 291/291/1 307/307/1 290/290/1 +f 292/292/1 306/306/1 291/291/1 +f 306/306/1 309/309/1 291/291/1 +f 291/291/1 309/309/1 308/308/1 +f 310/310/453 311/311/454 298/298/455 +f 311/311/454 301/301/456 298/298/457 +f 301/301/456 311/311/454 312/312/458 +f 312/312/458 313/313/459 301/301/456 +f 301/301/456 313/313/459 304/304/460 +f 313/313/459 314/314/461 304/304/460 +f 304/304/460 314/314/461 315/315/462 +f 315/315/462 303/303/463 304/304/460 +f 315/315/462 300/300/464 303/303/463 +f 315/315/462 316/316/465 300/300/464 +f 316/316/465 299/299/466 300/300/464 +f 299/299/466 316/316/465 317/317/467 +f 318/318/468 302/302/469 299/299/466 +f 318/318/468 299/299/466 317/317/467 +f 318/318/468 319/319/470 302/302/469 +f 302/302/469 319/319/470 306/306/471 +f 306/306/471 319/319/470 320/320/472 +f 306/306/471 320/320/472 309/309/473 +f 320/320/472 321/321/474 309/309/473 +f 321/321/474 322/322/475 309/309/473 +f 309/309/473 322/322/475 308/308/476 +f 322/322/475 323/323/477 308/308/476 +f 308/308/476 323/323/477 307/307/478 +f 323/323/477 324/324/479 307/307/478 +f 307/307/478 324/324/479 305/305/480 +f 324/324/479 325/325/481 305/305/480 +f 325/325/481 326/326/482 305/305/480 +f 305/305/480 326/326/482 297/297/483 +f 326/326/482 327/327/484 297/297/483 +f 297/297/483 327/327/484 298/298/455 +f 298/298/455 327/327/484 310/310/453 +f 328/328/485 274/274/486 329/329/487 +f 328/328/485 329/329/487 330/330/488 +f 319/319/470 318/318/468 330/330/488 +f 319/319/470 330/330/488 329/329/487 +f 274/274/486 331/331/489 329/329/487 +f 329/329/487 320/320/472 319/319/470 +f 320/320/472 329/329/487 331/331/489 +f 331/331/489 274/274/486 273/273/490 +f 332/332/491 320/320/472 331/331/489 +f 273/273/490 333/333/492 331/331/489 +f 320/320/472 332/332/491 321/321/474 +f 332/332/491 331/331/489 333/333/492 +f 321/321/474 332/332/491 322/322/475 +f 332/332/491 333/333/492 334/334/493 +f 271/271/494 333/333/492 273/273/490 +f 271/271/494 334/334/493 333/333/492 +f 332/332/491 334/334/493 322/322/475 +f 335/335/495 334/334/493 271/271/494 +f 323/323/477 322/322/475 334/334/493 +f 323/323/477 334/334/493 336/336/496 +f 336/336/496 334/334/493 335/335/495 +f 270/270/497 335/335/495 271/271/494 +f 335/335/495 270/270/497 337/337/498 +f 335/335/495 337/337/498 336/336/496 +f 324/324/479 323/323/477 336/336/496 +f 336/336/496 337/337/498 324/324/479 +f 260/260/499 337/337/498 270/270/497 +f 338/338/500 337/337/498 260/260/499 +f 337/337/498 338/338/500 324/324/479 +f 324/324/479 338/338/500 339/339/501 +f 325/325/481 324/324/479 339/339/501 +f 339/339/501 326/326/482 325/325/481 +f 326/326/482 339/339/501 338/338/500 +f 338/338/500 340/340/502 326/326/482 +f 260/260/499 340/340/502 338/338/500 +f 326/326/482 340/340/502 327/327/484 +f 259/259/503 340/340/502 260/260/499 +f 327/327/484 340/340/502 341/341/504 +f 340/340/502 259/259/503 341/341/504 +f 310/310/453 327/327/484 341/341/504 +f 341/341/504 259/259/503 342/342/505 +f 342/342/505 310/310/453 341/341/504 +f 259/259/503 269/269/506 343/343/507 +f 259/259/503 343/343/507 342/342/505 +f 311/311/454 310/310/453 342/342/505 +f 344/344/508 311/311/454 342/342/505 +f 344/344/508 342/342/505 343/343/507 +f 312/312/458 311/311/454 344/344/508 +f 267/267/509 343/343/507 269/269/506 +f 345/345/510 344/344/508 267/267/509 +f 267/267/509 344/344/508 343/343/507 +f 344/344/508 345/345/510 312/312/458 +f 313/313/459 312/312/458 345/345/510 +f 267/267/509 346/346/511 345/345/510 +f 347/347/512 313/313/459 345/345/510 +f 266/266/403 346/346/511 267/267/509 +f 345/345/510 346/346/511 347/347/512 +f 347/347/512 346/346/511 348/348/513 +f 313/313/459 347/347/512 314/314/461 +f 348/348/513 314/314/461 347/347/512 +f 346/346/511 266/266/403 348/348/513 +f 314/314/461 348/348/513 315/315/462 +f 349/349/514 348/348/513 266/266/403 +f 348/348/513 350/350/515 315/315/462 +f 350/350/515 348/348/513 349/349/514 +f 266/266/403 263/263/400 349/349/514 +f 350/350/515 351/351/516 315/315/462 +f 351/351/516 350/350/515 349/349/514 +f 351/351/516 349/349/514 352/352/517 +f 352/352/517 349/349/514 263/263/400 +f 315/315/462 351/351/516 316/316/465 +f 353/353/518 351/351/516 352/352/517 +f 351/351/516 353/353/518 316/316/465 +f 353/353/518 352/352/517 263/263/400 +f 353/353/518 317/317/467 316/316/465 +f 317/317/467 353/353/518 328/328/485 +f 353/353/518 263/263/400 262/262/519 +f 317/317/467 328/328/485 330/330/488 +f 318/318/468 317/317/467 330/330/488 +f 328/328/485 353/353/518 262/262/519 +f 262/262/519 274/274/486 328/328/485 +f 268/268/124 261/261/124 354/354/124 +f 354/354/124 261/261/124 355/355/124 +f 265/265/125 268/268/125 356/356/125 +f 356/356/125 268/268/125 354/354/126 +f 264/264/127 265/265/127 357/357/127 +f 357/357/127 265/265/127 356/356/127 +f 275/275/128 264/264/128 358/358/128 +f 358/358/128 264/264/128 357/357/128 +f 272/272/129 275/275/129 359/359/129 +f 359/359/129 275/275/129 358/358/129 +f 261/261/130 272/272/130 355/355/130 +f 355/355/130 272/272/130 359/359/130 +f 359/359/2 358/358/2 355/355/2 +f 355/355/2 358/358/2 357/357/2 +f 355/355/2 357/357/2 354/354/2 +f 354/354/2 357/357/2 356/356/2 +f 360/360/520 361/361/521 362/362/522 +f 361/361/521 363/363/523 362/362/522 +f 364/364/524 363/363/523 361/361/521 +f 361/361/521 365/365/525 364/364/524 +f 361/361/521 366/366/526 365/365/525 +f 367/367/527 368/368/528 369/369/529 +f 369/369/529 368/368/528 370/370/530 +f 370/370/530 368/368/528 371/371/531 +f 370/370/530 371/371/531 372/372/532 +f 372/372/532 371/371/531 373/373/533 +f 372/372/532 373/373/533 374/374/534 +f 373/373/533 375/375/535 374/374/534 +f 374/374/534 375/375/535 376/376/536 +f 376/376/536 375/375/535 377/377/537 +f 376/376/536 377/377/537 378/378/538 +f 378/378/538 377/377/537 379/379/539 +f 378/378/538 379/379/539 380/380/540 +f 380/380/540 379/379/539 381/381/541 +f 379/379/539 382/382/542 381/381/541 +f 381/381/543 382/382/544 383/383/545 +f 381/381/543 383/383/545 384/384/546 +f 383/383/545 385/385/547 384/384/546 +f 384/384/546 385/385/547 369/369/548 +f 385/385/547 367/367/549 369/369/548 +f 365/365/550 377/377/551 364/364/552 +f 364/364/552 377/377/551 375/375/553 +f 375/375/553 373/373/554 364/364/552 +f 364/364/552 373/373/554 363/363/555 +f 363/363/555 373/373/554 371/371/556 +f 363/363/555 371/371/556 362/362/557 +f 362/362/557 371/371/556 368/368/558 +f 368/368/558 367/367/559 362/362/557 +f 362/362/557 367/367/559 360/360/560 +f 367/367/559 385/385/561 360/360/560 +f 360/360/560 385/385/561 361/361/562 +f 385/385/561 383/383/563 361/361/562 +f 361/361/562 383/383/563 382/382/564 +f 361/361/562 382/382/564 366/366/565 +f 382/382/564 379/379/566 366/366/565 +f 366/366/565 379/379/566 365/365/567 +f 365/365/567 379/379/566 377/377/568 +f 369/369/147 386/386/147 387/387/147 +f 369/369/147 387/387/147 384/384/147 +f 370/370/147 388/388/147 369/369/147 +f 369/369/147 388/388/147 386/386/147 +f 372/372/147 389/389/147 390/390/147 +f 372/372/147 390/390/147 370/370/147 +f 378/378/147 391/391/147 376/376/147 +f 384/384/147 392/392/147 381/381/147 +f 384/384/147 393/393/147 392/392/147 +f 387/387/147 393/393/147 384/384/147 +f 370/370/147 390/390/147 388/388/147 +f 378/378/147 394/394/147 391/391/147 +f 380/380/147 395/395/147 394/394/147 +f 380/380/147 394/394/147 378/378/147 +f 374/374/147 396/396/147 397/397/147 +f 374/374/147 389/389/147 372/372/147 +f 374/374/147 397/397/147 389/389/147 +f 376/376/147 396/396/147 374/374/147 +f 376/376/147 391/391/147 396/396/147 +f 381/381/147 395/395/147 380/380/147 +f 381/381/147 392/392/147 398/398/147 +f 381/381/147 398/398/147 395/395/147 +f 399/399/569 400/400/570 401/401/571 +f 402/402/572 403/403/573 404/404/574 +f 404/404/574 403/403/573 405/405/575 +f 404/404/574 405/405/575 406/406/576 +f 406/406/576 405/405/575 407/407/577 +f 407/407/577 408/408/578 399/399/569 +f 399/399/569 408/408/578 400/400/570 +f 409/409/579 410/410/580 411/411/581 +f 409/409/579 411/411/581 412/412/582 +f 407/407/577 405/405/575 408/408/578 +f 401/401/571 400/400/570 413/413/583 +f 414/414/584 410/410/580 409/409/579 +f 415/415/585 416/416/586 417/417/587 +f 402/402/572 418/418/588 403/403/573 +f 419/419/589 420/420/590 414/414/584 +f 414/414/584 420/420/590 410/410/580 +f 415/415/585 417/417/587 402/402/572 +f 402/402/572 417/417/587 418/418/588 +f 401/401/571 413/413/583 421/421/591 +f 422/422/592 423/423/593 424/424/594 +f 422/422/592 424/424/594 419/419/589 +f 419/419/589 424/424/594 420/420/590 +f 421/421/591 413/413/583 423/423/593 +f 421/421/591 423/423/593 422/422/592 +f 412/412/582 411/411/581 416/416/586 +f 412/412/582 416/416/586 415/415/585 +f 389/389/595 419/419/596 390/390/597 +f 390/390/598 419/419/599 414/414/600 +f 390/390/598 414/414/600 388/388/601 +f 388/388/601 414/414/600 386/386/602 +f 386/386/602 414/414/600 409/409/603 +f 386/386/602 409/409/603 412/412/604 +f 386/386/602 412/412/604 387/387/605 +f 387/387/606 412/412/607 415/415/608 +f 387/387/606 415/415/608 393/393/609 +f 393/393/609 415/415/608 402/402/610 +f 393/393/609 402/402/610 392/392/611 +f 392/392/612 402/402/613 404/404/614 +f 392/392/612 404/404/614 398/398/615 +f 398/398/615 404/404/614 395/395/616 +f 395/395/616 404/404/614 406/406/617 +f 395/395/616 406/406/617 407/407/618 +f 395/395/616 407/407/618 394/394/619 +f 394/394/620 407/407/620 399/399/620 +f 394/394/621 399/399/621 391/391/621 +f 391/391/622 399/399/622 401/401/622 +f 391/391/623 401/401/623 396/396/623 +f 396/396/624 401/401/625 421/421/626 +f 396/396/624 421/421/626 397/397/627 +f 397/397/627 421/421/626 422/422/628 +f 397/397/627 422/422/628 389/389/595 +f 389/389/595 422/422/628 419/419/596 +f 425/425/629 426/426/630 427/427/631 +f 426/426/630 428/428/632 429/429/633 +f 430/430/634 431/431/635 432/432/636 +f 426/426/630 433/433/637 428/428/632 +f 427/427/631 434/434/638 425/425/629 +f 435/435/639 434/434/638 427/427/631 +f 431/431/635 436/436/640 437/437/641 +f 436/436/640 438/438/642 439/439/643 +f 439/439/643 438/438/642 440/440/644 +f 425/425/629 433/433/637 426/426/630 +f 431/431/635 430/430/634 435/435/639 +f 439/439/643 441/441/645 436/436/640 +f 440/440/644 442/442/646 439/439/643 +f 443/443/647 444/444/648 440/440/644 +f 436/436/640 441/441/645 437/437/641 +f 435/435/639 430/430/634 434/434/638 +f 431/431/635 437/437/641 432/432/636 +f 440/440/644 444/444/648 442/442/646 +f 429/429/633 445/445/649 443/443/647 +f 429/429/633 428/428/632 445/445/649 +f 443/443/647 445/445/649 444/444/648 +f 444/444/650 446/446/651 442/442/652 +f 442/442/652 447/447/653 439/439/654 +f 441/441/655 448/448/656 437/437/657 +f 437/437/657 449/449/658 432/432/659 +f 432/432/659 450/450/660 430/430/661 +f 430/430/661 451/451/662 434/434/663 +f 434/434/663 452/452/664 425/425/665 +f 439/439/654 453/453/666 441/441/655 +f 437/437/657 448/448/656 454/454/667 +f 425/425/665 455/455/668 433/433/669 +f 433/433/669 456/456/670 428/428/671 +f 428/428/671 457/457/672 445/445/673 +f 445/445/673 458/458/674 444/444/650 +f 444/444/650 458/458/674 446/446/651 +f 442/442/652 446/446/651 459/459/675 +f 442/442/652 459/459/675 447/447/653 +f 439/439/654 447/447/653 453/453/666 +f 453/453/666 460/460/676 441/441/655 +f 441/441/655 460/460/676 448/448/656 +f 454/454/667 449/449/658 437/437/657 +f 450/450/660 461/461/677 430/430/661 +f 451/451/662 462/462/678 434/434/663 +f 434/434/663 462/462/678 452/452/664 +f 425/425/665 452/452/664 455/455/668 +f 428/428/671 456/456/670 457/457/672 +f 445/445/673 457/457/672 463/463/679 +f 445/445/673 463/463/679 458/458/674 +f 449/449/658 464/464/680 432/432/659 +f 432/432/659 464/464/680 465/465/681 +f 432/432/659 465/465/681 450/450/660 +f 450/450/660 465/465/681 461/461/677 +f 430/430/661 461/461/677 451/451/662 +f 455/455/668 456/456/670 433/433/669 +f 447/447/653 466/466/682 453/453/666 +f 454/454/667 467/467/683 449/449/658 +f 462/462/678 468/468/684 452/452/664 +f 447/447/653 459/459/675 469/469/685 +f 447/447/653 469/469/685 466/466/682 +f 448/448/656 460/460/676 454/454/667 +f 461/461/677 470/470/686 451/451/662 +f 453/453/666 466/466/682 460/460/676 +f 451/451/662 470/470/686 462/462/678 +f 455/455/668 411/411/687 456/456/670 +f 457/457/672 420/420/688 463/463/679 +f 458/458/674 471/471/689 446/446/651 +f 446/446/651 471/471/689 459/459/675 +f 449/449/658 467/467/683 464/464/680 +f 456/456/670 411/411/687 410/410/690 +f 456/456/670 410/410/690 457/457/672 +f 460/460/676 400/400/691 454/454/667 +f 454/454/667 408/408/692 467/467/683 +f 464/464/680 405/405/693 465/465/681 +f 465/465/681 403/403/694 461/461/677 +f 461/461/677 403/403/694 470/470/686 +f 470/470/686 403/403/694 418/418/695 +f 468/468/684 416/416/696 452/452/664 +f 452/452/664 416/416/696 455/455/668 +f 455/455/668 416/416/696 411/411/687 +f 463/463/679 424/424/697 458/458/674 +f 458/458/674 424/424/697 471/471/689 +f 471/471/689 423/423/698 459/459/675 +f 459/459/675 423/423/698 469/469/685 +f 469/469/685 423/423/698 413/413/699 +f 469/469/685 413/413/699 466/466/682 +f 466/466/682 400/400/691 460/460/676 +f 400/400/691 408/408/692 454/454/667 +f 408/408/692 405/405/693 467/467/683 +f 467/467/683 405/405/693 464/464/680 +f 465/465/681 405/405/693 403/403/694 +f 470/470/686 418/418/695 462/462/678 +f 462/462/678 417/417/700 468/468/684 +f 468/468/684 417/417/700 416/416/696 +f 471/471/689 424/424/697 423/423/698 +f 466/466/682 413/413/699 400/400/691 +f 418/418/695 417/417/700 462/462/678 +f 457/457/672 410/410/690 420/420/688 +f 463/463/679 420/420/688 424/424/697 +f 472/472/701 431/431/702 435/435/703 +f 473/473/704 435/435/705 427/427/706 +f 473/473/704 427/427/706 426/426/707 +f 474/474/708 426/426/709 429/429/710 +f 474/474/708 429/429/710 443/443/711 +f 475/475/712 443/443/713 440/440/714 +f 476/476/715 440/440/716 438/438/717 +f 476/476/715 438/438/717 436/436/718 +f 477/477/719 436/436/720 431/431/721 +f 478/478/266 479/479/266 480/480/266 +f 480/480/266 479/479/266 481/481/266 +f 480/480/266 481/481/266 482/482/266 +f 482/482/266 481/481/266 483/483/266 +f 472/472/701 478/478/722 480/480/723 +f 431/431/702 472/472/701 480/480/723 +f 478/478/722 472/472/701 435/435/703 +f 478/478/724 473/473/725 479/479/726 +f 478/478/724 435/435/727 473/473/725 +f 479/479/726 473/473/725 426/426/728 +f 479/479/729 474/474/730 481/481/731 +f 426/426/732 474/474/730 479/479/729 +f 481/481/731 474/474/730 443/443/733 +f 481/481/734 475/475/712 483/483/735 +f 443/443/713 475/475/712 481/481/734 +f 483/483/735 475/475/712 440/440/714 +f 483/483/736 476/476/737 482/482/738 +f 483/483/736 440/440/739 476/476/737 +f 476/476/737 436/436/740 482/482/738 +f 482/482/741 477/477/719 480/480/742 +f 482/482/741 436/436/720 477/477/719 +f 480/480/742 477/477/719 431/431/721 +f 484/484/743 485/485/744 486/486/745 +f 486/486/745 485/485/744 487/487/746 +f 486/486/745 487/487/746 488/488/747 +f 488/488/747 487/487/746 489/489/748 +f 488/488/747 489/489/748 490/490/749 +f 490/490/749 489/489/748 491/491/750 +f 490/490/749 491/491/750 492/492/751 +f 492/492/751 491/491/750 493/493/752 +f 492/492/751 493/493/752 494/494/753 +f 494/494/753 493/493/752 495/495/754 +f 494/494/753 495/495/754 496/496/755 +f 496/496/755 495/495/754 497/497/756 +f 496/496/755 497/497/756 498/498/757 +f 498/498/757 497/497/756 499/499/758 +f 498/498/757 499/499/758 500/500/759 +f 500/500/759 499/499/758 501/501/760 +f 500/500/759 501/501/760 502/502/761 +f 502/502/761 501/501/760 503/503/762 +f 502/502/761 503/503/762 504/504/763 +f 504/504/763 503/503/762 505/505/764 +f 504/504/763 505/505/764 506/506/765 +f 506/506/765 505/505/764 507/507/766 +f 506/506/765 507/507/766 508/508/767 +f 508/508/768 507/507/768 509/509/768 +f 508/508/769 509/509/769 510/510/769 +f 510/510/770 509/509/770 511/511/770 +f 510/510/771 511/511/771 484/484/771 +f 484/484/743 511/511/772 485/485/744 +f 512/512/266 505/505/266 513/513/266 +f 514/514/266 509/509/266 507/507/266 +f 515/515/266 509/509/266 514/514/266 +f 513/513/266 505/505/266 503/503/266 +f 512/512/266 507/507/266 505/505/266 +f 514/514/266 507/507/266 512/512/266 +f 516/516/266 497/497/266 517/517/266 +f 501/501/266 499/499/266 518/518/266 +f 518/518/266 499/499/266 516/516/266 +f 513/513/266 503/503/266 501/501/266 +f 513/513/266 501/501/266 518/518/266 +f 519/519/266 493/493/266 520/520/266 +f 516/516/266 499/499/266 497/497/266 +f 521/521/266 485/485/266 522/522/266 +f 521/521/266 487/487/266 485/485/266 +f 523/523/266 489/489/266 521/521/266 +f 519/519/266 495/495/266 493/493/266 +f 517/517/266 497/497/266 495/495/266 +f 522/522/266 511/511/266 515/515/266 +f 515/515/266 511/511/266 509/509/266 +f 489/489/266 487/487/266 521/521/266 +f 520/520/266 491/491/266 523/523/266 +f 523/523/266 491/491/266 489/489/266 +f 520/520/266 493/493/266 491/491/266 +f 517/517/266 495/495/266 519/519/266 +f 485/485/266 511/511/266 522/522/266 +f 522/522/773 524/524/774 521/521/775 +f 521/521/775 524/524/774 525/525/776 +f 521/521/775 525/525/776 523/523/777 +f 523/523/777 525/525/776 520/520/778 +f 520/520/778 525/525/776 526/526/779 +f 520/520/778 526/526/779 519/519/780 +f 519/519/780 526/526/779 527/527/781 +f 519/519/780 527/527/781 517/517/782 +f 517/517/782 527/527/781 528/528/783 +f 517/517/782 528/528/783 516/516/784 +f 516/516/784 528/528/783 529/529/785 +f 516/516/784 529/529/785 518/518/786 +f 518/518/787 529/529/788 513/513/789 +f 513/513/789 529/529/788 530/530/790 +f 513/513/791 530/530/792 531/531/793 +f 513/513/791 531/531/793 512/512/794 +f 512/512/794 531/531/793 532/532/795 +f 512/512/794 532/532/795 514/514/796 +f 514/514/796 532/532/795 515/515/797 +f 515/515/797 532/532/795 533/533/798 +f 515/515/797 533/533/798 534/534/799 +f 515/515/797 534/534/799 522/522/773 +f 522/522/773 534/534/799 524/524/774 +f 532/532/800 535/535/801 533/533/802 +f 533/533/802 535/535/801 536/536/803 +f 533/533/802 536/536/803 534/534/147 +f 531/531/804 537/537/805 532/532/800 +f 532/532/800 537/537/805 535/535/801 +f 534/534/147 536/536/803 538/538/806 +f 534/534/147 538/538/806 524/524/807 +f 524/524/807 538/538/806 539/539/808 +f 529/529/809 540/540/810 541/541/811 +f 529/529/809 541/541/811 530/530/812 +f 530/530/812 541/541/811 537/537/805 +f 530/530/812 537/537/805 531/531/804 +f 524/524/807 539/539/808 525/525/813 +f 525/525/813 539/539/808 542/542/814 +f 527/527/815 543/543/147 528/528/816 +f 528/528/816 543/543/147 540/540/810 +f 528/528/816 540/540/810 529/529/809 +f 526/526/817 544/544/818 527/527/815 +f 527/527/815 544/544/818 543/543/147 +f 525/525/813 542/542/814 526/526/817 +f 526/526/817 542/542/814 544/544/818 +f 545/545/819 546/546/820 547/547/821 +f 546/546/820 545/545/819 548/548/822 +f 545/545/819 549/549/823 548/548/822 +f 549/549/823 545/545/819 550/550/824 +f 550/550/824 551/551/825 549/549/823 +f 551/551/825 550/550/824 552/552/826 +f 552/552/826 553/553/827 551/551/825 +f 552/552/826 554/554/828 553/553/827 +f 554/554/828 552/552/826 555/555/829 +f 556/556/830 555/555/829 552/552/826 +f 555/555/829 556/556/830 557/557/831 +f 557/557/831 556/556/830 558/558/832 +f 558/558/832 556/556/830 559/559/833 +f 559/559/833 560/560/834 558/558/832 +f 559/559/833 561/561/835 560/560/834 +f 562/562/836 561/561/835 559/559/833 +f 563/563/837 561/561/835 562/562/836 +f 563/563/837 562/562/836 564/564/838 +f 564/564/838 562/562/836 565/565/839 +f 565/565/839 566/566/840 564/564/838 +f 566/566/840 565/565/839 567/567/841 +f 566/566/840 567/567/841 568/568/842 +f 567/567/841 569/569/843 568/568/842 +f 569/569/843 567/567/841 570/570/844 +f 570/570/844 571/571/845 569/569/843 +f 572/572/846 573/573/847 570/570/844 +f 570/570/844 573/573/847 571/571/845 +f 573/573/847 572/572/846 574/574/848 +f 574/574/848 572/572/846 575/575/849 +f 574/574/848 575/575/849 576/576/850 +f 576/576/850 575/575/849 577/577/851 +f 577/577/851 575/575/849 547/547/821 +f 577/577/851 547/547/821 578/578/852 +f 547/547/821 546/546/820 578/578/852 +f 510/510/853 579/579/854 580/580/855 +f 510/510/853 580/580/855 508/508/856 +f 510/510/853 581/581/857 579/579/854 +f 484/484/858 582/582/859 581/581/857 +f 484/484/858 581/581/857 510/510/853 +f 508/508/856 580/580/855 583/583/860 +f 504/504/861 584/584/862 585/585/863 +f 504/504/861 585/585/863 502/502/864 +f 506/506/865 584/584/862 504/504/861 +f 508/508/856 583/583/860 506/506/865 +f 506/506/865 583/583/860 584/584/862 +f 502/502/864 585/585/863 586/586/866 +f 502/502/864 586/586/866 500/500/867 +f 500/500/867 586/586/866 587/587/868 +f 486/486/869 588/588/870 582/582/859 +f 486/486/869 582/582/859 484/484/858 +f 496/496/871 589/589/872 494/494/873 +f 492/492/874 590/590/875 490/490/876 +f 490/490/876 590/590/875 591/591/877 +f 500/500/867 587/587/868 498/498/878 +f 498/498/878 587/587/868 592/592/879 +f 496/496/871 593/593/880 589/589/872 +f 591/591/877 594/594/881 490/490/876 +f 490/490/876 594/594/881 488/488/882 +f 498/498/878 592/592/879 496/496/871 +f 496/496/871 592/592/879 593/593/880 +f 494/494/873 589/589/872 492/492/874 +f 492/492/874 589/589/872 590/590/875 +f 488/488/882 594/594/881 588/588/870 +f 488/488/882 588/588/870 486/486/869 +f 554/554/883 583/583/884 580/580/885 +f 555/555/886 583/583/884 554/554/883 +f 554/554/883 580/580/885 553/553/887 +f 571/571/888 589/589/889 569/569/890 +f 590/590/891 589/589/889 571/571/888 +f 563/563/892 564/564/893 587/587/894 +f 586/586/895 585/585/896 561/561/897 +f 585/585/896 584/584/898 558/558/899 +f 558/558/899 584/584/898 557/557/900 +f 551/551/901 581/581/902 549/549/903 +f 581/581/902 582/582/904 548/548/905 +f 589/589/906 593/593/907 568/568/842 +f 568/568/842 593/593/907 566/566/908 +f 593/593/907 592/592/909 566/566/908 +f 561/561/897 563/563/892 587/587/894 +f 586/586/895 561/561/897 587/587/894 +f 560/560/910 561/561/897 585/585/896 +f 558/558/899 560/560/910 585/585/896 +f 584/584/898 583/583/884 557/557/900 +f 557/557/900 583/583/884 555/555/886 +f 553/553/887 580/580/885 551/551/901 +f 551/551/901 580/580/885 579/579/911 +f 579/579/911 581/581/902 551/551/901 +f 549/549/903 581/581/902 548/548/905 +f 546/546/912 548/548/905 582/582/904 +f 582/582/904 588/588/913 546/546/912 +f 546/546/912 588/588/913 578/578/914 +f 577/577/915 578/578/914 588/588/913 +f 588/588/913 594/594/916 577/577/915 +f 577/577/915 594/594/916 576/576/917 +f 576/576/917 591/591/918 574/574/919 +f 591/591/918 576/576/917 594/594/916 +f 573/573/920 574/574/919 591/591/918 +f 573/573/920 591/591/918 590/590/891 +f 573/573/920 590/590/891 571/571/888 +f 569/569/843 589/589/906 568/568/842 +f 564/564/893 566/566/908 587/587/894 +f 587/587/894 566/566/908 592/592/909 +f 562/562/836 540/540/921 565/565/839 +f 565/565/839 540/540/921 567/567/841 +f 567/567/841 540/540/921 543/543/922 +f 567/567/841 543/543/922 544/544/923 +f 567/567/841 544/544/924 570/570/844 +f 570/570/925 544/544/926 542/542/927 +f 570/570/925 542/542/927 572/572/928 +f 572/572/846 542/542/929 575/575/849 +f 575/575/930 542/542/930 539/539/930 +f 575/575/849 539/539/931 547/547/821 +f 547/547/821 539/539/932 538/538/933 +f 547/547/821 538/538/933 545/545/819 +f 545/545/819 538/538/933 536/536/934 +f 545/545/819 536/536/934 550/550/824 +f 550/550/824 536/536/934 552/552/826 +f 552/552/826 536/536/934 535/535/935 +f 552/552/826 535/535/936 556/556/830 +f 556/556/830 535/535/936 537/537/937 +f 556/556/830 537/537/938 559/559/833 +f 559/559/939 537/537/939 541/541/939 +f 559/559/833 541/541/940 562/562/836 +f 562/562/836 541/541/941 540/540/921 +f 595/595/942 596/596/943 597/597/576 +f 597/597/576 598/598/944 595/595/942 +f 597/597/576 599/599/945 598/598/944 +f 597/597/576 600/600/946 599/599/945 +f 601/601/947 602/602/948 603/603/949 +f 603/603/949 602/602/948 604/604/950 +f 604/604/950 602/602/948 605/605/951 +f 604/604/950 605/605/951 606/606/952 +f 605/605/951 607/607/953 606/606/952 +f 606/606/952 607/607/953 608/608/954 +f 608/608/954 607/607/953 609/609/955 +f 608/608/954 609/609/955 610/610/956 +f 610/610/956 609/609/955 611/611/957 +f 610/610/956 611/611/957 612/612/958 +f 611/611/957 613/613/959 612/612/958 +f 612/612/958 613/613/959 614/614/960 +f 614/614/960 613/613/959 615/615/961 +f 615/615/962 616/616/963 614/614/964 +f 614/614/964 616/616/963 617/617/965 +f 617/617/966 616/616/967 618/618/968 +f 616/616/967 619/619/969 618/618/968 +f 618/618/968 619/619/969 620/620/970 +f 620/620/970 619/619/969 621/621/971 +f 620/620/970 621/621/971 603/603/972 +f 621/621/971 601/601/973 603/603/972 +f 598/598/974 611/611/975 595/595/976 +f 595/595/976 611/611/975 609/609/977 +f 595/595/976 609/609/977 607/607/978 +f 595/595/976 607/607/978 596/596/979 +f 607/607/978 605/605/980 596/596/979 +f 596/596/979 605/605/980 602/602/981 +f 596/596/979 602/602/981 597/597/982 +f 602/602/981 601/601/983 597/597/982 +f 601/601/983 621/621/984 597/597/982 +f 597/597/982 621/621/984 600/600/985 +f 600/600/985 621/621/984 619/619/986 +f 619/619/986 616/616/987 600/600/985 +f 600/600/985 616/616/987 599/599/988 +f 616/616/987 615/615/989 599/599/988 +f 599/599/988 615/615/989 613/613/990 +f 599/599/988 613/613/990 598/598/974 +f 613/613/990 611/611/975 598/598/974 +f 603/603/266 622/622/266 620/620/266 +f 620/620/266 622/622/266 623/623/266 +f 603/603/266 624/624/266 622/622/266 +f 604/604/266 624/624/266 603/603/266 +f 604/604/266 625/625/266 626/626/266 +f 606/606/266 625/625/266 604/604/266 +f 612/612/266 627/627/266 610/610/266 +f 618/618/266 623/623/266 628/628/266 +f 620/620/266 623/623/266 618/618/266 +f 604/604/266 626/626/266 624/624/266 +f 608/608/266 629/629/266 630/630/266 +f 612/612/266 631/631/266 627/627/266 +f 610/610/266 629/629/266 608/608/266 +f 608/608/266 630/630/266 606/606/266 +f 606/606/266 630/630/266 625/625/266 +f 610/610/266 632/632/266 629/629/266 +f 610/610/266 627/627/266 632/632/266 +f 614/614/266 631/631/266 612/612/266 +f 614/614/266 633/633/266 631/631/266 +f 617/617/266 634/634/266 614/614/266 +f 614/614/266 634/634/266 633/633/266 +f 618/618/266 628/628/266 617/617/266 +f 617/617/266 628/628/266 634/634/266 +f 635/635/991 636/636/992 637/637/993 +f 638/638/994 639/639/995 640/640/996 +f 641/641/997 642/642/998 639/639/995 +f 641/641/997 639/639/995 638/638/994 +f 638/638/994 640/640/996 643/643/999 +f 635/635/991 644/644/1000 645/645/1001 +f 635/635/991 645/645/1001 636/636/992 +f 646/646/1002 647/647/1003 648/648/1004 +f 643/643/999 640/640/996 644/644/1000 +f 643/643/999 644/644/1000 635/635/991 +f 637/637/993 636/636/992 649/649/1005 +f 649/649/1005 636/636/992 650/650/1006 +f 651/651/1007 652/652/1008 653/653/1009 +f 653/653/1009 652/652/1008 654/654/1010 +f 655/655/1011 656/656/1012 646/646/1002 +f 646/646/1002 656/656/1012 647/647/1003 +f 657/657/1013 658/658/1014 655/655/1011 +f 658/658/1014 656/656/1012 655/655/1011 +f 659/659/1015 660/660/1016 641/641/997 +f 641/641/997 660/660/1016 642/642/998 +f 649/649/1005 650/650/1006 661/661/1017 +f 653/653/1009 662/662/1018 657/657/1013 +f 657/657/1013 662/662/1018 658/658/1014 +f 649/649/1005 661/661/1017 651/651/1007 +f 651/651/1007 661/661/1017 652/652/1008 +f 648/648/1004 647/647/1003 660/660/1016 +f 648/648/1004 660/660/1016 659/659/1015 +f 654/654/1010 662/662/1018 653/653/1009 +f 625/625/1019 653/653/1020 657/657/1021 +f 625/625/1019 657/657/1021 626/626/1022 +f 626/626/1022 657/657/1021 655/655/1023 +f 626/626/1022 655/655/1023 624/624/1024 +f 624/624/1024 655/655/1023 646/646/1025 +f 624/624/1024 646/646/1025 622/622/1026 +f 622/622/1027 646/646/1028 648/648/1029 +f 622/622/1027 648/648/1029 659/659/1030 +f 622/622/1027 659/659/1030 623/623/1031 +f 623/623/1032 659/659/1032 641/641/1032 +f 623/623/1033 641/641/1033 628/628/1033 +f 628/628/1034 641/641/1035 638/638/1036 +f 628/628/1034 638/638/1036 634/634/1037 +f 634/634/1037 638/638/1036 643/643/1038 +f 634/634/1037 643/643/1038 633/633/1039 +f 633/633/1040 643/643/1041 635/635/1042 +f 633/633/1040 635/635/1042 631/631/1043 +f 631/631/1043 635/635/1042 627/627/1044 +f 627/627/1044 635/635/1042 637/637/1045 +f 627/627/1044 637/637/1045 649/649/1046 +f 627/627/1044 649/649/1046 632/632/1047 +f 632/632/1047 649/649/1046 629/629/1048 +f 629/629/1048 649/649/1046 651/651/1049 +f 629/629/1050 651/651/1051 630/630/1052 +f 630/630/1052 651/651/1051 653/653/1053 +f 630/630/1052 653/653/1053 625/625/1054 +f 663/663/1055 664/664/1056 665/665/1057 +f 664/664/1056 666/666/1058 667/667/1059 +f 668/668/1060 669/669/1061 670/670/1062 +f 665/665/1057 671/671/1063 663/663/1055 +f 672/672/1064 671/671/1063 665/665/1057 +f 670/670/1062 673/673/1065 668/668/1060 +f 674/674/1066 673/673/1065 675/675/1067 +f 663/663/1055 666/666/1058 664/664/1056 +f 672/672/1064 676/676/1068 677/677/1069 +f 678/678/1070 677/677/1069 676/676/1068 +f 669/669/1061 679/679/1071 678/678/1070 +f 668/668/1060 679/679/1071 669/669/1061 +f 673/673/1065 674/674/1066 668/668/1060 +f 680/680/1072 674/674/1066 675/675/1067 +f 681/681/1073 682/682/1074 680/680/1072 +f 672/672/1064 677/677/1069 671/671/1063 +f 680/680/1072 682/682/1074 674/674/1066 +f 678/678/1070 679/679/1071 677/677/1069 +f 681/681/1073 683/683/1075 682/682/1074 +f 667/667/1059 683/683/1075 681/681/1073 +f 667/667/1059 666/666/1058 683/683/1075 +f 671/671/1076 684/684/1077 663/663/1078 +f 663/663/1078 685/685/1079 666/666/1080 +f 666/666/1080 686/686/1081 683/683/1082 +f 674/674/1066 687/687/1083 668/668/1060 +f 668/668/1060 688/688/1084 679/679/1085 +f 679/679/1085 689/689/1086 677/677/1087 +f 677/677/1087 690/690/1088 691/691/1089 +f 677/677/1087 691/691/1089 671/671/1076 +f 668/668/1060 692/692/1090 688/688/1084 +f 679/679/1085 688/688/1084 689/689/1086 +f 677/677/1087 689/689/1086 693/693/1091 +f 677/677/1087 693/693/1091 690/690/1088 +f 666/666/1080 685/685/1079 694/694/1092 +f 666/666/1080 694/694/1092 686/686/1081 +f 683/683/1082 695/695/1093 682/682/1094 +f 682/682/1094 696/696/1095 674/674/1066 +f 674/674/1066 697/697/1096 687/687/1083 +f 668/668/1060 687/687/1083 692/692/1090 +f 671/671/1076 691/691/1089 698/698/1097 +f 671/671/1076 698/698/1097 684/684/1077 +f 684/684/1077 685/685/1079 663/663/1078 +f 682/682/1094 695/695/1093 696/696/1095 +f 696/696/1095 699/699/1098 674/674/1066 +f 674/674/1066 699/699/1098 697/697/1096 +f 688/688/1084 700/700/1099 689/689/1086 +f 683/683/1082 686/686/1081 695/695/1093 +f 697/697/1096 701/701/1100 687/687/1083 +f 692/692/1090 687/687/1083 702/702/1101 +f 692/692/1090 702/702/1101 703/703/1102 +f 692/692/1090 703/703/1102 688/688/1084 +f 690/690/1088 693/693/1091 704/704/1103 +f 690/690/1088 704/704/1103 691/691/1089 +f 698/698/1097 705/705/1104 684/684/1077 +f 684/684/1077 705/705/1104 685/685/1079 +f 686/686/1081 706/706/1105 695/695/1093 +f 697/697/1096 699/699/1098 701/701/1100 +f 687/687/1083 701/701/1100 702/702/1101 +f 685/685/1079 707/707/1106 694/694/1092 +f 694/694/1092 708/708/1107 686/686/1081 +f 686/686/1081 708/708/1107 706/706/1105 +f 706/706/1105 709/709/1108 695/695/1093 +f 695/695/1093 709/709/1108 696/696/1095 +f 689/689/1086 700/700/1099 644/644/1109 +f 691/691/1089 704/704/1103 698/698/1097 +f 696/696/1095 654/654/1110 699/699/1098 +f 689/689/1086 644/644/1109 693/693/1091 +f 685/685/1079 705/705/1104 707/707/1106 +f 701/701/1100 661/661/1111 702/702/1101 +f 703/703/1102 645/645/1112 688/688/1084 +f 688/688/1084 645/645/1112 700/700/1099 +f 644/644/1109 640/640/1113 693/693/1091 +f 693/693/1091 640/640/1113 704/704/1103 +f 704/704/1103 640/640/1113 639/639/1114 +f 704/704/1103 642/642/1115 698/698/1097 +f 698/698/1097 642/642/1115 705/705/1104 +f 707/707/1106 647/647/1116 694/694/1092 +f 694/694/1092 647/647/1116 708/708/1107 +f 708/708/1107 656/656/1117 706/706/1105 +f 706/706/1105 656/656/1117 709/709/1108 +f 709/709/1108 658/658/1118 662/662/1119 +f 709/709/1108 662/662/1119 696/696/1095 +f 696/696/1095 662/662/1119 654/654/1110 +f 654/654/1110 652/652/1120 699/699/1098 +f 699/699/1098 652/652/1120 701/701/1100 +f 701/701/1100 652/652/1120 661/661/1111 +f 702/702/1101 661/661/1111 650/650/1121 +f 703/703/1102 636/636/1122 645/645/1112 +f 645/645/1112 644/644/1109 700/700/1099 +f 705/705/1104 660/660/1123 707/707/1106 +f 702/702/1101 650/650/1121 636/636/1122 +f 702/702/1101 636/636/1122 703/703/1102 +f 704/704/1103 639/639/1114 642/642/1115 +f 705/705/1104 642/642/1115 660/660/1123 +f 707/707/1106 660/660/1123 647/647/1116 +f 647/647/1116 656/656/1117 708/708/1107 +f 656/656/1117 658/658/1118 709/709/1108 +f 710/710/1124 678/678/1125 676/676/1126 +f 710/710/1124 676/676/1126 672/672/1127 +f 672/672/1128 665/665/1129 711/711/1130 +f 711/711/1130 665/665/1129 664/664/1131 +f 664/664/1132 667/667/1133 712/712/1134 +f 712/712/1134 667/667/1133 681/681/1135 +f 713/713/1136 681/681/1137 680/680/1138 +f 713/713/1136 680/680/1138 675/675/1139 +f 714/714/1140 675/675/1141 673/673/1142 +f 714/714/1140 673/673/1142 670/670/1143 +f 670/670/1144 669/669/1145 715/715/1146 +f 715/715/1146 669/669/1145 678/678/1147 +f 716/716/147 717/717/147 718/718/147 +f 718/718/147 717/717/147 719/719/147 +f 718/718/147 719/719/147 720/720/147 +f 720/720/147 719/719/147 721/721/147 +f 710/710/1148 716/716/1149 718/718/1150 +f 678/678/1151 710/710/1148 718/718/1150 +f 710/710/1148 672/672/1152 716/716/1149 +f 716/716/1153 711/711/1154 717/717/1155 +f 672/672/1156 711/711/1154 716/716/1153 +f 717/717/1155 711/711/1154 664/664/1157 +f 717/717/1158 712/712/1159 719/719/1160 +f 664/664/1161 712/712/1159 717/717/1158 +f 719/719/1160 712/712/1159 681/681/1162 +f 719/719/1163 713/713/1164 721/721/1165 +f 681/681/1166 713/713/1164 719/719/1163 +f 713/713/1164 675/675/1167 721/721/1165 +f 721/721/1168 714/714/1169 720/720/1170 +f 675/675/1171 714/714/1169 721/721/1168 +f 714/714/1169 670/670/1172 720/720/1170 +f 720/720/1173 715/715/1174 718/718/1175 +f 720/720/1173 670/670/1176 715/715/1174 +f 715/715/1174 678/678/1177 718/718/1175 +f 722/722/1178 723/723/1179 724/724/1180 +f 725/725/1181 726/726/1182 722/722/1178 +f 725/725/1181 722/722/1178 724/724/1180 +f 727/727/1183 728/728/1184 729/729/1185 +f 730/730/1186 731/731/1187 732/732/1188 +f 730/730/1186 732/732/1188 733/733/1189 +f 731/731/1187 730/730/1186 734/734/1190 +f 724/724/1180 723/723/1179 732/732/1188 +f 732/732/1188 723/723/1179 733/733/1189 +f 725/725/1181 729/729/1185 726/726/1182 +f 727/727/1183 729/729/1185 725/725/1181 +f 735/735/1191 736/736/1192 731/731/1187 +f 731/731/1187 734/734/1190 735/735/1191 +f 736/736/1192 735/735/1191 737/737/1193 +f 736/736/1192 737/737/1193 727/727/1183 +f 727/727/1183 737/737/1193 728/728/1184 +f 738/738/1194 739/739/1195 740/740/1196 +f 738/738/1194 741/741/1197 739/739/1195 +f 742/742/1198 741/741/1197 738/738/1194 +f 738/738/1194 743/743/1199 742/742/1198 +f 738/738/1194 744/744/1200 743/743/1199 +f 738/738/1194 745/745/1201 744/744/1200 +f 738/738/1194 746/746/1202 747/747/1203 +f 738/738/1194 748/748/1204 746/746/1202 +f 749/749/1205 748/748/1204 738/738/1194 +f 740/740/1196 749/749/1205 738/738/1194 +f 750/750/1206 740/740/1207 751/751/1208 +f 751/751/1208 740/740/1207 739/739/1209 +f 751/751/1208 739/739/1209 752/752/1210 +f 752/752/1210 739/739/1209 741/741/1211 +f 752/752/1210 741/741/1211 742/742/1212 +f 752/752/1210 742/742/1212 753/753/1213 +f 753/753/1213 742/742/1212 743/743/1214 +f 753/753/1213 743/743/1214 754/754/1215 +f 754/754/1215 743/743/1214 744/744/1216 +f 754/754/1215 744/744/1216 755/755/1217 +f 755/755/1217 744/744/1216 745/745/1218 +f 755/755/1217 745/745/1218 756/756/1219 +f 755/755/1217 756/756/1219 757/757/1220 +f 757/757/1220 756/756/1219 738/738/1221 +f 757/757/1220 738/738/1221 758/758/1222 +f 758/758/1222 738/738/1221 747/747/1223 +f 758/758/1222 747/747/1223 746/746/1224 +f 758/758/1222 746/746/1224 759/759/1225 +f 759/759/1225 746/746/1224 748/748/1226 +f 759/759/1225 748/748/1226 749/749/1227 +f 759/759/1225 749/749/1227 750/750/1206 +f 750/750/1206 749/749/1227 740/740/1207 +f 751/751/1 760/760/1 761/761/1 +f 751/751/1 761/761/1 750/750/1 +f 758/758/1 762/762/1 757/757/1 +f 757/757/1 762/762/1 763/763/1 +f 750/750/1 761/761/1 764/764/1 +f 757/757/1 763/763/1 755/755/1 +f 755/755/1 763/763/1 765/765/1 +f 750/750/1 764/764/1 759/759/1 +f 759/759/1 764/764/1 766/766/1 +f 759/759/1 766/766/1 767/767/1 +f 752/752/1 768/768/1 760/760/1 +f 752/752/1 760/760/1 751/751/1 +f 755/755/1 765/765/1 769/769/1 +f 759/759/1 770/770/1 758/758/1 +f 758/758/1 770/770/1 762/762/1 +f 752/752/1 771/771/1 768/768/1 +f 753/753/1 772/772/1 771/771/1 +f 753/753/1 771/771/1 752/752/1 +f 759/759/1 767/767/1 770/770/1 +f 754/754/1 772/772/1 753/753/1 +f 755/755/1 769/769/1 754/754/1 +f 754/754/1 773/773/1 772/772/1 +f 769/769/1 773/773/1 754/754/1 +f 761/761/1228 774/774/1229 764/764/1230 +f 764/764/1230 774/774/1229 775/775/1231 +f 775/775/1231 776/776/1232 764/764/1230 +f 764/764/1230 776/776/1232 766/766/1233 +f 776/776/1232 777/777/1234 766/766/1233 +f 766/766/1233 777/777/1234 767/767/1235 +f 777/777/1234 778/778/1236 767/767/1235 +f 778/778/1236 779/779/1237 767/767/1235 +f 767/767/1235 779/779/1237 770/770/1238 +f 770/770/1238 779/779/1237 762/762/1239 +f 779/779/1237 780/780/1240 762/762/1239 +f 762/762/1239 780/780/1240 781/781/1241 +f 781/781/1241 763/763/1242 762/762/1239 +f 781/781/1241 782/782/1243 763/763/1242 +f 763/763/1242 782/782/1243 765/765/1244 +f 765/765/1244 782/782/1243 783/783/1245 +f 765/765/1244 783/783/1245 769/769/1246 +f 769/769/1246 783/783/1245 784/784/1247 +f 769/769/1246 784/784/1247 773/773/1248 +f 773/773/1248 784/784/1247 785/785/1249 +f 773/773/1248 785/785/1249 786/786/1250 +f 773/773/1248 786/786/1250 772/772/1251 +f 786/786/1250 787/787/1252 772/772/1251 +f 772/772/1251 787/787/1252 771/771/1253 +f 771/771/1253 787/787/1252 788/788/1254 +f 771/771/1253 788/788/1254 768/768/1255 +f 789/789/1256 768/768/1255 788/788/1254 +f 768/768/1255 789/789/1256 760/760/1257 +f 760/760/1257 789/789/1256 790/790/1258 +f 760/760/1257 790/790/1258 761/761/1228 +f 761/761/1228 790/790/1258 774/774/1229 +f 791/791/1259 792/792/1260 793/793/1261 +f 737/737/1262 794/794/1263 791/791/1259 +f 791/791/1259 795/795/1264 792/792/1260 +f 792/792/1260 795/795/1264 783/783/1245 +f 791/791/1259 794/794/1263 795/795/1264 +f 783/783/1245 795/795/1264 784/784/1247 +f 735/735/1265 794/794/1263 737/737/1262 +f 796/796/1266 794/794/1263 735/735/1265 +f 796/796/1266 795/795/1264 794/794/1263 +f 784/784/1247 795/795/1264 785/785/1249 +f 797/797/1267 785/785/1249 795/795/1264 +f 797/797/1267 795/795/1264 796/796/1266 +f 796/796/1266 735/735/1265 798/798/1268 +f 797/797/1267 796/796/1266 798/798/1268 +f 785/785/1249 797/797/1267 786/786/1250 +f 799/799/1269 786/786/1250 797/797/1267 +f 799/799/1269 797/797/1267 798/798/1268 +f 734/734/1270 798/798/1268 735/735/1265 +f 787/787/1252 786/786/1250 799/799/1269 +f 800/800/1271 799/799/1269 798/798/1268 +f 800/800/1271 798/798/1268 734/734/1270 +f 787/787/1252 799/799/1269 800/800/1271 +f 730/730/1186 800/800/1271 734/734/1270 +f 787/787/1252 800/800/1271 801/801/1272 +f 802/802/1273 801/801/1272 800/800/1271 +f 802/802/1273 800/800/1271 730/730/1186 +f 787/787/1252 801/801/1272 788/788/1254 +f 802/802/1273 788/788/1254 801/801/1272 +f 803/803/1274 802/802/1273 730/730/1186 +f 733/733/1189 803/803/1274 730/730/1186 +f 804/804/1275 788/788/1254 802/802/1273 +f 802/802/1273 803/803/1274 804/804/1275 +f 788/788/1254 804/804/1275 789/789/1256 +f 805/805/1276 789/789/1256 804/804/1275 +f 805/805/1276 804/804/1275 803/803/1274 +f 803/803/1274 733/733/1189 806/806/1277 +f 803/803/1274 806/806/1277 805/805/1276 +f 789/789/1256 805/805/1276 790/790/1258 +f 807/807/1278 805/805/1276 806/806/1277 +f 805/805/1276 807/807/1278 790/790/1258 +f 723/723/1179 806/806/1277 733/733/1189 +f 790/790/1258 807/807/1278 774/774/1229 +f 806/806/1277 808/808/1279 807/807/1278 +f 808/808/1279 806/806/1277 723/723/1179 +f 809/809/1280 774/774/1229 807/807/1278 +f 809/809/1280 807/807/1278 808/808/1279 +f 723/723/1179 810/810/1281 808/808/1279 +f 808/808/1279 810/810/1281 809/809/1280 +f 774/774/1229 809/809/1280 775/775/1231 +f 723/723/1179 722/722/1282 810/810/1281 +f 810/810/1281 811/811/1283 809/809/1280 +f 809/809/1280 811/811/1283 776/776/1232 +f 809/809/1280 776/776/1232 775/775/1231 +f 810/810/1281 722/722/1282 811/811/1283 +f 811/811/1283 812/812/1284 776/776/1232 +f 777/777/1234 776/776/1232 812/812/1284 +f 813/813/1285 812/812/1284 811/811/1283 +f 813/813/1285 811/811/1283 722/722/1282 +f 812/812/1284 813/813/1285 814/814/1286 +f 777/777/1234 812/812/1284 778/778/1236 +f 722/722/1282 726/726/1287 813/813/1285 +f 812/812/1284 814/814/1286 778/778/1236 +f 779/779/1237 778/778/1236 814/814/1286 +f 814/814/1286 813/813/1285 726/726/1287 +f 726/726/1287 815/815/1288 814/814/1286 +f 814/814/1286 815/815/1288 779/779/1237 +f 816/816/1289 779/779/1237 815/815/1288 +f 817/817/1290 815/815/1288 726/726/1287 +f 817/817/1290 726/726/1287 729/729/1185 +f 816/816/1289 815/815/1288 817/817/1290 +f 779/779/1237 816/816/1289 780/780/1240 +f 818/818/1291 780/780/1240 816/816/1289 +f 818/818/1291 816/816/1289 817/817/1290 +f 817/817/1290 729/729/1185 818/818/1291 +f 819/819/1292 818/818/1291 729/729/1185 +f 818/818/1291 820/820/1293 780/780/1240 +f 781/781/1241 780/780/1240 820/820/1293 +f 820/820/1293 818/818/1291 819/819/1292 +f 819/819/1292 821/821/1294 820/820/1293 +f 821/821/1294 781/781/1241 820/820/1293 +f 728/728/1184 819/819/1292 729/729/1185 +f 819/819/1292 728/728/1184 821/821/1294 +f 781/781/1241 821/821/1294 782/782/1243 +f 821/821/1294 793/793/1261 782/782/1243 +f 783/783/1245 782/782/1243 793/793/1261 +f 791/791/1259 821/821/1294 728/728/1184 +f 793/793/1261 821/821/1294 791/791/1259 +f 728/728/1184 737/737/1262 791/791/1259 +f 793/793/1261 792/792/1260 783/783/1245 +f 724/724/128 732/732/128 822/822/128 +f 822/822/128 732/732/128 823/823/128 +f 725/725/129 724/724/129 824/824/129 +f 824/824/129 724/724/129 822/822/129 +f 727/727/130 725/725/130 825/825/130 +f 825/825/130 725/725/130 824/824/130 +f 736/736/124 727/727/124 826/826/124 +f 826/826/124 727/727/124 825/825/124 +f 731/731/125 736/736/125 827/827/125 +f 827/827/125 736/736/125 826/826/126 +f 732/732/127 731/731/127 823/823/127 +f 823/823/127 731/731/127 827/827/127 +f 827/827/2 826/826/2 823/823/2 +f 823/823/2 826/826/2 825/825/2 +f 823/823/2 825/825/2 822/822/2 +f 822/822/2 825/825/2 824/824/2 +f 756/756/1295 745/745/1201 738/738/1194 +f 828/828/1296 829/829/1297 830/830/1298 +f 831/831/1299 832/832/1300 833/833/1301 +f 830/830/1298 829/829/1297 832/832/1300 +f 834/834/1302 835/835/1303 828/828/1296 +f 834/834/1302 828/828/1296 830/830/1298 +f 834/834/1302 836/836/1304 835/835/1303 +f 837/837/1305 838/838/1306 839/839/1307 +f 833/833/1301 839/839/1307 831/831/1299 +f 830/830/1298 832/832/1300 831/831/1299 +f 833/833/1301 837/837/1305 839/839/1307 +f 840/840/1308 841/841/1309 834/834/1302 +f 834/834/1302 841/841/1309 836/836/1304 +f 842/842/1310 843/843/1311 844/844/1312 +f 840/840/1308 844/844/1312 841/841/1309 +f 838/838/1306 842/842/1310 839/839/1307 +f 842/842/1310 838/838/1306 843/843/1311 +f 842/842/1310 844/844/1312 840/840/1308 +f 845/845/1313 846/846/1314 847/847/1315 +f 845/845/1313 848/848/1316 846/846/1314 +f 845/845/1313 849/849/1317 848/848/1316 +f 850/850/1318 849/849/1317 845/845/1313 +f 851/851/1319 850/850/1318 845/845/1313 +f 845/845/1313 852/852/1320 851/851/1319 +f 845/845/1313 853/853/1321 852/852/1320 +f 845/845/1313 854/854/1322 853/853/1321 +f 845/845/1313 855/855/1323 854/854/1322 +f 856/856/1324 855/855/1323 845/845/1313 +f 857/857/1325 846/846/1326 858/858/1327 +f 858/858/1327 846/846/1326 848/848/1328 +f 858/858/1327 848/848/1328 859/859/1329 +f 859/859/1329 848/848/1328 849/849/1330 +f 859/859/1329 849/849/1330 860/860/1331 +f 860/860/1331 849/849/1330 850/850/1332 +f 860/860/1331 850/850/1332 861/861/1333 +f 861/861/1333 850/850/1332 851/851/1334 +f 861/861/1335 851/851/1336 852/852/1337 +f 861/861/1335 852/852/1337 862/862/1338 +f 862/862/1338 852/852/1337 853/853/1339 +f 862/862/1338 853/853/1339 854/854/1340 +f 862/862/1338 854/854/1340 863/863/1341 +f 863/863/1341 854/854/1340 855/855/1342 +f 863/863/1341 855/855/1342 864/864/1343 +f 864/864/1343 855/855/1342 856/856/1344 +f 864/864/1345 856/856/1346 845/845/1347 +f 864/864/1345 845/845/1347 857/857/1348 +f 857/857/1348 845/845/1347 847/847/1349 +f 857/857/1325 847/847/1350 846/846/1326 +f 858/858/1 865/865/1 866/866/1 +f 858/858/1 866/866/1 857/857/1 +f 863/863/1 867/867/1 862/862/1 +f 862/862/1 867/867/1 868/868/1 +f 857/857/1 869/869/1 864/864/1 +f 864/864/1 869/869/1 870/870/1 +f 857/857/1 866/866/1 869/869/1 +f 862/862/1 868/868/1 871/871/1 +f 863/863/1 872/872/1 867/867/1 +f 859/859/1 873/873/1 865/865/1 +f 859/859/1 865/865/1 858/858/1 +f 862/862/1 871/871/1 861/861/1 +f 861/861/1 871/871/1 874/874/1 +f 864/864/1 872/872/1 863/863/1 +f 859/859/1 875/875/1 873/873/1 +f 860/860/1 875/875/1 859/859/1 +f 870/870/1 876/876/1 864/864/1 +f 864/864/1 876/876/1 872/872/1 +f 860/860/1 877/877/1 875/875/1 +f 861/861/1 878/878/1 860/860/1 +f 860/860/1 878/878/1 877/877/1 +f 874/874/1 878/878/1 861/861/1 +f 879/879/1351 880/880/1352 866/866/1353 +f 866/866/1353 880/880/1352 869/869/1354 +f 880/880/1352 881/881/1355 869/869/1356 +f 881/881/1355 870/870/1357 869/869/1356 +f 870/870/1357 881/881/1355 882/882/1358 +f 882/882/1358 876/876/1359 870/870/1357 +f 882/882/1358 883/883/1360 876/876/1359 +f 883/883/1360 872/872/1361 876/876/1359 +f 883/883/1360 884/884/1362 872/872/1361 +f 884/884/1362 885/885/1363 872/872/1361 +f 872/872/1361 885/885/1363 867/867/1364 +f 885/885/1363 886/886/1365 867/867/1364 +f 867/867/1364 886/886/1365 868/868/1366 +f 886/886/1365 887/887/1367 868/868/1366 +f 868/868/1366 887/887/1367 871/871/1368 +f 871/871/1368 887/887/1367 888/888/1369 +f 871/871/1368 888/888/1369 874/874/1370 +f 874/874/1370 888/888/1369 889/889/1371 +f 889/889/1371 890/890/1372 874/874/1370 +f 874/874/1370 890/890/1372 878/878/1373 +f 890/890/1372 891/891/1374 878/878/1373 +f 878/878/1373 891/891/1374 892/892/1375 +f 878/878/1373 892/892/1375 877/877/1376 +f 892/892/1375 893/893/1377 877/877/1376 +f 893/893/1377 875/875/1378 877/877/1376 +f 893/893/1377 894/894/1379 875/875/1378 +f 894/894/1379 873/873/1380 875/875/1378 +f 894/894/1379 895/895/1381 873/873/1380 +f 873/873/1380 895/895/1381 865/865/1382 +f 895/895/1381 879/879/1351 865/865/1382 +f 865/865/1382 879/879/1351 866/866/1353 +f 896/896/1383 888/888/1369 897/897/1384 +f 896/896/1383 897/897/1384 844/844/1385 +f 843/843/1386 896/896/1383 844/844/1385 +f 896/896/1383 889/889/1371 888/888/1369 +f 898/898/1387 889/889/1371 896/896/1383 +f 898/898/1387 896/896/1383 843/843/1386 +f 890/890/1372 889/889/1371 899/899/1388 +f 899/899/1388 889/889/1371 898/898/1387 +f 898/898/1387 843/843/1386 900/900/1389 +f 898/898/1387 900/900/1389 899/899/1388 +f 838/838/1390 900/900/1389 843/843/1386 +f 899/899/1388 900/900/1389 891/891/1374 +f 899/899/1388 891/891/1374 890/890/1372 +f 901/901/1391 900/900/1389 838/838/1390 +f 900/900/1389 901/901/1391 902/902/1392 +f 900/900/1389 902/902/1392 891/891/1374 +f 892/892/1375 891/891/1374 902/902/1392 +f 901/901/1391 838/838/1390 903/903/1393 +f 893/893/1377 892/892/1375 902/902/1392 +f 903/903/1393 902/902/1392 901/901/1391 +f 837/837/1394 903/903/1393 838/838/1390 +f 902/902/1392 903/903/1393 904/904/1395 +f 904/904/1395 893/893/1377 902/902/1392 +f 905/905/1396 903/903/1393 837/837/1394 +f 906/906/1397 893/893/1377 904/904/1395 +f 906/906/1397 904/904/1395 905/905/1396 +f 905/905/1396 904/904/1395 903/903/1393 +f 893/893/1377 906/906/1397 894/894/1379 +f 833/833/1398 905/905/1396 837/837/1394 +f 894/894/1379 906/906/1397 907/907/1399 +f 907/907/1399 906/906/1397 905/905/1396 +f 833/833/1398 907/907/1399 905/905/1396 +f 895/895/1381 894/894/1379 907/907/1399 +f 833/833/1398 908/908/1400 907/907/1399 +f 907/907/1399 908/908/1400 895/895/1381 +f 833/833/1398 832/832/1401 909/909/1402 +f 833/833/1398 909/909/1402 908/908/1400 +f 908/908/1400 909/909/1402 895/895/1381 +f 879/879/1351 895/895/1381 909/909/1402 +f 909/909/1402 910/910/1403 879/879/1351 +f 909/909/1402 832/832/1401 911/911/1404 +f 909/909/1402 911/911/1404 910/910/1403 +f 829/829/1405 911/911/1404 832/832/1401 +f 910/910/1403 911/911/1404 912/912/1406 +f 910/910/1403 912/912/1406 879/879/1351 +f 879/879/1351 912/912/1406 880/880/1352 +f 913/913/1407 911/911/1404 829/829/1405 +f 914/914/1408 912/912/1406 911/911/1404 +f 829/829/1405 828/828/1409 913/913/1407 +f 911/911/1404 913/913/1407 914/914/1408 +f 912/912/1406 914/914/1408 880/880/1352 +f 880/880/1352 914/914/1408 881/881/1355 +f 915/915/1410 914/914/1408 913/913/1407 +f 915/915/1410 913/913/1407 828/828/1409 +f 915/915/1410 881/881/1355 914/914/1408 +f 882/882/1358 881/881/1355 915/915/1410 +f 916/916/1411 915/915/1410 828/828/1409 +f 828/828/1409 835/835/1412 916/916/1411 +f 915/915/1410 917/917/1413 882/882/1358 +f 915/915/1410 916/916/1411 917/917/1413 +f 882/882/1358 917/917/1413 883/883/1360 +f 918/918/1414 883/883/1360 917/917/1413 +f 918/918/1414 917/917/1413 916/916/1411 +f 835/835/1412 836/836/1415 916/916/1411 +f 884/884/1362 883/883/1360 918/918/1414 +f 919/919/1416 918/918/1414 916/916/1411 +f 919/919/1416 916/916/1411 836/836/1415 +f 919/919/1416 884/884/1362 918/918/1414 +f 919/919/1416 836/836/1415 920/920/1417 +f 884/884/1362 919/919/1416 885/885/1363 +f 920/920/1417 836/836/1415 841/841/1418 +f 919/919/1416 920/920/1417 921/921/1419 +f 919/919/1416 921/921/1419 885/885/1363 +f 920/920/1417 841/841/1418 921/921/1419 +f 885/885/1363 921/921/1419 886/886/1365 +f 922/922/1420 921/921/1419 841/841/1418 +f 921/921/1419 922/922/1420 886/886/1365 +f 886/886/1365 922/922/1420 887/887/1367 +f 841/841/1418 923/923/1421 922/922/1420 +f 887/887/1367 922/922/1420 923/923/1421 +f 844/844/1385 923/923/1421 841/841/1418 +f 897/897/1384 887/887/1367 923/923/1421 +f 923/923/1421 844/844/1385 897/897/1384 +f 897/897/1384 888/888/1369 887/887/1367 +f 830/830/128 831/831/128 924/924/128 +f 924/924/128 831/831/128 925/925/128 +f 834/834/129 830/830/129 926/926/129 +f 926/926/129 830/830/129 924/924/129 +f 840/840/130 834/834/130 927/927/130 +f 927/927/130 834/834/130 926/926/130 +f 842/842/124 840/840/124 928/928/124 +f 928/928/124 840/840/124 927/927/124 +f 839/839/125 842/842/125 929/929/125 +f 929/929/125 842/842/125 928/928/126 +f 831/831/127 839/839/127 925/925/127 +f 925/925/127 839/839/127 929/929/127 +f 929/929/2 928/928/2 925/925/2 +f 925/925/2 928/928/2 927/927/2 +f 925/925/2 927/927/2 924/924/2 +f 924/924/2 927/927/2 926/926/2 +f 930/930/147 931/931/147 932/932/147 +f 933/933/147 934/934/147 935/935/147 +f 935/935/147 934/934/147 936/936/147 +f 937/937/147 938/938/147 939/939/147 +f 937/937/147 939/939/147 933/933/147 +f 935/935/147 936/936/147 930/930/147 +f 930/930/147 936/936/147 931/931/147 +f 933/933/147 939/939/147 934/934/147 +f 940/940/147 941/941/147 937/937/147 +f 941/941/147 938/938/147 937/937/147 +f 932/932/147 942/942/147 943/943/147 +f 943/943/147 942/942/147 944/944/147 +f 945/945/147 946/946/147 947/947/147 +f 947/947/147 946/946/147 948/948/147 +f 947/947/147 948/948/147 949/949/147 +f 947/947/147 949/949/147 207/207/147 +f 943/943/147 944/944/147 950/950/147 +f 950/950/147 944/944/147 951/951/147 +f 207/207/147 952/952/147 941/941/147 +f 207/207/147 941/941/147 940/940/147 +f 950/950/147 951/951/147 946/946/147 +f 950/950/147 946/946/147 945/945/147 +f 931/931/147 953/953/147 932/932/147 +f 932/932/147 953/953/147 942/942/147 +f 207/207/147 949/949/147 952/952/147 +f 954/954/1422 932/932/1423 955/955/1424 +f 955/955/1425 932/932/1426 956/956/1427 +f 956/956/1427 932/932/1426 943/943/1428 +f 956/956/1429 943/943/1430 950/950/1431 +f 956/956/1429 950/950/1431 957/957/1432 +f 957/957/1433 950/950/1434 945/945/1435 +f 957/957/1433 945/945/1435 958/958/1436 +f 958/958/1437 945/945/1437 947/947/1437 +f 958/958/1438 947/947/1438 959/959/1438 +f 959/959/1439 947/947/1440 960/960/1441 +f 960/960/1441 947/947/1440 207/207/1442 +f 960/960/1443 207/207/1444 961/961/1445 +f 961/961/1445 207/207/1444 940/940/1446 +f 961/961/1447 940/940/1447 937/937/1447 +f 961/961/1448 937/937/1448 962/962/1448 +f 962/962/1449 937/937/1449 933/933/1449 +f 962/962/1450 933/933/1450 963/963/1450 +f 963/963/1451 933/933/1451 935/935/1451 +f 963/963/1452 935/935/1452 964/964/1452 +f 964/964/1453 935/935/1453 930/930/1453 +f 964/964/1454 930/930/1454 954/954/1454 +f 954/954/1422 930/930/1455 932/932/1423 +f 960/960/266 965/965/266 959/959/266 +f 959/959/266 965/965/266 966/966/266 +f 967/967/266 968/968/266 962/962/266 +f 962/962/266 968/968/266 961/961/266 +f 960/960/266 969/969/266 965/965/266 +f 961/961/266 970/970/266 969/969/266 +f 961/961/266 968/968/266 970/970/266 +f 963/963/266 971/971/266 967/967/266 +f 963/963/266 967/967/266 962/962/266 +f 964/964/266 972/972/266 963/963/266 +f 963/963/266 972/972/266 971/971/266 +f 958/958/266 966/966/266 973/973/266 +f 959/959/266 966/966/266 958/958/266 +f 954/954/266 972/972/266 964/964/266 +f 961/961/266 969/969/266 960/960/266 +f 954/954/266 974/974/266 972/972/266 +f 975/975/266 976/976/266 957/957/266 +f 957/957/266 976/976/266 956/956/266 +f 956/956/266 976/976/266 977/977/266 +f 958/958/266 973/973/266 975/975/266 +f 958/958/266 975/975/266 957/957/266 +f 955/955/266 978/978/266 954/954/266 +f 954/954/266 978/978/266 974/974/266 +f 977/977/266 978/978/266 956/956/266 +f 956/956/266 978/978/266 955/955/266 +f 931/931/1456 978/978/1456 953/953/1456 +f 953/953/1457 978/978/1457 942/942/1457 +f 942/942/1458 978/978/1459 977/977/1460 +f 942/942/1458 977/977/1460 944/944/1461 +f 944/944/1461 977/977/1460 976/976/1462 +f 944/944/1461 976/976/1462 951/951/1463 +f 951/951/1463 976/976/1462 975/975/1464 +f 951/951/1465 975/975/1465 946/946/1465 +f 946/946/1466 975/975/1466 973/973/1466 +f 946/946/1467 973/973/1468 966/966/1469 +f 946/946/1467 966/966/1469 948/948/1470 +f 948/948/1471 966/966/1472 965/965/1473 +f 948/948/1471 965/965/1473 949/949/1474 +f 949/949/1475 965/965/1475 952/952/1475 +f 952/952/1476 965/965/1476 969/969/1476 +f 952/952/1477 969/969/1477 941/941/1477 +f 941/941/1478 969/969/1478 970/970/1478 +f 941/941/1479 970/970/1480 938/938/1481 +f 938/938/1481 970/970/1480 968/968/1482 +f 938/938/1481 968/968/1482 939/939/1483 +f 939/939/1483 968/968/1482 967/967/1484 +f 939/939/1485 967/967/1485 934/934/1485 +f 934/934/1486 967/967/1486 971/971/1486 +f 934/934/1487 971/971/1488 972/972/1489 +f 934/934/1487 972/972/1489 936/936/1490 +f 936/936/1491 972/972/1492 931/931/1493 +f 931/931/1493 972/972/1492 974/974/1494 +f 931/931/1495 974/974/1495 978/978/1495 +f 979/979/266 980/980/266 981/981/266 +f 982/982/266 983/983/266 980/980/266 +f 982/982/266 980/980/266 979/979/266 +f 984/984/266 985/985/266 986/986/266 +f 986/986/266 985/985/266 987/987/266 +f 988/988/266 989/989/266 984/984/266 +f 988/988/266 990/990/266 989/989/266 +f 986/986/266 987/987/266 983/983/266 +f 986/986/266 983/983/266 982/982/266 +f 989/989/266 985/985/266 984/984/266 +f 991/991/266 992/992/266 988/988/266 +f 993/993/266 994/994/266 995/995/266 +f 996/996/266 997/997/266 998/998/266 +f 992/992/266 990/990/266 988/988/266 +f 999/999/266 997/997/266 996/996/266 +f 1000/1000/266 1001/1001/266 993/993/266 +f 993/993/266 1001/1001/266 994/994/266 +f 996/996/266 1002/1002/266 1000/1000/266 +f 996/996/266 998/998/266 1002/1002/266 +f 991/991/266 1003/1003/266 992/992/266 +f 1000/1000/266 1002/1002/266 1001/1001/266 +f 979/979/266 981/981/266 999/999/266 +f 999/999/266 981/981/266 997/997/266 +f 995/995/266 1004/1004/266 991/991/266 +f 991/991/266 1004/1004/266 1003/1003/266 +f 994/994/266 1004/1004/266 995/995/266 +f 1005/1005/1496 979/979/1497 1006/1006/1498 +f 1006/1006/1498 979/979/1497 999/999/1499 +f 1006/1006/1498 999/999/1499 996/996/1500 +f 1006/1006/1498 996/996/1500 1007/1007/1501 +f 1007/1007/1502 996/996/1503 1008/1008/1504 +f 1008/1008/1504 996/996/1503 1000/1000/1505 +f 1008/1008/1506 1000/1000/1507 993/993/1508 +f 1008/1008/1506 993/993/1508 1009/1009/1509 +f 1009/1009/1510 993/993/1510 995/995/1510 +f 1009/1009/1511 995/995/1511 1010/1010/1511 +f 1010/1010/1512 995/995/1513 991/991/1514 +f 1010/1010/1512 991/991/1514 1011/1011/1515 +f 1011/1011/1516 991/991/1516 988/988/1516 +f 1011/1011/1517 988/988/1517 1012/1012/1517 +f 1012/1012/1518 988/988/1518 984/984/1518 +f 1012/1012/1519 984/984/1519 1013/1013/1519 +f 1013/1013/1520 984/984/1520 986/986/1520 +f 1013/1013/1521 986/986/1521 1014/1014/1521 +f 1014/1014/1522 986/986/1522 982/982/1522 +f 1014/1014/1523 982/982/1524 1005/1005/1525 +f 1005/1005/1525 982/982/1524 979/979/1526 +f 1013/1013/147 1015/1015/147 1012/1012/147 +f 1010/1010/147 1016/1016/147 1009/1009/147 +f 1012/1012/147 1017/1017/147 1011/1011/147 +f 1010/1010/147 1018/1018/147 1016/1016/147 +f 1011/1011/147 1019/1019/147 1018/1018/147 +f 1011/1011/147 1018/1018/147 1010/1010/147 +f 1011/1011/147 1017/1017/147 1019/1019/147 +f 1015/1015/147 1017/1017/147 1012/1012/147 +f 1013/1013/147 1020/1020/147 1015/1015/147 +f 1014/1014/147 1020/1020/147 1013/1013/147 +f 1009/1009/147 1021/1021/147 1008/1008/147 +f 1008/1008/147 1021/1021/147 1022/1022/147 +f 1016/1016/147 1021/1021/147 1009/1009/147 +f 1014/1014/147 1023/1023/147 1020/1020/147 +f 1014/1014/147 1024/1024/147 1023/1023/147 +f 1005/1005/147 1024/1024/147 1014/1014/147 +f 1008/1008/147 1025/1025/147 1007/1007/147 +f 1005/1005/147 1026/1026/147 1024/1024/147 +f 1007/1007/147 1027/1027/147 1028/1028/147 +f 1007/1007/147 1028/1028/147 1006/1006/147 +f 1007/1007/147 1025/1025/147 1027/1027/147 +f 1008/1008/147 1022/1022/147 1025/1025/147 +f 1006/1006/147 1026/1026/147 1005/1005/147 +f 1006/1006/147 1028/1028/147 1026/1026/147 +f 981/981/1527 1026/1026/1528 997/997/1529 +f 997/997/1529 1026/1026/1528 1028/1028/1530 +f 997/997/1529 1028/1028/1530 1027/1027/1531 +f 997/997/1529 1027/1027/1531 998/998/1532 +f 998/998/1532 1027/1027/1531 1025/1025/1533 +f 998/998/1532 1025/1025/1533 1002/1002/1534 +f 1002/1002/1534 1025/1025/1533 1022/1022/1535 +f 1002/1002/1534 1022/1022/1535 1001/1001/1536 +f 1001/1001/1537 1022/1022/1537 1021/1021/1537 +f 1001/1001/1538 1021/1021/1538 994/994/1538 +f 994/994/1539 1021/1021/1539 1016/1016/1539 +f 994/994/1540 1016/1016/1540 1004/1004/1540 +f 1004/1004/1541 1016/1016/1542 1018/1018/1543 +f 1004/1004/1541 1018/1018/1543 1003/1003/1544 +f 1003/1003/1544 1018/1018/1543 1019/1019/1545 +f 1003/1003/1546 1019/1019/1546 992/992/1546 +f 992/992/1547 1019/1019/1547 1017/1017/1547 +f 992/992/1548 1017/1017/1548 990/990/1548 +f 990/990/1549 1017/1017/1550 1015/1015/1551 +f 990/990/1549 1015/1015/1551 989/989/1552 +f 989/989/1553 1015/1015/1553 985/985/1553 +f 985/985/1554 1015/1015/1554 1020/1020/1554 +f 985/985/1555 1020/1020/1555 987/987/1555 +f 987/987/1556 1020/1020/1557 1023/1023/1558 +f 987/987/1556 1023/1023/1558 983/983/1559 +f 983/983/1559 1023/1023/1558 1024/1024/1560 +f 983/983/1559 1024/1024/1560 980/980/1561 +f 980/980/1561 1024/1024/1560 1026/1026/1528 +f 980/980/1561 1026/1026/1528 981/981/1527 +f 8/8/124 4/4/124 3/3/124 +f 7/7/124 4/4/124 8/8/124 +f 6/6/147 1/1/147 4/4/147 +f 4/4/147 7/7/147 6/6/147 +f 2/2/266 5/5/266 8/8/266 +f 8/8/266 3/3/266 2/2/266 +f 6/6/128 5/5/128 2/2/128 +f 6/6/128 2/2/128 1/1/128 diff --git a/examples/Cassie/urdf/meshes/agility/knee.obj b/examples/Cassie/urdf/meshes/agility/knee.obj new file mode 100644 index 0000000000..98830d3f73 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/knee.obj @@ -0,0 +1,4543 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o knee +v 0.060677 -0.025000 -0.090906 +v 0.010677 0.025000 -0.090906 +v 0.060677 0.025000 -0.090906 +v 0.010677 -0.025000 -0.090906 +v 0.010677 0.025000 -0.082406 +v 0.010677 -0.025000 -0.082406 +v 0.060677 -0.025000 -0.082406 +v 0.060677 0.025000 -0.082406 +v 0.060677 0.008450 -0.090906 +v 0.057872 -0.017056 -0.090899 +v 0.061715 -0.025000 -0.090924 +v 0.061801 0.025000 -0.090920 +v 0.065745 -0.025000 -0.092613 +v 0.065811 0.025000 -0.092708 +v 0.011677 0.000000 -0.095906 +v 0.014772 -0.010734 -0.095893 +v 0.011095 -0.015271 -0.095339 +v 0.026759 -0.008299 -0.095906 +v 0.020151 -0.022425 -0.095900 +v 0.023150 -0.017480 -0.095898 +v 0.026489 -0.023813 -0.095906 +v 0.011885 -0.023765 -0.095912 +v 0.011396 -0.020055 -0.095666 +v 0.014711 -0.023137 -0.095901 +v 0.020854 -0.012110 -0.095901 +v 0.026821 0.008335 -0.095906 +v 0.017782 0.010664 -0.095901 +v 0.022475 0.014105 -0.095898 +v 0.022368 0.019997 -0.095901 +v 0.026489 0.024000 -0.095906 +v 0.018268 0.023195 -0.095903 +v 0.011898 0.023779 -0.095912 +v 0.014094 0.022784 -0.095905 +v 0.011663 0.012774 -0.095885 +v 0.011134 0.019120 -0.095408 +v 0.050940 0.022180 -0.095903 +v 0.048204 0.017480 -0.095898 +v 0.047927 0.024000 -0.095906 +v 0.047516 0.008946 -0.095906 +v 0.049754 0.013067 -0.095905 +v 0.060580 0.019679 -0.095899 +v 0.055996 0.023296 -0.095901 +v 0.064585 0.024025 -0.095881 +v 0.057704 -0.000853 -0.095959 +v 0.059692 0.012700 -0.095897 +v 0.053358 0.010704 -0.095901 +v 0.049505 0.007317 -0.095906 +v 0.049448 -0.007443 -0.095906 +v 0.050940 -0.011820 -0.095903 +v 0.047446 -0.008954 -0.095906 +v 0.048276 -0.016229 -0.095900 +v 0.045177 -0.023813 -0.095906 +v 0.049495 -0.020651 -0.095905 +v 0.059598 -0.013076 -0.095906 +v 0.055996 -0.010704 -0.095901 +v 0.064610 -0.024027 -0.095880 +v 0.058674 -0.022035 -0.095902 +v 0.061116 -0.017107 -0.095901 +v 0.053477 -0.023407 -0.095940 +v 0.036782 -0.023336 -0.095901 +v 0.031838 -0.022100 -0.095903 +v 0.041263 -0.020187 -0.095901 +v 0.029180 -0.017371 -0.095897 +v 0.031667 -0.011970 -0.095901 +v 0.036186 -0.010685 -0.095905 +v 0.041253 -0.013427 -0.095883 +v 0.054198 0.003257 -0.095906 +v 0.051451 -0.000191 -0.095906 +v 0.054583 -0.003291 -0.095906 +v 0.057222 0.001689 -0.095906 +v 0.017162 -0.001003 -0.095906 +v 0.019289 -0.002924 -0.095906 +v 0.022798 -0.002704 -0.095906 +v 0.024213 -0.000342 -0.095906 +v 0.018304 0.002604 -0.095906 +v 0.023091 0.002614 -0.095906 +v 0.030374 0.020436 -0.095905 +v 0.029310 0.015368 -0.095890 +v 0.041573 0.014415 -0.095901 +v 0.041369 0.019997 -0.095901 +v 0.037992 0.022872 -0.095905 +v 0.033834 0.023157 -0.095901 +v 0.033711 0.010864 -0.095900 +v 0.038260 0.011217 -0.095904 +v 0.011057 -0.024564 -0.095027 +v 0.011032 -0.024523 -0.090906 +v 0.010677 0.000000 -0.090906 +v 0.010692 0.023373 -0.094915 +v 0.011108 0.024568 -0.090906 +v 0.011654 0.024857 -0.094928 +v 0.025177 0.025000 -0.090906 +v 0.045177 0.025000 -0.090906 +v 0.065765 0.025002 -0.094897 +v 0.025177 -0.025000 -0.090906 +v 0.065778 -0.025006 -0.094883 +v 0.045177 -0.025000 -0.090906 +v 0.057786 0.000358 -0.090906 +v 0.056150 0.002715 -0.090906 +v 0.052749 0.002594 -0.090906 +v 0.051723 -0.001169 -0.090906 +v 0.054489 -0.003124 -0.090906 +v 0.056890 -0.002106 -0.090906 +v 0.018007 0.002493 -0.090906 +v 0.017378 -0.001400 -0.090906 +v 0.020796 -0.003277 -0.090906 +v 0.022550 0.002783 -0.090906 +v 0.024434 -0.000479 -0.090906 +v 0.013495 0.016866 -0.092761 +v 0.014439 0.019275 -0.092744 +v 0.013379 0.017000 -0.090906 +v 0.015102 0.019782 -0.090906 +v 0.017116 0.020174 -0.092751 +v 0.018049 0.019930 -0.090906 +v 0.019047 0.019036 -0.092757 +v 0.019974 0.017000 -0.090906 +v 0.019919 0.016224 -0.092732 +v 0.018251 0.014218 -0.090906 +v 0.017323 0.013877 -0.092752 +v 0.015305 0.014070 -0.090906 +v 0.014671 0.014521 -0.092745 +v 0.051379 0.017000 -0.090906 +v 0.051463 0.016120 -0.092727 +v 0.052976 0.019793 -0.092743 +v 0.053102 0.019782 -0.090906 +v 0.056346 0.019834 -0.090906 +v 0.056410 0.019744 -0.092750 +v 0.057873 0.017045 -0.092753 +v 0.057871 0.015851 -0.090905 +v 0.056802 0.014638 -0.092754 +v 0.053814 0.013771 -0.090906 +v 0.054238 0.013826 -0.092751 +v 0.032379 0.017000 -0.090906 +v 0.032480 0.016953 -0.092753 +v 0.033610 0.019429 -0.092753 +v 0.034102 0.019782 -0.090906 +v 0.036512 0.020120 -0.092743 +v 0.037049 0.019930 -0.090906 +v 0.038908 0.017634 -0.092748 +v 0.038974 0.017000 -0.090906 +v 0.037546 0.014367 -0.092743 +v 0.037251 0.014218 -0.090906 +v 0.034115 0.014108 -0.092748 +v 0.034305 0.014070 -0.090906 +v 0.051531 -0.016430 -0.090906 +v 0.051437 -0.016217 -0.092726 +v 0.053102 -0.014218 -0.090906 +v 0.054031 -0.013877 -0.092752 +v 0.056346 -0.014166 -0.090906 +v 0.057299 -0.014978 -0.092737 +v 0.057493 -0.018496 -0.092752 +v 0.055801 -0.020206 -0.090906 +v 0.055674 -0.019983 -0.092757 +v 0.053023 -0.019811 -0.092743 +v 0.052223 -0.019043 -0.090906 +v 0.032379 -0.017000 -0.090906 +v 0.032768 -0.015780 -0.092753 +v 0.034102 -0.014218 -0.090906 +v 0.034670 -0.013915 -0.092750 +v 0.037049 -0.014070 -0.090906 +v 0.037810 -0.014600 -0.092751 +v 0.038823 -0.016430 -0.090906 +v 0.038854 -0.017907 -0.092736 +v 0.038130 -0.019045 -0.090906 +v 0.035725 -0.020282 -0.092737 +v 0.034814 -0.020229 -0.090906 +v 0.032809 -0.018448 -0.092751 +v 0.013531 -0.016430 -0.090906 +v 0.014119 -0.014943 -0.092744 +v 0.015102 -0.014218 -0.090906 +v 0.017512 -0.013880 -0.092743 +v 0.018049 -0.014070 -0.090906 +v 0.019545 -0.015652 -0.092764 +v 0.019974 -0.017000 -0.090906 +v 0.019571 -0.018378 -0.092742 +v 0.017540 -0.020229 -0.090906 +v 0.017323 -0.020123 -0.092752 +v 0.014042 -0.019001 -0.092725 +v 0.014223 -0.019043 -0.090906 +v 0.026860 -0.008404 -0.092906 +v 0.047565 -0.008924 -0.092906 +v 0.026349 0.007317 -0.092906 +v 0.028299 0.008924 -0.092906 +v 0.048992 0.008415 -0.092906 +v 0.049505 -0.007317 -0.092906 +v 0.053505 0.002805 -0.078790 +v 0.052667 0.002394 -0.093997 +v 0.051673 0.000951 -0.078779 +v 0.051602 -0.000204 -0.093984 +v 0.052127 -0.001668 -0.078795 +v 0.052700 -0.002092 -0.095028 +v 0.053945 -0.003011 -0.078800 +v 0.054965 -0.003116 -0.093985 +v 0.056817 -0.002255 -0.078781 +v 0.057321 -0.001581 -0.093989 +v 0.057735 0.000084 -0.078766 +v 0.057645 0.000765 -0.093967 +v 0.056923 0.002077 -0.078801 +v 0.056473 0.002182 -0.095132 +v 0.055104 0.002842 -0.095051 +v 0.055282 0.002980 -0.078800 +v 0.054401 -0.002770 -0.095153 +v 0.051933 -0.000091 -0.095166 +v 0.053178 0.002331 -0.095206 +v 0.057433 0.000041 -0.095162 +v 0.056608 -0.001930 -0.095140 +v 0.055917 -0.000827 -0.095754 +v 0.053378 0.000383 -0.095779 +v 0.054087 -0.001282 -0.095750 +v 0.055220 0.001164 -0.095771 +v 0.054727 0.000135 -0.095934 +v 0.054708 -0.000750 -0.077923 +v 0.054834 0.000418 -0.077901 +v 0.053135 0.000657 -0.078102 +v 0.053292 -0.001197 -0.078149 +v 0.054306 0.001956 -0.078238 +v 0.055865 0.001274 -0.078135 +v 0.056069 -0.000511 -0.078074 +v 0.055192 -0.002121 -0.078327 +v 0.022346 0.002859 -0.078803 +v 0.021656 0.002806 -0.095052 +v 0.020294 0.002906 -0.093959 +v 0.020444 0.002935 -0.078783 +v 0.018834 0.001974 -0.078787 +v 0.018587 0.001670 -0.093984 +v 0.018112 -0.000374 -0.078799 +v 0.018323 -0.000366 -0.095078 +v 0.019550 -0.002674 -0.093985 +v 0.019085 -0.002202 -0.078807 +v 0.020691 -0.003000 -0.078768 +v 0.022356 -0.002846 -0.093989 +v 0.023148 -0.002417 -0.078782 +v 0.024016 -0.001156 -0.093967 +v 0.024263 0.000625 -0.078794 +v 0.023966 0.000530 -0.095070 +v 0.023135 0.002103 -0.095032 +v 0.018847 -0.001433 -0.095128 +v 0.020757 -0.002759 -0.095181 +v 0.019342 0.002075 -0.095176 +v 0.023388 -0.001637 -0.095160 +v 0.022035 -0.001510 -0.095642 +v 0.022198 0.001232 -0.095700 +v 0.019713 -0.000262 -0.095741 +v 0.022414 -0.000149 -0.095788 +v 0.021091 0.000824 -0.095898 +v 0.020877 -0.000788 -0.095866 +v 0.019471 0.000645 -0.078183 +v 0.020843 0.001680 -0.078120 +v 0.021356 0.000027 -0.077867 +v 0.022399 0.000997 -0.078079 +v 0.022984 -0.000978 -0.078260 +v 0.021395 -0.001491 -0.078079 +v 0.019649 -0.001066 -0.078168 +v 0.056828 -0.018029 -0.095976 +v 0.059332 -0.020952 -0.095836 +v 0.057178 -0.022586 -0.095832 +v 0.060666 -0.015802 -0.095886 +v 0.060422 -0.019201 -0.095894 +v 0.052526 -0.015971 -0.095976 +v 0.048897 -0.018907 -0.095903 +v 0.048596 -0.016091 -0.095862 +v 0.053414 -0.018933 -0.095976 +v 0.054040 -0.023063 -0.095889 +v 0.050900 -0.021891 -0.095818 +v 0.055940 -0.015067 -0.095976 +v 0.056347 -0.011061 -0.095893 +v 0.059231 -0.012925 -0.095813 +v 0.052121 -0.011401 -0.095817 +v 0.049742 -0.013420 -0.095870 +v 0.054367 -0.014408 -0.077975 +v 0.053792 -0.019762 -0.078127 +v 0.056378 -0.019500 -0.078199 +v 0.051934 -0.016752 -0.077952 +v 0.057209 -0.015616 -0.078066 +v 0.056921 -0.019312 -0.092674 +v 0.053510 -0.019899 -0.092668 +v 0.051630 -0.017827 -0.078463 +v 0.051457 -0.017104 -0.092674 +v 0.052379 -0.014943 -0.078472 +v 0.053569 -0.014026 -0.092669 +v 0.054994 -0.013885 -0.078467 +v 0.056349 -0.014430 -0.092675 +v 0.057649 -0.016164 -0.092667 +v 0.057761 -0.016991 -0.078472 +v 0.053414 -0.018933 -0.093676 +v 0.052870 -0.015444 -0.093676 +v 0.056483 -0.018556 -0.093676 +v 0.055940 -0.015067 -0.093676 +v 0.015851 0.020500 0.045928 +v -0.010881 0.020500 0.047432 +v 0.003533 0.020500 0.048536 +v -0.024336 0.020500 0.042142 +v 0.027256 0.020500 0.040316 +v -0.035642 0.020500 0.033134 +v -0.048542 0.020500 -0.003455 +v 0.048734 0.020500 -0.002218 +v 0.046578 0.020500 -0.015619 +v 0.010048 0.020500 -0.047619 +v -0.015015 0.020500 -0.046385 +v 0.026578 0.020500 -0.040987 +v 0.037650 0.020500 0.030820 +v -0.043803 0.020500 0.021201 +v -0.047724 0.020500 0.009110 +v 0.051420 0.020500 -0.000351 +v 0.054530 0.020500 -0.000824 +v 0.063605 0.020500 -0.009666 +v 0.060295 0.020500 -0.009396 +v 0.059960 0.020500 -0.012847 +v 0.061805 0.020500 -0.015319 +v -0.044350 0.020500 -0.020508 +v -0.018503 0.020500 -0.051288 +v 0.000257 0.020500 -0.077138 +v -0.001478 0.020500 -0.079729 +v 0.050856 0.020500 -0.018105 +v 0.042425 0.020500 -0.027224 +v 0.029543 0.020500 -0.041371 +v 0.037053 0.020500 -0.034270 +v 0.031243 0.020500 -0.044046 +v 0.033782 0.020500 -0.042938 +v -0.017703 0.020500 -0.048080 +v -0.004271 0.020500 -0.048479 +v 0.031419 0.020500 -0.052280 +v 0.034609 0.020500 -0.055044 +v 0.036103 0.020500 -0.064193 +v 0.038883 0.020500 -0.063489 +v 0.044233 0.020500 -0.068907 +v 0.043303 0.020500 -0.071624 +v 0.043252 0.020500 -0.075184 +v 0.058666 0.020500 -0.077457 +v 0.040816 0.020500 -0.077311 +v 0.045161 -0.029500 -0.025263 +v 0.050622 -0.029500 -0.018152 +v 0.046571 -0.029500 -0.015425 +v -0.001174 -0.029500 0.048874 +v -0.018760 -0.029500 0.044903 +v 0.014991 -0.029500 0.046216 +v -0.031123 -0.029500 0.037411 +v 0.026397 -0.029500 0.040883 +v 0.036905 -0.029500 0.031694 +v -0.039622 -0.029500 0.028120 +v -0.045629 -0.029500 0.016919 +v -0.048756 -0.029500 0.000926 +v 0.053975 -0.029500 -0.000356 +v 0.048959 -0.029500 -0.001704 +v 0.058955 -0.029500 -0.007527 +v 0.063722 -0.029500 -0.009922 +v -0.045746 -0.029500 -0.016892 +v 0.057617 -0.029500 -0.014281 +v 0.023852 -0.029500 -0.042653 +v 0.061570 -0.029500 -0.015488 +v -0.035393 -0.029500 -0.033744 +v -0.020961 -0.029500 -0.043889 +v 0.007196 -0.029500 -0.048114 +v -0.007484 -0.029500 -0.048097 +v -0.001436 0.025000 -0.079751 +v -0.000548 0.025000 -0.077600 +v 0.007677 0.025000 -0.092406 +v 0.010677 0.025000 -0.082406 +v 0.010677 0.025000 -0.092406 +v 0.064119 0.025000 -0.080625 +v 0.064178 0.025000 -0.082037 +v 0.058628 0.025000 -0.077445 +v 0.064206 0.012000 -0.080698 +v 0.041576 0.012000 -0.066986 +v 0.051572 -0.002000 -0.017912 +v 0.057597 -0.002000 -0.014267 +v 0.046560 -0.002000 -0.014700 +v 0.058974 -0.002000 -0.007523 +v 0.049011 -0.002000 -0.001595 +v 0.053987 -0.002000 -0.000406 +v 0.048586 -0.002000 -0.017536 +v 0.000750 -0.002091 -0.055743 +v 0.007594 -0.002177 -0.067262 +v 0.011546 -0.002071 -0.067369 +v -0.007312 -0.002218 -0.062432 +v 0.000060 -0.002191 -0.072041 +v 0.000688 -0.002179 -0.051468 +v 0.013918 -0.002089 -0.049772 +v 0.040225 -0.002029 -0.073920 +v 0.016850 -0.002269 -0.075077 +v 0.031021 -0.002180 -0.059752 +v 0.027313 -0.002055 -0.043914 +v 0.036075 -0.002162 -0.068360 +v 0.000587 -0.025000 -0.077159 +v 0.001241 -0.013744 -0.077263 +v -0.000164 -0.013299 -0.076349 +v -0.018794 -0.025000 -0.050518 +v -0.001423 -0.012348 -0.074299 +v -0.018409 -0.013529 -0.051321 +v -0.009841 -0.012244 -0.062753 +v -0.009316 -0.004411 -0.063648 +v -0.001880 -0.004880 -0.073883 +v 0.018075 -0.004706 -0.045257 +v 0.026567 -0.004796 -0.040942 +v 0.026416 -0.025000 -0.040836 +v 0.009353 -0.004943 -0.047766 +v 0.000527 -0.013289 -0.048633 +v 0.000894 -0.004894 -0.048649 +v -0.006398 -0.012759 -0.048341 +v -0.014752 -0.013343 -0.046484 +v -0.015387 -0.025000 -0.046338 +v -0.033988 -0.025000 -0.035224 +v -0.017538 -0.013525 -0.047937 +v 0.083966 -0.012000 -0.051527 +v 0.084399 0.012000 -0.049339 +v 0.083350 -0.012000 -0.040165 +v 0.082434 0.012000 -0.038131 +v 0.073813 0.012000 -0.079141 +v 0.074166 -0.012000 -0.078654 +v 0.063614 -0.012000 -0.009381 +v 0.063732 0.012000 -0.009824 +v 0.063839 -0.012000 -0.082245 +v 0.064066 0.012000 -0.082082 +v 0.063440 -0.025000 -0.082288 +v 0.010677 -0.025000 -0.092406 +v 0.010677 -0.025000 -0.082406 +v 0.007677 -0.025000 -0.092406 +v 0.034920 -0.025000 -0.038467 +v 0.040992 -0.025000 -0.028739 +v 0.030824 -0.025000 -0.042302 +v 0.043434 -0.025000 -0.075033 +v 0.040664 -0.025000 -0.077316 +v 0.044468 -0.025000 -0.069065 +v 0.043050 -0.025000 -0.071292 +v 0.064489 -0.025000 -0.081190 +v 0.037629 -0.025000 -0.061970 +v 0.037020 -0.025000 -0.065300 +v 0.033689 -0.025000 -0.050493 +v 0.031592 -0.025000 -0.053705 +v 0.043340 0.012000 -0.026494 +v 0.036640 0.012000 -0.034754 +v 0.033613 0.012000 -0.045084 +v 0.034836 0.012000 -0.055779 +v 0.061570 0.012000 -0.015488 +v 0.045826 0.012000 -0.056965 +v 0.043071 0.012000 -0.048802 +v 0.054025 0.012000 -0.064003 +v 0.064757 0.012000 -0.064589 +v 0.073275 0.012000 -0.059924 +v 0.078202 0.012000 -0.050307 +v 0.077031 0.012000 -0.040738 +v 0.044505 0.012000 -0.040307 +v 0.070266 0.012000 -0.032314 +v 0.059824 0.012000 -0.029765 +v 0.050593 0.012000 -0.032786 +v 0.044401 -0.012000 -0.069050 +v 0.037202 -0.012000 -0.061271 +v 0.033613 -0.012000 -0.049727 +v 0.035609 -0.012000 -0.036378 +v 0.043478 -0.012000 -0.026448 +v 0.061805 -0.012000 -0.015319 +v 0.064340 -0.012000 -0.080897 +v 0.071276 -0.012000 -0.061442 +v 0.064456 -0.012000 -0.064662 +v 0.076240 -0.012000 -0.055763 +v 0.055842 -0.012000 -0.064397 +v 0.076124 -0.012000 -0.039111 +v 0.078408 -0.012000 -0.046312 +v 0.047549 -0.012000 -0.059374 +v 0.049898 -0.012000 -0.033133 +v 0.043843 -0.012000 -0.042051 +v 0.060133 -0.012000 -0.029749 +v 0.070556 -0.012000 -0.032497 +v 0.043312 -0.012000 -0.050652 +v 0.043116 -0.027300 -0.045231 +v 0.045915 -0.027300 -0.037853 +v 0.051247 -0.027300 -0.032474 +v 0.061226 -0.027300 -0.029585 +v 0.071008 -0.027300 -0.033083 +v 0.075593 -0.027300 -0.038170 +v 0.078103 -0.027300 -0.044542 +v 0.077198 -0.027300 -0.053806 +v 0.071341 -0.027300 -0.061527 +v 0.061910 -0.027300 -0.065122 +v 0.050828 -0.027300 -0.062269 +v 0.044353 -0.027300 -0.054145 +v 0.077802 0.027300 -0.051814 +v 0.072801 0.027300 -0.060384 +v 0.061985 0.027300 -0.065238 +v 0.050593 0.027300 -0.062026 +v 0.043537 0.027300 -0.052499 +v 0.043692 0.027300 -0.042853 +v 0.047777 0.027300 -0.035199 +v 0.056142 0.027300 -0.030337 +v 0.066942 0.027300 -0.030659 +v 0.075269 0.027300 -0.037456 +v 0.077986 0.027300 -0.044338 +v 0.020543 0.004236 -0.044243 +v 0.026461 0.004720 -0.041007 +v 0.011919 0.004991 -0.047182 +v 0.002931 0.004915 -0.048530 +v -0.004116 0.004873 -0.048451 +v -0.014300 0.004794 -0.046623 +v 0.042667 0.004436 -0.071159 +v 0.038728 0.004859 -0.067357 +v 0.035457 0.004529 -0.063036 +v 0.033099 0.004929 -0.058307 +v 0.031148 0.004925 -0.050511 +v 0.031083 0.004741 -0.043832 +v 0.029399 0.005016 -0.041394 +v -0.016248 0.004826 -0.046898 +v -0.018139 0.004632 -0.049164 +v -0.018191 0.005404 -0.051884 +v -0.000146 0.004415 -0.076245 +v 0.001222 0.004854 -0.077192 +v 0.040913 0.005049 -0.077188 +v 0.042683 0.004792 -0.075781 +v 0.043543 0.004943 -0.073072 +v 0.036753 0.002122 -0.069209 +v 0.040313 0.002073 -0.074277 +v 0.001985 0.002062 -0.074192 +v 0.029505 0.002071 -0.057970 +v -0.005306 0.002094 -0.051335 +v 0.013626 0.002130 -0.049608 +v -0.015080 0.002088 -0.049436 +v 0.027609 0.002097 -0.043619 +v 0.048694 0.002000 -0.002515 +v 0.046525 0.002000 -0.014395 +v 0.048445 0.002000 -0.017512 +v 0.051656 0.002000 -0.017878 +v 0.059834 0.002000 -0.012947 +v 0.060388 0.002000 -0.009666 +v 0.054986 0.002000 -0.001244 +v 0.051523 0.002000 -0.000180 +v 0.031069 -0.004932 -0.043668 +v 0.031644 -0.005225 -0.053272 +v 0.033420 -0.004435 -0.059320 +v 0.035887 -0.004809 -0.063737 +v 0.038853 -0.004826 -0.067504 +v 0.042817 -0.004702 -0.071242 +v 0.043498 -0.005153 -0.072791 +v 0.043317 -0.005334 -0.074810 +v 0.042136 -0.004793 -0.076366 +v 0.040440 -0.004411 -0.077133 +v 0.016208 -0.013366 -0.077300 +v 0.016715 -0.004546 -0.077194 +v 0.029434 -0.005237 -0.041468 +v -0.009515 -0.004840 -0.061531 +v -0.008535 -0.004880 -0.059778 +v -0.008611 -0.010546 -0.059733 +v -0.002001 -0.010500 -0.054564 +v -0.001861 -0.004985 -0.053995 +v -0.002089 -0.010608 -0.051525 +v -0.002036 -0.005091 -0.051836 +v -0.001036 -0.005053 -0.049691 +v -0.001037 -0.011600 -0.049724 +v -0.002340 -0.004903 -0.055124 +v -0.015621 -0.010580 -0.050289 +v 0.009962 -0.005204 -0.070158 +v 0.009044 -0.010500 -0.069610 +v 0.014915 -0.005367 -0.076695 +v 0.013801 -0.010921 -0.075529 +v 0.001576 -0.010640 -0.074357 +v 0.001326 -0.005047 -0.074406 +v 0.008385 -0.005325 -0.069690 +v 0.041692 0.002800 -0.074814 +v 0.041272 0.002433 -0.072465 +v 0.042863 0.003589 -0.073859 +v 0.040221 0.003404 -0.076454 +v 0.030824 0.003307 -0.054179 +v 0.037913 0.003165 -0.068043 +v 0.033284 0.002754 -0.062255 +v 0.029437 0.002459 -0.053146 +v 0.029389 0.002634 -0.043581 +v 0.001365 0.002801 -0.075741 +v 0.026980 0.003094 -0.041997 +v 0.011109 0.003353 -0.048266 +v 0.001752 0.002763 -0.050039 +v -0.006646 0.003168 -0.049325 +v -0.015335 0.002977 -0.047792 +v -0.017611 0.003631 -0.051574 +v -0.016555 0.002490 -0.050463 +v 0.040959 -0.002710 -0.075451 +v 0.041580 -0.002596 -0.072325 +v 0.042516 -0.003189 -0.073826 +v 0.015315 -0.003347 -0.075813 +v 0.030721 -0.003718 -0.051862 +v 0.030327 -0.003455 -0.043718 +v 0.035642 -0.003165 -0.065220 +v 0.029373 -0.002470 -0.051856 +v 0.028540 -0.002207 -0.043904 +v 0.010122 -0.003156 -0.068895 +v 0.026708 -0.002885 -0.042302 +v 0.028495 -0.003589 -0.041781 +v 0.007752 -0.003986 -0.069433 +v 0.017406 -0.002791 -0.046967 +v 0.000826 -0.003134 -0.049798 +v 0.007811 -0.003076 -0.049193 +v 0.001423 -0.003359 -0.073387 +v -0.000905 -0.003220 -0.054979 +v -0.001107 -0.003340 -0.051476 +v -0.001059 -0.003273 -0.073288 +v -0.008051 -0.003014 -0.061063 +v 0.001255 -0.011474 -0.076048 +v -0.017259 -0.011861 -0.051742 +v -0.015278 -0.011542 -0.047679 +v -0.017355 -0.011840 -0.049530 +v -0.014984 -0.010802 -0.048883 +v 0.022550 0.018696 -0.095821 +v 0.022508 0.015039 -0.095882 +v 0.018828 0.015971 -0.095976 +v 0.011805 0.013126 -0.095870 +v 0.010565 0.017116 -0.095828 +v 0.014526 0.018029 -0.095976 +v 0.015414 0.015067 -0.095976 +v 0.015623 0.010960 -0.095882 +v 0.011348 0.019940 -0.095903 +v 0.019713 0.011588 -0.095816 +v 0.017002 0.023092 -0.095835 +v 0.017940 0.018933 -0.095976 +v 0.020499 0.021898 -0.095900 +v 0.013368 0.022202 -0.095833 +v 0.014613 0.018950 -0.078033 +v 0.016366 0.014128 -0.078111 +v 0.018845 0.015472 -0.077969 +v 0.013741 0.016823 -0.078155 +v 0.019404 0.018025 -0.078131 +v 0.016363 0.019853 -0.078126 +v 0.019735 0.016286 -0.092671 +v 0.019137 0.015021 -0.078463 +v 0.017535 0.013971 -0.092668 +v 0.014502 0.014742 -0.092674 +v 0.014620 0.014702 -0.078472 +v 0.013621 0.017095 -0.092672 +v 0.014633 0.019376 -0.092674 +v 0.017333 0.020022 -0.092673 +v 0.018211 0.019676 -0.078472 +v 0.019165 0.018777 -0.092672 +v 0.015414 0.015067 -0.093676 +v 0.014870 0.018556 -0.093676 +v 0.018483 0.015444 -0.093676 +v 0.017940 0.018933 -0.093676 +v 0.056828 0.015971 -0.095976 +v 0.060666 0.018198 -0.095886 +v 0.060351 0.014577 -0.095848 +v 0.049583 0.020374 -0.095884 +v 0.051653 0.022278 -0.095872 +v 0.052526 0.018029 -0.095976 +v 0.053414 0.015067 -0.095976 +v 0.052353 0.011357 -0.095895 +v 0.050218 0.012820 -0.095869 +v 0.048814 0.015296 -0.095794 +v 0.048678 0.018044 -0.095860 +v 0.055940 0.018933 -0.095976 +v 0.054625 0.023145 -0.095848 +v 0.058764 0.021656 -0.095842 +v 0.057615 0.011616 -0.095893 +v 0.055278 0.010932 -0.095802 +v 0.055564 0.014278 -0.078133 +v 0.057279 0.016626 -0.077971 +v 0.053620 0.014360 -0.078032 +v 0.052639 0.019109 -0.078163 +v 0.051842 0.017296 -0.078084 +v 0.055970 0.019316 -0.077969 +v 0.057067 0.014845 -0.092661 +v 0.057287 0.015316 -0.078470 +v 0.054120 0.013982 -0.092674 +v 0.051731 0.015748 -0.092669 +v 0.051951 0.015601 -0.078473 +v 0.052470 0.019270 -0.092672 +v 0.054830 0.020103 -0.078470 +v 0.055333 0.020022 -0.092673 +v 0.057486 0.018443 -0.078463 +v 0.057529 0.018304 -0.092674 +v 0.053414 0.015067 -0.093676 +v 0.052870 0.018556 -0.093676 +v 0.056483 0.015444 -0.093676 +v 0.055940 0.018933 -0.093676 +v 0.041466 0.018923 -0.095835 +v 0.041700 0.015801 -0.095857 +v 0.037828 0.015971 -0.095976 +v 0.033526 0.018029 -0.095976 +v 0.029919 0.014893 -0.095882 +v 0.029801 0.018853 -0.095830 +v 0.031804 0.021726 -0.095884 +v 0.034898 0.023080 -0.095860 +v 0.034414 0.015067 -0.095976 +v 0.032167 0.011932 -0.095856 +v 0.039619 0.012203 -0.095879 +v 0.035604 0.010882 -0.095836 +v 0.036940 0.018933 -0.095976 +v 0.039091 0.022185 -0.095854 +v 0.036704 0.019400 -0.077975 +v 0.036654 0.014559 -0.077971 +v 0.038597 0.017043 -0.078129 +v 0.034642 0.014319 -0.078141 +v 0.033016 0.015671 -0.078184 +v 0.033874 0.018945 -0.077969 +v 0.038650 0.016216 -0.092672 +v 0.037279 0.014246 -0.078457 +v 0.036654 0.013952 -0.092669 +v 0.033212 0.015013 -0.092672 +v 0.032813 0.018307 -0.092668 +v 0.032856 0.018246 -0.078472 +v 0.034715 0.019930 -0.078472 +v 0.035209 0.020072 -0.092676 +v 0.037509 0.019539 -0.078467 +v 0.038109 0.019041 -0.092668 +v 0.035232 0.014657 -0.093676 +v 0.033870 0.018556 -0.093676 +v 0.037928 0.017786 -0.093676 +v 0.018828 -0.018029 -0.095976 +v 0.020979 -0.021379 -0.095836 +v 0.017742 -0.023053 -0.095870 +v 0.021958 -0.013927 -0.095877 +v 0.022853 -0.017439 -0.095833 +v 0.014526 -0.015971 -0.095976 +v 0.010644 -0.017782 -0.095825 +v 0.010862 -0.015059 -0.095879 +v 0.017940 -0.015067 -0.095976 +v 0.016627 -0.010886 -0.095886 +v 0.019593 -0.011605 -0.095848 +v 0.014144 -0.022574 -0.095893 +v 0.011787 -0.020683 -0.095838 +v 0.015414 -0.018933 -0.095976 +v 0.013132 -0.011971 -0.095859 +v 0.019014 -0.015387 -0.078033 +v 0.017476 -0.019737 -0.078082 +v 0.019561 -0.017269 -0.078164 +v 0.014889 -0.019355 -0.078133 +v 0.014340 -0.015203 -0.078130 +v 0.016088 -0.014414 -0.077969 +v 0.019383 -0.018447 -0.092674 +v 0.018747 -0.019286 -0.078472 +v 0.016978 -0.020187 -0.092669 +v 0.013649 -0.018124 -0.092670 +v 0.013575 -0.017172 -0.078470 +v 0.014388 -0.014921 -0.092673 +v 0.016994 -0.013885 -0.078467 +v 0.017407 -0.013875 -0.092665 +v 0.019649 -0.016150 -0.092673 +v 0.014426 -0.017786 -0.093676 +v 0.017121 -0.014657 -0.093676 +v 0.018483 -0.018556 -0.093676 +v 0.029796 -0.018764 -0.095871 +v 0.029809 -0.015332 -0.095842 +v 0.033710 -0.018348 -0.095976 +v 0.037828 -0.018029 -0.095976 +v 0.040485 -0.020778 -0.095908 +v 0.037930 -0.022721 -0.095862 +v 0.035225 -0.023068 -0.095854 +v 0.032113 -0.022023 -0.095830 +v 0.035493 -0.014623 -0.095976 +v 0.037826 -0.011319 -0.095856 +v 0.040673 -0.013347 -0.095834 +v 0.041820 -0.017505 -0.095856 +v 0.034682 -0.010931 -0.095820 +v 0.031832 -0.012146 -0.095911 +v 0.035658 -0.014166 -0.078016 +v 0.035841 -0.019869 -0.078114 +v 0.038073 -0.018677 -0.078086 +v 0.033388 -0.018207 -0.077974 +v 0.032722 -0.016823 -0.078150 +v 0.037824 -0.015012 -0.078157 +v 0.037557 -0.019488 -0.092671 +v 0.035120 -0.020018 -0.092674 +v 0.033845 -0.019539 -0.078467 +v 0.033028 -0.018646 -0.092671 +v 0.032885 -0.015506 -0.092672 +v 0.033829 -0.014473 -0.078467 +v 0.035576 -0.013884 -0.092671 +v 0.038235 -0.015188 -0.092674 +v 0.038737 -0.017152 -0.078473 +v 0.038681 -0.017496 -0.092671 +v 0.033426 -0.017786 -0.093676 +v 0.034634 -0.014939 -0.093676 +v 0.036720 -0.019061 -0.093676 +v 0.037928 -0.016214 -0.093676 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.0070 -0.0000 1.0000 +vn 0.0033 -0.0009 1.0000 +vn 0.1982 -0.0014 0.9802 +vn 0.2087 0.0012 0.9780 +vn 0.3877 -0.0006 0.9218 +vn 0.4072 0.0012 0.9133 +vn -0.0116 -0.0033 -0.9999 +vn -0.0565 -0.0173 -0.9983 +vn -0.1093 -0.0327 -0.9935 +vn -0.0002 -0.0006 -1.0000 +vn -0.0004 0.0025 -1.0000 +vn -0.0016 0.0001 -1.0000 +vn -0.0001 0.0012 -1.0000 +vn -0.0091 0.0584 -0.9983 +vn -0.0108 0.0647 -0.9978 +vn -0.0023 0.0261 -0.9997 +vn -0.0008 0.0000 -1.0000 +vn 0.0001 0.0009 -1.0000 +vn -0.0009 0.0011 -1.0000 +vn -0.0011 0.0004 -1.0000 +vn -0.0005 -0.0007 -1.0000 +vn -0.0000 -0.0010 -1.0000 +vn 0.0004 -0.0075 -1.0000 +vn -0.0315 -0.0768 -0.9965 +vn -0.0136 -0.0370 -0.9992 +vn -0.0021 0.0016 -1.0000 +vn -0.0424 -0.1006 -0.9940 +vn 0.0004 -0.0009 -1.0000 +vn 0.0131 -0.0004 -0.9999 +vn 0.0003 -0.0004 -1.0000 +vn -0.0001 0.0004 -1.0000 +vn -0.0006 0.0007 -1.0000 +vn 0.0042 0.0003 -1.0000 +vn 0.0015 0.0077 -1.0000 +vn 0.0033 0.0019 -1.0000 +vn 0.0019 -0.0004 -1.0000 +vn -0.0078 0.0045 -1.0000 +vn 0.0006 0.0008 -1.0000 +vn 0.0004 0.0003 -1.0000 +vn -0.0004 -0.0023 -1.0000 +vn 0.0004 -0.0006 -1.0000 +vn -0.0004 -0.0011 -1.0000 +vn 0.0020 -0.0003 -1.0000 +vn -0.0022 -0.3689 -0.9295 +vn -0.0024 0.0036 -1.0000 +vn -0.0126 -0.0064 -0.9999 +vn -0.0029 -0.0044 -1.0000 +vn 0.0046 -0.0001 -1.0000 +vn 0.0048 0.0034 -1.0000 +vn -0.0008 -0.0034 -1.0000 +vn 0.0129 -0.3845 -0.9230 +vn 0.0057 0.0060 -1.0000 +vn -0.0002 0.0076 -1.0000 +vn 0.0004 0.0006 -1.0000 +vn 0.0004 0.0018 -1.0000 +vn 0.0022 0.0001 -1.0000 +vn -0.0000 -0.0014 -1.0000 +vn 0.0001 -0.0016 -1.0000 +vn -0.0013 -0.0026 -1.0000 +vn 0.0003 0.0004 -1.0000 +vn -0.0325 0.0081 -0.9994 +vn -0.3917 0.4846 -0.7821 +vn -0.0008 -0.0011 -1.0000 +vn 0.0034 0.0004 -1.0000 +vn -0.0005 0.0004 -1.0000 +vn -0.0004 -0.0006 -1.0000 +vn -0.0005 0.0034 -1.0000 +vn 0.0001 -0.0043 -1.0000 +vn -0.0001 0.0022 -1.0000 +vn -0.0005 -0.0013 -1.0000 +vn -0.9576 -0.0261 -0.2868 +vn -0.9999 -0.0145 -0.0059 +vn -0.9993 -0.0065 -0.0374 +vn -0.8923 0.1092 -0.4380 +vn -0.9950 0.0175 0.0980 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn -0.0256 0.9983 0.0517 +vn -0.0306 0.9972 0.0675 +vn -0.0028 0.9997 -0.0260 +vn -0.0024 0.9999 -0.0133 +vn -0.0001 1.0000 -0.0010 +vn 0.0001 1.0000 0.0006 +vn 0.0004 1.0000 0.0009 +vn -0.0030 -0.9955 -0.0949 +vn -0.0337 -0.9994 0.0097 +vn -0.0283 -0.9996 -0.0060 +vn -0.0006 -1.0000 -0.0033 +vn 0.0002 -1.0000 0.0017 +vn -0.0072 -0.9992 -0.0398 +vn 0.0011 -1.0000 0.0027 +vn -0.8371 0.5420 -0.0747 +vn -0.0021 -0.7396 -0.6731 +vn -0.0021 -0.7409 -0.6716 +vn -0.0001 -0.7595 -0.6506 +vn -0.0297 -0.7086 -0.7050 +vn -0.0373 -0.7345 -0.6776 +vn -0.6653 0.2347 -0.7087 +vn -0.7345 0.0018 -0.6786 +vn -0.9446 -0.0067 -0.3282 +vn -0.8249 -0.0179 -0.5650 +vn -0.6884 -0.0007 -0.7253 +vn -0.6659 0.0005 -0.7461 +vn -0.7081 -0.0466 -0.7046 +vn -0.6581 0.4213 -0.6240 +vn -0.0003 0.7498 -0.6617 +vn -0.0099 0.6733 -0.7393 +vn -0.0093 0.6777 -0.7353 +vn 0.0000 0.7094 -0.7048 +vn -0.0015 0.7231 -0.6908 +vn -0.0001 0.7106 -0.7036 +vn 0.6491 -0.0000 -0.7607 +vn 0.6406 0.0003 -0.7679 +vn 0.6492 -0.0000 -0.7606 +vn 0.6403 0.0003 -0.7681 +vn 0.9999 -0.0012 0.0135 +vn 0.9998 0.0003 -0.0210 +vn 0.9998 0.0002 -0.0200 +vn 0.9999 -0.0013 0.0145 +vn -0.9805 -0.1869 0.0607 +vn -0.8816 -0.4713 -0.0260 +vn -0.8066 -0.5886 0.0533 +vn -0.7189 -0.6950 -0.0115 +vn -0.4587 -0.8847 0.0832 +vn 0.0353 -0.9920 -0.1213 +vn 0.7741 -0.6168 0.1426 +vn 0.9029 -0.4298 0.0050 +vn 0.8734 -0.4851 0.0434 +vn 0.9596 -0.2616 -0.1034 +vn 0.6999 0.7071 0.1002 +vn 0.6358 0.7710 0.0365 +vn 0.6566 0.7521 0.0564 +vn 0.5771 0.8165 -0.0164 +vn -0.5498 0.8334 0.0562 +vn -0.3901 0.9200 -0.0381 +vn -0.4846 0.8746 0.0163 +vn -0.6117 0.7852 0.0962 +vn -0.9378 0.3407 -0.0665 +vn 0.9522 -0.3015 0.0499 +vn 0.9758 -0.2185 -0.0121 +vn 0.9702 -0.2424 0.0055 +vn 0.9857 -0.1593 -0.0552 +vn 0.6700 0.7418 0.0300 +vn 0.5453 0.8369 -0.0467 +vn 0.5991 0.8005 -0.0150 +vn 0.4799 0.8734 -0.0827 +vn 0.0021 -0.9998 -0.0221 +vn 0.0310 -0.9995 0.0074 +vn 0.0338 -0.9994 0.0102 +vn 0.0637 -0.9971 0.0406 +vn -0.7612 0.6473 -0.0390 +vn -0.6026 0.7835 -0.1515 +vn -0.6966 0.7120 -0.0889 +vn -0.8567 0.5132 0.0519 +vn -0.9346 -0.3544 0.0316 +vn -0.8928 -0.4488 -0.0378 +vn -0.9096 -0.4152 -0.0125 +vn -0.8634 -0.4985 -0.0769 +vn -0.0619 0.9941 0.0890 +vn 0.9275 -0.3643 0.0840 +vn 0.8769 -0.4738 -0.0807 +vn 0.9026 -0.4304 -0.0122 +vn 0.8393 -0.5198 -0.1594 +vn 0.3153 -0.9378 0.1450 +vn 0.1495 -0.9877 -0.0467 +vn 0.2195 -0.9751 0.0324 +vn 0.0495 -0.9866 -0.1555 +vn -0.5023 -0.8531 0.1412 +vn -0.8793 -0.4700 -0.0766 +vn -0.9201 -0.3903 0.0321 +vn -0.8218 -0.5399 -0.1823 +vn -0.9444 -0.2915 0.1523 +vn -0.8339 0.5165 -0.1944 +vn -0.7968 0.6003 -0.0684 +vn -0.7305 0.6784 0.0780 +vn -0.6584 0.7265 0.1968 +vn -0.0495 0.9863 -0.1573 +vn 0.0555 0.9975 -0.0436 +vn 0.1268 0.9913 0.0350 +vn 0.2335 0.9599 0.1549 +vn 0.8504 0.5167 -0.0990 +vn 0.8714 0.4884 -0.0462 +vn 0.8260 0.5429 -0.1516 +vn 0.8936 0.4483 0.0235 +vn 0.4607 -0.4907 -0.7395 +vn 0.6981 0.0448 -0.7146 +vn 0.6841 -0.2382 -0.6894 +vn 0.7178 0.1900 -0.6698 +vn 0.6020 0.2966 -0.7413 +vn 0.2485 0.7255 -0.6417 +vn 0.2176 0.7172 -0.6620 +vn 0.2188 0.7175 -0.6612 +vn 0.1687 0.7021 -0.6918 +vn -0.4372 0.5969 -0.6727 +vn -0.4486 0.5634 -0.6938 +vn -0.4488 0.5626 -0.6942 +vn -0.4625 0.5177 -0.7198 +vn -0.7827 -0.0145 -0.6222 +vn -0.7251 -0.1014 -0.6811 +vn -0.6349 -0.3288 -0.6992 +vn -0.5226 -0.4421 -0.7290 +vn -0.1947 -0.6843 -0.7027 +vn -0.0810 -0.6712 -0.7368 +vn 0.2890 -0.6546 -0.6986 +vn 0.8973 -0.4162 0.1472 +vn 0.9022 -0.3707 0.2207 +vn 0.8765 -0.4803 0.0317 +vn 0.8486 -0.5255 -0.0614 +vn 0.0160 -0.9998 -0.0071 +vn 0.0060 -0.9999 0.0114 +vn -0.0048 -0.9995 0.0311 +vn -0.0142 -0.9987 0.0483 +vn -0.8967 -0.4343 -0.0855 +vn -0.8791 -0.4765 -0.0073 +vn -0.9077 -0.3827 -0.1722 +vn -0.9097 -0.3484 -0.2261 +vn -0.8839 0.3932 0.2531 +vn -0.4058 0.8811 -0.2428 +vn -0.3606 0.9204 -0.1513 +vn -0.4345 0.8475 -0.3048 +vn -0.3015 0.9526 -0.0412 +vn 0.6886 0.7238 0.0441 +vn 0.6291 0.7592 0.1669 +vn 0.7520 0.6441 -0.1399 +vn 0.7738 0.5835 -0.2463 +vn 0.7269 0.2563 -0.6371 +vn 0.5594 0.4458 -0.6988 +vn 0.5255 0.4545 -0.7192 +vn 0.4069 0.5636 -0.7188 +vn 0.4597 0.5632 -0.6866 +vn -0.2273 0.7227 -0.6527 +vn -0.2279 0.7219 -0.6534 +vn -0.2289 0.7204 -0.6547 +vn -0.6173 0.2750 -0.7371 +vn -0.6963 -0.0034 -0.7177 +vn -0.7332 0.1695 -0.6585 +vn -0.6661 -0.2807 -0.6910 +vn -0.3479 -0.5679 -0.7460 +vn -0.1489 -0.6981 -0.7004 +vn 0.0781 -0.7039 -0.7060 +vn 0.1623 -0.7342 -0.6592 +vn 0.6303 -0.3676 -0.6838 +vn 0.6252 -0.3175 -0.7129 +vn 0.6251 -0.3160 -0.7138 +vn 0.6166 -0.2572 -0.7441 +vn 0.8888 -0.4581 -0.0109 +vn 0.9081 -0.4144 0.0602 +vn 0.8690 -0.4904 -0.0657 +vn 0.8435 -0.5223 -0.1253 +vn 0.1683 -0.9849 0.0396 +vn 0.2295 -0.9655 0.1234 +vn 0.1146 -0.9929 -0.0323 +vn 0.0498 -0.9919 -0.1172 +vn -0.7573 -0.6513 0.0475 +vn -0.7131 -0.6875 0.1373 +vn -0.8017 -0.5937 -0.0691 +vn -0.8253 -0.5425 -0.1568 +vn -0.9000 0.4269 0.0877 +vn -0.9105 0.3798 0.1634 +vn -0.8759 0.4823 -0.0104 +vn -0.8464 0.5242 -0.0934 +vn -0.0678 0.9962 0.0551 +vn -0.0752 0.9948 0.0686 +vn -0.0592 0.9974 0.0413 +vn -0.0502 0.9984 0.0258 +vn 0.8448 0.5335 -0.0414 +vn 0.8572 0.5150 -0.0015 +vn 0.8333 0.5477 -0.0751 +vn 0.8665 0.4980 0.0347 +vn 0.6621 0.0125 -0.7493 +vn 0.5677 0.4563 -0.6852 +vn 0.6761 0.1901 -0.7118 +vn 0.5548 0.5435 -0.6299 +vn -0.0537 0.7003 -0.7118 +vn -0.0517 0.6992 -0.7130 +vn -0.3661 0.5449 -0.7543 +vn -0.2730 0.6499 -0.7093 +vn -0.6572 0.2735 -0.7024 +vn -0.6999 0.1116 -0.7055 +vn -0.7775 -0.0284 -0.6282 +vn -0.4763 -0.5154 -0.7124 +vn -0.4894 -0.4702 -0.7344 +vn -0.1941 -0.6321 -0.7502 +vn -0.2771 -0.6568 -0.7013 +vn 0.2064 -0.6774 -0.7060 +vn 0.4310 -0.5069 -0.7466 +vn 0.6101 -0.3793 -0.6956 +vn 0.8103 -0.5757 -0.1095 +vn 0.7648 -0.6442 0.0079 +vn 0.7151 -0.6911 0.1050 +vn 0.6578 -0.7270 0.1967 +vn 0.0158 -0.9846 -0.1739 +vn -0.3105 -0.9183 0.2456 +vn -0.8572 -0.4531 -0.2447 +vn -0.9691 -0.0545 0.2405 +vn -0.8091 0.5329 -0.2479 +vn -0.7735 0.6191 -0.1355 +vn -0.7277 0.6851 -0.0324 +vn -0.6273 0.7669 0.1354 +vn 0.2362 0.9599 -0.1508 +vn 0.1619 0.9863 -0.0328 +vn 0.0649 0.9912 0.1150 +vn 0.2990 0.9198 -0.2543 +vn 0.9198 0.3586 0.1595 +vn 0.8920 0.3925 0.2243 +vn 0.9467 0.3128 0.0768 +vn 0.9665 0.2560 -0.0200 +vn 0.6950 0.1924 -0.6928 +vn 0.6500 0.2337 -0.7231 +vn 0.5813 0.3982 -0.7096 +vn 0.3707 0.5381 -0.7570 +vn 0.1202 0.7042 -0.6997 +vn -0.2065 0.6474 -0.7336 +vn -0.4479 0.5611 -0.6961 +vn -0.6059 0.2811 -0.7442 +vn -0.7065 0.0273 -0.7072 +vn -0.5155 -0.3966 -0.7596 +vn -0.5679 -0.4557 -0.6855 +vn -0.1359 -0.6934 -0.7076 +vn 0.1347 -0.6399 -0.7566 +vn 0.4174 -0.5795 -0.7000 +vn 0.5495 -0.4476 -0.7055 +vn 0.6519 -0.3943 -0.6477 +vn 0.8383 -0.5192 -0.1664 +vn 0.8015 -0.5930 -0.0770 +vn 0.7638 -0.6454 -0.0058 +vn 0.6970 -0.7104 0.0976 +vn 0.0496 -0.9878 -0.1475 +vn -0.0440 -0.9987 -0.0272 +vn -0.1252 -0.9890 0.0783 +vn -0.2092 -0.9594 0.1893 +vn -0.8670 -0.4979 -0.0178 +vn -0.9094 -0.4042 0.0980 +vn -0.7897 -0.5936 -0.1552 +vn -0.9304 -0.2927 0.2205 +vn -0.9434 0.2500 -0.2178 +vn -0.5857 0.7716 0.2481 +vn -0.3301 0.9244 -0.1910 +vn 0.5170 0.8237 0.2329 +vn 0.7676 0.5788 -0.2754 +vn 0.9764 0.0149 0.2155 +vn 0.7140 0.0302 -0.6995 +vn 0.5772 0.3243 -0.7494 +vn 0.4309 0.5705 -0.6991 +vn 0.2729 0.6506 -0.7087 +vn 0.1846 0.7372 -0.6499 +vn -0.4103 0.5838 -0.7006 +vn -0.4147 0.5707 -0.7088 +vn -0.4149 0.5701 -0.7091 +vn -0.4202 0.5539 -0.7188 +vn -0.7956 0.0004 -0.6059 +vn -0.7332 -0.0815 -0.6751 +vn -0.7239 -0.0926 -0.6837 +vn -0.6213 -0.1996 -0.7577 +vn -0.3604 -0.6713 -0.6477 +vn -0.2593 -0.6688 -0.6967 +vn -0.0780 -0.7156 -0.6942 +vn 0.1828 -0.6379 -0.7481 +vn 0.4656 -0.5494 -0.6938 +vn 0.6288 -0.2670 -0.7303 +vn 0.7982 -0.5672 -0.2030 +vn 0.2213 -0.9687 0.1121 +vn 0.2921 -0.9327 0.2117 +vn 0.1391 -0.9903 0.0003 +vn 0.0498 -0.9919 -0.1171 +vn -0.7320 -0.6812 -0.0093 +vn -0.6522 -0.7496 0.1131 +vn -0.7795 -0.6182 -0.1013 +vn -0.8187 -0.5379 -0.2012 +vn -0.9755 -0.0072 0.2199 +vn -0.7697 0.5802 -0.2665 +vn -0.7415 0.6505 -0.1645 +vn -0.6865 0.7267 -0.0271 +vn -0.6094 0.7843 0.1163 +vn 0.3279 0.9447 0.0071 +vn 0.3236 0.9460 0.0163 +vn 0.3326 0.9431 -0.0030 +vn 0.3367 0.9416 -0.0118 +vn 0.9628 0.2550 -0.0899 +vn 0.9863 0.1532 0.0606 +vn 0.9798 0.0597 0.1908 +vn 0.9562 -0.0168 0.2923 +vn 0.6892 0.0375 -0.7236 +vn 0.6521 -0.0159 -0.7579 +vn 0.6936 0.0442 -0.7190 +vn 0.7236 0.0923 -0.6841 +vn 0.4921 0.5789 -0.6502 +vn 0.3393 0.6068 -0.7188 +vn 0.1948 0.6829 -0.7040 +vn -0.1141 0.6522 -0.7494 +vn -0.3907 0.6026 -0.6959 +vn -0.6033 0.2987 -0.7395 +vn -0.7147 0.0490 -0.6978 +vn -0.6177 -0.2854 -0.7328 +vn -0.4687 -0.5529 -0.6889 +vn -0.1524 -0.6537 -0.7412 +vn 0.1856 -0.6888 -0.7008 +vn 0.4045 -0.5873 -0.7011 +vn 0.5797 -0.5439 -0.6068 +vn 0.0315 0.9989 0.0342 +vn 0.0310 0.9991 0.0299 +vn 0.0257 0.9996 -0.0070 +vn 0.0251 0.9996 -0.0113 +vn 0.9880 -0.0037 0.1542 +vn 0.9908 -0.0001 0.1357 +vn 0.9995 0.0282 -0.0102 +vn 0.9989 0.0325 -0.0325 +vn 0.6278 -0.7618 -0.1601 +vn -0.0202 -0.9904 -0.1367 +vn -0.0243 -0.9864 -0.1627 +vn 0.0250 -0.9879 0.1530 +vn 0.0290 -0.9835 0.1788 +vn -0.6242 -0.7621 0.1722 +vn -0.9998 0.0039 0.0188 +vn -1.0000 -0.0007 -0.0035 +vn -0.9900 -0.0284 -0.1384 +vn -0.9871 -0.0322 -0.1567 +vn -0.6378 0.7699 -0.0202 +vn -0.6183 0.7859 -0.0001 +vn -0.6224 0.7827 -0.0042 +vn -0.6023 0.7981 0.0159 +vn -0.7109 0.7030 0.0202 +vn -0.8905 0.4171 -0.1818 +vn -0.7405 0.6719 0.0153 +vn -0.9191 0.3762 -0.1175 +vn -0.9851 -0.1709 0.0176 +vn -0.8931 -0.4367 -0.1081 +vn -0.8485 -0.5292 0.0080 +vn -0.6804 -0.7289 -0.0758 +vn -0.5771 -0.8166 -0.0020 +vn -0.3965 -0.9172 -0.0394 +vn 0.2549 -0.9667 0.0238 +vn 0.4577 -0.8711 -0.1780 +vn 0.2894 -0.9570 0.0190 +vn 0.5455 -0.8369 -0.0442 +vn 0.9559 -0.2339 -0.1774 +vn 0.9387 -0.3445 0.0121 +vn 0.9307 -0.3654 0.0147 +vn 0.9896 -0.1368 -0.0441 +vn 0.8283 0.5369 -0.1605 +vn 0.7441 0.6681 0.0011 +vn 0.9260 0.3775 0.0114 +vn 0.6563 0.7488 -0.0920 +vn 0.4336 0.9010 -0.0124 +vn 0.4793 0.8776 -0.0079 +vn -0.2036 0.9774 -0.0561 +vn -0.1067 0.9943 -0.0082 +vn -0.1977 0.9787 -0.0554 +vn -0.0980 0.9952 -0.0074 +vn -0.3745 -0.9226 -0.0925 +vn -0.8887 -0.3605 -0.2831 +vn -0.8281 0.4195 -0.3719 +vn -0.8865 0.3836 -0.2588 +vn -0.2417 0.9583 -0.1522 +vn 0.8416 0.3827 -0.3812 +vn 0.9580 -0.2087 -0.1966 +vn 0.8392 -0.3557 -0.4114 +vn 0.3266 -0.8516 -0.4100 +vn 0.4947 -0.8520 -0.1712 +vn 0.2471 -0.1521 -0.9570 +vn 0.2876 -0.3219 -0.9020 +vn -0.0299 -0.3930 -0.9191 +vn 0.3438 0.0395 -0.9382 +vn -0.1739 0.3022 -0.9373 +vn -0.2670 0.0793 -0.9604 +vn -0.3882 -0.0429 -0.9206 +vn -0.1306 -0.2539 -0.9584 +vn -0.3069 -0.2841 -0.9083 +vn 0.2438 0.2614 -0.9339 +vn 0.1312 0.2317 -0.9639 +vn 0.0442 0.3971 -0.9167 +vn 0.0144 0.0286 -0.9995 +vn 0.0002 -0.1427 0.9898 +vn 0.0174 0.0803 0.9966 +vn -0.2806 0.1204 0.9522 +vn -0.4029 0.1205 0.9073 +vn -0.3973 -0.2353 0.8870 +vn -0.2606 -0.2160 0.9410 +vn -0.2019 0.4111 0.8890 +vn -0.0713 0.3520 0.9333 +vn 0.1023 0.4419 0.8912 +vn 0.2289 0.2316 0.9455 +vn 0.3339 0.3009 0.8933 +vn 0.4073 0.0120 0.9132 +vn 0.2746 -0.0965 0.9567 +vn 0.2994 -0.3124 0.9015 +vn 0.1032 -0.4279 0.8979 +vn -0.1041 -0.4405 0.8917 +vn 0.4322 0.9018 0.0013 +vn 0.2966 0.9549 -0.0157 +vn 0.0667 0.9978 -0.0059 +vn 0.0399 0.9992 -0.0023 +vn -0.5125 0.8587 0.0034 +vn -0.4674 0.8645 -0.1848 +vn -0.5191 0.8547 0.0026 +vn -0.5856 0.8096 -0.0408 +vn -0.9558 0.2939 0.0097 +vn -0.9546 0.2322 -0.1868 +vn -0.9598 0.2806 0.0077 +vn -0.9643 0.2110 -0.1599 +vn -0.8825 -0.4702 -0.0123 +vn -0.8850 -0.4655 0.0104 +vn -0.8828 -0.4697 -0.0014 +vn -0.8825 -0.4701 -0.0124 +vn -0.4452 -0.8953 0.0142 +vn -0.0804 -0.9967 -0.0068 +vn -0.1124 -0.9936 0.0137 +vn -0.0400 -0.9992 -0.0071 +vn 0.2309 -0.9728 0.0154 +vn 0.9232 -0.3653 -0.1194 +vn 0.9243 -0.3810 0.0212 +vn 0.7131 -0.6999 -0.0402 +vn 0.9831 0.1826 0.0154 +vn 0.9758 0.1941 -0.1004 +vn 0.6930 0.7206 -0.0195 +vn -0.5131 -0.7204 -0.4666 +vn -0.8941 -0.4424 0.0696 +vn -0.8431 0.3351 -0.4205 +vn -0.4762 0.8538 -0.2104 +vn -0.2563 0.8797 -0.4005 +vn 0.8968 -0.2233 -0.3820 +vn 0.7109 -0.6971 -0.0928 +vn 0.3402 -0.7879 -0.5132 +vn 0.0347 -0.5028 -0.8637 +vn 0.3666 -0.3960 -0.8419 +vn -0.0612 -0.9981 0.0099 +vn 0.1746 -0.3357 -0.9256 +vn 0.3201 0.3356 -0.8859 +vn 0.4173 0.0792 -0.9053 +vn 0.2139 0.2616 -0.9412 +vn 0.0493 0.4180 -0.9071 +vn -0.4294 -0.0134 -0.9030 +vn -0.2937 -0.0455 -0.9548 +vn -0.3160 -0.2459 -0.9163 +vn 0.2655 -0.0328 -0.9636 +vn -0.0459 0.1858 -0.9815 +vn -0.2337 0.2751 -0.9326 +vn -0.0724 -0.1777 -0.9814 +vn -0.3376 0.2782 0.8992 +vn -0.4498 -0.0463 0.8919 +vn -0.3137 0.1168 0.9423 +vn -0.0658 0.3068 0.9495 +vn 0.0215 -0.0038 0.9998 +vn -0.1106 0.4360 0.8931 +vn 0.1857 0.3972 0.8988 +vn 0.2486 0.1936 0.9491 +vn 0.4271 0.0894 0.8998 +vn 0.3717 -0.1692 0.9128 +vn 0.2792 -0.3456 0.8959 +vn 0.0385 -0.2859 0.9575 +vn -0.0625 -0.4096 0.9101 +vn -0.2704 -0.1953 0.9427 +vn -0.3174 -0.3403 0.8851 +vn 0.0173 -0.0138 -0.9998 +vn 0.0159 -0.0342 -0.9993 +vn 0.0220 -0.0299 -0.9993 +vn 0.0229 0.0156 -0.9996 +vn 0.0165 -0.0193 -0.9997 +vn -0.0179 0.0154 -0.9997 +vn -0.0212 -0.0114 -0.9997 +vn -0.0293 0.0106 -0.9995 +vn -0.0114 -0.0207 -0.9997 +vn -0.0038 -0.0259 -0.9997 +vn -0.0241 -0.0329 -0.9992 +vn 0.0137 0.0193 -0.9997 +vn 0.0089 0.0232 -0.9997 +vn 0.0309 0.0285 -0.9991 +vn -0.0154 0.0334 -0.9993 +vn -0.0171 0.0228 -0.9996 +vn 0.0285 -0.0345 0.9990 +vn 0.0343 -0.0320 0.9989 +vn 0.0796 -0.0457 0.9958 +vn 0.0410 -0.0328 0.9986 +vn 0.1156 -0.0587 0.9916 +vn 0.1696 -0.9855 -0.0064 +vn 0.1109 -0.9938 0.0054 +vn 0.1618 -0.9868 -0.0049 +vn 0.1010 -0.9949 0.0074 +vn -0.7902 -0.6127 -0.0152 +vn -0.6685 -0.7434 0.0200 +vn -0.6894 -0.7242 0.0144 +vn -0.8058 -0.5919 -0.0203 +vn -0.8484 0.5287 -0.0254 +vn -0.9674 0.2513 0.0295 +vn -0.9551 0.2957 0.0201 +vn -0.8241 0.5655 -0.0325 +vn -0.3750 0.9266 0.0284 +vn -0.3736 0.9228 0.0940 +vn -0.3707 0.9154 0.1567 +vn 0.1437 0.9893 -0.0242 +vn 0.5686 0.8223 0.0227 +vn 0.5175 0.8557 -0.0096 +vn 0.7946 0.6067 0.0210 +vn 0.8100 0.5865 0.0024 +vn 0.9294 0.3689 0.0142 +vn 0.9741 -0.2252 -0.0208 +vn 0.8934 -0.4489 0.0205 +vn 0.9660 -0.2582 -0.0149 +vn 0.8767 -0.4803 0.0266 +vn 0.5575 -0.4827 0.6754 +vn 0.4507 -0.4802 0.7525 +vn 0.2552 -0.6661 0.7008 +vn -0.2445 -0.6160 0.7488 +vn -0.0558 -0.7169 0.6950 +vn -0.4519 -0.5479 0.7040 +vn -0.6564 -0.0210 0.7541 +vn -0.6803 -0.2609 0.6850 +vn -0.7202 0.1177 0.6837 +vn -0.5747 0.4137 0.7061 +vn -0.2544 0.6174 0.7444 +vn -0.2859 0.6672 0.6878 +vn 0.1779 0.7043 0.6872 +vn 0.3523 0.5888 0.7275 +vn 0.5418 0.4837 0.6874 +vn 0.6699 0.1465 0.7278 +vn 0.7163 0.1265 0.6862 +vn 0.6857 -0.2100 0.6969 +vn 0.9579 0.2872 0.0000 +vn 0.9726 0.2021 -0.1152 +vn 0.9698 0.2323 -0.0748 +vn 0.9719 0.1515 -0.1801 +vn -0.2518 0.9509 0.1801 +vn -0.1765 0.9815 0.0746 +vn -0.2057 0.9718 0.1152 +vn -0.1219 0.9925 0.0000 +vn -0.9579 -0.2872 0.0000 +vn -0.9726 -0.2020 -0.1154 +vn -0.9697 -0.2326 -0.0748 +vn -0.9719 -0.1513 -0.1804 +vn 0.2518 -0.9509 0.1802 +vn 0.1765 -0.9815 0.0747 +vn 0.2057 -0.9718 0.1153 +vn 0.1219 -0.9925 0.0000 +vn -0.4014 -0.2981 0.8660 +vn -0.9668 0.2513 0.0473 +vn -0.3120 0.3326 0.8900 +vn -0.3354 0.8268 0.4515 +vn 0.2385 0.4983 0.8336 +vn 0.3874 -0.1141 0.9148 +vn 0.5012 -0.0015 0.8654 +vn 0.5029 -0.0005 0.8643 +vn 0.5120 0.0067 0.8590 +vn 0.5116 0.0085 0.8592 +vn 0.7012 0.0146 0.7128 +vn -0.4842 0.0091 0.8749 +vn -0.4896 0.0075 0.8719 +vn -0.5117 0.0009 0.8591 +vn -0.5176 -0.0008 0.8556 +vn 0.0056 -1.0000 -0.0028 +vn 0.0148 -0.9998 0.0163 +vn 0.0938 -0.9838 0.1525 +vn 0.0110 -0.9999 0.0057 +vn 0.0034 -1.0000 0.0060 +vn 0.0092 -0.9998 -0.0202 +vn 0.0896 -0.9615 -0.2599 +vn -0.1932 -0.9722 0.1325 +vn 0.1302 -0.9001 0.4157 +vn -0.0029 -1.0000 -0.0001 +vn 0.0247 -0.9451 -0.3257 +vn -0.1734 -0.9700 -0.1703 +vn 0.7890 0.0081 0.6143 +vn 0.2465 -0.2153 0.9449 +vn 0.6397 -0.2560 0.7248 +vn 0.8045 0.0068 0.5940 +vn 0.8205 -0.0484 0.5696 +vn 0.9541 -0.2252 0.1976 +vn 0.8073 -0.0058 0.5901 +vn 0.8084 0.0143 0.5885 +vn 0.8093 0.0168 0.5872 +vn 0.3518 -0.3106 -0.8831 +vn 0.4529 -0.0081 -0.8915 +vn 0.5770 -0.0093 -0.8167 +vn 0.4755 -0.0121 -0.8796 +vn 0.1625 -0.0186 -0.9865 +vn 0.2121 -0.2540 -0.9437 +vn 0.1104 -0.0105 -0.9938 +vn -0.1329 -0.0376 -0.9904 +vn 0.2772 -0.2734 -0.9211 +vn -0.1269 -0.0062 -0.9919 +vn -0.2171 -0.0002 -0.9761 +vn -0.2938 -0.0409 -0.9550 +vn -0.4752 0.0794 -0.8763 +vn -0.7257 -0.0041 -0.6880 +vn -0.7433 -0.0317 -0.6682 +vn -0.9067 0.0057 -0.4217 +vn -0.9366 -0.0101 -0.3502 +vn -0.9961 0.0077 -0.0881 +vn -0.9999 -0.0092 0.0127 +vn -0.9820 0.0071 0.1887 +vn -0.9415 -0.0083 0.3368 +vn -0.8976 0.0074 0.4408 +vn -0.8160 -0.0071 0.5781 +vn -0.7327 0.0084 0.6805 +vn -0.6349 -0.0080 0.7726 +vn -0.5001 0.0087 0.8659 +vn -0.3753 -0.0106 0.9269 +vn -0.2246 0.0093 0.9744 +vn -0.0277 -0.0093 0.9996 +vn 0.0699 0.0066 0.9975 +vn 0.2976 -0.0046 0.9547 +vn 0.3267 0.0020 0.9451 +vn 0.5461 -0.0021 0.8377 +vn 0.5636 0.0023 0.8260 +vn 0.7567 -0.0024 0.6537 +vn 0.7651 0.0008 0.6440 +vn 0.8214 0.0381 -0.5691 +vn 0.7554 -0.2433 -0.6084 +vn 0.7310 0.0421 -0.6811 +vn 0.4633 -0.2000 -0.8633 +vn 0.9878 -0.0052 -0.1557 +vn 0.9962 0.0122 -0.0861 +vn 0.9509 -0.0122 0.3093 +vn 0.9264 0.0076 0.3766 +vn 0.9413 0.0098 -0.3375 +vn 0.9405 0.0069 -0.3398 +vn 0.8382 -0.0073 0.5453 +vn 0.8376 -0.0048 0.5463 +vn 0.8419 0.0025 0.5397 +vn 0.8394 0.0049 0.5434 +vn -0.0027 0.0023 -1.0000 +vn 0.2587 0.0021 -0.9660 +vn 0.2996 -0.0011 -0.9541 +vn 0.3284 -0.0143 -0.9444 +vn 0.0036 0.0026 -1.0000 +vn 0.0079 0.0049 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.6756 0.0005 -0.7373 +vn 0.6476 0.0068 -0.7619 +vn 0.8834 0.0119 -0.4685 +vn 0.8712 -0.0144 -0.4906 +vn 0.9880 -0.0049 -0.1542 +vn 0.9974 0.0128 -0.0704 +vn 0.9635 -0.0106 0.2675 +vn 0.9493 0.0186 0.3138 +vn 0.8218 -0.0019 0.5697 +vn 0.5917 -0.0028 0.8061 +vn 0.5168 0.0027 -0.8561 +vn 0.5185 -0.0020 -0.8551 +vn 0.6239 0.0023 0.7815 +vn 0.6281 -0.0047 0.7781 +vn 0.8510 0.0047 0.5252 +vn 0.8666 -0.0060 0.4990 +vn 0.9933 0.0066 0.1149 +vn 0.9968 -0.0109 0.0795 +vn 0.9495 0.0134 -0.3135 +vn 0.9175 -0.0154 -0.3974 +vn 0.6963 -0.0024 -0.7178 +vn 0.6541 -0.0197 -0.7561 +vn 0.5750 -0.0023 -0.8181 +vn 0.5152 -0.0030 -0.8571 +vn 0.5118 0.0014 -0.8591 +vn 0.5131 -0.0086 0.8583 +vn -0.9933 -0.0214 0.1136 +vn -0.9466 0.0282 0.3211 +vn -0.9810 0.0241 -0.1923 +vn -0.8411 -0.0153 0.5407 +vn -0.5907 0.0111 0.8068 +vn -0.4970 -0.0064 0.8677 +vn -0.2922 0.0054 0.9563 +vn -0.3139 -0.0122 0.9494 +vn 0.2548 0.0286 0.9666 +vn 0.3053 -0.0049 0.9522 +vn 0.5378 0.0086 0.8430 +vn 0.5625 -0.0150 0.8267 +vn 0.8490 -0.0038 0.5284 +vn 0.8756 0.0113 0.4829 +vn 0.9892 -0.0162 0.1455 +vn 0.9989 0.0136 0.0447 +vn 0.9311 -0.0179 -0.3644 +vn 0.8866 0.0123 -0.4624 +vn 0.6004 -0.0194 -0.7995 +vn 0.6026 0.0070 -0.7980 +vn 0.2132 0.0123 -0.9769 +vn 0.0619 -0.0292 -0.9977 +vn -0.2788 0.0218 -0.9601 +vn -0.5440 -0.0327 -0.8385 +vn -0.7418 0.0262 -0.6702 +vn -0.9199 -0.0275 -0.3911 +vn 0.9606 0.0108 -0.2776 +vn 0.9839 -0.0201 -0.1778 +vn 0.8807 -0.0095 -0.4736 +vn 0.8636 0.0116 -0.5040 +vn 0.4350 0.0187 -0.9002 +vn 0.4803 -0.0115 -0.8770 +vn 0.2352 -0.0195 -0.9718 +vn 0.0797 0.0282 -0.9964 +vn -0.3718 -0.0247 -0.9280 +vn -0.5713 0.0376 -0.8199 +vn -0.8282 -0.0251 -0.5599 +vn -0.9534 0.0288 -0.3003 +vn -0.9972 -0.0240 -0.0711 +vn -0.9678 0.0234 0.2506 +vn -0.9134 -0.0228 0.4065 +vn -0.7228 0.0229 0.6907 +vn -0.5654 -0.0260 0.8244 +vn -0.2467 0.0289 0.9687 +vn -0.0414 -0.0274 0.9988 +vn 0.3455 0.0288 0.9380 +vn 0.5403 -0.0288 0.8410 +vn 0.8110 0.0225 0.5847 +vn 0.9223 -0.0298 0.3853 +vn 0.9848 0.0149 0.1729 +vn 0.7229 -0.0199 -0.6907 +vn 0.9267 0.0159 -0.3754 +vn 0.7414 -0.0175 -0.6708 +vn 0.9372 0.0186 -0.3483 +vn 0.9949 -0.0082 -0.1006 +vn 0.9995 0.0055 0.0321 +vn 0.9958 -0.0072 -0.0909 +vn 0.9991 0.0064 0.0414 +vn 0.3959 0.0413 -0.9173 +vn 0.3996 0.0351 -0.9160 +vn 0.4799 -0.0024 -0.8773 +vn 0.2143 0.0264 -0.9764 +vn 0.2582 0.2244 -0.9397 +vn 0.0661 0.0042 -0.9978 +vn -0.0738 0.0123 -0.9972 +vn -0.0941 -0.0027 -0.9956 +vn -0.0405 0.2935 -0.9551 +vn 0.1776 -0.0031 -0.9841 +vn -0.8076 0.0149 -0.5896 +vn -0.7438 0.0017 -0.6684 +vn -0.9252 0.0016 -0.3794 +vn -0.8371 0.0233 -0.5465 +vn -0.8519 -0.0035 -0.5236 +vn -0.9355 0.0076 -0.3531 +vn -0.9817 0.0211 -0.1892 +vn -0.9928 0.0013 -0.1194 +vn -0.9999 0.0100 -0.0095 +vn -0.9997 0.0137 -0.0183 +vn -0.8440 0.0013 -0.5364 +vn -0.7899 0.2308 -0.5681 +vn -0.8415 0.0021 -0.5403 +vn -0.5021 0.2631 -0.8238 +vn -0.1284 0.0027 -0.9917 +vn -0.1287 0.0026 -0.9917 +vn -0.1501 0.2340 -0.9606 +vn 0.4022 0.1581 -0.9018 +vn 0.8109 -0.0108 -0.5851 +vn 0.8821 0.3322 -0.3338 +vn 0.9759 -0.0068 -0.2180 +vn 0.9325 0.1584 0.3247 +vn 0.6348 0.3632 0.6819 +vn 0.8053 -0.0009 0.5929 +vn 0.7961 0.0136 0.6050 +vn 0.5620 0.0318 0.8265 +vn 0.0082 -0.0026 1.0000 +vn 0.0065 0.0041 1.0000 +vn 0.0004 0.0286 0.9996 +vn 0.0037 0.0980 0.9952 +vn 0.0027 0.0549 0.9985 +vn -0.6577 0.0019 0.7533 +vn -0.6272 -0.0061 0.7788 +vn -0.6545 0.0010 0.7561 +vn -0.6225 -0.0073 0.7826 +vn -0.9988 -0.0123 0.0467 +vn -0.7964 0.3630 0.4837 +vn -0.9963 0.0859 -0.0000 +vn -0.1952 0.9654 -0.1730 +vn -0.1827 0.9568 0.2261 +vn 0.1286 0.9642 0.2320 +vn -0.0102 0.9999 -0.0014 +vn -0.0136 0.9716 -0.2362 +vn -0.0000 1.0000 -0.0071 +vn 0.0260 0.9835 -0.1793 +vn -0.1530 0.9880 -0.0220 +vn 0.9873 0.0004 -0.1588 +vn 0.9852 -0.0086 -0.1713 +vn 0.9860 -0.0052 -0.1665 +vn 0.9836 -0.0147 -0.1796 +vn 0.5513 -0.0297 0.8338 +vn 0.8510 0.0322 0.5242 +vn 0.5321 0.0213 0.8464 +vn 0.4641 -0.0321 0.8852 +vn 0.1132 0.0171 0.9934 +vn -0.5164 -0.0011 0.8564 +vn -0.5051 -0.0080 0.8630 +vn -0.5111 -0.0043 0.8595 +vn -0.5001 -0.0110 0.8659 +vn -0.9945 -0.0050 0.1045 +vn -0.9860 0.0058 0.1665 +vn -0.9874 0.0044 0.1583 +vn -0.9953 -0.0064 0.0966 +vn -0.8417 0.0036 -0.5399 +vn -0.8379 -0.0000 -0.5458 +vn -0.8336 -0.0042 -0.5524 +vn -0.8298 -0.0078 -0.5581 +vn -0.1679 -0.0070 -0.9858 +vn -0.2937 0.0145 -0.9558 +vn -0.2786 0.0119 -0.9603 +vn -0.1504 -0.0100 -0.9886 +vn 0.5707 -0.0044 -0.8211 +vn 0.6294 0.0093 -0.7770 +vn 0.5791 -0.0025 -0.8152 +vn 0.6365 0.0110 -0.7712 +vn -0.9981 0.0053 -0.0620 +vn -0.9704 -0.0060 -0.2416 +vn -0.9977 0.0076 -0.0672 +vn -0.9650 -0.1628 -0.2058 +vn -0.8351 -0.4071 -0.3700 +vn -0.8195 -0.2710 -0.5049 +vn -0.8169 -0.0145 -0.5766 +vn -0.7354 -0.0026 -0.6776 +vn -0.8071 -0.0078 -0.5903 +vn -0.8986 0.0007 -0.4389 +vn -0.9636 -0.2289 -0.1381 +vn -0.9959 0.0133 -0.0897 +vn -0.9156 -0.2036 0.3467 +vn -0.6470 0.0087 0.7625 +vn -0.6394 -0.2878 0.7130 +vn -0.3329 0.0023 0.9430 +vn -0.1983 -0.0112 0.9801 +vn 0.0045 0.0024 -1.0000 +vn 0.0814 -0.0808 0.9934 +vn 0.0022 0.0000 -1.0000 +vn 0.0030 0.0082 1.0000 +vn 0.1510 -0.3607 0.9204 +vn 0.0010 0.1837 0.9830 +vn 0.0947 0.3672 0.9253 +vn 0.5108 -0.0135 0.8596 +vn -0.3156 -0.0026 -0.9489 +vn 0.0175 -0.3541 -0.9350 +vn -0.3028 0.0003 -0.9530 +vn -0.1926 -0.0864 -0.9775 +vn -0.8002 -0.0310 -0.5990 +vn -0.7460 -0.2440 -0.6197 +vn -0.7704 -0.2106 -0.6018 +vn 0.9852 0.0049 -0.1715 +vn 0.9836 0.0007 -0.1802 +vn 0.9846 0.0032 -0.1750 +vn 0.9830 -0.0011 -0.1838 +vn 0.2595 0.0033 -0.9657 +vn 0.2356 -0.0013 -0.9718 +vn 0.2564 0.0027 -0.9666 +vn 0.2324 -0.0019 -0.9726 +vn -0.8190 -0.0007 -0.5739 +vn -0.8194 -0.0004 -0.5732 +vn -0.8209 0.0004 -0.5711 +vn -0.8214 0.0007 -0.5704 +vn 0.5325 0.0205 0.8462 +vn 0.1249 -0.0130 0.9921 +vn 0.5117 -0.0129 0.8590 +vn 0.5812 0.0199 0.8135 +vn 0.8136 -0.0150 0.5812 +vn 0.9324 -0.2883 -0.2182 +vn 0.9583 0.0049 -0.2856 +vn 0.9950 -0.0573 0.0819 +vn 0.7205 -0.2785 -0.6351 +vn 0.8090 0.0035 -0.5878 +vn 0.9994 -0.0227 -0.0255 +vn 0.9509 -0.2778 -0.1364 +vn 0.9608 -0.0126 -0.2769 +vn 0.9622 -0.2217 -0.1579 +vn 0.7008 -0.2527 -0.6671 +vn 0.6845 0.0036 -0.7290 +vn 0.6066 -0.0318 -0.7944 +vn 0.6380 -0.3485 -0.6867 +vn -0.0104 -0.9958 -0.0909 +vn 0.0030 -0.9999 -0.0099 +vn 0.0039 -0.9514 -0.3079 +vn 0.0339 -0.9988 -0.0345 +vn 0.7694 -0.2511 0.5874 +vn 0.7881 -0.0553 0.6130 +vn 0.5712 -0.1930 0.7978 +vn 0.6994 0.0097 0.7146 +vn 0.0140 0.0094 0.9999 +vn 0.0966 -0.2468 0.9642 +vn 0.0693 -0.0115 0.9975 +vn 0.1463 -0.2120 0.9663 +vn -0.5349 -0.0551 0.8431 +vn -0.3123 -0.2884 0.9051 +vn -0.5487 -0.0307 0.8355 +vn -0.5472 -0.2058 0.8113 +vn 0.1770 -0.9248 0.3368 +vn -0.0092 -0.7649 0.6441 +vn -0.0175 -0.9982 0.0569 +vn 0.2806 0.0505 0.9585 +vn 0.9209 0.0168 -0.3895 +vn -0.5137 0.7719 0.3745 +vn -0.4622 0.8582 -0.2232 +vn -0.7985 0.5951 0.0907 +vn -0.1880 0.6508 0.7356 +vn -0.8106 0.5394 -0.2279 +vn -0.6490 0.6459 -0.4020 +vn -0.4848 0.5183 0.7045 +vn -0.8087 0.5086 -0.2956 +vn -0.7044 0.6698 -0.2350 +vn -0.7979 0.5992 -0.0656 +vn -0.6303 0.5322 -0.5653 +vn -0.5280 0.7117 -0.4634 +vn -0.6609 0.5988 -0.4524 +vn -0.5923 0.7264 -0.3487 +vn -0.6517 0.7385 -0.1728 +vn -0.7891 0.6141 -0.0110 +vn -0.7802 0.6254 -0.0154 +vn -0.2852 0.9533 -0.0996 +vn -0.9897 -0.1429 -0.0024 +vn -0.2878 0.9569 -0.0398 +vn 0.2574 0.7700 0.5839 +vn -0.4478 0.6431 -0.6212 +vn -0.2459 0.6194 -0.7456 +vn -0.2257 0.7885 -0.5722 +vn 0.1374 0.6706 -0.7289 +vn 0.0772 0.5424 -0.8366 +vn 0.0461 0.6519 -0.7569 +vn -0.0657 0.5446 -0.8361 +vn 0.3593 0.5663 -0.7418 +vn 0.3330 0.7480 -0.5741 +vn 0.2734 0.7353 -0.6201 +vn -0.1022 0.7383 -0.6667 +vn -0.0601 0.6927 -0.7187 +vn 0.2931 0.8292 -0.4759 +vn 0.1378 0.8209 -0.5542 +vn 0.7771 0.5724 0.2618 +vn 0.3367 0.9102 0.2413 +vn 0.6072 0.5683 -0.5553 +vn 0.5773 0.6779 -0.4552 +vn 0.6479 0.7056 -0.2869 +vn 0.4715 0.8041 -0.3621 +vn -0.1869 -0.6606 0.7271 +vn -0.3336 -0.7913 0.5124 +vn -0.6890 -0.5956 -0.4130 +vn -0.6787 -0.5929 -0.4335 +vn -0.7350 -0.6678 0.1174 +vn -0.3266 -0.9416 -0.0823 +vn 0.4636 -0.6386 0.6142 +vn -0.8895 -0.4560 -0.0296 +vn -0.7826 -0.6135 -0.1062 +vn -0.7178 -0.6291 -0.2983 +vn -0.6049 -0.6806 -0.4134 +vn -0.6423 -0.5029 -0.5784 +vn -0.7726 -0.6168 -0.1504 +vn -0.6360 -0.7266 -0.2599 +vn -0.4062 -0.8462 -0.3449 +vn -0.1231 -0.9922 0.0199 +vn -0.8517 -0.4861 -0.1956 +vn 0.1994 -0.8543 0.4800 +vn 0.7273 -0.4009 0.5571 +vn 0.1200 -0.7563 -0.6431 +vn -0.3144 -0.5918 -0.7423 +vn 0.0879 -0.4041 0.9105 +vn -0.3925 -0.4870 0.7803 +vn 0.0855 -0.7906 0.6064 +vn 0.1202 -0.7584 0.6407 +vn 0.2795 -0.5197 0.8073 +vn 0.2298 -0.7557 -0.6133 +vn 0.2839 -0.6954 -0.6602 +vn 0.1041 -0.7092 -0.6973 +vn 0.3881 -0.8605 -0.3300 +vn -0.3941 -0.7433 0.5405 +vn -0.1511 -0.8172 0.5562 +vn -0.2536 -0.6493 0.7169 +vn 0.6101 -0.7428 -0.2757 +vn 0.7227 -0.6435 -0.2522 +vn 0.0602 -0.5595 0.8267 +vn 0.4746 -0.8522 -0.2204 +vn 0.6851 -0.6990 0.2052 +vn 0.6725 -0.5335 0.5130 +vn 0.5747 -0.6930 0.4353 +vn 0.6462 -0.7292 0.2253 +vn 0.4367 -0.8358 0.3328 +vn 0.2958 -0.8796 -0.3726 +vn 0.6015 -0.7246 -0.3364 +vn 0.2690 -0.7123 0.6482 +vn 0.5440 -0.6784 0.4939 +vn 0.6878 -0.6646 0.2920 +vn 0.4175 -0.8550 0.3078 +vn 0.4950 -0.8688 -0.0142 +vn 0.4201 -0.8534 0.3087 +vn 0.5036 -0.6225 -0.5991 +vn 0.7233 -0.6441 -0.2489 +vn 0.5132 -0.7813 -0.3553 +vn -0.0599 -0.9308 -0.3605 +vn -0.1250 -0.7098 -0.6932 +vn -0.1174 -0.7146 -0.6896 +vn -0.1389 -0.5754 -0.8060 +vn -0.0225 -0.7217 -0.6919 +vn -0.0791 -0.5915 -0.8024 +vn 0.9565 0.0149 -0.2914 +vn 0.9383 -0.0039 -0.3459 +vn 0.9520 0.0099 -0.3060 +vn 0.9327 -0.0090 -0.3606 +vn 0.9527 0.0199 -0.3033 +vn 0.9418 -0.0038 -0.3361 +vn 0.9459 0.0047 -0.3244 +vn 0.9341 -0.0187 -0.3565 +vn -0.9809 0.0006 0.1943 +vn -0.9800 -0.0006 0.1992 +vn -0.9808 0.0004 0.1952 +vn -0.9798 -0.0008 0.2001 +vn -0.9244 0.0106 0.3813 +vn -0.8612 -0.0607 0.5046 +vn -0.8934 -0.0276 0.4485 +vn -0.8275 -0.0911 0.5541 +vn -0.8102 0.0024 -0.5862 +vn -0.8108 0.0008 -0.5853 +vn -0.8087 0.0011 -0.5882 +vn -0.8115 0.0047 -0.5844 +vn 0.0323 0.0074 -0.9995 +vn 0.0239 -0.0064 -0.9997 +vn 0.0228 -0.0109 -0.9997 +vn -0.0256 -0.0122 -0.9996 +vn -0.0355 -0.0078 -0.9993 +vn -0.0195 0.0118 -0.9997 +vn -0.0113 -0.0172 -0.9998 +vn 0.0020 -0.0264 -0.9997 +vn -0.0176 0.0089 -0.9998 +vn 0.0196 -0.0325 -0.9993 +vn -0.0081 0.0320 -0.9995 +vn 0.0110 0.0195 -0.9997 +vn 0.0137 0.0138 -0.9998 +vn -0.0062 0.0325 -0.9995 +vn -0.0106 0.0066 0.9999 +vn -0.0946 -0.0802 0.9923 +vn -0.0059 0.0112 0.9999 +vn -0.0920 -0.0728 0.9931 +vn 0.0639 0.1083 0.9921 +vn 0.0621 0.1006 0.9930 +vn 0.7245 -0.6886 -0.0308 +vn 0.3674 -0.9297 0.0273 +vn 0.6826 -0.7304 -0.0230 +vn 0.3106 -0.9499 0.0352 +vn -0.2467 -0.9691 -0.0093 +vn -0.3027 -0.9531 -0.0014 +vn -0.2517 -0.9678 -0.0086 +vn -0.3123 -0.9500 -0.0001 +vn -0.9353 -0.3540 0.0017 +vn -0.9234 -0.3837 0.0066 +vn -0.9250 -0.3798 0.0060 +vn -0.9365 -0.3506 0.0012 +vn -0.9140 0.4055 0.0152 +vn -0.9242 0.3817 0.0103 +vn -0.9152 0.4028 0.0146 +vn -0.9254 0.3788 0.0098 +vn -0.2524 0.9676 -0.0017 +vn -0.4571 0.8891 0.0254 +vn -0.2069 0.9781 0.0211 +vn 0.1767 0.9842 -0.0090 +vn 0.4955 0.8684 0.0177 +vn 0.8274 0.5616 -0.0089 +vn 0.9644 0.2633 0.0251 +vn 0.9828 0.1844 0.0003 +vn 0.9952 -0.0922 0.0337 +vn 0.6814 -0.2532 0.6868 +vn 0.6586 -0.1850 0.7294 +vn 0.3661 -0.6169 0.6967 +vn 0.1882 -0.6441 0.7414 +vn -0.1396 -0.7172 0.6828 +vn -0.4665 -0.5039 0.7269 +vn -0.5635 -0.4500 0.6928 +vn -0.6981 0.0137 0.7158 +vn -0.7184 -0.0030 0.6956 +vn -0.6418 0.3445 0.6852 +vn -0.4359 0.5329 0.7253 +vn -0.3678 0.6145 0.6980 +vn 0.1150 0.6838 0.7205 +vn 0.0273 0.7186 0.6949 +vn 0.4474 0.5729 0.6867 +vn 0.5674 0.3897 0.7254 +vn 0.6985 0.2026 0.6863 +vn 0.9697 0.2328 -0.0746 +vn 0.9719 0.1512 -0.1804 +vn -0.2057 0.9718 0.1155 +vn -0.9726 -0.2021 -0.1151 +vn 0.2912 -0.6146 0.7332 +vn -0.2746 -0.2522 0.9279 +vn 0.2044 0.3375 0.9189 +vn 0.7934 -0.1361 0.5932 +vn 0.0171 -0.0142 -0.9998 +vn 0.0252 0.0057 -0.9997 +vn 0.0310 -0.0133 -0.9994 +vn -0.0217 0.0120 -0.9997 +vn -0.0048 0.0235 -0.9997 +vn -0.0213 0.0074 -0.9997 +vn -0.0074 -0.0213 -0.9997 +vn 0.0041 -0.0230 -0.9997 +vn -0.0333 -0.0080 -0.9994 +vn -0.0430 -0.0088 -0.9990 +vn -0.0302 -0.0136 -0.9995 +vn 0.0102 0.0238 -0.9997 +vn 0.0034 0.0293 -0.9996 +vn 0.0188 0.0297 -0.9994 +vn -0.0094 -0.0208 -0.9997 +vn 0.0013 -0.0300 -0.9995 +vn 0.1044 -0.1442 0.9840 +vn 0.1543 -0.0485 0.9868 +vn -0.0716 -0.0562 0.9958 +vn -0.0424 0.0935 0.9947 +vn -0.0608 -0.0192 0.9980 +vn 0.0409 0.1427 0.9889 +vn 0.3024 -0.9531 -0.0059 +vn 0.5188 -0.8546 0.0203 +vn 0.2300 -0.9730 0.0212 +vn 0.2553 -0.9668 -0.0057 +vn -0.0405 -0.9989 0.0244 +vn -0.5942 -0.8043 0.0003 +vn -0.5965 -0.8026 0.0009 +vn -0.5947 -0.8040 0.0005 +vn -0.5968 -0.8024 0.0009 +vn -0.9825 0.1857 -0.0122 +vn -0.9976 -0.0672 0.0147 +vn -0.9821 0.1881 0.0128 +vn -0.9748 0.2227 -0.0118 +vn -0.9151 0.4029 0.0151 +vn -0.2713 0.9624 -0.0114 +vn -0.4114 0.9113 0.0149 +vn -0.3932 0.9194 0.0114 +vn -0.2540 0.9671 -0.0145 +vn 0.6048 0.7963 -0.0032 +vn 0.5296 0.8475 0.0346 +vn 0.5390 0.8418 0.0288 +vn 0.6162 0.7876 -0.0058 +vn 0.9924 -0.1230 -0.0090 +vn 0.9975 -0.0636 0.0298 +vn 0.9968 -0.0718 0.0347 +vn 0.9911 -0.1324 -0.0110 +vn 0.6615 -0.2600 0.7035 +vn 0.5150 -0.4330 0.7398 +vn 0.3693 -0.6254 0.6874 +vn 0.0676 -0.7070 0.7039 +vn -0.1302 -0.6671 0.7335 +vn -0.2839 -0.6553 0.7000 +vn -0.6137 -0.2513 0.7485 +vn -0.5003 -0.5079 0.7013 +vn -0.7027 -0.1954 0.6842 +vn -0.6956 0.1301 0.7065 +vn -0.4739 0.4699 0.7447 +vn -0.6087 0.4006 0.6848 +vn -0.3470 0.6375 0.6879 +vn 0.0010 0.7172 0.6968 +vn 0.1311 0.6704 0.7303 +vn 0.4748 0.5512 0.6861 +vn 0.6337 0.2417 0.7349 +vn 0.7053 0.1232 0.6982 +vn 0.9726 0.2019 -0.1154 +vn 0.9697 0.2325 -0.0748 +vn 0.9719 0.1513 -0.1803 +vn -0.9726 -0.2021 -0.1149 +vn 0.3683 -0.3290 0.8696 +vn -0.4044 -0.2292 0.8854 +vn -0.0798 0.4505 0.8892 +vn 0.5256 0.8415 0.1251 +vn 0.4040 0.1959 0.8935 +vn 0.9817 -0.0627 0.1797 +vn 0.0312 0.0121 -0.9994 +vn 0.0307 0.0005 -0.9995 +vn 0.0206 -0.0095 -0.9997 +vn -0.0213 0.0113 -0.9997 +vn -0.0260 -0.0066 -0.9996 +vn -0.0370 0.0098 -0.9993 +vn -0.0167 0.0171 -0.9997 +vn 0.0002 0.0270 -0.9996 +vn -0.0079 -0.0234 -0.9997 +vn -0.0125 -0.0293 -0.9995 +vn 0.0110 -0.0205 -0.9997 +vn -0.0003 -0.0311 -0.9995 +vn 0.0150 0.0205 -0.9997 +vn 0.0198 0.0244 -0.9995 +vn 0.1706 0.0968 0.9806 +vn -0.0388 0.0013 0.9992 +vn 0.1392 0.0477 0.9891 +vn -0.0604 -0.0081 0.9981 +vn -0.0262 -0.0301 0.9992 +vn 0.0135 -0.0692 0.9975 +vn 0.7738 -0.6333 -0.0131 +vn 0.8881 -0.4592 0.0220 +vn 0.7500 -0.6612 -0.0193 +vn -0.2652 -0.9641 -0.0124 +vn -0.0251 -0.9994 0.0218 +vn -0.3611 -0.9323 0.0219 +vn -0.3278 -0.9447 -0.0129 +vn -0.6395 -0.7683 0.0262 +vn -0.9927 -0.1202 -0.0080 +vn -0.9975 -0.0705 0.0011 +vn -0.9935 -0.1137 -0.0068 +vn -0.9981 -0.0617 0.0028 +vn -0.6021 0.7984 -0.0106 +vn -0.6698 0.7394 0.0692 +vn -0.6621 0.7467 0.0641 +vn -0.5931 0.8050 -0.0126 +vn 0.3115 0.9501 -0.0148 +vn 0.1384 0.9872 0.0796 +vn 0.1566 0.9784 0.1350 +vn 0.3350 0.9420 -0.0189 +vn 0.9769 0.2134 -0.0035 +vn 0.9152 0.4023 0.0246 +vn 0.9267 0.3754 0.0205 +vn 0.9821 0.1881 -0.0071 +vn 0.9030 -0.4288 0.0277 +vn 0.4692 -0.5562 0.6859 +vn 0.1778 -0.6451 0.7431 +vn -0.0188 -0.7151 0.6988 +vn -0.5114 -0.4261 0.7463 +vn -0.3918 -0.5936 0.7030 +vn -0.6857 -0.2298 0.6907 +vn -0.6199 0.2636 0.7391 +vn -0.6926 0.1972 0.6938 +vn -0.4546 0.5659 0.6878 +vn -0.0955 0.6750 0.7316 +vn -0.0768 0.7210 0.6887 +vn 0.3827 0.6138 0.6905 +vn 0.5134 0.4388 0.7375 +vn 0.6866 0.2338 0.6884 +vn 0.6582 -0.1792 0.7312 +vn 0.7027 -0.1586 0.6936 +vn 0.9201 0.2757 -0.2783 +vn 0.9225 0.3073 -0.2337 +vn 0.9219 0.2961 -0.2498 +vn 0.9226 0.3223 -0.2118 +vn -0.2475 0.9348 0.2547 +vn -0.6824 0.5880 -0.4343 +vn -0.9252 -0.2774 0.2591 +vn -0.1725 -0.9091 -0.3793 +vn 0.0475 -0.8113 0.5827 +vn -0.4791 0.0681 0.8751 +vn -0.6378 0.7041 0.3124 +vn -0.0796 0.5064 0.8586 +vn 0.1230 0.8839 0.4511 +vn 0.4558 0.3116 0.8338 +vn 0.4768 -0.3209 0.8184 +vn 0.0249 -0.0129 -0.9996 +vn 0.0298 -0.0226 -0.9993 +vn 0.0113 -0.0243 -0.9996 +vn 0.0248 0.0123 -0.9996 +vn 0.0368 -0.0090 -0.9993 +vn -0.0223 0.0067 -0.9997 +vn -0.0331 -0.0124 -0.9994 +vn -0.0263 0.0006 -0.9997 +vn 0.0119 0.0185 -0.9998 +vn 0.0012 0.0240 -0.9997 +vn 0.0180 0.0284 -0.9994 +vn -0.0137 -0.0180 -0.9997 +vn -0.0334 -0.0100 -0.9994 +vn -0.0155 -0.0162 -0.9997 +vn -0.0174 0.0232 -0.9996 +vn 0.0104 -0.0334 0.9994 +vn 0.0802 -0.0709 0.9942 +vn 0.1315 -0.0783 0.9882 +vn -0.0764 -0.0111 0.9970 +vn -0.0868 -0.0397 0.9954 +vn -0.0261 -0.1442 0.9892 +vn 0.5860 -0.8100 -0.0216 +vn 0.3672 -0.9300 0.0133 +vn 0.0377 -0.9990 -0.0233 +vn 0.0825 -0.9962 0.0279 +vn -0.5381 -0.8423 0.0302 +vn -0.5687 -0.8223 -0.0211 +vn -0.8584 -0.5121 0.0299 +vn -0.9742 0.2248 -0.0201 +vn -0.9389 0.3441 0.0008 +vn -0.9711 0.2380 -0.0179 +vn -0.9325 0.3611 0.0039 +vn -0.3427 0.9394 -0.0056 +vn -0.4405 0.8970 0.0363 +vn -0.4274 0.9031 0.0407 +vn -0.3273 0.9449 -0.0089 +vn 0.7004 0.7138 -0.0032 +vn 0.5941 0.8042 0.0178 +vn 0.8257 0.5637 0.0218 +vn 0.9460 0.3241 -0.0032 +vn 0.9992 -0.0319 0.0234 +vn 0.9902 -0.1396 -0.0008 +vn 0.9261 -0.3767 0.0192 +vn 0.5107 -0.5112 0.6913 +vn 0.5925 -0.3453 0.7278 +vn 0.0343 -0.6625 0.7483 +vn 0.1268 -0.7238 0.6783 +vn -0.2921 -0.6467 0.7046 +vn -0.6059 -0.2457 0.7567 +vn -0.5604 -0.4517 0.6942 +vn -0.7261 -0.0843 0.6824 +vn -0.6746 0.2442 0.6966 +vn -0.4958 0.4564 0.7388 +vn -0.4042 0.5921 0.6972 +vn 0.1522 0.6563 0.7390 +vn -0.0406 0.7275 0.6849 +vn 0.3656 0.6206 0.6937 +vn 0.6125 0.3723 0.6972 +vn 0.6424 0.2292 0.7313 +vn 0.7239 -0.0629 0.6870 +vn 0.6825 -0.5879 -0.4342 +vn 0.9252 0.2774 0.2591 +vn 0.1725 0.9091 -0.3792 +vn -0.9200 -0.2758 -0.2784 +vn -0.9224 -0.3072 -0.2341 +vn -0.9218 -0.2960 -0.2501 +vn -0.9226 -0.3223 -0.2122 +vn 0.2476 -0.9348 0.2545 +vn -0.3133 -0.0421 0.9487 +vn -0.4183 0.8897 0.1830 +vn 0.1818 0.4908 0.8521 +vn 0.3722 -0.2851 0.8833 +vn -0.0260 -0.0074 -0.9996 +vn -0.0319 0.0031 -0.9995 +vn -0.0168 -0.0146 -0.9998 +vn 0.0157 -0.0042 -0.9999 +vn 0.0134 -0.0118 -0.9998 +vn 0.0003 -0.0243 -0.9997 +vn -0.0058 -0.0271 -0.9996 +vn -0.0205 -0.0308 -0.9993 +vn 0.0049 0.0216 -0.9998 +vn 0.0106 0.0288 -0.9995 +vn 0.0247 0.0166 -0.9996 +vn 0.0288 0.0092 -0.9995 +vn 0.0037 0.0430 -0.9991 +vn -0.0102 0.0195 -0.9998 +vn -0.0468 0.0678 0.9966 +vn -0.0273 -0.0920 0.9954 +vn 0.0990 0.0029 0.9951 +vn -0.0573 -0.0731 0.9957 +vn -0.1415 0.1068 0.9842 +vn 0.1296 0.0282 0.9912 +vn 0.2409 -0.9706 0.0030 +vn 0.4705 -0.8818 0.0324 +vn 0.1768 -0.9839 0.0254 +vn -0.1757 -0.9844 -0.0101 +vn -0.2041 -0.9788 0.0145 +vn -0.5483 -0.8360 -0.0210 +vn -0.9961 -0.0879 -0.0100 +vn -0.9202 -0.3872 0.0571 +vn -0.9989 -0.0107 0.0453 +vn -0.9999 0.0061 -0.0107 +vn -0.9028 0.4292 0.0288 +vn -0.5160 0.8561 -0.0280 +vn -0.2118 0.9772 0.0145 +vn -0.4901 0.8713 -0.0241 +vn -0.1703 0.9852 0.0199 +vn 0.4328 0.9015 0.0030 +vn 0.3650 0.9309 0.0159 +vn 0.3740 0.9273 0.0141 +vn 0.4403 0.8978 0.0016 +vn 0.9776 0.2106 -0.0054 +vn 0.9207 0.3897 0.0213 +vn 0.9282 0.3717 0.0185 +vn 0.9818 0.1897 -0.0085 +vn 0.8746 -0.4849 -0.0028 +vn 0.9174 -0.3979 0.0060 +vn 0.9127 -0.4085 0.0050 +vn 0.8709 -0.4914 -0.0035 +vn 0.5807 -0.4248 0.6945 +vn 0.4332 -0.5474 0.7161 +vn 0.2692 -0.6698 0.6920 +vn -0.1191 -0.6768 0.7264 +vn -0.0589 -0.7214 0.6900 +vn -0.4278 -0.5864 0.6878 +vn -0.5946 -0.3329 0.7318 +vn -0.6906 -0.2008 0.6948 +vn -0.5983 0.3110 0.7385 +vn -0.6991 0.1899 0.6893 +vn -0.4556 0.5557 0.6954 +vn -0.0252 0.6705 0.7415 +vn -0.1190 0.7072 0.6969 +vn 0.2682 0.6717 0.6906 +vn 0.5560 0.4084 0.7239 +vn 0.5871 0.4153 0.6949 +vn 0.7077 -0.0615 0.7038 +vn 0.7053 -0.1374 0.6955 +vn 0.8816 -0.4217 0.2122 +vn 0.8837 -0.3956 0.2502 +vn 0.8830 -0.4069 0.2340 +vn 0.8841 -0.3751 0.2787 +vn -0.0715 0.9224 0.3795 +vn 0.3547 0.9174 -0.1803 +vn -0.8890 0.3775 -0.2593 +vn -0.7430 -0.5093 0.4342 +vn -0.3491 -0.9019 -0.2543 +vn -0.2237 -0.4049 0.8866 +vn -0.8853 -0.3947 0.2459 +vn -0.2715 0.2531 0.9286 +vn 0.4217 0.0465 0.9056 +vn 0.0001 -0.0003 1.0000 +vn 0.0008 -0.0021 1.0000 +vn 0.0002 0.0002 1.0000 +vn 0.0004 0.0010 1.0000 +vn -0.0045 -0.0008 1.0000 +vn -0.0002 0.0002 1.0000 +vn -0.0009 0.0003 1.0000 +vn -0.0008 0.0004 1.0000 +vn 0.0014 0.0005 1.0000 +vn 0.0007 0.0019 1.0000 +s 1 +f 1/1/1 2/2/1 3/3/1 +f 4/4/1 2/2/1 1/1/1 +f 5/5/2 6/6/2 7/7/2 +f 5/5/2 7/7/2 8/8/2 +f 9/9/3 10/10/4 11/11/5 +f 9/9/3 11/11/5 12/12/6 +f 12/12/6 11/11/5 13/13/7 +f 12/12/6 13/13/7 14/14/8 +f 15/15/9 16/16/10 17/17/11 +f 18/18/12 16/16/10 15/15/9 +f 19/19/13 20/20/14 21/21/15 +f 22/22/16 23/23/17 24/24/18 +f 18/18/12 25/25/19 16/16/10 +f 22/22/16 24/24/18 21/21/15 +f 21/21/15 24/24/18 19/19/13 +f 20/20/14 25/25/19 18/18/12 +f 26/26/20 27/27/21 28/28/22 +f 28/28/22 29/29/23 30/30/24 +f 29/29/23 31/31/25 30/30/24 +f 30/30/24 31/31/25 32/32/26 +f 32/32/26 31/31/25 33/33/27 +f 34/34/28 27/27/21 15/15/9 +f 32/32/26 33/33/27 35/35/29 +f 36/36/30 37/37/31 38/38/32 +f 39/39/33 37/37/31 40/40/34 +f 38/38/32 37/37/31 39/39/33 +f 41/41/35 42/42/36 43/43/37 +f 42/42/36 36/36/30 38/38/32 +f 43/43/37 42/42/36 38/38/32 +f 44/44/38 45/45/39 43/43/37 +f 43/43/37 45/45/39 41/41/35 +f 40/40/34 46/46/40 47/47/41 +f 39/39/33 40/40/34 47/47/41 +f 47/47/41 46/46/40 45/45/39 +f 48/48/42 49/49/43 50/50/44 +f 50/50/44 49/49/43 51/51/45 +f 52/52/46 51/51/45 53/53/47 +f 50/50/44 51/51/45 52/52/46 +f 44/44/38 54/54/48 55/55/49 +f 48/48/42 55/55/49 49/49/43 +f 56/56/50 57/57/51 58/58/52 +f 56/56/50 58/58/52 44/44/38 +f 44/44/38 58/58/52 54/54/48 +f 52/52/46 53/53/47 59/59/53 +f 56/56/50 59/59/54 57/57/51 +f 60/60/55 21/21/15 61/61/56 +f 52/52/46 21/21/15 60/60/55 +f 60/60/55 62/62/57 52/52/46 +f 63/63/58 61/61/56 21/21/15 +f 64/64/59 18/18/12 65/65/60 +f 18/18/12 64/64/59 63/63/58 +f 52/52/46 62/62/57 66/66/61 +f 52/52/46 66/66/61 50/50/44 +f 50/50/44 66/66/61 65/65/60 +f 50/50/44 65/65/60 18/18/12 +f 21/21/15 20/20/14 18/18/12 +f 21/21/15 18/18/12 63/63/58 +f 67/67/62 68/68/1 47/47/41 +f 47/47/41 68/68/1 48/48/1 +f 48/48/1 68/68/1 69/69/1 +f 45/45/39 44/44/38 70/70/63 +f 45/45/39 67/67/62 47/47/41 +f 55/55/49 48/48/42 44/44/38 +f 44/44/64 48/48/64 69/69/64 +f 70/70/63 67/67/62 45/45/39 +f 15/15/9 71/71/1 72/72/1 +f 18/18/12 73/73/1 74/74/1 +f 75/75/1 71/71/1 15/15/9 +f 15/15/9 72/72/1 18/18/12 +f 18/18/12 72/72/1 73/73/1 +f 18/18/12 74/74/1 26/26/20 +f 26/26/20 74/74/1 76/76/1 +f 26/26/20 76/76/1 75/75/1 +f 27/27/21 26/26/20 15/15/9 +f 15/15/9 26/26/20 75/75/1 +f 77/77/65 78/78/66 30/30/24 +f 38/38/32 79/79/67 80/80/68 +f 80/80/68 81/81/69 38/38/32 +f 30/30/24 82/82/70 77/77/65 +f 79/79/67 38/38/32 39/39/33 +f 38/38/32 81/81/69 82/82/70 +f 38/38/32 82/82/70 30/30/24 +f 26/26/20 78/78/66 83/83/71 +f 79/79/67 39/39/33 84/84/72 +f 26/26/20 83/83/71 39/39/33 +f 39/39/33 83/83/71 84/84/72 +f 26/26/20 28/28/22 30/30/24 +f 26/26/20 30/30/24 78/78/66 +f 85/85/73 86/86/74 87/87/75 +f 85/85/73 87/87/75 88/88/76 +f 88/88/76 87/87/75 89/89/77 +f 2/2/78 6/6/78 5/5/78 +f 4/4/78 6/6/78 2/2/78 +f 3/3/79 5/5/79 8/8/79 +f 2/2/79 5/5/79 3/3/79 +f 4/4/80 7/7/80 6/6/80 +f 1/1/80 7/7/80 4/4/80 +f 90/90/81 89/89/82 91/91/83 +f 90/90/81 91/91/83 92/92/84 +f 90/90/81 92/92/84 93/93/85 +f 92/92/84 12/12/86 93/93/85 +f 93/93/85 12/12/86 14/14/87 +f 94/94/88 86/86/89 85/85/90 +f 95/95/91 11/11/92 96/96/93 +f 95/95/91 96/96/93 85/85/90 +f 85/85/90 96/96/93 94/94/88 +f 95/95/91 13/13/94 11/11/92 +f 89/89/95 90/90/95 88/88/95 +f 85/85/96 22/22/97 21/21/98 +f 85/85/96 21/21/98 52/52/46 +f 85/85/96 52/52/46 95/95/99 +f 52/52/46 59/59/53 95/95/99 +f 95/95/99 59/59/53 56/56/100 +f 32/32/101 35/35/102 88/88/76 +f 88/88/76 17/17/103 85/85/73 +f 17/17/103 23/23/104 85/85/73 +f 15/15/105 17/17/103 35/35/102 +f 15/15/105 35/35/102 34/34/106 +f 35/35/102 17/17/103 88/88/76 +f 23/23/104 22/22/107 85/85/73 +f 32/32/101 88/88/76 90/90/108 +f 30/30/109 32/32/110 90/90/111 +f 43/43/112 38/38/113 93/93/114 +f 93/93/114 38/38/113 90/90/111 +f 90/90/111 38/38/113 30/30/109 +f 56/56/115 93/93/116 95/95/117 +f 56/56/115 43/43/118 93/93/116 +f 56/56/50 44/44/38 43/43/37 +f 95/95/119 93/93/120 14/14/121 +f 95/95/119 14/14/121 13/13/122 +f 44/44/123 97/97/124 70/70/125 +f 70/70/125 97/97/124 98/98/126 +f 70/70/125 98/98/126 67/67/127 +f 67/67/128 98/98/128 99/99/128 +f 67/67/129 99/99/130 68/68/131 +f 68/68/131 99/99/130 100/100/132 +f 68/68/133 100/100/134 69/69/135 +f 69/69/135 100/100/134 101/101/136 +f 69/69/137 101/101/138 102/102/139 +f 69/69/137 102/102/139 44/44/140 +f 44/44/141 102/102/141 97/97/141 +f 75/75/142 103/103/143 71/71/144 +f 71/71/144 103/103/143 104/104/145 +f 71/71/146 104/104/147 72/72/148 +f 72/72/148 104/104/147 105/105/149 +f 75/75/150 76/76/151 103/103/152 +f 103/103/152 76/76/151 106/106/153 +f 73/73/154 105/105/155 107/107/156 +f 73/73/154 107/107/156 74/74/157 +f 74/74/158 107/107/159 76/76/160 +f 76/76/160 107/107/159 106/106/161 +f 73/73/162 72/72/162 105/105/162 +f 108/108/163 109/109/164 110/110/165 +f 110/110/165 109/109/164 111/111/166 +f 109/109/167 112/112/168 111/111/169 +f 111/111/169 112/112/168 113/113/170 +f 113/113/171 112/112/171 114/114/171 +f 114/114/172 115/115/173 113/113/174 +f 115/115/173 114/114/172 116/116/175 +f 115/115/176 116/116/177 117/117/178 +f 117/117/178 116/116/177 118/118/179 +f 117/117/180 118/118/181 119/119/182 +f 119/119/182 118/118/181 120/120/183 +f 120/120/184 110/110/185 119/119/186 +f 110/110/185 120/120/184 108/108/187 +f 109/109/188 108/108/189 35/35/190 +f 35/35/190 108/108/189 34/34/191 +f 34/34/191 108/108/189 120/120/192 +f 34/34/193 120/120/194 27/27/195 +f 120/120/194 118/118/196 27/27/195 +f 27/27/197 118/118/198 28/28/199 +f 28/28/199 118/118/198 116/116/200 +f 28/28/201 116/116/202 29/29/203 +f 116/116/202 114/114/204 29/29/203 +f 29/29/203 114/114/204 31/31/205 +f 114/114/204 112/112/206 31/31/205 +f 31/31/205 112/112/206 33/33/207 +f 33/33/207 112/112/206 109/109/188 +f 33/33/207 109/109/188 35/35/190 +f 121/121/208 122/122/209 123/123/210 +f 121/121/208 123/123/210 124/124/211 +f 124/124/212 123/123/213 125/125/214 +f 126/126/215 125/125/214 123/123/213 +f 125/125/216 126/126/217 127/127/218 +f 125/125/216 127/127/218 128/128/219 +f 128/128/220 127/127/220 129/129/220 +f 129/129/221 130/130/222 128/128/223 +f 129/129/221 131/131/224 130/130/222 +f 130/130/225 131/131/226 122/122/227 +f 122/122/227 121/121/228 130/130/225 +f 37/37/229 122/122/230 40/40/231 +f 40/40/231 122/122/230 46/46/232 +f 122/122/230 131/131/233 46/46/232 +f 46/46/234 131/131/235 45/45/235 +f 45/45/235 131/131/235 129/129/236 +f 129/129/237 127/127/238 45/45/239 +f 45/45/239 127/127/238 41/41/240 +f 127/127/238 126/126/241 41/41/240 +f 41/41/240 126/126/241 42/42/242 +f 42/42/242 126/126/241 123/123/243 +f 42/42/242 123/123/243 36/36/244 +f 36/36/245 123/123/246 37/37/247 +f 123/123/246 122/122/248 37/37/247 +f 132/132/249 133/133/250 134/134/251 +f 132/132/249 134/134/251 135/135/252 +f 135/135/253 134/134/254 136/136/255 +f 135/135/253 136/136/255 137/137/256 +f 137/137/257 136/136/258 138/138/259 +f 138/138/259 139/139/260 137/137/257 +f 139/139/261 138/138/262 140/140/263 +f 139/139/261 140/140/263 141/141/264 +f 141/141/265 140/140/266 142/142/267 +f 141/141/265 142/142/267 143/143/268 +f 142/142/269 132/132/270 143/143/271 +f 132/132/270 142/142/269 133/133/272 +f 133/133/273 142/142/274 78/78/275 +f 78/78/275 142/142/274 83/83/276 +f 83/83/277 142/142/278 140/140/279 +f 83/83/277 140/140/279 84/84/280 +f 84/84/280 140/140/279 79/79/281 +f 140/140/279 138/138/282 79/79/281 +f 79/79/281 138/138/282 80/80/283 +f 80/80/284 138/138/285 136/136/286 +f 80/80/284 136/136/286 81/81/287 +f 81/81/287 136/136/286 82/82/288 +f 136/136/286 134/134/289 82/82/288 +f 82/82/288 134/134/289 77/77/290 +f 134/134/289 133/133/273 77/77/290 +f 77/77/290 133/133/273 78/78/275 +f 144/144/291 145/145/292 146/146/293 +f 146/146/293 145/145/292 147/147/294 +f 146/146/295 147/147/295 148/148/295 +f 148/148/296 147/147/296 149/149/296 +f 148/148/297 149/149/297 10/10/297 +f 150/150/298 10/10/298 149/149/298 +f 10/10/299 150/150/300 151/151/301 +f 151/151/301 150/150/300 152/152/302 +f 153/153/303 151/151/304 152/152/305 +f 153/153/303 154/154/306 151/151/304 +f 154/154/307 153/153/308 145/145/309 +f 154/154/307 145/145/309 144/144/310 +f 51/51/311 145/145/312 53/53/313 +f 145/145/312 153/153/314 53/53/313 +f 53/53/313 153/153/314 59/59/315 +f 153/153/314 152/152/316 59/59/315 +f 59/59/315 152/152/316 57/57/317 +f 57/57/317 152/152/316 150/150/318 +f 57/57/317 150/150/318 58/58/319 +f 58/58/319 150/150/318 149/149/320 +f 58/58/319 149/149/320 54/54/321 +f 54/54/321 149/149/320 55/55/322 +f 149/149/320 147/147/323 55/55/322 +f 55/55/322 147/147/323 49/49/324 +f 145/145/325 49/49/324 147/147/323 +f 49/49/324 145/145/325 51/51/326 +f 155/155/327 156/156/328 157/157/329 +f 158/158/330 157/157/329 156/156/328 +f 157/157/331 158/158/332 159/159/333 +f 159/159/333 158/158/332 160/160/334 +f 160/160/335 161/161/336 159/159/337 +f 160/160/335 162/162/338 161/161/336 +f 162/162/339 163/163/339 161/161/339 +f 163/163/340 162/162/340 164/164/340 +f 164/164/341 165/165/341 163/163/341 +f 165/165/342 164/164/342 166/166/342 +f 166/166/343 155/155/343 165/165/343 +f 155/155/344 166/166/344 156/156/344 +f 63/63/345 166/166/346 61/61/347 +f 166/166/346 164/164/348 61/61/347 +f 61/61/347 164/164/348 60/60/349 +f 60/60/350 164/164/351 62/62/352 +f 62/62/352 164/164/351 162/162/353 +f 62/62/354 162/162/355 66/66/356 +f 66/66/356 162/162/355 160/160/357 +f 66/66/358 160/160/359 65/65/360 +f 160/160/359 158/158/361 65/65/360 +f 65/65/360 158/158/361 64/64/362 +f 64/64/362 158/158/361 156/156/363 +f 64/64/362 156/156/363 63/63/345 +f 63/63/345 156/156/363 166/166/346 +f 167/167/364 168/168/364 169/169/364 +f 169/169/365 168/168/366 170/170/367 +f 169/169/365 170/170/367 171/171/368 +f 171/171/369 170/170/370 172/172/371 +f 172/172/371 173/173/372 171/171/369 +f 172/172/373 174/174/373 173/173/373 +f 173/173/374 174/174/375 175/175/376 +f 175/175/376 174/174/375 176/176/377 +f 175/175/378 176/176/379 177/177/380 +f 177/177/380 178/178/381 175/175/378 +f 178/178/382 177/177/383 167/167/384 +f 167/167/384 177/177/383 168/168/385 +f 17/17/386 168/168/387 177/177/388 +f 17/17/386 177/177/388 23/23/389 +f 23/23/390 177/177/391 24/24/392 +f 177/177/391 176/176/393 24/24/392 +f 24/24/392 176/176/393 19/19/394 +f 19/19/394 176/176/393 174/174/395 +f 19/19/394 174/174/395 20/20/396 +f 174/174/395 172/172/397 20/20/396 +f 20/20/396 172/172/397 25/25/398 +f 25/25/398 172/172/397 170/170/399 +f 25/25/398 170/170/399 16/16/400 +f 170/170/399 168/168/401 16/16/400 +f 168/168/401 17/17/402 16/16/400 +f 18/18/403 179/179/404 50/50/405 +f 50/50/405 179/179/404 180/180/406 +f 26/26/407 181/181/408 18/18/409 +f 18/18/409 181/181/408 179/179/410 +f 181/181/411 26/26/411 182/182/411 +f 39/39/412 183/183/413 182/182/414 +f 39/39/412 182/182/414 26/26/415 +f 183/183/416 39/39/416 47/47/416 +f 48/48/417 184/184/418 47/47/419 +f 47/47/419 184/184/418 183/183/420 +f 184/184/421 48/48/422 180/180/423 +f 180/180/423 48/48/422 50/50/424 +f 184/184/1 180/180/1 179/179/1 +f 181/181/1 182/182/1 183/183/1 +f 183/183/1 179/179/1 181/181/1 +f 183/183/1 184/184/1 179/179/1 +f 185/185/425 186/186/426 187/187/427 +f 187/187/427 186/186/426 188/188/428 +f 187/187/429 188/188/430 189/189/431 +f 189/189/431 188/188/430 190/190/432 +f 189/189/431 190/190/432 191/191/433 +f 191/191/433 190/190/432 192/192/434 +f 191/191/435 192/192/436 193/193/437 +f 194/194/438 193/193/437 192/192/436 +f 194/194/439 195/195/440 193/193/441 +f 196/196/442 195/195/440 194/194/439 +f 196/196/443 197/197/444 195/195/445 +f 198/198/446 197/197/444 196/196/443 +f 199/199/447 200/200/448 198/198/446 +f 198/198/446 200/200/448 197/197/444 +f 186/186/449 185/185/450 199/199/451 +f 199/199/451 185/185/450 200/200/452 +f 190/190/432 201/201/453 192/192/434 +f 188/188/430 202/202/454 190/190/432 +f 186/186/426 203/203/455 202/202/456 +f 186/186/426 202/202/456 188/188/428 +f 199/199/451 203/203/457 186/186/449 +f 196/196/443 204/204/458 198/198/446 +f 194/194/439 204/204/459 196/196/442 +f 194/194/439 205/205/460 204/204/459 +f 201/201/461 205/205/462 192/192/436 +f 192/192/436 205/205/462 194/194/438 +f 206/206/463 205/205/464 201/201/465 +f 205/205/464 206/206/463 204/204/466 +f 203/203/467 207/207/468 202/202/469 +f 202/202/469 208/208/470 190/190/471 +f 190/190/471 208/208/470 201/201/465 +f 201/201/465 208/208/470 206/206/463 +f 198/198/472 209/209/473 199/199/474 +f 199/199/474 209/209/473 203/203/467 +f 202/202/469 207/207/468 208/208/470 +f 204/204/466 206/206/463 198/198/472 +f 206/206/463 209/209/473 198/198/472 +f 203/203/467 209/209/473 207/207/468 +f 206/206/463 210/210/475 209/209/473 +f 209/209/473 210/210/475 207/207/468 +f 207/207/468 210/210/475 208/208/470 +f 208/208/470 210/210/475 206/206/463 +f 211/211/476 212/212/477 213/213/478 +f 187/187/479 189/189/480 214/214/481 +f 213/213/478 187/187/479 214/214/481 +f 214/214/481 211/211/476 213/213/478 +f 185/185/482 187/187/479 213/213/478 +f 215/215/483 185/185/482 213/213/478 +f 212/212/477 215/215/483 213/213/478 +f 200/200/484 185/185/482 215/215/483 +f 216/216/485 215/215/483 212/212/477 +f 216/216/485 200/200/484 215/215/483 +f 197/197/486 200/200/484 216/216/485 +f 195/195/487 197/197/486 216/216/485 +f 217/217/488 195/195/487 216/216/485 +f 217/217/488 216/216/485 212/212/477 +f 193/193/489 195/195/487 217/217/488 +f 211/211/476 217/217/488 212/212/477 +f 218/218/490 193/193/489 217/217/488 +f 218/218/490 217/217/488 211/211/476 +f 191/191/491 193/193/489 218/218/490 +f 214/214/481 218/218/490 211/211/476 +f 214/214/481 191/191/491 218/218/490 +f 189/189/480 191/191/491 214/214/481 +f 219/219/492 220/220/493 221/221/494 +f 219/219/492 221/221/494 222/222/495 +f 222/222/496 221/221/497 223/223/498 +f 223/223/498 221/221/497 224/224/499 +f 223/223/500 224/224/501 225/225/502 +f 225/225/502 224/224/501 226/226/503 +f 225/225/504 226/226/505 227/227/506 +f 225/225/504 227/227/506 228/228/507 +f 228/228/508 227/227/509 229/229/510 +f 230/230/511 231/231/512 229/229/510 +f 230/230/511 229/229/510 227/227/509 +f 232/232/513 231/231/514 230/230/515 +f 232/232/513 233/233/516 231/231/514 +f 234/234/517 233/233/516 232/232/513 +f 235/235/518 233/233/516 234/234/517 +f 235/235/518 219/219/492 233/233/516 +f 220/220/493 219/219/492 235/235/518 +f 227/227/519 236/236/519 237/237/519 +f 226/226/505 236/236/520 227/227/506 +f 224/224/501 238/238/521 226/226/503 +f 221/221/497 238/238/522 224/224/499 +f 221/221/497 220/220/523 238/238/522 +f 232/232/513 239/239/524 234/234/517 +f 230/230/515 239/239/525 232/232/513 +f 230/230/526 237/237/527 239/239/528 +f 227/227/509 237/237/529 230/230/511 +f 239/239/528 237/237/527 240/240/530 +f 235/235/531 234/234/532 241/241/533 +f 235/235/531 241/241/533 220/220/534 +f 226/226/535 242/242/536 236/236/537 +f 236/236/537 242/242/536 237/237/527 +f 239/239/528 243/243/538 234/234/532 +f 234/234/532 243/243/538 241/241/533 +f 241/241/533 244/244/539 220/220/534 +f 220/220/534 244/244/539 238/238/540 +f 238/238/540 242/242/536 226/226/535 +f 240/240/530 243/243/538 239/239/528 +f 238/238/540 244/244/539 242/242/536 +f 242/242/536 245/245/541 237/237/527 +f 245/245/541 240/240/530 237/237/527 +f 240/240/530 245/245/541 243/243/538 +f 243/243/538 244/244/539 241/241/533 +f 242/242/536 244/244/539 245/245/541 +f 245/245/541 244/244/539 243/243/538 +f 223/223/542 225/225/543 246/246/544 +f 247/247/545 246/246/544 248/248/546 +f 223/223/542 246/246/544 247/247/545 +f 247/247/545 222/222/547 223/223/542 +f 219/219/548 222/222/547 247/247/545 +f 249/249/549 219/219/548 247/247/545 +f 249/249/549 247/247/545 248/248/546 +f 233/233/550 219/219/548 249/249/549 +f 250/250/551 233/233/550 249/249/549 +f 248/248/546 250/250/551 249/249/549 +f 231/231/552 233/233/550 250/250/551 +f 251/251/553 250/250/551 248/248/546 +f 251/251/553 231/231/552 250/250/551 +f 229/229/554 231/231/552 251/251/553 +f 252/252/555 229/229/554 251/251/553 +f 252/252/555 228/228/556 229/229/554 +f 252/252/555 251/251/553 248/248/546 +f 225/225/543 228/228/556 252/252/555 +f 248/248/546 246/246/544 252/252/555 +f 246/246/544 225/225/543 252/252/555 +f 253/253/557 254/254/558 255/255/559 +f 253/253/557 256/256/560 257/257/561 +f 258/258/562 259/259/563 260/260/564 +f 261/261/565 262/262/566 263/263/567 +f 264/264/568 265/265/569 266/266/570 +f 258/258/562 267/267/571 265/265/569 +f 268/268/572 267/267/571 258/258/562 +f 253/253/557 255/255/559 262/262/566 +f 258/258/562 265/265/569 264/264/568 +f 260/260/564 268/268/572 258/258/562 +f 263/263/567 259/259/563 261/261/565 +f 261/261/565 259/259/563 258/258/562 +f 253/253/557 262/262/566 261/261/565 +f 257/257/561 254/254/558 253/253/557 +f 266/266/570 256/256/560 264/264/568 +f 264/264/568 256/256/560 253/253/557 +f 269/269/573 270/270/574 271/271/575 +f 269/269/573 272/272/576 270/270/574 +f 269/269/573 271/271/575 273/273/577 +f 274/274/578 271/271/579 275/275/580 +f 275/275/580 271/271/579 270/270/581 +f 275/275/582 270/270/583 276/276/584 +f 275/275/582 276/276/584 277/277/585 +f 277/277/586 276/276/587 278/278/588 +f 277/277/586 278/278/588 279/279/589 +f 279/279/590 278/278/591 280/280/592 +f 279/279/593 280/280/594 281/281/595 +f 281/281/595 280/280/594 273/273/596 +f 281/281/595 273/273/596 282/282/597 +f 282/282/597 273/273/596 283/283/598 +f 282/282/599 283/283/600 274/274/601 +f 274/274/601 283/283/600 271/271/602 +f 254/254/603 274/274/604 255/255/605 +f 255/255/605 274/274/604 275/275/606 +f 255/255/605 275/275/606 262/262/607 +f 262/262/607 275/275/606 263/263/608 +f 263/263/608 275/275/606 277/277/609 +f 263/263/608 277/277/609 259/259/610 +f 259/259/610 277/277/609 260/260/611 +f 260/260/611 277/277/609 268/268/612 +f 268/268/612 277/277/609 279/279/613 +f 268/268/612 279/279/613 267/267/614 +f 267/267/614 279/279/613 265/265/615 +f 265/265/615 279/279/613 281/281/616 +f 265/265/615 281/281/616 266/266/617 +f 266/266/617 281/281/616 282/282/618 +f 266/266/617 282/282/618 256/256/619 +f 256/256/619 282/282/618 257/257/620 +f 257/257/620 282/282/618 274/274/604 +f 257/257/620 274/274/604 254/254/603 +f 261/261/621 258/258/622 284/284/623 +f 284/284/623 258/258/622 285/285/624 +f 253/253/625 261/261/626 286/286/627 +f 286/286/627 261/261/626 284/284/628 +f 264/264/629 253/253/630 287/287/631 +f 287/287/631 253/253/630 286/286/632 +f 258/258/633 264/264/634 285/285/635 +f 285/285/635 264/264/634 287/287/636 +f 284/284/1 285/285/1 286/286/1 +f 286/286/1 285/285/1 287/287/1 +f 276/276/637 270/270/637 272/272/637 +f 276/276/587 272/272/638 278/278/588 +f 278/278/639 272/272/639 269/269/639 +f 278/278/591 269/269/640 280/280/592 +f 280/280/641 269/269/641 273/273/641 +f 283/283/642 273/273/577 271/271/575 +f 288/288/79 289/289/79 290/290/79 +f 289/289/79 288/288/79 291/291/79 +f 291/291/79 288/288/79 292/292/79 +f 291/291/79 292/292/79 293/293/79 +f 294/294/79 295/295/79 296/296/79 +f 297/297/79 298/298/79 299/299/79 +f 293/293/79 300/300/79 301/301/79 +f 302/302/79 300/300/79 294/294/79 +f 303/303/79 300/300/79 304/304/79 +f 300/300/79 303/303/79 295/295/79 +f 300/300/79 305/305/79 304/304/79 +f 300/300/79 295/295/79 294/294/79 +f 304/304/79 305/305/79 306/306/79 +f 301/301/79 300/300/79 302/302/79 +f 307/307/79 306/306/79 305/305/79 +f 305/305/79 308/308/79 307/307/79 +f 294/294/79 296/296/79 309/309/79 +f 310/310/79 311/311/79 312/312/79 +f 300/300/79 293/293/79 292/292/79 +f 307/307/79 308/308/79 313/313/79 +f 308/308/79 314/314/79 313/313/79 +f 313/313/79 314/314/79 296/296/79 +f 315/315/79 299/299/79 316/316/79 +f 299/299/79 296/296/79 314/314/79 +f 299/299/79 314/314/79 316/316/79 +f 298/298/79 309/309/79 299/299/79 +f 317/317/79 315/315/79 318/318/79 +f 309/309/79 296/296/79 299/299/79 +f 309/309/79 298/298/79 319/319/79 +f 298/298/79 297/297/79 320/320/79 +f 317/317/79 318/318/79 321/321/79 +f 309/309/79 319/319/79 310/310/79 +f 321/321/79 318/318/79 322/322/79 +f 321/321/79 322/322/79 323/323/79 +f 322/322/79 324/324/79 323/323/79 +f 324/324/79 325/325/79 323/323/79 +f 323/323/79 325/325/79 326/326/79 +f 326/326/79 325/325/79 327/327/79 +f 325/325/79 328/328/79 327/327/79 +f 329/329/79 327/327/79 328/328/79 +f 316/316/79 318/318/79 315/315/79 +f 309/309/79 310/310/79 312/312/79 +f 330/330/80 331/331/80 332/332/80 +f 333/333/80 334/334/80 335/335/80 +f 334/334/80 336/336/80 337/337/80 +f 336/336/80 338/338/80 337/337/80 +f 338/338/80 336/336/80 339/339/80 +f 338/338/80 339/339/80 340/340/80 +f 341/341/80 338/338/80 340/340/80 +f 342/342/80 338/338/80 343/343/80 +f 344/344/80 345/345/80 342/342/80 +f 343/343/80 346/346/80 332/332/80 +f 345/345/80 344/344/80 347/347/80 +f 334/334/80 337/337/80 335/335/80 +f 346/346/80 348/348/80 332/332/80 +f 330/330/80 349/349/80 331/331/80 +f 345/345/80 347/347/80 349/349/80 +f 343/343/80 341/341/80 346/346/80 +f 348/348/80 330/330/80 332/332/80 +f 349/349/80 347/347/80 331/331/80 +f 345/345/80 338/338/80 342/342/80 +f 343/343/80 338/338/80 341/341/80 +f 348/348/80 346/346/80 350/350/80 +f 348/348/80 350/350/80 351/351/80 +f 351/351/80 352/352/80 348/348/80 +f 352/352/80 351/351/80 353/353/80 +f 354/354/79 355/355/79 356/356/79 +f 356/356/79 355/355/79 357/357/79 +f 356/356/79 357/357/79 358/358/79 +f 359/359/79 360/360/79 361/361/79 +f 361/361/79 360/360/79 357/357/79 +f 361/361/79 357/357/79 355/355/79 +f 359/359/643 361/361/644 362/362/645 +f 362/362/645 361/361/644 328/328/646 +f 328/328/646 363/363/647 362/362/645 +f 331/331/648 347/347/649 364/364/650 +f 364/364/650 347/347/649 365/365/651 +f 366/366/80 367/367/80 368/368/80 +f 366/366/80 365/365/80 367/367/80 +f 366/366/80 364/364/80 365/365/80 +f 368/368/80 367/367/80 369/369/80 +f 364/364/80 366/366/80 370/370/80 +f 371/371/652 372/372/653 373/373/654 +f 371/371/652 374/374/655 375/375/656 +f 375/375/656 372/372/653 371/371/652 +f 376/376/657 371/371/652 377/377/658 +f 378/378/659 373/373/654 379/379/660 +f 371/371/652 380/380/661 381/381/662 +f 371/371/652 381/381/662 377/377/658 +f 382/382/663 380/380/661 371/371/652 +f 382/382/663 371/371/652 378/378/659 +f 371/371/652 373/373/654 378/378/659 +f 383/383/664 384/384/665 385/385/666 +f 383/383/664 385/385/666 386/386/667 +f 386/386/667 385/385/666 387/387/668 +f 388/388/669 386/386/667 389/389/670 +f 389/389/670 386/386/667 387/387/668 +f 389/389/670 387/387/668 390/390/671 +f 390/390/671 387/387/668 391/391/672 +f 392/392/673 393/393/674 394/394/675 +f 348/348/676 392/392/673 394/394/675 +f 352/352/677 395/395/678 348/348/676 +f 348/348/676 395/395/678 392/392/673 +f 396/396/679 352/352/677 353/353/680 +f 395/395/678 352/352/677 397/397/681 +f 397/397/681 352/352/677 396/396/679 +f 353/353/680 398/398/682 396/396/679 +f 398/398/682 353/353/680 399/399/683 +f 399/399/683 353/353/680 400/400/684 +f 353/353/680 351/351/685 400/400/684 +f 400/400/684 351/351/685 401/401/686 +f 401/401/686 351/351/685 350/350/687 +f 401/401/686 350/350/687 309/309/688 +f 309/309/688 350/350/687 346/346/689 +f 309/309/688 346/346/689 294/294/690 +f 294/294/690 346/346/689 341/341/691 +f 294/294/690 341/341/691 302/302/692 +f 302/302/692 341/341/691 340/340/693 +f 302/302/692 340/340/693 301/301/694 +f 301/301/694 340/340/693 339/339/695 +f 301/301/694 339/339/695 293/293/696 +f 293/293/696 339/339/695 336/336/697 +f 293/293/696 336/336/697 291/291/698 +f 291/291/698 336/336/697 334/334/699 +f 291/291/698 334/334/699 289/289/700 +f 289/289/700 334/334/699 333/333/701 +f 289/289/700 333/333/701 290/290/702 +f 290/290/702 333/333/701 335/335/703 +f 290/290/702 335/335/703 288/288/704 +f 288/288/704 335/335/703 337/337/705 +f 288/288/704 337/337/705 292/292/706 +f 292/292/706 337/337/705 338/338/707 +f 292/292/706 338/338/707 300/300/708 +f 386/386/709 388/388/669 402/402/710 +f 386/386/709 402/402/710 400/400/711 +f 400/400/711 402/402/710 399/399/712 +f 403/403/713 404/404/714 405/405/715 +f 405/405/715 404/404/714 406/406/716 +f 404/404/714 403/403/713 407/407/717 +f 407/407/717 403/403/713 408/408/718 +f 338/338/707 345/345/719 300/300/708 +f 300/300/708 345/345/719 409/409/720 +f 305/305/721 300/300/708 410/410/722 +f 410/410/722 300/300/708 409/409/720 +f 410/410/722 409/409/720 406/406/716 +f 406/406/716 409/409/720 405/405/715 +f 411/411/723 412/412/724 407/407/725 +f 411/411/723 407/407/725 408/408/726 +f 412/412/724 411/411/723 413/413/727 +f 412/412/724 413/413/727 360/360/728 +f 358/358/729 357/357/729 414/414/729 +f 414/414/729 357/357/729 415/415/729 +f 414/414/1 416/416/1 358/358/1 +f 358/358/1 416/416/1 356/356/1 +f 417/417/80 418/418/80 419/419/80 +f 419/419/80 418/418/80 394/394/80 +f 413/413/80 420/420/80 421/421/80 +f 421/421/80 383/383/80 413/413/80 +f 386/386/80 400/400/80 401/401/80 +f 413/413/80 383/383/80 415/415/80 +f 415/415/80 383/383/80 416/416/80 +f 415/415/80 416/416/80 414/414/80 +f 416/416/80 383/383/80 386/386/80 +f 386/386/80 401/401/80 416/416/80 +f 422/422/80 423/423/80 424/424/80 +f 424/424/80 423/423/80 420/420/80 +f 413/413/80 424/424/80 420/420/80 +f 425/425/80 426/426/80 422/422/80 +f 422/422/80 426/426/80 423/423/80 +f 417/417/80 419/419/80 427/427/80 +f 427/427/80 419/419/80 428/428/80 +f 427/427/80 428/428/80 425/425/80 +f 425/425/80 428/428/80 426/426/80 +f 314/314/730 429/429/731 430/430/732 +f 314/314/730 430/430/732 316/316/733 +f 316/316/733 430/430/732 318/318/734 +f 318/318/734 430/430/732 431/431/735 +f 318/318/734 431/431/735 322/322/736 +f 322/322/736 431/431/735 432/432/737 +f 322/322/736 432/432/737 324/324/738 +f 324/324/738 432/432/737 363/363/647 +f 324/324/738 363/363/647 325/325/739 +f 433/433/740 429/429/731 308/308/741 +f 308/308/741 429/429/731 314/314/730 +f 407/407/79 412/412/79 362/362/79 +f 407/407/79 362/362/79 404/404/79 +f 433/433/79 410/410/79 406/406/79 +f 434/434/79 363/363/79 432/432/79 +f 434/434/79 432/432/79 435/435/79 +f 436/436/79 363/363/79 434/434/79 +f 363/363/79 436/436/79 362/362/79 +f 362/362/79 436/436/79 437/437/79 +f 362/362/79 438/438/79 404/404/79 +f 438/438/79 439/439/79 404/404/79 +f 404/404/79 439/439/79 440/440/79 +f 432/432/79 431/431/79 435/435/79 +f 435/435/79 431/431/79 441/441/79 +f 441/441/79 431/431/79 430/430/79 +f 437/437/79 438/438/79 362/362/79 +f 404/404/79 440/440/79 442/442/79 +f 433/433/79 406/406/79 404/404/79 +f 433/433/79 404/404/79 442/442/79 +f 429/429/79 433/433/79 443/443/79 +f 441/441/79 430/430/79 444/444/79 +f 444/444/79 430/430/79 429/429/79 +f 444/444/79 429/429/79 443/443/79 +f 442/442/79 443/443/79 433/433/79 +f 422/422/742 445/445/743 425/425/744 +f 425/425/744 445/445/743 446/446/745 +f 425/425/744 446/446/745 427/427/746 +f 427/427/746 446/446/745 447/447/747 +f 427/427/746 447/447/747 417/417/748 +f 417/417/748 447/447/747 448/448/749 +f 417/417/748 448/448/749 418/418/750 +f 418/418/750 448/448/749 449/449/751 +f 330/330/752 418/418/750 449/449/751 +f 449/449/751 450/450/753 330/330/752 +f 330/330/752 450/450/753 349/349/754 +f 424/424/755 445/445/743 422/422/742 +f 405/405/80 409/409/80 450/450/80 +f 451/451/80 411/411/80 408/408/80 +f 451/451/80 452/452/80 453/453/80 +f 451/451/80 408/408/80 403/403/80 +f 451/451/80 403/403/80 454/454/80 +f 451/451/80 454/454/80 452/452/80 +f 453/453/80 455/455/80 451/451/80 +f 451/451/80 455/455/80 445/445/80 +f 456/456/80 457/457/80 405/405/80 +f 405/405/80 457/457/80 403/403/80 +f 403/403/80 457/457/80 454/454/80 +f 445/445/80 455/455/80 458/458/80 +f 445/445/80 458/458/80 446/446/80 +f 459/459/80 448/448/80 460/460/80 +f 450/450/80 449/449/80 459/459/80 +f 461/461/80 462/462/80 450/450/80 +f 460/460/80 448/448/80 447/447/80 +f 460/460/80 447/447/80 463/463/80 +f 463/463/80 447/447/80 446/446/80 +f 463/463/80 446/446/80 458/458/80 +f 448/448/80 459/459/80 449/449/80 +f 459/459/80 461/461/80 450/450/80 +f 450/450/80 462/462/80 405/405/80 +f 405/405/80 462/462/80 456/456/80 +f 464/464/756 460/460/757 463/463/758 +f 460/460/757 464/464/756 465/465/759 +f 460/460/757 465/465/759 459/459/760 +f 459/459/760 465/465/759 466/466/761 +f 459/459/760 466/466/761 467/467/762 +f 459/459/760 467/467/762 461/461/763 +f 461/461/764 467/467/765 462/462/766 +f 467/467/765 468/468/767 462/462/766 +f 468/468/767 469/469/768 462/462/766 +f 462/462/766 469/469/768 456/456/769 +f 456/456/769 469/469/768 470/470/770 +f 456/456/769 470/470/770 457/457/771 +f 457/457/771 470/470/770 471/471/772 +f 457/457/771 471/471/772 454/454/773 +f 471/471/772 472/472/774 454/454/773 +f 454/454/773 472/472/774 452/452/775 +f 452/452/775 472/472/774 453/453/776 +f 453/453/776 472/472/774 473/473/777 +f 453/453/776 473/473/777 455/455/778 +f 455/455/778 473/473/777 474/474/779 +f 455/455/778 474/474/779 458/458/780 +f 474/474/779 475/475/781 458/458/780 +f 458/458/780 475/475/781 463/463/758 +f 475/475/781 464/464/756 463/463/758 +f 476/476/782 439/439/783 438/438/784 +f 476/476/782 438/438/784 477/477/785 +f 477/477/786 438/438/787 437/437/788 +f 477/477/786 437/437/788 478/478/789 +f 478/478/789 437/437/788 436/436/790 +f 478/478/789 436/436/790 479/479/791 +f 479/479/791 436/436/790 434/434/792 +f 479/479/791 434/434/792 480/480/793 +f 480/480/793 434/434/792 435/435/794 +f 480/480/793 435/435/794 481/481/795 +f 481/481/795 435/435/794 441/441/796 +f 481/481/795 441/441/796 482/482/797 +f 482/482/797 441/441/796 444/444/798 +f 482/482/797 444/444/798 483/483/799 +f 483/483/799 444/444/798 443/443/800 +f 483/483/799 443/443/800 484/484/801 +f 484/484/801 443/443/800 442/442/802 +f 484/484/801 442/442/802 485/485/803 +f 485/485/803 442/442/802 440/440/804 +f 485/485/803 440/440/804 486/486/805 +f 486/486/805 440/440/804 439/439/783 +f 486/486/805 439/439/783 476/476/782 +f 413/413/806 411/411/807 424/424/808 +f 424/424/808 411/411/807 451/451/809 +f 412/412/810 360/360/811 362/362/812 +f 362/362/812 360/360/811 359/359/813 +f 487/487/814 299/299/815 488/488/816 +f 299/299/815 487/487/814 297/297/817 +f 489/489/818 297/297/817 487/487/814 +f 490/490/819 297/297/817 489/489/818 +f 297/297/817 490/490/819 320/320/820 +f 491/491/821 320/320/820 490/490/819 +f 320/320/820 491/491/821 492/492/822 +f 492/492/822 298/298/823 320/320/820 +f 493/493/824 494/494/825 326/326/826 +f 326/326/826 494/494/825 323/323/827 +f 495/495/828 323/323/827 494/494/825 +f 323/323/827 495/495/828 496/496/829 +f 496/496/829 321/321/830 323/323/827 +f 321/321/830 496/496/829 497/497/831 +f 498/498/832 317/317/833 497/497/831 +f 497/497/831 317/317/833 321/321/830 +f 317/317/834 498/498/835 315/315/836 +f 315/315/836 498/498/835 499/499/837 +f 315/315/838 499/499/837 299/299/839 +f 299/299/839 499/499/837 488/488/840 +f 298/298/823 492/492/822 500/500/841 +f 298/298/823 500/500/841 319/319/842 +f 319/319/842 500/500/841 501/501/843 +f 319/319/842 501/501/843 310/310/844 +f 310/310/844 501/501/843 502/502/845 +f 502/502/845 503/503/846 310/310/847 +f 310/310/847 503/503/846 311/311/848 +f 311/311/848 503/503/846 504/504/849 +f 328/328/850 361/361/851 329/329/852 +f 329/329/852 361/361/851 355/355/853 +f 329/329/852 355/355/853 311/311/854 +f 329/329/855 505/505/856 327/327/857 +f 327/327/857 505/505/856 506/506/858 +f 327/327/859 506/506/860 507/507/861 +f 327/327/859 507/507/861 326/326/826 +f 326/326/826 507/507/861 493/493/824 +f 508/508/862 509/509/863 510/510/864 +f 511/511/865 508/508/862 510/510/864 +f 511/511/865 512/512/866 513/513/867 +f 510/510/864 514/514/868 512/512/866 +f 511/511/865 510/510/864 512/512/866 +f 511/511/865 513/513/867 515/515/869 +f 295/295/870 516/516/871 296/296/872 +f 296/296/872 516/516/871 517/517/873 +f 296/296/874 517/517/875 518/518/876 +f 296/296/874 518/518/876 313/313/877 +f 313/313/877 518/518/876 519/519/878 +f 520/520/879 307/307/880 519/519/881 +f 519/519/881 307/307/880 313/313/882 +f 307/307/883 520/520/884 521/521/885 +f 307/307/883 521/521/885 306/306/886 +f 521/521/887 522/522/888 306/306/889 +f 306/306/889 522/522/888 304/304/890 +f 304/304/891 522/522/892 523/523/893 +f 304/304/891 523/523/893 303/303/894 +f 303/303/895 523/523/896 295/295/897 +f 295/295/897 523/523/896 516/516/898 +f 516/516/79 520/520/79 517/517/79 +f 517/517/79 520/520/79 519/519/79 +f 521/521/79 520/520/79 516/516/79 +f 518/518/79 517/517/79 519/519/79 +f 521/521/79 516/516/79 522/522/79 +f 522/522/79 516/516/79 523/523/79 +f 394/394/675 418/418/750 348/348/676 +f 348/348/676 418/418/750 330/330/752 +f 524/524/899 428/428/900 419/419/901 +f 428/428/900 524/524/899 525/525/902 +f 428/428/900 525/525/902 526/526/903 +f 527/527/904 426/426/905 428/428/900 +f 527/527/904 428/428/900 526/526/903 +f 426/426/905 527/527/904 528/528/906 +f 529/529/907 423/423/908 528/528/906 +f 528/528/906 423/423/908 426/426/905 +f 423/423/908 529/529/907 530/530/909 +f 423/423/908 530/530/909 420/420/910 +f 420/420/910 530/530/909 531/531/911 +f 420/420/912 531/531/911 532/532/913 +f 420/420/912 532/532/913 421/421/914 +f 421/421/914 532/532/913 533/533/915 +f 413/413/727 357/357/916 360/360/728 +f 534/534/917 421/421/914 533/533/915 +f 357/357/916 413/413/727 415/415/918 +f 383/383/919 421/421/914 534/534/917 +f 534/534/917 384/384/665 383/383/919 +f 533/533/915 535/535/920 534/534/917 +f 505/505/921 329/329/852 311/311/854 +f 311/311/854 504/504/922 505/505/921 +f 424/424/755 451/451/923 445/445/743 +f 328/328/646 325/325/739 363/363/647 +f 394/394/924 393/393/925 419/419/926 +f 419/419/926 393/393/925 536/536/927 +f 419/419/928 536/536/929 524/524/930 +f 332/332/931 366/366/932 343/343/933 +f 343/343/933 366/366/932 368/368/934 +f 343/343/935 368/368/936 342/342/937 +f 342/342/937 368/368/936 369/369/938 +f 369/369/939 367/367/940 342/342/941 +f 342/342/941 367/367/940 344/344/942 +f 331/331/943 364/364/944 370/370/945 +f 331/331/943 370/370/945 332/332/946 +f 332/332/946 370/370/945 366/366/947 +f 537/537/948 389/389/949 390/390/950 +f 538/538/951 539/539/952 537/537/948 +f 537/537/948 539/539/952 389/389/949 +f 540/540/953 541/541/954 542/542/955 +f 542/542/955 541/541/954 543/543/956 +f 544/544/957 542/542/955 543/543/956 +f 544/544/957 545/545/958 542/542/955 +f 544/544/957 396/396/679 545/545/958 +f 396/396/679 544/544/957 397/397/681 +f 539/539/952 538/538/951 540/540/959 +f 540/540/959 538/538/951 546/546/960 +f 547/547/961 539/539/962 542/542/963 +f 542/542/963 539/539/962 540/540/964 +f 548/548/965 549/549/966 550/550/967 +f 550/550/967 549/549/966 551/551/968 +f 550/550/967 534/534/917 535/535/920 +f 551/551/968 534/534/917 550/550/967 +f 552/552/969 553/553/970 387/387/971 +f 387/387/971 553/553/970 391/391/972 +f 549/549/973 554/554/974 552/552/975 +f 552/552/975 554/554/974 553/553/976 +f 552/552/977 551/551/978 549/549/979 +f 549/549/980 548/548/980 554/554/980 +f 546/546/981 541/541/954 540/540/953 +f 555/555/982 509/509/863 556/556/983 +f 557/557/984 555/555/982 556/556/983 +f 558/558/985 509/509/863 555/555/982 +f 507/507/986 557/557/984 493/493/987 +f 493/493/987 557/557/984 556/556/983 +f 505/505/988 558/558/985 506/506/860 +f 506/506/860 558/558/985 555/555/982 +f 506/506/860 555/555/982 557/557/984 +f 506/506/860 557/557/984 507/507/861 +f 496/496/989 559/559/990 497/497/991 +f 494/494/992 493/493/987 560/560/993 +f 494/494/992 560/560/993 495/495/994 +f 496/496/989 495/495/994 561/561/995 +f 496/496/989 561/561/995 559/559/990 +f 497/497/991 559/559/990 562/562/996 +f 497/497/991 562/562/996 498/498/997 +f 498/498/997 562/562/996 563/563/998 +f 493/493/987 556/556/983 560/560/993 +f 495/495/994 560/560/993 561/561/995 +f 559/559/990 561/561/995 562/562/996 +f 560/560/993 556/556/983 508/508/862 +f 560/560/993 508/508/862 561/561/995 +f 561/561/995 511/511/999 562/562/996 +f 556/556/983 509/509/863 508/508/862 +f 561/561/995 508/508/862 511/511/999 +f 562/562/1000 511/511/1000 563/563/1000 +f 563/563/1001 511/511/865 515/515/869 +f 505/505/921 504/504/922 558/558/985 +f 558/558/985 504/504/922 564/564/1002 +f 558/558/985 564/564/1002 509/509/863 +f 509/509/863 564/564/1002 510/510/864 +f 498/498/835 563/563/1003 499/499/837 +f 488/488/840 499/499/837 565/565/1004 +f 565/565/1004 499/499/837 563/563/1003 +f 565/565/1004 563/563/1003 515/515/1005 +f 503/503/846 564/564/1002 504/504/922 +f 489/489/818 566/566/1006 490/490/1007 +f 490/490/1007 567/567/1008 491/491/1009 +f 488/488/1010 565/565/1011 487/487/1012 +f 489/489/818 487/487/814 566/566/1006 +f 490/490/1007 566/566/1006 567/567/1008 +f 491/491/1009 567/567/1008 568/568/1013 +f 491/491/1009 568/568/1013 492/492/822 +f 492/492/822 568/568/1013 569/569/1014 +f 565/565/1011 515/515/1015 487/487/1012 +f 487/487/1012 515/515/1015 513/513/1016 +f 487/487/1012 513/513/1016 566/566/1006 +f 566/566/1006 513/513/1016 567/567/1008 +f 568/568/1013 567/567/1008 512/512/866 +f 568/568/1013 512/512/866 569/569/1014 +f 569/569/1014 512/512/866 514/514/868 +f 567/567/1008 513/513/1016 512/512/866 +f 503/503/846 502/502/845 570/570/1017 +f 503/503/846 570/570/1017 564/564/1002 +f 564/564/1002 570/570/1017 571/571/1018 +f 564/564/1002 571/571/1018 510/510/864 +f 510/510/864 571/571/1018 514/514/868 +f 492/492/822 569/569/1014 500/500/841 +f 501/501/843 500/500/1019 569/569/1020 +f 571/571/1021 501/501/843 569/569/1020 +f 571/571/1021 569/569/1020 514/514/1022 +f 570/570/1017 502/502/845 501/501/843 +f 571/571/1021 570/570/1017 501/501/843 +f 535/535/920 533/533/1023 379/379/660 +f 379/379/660 533/533/1023 572/572/1024 +f 379/379/660 572/572/1024 378/378/659 +f 529/529/1025 573/573/1026 574/574/1027 +f 530/530/909 529/529/1025 574/574/1027 +f 530/530/909 574/574/1027 531/531/911 +f 532/532/913 531/531/911 574/574/1027 +f 572/572/1024 532/532/913 574/574/1027 +f 572/572/1024 574/574/1027 378/378/659 +f 378/378/659 574/574/1027 573/573/1028 +f 533/533/1023 532/532/913 572/572/1024 +f 379/379/660 575/575/1029 535/535/920 +f 535/535/920 575/575/1029 550/550/967 +f 525/525/902 524/524/1030 576/576/1031 +f 525/525/902 576/576/1031 526/526/903 +f 524/524/1030 577/577/1032 576/576/1031 +f 527/527/904 526/526/903 578/578/1033 +f 527/527/904 578/578/1033 528/528/1034 +f 528/528/1034 578/578/1033 573/573/1026 +f 528/528/1034 573/573/1026 529/529/1025 +f 576/576/1031 579/579/1035 380/380/1036 +f 576/576/1031 380/380/1036 526/526/903 +f 526/526/903 380/380/1036 578/578/1033 +f 577/577/1032 580/580/1037 576/576/1031 +f 576/576/1031 580/580/1037 579/579/1035 +f 578/578/1033 380/380/1036 382/382/663 +f 578/578/1033 382/382/663 573/573/1028 +f 580/580/1038 381/381/1038 579/579/1038 +f 579/579/1035 381/381/1039 380/380/1036 +f 382/382/663 378/378/659 573/573/1028 +f 373/373/654 581/581/1040 379/379/660 +f 379/379/660 581/581/1040 575/575/1029 +f 575/575/1029 581/581/1041 548/548/965 +f 575/575/1029 548/548/965 550/550/967 +f 393/393/925 582/582/1042 583/583/1043 +f 536/536/927 393/393/925 583/583/1043 +f 524/524/930 536/536/929 577/577/1032 +f 577/577/1032 536/536/929 583/583/1043 +f 580/580/1037 583/583/1043 582/582/1042 +f 580/580/1037 582/582/1042 381/381/662 +f 577/577/1032 583/583/1043 580/580/1037 +f 581/581/1044 584/584/1045 554/554/974 +f 372/372/1046 584/584/1047 581/581/1040 +f 554/554/974 548/548/1048 581/581/1044 +f 581/581/1040 373/373/654 372/372/1046 +f 392/392/673 585/585/1049 393/393/925 +f 397/397/681 586/586/1050 395/395/678 +f 395/395/678 586/586/1050 587/587/1051 +f 395/395/678 587/587/1051 392/392/673 +f 393/393/925 585/585/1049 582/582/1042 +f 392/392/673 587/587/1051 585/585/1049 +f 586/586/1050 376/376/1052 587/587/1051 +f 587/587/1051 376/376/1052 377/377/658 +f 585/585/1049 377/377/658 381/381/662 +f 585/585/1049 381/381/662 582/582/1042 +f 587/587/1051 377/377/658 585/585/1049 +f 372/372/1053 375/375/1054 588/588/1055 +f 372/372/1053 588/588/1055 584/584/1045 +f 584/584/1045 588/588/1055 553/553/976 +f 584/584/1045 553/553/976 554/554/974 +f 397/397/681 544/544/957 586/586/1050 +f 541/541/954 589/589/1056 543/543/956 +f 543/543/956 589/589/1056 590/590/1057 +f 543/543/956 590/590/1057 544/544/957 +f 586/586/1050 544/544/957 590/590/1057 +f 586/586/1050 590/590/1057 376/376/1052 +f 591/591/1058 588/588/1055 375/375/1054 +f 553/553/970 588/588/1055 591/591/1058 +f 553/553/970 591/591/1058 391/391/972 +f 590/590/1057 589/589/1056 371/371/1059 +f 590/590/1057 371/371/1059 376/376/1052 +f 541/541/954 546/546/960 589/589/1056 +f 390/390/1060 391/391/1061 591/591/1062 +f 390/390/1060 591/591/1062 374/374/1063 +f 374/374/1063 591/591/1062 375/375/1064 +f 374/374/1065 371/371/1059 589/589/1056 +f 374/374/1065 589/589/1056 592/592/1066 +f 592/592/1066 589/589/1056 538/538/951 +f 538/538/951 589/589/1056 546/546/960 +f 390/390/1060 374/374/1063 592/592/1066 +f 537/537/948 390/390/1060 592/592/1066 +f 538/538/951 537/537/948 592/592/1066 +f 551/551/978 552/552/977 593/593/1067 +f 384/384/665 534/534/917 593/593/1067 +f 593/593/1067 534/534/917 551/551/978 +f 385/385/666 384/384/665 593/593/1067 +f 593/593/1067 552/552/977 387/387/1068 +f 385/385/666 593/593/1067 387/387/1068 +f 594/594/1069 389/389/1070 547/547/1071 +f 547/547/1071 389/389/1070 539/539/1072 +f 389/389/670 594/594/1069 388/388/669 +f 595/595/1073 399/399/712 402/402/710 +f 595/595/1073 402/402/710 596/596/1074 +f 597/597/1075 595/595/1073 547/547/1071 +f 547/547/1071 595/595/1073 596/596/1074 +f 596/596/1074 594/594/1069 547/547/1071 +f 402/402/710 388/388/669 596/596/1074 +f 596/596/1074 388/388/669 594/594/1069 +f 547/547/961 542/542/963 597/597/1076 +f 597/597/1076 542/542/963 595/595/1077 +f 595/595/1077 542/542/963 398/398/1078 +f 595/595/1077 398/398/1078 399/399/1079 +f 542/542/963 545/545/1080 398/398/1078 +f 398/398/1078 545/545/1080 396/396/1081 +f 409/409/1082 345/345/1083 450/450/1084 +f 450/450/1084 345/345/1083 349/349/1085 +f 305/305/1086 410/410/1087 308/308/1088 +f 308/308/1088 410/410/1087 433/433/1089 +f 466/466/80 468/468/80 467/467/80 +f 468/468/80 470/470/80 469/469/80 +f 468/468/80 466/466/80 470/470/80 +f 470/470/80 465/465/80 464/464/80 +f 464/464/80 472/472/80 470/470/80 +f 475/475/80 472/472/80 464/464/80 +f 472/472/80 471/471/80 470/470/80 +f 474/474/80 472/472/80 475/475/80 +f 466/466/80 465/465/80 470/470/80 +f 472/472/80 474/474/80 473/473/80 +f 482/482/79 486/486/79 476/476/79 +f 484/484/79 486/486/79 483/483/79 +f 486/486/79 482/482/79 483/483/79 +f 481/481/79 482/482/79 480/480/79 +f 480/480/79 482/482/79 476/476/79 +f 480/480/79 476/476/79 479/479/79 +f 486/486/79 484/484/79 485/485/79 +f 476/476/79 477/477/79 479/479/79 +f 479/479/79 477/477/79 478/478/79 +f 344/344/1090 367/367/1091 347/347/1092 +f 347/347/1092 367/367/1091 365/365/1093 +f 354/354/1094 312/312/1095 355/355/1096 +f 355/355/1096 312/312/1095 311/311/1097 +f 312/312/1098 356/356/1099 416/416/1100 +f 356/356/1099 312/312/1098 354/354/1101 +f 312/312/1098 401/401/686 309/309/688 +f 401/401/686 312/312/1098 416/416/1100 +f 598/598/1102 599/599/1103 600/600/1104 +f 601/601/1105 602/602/1106 603/603/1107 +f 604/604/1108 605/605/1109 601/601/1105 +f 603/603/1107 602/602/1106 606/606/1110 +f 600/600/1104 607/607/1111 605/605/1109 +f 600/600/1104 599/599/1103 607/607/1111 +f 603/603/1107 608/608/1112 609/609/1113 +f 609/609/1113 608/608/1112 610/610/1114 +f 603/603/1107 606/606/1110 611/611/1115 +f 604/604/1108 601/601/1105 603/603/1107 +f 600/600/1104 605/605/1109 604/604/1108 +f 609/609/1113 610/610/1114 598/598/1102 +f 609/609/1113 598/598/1102 600/600/1104 +f 603/603/1107 611/611/1115 608/608/1112 +f 612/612/1116 613/613/1117 614/614/1118 +f 612/612/1116 615/615/1119 613/613/1117 +f 612/612/1116 616/616/1120 617/617/1121 +f 612/612/1116 614/614/1118 616/616/1120 +f 618/618/1122 619/619/1123 620/620/1124 +f 620/620/1124 619/619/1123 613/613/1125 +f 620/620/1126 613/613/1127 621/621/1128 +f 621/621/1128 613/613/1127 622/622/1129 +f 621/621/1130 622/622/1131 615/615/1132 +f 621/621/1130 615/615/1132 623/623/1133 +f 623/623/1134 615/615/1135 624/624/1136 +f 624/624/1136 615/615/1135 612/612/1137 +f 624/624/1138 612/612/1139 617/617/1140 +f 624/624/1138 617/617/1140 625/625/1141 +f 625/625/1141 617/617/1140 626/626/1142 +f 625/625/1141 626/626/1142 627/627/1143 +f 627/627/1143 626/626/1142 616/616/1144 +f 627/627/1143 616/616/1144 618/618/1145 +f 618/618/1145 616/616/1144 619/619/1146 +f 599/599/1147 618/618/1148 607/607/1149 +f 607/607/1149 618/618/1148 620/620/1150 +f 607/607/1149 620/620/1150 605/605/1151 +f 605/605/1151 620/620/1150 621/621/1152 +f 605/605/1151 621/621/1152 601/601/1153 +f 601/601/1153 621/621/1152 623/623/1154 +f 601/601/1153 623/623/1154 602/602/1155 +f 602/602/1155 623/623/1154 606/606/1156 +f 606/606/1156 623/623/1154 624/624/1157 +f 606/606/1156 624/624/1157 611/611/1158 +f 611/611/1158 624/624/1157 625/625/1159 +f 611/611/1158 625/625/1159 608/608/1160 +f 608/608/1160 625/625/1159 610/610/1161 +f 610/610/1161 625/625/1159 627/627/1162 +f 610/610/1161 627/627/1162 598/598/1163 +f 598/598/1163 627/627/1162 618/618/1148 +f 598/598/1163 618/618/1148 599/599/1147 +f 604/604/621 603/603/622 628/628/1164 +f 628/628/1164 603/603/622 629/629/1165 +f 600/600/625 604/604/626 630/630/1166 +f 630/630/1166 604/604/626 628/628/628 +f 609/609/629 600/600/1167 631/631/631 +f 631/631/631 600/600/1167 630/630/632 +f 603/603/633 609/609/634 629/629/635 +f 629/629/635 609/609/634 631/631/636 +f 628/628/1 629/629/1 630/630/1 +f 630/630/1 629/629/1 631/631/1 +f 619/619/1168 614/614/1168 613/613/1168 +f 622/622/1169 613/613/1117 615/615/1119 +f 626/626/1170 617/617/1121 616/616/1120 +f 616/616/1171 614/614/1171 619/619/1171 +f 632/632/1172 633/633/1173 634/634/1174 +f 635/635/1175 636/636/1176 637/637/1177 +f 638/638/1178 639/639/1179 640/640/1180 +f 637/637/1177 641/641/1181 642/642/1182 +f 643/643/1183 644/644/1184 645/645/1185 +f 637/637/1177 642/642/1182 635/635/1175 +f 632/632/1172 646/646/1186 647/647/1187 +f 637/637/1177 644/644/1184 643/643/1183 +f 638/638/1178 640/640/1180 637/637/1177 +f 637/637/1177 640/640/1180 641/641/1181 +f 632/632/1172 647/647/1187 638/638/1178 +f 638/638/1178 647/647/1187 639/639/1179 +f 634/634/1174 646/646/1186 632/632/1172 +f 645/645/1185 633/633/1173 643/643/1183 +f 643/643/1183 633/633/1173 632/632/1172 +f 637/637/1177 636/636/1176 644/644/1184 +f 648/648/1188 649/649/1189 650/650/1190 +f 651/651/1191 652/652/1192 650/650/1190 +f 650/650/1190 653/653/1193 651/651/1191 +f 650/650/1190 649/649/1189 653/653/1193 +f 654/654/1194 655/655/1195 648/648/1196 +f 654/654/1194 648/648/1196 656/656/1197 +f 656/656/1197 648/648/1196 650/650/1198 +f 656/656/1199 650/650/1200 657/657/1201 +f 657/657/1201 650/650/1200 658/658/1202 +f 657/657/1203 658/658/1204 652/652/1205 +f 657/657/1203 652/652/1205 659/659/1206 +f 659/659/1206 652/652/1205 651/651/1207 +f 659/659/1208 651/651/1209 660/660/1210 +f 659/659/1208 660/660/1210 661/661/1211 +f 661/661/1212 660/660/1213 662/662/1214 +f 661/661/1212 662/662/1214 663/663/1215 +f 663/663/1216 662/662/1217 655/655/1218 +f 663/663/1216 655/655/1218 654/654/1219 +f 634/634/1220 654/654/1221 646/646/1222 +f 646/646/1222 654/654/1221 647/647/1223 +f 647/647/1223 654/654/1221 656/656/1224 +f 647/647/1223 656/656/1224 639/639/1225 +f 639/639/1225 656/656/1224 657/657/1226 +f 639/639/1225 657/657/1226 640/640/1227 +f 640/640/1227 657/657/1226 641/641/1228 +f 641/641/1228 657/657/1226 642/642/1229 +f 642/642/1229 657/657/1226 659/659/1230 +f 642/642/1229 659/659/1230 635/635/1231 +f 635/635/1231 659/659/1230 636/636/1232 +f 636/636/1232 659/659/1230 644/644/1233 +f 644/644/1233 659/659/1230 661/661/1234 +f 644/644/1233 661/661/1234 645/645/1235 +f 645/645/1235 661/661/1234 663/663/1236 +f 645/645/1235 663/663/1236 633/633/1237 +f 633/633/1237 663/663/1236 654/654/1221 +f 633/633/1237 654/654/1221 634/634/1220 +f 638/638/621 637/637/1238 664/664/1239 +f 664/664/1239 637/637/1238 665/665/1240 +f 632/632/625 638/638/626 666/666/627 +f 666/666/627 638/638/626 664/664/628 +f 643/643/629 632/632/1241 667/667/631 +f 667/667/631 632/632/1241 666/666/632 +f 637/637/633 643/643/634 665/665/635 +f 665/665/635 643/643/634 667/667/636 +f 664/664/1 665/665/1 666/666/1 +f 666/666/1 665/665/1 667/667/1 +f 655/655/1242 649/649/1189 648/648/1188 +f 658/658/1243 650/650/1190 652/652/1192 +f 660/660/1244 651/651/1191 653/653/1193 +f 660/660/1213 653/653/1245 662/662/1214 +f 662/662/1246 653/653/1193 649/649/1189 +f 662/662/1217 649/649/1247 655/655/1218 +f 668/668/1248 669/669/1249 670/670/1250 +f 671/671/1251 672/672/1252 673/673/1253 +f 671/671/1251 674/674/1254 675/675/1255 +f 676/676/1256 677/677/1257 672/672/1252 +f 678/678/1258 679/679/1259 670/670/1250 +f 670/670/1250 669/669/1249 678/678/1258 +f 671/671/1251 675/675/1255 680/680/1260 +f 680/680/1260 675/675/1255 681/681/1261 +f 673/673/1253 674/674/1254 671/671/1251 +f 676/676/1256 672/672/1252 671/671/1251 +f 670/670/1250 679/679/1259 676/676/1256 +f 676/676/1256 679/679/1259 677/677/1257 +f 680/680/1260 681/681/1261 668/668/1248 +f 680/680/1260 668/668/1248 670/670/1250 +f 682/682/1262 683/683/1263 684/684/1264 +f 682/682/1262 685/685/1265 683/683/1263 +f 682/682/1262 686/686/1266 685/685/1265 +f 682/682/1262 687/687/1267 686/686/1266 +f 688/688/1268 689/689/1269 690/690/1270 +f 690/690/1271 689/689/1272 685/685/1273 +f 690/690/1271 685/685/1273 691/691/1274 +f 691/691/1274 685/685/1273 686/686/1275 +f 691/691/1276 686/686/1277 692/692/1278 +f 692/692/1278 686/686/1277 693/693/1279 +f 692/692/1280 693/693/1281 694/694/1282 +f 692/692/1280 694/694/1282 695/695/1283 +f 695/695/1284 694/694/1285 696/696/1286 +f 695/695/1284 696/696/1286 697/697/1287 +f 697/697/1288 696/696/1289 684/684/1290 +f 697/697/1288 684/684/1290 688/688/1291 +f 688/688/1268 684/684/1292 689/689/1269 +f 678/678/1293 690/690/1294 679/679/1295 +f 679/679/1295 690/690/1294 691/691/1296 +f 679/679/1295 691/691/1296 677/677/1297 +f 677/677/1297 691/691/1296 672/672/1298 +f 672/672/1298 691/691/1296 692/692/1299 +f 672/672/1298 692/692/1299 673/673/1300 +f 673/673/1300 692/692/1299 674/674/1301 +f 674/674/1301 692/692/1299 695/695/1302 +f 674/674/1301 695/695/1302 675/675/1303 +f 675/675/1303 695/695/1302 681/681/1304 +f 681/681/1304 695/695/1302 697/697/1305 +f 681/681/1304 697/697/1305 668/668/1306 +f 668/668/1306 697/697/1305 688/688/1307 +f 668/668/1306 688/688/1307 669/669/1308 +f 669/669/1308 688/688/1307 678/678/1293 +f 678/678/1293 688/688/1307 690/690/1294 +f 676/676/1309 671/671/1310 698/698/1311 +f 698/698/1311 671/671/1310 699/699/1312 +f 670/670/1313 676/676/1313 698/698/1313 +f 700/700/1314 670/670/1314 698/698/1314 +f 680/680/1315 670/670/1315 700/700/1315 +f 671/671/633 680/680/633 699/699/633 +f 699/699/1316 680/680/1316 700/700/1316 +f 698/698/1 699/699/1 700/700/1 +f 689/689/1317 683/683/1317 685/685/1317 +f 693/693/1318 686/686/1318 687/687/1318 +f 693/693/1281 687/687/1319 694/694/1282 +f 694/694/1320 687/687/1320 682/682/1320 +f 694/694/1285 682/682/1321 696/696/1286 +f 696/696/1322 682/682/1262 684/684/1264 +f 689/689/1323 684/684/1323 683/683/1323 +f 701/701/1324 702/702/1325 703/703/1326 +f 704/704/1327 705/705/1328 701/701/1324 +f 706/706/1329 707/707/1330 708/708/1331 +f 709/709/1332 710/710/1333 711/711/1334 +f 712/712/1335 713/713/1336 714/714/1337 +f 705/705/1328 702/702/1325 701/701/1324 +f 706/706/1329 710/710/1333 709/709/1332 +f 706/706/1329 708/708/1331 715/715/1338 +f 714/714/1337 713/713/1336 706/706/1329 +f 706/706/1329 713/713/1336 707/707/1330 +f 701/701/1324 703/703/1326 714/714/1337 +f 714/714/1337 703/703/1326 712/712/1335 +f 711/711/1334 704/704/1327 709/709/1332 +f 709/709/1332 704/704/1327 701/701/1324 +f 706/706/1329 715/715/1338 710/710/1333 +f 716/716/1339 717/717/1340 718/718/1341 +f 716/716/1339 719/719/1342 717/717/1340 +f 716/716/1339 720/720/1343 719/719/1342 +f 721/721/1344 720/720/1343 716/716/1339 +f 722/722/1345 723/723/1346 724/724/1347 +f 724/724/1347 723/723/1346 717/717/1348 +f 724/724/1347 717/717/1348 719/719/1349 +f 724/724/1347 719/719/1349 725/725/1350 +f 725/725/1350 719/719/1349 726/726/1351 +f 725/725/1352 726/726/1353 727/727/1354 +f 727/727/1354 726/726/1353 720/720/1355 +f 727/727/1356 720/720/1357 728/728/1358 +f 727/727/1356 728/728/1358 729/729/1359 +f 729/729/1360 728/728/1361 716/716/1362 +f 729/729/1360 716/716/1362 730/730/1363 +f 730/730/1363 716/716/1362 718/718/1364 +f 730/730/1363 718/718/1364 722/722/1365 +f 722/722/1365 718/718/1364 723/723/1366 +f 702/702/1367 722/722/1368 724/724/1369 +f 702/702/1367 724/724/1369 703/703/1370 +f 703/703/1370 724/724/1369 712/712/1371 +f 712/712/1371 724/724/1369 725/725/1372 +f 712/712/1371 725/725/1372 713/713/1373 +f 713/713/1373 725/725/1372 707/707/1374 +f 707/707/1374 725/725/1372 708/708/1375 +f 708/708/1375 725/725/1372 727/727/1376 +f 708/708/1375 727/727/1376 715/715/1377 +f 715/715/1377 727/727/1376 729/729/1378 +f 715/715/1377 729/729/1378 710/710/1379 +f 710/710/1379 729/729/1378 711/711/1380 +f 711/711/1380 729/729/1378 704/704/1381 +f 704/704/1381 729/729/1378 730/730/1382 +f 704/704/1381 730/730/1382 705/705/1383 +f 705/705/1383 730/730/1382 722/722/1368 +f 705/705/1383 722/722/1368 702/702/1367 +f 731/731/1384 706/706/1384 732/732/1384 +f 714/714/1385 706/706/1385 731/731/1385 +f 701/701/625 714/714/625 733/733/625 +f 733/733/1386 714/714/1386 731/731/1386 +f 709/709/1387 701/701/1388 732/732/1389 +f 732/732/1389 701/701/1388 733/733/1390 +f 706/706/1391 709/709/1391 732/732/1391 +f 733/733/1 731/731/1 732/732/1 +f 726/726/1392 719/719/1342 720/720/1343 +f 720/720/1357 721/721/1393 728/728/1358 +f 728/728/1394 721/721/1394 716/716/1394 +f 723/723/1395 718/718/1341 717/717/1340 +f 734/734/1396 735/735/1397 736/736/1398 +f 737/737/1399 738/738/1400 739/739/1401 +f 740/740/1402 741/741/1403 736/736/1398 +f 742/742/1404 743/743/1405 744/744/1406 +f 736/736/1398 741/741/1403 734/734/1396 +f 737/737/1399 745/745/1407 738/738/1400 +f 742/742/1404 746/746/1408 743/743/1405 +f 736/736/1398 735/735/1397 747/747/1409 +f 736/736/1398 747/747/1409 742/742/1404 +f 737/737/1399 739/739/1401 740/740/1402 +f 737/737/1399 740/740/1402 736/736/1398 +f 742/742/1404 744/744/1406 737/737/1399 +f 737/737/1399 744/744/1406 745/745/1407 +f 742/742/1404 747/747/1409 746/746/1408 +f 748/748/1410 749/749/1411 750/750/1412 +f 748/748/1410 751/751/1413 749/749/1411 +f 748/748/1410 752/752/1414 751/751/1413 +f 750/750/1412 753/753/1415 748/748/1410 +f 754/754/1416 750/750/1417 749/749/1418 +f 754/754/1416 749/749/1418 755/755/1419 +f 755/755/1419 749/749/1418 756/756/1420 +f 755/755/1419 756/756/1420 757/757/1421 +f 757/757/1422 756/756/1423 752/752/1424 +f 757/757/1422 752/752/1424 758/758/1425 +f 758/758/1425 752/752/1424 759/759/1426 +f 758/758/1427 759/759/1428 760/760/1429 +f 760/760/1429 759/759/1428 748/748/1430 +f 760/760/1431 748/748/1432 753/753/1433 +f 760/760/1431 753/753/1433 761/761/1434 +f 761/761/1435 753/753/1436 762/762/1437 +f 761/761/1435 762/762/1437 763/763/1438 +f 763/763/1439 762/762/1440 750/750/1441 +f 763/763/1439 750/750/1441 754/754/1442 +f 738/738/1443 754/754/1444 739/739/1445 +f 739/739/1445 754/754/1444 755/755/1446 +f 739/739/1445 755/755/1446 740/740/1447 +f 740/740/1447 755/755/1446 741/741/1448 +f 741/741/1448 755/755/1446 757/757/1449 +f 741/741/1448 757/757/1449 734/734/1450 +f 734/734/1450 757/757/1449 758/758/1451 +f 734/734/1450 758/758/1451 735/735/1452 +f 735/735/1452 758/758/1451 747/747/1453 +f 747/747/1453 758/758/1451 760/760/1454 +f 747/747/1453 760/760/1454 746/746/1455 +f 746/746/1455 760/760/1454 743/743/1456 +f 743/743/1456 760/760/1454 761/761/1457 +f 743/743/1456 761/761/1457 744/744/1458 +f 744/744/1458 761/761/1457 745/745/1459 +f 745/745/1459 761/761/1457 763/763/1460 +f 745/745/1459 763/763/1460 754/754/1444 +f 745/745/1459 754/754/1444 738/738/1443 +f 736/736/1461 742/742/1462 764/764/1463 +f 764/764/1463 742/742/1462 765/765/1464 +f 737/737/1465 736/736/1465 766/766/1465 +f 766/766/1466 736/736/1466 764/764/1466 +f 767/767/1467 737/737/1467 766/766/1467 +f 742/742/1468 737/737/1468 767/767/1468 +f 765/765/1469 742/742/1469 767/767/1469 +f 766/766/1 764/764/1 765/765/1 +f 766/766/1 765/765/1 767/767/1 +f 756/756/1470 749/749/1411 751/751/1413 +f 756/756/1423 751/751/1471 752/752/1424 +f 759/759/1472 752/752/1414 748/748/1410 +f 762/762/1473 753/753/1415 750/750/1412 +f 96/96/1474 144/144/2 161/161/2 +f 165/165/2 94/94/2 96/96/1474 +f 10/10/4 151/151/1475 11/11/5 +f 178/178/2 167/167/2 86/86/2 +f 96/96/1474 151/151/1475 154/154/2 +f 165/165/2 96/96/1474 163/163/2 +f 94/94/2 165/165/2 155/155/2 +f 151/151/1475 96/96/1474 11/11/5 +f 173/173/2 175/175/2 94/94/2 +f 92/92/1476 139/139/2 121/121/2 +f 163/163/2 96/96/1474 161/161/2 +f 100/100/2 159/159/2 146/146/2 +f 87/87/2 86/86/2 167/167/2 +f 146/146/2 159/159/2 144/144/2 +f 157/157/2 105/105/2 155/155/2 +f 169/169/2 87/87/2 167/167/2 +f 86/86/2 175/175/2 178/178/2 +f 92/92/1476 124/124/1477 12/12/6 +f 146/146/2 148/148/1478 101/101/1479 +f 171/171/2 87/87/2 169/169/2 +f 97/97/1480 102/102/1481 10/10/4 +f 102/102/1481 101/101/1479 10/10/4 +f 119/119/2 87/87/2 103/103/2 +f 105/105/2 104/104/2 87/87/2 +f 106/106/2 143/143/2 132/132/2 +f 105/105/2 171/171/2 173/173/2 +f 105/105/2 157/157/2 107/107/2 +f 107/107/2 141/141/2 143/143/2 +f 175/175/2 86/86/2 94/94/2 +f 103/103/2 87/87/2 104/104/2 +f 99/99/2 141/141/2 100/100/2 +f 106/106/2 132/132/2 115/115/2 +f 141/141/2 107/107/2 100/100/2 +f 9/9/3 98/98/2 97/97/1480 +f 10/10/4 9/9/3 97/97/1480 +f 130/130/2 99/99/2 9/9/3 +f 9/9/3 99/99/2 98/98/2 +f 12/12/6 128/128/1482 9/9/3 +f 128/128/1482 130/130/2 9/9/3 +f 119/119/2 110/110/2 87/87/2 +f 103/103/2 106/106/2 117/117/2 +f 157/157/2 159/159/2 107/107/2 +f 99/99/2 130/130/2 141/141/2 +f 106/106/2 107/107/2 143/143/2 +f 121/121/2 141/141/2 130/130/2 +f 121/121/2 139/139/2 141/141/2 +f 105/105/2 173/173/2 155/155/2 +f 117/117/2 106/106/2 115/115/2 +f 159/159/2 161/161/2 144/144/2 +f 94/94/2 155/155/2 173/173/2 +f 12/12/6 125/125/1483 128/128/1482 +f 159/159/2 100/100/2 107/107/2 +f 124/124/1477 92/92/1476 121/121/2 +f 113/113/2 115/115/2 91/91/2 +f 135/135/2 91/91/2 132/132/2 +f 111/111/2 89/89/2 110/110/2 +f 92/92/1476 137/137/2 139/139/2 +f 105/105/2 87/87/2 171/171/2 +f 96/96/1474 154/154/2 144/144/2 +f 137/137/2 91/91/2 135/135/2 +f 12/12/6 124/124/1477 125/125/1483 +f 111/111/2 113/113/2 89/89/2 +f 101/101/1479 148/148/1478 10/10/4 +f 101/101/1479 100/100/2 146/146/2 +f 117/117/2 119/119/2 103/103/2 +f 110/110/2 89/89/2 87/87/2 +f 91/91/2 115/115/2 132/132/2 +f 137/137/2 92/92/1476 91/91/2 +f 89/89/2 113/113/2 91/91/2 +f 8/8/729 7/7/729 1/1/729 +f 8/8/729 1/1/729 3/3/729 diff --git a/examples/Cassie/urdf/meshes/agility/pelvis.obj b/examples/Cassie/urdf/meshes/agility/pelvis.obj index 94f62d9246..f616aac0eb 100644 --- a/examples/Cassie/urdf/meshes/agility/pelvis.obj +++ b/examples/Cassie/urdf/meshes/agility/pelvis.obj @@ -1,46992 +1,51368 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object pelvis.obj -# -# Vertices: 15983 -# Faces: 30993 -# -#### -v -0.005200 -0.078860 0.099115 -v -0.005200 -0.079803 0.101430 -v -0.005200 -0.081140 0.100885 -v -0.005200 -0.078663 0.100545 -v -0.005200 -0.081337 0.099455 -v -0.005195 -0.081681 0.098516 -v -0.003781 -0.076496 0.101374 -v -0.003000 -0.076842 0.102012 -v -0.003856 -0.078115 0.103176 -v -0.003001 -0.079013 0.103791 -v -0.003678 -0.080453 0.103804 -v -0.003000 -0.082423 0.103092 -v -0.003826 -0.082722 0.102535 -v -0.003632 -0.083933 0.100169 -v -0.003000 -0.083138 0.097930 -v -0.003000 -0.081001 0.096200 -v -0.003000 -0.077171 0.097169 -v -0.003570 -0.082612 0.097155 -v -0.003716 -0.079878 0.096167 -v -0.005200 -0.079166 0.098008 -v -0.003655 -0.077055 0.097495 -v -0.005189 -0.077760 0.099519 -v -0.003000 -0.076224 0.100102 -v -0.005207 -0.079418 0.102285 -v -0.005170 -0.082253 0.100721 -v -0.004000 -0.078663 0.100545 -v -0.004000 -0.081140 0.100885 -v -0.004000 -0.079803 0.101430 -v -0.004000 -0.081337 0.099455 -v -0.005200 -0.080197 0.098570 -v -0.004000 -0.080197 0.098570 -v -0.004000 -0.078860 0.099115 -v -0.005200 -0.080421 -0.006381 -v -0.005200 -0.079015 -0.006055 -v -0.005200 -0.079579 -0.003619 -v -0.005210 -0.081411 -0.005321 -v -0.005200 -0.080985 -0.003945 -v -0.003000 -0.076242 -0.004882 -v -0.003000 -0.083741 -0.004626 -v -0.003501 -0.078736 -0.008736 -v -0.003496 -0.076280 -0.006301 -v -0.003633 -0.083535 -0.006533 -v -0.005200 -0.081560 -0.006402 -v -0.003618 -0.081796 -0.008376 -v -0.005159 -0.079802 -0.007450 -v -0.005186 -0.077664 -0.005628 -v -0.003513 -0.076695 -0.002953 -v -0.005160 -0.078744 -0.002909 -v -0.003432 -0.079678 -0.001095 -v -0.005180 -0.080975 -0.002894 -v -0.003001 -0.082520 -0.001876 -v -0.004108 -0.083512 -0.004264 -v -0.005200 -0.078594 -0.004674 -v -0.004000 -0.078594 -0.004674 -v -0.004000 -0.080985 -0.003945 -v -0.004000 -0.080421 -0.006381 -v -0.004000 -0.079015 -0.006055 -v -0.004000 -0.081406 -0.005326 -v -0.004000 -0.079579 -0.003619 -v -0.005200 0.079015 -0.006055 -v -0.005202 0.081751 -0.003371 -v -0.005200 0.081406 -0.005326 -v -0.005200 0.080985 -0.003945 -v -0.005261 0.078578 -0.004671 -v -0.005200 0.079579 -0.003619 -v -0.003819 0.082584 -0.002310 -v -0.003001 0.076150 -0.003765 -v -0.003000 0.076348 -0.005611 -v -0.003000 0.077343 -0.007804 -v -0.003000 0.083426 -0.006547 -v -0.003001 0.078631 -0.001287 -v -0.003718 0.077625 -0.007961 -v -0.003830 0.076528 -0.006296 -v -0.005199 0.078817 -0.006782 -v -0.004496 0.080127 -0.008075 -v -0.003741 0.082756 -0.007667 -v -0.005204 0.081654 -0.006440 -v -0.003590 0.083865 -0.004629 -v -0.003002 0.081819 -0.001423 -v -0.003816 0.079538 -0.001284 -v -0.005152 0.077905 -0.003590 -v -0.004000 0.080985 -0.003945 -v -0.004000 0.081406 -0.005326 -v -0.005200 0.080421 -0.006381 -v -0.004000 0.079015 -0.006055 -v -0.004000 0.080421 -0.006381 -v -0.004000 0.078594 -0.004674 -v -0.004000 0.079579 -0.003619 -v -0.005200 0.081140 0.100885 -v -0.005260 0.080203 0.098548 -v -0.005200 0.081337 0.099455 -v -0.005200 0.078860 0.099115 -v -0.005200 0.078663 0.100545 -v -0.003000 0.083577 -0.004036 -v -0.003000 0.082289 -0.008084 -v -0.003000 -0.077292 -0.002101 -v -0.003028 0.079941 -0.008962 -v -0.003000 -0.082322 -0.008211 -v -0.003000 -0.077224 -0.007900 -v -0.003000 -0.083685 0.100385 -v -0.003000 0.082434 0.103191 -v -0.003000 0.077756 0.103280 -v -0.003000 0.082459 0.096828 -v -0.003660 0.076437 0.101470 -v -0.003644 0.076445 0.098498 -v -0.005193 0.078296 0.098496 -v -0.003845 0.078476 0.096592 -v -0.003605 0.080568 0.096232 -v -0.003634 0.082779 0.097295 -v -0.005021 0.082554 0.099670 -v -0.003000 0.083723 0.099960 -v -0.005201 0.081565 0.101506 -v -0.003838 0.079180 0.103698 -v -0.003841 0.082431 0.102976 -v -0.005183 0.078493 0.101733 -v -0.005201 0.077878 0.100019 -v -0.004000 0.081140 0.100885 -v -0.005200 0.079803 0.101430 -v -0.004000 0.079803 0.101430 -v -0.004000 0.078860 0.099115 -v -0.004000 0.080197 0.098570 -v -0.004000 0.081337 0.099455 -v -0.004000 0.078663 0.100545 -v -0.003000 0.077831 0.096682 -v -0.003000 0.076317 0.099917 -v 0.000000 -0.069506 0.047500 -v -0.004184 -0.069140 -0.013350 -v -0.005898 -0.068990 0.085836 -v -0.003630 -0.069188 0.075482 -v -0.003630 -0.069188 0.019518 -v -0.001613 -0.069365 0.024398 -v -0.005898 -0.068990 -0.009843 -v -0.021323 -0.066894 0.116238 -v -0.015417 -0.067951 0.112736 -v -0.005649 -0.068836 0.112841 -v -0.005898 -0.068968 0.110787 -v -0.003673 -0.068076 0.117851 -v -0.003586 -0.068042 0.118022 -v -0.029424 -0.064436 0.121385 -v -0.029633 -0.064281 0.121679 -v -0.001809 -0.067245 0.120916 -v -0.030925 -0.062704 0.124434 -v -0.001641 -0.067162 0.121170 -v -0.029856 -0.064116 0.121991 -v 0.000000 -0.066639 0.122760 -v -0.030375 -0.063582 0.122964 -v -0.031472 -0.061140 0.126695 -v 0.000000 -0.064128 0.127235 -v -0.031327 -0.058901 0.129337 -v -0.031494 -0.059764 0.128416 -v -0.031632 -0.060387 0.127650 -v -0.030691 -0.055109 0.132823 -v -0.030743 -0.055478 0.132538 -v 0.000000 -0.060923 0.131243 -v -0.030278 -0.051545 0.135104 -v -0.005776 0.069000 0.083703 -v -0.001613 0.069365 0.070602 -v -0.005898 0.068990 0.009164 -v -0.003630 0.069188 0.019518 -v -0.010131 0.068619 -0.024813 -v 0.000000 0.069130 -0.031598 -v -0.021482 0.067227 -0.031378 -v -0.019308 0.066094 -0.038945 -v -0.024068 0.066776 -0.033369 -v -0.017773 0.065977 -0.040071 -v 0.000000 0.067764 -0.039345 -v -0.011896 -0.048546 -0.077901 -v -0.011760 -0.050579 -0.076432 -v 0.000000 -0.049890 -0.078252 -v 0.000000 -0.052556 -0.076035 -v -0.011349 -0.053770 -0.073179 -v 0.000000 -0.056657 -0.070472 -v -0.068658 -0.026889 -0.079513 -v -0.064167 -0.024790 -0.081096 -v -0.066230 -0.042693 -0.067865 -v -0.069868 -0.041471 -0.066876 -v -0.075365 -0.039489 -0.065256 -v -0.076231 -0.037760 -0.068011 -v -0.067744 -0.023712 -0.080069 -v -0.086160 -0.020712 -0.073379 -v -0.084120 -0.018118 -0.074450 -v -0.079486 -0.019807 -0.076220 -v -0.080472 -0.022852 -0.075586 -v -0.077481 -0.020497 -0.076911 -v -0.075856 -0.039312 -0.065111 -v -0.082063 -0.035484 -0.066058 -v -0.087678 -0.033128 -0.063973 -v -0.091661 -0.018542 -0.070998 -v -0.085160 -0.017738 -0.074052 -v -0.097508 -0.029953 -0.056851 -v -0.096931 -0.016397 -0.068438 -v -0.090667 -0.015643 -0.071710 -v -0.100586 -0.011770 -0.066704 -v -0.101300 -0.014601 -0.066055 -v -0.065968 -0.041344 -0.071021 -v -0.065842 -0.039438 -0.073813 -v -0.070344 -0.037944 -0.072530 -v -0.070217 -0.039924 -0.069829 -v -0.076374 -0.035792 -0.070669 -v -0.087874 -0.031186 -0.066519 -v -0.093030 -0.030735 -0.061758 -v -0.093268 -0.028805 -0.064230 -v -0.098057 -0.028366 -0.059426 -v -0.098350 -0.026447 -0.061808 -v -0.102473 -0.024466 -0.059599 -v -0.105995 -0.022744 -0.057480 -v -0.076279 -0.033459 -0.073015 -v -0.087815 -0.028914 -0.068784 -v -0.087504 -0.026369 -0.070712 -v -0.093246 -0.026565 -0.066439 -v -0.102402 -0.019876 -0.063444 -v -0.109177 -0.019176 -0.057365 -v -0.064917 -0.031403 -0.079749 -v -0.074631 -0.024920 -0.077628 -v -0.086947 -0.023612 -0.072256 -v -0.092433 -0.021372 -0.069863 -v -0.097665 -0.019155 -0.067298 -v -0.101976 -0.017297 -0.064921 -v -0.105734 -0.015685 -0.062594 -v -0.105133 -0.013047 -0.063711 -v -0.108927 -0.014353 -0.060370 -v -0.101505 -0.027979 -0.054847 -v -0.102115 -0.026378 -0.057313 -v -0.105563 -0.024652 -0.055302 -v -0.104882 -0.026269 -0.052959 -v -0.108398 -0.023225 -0.053447 -v -0.108914 -0.021318 -0.055502 -v -0.111332 -0.020148 -0.053668 -v -0.106169 -0.020583 -0.059446 -v -0.102569 -0.022283 -0.061658 -v -0.098382 -0.024238 -0.063946 -v -0.082145 -0.031227 -0.070976 -v -0.082227 -0.033529 -0.068665 -v -0.070246 -0.035583 -0.074907 -v -0.111510 -0.018003 -0.055622 -v -0.109181 -0.016839 -0.058998 -v -0.106081 -0.018214 -0.061163 -v -0.098152 -0.021789 -0.065790 -v -0.092965 -0.024068 -0.068332 -v -0.081257 -0.025819 -0.074480 -v -0.075397 -0.027952 -0.076541 -v -0.081819 -0.028635 -0.072931 -v -0.075951 -0.030823 -0.074990 -v -0.069391 -0.029980 -0.078446 -v -0.069926 -0.032904 -0.076897 -v -0.065390 -0.034375 -0.078214 -v -0.108419 -0.011767 -0.061455 -v -0.117911 -0.005236 -0.052230 -v -0.120650 -0.006262 -0.042119 -v -0.120370 -0.006744 -0.044972 -v -0.119996 -0.008596 -0.045591 -v -0.120184 -0.009176 -0.043072 -v -0.119328 -0.010893 -0.046433 -v -0.117548 -0.014663 -0.048046 -v -0.116646 -0.016067 -0.048723 -v -0.114785 -0.019605 -0.047396 -v -0.113870 -0.019317 -0.050488 -v -0.116348 -0.005501 -0.054514 -v -0.114504 -0.008745 -0.056398 -v -0.113215 -0.006772 -0.057795 -v -0.112475 -0.007310 -0.058458 -v -0.119490 -0.007960 -0.048051 -v -0.118322 -0.013230 -0.047399 -v -0.117708 -0.012543 -0.049951 -v -0.115396 -0.017719 -0.049561 -v -0.114108 -0.017296 -0.052662 -v -0.110619 -0.008146 -0.060010 -v -0.111884 -0.010563 -0.058757 -v -0.116930 -0.008240 -0.053359 -v -0.119132 -0.005279 -0.049792 -v -0.116439 -0.012192 -0.052702 -v -0.115185 -0.011081 -0.055049 -v -0.113372 -0.015726 -0.055086 -v -0.113085 -0.013210 -0.056772 -v -0.111765 -0.013265 -0.058122 -v -0.111810 -0.015723 -0.056921 -v -0.118534 -0.007767 -0.050598 -v -0.117660 -0.010019 -0.051552 -v -0.118881 -0.009940 -0.048797 -v -0.116519 -0.014446 -0.050939 -v -0.115143 -0.013896 -0.053786 -v -0.115423 -0.015893 -0.051767 -v -0.112855 -0.018428 -0.053451 -v -0.112423 -0.020595 -0.051275 -v -0.113102 -0.021299 -0.048238 -v -0.110726 -0.022065 -0.051730 -v -0.109874 -0.023721 -0.049673 -v -0.065165 -0.043038 -0.068144 -v -0.060759 -0.029657 -0.081365 -v -0.062614 -0.031010 -0.080618 -v -0.063863 -0.028376 -0.080904 -v -0.061975 -0.027394 -0.081532 -v -0.063123 -0.025094 -0.081385 -v -0.065693 -0.037076 -0.076222 -v -0.062836 -0.038837 -0.075930 -v -0.065387 -0.035953 -0.077124 -v -0.062398 -0.036524 -0.077990 -v -0.062614 -0.033865 -0.079481 -v -0.119740 0.004898 -0.048164 -v -0.116929 0.003110 -0.053780 -v -0.114979 -0.001200 -0.056101 -v -0.117029 -0.001277 -0.053665 -v -0.118661 0.001931 -0.050960 -v -0.118677 -0.001351 -0.050941 -v -0.119869 0.002032 -0.048011 -v -0.119883 -0.001422 -0.047995 -v -0.120605 0.002126 -0.044910 -v -0.119996 -0.005678 -0.047240 -v -0.120618 -0.001488 -0.044897 -v -0.120556 -0.005160 -0.044507 -v -0.055898 -0.039500 -0.077408 -v -0.056808 -0.041503 -0.075422 -v -0.063752 -0.040586 -0.073602 -v -0.062842 -0.043991 -0.068049 -v -0.058881 -0.045614 -0.067888 -v -0.052682 -0.047904 -0.067648 -v -0.064572 -0.041988 -0.070980 -v -0.054907 -0.037244 -0.079056 -v -0.048298 -0.037381 -0.079816 -v -0.053857 -0.034784 -0.080332 -v -0.043974 -0.041827 -0.078083 -v -0.043181 -0.039512 -0.079388 -v -0.046978 -0.049791 -0.067456 -v -0.040680 -0.050530 -0.069781 -v -0.058316 -0.044593 -0.070612 -v -0.051574 -0.045543 -0.072722 -v -0.052183 -0.046892 -0.070275 -v -0.046545 -0.048786 -0.070005 -v -0.023313 -0.053040 -0.071783 -v -0.029162 -0.053283 -0.069567 -v -0.034889 -0.052025 -0.069631 -v -0.036896 -0.052584 -0.067241 -v -0.038526 -0.043721 -0.077702 -v -0.037855 -0.041465 -0.079014 -v -0.032593 -0.043129 -0.078731 -v -0.027385 -0.044517 -0.078554 -v -0.022221 -0.045638 -0.078490 -v -0.017302 -0.048629 -0.077234 -v -0.050866 -0.043883 -0.074940 -v -0.050074 -0.041943 -0.076885 -v -0.033659 -0.047363 -0.075820 -v -0.034126 -0.049172 -0.073969 -v -0.022840 -0.049750 -0.075602 -v -0.017488 -0.050582 -0.075670 -v -0.017842 -0.055120 -0.069724 -v -0.023485 -0.054312 -0.069595 -v -0.028225 -0.048680 -0.075654 -v -0.022547 -0.047782 -0.077174 -v -0.027823 -0.046688 -0.077237 -v -0.033145 -0.045338 -0.077416 -v -0.039154 -0.045790 -0.076092 -v -0.044720 -0.043949 -0.076460 -v -0.049212 -0.039762 -0.078521 -v -0.060822 -0.034366 -0.079626 -v -0.017642 -0.052332 -0.073879 -v -0.023097 -0.051512 -0.073795 -v -0.028900 -0.052004 -0.071788 -v -0.028586 -0.050461 -0.073827 -v -0.034538 -0.050735 -0.071895 -v -0.039729 -0.047635 -0.074213 -v -0.040241 -0.049224 -0.072097 -v -0.045406 -0.045838 -0.074548 -v -0.046017 -0.047460 -0.072384 -v -0.057620 -0.043213 -0.073141 -v -0.017760 -0.053852 -0.071887 -v -0.010230 -0.000063 -0.090615 -v -0.062620 -0.024856 -0.081514 -v -0.057501 -0.030535 -0.081491 -v -0.052501 -0.027239 -0.083010 -v -0.038864 -0.015155 -0.086776 -v -0.039473 -0.013929 -0.086713 -v -0.030227 -0.011704 -0.088151 -v -0.030665 -0.010838 -0.088153 -v -0.027951 -0.008480 -0.088549 -v -0.022636 -0.005961 -0.089290 -v -0.021212 -0.006155 -0.089450 -v -0.022250 -0.006730 -0.089318 -v -0.038241 -0.016375 -0.086750 -v -0.046186 -0.021026 -0.085108 -v -0.047002 -0.019446 -0.085172 -v -0.053542 -0.025362 -0.083344 -v -0.054551 -0.023441 -0.083455 -v -0.012557 -0.001553 -0.090399 -v -0.020856 -0.006857 -0.089449 -v -0.111492 0.011056 -0.058999 -v -0.113268 0.009935 -0.057506 -v -0.112199 0.020774 -0.051391 -v -0.114557 0.019853 -0.047520 -v -0.116958 0.016800 -0.046072 -v -0.118229 0.013417 -0.047481 -v -0.118248 0.014577 -0.045115 -v -0.113621 0.006383 -0.057420 -v -0.118892 0.011976 -0.046868 -v -0.119602 0.011299 -0.043830 -v -0.112032 0.013942 -0.057599 -v -0.117658 0.006297 -0.052551 -v -0.115412 0.007593 -0.055507 -v -0.118518 0.004654 -0.051134 -v -0.112257 0.016580 -0.055879 -v -0.114075 0.012283 -0.056005 -v -0.116161 0.009737 -0.054129 -v -0.119050 0.005728 -0.049908 -v -0.119186 0.009062 -0.048440 -v -0.118393 0.008222 -0.050757 -v -0.117501 0.010353 -0.051710 -v -0.116533 0.012048 -0.052616 -v -0.116035 0.015111 -0.051312 -v -0.115143 0.013888 -0.053794 -v -0.113862 0.015220 -0.054755 -v -0.112661 0.018587 -0.053568 -v -0.113658 0.019518 -0.050608 -v -0.113925 0.017474 -0.052781 -v -0.114968 0.018182 -0.049836 -v -0.115060 0.016297 -0.052019 -v -0.116091 0.016828 -0.049110 -v -0.117262 0.015162 -0.048273 -v -0.117052 0.013664 -0.050512 -v -0.118176 0.011614 -0.049515 -v -0.119871 0.006249 -0.047483 -v -0.120481 0.005124 -0.045038 -v -0.119681 0.009819 -0.046014 -v -0.120197 0.009045 -0.043031 -v -0.120418 0.007992 -0.042672 -v -0.120653 0.006222 -0.042106 -v -0.120328 0.007065 -0.045000 -v -0.012149 -0.054440 -0.072125 -v -0.011252 -0.055313 -0.070888 -v -0.010539 -0.056270 -0.069154 -v -0.011665 -0.051965 -0.075185 -v -0.012097 -0.055721 -0.069966 -v -0.012033 -0.051190 -0.075872 -v -0.011948 -0.052956 -0.074091 -v -0.011964 -0.047115 -0.078729 -v -0.012035 -0.049235 -0.077424 -v -0.108677 0.008793 -0.061471 -v -0.109181 0.016839 -0.058998 -v -0.096931 0.016397 -0.068438 -v -0.087678 0.033128 -0.063973 -v -0.064167 0.024790 -0.081096 -v -0.064903 0.031407 -0.079753 -v -0.065387 0.035953 -0.077124 -v -0.065520 0.037123 -0.076260 -v -0.066589 0.036784 -0.075963 -v -0.066230 0.042693 -0.067865 -v -0.066565 0.041149 -0.070847 -v -0.070344 0.037944 -0.072530 -v -0.065828 0.039447 -0.073813 -v -0.065386 0.034376 -0.078215 -v -0.068658 0.026889 -0.079513 -v -0.064290 0.028247 -0.080780 -v -0.070217 0.039924 -0.069829 -v -0.076231 0.037760 -0.068011 -v -0.070246 0.035583 -0.074907 -v -0.069926 0.032904 -0.076897 -v -0.075951 0.030823 -0.074990 -v -0.069391 0.029980 -0.078446 -v -0.074631 0.024920 -0.077628 -v -0.067744 0.023712 -0.080069 -v -0.081656 0.037042 -0.063221 -v -0.082063 0.035484 -0.066058 -v -0.076374 0.035792 -0.070669 -v -0.076279 0.033459 -0.073015 -v -0.080472 0.022852 -0.075586 -v -0.075397 0.027952 -0.076541 -v -0.073675 0.021807 -0.078222 -v -0.087234 0.034693 -0.061207 -v -0.082227 0.033529 -0.068665 -v -0.087815 0.028914 -0.068784 -v -0.082145 0.031227 -0.070976 -v -0.087504 0.026369 -0.070712 -v -0.081819 0.028635 -0.072931 -v -0.081257 0.025819 -0.074480 -v -0.086160 0.020712 -0.073379 -v -0.084120 0.018118 -0.074450 -v -0.087500 0.034574 -0.061101 -v -0.087874 0.031186 -0.066519 -v -0.093268 0.028805 -0.064230 -v -0.093246 0.026565 -0.066439 -v -0.092965 0.024068 -0.068332 -v -0.086947 0.023612 -0.072256 -v -0.091661 0.018542 -0.070998 -v -0.090192 0.015824 -0.071912 -v -0.085160 0.017738 -0.074052 -v -0.092433 0.021372 -0.069863 -v -0.097665 0.019155 -0.067298 -v -0.098152 0.021789 -0.065790 -v -0.093030 0.030735 -0.061758 -v -0.099189 0.029123 -0.056008 -v -0.097508 0.029953 -0.056851 -v -0.101976 0.017297 -0.064921 -v -0.102569 0.022283 -0.061658 -v -0.108927 0.014353 -0.060370 -v -0.108914 0.021318 -0.055502 -v -0.100586 0.011770 -0.066704 -v -0.105133 0.013047 -0.063711 -v -0.108419 0.011767 -0.061455 -v -0.107667 0.009129 -0.062232 -v -0.105734 0.015685 -0.062594 -v -0.106081 0.018214 -0.061163 -v -0.105995 0.022744 -0.057480 -v -0.106169 0.020583 -0.059446 -v -0.109177 0.019176 -0.057365 -v -0.111482 0.019474 -0.054251 -v -0.100387 0.011846 -0.066823 -v -0.101300 0.014601 -0.066055 -v -0.102402 0.019876 -0.063444 -v -0.098382 0.024238 -0.063946 -v -0.098350 0.026447 -0.061808 -v -0.098057 0.028366 -0.059426 -v -0.102473 0.024466 -0.059599 -v -0.102115 0.026378 -0.057313 -v -0.101505 0.027979 -0.054847 -v -0.105563 0.024652 -0.055302 -v -0.108398 0.023225 -0.053447 -v -0.104882 0.026269 -0.052959 -v -0.110766 0.021811 -0.052108 -v -0.109874 0.023721 -0.049673 -v -0.062614 0.033865 -0.079481 -v -0.062398 0.036524 -0.077990 -v -0.060822 0.034366 -0.079626 -v -0.065562 0.038161 -0.075215 -v -0.062614 0.031010 -0.080618 -v -0.062484 0.027644 -0.081399 -v -0.057501 0.030535 -0.081491 -v -0.060759 0.029662 -0.081364 -v -0.062620 0.024856 -0.081514 -v -0.054551 0.023441 -0.083455 -v -0.052501 0.027239 -0.083010 -v -0.045350 0.022582 -0.084892 -v -0.046186 0.021026 -0.085108 -v -0.038864 0.015155 -0.086776 -v -0.039473 0.013929 -0.086713 -v -0.047002 0.019446 -0.085172 -v -0.047792 0.017854 -0.085084 -v -0.038241 0.016375 -0.086750 -v -0.030227 0.011704 -0.088151 -v -0.029783 0.012566 -0.088103 -v -0.027951 0.008480 -0.088549 -v -0.031097 0.009971 -0.088110 -v -0.037066 0.012791 -0.087114 -v -0.022121 0.006987 -0.089322 -v -0.020856 0.006857 -0.089449 -v -0.012557 0.001553 -0.090399 -v -0.012717 0.001237 -0.090387 -v -0.010131 0.000000 -0.090624 -v -0.022636 0.005961 -0.089290 -v -0.030665 0.010838 -0.088153 -v -0.053542 0.025362 -0.083344 -v -0.018672 0.004074 -0.089738 -v -0.021212 0.006155 -0.089450 -v -0.065165 0.043038 -0.068144 -v -0.062842 0.043991 -0.068049 -v -0.064540 0.042002 -0.070977 -v -0.062837 0.038837 -0.075930 -v -0.054907 0.037244 -0.079056 -v -0.049212 0.039762 -0.078521 -v -0.048298 0.037381 -0.079816 -v -0.043974 0.041827 -0.078083 -v -0.058881 0.045614 -0.067888 -v -0.046545 0.048786 -0.070005 -v -0.041040 0.051530 -0.067304 -v -0.036896 0.052584 -0.067241 -v -0.063760 0.040582 -0.073602 -v -0.058316 0.044593 -0.070612 -v -0.057620 0.043213 -0.073141 -v -0.052183 0.046892 -0.070275 -v -0.051574 0.045543 -0.072722 -v -0.046017 0.047460 -0.072384 -v -0.040680 0.050530 -0.069781 -v -0.034889 0.052025 -0.069631 -v -0.034539 0.050735 -0.071895 -v -0.029162 0.053283 -0.069567 -v -0.023313 0.053040 -0.071783 -v -0.023485 0.054312 -0.069595 -v -0.017760 0.053852 -0.071887 -v -0.055898 0.039500 -0.077408 -v -0.050074 0.041943 -0.076885 -v -0.039729 0.047635 -0.074213 -v -0.034126 0.049172 -0.073969 -v -0.028586 0.050461 -0.073827 -v -0.023097 0.051512 -0.073795 -v -0.028225 0.048680 -0.075654 -v -0.017642 0.052332 -0.073879 -v -0.022840 0.049750 -0.075602 -v -0.035173 0.053023 -0.067215 -v -0.029367 0.054279 -0.067199 -v -0.023610 0.055308 -0.067266 -v -0.017842 0.055120 -0.069724 -v -0.011993 0.054462 -0.072124 -v -0.028900 0.052004 -0.071788 -v -0.040241 0.049224 -0.072097 -v -0.045406 0.045838 -0.074548 -v -0.050866 0.043883 -0.074940 -v -0.056808 0.041503 -0.075422 -v -0.017488 0.050582 -0.075670 -v -0.044720 0.043949 -0.076460 -v -0.039154 0.045790 -0.076092 -v -0.038526 0.043721 -0.077702 -v -0.033659 0.047363 -0.075820 -v -0.037855 0.041465 -0.079014 -v -0.033145 0.045338 -0.077416 -v -0.032593 0.043129 -0.078731 -v -0.027823 0.046688 -0.077237 -v -0.022547 0.047782 -0.077174 -v -0.022221 0.045638 -0.078490 -v -0.017302 0.048629 -0.077234 -v -0.017086 0.046502 -0.078546 -v -0.011542 0.053753 -0.073174 -v -0.011817 0.051958 -0.075174 -v -0.011853 0.053892 -0.072980 -v -0.012039 0.049233 -0.077424 -v -0.011974 0.050574 -0.076413 -v -0.012117 0.051183 -0.075867 -v -0.012050 0.052941 -0.074092 -v -0.012007 0.055730 -0.069970 -v -0.016221 0.067983 -0.028345 -v -0.010228 0.068611 -0.024870 -v -0.010235 0.068610 -0.024851 -v -0.025806 0.066743 -0.031992 -v -0.026202 0.066424 -0.034135 -v -0.024368 0.066920 -0.031383 -v -0.024209 0.065959 -0.037494 -v -0.025616 0.065706 -0.037627 -v -0.010131 0.064964 -0.045546 -v -0.018651 0.065328 -0.041825 -v -0.018215 0.065677 -0.040956 -v -0.012531 0.065334 -0.043843 -v -0.023435 0.066409 -0.035921 -v -0.010131 -0.064964 -0.045546 -v -0.010216 -0.064969 -0.045511 -v -0.012669 -0.065228 -0.044115 -v -0.018215 -0.065677 -0.040956 -v -0.024938 -0.066922 -0.031383 -v -0.024209 -0.065959 -0.037494 -v -0.010228 -0.068611 -0.024870 -v -0.016677 -0.067973 -0.027144 -v -0.038841 -0.055412 0.130099 -v -0.039248 -0.049810 0.133491 -v -0.039447 -0.052084 0.132164 -v -0.035318 -0.054610 0.132274 -v -0.037613 -0.051900 0.133158 -v -0.036092 -0.057289 0.129776 -v -0.037043 -0.054827 0.131513 -v -0.037090 -0.060716 0.125048 -v -0.035284 -0.059089 0.128212 -v -0.032712 -0.058786 0.129294 -v -0.028783 -0.064773 0.120740 -v -0.028270 -0.064972 0.120372 -v -0.034130 -0.064526 0.118724 -v -0.032929 -0.064323 0.120339 -v -0.031435 -0.065360 0.117907 -v -0.029746 -0.065360 0.118792 -v -0.029837 -0.066053 0.115599 -v -0.033892 -0.063323 0.122254 -v -0.035465 -0.063257 0.121277 -v -0.030924 -0.064672 0.120380 -v -0.030053 -0.063937 0.122323 -v -0.030664 -0.063175 0.123666 -v -0.031739 -0.063943 0.121857 -v -0.031071 -0.062382 0.124935 -v -0.031284 -0.061804 0.125785 -v -0.034887 -0.062027 0.124253 -v -0.032602 -0.062739 0.123989 -v -0.034258 -0.060969 0.126228 -v -0.036563 -0.061975 0.123274 -v -0.023219 -0.066370 0.117366 -v -0.014184 -0.068171 0.112005 -v -0.010131 -0.068619 0.109630 -v -0.014289 -0.068220 0.110990 -v -0.014488 -0.068206 0.110402 -v -0.012968 -0.068357 0.110136 -v -0.010241 -0.068610 0.109650 -v -0.029626 -0.066257 0.112816 -v -0.021894 -0.067293 0.113214 -v -0.028761 -0.065722 0.117922 -v -0.021615 -0.067151 0.114735 -v -0.038912 0.046545 0.134907 -v -0.038235 0.049665 0.134008 -v -0.039885 0.047403 0.134129 -v -0.036274 0.051790 0.133701 -v -0.037889 0.051960 0.133001 -v -0.039451 0.052059 0.132178 -v -0.035284 0.059089 0.128212 -v -0.038841 0.055412 0.130099 -v -0.037075 0.054815 0.131509 -v -0.032712 0.058786 0.129294 -v -0.036092 0.057288 0.129776 -v -0.028761 0.065722 0.117922 -v -0.028270 0.064972 0.120372 -v -0.030581 0.064913 0.119850 -v -0.030826 0.066015 0.114134 -v -0.033426 0.064953 0.117662 -v -0.029633 0.064281 0.121679 -v -0.030375 0.063582 0.122964 -v -0.030664 0.063175 0.123666 -v -0.030925 0.062704 0.124434 -v -0.031071 0.062382 0.124935 -v -0.036042 0.062526 0.122500 -v -0.034723 0.063406 0.121586 -v -0.036641 0.061106 0.124743 -v -0.031548 0.065285 0.118092 -v -0.033026 0.064292 0.120368 -v -0.034216 0.060988 0.126216 -v -0.032182 0.063464 0.122773 -v -0.034280 0.061965 0.124684 -v -0.031632 0.060387 0.127650 -v -0.029216 0.066153 0.115390 -v -0.010131 0.068619 0.109630 -v -0.014184 0.068171 0.112005 -v -0.014287 0.068197 0.111471 -v -0.015417 0.067951 0.112736 -v -0.021894 0.067293 0.113214 -v -0.014488 0.068206 0.110402 -v -0.012969 0.068357 0.110136 -v -0.021615 0.067151 0.114735 -v -0.021323 0.066894 0.116238 -v -0.033671 -0.056999 0.130811 -v -0.037175 -0.049569 0.134462 -v -0.031095 -0.057704 0.130615 -v -0.030760 -0.055598 0.132447 -v -0.036945 -0.048881 0.134825 -v -0.036421 -0.047587 0.135479 -v -0.032740 -0.053032 0.133907 -v -0.030471 -0.053372 0.134031 -v -0.030295 -0.051737 0.135006 -v -0.032405 -0.051263 0.134958 -v -0.030154 -0.050189 0.135798 -v -0.030052 -0.048843 0.136394 -v -0.032198 -0.049865 0.135667 -v -0.034165 -0.048299 0.135903 -v -0.034644 -0.050426 0.134866 -v -0.035113 -0.052102 0.133880 -v -0.033150 -0.055064 0.132467 -v -0.032170 -0.047971 0.136459 -v -0.038567 -0.044922 0.135432 -v -0.039398 -0.041531 0.135590 -v -0.037242 -0.042809 0.136359 -v -0.023431 -0.038002 0.140842 -v -0.026758 -0.030913 0.141748 -v -0.019258 -0.015750 0.145442 -v -0.021484 -0.014835 0.144778 -v -0.020322 -0.018556 0.144942 -v -0.022585 -0.017475 0.144274 -v -0.021557 -0.021398 0.144352 -v -0.025442 -0.023071 0.142927 -v -0.017549 -0.018409 0.145592 -v -0.019177 -0.022624 0.144759 -v -0.023084 -0.024510 0.143607 -v -0.018146 -0.027279 0.144084 -v -0.016748 -0.023813 0.144897 -v -0.014641 -0.017526 0.146086 -v -0.019608 -0.030529 0.143214 -v -0.020643 -0.025918 0.143994 -v -0.027247 -0.026068 0.142049 -v -0.019744 -0.030834 0.143133 -v -0.022318 -0.029298 0.143098 -v -0.024830 -0.027703 0.142735 -v -0.028911 -0.028583 0.141219 -v -0.031410 -0.032101 0.139941 -v -0.021509 -0.034409 0.142053 -v -0.024169 -0.032698 0.142082 -v -0.028859 -0.034139 0.140641 -v -0.031125 -0.037378 0.139412 -v -0.036248 -0.038166 0.137345 -v -0.026186 -0.036116 0.140943 -v -0.033546 -0.040626 0.138059 -v -0.035908 -0.045465 0.136313 -v -0.033742 -0.045937 0.136769 -v -0.025503 -0.041610 0.139497 -v -0.028360 -0.039550 0.139678 -v -0.030683 -0.042996 0.138283 -v -0.053580 -0.061517 0.101752 -v -0.073039 -0.034775 0.116842 -v -0.101802 -0.025525 0.093966 -v -0.106757 -0.023625 0.089171 -v -0.042633 -0.045515 0.133302 -v -0.039701 -0.043611 0.135198 -v -0.041835 -0.041555 0.134426 -v -0.039552 -0.046962 0.134484 -v -0.042634 -0.049402 0.131851 -v -0.042346 -0.053039 0.129876 -v -0.039066 -0.054261 0.130898 -v -0.041774 -0.056337 0.127424 -v -0.037758 -0.059110 0.126886 -v -0.038337 -0.057336 0.128580 -v -0.040934 -0.059215 0.124557 -v -0.039845 -0.061603 0.121343 -v -0.032948 -0.065263 0.116779 -v -0.035381 -0.065306 0.110445 -v -0.030671 -0.066060 0.113937 -v -0.031779 -0.065730 0.115307 -v -0.037034 -0.064686 0.114199 -v -0.105180 -0.041502 0.077329 -v -0.107049 -0.040650 0.075528 -v -0.109591 -0.035423 0.079849 -v -0.108571 -0.038167 0.077685 -v -0.108266 -0.033265 0.083822 -v -0.110278 -0.032391 0.081769 -v -0.110561 -0.027324 0.084149 -v -0.103345 -0.028668 0.091932 -v -0.108513 -0.026607 0.086849 -v -0.103123 -0.035408 0.088844 -v -0.108577 -0.030013 0.085489 -v -0.102457 -0.038471 0.086845 -v -0.107587 -0.036302 0.081881 -v -0.106551 -0.039065 0.079703 -v -0.098418 -0.045729 0.079511 -v -0.103499 -0.043565 0.074806 -v -0.101540 -0.045216 0.072180 -v -0.098013 -0.030684 0.096845 -v -0.103421 -0.032119 0.090551 -v -0.098098 -0.034181 0.095446 -v -0.097812 -0.037507 0.093702 -v -0.101437 -0.041248 0.084593 -v -0.100081 -0.043683 0.082132 -v -0.091257 -0.049428 0.081229 -v -0.096478 -0.047346 0.076782 -v -0.094302 -0.048501 0.073998 -v -0.092520 -0.032648 0.101586 -v -0.097160 -0.040596 0.091647 -v -0.090705 -0.045470 0.093891 -v -0.096154 -0.043386 0.089323 -v -0.094816 -0.045819 0.086777 -v -0.087766 -0.049908 0.088452 -v -0.085878 -0.051453 0.085519 -v -0.093173 -0.047846 0.084061 -v -0.086697 -0.051420 0.080224 -v -0.089108 -0.050531 0.078338 -v -0.083760 -0.052503 0.082523 -v -0.078262 -0.054410 0.086554 -v -0.080342 -0.053414 0.089652 -v -0.089386 -0.047900 0.091262 -v -0.083793 -0.049918 0.095587 -v -0.091694 -0.042669 0.096285 -v -0.086063 -0.044679 0.100758 -v -0.086691 -0.041539 0.102917 -v -0.092334 -0.039554 0.098393 -v -0.086961 -0.038138 0.104729 -v -0.092611 -0.036190 0.100172 -v -0.086867 -0.034550 0.106154 -v -0.086411 -0.030850 0.107163 -v -0.092062 -0.028999 0.102604 -v -0.081147 -0.040017 0.109115 -v -0.080882 -0.043454 0.107274 -v -0.085090 -0.047492 0.098297 -v -0.076471 -0.053833 0.096758 -v -0.082199 -0.051907 0.092684 -v -0.081054 -0.036383 0.110550 -v -0.080265 -0.046619 0.105066 -v -0.077596 -0.049996 0.103744 -v -0.076329 -0.052417 0.100932 -v -0.079309 -0.049443 0.102540 -v -0.078035 -0.051865 0.099750 -v -0.074774 -0.054379 0.097914 -v -0.074650 -0.055303 0.093629 -v -0.071799 -0.056496 0.090964 -v -0.079333 -0.036903 0.111797 -v -0.079425 -0.040550 0.110359 -v -0.079161 -0.043997 0.108510 -v -0.072691 -0.048959 0.110277 -v -0.078547 -0.047169 0.106288 -v -0.071758 -0.051797 0.107672 -v -0.067090 -0.036321 0.120697 -v -0.071612 -0.035146 0.117767 -v -0.073472 -0.038592 0.115863 -v -0.067319 -0.047434 0.116385 -v -0.073558 -0.042282 0.114419 -v -0.073296 -0.045764 0.112543 -v -0.066723 -0.050652 0.114078 -v -0.070516 -0.054213 0.104786 -v -0.068994 -0.056154 0.101683 -v -0.067226 -0.057576 0.098433 -v -0.055441 -0.060751 0.105258 -v -0.059463 -0.060033 0.098516 -v -0.061436 -0.041680 0.123411 -v -0.067505 -0.040186 0.119733 -v -0.061499 -0.045454 0.121960 -v -0.067582 -0.043919 0.118285 -v -0.061234 -0.049002 0.120039 -v -0.060645 -0.052242 0.117691 -v -0.059748 -0.055098 0.114973 -v -0.058562 -0.057503 0.111947 -v -0.065807 -0.053499 0.111415 -v -0.064593 -0.055910 0.108457 -v -0.063107 -0.057830 0.105272 -v -0.057115 -0.059402 0.108683 -v -0.061384 -0.059215 0.101933 -v -0.065251 -0.058447 0.095109 -v -0.072965 -0.055838 0.094756 -v -0.047604 -0.062894 0.104817 -v -0.049401 -0.062178 0.108410 -v -0.052426 -0.058986 0.115257 -v -0.053581 -0.056587 0.118349 -v -0.054460 -0.053723 0.121120 -v -0.055042 -0.050463 0.123504 -v -0.055266 -0.043070 0.126897 -v -0.052032 -0.039682 0.129335 -v -0.054903 -0.039113 0.127826 -v -0.043265 -0.063491 0.111390 -v -0.041289 -0.064204 0.107824 -v -0.038534 -0.063442 0.117862 -v -0.046186 -0.060355 0.118389 -v -0.047309 -0.057961 0.121543 -v -0.048169 -0.055090 0.124364 -v -0.041537 -0.064158 0.107714 -v -0.051021 -0.060865 0.111918 -v -0.044827 -0.062213 0.114977 -v -0.048745 -0.051810 0.126783 -v -0.055313 -0.046883 0.125445 -v -0.049024 -0.048201 0.128742 -v -0.048998 -0.044350 0.130194 -v -0.042341 -0.041473 0.134192 -v -0.011082 -0.003672 0.147520 -v -0.012762 -0.003119 0.147329 -v -0.020708 -0.012673 0.145130 -v -0.018508 -0.013454 0.145790 -v -0.011923 -0.003396 0.147439 -v -0.014672 -0.008629 0.146878 -v -0.016235 -0.014182 0.146242 -v -0.013954 -0.014970 0.146465 -v -0.114593 -0.032795 0.069434 -v -0.114593 -0.029708 0.075718 -v -0.114593 -0.031734 0.072813 -v -0.115578 -0.027834 0.074068 -v -0.112695 -0.028481 0.080732 -v -0.110618 -0.025584 0.084708 -v -0.112667 -0.024176 0.082287 -v -0.112695 -0.026416 0.081677 -v -0.110597 -0.029160 0.083411 -v -0.110355 -0.034205 0.080002 -v -0.103520 -0.044352 0.070296 -v -0.104908 -0.043404 0.070856 -v -0.107620 -0.041497 0.070769 -v -0.105511 -0.042674 0.072853 -v -0.110355 -0.039141 0.067663 -v -0.108626 -0.040780 0.067663 -v -0.107620 -0.040792 0.073803 -v -0.110355 -0.038934 0.070376 -v -0.112695 -0.030379 0.079485 -v -0.112695 -0.032066 0.077964 -v -0.110355 -0.035927 0.077895 -v -0.112695 -0.033503 0.076205 -v -0.112695 -0.034657 0.074249 -v -0.110355 -0.037308 0.075551 -v -0.112695 -0.035500 0.072140 -v -0.110355 -0.038319 0.073026 -v -0.112695 -0.036187 0.067663 -v -0.114593 -0.026905 0.077883 -v -0.114593 -0.028389 0.076907 -v -0.114593 -0.030832 0.074343 -v -0.114593 -0.032393 0.071164 -v -0.112695 -0.036014 0.069928 -v -0.101313 -0.045579 0.067663 -v -0.104544 -0.043912 0.067663 -v -0.107525 -0.041811 -0.001018 -v -0.105164 -0.043473 0.067663 -v -0.108626 -0.040780 -0.001018 -v -0.107620 -0.041734 0.067663 -v -0.111609 -0.037565 -0.001018 -v -0.111605 -0.037563 0.067663 -v -0.114035 -0.033912 -0.001018 -v -0.114024 -0.033906 0.067663 -v -0.114593 -0.032930 0.067663 -v -0.115351 -0.027283 0.075623 -v -0.115893 -0.029159 0.070150 -v -0.117390 -0.025022 0.066674 -v -0.117941 -0.022994 0.066317 -v -0.112697 -0.023212 0.082492 -v -0.111559 -0.017892 0.084460 -v -0.117867 -0.022037 0.070268 -v -0.120296 -0.010136 0.064770 -v -0.119923 -0.011009 0.068742 -v -0.120557 -0.007652 0.064596 -v -0.115905 -0.009224 0.079536 -v -0.120596 0.007167 0.064570 -v -0.116265 0.005749 0.079197 -v -0.113910 0.005339 0.082257 -v -0.115958 0.008800 0.079486 -v -0.115513 0.011898 0.079904 -v -0.120335 0.006862 0.068431 -v -0.111898 0.016708 0.084147 -v -0.114938 0.014959 0.080439 -v -0.114280 -0.025472 0.079234 -v -0.113888 -0.019281 0.081408 -v -0.114848 -0.015382 0.080523 -v -0.115445 -0.012303 0.079968 -v -0.117302 -0.013153 0.076583 -v -0.117776 -0.009860 0.076158 -v -0.116233 -0.006138 0.079228 -v -0.118113 -0.006561 0.075854 -v -0.116429 -0.003038 0.079042 -v -0.118315 -0.003248 0.075672 -v -0.116493 0.000082 0.078982 -v -0.118329 0.002887 0.075659 -v -0.116443 0.002701 0.079030 -v -0.117372 0.012720 0.076520 -v -0.114231 0.018004 0.081093 -v -0.113389 0.021036 0.081864 -v -0.115665 -0.026336 0.075358 -v -0.115698 -0.020715 0.078004 -v -0.117192 -0.020945 0.074125 -v -0.116688 -0.016446 0.077129 -v -0.119125 -0.010460 0.072533 -v -0.119478 -0.006960 0.072239 -v -0.119689 -0.003445 0.072062 -v -0.118380 0.000087 0.075613 -v -0.119704 0.003062 0.072050 -v -0.118146 0.006145 0.075824 -v -0.117830 0.009407 0.076109 -v -0.119182 0.009979 0.072486 -v -0.118702 0.013493 0.072885 -v -0.116781 0.015994 0.077047 -v -0.118083 0.016966 0.073396 -v -0.117320 0.020422 0.074021 -v -0.116053 0.019252 0.077691 -v -0.115185 0.022497 0.078451 -v -0.116412 0.023864 0.074758 -v -0.119473 0.014201 0.069078 -v -0.119983 0.010503 0.068696 -v -0.120538 0.003224 0.068278 -v -0.119512 0.006519 0.072210 -v -0.119758 0.000093 0.072004 -v -0.120596 0.000098 0.068234 -v -0.120523 -0.003627 0.068289 -v -0.120298 -0.007326 0.068459 -v -0.119395 -0.014684 0.069137 -v -0.118628 -0.013953 0.072946 -v -0.118711 -0.018358 0.069645 -v -0.117986 -0.017446 0.073476 -v -0.117354 -0.023986 0.070643 -v -0.116709 -0.022800 0.074517 -v -0.116246 -0.027699 0.071449 -v -0.115934 -0.028659 0.071664 -v -0.117039 0.025104 0.070874 -v -0.118960 0.018636 0.065652 -v -0.118815 0.017853 0.069568 -v -0.118004 0.021487 0.070167 -v -0.118088 0.022422 0.066222 -v -0.114455 -0.033207 -0.001018 -v -0.104492 -0.043788 -0.003668 -v -0.104492 -0.043943 -0.001018 -v -0.105163 -0.043472 -0.001018 -v -0.107525 -0.041250 -0.005787 -v -0.107525 -0.041671 -0.003419 -v -0.110230 -0.038785 -0.005199 -v -0.112505 -0.035985 -0.004546 -v -0.112555 -0.036287 -0.002786 -v -0.110230 -0.039154 -0.003123 -v -0.110230 -0.039277 -0.001018 -v -0.112555 -0.036390 -0.001018 -v -0.114455 -0.033126 -0.002414 -v -0.114593 0.026905 0.077883 -v -0.104539 0.043490 0.071635 -v -0.107620 0.041497 0.070769 -v -0.105485 0.042688 0.072879 -v -0.106287 0.041704 0.074060 -v -0.107620 0.040792 0.073803 -v -0.110355 0.038319 0.073026 -v -0.107742 0.039610 0.076330 -v -0.110355 0.034205 0.080002 -v -0.112695 0.028481 0.080732 -v -0.112695 0.026416 0.081677 -v -0.110601 0.029161 0.083406 -v -0.112680 0.024298 0.082230 -v -0.112412 0.024044 0.082749 -v -0.114175 0.025723 0.079330 -v -0.114579 0.026249 0.078060 -v -0.114593 0.028389 0.076907 -v -0.115369 0.027249 0.075592 -v -0.114593 0.031734 0.072813 -v -0.115941 0.028600 0.071710 -v -0.114593 0.032795 0.069434 -v -0.115871 0.029538 0.068902 -v -0.114593 0.032930 0.067663 -v -0.104544 0.043650 0.071099 -v -0.104544 0.043912 0.067663 -v -0.107173 0.040618 0.075363 -v -0.107620 0.041734 0.067663 -v -0.108626 0.040780 0.067663 -v -0.110279 0.032391 0.081767 -v -0.112695 0.030379 0.079485 -v -0.110355 0.035926 0.077895 -v -0.112695 0.034657 0.074249 -v -0.110355 0.037308 0.075551 -v -0.112695 0.035500 0.072140 -v -0.112695 0.036014 0.069928 -v -0.110355 0.038934 0.070376 -v -0.112695 0.032066 0.077964 -v -0.114593 0.029708 0.075718 -v -0.114593 0.030832 0.074343 -v -0.112695 0.033503 0.076205 -v -0.114593 0.032393 0.071164 -v -0.112695 0.036187 0.067663 -v -0.029237 -0.066317 -0.029533 -v -0.024881 -0.066954 -0.030020 -v -0.024952 -0.066573 -0.034595 -v -0.025616 -0.065706 -0.037627 -v -0.104505 -0.043362 -0.006075 -v -0.100969 -0.043941 -0.012011 -v -0.099710 -0.045469 -0.009537 -v -0.099187 -0.044703 -0.013193 -v -0.089116 -0.050335 -0.012814 -v -0.093743 -0.048529 -0.009990 -v -0.096648 -0.047547 -0.004404 -v -0.101313 -0.045579 -0.001018 -v -0.103017 -0.044633 -0.003552 -v -0.091543 -0.047868 -0.018010 -v -0.095116 -0.047390 -0.012582 -v -0.085600 -0.051079 -0.018141 -v -0.079535 -0.053792 -0.017943 -v -0.084381 -0.052090 -0.015465 -v -0.092212 -0.049331 -0.007361 -v -0.087497 -0.049427 -0.020275 -v -0.081666 -0.051567 -0.023299 -v -0.080675 -0.052840 -0.020658 -v -0.075362 -0.053704 -0.026183 -v -0.074576 -0.055435 -0.020250 -v -0.078263 -0.054409 -0.015190 -v -0.061781 -0.059232 -0.025232 -v -0.060829 -0.059670 -0.022356 -v -0.071322 -0.055005 -0.027887 -v -0.070476 -0.056172 -0.025174 -v -0.065198 -0.057736 -0.027174 -v -0.062628 -0.058458 -0.028070 -v -0.063361 -0.057358 -0.030831 -v -0.058009 -0.058802 -0.032546 -v -0.057354 -0.059861 -0.029755 -v -0.055732 -0.060989 -0.023983 -v -0.051333 -0.061871 -0.028369 -v -0.050568 -0.062227 -0.025435 -v -0.046595 -0.062401 -0.032594 -v -0.041530 -0.062569 -0.036613 -v -0.036897 -0.063440 -0.037436 -v -0.035896 -0.063628 -0.037613 -v -0.030191 -0.064583 -0.038435 -v -0.029615 -0.066081 -0.032554 -v -0.029688 -0.065544 -0.035547 -v -0.035147 -0.065169 -0.031767 -v -0.035557 -0.064566 -0.034730 -v -0.041111 -0.063531 -0.033750 -v -0.040611 -0.064161 -0.030808 -v -0.046006 -0.063061 -0.029675 -v -0.052009 -0.061176 -0.031263 -v -0.056591 -0.060594 -0.026888 -v -0.064308 -0.058532 -0.024352 -v -0.069502 -0.057017 -0.022386 -v -0.075634 -0.054539 -0.023002 -v -0.090413 -0.049262 -0.015449 -v -0.098263 -0.046677 -0.006989 -v -0.120297 -0.010136 -0.033087 -v -0.120413 -0.009212 -0.034716 -v -0.111666 -0.022473 -0.048926 -v -0.114972 -0.021937 -0.039957 -v -0.117484 -0.015961 -0.045704 -v -0.116462 -0.017523 -0.046400 -v -0.115291 -0.019028 -0.047112 -v -0.117052 -0.019068 -0.038741 -v -0.118352 -0.014367 -0.045029 -v -0.119154 -0.012551 -0.044304 -v -0.119738 -0.010868 -0.043672 -v -0.120503 -0.007459 -0.042498 -v -0.114867 -0.031063 -0.009461 -v -0.114430 -0.033047 -0.002786 -v -0.113280 -0.033345 -0.010747 -v -0.113565 -0.034563 -0.003672 -v -0.112002 -0.036659 -0.004959 -v -0.110183 -0.038569 -0.006198 -v -0.108130 -0.040269 -0.007375 -v -0.106890 -0.038890 -0.014224 -v -0.109264 -0.037285 -0.013144 -v -0.111403 -0.035428 -0.011980 -v -0.114426 -0.029948 -0.016956 -v -0.116032 -0.027473 -0.015670 -v -0.118609 -0.020146 -0.016065 -v -0.108511 -0.033095 -0.026794 -v -0.111115 -0.031209 -0.025758 -v -0.110269 -0.034232 -0.019336 -v -0.115406 -0.026577 -0.023395 -v -0.112495 -0.032212 -0.018184 -v -0.117291 -0.024824 -0.014344 -v -0.118254 -0.021057 -0.020776 -v -0.118184 -0.022039 -0.012998 -v -0.117097 -0.026030 -0.006799 -v -0.116145 -0.028614 -0.008139 -v -0.114865 -0.032274 -0.002335 -v -0.116335 -0.022756 -0.031032 -v -0.113426 -0.029024 -0.024619 -v -0.117025 -0.023907 -0.022107 -v -0.119075 -0.018073 -0.019422 -v -0.112474 -0.024498 -0.041068 -v -0.111895 -0.027790 -0.033376 -v -0.114302 -0.025415 -0.032251 -v -0.118672 -0.015948 -0.037445 -v -0.117958 -0.019859 -0.029741 -v -0.119799 -0.012641 -0.036094 -v -0.119142 -0.016778 -0.028400 -v -0.114455 0.033207 -0.001018 -v -0.114035 0.033912 -0.001018 -v -0.114024 0.033906 0.067663 -v -0.112555 0.036390 -0.001018 -v -0.111605 0.037563 0.067663 -v -0.110230 0.039277 -0.001018 -v -0.110355 0.039141 0.067663 -v -0.108626 0.040780 -0.001018 -v -0.107525 0.041811 -0.001018 -v -0.105164 0.043473 0.067663 -v -0.101313 0.045579 -0.001018 -v -0.101313 0.045579 0.067663 -v -0.067536 0.040178 0.119714 -v -0.078918 0.033127 0.112768 -v -0.092881 0.048793 0.079877 -v -0.099671 0.030069 0.095351 -v -0.037787 0.059098 0.126881 -v -0.038340 0.057334 0.128579 -v -0.041784 0.056335 0.127420 -v -0.039078 0.054226 0.130918 -v -0.039719 0.049779 0.133252 -v -0.042644 0.049400 0.131847 -v -0.042642 0.045513 0.133297 -v -0.039914 0.041963 0.135307 -v -0.035391 0.065304 0.110441 -v -0.032400 0.065476 0.116152 -v -0.031779 0.065730 0.115307 -v -0.034447 0.064243 0.119364 -v -0.039854 0.061601 0.121339 -v -0.104953 0.028037 0.090386 -v -0.110528 0.025756 0.084777 -v -0.105026 0.031474 0.089010 -v -0.110561 0.027324 0.084149 -v -0.108586 0.038162 0.077662 -v -0.109591 0.035423 0.079849 -v -0.101669 0.043016 0.080670 -v -0.100000 0.045067 0.078079 -v -0.098054 0.046694 0.075382 -v -0.103520 0.044352 0.070296 -v -0.094804 0.047200 0.082677 -v -0.098808 0.039948 0.090186 -v -0.103030 0.040580 0.083104 -v -0.104055 0.037807 0.085334 -v -0.104725 0.034752 0.087315 -v -0.099754 0.033551 0.093958 -v -0.087548 0.050837 0.084217 -v -0.096454 0.045167 0.085365 -v -0.091073 0.047267 0.089900 -v -0.097798 0.042733 0.087884 -v -0.093392 0.042038 0.094877 -v -0.094036 0.038931 0.096969 -v -0.099464 0.036866 0.092225 -v -0.083924 0.051301 0.091402 -v -0.089445 0.049281 0.087119 -v -0.085527 0.049306 0.094277 -v -0.092398 0.044836 0.092504 -v -0.087809 0.044069 0.099403 -v -0.088441 0.040936 0.101546 -v -0.088713 0.037547 0.103348 -v -0.094315 0.035579 0.098738 -v -0.094226 0.032050 0.100147 -v -0.093768 0.028418 0.101167 -v -0.076410 0.054733 0.092427 -v -0.082058 0.052820 0.088400 -v -0.086831 0.046878 0.096962 -v -0.088619 0.033973 0.104771 -v -0.082852 0.035830 0.109222 -v -0.072995 0.055828 0.094736 -v -0.074805 0.054369 0.097893 -v -0.078242 0.053251 0.095527 -v -0.079816 0.051277 0.098492 -v -0.081097 0.048853 0.101258 -v -0.082059 0.046032 0.103764 -v -0.082679 0.042875 0.105957 -v -0.082945 0.039450 0.107790 -v -0.065281 0.058438 0.095090 -v -0.070548 0.054203 0.104766 -v -0.076360 0.052407 0.100910 -v -0.077627 0.049986 0.103722 -v -0.071789 0.051787 0.107651 -v -0.078578 0.047159 0.106266 -v -0.079192 0.043987 0.108487 -v -0.073590 0.042273 0.114398 -v -0.079456 0.040540 0.110337 -v -0.079364 0.036893 0.111774 -v -0.059492 0.060026 0.098499 -v -0.061414 0.059207 0.101916 -v -0.067257 0.057566 0.098414 -v -0.069025 0.056144 0.101663 -v -0.065838 0.053491 0.111396 -v -0.066754 0.050644 0.114059 -v -0.067350 0.047426 0.116366 -v -0.072723 0.048950 0.110256 -v -0.073328 0.045754 0.112522 -v -0.073503 0.038583 0.115841 -v -0.071612 0.035146 0.117767 -v -0.053607 0.061511 0.101737 -v -0.056643 0.060745 0.100067 -v -0.063137 0.057822 0.105254 -v -0.064623 0.055902 0.108439 -v -0.067613 0.043911 0.118266 -v -0.061464 0.041674 0.123394 -v -0.055469 0.060744 0.105243 -v -0.049424 0.062172 0.108398 -v -0.057143 0.059395 0.108668 -v -0.052449 0.058981 0.115245 -v -0.058590 0.057496 0.111931 -v -0.059776 0.055090 0.114957 -v -0.060674 0.052235 0.117675 -v -0.061262 0.048995 0.120022 -v -0.061527 0.045447 0.121944 -v -0.054926 0.039108 0.127813 -v -0.047627 0.062889 0.104806 -v -0.051045 0.060860 0.111906 -v -0.048187 0.055086 0.124355 -v -0.053605 0.056581 0.118336 -v -0.054484 0.053717 0.121107 -v -0.048763 0.051806 0.126774 -v -0.049041 0.048197 0.128733 -v -0.055066 0.050457 0.123491 -v -0.055336 0.046878 0.125432 -v -0.052032 0.039682 0.129335 -v -0.055290 0.043065 0.126884 -v -0.037044 0.064684 0.114195 -v -0.038544 0.063440 0.117858 -v -0.043282 0.063488 0.111382 -v -0.044845 0.062209 0.114969 -v -0.046204 0.060351 0.118380 -v -0.040943 0.059214 0.124552 -v -0.047327 0.057957 0.121534 -v -0.042355 0.053037 0.129872 -v -0.049015 0.044346 0.130185 -v -0.104527 0.043352 -0.006066 -v -0.114455 0.033126 -0.002414 -v -0.107525 0.041250 -0.005787 -v -0.104492 0.043788 -0.003668 -v -0.104492 0.043943 -0.001018 -v -0.105163 0.043472 -0.001018 -v -0.110230 0.038785 -0.005199 -v -0.112555 0.036287 -0.002786 -v -0.110230 0.039154 -0.003123 -v -0.107525 0.041671 -0.003419 -v -0.115849 0.029915 -0.001018 -v -0.111609 0.037565 -0.001018 -v -0.031327 0.058901 0.129337 -v -0.033704 0.056976 0.130823 -v -0.039637 0.043457 0.135260 -v -0.036945 0.048881 0.134825 -v -0.035329 0.053921 0.132720 -v -0.034749 0.055101 0.132059 -v -0.031494 0.059764 0.128416 -v -0.031095 0.057704 0.130615 -v -0.038385 0.044731 0.135539 -v -0.035113 0.052102 0.133880 -v -0.033150 0.055064 0.132467 -v -0.030760 0.055598 0.132447 -v -0.032736 0.053070 0.133899 -v -0.032405 0.051263 0.134958 -v -0.034285 0.048999 0.135584 -v -0.034056 0.047878 0.136071 -v -0.036468 0.047703 0.135428 -v -0.034650 0.050469 0.134853 -v -0.030691 0.055109 0.132823 -v -0.030471 0.053372 0.134031 -v -0.037242 0.042809 0.136359 -v -0.035671 0.044753 0.136540 -v -0.036019 0.046376 0.135996 -v -0.033987 0.046309 0.136615 -v -0.032198 0.049865 0.135667 -v -0.119058 0.012775 -0.044393 -v -0.120056 0.009718 -0.043260 -v -0.120722 0.005325 -0.041833 -v -0.118691 0.015826 -0.037691 -v -0.119817 0.012512 -0.036340 -v -0.117522 0.015877 -0.045668 -v -0.114990 0.021828 -0.040203 -v -0.117071 0.018953 -0.038987 -v -0.115832 0.018365 -0.046793 -v -0.112489 0.024396 -0.041314 -v -0.113069 0.021324 -0.048243 -v -0.111412 0.022665 -0.049037 -v -0.110265 0.038369 -0.006559 -v -0.113652 0.034341 -0.004033 -v -0.115027 0.031836 -0.003075 -v -0.116018 0.029421 -0.001739 -v -0.115059 0.030506 -0.010406 -v -0.112174 0.036237 -0.005681 -v -0.109431 0.036810 -0.014087 -v -0.108206 0.040079 -0.007735 -v -0.107904 0.035528 -0.021371 -v -0.112650 0.031716 -0.019167 -v -0.111583 0.034928 -0.012925 -v -0.113468 0.032817 -0.011692 -v -0.116335 0.028026 -0.009084 -v -0.118612 0.020147 -0.016058 -v -0.118334 0.021423 -0.013979 -v -0.117278 0.025411 -0.007744 -v -0.111215 0.030812 -0.026623 -v -0.115524 0.026134 -0.024263 -v -0.114350 0.025192 -0.032735 -v -0.117143 0.023438 -0.022974 -v -0.118368 0.020561 -0.021642 -v -0.110411 0.033761 -0.020317 -v -0.113537 0.028606 -0.025486 -v -0.114588 0.029424 -0.017940 -v -0.116197 0.026919 -0.016653 -v -0.117452 0.024238 -0.015326 -v -0.119190 0.016513 -0.028883 -v -0.120426 0.009076 -0.034961 -v -0.118009 0.019609 -0.030224 -v -0.116386 0.022520 -0.031516 -v -0.109619 0.026603 -0.042297 -v -0.111938 0.027578 -0.033859 -v -0.109193 0.029635 -0.034868 -v -0.024963 0.065356 -0.039025 -v -0.030143 0.064590 -0.038441 -v -0.029887 0.065508 -0.035540 -v -0.024881 0.066954 -0.030020 -v -0.025768 0.066824 -0.029921 -v -0.029191 0.066324 -0.029539 -v -0.029569 0.066088 -0.032560 -v -0.098709 0.046689 -0.002945 -v -0.100362 0.045787 -0.005508 -v -0.094317 0.048495 -0.005988 -v -0.089811 0.050262 -0.008861 -v -0.086699 0.051424 -0.010681 -v -0.091297 0.049495 -0.011513 -v -0.105867 0.041740 -0.008475 -v -0.101844 0.044545 -0.008034 -v -0.099191 0.044706 -0.013204 -v -0.093791 0.046968 -0.016669 -v -0.088938 0.048884 -0.019498 -v -0.086589 0.051283 -0.014258 -v -0.078853 0.052545 -0.024637 -v -0.071796 0.056488 -0.018132 -v -0.074905 0.055515 -0.016778 -v -0.075360 0.053701 -0.026177 -v -0.072160 0.055651 -0.024490 -v -0.071158 0.056512 -0.021713 -v -0.070038 0.057038 -0.018898 -v -0.066120 0.058015 -0.023691 -v -0.065090 0.058493 -0.020842 -v -0.056644 0.060750 -0.023684 -v -0.060062 0.059875 -0.022614 -v -0.061000 0.059443 -0.025494 -v -0.061835 0.058676 -0.028336 -v -0.054953 0.061182 -0.024214 -v -0.050513 0.062061 -0.028582 -v -0.049763 0.062412 -0.025645 -v -0.039695 0.064338 -0.030981 -v -0.044491 0.063559 -0.026906 -v -0.051742 0.060354 -0.034301 -v -0.050003 0.060746 -0.034721 -v -0.051176 0.061372 -0.031480 -v -0.039137 0.064622 -0.027996 -v -0.033700 0.065596 -0.028916 -v -0.034159 0.065340 -0.031921 -v -0.040180 0.063713 -0.033927 -v -0.045720 0.062588 -0.032791 -v -0.045146 0.063243 -0.029868 -v -0.056547 0.060067 -0.029995 -v -0.055798 0.060793 -0.027124 -v -0.067039 0.057203 -0.026502 -v -0.077550 0.053905 -0.022138 -v -0.076461 0.054822 -0.019399 -v -0.082937 0.052044 -0.019531 -v -0.081761 0.053022 -0.016833 -v -0.087845 0.050244 -0.016915 -v -0.092630 0.048391 -0.014128 -v -0.097296 0.046490 -0.011168 -v -0.095888 0.047661 -0.008597 -v -0.103021 0.044631 -0.003546 -v -0.040586 0.062755 -0.036794 -v -0.034553 0.064741 -0.034887 -v -0.026084 0.066075 -0.035979 -v -0.032905 0.034060 0.139156 -v -0.030729 0.036823 0.139629 -v -0.038886 0.041192 0.135862 -v -0.030333 0.030630 0.140498 -v -0.030052 0.048843 0.136394 -v -0.028218 0.046023 0.137670 -v -0.032047 0.047665 0.136579 -v -0.025854 0.042182 0.139261 -v -0.025527 0.041650 0.139481 -v -0.024755 0.040334 0.139988 -v -0.025184 0.034452 0.141513 -v -0.019622 0.030525 0.143202 -v -0.021178 0.027035 0.143710 -v -0.018657 0.028453 0.143783 -v -0.017103 0.024734 0.144692 -v -0.019550 0.023500 0.144566 -v -0.015775 0.021120 0.145451 -v -0.034096 0.041339 0.137745 -v -0.031211 0.043752 0.137960 -v -0.027960 0.038943 0.139922 -v -0.027816 0.032568 0.141194 -v -0.025596 0.029012 0.142346 -v -0.023054 0.030684 0.142698 -v -0.023642 0.025565 0.143331 -v -0.021946 0.022225 0.144164 -v -0.019407 0.016170 0.145373 -v -0.018158 0.020065 0.145281 -v -0.028039 0.027296 0.141657 -v -0.026018 0.024062 0.142649 -v -0.024265 0.020924 0.143489 -v -0.022765 0.017872 0.144191 -v -0.020495 0.018979 0.144860 -v -0.014778 0.017993 0.146010 -v -0.017113 0.017094 0.145808 -v -0.012762 0.003119 0.147329 -v -0.011923 0.003396 0.147439 -v -0.010148 0.000022 0.147653 -v -0.013954 0.014970 0.146465 -v -0.016250 0.014222 0.146237 -v -0.014672 0.008629 0.146878 -v -0.011082 0.003672 0.147520 -v -0.018508 0.013454 0.145790 -v -0.031382 0.028517 0.140200 -v -0.023863 -0.020146 0.143678 -v -0.033750 -0.035131 0.138705 -v -0.031382 -0.028517 0.140200 -v -0.048668 -0.040349 0.131103 -v -0.061044 -0.037769 0.124358 -v -0.052045 -0.027875 0.130287 -v -0.080774 -0.032581 0.111421 -v -0.071623 -0.027104 0.118383 -v -0.078887 -0.033136 0.112790 -v -0.080945 -0.026672 0.111720 -v -0.097557 -0.027088 0.097870 -v -0.089908 -0.029705 0.104342 -v -0.112508 -0.014277 0.083578 -v -0.102896 -0.025123 0.092961 -v -0.108075 -0.023114 0.087878 -v -0.110243 -0.021914 0.085668 -v -0.113554 -0.008564 0.082594 -v -0.112997 -0.011911 0.083120 -v -0.113606 0.008171 0.082545 -v -0.114110 0.001273 0.082066 -v -0.114073 -0.002822 0.082102 -v -0.106749 0.023623 0.089163 -v -0.110102 0.022300 0.085796 -v -0.111066 0.019516 0.084915 -v -0.112597 0.013885 0.083495 -v -0.106773 0.012610 0.089700 -v -0.104508 0.024509 0.091414 -v -0.099217 0.026488 0.096378 -v -0.080945 0.026672 0.111720 -v -0.082400 0.032094 0.110224 -v -0.088162 0.030289 0.105783 -v -0.073071 0.034767 0.116821 -v -0.071623 0.027104 0.118383 -v -0.067121 0.036314 0.120678 -v -0.061982 0.027505 0.124577 -v -0.061072 0.037762 0.124341 -v -0.048685 0.040346 0.131094 -v -0.033777 0.035165 0.138691 -v -0.036816 0.038831 0.137030 -v -0.042351 0.041471 0.134187 -v -0.031381 0.032028 0.139951 -v -0.020708 0.012673 0.145130 -v -0.021638 0.015230 0.144708 -v -0.031382 0.014266 0.140892 -v -0.098542 0.025722 0.097055 -v -0.101785 0.025527 0.093968 -v -0.089926 0.026211 0.104605 -v -0.089926 0.013113 0.105241 -v -0.080945 0.013343 0.112368 -v -0.061982 0.013760 0.125244 -v -0.052045 0.027875 0.130287 -v -0.041836 0.028213 0.135499 -v -0.113166 0.011046 0.082961 -v -0.106773 -0.000000 0.089904 -v -0.098542 0.012868 0.097679 -v -0.089926 -0.000000 0.105453 -v -0.071623 0.000000 0.119260 -v -0.071623 0.013559 0.119041 -v -0.052045 0.013945 0.130963 -v -0.041836 0.014114 0.136183 -v -0.031382 0.000000 0.141122 -v -0.113879 -0.005699 0.082287 -v -0.106773 -0.012610 0.089700 -v -0.098542 -0.000000 0.097887 -v -0.098542 -0.012868 0.097679 -v -0.080945 0.000000 0.112583 -v -0.071623 -0.013559 0.119041 -v -0.061982 -0.000000 0.125467 -v -0.052045 -0.000000 0.131189 -v -0.052045 -0.013945 0.130963 -v -0.041836 0.000000 0.136412 -v -0.031382 -0.014266 0.140892 -v -0.098542 -0.025722 0.097055 -v -0.089926 -0.013113 0.105241 -v -0.080945 -0.013343 0.112368 -v -0.089926 -0.026211 0.104605 -v -0.061982 -0.013760 0.125244 -v -0.061982 -0.027505 0.124577 -v -0.041836 -0.014114 0.136183 -v -0.041836 -0.028213 0.135499 -v -0.013671 0.004205 0.147131 -v -0.013677 -0.000000 0.147190 -v -0.017234 0.000000 0.146404 -v -0.016778 0.007916 0.146453 -v -0.016778 -0.007916 0.146453 -v -0.017228 -0.008461 0.146301 -v -0.020708 0.000000 0.145310 -v -0.104910 -0.010130 -0.064077 -v -0.111247 -0.007924 -0.059500 -v -0.110619 0.008146 -0.060010 -v -0.108677 -0.008793 -0.061471 -v -0.107667 -0.009129 -0.062232 -v -0.104910 0.010130 -0.064077 -v -0.104292 -0.010354 -0.064491 -v -0.104292 0.010354 -0.064491 -v -0.100387 -0.011846 -0.066823 -v -0.095968 -0.013574 -0.069183 -v -0.095681 0.013686 -0.069321 -v -0.095968 0.013574 -0.069183 -v -0.090667 0.015643 -0.071710 -v -0.090192 -0.015824 -0.071912 -v -0.070301 0.022891 -0.079273 -v -0.070301 -0.022891 -0.079273 -v -0.073675 -0.021807 -0.078222 -v -0.077481 0.020497 -0.076911 -v -0.079486 0.019807 -0.076220 -v -0.055517 -0.021499 -0.083341 -v -0.055517 0.021499 -0.083341 -v -0.054475 0.021007 -0.083576 -v -0.054475 -0.021007 -0.083576 -v -0.047792 -0.017854 -0.085084 -v -0.045932 -0.016976 -0.085448 -v -0.045932 0.016976 -0.085448 -v -0.037066 -0.012791 -0.087114 -v -0.031097 -0.009971 -0.088110 -v -0.021564 -0.005452 -0.089423 -v -0.021564 0.005452 -0.089423 -v -0.018672 -0.004074 -0.089738 -v -0.114765 0.004132 -0.056317 -v -0.111885 -0.007637 -0.058966 -v -0.111749 0.007705 -0.059081 -v -0.112535 0.007267 -0.058403 -v -0.114202 -0.005606 -0.056867 -v -0.114958 0.001715 -0.056122 -v -0.016677 0.067973 -0.027144 -v -0.010241 0.068610 0.109650 -v -0.041289 0.064204 0.107824 -v -0.022160 0.067318 0.111685 -v -0.025765 0.066805 0.112231 -v -0.029626 0.066257 0.112816 -v -0.041287 0.064195 -0.027558 -v -0.041554 0.064155 0.107706 -v -0.070971 0.056753 0.091508 -v -0.071798 0.056494 0.090959 -v -0.079965 0.053832 0.085333 -v -0.075584 0.055295 -0.016466 -v -0.074359 0.055690 0.089259 -v -0.080449 0.053666 -0.014098 -v -0.085420 0.051903 0.081253 -v -0.085189 0.051987 -0.011563 -v -0.086699 0.051423 0.080232 -v -0.095870 0.047866 0.072631 -v -0.090722 0.049912 0.077019 -v -0.010131 -0.068619 -0.024813 -v -0.010235 -0.068610 -0.024851 -v -0.025768 -0.066824 -0.029921 -v -0.022160 -0.067318 0.111685 -v -0.025765 -0.066805 0.112231 -v -0.041287 -0.064198 -0.027564 -v -0.040037 -0.064450 -0.027826 -v -0.034670 -0.065430 -0.028765 -v -0.056645 -0.060753 -0.023691 -v -0.056643 -0.060745 0.100067 -v -0.045336 -0.063382 -0.026716 -v -0.063311 -0.058993 -0.021492 -v -0.071796 -0.056488 -0.018133 -v -0.070941 -0.056762 0.091527 -v -0.068411 -0.057527 -0.019560 -v -0.072613 -0.056244 0.090429 -v -0.083021 -0.052766 -0.012751 -v -0.073394 -0.055998 -0.017459 -v -0.086700 -0.051426 -0.010687 -v -0.087670 -0.051072 -0.010142 -v -0.099341 -0.046422 0.069504 -v -0.012806 0.065117 -0.044386 -v -0.017885 0.056116 -0.067422 -v -0.010131 0.056896 -0.067712 -v -0.012174 0.056709 -0.067671 -v -0.010216 0.064969 -0.045511 -v -0.046978 0.049791 -0.067456 -v -0.046207 0.061602 -0.035636 -v -0.050002 0.048790 -0.067558 -v -0.023584 0.065350 -0.039637 -v -0.034877 0.063807 -0.037774 -v -0.036895 0.063435 -0.037428 -v -0.057191 0.059013 -0.032790 -v -0.052682 0.047904 -0.067648 -v -0.062555 0.057583 -0.031102 -v -0.067834 0.056066 -0.029236 -v -0.069868 0.041471 -0.066876 -v -0.062849 0.057498 -0.030998 -v -0.083960 0.050745 -0.022154 -v -0.075856 0.039312 -0.065111 -v -0.075365 0.039489 -0.065256 -v -0.073029 0.054467 -0.027192 -v -0.078140 0.052788 -0.024966 -v -0.092539 0.032310 -0.059079 -v -0.087494 0.049424 -0.020268 -v -0.103133 0.042983 -0.010487 -v -0.107637 0.024859 -0.051238 -v -0.108596 0.032716 -0.027656 -v -0.098521 0.044999 -0.013666 -v -0.107039 0.038438 -0.015164 -v -0.120296 0.010136 -0.033088 -v -0.120815 0.003367 0.064424 -v -0.120864 -0.001547 -0.041722 -v -0.120859 -0.000000 -0.041726 -v -0.120799 -0.003788 0.064435 -v -0.120851 0.002210 -0.041733 -v -0.120875 0.000000 0.064384 -v -0.120877 0.000102 0.064382 -v -0.119668 0.014827 0.065186 -v -0.120218 0.010969 0.064822 -v -0.119178 0.017551 -0.020287 -v -0.120301 0.010136 0.064767 -v -0.119907 0.013289 -0.027517 -v -0.115849 0.029915 0.067663 -v -0.118612 0.020146 0.065879 -v -0.117050 0.026186 0.066893 -v -0.118615 -0.020147 0.065877 -v -0.118848 -0.019162 0.065725 -v -0.119584 -0.015332 0.065241 -v -0.119866 -0.013568 -0.027035 -v -0.120152 -0.011497 0.064865 -v -0.120722 -0.005325 -0.041833 -v -0.115849 -0.029915 0.067663 -v -0.115849 -0.029915 -0.001018 -v -0.116199 -0.028884 0.067440 -v -0.017885 -0.056116 -0.067422 -v -0.012174 -0.056709 -0.067671 -v -0.010131 -0.056896 -0.067712 -v -0.012806 -0.065117 -0.044386 -v -0.023610 -0.055308 -0.067266 -v -0.018651 -0.065328 -0.041825 -v -0.023584 -0.065350 -0.039637 -v -0.024963 -0.065356 -0.039025 -v -0.029367 -0.054279 -0.067199 -v -0.035173 -0.053023 -0.067215 -v -0.041040 -0.051530 -0.067304 -v -0.047094 -0.061410 -0.035436 -v -0.050002 -0.048790 -0.067558 -v -0.050002 -0.060745 -0.034718 -v -0.052587 -0.060153 -0.034080 -v -0.065967 -0.056615 -0.029920 -v -0.062848 -0.057497 -0.030995 -v -0.087500 -0.034574 -0.061101 -v -0.086662 -0.049748 -0.020742 -v -0.076554 -0.053320 -0.025680 -v -0.087234 -0.034693 -0.061207 -v -0.081656 -0.037042 -0.063221 -v -0.092539 -0.032310 -0.059079 -v -0.109159 -0.029836 -0.034386 -v -0.099189 -0.029123 -0.056008 -v -0.096311 -0.045931 -0.015101 -v -0.107637 -0.024859 -0.051238 -v -0.109607 -0.026701 -0.042052 -v -0.105867 -0.041740 -0.008475 -v -0.107781 -0.035977 -0.020394 -v -0.000000 0.057729 -0.068015 -v -0.010215 0.056788 -0.067981 -v -0.011083 0.056242 -0.069104 -v -0.011280 0.055304 -0.070897 -v -0.000000 0.052556 -0.076035 -v -0.000000 0.049890 -0.078252 -v -0.011896 0.048546 -0.077901 -v -0.037608 0.017585 -0.086633 -v -0.027385 0.044517 -0.078554 -v -0.011964 0.047115 -0.078729 -v -0.059494 0.031848 -0.080886 -v -0.000000 0.032141 -0.086287 -v -0.053857 0.034784 -0.080332 -v -0.043181 0.039512 -0.079388 -v -0.039575 0.040834 -0.079135 -v -0.042631 0.020827 -0.085503 -v -0.021860 0.007499 -0.089315 -v -0.026740 0.010619 -0.088568 -v -0.000000 0.021635 -0.089177 -v -0.000000 -0.010880 -0.090925 -v -0.021860 -0.007499 -0.089315 -v -0.000000 0.000000 -0.091510 -v -0.000000 0.010880 -0.090925 -v -0.026740 -0.010619 -0.088568 -v -0.029783 -0.012566 -0.088103 -v -0.045350 -0.022582 -0.084892 -v -0.000000 -0.021635 -0.089177 -v -0.042631 -0.020827 -0.085503 -v -0.037608 -0.017585 -0.086633 -v -0.039575 -0.040834 -0.079135 -v -0.059495 -0.031846 -0.080886 -v -0.000000 -0.032141 -0.086287 -v 0.000000 -0.042276 -0.082287 -v -0.017086 -0.046502 -0.078546 -v 0.000000 -0.069130 -0.031598 -v -0.019308 -0.066094 -0.038945 -v -0.012531 -0.065334 -0.043843 -v -0.017773 -0.065977 -0.040071 -v 0.000000 -0.067764 -0.039345 -v -0.021482 -0.067227 -0.031378 -v -0.023855 -0.066887 -0.032747 -v -0.016221 -0.067983 -0.028345 -v -0.030154 0.050189 0.135798 -v -0.000000 0.052791 0.137448 -v -0.030295 0.051737 0.135006 -v -0.000000 0.060923 0.131243 -v -0.031472 0.061140 0.126695 -v 0.000000 0.064128 0.127235 -v -0.031284 0.061804 0.125785 -v -0.030053 0.063937 0.122323 -v -0.001641 0.067162 0.121170 -v 0.000000 0.066639 0.122760 -v -0.029176 0.064573 0.121123 -v -0.023219 0.066370 0.117366 -v -0.005500 0.068775 0.113554 -v -0.025853 -0.042182 0.139262 -v 0.000000 -0.049830 0.138830 -v -0.027716 -0.045229 0.138013 -v -0.014940 -0.018483 0.145919 -v -0.015616 -0.020650 0.145541 -v 0.000000 -0.030930 0.144886 -v -0.011728 -0.006191 0.147339 -v 0.000000 -0.018668 0.147221 -v -0.012533 -0.009333 0.147113 -v 0.000000 -0.006241 0.148394 -v -0.012533 0.009333 0.147113 -v -0.000000 0.006241 0.148394 -v -0.011728 0.006191 0.147339 -v 0.000000 0.018668 0.147221 -v -0.022477 0.036252 0.141448 -v -0.020445 0.032291 0.142707 -v -0.000000 0.030930 0.144886 -v -0.000000 0.042918 0.141409 -v -0.000000 0.049830 0.138830 -v 0.000000 -0.057729 -0.068015 -v 0.000000 0.067242 0.121357 -v -0.001732 0.083303 0.105499 -v 0.000000 0.083467 0.105569 -v -0.000764 0.084833 0.104368 -v 0.000000 0.085761 0.103138 -v 0.000000 0.086559 0.099891 -v 0.000000 0.084203 0.094963 -v -0.001619 0.069599 0.074088 -v 0.000000 0.079859 0.091984 -v 0.000000 0.076826 0.089163 -v -0.001812 0.070292 0.077706 -v 0.000000 0.074251 0.085918 -v -0.001887 0.075084 0.087361 -v 0.000000 0.069506 0.070461 -v 0.000000 0.071745 0.113859 -v 0.000000 0.069160 0.117485 -v 0.000000 0.074881 0.110696 -v 0.000000 0.078485 0.108081 -v 0.000000 0.083280 0.000681 -v 0.000000 0.084217 0.000025 -v -0.000732 0.085964 -0.002370 -v -0.000000 0.086460 -0.006139 -v -0.001726 0.084921 -0.009115 -v 0.000000 0.084217 -0.010025 -v -0.000000 0.083280 -0.010681 -v -0.000001 0.081800 -0.011331 -v -0.001613 0.069365 0.024398 -v 0.000000 0.069506 0.024539 -v -0.001894 0.069561 0.021034 -v 0.000000 0.069792 0.020580 -v 0.000000 0.070693 0.016537 -v 0.000000 0.072191 0.012675 -v 0.000000 0.074251 0.009082 -v 0.000000 0.076826 0.005837 -v 0.000000 0.079859 0.003016 -v -0.001704 0.084028 -0.000003 -v -0.002770 0.079717 0.002055 -v -0.002293 0.071232 0.013899 -v -0.003000 0.073827 0.006735 -v -0.003000 0.079235 0.001324 -v -0.002910 0.072083 0.010372 -v -0.002874 0.074314 0.007141 -v -0.002059 0.077416 0.004910 -v -0.002894 0.076730 0.004381 -v -0.002484 0.072710 0.010550 -v -0.001711 0.075148 0.007578 -v -0.001645 0.071454 0.013977 -v -0.001646 0.070292 0.017423 -v -0.001764 0.073037 0.010728 -v -0.002410 0.074822 0.007524 -v -0.001909 0.080146 0.002566 -v -0.002880 0.083429 -0.000739 -v -0.002163 0.086248 -0.003804 -v -0.002002 0.082170 -0.010999 -v -0.001551 0.080000 -0.011424 -v -0.002109 0.086355 -0.005656 -v -0.002109 0.085749 -0.007787 -v -0.002110 0.083583 -0.010289 -v -0.002428 0.083844 -0.000255 -v -0.002613 0.084941 -0.001604 -v -0.002957 0.085464 -0.005021 -v -0.002930 0.083841 -0.008895 -v -0.002910 0.072177 -0.010371 -v -0.002978 0.080000 -0.010103 -v -0.002833 0.080940 -0.010584 -v -0.002491 0.080000 -0.011008 -v -0.002050 0.080933 -0.011305 -v -0.002205 0.072361 -0.011211 -v -0.002508 0.072893 0.111795 -v -0.002864 0.072211 0.111776 -v -0.003000 0.081819 0.104488 -v -0.003000 0.078293 0.106201 -v -0.003000 0.075027 0.108369 -v -0.002874 0.078585 0.106764 -v -0.002395 0.078895 0.107334 -v -0.002355 0.070500 0.114718 -v -0.002769 0.075511 0.109100 -v -0.001757 0.073163 0.112078 -v -0.001945 0.076112 0.109458 -v -0.001752 0.078954 0.107611 -v -0.001748 0.070720 0.114895 -v -0.002109 0.085888 0.102477 -v -0.002109 0.086378 0.100351 -v -0.002109 0.086124 0.098183 -v -0.001972 0.085163 0.096211 -v -0.001999 0.083996 0.095020 -v -0.002817 0.083085 0.104830 -v -0.002829 0.083495 0.095622 -v -0.002723 0.084438 0.103901 -v -0.002926 0.085367 0.100763 -v -0.003000 0.083825 0.102423 -v -0.002892 0.084894 0.097314 -v -0.002491 0.071162 0.081246 -v -0.001717 0.071402 0.080927 -v -0.001551 0.072120 0.082358 -v -0.002060 0.072808 0.083999 -v -0.002878 0.072386 0.084920 -v -0.001779 0.077487 0.090075 -v -0.002769 0.074559 0.087782 -v -0.001793 0.080218 0.092466 -v -0.002401 0.077243 0.090271 -v -0.002894 0.076882 0.090771 -v -0.002705 0.079898 0.092933 -v -0.003000 0.079235 0.093676 -v 0.000000 -0.069506 0.070461 -v -0.001613 -0.069365 0.070602 -v -0.001731 -0.084026 0.095004 -v -0.000001 -0.085310 0.096111 -v 0.000000 -0.086444 0.098772 -v 0.000000 -0.085761 0.103138 -v 0.000000 -0.083467 0.105569 -v 0.000000 -0.082464 0.106080 -v 0.000000 -0.069160 0.117485 -v -0.001978 -0.070703 0.114836 -v 0.000000 -0.074881 0.110696 -v 0.000000 -0.067242 0.121357 -v 0.000000 -0.072191 0.082325 -v 0.000000 -0.073000 0.083736 -v 0.000000 -0.076826 0.089163 -v -0.001551 -0.080000 -0.011424 -v -0.000001 -0.081608 -0.011383 -v 0.000000 -0.086560 -0.005000 -v 0.000000 -0.086164 -0.002756 -v -0.001619 -0.069599 0.020912 -v 0.000000 -0.079859 0.003016 -v -0.001793 -0.080218 0.002534 -v 0.000000 -0.076826 0.005837 -v 0.000000 -0.074251 0.009082 -v 0.000000 -0.069792 0.020580 -v -0.001812 -0.070292 0.017294 -v -0.003000 0.073827 0.088265 -v -0.003000 0.076353 0.091148 -v -0.003000 0.083065 -0.001347 -v -0.003000 0.082909 -0.007977 -v -0.003000 0.080000 -0.009843 -v -0.003000 0.072153 -0.009843 -v -0.003000 0.076353 0.003852 -v -0.003000 0.072153 0.009164 -v -0.003000 -0.083882 0.101612 -v -0.003000 -0.079238 0.093679 -v -0.003000 -0.072153 0.109630 -v -0.001887 -0.075084 0.007639 -v -0.001806 -0.072997 0.010782 -v -0.003000 -0.072153 0.009164 -v -0.002491 -0.071162 0.013753 -v -0.001750 -0.071480 0.013853 -v -0.002394 -0.072789 0.010547 -v -0.002878 -0.072386 0.010080 -v -0.001779 -0.077487 0.004925 -v -0.002769 -0.074559 0.007218 -v -0.003000 -0.076353 0.003852 -v -0.003000 -0.073827 0.006735 -v -0.002401 -0.077243 0.004729 -v -0.002894 -0.076882 0.004229 -v -0.003000 -0.079235 0.001324 -v -0.002930 -0.083599 -0.000974 -v -0.002705 -0.079898 0.002067 -v -0.002818 -0.080759 -0.010610 -v -0.002491 -0.080000 -0.011008 -v -0.002109 -0.086355 -0.004344 -v -0.002301 -0.084654 -0.000702 -v -0.001688 -0.084015 0.000007 -v -0.001898 -0.082190 -0.011004 -v -0.002005 -0.083740 -0.010197 -v -0.002164 -0.084813 -0.009158 -v -0.002104 -0.085832 -0.007617 -v -0.002163 -0.086248 -0.006196 -v -0.002109 -0.085749 -0.002213 -v -0.002978 -0.080000 -0.010103 -v -0.003000 -0.081656 -0.009551 -v -0.002885 -0.082925 -0.009799 -v -0.002947 -0.085106 -0.006696 -v -0.002886 -0.085347 -0.003498 -v -0.003000 -0.080000 -0.009843 -v -0.003000 -0.084130 -0.002616 -v -0.003000 -0.082421 -0.000806 -v -0.001551 -0.072533 -0.011424 -v -0.002026 -0.080934 -0.011319 -v -0.002431 -0.072302 -0.011053 -v -0.002922 -0.072085 -0.010314 -v -0.001815 -0.068738 0.117874 -v -0.002710 -0.069061 0.116326 -v -0.002606 -0.070258 0.114647 -v -0.001806 -0.073103 0.112126 -v -0.001884 -0.076015 0.109561 -v -0.002396 -0.072972 0.111835 -v -0.002769 -0.075606 0.109027 -v -0.002973 -0.072351 0.111379 -v -0.003000 -0.078293 0.106201 -v -0.003000 -0.075027 0.108369 -v -0.003000 -0.081819 0.104488 -v -0.002874 -0.078630 0.106739 -v -0.002881 -0.083093 0.104610 -v -0.002500 -0.078889 0.107214 -v -0.001790 -0.079111 0.107529 -v -0.002966 -0.083651 0.096213 -v -0.002548 -0.083646 0.095224 -v -0.002109 -0.085262 0.096378 -v -0.002163 -0.086357 0.099807 -v -0.002109 -0.086181 0.101615 -v -0.002105 -0.086178 0.098363 -v -0.002109 -0.085275 0.103603 -v -0.002007 -0.083601 0.105313 -v -0.002917 -0.084985 0.097711 -v -0.002933 -0.085191 0.101838 -v -0.002909 -0.072092 0.084639 -v -0.001895 -0.069564 0.073994 -v -0.002294 -0.071240 0.081124 -v -0.003000 -0.073836 0.088277 -v -0.003000 -0.076360 0.091155 -v -0.002392 -0.072792 0.084411 -v -0.002851 -0.079608 0.092996 -v -0.002874 -0.074323 0.087870 -v -0.002769 -0.076935 0.090493 -v -0.002409 -0.074830 0.087487 -v -0.001910 -0.080148 0.092435 -v -0.001962 -0.077388 0.090040 -v -0.001551 -0.074187 0.085962 -v -0.001712 -0.075158 0.087434 -v -0.001706 -0.073118 0.084406 -v -0.001646 -0.071462 0.081042 -v -0.001805 -0.070278 0.077586 -v -0.000000 0.069506 -0.014723 -v -0.002392 0.069766 -0.012765 -v -0.002412 0.069382 -0.013684 -v -0.002625 0.072251 -0.010858 -v -0.003380 0.070646 -0.009843 -v -0.003171 0.071125 -0.009843 -v -0.001551 0.072533 -0.011424 -v -0.002038 0.071096 -0.011630 -v -0.003666 0.070208 -0.009843 -v -0.004019 0.069822 -0.009843 -v -0.003249 0.070497 -0.010681 -v -0.004430 0.069500 -0.009843 -v -0.004889 0.069250 -0.009843 -v -0.005898 0.068990 -0.009843 -v -0.004673 0.069224 -0.011458 -v -0.004011 0.069155 -0.013577 -v -0.002371 0.069298 -0.014442 -v -0.003043 0.071632 -0.009843 -v -0.003043 0.071632 0.009164 -v -0.003171 0.071125 0.009164 -v -0.003380 0.070646 0.009164 -v -0.004430 0.069500 0.009164 -v -0.004889 0.069250 0.009164 -v -0.005383 0.069078 0.009164 -v -0.005383 0.069078 -0.009843 -v -0.005099 0.069104 0.012363 -v -0.005776 0.069000 0.011297 -v -0.001991 0.069332 0.023529 -v -0.003313 0.069604 0.015868 -v -0.002364 0.070047 0.017312 -v -0.002863 0.070536 0.013884 -v -0.003692 0.069947 0.011850 -v -0.003794 0.069335 0.016018 -v -0.004441 0.069360 0.012254 -v -0.004721 0.069092 0.016300 -v -0.004019 0.069822 0.009164 -v -0.003666 0.070208 0.009164 -v -0.003188 0.070843 0.010913 -v 0.000000 -0.072834 -0.011560 -v -0.002386 -0.069443 -0.013436 -v 0.000000 -0.069929 -0.013140 -v -0.001955 -0.072427 -0.011328 -v -0.001999 -0.071573 -0.011494 -v -0.002714 -0.072228 -0.010751 -v -0.003000 -0.072153 -0.009843 -v -0.003043 -0.071632 -0.009843 -v -0.003171 -0.071125 -0.009843 -v -0.003243 -0.070508 -0.010843 -v -0.003380 -0.070646 -0.009843 -v -0.002059 -0.070406 -0.012103 -v -0.003665 -0.070208 -0.009843 -v -0.004019 -0.069822 -0.009843 -v -0.004307 -0.069307 -0.011796 -v -0.001552 -0.069370 -0.014587 -v -0.005898 -0.068990 0.009164 -v -0.005383 -0.069078 -0.009843 -v -0.004889 -0.069250 0.009164 -v -0.004430 -0.069500 0.009164 -v -0.004889 -0.069250 -0.009843 -v -0.004430 -0.069500 -0.009843 -v -0.003665 -0.070208 0.009164 -v -0.003171 -0.071125 0.009164 -v -0.003043 -0.071632 0.009164 -v -0.001991 -0.069332 0.023529 -v -0.002073 -0.069476 0.021085 -v -0.002452 -0.069883 0.017597 -v -0.004721 -0.069092 0.016300 -v -0.005409 -0.069033 0.013592 -v -0.003328 -0.069610 0.015763 -v -0.003709 -0.069225 0.017747 -v -0.005776 -0.069000 0.011297 -v -0.003943 -0.069735 0.011802 -v -0.003181 -0.070671 0.011657 -v -0.003380 -0.070646 0.009164 -v -0.004019 -0.069822 0.009164 -v -0.005383 -0.069078 0.009164 -v -0.004898 -0.069179 0.012336 -v -0.001991 -0.069332 0.071471 -v -0.004721 -0.069092 0.078700 -v -0.003794 -0.069335 0.078982 -v -0.002619 -0.069798 0.077585 -v -0.002863 -0.070536 0.081123 -v -0.003692 -0.069947 0.083152 -v -0.004441 -0.069360 0.082746 -v -0.005099 -0.069104 0.082637 -v -0.003043 -0.071632 0.085836 -v -0.005383 -0.069078 0.085836 -v -0.005776 -0.069000 0.083703 -v -0.004430 -0.069500 0.085836 -v -0.004019 -0.069822 0.085836 -v -0.003665 -0.070208 0.085836 -v -0.003380 -0.070646 0.085836 -v -0.003188 -0.070843 0.084087 -v -0.005383 -0.069078 0.109630 -v -0.004889 -0.069250 0.109630 -v -0.004889 -0.069250 0.085836 -v -0.004019 -0.069822 0.109630 -v -0.003665 -0.070208 0.109630 -v -0.003380 -0.070646 0.109630 -v -0.003171 -0.071125 0.109630 -v -0.003171 -0.071125 0.085836 -v -0.003000 -0.072153 0.085836 -v -0.003043 -0.071632 0.109630 -v -0.004430 -0.069500 0.109630 -v -0.005898 -0.068990 0.109630 -v -0.002737 -0.068160 0.118166 -v -0.003024 -0.067805 0.118993 -v -0.004281 -0.068870 0.114555 -v -0.004557 -0.068423 0.116116 -v -0.005265 -0.068687 0.114329 -v -0.005500 -0.068775 0.113554 -v -0.003295 -0.069871 0.113616 -v -0.003174 -0.070908 0.111545 -v -0.003874 -0.069878 0.111463 -v -0.004809 -0.069197 0.111605 -v -0.005572 -0.068917 0.112134 -v -0.001991 0.069332 0.071471 -v -0.003630 0.069188 0.075482 -v -0.002073 0.069476 0.073915 -v -0.004721 0.069092 0.078700 -v -0.003709 0.069225 0.077253 -v -0.002452 0.069883 0.077403 -v -0.005409 0.069033 0.081408 -v -0.003328 0.069610 0.079236 -v -0.003181 0.070671 0.083343 -v -0.003000 0.072153 0.085836 -v -0.003043 0.071632 0.085836 -v -0.003665 0.070208 0.085836 -v -0.004019 0.069822 0.085836 -v -0.004430 0.069500 0.085836 -v -0.003943 0.069735 0.083198 -v -0.005383 0.069078 0.085836 -v -0.005898 0.068990 0.085836 -v -0.004898 0.069179 0.082664 -v -0.003043 0.071632 0.109630 -v -0.003171 0.071125 0.085836 -v -0.003380 0.070646 0.109630 -v -0.003380 0.070646 0.085836 -v -0.004889 0.069250 0.085836 -v -0.003000 0.072153 0.109630 -v -0.003171 0.071125 0.109630 -v -0.003665 0.070208 0.109630 -v -0.004019 0.069822 0.109630 -v -0.004430 0.069500 0.109630 -v -0.004889 0.069250 0.109630 -v -0.005383 0.069078 0.109630 -v -0.005898 0.068990 0.109630 -v -0.003023 0.071267 0.111445 -v -0.002597 0.068130 0.118343 -v -0.003024 0.067805 0.118993 -v -0.001809 0.067245 0.120916 -v -0.001765 0.068673 0.118017 -v -0.004557 0.068423 0.116116 -v -0.003586 0.068042 0.118022 -v -0.003140 0.069559 0.114698 -v -0.004074 0.068996 0.114317 -v -0.005265 0.068687 0.114329 -v -0.005798 0.068897 0.112130 -v -0.005898 0.068968 0.110787 -v -0.004909 0.069147 0.111623 -v -0.003883 0.069876 0.111523 -v 0.042000 0.020848 -0.087803 -v 0.028165 0.016660 -0.088602 -v 0.027783 0.016649 -0.088604 -v -0.000000 0.016441 -0.088639 -v 0.042000 0.053042 -0.077600 -v 0.042000 0.049830 -0.077489 -v 0.032122 0.046749 -0.078403 -v 0.002000 0.050161 0.146466 -v -0.000000 0.029108 0.150941 -v 0.040000 0.017547 0.152896 -v 0.002159 -0.004962 0.153898 -v 0.042000 0.005863 0.153877 -v 0.039759 0.004737 0.153920 -v 0.002936 0.003515 0.153956 -v 0.005303 0.002109 0.153984 -v 0.036000 0.002060 0.153985 -v 0.036000 -0.002060 0.153985 -v 0.036606 0.002100 0.153984 -v 0.037285 0.002269 0.153982 -v 0.037373 -0.002294 0.153981 -v 0.038504 0.002947 0.153969 -v 0.039064 0.003515 0.153956 -v 0.002241 0.004737 0.153920 -v 0.002061 0.005420 0.153895 -v 0.040000 -0.029108 0.150941 -v 0.042000 -0.005863 0.153877 -v 0.040000 -0.005527 0.153916 -v 0.000000 -0.005863 0.153877 -v 0.000000 -0.017547 0.152896 -v 0.000000 -0.029108 0.150941 -v -0.000000 0.005863 0.153877 -v 0.002000 0.006124 0.153866 -v 0.042000 0.058696 0.143232 -v 0.040000 0.054552 0.145175 -v 0.042000 0.054552 0.145175 -v 0.042000 0.062496 0.140681 -v 0.039464 0.060832 0.141902 -v 0.039759 0.060266 0.142279 -v 0.006000 0.062600 0.140598 -v 0.037093 0.062471 0.140704 -v 0.037851 0.062206 0.140907 -v 0.002241 0.060266 0.142279 -v -0.000000 0.062496 0.140681 -v 0.004707 0.062419 0.140752 -v 0.003496 0.061835 0.141189 -v -0.000000 0.058696 0.143232 -v 0.002000 0.054552 0.145175 -v 0.042000 0.141521 0.041997 -v 0.042000 0.095076 0.056031 -v 0.042000 0.095000 0.056899 -v 0.042000 -0.094699 0.033154 -v 0.042000 -0.138556 0.044899 -v 0.042000 -0.138255 0.046610 -v 0.042000 -0.095125 0.046012 -v 0.042000 -0.095008 0.045180 -v 0.042000 -0.095195 0.043515 -v 0.042000 0.146309 0.041472 -v 0.042000 -0.095922 0.042006 -v 0.042000 -0.095495 0.042730 -v 0.042000 -0.093283 0.032280 -v 0.042000 -0.093383 0.035544 -v 0.042000 -0.091881 0.030231 -v 0.042000 -0.095766 0.047560 -v 0.042000 -0.096272 0.048231 -v 0.042000 -0.095076 0.056031 -v 0.042000 -0.095670 0.054399 -v 0.042000 0.126474 0.067744 -v 0.042000 0.138556 0.044899 -v 0.042000 0.138556 0.044477 -v 0.042000 0.126864 0.066052 -v 0.042000 0.136770 0.048730 -v 0.042000 0.138255 0.046610 -v 0.042000 -0.146556 0.051049 -v 0.042000 -0.136056 0.049230 -v 0.042000 -0.096786 0.053069 -v 0.042000 -0.126834 0.065181 -v 0.042000 -0.126864 0.066052 -v 0.042000 -0.126743 0.066915 -v 0.042000 -0.097160 0.033487 -v 0.042000 -0.097473 0.033441 -v 0.042000 -0.126326 0.063520 -v 0.042000 -0.126653 0.064329 -v 0.042000 0.100287 0.092603 -v 0.042000 0.095670 0.054399 -v 0.042000 -0.095267 0.088026 -v 0.042000 0.102873 0.092513 -v 0.042000 -0.126065 0.068514 -v 0.042000 -0.104420 0.091724 -v 0.042000 -0.103681 0.092186 -v 0.042000 -0.094454 0.106923 -v 0.042000 -0.101150 0.092724 -v 0.042000 -0.084172 0.117948 -v 0.042000 -0.099458 0.092334 -v 0.042000 -0.095000 0.086415 -v 0.042000 -0.114513 0.052398 -v 0.042000 0.092214 0.096133 -v 0.042000 0.115162 0.052774 -v 0.042000 0.113816 0.052123 -v 0.042000 -0.096883 0.048809 -v 0.042000 0.104420 0.091724 -v 0.042000 0.105068 0.091141 -v 0.042000 0.091881 0.030231 -v 0.042000 0.092231 0.030990 -v 0.042000 0.093954 0.032777 -v 0.042000 0.095922 0.042006 -v 0.042000 0.095495 0.042730 -v 0.042000 0.095195 0.043515 -v 0.042000 0.095000 0.049381 -v 0.042000 0.098290 0.052201 -v 0.042000 0.097581 0.049276 -v 0.042000 -0.100000 0.049899 -v 0.042000 -0.115747 0.053243 -v 0.042000 -0.095593 0.088778 -v 0.042000 0.134425 0.049824 -v 0.042000 0.125865 0.062781 -v 0.042000 0.133556 0.049899 -v 0.042000 0.099132 0.051975 -v 0.042000 0.098349 0.049619 -v 0.042000 0.100000 0.051899 -v 0.042000 0.100000 0.049899 -v 0.042000 0.063767 0.130717 -v 0.042000 0.084115 0.112526 -v 0.042000 0.098688 0.091924 -v 0.042000 0.098001 0.091388 -v 0.042000 0.095067 0.087231 -v 0.042000 0.095267 0.088026 -v 0.042000 0.095593 0.088778 -v 0.042000 0.097160 0.033487 -v 0.042000 -0.088792 0.104640 -v 0.042000 -0.098001 0.091388 -v 0.042000 0.099964 0.037864 -v 0.042001 0.100372 0.036645 -v 0.042000 -0.078290 0.119607 -v 0.042000 -0.062496 0.140681 -v 0.042000 0.051796 0.136500 -v 0.042000 0.026425 0.144349 -v 0.042000 0.029108 0.150941 -v 0.042000 0.013279 0.146335 -v 0.042000 0.017547 0.152896 -v 0.042000 -0.017547 0.152896 -v 0.042000 -0.026425 0.144349 -v 0.042000 -0.050161 0.146466 -v 0.042000 -0.054552 0.145175 -v 0.042000 -0.058696 0.143232 -v 0.004695 0.090721 -0.015556 -v 0.011071 0.090376 -0.015556 -v 0.004000 0.082218 -0.015556 -v 0.019000 0.089536 -0.015556 -v 0.017878 0.090437 -0.015556 -v 0.038000 0.082218 -0.015556 -v 0.032000 0.089536 -0.015556 -v 0.024071 0.090376 -0.015556 -v 0.030878 0.090437 -0.015556 -v 0.017104 0.092026 -0.015557 -v 0.024900 0.092024 -0.015558 -v 0.040185 0.095315 0.000016 -v 0.040082 0.095420 0.000434 -v 0.032291 0.094827 -0.001099 -v 0.031514 0.092703 -0.003064 -v 0.031638 0.092178 -0.003275 -v 0.022242 0.095163 -0.000438 -v 0.009915 0.094607 -0.001442 -v 0.010349 0.093855 -0.002285 -v 0.019048 0.091431 -0.003473 -v 0.010266 0.091945 -0.003350 -v 0.010456 0.092520 -0.003143 -v 0.009566 0.091046 -0.003530 -v 0.009201 0.090802 -0.003549 -v 0.040021 0.095488 0.000851 -v 0.007000 0.095521 0.001281 -v 0.035915 0.094607 -0.001442 -v 0.036149 0.094272 -0.001865 -v 0.041287 0.094263 -0.001876 -v 0.041844 0.092976 -0.002913 -v 0.042000 0.092613 -0.003099 -v 0.042000 0.090523 -0.003556 -v 0.042000 0.091374 -0.003483 -v 0.042000 0.092200 -0.003267 -v 0.035566 0.091045 -0.003530 -v 0.024731 0.150556 0.043472 -v 0.041999 0.102970 0.029935 -v 0.042000 0.104648 0.031859 -v 0.042000 0.093003 -0.006521 -v 0.042000 0.077983 -0.012212 -v 0.042000 0.083510 -0.002387 -v 0.042000 0.082894 -0.001770 -v 0.042000 0.092563 -0.011556 -v 0.042000 0.081724 0.001444 -v 0.037000 0.098416 -0.008238 -v 0.037000 0.097783 -0.004601 -v 0.005000 0.097783 -0.004601 -v 0.005000 0.097678 -0.002007 -v 0.037000 0.097678 -0.002007 -v 0.037000 0.097533 0.001580 -v 0.005000 0.097533 0.001580 -v 0.037000 0.097869 0.004255 -v 0.005000 0.097869 0.004255 -v 0.037000 0.099102 0.010397 -v 0.037000 0.100072 0.013647 -v 0.005000 0.100072 0.013647 -v 0.005000 0.101344 0.016247 -v 0.037000 0.102791 0.019204 -v 0.005000 0.108574 0.026426 -v 0.037000 0.115795 0.032209 -v 0.037000 0.121353 0.034928 -v 0.005000 0.118753 0.033656 -v 0.005000 0.121353 0.034928 -v 0.037000 0.127281 0.036697 -v 0.005000 0.127281 0.036697 -v 0.037000 0.130745 0.037131 -v 0.005000 0.130745 0.037131 -v 0.037000 0.137007 0.037322 -v 0.037000 0.139601 0.037217 -v 0.037000 0.143238 0.036584 -v 0.004183 0.150738 0.043820 -v 0.004004 0.150560 0.042459 -v 0.033145 0.132940 0.065651 -v 0.033566 0.136221 0.062132 -v 0.034434 0.132863 0.065733 -v 0.031651 0.135125 0.063308 -v 0.032085 0.135638 0.062758 -v 0.032393 0.133236 0.065333 -v 0.032085 0.133446 0.065108 -v 0.031835 0.133690 0.064847 -v 0.031651 0.133959 0.064558 -v 0.034855 0.136144 0.062215 -v 0.042000 0.146556 0.051049 -v 0.036165 0.135395 0.063019 -v 0.036165 0.133690 0.064847 -v 0.035607 0.133236 0.065333 -v 0.035250 0.133066 0.065516 -v 0.036462 0.134838 0.063615 -v 0.036500 0.134542 0.063933 -v 0.036349 0.133959 0.064558 -v 0.022575 0.074134 0.128712 -v 0.020566 0.070067 0.133074 -v 0.021000 0.070093 0.133046 -v 0.022575 0.065864 0.137581 -v 0.022049 0.066837 0.136538 -v 0.020145 0.066786 0.136592 -v 0.019393 0.069694 0.133474 -v 0.020145 0.069990 0.133156 -v 0.019085 0.067292 0.136049 -v 0.018538 0.068092 0.135192 -v 0.018651 0.068971 0.134249 -v 0.023165 0.067536 0.135788 -v 0.022915 0.067292 0.136049 -v 0.023349 0.068971 0.134249 -v 0.021434 0.132863 0.065733 -v 0.019750 0.133066 0.065516 -v 0.021000 0.136247 0.062104 -v 0.021434 0.136221 0.062132 -v 0.021855 0.136144 0.062215 -v 0.019085 0.133446 0.065108 -v 0.018835 0.135395 0.063019 -v 0.019085 0.135638 0.062758 -v 0.019393 0.135848 0.062532 -v 0.022575 0.148944 0.048488 -v 0.027500 0.148944 0.048488 -v 0.022915 0.135638 0.062758 -v 0.023349 0.135125 0.063308 -v 0.023500 0.134542 0.063933 -v 0.027500 0.117492 0.082217 -v 0.023165 0.133690 0.064847 -v 0.021434 0.102121 0.098700 -v 0.022606 0.099135 0.101902 -v 0.022044 0.098890 0.102166 -v 0.022575 0.117492 0.082217 -v 0.020145 0.098840 0.102219 -v 0.018425 0.094454 0.106923 -v 0.020145 0.102044 0.098782 -v 0.018651 0.101025 0.099875 -v 0.019085 0.101538 0.099325 -v 0.018538 0.100146 0.100818 -v 0.022915 0.101538 0.099325 -v 0.023165 0.101295 0.099586 -v 0.023462 0.100146 0.100818 -v 0.023349 0.099859 0.101126 -v 0.023462 0.100738 0.100183 -v 0.023500 0.100442 0.100501 -v 0.000000 0.112945 0.087093 -v 0.000000 0.110789 0.089405 -v 0.000000 0.091171 0.110443 -v 0.000000 0.094454 0.106923 -v 0.008434 0.132863 0.065733 -v 0.008000 0.132837 0.065761 -v 0.007566 0.132863 0.065733 -v 0.007145 0.132940 0.065651 -v 0.007566 0.136221 0.062132 -v 0.008000 0.136247 0.062104 -v 0.002750 0.148944 0.048488 -v 0.014425 0.148944 0.048488 -v 0.009915 0.135638 0.062758 -v 0.010349 0.135125 0.063308 -v 0.009607 0.133236 0.065333 -v 0.005835 0.135395 0.063019 -v 0.006085 0.135638 0.062758 -v 0.007145 0.136144 0.062215 -v 0.006085 0.133446 0.065108 -v 0.002750 0.117492 0.082217 -v 0.010462 0.134246 0.064250 -v 0.005500 0.134542 0.063933 -v 0.002750 0.094454 0.106923 -v 0.007145 0.098840 0.102219 -v 0.009915 0.099346 0.101676 -v 0.009250 0.098966 0.102084 -v 0.006393 0.099136 0.101901 -v 0.006393 0.101748 0.099100 -v 0.006750 0.101919 0.098917 -v 0.009250 0.101919 0.098917 -v 0.009607 0.101748 0.099100 -v 0.010462 0.100146 0.100818 -v 0.008000 0.102147 0.098672 -v 0.008855 0.102044 0.098782 -v 0.010165 0.101295 0.099586 -v 0.005538 0.100146 0.100818 -v 0.005538 0.100738 0.100183 -v 0.005835 0.101295 0.099586 -v 0.008434 0.070067 0.133074 -v 0.006750 0.069865 0.133291 -v 0.014425 0.074134 0.128712 -v 0.002750 0.084172 0.117948 -v 0.014425 0.094454 0.106923 -v 0.008434 0.098763 0.102301 -v 0.007145 0.066786 0.136592 -v 0.008855 0.069990 0.133156 -v 0.009250 0.069865 0.133291 -v 0.014425 0.066274 0.137142 -v 0.009250 0.066912 0.136458 -v 0.010462 0.068092 0.135192 -v 0.006085 0.067292 0.136049 -v 0.005835 0.067536 0.135788 -v 0.005651 0.067805 0.135499 -v 0.010349 0.067805 0.135499 -v 0.010165 0.067536 0.135788 -v 0.005538 0.068092 0.135192 -v 0.005500 0.068388 0.134874 -v 0.002750 0.074134 0.128712 -v 0.005538 0.068684 0.134557 -v 0.018425 0.117492 0.082217 -v 0.014425 0.117492 0.082217 -v 0.010349 0.068971 0.134249 -v 0.022915 0.099346 0.101676 -v 0.036500 0.100442 0.100501 -v 0.034434 0.098763 0.102301 -v 0.033566 0.098763 0.102301 -v 0.036462 0.100738 0.100183 -v 0.042000 0.094454 0.106923 -v 0.036349 0.101025 0.099875 -v 0.035607 0.101748 0.099100 -v 0.042000 0.117492 0.082217 -v 0.027500 0.094454 0.106923 -v 0.033566 0.102121 0.098700 -v 0.031651 0.101025 0.099875 -v 0.034000 0.066683 0.136703 -v 0.034434 0.070067 0.133074 -v 0.042000 0.066274 0.137142 -v 0.042000 0.084172 0.117948 -v 0.034855 0.098840 0.102219 -v 0.042000 0.074134 0.128712 -v 0.036165 0.067536 0.135788 -v 0.032393 0.069694 0.133474 -v 0.032750 0.069865 0.133291 -v 0.033145 0.069990 0.133156 -v 0.035915 0.069484 0.133699 -v 0.036165 0.069241 0.133960 -v 0.036462 0.068684 0.134557 -v 0.027500 0.074134 0.128712 -v 0.031835 0.069241 0.133960 -v 0.031500 0.068388 0.134874 -v 0.002750 0.065864 0.137581 -v 0.014425 0.065864 0.137581 -v 0.018425 0.066274 0.137142 -v 0.027500 0.065864 0.137581 -v 0.027500 0.066274 0.137142 -v 0.042000 0.065864 0.137581 -v 0.040000 0.029108 0.150941 -v 0.040000 0.050161 0.146466 -v 0.042000 0.050161 0.146466 -v 0.032000 0.051604 -0.074854 -v -0.000000 0.051604 -0.074854 -v -0.000000 0.053528 -0.072642 -v -0.000000 0.055108 -0.070172 -v 0.032000 0.056310 -0.067498 -v 0.042000 0.056702 -0.066421 -v 0.003931 0.072417 -0.023246 -v 0.034000 0.058366 -0.061851 -v 0.002882 0.071159 -0.026703 -v 0.041840 0.076086 -0.013164 -v 0.001715 0.070380 -0.028841 -v -0.000000 0.064382 -0.045322 -v -0.000000 0.056310 -0.067498 -v 0.007550 0.090534 -0.003556 -v 0.040000 0.103023 0.023189 -v 0.007000 0.100497 0.019229 -v 0.040000 0.100008 0.018154 -v 0.007000 0.099987 0.018172 -v 0.040000 0.099428 0.017173 -v 0.040000 0.097060 0.010990 -v 0.007000 0.097697 0.012775 -v 0.007000 0.096936 0.010553 -v 0.040000 0.095757 0.004499 -v 0.007000 0.103731 0.027671 -v 0.041426 0.103914 0.026909 -v 0.007000 0.103914 0.026909 -v 0.007000 0.103976 0.026127 -v 0.007000 0.103915 0.025345 -v 0.007000 0.103433 0.023858 -v 0.040018 0.103243 0.023519 -v 0.040274 0.103732 0.024583 -v 0.007000 0.103021 0.029064 -v 0.042000 0.103411 0.028432 -v 0.041706 0.103021 0.029064 -v 0.041042 0.102624 0.029538 -v 0.007000 0.102511 0.029660 -v 0.041599 0.097798 0.033364 -v 0.041378 0.097978 0.033321 -v 0.040162 0.099477 0.032596 -v 0.040342 0.099141 0.032814 -v 0.007000 0.097978 0.033321 -v 0.007000 0.098758 0.033022 -v 0.007000 0.092231 0.030990 -v 0.042000 0.092703 0.031679 -v 0.007000 0.092703 0.031679 -v 0.042000 0.093283 0.032280 -v 0.007000 0.093283 0.032280 -v 0.042000 0.094700 0.033154 -v 0.042000 0.095497 0.033403 -v 0.042000 0.096325 0.033515 -v 0.007000 0.096325 0.033515 -v 0.007000 0.097160 0.033487 -v 0.042000 0.091382 0.028860 -v 0.007000 0.091881 0.030231 -v 0.042000 0.085856 -0.003480 -v 0.042000 0.085014 -0.003255 -v 0.042000 0.084224 -0.002886 -v 0.007000 0.084224 -0.002886 -v 0.007000 0.082894 -0.001770 -v 0.042000 0.082394 -0.001056 -v 0.042000 0.082025 -0.000266 -v 0.042000 0.081800 0.000575 -v 0.007000 0.082025 -0.000266 -v 0.042000 0.081800 0.002312 -v 0.007000 0.081724 0.001444 -v 0.042000 0.082025 0.003154 -v 0.007000 0.082025 0.003154 -v 0.008341 0.090523 -0.003556 -v 0.007000 0.086724 -0.003556 -v 0.008000 0.090500 -0.003556 -v 0.042000 0.086724 -0.003556 -v 0.021000 0.090500 -0.003556 -v 0.002000 0.091009 0.006714 -v 0.002000 0.092117 0.011889 -v 0.002000 0.093832 0.016895 -v 0.042000 0.095000 0.086415 -v 0.002000 0.095000 0.086415 -v 0.002000 0.095067 0.087231 -v 0.002000 0.095267 0.088026 -v 0.002000 0.095593 0.088778 -v 0.042000 0.096039 0.089466 -v 0.002000 0.095000 0.056899 -v 0.042000 0.095000 0.078062 -v 0.002000 0.099132 0.051975 -v 0.042000 0.097500 0.052569 -v 0.042000 0.096786 0.053069 -v 0.002000 0.097500 0.052569 -v 0.002000 0.096786 0.053069 -v 0.042000 0.096170 0.053686 -v 0.002000 0.096170 0.053686 -v 0.002000 0.095302 0.055189 -v 0.042000 0.095302 0.055189 -v 0.002000 0.095076 0.056031 -v 0.042000 0.112337 0.051899 -v 0.042000 0.114513 0.052398 -v 0.002000 0.113816 0.052123 -v 0.042000 0.113085 0.051956 -v 0.042000 0.115747 0.053243 -v 0.042000 0.125281 0.062134 -v 0.002000 0.125528 0.069200 -v 0.042000 0.126065 0.068514 -v 0.002000 0.126065 0.068514 -v 0.042000 0.126743 0.066915 -v 0.002000 0.126864 0.066052 -v 0.042000 0.126834 0.065181 -v 0.002000 0.126834 0.065181 -v 0.042000 0.126653 0.064329 -v 0.002000 0.126326 0.063520 -v 0.042000 0.126326 0.063520 -v 0.002000 0.125865 0.062781 -v 0.002000 0.125281 0.062134 -v 0.042000 0.125528 0.069200 -v 0.042000 0.099458 0.092334 -v 0.002000 0.100287 0.092603 -v 0.002000 0.101150 0.092724 -v 0.042000 0.101150 0.092724 -v 0.042000 0.102021 0.092694 -v 0.002000 0.102873 0.092513 -v 0.042000 0.103681 0.092186 -v 0.002000 0.103681 0.092186 -v 0.002000 0.105068 0.091141 -v 0.002000 0.096590 0.090072 -v 0.042000 0.096590 0.090072 -v 0.002000 0.115747 0.053243 -v 0.002000 0.113085 0.051956 -v 0.002000 0.096039 0.089466 -v 0.002000 0.112337 0.051899 -v 0.002000 0.114513 0.052398 -v 0.002000 0.115162 0.052774 -v 0.002000 0.095670 0.054399 -v 0.002000 0.102021 0.092694 -v 0.002000 0.100000 0.051899 -v 0.002000 0.098290 0.052201 -v 0.002000 0.126653 0.064329 -v 0.002000 0.126743 0.066915 -v 0.002000 0.126474 0.067744 -v 0.002000 0.104420 0.091724 -v 0.002000 0.099458 0.092334 -v 0.002000 0.098688 0.091924 -v 0.002000 0.098001 0.091388 -v 0.042000 0.135266 0.049598 -v 0.042000 0.136056 0.049230 -v 0.007000 0.136770 0.048730 -v 0.042000 0.137387 0.048113 -v 0.007000 0.137387 0.048113 -v 0.042000 0.137886 0.047399 -v 0.007000 0.137886 0.047399 -v 0.007000 0.138255 0.046610 -v 0.042000 0.138480 0.045768 -v 0.042000 0.096464 0.041364 -v 0.007000 0.095495 0.042730 -v 0.042000 0.095031 0.044340 -v 0.042000 0.095008 0.045180 -v 0.007000 0.095031 0.044340 -v 0.007000 0.095008 0.045180 -v 0.042000 0.095125 0.046012 -v 0.042000 0.095381 0.046813 -v 0.007000 0.095381 0.046813 -v 0.042000 0.095766 0.047560 -v 0.007000 0.096272 0.048231 -v 0.042000 0.096272 0.048231 -v 0.042000 0.096883 0.048809 -v 0.007000 0.096883 0.048809 -v 0.007000 0.097581 0.049276 -v 0.007000 0.098349 0.049619 -v 0.042000 0.099162 0.049829 -v 0.040880 0.105340 0.032489 -v 0.040000 0.103772 0.034057 -v 0.007000 0.105340 0.032489 -v 0.040000 0.111811 0.031977 -v 0.040018 0.111481 0.031757 -v 0.007000 0.110417 0.031268 -v 0.007000 0.109655 0.031085 -v 0.007000 0.108873 0.031024 -v 0.041293 0.108527 0.031036 -v 0.007000 0.108091 0.031086 -v 0.007000 0.107329 0.031269 -v 0.041426 0.108091 0.031086 -v 0.042000 0.106131 0.031844 -v 0.040000 0.130501 0.039243 -v 0.007000 0.129041 0.039048 -v 0.040000 0.127908 0.038723 -v 0.007000 0.127893 0.038802 -v 0.040000 0.124010 0.037940 -v 0.007000 0.124447 0.038064 -v 0.007000 0.122225 0.037303 -v 0.040000 0.122243 0.037263 -v 0.040000 0.117827 0.035572 -v 0.007000 0.116828 0.035013 -v 0.035782 0.136215 0.040230 -v 0.041540 0.137433 0.041318 -v 0.042000 0.138099 0.042387 -v 0.041844 0.137913 0.042024 -v 0.035954 0.138474 0.043567 -v 0.042000 0.138483 0.043626 -v 0.042000 0.138267 0.042800 -v 0.036329 0.138311 0.042936 -v 0.035511 0.138533 0.044001 -v 0.040000 0.133719 0.039479 -v 0.022245 0.135446 0.039840 -v 0.019752 0.135447 0.039842 -v 0.019085 0.136442 0.040393 -v 0.018651 0.137285 0.041145 -v 0.010160 0.136878 0.040742 -v 0.009952 0.138473 0.043569 -v 0.018544 0.138143 0.042480 -v 0.009607 0.138525 0.043915 -v 0.032390 0.135950 0.040087 -v 0.032085 0.136442 0.040393 -v 0.022915 0.136442 0.040393 -v 0.023486 0.138064 0.042297 -v 0.031860 0.138417 0.043300 -v 0.022607 0.138525 0.043915 -v 0.032092 0.138482 0.043617 -v 0.033609 0.138556 0.044473 -v 0.007725 0.138555 0.044492 -v 0.034000 0.138556 0.044500 -v 0.002000 0.118105 0.041168 -v 0.002000 0.128286 0.043991 -v 0.038000 0.092563 -0.015556 -v 0.038000 0.094483 -0.015241 -v 0.037572 0.094319 -0.015313 -v 0.038000 0.095380 -0.014854 -v 0.033685 0.095947 -0.014509 -v 0.021865 0.095908 -0.014540 -v 0.038000 0.096202 -0.014327 -v 0.019811 0.095825 -0.014594 -v 0.018917 0.095483 -0.014798 -v 0.004000 0.096202 -0.014327 -v 0.038000 0.096928 -0.013673 -v 0.004000 0.097538 -0.012910 -v 0.038000 0.097538 -0.012910 -v 0.038000 0.098350 -0.011141 -v 0.004000 0.098515 -0.010312 -v 0.037356 0.098562 -0.009467 -v 0.004941 0.098506 -0.008735 -v 0.037222 0.098552 -0.009205 -v 0.037118 0.098531 -0.008941 -v 0.004255 0.093973 -0.015394 -v 0.004000 0.095380 -0.014854 -v 0.018179 0.095028 -0.015028 -v 0.017158 0.093811 -0.015445 -v 0.011740 0.094093 -0.015389 -v 0.030695 0.094629 -0.015204 -v 0.037818 0.150737 0.043819 -v 0.003732 0.150288 0.046171 -v 0.032676 0.150427 0.045637 -v 0.022704 0.150452 0.045524 -v 0.034980 0.150406 0.045737 -v 0.038598 0.149958 0.047008 -v 0.018425 0.148944 0.048488 -v 0.002951 0.149507 0.047786 -v 0.039612 0.148944 0.048488 -v 0.031540 0.150517 0.045144 -v 0.004000 0.149854 0.039620 -v 0.023821 0.150028 0.039972 -v 0.038000 0.149327 0.038798 -v 0.038000 0.149854 0.039620 -v 0.017814 0.150160 0.040277 -v 0.004000 0.150241 0.040517 -v 0.004000 0.148673 0.038072 -v 0.004000 0.147910 0.037462 -v 0.038000 0.147059 0.036984 -v 0.004000 0.147059 0.036984 -v 0.004000 0.146141 0.036650 -v 0.037880 0.145181 0.036470 -v 0.004643 0.144467 0.036438 -v 0.004778 0.144205 0.036448 -v 0.037015 0.143487 0.036533 -v 0.037309 0.150203 0.040380 -v 0.037945 0.150532 0.041459 -v 0.038000 0.150241 0.040517 -v 0.038000 0.079193 -0.016025 -v 0.038000 0.077770 -0.016600 -v 0.038000 0.077232 -0.016921 -v 0.038000 0.076452 -0.017386 -v 0.004000 0.075803 -0.017910 -v 0.004000 0.074791 -0.018860 -v 0.038000 0.074251 -0.019512 -v 0.038000 0.073572 -0.020566 -v 0.038000 0.072821 -0.022136 -v 0.004000 0.072821 -0.022136 -v 0.002000 0.096579 0.028521 -v 0.003392 0.098567 0.031457 -v 0.005997 0.103016 0.029010 -v 0.002670 0.094230 0.029376 -v 0.003170 0.093559 0.029620 -v 0.003339 0.094466 0.031325 -v 0.004500 0.092510 0.030002 -v 0.003786 0.092980 0.029831 -v 0.004151 0.093174 0.030885 -v 0.002560 0.095797 0.030972 -v 0.005787 0.092725 0.031558 -v 0.005282 0.094132 0.032628 -v 0.007000 0.100115 0.032057 -v 0.005632 0.099445 0.032476 -v 0.004611 0.099111 0.032198 -v 0.002423 0.097716 0.030288 -v 0.002073 0.096707 0.029585 -v 0.007000 0.093954 0.032777 -v 0.007000 0.094700 0.033154 -v 0.007000 0.095497 0.033403 -v 0.005218 0.095692 0.033196 -v 0.005713 0.097559 0.033289 -v 0.004013 0.096919 0.032600 -v 0.007000 0.099477 0.032596 -v 0.002301 0.100518 0.026997 -v 0.002930 0.101301 0.027948 -v 0.003871 0.102344 0.028255 -v 0.003134 0.102118 0.026829 -v 0.003167 0.101993 0.024895 -v 0.002075 0.100073 0.026244 -v 0.003819 0.102632 0.024702 -v 0.002647 0.101525 0.025555 -v 0.002302 0.100360 0.025121 -v 0.004552 0.103401 0.026625 -v 0.004500 0.102786 0.024062 -v 0.006133 0.103318 0.023792 -v 0.005716 0.103706 0.024983 -v 0.004948 0.102207 0.029369 -v 0.007000 0.103023 0.023189 -v 0.007000 0.103732 0.024583 -v 0.005832 0.103850 0.026783 -v 0.007000 0.103430 0.028396 -v 0.002076 0.095763 0.028818 -v 0.002302 0.085117 0.002029 -v 0.002302 0.094972 0.029106 -v 0.003786 0.083125 0.002754 -v 0.005290 0.092164 0.030128 -v 0.006132 0.091952 0.030205 -v 0.006132 0.095877 0.005971 -v 0.007000 0.095952 0.005959 -v 0.006132 0.100430 0.019266 -v 0.007000 0.098458 0.014997 -v 0.004500 0.095290 0.006060 -v 0.003783 0.094275 0.000531 -v 0.003170 0.094186 0.006229 -v 0.002670 0.093481 0.006336 -v 0.003169 0.093673 0.000680 -v 0.002668 0.092967 0.001032 -v 0.002302 0.092700 0.006456 -v 0.002302 0.092233 0.001388 -v 0.002076 0.091868 0.006583 -v 0.002077 0.091325 0.000573 -v 0.007000 0.096198 0.007107 -v 0.006132 0.096863 0.010573 -v 0.005290 0.095654 0.006005 -v 0.005290 0.096645 0.010633 -v 0.004500 0.096290 0.010732 -v 0.003786 0.095808 0.010865 -v 0.003786 0.094796 0.006136 -v 0.002670 0.094527 0.011221 -v 0.002076 0.092954 0.011657 -v 0.006132 0.098387 0.015026 -v 0.004500 0.097838 0.015251 -v 0.003786 0.097376 0.015441 -v 0.003170 0.096805 0.015675 -v 0.003170 0.095215 0.011030 -v 0.002302 0.093765 0.011432 -v 0.005290 0.100233 0.019376 -v 0.005290 0.098179 0.015112 -v 0.004500 0.099911 0.019555 -v 0.003786 0.099475 0.019799 -v 0.002670 0.098313 0.020446 -v 0.002302 0.097623 0.020831 -v 0.002670 0.096145 0.015946 -v 0.002302 0.095414 0.016246 -v 0.002076 0.096887 0.021241 -v 0.002076 0.094635 0.016566 -v 0.002000 0.096129 0.021663 -v 0.005290 0.103117 0.023897 -v 0.003170 0.098936 0.020099 -v 0.002000 0.098976 0.026125 -v 0.002072 0.086061 0.000594 -v 0.003231 0.085883 -0.001832 -v 0.004152 0.082953 -0.000281 -v 0.004898 0.084772 -0.002692 -v 0.005411 0.083520 -0.002172 -v 0.006166 0.085887 -0.003477 -v 0.005299 0.086263 -0.003256 -v 0.005702 0.082119 -0.000218 -v 0.006132 0.082097 0.003128 -v 0.005710 0.081875 0.001879 -v 0.005290 0.082309 0.003051 -v 0.004500 0.082655 0.002925 -v 0.004138 0.082560 0.001481 -v 0.003170 0.083704 0.002543 -v 0.002670 0.084375 0.002299 -v 0.002783 0.083924 0.001285 -v 0.002076 0.085908 0.001741 -v 0.007000 0.085856 -0.003480 -v 0.007000 0.085014 -0.003255 -v 0.007000 0.083510 -0.002387 -v 0.007000 0.082394 -0.001056 -v 0.007000 0.081800 0.000575 -v 0.007000 0.081800 0.002312 -v 0.002930 0.084544 -0.000767 -v 0.006085 0.094607 -0.001293 -v 0.002000 0.090523 0.001444 -v 0.005538 0.093434 -0.002350 -v 0.004319 0.093944 -0.001164 -v 0.004812 0.090900 -0.003069 -v 0.003165 0.092657 -0.001099 -v 0.007000 0.095420 0.000434 -v 0.004500 0.094808 0.000936 -v 0.005260 0.095092 0.000104 -v 0.006129 0.095379 0.000585 -v 0.002845 0.091057 -0.001366 -v 0.002000 0.086724 0.001444 -v 0.002298 0.091116 -0.000252 -v 0.002489 0.086338 -0.000751 -v 0.003873 0.091648 -0.002449 -v 0.004188 0.086320 -0.002710 -v 0.003786 0.097292 0.042191 -v 0.005290 0.096678 0.041577 -v 0.006132 0.105393 0.032542 -v 0.006132 0.096518 0.041418 -v 0.007000 0.096464 0.041364 -v 0.003167 0.110074 0.032989 -v 0.003765 0.110095 0.032295 -v 0.005391 0.109671 0.031274 -v 0.004500 0.105813 0.032962 -v 0.003786 0.106167 0.033316 -v 0.004180 0.107462 0.032025 -v 0.003170 0.106603 0.033752 -v 0.002670 0.107107 0.034256 -v 0.002302 0.107666 0.034815 -v 0.002076 0.108751 0.034918 -v 0.005289 0.111100 0.031881 -v 0.002862 0.107997 0.033234 -v 0.005290 0.105553 0.032702 -v 0.005712 0.106324 0.031882 -v 0.005713 0.107727 0.031296 -v 0.007000 0.105936 0.031979 -v 0.007000 0.106604 0.031570 -v 0.007000 0.111142 0.031567 -v 0.006131 0.111206 0.031682 -v 0.002076 0.098794 0.044881 -v 0.002670 0.098232 0.043132 -v 0.002302 0.098791 0.043690 -v 0.002870 0.097393 0.046206 -v 0.002000 0.100000 0.044899 -v 0.003170 0.097727 0.042627 -v 0.004137 0.096236 0.043129 -v 0.004141 0.096166 0.046522 -v 0.003411 0.098731 0.048223 -v 0.004500 0.096938 0.041838 -v 0.005390 0.095184 0.045127 -v 0.005318 0.098798 0.049534 -v 0.002450 0.099041 0.046854 -v 0.005702 0.095584 0.042792 -v 0.006132 0.100000 0.049824 -v 0.004500 0.100000 0.049230 -v 0.002302 0.100000 0.046610 -v 0.007000 0.095922 0.042006 -v 0.007000 0.095195 0.043515 -v 0.007000 0.095125 0.046012 -v 0.007000 0.095766 0.047560 -v 0.005560 0.097190 0.048888 -v 0.005711 0.095681 0.047143 -v 0.003136 0.096753 0.044217 -v 0.007000 0.099162 0.049829 -v 0.004200 0.097362 0.048164 -v 0.007000 0.133719 0.039479 -v 0.006132 0.124427 0.038137 -v 0.007000 0.111811 0.031977 -v 0.007000 0.115771 0.034503 -v 0.007000 0.120003 0.036542 -v 0.004500 0.115445 0.035089 -v 0.003786 0.115201 0.035525 -v 0.004499 0.110932 0.032210 -v 0.003170 0.114901 0.036064 -v 0.002670 0.109950 0.033749 -v 0.002302 0.114169 0.037377 -v 0.002302 0.109432 0.034357 -v 0.002076 0.113759 0.038113 -v 0.002000 0.108875 0.036024 -v 0.006132 0.115734 0.034570 -v 0.005290 0.115624 0.034767 -v 0.004500 0.119749 0.037162 -v 0.003786 0.119559 0.037624 -v 0.002670 0.114554 0.036687 -v 0.002302 0.118754 0.039586 -v 0.002076 0.118434 0.040365 -v 0.002000 0.113337 0.038871 -v 0.006132 0.119974 0.036613 -v 0.005290 0.119888 0.036821 -v 0.005290 0.124367 0.038355 -v 0.003170 0.123970 0.039785 -v 0.003170 0.119325 0.038195 -v 0.002670 0.123779 0.040473 -v 0.002670 0.119054 0.038855 -v 0.002302 0.123568 0.041235 -v 0.002076 0.123343 0.042046 -v 0.006132 0.129029 0.039123 -v 0.005290 0.128995 0.039346 -v 0.004500 0.128940 0.039710 -v 0.003786 0.128864 0.040204 -v 0.004500 0.124268 0.038710 -v 0.003786 0.124135 0.039192 -v 0.003170 0.128771 0.040813 -v 0.002302 0.128544 0.042300 -v 0.002076 0.128417 0.043132 -v 0.002000 0.123111 0.042883 -v 0.002670 0.128664 0.041519 -v 0.002297 0.134495 0.042864 -v 0.002076 0.100000 0.045768 -v 0.002076 0.133556 0.045768 -v 0.002670 0.100000 0.047399 -v 0.003170 0.100000 0.048113 -v 0.003786 0.100000 0.048730 -v 0.003786 0.133556 0.048730 -v 0.004500 0.133556 0.049230 -v 0.005290 0.100000 0.049598 -v 0.005290 0.133556 0.049598 -v 0.007000 0.100000 0.049899 -v 0.006085 0.136292 0.040393 -v 0.006127 0.138411 0.043665 -v 0.006500 0.138515 0.044009 -v 0.003239 0.136913 0.043916 -v 0.004731 0.137913 0.043440 -v 0.002076 0.133584 0.043609 -v 0.003128 0.136236 0.042603 -v 0.005538 0.137880 0.042434 -v 0.004537 0.137168 0.042020 -v 0.004405 0.135817 0.040751 -v 0.005538 0.137350 0.041566 -v 0.005834 0.136682 0.040752 -v 0.002669 0.134273 0.042040 -v 0.005289 0.134667 0.039872 -v 0.006121 0.134679 0.039648 -v 0.006393 0.135868 0.040085 -v 0.003160 0.134703 0.041375 -v 0.003786 0.134202 0.040697 -v 0.007000 0.134566 0.039580 -v 0.004500 0.134300 0.040205 -v 0.002000 0.133556 0.044899 -v 0.002670 0.133556 0.047399 -v 0.002302 0.133556 0.046610 -v 0.002445 0.134670 0.046767 -v 0.003170 0.133556 0.048113 -v 0.003151 0.136389 0.046670 -v 0.003482 0.134833 0.048281 -v 0.004120 0.137666 0.045443 -v 0.004791 0.135006 0.049205 -v 0.005303 0.136817 0.048398 -v 0.006105 0.135266 0.049565 -v 0.007000 0.138480 0.045768 -v 0.005318 0.137894 0.046902 -v 0.007000 0.136056 0.049230 -v 0.007000 0.135266 0.049598 -v 0.006132 0.133556 0.049824 -v 0.007000 0.134425 0.049824 -v 0.007000 0.133556 0.049899 -v 0.002097 0.134774 0.044968 -v 0.005627 0.138381 0.045331 -v 0.007000 0.138556 0.044899 -v 0.038000 0.073420 -0.020803 -v 0.038467 0.073878 -0.019230 -v 0.039125 0.074488 -0.017555 -v 0.038000 0.074576 -0.019146 -v 0.038000 0.075269 -0.018364 -v 0.040177 0.075197 -0.015608 -v 0.038000 0.075808 -0.017918 -v 0.038000 0.078806 -0.016181 -v 0.042000 0.082218 -0.011556 -v 0.038000 0.080687 -0.015674 -v 0.042000 0.080075 -0.011721 -v 0.038000 0.080484 -0.015722 -v 0.038268 0.150288 0.046171 -v 0.042000 0.146556 0.042437 -v 0.038417 0.150139 0.046595 -v 0.039049 0.149507 0.047786 -v 0.037993 0.098514 -0.010315 -v 0.038000 0.098016 -0.012059 -v 0.042000 0.093339 -0.011415 -v 0.038000 0.093536 -0.015477 -v 0.038000 0.146141 0.036650 -v 0.038699 0.144471 0.037081 -v 0.038000 0.147910 0.037462 -v 0.038000 0.148673 0.038072 -v 0.042000 0.146521 0.042052 -v 0.040602 0.094906 -0.001013 -v 0.038707 0.096975 -0.002045 -v 0.041060 0.103976 0.026127 -v 0.040609 0.103915 0.025345 -v 0.040428 0.103840 0.024966 -v 0.040069 0.103433 0.023858 -v 0.040156 0.103598 0.024217 -v 0.038707 0.105847 0.024696 -v 0.040000 0.102796 0.022873 -v 0.038707 0.100709 0.016554 -v 0.040000 0.097737 0.012757 -v 0.038707 0.098425 0.010594 -v 0.038707 0.097611 0.007865 -v 0.040000 0.096277 0.007092 -v 0.038707 0.097169 0.004335 -v 0.038707 0.096827 0.001610 -v 0.040000 0.095521 0.001281 -v 0.040069 0.111142 0.031567 -v 0.040156 0.110783 0.031402 -v 0.041060 0.108873 0.031024 -v 0.041293 0.106245 0.028755 -v 0.040609 0.109655 0.031085 -v 0.038707 0.108076 0.026924 -v 0.038707 0.110304 0.029153 -v 0.040429 0.110033 0.031160 -v 0.040274 0.110417 0.031268 -v 0.038707 0.137045 0.038025 -v 0.040695 0.136133 0.040180 -v 0.040265 0.135249 0.039764 -v 0.040082 0.134566 0.039580 -v 0.038707 0.133390 0.038173 -v 0.040021 0.134148 0.039512 -v 0.038707 0.127135 0.037389 -v 0.038707 0.124406 0.036575 -v 0.038707 0.121095 0.035587 -v 0.038707 0.118446 0.034291 -v 0.038707 0.115433 0.032817 -v 0.040000 0.116846 0.034992 -v 0.040000 0.112127 0.032204 -v 0.038707 0.097082 -0.004688 -v 0.041294 0.136887 0.040750 -v 0.003580 0.071819 -0.024889 -v 0.004000 0.080553 -0.015696 -v 0.004000 0.078932 -0.016112 -v 0.004000 0.078802 -0.016169 -v 0.004000 0.077404 -0.016791 -v -0.000000 0.075478 -0.013285 -v 0.004000 0.077226 -0.016909 -v 0.004000 0.076011 -0.017716 -v 0.004000 0.074576 -0.019143 -v 0.000000 0.070403 -0.018045 -v 0.004000 0.073779 -0.020191 -v 0.004000 0.073581 -0.020569 -v 0.004000 0.073003 -0.021672 -v 0.004000 0.098350 -0.011141 -v 0.000707 0.095204 -0.008962 -v 0.004000 0.098016 -0.012059 -v 0.004000 0.096928 -0.013673 -v -0.000000 0.093527 -0.011309 -v 0.004000 0.094483 -0.015241 -v 0.004000 0.093536 -0.015477 -v 0.003299 0.097081 -0.004645 -v 0.000709 0.094469 -0.004553 -v 0.000709 0.094266 0.002096 -v 0.003299 0.096832 0.001638 -v 0.000705 0.100006 0.020972 -v 0.003293 0.110295 0.029145 -v 0.000707 0.108600 0.031098 -v 0.003297 0.121072 0.035576 -v 0.000709 0.119957 0.037914 -v 0.003299 0.127101 0.037379 -v 0.003301 0.133348 0.038167 -v 0.003303 0.139615 0.037921 -v 0.003301 0.144088 0.037148 -v 0.000702 0.144559 0.039701 -v 0.004000 0.149327 0.038798 -v 0.004052 0.150528 0.041451 -v 0.000000 0.146556 0.051049 -v 0.002388 0.148944 0.048488 -v 0.000000 0.146556 0.042437 -v 0.003402 0.149958 0.047008 -v 0.003583 0.150139 0.046595 -v 0.041492 0.145235 0.040013 -v 0.041902 0.145914 0.040818 -v 0.041299 0.144372 0.039728 -v 0.041293 0.141259 0.040310 -v 0.041293 0.103964 0.026473 -v 0.042000 0.106568 0.031589 -v 0.041985 0.103427 0.028394 -v 0.041691 0.107329 0.031269 -v 0.041691 0.103731 0.027671 -v -0.000000 0.092763 -0.004721 -v 0.000087 0.094151 -0.010932 -v 0.000582 0.095113 -0.010076 -v 0.000165 0.145785 0.040620 -v 0.000000 0.143879 0.041452 -v 0.000709 0.139545 0.040534 -v 0.000709 0.132900 0.040734 -v 0.000707 0.126306 0.039856 -v 0.000707 0.123688 0.039057 -v -0.000000 0.119323 0.039503 -v -0.000000 0.113119 0.036434 -v 0.000708 0.113995 0.034967 -v 0.000707 0.103916 0.026415 -v 0.000000 0.101645 0.026173 -v 0.000707 0.101852 0.023543 -v 0.000000 0.098566 0.021881 -v -0.000000 0.095497 0.015677 -v 0.000707 0.097084 0.015048 -v 0.000709 0.095147 0.008687 -v -0.000000 0.093476 0.009058 -v 0.004120 0.098530 -0.010181 -v 0.004485 0.098560 -0.009718 -v 0.004825 0.098543 -0.009089 -v 0.004643 0.098562 -0.009467 -v 0.004007 0.145315 0.036486 -v 0.005000 0.143238 0.036584 -v 0.004973 0.143599 0.036513 -v 0.004401 0.144837 0.036444 -v 0.004882 0.143941 0.036469 -v 0.005000 0.139601 0.037217 -v 0.005000 0.137007 0.037322 -v 0.005000 0.133420 0.037467 -v 0.005000 0.124602 0.035898 -v 0.003295 0.115417 0.032806 -v 0.005000 0.115795 0.032209 -v 0.005000 0.113359 0.030469 -v 0.005000 0.110761 0.028613 -v 0.003291 0.105840 0.024688 -v 0.005000 0.106387 0.024239 -v 0.005000 0.104531 0.021641 -v 0.003290 0.102178 0.019560 -v 0.005000 0.102791 0.019205 -v 0.003293 0.099413 0.013905 -v 0.005000 0.099102 0.010397 -v 0.003298 0.097620 0.007893 -v 0.005000 0.098303 0.007719 -v 0.003301 0.097919 -0.009471 -v 0.005000 0.098416 -0.008238 -v 0.004985 0.098467 -0.008487 -v 0.041540 0.093682 -0.002433 -v 0.041293 0.094690 -0.006259 -v 0.041293 0.094281 -0.002187 -v 0.041295 0.095278 -0.009364 -v 0.041861 0.094241 -0.010904 -v 0.041496 0.094994 -0.010175 -v 0.038000 0.145312 0.036485 -v 0.037515 0.144718 0.036440 -v 0.037059 0.143735 0.036494 -v 0.037171 0.144095 0.036454 -v 0.037357 0.144467 0.036438 -v 0.037027 0.098487 -0.008599 -v 0.037599 0.098556 -0.009837 -v 0.038707 0.139688 0.037918 -v 0.037000 0.133420 0.037467 -v 0.038707 0.130665 0.037831 -v 0.037000 0.124602 0.035898 -v 0.037000 0.118753 0.033656 -v 0.037000 0.113359 0.030469 -v 0.038707 0.112951 0.031044 -v 0.037000 0.110761 0.028613 -v 0.037000 0.108574 0.026426 -v 0.037000 0.106387 0.024239 -v 0.037000 0.104531 0.021641 -v 0.038707 0.103956 0.022049 -v 0.038707 0.102183 0.019567 -v 0.037000 0.101344 0.016247 -v 0.038707 0.099413 0.013905 -v 0.037000 0.098303 0.007719 -v 0.038710 0.097842 -0.009052 -v 0.020795 0.135556 0.039508 -v 0.021000 0.149056 0.044500 -v 0.021338 0.138556 0.044477 -v 0.021434 0.149056 0.044462 -v 0.021852 0.138556 0.044359 -v 0.022349 0.138543 0.044108 -v 0.022250 0.149056 0.044165 -v 0.022607 0.149056 0.043915 -v 0.023165 0.149056 0.043250 -v 0.022952 0.138473 0.043569 -v 0.022915 0.149056 0.043607 -v 0.023462 0.149056 0.042434 -v 0.023362 0.138275 0.042822 -v 0.023349 0.149056 0.042855 -v 0.023222 0.138379 0.043151 -v 0.023500 0.149056 0.042000 -v 0.023349 0.149056 0.041145 -v 0.023477 0.137672 0.041632 -v 0.022915 0.149056 0.040393 -v 0.023160 0.136878 0.040742 -v 0.023349 0.137286 0.041146 -v 0.022607 0.149056 0.040085 -v 0.019390 0.135950 0.040087 -v 0.019085 0.149056 0.040393 -v 0.018835 0.149056 0.040750 -v 0.018651 0.149056 0.041145 -v 0.018852 0.136862 0.040725 -v 0.018538 0.149056 0.042434 -v 0.018517 0.137699 0.041664 -v 0.018734 0.138350 0.043055 -v 0.018651 0.149056 0.042855 -v 0.019393 0.149056 0.043915 -v 0.019434 0.138530 0.043955 -v 0.019085 0.149056 0.043607 -v 0.019092 0.138482 0.043617 -v 0.018860 0.138417 0.043300 -v 0.020145 0.149056 0.044349 -v 0.019799 0.138549 0.044198 -v 0.021000 0.138556 0.044500 -v 0.020609 0.138556 0.044473 -v 0.020201 0.138556 0.044374 -v 0.022709 0.136099 0.040173 -v 0.022250 0.149056 0.039835 -v 0.021855 0.149056 0.039651 -v 0.022000 0.135556 0.039709 -v 0.021205 0.135556 0.039508 -v 0.021611 0.135556 0.039576 -v 0.021434 0.149056 0.039538 -v 0.020566 0.149056 0.039538 -v 0.019750 0.149056 0.039835 -v 0.020000 0.135556 0.039709 -v 0.020389 0.135556 0.039576 -v 0.018500 0.149056 0.042000 -v 0.017027 0.150517 0.041579 -v 0.018538 0.149056 0.041566 -v 0.022189 0.149594 0.039175 -v 0.021000 0.149056 0.039500 -v 0.020762 0.149507 0.039048 -v 0.020145 0.149056 0.039651 -v 0.019393 0.149056 0.040085 -v 0.019311 0.149690 0.039324 -v 0.023083 0.149798 0.039517 -v 0.023165 0.149056 0.040750 -v 0.024960 0.150499 0.041401 -v 0.023462 0.149056 0.041566 -v 0.019676 0.150427 0.045637 -v 0.020333 0.150395 0.045780 -v 0.020566 0.149056 0.044462 -v 0.021000 0.150383 0.045827 -v 0.021667 0.150395 0.045780 -v 0.021855 0.149056 0.044349 -v 0.019750 0.149056 0.044165 -v 0.018535 0.150517 0.045140 -v 0.023961 0.150554 0.044721 -v 0.018835 0.149056 0.043250 -v 0.017320 0.150556 0.043627 -v 0.007779 0.135556 0.039510 -v 0.007370 0.135556 0.039581 -v 0.005835 0.149056 0.040750 -v 0.005651 0.137032 0.041145 -v 0.005500 0.137633 0.042000 -v 0.005723 0.138183 0.043060 -v 0.006085 0.149056 0.043607 -v 0.007175 0.138568 0.044361 -v 0.007145 0.149056 0.044349 -v 0.006750 0.149056 0.044165 -v 0.007566 0.149056 0.044462 -v 0.008000 0.149056 0.044500 -v 0.008450 0.138556 0.044466 -v 0.008855 0.149056 0.044349 -v 0.009197 0.138551 0.044208 -v 0.009250 0.149056 0.044165 -v 0.010165 0.149056 0.043250 -v 0.010222 0.138379 0.043151 -v 0.010362 0.138275 0.042822 -v 0.010349 0.149056 0.042855 -v 0.010462 0.149056 0.041566 -v 0.010477 0.137672 0.041632 -v 0.010486 0.138064 0.042297 -v 0.010165 0.149056 0.040750 -v 0.010349 0.137286 0.041146 -v 0.009709 0.136099 0.040173 -v 0.009915 0.149056 0.040393 -v 0.009915 0.136442 0.040393 -v 0.009254 0.135459 0.039846 -v 0.009250 0.149056 0.039835 -v 0.008996 0.135556 0.039707 -v 0.008603 0.135556 0.039574 -v 0.008000 0.149056 0.039500 -v 0.008194 0.135556 0.039508 -v 0.007566 0.149056 0.039538 -v 0.006853 0.135321 0.039774 -v 0.007145 0.149056 0.039651 -v 0.005538 0.149056 0.041566 -v 0.005500 0.149056 0.042000 -v 0.006085 0.149056 0.040393 -v 0.005651 0.149056 0.041145 -v 0.009821 0.149735 0.039409 -v 0.008627 0.149523 0.039071 -v 0.008855 0.149056 0.039651 -v 0.008434 0.149056 0.039538 -v 0.006946 0.149573 0.039141 -v 0.006750 0.149056 0.039835 -v 0.006393 0.149056 0.040085 -v 0.005201 0.150010 0.039890 -v 0.011266 0.150184 0.040316 -v 0.009607 0.149056 0.040085 -v 0.010349 0.149056 0.041145 -v 0.011996 0.150537 0.041797 -v 0.010500 0.149056 0.042000 -v 0.009915 0.149056 0.043607 -v 0.008304 0.150383 0.045829 -v 0.008434 0.149056 0.044462 -v 0.009704 0.150452 0.045523 -v 0.009607 0.149056 0.043915 -v 0.010961 0.150554 0.044721 -v 0.006244 0.150443 0.045553 -v 0.006393 0.149056 0.043915 -v 0.005835 0.149056 0.043250 -v 0.011731 0.150556 0.043472 -v 0.010462 0.149056 0.042434 -v 0.005538 0.149056 0.042434 -v 0.005651 0.149056 0.042855 -v 0.032752 0.135445 0.039842 -v 0.033389 0.135556 0.039576 -v 0.034000 0.149056 0.044500 -v 0.034338 0.138556 0.044477 -v 0.034852 0.138556 0.044359 -v 0.035250 0.149056 0.044165 -v 0.035915 0.149056 0.043607 -v 0.035607 0.149056 0.043915 -v 0.036500 0.149056 0.042000 -v 0.036494 0.138035 0.042224 -v 0.036462 0.149056 0.041566 -v 0.036352 0.137276 0.041151 -v 0.036477 0.137676 0.041637 -v 0.035607 0.149056 0.040085 -v 0.035915 0.149056 0.040393 -v 0.036163 0.136888 0.040747 -v 0.031852 0.136862 0.040725 -v 0.031835 0.149056 0.040750 -v 0.031651 0.137285 0.041145 -v 0.031500 0.149056 0.042000 -v 0.031517 0.137699 0.041664 -v 0.031538 0.149056 0.041566 -v 0.031651 0.149056 0.042855 -v 0.031734 0.138350 0.043055 -v 0.031544 0.138143 0.042480 -v 0.032085 0.149056 0.043607 -v 0.032434 0.138530 0.043954 -v 0.031835 0.149056 0.043250 -v 0.033145 0.149056 0.044349 -v 0.032750 0.149056 0.044165 -v 0.032799 0.138549 0.044198 -v 0.032393 0.149056 0.043915 -v 0.033201 0.138556 0.044374 -v 0.035258 0.135467 0.039848 -v 0.035000 0.135556 0.039709 -v 0.034855 0.149056 0.039651 -v 0.034205 0.135556 0.039508 -v 0.034611 0.135556 0.039576 -v 0.034000 0.149056 0.039500 -v 0.033795 0.135556 0.039508 -v 0.032393 0.149056 0.040085 -v 0.032750 0.149056 0.039835 -v 0.033145 0.149056 0.039651 -v 0.033000 0.135556 0.039709 -v 0.030027 0.150517 0.041579 -v 0.031538 0.149056 0.042434 -v 0.030706 0.150205 0.040400 -v 0.031651 0.149056 0.041145 -v 0.035250 0.149056 0.039835 -v 0.034434 0.149056 0.039538 -v 0.033764 0.149506 0.039049 -v 0.033566 0.149056 0.039538 -v 0.031870 0.149797 0.039492 -v 0.032085 0.149056 0.040393 -v 0.035461 0.149628 0.039238 -v 0.036165 0.149056 0.040750 -v 0.036349 0.149056 0.041145 -v 0.036462 0.149056 0.042434 -v 0.033633 0.150384 0.045824 -v 0.033566 0.149056 0.044462 -v 0.034434 0.149056 0.044462 -v 0.034855 0.149056 0.044349 -v 0.036294 0.150504 0.045248 -v 0.036165 0.149056 0.043250 -v 0.036349 0.149056 0.042855 -v 0.037996 0.150561 0.042454 -v 0.030320 0.150556 0.043627 -v 0.019747 0.095155 -0.000458 -v 0.020389 0.095424 -0.000556 -v 0.020795 0.095492 -0.000556 -v 0.021205 0.095492 -0.000556 -v 0.021000 0.090500 -0.014056 -v 0.020566 0.090538 -0.014056 -v 0.020551 0.090533 -0.003556 -v 0.020145 0.090651 -0.014056 -v 0.019803 0.090792 -0.003551 -v 0.019393 0.091085 -0.003525 -v 0.018835 0.091750 -0.014056 -v 0.019085 0.091393 -0.014056 -v 0.019393 0.091085 -0.014056 -v 0.018778 0.091849 -0.003379 -v 0.018638 0.092178 -0.003275 -v 0.018651 0.092145 -0.014056 -v 0.018500 0.093000 -0.014056 -v 0.018538 0.092566 -0.014056 -v 0.018514 0.092703 -0.003064 -v 0.018651 0.093854 -0.002286 -v 0.018523 0.093368 -0.002672 -v 0.018840 0.094258 -0.001878 -v 0.019291 0.094827 -0.001099 -v 0.019085 0.094607 -0.001442 -v 0.022915 0.094607 -0.001442 -v 0.022915 0.094607 -0.014056 -v 0.023148 0.094275 -0.001862 -v 0.023349 0.093855 -0.002285 -v 0.023500 0.093000 -0.014056 -v 0.023483 0.093336 -0.002699 -v 0.023266 0.091945 -0.003350 -v 0.023456 0.092520 -0.003143 -v 0.022915 0.091393 -0.014056 -v 0.022908 0.091383 -0.003482 -v 0.023140 0.091700 -0.003417 -v 0.022201 0.090802 -0.003549 -v 0.022566 0.091046 -0.003530 -v 0.021341 0.090523 -0.003556 -v 0.021434 0.090538 -0.014056 -v 0.021802 0.090629 -0.003556 -v 0.020000 0.095291 -0.000556 -v 0.019750 0.095165 -0.014056 -v 0.020566 0.095462 -0.014056 -v 0.021000 0.095500 -0.014056 -v 0.021611 0.095424 -0.000556 -v 0.022610 0.094913 -0.000950 -v 0.022250 0.095165 -0.014056 -v 0.022000 0.095291 -0.000556 -v 0.023349 0.093855 -0.014056 -v 0.023462 0.093434 -0.014056 -v 0.024807 0.093890 -0.015430 -v 0.023165 0.094250 -0.014056 -v 0.020145 0.095349 -0.014056 -v 0.021434 0.095462 -0.014056 -v 0.021855 0.095349 -0.014056 -v 0.023083 0.095483 -0.014798 -v 0.022607 0.094915 -0.014056 -v 0.023881 0.094972 -0.015050 -v 0.019085 0.094607 -0.014056 -v 0.019393 0.094915 -0.014056 -v 0.018651 0.093855 -0.014056 -v 0.018835 0.094250 -0.014056 -v 0.018538 0.093434 -0.014056 -v 0.023462 0.092566 -0.014056 -v 0.023349 0.092145 -0.014056 -v 0.023165 0.091750 -0.014056 -v 0.022607 0.091085 -0.014056 -v 0.022250 0.090835 -0.014056 -v 0.023000 0.089536 -0.015556 -v 0.021855 0.090651 -0.014056 -v 0.022017 0.089116 -0.015556 -v 0.021000 0.089000 -0.015556 -v 0.019928 0.089131 -0.015556 -v 0.019750 0.090835 -0.014056 -v 0.009249 0.095157 -0.000449 -v 0.006393 0.094915 -0.000868 -v 0.006393 0.094915 -0.014056 -v 0.008000 0.090500 -0.014056 -v 0.007145 0.090651 -0.014056 -v 0.006740 0.090825 -0.003538 -v 0.006750 0.090835 -0.014056 -v 0.006085 0.091393 -0.014056 -v 0.006393 0.091085 -0.014056 -v 0.005538 0.092566 -0.014056 -v 0.005668 0.092086 -0.003120 -v 0.005835 0.091750 -0.014056 -v 0.006054 0.091413 -0.003460 -v 0.005500 0.093000 -0.014056 -v 0.005538 0.092566 -0.002880 -v 0.005500 0.093000 -0.002633 -v 0.005835 0.094250 -0.014056 -v 0.005834 0.094248 -0.001675 -v 0.005651 0.093855 -0.014056 -v 0.005651 0.093855 -0.002032 -v 0.010148 0.094275 -0.001862 -v 0.010462 0.093434 -0.014056 -v 0.010349 0.093855 -0.014056 -v 0.010483 0.093336 -0.002699 -v 0.010349 0.092145 -0.014056 -v 0.010462 0.092566 -0.014056 -v 0.009915 0.091393 -0.014056 -v 0.009908 0.091383 -0.003482 -v 0.010140 0.091700 -0.003417 -v 0.009607 0.091085 -0.014056 -v 0.008802 0.090629 -0.003556 -v 0.008855 0.090651 -0.014056 -v 0.006865 0.095231 -0.000274 -v 0.007779 0.095490 -0.000556 -v 0.007566 0.095462 -0.014056 -v 0.007370 0.095419 -0.000556 -v 0.008194 0.095492 -0.000556 -v 0.008434 0.095462 -0.014056 -v 0.009610 0.094913 -0.000950 -v 0.009607 0.094915 -0.014056 -v 0.008996 0.095293 -0.000556 -v 0.008855 0.095349 -0.014056 -v 0.008603 0.095426 -0.000556 -v 0.010500 0.093000 -0.014056 -v 0.010165 0.094250 -0.014056 -v 0.006750 0.095165 -0.014056 -v 0.007145 0.095349 -0.014056 -v 0.005960 0.095591 -0.014745 -v 0.008000 0.095500 -0.014056 -v 0.008236 0.095951 -0.014506 -v 0.010130 0.095508 -0.014797 -v 0.009250 0.095165 -0.014056 -v 0.009915 0.094607 -0.014056 -v 0.006085 0.094607 -0.014056 -v 0.005538 0.093434 -0.014056 -v 0.011900 0.092024 -0.015558 -v 0.010165 0.091750 -0.014056 -v 0.009250 0.090835 -0.014056 -v 0.008434 0.090538 -0.014056 -v 0.009684 0.089388 -0.015556 -v 0.007566 0.090538 -0.014056 -v 0.007593 0.088946 -0.015556 -v 0.005675 0.089727 -0.015556 -v 0.005651 0.092145 -0.014056 -v 0.003999 0.092419 -0.015556 -v 0.032756 0.095161 -0.000446 -v 0.033795 0.095492 -0.000556 -v 0.035238 0.095165 -0.000434 -v 0.034000 0.090500 -0.003556 -v 0.033566 0.090538 -0.014056 -v 0.033551 0.090533 -0.003556 -v 0.033145 0.090651 -0.014056 -v 0.032803 0.090792 -0.003551 -v 0.032085 0.091393 -0.014056 -v 0.032393 0.091085 -0.014056 -v 0.032393 0.091085 -0.003525 -v 0.031778 0.091849 -0.003379 -v 0.032047 0.091431 -0.003473 -v 0.031500 0.093000 -0.014056 -v 0.031538 0.092566 -0.014056 -v 0.031651 0.093854 -0.002286 -v 0.031523 0.093368 -0.002672 -v 0.031538 0.093434 -0.014056 -v 0.031840 0.094258 -0.001878 -v 0.032750 0.095165 -0.014056 -v 0.032085 0.094607 -0.001442 -v 0.032085 0.094607 -0.014056 -v 0.035609 0.094914 -0.000943 -v 0.035915 0.094607 -0.014056 -v 0.036165 0.094250 -0.014056 -v 0.036349 0.093855 -0.014056 -v 0.036353 0.093846 -0.002278 -v 0.036462 0.092566 -0.014056 -v 0.036469 0.092602 -0.003100 -v 0.036500 0.093000 -0.014056 -v 0.036485 0.093317 -0.002710 -v 0.036462 0.093434 -0.014056 -v 0.036342 0.092116 -0.003295 -v 0.036349 0.092145 -0.014056 -v 0.035915 0.091393 -0.014056 -v 0.036054 0.091553 -0.003464 -v 0.035250 0.090835 -0.014056 -v 0.035201 0.090802 -0.003549 -v 0.035607 0.091085 -0.014056 -v 0.034389 0.090527 -0.003556 -v 0.034799 0.090626 -0.003556 -v 0.033000 0.095291 -0.000556 -v 0.033145 0.095349 -0.014056 -v 0.033389 0.095424 -0.000556 -v 0.034000 0.095500 -0.014056 -v 0.034205 0.095492 -0.000556 -v 0.034434 0.095462 -0.014056 -v 0.034611 0.095424 -0.000556 -v 0.035250 0.095165 -0.014056 -v 0.034855 0.095349 -0.014056 -v 0.035000 0.095291 -0.000556 -v 0.033566 0.095462 -0.014056 -v 0.035607 0.094915 -0.014056 -v 0.035741 0.095694 -0.014669 -v 0.032281 0.095660 -0.014698 -v 0.032393 0.094915 -0.014056 -v 0.031835 0.094250 -0.014056 -v 0.031651 0.093855 -0.014056 -v 0.029894 0.092873 -0.015561 -v 0.037477 0.090944 -0.015556 -v 0.036165 0.091750 -0.014056 -v 0.035981 0.089480 -0.015556 -v 0.034855 0.090651 -0.014056 -v 0.034434 0.090538 -0.014056 -v 0.034321 0.088998 -0.015556 -v 0.034000 0.090500 -0.014056 -v 0.032932 0.089130 -0.015556 -v 0.032750 0.090835 -0.014056 -v 0.031835 0.091750 -0.014056 -v 0.031651 0.092145 -0.014056 -v 0.040000 0.101368 0.032865 -v 0.040000 0.100943 0.031228 -v 0.040409 0.102015 0.030156 -v 0.040880 0.102511 0.029660 -v 0.041278 0.102789 0.029359 -v 0.040973 0.102828 0.030630 -v 0.040364 0.104765 0.033064 -v 0.040966 0.104526 0.032225 -v 0.041278 0.105641 0.032211 -v 0.040110 0.102587 0.032424 -v 0.040001 0.100115 0.032057 -v 0.040070 0.099722 0.032410 -v 0.040612 0.098758 0.033022 -v 0.040973 0.098356 0.033195 -v 0.042000 0.098511 0.033829 -v 0.040534 0.099444 0.033478 -v 0.040149 0.101241 0.034822 -v 0.042000 0.099528 0.035141 -v 0.040012 0.102298 0.035530 -v 0.040472 0.101334 0.036495 -v 0.041030 0.100616 0.035981 -v 0.008000 0.059370 0.129883 -v 0.009915 0.059979 0.129229 -v 0.010349 0.060492 0.128679 -v 0.010462 0.061371 0.127737 -v 0.010500 0.061075 0.128054 -v 0.009915 0.062171 0.126879 -v 0.009607 0.062381 0.126654 -v 0.008434 0.062754 0.126254 -v 0.006750 0.062551 0.126471 -v 0.006393 0.062381 0.126654 -v 0.005651 0.061658 0.127429 -v 0.005538 0.060779 0.128372 -v 0.008000 0.059976 0.127030 -v 0.005538 0.061371 0.127737 -v 0.005651 0.060492 0.128679 -v 0.008000 0.066683 0.136703 -v 0.008434 0.059396 0.129855 -v 0.008434 0.066709 0.136675 -v 0.008855 0.059473 0.129772 -v 0.008855 0.066786 0.136592 -v 0.009250 0.059598 0.129638 -v 0.009607 0.059769 0.129455 -v 0.009607 0.067082 0.136275 -v 0.009915 0.067292 0.136049 -v 0.010165 0.060222 0.128968 -v 0.010462 0.060779 0.128372 -v 0.010500 0.068388 0.134874 -v 0.010349 0.061658 0.127429 -v 0.010462 0.068684 0.134557 -v 0.010165 0.061927 0.127140 -v 0.010165 0.069241 0.133960 -v 0.009915 0.069484 0.133699 -v 0.009607 0.069694 0.133474 -v 0.009250 0.062551 0.126471 -v 0.008855 0.062677 0.126336 -v 0.008000 0.062780 0.126226 -v 0.008000 0.070093 0.133046 -v 0.007566 0.062754 0.126254 -v 0.007566 0.070067 0.133074 -v 0.007145 0.062677 0.126336 -v 0.007145 0.069990 0.133156 -v 0.006393 0.069694 0.133474 -v 0.006085 0.062171 0.126879 -v 0.006085 0.069484 0.133699 -v 0.005835 0.061927 0.127140 -v 0.005835 0.069241 0.133960 -v 0.005651 0.068971 0.134249 -v 0.005500 0.061075 0.128054 -v 0.005835 0.060222 0.128968 -v 0.006085 0.059979 0.129229 -v 0.006393 0.059769 0.129455 -v 0.006393 0.067082 0.136275 -v 0.006750 0.059598 0.129638 -v 0.006750 0.066912 0.136458 -v 0.007145 0.059473 0.129772 -v 0.007566 0.059396 0.129855 -v 0.007566 0.066709 0.136675 -v 0.021855 0.059473 0.129772 -v 0.021434 0.059396 0.129855 -v 0.022607 0.059769 0.129455 -v 0.023165 0.060222 0.128968 -v 0.022915 0.059979 0.129229 -v 0.023462 0.061371 0.127737 -v 0.022607 0.062381 0.126654 -v 0.023165 0.061927 0.127140 -v 0.022250 0.062551 0.126471 -v 0.021000 0.062780 0.126226 -v 0.020566 0.062754 0.126254 -v 0.021000 0.059976 0.127030 -v 0.019750 0.062551 0.126471 -v 0.018651 0.061658 0.127429 -v 0.018538 0.060779 0.128372 -v 0.018500 0.061075 0.128054 -v 0.018538 0.061371 0.127737 -v 0.021000 0.059370 0.129883 -v 0.022609 0.067083 0.136274 -v 0.023349 0.060492 0.128679 -v 0.023462 0.060779 0.128372 -v 0.023349 0.067805 0.135499 -v 0.023462 0.068092 0.135192 -v 0.023500 0.061075 0.128054 -v 0.023500 0.068388 0.134874 -v 0.023462 0.068684 0.134557 -v 0.023349 0.061658 0.127429 -v 0.023165 0.069241 0.133960 -v 0.022915 0.062171 0.126879 -v 0.022915 0.069484 0.133699 -v 0.022603 0.069697 0.133471 -v 0.022250 0.069865 0.133291 -v 0.021855 0.062677 0.126336 -v 0.021855 0.069990 0.133156 -v 0.021434 0.062754 0.126254 -v 0.021434 0.070067 0.133074 -v 0.020145 0.062677 0.126336 -v 0.019750 0.069865 0.133291 -v 0.019393 0.062381 0.126654 -v 0.019085 0.062171 0.126879 -v 0.019085 0.069484 0.133699 -v 0.018835 0.061927 0.127140 -v 0.018835 0.069241 0.133960 -v 0.018538 0.068684 0.134557 -v 0.018500 0.068388 0.134874 -v 0.018651 0.067805 0.135499 -v 0.018651 0.060492 0.128679 -v 0.018835 0.067536 0.135788 -v 0.018835 0.060222 0.128968 -v 0.019085 0.059979 0.129229 -v 0.019393 0.059769 0.129455 -v 0.019393 0.067082 0.136275 -v 0.019750 0.059598 0.129638 -v 0.019750 0.066912 0.136458 -v 0.020145 0.059473 0.129772 -v 0.020566 0.059396 0.129855 -v 0.020566 0.066709 0.136675 -v 0.021000 0.066683 0.136703 -v 0.021434 0.066709 0.136675 -v 0.022250 0.059598 0.129638 -v 0.035607 0.059769 0.129455 -v 0.034855 0.059473 0.129772 -v 0.036349 0.061658 0.127429 -v 0.036500 0.061075 0.128054 -v 0.036165 0.061927 0.127140 -v 0.034855 0.062677 0.126336 -v 0.034434 0.062754 0.126254 -v 0.034000 0.059976 0.127030 -v 0.032085 0.062171 0.126879 -v 0.033145 0.062677 0.126336 -v 0.031651 0.061658 0.127429 -v 0.031835 0.061927 0.127140 -v 0.033145 0.059473 0.129772 -v 0.032750 0.059598 0.129638 -v 0.034000 0.059370 0.129883 -v 0.034434 0.059396 0.129855 -v 0.034434 0.066709 0.136675 -v 0.034855 0.066786 0.136592 -v 0.035250 0.059598 0.129638 -v 0.035250 0.066912 0.136458 -v 0.035915 0.059979 0.129229 -v 0.035607 0.067082 0.136275 -v 0.035915 0.067292 0.136049 -v 0.036165 0.060222 0.128968 -v 0.036349 0.060492 0.128679 -v 0.036349 0.067805 0.135499 -v 0.036462 0.060779 0.128372 -v 0.036462 0.068092 0.135192 -v 0.036462 0.061371 0.127737 -v 0.036500 0.068388 0.134874 -v 0.036349 0.068971 0.134249 -v 0.035915 0.062171 0.126879 -v 0.035607 0.062381 0.126654 -v 0.035607 0.069694 0.133474 -v 0.035250 0.069865 0.133291 -v 0.035250 0.062551 0.126471 -v 0.034855 0.069990 0.133156 -v 0.034000 0.062780 0.126226 -v 0.034000 0.070093 0.133046 -v 0.033566 0.062754 0.126254 -v 0.033566 0.070067 0.133074 -v 0.032750 0.062551 0.126471 -v 0.032393 0.062381 0.126654 -v 0.032085 0.069484 0.133699 -v 0.031651 0.068971 0.134249 -v 0.031538 0.068684 0.134557 -v 0.031538 0.061371 0.127737 -v 0.031500 0.061075 0.128054 -v 0.031538 0.060779 0.128372 -v 0.031538 0.068092 0.135192 -v 0.031651 0.067805 0.135499 -v 0.031651 0.060492 0.128679 -v 0.031835 0.060222 0.128968 -v 0.031835 0.067536 0.135788 -v 0.032085 0.059979 0.129229 -v 0.032393 0.059769 0.129455 -v 0.032085 0.067292 0.136049 -v 0.032393 0.067082 0.136275 -v 0.032750 0.066912 0.136458 -v 0.033145 0.066786 0.136592 -v 0.033566 0.059396 0.129855 -v 0.033566 0.066709 0.136675 -v 0.021434 0.125550 0.058913 -v 0.021855 0.125626 0.058831 -v 0.023165 0.126376 0.058027 -v 0.022915 0.126133 0.058288 -v 0.023462 0.127525 0.056795 -v 0.022607 0.128535 0.055712 -v 0.023165 0.128081 0.056199 -v 0.022250 0.128705 0.055529 -v 0.021000 0.128934 0.055284 -v 0.019750 0.128705 0.055529 -v 0.019393 0.128535 0.055712 -v 0.020145 0.128831 0.055395 -v 0.018651 0.127812 0.056488 -v 0.018651 0.126645 0.057738 -v 0.018538 0.127525 0.056795 -v 0.018835 0.126376 0.058027 -v 0.020145 0.125626 0.058831 -v 0.020566 0.125550 0.058913 -v 0.021000 0.125524 0.058941 -v 0.021000 0.126130 0.056088 -v 0.022607 0.125923 0.058513 -v 0.022915 0.133446 0.065108 -v 0.023349 0.126645 0.057738 -v 0.023462 0.126933 0.057430 -v 0.023349 0.133959 0.064558 -v 0.023462 0.134246 0.064250 -v 0.023500 0.127229 0.057113 -v 0.023462 0.134838 0.063615 -v 0.023349 0.127812 0.056488 -v 0.023165 0.135395 0.063019 -v 0.022915 0.128325 0.055938 -v 0.022575 0.135864 0.062516 -v 0.022250 0.136019 0.062349 -v 0.021855 0.128831 0.055395 -v 0.021434 0.128908 0.055312 -v 0.020566 0.128908 0.055312 -v 0.020566 0.136221 0.062132 -v 0.020145 0.136144 0.062215 -v 0.019750 0.136019 0.062349 -v 0.019085 0.128325 0.055938 -v 0.018835 0.128081 0.056199 -v 0.018651 0.135125 0.063308 -v 0.018538 0.134838 0.063615 -v 0.018500 0.127229 0.057113 -v 0.018500 0.134542 0.063933 -v 0.018538 0.126933 0.057430 -v 0.018538 0.134246 0.064250 -v 0.018651 0.133959 0.064558 -v 0.018835 0.133690 0.064847 -v 0.019085 0.126133 0.058288 -v 0.019393 0.125923 0.058513 -v 0.019750 0.125752 0.058696 -v 0.019393 0.133236 0.065333 -v 0.020145 0.132940 0.065651 -v 0.020566 0.132863 0.065733 -v 0.021000 0.132837 0.065761 -v 0.021855 0.132940 0.065651 -v 0.022250 0.125752 0.058696 -v 0.022250 0.133066 0.065516 -v 0.022607 0.133236 0.065333 -v 0.023349 0.092546 0.094306 -v 0.023165 0.092276 0.094595 -v 0.022915 0.094225 0.092505 -v 0.021434 0.094808 0.091880 -v 0.021000 0.094834 0.091852 -v 0.019085 0.094225 0.092505 -v 0.019393 0.094435 0.092280 -v 0.018651 0.093712 0.093055 -v 0.018835 0.093981 0.092766 -v 0.018651 0.092546 0.094306 -v 0.018538 0.093425 0.093363 -v 0.019085 0.092033 0.094856 -v 0.021000 0.092030 0.092656 -v 0.020145 0.091527 0.095399 -v 0.019750 0.091652 0.095264 -v 0.022250 0.091652 0.095264 -v 0.022607 0.091823 0.095081 -v 0.022915 0.092033 0.094856 -v 0.023165 0.099590 0.101415 -v 0.023462 0.092833 0.093998 -v 0.023500 0.093129 0.093681 -v 0.023462 0.093425 0.093363 -v 0.023349 0.093712 0.093055 -v 0.023349 0.101025 0.099875 -v 0.023165 0.093981 0.092766 -v 0.022607 0.094435 0.092280 -v 0.022250 0.094605 0.092097 -v 0.022575 0.101764 0.099084 -v 0.022250 0.101919 0.098917 -v 0.021855 0.094731 0.091962 -v 0.021855 0.102044 0.098782 -v 0.021000 0.102147 0.098672 -v 0.020566 0.094808 0.091880 -v 0.020145 0.094731 0.091962 -v 0.020566 0.102121 0.098700 -v 0.019750 0.094605 0.092097 -v 0.019750 0.101919 0.098917 -v 0.019393 0.101748 0.099100 -v 0.018835 0.101295 0.099586 -v 0.018500 0.093129 0.093681 -v 0.018538 0.100738 0.100183 -v 0.018538 0.092833 0.093998 -v 0.018500 0.100442 0.100501 -v 0.018835 0.092276 0.094595 -v 0.018651 0.099859 0.101126 -v 0.018835 0.099590 0.101415 -v 0.019085 0.099346 0.101676 -v 0.019393 0.091823 0.095081 -v 0.019393 0.099136 0.101901 -v 0.019750 0.098966 0.102084 -v 0.020566 0.091450 0.095481 -v 0.021000 0.091424 0.095509 -v 0.020566 0.098763 0.102301 -v 0.021000 0.098737 0.102329 -v 0.021434 0.091450 0.095481 -v 0.021434 0.098763 0.102301 -v 0.021855 0.091527 0.095399 -v 0.008434 0.125550 0.058913 -v 0.008855 0.125626 0.058831 -v 0.009915 0.126133 0.058288 -v 0.010462 0.126933 0.057430 -v 0.010462 0.127525 0.056795 -v 0.010349 0.127812 0.056488 -v 0.010165 0.128081 0.056199 -v 0.006393 0.128535 0.055712 -v 0.006750 0.128705 0.055529 -v 0.005835 0.128081 0.056199 -v 0.006085 0.128325 0.055938 -v 0.008000 0.126130 0.056088 -v 0.005538 0.126933 0.057430 -v 0.005500 0.127229 0.057113 -v 0.007145 0.125626 0.058831 -v 0.008000 0.125524 0.058941 -v 0.008855 0.132940 0.065651 -v 0.009250 0.125752 0.058696 -v 0.009250 0.133066 0.065516 -v 0.009607 0.125923 0.058513 -v 0.009915 0.133446 0.065108 -v 0.010165 0.126376 0.058027 -v 0.010349 0.126645 0.057738 -v 0.010165 0.133690 0.064847 -v 0.010349 0.133959 0.064558 -v 0.010500 0.127229 0.057113 -v 0.010500 0.134542 0.063933 -v 0.010462 0.134838 0.063615 -v 0.010165 0.135395 0.063019 -v 0.009915 0.128325 0.055938 -v 0.009607 0.128535 0.055712 -v 0.009607 0.135848 0.062532 -v 0.009250 0.128705 0.055529 -v 0.009250 0.136019 0.062349 -v 0.008855 0.128831 0.055395 -v 0.008855 0.136144 0.062215 -v 0.008434 0.128908 0.055312 -v 0.008434 0.136221 0.062132 -v 0.008000 0.128934 0.055284 -v 0.007566 0.128908 0.055312 -v 0.007145 0.128831 0.055395 -v 0.006750 0.136019 0.062349 -v 0.006393 0.135848 0.062532 -v 0.005651 0.127812 0.056488 -v 0.005651 0.135125 0.063308 -v 0.005538 0.127525 0.056795 -v 0.005538 0.134838 0.063615 -v 0.005538 0.134246 0.064250 -v 0.005651 0.126645 0.057738 -v 0.005835 0.126376 0.058027 -v 0.005651 0.133959 0.064558 -v 0.005835 0.133690 0.064847 -v 0.006085 0.126133 0.058288 -v 0.006393 0.125923 0.058513 -v 0.006393 0.133236 0.065333 -v 0.006750 0.125752 0.058696 -v 0.006750 0.133066 0.065516 -v 0.007566 0.125550 0.058913 -v 0.034434 0.125550 0.058913 -v 0.035607 0.125923 0.058513 -v 0.036165 0.126376 0.058027 -v 0.036462 0.127525 0.056795 -v 0.036349 0.127812 0.056488 -v 0.036500 0.127229 0.057113 -v 0.035915 0.128325 0.055938 -v 0.036165 0.128081 0.056199 -v 0.034000 0.126130 0.056088 -v 0.034434 0.128908 0.055312 -v 0.034855 0.128831 0.055395 -v 0.035250 0.128705 0.055529 -v 0.033566 0.128908 0.055312 -v 0.034000 0.128934 0.055284 -v 0.032085 0.128325 0.055938 -v 0.031538 0.127525 0.056795 -v 0.031651 0.126645 0.057738 -v 0.033145 0.125626 0.058831 -v 0.033566 0.125550 0.058913 -v 0.034855 0.125626 0.058831 -v 0.034855 0.132940 0.065651 -v 0.035250 0.125752 0.058696 -v 0.035915 0.126133 0.058288 -v 0.035915 0.133446 0.065108 -v 0.036349 0.126645 0.057738 -v 0.036462 0.126933 0.057430 -v 0.036462 0.134246 0.064250 -v 0.036349 0.135125 0.063308 -v 0.035915 0.135638 0.062758 -v 0.035607 0.128535 0.055712 -v 0.035607 0.135848 0.062532 -v 0.035250 0.136019 0.062349 -v 0.034434 0.136221 0.062132 -v 0.034000 0.136247 0.062104 -v 0.033145 0.136144 0.062215 -v 0.033145 0.128831 0.055395 -v 0.032750 0.136019 0.062349 -v 0.032750 0.128705 0.055529 -v 0.032393 0.135848 0.062532 -v 0.032393 0.128535 0.055712 -v 0.031835 0.128081 0.056199 -v 0.031835 0.135395 0.063019 -v 0.031651 0.127812 0.056488 -v 0.031538 0.134838 0.063615 -v 0.031500 0.127229 0.057113 -v 0.031500 0.134542 0.063933 -v 0.031538 0.134246 0.064250 -v 0.031538 0.126933 0.057430 -v 0.031835 0.126376 0.058027 -v 0.032085 0.126133 0.058288 -v 0.032393 0.125923 0.058513 -v 0.032750 0.125752 0.058696 -v 0.032750 0.133066 0.065516 -v 0.033566 0.132863 0.065733 -v 0.034000 0.125524 0.058941 -v 0.034000 0.132837 0.065761 -v 0.008855 0.091527 0.095399 -v 0.009607 0.091823 0.095081 -v 0.010349 0.092546 0.094306 -v 0.010462 0.093425 0.093363 -v 0.010349 0.093712 0.093055 -v 0.010500 0.093129 0.093681 -v 0.010165 0.093981 0.092766 -v 0.008855 0.094731 0.091962 -v 0.008434 0.094808 0.091880 -v 0.008000 0.092030 0.092656 -v 0.006750 0.094605 0.092097 -v 0.006393 0.094435 0.092280 -v 0.005651 0.093712 0.093055 -v 0.005835 0.093981 0.092766 -v 0.005538 0.092833 0.093998 -v 0.006085 0.092033 0.094856 -v 0.006393 0.091823 0.095081 -v 0.005835 0.092276 0.094595 -v 0.005651 0.092546 0.094306 -v 0.008000 0.091424 0.095509 -v 0.008000 0.098737 0.102329 -v 0.008434 0.091450 0.095481 -v 0.008855 0.098840 0.102219 -v 0.009250 0.091652 0.095264 -v 0.009607 0.099136 0.101901 -v 0.009915 0.092033 0.094856 -v 0.010165 0.092276 0.094595 -v 0.010165 0.099590 0.101415 -v 0.010349 0.099859 0.101126 -v 0.010462 0.092833 0.093998 -v 0.010500 0.100442 0.100501 -v 0.010462 0.100738 0.100183 -v 0.010349 0.101025 0.099875 -v 0.009915 0.094225 0.092505 -v 0.009607 0.094435 0.092280 -v 0.009915 0.101538 0.099325 -v 0.009250 0.094605 0.092097 -v 0.008434 0.102121 0.098700 -v 0.008000 0.094834 0.091852 -v 0.007566 0.094808 0.091880 -v 0.007566 0.102121 0.098700 -v 0.007145 0.094731 0.091962 -v 0.007145 0.102044 0.098782 -v 0.006085 0.094225 0.092505 -v 0.006085 0.101538 0.099325 -v 0.005651 0.101025 0.099875 -v 0.005538 0.093425 0.093363 -v 0.005500 0.093129 0.093681 -v 0.005500 0.100442 0.100501 -v 0.005651 0.099859 0.101126 -v 0.005835 0.099590 0.101415 -v 0.006085 0.099346 0.101676 -v 0.006750 0.098966 0.102084 -v 0.006750 0.091652 0.095264 -v 0.007145 0.091527 0.095399 -v 0.007566 0.091450 0.095481 -v 0.007566 0.098763 0.102301 -v 0.034000 0.091424 0.095509 -v 0.035915 0.092033 0.094856 -v 0.036349 0.093712 0.093055 -v 0.036500 0.093129 0.093681 -v 0.036462 0.092833 0.093998 -v 0.036165 0.093981 0.092766 -v 0.035250 0.094605 0.092097 -v 0.034000 0.092030 0.092656 -v 0.032085 0.094225 0.092505 -v 0.033145 0.094731 0.091962 -v 0.031835 0.093981 0.092766 -v 0.031538 0.092833 0.093998 -v 0.031651 0.092546 0.094306 -v 0.031500 0.093129 0.093681 -v 0.032085 0.092033 0.094856 -v 0.031835 0.092276 0.094595 -v 0.033145 0.091527 0.095399 -v 0.033566 0.091450 0.095481 -v 0.034434 0.091450 0.095481 -v 0.034855 0.091527 0.095399 -v 0.035250 0.098966 0.102084 -v 0.035250 0.091652 0.095264 -v 0.035607 0.091823 0.095081 -v 0.035607 0.099136 0.101901 -v 0.035915 0.099346 0.101676 -v 0.036165 0.099590 0.101415 -v 0.036165 0.092276 0.094595 -v 0.036349 0.092546 0.094306 -v 0.036349 0.099859 0.101126 -v 0.036462 0.100146 0.100818 -v 0.036462 0.093425 0.093363 -v 0.036165 0.101295 0.099586 -v 0.035915 0.094225 0.092505 -v 0.035915 0.101538 0.099325 -v 0.035607 0.094435 0.092280 -v 0.035250 0.101919 0.098917 -v 0.034855 0.094731 0.091962 -v 0.034855 0.102044 0.098782 -v 0.034434 0.094808 0.091880 -v 0.034434 0.102121 0.098700 -v 0.034000 0.094834 0.091852 -v 0.034000 0.102147 0.098672 -v 0.033566 0.094808 0.091880 -v 0.032750 0.094605 0.092097 -v 0.033145 0.102044 0.098782 -v 0.032750 0.101919 0.098917 -v 0.032393 0.094435 0.092280 -v 0.032393 0.101748 0.099100 -v 0.032085 0.101538 0.099325 -v 0.031835 0.101295 0.099586 -v 0.031651 0.093712 0.093055 -v 0.031538 0.093425 0.093363 -v 0.031538 0.100738 0.100183 -v 0.031500 0.100442 0.100501 -v 0.031538 0.100146 0.100818 -v 0.031651 0.099859 0.101126 -v 0.031835 0.099590 0.101415 -v 0.032393 0.091823 0.095081 -v 0.032085 0.099346 0.101676 -v 0.032393 0.099136 0.101901 -v 0.032750 0.091652 0.095264 -v 0.032750 0.098966 0.102084 -v 0.033145 0.098840 0.102219 -v 0.034000 0.098737 0.102329 -v 0.042000 0.016441 -0.088639 -v 0.029007 0.016175 -0.088688 -v 0.028718 0.016441 -0.088639 -v 0.029242 0.015632 -0.088830 -v 0.031482 0.014673 -0.089225 -v 0.032357 0.014835 -0.089146 -v 0.042000 0.015429 -0.088900 -v 0.042000 0.013615 -0.089925 -v -0.000000 0.015429 -0.088900 -v -0.000000 0.014477 -0.089333 -v 0.042000 0.012868 -0.090657 -v -0.000000 0.012260 -0.091508 -v -0.000000 0.013615 -0.089925 -v 0.042000 0.014477 -0.089333 -v 0.042000 -0.012868 -0.090657 -v 0.042000 0.005421 -0.089853 -v 0.042000 0.011399 -0.092000 -v 0.042000 0.011738 -0.091941 -v 0.042000 0.011895 -0.091868 -v 0.042000 0.012162 -0.091645 -v 0.042000 -0.012037 -0.091770 -v 0.042000 -0.011571 -0.091985 -v 0.042000 -0.012260 -0.091508 -v -0.000000 0.016199 -0.088679 -v -0.000000 -0.005421 -0.089853 -v -0.000000 0.012868 -0.090657 -v -0.000000 0.012037 -0.091770 -v -0.000000 0.011399 -0.092000 -v -0.000000 -0.011399 -0.092000 -v -0.000000 -0.012037 -0.091770 -v 0.000000 -0.012161 -0.091646 -v -0.000000 0.011571 -0.091985 -v 0.042000 0.011571 -0.091985 -v -0.000000 0.011738 -0.091941 -v -0.000000 0.011895 -0.091868 -v -0.000000 0.012160 -0.091649 -v 0.042000 0.012037 -0.091770 -v 0.035000 0.057474 -0.073073 -v 0.035000 0.057469 -0.072630 -v 0.032589 0.056610 -0.066965 -v 0.032000 0.056702 -0.066421 -v 0.034242 0.056582 -0.069449 -v 0.042000 0.056584 -0.069485 -v 0.042000 0.056878 -0.070996 -v 0.042000 0.037058 -0.082880 -v 0.042000 0.054851 -0.078114 -v 0.042000 0.024629 -0.088230 -v 0.042000 0.025470 -0.088707 -v 0.042000 0.045361 -0.079488 -v 0.042000 0.048254 -0.077820 -v 0.042000 0.051440 -0.077415 -v 0.042000 0.044274 -0.081079 -v 0.042000 0.043937 -0.081985 -v 0.042000 0.026223 -0.089312 -v 0.042000 0.043425 -0.083816 -v 0.042000 0.026743 -0.089668 -v 0.042000 0.027038 -0.089780 -v 0.042000 0.042733 -0.084453 -v 0.042000 0.043749 -0.082934 -v 0.042000 0.042996 -0.084278 -v 0.042000 0.043229 -0.084064 -v 0.042000 0.055382 -0.078011 -v 0.042000 0.027663 -0.089859 -v 0.042000 0.027348 -0.089844 -v 0.042000 0.026469 -0.089511 -v 0.039731 0.056145 -0.076722 -v 0.040074 0.056328 -0.076220 -v 0.035000 0.055850 -0.077532 -v 0.037203 0.056646 -0.075348 -v 0.037433 0.056806 -0.074906 -v 0.037808 0.056930 -0.074566 -v 0.037991 0.048509 -0.071389 -v 0.038285 0.057003 -0.074366 -v 0.038492 0.048558 -0.071254 -v 0.038808 0.057015 -0.074332 -v 0.039307 0.056967 -0.074466 -v 0.039733 0.056860 -0.074757 -v 0.040023 0.056714 -0.075160 -v 0.040148 0.056545 -0.075624 -v 0.040112 0.047889 -0.073019 -v 0.039825 0.047646 -0.073508 -v 0.039302 0.056038 -0.077015 -v 0.038649 0.055985 -0.077162 -v 0.038017 0.056036 -0.077022 -v 0.037954 0.047421 -0.073853 -v 0.037583 0.056139 -0.076739 -v 0.037351 0.056247 -0.076443 -v 0.037500 0.047626 -0.073548 -v 0.037155 0.056419 -0.075969 -v 0.042000 0.057458 -0.073117 -v 0.042000 0.057483 -0.072668 -v 0.035000 0.054897 -0.078127 -v 0.035000 0.055555 -0.077914 -v 0.042000 0.055812 -0.077634 -v 0.033417 0.056524 -0.067936 -v 0.032000 0.046895 -0.078322 -v 0.033228 0.048239 -0.077826 -v 0.034119 0.049891 -0.077465 -v 0.033739 0.051928 -0.075297 -v 0.034916 0.052266 -0.077483 -v 0.034667 0.051223 -0.077410 -v 0.035000 0.053054 -0.077603 -v 0.032000 0.055108 -0.070172 -v 0.032774 0.055188 -0.070213 -v 0.032804 0.049448 -0.076830 -v 0.032782 0.051670 -0.074918 -v 0.032000 0.049377 -0.076761 -v 0.034621 0.054775 -0.073452 -v 0.034912 0.056974 -0.071352 -v 0.034578 0.056710 -0.070279 -v 0.033878 0.055727 -0.070364 -v 0.032000 0.053528 -0.072642 -v 0.032784 0.053604 -0.072695 -v 0.033729 0.053961 -0.072957 -v 0.034481 0.052511 -0.075781 -v 0.034954 0.055513 -0.074128 -v 0.021000 -0.000150 0.143589 -v 0.006000 0.002060 0.153985 -v 0.002000 0.017547 0.152896 -v 0.002000 0.059030 0.143040 -v 0.002000 0.058696 0.143232 -v 0.002000 0.029108 0.150941 -v 0.040000 0.058863 0.143136 -v 0.040000 0.056583 0.131530 -v 0.036000 0.060496 0.130698 -v 0.040000 0.003763 0.142757 -v 0.040000 0.006124 0.153866 -v 0.039939 0.005420 0.153895 -v 0.039759 0.002425 0.143041 -v 0.039464 0.001807 0.143173 -v 0.039464 0.004095 0.153940 -v 0.037368 0.000086 0.143538 -v 0.038000 0.000375 0.143477 -v 0.037923 0.002554 0.153977 -v 0.036695 -0.000090 0.143576 -v 0.036000 -0.000150 0.143589 -v 0.004632 0.000086 0.143538 -v 0.004308 0.002436 0.153979 -v 0.003429 0.000766 0.143394 -v 0.003493 0.002949 0.153970 -v 0.002936 0.001248 0.143292 -v 0.002536 0.001807 0.143173 -v 0.002241 0.002425 0.143041 -v 0.002536 0.004095 0.153940 -v 0.002061 0.003084 0.142901 -v 0.002000 0.003763 0.142757 -v 0.036000 0.062600 0.140598 -v 0.036695 0.060436 0.130711 -v 0.037368 0.060260 0.130748 -v 0.038509 0.061832 0.141190 -v 0.039064 0.059098 0.130995 -v 0.039064 0.061341 0.141547 -v 0.039464 0.058539 0.131114 -v 0.039759 0.057921 0.131245 -v 0.039939 0.059660 0.142663 -v 0.002061 0.059660 0.142663 -v 0.002536 0.060832 0.141902 -v 0.002936 0.061341 0.141547 -v 0.004079 0.062176 0.140930 -v 0.005398 0.062567 0.140625 -v 0.010870 0.064264 -0.055904 -v 0.029135 0.064260 -0.055905 -v 0.010197 0.062416 -0.056820 -v 0.009529 0.061313 -0.057629 -v 0.031402 0.060211 -0.058715 -v 0.032168 0.059548 -0.059619 -v 0.007008 0.059127 -0.060230 -v 0.033245 0.058796 -0.060919 -v 0.033729 0.058497 -0.061510 -v 0.029000 0.072521 -0.053643 -v 0.024000 0.070308 -0.037658 -v 0.029000 0.073935 -0.051194 -v 0.026128 0.073432 -0.049317 -v 0.010999 0.074008 -0.051472 -v 0.013872 0.073432 -0.049317 -v 0.025142 0.070515 -0.038430 -v 0.020000 0.070031 -0.036623 -v 0.018611 0.070062 -0.036740 -v 0.017264 0.070156 -0.037089 -v 0.027518 0.072810 -0.046993 -v 0.029000 0.071153 -0.040809 -v 0.027878 0.071742 -0.043008 -v 0.027518 0.071393 -0.041707 -v 0.026928 0.071066 -0.040486 -v 0.013872 0.070771 -0.039383 -v 0.016000 0.070308 -0.037658 -v 0.009992 0.069794 -0.035739 -v 0.014858 0.070515 -0.038430 -v 0.007090 0.069655 -0.031153 -v 0.009213 0.069518 -0.034278 -v 0.031816 0.069498 -0.032717 -v 0.008246 0.069460 -0.032785 -v 0.030000 0.065280 -0.054548 -v 0.030000 0.073111 -0.051985 -v 0.010000 0.072969 -0.051452 -v 0.018615 0.073983 -0.051979 -v 0.017264 0.055137 -0.056678 -v 0.018092 0.073996 -0.051886 -v 0.020000 0.073958 -0.052135 -v 0.020695 0.073965 -0.052102 -v 0.021389 0.073982 -0.052002 -v 0.022736 0.055137 -0.056678 -v 0.022736 0.074002 -0.051624 -v 0.023885 0.073917 -0.051119 -v 0.016099 0.073915 -0.051108 -v 0.014858 0.054777 -0.055337 -v 0.014858 0.073688 -0.050269 -v 0.013872 0.054522 -0.054384 -v 0.013072 0.054226 -0.053281 -v 0.013072 0.073137 -0.048214 -v 0.012482 0.072810 -0.046993 -v 0.012122 0.053550 -0.050759 -v 0.012122 0.072461 -0.045692 -v 0.012000 0.072102 -0.044350 -v 0.012122 0.071742 -0.043008 -v 0.012482 0.071393 -0.041707 -v 0.013072 0.071066 -0.040486 -v 0.013872 0.051860 -0.044450 -v 0.016000 0.051398 -0.042725 -v 0.017264 0.051245 -0.042156 -v 0.018611 0.051152 -0.041807 -v 0.020000 0.051120 -0.041690 -v 0.021389 0.070062 -0.036740 -v 0.022736 0.051245 -0.042156 -v 0.022736 0.070156 -0.037089 -v 0.025142 0.051605 -0.043497 -v 0.026128 0.070771 -0.039383 -v 0.026128 0.051860 -0.044450 -v 0.026928 0.052156 -0.045553 -v 0.028000 0.072102 -0.044350 -v 0.028000 0.053191 -0.049417 -v 0.027878 0.053550 -0.050759 -v 0.027878 0.072461 -0.045692 -v 0.026928 0.073137 -0.048214 -v 0.025142 0.073688 -0.050269 -v 0.021908 0.073996 -0.051886 -v 0.022931 0.073988 -0.051538 -v 0.029000 0.074009 -0.051674 -v 0.019305 0.073965 -0.052102 -v 0.017036 0.073996 -0.051535 -v 0.011000 0.072521 -0.053643 -v 0.011000 0.072821 -0.053536 -v 0.028999 0.073810 -0.052578 -v 0.011000 0.073960 -0.052126 -v 0.032880 0.059230 -0.059943 -v 0.032428 0.069351 -0.032611 -v 0.032946 0.059179 -0.060056 -v 0.032954 0.069553 -0.031629 -v 0.033341 0.058874 -0.060729 -v 0.033628 0.058653 -0.061217 -v 0.032447 0.059701 -0.059225 -v 0.031841 0.060361 -0.058218 -v 0.032305 0.069335 -0.032865 -v 0.031712 0.060556 -0.058001 -v 0.031498 0.060879 -0.057642 -v 0.031044 0.061564 -0.056880 -v 0.031196 0.069314 -0.035268 -v 0.030811 0.069376 -0.036238 -v 0.030627 0.069479 -0.036724 -v 0.030164 0.069834 -0.038755 -v 0.030185 0.063743 -0.055251 -v 0.030000 0.070187 -0.041068 -v 0.009823 0.069842 -0.038955 -v 0.009195 0.069379 -0.036250 -v 0.008391 0.069265 -0.034317 -v 0.008186 0.069248 -0.033853 -v 0.007689 0.059840 -0.058998 -v 0.007335 0.059277 -0.060017 -v 0.006000 0.070057 -0.029730 -v 0.006331 0.058594 -0.061280 -v 0.006000 0.058366 -0.061851 -v 0.030008 0.069794 -0.035739 -v 0.030468 0.069602 -0.034866 -v 0.031863 0.069504 -0.032649 -v 0.031425 0.069454 -0.033283 -v 0.031710 0.069262 -0.034090 -v 0.030884 0.069537 -0.034177 -v 0.031547 0.069242 -0.034426 -v 0.034000 0.070057 -0.029730 -v 0.033461 0.069749 -0.030682 -v 0.032674 0.069595 -0.031474 -v 0.033133 0.069622 -0.031296 -v 0.032991 0.069705 -0.031058 -v 0.029076 0.070770 -0.039381 -v 0.030053 0.070064 -0.040317 -v 0.029361 0.070338 -0.037768 -v 0.030000 0.072262 -0.052677 -v 0.029000 0.072821 -0.053536 -v 0.029000 0.073089 -0.053391 -v 0.029000 0.073342 -0.053198 -v 0.029000 0.073559 -0.052969 -v 0.029000 0.073960 -0.052126 -v 0.029000 0.065539 -0.055514 -v 0.032519 0.059244 -0.060032 -v 0.030028 0.064694 -0.054778 -v 0.029009 0.065174 -0.055612 -v 0.029094 0.064536 -0.055815 -v 0.029372 0.063408 -0.056269 -v 0.030530 0.061227 -0.057701 -v 0.030505 0.062715 -0.055913 -v 0.029811 0.062385 -0.056840 -v 0.008815 0.069302 -0.035276 -v 0.008968 0.069315 -0.035623 -v 0.007132 0.069488 -0.031769 -v 0.009563 0.069645 -0.034953 -v 0.007696 0.069359 -0.032885 -v 0.007054 0.069528 -0.031629 -v 0.006869 0.069620 -0.031296 -v 0.009599 0.069632 -0.037644 -v 0.010000 0.070187 -0.041068 -v 0.011000 0.071153 -0.040809 -v 0.010424 0.070102 -0.036886 -v 0.010839 0.070584 -0.038687 -v 0.009975 0.070042 -0.040149 -v 0.009706 0.069692 -0.038040 -v 0.011000 0.073870 -0.052430 -v 0.011000 0.073735 -0.052711 -v 0.011000 0.073560 -0.052968 -v 0.010000 0.072719 -0.052554 -v 0.011000 0.073342 -0.053198 -v 0.011000 0.073089 -0.053391 -v 0.009991 0.064953 -0.054684 -v 0.010000 0.065280 -0.054548 -v 0.011000 0.065539 -0.055514 -v 0.011002 0.065117 -0.055630 -v 0.009921 0.064388 -0.054932 -v 0.009053 0.061742 -0.056712 -v 0.010608 0.063345 -0.056299 -v 0.009589 0.062968 -0.055740 -v 0.009817 0.063817 -0.055224 -v 0.009879 0.064065 -0.055079 -v 0.006789 0.058822 -0.060879 -v 0.008569 0.060182 -0.058749 -v 0.008260 0.060493 -0.058051 -v 0.008655 0.061117 -0.057384 -v 0.028709 0.016452 -0.082000 -v 0.027891 0.016663 -0.088602 -v 0.027887 0.016667 -0.082000 -v 0.027566 0.016594 -0.088614 -v 0.027186 0.016376 -0.088650 -v 0.026909 0.016036 -0.088721 -v 0.026766 0.015646 -0.088829 -v 0.026833 0.015936 -0.082000 -v 0.026750 0.015432 -0.088900 -v 0.026759 0.015309 -0.082000 -v 0.026791 0.015081 -0.089034 -v 0.026970 0.014706 -0.089210 -v 0.027180 0.014477 -0.089334 -v 0.026904 0.014786 -0.082000 -v 0.027477 0.014271 -0.089454 -v 0.028078 0.014157 -0.089528 -v 0.028108 0.014168 -0.082000 -v 0.028696 0.014362 -0.089397 -v 0.029169 0.014917 -0.089104 -v 0.029237 0.015168 -0.082000 -v 0.029163 0.015948 -0.082000 -v 0.031997 0.014638 -0.089246 -v 0.032620 0.015332 -0.088928 -v 0.032489 0.015886 -0.088754 -v 0.031990 0.016197 -0.088685 -v 0.031735 0.016222 -0.080223 -v 0.031533 0.016176 -0.088689 -v 0.031282 0.016022 -0.080223 -v 0.031048 0.015706 -0.088805 -v 0.042000 0.021807 -0.087678 -v -0.000000 0.022773 -0.087709 -v 0.042000 0.022773 -0.087709 -v 0.042000 0.023722 -0.087894 -v -0.000000 0.024629 -0.088230 -v 0.020316 0.037130 -0.086519 -v 0.022000 0.033736 -0.087754 -v 0.004538 0.034956 -0.087310 -v 0.022286 0.033924 -0.087685 -v 0.035855 0.037571 -0.086358 -v 0.000000 0.042446 -0.084584 -v 0.019714 0.036804 -0.086637 -v 0.021000 0.033484 -0.087845 -v 0.020653 0.033513 -0.087835 -v 0.021347 0.037215 -0.086488 -v 0.042000 0.042446 -0.084584 -v 0.021000 0.037243 -0.086477 -v 0.004500 0.035364 -0.087161 -v 0.022286 0.036804 -0.086637 -v 0.034145 0.037571 -0.086358 -v 0.033750 0.037398 -0.086421 -v 0.033085 0.036874 -0.086612 -v 0.019714 0.033924 -0.087685 -v 0.020000 0.033736 -0.087754 -v 0.032835 0.036538 -0.086734 -v 0.032651 0.036167 -0.086869 -v 0.032651 0.034560 -0.087454 -v 0.022879 0.034721 -0.087395 -v 0.037349 0.036167 -0.086869 -v 0.036915 0.036874 -0.086612 -v 0.008607 0.037163 -0.086506 -v 0.019268 0.036304 -0.086819 -v 0.033750 0.033329 -0.087902 -v 0.034145 0.033156 -0.087965 -v 0.042000 0.028282 -0.089739 -v 0.035000 0.033015 -0.088016 -v 0.036250 0.033329 -0.087902 -v 0.036607 0.033564 -0.087816 -v 0.037165 0.034189 -0.087589 -v 0.037349 0.034560 -0.087454 -v 0.032538 0.034956 -0.087310 -v 0.022996 0.035166 -0.087233 -v 0.032538 0.035772 -0.087013 -v 0.008915 0.033854 -0.087711 -v 0.009349 0.036167 -0.086869 -v 0.009165 0.036538 -0.086734 -v 0.008250 0.037398 -0.086421 -v 0.007855 0.037571 -0.086358 -v 0.037462 0.034956 -0.087310 -v 0.037462 0.035772 -0.087013 -v 0.019121 0.036007 -0.086927 -v 0.006145 0.033156 -0.087965 -v 0.019468 0.034156 -0.087601 -v 0.008607 0.033564 -0.087816 -v -0.000000 0.043749 -0.082934 -v 0.042000 0.044753 -0.080240 -v -0.000000 0.044274 -0.081079 -v -0.000000 0.046081 -0.078843 -v 0.042000 0.046081 -0.078843 -v -0.000000 0.045361 -0.079488 -v -0.000000 0.023722 -0.087894 -v -0.000000 0.021807 -0.087678 -v -0.000000 0.044753 -0.080240 -v -0.000000 0.043937 -0.081985 -v 0.000000 0.037058 -0.082880 -v -0.000000 0.025470 -0.088707 -v -0.000000 0.028282 -0.089739 -v -0.000000 0.043688 -0.083244 -v -0.000000 0.026223 -0.089312 -v -0.000000 0.027348 -0.089844 -v -0.000000 0.042733 -0.084452 -v -0.000000 0.042996 -0.084278 -v -0.000000 0.043229 -0.084064 -v -0.000000 0.043425 -0.083816 -v -0.000000 0.043579 -0.083540 -v 0.042000 0.043579 -0.083540 -v 0.042000 0.043688 -0.083244 -v -0.000000 0.026469 -0.089511 -v -0.000000 0.026743 -0.089668 -v -0.000000 0.027038 -0.089780 -v -0.000000 0.027663 -0.089859 -v -0.000000 0.027977 -0.089823 -v 0.042000 0.027977 -0.089823 -v 0.035434 0.034257 -0.076922 -v 0.036250 0.033978 -0.077024 -v 0.037165 0.033118 -0.077337 -v 0.037462 0.031536 -0.077913 -v 0.037462 0.032352 -0.077616 -v 0.037165 0.030769 -0.078192 -v 0.036250 0.029909 -0.078505 -v 0.034145 0.029736 -0.078568 -v 0.035000 0.029594 -0.078619 -v 0.034566 0.029630 -0.078606 -v 0.035434 0.029630 -0.078606 -v 0.033393 0.030144 -0.078419 -v 0.035000 0.031430 -0.076353 -v 0.032538 0.031536 -0.077913 -v 0.033085 0.033454 -0.077215 -v 0.032651 0.032747 -0.077472 -v 0.032835 0.033118 -0.077337 -v 0.033393 0.033743 -0.077109 -v 0.033750 0.033978 -0.077024 -v 0.034566 0.034257 -0.076922 -v 0.035000 0.034293 -0.076909 -v 0.035000 0.037713 -0.086306 -v 0.035855 0.034151 -0.076961 -v 0.035434 0.037677 -0.086319 -v 0.036250 0.037398 -0.086421 -v 0.036607 0.033743 -0.077109 -v 0.036607 0.037163 -0.086506 -v 0.036915 0.033454 -0.077215 -v 0.037165 0.036538 -0.086734 -v 0.037349 0.032747 -0.077472 -v 0.037500 0.031944 -0.077764 -v 0.037500 0.035364 -0.087161 -v 0.037349 0.031140 -0.078057 -v 0.036915 0.030434 -0.078314 -v 0.036915 0.033854 -0.087711 -v 0.036607 0.030144 -0.078419 -v 0.035855 0.029736 -0.078568 -v 0.035855 0.033156 -0.087965 -v 0.035434 0.033050 -0.088003 -v 0.034566 0.033050 -0.088003 -v 0.033750 0.029909 -0.078505 -v 0.033393 0.033564 -0.087816 -v 0.033085 0.030434 -0.078314 -v 0.033085 0.033854 -0.087711 -v 0.032835 0.034189 -0.087589 -v 0.032835 0.030769 -0.078192 -v 0.032651 0.031140 -0.078057 -v 0.032500 0.031944 -0.077764 -v 0.032538 0.032352 -0.077616 -v 0.032500 0.035364 -0.087161 -v 0.033393 0.037163 -0.086506 -v 0.034145 0.034151 -0.076961 -v 0.034566 0.037677 -0.086319 -v 0.007000 0.034293 -0.076909 -v 0.008607 0.033743 -0.077109 -v 0.008250 0.033978 -0.077024 -v 0.009462 0.031536 -0.077913 -v 0.009500 0.031944 -0.077764 -v 0.008607 0.030144 -0.078419 -v 0.007434 0.029630 -0.078606 -v 0.008250 0.029909 -0.078505 -v 0.005393 0.030144 -0.078419 -v 0.005085 0.030434 -0.078314 -v 0.004835 0.030769 -0.078192 -v 0.004538 0.032352 -0.077616 -v 0.004500 0.031944 -0.077764 -v 0.007000 0.031430 -0.076353 -v 0.007000 0.037713 -0.086306 -v 0.007434 0.034257 -0.076922 -v 0.007434 0.037677 -0.086319 -v 0.007855 0.034151 -0.076961 -v 0.008915 0.033454 -0.077215 -v 0.008915 0.036874 -0.086612 -v 0.009165 0.033118 -0.077337 -v 0.009349 0.032747 -0.077472 -v 0.009462 0.032352 -0.077616 -v 0.009462 0.035772 -0.087013 -v 0.009500 0.035364 -0.087161 -v 0.009349 0.031140 -0.078057 -v 0.009462 0.034956 -0.087310 -v 0.009165 0.030769 -0.078192 -v 0.009349 0.034560 -0.087454 -v 0.008915 0.030434 -0.078314 -v 0.009165 0.034189 -0.087589 -v 0.008250 0.033329 -0.087902 -v 0.007855 0.033156 -0.087965 -v 0.007855 0.029736 -0.078568 -v 0.007434 0.033050 -0.088003 -v 0.007000 0.029594 -0.078619 -v 0.006566 0.029630 -0.078606 -v 0.007000 0.033015 -0.088016 -v 0.006145 0.029736 -0.078568 -v 0.006566 0.033050 -0.088003 -v 0.005750 0.029909 -0.078505 -v 0.005750 0.033329 -0.087902 -v 0.005393 0.033564 -0.087816 -v 0.005085 0.033854 -0.087711 -v 0.004835 0.034189 -0.087589 -v 0.004651 0.034560 -0.087454 -v 0.004651 0.031140 -0.078057 -v 0.004538 0.031536 -0.077913 -v 0.004538 0.035772 -0.087013 -v 0.004651 0.036167 -0.086869 -v 0.004651 0.032747 -0.077472 -v 0.004835 0.033118 -0.077337 -v 0.004835 0.036538 -0.086734 -v 0.005085 0.033454 -0.077215 -v 0.005085 0.036874 -0.086612 -v 0.005393 0.033743 -0.077109 -v 0.005750 0.033978 -0.077024 -v 0.005393 0.037163 -0.086506 -v 0.005750 0.037398 -0.086421 -v 0.006145 0.034151 -0.076961 -v 0.006566 0.034257 -0.076922 -v 0.006145 0.037571 -0.086358 -v 0.006566 0.037677 -0.086319 -v 0.022804 0.032769 -0.077463 -v 0.022948 0.031488 -0.077929 -v 0.021548 0.030130 -0.078424 -v 0.019030 0.031617 -0.077883 -v 0.019468 0.033152 -0.077325 -v 0.021000 0.031533 -0.076635 -v 0.021140 0.033824 -0.077079 -v 0.021684 0.037130 -0.086519 -v 0.021818 0.033666 -0.077137 -v 0.022000 0.036991 -0.086569 -v 0.022396 0.033298 -0.077271 -v 0.022663 0.036419 -0.086777 -v 0.022947 0.035820 -0.086995 -v 0.022996 0.032140 -0.077692 -v 0.022663 0.030888 -0.078148 -v 0.022627 0.034260 -0.087563 -v 0.022177 0.030415 -0.078320 -v 0.021684 0.033598 -0.087804 -v 0.021347 0.033513 -0.087835 -v 0.021000 0.030064 -0.078448 -v 0.020512 0.030115 -0.078429 -v 0.020316 0.033598 -0.087804 -v 0.020000 0.030316 -0.078357 -v 0.019605 0.030588 -0.078257 -v 0.019268 0.034424 -0.087503 -v 0.019052 0.034909 -0.087327 -v 0.019196 0.031117 -0.078064 -v 0.019004 0.035560 -0.087090 -v 0.018998 0.032083 -0.077713 -v 0.019170 0.032716 -0.077482 -v 0.019468 0.036572 -0.086722 -v 0.019821 0.033470 -0.077208 -v 0.020000 0.036991 -0.086569 -v 0.020446 0.033756 -0.077105 -v 0.020653 0.037215 -0.086488 -v 0.027282 -0.016441 -0.088639 -v 0.027624 -0.016612 -0.088610 -v 0.033215 -0.048287 -0.077811 -v 0.042000 -0.051440 -0.077415 -v 0.035001 -0.052999 -0.077586 -v 0.042000 -0.049830 -0.077489 -v 0.002000 -0.029108 0.150941 -v 0.002000 -0.050161 0.146466 -v 0.003548 -0.061879 0.141156 -v 0.000000 -0.062496 0.140681 -v 0.002000 -0.058696 0.143232 -v 0.027500 -0.065864 0.137581 -v 0.014425 -0.065864 0.137581 -v 0.006000 -0.062600 0.140598 -v 0.040000 -0.054552 0.145175 -v 0.006019 -0.089480 -0.015556 -v 0.038000 -0.082218 -0.015556 -v 0.008040 -0.088961 -0.015556 -v 0.004000 -0.082218 -0.015556 -v 0.021000 -0.089000 -0.015556 -v 0.010571 -0.089936 -0.015556 -v 0.024124 -0.090440 -0.015556 -v 0.011899 -0.092035 -0.015557 -v 0.030439 -0.091062 -0.015556 -v 0.041844 -0.092976 -0.002913 -v 0.035915 -0.094607 -0.001442 -v 0.040580 -0.094929 -0.000961 -v 0.040185 -0.095315 0.000016 -v 0.040082 -0.095420 0.000434 -v 0.040021 -0.095488 0.000851 -v 0.007000 -0.095420 0.000434 -v 0.010349 -0.093855 -0.002285 -v 0.019085 -0.094607 -0.001442 -v 0.010139 -0.094293 -0.001841 -v 0.018651 -0.093855 -0.002285 -v 0.018523 -0.093375 -0.002667 -v 0.010475 -0.093383 -0.002661 -v 0.010492 -0.092720 -0.003055 -v 0.010266 -0.091945 -0.003350 -v 0.018498 -0.092795 -0.003020 -v 0.009510 -0.090998 -0.003537 -v 0.019393 -0.091085 -0.003525 -v 0.008838 -0.090635 -0.003556 -v 0.008341 -0.090523 -0.003556 -v 0.022234 -0.095167 -0.000422 -v 0.022612 -0.094911 -0.000951 -v 0.022915 -0.094607 -0.001442 -v 0.031651 -0.093855 -0.002285 -v 0.031523 -0.093375 -0.002668 -v 0.022510 -0.090998 -0.003537 -v 0.022989 -0.091471 -0.003470 -v 0.032769 -0.090819 -0.003549 -v 0.021341 -0.090523 -0.003556 -v 0.032393 -0.091085 -0.003525 -v 0.021838 -0.090635 -0.003556 -v 0.042000 -0.091374 -0.003483 -v 0.036346 -0.092121 -0.003293 -v 0.042000 -0.092200 -0.003267 -v 0.042000 -0.090523 -0.003556 -v 0.034450 -0.090533 -0.003556 -v 0.035510 -0.090998 -0.003533 -v 0.035988 -0.091469 -0.003470 -v 0.011849 -0.150558 0.043193 -v 0.030372 -0.150557 0.043769 -v 0.042000 -0.105086 0.032033 -v 0.042000 -0.081800 0.002312 -v 0.042000 -0.081724 0.001444 -v 0.042000 -0.086724 -0.003556 -v 0.042000 -0.080075 -0.011721 -v 0.042000 -0.084224 -0.002886 -v 0.042000 -0.085856 -0.003480 -v 0.037000 -0.139601 0.037217 -v 0.037000 -0.133420 0.037467 -v 0.037000 -0.130745 0.037131 -v 0.005000 -0.130745 0.037131 -v 0.037000 -0.127281 0.036697 -v 0.005000 -0.127281 0.036697 -v 0.005000 -0.121353 0.034928 -v 0.037000 -0.115795 0.032209 -v 0.005000 -0.113359 0.030469 -v 0.037000 -0.108574 0.026426 -v 0.005000 -0.108574 0.026426 -v 0.037000 -0.106387 0.024239 -v 0.005000 -0.106387 0.024239 -v 0.005000 -0.104531 0.021641 -v 0.005000 -0.102791 0.019205 -v 0.005000 -0.100072 0.013647 -v 0.037000 -0.099102 0.010397 -v 0.005000 -0.097869 0.004255 -v 0.037000 -0.097533 0.001580 -v 0.005000 -0.097678 -0.002007 -v 0.037000 -0.098416 -0.008238 -v 0.042000 -0.065864 0.137581 -v 0.034000 -0.136247 0.062104 -v 0.032750 -0.133066 0.065516 -v 0.034434 -0.136221 0.062132 -v 0.031835 -0.135395 0.063019 -v 0.042000 -0.117492 0.082217 -v 0.035250 -0.133066 0.065516 -v 0.035915 -0.135638 0.062758 -v 0.036165 -0.135395 0.063019 -v 0.035250 -0.136019 0.062349 -v 0.034855 -0.136144 0.062215 -v 0.031651 -0.133959 0.064558 -v 0.036165 -0.133690 0.064847 -v 0.031651 -0.135125 0.063308 -v 0.027500 -0.148944 0.048488 -v 0.031500 -0.134542 0.063933 -v 0.036462 -0.134838 0.063615 -v 0.008000 -0.136247 0.062104 -v 0.007145 -0.136144 0.062215 -v 0.000000 -0.146556 0.051049 -v 0.005835 -0.135395 0.063019 -v 0.005651 -0.135125 0.063308 -v 0.006085 -0.133446 0.065108 -v 0.007566 -0.132863 0.065733 -v 0.007145 -0.132940 0.065651 -v 0.008434 -0.132863 0.065733 -v 0.009250 -0.133066 0.065516 -v 0.009607 -0.133236 0.065333 -v 0.009915 -0.133446 0.065108 -v 0.010165 -0.133690 0.064847 -v 0.010165 -0.135395 0.063019 -v 0.009915 -0.135638 0.062758 -v 0.009607 -0.135848 0.062532 -v 0.014425 -0.148944 0.048488 -v 0.008855 -0.136144 0.062215 -v 0.005500 -0.134542 0.063933 -v 0.005651 -0.133959 0.064558 -v 0.010462 -0.134246 0.064250 -v 0.021434 -0.070067 0.133074 -v 0.022575 -0.074134 0.128712 -v 0.019750 -0.066912 0.136458 -v 0.020145 -0.066786 0.136592 -v 0.020566 -0.066709 0.136675 -v 0.021000 -0.066683 0.136703 -v 0.018425 -0.074134 0.128712 -v 0.019085 -0.069484 0.133699 -v 0.018425 -0.066274 0.137142 -v 0.019085 -0.067292 0.136049 -v 0.018651 -0.067805 0.135499 -v 0.022250 -0.066912 0.136458 -v 0.022608 -0.067082 0.136274 -v 0.027500 -0.066274 0.137142 -v 0.022915 -0.067292 0.136049 -v 0.023349 -0.067805 0.135499 -v 0.023462 -0.068092 0.135192 -v 0.023500 -0.068388 0.134874 -v 0.023349 -0.068971 0.134249 -v 0.020566 -0.132863 0.065733 -v 0.021855 -0.136144 0.062215 -v 0.020566 -0.136221 0.062132 -v 0.019393 -0.135848 0.062532 -v 0.019085 -0.135638 0.062758 -v 0.018425 -0.148944 0.048488 -v 0.018835 -0.135395 0.063019 -v 0.019085 -0.133446 0.065108 -v 0.018835 -0.133690 0.064847 -v 0.022575 -0.148944 0.048488 -v 0.022607 -0.135848 0.062532 -v 0.022250 -0.136019 0.062349 -v 0.023349 -0.135125 0.063308 -v 0.023165 -0.135395 0.063019 -v 0.022915 -0.135638 0.062758 -v 0.021855 -0.132940 0.065651 -v 0.022250 -0.133066 0.065516 -v 0.027500 -0.117492 0.082217 -v 0.023349 -0.133959 0.064558 -v 0.023462 -0.134838 0.063615 -v 0.022250 -0.101919 0.098917 -v 0.022575 -0.094454 0.106923 -v 0.021000 -0.098737 0.102329 -v 0.019750 -0.098966 0.102084 -v 0.020145 -0.098840 0.102219 -v 0.020566 -0.098763 0.102301 -v 0.019750 -0.101919 0.098917 -v 0.019393 -0.101748 0.099100 -v 0.018835 -0.101295 0.099586 -v 0.021434 -0.102121 0.098700 -v 0.021000 -0.102147 0.098672 -v 0.020566 -0.102121 0.098700 -v 0.019393 -0.099136 0.101901 -v 0.018425 -0.094454 0.106923 -v 0.022915 -0.099346 0.101676 -v 0.022575 -0.117492 0.082217 -v 0.023349 -0.099859 0.101126 -v 0.023500 -0.100442 0.100501 -v 0.027500 -0.094454 0.106923 -v 0.034434 -0.098763 0.102301 -v 0.035915 -0.101538 0.099325 -v 0.033145 -0.098840 0.102219 -v 0.033566 -0.102121 0.098700 -v 0.033145 -0.102044 0.098782 -v 0.034855 -0.102044 0.098782 -v 0.034000 -0.102147 0.098672 -v 0.032750 -0.101919 0.098917 -v 0.032085 -0.101538 0.099325 -v 0.031651 -0.101025 0.099875 -v 0.032085 -0.099346 0.101676 -v 0.036462 -0.100146 0.100818 -v 0.036500 -0.100442 0.100501 -v 0.036462 -0.100738 0.100183 -v 0.036165 -0.101295 0.099586 -v 0.034434 -0.070067 0.133074 -v 0.042000 -0.074134 0.128712 -v 0.034000 -0.098737 0.102329 -v 0.033566 -0.098763 0.102301 -v 0.034855 -0.066786 0.136592 -v 0.042000 -0.066274 0.137142 -v 0.035915 -0.067292 0.136049 -v 0.036165 -0.069241 0.133960 -v 0.032750 -0.066912 0.136458 -v 0.034434 -0.066709 0.136675 -v 0.036349 -0.068971 0.134249 -v 0.033145 -0.069990 0.133156 -v 0.032393 -0.069694 0.133474 -v 0.031538 -0.068092 0.135192 -v 0.031651 -0.067805 0.135499 -v 0.032085 -0.067292 0.136049 -v 0.032393 -0.067082 0.136275 -v 0.027500 -0.074134 0.128712 -v 0.031500 -0.068388 0.134874 -v 0.022250 -0.098966 0.102084 -v 0.014425 -0.117492 0.082217 -v 0.010462 -0.134838 0.063615 -v 0.006750 -0.098966 0.102084 -v 0.014425 -0.094454 0.106923 -v 0.008434 -0.098763 0.102301 -v 0.009250 -0.101919 0.098917 -v 0.006750 -0.101919 0.098917 -v 0.006085 -0.101538 0.099325 -v 0.005835 -0.101295 0.099586 -v 0.006393 -0.099136 0.101901 -v 0.010165 -0.101295 0.099586 -v 0.009915 -0.101538 0.099325 -v 0.008000 -0.102147 0.098672 -v 0.000000 -0.117492 0.082217 -v 0.000000 -0.112945 0.087093 -v 0.000000 -0.110789 0.089405 -v 0.010165 -0.099590 0.101415 -v 0.010349 -0.099859 0.101126 -v 0.010462 -0.100146 0.100818 -v 0.018425 -0.117492 0.082217 -v 0.010462 -0.100738 0.100183 -v 0.005538 -0.100738 0.100183 -v 0.014425 -0.084172 0.117948 -v 0.007145 -0.098840 0.102219 -v 0.008000 -0.070093 0.133046 -v 0.000000 -0.074134 0.128712 -v 0.007566 -0.070067 0.133074 -v 0.007145 -0.069990 0.133156 -v 0.010165 -0.069241 0.133960 -v 0.006393 -0.069694 0.133474 -v 0.014425 -0.074134 0.128712 -v 0.009607 -0.067082 0.136275 -v 0.009915 -0.067292 0.136049 -v 0.000000 -0.066274 0.137142 -v 0.010349 -0.067805 0.135499 -v 0.014425 -0.066274 0.137142 -v 0.010462 -0.068092 0.135192 -v 0.005538 -0.068092 0.135192 -v 0.006085 -0.069484 0.133699 -v 0.005538 -0.068684 0.134557 -v 0.005500 -0.068388 0.134874 -v 0.022575 -0.065864 0.137581 -v 0.018425 -0.065864 0.137581 -v 0.042000 -0.029108 0.150941 -v 0.032000 -0.055108 -0.070172 -v 0.032000 -0.053528 -0.072642 -v 0.000000 -0.051604 -0.074854 -v 0.032000 -0.049377 -0.076761 -v 0.000000 -0.049377 -0.076761 -v 0.032000 -0.056702 -0.066421 -v 0.006000 -0.058366 -0.061851 -v 0.000000 -0.069470 -0.031343 -v 0.000000 -0.056310 -0.067498 -v 0.003580 -0.071819 -0.024889 -v 0.002882 -0.071159 -0.026703 -v 0.001715 -0.070380 -0.028841 -v 0.041840 -0.076086 -0.013164 -v 0.034000 -0.070057 -0.029730 -v 0.034000 -0.058366 -0.061851 -v 0.040000 -0.095521 0.001281 -v 0.007000 -0.095521 0.001281 -v 0.040000 -0.095757 0.004499 -v 0.007000 -0.096198 0.007107 -v 0.040000 -0.097060 0.010990 -v 0.040000 -0.097737 0.012757 -v 0.007000 -0.098458 0.014997 -v 0.040000 -0.099428 0.017173 -v 0.007000 -0.099987 0.018172 -v 0.007000 -0.100497 0.019229 -v 0.007000 -0.103023 0.023189 -v 0.040000 -0.103023 0.023189 -v 0.007000 -0.103021 0.029064 -v 0.040609 -0.103915 0.025345 -v 0.040274 -0.103732 0.024583 -v 0.007000 -0.103430 0.028396 -v 0.042000 -0.103411 0.028432 -v 0.041426 -0.103914 0.026909 -v 0.041293 -0.103964 0.026473 -v 0.007000 -0.102511 0.029660 -v 0.040162 -0.099477 0.032596 -v 0.040016 -0.099960 0.032205 -v 0.007000 -0.098758 0.033022 -v 0.007000 -0.099477 0.032596 -v 0.041599 -0.097798 0.033364 -v 0.007000 -0.092231 0.030990 -v 0.042000 -0.092231 0.030990 -v 0.042000 -0.092703 0.031679 -v 0.007000 -0.093954 0.032777 -v 0.042000 -0.093954 0.032777 -v 0.042000 -0.095497 0.033403 -v 0.042000 -0.096325 0.033515 -v 0.007000 -0.096325 0.033515 -v 0.042000 -0.081800 0.000575 -v 0.042000 -0.082025 -0.000266 -v 0.042000 -0.082394 -0.001056 -v 0.042000 -0.082894 -0.001770 -v 0.007000 -0.082394 -0.001056 -v 0.042000 -0.083510 -0.002387 -v 0.007000 -0.084224 -0.002886 -v 0.042000 -0.085014 -0.003255 -v 0.007000 -0.085014 -0.003255 -v 0.007000 -0.086724 -0.003556 -v 0.002000 -0.096129 0.021663 -v 0.002000 -0.093832 0.016895 -v 0.002000 -0.091009 0.006714 -v 0.002000 -0.096590 0.090072 -v 0.042000 -0.096039 0.089466 -v 0.002000 -0.095593 0.088778 -v 0.002000 -0.095267 0.088026 -v 0.042000 -0.095067 0.087231 -v 0.002000 -0.095067 0.087231 -v 0.002000 -0.095000 0.056899 -v 0.042000 -0.095000 0.078062 -v 0.042000 -0.095000 0.056899 -v 0.002000 -0.095076 0.056031 -v 0.042000 -0.095302 0.055189 -v 0.002000 -0.095302 0.055189 -v 0.042000 -0.096170 0.053686 -v 0.002000 -0.096170 0.053686 -v 0.002000 -0.096786 0.053069 -v 0.042000 -0.097500 0.052569 -v 0.042000 -0.098290 0.052201 -v 0.042000 -0.099132 0.051975 -v 0.002000 -0.099132 0.051975 -v 0.002000 -0.100000 0.051899 -v 0.042000 -0.100000 0.051899 -v 0.042000 -0.112337 0.051899 -v 0.042000 -0.113085 0.051956 -v 0.042000 -0.113816 0.052123 -v 0.002000 -0.113816 0.052123 -v 0.002000 -0.114513 0.052398 -v 0.042000 -0.115162 0.052774 -v 0.002000 -0.115747 0.053243 -v 0.042000 -0.125281 0.062134 -v 0.042000 -0.125865 0.062781 -v 0.002000 -0.125865 0.062781 -v 0.002000 -0.126326 0.063520 -v 0.002000 -0.126653 0.064329 -v 0.002000 -0.126834 0.065181 -v 0.002000 -0.126864 0.066052 -v 0.042000 -0.126474 0.067744 -v 0.002000 -0.126743 0.066915 -v 0.002000 -0.126474 0.067744 -v 0.042000 -0.125528 0.069200 -v 0.042000 -0.105068 0.091141 -v 0.002000 -0.104420 0.091724 -v 0.002000 -0.103681 0.092186 -v 0.042000 -0.102873 0.092513 -v 0.042000 -0.102021 0.092694 -v 0.002000 -0.102873 0.092513 -v 0.002000 -0.102021 0.092694 -v 0.002000 -0.101150 0.092724 -v 0.042000 -0.100287 0.092603 -v 0.042000 -0.098688 0.091924 -v 0.002000 -0.098688 0.091924 -v 0.042000 -0.096590 0.090072 -v 0.002000 -0.098001 0.091388 -v 0.002000 -0.095670 0.054399 -v 0.002000 -0.125281 0.062134 -v 0.002000 -0.115162 0.052774 -v 0.002000 -0.113085 0.051956 -v 0.002000 -0.098290 0.052201 -v 0.002000 -0.097500 0.052569 -v 0.002000 -0.112337 0.051899 -v 0.002000 -0.095000 0.086415 -v 0.002000 -0.096039 0.089466 -v 0.002000 -0.126065 0.068514 -v 0.002000 -0.125528 0.069200 -v 0.002000 -0.105068 0.091141 -v 0.002000 -0.099458 0.092334 -v 0.002000 -0.100287 0.092603 -v 0.042000 -0.138480 0.045768 -v 0.007000 -0.138255 0.046610 -v 0.042000 -0.137886 0.047399 -v 0.007000 -0.137886 0.047399 -v 0.042000 -0.137387 0.048113 -v 0.042000 -0.136770 0.048730 -v 0.042000 -0.135266 0.049598 -v 0.007000 -0.134425 0.049824 -v 0.042000 -0.134425 0.049824 -v 0.042000 -0.133556 0.049899 -v 0.007000 -0.133556 0.049899 -v 0.042000 -0.099162 0.049829 -v 0.042000 -0.098349 0.049619 -v 0.007000 -0.098349 0.049619 -v 0.042000 -0.097581 0.049276 -v 0.007000 -0.097581 0.049276 -v 0.042000 -0.095381 0.046813 -v 0.007000 -0.095766 0.047560 -v 0.007000 -0.095125 0.046012 -v 0.042000 -0.095031 0.044340 -v 0.007000 -0.095008 0.045180 -v 0.007000 -0.095031 0.044340 -v 0.007000 -0.095495 0.042730 -v 0.042000 -0.096464 0.041364 -v 0.007000 -0.095922 0.042006 -v 0.040862 -0.105324 0.032504 -v 0.007000 -0.105340 0.032489 -v 0.040000 -0.102495 0.035333 -v 0.007000 -0.096464 0.041364 -v 0.041042 -0.105462 0.032376 -v 0.007000 -0.105936 0.031979 -v 0.042000 -0.106568 0.031589 -v 0.007000 -0.106604 0.031570 -v 0.007000 -0.108091 0.031086 -v 0.041426 -0.108091 0.031086 -v 0.007000 -0.109655 0.031085 -v 0.040609 -0.109655 0.031085 -v 0.040429 -0.110033 0.031160 -v 0.007000 -0.111142 0.031567 -v 0.040156 -0.110783 0.031402 -v 0.040000 -0.116846 0.034992 -v 0.007000 -0.115771 0.034503 -v 0.040000 -0.117827 0.035572 -v 0.007000 -0.116828 0.035013 -v 0.007000 -0.120003 0.036542 -v 0.040000 -0.122243 0.037263 -v 0.007000 -0.122225 0.037303 -v 0.007000 -0.124447 0.038064 -v 0.040000 -0.127908 0.038723 -v 0.007000 -0.127893 0.038802 -v 0.007000 -0.129041 0.039048 -v 0.007000 -0.133719 0.039479 -v 0.040000 -0.130501 0.039243 -v 0.040000 -0.133719 0.039479 -v 0.040082 -0.134566 0.039580 -v 0.033625 -0.138556 0.044474 -v 0.021788 -0.138556 0.044378 -v 0.032490 -0.138537 0.044002 -v 0.031734 -0.138350 0.043055 -v 0.022902 -0.138483 0.043623 -v 0.031508 -0.138055 0.042281 -v 0.023477 -0.137668 0.041625 -v 0.022715 -0.136104 0.040178 -v 0.032388 -0.135951 0.040089 -v 0.018651 -0.137285 0.041145 -v 0.019388 -0.135951 0.040089 -v 0.010163 -0.136882 0.040746 -v 0.010349 -0.137285 0.041145 -v 0.010341 -0.138302 0.042893 -v 0.018734 -0.138350 0.043055 -v 0.020143 -0.138556 0.044357 -v 0.009607 -0.138525 0.043915 -v 0.009231 -0.138549 0.044181 -v 0.007000 -0.134566 0.039580 -v 0.040265 -0.135249 0.039765 -v 0.040739 -0.136210 0.040222 -v 0.035790 -0.136234 0.040243 -v 0.041999 -0.138139 0.042399 -v 0.036344 -0.138291 0.042880 -v 0.042000 -0.138483 0.043626 -v 0.042000 -0.138556 0.044477 -v 0.007000 -0.138556 0.044899 -v 0.021369 -0.138556 0.044475 -v 0.002000 -0.118105 0.041168 -v 0.024893 -0.093602 -0.015479 -v 0.004000 -0.096202 -0.014327 -v 0.008627 -0.095929 -0.014523 -v 0.038000 -0.096202 -0.014327 -v 0.033764 -0.095951 -0.014506 -v 0.011096 -0.094820 -0.015123 -v 0.017695 -0.094630 -0.015203 -v 0.011893 -0.093602 -0.015479 -v 0.004428 -0.094319 -0.015313 -v 0.004000 -0.094483 -0.015241 -v 0.037599 -0.098556 -0.009837 -v 0.004120 -0.098530 -0.010181 -v 0.004985 -0.098467 -0.008487 -v 0.037222 -0.098552 -0.009205 -v 0.004906 -0.098520 -0.008855 -v 0.037356 -0.098562 -0.009467 -v 0.004000 -0.098515 -0.010312 -v 0.004000 -0.098350 -0.011141 -v 0.038000 -0.098350 -0.011141 -v 0.004000 -0.098016 -0.012059 -v 0.004000 -0.097538 -0.012910 -v 0.038000 -0.097538 -0.012910 -v 0.004000 -0.096928 -0.013673 -v 0.038000 -0.095380 -0.014854 -v 0.037745 -0.093973 -0.015394 -v 0.038000 -0.093536 -0.015477 -v 0.038000 -0.092563 -0.015556 -v 0.002388 -0.148944 0.048488 -v 0.005706 -0.150504 0.045248 -v 0.003732 -0.150288 0.046171 -v 0.022324 -0.150427 0.045637 -v 0.031652 -0.150506 0.045212 -v 0.021000 -0.150383 0.045827 -v 0.021667 -0.150395 0.045780 -v 0.010961 -0.150554 0.044721 -v 0.004182 -0.150737 0.043819 -v 0.003402 -0.149958 0.047008 -v 0.038418 -0.150139 0.046595 -v 0.038598 -0.149958 0.047008 -v 0.004644 -0.144467 0.036438 -v 0.037000 -0.143238 0.036584 -v 0.037015 -0.143487 0.036533 -v 0.004778 -0.144205 0.036448 -v 0.037094 -0.143854 0.036480 -v 0.037880 -0.145181 0.036470 -v 0.004000 -0.145312 0.036485 -v 0.038000 -0.146141 0.036650 -v 0.038000 -0.147910 0.037462 -v 0.038000 -0.148673 0.038072 -v 0.004000 -0.148673 0.038072 -v 0.038000 -0.149854 0.039620 -v 0.004000 -0.149327 0.038798 -v 0.004691 -0.150203 0.040380 -v 0.004055 -0.150532 0.041459 -v 0.038000 -0.080484 -0.015722 -v 0.038000 -0.079193 -0.016025 -v 0.004000 -0.078932 -0.016112 -v 0.038000 -0.078806 -0.016181 -v 0.004000 -0.077404 -0.016791 -v 0.038000 -0.076452 -0.017386 -v 0.004000 -0.077226 -0.016909 -v 0.038000 -0.075808 -0.017918 -v 0.038000 -0.075269 -0.018364 -v 0.004000 -0.074791 -0.018860 -v 0.038000 -0.074251 -0.019512 -v 0.004000 -0.074576 -0.019143 -v 0.004000 -0.073779 -0.020191 -v 0.038000 -0.073572 -0.020566 -v 0.004000 -0.073581 -0.020569 -v 0.038000 -0.073420 -0.020803 -v 0.004000 -0.073003 -0.021672 -v 0.004064 -0.102280 0.028569 -v 0.002938 -0.098193 0.031066 -v 0.002175 -0.097238 0.029803 -v 0.002331 -0.095610 0.030210 -v 0.004184 -0.099236 0.031735 -v 0.003113 -0.096013 0.031747 -v 0.004823 -0.097924 0.032931 -v 0.005776 -0.099454 0.032517 -v 0.004200 -0.096391 0.032714 -v 0.005290 -0.092164 0.030128 -v 0.004759 -0.093148 0.031478 -v 0.004500 -0.092510 0.030002 -v 0.003786 -0.092980 0.029831 -v 0.003266 -0.094043 0.030851 -v 0.003170 -0.093559 0.029620 -v 0.002670 -0.094230 0.029376 -v 0.002302 -0.094972 0.029106 -v 0.007000 -0.100115 0.032057 -v 0.007000 -0.097978 0.033321 -v 0.005807 -0.096224 0.033421 -v 0.007000 -0.097160 0.033487 -v 0.007000 -0.095497 0.033403 -v 0.007000 -0.094699 0.033154 -v 0.005315 -0.094400 0.032770 -v 0.007000 -0.093283 0.032280 -v 0.007000 -0.092703 0.031679 -v 0.005802 -0.092705 0.031540 -v 0.002302 -0.100360 0.025121 -v 0.002075 -0.100070 0.026242 -v 0.002665 -0.101621 0.025663 -v 0.003154 -0.101696 0.027915 -v 0.003784 -0.102473 0.024503 -v 0.004178 -0.103214 0.026234 -v 0.002424 -0.100721 0.027287 -v 0.002000 -0.098976 0.026125 -v 0.004499 -0.102790 0.024068 -v 0.005631 -0.102379 0.029548 -v 0.005712 -0.103118 0.028676 -v 0.005713 -0.103704 0.027273 -v 0.005708 -0.103807 0.025378 -v 0.005289 -0.103119 0.023900 -v 0.007000 -0.103731 0.027671 -v 0.007000 -0.103914 0.026909 -v 0.007000 -0.103976 0.026127 -v 0.007000 -0.103915 0.025345 -v 0.007000 -0.103732 0.024583 -v 0.007000 -0.103433 0.023858 -v 0.007000 -0.082025 0.003154 -v 0.006132 -0.082097 0.003128 -v 0.007000 -0.091881 0.030231 -v 0.006132 -0.091952 0.030205 -v 0.005290 -0.082309 0.003051 -v 0.004500 -0.082655 0.002925 -v 0.003786 -0.083125 0.002754 -v 0.003170 -0.083704 0.002543 -v 0.002302 -0.085117 0.002029 -v 0.002076 -0.095763 0.028818 -v 0.002000 -0.096579 0.028521 -v 0.007000 -0.095952 0.005959 -v 0.006132 -0.096863 0.010573 -v 0.007000 -0.097697 0.012775 -v 0.007000 -0.096936 0.010553 -v 0.006132 -0.100430 0.019266 -v 0.006131 -0.103318 0.023794 -v 0.004500 -0.099911 0.019555 -v 0.003786 -0.099475 0.019799 -v 0.003170 -0.101709 0.024453 -v 0.002670 -0.098313 0.020446 -v 0.002076 -0.096887 0.021241 -v 0.005290 -0.098179 0.015112 -v 0.005290 -0.100233 0.019376 -v 0.004500 -0.097838 0.015251 -v 0.003170 -0.098936 0.020099 -v 0.002302 -0.095414 0.016246 -v 0.002076 -0.094635 0.016566 -v 0.002302 -0.097623 0.020831 -v 0.006132 -0.098387 0.015026 -v 0.003786 -0.097376 0.015441 -v 0.003170 -0.096805 0.015675 -v 0.002670 -0.094527 0.011221 -v 0.002670 -0.096145 0.015946 -v 0.002076 -0.092954 0.011657 -v 0.002000 -0.092117 0.011889 -v 0.006132 -0.095877 0.005971 -v 0.005290 -0.095654 0.006005 -v 0.005290 -0.096645 0.010633 -v 0.004500 -0.096290 0.010732 -v 0.003786 -0.095808 0.010865 -v 0.003170 -0.095215 0.011030 -v 0.002670 -0.093481 0.006336 -v 0.002076 -0.091868 0.006583 -v 0.002302 -0.093765 0.011432 -v 0.005343 -0.095137 0.000238 -v 0.004498 -0.094767 0.000427 -v 0.004500 -0.095290 0.006060 -v 0.003784 -0.094279 0.000557 -v 0.003786 -0.094796 0.006136 -v 0.003169 -0.093676 0.000711 -v 0.003170 -0.094186 0.006229 -v 0.002302 -0.092233 0.001388 -v 0.002302 -0.092700 0.006456 -v 0.002000 -0.086724 0.001444 -v 0.002076 -0.085908 0.001741 -v 0.002904 -0.084785 -0.000763 -v 0.002681 -0.084080 0.001229 -v 0.002670 -0.084375 0.002299 -v 0.004153 -0.082590 0.001780 -v 0.004119 -0.084026 -0.001697 -v 0.005710 -0.081873 0.001853 -v 0.005711 -0.082025 0.000171 -v 0.005700 -0.082983 -0.001715 -v 0.006117 -0.086240 -0.003474 -v 0.004816 -0.086285 -0.003071 -v 0.002132 -0.086095 0.000232 -v 0.007000 -0.081800 0.002312 -v 0.007000 -0.081724 0.001444 -v 0.007000 -0.081800 0.000575 -v 0.007000 -0.082025 -0.000266 -v 0.007000 -0.082894 -0.001770 -v 0.007000 -0.083510 -0.002387 -v 0.005317 -0.084724 -0.002894 -v 0.007000 -0.085856 -0.003480 -v 0.003876 -0.083045 -0.000144 -v 0.005500 -0.093000 -0.002633 -v 0.003791 -0.091159 -0.002387 -v 0.004539 -0.091260 -0.002901 -v 0.005290 -0.090523 -0.003255 -v 0.002000 -0.090523 0.001444 -v 0.003276 -0.092703 -0.001210 -v 0.004538 -0.092979 -0.002170 -v 0.004485 -0.094181 -0.000985 -v 0.002074 -0.091305 0.000587 -v 0.002669 -0.092961 0.000727 -v 0.006134 -0.095380 0.000587 -v 0.006151 -0.091306 -0.003480 -v 0.003768 -0.086102 -0.002367 -v 0.002927 -0.091103 -0.001484 -v 0.002844 -0.086180 -0.001365 -v 0.002315 -0.091455 -0.000291 -v 0.003786 -0.106167 0.033316 -v 0.002077 -0.108752 0.034915 -v 0.002000 -0.108875 0.036024 -v 0.002302 -0.107666 0.034815 -v 0.003170 -0.106603 0.033752 -v 0.002670 -0.107107 0.034256 -v 0.003232 -0.107747 0.032827 -v 0.003785 -0.110518 0.032539 -v 0.004494 -0.106269 0.032511 -v 0.003170 -0.110547 0.033290 -v 0.002686 -0.109390 0.033367 -v 0.005710 -0.106346 0.031869 -v 0.004499 -0.110722 0.032078 -v 0.004492 -0.108472 0.031608 -v 0.005716 -0.110017 0.031294 -v 0.005290 -0.105553 0.032702 -v 0.007000 -0.111811 0.031977 -v 0.007000 -0.110417 0.031268 -v 0.007000 -0.108873 0.031024 -v 0.005832 -0.108217 0.031150 -v 0.007000 -0.107329 0.031269 -v 0.006132 -0.105393 0.032542 -v 0.002670 -0.100000 0.047399 -v 0.002302 -0.100000 0.046610 -v 0.002219 -0.098869 0.046266 -v 0.003759 -0.098232 0.048398 -v 0.002000 -0.100000 0.044899 -v 0.004500 -0.100000 0.049230 -v 0.004887 -0.095515 0.045900 -v 0.006106 -0.095407 0.046785 -v 0.006132 -0.096518 0.041418 -v 0.005290 -0.096678 0.041577 -v 0.004500 -0.096938 0.041838 -v 0.003786 -0.097292 0.042191 -v 0.003170 -0.097727 0.042627 -v 0.002670 -0.098232 0.043132 -v 0.002305 -0.098183 0.044286 -v 0.002076 -0.099386 0.044286 -v 0.007000 -0.099162 0.049829 -v 0.006132 -0.100000 0.049824 -v 0.005316 -0.098785 0.049518 -v 0.007000 -0.096883 0.048809 -v 0.007000 -0.096272 0.048231 -v 0.005560 -0.096737 0.048527 -v 0.007000 -0.095381 0.046813 -v 0.007000 -0.095195 0.043515 -v 0.002956 -0.097373 0.046445 -v 0.005410 -0.095219 0.044229 -v 0.003434 -0.096524 0.043845 -v 0.003995 -0.096434 0.046886 -v 0.005317 -0.095900 0.042451 -v 0.006133 -0.111208 0.031682 -v 0.006132 -0.124427 0.038137 -v 0.006132 -0.115734 0.034570 -v 0.006132 -0.129029 0.039123 -v 0.005290 -0.128995 0.039346 -v 0.004500 -0.128940 0.039710 -v 0.003786 -0.128864 0.040204 -v 0.002302 -0.128544 0.042300 -v 0.002300 -0.134305 0.042837 -v 0.002076 -0.128417 0.043132 -v 0.002000 -0.128286 0.043991 -v 0.004500 -0.124268 0.038710 -v 0.003170 -0.123970 0.039785 -v 0.003170 -0.128771 0.040813 -v 0.002670 -0.128664 0.041519 -v 0.002000 -0.123111 0.042883 -v 0.005290 -0.119888 0.036821 -v 0.005290 -0.124367 0.038355 -v 0.003786 -0.124135 0.039192 -v 0.002670 -0.119054 0.038855 -v 0.002670 -0.123779 0.040473 -v 0.002302 -0.123568 0.041235 -v 0.002302 -0.118754 0.039586 -v 0.002076 -0.118434 0.040365 -v 0.002076 -0.123343 0.042046 -v 0.005290 -0.115624 0.034767 -v 0.006132 -0.119974 0.036613 -v 0.004500 -0.115445 0.035089 -v 0.004500 -0.119749 0.037162 -v 0.003786 -0.119559 0.037624 -v 0.003170 -0.114901 0.036064 -v 0.003170 -0.119325 0.038195 -v 0.002302 -0.114169 0.037377 -v 0.002076 -0.113759 0.038113 -v 0.005291 -0.111103 0.031883 -v 0.003786 -0.115201 0.035525 -v 0.002670 -0.114554 0.036687 -v 0.002302 -0.109469 0.034380 -v 0.002000 -0.113337 0.038871 -v 0.007000 -0.100000 0.049899 -v 0.006132 -0.133556 0.049824 -v 0.005290 -0.100000 0.049598 -v 0.004500 -0.133556 0.049230 -v 0.003786 -0.100000 0.048730 -v 0.003170 -0.100000 0.048113 -v 0.002670 -0.133556 0.047399 -v 0.002076 -0.100000 0.045768 -v 0.002302 -0.133556 0.046610 -v 0.005651 -0.137032 0.041145 -v 0.003097 -0.136723 0.043781 -v 0.005834 -0.136675 0.040752 -v 0.004619 -0.136688 0.041365 -v 0.005500 -0.137633 0.042000 -v 0.003899 -0.137059 0.042465 -v 0.006393 -0.135868 0.040085 -v 0.002678 -0.134742 0.042071 -v 0.003170 -0.134090 0.041304 -v 0.004498 -0.134306 0.040207 -v 0.006129 -0.134415 0.039621 -v 0.002062 -0.134485 0.043776 -v 0.003833 -0.134887 0.040724 -v 0.005260 -0.134896 0.039908 -v 0.002000 -0.133556 0.044899 -v 0.002142 -0.134416 0.045975 -v 0.002759 -0.136275 0.045383 -v 0.004107 -0.137326 0.046702 -v 0.003786 -0.133556 0.048730 -v 0.003170 -0.133556 0.048113 -v 0.002864 -0.135209 0.047371 -v 0.002076 -0.133556 0.045768 -v 0.005290 -0.133556 0.049598 -v 0.004106 -0.135285 0.048703 -v 0.005711 -0.134804 0.049606 -v 0.005712 -0.136339 0.048895 -v 0.005712 -0.137538 0.047702 -v 0.005716 -0.138257 0.046169 -v 0.007000 -0.135266 0.049598 -v 0.007000 -0.136056 0.049230 -v 0.007000 -0.136770 0.048730 -v 0.007000 -0.137387 0.048113 -v 0.007000 -0.138480 0.045768 -v 0.006720 -0.138600 0.044163 -v 0.004577 -0.138001 0.044397 -v 0.038467 -0.073878 -0.019230 -v 0.038000 -0.072821 -0.022136 -v 0.042000 -0.077983 -0.012212 -v 0.038000 -0.077770 -0.016600 -v 0.038000 -0.077232 -0.016921 -v 0.040177 -0.075197 -0.015608 -v 0.039125 -0.074488 -0.017555 -v 0.038000 -0.074576 -0.019146 -v 0.038000 -0.080687 -0.015674 -v 0.042000 -0.082218 -0.011556 -v 0.039612 -0.148944 0.048488 -v 0.039049 -0.149507 0.047786 -v 0.038268 -0.150288 0.046171 -v 0.042000 -0.146556 0.042437 -v 0.037817 -0.150738 0.043820 -v 0.038419 -0.098173 -0.009745 -v 0.038000 -0.098016 -0.012059 -v 0.038000 -0.096928 -0.013673 -v 0.041816 -0.094387 -0.010816 -v 0.038000 -0.094483 -0.015241 -v 0.042000 -0.093379 -0.011395 -v 0.042000 -0.092563 -0.011556 -v 0.041772 -0.145836 0.040578 -v 0.038000 -0.147059 0.036984 -v 0.038000 -0.145312 0.036485 -v 0.042000 -0.146415 0.041662 -v 0.038000 -0.149327 0.038798 -v 0.038000 -0.150241 0.040517 -v 0.037948 -0.150528 0.041451 -v 0.040021 -0.134148 0.039512 -v 0.041293 -0.108527 0.031036 -v 0.041060 -0.108873 0.031024 -v 0.040274 -0.110417 0.031268 -v 0.040018 -0.111481 0.031757 -v 0.038707 -0.112876 0.031150 -v 0.040069 -0.111142 0.031567 -v 0.040000 -0.111811 0.031977 -v 0.040000 -0.112127 0.032204 -v 0.038707 -0.115502 0.032701 -v 0.038707 -0.118389 0.034407 -v 0.038707 -0.121143 0.035462 -v 0.040000 -0.124010 0.037940 -v 0.038707 -0.130649 0.037959 -v 0.038707 -0.133394 0.038042 -v 0.040018 -0.103243 0.023519 -v 0.040069 -0.103433 0.023858 -v 0.040156 -0.103598 0.024217 -v 0.040428 -0.103840 0.024966 -v 0.038707 -0.105950 0.024609 -v 0.041060 -0.103976 0.026127 -v 0.038707 -0.107983 0.027017 -v 0.038707 -0.096848 -0.002050 -v 0.038707 -0.096958 0.001606 -v 0.040000 -0.096277 0.007092 -v 0.038707 -0.098302 0.010630 -v 0.038707 -0.099538 0.013857 -v 0.038707 -0.102299 0.019498 -v 0.040000 -0.100008 0.018154 -v 0.040000 -0.102796 0.022873 -v 0.038706 -0.143839 0.037210 -v 0.041293 -0.141240 0.040173 -v 0.041295 -0.136912 0.040774 -v 0.038707 -0.137050 0.038152 -v 0.041310 -0.095277 -0.009613 -v 0.041293 -0.094827 -0.006240 -v 0.041293 -0.094228 -0.001911 -v 0.004000 -0.072821 -0.022136 -v 0.003931 -0.072417 -0.023246 -v 0.000000 -0.068727 -0.029300 -v 0.000000 -0.070403 -0.018045 -v 0.004000 -0.075803 -0.017910 -v 0.004000 -0.076011 -0.017716 -v 0.000000 -0.082218 -0.011556 -v 0.004000 -0.080555 -0.015696 -v 0.004000 -0.078802 -0.016169 -v 0.004000 -0.095380 -0.014854 -v 0.004000 -0.093536 -0.015477 -v 0.000000 -0.092563 -0.011556 -v 0.003293 -0.097726 -0.008394 -v 0.000707 -0.094588 -0.004513 -v 0.003293 -0.096848 -0.002050 -v 0.003293 -0.097041 0.004351 -v 0.003293 -0.097741 0.007838 -v 0.000707 -0.098257 0.017718 -v 0.003293 -0.099538 0.013857 -v 0.003293 -0.100593 0.016611 -v 0.000707 -0.101732 0.023606 -v 0.003293 -0.103850 0.022124 -v 0.003293 -0.105950 0.024609 -v 0.000707 -0.117265 0.036736 -v 0.000707 -0.120003 0.037785 -v 0.000707 -0.123650 0.039182 -v 0.003293 -0.121143 0.035462 -v 0.000707 -0.126333 0.039721 -v 0.003293 -0.127162 0.037259 -v 0.000707 -0.130354 0.040527 -v 0.000707 -0.132895 0.040604 -v 0.003293 -0.130649 0.037959 -v 0.003293 -0.133394 0.038042 -v 0.003293 -0.137050 0.038152 -v 0.004000 -0.146141 0.036650 -v 0.004000 -0.147059 0.036984 -v 0.004000 -0.147910 0.037462 -v 0.000112 -0.145787 0.040678 -v 0.004000 -0.149854 0.039620 -v 0.004000 -0.150241 0.040517 -v 0.000000 -0.146556 0.042437 -v 0.003583 -0.150139 0.046595 -v 0.002951 -0.149507 0.047786 -v 0.041297 -0.144622 0.039710 -v 0.042000 -0.141521 0.041997 -v 0.041540 -0.137433 0.041318 -v 0.041691 -0.103731 0.027671 -v 0.041985 -0.106606 0.031573 -v 0.041293 -0.106155 0.028845 -v 0.041691 -0.107329 0.031269 -v 0.000365 -0.094695 -0.010591 -v 0.000017 -0.093988 -0.010986 -v 0.000705 -0.144617 0.039707 -v 0.000707 -0.139513 0.040412 -v 0.000000 -0.143879 0.041452 -v 0.000705 -0.095293 -0.009619 -v 0.000707 -0.094266 -0.002189 -v 0.000000 -0.092557 0.002198 -v 0.000707 -0.094472 0.004632 -v 0.000000 -0.093476 0.009058 -v 0.000707 -0.095813 0.011332 -v 0.000000 -0.098566 0.021881 -v 0.000000 -0.107495 0.032399 -v 0.000707 -0.104012 0.026308 -v 0.000707 -0.106155 0.028845 -v 0.000707 -0.108692 0.030988 -v 0.000707 -0.111378 0.033258 -v 0.000000 -0.113119 0.036434 -v 0.000707 -0.114070 0.034848 -v 0.000000 -0.119323 0.039503 -v 0.000000 -0.132802 0.042443 -v 0.000000 -0.139721 0.042237 -v 0.000707 -0.137189 0.040734 -v 0.004882 -0.143941 0.036469 -v 0.003804 -0.145044 0.036646 -v 0.004401 -0.144837 0.036444 -v 0.004711 -0.098557 -0.009336 -v 0.004485 -0.098560 -0.009718 -v 0.003792 -0.098343 -0.010019 -v 0.004970 -0.143577 0.036518 -v 0.005000 -0.143238 0.036584 -v 0.003299 -0.143771 0.037213 -v 0.003293 -0.139670 0.037789 -v 0.005000 -0.139601 0.037217 -v 0.005000 -0.137007 0.037322 -v 0.005000 -0.133420 0.037467 -v 0.005000 -0.124602 0.035898 -v 0.003293 -0.124370 0.036698 -v 0.005000 -0.118753 0.033656 -v 0.003293 -0.118389 0.034407 -v 0.005000 -0.115795 0.032209 -v 0.003293 -0.115502 0.032701 -v 0.005000 -0.110761 0.028613 -v 0.003293 -0.112876 0.031150 -v 0.003293 -0.110391 0.029050 -v 0.003293 -0.107983 0.027017 -v 0.003293 -0.102299 0.019498 -v 0.005000 -0.101344 0.016247 -v 0.005000 -0.099102 0.010397 -v 0.005000 -0.098303 0.007719 -v 0.003293 -0.098302 0.010630 -v 0.005000 -0.097533 0.001580 -v 0.003293 -0.096958 0.001606 -v 0.005000 -0.097783 -0.004601 -v 0.003293 -0.097211 -0.004670 -v 0.005000 -0.098416 -0.008238 -v 0.042000 -0.092613 -0.003099 -v 0.041540 -0.093682 -0.002433 -v 0.042000 -0.093003 -0.006521 -v 0.037118 -0.098531 -0.008941 -v 0.038000 -0.098515 -0.010312 -v 0.037296 -0.144357 0.036440 -v 0.037515 -0.144718 0.036440 -v 0.038208 -0.145019 0.036657 -v 0.037030 -0.098482 -0.008577 -v 0.038707 -0.097726 -0.008394 -v 0.037000 -0.097783 -0.004601 -v 0.038707 -0.097211 -0.004670 -v 0.037000 -0.097678 -0.002007 -v 0.037000 -0.097869 0.004255 -v 0.038707 -0.097041 0.004351 -v 0.038707 -0.097741 0.007838 -v 0.037000 -0.098303 0.007719 -v 0.037000 -0.100072 0.013647 -v 0.037000 -0.101344 0.016247 -v 0.038707 -0.100593 0.016611 -v 0.037000 -0.102791 0.019204 -v 0.038707 -0.103850 0.022124 -v 0.037000 -0.104531 0.021641 -v 0.037000 -0.110761 0.028613 -v 0.038707 -0.110391 0.029050 -v 0.037000 -0.113359 0.030469 -v 0.037000 -0.118753 0.033656 -v 0.037000 -0.121353 0.034928 -v 0.037000 -0.124602 0.035898 -v 0.038707 -0.124370 0.036698 -v 0.038707 -0.127162 0.037259 -v 0.037000 -0.137007 0.037322 -v 0.038707 -0.139670 0.037789 -v 0.022245 -0.135446 0.039840 -v 0.022915 -0.136442 0.040393 -v 0.023163 -0.136882 0.040746 -v 0.023349 -0.149056 0.041145 -v 0.023349 -0.137285 0.041145 -v 0.023462 -0.149056 0.042434 -v 0.023502 -0.138020 0.042205 -v 0.023136 -0.138419 0.043307 -v 0.023349 -0.149056 0.042855 -v 0.023341 -0.138302 0.042893 -v 0.022250 -0.149056 0.044165 -v 0.022231 -0.138549 0.044181 -v 0.022607 -0.149056 0.043915 -v 0.022607 -0.138525 0.043915 -v 0.022915 -0.149056 0.043607 -v 0.021855 -0.149056 0.044349 -v 0.021000 -0.149056 0.044500 -v 0.021000 -0.138556 0.044500 -v 0.021434 -0.149056 0.044462 -v 0.020566 -0.149056 0.044462 -v 0.020625 -0.138556 0.044474 -v 0.019393 -0.149056 0.043915 -v 0.019490 -0.138537 0.044002 -v 0.019750 -0.149056 0.044165 -v 0.019011 -0.138470 0.043530 -v 0.018633 -0.138269 0.042805 -v 0.018538 -0.149056 0.042434 -v 0.018525 -0.137661 0.041617 -v 0.018508 -0.138055 0.042281 -v 0.018651 -0.149056 0.041145 -v 0.018835 -0.149056 0.040750 -v 0.018861 -0.136842 0.040707 -v 0.019085 -0.136442 0.040393 -v 0.019752 -0.135447 0.039842 -v 0.019750 -0.149056 0.039835 -v 0.020389 -0.135556 0.039576 -v 0.020145 -0.149056 0.039651 -v 0.020000 -0.135556 0.039709 -v 0.021000 -0.149056 0.039500 -v 0.020566 -0.149056 0.039538 -v 0.021205 -0.135556 0.039508 -v 0.020795 -0.135556 0.039508 -v 0.021611 -0.135556 0.039576 -v 0.022607 -0.149056 0.040085 -v 0.022250 -0.149056 0.039835 -v 0.022000 -0.135556 0.039709 -v 0.021855 -0.149056 0.039651 -v 0.023500 -0.149056 0.042000 -v 0.023462 -0.149056 0.041566 -v 0.023165 -0.149056 0.040750 -v 0.024933 -0.150486 0.041315 -v 0.019393 -0.149056 0.040085 -v 0.020686 -0.149510 0.039052 -v 0.022092 -0.149579 0.039151 -v 0.021434 -0.149056 0.039538 -v 0.023084 -0.149798 0.039517 -v 0.022915 -0.149056 0.040393 -v 0.023828 -0.150031 0.039983 -v 0.019085 -0.149056 0.040393 -v 0.018611 -0.149870 0.039621 -v 0.017212 -0.150420 0.041095 -v 0.018500 -0.149056 0.042000 -v 0.018538 -0.149056 0.041566 -v 0.020333 -0.150395 0.045780 -v 0.019304 -0.150451 0.045526 -v 0.020145 -0.149056 0.044349 -v 0.023465 -0.150518 0.045140 -v 0.023165 -0.149056 0.043250 -v 0.018075 -0.150551 0.044757 -v 0.019085 -0.149056 0.043607 -v 0.018835 -0.149056 0.043250 -v 0.018651 -0.149056 0.042855 -v 0.017091 -0.150559 0.043027 -v 0.024681 -0.150556 0.043624 -v 0.006862 -0.135287 0.039771 -v 0.008194 -0.135556 0.039508 -v 0.009254 -0.135460 0.039846 -v 0.008000 -0.149056 0.044500 -v 0.008000 -0.138556 0.044500 -v 0.007539 -0.138556 0.044466 -v 0.006750 -0.149056 0.044165 -v 0.006393 -0.149056 0.043915 -v 0.006037 -0.138379 0.043567 -v 0.005835 -0.149056 0.043250 -v 0.005538 -0.149056 0.042434 -v 0.005538 -0.137880 0.042434 -v 0.005668 -0.138120 0.042914 -v 0.005538 -0.137350 0.041566 -v 0.005835 -0.149056 0.040750 -v 0.006085 -0.136293 0.040393 -v 0.006393 -0.149056 0.040085 -v 0.009915 -0.136442 0.040393 -v 0.010165 -0.149056 0.040750 -v 0.010462 -0.149056 0.041566 -v 0.010477 -0.137668 0.041625 -v 0.010462 -0.149056 0.042434 -v 0.010500 -0.149056 0.042000 -v 0.010349 -0.149056 0.042855 -v 0.010502 -0.138020 0.042205 -v 0.009915 -0.149056 0.043607 -v 0.010165 -0.149056 0.043250 -v 0.009902 -0.138483 0.043623 -v 0.010136 -0.138419 0.043307 -v 0.008788 -0.138556 0.044378 -v 0.009250 -0.149056 0.044165 -v 0.009607 -0.149056 0.043915 -v 0.008434 -0.149056 0.044462 -v 0.008369 -0.138556 0.044475 -v 0.008855 -0.149056 0.044349 -v 0.007779 -0.135556 0.039510 -v 0.007370 -0.135556 0.039581 -v 0.008000 -0.149056 0.039500 -v 0.008603 -0.135556 0.039574 -v 0.008434 -0.149056 0.039538 -v 0.009715 -0.136104 0.040178 -v 0.009607 -0.149056 0.040085 -v 0.009250 -0.149056 0.039835 -v 0.008996 -0.135556 0.039707 -v 0.010349 -0.149056 0.041145 -v 0.011921 -0.150498 0.041558 -v 0.011262 -0.150182 0.040310 -v 0.006750 -0.149056 0.039835 -v 0.006767 -0.149573 0.039149 -v 0.007145 -0.149056 0.039651 -v 0.007566 -0.149056 0.039538 -v 0.008516 -0.149526 0.039075 -v 0.008855 -0.149056 0.039651 -v 0.009821 -0.149735 0.039409 -v 0.009915 -0.149056 0.040393 -v 0.006085 -0.149056 0.040393 -v 0.005651 -0.149056 0.041145 -v 0.005500 -0.149056 0.042000 -v 0.005538 -0.149056 0.041566 -v 0.008367 -0.150384 0.045824 -v 0.007019 -0.150406 0.045737 -v 0.007566 -0.149056 0.044462 -v 0.007145 -0.149056 0.044349 -v 0.010043 -0.150480 0.045358 -v 0.009324 -0.150427 0.045637 -v 0.006085 -0.149056 0.043607 -v 0.005651 -0.149056 0.042855 -v 0.004004 -0.150561 0.042454 -v 0.032752 -0.135445 0.039842 -v 0.035000 -0.135556 0.039709 -v 0.035258 -0.135467 0.039848 -v 0.036504 -0.138008 0.042175 -v 0.036500 -0.149056 0.042000 -v 0.035915 -0.149056 0.040393 -v 0.036166 -0.136891 0.040751 -v 0.036165 -0.149056 0.040750 -v 0.036349 -0.137285 0.041145 -v 0.036349 -0.149056 0.041145 -v 0.036461 -0.137633 0.041554 -v 0.036462 -0.149056 0.042434 -v 0.036349 -0.149056 0.042855 -v 0.035607 -0.149056 0.043915 -v 0.035566 -0.138530 0.043955 -v 0.035915 -0.149056 0.043607 -v 0.036054 -0.138464 0.043446 -v 0.034855 -0.149056 0.044349 -v 0.034788 -0.138556 0.044378 -v 0.035250 -0.149056 0.044165 -v 0.035198 -0.138549 0.044200 -v 0.033566 -0.149056 0.044462 -v 0.034000 -0.149056 0.044500 -v 0.034000 -0.138556 0.044500 -v 0.034369 -0.138556 0.044475 -v 0.032750 -0.149056 0.044165 -v 0.033145 -0.149056 0.044349 -v 0.033143 -0.138556 0.044357 -v 0.032393 -0.149056 0.043915 -v 0.032011 -0.138470 0.043529 -v 0.031835 -0.149056 0.043250 -v 0.031633 -0.138269 0.042805 -v 0.031538 -0.149056 0.042434 -v 0.031500 -0.149056 0.042000 -v 0.031651 -0.137285 0.041145 -v 0.031651 -0.149056 0.041145 -v 0.031538 -0.149056 0.041566 -v 0.031525 -0.137661 0.041617 -v 0.032085 -0.149056 0.040393 -v 0.031861 -0.136842 0.040707 -v 0.032393 -0.149056 0.040085 -v 0.032085 -0.136442 0.040393 -v 0.032750 -0.149056 0.039835 -v 0.033145 -0.149056 0.039651 -v 0.033566 -0.149056 0.039538 -v 0.033000 -0.135556 0.039709 -v 0.034000 -0.149056 0.039500 -v 0.033389 -0.135556 0.039576 -v 0.033795 -0.135556 0.039508 -v 0.034611 -0.135556 0.039576 -v 0.034205 -0.135556 0.039508 -v 0.034855 -0.149056 0.039651 -v 0.036462 -0.149056 0.041566 -v 0.033685 -0.149509 0.039053 -v 0.035053 -0.149572 0.039140 -v 0.034434 -0.149056 0.039538 -v 0.035250 -0.149056 0.039835 -v 0.035607 -0.149056 0.040085 -v 0.036799 -0.150009 0.039889 -v 0.030816 -0.150160 0.040276 -v 0.032273 -0.149701 0.039343 -v 0.031835 -0.149056 0.040750 -v 0.030018 -0.150522 0.041603 -v 0.034434 -0.149056 0.044462 -v 0.033696 -0.150383 0.045829 -v 0.032676 -0.150427 0.045637 -v 0.035756 -0.150443 0.045553 -v 0.036165 -0.149056 0.043250 -v 0.032085 -0.149056 0.043607 -v 0.031651 -0.149056 0.042855 -v 0.037996 -0.150560 0.042459 -v 0.021205 -0.095492 -0.000556 -v 0.020389 -0.095424 -0.000556 -v 0.020000 -0.095291 -0.000556 -v 0.019285 -0.094822 -0.001104 -v 0.019393 -0.094915 -0.014056 -v 0.018837 -0.094254 -0.001882 -v 0.018651 -0.093855 -0.014056 -v 0.018500 -0.093000 -0.014056 -v 0.019085 -0.091393 -0.014056 -v 0.018864 -0.091693 -0.003419 -v 0.018651 -0.092145 -0.014056 -v 0.018659 -0.092107 -0.003302 -v 0.019393 -0.091085 -0.014056 -v 0.019769 -0.090819 -0.003549 -v 0.019098 -0.091377 -0.003483 -v 0.020212 -0.090622 -0.003556 -v 0.020145 -0.090651 -0.014056 -v 0.019750 -0.090835 -0.014056 -v 0.021000 -0.090500 -0.003556 -v 0.020659 -0.090523 -0.003556 -v 0.021855 -0.090651 -0.014056 -v 0.021434 -0.090538 -0.014056 -v 0.022607 -0.091085 -0.014056 -v 0.022915 -0.091393 -0.014056 -v 0.023266 -0.091945 -0.003350 -v 0.023367 -0.092195 -0.003269 -v 0.023349 -0.092145 -0.014056 -v 0.023462 -0.092566 -0.014056 -v 0.023500 -0.093000 -0.014056 -v 0.023492 -0.092720 -0.003055 -v 0.023475 -0.093383 -0.002661 -v 0.023139 -0.094293 -0.001842 -v 0.023349 -0.093855 -0.002285 -v 0.022250 -0.095165 -0.014056 -v 0.021434 -0.095462 -0.014056 -v 0.022000 -0.095291 -0.000556 -v 0.021000 -0.095500 -0.014056 -v 0.021611 -0.095424 -0.000556 -v 0.020566 -0.095462 -0.014056 -v 0.020795 -0.095492 -0.000556 -v 0.019745 -0.095153 -0.000462 -v 0.020145 -0.095349 -0.014056 -v 0.018538 -0.093434 -0.014056 -v 0.017009 -0.093224 -0.015533 -v 0.018835 -0.094250 -0.014056 -v 0.021855 -0.095349 -0.014056 -v 0.022188 -0.095826 -0.014594 -v 0.020762 -0.095952 -0.014507 -v 0.019750 -0.095165 -0.014056 -v 0.019085 -0.094607 -0.014056 -v 0.019321 -0.095680 -0.014687 -v 0.022915 -0.094607 -0.014056 -v 0.024096 -0.094820 -0.015123 -v 0.022607 -0.094915 -0.014056 -v 0.023084 -0.095483 -0.014798 -v 0.023165 -0.094250 -0.014056 -v 0.023349 -0.093855 -0.014056 -v 0.023462 -0.093434 -0.014056 -v 0.018538 -0.092566 -0.014056 -v 0.017439 -0.091062 -0.015556 -v 0.018835 -0.091750 -0.014056 -v 0.018719 -0.089696 -0.015556 -v 0.019632 -0.089241 -0.015556 -v 0.020566 -0.090538 -0.014056 -v 0.020305 -0.089061 -0.015556 -v 0.021000 -0.090500 -0.014056 -v 0.021695 -0.089061 -0.015556 -v 0.022250 -0.090835 -0.014056 -v 0.022722 -0.089373 -0.015556 -v 0.023165 -0.091750 -0.014056 -v 0.024899 -0.092035 -0.015557 -v 0.009249 -0.095158 -0.000449 -v 0.006085 -0.094607 -0.001292 -v 0.006393 -0.094915 -0.014056 -v 0.005538 -0.093434 -0.002350 -v 0.005651 -0.093855 -0.014056 -v 0.005651 -0.093855 -0.002032 -v 0.005835 -0.094250 -0.014056 -v 0.005834 -0.094248 -0.001682 -v 0.005538 -0.093434 -0.014056 -v 0.005500 -0.093000 -0.014056 -v 0.005538 -0.092566 -0.002880 -v 0.005651 -0.092145 -0.014056 -v 0.005723 -0.091940 -0.003183 -v 0.006500 -0.090991 -0.003516 -v 0.006085 -0.091393 -0.014056 -v 0.007166 -0.090637 -0.003565 -v 0.006750 -0.090835 -0.014056 -v 0.007742 -0.090507 -0.003556 -v 0.009989 -0.091471 -0.003470 -v 0.010165 -0.091750 -0.014056 -v 0.010367 -0.092195 -0.003269 -v 0.010462 -0.093434 -0.014056 -v 0.009607 -0.094915 -0.014056 -v 0.009612 -0.094911 -0.000951 -v 0.009915 -0.094607 -0.014056 -v 0.009915 -0.094607 -0.001442 -v 0.009250 -0.095165 -0.014056 -v 0.008996 -0.095293 -0.000556 -v 0.008434 -0.095462 -0.014056 -v 0.008603 -0.095426 -0.000556 -v 0.008000 -0.095500 -0.014056 -v 0.008194 -0.095492 -0.000556 -v 0.007145 -0.095349 -0.014056 -v 0.007370 -0.095419 -0.000556 -v 0.007566 -0.095462 -0.014056 -v 0.007779 -0.095490 -0.000556 -v 0.006393 -0.094915 -0.000868 -v 0.006854 -0.095226 -0.000313 -v 0.009811 -0.095602 -0.014729 -v 0.008855 -0.095349 -0.014056 -v 0.006750 -0.095165 -0.014056 -v 0.006085 -0.094607 -0.014056 -v 0.006259 -0.095694 -0.014669 -v 0.010165 -0.094250 -0.014056 -v 0.010349 -0.093855 -0.014056 -v 0.010500 -0.093000 -0.014056 -v 0.005538 -0.092566 -0.014056 -v 0.004000 -0.092563 -0.015556 -v 0.005835 -0.091750 -0.014056 -v 0.004523 -0.090944 -0.015556 -v 0.006393 -0.091085 -0.014056 -v 0.007145 -0.090651 -0.014056 -v 0.007566 -0.090538 -0.014056 -v 0.008000 -0.090500 -0.014056 -v 0.008434 -0.090538 -0.014056 -v 0.009368 -0.089241 -0.015556 -v 0.008855 -0.090651 -0.014056 -v 0.009250 -0.090835 -0.014056 -v 0.009607 -0.091085 -0.014056 -v 0.009915 -0.091393 -0.014056 -v 0.011264 -0.090714 -0.015556 -v 0.010349 -0.092145 -0.014056 -v 0.010462 -0.092566 -0.014056 -v 0.035236 -0.095166 -0.000431 -v 0.032755 -0.095161 -0.000446 -v 0.032085 -0.094607 -0.001442 -v 0.032393 -0.094915 -0.014056 -v 0.032085 -0.094607 -0.014056 -v 0.031837 -0.094254 -0.001882 -v 0.031651 -0.093855 -0.014056 -v 0.031538 -0.093434 -0.014056 -v 0.031498 -0.092795 -0.003020 -v 0.032085 -0.091393 -0.014056 -v 0.032098 -0.091377 -0.003483 -v 0.031864 -0.091693 -0.003419 -v 0.031651 -0.092145 -0.014056 -v 0.031659 -0.092107 -0.003302 -v 0.033212 -0.090622 -0.003556 -v 0.032750 -0.090835 -0.014056 -v 0.034000 -0.090500 -0.014056 -v 0.034000 -0.090500 -0.003556 -v 0.033566 -0.090538 -0.014056 -v 0.033659 -0.090523 -0.003556 -v 0.034434 -0.090538 -0.014056 -v 0.034855 -0.090651 -0.014056 -v 0.034962 -0.090690 -0.003554 -v 0.035607 -0.091085 -0.014056 -v 0.035915 -0.091393 -0.014056 -v 0.036478 -0.092637 -0.003085 -v 0.036500 -0.093000 -0.014056 -v 0.036494 -0.093237 -0.002752 -v 0.036351 -0.093850 -0.002275 -v 0.035915 -0.094607 -0.014056 -v 0.036139 -0.094293 -0.001841 -v 0.035620 -0.094904 -0.000947 -v 0.035250 -0.095165 -0.014056 -v 0.035000 -0.095291 -0.000556 -v 0.034855 -0.095349 -0.014056 -v 0.034611 -0.095424 -0.000556 -v 0.034205 -0.095492 -0.000556 -v 0.034434 -0.095462 -0.014056 -v 0.034000 -0.095500 -0.014056 -v 0.033145 -0.095349 -0.014056 -v 0.033389 -0.095424 -0.000556 -v 0.033795 -0.095492 -0.000556 -v 0.032285 -0.094822 -0.001104 -v 0.033000 -0.095291 -0.000556 -v 0.031538 -0.092566 -0.014056 -v 0.030009 -0.093224 -0.015533 -v 0.031500 -0.093000 -0.014056 -v 0.031835 -0.094250 -0.014056 -v 0.030695 -0.094630 -0.015203 -v 0.035607 -0.094915 -0.014056 -v 0.036040 -0.095591 -0.014744 -v 0.033566 -0.095462 -0.014056 -v 0.032750 -0.095165 -0.014056 -v 0.032321 -0.095680 -0.014687 -v 0.036165 -0.094250 -0.014056 -v 0.036462 -0.093434 -0.014056 -v 0.036349 -0.093855 -0.014056 -v 0.036462 -0.092566 -0.014056 -v 0.031835 -0.091750 -0.014056 -v 0.032393 -0.091085 -0.014056 -v 0.031429 -0.089936 -0.015556 -v 0.033145 -0.090651 -0.014056 -v 0.032632 -0.089241 -0.015556 -v 0.034407 -0.088946 -0.015556 -v 0.035250 -0.090835 -0.014056 -v 0.036325 -0.089727 -0.015556 -v 0.036165 -0.091750 -0.014056 -v 0.036349 -0.092145 -0.014056 -v 0.037519 -0.091017 -0.015556 -v 0.040000 -0.103772 0.034057 -v 0.040000 -0.100943 0.031228 -v 0.041278 -0.102789 0.029359 -v 0.040880 -0.102511 0.029660 -v 0.041999 -0.103114 0.028938 -v 0.042000 -0.103105 0.030270 -v 0.040878 -0.102768 0.030587 -v 0.041278 -0.105641 0.032211 -v 0.040364 -0.104765 0.033064 -v 0.040003 -0.102386 0.032567 -v 0.041722 -0.105941 0.031987 -v 0.041039 -0.104411 0.032160 -v 0.041378 -0.097978 0.033321 -v 0.040973 -0.098356 0.033195 -v 0.040612 -0.098758 0.033022 -v 0.040357 -0.099113 0.032832 -v 0.040070 -0.099722 0.032410 -v 0.040001 -0.100115 0.032057 -v 0.042000 -0.098368 0.033816 -v 0.040727 -0.099229 0.033660 -v 0.040070 -0.100594 0.033432 -v 0.042000 -0.099528 0.035141 -v 0.042000 -0.100529 0.037294 -v 0.040232 -0.101668 0.036160 -v 0.041134 -0.100591 0.037238 -v 0.040541 -0.100895 0.035817 -v 0.006750 -0.059598 0.129638 -v 0.006393 -0.059769 0.129455 -v 0.007145 -0.059473 0.129772 -v 0.006085 -0.059979 0.129229 -v 0.005835 -0.060222 0.128968 -v 0.005835 -0.061927 0.127140 -v 0.007566 -0.062754 0.126254 -v 0.007145 -0.062677 0.126336 -v 0.008855 -0.062677 0.126336 -v 0.008000 -0.062780 0.126226 -v 0.009250 -0.062551 0.126471 -v 0.010462 -0.061371 0.127737 -v 0.010349 -0.061658 0.127429 -v 0.010165 -0.061927 0.127140 -v 0.010349 -0.060492 0.128679 -v 0.010500 -0.061075 0.128054 -v 0.009915 -0.059979 0.129229 -v 0.008000 -0.059976 0.127030 -v 0.009250 -0.059598 0.129638 -v 0.008855 -0.059473 0.129772 -v 0.009607 -0.059769 0.129455 -v 0.008000 -0.066683 0.136703 -v 0.007566 -0.059396 0.129855 -v 0.007566 -0.066709 0.136675 -v 0.007145 -0.066786 0.136592 -v 0.006750 -0.066912 0.136458 -v 0.006393 -0.067082 0.136275 -v 0.006085 -0.067292 0.136049 -v 0.005835 -0.067536 0.135788 -v 0.005651 -0.060492 0.128679 -v 0.005538 -0.060779 0.128372 -v 0.005651 -0.067805 0.135499 -v 0.005500 -0.061075 0.128054 -v 0.005538 -0.061371 0.127737 -v 0.005651 -0.061658 0.127429 -v 0.005651 -0.068971 0.134249 -v 0.005835 -0.069241 0.133960 -v 0.006085 -0.062171 0.126879 -v 0.006393 -0.062381 0.126654 -v 0.006750 -0.069865 0.133291 -v 0.006750 -0.062551 0.126471 -v 0.008434 -0.070067 0.133074 -v 0.008434 -0.062754 0.126254 -v 0.008855 -0.069990 0.133156 -v 0.009250 -0.069865 0.133291 -v 0.009607 -0.069694 0.133474 -v 0.009607 -0.062381 0.126654 -v 0.009915 -0.062171 0.126879 -v 0.009915 -0.069484 0.133699 -v 0.010349 -0.068971 0.134249 -v 0.010462 -0.068684 0.134557 -v 0.010500 -0.068388 0.134874 -v 0.010462 -0.060779 0.128372 -v 0.010165 -0.060222 0.128968 -v 0.010165 -0.067536 0.135788 -v 0.009250 -0.066912 0.136458 -v 0.008855 -0.066786 0.136592 -v 0.008434 -0.059396 0.129855 -v 0.008434 -0.066709 0.136675 -v 0.008000 -0.059370 0.129883 -v 0.020566 -0.059396 0.129855 -v 0.018538 -0.060779 0.128372 -v 0.018835 -0.060222 0.128968 -v 0.019393 -0.062381 0.126654 -v 0.018651 -0.061658 0.127429 -v 0.019750 -0.062551 0.126471 -v 0.021000 -0.059976 0.127030 -v 0.021434 -0.062754 0.126254 -v 0.021855 -0.062677 0.126336 -v 0.023462 -0.061371 0.127737 -v 0.023165 -0.061927 0.127140 -v 0.023500 -0.061075 0.128054 -v 0.022607 -0.059769 0.129455 -v 0.022250 -0.059598 0.129638 -v 0.022250 -0.062551 0.126471 -v 0.022604 -0.069696 0.133472 -v 0.022607 -0.062381 0.126654 -v 0.022915 -0.062171 0.126879 -v 0.022915 -0.069484 0.133699 -v 0.023165 -0.069241 0.133960 -v 0.023349 -0.061658 0.127429 -v 0.023462 -0.068684 0.134557 -v 0.023462 -0.060779 0.128372 -v 0.023349 -0.060492 0.128679 -v 0.023165 -0.060222 0.128968 -v 0.022915 -0.059979 0.129229 -v 0.023165 -0.067536 0.135788 -v 0.021855 -0.059473 0.129772 -v 0.021855 -0.066786 0.136592 -v 0.021434 -0.059396 0.129855 -v 0.021000 -0.059370 0.129883 -v 0.021434 -0.066709 0.136675 -v 0.020145 -0.059473 0.129772 -v 0.019750 -0.059598 0.129638 -v 0.019393 -0.059769 0.129455 -v 0.019393 -0.067082 0.136275 -v 0.019085 -0.059979 0.129229 -v 0.018835 -0.067536 0.135788 -v 0.018651 -0.060492 0.128679 -v 0.018538 -0.068092 0.135192 -v 0.018500 -0.061075 0.128054 -v 0.018500 -0.068388 0.134874 -v 0.018538 -0.061371 0.127737 -v 0.018538 -0.068684 0.134557 -v 0.018651 -0.068971 0.134249 -v 0.018835 -0.061927 0.127140 -v 0.019085 -0.062171 0.126879 -v 0.018835 -0.069241 0.133960 -v 0.019393 -0.069694 0.133474 -v 0.019750 -0.069865 0.133291 -v 0.020145 -0.062677 0.126336 -v 0.020145 -0.069990 0.133156 -v 0.020566 -0.062754 0.126254 -v 0.020566 -0.070067 0.133074 -v 0.021000 -0.062780 0.126226 -v 0.021000 -0.070093 0.133046 -v 0.022045 -0.069940 0.133210 -v 0.034000 -0.059370 0.129883 -v 0.033566 -0.059396 0.129855 -v 0.032393 -0.059769 0.129455 -v 0.033145 -0.059473 0.129772 -v 0.031835 -0.060222 0.128968 -v 0.032085 -0.059979 0.129229 -v 0.031538 -0.061371 0.127737 -v 0.031651 -0.061658 0.127429 -v 0.031500 -0.061075 0.128054 -v 0.032085 -0.062171 0.126879 -v 0.033145 -0.062677 0.126336 -v 0.032393 -0.062381 0.126654 -v 0.032750 -0.062551 0.126471 -v 0.034000 -0.062780 0.126226 -v 0.034000 -0.059976 0.127030 -v 0.033566 -0.062754 0.126254 -v 0.035915 -0.062171 0.126879 -v 0.036165 -0.060222 0.128968 -v 0.036349 -0.060492 0.128679 -v 0.034000 -0.066683 0.136703 -v 0.033566 -0.066709 0.136675 -v 0.033145 -0.066786 0.136592 -v 0.032750 -0.059598 0.129638 -v 0.031651 -0.060492 0.128679 -v 0.031835 -0.067536 0.135788 -v 0.031538 -0.060779 0.128372 -v 0.031538 -0.068684 0.134557 -v 0.031651 -0.068971 0.134249 -v 0.031835 -0.061927 0.127140 -v 0.031835 -0.069241 0.133960 -v 0.032085 -0.069484 0.133699 -v 0.032750 -0.069865 0.133291 -v 0.033566 -0.070067 0.133074 -v 0.034000 -0.070093 0.133046 -v 0.034434 -0.062754 0.126254 -v 0.034855 -0.062677 0.126336 -v 0.034855 -0.069990 0.133156 -v 0.035250 -0.062551 0.126471 -v 0.035250 -0.069865 0.133291 -v 0.035607 -0.062381 0.126654 -v 0.035607 -0.069694 0.133474 -v 0.035915 -0.069484 0.133699 -v 0.036165 -0.061927 0.127140 -v 0.036349 -0.061658 0.127429 -v 0.036462 -0.068684 0.134557 -v 0.036462 -0.061371 0.127737 -v 0.036500 -0.061075 0.128054 -v 0.036500 -0.068388 0.134874 -v 0.036462 -0.060779 0.128372 -v 0.036462 -0.068092 0.135192 -v 0.036349 -0.067805 0.135499 -v 0.036165 -0.067536 0.135788 -v 0.035915 -0.059979 0.129229 -v 0.035607 -0.059769 0.129455 -v 0.035607 -0.067082 0.136275 -v 0.035250 -0.059598 0.129638 -v 0.035250 -0.066912 0.136458 -v 0.034855 -0.059473 0.129772 -v 0.034434 -0.059396 0.129855 -v 0.020566 -0.125550 0.058913 -v 0.019085 -0.126133 0.058288 -v 0.018538 -0.127525 0.056795 -v 0.018500 -0.127229 0.057113 -v 0.018651 -0.127812 0.056488 -v 0.020145 -0.128831 0.055395 -v 0.022250 -0.128705 0.055529 -v 0.023462 -0.127525 0.056795 -v 0.023165 -0.128081 0.056199 -v 0.023165 -0.126376 0.058027 -v 0.021000 -0.126130 0.056088 -v 0.021855 -0.125626 0.058831 -v 0.022607 -0.128535 0.055712 -v 0.022915 -0.128325 0.055938 -v 0.023349 -0.127812 0.056488 -v 0.023500 -0.127229 0.057113 -v 0.023500 -0.134542 0.063933 -v 0.023462 -0.134246 0.064250 -v 0.023462 -0.126933 0.057430 -v 0.023349 -0.126645 0.057738 -v 0.022915 -0.126133 0.058288 -v 0.023165 -0.133690 0.064847 -v 0.022915 -0.133446 0.065108 -v 0.022607 -0.125923 0.058513 -v 0.022575 -0.133221 0.065350 -v 0.022250 -0.125752 0.058696 -v 0.021434 -0.125550 0.058913 -v 0.021434 -0.132863 0.065733 -v 0.021000 -0.125524 0.058941 -v 0.021000 -0.132837 0.065761 -v 0.020145 -0.125626 0.058831 -v 0.019750 -0.125752 0.058696 -v 0.020145 -0.132940 0.065651 -v 0.019750 -0.133066 0.065516 -v 0.019393 -0.125923 0.058513 -v 0.019393 -0.133236 0.065333 -v 0.018835 -0.126376 0.058027 -v 0.018651 -0.126645 0.057738 -v 0.018651 -0.133959 0.064558 -v 0.018538 -0.126933 0.057430 -v 0.018538 -0.134246 0.064250 -v 0.018500 -0.134542 0.063933 -v 0.018538 -0.134838 0.063615 -v 0.018651 -0.135125 0.063308 -v 0.018835 -0.128081 0.056199 -v 0.019085 -0.128325 0.055938 -v 0.019393 -0.128535 0.055712 -v 0.019750 -0.128705 0.055529 -v 0.019750 -0.136019 0.062349 -v 0.020566 -0.128908 0.055312 -v 0.020145 -0.136144 0.062215 -v 0.021000 -0.136247 0.062104 -v 0.021000 -0.128934 0.055284 -v 0.021434 -0.128908 0.055312 -v 0.021855 -0.128831 0.055395 -v 0.021434 -0.136221 0.062132 -v 0.020566 -0.091450 0.095481 -v 0.021000 -0.091424 0.095509 -v 0.019750 -0.091652 0.095264 -v 0.019393 -0.091823 0.095081 -v 0.021000 -0.092030 0.092656 -v 0.020145 -0.091527 0.095399 -v 0.018651 -0.092546 0.094306 -v 0.018835 -0.092276 0.094595 -v 0.018538 -0.093425 0.093363 -v 0.018835 -0.093981 0.092766 -v 0.019393 -0.094435 0.092280 -v 0.022607 -0.094435 0.092280 -v 0.022250 -0.094605 0.092097 -v 0.023349 -0.093712 0.093055 -v 0.023500 -0.093129 0.093681 -v 0.023462 -0.092833 0.093998 -v 0.023165 -0.092276 0.094595 -v 0.023349 -0.092546 0.094306 -v 0.022607 -0.091823 0.095081 -v 0.022915 -0.094225 0.092505 -v 0.022915 -0.101538 0.099325 -v 0.023165 -0.101295 0.099586 -v 0.023165 -0.093981 0.092766 -v 0.023349 -0.101025 0.099875 -v 0.023462 -0.093425 0.093363 -v 0.023462 -0.100738 0.100183 -v 0.023462 -0.100146 0.100818 -v 0.023165 -0.099590 0.101415 -v 0.022915 -0.092033 0.094856 -v 0.022250 -0.091652 0.095264 -v 0.022603 -0.099134 0.101904 -v 0.021855 -0.091527 0.095399 -v 0.021855 -0.098840 0.102219 -v 0.021434 -0.091450 0.095481 -v 0.021434 -0.098763 0.102301 -v 0.019085 -0.092033 0.094856 -v 0.019085 -0.099346 0.101676 -v 0.018835 -0.099590 0.101415 -v 0.018651 -0.099859 0.101126 -v 0.018538 -0.092833 0.093998 -v 0.018538 -0.100146 0.100818 -v 0.018500 -0.100442 0.100501 -v 0.018500 -0.093129 0.093681 -v 0.018538 -0.100738 0.100183 -v 0.018651 -0.093712 0.093055 -v 0.018651 -0.101025 0.099875 -v 0.019085 -0.101538 0.099325 -v 0.019085 -0.094225 0.092505 -v 0.019750 -0.094605 0.092097 -v 0.020145 -0.094731 0.091962 -v 0.020145 -0.102044 0.098782 -v 0.020566 -0.094808 0.091880 -v 0.021000 -0.094834 0.091852 -v 0.021434 -0.094808 0.091880 -v 0.021855 -0.094731 0.091962 -v 0.021855 -0.102044 0.098782 -v 0.022607 -0.101748 0.099100 -v 0.007566 -0.125550 0.058913 -v 0.007145 -0.125626 0.058831 -v 0.008000 -0.125524 0.058941 -v 0.006393 -0.125923 0.058513 -v 0.005651 -0.126645 0.057738 -v 0.005538 -0.126933 0.057430 -v 0.005651 -0.127812 0.056488 -v 0.005538 -0.127525 0.056795 -v 0.008000 -0.126130 0.056088 -v 0.005500 -0.127229 0.057113 -v 0.005835 -0.128081 0.056199 -v 0.006085 -0.128325 0.055938 -v 0.008434 -0.128908 0.055312 -v 0.007566 -0.128908 0.055312 -v 0.009607 -0.128535 0.055712 -v 0.010165 -0.128081 0.056199 -v 0.009915 -0.128325 0.055938 -v 0.010349 -0.126645 0.057738 -v 0.010500 -0.127229 0.057113 -v 0.009607 -0.125923 0.058513 -v 0.008434 -0.125550 0.058913 -v 0.008000 -0.132837 0.065761 -v 0.006750 -0.125752 0.058696 -v 0.006750 -0.133066 0.065516 -v 0.006393 -0.133236 0.065333 -v 0.006085 -0.126133 0.058288 -v 0.005835 -0.126376 0.058027 -v 0.005835 -0.133690 0.064847 -v 0.005538 -0.134246 0.064250 -v 0.005538 -0.134838 0.063615 -v 0.006085 -0.135638 0.062758 -v 0.006393 -0.128535 0.055712 -v 0.006393 -0.135848 0.062532 -v 0.006750 -0.128705 0.055529 -v 0.006750 -0.136019 0.062349 -v 0.007145 -0.128831 0.055395 -v 0.008000 -0.128934 0.055284 -v 0.007566 -0.136221 0.062132 -v 0.008434 -0.136221 0.062132 -v 0.008855 -0.128831 0.055395 -v 0.009250 -0.128705 0.055529 -v 0.009250 -0.136019 0.062349 -v 0.010349 -0.127812 0.056488 -v 0.010462 -0.127525 0.056795 -v 0.010349 -0.135125 0.063308 -v 0.010500 -0.134542 0.063933 -v 0.010462 -0.126933 0.057430 -v 0.010349 -0.133959 0.064558 -v 0.010165 -0.126376 0.058027 -v 0.009915 -0.126133 0.058288 -v 0.009250 -0.125752 0.058696 -v 0.008855 -0.125626 0.058831 -v 0.008855 -0.132940 0.065651 -v 0.033566 -0.125550 0.058913 -v 0.032085 -0.126133 0.058288 -v 0.032750 -0.125752 0.058696 -v 0.032393 -0.125923 0.058513 -v 0.033145 -0.125626 0.058831 -v 0.031651 -0.126645 0.057738 -v 0.031651 -0.127812 0.056488 -v 0.033566 -0.128908 0.055312 -v 0.033145 -0.128831 0.055395 -v 0.032393 -0.128535 0.055712 -v 0.034434 -0.128908 0.055312 -v 0.034855 -0.128831 0.055395 -v 0.035250 -0.128705 0.055529 -v 0.035607 -0.128535 0.055712 -v 0.036462 -0.127525 0.056795 -v 0.036462 -0.126933 0.057430 -v 0.036500 -0.127229 0.057113 -v 0.034000 -0.126130 0.056088 -v 0.035915 -0.126133 0.058288 -v 0.034855 -0.125626 0.058831 -v 0.034434 -0.125550 0.058913 -v 0.034000 -0.125524 0.058941 -v 0.034000 -0.132837 0.065761 -v 0.033566 -0.132863 0.065733 -v 0.033145 -0.132940 0.065651 -v 0.032393 -0.133236 0.065333 -v 0.032085 -0.133446 0.065108 -v 0.031835 -0.126376 0.058027 -v 0.031835 -0.133690 0.064847 -v 0.031538 -0.126933 0.057430 -v 0.031538 -0.134246 0.064250 -v 0.031500 -0.127229 0.057113 -v 0.031538 -0.127525 0.056795 -v 0.031538 -0.134838 0.063615 -v 0.031835 -0.128081 0.056199 -v 0.032085 -0.128325 0.055938 -v 0.032085 -0.135638 0.062758 -v 0.032393 -0.135848 0.062532 -v 0.032750 -0.128705 0.055529 -v 0.032750 -0.136019 0.062349 -v 0.033145 -0.136144 0.062215 -v 0.033566 -0.136221 0.062132 -v 0.034000 -0.128934 0.055284 -v 0.035607 -0.135848 0.062532 -v 0.035915 -0.128325 0.055938 -v 0.036165 -0.128081 0.056199 -v 0.036349 -0.127812 0.056488 -v 0.036349 -0.135125 0.063308 -v 0.036500 -0.134542 0.063933 -v 0.036462 -0.134246 0.064250 -v 0.036349 -0.126645 0.057738 -v 0.036349 -0.133959 0.064558 -v 0.036165 -0.126376 0.058027 -v 0.035915 -0.133446 0.065108 -v 0.035607 -0.125923 0.058513 -v 0.035607 -0.133236 0.065333 -v 0.035250 -0.125752 0.058696 -v 0.034855 -0.132940 0.065651 -v 0.034434 -0.132863 0.065733 -v 0.007566 -0.091450 0.095481 -v 0.008000 -0.092030 0.092656 -v 0.006085 -0.092033 0.094856 -v 0.006750 -0.091652 0.095264 -v 0.005651 -0.092546 0.094306 -v 0.005538 -0.093425 0.093363 -v 0.006393 -0.094435 0.092280 -v 0.009915 -0.094225 0.092505 -v 0.008855 -0.094731 0.091962 -v 0.010349 -0.093712 0.093055 -v 0.010349 -0.092546 0.094306 -v 0.010500 -0.093129 0.093681 -v 0.009607 -0.091823 0.095081 -v 0.010165 -0.092276 0.094595 -v 0.008434 -0.091450 0.095481 -v 0.008855 -0.091527 0.095399 -v 0.008000 -0.091424 0.095509 -v 0.007566 -0.098763 0.102301 -v 0.007145 -0.091527 0.095399 -v 0.006393 -0.091823 0.095081 -v 0.006085 -0.099346 0.101676 -v 0.005835 -0.092276 0.094595 -v 0.005835 -0.099590 0.101415 -v 0.005538 -0.092833 0.093998 -v 0.005651 -0.099859 0.101126 -v 0.005500 -0.093129 0.093681 -v 0.005538 -0.100146 0.100818 -v 0.005500 -0.100442 0.100501 -v 0.005651 -0.101025 0.099875 -v 0.005651 -0.093712 0.093055 -v 0.005835 -0.093981 0.092766 -v 0.006085 -0.094225 0.092505 -v 0.006750 -0.094605 0.092097 -v 0.006393 -0.101748 0.099100 -v 0.007145 -0.094731 0.091962 -v 0.007566 -0.094808 0.091880 -v 0.007145 -0.102044 0.098782 -v 0.007566 -0.102121 0.098700 -v 0.008000 -0.094834 0.091852 -v 0.008434 -0.094808 0.091880 -v 0.008434 -0.102121 0.098700 -v 0.008855 -0.102044 0.098782 -v 0.009250 -0.094605 0.092097 -v 0.009607 -0.094435 0.092280 -v 0.009607 -0.101748 0.099100 -v 0.010165 -0.093981 0.092766 -v 0.010462 -0.093425 0.093363 -v 0.010349 -0.101025 0.099875 -v 0.010500 -0.100442 0.100501 -v 0.010462 -0.092833 0.093998 -v 0.009915 -0.092033 0.094856 -v 0.009915 -0.099346 0.101676 -v 0.009607 -0.099136 0.101901 -v 0.009250 -0.091652 0.095264 -v 0.009250 -0.098966 0.102084 -v 0.008855 -0.098840 0.102219 -v 0.008000 -0.098737 0.102329 -v 0.034000 -0.091424 0.095509 -v 0.032750 -0.091652 0.095264 -v 0.032085 -0.092033 0.094856 -v 0.031835 -0.092276 0.094595 -v 0.031500 -0.093129 0.093681 -v 0.031835 -0.093981 0.092766 -v 0.032393 -0.094435 0.092280 -v 0.034434 -0.094808 0.091880 -v 0.034855 -0.094731 0.091962 -v 0.033566 -0.094808 0.091880 -v 0.034000 -0.094834 0.091852 -v 0.035915 -0.094225 0.092505 -v 0.036349 -0.093712 0.093055 -v 0.036349 -0.092546 0.094306 -v 0.036500 -0.093129 0.093681 -v 0.034000 -0.092030 0.092656 -v 0.035250 -0.091652 0.095264 -v 0.033566 -0.091450 0.095481 -v 0.033145 -0.091527 0.095399 -v 0.032750 -0.098966 0.102084 -v 0.032393 -0.091823 0.095081 -v 0.032393 -0.099136 0.101901 -v 0.031835 -0.099590 0.101415 -v 0.031651 -0.092546 0.094306 -v 0.031538 -0.092833 0.093998 -v 0.031651 -0.099859 0.101126 -v 0.031538 -0.100146 0.100818 -v 0.031500 -0.100442 0.100501 -v 0.031538 -0.093425 0.093363 -v 0.031538 -0.100738 0.100183 -v 0.031651 -0.093712 0.093055 -v 0.031835 -0.101295 0.099586 -v 0.032085 -0.094225 0.092505 -v 0.032750 -0.094605 0.092097 -v 0.032393 -0.101748 0.099100 -v 0.033145 -0.094731 0.091962 -v 0.034434 -0.102121 0.098700 -v 0.035250 -0.101919 0.098917 -v 0.035250 -0.094605 0.092097 -v 0.035607 -0.094435 0.092280 -v 0.035607 -0.101748 0.099100 -v 0.036165 -0.093981 0.092766 -v 0.036349 -0.101025 0.099875 -v 0.036462 -0.093425 0.093363 -v 0.036462 -0.092833 0.093998 -v 0.036349 -0.099859 0.101126 -v 0.036165 -0.092276 0.094595 -v 0.035915 -0.092033 0.094856 -v 0.036165 -0.099590 0.101415 -v 0.035915 -0.099346 0.101676 -v 0.035607 -0.091823 0.095081 -v 0.035607 -0.099136 0.101901 -v 0.035250 -0.098966 0.102084 -v 0.034855 -0.091527 0.095399 -v 0.034434 -0.091450 0.095481 -v 0.034855 -0.098840 0.102219 -v 0.040110 -0.048171 -0.072318 -v 0.039172 -0.047364 -0.073938 -v 0.038428 -0.047329 -0.073985 -v 0.037961 -0.047419 -0.073856 -v 0.039986 0.048296 -0.071975 -v 0.039448 0.047452 -0.073807 -v 0.038910 0.047334 -0.073978 -v 0.039008 0.048544 -0.071286 -v 0.038428 0.047329 -0.073985 -v 0.039492 0.048473 -0.071488 -v 0.037567 0.048403 -0.071679 -v 0.037218 0.048216 -0.072198 -v 0.028000 -0.053191 -0.049417 -v 0.037178 0.047915 -0.072977 -v 0.027518 -0.052483 -0.046774 -v 0.025142 -0.051605 -0.043497 -v 0.026128 -0.054522 -0.054384 -v 0.021389 -0.051152 -0.041807 -v 0.024000 -0.054984 -0.056109 -v 0.021389 -0.055230 -0.057027 -v 0.014858 -0.054777 -0.055337 -v 0.013872 -0.054522 -0.054384 -v 0.013072 -0.052156 -0.045553 -v 0.012482 -0.052483 -0.046774 -v 0.012122 -0.053550 -0.050759 -v 0.020000 -0.055261 -0.057144 -v 0.022736 -0.055137 -0.056678 -v 0.026928 0.054226 -0.053281 -v 0.024000 0.054984 -0.056109 -v 0.027518 0.052483 -0.046774 -v 0.027878 0.052831 -0.048075 -v 0.026128 0.054522 -0.054384 -v 0.024000 0.051398 -0.042725 -v 0.021389 0.055230 -0.057027 -v 0.020000 0.055261 -0.057144 -v 0.021389 0.051152 -0.041807 -v 0.014858 0.051605 -0.043497 -v 0.016000 0.054984 -0.056109 -v 0.013072 0.052156 -0.045553 -v 0.018611 0.055230 -0.057027 -v 0.012482 0.053899 -0.052060 -v 0.027518 0.053899 -0.052060 -v 0.025142 0.054777 -0.055337 -v 0.012122 0.052831 -0.048075 -v 0.012482 0.052483 -0.046774 -v 0.012000 0.053191 -0.049417 -v 0.039759 -0.004145 0.151135 -v 0.038339 -0.061502 0.138943 -v 0.040000 -0.031893 0.145237 -v 0.036000 -0.062216 0.138792 -v 0.006000 -0.001571 0.151682 -v 0.006000 -0.062216 0.138792 -v 0.004995 -0.001681 0.151658 -v 0.002000 -0.031893 0.145237 -v 0.002936 -0.060818 0.139089 -v 0.002241 -0.004145 0.151135 -v 0.002536 -0.060260 0.139207 -v 0.021000 -0.062216 0.138792 -v 0.002000 0.056583 0.131530 -v 0.039939 0.003084 0.142901 -v 0.040000 0.030173 0.137143 -v 0.038571 0.059580 0.130893 -v 0.039064 0.001248 0.143292 -v 0.038000 0.059971 0.130810 -v 0.038571 0.000766 0.143394 -v 0.039939 0.057262 0.131385 -v 0.021000 0.060496 0.130698 -v 0.006000 0.060496 0.130698 -v 0.002000 0.030173 0.137143 -v 0.006000 -0.000150 0.143589 -v 0.005305 0.060436 0.130711 -v 0.004632 0.060260 0.130748 -v 0.005305 -0.000090 0.143576 -v 0.004000 0.059971 0.130810 -v 0.003429 0.059580 0.130893 -v 0.004000 0.000375 0.143477 -v 0.002536 0.058539 0.131114 -v 0.002936 0.059098 0.130995 -v 0.002241 0.057921 0.131245 -v 0.002061 0.057262 0.131385 -v 0.002000 -0.005483 0.150850 -v 0.014425 0.084172 0.117948 -v 0.027500 0.084172 0.117948 -v 0.022575 0.094454 0.106923 -v 0.027500 -0.084172 0.117948 -v 0.018425 0.074134 0.128712 -v 0.027074 -0.016261 -0.088672 -v 0.027145 -0.014493 -0.089321 -v -0.000000 -0.015429 -0.088900 -v 0.042000 -0.013615 -0.089925 -v -0.000000 -0.014477 -0.089333 -v 0.042000 -0.014477 -0.089333 -v 0.031879 -0.014605 -0.089263 -v 0.028713 -0.014376 -0.089402 -v 0.031962 -0.016210 -0.088682 -v 0.032419 -0.015951 -0.088740 -v 0.042000 -0.016441 -0.088639 -v 0.042000 -0.015429 -0.088900 -v -0.000000 -0.013615 -0.089925 -v -0.000000 -0.012868 -0.090657 -v 0.042000 -0.012160 -0.091649 -v -0.000000 -0.011895 -0.091868 -v 0.042000 -0.011895 -0.091868 -v -0.000000 -0.011738 -0.091941 -v 0.042000 -0.011738 -0.091941 -v -0.000000 -0.011571 -0.091985 -v 0.042000 -0.011399 -0.092000 -v 0.035000 -0.055315 -0.078048 -v 0.042000 -0.056878 -0.070996 -v 0.042000 -0.057468 -0.072625 -v 0.034300 -0.056595 -0.069692 -v 0.042000 -0.056584 -0.069486 -v 0.042000 -0.056702 -0.066421 -v 0.042000 -0.056525 -0.067949 -v 0.042000 -0.053042 -0.077600 -v 0.042000 -0.023722 -0.087894 -v 0.042000 -0.020848 -0.087803 -v 0.042000 -0.048252 -0.077821 -v 0.042000 -0.044753 -0.080240 -v 0.042000 -0.043749 -0.082934 -v 0.042000 -0.026223 -0.089312 -v 0.042000 -0.024629 -0.088230 -v 0.042000 -0.054669 -0.078063 -v 0.042000 -0.043688 -0.083244 -v 0.042000 -0.043579 -0.083540 -v 0.042000 -0.027038 -0.089780 -v 0.042000 -0.026743 -0.089668 -v 0.042000 -0.043229 -0.084064 -v 0.042000 -0.037058 -0.082880 -v 0.042000 -0.042996 -0.084278 -v 0.037225 -0.056328 -0.076221 -v 0.040079 -0.056332 -0.076209 -v 0.038102 -0.056987 -0.074412 -v 0.042000 -0.057474 -0.073073 -v 0.039832 -0.048370 -0.071770 -v 0.039943 -0.056773 -0.074998 -v 0.039308 -0.048509 -0.071389 -v 0.039376 -0.056958 -0.074490 -v 0.038813 -0.048559 -0.071255 -v 0.038762 -0.057016 -0.074328 -v 0.038286 -0.048545 -0.071288 -v 0.037808 -0.048473 -0.071488 -v 0.037567 -0.056860 -0.074757 -v 0.037312 -0.048295 -0.071978 -v 0.037274 -0.056712 -0.075165 -v 0.037152 -0.056544 -0.075626 -v 0.037216 -0.047822 -0.073133 -v 0.037604 -0.047562 -0.073634 -v 0.037656 -0.056112 -0.076813 -v 0.038263 -0.056005 -0.077106 -v 0.038783 -0.055990 -0.077148 -v 0.039282 -0.056036 -0.077022 -v 0.039717 -0.056139 -0.076739 -v 0.039800 -0.047623 -0.073547 -v 0.040149 -0.056555 -0.075598 -v 0.040123 -0.047916 -0.072973 -v 0.035000 -0.057522 -0.072938 -v 0.042000 -0.055805 -0.077652 -v 0.035000 -0.055813 -0.077634 -v 0.042000 -0.055196 -0.078096 -v 0.035000 -0.054794 -0.078098 -v 0.032000 -0.056310 -0.067498 -v 0.034899 -0.052178 -0.077474 -v 0.034744 -0.051390 -0.077420 -v 0.034598 -0.052661 -0.075919 -v 0.034169 -0.049944 -0.077465 -v 0.032411 -0.047174 -0.078228 -v 0.032607 -0.056611 -0.066954 -v 0.033312 -0.056524 -0.067774 -v 0.033725 -0.051964 -0.075246 -v 0.032959 -0.049356 -0.076946 -v 0.032000 -0.051604 -0.074854 -v 0.034912 -0.056983 -0.071377 -v 0.034469 -0.054537 -0.073425 -v 0.033749 -0.055597 -0.070427 -v 0.032829 -0.055195 -0.070233 -v 0.032783 -0.051667 -0.074922 -v 0.032783 -0.053600 -0.072699 -v 0.033730 -0.053953 -0.072969 -v 0.034298 -0.052359 -0.075615 -v 0.034819 -0.055108 -0.073825 -v 0.035000 -0.054823 -0.075712 -v 0.006000 -0.002060 0.153985 -v 0.021000 -0.001571 0.151682 -v 0.002000 -0.054552 0.145175 -v 0.002000 -0.006124 0.153866 -v 0.002000 -0.017547 0.152896 -v 0.002000 -0.058303 0.139623 -v 0.040000 -0.005483 0.150850 -v 0.040000 -0.058303 0.139623 -v 0.040000 -0.050161 0.146466 -v 0.040000 -0.017547 0.152896 -v 0.036000 -0.001571 0.151682 -v 0.037035 -0.001689 0.151657 -v 0.038297 -0.002264 0.151535 -v 0.038445 -0.002892 0.153971 -v 0.039064 -0.002968 0.151385 -v 0.039464 -0.003527 0.151266 -v 0.039331 -0.003852 0.153944 -v 0.039939 -0.004804 0.150995 -v 0.002061 -0.004804 0.150995 -v 0.002536 -0.003527 0.151266 -v 0.002936 -0.002968 0.151385 -v 0.002742 -0.003746 0.153950 -v 0.004000 -0.002095 0.151571 -v 0.003693 -0.002783 0.153972 -v 0.003429 -0.002486 0.151488 -v 0.004952 -0.002183 0.153984 -v 0.039939 -0.058983 0.139479 -v 0.040002 -0.059170 0.143002 -v 0.039759 -0.059642 0.139339 -v 0.039464 -0.060260 0.139207 -v 0.039622 -0.060590 0.142067 -v 0.039064 -0.060818 0.139089 -v 0.038858 -0.061553 0.141396 -v 0.036000 -0.062600 0.140598 -v 0.037451 -0.062401 0.140768 -v 0.037018 -0.062102 0.138816 -v 0.004962 -0.062098 0.138817 -v 0.004951 -0.062510 0.140669 -v 0.003693 -0.061517 0.138940 -v 0.002665 -0.061040 0.141761 -v 0.002241 -0.059642 0.139339 -v 0.002061 -0.058983 0.139479 -v 0.002104 -0.059905 0.142515 -v 0.010900 -0.064450 -0.055835 -v 0.029130 -0.064312 -0.055885 -v 0.009642 -0.061473 -0.057496 -v 0.032390 -0.059341 -0.059879 -v 0.033629 -0.058655 -0.061219 -v 0.033793 -0.058465 -0.061590 -v 0.029000 -0.065539 -0.055514 -v 0.029009 -0.065174 -0.055612 -v 0.026928 -0.073137 -0.048214 -v 0.016000 -0.070308 -0.037658 -v 0.029001 -0.074008 -0.051469 -v 0.010999 -0.074006 -0.051461 -v 0.012122 -0.072461 -0.045692 -v 0.012000 -0.072102 -0.044350 -v 0.020000 -0.070031 -0.036623 -v 0.022736 -0.070156 -0.037089 -v 0.024000 -0.070308 -0.037658 -v 0.025142 -0.070515 -0.038430 -v 0.026128 -0.070771 -0.039383 -v 0.027878 -0.071742 -0.043008 -v 0.027878 -0.072461 -0.045692 -v 0.026928 -0.071066 -0.040486 -v 0.012122 -0.071742 -0.043008 -v 0.012482 -0.071393 -0.041707 -v 0.011000 -0.071153 -0.040809 -v 0.013872 -0.070771 -0.039383 -v 0.007362 -0.069587 -0.031524 -v 0.008049 -0.069472 -0.032538 -v 0.030951 -0.069493 -0.034037 -v 0.030128 -0.069733 -0.035500 -v 0.009563 -0.069645 -0.034953 -v 0.009199 -0.069518 -0.034287 -v 0.030000 -0.072262 -0.052677 -v 0.010000 -0.072969 -0.051452 -v 0.010000 -0.072719 -0.052554 -v 0.019305 -0.073965 -0.052102 -v 0.018611 -0.055230 -0.057027 -v 0.017264 -0.055137 -0.056678 -v 0.023887 -0.073917 -0.051117 -v 0.025142 -0.073688 -0.050269 -v 0.025142 -0.054777 -0.055337 -v 0.026128 -0.073432 -0.049317 -v 0.026928 -0.054226 -0.053281 -v 0.027518 -0.053899 -0.052060 -v 0.027518 -0.072810 -0.046993 -v 0.027878 -0.053550 -0.050759 -v 0.028000 -0.072102 -0.044350 -v 0.027878 -0.052831 -0.048075 -v 0.027518 -0.071393 -0.041707 -v 0.026928 -0.052156 -0.045553 -v 0.026128 -0.051860 -0.044450 -v 0.024000 -0.051398 -0.042725 -v 0.022736 -0.051245 -0.042156 -v 0.020000 -0.051120 -0.041690 -v 0.021389 -0.070062 -0.036740 -v 0.018611 -0.051152 -0.041807 -v 0.017264 -0.051245 -0.042156 -v 0.018611 -0.070062 -0.036740 -v 0.017264 -0.070156 -0.037089 -v 0.016000 -0.051398 -0.042725 -v 0.014858 -0.070515 -0.038430 -v 0.014858 -0.051605 -0.043497 -v 0.013872 -0.051860 -0.044450 -v 0.013072 -0.071066 -0.040486 -v 0.012122 -0.052831 -0.048075 -v 0.012000 -0.053191 -0.049417 -v 0.012482 -0.072810 -0.046993 -v 0.012482 -0.053899 -0.052060 -v 0.013072 -0.054226 -0.053281 -v 0.013072 -0.073137 -0.048214 -v 0.013872 -0.073432 -0.049317 -v 0.014858 -0.073688 -0.050269 -v 0.016000 -0.054984 -0.056109 -v 0.016101 -0.073914 -0.051109 -v 0.018093 -0.073996 -0.051886 -v 0.017036 -0.073995 -0.051535 -v 0.021389 -0.073982 -0.052002 -v 0.021908 -0.073996 -0.051886 -v 0.022736 -0.073999 -0.051625 -v 0.020695 -0.073965 -0.052102 -v 0.020000 -0.073958 -0.052135 -v 0.029001 -0.073957 -0.052134 -v 0.011000 -0.073960 -0.052126 -v 0.029000 -0.073735 -0.052711 -v 0.011001 -0.073810 -0.052578 -v 0.011000 -0.073342 -0.053198 -v 0.029000 -0.073342 -0.053198 -v 0.011000 -0.073089 -0.053391 -v 0.029000 -0.072821 -0.053536 -v 0.011000 -0.072521 -0.053643 -v 0.030801 -0.069383 -0.036251 -v 0.030626 -0.069480 -0.036728 -v 0.030413 -0.069631 -0.037659 -v 0.030056 -0.070065 -0.040318 -v 0.030000 -0.065280 -0.054548 -v 0.009992 -0.064963 -0.054677 -v 0.009823 -0.069842 -0.038955 -v 0.009970 -0.070032 -0.040170 -v 0.009875 -0.064032 -0.055106 -v 0.009766 -0.069769 -0.038506 -v 0.009707 -0.069692 -0.038031 -v 0.009260 -0.069432 -0.036439 -v 0.007180 -0.069471 -0.031860 -v 0.006000 -0.070057 -0.029730 -v 0.030008 -0.069794 -0.035739 -v 0.031196 -0.069314 -0.035268 -v 0.031300 -0.069459 -0.033477 -v 0.031544 -0.069242 -0.034433 -v 0.032298 -0.069341 -0.032883 -v 0.031820 -0.069507 -0.032717 -v 0.032486 -0.069366 -0.032498 -v 0.032615 -0.069581 -0.031556 -v 0.032992 -0.069711 -0.031059 -v 0.033135 -0.069646 -0.031303 -v 0.033788 -0.069927 -0.030101 -v 0.030182 -0.069795 -0.038678 -v 0.030000 -0.070187 -0.041068 -v 0.029429 -0.070238 -0.037397 -v 0.030000 -0.073111 -0.051984 -v 0.029000 -0.071153 -0.040809 -v 0.029000 -0.073870 -0.052430 -v 0.029000 -0.073560 -0.052968 -v 0.029000 -0.073089 -0.053391 -v 0.029000 -0.072521 -0.053643 -v 0.030048 -0.064613 -0.054827 -v 0.030965 -0.061709 -0.056743 -v 0.029748 -0.062519 -0.056755 -v 0.030145 -0.063919 -0.055163 -v 0.029359 -0.063442 -0.056252 -v 0.030432 -0.062908 -0.055780 -v 0.032818 -0.059288 -0.059839 -v 0.032166 -0.059542 -0.059615 -v 0.032315 -0.059848 -0.059006 -v 0.031762 -0.060464 -0.058087 -v 0.031706 -0.060551 -0.057993 -v 0.031299 -0.060317 -0.058595 -v 0.030444 -0.061366 -0.057584 -v 0.031191 -0.061355 -0.057125 -v 0.009993 -0.069794 -0.035738 -v 0.008799 -0.069321 -0.035265 -v 0.008977 -0.069391 -0.034581 -v 0.007691 -0.069372 -0.032885 -v 0.007008 -0.069709 -0.031058 -v 0.008495 -0.069265 -0.034543 -v 0.008365 -0.069241 -0.034234 -v 0.009600 -0.069630 -0.037650 -v 0.010000 -0.070187 -0.041068 -v 0.010616 -0.070330 -0.037738 -v 0.009194 -0.069394 -0.036204 -v 0.011000 -0.072821 -0.053536 -v 0.011000 -0.073559 -0.052969 -v 0.011000 -0.065539 -0.055514 -v 0.010000 -0.065280 -0.054548 -v 0.010990 -0.065174 -0.055612 -v 0.007552 -0.059712 -0.059227 -v 0.007390 -0.059179 -0.060141 -v 0.008293 -0.060552 -0.057994 -v 0.008233 -0.060458 -0.058095 -v 0.008614 -0.060228 -0.058696 -v 0.007829 -0.059555 -0.059623 -v 0.009921 -0.064388 -0.054931 -v 0.010673 -0.063537 -0.056208 -v 0.010265 -0.062550 -0.056737 -v 0.009598 -0.062995 -0.055715 -v 0.007055 -0.059173 -0.060052 -v 0.006754 -0.058807 -0.060923 -v 0.006372 -0.058651 -0.061216 -v 0.009068 -0.061771 -0.056686 -v 0.008502 -0.060880 -0.057642 -v 0.027891 -0.016663 -0.088602 -v 0.028405 -0.016622 -0.088610 -v 0.029137 -0.016014 -0.088717 -v 0.029195 -0.015832 -0.082001 -v 0.029240 -0.015196 -0.082000 -v 0.029220 -0.015014 -0.089057 -v 0.028622 -0.014320 -0.082000 -v 0.028077 -0.014157 -0.089528 -v 0.028000 -0.014156 -0.082000 -v 0.027539 -0.014250 -0.089467 -v 0.026854 -0.014906 -0.089112 -v 0.026769 -0.015201 -0.088986 -v 0.026780 -0.015054 -0.082000 -v 0.026750 -0.015422 -0.088903 -v 0.026807 -0.015832 -0.088770 -v 0.027282 -0.016473 -0.082000 -v 0.031062 -0.015751 -0.088794 -v 0.031526 -0.016168 -0.088691 -v 0.031738 -0.016222 -0.080223 -v 0.032451 -0.014924 -0.089102 -v 0.031136 -0.014926 -0.089103 -v -0.000000 -0.025470 -0.088707 -v 0.042000 -0.025470 -0.088707 -v 0.042000 -0.022773 -0.087709 -v -0.000000 -0.023722 -0.087894 -v 0.042000 -0.021807 -0.087678 -v -0.000000 -0.022773 -0.087709 -v -0.000000 -0.020848 -0.087803 -v 0.021684 -0.037130 -0.086519 -v 0.020316 -0.033598 -0.087804 -v 0.019714 -0.033924 -0.087685 -v 0.019468 -0.034156 -0.087601 -v 0.021347 -0.033513 -0.087835 -v 0.021000 -0.033484 -0.087845 -v 0.020653 -0.037215 -0.086488 -v 0.008250 -0.037398 -0.086421 -v 0.008607 -0.037163 -0.086506 -v 0.008915 -0.036874 -0.086612 -v 0.009349 -0.034560 -0.087454 -v -0.000000 -0.028282 -0.089739 -v 0.007855 -0.033156 -0.087965 -v 0.034145 -0.037571 -0.086358 -v 0.037462 -0.034956 -0.087310 -v 0.037349 -0.034560 -0.087454 -v 0.036607 -0.033564 -0.087816 -v 0.036250 -0.033329 -0.087902 -v 0.009349 -0.036167 -0.086869 -v 0.009500 -0.035364 -0.087161 -v 0.033393 -0.037163 -0.086506 -v 0.035000 -0.037713 -0.086306 -v 0.042000 -0.042446 -0.084584 -v 0.035855 -0.037571 -0.086358 -v 0.042000 -0.028282 -0.089739 -v 0.035434 -0.033050 -0.088003 -v 0.005750 -0.033329 -0.087902 -v 0.005393 -0.033564 -0.087816 -v 0.004835 -0.034189 -0.087589 -v 0.022532 -0.034156 -0.087601 -v 0.032835 -0.034189 -0.087589 -v 0.036607 -0.037163 -0.086506 -v 0.037165 -0.036538 -0.086734 -v 0.037462 -0.035772 -0.087013 -v 0.037500 -0.035364 -0.087161 -v 0.035000 -0.033015 -0.088016 -v 0.022286 -0.033924 -0.087685 -v 0.034566 -0.033050 -0.088003 -v 0.034145 -0.033156 -0.087965 -v 0.004651 -0.036167 -0.086869 -v 0.005393 -0.037163 -0.086506 -v 0.006145 -0.037571 -0.086358 -v 0.019714 -0.036804 -0.086637 -v 0.020316 -0.037130 -0.086519 -v 0.004651 -0.034560 -0.087454 -v 0.004500 -0.035364 -0.087161 -v 0.019268 -0.034424 -0.087503 -v 0.005085 -0.036874 -0.086612 -v 0.032651 -0.036167 -0.086869 -v 0.032835 -0.036538 -0.086734 -v 0.000000 -0.042446 -0.084584 -v 0.032538 -0.035772 -0.087013 -v 0.032500 -0.035364 -0.087161 -v 0.022996 -0.035560 -0.087090 -v 0.032538 -0.034956 -0.087310 -v 0.032651 -0.034560 -0.087454 -v 0.022948 -0.034909 -0.087327 -v 0.022732 -0.034424 -0.087503 -v 0.007855 -0.037571 -0.086358 -v 0.000000 -0.046895 -0.078322 -v 0.000000 -0.046081 -0.078843 -v 0.032000 -0.046895 -0.078322 -v 0.032122 -0.046749 -0.078403 -v 0.042000 -0.046081 -0.078843 -v 0.042000 -0.045361 -0.079488 -v 0.000000 -0.045361 -0.079488 -v 0.042000 -0.044274 -0.081079 -v 0.042000 -0.043937 -0.081985 -v 0.000000 -0.044274 -0.081079 -v -0.000000 -0.021807 -0.087678 -v -0.000000 -0.026786 -0.086346 -v 0.000000 -0.043937 -0.081985 -v 0.000000 -0.044753 -0.080240 -v -0.000000 -0.024629 -0.088230 -v 0.000000 -0.037058 -0.082880 -v 0.000000 -0.042996 -0.084278 -v -0.000000 -0.027977 -0.089823 -v 0.000000 -0.043749 -0.082934 -v 0.000000 -0.043579 -0.083540 -v -0.000000 -0.026223 -0.089312 -v -0.000000 -0.027348 -0.089844 -v 0.000000 -0.043688 -0.083244 -v 0.000000 -0.043425 -0.083816 -v 0.000000 -0.043229 -0.084064 -v 0.042000 -0.043425 -0.083816 -v 0.000000 -0.042733 -0.084452 -v 0.042000 -0.042733 -0.084453 -v -0.000000 -0.027663 -0.089859 -v 0.042000 -0.027977 -0.089823 -v 0.042000 -0.027663 -0.089859 -v 0.042000 -0.027348 -0.089844 -v -0.000000 -0.027038 -0.089780 -v -0.000000 -0.026743 -0.089668 -v -0.000000 -0.026469 -0.089511 -v 0.042000 -0.026469 -0.089511 -v 0.034566 -0.034257 -0.076922 -v 0.033393 -0.033743 -0.077109 -v 0.033085 -0.033454 -0.077215 -v 0.033750 -0.033978 -0.077024 -v 0.032538 -0.032352 -0.077616 -v 0.035000 -0.031430 -0.076353 -v 0.032538 -0.031536 -0.077913 -v 0.032835 -0.030769 -0.078192 -v 0.034145 -0.029736 -0.078568 -v 0.033750 -0.029909 -0.078505 -v 0.036607 -0.030144 -0.078419 -v 0.037349 -0.031140 -0.078057 -v 0.036915 -0.030434 -0.078314 -v 0.037462 -0.032352 -0.077616 -v 0.036915 -0.033454 -0.077215 -v 0.035855 -0.034151 -0.076961 -v 0.036250 -0.033978 -0.077024 -v 0.035434 -0.034257 -0.076922 -v 0.035000 -0.034293 -0.076909 -v 0.034145 -0.034151 -0.076961 -v 0.034566 -0.037677 -0.086319 -v 0.033750 -0.037398 -0.086421 -v 0.033085 -0.036874 -0.086612 -v 0.032835 -0.033118 -0.077337 -v 0.032651 -0.032747 -0.077472 -v 0.032500 -0.031944 -0.077764 -v 0.032651 -0.031140 -0.078057 -v 0.033085 -0.030434 -0.078314 -v 0.033393 -0.030144 -0.078419 -v 0.033085 -0.033854 -0.087711 -v 0.033393 -0.033564 -0.087816 -v 0.033750 -0.033329 -0.087902 -v 0.034566 -0.029630 -0.078606 -v 0.035000 -0.029594 -0.078619 -v 0.035434 -0.029630 -0.078606 -v 0.035855 -0.029736 -0.078568 -v 0.036250 -0.029909 -0.078505 -v 0.035855 -0.033156 -0.087965 -v 0.036915 -0.033854 -0.087711 -v 0.037165 -0.030769 -0.078192 -v 0.037165 -0.034189 -0.087589 -v 0.037462 -0.031536 -0.077913 -v 0.037500 -0.031944 -0.077764 -v 0.037349 -0.032747 -0.077472 -v 0.037349 -0.036167 -0.086869 -v 0.037165 -0.033118 -0.077337 -v 0.036607 -0.033743 -0.077109 -v 0.036915 -0.036874 -0.086612 -v 0.036250 -0.037398 -0.086421 -v 0.035434 -0.037677 -0.086319 -v 0.006566 -0.034257 -0.076922 -v 0.006145 -0.034151 -0.076961 -v 0.004835 -0.033118 -0.077337 -v 0.007000 -0.031430 -0.076353 -v 0.004538 -0.031536 -0.077913 -v 0.004651 -0.031140 -0.078057 -v 0.004500 -0.031944 -0.077764 -v 0.006566 -0.029630 -0.078606 -v 0.007000 -0.029594 -0.078619 -v 0.008915 -0.030434 -0.078314 -v 0.008250 -0.029909 -0.078505 -v 0.008607 -0.030144 -0.078419 -v 0.009165 -0.030769 -0.078192 -v 0.009500 -0.031944 -0.077764 -v 0.009462 -0.032352 -0.077616 -v 0.008915 -0.033454 -0.077215 -v 0.009349 -0.032747 -0.077472 -v 0.009165 -0.033118 -0.077337 -v 0.007855 -0.034151 -0.076961 -v 0.006566 -0.037677 -0.086319 -v 0.005750 -0.033978 -0.077024 -v 0.005393 -0.033743 -0.077109 -v 0.005750 -0.037398 -0.086421 -v 0.005085 -0.033454 -0.077215 -v 0.004835 -0.036538 -0.086734 -v 0.004651 -0.032747 -0.077472 -v 0.004538 -0.032352 -0.077616 -v 0.004538 -0.035772 -0.087013 -v 0.004538 -0.034956 -0.087310 -v 0.004835 -0.030769 -0.078192 -v 0.005085 -0.030434 -0.078314 -v 0.005085 -0.033854 -0.087711 -v 0.005393 -0.030144 -0.078419 -v 0.005750 -0.029909 -0.078505 -v 0.006145 -0.033156 -0.087965 -v 0.006145 -0.029736 -0.078568 -v 0.006566 -0.033050 -0.088003 -v 0.007434 -0.029630 -0.078606 -v 0.007000 -0.033015 -0.088016 -v 0.007434 -0.033050 -0.088003 -v 0.007855 -0.029736 -0.078568 -v 0.008250 -0.033329 -0.087902 -v 0.008607 -0.033564 -0.087816 -v 0.008915 -0.033854 -0.087711 -v 0.009165 -0.034189 -0.087589 -v 0.009349 -0.031140 -0.078057 -v 0.009462 -0.031536 -0.077913 -v 0.009462 -0.034956 -0.087310 -v 0.009462 -0.035772 -0.087013 -v 0.009165 -0.036538 -0.086734 -v 0.008607 -0.033743 -0.077109 -v 0.008250 -0.033978 -0.077024 -v 0.007434 -0.037677 -0.086319 -v 0.007434 -0.034257 -0.076922 -v 0.007000 -0.034293 -0.076909 -v 0.007000 -0.037713 -0.086306 -v 0.021000 -0.031533 -0.076635 -v 0.020452 -0.030130 -0.078424 -v 0.021000 -0.030064 -0.078448 -v 0.022000 -0.030316 -0.078357 -v 0.021000 -0.037243 -0.086477 -v 0.020182 -0.033666 -0.077137 -v 0.020000 -0.036991 -0.086569 -v 0.019604 -0.033298 -0.077271 -v 0.019337 -0.036419 -0.086777 -v 0.019196 -0.032769 -0.077463 -v 0.019121 -0.036007 -0.086927 -v 0.019004 -0.032140 -0.077692 -v 0.018998 -0.035503 -0.087111 -v 0.019068 -0.034852 -0.087347 -v 0.019052 -0.031488 -0.077929 -v 0.019337 -0.030888 -0.078148 -v 0.019823 -0.030415 -0.078320 -v 0.020000 -0.033736 -0.087754 -v 0.020653 -0.033513 -0.087835 -v 0.021488 -0.030115 -0.078429 -v 0.021684 -0.033598 -0.087804 -v 0.022000 -0.033736 -0.087754 -v 0.022395 -0.030588 -0.078257 -v 0.022804 -0.031117 -0.078064 -v 0.022970 -0.031617 -0.077883 -v 0.023002 -0.032083 -0.077713 -v 0.022830 -0.032716 -0.077482 -v 0.022804 -0.036189 -0.086860 -v 0.022532 -0.033152 -0.077325 -v 0.022532 -0.036572 -0.086722 -v 0.022179 -0.033470 -0.077208 -v 0.022286 -0.036804 -0.086637 -v 0.022000 -0.036991 -0.086569 -v 0.021554 -0.033756 -0.077105 -v 0.021347 -0.037215 -0.086488 -v 0.020860 -0.033824 -0.077079 -v 0.032614 -0.015474 -0.088879 -v 0.032202 -0.016117 -0.080223 -v 0.031214 -0.015970 -0.080224 -v 0.031034 -0.015192 -0.080243 -v 0.031301 -0.014800 -0.080223 -v 0.031810 -0.014601 -0.080223 -v 0.032448 -0.014906 -0.080224 -v 0.028732 -0.016463 -0.082000 -v 0.029029 -0.014698 -0.082000 -v 0.027281 -0.014368 -0.082000 -v 0.028006 -0.016680 -0.082000 -v 0.026808 -0.015842 -0.082000 -v 0.032530 -0.015775 -0.080227 -v 0.032586 0.015192 -0.080243 -v 0.032319 0.014800 -0.080224 -v 0.031914 0.014621 -0.080222 -v 0.031433 0.014699 -0.080225 -v 0.031093 0.015052 -0.089049 -v 0.031011 0.015379 -0.080252 -v 0.032192 0.016124 -0.080223 -v 0.032546 0.015754 -0.080233 -v 0.029017 0.014683 -0.082000 -v 0.028313 0.016633 -0.082000 -v 0.028628 0.014321 -0.082000 -v 0.027370 0.016512 -0.082000 -v 0.027468 0.014261 -0.082000 -v 0.124653 0.086004 0.030817 -v 0.123994 0.086490 0.032030 -v 0.120967 0.088560 0.038778 -v 0.121736 0.088058 0.036806 -v 0.042131 0.096496 0.049380 -v 0.119039 0.089744 0.047763 -v 0.042131 0.096081 0.042241 -v 0.119722 0.089335 0.043029 -v 0.042131 0.094839 0.035199 -v 0.119763 0.089311 0.042830 -v 0.119773 0.089305 0.085652 -v 0.119856 0.089254 0.086001 -v 0.118991 0.089772 0.079060 -v 0.119183 0.089659 0.082306 -v 0.121152 0.088441 0.090168 -v 0.042131 0.094306 0.095326 -v 0.122544 0.087511 0.093462 -v 0.126170 0.084834 0.100230 -v 0.042131 0.091605 0.103095 -v 0.042131 0.087892 0.110433 -v 0.130378 0.081197 0.106586 -v 0.129314 0.072599 0.117637 -v 0.042131 0.071423 0.128609 -v 0.123849 0.067181 0.122841 -v 0.126433 0.069855 0.120463 -v 0.042131 0.077710 0.123306 -v 0.137314 0.077535 0.010787 -v 0.133224 0.080697 0.018430 -v 0.123026 0.057102 -0.049011 -v 0.117794 0.056625 -0.051659 -v 0.079271 0.055356 -0.064999 -v 0.113587 0.056301 -0.053626 -v 0.102491 0.055680 -0.058170 -v 0.096810 0.055485 -0.060160 -v 0.160006 0.057105 0.029137 -v 0.158384 0.058230 0.002879 -v 0.158608 0.058585 0.006007 -v 0.158942 0.058236 0.010023 -v 0.156802 0.050006 -0.019624 -v 0.155997 0.046371 -0.027279 -v 0.155542 0.046362 -0.029851 -v 0.155336 0.024276 -0.039762 -v 0.153367 0.031703 -0.047261 -v 0.153904 0.036928 -0.043012 -v 0.155662 0.016160 -0.039710 -v 0.155857 0.007826 -0.039679 -v 0.153298 -0.004211 -0.051862 -v 0.153228 -0.009050 -0.051788 -v 0.155837 -0.009051 -0.039682 -v 0.155622 -0.017362 -0.039716 -v 0.153367 -0.031703 -0.047261 -v 0.153518 -0.033171 -0.046067 -v 0.156561 -0.040494 -0.027171 -v 0.155837 -0.047085 -0.027805 -v 0.154524 -0.043866 -0.036921 -v 0.157808 -0.047313 -0.014486 -v 0.155911 -0.047309 -0.027176 -v 0.158468 -0.040494 -0.014337 -v 0.158608 -0.058585 0.006007 -v 0.160319 -0.053580 0.023992 -v 0.160006 -0.057105 0.029137 -v 0.161132 0.046371 0.024261 -v 0.161228 0.047636 0.037165 -v 0.161368 0.046371 0.037216 -v 0.161869 0.040827 0.037400 -v 0.161763 0.039463 0.024470 -v 0.162419 0.033525 0.037602 -v 0.162301 0.032073 0.024648 -v 0.162523 0.032073 0.037641 -v 0.162731 0.024276 0.024790 -v 0.162949 0.024276 0.037797 -v 0.163258 0.016160 0.037911 -v 0.163044 0.016160 0.024894 -v 0.163408 0.009437 0.037966 -v 0.163444 0.007826 0.037979 -v 0.163232 0.007826 0.024956 -v 0.163439 -0.007438 0.037978 -v 0.163288 -0.000616 0.024975 -v 0.163213 -0.009051 0.024950 -v 0.163425 -0.009051 0.037972 -v 0.163260 -0.015781 0.037912 -v 0.163006 -0.017362 0.024882 -v 0.162535 -0.031723 0.037645 -v 0.162452 -0.033179 0.037614 -v 0.162229 -0.033179 0.024624 -v 0.159833 -0.017362 -0.014028 -v 0.157936 -0.017362 -0.026906 -v 0.160123 -0.000616 -0.013962 -v 0.158169 0.007826 -0.026861 -v 0.157652 0.024276 -0.026961 -v 0.159551 0.024276 -0.014092 -v 0.159108 0.032073 -0.014192 -v 0.158556 0.039463 -0.014317 -v 0.157908 0.046371 -0.014463 -v 0.157131 -0.033179 -0.027061 -v 0.154813 -0.033179 -0.039845 -v 0.155278 -0.025438 -0.039771 -v 0.157594 -0.025438 -0.026972 -v 0.158149 -0.009051 -0.026865 -v 0.155915 -0.000616 -0.039670 -v 0.158228 -0.000616 -0.026850 -v 0.157975 0.016160 -0.026899 -v 0.154888 0.032073 -0.039833 -v 0.157206 0.032073 -0.027047 -v 0.154329 0.039463 -0.039922 -v 0.156650 0.039463 -0.027154 -v 0.161907 -0.040494 0.037414 -v 0.159303 -0.047313 -0.001618 -v 0.159034 -0.033179 -0.014209 -v 0.160519 -0.033179 -0.001301 -v 0.159493 -0.025438 -0.014105 -v 0.161312 -0.017362 -0.001095 -v 0.160045 -0.009051 -0.013980 -v 0.161522 -0.009051 -0.001040 -v 0.161599 -0.000616 -0.001020 -v 0.160065 0.007826 -0.013975 -v 0.159872 0.016160 -0.014019 -v 0.159401 0.046371 -0.001593 -v 0.157495 0.052736 -0.012070 -v 0.158677 0.052744 -0.001781 -v 0.161036 -0.047313 0.024229 -v 0.161272 -0.047313 0.037181 -v 0.160694 -0.052420 0.036969 -v 0.160563 -0.053580 0.036921 -v 0.160120 -0.056981 0.036758 -v 0.161027 -0.040494 0.011483 -v 0.161677 -0.040494 0.024441 -v 0.161584 -0.033179 0.011647 -v 0.162675 -0.025438 0.024772 -v 0.162370 -0.017362 0.011880 -v 0.162578 -0.009051 0.011941 -v 0.162408 0.016160 0.011891 -v 0.161114 0.039463 0.011508 -v 0.160476 0.046371 0.011320 -v 0.160422 0.052744 0.024026 -v 0.159654 -0.053580 0.011078 -v 0.158572 -0.053580 -0.001808 -v 0.160379 -0.047313 0.011291 -v 0.159957 -0.040494 -0.001448 -v 0.162035 -0.025438 0.011781 -v 0.160974 -0.025438 -0.001183 -v 0.161541 0.007826 -0.001035 -v 0.162655 -0.000616 0.011964 -v 0.162597 0.007826 0.011947 -v 0.161350 0.016160 -0.001084 -v 0.161031 0.024276 -0.001168 -v 0.162092 0.024276 0.011798 -v 0.160592 0.032073 -0.001282 -v 0.161657 0.032073 0.011669 -v 0.160044 0.039463 -0.001425 -v 0.158198 0.056522 -0.001718 -v 0.159759 0.052744 0.011108 -v 0.158609 0.058581 0.069781 -v 0.159233 0.053902 0.070065 -v 0.160147 -0.052422 0.059102 -v 0.159831 -0.057294 0.052038 -v 0.158722 -0.058466 0.068646 -v 0.158676 -0.058216 0.069806 -v 0.158963 -0.058215 0.065816 -v 0.154357 -0.062689 0.100263 -v 0.157011 -0.052422 0.092152 -v 0.155126 -0.055569 0.102057 -v 0.158246 -0.039127 0.092812 -v 0.157665 -0.046046 0.092501 -v 0.156491 -0.041748 0.102942 -v 0.156095 -0.046041 0.102674 -v 0.157516 -0.023910 0.103755 -v 0.157916 -0.010666 0.104097 -v 0.157781 -0.015780 0.103980 -v 0.159421 -0.015781 0.093441 -v 0.159637 0.001007 0.093556 -v 0.158008 -0.000074 0.104179 -v 0.157892 0.011946 0.104077 -v 0.157735 0.017737 0.103940 -v 0.159364 0.017738 0.093410 -v 0.157276 0.029563 0.103553 -v 0.159051 0.025800 0.093243 -v 0.158631 0.033525 0.093018 -v 0.158115 0.040828 0.092742 -v 0.157513 0.047637 0.092420 -v 0.155967 0.047636 0.102581 -v 0.156841 0.053902 0.092061 -v 0.154590 0.059586 0.101780 -v 0.157620 0.059586 0.078898 -v 0.159831 0.057294 0.052038 -v 0.160120 0.056981 0.036758 -v 0.160400 0.053902 0.047969 -v 0.160666 0.052744 0.036958 -v 0.161992 0.039463 0.037445 -v 0.161741 0.040828 0.048505 -v 0.161108 0.047637 0.048252 -v 0.163198 0.017737 0.037889 -v 0.162866 0.025800 0.037767 -v 0.162286 0.033525 0.048722 -v 0.163057 0.017738 0.049030 -v 0.163295 -0.007438 0.049126 -v 0.163344 0.001007 0.049145 -v 0.163500 -0.000616 0.038000 -v 0.163489 0.001007 0.037996 -v 0.162817 -0.023911 0.048934 -v 0.162894 -0.025438 0.037777 -v 0.162956 -0.023911 0.037800 -v 0.163221 -0.017362 0.037897 -v 0.163117 -0.015781 0.049055 -v 0.161390 -0.046045 0.037224 -v 0.161880 -0.039127 0.048560 -v 0.162009 -0.039126 0.037452 -v 0.162400 -0.031723 0.048768 -v 0.160828 -0.046046 0.059395 -v 0.161433 -0.039127 0.059657 -v 0.160080 -0.046046 0.070459 -v 0.160677 -0.039127 0.070736 -v 0.161592 -0.023911 0.071162 -v 0.162656 -0.015781 0.060185 -v 0.161886 -0.015781 0.071299 -v 0.162059 -0.007438 0.071380 -v 0.162801 0.009437 0.060248 -v 0.162029 0.009437 0.071366 -v 0.162271 0.025800 0.060019 -v 0.161505 0.025800 0.071122 -v 0.161296 0.040828 0.059597 -v 0.160542 0.040828 0.070674 -v 0.160670 0.047637 0.059327 -v 0.159924 0.047637 0.070386 -v 0.161268 -0.046046 0.048316 -v 0.161947 -0.031723 0.059879 -v 0.162359 -0.023911 0.060057 -v 0.162832 -0.007438 0.060261 -v 0.162880 0.001007 0.060282 -v 0.163264 0.009437 0.049113 -v 0.162596 0.017738 0.060159 -v 0.162728 0.025800 0.048899 -v 0.161834 0.033525 0.059830 -v 0.159970 0.053902 0.059025 -v 0.160579 -0.052422 0.048041 -v 0.156299 -0.058216 0.091772 -v 0.158362 -0.052422 0.081166 -v 0.159025 -0.046046 0.081497 -v 0.160117 -0.031723 0.082042 -v 0.160517 -0.023911 0.082242 -v 0.158741 -0.031723 0.093076 -v 0.159136 -0.023911 0.093288 -v 0.159590 -0.007438 0.093531 -v 0.161026 0.001007 0.082496 -v 0.159561 0.009437 0.093515 -v 0.160949 0.009437 0.082458 -v 0.160749 0.017738 0.082358 -v 0.160432 0.025800 0.082199 -v 0.159482 0.040828 0.081724 -v 0.158871 0.047637 0.081420 -v 0.158189 0.053902 0.081079 -v 0.156112 0.059588 0.091672 -v 0.157640 -0.058216 0.080806 -v 0.159408 -0.052422 0.070146 -v 0.159615 -0.039127 0.081791 -v 0.161186 -0.031723 0.070973 -v 0.160807 -0.015781 0.082387 -v 0.160978 -0.007438 0.082472 -v 0.162107 0.001007 0.071402 -v 0.161827 0.017738 0.071271 -v 0.161074 0.033525 0.070921 -v 0.160006 0.033525 0.081986 -v 0.129894 -0.059307 0.124483 -v 0.151670 0.038193 0.112976 -v 0.108379 0.042243 0.135631 -v 0.065421 0.006898 0.147257 -v 0.058936 0.001770 0.148012 -v 0.080404 0.014398 0.144798 -v 0.095760 0.031906 0.140342 -v 0.101804 0.036859 0.138243 -v 0.112783 0.042062 0.134207 -v 0.117482 0.041851 0.132533 -v 0.121924 0.053340 0.129080 -v 0.126850 0.057255 0.126302 -v 0.137252 0.054160 0.121427 -v 0.133813 0.054477 0.123310 -v 0.144000 0.065394 0.114922 -v 0.143351 0.053518 0.117617 -v 0.149588 0.054190 0.112572 -v 0.150620 0.039497 0.113824 -v 0.148440 0.039737 0.115733 -v 0.150620 0.026369 0.115199 -v 0.153450 0.010693 0.113274 -v 0.153023 0.020977 0.113215 -v 0.150620 -0.026369 0.115199 -v 0.150620 -0.039497 0.113824 -v 0.151265 -0.041912 0.112897 -v 0.151515 -0.039389 0.112945 -v 0.148440 -0.052875 0.113800 -v 0.146019 -0.053196 0.115706 -v 0.143086 -0.065980 0.115451 -v 0.126156 -0.055097 0.126991 -v 0.126850 -0.057255 0.126302 -v 0.130114 -0.054790 0.125168 -v 0.121943 -0.041633 0.130796 -v 0.121924 -0.053340 0.129080 -v 0.126156 -0.041407 0.129005 -v 0.112783 -0.042062 0.134207 -v 0.112777 -0.045844 0.133697 -v 0.113463 -0.046406 0.133395 -v 0.117482 -0.041851 0.132533 -v 0.117469 -0.049688 0.131428 -v 0.101804 -0.036859 0.138243 -v 0.107857 -0.028217 0.137279 -v 0.107856 -0.041814 0.135862 -v 0.091872 -0.028576 0.141569 -v 0.095760 -0.031906 0.140342 -v 0.097383 -0.028464 0.140237 -v 0.091872 -0.014300 0.142464 -v 0.086201 -0.024057 0.143133 -v 0.089592 -0.026844 0.142222 -v 0.080404 -0.014398 0.144798 -v 0.080399 -0.019281 0.144533 -v 0.086204 -0.014351 0.143689 -v 0.080404 0.000000 0.145098 -v 0.074496 0.000000 0.146084 -v 0.068502 -0.009451 0.146780 -v 0.071954 -0.012311 0.146246 -v 0.057207 -0.000074 0.148175 -v 0.062460 0.000000 0.147662 -v 0.068506 0.000000 0.146940 -v 0.062458 -0.004434 0.147604 -v 0.065421 -0.006898 0.147257 -v 0.126156 0.041407 0.129005 -v 0.126156 0.055097 0.126991 -v 0.130114 0.041176 0.127170 -v 0.130114 0.054790 0.125168 -v 0.133813 0.040941 0.125301 -v 0.140430 0.053840 0.119526 -v 0.146019 0.053196 0.115706 -v 0.148440 0.052875 0.113800 -v 0.150720 0.046368 0.112789 -v 0.124238 -0.055237 0.127814 -v 0.133813 -0.054477 0.123310 -v 0.137252 -0.054160 0.121427 -v 0.137252 -0.040703 0.123406 -v 0.140430 -0.040462 0.121494 -v 0.140430 -0.053840 0.119526 -v 0.143351 -0.053518 0.117617 -v 0.143351 -0.040220 0.119574 -v 0.150612 -0.046872 0.112769 -v 0.107709 0.041695 0.135926 -v 0.107857 0.028217 0.137279 -v 0.121943 0.041633 0.130796 -v 0.121943 0.027795 0.132245 -v 0.130114 0.027491 0.128603 -v 0.137252 0.040703 0.123406 -v 0.137252 0.027175 0.124823 -v 0.140430 0.040462 0.121494 -v 0.140430 0.027014 0.122903 -v 0.143351 0.040220 0.119574 -v 0.146019 0.026691 0.119042 -v 0.146019 0.039978 0.117651 -v 0.148440 0.026530 0.117115 -v 0.152439 0.029715 0.113119 -v 0.108379 -0.042243 0.135631 -v 0.112783 -0.028082 0.135671 -v 0.126156 -0.027645 0.130446 -v 0.130114 -0.041176 0.127170 -v 0.130114 -0.027491 0.128603 -v 0.133813 -0.040941 0.125301 -v 0.133813 -0.027334 0.126726 -v 0.140430 -0.027014 0.122903 -v 0.146019 -0.026691 0.119042 -v 0.146019 -0.039978 0.117651 -v 0.148440 -0.039737 0.115733 -v 0.091872 0.028576 0.141569 -v 0.091872 0.014300 0.142464 -v 0.097383 0.014244 0.141128 -v 0.097383 0.028464 0.140237 -v 0.107857 0.014121 0.138163 -v 0.102718 0.028344 0.138804 -v 0.112783 0.014053 0.136551 -v 0.112783 0.028082 0.135671 -v 0.117482 0.027941 0.133990 -v 0.117482 0.013983 0.134865 -v 0.126156 0.013835 0.131312 -v 0.126156 0.027645 0.130446 -v 0.130114 0.013757 0.129464 -v 0.133813 0.013679 0.127582 -v 0.133813 0.027334 0.126726 -v 0.137252 0.013599 0.125674 -v 0.140430 0.013519 0.123749 -v 0.143351 0.013438 0.121814 -v 0.143351 0.026853 0.120973 -v 0.148440 0.013276 0.117946 -v 0.152569 0.026210 0.113298 -v 0.097383 -0.014244 0.141128 -v 0.102718 -0.028344 0.138804 -v 0.102718 -0.014184 0.139692 -v 0.112783 -0.014053 0.136551 -v 0.117482 -0.013983 0.134865 -v 0.117482 -0.027941 0.133990 -v 0.121943 -0.013910 0.133115 -v 0.121943 -0.027795 0.132245 -v 0.126156 -0.013835 0.131312 -v 0.137252 -0.027175 0.124823 -v 0.140430 -0.013519 0.123749 -v 0.143351 -0.026852 0.120973 -v 0.143351 -0.013438 0.121814 -v 0.148440 -0.026530 0.117115 -v 0.152569 -0.026210 0.113298 -v 0.153002 -0.021363 0.113211 -v 0.086204 0.000000 0.143989 -v 0.086204 0.014351 0.143689 -v 0.091872 0.000000 0.142762 -v 0.097383 0.000000 0.141426 -v 0.102718 0.000000 0.139988 -v 0.102718 0.014184 0.139692 -v 0.112783 0.000000 0.136844 -v 0.121943 0.000000 0.133406 -v 0.121943 0.013910 0.133115 -v 0.130114 0.000000 0.129751 -v 0.133813 0.000000 0.127867 -v 0.137252 0.000000 0.125958 -v 0.143351 0.000000 0.122095 -v 0.146019 0.000000 0.120157 -v 0.146019 0.013357 0.119878 -v 0.148440 0.000000 0.118223 -v 0.150620 0.000000 0.116300 -v 0.150620 0.013196 0.116025 -v 0.152569 0.013117 0.114118 -v 0.107857 -0.014121 0.138163 -v 0.107857 0.000000 0.138458 -v 0.117482 0.000000 0.135157 -v 0.126156 0.000000 0.131601 -v 0.130114 -0.013757 0.129464 -v 0.133813 -0.013679 0.127582 -v 0.137252 -0.013599 0.125674 -v 0.140430 0.000000 0.124031 -v 0.146019 -0.013357 0.119878 -v 0.148440 -0.013276 0.117946 -v 0.150620 -0.013196 0.116025 -v 0.152569 -0.013117 0.114118 -v 0.152569 0.000000 0.114392 -v 0.042131 -0.096081 0.042241 -v 0.119290 -0.089596 0.045325 -v 0.042131 -0.094839 0.035199 -v 0.123360 -0.086946 0.033259 -v 0.121748 -0.088048 0.036809 -v 0.042131 -0.071423 0.128609 -v 0.126433 -0.069855 0.120463 -v 0.042131 -0.077710 0.123306 -v 0.129314 -0.072599 0.117637 -v 0.126170 -0.084834 0.100230 -v 0.126165 -0.084838 0.100221 -v 0.128185 -0.083167 0.103401 -v 0.130315 -0.081253 0.106495 -v 0.042131 -0.083232 0.117211 -v 0.119955 -0.089193 0.086357 -v 0.118991 -0.089772 0.079060 -v 0.119039 -0.089744 0.080684 -v 0.119183 -0.089659 0.082306 -v 0.139744 -0.062105 -0.030987 -v 0.140669 -0.064863 -0.023173 -v 0.142018 -0.070961 -0.006071 -v 0.142260 -0.073030 -0.000326 -v 0.125389 -0.085610 0.029923 -v 0.067190 -0.055658 -0.067261 -v 0.042131 -0.092788 0.028348 -v 0.085197 -0.055322 -0.063577 -v 0.113587 -0.056301 -0.053626 -v 0.074612 0.047909 -0.075275 -v 0.063332 0.048522 -0.076895 -v 0.081418 0.039401 -0.079448 -v 0.095053 0.030803 -0.081224 -v 0.098589 0.036699 -0.076714 -v 0.110404 0.034997 -0.074043 -v 0.122089 0.033054 -0.070992 -v 0.122078 0.032336 -0.071409 -v 0.117010 0.031537 -0.073834 -v 0.122041 0.041601 -0.065373 -v 0.133573 0.039419 -0.061948 -v 0.134639 0.034023 -0.065108 -v 0.133337 0.047689 -0.055933 -v 0.143142 0.045639 -0.052662 -v 0.117397 0.049961 -0.061080 -v 0.119991 0.050184 -0.059849 -v 0.105641 0.049212 -0.065964 -v 0.098552 0.045244 -0.071092 -v 0.068231 0.049035 -0.075709 -v 0.086630 0.046700 -0.073377 -v 0.081034 0.048746 -0.073290 -v 0.087315 0.048733 -0.071766 -v 0.121830 0.049866 -0.059351 -v 0.110362 0.043544 -0.068423 -v 0.086661 0.038155 -0.079000 -v 0.062366 0.047684 -0.077564 -v 0.042131 0.050268 -0.077966 -v 0.042131 0.047601 -0.079644 -v 0.062605 0.050724 -0.075284 -v 0.062329 0.049583 -0.076270 -v 0.063229 0.052015 -0.073924 -v 0.042131 0.056426 -0.070885 -v 0.064212 0.053309 -0.072209 -v 0.066299 0.055112 -0.068789 -v 0.067190 0.055658 -0.067261 -v 0.092624 -0.015726 -0.085798 -v 0.042131 -0.037616 -0.084270 -v 0.069711 -0.043081 -0.079230 -v 0.085985 -0.032103 -0.082234 -v 0.093951 -0.025973 -0.083409 -v 0.093725 -0.018470 -0.085209 -v 0.042131 -0.027189 -0.087789 -v 0.091013 -0.010541 -0.086649 -v 0.091672 -0.012914 -0.086302 -v 0.089811 -0.003152 -0.087276 -v 0.090032 -0.005275 -0.087161 -v 0.090466 -0.008060 -0.086935 -v 0.089931 0.004474 -0.087214 -v 0.042131 0.016442 -0.090158 -v 0.092498 0.027123 -0.083226 -v 0.096461 0.023988 -0.083724 -v 0.092622 0.015727 -0.085799 -v 0.042131 0.037616 -0.084270 -v 0.080060 0.036385 -0.081181 -v 0.042131 0.027189 -0.087789 -v 0.074254 0.040301 -0.080084 -v 0.079631 0.036695 -0.081105 -v 0.062567 0.046762 -0.078065 -v 0.064114 -0.053180 -0.072380 -v 0.042131 -0.056426 -0.070885 -v 0.065625 -0.054599 -0.069898 -v 0.066299 -0.055112 -0.068789 -v 0.062291 -0.049222 -0.076546 -v 0.042131 -0.050268 -0.077966 -v 0.118896 0.061265 0.127133 -v 0.098541 0.040599 0.138033 -v 0.103922 0.045963 0.135628 -v 0.042131 0.053503 0.138394 -v 0.042131 0.064485 0.133027 -v 0.109122 0.051199 0.133005 -v 0.075416 0.017882 0.145335 -v 0.042131 0.042079 0.142742 -v 0.087312 0.029525 0.142159 -v 0.063283 0.006023 0.147482 -v 0.042131 -0.006112 0.149355 -v 0.058936 -0.001770 0.148012 -v 0.042131 -0.018285 0.148246 -v 0.076984 -0.019414 0.145003 -v 0.082958 -0.025257 0.143463 -v 0.092998 -0.035117 0.140213 -v 0.042131 -0.042079 0.142742 -v 0.042131 -0.030307 0.146035 -v 0.087312 -0.029525 0.142159 -v 0.042131 -0.053503 0.138394 -v 0.042131 -0.064485 0.133027 -v 0.109122 -0.051199 0.133005 -v 0.074612 -0.047909 -0.075275 -v 0.081034 -0.048746 -0.073290 -v 0.086630 -0.046700 -0.073377 -v 0.093511 -0.048807 -0.070036 -v 0.119991 -0.050184 -0.059849 -v 0.110362 -0.043544 -0.068423 -v 0.111568 -0.049543 -0.063623 -v 0.127397 -0.050905 -0.056115 -v 0.138031 -0.052265 -0.049897 -v 0.133337 -0.047689 -0.055933 -v 0.142021 -0.034760 -0.061150 -v 0.098589 -0.036699 -0.076714 -v 0.095053 -0.030803 -0.081224 -v 0.062962 -0.047506 -0.077612 -v 0.074636 -0.043223 -0.078424 -v 0.133573 -0.039419 -0.061948 -v 0.121830 -0.049866 -0.059351 -v 0.124339 -0.032692 -0.070327 -v 0.081418 -0.039401 -0.079448 -v 0.086661 -0.038155 -0.079000 -v 0.098552 -0.045244 -0.071092 -v 0.110404 -0.034997 -0.074043 -v 0.122089 -0.033054 -0.070992 -v 0.122041 -0.041601 -0.065373 -v 0.144289 0.000000 -0.063703 -v 0.132257 0.000000 -0.069910 -v 0.106991 0.000000 -0.081342 -v 0.106991 0.013961 -0.081116 -v 0.098631 0.015662 -0.084390 -v 0.094749 0.004394 -0.086123 -v 0.096588 0.011234 -0.085309 -v 0.095504 -0.007890 -0.085790 -v 0.106984 -0.021434 -0.080791 -v 0.106991 -0.013961 -0.081116 -v 0.097456 -0.013294 -0.084920 -v 0.111652 -0.022336 -0.078808 -v 0.119723 -0.013783 -0.075621 -v 0.132257 -0.013591 -0.069690 -v 0.144121 -0.014859 -0.063526 -v 0.144276 -0.004234 -0.063688 -v 0.136449 0.025825 -0.067007 -v 0.119723 0.013783 -0.075621 -v 0.132257 0.013591 -0.069690 -v 0.129095 0.024999 -0.070715 -v 0.132248 0.025353 -0.069125 -v 0.104265 0.020909 -0.081946 -v 0.119723 0.000000 -0.075844 -v 0.144205 0.010548 -0.063614 -v 0.152965 0.069358 0.073579 -v 0.155324 0.066948 0.044099 -v 0.155392 0.066875 0.036814 -v 0.155258 0.067018 0.029534 -v 0.148680 0.073251 0.014394 -v 0.151770 0.070513 0.081431 -v 0.148061 0.073878 0.098652 -v 0.142158 0.078466 0.024563 -v 0.127580 0.087017 0.043568 -v 0.126475 0.087525 0.042954 -v 0.124926 0.088209 0.081275 -v 0.125412 0.087998 0.083491 -v 0.133041 0.084227 0.092909 -v 0.130668 0.085499 0.037756 -v 0.141160 -0.079164 0.099222 -v 0.143363 -0.077585 0.022866 -v 0.148706 -0.073281 0.014466 -v 0.153406 -0.068920 0.005806 -v 0.151770 -0.070513 0.081431 -v 0.150313 -0.071867 0.089395 -v 0.153870 -0.068453 0.066191 -v 0.154369 -0.067945 0.014869 -v 0.154918 -0.067375 0.022227 -v 0.155050 -0.067237 0.051409 -v 0.137969 -0.081303 0.029963 -v 0.133032 -0.084211 0.035368 -v 0.132404 -0.084581 0.036056 -v 0.129446 -0.086117 0.089400 -v 0.126225 -0.087638 0.085098 -v 0.127999 -0.086819 0.043165 -v 0.124926 -0.088209 0.081275 -v 0.124439 -0.088417 0.079060 -v 0.124959 -0.088195 0.046186 -v 0.065048 -0.007344 0.147283 -v 0.063283 -0.006023 0.147482 -v 0.064860 -0.007567 0.147289 -v 0.075416 -0.017882 0.145335 -v 0.077475 -0.018837 0.145030 -v 0.074510 -0.014422 0.145750 -v 0.071620 -0.012713 0.146272 -v 0.078447 -0.017673 0.144988 -v 0.084886 -0.022977 0.143486 -v 0.083608 -0.024505 0.143525 -v 0.088083 -0.028643 0.142255 -v 0.093936 -0.034068 0.140364 -v 0.094859 -0.032995 0.140407 -v 0.097375 -0.033229 0.139781 -v 0.091863 -0.028708 0.141530 -v 0.106489 -0.043163 0.136020 -v 0.100745 -0.038136 0.138320 -v 0.107709 -0.041695 0.135926 -v 0.102712 -0.037602 0.137886 -v 0.098477 -0.040536 0.138059 -v 0.098541 -0.040599 0.138033 -v 0.103922 -0.045963 0.135628 -v 0.105222 -0.044591 0.135920 -v 0.117485 -0.052846 0.130798 -v 0.114117 -0.056299 0.130173 -v 0.120066 -0.060181 0.127468 -v 0.120847 -0.059458 0.127691 -v 0.070946 -0.013515 0.146279 -v 0.077963 -0.018256 0.145025 -v 0.084252 -0.023744 0.143532 -v 0.088844 -0.027749 0.142276 -v 0.099655 -0.039386 0.138250 -v 0.110620 -0.049675 0.133380 -v 0.112074 -0.048069 0.133511 -v 0.115831 -0.054629 0.130637 -v 0.119049 -0.050982 0.130652 -v 0.136677 -0.063106 0.120128 -v 0.140192 -0.064759 0.117647 -v 0.138403 -0.073419 0.114493 -v 0.137422 -0.069505 0.117446 -v 0.138904 -0.067196 0.117723 -v 0.134016 -0.073524 0.115871 -v 0.136416 -0.075217 0.113631 -v 0.134645 -0.077009 0.112019 -v 0.134265 -0.076904 0.112206 -v 0.132172 -0.075140 0.114609 -v 0.135446 -0.065283 0.120212 -v 0.135780 -0.071631 0.116824 -v 0.134067 -0.067360 0.119997 -v 0.132049 -0.063208 0.122504 -v 0.130762 -0.065056 0.122355 -v 0.129122 -0.072417 0.117824 -v 0.133223 -0.061284 0.122406 -v 0.129382 -0.066798 0.121960 -v 0.127570 -0.062607 0.124515 -v 0.128774 -0.060986 0.124600 -v 0.122717 -0.057496 0.127879 -v 0.125780 -0.058702 0.126441 -v 0.124646 -0.060106 0.126416 -v 0.132565 -0.069295 0.119489 -v 0.130971 -0.071053 0.118697 -v 0.126295 -0.064150 0.124229 -v 0.123459 -0.061452 0.126228 -v 0.122231 -0.062728 0.125878 -v 0.127932 -0.068406 0.121326 -v 0.123849 -0.067181 0.122841 -v 0.124967 -0.065596 0.123744 -v 0.123602 -0.066925 0.123069 -v 0.120975 -0.063921 0.125369 -v 0.118896 -0.061265 0.127133 -v 0.136025 -0.080526 0.105386 -v 0.138664 -0.078421 0.108081 -v 0.137799 -0.080511 0.103337 -v 0.134127 -0.080179 0.107290 -v 0.132149 -0.079480 0.109006 -v 0.130378 -0.081197 0.106586 -v 0.132226 -0.081763 0.104976 -v 0.139409 -0.080136 0.101189 -v 0.140819 -0.079409 0.098992 -v 0.138614 -0.080887 0.097408 -v 0.137233 -0.081575 0.099396 -v 0.134549 -0.083228 0.097039 -v 0.135885 -0.082593 0.095313 -v 0.132092 -0.084630 0.094696 -v 0.129880 -0.083576 0.101944 -v 0.127731 -0.085107 0.098939 -v 0.125825 -0.086367 0.096010 -v 0.124381 -0.086207 0.097127 -v 0.123014 -0.087190 0.094481 -v 0.122544 -0.087511 0.093462 -v 0.122065 -0.087840 0.092423 -v 0.121152 -0.088441 0.090168 -v 0.120426 -0.088902 0.088047 -v 0.119856 -0.089254 0.086001 -v 0.119773 -0.089305 0.085652 -v 0.119425 -0.089515 0.083953 -v 0.134008 -0.082017 0.103217 -v 0.131523 -0.083723 0.100381 -v 0.123869 -0.087568 0.092551 -v 0.122013 -0.088629 0.088472 -v 0.120776 -0.089295 0.084518 -v 0.121919 -0.089111 0.084140 -v 0.120237 -0.089574 0.081340 -v 0.135688 -0.081954 0.101345 -v 0.129251 -0.085165 0.097575 -v 0.127239 -0.086351 0.094843 -v 0.125177 -0.087481 0.091619 -v 0.128607 -0.086158 0.093637 -v 0.123222 -0.088482 0.087820 -v 0.133088 -0.083606 0.098737 -v 0.130710 -0.085005 0.096155 -v 0.129914 -0.085789 0.092405 -v 0.126451 -0.087258 0.090663 -v 0.127680 -0.086898 0.089692 -v 0.124407 -0.088233 0.087156 -v 0.121902 -0.089239 0.081101 -v 0.123387 -0.088823 0.079060 -v 0.133376 -0.084046 0.093219 -v 0.133041 -0.084227 0.092909 -v 0.131148 -0.085250 0.091161 -v 0.128265 -0.086692 0.088026 -v 0.127129 -0.087226 0.086519 -v 0.125560 -0.087882 0.086485 -v 0.123608 -0.088669 0.083594 -v 0.125464 -0.087975 0.083608 -v 0.140186 -0.077306 0.108962 -v 0.142822 -0.076045 0.108258 -v 0.142822 -0.068380 0.114925 -v 0.142822 -0.077108 0.105899 -v 0.140454 -0.078566 0.105677 -v 0.142414 -0.077990 0.103552 -v 0.136517 -0.078005 0.110093 -v 0.142822 -0.070702 0.113783 -v 0.141746 -0.068636 0.115533 -v 0.140291 -0.071217 0.115103 -v 0.140186 -0.073742 0.113349 -v 0.140186 -0.075713 0.111310 -v 0.142822 -0.072794 0.112259 -v 0.137347 -0.076478 0.111931 -v 0.142822 -0.074593 0.110399 -v 0.071954 0.012311 0.146246 -v 0.071620 0.012713 0.146272 -v 0.062458 0.004434 0.147604 -v 0.068502 0.009451 0.146780 -v 0.064860 0.007567 0.147289 -v 0.070946 0.013515 0.146279 -v 0.074529 0.014438 0.145747 -v 0.077719 0.018546 0.145028 -v 0.076984 0.019414 0.145003 -v 0.083608 0.024505 0.143525 -v 0.089592 0.026844 0.142222 -v 0.084886 0.022977 0.143486 -v 0.084252 0.023744 0.143532 -v 0.078447 0.017673 0.144988 -v 0.088844 0.027749 0.142276 -v 0.091705 0.028578 0.141578 -v 0.082958 0.025257 0.143463 -v 0.088083 0.028643 0.142255 -v 0.087203 0.029418 0.142191 -v 0.093936 0.034068 0.140364 -v 0.094859 0.032995 0.140407 -v 0.097375 0.033229 0.139781 -v 0.092998 0.035117 0.140213 -v 0.099655 0.039386 0.138250 -v 0.098477 0.040536 0.138059 -v 0.100745 0.038136 0.138320 -v 0.106489 0.043163 0.136020 -v 0.112074 0.048069 0.133511 -v 0.113463 0.046406 0.133395 -v 0.119049 0.050982 0.130652 -v 0.117485 0.052846 0.130798 -v 0.124238 0.055237 0.127814 -v 0.120847 0.059458 0.127691 -v 0.109095 0.051172 0.133018 -v 0.105222 0.044591 0.135920 -v 0.110620 0.049675 0.133380 -v 0.115831 0.054629 0.130637 -v 0.114117 0.056299 0.130173 -v 0.118991 -0.089772 0.049380 -v 0.120110 -0.089639 0.079060 -v 0.122313 -0.089163 0.079060 -v 0.121219 -0.089436 0.079060 -v 0.146000 -0.064072 0.113658 -v 0.149026 -0.072043 0.103643 -v 0.147271 -0.063231 0.112854 -v 0.149182 -0.069005 0.107906 -v 0.148876 -0.067163 0.109757 -v 0.149464 -0.070450 0.105720 -v 0.148462 -0.065070 0.111270 -v 0.145003 -0.070084 0.112211 -v 0.144000 -0.065394 0.114922 -v 0.144497 -0.067910 0.113797 -v 0.145319 -0.072034 0.110304 -v 0.145383 -0.073738 0.108161 -v 0.145192 -0.075168 0.105833 -v 0.148698 -0.073071 0.101243 -v 0.144751 -0.076289 0.103359 -v 0.143954 -0.077164 0.100828 -v 0.138403 0.073419 0.114493 -v 0.136464 0.075383 0.113443 -v 0.134265 0.076904 0.112206 -v 0.137422 0.069505 0.117446 -v 0.143086 0.065980 0.115451 -v 0.140192 0.064759 0.117647 -v 0.138904 0.067196 0.117723 -v 0.132172 0.075140 0.114609 -v 0.134016 0.073524 0.115871 -v 0.129123 0.072417 0.117824 -v 0.136677 0.063106 0.120128 -v 0.123602 0.066925 0.123069 -v 0.120975 0.063921 0.125369 -v 0.135446 0.065283 0.120212 -v 0.132049 0.063208 0.122504 -v 0.128774 0.060986 0.124600 -v 0.129894 0.059307 0.124483 -v 0.133223 0.061284 0.122406 -v 0.122231 0.062728 0.125878 -v 0.120066 0.060181 0.127468 -v 0.130971 0.071053 0.118697 -v 0.135780 0.071631 0.116824 -v 0.132565 0.069295 0.119489 -v 0.127932 0.068406 0.121326 -v 0.124967 0.065596 0.123744 -v 0.126295 0.064150 0.124229 -v 0.123459 0.061452 0.126228 -v 0.127570 0.062607 0.124515 -v 0.130762 0.065056 0.122355 -v 0.129382 0.066798 0.121960 -v 0.134067 0.067360 0.119997 -v 0.122717 0.057496 0.127879 -v 0.125780 0.058702 0.126441 -v 0.124646 0.060106 0.126416 -v 0.121762 -0.089284 0.049380 -v 0.120851 -0.089511 0.049380 -v 0.119004 -0.089765 0.048549 -v 0.119098 -0.089709 0.046952 -v 0.120968 -0.089455 0.047212 -v 0.119527 -0.089454 0.043937 -v 0.119731 -0.089330 0.043030 -v 0.119930 -0.089209 0.042146 -v 0.120455 -0.088884 0.040300 -v 0.121095 -0.088478 0.038427 -v 0.121224 -0.088394 0.038080 -v 0.124379 -0.087727 0.037141 -v 0.122673 -0.089058 0.049380 -v 0.121308 -0.089293 0.045139 -v 0.122167 -0.088873 0.042093 -v 0.123299 -0.088299 0.039280 -v 0.124855 -0.088100 0.041396 -v 0.125647 -0.087026 0.034955 -v 0.124653 -0.086004 0.030817 -v 0.122207 -0.087744 0.035694 -v 0.128606 -0.086279 0.035782 -v 0.124439 -0.088417 0.049380 -v 0.123053 -0.088896 0.046297 -v 0.126577 -0.087476 0.042846 -v 0.126472 -0.087346 0.038653 -v 0.129160 -0.086254 0.039386 -v 0.131488 -0.085072 0.036950 -v 0.150192 -0.071777 0.098706 -v 0.151630 -0.069805 0.099812 -v 0.154114 -0.062907 0.101553 -v 0.148099 -0.073834 0.098771 -v 0.155332 -0.063719 0.091378 -v 0.155825 -0.061334 0.091802 -v 0.158380 -0.060597 0.067275 -v 0.156582 -0.062477 0.083104 -v 0.158069 -0.059138 0.075246 -v 0.157058 -0.060146 0.083466 -v 0.159424 -0.057730 0.059739 -v 0.158977 -0.059948 0.059564 -v 0.159473 -0.057678 0.058814 -v 0.151983 -0.070119 0.089915 -v 0.154722 -0.066828 0.082299 -v 0.155369 -0.066726 0.066473 -v 0.156033 -0.066018 0.058973 -v 0.157268 -0.064125 0.059178 -v 0.157706 -0.063637 0.051675 -v 0.153843 -0.065137 0.099776 -v 0.152881 -0.067564 0.099852 -v 0.154517 -0.066007 0.090916 -v 0.155799 -0.064717 0.082713 -v 0.156848 -0.063621 0.074627 -v 0.157605 -0.061421 0.074948 -v 0.157643 -0.062766 0.067020 -v 0.158255 -0.062091 0.059375 -v 0.159389 -0.059492 0.051924 -v 0.159959 -0.057156 0.047800 -v 0.159623 -0.059231 0.044333 -v 0.160062 -0.057044 0.044385 -v 0.148711 -0.073286 0.096861 -v 0.153371 -0.068771 0.081869 -v 0.152965 -0.069358 0.073579 -v 0.154508 -0.067623 0.073936 -v 0.154568 -0.067739 0.058765 -v 0.156491 -0.065520 0.051543 -v 0.155324 -0.066948 0.044099 -v 0.155392 -0.066875 0.036814 -v 0.156750 -0.065235 0.044160 -v 0.157954 -0.063358 0.044220 -v 0.158917 -0.061346 0.044278 -v 0.158677 -0.061618 0.051803 -v 0.156634 -0.064820 0.066751 -v 0.155810 -0.065700 0.074288 -v 0.153393 -0.068154 0.090425 -v 0.158977 -0.061277 0.036779 -v 0.150115 -0.064200 0.109804 -v 0.149840 -0.062931 0.110527 -v 0.153206 -0.062993 0.104806 -v 0.150115 -0.071172 0.102659 -v 0.150115 -0.070322 0.104533 -v 0.150115 -0.069161 0.106233 -v 0.150115 -0.067723 0.107706 -v 0.150115 -0.066053 0.108908 -v 0.151881 -0.064832 0.106859 -v 0.153420 -0.063533 0.104069 -v 0.151881 -0.066167 0.105898 -v 0.153223 -0.065024 0.103384 -v 0.151881 -0.067315 0.104721 -v 0.153232 -0.065940 0.102067 -v 0.151881 -0.068243 0.103363 -v 0.151881 -0.068923 0.101865 -v 0.151372 -0.063006 0.108516 -v 0.150115 -0.071686 0.100665 -v 0.140312 0.071232 0.115087 -v 0.142822 0.072759 0.112290 -v 0.142822 0.077078 0.105985 -v 0.142091 0.068721 0.115295 -v 0.136534 0.078081 0.109969 -v 0.140435 0.078575 0.105686 -v 0.142524 0.077912 0.103640 -v 0.142822 0.070676 0.113799 -v 0.140186 0.073703 0.113382 -v 0.140186 0.075671 0.111362 -v 0.134825 0.076761 0.112249 -v 0.140186 0.077264 0.109036 -v 0.142822 0.074554 0.110447 -v 0.142822 0.076008 0.108325 -v 0.137347 0.076433 0.111987 -v 0.131133 -0.085157 0.034773 -v 0.128361 -0.085760 0.032264 -v 0.129780 -0.085552 0.033505 -v 0.140024 -0.079341 0.020266 -v 0.144887 -0.075665 0.012159 -v 0.146807 -0.074700 0.013461 -v 0.148531 -0.073444 0.014789 -v 0.141768 -0.078588 0.021555 -v 0.141132 -0.079123 0.025802 -v 0.138344 -0.076664 0.008656 -v 0.136205 -0.080047 0.017835 -v 0.134193 -0.079990 0.016733 -v 0.129860 -0.082976 0.023831 -v 0.127073 -0.086198 0.032757 -v 0.140614 -0.076657 0.009733 -v 0.138160 -0.079830 0.019019 -v 0.131616 -0.083092 0.024955 -v 0.133328 -0.082980 0.026147 -v 0.126892 -0.085779 0.031066 -v 0.142809 -0.076322 0.010908 -v 0.147894 -0.072241 0.002257 -v 0.149502 -0.071648 0.003141 -v 0.134972 -0.082641 0.027390 -v 0.136526 -0.082079 0.028668 -v 0.157992 -0.061396 0.006331 -v 0.156933 -0.064068 0.006685 -v 0.159719 -0.057414 0.021487 -v 0.158651 -0.060681 0.014031 -v 0.159255 -0.057908 0.013785 -v 0.159681 -0.059165 0.036768 -v 0.159414 -0.059831 0.029228 -v 0.158105 -0.062775 0.021838 -v 0.157616 -0.063321 0.014299 -v 0.159123 -0.060159 0.021656 -v 0.158408 -0.062434 0.029326 -v 0.158017 -0.063287 0.036790 -v 0.157011 -0.064849 0.029429 -v 0.155365 -0.066629 0.006230 -v 0.153603 -0.068723 0.007440 -v 0.156177 -0.065763 0.014580 -v 0.156692 -0.065201 0.022030 -v 0.155258 -0.067018 0.029534 -v 0.156816 -0.065163 0.036802 -v 0.148035 -0.062713 0.112326 -v 0.150227 0.060693 0.110622 -v 0.153864 0.060759 0.104131 -v 0.148452 0.060626 0.112384 -v 0.155297 0.054133 0.102155 -v 0.156112 0.046222 0.102674 -v 0.156543 0.040826 0.102987 -v 0.156766 0.038024 0.103149 -v 0.156256 0.038105 0.105338 -v 0.157037 0.033524 0.103364 -v 0.152621 0.026997 0.113148 -v 0.157179 0.020906 0.105929 -v 0.156787 0.029626 0.105672 -v 0.157650 0.020862 0.103867 -v 0.157438 0.025799 0.103689 -v 0.154720 0.012013 0.111662 -v 0.157433 0.011971 0.106098 -v 0.157459 0.010655 0.106115 -v 0.157999 0.001007 0.104171 -v 0.157927 0.009437 0.104107 -v 0.157556 -0.000074 0.106179 -v 0.157944 -0.007438 0.104122 -v 0.157458 -0.010688 0.106114 -v 0.153364 0.013081 0.113262 -v 0.153599 -0.000074 0.113292 -v 0.154755 0.010691 0.111669 -v 0.154754 -0.010725 0.111669 -v 0.153449 -0.010727 0.113273 -v 0.152614 -0.026887 0.113146 -v 0.153705 -0.031795 0.111432 -v 0.157165 -0.021291 0.105919 -v 0.157165 -0.031630 0.103463 -v 0.157636 -0.021245 0.103855 -v 0.152270 -0.031789 0.113089 -v 0.155969 -0.041835 0.105166 -v 0.156672 -0.031699 0.105598 -v 0.156666 -0.039125 0.103077 -v 0.152800 -0.041935 0.111204 -v 0.151055 -0.055683 0.110786 -v 0.149990 -0.051601 0.112647 -v 0.154754 0.046378 0.107122 -v 0.155531 0.020964 0.109817 -v 0.155837 0.012005 0.109916 -v 0.156773 0.010672 0.108066 -v 0.155867 -0.010718 0.109925 -v 0.156772 -0.010706 0.108066 -v 0.155514 -0.021350 0.109811 -v 0.154929 -0.031781 0.109612 -v 0.155923 -0.031749 0.107658 -v 0.154184 -0.051661 0.106886 -v 0.152505 -0.055723 0.108829 -v 0.153680 -0.055717 0.106695 -v 0.155591 -0.051505 0.102332 -v 0.149357 -0.055599 0.112531 -v 0.151733 0.060770 0.108633 -v 0.152702 0.054297 0.108885 -v 0.151268 0.054265 0.110833 -v 0.152305 0.046404 0.111079 -v 0.153657 0.046408 0.109179 -v 0.154441 0.038197 0.109444 -v 0.153166 0.038207 0.111297 -v 0.153857 0.029719 0.111468 -v 0.155065 0.029705 0.109659 -v 0.154377 0.020976 0.111589 -v 0.155867 0.010684 0.109926 -v 0.155985 -0.000074 0.109962 -v 0.154887 -0.000074 0.111695 -v 0.154358 -0.021362 0.111585 -v 0.151637 -0.051661 0.110917 -v 0.154109 -0.041929 0.109330 -v 0.153044 -0.051681 0.108986 -v 0.152596 -0.063006 0.106353 -v 0.154559 -0.055666 0.104424 -v 0.155038 -0.051602 0.104655 -v 0.155171 -0.041896 0.107307 -v 0.156454 -0.021326 0.107914 -v 0.156878 -0.000074 0.108116 -v 0.156745 0.011991 0.108053 -v 0.156469 0.020941 0.107921 -v 0.156047 0.029674 0.107718 -v 0.155477 0.038163 0.107447 -v 0.155577 0.046316 0.104941 -v 0.154736 0.054230 0.104506 -v 0.153865 0.054285 0.106763 -v 0.152953 0.060792 0.106455 -v 0.154762 -0.058211 0.101875 -v 0.148905 0.067145 0.109735 -v 0.149265 0.070617 0.105831 -v 0.149730 0.062975 0.110639 -v 0.147271 0.063231 0.112854 -v 0.148442 0.065068 0.111289 -v 0.144792 0.076258 0.103341 -v 0.145205 0.075160 0.105824 -v 0.148878 0.072165 0.103726 -v 0.144986 0.070100 0.112217 -v 0.148680 0.073089 0.101247 -v 0.149389 0.068846 0.107771 -v 0.145388 0.073735 0.108158 -v 0.145310 0.072042 0.110306 -v 0.146000 0.064072 0.113658 -v 0.144459 0.067911 0.113829 -v 0.144020 0.077112 0.100850 -v 0.141160 0.079164 0.099222 -v 0.134454 0.077064 0.111988 -v 0.132149 0.079480 0.109006 -v 0.130315 0.081253 0.106495 -v 0.128185 0.083167 0.103401 -v 0.129880 0.083576 0.101944 -v 0.139409 0.080136 0.101189 -v 0.140819 0.079409 0.098992 -v 0.138614 0.080887 0.097408 -v 0.137233 0.081575 0.099396 -v 0.135885 0.082593 0.095313 -v 0.133376 0.084046 0.093219 -v 0.132092 0.084630 0.094696 -v 0.124381 0.086207 0.097127 -v 0.123014 0.087190 0.094481 -v 0.122065 0.087840 0.092423 -v 0.131148 0.085250 0.091161 -v 0.129446 0.086117 0.089400 -v 0.128265 0.086692 0.088026 -v 0.127129 0.087226 0.086519 -v 0.126225 0.087638 0.085098 -v 0.124172 0.088491 0.083433 -v 0.137799 0.080511 0.103337 -v 0.134549 0.083228 0.097039 -v 0.133088 0.083606 0.098737 -v 0.130710 0.085005 0.096155 -v 0.128607 0.086158 0.093637 -v 0.129914 0.085789 0.092405 -v 0.128255 0.086622 0.090452 -v 0.126000 0.087685 0.087268 -v 0.124439 0.088417 0.079060 -v 0.122313 0.089163 0.079060 -v 0.138664 0.078421 0.108081 -v 0.136025 0.080526 0.105386 -v 0.135688 0.081954 0.101345 -v 0.134008 0.082017 0.103217 -v 0.131523 0.083723 0.100381 -v 0.129251 0.085165 0.097575 -v 0.127239 0.086351 0.094843 -v 0.127005 0.086984 0.091495 -v 0.124407 0.088233 0.087156 -v 0.123222 0.088482 0.087820 -v 0.122751 0.088856 0.084880 -v 0.121902 0.089239 0.081101 -v 0.134127 0.080179 0.107290 -v 0.132226 0.081763 0.104976 -v 0.127731 0.085107 0.098939 -v 0.125825 0.086367 0.096010 -v 0.125707 0.087200 0.092520 -v 0.124646 0.087763 0.090717 -v 0.123955 0.087513 0.092841 -v 0.120776 0.089295 0.084518 -v 0.120426 0.088902 0.088047 -v 0.119955 0.089193 0.086357 -v 0.122013 0.088629 0.088472 -v 0.119425 0.089515 0.083953 -v 0.119039 0.089744 0.080684 -v 0.120237 0.089574 0.081340 -v 0.120110 0.089639 0.079060 -v 0.068231 -0.049035 -0.075709 -v 0.067523 -0.054509 -0.069722 -v 0.065254 -0.054316 -0.070509 -v 0.064796 -0.051933 -0.073807 -v 0.064212 -0.053309 -0.072209 -v 0.063370 -0.051170 -0.074788 -v 0.063229 -0.052015 -0.073924 -v 0.065747 -0.050528 -0.074984 -v 0.062884 -0.051380 -0.074626 -v 0.062605 -0.050724 -0.075284 -v 0.062477 -0.050311 -0.075661 -v 0.062329 -0.049583 -0.076270 -v 0.062283 -0.048474 -0.077072 -v 0.062567 -0.046762 -0.078065 -v 0.066138 -0.053619 -0.071465 -v 0.068049 -0.051159 -0.073995 -v 0.067811 -0.052998 -0.071984 -v 0.063219 -0.048675 -0.076807 -v 0.158441 -0.058757 0.004297 -v 0.157719 -0.061470 0.003342 -v 0.147981 -0.071582 0.000009 -v 0.144787 -0.072953 0.000721 -v 0.146017 -0.072719 0.001310 -v 0.147220 -0.072489 0.001886 -v 0.150542 -0.070719 0.001863 -v 0.150523 -0.071059 0.003788 -v 0.154927 -0.067101 0.004369 -v 0.152904 -0.069290 0.004081 -v 0.152887 -0.069355 0.005423 -v 0.151580 -0.070449 0.004458 -v 0.156629 -0.064408 0.004134 -v 0.152933 -0.068801 0.001835 -v 0.150115 0.071672 0.100750 -v 0.151881 0.068903 0.101921 -v 0.154114 0.062907 0.101553 -v 0.150115 0.064188 0.109809 -v 0.151372 0.062960 0.108531 -v 0.150115 0.066032 0.108921 -v 0.150115 0.067695 0.107730 -v 0.150115 0.070292 0.104586 -v 0.150062 0.071195 0.102812 -v 0.153233 0.065524 0.102745 -v 0.151881 0.067291 0.104751 -v 0.151881 0.066145 0.105917 -v 0.153305 0.063892 0.104142 -v 0.152607 0.062987 0.106334 -v 0.151796 0.069589 0.099794 -v 0.151881 0.068219 0.103406 -v 0.150115 0.069130 0.106270 -v 0.151899 0.064741 0.106881 -v 0.118991 0.089772 0.049380 -v 0.123387 0.088823 0.079060 -v 0.124439 0.088417 0.049380 -v 0.121219 0.089436 0.079060 -v 0.122673 0.089058 0.049380 -v 0.099206 -0.028009 -0.081639 -v 0.093802 -0.029027 -0.082378 -v 0.092498 -0.027123 -0.083226 -v 0.086650 -0.036191 -0.080185 -v 0.088151 -0.035269 -0.080397 -v 0.080537 -0.038089 -0.080358 -v 0.075719 -0.042656 -0.078586 -v 0.074995 -0.041511 -0.079395 -v 0.070903 -0.045174 -0.077866 -v 0.066848 -0.047076 -0.077308 -v 0.066372 -0.046147 -0.077972 -v 0.080060 -0.036385 -0.081181 -v 0.087087 -0.033739 -0.081429 -v 0.079631 -0.036695 -0.081105 -v 0.074254 -0.040301 -0.080084 -v 0.070313 -0.044153 -0.078594 -v 0.065885 -0.045175 -0.078564 -v 0.074406 -0.050969 -0.072907 -v 0.137871 -0.058958 -0.040113 -v 0.138487 -0.059053 -0.039694 -v 0.139927 -0.058040 -0.041571 -v 0.141225 -0.056680 -0.043361 -v 0.142277 -0.055018 -0.045015 -v 0.143670 -0.053140 -0.046174 -v 0.136934 -0.054198 -0.048555 -v 0.132790 -0.051546 -0.053092 -v 0.131762 -0.053508 -0.051702 -v 0.135724 -0.055865 -0.046975 -v 0.134426 -0.057231 -0.045190 -v 0.133067 -0.058269 -0.043236 -v 0.126441 -0.052895 -0.054681 -v 0.125378 -0.054615 -0.052994 -v 0.130625 -0.055203 -0.050067 -v 0.124232 -0.056027 -0.051090 -v 0.129401 -0.056593 -0.048221 -v 0.128118 -0.057650 -0.046203 -v 0.121854 -0.050345 -0.058965 -v 0.118919 -0.055534 -0.053796 -v 0.117794 -0.056625 -0.051659 -v 0.123026 -0.057102 -0.049011 -v 0.120972 -0.052360 -0.057489 -v 0.108085 -0.055952 -0.055992 -v 0.114647 -0.055199 -0.055805 -v 0.109060 -0.054838 -0.058221 -v 0.115650 -0.053753 -0.057802 -v 0.119986 -0.054102 -0.055753 -v 0.117397 -0.049961 -0.061080 -v 0.116573 -0.051994 -0.059573 -v 0.104972 -0.051284 -0.064386 -v 0.110821 -0.051597 -0.062079 -v 0.104212 -0.053078 -0.062533 -v 0.103379 -0.054555 -0.060445 -v 0.109978 -0.053375 -0.060265 -v 0.105641 -0.049212 -0.065964 -v 0.098355 -0.052862 -0.064604 -v 0.097609 -0.054350 -0.062477 -v 0.096810 -0.055485 -0.060160 -v 0.102491 -0.055680 -0.058170 -v 0.099621 -0.048966 -0.068101 -v 0.099031 -0.051054 -0.066493 -v 0.092410 -0.052727 -0.066480 -v 0.093001 -0.050907 -0.068400 -v 0.086381 -0.052672 -0.068158 -v 0.085814 -0.054177 -0.065964 -v 0.091753 -0.054224 -0.064318 -v 0.091045 -0.055365 -0.061963 -v 0.087315 -0.048733 -0.071766 -v 0.080269 -0.052699 -0.069636 -v 0.086885 -0.050844 -0.070107 -v 0.079794 -0.054208 -0.067416 -v 0.074079 -0.052807 -0.070913 -v 0.080686 -0.050864 -0.071609 -v 0.073696 -0.054318 -0.068669 -v 0.073268 -0.055468 -0.066229 -v 0.079271 -0.055356 -0.064999 -v 0.074672 -0.048846 -0.074606 -v 0.154692 -0.064216 -0.004301 -v 0.144946 -0.070440 -0.006035 -v 0.145182 -0.072528 -0.000241 -v 0.154947 -0.066623 0.002300 -v 0.156304 -0.061839 -0.003530 -v 0.156553 -0.063997 0.002468 -v 0.158198 -0.056522 -0.001718 -v 0.147751 -0.069472 -0.005832 -v 0.144393 -0.067357 -0.014643 -v 0.147201 -0.066359 -0.014509 -v 0.150356 -0.068086 -0.005468 -v 0.152691 -0.066317 -0.004953 -v 0.149809 -0.064941 -0.014209 -v 0.152144 -0.063142 -0.013752 -v 0.154142 -0.061011 -0.013149 -v 0.154941 -0.055401 -0.021337 -v 0.155147 -0.049860 -0.028691 -v 0.156921 -0.055994 -0.011580 -v 0.156802 -0.050006 -0.019624 -v 0.157263 -0.051823 -0.014595 -v 0.157625 -0.053247 -0.010656 -v 0.142671 -0.061504 -0.031158 -v 0.143600 -0.064286 -0.023280 -v 0.141461 -0.067907 -0.014607 -v 0.144203 -0.057351 -0.040002 -v 0.145475 -0.060454 -0.031155 -v 0.149013 -0.061814 -0.022979 -v 0.146407 -0.063260 -0.023215 -v 0.150583 -0.070219 0.000417 -v 0.148076 -0.058984 -0.030977 -v 0.150403 -0.057133 -0.030630 -v 0.151345 -0.059986 -0.022579 -v 0.153340 -0.057829 -0.022027 -v 0.152393 -0.054954 -0.030124 -v 0.157484 -0.059251 -0.002661 -v 0.155749 -0.058606 -0.012419 -v 0.156106 -0.052769 -0.020529 -v 0.153989 -0.052507 -0.029471 -v 0.152737 0.067707 0.100520 -v 0.153462 0.065882 0.101024 -v 0.150192 0.071777 0.098706 -v 0.154357 0.062689 0.100263 -v 0.155332 0.063719 0.091378 -v 0.155825 0.061334 0.091802 -v 0.156582 0.062477 0.083104 -v 0.157058 0.060146 0.083466 -v 0.157450 0.059588 0.080711 -v 0.158069 0.059138 0.075246 -v 0.158834 0.058351 0.067512 -v 0.158380 0.060597 0.067275 -v 0.158977 0.059948 0.059564 -v 0.159424 0.057730 0.059739 -v 0.159623 0.059231 0.044333 -v 0.160062 0.057044 0.044385 -v 0.151809 0.069664 0.098675 -v 0.152988 0.067478 0.099244 -v 0.156848 0.063621 0.074627 -v 0.157643 0.062766 0.067020 -v 0.156634 0.064820 0.066751 -v 0.158255 0.062091 0.059375 -v 0.158677 0.061618 0.051803 -v 0.157706 0.063637 0.051675 -v 0.158917 0.061346 0.044278 -v 0.159389 0.059492 0.051924 -v 0.157605 0.061421 0.074948 -v 0.155799 0.064717 0.082713 -v 0.154517 0.066007 0.090916 -v 0.153843 0.065137 0.099776 -v 0.157954 0.063358 0.044220 -v 0.153393 0.068154 0.090425 -v 0.151983 0.070119 0.089915 -v 0.153371 0.068771 0.081869 -v 0.154722 0.066828 0.082299 -v 0.155810 0.065700 0.074288 -v 0.155369 0.066726 0.066473 -v 0.157268 0.064125 0.059178 -v 0.156033 0.066018 0.058973 -v 0.156491 0.065520 0.051543 -v 0.156750 0.065235 0.044160 -v 0.148711 0.073286 0.096861 -v 0.150313 0.071867 0.089395 -v 0.154508 0.067623 0.073936 -v 0.153870 0.068454 0.066191 -v 0.154568 0.067739 0.058765 -v 0.155050 0.067237 0.051409 -v 0.126346 0.086625 0.033850 -v 0.122688 0.087416 0.034641 -v 0.123959 0.087952 0.037934 -v 0.121825 0.088000 0.036578 -v 0.120287 0.088989 0.040851 -v 0.119421 0.089517 0.044507 -v 0.119181 0.089660 0.046147 -v 0.121509 0.089196 0.044279 -v 0.120851 0.089511 0.049380 -v 0.124908 0.087439 0.036196 -v 0.123016 0.088444 0.039906 -v 0.124604 0.088214 0.041885 -v 0.120981 0.089449 0.047215 -v 0.121762 0.089284 0.049380 -v 0.131488 0.085072 0.036950 -v 0.128591 0.086292 0.035776 -v 0.126530 0.087315 0.038587 -v 0.128504 0.086576 0.040142 -v 0.123098 0.088877 0.046193 -v 0.124887 0.088225 0.046645 -v 0.096461 -0.023988 -0.083724 -v 0.098485 -0.025707 -0.082896 -v 0.098677 -0.022868 -0.083651 -v 0.099893 -0.021562 -0.083522 -v 0.143959 -0.053657 -0.045529 -v 0.153737 -0.045739 -0.038886 -v 0.150819 -0.049831 -0.042120 -v 0.141210 -0.057554 -0.041923 -v 0.141408 -0.058427 -0.039936 -v 0.146679 -0.055609 -0.040614 -v 0.152688 -0.049315 -0.038535 -v 0.153786 -0.046548 -0.038132 -v 0.150852 -0.051254 -0.040485 -v 0.148785 -0.051344 -0.043577 -v 0.146436 -0.052604 -0.044782 -v 0.148843 -0.052912 -0.041754 -v 0.146526 -0.054293 -0.042810 -v 0.151099 -0.051781 -0.039145 -v 0.149051 -0.053868 -0.039963 -v 0.143959 -0.055360 -0.043627 -v 0.143959 -0.056751 -0.041485 -v 0.153406 0.068920 0.005806 -v 0.156933 0.064068 0.006685 -v 0.157992 0.061396 0.006331 -v 0.155365 0.066629 0.006230 -v 0.154369 0.067945 0.014869 -v 0.154918 0.067375 0.022227 -v 0.156177 0.065763 0.014580 -v 0.157616 0.063321 0.014299 -v 0.156692 0.065201 0.022030 -v 0.158651 0.060681 0.014031 -v 0.159123 0.060159 0.021656 -v 0.159255 0.057908 0.013785 -v 0.159719 0.057414 0.021487 -v 0.156816 0.065163 0.036802 -v 0.158017 0.063287 0.036790 -v 0.159414 0.059832 0.029228 -v 0.158977 0.061278 0.036779 -v 0.159681 0.059165 0.036768 -v 0.157011 0.064849 0.029429 -v 0.158105 0.062775 0.021838 -v 0.158408 0.062434 0.029326 -v 0.143686 0.073983 0.003241 -v 0.151220 0.070759 0.004935 -v 0.152121 0.070178 0.008318 -v 0.150319 0.071631 0.006975 -v 0.147250 0.074529 0.016920 -v 0.140595 0.079416 0.023256 -v 0.135179 0.080769 0.019538 -v 0.146055 0.073555 0.004408 -v 0.141654 0.077241 0.013048 -v 0.137078 0.080576 0.020724 -v 0.132378 0.083546 0.027408 -v 0.133978 0.083234 0.028651 -v 0.130713 0.083640 0.026215 -v 0.129005 0.083513 0.025087 -v 0.139519 0.077545 0.011871 -v 0.141228 0.074040 0.002185 -v 0.127073 0.086198 0.032757 -v 0.129374 0.085884 0.034822 -v 0.148282 0.072765 0.005662 -v 0.145556 0.075719 0.015597 -v 0.143679 0.076628 0.014298 -v 0.138893 0.080123 0.021970 -v 0.141145 0.079141 0.025846 -v 0.136906 0.081971 0.031219 -v 0.135494 0.082706 0.029926 -v 0.130219 0.085559 0.035673 -v 0.133022 0.084193 0.035327 -v 0.074995 0.041511 -0.079395 -v 0.093951 0.025973 -0.083409 -v 0.093802 0.029027 -0.082378 -v 0.085985 0.032103 -0.082234 -v 0.080537 0.038089 -0.080358 -v 0.082783 0.038563 -0.079640 -v 0.087087 0.033739 -0.081429 -v 0.088151 0.035269 -0.080397 -v 0.075719 0.042656 -0.078586 -v 0.065885 0.045175 -0.078564 -v 0.069711 0.043081 -0.079230 -v 0.070903 0.045174 -0.077866 -v 0.070313 0.044153 -0.078594 -v 0.066372 0.046147 -0.077972 -v 0.066848 0.047076 -0.077308 -v 0.101495 -0.020327 -0.083079 -v 0.099323 -0.016862 -0.084075 -v 0.096751 -0.020261 -0.084465 -v 0.095048 -0.021312 -0.084495 -v 0.092603 -0.015676 -0.085809 -v 0.094260 -0.014901 -0.085694 -v 0.090067 -0.005603 -0.087143 -v 0.095401 -0.012862 -0.085617 -v 0.096481 -0.010954 -0.085357 -v 0.093954 -0.008369 -0.086278 -v 0.094666 -0.003714 -0.086159 -v 0.091415 -0.002996 -0.087067 -v 0.089699 -0.000692 -0.087334 -v 0.089694 -0.000307 -0.087337 -v 0.089744 0.002080 -0.087311 -v 0.091323 0.000751 -0.087111 -v 0.090105 0.005882 -0.087123 -v 0.090518 0.008327 -0.086908 -v 0.091073 0.010779 -0.086617 -v 0.091774 0.013245 -0.086248 -v 0.093923 0.014056 -0.085861 -v 0.094439 0.000736 -0.086259 -v 0.095564 0.008105 -0.085764 -v 0.094012 0.008597 -0.086252 -v 0.097477 0.013338 -0.084911 -v 0.093726 0.018472 -0.085209 -v 0.095015 0.021245 -0.084513 -v 0.095403 -0.017558 -0.085133 -v 0.097729 -0.017896 -0.084539 -v 0.092956 -0.011205 -0.086328 -v 0.091879 -0.006493 -0.086846 -v 0.093126 -0.003939 -0.086654 -v 0.091606 0.004991 -0.086975 -v 0.092899 0.000712 -0.086756 -v 0.093207 0.004659 -0.086617 -v 0.092422 0.009224 -0.086586 -v 0.095404 0.017560 -0.085133 -v 0.096718 0.020197 -0.084482 -v 0.095464 0.013035 -0.085589 -v 0.097713 0.017867 -0.084547 -v 0.099981 0.018008 -0.083776 -v 0.104265 -0.020909 -0.081946 -v 0.100903 -0.022987 -0.082966 -v 0.102924 -0.026175 -0.081335 -v 0.103666 -0.023582 -0.081833 -v 0.102057 -0.028627 -0.080465 -v 0.109536 -0.030175 -0.077235 -v 0.110385 -0.027689 -0.078142 -v 0.117010 -0.031537 -0.073834 -v 0.119035 -0.023584 -0.075502 -v 0.118522 -0.026347 -0.075338 -v 0.122078 -0.032336 -0.071409 -v 0.125291 -0.030167 -0.071241 -v 0.100125 -0.025560 -0.082489 -v 0.111096 -0.025055 -0.078670 -v 0.117842 -0.029019 -0.074778 -v 0.128643 -0.027817 -0.070514 -v 0.128004 -0.030540 -0.069909 -v 0.136449 -0.025825 -0.067007 -v 0.132248 -0.025353 -0.069125 -v 0.129095 -0.024999 -0.070715 -v 0.125941 -0.027457 -0.071834 -v 0.126409 -0.024654 -0.072025 -v 0.136041 -0.028681 -0.066776 -v 0.127195 -0.033098 -0.068916 -v 0.135433 -0.031437 -0.066138 -v 0.134584 -0.034017 -0.065137 -v 0.152487 -0.048061 -0.040473 -v 0.154204 -0.040135 -0.040254 -v 0.153904 -0.036928 -0.043012 -v 0.143423 -0.048898 -0.049899 -v 0.146025 -0.047887 -0.049012 -v 0.148378 -0.046623 -0.047809 -v 0.145755 -0.044898 -0.051560 -v 0.150145 -0.042186 -0.048839 -v 0.151818 -0.040549 -0.047083 -v 0.142319 -0.037564 -0.059038 -v 0.145214 -0.039412 -0.055995 -v 0.142620 -0.040399 -0.056903 -v 0.143128 -0.045618 -0.052684 -v 0.147560 -0.038191 -0.054757 -v 0.148106 -0.043649 -0.050345 -v 0.150418 -0.045139 -0.046320 -v 0.149597 -0.036771 -0.053220 -v 0.151272 -0.035188 -0.051427 -v 0.153354 -0.041672 -0.042652 -v 0.152091 -0.043474 -0.044586 -v 0.151915 -0.027887 -0.053664 -v 0.153082 -0.038780 -0.045123 -v 0.152539 -0.033484 -0.049423 -v 0.147981 0.071582 0.000009 -v 0.145182 0.072528 -0.000241 -v 0.147220 0.072489 0.001886 -v 0.152946 0.068786 0.001827 -v 0.150583 0.070219 0.000417 -v 0.152904 0.069290 0.004081 -v 0.154927 0.067101 0.004369 -v 0.149502 0.071648 0.003141 -v 0.157766 0.061666 0.004238 -v 0.156634 0.064405 0.004189 -v 0.154949 0.066650 0.002373 -v 0.150542 0.070719 0.001863 -v 0.068049 0.051159 -0.073995 -v 0.066599 0.053966 -0.070836 -v 0.065254 0.054316 -0.070509 -v 0.065666 0.050525 -0.074999 -v 0.065422 0.051834 -0.073795 -v 0.063306 0.050258 -0.075614 -v 0.067523 0.054509 -0.069722 -v 0.064911 0.052732 -0.072847 -v 0.062884 0.051380 -0.074626 -v 0.062279 0.048568 -0.077008 -v 0.097987 0.026030 -0.082853 -v 0.099910 0.021580 -0.083516 -v 0.101495 0.020327 -0.083079 -v 0.100904 0.022988 -0.082965 -v 0.099251 0.027999 -0.081632 -v 0.098681 0.022861 -0.083652 -v 0.099528 0.025482 -0.082711 -v 0.142800 -0.032148 -0.062217 -v 0.148924 -0.027713 -0.058792 -v 0.146872 -0.028108 -0.060796 -v 0.146307 -0.026508 -0.061474 -v 0.144519 -0.028434 -0.062450 -v 0.143742 -0.026468 -0.063149 -v 0.146890 -0.032042 -0.059389 -v 0.144611 -0.033790 -0.060228 -v 0.152770 -0.026364 -0.051319 -v 0.150631 -0.027786 -0.056373 -v 0.143378 -0.029360 -0.062889 -v 0.150631 -0.029681 -0.055641 -v 0.148924 -0.029223 -0.058389 -v 0.146872 -0.029880 -0.060322 -v 0.148948 -0.030884 -0.057664 -v 0.144519 -0.030424 -0.061918 -v 0.144519 -0.032325 -0.061126 -v 0.157719 0.061470 0.003342 -v 0.156304 0.061839 -0.003530 -v 0.156553 0.063997 0.002468 -v 0.142260 0.073030 -0.000326 -v 0.157484 0.059251 -0.002661 -v 0.157625 0.053247 -0.010656 -v 0.156921 0.055994 -0.011580 -v 0.157263 0.051823 -0.014595 -v 0.156106 0.052769 -0.020529 -v 0.155147 0.049860 -0.028691 -v 0.154142 0.061011 -0.013149 -v 0.154941 0.055401 -0.021337 -v 0.150356 0.068086 -0.005468 -v 0.149809 0.064941 -0.014209 -v 0.151345 0.059986 -0.022579 -v 0.150403 0.057133 -0.030630 -v 0.149013 0.061814 -0.022979 -v 0.148076 0.058984 -0.030977 -v 0.144393 0.067357 -0.014643 -v 0.146407 0.063260 -0.023215 -v 0.145475 0.060454 -0.031155 -v 0.155867 0.047176 -0.027550 -v 0.153989 0.052507 -0.029471 -v 0.155749 0.058606 -0.012419 -v 0.154692 0.064216 -0.004301 -v 0.152691 0.066318 -0.004953 -v 0.152144 0.063142 -0.013752 -v 0.153340 0.057829 -0.022027 -v 0.152393 0.054955 -0.030124 -v 0.147201 0.066359 -0.014509 -v 0.147751 0.069472 -0.005832 -v 0.144946 0.070440 -0.006035 -v 0.142018 0.070961 -0.006071 -v 0.141461 0.067907 -0.014607 -v 0.140669 0.064863 -0.023173 -v 0.143600 0.064286 -0.023280 -v 0.142671 0.061504 -0.031158 -v 0.139744 0.062105 -0.030987 -v 0.138487 0.059053 -0.039694 -v 0.143117 0.053063 -0.046532 -v 0.142275 0.055016 -0.045018 -v 0.138031 0.052265 -0.049897 -v 0.132790 0.051546 -0.053092 -v 0.127397 0.050905 -0.056115 -v 0.121854 0.050345 -0.058965 -v 0.110821 0.051597 -0.062079 -v 0.111568 0.049543 -0.063623 -v 0.099031 0.051054 -0.066493 -v 0.099621 0.048966 -0.068101 -v 0.093511 0.048807 -0.070036 -v 0.093001 0.050907 -0.068400 -v 0.086885 0.050844 -0.070107 -v 0.074672 0.048846 -0.074606 -v 0.136934 0.054198 -0.048555 -v 0.130625 0.055203 -0.050067 -v 0.131762 0.053508 -0.051702 -v 0.126441 0.052895 -0.054681 -v 0.120972 0.052360 -0.057489 -v 0.116573 0.051994 -0.059573 -v 0.115650 0.053753 -0.057802 -v 0.109978 0.053375 -0.060265 -v 0.104972 0.051284 -0.064386 -v 0.092410 0.052727 -0.066480 -v 0.086381 0.052672 -0.068158 -v 0.080686 0.050864 -0.071609 -v 0.074406 0.050969 -0.072907 -v 0.139627 0.057991 -0.041773 -v 0.135724 0.055865 -0.046975 -v 0.134426 0.057231 -0.045190 -v 0.129401 0.056593 -0.048221 -v 0.125378 0.054615 -0.052994 -v 0.119986 0.054102 -0.055753 -v 0.118919 0.055534 -0.053796 -v 0.114647 0.055199 -0.055805 -v 0.104212 0.053079 -0.062533 -v 0.098355 0.052862 -0.064604 -v 0.085814 0.054177 -0.065964 -v 0.080269 0.052699 -0.069636 -v 0.073696 0.054318 -0.068669 -v 0.074079 0.052807 -0.070913 -v 0.067340 0.052991 -0.072094 -v 0.137871 0.058958 -0.040113 -v 0.133067 0.058269 -0.043236 -v 0.128118 0.057650 -0.046203 -v 0.124232 0.056027 -0.051090 -v 0.109060 0.054838 -0.058221 -v 0.108085 0.055952 -0.055992 -v 0.103379 0.054555 -0.060445 -v 0.097609 0.054350 -0.062477 -v 0.091753 0.054224 -0.064318 -v 0.091045 0.055365 -0.061963 -v 0.085197 0.055322 -0.063577 -v 0.079794 0.054208 -0.067416 -v 0.073267 0.055468 -0.066229 -v 0.102057 0.028627 -0.080465 -v 0.102924 0.026175 -0.081335 -v 0.103666 0.023582 -0.081833 -v 0.106984 0.021434 -0.080791 -v 0.109536 0.030175 -0.077235 -v 0.110385 0.027689 -0.078142 -v 0.111652 0.022336 -0.078808 -v 0.111096 0.025055 -0.078670 -v 0.118522 0.026347 -0.075338 -v 0.124476 0.032714 -0.070262 -v 0.125291 0.030167 -0.071241 -v 0.119035 0.023584 -0.075502 -v 0.117842 0.029019 -0.074778 -v 0.127195 0.033098 -0.068916 -v 0.128004 0.030540 -0.069909 -v 0.125941 0.027457 -0.071834 -v 0.128643 0.027817 -0.070514 -v 0.126409 0.024654 -0.072025 -v 0.135433 0.031437 -0.066138 -v 0.142800 0.032148 -0.062217 -v 0.136041 0.028681 -0.066776 -v 0.133624 0.033897 -0.065628 -v 0.152036 0.021010 -0.054439 -v 0.150617 0.021053 -0.057154 -v 0.146513 0.021068 -0.061676 -v 0.152848 0.024276 -0.051398 -v 0.152974 0.020944 -0.051522 -v 0.153090 0.016159 -0.051644 -v 0.153228 0.010492 -0.051787 -v 0.152290 0.010527 -0.054703 -v 0.153249 0.007825 -0.051810 -v 0.152374 0.000000 -0.054793 -v 0.153311 0.000000 -0.051877 -v 0.143948 0.021039 -0.063351 -v 0.144135 0.013392 -0.063542 -v 0.146854 0.000000 -0.062028 -v 0.150872 0.010550 -0.057418 -v 0.150956 0.000000 -0.057508 -v 0.150942 -0.004235 -0.057493 -v 0.152361 -0.004225 -0.054778 -v 0.148758 0.021073 -0.059590 -v 0.149014 0.010561 -0.059854 -v 0.146770 0.010561 -0.061939 -v 0.146841 -0.004239 -0.062014 -v 0.153145 -0.014785 -0.051699 -v 0.152800 -0.025438 -0.051350 -v 0.151831 -0.026444 -0.054236 -v 0.153061 -0.017361 -0.051615 -v 0.152207 -0.014832 -0.054615 -v 0.150411 -0.026496 -0.056951 -v 0.150789 -0.014864 -0.057331 -v 0.149085 -0.004239 -0.059929 -v 0.149098 0.000000 -0.059943 -v 0.148552 -0.026517 -0.059388 -v 0.148930 -0.014880 -0.059766 -v 0.144142 -0.013392 -0.063549 -v 0.146686 -0.014878 -0.061851 -v 0.146432 0.052574 -0.044810 -v 0.143901 0.053595 -0.045640 -v 0.148782 0.051326 -0.043595 -v 0.150816 0.049829 -0.042126 -v 0.154524 0.043866 -0.036921 -v 0.153748 0.046389 -0.038460 -v 0.152488 0.048122 -0.040429 -v 0.148843 0.052912 -0.041754 -v 0.150852 0.051254 -0.040485 -v 0.151099 0.051781 -0.039145 -v 0.144203 0.057351 -0.040002 -v 0.141408 0.058427 -0.039936 -v 0.141210 0.057554 -0.041923 -v 0.143959 0.056751 -0.041485 -v 0.149117 0.053981 -0.039601 -v 0.146690 0.055634 -0.040543 -v 0.146526 0.054293 -0.042810 -v 0.141103 0.056661 -0.043443 -v 0.143959 0.055360 -0.043627 -v 0.152688 0.049315 -0.038535 -v 0.150631 0.029682 -0.055640 -v 0.148952 0.030909 -0.057644 -v 0.146899 0.032069 -0.059364 -v 0.144519 0.032325 -0.061126 -v 0.142021 0.034760 -0.061150 -v 0.146872 0.028108 -0.060796 -v 0.146311 0.026524 -0.061470 -v 0.150411 0.026496 -0.056951 -v 0.148552 0.026517 -0.059388 -v 0.151831 0.026444 -0.054236 -v 0.150634 0.028198 -0.056245 -v 0.146872 0.029880 -0.060322 -v 0.152770 0.026364 -0.051319 -v 0.148924 0.029223 -0.058389 -v 0.148924 0.027713 -0.058792 -v 0.144519 0.030424 -0.061918 -v 0.144519 0.028434 -0.062450 -v 0.143378 0.029360 -0.062889 -v 0.143742 0.026468 -0.063149 -v 0.154235 0.040498 -0.039930 -v 0.152091 0.043474 -0.044586 -v 0.153354 0.041672 -0.042652 -v 0.148106 0.043649 -0.050345 -v 0.150145 0.042186 -0.048839 -v 0.148378 0.046623 -0.047809 -v 0.142319 0.037564 -0.059038 -v 0.142620 0.040399 -0.056903 -v 0.151934 0.028069 -0.053528 -v 0.153082 0.038781 -0.045123 -v 0.152539 0.033484 -0.049423 -v 0.151818 0.040549 -0.047083 -v 0.151272 0.035188 -0.051427 -v 0.150418 0.045139 -0.046320 -v 0.149598 0.036771 -0.053220 -v 0.145755 0.044898 -0.051560 -v 0.146025 0.047887 -0.049012 -v 0.143423 0.048898 -0.049899 -v 0.147560 0.038191 -0.054757 -v 0.145214 0.039412 -0.055995 -v 0.144610 0.033795 -0.060226 -v 0.042131 0.006112 0.149355 -v 0.042131 0.018285 0.148246 -v 0.042131 0.030307 0.146035 -v 0.042131 0.095946 0.087266 -v 0.042131 0.096496 0.079060 -v 0.042131 0.083232 0.117211 -v 0.042131 0.052661 -0.075916 -v 0.042131 -0.094306 0.095326 -v 0.042131 -0.095946 0.087266 -v 0.042131 -0.091605 0.103095 -v 0.042131 -0.087892 0.110433 -v 0.042131 -0.047601 -0.079644 -v 0.042131 -0.096496 0.079060 -v 0.042131 0.092788 0.028348 -v 0.042131 0.054729 -0.073539 -v 0.042131 -0.096496 0.049380 -v 0.042131 0.005502 -0.091349 -v 0.042131 -0.052661 -0.075916 -v 0.042131 0.057718 -0.068011 -v 0.042131 -0.057718 -0.068011 -v 0.042131 -0.016442 -0.090158 -v 0.042131 -0.054729 -0.073539 -v -0.000000 0.080000 -0.011560 -v 0.000000 -0.070693 0.078463 -v 0.000000 -0.042918 0.141409 -v 0.000000 -0.085681 -0.001720 -v 0.000000 -0.057111 0.134678 -v 0.000000 0.070693 0.078463 -v 0.000000 0.084368 0.104895 -v 0.000000 -0.083280 0.000681 -v 0.000000 -0.073000 0.112593 -v 0.000000 -0.074251 0.085918 -v 0.000000 -0.071745 0.113859 -v -0.000000 0.085681 -0.001720 -v -0.000001 -0.084852 0.104448 -v 0.000000 -0.069554 -0.014173 -v 0.042131 -0.005502 -0.091349 -v -0.000000 -0.086414 0.101481 -v -0.000000 0.086367 0.101669 -v 0.000000 -0.086139 0.097688 -v 0.000000 0.086139 0.097688 -v -0.000000 -0.084723 -0.000415 -v 0.000000 -0.083742 0.094641 -v 0.000000 -0.078485 0.108081 -v 0.000000 -0.079859 0.091984 -v 0.000000 0.083280 0.094319 -v 0.000000 0.082464 0.106080 -v 0.000000 -0.080000 -0.011560 -v 0.000000 -0.070338 -0.012587 -v 0.000000 -0.070693 0.016537 -v -0.000000 0.071330 -0.011856 -v 0.000000 -0.071330 -0.011856 -v 0.000000 -0.073000 0.011264 -v 0.000000 0.086444 0.098772 -v -0.000000 0.069554 -0.014173 -v 0.000000 -0.069506 -0.014723 -v 0.000000 -0.069506 -0.024813 -v 0.000000 -0.065796 -0.045850 -v -0.000000 0.069506 -0.024813 -v -0.000000 0.069929 -0.013140 -v -0.000000 0.065796 -0.045850 -v 0.000000 -0.054832 -0.073419 -v -0.000000 0.056657 -0.070472 -v 0.000000 0.072191 0.082325 -v -0.000000 0.047606 -0.079654 -v -0.000000 0.054832 -0.073419 -v -0.000000 0.020848 -0.087803 -v 0.000000 -0.047606 -0.079654 -v 0.042000 -0.013279 0.146335 -v 0.042000 0.039306 0.141059 -v 0.042000 -0.039306 0.141059 -v 0.042000 -0.092214 0.096133 -v 0.042000 -0.084115 0.112526 -v 0.042000 -0.071454 0.125718 -v 0.042000 -0.082025 0.003154 -v 0.042000 0.078290 0.119607 -v 0.042000 0.071454 0.125718 -v 0.042000 0.046750 -0.078402 -v 0.000000 0.042276 -0.082287 -v 0.042000 -0.051796 0.136500 -v 0.042000 -0.095000 0.049381 -v 0.042000 0.000000 0.147000 -v 0.042000 -0.063767 0.130717 -v 0.042000 0.093383 0.035544 -v 0.042000 -0.091382 0.028860 -v 0.042000 0.016199 -0.088679 -v 0.042000 -0.094299 0.087205 -v 0.042000 0.088792 0.104640 -v 0.042000 0.056525 -0.067948 -v 0.042000 -0.026786 -0.086346 -v 0.042000 -0.055108 -0.070172 -v 0.042000 -0.046750 -0.078402 -v 0.042000 0.026786 -0.086346 -v 0.042000 -0.076172 -0.012929 -v 0.042000 -0.016199 -0.088679 -v 0.042000 0.076172 -0.012929 -v 0.000000 -0.095497 0.015677 -v -0.000000 0.073528 -0.014580 -v -0.000000 0.050161 0.146466 -v -0.000000 0.065874 0.137571 -v 0.000000 0.074134 0.128712 -v 0.000000 -0.084172 0.117948 -v -0.000000 0.054552 0.145175 -v 0.000000 -0.065864 0.137581 -v 0.000000 -0.058696 0.143232 -v 0.000000 -0.073528 -0.014580 -v 0.000000 -0.050161 0.146466 -v 0.000000 0.084172 0.117948 -v 0.000000 0.101645 0.099211 -v 0.000000 -0.105021 0.095590 -v 0.000000 -0.125825 0.041488 -v 0.000000 0.132802 0.042443 -v 0.000000 0.139721 0.042237 -v 0.000000 -0.114103 0.036921 -v 0.000000 0.125825 0.041488 -v -0.000001 -0.146474 0.041790 -v -0.000000 0.107495 0.032399 -v -0.000000 0.068727 -0.029300 -v 0.000000 -0.069792 0.074420 -v -0.000003 0.146413 0.041663 -v 0.000000 -0.114103 0.085851 -v 0.000000 0.102601 0.027505 -v 0.000000 0.104345 0.029249 -v 0.000000 -0.094454 0.106923 -v 0.000000 -0.102601 0.027505 -v 0.000000 0.017547 0.152896 -v -0.000000 -0.093338 -0.011415 -v -0.000000 0.092830 -0.011548 -v 0.000000 -0.092763 -0.004721 -v 0.000000 -0.054552 0.145175 -v -0.000000 0.082218 -0.011556 -v -0.000000 0.091171 -0.011556 -v -0.000000 0.079885 -0.011752 -v -0.000000 0.077617 -0.012334 -v -0.000000 0.092557 0.002198 -v 0.000000 -0.077617 -0.012334 -v 0.000000 -0.079885 -0.011752 -v 0.000000 -0.075478 -0.013285 -v 0.000000 0.071820 -0.016181 -v 0.000000 0.104345 0.096315 -v 0.000000 0.105021 0.095590 -v 0.000000 -0.071820 -0.016181 -v 0.000000 -0.000000 0.153877 -v 0.000000 0.069317 -0.020118 -v 0.000000 -0.069317 -0.020118 -v 0.000000 -0.068591 -0.022344 -v 0.000000 -0.068246 -0.024659 -v -0.000000 0.068591 -0.022344 -v -0.000000 0.068246 -0.024659 -v -0.000000 0.068291 -0.026994 -v -0.000000 -0.016441 -0.088639 -v 0.000000 -0.064382 -0.045322 -v -0.000000 0.117492 0.082217 -v -0.000000 -0.068291 -0.026994 -v -0.000000 -0.016199 -0.088679 -v -0.000000 0.057111 0.134678 -v 0.042000 -0.005421 -0.089853 -v -0.000000 0.005421 -0.089853 -v 0.000000 0.069470 -0.031343 -v 0.000000 0.069792 0.074420 -v 0.000000 0.069506 0.047500 -v 0.000000 -0.069506 0.024539 -v 0.000000 -0.055108 -0.070172 -v 0.000000 -0.053528 -0.072642 -v 0.000000 -0.072191 0.012675 -v -0.000000 0.070431 -0.012485 -v 0.000000 -0.072118 -0.011608 -v -0.000000 0.072669 -0.011560 -v -0.000434 0.084991 -0.000792 -v -0.000001 0.085423 0.096270 -v 0.000000 -0.086460 -0.006139 -v -0.000000 -0.084585 -0.009723 -v 0.000000 -0.083280 -0.010681 -v -0.000000 0.086560 -0.005000 -v -0.000000 0.086460 -0.003861 -v 0.000000 -0.086460 -0.003861 -v 0.000000 -0.086164 -0.007244 -v 0.000000 -0.085681 -0.008280 -v -0.000000 0.086164 -0.007244 -v 0.000000 -0.052791 0.137448 -v -0.000000 0.085681 -0.008280 -v 0.000000 -0.086559 0.099891 -v -0.000000 0.049377 -0.076761 -v -0.000000 0.046895 -0.078322 -v -0.000000 0.026786 -0.086346 -v 0.013286 0.072627 -0.046018 -v 0.009839 0.072859 -0.046885 -v 0.013387 0.072685 -0.046233 -v 0.009824 0.072960 -0.047261 -v 0.011803 0.072142 -0.044206 -v 0.017323 0.070502 -0.038089 -v 0.013812 0.071367 -0.041316 -v 0.014983 0.070945 -0.039740 -v 0.019190 0.073956 -0.050978 -v 0.028928 0.071682 -0.042490 -v 0.024821 0.073474 -0.049177 -v 0.022015 0.073898 -0.050764 -v 0.020567 0.074406 -0.052658 -v 0.014763 0.074326 -0.048496 -v 0.010658 0.074375 -0.048678 -v 0.009537 0.073427 -0.045141 -v 0.015609 0.071213 -0.036877 -v 0.012647 0.072076 -0.040100 -v 0.018995 0.075343 -0.052294 -v 0.011339 0.073040 -0.043695 -v 0.018534 0.070905 -0.035726 -v 0.021227 0.070864 -0.035574 -v 0.023448 0.071003 -0.036090 -v 0.026146 0.071394 -0.037553 -v 0.018998 0.074922 -0.050722 -v 0.012847 0.074388 -0.048727 -v 0.022238 0.074846 -0.050436 -v 0.027391 0.074473 -0.049043 -v 0.014134 0.073143 -0.047945 -v 0.013351 0.073654 -0.045986 -v 0.015863 0.073608 -0.049678 -v 0.017268 0.073818 -0.050462 -v 0.016652 0.074705 -0.049911 -v 0.025296 0.074323 -0.048484 -v 0.026573 0.072766 -0.046535 -v 0.026908 0.072030 -0.043788 -v 0.026941 0.073362 -0.044897 -v 0.026521 0.072534 -0.041806 -v 0.026132 0.071324 -0.041154 -v 0.025045 0.071900 -0.039442 -v 0.021928 0.071401 -0.037578 -v 0.023976 0.070697 -0.038815 -v 0.020950 0.070391 -0.037672 -v 0.018277 0.071396 -0.037559 -v 0.015743 0.071725 -0.038788 -v 0.014371 0.072103 -0.040199 -v 0.013591 0.072472 -0.041574 -v 0.013114 0.071971 -0.043573 -v 0.013043 0.073100 -0.043920 -v 0.009839 0.073825 -0.046627 -v 0.013323 0.073591 -0.045751 -v 0.009517 0.072406 -0.045195 -v 0.013073 0.070891 -0.039540 -v 0.013659 0.071680 -0.038620 -v 0.015071 0.070360 -0.037559 -v 0.016595 0.070117 -0.036650 -v 0.018753 0.069927 -0.035942 -v 0.021449 0.069904 -0.035856 -v 0.024897 0.070194 -0.036938 -v 0.027769 0.070929 -0.039679 -v 0.028282 0.072150 -0.040374 -v 0.029035 0.072501 -0.045547 -v 0.029113 0.072930 -0.043286 -v 0.028767 0.073745 -0.046326 -v 0.027759 0.073370 -0.048789 -v 0.025969 0.073877 -0.050684 -v 0.023639 0.074251 -0.052080 -v 0.024311 0.075149 -0.051567 -v 0.021210 0.075358 -0.052344 -v 0.018362 0.074340 -0.052411 -v 0.016468 0.075114 -0.051507 -v 0.015875 0.074076 -0.051426 -v 0.009937 0.073917 -0.046968 -v 0.010441 0.073091 -0.043887 -v 0.010424 0.072100 -0.044054 -v 0.011105 0.072556 -0.045753 -v 0.010734 0.073496 -0.045399 -v 0.011979 0.072311 -0.044839 -v 0.012076 0.073245 -0.044462 -v 0.011531 0.073058 -0.047629 -v 0.011466 0.074061 -0.047508 -v 0.011838 0.073496 -0.049262 -v 0.012820 0.073405 -0.048921 -v 0.012922 0.074086 -0.047601 -v 0.013044 0.073189 -0.048116 -v 0.009593 0.072825 -0.042894 -v 0.011926 0.071513 -0.041860 -v 0.009568 0.071860 -0.043158 -v 0.011684 0.073841 -0.050548 -v 0.011704 0.074808 -0.050292 -v 0.014517 0.073823 -0.050480 -v 0.014523 0.074789 -0.050221 -v 0.014031 0.081246 -0.046417 -v 0.014736 0.081644 -0.047921 -v 0.018623 0.082006 -0.049258 -v 0.016602 0.081967 -0.049110 -v 0.023612 0.081940 -0.049009 -v 0.025849 0.081303 -0.046632 -v 0.025695 0.081550 -0.047552 -v 0.027089 0.081028 -0.045615 -v 0.015601 0.078565 -0.036415 -v 0.017656 0.077736 -0.035537 -v 0.014692 0.078229 -0.037379 -v 0.013128 0.079383 -0.039466 -v 0.012657 0.080414 -0.043315 -v 0.012738 0.079926 -0.043680 -v 0.015823 0.081686 -0.048063 -v 0.019866 0.081474 -0.049492 -v 0.022615 0.081917 -0.048923 -v 0.027381 0.080344 -0.043053 -v 0.027071 0.079582 -0.040210 -v 0.026794 0.078826 -0.039604 -v 0.025969 0.078987 -0.037987 -v 0.024178 0.078547 -0.036343 -v 0.021377 0.078226 -0.035147 -v 0.018420 0.078254 -0.035253 -v 0.021140 0.077669 -0.035295 -v 0.027431 0.079602 -0.042499 -v 0.015225 0.081029 -0.047799 -v 0.023442 0.077879 -0.036062 -v 0.025499 0.078285 -0.037578 -v 0.025307 0.080894 -0.047323 -v 0.023302 0.081264 -0.048710 -v 0.017446 0.081349 -0.049025 -v 0.012885 0.079006 -0.040274 -v 0.013559 0.080512 -0.045761 -v 0.019574 0.079672 -0.049933 -v 0.014857 0.078880 -0.046909 -v 0.025829 0.077345 -0.040475 -v 0.019638 0.076128 -0.036479 -v 0.017225 0.076858 -0.037501 -v 0.026561 0.078175 -0.044276 -v 0.015425 0.076680 -0.038516 -v 0.013829 0.077811 -0.041879 -v 0.014532 0.079040 -0.044839 -v 0.016537 0.079757 -0.047385 -v 0.024132 0.079127 -0.047783 -v 0.025962 0.078454 -0.042437 -v 0.020680 0.077385 -0.036840 -v 0.025333 0.079407 -0.045153 -v 0.022915 0.079977 -0.047662 -v 0.023752 0.077095 -0.038091 -v 0.020141 0.079779 -0.048474 -v 0.018366 0.077775 -0.036625 -v 0.024516 0.080580 -0.046758 -v 0.018276 0.080935 -0.048266 -v 0.014366 0.078613 -0.040099 -v 0.013922 0.079475 -0.043363 -v 0.026316 0.080025 -0.044163 -v 0.016301 0.078181 -0.037431 -v 0.021761 0.081004 -0.048374 -v 0.015536 0.080507 -0.046725 -v 0.021560 0.081422 -0.049287 -v 0.024462 0.078249 -0.037864 -v 0.026725 0.080344 -0.045250 -v 0.026176 0.079018 -0.040849 -v 0.027383 0.077875 -0.043206 -v 0.025320 0.076438 -0.037873 -v 0.023284 0.076276 -0.037208 -v 0.020888 0.075873 -0.035741 -v 0.018420 0.075910 -0.035882 -v 0.017608 0.079576 -0.049559 -v 0.021574 0.079635 -0.049781 -v 0.015428 0.079278 -0.048443 -v 0.016542 0.076090 -0.036548 -v 0.014918 0.076393 -0.037681 -v 0.013666 0.076801 -0.039200 -v 0.012739 0.077406 -0.041490 -v 0.012636 0.076639 -0.043034 -v 0.012715 0.078055 -0.043880 -v 0.013493 0.078676 -0.046221 -v 0.015231 0.078125 -0.048585 -v 0.017441 0.078450 -0.049799 -v 0.022821 0.078432 -0.049729 -v 0.025305 0.078003 -0.048099 -v 0.023946 0.079391 -0.048870 -v 0.026422 0.078742 -0.046445 -v 0.027189 0.077365 -0.041375 -v 0.026722 0.076995 -0.039923 -v 0.023315 0.076072 -0.036477 -v 0.018595 0.074792 -0.036143 -v 0.022377 0.074260 -0.035939 -v 0.026161 0.077005 -0.037843 -v 0.027242 0.075308 -0.040193 -v 0.027567 0.076747 -0.045560 -v 0.021535 0.080318 -0.050205 -v 0.019533 0.080346 -0.050310 -v 0.012109 0.078185 -0.042243 -v 0.014980 0.074551 -0.037367 -v 0.017832 0.074242 -0.035893 -v 0.026746 0.078449 -0.043213 -v 0.012087 0.079031 -0.042487 -v 0.020091 0.080719 -0.048846 -v 0.026198 0.079610 -0.044755 -v 0.026673 0.078826 -0.041735 -v 0.025352 0.080556 -0.048182 -v 0.013927 0.079306 -0.044900 -v 0.025238 0.077572 -0.038788 -v 0.016625 0.079782 -0.048103 -v 0.013841 0.077673 -0.040224 -v 0.019688 0.077304 -0.036094 -v 0.023812 0.080079 -0.047732 -v 0.023031 0.076761 -0.036900 -v 0.017638 0.076640 -0.036467 -v 0.015566 0.077681 -0.037469 -v 0.018307 0.077110 -0.034976 -v 0.018833 0.078082 -0.034611 -v 0.021935 0.078120 -0.034754 -v 0.024323 0.078400 -0.035798 -v 0.025856 0.078736 -0.037054 -v 0.027306 0.079304 -0.039172 -v 0.026552 0.077959 -0.038145 -v 0.027963 0.080232 -0.042636 -v 0.019064 0.082158 -0.049821 -v 0.021650 0.082120 -0.049681 -v 0.013168 0.081165 -0.046113 -v 0.012140 0.080417 -0.043327 -v 0.014673 0.078599 -0.036543 -v 0.013988 0.077689 -0.037490 -v 0.016386 0.078292 -0.035397 -v 0.027667 0.078807 -0.044564 -v 0.027944 0.078131 -0.042044 -v 0.023990 0.076524 -0.036046 -v 0.012194 0.078653 -0.043995 -v 0.012388 0.076784 -0.045338 -v 0.015132 0.079931 -0.048768 -v 0.017669 0.080263 -0.049998 -v 0.024102 0.078937 -0.049532 -v 0.013672 0.079528 -0.047256 -v 0.027283 0.077504 -0.039704 -v 0.012492 0.077647 -0.040235 -v 0.018646 0.076283 -0.035147 -v 0.027038 0.079247 -0.046209 -v 0.024925 0.079901 -0.048660 -v 0.013940 0.076975 -0.037750 -v 0.021289 0.076274 -0.035113 -v 0.024398 0.077319 -0.036106 -v 0.020502 0.081083 -0.050153 -v 0.017479 0.080979 -0.049766 -v 0.015338 0.080684 -0.048664 -v 0.012668 0.079855 -0.045565 -v 0.012229 0.079711 -0.040718 -v 0.027814 0.079423 -0.043958 -v 0.021515 0.077007 -0.034945 -v 0.013028 0.079119 -0.038530 -v 0.022896 0.080939 -0.049616 -v 0.024151 0.077615 -0.037225 -v 0.015875 0.077282 -0.035968 -v 0.027629 0.078483 -0.040453 -v 0.020600 0.074763 -0.036037 -v 0.027309 0.076429 -0.042248 -v 0.027283 0.076948 -0.044192 -v 0.026716 0.077447 -0.046047 -v 0.023065 0.074923 -0.036629 -v 0.026626 0.075816 -0.039959 -v 0.025089 0.075304 -0.037981 -v 0.023157 0.078176 -0.048816 -v 0.019866 0.078577 -0.050268 -v 0.012933 0.076125 -0.041121 -v 0.013422 0.076590 -0.042940 -v 0.013760 0.075652 -0.039348 -v 0.013123 0.077400 -0.045849 -v 0.015047 0.075261 -0.037860 -v 0.016700 0.074959 -0.036767 -v 0.014806 0.076015 -0.047361 -v 0.020511 0.076631 -0.050124 -v 0.023003 0.076578 -0.050138 -v 0.019435 0.072957 -0.036519 -v 0.017447 0.073520 -0.038022 -v 0.013374 0.074709 -0.042899 -v 0.026133 0.075570 -0.046131 -v 0.025962 0.074105 -0.040624 -v 0.015267 0.074430 -0.040037 -v 0.014130 0.075394 -0.042441 -v 0.024344 0.076595 -0.047385 -v 0.014259 0.076554 -0.044955 -v 0.025872 0.075962 -0.044521 -v 0.016225 0.077215 -0.047811 -v 0.022648 0.073442 -0.037998 -v 0.020235 0.077994 -0.049239 -v 0.019900 0.073755 -0.037694 -v 0.018468 0.076828 -0.049305 -v 0.018105 0.074726 -0.037640 -v 0.021693 0.077114 -0.048925 -v 0.022429 0.074624 -0.037890 -v 0.014768 0.075529 -0.039480 -v 0.025661 0.077311 -0.046108 -v 0.026239 0.076350 -0.042365 -v 0.025060 0.075112 -0.040343 -v 0.023682 0.075209 -0.037762 -v 0.018942 0.074885 -0.036514 -v 0.015990 0.078117 -0.048597 -v 0.027007 0.075486 -0.045885 -v 0.025483 0.076160 -0.048397 -v 0.025322 0.073543 -0.038651 -v 0.023318 0.073174 -0.037255 -v 0.021420 0.073004 -0.036626 -v 0.012993 0.074265 -0.041329 -v 0.016174 0.076498 -0.049669 -v 0.018124 0.076726 -0.050514 -v 0.012633 0.075037 -0.044214 -v 0.020586 0.076775 -0.050699 -v 0.013277 0.075653 -0.046512 -v 0.017459 0.073085 -0.036929 -v 0.014037 0.072634 -0.039682 -v 0.014827 0.073493 -0.038451 -v 0.014675 0.076202 -0.048562 -v 0.014228 0.074949 -0.048324 -v 0.020410 0.075668 -0.051008 -v 0.026501 0.074676 -0.047304 -v 0.027367 0.074713 -0.043000 -v 0.026723 0.074098 -0.040702 -v 0.021141 0.071876 -0.036848 -v 0.018597 0.071894 -0.036920 -v 0.017683 0.072617 -0.036380 -v 0.021099 0.071288 -0.036422 -v 0.027842 0.073846 -0.042772 -v 0.027843 0.073605 -0.045428 -v 0.022576 0.077336 -0.050723 -v 0.016567 0.075098 -0.050936 -v 0.014761 0.076946 -0.049214 -v 0.012229 0.074998 -0.041945 -v 0.012739 0.072405 -0.040949 -v 0.013894 0.071936 -0.039196 -v 0.014180 0.075312 -0.040240 -v 0.016831 0.077646 -0.048943 -v 0.021417 0.074433 -0.036947 -v 0.016878 0.074581 -0.037490 -v 0.013349 0.076553 -0.044865 -v 0.013303 0.075584 -0.044109 -v 0.026310 0.076226 -0.044874 -v 0.015832 0.076828 -0.048763 -v 0.024832 0.076868 -0.047670 -v 0.024677 0.073758 -0.037312 -v 0.019711 0.073360 -0.035828 -v 0.015146 0.074153 -0.038761 -v 0.021061 0.077135 -0.049895 -v 0.022133 0.073749 -0.037200 -v 0.026184 0.075540 -0.041122 -v 0.022024 0.077822 -0.049601 -v 0.025287 0.076951 -0.049229 -v 0.026160 0.074008 -0.038645 -v 0.022239 0.073428 -0.036080 -v 0.015602 0.073700 -0.037095 -v 0.012961 0.074463 -0.039944 -v 0.012129 0.075735 -0.044696 -v 0.018385 0.077415 -0.050961 -v 0.020230 0.076098 -0.051464 -v 0.027889 0.075531 -0.043937 -v 0.013968 0.073987 -0.038556 -v 0.027439 0.074702 -0.040833 -v 0.013418 0.074393 -0.048309 -v 0.027301 0.076211 -0.046521 -v 0.026508 0.074971 -0.038936 -v 0.026306 0.078345 -0.047636 -v 0.016424 0.077976 -0.050149 -v 0.013078 0.078186 -0.046688 -v 0.012086 0.076123 -0.043232 -v 0.013237 0.075063 -0.039277 -v 0.012376 0.075578 -0.041199 -v 0.014173 0.077526 -0.048464 -v 0.016308 0.075720 -0.036104 -v 0.025637 0.077568 -0.048629 -v 0.020044 0.074084 -0.035626 -v 0.025004 0.074541 -0.037325 -v 0.019650 0.078182 -0.050919 -v 0.022175 0.078103 -0.050622 -v 0.027931 0.075916 -0.042458 -v 0.027013 0.073166 -0.041641 -v 0.023951 0.072149 -0.037868 -v 0.025774 0.072581 -0.039487 -v 0.012791 0.073355 -0.042317 -v 0.024952 0.075176 -0.049171 -v 0.022823 0.075535 -0.050504 -v 0.018411 0.075628 -0.050851 -v 0.016046 0.075383 -0.049939 -v 0.012691 0.074001 -0.044784 -v 0.016272 0.072114 -0.037737 -v 0.013896 0.070889 -0.040358 -v 0.024900 0.073114 -0.048535 -v 0.018526 0.070354 -0.038154 -v 0.022720 0.070443 -0.038582 -v 0.020473 0.073745 -0.050623 -v 0.018607 0.071210 -0.038560 -v 0.024770 0.071327 -0.040429 -v 0.014182 0.072808 -0.045957 -v 0.021444 0.071319 -0.038598 -v 0.015393 0.073758 -0.047818 -v 0.026152 0.072418 -0.044426 -v 0.023496 0.072319 -0.038955 -v 0.023932 0.073815 -0.048516 -v 0.015090 0.071425 -0.040732 -v 0.014273 0.072284 -0.042573 -v 0.018576 0.074505 -0.049832 -v 0.025878 0.073800 -0.045777 -v 0.025723 0.072835 -0.041692 -v 0.018788 0.075368 -0.050096 -v 0.014681 0.072727 -0.040181 -v 0.013761 0.073376 -0.043373 -v 0.013221 0.074529 -0.046672 -v 0.014351 0.074588 -0.047133 -v 0.022977 0.075088 -0.049284 -v 0.017868 0.072146 -0.038006 -v 0.027359 0.073952 -0.044578 -v 0.021123 0.072049 -0.037684 -v 0.023740 0.070328 -0.038222 -v 0.023459 0.073647 -0.050666 -v 0.015430 0.073483 -0.049997 -v 0.016056 0.073369 -0.049472 -v 0.017609 0.073779 -0.051113 -v 0.019584 0.073882 -0.051486 -v 0.021584 0.073839 -0.051331 -v 0.018355 0.070100 -0.037382 -v 0.013750 0.072986 -0.048147 -v 0.012738 0.071617 -0.043040 -v 0.015682 0.070432 -0.038619 -v 0.012789 0.072387 -0.045960 -v 0.013894 0.071955 -0.048705 -v 0.015693 0.072416 -0.050452 -v 0.020412 0.072758 -0.051789 -v 0.024184 0.072438 -0.050535 -v 0.025698 0.072076 -0.049192 -v 0.025483 0.073262 -0.049174 -v 0.026787 0.072714 -0.047147 -v 0.026723 0.071648 -0.047586 -v 0.027377 0.071030 -0.045188 -v 0.027502 0.071931 -0.044240 -v 0.027365 0.071957 -0.044305 -v 0.025661 0.070757 -0.039832 -v 0.026704 0.071164 -0.041454 -v 0.025761 0.069681 -0.040247 -v 0.021419 0.070106 -0.037403 -v 0.019948 0.068019 -0.037248 -v 0.018245 0.070513 -0.036795 -v 0.025122 0.070858 -0.038405 -v 0.027440 0.071805 -0.041616 -v 0.027646 0.072993 -0.046425 -v 0.019652 0.072467 -0.052450 -v 0.019796 0.074556 -0.051882 -v 0.017256 0.072007 -0.052055 -v 0.015443 0.074094 -0.050545 -v 0.012248 0.070525 -0.046440 -v 0.026184 0.071865 -0.041810 -v 0.026145 0.072431 -0.041059 -v 0.022467 0.071599 -0.037951 -v 0.013363 0.073565 -0.045292 -v 0.024147 0.074615 -0.049228 -v 0.020193 0.074975 -0.050562 -v 0.015597 0.074539 -0.048951 -v 0.017124 0.071559 -0.037802 -v 0.014370 0.072016 -0.040873 -v 0.026387 0.073222 -0.045348 -v 0.023154 0.070967 -0.038474 -v 0.018099 0.071121 -0.038071 -v 0.013476 0.072200 -0.043059 -v 0.017474 0.074163 -0.050404 -v 0.013843 0.073185 -0.046744 -v 0.023334 0.074088 -0.050119 -v 0.019008 0.075265 -0.051622 -v 0.012109 0.073077 -0.043448 -v 0.025947 0.073865 -0.049308 -v 0.020542 0.070462 -0.036602 -v 0.015875 0.070760 -0.037717 -v 0.012124 0.072299 -0.043458 -v 0.012243 0.072945 -0.045873 -v 0.012950 0.071135 -0.048343 -v 0.017669 0.074467 -0.051551 -v 0.023684 0.074330 -0.051042 -v 0.013812 0.073783 -0.048995 -v 0.012387 0.069573 -0.042796 -v 0.022453 0.069475 -0.037252 -v 0.012988 0.070783 -0.040883 -v 0.026582 0.071376 -0.040012 -v 0.014216 0.071107 -0.039015 -v 0.024485 0.074919 -0.050334 -v 0.012285 0.073714 -0.045830 -v 0.021847 0.075224 -0.051473 -v 0.023815 0.071430 -0.037309 -v 0.025911 0.074599 -0.049135 -v 0.015444 0.071556 -0.037780 -v 0.014977 0.074815 -0.049943 -v 0.018867 0.071208 -0.036484 -v 0.026040 0.071898 -0.039057 -v 0.027375 0.072485 -0.041248 -v 0.024133 0.068321 -0.038365 -v 0.025823 0.068664 -0.039703 -v 0.027243 0.069213 -0.041737 -v 0.027574 0.070713 -0.047144 -v 0.026156 0.071419 -0.049707 -v 0.014334 0.068672 -0.039505 -v 0.012104 0.070019 -0.044583 -v 0.027924 0.071137 -0.044059 -v 0.024144 0.071868 -0.051391 -v 0.014632 0.071566 -0.050582 -v 0.022077 0.072091 -0.052259 -v 0.027004 0.070256 -0.042393 -v 0.023905 0.069253 -0.038612 -v 0.019586 0.068967 -0.037576 -v 0.022381 0.072674 -0.051412 -v 0.021586 0.068992 -0.037735 -v 0.017940 0.072717 -0.051538 -v 0.016916 0.068200 -0.037807 -v 0.017618 0.069066 -0.037948 -v 0.015023 0.069445 -0.039346 -v 0.013277 0.070090 -0.041774 -v 0.012715 0.070587 -0.043628 -v 0.012738 0.071227 -0.046024 -v 0.014134 -0.073143 -0.047945 -v 0.011979 -0.072311 -0.044839 -v 0.013387 -0.072685 -0.046233 -v 0.013812 -0.071367 -0.041316 -v 0.009824 -0.072960 -0.047261 -v 0.014517 -0.073823 -0.050480 -v 0.009568 -0.071860 -0.043158 -v 0.010424 -0.072100 -0.044054 -v 0.020567 -0.074406 -0.052658 -v 0.017323 -0.070502 -0.038089 -v 0.014983 -0.070945 -0.039740 -v 0.016595 -0.070117 -0.036650 -v 0.023976 -0.070697 -0.038815 -v 0.018753 -0.069927 -0.035942 -v 0.022377 -0.069931 -0.035955 -v 0.027968 -0.071027 -0.040048 -v 0.026132 -0.071324 -0.041154 -v 0.024821 -0.073474 -0.049177 -v 0.013043 -0.073100 -0.043920 -v 0.013323 -0.073591 -0.045751 -v 0.009839 -0.073825 -0.046627 -v 0.018995 -0.075343 -0.052294 -v 0.010658 -0.074375 -0.048678 -v 0.009937 -0.073917 -0.046968 -v 0.013351 -0.073654 -0.045986 -v 0.011339 -0.073040 -0.043695 -v 0.011704 -0.074808 -0.050292 -v 0.015609 -0.071213 -0.036877 -v 0.025045 -0.071900 -0.039442 -v 0.018534 -0.070905 -0.035726 -v 0.026941 -0.073362 -0.044897 -v 0.026521 -0.072534 -0.041806 -v 0.028767 -0.073745 -0.046326 -v 0.012847 -0.074388 -0.048727 -v 0.021210 -0.075358 -0.052344 -v 0.014763 -0.074326 -0.048496 -v 0.015863 -0.073608 -0.049678 -v 0.017267 -0.073818 -0.050461 -v 0.016653 -0.074705 -0.049912 -v 0.019190 -0.073956 -0.050978 -v 0.018999 -0.074922 -0.050722 -v 0.022238 -0.074846 -0.050436 -v 0.022015 -0.073898 -0.050764 -v 0.025296 -0.074323 -0.048484 -v 0.026573 -0.072766 -0.046535 -v 0.026908 -0.072030 -0.043788 -v 0.021928 -0.071401 -0.037578 -v 0.020950 -0.070391 -0.037672 -v 0.018277 -0.071396 -0.037559 -v 0.015743 -0.071725 -0.038788 -v 0.014371 -0.072103 -0.040199 -v 0.013591 -0.072472 -0.041574 -v 0.013114 -0.071971 -0.043573 -v 0.013286 -0.072627 -0.046018 -v 0.009839 -0.072859 -0.046885 -v 0.009537 -0.073427 -0.045141 -v 0.009517 -0.072406 -0.045195 -v 0.013073 -0.070891 -0.039540 -v 0.012647 -0.072076 -0.040100 -v 0.013659 -0.071680 -0.038620 -v 0.015071 -0.070360 -0.037559 -v 0.021227 -0.070864 -0.035574 -v 0.024661 -0.071125 -0.036548 -v 0.025976 -0.070402 -0.037716 -v 0.027626 -0.071838 -0.039211 -v 0.028928 -0.071682 -0.042490 -v 0.029099 -0.072811 -0.042841 -v 0.029035 -0.072501 -0.045547 -v 0.027759 -0.073370 -0.048789 -v 0.027391 -0.074473 -0.049043 -v 0.025969 -0.073877 -0.050684 -v 0.023639 -0.074251 -0.052080 -v 0.024311 -0.075149 -0.051567 -v 0.018362 -0.074340 -0.052411 -v 0.016468 -0.075114 -0.051507 -v 0.015875 -0.074076 -0.051426 -v 0.010441 -0.073091 -0.043887 -v 0.010734 -0.073496 -0.045399 -v 0.011105 -0.072556 -0.045753 -v 0.012076 -0.073245 -0.044462 -v 0.011803 -0.072142 -0.044206 -v 0.011466 -0.074061 -0.047508 -v 0.011838 -0.073496 -0.049262 -v 0.012820 -0.073405 -0.048921 -v 0.012922 -0.074086 -0.047601 -v 0.013044 -0.073189 -0.048116 -v 0.011531 -0.073058 -0.047629 -v 0.009593 -0.072825 -0.042894 -v 0.011926 -0.071513 -0.041860 -v 0.011684 -0.073841 -0.050548 -v 0.014523 -0.074789 -0.050221 -v 0.014031 -0.081246 -0.046417 -v 0.014144 -0.081496 -0.047351 -v 0.025695 -0.081550 -0.047552 -v 0.027071 -0.079582 -0.040210 -v 0.021935 -0.078120 -0.034754 -v 0.021376 -0.078226 -0.035147 -v 0.018420 -0.078254 -0.035253 -v 0.015601 -0.078565 -0.036415 -v 0.016269 -0.077910 -0.036185 -v 0.013128 -0.079383 -0.039466 -v 0.012657 -0.080414 -0.043315 -v 0.013559 -0.080512 -0.045761 -v 0.015820 -0.081686 -0.048060 -v 0.018622 -0.082006 -0.049258 -v 0.022615 -0.081917 -0.048923 -v 0.025849 -0.081303 -0.046632 -v 0.027431 -0.079602 -0.042499 -v 0.027381 -0.080344 -0.043053 -v 0.025969 -0.078987 -0.037987 -v 0.024175 -0.078546 -0.036341 -v 0.021660 -0.077687 -0.035353 -v 0.026794 -0.078826 -0.039604 -v 0.026725 -0.080344 -0.045250 -v 0.025185 -0.078183 -0.037207 -v 0.025307 -0.080894 -0.047323 -v 0.022818 -0.081330 -0.048954 -v 0.019866 -0.081474 -0.049492 -v 0.015975 -0.081200 -0.048442 -v 0.012717 -0.079277 -0.041286 -v 0.013729 -0.078529 -0.038497 -v 0.018593 -0.077691 -0.035367 -v 0.012738 -0.079926 -0.043680 -v 0.015631 -0.079098 -0.047656 -v 0.025380 -0.078689 -0.045789 -v 0.026013 -0.078247 -0.042810 -v 0.025362 -0.076785 -0.038962 -v 0.020499 -0.076047 -0.036319 -v 0.013829 -0.077811 -0.041879 -v 0.014532 -0.079040 -0.044839 -v 0.016908 -0.080064 -0.047640 -v 0.019233 -0.079484 -0.049072 -v 0.024487 -0.077739 -0.038859 -v 0.014687 -0.077916 -0.040019 -v 0.021317 -0.077059 -0.036925 -v 0.016923 -0.077189 -0.037730 -v 0.022138 -0.079752 -0.048200 -v 0.019430 -0.077794 -0.036252 -v 0.020689 -0.080528 -0.048268 -v 0.024178 -0.078160 -0.037188 -v 0.013852 -0.079382 -0.042987 -v 0.015536 -0.080507 -0.046725 -v 0.025972 -0.080091 -0.044627 -v 0.025931 -0.078893 -0.041161 -v 0.015143 -0.078349 -0.037930 -v 0.018660 -0.081194 -0.048548 -v 0.023189 -0.080998 -0.047861 -v 0.027366 -0.077608 -0.042224 -v 0.025765 -0.078960 -0.047257 -v 0.023946 -0.079391 -0.048870 -v 0.023712 -0.079254 -0.048297 -v 0.021121 -0.079664 -0.049890 -v 0.016542 -0.076090 -0.036548 -v 0.015426 -0.079277 -0.048440 -v 0.014918 -0.076393 -0.037681 -v 0.015258 -0.076513 -0.038093 -v 0.016274 -0.075010 -0.036960 -v 0.013666 -0.076801 -0.039200 -v 0.012636 -0.076639 -0.043034 -v 0.012739 -0.077406 -0.041490 -v 0.012715 -0.078055 -0.043880 -v 0.013493 -0.078676 -0.046221 -v 0.015229 -0.078125 -0.048583 -v 0.018117 -0.079624 -0.049736 -v 0.017440 -0.078450 -0.049799 -v 0.026716 -0.077447 -0.046047 -v 0.027007 -0.078385 -0.045110 -v 0.027283 -0.076948 -0.044192 -v 0.026722 -0.076995 -0.039923 -v 0.025321 -0.076438 -0.037874 -v 0.023319 -0.076072 -0.036478 -v 0.021141 -0.074774 -0.036071 -v 0.020888 -0.075873 -0.035741 -v 0.018595 -0.074792 -0.036143 -v 0.018420 -0.075910 -0.035882 -v 0.027242 -0.075308 -0.040193 -v 0.027667 -0.078807 -0.044564 -v 0.026764 -0.077203 -0.047261 -v 0.026748 -0.079401 -0.046783 -v 0.021535 -0.080318 -0.050205 -v 0.019533 -0.080346 -0.050310 -v 0.017118 -0.078041 -0.050394 -v 0.014760 -0.077698 -0.049015 -v 0.013335 -0.077238 -0.047390 -v 0.013195 -0.079352 -0.046600 -v 0.012086 -0.076123 -0.043232 -v 0.013237 -0.075063 -0.039277 -v 0.014980 -0.074551 -0.037367 -v 0.017832 -0.074242 -0.035893 -v 0.013241 -0.080096 -0.046473 -v 0.014983 -0.080031 -0.046901 -v 0.020373 -0.080728 -0.048868 -v 0.025059 -0.080086 -0.046524 -v 0.013163 -0.078981 -0.042326 -v 0.024307 -0.077449 -0.037786 -v 0.026263 -0.078224 -0.040763 -v 0.026713 -0.079045 -0.042552 -v 0.019688 -0.077304 -0.036094 -v 0.014249 -0.077400 -0.039298 -v 0.022162 -0.079927 -0.048699 -v 0.023031 -0.076761 -0.036900 -v 0.016397 -0.079795 -0.048224 -v 0.013289 -0.078639 -0.043919 -v 0.027790 -0.077931 -0.041306 -v 0.027278 -0.077500 -0.039693 -v 0.017638 -0.076640 -0.036467 -v 0.022432 -0.080976 -0.049757 -v 0.015566 -0.077681 -0.037469 -v 0.018833 -0.078082 -0.034611 -v 0.024323 -0.078400 -0.035798 -v 0.025856 -0.078736 -0.037054 -v 0.026552 -0.077959 -0.038145 -v 0.027306 -0.079304 -0.039172 -v 0.027963 -0.080232 -0.042636 -v 0.027089 -0.081028 -0.045615 -v 0.023651 -0.081928 -0.048987 -v 0.021159 -0.082145 -0.049785 -v 0.018064 -0.082111 -0.049651 -v 0.015121 -0.081708 -0.048264 -v 0.017068 -0.080934 -0.049596 -v 0.012954 -0.081051 -0.045692 -v 0.012083 -0.079314 -0.043542 -v 0.012140 -0.080417 -0.043327 -v 0.014673 -0.078599 -0.036543 -v 0.016386 -0.078292 -0.035397 -v 0.027916 -0.077243 -0.043084 -v 0.026161 -0.077005 -0.037843 -v 0.023990 -0.076524 -0.036046 -v 0.012056 -0.078477 -0.043332 -v 0.012388 -0.076784 -0.045338 -v 0.015714 -0.080029 -0.049127 -v 0.017669 -0.080263 -0.049998 -v 0.024114 -0.079003 -0.049508 -v 0.012492 -0.077647 -0.040235 -v 0.024924 -0.079906 -0.048664 -v 0.018646 -0.076283 -0.035147 -v 0.013940 -0.076975 -0.037750 -v 0.021289 -0.076274 -0.035113 -v 0.024398 -0.077319 -0.036106 -v 0.027814 -0.079423 -0.043957 -v 0.019170 -0.081068 -0.050098 -v 0.012229 -0.079711 -0.040718 -v 0.013988 -0.077689 -0.037490 -v 0.018307 -0.077110 -0.034976 -v 0.021515 -0.077007 -0.034945 -v 0.013028 -0.079119 -0.038530 -v 0.025451 -0.080527 -0.048080 -v 0.015875 -0.077282 -0.035968 -v 0.027666 -0.078522 -0.040592 -v 0.027309 -0.076429 -0.042248 -v 0.023473 -0.074982 -0.036854 -v 0.025099 -0.075288 -0.037994 -v 0.025305 -0.078003 -0.048099 -v 0.022821 -0.078432 -0.049729 -v 0.019866 -0.078576 -0.050268 -v 0.012933 -0.076125 -0.041121 -v 0.014039 -0.075532 -0.038903 -v 0.013123 -0.077400 -0.045849 -v 0.013374 -0.074709 -0.042899 -v 0.014542 -0.075907 -0.045872 -v 0.016489 -0.076399 -0.048846 -v 0.024788 -0.076130 -0.048254 -v 0.024973 -0.074288 -0.040050 -v 0.016415 -0.073442 -0.038187 -v 0.026651 -0.074733 -0.043010 -v 0.015071 -0.073934 -0.039575 -v 0.014130 -0.075394 -0.042441 -v 0.020935 -0.076602 -0.049755 -v 0.016806 -0.077274 -0.048153 -v 0.024344 -0.076595 -0.047385 -v 0.022838 -0.074045 -0.038356 -v 0.020098 -0.077652 -0.049143 -v 0.015485 -0.074828 -0.039609 -v 0.025879 -0.075793 -0.044465 -v 0.025651 -0.075568 -0.041072 -v 0.020007 -0.073793 -0.037689 -v 0.013532 -0.076228 -0.041636 -v 0.017697 -0.078371 -0.049524 -v 0.023571 -0.078004 -0.048299 -v 0.017992 -0.074508 -0.037934 -v 0.025661 -0.077311 -0.046108 -v 0.026517 -0.076687 -0.043275 -v 0.014030 -0.077339 -0.045801 -v 0.026622 -0.075834 -0.039952 -v 0.022898 -0.075109 -0.037580 -v 0.017661 -0.074945 -0.036752 -v 0.027007 -0.075486 -0.045885 -v 0.022826 -0.073098 -0.037011 -v 0.023050 -0.076619 -0.050112 -v 0.017459 -0.073085 -0.036929 -v 0.013277 -0.075653 -0.046512 -v 0.014827 -0.073493 -0.038451 -v 0.015827 -0.072196 -0.038041 -v 0.014037 -0.072634 -0.039682 -v 0.012993 -0.074265 -0.041329 -v 0.012791 -0.073355 -0.042317 -v 0.012633 -0.075037 -0.044214 -v 0.013186 -0.074502 -0.046579 -v 0.014228 -0.074949 -0.048324 -v 0.015025 -0.076303 -0.048942 -v 0.016046 -0.075382 -0.049938 -v 0.018123 -0.076726 -0.050514 -v 0.020586 -0.076775 -0.050699 -v 0.025483 -0.076160 -0.048397 -v 0.025314 -0.075117 -0.048854 -v 0.027367 -0.074713 -0.043000 -v 0.026723 -0.074098 -0.040702 -v 0.025662 -0.073657 -0.039055 -v 0.024662 -0.073405 -0.038118 -v 0.021593 -0.071904 -0.036958 -v 0.019887 -0.072953 -0.036469 -v 0.019593 -0.071863 -0.036801 -v 0.017624 -0.071961 -0.037170 -v 0.017768 -0.073364 -0.036155 -v 0.020683 -0.071754 -0.036232 -v 0.025241 -0.073866 -0.037716 -v 0.027625 -0.073789 -0.046117 -v 0.016435 -0.076077 -0.050602 -v 0.013670 -0.076654 -0.048122 -v 0.012079 -0.074051 -0.043560 -v 0.012229 -0.074998 -0.041945 -v 0.012961 -0.074463 -0.039944 -v 0.018548 -0.077116 -0.049831 -v 0.020882 -0.073708 -0.037092 -v 0.022552 -0.074481 -0.037126 -v 0.013661 -0.075543 -0.041097 -v 0.013665 -0.076746 -0.045570 -v 0.020464 -0.077842 -0.049680 -v 0.024663 -0.077378 -0.047949 -v 0.026542 -0.075730 -0.043252 -v 0.016969 -0.074610 -0.037650 -v 0.013494 -0.074886 -0.041506 -v 0.025171 -0.074299 -0.039311 -v 0.014336 -0.076398 -0.047146 -v 0.023191 -0.076951 -0.049209 -v 0.026025 -0.076184 -0.046348 -v 0.025777 -0.075264 -0.040049 -v 0.016216 -0.077556 -0.048615 -v 0.026580 -0.074273 -0.039233 -v 0.022239 -0.073428 -0.036080 -v 0.015602 -0.073700 -0.037095 -v 0.018904 -0.077448 -0.051087 -v 0.012411 -0.075983 -0.045620 -v 0.027889 -0.075531 -0.043937 -v 0.025464 -0.076916 -0.049099 -v 0.014333 -0.071803 -0.038671 -v 0.027439 -0.074702 -0.040833 -v 0.015330 -0.077056 -0.049623 -v 0.022377 -0.074260 -0.035939 -v 0.026508 -0.074971 -0.038936 -v 0.027625 -0.076688 -0.045340 -v 0.012376 -0.075578 -0.041199 -v 0.016308 -0.075720 -0.036104 -v 0.025004 -0.074541 -0.037325 -v 0.020044 -0.074084 -0.035626 -v 0.022569 -0.078168 -0.050501 -v 0.025637 -0.077568 -0.048629 -v 0.027689 -0.075655 -0.041489 -v 0.027865 -0.076324 -0.043982 -v 0.019650 -0.078182 -0.050919 -v 0.027012 -0.073159 -0.041640 -v 0.027364 -0.073790 -0.043998 -v 0.026922 -0.074437 -0.046414 -v 0.023951 -0.072149 -0.037868 -v 0.022823 -0.075535 -0.050504 -v 0.020287 -0.075683 -0.051008 -v 0.018411 -0.075628 -0.050851 -v 0.012691 -0.074001 -0.044784 -v 0.017258 -0.070500 -0.038707 -v 0.013896 -0.070889 -0.040358 -v 0.025523 -0.072954 -0.047304 -v 0.013963 -0.072676 -0.046459 -v 0.016704 -0.073499 -0.049887 -v 0.020883 -0.070059 -0.037301 -v 0.020042 -0.074388 -0.049810 -v 0.025951 -0.072515 -0.043888 -v 0.018314 -0.071133 -0.038706 -v 0.014359 -0.073707 -0.046005 -v 0.017628 -0.074528 -0.049353 -v 0.023266 -0.073604 -0.049373 -v 0.023998 -0.070769 -0.039552 -v 0.015393 -0.073758 -0.047818 -v 0.024989 -0.074013 -0.047268 -v 0.025110 -0.072495 -0.040784 -v 0.014273 -0.072284 -0.042573 -v 0.020822 -0.071034 -0.038518 -v 0.015090 -0.071425 -0.040732 -v 0.013761 -0.073376 -0.043373 -v 0.022503 -0.071846 -0.038719 -v 0.014681 -0.072727 -0.040181 -v 0.023061 -0.074755 -0.049074 -v 0.023466 -0.072261 -0.038349 -v 0.026562 -0.073869 -0.044351 -v 0.025781 -0.072590 -0.039495 -v 0.018716 -0.072054 -0.037742 -v 0.027115 -0.072467 -0.046223 -v 0.027197 -0.071590 -0.042942 -v 0.025791 -0.071376 -0.041800 -v 0.023414 -0.073660 -0.050688 -v 0.025483 -0.073262 -0.049174 -v 0.025322 -0.070648 -0.039426 -v 0.014029 -0.073106 -0.048595 -v 0.015817 -0.073548 -0.050239 -v 0.017608 -0.073779 -0.051112 -v 0.019584 -0.073882 -0.051486 -v 0.017888 -0.070143 -0.037540 -v 0.015682 -0.070432 -0.038619 -v 0.012738 -0.071617 -0.043040 -v 0.012789 -0.072387 -0.045960 -v 0.017939 -0.072717 -0.051538 -v 0.021584 -0.073839 -0.051331 -v 0.025698 -0.072076 -0.049192 -v 0.026533 -0.072844 -0.047635 -v 0.027365 -0.071957 -0.044305 -v 0.026723 -0.071200 -0.041478 -v 0.023316 -0.070276 -0.038030 -v 0.019948 -0.068019 -0.037248 -v 0.021116 -0.070483 -0.036679 -v 0.025823 -0.068664 -0.039703 -v 0.027243 -0.069213 -0.041737 -v 0.027440 -0.071805 -0.041616 -v 0.019760 -0.072474 -0.052459 -v 0.015443 -0.074094 -0.050545 -v 0.012950 -0.071135 -0.048343 -v 0.012124 -0.072299 -0.043458 -v 0.023637 -0.070984 -0.038545 -v 0.014907 -0.074454 -0.048612 -v 0.026145 -0.072431 -0.041059 -v 0.026288 -0.073697 -0.045942 -v 0.022992 -0.071683 -0.038321 -v 0.014579 -0.072249 -0.040423 -v 0.020894 -0.075015 -0.050702 -v 0.013433 -0.072978 -0.044979 -v 0.023667 -0.074243 -0.049341 -v 0.018636 -0.070964 -0.037926 -v 0.015383 -0.073885 -0.048730 -v 0.019219 -0.074258 -0.050747 -v 0.026219 -0.071892 -0.041916 -v 0.018236 -0.071534 -0.037710 -v 0.013262 -0.073075 -0.043462 -v 0.024133 -0.074168 -0.050783 -v 0.025122 -0.070858 -0.038405 -v 0.012465 -0.073125 -0.046550 -v 0.017669 -0.074467 -0.051551 -v 0.019796 -0.074556 -0.051882 -v 0.013812 -0.073783 -0.048995 -v 0.012156 -0.072680 -0.045265 -v 0.012387 -0.069573 -0.042796 -v 0.019050 -0.070465 -0.036617 -v 0.022453 -0.069475 -0.037252 -v 0.022726 -0.074426 -0.051400 -v 0.012988 -0.070783 -0.040883 -v 0.015871 -0.070761 -0.037719 -v 0.026582 -0.071376 -0.040012 -v 0.027050 -0.073472 -0.047843 -v 0.014216 -0.071107 -0.039015 -v 0.014659 -0.071531 -0.040589 -v 0.024842 -0.071615 -0.038002 -v 0.027925 -0.073649 -0.043383 -v 0.027362 -0.076165 -0.046352 -v 0.022576 -0.077339 -0.050723 -v 0.018765 -0.075281 -0.051678 -v 0.012739 -0.072405 -0.040949 -v 0.012375 -0.073823 -0.046235 -v 0.024485 -0.074919 -0.050334 -v 0.014158 -0.074639 -0.049288 -v 0.017016 -0.071321 -0.036904 -v 0.021847 -0.075224 -0.051473 -v 0.025911 -0.074599 -0.049135 -v 0.027375 -0.072485 -0.041248 -v 0.026319 -0.072001 -0.039439 -v 0.023175 -0.071360 -0.037049 -v 0.024133 -0.068321 -0.038365 -v 0.027574 -0.070713 -0.047144 -v 0.022527 -0.072066 -0.052146 -v 0.017256 -0.072007 -0.052055 -v 0.012248 -0.070525 -0.046440 -v 0.012104 -0.070019 -0.044583 -v 0.026116 -0.071518 -0.049734 -v 0.014334 -0.068672 -0.039505 -v 0.027886 -0.071533 -0.045255 -v 0.025079 -0.073259 -0.050357 -v 0.014632 -0.071567 -0.050582 -v 0.027898 -0.071430 -0.043760 -v 0.027377 -0.071030 -0.045188 -v 0.027004 -0.070256 -0.042393 -v 0.025761 -0.069681 -0.040247 -v 0.024184 -0.072438 -0.050535 -v 0.023905 -0.069253 -0.038612 -v 0.022381 -0.072674 -0.051412 -v 0.021586 -0.068992 -0.037735 -v 0.020412 -0.072758 -0.051789 -v 0.019586 -0.068967 -0.037576 -v 0.016916 -0.068200 -0.037807 -v 0.017618 -0.069066 -0.037948 -v 0.026723 -0.071648 -0.047586 -v 0.015690 -0.072416 -0.050449 -v 0.013277 -0.070090 -0.041774 -v 0.013894 -0.071955 -0.048705 -v 0.015023 -0.069445 -0.039346 -v 0.012715 -0.070587 -0.043628 -v 0.012738 -0.071227 -0.046024 -v 0.030231 -0.014410 -0.098424 -v 0.026983 -0.014212 -0.097668 -v 0.027707 -0.014861 -0.095105 -v 0.030665 -0.014215 -0.095024 -v 0.029372 0.015336 -0.096717 -v 0.030269 0.014242 -0.098664 -v 0.029463 0.014568 -0.094285 -v 0.026692 0.014250 -0.096677 -v 0.034504 0.014285 -0.096609 -v 0.037668 0.014560 -0.097208 -v 0.033963 0.014452 -0.099284 -v 0.037043 0.014446 -0.100289 -v 0.035160 0.014189 -0.100448 -v 0.034542 -0.014287 -0.100147 -v 0.037280 -0.014940 -0.099926 -v 0.037075 -0.014235 -0.096634 -v 0.034144 -0.014392 -0.097053 -v 0.033902 -0.014021 -0.099007 -v 0.018039 -0.014586 -0.095664 -v 0.017767 -0.014391 -0.098527 -v 0.014470 -0.014489 -0.097550 -v 0.015355 -0.014260 -0.095192 -v 0.016125 -0.014021 -0.098790 -v 0.058975 -0.009524 -0.094292 -v 0.055458 -0.009609 -0.094055 -v 0.058006 -0.009640 -0.098088 -v 0.057291 -0.010733 -0.095448 -v 0.058856 0.009269 -0.095654 -v 0.058833 0.009269 -0.095918 -v 0.058766 -0.009368 -0.096174 -v 0.058766 0.009269 -0.096174 -v 0.058657 -0.009368 -0.096416 -v 0.058657 0.009269 -0.096416 -v 0.058509 -0.009368 -0.096635 -v 0.058509 0.009269 -0.096635 -v 0.058326 -0.009368 -0.096826 -v 0.058326 0.009269 -0.096826 -v 0.058113 0.009269 -0.096984 -v 0.058113 -0.009368 -0.096984 -v 0.057876 -0.009368 -0.097103 -v 0.057876 0.009269 -0.097103 -v 0.057623 -0.009368 -0.097181 -v 0.057623 0.009269 -0.097181 -v 0.057360 -0.009368 -0.097215 -v 0.057095 -0.009368 -0.097203 -v 0.057360 0.009269 -0.097215 -v 0.056836 -0.009368 -0.097147 -v 0.057095 0.009269 -0.097203 -v 0.056836 0.009269 -0.097147 -v 0.056590 -0.009368 -0.097049 -v 0.056590 0.009269 -0.097049 -v 0.056365 -0.009368 -0.096910 -v 0.056365 0.009269 -0.096910 -v 0.056166 0.009269 -0.096735 -v 0.056166 -0.009368 -0.096735 -v 0.055999 0.009269 -0.096529 -v 0.055999 -0.009368 -0.096529 -v 0.055870 -0.009368 -0.096297 -v 0.055870 0.009269 -0.096297 -v 0.055782 -0.009368 -0.096047 -v 0.055782 0.009269 -0.096047 -v 0.055737 -0.009368 -0.095786 -v 0.055737 0.009269 -0.095786 -v 0.055737 -0.009368 -0.095521 -v 0.055737 0.009269 -0.095521 -v 0.055782 -0.009368 -0.095260 -v 0.055782 0.009269 -0.095260 -v 0.055870 -0.009368 -0.095010 -v 0.055999 -0.009368 -0.094779 -v 0.055870 0.009269 -0.095010 -v 0.056166 -0.009368 -0.094573 -v 0.055999 0.009269 -0.094779 -v 0.056166 0.009269 -0.094573 -v 0.056365 -0.009368 -0.094398 -v 0.056365 0.009269 -0.094398 -v 0.056590 -0.009368 -0.094259 -v 0.056836 -0.009368 -0.094160 -v 0.056590 0.009269 -0.094259 -v 0.056836 0.009269 -0.094160 -v 0.057095 0.009269 -0.094104 -v 0.057095 -0.009368 -0.094104 -v 0.057360 0.009269 -0.094093 -v 0.057360 -0.009368 -0.094093 -v 0.057623 -0.009368 -0.094127 -v 0.057876 -0.009368 -0.094204 -v 0.057623 0.009269 -0.094127 -v 0.057876 0.009269 -0.094204 -v 0.058113 -0.009368 -0.094324 -v 0.058113 0.009269 -0.094324 -v 0.058326 -0.009368 -0.094481 -v 0.058509 -0.009368 -0.094673 -v 0.058326 0.009269 -0.094481 -v 0.058509 0.009269 -0.094673 -v 0.058657 -0.009368 -0.094892 -v 0.058766 -0.009368 -0.095133 -v 0.058657 0.009269 -0.094892 -v 0.058766 0.009269 -0.095133 -v 0.058833 -0.009368 -0.095390 -v 0.058833 0.009269 -0.095390 -v 0.058856 -0.009368 -0.095654 -v 0.058833 -0.009368 -0.095918 -v 0.058771 0.009639 -0.097365 -v 0.056827 0.009747 -0.093402 -v 0.055513 0.010041 -0.096397 -v 0.057302 0.009269 -0.097781 -v 0.059300 0.009351 -0.094869 -v 0.069532 -0.006462 -0.093524 -v 0.069732 -0.005936 -0.092000 -v 0.061029 -0.006350 -0.093524 -v 0.061029 0.006350 -0.093524 -v 0.064924 -0.002176 -0.093524 -v 0.058224 0.006350 -0.093524 -v 0.067137 0.007936 -0.093524 -v 0.063717 0.004676 -0.093524 -v 0.063415 0.007937 -0.093524 -v 0.068745 0.007281 -0.093524 -v 0.069900 -0.004762 -0.093524 -v 0.067010 0.002917 -0.093524 -v 0.069900 0.004763 -0.093524 -v 0.065634 -0.005929 -0.093524 -v 0.065968 0.002109 -0.093524 -v 0.067422 -0.007931 -0.093524 -v 0.067138 -0.003136 -0.093524 -v 0.067746 0.007928 -0.092000 -v 0.069783 0.005734 -0.093524 -v 0.067130 -0.007936 -0.092000 -v 0.063944 -0.003078 -0.092000 -v 0.061029 0.006350 -0.092000 -v 0.068555 -0.007397 -0.092000 -v 0.063413 -0.007936 -0.092000 -v 0.065404 -0.005866 -0.092000 -v 0.063873 0.005046 -0.092000 -v 0.065792 0.005825 -0.092000 -v 0.065081 0.002152 -0.092000 -v 0.061614 0.007132 -0.092000 -v 0.061861 0.007360 -0.093524 -v 0.063199 0.007934 -0.092000 -v 0.057326 0.006350 -0.100386 -v 0.056087 0.006350 -0.097629 -v 0.054795 0.006350 -0.098439 -v 0.055893 0.006350 -0.097304 -v 0.054555 0.006350 -0.098034 -v 0.057476 0.006350 -0.093634 -v 0.055633 0.006350 -0.095830 -v 0.055704 0.006350 -0.095458 -v 0.054178 0.006350 -0.095292 -v 0.054472 0.006350 -0.094400 -v 0.056004 0.006350 -0.094763 -v 0.056226 0.006350 -0.094456 -v 0.055748 0.006350 -0.096953 -v 0.054363 0.006350 -0.097605 -v 0.054220 0.006350 -0.097157 -v 0.055617 0.006350 -0.096209 -v 0.054093 0.006350 -0.096227 -v 0.054693 0.006350 -0.093985 -v 0.055616 0.006350 -0.092927 -v 0.055997 0.006350 -0.092651 -v 0.056840 0.006350 -0.092239 -v 0.057292 0.006350 -0.092107 -v 0.056327 -0.006350 -0.097923 -v 0.056728 0.006350 -0.098280 -v 0.056327 0.006350 -0.097923 -v 0.056087 -0.006350 -0.097629 -v 0.055748 -0.006350 -0.096953 -v 0.055655 0.006350 -0.096586 -v 0.055704 -0.006350 -0.095458 -v 0.055829 0.006350 -0.095100 -v 0.055829 -0.006350 -0.095100 -v 0.056490 -0.006350 -0.094184 -v 0.056490 0.006350 -0.094184 -v 0.056791 -0.006350 -0.093953 -v 0.056791 0.006350 -0.093953 -v 0.057122 -0.006350 -0.093768 -v 0.057122 0.006350 -0.093768 -v 0.057476 -0.006350 -0.093634 -v 0.057846 0.006350 -0.093552 -v 0.057846 -0.006350 -0.093552 -v 0.056745 -0.006350 -0.098289 -v 0.055403 -0.006350 -0.099153 -v 0.054220 -0.006350 -0.097157 -v 0.055893 -0.006350 -0.097304 -v 0.054363 -0.006350 -0.097605 -v 0.055079 -0.006350 -0.098813 -v 0.058224 -0.006350 -0.093524 -v 0.058224 -0.006350 -0.092000 -v 0.055633 -0.006350 -0.095830 -v 0.054109 -0.006350 -0.095757 -v 0.055617 -0.006350 -0.096209 -v 0.055655 -0.006350 -0.096586 -v 0.056226 -0.006350 -0.094456 -v 0.054960 -0.006350 -0.093598 -v 0.054693 -0.006350 -0.093985 -v 0.056004 -0.006350 -0.094763 -v 0.054472 -0.006350 -0.094400 -v 0.054300 -0.006350 -0.094838 -v 0.054178 -0.006350 -0.095292 -v 0.055616 -0.006350 -0.092927 -v 0.063373 -0.007936 -0.093524 -v 0.061866 -0.007363 -0.092000 -v 0.061763 -0.007284 -0.093524 -v 0.061029 -0.006350 -0.092000 -v 0.058224 0.006350 -0.092000 -v 0.057755 0.006350 -0.092027 -v 0.057755 -0.006350 -0.092027 -v 0.057292 -0.006350 -0.092107 -v 0.056840 -0.006350 -0.092239 -v 0.056407 0.006350 -0.092421 -v 0.056407 -0.006350 -0.092421 -v 0.055997 -0.006350 -0.092651 -v 0.055269 0.006350 -0.093244 -v 0.055269 -0.006350 -0.093244 -v 0.054960 0.006350 -0.093598 -v 0.054300 0.006350 -0.094838 -v 0.054109 0.006350 -0.095757 -v 0.054093 -0.006350 -0.096227 -v 0.054130 -0.006350 -0.096696 -v 0.054130 0.006350 -0.096696 -v 0.054555 -0.006350 -0.098034 -v 0.054795 -0.006350 -0.098439 -v 0.055079 0.006350 -0.098813 -v 0.055403 0.006350 -0.099153 -v 0.055909 0.006350 -0.099565 -v 0.055950 -0.006350 -0.099590 -v 0.057326 -0.006350 -0.100386 -v 0.058088 0.006350 -0.099066 -v 0.058088 -0.006350 -0.099066 -v 0.069900 -0.004762 -0.092000 -v 0.069899 0.005644 -0.092000 -v 0.067369 0.003753 -0.093524 -v 0.066992 0.005134 -0.093524 -v 0.065406 0.005867 -0.093524 -v 0.064132 0.002652 -0.093524 -v 0.063913 0.002978 -0.092000 -v 0.066821 0.002529 -0.092000 -v 0.067319 0.004676 -0.092000 -v 0.067346 -0.004507 -0.093524 -v 0.066693 -0.002491 -0.092000 -v 0.066350 -0.002296 -0.093524 -v 0.064951 -0.002141 -0.092000 -v 0.064117 -0.002787 -0.093524 -v 0.063667 -0.003758 -0.093524 -v 0.063812 -0.004816 -0.092000 -v 0.063967 -0.004994 -0.093524 -v 0.066993 -0.005133 -0.092000 -v 0.067369 -0.003753 -0.092000 -v 0.014031 -0.002671 -0.093027 -v 0.013591 -0.002066 -0.094789 -v 0.016867 0.001111 -0.095011 -v 0.014455 0.001007 -0.096452 -v 0.016279 0.001659 -0.094963 -v 0.016431 0.001543 -0.098626 -v 0.014309 0.002025 -0.097442 -v 0.018407 0.001456 -0.097969 -v 0.015149 0.000987 -0.098634 -v 0.017342 0.002383 -0.094645 -v 0.015889 0.001470 -0.098754 -v 0.016231 0.001737 -0.094669 -v 0.017838 0.002041 -0.098292 -v 0.018038 0.001995 -0.097644 -v 0.015230 0.002387 -0.095263 -v 0.017828 0.002559 -0.097878 -v 0.016615 0.001038 -0.098317 -v 0.018324 0.001214 -0.095694 -v 0.016975 0.000449 -0.099001 -v 0.017908 0.000777 -0.098294 -v 0.014658 0.000819 -0.095639 -v 0.016310 0.000058 -0.098808 -v 0.014914 0.000574 -0.097423 -v 0.018184 -0.000066 -0.096429 -v 0.016957 0.000551 -0.094837 -v 0.014929 0.000875 -0.098095 -v 0.017749 0.000895 -0.096077 -v 0.014460 0.000168 -0.097900 -v 0.014645 -0.000391 -0.095850 -v 0.018617 0.000499 -0.096434 -v 0.015277 -0.000698 -0.098883 -v 0.017107 -0.000304 -0.094954 -v 0.017621 -0.000408 -0.098758 -v 0.014646 -0.000873 -0.097422 -v 0.017923 -0.000513 -0.097833 -v 0.015761 0.000326 -0.094885 -v 0.014609 -0.000303 -0.096415 -v 0.014831 0.000162 -0.096579 -v 0.018555 -0.001089 -0.097556 -v 0.015610 -0.000851 -0.095039 -v 0.017505 0.000119 -0.098443 -v 0.017674 -0.001154 -0.095804 -v 0.018271 -0.000189 -0.095870 -v 0.014653 -0.001533 -0.095686 -v 0.018030 -0.000521 -0.098171 -v 0.014997 -0.002298 -0.097710 -v 0.015067 -0.000870 -0.095441 -v 0.017814 -0.002511 -0.098176 -v 0.017426 -0.002675 -0.094902 -v 0.016907 -0.002068 -0.099112 -v 0.017351 -0.002431 -0.095556 -v 0.017367 -0.001492 -0.098219 -v 0.016589 -0.001701 -0.095467 -v 0.018428 -0.001275 -0.097643 -v 0.018003 -0.001920 -0.095168 -v 0.014940 -0.001646 -0.098353 -v 0.015738 -0.001533 -0.094927 -v 0.015047 -0.001062 -0.098319 -v 0.014400 -0.002158 -0.097304 -v 0.017385 -0.001042 -0.095087 -v 0.015477 -0.001719 -0.098811 -v 0.016699 0.001530 -0.095425 -v 0.010418 0.002050 -0.100707 -v 0.010514 0.002708 -0.100851 -v 0.017586 0.002590 -0.098481 -v 0.010593 0.002190 -0.101111 -v 0.015961 0.002230 -0.098497 -v 0.010346 0.002348 -0.100511 -v 0.013485 -0.002270 -0.096098 -v 0.018071 -0.009906 -0.093364 -v 0.017796 -0.005080 -0.093091 -v 0.015171 -0.009906 -0.092770 -v 0.015463 -0.009906 -0.094766 -v 0.017120 -0.009906 -0.092773 -v 0.018440 -0.009906 -0.094062 -v 0.017637 -0.009906 -0.095521 -v 0.018841 -0.009906 -0.096331 -v 0.017925 -0.009906 -0.096362 -v 0.016188 -0.009906 -0.094667 -v 0.016966 -0.009906 -0.094879 -v 0.015363 -0.010312 -0.091403 -v 0.015386 -0.010148 -0.090980 -v 0.014409 -0.005080 -0.091431 -v 0.016535 -0.005080 -0.092522 -v 0.016916 -0.010191 -0.091862 -v 0.016535 -0.010148 -0.092522 -v 0.015171 -0.009906 -0.095088 -v 0.015171 -0.005080 -0.095122 -v 0.015176 -0.005080 -0.097276 -v 0.016454 -0.009934 -0.098195 -v 0.015332 -0.010163 -0.097568 -v 0.015171 -0.009934 -0.096909 -v 0.015874 -0.010248 -0.098053 -v 0.015013 -0.010246 -0.091462 -v 0.015170 -0.010035 -0.091735 -v 0.015085 -0.010260 -0.098434 -v 0.015306 -0.010312 -0.091376 -v 0.014409 -0.009934 -0.091735 -v 0.014502 -0.010245 -0.091299 -v 0.016747 -0.010274 -0.098931 -v 0.014409 -0.009934 -0.096909 -v 0.014464 -0.010145 -0.097452 -v 0.014976 -0.005081 -0.098358 -v 0.015675 -0.010106 -0.098800 -v 0.016794 -0.005080 -0.098910 -v 0.016916 -0.005080 -0.091862 -v 0.015261 -0.005080 -0.090909 -v 0.016044 -0.005081 -0.098919 -v 0.015171 -0.005080 -0.091735 -v 0.015418 -0.005080 -0.094784 -v 0.015171 -0.005080 -0.092770 -v 0.016287 -0.005080 -0.098222 -v 0.015624 -0.005080 -0.097881 -v 0.017891 -0.005080 -0.096231 -v 0.018841 -0.005080 -0.096331 -v 0.016200 -0.005080 -0.094663 -v 0.016904 -0.005080 -0.092771 -v 0.014526 -0.005080 -0.097588 -v 0.014409 -0.005080 -0.096909 -v 0.018212 -0.005080 -0.096441 -v 0.017317 -0.005080 -0.095083 -v 0.018424 -0.005080 -0.093970 -v 0.019111 -0.005080 -0.098181 -v 0.019085 -0.009934 -0.098145 -v 0.018574 -0.005080 -0.097824 -v 0.018551 -0.009934 -0.097827 -v 0.019744 -0.008081 -0.105485 -v 0.020135 -0.007772 -0.105588 -v 0.019562 0.010303 -0.103116 -v 0.020099 0.009169 -0.105401 -v 0.019960 0.007773 -0.105601 -v 0.019805 0.007773 -0.105538 -v 0.019518 0.010202 -0.103980 -v 0.019692 0.007773 -0.105414 -v 0.019648 0.007773 -0.105295 -v 0.018403 0.010313 -0.098236 -v 0.019941 0.010257 -0.103431 -v 0.018777 0.010142 -0.097908 -v 0.019126 0.010137 -0.098198 -v 0.019645 0.010313 -0.103101 -v 0.018470 0.010157 -0.098614 -v 0.018470 -0.010175 -0.098614 -v 0.019272 0.009934 -0.103167 -v 0.018470 -0.005080 -0.098614 -v 0.018470 0.005080 -0.098614 -v 0.018832 -0.010312 -0.098487 -v 0.019648 -0.007772 -0.105295 -v 0.019878 -0.007772 -0.105578 -v 0.019272 -0.009934 -0.103167 -v 0.018847 -0.010312 -0.098548 -v 0.019220 -0.010117 -0.098482 -v 0.019635 -0.010306 -0.104261 -v 0.020023 -0.009934 -0.103034 -v 0.020340 -0.007772 -0.105436 -v 0.020227 0.007773 -0.105545 -v 0.020397 -0.007772 -0.105290 -v 0.020398 0.007773 -0.105163 -v 0.020380 0.007773 -0.105332 -v 0.019650 0.010313 -0.103100 -v 0.019220 0.009934 -0.098482 -v 0.020023 0.009934 -0.103034 -v 0.019220 0.005080 -0.098482 -v 0.020348 -0.008725 -0.104877 -v 0.019220 -0.005080 -0.098482 -v 0.020398 -0.007772 -0.105163 -v 0.018212 0.009906 -0.096441 -v 0.016167 0.005080 -0.094665 -v 0.016219 0.009906 -0.094666 -v 0.015171 0.005080 -0.095088 -v 0.015455 0.005080 -0.094771 -v 0.015322 0.009906 -0.094818 -v 0.015171 0.009906 -0.092770 -v 0.017891 0.009906 -0.096231 -v 0.017317 0.009906 -0.095083 -v 0.018422 0.009906 -0.093966 -v 0.018841 0.009906 -0.096331 -v 0.017796 0.009906 -0.093091 -v 0.018071 0.005080 -0.093364 -v 0.016899 0.009906 -0.092771 -v 0.014790 0.010313 -0.095608 -v 0.014976 0.010272 -0.091405 -v 0.016250 0.009935 -0.098227 -v 0.015171 0.010106 -0.097121 -v 0.015306 0.010313 -0.091376 -v 0.014409 0.005080 -0.091413 -v 0.014409 0.009934 -0.096909 -v 0.015286 0.005080 -0.090923 -v 0.014409 0.010171 -0.091474 -v 0.016535 0.005080 -0.092522 -v 0.016535 0.010149 -0.092522 -v 0.016916 0.005080 -0.091862 -v 0.016916 0.010194 -0.091862 -v 0.015171 0.010039 -0.091735 -v 0.015171 0.009906 -0.095237 -v 0.016407 0.005080 -0.098203 -v 0.015172 0.005080 -0.097166 -v 0.018399 0.009934 -0.097853 -v 0.015171 0.005080 -0.091735 -v 0.015171 0.005080 -0.092770 -v 0.014409 0.005080 -0.096909 -v 0.014515 0.005081 -0.097595 -v 0.015580 0.005081 -0.097870 -v 0.017127 0.005080 -0.092776 -v 0.016966 0.005080 -0.094879 -v 0.019059 0.005080 -0.098104 -v 0.018441 0.005080 -0.094066 -v 0.017637 0.005080 -0.095521 -v 0.018522 0.005080 -0.097832 -v 0.018841 0.005080 -0.096331 -v 0.017925 0.005080 -0.096362 -v 0.015235 0.005082 -0.098581 -v 0.016794 0.005080 -0.098910 -v 0.016249 0.005084 -0.098935 -v 0.016791 0.010217 -0.098915 -v 0.015746 0.010083 -0.098824 -v 0.014877 0.010180 -0.098214 -v 0.014435 0.010101 -0.097267 -v 0.015363 0.010313 -0.091403 -v 0.015226 0.010169 -0.090892 -v 0.059616 -0.009318 -0.094522 -v 0.059925 -0.007794 -0.095905 -v 0.057300 -0.007794 -0.093929 -v 0.058969 -0.007794 -0.095466 -v 0.052439 -0.007794 -0.095994 -v 0.033341 -0.007794 -0.101074 -v 0.055617 -0.007794 -0.095804 -v 0.056582 -0.007794 -0.093048 -v 0.059065 -0.007794 -0.093739 -v 0.058761 -0.007794 -0.097801 -v 0.057237 -0.007794 -0.097461 -v 0.042272 -0.007794 -0.101074 -v 0.042272 -0.009318 -0.101074 -v 0.044103 -0.007794 -0.101035 -v 0.044103 -0.009318 -0.101035 -v 0.046975 -0.009318 -0.100826 -v 0.046677 -0.007794 -0.100858 -v 0.050338 -0.007794 -0.100322 -v 0.054636 -0.007794 -0.099289 -v 0.054192 -0.009318 -0.099402 -v 0.058530 -0.009318 -0.097918 -v 0.032947 -0.009318 -0.101074 -v 0.058423 -0.009318 -0.094232 -v 0.050621 -0.009318 -0.100267 -v 0.055758 -0.009318 -0.096004 -v 0.055949 -0.009318 -0.096509 -v 0.056220 -0.009318 -0.093308 -v 0.058013 -0.009318 -0.093112 -v 0.057813 -0.009318 -0.097465 -v 0.059790 -0.009318 -0.096411 -v 0.052439 -0.009318 -0.095994 -v 0.032947 -0.009318 -0.095994 -v 0.031767 0.007717 -0.095994 -v 0.031767 -0.007816 -0.095994 -v 0.032045 -0.008811 -0.095994 -v 0.033341 -0.007794 -0.095994 -v 0.032158 0.008893 -0.095994 -v 0.033341 0.007694 -0.095994 -v 0.050337 0.009269 -0.100322 -v 0.058530 0.007694 -0.097918 -v 0.058761 0.009269 -0.097801 -v 0.059790 0.007694 -0.096411 -v 0.057300 0.009269 -0.093929 -v 0.054641 0.009269 -0.099287 -v 0.046676 0.009269 -0.100858 -v 0.044103 0.009269 -0.101035 -v 0.042272 0.009269 -0.101074 -v 0.033341 0.009269 -0.095994 -v 0.033341 0.009269 -0.101074 -v 0.059590 0.009269 -0.094560 -v 0.052439 0.009269 -0.095994 -v 0.055617 0.009269 -0.095804 -v 0.056298 0.009269 -0.093246 -v 0.059787 0.009269 -0.096326 -v 0.057237 0.009269 -0.097461 -v 0.058337 0.009269 -0.093262 -v 0.056124 0.007694 -0.093369 -v 0.033341 0.007694 -0.101074 -v 0.052439 0.007694 -0.095994 -v 0.050622 0.007694 -0.100267 -v 0.055949 0.007694 -0.096509 -v 0.046975 0.007694 -0.100826 -v 0.056069 0.007694 -0.094263 -v 0.059438 0.007694 -0.094113 -v 0.059201 0.007694 -0.095648 -v 0.056983 0.007694 -0.097238 -v 0.054192 0.007694 -0.099402 -v 0.057580 0.007694 -0.093086 -v 0.042272 0.007694 -0.101074 -v 0.055758 0.007694 -0.096004 -v 0.044103 0.007694 -0.101035 -v 0.048172 0.007112 -0.094318 -v 0.048172 0.007112 -0.101049 -v 0.048172 -0.007112 -0.094318 -v 0.048172 -0.007112 -0.101049 -v 0.047410 -0.007112 -0.094318 -v 0.047410 -0.007112 -0.102126 -v 0.047410 -0.007112 -0.101430 -v 0.047874 -0.007112 -0.101818 -v 0.047410 0.009652 -0.095227 -v 0.046267 0.009652 -0.094089 -v 0.046267 -0.009652 -0.094089 -v 0.023331 -0.010414 -0.094089 -v 0.046267 -0.009652 -0.094851 -v 0.030604 -0.009652 -0.096198 -v 0.030395 -0.009652 -0.095695 -v 0.030086 -0.009652 -0.095310 -v 0.047407 -0.009652 -0.094543 -v 0.027225 -0.009652 -0.096607 -v 0.030623 -0.009652 -0.096733 -v 0.029501 -0.009652 -0.094969 -v 0.027872 -0.009652 -0.095263 -v 0.023331 -0.009652 -0.101430 -v 0.030314 -0.009652 -0.097548 -v 0.030546 -0.009652 -0.097084 -v 0.028069 -0.009652 -0.098023 -v 0.029239 -0.009652 -0.098195 -v 0.029801 -0.009652 -0.098002 -v 0.047410 -0.010414 -0.095227 -v 0.027479 -0.010414 -0.095605 -v 0.027580 -0.010414 -0.097394 -v 0.030623 -0.010414 -0.096733 -v 0.047410 -0.010414 -0.102192 -v 0.030490 -0.010414 -0.097251 -v 0.030073 -0.010414 -0.097809 -v 0.029585 -0.010414 -0.098098 -v 0.023331 -0.010414 -0.102192 -v 0.028559 -0.010414 -0.098201 -v 0.029548 -0.010414 -0.094990 -v 0.030083 -0.010414 -0.095307 -v 0.030493 -0.010414 -0.095862 -v 0.030623 -0.010414 -0.096373 -v 0.046267 -0.010414 -0.094089 -v 0.023331 -0.009652 -0.094851 -v 0.047410 0.007112 -0.094318 -v 0.047874 0.007112 -0.101818 -v 0.047410 0.007112 -0.101430 -v 0.048036 0.007112 -0.101589 -v 0.047661 -0.007112 -0.102001 -v 0.047661 0.007112 -0.102001 -v 0.048036 -0.007112 -0.101589 -v 0.048137 -0.007112 -0.101327 -v 0.048137 0.007112 -0.101327 -v 0.047410 -0.009652 -0.101430 -v 0.047410 0.007112 -0.102126 -v 0.023331 0.010414 -0.094089 -v 0.023331 0.010414 -0.102192 -v 0.047410 0.010414 -0.102192 -v 0.029059 0.010414 -0.094892 -v 0.029059 0.010414 -0.098214 -v 0.047410 0.010414 -0.095227 -v 0.046267 0.010414 -0.094089 -v 0.046884 0.010414 -0.094241 -v 0.030302 0.010414 -0.095385 -v 0.030594 0.010414 -0.096911 -v 0.030142 0.010414 -0.097664 -v 0.027279 0.009652 -0.096254 -v 0.027777 0.010414 -0.097864 -v 0.028124 0.009652 -0.095067 -v 0.027703 0.010414 -0.095258 -v 0.047090 0.009652 -0.094336 -v 0.023331 0.009652 -0.101430 -v 0.023331 0.009652 -0.094851 -v 0.027901 0.009652 -0.097888 -v 0.029414 0.009652 -0.094950 -v 0.029059 0.009652 -0.094892 -v 0.046267 0.009652 -0.094851 -v 0.047410 0.009652 -0.101430 -v 0.030176 0.009652 -0.095342 -v 0.030575 0.009652 -0.096728 -v 0.029414 0.009652 -0.098156 -v 0.035878 0.014021 -0.092921 -v 0.038109 0.012764 -0.093593 -v 0.035878 0.012764 -0.092921 -v 0.039838 0.014021 -0.096269 -v 0.039829 0.014021 -0.101275 -v 0.039840 0.012764 -0.100850 -v 0.033767 0.012764 -0.102445 -v 0.031112 0.012764 -0.101234 -v 0.032053 0.012764 -0.100869 -v 0.011707 0.012734 -0.102524 -v 0.013647 0.013688 -0.102446 -v 0.013576 0.013238 -0.102446 -v 0.013435 0.012936 -0.100922 -v 0.004237 0.014288 -0.104384 -v 0.005232 0.014288 -0.102360 -v 0.007276 0.014288 -0.103314 -v 0.006868 0.014288 -0.101845 -v 0.008843 0.014288 -0.102935 -v 0.000017 0.010478 -0.106732 -v -0.000855 0.010478 -0.105482 -v 0.000259 0.012235 -0.106558 -v -0.000730 0.011686 -0.105395 -v 0.000017 -0.010477 -0.106732 -v -0.000855 -0.010477 -0.105482 -v 0.000315 -0.012377 -0.106520 -v 0.001207 -0.014019 -0.104187 -v 0.002014 -0.013993 -0.105482 -v 0.002430 -0.014158 -0.105253 -v 0.013647 -0.014021 -0.102446 -v 0.012782 0.012471 -0.102459 -v 0.012883 -0.012576 -0.102458 -v 0.010867 -0.013820 -0.102609 -v 0.008843 -0.014287 -0.102935 -v 0.010407 0.014259 -0.102667 -v 0.011347 0.013255 -0.102557 -v 0.010867 0.013821 -0.102609 -v 0.001880 0.013931 -0.105556 -v 0.002288 0.014108 -0.105330 -v 0.001369 -0.013589 -0.105855 -v 0.000686 -0.012033 -0.106282 -v 0.001369 0.013589 -0.105855 -v 0.000686 0.012033 -0.106282 -v 0.003171 -0.014288 -0.104870 -v 0.002778 0.014241 -0.105071 -v 0.003317 0.014288 -0.104803 -v 0.004237 -0.014287 -0.104384 -v 0.005738 -0.014287 -0.103797 -v 0.005738 0.014288 -0.103797 -v 0.010147 0.014288 -0.102704 -v 0.007276 -0.014287 -0.103314 -v 0.008535 -0.014287 -0.101443 -v 0.003634 -0.014287 -0.102984 -v 0.011023 -0.013977 -0.101401 -v 0.010248 -0.014288 -0.102686 -v 0.010183 -0.014287 -0.101159 -v 0.013646 -0.013607 -0.102446 -v 0.013435 -0.012936 -0.102445 -v 0.012751 -0.012488 -0.100933 -v 0.012453 -0.012476 -0.102475 -v 0.011599 -0.012803 -0.102531 -v 0.013647 -0.014021 -0.100922 -v 0.035878 -0.014021 -0.092921 -v 0.015628 -0.012763 -0.092921 -v 0.031104 -0.014021 -0.102446 -v 0.031109 -0.010715 -0.102446 -v 0.031109 -0.010715 -0.100922 -v 0.031112 -0.012763 -0.101292 -v 0.031305 -0.014021 -0.101118 -v 0.038245 -0.012763 -0.102445 -v 0.039840 -0.014021 -0.100850 -v 0.039829 -0.012763 -0.101275 -v 0.039838 -0.012763 -0.096269 -v 0.039834 -0.014021 -0.096186 -v 0.038661 -0.014021 -0.093961 -v 0.037328 -0.012763 -0.093155 -v 0.015666 -0.014021 -0.097877 -v 0.017582 -0.014021 -0.097214 -v 0.017510 -0.014021 -0.096356 -v 0.027362 -0.014021 -0.096984 -v 0.028148 -0.014021 -0.098001 -v 0.027610 -0.014021 -0.097531 -v 0.030611 -0.014021 -0.096082 -v 0.034419 -0.014021 -0.097612 -v 0.034214 -0.014021 -0.098477 -v 0.030453 -0.014021 -0.097372 -v 0.029643 -0.014021 -0.098092 -v 0.017464 -0.014021 -0.097499 -v 0.017276 -0.014021 -0.097744 -v 0.016991 -0.014021 -0.097957 -v 0.035433 -0.014021 -0.100195 -v 0.033460 -0.014021 -0.102443 -v 0.027306 -0.014021 -0.096553 -v 0.016730 -0.014021 -0.095803 -v 0.015601 -0.014021 -0.095983 -v 0.037376 -0.014021 -0.097522 -v 0.027362 -0.014021 -0.096122 -v 0.015628 -0.014021 -0.092921 -v 0.027623 -0.014021 -0.095556 -v 0.037236 -0.014021 -0.099538 -v 0.032377 -0.014021 -0.100932 -v 0.035046 -0.014021 -0.097036 -v 0.035892 -0.014021 -0.096780 -v 0.036846 -0.014021 -0.093027 -v 0.038669 -0.014021 -0.102435 -v 0.016441 -0.014021 -0.098090 -v 0.034271 -0.014021 -0.098908 -v 0.028231 -0.014021 -0.095053 -v 0.028969 -0.014021 -0.094889 -v 0.014809 -0.012763 -0.093063 -v 0.014142 -0.014021 -0.093412 -v 0.013647 -0.014021 -0.094899 -v 0.017464 -0.012763 -0.096318 -v 0.034171 -0.012763 -0.098683 -v 0.027408 -0.012763 -0.095944 -v 0.027306 -0.012763 -0.096553 -v 0.017523 -0.012763 -0.097356 -v 0.037575 -0.012763 -0.097868 -v 0.030460 -0.012763 -0.097372 -v 0.033404 -0.012763 -0.102438 -v 0.030308 -0.012763 -0.095544 -v 0.029608 -0.012763 -0.094996 -v 0.029309 -0.012763 -0.098234 -v 0.035120 -0.012763 -0.096990 -v 0.032307 -0.012763 -0.100877 -v 0.035218 -0.012763 -0.100076 -v 0.036939 -0.012763 -0.099835 -v 0.030605 -0.012763 -0.096337 -v 0.038998 -0.012763 -0.094378 -v 0.035878 -0.012763 -0.092921 -v 0.027920 -0.012763 -0.095241 -v 0.017621 -0.012763 -0.096715 -v 0.017276 -0.012763 -0.096073 -v 0.015829 -0.012763 -0.095767 -v 0.027410 -0.012763 -0.097168 -v 0.027793 -0.012763 -0.097729 -v 0.013648 -0.012763 -0.094285 -v 0.015590 -0.012763 -0.097862 -v 0.013647 -0.012763 -0.100922 -v 0.017197 -0.012763 -0.097827 -v 0.013647 0.012764 -0.100922 -v 0.018022 -0.010715 -0.100922 -v 0.031109 -0.012763 -0.100922 -v 0.034960 0.012764 -0.099903 -v 0.015632 0.012764 -0.097840 -v 0.039834 0.012764 -0.096185 -v 0.037236 0.012764 -0.099538 -v 0.016441 0.012764 -0.098090 -v 0.034214 0.012764 -0.098477 -v 0.034282 0.012764 -0.098948 -v 0.015628 0.012764 -0.092921 -v 0.030633 0.012764 -0.096553 -v 0.037429 0.012764 -0.097646 -v 0.013647 0.012764 -0.094513 -v 0.015513 0.012764 -0.096040 -v 0.014489 0.012764 -0.093209 -v 0.027362 0.012764 -0.096122 -v 0.027623 0.012764 -0.095556 -v 0.035191 0.012764 -0.096945 -v 0.016441 0.012764 -0.095727 -v 0.027306 0.012764 -0.096553 -v 0.017336 0.012764 -0.096102 -v 0.034393 0.012764 -0.097659 -v 0.030453 0.012764 -0.097372 -v 0.017582 0.012764 -0.097214 -v 0.027362 0.012764 -0.096984 -v 0.017622 0.012764 -0.096758 -v 0.029643 0.012764 -0.098092 -v 0.028231 0.012764 -0.095053 -v 0.028969 0.012764 -0.094889 -v 0.029680 0.012764 -0.095037 -v 0.028148 0.012764 -0.098001 -v 0.027610 0.012764 -0.097531 -v 0.017464 0.012764 -0.097499 -v 0.017276 0.012764 -0.097744 -v 0.016991 0.012764 -0.097957 -v 0.031109 0.012764 -0.100922 -v 0.036846 0.012764 -0.093027 -v 0.030477 0.012764 -0.095761 -v 0.039112 0.012764 -0.094619 -v 0.038669 0.012764 -0.102435 -v 0.032734 0.012764 -0.101611 -v 0.031109 0.010716 -0.100922 -v 0.031109 0.010716 -0.102446 -v 0.018022 0.010716 -0.100922 -v 0.018022 -0.010715 -0.102446 -v 0.018022 0.010716 -0.102446 -v 0.013647 0.014021 -0.102446 -v 0.037673 0.014021 -0.093270 -v 0.039112 0.014021 -0.094619 -v 0.028969 0.014021 -0.094889 -v 0.028231 0.014021 -0.095053 -v 0.013648 0.014021 -0.094464 -v 0.015989 0.014021 -0.098039 -v 0.029680 0.014021 -0.095037 -v 0.016747 0.014021 -0.098049 -v 0.017191 0.014021 -0.097832 -v 0.017582 0.014021 -0.097214 -v 0.031262 0.014021 -0.101147 -v 0.017464 0.014021 -0.097499 -v 0.031108 0.014021 -0.102446 -v 0.030481 0.014021 -0.095762 -v 0.027623 0.014021 -0.095556 -v 0.015628 0.014021 -0.092921 -v 0.016353 0.014021 -0.095671 -v 0.014601 0.014021 -0.093138 -v 0.015110 0.014021 -0.096773 -v 0.017464 0.014021 -0.096318 -v 0.027362 0.014021 -0.096122 -v 0.017622 0.014021 -0.096756 -v 0.027306 0.014021 -0.096553 -v 0.027410 0.014021 -0.097168 -v 0.037575 0.014021 -0.097868 -v 0.030633 0.014021 -0.096553 -v 0.035191 0.014021 -0.096945 -v 0.034099 0.014021 -0.102446 -v 0.034921 0.014021 -0.100013 -v 0.038245 0.014021 -0.102445 -v 0.036939 0.014021 -0.099835 -v 0.027875 0.014021 -0.097817 -v 0.031938 0.014021 -0.100882 -v 0.029240 0.014021 -0.098206 -v 0.032463 0.014021 -0.101079 -v 0.034186 0.014021 -0.098017 -v 0.030339 0.014021 -0.097572 -v 0.033096 0.014021 -0.102153 -v 0.013647 0.014021 -0.100922 -v 0.012753 0.012510 -0.100935 -v 0.013530 -0.013098 -0.100921 -v 0.011347 -0.013254 -0.101026 -v 0.011787 0.012703 -0.100990 -v 0.011792 -0.012681 -0.100990 -v 0.011407 0.013125 -0.101021 -v 0.002434 0.014288 -0.103538 -v 0.001583 0.014195 -0.103973 -v 0.002075 -0.014274 -0.103718 -v 0.000584 -0.013659 -0.104549 -v 0.000695 0.013748 -0.104480 -v -0.000121 0.012962 -0.104988 -v -0.000109 -0.012971 -0.104980 -v -0.000756 -0.011587 -0.105412 -v 0.002434 -0.014287 -0.103538 -v 0.003634 0.014288 -0.102984 -v 0.005232 -0.014287 -0.102360 -v 0.006868 -0.014287 -0.101845 -v 0.008535 0.014288 -0.101443 -v 0.010181 0.014288 -0.101159 -v 0.011026 0.013975 -0.101366 -v 0.015294 -0.014021 -0.097191 -v 0.015395 -0.014021 -0.097457 -v 0.015557 0.015342 -0.097692 -v 0.015557 -0.014021 -0.097692 -v 0.015770 -0.014021 -0.097881 -v 0.016022 -0.014021 -0.098013 -v 0.016022 0.015342 -0.098013 -v 0.016298 0.015342 -0.098081 -v 0.016298 -0.014021 -0.098081 -v 0.016583 -0.014021 -0.098081 -v 0.016860 0.015342 -0.098013 -v 0.016860 -0.014021 -0.098013 -v 0.017112 0.015342 -0.097881 -v 0.017112 -0.014021 -0.097881 -v 0.017325 0.015342 -0.097692 -v 0.017325 -0.014021 -0.097692 -v 0.017487 0.015342 -0.097457 -v 0.017487 -0.014021 -0.097457 -v 0.017588 -0.014021 -0.097191 -v 0.017588 0.015342 -0.097191 -v 0.017622 -0.014021 -0.096909 -v 0.017588 -0.014021 -0.096626 -v 0.017487 -0.014021 -0.096360 -v 0.017325 -0.014021 -0.096125 -v 0.017325 0.015342 -0.096125 -v 0.017112 -0.014021 -0.095937 -v 0.016860 0.015342 -0.095804 -v 0.016860 -0.014021 -0.095804 -v 0.016583 0.015342 -0.095736 -v 0.016583 -0.014021 -0.095736 -v 0.016298 0.015342 -0.095736 -v 0.016298 -0.014021 -0.095736 -v 0.016022 0.015342 -0.095804 -v 0.016022 -0.014021 -0.095804 -v 0.015770 -0.014021 -0.095937 -v 0.015557 0.015342 -0.096125 -v 0.015557 -0.014021 -0.096125 -v 0.015395 -0.014021 -0.096360 -v 0.015294 -0.014021 -0.096626 -v 0.015260 -0.014021 -0.096909 -v 0.015294 0.015342 -0.096626 -v 0.015260 0.015342 -0.096909 -v 0.015294 0.015342 -0.097191 -v 0.015770 0.015342 -0.097881 -v 0.015395 0.015342 -0.097457 -v 0.016583 0.015342 -0.098081 -v 0.017487 0.015342 -0.096360 -v 0.017588 0.015342 -0.096626 -v 0.017622 0.015342 -0.096909 -v 0.017112 0.015342 -0.095937 -v 0.015770 0.015342 -0.095937 -v 0.015395 0.015342 -0.096360 -v 0.037230 0.012294 -0.099565 -v 0.037259 0.012294 -0.097404 -v 0.035956 0.012294 -0.096836 -v 0.034760 0.012294 -0.097199 -v 0.034541 0.012294 -0.102281 -v 0.035705 0.012294 -0.100188 -v 0.038674 0.012294 -0.102291 -v 0.031917 0.012294 -0.099362 -v 0.034213 0.012294 -0.099088 -v 0.032730 0.012294 -0.101037 -v 0.016822 0.010716 -0.092000 -v 0.016822 0.002312 -0.092000 -v 0.016822 0.010716 -0.093575 -v 0.029862 0.010015 -0.093575 -v 0.030315 0.009662 -0.092000 -v 0.030633 0.009654 -0.093575 -v 0.031337 0.009837 -0.092000 -v 0.031715 0.010127 -0.093575 -v 0.031916 0.012294 -0.092000 -v 0.031916 0.010719 -0.093575 -v 0.034552 0.010719 -0.099778 -v 0.034628 0.010719 -0.102293 -v 0.038408 0.010719 -0.102295 -v 0.037274 0.010719 -0.099599 -v 0.034486 0.010719 -0.097497 -v 0.032636 0.010719 -0.100954 -v 0.031916 0.010719 -0.099216 -v 0.035878 0.010719 -0.096716 -v 0.037265 0.010719 -0.097491 -v 0.038354 -0.010719 -0.102300 -v 0.039840 -0.012293 -0.100959 -v 0.031916 -0.012293 -0.098727 -v 0.032730 -0.010719 -0.101037 -v 0.034628 -0.012293 -0.102293 -v 0.034616 -0.012293 -0.097304 -v 0.031916 -0.012293 -0.092000 -v 0.036251 -0.012293 -0.096769 -v 0.039841 -0.012293 -0.092000 -v 0.034552 -0.012293 -0.099778 -v 0.038408 -0.012293 -0.102295 -v 0.037274 -0.012293 -0.099599 -v 0.032636 -0.012293 -0.100954 -v 0.037279 -0.012293 -0.097562 -v 0.039839 0.010719 -0.100962 -v 0.039841 0.012294 -0.100318 -v 0.039841 -0.010719 -0.093575 -v 0.039840 -0.010719 -0.101010 -v 0.037233 -0.010719 -0.099565 -v 0.037442 -0.010719 -0.097885 -v 0.036812 -0.010719 -0.097053 -v 0.035705 -0.010719 -0.100188 -v 0.034541 -0.010719 -0.102281 -v 0.034960 -0.010719 -0.096995 -v 0.034213 -0.010719 -0.099088 -v 0.031918 -0.010719 -0.099369 -v 0.031207 -0.009694 -0.093575 -v 0.029721 -0.010167 -0.093575 -v 0.016822 -0.010715 -0.093575 -v 0.016822 -0.010715 -0.092000 -v 0.018715 -0.008558 -0.093575 -v 0.020098 -0.008959 -0.093575 -v 0.021850 -0.007369 -0.093575 -v 0.021615 -0.006230 -0.093575 -v 0.031916 -0.010719 -0.092000 -v 0.021121 -0.008691 -0.092000 -v 0.031912 0.010519 -0.092000 -v 0.020098 0.008960 -0.092000 -v 0.021615 0.006230 -0.092000 -v 0.029494 0.010716 -0.092000 -v 0.030429 -0.009672 -0.092000 -v 0.031149 -0.009726 -0.092000 -v 0.019554 -0.008945 -0.092000 -v 0.029721 0.010168 -0.092000 -v 0.018811 0.005647 -0.092000 -v 0.039841 0.012294 -0.092000 -v 0.031718 -0.010170 -0.092000 -v 0.021653 -0.006340 -0.092000 -v 0.021860 -0.007279 -0.092000 -v 0.018420 -0.008162 -0.092000 -v 0.016822 -0.002311 -0.092000 -v 0.018200 -0.006601 -0.092000 -v 0.019252 -0.005419 -0.092000 -v 0.029721 -0.010167 -0.092000 -v 0.018145 0.007094 -0.092000 -v 0.029505 -0.010715 -0.092000 -v 0.020830 -0.005457 -0.092000 -v 0.021850 0.007370 -0.092000 -v 0.016822 -0.002311 -0.093575 -v 0.019682 -0.002286 -0.094859 -v 0.019592 0.002286 -0.094892 -v 0.015535 -0.002286 -0.093758 -v 0.015535 0.002286 -0.093758 -v 0.018712 0.002286 -0.094914 -v 0.014996 -0.002286 -0.095238 -v 0.014996 0.002286 -0.095238 -v 0.023056 0.002312 -0.093575 -v 0.021656 0.002286 -0.095226 -v 0.020355 0.002286 -0.094337 -v 0.019195 0.002286 -0.096742 -v 0.022791 0.002312 -0.092000 -v 0.021798 0.002286 -0.092361 -v 0.021169 0.002286 -0.092943 -v 0.021144 -0.002286 -0.092981 -v 0.022791 -0.002311 -0.092000 -v 0.018803 -0.002286 -0.096615 -v 0.018735 -0.002286 -0.094922 -v 0.020362 -0.002286 -0.094321 -v 0.021732 -0.002286 -0.092405 -v 0.022385 -0.002286 -0.092103 -v 0.031916 -0.010719 -0.093575 -v 0.016822 0.002312 -0.093575 -v 0.031851 -0.010432 -0.093575 -v 0.039841 0.010719 -0.093575 -v 0.029494 -0.010715 -0.093575 -v 0.018812 -0.005647 -0.093575 -v 0.018145 -0.007093 -0.093575 -v 0.020098 -0.005328 -0.093575 -v 0.023056 -0.002311 -0.093575 -v 0.021417 -0.002286 -0.095595 -v 0.031286 0.009779 -0.093575 -v 0.019551 0.008944 -0.093575 -v 0.029505 0.010716 -0.093575 -v 0.030154 -0.009777 -0.093575 -v 0.020677 -0.005445 -0.093575 -v 0.021860 0.007279 -0.093575 -v 0.019249 0.005420 -0.093575 -v 0.021174 -0.008612 -0.093575 -v 0.018200 0.006600 -0.093575 -v 0.020098 0.005328 -0.092000 -v 0.020828 0.005456 -0.093575 -v 0.020852 0.005537 -0.092000 -v 0.021653 0.006340 -0.093575 -v 0.021120 0.008693 -0.093575 -v 0.021174 0.008613 -0.092000 -v 0.018420 0.008163 -0.093575 -v 0.018715 0.008559 -0.092000 -v 0.030002 -0.078947 0.132954 -v 0.027286 -0.076358 0.130636 -v 0.031025 -0.076670 0.131264 -v 0.027697 -0.078694 0.133057 -v 0.030531 -0.096868 0.111010 -v 0.030499 -0.097098 0.111224 -v 0.030405 -0.078194 0.131938 -v 0.030405 -0.097318 0.111430 -v 0.030251 -0.097520 0.111618 -v 0.030251 -0.078396 0.132127 -v 0.030046 -0.078571 0.132290 -v 0.029796 -0.078713 0.132422 -v 0.030046 -0.097696 0.111782 -v 0.029512 -0.078815 0.132517 -v 0.029796 -0.097837 0.111914 -v 0.029512 -0.097939 0.112009 -v 0.029206 -0.097997 0.112063 -v 0.029206 -0.078873 0.132571 -v 0.028890 -0.098009 0.112074 -v 0.028890 -0.078884 0.132582 -v 0.028578 -0.078849 0.132549 -v 0.028578 -0.097974 0.112041 -v 0.028281 -0.078769 0.132475 -v 0.028281 -0.097893 0.111966 -v 0.028013 -0.078647 0.132361 -v 0.027784 -0.078487 0.132212 -v 0.028013 -0.097771 0.111852 -v 0.027784 -0.097612 0.111704 -v 0.027604 -0.078298 0.132035 -v 0.027604 -0.097422 0.111527 -v 0.027479 -0.097210 0.111329 -v 0.027479 -0.078085 0.131837 -v 0.027415 -0.096983 0.111118 -v 0.027415 -0.077859 0.131626 -v 0.027415 -0.077628 0.131410 -v 0.027415 -0.096752 0.110902 -v 0.027479 -0.077401 0.131199 -v 0.027479 -0.096526 0.110691 -v 0.027604 -0.077189 0.131001 -v 0.027604 -0.096313 0.110493 -v 0.027784 -0.076999 0.130824 -v 0.027784 -0.096123 0.110316 -v 0.028013 -0.076840 0.130676 -v 0.028013 -0.095964 0.110167 -v 0.028281 -0.095842 0.110053 -v 0.028281 -0.076718 0.130562 -v 0.028578 -0.076637 0.130487 -v 0.028890 -0.076602 0.130454 -v 0.028578 -0.095762 0.109978 -v 0.028890 -0.095727 0.109946 -v 0.029206 -0.076614 0.130465 -v 0.029206 -0.095738 0.109957 -v 0.029512 -0.095796 0.110011 -v 0.029512 -0.076672 0.130519 -v 0.029796 -0.076774 0.130614 -v 0.029796 -0.095898 0.110106 -v 0.030046 -0.096040 0.110238 -v 0.030046 -0.076915 0.130746 -v 0.030251 -0.077091 0.130909 -v 0.030251 -0.096215 0.110401 -v 0.030405 -0.096417 0.110590 -v 0.030405 -0.077293 0.131098 -v 0.030499 -0.077513 0.131304 -v 0.030500 -0.096638 0.110795 -v 0.030531 -0.077743 0.131518 -v 0.030499 -0.077973 0.131733 -v 0.028572 -0.098745 0.112412 -v 0.030574 -0.097662 0.110224 -v 0.030122 -0.095618 0.109613 -v 0.027016 -0.096129 0.109939 -v 0.037814 -0.097795 0.111712 -v 0.037701 -0.099390 0.112950 -v 0.033990 -0.099692 0.112819 -v 0.036093 -0.097152 0.110445 -v 0.034715 -0.096984 0.111118 -v 0.034280 -0.080153 0.134204 -v 0.034034 -0.078151 0.132141 -v 0.035957 -0.078201 0.133851 -v 0.036973 -0.077498 0.131701 -v 0.037830 -0.079900 0.133727 -v 0.014400 -0.078232 0.132521 -v 0.015535 -0.076504 0.130834 -v 0.018136 -0.076838 0.131313 -v 0.016987 -0.076659 0.130506 -v 0.017551 -0.079267 0.132939 -v 0.017506 -0.078936 0.133383 -v 0.059038 -0.081037 0.128718 -v 0.058898 -0.078992 0.126702 -v 0.056784 -0.078378 0.126841 -v 0.056177 -0.081437 0.128993 -v 0.055161 -0.079759 0.127295 -v 0.058856 -0.092969 0.113872 -v 0.058833 -0.093162 0.114052 -v 0.058766 -0.093350 0.114227 -v 0.058766 -0.080639 0.127857 -v 0.058657 -0.080816 0.128022 -v 0.058509 -0.080976 0.128172 -v 0.058657 -0.093526 0.114392 -v 0.058509 -0.093687 0.114541 -v 0.058326 -0.081116 0.128302 -v 0.058113 -0.081231 0.128410 -v 0.058326 -0.093827 0.114672 -v 0.058113 -0.093942 0.114779 -v 0.057876 -0.081319 0.128491 -v 0.057876 -0.094029 0.114861 -v 0.057623 -0.094086 0.114914 -v 0.057623 -0.081375 0.128544 -v 0.057360 -0.081400 0.128567 -v 0.057360 -0.094110 0.114937 -v 0.057095 -0.081392 0.128559 -v 0.057095 -0.094102 0.114929 -v 0.056836 -0.081351 0.128521 -v 0.056590 -0.081279 0.128454 -v 0.056836 -0.094061 0.114891 -v 0.056590 -0.093989 0.114823 -v 0.056365 -0.093888 0.114729 -v 0.056365 -0.081177 0.128359 -v 0.056166 -0.081049 0.128240 -v 0.056166 -0.093760 0.114609 -v 0.055999 -0.080898 0.128099 -v 0.055999 -0.093609 0.114469 -v 0.055870 -0.080729 0.127941 -v 0.055870 -0.093440 0.114311 -v 0.055782 -0.080546 0.127771 -v 0.055782 -0.093257 0.114141 -v 0.055737 -0.080355 0.127593 -v 0.055737 -0.093066 0.113962 -v 0.055737 -0.080162 0.127412 -v 0.055782 -0.079971 0.127234 -v 0.055737 -0.092872 0.113782 -v 0.055782 -0.092681 0.113604 -v 0.055870 -0.092498 0.113433 -v 0.055870 -0.079788 0.127064 -v 0.055999 -0.092329 0.113276 -v 0.055999 -0.079619 0.126906 -v 0.056166 -0.092179 0.113135 -v 0.056166 -0.079468 0.126765 -v 0.056365 -0.079340 0.126646 -v 0.056365 -0.092051 0.113016 -v 0.056590 -0.079238 0.126551 -v 0.056836 -0.079166 0.126484 -v 0.056590 -0.091949 0.112921 -v 0.056836 -0.091877 0.112853 -v 0.057095 -0.091836 0.112815 -v 0.057095 -0.079125 0.126446 -v 0.057360 -0.079117 0.126438 -v 0.057360 -0.091828 0.112808 -v 0.057623 -0.091852 0.112831 -v 0.057623 -0.079142 0.126461 -v 0.057876 -0.079198 0.126514 -v 0.057876 -0.091909 0.112884 -v 0.058113 -0.091996 0.112965 -v 0.058113 -0.079286 0.126595 -v 0.058326 -0.079401 0.126703 -v 0.058326 -0.092111 0.113072 -v 0.058509 -0.079541 0.126833 -v 0.058509 -0.092251 0.113203 -v 0.058657 -0.092412 0.113353 -v 0.058657 -0.079701 0.126983 -v 0.058766 -0.092588 0.113517 -v 0.058766 -0.079878 0.127148 -v 0.058833 -0.092776 0.113692 -v 0.058833 -0.080065 0.127323 -v 0.058856 -0.080258 0.127503 -v 0.058833 -0.080452 0.127683 -v 0.055285 -0.092132 0.112729 -v 0.057724 -0.094884 0.115351 -v 0.059128 -0.092220 0.112857 -v 0.057240 -0.093971 0.112941 -v 0.059363 -0.092846 0.113757 -v 0.061029 -0.089421 0.114554 -v 0.064926 -0.083606 0.120789 -v 0.058224 -0.080759 0.123842 -v 0.063418 -0.090503 0.113393 -v 0.061029 -0.080759 0.123842 -v 0.069900 -0.088787 0.115233 -v 0.061763 -0.080122 0.124525 -v 0.063373 -0.079678 0.125002 -v 0.069532 -0.080683 0.123925 -v 0.069900 -0.081842 0.122681 -v 0.067420 -0.079681 0.124998 -v 0.067347 -0.082017 0.122494 -v 0.067141 -0.082988 0.121453 -v 0.067134 -0.090503 0.113394 -v 0.068743 -0.090057 0.113872 -v 0.065942 -0.082509 0.119731 -v 0.064098 -0.082202 0.120061 -v 0.061029 -0.079645 0.122803 -v 0.069899 -0.087825 0.114032 -v 0.069899 -0.080274 0.122129 -v 0.068743 -0.079009 0.123485 -v 0.067130 -0.078563 0.123963 -v 0.061762 -0.088943 0.112832 -v 0.067747 -0.089382 0.112361 -v 0.065403 -0.085379 0.116653 -v 0.061029 -0.088306 0.113515 -v 0.061865 -0.090111 0.113814 -v 0.063370 -0.089388 0.112355 -v 0.057326 -0.094440 0.119234 -v 0.055403 -0.093538 0.118393 -v 0.056327 -0.092638 0.117554 -v 0.056087 -0.092423 0.117354 -v 0.054795 -0.093015 0.117906 -v 0.055893 -0.092185 0.117132 -v 0.058224 -0.088306 0.113515 -v 0.054178 -0.090714 0.115760 -v 0.055704 -0.090835 0.115873 -v 0.054300 -0.090382 0.115450 -v 0.054472 -0.090062 0.115152 -v 0.056004 -0.090327 0.115399 -v 0.056226 -0.090102 0.115190 -v 0.054363 -0.092406 0.117337 -v 0.055655 -0.091660 0.116642 -v 0.054220 -0.092078 0.117032 -v 0.055617 -0.091384 0.116385 -v 0.054093 -0.091398 0.116397 -v 0.055633 -0.091107 0.116127 -v 0.054109 -0.091054 0.116077 -v 0.056490 -0.089904 0.115004 -v 0.056791 -0.089735 0.114847 -v 0.055616 -0.088984 0.114147 -v 0.055997 -0.088783 0.113959 -v 0.057122 -0.089600 0.114721 -v 0.057476 -0.089501 0.114629 -v 0.056327 -0.083977 0.126842 -v 0.056727 -0.092899 0.117797 -v 0.056087 -0.083762 0.126642 -v 0.055748 -0.091929 0.116893 -v 0.055748 -0.083268 0.126181 -v 0.055829 -0.090573 0.115629 -v 0.056791 -0.081073 0.124135 -v 0.057122 -0.080938 0.124009 -v 0.057846 -0.089441 0.114573 -v 0.058224 -0.089421 0.114554 -v 0.056744 -0.084244 0.127091 -v 0.055945 -0.085194 0.127977 -v 0.055403 -0.084876 0.127681 -v 0.055655 -0.082999 0.125930 -v 0.054220 -0.083416 0.126320 -v 0.054363 -0.083744 0.126626 -v 0.054555 -0.084058 0.126918 -v 0.055893 -0.083524 0.126420 -v 0.055079 -0.084628 0.127450 -v 0.057846 -0.080780 0.123861 -v 0.055633 -0.082446 0.125415 -v 0.055617 -0.082723 0.125673 -v 0.054093 -0.082736 0.125686 -v 0.054130 -0.083079 0.126005 -v 0.054960 -0.080814 0.123893 -v 0.056226 -0.081441 0.124478 -v 0.056004 -0.081666 0.124687 -v 0.054693 -0.081097 0.124157 -v 0.055829 -0.081912 0.124917 -v 0.055704 -0.082174 0.125161 -v 0.054300 -0.081720 0.124738 -v 0.057755 -0.079664 0.122821 -v 0.057292 -0.079723 0.122876 -v 0.057476 -0.080840 0.123917 -v 0.056490 -0.081242 0.124292 -v 0.055616 -0.080323 0.123435 -v 0.061865 -0.078954 0.123543 -v 0.063413 -0.078563 0.123963 -v 0.058224 -0.079645 0.122803 -v 0.057755 -0.088326 0.113533 -v 0.057292 -0.088384 0.113587 -v 0.056840 -0.088481 0.113677 -v 0.056840 -0.079819 0.122966 -v 0.056407 -0.088614 0.113802 -v 0.056407 -0.079953 0.123090 -v 0.055997 -0.080121 0.123247 -v 0.055269 -0.089216 0.114363 -v 0.054960 -0.089475 0.114605 -v 0.055269 -0.080555 0.123651 -v 0.054693 -0.089758 0.114869 -v 0.054472 -0.081400 0.124440 -v 0.054178 -0.082053 0.125048 -v 0.054109 -0.082393 0.125365 -v 0.054130 -0.091740 0.116717 -v 0.054555 -0.092719 0.117630 -v 0.054795 -0.084354 0.127194 -v 0.055079 -0.093289 0.118161 -v 0.055905 -0.093836 0.118672 -v 0.057326 -0.085778 0.128522 -v 0.058088 -0.093474 0.118334 -v 0.058088 -0.084813 0.127622 -v 0.067369 -0.087649 0.116454 -v 0.066993 -0.088591 0.115444 -v 0.065794 -0.087948 0.113899 -v 0.065404 -0.089092 0.114908 -v 0.063873 -0.087417 0.114468 -v 0.063717 -0.088278 0.115779 -v 0.064134 -0.086898 0.117260 -v 0.063913 -0.086007 0.115980 -v 0.065479 -0.086533 0.117650 -v 0.066704 -0.086796 0.117369 -v 0.067010 -0.085895 0.116100 -v 0.067319 -0.087165 0.114739 -v 0.067318 -0.081761 0.120533 -v 0.066346 -0.083526 0.120876 -v 0.064117 -0.083190 0.121236 -v 0.063667 -0.082528 0.121945 -v 0.063813 -0.080691 0.121681 -v 0.063969 -0.081683 0.122852 -v 0.065404 -0.079974 0.122449 -v 0.065634 -0.081047 0.123534 -v 0.066993 -0.080475 0.121913 -v 0.013781 -0.085628 0.122269 -v 0.017516 -0.084592 0.122389 -v 0.013774 -0.084870 0.122776 -v 0.014986 -0.087639 0.120203 -v 0.017937 -0.089508 0.120624 -v 0.014947 -0.089330 0.121089 -v 0.014460 -0.088108 0.119678 -v 0.015342 -0.089452 0.122049 -v 0.016582 -0.087120 0.118650 -v 0.016177 -0.090441 0.121367 -v 0.018414 -0.089540 0.121083 -v 0.017795 -0.087395 0.119731 -v 0.017144 -0.087370 0.118932 -v 0.014611 -0.087471 0.119741 -v 0.016556 -0.090049 0.121828 -v 0.018510 -0.089477 0.120232 -v 0.017369 -0.087888 0.118436 -v 0.014339 -0.089333 0.120071 -v 0.014689 -0.088676 0.120338 -v 0.018160 -0.088600 0.120674 -v 0.018446 -0.087580 0.120296 -v 0.016571 -0.087033 0.119932 -v 0.018154 -0.088647 0.121599 -v 0.015211 -0.086427 0.119778 -v 0.015025 -0.089221 0.121821 -v 0.016532 -0.088983 0.122812 -v 0.015430 -0.086991 0.119534 -v 0.015577 -0.088697 0.122391 -v 0.017205 -0.089232 0.121638 -v 0.018413 -0.088584 0.122151 -v 0.015418 -0.088925 0.121808 -v 0.014347 -0.087192 0.122231 -v 0.018715 -0.086947 0.121707 -v 0.015739 -0.085667 0.120489 -v 0.017959 -0.087464 0.123135 -v 0.014311 -0.087139 0.121527 -v 0.017514 -0.086067 0.121294 -v 0.016097 -0.089232 0.122969 -v 0.016260 -0.086641 0.120410 -v 0.018455 -0.086912 0.120346 -v 0.014674 -0.087136 0.120593 -v 0.015552 -0.088442 0.123504 -v 0.014320 -0.087288 0.121707 -v 0.018355 -0.085603 0.121547 -v 0.017279 -0.086036 0.120979 -v 0.016493 -0.085080 0.122138 -v 0.016339 -0.088657 0.123153 -v 0.018189 -0.086935 0.120979 -v 0.018531 -0.086722 0.121847 -v 0.016511 -0.084513 0.121767 -v 0.015333 -0.087463 0.123523 -v 0.017085 -0.087247 0.124545 -v 0.015541 -0.087903 0.124156 -v 0.015298 -0.085450 0.121593 -v 0.017936 -0.086514 0.122503 -v 0.016905 -0.085200 0.121243 -v 0.014233 -0.086396 0.122434 -v 0.016405 -0.085556 0.120746 -v 0.018580 -0.085963 0.123027 -v 0.016982 -0.087309 0.124037 -v 0.016561 -0.088306 0.123991 -v 0.014588 -0.086253 0.123364 -v 0.018504 -0.085961 0.122613 -v 0.014849 -0.087937 0.123328 -v 0.010535 -0.092006 0.122794 -v 0.010365 -0.091711 0.122425 -v 0.010554 -0.092379 0.122416 -v 0.017460 -0.090408 0.120465 -v 0.017525 -0.090388 0.120961 -v 0.016565 -0.090060 0.120862 -v 0.010381 -0.092027 0.122132 -v 0.013717 -0.082778 0.120878 -v 0.013864 -0.083298 0.120316 -v 0.017585 -0.077932 0.126068 -v 0.015171 -0.077783 0.125929 -v 0.015462 -0.079243 0.127290 -v 0.016876 -0.077783 0.125929 -v 0.018392 -0.078543 0.126639 -v 0.017228 -0.079454 0.127487 -v 0.017926 -0.080409 0.128379 -v 0.018841 -0.080387 0.128357 -v 0.017709 -0.079909 0.127911 -v 0.016331 -0.079170 0.127223 -v 0.015171 -0.082795 0.124004 -v 0.015306 -0.076486 0.125275 -v 0.015363 -0.076506 0.125293 -v 0.015350 -0.079749 0.121164 -v 0.014562 -0.079934 0.121336 -v 0.014409 -0.077007 0.125243 -v 0.016535 -0.080893 0.122230 -v 0.016916 -0.080410 0.121780 -v 0.016916 -0.076947 0.125494 -v 0.016535 -0.077435 0.125937 -v 0.016725 -0.077083 0.125832 -v 0.015170 -0.076921 0.125334 -v 0.015171 -0.080317 0.121693 -v 0.015171 -0.079479 0.127510 -v 0.016512 -0.081724 0.129643 -v 0.015174 -0.084288 0.125397 -v 0.015171 -0.080791 0.128772 -v 0.015331 -0.081127 0.129376 -v 0.014805 -0.076218 0.125070 -v 0.015321 -0.076281 0.124860 -v 0.014480 -0.076563 0.125212 -v 0.016371 -0.082191 0.130260 -v 0.015567 -0.081905 0.130293 -v 0.014409 -0.080791 0.128772 -v 0.014409 -0.084341 0.125445 -v 0.014529 -0.081210 0.129359 -v 0.014977 -0.085156 0.126214 -v 0.016617 -0.085601 0.126623 -v 0.015416 -0.082548 0.123774 -v 0.016384 -0.085051 0.126107 -v 0.017949 -0.083716 0.124862 -v 0.014409 -0.080317 0.121693 -v 0.015171 -0.081074 0.122399 -v 0.015740 -0.085496 0.126522 -v 0.015613 -0.084821 0.125895 -v 0.018841 -0.083678 0.124828 -v 0.018402 -0.081865 0.123137 -v 0.016353 -0.082459 0.123690 -v 0.016901 -0.081075 0.122400 -v 0.019018 -0.084924 0.125989 -v 0.017654 -0.081252 0.122566 -v 0.017146 -0.082709 0.123924 -v 0.017675 -0.083134 0.124320 -v 0.018434 -0.084788 0.125861 -v 0.018549 -0.081462 0.129398 -v 0.019648 -0.088399 0.132911 -v 0.019715 -0.087954 0.133633 -v 0.019878 -0.088605 0.133103 -v 0.019960 -0.099223 0.121751 -v 0.020002 -0.088627 0.133124 -v 0.019645 -0.099127 0.118188 -v 0.019805 -0.099178 0.121707 -v 0.019692 -0.099087 0.121623 -v 0.019272 -0.098917 0.118509 -v 0.020113 -0.100015 0.120614 -v 0.019648 -0.099000 0.121542 -v 0.019832 -0.099421 0.118462 -v 0.018844 -0.095204 0.114817 -v 0.019220 -0.095491 0.115314 -v 0.019133 -0.095464 0.114976 -v 0.019521 -0.099159 0.118258 -v 0.018470 -0.095740 0.115241 -v 0.019484 -0.099678 0.118943 -v 0.018470 -0.081874 0.130111 -v 0.018470 -0.092277 0.118954 -v 0.018470 -0.085348 0.126385 -v 0.018726 -0.081516 0.129958 -v 0.019272 -0.085368 0.133040 -v 0.019046 -0.081718 0.130129 -v 0.019180 -0.081777 0.129692 -v 0.020023 -0.085271 0.132949 -v 0.019976 -0.085825 0.133960 -v 0.020179 -0.088602 0.133101 -v 0.020227 -0.099183 0.121712 -v 0.020394 -0.087943 0.133497 -v 0.020398 -0.098903 0.121452 -v 0.020402 -0.098975 0.121519 -v 0.019650 -0.099127 0.118187 -v 0.020358 -0.099078 0.121615 -v 0.020023 -0.098821 0.118419 -v 0.019220 -0.085252 0.126295 -v 0.020398 -0.088302 0.132820 -v 0.019220 -0.092181 0.118864 -v 0.015171 -0.093099 0.113122 -v 0.015171 -0.089732 0.116581 -v 0.015403 -0.089480 0.116346 -v 0.015171 -0.091295 0.111439 -v 0.015322 -0.092792 0.112836 -v 0.016369 -0.092682 0.112733 -v 0.018841 -0.093899 0.113868 -v 0.017652 -0.091473 0.111605 -v 0.017949 -0.093936 0.113902 -v 0.017675 -0.093355 0.113360 -v 0.017147 -0.092931 0.112964 -v 0.018841 -0.090607 0.117397 -v 0.018399 -0.092082 0.112173 -v 0.018441 -0.088951 0.115853 -v 0.018071 -0.088438 0.115374 -v 0.016901 -0.091295 0.111439 -v 0.016018 -0.095397 0.114891 -v 0.015170 -0.094552 0.114136 -v 0.016724 -0.095776 0.115059 -v 0.016595 -0.095263 0.115102 -v 0.014792 -0.094599 0.113964 -v 0.015306 -0.090552 0.110191 -v 0.015363 -0.090572 0.110209 -v 0.016683 -0.091213 0.110786 -v 0.014409 -0.090556 0.110713 -v 0.015350 -0.086678 0.113734 -v 0.016916 -0.087339 0.114350 -v 0.015438 -0.090093 0.110146 -v 0.016535 -0.091199 0.111178 -v 0.016916 -0.090765 0.110676 -v 0.015170 -0.090700 0.110557 -v 0.015363 -0.094963 0.114632 -v 0.018395 -0.095032 0.114886 -v 0.019059 -0.091905 0.118607 -v 0.016535 -0.087822 0.114800 -v 0.015171 -0.088003 0.114969 -v 0.015171 -0.087246 0.114263 -v 0.014409 -0.087246 0.114263 -v 0.014563 -0.086863 0.113905 -v 0.015173 -0.091297 0.118040 -v 0.015624 -0.091742 0.118455 -v 0.017126 -0.088008 0.114973 -v 0.017452 -0.089831 0.116673 -v 0.016460 -0.089391 0.116263 -v 0.018522 -0.091706 0.118421 -v 0.017946 -0.090620 0.117407 -v 0.016302 -0.091990 0.118686 -v 0.016743 -0.092509 0.119168 -v 0.014409 -0.091030 0.117791 -v 0.014435 -0.094717 0.114361 -v 0.014566 -0.091666 0.118383 -v 0.015955 -0.095965 0.115412 -v 0.015538 -0.092387 0.119055 -v 0.014731 -0.095430 0.114742 -v 0.014409 -0.094340 0.114241 -v 0.016739 -0.095872 0.115165 -v 0.014647 -0.090387 0.110054 -v 0.015040 -0.090229 0.109958 -v 0.056401 -0.078482 0.125777 -v 0.058761 -0.082903 0.127815 -v 0.059863 -0.081671 0.126667 -v 0.054624 -0.083993 0.128832 -v 0.044103 -0.085268 0.130021 -v 0.042272 -0.085297 0.130047 -v 0.033341 -0.085297 0.130047 -v 0.057300 -0.080072 0.125175 -v 0.056300 -0.079571 0.124708 -v 0.055616 -0.081442 0.126453 -v 0.057905 -0.079512 0.124654 -v 0.059362 -0.080169 0.125266 -v 0.056638 -0.082409 0.127355 -v 0.059054 -0.081764 0.126753 -v 0.042272 -0.084257 0.131163 -v 0.044103 -0.084228 0.131136 -v 0.046706 -0.085136 0.129897 -v 0.047005 -0.084073 0.130991 -v 0.050339 -0.084746 0.129534 -v 0.058531 -0.081948 0.129010 -v 0.032947 -0.084257 0.131163 -v 0.052439 -0.080541 0.127698 -v 0.032947 -0.080541 0.127698 -v 0.056069 -0.079275 0.126517 -v 0.050622 -0.083666 0.130612 -v 0.059615 -0.079464 0.126694 -v 0.058408 -0.078589 0.125876 -v 0.055758 -0.080549 0.127705 -v 0.055950 -0.080918 0.128050 -v 0.056983 -0.081451 0.128547 -v 0.054179 -0.083036 0.130025 -v 0.059790 -0.080847 0.127982 -v 0.059202 -0.080288 0.127462 -v 0.052439 -0.081581 0.126583 -v 0.052439 -0.092144 0.115256 -v 0.052439 -0.093218 0.114104 -v 0.031768 -0.092751 0.114605 -v 0.031767 -0.081096 0.127103 -v 0.033341 -0.081581 0.126583 -v 0.033341 -0.092144 0.115256 -v 0.050330 -0.096384 0.117057 -v 0.052420 -0.094980 0.117900 -v 0.054628 -0.095630 0.116353 -v 0.046692 -0.096773 0.117420 -v 0.044103 -0.096905 0.117542 -v 0.042272 -0.096933 0.117569 -v 0.033341 -0.093218 0.114104 -v 0.033341 -0.096933 0.117569 -v 0.056298 -0.091208 0.112230 -v 0.055617 -0.093079 0.113974 -v 0.059866 -0.092525 0.113458 -v 0.057914 -0.091684 0.112674 -v 0.056638 -0.094046 0.114876 -v 0.059428 -0.094029 0.114861 -v 0.058651 -0.093741 0.114592 -v 0.058478 -0.094621 0.115414 -v 0.058338 -0.091220 0.112241 -v 0.059935 -0.091980 0.115103 -v 0.049564 -0.095405 0.118297 -v 0.055949 -0.092520 0.115606 -v 0.047005 -0.095675 0.118549 -v 0.056543 -0.090013 0.113269 -v 0.055951 -0.091114 0.114296 -v 0.058964 -0.092319 0.115420 -v 0.058818 -0.093443 0.116468 -v 0.056982 -0.093054 0.116104 -v 0.055938 -0.094240 0.117210 -v 0.058965 -0.090430 0.113657 -v 0.058009 -0.090806 0.114009 -v 0.033341 -0.095859 0.118720 -v 0.042272 -0.095859 0.118721 -v 0.055758 -0.092151 0.115263 -v 0.044103 -0.095831 0.118694 -v 0.048172 -0.090521 0.114538 -v 0.048172 -0.080820 0.124941 -v 0.048172 -0.085743 0.129531 -v 0.047410 -0.086022 0.129791 -v 0.047661 -0.086440 0.130181 -v 0.047874 -0.086306 0.130056 -v 0.048137 -0.085947 0.129721 -v 0.047410 -0.092918 0.113300 -v 0.046884 -0.092717 0.112071 -v 0.023331 -0.092606 0.111967 -v 0.046267 -0.092086 0.112525 -v 0.046267 -0.078921 0.126643 -v 0.030604 -0.080463 0.128081 -v 0.030395 -0.080095 0.127738 -v 0.046267 -0.079478 0.127162 -v 0.030087 -0.079814 0.127475 -v 0.047407 -0.079253 0.126952 -v 0.027225 -0.080762 0.128360 -v 0.023331 -0.079478 0.127162 -v 0.030623 -0.080854 0.128446 -v 0.047410 -0.084289 0.131649 -v 0.029501 -0.079564 0.127243 -v 0.027870 -0.079780 0.127444 -v 0.030313 -0.081452 0.129002 -v 0.030546 -0.081111 0.128685 -v 0.028068 -0.081797 0.129325 -v 0.029239 -0.081923 0.129443 -v 0.029800 -0.081784 0.129312 -v 0.047410 -0.079233 0.127976 -v 0.023331 -0.078401 0.127200 -v 0.027479 -0.079509 0.128233 -v 0.027531 -0.080869 0.129500 -v 0.030084 -0.079292 0.128031 -v 0.047410 -0.084327 0.132726 -v 0.030491 -0.080711 0.129354 -v 0.030076 -0.081120 0.129735 -v 0.029585 -0.081333 0.129934 -v 0.028558 -0.081408 0.130005 -v 0.029431 -0.079023 0.127780 -v 0.030493 -0.079699 0.128410 -v 0.030623 -0.080335 0.129003 -v 0.030623 -0.080072 0.128758 -v 0.046267 -0.078401 0.127200 -v 0.023331 -0.098532 0.117493 -v 0.023331 -0.084327 0.132726 -v 0.023331 -0.084289 0.131649 -v 0.047410 -0.080820 0.124941 -v 0.048036 -0.095839 0.119497 -v 0.047410 -0.095722 0.119388 -v 0.047410 -0.096232 0.119864 -v 0.047410 -0.090521 0.114538 -v 0.048172 -0.095444 0.119129 -v 0.048137 -0.095648 0.119319 -v 0.047661 -0.096140 0.119778 -v 0.047874 -0.096007 0.119653 -v 0.048036 -0.086138 0.129900 -v 0.047410 -0.086531 0.130266 -v 0.027633 -0.095269 0.114451 -v 0.047410 -0.098532 0.117493 -v 0.047410 -0.093438 0.112743 -v 0.030594 -0.094669 0.113892 -v 0.046267 -0.092606 0.111967 -v 0.030391 -0.094619 0.114887 -v 0.030063 -0.095396 0.114568 -v 0.029059 -0.095623 0.114781 -v 0.027176 -0.094372 0.114655 -v 0.027703 -0.093461 0.112765 -v 0.029414 -0.092716 0.113112 -v 0.029236 -0.093214 0.112535 -v 0.030527 -0.093326 0.113680 -v 0.030392 -0.093677 0.112967 -v 0.023331 -0.092643 0.113044 -v 0.047089 -0.092266 0.112692 -v 0.046267 -0.092643 0.113044 -v 0.028122 -0.092802 0.113192 -v 0.023331 -0.097455 0.117531 -v 0.029161 -0.095085 0.115322 -v 0.047410 -0.097455 0.117531 -v 0.013647 -0.094520 0.110539 -v 0.014488 -0.093565 0.109649 -v 0.014808 -0.094316 0.108630 -v 0.035878 -0.094211 0.108533 -v 0.038109 -0.093845 0.109910 -v 0.039829 -0.100321 0.114230 -v 0.034099 -0.101177 0.115029 -v 0.033096 -0.100964 0.114829 -v 0.031112 -0.099434 0.115122 -v 0.013576 -0.100643 0.115601 -v 0.011837 -0.099157 0.115053 -v 0.005232 -0.101296 0.114775 -v 0.007276 -0.101994 0.115426 -v 0.006868 -0.100920 0.114424 -v 0.008535 -0.100626 0.114149 -v 0.000017 -0.101896 0.120543 -v 0.002132 -0.103377 0.117021 -v 0.002898 -0.103217 0.116599 -v 0.002434 -0.102158 0.115578 -v 0.000017 -0.087604 0.135869 -v -0.000855 -0.086690 0.135016 -v 0.001444 -0.084761 0.137564 -v 0.002255 -0.084114 0.137580 -v 0.001561 -0.083080 0.136698 -v 0.013647 -0.100950 0.115272 -v 0.013640 -0.082419 0.135143 -v 0.012318 -0.083133 0.134430 -v 0.012773 -0.100128 0.116173 -v 0.011493 -0.100481 0.115915 -v 0.010867 -0.082309 0.135502 -v 0.010197 -0.101542 0.115003 -v 0.010427 -0.082054 0.135857 -v 0.010867 -0.101160 0.115286 -v 0.000316 -0.086153 0.137114 -v 0.000686 -0.086214 0.136700 -v 0.000807 -0.103244 0.118321 -v 0.001369 -0.103376 0.117669 -v 0.000116 -0.102599 0.119687 -v 0.003179 -0.083641 0.137384 -v 0.003317 -0.103083 0.116441 -v 0.004237 -0.102777 0.116155 -v 0.005738 -0.102348 0.115755 -v 0.008843 -0.101717 0.115167 -v 0.008843 -0.082229 0.136066 -v 0.006868 -0.081432 0.135323 -v 0.007276 -0.082506 0.136324 -v 0.005738 -0.082860 0.136654 -v 0.005232 -0.081808 0.135673 -v 0.004237 -0.083289 0.137054 -v 0.010147 -0.082060 0.135908 -v 0.011023 -0.081320 0.134793 -v 0.013324 -0.082861 0.134673 -v 0.012883 -0.083047 0.134489 -v 0.011533 -0.082895 0.134768 -v 0.011347 -0.081537 0.134009 -v 0.031109 -0.082053 0.135537 -v 0.031109 -0.084307 0.133120 -v 0.032308 -0.081763 0.133548 -v 0.038249 -0.082909 0.134616 -v 0.038298 -0.082051 0.135535 -v 0.039098 -0.076279 0.130152 -v 0.037328 -0.076116 0.128280 -v 0.035878 -0.075944 0.128121 -v 0.027306 -0.077743 0.131518 -v 0.013647 -0.080938 0.134498 -v 0.015668 -0.078713 0.132422 -v 0.017582 -0.078227 0.131969 -v 0.027611 -0.078460 0.132185 -v 0.017510 -0.077600 0.131384 -v 0.027362 -0.078058 0.131812 -v 0.017622 -0.078003 0.131761 -v 0.028148 -0.078802 0.132505 -v 0.030611 -0.077399 0.131197 -v 0.034421 -0.078516 0.132239 -v 0.030453 -0.078343 0.132077 -v 0.017464 -0.078435 0.132163 -v 0.029644 -0.078868 0.132568 -v 0.017276 -0.078614 0.132330 -v 0.036567 -0.080313 0.133914 -v 0.033460 -0.082051 0.135535 -v 0.015602 -0.077325 0.131128 -v 0.016731 -0.077195 0.131007 -v 0.027362 -0.077428 0.131224 -v 0.037491 -0.075280 0.129221 -v 0.027624 -0.077013 0.130837 -v 0.037205 -0.078339 0.132074 -v 0.039834 -0.077476 0.131268 -v 0.037516 -0.079487 0.133144 -v 0.039836 -0.081148 0.134694 -v 0.035023 -0.080221 0.133829 -v 0.013647 -0.082053 0.135537 -v 0.035892 -0.077909 0.131673 -v 0.035878 -0.075087 0.129041 -v 0.016991 -0.078770 0.132476 -v 0.016441 -0.078867 0.132566 -v 0.034214 -0.079150 0.132830 -v 0.034271 -0.079465 0.133124 -v 0.032377 -0.080946 0.134504 -v 0.015628 -0.075087 0.129041 -v 0.028232 -0.076647 0.130495 -v 0.028969 -0.076527 0.130383 -v 0.035046 -0.078097 0.131848 -v 0.014143 -0.075445 0.129376 -v 0.013647 -0.076536 0.130392 -v 0.039829 -0.082054 0.133819 -v 0.017464 -0.078429 0.130438 -v 0.017598 -0.079104 0.131069 -v 0.031109 -0.081796 0.133578 -v 0.031116 -0.081178 0.134721 -v 0.027408 -0.078155 0.130183 -v 0.017582 -0.078637 0.130633 -v 0.027307 -0.078759 0.130746 -v 0.039838 -0.078393 0.130405 -v 0.037574 -0.079563 0.131495 -v 0.030459 -0.079201 0.131158 -v 0.034386 -0.079349 0.131295 -v 0.033404 -0.082904 0.134612 -v 0.034244 -0.080320 0.132202 -v 0.030584 -0.078242 0.130264 -v 0.029308 -0.079829 0.131745 -v 0.035200 -0.078885 0.130864 -v 0.035218 -0.081177 0.133000 -v 0.036939 -0.081001 0.132837 -v 0.038997 -0.077009 0.129116 -v 0.029847 -0.077533 0.129603 -v 0.027918 -0.077642 0.129705 -v 0.014806 -0.076050 0.128220 -v 0.015828 -0.078026 0.130062 -v 0.015628 -0.075944 0.128121 -v 0.017276 -0.078250 0.130271 -v 0.027650 -0.079365 0.131311 -v 0.013648 -0.076942 0.129052 -v 0.015589 -0.079559 0.131491 -v 0.017140 -0.079570 0.131503 -v 0.013647 -0.099205 0.114909 -v 0.018022 -0.083193 0.132080 -v 0.034958 -0.098459 0.114213 -v 0.015633 -0.096952 0.112807 -v 0.027362 -0.095695 0.111636 -v 0.035193 -0.096297 0.112197 -v 0.039834 -0.095741 0.111678 -v 0.039836 -0.099415 0.115105 -v 0.037236 -0.098194 0.113966 -v 0.038297 -0.100318 0.115946 -v 0.016441 -0.097134 0.112977 -v 0.034282 -0.097761 0.113562 -v 0.037428 -0.096810 0.112674 -v 0.031109 -0.099205 0.114909 -v 0.015513 -0.095635 0.111580 -v 0.015628 -0.093354 0.109452 -v 0.027623 -0.095280 0.111248 -v 0.016441 -0.095406 0.111366 -v 0.027306 -0.096010 0.111929 -v 0.017336 -0.095680 0.111622 -v 0.034394 -0.096818 0.112683 -v 0.030453 -0.096609 0.112489 -v 0.028148 -0.097069 0.112917 -v 0.029642 -0.097136 0.112979 -v 0.027362 -0.096325 0.112223 -v 0.017622 -0.096160 0.112069 -v 0.017582 -0.096494 0.112380 -v 0.034214 -0.097417 0.113241 -v 0.035878 -0.093354 0.109452 -v 0.028376 -0.094851 0.110849 -v 0.027611 -0.096725 0.112597 -v 0.017464 -0.096702 0.112575 -v 0.017276 -0.096881 0.112741 -v 0.016991 -0.097037 0.112887 -v 0.032377 -0.099213 0.114916 -v 0.029679 -0.094901 0.110896 -v 0.030314 -0.095277 0.111245 -v 0.036850 -0.093432 0.109525 -v 0.030608 -0.095797 0.111730 -v 0.039099 -0.094546 0.110563 -v 0.036309 -0.098593 0.114337 -v 0.033460 -0.100318 0.115946 -v 0.031109 -0.097809 0.116407 -v 0.018022 -0.097809 0.116407 -v 0.031109 -0.083193 0.132080 -v 0.018022 -0.084307 0.133120 -v 0.018022 -0.098923 0.117446 -v 0.031109 -0.098923 0.117446 -v 0.017464 -0.097560 0.111655 -v 0.039167 -0.095474 0.109710 -v 0.037674 -0.094466 0.108771 -v 0.028378 -0.095709 0.109929 -v 0.015988 -0.097954 0.112024 -v 0.030610 -0.096666 0.110821 -v 0.030115 -0.095934 0.110139 -v 0.013647 -0.101177 0.115029 -v 0.016747 -0.097962 0.112030 -v 0.031109 -0.101177 0.115029 -v 0.017188 -0.097804 0.111884 -v 0.031112 -0.100335 0.114243 -v 0.017582 -0.097351 0.111461 -v 0.039838 -0.096660 0.110817 -v 0.015110 -0.097030 0.111160 -v 0.017601 -0.096871 0.111013 -v 0.027623 -0.096137 0.110329 -v 0.016352 -0.096223 0.110408 -v 0.015628 -0.094211 0.108533 -v 0.013649 -0.095207 0.109462 -v 0.027309 -0.096680 0.110834 -v 0.027410 -0.097317 0.111429 -v 0.037574 -0.097830 0.111907 -v 0.035192 -0.097154 0.111277 -v 0.034922 -0.099398 0.113370 -v 0.036939 -0.099268 0.113248 -v 0.038248 -0.101176 0.115028 -v 0.027978 -0.097868 0.111943 -v 0.031935 -0.100033 0.113962 -v 0.029246 -0.098076 0.112136 -v 0.032463 -0.100179 0.114097 -v 0.030338 -0.097613 0.111705 -v 0.034186 -0.097938 0.112008 -v 0.013647 -0.100063 0.113989 -v 0.012935 -0.099066 0.115071 -v 0.013136 -0.081836 0.133542 -v 0.013647 -0.081796 0.133578 -v 0.013530 -0.081567 0.133823 -v 0.012268 -0.082022 0.133388 -v 0.010180 -0.100418 0.113956 -v 0.011407 -0.099524 0.114712 -v 0.010172 -0.080931 0.134855 -v 0.008535 -0.081137 0.135048 -v 0.002434 -0.082670 0.136477 -v 0.002082 -0.082813 0.136583 -v 0.001580 -0.102414 0.115946 -v 0.000700 -0.102479 0.116611 -v -0.000558 -0.102122 0.118157 -v -0.000855 -0.100982 0.119691 -v -0.000144 -0.101716 0.118201 -v -0.000756 -0.085883 0.135780 -v -0.000109 -0.084622 0.136498 -v 0.000689 -0.083729 0.136728 -v 0.003634 -0.082265 0.136099 -v 0.003634 -0.101753 0.115201 -v 0.011025 -0.100358 0.114326 -v 0.015260 -0.078003 0.131761 -v 0.015294 -0.078210 0.131953 -v 0.015395 -0.078405 0.132135 -v 0.015557 -0.098601 0.110820 -v 0.015557 -0.078576 0.132295 -v 0.015770 -0.098739 0.110949 -v 0.015770 -0.078714 0.132424 -v 0.016022 -0.078811 0.132514 -v 0.016298 -0.078861 0.132560 -v 0.016583 -0.078861 0.132560 -v 0.016860 -0.078811 0.132514 -v 0.016860 -0.098836 0.111039 -v 0.017112 -0.098739 0.110949 -v 0.017112 -0.078714 0.132424 -v 0.017325 -0.098601 0.110820 -v 0.017325 -0.078576 0.132295 -v 0.017487 -0.098430 0.110661 -v 0.017487 -0.078405 0.132135 -v 0.017588 -0.078210 0.131953 -v 0.017622 -0.098028 0.110286 -v 0.017588 -0.077797 0.131568 -v 0.017487 -0.097627 0.109912 -v 0.017487 -0.077602 0.131386 -v 0.017325 -0.097456 0.109752 -v 0.017325 -0.077431 0.131226 -v 0.017112 -0.097318 0.109623 -v 0.017112 -0.077292 0.131098 -v 0.016860 -0.077196 0.131007 -v 0.016583 -0.077146 0.130961 -v 0.016298 -0.077146 0.130961 -v 0.016022 -0.077196 0.131007 -v 0.015770 -0.077292 0.131098 -v 0.015557 -0.097456 0.109752 -v 0.015395 -0.097627 0.109912 -v 0.015557 -0.077431 0.131226 -v 0.015395 -0.077602 0.131386 -v 0.015294 -0.077797 0.131568 -v 0.015260 -0.098028 0.110286 -v 0.015395 -0.098430 0.110661 -v 0.015294 -0.098235 0.110479 -v 0.016298 -0.098886 0.111086 -v 0.016022 -0.098836 0.111039 -v 0.016583 -0.098886 0.111086 -v 0.017588 -0.098235 0.110479 -v 0.017588 -0.097822 0.110094 -v 0.016583 -0.097171 0.109487 -v 0.016860 -0.097221 0.109533 -v 0.015770 -0.097318 0.109623 -v 0.016022 -0.097221 0.109533 -v 0.016298 -0.097171 0.109487 -v 0.015294 -0.097822 0.110094 -v 0.033044 -0.099259 0.115601 -v 0.031916 -0.096563 0.115241 -v 0.031917 -0.097744 0.114189 -v 0.039841 -0.098715 0.115094 -v 0.038741 -0.098802 0.117328 -v 0.037231 -0.097892 0.114327 -v 0.037260 -0.096313 0.112854 -v 0.034968 -0.099891 0.116190 -v 0.035956 -0.095897 0.112466 -v 0.039841 -0.092360 0.109168 -v 0.031916 -0.092360 0.109168 -v 0.035706 -0.098348 0.114752 -v 0.038674 -0.099886 0.116186 -v 0.034759 -0.096163 0.112714 -v 0.034213 -0.097544 0.114002 -v 0.016822 -0.085552 0.116468 -v 0.029721 -0.090910 0.110723 -v 0.030315 -0.090565 0.111093 -v 0.031149 -0.090609 0.111045 -v 0.031716 -0.092034 0.111826 -v 0.031907 -0.091068 0.110554 -v 0.037274 -0.096843 0.115502 -v 0.035296 -0.097202 0.115836 -v 0.034835 -0.098817 0.117343 -v 0.032787 -0.097997 0.116577 -v 0.031916 -0.092438 0.111394 -v 0.037163 -0.095183 0.113953 -v 0.034036 -0.095913 0.114634 -v 0.035488 -0.094774 0.113572 -v 0.039841 -0.097612 0.116218 -v 0.038741 -0.083107 0.134158 -v 0.031918 -0.082055 0.131025 -v 0.031916 -0.075591 0.127150 -v 0.034406 -0.079733 0.131011 -v 0.031916 -0.080866 0.132069 -v 0.035506 -0.079080 0.130402 -v 0.037136 -0.079468 0.130765 -v 0.039841 -0.081913 0.133045 -v 0.034552 -0.081280 0.132454 -v 0.034628 -0.083119 0.134169 -v 0.037274 -0.081149 0.132332 -v 0.032637 -0.082142 0.133258 -v 0.037234 -0.082197 0.131157 -v 0.039841 -0.083021 0.131925 -v 0.039841 -0.077817 0.127072 -v 0.037300 -0.080651 0.129715 -v 0.035947 -0.080204 0.129297 -v 0.031916 -0.077817 0.127072 -v 0.034543 -0.084184 0.133010 -v 0.035703 -0.082654 0.131582 -v 0.038674 -0.084192 0.133017 -v 0.034738 -0.080481 0.129556 -v 0.034213 -0.081849 0.130832 -v 0.032732 -0.083277 0.132163 -v 0.031718 -0.077040 0.125597 -v 0.031128 -0.077385 0.125226 -v 0.029937 -0.077174 0.125453 -v 0.030154 -0.078459 0.126384 -v 0.029721 -0.078193 0.126669 -v 0.016822 -0.083551 0.120923 -v 0.018145 -0.080289 0.124420 -v 0.018715 -0.079290 0.125493 -v 0.019555 -0.077875 0.124701 -v 0.021850 -0.080101 0.124623 -v 0.021860 -0.079010 0.123483 -v 0.018200 -0.079474 0.122986 -v 0.031915 -0.076744 0.125913 -v 0.039841 -0.075591 0.127150 -v 0.021395 -0.087958 0.113889 -v 0.029494 -0.091284 0.110322 -v 0.030429 -0.077379 0.125233 -v 0.016822 -0.082399 0.119849 -v 0.021654 -0.079651 0.122796 -v 0.021120 -0.078047 0.124516 -v 0.018420 -0.078409 0.124128 -v 0.016822 -0.076668 0.125996 -v 0.019249 -0.080279 0.122123 -v 0.029505 -0.076668 0.125996 -v 0.016822 -0.091284 0.110322 -v 0.018145 -0.088813 0.112971 -v 0.020830 -0.080254 0.122150 -v 0.021850 -0.089002 0.112769 -v 0.022791 -0.082399 0.119849 -v 0.020362 -0.084114 0.121414 -v 0.019592 -0.087649 0.118459 -v 0.019683 -0.084507 0.121780 -v 0.015535 -0.083702 0.121030 -v 0.018736 -0.084554 0.121824 -v 0.015535 -0.086820 0.117686 -v 0.014996 -0.087903 0.118695 -v 0.021654 -0.087896 0.118689 -v 0.018710 -0.087665 0.118474 -v 0.019194 -0.089002 0.119721 -v 0.020355 -0.087243 0.118081 -v 0.022791 -0.085552 0.116468 -v 0.021796 -0.085800 0.116734 -v 0.021168 -0.086225 0.117131 -v 0.022791 -0.083551 0.120923 -v 0.023056 -0.083568 0.120905 -v 0.014996 -0.084785 0.122039 -v 0.019195 -0.085884 0.123065 -v 0.021145 -0.083133 0.120499 -v 0.021733 -0.082712 0.120106 -v 0.022385 -0.082491 0.119901 -v 0.030634 -0.091711 0.112173 -v 0.031851 -0.078012 0.126863 -v 0.020098 -0.079018 0.125785 -v 0.018810 -0.081276 0.123363 -v 0.016822 -0.077819 0.127070 -v 0.029862 -0.091958 0.111908 -v 0.039841 -0.092438 0.111394 -v 0.020098 -0.081493 0.123130 -v 0.021824 -0.084582 0.121850 -v 0.022376 -0.085611 0.116559 -v 0.023056 -0.086704 0.117542 -v 0.031286 -0.091797 0.112081 -v 0.029505 -0.092435 0.111396 -v 0.031207 -0.078516 0.126322 -v 0.020677 -0.081414 0.123215 -v 0.021616 -0.080877 0.123791 -v 0.018200 -0.089628 0.114405 -v 0.016822 -0.086704 0.117542 -v 0.021172 -0.079253 0.125532 -v 0.029494 -0.077819 0.127070 -v 0.016822 -0.092435 0.111396 -v 0.019249 -0.088824 0.115269 -v 0.018676 -0.087937 0.113911 -v 0.020029 -0.087611 0.114261 -v 0.020828 -0.088848 0.115242 -v 0.021653 -0.089451 0.114596 -v 0.021860 -0.090092 0.113909 -v 0.021174 -0.089849 0.111860 -v 0.021120 -0.091056 0.112875 -v 0.019553 -0.091228 0.112691 -v 0.020098 -0.090086 0.111606 -v 0.018420 -0.090694 0.113263 -v 0.018715 -0.089813 0.111899 -v 0.030116 0.095835 0.109276 -v 0.030725 0.098391 0.111611 -v 0.027504 0.098495 0.110794 -v 0.027402 0.096094 0.109631 -v 0.030499 0.078170 0.131521 -v 0.030405 0.078391 0.131727 -v 0.030405 0.097515 0.111219 -v 0.030251 0.097717 0.111407 -v 0.030046 0.097893 0.111571 -v 0.030251 0.078593 0.131915 -v 0.030046 0.078768 0.132079 -v 0.029796 0.098034 0.111703 -v 0.029796 0.078910 0.132211 -v 0.029512 0.098136 0.111797 -v 0.029512 0.079012 0.132306 -v 0.029206 0.098194 0.111852 -v 0.029206 0.079070 0.132360 -v 0.028890 0.098206 0.111862 -v 0.028578 0.098171 0.111830 -v 0.028890 0.079081 0.132371 -v 0.028578 0.079046 0.132338 -v 0.028281 0.098090 0.111755 -v 0.028281 0.078966 0.132263 -v 0.028013 0.078844 0.132149 -v 0.028013 0.097968 0.111641 -v 0.027784 0.097809 0.111492 -v 0.027784 0.078684 0.132001 -v 0.027604 0.097619 0.111315 -v 0.027479 0.097407 0.111117 -v 0.027604 0.078495 0.131824 -v 0.027415 0.097180 0.110906 -v 0.027479 0.078282 0.131626 -v 0.027415 0.078056 0.131415 -v 0.027415 0.077825 0.131199 -v 0.027415 0.096949 0.110691 -v 0.027479 0.096723 0.110480 -v 0.027479 0.077598 0.130988 -v 0.027604 0.096510 0.110281 -v 0.027784 0.096320 0.110105 -v 0.027604 0.077386 0.130790 -v 0.027784 0.077196 0.130613 -v 0.028013 0.096161 0.109956 -v 0.028013 0.077037 0.130464 -v 0.028281 0.096039 0.109842 -v 0.028281 0.076915 0.130350 -v 0.028578 0.095959 0.109767 -v 0.028578 0.076834 0.130275 -v 0.028890 0.076799 0.130243 -v 0.028890 0.095924 0.109734 -v 0.029206 0.095935 0.109745 -v 0.029512 0.095993 0.109799 -v 0.029206 0.076811 0.130254 -v 0.029796 0.096095 0.109894 -v 0.029512 0.076869 0.130308 -v 0.029796 0.076971 0.130403 -v 0.030046 0.096237 0.110026 -v 0.030251 0.096412 0.110190 -v 0.030046 0.077112 0.130535 -v 0.030405 0.096614 0.110378 -v 0.030251 0.077288 0.130698 -v 0.030499 0.096835 0.110584 -v 0.030405 0.077490 0.130887 -v 0.030499 0.077710 0.131092 -v 0.030531 0.097065 0.110798 -v 0.030531 0.077940 0.131307 -v 0.030499 0.097295 0.111013 -v 0.028938 0.076970 0.132299 -v 0.028960 0.079347 0.132994 -v 0.031102 0.076947 0.130805 -v 0.026597 0.077376 0.131253 -v 0.028803 0.076449 0.129917 -v 0.030562 0.078927 0.132226 -v 0.038108 0.078911 0.132623 -v 0.034612 0.077618 0.131389 -v 0.035242 0.079669 0.134478 -v 0.036951 0.080670 0.133852 -v 0.033989 0.079962 0.133192 -v 0.033837 0.099268 0.112495 -v 0.037118 0.100321 0.113055 -v 0.035891 0.097040 0.110092 -v 0.014970 0.096488 0.109790 -v 0.018507 0.096892 0.110262 -v 0.017682 0.098862 0.111338 -v 0.015224 0.098787 0.112125 -v 0.056447 0.094877 0.114763 -v 0.058400 0.091968 0.112122 -v 0.058768 0.094322 0.112941 -v 0.055134 0.092769 0.112789 -v 0.058350 0.094553 0.114816 -v 0.058833 0.080717 0.127398 -v 0.058766 0.093615 0.113943 -v 0.058766 0.080904 0.127573 -v 0.058657 0.093791 0.114107 -v 0.058657 0.081081 0.127738 -v 0.058509 0.093952 0.114257 -v 0.058509 0.081241 0.127887 -v 0.058326 0.094092 0.114387 -v 0.058326 0.081381 0.128018 -v 0.058113 0.094207 0.114495 -v 0.058113 0.081497 0.128125 -v 0.057876 0.094294 0.114576 -v 0.057876 0.081584 0.128207 -v 0.057623 0.094351 0.114629 -v 0.057623 0.081641 0.128259 -v 0.057360 0.094376 0.114652 -v 0.057360 0.081665 0.128282 -v 0.057095 0.094368 0.114644 -v 0.057095 0.081657 0.128275 -v 0.056836 0.081616 0.128237 -v 0.056836 0.094327 0.114606 -v 0.056590 0.081544 0.128169 -v 0.056590 0.094254 0.114539 -v 0.056365 0.094153 0.114444 -v 0.056166 0.094025 0.114325 -v 0.056365 0.081442 0.128075 -v 0.056166 0.081314 0.127955 -v 0.055999 0.093874 0.114184 -v 0.055870 0.093705 0.114026 -v 0.055999 0.081163 0.127815 -v 0.055870 0.080994 0.127657 -v 0.055782 0.093522 0.113856 -v 0.055782 0.080812 0.127487 -v 0.055737 0.093331 0.113678 -v 0.055737 0.080621 0.127308 -v 0.055737 0.080427 0.127128 -v 0.055737 0.093137 0.113497 -v 0.055782 0.092946 0.113319 -v 0.055782 0.080236 0.126950 -v 0.055870 0.092764 0.113149 -v 0.055870 0.080053 0.126779 -v 0.055999 0.092595 0.112991 -v 0.055999 0.079884 0.126621 -v 0.056166 0.079733 0.126481 -v 0.056166 0.092444 0.112850 -v 0.056365 0.092316 0.112731 -v 0.056365 0.079605 0.126362 -v 0.056590 0.092214 0.112636 -v 0.056590 0.079504 0.126267 -v 0.056836 0.092142 0.112569 -v 0.056836 0.079431 0.126199 -v 0.057095 0.079391 0.126161 -v 0.057095 0.092101 0.112531 -v 0.057360 0.092093 0.112523 -v 0.057360 0.079382 0.126154 -v 0.057623 0.092118 0.112546 -v 0.057623 0.079407 0.126177 -v 0.057876 0.092174 0.112599 -v 0.057876 0.079464 0.126230 -v 0.058113 0.079551 0.126311 -v 0.058113 0.092262 0.112680 -v 0.058326 0.092377 0.112788 -v 0.058326 0.079666 0.126418 -v 0.058509 0.092517 0.112918 -v 0.058509 0.079806 0.126549 -v 0.058657 0.092677 0.113068 -v 0.058657 0.079967 0.126698 -v 0.058766 0.092854 0.113233 -v 0.058766 0.080143 0.126863 -v 0.058833 0.080331 0.127038 -v 0.058833 0.093041 0.113408 -v 0.058856 0.093234 0.113588 -v 0.058856 0.080524 0.127218 -v 0.058833 0.093427 0.113768 -v 0.058870 0.079116 0.126597 -v 0.059287 0.081044 0.128051 -v 0.055390 0.081090 0.128594 -v 0.056370 0.078980 0.126065 -v 0.069532 0.089694 0.114261 -v 0.068741 0.089141 0.112620 -v 0.067419 0.090697 0.113187 -v 0.061029 0.089618 0.114343 -v 0.058224 0.080957 0.123631 -v 0.061029 0.080957 0.123631 -v 0.066993 0.081786 0.122741 -v 0.064344 0.089068 0.114932 -v 0.069900 0.088535 0.115504 -v 0.066706 0.083581 0.120817 -v 0.069900 0.081590 0.122951 -v 0.065477 0.083844 0.120535 -v 0.066265 0.089154 0.114841 -v 0.067136 0.079875 0.124791 -v 0.068743 0.080320 0.124313 -v 0.069899 0.080324 0.122076 -v 0.063416 0.079874 0.124791 -v 0.065943 0.085639 0.116375 -v 0.058224 0.079842 0.122592 -v 0.061029 0.079842 0.122592 -v 0.063417 0.089585 0.112143 -v 0.067227 0.080752 0.121616 -v 0.063201 0.078762 0.123750 -v 0.067746 0.078766 0.123746 -v 0.067318 0.086387 0.115572 -v 0.069899 0.087874 0.113978 -v 0.061615 0.079309 0.123164 -v 0.061862 0.080267 0.124370 -v 0.055079 0.084825 0.127238 -v 0.054795 0.084551 0.126983 -v 0.055893 0.083721 0.126209 -v 0.054555 0.084255 0.126707 -v 0.057292 0.079920 0.122664 -v 0.057846 0.080977 0.123650 -v 0.055704 0.082371 0.124950 -v 0.055829 0.082109 0.124705 -v 0.054693 0.081294 0.123946 -v 0.056226 0.081638 0.124267 -v 0.054960 0.081011 0.123682 -v 0.055997 0.080318 0.123036 -v 0.057476 0.081037 0.123706 -v 0.056327 0.092835 0.117343 -v 0.056327 0.084174 0.126631 -v 0.056087 0.092620 0.117143 -v 0.056087 0.083959 0.126431 -v 0.055893 0.092382 0.116921 -v 0.055748 0.083465 0.125970 -v 0.055655 0.083196 0.125719 -v 0.055617 0.082920 0.125462 -v 0.055633 0.082643 0.125204 -v 0.055829 0.090770 0.115417 -v 0.056004 0.081863 0.124476 -v 0.056490 0.081439 0.124081 -v 0.056791 0.089932 0.114635 -v 0.056791 0.081270 0.123924 -v 0.057122 0.081135 0.123798 -v 0.057476 0.089698 0.114418 -v 0.057846 0.089638 0.114362 -v 0.056740 0.093100 0.117590 -v 0.055951 0.094056 0.118480 -v 0.055655 0.091857 0.116431 -v 0.055748 0.092126 0.116682 -v 0.054795 0.093212 0.117695 -v 0.055403 0.093735 0.118182 -v 0.061029 0.088503 0.113303 -v 0.058224 0.088503 0.113303 -v 0.058224 0.089618 0.114343 -v 0.055633 0.091304 0.115915 -v 0.054109 0.091251 0.115866 -v 0.055617 0.091581 0.116174 -v 0.054093 0.091595 0.116186 -v 0.054130 0.091937 0.116506 -v 0.056490 0.090101 0.114793 -v 0.055269 0.089413 0.114152 -v 0.056226 0.090299 0.114978 -v 0.056004 0.090524 0.115188 -v 0.054693 0.089955 0.114658 -v 0.055704 0.091032 0.115662 -v 0.054300 0.090579 0.115239 -v 0.057122 0.089797 0.114509 -v 0.055997 0.088980 0.113748 -v 0.063375 0.090700 0.113183 -v 0.061761 0.090254 0.113660 -v 0.061865 0.089194 0.112563 -v 0.067128 0.089585 0.112143 -v 0.057755 0.088523 0.113322 -v 0.057755 0.079862 0.122610 -v 0.057292 0.088581 0.113376 -v 0.056840 0.080016 0.122754 -v 0.056840 0.088678 0.113466 -v 0.056407 0.080150 0.122879 -v 0.056407 0.088811 0.113591 -v 0.055616 0.080520 0.123224 -v 0.055616 0.089181 0.113936 -v 0.055269 0.080752 0.123440 -v 0.054960 0.089672 0.114393 -v 0.054472 0.090259 0.114941 -v 0.054472 0.081598 0.124229 -v 0.054300 0.081917 0.124527 -v 0.054178 0.082250 0.124837 -v 0.054178 0.090911 0.115549 -v 0.054109 0.082590 0.125154 -v 0.054093 0.082933 0.125474 -v 0.054130 0.083276 0.125794 -v 0.054220 0.083614 0.126109 -v 0.054220 0.092275 0.116820 -v 0.054363 0.092603 0.117126 -v 0.054363 0.083941 0.126414 -v 0.054555 0.092916 0.117419 -v 0.055079 0.093486 0.117950 -v 0.055403 0.085074 0.127470 -v 0.055907 0.085373 0.127750 -v 0.057326 0.085975 0.128311 -v 0.058088 0.085010 0.127411 -v 0.057326 0.094637 0.119023 -v 0.056726 0.084434 0.126874 -v 0.058088 0.093671 0.118123 -v 0.064806 0.080242 0.122163 -v 0.065404 0.081286 0.123277 -v 0.063708 0.081173 0.121165 -v 0.063717 0.082099 0.122406 -v 0.064134 0.083480 0.120924 -v 0.063914 0.082142 0.120125 -v 0.065405 0.082769 0.119453 -v 0.067009 0.082254 0.120005 -v 0.067369 0.082728 0.121732 -v 0.067347 0.088361 0.115691 -v 0.067142 0.087391 0.116731 -v 0.066348 0.086852 0.117309 -v 0.064923 0.086772 0.117396 -v 0.064098 0.085946 0.116045 -v 0.064117 0.087188 0.116949 -v 0.063667 0.087850 0.116239 -v 0.063812 0.087458 0.114425 -v 0.065404 0.088174 0.113657 -v 0.066992 0.087674 0.114193 -v 0.013638 0.087215 0.117066 -v 0.013913 0.087886 0.118564 -v 0.018130 0.086336 0.122583 -v 0.014624 0.087304 0.122035 -v 0.015344 0.087144 0.123272 -v 0.014044 0.086339 0.122118 -v 0.017709 0.085943 0.121242 -v 0.018427 0.085940 0.121748 -v 0.016305 0.088220 0.123887 -v 0.018189 0.087172 0.123493 -v 0.017986 0.085119 0.121848 -v 0.014386 0.087517 0.122662 -v 0.017417 0.085040 0.122096 -v 0.015431 0.085393 0.121010 -v 0.018246 0.086346 0.122606 -v 0.017056 0.088321 0.123661 -v 0.014545 0.085550 0.122257 -v 0.017580 0.086954 0.124224 -v 0.016703 0.086688 0.121331 -v 0.014544 0.086495 0.122207 -v 0.015424 0.085727 0.120846 -v 0.018501 0.087768 0.122223 -v 0.017133 0.089019 0.122581 -v 0.018225 0.086124 0.121390 -v 0.016064 0.089593 0.122422 -v 0.014094 0.087235 0.121147 -v 0.017456 0.086263 0.120023 -v 0.014917 0.086321 0.120436 -v 0.017694 0.088550 0.122888 -v 0.014764 0.088199 0.122838 -v 0.018411 0.088378 0.120939 -v 0.018477 0.088176 0.119840 -v 0.015311 0.087015 0.119475 -v 0.017763 0.089081 0.122455 -v 0.016965 0.086726 0.120256 -v 0.017208 0.088538 0.122605 -v 0.016485 0.088854 0.122220 -v 0.016910 0.089670 0.122280 -v 0.018147 0.087473 0.120110 -v 0.014806 0.088124 0.121136 -v 0.014959 0.087387 0.121352 -v 0.018484 0.086916 0.121293 -v 0.017151 0.087090 0.120129 -v 0.017828 0.086535 0.119982 -v 0.014816 0.089228 0.121260 -v 0.017486 0.089085 0.121294 -v 0.014474 0.088799 0.121376 -v 0.014476 0.088644 0.119244 -v 0.018428 0.089734 0.119745 -v 0.015361 0.086931 0.119268 -v 0.015867 0.090917 0.121218 -v 0.016662 0.087410 0.119404 -v 0.015895 0.090313 0.120631 -v 0.016714 0.087215 0.118823 -v 0.017446 0.090103 0.121798 -v 0.014750 0.089847 0.120994 -v 0.014903 0.089392 0.121398 -v 0.017720 0.088303 0.118073 -v 0.018552 0.089527 0.120520 -v 0.015249 0.089144 0.120955 -v 0.014401 0.089073 0.120111 -v 0.018033 0.088757 0.119781 -v 0.018240 0.089341 0.120219 -v 0.015322 0.088535 0.118855 -v 0.017164 0.087760 0.118438 -v 0.010547 0.089014 0.125323 -v 0.010710 0.089148 0.125926 -v 0.010555 0.089345 0.125598 -v 0.010444 0.088756 0.125911 -v 0.010460 0.088718 0.125505 -v 0.018122 0.088679 0.115204 -v 0.017498 0.088327 0.114875 -v 0.017121 0.091494 0.111230 -v 0.018440 0.092436 0.112109 -v 0.018071 0.091927 0.111634 -v 0.018841 0.094096 0.113656 -v 0.016478 0.092885 0.112527 -v 0.017559 0.093398 0.113005 -v 0.017925 0.094118 0.113677 -v 0.015359 0.092977 0.112613 -v 0.015435 0.090587 0.109892 -v 0.015363 0.090769 0.109998 -v 0.016668 0.091422 0.110599 -v 0.014409 0.087443 0.114051 -v 0.014570 0.087064 0.113696 -v 0.016916 0.090981 0.110444 -v 0.016916 0.087536 0.114138 -v 0.016535 0.091387 0.110976 -v 0.015171 0.091492 0.111228 -v 0.015171 0.093296 0.112911 -v 0.015171 0.094537 0.114030 -v 0.016289 0.092188 0.118476 -v 0.015177 0.091482 0.117817 -v 0.015624 0.091939 0.118243 -v 0.016594 0.095461 0.114891 -v 0.015977 0.095521 0.114741 -v 0.015170 0.090822 0.110428 -v 0.015411 0.095280 0.114336 -v 0.018403 0.095767 0.114659 -v 0.015306 0.090749 0.109980 -v 0.014915 0.090480 0.109728 -v 0.015440 0.090270 0.109957 -v 0.014409 0.090754 0.110501 -v 0.014449 0.090718 0.110168 -v 0.016794 0.096280 0.115095 -v 0.014409 0.094537 0.114030 -v 0.014447 0.094989 0.114190 -v 0.014409 0.091467 0.117804 -v 0.014679 0.095537 0.114461 -v 0.015414 0.096021 0.115019 -v 0.014977 0.092287 0.118567 -v 0.016544 0.092727 0.118978 -v 0.016260 0.096118 0.115326 -v 0.015349 0.086876 0.113522 -v 0.016535 0.088019 0.114588 -v 0.015171 0.087443 0.114051 -v 0.015173 0.089772 0.116223 -v 0.018644 0.091889 0.118196 -v 0.017949 0.090842 0.117220 -v 0.015171 0.088200 0.114757 -v 0.015740 0.092622 0.118881 -v 0.018841 0.090804 0.117186 -v 0.016902 0.088201 0.114758 -v 0.016352 0.089585 0.116048 -v 0.019147 0.092212 0.118499 -v 0.018470 0.092474 0.118743 -v 0.018445 0.089165 0.115657 -v 0.017676 0.090261 0.116679 -v 0.017149 0.089836 0.116284 -v 0.019185 0.095554 0.114957 -v 0.018551 0.095209 0.114656 -v 0.019905 0.085719 0.133464 -v 0.019648 0.099197 0.121331 -v 0.019648 0.088596 0.132699 -v 0.019807 0.099708 0.121149 -v 0.019462 0.085550 0.133251 -v 0.019960 0.088819 0.132907 -v 0.019805 0.088773 0.132865 -v 0.019692 0.088682 0.132780 -v 0.018473 0.081669 0.129196 -v 0.018470 0.082009 0.129966 -v 0.018840 0.081906 0.129934 -v 0.019183 0.081888 0.129594 -v 0.019645 0.085258 0.133060 -v 0.019272 0.085565 0.132828 -v 0.018470 0.095930 0.115038 -v 0.018470 0.085545 0.126174 -v 0.018726 0.095772 0.114671 -v 0.019456 0.100052 0.118824 -v 0.019692 0.099284 0.121411 -v 0.020002 0.099425 0.121544 -v 0.018936 0.095985 0.114859 -v 0.020023 0.099018 0.118208 -v 0.020179 0.099401 0.121521 -v 0.020086 0.088820 0.132909 -v 0.020394 0.099902 0.120671 -v 0.020402 0.088571 0.132676 -v 0.020398 0.088499 0.132609 -v 0.020381 0.088642 0.132742 -v 0.020243 0.088765 0.132858 -v 0.020038 0.087649 0.133832 -v 0.020023 0.085468 0.132738 -v 0.019220 0.085449 0.126083 -v 0.020398 0.099100 0.121240 -v 0.019220 0.092378 0.118653 -v 0.017289 0.079688 0.127310 -v 0.015171 0.079664 0.127291 -v 0.015475 0.079438 0.127077 -v 0.018841 0.080584 0.128146 -v 0.016372 0.079368 0.127012 -v 0.017910 0.080571 0.128133 -v 0.018268 0.080661 0.128218 -v 0.017731 0.080141 0.127733 -v 0.018121 0.078458 0.126164 -v 0.018444 0.078942 0.126614 -v 0.018071 0.081706 0.122594 -v 0.017500 0.078106 0.125836 -v 0.016897 0.077980 0.125717 -v 0.016724 0.081903 0.129935 -v 0.016452 0.081928 0.129438 -v 0.015874 0.081654 0.129520 -v 0.015170 0.080918 0.128730 -v 0.014870 0.076609 0.125004 -v 0.016535 0.077633 0.125726 -v 0.015306 0.076683 0.125064 -v 0.015171 0.077132 0.125109 -v 0.014409 0.080279 0.121263 -v 0.016535 0.081090 0.122019 -v 0.016916 0.077119 0.125310 -v 0.015171 0.077980 0.125717 -v 0.015333 0.081373 0.129117 -v 0.015624 0.085010 0.125674 -v 0.019117 0.085244 0.125893 -v 0.018615 0.084963 0.125631 -v 0.016916 0.080607 0.121569 -v 0.015286 0.079920 0.120929 -v 0.014409 0.084298 0.125010 -v 0.015171 0.080514 0.121482 -v 0.015171 0.081271 0.122188 -v 0.015174 0.082842 0.123653 -v 0.015173 0.084565 0.125259 -v 0.014528 0.084887 0.125561 -v 0.017127 0.081276 0.122192 -v 0.016461 0.082660 0.123482 -v 0.017452 0.083098 0.123892 -v 0.018441 0.082219 0.123072 -v 0.017946 0.083888 0.124627 -v 0.015127 0.085431 0.126067 -v 0.016301 0.085258 0.125905 -v 0.015740 0.085693 0.126311 -v 0.016084 0.085761 0.126375 -v 0.018841 0.083875 0.124616 -v 0.014987 0.081882 0.129716 -v 0.015417 0.085582 0.126208 -v 0.016794 0.085762 0.126375 -v 0.016439 0.085784 0.126396 -v 0.016791 0.082322 0.130071 -v 0.015859 0.082257 0.130088 -v 0.014525 0.081321 0.129213 -v 0.014409 0.076871 0.125006 -v 0.014409 0.080988 0.128560 -v 0.015363 0.076703 0.125082 -v 0.015227 0.076427 0.124629 -v 0.059722 0.091563 0.114182 -v 0.058369 0.090366 0.113066 -v 0.059863 0.092985 0.113424 -v 0.052439 0.092409 0.114971 -v 0.042272 0.096124 0.118436 -v 0.033341 0.096124 0.118436 -v 0.056161 0.090470 0.113164 -v 0.059787 0.092653 0.115198 -v 0.057300 0.090899 0.113563 -v 0.055616 0.092270 0.114841 -v 0.054622 0.094822 0.117221 -v 0.059054 0.092592 0.115141 -v 0.058759 0.093732 0.116205 -v 0.056638 0.093237 0.115743 -v 0.042272 0.097164 0.117321 -v 0.044103 0.096096 0.118409 -v 0.044103 0.097136 0.117294 -v 0.046689 0.095966 0.118287 -v 0.051574 0.096440 0.116646 -v 0.050336 0.095574 0.117923 -v 0.032947 0.097164 0.117321 -v 0.032947 0.093449 0.113856 -v 0.056070 0.092182 0.112675 -v 0.056123 0.091530 0.112067 -v 0.055949 0.093825 0.114207 -v 0.058849 0.092653 0.113114 -v 0.059111 0.091858 0.112373 -v 0.059136 0.094637 0.114964 -v 0.055758 0.093456 0.113863 -v 0.046974 0.096983 0.117152 -v 0.057579 0.091323 0.111873 -v 0.055918 0.095550 0.115815 -v 0.057635 0.094501 0.114837 -v 0.052439 0.093449 0.113856 -v 0.033341 0.092409 0.114971 -v 0.031768 0.081239 0.126950 -v 0.031767 0.092895 0.114451 -v 0.033341 0.081847 0.126298 -v 0.044103 0.084459 0.130888 -v 0.042272 0.085562 0.129763 -v 0.046683 0.084329 0.130767 -v 0.054622 0.083185 0.129699 -v 0.057300 0.079262 0.126042 -v 0.050331 0.083939 0.130403 -v 0.033341 0.080773 0.127450 -v 0.042272 0.084488 0.130915 -v 0.033341 0.084488 0.130915 -v 0.058969 0.080386 0.127090 -v 0.056162 0.078833 0.125641 -v 0.052439 0.080773 0.127450 -v 0.055617 0.080633 0.127320 -v 0.059696 0.081173 0.127824 -v 0.058760 0.082095 0.128683 -v 0.057237 0.081845 0.128450 -v 0.059438 0.080470 0.125015 -v 0.059727 0.079771 0.126516 -v 0.057926 0.078672 0.125491 -v 0.033341 0.085562 0.129763 -v 0.052439 0.081847 0.126298 -v 0.055803 0.081202 0.125697 -v 0.054180 0.084342 0.128625 -v 0.050616 0.084973 0.129213 -v 0.055950 0.082223 0.126650 -v 0.056129 0.079925 0.124507 -v 0.057705 0.080305 0.124861 -v 0.058849 0.082143 0.126574 -v 0.059790 0.082152 0.126584 -v 0.056985 0.082757 0.127147 -v 0.058532 0.083253 0.127610 -v 0.057584 0.079721 0.124316 -v 0.055758 0.081854 0.126305 -v 0.044103 0.085533 0.129736 -v 0.046983 0.085379 0.129593 -v 0.048172 0.090718 0.114327 -v 0.048172 0.081017 0.124730 -v 0.047661 0.096337 0.119567 -v 0.048036 0.096036 0.119286 -v 0.047410 0.095920 0.119177 -v 0.047410 0.079950 0.127207 -v 0.046884 0.078710 0.127093 -v 0.047090 0.079298 0.126600 -v 0.046267 0.092283 0.112313 -v 0.046267 0.079118 0.126431 -v 0.030623 0.093954 0.113871 -v 0.030495 0.093583 0.113525 -v 0.030087 0.093176 0.113146 -v 0.046267 0.092841 0.112833 -v 0.027225 0.094125 0.114031 -v 0.023331 0.097652 0.117320 -v 0.030623 0.094217 0.114116 -v 0.029497 0.092926 0.112913 -v 0.027872 0.093142 0.113114 -v 0.047410 0.097652 0.117320 -v 0.030312 0.094814 0.114674 -v 0.030546 0.094474 0.114356 -v 0.028071 0.095161 0.114997 -v 0.029239 0.095286 0.115113 -v 0.029800 0.095146 0.114983 -v 0.027479 0.093911 0.112790 -v 0.023331 0.098729 0.117282 -v 0.027531 0.095270 0.114057 -v 0.030084 0.093694 0.112586 -v 0.030491 0.095113 0.113911 -v 0.030076 0.095522 0.114291 -v 0.047410 0.098729 0.117282 -v 0.029585 0.095735 0.114490 -v 0.028558 0.095810 0.114561 -v 0.023331 0.092803 0.111756 -v 0.029435 0.093426 0.112337 -v 0.030493 0.094100 0.112965 -v 0.030623 0.094473 0.113314 -v 0.030623 0.094736 0.113559 -v 0.047410 0.093635 0.112532 -v 0.046267 0.092803 0.111756 -v 0.023331 0.092841 0.112833 -v 0.023331 0.079675 0.126951 -v 0.023331 0.084524 0.132515 -v 0.047410 0.090718 0.114327 -v 0.047410 0.081017 0.124730 -v 0.048172 0.085940 0.129320 -v 0.047661 0.086637 0.129970 -v 0.047410 0.086219 0.129580 -v 0.048137 0.086144 0.129510 -v 0.047410 0.096429 0.119652 -v 0.047874 0.086503 0.129845 -v 0.047874 0.096204 0.119442 -v 0.048036 0.086335 0.129689 -v 0.048137 0.095845 0.119107 -v 0.048172 0.095641 0.118917 -v 0.047410 0.084524 0.132515 -v 0.047407 0.092616 0.112623 -v 0.047410 0.086728 0.130055 -v 0.046267 0.078598 0.126989 -v 0.023331 0.078598 0.126989 -v 0.027703 0.079453 0.127786 -v 0.047410 0.079430 0.127764 -v 0.030594 0.080662 0.128913 -v 0.029393 0.081559 0.129750 -v 0.027633 0.081262 0.129472 -v 0.029236 0.079206 0.127556 -v 0.030392 0.079670 0.127988 -v 0.046267 0.079675 0.126951 -v 0.027175 0.081403 0.128562 -v 0.023331 0.084486 0.131438 -v 0.028121 0.079834 0.127099 -v 0.029162 0.082117 0.129228 -v 0.047410 0.084486 0.131438 -v 0.029414 0.079747 0.127018 -v 0.030527 0.080357 0.127587 -v 0.030392 0.081650 0.128792 -v 0.013647 0.081993 0.133367 -v 0.037675 0.075540 0.129069 -v 0.035878 0.075284 0.128830 -v 0.038297 0.083106 0.134404 -v 0.038247 0.082249 0.135325 -v 0.039829 0.081394 0.134527 -v 0.039836 0.082203 0.133563 -v 0.034099 0.082250 0.135326 -v 0.032462 0.081250 0.134393 -v 0.004237 0.083486 0.136843 -v 0.002434 0.082867 0.136266 -v 0.005232 0.082005 0.135462 -v 0.005738 0.083057 0.136443 -v 0.008843 0.082426 0.135855 -v 0.006868 0.081629 0.135111 -v -0.000730 0.086000 0.135629 -v 0.001880 0.084586 0.137381 -v 0.001586 0.083247 0.136494 -v 0.000017 0.102093 0.120332 -v -0.000855 0.086887 0.134805 -v -0.000855 0.101179 0.119480 -v 0.000584 0.102666 0.116516 -v 0.002236 0.103559 0.116742 -v 0.002434 0.102355 0.115367 -v 0.002881 0.103414 0.116402 -v 0.013647 0.082477 0.135082 -v 0.012568 0.083315 0.134218 -v 0.012883 0.100398 0.115882 -v 0.013465 0.082976 0.134547 -v 0.010867 0.082506 0.135290 -v 0.011026 0.081493 0.134557 -v 0.011023 0.100581 0.114137 -v 0.011538 0.083130 0.134514 -v 0.011388 0.100772 0.115616 -v 0.001369 0.085038 0.137335 -v 0.000686 0.102824 0.118887 -v 0.001369 0.103573 0.117458 -v 0.000315 0.103234 0.118798 -v 0.000017 0.087801 0.135657 -v 0.000069 0.087241 0.136205 -v 0.000648 0.085888 0.137084 -v 0.002467 0.084178 0.137343 -v 0.003272 0.083806 0.137143 -v 0.004237 0.102974 0.115944 -v 0.005738 0.102545 0.115544 -v 0.007276 0.102191 0.115214 -v 0.007276 0.082703 0.136113 -v 0.008843 0.101914 0.114956 -v 0.006868 0.101117 0.114213 -v 0.005232 0.101493 0.114564 -v 0.003317 0.103280 0.116230 -v 0.010147 0.101745 0.114799 -v 0.010433 0.101692 0.114796 -v 0.013640 0.101008 0.115210 -v 0.013530 0.099631 0.114452 -v 0.013326 0.100569 0.115682 -v 0.013136 0.099369 0.114740 -v 0.012301 0.100347 0.115972 -v 0.031109 0.099120 0.117235 -v 0.031116 0.100500 0.114002 -v 0.038245 0.100516 0.115736 -v 0.038298 0.101372 0.114815 -v 0.039834 0.096796 0.110548 -v 0.039099 0.095601 0.109434 -v 0.038998 0.094617 0.110235 -v 0.037330 0.093723 0.109401 -v 0.016731 0.096516 0.110287 -v 0.015667 0.098034 0.111703 -v 0.016441 0.098188 0.111846 -v 0.027306 0.097065 0.110798 -v 0.017510 0.096921 0.110665 -v 0.027362 0.097380 0.111092 -v 0.017622 0.097325 0.111041 -v 0.017582 0.097548 0.111249 -v 0.028148 0.098123 0.111785 -v 0.027611 0.097781 0.111467 -v 0.030611 0.096721 0.110477 -v 0.034420 0.097838 0.111519 -v 0.030453 0.097665 0.111358 -v 0.029643 0.098190 0.111848 -v 0.017464 0.097757 0.111444 -v 0.017276 0.097935 0.111611 -v 0.036567 0.099635 0.113195 -v 0.033459 0.101372 0.114815 -v 0.027362 0.096750 0.110505 -v 0.014142 0.094768 0.108656 -v 0.015602 0.096647 0.110409 -v 0.037491 0.094601 0.108501 -v 0.027623 0.096334 0.110118 -v 0.037205 0.097660 0.111354 -v 0.037516 0.098808 0.112424 -v 0.039836 0.100470 0.113974 -v 0.032377 0.100267 0.113785 -v 0.035023 0.099543 0.113110 -v 0.035892 0.097230 0.110954 -v 0.035878 0.094408 0.108321 -v 0.016993 0.098091 0.111756 -v 0.034214 0.098472 0.112111 -v 0.034271 0.098787 0.112404 -v 0.015628 0.094408 0.108321 -v 0.028234 0.095967 0.109775 -v 0.028969 0.095848 0.109664 -v 0.035046 0.097418 0.111128 -v 0.015628 0.093551 0.109241 -v 0.013648 0.094548 0.110171 -v 0.013647 0.095857 0.109672 -v 0.017464 0.096035 0.111558 -v 0.017599 0.096711 0.112187 -v 0.034386 0.096954 0.112415 -v 0.039829 0.099660 0.114938 -v 0.017582 0.096244 0.111752 -v 0.027408 0.095762 0.111303 -v 0.027307 0.096365 0.111866 -v 0.027650 0.096971 0.112431 -v 0.037575 0.097169 0.112615 -v 0.030460 0.096807 0.112277 -v 0.033405 0.100511 0.115732 -v 0.030307 0.095469 0.111030 -v 0.029610 0.095069 0.110656 -v 0.031109 0.099402 0.114698 -v 0.029308 0.097436 0.112864 -v 0.039838 0.096000 0.111525 -v 0.035201 0.096492 0.111984 -v 0.034245 0.097927 0.113322 -v 0.032307 0.099369 0.114666 -v 0.035217 0.098783 0.114120 -v 0.036941 0.098607 0.113956 -v 0.030615 0.096020 0.111544 -v 0.035878 0.093551 0.109241 -v 0.027920 0.095248 0.110824 -v 0.017276 0.095856 0.111391 -v 0.014807 0.093656 0.109339 -v 0.015829 0.095632 0.111182 -v 0.015590 0.097165 0.112612 -v 0.013647 0.099402 0.114698 -v 0.017140 0.097176 0.112622 -v 0.031109 0.081993 0.133367 -v 0.031109 0.098006 0.116195 -v 0.034958 0.081247 0.132671 -v 0.015632 0.079739 0.131265 -v 0.035192 0.079084 0.130655 -v 0.037235 0.080982 0.132424 -v 0.016441 0.079922 0.131435 -v 0.034214 0.080205 0.131699 -v 0.034282 0.080549 0.132021 -v 0.037428 0.079598 0.131132 -v 0.013647 0.077307 0.128997 -v 0.014486 0.076353 0.128108 -v 0.016441 0.078194 0.129824 -v 0.015514 0.078422 0.130037 -v 0.015628 0.076141 0.127910 -v 0.027362 0.078483 0.130094 -v 0.027623 0.078067 0.129707 -v 0.027306 0.078798 0.130387 -v 0.017336 0.078468 0.130080 -v 0.034394 0.079607 0.131141 -v 0.030453 0.079397 0.130947 -v 0.017582 0.079281 0.130838 -v 0.028148 0.079857 0.131375 -v 0.027362 0.079113 0.130681 -v 0.017622 0.078947 0.130526 -v 0.029642 0.079924 0.131437 -v 0.028378 0.077639 0.129307 -v 0.035878 0.076141 0.127910 -v 0.039834 0.078529 0.130136 -v 0.027611 0.079513 0.131055 -v 0.017464 0.079490 0.131033 -v 0.017276 0.079669 0.131199 -v 0.016991 0.079825 0.131345 -v 0.032054 0.081954 0.133331 -v 0.032732 0.082495 0.133835 -v 0.029676 0.077688 0.129353 -v 0.030314 0.078064 0.129703 -v 0.036847 0.076219 0.127982 -v 0.030608 0.078585 0.130188 -v 0.039100 0.077335 0.129023 -v 0.038112 0.076634 0.128369 -v 0.033769 0.083108 0.134406 -v 0.031109 0.083390 0.131869 -v 0.031112 0.082221 0.133580 -v 0.018022 0.083390 0.131869 -v 0.018022 0.098006 0.116195 -v 0.018022 0.084504 0.132908 -v 0.031109 0.101374 0.114817 -v 0.018022 0.099120 0.117235 -v 0.013647 0.101374 0.114817 -v 0.013647 0.082250 0.135326 -v 0.031109 0.084504 0.132908 -v 0.031109 0.082250 0.135326 -v 0.039167 0.076547 0.130008 -v 0.028378 0.076782 0.130226 -v 0.013648 0.076414 0.129883 -v 0.015989 0.079027 0.132321 -v 0.039838 0.077734 0.131114 -v 0.030610 0.077738 0.131118 -v 0.030114 0.077007 0.130435 -v 0.016747 0.079035 0.132327 -v 0.017190 0.078876 0.132179 -v 0.031112 0.081408 0.134540 -v 0.017582 0.078424 0.131758 -v 0.017464 0.078632 0.131952 -v 0.015628 0.075284 0.128830 -v 0.027624 0.077210 0.130625 -v 0.016351 0.077296 0.130705 -v 0.014599 0.075444 0.128978 -v 0.015110 0.078102 0.131458 -v 0.017601 0.077944 0.131310 -v 0.027309 0.077752 0.131131 -v 0.027410 0.078390 0.131726 -v 0.037574 0.078902 0.132204 -v 0.035192 0.078227 0.131574 -v 0.034920 0.080471 0.133667 -v 0.036939 0.080341 0.133545 -v 0.031935 0.081106 0.134259 -v 0.027978 0.078941 0.132240 -v 0.029246 0.079149 0.132433 -v 0.034186 0.079011 0.132305 -v 0.030338 0.078686 0.132002 -v 0.033097 0.082037 0.135127 -v 0.013647 0.081135 0.134286 -v 0.013592 0.081641 0.133744 -v 0.012939 0.082143 0.133218 -v 0.012465 0.099229 0.114922 -v 0.011832 0.082131 0.133312 -v 0.013647 0.100260 0.113778 -v 0.011528 0.099530 0.114685 -v 0.011407 0.081819 0.133698 -v 0.010170 0.100616 0.113746 -v 0.010181 0.081127 0.134643 -v 0.003634 0.082462 0.135888 -v 0.001173 0.102668 0.116007 -v 0.002074 0.102479 0.115499 -v -0.000121 0.084832 0.136285 -v 0.000698 0.083922 0.136514 -v -0.000756 0.101884 0.118620 -v -0.000033 0.102544 0.117205 -v 0.003634 0.101950 0.114989 -v 0.008535 0.081335 0.134837 -v 0.008535 0.100823 0.113938 -v 0.010201 0.082249 0.135691 -v 0.015294 0.097531 0.111234 -v 0.015395 0.097726 0.111415 -v 0.015557 0.097897 0.111575 -v 0.015557 0.077872 0.133049 -v 0.015770 0.078010 0.133178 -v 0.015770 0.098036 0.111704 -v 0.016298 0.078157 0.133315 -v 0.016022 0.098132 0.111794 -v 0.016298 0.098182 0.111841 -v 0.016583 0.078157 0.133315 -v 0.016583 0.098182 0.111841 -v 0.016860 0.098132 0.111794 -v 0.017112 0.098036 0.111704 -v 0.017112 0.078010 0.133178 -v 0.017325 0.097897 0.111575 -v 0.017325 0.077872 0.133049 -v 0.017487 0.077701 0.132890 -v 0.017487 0.097726 0.111415 -v 0.017588 0.077506 0.132708 -v 0.017588 0.097531 0.111234 -v 0.017588 0.097118 0.110848 -v 0.017487 0.096923 0.110667 -v 0.017487 0.076898 0.132141 -v 0.017325 0.076727 0.131981 -v 0.017325 0.096752 0.110507 -v 0.017112 0.096614 0.110378 -v 0.016860 0.076492 0.131762 -v 0.016860 0.096517 0.110288 -v 0.016583 0.076442 0.131716 -v 0.016583 0.096467 0.110241 -v 0.016298 0.096467 0.110241 -v 0.016022 0.076492 0.131762 -v 0.015770 0.076589 0.131852 -v 0.016022 0.096517 0.110288 -v 0.015770 0.096614 0.110378 -v 0.015557 0.096752 0.110507 -v 0.015395 0.076898 0.132141 -v 0.015395 0.096923 0.110667 -v 0.015294 0.097118 0.110848 -v 0.015294 0.077093 0.132323 -v 0.015260 0.097325 0.111041 -v 0.015294 0.077506 0.132708 -v 0.015395 0.077701 0.132890 -v 0.016022 0.078107 0.133268 -v 0.016860 0.078107 0.133268 -v 0.017622 0.077300 0.132515 -v 0.015260 0.077300 0.132515 -v 0.017588 0.077093 0.132323 -v 0.017112 0.076589 0.131852 -v 0.016298 0.076442 0.131716 -v 0.015557 0.076727 0.131981 -v 0.037230 0.081322 0.132098 -v 0.037260 0.079741 0.130625 -v 0.035704 0.081777 0.132522 -v 0.035956 0.079326 0.130237 -v 0.032730 0.082398 0.133102 -v 0.034541 0.083307 0.133950 -v 0.038674 0.083315 0.133957 -v 0.034759 0.079591 0.130485 -v 0.034213 0.080972 0.131772 -v 0.031917 0.081173 0.131959 -v 0.016822 0.076865 0.125784 -v 0.031286 0.078655 0.126174 -v 0.031715 0.078418 0.126428 -v 0.031916 0.075788 0.126938 -v 0.037274 0.082420 0.130969 -v 0.034552 0.082551 0.131091 -v 0.034628 0.084390 0.132806 -v 0.038741 0.084378 0.132795 -v 0.039841 0.078014 0.126861 -v 0.039841 0.083188 0.131686 -v 0.032637 0.083412 0.131894 -v 0.031916 0.082140 0.130708 -v 0.034486 0.080883 0.129536 -v 0.035878 0.080312 0.129003 -v 0.037265 0.080879 0.129532 -v 0.038741 0.100073 0.115965 -v 0.039841 0.097839 0.116035 -v 0.031916 0.097832 0.113876 -v 0.032546 0.097944 0.116133 -v 0.034615 0.096437 0.112575 -v 0.036248 0.096045 0.112209 -v 0.034551 0.098245 0.114260 -v 0.034628 0.100085 0.115976 -v 0.037274 0.098114 0.114139 -v 0.032635 0.099105 0.115063 -v 0.037343 0.096690 0.112811 -v 0.039841 0.092557 0.108957 -v 0.039841 0.098878 0.114851 -v 0.039841 0.082144 0.132865 -v 0.039841 0.092635 0.111182 -v 0.038673 0.099009 0.117127 -v 0.037233 0.097015 0.115267 -v 0.037300 0.095469 0.113826 -v 0.034541 0.099002 0.117120 -v 0.031916 0.092635 0.111182 -v 0.035948 0.095021 0.113407 -v 0.035705 0.097471 0.115692 -v 0.034737 0.095299 0.113667 -v 0.031917 0.096723 0.114994 -v 0.034213 0.096667 0.114942 -v 0.031130 0.090764 0.110880 -v 0.030429 0.090769 0.110873 -v 0.029721 0.092259 0.111585 -v 0.019552 0.090273 0.111405 -v 0.021121 0.090100 0.111590 -v 0.021850 0.090350 0.113632 -v 0.021616 0.089573 0.114464 -v 0.020829 0.087894 0.113957 -v 0.020098 0.088959 0.115124 -v 0.019249 0.087869 0.113984 -v 0.018813 0.089175 0.114892 -v 0.031915 0.091404 0.110193 -v 0.031916 0.092557 0.108957 -v 0.031718 0.091109 0.110509 -v 0.031907 0.077080 0.125553 -v 0.031149 0.077539 0.125061 -v 0.022791 0.085749 0.116257 -v 0.029937 0.090974 0.110654 -v 0.016822 0.091481 0.110111 -v 0.018200 0.088674 0.113121 -v 0.030311 0.077583 0.125014 -v 0.016822 0.082596 0.119638 -v 0.039841 0.075788 0.126938 -v 0.021654 0.088498 0.113309 -v 0.021860 0.089137 0.112624 -v 0.018419 0.089738 0.111978 -v 0.016822 0.085749 0.116257 -v 0.020028 0.080537 0.121846 -v 0.018145 0.079335 0.123135 -v 0.029505 0.091481 0.110111 -v 0.029494 0.076865 0.125784 -v 0.029721 0.077238 0.125384 -v 0.019683 0.087822 0.118225 -v 0.014996 0.088100 0.118484 -v 0.015535 0.087017 0.117475 -v 0.021655 0.084974 0.121820 -v 0.014996 0.084982 0.121828 -v 0.015535 0.083899 0.120818 -v 0.019195 0.086081 0.122853 -v 0.018710 0.084744 0.121606 -v 0.020355 0.084323 0.121213 -v 0.019592 0.084728 0.121591 -v 0.022376 0.082690 0.119691 -v 0.022385 0.085806 0.116345 -v 0.021799 0.082877 0.119866 -v 0.021170 0.083302 0.120262 -v 0.022791 0.082596 0.119638 -v 0.019195 0.089199 0.119510 -v 0.018736 0.087869 0.118269 -v 0.020362 0.087429 0.117859 -v 0.021145 0.086447 0.116943 -v 0.021734 0.086027 0.116551 -v 0.031916 0.078014 0.126861 -v 0.029864 0.078495 0.126345 -v 0.031851 0.092439 0.111392 -v 0.018716 0.091162 0.112762 -v 0.020098 0.091434 0.112469 -v 0.029494 0.092632 0.111185 -v 0.016822 0.086901 0.117331 -v 0.018145 0.090162 0.113833 -v 0.031209 0.091937 0.111932 -v 0.022791 0.086901 0.117331 -v 0.021827 0.087894 0.118292 -v 0.023056 0.083748 0.120712 -v 0.030636 0.078740 0.126082 -v 0.023056 0.086883 0.117350 -v 0.019553 0.079224 0.125564 -v 0.016822 0.092632 0.111185 -v 0.029505 0.078016 0.126858 -v 0.016822 0.078016 0.126858 -v 0.020677 0.089038 0.115039 -v 0.030154 0.091993 0.111871 -v 0.019249 0.081628 0.122985 -v 0.021172 0.091199 0.112722 -v 0.016822 0.083748 0.120712 -v 0.018200 0.080822 0.123849 -v 0.018677 0.080212 0.122195 -v 0.020829 0.081603 0.123012 -v 0.021654 0.080999 0.123660 -v 0.021396 0.080191 0.122218 -v 0.021860 0.080360 0.124346 -v 0.021850 0.079146 0.123337 -v 0.021121 0.079397 0.125379 -v 0.021172 0.078298 0.124247 -v 0.020098 0.078063 0.124500 -v 0.018420 0.079758 0.124992 -v 0.018715 0.078336 0.124207 -v 0.036735 -0.006730 0.152433 -v 0.036404 -0.004801 0.152843 -v 0.039300 -0.006028 0.152579 -v 0.037139 -0.005672 0.152658 -v 0.035596 -0.006917 0.152394 -v 0.035265 -0.004988 0.152804 -v 0.036889 -0.006187 0.147943 -v 0.034976 -0.006618 0.150698 -v 0.035170 -0.004239 0.151204 -v 0.036294 -0.007006 0.150610 -v 0.037372 -0.006172 0.150793 -v 0.037371 -0.004717 0.151100 -v 0.038128 -0.003359 0.153142 -v 0.036187 -0.004024 0.151246 -v 0.037750 -0.008635 0.152004 -v 0.035353 -0.008951 0.151959 -v 0.036110 -0.002715 0.153284 -v 0.034270 -0.003114 0.153189 -v 0.032979 -0.004746 0.152853 -v 0.034422 -0.005407 0.150976 -v 0.033636 -0.008081 0.152142 -v 0.037139 -0.005527 0.151973 -v 0.036735 -0.006585 0.151749 -v 0.035596 -0.006772 0.151709 -v 0.034861 -0.006046 0.152579 -v 0.034861 -0.005900 0.151894 -v 0.035265 -0.004842 0.152119 -v 0.036404 -0.004656 0.152159 -v 0.037564 -0.004619 0.147864 -v 0.036744 -0.003561 0.148066 -v 0.034623 -0.004232 0.148061 -v 0.035548 -0.003472 0.148522 -v 0.034600 -0.005478 0.147768 -v 0.035523 -0.006349 0.147911 -v 0.036735 -0.057808 0.141576 -v 0.035265 -0.059550 0.141206 -v 0.037139 -0.058866 0.141351 -v 0.036404 -0.059737 0.141166 -v 0.032786 -0.059200 0.141276 -v 0.035596 -0.057621 0.141616 -v 0.034861 -0.058492 0.141431 -v 0.037529 -0.057624 0.137012 -v 0.037017 -0.056619 0.137227 -v 0.034903 -0.058698 0.136434 -v 0.034434 -0.058381 0.139689 -v 0.035288 -0.056933 0.140002 -v 0.036672 -0.056986 0.139989 -v 0.037074 -0.059393 0.139480 -v 0.037558 -0.058018 0.139771 -v 0.037987 -0.056107 0.141924 -v 0.035120 -0.059551 0.139446 -v 0.036124 -0.059804 0.139390 -v 0.036004 -0.061861 0.140706 -v 0.038422 -0.060907 0.140911 -v 0.039258 -0.058326 0.141462 -v 0.035292 -0.055524 0.142057 -v 0.033186 -0.057032 0.141737 -v 0.033890 -0.061135 0.140865 -v 0.037139 -0.058720 0.140667 -v 0.034861 -0.058347 0.140746 -v 0.035596 -0.057476 0.140931 -v 0.035265 -0.059405 0.140521 -v 0.036404 -0.059592 0.140482 -v 0.036735 -0.057662 0.140892 -v 0.036062 -0.059258 0.136664 -v 0.037193 -0.058592 0.136463 -v 0.035723 -0.056164 0.136894 -v 0.034451 -0.057390 0.137057 -v 0.005265 -0.057808 0.141576 -v 0.006404 -0.057621 0.141616 -v 0.004861 -0.058866 0.141351 -v 0.005596 -0.059737 0.141166 -v 0.007139 -0.058492 0.141431 -v 0.006735 -0.059550 0.141206 -v 0.004676 -0.056881 0.137165 -v 0.004608 -0.058233 0.136430 -v 0.005519 -0.059184 0.136680 -v 0.007375 -0.058301 0.136517 -v 0.007026 -0.057206 0.139946 -v 0.007505 -0.058106 0.139751 -v 0.007137 -0.059406 0.139476 -v 0.005809 -0.059797 0.139391 -v 0.004628 -0.057650 0.139851 -v 0.004629 -0.059105 0.139539 -v 0.004779 -0.055741 0.142012 -v 0.008593 -0.060122 0.140801 -v 0.005704 -0.056815 0.140023 -v 0.003690 -0.056737 0.141571 -v 0.002781 -0.058172 0.141496 -v 0.003288 -0.060518 0.140995 -v 0.005336 -0.061799 0.140724 -v 0.007259 -0.061600 0.140765 -v 0.009190 -0.057828 0.141568 -v 0.007211 -0.055647 0.142029 -v 0.004861 -0.058720 0.140667 -v 0.006735 -0.059405 0.140521 -v 0.007139 -0.058347 0.140746 -v 0.006404 -0.057476 0.140931 -v 0.005596 -0.059592 0.140482 -v 0.005265 -0.057662 0.140892 -v 0.006660 -0.059084 0.136703 -v 0.007386 -0.057024 0.137138 -v 0.006145 -0.056184 0.137009 -v 0.029863 -0.011045 0.151291 -v 0.031249 -0.010038 0.151506 -v 0.029146 -0.004574 0.154200 -v 0.027367 -0.004431 0.152697 -v 0.026101 -0.005149 0.152545 -v 0.024886 -0.007658 0.153545 -v 0.026131 -0.007178 0.153647 -v 0.031461 -0.005961 0.153905 -v 0.031321 -0.010264 0.152991 -v 0.032114 -0.008505 0.153365 -v 0.030752 -0.006747 0.153738 -v 0.027250 -0.004783 0.154156 -v 0.025821 -0.005707 0.153959 -v 0.029994 -0.011302 0.152770 -v 0.027852 -0.011589 0.152709 -v 0.025538 -0.010201 0.153004 -v 0.027556 -0.006247 0.156260 -v 0.027175 -0.005963 0.153905 -v 0.028776 -0.005608 0.153981 -v 0.030870 -0.008983 0.153263 -v 0.029826 -0.010200 0.153004 -v 0.028224 -0.010555 0.152929 -v 0.028567 -0.011012 0.154907 -v 0.026656 -0.009851 0.153102 -v 0.025963 -0.008322 0.153412 -v 0.031094 -0.008403 0.155760 -v 0.030272 -0.010326 0.155273 -v 0.029748 -0.006390 0.156370 -v 0.026264 -0.007390 0.155861 -v 0.029385 -0.010270 0.156555 -v 0.028982 -0.007670 0.157422 -v 0.026880 -0.009598 0.156823 -v 0.010949 -0.010276 0.151455 -v 0.012083 -0.011315 0.152767 -v 0.014021 -0.011604 0.152706 -v 0.014364 -0.011184 0.151261 -v 0.017069 -0.008780 0.153306 -v 0.017168 -0.007890 0.151962 -v 0.016884 -0.006891 0.153708 -v 0.015947 -0.005478 0.154008 -v 0.013975 -0.004560 0.154203 -v 0.010770 -0.005451 0.152480 -v 0.010075 -0.008842 0.151759 -v 0.010381 -0.009973 0.153052 -v 0.009912 -0.007857 0.153502 -v 0.011814 -0.004953 0.154120 -v 0.010396 -0.006267 0.153841 -v 0.015987 -0.010648 0.152909 -v 0.010969 -0.008329 0.153402 -v 0.011338 -0.006779 0.153731 -v 0.013133 -0.005543 0.153999 -v 0.015943 -0.007412 0.153597 -v 0.014185 -0.010507 0.152939 -v 0.011955 -0.010120 0.153021 -v 0.015764 -0.007605 0.156274 -v 0.015010 -0.006073 0.153896 -v 0.011226 -0.009643 0.155552 -v 0.015000 -0.010668 0.155446 -v 0.015856 -0.009106 0.153243 -v 0.012279 -0.006341 0.156090 -v 0.012463 -0.010885 0.155282 -v 0.011071 -0.008003 0.156433 -v 0.013445 -0.010221 0.156830 -v 0.014343 -0.007298 0.157325 -v 0.025076 -0.001901 0.153235 -v 0.009663 -0.001901 0.153235 -v 0.007170 -0.003064 0.152987 -v 0.005450 -0.002901 0.153021 -v 0.036240 -0.002769 0.153041 -v 0.003815 -0.003718 0.152844 -v 0.007500 -0.008355 0.151863 -v 0.006554 -0.008727 0.151784 -v 0.002000 -0.012795 0.150919 -v 0.038233 -0.002987 0.153004 -v 0.038810 -0.004503 0.152667 -v 0.003130 -0.003632 0.152867 -v 0.002018 -0.005912 0.152382 -v 0.032955 -0.005564 0.152457 -v 0.040000 -0.006792 0.152195 -v 0.032338 -0.001901 0.153235 -v 0.008298 -0.007700 0.152002 -v 0.040000 -0.009812 0.151553 -v 0.008298 -0.056747 0.141577 -v 0.034072 -0.008061 0.151925 -v 0.040000 -0.012795 0.150919 -v 0.002000 -0.009812 0.151553 -v 0.033702 -0.007700 0.152002 -v 0.040000 -0.038092 0.145542 -v 0.035500 -0.008736 0.151782 -v 0.007008 -0.055839 0.141770 -v 0.007928 -0.056386 0.141654 -v 0.002000 -0.056465 0.141637 -v 0.002000 -0.057655 0.141384 -v 0.040000 -0.056465 0.141637 -v 0.009044 -0.058889 0.141122 -v 0.039578 -0.059663 0.140957 -v 0.038907 -0.059633 0.140956 -v 0.025076 -0.062546 0.140344 -v 0.038539 -0.056840 0.141552 -v 0.003456 -0.061126 0.140646 -v 0.037085 -0.061455 0.140569 -v 0.017597 -0.062546 0.140344 -v 0.034733 -0.061354 0.140598 -v 0.035927 -0.062523 0.140349 -v 0.007827 -0.061122 0.140645 -v 0.036643 -0.055799 0.141778 -v 0.024548 -0.008342 0.151866 -v 0.017515 -0.008637 0.151803 -v 0.020177 -0.011194 0.151259 -v 0.014570 -0.004412 0.152701 -v 0.012398 -0.004402 0.152703 -v 0.016242 -0.005427 0.152485 -v 0.009936 -0.007174 0.152114 -v 0.016079 -0.010283 0.151453 -v 0.012429 -0.011128 0.151273 -v 0.031826 -0.006433 0.152272 -v 0.025122 -0.006510 0.152255 -v 0.029555 -0.004388 0.152707 -v 0.031007 -0.005248 0.152524 -v 0.024943 -0.008400 0.151853 -v 0.032094 -0.008337 0.151867 -v 0.025803 -0.010124 0.151487 -v 0.027442 -0.011152 0.151269 -v 0.035400 -0.012465 0.150989 -v 0.004600 -0.036527 0.145875 -v 0.037400 -0.036527 0.145875 -v 0.035892 -0.038431 0.145470 -v 0.035400 -0.038484 0.145459 -v 0.035951 -0.012534 0.150974 -v 0.006253 -0.038454 0.145465 -v 0.005550 -0.038214 0.145516 -v 0.035000 -0.038484 0.145459 -v 0.006513 -0.038536 0.145448 -v 0.005000 -0.040440 0.145043 -v 0.037000 -0.050221 0.142964 -v 0.036128 -0.051845 0.142619 -v 0.037000 -0.040440 0.145043 -v 0.005132 -0.051014 0.142796 -v 0.007000 -0.052178 0.142548 -v 0.018547 -0.010712 0.152896 -v 0.018438 -0.010299 0.151449 -v 0.021918 -0.011513 0.152725 -v 0.022349 -0.011051 0.151291 -v 0.023895 -0.009888 0.151537 -v 0.024438 -0.006676 0.152220 -v 0.023358 -0.005089 0.152557 -v 0.021823 -0.004345 0.152715 -v 0.019884 -0.004425 0.152698 -v 0.020183 -0.004555 0.154204 -v 0.018426 -0.005286 0.152515 -v 0.017478 -0.006971 0.152158 -v 0.017720 -0.006471 0.153797 -v 0.018393 -0.008449 0.153377 -v 0.024284 -0.006648 0.153759 -v 0.023058 -0.005145 0.154079 -v 0.024610 -0.008282 0.153412 -v 0.023851 -0.010296 0.152984 -v 0.020297 -0.011531 0.152721 -v 0.019748 -0.010247 0.152994 -v 0.017469 -0.008839 0.153293 -v 0.019146 -0.006385 0.153815 -v 0.020590 -0.005626 0.153977 -v 0.019591 -0.006471 0.156052 -v 0.022253 -0.005916 0.153915 -v 0.023506 -0.008760 0.153311 -v 0.021814 -0.010490 0.152943 -v 0.023322 -0.007085 0.153678 -v 0.022739 -0.006898 0.156490 -v 0.018453 -0.008051 0.155480 -v 0.019207 -0.010348 0.155025 -v 0.023401 -0.009580 0.155797 -v 0.021295 -0.006063 0.156103 -v 0.021267 -0.011038 0.155239 -v 0.019527 -0.009478 0.157030 -v 0.020864 -0.007490 0.157480 -v 0.005000 -0.050221 0.142964 -v 0.035000 -0.052178 0.142548 -v 0.007000 -0.052593 0.144505 -v 0.035730 -0.052479 0.144529 -v 0.032957 -0.049855 0.145087 -v 0.035000 -0.052593 0.144505 -v 0.009043 -0.041638 0.146833 -v 0.005000 -0.050922 0.144859 -v 0.005596 -0.052081 0.144613 -v 0.009208 -0.041808 0.147631 -v 0.009208 -0.050024 0.145884 -v 0.031865 -0.042340 0.150136 -v 0.032339 -0.050331 0.147326 -v 0.032339 -0.042114 0.149072 -v 0.012991 -0.050285 0.147112 -v 0.015480 -0.042052 0.148779 -v 0.020449 -0.042117 0.149087 -v 0.022909 -0.042199 0.149473 -v 0.012991 -0.042069 0.148858 -v 0.017970 -0.042068 0.148855 -v 0.032957 -0.041638 0.146833 -v 0.025338 -0.042314 0.150013 -v 0.027726 -0.042461 0.150702 -v 0.032704 -0.041879 0.147967 -v 0.009486 -0.042014 0.148605 -v 0.010176 -0.042126 0.149124 -v 0.015480 -0.050268 0.147033 -v 0.009043 -0.049855 0.145087 -v 0.025338 -0.050530 0.148266 -v 0.022909 -0.050416 0.147727 -v 0.020449 -0.050334 0.147341 -v 0.017970 -0.050285 0.147109 -v 0.027726 -0.050677 0.148956 -v 0.032704 -0.050096 0.146221 -v 0.010347 -0.050338 0.147363 -v 0.031865 -0.050557 0.148390 -v 0.030208 -0.050866 0.149845 -v 0.031256 -0.050784 0.149460 -v 0.031263 -0.042565 0.151193 -v 0.030981 -0.042623 0.151464 -v 0.030808 -0.050860 0.149820 -v 0.030340 -0.042660 0.151638 -v 0.009816 -0.050303 0.147200 -v 0.009460 -0.050214 0.146777 -v 0.037000 -0.040418 0.147092 -v 0.036868 -0.039647 0.145211 -v 0.036128 -0.039196 0.147352 -v 0.036181 -0.038852 0.145381 -v 0.035545 -0.038551 0.145445 -v 0.006533 -0.038957 0.147403 -v 0.005868 -0.038819 0.145388 -v 0.005173 -0.039561 0.145230 -v 0.005000 -0.040174 0.147144 -v 0.005822 -0.051811 0.142627 -v 0.006448 -0.052109 0.142563 -v 0.035491 -0.052125 0.142559 -v 0.036828 -0.051100 0.142777 -v 0.037000 -0.051320 0.144775 -v 0.037400 -0.014421 0.150574 -v 0.006600 -0.012881 0.152946 -v 0.009043 -0.016451 0.152187 -v 0.004600 -0.036943 0.147831 -v 0.032957 -0.035329 0.148174 -v 0.037400 -0.036943 0.147831 -v 0.009043 -0.035329 0.148174 -v 0.005870 -0.012996 0.152922 -v 0.035000 -0.038899 0.147415 -v 0.009208 -0.016620 0.152984 -v 0.031288 -0.017369 0.156504 -v 0.032035 -0.017079 0.155140 -v 0.032595 -0.016771 0.153693 -v 0.032595 -0.035649 0.149680 -v 0.012991 -0.016881 0.154212 -v 0.015480 -0.035743 0.150120 -v 0.017970 -0.035759 0.150196 -v 0.017970 -0.016881 0.154209 -v 0.020449 -0.035808 0.150428 -v 0.027726 -0.017273 0.156056 -v 0.027726 -0.036152 0.152043 -v 0.015480 -0.016865 0.154133 -v 0.020449 -0.016930 0.154441 -v 0.032957 -0.016451 0.152187 -v 0.022909 -0.017012 0.154827 -v 0.025338 -0.017127 0.155366 -v 0.010419 -0.016933 0.154456 -v 0.009429 -0.016787 0.153769 -v 0.009208 -0.035499 0.148972 -v 0.012991 -0.035760 0.150199 -v 0.022909 -0.035890 0.150814 -v 0.025338 -0.036005 0.151354 -v 0.032035 -0.035957 0.151128 -v 0.030065 -0.036330 0.152881 -v 0.010512 -0.035810 0.150434 -v 0.010267 -0.035810 0.150438 -v 0.009982 -0.035793 0.150357 -v 0.031288 -0.036247 0.152491 -v 0.031154 -0.017405 0.156675 -v 0.030891 -0.017444 0.156856 -v 0.031134 -0.036287 0.152681 -v 0.030891 -0.036321 0.152844 -v 0.030598 -0.036341 0.152937 -v 0.030598 -0.017463 0.156949 -v 0.030299 -0.017465 0.156958 -v 0.030276 -0.036342 0.152942 -v 0.030065 -0.017451 0.156894 -v 0.010128 -0.016926 0.154420 -v 0.009911 -0.016908 0.154339 -v 0.009724 -0.016883 0.154216 -v 0.009706 -0.035757 0.150188 -v 0.009528 -0.016834 0.153988 -v 0.009514 -0.035707 0.149952 -v 0.009429 -0.035665 0.149756 -v 0.037400 -0.014837 0.152530 -v 0.037282 -0.014122 0.152682 -v 0.036528 -0.013178 0.152882 -v 0.037269 -0.013629 0.150742 -v 0.036577 -0.012831 0.150912 -v 0.035400 -0.012881 0.152946 -v 0.006600 -0.012465 0.150989 -v 0.006110 -0.012518 0.150978 -v 0.005472 -0.012798 0.150919 -v 0.004772 -0.013544 0.150760 -v 0.004905 -0.013732 0.152765 -v 0.004600 -0.014421 0.150574 -v 0.004600 -0.014837 0.152530 -v 0.004718 -0.037657 0.147679 -v 0.004732 -0.037320 0.145707 -v 0.005617 -0.038713 0.147455 -v 0.006800 -0.038484 0.145459 -v 0.036008 -0.038842 0.147427 -v 0.036534 -0.038147 0.145530 -v 0.037227 -0.037406 0.145688 -v 0.037094 -0.038048 0.147596 -v 0.005596 -0.004801 0.152843 -v 0.005265 -0.006730 0.152433 -v 0.004861 -0.005672 0.152658 -v 0.006404 -0.006917 0.152394 -v 0.006597 -0.003471 0.148187 -v 0.006894 -0.006050 0.147536 -v 0.005368 -0.003556 0.148505 -v 0.005361 -0.006324 0.147914 -v 0.006453 -0.004068 0.151240 -v 0.007292 -0.006310 0.150763 -v 0.004467 -0.005453 0.150946 -v 0.005089 -0.004253 0.151195 -v 0.003022 -0.004514 0.152900 -v 0.002836 -0.006553 0.152468 -v 0.004996 -0.006692 0.150693 -v 0.006007 -0.008760 0.151769 -v 0.006362 -0.006960 0.150626 -v 0.007472 -0.004973 0.151042 -v 0.007113 -0.003066 0.152970 -v 0.004958 -0.002791 0.153266 -v 0.004496 -0.008667 0.152018 -v 0.007538 -0.008647 0.152018 -v 0.008878 -0.007360 0.152296 -v 0.009216 -0.005340 0.152725 -v 0.008455 -0.003812 0.153047 -v 0.005265 -0.006585 0.151749 -v 0.006404 -0.006772 0.151709 -v 0.004861 -0.005527 0.151973 -v 0.005596 -0.004656 0.152159 -v 0.006735 -0.004988 0.152804 -v 0.007139 -0.006046 0.152579 -v 0.007139 -0.005900 0.151894 -v 0.006735 -0.004842 0.152119 -v 0.004575 -0.004368 0.148333 -v 0.004565 -0.005281 0.147758 -v 0.007585 -0.004802 0.148235 -v 0.032338 -0.062546 0.140344 -v 0.022163 -0.062546 0.140344 -v 0.017250 -0.062216 0.138792 -v 0.009663 -0.062546 0.140344 -v 0.009013 -0.062216 0.138792 -v 0.040000 -0.008846 0.150136 -v 0.040000 -0.012465 0.149366 -v 0.040000 -0.037762 0.143989 -v 0.040000 -0.053510 0.140642 -v 0.024750 -0.001571 0.151682 -v 0.009013 -0.001571 0.151682 -v 0.017250 -0.001571 0.151682 -v 0.018679 -0.001901 0.153235 -v 0.022163 -0.001901 0.153235 -v 0.002000 -0.053510 0.140642 -v 0.002000 -0.038092 0.145542 -v 0.007334 -0.004782 0.151001 -v 0.005170 -0.006681 0.150596 -v 0.004799 -0.004609 0.151042 -v 0.002916 -0.005846 0.152392 -v 0.004330 -0.005896 0.151035 -v 0.004236 -0.008342 0.151865 -v 0.006505 -0.007116 0.150744 -v 0.007928 -0.008061 0.151925 -v 0.007515 -0.006313 0.150947 -v 0.008958 -0.006566 0.152243 -v 0.008805 -0.004631 0.152655 -v 0.034573 -0.005094 0.150933 -v 0.033813 -0.003714 0.152849 -v 0.034559 -0.006438 0.150920 -v 0.033292 -0.007049 0.152140 -v 0.034500 -0.008355 0.151863 -v 0.035778 -0.007133 0.150684 -v 0.037314 -0.008512 0.151829 -v 0.038781 -0.007053 0.152139 -v 0.036938 -0.004287 0.151107 -v 0.036588 -0.056999 0.139901 -v 0.034907 -0.057030 0.139894 -v 0.034915 -0.059478 0.139471 -v 0.033702 -0.056747 0.141577 -v 0.034306 -0.058141 0.139930 -v 0.033044 -0.057872 0.141338 -v 0.033210 -0.059858 0.140916 -v 0.034947 -0.055855 0.141766 -v 0.035264 -0.056932 0.140011 -v 0.034072 -0.056386 0.141654 -v 0.037404 -0.057848 0.139724 -v 0.007093 -0.057030 0.139894 -v 0.005174 -0.057104 0.139883 -v 0.004489 -0.058435 0.139596 -v 0.006401 -0.059676 0.139331 -v 0.005262 -0.061528 0.140558 -v 0.003012 -0.058147 0.141279 -v 0.003344 -0.060153 0.140844 -v 0.006441 -0.056750 0.140182 -v 0.005739 -0.055721 0.141795 -v 0.004974 -0.055876 0.141762 -v 0.003815 -0.056537 0.141621 -v 0.007408 -0.058787 0.139521 -v 0.007544 -0.057672 0.140008 -v 0.008716 -0.057361 0.141447 -v 0.002296 -0.059447 0.141003 -v 0.002577 -0.059706 0.139325 -v 0.004888 -0.061774 0.138886 -v 0.004878 -0.062111 0.140437 -v 0.006440 -0.062535 0.140345 -v 0.007000 -0.062216 0.138792 -v 0.006474 -0.001906 0.153234 -v 0.004810 -0.002374 0.153134 -v 0.036710 -0.061921 0.138854 -v 0.038226 -0.061474 0.140559 -v 0.039105 -0.060138 0.139233 -v 0.039974 -0.058226 0.141262 -v 0.039979 -0.005663 0.150813 -v 0.039750 -0.005166 0.152541 -v 0.035831 -0.001920 0.153231 -v 0.033883 0.039335 0.141626 -v 0.033226 0.041095 0.146933 -v 0.032074 0.040067 0.141471 -v 0.031070 0.040405 0.147079 -v 0.032711 0.038153 0.147558 -v 0.033925 0.040445 0.147071 -v 0.031076 0.038948 0.147389 -v 0.033375 0.038386 0.147525 -v 0.033930 0.038989 0.147380 -v 0.034092 0.039636 0.147243 -v 0.031900 0.038228 0.147541 -v 0.030908 0.039758 0.147217 -v 0.031735 0.041090 0.146934 -v 0.032567 0.041254 0.146899 -v 0.035529 0.036628 0.147325 -v 0.031737 0.036129 0.147956 -v 0.029305 0.036465 0.146904 -v 0.029177 0.039530 0.147264 -v 0.028114 0.039411 0.146645 -v 0.029620 0.042694 0.145886 -v 0.031464 0.043521 0.144388 -v 0.032427 0.043805 0.145695 -v 0.032357 0.043268 0.146470 -v 0.035211 0.042898 0.145978 -v 0.035856 0.039287 0.147315 -v 0.036803 0.038777 0.146645 -v 0.034874 0.043016 0.144496 -v 0.035680 0.036208 0.145943 -v 0.030532 0.035311 0.146134 -v 0.030369 0.040517 0.145027 -v 0.028515 0.041322 0.144856 -v 0.028291 0.037902 0.145582 -v 0.033443 0.035012 0.146200 -v 0.034713 0.040372 0.145058 -v 0.032941 0.036901 0.145795 -v 0.036985 0.040038 0.145130 -v 0.034692 0.038214 0.145516 -v 0.032584 0.041734 0.144768 -v 0.030417 0.037865 0.145590 -v 0.031784 0.036635 0.144229 -v 0.031180 0.037629 0.141989 -v 0.029912 0.036241 0.142291 -v 0.032088 0.037013 0.142120 -v 0.030889 0.038674 0.141767 -v 0.033191 0.037112 0.142099 -v 0.033970 0.037883 0.141934 -v 0.031265 0.039540 0.141583 -v 0.034085 0.038697 0.141762 -v 0.033176 0.039978 0.141490 -v 0.035135 0.036692 0.142189 -v 0.035919 0.036087 0.143079 -v 0.036794 0.038147 0.142534 -v 0.034713 0.040984 0.141276 -v 0.036353 0.040599 0.142071 -v 0.034780 0.042799 0.142918 -v 0.033966 0.042723 0.141709 -v 0.031200 0.042808 0.141669 -v 0.029690 0.040866 0.141316 -v 0.028981 0.038193 0.141884 -v 0.029139 0.036055 0.144350 -v 0.031757 0.034392 0.143556 -v 0.033748 0.035404 0.142470 -v 0.036514 0.036964 0.144159 -v 0.036755 0.040154 0.143481 -v 0.031156 0.043093 0.142856 -v 0.027906 0.038552 0.143812 -v 0.031524 0.034753 0.144629 -v 0.034299 0.034947 0.144586 -v 0.030118 0.038292 0.143877 -v 0.030743 0.040701 0.143364 -v 0.034709 0.040111 0.143490 -v 0.034404 0.037312 0.144085 -v 0.028926 0.041553 0.143182 -v 0.032862 0.041303 0.143237 -v 0.018633 0.057028 0.143204 -v 0.020494 0.057745 0.143052 -v 0.019056 0.055977 0.143427 -v 0.020198 0.055810 0.143463 -v 0.020917 0.056694 0.143275 -v 0.018799 0.055356 0.141873 -v 0.020359 0.053947 0.136241 -v 0.020913 0.055528 0.141836 -v 0.021254 0.055005 0.136016 -v 0.021173 0.055900 0.135636 -v 0.021256 0.056868 0.141551 -v 0.020486 0.056618 0.135673 -v 0.019970 0.057985 0.141314 -v 0.018387 0.057106 0.141501 -v 0.018270 0.056283 0.141676 -v 0.018264 0.055222 0.135773 -v 0.016828 0.056317 0.141668 -v 0.019010 0.057823 0.141348 -v 0.019575 0.055059 0.141936 -v 0.020743 0.057669 0.141381 -v 0.021231 0.056149 0.141704 -v 0.020184 0.055094 0.141928 -v 0.018385 0.059280 0.141048 -v 0.021599 0.058760 0.141149 -v 0.022803 0.056234 0.141689 -v 0.021211 0.053988 0.142165 -v 0.018213 0.054018 0.142158 -v 0.021465 0.056949 0.143212 -v 0.021838 0.055339 0.142842 -v 0.019908 0.053858 0.142833 -v 0.020342 0.055219 0.143591 -v 0.016872 0.056484 0.142267 -v 0.018593 0.055488 0.143507 -v 0.019223 0.057974 0.143099 -v 0.021514 0.058959 0.141738 -v 0.018633 0.056893 0.142568 -v 0.020494 0.057610 0.142416 -v 0.020917 0.056559 0.142639 -v 0.019352 0.057777 0.142380 -v 0.020198 0.055675 0.142827 -v 0.019056 0.055842 0.142792 -v 0.018572 0.054375 0.136148 -v 0.019517 0.053803 0.136071 -v 0.020942 0.054332 0.135965 -v 0.019666 0.056758 0.135448 -v 0.018876 0.056501 0.135697 -v 0.018413 0.055954 0.135814 -v 0.009680 0.033883 0.148202 -v 0.009864 0.032691 0.148377 -v 0.010615 0.034504 0.147992 -v 0.011845 0.032962 0.148320 -v 0.009969 0.030594 0.141205 -v 0.010355 0.031621 0.146918 -v 0.011203 0.031613 0.146920 -v 0.012015 0.030989 0.141120 -v 0.011812 0.031977 0.146842 -v 0.012191 0.032355 0.140830 -v 0.011249 0.033233 0.140644 -v 0.010234 0.034436 0.146319 -v 0.009569 0.033935 0.146426 -v 0.009237 0.033039 0.146617 -v 0.009332 0.035536 0.146085 -v 0.009638 0.032051 0.146826 -v 0.009195 0.030451 0.147184 -v 0.012188 0.033636 0.146489 -v 0.011319 0.034450 0.146316 -v 0.012221 0.032574 0.146715 -v 0.007869 0.034017 0.146426 -v 0.011505 0.030219 0.147221 -v 0.007886 0.032213 0.146799 -v 0.011814 0.031312 0.148251 -v 0.009222 0.032504 0.148438 -v 0.010118 0.035921 0.146547 -v 0.011756 0.034136 0.148194 -v 0.012787 0.035446 0.146118 -v 0.013799 0.032244 0.146795 -v 0.009705 0.033675 0.147504 -v 0.010943 0.032265 0.148476 -v 0.009864 0.032556 0.147741 -v 0.011686 0.033945 0.147446 -v 0.010615 0.034369 0.147356 -v 0.011845 0.032826 0.147684 -v 0.010935 0.032132 0.147831 -v 0.009452 0.031060 0.140912 -v 0.010526 0.030378 0.141252 -v 0.011364 0.030423 0.141047 -v 0.012275 0.031611 0.140793 -v 0.011781 0.032899 0.140514 -v 0.010541 0.033269 0.140441 -v 0.009682 0.032874 0.140720 -v 0.009263 0.031984 0.140715 -v 0.020586 0.031227 0.148731 -v 0.020586 0.032429 0.148579 -v 0.022602 0.031108 0.148714 -v 0.021736 0.032879 0.148344 -v 0.020271 0.030798 0.147093 -v 0.020873 0.028929 0.141558 -v 0.022333 0.030084 0.147244 -v 0.022586 0.028983 0.141355 -v 0.022960 0.030642 0.147126 -v 0.021429 0.032879 0.146650 -v 0.020189 0.030580 0.141208 -v 0.020148 0.031726 0.146895 -v 0.018544 0.031535 0.146954 -v 0.019917 0.033877 0.146439 -v 0.020665 0.032527 0.146725 -v 0.020817 0.030157 0.147229 -v 0.022490 0.032664 0.146696 -v 0.021625 0.029925 0.147278 -v 0.023161 0.031687 0.146903 -v 0.023728 0.033719 0.146477 -v 0.024197 0.029832 0.147298 -v 0.020951 0.028420 0.147620 -v 0.019121 0.029666 0.147352 -v 0.023093 0.029190 0.148116 -v 0.021307 0.034261 0.147062 -v 0.022723 0.032308 0.148523 -v 0.024611 0.031420 0.147570 -v 0.021741 0.032738 0.147703 -v 0.022692 0.032098 0.147839 -v 0.022602 0.030972 0.148078 -v 0.021564 0.030616 0.148830 -v 0.021559 0.030486 0.148181 -v 0.020698 0.032252 0.147806 -v 0.020608 0.031126 0.148045 -v 0.020162 0.029979 0.141336 -v 0.020363 0.029381 0.141261 -v 0.021680 0.028708 0.141605 -v 0.023121 0.029809 0.141371 -v 0.023065 0.030710 0.140983 -v 0.021986 0.031651 0.140980 -v 0.022608 0.031292 0.140857 -v 0.021250 0.031616 0.140988 -v 0.020618 0.031255 0.140870 -v 0.011690 0.009097 0.153492 -v 0.012362 0.007162 0.153836 -v 0.013594 0.007491 0.153820 -v 0.012638 0.005232 0.146595 -v 0.013694 0.006858 0.152181 -v 0.013886 0.005884 0.146458 -v 0.014083 0.007456 0.152054 -v 0.013476 0.007935 0.145828 -v 0.011185 0.008294 0.151876 -v 0.012469 0.009409 0.151639 -v 0.011599 0.009007 0.151725 -v 0.011234 0.007341 0.152078 -v 0.014109 0.008405 0.151853 -v 0.013416 0.009217 0.151680 -v 0.015484 0.008653 0.151799 -v 0.011994 0.006584 0.152239 -v 0.012100 0.005114 0.152552 -v 0.009667 0.007169 0.152115 -v 0.012952 0.006468 0.152264 -v 0.009631 0.008358 0.152264 -v 0.011442 0.010702 0.151364 -v 0.014108 0.005559 0.152995 -v 0.014850 0.005916 0.152381 -v 0.011155 0.005607 0.153042 -v 0.011900 0.010727 0.152014 -v 0.014304 0.010497 0.151427 -v 0.015448 0.008450 0.152599 -v 0.011517 0.007971 0.153656 -v 0.012959 0.009383 0.153360 -v 0.013767 0.008422 0.152871 -v 0.013769 0.008560 0.153513 -v 0.013461 0.007333 0.153103 -v 0.012956 0.009226 0.152700 -v 0.011839 0.008940 0.152761 -v 0.012344 0.007048 0.153163 -v 0.011533 0.007851 0.152992 -v 0.011166 0.006400 0.146152 -v 0.011617 0.005567 0.146324 -v 0.013450 0.005428 0.146360 -v 0.014160 0.006524 0.146321 -v 0.014020 0.007309 0.145960 -v 0.012419 0.008210 0.145962 -v 0.011570 0.007718 0.145872 -v 0.011201 0.007147 0.146189 -v 0.036735 0.057808 0.141576 -v 0.035596 0.057621 0.141616 -v 0.034861 0.058492 0.141431 -v 0.032810 0.057828 0.141568 -v 0.036296 0.056815 0.140023 -v 0.034495 0.058106 0.139751 -v 0.034863 0.059406 0.139476 -v 0.037372 0.057650 0.139851 -v 0.037371 0.059105 0.139539 -v 0.036191 0.059797 0.139391 -v 0.033407 0.060122 0.140801 -v 0.034974 0.057206 0.139946 -v 0.037221 0.055741 0.142012 -v 0.038310 0.056737 0.141571 -v 0.039219 0.058172 0.141496 -v 0.038712 0.060518 0.140995 -v 0.036664 0.061799 0.140724 -v 0.034741 0.061600 0.140765 -v 0.034789 0.055647 0.142029 -v 0.036404 0.059737 0.141166 -v 0.035265 0.059550 0.141206 -v 0.036404 0.059592 0.140482 -v 0.037139 0.058720 0.140667 -v 0.037139 0.058866 0.141351 -v 0.035596 0.057476 0.140931 -v 0.035265 0.059405 0.140521 -v 0.034861 0.058347 0.140746 -v 0.036735 0.057662 0.140892 -v 0.037324 0.056881 0.137165 -v 0.037392 0.058233 0.136430 -v 0.036481 0.059184 0.136680 -v 0.035340 0.059084 0.136703 -v 0.034625 0.058301 0.136517 -v 0.034614 0.057024 0.137138 -v 0.035855 0.056184 0.137009 -v 0.037139 0.005672 0.152658 -v 0.033545 0.003812 0.153047 -v 0.036404 0.004801 0.152843 -v 0.032784 0.005340 0.152725 -v 0.034861 0.006046 0.152579 -v 0.036735 0.006730 0.152433 -v 0.035265 0.004988 0.152804 -v 0.037352 0.005602 0.147721 -v 0.035638 0.006960 0.150626 -v 0.035547 0.004068 0.151240 -v 0.036911 0.004253 0.151195 -v 0.037533 0.005453 0.150946 -v 0.037042 0.002791 0.153266 -v 0.034708 0.006310 0.150763 -v 0.034528 0.004973 0.151042 -v 0.038978 0.004514 0.152900 -v 0.039164 0.006553 0.152468 -v 0.037004 0.006692 0.150693 -v 0.037504 0.008667 0.152018 -v 0.035993 0.008760 0.151769 -v 0.034462 0.008647 0.152018 -v 0.033122 0.007360 0.152296 -v 0.034887 0.003066 0.152970 -v 0.035596 0.006917 0.152394 -v 0.036735 0.006585 0.151749 -v 0.034861 0.005900 0.151894 -v 0.035265 0.004842 0.152119 -v 0.035596 0.006772 0.151709 -v 0.036404 0.004656 0.152159 -v 0.037139 0.005527 0.151973 -v 0.036632 0.003556 0.148505 -v 0.037425 0.004368 0.148333 -v 0.036057 0.006438 0.147891 -v 0.034934 0.005866 0.147566 -v 0.034415 0.004802 0.148235 -v 0.035403 0.003471 0.148187 -v 0.006404 0.006917 0.152394 -v 0.005265 0.006730 0.152433 -v 0.006735 0.004988 0.152804 -v 0.007139 0.006046 0.152579 -v 0.005255 0.003561 0.148066 -v 0.005706 0.007006 0.150610 -v 0.005813 0.004024 0.151246 -v 0.004628 0.006172 0.150793 -v 0.004629 0.004717 0.151100 -v 0.007730 0.003114 0.153189 -v 0.006830 0.004239 0.151204 -v 0.009021 0.004746 0.152853 -v 0.008364 0.008081 0.152142 -v 0.007024 0.006618 0.150698 -v 0.006647 0.008951 0.151959 -v 0.002700 0.006028 0.152579 -v 0.003872 0.003359 0.153142 -v 0.005890 0.002715 0.153284 -v 0.007578 0.005407 0.150976 -v 0.004250 0.008635 0.152004 -v 0.005596 0.004801 0.152843 -v 0.004861 0.005527 0.151973 -v 0.005596 0.004656 0.152159 -v 0.004861 0.005672 0.152658 -v 0.006404 0.006772 0.151709 -v 0.007139 0.005900 0.151894 -v 0.006735 0.004842 0.152119 -v 0.005265 0.006585 0.151749 -v 0.004436 0.004619 0.147864 -v 0.007377 0.004232 0.148061 -v 0.006452 0.003472 0.148522 -v 0.007400 0.005478 0.147768 -v 0.006477 0.006349 0.147911 -v 0.005111 0.006187 0.147943 -v 0.005596 0.059737 0.141166 -v 0.006735 0.059550 0.141206 -v 0.004861 0.058866 0.141351 -v 0.009214 0.059200 0.141276 -v 0.006404 0.057621 0.141616 -v 0.007139 0.058492 0.141431 -v 0.006277 0.056164 0.136894 -v 0.004983 0.056619 0.137227 -v 0.007549 0.057390 0.137057 -v 0.006880 0.059551 0.139446 -v 0.007566 0.058381 0.139689 -v 0.005876 0.059804 0.139390 -v 0.005328 0.056986 0.139989 -v 0.004926 0.059393 0.139480 -v 0.004442 0.058018 0.139771 -v 0.005992 0.061579 0.140516 -v 0.006708 0.055524 0.142057 -v 0.006712 0.056933 0.140002 -v 0.002675 0.058667 0.141387 -v 0.003883 0.061131 0.140867 -v 0.004013 0.056107 0.141924 -v 0.008814 0.057032 0.141737 -v 0.008096 0.061149 0.140863 -v 0.005265 0.057662 0.140892 -v 0.004861 0.058720 0.140667 -v 0.005265 0.057808 0.141576 -v 0.005596 0.059592 0.140482 -v 0.006404 0.057476 0.140931 -v 0.007139 0.058347 0.140746 -v 0.006735 0.059405 0.140521 -v 0.005938 0.059258 0.136664 -v 0.004807 0.058592 0.136463 -v 0.004471 0.057624 0.137012 -v 0.007097 0.058698 0.136434 -v 0.035000 0.001901 0.153235 -v 0.031550 0.001901 0.153235 -v 0.027813 0.001901 0.153235 -v 0.024775 0.000091 0.144722 -v 0.019113 0.000091 0.144722 -v 0.015810 0.001901 0.153235 -v 0.040000 0.031065 0.147036 -v 0.040000 0.035002 0.137301 -v 0.040000 0.031979 0.137944 -v 0.040000 0.028861 0.147504 -v 0.040000 0.010472 0.151413 -v 0.035000 0.060736 0.131831 -v 0.024775 0.060736 0.131831 -v 0.019761 0.062546 0.140344 -v 0.019113 0.060736 0.131831 -v 0.002000 0.055846 0.132871 -v 0.002000 0.004982 0.143682 -v 0.002000 0.010472 0.151413 -v 0.002000 0.010267 0.142559 -v 0.002000 0.027051 0.138991 -v 0.002000 0.028861 0.147504 -v 0.002000 0.035002 0.137301 -v 0.002000 0.045444 0.135082 -v 0.005998 0.059847 0.139366 -v 0.004679 0.058989 0.139482 -v 0.004791 0.057412 0.139819 -v 0.004033 0.060884 0.140695 -v 0.003043 0.059375 0.141015 -v 0.006559 0.055722 0.141795 -v 0.008182 0.056541 0.141621 -v 0.007441 0.057913 0.139710 -v 0.007348 0.059360 0.139639 -v 0.037072 0.059359 0.139404 -v 0.035383 0.059863 0.139482 -v 0.034625 0.058810 0.139520 -v 0.033084 0.059632 0.140964 -v 0.033046 0.058124 0.141284 -v 0.035921 0.056740 0.140074 -v 0.034974 0.055876 0.141762 -v 0.037392 0.057717 0.139754 -v 0.034481 0.005190 0.150917 -v 0.037689 0.005743 0.151042 -v 0.036569 0.006881 0.150572 -v 0.034967 0.006848 0.150799 -v 0.033019 0.005284 0.152516 -v 0.033861 0.003679 0.152857 -v 0.035650 0.003936 0.151382 -v 0.037100 0.004481 0.151068 -v 0.036309 0.002775 0.153039 -v 0.038341 0.003934 0.152801 -v 0.037778 0.008338 0.151865 -v 0.007003 0.004399 0.151092 -v 0.005280 0.004130 0.151168 -v 0.007431 0.006042 0.150734 -v 0.005951 0.007088 0.150639 -v 0.006406 0.008755 0.151778 -v 0.007068 0.003040 0.152992 -v 0.008521 0.004125 0.152761 -v 0.008954 0.006323 0.152295 -v 0.002076 0.005942 0.152376 -v 0.002302 0.005119 0.152551 -v 0.002670 0.002537 0.144202 -v 0.003170 0.003648 0.152864 -v 0.003786 0.001236 0.144478 -v 0.004500 0.000747 0.144582 -v 0.006132 0.060662 0.131847 -v 0.005290 0.060442 0.131894 -v 0.004500 0.061891 0.140484 -v 0.004500 0.060081 0.131970 -v 0.003786 0.061402 0.140588 -v 0.003786 0.059592 0.132074 -v 0.003170 0.060799 0.140716 -v 0.003168 0.058987 0.132203 -v 0.002302 0.057518 0.132515 -v 0.002076 0.056695 0.132690 -v 0.002076 0.058505 0.141203 -v 0.035000 0.000091 0.144722 -v 0.035868 0.000166 0.144706 -v 0.035868 0.001975 0.153219 -v 0.038214 0.001236 0.144478 -v 0.038214 0.003045 0.152992 -v 0.038830 0.003648 0.152864 -v 0.039330 0.004346 0.152715 -v 0.039698 0.005119 0.152551 -v 0.040000 0.004982 0.143682 -v 0.040000 0.006792 0.152195 -v 0.040000 0.057655 0.141384 -v 0.039698 0.057518 0.132515 -v 0.037500 0.061891 0.140484 -v 0.036710 0.062251 0.140407 -v 0.035868 0.060662 0.131847 -v 0.019761 0.036686 0.145841 -v 0.008930 0.036356 0.144288 -v 0.019112 0.052545 0.140847 -v 0.016213 0.052545 0.140847 -v 0.023100 0.011450 0.151205 -v 0.008452 0.011458 0.151203 -v 0.010113 0.011120 0.149652 -v 0.008930 0.011120 0.149652 -v 0.008000 0.011651 0.149539 -v 0.008000 0.021678 0.149031 -v 0.025370 0.027883 0.147712 -v 0.024038 0.027883 0.147712 -v 0.022163 0.027883 0.147712 -v 0.010113 0.027883 0.147712 -v 0.026300 0.021678 0.149031 -v 0.026300 0.026643 0.146353 -v 0.026300 0.012360 0.151012 -v 0.022110 0.052419 0.140874 -v 0.022550 0.037596 0.145648 -v 0.022085 0.036808 0.145815 -v 0.008506 0.036436 0.144272 -v 0.008000 0.026973 0.147906 -v 0.008221 0.027141 0.146017 -v 0.008401 0.027700 0.147751 -v 0.008675 0.011152 0.149645 -v 0.008000 0.012360 0.151012 -v 0.012804 0.040641 0.140657 -v 0.011590 0.040434 0.139682 -v 0.013587 0.041737 0.142267 -v 0.013590 0.045405 0.140702 -v 0.012939 0.046640 0.139562 -v 0.016004 0.050172 0.143274 -v 0.016012 0.050421 0.143252 -v 0.014037 0.050420 0.143242 -v 0.011991 0.042986 0.146916 -v 0.012140 0.043510 0.146466 -v 0.013570 0.043813 0.142515 -v 0.012780 0.044507 0.144185 -v 0.013176 0.043915 0.141399 -v 0.011592 0.043391 0.138937 -v 0.012122 0.044877 0.146361 -v 0.012938 0.044653 0.139983 -v 0.012140 0.046130 0.147046 -v 0.012099 0.045672 0.145872 -v 0.012140 0.045729 0.147132 -v 0.013105 0.045719 0.140114 -v 0.012112 0.046774 0.145674 -v 0.011913 0.047124 0.146835 -v 0.012140 0.047486 0.145621 -v 0.012140 0.047887 0.145536 -v 0.011590 0.048815 0.144905 -v 0.012140 0.048479 0.145410 -v 0.012140 0.048880 0.145325 -v 0.012140 0.048711 0.146498 -v 0.013579 0.044965 0.142703 -v 0.013005 0.044354 0.139519 -v 0.012729 0.044161 0.139869 -v 0.013030 0.047356 0.142924 -v 0.012697 0.047076 0.143809 -v 0.013655 0.046698 0.141109 -v 0.013171 0.046331 0.140309 -v 0.013188 0.041731 0.143101 -v 0.012870 0.045195 0.139846 -v 0.013039 0.047232 0.138944 -v 0.013572 0.048019 0.142090 -v 0.012783 0.044641 0.144878 -v 0.012729 0.043167 0.140082 -v 0.012781 0.041525 0.144819 -v 0.013593 0.041191 0.143453 -v 0.012869 0.040226 0.140902 -v 0.013136 0.042803 0.141057 -v 0.012780 0.043514 0.144398 -v 0.013590 0.042588 0.142159 -v 0.014036 0.039511 0.145539 -v 0.016011 0.039513 0.145548 -v 0.014028 0.050173 0.143283 -v 0.016020 0.050408 0.145193 -v 0.014020 0.050649 0.145107 -v 0.018365 0.041263 0.142724 -v 0.017525 0.040486 0.139066 -v 0.018400 0.042622 0.149091 -v 0.017116 0.046655 0.137754 -v 0.018400 0.048774 0.147783 -v 0.013186 0.041064 0.142647 -v 0.013129 0.040407 0.140679 -v 0.011590 0.042155 0.147891 -v 0.012065 0.041945 0.146908 -v 0.012130 0.041681 0.147628 -v 0.013106 0.041744 0.140959 -v 0.012957 0.042411 0.145076 -v 0.012780 0.042520 0.144608 -v 0.012140 0.042703 0.147227 -v 0.011590 0.043846 0.145961 -v 0.013072 0.043528 0.144505 -v 0.012868 0.042359 0.139837 -v 0.012076 0.043936 0.146503 -v 0.011694 0.043845 0.147532 -v 0.013057 0.043424 0.139807 -v 0.012140 0.044735 0.147343 -v 0.012975 0.045424 0.143615 -v 0.011590 0.046130 0.147046 -v 0.011590 0.045729 0.147132 -v 0.011590 0.046827 0.145328 -v 0.012780 0.046495 0.143763 -v 0.013070 0.046331 0.143965 -v 0.012140 0.046723 0.146920 -v 0.012779 0.047628 0.144250 -v 0.011590 0.048301 0.145070 -v 0.011595 0.047889 0.145544 -v 0.012140 0.048118 0.146624 -v 0.011590 0.048118 0.146624 -v 0.012140 0.047717 0.146709 -v 0.012569 0.048556 0.143686 -v 0.013250 0.047985 0.141002 -v 0.012140 0.049112 0.146413 -v 0.011590 0.044173 0.138372 -v 0.011590 0.043964 0.138943 -v 0.013226 0.044832 0.143028 -v 0.011590 0.046395 0.138406 -v 0.011591 0.046254 0.137898 -v 0.011590 0.047434 0.145383 -v 0.011590 0.045699 0.138607 -v 0.011590 0.040979 0.139557 -v 0.012834 0.041192 0.140564 -v 0.011602 0.042462 0.146535 -v 0.011590 0.045061 0.138205 -v 0.011590 0.044958 0.138732 -v 0.013186 0.045615 0.141827 -v 0.012697 0.046082 0.144021 -v 0.011590 0.047367 0.138091 -v 0.011590 0.047054 0.137744 -v 0.013086 0.047919 0.142888 -v 0.012870 0.047182 0.139423 -v 0.011590 0.046945 0.138309 -v 0.011590 0.042655 0.139238 -v 0.011592 0.044436 0.145969 -v 0.013239 0.043752 0.142831 -v 0.013166 0.040826 0.143724 -v 0.011590 0.042322 0.138805 -v 0.013171 0.042357 0.141154 -v 0.012697 0.043100 0.144655 -v 0.011590 0.041761 0.139444 -v 0.016003 0.039272 0.145612 -v 0.014020 0.039771 0.149556 -v 0.014028 0.039275 0.145622 -v 0.014020 0.040075 0.147388 -v 0.016020 0.039821 0.147409 -v 0.014020 0.039821 0.147409 -v 0.020770 0.039827 0.152394 -v 0.019170 0.052670 0.149664 -v 0.014020 0.050408 0.145193 -v 0.016020 0.051475 0.146900 -v 0.016020 0.050649 0.145107 -v 0.017435 0.047427 0.141414 -v 0.017115 0.050184 0.140828 -v 0.017115 0.047805 0.141333 -v 0.021660 0.042622 0.149091 -v 0.015655 0.049094 0.135702 -v 0.015655 0.037357 0.138197 -v 0.017115 0.049406 0.137169 -v 0.021660 0.048774 0.147783 -v 0.020045 0.048866 0.148070 -v 0.017116 0.041250 0.142727 -v 0.018365 0.038446 0.143323 -v 0.011590 0.041754 0.147977 -v 0.011590 0.044735 0.147343 -v 0.011590 0.049171 0.141323 -v 0.011590 0.048025 0.135929 -v 0.011591 0.048892 0.145494 -v 0.011590 0.048711 0.146498 -v 0.011590 0.049112 0.146413 -v 0.011590 0.046235 0.136310 -v 0.011590 0.047717 0.146709 -v 0.011590 0.047381 0.141703 -v 0.011590 0.045241 0.136521 -v 0.011590 0.046723 0.146920 -v 0.011590 0.044247 0.136732 -v 0.011590 0.044407 0.138828 -v 0.011590 0.046403 0.145426 -v 0.011590 0.043253 0.136944 -v 0.011590 0.044848 0.145752 -v 0.011590 0.045136 0.147258 -v 0.011590 0.045406 0.145640 -v 0.011590 0.041266 0.137366 -v 0.011590 0.046442 0.148278 -v 0.011590 0.045813 0.145550 -v 0.011590 0.051471 0.146885 -v 0.011590 0.040272 0.137577 -v 0.011594 0.041081 0.138882 -v 0.011590 0.041418 0.142971 -v 0.011590 0.043149 0.147680 -v 0.011590 0.042852 0.146173 -v 0.011590 0.042748 0.147765 -v 0.011590 0.040110 0.139216 -v 0.011590 0.039985 0.139768 -v 0.011590 0.041463 0.146577 -v 0.011590 0.043427 0.146084 -v 0.011590 0.037357 0.138197 -v 0.017115 0.038446 0.143323 -v 0.016020 0.040075 0.147388 -v 0.011495 0.039819 0.149783 -v 0.019170 0.039827 0.152394 -v 0.019170 0.042370 0.151853 -v 0.020770 0.042370 0.151853 -v 0.020770 0.052670 0.149664 -v 0.019170 0.050127 0.150204 -v 0.020770 0.050127 0.150204 -v 0.011590 0.049094 0.135702 -v 0.016020 0.051323 0.146185 -v 0.018365 0.050184 0.140828 -v 0.011590 0.050241 0.141095 -v 0.014020 0.051323 0.146185 -v 0.014020 0.051475 0.146900 -v 0.011495 0.051557 0.147288 -v 0.018365 0.047425 0.141414 -v 0.021725 0.043740 0.149159 -v 0.021725 0.042653 0.149390 -v 0.018365 0.043070 0.151346 -v 0.018385 0.042592 0.149097 -v 0.020045 0.042655 0.149390 -v 0.021660 0.040490 0.139065 -v 0.021660 0.046643 0.137757 -v 0.017115 0.037668 0.139664 -v 0.017115 0.040170 0.139133 -v 0.018400 0.046643 0.137757 -v 0.015655 0.037668 0.139664 -v 0.015655 0.049406 0.137169 -v 0.018400 0.040490 0.139065 -v 0.018365 0.049282 0.150026 -v 0.021725 0.048867 0.148069 -v 0.018400 0.048807 0.147791 -v 0.020045 0.047721 0.148313 -v 0.020045 0.043740 0.149159 -v 0.011590 0.038503 0.143590 -v 0.011590 0.039800 0.149690 -v 0.014020 0.039619 0.148841 -v 0.011495 0.040278 0.151940 -v 0.016020 0.039771 0.149556 -v 0.016020 0.039619 0.148841 -v 0.021103 0.039453 0.152160 -v 0.021091 0.052926 0.149297 -v 0.018859 0.052916 0.149303 -v 0.018864 0.049761 0.149976 -v 0.021103 0.049761 0.149970 -v 0.021115 0.039500 0.152463 -v 0.011145 0.040008 0.152355 -v 0.008775 0.042336 0.151860 -v 0.018855 0.039500 0.152463 -v 0.020050 0.043086 0.151470 -v 0.021725 0.043887 0.151531 -v 0.020056 0.049313 0.150150 -v 0.020057 0.048208 0.150524 -v 0.011145 0.052431 0.149715 -v 0.021775 0.053304 0.149529 -v 0.021115 0.049819 0.150270 -v 0.008775 0.050161 0.150197 -v 0.011145 0.050161 0.150197 -v 0.011495 0.052016 0.149445 -v 0.018365 0.052016 0.149445 -v 0.018715 0.052431 0.149715 -v 0.018819 0.049813 0.150353 -v 0.021725 0.047721 0.148313 -v 0.021725 0.040461 0.139071 -v 0.021725 0.048552 0.150539 -v 0.021725 0.046672 0.137751 -v 0.021725 0.048137 0.150270 -v 0.021725 0.044156 0.151116 -v 0.020066 0.044199 0.151365 -v 0.018365 0.040278 0.151940 -v 0.018715 0.040008 0.152355 -v 0.011145 0.042336 0.151860 -v 0.021090 0.042613 0.151491 -v 0.021115 0.042679 0.151788 -v 0.018863 0.039447 0.152166 -v 0.018860 0.042608 0.151497 -v 0.018812 0.042722 0.151849 -v 0.018855 0.052998 0.149594 -v 0.021115 0.052998 0.149594 -v 0.009375 0.038320 0.152203 -v 0.009375 0.038913 0.152588 -v 0.008448 0.038772 0.152107 -v 0.008775 0.039239 0.152519 -v 0.008780 0.053585 0.149469 -v 0.021775 0.039500 0.152463 -v 0.021758 0.038442 0.152181 -v 0.021175 0.038320 0.152203 -v 0.021175 0.038913 0.152588 -v 0.021175 0.053585 0.149469 -v 0.008275 0.039396 0.151974 -v 0.009375 0.037390 0.147902 -v 0.008900 0.036694 0.144217 -v 0.008260 0.038481 0.147670 -v 0.009375 0.053970 0.148876 -v 0.008762 0.053834 0.148904 -v 0.008275 0.053174 0.149046 -v 0.022275 0.039396 0.151974 -v 0.022228 0.039056 0.152039 -v 0.022275 0.052894 0.149105 -v 0.021842 0.053808 0.148918 -v 0.021175 0.053970 0.148876 -v 0.021175 0.053070 0.144569 -v 0.021175 0.037390 0.147902 -v 0.009012 0.038371 0.152190 -v 0.008260 0.051979 0.144801 -v 0.022290 0.051200 0.141133 -v 0.021175 0.036610 0.144234 -v 0.008430 0.037099 0.144243 -v 0.008260 0.051200 0.141133 -v 0.008260 0.037701 0.144002 -v 0.021175 0.052290 0.140901 -v 0.009375 0.053070 0.144569 -v 0.008851 0.052222 0.141017 -v 0.022290 0.038481 0.147670 -v 0.022290 0.051979 0.144801 -v 0.018000 0.019072 0.152542 -v 0.011551 0.025368 0.149589 -v 0.013766 0.017915 0.148168 -v 0.013759 0.019887 0.147736 -v 0.013463 0.022233 0.147130 -v 0.013469 0.023216 0.146943 -v 0.010996 0.024747 0.149721 -v 0.011505 0.024931 0.149982 -v 0.011074 0.014800 0.151853 -v 0.011489 0.014512 0.151897 -v 0.018000 0.015381 0.153347 -v 0.018000 0.025163 0.151268 -v 0.018649 0.013905 0.153136 -v 0.021963 0.022233 0.147130 -v 0.021969 0.023216 0.146943 -v 0.021963 0.019788 0.147650 -v 0.022261 0.019882 0.147740 -v 0.021963 0.017832 0.148066 -v 0.021963 0.015386 0.148585 -v 0.022267 0.015469 0.148688 -v 0.021324 0.014868 0.146147 -v 0.020005 0.024931 0.149982 -v 0.015652 0.026440 0.150548 -v 0.015650 0.014248 0.152346 -v 0.015208 0.023227 0.146924 -v 0.014721 0.023337 0.147872 -v 0.015032 0.023334 0.147847 -v 0.015072 0.016700 0.150016 -v 0.015043 0.017449 0.149128 -v 0.013577 0.023124 0.146507 -v 0.012824 0.022845 0.145198 -v 0.013577 0.020678 0.147027 -v 0.012824 0.020248 0.145003 -v 0.012824 0.018902 0.148290 -v 0.013469 0.018815 0.147879 -v 0.013668 0.018774 0.147689 -v 0.013668 0.016329 0.148209 -v 0.012824 0.015998 0.146654 -v 0.012824 0.013738 0.148261 -v 0.012604 0.015069 0.152078 -v 0.012604 0.024932 0.149982 -v 0.013469 0.016369 0.148399 -v 0.012824 0.015020 0.146862 -v 0.013463 0.015386 0.148585 -v 0.012824 0.014868 0.146147 -v 0.013767 0.015469 0.148688 -v 0.013463 0.017832 0.148066 -v 0.013469 0.020771 0.147463 -v 0.013463 0.019788 0.147650 -v 0.012824 0.020400 0.145718 -v 0.012824 0.020128 0.148029 -v 0.013759 0.022333 0.147217 -v 0.010996 0.023103 0.141987 -v 0.011124 0.025162 0.149634 -v 0.011076 0.023462 0.141911 -v 0.011524 0.023724 0.141855 -v 0.011503 0.015069 0.152078 -v 0.010996 0.015132 0.151765 -v 0.018650 0.014270 0.152445 -v 0.018649 0.026427 0.150479 -v 0.019184 0.015347 0.148476 -v 0.019184 0.017325 0.148056 -v 0.022697 0.024706 0.143594 -v 0.022168 0.016329 0.148209 -v 0.021969 0.016369 0.148399 -v 0.021969 0.018815 0.147879 -v 0.022168 0.018774 0.147689 -v 0.022133 0.020710 0.147178 -v 0.021969 0.020771 0.147463 -v 0.021324 0.022386 0.147846 -v 0.022077 0.023124 0.146507 -v 0.021324 0.013738 0.148261 -v 0.021324 0.014498 0.151837 -v 0.021104 0.015069 0.152078 -v 0.021104 0.024932 0.149982 -v 0.021324 0.022845 0.145198 -v 0.022259 0.022333 0.147217 -v 0.021324 0.020400 0.145718 -v 0.021324 0.017466 0.146342 -v 0.022266 0.017915 0.148168 -v 0.021324 0.015508 0.149159 -v 0.019496 0.023336 0.141937 -v 0.019496 0.024884 0.149692 -v 0.019707 0.025222 0.149637 -v 0.020020 0.025368 0.149589 -v 0.020003 0.015069 0.152078 -v 0.020020 0.012867 0.144163 -v 0.019945 0.014513 0.151900 -v 0.019496 0.021682 0.148652 -v 0.019496 0.015514 0.149009 -v 0.013336 0.013031 0.146948 -v 0.010502 0.021201 0.147363 -v 0.015504 0.026080 0.149578 -v 0.015650 0.025790 0.149892 -v 0.015217 0.017339 0.148180 -v 0.015228 0.015347 0.148476 -v 0.015038 0.015654 0.149458 -v 0.014844 0.016480 0.148941 -v 0.014817 0.021554 0.148244 -v 0.015503 0.020264 0.144111 -v 0.015504 0.022835 0.143552 -v 0.015275 0.022642 0.148970 -v 0.015504 0.021833 0.149134 -v 0.012824 0.020492 0.142542 -v 0.012824 0.015846 0.145939 -v 0.012824 0.018292 0.145419 -v 0.012824 0.018444 0.146134 -v 0.012824 0.017466 0.146342 -v 0.012824 0.017312 0.145625 -v 0.012824 0.019422 0.145926 -v 0.012824 0.019269 0.145210 -v 0.012824 0.021867 0.145406 -v 0.012824 0.021713 0.144690 -v 0.012824 0.014498 0.151837 -v 0.012824 0.015508 0.149159 -v 0.012824 0.016457 0.148809 -v 0.012824 0.016517 0.149094 -v 0.012824 0.017954 0.148641 -v 0.012824 0.021017 0.150424 -v 0.012824 0.019940 0.148366 -v 0.012824 0.018985 0.148565 -v 0.012824 0.022386 0.147846 -v 0.012824 0.021633 0.147905 -v 0.012824 0.025360 0.149550 -v 0.012824 0.023352 0.147581 -v 0.012824 0.022696 0.144480 -v 0.023829 0.023305 0.146912 -v 0.023829 0.021199 0.147357 -v 0.023647 0.023500 0.148499 -v 0.023829 0.015300 0.148610 -v 0.021652 0.013129 0.145639 -v 0.018908 0.014400 0.145450 -v 0.018921 0.015973 0.150476 -v 0.018908 0.017345 0.148229 -v 0.019496 0.017492 0.149501 -v 0.019496 0.023275 0.147337 -v 0.018908 0.023233 0.146977 -v 0.019491 0.023359 0.148065 -v 0.018910 0.022836 0.143579 -v 0.019257 0.021449 0.147909 -v 0.018908 0.021773 0.148943 -v 0.018908 0.020258 0.144100 -v 0.018908 0.021287 0.147391 -v 0.019496 0.021395 0.147736 -v 0.019135 0.022642 0.148970 -v 0.022697 0.012669 0.146153 -v 0.023434 0.024699 0.143595 -v 0.023434 0.012706 0.146144 -v 0.021324 0.017312 0.145625 -v 0.021324 0.015846 0.145939 -v 0.021324 0.015998 0.146654 -v 0.021324 0.015020 0.146862 -v 0.021324 0.018292 0.145419 -v 0.021324 0.018444 0.146134 -v 0.021324 0.019269 0.145210 -v 0.021324 0.020248 0.145003 -v 0.021324 0.019422 0.145926 -v 0.021324 0.022693 0.144483 -v 0.021324 0.021867 0.145406 -v 0.021324 0.021713 0.144690 -v 0.021324 0.016457 0.148810 -v 0.021324 0.016517 0.149094 -v 0.021324 0.017954 0.148641 -v 0.021324 0.020128 0.148029 -v 0.021324 0.021017 0.150424 -v 0.021324 0.019940 0.148366 -v 0.021324 0.018985 0.148565 -v 0.021324 0.018902 0.148290 -v 0.021324 0.021633 0.147905 -v 0.021324 0.023352 0.147581 -v 0.021324 0.025360 0.149550 -v 0.019496 0.014940 0.151806 -v 0.019493 0.015767 0.149817 -v 0.019496 0.017389 0.148610 -v 0.012123 0.013016 0.146806 -v 0.013616 0.013424 0.150144 -v 0.012950 0.013107 0.145650 -v 0.013329 0.012742 0.146935 -v 0.010718 0.013804 0.151935 -v 0.010318 0.013922 0.151827 -v 0.010265 0.012409 0.144261 -v 0.010502 0.017411 0.148162 -v 0.010509 0.017636 0.149996 -v 0.010814 0.017497 0.148859 -v 0.010502 0.015302 0.148617 -v 0.010671 0.015572 0.149500 -v 0.010986 0.015572 0.149500 -v 0.010793 0.021406 0.148032 -v 0.010684 0.021668 0.148889 -v 0.010502 0.023305 0.146909 -v 0.010265 0.023328 0.147103 -v 0.010265 0.023504 0.148531 -v 0.010674 0.023412 0.147786 -v 0.010916 0.023384 0.147556 -v 0.010288 0.015895 0.150559 -v 0.012117 0.024966 0.144337 -v 0.012648 0.024012 0.143370 -v 0.011830 0.025648 0.147544 -v 0.013609 0.025631 0.147466 -v 0.013280 0.024517 0.143856 -v 0.012100 0.024742 0.144582 -v 0.015504 0.016750 0.150215 -v 0.015504 0.015399 0.148642 -v 0.015504 0.014400 0.145450 -v 0.015504 0.016959 0.144906 -v 0.015504 0.021769 0.148930 -v 0.015504 0.017531 0.149831 -v 0.015504 0.015881 0.150182 -v 0.015504 0.023432 0.148686 -v 0.015504 0.023233 0.146977 -v 0.015504 0.017345 0.148229 -v 0.015504 0.021287 0.147391 -v 0.012824 0.023724 0.141855 -v 0.010996 0.013488 0.144031 -v 0.012824 0.012867 0.144163 -v 0.011121 0.013088 0.144116 -v 0.011520 0.012867 0.144163 -v 0.010467 0.012184 0.144308 -v 0.010265 0.024177 0.141759 -v 0.010460 0.024407 0.141710 -v 0.021943 0.024621 0.144189 -v 0.020751 0.024964 0.144328 -v 0.021063 0.024067 0.143299 -v 0.020744 0.024709 0.144465 -v 0.022245 0.025637 0.147499 -v 0.021962 0.024964 0.144328 -v 0.024065 0.024192 0.141756 -v 0.024063 0.025637 0.149407 -v 0.023541 0.023392 0.147622 -v 0.024065 0.023504 0.148531 -v 0.024063 0.021961 0.149207 -v 0.023658 0.021457 0.148200 -v 0.023327 0.021473 0.148250 -v 0.024062 0.016053 0.150501 -v 0.023658 0.015558 0.149454 -v 0.023337 0.015564 0.149472 -v 0.023829 0.017411 0.148165 -v 0.023541 0.017498 0.148875 -v 0.023647 0.017607 0.149754 -v 0.024065 0.017610 0.149784 -v 0.021979 0.013043 0.147068 -v 0.020762 0.013011 0.146735 -v 0.018908 0.017543 0.149937 -v 0.018908 0.021833 0.149134 -v 0.018908 0.026049 0.149433 -v 0.018907 0.023427 0.148644 -v 0.018908 0.016959 0.144906 -v 0.018908 0.015881 0.150182 -v 0.018908 0.015417 0.148701 -v 0.022697 0.024321 0.141729 -v 0.021324 0.017741 0.143127 -v 0.021324 0.012867 0.144163 -v 0.024065 0.012324 0.144278 -v 0.021324 0.023724 0.141855 -v 0.018908 0.024407 0.141710 -v 0.023434 0.024321 0.141729 -v 0.019496 0.013359 0.144058 -v 0.019989 0.023724 0.141855 -v 0.023434 0.012271 0.144290 -v 0.018908 0.012184 0.144308 -v 0.022697 0.012271 0.144290 -v 0.019707 0.013017 0.144131 -v 0.024065 0.014218 0.151816 -v 0.015504 0.012184 0.144308 -v 0.012117 0.012742 0.146935 -v 0.011831 0.013422 0.150131 -v 0.010265 0.022975 0.144228 -v 0.010265 0.014346 0.151876 -v 0.010265 0.014511 0.146027 -v 0.010266 0.020411 0.144778 -v 0.010265 0.017080 0.145475 -v 0.010265 0.021253 0.147531 -v 0.010265 0.017433 0.148343 -v 0.010265 0.015359 0.148800 -v 0.010265 0.015778 0.150173 -v 0.010265 0.017620 0.149857 -v 0.010265 0.021713 0.149037 -v 0.010301 0.023559 0.148976 -v 0.015504 0.024407 0.141710 -v 0.013329 0.024966 0.144337 -v 0.023442 0.026049 0.149434 -v 0.023760 0.024407 0.141710 -v 0.020467 0.025640 0.147509 -v 0.024065 0.017433 0.148343 -v 0.024065 0.022976 0.144235 -v 0.024065 0.014513 0.146034 -v 0.024065 0.015778 0.150173 -v 0.024065 0.015357 0.148796 -v 0.024065 0.023328 0.147099 -v 0.024065 0.021253 0.147531 -v 0.024065 0.017083 0.145488 -v 0.024065 0.020412 0.144781 -v 0.023760 0.012184 0.144308 -v 0.020751 0.012740 0.146926 -v 0.021962 0.012740 0.146926 -v 0.023442 0.013826 0.152032 -v 0.020467 0.013415 0.150098 -v 0.022246 0.013416 0.150104 -v 0.018908 0.013825 0.152031 -v 0.010219 0.013766 0.152452 -v 0.010265 0.025570 0.149458 -v 0.010150 0.014583 0.152236 -v 0.010341 0.025893 0.149282 -v 0.010152 0.026276 0.149790 -v 0.010570 0.026013 0.149263 -v 0.018792 0.026274 0.149767 -v 0.023944 0.025938 0.149273 -v 0.024065 0.021713 0.149037 -v 0.024148 0.026269 0.149751 -v 0.023950 0.013870 0.151838 -v 0.018814 0.013756 0.152407 -v 0.024148 0.013755 0.152418 -v 0.015504 0.013858 0.152184 -v 0.018650 0.025812 0.149992 -v 0.024151 0.026150 0.150533 -v 0.024150 0.019989 0.151039 -v 0.018142 0.013467 0.153753 -v 0.015650 0.014366 0.152898 -v 0.015747 0.013860 0.153399 -v 0.016034 0.026890 0.150852 -v 0.015336 0.013767 0.152485 -v 0.010149 0.013907 0.153143 -v 0.009641 0.013546 0.153736 -v 0.009975 0.014456 0.153324 -v 0.009601 0.026948 0.150888 -v 0.009825 0.026024 0.150993 -v 0.010150 0.026426 0.150476 -v 0.018181 0.027064 0.150863 -v 0.018485 0.020226 0.152088 -v 0.021312 0.026751 0.150796 -v 0.024678 0.013581 0.153728 -v 0.024616 0.027027 0.150871 -v 0.024334 0.020230 0.152108 -v 0.024151 0.013915 0.153165 -v 0.018896 0.013756 0.153557 -v 0.008925 0.012189 0.153361 -v 0.008925 0.012248 0.153519 -v 0.008439 0.012479 0.153760 -v 0.008598 0.027891 0.150605 -v 0.008925 0.028084 0.149982 -v 0.025853 0.028003 0.150456 -v 0.026002 0.027650 0.150270 -v 0.016300 0.015381 0.153347 -v 0.016300 0.025163 0.151268 -v 0.025471 0.027691 0.150729 -v 0.025476 0.012847 0.153885 -v 0.025375 0.012189 0.153361 -v 0.026025 0.012825 0.153226 -v 0.025976 0.012626 0.153555 -v 0.025575 0.012245 0.153521 -v 0.008925 0.012384 0.153700 -v 0.025375 0.012384 0.153700 -v 0.008925 0.012572 0.153822 -v 0.008275 0.027449 0.150118 -v 0.008292 0.012718 0.153411 -v 0.008299 0.027484 0.150281 -v 0.008398 0.027913 0.150412 -v 0.008812 0.012859 0.153882 -v 0.008275 0.026440 0.145374 -v 0.025375 0.028084 0.149982 -v 0.025625 0.028089 0.150240 -v 0.008616 0.028075 0.150309 -v 0.025727 0.027908 0.150581 -v 0.008861 0.027698 0.150728 -v 0.025756 0.026999 0.145273 -v 0.026025 0.027449 0.150118 -v 0.025748 0.012567 0.153825 -v 0.008925 0.011181 0.148617 -v 0.008275 0.011817 0.148482 -v 0.008275 0.012825 0.153226 -v 0.008925 0.027076 0.145238 -v 0.025375 0.027076 0.145238 -v 0.026025 0.011817 0.148482 -v 0.026150 0.011866 0.148471 -v 0.026025 0.026440 0.145374 -v 0.025300 0.027223 0.145207 -v 0.008540 0.026988 0.145279 -v 0.008150 0.026391 0.145384 -v 0.008150 0.011866 0.148471 -v 0.025740 0.011284 0.148624 -v 0.025375 0.011181 0.148617 -v 0.025300 0.011034 0.148648 -v 0.009000 0.011034 0.148648 -v 0.008150 0.012074 0.149450 -v 0.008150 0.026599 0.146362 -v 0.009000 0.027223 0.145207 -v 0.009000 0.027431 0.146185 -v 0.026150 0.026599 0.146362 -v 0.026098 0.027121 0.146026 -v 0.025300 0.027431 0.146185 -v 0.026150 0.026391 0.145384 -v 0.026150 0.012074 0.149450 -v 0.009000 0.011242 0.149626 -v 0.032038 0.014776 0.160530 -v 0.030060 0.015862 0.160299 -v 0.029327 0.017962 0.159853 -v 0.029495 0.018852 0.159664 -v 0.029378 0.018413 0.159757 -v 0.030946 0.020557 0.159301 -v 0.030560 0.020307 0.159354 -v 0.030214 0.020005 0.159419 -v 0.031366 0.020750 0.159260 -v 0.032732 0.020946 0.159218 -v 0.034440 0.020307 0.159354 -v 0.034054 0.020557 0.159301 -v 0.033634 0.020750 0.159260 -v 0.035324 0.019269 0.159575 -v 0.035082 0.019656 0.159493 -v 0.035656 0.017509 0.159949 -v 0.035673 0.017962 0.159853 -v 0.034619 0.015536 0.160368 -v 0.032962 0.014776 0.160530 -v 0.032500 0.012373 0.149386 -v 0.032038 0.012406 0.149379 -v 0.031585 0.014875 0.160509 -v 0.031152 0.012667 0.149324 -v 0.031152 0.015037 0.160474 -v 0.030748 0.015259 0.160427 -v 0.030381 0.015536 0.160368 -v 0.030381 0.013166 0.149217 -v 0.029790 0.016231 0.160221 -v 0.029578 0.014264 0.148984 -v 0.029578 0.016634 0.160135 -v 0.029428 0.017063 0.160044 -v 0.029344 0.017509 0.159949 -v 0.029327 0.015592 0.148702 -v 0.029378 0.016043 0.148606 -v 0.029495 0.016482 0.148513 -v 0.029676 0.016899 0.148424 -v 0.029676 0.019269 0.159575 -v 0.029918 0.019656 0.159493 -v 0.029918 0.017286 0.148342 -v 0.030946 0.018187 0.148150 -v 0.031366 0.018379 0.148109 -v 0.031810 0.020880 0.159232 -v 0.032268 0.020946 0.159218 -v 0.032268 0.018576 0.148067 -v 0.033190 0.020880 0.159232 -v 0.033634 0.018379 0.148109 -v 0.034054 0.018187 0.148150 -v 0.034786 0.020005 0.159419 -v 0.035324 0.016899 0.148424 -v 0.035505 0.018852 0.159664 -v 0.035505 0.016482 0.148513 -v 0.035622 0.018413 0.159757 -v 0.035673 0.015592 0.148702 -v 0.035572 0.017063 0.160044 -v 0.035422 0.014264 0.148984 -v 0.035422 0.016634 0.160135 -v 0.035210 0.016231 0.160221 -v 0.035210 0.013861 0.149070 -v 0.034940 0.013492 0.149148 -v 0.034940 0.015862 0.160299 -v 0.034619 0.013166 0.149217 -v 0.034252 0.015259 0.160427 -v 0.033848 0.015037 0.160474 -v 0.033848 0.012667 0.149324 -v 0.033415 0.014875 0.160509 -v 0.032962 0.012406 0.149379 -v 0.032500 0.014743 0.160537 -v 0.036500 0.017738 0.148246 -v 0.032500 0.019290 0.144440 -v 0.036500 0.012513 0.145880 -v 0.036500 0.013220 0.149206 -v 0.028500 0.017031 0.144920 -v 0.032500 0.010254 0.146360 -v 0.036500 0.017031 0.144920 -v 0.028500 0.012513 0.145880 -v 0.031810 0.018510 0.148082 -v 0.032732 0.018576 0.148067 -v 0.032500 0.010961 0.149686 -v 0.033415 0.012505 0.149358 -v 0.032500 0.019997 0.147766 -v 0.033190 0.018510 0.148082 -v 0.035656 0.015139 0.148798 -v 0.035572 0.014693 0.148893 -v 0.034252 0.012889 0.149276 -v 0.030060 0.013492 0.149148 -v 0.029790 0.013861 0.149070 -v 0.029428 0.014693 0.148893 -v 0.029344 0.015139 0.148798 -v 0.030214 0.017634 0.148268 -v 0.034440 0.017937 0.148203 -v 0.034786 0.017634 0.148268 -v 0.035082 0.017286 0.148342 -v 0.031585 0.012505 0.149358 -v 0.030748 0.012889 0.149276 -v 0.028500 0.013220 0.149206 -v 0.030560 0.017937 0.148203 -v 0.028500 0.017738 0.148246 -v 0.035622 0.016043 0.148606 -v 0.032500 0.026481 0.158042 -v 0.032962 0.026514 0.158035 -v 0.030060 0.027600 0.157804 -v 0.030748 0.026997 0.157932 -v 0.029428 0.028801 0.157549 -v 0.029578 0.028372 0.157640 -v 0.029790 0.027969 0.157726 -v 0.029378 0.030151 0.157262 -v 0.029495 0.030589 0.157169 -v 0.030946 0.032295 0.156806 -v 0.030214 0.031742 0.156924 -v 0.031810 0.032618 0.156737 -v 0.031366 0.032487 0.156765 -v 0.033190 0.032618 0.156737 -v 0.034440 0.032045 0.156859 -v 0.034054 0.032295 0.156806 -v 0.035082 0.031394 0.156998 -v 0.035673 0.029700 0.157358 -v 0.035505 0.030589 0.157169 -v 0.035422 0.028372 0.157640 -v 0.029344 0.029247 0.157454 -v 0.035656 0.029247 0.157454 -v 0.034940 0.027600 0.157804 -v 0.035210 0.027969 0.157726 -v 0.032038 0.024144 0.146884 -v 0.031585 0.026613 0.158014 -v 0.031585 0.024243 0.146863 -v 0.031152 0.026775 0.157979 -v 0.030748 0.024626 0.146781 -v 0.030381 0.027274 0.157873 -v 0.030381 0.024904 0.146723 -v 0.029790 0.025599 0.146575 -v 0.029327 0.029700 0.157358 -v 0.029676 0.031007 0.157080 -v 0.029676 0.028637 0.145929 -v 0.029918 0.031394 0.156998 -v 0.030560 0.032045 0.156859 -v 0.030560 0.029675 0.145708 -v 0.030946 0.029925 0.145655 -v 0.032268 0.030314 0.145573 -v 0.032268 0.032684 0.156723 -v 0.032732 0.032684 0.156723 -v 0.032732 0.030314 0.145573 -v 0.033634 0.032487 0.156765 -v 0.033634 0.030117 0.145614 -v 0.034440 0.029675 0.145708 -v 0.034786 0.031742 0.156924 -v 0.035082 0.029024 0.145847 -v 0.035324 0.031007 0.157080 -v 0.035622 0.027781 0.146111 -v 0.035622 0.030151 0.157262 -v 0.035656 0.026877 0.146303 -v 0.035572 0.028801 0.157549 -v 0.035572 0.026431 0.146398 -v 0.034619 0.027274 0.157873 -v 0.034619 0.024904 0.146723 -v 0.034252 0.026997 0.157932 -v 0.033848 0.026775 0.157979 -v 0.033415 0.026613 0.158014 -v 0.033415 0.024243 0.146863 -v 0.032962 0.024144 0.146884 -v 0.032500 0.024111 0.146891 -v 0.032038 0.026514 0.158035 -v 0.032500 0.031028 0.141945 -v 0.032500 0.031734 0.145271 -v 0.036500 0.028769 0.142425 -v 0.036500 0.024251 0.143385 -v 0.028500 0.028769 0.142425 -v 0.032500 0.021992 0.143866 -v 0.028500 0.024251 0.143385 -v 0.036500 0.024958 0.146711 -v 0.032500 0.022699 0.147191 -v 0.033848 0.024405 0.146829 -v 0.034054 0.029925 0.145655 -v 0.033190 0.030248 0.145587 -v 0.035422 0.026002 0.146489 -v 0.035210 0.025599 0.146575 -v 0.034940 0.025230 0.146653 -v 0.034252 0.024626 0.146781 -v 0.030060 0.025230 0.146653 -v 0.029578 0.026002 0.146489 -v 0.029428 0.026431 0.146398 -v 0.029344 0.026877 0.146303 -v 0.029327 0.027330 0.146207 -v 0.029378 0.027781 0.146111 -v 0.029495 0.028219 0.146018 -v 0.028500 0.029475 0.145751 -v 0.029918 0.029024 0.145847 -v 0.030214 0.029372 0.145773 -v 0.034786 0.029372 0.145773 -v 0.036500 0.029475 0.145751 -v 0.031152 0.024405 0.146829 -v 0.028500 0.024958 0.146711 -v 0.031366 0.030117 0.145614 -v 0.031810 0.030248 0.145587 -v 0.035324 0.028637 0.145929 -v 0.035505 0.028219 0.146018 -v 0.035673 0.027330 0.146207 -v 0.038214 -0.061072 0.139035 -v 0.035436 -0.062216 0.138792 -v 0.003786 -0.061072 0.139035 -v 0.035419 -0.056741 0.139955 -v 0.036371 -0.001741 0.151646 -v 0.024750 -0.062216 0.138792 -v 0.034083 -0.058597 0.139561 -v 0.002003 -0.057760 0.139738 -v 0.039989 -0.058190 0.139647 -v 0.036299 -0.059703 0.139326 -v 0.006581 -0.056741 0.139955 -v 0.002000 -0.037762 0.143989 -v 0.002000 -0.012465 0.149366 -v 0.034907 -0.006757 0.150580 -v 0.002000 -0.008846 0.150136 -v 0.037204 -0.059147 0.139451 -v 0.006053 -0.001605 0.151675 -v 0.002009 -0.005706 0.150804 -v 0.007093 -0.006757 0.150580 -v 0.037375 -0.006170 0.150705 -v 0.002886 -0.003639 0.151242 -v 0.035384 -0.004185 0.151133 -v 0.037941 -0.002485 0.151488 -v 0.005396 -0.059619 0.139354 -v 0.039151 -0.003703 0.151229 -v 0.035000 -0.001571 0.151682 -v 0.004083 -0.002480 0.151489 -v 0.006023 -0.004043 0.151160 -v 0.008764 0.052530 0.140850 -v 0.021710 0.052545 0.140847 -v 0.022041 0.051974 0.140986 -v 0.008475 0.051949 0.140962 -v 0.008001 0.052056 0.140952 -v 0.022550 0.051894 0.140986 -v 0.008000 0.046923 0.142042 -v 0.022550 0.046923 0.142042 -v 0.022290 0.037701 0.144002 -v 0.022550 0.036921 0.144168 -v 0.008000 0.037027 0.144146 -v 0.021985 0.036946 0.144323 -v 0.021565 0.036658 0.144217 -v 0.009375 0.036610 0.144234 -v 0.008769 0.027539 0.146162 -v 0.021869 0.036384 0.144283 -v 0.021620 0.036356 0.144288 -v 0.009375 0.052290 0.140901 -v 0.016213 0.027553 0.146159 -v 0.008547 0.027476 0.146175 -v 0.025584 0.027553 0.146159 -v 0.008000 0.026643 0.146353 -v 0.026300 0.012030 0.149459 -v 0.008496 0.011393 0.149116 -v 0.026073 0.011431 0.149342 -v 0.025300 0.011242 0.149626 -v 0.025370 0.011120 0.149652 -v 0.019761 0.011450 0.151205 -v 0.025672 0.011160 0.149644 -v 0.022163 0.062546 0.140344 -v 0.006132 0.062472 0.140360 -v 0.035868 0.062472 0.140360 -v 0.005291 0.062251 0.140407 -v 0.015810 0.062546 0.140344 -v 0.008980 0.059168 0.141063 -v 0.035000 0.062546 0.140344 -v 0.034676 0.061327 0.140603 -v 0.007961 0.060968 0.140679 -v 0.031550 0.062546 0.140344 -v 0.038214 0.061402 0.140588 -v 0.021620 0.052875 0.142400 -v 0.010113 0.062546 0.140344 -v 0.007000 0.062546 0.140344 -v 0.039330 0.060101 0.140864 -v 0.002670 0.060101 0.140864 -v 0.002302 0.059328 0.141028 -v 0.039698 0.059328 0.141028 -v 0.029712 0.062546 0.140344 -v 0.039924 0.058505 0.141203 -v 0.038978 0.059171 0.141061 -v 0.010113 0.036686 0.145841 -v 0.002000 0.057655 0.141384 -v 0.038692 0.057152 0.141490 -v 0.024038 0.062546 0.140344 -v 0.003342 0.057095 0.141502 -v 0.036825 0.055756 0.141787 -v 0.022332 0.052550 0.142469 -v 0.040000 0.053914 0.142179 -v 0.008954 0.058124 0.141284 -v 0.015810 0.052875 0.142400 -v 0.005018 0.055830 0.141772 -v 0.002000 0.055326 0.141879 -v 0.026082 0.027558 0.147781 -v 0.038830 0.060799 0.140716 -v 0.002000 0.053914 0.142179 -v 0.006132 0.001975 0.153219 -v 0.008640 0.052873 0.142400 -v 0.027813 0.062546 0.140344 -v 0.040000 0.055326 0.141879 -v 0.040000 0.036812 0.145814 -v 0.022550 0.051965 0.142593 -v 0.008000 0.037596 0.145648 -v 0.040000 0.035647 0.146062 -v 0.002000 0.036812 0.145814 -v 0.002000 0.035647 0.146062 -v 0.021620 0.036686 0.145841 -v 0.015810 0.036686 0.145841 -v 0.015810 0.027883 0.147712 -v 0.008000 0.051965 0.142593 -v 0.005703 0.061607 0.140542 -v 0.008478 0.036820 0.145812 -v 0.038137 0.060764 0.140719 -v 0.033278 0.057374 0.141444 -v 0.036497 0.061555 0.140554 -v 0.035479 0.008703 0.151789 -v 0.019761 0.052875 0.142400 -v 0.040000 0.021678 0.149031 -v 0.003077 0.006764 0.152199 -v 0.002000 0.007982 0.151942 -v 0.024038 0.001901 0.153235 -v 0.002000 0.031065 0.147036 -v 0.019761 0.027883 0.147712 -v 0.033345 0.007231 0.152102 -v 0.033046 0.006323 0.152295 -v 0.026300 0.026973 0.147906 -v 0.025570 0.011481 0.151198 -v 0.035479 0.055744 0.141790 -v 0.002000 0.021678 0.149031 -v 0.004544 0.008419 0.151849 -v 0.008145 0.007951 0.151948 -v 0.034070 0.056350 0.141662 -v 0.025835 0.027761 0.147738 -v 0.040000 0.007982 0.151942 -v 0.034481 0.008375 0.151859 -v 0.026211 0.011913 0.151107 -v 0.002000 0.006792 0.152195 -v 0.015810 0.011450 0.151205 -v 0.039084 0.005846 0.152392 -v 0.039924 0.005942 0.152376 -v 0.002670 0.004346 0.152715 -v 0.003350 0.004274 0.152722 -v 0.019761 0.001901 0.153235 -v 0.003786 0.003045 0.152992 -v 0.004500 0.002556 0.153096 -v 0.036710 0.002196 0.153172 -v 0.005241 0.002920 0.153015 -v 0.005291 0.002196 0.153172 -v 0.037500 0.002556 0.153096 -v 0.007000 0.001901 0.153235 -v 0.022163 0.001901 0.153235 -v 0.029713 0.001901 0.153235 -v 0.010113 0.001901 0.153235 -v 0.004524 0.005939 0.150758 -v 0.034704 0.057606 0.139782 -v 0.006334 0.056859 0.139953 -v 0.032200 0.060736 0.131831 -v 0.016213 0.060736 0.131831 -v 0.010113 0.060736 0.131831 -v 0.007038 0.000091 0.144722 -v 0.007057 0.060736 0.131831 -v 0.037500 0.060081 0.131970 -v 0.005290 0.000386 0.144659 -v 0.039924 0.004133 0.143863 -v 0.039330 0.058291 0.132351 -v 0.039924 0.056695 0.132690 -v 0.040000 0.054152 0.133231 -v 0.036714 0.060440 0.131894 -v 0.040000 0.052104 0.133666 -v 0.029713 0.060736 0.131831 -v 0.040000 0.045444 0.135082 -v 0.002000 0.031979 0.137944 -v 0.002000 0.029255 0.138523 -v 0.040000 0.029255 0.138523 -v 0.040000 0.027052 0.138991 -v 0.040000 0.006675 0.143322 -v 0.002076 0.004133 0.143863 -v 0.002000 0.052104 0.133666 -v 0.010113 0.000091 0.144722 -v 0.038214 0.059592 0.132074 -v 0.040000 0.055846 0.132871 -v 0.002302 0.003309 0.144038 -v 0.039698 0.003308 0.144038 -v 0.039330 0.002537 0.144202 -v 0.038830 0.001838 0.144350 -v 0.036709 0.000385 0.144659 -v 0.002000 0.007668 0.143111 -v 0.038830 0.058989 0.132202 -v 0.006132 0.000166 0.144706 -v 0.037500 0.000747 0.144582 -v 0.032200 0.000091 0.144722 -v 0.003170 0.001838 0.144350 -v 0.016213 0.000091 0.144722 -v 0.040000 0.010267 0.142559 -v 0.029713 0.000091 0.144722 -v 0.002670 0.058291 0.132351 -# 15983 vertices, 0 vertices normals - -f 1 20 30 -f 1 22 20 -f 4 22 1 -f 4 24 22 -f 3 25 24 -f 2 24 4 -f 30 20 6 -f 6 25 5 -f 5 25 3 -f 30 6 5 -f 3 24 2 -f 7 8 23 -f 7 9 8 -f 8 9 10 -f 10 11 12 -f 12 11 13 -f 14 12 13 -f 12 14 100 -f 14 15 100 -f 14 18 15 -f 15 18 16 -f 18 19 16 -f 16 19 17 -f 17 19 21 -f 17 21 23 -f 25 6 14 -f 18 14 6 -f 18 6 19 -f 6 20 19 -f 21 19 20 -f 22 21 20 -f 21 22 23 -f 7 23 22 -f 22 24 7 -f 9 7 24 -f 10 9 11 -f 11 9 24 -f 13 11 24 -f 25 13 24 -f 25 14 13 -f 4 1 26 -f 26 1 32 -f 2 4 28 -f 28 4 26 -f 3 2 27 -f 27 2 28 -f 5 3 29 -f 29 3 27 -f 30 5 31 -f 31 5 29 -f 1 30 32 -f 32 30 31 -f 31 29 32 -f 32 29 27 -f 32 27 26 -f 26 27 28 -f 33 45 43 -f 34 45 33 -f 34 46 45 -f 53 46 34 -f 35 50 48 -f 35 48 53 -f 53 48 46 -f 36 50 37 -f 33 43 36 -f 37 50 35 -f 41 38 99 -f 47 38 41 -f 38 47 96 -f 47 49 96 -f 51 52 39 -f 52 42 39 -f 39 42 98 -f 98 42 44 -f 40 98 44 -f 41 99 40 -f 49 47 48 -f 36 43 52 -f 42 52 43 -f 44 42 43 -f 43 45 44 -f 40 44 45 -f 40 45 46 -f 41 40 46 -f 47 41 46 -f 47 46 48 -f 50 49 48 -f 49 50 51 -f 52 51 50 -f 36 52 50 -f 53 34 54 -f 54 34 57 -f 35 53 59 -f 59 53 54 -f 37 35 55 -f 55 35 59 -f 36 37 58 -f 58 37 55 -f 33 36 56 -f 56 36 58 -f 34 33 57 -f 57 33 56 -f 56 58 57 -f 57 58 55 -f 57 55 54 -f 54 55 59 -f 62 77 84 -f 63 61 62 -f 62 61 77 -f 65 81 61 -f 65 61 63 -f 60 74 64 -f 84 77 74 -f 84 74 60 -f 64 81 65 -f 78 66 94 -f 94 66 79 -f 79 80 71 -f 68 67 73 -f 73 69 68 -f 73 72 69 -f 72 97 69 -f 76 95 97 -f 95 76 70 -f 70 76 78 -f 78 94 70 -f 67 71 81 -f 64 74 73 -f 73 74 72 -f 72 75 97 -f 75 72 74 -f 75 74 77 -f 75 76 97 -f 77 76 75 -f 78 76 77 -f 61 78 77 -f 66 78 61 -f 61 79 66 -f 61 80 79 -f 81 80 61 -f 81 71 80 -f 81 73 67 -f 73 81 64 -f 63 62 82 -f 82 62 83 -f 65 63 88 -f 88 63 82 -f 64 65 87 -f 87 65 88 -f 60 64 85 -f 85 64 87 -f 84 60 86 -f 86 60 85 -f 62 84 83 -f 83 84 86 -f 86 85 83 -f 83 85 87 -f 83 87 82 -f 82 87 88 -f 118 115 112 -f 110 90 91 -f 89 112 91 -f 91 112 110 -f 93 116 115 -f 118 112 89 -f 92 106 116 -f 92 116 93 -f 90 106 92 -f 93 115 118 -f 68 69 70 -f 94 79 67 -f 94 68 70 -f 67 68 94 -f 70 69 95 -f 71 67 79 -f 97 95 69 -f 51 96 49 -f 96 51 39 -f 38 96 39 -f 99 38 39 -f 39 98 99 -f 98 40 99 -f 23 100 15 -f 8 10 12 -f 8 12 100 -f 111 114 101 -f 114 113 101 -f 102 113 104 -f 102 104 125 -f 125 104 105 -f 125 105 124 -f 124 105 107 -f 107 108 124 -f 108 109 103 -f 109 111 103 -f 106 105 116 -f 107 105 106 -f 106 90 107 -f 108 107 90 -f 109 108 90 -f 90 110 109 -f 111 109 110 -f 114 111 110 -f 114 110 112 -f 113 114 112 -f 115 113 112 -f 113 115 104 -f 115 116 104 -f 105 104 116 -f 89 91 117 -f 117 91 122 -f 118 89 119 -f 119 89 117 -f 93 118 123 -f 123 118 119 -f 92 93 120 -f 120 93 123 -f 90 92 121 -f 121 92 120 -f 91 90 122 -f 122 90 121 -f 121 120 122 -f 122 120 123 -f 122 123 117 -f 117 123 119 -f 8 100 23 -f 17 23 15 -f 17 15 16 -f 113 102 101 -f 102 125 111 -f 101 102 111 -f 125 124 103 -f 111 125 103 -f 124 108 103 -f 126 1942 1943 -f 131 9589 126 -f 2164 668 128 -f 128 668 2147 -f 126 1943 131 -f 131 1943 2137 -f 131 2137 129 -f 9483 2113 9484 -f 9484 2113 1658 -f 1658 2113 127 -f 2127 2126 668 -f 668 2126 130 -f 131 2147 668 -f 131 668 2123 -f 2123 668 130 -f 129 2138 131 -f 131 2138 2147 -f 1658 127 132 -f 1658 132 2114 -f 1658 2114 668 -f 668 2114 2130 -f 668 2130 2127 -f 719 149 154 -f 143 1953 145 -f 668 2164 672 -f 672 2164 136 -f 2169 666 2170 -f 2170 666 133 -f 2170 133 135 -f 135 133 134 -f 135 134 2175 -f 2175 134 667 -f 2175 667 136 -f 136 667 669 -f 136 669 672 -f 139 647 138 -f 2169 2168 666 -f 666 2168 137 -f 666 137 648 -f 648 137 138 -f 648 138 647 -f 139 138 140 -f 140 138 2166 -f 140 2166 141 -f 660 142 148 -f 148 142 658 -f 148 658 146 -f 141 143 140 -f 140 143 145 -f 140 145 144 -f 144 145 148 -f 144 148 657 -f 657 148 146 -f 151 147 148 -f 154 149 148 -f 148 149 150 -f 148 150 151 -f 147 661 148 -f 148 661 660 -f 724 152 9454 -f 9454 152 153 -f 9454 153 154 -f 154 153 720 -f 154 720 719 -f 9607 1819 728 -f 728 727 9607 -f 9607 727 155 -f 9607 155 9454 -f 9454 155 725 -f 9454 725 724 -f 9588 1865 1864 -f 2206 2192 708 -f 708 2192 156 -f 708 156 160 -f 157 1851 9588 -f 156 2182 160 -f 160 2182 2179 -f 2179 2177 160 -f 160 2177 2176 -f 160 2176 157 -f 2094 2086 157 -f 9588 1864 157 -f 157 1864 2087 -f 157 2087 159 -f 157 2086 160 -f 160 2086 158 -f 160 158 2073 -f 160 2075 2076 -f 160 2076 9486 -f 9486 2076 2060 -f 159 2094 157 -f 2073 2075 160 -f 1681 624 1763 -f 1763 624 9488 -f 162 161 166 -f 160 9486 617 -f 617 9486 161 -f 617 161 616 -f 616 161 162 -f 164 163 628 -f 164 162 163 -f 163 162 166 -f 163 166 165 -f 165 166 627 -f 9488 624 166 -f 166 624 1683 -f 166 1683 627 -f 433 9495 167 -f 167 9495 169 -f 167 169 168 -f 168 169 170 -f 168 170 429 -f 9489 171 170 -f 170 171 429 -f 172 427 9489 -f 9489 427 171 -f 1837 1735 172 -f 172 1735 428 -f 172 428 427 -f 195 288 175 -f 246 296 294 -f 174 293 291 -f 174 291 173 -f 174 173 179 -f 195 175 176 -f 195 176 198 -f 198 176 177 -f 198 177 178 -f 183 184 214 -f 214 184 1618 -f 214 1618 173 -f 173 1618 1617 -f 173 1617 179 -f 180 181 183 -f 183 181 182 -f 183 182 184 -f 177 185 178 -f 178 185 1754 -f 178 1754 186 -f 186 1754 1753 -f 186 1753 187 -f 187 1753 1750 -f 187 1750 201 -f 188 1615 180 -f 180 1615 189 -f 180 189 181 -f 1750 1755 201 -f 201 1755 190 -f 201 190 203 -f 203 190 1757 -f 203 1757 223 -f 194 1611 191 -f 191 1611 188 -f 188 1611 192 -f 188 192 1615 -f 220 193 194 -f 194 193 1610 -f 194 1610 1611 -f 196 195 198 -f 196 198 197 -f 197 198 178 -f 197 178 199 -f 199 178 186 -f 199 186 233 -f 233 186 187 -f 233 187 200 -f 200 187 201 -f 200 201 202 -f 202 201 203 -f 202 203 204 -f 204 203 223 -f 204 223 205 -f 205 223 224 -f 205 224 206 -f 206 224 226 -f 206 226 227 -f 246 294 234 -f 246 234 245 -f 245 234 207 -f 245 207 243 -f 243 207 232 -f 243 232 242 -f 242 232 208 -f 242 208 209 -f 209 208 210 -f 209 210 239 -f 239 210 231 -f 239 231 238 -f 238 231 230 -f 238 230 211 -f 211 230 229 -f 211 229 237 -f 237 229 212 -f 237 212 236 -f 291 213 244 -f 291 244 173 -f 173 244 241 -f 173 241 214 -f 214 241 240 -f 214 240 183 -f 183 240 215 -f 183 215 180 -f 180 215 216 -f 180 216 188 -f 188 216 217 -f 188 217 191 -f 191 217 218 -f 191 218 194 -f 194 218 219 -f 194 219 220 -f 220 219 221 -f 220 221 247 -f 1605 1606 247 -f 247 1606 1602 -f 247 1602 220 -f 220 1602 1608 -f 220 1608 193 -f 1757 222 223 -f 223 222 225 -f 223 225 224 -f 224 225 1759 -f 224 1759 226 -f 226 1759 287 -f 287 286 226 -f 226 286 227 -f 227 286 228 -f 228 212 227 -f 227 212 229 -f 227 229 206 -f 206 229 230 -f 206 230 205 -f 205 230 231 -f 205 231 204 -f 204 231 210 -f 204 210 202 -f 202 210 208 -f 202 208 200 -f 200 208 232 -f 200 232 233 -f 233 232 207 -f 233 207 199 -f 199 207 234 -f 199 234 197 -f 197 234 294 -f 197 294 196 -f 228 235 212 -f 212 235 236 -f 236 235 276 -f 236 276 275 -f 275 221 236 -f 236 221 219 -f 236 219 237 -f 237 219 218 -f 237 218 211 -f 211 218 217 -f 211 217 238 -f 238 217 216 -f 238 216 239 -f 239 216 215 -f 239 215 209 -f 209 215 240 -f 209 240 242 -f 242 240 241 -f 242 241 243 -f 243 241 244 -f 243 244 245 -f 245 244 213 -f 245 213 246 -f 267 1605 268 -f 268 1605 247 -f 268 247 221 -f 268 221 275 -f 276 235 273 -f 310 250 1729 -f 1729 250 249 -f 249 250 1161 -f 1161 250 252 -f 252 250 251 -f 252 251 253 -f 252 253 1160 -f 1160 253 1159 -f 1159 253 263 -f 1159 263 1158 -f 1158 263 1154 -f 1154 263 254 -f 1154 254 255 -f 1154 255 1155 -f 1155 255 1156 -f 1156 255 265 -f 1156 265 256 -f 256 265 257 -f 256 257 285 -f 258 1637 259 -f 259 1637 260 -f 259 260 261 -f 259 261 1634 -f 259 1634 268 -f 268 1634 1603 -f 310 308 250 -f 250 308 262 -f 250 262 251 -f 251 262 279 -f 251 279 253 -f 253 279 264 -f 253 264 263 -f 263 264 254 -f 254 264 280 -f 254 280 255 -f 255 280 282 -f 255 282 265 -f 265 282 266 -f 265 266 257 -f 257 266 283 -f 257 283 284 -f 1603 267 268 -f 248 258 269 -f 269 258 259 -f 269 259 272 -f 272 259 268 -f 272 268 274 -f 274 268 275 -f 270 248 277 -f 277 248 269 -f 277 269 278 -f 278 269 272 -f 278 272 271 -f 271 272 281 -f 281 272 274 -f 281 274 273 -f 273 274 275 -f 273 275 276 -f 308 270 277 -f 308 277 262 -f 262 277 279 -f 279 277 278 -f 279 278 264 -f 264 278 271 -f 264 271 280 -f 280 271 281 -f 280 281 282 -f 282 281 273 -f 282 273 266 -f 266 273 283 -f 283 273 235 -f 235 228 283 -f 283 228 284 -f 284 228 286 -f 285 257 284 -f 285 284 1152 -f 1152 284 286 -f 1152 286 287 -f 195 317 288 -f 1793 290 289 -f 289 290 291 -f 291 292 289 -f 293 292 291 -f 291 290 213 -f 290 1793 298 -f 290 298 213 -f 317 195 313 -f 313 195 196 -f 313 196 295 -f 295 196 294 -f 295 294 296 -f 295 296 297 -f 297 296 246 -f 297 246 298 -f 298 246 213 -f 1793 354 298 -f 298 354 297 -f 299 398 303 -f 301 300 1638 -f 1638 300 1633 -f 306 309 307 -f 301 258 302 -f 301 302 300 -f 300 302 303 -f 300 303 398 -f 258 248 302 -f 302 248 304 -f 302 304 303 -f 303 304 305 -f 303 305 299 -f 248 270 304 -f 304 270 306 -f 304 306 305 -f 305 306 307 -f 305 307 299 -f 299 307 420 -f 270 308 306 -f 306 308 309 -f 309 308 310 -f 1368 420 1713 -f 1713 420 307 -f 1713 307 1711 -f 1711 307 309 -f 1711 309 1710 -f 1710 309 310 -f 1710 310 1729 -f 295 297 311 -f 364 313 295 -f 325 317 313 -f 314 288 317 -f 314 317 315 -f 1745 316 327 -f 327 316 315 -f 327 315 325 -f 325 315 317 -f 322 353 319 -f 319 353 318 -f 319 318 320 -f 320 318 354 -f 320 354 1793 -f 1792 333 322 -f 322 333 321 -f 322 321 353 -f 1745 327 323 -f 323 327 328 -f 323 328 324 -f 313 364 325 -f 325 364 326 -f 325 326 327 -f 327 326 363 -f 327 363 328 -f 328 363 361 -f 328 361 324 -f 324 361 359 -f 324 359 331 -f 331 359 357 -f 331 357 330 -f 330 357 329 -f 330 329 346 -f 346 1737 1741 -f 346 1741 330 -f 330 1741 1742 -f 330 1742 331 -f 331 1742 332 -f 331 332 324 -f 324 332 1743 -f 324 1743 323 -f 1792 334 333 -f 333 334 335 -f 333 335 350 -f 350 335 336 -f 350 336 349 -f 349 336 337 -f 349 337 348 -f 348 337 1796 -f 348 1796 338 -f 295 311 312 -f 312 311 340 -f 312 340 339 -f 339 340 352 -f 339 352 362 -f 362 352 351 -f 362 351 360 -f 360 351 341 -f 360 341 342 -f 342 341 347 -f 342 347 358 -f 358 347 343 -f 358 343 356 -f 356 343 344 -f 356 344 355 -f 1733 1737 345 -f 345 1737 346 -f 345 346 365 -f 365 346 329 -f 1796 433 338 -f 338 433 434 -f 434 344 338 -f 338 344 343 -f 338 343 348 -f 348 343 347 -f 348 347 349 -f 349 347 341 -f 349 341 350 -f 350 341 351 -f 350 351 333 -f 333 351 352 -f 333 352 321 -f 321 352 340 -f 321 340 353 -f 353 340 311 -f 353 311 318 -f 318 311 297 -f 318 297 354 -f 434 431 344 -f 344 431 355 -f 355 431 432 -f 355 432 426 -f 426 365 355 -f 355 365 329 -f 355 329 356 -f 356 329 357 -f 356 357 358 -f 358 357 359 -f 358 359 342 -f 342 359 361 -f 342 361 360 -f 360 361 363 -f 360 363 362 -f 362 363 326 -f 362 326 339 -f 339 326 364 -f 339 364 312 -f 312 364 295 -f 1734 1733 430 -f 430 1733 345 -f 430 345 365 -f 430 365 426 -f 382 292 367 -f 367 292 293 -f 368 1793 289 -f 368 289 369 -f 367 1621 382 -f 382 1621 1624 -f 382 1624 380 -f 1790 1788 379 -f 379 1788 369 -f 379 369 381 -f 381 369 289 -f 381 289 292 -f 1624 1625 380 -f 380 1625 1626 -f 380 1626 370 -f 1626 371 370 -f 370 371 1628 -f 370 1628 373 -f 1790 379 1791 -f 1791 379 378 -f 1791 378 372 -f 1628 1629 373 -f 373 1629 374 -f 373 374 377 -f 374 375 377 -f 377 375 1630 -f 377 1630 376 -f 376 1630 1632 -f 376 1632 383 -f 377 372 373 -f 373 372 378 -f 373 378 370 -f 370 378 379 -f 370 379 380 -f 380 379 381 -f 380 381 382 -f 382 381 292 -f 383 384 376 -f 376 384 1783 -f 376 1783 377 -f 377 1783 1786 -f 377 1786 372 -f 372 1786 1787 -f 372 1787 1791 -f 516 503 410 -f 410 503 399 -f 385 1604 1635 -f 385 1635 386 -f 517 516 1377 -f 1377 516 387 -f 1377 387 1376 -f 1376 387 411 -f 1376 411 413 -f 413 1374 388 -f 413 388 1376 -f 413 415 1374 -f 1374 415 416 -f 1374 416 389 -f 389 416 1371 -f 1371 416 390 -f 1371 390 391 -f 391 390 393 -f 391 393 1366 -f 1635 1636 386 -f 386 1636 392 -f 386 392 397 -f 397 392 1633 -f 1366 393 421 -f 1366 421 394 -f 394 421 1367 -f 395 385 386 -f 395 386 400 -f 400 386 397 -f 400 397 401 -f 401 397 396 -f 396 397 300 -f 397 1633 300 -f 396 300 398 -f 399 395 400 -f 399 400 409 -f 409 400 408 -f 408 400 401 -f 408 401 406 -f 406 401 405 -f 405 401 396 -f 405 396 404 -f 404 396 402 -f 402 396 398 -f 402 398 299 -f 299 419 402 -f 402 419 403 -f 402 403 404 -f 404 403 418 -f 404 418 405 -f 405 418 417 -f 405 417 406 -f 406 417 407 -f 406 407 408 -f 408 407 414 -f 408 414 412 -f 408 412 409 -f 409 412 410 -f 409 410 399 -f 419 299 420 -f 516 410 387 -f 387 410 412 -f 387 412 411 -f 411 412 414 -f 411 414 413 -f 413 414 407 -f 413 407 415 -f 415 407 417 -f 415 417 416 -f 416 417 418 -f 416 418 390 -f 390 418 393 -f 393 418 403 -f 393 403 421 -f 421 403 419 -f 421 419 425 -f 425 419 420 -f 1367 421 422 -f 422 421 425 -f 422 425 423 -f 423 425 424 -f 424 425 420 -f 424 420 1368 -f 432 429 171 -f 432 171 427 -f 431 167 168 -f 431 168 429 -f 428 1735 1734 -f 428 1734 430 -f 427 428 430 -f 427 430 426 -f 426 432 427 -f 432 431 429 -f 433 167 434 -f 434 167 431 -f 435 1604 385 -f 501 499 436 -f 506 490 498 -f 1612 1613 437 -f 475 466 438 -f 482 1614 481 -f 474 483 473 -f 1619 1620 463 -f 1698 1694 451 -f 523 439 450 -f 441 448 443 -f 441 443 442 -f 443 447 521 -f 443 521 442 -f 445 444 551 -f 1694 444 451 -f 451 444 445 -f 451 445 446 -f 446 445 447 -f 446 447 453 -f 453 447 443 -f 453 443 454 -f 454 443 448 -f 454 448 456 -f 456 448 440 -f 456 440 449 -f 449 440 450 -f 449 450 458 -f 458 450 439 -f 1697 1698 452 -f 452 1698 451 -f 452 451 461 -f 461 451 446 -f 461 446 462 -f 462 446 453 -f 462 453 455 -f 455 453 454 -f 455 454 464 -f 464 454 456 -f 464 456 457 -f 457 456 449 -f 457 449 1616 -f 1616 449 458 -f 1619 463 465 -f 459 1697 460 -f 460 1697 452 -f 460 452 467 -f 467 452 461 -f 467 461 469 -f 469 461 462 -f 469 462 471 -f 471 462 455 -f 471 455 472 -f 472 455 464 -f 472 464 463 -f 463 464 457 -f 463 457 465 -f 465 457 1616 -f 466 459 438 -f 438 459 460 -f 438 460 476 -f 476 460 467 -f 476 467 468 -f 468 467 469 -f 468 469 470 -f 470 469 471 -f 470 471 480 -f 480 471 472 -f 480 472 473 -f 473 472 463 -f 473 463 474 -f 474 463 1620 -f 1701 475 487 -f 487 475 438 -f 487 438 477 -f 477 438 476 -f 477 476 478 -f 478 476 468 -f 478 468 479 -f 479 468 470 -f 479 470 484 -f 484 470 480 -f 484 480 481 -f 481 480 473 -f 481 473 482 -f 482 473 483 -f 1614 1612 481 -f 481 1612 437 -f 481 437 484 -f 484 437 485 -f 484 485 479 -f 479 485 486 -f 479 486 478 -f 478 486 507 -f 478 507 477 -f 477 507 508 -f 477 508 487 -f 487 508 509 -f 487 509 1701 -f 512 488 509 -f 509 488 489 -f 509 489 1701 -f 504 494 505 -f 505 494 495 -f 505 495 490 -f 506 499 491 -f 491 499 501 -f 491 501 510 -f 490 495 498 -f 498 495 496 -f 498 496 492 -f 502 493 500 -f 494 1609 495 -f 495 1609 1607 -f 495 1607 496 -f 496 1607 497 -f 496 497 435 -f 435 385 496 -f 496 385 492 -f 492 385 395 -f 506 498 499 -f 499 498 492 -f 499 492 436 -f 436 492 395 -f 436 395 399 -f 436 399 502 -f 436 502 501 -f 501 502 500 -f 501 500 510 -f 510 500 511 -f 502 399 503 -f 502 503 493 -f 493 503 516 -f 511 500 513 -f 513 500 493 -f 513 493 514 -f 514 493 516 -f 1613 504 437 -f 437 504 505 -f 437 505 485 -f 485 505 490 -f 485 490 486 -f 486 490 506 -f 486 506 507 -f 507 506 491 -f 507 491 508 -f 508 491 510 -f 508 510 509 -f 509 510 511 -f 509 511 512 -f 512 511 513 -f 512 513 515 -f 515 513 514 -f 515 514 1704 -f 1704 514 516 -f 1704 516 517 -f 1773 522 518 -f 519 520 518 -f 518 520 1773 -f 442 521 554 -f 554 521 563 -f 563 521 447 -f 563 447 553 -f 553 447 445 -f 553 445 551 -f 442 554 441 -f 441 554 519 -f 441 519 448 -f 448 519 518 -f 448 518 440 -f 440 518 522 -f 440 522 450 -f 450 522 523 -f 1773 525 522 -f 522 525 523 -f 1773 524 525 -f 525 524 528 -f 526 523 1622 -f 1622 523 527 -f 1622 527 1623 -f 1623 527 533 -f 1623 533 534 -f 525 528 548 -f 548 528 529 -f 548 529 530 -f 530 529 1778 -f 530 1778 535 -f 531 532 533 -f 533 532 1627 -f 533 1627 534 -f 1778 1770 535 -f 535 1770 537 -f 535 537 536 -f 536 537 1780 -f 536 1780 541 -f 546 538 547 -f 547 538 539 -f 547 539 531 -f 531 539 540 -f 531 540 532 -f 1780 1779 541 -f 541 1779 542 -f 541 542 550 -f 550 542 543 -f 550 543 544 -f 544 543 545 -f 550 546 541 -f 541 546 547 -f 541 547 536 -f 536 547 531 -f 536 531 535 -f 535 531 533 -f 535 533 530 -f 530 533 527 -f 530 527 548 -f 548 527 523 -f 548 523 525 -f 544 549 550 -f 550 549 1631 -f 550 1631 546 -f 551 552 553 -f 553 552 564 -f 553 564 563 -f 576 519 554 -f 555 520 519 -f 1775 1773 520 -f 520 555 1775 -f 1775 555 556 -f 1775 556 557 -f 557 556 558 -f 557 558 1776 -f 552 559 564 -f 564 559 1691 -f 564 1691 566 -f 566 1691 1686 -f 566 1686 560 -f 560 1686 1684 -f 560 1684 561 -f 562 570 561 -f 561 570 569 -f 561 569 560 -f 563 564 565 -f 565 564 566 -f 565 566 567 -f 567 566 560 -f 567 560 568 -f 568 560 569 -f 568 569 591 -f 591 569 570 -f 591 570 571 -f 571 570 572 -f 571 572 590 -f 590 572 574 -f 590 574 573 -f 573 574 588 -f 573 588 575 -f 554 594 576 -f 576 594 593 -f 576 593 577 -f 577 593 592 -f 577 592 596 -f 596 592 578 -f 596 578 597 -f 597 578 579 -f 597 579 599 -f 599 579 580 -f 599 580 582 -f 582 580 581 -f 582 581 584 -f 584 581 583 -f 584 583 595 -f 562 585 570 -f 570 585 586 -f 570 586 572 -f 572 586 587 -f 572 587 574 -f 574 587 588 -f 588 587 1680 -f 588 1680 1682 -f 1682 615 588 -f 588 615 575 -f 575 615 589 -f 589 583 575 -f 575 583 581 -f 575 581 573 -f 573 581 580 -f 573 580 590 -f 590 580 579 -f 590 579 571 -f 571 579 578 -f 571 578 591 -f 591 578 592 -f 591 592 568 -f 568 592 593 -f 568 593 567 -f 567 593 594 -f 567 594 565 -f 565 594 554 -f 565 554 563 -f 589 614 583 -f 583 614 613 -f 583 613 595 -f 595 613 611 -f 519 576 555 -f 555 576 577 -f 555 577 556 -f 556 577 596 -f 556 596 558 -f 558 596 597 -f 558 597 598 -f 598 597 599 -f 598 599 601 -f 601 599 582 -f 601 582 603 -f 603 582 584 -f 603 584 604 -f 604 584 595 -f 604 595 606 -f 606 595 611 -f 1776 558 1777 -f 1777 558 598 -f 1777 598 600 -f 600 598 601 -f 600 601 602 -f 602 601 603 -f 602 603 1771 -f 1771 603 604 -f 1771 604 605 -f 605 604 606 -f 605 606 607 -f 607 606 611 -f 607 611 1772 -f 1764 1765 1681 -f 610 1765 1766 -f 609 610 608 -f 608 610 1766 -f 609 612 610 -f 610 589 1765 -f 612 1769 611 -f 611 1769 1772 -f 611 613 612 -f 612 613 614 -f 612 614 610 -f 610 614 589 -f 1765 589 615 -f 1681 1765 1682 -f 1682 1765 615 -f 164 621 162 -f 162 621 616 -f 160 617 618 -f 618 617 616 -f 618 616 1639 -f 1639 616 621 -f 1639 621 1414 -f 1414 621 619 -f 620 622 1471 -f 621 164 619 -f 619 164 620 -f 620 164 622 -f 622 164 628 -f 1471 622 623 -f 623 622 1411 -f 1687 1411 622 -f 1679 625 626 -f 163 165 626 -f 626 165 627 -f 626 627 1679 -f 1679 627 1683 -f 1687 622 625 -f 625 622 626 -f 626 622 628 -f 626 628 163 -f 630 631 1736 -f 1736 631 632 -f 1736 632 1738 -f 1096 634 1798 -f 1798 634 632 -f 1798 632 1800 -f 1800 632 631 -f 1800 631 1799 -f 1799 631 630 -f 1738 632 1739 -f 1739 632 634 -f 1739 634 1740 -f 1096 1137 1097 -f 1096 1097 634 -f 634 1097 1740 -f 1803 633 1096 -f 1658 1659 635 -f 635 1659 636 -f 635 636 1804 -f 633 1803 1802 -f 1804 636 1802 -f 1802 636 1095 -f 1802 1095 633 -f 779 735 777 -f 641 718 638 -f 638 718 779 -f 638 639 641 -f 641 639 782 -f 641 782 643 -f 643 782 637 -f 643 640 641 -f 717 640 642 -f 642 640 643 -f 642 643 785 -f 785 643 637 -f 644 664 784 -f 642 785 784 -f 642 784 645 -f 645 784 664 -f 717 642 645 -f 717 645 646 -f 646 645 664 -f 646 664 151 -f 662 665 655 -f 139 652 647 -f 647 652 675 -f 647 675 648 -f 673 653 790 -f 790 653 651 -f 790 651 791 -f 140 656 139 -f 139 656 652 -f 791 651 788 -f 788 651 650 -f 788 650 649 -f 663 654 650 -f 663 650 659 -f 659 650 651 -f 659 651 656 -f 656 651 652 -f 652 651 653 -f 652 653 675 -f 649 650 654 -f 649 654 655 -f 140 144 656 -f 656 144 657 -f 656 657 146 -f 656 146 659 -f 659 146 658 -f 659 658 142 -f 659 142 663 -f 663 142 660 -f 663 660 661 -f 663 661 147 -f 655 654 662 -f 662 654 663 -f 662 663 664 -f 664 663 147 -f 664 147 151 -f 644 665 664 -f 664 665 662 -f 666 648 675 -f 133 676 134 -f 134 676 669 -f 134 669 667 -f 669 676 674 -f 1662 1661 674 -f 674 1661 670 -f 674 670 669 -f 669 670 671 -f 669 671 672 -f 673 1662 653 -f 653 1662 674 -f 653 674 675 -f 675 674 676 -f 675 676 666 -f 666 676 133 -f 677 1343 1349 -f 678 679 677 -f 681 1217 678 -f 678 1217 679 -f 678 680 681 -f 681 680 1345 -f 681 1345 685 -f 685 1216 681 -f 681 1216 682 -f 681 682 1217 -f 685 1345 1346 -f 685 1346 687 -f 683 1213 1214 -f 683 1214 687 -f 687 1214 685 -f 685 1214 684 -f 685 684 1216 -f 706 703 686 -f 686 703 683 -f 686 683 1342 -f 1342 683 687 -f 1342 687 1346 -f 700 1213 703 -f 703 1213 683 -f 707 1644 691 -f 689 688 1815 -f 1815 688 690 -f 707 691 1223 -f 707 1223 701 -f 701 1223 1222 -f 1222 692 701 -f 701 692 702 -f 702 692 1224 -f 702 1224 699 -f 1815 690 693 -f 693 690 1812 -f 1812 690 704 -f 1812 704 694 -f 694 704 695 -f 695 704 696 -f 696 704 697 -f 700 705 698 -f 698 705 699 -f 705 700 703 -f 688 707 701 -f 688 701 690 -f 690 701 702 -f 690 702 704 -f 704 702 699 -f 704 699 705 -f 697 704 1811 -f 1811 704 705 -f 1811 705 703 -f 1811 703 1809 -f 1809 703 706 -f 1643 1644 707 -f 711 709 710 -f 710 712 715 -f 710 715 711 -f 711 715 716 -f 1643 707 1642 -f 688 715 707 -f 707 715 712 -f 707 712 1642 -f 1642 712 710 -f 1642 710 713 -f 713 710 714 -f 714 710 1640 -f 688 689 715 -f 715 689 1816 -f 715 1816 716 -f 641 640 732 -f 646 151 150 -f 733 640 717 -f 641 732 718 -f 735 779 721 -f 721 779 718 -f 736 777 735 -f 646 150 717 -f 717 150 149 -f 717 149 733 -f 149 719 733 -f 733 719 720 -f 733 720 723 -f 723 720 153 -f 718 732 721 -f 721 732 731 -f 721 731 722 -f 722 731 730 -f 722 730 767 -f 153 152 723 -f 723 152 724 -f 723 724 726 -f 726 724 725 -f 726 725 729 -f 729 725 155 -f 729 155 734 -f 734 155 727 -f 734 727 728 -f 734 730 729 -f 729 730 726 -f 726 730 731 -f 726 731 723 -f 723 731 732 -f 723 732 733 -f 733 732 640 -f 734 768 730 -f 730 768 767 -f 735 721 722 -f 735 722 767 -f 735 767 737 -f 736 735 737 -f 737 767 766 -f 770 769 738 -f 761 739 762 -f 915 741 916 -f 916 741 740 -f 916 740 919 -f 919 746 920 -f 740 741 743 -f 740 743 742 -f 742 743 1515 -f 742 1515 744 -f 744 1515 745 -f 744 745 748 -f 919 740 746 -f 746 740 742 -f 746 742 744 -f 746 744 747 -f 747 744 748 -f 747 748 753 -f 752 749 753 -f 753 749 750 -f 753 750 747 -f 747 750 1822 -f 747 1822 746 -f 746 1822 1821 -f 746 1821 751 -f 746 751 920 -f 755 752 756 -f 756 752 753 -f 756 753 757 -f 757 753 748 -f 757 748 754 -f 754 748 745 -f 760 755 761 -f 761 755 756 -f 761 756 739 -f 739 756 757 -f 739 757 758 -f 758 757 754 -f 739 758 759 -f 739 759 762 -f 762 759 1516 -f 760 761 765 -f 765 761 762 -f 765 762 763 -f 763 762 1516 -f 763 1516 764 -f 766 771 770 -f 736 737 764 -f 764 737 766 -f 764 766 763 -f 763 766 770 -f 763 770 765 -f 765 770 738 -f 765 738 760 -f 766 767 768 -f 766 768 771 -f 771 768 734 -f 769 770 1818 -f 1818 770 771 -f 1818 771 1820 -f 1820 771 734 -f 1820 734 728 -f 900 789 792 -f 1519 863 876 -f 1667 772 873 -f 864 773 865 -f 1521 841 840 -f 827 829 825 -f 774 1528 800 -f 775 1529 801 -f 776 779 777 -f 776 777 778 -f 778 777 736 -f 780 638 776 -f 776 638 779 -f 638 780 639 -f 639 780 781 -f 639 781 782 -f 782 781 783 -f 782 783 637 -f 786 784 785 -f 786 785 783 -f 783 785 637 -f 787 665 786 -f 786 665 644 -f 786 644 784 -f 649 655 901 -f 901 655 787 -f 787 655 665 -f 792 788 649 -f 792 649 901 -f 789 673 790 -f 789 790 791 -f 789 791 792 -f 792 791 788 -f 953 1678 931 -f 931 1678 809 -f 931 809 932 -f 932 809 808 -f 932 808 934 -f 934 808 793 -f 934 793 794 -f 806 794 793 -f 805 796 806 -f 806 796 794 -f 797 798 805 -f 805 798 795 -f 805 795 796 -f 798 797 929 -f 929 797 803 -f 801 926 799 -f 801 799 803 -f 803 799 929 -f 926 801 1529 -f 926 1529 1530 -f 1528 775 800 -f 800 775 801 -f 800 801 811 -f 811 801 803 -f 811 803 802 -f 802 803 797 -f 802 797 804 -f 804 797 805 -f 804 805 814 -f 814 805 806 -f 814 806 815 -f 815 806 793 -f 815 793 807 -f 807 793 808 -f 807 808 817 -f 817 808 809 -f 817 809 818 -f 818 809 1678 -f 1525 774 810 -f 810 774 800 -f 810 800 812 -f 812 800 811 -f 812 811 813 -f 813 811 802 -f 813 802 820 -f 820 802 804 -f 820 804 822 -f 822 804 814 -f 822 814 823 -f 823 814 815 -f 823 815 826 -f 826 815 807 -f 826 807 816 -f 816 807 817 -f 816 817 828 -f 828 817 818 -f 842 1525 819 -f 819 1525 810 -f 819 810 839 -f 839 810 812 -f 839 812 837 -f 837 812 813 -f 837 813 834 -f 834 813 820 -f 834 820 821 -f 821 820 822 -f 821 822 832 -f 832 822 823 -f 832 823 824 -f 824 823 826 -f 824 826 825 -f 825 826 816 -f 825 816 827 -f 827 816 828 -f 829 830 825 -f 825 830 831 -f 825 831 824 -f 824 831 847 -f 824 847 832 -f 832 847 833 -f 832 833 821 -f 821 833 845 -f 821 845 834 -f 834 845 835 -f 834 835 837 -f 837 835 836 -f 837 836 839 -f 839 836 838 -f 839 838 819 -f 819 838 840 -f 840 841 819 -f 819 841 1526 -f 819 1526 842 -f 848 1521 840 -f 848 840 843 -f 843 840 838 -f 843 838 844 -f 844 838 836 -f 844 836 849 -f 849 836 835 -f 849 835 852 -f 852 835 845 -f 852 845 853 -f 853 845 833 -f 853 833 846 -f 846 833 847 -f 846 847 855 -f 855 847 831 -f 855 831 1673 -f 1673 831 830 -f 1523 1521 857 -f 857 1521 848 -f 857 848 858 -f 858 848 843 -f 858 843 859 -f 859 843 844 -f 859 844 861 -f 861 844 849 -f 861 849 850 -f 850 849 852 -f 850 852 851 -f 851 852 853 -f 851 853 854 -f 854 853 846 -f 854 846 889 -f 889 846 855 -f 889 855 856 -f 856 855 1673 -f 773 1523 865 -f 865 1523 857 -f 865 857 867 -f 867 857 858 -f 867 858 868 -f 868 858 859 -f 868 859 860 -f 860 859 861 -f 860 861 862 -f 862 861 850 -f 862 850 870 -f 870 850 851 -f 870 851 871 -f 871 851 854 -f 871 854 872 -f 872 854 889 -f 863 864 876 -f 876 864 865 -f 876 865 878 -f 878 865 867 -f 878 867 866 -f 866 867 868 -f 866 868 869 -f 869 868 860 -f 869 860 883 -f 883 860 862 -f 883 862 884 -f 884 862 870 -f 884 870 885 -f 885 870 871 -f 885 871 887 -f 887 871 872 -f 1667 873 874 -f 875 1519 876 -f 875 876 877 -f 877 876 878 -f 877 878 879 -f 879 878 866 -f 879 866 880 -f 880 866 869 -f 880 869 881 -f 881 869 883 -f 881 883 882 -f 882 883 884 -f 882 884 886 -f 886 884 885 -f 886 885 873 -f 873 885 887 -f 873 887 874 -f 874 887 872 -f 874 872 888 -f 888 872 889 -f 888 889 1671 -f 1671 889 856 -f 772 890 873 -f 873 890 891 -f 873 891 886 -f 886 891 906 -f 886 906 882 -f 882 906 892 -f 882 892 881 -f 881 892 893 -f 881 893 880 -f 880 893 894 -f 880 894 879 -f 879 894 895 -f 879 895 877 -f 877 895 909 -f 877 909 875 -f 875 909 896 -f 875 896 1519 -f 1518 897 896 -f 896 897 898 -f 896 898 1519 -f 905 900 899 -f 899 900 792 -f 899 792 907 -f 907 792 901 -f 907 901 902 -f 902 901 787 -f 902 787 903 -f 903 787 786 -f 903 786 904 -f 904 786 783 -f 904 783 908 -f 908 783 781 -f 908 781 910 -f 910 781 780 -f 910 780 911 -f 911 780 776 -f 890 905 891 -f 891 905 899 -f 891 899 906 -f 906 899 907 -f 906 907 892 -f 892 907 902 -f 892 902 893 -f 893 902 903 -f 893 903 894 -f 894 903 904 -f 894 904 895 -f 895 904 908 -f 895 908 909 -f 909 908 910 -f 909 910 896 -f 896 910 911 -f 896 911 1518 -f 1518 911 776 -f 1518 776 912 -f 912 776 778 -f 917 913 1508 -f 917 1508 914 -f 917 914 918 -f 918 1599 1600 -f 1600 915 916 -f 1600 916 918 -f 918 916 919 -f 913 917 1824 -f 1824 917 918 -f 1824 918 1826 -f 1826 918 919 -f 1826 919 920 -f 983 964 948 -f 923 965 951 -f 951 965 921 -f 949 924 922 -f 922 924 1033 -f 922 1033 950 -f 950 1033 923 -f 923 1033 965 -f 948 964 949 -f 949 964 924 -f 983 925 928 -f 983 928 927 -f 926 927 799 -f 799 927 928 -f 799 928 929 -f 929 928 925 -f 798 930 795 -f 795 930 941 -f 795 941 796 -f 796 941 944 -f 796 944 794 -f 933 932 934 -f 933 934 937 -f 937 934 794 -f 953 931 954 -f 954 931 932 -f 954 932 956 -f 956 932 933 -f 956 933 958 -f 960 935 938 -f 938 935 936 -f 794 944 946 -f 794 946 937 -f 937 946 938 -f 937 938 933 -f 933 938 936 -f 933 936 958 -f 929 925 798 -f 798 925 939 -f 798 939 940 -f 798 940 930 -f 930 940 942 -f 930 942 941 -f 941 942 943 -f 941 943 944 -f 944 943 945 -f 944 945 946 -f 946 945 952 -f 946 952 938 -f 938 952 947 -f 938 947 960 -f 965 1730 921 -f 921 1730 963 -f 921 963 962 -f 983 948 925 -f 925 948 949 -f 925 949 939 -f 939 949 922 -f 939 922 940 -f 940 922 950 -f 940 950 942 -f 942 950 923 -f 942 923 943 -f 943 923 951 -f 943 951 945 -f 945 951 921 -f 945 921 952 -f 952 921 962 -f 952 962 947 -f 1105 953 1041 -f 1041 953 954 -f 1041 954 1042 -f 1042 954 956 -f 1042 956 955 -f 955 956 958 -f 955 958 957 -f 957 958 936 -f 957 936 1049 -f 1049 936 935 -f 1049 935 959 -f 959 935 960 -f 959 960 1050 -f 1050 960 947 -f 1050 947 961 -f 961 947 962 -f 961 962 1039 -f 1039 962 963 -f 1039 963 1731 -f 1731 963 1730 -f 1073 1721 1723 -f 1067 1069 1017 -f 983 927 968 -f 968 927 926 -f 968 926 1530 -f 924 964 999 -f 1732 1730 965 -f 1032 965 1033 -f 965 1032 1732 -f 1732 1032 1030 -f 1732 1030 966 -f 966 1030 970 -f 966 970 967 -f 968 1530 969 -f 968 969 984 -f 984 969 1527 -f 984 1527 985 -f 985 1527 1532 -f 985 1532 986 -f 967 970 1724 -f 1724 970 1028 -f 1724 1028 1725 -f 1725 1028 1026 -f 1725 1026 1726 -f 1726 1026 972 -f 1726 972 1728 -f 1728 972 971 -f 971 972 1025 -f 971 1025 973 -f 973 1025 1024 -f 973 1024 1712 -f 986 1532 1531 -f 986 1531 974 -f 974 1531 1576 -f 974 1576 989 -f 989 1576 1535 -f 989 1535 991 -f 991 1535 1534 -f 991 1534 993 -f 1712 1024 1714 -f 1714 1024 1023 -f 1714 1023 1715 -f 1715 1023 1020 -f 1715 1020 1709 -f 1709 1020 980 -f 1709 980 975 -f 993 1534 995 -f 995 1534 977 -f 995 977 976 -f 976 977 1533 -f 976 1533 978 -f 978 1533 1567 -f 978 1567 979 -f 979 1567 1539 -f 979 1539 982 -f 975 980 1719 -f 1719 980 1019 -f 1719 1019 1717 -f 1717 1019 1018 -f 1717 1018 1716 -f 1716 1018 1036 -f 1716 1036 1035 -f 982 1539 981 -f 982 981 997 -f 997 981 1538 -f 997 1538 998 -f 983 968 984 -f 983 984 1000 -f 1000 984 985 -f 1000 985 1002 -f 1002 985 986 -f 1002 986 987 -f 987 986 974 -f 987 974 988 -f 988 974 989 -f 988 989 990 -f 990 989 991 -f 990 991 992 -f 992 991 993 -f 992 993 1006 -f 1006 993 995 -f 1006 995 994 -f 994 995 976 -f 994 976 1008 -f 1008 976 978 -f 1008 978 1009 -f 1009 978 979 -f 1009 979 996 -f 996 979 982 -f 996 982 1012 -f 1012 982 997 -f 1012 997 1015 -f 1015 997 998 -f 1015 998 1016 -f 1538 1537 998 -f 998 1537 1065 -f 998 1065 1064 -f 998 1064 1066 -f 998 1066 1016 -f 1016 1066 1067 -f 964 983 999 -f 999 983 1000 -f 999 1000 1031 -f 1031 1000 1001 -f 1001 1000 1002 -f 1001 1002 1029 -f 1029 1002 987 -f 1029 987 1027 -f 1027 987 988 -f 1027 988 1003 -f 1003 988 990 -f 1003 990 1004 -f 1004 990 992 -f 1004 992 1005 -f 1005 992 1006 -f 1005 1006 1022 -f 1022 1006 994 -f 1022 994 1007 -f 1007 994 1008 -f 1007 1008 1021 -f 1021 1008 1009 -f 1021 1009 1010 -f 1010 1009 996 -f 1010 996 1011 -f 1011 996 1012 -f 1011 1012 1013 -f 1013 1012 1015 -f 1013 1015 1014 -f 1014 1015 1016 -f 1014 1016 1017 -f 1017 1016 1067 -f 1017 1069 1071 -f 1071 1034 1017 -f 1017 1034 1037 -f 1017 1037 1014 -f 1014 1037 1036 -f 1014 1036 1013 -f 1013 1036 1018 -f 1013 1018 1011 -f 1011 1018 1019 -f 1011 1019 1010 -f 1010 1019 980 -f 1010 980 1021 -f 1021 980 1020 -f 1021 1020 1007 -f 1007 1020 1023 -f 1007 1023 1022 -f 1022 1023 1024 -f 1022 1024 1005 -f 1005 1024 1025 -f 1005 1025 1004 -f 1004 1025 972 -f 1004 972 1003 -f 1003 972 1026 -f 1003 1026 1027 -f 1027 1026 1028 -f 1027 1028 1029 -f 1029 1028 970 -f 1029 970 1001 -f 1001 970 1030 -f 1001 1030 1031 -f 1031 1030 1032 -f 1031 1032 999 -f 999 1032 1033 -f 999 1033 924 -f 1034 1071 1073 -f 1035 1036 1722 -f 1722 1036 1037 -f 1722 1037 1038 -f 1038 1037 1034 -f 1038 1034 1723 -f 1723 1034 1073 -f 1106 1040 1098 -f 1106 1105 1041 -f 1043 1168 1761 -f 1045 1167 1043 -f 1043 1167 1168 -f 1046 1166 1045 -f 1045 1166 1167 -f 1165 1047 1163 -f 1163 1047 1051 -f 1163 1051 1185 -f 1185 1051 1039 -f 1185 1039 1731 -f 1098 1040 1044 -f 1106 1041 1040 -f 1040 1041 1042 -f 1040 1042 1044 -f 1761 1098 1043 -f 1043 1098 1044 -f 1043 1044 1045 -f 1045 1044 1048 -f 1045 1048 1046 -f 1046 1048 1047 -f 1046 1047 1165 -f 1042 955 1044 -f 1044 955 957 -f 1044 957 1048 -f 1048 957 1049 -f 1048 1049 1047 -f 1049 959 1047 -f 1047 959 1050 -f 1047 1050 1051 -f 1051 1050 961 -f 1051 961 1039 -f 1199 1074 1072 -f 1064 1062 1066 -f 1235 1075 1053 -f 1235 1208 1076 -f 1053 1075 1055 -f 1055 1075 1054 -f 1055 1054 1056 -f 1057 1059 1077 -f 1057 1058 1059 -f 1059 1058 1084 -f 1059 1084 1230 -f 1230 1084 1082 -f 1060 1080 1231 -f 1060 1231 1082 -f 1082 1231 1230 -f 1063 1080 1061 -f 1061 1080 1081 -f 1063 1061 1062 -f 1063 1062 1229 -f 1229 1062 1227 -f 1227 1062 1064 -f 1227 1064 1065 -f 1227 1065 1537 -f 1066 1062 1061 -f 1066 1061 1067 -f 1067 1052 1069 -f 1069 1052 1068 -f 1069 1068 1089 -f 1069 1089 1071 -f 1071 1089 1090 -f 1071 1090 1070 -f 1071 1070 1092 -f 1071 1092 1073 -f 1073 1092 1072 -f 1073 1072 1074 -f 1073 1074 1721 -f 1235 1076 1075 -f 1075 1076 1206 -f 1075 1206 1054 -f 1077 1056 1057 -f 1057 1056 1054 -f 1057 1054 1058 -f 1058 1054 1087 -f 1206 1078 1054 -f 1054 1078 1079 -f 1054 1079 1087 -f 1087 1079 1203 -f 1087 1203 1201 -f 1081 1080 1060 -f 1081 1060 1088 -f 1088 1060 1082 -f 1088 1082 1091 -f 1091 1082 1084 -f 1091 1084 1083 -f 1083 1084 1058 -f 1083 1058 1085 -f 1085 1058 1087 -f 1085 1087 1086 -f 1086 1087 1201 -f 1086 1201 1093 -f 1067 1061 1052 -f 1052 1061 1081 -f 1052 1081 1068 -f 1068 1081 1088 -f 1068 1088 1089 -f 1089 1088 1091 -f 1089 1091 1090 -f 1090 1091 1083 -f 1090 1083 1070 -f 1070 1083 1085 -f 1070 1085 1092 -f 1092 1085 1086 -f 1092 1086 1072 -f 1072 1086 1093 -f 1072 1093 1199 -f 1135 1137 1139 -f 1098 1761 1099 -f 1094 633 1660 -f 1660 633 1095 -f 1136 1096 633 -f 1740 1097 1135 -f 1097 1137 1135 -f 1098 1099 1100 -f 1100 1099 1101 -f 1100 1101 1108 -f 1102 1112 1103 -f 1103 1112 1104 -f 1103 1104 1149 -f 1149 1104 1105 -f 1149 1105 1106 -f 1101 1758 1108 -f 1108 1758 1107 -f 1108 1107 1148 -f 1148 1107 1113 -f 1148 1113 1109 -f 1117 1118 1110 -f 1110 1118 1674 -f 1110 1674 1111 -f 1111 1674 1676 -f 1111 1676 1102 -f 1102 1676 1677 -f 1102 1677 1112 -f 1113 1751 1109 -f 1109 1751 1114 -f 1109 1114 1115 -f 1115 1114 1752 -f 1115 1752 1147 -f 1147 1752 1116 -f 1147 1116 1122 -f 1672 1670 1117 -f 1117 1670 1675 -f 1117 1675 1118 -f 1117 1146 1672 -f 1672 1146 1145 -f 1672 1145 1669 -f 1669 1145 1119 -f 1669 1119 1120 -f 1116 1121 1122 -f 1122 1121 1748 -f 1122 1748 1123 -f 1123 1748 1125 -f 1123 1125 1124 -f 1124 1125 1749 -f 1124 1749 1127 -f 1749 1126 1127 -f 1127 1126 1747 -f 1127 1747 1143 -f 1143 1747 1746 -f 1143 1746 1131 -f 1120 1119 1666 -f 1666 1119 1144 -f 1666 1144 1128 -f 1128 1144 1129 -f 1128 1129 1130 -f 1130 1129 1142 -f 1130 1142 1668 -f 1746 1744 1131 -f 1131 1744 1132 -f 1131 1132 1140 -f 1140 1132 1133 -f 1140 1133 1139 -f 1139 1133 1134 -f 1139 1134 1135 -f 1096 1136 1137 -f 1137 1136 1138 -f 1137 1138 1139 -f 1139 1138 1141 -f 1139 1141 1140 -f 1140 1141 1142 -f 1140 1142 1131 -f 1131 1142 1129 -f 1131 1129 1143 -f 1143 1129 1144 -f 1143 1144 1127 -f 1127 1144 1119 -f 1127 1119 1124 -f 1124 1119 1145 -f 1124 1145 1123 -f 1123 1145 1146 -f 1123 1146 1122 -f 1122 1146 1117 -f 1122 1117 1147 -f 1147 1117 1110 -f 1147 1110 1115 -f 1115 1110 1111 -f 1115 1111 1109 -f 1109 1111 1102 -f 1109 1102 1148 -f 1148 1102 1103 -f 1148 1103 1108 -f 1108 1103 1149 -f 1108 1149 1100 -f 1100 1149 1106 -f 1100 1106 1098 -f 1668 1142 1663 -f 1663 1142 1141 -f 1663 1141 1664 -f 1664 1141 1138 -f 1664 1138 1665 -f 1665 1138 1136 -f 1665 1136 1094 -f 1094 1136 633 -f 1150 1151 1195 -f 1174 1189 1181 -f 1190 285 1760 -f 1760 285 1152 -f 1760 1152 287 -f 285 1190 256 -f 256 1190 1153 -f 256 1153 1156 -f 1157 1154 1155 -f 1157 1155 1153 -f 1153 1155 1156 -f 1154 1157 1158 -f 1158 1157 1193 -f 1158 1193 1159 -f 1159 1193 1160 -f 1160 1193 1195 -f 1160 1195 252 -f 1729 249 1151 -f 1151 249 1161 -f 1151 1161 1195 -f 1195 1161 252 -f 1162 1163 1184 -f 1184 1163 1185 -f 1166 1046 1164 -f 1164 1046 1162 -f 1162 1046 1165 -f 1162 1165 1163 -f 1166 1164 1167 -f 1167 1164 1171 -f 1167 1171 1168 -f 1168 1171 1170 -f 1168 1170 1169 -f 1168 1169 1761 -f 1762 1169 1177 -f 1177 1169 1170 -f 1177 1170 1179 -f 1179 1170 1171 -f 1179 1171 1172 -f 1172 1171 1164 -f 1172 1164 1173 -f 1173 1164 1162 -f 1173 1162 1180 -f 1180 1162 1184 -f 1174 1181 1182 -f 1175 1762 1176 -f 1176 1762 1177 -f 1176 1177 1187 -f 1187 1177 1179 -f 1187 1179 1178 -f 1178 1179 1172 -f 1178 1172 1188 -f 1188 1172 1173 -f 1188 1173 1181 -f 1181 1173 1180 -f 1181 1180 1182 -f 1182 1180 1184 -f 1182 1184 1183 -f 1183 1184 1185 -f 1183 1185 1731 -f 1756 1175 1191 -f 1191 1175 1176 -f 1191 1176 1192 -f 1192 1176 1187 -f 1192 1187 1186 -f 1186 1187 1178 -f 1186 1178 1194 -f 1194 1178 1188 -f 1194 1188 1196 -f 1196 1188 1181 -f 1196 1181 1727 -f 1727 1181 1189 -f 1760 1756 1190 -f 1190 1756 1191 -f 1190 1191 1153 -f 1153 1191 1192 -f 1153 1192 1157 -f 1157 1192 1186 -f 1157 1186 1193 -f 1193 1186 1194 -f 1193 1194 1195 -f 1195 1194 1196 -f 1195 1196 1150 -f 1150 1196 1727 -f 1339 1721 1197 -f 1197 1721 1074 -f 1197 1074 1198 -f 1198 1074 1199 -f 1198 1199 1200 -f 1200 1199 1093 -f 1200 1093 1340 -f 1340 1093 1201 -f 1340 1201 1202 -f 1202 1201 1203 -f 1202 1203 1204 -f 1204 1203 1079 -f 1204 1079 1205 -f 1205 1079 1078 -f 1205 1078 1334 -f 1334 1078 1206 -f 1334 1206 1333 -f 1333 1206 1076 -f 1333 1076 1207 -f 1207 1076 1208 -f 1641 1646 1322 -f 1318 1551 1328 -f 1294 1282 1283 -f 1292 1548 1209 -f 1648 1651 1259 -f 1544 1210 1281 -f 1655 1657 1211 -f 1560 1542 1212 -f 700 1225 1325 -f 700 1325 1213 -f 1213 1325 1214 -f 1214 1325 1215 -f 1327 1216 1215 -f 1215 1216 684 -f 1215 684 1214 -f 1218 682 1327 -f 1327 682 1216 -f 677 679 1219 -f 1219 679 1217 -f 1219 1217 1218 -f 1218 1217 682 -f 1554 1220 1219 -f 1219 1220 1343 -f 1219 1343 677 -f 1644 1221 691 -f 1320 692 1222 -f 1320 1222 1221 -f 1221 1222 1223 -f 1221 1223 691 -f 699 1224 1321 -f 1321 1224 1320 -f 1320 1224 692 -f 700 698 1225 -f 1225 698 1321 -f 1321 698 699 -f 1226 1227 1537 -f 1226 1537 1536 -f 1228 1229 1226 -f 1226 1229 1227 -f 1240 1080 1063 -f 1240 1063 1228 -f 1228 1063 1229 -f 1239 1231 1240 -f 1240 1231 1080 -f 1238 1230 1239 -f 1239 1230 1231 -f 1077 1059 1232 -f 1232 1059 1238 -f 1238 1059 1230 -f 1077 1232 1056 -f 1056 1232 1233 -f 1056 1233 1055 -f 1055 1233 1053 -f 1053 1233 1234 -f 1053 1234 1235 -f 1656 1208 1234 -f 1234 1208 1235 -f 1560 1212 1541 -f 1657 1656 1211 -f 1211 1656 1234 -f 1211 1234 1236 -f 1236 1234 1233 -f 1236 1233 1243 -f 1243 1233 1232 -f 1243 1232 1245 -f 1245 1232 1238 -f 1245 1238 1237 -f 1237 1238 1239 -f 1237 1239 1248 -f 1248 1239 1240 -f 1248 1240 1241 -f 1241 1240 1228 -f 1241 1228 1212 -f 1212 1228 1226 -f 1212 1226 1541 -f 1541 1226 1536 -f 1653 1655 1242 -f 1242 1655 1211 -f 1242 1211 1250 -f 1250 1211 1236 -f 1250 1236 1244 -f 1244 1236 1243 -f 1244 1243 1252 -f 1252 1243 1245 -f 1252 1245 1246 -f 1246 1245 1237 -f 1246 1237 1247 -f 1247 1237 1248 -f 1247 1248 1256 -f 1256 1248 1241 -f 1256 1241 1257 -f 1257 1241 1212 -f 1257 1212 1542 -f 1545 1262 1258 -f 1649 1653 1260 -f 1260 1653 1242 -f 1260 1242 1249 -f 1249 1242 1250 -f 1249 1250 1251 -f 1251 1250 1244 -f 1251 1244 1261 -f 1261 1244 1252 -f 1261 1252 1253 -f 1253 1252 1246 -f 1253 1246 1254 -f 1254 1246 1247 -f 1254 1247 1255 -f 1255 1247 1256 -f 1255 1256 1262 -f 1262 1256 1257 -f 1262 1257 1258 -f 1258 1257 1542 -f 1651 1649 1259 -f 1259 1649 1260 -f 1259 1260 1266 -f 1266 1260 1249 -f 1266 1249 1267 -f 1267 1249 1251 -f 1267 1251 1268 -f 1268 1251 1261 -f 1268 1261 1269 -f 1269 1261 1253 -f 1269 1253 1270 -f 1270 1253 1254 -f 1270 1254 1271 -f 1271 1254 1255 -f 1271 1255 1263 -f 1263 1255 1262 -f 1263 1262 1544 -f 1544 1262 1545 -f 1647 1648 1264 -f 1264 1648 1259 -f 1264 1259 1265 -f 1265 1259 1266 -f 1265 1266 1274 -f 1274 1266 1267 -f 1274 1267 1275 -f 1275 1267 1268 -f 1275 1268 1277 -f 1277 1268 1269 -f 1277 1269 1278 -f 1278 1269 1270 -f 1278 1270 1280 -f 1280 1270 1271 -f 1280 1271 1281 -f 1281 1271 1263 -f 1281 1263 1544 -f 1272 1647 1284 -f 1284 1647 1264 -f 1284 1264 1285 -f 1285 1264 1265 -f 1285 1265 1273 -f 1273 1265 1274 -f 1273 1274 1276 -f 1276 1274 1275 -f 1276 1275 1289 -f 1289 1275 1277 -f 1289 1277 1290 -f 1290 1277 1278 -f 1290 1278 1279 -f 1279 1278 1280 -f 1279 1280 1291 -f 1291 1280 1281 -f 1291 1281 1546 -f 1546 1281 1210 -f 1282 1272 1283 -f 1283 1272 1284 -f 1283 1284 1295 -f 1295 1284 1285 -f 1295 1285 1296 -f 1296 1285 1273 -f 1296 1273 1286 -f 1286 1273 1276 -f 1286 1276 1287 -f 1287 1276 1289 -f 1287 1289 1288 -f 1288 1289 1290 -f 1288 1290 1297 -f 1297 1290 1279 -f 1297 1279 1209 -f 1209 1279 1291 -f 1209 1291 1292 -f 1292 1291 1546 -f 1293 1294 1299 -f 1299 1294 1283 -f 1299 1283 1301 -f 1301 1283 1295 -f 1301 1295 1303 -f 1303 1295 1296 -f 1303 1296 1304 -f 1304 1296 1286 -f 1304 1286 1305 -f 1305 1286 1287 -f 1305 1287 1306 -f 1306 1287 1288 -f 1306 1288 1307 -f 1307 1288 1297 -f 1307 1297 1298 -f 1298 1297 1209 -f 1298 1209 1550 -f 1550 1209 1548 -f 1309 1293 1300 -f 1300 1293 1299 -f 1300 1299 1310 -f 1310 1299 1301 -f 1310 1301 1302 -f 1302 1301 1303 -f 1302 1303 1312 -f 1312 1303 1304 -f 1312 1304 1313 -f 1313 1304 1305 -f 1313 1305 1316 -f 1316 1305 1306 -f 1316 1306 1317 -f 1317 1306 1307 -f 1317 1307 1319 -f 1319 1307 1298 -f 1319 1298 1308 -f 1308 1298 1550 -f 1646 1309 1322 -f 1322 1309 1300 -f 1322 1300 1323 -f 1323 1300 1310 -f 1323 1310 1324 -f 1324 1310 1302 -f 1324 1302 1326 -f 1326 1302 1312 -f 1326 1312 1311 -f 1311 1312 1313 -f 1311 1313 1314 -f 1314 1313 1316 -f 1314 1316 1315 -f 1315 1316 1317 -f 1315 1317 1328 -f 1328 1317 1319 -f 1328 1319 1318 -f 1318 1319 1308 -f 1221 1641 1320 -f 1320 1641 1322 -f 1320 1322 1321 -f 1321 1322 1323 -f 1321 1323 1225 -f 1225 1323 1324 -f 1225 1324 1325 -f 1325 1324 1326 -f 1325 1326 1215 -f 1215 1326 1311 -f 1215 1311 1327 -f 1327 1311 1314 -f 1327 1314 1218 -f 1218 1314 1315 -f 1218 1315 1219 -f 1219 1315 1328 -f 1219 1328 1554 -f 1554 1328 1551 -f 1337 1338 1331 -f 1329 1331 1338 -f 1329 1338 1332 -f 1329 1332 1468 -f 1330 1380 1339 -f 1336 1379 1330 -f 1330 1379 1380 -f 1335 1378 1383 -f 1329 1424 1331 -f 1331 1424 1385 -f 1207 1468 1333 -f 1333 1468 1332 -f 1333 1332 1334 -f 1334 1332 1338 -f 1334 1338 1205 -f 1385 1378 1331 -f 1331 1378 1335 -f 1331 1335 1337 -f 1337 1335 1383 -f 1337 1383 1336 -f 1336 1383 1379 -f 1336 1340 1337 -f 1337 1340 1202 -f 1337 1202 1338 -f 1338 1202 1204 -f 1338 1204 1205 -f 1339 1197 1330 -f 1330 1197 1198 -f 1330 1198 1336 -f 1336 1198 1200 -f 1336 1200 1340 -f 1341 1347 1342 -f 1349 1343 1220 -f 1349 1344 677 -f 677 1344 678 -f 1350 680 1344 -f 1344 680 678 -f 1351 1346 1345 -f 1351 1345 1350 -f 1350 1345 680 -f 686 1342 1347 -f 686 1347 706 -f 1346 1351 1342 -f 1342 1351 1348 -f 1342 1348 1341 -f 1344 1349 1357 -f 1344 1357 1350 -f 1350 1357 1358 -f 1350 1358 1351 -f 1351 1358 1353 -f 1351 1353 1348 -f 1359 1352 1353 -f 1353 1352 1348 -f 1357 1349 1363 -f 1357 1363 1358 -f 1358 1363 1355 -f 1358 1355 1353 -f 1353 1355 1354 -f 1355 1363 1356 -f 1355 1356 1354 -f 1354 1356 1365 -f 1359 1353 1354 -f 1359 1354 1360 -f 1360 1354 1365 -f 1805 1807 1365 -f 1365 1807 1360 -f 1220 1474 1349 -f 1349 1474 1361 -f 1349 1361 1362 -f 1363 1349 1362 -f 1363 1362 1356 -f 1356 1362 1364 -f 1356 1364 1365 -f 1365 1364 1478 -f 1365 1478 1805 -f 1805 1478 1476 -f 1367 422 1370 -f 424 1368 1405 -f 1370 422 1405 -f 1405 422 423 -f 1405 423 424 -f 1369 1366 1370 -f 1370 1366 394 -f 1370 394 1367 -f 1373 1371 1369 -f 1369 1371 391 -f 1369 391 1366 -f 388 1374 1372 -f 1372 1374 1373 -f 1373 1374 389 -f 1373 389 1371 -f 388 1372 1376 -f 1376 1372 1375 -f 1376 1375 1377 -f 1377 1375 1408 -f 1377 1408 517 -f 1380 1381 1339 -f 1393 1381 1390 -f 1390 1381 1380 -f 1390 1380 1382 -f 1382 1380 1379 -f 1382 1379 1389 -f 1389 1379 1383 -f 1389 1383 1388 -f 1388 1383 1378 -f 1388 1378 1384 -f 1384 1378 1385 -f 1384 1385 1707 -f 1707 1385 1424 -f 1707 1386 1384 -f 1384 1386 1399 -f 1384 1399 1388 -f 1388 1399 1387 -f 1388 1387 1389 -f 1389 1387 1401 -f 1389 1401 1382 -f 1382 1401 1402 -f 1382 1402 1390 -f 1390 1402 1403 -f 1390 1403 1393 -f 1718 1391 1403 -f 1403 1391 1392 -f 1403 1392 1393 -f 1705 1410 1394 -f 1394 1410 1409 -f 1394 1409 1400 -f 1400 1409 1396 -f 1400 1396 1395 -f 1395 1396 1407 -f 1395 1407 1397 -f 1397 1407 1406 -f 1397 1406 1398 -f 1398 1406 1404 -f 1386 1705 1399 -f 1399 1705 1394 -f 1399 1394 1387 -f 1387 1394 1400 -f 1387 1400 1401 -f 1401 1400 1395 -f 1401 1395 1402 -f 1402 1395 1397 -f 1402 1397 1403 -f 1403 1397 1398 -f 1403 1398 1718 -f 1718 1398 1404 -f 1718 1404 1720 -f 1720 1404 1708 -f 1405 1708 1370 -f 1370 1708 1404 -f 1370 1404 1369 -f 1369 1404 1406 -f 1369 1406 1373 -f 1373 1406 1407 -f 1373 1407 1372 -f 1372 1407 1396 -f 1372 1396 1375 -f 1375 1396 1409 -f 1375 1409 1408 -f 1408 1409 1410 -f 623 1411 1412 -f 1413 620 1471 -f 1417 619 620 -f 1415 1414 619 -f 1415 619 1416 -f 1468 1207 1418 -f 1425 1329 1468 -f 1468 1418 1419 -f 1419 1418 1420 -f 1419 1420 1467 -f 1467 1420 1421 -f 1467 1421 1423 -f 1423 1421 1422 -f 1423 1422 1429 -f 1424 1329 1703 -f 1703 1329 1425 -f 1703 1425 1426 -f 1426 1425 1466 -f 1426 1466 1706 -f 1706 1466 1465 -f 1706 1465 1427 -f 1427 1465 1464 -f 1427 1464 1428 -f 1422 1654 1429 -f 1429 1654 1652 -f 1429 1652 1463 -f 1463 1652 1650 -f 1463 1650 1461 -f 1461 1650 1432 -f 1428 1464 1702 -f 1702 1464 1462 -f 1702 1462 1696 -f 1696 1462 1460 -f 1696 1460 1430 -f 1430 1460 1700 -f 1431 1435 1432 -f 1432 1435 1461 -f 1700 1460 1433 -f 1433 1460 1434 -f 1433 1434 1699 -f 1699 1434 1459 -f 1699 1459 1693 -f 1431 1436 1435 -f 1435 1436 1438 -f 1435 1438 1437 -f 1437 1438 1440 -f 1439 1458 1440 -f 1440 1458 1441 -f 1440 1441 1437 -f 1693 1459 1695 -f 1695 1459 1442 -f 1695 1442 1692 -f 1692 1442 1457 -f 1692 1457 1690 -f 1690 1457 1450 -f 1690 1450 1448 -f 1439 1443 1458 -f 1458 1443 1445 -f 1458 1445 1444 -f 1444 1445 1447 -f 1645 1446 1447 -f 1447 1446 1456 -f 1447 1456 1444 -f 1448 1450 1449 -f 1449 1450 1455 -f 1449 1455 1685 -f 1685 1455 1454 -f 1685 1454 1469 -f 1645 1451 1446 -f 1446 1451 1452 -f 1446 1452 1453 -f 1453 1452 1416 -f 1453 1416 1417 -f 1417 1416 619 -f 620 1413 1417 -f 1417 1413 1470 -f 1417 1470 1453 -f 1453 1470 1454 -f 1453 1454 1446 -f 1446 1454 1455 -f 1446 1455 1456 -f 1456 1455 1450 -f 1456 1450 1444 -f 1444 1450 1457 -f 1444 1457 1458 -f 1458 1457 1442 -f 1458 1442 1441 -f 1441 1442 1459 -f 1441 1459 1437 -f 1437 1459 1434 -f 1437 1434 1435 -f 1435 1434 1460 -f 1435 1460 1461 -f 1461 1460 1462 -f 1461 1462 1463 -f 1463 1462 1464 -f 1463 1464 1429 -f 1429 1464 1465 -f 1429 1465 1423 -f 1423 1465 1466 -f 1423 1466 1467 -f 1467 1466 1425 -f 1467 1425 1419 -f 1419 1425 1468 -f 1469 1454 1689 -f 1689 1454 1470 -f 1689 1470 1688 -f 1688 1470 1413 -f 1688 1413 1412 -f 1412 1413 1471 -f 1412 1471 623 -f 1364 1362 1489 -f 1489 1362 1361 -f 1478 1364 1490 -f 1492 1473 1472 -f 1472 1473 1552 -f 1552 1473 1489 -f 1552 1489 1553 -f 1553 1489 1361 -f 1553 1361 1474 -f 1472 1555 1492 -f 1492 1555 1475 -f 1492 1475 1493 -f 1493 1475 1499 -f 1476 1478 1477 -f 1477 1478 1490 -f 1477 1490 1479 -f 1479 1490 1491 -f 1479 1491 1480 -f 1480 1491 1481 -f 1481 1491 1482 -f 1481 1482 1832 -f 1832 1482 1494 -f 1832 1494 1833 -f 1833 1494 1483 -f 1483 1494 1484 -f 1483 1484 1485 -f 1485 1484 1487 -f 1485 1487 1486 -f 1486 1487 1498 -f 1486 1498 1488 -f 1364 1489 1490 -f 1490 1489 1473 -f 1490 1473 1491 -f 1491 1473 1492 -f 1491 1492 1482 -f 1482 1492 1493 -f 1482 1493 1494 -f 1494 1493 1495 -f 1494 1495 1484 -f 1484 1495 1496 -f 1484 1496 1487 -f 1487 1496 1503 -f 1487 1503 1498 -f 1498 1503 1497 -f 1498 1497 1505 -f 1488 1498 1504 -f 1504 1498 1505 -f 1493 1499 1500 -f 1493 1500 1495 -f 1495 1500 1501 -f 1495 1501 1496 -f 1496 1501 1502 -f 1496 1502 1503 -f 1503 1502 1557 -f 1503 1557 1497 -f 1509 1504 1510 -f 1510 1504 1505 -f 1510 1505 1513 -f 1513 1505 1497 -f 1513 1497 1557 -f 1513 1557 1556 -f 1508 1507 1506 -f 1506 1507 1595 -f 1598 1595 1511 -f 1511 1595 1507 -f 1511 1507 1512 -f 1512 1507 1508 -f 1509 1510 1828 -f 1828 1510 1511 -f 1828 1511 1830 -f 1830 1511 1512 -f 1556 1598 1513 -f 1513 1598 1511 -f 1513 1511 1510 -f 915 1601 1575 -f 758 754 1586 -f 1586 754 745 -f 1586 745 1515 -f 1515 743 1586 -f 1586 743 741 -f 778 736 1594 -f 1594 736 764 -f 764 1516 1594 -f 1594 1516 759 -f 1594 759 1517 -f 1517 759 758 -f 1520 1518 1594 -f 1594 1518 912 -f 1594 912 778 -f 1592 1519 898 -f 1592 898 1520 -f 1520 898 897 -f 1520 897 1518 -f 1519 1592 863 -f 863 1592 1522 -f 863 1522 864 -f 1524 1521 1523 -f 1524 1523 1522 -f 1522 1523 773 -f 1522 773 864 -f 1590 1526 1524 -f 1524 1526 841 -f 1524 841 1521 -f 774 1525 1587 -f 1587 1525 1590 -f 1590 1525 842 -f 1590 842 1526 -f 1527 969 1577 -f 1577 969 1530 -f 1528 1579 775 -f 775 1579 1577 -f 775 1577 1529 -f 1529 1577 1530 -f 1531 1532 1577 -f 1577 1532 1527 -f 1535 1576 1568 -f 1567 1533 1568 -f 1568 1533 977 -f 1568 977 1534 -f 1568 1534 1535 -f 1536 1537 1540 -f 1540 1537 1538 -f 1538 981 1540 -f 1540 981 1539 -f 1536 1540 1541 -f 1541 1540 1569 -f 1541 1569 1560 -f 1542 1559 1258 -f 1258 1559 1561 -f 1258 1561 1545 -f 1210 1544 1543 -f 1543 1544 1561 -f 1561 1544 1545 -f 1210 1543 1546 -f 1546 1543 1547 -f 1546 1547 1292 -f 1292 1547 1548 -f 1548 1547 1549 -f 1548 1549 1550 -f 1565 1308 1549 -f 1549 1308 1550 -f 1566 1554 1551 -f 1566 1551 1565 -f 1565 1551 1318 -f 1565 1318 1308 -f 1552 1553 1566 -f 1566 1553 1474 -f 1474 1220 1566 -f 1220 1554 1566 -f 1499 1475 1514 -f 1514 1475 1555 -f 1514 1555 1566 -f 1566 1555 1472 -f 1566 1472 1552 -f 1556 1557 1558 -f 1557 1502 1558 -f 1558 1502 1501 -f 1558 1501 1500 -f 1542 1560 1559 -f 1559 1560 1569 -f 1559 1569 1561 -f 1561 1569 1562 -f 1561 1562 1543 -f 1543 1562 1563 -f 1543 1563 1547 -f 1547 1563 1572 -f 1547 1572 1549 -f 1549 1572 1564 -f 1549 1564 1565 -f 1565 1564 1573 -f 1565 1573 1566 -f 1566 1573 1574 -f 1566 1574 1514 -f 1514 1574 1558 -f 1514 1558 1499 -f 1499 1558 1500 -f 1539 1567 1540 -f 1540 1567 1568 -f 1540 1568 1569 -f 1569 1568 1578 -f 1569 1578 1562 -f 1562 1578 1570 -f 1562 1570 1563 -f 1563 1570 1580 -f 1563 1580 1572 -f 1572 1580 1571 -f 1572 1571 1564 -f 1564 1571 1582 -f 1564 1582 1573 -f 1573 1582 1583 -f 1573 1583 1574 -f 1574 1583 1585 -f 1574 1585 1558 -f 1558 1585 1575 -f 1558 1575 1556 -f 1556 1575 1601 -f 1576 1531 1568 -f 1568 1531 1577 -f 1568 1577 1578 -f 1578 1577 1579 -f 1578 1579 1570 -f 1570 1579 1588 -f 1570 1588 1580 -f 1580 1588 1589 -f 1580 1589 1571 -f 1571 1589 1581 -f 1571 1581 1582 -f 1582 1581 1591 -f 1582 1591 1583 -f 1583 1591 1584 -f 1583 1584 1585 -f 1585 1584 1593 -f 1585 1593 1575 -f 1575 1593 1586 -f 1575 1586 915 -f 915 1586 741 -f 1528 774 1579 -f 1579 774 1587 -f 1579 1587 1588 -f 1588 1587 1590 -f 1588 1590 1589 -f 1589 1590 1524 -f 1589 1524 1581 -f 1581 1524 1522 -f 1581 1522 1591 -f 1591 1522 1592 -f 1591 1592 1584 -f 1584 1592 1520 -f 1584 1520 1593 -f 1593 1520 1594 -f 1593 1594 1586 -f 1586 1594 1517 -f 1586 1517 758 -f 1601 1597 1556 -f 1556 1597 1598 -f 1508 1506 1596 -f 1596 1506 1595 -f 1596 1595 1597 -f 1597 1595 1598 -f 918 914 1596 -f 1596 914 1508 -f 918 1596 1599 -f 1599 1596 1597 -f 1599 1597 1600 -f 1600 1597 1601 -f 1600 1601 915 -f 1607 1602 1606 -f 1634 1635 1603 -f 1603 1635 1604 -f 1603 1604 267 -f 267 1604 1605 -f 1605 1604 435 -f 1605 435 1606 -f 1606 435 497 -f 1606 497 1607 -f 1602 1607 1608 -f 1608 1607 1609 -f 1608 1609 494 -f 504 1610 494 -f 494 1610 193 -f 494 193 1608 -f 1612 1611 1610 -f 1612 1610 1613 -f 1613 1610 504 -f 1611 1612 192 -f 192 1612 1614 -f 192 1614 1615 -f 474 189 483 -f 483 189 1615 -f 483 1615 482 -f 482 1615 1614 -f 367 293 526 -f 526 293 174 -f 523 526 439 -f 439 526 174 -f 439 174 458 -f 458 174 179 -f 458 179 1616 -f 1616 179 1617 -f 1616 1617 465 -f 465 1617 1618 -f 465 1618 1619 -f 1619 1618 184 -f 1619 184 1620 -f 1620 184 182 -f 1620 182 474 -f 474 182 181 -f 474 181 189 -f 367 526 1621 -f 1621 526 1622 -f 1621 1622 1624 -f 1622 1623 1624 -f 1624 1623 534 -f 1624 534 1625 -f 1625 534 1627 -f 1625 1627 1626 -f 1626 1627 532 -f 1626 532 371 -f 371 532 540 -f 371 540 1628 -f 1628 540 539 -f 1628 539 1629 -f 1629 539 538 -f 1629 538 374 -f 374 538 546 -f 374 546 375 -f 375 546 1630 -f 1630 546 1631 -f 1630 1631 1632 -f 1631 549 1632 -f 1632 549 544 -f 1632 544 383 -f 383 544 545 -f 383 545 366 -f 392 260 1637 -f 392 1637 1633 -f 1634 261 1635 -f 1635 261 1636 -f 260 392 261 -f 261 392 1636 -f 258 301 1637 -f 1637 301 1638 -f 1637 1638 1633 -f 1642 713 1415 -f 1415 713 714 -f 1415 714 1640 -f 1640 708 160 -f 1414 1415 1639 -f 1639 1415 1640 -f 1639 1640 618 -f 618 1640 160 -f 1221 1415 1416 -f 1416 1452 1221 -f 1221 1452 1451 -f 1221 1451 1641 -f 1641 1451 1645 -f 1641 1645 1646 -f 1642 1415 1643 -f 1643 1415 1221 -f 1643 1221 1644 -f 1447 1293 1645 -f 1645 1293 1309 -f 1645 1309 1646 -f 1447 1445 1293 -f 1293 1445 1443 -f 1293 1443 1294 -f 1294 1443 1439 -f 1294 1439 1282 -f 1440 1438 1647 -f 1647 1438 1436 -f 1647 1436 1648 -f 1440 1647 1439 -f 1439 1647 1272 -f 1439 1272 1282 -f 1436 1431 1648 -f 1648 1431 1432 -f 1648 1432 1650 -f 1653 1649 1650 -f 1650 1649 1651 -f 1650 1651 1648 -f 1650 1652 1653 -f 1653 1652 1654 -f 1653 1654 1655 -f 1655 1654 1422 -f 1655 1422 1421 -f 1421 1420 1655 -f 1655 1420 1418 -f 1655 1418 1657 -f 1207 1208 1418 -f 1418 1208 1656 -f 1418 1656 1657 -f 1094 1660 789 -f 789 1660 673 -f 1658 668 1659 -f 1659 668 672 -f 1659 672 636 -f 636 672 1095 -f 1095 672 1660 -f 1660 672 671 -f 1660 671 670 -f 670 1661 1660 -f 1660 1661 1662 -f 1660 1662 673 -f 905 1663 900 -f 900 1663 1664 -f 900 1664 789 -f 789 1664 1665 -f 789 1665 1094 -f 905 890 1663 -f 1663 890 772 -f 1663 772 1668 -f 874 1666 1667 -f 1667 1666 1128 -f 1667 1128 772 -f 772 1128 1130 -f 772 1130 1668 -f 874 888 1666 -f 1666 888 1671 -f 1666 1671 1120 -f 1120 1671 1669 -f 856 1670 1671 -f 1671 1670 1672 -f 1671 1672 1669 -f 856 1673 1670 -f 1670 1673 830 -f 1670 830 829 -f 1674 1118 829 -f 829 1118 1675 -f 829 1675 1670 -f 1674 829 1676 -f 1676 829 827 -f 1676 827 828 -f 828 818 1676 -f 1676 818 1678 -f 1676 1678 1677 -f 1677 1678 1112 -f 953 1105 1678 -f 1678 1105 1104 -f 1678 1104 1112 -f 1683 1680 1679 -f 1679 1680 625 -f 1683 624 1681 -f 1683 1682 1680 -f 1683 1681 1682 -f 1469 1684 1685 -f 1685 1684 1686 -f 1685 1686 1449 -f 625 1680 1687 -f 1687 1680 587 -f 1687 587 1411 -f 1411 587 1412 -f 1412 587 586 -f 1412 586 1688 -f 1688 586 585 -f 1688 585 1689 -f 1689 585 562 -f 1689 562 1469 -f 1469 562 561 -f 1469 561 1684 -f 552 1690 559 -f 559 1690 1448 -f 1449 1686 1448 -f 1448 1686 1691 -f 1448 1691 559 -f 551 1695 552 -f 552 1695 1692 -f 552 1692 1690 -f 1698 1693 1694 -f 1694 1693 1695 -f 1694 1695 444 -f 444 1695 551 -f 475 1702 1696 -f 1697 1433 1698 -f 1698 1433 1699 -f 1698 1699 1693 -f 1696 1430 475 -f 475 1430 1700 -f 475 1700 466 -f 466 1700 1433 -f 466 1433 459 -f 459 1433 1697 -f 1706 1427 488 -f 488 1427 1428 -f 488 1428 489 -f 489 1428 1702 -f 489 1702 1701 -f 1701 1702 475 -f 1408 488 512 -f 512 515 1408 -f 1408 515 1704 -f 1408 1704 517 -f 1408 1410 488 -f 488 1410 1705 -f 488 1705 1386 -f 1706 488 1426 -f 1426 488 1386 -f 1426 1386 1703 -f 1703 1386 1707 -f 1703 1707 1424 -f 1368 1713 1405 -f 1405 1713 1709 -f 1405 1709 1708 -f 1708 1709 975 -f 1708 975 1719 -f 1710 1712 1711 -f 1711 1712 1714 -f 1711 1714 1713 -f 1713 1714 1715 -f 1713 1715 1709 -f 1716 1391 1717 -f 1717 1391 1718 -f 1717 1718 1719 -f 1719 1718 1720 -f 1719 1720 1708 -f 1723 1721 1339 -f 1381 1393 1722 -f 1381 1722 1339 -f 1339 1722 1038 -f 1339 1038 1723 -f 1716 1035 1391 -f 1391 1035 1722 -f 1391 1722 1392 -f 1392 1722 1393 -f 1724 1725 1174 -f 1174 1725 1726 -f 1174 1726 1189 -f 1189 1726 1728 -f 1189 1728 1727 -f 1727 1728 971 -f 1727 971 1150 -f 1150 971 973 -f 1150 973 1151 -f 1151 973 1712 -f 1151 1712 1729 -f 1729 1712 1710 -f 1731 1730 1732 -f 1174 1182 1724 -f 1724 1182 1183 -f 1724 1183 967 -f 967 1183 1731 -f 967 1731 966 -f 966 1731 1732 -f 1121 1116 177 -f 1733 1734 630 -f 1735 629 630 -f 1735 630 1734 -f 630 1736 1733 -f 1733 1736 1738 -f 1733 1738 1737 -f 1737 1738 1739 -f 1737 1739 1740 -f 1737 1740 1741 -f 1741 1740 1135 -f 1741 1135 1742 -f 1742 1135 1134 -f 1742 1134 1133 -f 1745 323 1132 -f 1132 323 1743 -f 1132 1743 1133 -f 1133 1743 332 -f 1133 332 1742 -f 1132 1744 1745 -f 1745 1744 1746 -f 1745 1746 316 -f 316 1746 1747 -f 316 1747 315 -f 315 1747 314 -f 1121 177 1748 -f 1747 1126 314 -f 314 1126 1749 -f 314 1749 288 -f 1748 177 1125 -f 1125 177 176 -f 1125 176 1749 -f 1749 176 175 -f 1749 175 288 -f 1752 1114 1750 -f 1750 1114 1751 -f 1750 1751 1113 -f 1750 1753 1752 -f 1752 1753 1754 -f 1752 1754 1116 -f 1116 1754 185 -f 1116 185 177 -f 1758 1757 1107 -f 1107 1757 190 -f 1107 190 1113 -f 1113 190 1755 -f 1113 1755 1750 -f 222 1757 1760 -f 1760 1757 1756 -f 1175 1756 1099 -f 1099 1756 1757 -f 1099 1757 1101 -f 1101 1757 1758 -f 287 1759 1760 -f 1760 1759 225 -f 1760 225 222 -f 1761 1169 1099 -f 1099 1169 1762 -f 1099 1762 1175 -f 1681 1763 1764 -f 1764 1763 9490 -f 1764 9490 1765 -f 9493 1766 9490 -f 9490 1766 1765 -f 1767 609 608 -f 1767 608 9493 -f 9493 608 1766 -f 609 1767 612 -f 612 1767 1768 -f 612 1768 1769 -f 1769 1768 9492 -f 1769 9492 1772 -f 1770 1778 1781 -f 600 602 9506 -f 9506 602 1771 -f 9506 1771 605 -f 605 607 9506 -f 9506 607 1772 -f 9506 1772 9492 -f 528 524 1774 -f 1774 524 1773 -f 1774 1773 1775 -f 1775 557 1774 -f 1774 557 1776 -f 1774 1776 9506 -f 9506 1776 1777 -f 9506 1777 600 -f 1781 1778 1774 -f 1774 1778 529 -f 1774 529 528 -f 1785 543 542 -f 542 1779 1785 -f 1785 1779 1780 -f 1785 1780 1781 -f 1781 1780 537 -f 1781 537 1770 -f 384 1782 1783 -f 1783 1782 1786 -f 384 383 1782 -f 1782 383 366 -f 1782 366 1784 -f 1784 366 545 -f 1784 545 1785 -f 1785 545 543 -f 1786 1782 1787 -f 1787 1782 1789 -f 1787 1789 1791 -f 368 369 1794 -f 1794 369 1788 -f 1794 1788 1789 -f 1789 1788 1790 -f 1789 1790 1791 -f 322 1794 1792 -f 1792 1794 1795 -f 1792 1795 334 -f 1793 368 320 -f 320 368 1794 -f 320 1794 319 -f 319 1794 322 -f 337 336 1795 -f 1795 336 335 -f 1795 335 334 -f 9495 433 1795 -f 1795 433 1796 -f 1795 1796 337 -f 1804 1802 1797 -f 1801 1798 1800 -f 629 9485 630 -f 630 9485 1801 -f 630 1801 1799 -f 1799 1801 1800 -f 1797 1802 1801 -f 1801 1802 1798 -f 1798 1802 1803 -f 1803 1096 1798 -f 9484 1658 1797 -f 1797 1658 635 -f 1797 635 1804 -f 1476 1836 1805 -f 1805 1836 1806 -f 9583 1352 1359 -f 1359 1360 9583 -f 9583 1360 1807 -f 9583 1807 1806 -f 1806 1807 1805 -f 1352 9583 1808 -f 1352 1808 1348 -f 1811 1809 1810 -f 1809 706 1810 -f 1810 706 1347 -f 1810 1347 1808 -f 1808 1347 1341 -f 1808 1341 1348 -f 696 697 1810 -f 1810 697 1811 -f 1814 693 1810 -f 1810 693 1812 -f 1812 694 1810 -f 1810 694 695 -f 1810 695 696 -f 2210 693 1813 -f 1813 693 1814 -f 1813 1814 1838 -f 2213 689 1815 -f 2210 2209 693 -f 693 2209 2213 -f 693 2213 1815 -f 689 2213 1816 -f 1816 2213 2212 -f 2212 2216 1816 -f 1816 2216 1817 -f 1816 1817 716 -f 716 1817 711 -f 711 1817 2217 -f 2218 2206 708 -f 708 1640 2218 -f 2218 1640 710 -f 2218 710 2217 -f 2217 710 709 -f 2217 709 711 -f 751 1821 1825 -f 9452 760 738 -f 738 769 9452 -f 9452 769 1818 -f 9452 1818 1819 -f 1819 1818 1820 -f 1819 1820 728 -f 1825 1821 1823 -f 1823 1821 1822 -f 1823 1822 750 -f 750 749 1823 -f 1823 749 752 -f 1823 752 9452 -f 9452 752 755 -f 9452 755 760 -f 913 1824 1827 -f 1827 1824 1826 -f 1827 1826 1825 -f 1825 1826 920 -f 1825 920 751 -f 1512 1508 1829 -f 1829 1508 1827 -f 1827 1508 913 -f 1504 1509 1831 -f 1831 1509 1828 -f 1831 1828 1829 -f 1829 1828 1830 -f 1829 1830 1512 -f 1485 1486 1834 -f 1834 1486 1488 -f 1834 1488 1831 -f 1831 1488 1504 -f 1481 1835 1480 -f 1480 1835 1479 -f 1481 1832 1835 -f 1835 1832 1833 -f 1835 1833 1834 -f 1834 1833 1483 -f 1834 1483 1485 -f 1479 1835 1477 -f 1477 1835 1836 -f 1477 1836 1476 -f 1735 1837 629 -f 629 1837 9485 -f 1838 2211 2208 -f 2208 2210 1838 -f 1838 2210 1813 -f 1839 9474 1840 -f 1839 1840 9456 -f 1839 9456 1841 -f 1841 1842 1919 -f 1919 1842 9466 -f 1919 9466 1920 -f 1920 9466 1843 -f 1920 1843 9481 -f 1920 9481 1921 -f 1921 9481 9468 -f 1921 9468 9597 -f 1921 9597 1922 -f 1922 9597 1844 -f 1922 1844 1923 -f 1923 1844 9473 -f 1923 9473 1937 -f 1937 9473 1846 -f 1937 1846 1935 -f 1935 1846 1847 -f 1935 1847 1850 -f 1850 1847 1849 -f 9491 9455 1848 -f 1848 1931 9491 -f 9491 1931 1932 -f 9491 1932 1849 -f 1849 1932 1933 -f 1849 1933 1850 -f 1851 1845 9587 -f 9587 1845 9455 -f 9455 1845 1848 -f 2178 1845 1851 -f 1851 157 2178 -f 2211 1838 1853 -f 1852 1918 1853 -f 1853 1918 2211 -f 1916 1915 1854 -f 1854 1915 1852 -f 1852 1915 1918 -f 1916 1854 1917 -f 1917 1854 1855 -f 1917 1855 9474 -f 1917 9474 1839 -f 1873 1856 1857 -f 1873 1857 9596 -f 9596 9461 1858 -f 1858 9602 1890 -f 1890 9602 9601 -f 1890 9601 1893 -f 1893 9601 1859 -f 1893 1859 9606 -f 1893 9606 1894 -f 1894 9606 9608 -f 1894 9608 1860 -f 1860 1861 1895 -f 1895 1861 1862 -f 1895 1862 1863 -f 1895 1863 1891 -f 1891 1863 1904 -f 1904 1863 9450 -f 1904 9450 1892 -f 2066 1892 9595 -f 9595 1892 9450 -f 2087 1864 1865 -f 1865 1866 2087 -f 1969 1968 2199 -f 1941 1969 1909 -f 1866 1865 1867 -f 1866 1867 1885 -f 1885 1867 1868 -f 1885 1868 1884 -f 1884 1868 1869 -f 1884 1869 1886 -f 1886 1869 1870 -f 1871 1880 1870 -f 1870 1880 1883 -f 1870 1883 1886 -f 1880 1871 1888 -f 1888 1871 1872 -f 1888 1872 1856 -f 1888 1856 1873 -f 1875 2090 2089 -f 1975 1878 1876 -f 1876 1881 1974 -f 1974 1881 1877 -f 1878 1879 1876 -f 1876 1879 1881 -f 1881 1874 1877 -f 1877 1874 1889 -f 1877 1889 1970 -f 1874 1881 1880 -f 1880 1881 1887 -f 1896 1874 1888 -f 1888 1874 1880 -f 1875 1882 2090 -f 2090 1882 1878 -f 1878 1882 1887 -f 1878 1887 1879 -f 1879 1887 1881 -f 1874 1896 1889 -f 1875 1886 1882 -f 1882 1886 1887 -f 1866 1885 2089 -f 2089 1885 1884 -f 2089 1884 1875 -f 1875 1884 1886 -f 1886 1883 1887 -f 1887 1883 1880 -f 1888 1873 1896 -f 1896 1873 9596 -f 1896 9596 1897 -f 1897 9596 1858 -f 1897 1858 1890 -f 1891 1904 1902 -f 1902 1904 1903 -f 1894 1860 1899 -f 1899 1860 1895 -f 1895 1891 1902 -f 1889 1896 1897 -f 1897 1890 1898 -f 1898 1890 1893 -f 1898 1893 1894 -f 1898 1894 1899 -f 1899 1895 1902 -f 1970 1889 1897 -f 1970 1897 1898 -f 1971 1898 1899 -f 1971 1899 1902 -f 1902 1901 1972 -f 1973 1972 1901 -f 1973 1901 1900 -f 1900 1902 2063 -f 1902 1900 1901 -f 2063 1902 1903 -f 2063 1903 1905 -f 1905 1903 1904 -f 1905 1904 2066 -f 2066 1904 1892 -f 1917 1912 1916 -f 2214 2211 1913 -f 2214 1913 1907 -f 1908 1909 1924 -f 1924 1909 1911 -f 1924 1911 1912 -f 1909 1910 1911 -f 1911 1910 1914 -f 1911 1914 1912 -f 1910 2207 1907 -f 1910 1907 1914 -f 1914 1907 1906 -f 1907 1913 1906 -f 1906 1916 1914 -f 1914 1916 1912 -f 1839 1912 1917 -f 2211 1918 1913 -f 1913 1918 1915 -f 1913 1915 1906 -f 1906 1915 1916 -f 1924 1912 1839 -f 1839 1841 1926 -f 1926 1841 1919 -f 1924 1839 1926 -f 1921 1922 1929 -f 1929 1922 1923 -f 1929 1923 1925 -f 1926 1919 1927 -f 1927 1919 1920 -f 1927 1920 1921 -f 1927 1921 1929 -f 1908 1924 1928 -f 1928 1924 1926 -f 1928 1926 1927 -f 1928 1927 1929 -f 1928 1929 1925 -f 1928 1925 1941 -f 2185 1968 1934 -f 1934 1930 2184 -f 2178 2181 1848 -f 2178 1848 1845 -f 2181 1930 1848 -f 1848 1930 1931 -f 1930 1934 1933 -f 1930 1933 1931 -f 1931 1933 1932 -f 1850 1933 1936 -f 1936 1933 1934 -f 1936 1934 1968 -f 1935 1850 1938 -f 1938 1850 1936 -f 1938 1936 1939 -f 1939 1936 1968 -f 1939 1968 1969 -f 1937 1935 1940 -f 1940 1935 1938 -f 1940 1938 1939 -f 1940 1939 1941 -f 1941 1939 1969 -f 1940 1941 1925 -f 1940 1925 1923 -f 1940 1923 1937 -f 1942 2044 2137 -f 1942 2137 1943 -f 1944 9470 1945 -f 1944 1945 2035 -f 2035 1945 9467 -f 2035 9467 2038 -f 2038 9467 1946 -f 2038 1946 9609 -f 2038 9609 2036 -f 2036 9609 9465 -f 2036 9465 2037 -f 2037 9465 1947 -f 2037 1947 2039 -f 2039 1947 9462 -f 2039 9462 2040 -f 2040 9462 1948 -f 2040 1948 1949 -f 2040 1949 2032 -f 2032 1949 9471 -f 1952 2022 9471 -f 9471 2022 2032 -f 1953 2018 1950 -f 1950 2018 9460 -f 2018 1951 9460 -f 9460 1951 9458 -f 9458 1951 2021 -f 9458 2021 1952 -f 1952 2021 2022 -f 1953 143 141 -f 1953 141 2018 -f 2044 1942 9546 -f 9451 2059 9546 -f 9546 2059 2044 -f 1954 2058 9451 -f 9451 2058 2059 -f 1956 2054 9459 -f 2054 2056 9459 -f 9459 2056 2055 -f 9459 2055 1955 -f 1955 2055 2057 -f 1955 2057 1954 -f 1954 2057 2058 -f 2054 1956 2053 -f 2053 1956 9472 -f 2053 9472 9470 -f 2053 9470 1944 -f 131 2124 9589 -f 9589 2124 1961 -f 9475 1957 2098 -f 2098 1957 2014 -f 1957 9475 1958 -f 1957 1958 2015 -f 2015 1958 2000 -f 2000 1958 9600 -f 2000 9600 2001 -f 2001 9600 9599 -f 2001 9599 2002 -f 2002 9599 9605 -f 2002 9605 2003 -f 2003 9605 9604 -f 2003 9604 9598 -f 2003 9598 2004 -f 2004 9598 1959 -f 2004 1959 1997 -f 1997 1959 9603 -f 1997 9603 1960 -f 1997 1960 2005 -f 2005 1960 9453 -f 2005 9453 9469 -f 2005 9469 1998 -f 1998 9469 1999 -f 1999 9469 9457 -f 1999 9457 1963 -f 1963 9457 1962 -f 1964 1986 1962 -f 1962 1986 1963 -f 1965 1979 1964 -f 1964 1979 1986 -f 9592 9477 1967 -f 1967 1983 9592 -f 9592 1983 9480 -f 9480 1983 1980 -f 9480 1980 1965 -f 1965 1980 1979 -f 9589 1961 1966 -f 1966 1961 9477 -f 9477 1961 1967 -f 1968 2185 2199 -f 1908 1928 1941 -f 1908 1941 1909 -f 1909 1969 1910 -f 1910 1969 2199 -f 1972 1973 1877 -f 1970 1898 1971 -f 1902 1972 1971 -f 1972 1970 1971 -f 2199 2207 1910 -f 1970 1972 1877 -f 1973 1974 1877 -f 1973 1876 1974 -f 2007 2009 2012 -f 1973 1975 1876 -f 2011 2007 2013 -f 1993 2013 2012 -f 2007 2012 2013 -f 2011 2013 1992 -f 2104 2011 1992 -f 2104 1992 1988 -f 2104 1988 1989 -f 1977 2033 1976 -f 1976 2028 1977 -f 2047 1977 2026 -f 1977 2028 2026 -f 2047 2027 1978 -f 2104 1989 1981 -f 2046 2047 1978 -f 2047 2026 2027 -f 2161 2046 1978 -f 1978 2027 2025 -f 1981 1989 1985 -f 1985 1982 2132 -f 2124 2125 1967 -f 2124 1967 1961 -f 2125 1982 1967 -f 1967 1982 1983 -f 1982 1985 1984 -f 1982 1984 1980 -f 1982 1980 1983 -f 1979 1980 1984 -f 1979 1984 1987 -f 1987 1984 1985 -f 1987 1985 1989 -f 1986 1979 1990 -f 1990 1979 1987 -f 1990 1987 1991 -f 1991 1987 1989 -f 1991 1989 1988 -f 1963 1986 1994 -f 1994 1986 1990 -f 1994 1990 1991 -f 1994 1991 1992 -f 1992 1991 1988 -f 1992 2013 1993 -f 1992 1993 1994 -f 1994 1993 1998 -f 1994 1998 1963 -f 1963 1998 1999 -f 2011 2006 2007 -f 1996 2015 1995 -f 1995 2015 2000 -f 1995 2000 2008 -f 2008 2000 2001 -f 2008 2001 2002 -f 2008 2002 2003 -f 2008 2003 2009 -f 2009 2003 2004 -f 2009 2004 1997 -f 2009 1997 2010 -f 2010 1997 2005 -f 2010 2005 1998 -f 2010 1998 1993 -f 2006 1995 2007 -f 2007 1995 2008 -f 2009 2010 2012 -f 2012 2010 1993 -f 2007 2008 2009 -f 2014 1957 2015 -f 2015 2101 2014 -f 1996 2016 2015 -f 2015 2016 2101 -f 1995 2016 1996 -f 1995 2103 2016 -f 2103 1995 2017 -f 2006 2017 1995 -f 2017 2006 2104 -f 2104 2006 2011 -f 1951 2019 2020 -f 2018 141 2019 -f 2018 2019 1951 -f 2020 2025 2023 -f 2020 2023 1951 -f 1951 2023 2021 -f 2022 2021 2023 -f 2022 2023 2024 -f 2024 2023 2025 -f 2024 2025 2027 -f 2032 2022 2031 -f 2031 2022 2024 -f 2031 2024 2029 -f 2029 2024 2026 -f 2026 2024 2027 -f 2026 2028 2030 -f 2026 2030 2029 -f 2029 2030 2031 -f 2031 2030 2040 -f 2031 2040 2032 -f 2034 1944 2035 -f 2039 2040 2030 -f 2034 2035 2041 -f 2041 2035 2038 -f 2041 2038 2036 -f 2041 2036 2042 -f 2042 2036 2037 -f 2042 2037 2039 -f 2042 2039 2030 -f 2033 2034 2041 -f 1976 2033 2041 -f 1976 2041 2042 -f 1976 2042 2030 -f 1976 2030 2028 -f 2045 2141 2140 -f 2161 2043 2046 -f 2047 2049 1977 -f 1977 2049 2033 -f 2043 2050 2046 -f 2046 2050 2051 -f 2046 2051 2047 -f 2047 2051 2049 -f 2049 2034 2033 -f 2034 2049 2053 -f 2053 2049 2051 -f 2053 2051 2054 -f 2054 2051 2052 -f 2045 2048 2141 -f 2141 2048 2043 -f 2043 2048 2052 -f 2043 2052 2050 -f 2050 2052 2051 -f 2044 2059 2140 -f 2140 2059 2045 -f 2057 2055 2056 -f 2059 2058 2045 -f 2045 2058 2057 -f 2045 2057 2048 -f 2048 2057 2056 -f 2048 2056 2052 -f 2052 2056 2054 -f 2053 1944 2034 -f 2060 2076 2062 -f 2060 2062 9482 -f 2061 9593 9487 -f 2061 9487 2062 -f 2062 9487 9482 -f 9593 2061 2067 -f 9593 2067 9478 -f 9478 2067 9595 -f 9595 2067 2066 -f 2065 2077 2070 -f 2077 1973 2070 -f 2070 1973 1900 -f 1900 2063 2070 -f 2070 2063 2067 -f 2063 1905 2067 -f 2067 1905 2066 -f 2064 2065 2070 -f 2064 2070 2068 -f 2067 2061 2070 -f 2068 2070 2069 -f 2069 2070 2071 -f 2070 2061 2074 -f 2070 2074 2071 -f 2071 2074 2072 -f 2072 2074 2084 -f 2061 2062 2074 -f 2084 2074 2073 -f 2073 2074 2075 -f 2075 2074 2062 -f 2075 2062 2076 -f 1975 1973 2078 -f 2078 1973 2077 -f 2078 2077 2079 -f 2079 2077 2065 -f 2079 2065 2080 -f 2080 2065 2064 -f 2080 2064 2096 -f 2096 2064 2068 -f 2096 2068 2095 -f 2095 2068 2069 -f 2095 2069 2081 -f 2081 2069 2071 -f 2081 2071 2082 -f 2082 2071 2072 -f 2082 2072 2083 -f 2083 2072 2084 -f 2083 2084 158 -f 158 2084 2073 -f 1878 1975 2078 -f 2085 2086 2094 -f 2087 1866 159 -f 159 1866 2092 -f 1866 2089 2088 -f 1866 2088 2092 -f 2089 2090 2091 -f 2089 2091 2088 -f 2088 2091 2093 -f 2088 2093 2092 -f 2092 2093 2085 -f 2092 2085 159 -f 159 2085 2094 -f 1878 2097 2090 -f 2090 2097 2091 -f 158 2086 2083 -f 2083 2086 2085 -f 2083 2085 2082 -f 2082 2085 2093 -f 2082 2093 2081 -f 2081 2093 2095 -f 2095 2093 2091 -f 2095 2091 2096 -f 2096 2091 2080 -f 2080 2091 2079 -f 2079 2091 2097 -f 2079 2097 2078 -f 2078 2097 1878 -f 9476 9479 2109 -f 2098 2014 2102 -f 2098 2102 9594 -f 2109 9479 2102 -f 2102 9479 9594 -f 9476 2109 2099 -f 9476 2099 2100 -f 2100 2099 9463 -f 9463 2099 2113 -f 9463 2113 9483 -f 2102 2014 2101 -f 2102 2101 2016 -f 2102 2016 2103 -f 2102 2103 2017 -f 2104 2105 2017 -f 2017 2105 2107 -f 2017 2107 2102 -f 2105 2106 2107 -f 2106 2108 2107 -f 2102 2107 2109 -f 2108 2110 2107 -f 2107 2112 2109 -f 2110 2111 2107 -f 2107 2111 2112 -f 2109 2112 2099 -f 2111 2119 2112 -f 2119 2118 2112 -f 2112 2118 2115 -f 2113 2099 127 -f 127 2099 2112 -f 127 2112 2115 -f 127 2115 132 -f 2114 132 2135 -f 2135 132 2115 -f 2135 2115 2116 -f 2116 2115 2118 -f 2116 2118 2117 -f 2117 2118 2119 -f 2117 2119 2134 -f 2134 2119 2111 -f 2134 2111 2120 -f 2120 2111 2110 -f 2120 2110 2133 -f 2133 2110 2108 -f 2133 2108 2121 -f 2121 2108 2106 -f 2121 2106 2122 -f 2122 2106 2105 -f 2122 2105 1981 -f 1981 2105 2104 -f 2124 131 2123 -f 2129 2124 2123 -f 2129 2123 130 -f 2129 130 2126 -f 2125 2124 2128 -f 2128 2124 2129 -f 2129 2126 2127 -f 1982 2125 2132 -f 2132 2125 2128 -f 2131 2128 2129 -f 2131 2129 2136 -f 2136 2129 2127 -f 2136 2127 2130 -f 2131 2132 2128 -f 1981 1985 2122 -f 2122 1985 2132 -f 2122 2132 2121 -f 2121 2132 2133 -f 2133 2132 2120 -f 2120 2132 2131 -f 2120 2131 2134 -f 2134 2131 2117 -f 2117 2131 2136 -f 2117 2136 2116 -f 2116 2136 2135 -f 2135 2136 2114 -f 2114 2136 2130 -f 2043 2161 2145 -f 2137 2044 129 -f 129 2044 2139 -f 2044 2140 2139 -f 2140 2141 2142 -f 2140 2142 2143 -f 2140 2143 2139 -f 2139 2143 2144 -f 2139 2144 129 -f 129 2144 2138 -f 2043 2152 2141 -f 2141 2152 2142 -f 2144 2147 2138 -f 128 2147 2146 -f 2146 2147 2144 -f 2146 2144 2155 -f 2155 2144 2143 -f 2155 2143 2148 -f 2148 2143 2149 -f 2149 2143 2142 -f 2149 2142 2150 -f 2150 2142 2151 -f 2151 2142 2160 -f 2160 2142 2152 -f 2160 2152 2145 -f 2145 2152 2043 -f 2164 128 2153 -f 2153 128 2146 -f 2153 2146 2154 -f 2154 2146 2155 -f 2154 2155 2163 -f 2163 2155 2148 -f 2163 2148 2156 -f 2156 2148 2149 -f 2156 2149 2157 -f 2157 2149 2150 -f 2157 2150 2158 -f 2158 2150 2151 -f 2158 2151 2159 -f 2159 2151 2160 -f 2159 2160 2162 -f 2162 2160 2145 -f 2162 2145 1978 -f 1978 2145 2161 -f 1978 2025 2172 -f 1978 2172 2162 -f 2162 2172 2159 -f 2159 2172 2158 -f 2158 2172 2173 -f 2158 2173 2157 -f 2157 2173 2156 -f 2156 2173 2174 -f 2156 2174 2163 -f 2163 2174 2154 -f 2154 2174 2153 -f 2153 2174 136 -f 2153 136 2164 -f 141 2165 2019 -f 2165 2167 2019 -f 141 2166 2165 -f 2165 2166 138 -f 2165 138 137 -f 2165 137 2167 -f 2167 137 2168 -f 2167 2168 2169 -f 2171 2025 2020 -f 2020 2019 2171 -f 2171 2019 2167 -f 2167 2169 2170 -f 135 2175 2170 -f 2170 2175 2167 -f 2167 2175 2174 -f 2167 2174 2173 -f 2167 2173 2171 -f 2171 2173 2172 -f 2171 2172 2025 -f 2174 2175 136 -f 2178 157 2176 -f 2180 2178 2176 -f 2180 2176 2177 -f 2180 2177 2179 -f 2181 2178 2183 -f 2183 2178 2180 -f 2180 2179 2182 -f 1930 2181 2184 -f 2184 2181 2183 -f 2190 2183 2180 -f 2190 2180 2193 -f 2193 2180 2182 -f 2193 2182 156 -f 2190 2184 2183 -f 2185 1934 2186 -f 2186 1934 2184 -f 2186 2184 2195 -f 2195 2184 2197 -f 2197 2184 2187 -f 2187 2184 2190 -f 2187 2190 2188 -f 2188 2190 2189 -f 2189 2190 2193 -f 2189 2193 2198 -f 2198 2193 2191 -f 2191 2193 2192 -f 2192 2193 156 -f 2199 2185 2194 -f 2194 2185 2186 -f 2194 2186 2200 -f 2200 2186 2195 -f 2200 2195 2196 -f 2196 2195 2197 -f 2196 2197 2201 -f 2201 2197 2187 -f 2201 2187 2202 -f 2202 2187 2188 -f 2202 2188 2203 -f 2203 2188 2189 -f 2203 2189 2204 -f 2204 2189 2198 -f 2204 2198 2205 -f 2205 2198 2191 -f 2205 2191 2206 -f 2206 2191 2192 -f 2207 2199 2194 -f 2207 2194 2200 -f 2207 2200 2196 -f 2207 2196 2201 -f 2207 2201 2220 -f 2220 2201 2202 -f 2220 2202 2203 -f 2220 2203 2219 -f 2219 2203 2204 -f 2219 2204 2205 -f 2219 2205 2206 -f 2219 2206 2218 -f 2215 1817 2216 -f 2208 2213 2209 -f 2209 2210 2208 -f 2211 2214 2208 -f 2208 2214 2215 -f 2215 2212 2208 -f 2208 2212 2213 -f 2215 2216 2212 -f 1907 2207 2214 -f 2214 2207 2220 -f 2214 2220 2215 -f 2215 2220 2219 -f 2215 2219 2217 -f 2215 2217 1817 -f 2218 2217 2219 -f 2221 4323 4325 -f 2221 4325 2222 -f 2221 2222 4659 -f 2221 4659 9494 -f 9494 4659 2223 -f 9494 2223 2224 -f 2224 2223 4661 -f 2224 4661 4662 -f 2225 4424 4368 -f 4368 4424 4414 -f 4423 4422 4373 -f 4373 4422 2225 -f 2225 4422 4424 -f 4420 4423 2226 -f 2226 4423 4373 -f 4419 4420 4372 -f 4372 4420 2226 -f 9505 2227 4419 -f 9505 4419 4372 -f 4418 4419 2227 -f 9526 2229 2228 -f 2228 2229 4444 -f 4444 2229 9553 -f 2357 2597 2230 -f 2248 2231 9570 -f 9570 2231 7107 -f 4449 4450 2232 -f 2232 4450 2233 -f 2232 2233 2246 -f 2246 2233 4453 -f 2246 4453 2242 -f 4462 2234 9570 -f 2237 2239 2238 -f 7109 4462 9570 -f 7109 9570 7107 -f 7111 2235 4460 -f 4462 7109 7111 -f 4462 7111 4460 -f 2235 7111 4440 -f 4440 7111 7086 -f 4440 7086 2236 -f 2236 7086 2237 -f 2236 2237 2238 -f 2239 2237 4456 -f 4456 2237 2240 -f 2240 2241 4456 -f 2241 2240 7099 -f 2241 7099 7102 -f 2241 7102 2242 -f 2242 7102 2246 -f 2246 7102 2247 -f 2234 4466 9570 -f 9570 4466 2243 -f 9570 2243 2251 -f 2251 2243 2244 -f 4449 2232 2230 -f 2230 2232 2359 -f 2230 2359 2357 -f 2245 5187 2360 -f 2246 2247 2360 -f 2360 2247 7095 -f 2360 7095 2245 -f 7090 7089 2248 -f 2248 7089 2231 -f 2248 2249 7090 -f 7090 2249 2250 -f 7090 2250 4927 -f 2244 2252 2251 -f 2251 2252 9553 -f 9553 2252 4441 -f 9553 4441 4444 -f 2253 4445 2254 -f 2253 2254 2255 -f 2255 2254 2598 -f 2255 2598 2599 -f 2261 4472 2256 -f 2256 4472 4474 -f 4474 2257 2256 -f 2256 2257 2258 -f 2256 2258 2253 -f 2253 2258 4477 -f 2253 4477 4445 -f 2264 4482 2591 -f 2591 4482 2259 -f 2591 2259 2592 -f 2596 2594 4469 -f 4469 2594 2458 -f 4469 2458 2259 -f 2259 2458 2592 -f 4469 2260 2596 -f 2596 2260 2256 -f 2256 2260 2261 -f 2262 2263 4478 -f 4478 2263 2266 -f 4478 2266 4442 -f 2262 4479 2263 -f 2263 4479 4480 -f 2263 4480 2265 -f 2591 9527 2264 -f 2264 9527 2263 -f 2264 2263 4481 -f 2263 2265 4481 -f 4442 2266 4443 -f 4443 2266 9530 -f 4443 9530 2267 -f 2267 9530 9526 -f 2267 9526 2228 -f 2795 2791 2268 -f 5394 5853 5392 -f 5395 2272 5756 -f 2292 2748 2447 -f 9508 5257 2285 -f 2273 5317 2293 -f 2269 2270 2328 -f 2447 2748 3170 -f 5394 5768 5853 -f 5853 5768 5765 -f 5233 2271 2281 -f 5756 2272 2293 -f 2293 2272 5315 -f 2293 5315 2273 -f 2706 2708 2447 -f 5395 5756 5394 -f 5394 5756 5768 -f 2268 3265 2277 -f 9508 2283 5331 -f 5331 2274 9508 -f 9508 2274 2275 -f 2275 5334 2281 -f 2281 5334 2276 -f 2286 5261 2319 -f 2269 2328 2691 -f 2795 2268 2794 -f 2794 2268 2277 -f 5338 6385 2278 -f 5234 5233 2278 -f 2278 5233 2281 -f 2278 2281 2279 -f 2279 2281 2276 -f 2271 5232 2281 -f 2281 5232 2280 -f 2281 2280 5230 -f 5230 5229 2281 -f 2281 5229 2282 -f 2281 2282 9512 -f 2283 9508 2284 -f 2284 9508 2285 -f 2284 2285 2319 -f 2319 2285 5259 -f 2319 5259 2286 -f 2287 2702 2447 -f 2447 2741 2291 -f 2748 2288 3170 -f 3170 2288 2289 -f 3170 2289 3181 -f 3181 2289 2794 -f 3181 2794 2277 -f 2702 2290 2447 -f 2447 2290 2704 -f 2447 2704 2706 -f 2291 2743 2447 -f 2447 2743 2745 -f 2447 2745 2292 -f 5317 5319 2293 -f 2293 5319 5320 -f 2293 5320 2294 -f 5261 2295 2319 -f 2319 2295 5264 -f 2319 5264 5265 -f 2296 2297 2293 -f 2293 2297 2298 -f 2293 2298 5284 -f 2741 2447 2740 -f 2740 2447 2708 -f 2740 2708 2334 -f 5234 2278 2299 -f 2299 2278 6382 -f 2299 6382 2300 -f 2294 5321 2301 -f 2301 5321 5323 -f 2294 2301 2293 -f 2293 2301 2302 -f 2293 2302 2296 -f 2712 2303 2568 -f 2568 2303 2715 -f 2685 2688 2328 -f 2328 2688 2304 -f 2328 2304 2691 -f 6385 6382 2278 -f 2305 5253 9499 -f 2715 2716 2568 -f 2568 2716 2306 -f 2568 2306 2718 -f 5284 2307 2293 -f 2293 2307 5287 -f 2293 5287 5018 -f 5018 5287 5288 -f 5018 5288 2310 -f 2310 5288 2308 -f 2310 2308 2309 -f 5338 6386 6385 -f 2309 5291 2310 -f 2310 5291 5292 -f 2310 5292 2311 -f 2311 5296 2310 -f 2310 5296 2313 -f 2310 2313 2312 -f 2312 2313 5297 -f 2312 5297 5125 -f 9499 5253 9514 -f 9514 5253 2314 -f 9514 2314 5256 -f 2712 2568 2343 -f 2343 2568 2578 -f 2343 2578 2580 -f 5272 2315 5324 -f 5324 2315 5275 -f 2675 2345 2316 -f 2317 2694 2336 -f 2336 2694 2318 -f 2331 5326 5266 -f 5266 5326 5327 -f 5266 5327 5265 -f 5265 5327 5329 -f 5265 5329 2319 -f 2324 9511 2645 -f 2645 9511 2643 -f 2328 2756 2758 -f 2718 2320 2568 -f 2568 2320 2321 -f 2568 2321 2571 -f 2571 2321 2711 -f 2571 2711 2447 -f 2447 2711 2700 -f 2447 2700 2287 -f 2652 2322 9511 -f 9511 2322 2323 -f 9511 2323 2643 -f 2324 2647 9511 -f 9511 2647 2325 -f 9511 2325 2326 -f 2327 2751 2326 -f 2326 2751 2752 -f 2326 2752 2328 -f 2328 2752 2755 -f 2328 2755 2756 -f 2685 2328 2684 -f 2684 2328 2758 -f 2684 2758 2329 -f 2329 2758 2760 -f 2329 2760 2337 -f 2337 2760 2761 -f 2337 2761 2330 -f 5266 5269 2331 -f 2331 5269 5270 -f 2331 5270 5324 -f 5324 5270 5271 -f 5324 5271 5272 -f 5275 2332 5324 -f 5324 2332 5277 -f 5324 5277 5323 -f 5323 5277 5278 -f 5323 5278 2301 -f 5299 5250 9499 -f 9499 5250 2333 -f 9499 2333 2305 -f 2708 2335 2334 -f 2334 2335 2698 -f 2334 2698 2336 -f 2336 2698 2697 -f 2336 2697 2317 -f 2647 2648 2325 -f 2325 2648 2649 -f 2325 2649 2348 -f 2330 2338 2337 -f 2337 2338 2765 -f 2337 2765 2339 -f 2339 2765 2340 -f 2339 2340 2693 -f 2693 2340 2336 -f 2693 2336 2696 -f 2696 2336 2318 -f 2325 3785 3788 -f 2325 3788 2749 -f 2341 9504 2580 -f 9504 9503 2580 -f 2580 9503 2342 -f 2580 2342 2343 -f 2343 2342 9515 -f 2343 9515 2344 -f 2344 9515 2722 -f 2345 2346 2316 -f 2316 2346 2347 -f 2316 2347 9515 -f 9515 2347 2680 -f 9515 2680 2722 -f 2348 3785 2325 -f 5299 9499 2350 -f 2350 9499 2349 -f 2350 2349 5297 -f 5297 2349 9500 -f 5297 9500 5125 -f 3788 2352 2351 -f 3788 2351 2749 -f 9500 2353 5125 -f 5125 2353 9501 -f 5125 9501 5129 -f 5129 9501 9510 -f 5129 9510 5013 -f 5013 9510 2354 -f 2354 9510 9507 -f 2354 9507 2364 -f 2580 2577 2341 -f 2341 2577 2596 -f 2341 2596 2355 -f 2355 2596 2256 -f 2256 2253 2355 -f 2355 2253 2255 -f 2355 2255 9497 -f 9497 2255 2599 -f 9497 2599 2356 -f 2356 2599 2357 -f 2356 2357 2358 -f 2358 2357 2359 -f 2358 2359 9509 -f 2359 2232 9509 -f 9509 2232 2246 -f 9509 2246 9496 -f 9496 2246 2360 -f 9496 2360 2361 -f 2361 2360 5187 -f 2361 5187 9498 -f 9498 5187 2362 -f 9498 2362 9507 -f 9507 2362 2363 -f 9507 2363 2364 -f 3632 3630 2370 -f 2368 3695 2366 -f 2367 2368 3634 -f 3700 2365 2367 -f 2365 3698 2367 -f 2367 3698 3697 -f 3695 2368 2367 -f 3695 2367 3697 -f 2369 2366 2374 -f 2368 2366 2369 -f 2367 3634 3633 -f 2367 3633 2370 -f 2370 3633 3632 -f 2371 3630 2372 -f 2370 3762 3760 -f 3767 3765 2370 -f 2370 3765 3762 -f 2819 2370 3760 -f 3759 2373 2372 -f 3630 2371 2370 -f 2370 2371 3767 -f 2371 2372 2373 -f 2366 3691 2374 -f 2372 2375 3759 -f 3703 3182 2376 -f 3703 2376 2377 -f 3607 2378 3701 -f 3607 3701 2381 -f 3586 3588 3719 -f 2378 3607 3586 -f 2378 3586 3721 -f 3721 3586 3719 -f 3719 3588 3589 -f 3719 3589 3716 -f 3716 3589 3591 -f 3716 3591 3717 -f 3717 3591 2379 -f 2379 3591 3593 -f 3592 3713 3712 -f 3592 3712 2380 -f 3592 2380 3593 -f 3593 2380 2379 -f 3713 3592 3596 -f 3706 3708 3599 -f 3598 3597 3711 -f 3596 3595 3713 -f 3713 3595 3711 -f 3711 3595 3598 -f 3711 3597 3601 -f 3599 3708 3711 -f 3599 3711 3601 -f 2381 3701 3003 -f 2381 3003 3562 -f 3562 3003 3636 -f 3674 3584 3562 -f 3674 3562 3636 -f 2382 3656 3583 -f 3584 3674 2382 -f 3584 2382 3585 -f 3585 2382 3583 -f 3583 3656 2383 -f 3583 2383 3581 -f 3581 2383 3659 -f 3581 3659 3582 -f 3582 3659 3580 -f 3580 3659 2386 -f 2385 2384 3575 -f 2385 3575 3576 -f 2385 3576 2386 -f 2386 3576 3580 -f 2384 2385 3664 -f 3568 3570 2667 -f 2387 2388 3571 -f 3664 3663 2384 -f 2384 3663 3571 -f 3571 3663 2387 -f 3571 2388 3666 -f 2667 3570 3571 -f 2667 3571 3666 -f 3003 3668 3636 -f 3198 2390 2389 -f 2389 2390 3003 -f 2389 3003 2377 -f 2377 3003 3701 -f 2377 3701 3703 -f 3182 3703 3723 -f 3182 3723 2391 -f 3182 2391 2392 -f 3182 2392 2393 -f 2393 2392 3727 -f 2393 3727 3322 -f 3727 3731 3322 -f 3322 3731 2394 -f 2394 3731 2395 -f 2395 3731 3729 -f 2395 3729 2398 -f 2399 3738 2396 -f 2396 3738 3741 -f 2396 3741 3740 -f 3729 3733 2398 -f 2398 3733 2397 -f 2397 3733 3736 -f 2397 3736 2396 -f 2396 3736 2399 -f 3487 3427 3491 -f 3405 3480 3427 -f 3427 3480 3491 -f 3425 3561 2400 -f 3539 3415 3561 -f 3561 3415 2400 -f 3269 2402 2632 -f 2632 2402 2401 -f 3269 2778 2402 -f 2397 2403 2398 -f 2398 2403 2395 -f 2670 2654 3165 -f 3165 2654 2655 -f 3165 2655 3167 -f 3167 2655 2656 -f 3167 2656 2404 -f 2404 2656 9523 -f 9523 2656 2405 -f 9523 2405 2406 -f 2670 3165 2396 -f 2396 3165 2407 -f 2396 2407 2397 -f 2397 2407 3175 -f 2406 2659 9523 -f 9523 2659 2660 -f 9523 2660 2661 -f 2661 2408 9523 -f 9523 2408 2663 -f 9523 2663 2665 -f 3326 2403 3175 -f 3175 2403 2397 -f 2409 3320 2410 -f 2410 3320 2411 -f 2410 2411 2413 -f 2413 2411 2412 -f 2413 2412 2414 -f 2414 2412 2415 -f 2414 2415 2416 -f 2416 2415 2417 -f 2416 2417 3350 -f 3350 2417 3318 -f 3350 3318 2418 -f 2418 3318 3316 -f 2418 3316 2419 -f 2419 3316 2420 -f 2419 2420 3348 -f 3348 2420 2421 -f 3348 2421 2422 -f 2422 2421 3314 -f 2422 3314 3345 -f 3345 3314 3312 -f 3345 3312 3344 -f 3344 3312 3311 -f 3344 3311 3343 -f 3343 3311 2423 -f 3343 2423 3342 -f 3342 2423 3309 -f 3342 3309 3340 -f 3340 3309 3308 -f 3340 3308 2424 -f 2424 3308 3307 -f 2424 3307 3339 -f 3339 3307 2426 -f 3339 2426 2425 -f 2425 2426 2427 -f 2425 2427 3338 -f 3338 2427 3305 -f 3338 3305 2428 -f 2428 3305 2429 -f 2428 2429 2430 -f 2430 2429 2431 -f 2430 2431 3336 -f 3336 2431 3304 -f 3336 3304 2432 -f 2432 3304 3303 -f 2432 3303 2433 -f 2433 3303 3302 -f 2433 3302 2434 -f 2434 3302 3298 -f 2511 3260 3259 -f 2483 4201 4199 -f 4199 2437 2483 -f 2483 2437 4198 -f 2483 4198 2442 -f 4180 2438 2479 -f 4201 2483 2439 -f 2439 2483 2571 -f 2439 2571 4166 -f 2479 2438 2852 -f 2438 4179 2852 -f 2852 4179 4178 -f 2852 4178 2447 -f 2441 2479 4187 -f 4187 2479 2440 -f 2441 4184 2479 -f 2479 4184 4182 -f 2479 4182 4180 -f 2449 4169 2571 -f 2442 2443 2483 -f 2483 2443 2444 -f 2483 2444 2445 -f 2445 4192 2483 -f 2483 4192 4191 -f 2483 4191 2479 -f 2479 4191 4189 -f 2479 4189 2440 -f 4178 2446 2447 -f 2447 2446 4177 -f 2447 4177 4176 -f 4176 4174 2447 -f 2447 4174 2448 -f 2447 2448 4173 -f 2449 2571 2454 -f 4169 2450 2571 -f 2571 2450 2451 -f 2571 2451 4166 -f 4173 2452 2447 -f 2447 2452 2453 -f 2447 2453 2571 -f 2571 2453 4172 -f 2571 4172 2454 -f 2462 2456 6989 -f 3880 2455 3882 -f 3882 2455 3884 -f 6989 2456 2455 -f 2455 2456 2457 -f 2455 2457 3884 -f 3867 2459 2458 -f 2460 3902 2593 -f 2459 3907 2458 -f 2458 3907 3906 -f 2458 3906 2593 -f 2593 3906 3905 -f 2593 3905 2460 -f 3891 3889 6989 -f 3889 2461 6989 -f 6989 2461 3886 -f 6989 3886 2462 -f 3902 3900 2593 -f 2593 3900 2463 -f 2593 2463 3896 -f 3896 3894 2593 -f 2593 3894 2464 -f 2593 2464 3893 -f 3893 3892 6989 -f 6989 3892 2465 -f 6989 2465 3891 -f 2588 3879 3878 -f 3867 2458 2595 -f 3867 2595 2467 -f 3873 3871 2595 -f 3871 3870 2595 -f 2595 3870 2466 -f 2595 2466 2467 -f 3878 3876 2588 -f 2588 3876 2468 -f 2588 2468 2595 -f 2595 2468 3874 -f 2595 3874 3873 -f 4026 4025 2560 -f 4008 4007 2850 -f 4029 4027 2488 -f 2488 4027 2469 -f 2488 2469 4026 -f 4025 4024 2560 -f 2560 4024 2470 -f 2560 2470 4023 -f 2850 4007 2478 -f 4007 2471 2478 -f 2478 2471 2472 -f 2478 2472 2473 -f 4023 2474 2560 -f 2560 2474 4019 -f 2560 4019 4018 -f 4018 4017 2560 -f 2560 4017 4015 -f 2560 4015 2850 -f 2850 4015 4013 -f 4013 4012 2850 -f 2850 4012 2475 -f 2850 2475 2476 -f 2476 2477 2850 -f 2850 2477 4009 -f 2850 4009 4008 -f 2473 4003 2478 -f 2478 4003 4002 -f 2478 4002 2479 -f 2483 4030 2488 -f 2488 4030 4029 -f 4002 2480 2479 -f 2479 2480 4000 -f 2479 4000 2481 -f 2481 3998 2479 -f 2479 3998 2482 -f 2479 2482 2483 -f 2483 2482 3996 -f 2483 3996 3995 -f 3995 2484 2483 -f 2483 2484 3992 -f 2483 3992 4030 -f 4061 2488 2485 -f 2485 2488 4062 -f 6987 2486 2487 -f 2487 4086 6987 -f 6987 4086 4084 -f 6987 4084 2490 -f 2490 4084 4083 -f 4026 2560 2488 -f 2488 2560 4065 -f 2488 4065 4062 -f 4083 2489 2490 -f 2490 2489 4080 -f 2490 4080 4079 -f 4068 4067 2560 -f 2560 4067 2491 -f 2560 2491 4065 -f 2492 4069 2560 -f 2560 4069 2493 -f 2560 2493 4068 -f 4079 4077 2490 -f 2490 4077 4076 -f 2490 4076 4075 -f 4075 2494 2490 -f 2490 2494 4073 -f 2490 4073 2560 -f 2560 4073 4071 -f 2560 4071 2492 -f 2495 2496 2483 -f 4061 4059 2488 -f 2488 4059 4058 -f 2488 4058 2483 -f 2483 4058 2495 -f 2497 2498 2572 -f 2572 2498 4049 -f 2572 4049 2563 -f 2496 4054 2483 -f 2483 4054 2499 -f 2483 2499 2572 -f 2572 2499 2500 -f 2572 2500 2497 -f 2511 3259 2520 -f 2520 3259 9580 -f 2520 9580 2501 -f 2501 2502 2520 -f 2520 2502 9568 -f 2520 9568 2523 -f 2523 9568 9567 -f 2523 9567 9536 -f 9527 2591 9528 -f 9528 2591 2558 -f 9528 2558 9535 -f 9535 2558 2542 -f 9535 2542 2503 -f 2503 2542 2523 -f 2503 2523 2504 -f 2504 2523 9536 -f 2515 4106 2561 -f 4106 4104 2561 -f 2561 4104 2505 -f 2561 2505 2520 -f 2520 2505 2506 -f 2520 2506 2507 -f 2507 2508 2520 -f 2520 2508 4144 -f 2520 4144 4142 -f 2518 2509 2511 -f 2511 2509 2510 -f 2511 2510 2512 -f 2512 2510 4125 -f 4125 4123 2512 -f 2512 4123 4121 -f 2512 4121 4119 -f 4119 2513 2512 -f 2512 2513 4116 -f 2512 4116 2514 -f 4112 4111 2561 -f 2561 4111 4108 -f 2561 4108 2515 -f 2517 2511 2516 -f 2516 2511 4132 -f 2517 4130 2511 -f 2511 4130 4129 -f 2511 4129 2518 -f 4142 2519 2520 -f 2520 2519 4139 -f 2520 4139 4138 -f 2514 4115 2512 -f 2512 4115 4114 -f 2512 4114 2561 -f 2561 4114 2521 -f 2561 2521 4112 -f 4138 4135 2520 -f 2520 4135 2522 -f 2520 2522 2511 -f 2511 2522 4134 -f 2511 4134 4132 -f 2544 4222 2523 -f 2523 4222 4258 -f 2523 4258 2524 -f 2525 4226 2543 -f 2543 4226 2526 -f 2543 2526 4224 -f 2524 4254 2523 -f 2523 4254 2527 -f 2523 2527 4253 -f 2520 2538 4246 -f 4246 2528 2520 -f 2520 2528 2529 -f 2520 2529 4244 -f 2561 2534 2530 -f 2530 2531 2561 -f 2561 2531 4237 -f 2561 4237 2535 -f 2532 4230 2543 -f 2543 4230 4229 -f 2543 4229 2525 -f 4244 4242 2520 -f 2520 4242 2533 -f 2520 2533 2561 -f 2561 2533 4239 -f 2561 4239 2534 -f 2535 4234 2561 -f 2561 4234 4233 -f 2561 4233 2543 -f 2543 4233 4232 -f 2543 4232 2532 -f 4253 4252 2523 -f 2523 4252 4251 -f 2523 4251 2536 -f 2536 4250 2523 -f 2523 4250 2537 -f 2523 2537 2520 -f 2520 2537 4247 -f 2520 4247 2538 -f 3828 2539 2541 -f 3833 2540 2558 -f 2558 2540 3832 -f 2558 3832 3830 -f 3830 3828 2558 -f 2558 3828 2541 -f 2558 2541 2542 -f 2542 2541 6985 -f 2542 6985 2523 -f 2523 6985 2543 -f 2523 2543 2544 -f 2544 2543 4224 -f 3811 3809 2548 -f 2548 3809 3807 -f 2548 3807 2591 -f 2591 3807 3848 -f 3848 2545 2591 -f 2591 2545 3845 -f 2591 3845 3843 -f 3838 3837 2558 -f 2558 3837 3835 -f 2558 3835 3833 -f 2539 2546 2541 -f 2541 2546 2547 -f 2541 2547 3824 -f 3815 3814 2548 -f 2548 3814 2549 -f 2548 2549 3811 -f 3824 3823 2541 -f 2541 3823 3822 -f 2541 3822 2562 -f 2550 2548 3818 -f 3818 2548 3820 -f 3843 2551 2591 -f 2591 2551 2552 -f 2591 2552 2553 -f 2550 2554 2548 -f 2548 2554 2555 -f 2548 2555 3815 -f 2553 2556 2591 -f 2591 2556 2557 -f 2591 2557 2558 -f 2558 2557 2559 -f 2558 2559 3838 -f 2543 2490 2561 -f 2561 2490 2560 -f 2561 2560 2512 -f 2512 2560 2850 -f 3893 6989 2593 -f 2593 6989 2541 -f 2593 2541 2548 -f 2548 2541 2562 -f 2548 2562 3820 -f 3880 3879 2455 -f 2455 3879 2588 -f 6987 2572 2486 -f 2486 2572 2563 -f 2564 4288 2568 -f 2565 4322 2572 -f 2572 4322 2566 -f 2572 2566 4321 -f 4296 4294 2571 -f 2571 4294 2570 -f 2564 2568 2567 -f 2567 2568 2571 -f 2567 2571 2569 -f 4288 4287 2568 -f 2568 4287 4284 -f 2568 4284 4283 -f 2570 4292 2571 -f 2571 4292 4290 -f 2571 4290 2569 -f 4283 4282 2568 -f 2568 4282 4279 -f 2568 4279 2579 -f 4321 4320 2572 -f 2572 4320 4318 -f 2572 4318 4317 -f 2483 4308 4307 -f 4307 4306 2483 -f 2483 4306 4304 -f 2483 4304 4303 -f 4303 2573 2483 -f 2483 2573 4300 -f 2483 4300 2571 -f 2571 4300 4298 -f 2571 4298 4296 -f 4317 4315 2572 -f 2572 4315 4314 -f 2572 4314 4313 -f 4313 4312 2572 -f 2572 4312 4311 -f 2572 4311 2483 -f 2483 4311 2574 -f 2483 2574 4308 -f 2584 3949 2588 -f 3938 3936 2577 -f 3968 3967 2595 -f 3926 3925 2577 -f 2577 3925 2575 -f 2577 2575 2595 -f 2595 2575 3970 -f 2595 3970 3968 -f 2590 3954 2595 -f 3947 2576 2580 -f 2580 2576 3945 -f 3931 3930 2577 -f 2577 3930 3928 -f 2577 3928 3926 -f 2589 3952 2588 -f 3949 3947 2588 -f 2588 3947 2580 -f 2588 2580 6986 -f 6986 2580 2578 -f 6986 2578 2572 -f 2572 2578 2568 -f 2572 2568 2565 -f 2565 2568 2579 -f 3945 3943 2580 -f 2580 3943 3942 -f 2580 3942 2585 -f 3936 3934 2577 -f 2577 3934 2581 -f 2577 2581 3931 -f 3952 2582 2588 -f 2588 2582 2583 -f 2588 2583 2584 -f 2585 2586 2580 -f 2580 2586 3939 -f 2580 3939 2577 -f 2577 3939 2587 -f 2577 2587 3938 -f 3967 3966 2595 -f 2595 3966 3965 -f 2595 3965 3962 -f 2595 3954 2588 -f 2588 3954 3953 -f 2588 3953 2589 -f 3962 3959 2595 -f 2595 3959 3958 -f 2595 3958 2590 -f 2591 2592 2548 -f 2548 2592 2593 -f 2593 2592 2458 -f 2458 2594 2595 -f 2595 2594 2596 -f 2595 2596 2577 -f 2597 2357 2598 -f 2598 2357 2599 -f 4418 9611 9610 -f 4418 9610 4429 -f 4429 9610 2601 -f 4429 2601 2600 -f 2600 2601 2602 -f 2600 2602 4434 -f 4434 2602 2603 -f 4434 2603 4425 -f 4425 2603 2612 -f 4425 2612 2604 -f 2609 9523 2605 -f 2606 2881 2880 -f 4601 2605 2607 -f 2607 2605 4363 -f 2607 4363 4593 -f 3223 4601 2608 -f 2608 4601 4591 -f 2608 4591 2610 -f 3158 3159 2605 -f 2605 3159 3162 -f 2605 3162 2609 -f 9586 2610 2611 -f 2611 2610 4591 -f 2611 4591 2612 -f 2612 4591 4593 -f 2612 4593 2604 -f 2604 4593 4363 -f 3223 2606 4601 -f 4601 2606 2880 -f 4601 2880 2605 -f 2605 2880 3158 -f 2614 2920 3190 -f 3190 2920 2615 -f 3190 2615 2616 -f 2616 2615 2617 -f 2616 2617 2618 -f 2618 2617 2933 -f 2618 2933 3192 -f 3192 2933 2620 -f 3192 2620 2619 -f 2619 2620 2621 -f 2619 2621 3195 -f 3195 2621 2944 -f 3195 2944 2622 -f 2622 2944 2931 -f 2622 2931 3198 -f 3198 2931 2390 -f 2632 2401 2633 -f 3270 2632 2631 -f 2625 3272 2623 -f 2623 3272 3270 -f 2623 3270 2923 -f 2923 3270 2631 -f 3184 3268 2625 -f 2625 3268 2624 -f 2625 2624 3272 -f 2625 2626 3184 -f 3184 2626 2627 -f 3184 2627 3185 -f 2921 2630 2627 -f 2627 2630 3186 -f 2627 3186 3185 -f 2628 2920 2614 -f 2614 2629 2628 -f 2628 2629 3187 -f 2628 3187 2921 -f 2921 3187 3188 -f 2921 3188 2630 -f 2633 3775 2631 -f 2632 2633 2631 -f 3774 2635 2634 -f 2634 2635 2631 -f 2634 2631 3775 -f 2635 3774 3773 -f 2635 3773 3772 -f 2635 3772 2894 -f 2894 3772 3781 -f 2636 3785 2348 -f 2640 2637 2651 -f 2651 2637 2636 -f 2640 3784 2637 -f 2905 2638 2639 -f 2639 3783 2641 -f 2641 3783 2640 -f 2640 3783 3784 -f 2905 2639 2641 -f 2894 3781 2905 -f 2905 3781 3782 -f 2905 3782 2638 -f 2322 2653 2323 -f 2323 2653 2642 -f 2323 2642 2643 -f 2643 2642 2644 -f 2643 2644 2645 -f 2645 2644 2646 -f 2645 2646 2324 -f 2324 2646 2899 -f 2324 2899 2647 -f 2647 2899 2900 -f 2647 2900 2648 -f 2648 2900 2901 -f 2648 2901 2649 -f 2649 2901 2650 -f 2649 2650 2348 -f 2348 2650 2651 -f 2348 2651 2636 -f 2665 2666 2652 -f 2652 2666 2653 -f 2652 2653 2322 -f 2670 2668 2654 -f 2654 2668 2990 -f 2654 2990 2655 -f 2655 2990 2991 -f 2655 2991 2656 -f 2656 2991 2657 -f 2656 2657 2405 -f 2405 2657 2992 -f 2405 2992 2406 -f 2406 2992 2658 -f 2406 2658 2659 -f 2659 2658 2993 -f 2659 2993 2660 -f 2660 2993 2662 -f 2660 2662 2661 -f 2661 2662 2994 -f 2661 2994 2408 -f 2408 2994 2664 -f 2408 2664 2663 -f 2663 2664 2995 -f 2663 2995 2665 -f 2665 2995 2666 -f 2613 3641 2668 -f 3704 2670 3740 -f 3740 2670 2396 -f 3568 2667 2668 -f 2668 2667 2669 -f 2668 2669 2613 -f 3704 3706 2670 -f 2670 3706 3599 -f 2670 3599 2668 -f 2668 3599 2671 -f 2668 2671 3568 -f 3008 2998 2672 -f 2672 2673 3008 -f 3008 2673 2674 -f 3008 2674 2882 -f 2882 2674 2969 -f 2882 2969 2972 -f 2675 2676 2345 -f 2345 2676 2677 -f 2345 2677 2346 -f 2346 2677 2678 -f 2346 2678 2347 -f 2347 2678 2679 -f 2347 2679 2680 -f 2680 2679 2725 -f 2680 2725 2722 -f 2722 2725 2721 -f 2270 2681 2682 -f 2682 2681 2676 -f 2682 2676 2675 -f 2339 2731 2337 -f 2337 2731 2683 -f 2337 2683 2329 -f 2329 2683 2732 -f 2329 2732 2684 -f 2684 2732 2686 -f 2684 2686 2685 -f 2685 2686 2687 -f 2685 2687 2688 -f 2688 2687 2689 -f 2688 2689 2304 -f 2304 2689 2729 -f 2304 2729 2691 -f 2691 2729 2690 -f 2691 2690 2269 -f 2269 2690 2692 -f 2269 2692 2270 -f 2270 2692 2681 -f 2731 2339 2726 -f 2726 2339 2693 -f 2697 2723 2317 -f 2317 2723 2728 -f 2317 2728 2694 -f 2694 2728 2727 -f 2694 2727 2318 -f 2318 2727 2695 -f 2318 2695 2696 -f 2696 2695 2724 -f 2696 2724 2693 -f 2693 2724 2726 -f 2723 2697 2710 -f 2710 2697 2698 -f 2711 2699 2700 -f 2700 2699 2701 -f 2700 2701 2287 -f 2287 2701 2735 -f 2287 2735 2702 -f 2702 2735 2734 -f 2702 2734 2290 -f 2290 2734 2703 -f 2290 2703 2704 -f 2704 2703 2705 -f 2704 2705 2706 -f 2706 2705 2733 -f 2706 2733 2708 -f 2708 2733 2707 -f 2708 2707 2335 -f 2335 2707 2709 -f 2335 2709 2698 -f 2698 2709 2710 -f 2699 2711 2720 -f 2720 2711 2321 -f 2344 2739 2343 -f 2343 2739 2738 -f 2343 2738 2712 -f 2712 2738 2737 -f 2712 2737 2303 -f 2303 2737 2713 -f 2303 2713 2715 -f 2715 2713 2714 -f 2715 2714 2716 -f 2716 2714 2730 -f 2716 2730 2306 -f 2306 2730 2717 -f 2306 2717 2718 -f 2718 2717 2719 -f 2718 2719 2320 -f 2320 2719 2736 -f 2320 2736 2321 -f 2321 2736 2720 -f 2739 2344 2721 -f 2721 2344 2722 -f 2739 2721 2720 -f 2720 2723 2710 -f 2726 2724 2720 -f 2720 2724 2695 -f 2721 2725 2720 -f 2720 2725 2679 -f 2720 2679 2678 -f 2678 2677 2720 -f 2720 2677 2676 -f 2720 2676 2726 -f 2726 2676 2681 -f 2726 2681 2731 -f 2695 2727 2720 -f 2720 2727 2728 -f 2720 2728 2723 -f 2735 2701 2710 -f 2710 2701 2699 -f 2710 2699 2720 -f 2690 2729 2689 -f 2714 2736 2730 -f 2730 2736 2719 -f 2730 2719 2717 -f 2689 2687 2690 -f 2690 2687 2686 -f 2690 2686 2732 -f 2681 2692 2731 -f 2731 2692 2690 -f 2731 2690 2683 -f 2683 2690 2732 -f 2709 2707 2703 -f 2703 2707 2733 -f 2703 2733 2705 -f 2709 2703 2710 -f 2710 2703 2734 -f 2710 2734 2735 -f 2714 2713 2736 -f 2736 2713 2737 -f 2736 2737 2720 -f 2720 2737 2738 -f 2720 2738 2739 -f 2336 3153 2334 -f 2334 3153 3152 -f 2334 3152 2740 -f 2740 3152 3150 -f 2740 3150 2741 -f 2741 3150 3149 -f 2741 3149 2291 -f 2291 3149 2742 -f 2291 2742 2743 -f 2743 2742 2744 -f 2743 2744 2745 -f 2745 2744 2746 -f 2745 2746 2292 -f 2292 2746 2747 -f 2292 2747 2748 -f 2748 2747 3147 -f 2748 3147 2288 -f 2288 3147 3156 -f 3153 2336 3115 -f 3115 2336 2340 -f 2749 3017 2325 -f 2325 3017 3054 -f 2325 3054 2326 -f 2326 3054 2750 -f 2326 2750 2327 -f 2327 2750 3055 -f 2327 3055 2751 -f 2751 3055 2753 -f 2751 2753 2752 -f 2752 2753 2754 -f 2752 2754 2755 -f 2755 2754 3056 -f 2755 3056 2756 -f 2756 3056 2757 -f 2756 2757 2758 -f 2758 2757 3057 -f 2758 3057 2760 -f 2760 3057 2759 -f 2760 2759 2761 -f 2761 2759 2762 -f 2761 2762 2330 -f 2330 2762 2763 -f 2330 2763 2338 -f 2338 2763 2764 -f 2338 2764 2765 -f 2765 2764 3061 -f 2765 3061 2340 -f 2340 3061 3115 -f 3017 3790 3789 -f 2768 3777 2766 -f 3017 3789 2768 -f 2768 3789 2767 -f 2768 2767 3777 -f 2351 3790 3017 -f 2749 2351 3017 -f 2769 3065 2770 -f 2770 3065 3035 -f 2770 3035 3199 -f 3199 3035 3200 -f 3200 3035 2771 -f 3200 2771 3207 -f 3207 2771 3206 -f 3206 2771 2772 -f 3206 2772 3203 -f 3203 2772 2773 -f 3203 2773 3201 -f 3201 2773 2774 -f 2774 2773 2775 -f 2774 2775 2777 -f 2777 2775 2776 -f 2777 2776 3271 -f 3271 2776 3034 -f 3271 3034 3269 -f 3269 3034 3033 -f 3269 3033 2778 -f 2768 2766 3033 -f 2766 3779 3033 -f 3033 3779 2778 -f 2798 3063 2779 -f 2779 3063 2780 -f 2779 2780 2781 -f 2781 2780 2782 -f 2781 2782 2783 -f 2783 2782 2784 -f 2783 2784 2786 -f 2784 2785 2786 -f 2786 2785 3067 -f 2786 3067 2787 -f 2787 3067 2788 -f 2787 2788 3219 -f 3219 2788 3066 -f 3219 3066 3220 -f 3220 3066 3065 -f 3220 3065 2769 -f 3507 3506 2790 -f 2807 3393 2799 -f 2807 2799 3495 -f 3456 3463 3134 -f 3209 2789 3210 -f 3210 2789 3528 -f 3211 3210 3495 -f 3495 3210 3528 -f 2789 3209 3510 -f 3510 3209 3222 -f 2790 3506 3222 -f 3222 3506 3510 -f 2795 3504 2791 -f 2791 3504 2792 -f 2792 3504 2790 -f 2790 3504 3507 -f 2794 2793 2796 -f 2794 2796 2795 -f 2795 2796 3504 -f 3499 2289 3498 -f 2289 3499 2797 -f 2289 2797 2794 -f 2794 2797 2793 -f 3063 2798 3134 -f 3134 2798 3213 -f 3134 3213 3211 -f 3495 2799 3211 -f 3211 2799 3134 -f 3134 2799 2800 -f 3134 2800 3456 -f 3374 3453 3456 -f 3374 3456 2800 -f 2801 3378 2803 -f 3453 3374 2801 -f 3453 2801 3455 -f 3455 2801 2803 -f 2803 3378 2802 -f 2803 2802 3452 -f 3452 2802 3380 -f 3452 3380 3449 -f 3449 3380 3450 -f 3450 3380 2805 -f 3381 2804 3445 -f 3381 3445 3446 -f 3381 3446 2805 -f 2805 3446 3450 -f 2804 3381 3387 -f 3440 3442 3391 -f 3384 3389 2806 -f 3387 3386 2804 -f 2804 3386 2806 -f 2806 3386 3384 -f 2806 3389 3392 -f 3391 3442 2806 -f 3391 2806 3392 -f 2808 3511 3371 -f 3393 2807 2808 -f 3393 2808 2809 -f 2809 2808 3371 -f 3371 3511 3513 -f 3371 3513 3372 -f 3372 3513 3515 -f 3372 3515 3369 -f 3369 3515 2810 -f 2810 3515 3519 -f 3518 3361 3366 -f 3518 3366 3364 -f 3518 3364 3519 -f 3519 3364 2810 -f 3361 3518 2811 -f 3356 2814 3354 -f 2814 3356 3357 -f 3521 3525 2812 -f 2811 2813 3361 -f 3361 2813 2812 -f 2812 2813 3521 -f 2812 3525 3527 -f 2814 3357 2812 -f 2814 2812 3527 -f 3435 2815 3156 -f 3156 2815 3440 -f 3440 3391 3156 -f 3156 3391 3390 -f 3156 3390 2288 -f 3354 2814 3390 -f 3390 2814 2816 -f 3390 2816 2288 -f 2288 2816 3498 -f 2288 3498 2289 -f 3076 3084 3041 -f 3041 3084 2817 -f 3121 3136 2818 -f 2818 3136 3041 -f 2818 3041 3103 -f 3103 3041 2817 -f 3176 2819 2821 -f 3176 2821 2820 -f 2820 2821 2822 -f 2821 3754 2822 -f 2822 3754 2825 -f 2825 3754 2823 -f 2826 2827 2828 -f 2824 2825 3617 -f 3617 2825 2823 -f 3617 2823 3755 -f 2824 2826 2828 -f 2827 3686 3685 -f 2827 3685 2828 -f 2828 3685 3683 -f 3683 2839 2828 -f 2824 2828 2825 -f 2825 2828 3239 -f 2825 3239 2829 -f 2829 3239 2830 -f 2829 2830 2831 -f 2831 2830 3238 -f 2831 3238 3174 -f 3174 3238 3236 -f 3174 3236 2832 -f 2832 3236 3173 -f 3173 3236 2833 -f 3173 2833 3293 -f 3173 3293 3334 -f 3334 3293 3294 -f 3334 3294 2834 -f 2834 3294 3296 -f 2834 3296 2836 -f 2836 3296 3295 -f 3295 2835 2836 -f 2836 2835 3321 -f 2836 3321 2837 -f 2837 3321 3333 -f 3320 2409 3321 -f 3321 2409 3333 -f 3242 2838 3700 -f 3241 2838 3242 -f 2839 3683 3241 -f 3241 3683 2838 -f 3686 2827 2840 -f 2841 2842 2840 -f 2840 2842 3686 -f 2374 3691 2841 -f 2841 3691 2842 -f 3617 3755 2843 -f 3612 2843 3759 -f 2843 3612 3619 -f 2843 3619 3617 -f 3759 2375 3612 -f 2844 3557 3169 -f 3169 3557 2848 -f 2845 3553 2846 -f 2845 2846 3420 -f 2853 2847 2846 -f 2846 2847 3421 -f 2846 3421 3420 -f 3424 3485 3417 -f 3417 3485 3483 -f 3483 3488 2845 -f 3420 3418 2845 -f 2845 3418 3417 -f 2845 3417 3483 -f 2845 3488 2435 -f 2848 3553 3169 -f 3169 3553 2845 -f 3169 2845 3171 -f 3171 2845 3263 -f 3171 3263 2849 -f 3263 3262 2849 -f 2849 3262 2851 -f 2849 2851 3172 -f 3260 2511 2851 -f 2851 2511 2512 -f 2512 2850 2851 -f 2851 2850 2478 -f 2851 2478 3172 -f 3172 2478 2479 -f 3172 2479 2852 -f 3485 3424 3487 -f 3427 3487 3424 -f 2847 2853 3425 -f 3561 3425 2853 -f 3539 3541 3415 -f 3415 3541 2855 -f 2855 3541 3547 -f 3407 3413 2856 -f 2854 3476 3257 -f 3257 3476 3473 -f 3257 3473 3470 -f 3470 3409 2856 -f 2856 3409 3407 -f 2855 3547 3413 -f 3413 3547 3545 -f 3413 3545 2856 -f 2856 3545 3549 -f 3549 2857 2856 -f 3470 3469 3409 -f 3409 3469 3412 -f 3412 3469 3477 -f 3405 3477 3480 -f 3405 2858 3477 -f 3477 2858 3412 -f 3258 3476 2859 -f 2859 3476 2854 -f 3470 2856 3257 -f 3257 2856 3180 -f 3257 3180 2860 -f 2860 3180 3179 -f 2860 3179 2861 -f 2861 3179 2862 -f 2861 2862 2863 -f 2863 2862 3177 -f 2863 3177 2864 -f 2864 3177 3297 -f 3297 3177 3328 -f 3297 3328 2865 -f 3297 2865 3300 -f 3300 2865 3329 -f 3300 3329 2866 -f 2866 3329 3332 -f 2866 3332 2867 -f 2867 3332 3331 -f 3331 3330 2867 -f 2867 3330 2868 -f 2867 2868 3301 -f 3301 2868 3299 -f 2434 3298 2868 -f 2868 3298 3299 -f 2871 2869 2870 -f 3549 2869 2857 -f 2857 2869 2871 -f 2367 2370 3224 -f 3224 2370 3166 -f 3224 3166 3168 -f 3224 3168 3225 -f 3225 3168 2872 -f 3225 2872 3226 -f 2872 3164 3226 -f 3226 3164 2873 -f 3226 2873 3227 -f 3227 2873 2874 -f 3227 2874 3229 -f 3229 2874 2875 -f 3229 2875 3230 -f 3230 2875 3163 -f 3230 3163 2876 -f 2876 3163 3161 -f 2876 3161 2877 -f 2877 3161 3160 -f 2877 3160 3231 -f 3231 3160 2878 -f 3231 2878 3233 -f 3233 2878 2879 -f 3233 2879 3234 -f 3234 2879 3157 -f 3234 3157 3235 -f 3235 3157 2880 -f 3235 2880 2881 -f 2882 2972 2898 -f 2898 2972 2911 -f 2898 2911 2897 -f 2897 2911 2906 -f 2897 2906 2907 -f 2897 2907 2883 -f 2883 2907 2908 -f 2883 2908 2896 -f 2896 2908 2919 -f 2896 2919 2895 -f 2895 2919 2884 -f 2895 2884 2894 -f 2894 2884 2635 -f 2882 2898 2924 -f 2926 2924 2891 -f 2891 2924 2898 -f 2885 2926 2891 -f 2886 2885 2887 -f 2887 2885 2891 -f 2897 2891 2898 -f 2889 2886 2890 -f 2890 2886 2887 -f 2904 2891 2883 -f 2888 2889 2890 -f 2893 2890 2887 -f 2893 2887 2902 -f 2902 2887 2904 -f 2896 2904 2883 -f 2883 2891 2897 -f 2928 2888 2892 -f 2892 2888 2890 -f 2892 2890 2893 -f 2929 2928 2892 -f 2653 2929 2642 -f 2642 2929 2892 -f 2642 2892 2644 -f 2644 2892 2646 -f 2646 2892 2899 -f 2899 2892 2893 -f 2899 2893 2900 -f 2900 2893 2901 -f 2901 2893 2902 -f 2901 2902 2650 -f 2650 2902 2651 -f 2651 2902 2903 -f 2651 2903 2640 -f 2640 2903 2641 -f 2905 2641 2895 -f 2895 2641 2903 -f 2904 2903 2902 -f 2891 2904 2887 -f 2894 2905 2895 -f 2896 2895 2903 -f 2896 2903 2904 -f 2913 2906 2911 -f 2907 2906 2913 -f 2909 2907 2913 -f 2908 2907 2909 -f 2908 2909 2915 -f 2915 2909 2912 -f 2914 2913 2911 -f 2884 2919 2908 -f 2884 2908 2915 -f 2922 2915 2918 -f 2918 2915 2912 -f 2918 2912 2970 -f 2916 2970 2912 -f 2910 2912 2909 -f 2910 2909 2913 -f 2970 2917 2918 -f 2915 2922 2884 -f 2917 2920 2628 -f 2917 2628 2918 -f 2918 2628 2921 -f 2918 2921 2627 -f 2918 2627 2922 -f 2922 2627 2626 -f 2922 2626 2625 -f 2922 2625 2623 -f 2922 2623 2884 -f 2884 2623 2923 -f 2884 2923 2631 -f 2884 2631 2635 -f 3008 2882 2989 -f 2989 2882 2924 -f 2989 2924 2925 -f 2925 2924 2926 -f 2925 2926 2987 -f 2987 2926 2885 -f 2987 2885 2986 -f 2986 2885 2886 -f 2986 2886 2927 -f 2927 2886 2889 -f 2927 2889 2984 -f 2984 2889 2888 -f 2984 2888 2983 -f 2983 2888 2928 -f 2983 2928 2981 -f 2981 2928 2929 -f 2981 2929 2666 -f 2666 2929 2653 -f 2615 2920 2917 -f 2617 2615 2932 -f 2620 2933 2953 -f 2944 2621 2945 -f 2390 2931 2930 -f 2930 2931 2944 -f 2620 2953 2621 -f 2617 2932 2933 -f 2390 2930 3006 -f 3006 2930 2946 -f 3006 2946 3005 -f 3005 2946 2934 -f 3005 2934 3004 -f 3004 2934 2950 -f 3004 2950 2935 -f 2935 2950 2936 -f 2935 2936 2938 -f 2938 2936 2937 -f 2938 2937 2939 -f 2939 2937 2940 -f 2939 2940 2941 -f 2941 2940 2942 -f 2941 2942 2943 -f 2943 2942 2672 -f 2943 2672 2998 -f 2944 2945 2930 -f 2930 2945 2947 -f 2930 2947 2946 -f 2946 2947 2948 -f 2946 2948 2934 -f 2934 2948 2949 -f 2934 2949 2950 -f 2950 2949 2957 -f 2950 2957 2936 -f 2936 2957 2951 -f 2936 2951 2937 -f 2937 2951 2958 -f 2937 2958 2940 -f 2940 2958 2952 -f 2940 2952 2942 -f 2942 2952 2673 -f 2942 2673 2672 -f 2621 2953 2945 -f 2945 2953 2960 -f 2945 2960 2947 -f 2947 2960 2954 -f 2947 2954 2948 -f 2948 2954 2955 -f 2948 2955 2949 -f 2949 2955 2956 -f 2949 2956 2957 -f 2957 2956 2965 -f 2957 2965 2951 -f 2951 2965 2966 -f 2951 2966 2958 -f 2958 2966 2968 -f 2958 2968 2952 -f 2952 2968 2674 -f 2952 2674 2673 -f 2933 2932 2953 -f 2953 2932 2959 -f 2953 2959 2960 -f 2960 2959 2961 -f 2960 2961 2954 -f 2954 2961 2962 -f 2954 2962 2955 -f 2955 2962 2971 -f 2955 2971 2956 -f 2956 2971 2963 -f 2956 2963 2965 -f 2965 2963 2964 -f 2965 2964 2966 -f 2966 2964 2967 -f 2966 2967 2968 -f 2968 2967 2969 -f 2968 2969 2674 -f 2615 2917 2932 -f 2932 2917 2970 -f 2932 2970 2959 -f 2959 2970 2916 -f 2959 2916 2961 -f 2961 2916 2912 -f 2961 2912 2962 -f 2962 2912 2910 -f 2962 2910 2971 -f 2971 2910 2913 -f 2971 2913 2963 -f 2963 2913 2914 -f 2963 2914 2964 -f 2964 2914 2911 -f 2964 2911 2967 -f 2967 2911 2972 -f 2967 2972 2969 -f 3010 2973 2996 -f 2974 3010 2996 -f 2975 2996 2988 -f 2985 2975 2988 -f 2988 2996 2973 -f 3012 2974 2976 -f 2976 2974 2996 -f 2976 2996 2977 -f 2977 2996 2975 -f 2979 3012 2976 -f 2980 2977 2975 -f 2978 2979 2976 -f 2978 2976 2977 -f 2666 2982 2981 -f 2981 2982 2983 -f 2983 2982 2985 -f 2983 2985 2984 -f 2984 2985 2927 -f 2927 2985 2988 -f 2927 2988 2986 -f 2986 2988 2987 -f 2987 2988 2925 -f 2925 2988 2973 -f 2925 2973 2989 -f 2989 2973 3008 -f 2668 2978 2990 -f 2990 2978 2991 -f 2991 2978 2657 -f 2657 2978 2977 -f 2657 2977 2992 -f 2992 2977 2658 -f 2658 2977 2993 -f 2993 2977 2980 -f 2993 2980 2662 -f 2662 2980 2994 -f 2994 2980 2664 -f 2664 2980 2982 -f 2664 2982 2995 -f 2666 2995 2982 -f 2982 2980 2985 -f 2985 2980 2975 -f 3650 3651 3011 -f 3655 3653 3000 -f 3668 3005 3637 -f 2997 3005 3653 -f 3655 3000 2999 -f 3651 2999 3000 -f 3005 3000 3653 -f 3011 3651 3000 -f 3646 3650 3011 -f 3011 3000 3002 -f 3648 3646 3001 -f 3001 3646 3011 -f 3009 3002 2943 -f 2943 3002 2939 -f 2939 3002 2938 -f 2938 3002 3000 -f 2938 3000 2935 -f 3005 2997 3637 -f 2941 2943 2939 -f 3006 3003 2390 -f 2935 3000 3004 -f 3004 3000 3005 -f 3006 3005 3668 -f 3006 3668 3003 -f 3007 3011 3002 -f 3007 3002 3009 -f 2998 3008 2943 -f 2943 3008 2973 -f 2943 2973 3009 -f 3009 2973 3010 -f 3009 3010 3007 -f 3007 3010 2974 -f 3007 2974 3011 -f 3011 2974 3012 -f 3011 3012 3001 -f 3001 3012 2979 -f 3001 2979 3648 -f 3648 2979 2978 -f 3648 2978 3641 -f 3641 2978 2668 -f 3076 3041 3027 -f 3027 3041 3037 -f 3027 3037 3026 -f 3026 3037 3039 -f 3026 3039 3025 -f 3025 3039 3038 -f 3025 3038 3024 -f 3024 3038 3042 -f 3024 3042 3022 -f 3022 3042 3013 -f 3022 3013 3021 -f 3021 3013 3046 -f 3021 3046 3030 -f 3030 3046 3014 -f 3030 3014 3015 -f 3015 3014 3016 -f 3015 3016 2768 -f 2768 3016 3017 -f 3029 3074 3027 -f 3072 3074 3029 -f 3018 3072 3029 -f 3019 3018 3029 -f 3019 3029 3023 -f 3029 3027 3026 -f 3070 3019 3020 -f 3020 3019 3023 -f 3030 3023 3021 -f 3021 3023 3022 -f 3022 3023 3029 -f 3022 3029 3024 -f 3024 3029 3025 -f 3025 3029 3026 -f 3028 3070 3020 -f 3020 3023 3032 -f 3032 3023 3031 -f 3030 3031 3023 -f 3030 3015 3031 -f 3028 3020 3036 -f 3015 2768 3031 -f 3031 2768 3033 -f 3031 3033 3034 -f 3031 3034 3032 -f 3032 3034 2776 -f 3032 2776 2775 -f 3032 2775 3020 -f 3020 2775 2773 -f 3020 2773 2772 -f 3020 2772 2771 -f 3020 2771 3036 -f 3036 2771 3035 -f 3036 3035 3065 -f 3040 3037 3049 -f 3038 3039 3060 -f 3060 3039 3037 -f 3042 3038 3060 -f 3062 3040 3045 -f 3045 3040 3049 -f 3013 3042 3043 -f 3043 3042 3060 -f 3046 3013 3043 -f 3047 3043 3060 -f 3047 3060 3044 -f 3058 3062 3048 -f 3048 3062 3045 -f 3014 3046 3050 -f 3050 3046 3043 -f 3050 3043 3047 -f 3047 3044 3059 -f 3016 3014 3050 -f 3115 3048 3051 -f 3051 3048 3113 -f 3113 3048 3052 -f 3052 3048 3045 -f 3052 3045 3110 -f 3110 3045 3109 -f 3109 3045 3049 -f 3109 3049 3108 -f 3108 3049 3053 -f 3053 3049 3037 -f 3053 3037 3106 -f 3106 3037 3041 -f 3017 3016 3054 -f 3054 3016 3050 -f 3054 3050 2750 -f 2750 3050 3055 -f 3055 3050 2753 -f 2753 3050 3047 -f 2753 3047 2754 -f 2754 3047 3056 -f 3056 3047 2757 -f 2757 3047 3059 -f 2757 3059 3057 -f 3057 3059 2759 -f 2759 3059 3058 -f 2759 3058 2762 -f 2763 2762 3058 -f 3058 3059 3044 -f 3040 3044 3060 -f 3040 3060 3037 -f 2764 2763 3058 -f 3062 3058 3044 -f 3061 2764 3048 -f 3048 2764 3058 -f 3062 3044 3040 -f 3115 3061 3048 -f 2780 3063 3130 -f 2782 2780 3094 -f 2785 2784 3064 -f 3065 3066 3077 -f 3077 3066 2788 -f 2788 3067 3085 -f 3085 3067 2785 -f 2782 3094 2784 -f 3065 3077 3036 -f 3036 3077 3078 -f 3036 3078 3028 -f 3028 3078 3068 -f 3028 3068 3070 -f 3070 3068 3069 -f 3070 3069 3019 -f 3019 3069 3071 -f 3019 3071 3018 -f 3018 3071 3081 -f 3018 3081 3072 -f 3072 3081 3073 -f 3072 3073 3074 -f 3074 3073 3075 -f 3074 3075 3027 -f 3027 3075 3084 -f 3027 3084 3076 -f 2788 3085 3077 -f 3077 3085 3086 -f 3077 3086 3078 -f 3078 3086 3079 -f 3078 3079 3068 -f 3068 3079 3080 -f 3068 3080 3069 -f 3069 3080 3089 -f 3069 3089 3071 -f 3071 3089 3091 -f 3071 3091 3081 -f 3081 3091 3082 -f 3081 3082 3073 -f 3073 3082 3083 -f 3073 3083 3075 -f 3075 3083 2817 -f 3075 2817 3084 -f 2785 3064 3085 -f 3085 3064 3087 -f 3085 3087 3086 -f 3086 3087 3098 -f 3086 3098 3079 -f 3079 3098 3099 -f 3079 3099 3080 -f 3080 3099 3088 -f 3080 3088 3089 -f 3089 3088 3090 -f 3089 3090 3091 -f 3091 3090 3092 -f 3091 3092 3082 -f 3082 3092 3093 -f 3082 3093 3083 -f 3083 3093 3103 -f 3083 3103 2817 -f 2784 3094 3064 -f 3064 3094 3095 -f 3064 3095 3087 -f 3087 3095 3096 -f 3087 3096 3098 -f 3098 3096 3097 -f 3098 3097 3099 -f 3099 3097 3100 -f 3099 3100 3088 -f 3088 3100 3104 -f 3088 3104 3090 -f 3090 3104 3101 -f 3090 3101 3092 -f 3092 3101 3102 -f 3092 3102 3093 -f 3093 3102 2818 -f 3093 2818 3103 -f 2780 3130 3094 -f 3094 3130 3129 -f 3094 3129 3095 -f 3095 3129 3135 -f 3095 3135 3096 -f 3096 3135 3133 -f 3096 3133 3097 -f 3097 3133 3132 -f 3097 3132 3100 -f 3100 3132 3128 -f 3100 3128 3104 -f 3104 3128 3105 -f 3104 3105 3101 -f 3101 3105 3121 -f 3101 3121 3102 -f 3102 3121 2818 -f 3041 3136 3106 -f 3106 3136 3107 -f 3106 3107 3053 -f 3053 3107 3138 -f 3053 3138 3108 -f 3108 3138 3137 -f 3108 3137 3109 -f 3109 3137 3140 -f 3109 3140 3110 -f 3110 3140 3111 -f 3110 3111 3052 -f 3052 3111 3112 -f 3052 3112 3113 -f 3113 3112 3114 -f 3113 3114 3051 -f 3051 3114 3151 -f 3051 3151 3115 -f 3115 3151 3153 -f 3123 3433 3120 -f 3155 3117 3118 -f 3118 3435 3155 -f 3120 3433 3117 -f 3125 3127 3431 -f 3125 3116 3127 -f 3130 3463 3131 -f 3119 3120 3143 -f 3143 3120 3155 -f 3155 3120 3117 -f 3154 3105 3122 -f 3154 3122 3119 -f 3119 3122 3124 -f 3119 3124 3120 -f 3120 3124 3432 -f 3120 3432 3123 -f 3124 3126 3432 -f 3122 3132 3125 -f 3122 3125 3124 -f 3124 3125 3431 -f 3124 3431 3126 -f 3154 3121 3105 -f 3105 3128 3122 -f 3122 3128 3132 -f 3125 3129 3130 -f 3125 3130 3131 -f 3125 3131 3116 -f 3132 3133 3125 -f 3125 3133 3135 -f 3125 3135 3129 -f 3130 3134 3463 -f 3130 3063 3134 -f 3136 3154 3107 -f 3138 3107 3139 -f 3139 3107 3154 -f 3137 3138 3139 -f 3140 3137 3142 -f 3142 3137 3139 -f 3142 3139 3141 -f 3141 3139 3154 -f 3111 3140 3142 -f 3112 3111 3144 -f 3144 3111 3142 -f 3144 3142 3145 -f 3145 3142 3141 -f 3145 3141 3148 -f 3119 3143 3141 -f 3119 3141 3154 -f 3114 3112 3144 -f 3143 3155 3148 -f 3143 3148 3141 -f 3145 3146 3144 -f 3144 3146 3114 -f 3114 3146 3151 -f 3155 3156 3147 -f 3155 3147 3148 -f 3148 3147 2747 -f 3148 2747 2746 -f 3148 2746 3145 -f 3145 2746 2744 -f 3145 2744 2742 -f 3145 2742 3146 -f 3146 2742 3149 -f 3146 3149 3150 -f 3146 3150 3152 -f 3146 3152 3151 -f 3151 3152 3153 -f 3136 3121 3154 -f 3156 3155 3435 -f 2880 3157 2879 -f 2880 2879 3158 -f 3158 2879 2878 -f 3158 2878 3159 -f 2878 3160 3159 -f 3159 3160 3161 -f 3159 3161 3162 -f 3161 3163 3162 -f 3162 3163 2875 -f 3162 2875 2609 -f 2609 2875 2874 -f 2609 2874 2873 -f 2873 3164 2609 -f 2609 3164 2404 -f 2609 2404 9523 -f 2370 3165 3166 -f 3166 3165 3167 -f 3166 3167 3168 -f 3168 3167 2404 -f 3168 2404 2872 -f 2872 2404 3164 -f 2819 2407 2370 -f 2370 2407 3165 -f 3170 3560 2844 -f 2844 3169 3170 -f 3170 3169 3171 -f 3170 3171 2849 -f 2849 3172 3170 -f 3170 3172 2852 -f 3170 2852 2447 -f 3351 3325 3173 -f 2825 2829 3326 -f 3326 2829 2831 -f 3174 3326 2831 -f 3173 3325 3327 -f 3173 3327 2832 -f 2832 3327 3174 -f 3174 3327 3326 -f 3326 3175 2825 -f 2825 3175 2822 -f 2822 3175 2820 -f 2820 3175 3176 -f 3176 3175 2407 -f 3176 2407 2819 -f 3178 3328 3177 -f 3177 3264 3178 -f 3178 3264 3266 -f 3264 3177 2862 -f 3264 2862 3265 -f 3265 2862 3179 -f 3265 3179 3180 -f 3265 3180 2856 -f 3265 2856 2277 -f 2277 2856 2857 -f 2277 2857 2871 -f 2277 2871 3181 -f 3181 2871 2870 -f 3181 2870 3560 -f 3181 3560 3170 -f 3197 2389 3183 -f 3183 2389 2377 -f 3183 2377 2376 -f 2376 3182 3183 -f 2393 3324 3182 -f 3204 3202 3268 -f 3268 3184 3204 -f 3204 3184 3185 -f 3204 3185 3189 -f 3189 3185 3186 -f 3189 3186 2630 -f 2629 3346 3187 -f 3187 3346 3189 -f 3187 3189 3188 -f 3188 3189 2630 -f 2629 2614 3346 -f 3346 2614 3190 -f 3346 3190 3347 -f 3347 3190 2616 -f 3347 2616 3191 -f 3191 2616 2618 -f 3191 2618 3349 -f 3349 2618 3192 -f 3349 3192 3193 -f 3193 3192 2619 -f 3193 2619 3194 -f 3194 2619 3195 -f 3194 3195 3196 -f 3196 3195 2622 -f 3196 2622 3197 -f 3197 2622 3198 -f 3197 3198 2389 -f 2769 2770 3341 -f 3341 2770 3205 -f 2770 3199 3205 -f 3205 3199 3200 -f 3205 3200 3207 -f 2774 3202 3201 -f 3201 3202 3204 -f 3201 3204 3203 -f 3203 3204 3205 -f 3203 3205 3206 -f 3206 3205 3207 -f 3209 3210 3208 -f 3208 3222 3209 -f 3208 3210 3211 -f 3208 3211 3212 -f 3211 3213 3212 -f 3212 3213 2798 -f 3212 2798 3337 -f 3337 2798 2779 -f 3337 2779 3214 -f 3214 2779 2781 -f 3214 2781 3215 -f 3215 2781 2783 -f 3215 2783 3216 -f 3216 2783 2786 -f 3216 2786 3217 -f 3217 2786 2787 -f 3217 2787 3218 -f 3218 2787 3219 -f 3218 3219 3341 -f 3341 3219 3220 -f 3341 3220 2769 -f 3183 3182 3324 -f 3183 3324 3221 -f 3221 3324 3323 -f 3221 3323 3351 -f 3351 3323 3325 -f 3178 3266 3335 -f 3335 3266 3267 -f 3335 3267 3208 -f 3208 3267 3222 -f 9586 9545 2610 -f 2610 9545 9577 -f 2610 9577 2608 -f 2608 9577 3223 -f 3223 9577 9576 -f 3223 9576 9575 -f 9571 2881 9575 -f 9575 2881 2606 -f 9575 2606 3223 -f 9560 9558 2367 -f 2367 3224 9560 -f 9560 3224 9561 -f 3224 3225 9561 -f 9561 3225 3226 -f 9561 3226 3228 -f 3226 3227 3228 -f 3228 3227 3229 -f 3228 3229 9525 -f 3229 3230 9525 -f 9525 3230 2876 -f 9525 2876 9566 -f 2876 2877 9566 -f 9566 2877 3231 -f 9566 3231 3232 -f 3231 3233 3232 -f 3232 3233 3234 -f 3232 3234 9571 -f 9571 3234 3235 -f 9571 3235 2881 -f 9555 3700 9559 -f 9559 3700 2367 -f 9559 2367 9558 -f 3319 2833 3236 -f 3236 3275 3319 -f 3319 3275 3237 -f 3275 3236 3238 -f 3275 3238 3274 -f 3274 3238 2830 -f 3274 2830 3239 -f 3274 3239 2828 -f 3274 2828 3240 -f 3240 2828 2839 -f 3240 2839 3241 -f 3240 3241 9555 -f 9555 3241 3242 -f 9555 3242 3700 -f 3319 3237 3243 -f 3243 3237 3244 -f 3243 3244 3246 -f 3246 3244 3245 -f 3246 3245 3317 -f 3317 3245 3291 -f 3317 3291 3315 -f 3315 3291 3290 -f 3315 3290 3313 -f 3313 3290 3247 -f 3313 3247 3310 -f 3310 3247 3287 -f 3310 3287 3285 -f 3310 3285 3248 -f 3248 3285 3249 -f 3248 3249 3306 -f 3306 3249 3284 -f 3306 3284 3250 -f 3250 3284 3251 -f 3250 3251 3252 -f 3252 3251 3281 -f 3252 3281 3280 -f 3252 3280 3253 -f 3253 3280 3279 -f 3253 3279 3254 -f 3254 3279 3278 -f 3254 3278 3255 -f 3255 3278 3256 -f 3255 3256 3297 -f 3257 2860 3276 -f 3276 2860 2861 -f 2863 3276 2861 -f 3297 3256 2864 -f 2864 3256 3276 -f 2864 3276 2863 -f 2854 9547 2859 -f 2859 9547 3258 -f 3258 9547 3261 -f 3258 3261 2436 -f 3276 9547 3257 -f 3257 9547 2854 -f 3261 3259 3260 -f 3260 2851 3261 -f 3261 2851 3262 -f 3261 3262 3263 -f 3263 2845 3261 -f 3261 2845 2435 -f 3261 2435 2436 -f 3264 3265 2268 -f 2791 3267 2268 -f 2268 3267 3266 -f 2268 3266 3264 -f 2791 2792 3267 -f 3267 2792 2790 -f 3267 2790 3222 -f 2624 3268 3202 -f 3271 3202 2777 -f 2777 3202 2774 -f 3269 2632 3270 -f 3269 3270 3271 -f 3271 3270 3202 -f 3202 3270 3272 -f 3202 3272 2624 -f 3275 3274 3273 -f 3273 3244 3237 -f 3273 3237 3275 -f 3277 3276 3256 -f 3277 3256 9540 -f 3256 3278 9540 -f 9540 3278 9539 -f 3278 3279 9539 -f 9539 3279 9542 -f 9542 3279 3280 -f 9542 3280 3281 -f 9542 3281 3282 -f 3281 3251 3282 -f 3282 3251 3283 -f 3251 3284 3283 -f 3283 3284 9544 -f 9544 3284 3249 -f 9544 3249 9550 -f 9550 3249 3285 -f 9550 3285 9549 -f 9549 3285 3286 -f 3286 3285 3287 -f 3286 3287 3288 -f 3288 3287 3247 -f 3288 3247 3289 -f 3289 3247 3290 -f 3289 3290 3292 -f 3290 3291 3292 -f 3292 3291 9562 -f 3291 3245 9562 -f 9562 3245 3273 -f 3273 3245 3244 -f 2833 3319 3293 -f 3293 3319 3294 -f 2835 3295 3319 -f 3319 3295 3296 -f 3294 3319 3296 -f 3301 3299 3255 -f 3255 3299 3298 -f 3255 3297 3300 -f 3255 3300 2866 -f 3255 2866 2867 -f 3255 2867 3301 -f 3255 3298 3254 -f 3254 3298 3302 -f 3254 3302 3303 -f 3254 3303 3253 -f 3253 3303 3304 -f 3253 3304 2431 -f 3253 2431 3252 -f 3252 2431 2429 -f 3252 2429 3305 -f 3252 3305 3250 -f 3250 3305 2427 -f 3250 2427 2426 -f 3250 2426 3306 -f 3306 2426 3307 -f 3306 3307 3308 -f 3306 3308 3248 -f 3248 3308 3309 -f 3248 3309 2423 -f 3248 2423 3310 -f 3310 2423 3311 -f 3310 3311 3312 -f 3310 3312 3313 -f 3313 3312 3314 -f 3313 3314 2421 -f 3313 2421 3315 -f 3315 2421 2420 -f 3315 2420 3317 -f 3317 2420 3316 -f 3317 3316 3318 -f 3317 3318 3246 -f 3246 3318 2417 -f 3246 2417 2415 -f 3246 2415 3243 -f 3243 2415 2412 -f 3243 2412 2411 -f 3243 2411 3319 -f 3319 2411 3320 -f 3319 3320 3321 -f 3319 3321 2835 -f 2394 3323 3322 -f 3322 3323 3324 -f 3322 3324 2393 -f 3326 3327 3325 -f 3326 3325 3323 -f 3326 3323 2403 -f 2403 3323 2394 -f 2403 2394 2395 -f 3328 3178 2865 -f 2865 3178 3329 -f 3330 3331 3178 -f 3330 3178 2868 -f 3178 3331 3332 -f 3329 3178 3332 -f 2837 3333 3351 -f 3351 3333 2409 -f 3351 3173 3334 -f 3351 3334 2834 -f 3351 2834 2836 -f 3351 2836 2837 -f 2868 3178 2434 -f 2434 3178 2433 -f 2433 3178 3335 -f 2433 3335 2432 -f 2432 3335 3208 -f 2432 3208 3336 -f 3336 3208 3212 -f 3336 3212 2430 -f 2430 3212 3337 -f 2430 3337 2428 -f 2428 3337 3214 -f 2428 3214 3338 -f 3338 3214 3215 -f 3338 3215 2425 -f 2425 3215 3216 -f 2425 3216 3339 -f 3339 3216 3217 -f 3339 3217 2424 -f 2424 3217 3218 -f 2424 3218 3340 -f 3340 3218 3341 -f 3340 3341 3342 -f 3342 3341 3205 -f 3342 3205 3343 -f 3343 3205 3204 -f 3343 3204 3344 -f 3344 3204 3189 -f 3344 3189 3345 -f 3345 3189 3346 -f 3345 3346 2422 -f 2422 3346 3347 -f 2422 3347 3348 -f 3348 3347 3191 -f 3348 3191 2419 -f 2419 3191 3349 -f 2419 3349 2418 -f 2418 3349 3193 -f 2418 3193 3350 -f 3350 3193 3194 -f 3350 3194 2416 -f 2416 3194 3196 -f 2416 3196 2414 -f 2414 3196 3197 -f 2414 3197 2413 -f 2413 3197 3183 -f 2413 3183 2410 -f 2410 3183 3221 -f 2410 3221 2409 -f 2409 3221 3351 -f 2799 3396 3398 -f 2799 3398 3397 -f 2799 3397 2800 -f 2800 3397 3352 -f 2800 3352 3403 -f 2800 3403 3402 -f 3419 3353 3390 -f 3390 3353 3354 -f 3354 3353 3355 -f 3354 3355 3356 -f 3356 3355 3422 -f 3356 3422 3358 -f 3356 3358 3357 -f 3357 3358 3359 -f 3357 3359 2812 -f 3360 3361 3362 -f 3362 3361 3359 -f 3359 3361 2812 -f 3365 3366 3360 -f 3360 3366 3361 -f 3363 2810 3364 -f 3363 3364 3365 -f 3365 3364 3366 -f 3416 3369 3367 -f 3367 3369 2810 -f 3367 2810 3363 -f 3414 3372 3368 -f 3368 3372 3416 -f 3416 3372 3369 -f 3370 3371 3414 -f 3414 3371 3372 -f 3394 3393 3373 -f 3373 3393 3370 -f 3370 3393 2809 -f 3370 2809 3371 -f 3374 3411 2801 -f 2801 3411 3375 -f 2801 3375 3378 -f 3375 3376 3378 -f 3378 3376 3377 -f 3378 3377 2802 -f 3406 3380 3377 -f 3377 3380 2802 -f 3379 2805 3404 -f 2805 3380 3404 -f 3404 3380 3406 -f 3382 3426 3387 -f 3387 3381 3382 -f 3382 3381 2805 -f 3382 2805 3379 -f 3385 3383 3384 -f 3384 3386 3385 -f 3385 3386 3426 -f 3426 3386 3387 -f 3423 3388 3392 -f 3392 3389 3423 -f 3423 3389 3383 -f 3383 3389 3384 -f 3390 3391 3419 -f 3419 3391 3388 -f 3388 3391 3392 -f 2799 3393 3394 -f 2799 3394 3396 -f 3396 3394 3395 -f 3399 3398 3395 -f 3395 3398 3396 -f 3408 3397 3399 -f 3399 3397 3398 -f 3400 3352 3408 -f 3408 3352 3397 -f 3410 3403 3400 -f 3400 3403 3352 -f 3411 3374 2800 -f 3411 2800 3401 -f 3401 2800 3402 -f 3401 3402 3410 -f 3410 3402 3403 -f 3404 3405 3379 -f 3377 3405 3406 -f 3406 3405 3404 -f 3375 2858 3376 -f 3376 2858 3377 -f 3377 2858 3405 -f 3373 3407 3394 -f 3394 3407 3395 -f 3395 3407 3399 -f 3399 3407 3409 -f 3399 3409 3408 -f 3408 3409 3400 -f 3400 3409 3412 -f 3400 3412 3410 -f 3410 3412 3401 -f 3401 3412 3411 -f 3411 3412 3375 -f 3375 3412 2858 -f 3414 2855 3370 -f 3370 2855 3373 -f 3373 2855 3413 -f 3373 3413 3407 -f 3368 3415 3414 -f 3414 3415 2855 -f 3416 3415 3368 -f 3367 3415 3416 -f 3415 3367 3363 -f 3425 3362 3359 -f 3423 3417 3388 -f 3388 3417 3418 -f 3388 3418 3419 -f 3419 3418 3420 -f 3419 3420 3353 -f 3353 3420 3421 -f 3353 3421 3355 -f 3355 3421 2847 -f 3355 2847 3422 -f 3422 2847 3358 -f 3358 2847 3359 -f 3359 2847 3425 -f 3383 3424 3423 -f 3423 3424 3417 -f 3385 3424 3383 -f 3426 3427 3385 -f 3385 3427 3424 -f 3362 3425 3360 -f 3360 3425 2400 -f 3360 2400 3365 -f 3365 2400 3363 -f 3363 2400 3415 -f 3379 3405 3427 -f 3379 3427 3382 -f 3382 3427 3426 -f 3456 3458 3459 -f 3456 3459 3463 -f 3459 3461 3463 -f 3463 3461 3428 -f 3463 3428 3429 -f 3475 3467 3116 -f 3116 3467 3430 -f 3116 3430 3127 -f 3468 3126 3431 -f 3468 3431 3430 -f 3430 3431 3127 -f 3468 3465 3126 -f 3126 3465 3466 -f 3126 3466 3432 -f 3432 3466 3493 -f 3432 3493 3123 -f 3123 3493 3494 -f 3123 3494 3433 -f 3490 3433 3494 -f 3434 3117 3490 -f 3490 3117 3433 -f 3489 3437 3118 -f 3489 3118 3434 -f 3434 3118 3117 -f 3438 2815 3436 -f 2815 3435 3436 -f 3436 3435 3437 -f 3437 3435 3118 -f 2815 3438 3439 -f 2815 3439 3440 -f 3440 3439 3484 -f 3440 3484 3441 -f 3440 3441 3442 -f 3442 3441 3443 -f 3442 3443 3486 -f 3442 3486 2806 -f 3444 2804 3482 -f 3482 2804 3486 -f 3486 2804 2806 -f 3447 3445 3444 -f 3444 3445 2804 -f 3492 3450 3446 -f 3492 3446 3447 -f 3447 3446 3445 -f 3448 3449 3481 -f 3481 3449 3450 -f 3481 3450 3492 -f 3451 3452 3479 -f 3479 3452 3448 -f 3448 3452 3449 -f 3454 2803 3451 -f 3451 2803 3452 -f 3457 3453 3478 -f 3478 3453 3454 -f 3454 3453 3455 -f 3454 3455 2803 -f 3456 3453 3457 -f 3456 3457 3458 -f 3458 3457 3471 -f 3472 3459 3471 -f 3471 3459 3458 -f 3460 3461 3472 -f 3472 3461 3459 -f 3462 3428 3460 -f 3460 3428 3461 -f 3464 3429 3462 -f 3462 3429 3428 -f 3116 3131 3475 -f 3475 3131 3463 -f 3475 3463 3474 -f 3474 3463 3464 -f 3464 3463 3429 -f 3258 2436 3466 -f 3466 2436 3493 -f 3468 3258 3465 -f 3465 3258 3466 -f 3467 3476 3430 -f 3430 3476 3468 -f 3468 3476 3258 -f 3478 3469 3457 -f 3457 3469 3470 -f 3457 3470 3471 -f 3471 3470 3472 -f 3472 3470 3460 -f 3460 3470 3473 -f 3460 3473 3462 -f 3462 3473 3464 -f 3464 3473 3474 -f 3474 3473 3476 -f 3474 3476 3475 -f 3475 3476 3467 -f 3451 3477 3454 -f 3454 3477 3478 -f 3478 3477 3469 -f 3479 3477 3451 -f 3448 3477 3479 -f 3481 3480 3448 -f 3448 3480 3477 -f 3480 3481 3492 -f 3487 3482 3486 -f 3437 3488 3436 -f 3436 3488 3438 -f 3438 3488 3483 -f 3438 3483 3439 -f 3439 3483 3484 -f 3484 3483 3485 -f 3484 3485 3441 -f 3441 3485 3443 -f 3443 3485 3486 -f 3486 3485 3487 -f 3489 3488 3437 -f 3434 3488 3489 -f 3490 2435 3434 -f 3434 2435 3488 -f 3482 3487 3444 -f 3444 3487 3491 -f 3444 3491 3447 -f 3447 3491 3492 -f 3492 3491 3480 -f 3493 2436 3494 -f 3494 2436 2435 -f 3494 2435 3490 -f 3528 3529 3532 -f 3528 3532 3495 -f 3495 3532 3531 -f 3495 3531 3534 -f 3495 3534 3496 -f 3495 3496 3538 -f 3554 3497 2816 -f 2816 3497 3498 -f 3498 3497 3555 -f 3498 3555 3499 -f 3499 3555 3556 -f 3499 3556 3500 -f 3499 3500 2797 -f 2797 3500 3502 -f 3558 2793 3501 -f 3501 2793 3502 -f 3502 2793 2797 -f 3559 2796 3558 -f 3558 2796 2793 -f 3552 3504 2796 -f 3552 2796 3559 -f 3505 3507 3503 -f 3503 3507 3504 -f 3503 3504 3552 -f 3550 3506 3551 -f 3551 3506 3505 -f 3505 3506 3507 -f 3509 3510 3550 -f 3550 3510 3506 -f 3543 2789 3508 -f 3508 2789 3509 -f 3509 2789 3510 -f 2807 3535 2808 -f 2808 3535 3548 -f 2808 3548 3511 -f 3548 3512 3511 -f 3511 3512 3542 -f 3511 3542 3513 -f 3516 3515 3542 -f 3542 3515 3513 -f 3540 3519 3514 -f 3519 3515 3514 -f 3514 3515 3516 -f 3517 3522 2811 -f 2811 3518 3517 -f 3517 3518 3519 -f 3517 3519 3540 -f 3520 3526 3521 -f 3521 2813 3520 -f 3520 2813 3522 -f 3522 2813 2811 -f 3524 3523 3527 -f 3527 3525 3524 -f 3524 3525 3526 -f 3526 3525 3521 -f 2816 2814 3554 -f 3554 2814 3523 -f 3523 2814 3527 -f 3528 2789 3543 -f 3528 3543 3529 -f 3529 3543 3530 -f 3544 3532 3530 -f 3530 3532 3529 -f 3533 3531 3544 -f 3544 3531 3532 -f 3546 3534 3533 -f 3533 3534 3531 -f 3537 3496 3546 -f 3546 3496 3534 -f 3535 2807 3495 -f 3535 3495 3536 -f 3536 3495 3538 -f 3536 3538 3537 -f 3537 3538 3496 -f 3514 3539 3540 -f 3542 3539 3516 -f 3516 3539 3514 -f 3548 3541 3512 -f 3512 3541 3542 -f 3542 3541 3539 -f 3508 3549 3543 -f 3543 3549 3530 -f 3530 3549 3544 -f 3544 3549 3545 -f 3544 3545 3533 -f 3533 3545 3546 -f 3546 3545 3547 -f 3546 3547 3537 -f 3537 3547 3536 -f 3536 3547 3535 -f 3535 3547 3548 -f 3548 3547 3541 -f 3550 2869 3509 -f 3509 2869 3549 -f 3509 3549 3508 -f 3551 2869 3550 -f 3505 2869 3551 -f 3560 2870 3503 -f 3503 2870 3505 -f 3505 2870 2869 -f 3560 3503 3552 -f 3557 3501 3502 -f 3524 2846 3523 -f 3523 2846 3553 -f 3523 3553 3554 -f 3554 3553 3497 -f 3497 3553 2848 -f 3497 2848 3555 -f 3555 2848 3556 -f 3556 2848 3557 -f 3556 3557 3500 -f 3500 3557 3502 -f 3526 2853 3524 -f 3524 2853 2846 -f 3520 2853 3526 -f 3522 3561 3520 -f 3520 3561 2853 -f 3557 2844 3501 -f 3501 2844 3558 -f 3558 2844 3559 -f 3559 2844 3552 -f 3552 2844 3560 -f 3540 3539 3561 -f 3540 3561 3517 -f 3517 3561 3522 -f 3602 3563 3562 -f 3562 3563 3564 -f 3562 3564 2381 -f 2381 3564 3565 -f 2381 3565 3606 -f 2381 3606 3609 -f 3600 3566 2671 -f 2671 3566 3568 -f 3568 3566 3567 -f 3568 3567 3569 -f 3568 3569 3570 -f 3570 3569 3635 -f 3570 3635 3574 -f 3570 3574 3571 -f 3572 2384 3573 -f 3573 2384 3574 -f 3574 2384 3571 -f 3577 3575 3572 -f 3572 3575 2384 -f 3579 3580 3576 -f 3579 3576 3577 -f 3577 3576 3575 -f 3624 3582 3578 -f 3578 3582 3580 -f 3578 3580 3579 -f 3623 3581 3622 -f 3622 3581 3624 -f 3624 3581 3582 -f 3620 3583 3623 -f 3623 3583 3581 -f 3603 3584 3621 -f 3621 3584 3620 -f 3620 3584 3585 -f 3620 3585 3583 -f 3607 3618 3586 -f 3586 3618 3587 -f 3586 3587 3588 -f 3587 3613 3588 -f 3588 3613 3610 -f 3588 3610 3589 -f 3611 3591 3610 -f 3610 3591 3589 -f 3625 3593 3590 -f 3593 3591 3590 -f 3590 3591 3611 -f 3626 3627 3596 -f 3596 3592 3626 -f 3626 3592 3593 -f 3626 3593 3625 -f 3594 3628 3598 -f 3598 3595 3594 -f 3594 3595 3627 -f 3627 3595 3596 -f 3629 3631 3601 -f 3601 3597 3629 -f 3629 3597 3628 -f 3628 3597 3598 -f 2671 3599 3600 -f 3600 3599 3601 -f 3600 3601 3631 -f 3562 3584 3603 -f 3562 3603 3602 -f 3602 3603 3614 -f 3604 3563 3614 -f 3614 3563 3602 -f 3605 3564 3604 -f 3604 3564 3563 -f 3615 3565 3605 -f 3605 3565 3564 -f 3616 3606 3615 -f 3615 3606 3565 -f 3618 3607 2381 -f 3618 2381 3608 -f 3608 2381 3609 -f 3608 3609 3616 -f 3616 3609 3606 -f 3590 3612 2375 -f 3590 2375 3625 -f 3610 3612 3611 -f 3611 3612 3590 -f 3587 3619 3613 -f 3613 3619 3612 -f 3613 3612 3610 -f 3621 2826 3603 -f 3603 2826 3614 -f 3614 2826 3604 -f 3604 2826 2824 -f 3604 2824 3605 -f 3605 2824 3615 -f 3615 2824 3616 -f 3616 2824 3608 -f 3608 2824 3617 -f 3608 3617 3618 -f 3618 3617 3587 -f 3587 3617 3619 -f 3623 2840 3620 -f 3620 2840 3621 -f 3621 2840 2827 -f 3621 2827 2826 -f 3622 2841 3623 -f 3623 2841 2840 -f 3624 2841 3622 -f 3578 2841 3624 -f 2841 3578 2374 -f 2374 3578 3579 -f 3625 2375 3626 -f 3626 2375 3627 -f 3627 2375 2372 -f 3627 2372 3594 -f 3594 2372 3628 -f 3628 2372 3629 -f 3629 2372 3630 -f 3629 3630 3631 -f 3631 3630 3632 -f 3631 3632 3600 -f 3600 3632 3566 -f 3566 3632 3633 -f 3566 3633 3567 -f 3567 3633 3634 -f 3567 3634 3569 -f 3569 3634 3635 -f 3635 3634 2368 -f 3635 2368 3574 -f 3574 2368 2369 -f 3574 2369 3573 -f 3573 2369 3572 -f 3572 2369 3577 -f 3577 2369 2374 -f 3577 2374 3579 -f 3671 3669 3668 -f 3668 3669 3672 -f 3668 3672 3636 -f 3636 3672 3678 -f 3636 3678 3676 -f 3637 3638 3681 -f 3696 2613 3639 -f 3639 2613 2669 -f 3639 2669 3694 -f 3640 2613 3696 -f 3642 3641 3640 -f 3640 3641 2613 -f 3644 3641 3642 -f 3643 3648 3644 -f 3644 3648 3641 -f 3647 3648 3643 -f 3645 3646 3699 -f 3699 3646 3647 -f 3647 3646 3648 -f 3690 3651 3649 -f 3649 3651 3645 -f 3645 3651 3650 -f 3645 3650 3646 -f 3654 2999 3690 -f 3690 2999 3651 -f 3689 3653 3652 -f 3652 3653 3654 -f 3654 3653 3655 -f 3654 3655 2999 -f 3637 2997 3638 -f 3638 2997 3689 -f 3689 2997 3653 -f 3674 3675 2382 -f 2382 3675 3688 -f 2382 3688 3656 -f 3688 3680 3656 -f 3656 3680 3658 -f 3656 3658 2383 -f 3657 3659 3658 -f 3658 3659 2383 -f 3661 2386 3679 -f 2386 3659 3679 -f 3679 3659 3657 -f 3660 3692 3664 -f 3664 2385 3660 -f 3660 2385 2386 -f 3660 2386 3661 -f 3662 3665 2387 -f 2387 3663 3662 -f 3662 3663 3692 -f 3692 3663 3664 -f 3693 3667 3666 -f 3666 2388 3693 -f 3693 2388 3665 -f 3665 2388 2387 -f 2669 2667 3694 -f 3694 2667 3666 -f 3694 3666 3667 -f 3668 3637 3681 -f 3668 3681 3682 -f 3670 3671 3682 -f 3682 3671 3668 -f 3684 3669 3670 -f 3670 3669 3671 -f 3673 3672 3684 -f 3684 3672 3669 -f 3677 3678 3673 -f 3673 3678 3672 -f 3675 3674 3636 -f 3675 3636 3687 -f 3687 3636 3676 -f 3687 3676 3677 -f 3677 3676 3678 -f 3679 2842 3691 -f 3679 3691 3661 -f 3658 2842 3657 -f 3657 2842 3679 -f 3688 2842 3680 -f 3680 2842 3658 -f 3638 3683 3681 -f 3681 3683 3682 -f 3682 3683 3670 -f 3670 3683 3685 -f 3670 3685 3684 -f 3684 3685 3673 -f 3673 3685 3686 -f 3673 3686 3677 -f 3677 3686 3687 -f 3687 3686 3675 -f 3675 3686 3688 -f 3688 3686 2842 -f 3652 3683 3689 -f 3689 3683 3638 -f 3654 2838 3652 -f 3652 2838 3683 -f 3690 2838 3654 -f 3700 2838 3649 -f 3649 2838 3690 -f 3700 3649 3645 -f 3661 3691 3660 -f 3660 3691 3692 -f 3692 3691 2366 -f 3692 2366 3662 -f 3662 2366 3665 -f 3665 2366 3693 -f 3693 2366 3695 -f 3693 3695 3667 -f 3667 3695 3694 -f 3694 3695 3697 -f 3694 3697 3639 -f 3639 3697 3696 -f 3696 3697 3640 -f 3640 3697 3642 -f 3642 3697 3698 -f 3642 3698 3644 -f 3644 3698 3643 -f 3643 3698 2365 -f 3643 2365 3647 -f 3647 2365 3699 -f 3699 2365 3700 -f 3699 3700 3645 -f 3742 3744 3701 -f 3701 3744 3702 -f 3701 3702 3746 -f 3701 3746 3703 -f 3703 3746 3748 -f 3703 3748 3751 -f 3764 3766 3704 -f 3704 3766 3706 -f 3706 3766 3705 -f 3706 3705 3707 -f 3706 3707 3708 -f 3708 3707 3768 -f 3708 3768 3710 -f 3708 3710 3711 -f 3769 3713 3709 -f 3709 3713 3710 -f 3710 3713 3711 -f 3770 3712 3769 -f 3769 3712 3713 -f 3715 2379 2380 -f 3715 2380 3770 -f 3770 2380 3712 -f 3718 3717 3714 -f 3714 3717 2379 -f 3714 2379 3715 -f 3757 3716 3758 -f 3758 3716 3718 -f 3718 3716 3717 -f 3722 3719 3757 -f 3757 3719 3716 -f 3720 2378 3756 -f 3756 2378 3722 -f 3722 2378 3721 -f 3722 3721 3719 -f 3723 3753 2391 -f 2391 3753 3724 -f 2391 3724 2392 -f 3724 3725 2392 -f 2392 3725 3726 -f 2392 3726 3727 -f 3732 3731 3726 -f 3726 3731 3727 -f 3728 3729 3730 -f 3729 3731 3730 -f 3730 3731 3732 -f 3734 3761 3736 -f 3736 3733 3734 -f 3734 3733 3728 -f 3728 3733 3729 -f 3735 3739 2399 -f 2399 3736 3735 -f 3735 3736 3761 -f 3737 3763 3741 -f 3741 3738 3737 -f 3737 3738 3739 -f 3739 3738 2399 -f 3704 3740 3764 -f 3764 3740 3763 -f 3763 3740 3741 -f 3701 2378 3720 -f 3701 3720 3742 -f 3742 3720 3743 -f 3752 3744 3743 -f 3743 3744 3742 -f 3745 3702 3752 -f 3752 3702 3744 -f 3747 3746 3745 -f 3745 3746 3702 -f 3750 3748 3747 -f 3747 3748 3746 -f 3753 3723 3703 -f 3753 3703 3749 -f 3749 3703 3751 -f 3749 3751 3750 -f 3750 3751 3748 -f 3730 2819 3728 -f 3726 2821 3732 -f 3732 2821 3730 -f 3730 2821 2819 -f 3724 2821 3725 -f 3725 2821 3726 -f 3756 3755 3720 -f 3720 3755 3743 -f 3743 3755 2823 -f 3743 2823 3752 -f 3752 2823 3745 -f 3745 2823 3754 -f 3745 3754 3747 -f 3747 3754 3750 -f 3750 3754 3749 -f 3749 3754 3753 -f 3753 3754 3724 -f 3724 3754 2821 -f 3757 2843 3722 -f 3722 2843 3755 -f 3722 3755 3756 -f 3758 2843 3757 -f 3718 2843 3758 -f 3714 3759 3718 -f 3718 3759 2843 -f 3759 3714 3715 -f 3728 2819 3734 -f 3734 2819 3760 -f 3734 3760 3761 -f 3761 3760 3735 -f 3735 3760 3739 -f 3739 3760 3762 -f 3739 3762 3737 -f 3737 3762 3763 -f 3763 3762 3764 -f 3764 3762 3765 -f 3764 3765 3766 -f 3766 3765 3705 -f 3705 3765 3767 -f 3705 3767 3707 -f 3707 3767 3768 -f 3768 3767 2371 -f 3768 2371 3710 -f 3710 2371 2373 -f 3710 2373 3709 -f 3709 2373 3769 -f 3769 2373 3770 -f 3770 2373 3759 -f 3770 3759 3715 -f 2767 3789 3771 -f 3781 3772 3771 -f 2401 2402 3776 -f 3775 2633 3776 -f 3776 3773 3774 -f 3780 3772 3773 -f 3772 3780 3771 -f 2401 3776 2633 -f 3780 3773 3776 -f 3776 3774 2634 -f 3776 2634 3775 -f 3771 3780 2767 -f 3780 3777 2767 -f 3777 3780 3778 -f 3777 3778 2766 -f 3778 2778 3779 -f 3778 3779 2766 -f 2402 2778 3778 -f 2402 3778 3776 -f 3776 3778 3780 -f 3784 3785 2637 -f 2639 3786 3783 -f 3787 3781 3771 -f 3781 3787 3782 -f 3782 3787 2638 -f 2638 3787 3786 -f 2638 3786 2639 -f 3783 3786 3784 -f 3784 3786 3785 -f 2637 3785 2636 -f 3791 3786 3787 -f 3786 3791 3785 -f 3785 3791 3788 -f 2352 3788 3791 -f 3791 3790 2351 -f 3790 3791 3787 -f 3789 3790 3787 -f 3771 3789 3787 -f 2351 2352 3791 -f 3804 3808 3810 -f 3792 3808 3804 -f 3804 3813 3793 -f 3812 3813 3804 -f 3810 3812 3804 -f 3804 3794 3817 -f 3816 3794 3804 -f 3793 3816 3804 -f 3804 3795 3819 -f 3796 3795 3804 -f 3817 3796 3804 -f 3804 3797 3798 -f 3821 3797 3804 -f 3819 3821 3804 -f 3804 3826 3799 -f 3825 3826 3804 -f 3798 3825 3804 -f 3804 3829 3831 -f 3827 3829 3804 -f 3799 3827 3804 -f 3804 3801 3834 -f 3800 3801 3804 -f 3831 3800 3804 -f 3804 3802 3805 -f 3836 3802 3804 -f 3834 3836 3804 -f 3804 3803 3806 -f 3839 3803 3804 -f 3805 3839 3804 -f 3804 3841 3842 -f 3840 3841 3804 -f 3806 3840 3804 -f 3804 3846 3847 -f 3844 3846 3804 -f 3842 3844 3804 -f 3847 3792 3804 -f 3792 3807 3808 -f 3808 3807 3809 -f 3808 3809 3810 -f 3810 3809 3811 -f 3810 3811 3812 -f 3812 3811 2549 -f 3812 2549 3813 -f 3813 2549 3814 -f 3813 3814 3793 -f 3793 3814 3815 -f 3793 3815 3816 -f 3816 3815 2555 -f 3816 2555 3794 -f 3794 2555 2554 -f 3794 2554 3817 -f 3817 2554 2550 -f 3817 2550 3796 -f 3796 2550 3818 -f 3796 3818 3795 -f 3795 3818 3820 -f 3795 3820 3819 -f 3819 3820 2562 -f 3819 2562 3821 -f 3821 2562 3822 -f 3821 3822 3797 -f 3797 3822 3823 -f 3797 3823 3798 -f 3798 3823 3824 -f 3798 3824 3825 -f 3825 3824 2547 -f 3825 2547 3826 -f 3826 2547 2546 -f 3826 2546 3799 -f 3799 2546 2539 -f 3799 2539 3827 -f 3827 2539 3828 -f 3827 3828 3829 -f 3829 3828 3830 -f 3829 3830 3831 -f 3831 3830 3832 -f 3831 3832 3800 -f 3800 3832 2540 -f 3800 2540 3801 -f 3801 2540 3833 -f 3801 3833 3834 -f 3834 3833 3835 -f 3834 3835 3836 -f 3836 3835 3837 -f 3836 3837 3802 -f 3802 3837 3838 -f 3802 3838 3805 -f 3805 3838 2559 -f 3805 2559 3839 -f 3839 2559 2557 -f 3839 2557 3803 -f 3803 2557 2556 -f 3803 2556 3806 -f 3806 2556 2553 -f 3806 2553 3840 -f 3840 2553 2552 -f 3840 2552 3841 -f 3841 2552 2551 -f 3841 2551 3842 -f 3842 2551 3843 -f 3842 3843 3844 -f 3844 3843 3845 -f 3844 3845 3846 -f 3846 3845 2545 -f 3846 2545 3847 -f 3847 2545 3848 -f 3847 3848 3792 -f 3792 3848 3807 -f 3860 3850 3849 -f 3866 3850 3860 -f 3860 3851 3853 -f 3908 3851 3860 -f 3849 3908 3860 -f 3860 3868 3869 -f 3852 3868 3860 -f 3853 3852 3860 -f 3860 3854 3875 -f 3872 3854 3860 -f 3869 3872 3860 -f 3860 3877 3855 -f 3856 3877 3860 -f 3875 3856 3860 -f 3860 3881 3883 -f 3857 3881 3860 -f 3855 3857 3860 -f 3860 3859 3885 -f 3858 3859 3860 -f 3883 3858 3860 -f 3860 3887 3888 -f 3861 3887 3860 -f 3885 3861 3860 -f 3860 3862 3865 -f 3890 3862 3860 -f 3888 3890 3860 -f 3860 3863 3895 -f 3864 3863 3860 -f 3865 3864 3860 -f 3860 3898 3899 -f 3897 3898 3860 -f 3895 3897 3860 -f 3860 3903 3904 -f 3901 3903 3860 -f 3899 3901 3860 -f 3904 3866 3860 -f 3908 3867 3851 -f 3851 3867 3853 -f 3853 3867 2467 -f 3853 2467 3852 -f 3852 2467 2466 -f 3852 2466 3868 -f 3868 2466 3870 -f 3868 3870 3869 -f 3869 3870 3871 -f 3869 3871 3872 -f 3872 3871 3873 -f 3872 3873 3854 -f 3854 3873 3874 -f 3854 3874 3875 -f 3875 3874 2468 -f 3875 2468 3856 -f 3856 2468 3876 -f 3856 3876 3877 -f 3877 3876 3878 -f 3877 3878 3855 -f 3855 3878 3879 -f 3855 3879 3857 -f 3857 3879 3880 -f 3857 3880 3881 -f 3881 3880 3882 -f 3881 3882 3883 -f 3883 3882 3884 -f 3883 3884 3858 -f 3858 3884 2457 -f 3858 2457 3859 -f 3859 2457 2456 -f 3859 2456 3885 -f 3885 2456 2462 -f 3885 2462 3861 -f 3861 2462 3886 -f 3861 3886 3887 -f 3887 3886 2461 -f 3887 2461 3888 -f 3888 2461 3889 -f 3888 3889 3890 -f 3890 3889 3891 -f 3890 3891 3862 -f 3862 3891 2465 -f 3862 2465 3865 -f 3865 2465 3892 -f 3865 3892 3864 -f 3864 3892 3893 -f 3864 3893 3863 -f 3863 3893 2464 -f 3863 2464 3895 -f 3895 2464 3894 -f 3895 3894 3897 -f 3897 3894 3896 -f 3897 3896 3898 -f 3898 3896 2463 -f 3898 2463 3899 -f 3899 2463 3900 -f 3899 3900 3901 -f 3901 3900 3902 -f 3901 3902 3903 -f 3903 3902 2460 -f 3903 2460 3904 -f 3904 2460 3905 -f 3904 3905 3866 -f 3866 3905 3906 -f 3866 3906 3850 -f 3850 3906 3907 -f 3850 3907 3849 -f 3849 3907 2459 -f 3849 2459 3908 -f 3908 2459 3867 -f 3916 3924 3910 -f 3923 3924 3916 -f 3916 3909 3929 -f 3927 3909 3916 -f 3910 3927 3916 -f 3916 3933 3935 -f 3932 3933 3916 -f 3929 3932 3916 -f 3916 3937 3911 -f 3912 3937 3916 -f 3935 3912 3916 -f 3916 3940 3941 -f 3913 3940 3916 -f 3911 3913 3916 -f 3916 3914 3915 -f 3944 3914 3916 -f 3941 3944 3916 -f 3916 3948 3918 -f 3946 3948 3916 -f 3915 3946 3916 -f 3916 3951 3917 -f 3950 3951 3916 -f 3918 3950 3916 -f 3916 3919 3955 -f 3920 3919 3916 -f 3917 3920 3916 -f 3916 3957 3960 -f 3956 3957 3916 -f 3955 3956 3916 -f 3916 3963 3964 -f 3961 3963 3916 -f 3960 3961 3916 -f 3916 3921 3969 -f 3922 3921 3916 -f 3964 3922 3916 -f 3969 3923 3916 -f 3923 2575 3924 -f 3924 2575 3925 -f 3924 3925 3910 -f 3910 3925 3926 -f 3910 3926 3927 -f 3927 3926 3928 -f 3927 3928 3909 -f 3909 3928 3930 -f 3909 3930 3929 -f 3929 3930 3931 -f 3929 3931 3932 -f 3932 3931 2581 -f 3932 2581 3933 -f 3933 2581 3934 -f 3933 3934 3935 -f 3935 3934 3936 -f 3935 3936 3912 -f 3912 3936 3938 -f 3912 3938 3937 -f 3937 3938 2587 -f 3937 2587 3911 -f 3911 2587 3939 -f 3911 3939 3913 -f 3913 3939 2586 -f 3913 2586 3940 -f 3940 2586 2585 -f 3940 2585 3941 -f 3941 2585 3942 -f 3941 3942 3944 -f 3944 3942 3943 -f 3944 3943 3914 -f 3914 3943 3945 -f 3914 3945 3915 -f 3915 3945 2576 -f 3915 2576 3946 -f 3946 2576 3947 -f 3946 3947 3948 -f 3948 3947 3949 -f 3948 3949 3918 -f 3918 3949 2584 -f 3918 2584 3950 -f 3950 2584 2583 -f 3950 2583 3951 -f 3951 2583 2582 -f 3951 2582 3917 -f 3917 2582 3952 -f 3917 3952 3920 -f 3920 3952 2589 -f 3920 2589 3919 -f 3919 2589 3953 -f 3919 3953 3955 -f 3955 3953 3954 -f 3955 3954 3956 -f 3956 3954 2590 -f 3956 2590 3957 -f 3957 2590 3958 -f 3957 3958 3960 -f 3960 3958 3959 -f 3960 3959 3961 -f 3961 3959 3962 -f 3961 3962 3963 -f 3963 3962 3965 -f 3963 3965 3964 -f 3964 3965 3966 -f 3964 3966 3922 -f 3922 3966 3967 -f 3922 3967 3921 -f 3921 3967 3968 -f 3921 3968 3969 -f 3969 3968 3970 -f 3969 3970 3923 -f 3923 3970 2575 -f 3990 3971 3972 -f 3989 3971 3990 -f 3990 3991 3974 -f 4028 3991 3990 -f 3972 4028 3990 -f 3990 3993 3994 -f 3973 3993 3990 -f 3974 3973 3990 -f 3990 3975 3999 -f 3997 3975 3990 -f 3994 3997 3990 -f 3990 4001 3976 -f 3977 4001 3990 -f 3999 3977 3990 -f 3990 4004 4005 -f 3978 4004 3990 -f 3976 3978 3990 -f 3990 4006 3982 -f 3979 4006 3990 -f 4005 3979 3990 -f 3990 3981 4010 -f 3980 3981 3990 -f 3982 3980 3990 -f 3990 3983 3985 -f 4011 3983 3990 -f 4010 4011 3990 -f 3990 4016 3984 -f 4014 4016 3990 -f 3985 4014 3990 -f 3990 4020 4021 -f 3986 4020 3990 -f 3984 3986 3990 -f 3990 3987 3988 -f 4022 3987 3990 -f 4021 4022 3990 -f 3988 3989 3990 -f 4028 4030 3991 -f 3991 4030 3974 -f 3974 4030 3992 -f 3974 3992 3973 -f 3973 3992 2484 -f 3973 2484 3993 -f 3993 2484 3995 -f 3993 3995 3994 -f 3994 3995 3996 -f 3994 3996 3997 -f 3997 3996 2482 -f 3997 2482 3975 -f 3975 2482 3998 -f 3975 3998 3999 -f 3999 3998 2481 -f 3999 2481 3977 -f 3977 2481 4000 -f 3977 4000 4001 -f 4001 4000 2480 -f 4001 2480 3976 -f 3976 2480 4002 -f 3976 4002 3978 -f 3978 4002 4003 -f 3978 4003 4004 -f 4004 4003 2473 -f 4004 2473 4005 -f 4005 2473 2472 -f 4005 2472 3979 -f 3979 2472 2471 -f 3979 2471 4006 -f 4006 2471 4007 -f 4006 4007 3982 -f 3982 4007 4008 -f 3982 4008 3980 -f 3980 4008 4009 -f 3980 4009 3981 -f 3981 4009 2477 -f 3981 2477 4010 -f 4010 2477 2476 -f 4010 2476 4011 -f 4011 2476 2475 -f 4011 2475 3983 -f 3983 2475 4012 -f 3983 4012 3985 -f 3985 4012 4013 -f 3985 4013 4014 -f 4014 4013 4015 -f 4014 4015 4016 -f 4016 4015 4017 -f 4016 4017 3984 -f 3984 4017 4018 -f 3984 4018 3986 -f 3986 4018 4019 -f 3986 4019 4020 -f 4020 4019 2474 -f 4020 2474 4021 -f 4021 2474 4023 -f 4021 4023 4022 -f 4022 4023 2470 -f 4022 2470 3987 -f 3987 2470 4024 -f 3987 4024 3988 -f 3988 4024 4025 -f 3988 4025 3989 -f 3989 4025 4026 -f 3989 4026 3971 -f 3971 4026 2469 -f 3971 2469 3972 -f 3972 2469 4027 -f 3972 4027 4028 -f 4028 4027 4029 -f 4028 4029 4030 -f 4043 4085 4087 -f 4082 4085 4043 -f 4043 4047 4048 -f 4046 4047 4043 -f 4087 4046 4043 -f 4043 4031 4050 -f 4032 4031 4043 -f 4048 4032 4043 -f 4043 4052 4053 -f 4051 4052 4043 -f 4050 4051 4043 -f 4043 4033 4056 -f 4055 4033 4043 -f 4053 4055 4043 -f 4043 4060 4034 -f 4057 4060 4043 -f 4056 4057 4043 -f 4043 4063 4064 -f 4035 4063 4043 -f 4034 4035 4043 -f 4043 4037 4036 -f 4066 4037 4043 -f 4064 4066 4043 -f 4043 4038 4041 -f 4039 4038 4043 -f 4036 4039 4043 -f 4043 4072 4040 -f 4070 4072 4043 -f 4041 4070 4043 -f 4043 4042 4078 -f 4074 4042 4043 -f 4040 4074 4043 -f 4043 4044 4081 -f 4045 4044 4043 -f 4078 4045 4043 -f 4081 4082 4043 -f 4046 2486 4047 -f 4047 2486 4048 -f 4048 2486 2563 -f 4048 2563 4032 -f 4032 2563 4049 -f 4032 4049 4031 -f 4031 4049 2498 -f 4031 2498 4050 -f 4050 2498 2497 -f 4050 2497 4051 -f 4051 2497 2500 -f 4051 2500 4052 -f 4052 2500 2499 -f 4052 2499 4053 -f 4053 2499 4054 -f 4053 4054 4055 -f 4055 4054 2496 -f 4055 2496 4033 -f 4033 2496 2495 -f 4033 2495 4056 -f 4056 2495 4058 -f 4056 4058 4057 -f 4057 4058 4059 -f 4057 4059 4060 -f 4060 4059 4061 -f 4060 4061 4034 -f 4034 4061 2485 -f 4034 2485 4035 -f 4035 2485 4062 -f 4035 4062 4063 -f 4063 4062 4065 -f 4063 4065 4064 -f 4064 4065 2491 -f 4064 2491 4066 -f 4066 2491 4067 -f 4066 4067 4037 -f 4037 4067 4068 -f 4037 4068 4036 -f 4036 4068 2493 -f 4036 2493 4039 -f 4039 2493 4069 -f 4039 4069 4038 -f 4038 4069 2492 -f 4038 2492 4041 -f 4041 2492 4071 -f 4041 4071 4070 -f 4070 4071 4073 -f 4070 4073 4072 -f 4072 4073 2494 -f 4072 2494 4040 -f 4040 2494 4075 -f 4040 4075 4074 -f 4074 4075 4076 -f 4074 4076 4042 -f 4042 4076 4077 -f 4042 4077 4078 -f 4078 4077 4079 -f 4078 4079 4045 -f 4045 4079 4080 -f 4045 4080 4044 -f 4044 4080 2489 -f 4044 2489 4081 -f 4081 2489 4083 -f 4081 4083 4082 -f 4082 4083 4084 -f 4082 4084 4085 -f 4085 4084 4086 -f 4085 4086 4087 -f 4087 4086 2487 -f 4087 2487 4046 -f 4046 2487 2486 -f 4099 4088 4089 -f 4103 4088 4099 -f 4099 4107 4090 -f 4105 4107 4099 -f 4089 4105 4099 -f 4099 4110 4091 -f 4109 4110 4099 -f 4090 4109 4099 -f 4099 4092 4093 -f 4113 4092 4099 -f 4091 4113 4099 -f 4099 4117 4118 -f 4094 4117 4099 -f 4093 4094 4099 -f 4099 4122 4124 -f 4120 4122 4099 -f 4118 4120 4099 -f 4099 4127 4128 -f 4126 4127 4099 -f 4124 4126 4099 -f 4099 4095 4098 -f 4096 4095 4099 -f 4128 4096 4099 -f 4099 4131 4133 -f 4097 4131 4099 -f 4098 4097 4099 -f 4099 4100 4136 -f 4101 4100 4099 -f 4133 4101 4099 -f 4099 4140 4141 -f 4137 4140 4099 -f 4136 4137 4099 -f 4099 4102 4145 -f 4143 4102 4099 -f 4141 4143 4099 -f 4145 4103 4099 -f 4103 2506 4088 -f 4088 2506 2505 -f 4088 2505 4089 -f 4089 2505 4104 -f 4089 4104 4105 -f 4105 4104 4106 -f 4105 4106 4107 -f 4107 4106 2515 -f 4107 2515 4090 -f 4090 2515 4108 -f 4090 4108 4109 -f 4109 4108 4111 -f 4109 4111 4110 -f 4110 4111 4112 -f 4110 4112 4091 -f 4091 4112 2521 -f 4091 2521 4113 -f 4113 2521 4114 -f 4113 4114 4092 -f 4092 4114 4115 -f 4092 4115 4093 -f 4093 4115 2514 -f 4093 2514 4094 -f 4094 2514 4116 -f 4094 4116 4117 -f 4117 4116 2513 -f 4117 2513 4118 -f 4118 2513 4119 -f 4118 4119 4120 -f 4120 4119 4121 -f 4120 4121 4122 -f 4122 4121 4123 -f 4122 4123 4124 -f 4124 4123 4125 -f 4124 4125 4126 -f 4126 4125 2510 -f 4126 2510 4127 -f 4127 2510 2509 -f 4127 2509 4128 -f 4128 2509 2518 -f 4128 2518 4096 -f 4096 2518 4129 -f 4096 4129 4095 -f 4095 4129 4130 -f 4095 4130 4098 -f 4098 4130 2517 -f 4098 2517 4097 -f 4097 2517 2516 -f 4097 2516 4131 -f 4131 2516 4132 -f 4131 4132 4133 -f 4133 4132 4134 -f 4133 4134 4101 -f 4101 4134 2522 -f 4101 2522 4100 -f 4100 2522 4135 -f 4100 4135 4136 -f 4136 4135 4138 -f 4136 4138 4137 -f 4137 4138 4139 -f 4137 4139 4140 -f 4140 4139 2519 -f 4140 2519 4141 -f 4141 2519 4142 -f 4141 4142 4143 -f 4143 4142 4144 -f 4143 4144 4102 -f 4102 4144 2508 -f 4102 2508 4145 -f 4145 2508 2507 -f 4145 2507 4103 -f 4103 2507 2506 -f 4154 4146 4165 -f 4200 4146 4154 -f 4154 4147 4168 -f 4167 4147 4154 -f 4165 4167 4154 -f 4154 4170 4171 -f 4148 4170 4154 -f 4168 4148 4154 -f 4154 4149 4150 -f 4151 4149 4154 -f 4171 4151 4154 -f 4154 4152 4175 -f 4153 4152 4154 -f 4150 4153 4154 -f 4154 4156 4155 -f 4157 4156 4154 -f 4175 4157 4154 -f 4154 4158 4181 -f 4159 4158 4154 -f 4155 4159 4154 -f 4154 4185 4160 -f 4183 4185 4154 -f 4181 4183 4154 -f 4154 4188 4161 -f 4186 4188 4154 -f 4160 4186 4154 -f 4154 4193 4162 -f 4190 4193 4154 -f 4161 4190 4154 -f 4154 4195 4196 -f 4194 4195 4154 -f 4162 4194 4154 -f 4154 4163 4164 -f 4197 4163 4154 -f 4196 4197 4154 -f 4164 4200 4154 -f 4200 4201 4146 -f 4146 4201 2439 -f 4146 2439 4165 -f 4165 2439 4166 -f 4165 4166 4167 -f 4167 4166 2451 -f 4167 2451 4147 -f 4147 2451 2450 -f 4147 2450 4168 -f 4168 2450 4169 -f 4168 4169 4148 -f 4148 4169 2449 -f 4148 2449 4170 -f 4170 2449 2454 -f 4170 2454 4171 -f 4171 2454 4172 -f 4171 4172 4151 -f 4151 4172 2453 -f 4151 2453 4149 -f 4149 2453 2452 -f 4149 2452 4150 -f 4150 2452 4173 -f 4150 4173 4153 -f 4153 4173 2448 -f 4153 2448 4152 -f 4152 2448 4174 -f 4152 4174 4175 -f 4175 4174 4176 -f 4175 4176 4157 -f 4157 4176 4177 -f 4157 4177 4156 -f 4156 4177 2446 -f 4156 2446 4155 -f 4155 2446 4178 -f 4155 4178 4159 -f 4159 4178 4179 -f 4159 4179 4158 -f 4158 4179 2438 -f 4158 2438 4181 -f 4181 2438 4180 -f 4181 4180 4183 -f 4183 4180 4182 -f 4183 4182 4185 -f 4185 4182 4184 -f 4185 4184 4160 -f 4160 4184 2441 -f 4160 2441 4186 -f 4186 2441 4187 -f 4186 4187 4188 -f 4188 4187 2440 -f 4188 2440 4161 -f 4161 2440 4189 -f 4161 4189 4190 -f 4190 4189 4191 -f 4190 4191 4193 -f 4193 4191 4192 -f 4193 4192 4162 -f 4162 4192 2445 -f 4162 2445 4194 -f 4194 2445 2444 -f 4194 2444 4195 -f 4195 2444 2443 -f 4195 2443 4196 -f 4196 2443 2442 -f 4196 2442 4197 -f 4197 2442 4198 -f 4197 4198 4163 -f 4163 4198 2437 -f 4163 2437 4164 -f 4164 2437 4199 -f 4164 4199 4200 -f 4200 4199 4201 -f 4211 4223 4202 -f 4221 4223 4211 -f 4211 4203 4227 -f 4225 4203 4211 -f 4202 4225 4211 -f 4211 4204 4231 -f 4228 4204 4211 -f 4227 4228 4211 -f 4211 4205 4206 -f 4207 4205 4211 -f 4231 4207 4211 -f 4211 4235 4236 -f 4208 4235 4211 -f 4206 4208 4211 -f 4211 4209 4210 -f 4238 4209 4211 -f 4236 4238 4211 -f 4211 4241 4243 -f 4240 4241 4211 -f 4210 4240 4211 -f 4211 4213 4245 -f 4212 4213 4211 -f 4243 4212 4211 -f 4211 4214 4248 -f 4215 4214 4211 -f 4245 4215 4211 -f 4211 4216 4220 -f 4249 4216 4211 -f 4248 4249 4211 -f 4211 4217 4218 -f 4219 4217 4211 -f 4220 4219 4211 -f 4211 4256 4257 -f 4255 4256 4211 -f 4218 4255 4211 -f 4257 4221 4211 -f 4221 4222 4223 -f 4223 4222 2544 -f 4223 2544 4202 -f 4202 2544 4224 -f 4202 4224 4225 -f 4225 4224 2526 -f 4225 2526 4203 -f 4203 2526 4226 -f 4203 4226 4227 -f 4227 4226 2525 -f 4227 2525 4228 -f 4228 2525 4229 -f 4228 4229 4204 -f 4204 4229 4230 -f 4204 4230 4231 -f 4231 4230 2532 -f 4231 2532 4207 -f 4207 2532 4232 -f 4207 4232 4205 -f 4205 4232 4233 -f 4205 4233 4206 -f 4206 4233 4234 -f 4206 4234 4208 -f 4208 4234 2535 -f 4208 2535 4235 -f 4235 2535 4237 -f 4235 4237 4236 -f 4236 4237 2531 -f 4236 2531 4238 -f 4238 2531 2530 -f 4238 2530 4209 -f 4209 2530 2534 -f 4209 2534 4210 -f 4210 2534 4239 -f 4210 4239 4240 -f 4240 4239 2533 -f 4240 2533 4241 -f 4241 2533 4242 -f 4241 4242 4243 -f 4243 4242 4244 -f 4243 4244 4212 -f 4212 4244 2529 -f 4212 2529 4213 -f 4213 2529 2528 -f 4213 2528 4245 -f 4245 2528 4246 -f 4245 4246 4215 -f 4215 4246 2538 -f 4215 2538 4214 -f 4214 2538 4247 -f 4214 4247 4248 -f 4248 4247 2537 -f 4248 2537 4249 -f 4249 2537 4250 -f 4249 4250 4216 -f 4216 4250 2536 -f 4216 2536 4220 -f 4220 2536 4251 -f 4220 4251 4219 -f 4219 4251 4252 -f 4219 4252 4217 -f 4217 4252 4253 -f 4217 4253 4218 -f 4218 4253 2527 -f 4218 2527 4255 -f 4255 2527 4254 -f 4255 4254 4256 -f 4256 4254 2524 -f 4256 2524 4257 -f 4257 2524 4258 -f 4257 4258 4221 -f 4221 4258 4222 -f 4266 4277 4278 -f 4259 4277 4266 -f 4266 4281 4260 -f 4280 4281 4266 -f 4278 4280 4266 -f 4266 4286 4263 -f 4285 4286 4266 -f 4260 4285 4266 -f 4266 4289 4261 -f 4262 4289 4266 -f 4263 4262 4266 -f 4266 4291 4293 -f 4264 4291 4266 -f 4261 4264 4266 -f 4266 4295 4297 -f 4265 4295 4266 -f 4293 4265 4266 -f 4266 4301 4268 -f 4299 4301 4266 -f 4297 4299 4266 -f 4266 4305 4267 -f 4302 4305 4266 -f 4268 4302 4266 -f 4266 4309 4310 -f 4269 4309 4266 -f 4267 4269 4266 -f 4266 4270 4271 -f 4272 4270 4266 -f 4310 4272 4266 -f 4266 4273 4316 -f 4274 4273 4266 -f 4271 4274 4266 -f 4266 4275 4276 -f 4319 4275 4266 -f 4316 4319 4266 -f 4276 4259 4266 -f 4259 4322 4277 -f 4277 4322 2565 -f 4277 2565 4278 -f 4278 2565 2579 -f 4278 2579 4280 -f 4280 2579 4279 -f 4280 4279 4281 -f 4281 4279 4282 -f 4281 4282 4260 -f 4260 4282 4283 -f 4260 4283 4285 -f 4285 4283 4284 -f 4285 4284 4286 -f 4286 4284 4287 -f 4286 4287 4263 -f 4263 4287 4288 -f 4263 4288 4262 -f 4262 4288 2564 -f 4262 2564 4289 -f 4289 2564 2567 -f 4289 2567 4261 -f 4261 2567 2569 -f 4261 2569 4264 -f 4264 2569 4290 -f 4264 4290 4291 -f 4291 4290 4292 -f 4291 4292 4293 -f 4293 4292 2570 -f 4293 2570 4265 -f 4265 2570 4294 -f 4265 4294 4295 -f 4295 4294 4296 -f 4295 4296 4297 -f 4297 4296 4298 -f 4297 4298 4299 -f 4299 4298 4300 -f 4299 4300 4301 -f 4301 4300 2573 -f 4301 2573 4268 -f 4268 2573 4303 -f 4268 4303 4302 -f 4302 4303 4304 -f 4302 4304 4305 -f 4305 4304 4306 -f 4305 4306 4267 -f 4267 4306 4307 -f 4267 4307 4269 -f 4269 4307 4308 -f 4269 4308 4309 -f 4309 4308 2574 -f 4309 2574 4310 -f 4310 2574 4311 -f 4310 4311 4272 -f 4272 4311 4312 -f 4272 4312 4270 -f 4270 4312 4313 -f 4270 4313 4271 -f 4271 4313 4314 -f 4271 4314 4274 -f 4274 4314 4315 -f 4274 4315 4273 -f 4273 4315 4317 -f 4273 4317 4316 -f 4316 4317 4318 -f 4316 4318 4319 -f 4319 4318 4320 -f 4319 4320 4275 -f 4275 4320 4321 -f 4275 4321 4276 -f 4276 4321 2566 -f 4276 2566 4259 -f 4259 2566 4322 -f 4323 4329 4680 -f 4680 4681 4323 -f 4681 4682 4323 -f 4323 4682 4325 -f 4325 4682 4684 -f 4325 4684 4686 -f 4686 4326 4324 -f 4325 4686 4324 -f 7580 4676 4686 -f 4686 4676 4326 -f 4675 4676 7580 -f 4675 7580 4327 -f 4336 4679 4328 -f 4336 4328 4680 -f 4336 4680 4329 -f 4335 4672 4673 -f 4670 4672 4335 -f 4673 4675 4336 -f 4330 4673 4336 -f 4327 4679 4675 -f 4675 4679 4336 -f 4670 4335 4332 -f 4670 4332 4669 -f 4332 4668 4669 -f 2224 4662 4663 -f 2224 4663 4664 -f 2224 4664 4331 -f 4331 4664 4666 -f 4331 4666 4332 -f 4332 4666 4668 -f 4342 4334 4333 -f 4333 4334 4348 -f 4333 4348 4330 -f 4330 4348 4335 -f 4330 4335 4673 -f 9522 7000 7001 -f 9522 7001 9584 -f 9584 7001 6995 -f 9584 6995 6993 -f 4323 9513 4329 -f 4329 9513 4338 -f 4329 4338 4336 -f 4336 4338 4330 -f 7010 4342 4345 -f 4345 4342 4333 -f 4345 4333 4337 -f 4337 4333 4330 -f 4337 4330 6993 -f 6993 4330 4338 -f 6993 4338 9584 -f 7010 4339 4342 -f 4342 4339 4355 -f 4342 4355 4340 -f 4340 4341 4342 -f 4342 4341 4359 -f 7006 4345 4343 -f 4343 4345 7004 -f 7006 7008 4345 -f 4345 7008 4344 -f 4345 4344 7010 -f 4332 9585 4331 -f 4331 9585 4346 -f 4331 4346 2224 -f 7003 7002 4347 -f 7003 4347 4353 -f 9578 9582 6992 -f 6992 9582 4347 -f 6992 4347 6994 -f 6994 4347 7002 -f 4332 4335 9585 -f 9585 4335 4348 -f 9585 4348 4334 -f 4358 4349 4334 -f 4334 4349 4357 -f 4334 4357 4356 -f 4356 4354 4334 -f 4334 4354 4350 -f 4334 4350 9585 -f 9585 4350 4351 -f 9585 4351 4347 -f 4347 4351 4353 -f 4353 4351 7009 -f 4353 7009 7007 -f 7007 7005 4353 -f 4353 7005 4352 -f 4339 4350 4354 -f 4339 4354 4355 -f 4355 4354 4356 -f 4355 4356 4340 -f 4340 4356 4357 -f 4340 4357 4341 -f 4341 4357 4349 -f 4341 4349 4359 -f 4359 4349 4358 -f 4359 4358 4342 -f 4342 4358 4334 -f 4361 4414 4424 -f 4360 4390 4361 -f 4390 4415 4361 -f 4361 4415 4414 -f 9516 4417 2605 -f 2605 4417 4362 -f 4362 4363 2605 -f 4365 4364 9516 -f 9516 4364 4417 -f 4432 4365 4366 -f 4432 4364 4365 -f 4366 4431 4432 -f 4361 4431 4413 -f 4413 4431 4366 -f 4367 9520 4370 -f 4374 4742 4370 -f 4413 4366 4368 -f 4689 9520 4687 -f 4687 9520 2221 -f 4689 4690 9520 -f 9520 4690 4369 -f 9520 4369 4370 -f 4368 4366 2225 -f 4742 4371 4370 -f 4370 4371 4745 -f 4370 4745 4367 -f 4367 4745 9505 -f 4372 2226 4373 -f 4372 4373 4365 -f 4365 4373 2225 -f 4365 2225 4366 -f 4416 4412 4413 -f 4769 4721 4376 -f 4769 4376 4385 -f 4374 4370 4375 -f 4375 4370 4376 -f 4375 4376 4381 -f 4381 4376 4721 -f 4381 4721 4702 -f 4377 4762 4763 -f 4378 4379 4386 -f 4413 4368 4416 -f 4702 4380 4381 -f 4381 4380 4382 -f 4381 4382 4763 -f 4763 4382 4383 -f 4763 4383 4377 -f 4368 4384 4416 -f 4385 4376 4386 -f 4386 4376 4387 -f 4386 4387 4378 -f 4398 4397 4412 -f 4412 4397 4360 -f 4397 4395 4360 -f 4360 4395 4393 -f 4416 4404 4388 -f 4360 4393 4392 -f 4390 4411 4409 -f 4390 4409 4408 -f 4390 4408 4406 -f 4406 4405 4390 -f 4390 4405 4416 -f 4416 4405 4404 -f 4416 4388 4389 -f 4416 4389 4401 -f 4416 4401 4412 -f 4401 4400 4412 -f 4412 4400 4399 -f 4392 4391 4360 -f 4360 4391 4390 -f 4390 4391 4411 -f 4412 4399 4398 -f 4411 4391 6915 -f 6915 4391 4392 -f 6915 4392 6914 -f 6914 4392 4393 -f 6914 4393 4394 -f 4394 4393 4395 -f 4394 4395 4396 -f 4396 4395 4397 -f 4396 4397 6911 -f 6911 4397 4398 -f 6911 4398 6913 -f 6913 4398 4399 -f 6913 4399 6908 -f 6908 4399 4400 -f 6908 4400 4401 -f 4402 4401 4389 -f 4402 4389 4403 -f 4403 4389 4388 -f 4403 4388 6909 -f 6909 4388 4404 -f 6909 4404 6910 -f 6910 4404 4405 -f 6910 4405 6912 -f 6912 4405 4406 -f 6912 4406 4407 -f 4407 4406 4408 -f 4407 4408 4410 -f 4410 4408 4409 -f 4411 6917 4409 -f 4409 6917 4410 -f 4411 6915 6917 -f 4412 4360 4413 -f 4413 4360 4361 -f 4368 4414 4384 -f 4384 4414 4415 -f 4384 4415 4416 -f 4416 4415 4390 -f 4363 4362 2604 -f 2600 4434 4435 -f 4429 4427 4418 -f 4418 4427 4419 -f 4427 4421 4419 -f 4419 4421 4420 -f 4437 4423 4420 -f 4437 4420 4421 -f 4422 4423 4437 -f 4361 4438 4431 -f 4431 4438 4430 -f 4432 4433 4364 -f 4364 4433 4417 -f 4417 4433 4426 -f 2604 4362 4425 -f 4425 4362 4426 -f 4426 4362 4417 -f 4421 4427 4428 -f 4428 4427 4429 -f 4428 4429 2600 -f 4431 4430 4432 -f 4432 4430 4433 -f 4433 4430 4436 -f 4433 4436 4435 -f 4433 4435 4426 -f 4426 4435 4434 -f 4426 4434 4425 -f 2600 4435 4428 -f 4428 4435 4436 -f 4428 4436 4421 -f 4421 4436 4430 -f 4421 4430 4437 -f 4437 4430 4422 -f 4422 4430 4438 -f 4422 4438 4361 -f 4422 4361 4424 -f 6973 4440 4439 -f 4439 4440 2236 -f 4439 2236 4458 -f 2252 4468 4441 -f 4441 4468 6972 -f 6962 4442 4443 -f 4443 2267 6962 -f 6962 2267 2228 -f 6962 2228 6972 -f 6972 2228 4444 -f 6972 4444 4441 -f 6964 4448 4449 -f 4445 4446 2254 -f 4449 2230 6964 -f 6964 2230 2597 -f 6964 2597 4446 -f 4446 2597 2598 -f 4446 2598 2254 -f 4447 4469 6970 -f 6970 4469 2259 -f 6970 2259 6971 -f 4449 4448 6963 -f 4449 6963 4450 -f 4450 6963 4451 -f 4450 4451 2233 -f 2233 4451 4452 -f 2233 4452 4453 -f 4453 4452 6966 -f 4453 6966 2242 -f 2242 6966 6968 -f 2242 6968 2241 -f 4455 4454 2239 -f 2239 4456 4455 -f 4455 4456 6968 -f 6968 4456 2241 -f 4457 4458 2236 -f 2236 2238 4457 -f 4457 2238 4454 -f 4454 2238 2239 -f 4440 6973 2235 -f 2235 6973 6976 -f 2235 6976 4459 -f 2235 4459 4460 -f 4460 4459 6979 -f 4460 6979 4462 -f 4462 6979 4461 -f 4462 4461 4463 -f 4462 4463 2234 -f 2234 4463 4464 -f 2234 4464 4466 -f 4466 4464 4465 -f 4466 4465 2243 -f 2243 4465 4467 -f 2243 4467 2244 -f 2244 4467 2252 -f 2252 4467 4468 -f 4469 4447 4470 -f 4469 4470 2260 -f 2260 4470 4471 -f 2260 4471 2261 -f 2261 4471 6967 -f 2261 6967 4472 -f 4472 6967 6965 -f 4472 6965 4473 -f 4472 4473 4474 -f 4474 4473 4475 -f 4474 4475 2257 -f 2257 4475 4476 -f 2257 4476 2258 -f 2258 4476 6969 -f 2258 6969 4477 -f 4477 6969 4446 -f 4477 4446 4445 -f 4442 6962 6983 -f 4442 6983 4478 -f 4478 6983 6982 -f 4478 6982 2262 -f 2262 6982 6980 -f 2262 6980 4479 -f 4479 6980 6981 -f 4479 6981 4480 -f 4480 6981 6978 -f 4480 6978 2265 -f 6977 6975 2264 -f 2264 4481 6977 -f 6977 4481 6978 -f 6978 4481 2265 -f 6974 6971 2259 -f 2259 4482 6974 -f 6974 4482 6975 -f 6975 4482 2264 -f 4487 4488 4655 -f 4619 4483 4618 -f 4618 4483 4647 -f 4619 4484 4483 -f 4483 4484 4650 -f 4650 4484 4620 -f 4650 4620 4485 -f 4485 4620 4623 -f 4623 4486 4485 -f 4487 4486 4621 -f 4623 4621 4486 -f 4486 4487 4655 -f 4489 4490 4654 -f 4488 4590 4655 -f 4488 4616 4590 -f 4590 4616 4489 -f 4489 4616 4490 -f 4654 4490 4593 -f 4593 4490 4491 -f 4593 4491 2607 -f 4618 4647 4646 -f 4563 4492 4646 -f 4646 4492 4615 -f 4646 4615 4618 -f 4493 4547 4594 -f 4557 4494 4526 -f 4557 4495 4494 -f 4494 4495 4556 -f 4494 4556 4502 -f 4535 4533 4496 -f 4527 4496 4529 -f 4533 4532 4496 -f 4496 4532 4497 -f 4496 4497 4529 -f 4608 4549 4594 -f 4594 4549 4498 -f 4594 4498 4493 -f 4547 4545 4594 -f 4594 4545 4499 -f 4594 4499 4509 -f 4509 4499 4500 -f 4509 4500 4501 -f 4535 4496 4536 -f 4536 4496 4633 -f 4536 4633 4537 -f 4502 4555 4494 -f 4494 4555 4552 -f 4494 4552 4503 -f 4549 4608 4506 -f 4552 4504 4503 -f 4503 4504 4505 -f 4503 4505 4606 -f 4606 4505 4506 -f 4606 4506 4608 -f 4635 4507 4539 -f 4635 4539 4633 -f 4633 4539 4538 -f 4633 4538 4537 -f 4501 4508 4509 -f 4509 4508 4510 -f 4509 4510 4634 -f 4634 4510 4507 -f 4634 4507 4635 -f 4627 4512 4595 -f 4601 4605 4591 -f 4591 4605 4511 -f 4596 4513 4514 -f 4511 4605 4603 -f 4511 4603 4596 -f 4511 4596 4514 -f 4513 4512 4514 -f 4513 4597 4512 -f 4512 4597 4599 -f 4512 4599 4595 -f 4627 4595 4509 -f 4509 4595 4594 -f 4584 4515 4609 -f 4584 4609 4516 -f 4645 4632 4517 -f 4517 4641 4645 -f 4561 4518 6943 -f 4519 4562 6941 -f 6943 4518 4519 -f 4519 4518 4520 -f 4519 4520 4562 -f 4561 6943 4521 -f 4521 6943 6938 -f 4521 6938 4522 -f 4522 6938 6937 -f 4522 6937 4523 -f 4523 6937 4558 -f 4558 6937 4524 -f 4558 4524 4525 -f 4525 4524 4559 -f 4559 4524 6932 -f 4559 6932 4526 -f 4562 4527 6941 -f 6941 4527 4528 -f 4528 4527 4529 -f 4528 4529 4530 -f 4530 4529 4497 -f 4530 4497 4531 -f 4531 4497 4532 -f 4531 4532 6944 -f 6944 4532 4533 -f 6944 4533 4534 -f 4534 4533 4535 -f 4534 4535 6949 -f 6949 4535 4536 -f 6949 4536 6947 -f 6947 4536 4537 -f 6947 4537 6948 -f 6948 4537 4538 -f 6948 4538 6942 -f 6942 4538 4539 -f 6942 4539 4540 -f 4540 4539 4507 -f 4540 4507 6940 -f 6940 4507 4510 -f 6940 4510 4541 -f 4541 4510 4508 -f 4541 4508 4542 -f 4542 4508 4501 -f 4542 4501 4543 -f 4543 4501 4500 -f 4543 4500 4544 -f 4544 4500 4499 -f 4544 4499 6939 -f 6939 4499 4545 -f 6939 4545 4546 -f 4546 4545 4547 -f 4546 4547 6936 -f 6936 4547 4493 -f 6936 4493 4548 -f 4548 4493 4498 -f 4548 4498 4550 -f 4550 4498 4549 -f 4550 4549 4551 -f 4551 4549 4506 -f 4551 4506 6933 -f 6933 4506 4505 -f 6933 4505 6934 -f 6934 4505 4504 -f 6934 4504 4553 -f 4553 4504 4552 -f 4553 4552 4554 -f 4554 4552 4555 -f 4554 4555 6945 -f 6945 4555 4502 -f 6945 4502 6931 -f 6931 4502 4556 -f 6931 4556 6935 -f 6935 4556 4495 -f 6935 4495 6946 -f 6946 4495 4557 -f 6946 4557 6932 -f 6932 4557 4526 -f 4559 4526 4494 -f 4560 4558 4525 -f 4494 4560 4559 -f 4559 4560 4525 -f 4520 4518 4566 -f 4566 4518 4561 -f 4614 4521 4522 -f 4614 4522 4560 -f 4560 4522 4523 -f 4560 4523 4558 -f 4566 4496 4520 -f 4520 4496 4562 -f 4496 4527 4562 -f 4492 4563 4610 -f 4610 4563 4564 -f 4610 4564 4611 -f 4611 4564 4643 -f 4611 4643 4612 -f 4612 4643 4642 -f 4612 4642 4613 -f 4613 4642 4640 -f 4613 4640 4565 -f 4565 4640 4639 -f 4565 4639 4638 -f 4565 4638 4614 -f 4614 4638 4566 -f 4614 4566 4521 -f 4521 4566 4561 -f 4600 4598 4576 -f 2607 4572 4601 -f 4601 4572 4602 -f 4573 4575 4567 -f 4567 4575 4568 -f 4567 4568 4569 -f 4569 4568 4570 -f 4569 4570 4571 -f 4571 4570 4604 -f 4571 4604 4572 -f 4572 4604 4602 -f 4575 4573 4574 -f 4576 4598 4574 -f 4574 4598 4575 -f 4600 4576 4577 -f 4600 4577 4579 -f 4579 4577 4578 -f 4622 4580 4578 -f 4578 4580 4579 -f 4580 4622 4581 -f 4581 4622 4582 -f 4583 4582 4622 -f 4583 4617 4582 -f 4582 4617 4607 -f 4515 4584 4617 -f 4617 4584 4607 -f 4636 4632 4645 -f 4645 4644 4636 -f 4636 4644 4648 -f 4636 4648 4585 -f 4648 4653 4585 -f 4585 4653 4637 -f 4637 4653 4652 -f 4637 4652 4631 -f 4652 4651 4631 -f 4631 4651 4586 -f 4649 4624 4625 -f 4651 4649 4586 -f 4586 4649 4625 -f 4589 4628 4588 -f 4589 4588 4656 -f 4624 4649 4657 -f 4624 4657 4587 -f 4587 4657 4656 -f 4587 4656 4588 -f 4590 4629 4589 -f 4589 4629 4626 -f 4589 4626 4628 -f 4629 4590 4489 -f 4629 4489 4630 -f 4630 4489 4592 -f 4630 4592 4591 -f 4591 4592 4593 -f 4580 4594 4579 -f 4579 4594 4595 -f 4579 4595 4600 -f 4600 4595 4599 -f 4568 4575 4596 -f 4596 4575 4513 -f 4513 4575 4597 -f 4597 4575 4598 -f 4597 4598 4599 -f 4599 4598 4600 -f 4601 4602 4605 -f 4605 4602 4604 -f 4568 4596 4570 -f 4570 4596 4603 -f 4570 4603 4604 -f 4604 4603 4605 -f 4608 4582 4606 -f 4594 4580 4608 -f 4584 4503 4607 -f 4607 4503 4606 -f 4607 4606 4582 -f 4580 4581 4608 -f 4608 4581 4582 -f 4516 4494 4584 -f 4584 4494 4503 -f 4609 4492 4610 -f 4609 4610 4516 -f 4610 4611 4516 -f 4611 4612 4516 -f 4612 4613 4516 -f 4613 4565 4516 -f 4516 4565 4614 -f 4516 4614 4560 -f 4516 4560 4494 -f 4515 4615 4609 -f 4609 4615 4492 -f 4515 4617 4615 -f 4615 4617 4618 -f 4616 4488 4573 -f 4573 4488 4487 -f 4573 4487 4574 -f 4574 4487 4576 -f 4576 4487 4621 -f 4576 4621 4577 -f 4617 4484 4619 -f 4617 4619 4618 -f 4617 4583 4484 -f 4484 4583 4620 -f 4620 4583 4622 -f 4573 4567 4616 -f 4616 4567 4569 -f 4616 4569 4490 -f 4490 4569 4571 -f 4490 4571 4572 -f 4490 4572 4491 -f 4491 4572 2607 -f 4577 4621 4578 -f 4578 4621 4622 -f 4622 4621 4623 -f 4622 4623 4620 -f 4512 4586 4625 -f 4587 4512 4624 -f 4624 4512 4625 -f 4629 4511 4626 -f 4626 4511 4628 -f 4512 4587 4588 -f 4512 4588 4628 -f 4509 4586 4627 -f 4627 4586 4512 -f 4514 4512 4628 -f 4629 4630 4511 -f 4511 4630 4591 -f 4628 4511 4514 -f 4586 4509 4634 -f 4635 4637 4631 -f 4633 4632 4636 -f 4633 4636 4635 -f 4635 4631 4634 -f 4634 4631 4586 -f 4635 4636 4585 -f 4635 4585 4637 -f 4496 4517 4633 -f 4633 4517 4632 -f 4517 4496 4641 -f 4496 4566 4641 -f 4566 4638 4641 -f 4638 4639 4641 -f 4641 4639 4640 -f 4641 4640 4642 -f 4641 4642 4643 -f 4641 4643 4564 -f 4641 4564 4563 -f 4646 4645 4563 -f 4563 4645 4641 -f 4644 4645 4647 -f 4647 4645 4646 -f 4644 4647 4648 -f 4648 4647 4653 -f 4486 4649 4485 -f 4485 4649 4651 -f 4485 4651 4650 -f 4650 4651 4652 -f 4650 4652 4483 -f 4483 4652 4653 -f 4483 4653 4647 -f 4593 4592 4654 -f 4654 4592 4489 -f 4590 4589 4655 -f 4655 4589 4656 -f 4655 4656 4486 -f 4486 4656 4657 -f 4486 4657 4649 -f 2222 4325 7585 -f 7585 4325 4658 -f 4660 4659 2222 -f 4660 2222 7585 -f 7587 4661 4660 -f 4660 4661 2223 -f 4660 2223 4659 -f 7587 4662 4661 -f 4665 4662 7587 -f 4665 4663 4662 -f 4665 4664 4663 -f 4665 4666 4664 -f 4665 4667 4666 -f 4666 4667 4668 -f 4668 4667 4671 -f 4668 4671 4669 -f 4669 4671 4670 -f 4670 4671 7588 -f 4670 7588 4672 -f 4672 7588 4673 -f 4673 7588 4674 -f 4673 4674 7586 -f 4673 7586 4675 -f 4675 7586 7584 -f 4675 7584 4676 -f 4676 7584 4677 -f 4676 4677 4326 -f 4326 4677 4678 -f 4678 4324 4326 -f 4658 4325 4324 -f 4658 4324 4678 -f 4686 7581 7580 -f 7580 7579 4327 -f 4327 7579 7578 -f 4327 7578 4679 -f 4679 7578 7577 -f 4679 7577 4328 -f 4328 7577 7576 -f 4328 7576 4680 -f 4680 7576 7583 -f 4680 7583 4681 -f 7582 4681 7583 -f 4683 4682 7582 -f 7582 4682 4681 -f 4682 4683 4684 -f 4684 4683 4685 -f 4684 4685 4686 -f 2221 9494 4687 -f 4687 9494 4748 -f 4687 4748 4689 -f 4689 4748 4688 -f 4689 4688 4690 -f 4690 4688 4747 -f 4690 4747 4369 -f 4369 4747 4691 -f 4369 4691 4370 -f 4370 4691 4752 -f 4370 4752 4376 -f 4376 4752 4755 -f 4796 4794 4702 -f 4692 4918 4697 -f 4904 4903 4721 -f 4721 4903 4693 -f 4721 4693 4695 -f 4837 4885 4697 -f 4697 4885 4884 -f 4697 4884 4881 -f 4867 4753 4868 -f 4868 4753 4694 -f 4695 4901 4721 -f 4721 4901 4714 -f 4794 4696 4702 -f 4702 4696 4793 -f 4702 4793 4791 -f 4881 4880 4697 -f 4697 4880 4877 -f 4697 4877 4875 -f 4918 4698 4697 -f 4697 4698 4916 -f 4697 4916 4718 -f 4904 4721 4699 -f 4699 4721 4753 -f 4699 4753 4700 -f 4893 4701 4702 -f 4702 4701 4703 -f 4702 4703 4697 -f 4697 4703 4920 -f 4697 4920 4692 -f 4875 4872 4697 -f 4697 4872 4871 -f 4697 4871 4753 -f 4753 4871 4704 -f 4753 4704 4694 -f 4753 4739 4709 -f 4893 4702 4895 -f 4895 4702 4791 -f 4895 4791 4705 -f 4705 4791 4822 -f 4705 4822 4706 -f 4706 4707 4705 -f 4705 4707 4820 -f 4705 4820 4708 -f 4709 4710 4753 -f 4753 4710 4907 -f 4753 4907 4700 -f 4708 4711 4705 -f 4705 4711 4712 -f 4705 4712 4897 -f 4713 4814 4714 -f 4714 4814 4813 -f 4714 4813 4811 -f 4721 4722 4808 -f 4715 4798 4702 -f 4702 4798 4716 -f 4702 4716 4796 -f 4842 4717 4718 -f 4811 4719 4714 -f 4714 4719 4720 -f 4714 4720 4721 -f 4721 4720 4809 -f 4721 4809 4722 -f 4808 4807 4721 -f 4721 4807 4723 -f 4721 4723 4724 -f 4724 4804 4721 -f 4721 4804 4725 -f 4721 4725 4726 -f 4911 4910 4849 -f 4849 4910 4739 -f 4849 4739 4851 -f 4713 4714 4727 -f 4727 4714 4728 -f 4727 4728 4819 -f 4819 4728 4729 -f 4729 4728 4898 -f 4729 4898 4712 -f 4712 4898 4897 -f 4740 4730 4739 -f 4739 4730 4853 -f 4739 4853 4851 -f 4846 4731 4718 -f 4718 4731 4732 -f 4718 4732 4842 -f 4717 4733 4718 -f 4718 4733 4734 -f 4718 4734 4697 -f 4697 4734 4839 -f 4697 4839 4837 -f 4726 4735 4721 -f 4721 4735 4801 -f 4721 4801 4702 -f 4702 4801 4736 -f 4702 4736 4715 -f 4867 4866 4753 -f 4753 4866 4865 -f 4753 4865 4864 -f 4718 4737 4846 -f 4846 4737 4913 -f 4846 4913 4847 -f 4847 4913 4849 -f 4849 4913 4911 -f 4864 4738 4753 -f 4753 4738 4862 -f 4753 4862 4860 -f 4860 4857 4753 -f 4753 4857 4855 -f 4753 4855 4739 -f 4739 4855 4854 -f 4739 4854 4740 -f 2227 9505 4745 -f 9611 4418 4744 -f 4381 4741 4375 -f 4375 4741 4750 -f 4375 4750 4374 -f 4374 4750 4743 -f 4374 4743 4742 -f 4742 4743 4749 -f 4742 4749 4371 -f 4371 4749 4746 -f 4371 4746 4745 -f 4745 4746 4744 -f 4745 4744 2227 -f 2227 4744 4418 -f 9611 4744 4751 -f 4751 4744 4746 -f 4751 4746 4749 -f 9612 4691 4747 -f 4747 4688 9612 -f 9612 4688 4748 -f 9612 4748 9494 -f 4749 4743 4751 -f 4751 4743 4750 -f 4751 4750 4741 -f 4751 4755 9612 -f 9612 4755 4752 -f 9612 4752 4691 -f 4753 4755 4697 -f 4697 4755 4751 -f 4697 4751 4757 -f 4741 4754 4751 -f 4751 4754 4761 -f 4751 4761 4760 -f 4760 4759 4751 -f 4751 4759 4758 -f 4751 4758 4757 -f 4753 4768 4755 -f 4755 4768 4767 -f 4755 4767 4756 -f 4766 4765 4756 -f 4756 4765 4764 -f 4756 4764 4755 -f 4702 4697 4757 -f 4702 4757 4380 -f 4380 4757 4758 -f 4380 4758 4382 -f 4382 4758 4759 -f 4382 4759 4383 -f 4383 4759 4760 -f 4383 4760 4377 -f 4377 4760 4761 -f 4377 4761 4762 -f 4762 4761 4754 -f 4762 4754 4763 -f 4763 4754 4741 -f 4763 4741 4381 -f 4376 4755 4764 -f 4376 4764 4387 -f 4387 4764 4765 -f 4387 4765 4378 -f 4378 4765 4766 -f 4378 4766 4379 -f 4379 4766 4756 -f 4379 4756 4386 -f 4386 4756 4767 -f 4386 4767 4385 -f 4385 4767 4768 -f 4385 4768 4769 -f 4769 4768 4753 -f 4769 4753 4721 -f 4782 4770 4792 -f 4790 4770 4782 -f 4782 4795 4797 -f 4771 4795 4782 -f 4792 4771 4782 -f 4782 4799 4774 -f 4772 4799 4782 -f 4797 4772 4782 -f 4782 4773 4802 -f 4800 4773 4782 -f 4774 4800 4782 -f 4782 4803 4805 -f 4775 4803 4782 -f 4802 4775 4782 -f 4782 4806 4780 -f 4776 4806 4782 -f 4805 4776 4782 -f 4782 4779 4777 -f 4778 4779 4782 -f 4780 4778 4782 -f 4782 4781 4812 -f 4810 4781 4782 -f 4777 4810 4782 -f 4782 4816 4783 -f 4815 4816 4782 -f 4812 4815 4782 -f 4782 4818 4785 -f 4817 4818 4782 -f 4783 4817 4782 -f 4782 4784 4787 -f 4786 4784 4782 -f 4785 4786 4782 -f 4782 4821 4789 -f 4788 4821 4782 -f 4787 4788 4782 -f 4789 4790 4782 -f 4790 4791 4770 -f 4770 4791 4793 -f 4770 4793 4792 -f 4792 4793 4696 -f 4792 4696 4771 -f 4771 4696 4794 -f 4771 4794 4795 -f 4795 4794 4796 -f 4795 4796 4797 -f 4797 4796 4716 -f 4797 4716 4772 -f 4772 4716 4798 -f 4772 4798 4799 -f 4799 4798 4715 -f 4799 4715 4774 -f 4774 4715 4736 -f 4774 4736 4800 -f 4800 4736 4801 -f 4800 4801 4773 -f 4773 4801 4735 -f 4773 4735 4802 -f 4802 4735 4726 -f 4802 4726 4775 -f 4775 4726 4725 -f 4775 4725 4803 -f 4803 4725 4804 -f 4803 4804 4805 -f 4805 4804 4724 -f 4805 4724 4776 -f 4776 4724 4723 -f 4776 4723 4806 -f 4806 4723 4807 -f 4806 4807 4780 -f 4780 4807 4808 -f 4780 4808 4778 -f 4778 4808 4722 -f 4778 4722 4779 -f 4779 4722 4809 -f 4779 4809 4777 -f 4777 4809 4720 -f 4777 4720 4810 -f 4810 4720 4719 -f 4810 4719 4781 -f 4781 4719 4811 -f 4781 4811 4812 -f 4812 4811 4813 -f 4812 4813 4815 -f 4815 4813 4814 -f 4815 4814 4816 -f 4816 4814 4713 -f 4816 4713 4783 -f 4783 4713 4727 -f 4783 4727 4817 -f 4817 4727 4819 -f 4817 4819 4818 -f 4818 4819 4729 -f 4818 4729 4785 -f 4785 4729 4712 -f 4785 4712 4786 -f 4786 4712 4711 -f 4786 4711 4784 -f 4784 4711 4708 -f 4784 4708 4787 -f 4787 4708 4820 -f 4787 4820 4788 -f 4788 4820 4707 -f 4788 4707 4821 -f 4821 4707 4706 -f 4821 4706 4789 -f 4789 4706 4822 -f 4789 4822 4790 -f 4790 4822 4791 -f 4836 4838 4840 -f 4823 4838 4836 -f 4836 4824 4841 -f 4825 4824 4836 -f 4840 4825 4836 -f 4836 4844 4845 -f 4843 4844 4836 -f 4841 4843 4836 -f 4836 4826 4848 -f 4827 4826 4836 -f 4845 4827 4836 -f 4836 4852 4828 -f 4850 4852 4836 -f 4848 4850 4836 -f 4836 4856 4829 -f 4830 4856 4836 -f 4828 4830 4836 -f 4836 4859 4861 -f 4858 4859 4836 -f 4829 4858 4836 -f 4836 4831 4832 -f 4863 4831 4836 -f 4861 4863 4836 -f 4836 4869 4870 -f 4833 4869 4836 -f 4832 4833 4836 -f 4836 4834 4873 -f 4835 4834 4836 -f 4870 4835 4836 -f 4836 4876 4878 -f 4874 4876 4836 -f 4873 4874 4836 -f 4836 4882 4883 -f 4879 4882 4836 -f 4878 4879 4836 -f 4883 4823 4836 -f 4823 4837 4838 -f 4838 4837 4839 -f 4838 4839 4840 -f 4840 4839 4734 -f 4840 4734 4825 -f 4825 4734 4733 -f 4825 4733 4824 -f 4824 4733 4717 -f 4824 4717 4841 -f 4841 4717 4842 -f 4841 4842 4843 -f 4843 4842 4732 -f 4843 4732 4844 -f 4844 4732 4731 -f 4844 4731 4845 -f 4845 4731 4846 -f 4845 4846 4827 -f 4827 4846 4847 -f 4827 4847 4826 -f 4826 4847 4849 -f 4826 4849 4848 -f 4848 4849 4851 -f 4848 4851 4850 -f 4850 4851 4853 -f 4850 4853 4852 -f 4852 4853 4730 -f 4852 4730 4828 -f 4828 4730 4740 -f 4828 4740 4830 -f 4830 4740 4854 -f 4830 4854 4856 -f 4856 4854 4855 -f 4856 4855 4829 -f 4829 4855 4857 -f 4829 4857 4858 -f 4858 4857 4860 -f 4858 4860 4859 -f 4859 4860 4862 -f 4859 4862 4861 -f 4861 4862 4738 -f 4861 4738 4863 -f 4863 4738 4864 -f 4863 4864 4831 -f 4831 4864 4865 -f 4831 4865 4832 -f 4832 4865 4866 -f 4832 4866 4833 -f 4833 4866 4867 -f 4833 4867 4869 -f 4869 4867 4868 -f 4869 4868 4870 -f 4870 4868 4694 -f 4870 4694 4835 -f 4835 4694 4704 -f 4835 4704 4834 -f 4834 4704 4871 -f 4834 4871 4873 -f 4873 4871 4872 -f 4873 4872 4874 -f 4874 4872 4875 -f 4874 4875 4876 -f 4876 4875 4877 -f 4876 4877 4878 -f 4878 4877 4880 -f 4878 4880 4879 -f 4879 4880 4881 -f 4879 4881 4882 -f 4882 4881 4884 -f 4882 4884 4883 -f 4883 4884 4885 -f 4883 4885 4823 -f 4823 4885 4837 -f 4891 4892 4894 -f 4894 4896 4891 -f 4891 4886 4899 -f 4896 4886 4891 -f 4899 4887 4891 -f 4891 4900 4902 -f 4887 4900 4891 -f 4902 4888 4891 -f 4905 4906 4891 -f 4888 4905 4891 -f 4908 4909 4891 -f 4906 4908 4891 -f 4891 4912 4889 -f 4909 4912 4891 -f 4891 4914 4915 -f 4889 4914 4891 -f 4891 4890 4917 -f 4915 4890 4891 -f 4917 4919 4891 -f 4919 4892 4891 -f 4892 4703 4701 -f 4892 4701 4894 -f 4894 4701 4893 -f 4894 4893 4895 -f 4894 4895 4896 -f 4896 4895 4705 -f 4896 4705 4897 -f 4896 4897 4886 -f 4886 4897 4898 -f 4886 4898 4899 -f 4899 4898 4728 -f 4899 4728 4887 -f 4887 4728 4714 -f 4887 4714 4900 -f 4900 4714 4901 -f 4900 4901 4902 -f 4902 4901 4695 -f 4902 4695 4693 -f 4902 4693 4888 -f 4888 4693 4903 -f 4888 4903 4904 -f 4888 4904 4905 -f 4905 4904 4699 -f 4905 4699 4906 -f 4906 4699 4700 -f 4906 4700 4907 -f 4906 4907 4908 -f 4908 4907 4710 -f 4908 4710 4909 -f 4909 4710 4709 -f 4909 4709 4739 -f 4909 4739 4912 -f 4912 4739 4910 -f 4912 4910 4911 -f 4912 4911 4889 -f 4889 4911 4914 -f 4914 4911 4913 -f 4914 4913 4915 -f 4915 4913 4737 -f 4915 4737 4718 -f 4915 4718 4890 -f 4890 4718 4916 -f 4890 4916 4917 -f 4917 4916 4698 -f 4917 4698 4918 -f 4917 4918 4919 -f 4919 4918 4692 -f 4919 4692 4920 -f 4919 4920 4892 -f 4892 4920 4703 -f 9578 4921 7325 -f 7325 4921 4922 -f 7299 7000 7020 -f 7325 4922 7298 -f 7325 7298 7020 -f 7020 7298 7299 -f 7021 4923 9519 -f 4923 7070 9519 -f 9519 7070 7388 -f 7069 4923 7021 -f 7069 4926 7067 -f 4926 7069 7021 -f 7066 4924 7018 -f 7066 7018 4925 -f 7066 7067 4924 -f 4924 7067 4926 -f 7026 7064 7018 -f 7018 7064 4925 -f 7388 7070 7387 -f 2250 9534 4927 -f 4927 9534 4928 -f 9532 4931 7088 -f 9532 7088 9557 -f 9557 7088 4928 -f 9557 4928 9534 -f 4930 7123 4929 -f 4930 4929 7125 -f 4930 7125 7128 -f 4930 7128 9532 -f 9532 7128 4931 -f 4934 7123 9531 -f 5013 7120 7119 -f 5013 7119 4932 -f 9531 4933 4934 -f 4934 4933 5186 -f 4934 5186 7119 -f 7119 5186 5185 -f 7119 5185 4932 -f 9531 7123 4930 -f 7116 2354 7113 -f 7113 2354 2364 -f 2354 7116 7118 -f 2354 7120 5013 -f 2354 7118 7120 -f 7113 2364 2363 -f 7113 2363 4935 -f 4935 2363 2362 -f 4935 2362 7094 -f 6292 4941 6222 -f 6281 4939 4936 -f 4937 6363 6360 -f 6363 4937 5425 -f 6360 6358 4937 -f 4941 6287 4937 -f 4937 6287 4939 -f 4939 6287 4938 -f 4938 4936 4939 -f 6279 4939 6281 -f 6355 4942 6229 -f 6227 4940 4937 -f 4937 4940 6225 -f 4937 6225 4941 -f 4941 6225 6223 -f 4941 6223 6222 -f 4937 6358 6357 -f 4937 6357 6227 -f 6227 6357 6355 -f 6227 6355 6229 -f 6292 6222 6220 -f 4942 6355 4944 -f 6204 4943 6220 -f 6220 4943 6292 -f 6340 6231 4944 -f 4944 6231 4942 -f 4946 6326 4947 -f 6322 5916 4945 -f 6322 4945 5915 -f 6322 5915 6320 -f 6320 5915 4978 -f 5916 6322 6323 -f 5916 6323 5808 -f 5808 6323 6325 -f 4946 4947 6325 -f 6325 4947 5808 -f 6326 6295 4947 -f 4947 6295 4948 -f 4948 6295 4949 -f 4951 5204 5203 -f 6295 6296 4949 -f 4949 6296 4951 -f 4949 4951 4950 -f 4950 4951 5203 -f 6232 6269 4951 -f 4952 6166 4955 -f 4952 4955 4957 -f 6232 4965 6201 -f 6232 6201 6255 -f 6255 6201 6164 -f 6255 6164 6257 -f 6257 6164 4953 -f 6257 4953 4954 -f 4954 4953 6166 -f 4954 6166 4952 -f 4957 4955 4956 -f 4957 4956 4958 -f 4958 4956 4960 -f 4958 4960 6252 -f 6252 4960 6172 -f 6252 6172 4959 -f 4959 6172 6170 -f 6175 6250 4959 -f 6175 4959 6170 -f 4962 4963 4961 -f 4962 4961 6175 -f 6175 4961 6250 -f 6174 4964 4962 -f 4962 4964 4963 -f 4964 6174 6176 -f 4964 6176 6180 -f 4965 6232 4951 -f 4965 4951 6296 -f 6193 6300 4968 -f 6193 4968 6191 -f 4965 6296 4966 -f 4966 6296 6337 -f 4966 6337 4967 -f 4967 6337 6297 -f 4967 6297 6192 -f 6192 6297 6300 -f 6192 6300 6193 -f 6191 4968 4969 -f 6191 4969 6190 -f 6190 4969 6303 -f 6190 6303 6186 -f 6186 6303 6308 -f 6186 6308 6185 -f 6185 6308 6306 -f 6305 4971 6185 -f 6305 6185 6306 -f 4974 4975 4970 -f 4974 4970 6305 -f 6305 4970 4971 -f 4972 4973 4974 -f 4974 4973 4975 -f 4973 4972 6309 -f 4973 6309 6314 -f 4982 4977 4976 -f 4976 4977 4978 -f 4978 4977 6320 -f 4980 6317 4979 -f 4979 6317 4981 -f 4979 4981 4976 -f 4976 4981 4982 -f 6016 5433 6020 -f 4983 6020 5433 -f 6021 5998 6152 -f 6152 4984 6021 -f 6369 5219 6368 -f 5219 6369 5346 -f 5346 6369 4985 -f 4978 5915 5917 -f 5763 5764 4976 -f 5745 9521 4986 -f 4986 9521 9502 -f 5745 4986 4989 -f 4989 4986 4987 -f 4989 4987 5236 -f 4978 5917 4976 -f 4976 5764 4979 -f 4979 5764 4988 -f 4988 5764 5752 -f 4988 5752 4991 -f 5917 5761 5763 -f 5236 5237 4989 -f 4989 5237 5238 -f 4989 5238 5239 -f 5917 5763 4976 -f 5239 5241 4989 -f 4989 5241 4990 -f 4989 4990 5752 -f 5752 4990 5243 -f 5752 5243 4991 -f 5439 5889 4992 -f 4992 5889 5892 -f 4992 5892 5946 -f 5946 5892 5893 -f 5946 5893 4993 -f 4993 5893 5894 -f 4993 5894 4994 -f 4994 5894 4995 -f 4994 4995 4996 -f 4996 4995 4997 -f 4996 4997 5943 -f 5943 4997 5895 -f 5943 5895 5942 -f 5942 5895 4998 -f 5942 4998 5941 -f 5941 4998 5897 -f 5941 5897 4999 -f 4999 5897 5899 -f 4999 5899 5940 -f 5940 5899 5000 -f 5940 5000 5938 -f 5938 5000 5901 -f 5938 5901 5001 -f 5001 5901 5002 -f 5001 5002 5003 -f 5003 5002 5004 -f 5003 5004 5937 -f 5937 5004 5005 -f 5937 5005 5935 -f 5935 5005 5006 -f 5935 5006 5933 -f 5933 5006 5906 -f 5933 5906 5932 -f 5932 5906 5007 -f 5932 5007 5008 -f 5008 5007 5907 -f 5008 5907 5931 -f 5931 5907 5908 -f 5931 5908 5928 -f 5928 5908 5009 -f 5928 5009 5010 -f 5010 5009 5910 -f 5010 5910 5927 -f 5927 5910 5011 -f 5927 5011 5925 -f 5925 5011 5912 -f 5925 5912 5012 -f 5012 5912 5914 -f 5163 5103 5147 -f 5129 5013 4932 -f 5753 5014 5027 -f 5027 5014 6773 -f 6757 5015 5087 -f 5087 5015 6756 -f 2293 5023 5753 -f 5753 5023 5016 -f 5753 5016 5014 -f 6773 6772 5027 -f 5027 6772 6771 -f 5027 6771 6769 -f 6769 6768 5027 -f 5027 6768 5017 -f 5027 5017 5026 -f 6756 6755 5087 -f 5087 6755 6754 -f 5087 6754 5018 -f 5018 6754 6790 -f 6790 6789 5018 -f 5018 6789 5019 -f 5018 5019 6787 -f 5020 2293 5021 -f 5021 2293 6779 -f 5020 6775 2293 -f 2293 6775 5022 -f 2293 5022 5023 -f 5024 6760 5087 -f 5087 6760 6758 -f 5087 6758 6757 -f 6787 6785 5018 -f 5018 6785 5025 -f 5018 5025 6783 -f 5026 6765 5027 -f 5027 6765 5028 -f 5027 5028 5087 -f 5087 5028 6762 -f 5087 6762 5024 -f 6783 6781 5018 -f 5018 6781 6780 -f 5018 6780 2293 -f 2293 6780 5029 -f 2293 5029 6779 -f 5426 5030 6716 -f 5426 6716 5032 -f 6703 6702 5157 -f 5030 5426 6717 -f 6717 5426 5046 -f 6717 5046 5047 -f 6716 5031 5032 -f 5032 5031 6713 -f 5032 6713 6711 -f 6711 6709 5032 -f 5032 6709 5033 -f 5032 5033 5034 -f 5049 6706 5157 -f 5157 6706 5035 -f 5157 5035 6703 -f 6700 5144 5036 -f 5036 5144 5157 -f 5036 5157 5037 -f 5037 5157 6702 -f 6700 5038 5144 -f 5144 5038 6731 -f 5144 6731 5039 -f 5039 5040 5144 -f 5144 5040 5041 -f 5144 5041 5042 -f 5145 6723 5046 -f 5046 6723 5043 -f 5046 5043 5044 -f 5044 5045 5046 -f 5046 5045 6720 -f 5046 6720 5047 -f 5034 6708 5032 -f 5032 6708 5048 -f 5032 5048 5157 -f 5157 5048 6707 -f 5157 6707 5049 -f 5042 6726 5144 -f 5144 6726 5050 -f 5144 5050 6724 -f 5052 6465 6506 -f 6503 5057 6505 -f 6505 5057 5052 -f 6505 5052 5051 -f 5051 5052 6506 -f 6485 5053 5059 -f 5059 5053 5054 -f 5054 5055 5059 -f 5059 5055 5056 -f 5059 5056 5185 -f 5185 5056 6481 -f 5185 6481 6478 -f 6503 6501 5057 -f 5057 6501 6499 -f 5057 6499 6498 -f 6498 5058 5057 -f 5057 5058 6497 -f 5057 6497 6494 -f 5061 6487 5059 -f 5059 6487 5060 -f 5059 5060 6485 -f 6494 6493 5057 -f 5057 6493 6491 -f 5057 6491 5059 -f 5059 6491 6489 -f 5059 6489 5061 -f 6469 6468 5141 -f 6478 5062 5185 -f 5185 5062 5063 -f 5185 5063 5064 -f 5064 5063 5065 -f 5065 6476 5064 -f 5064 6476 5066 -f 5064 5066 5067 -f 5067 5068 5064 -f 5064 5068 6471 -f 5064 6471 5141 -f 5141 6471 5069 -f 5141 5069 6469 -f 5105 6593 5085 -f 6599 6598 5163 -f 5163 6598 5070 -f 5163 5070 5105 -f 5105 5070 6595 -f 5105 6595 6593 -f 5079 5081 5071 -f 5071 6621 5079 -f 5079 6621 6617 -f 5079 6617 5075 -f 5075 6617 5072 -f 5075 5072 6616 -f 6616 6614 5075 -f 5075 6614 5073 -f 5075 5073 5074 -f 5074 5076 5075 -f 5075 5076 6609 -f 5075 6609 6608 -f 5078 5077 5163 -f 5163 5077 6601 -f 5163 6601 6599 -f 6607 6606 5163 -f 5163 6606 6604 -f 5163 6604 5078 -f 5027 5080 5079 -f 5079 5080 5081 -f 5082 5083 5027 -f 5027 5083 5084 -f 5027 5084 5080 -f 5085 5086 5105 -f 5105 5086 6590 -f 5105 6590 5087 -f 6590 6588 5087 -f 5087 6588 6587 -f 5087 6587 5088 -f 5088 6583 5087 -f 5087 6583 6582 -f 5087 6582 5027 -f 5027 6582 5089 -f 5027 5089 5082 -f 5090 6677 5105 -f 5092 6656 5091 -f 5091 6656 6654 -f 5091 6654 5143 -f 5091 5103 5095 -f 5091 5095 5092 -f 5102 5093 5103 -f 5103 5093 5094 -f 5103 5094 5095 -f 5097 5163 5096 -f 5096 5163 6672 -f 5097 6668 5163 -f 5163 6668 5098 -f 5163 5098 6667 -f 6677 5099 5105 -f 5105 5099 5100 -f 5105 5100 5163 -f 5163 5100 5101 -f 5163 5101 6672 -f 6660 6659 5103 -f 5103 6659 6658 -f 5103 6658 5102 -f 6667 6665 5163 -f 5163 6665 6663 -f 5163 6663 5103 -f 5103 6663 6662 -f 5103 6662 6660 -f 5108 6652 5104 -f 6643 6642 5087 -f 5087 6642 6678 -f 5087 6678 5105 -f 5105 6678 5090 -f 5104 6649 5108 -f 5108 6649 5106 -f 5108 5106 6648 -f 6648 5107 5108 -f 5108 5107 6647 -f 5108 6647 5087 -f 5087 6647 6645 -f 5087 6645 6643 -f 5119 6869 5108 -f 5117 6879 5087 -f 5109 6903 2310 -f 5123 5110 5018 -f 5018 5110 6888 -f 5018 6888 6885 -f 6869 6867 5108 -f 5108 6867 5111 -f 5108 5111 5127 -f 5112 5113 5087 -f 5109 2310 5126 -f 6885 5114 5018 -f 5018 5114 6884 -f 5018 6884 5087 -f 5087 6884 5115 -f 5087 5115 5112 -f 5113 5116 5087 -f 5087 5116 6882 -f 5087 6882 5117 -f 6879 5118 5087 -f 5087 5118 6877 -f 5087 6877 5108 -f 5108 6877 6875 -f 5108 6875 6874 -f 6874 6873 5108 -f 5108 6873 6870 -f 5108 6870 5119 -f 6903 6900 2310 -f 2310 6900 6899 -f 2310 6899 6897 -f 6897 6896 2310 -f 2310 6896 6893 -f 2310 6893 5120 -f 5120 5121 2310 -f 2310 5121 5122 -f 2310 5122 5018 -f 5018 5122 6890 -f 5018 6890 5123 -f 6543 5124 5125 -f 5125 5124 5141 -f 5125 5141 2312 -f 2312 5141 6988 -f 2312 6988 2310 -f 2310 6988 5108 -f 2310 5108 5126 -f 5126 5108 5127 -f 5124 6540 5141 -f 5141 6540 6539 -f 5141 6539 5135 -f 5128 6563 5129 -f 5129 6563 6561 -f 5129 6561 5130 -f 5131 6548 5125 -f 5140 5132 5064 -f 5064 5132 6528 -f 6528 6527 5064 -f 5064 6527 6526 -f 5064 6526 5129 -f 5129 6526 5133 -f 5129 5133 5128 -f 5130 6558 5129 -f 5129 6558 6557 -f 5129 6557 6556 -f 6548 6547 5125 -f 5125 6547 6545 -f 5125 6545 6543 -f 6556 6554 5129 -f 5129 6554 6551 -f 5129 6551 5125 -f 5125 6551 5134 -f 5125 5134 5131 -f 5135 6538 5141 -f 5141 6538 5136 -f 5141 5136 6537 -f 5137 5138 5064 -f 5137 5064 5142 -f 5138 6531 5064 -f 5064 6531 5139 -f 5064 5139 5140 -f 6537 6536 5141 -f 5141 6536 6534 -f 5141 6534 5064 -f 5064 6534 6533 -f 5064 6533 5142 -f 6468 6465 5141 -f 5141 6465 5052 -f 5108 5091 6652 -f 6652 5091 5143 -f 5075 5144 5046 -f 5046 5144 6724 -f 5046 6724 5145 -f 5059 5179 5057 -f 5057 5179 5174 -f 6808 6847 5147 -f 5167 9551 5146 -f 5146 9551 5153 -f 6847 5148 5147 -f 5147 5148 6846 -f 5147 6846 6845 -f 5155 6835 5144 -f 5144 6835 5149 -f 5144 5149 6832 -f 6824 9537 5150 -f 5150 9537 5159 -f 5150 5159 6827 -f 6824 5151 9537 -f 9537 5151 5152 -f 9537 5152 6819 -f 6815 6813 9551 -f 9551 6813 6811 -f 9551 6811 5153 -f 5164 6838 5144 -f 5144 6838 5154 -f 5144 5154 5155 -f 6832 6831 5144 -f 5144 6831 5156 -f 5144 5156 5157 -f 5157 5156 6828 -f 5157 6828 9548 -f 9548 6828 6827 -f 9548 6827 5158 -f 5158 6827 5159 -f 6845 6843 5147 -f 5147 6843 6842 -f 5147 6842 5160 -f 5160 5161 5147 -f 5147 5161 5162 -f 5147 5162 6839 -f 6608 6607 5075 -f 5075 6607 5163 -f 5075 5163 5144 -f 5144 5163 5147 -f 5144 5147 5164 -f 5164 5147 6839 -f 6819 5165 9537 -f 9537 5165 6818 -f 9537 6818 9551 -f 9551 6818 6817 -f 9551 6817 6815 -f 5174 5169 5166 -f 5166 5169 9529 -f 5166 9529 5147 -f 5147 9529 9551 -f 5147 9551 6808 -f 6808 9551 5167 -f 6433 6431 5174 -f 5174 6431 5168 -f 5174 5168 5169 -f 5169 5168 5170 -f 5169 5170 5171 -f 6446 6445 5179 -f 6441 6440 5179 -f 6414 6413 5177 -f 5177 6413 6411 -f 5177 6411 5179 -f 5179 6411 6448 -f 5179 6448 6446 -f 5172 6438 5174 -f 5171 6429 5169 -f 5169 6429 5173 -f 5169 5173 5182 -f 6438 6435 5174 -f 5174 6435 6434 -f 5174 6434 6433 -f 6417 6416 5177 -f 5177 6416 6415 -f 5177 6415 6414 -f 6445 5175 5179 -f 5179 5175 5176 -f 5179 5176 6444 -f 5179 6440 5174 -f 5174 6440 6439 -f 5174 6439 5172 -f 5184 5181 5177 -f 6444 5178 5179 -f 5179 5178 5180 -f 5179 5180 6441 -f 5181 6421 5177 -f 5177 6421 6418 -f 5177 6418 6417 -f 5182 6426 5169 -f 5169 6426 6425 -f 5169 6425 5177 -f 5177 6425 5183 -f 5177 5183 5184 -f 5129 4932 5064 -f 5064 4932 5185 -f 5185 5186 5059 -f 5059 5186 4933 -f 5059 4933 5179 -f 5179 4933 9531 -f 5179 9531 5177 -f 5187 2245 2362 -f 2362 2245 7094 -f 7065 5196 9590 -f 7065 9590 5188 -f 5188 9590 9591 -f 5188 9591 5189 -f 5189 9591 5190 -f 5189 5190 7075 -f 7075 5190 5192 -f 7075 5192 5191 -f 5191 5192 7385 -f 5191 7385 7387 -f 7016 5202 5193 -f 5193 5202 5194 -f 5193 5194 7065 -f 5199 5195 7232 -f 7232 5195 9579 -f 7232 9579 5194 -f 5194 9579 5196 -f 5194 5196 7065 -f 5201 5744 5809 -f 5809 5810 5201 -f 5201 5810 5197 -f 5201 5197 7232 -f 7232 5197 5198 -f 7232 5198 5199 -f 7016 9521 5200 -f 5743 7016 5749 -f 5749 7016 5200 -f 5749 5200 5748 -f 5201 5202 5744 -f 5744 5202 7016 -f 5744 7016 5743 -f 5203 5204 5205 -f 5205 5204 5528 -f 5205 5528 5796 -f 5796 5528 5206 -f 5796 5206 5207 -f 5207 5206 5531 -f 5207 5531 5208 -f 5531 5530 5208 -f 5208 5530 5209 -f 5208 5209 5210 -f 5210 5209 5211 -f 5210 5211 5800 -f 5800 5211 5212 -f 5800 5212 5801 -f 5801 5212 5213 -f 5801 5213 5214 -f 5215 6368 5219 -f 5215 5219 5218 -f 5215 5222 6367 -f 5215 6367 6366 -f 6366 6368 5215 -f 5214 5213 5787 -f 5787 5213 5516 -f 5515 5789 5516 -f 5516 5789 5788 -f 5516 5788 5787 -f 5513 5216 5514 -f 5514 5216 5790 -f 5514 5790 5515 -f 5515 5790 5217 -f 5515 5217 5789 -f 5218 5219 5855 -f 5218 5855 5511 -f 5511 5855 5220 -f 5511 5220 5512 -f 5512 5220 5221 -f 5512 5221 5513 -f 5513 5221 5792 -f 5513 5792 5216 -f 5487 6381 5222 -f 5222 6381 6365 -f 5222 6365 6367 -f 5226 5223 6380 -f 6381 5487 5224 -f 5224 5487 5226 -f 5224 5226 6380 -f 6378 6379 5225 -f 5225 6379 5226 -f 5226 6379 5223 -f 6376 6377 5488 -f 5488 6377 5225 -f 5225 6377 6378 -f 2300 5227 5490 -f 5490 5227 5488 -f 5488 5227 6376 -f 5519 2282 5228 -f 5228 2282 5229 -f 5228 5229 5495 -f 5495 5229 5230 -f 5495 5230 5494 -f 5494 5230 2280 -f 5494 2280 5231 -f 5231 2280 5232 -f 5231 5232 5492 -f 5492 5232 2271 -f 5492 2271 5491 -f 5491 2271 5233 -f 5491 5233 5235 -f 5235 5233 5234 -f 5235 5234 5490 -f 5490 5234 2299 -f 5490 2299 2300 -f 2282 5519 9512 -f 9512 5519 5517 -f 9512 5517 9502 -f 9502 5517 4986 -f 4986 5517 5584 -f 4986 5584 4987 -f 4987 5584 5585 -f 4987 5585 5236 -f 5236 5585 5586 -f 5236 5586 5237 -f 5237 5586 5587 -f 5237 5587 5238 -f 5238 5587 5240 -f 5238 5240 5239 -f 5239 5240 5588 -f 5239 5588 5241 -f 5241 5588 5589 -f 5241 5589 4990 -f 4990 5589 5242 -f 4990 5242 5243 -f 5243 5242 5244 -f 5243 5244 4991 -f 4991 5244 5591 -f 4991 5591 4988 -f 4988 5591 5245 -f 5245 6247 6249 -f 5245 6249 4964 -f 5245 4964 6180 -f 4979 4988 4980 -f 4980 4988 6312 -f 6180 6179 5245 -f 5245 6179 4973 -f 5245 4973 4988 -f 4988 4973 6314 -f 4988 6314 6312 -f 5248 5597 5571 -f 5504 5246 5527 -f 5527 5246 5247 -f 5527 5247 5571 -f 5571 5247 5552 -f 5571 5552 5248 -f 5299 5249 5250 -f 5250 5249 5309 -f 5250 5309 2333 -f 2333 5309 5251 -f 2333 5251 2305 -f 2305 5251 5252 -f 2305 5252 5253 -f 5253 5252 5254 -f 5253 5254 2314 -f 2314 5254 5308 -f 2314 5308 5256 -f 5256 5308 5255 -f 5256 5255 5257 -f 5257 5255 2285 -f 2285 5255 5258 -f 2285 5258 5259 -f 5259 5258 5260 -f 5259 5260 2286 -f 2286 5260 5301 -f 2286 5301 5261 -f 5261 5301 5262 -f 5261 5262 2295 -f 2295 5262 5263 -f 2295 5263 5264 -f 5264 5263 5306 -f 5264 5306 5265 -f 5265 5306 5305 -f 5265 5305 5266 -f 5266 5305 5267 -f 5266 5267 5269 -f 5269 5267 5268 -f 5269 5268 5270 -f 5270 5268 5307 -f 5270 5307 5271 -f 5271 5307 5304 -f 5271 5304 5272 -f 5272 5304 5273 -f 5272 5273 2315 -f 2315 5273 5274 -f 2315 5274 5275 -f 5275 5274 5303 -f 5275 5303 2332 -f 2332 5303 5276 -f 2332 5276 5277 -f 5277 5276 5302 -f 5277 5302 5278 -f 5278 5302 5279 -f 5278 5279 2301 -f 2301 5279 5280 -f 2301 5280 2302 -f 2302 5280 5281 -f 2302 5281 2296 -f 2296 5281 5282 -f 2296 5282 2297 -f 2297 5282 5283 -f 2297 5283 2298 -f 2298 5283 5285 -f 2298 5285 5284 -f 5284 5285 5286 -f 5284 5286 2307 -f 2307 5286 5310 -f 2307 5310 5287 -f 5287 5310 5311 -f 5287 5311 5288 -f 5288 5311 5312 -f 5288 5312 2308 -f 2308 5312 5289 -f 2308 5289 2309 -f 2309 5289 5290 -f 2309 5290 5291 -f 5291 5290 5293 -f 5291 5293 5292 -f 5292 5293 5294 -f 5292 5294 2311 -f 2311 5294 5295 -f 2311 5295 5296 -f 5296 5295 5314 -f 5296 5314 2313 -f 2313 5314 5313 -f 2313 5313 5297 -f 5297 5313 5298 -f 5297 5298 2350 -f 2350 5298 5300 -f 2350 5300 5299 -f 5299 5300 5249 -f 5304 5307 5312 -f 5312 5249 5300 -f 5301 5260 5268 -f 5254 5252 5312 -f 5280 5279 5311 -f 5311 5279 5302 -f 5311 5302 5312 -f 5312 5302 5276 -f 5312 5276 5303 -f 5303 5274 5312 -f 5312 5274 5273 -f 5312 5273 5304 -f 5305 5306 5263 -f 5260 5258 5268 -f 5268 5258 5255 -f 5268 5255 5307 -f 5307 5255 5312 -f 5312 5255 5308 -f 5312 5308 5254 -f 5252 5251 5312 -f 5312 5251 5309 -f 5312 5309 5249 -f 5305 5263 5267 -f 5310 5286 5285 -f 5285 5283 5310 -f 5310 5283 5282 -f 5310 5282 5311 -f 5311 5282 5281 -f 5311 5281 5280 -f 5267 5263 5268 -f 5268 5263 5262 -f 5268 5262 5301 -f 5293 5290 5294 -f 5294 5290 5289 -f 5294 5289 5295 -f 5300 5298 5312 -f 5312 5298 5313 -f 5312 5313 5289 -f 5289 5313 5314 -f 5289 5314 5295 -f 2272 5396 5315 -f 5315 5396 5740 -f 5315 5740 2273 -f 2273 5740 5316 -f 2273 5316 5317 -f 5317 5316 5318 -f 5317 5318 5319 -f 5319 5318 5739 -f 5319 5739 5320 -f 5320 5739 5738 -f 5320 5738 2294 -f 2294 5738 5737 -f 2294 5737 5321 -f 5321 5737 5736 -f 5321 5736 5323 -f 5323 5736 5322 -f 5323 5322 5324 -f 5324 5322 5325 -f 5324 5325 2331 -f 2331 5325 5699 -f 2331 5699 5326 -f 5326 5699 5647 -f 5326 5647 5327 -f 5327 5647 5328 -f 5327 5328 5329 -f 5329 5328 5330 -f 5329 5330 2319 -f 2319 5330 5650 -f 2319 5650 2284 -f 2284 5650 5651 -f 2284 5651 2283 -f 2283 5651 5332 -f 2283 5332 5331 -f 5331 5332 5653 -f 5331 5653 2274 -f 2274 5653 5333 -f 2274 5333 2275 -f 2275 5333 5335 -f 2275 5335 5334 -f 5334 5335 5336 -f 5334 5336 2276 -f 2276 5336 5654 -f 2276 5654 2279 -f 2279 5654 5337 -f 2279 5337 2278 -f 2278 5337 5339 -f 2278 5339 5338 -f 5338 5339 5343 -f 5341 5340 6372 -f 5343 5342 6387 -f 6372 6364 5341 -f 5341 6364 5342 -f 5341 5342 5343 -f 6387 6388 5343 -f 5343 6388 5338 -f 6388 6386 5338 -f 6371 5345 6374 -f 5340 5341 5344 -f 5344 5341 5345 -f 5344 5345 6371 -f 5856 5346 5345 -f 6374 5345 5346 -f 6374 5346 4985 -f 5348 5858 5629 -f 5629 5858 5856 -f 5629 5856 5347 -f 5347 5856 5345 -f 5774 5773 5348 -f 5348 5773 5349 -f 5348 5349 5858 -f 5348 5627 5774 -f 5774 5627 5350 -f 5774 5350 5351 -f 5626 5775 5350 -f 5350 5775 5352 -f 5350 5352 5351 -f 5353 5625 5779 -f 5779 5776 5353 -f 5353 5776 5778 -f 5353 5778 5626 -f 5626 5778 5354 -f 5626 5354 5775 -f 5779 5625 5780 -f 5780 5625 5356 -f 5780 5356 5355 -f 5355 5356 5358 -f 5355 5358 5357 -f 5357 5358 5359 -f 5357 5359 5360 -f 5360 5359 5361 -f 5360 5361 5784 -f 5784 5361 5362 -f 5784 5362 5363 -f 5362 5364 5363 -f 5363 5364 5365 -f 5363 5365 5367 -f 5367 5365 5366 -f 5367 5366 5368 -f 6090 5389 5369 -f 5961 6117 5372 -f 5959 5370 5961 -f 5961 5370 6117 -f 5370 5959 5371 -f 5370 5371 5397 -f 5961 5372 5374 -f 5374 5372 6119 -f 5955 5373 5957 -f 5374 6119 5373 -f 5374 5373 5955 -f 5957 5373 6121 -f 5957 6121 5954 -f 5954 6121 5375 -f 5954 5375 5376 -f 5376 5375 6127 -f 6124 5950 5952 -f 6124 5952 6127 -f 6127 5952 5376 -f 6124 6129 5950 -f 5950 6129 5949 -f 5949 6129 6131 -f 5949 6131 5377 -f 5377 6131 5378 -f 5377 5378 5948 -f 5948 5378 6090 -f 5388 6022 6024 -f 5948 6090 5369 -f 5948 5388 5981 -f 5981 5388 6024 -f 5379 5381 5382 -f 5379 5382 5975 -f 5981 6024 5380 -f 5380 6024 6062 -f 5380 6062 5980 -f 5980 6062 6039 -f 5980 6039 5979 -f 5979 6039 5381 -f 5979 5381 5379 -f 5975 5382 6042 -f 5975 6042 5976 -f 5976 6042 6046 -f 5976 6046 5973 -f 5973 6046 5383 -f 5973 5383 5384 -f 5384 5383 6050 -f 6049 5972 5384 -f 6049 5384 6050 -f 5386 5385 5970 -f 5386 5970 6049 -f 6049 5970 5972 -f 5387 5968 5386 -f 5386 5968 5385 -f 5968 5387 6051 -f 5968 6051 6055 -f 5368 5366 5772 -f 5772 5366 5388 -f 5772 5388 5369 -f 5369 5388 5948 -f 5389 6090 6092 -f 5389 6092 5391 -f 5389 5391 5390 -f 5390 5391 6096 -f 5390 6096 5804 -f 5804 6096 6098 -f 5804 6098 6100 -f 5804 6100 5854 -f 5854 6100 6093 -f 5854 6093 5392 -f 6104 6110 5395 -f 5395 6110 6108 -f 5395 6108 6114 -f 6106 5394 5393 -f 5392 6093 5393 -f 5392 5393 5394 -f 5394 6106 5395 -f 5395 6106 6104 -f 6027 5741 5396 -f 2272 5965 5396 -f 5396 5965 5968 -f 5968 6055 5396 -f 5396 6055 6026 -f 5396 6026 6027 -f 5395 6114 2272 -f 2272 6114 6113 -f 2272 6113 5965 -f 5965 6113 5370 -f 5965 5370 5397 -f 5675 5398 5635 -f 5635 5398 5698 -f 5635 5698 5611 -f 5675 5635 5670 -f 5670 5635 5722 -f 5670 5722 5719 -f 5405 6211 5404 -f 6231 6340 5399 -f 6343 6213 5399 -f 5399 6340 6343 -f 5818 6274 5400 -f 6207 6215 5402 -f 5400 6274 5401 -f 5401 6208 5402 -f 5402 6208 6207 -f 5404 6211 6270 -f 5401 6270 6208 -f 6208 6270 6211 -f 6213 6343 6348 -f 6213 6348 6215 -f 6215 6348 5403 -f 6215 5403 5402 -f 5402 5403 6345 -f 6345 5422 5402 -f 5405 5404 5406 -f 5405 5406 6204 -f 4943 6204 5406 -f 5819 5407 5408 -f 5408 5407 5818 -f 5818 5407 6274 -f 5819 6279 5407 -f 5410 5919 5409 -f 5410 5409 5886 -f 5886 5409 5414 -f 5012 5914 5923 -f 5923 5914 5411 -f 5413 5412 5411 -f 5411 5412 5918 -f 5411 5918 5923 -f 5412 5413 5885 -f 5412 5885 5414 -f 5414 5885 5886 -f 5410 5415 5919 -f 5919 5415 5416 -f 5919 5416 5417 -f 5417 5416 5418 -f 5417 5418 5759 -f 5759 5418 5419 -f 5759 5419 5420 -f 5420 5419 5421 -f 5420 5421 5760 -f 5760 5421 5400 -f 5760 5400 5402 -f 5402 5400 5401 -f 5422 6345 5762 -f 5762 6345 5423 -f 5423 5424 5762 -f 5424 5423 5425 -f 5046 5426 5851 -f 6021 4984 6014 -f 6014 4984 5430 -f 5434 5427 5428 -f 5428 5427 6082 -f 6011 6086 6012 -f 6012 6086 6085 -f 5755 6081 6086 -f 5755 6086 5431 -f 5431 6086 6011 -f 6154 6156 5755 -f 6014 5430 5429 -f 5429 5430 6155 -f 5429 6155 6154 -f 5431 5432 5755 -f 5755 5432 5429 -f 5755 5429 6154 -f 5755 6156 5757 -f 6012 6085 6016 -f 6016 6085 5433 -f 6082 6081 5428 -f 5428 6081 5755 -f 5428 5755 5850 -f 5850 5755 5436 -f 5850 5436 5435 -f 5436 5437 5435 -f 5435 5437 5754 -f 5435 5754 5851 -f 5753 5027 5754 -f 5754 5027 5079 -f 5754 5079 5851 -f 5851 5079 5075 -f 5851 5075 5046 -f 5443 5444 5884 -f 5443 5884 5921 -f 5921 5884 5438 -f 5889 5439 5888 -f 5888 5439 5440 -f 5442 5441 5440 -f 5440 5441 5882 -f 5440 5882 5888 -f 5441 5442 5920 -f 5441 5920 5438 -f 5438 5920 5921 -f 5443 5767 5444 -f 5444 5767 5445 -f 5444 5445 5843 -f 5843 5445 5766 -f 5843 5766 5844 -f 5844 5766 5446 -f 5844 5446 5845 -f 5845 5446 5447 -f 5845 5447 5448 -f 5448 5447 5769 -f 5448 5769 5450 -f 5449 6148 5769 -f 6007 6075 6000 -f 6075 6007 6068 -f 5769 6148 6144 -f 5769 6144 6143 -f 6001 5769 6003 -f 6003 5769 6143 -f 6003 6143 6150 -f 5769 6001 6000 -f 6000 6075 6073 -f 6000 6073 5769 -f 5769 6073 5450 -f 5450 6073 6070 -f 6070 5847 5450 -f 6070 5451 5847 -f 5847 5451 5848 -f 5452 5848 5451 -f 6007 6008 6068 -f 6068 6008 6067 -f 6020 4983 6067 -f 6020 6067 6008 -f 6149 5998 6005 -f 6149 6005 6150 -f 6150 6005 6003 -f 5998 6149 6152 -f 5771 6148 5770 -f 5770 6148 5449 -f 4937 4939 5751 -f 5751 4939 5816 -f 5751 5816 5453 -f 5453 5816 5454 -f 5454 5816 5455 -f 5454 5455 5456 -f 5456 5455 5817 -f 5456 5817 5746 -f 5746 5817 5457 -f 5746 5457 5747 -f 5747 5457 5459 -f 5747 5459 5458 -f 5458 5459 5814 -f 5458 5814 5460 -f 5460 5814 5813 -f 5460 5813 5461 -f 5461 5813 5462 -f 5461 5462 5750 -f 5750 5462 5464 -f 5750 5464 5463 -f 5463 5464 5465 -f 5463 5465 5466 -f 5466 5465 5467 -f 5466 5467 5468 -f 5468 5467 5469 -f 5468 5469 5744 -f 5744 5469 5809 -f 5487 5222 5477 -f 5477 5222 5506 -f 5477 5506 5474 -f 5474 5506 5470 -f 5474 5470 5471 -f 5471 5470 5500 -f 5471 5500 5503 -f 5471 5503 5472 -f 5472 5503 5498 -f 5472 5498 5527 -f 5527 5498 5504 -f 5473 5472 5527 -f 5471 5472 5475 -f 5483 5475 5473 -f 5474 5471 5476 -f 5476 5471 5478 -f 5478 5471 5475 -f 5478 5475 5493 -f 5477 5474 5476 -f 5476 5478 5489 -f 5489 5478 5493 -f 5519 5496 5520 -f 5520 5496 5479 -f 5479 5496 5480 -f 5479 5480 5481 -f 5481 5480 5483 -f 5481 5483 5482 -f 5482 5483 5484 -f 5484 5483 5485 -f 5485 5483 5473 -f 5485 5473 5486 -f 5486 5473 5526 -f 5526 5473 5527 -f 5487 5477 5226 -f 5226 5477 5225 -f 5225 5477 5488 -f 5488 5477 5476 -f 5488 5476 5490 -f 5490 5476 5489 -f 5490 5489 5235 -f 5235 5489 5491 -f 5491 5489 5492 -f 5492 5489 5493 -f 5492 5493 5231 -f 5231 5493 5494 -f 5494 5493 5496 -f 5494 5496 5495 -f 5228 5495 5496 -f 5480 5496 5493 -f 5519 5228 5496 -f 5480 5493 5483 -f 5483 5493 5475 -f 5473 5475 5472 -f 5497 5498 5499 -f 5503 5499 5498 -f 5500 5499 5503 -f 5501 5536 5499 -f 5501 5499 5502 -f 5505 5501 5502 -f 5510 5505 5509 -f 5509 5505 5502 -f 5509 5502 5508 -f 5508 5502 5507 -f 5507 5502 5470 -f 5506 5507 5470 -f 5470 5502 5500 -f 5500 5502 5499 -f 5510 5509 5533 -f 5506 5222 5507 -f 5507 5222 5215 -f 5507 5215 5218 -f 5507 5218 5508 -f 5508 5218 5511 -f 5508 5511 5512 -f 5508 5512 5509 -f 5509 5512 5513 -f 5509 5513 5514 -f 5509 5514 5515 -f 5509 5515 5533 -f 5533 5515 5516 -f 5533 5516 5213 -f 5517 5519 5518 -f 5518 5519 5520 -f 5518 5520 5521 -f 5521 5520 5479 -f 5521 5479 5522 -f 5522 5479 5481 -f 5522 5481 5523 -f 5523 5481 5482 -f 5523 5482 5524 -f 5524 5482 5484 -f 5524 5484 5575 -f 5575 5484 5485 -f 5575 5485 5525 -f 5525 5485 5486 -f 5525 5486 5572 -f 5572 5486 5526 -f 5572 5526 5571 -f 5571 5526 5527 -f 5528 5204 5603 -f 5206 5528 5553 -f 5530 5531 5529 -f 5213 5212 5532 -f 5532 5212 5211 -f 5211 5209 5546 -f 5546 5209 5530 -f 5206 5553 5531 -f 5213 5532 5533 -f 5533 5532 5540 -f 5533 5540 5510 -f 5510 5540 5534 -f 5510 5534 5505 -f 5505 5534 5535 -f 5505 5535 5501 -f 5501 5535 5542 -f 5501 5542 5536 -f 5536 5542 5537 -f 5536 5537 5499 -f 5499 5537 5545 -f 5499 5545 5497 -f 5497 5545 5538 -f 5497 5538 5498 -f 5498 5538 5246 -f 5498 5246 5504 -f 5211 5546 5532 -f 5532 5546 5539 -f 5532 5539 5540 -f 5540 5539 5541 -f 5540 5541 5534 -f 5534 5541 5547 -f 5534 5547 5535 -f 5535 5547 5548 -f 5535 5548 5542 -f 5542 5548 5550 -f 5542 5550 5537 -f 5537 5550 5543 -f 5537 5543 5545 -f 5545 5543 5544 -f 5545 5544 5538 -f 5538 5544 5247 -f 5538 5247 5246 -f 5530 5529 5546 -f 5546 5529 5555 -f 5546 5555 5539 -f 5539 5555 5556 -f 5539 5556 5541 -f 5541 5556 5557 -f 5541 5557 5547 -f 5547 5557 5558 -f 5547 5558 5548 -f 5548 5558 5549 -f 5548 5549 5550 -f 5550 5549 5561 -f 5550 5561 5543 -f 5543 5561 5551 -f 5543 5551 5544 -f 5544 5551 5552 -f 5544 5552 5247 -f 5531 5553 5529 -f 5529 5553 5554 -f 5529 5554 5555 -f 5555 5554 5564 -f 5555 5564 5556 -f 5556 5564 5566 -f 5556 5566 5557 -f 5557 5566 5568 -f 5557 5568 5558 -f 5558 5568 5559 -f 5558 5559 5549 -f 5549 5559 5570 -f 5549 5570 5561 -f 5561 5570 5560 -f 5561 5560 5551 -f 5551 5560 5248 -f 5551 5248 5552 -f 5528 5603 5553 -f 5553 5603 5562 -f 5553 5562 5554 -f 5554 5562 5563 -f 5554 5563 5564 -f 5564 5563 5565 -f 5564 5565 5566 -f 5566 5565 5567 -f 5566 5567 5568 -f 5568 5567 5602 -f 5568 5602 5559 -f 5559 5602 5569 -f 5559 5569 5570 -f 5570 5569 5601 -f 5570 5601 5560 -f 5560 5601 5597 -f 5560 5597 5248 -f 5571 5583 5572 -f 5525 5572 5574 -f 5574 5572 5583 -f 5575 5525 5574 -f 5573 5574 5583 -f 5524 5575 5574 -f 5523 5524 5576 -f 5576 5524 5574 -f 5576 5574 5592 -f 5607 5573 5583 -f 5522 5523 5576 -f 5590 5577 5605 -f 5605 5577 5573 -f 5605 5573 5607 -f 5521 5522 5578 -f 5578 5522 5576 -f 5578 5576 5579 -f 5579 5576 5592 -f 5579 5592 5580 -f 5580 5592 5577 -f 5580 5577 5590 -f 5581 5590 5582 -f 5582 5590 5605 -f 5518 5521 5578 -f 5517 5518 5584 -f 5584 5518 5578 -f 5584 5578 5585 -f 5585 5578 5586 -f 5586 5578 5579 -f 5586 5579 5587 -f 5587 5579 5240 -f 5240 5579 5580 -f 5240 5580 5588 -f 5588 5580 5589 -f 5589 5580 5242 -f 5242 5580 5590 -f 5242 5590 5244 -f 5244 5590 5591 -f 5245 5591 5581 -f 5581 5591 5590 -f 5577 5592 5573 -f 5573 5592 5574 -f 6242 6244 5595 -f 5562 6269 6268 -f 6245 6247 5604 -f 5595 6244 5604 -f 5600 6239 6237 -f 5600 6233 6239 -f 5596 5595 5604 -f 5606 5598 5594 -f 5594 5598 5599 -f 5594 5599 5595 -f 5595 5599 5593 -f 5595 5593 6242 -f 5606 5608 5598 -f 5599 6235 5593 -f 5598 5600 5599 -f 5599 5600 6237 -f 5599 6237 6235 -f 5608 5602 5598 -f 5601 5569 5608 -f 5608 5569 5602 -f 5602 5567 5598 -f 5598 5567 5565 -f 5598 5565 5600 -f 5600 5565 5563 -f 5600 5563 5562 -f 5600 5562 6268 -f 5600 6268 6233 -f 5562 5603 4951 -f 5562 4951 6269 -f 5603 5204 4951 -f 6247 5245 5604 -f 5604 5245 5581 -f 5604 5581 5596 -f 5596 5581 5582 -f 5596 5582 5595 -f 5595 5582 5594 -f 5594 5582 5605 -f 5594 5605 5606 -f 5606 5605 5607 -f 5606 5607 5608 -f 5608 5607 5583 -f 5608 5583 5601 -f 5601 5583 5597 -f 5597 5583 5571 -f 5341 5343 5630 -f 5630 5343 5639 -f 5630 5639 5624 -f 5624 5639 5640 -f 5624 5640 5617 -f 5617 5640 5641 -f 5617 5641 5609 -f 5609 5641 5642 -f 5609 5642 5613 -f 5613 5642 5643 -f 5613 5643 5614 -f 5614 5643 5644 -f 5614 5644 5612 -f 5612 5644 5645 -f 5612 5645 5610 -f 5610 5645 5646 -f 5610 5646 5611 -f 5611 5646 5635 -f 5619 5610 5697 -f 5614 5612 5615 -f 5615 5612 5610 -f 5615 5610 5619 -f 5613 5614 5615 -f 5609 5613 5617 -f 5617 5613 5615 -f 5615 5619 5622 -f 5616 5619 5618 -f 5617 5615 5622 -f 5624 5617 5620 -f 5620 5617 5622 -f 5628 5622 5623 -f 5623 5622 5621 -f 5623 5621 5694 -f 5616 5621 5622 -f 5616 5622 5619 -f 5694 5660 5623 -f 5622 5628 5620 -f 5624 5620 5630 -f 5660 5625 5353 -f 5660 5353 5623 -f 5623 5353 5626 -f 5623 5626 5350 -f 5623 5350 5628 -f 5628 5350 5627 -f 5628 5627 5348 -f 5628 5348 5629 -f 5628 5629 5620 -f 5620 5629 5347 -f 5620 5347 5345 -f 5620 5345 5630 -f 5630 5345 5341 -f 5635 5633 5706 -f 5632 5706 5633 -f 5655 5633 5645 -f 5631 5632 5633 -f 5657 5655 5645 -f 5704 5631 5634 -f 5634 5631 5633 -f 5634 5633 5655 -f 5703 5704 5634 -f 5634 5655 5658 -f 5636 5703 5649 -f 5649 5703 5634 -f 5659 5656 5657 -f 5701 5636 5649 -f 5652 5649 5634 -f 5652 5634 5658 -f 5652 5658 5637 -f 5648 5701 5649 -f 5638 5652 5637 -f 5638 5637 5656 -f 5343 5659 5639 -f 5639 5659 5640 -f 5640 5659 5641 -f 5641 5659 5657 -f 5641 5657 5642 -f 5642 5657 5643 -f 5643 5657 5645 -f 5643 5645 5644 -f 5645 5633 5646 -f 5646 5633 5635 -f 5699 5648 5647 -f 5647 5648 5649 -f 5647 5649 5328 -f 5328 5649 5330 -f 5330 5649 5652 -f 5330 5652 5650 -f 5650 5652 5651 -f 5651 5652 5332 -f 5332 5652 5638 -f 5332 5638 5653 -f 5653 5638 5333 -f 5333 5638 5335 -f 5335 5638 5656 -f 5335 5656 5336 -f 5654 5336 5656 -f 5337 5654 5656 -f 5339 5337 5659 -f 5659 5337 5656 -f 5656 5637 5657 -f 5657 5637 5658 -f 5657 5658 5655 -f 5343 5339 5659 -f 5356 5625 5660 -f 5358 5356 5662 -f 5361 5359 5686 -f 5366 5365 5663 -f 5663 5365 5364 -f 5364 5362 5661 -f 5661 5362 5361 -f 5358 5662 5359 -f 5366 5663 5718 -f 5718 5663 5664 -f 5718 5664 5721 -f 5721 5664 5665 -f 5721 5665 5717 -f 5717 5665 5666 -f 5717 5666 5720 -f 5720 5666 5673 -f 5720 5673 5716 -f 5716 5673 5674 -f 5716 5674 5715 -f 5715 5674 5667 -f 5715 5667 5668 -f 5668 5667 5669 -f 5668 5669 5719 -f 5719 5669 5670 -f 5364 5661 5663 -f 5663 5661 5677 -f 5663 5677 5664 -f 5664 5677 5671 -f 5664 5671 5665 -f 5665 5671 5678 -f 5665 5678 5666 -f 5666 5678 5672 -f 5666 5672 5673 -f 5673 5672 5680 -f 5673 5680 5674 -f 5674 5680 5681 -f 5674 5681 5667 -f 5667 5681 5684 -f 5667 5684 5669 -f 5669 5684 5675 -f 5669 5675 5670 -f 5361 5686 5661 -f 5661 5686 5676 -f 5661 5676 5677 -f 5677 5676 5688 -f 5677 5688 5671 -f 5671 5688 5689 -f 5671 5689 5678 -f 5678 5689 5691 -f 5678 5691 5672 -f 5672 5691 5679 -f 5672 5679 5680 -f 5680 5679 5682 -f 5680 5682 5681 -f 5681 5682 5683 -f 5681 5683 5684 -f 5684 5683 5398 -f 5684 5398 5675 -f 5359 5662 5686 -f 5686 5662 5685 -f 5686 5685 5676 -f 5676 5685 5687 -f 5676 5687 5688 -f 5688 5687 5695 -f 5688 5695 5689 -f 5689 5695 5690 -f 5689 5690 5691 -f 5691 5690 5696 -f 5691 5696 5679 -f 5679 5696 5692 -f 5679 5692 5682 -f 5682 5692 5693 -f 5682 5693 5683 -f 5683 5693 5698 -f 5683 5698 5398 -f 5356 5660 5662 -f 5662 5660 5694 -f 5662 5694 5685 -f 5685 5694 5621 -f 5685 5621 5687 -f 5687 5621 5616 -f 5687 5616 5695 -f 5695 5616 5618 -f 5695 5618 5690 -f 5690 5618 5619 -f 5690 5619 5696 -f 5696 5619 5697 -f 5696 5697 5692 -f 5692 5697 5610 -f 5692 5610 5693 -f 5693 5610 5611 -f 5693 5611 5698 -f 5699 5325 5648 -f 5648 5325 5700 -f 5648 5700 5701 -f 5701 5700 5730 -f 5701 5730 5636 -f 5636 5730 5702 -f 5636 5702 5703 -f 5703 5702 5726 -f 5703 5726 5704 -f 5704 5726 5727 -f 5704 5727 5631 -f 5631 5727 5705 -f 5631 5705 5632 -f 5632 5705 5707 -f 5632 5707 5706 -f 5706 5707 5729 -f 5706 5729 5635 -f 5635 5729 5722 -f 6033 5712 5713 -f 5708 5710 5711 -f 6022 5721 5714 -f 6037 5721 5710 -f 5708 5711 6035 -f 5712 6035 5711 -f 5709 5668 5719 -f 5742 5709 5724 -f 5720 5711 5721 -f 5721 5711 5710 -f 5713 5712 5711 -f 5713 5711 5720 -f 5713 5720 5715 -f 6034 6033 5713 -f 6030 6034 5742 -f 5742 6034 5713 -f 5741 6030 5742 -f 5742 5713 5709 -f 5721 6037 5714 -f 5718 5388 5366 -f 5716 5715 5720 -f 5717 5720 5721 -f 5718 5721 6022 -f 5718 6022 5388 -f 5709 5713 5715 -f 5709 5715 5668 -f 5728 5724 5723 -f 5742 5724 5725 -f 5725 5724 5728 -f 5725 5728 5731 -f 5730 5731 5702 -f 5702 5731 5726 -f 5726 5731 5728 -f 5726 5728 5727 -f 5727 5728 5705 -f 5705 5728 5723 -f 5705 5723 5707 -f 5707 5723 5729 -f 5729 5723 5722 -f 5735 5742 5725 -f 5735 5725 5734 -f 5734 5725 5733 -f 5733 5725 5731 -f 5733 5731 5732 -f 5730 5732 5731 -f 5730 5700 5732 -f 5742 5735 5741 -f 5700 5325 5732 -f 5732 5325 5322 -f 5732 5322 5736 -f 5732 5736 5733 -f 5733 5736 5737 -f 5733 5737 5738 -f 5733 5738 5734 -f 5734 5738 5739 -f 5734 5739 5318 -f 5734 5318 5735 -f 5735 5318 5316 -f 5735 5316 5740 -f 5735 5740 5741 -f 5741 5740 5396 -f 5724 5709 5719 -f 5724 5719 5723 -f 5723 5719 5722 -f 5743 5468 5744 -f 9521 5745 5200 -f 5200 5745 5456 -f 5456 5746 5200 -f 5200 5746 5747 -f 5200 5747 5748 -f 5747 5458 5748 -f 5748 5458 5460 -f 5748 5460 5749 -f 5460 5461 5749 -f 5749 5461 5750 -f 5749 5750 5743 -f 5743 5750 5463 -f 5743 5463 5466 -f 5743 5466 5468 -f 4989 5752 4937 -f 4937 5751 4989 -f 4989 5751 5453 -f 4989 5453 5745 -f 5745 5453 5454 -f 5745 5454 5456 -f 5764 5425 5752 -f 5752 5425 4937 -f 5756 2293 5753 -f 5753 5754 5756 -f 5756 5754 5437 -f 5756 5437 5436 -f 5436 5755 5756 -f 5756 5755 5757 -f 5756 5757 6160 -f 5758 5919 5417 -f 5806 5924 5758 -f 5806 5758 5417 -f 5806 5417 5761 -f 5761 5417 5759 -f 5761 5759 5420 -f 5761 5420 5760 -f 5761 5760 5402 -f 5761 5402 5763 -f 5763 5402 5422 -f 5763 5422 5762 -f 5763 5762 5424 -f 5763 5424 5764 -f 5764 5424 5425 -f 5769 5447 5765 -f 5765 5447 5446 -f 5766 5765 5446 -f 5445 5767 5922 -f 5802 5852 5922 -f 5922 5852 5445 -f 5445 5852 5765 -f 5445 5765 5766 -f 5765 5768 5769 -f 5769 5768 5449 -f 5449 5768 5770 -f 5770 5768 5771 -f 5771 5768 5756 -f 5771 5756 6160 -f 5805 5786 5772 -f 5772 5369 5805 -f 5805 5369 5389 -f 5389 5390 5805 -f 5793 5857 5773 -f 5773 5774 5793 -f 5793 5774 5351 -f 5793 5351 5939 -f 5939 5351 5352 -f 5939 5352 5775 -f 5776 5777 5778 -f 5778 5777 5939 -f 5778 5939 5354 -f 5354 5939 5775 -f 5776 5779 5777 -f 5777 5779 5780 -f 5777 5780 5781 -f 5781 5780 5355 -f 5781 5355 5782 -f 5782 5355 5357 -f 5782 5357 5783 -f 5783 5357 5360 -f 5783 5360 5944 -f 5944 5360 5784 -f 5944 5784 5945 -f 5945 5784 5363 -f 5945 5363 5785 -f 5785 5363 5367 -f 5785 5367 5786 -f 5786 5367 5368 -f 5786 5368 5772 -f 5214 5787 5936 -f 5936 5787 5791 -f 5791 5787 5788 -f 5791 5788 5789 -f 5789 5217 5791 -f 5791 5217 5790 -f 5791 5790 5793 -f 5221 5857 5792 -f 5792 5857 5793 -f 5792 5793 5216 -f 5216 5793 5790 -f 5794 5808 4947 -f 4947 4948 5794 -f 5794 4948 4949 -f 5794 4949 5795 -f 4949 4950 5795 -f 5795 4950 5203 -f 5795 5203 5929 -f 5929 5203 5205 -f 5929 5205 5930 -f 5930 5205 5796 -f 5930 5796 5797 -f 5797 5796 5207 -f 5797 5207 5798 -f 5798 5207 5208 -f 5798 5208 5934 -f 5934 5208 5210 -f 5934 5210 5799 -f 5799 5210 5800 -f 5799 5800 5936 -f 5936 5800 5801 -f 5936 5801 5214 -f 5852 5802 5803 -f 5803 5802 5947 -f 5803 5947 5804 -f 5804 5947 5805 -f 5804 5805 5390 -f 5924 5806 5926 -f 5926 5806 5807 -f 5926 5807 5794 -f 5794 5807 5808 -f 5809 9572 9573 -f 5809 9573 5810 -f 5810 9573 9574 -f 5810 9574 5197 -f 5197 9574 9581 -f 5197 9581 5198 -f 5195 5199 5811 -f 5811 5199 5198 -f 5811 5198 9581 -f 5809 5469 9572 -f 9572 5469 5467 -f 9572 5467 5812 -f 5467 5465 5812 -f 5812 5465 5464 -f 5812 5464 9569 -f 5464 5462 9569 -f 9569 5462 5813 -f 9569 5813 9533 -f 5813 5814 9533 -f 9533 5814 5459 -f 9533 5459 9565 -f 5459 5457 9565 -f 9565 5457 5817 -f 9565 5817 9563 -f 4939 5815 5816 -f 5816 5815 9564 -f 5816 9564 9563 -f 5816 9563 5455 -f 5455 9563 5817 -f 6279 5820 4939 -f 4939 5820 5815 -f 5400 5421 5860 -f 5860 5421 5419 -f 5860 5419 5859 -f 5418 5859 5419 -f 5416 5415 5887 -f 5821 5864 5887 -f 5887 5864 5416 -f 5416 5864 5859 -f 5416 5859 5418 -f 5860 9554 5400 -f 5400 9554 5818 -f 5818 9554 5408 -f 5408 9554 5819 -f 5819 9554 5820 -f 5819 5820 6279 -f 5864 5821 5822 -f 5822 5821 5913 -f 5822 5913 5865 -f 5865 5913 5823 -f 5865 5823 5867 -f 5867 5823 5911 -f 5867 5911 5824 -f 5867 5824 5869 -f 5869 5824 5825 -f 5869 5825 5909 -f 5869 5909 5826 -f 5826 5909 5827 -f 5826 5827 5828 -f 5826 5828 5829 -f 5829 5828 5905 -f 5829 5905 5830 -f 5829 5830 5872 -f 5872 5830 5831 -f 5872 5831 5873 -f 5873 5831 5904 -f 5873 5904 5874 -f 5874 5904 5903 -f 5874 5903 5875 -f 5875 5903 5902 -f 5875 5902 5877 -f 5877 5902 5900 -f 5877 5900 5832 -f 5832 5900 5898 -f 5832 5898 5833 -f 5833 5898 5835 -f 5833 5835 5834 -f 5834 5835 5896 -f 5834 5896 5836 -f 5836 5896 5837 -f 5836 5837 5838 -f 5838 5837 5840 -f 5838 5840 5839 -f 5839 5840 5841 -f 5839 5841 5881 -f 5881 5841 5842 -f 5881 5842 5862 -f 5862 5842 5891 -f 5862 5891 5861 -f 5861 5891 5890 -f 5883 5444 5843 -f 5861 5890 5883 -f 5861 5883 5843 -f 5861 5843 5846 -f 5846 5843 5844 -f 5846 5844 5845 -f 5846 5845 5448 -f 5846 5448 5450 -f 5846 5450 9543 -f 9543 5450 5847 -f 9543 5847 5848 -f 9543 5848 5452 -f 9543 5452 6089 -f 9543 6089 5849 -f 5849 6089 5434 -f 5434 5428 5849 -f 5849 5428 5850 -f 5849 5850 5435 -f 5435 5851 5849 -f 5849 5851 5426 -f 5849 5426 5032 -f 5852 5803 5765 -f 5765 5803 5853 -f 5392 5853 5803 -f 5392 5803 5854 -f 5854 5803 5804 -f 5855 5857 5220 -f 5220 5857 5221 -f 5855 5219 5858 -f 5858 5219 5856 -f 5856 5219 5346 -f 5855 5858 5857 -f 5857 5858 5349 -f 5857 5349 5773 -f 9556 5860 5859 -f 5863 5861 5846 -f 5880 5862 5863 -f 5863 5862 5861 -f 5859 5864 5822 -f 5859 5822 9556 -f 9556 5822 5865 -f 9556 5865 5866 -f 5865 5867 5866 -f 5866 5867 5868 -f 5867 5869 5868 -f 5868 5869 9524 -f 5869 5826 9524 -f 9524 5826 5870 -f 5826 5829 5870 -f 5870 5829 9552 -f 9552 5829 5872 -f 9552 5872 5871 -f 5872 5873 5871 -f 5871 5873 5874 -f 5871 5874 5876 -f 5874 5875 5876 -f 5876 5875 5877 -f 5876 5877 9541 -f 9541 5877 5832 -f 9541 5832 5878 -f 5878 5832 5833 -f 5878 5833 9538 -f 9538 5833 5834 -f 9538 5834 5836 -f 9538 5836 5879 -f 5836 5838 5879 -f 5879 5838 5839 -f 5879 5839 5880 -f 5880 5839 5881 -f 5880 5881 5862 -f 5890 5888 5882 -f 5882 5441 5890 -f 5890 5441 5438 -f 5890 5438 5884 -f 5444 5883 5884 -f 5884 5883 5890 -f 5821 5885 5413 -f 5821 5413 5411 -f 5821 5411 5914 -f 5885 5821 5887 -f 5885 5887 5886 -f 5886 5887 5410 -f 5410 5887 5415 -f 5888 5890 5889 -f 5889 5890 5892 -f 5892 5890 5891 -f 5892 5891 5893 -f 5893 5891 5842 -f 5893 5842 5894 -f 5894 5842 5841 -f 5894 5841 4995 -f 4995 5841 5840 -f 4995 5840 4997 -f 4997 5840 5837 -f 4997 5837 5895 -f 5895 5837 5896 -f 5895 5896 4998 -f 4998 5896 5835 -f 4998 5835 5897 -f 5897 5835 5898 -f 5897 5898 5899 -f 5899 5898 5900 -f 5899 5900 5000 -f 5000 5900 5902 -f 5000 5902 5901 -f 5901 5902 5903 -f 5901 5903 5002 -f 5002 5903 5904 -f 5002 5904 5004 -f 5004 5904 5831 -f 5004 5831 5005 -f 5005 5831 5830 -f 5005 5830 5006 -f 5006 5830 5905 -f 5006 5905 5906 -f 5906 5905 5828 -f 5906 5828 5007 -f 5007 5828 5827 -f 5007 5827 5907 -f 5907 5827 5909 -f 5907 5909 5908 -f 5908 5909 5825 -f 5908 5825 5009 -f 5009 5825 5824 -f 5009 5824 5910 -f 5910 5824 5911 -f 5910 5911 5011 -f 5011 5911 5823 -f 5011 5823 5912 -f 5912 5823 5913 -f 5912 5913 5914 -f 5914 5913 5821 -f 5915 4945 5807 -f 5807 4945 5916 -f 5807 5916 5808 -f 5806 5761 5917 -f 5915 5807 5917 -f 5917 5807 5806 -f 5758 5923 5918 -f 5918 5412 5758 -f 5758 5412 5414 -f 5758 5414 5409 -f 5919 5758 5409 -f 5802 5920 5442 -f 5802 5442 5440 -f 5802 5440 5439 -f 5920 5802 5922 -f 5920 5922 5921 -f 5921 5922 5443 -f 5443 5922 5767 -f 5923 5758 5012 -f 5012 5758 5924 -f 5012 5924 5925 -f 5925 5924 5926 -f 5925 5926 5927 -f 5927 5926 5794 -f 5927 5794 5010 -f 5010 5794 5795 -f 5010 5795 5928 -f 5928 5795 5929 -f 5928 5929 5931 -f 5931 5929 5930 -f 5931 5930 5008 -f 5008 5930 5797 -f 5008 5797 5932 -f 5932 5797 5798 -f 5932 5798 5933 -f 5933 5798 5934 -f 5933 5934 5935 -f 5935 5934 5799 -f 5935 5799 5937 -f 5937 5799 5936 -f 5937 5936 5003 -f 5003 5936 5791 -f 5003 5791 5001 -f 5001 5791 5793 -f 5001 5793 5938 -f 5938 5793 5939 -f 5938 5939 5940 -f 5940 5939 5777 -f 5940 5777 4999 -f 4999 5777 5781 -f 4999 5781 5941 -f 5941 5781 5782 -f 5941 5782 5942 -f 5942 5782 5783 -f 5942 5783 5943 -f 5943 5783 5944 -f 5943 5944 4996 -f 4996 5944 5945 -f 4996 5945 4994 -f 4994 5945 5785 -f 4994 5785 4993 -f 4993 5785 5786 -f 4993 5786 5946 -f 5946 5786 5805 -f 5946 5805 4992 -f 4992 5805 5947 -f 4992 5947 5439 -f 5439 5947 5802 -f 5985 5983 5981 -f 5981 5983 5989 -f 5981 5989 5948 -f 5948 5989 5988 -f 5948 5988 5990 -f 5948 5990 5993 -f 5377 5991 5949 -f 5949 5991 6004 -f 5949 6004 5950 -f 6004 5997 5950 -f 5950 5997 5951 -f 5950 5951 5952 -f 5995 5954 5996 -f 5954 5376 5996 -f 5996 5376 5951 -f 5951 5376 5952 -f 5953 5956 5957 -f 5953 5957 5954 -f 5953 5954 5995 -f 6015 5962 5374 -f 5374 5955 6015 -f 6015 5955 5956 -f 5956 5955 5957 -f 5960 5958 5959 -f 5960 5959 5961 -f 5960 5961 5962 -f 5962 5961 5374 -f 5963 5966 5397 -f 5397 5371 5963 -f 5963 5371 5958 -f 5958 5371 5959 -f 5967 5968 5964 -f 5964 5968 5965 -f 5964 5965 5966 -f 5966 5965 5397 -f 6013 5385 5967 -f 5967 5385 5968 -f 5971 5385 6013 -f 5972 5970 5969 -f 5969 5970 5971 -f 5971 5970 5385 -f 5972 5969 6017 -f 5972 6017 6018 -f 5972 6018 5384 -f 5384 6018 6019 -f 5384 6019 5973 -f 5973 6019 5974 -f 5973 5974 5976 -f 5976 5974 6009 -f 6010 5975 6009 -f 6009 5975 5976 -f 5978 5379 5977 -f 5977 5379 5975 -f 5977 5975 6010 -f 6006 5979 5978 -f 5978 5979 5379 -f 5982 5380 5999 -f 5999 5380 6006 -f 6006 5380 5980 -f 6006 5980 5979 -f 5981 5380 5982 -f 5981 5982 5985 -f 5985 5982 5984 -f 5987 5983 5984 -f 5984 5983 5985 -f 5986 5989 5987 -f 5987 5989 5983 -f 6002 5988 5986 -f 5986 5988 5989 -f 5994 5990 6002 -f 6002 5990 5988 -f 5991 5377 5948 -f 5991 5948 5992 -f 5992 5948 5993 -f 5992 5993 5994 -f 5994 5993 5990 -f 5995 5998 5953 -f 5951 5998 5996 -f 5996 5998 5995 -f 6004 6005 5997 -f 5997 6005 5998 -f 5997 5998 5951 -f 5999 6007 5982 -f 5982 6007 5984 -f 5984 6007 6000 -f 5984 6000 5987 -f 5987 6000 5986 -f 5986 6000 6001 -f 5986 6001 6002 -f 6002 6001 5994 -f 5994 6001 5992 -f 5992 6001 6003 -f 5992 6003 5991 -f 5991 6003 6004 -f 6004 6003 6005 -f 5978 6007 6006 -f 6006 6007 5999 -f 5977 6008 5978 -f 5978 6008 6007 -f 6010 6008 5977 -f 6020 6008 6009 -f 6009 6008 6010 -f 6020 6009 5974 -f 6016 6017 5969 -f 5958 5429 5963 -f 5963 5429 5432 -f 5963 5432 5966 -f 5966 5432 5431 -f 5966 5431 5964 -f 5964 5431 6011 -f 5964 6011 5967 -f 5967 6011 6012 -f 5967 6012 6013 -f 6013 6012 5971 -f 5971 6012 5969 -f 5969 6012 6016 -f 5960 6014 5958 -f 5958 6014 5429 -f 5962 6014 5960 -f 6015 6021 5962 -f 5962 6021 6014 -f 6017 6016 6018 -f 6018 6016 6020 -f 6018 6020 6019 -f 6019 6020 5974 -f 5953 5998 6021 -f 5953 6021 5956 -f 5956 6021 6015 -f 6058 6057 6022 -f 6022 6057 6023 -f 6022 6023 6024 -f 6024 6023 6060 -f 6024 6060 6065 -f 5714 6038 6069 -f 6083 6027 6025 -f 6025 6027 6026 -f 6025 6026 6054 -f 6084 6027 6083 -f 6028 5741 6084 -f 6084 5741 6027 -f 6029 5741 6028 -f 6087 6030 6029 -f 6029 6030 5741 -f 6031 6030 6087 -f 6032 6034 6088 -f 6088 6034 6031 -f 6031 6034 6030 -f 6080 5712 6079 -f 6079 5712 6032 -f 6032 5712 6033 -f 6032 6033 6034 -f 6078 6035 6080 -f 6080 6035 5712 -f 6077 5710 6036 -f 6036 5710 6078 -f 6078 5710 5708 -f 6078 5708 6035 -f 5714 6037 6038 -f 6038 6037 6077 -f 6077 6037 5710 -f 6062 6063 6039 -f 6039 6063 6076 -f 6039 6076 5381 -f 6076 6040 5381 -f 5381 6040 6066 -f 5381 6066 5382 -f 6044 6046 6041 -f 6046 6042 6041 -f 6041 6042 6066 -f 6066 6042 5382 -f 6043 6046 6044 -f 6045 6048 6050 -f 6050 5383 6045 -f 6045 5383 6043 -f 6043 5383 6046 -f 6047 6053 5386 -f 5386 6049 6047 -f 6047 6049 6048 -f 6048 6049 6050 -f 6052 6056 6051 -f 6051 5387 6052 -f 6052 5387 6053 -f 6053 5387 5386 -f 6026 6055 6054 -f 6054 6055 6056 -f 6056 6055 6051 -f 6022 5714 6069 -f 6022 6069 6071 -f 6072 6058 6071 -f 6071 6058 6022 -f 6059 6057 6072 -f 6072 6057 6058 -f 6061 6023 6059 -f 6059 6023 6057 -f 6074 6060 6061 -f 6061 6060 6023 -f 6063 6062 6024 -f 6063 6024 6064 -f 6064 6024 6065 -f 6064 6065 6074 -f 6074 6065 6060 -f 6044 6067 4983 -f 6044 4983 6043 -f 6066 6068 6041 -f 6041 6068 6067 -f 6041 6067 6044 -f 6076 6068 6040 -f 6040 6068 6066 -f 6038 6070 6069 -f 6069 6070 6071 -f 6071 6070 6072 -f 6072 6070 6059 -f 6059 6070 6073 -f 6059 6073 6061 -f 6061 6073 6074 -f 6074 6073 6075 -f 6074 6075 6064 -f 6064 6075 6063 -f 6063 6075 6068 -f 6063 6068 6076 -f 6036 5451 6077 -f 6077 5451 6070 -f 6077 6070 6038 -f 6078 5451 6036 -f 6080 5451 6078 -f 6089 5452 6079 -f 6079 5452 6080 -f 6080 5452 5451 -f 6089 6079 6032 -f 5427 6087 6029 -f 6052 6086 6056 -f 6056 6086 6081 -f 6056 6081 6054 -f 6054 6081 6025 -f 6025 6081 6082 -f 6025 6082 6083 -f 6083 6082 6084 -f 6084 6082 5427 -f 6084 5427 6028 -f 6028 5427 6029 -f 6053 6085 6052 -f 6052 6085 6086 -f 6047 5433 6053 -f 6053 5433 6085 -f 6048 5433 6047 -f 5427 5434 6087 -f 6087 5434 6031 -f 6031 5434 6088 -f 6088 5434 6032 -f 6032 5434 6089 -f 6043 4983 6045 -f 6045 4983 6048 -f 6048 4983 5433 -f 6135 6137 6090 -f 6090 6137 6138 -f 6090 6138 6140 -f 6090 6140 6139 -f 6090 6139 6092 -f 6092 6139 6091 -f 5391 6147 6095 -f 5391 6095 6096 -f 6095 6097 6096 -f 6096 6097 6099 -f 6096 6099 6098 -f 6094 6093 6142 -f 6093 6100 6142 -f 6142 6100 6099 -f 6099 6100 6098 -f 6101 6102 5393 -f 6101 5393 6093 -f 6101 6093 6094 -f 6157 6105 6106 -f 6157 6106 6102 -f 6102 6106 5393 -f 6103 6109 6110 -f 6110 6104 6103 -f 6103 6104 6105 -f 6105 6104 6106 -f 6107 6153 6114 -f 6114 6108 6107 -f 6107 6108 6109 -f 6109 6108 6110 -f 6111 5370 6112 -f 6112 5370 6113 -f 6112 6113 6153 -f 6153 6113 6114 -f 6116 6117 6111 -f 6111 6117 5370 -f 6115 6117 6116 -f 6119 5372 6118 -f 6118 5372 6115 -f 6115 5372 6117 -f 6119 6118 6158 -f 6119 6158 6120 -f 6119 6120 5373 -f 5373 6120 6159 -f 5373 6159 6121 -f 6121 6159 6122 -f 6121 6122 5375 -f 5375 6122 6123 -f 6126 6127 6123 -f 6123 6127 5375 -f 6151 6124 6125 -f 6125 6124 6127 -f 6125 6127 6126 -f 6128 6129 6151 -f 6151 6129 6124 -f 6132 5378 6130 -f 6130 5378 6128 -f 6128 5378 6131 -f 6128 6131 6129 -f 6090 5378 6132 -f 6090 6132 6135 -f 6135 6132 6133 -f 6134 6137 6133 -f 6133 6137 6135 -f 6136 6138 6134 -f 6134 6138 6137 -f 6145 6140 6136 -f 6136 6140 6138 -f 6141 6139 6145 -f 6145 6139 6140 -f 6147 5391 6092 -f 6147 6092 6146 -f 6146 6092 6091 -f 6146 6091 6141 -f 6141 6091 6139 -f 5771 6160 6094 -f 6094 6160 6101 -f 6099 5771 6142 -f 6142 5771 6094 -f 6095 6148 6097 -f 6097 6148 6099 -f 6099 6148 5771 -f 6130 6150 6132 -f 6132 6150 6133 -f 6133 6150 6143 -f 6133 6143 6134 -f 6134 6143 6136 -f 6136 6143 6144 -f 6136 6144 6145 -f 6145 6144 6141 -f 6141 6144 6146 -f 6146 6144 6148 -f 6146 6148 6147 -f 6147 6148 6095 -f 6151 6149 6128 -f 6128 6149 6150 -f 6128 6150 6130 -f 6125 6149 6151 -f 6126 6152 6125 -f 6125 6152 6149 -f 6123 6152 6126 -f 6152 6123 6122 -f 5430 6158 6118 -f 6109 6156 6107 -f 6107 6156 6153 -f 6153 6156 6154 -f 6153 6154 6112 -f 6112 6154 6111 -f 6111 6154 6155 -f 6111 6155 6116 -f 6116 6155 5430 -f 6116 5430 6115 -f 6115 5430 6118 -f 6103 6156 6109 -f 6105 6156 6103 -f 6157 5757 6105 -f 6105 5757 6156 -f 5430 4984 6158 -f 6158 4984 6120 -f 6120 4984 6159 -f 6159 4984 6122 -f 6122 4984 6152 -f 6101 6160 6102 -f 6102 6160 5757 -f 6102 5757 6157 -f 6196 6198 4965 -f 4965 6198 6161 -f 4965 6161 6200 -f 4965 6200 6162 -f 4965 6162 6163 -f 4965 6163 6201 -f 6164 6165 4953 -f 4953 6165 6210 -f 4953 6210 6166 -f 6210 6205 6166 -f 6166 6205 6167 -f 6166 6167 4955 -f 6168 4960 6203 -f 4960 4956 6203 -f 6203 4956 6167 -f 6167 4956 4955 -f 6219 6171 6172 -f 6219 6172 4960 -f 6219 4960 6168 -f 6221 6169 6175 -f 6175 6170 6221 -f 6221 6170 6171 -f 6171 6170 6172 -f 6173 6178 6174 -f 6173 6174 4962 -f 6173 4962 6169 -f 6169 4962 6175 -f 6177 6224 6180 -f 6180 6176 6177 -f 6177 6176 6178 -f 6178 6176 6174 -f 6182 4973 6226 -f 6226 4973 6179 -f 6226 6179 6224 -f 6224 6179 6180 -f 6181 4975 6182 -f 6182 4975 4973 -f 6228 4975 6181 -f 4971 4970 6183 -f 6183 4970 6228 -f 6228 4970 4975 -f 4971 6183 6184 -f 4971 6184 6230 -f 4971 6230 6185 -f 6185 6230 6187 -f 6185 6187 6186 -f 6186 6187 6188 -f 6186 6188 6190 -f 6190 6188 6189 -f 6218 6191 6189 -f 6189 6191 6190 -f 6216 6193 6217 -f 6217 6193 6191 -f 6217 6191 6218 -f 6212 6192 6216 -f 6216 6192 6193 -f 6194 4966 6214 -f 6214 4966 6212 -f 6212 4966 4967 -f 6212 4967 6192 -f 4965 4966 6194 -f 4965 6194 6196 -f 6196 6194 6206 -f 6195 6198 6206 -f 6206 6198 6196 -f 6197 6161 6195 -f 6195 6161 6198 -f 6199 6200 6197 -f 6197 6200 6161 -f 6202 6162 6199 -f 6199 6162 6200 -f 6165 6164 6201 -f 6165 6201 6209 -f 6209 6201 6163 -f 6209 6163 6202 -f 6202 6163 6162 -f 6168 6204 6219 -f 6167 5405 6203 -f 6203 5405 6204 -f 6203 6204 6168 -f 6210 5405 6205 -f 6205 5405 6167 -f 6214 6207 6194 -f 6194 6207 6206 -f 6206 6207 6195 -f 6195 6207 6208 -f 6195 6208 6197 -f 6197 6208 6199 -f 6199 6208 6211 -f 6199 6211 6202 -f 6202 6211 6209 -f 6209 6211 6165 -f 6165 6211 6210 -f 6210 6211 5405 -f 6216 6213 6212 -f 6212 6213 6214 -f 6214 6213 6215 -f 6214 6215 6207 -f 6217 6213 6216 -f 6218 5399 6217 -f 6217 5399 6213 -f 6189 5399 6218 -f 5399 6189 6231 -f 6231 6189 6188 -f 6219 6204 6220 -f 6219 6220 6171 -f 6171 6220 6221 -f 6221 6220 6169 -f 6169 6220 6173 -f 6173 6220 6222 -f 6173 6222 6178 -f 6178 6222 6177 -f 6177 6222 6223 -f 6177 6223 6224 -f 6224 6223 6225 -f 6224 6225 6226 -f 6226 6225 4940 -f 6226 4940 6182 -f 6182 4940 6227 -f 6182 6227 6181 -f 6181 6227 6229 -f 6181 6229 6228 -f 6228 6229 6183 -f 6183 6229 4942 -f 6183 4942 6184 -f 6184 4942 6230 -f 6230 4942 6187 -f 6187 4942 6231 -f 6187 6231 6188 -f 6259 6261 6232 -f 6232 6261 6263 -f 6232 6263 6269 -f 6269 6263 6267 -f 6269 6267 6265 -f 6234 6273 6233 -f 6233 6273 6238 -f 6233 6238 6239 -f 6236 6235 6237 -f 6236 6237 6238 -f 6238 6237 6239 -f 6236 6240 6235 -f 6235 6240 6241 -f 6235 6241 5593 -f 5593 6241 6278 -f 5593 6278 6242 -f 6242 6278 6243 -f 6242 6243 6244 -f 6280 6244 6243 -f 6246 5604 6280 -f 6280 5604 6244 -f 6282 6248 6245 -f 6282 6245 6246 -f 6246 6245 5604 -f 6283 6284 6249 -f 6249 6247 6283 -f 6283 6247 6248 -f 6248 6247 6245 -f 6286 4964 6285 -f 6285 4964 6249 -f 6285 6249 6284 -f 6288 4963 6286 -f 6286 4963 4964 -f 6289 4963 6288 -f 6250 4961 6290 -f 6290 4961 6289 -f 6289 4961 4963 -f 6250 6290 6291 -f 6250 6291 6251 -f 6250 6251 4959 -f 4959 6251 6293 -f 4959 6293 6252 -f 6252 6293 6294 -f 6252 6294 4958 -f 4958 6294 6277 -f 6253 4957 6277 -f 6277 4957 4958 -f 6275 4952 6276 -f 6276 4952 4957 -f 6276 4957 6253 -f 6256 4954 6275 -f 6275 4954 4952 -f 6258 6255 6254 -f 6254 6255 6256 -f 6256 6255 6257 -f 6256 6257 4954 -f 6232 6255 6258 -f 6232 6258 6259 -f 6259 6258 6271 -f 6260 6261 6271 -f 6271 6261 6259 -f 6262 6263 6260 -f 6260 6263 6261 -f 6266 6267 6262 -f 6262 6267 6263 -f 6264 6265 6266 -f 6266 6265 6267 -f 6233 6268 6234 -f 6234 6268 6269 -f 6234 6269 6272 -f 6272 6269 6264 -f 6264 6269 6265 -f 6241 6279 6278 -f 6236 5407 6240 -f 6240 5407 6241 -f 6241 5407 6279 -f 6273 5407 6238 -f 6238 5407 6236 -f 6254 6270 6258 -f 6258 6270 5401 -f 6258 5401 6271 -f 6271 5401 6260 -f 6260 5401 6262 -f 6262 5401 6274 -f 6262 6274 6266 -f 6266 6274 6264 -f 6264 6274 6272 -f 6272 6274 6234 -f 6234 6274 6273 -f 6273 6274 5407 -f 6275 5404 6256 -f 6256 5404 6254 -f 6254 5404 6270 -f 6276 5404 6275 -f 6253 5406 6276 -f 6276 5406 5404 -f 6277 5406 6253 -f 5406 6277 4943 -f 4943 6277 6294 -f 6278 6279 6243 -f 6243 6279 6281 -f 6243 6281 6280 -f 6280 6281 6246 -f 6246 6281 6282 -f 6282 6281 4936 -f 6282 4936 6248 -f 6248 4936 6283 -f 6283 4936 6284 -f 6284 4936 4938 -f 6284 4938 6285 -f 6285 4938 6286 -f 6286 4938 6288 -f 6288 4938 6287 -f 6288 6287 6289 -f 6289 6287 6290 -f 6290 6287 4941 -f 6290 4941 6291 -f 6291 4941 6292 -f 6291 6292 6251 -f 6251 6292 6293 -f 6293 6292 4943 -f 6293 4943 6294 -f 6328 6330 6295 -f 6295 6330 6331 -f 6295 6331 6336 -f 6295 6336 6296 -f 6296 6336 6335 -f 6296 6335 6338 -f 6337 6298 6297 -f 6297 6298 6299 -f 6297 6299 6300 -f 6299 6342 6300 -f 6300 6342 6301 -f 6300 6301 4968 -f 6341 6303 6302 -f 6303 4969 6302 -f 6302 4969 6301 -f 6301 4969 4968 -f 6339 6307 6308 -f 6339 6308 6303 -f 6339 6303 6341 -f 6353 6304 6305 -f 6305 6306 6353 -f 6353 6306 6307 -f 6307 6306 6308 -f 6354 6310 4972 -f 6354 4972 4974 -f 6354 4974 6304 -f 6304 4974 6305 -f 6356 6313 6314 -f 6314 6309 6356 -f 6356 6309 6310 -f 6310 6309 4972 -f 6315 4980 6311 -f 6311 4980 6312 -f 6311 6312 6313 -f 6313 6312 6314 -f 6316 4980 6315 -f 6359 6317 6316 -f 6316 6317 4980 -f 4982 4981 6318 -f 6318 4981 6359 -f 6359 4981 6317 -f 4982 6318 6319 -f 4982 6319 6361 -f 4982 6361 4977 -f 4977 6361 6362 -f 4977 6362 6352 -f 4977 6352 6320 -f 6320 6352 6321 -f 6320 6321 6322 -f 6350 6322 6321 -f 6349 6323 6351 -f 6351 6323 6350 -f 6350 6323 6322 -f 6324 6325 6349 -f 6349 6325 6323 -f 6327 6326 6344 -f 6344 6326 6324 -f 6324 6326 4946 -f 6324 4946 6325 -f 6295 6326 6327 -f 6295 6327 6328 -f 6328 6327 6329 -f 6332 6330 6329 -f 6329 6330 6328 -f 6333 6331 6332 -f 6332 6331 6330 -f 6346 6336 6333 -f 6333 6336 6331 -f 6334 6335 6346 -f 6346 6335 6336 -f 6298 6337 6296 -f 6298 6296 6347 -f 6347 6296 6338 -f 6347 6338 6334 -f 6334 6338 6335 -f 6341 6340 6339 -f 6301 6343 6302 -f 6302 6343 6340 -f 6302 6340 6341 -f 6299 6343 6342 -f 6342 6343 6301 -f 6344 6345 6327 -f 6327 6345 6329 -f 6329 6345 6332 -f 6332 6345 5403 -f 6332 5403 6333 -f 6333 5403 6346 -f 6346 5403 6348 -f 6346 6348 6334 -f 6334 6348 6347 -f 6347 6348 6298 -f 6298 6348 6299 -f 6299 6348 6343 -f 6349 6345 6324 -f 6324 6345 6344 -f 6351 5423 6349 -f 6349 5423 6345 -f 6350 5423 6351 -f 5425 5423 6321 -f 6321 5423 6350 -f 5425 6321 6352 -f 6339 6340 4944 -f 6339 4944 6307 -f 6307 4944 6353 -f 6353 4944 6304 -f 6304 4944 6354 -f 6354 4944 6355 -f 6354 6355 6310 -f 6310 6355 6357 -f 6310 6357 6356 -f 6356 6357 6313 -f 6313 6357 6358 -f 6313 6358 6311 -f 6311 6358 6315 -f 6315 6358 6316 -f 6316 6358 6359 -f 6359 6358 6360 -f 6359 6360 6318 -f 6318 6360 6319 -f 6319 6360 6363 -f 6319 6363 6361 -f 6361 6363 6362 -f 6362 6363 6352 -f 6352 6363 5425 -f 6365 6381 6373 -f 5342 6364 6373 -f 6370 6367 6373 -f 6373 6367 6365 -f 6369 6368 6366 -f 6369 6366 6370 -f 6370 6366 6367 -f 6369 6370 6375 -f 6375 6370 6373 -f 4985 6369 6375 -f 6371 6374 6375 -f 5340 5344 6375 -f 6375 5344 6371 -f 6373 6372 6375 -f 6375 6372 5340 -f 6373 6364 6372 -f 4985 6375 6374 -f 5224 6380 6384 -f 6383 6377 6376 -f 6383 6376 6382 -f 6382 6376 5227 -f 6383 6379 6378 -f 6383 6378 6377 -f 6379 6383 6384 -f 6379 6384 5223 -f 6384 6380 5223 -f 5224 6384 6381 -f 6381 6384 6373 -f 2300 6382 5227 -f 6389 6383 6382 -f 6389 6382 6385 -f 6385 6386 6389 -f 6388 6389 6386 -f 6387 6389 6388 -f 5342 6373 6389 -f 6387 5342 6389 -f 6383 6389 6384 -f 6384 6389 6373 -f 6407 6412 6392 -f 6449 6412 6407 -f 6407 6391 6393 -f 6390 6391 6407 -f 6392 6390 6407 -f 6407 6419 6420 -f 6394 6419 6407 -f 6393 6394 6407 -f 6407 6423 6424 -f 6422 6423 6407 -f 6420 6422 6407 -f 6407 6427 6428 -f 6395 6427 6407 -f 6424 6395 6407 -f 6407 6397 6396 -f 6430 6397 6407 -f 6428 6430 6407 -f 6407 6432 6398 -f 6399 6432 6407 -f 6396 6399 6407 -f 6407 6436 6437 -f 6400 6436 6407 -f 6398 6400 6407 -f 6407 6402 6401 -f 6403 6402 6407 -f 6437 6403 6407 -f 6407 6442 6404 -f 6405 6442 6407 -f 6401 6405 6407 -f 6407 6406 6410 -f 6443 6406 6407 -f 6404 6443 6407 -f 6407 6409 6447 -f 6408 6409 6407 -f 6410 6408 6407 -f 6447 6449 6407 -f 6449 6411 6412 -f 6412 6411 6413 -f 6412 6413 6392 -f 6392 6413 6414 -f 6392 6414 6390 -f 6390 6414 6415 -f 6390 6415 6391 -f 6391 6415 6416 -f 6391 6416 6393 -f 6393 6416 6417 -f 6393 6417 6394 -f 6394 6417 6418 -f 6394 6418 6419 -f 6419 6418 6421 -f 6419 6421 6420 -f 6420 6421 5181 -f 6420 5181 6422 -f 6422 5181 5184 -f 6422 5184 6423 -f 6423 5184 5183 -f 6423 5183 6424 -f 6424 5183 6425 -f 6424 6425 6395 -f 6395 6425 6426 -f 6395 6426 6427 -f 6427 6426 5182 -f 6427 5182 6428 -f 6428 5182 5173 -f 6428 5173 6430 -f 6430 5173 6429 -f 6430 6429 6397 -f 6397 6429 5171 -f 6397 5171 6396 -f 6396 5171 5170 -f 6396 5170 6399 -f 6399 5170 5168 -f 6399 5168 6432 -f 6432 5168 6431 -f 6432 6431 6398 -f 6398 6431 6433 -f 6398 6433 6400 -f 6400 6433 6434 -f 6400 6434 6436 -f 6436 6434 6435 -f 6436 6435 6437 -f 6437 6435 6438 -f 6437 6438 6403 -f 6403 6438 5172 -f 6403 5172 6402 -f 6402 5172 6439 -f 6402 6439 6401 -f 6401 6439 6440 -f 6401 6440 6405 -f 6405 6440 6441 -f 6405 6441 6442 -f 6442 6441 5180 -f 6442 5180 6404 -f 6404 5180 5178 -f 6404 5178 6443 -f 6443 5178 6444 -f 6443 6444 6406 -f 6406 6444 5176 -f 6406 5176 6410 -f 6410 5176 5175 -f 6410 5175 6408 -f 6408 5175 6445 -f 6408 6445 6409 -f 6409 6445 6446 -f 6409 6446 6447 -f 6447 6446 6448 -f 6447 6448 6449 -f 6449 6448 6411 -f 6456 6450 6482 -f 6480 6450 6456 -f 6456 6484 6486 -f 6483 6484 6456 -f 6482 6483 6456 -f 6456 6488 6451 -f 6452 6488 6456 -f 6486 6452 6456 -f 6456 6492 6454 -f 6490 6492 6456 -f 6451 6490 6456 -f 6456 6496 6453 -f 6495 6496 6456 -f 6454 6495 6456 -f 6456 6500 6502 -f 6455 6500 6456 -f 6453 6455 6456 -f 6456 6457 6458 -f 6504 6457 6456 -f 6502 6504 6456 -f 6456 6466 6467 -f 6464 6466 6456 -f 6458 6464 6456 -f 6456 6470 6459 -f 6460 6470 6456 -f 6467 6460 6456 -f 6456 6472 6473 -f 6461 6472 6456 -f 6459 6461 6456 -f 6456 6475 6462 -f 6474 6475 6456 -f 6473 6474 6456 -f 6456 6477 6479 -f 6463 6477 6456 -f 6462 6463 6456 -f 6479 6480 6456 -f 6464 6465 6466 -f 6466 6465 6467 -f 6467 6465 6468 -f 6467 6468 6460 -f 6460 6468 6469 -f 6460 6469 6470 -f 6470 6469 5069 -f 6470 5069 6459 -f 6459 5069 6471 -f 6459 6471 6461 -f 6461 6471 5068 -f 6461 5068 6472 -f 6472 5068 5067 -f 6472 5067 6473 -f 6473 5067 5066 -f 6473 5066 6474 -f 6474 5066 6476 -f 6474 6476 6475 -f 6475 6476 5065 -f 6475 5065 6462 -f 6462 5065 5063 -f 6462 5063 6463 -f 6463 5063 5062 -f 6463 5062 6477 -f 6477 5062 6478 -f 6477 6478 6479 -f 6479 6478 6481 -f 6479 6481 6480 -f 6480 6481 5056 -f 6480 5056 6450 -f 6450 5056 5055 -f 6450 5055 6482 -f 6482 5055 5054 -f 6482 5054 6483 -f 6483 5054 5053 -f 6483 5053 6484 -f 6484 5053 6485 -f 6484 6485 6486 -f 6486 6485 5060 -f 6486 5060 6452 -f 6452 5060 6487 -f 6452 6487 6488 -f 6488 6487 5061 -f 6488 5061 6451 -f 6451 5061 6489 -f 6451 6489 6490 -f 6490 6489 6491 -f 6490 6491 6492 -f 6492 6491 6493 -f 6492 6493 6454 -f 6454 6493 6494 -f 6454 6494 6495 -f 6495 6494 6497 -f 6495 6497 6496 -f 6496 6497 5058 -f 6496 5058 6453 -f 6453 5058 6498 -f 6453 6498 6455 -f 6455 6498 6499 -f 6455 6499 6500 -f 6500 6499 6501 -f 6500 6501 6502 -f 6502 6501 6503 -f 6502 6503 6504 -f 6504 6503 6505 -f 6504 6505 6457 -f 6457 6505 5051 -f 6457 5051 6458 -f 6458 5051 6506 -f 6458 6506 6464 -f 6464 6506 6465 -f 6521 6508 6510 -f 6507 6508 6521 -f 6521 6509 6512 -f 6529 6509 6521 -f 6510 6529 6521 -f 6521 6530 6532 -f 6511 6530 6521 -f 6512 6511 6521 -f 6521 6513 6514 -f 6515 6513 6521 -f 6532 6515 6521 -f 6521 6516 6518 -f 6535 6516 6521 -f 6514 6535 6521 -f 6521 6517 6522 -f 6519 6517 6521 -f 6518 6519 6521 -f 6521 6541 6542 -f 6520 6541 6521 -f 6522 6520 6521 -f 6521 6546 6523 -f 6544 6546 6521 -f 6542 6544 6521 -f 6521 6550 6552 -f 6549 6550 6521 -f 6523 6549 6521 -f 6521 6555 6525 -f 6553 6555 6521 -f 6552 6553 6521 -f 6521 6559 6560 -f 6524 6559 6521 -f 6525 6524 6521 -f 6521 6564 6565 -f 6562 6564 6521 -f 6560 6562 6521 -f 6565 6507 6521 -f 6507 6526 6508 -f 6508 6526 6527 -f 6508 6527 6510 -f 6510 6527 6528 -f 6510 6528 6529 -f 6529 6528 5132 -f 6529 5132 6509 -f 6509 5132 5140 -f 6509 5140 6512 -f 6512 5140 5139 -f 6512 5139 6511 -f 6511 5139 6531 -f 6511 6531 6530 -f 6530 6531 5138 -f 6530 5138 6532 -f 6532 5138 5137 -f 6532 5137 6515 -f 6515 5137 5142 -f 6515 5142 6513 -f 6513 5142 6533 -f 6513 6533 6514 -f 6514 6533 6534 -f 6514 6534 6535 -f 6535 6534 6536 -f 6535 6536 6516 -f 6516 6536 6537 -f 6516 6537 6518 -f 6518 6537 5136 -f 6518 5136 6519 -f 6519 5136 6538 -f 6519 6538 6517 -f 6517 6538 5135 -f 6517 5135 6522 -f 6522 5135 6539 -f 6522 6539 6520 -f 6520 6539 6540 -f 6520 6540 6541 -f 6541 6540 5124 -f 6541 5124 6542 -f 6542 5124 6543 -f 6542 6543 6544 -f 6544 6543 6545 -f 6544 6545 6546 -f 6546 6545 6547 -f 6546 6547 6523 -f 6523 6547 6548 -f 6523 6548 6549 -f 6549 6548 5131 -f 6549 5131 6550 -f 6550 5131 5134 -f 6550 5134 6552 -f 6552 5134 6551 -f 6552 6551 6553 -f 6553 6551 6554 -f 6553 6554 6555 -f 6555 6554 6556 -f 6555 6556 6525 -f 6525 6556 6557 -f 6525 6557 6524 -f 6524 6557 6558 -f 6524 6558 6559 -f 6559 6558 5130 -f 6559 5130 6560 -f 6560 5130 6561 -f 6560 6561 6562 -f 6562 6561 6563 -f 6562 6563 6564 -f 6564 6563 5128 -f 6564 5128 6565 -f 6565 5128 5133 -f 6565 5133 6507 -f 6507 5133 6526 -f 6576 6566 6596 -f 6594 6566 6576 -f 6576 6600 6567 -f 6597 6600 6576 -f 6596 6597 6576 -f 6576 6603 6605 -f 6602 6603 6576 -f 6567 6602 6576 -f 6576 6568 6570 -f 6569 6568 6576 -f 6605 6569 6576 -f 6576 6611 6612 -f 6610 6611 6576 -f 6570 6610 6576 -f 6576 6571 6615 -f 6613 6571 6576 -f 6612 6613 6576 -f 6576 6619 6620 -f 6618 6619 6576 -f 6615 6618 6576 -f 6576 6578 6579 -f 6572 6578 6576 -f 6620 6572 6576 -f 6576 6580 6573 -f 6574 6580 6576 -f 6579 6574 6576 -f 6576 6584 6585 -f 6581 6584 6576 -f 6573 6581 6576 -f 6576 6586 6589 -f 6575 6586 6576 -f 6585 6575 6576 -f 6576 6577 6592 -f 6591 6577 6576 -f 6589 6591 6576 -f 6592 6594 6576 -f 6572 5080 6578 -f 6578 5080 6579 -f 6579 5080 5084 -f 6579 5084 6574 -f 6574 5084 5083 -f 6574 5083 6580 -f 6580 5083 5082 -f 6580 5082 6573 -f 6573 5082 5089 -f 6573 5089 6581 -f 6581 5089 6582 -f 6581 6582 6584 -f 6584 6582 6583 -f 6584 6583 6585 -f 6585 6583 5088 -f 6585 5088 6575 -f 6575 5088 6587 -f 6575 6587 6586 -f 6586 6587 6588 -f 6586 6588 6589 -f 6589 6588 6590 -f 6589 6590 6591 -f 6591 6590 5086 -f 6591 5086 6577 -f 6577 5086 5085 -f 6577 5085 6592 -f 6592 5085 6593 -f 6592 6593 6594 -f 6594 6593 6595 -f 6594 6595 6566 -f 6566 6595 5070 -f 6566 5070 6596 -f 6596 5070 6598 -f 6596 6598 6597 -f 6597 6598 6599 -f 6597 6599 6600 -f 6600 6599 6601 -f 6600 6601 6567 -f 6567 6601 5077 -f 6567 5077 6602 -f 6602 5077 5078 -f 6602 5078 6603 -f 6603 5078 6604 -f 6603 6604 6605 -f 6605 6604 6606 -f 6605 6606 6569 -f 6569 6606 6607 -f 6569 6607 6568 -f 6568 6607 6608 -f 6568 6608 6570 -f 6570 6608 6609 -f 6570 6609 6610 -f 6610 6609 5076 -f 6610 5076 6611 -f 6611 5076 5074 -f 6611 5074 6612 -f 6612 5074 5073 -f 6612 5073 6613 -f 6613 5073 6614 -f 6613 6614 6571 -f 6571 6614 6616 -f 6571 6616 6615 -f 6615 6616 5072 -f 6615 5072 6618 -f 6618 5072 6617 -f 6618 6617 6619 -f 6619 6617 6621 -f 6619 6621 6620 -f 6620 6621 5071 -f 6620 5071 6572 -f 6572 5071 5081 -f 6572 5081 5080 -f 6626 6622 6627 -f 6623 6622 6626 -f 6626 6625 6657 -f 6624 6625 6626 -f 6627 6624 6626 -f 6626 6628 6661 -f 6629 6628 6626 -f 6657 6629 6626 -f 6626 6630 6666 -f 6664 6630 6626 -f 6661 6664 6626 -f 6626 6669 6632 -f 6631 6669 6626 -f 6666 6631 6626 -f 6626 6671 6673 -f 6670 6671 6626 -f 6632 6670 6626 -f 6626 6675 6676 -f 6674 6675 6626 -f 6673 6674 6626 -f 6626 6633 6641 -f 6634 6633 6626 -f 6676 6634 6626 -f 6626 6635 6646 -f 6644 6635 6626 -f 6641 6644 6626 -f 6626 6637 6639 -f 6636 6637 6626 -f 6646 6636 6626 -f 6626 6650 6640 -f 6638 6650 6626 -f 6639 6638 6626 -f 6626 6653 6655 -f 6651 6653 6626 -f 6640 6651 6626 -f 6655 6623 6626 -f 6634 6678 6633 -f 6633 6678 6641 -f 6641 6678 6642 -f 6641 6642 6644 -f 6644 6642 6643 -f 6644 6643 6635 -f 6635 6643 6645 -f 6635 6645 6646 -f 6646 6645 6647 -f 6646 6647 6636 -f 6636 6647 5107 -f 6636 5107 6637 -f 6637 5107 6648 -f 6637 6648 6639 -f 6639 6648 5106 -f 6639 5106 6638 -f 6638 5106 6649 -f 6638 6649 6650 -f 6650 6649 5104 -f 6650 5104 6640 -f 6640 5104 6652 -f 6640 6652 6651 -f 6651 6652 5143 -f 6651 5143 6653 -f 6653 5143 6654 -f 6653 6654 6655 -f 6655 6654 6656 -f 6655 6656 6623 -f 6623 6656 5092 -f 6623 5092 6622 -f 6622 5092 5095 -f 6622 5095 6627 -f 6627 5095 5094 -f 6627 5094 6624 -f 6624 5094 5093 -f 6624 5093 6625 -f 6625 5093 5102 -f 6625 5102 6657 -f 6657 5102 6658 -f 6657 6658 6629 -f 6629 6658 6659 -f 6629 6659 6628 -f 6628 6659 6660 -f 6628 6660 6661 -f 6661 6660 6662 -f 6661 6662 6664 -f 6664 6662 6663 -f 6664 6663 6630 -f 6630 6663 6665 -f 6630 6665 6666 -f 6666 6665 6667 -f 6666 6667 6631 -f 6631 6667 5098 -f 6631 5098 6669 -f 6669 5098 6668 -f 6669 6668 6632 -f 6632 6668 5097 -f 6632 5097 6670 -f 6670 5097 5096 -f 6670 5096 6671 -f 6671 5096 6672 -f 6671 6672 6673 -f 6673 6672 5101 -f 6673 5101 6674 -f 6674 5101 5100 -f 6674 5100 6675 -f 6675 5100 5099 -f 6675 5099 6676 -f 6676 5099 6677 -f 6676 6677 6634 -f 6634 6677 5090 -f 6634 5090 6678 -f 6687 6679 6680 -f 6681 6679 6687 -f 6687 6682 6704 -f 6701 6682 6687 -f 6680 6701 6687 -f 6687 6683 6684 -f 6705 6683 6687 -f 6704 6705 6687 -f 6687 6686 6685 -f 6688 6686 6687 -f 6684 6688 6687 -f 6687 6690 6710 -f 6689 6690 6687 -f 6685 6689 6687 -f 6687 6714 6692 -f 6712 6714 6687 -f 6710 6712 6687 -f 6687 6691 6718 -f 6715 6691 6687 -f 6692 6715 6687 -f 6687 6693 6695 -f 6719 6693 6687 -f 6718 6719 6687 -f 6687 6721 6722 -f 6694 6721 6687 -f 6695 6694 6687 -f 6687 6725 6696 -f 6697 6725 6687 -f 6722 6697 6687 -f 6687 6728 6698 -f 6727 6728 6687 -f 6696 6727 6687 -f 6687 6730 6699 -f 6729 6730 6687 -f 6698 6729 6687 -f 6699 6681 6687 -f 6681 6700 6679 -f 6679 6700 5036 -f 6679 5036 6680 -f 6680 5036 5037 -f 6680 5037 6701 -f 6701 5037 6702 -f 6701 6702 6682 -f 6682 6702 6703 -f 6682 6703 6704 -f 6704 6703 5035 -f 6704 5035 6705 -f 6705 5035 6706 -f 6705 6706 6683 -f 6683 6706 5049 -f 6683 5049 6684 -f 6684 5049 6707 -f 6684 6707 6688 -f 6688 6707 5048 -f 6688 5048 6686 -f 6686 5048 6708 -f 6686 6708 6685 -f 6685 6708 5034 -f 6685 5034 6689 -f 6689 5034 5033 -f 6689 5033 6690 -f 6690 5033 6709 -f 6690 6709 6710 -f 6710 6709 6711 -f 6710 6711 6712 -f 6712 6711 6713 -f 6712 6713 6714 -f 6714 6713 5031 -f 6714 5031 6692 -f 6692 5031 6716 -f 6692 6716 6715 -f 6715 6716 5030 -f 6715 5030 6691 -f 6691 5030 6717 -f 6691 6717 6718 -f 6718 6717 5047 -f 6718 5047 6719 -f 6719 5047 6720 -f 6719 6720 6693 -f 6693 6720 5045 -f 6693 5045 6695 -f 6695 5045 5044 -f 6695 5044 6694 -f 6694 5044 5043 -f 6694 5043 6721 -f 6721 5043 6723 -f 6721 6723 6722 -f 6722 6723 5145 -f 6722 5145 6697 -f 6697 5145 6724 -f 6697 6724 6725 -f 6725 6724 5050 -f 6725 5050 6696 -f 6696 5050 6726 -f 6696 6726 6727 -f 6727 6726 5042 -f 6727 5042 6728 -f 6728 5042 5041 -f 6728 5041 6698 -f 6698 5041 5040 -f 6698 5040 6729 -f 6729 5040 5039 -f 6729 5039 6730 -f 6730 5039 6731 -f 6730 6731 6699 -f 6699 6731 5038 -f 6699 5038 6681 -f 6681 5038 6700 -f 6749 6732 6736 -f 6753 6732 6749 -f 6749 6735 6733 -f 6734 6735 6749 -f 6736 6734 6749 -f 6749 6737 6761 -f 6759 6737 6749 -f 6733 6759 6749 -f 6749 6764 6738 -f 6763 6764 6749 -f 6761 6763 6749 -f 6749 6767 6741 -f 6766 6767 6749 -f 6738 6766 6749 -f 6749 6740 6739 -f 6770 6740 6749 -f 6741 6770 6749 -f 6749 6742 6743 -f 6774 6742 6749 -f 6739 6774 6749 -f 6749 6745 6776 -f 6744 6745 6749 -f 6743 6744 6749 -f 6749 6778 6746 -f 6777 6778 6749 -f 6776 6777 6749 -f 6749 6747 6782 -f 6748 6747 6749 -f 6746 6748 6749 -f 6749 6750 6786 -f 6784 6750 6749 -f 6782 6784 6749 -f 6749 6751 6752 -f 6788 6751 6749 -f 6786 6788 6749 -f 6752 6753 6749 -f 6753 6754 6732 -f 6732 6754 6755 -f 6732 6755 6736 -f 6736 6755 6756 -f 6736 6756 6734 -f 6734 6756 5015 -f 6734 5015 6735 -f 6735 5015 6757 -f 6735 6757 6733 -f 6733 6757 6758 -f 6733 6758 6759 -f 6759 6758 6760 -f 6759 6760 6737 -f 6737 6760 5024 -f 6737 5024 6761 -f 6761 5024 6762 -f 6761 6762 6763 -f 6763 6762 5028 -f 6763 5028 6764 -f 6764 5028 6765 -f 6764 6765 6738 -f 6738 6765 5026 -f 6738 5026 6766 -f 6766 5026 5017 -f 6766 5017 6767 -f 6767 5017 6768 -f 6767 6768 6741 -f 6741 6768 6769 -f 6741 6769 6770 -f 6770 6769 6771 -f 6770 6771 6740 -f 6740 6771 6772 -f 6740 6772 6739 -f 6739 6772 6773 -f 6739 6773 6774 -f 6774 6773 5014 -f 6774 5014 6742 -f 6742 5014 5016 -f 6742 5016 6743 -f 6743 5016 5023 -f 6743 5023 6744 -f 6744 5023 5022 -f 6744 5022 6745 -f 6745 5022 6775 -f 6745 6775 6776 -f 6776 6775 5020 -f 6776 5020 6777 -f 6777 5020 5021 -f 6777 5021 6778 -f 6778 5021 6779 -f 6778 6779 6746 -f 6746 6779 5029 -f 6746 5029 6748 -f 6748 5029 6780 -f 6748 6780 6747 -f 6747 6780 6781 -f 6747 6781 6782 -f 6782 6781 6783 -f 6782 6783 6784 -f 6784 6783 5025 -f 6784 5025 6750 -f 6750 5025 6785 -f 6750 6785 6786 -f 6786 6785 6787 -f 6786 6787 6788 -f 6788 6787 5019 -f 6788 5019 6751 -f 6751 5019 6789 -f 6751 6789 6752 -f 6752 6789 6790 -f 6752 6790 6753 -f 6753 6790 6754 -f 6792 6791 6809 -f 6807 6791 6792 -f 6792 6810 6793 -f 6794 6810 6792 -f 6809 6794 6792 -f 6792 6795 6814 -f 6812 6795 6792 -f 6793 6812 6792 -f 6792 6796 6820 -f 6816 6796 6792 -f 6814 6816 6792 -f 6792 6822 6797 -f 6821 6822 6792 -f 6820 6821 6792 -f 6792 6825 6826 -f 6823 6825 6792 -f 6797 6823 6792 -f 6792 6830 6799 -f 6829 6830 6792 -f 6826 6829 6792 -f 6792 6834 6798 -f 6833 6834 6792 -f 6799 6833 6792 -f 6792 6800 6837 -f 6836 6800 6792 -f 6798 6836 6792 -f 6792 6840 6801 -f 6802 6840 6792 -f 6837 6802 6792 -f 6792 6841 6803 -f 6804 6841 6792 -f 6801 6804 6792 -f 6792 6806 6805 -f 6844 6806 6792 -f 6803 6844 6792 -f 6805 6807 6792 -f 6807 6847 6791 -f 6791 6847 6808 -f 6791 6808 6809 -f 6809 6808 5167 -f 6809 5167 6794 -f 6794 5167 5146 -f 6794 5146 6810 -f 6810 5146 5153 -f 6810 5153 6793 -f 6793 5153 6811 -f 6793 6811 6812 -f 6812 6811 6813 -f 6812 6813 6795 -f 6795 6813 6815 -f 6795 6815 6814 -f 6814 6815 6817 -f 6814 6817 6816 -f 6816 6817 6818 -f 6816 6818 6796 -f 6796 6818 5165 -f 6796 5165 6820 -f 6820 5165 6819 -f 6820 6819 6821 -f 6821 6819 5152 -f 6821 5152 6822 -f 6822 5152 5151 -f 6822 5151 6797 -f 6797 5151 6824 -f 6797 6824 6823 -f 6823 6824 5150 -f 6823 5150 6825 -f 6825 5150 6827 -f 6825 6827 6826 -f 6826 6827 6828 -f 6826 6828 6829 -f 6829 6828 5156 -f 6829 5156 6830 -f 6830 5156 6831 -f 6830 6831 6799 -f 6799 6831 6832 -f 6799 6832 6833 -f 6833 6832 5149 -f 6833 5149 6834 -f 6834 5149 6835 -f 6834 6835 6798 -f 6798 6835 5155 -f 6798 5155 6836 -f 6836 5155 5154 -f 6836 5154 6800 -f 6800 5154 6838 -f 6800 6838 6837 -f 6837 6838 5164 -f 6837 5164 6802 -f 6802 5164 6839 -f 6802 6839 6840 -f 6840 6839 5162 -f 6840 5162 6801 -f 6801 5162 5161 -f 6801 5161 6804 -f 6804 5161 5160 -f 6804 5160 6841 -f 6841 5160 6842 -f 6841 6842 6803 -f 6803 6842 6843 -f 6803 6843 6844 -f 6844 6843 6845 -f 6844 6845 6806 -f 6806 6845 6846 -f 6806 6846 6805 -f 6805 6846 5148 -f 6805 5148 6807 -f 6807 5148 6847 -f 6863 6865 6866 -f 6848 6865 6863 -f 6863 6868 6850 -f 6849 6868 6863 -f 6866 6849 6863 -f 6863 6871 6872 -f 6851 6871 6863 -f 6850 6851 6863 -f 6863 6876 6878 -f 6852 6876 6863 -f 6872 6852 6863 -f 6863 6880 6854 -f 6853 6880 6863 -f 6878 6853 6863 -f 6863 6883 6857 -f 6881 6883 6863 -f 6854 6881 6863 -f 6863 6855 6856 -f 6858 6855 6863 -f 6857 6858 6863 -f 6863 6887 6859 -f 6886 6887 6863 -f 6856 6886 6863 -f 6863 6860 6891 -f 6889 6860 6863 -f 6859 6889 6863 -f 6863 6892 6861 -f 6862 6892 6863 -f 6891 6862 6863 -f 6863 6895 6898 -f 6894 6895 6863 -f 6861 6894 6863 -f 6863 6901 6902 -f 6864 6901 6863 -f 6898 6864 6863 -f 6902 6848 6863 -f 6848 5126 6865 -f 6865 5126 5127 -f 6865 5127 6866 -f 6866 5127 5111 -f 6866 5111 6849 -f 6849 5111 6867 -f 6849 6867 6868 -f 6868 6867 6869 -f 6868 6869 6850 -f 6850 6869 5119 -f 6850 5119 6851 -f 6851 5119 6870 -f 6851 6870 6871 -f 6871 6870 6873 -f 6871 6873 6872 -f 6872 6873 6874 -f 6872 6874 6852 -f 6852 6874 6875 -f 6852 6875 6876 -f 6876 6875 6877 -f 6876 6877 6878 -f 6878 6877 5118 -f 6878 5118 6853 -f 6853 5118 6879 -f 6853 6879 6880 -f 6880 6879 5117 -f 6880 5117 6854 -f 6854 5117 6882 -f 6854 6882 6881 -f 6881 6882 5116 -f 6881 5116 6883 -f 6883 5116 5113 -f 6883 5113 6857 -f 6857 5113 5112 -f 6857 5112 6858 -f 6858 5112 5115 -f 6858 5115 6855 -f 6855 5115 6884 -f 6855 6884 6856 -f 6856 6884 5114 -f 6856 5114 6886 -f 6886 5114 6885 -f 6886 6885 6887 -f 6887 6885 6888 -f 6887 6888 6859 -f 6859 6888 5110 -f 6859 5110 6889 -f 6889 5110 5123 -f 6889 5123 6860 -f 6860 5123 6890 -f 6860 6890 6891 -f 6891 6890 5122 -f 6891 5122 6862 -f 6862 5122 5121 -f 6862 5121 6892 -f 6892 5121 5120 -f 6892 5120 6861 -f 6861 5120 6893 -f 6861 6893 6894 -f 6894 6893 6896 -f 6894 6896 6895 -f 6895 6896 6897 -f 6895 6897 6898 -f 6898 6897 6899 -f 6898 6899 6864 -f 6864 6899 6900 -f 6864 6900 6901 -f 6901 6900 6903 -f 6901 6903 6902 -f 6902 6903 5109 -f 6902 5109 6848 -f 6848 5109 5126 -f 7040 7042 7057 -f 7059 6904 7057 -f 7057 6904 7038 -f 7045 7047 7050 -f 7038 7040 7057 -f 7042 7044 7050 -f 7042 6905 7057 -f 6905 7042 6906 -f 6906 7042 6907 -f 6907 7042 7051 -f 7044 7045 7050 -f 7051 7042 7050 -f 7050 7047 7049 -f 4402 6908 4401 -f 4402 4403 6908 -f 6913 6908 4403 -f 4394 4396 4410 -f 4396 6911 4410 -f 4403 6909 6911 -f 6910 6911 6909 -f 6910 6912 6911 -f 6911 6912 4407 -f 6911 4407 4410 -f 6914 4394 4410 -f 6911 6913 4403 -f 4410 6915 6914 -f 4410 6917 6915 -f 6919 7174 6918 -f 6916 7176 7174 -f 7201 7191 7197 -f 7174 6919 7171 -f 7174 7176 6918 -f 6918 7178 7179 -f 6919 6918 7179 -f 7172 7174 7171 -f 6920 6919 6922 -f 7169 6920 6922 -f 7180 7181 6919 -f 6919 7181 6921 -f 6919 6920 7171 -f 6922 6919 6921 -f 6929 6922 6921 -f 6923 6930 6929 -f 7182 7184 6921 -f 7184 6929 6921 -f 7165 6929 7184 -f 7184 7166 7165 -f 7184 7185 7166 -f 7185 7201 7166 -f 7185 7188 7201 -f 7188 7191 7201 -f 7190 7191 7188 -f 7197 6926 6927 -f 6924 7201 6925 -f 6925 7201 7197 -f 7191 6926 7197 -f 6927 7193 7194 -f 7196 7197 6927 -f 6927 6928 7196 -f 6929 6930 6922 -f 4551 6933 4550 -f 4553 4554 6934 -f 6946 6945 6931 -f 6933 6932 4550 -f 4531 6944 6948 -f 6932 6933 6934 -f 6935 6946 6931 -f 6948 4534 6949 -f 4531 6940 6941 -f 6946 6932 4554 -f 4548 4550 6932 -f 4548 6932 6936 -f 6936 6932 4524 -f 6936 4524 4546 -f 4524 6937 6938 -f 4546 4524 6939 -f 6939 4524 6938 -f 6938 4543 6939 -f 4543 4544 6939 -f 6932 6934 4554 -f 4543 6943 4519 -f 4543 4519 4542 -f 4542 4519 6941 -f 6941 6940 4542 -f 4531 6941 4530 -f 6940 4541 4542 -f 6928 6927 7194 -f 6940 4531 6942 -f 6941 4528 4530 -f 4540 6940 6942 -f 6938 6943 4543 -f 6942 4531 6948 -f 6948 6944 4534 -f 6945 6946 4554 -f 6947 6948 6949 -f 6957 7127 7126 -f 6952 7092 7103 -f 7093 6952 7112 -f 6952 7103 6950 -f 7112 6952 7114 -f 6952 6950 7101 -f 7114 6952 7115 -f 6952 7101 7100 -f 7115 6952 7117 -f 6952 7100 7098 -f 7117 6952 6951 -f 6952 7098 7097 -f 6951 6952 7121 -f 6952 7097 7096 -f 7121 6952 6953 -f 6952 7096 7087 -f 6957 6952 7087 -f 6953 6952 6961 -f 6954 6957 7087 -f 6957 6955 6961 -f 6956 6957 6954 -f 6957 7122 6955 -f 7108 6957 6956 -f 6957 7124 7122 -f 7110 6957 7108 -f 7106 6957 7110 -f 6957 6958 7124 -f 7105 6957 7106 -f 6957 6960 6958 -f 6959 6957 7105 -f 6957 7126 6960 -f 7104 6957 6959 -f 6952 6957 6961 -f 7091 7127 6957 -f 6983 6962 6972 -f 6964 4447 6970 -f 6964 6969 4476 -f 4448 6964 6963 -f 6964 4476 4475 -f 6963 6964 4451 -f 6964 4475 4473 -f 4451 6964 4452 -f 6964 4473 6965 -f 4452 6964 6966 -f 6964 6965 6967 -f 6966 6964 6968 -f 6964 6967 4471 -f 6968 6964 4455 -f 6964 4471 4470 -f 4455 6964 4454 -f 6964 4470 4447 -f 4454 6964 4457 -f 6964 6972 4439 -f 4457 6964 4458 -f 6972 6964 6970 -f 6964 4446 6969 -f 6971 6972 6970 -f 4458 6964 4439 -f 6974 6972 6971 -f 6972 6973 4439 -f 6975 6972 6974 -f 6972 6976 6973 -f 6977 6972 6975 -f 6972 4459 6976 -f 6978 6972 6977 -f 6972 6979 4459 -f 6981 6972 6978 -f 6972 4461 6979 -f 6980 6972 6981 -f 6972 4463 4461 -f 6982 6972 6980 -f 6972 4464 4463 -f 6983 6972 6982 -f 6972 4465 4464 -f 6972 4467 4465 -f 7104 6984 6957 -f 6986 2572 6987 -f 6987 6985 6986 -f 2490 2543 6985 -f 2588 6986 2455 -f 2490 6985 6987 -f 6985 2455 6986 -f 6985 6989 2455 -f 4467 6972 4468 -f 5166 5103 5091 -f 6988 5141 5052 -f 5108 6988 5091 -f 5052 5166 6988 -f 6989 6985 2541 -f 5057 5166 5052 -f 5166 5091 6988 -f 5147 5103 5166 -f 5057 5174 5166 -f 6992 7311 9578 -f 9578 7311 7312 -f 9578 7312 6990 -f 9578 6990 4921 -f 6994 6991 7308 -f 6994 7308 7309 -f 6994 7309 6992 -f 6992 7309 7311 -f 6997 7305 6993 -f 7002 7305 7307 -f 7307 6991 7002 -f 7002 6991 6994 -f 6995 7563 7317 -f 6995 7317 6996 -f 6995 6996 6997 -f 6995 6997 6993 -f 6996 7318 6997 -f 6997 7318 7303 -f 7303 7318 7314 -f 7303 7314 7300 -f 7300 7314 7299 -f 7299 7314 7315 -f 7299 7315 6998 -f 7299 6998 7000 -f 7000 6998 6999 -f 6999 7563 7000 -f 7000 7563 7001 -f 7001 7563 6995 -f 6993 7305 7002 -f 6993 7002 4337 -f 4337 7002 7003 -f 4337 7003 4345 -f 4345 7003 4353 -f 4345 4353 7004 -f 7004 4353 4352 -f 7004 4352 4343 -f 4343 4352 7005 -f 4343 7005 7006 -f 7006 7005 7007 -f 7006 7007 7008 -f 7008 7007 7009 -f 7008 7009 4344 -f 4344 7009 4351 -f 4344 4351 7010 -f 7076 7085 7060 -f 7085 4925 7064 -f 7064 7011 7085 -f 7085 7011 7062 -f 7085 7062 7060 -f 7012 7076 7013 -f 7015 7014 7012 -f 7012 7014 7076 -f 7014 7015 7017 -f 7014 7017 7072 -f 5193 7071 7016 -f 7016 7071 7072 -f 7016 7072 7017 -f 4924 9518 7018 -f 9518 7015 7012 -f 9517 7025 7019 -f 7019 7321 9517 -f 9517 7321 7323 -f 9517 7323 7020 -f 7015 9518 7017 -f 7017 9518 7016 -f 7018 9518 7026 -f 7026 9518 7012 -f 7026 7012 7013 -f 7021 4924 4926 -f 9519 7389 7032 -f 7032 7389 7390 -f 7032 7390 7022 -f 7022 7392 7032 -f 7032 7392 7393 -f 7032 7393 7023 -f 7032 7024 9517 -f 9517 7024 7320 -f 9517 7320 7025 -f 7412 7348 7032 -f 7061 7026 7037 -f 7037 7026 7013 -f 7032 7348 7024 -f 7024 7348 7350 -f 7024 7350 7414 -f 7061 7063 7026 -f 7023 7027 7032 -f 7032 7027 7028 -f 7032 7028 7410 -f 7416 7029 7030 -f 7410 7031 7032 -f 7032 7031 7033 -f 7032 7033 7412 -f 7414 7415 7024 -f 7024 7415 7416 -f 7024 7416 7420 -f 7420 7416 7030 -f 7053 7062 7054 -f 7054 7062 7061 -f 7062 7053 7052 -f 7062 7052 7034 -f 7056 7055 7061 -f 7061 7055 7054 -f 7062 7034 7049 -f 7062 7049 7060 -f 7061 7035 7056 -f 7049 7048 7060 -f 7060 7048 7046 -f 7060 7046 7036 -f 7060 7036 7043 -f 7060 7043 7037 -f 7037 7043 7041 -f 7037 7039 7058 -f 7037 7058 7061 -f 7061 7058 7035 -f 7037 7041 7039 -f 6904 7058 7039 -f 6904 7039 7038 -f 7038 7039 7041 -f 7038 7041 7040 -f 7040 7041 7042 -f 7042 7041 7043 -f 7042 7043 7044 -f 7044 7043 7036 -f 7044 7036 7045 -f 7045 7036 7046 -f 7045 7046 7047 -f 7047 7046 7048 -f 7047 7048 7049 -f 7050 7049 7034 -f 7050 7034 7052 -f 7050 7052 7051 -f 7051 7052 6907 -f 6907 7052 7053 -f 6907 7053 6906 -f 6906 7053 7054 -f 6906 7054 6905 -f 6905 7054 7055 -f 6905 7055 7056 -f 6905 7056 7057 -f 7057 7056 7035 -f 7035 7059 7057 -f 7058 6904 7059 -f 7058 7059 7035 -f 7013 7076 7060 -f 7013 7060 7037 -f 7061 7062 7011 -f 7061 7011 7063 -f 7063 7011 7064 -f 7063 7064 7026 -f 5193 7065 7071 -f 5189 7075 7080 -f 7079 7078 7072 -f 7072 7078 7014 -f 7084 7085 7076 -f 4925 7085 7066 -f 7067 7066 7068 -f 7067 7068 7083 -f 7067 7083 7069 -f 7069 7083 7073 -f 7069 7074 4923 -f 4923 7074 7070 -f 7070 7074 5191 -f 7070 5191 7387 -f 7065 5188 7071 -f 7071 5188 7079 -f 7071 7079 7072 -f 7069 7073 7074 -f 7074 7073 7080 -f 7074 7080 7075 -f 7074 7075 5191 -f 7084 7076 7014 -f 7084 7014 7077 -f 7077 7014 7078 -f 7077 7078 7082 -f 7082 7078 7079 -f 7082 7079 7081 -f 7081 7079 5188 -f 7081 5188 5189 -f 5189 7080 7081 -f 7081 7080 7073 -f 7081 7073 7082 -f 7082 7073 7083 -f 7082 7083 7077 -f 7077 7083 7068 -f 7077 7068 7066 -f 7077 7066 7084 -f 7084 7066 7085 -f 7096 2237 7087 -f 7087 2237 7086 -f 7087 7086 6954 -f 6957 6984 7089 -f 4931 7091 7088 -f 7089 7090 6957 -f 6957 7090 4927 -f 6957 4927 7091 -f 7091 4927 4928 -f 7091 4928 7088 -f 2247 7092 7095 -f 7095 7092 6952 -f 7113 4935 7093 -f 7093 4935 7094 -f 7093 7094 6952 -f 6952 7094 2245 -f 6952 2245 7095 -f 6955 4934 6961 -f 6961 4934 7119 -f 6961 7119 6953 -f 2237 7096 7097 -f 2237 7097 2240 -f 2240 7097 7098 -f 2240 7098 7099 -f 7099 7098 7100 -f 7099 7100 7102 -f 7102 7100 7101 -f 7102 7101 6950 -f 7102 6950 2247 -f 2247 6950 7103 -f 2247 7103 7092 -f 7089 6984 7104 -f 7089 7104 2231 -f 2231 7104 6959 -f 2231 6959 7105 -f 2231 7105 7107 -f 7107 7105 7106 -f 7107 7106 7110 -f 7107 7110 7109 -f 7108 6956 7111 -f 7111 7109 7108 -f 7108 7109 7110 -f 6956 6954 7086 -f 7086 7111 6956 -f 7113 7093 7112 -f 7113 7112 7114 -f 7113 7114 7116 -f 7116 7114 7115 -f 7116 7115 7117 -f 7116 7117 7118 -f 7118 7117 6951 -f 6951 7121 7120 -f 6951 7120 7118 -f 7121 6953 7119 -f 7119 7120 7121 -f 4934 6955 7123 -f 7123 6955 7122 -f 7123 7122 7124 -f 7123 7124 4929 -f 4929 7124 6958 -f 4929 6958 7125 -f 7125 6958 6960 -f 7125 6960 7126 -f 7125 7126 7128 -f 7128 7126 7127 -f 7128 7127 7091 -f 7128 7091 4931 -f 7136 7282 7130 -f 7130 7282 7129 -f 7290 7257 7130 -f 7290 7130 7129 -f 7290 7255 7257 -f 7291 7255 7290 -f 7291 7265 7255 -f 7291 7131 7265 -f 7265 7131 7264 -f 7131 7287 7264 -f 7264 7287 7260 -f 7260 7287 7288 -f 7260 7288 7132 -f 7132 7288 7284 -f 7294 7133 7132 -f 7294 7132 7284 -f 7133 7294 7134 -f 7134 7294 5194 -f 7134 5194 5202 -f 7252 7218 7135 -f 7135 7218 7280 -f 7135 7280 7136 -f 7136 7280 7282 -f 7138 7187 7267 -f 7137 7170 7139 -f 7200 7140 7202 -f 7138 7267 7189 -f 7137 7139 7173 -f 7170 7168 7139 -f 7139 7168 7167 -f 7200 7199 7140 -f 7140 7199 7198 -f 7140 7198 7195 -f 7195 7141 7140 -f 7140 7141 7142 -f 7140 7142 7153 -f 7150 7177 7248 -f 7187 7186 7267 -f 7267 7186 7143 -f 7267 7143 7233 -f 7233 7143 7183 -f 7233 7183 7144 -f 7144 7145 7233 -f 7233 7145 7146 -f 7233 7146 7246 -f 7246 7146 7147 -f 7177 7148 7248 -f 7248 7148 7175 -f 7248 7175 7139 -f 7139 7175 7149 -f 7139 7149 7173 -f 7150 7248 7147 -f 7147 7248 7246 -f 7142 7151 7153 -f 7153 7151 7152 -f 7153 7152 7192 -f 7153 7192 7276 -f 7276 7192 7154 -f 7189 7267 7154 -f 7154 7267 7276 -f 7232 7271 5201 -f 5201 7271 7241 -f 7155 7156 7240 -f 7155 7240 7271 -f 7156 7238 7240 -f 7271 7240 7241 -f 7157 7160 7158 -f 7156 7160 7238 -f 7238 7160 7235 -f 7235 7160 7157 -f 7267 7233 7159 -f 7159 7233 7158 -f 7159 7158 7160 -f 7161 7223 7245 -f 7245 7247 7161 -f 7275 7281 7162 -f 7162 7281 7163 -f 7208 7205 6923 -f 6930 7207 6922 -f 6923 7205 6930 -f 6930 7205 7206 -f 6930 7206 7207 -f 7208 6923 7209 -f 7209 6923 6929 -f 7209 6929 7164 -f 7164 6929 7165 -f 7164 7165 7203 -f 7203 7165 7166 -f 7203 7166 7204 -f 7204 7166 7201 -f 7204 7201 7202 -f 7207 7167 6922 -f 6922 7167 7169 -f 7169 7167 7168 -f 7169 7168 6920 -f 6920 7168 7170 -f 6920 7170 7171 -f 7171 7170 7137 -f 7171 7137 7172 -f 7172 7137 7173 -f 7172 7173 7174 -f 7174 7173 7149 -f 7174 7149 6916 -f 6916 7149 7175 -f 6916 7175 7176 -f 7176 7175 7148 -f 7176 7148 6918 -f 6918 7148 7177 -f 6918 7177 7178 -f 7178 7177 7150 -f 7178 7150 7179 -f 7179 7150 7147 -f 7179 7147 6919 -f 6919 7147 7146 -f 6919 7146 7180 -f 7180 7146 7145 -f 7180 7145 7181 -f 7181 7145 7144 -f 7181 7144 6921 -f 6921 7144 7183 -f 6921 7183 7182 -f 7182 7183 7143 -f 7182 7143 7184 -f 7184 7143 7186 -f 7184 7186 7185 -f 7185 7186 7187 -f 7185 7187 7188 -f 7188 7187 7138 -f 7188 7138 7190 -f 7190 7138 7189 -f 7190 7189 7191 -f 7191 7189 7154 -f 7191 7154 6926 -f 6926 7154 7192 -f 6926 7192 6927 -f 6927 7192 7152 -f 6927 7152 7193 -f 7193 7152 7151 -f 7193 7151 7194 -f 7194 7151 7142 -f 7194 7142 6928 -f 6928 7142 7141 -f 6928 7141 7196 -f 7196 7141 7195 -f 7196 7195 7197 -f 7197 7195 7198 -f 7197 7198 6925 -f 6925 7198 7199 -f 6925 7199 6924 -f 6924 7199 7200 -f 6924 7200 7201 -f 7201 7200 7202 -f 7204 7202 7140 -f 7164 7211 7209 -f 7164 7203 7211 -f 7211 7203 7140 -f 7140 7203 7204 -f 7208 7210 7205 -f 7205 7210 7206 -f 7206 7210 7139 -f 7206 7139 7207 -f 7139 7167 7207 -f 7208 7209 7210 -f 7210 7209 7211 -f 7210 7211 7249 -f 7249 7211 7213 -f 7249 7213 7212 -f 7212 7213 7250 -f 7250 7213 7279 -f 7250 7279 7215 -f 7215 7279 7214 -f 7215 7214 7251 -f 7251 7214 7216 -f 7251 7216 7217 -f 7217 7216 7278 -f 7217 7278 7252 -f 7252 7278 7218 -f 5202 5201 7243 -f 5202 7243 7133 -f 7133 7243 7242 -f 7239 7259 7242 -f 7242 7259 7133 -f 7262 7237 7263 -f 7262 7261 7237 -f 7237 7261 7239 -f 7239 7261 7259 -f 7237 7236 7263 -f 7263 7236 7266 -f 7266 7236 7234 -f 7266 7234 7254 -f 7254 7234 7219 -f 7258 7254 7219 -f 7219 7220 7258 -f 7258 7220 7221 -f 7258 7221 7256 -f 7221 7244 7256 -f 7256 7244 7253 -f 7253 7244 7222 -f 7245 7223 7222 -f 7222 7223 7253 -f 7281 7275 7224 -f 7224 7275 7226 -f 7225 7227 7226 -f 7226 7227 7289 -f 7224 7226 7289 -f 7228 7292 7227 -f 7228 7227 7225 -f 7228 7229 7292 -f 7292 7229 7274 -f 7292 7274 7230 -f 7297 7296 7268 -f 7292 7230 7296 -f 7296 7230 7277 -f 7296 7277 7268 -f 7297 7268 7272 -f 7297 7272 7285 -f 7283 7286 7270 -f 7272 7273 7285 -f 7285 7273 7286 -f 7286 7273 7270 -f 7293 7283 7270 -f 7270 7231 7293 -f 7293 7231 7295 -f 7231 7232 7295 -f 7295 7232 5194 -f 7233 7219 7158 -f 7158 7219 7234 -f 7158 7234 7236 -f 7158 7236 7157 -f 7157 7236 7235 -f 7235 7236 7237 -f 7235 7237 7238 -f 7243 5201 7241 -f 7238 7237 7239 -f 7238 7239 7240 -f 7240 7239 7242 -f 7240 7242 7241 -f 7241 7242 7243 -f 7246 7248 7244 -f 7219 7233 7246 -f 7219 7246 7220 -f 7244 7248 7222 -f 7222 7248 7245 -f 7246 7244 7221 -f 7246 7221 7220 -f 7139 7247 7248 -f 7248 7247 7245 -f 7139 7210 7247 -f 7210 7249 7247 -f 7249 7212 7247 -f 7247 7212 7250 -f 7247 7250 7215 -f 7247 7215 7251 -f 7247 7251 7217 -f 7247 7217 7161 -f 7161 7217 7252 -f 7135 7223 7252 -f 7252 7223 7161 -f 7136 7253 7223 -f 7135 7136 7223 -f 7253 7130 7256 -f 7253 7136 7130 -f 7265 7254 7255 -f 7255 7254 7258 -f 7256 7130 7257 -f 7256 7257 7258 -f 7258 7257 7255 -f 7133 7134 5202 -f 7133 7259 7132 -f 7132 7259 7260 -f 7260 7259 7261 -f 7260 7261 7264 -f 7264 7261 7262 -f 7264 7262 7263 -f 7264 7263 7266 -f 7264 7266 7265 -f 7265 7266 7254 -f 7277 7267 7268 -f 7268 7267 7269 -f 7270 7156 7231 -f 7231 7156 7271 -f 7269 7273 7272 -f 7269 7272 7268 -f 7269 7267 7159 -f 7269 7159 7160 -f 7160 7156 7269 -f 7269 7156 7273 -f 7273 7156 7270 -f 7271 7232 7231 -f 7156 7155 7271 -f 7275 7153 7226 -f 7274 7276 7230 -f 7230 7276 7267 -f 7230 7267 7277 -f 7274 7229 7276 -f 7276 7229 7228 -f 7276 7228 7225 -f 7276 7225 7153 -f 7153 7225 7226 -f 7162 7140 7275 -f 7275 7140 7153 -f 7163 7218 7278 -f 7278 7216 7163 -f 7216 7214 7163 -f 7214 7279 7163 -f 7279 7213 7163 -f 7163 7213 7211 -f 7163 7211 7140 -f 7163 7140 7162 -f 7281 7280 7163 -f 7163 7280 7218 -f 7280 7281 7224 -f 7280 7224 7282 -f 7287 7297 7285 -f 7287 7285 7286 -f 7287 7286 7283 -f 7287 7283 7288 -f 7288 7283 7284 -f 7224 7129 7282 -f 7224 7289 7129 -f 7129 7289 7227 -f 7129 7227 7290 -f 7290 7227 7292 -f 7291 7292 7131 -f 7290 7292 7291 -f 7283 7293 7284 -f 7284 7293 7294 -f 7294 7293 7295 -f 7294 7295 5194 -f 7292 7296 7131 -f 7131 7296 7297 -f 7131 7297 7287 -f 7573 4922 7313 -f 7573 7299 7298 -f 7573 7298 4922 -f 7570 7299 7573 -f 7570 7300 7299 -f 7301 7300 7570 -f 7301 7303 7300 -f 7301 7302 7303 -f 7303 7302 7571 -f 7303 7571 6997 -f 6997 7571 7304 -f 6997 7304 7305 -f 7305 7304 7306 -f 7305 7306 7307 -f 7307 7306 7572 -f 7307 7572 6991 -f 6991 7572 7310 -f 6991 7310 7308 -f 7308 7310 7309 -f 7309 7310 7311 -f 7311 7310 7574 -f 7311 7574 7312 -f 7574 7313 6990 -f 6990 7312 7574 -f 4922 4921 7313 -f 7313 4921 6990 -f 7315 7314 7565 -f 7316 7315 7565 -f 7316 6998 7315 -f 7564 6998 7316 -f 7564 6999 6998 -f 7575 6999 7564 -f 7575 7563 6999 -f 7569 7317 7563 -f 7568 6996 7569 -f 7569 6996 7317 -f 7567 7318 7568 -f 7568 7318 6996 -f 7566 7314 7318 -f 7566 7318 7567 -f 7024 7405 7320 -f 7320 7405 7319 -f 7320 7319 7025 -f 7025 7319 7399 -f 7025 7399 7019 -f 7019 7399 7322 -f 7019 7322 7321 -f 7321 7322 7324 -f 7321 7324 7323 -f 7323 7324 7395 -f 7323 7395 7020 -f 7020 7395 7325 -f 7559 7558 7348 -f 7559 7348 7326 -f 7513 7350 7514 -f 7514 7350 7515 -f 7364 7452 7362 -f 7544 7384 7327 -f 7327 7384 7333 -f 7544 7328 7384 -f 7384 7328 7329 -f 7384 7329 7372 -f 7547 7330 7350 -f 7350 7330 7331 -f 7350 7331 7545 -f 7369 7332 7376 -f 7376 7332 7531 -f 7376 7531 7348 -f 7348 7531 7561 -f 7348 7561 7326 -f 7333 7334 7327 -f 7327 7334 7335 -f 7327 7335 7520 -f 7515 7350 7336 -f 7336 7350 7545 -f 7336 7545 7518 -f 7518 7545 7327 -f 7518 7327 7345 -f 7513 7512 7350 -f 7350 7512 7338 -f 7350 7338 7337 -f 7337 7338 7510 -f 7337 7510 7509 -f 7509 7507 7337 -f 7337 7507 7505 -f 7337 7505 7352 -f 7558 7339 7348 -f 7348 7339 7441 -f 7348 7441 7347 -f 7340 7341 7350 -f 7350 7341 7461 -f 7461 7459 7350 -f 7350 7459 7342 -f 7350 7342 7343 -f 7520 7344 7327 -f 7327 7344 7519 -f 7327 7519 7345 -f 7443 7346 7558 -f 7558 7346 7442 -f 7558 7442 7339 -f 7347 7470 7348 -f 7348 7470 7349 -f 7348 7349 7469 -f 7343 7458 7350 -f 7350 7458 7351 -f 7350 7351 7361 -f 7352 7353 7337 -f 7337 7353 7502 -f 7337 7502 7354 -f 7362 7452 7355 -f 7355 7452 7451 -f 7355 7451 7450 -f 7450 7356 7355 -f 7355 7356 7381 -f 7355 7381 7383 -f 7469 7357 7348 -f 7348 7357 7468 -f 7348 7468 7358 -f 7358 7465 7348 -f 7348 7465 7359 -f 7348 7359 7350 -f 7350 7359 7360 -f 7350 7360 7340 -f 7547 7350 7548 -f 7548 7350 7361 -f 7548 7361 7362 -f 7362 7361 7363 -f 7362 7363 7364 -f 7498 7365 7376 -f 7366 7493 7376 -f 7376 7493 7367 -f 7376 7367 7490 -f 7535 7368 7376 -f 7376 7368 7533 -f 7376 7533 7369 -f 7354 7370 7337 -f 7337 7370 7499 -f 7337 7499 7376 -f 7376 7499 7371 -f 7376 7371 7498 -f 7372 7540 7384 -f 7384 7540 7539 -f 7365 7495 7376 -f 7376 7495 7373 -f 7376 7373 7366 -f 7556 7374 7558 -f 7558 7374 7375 -f 7558 7375 7443 -f 7490 7526 7376 -f 7376 7526 7523 -f 7376 7523 7384 -f 7556 7554 7374 -f 7374 7554 7377 -f 7377 7554 7379 -f 7377 7379 7378 -f 7378 7379 7380 -f 7380 7379 7382 -f 7380 7382 7381 -f 7381 7382 7383 -f 7384 7539 7537 -f 7384 7537 7376 -f 7376 7537 7535 -f 7387 7385 7386 -f 7387 7386 7388 -f 9519 7388 7389 -f 7389 7388 7386 -f 7389 7386 7390 -f 7390 7386 7391 -f 7390 7391 7022 -f 7022 7391 7398 -f 7022 7398 7392 -f 7392 7398 7394 -f 7392 7394 7393 -f 7393 7394 7397 -f 7393 7397 7023 -f 7023 7397 7403 -f 7324 7396 7395 -f 7395 7396 7325 -f 7324 7322 7396 -f 7396 7322 7399 -f 7396 7399 7400 -f 7399 7397 7394 -f 7399 7319 7397 -f 7397 7319 7405 -f 7397 7405 7403 -f 7394 7398 7399 -f 7399 7398 7391 -f 7399 7391 7400 -f 7400 7391 7386 -f 7400 7386 7385 -f 7407 7403 7401 -f 7401 7403 7411 -f 7413 7402 7405 -f 7405 7402 7337 -f 7405 7337 7403 -f 7403 7337 7376 -f 7403 7376 7411 -f 7418 7417 7406 -f 7409 7408 7401 -f 7401 7408 7404 -f 7401 7404 7407 -f 7413 7405 7406 -f 7406 7405 7419 -f 7406 7419 7418 -f 7023 7403 7407 -f 7023 7407 7027 -f 7027 7407 7404 -f 7027 7404 7028 -f 7028 7404 7408 -f 7028 7408 7410 -f 7410 7408 7409 -f 7410 7409 7031 -f 7031 7409 7401 -f 7031 7401 7033 -f 7033 7401 7411 -f 7033 7411 7412 -f 7412 7411 7376 -f 7412 7376 7348 -f 7350 7337 7402 -f 7350 7402 7414 -f 7414 7402 7413 -f 7414 7413 7415 -f 7415 7413 7406 -f 7415 7406 7416 -f 7416 7406 7417 -f 7416 7417 7029 -f 7029 7417 7418 -f 7029 7418 7030 -f 7030 7418 7419 -f 7030 7419 7420 -f 7420 7419 7405 -f 7420 7405 7024 -f 7426 7421 7440 -f 7439 7421 7426 -f 7426 7422 7423 -f 7424 7422 7426 -f 7440 7424 7426 -f 7426 7445 7425 -f 7444 7445 7426 -f 7423 7444 7426 -f 7426 7427 7447 -f 7446 7427 7426 -f 7425 7446 7426 -f 7426 7448 7449 -f 7428 7448 7426 -f 7447 7428 7426 -f 7426 7429 7453 -f 7430 7429 7426 -f 7449 7430 7426 -f 7426 7455 7456 -f 7454 7455 7426 -f 7453 7454 7426 -f 7426 7431 7433 -f 7457 7431 7426 -f 7456 7457 7426 -f 7426 7432 7462 -f 7460 7432 7426 -f 7433 7460 7426 -f 7426 7434 7464 -f 7463 7434 7426 -f 7462 7463 7426 -f 7426 7435 7467 -f 7466 7435 7426 -f 7464 7466 7426 -f 7426 7436 7438 -f 7437 7436 7426 -f 7467 7437 7426 -f 7438 7439 7426 -f 7439 7347 7421 -f 7421 7347 7441 -f 7421 7441 7440 -f 7440 7441 7339 -f 7440 7339 7424 -f 7424 7339 7442 -f 7424 7442 7422 -f 7422 7442 7346 -f 7422 7346 7423 -f 7423 7346 7443 -f 7423 7443 7444 -f 7444 7443 7375 -f 7444 7375 7445 -f 7445 7375 7374 -f 7445 7374 7425 -f 7425 7374 7377 -f 7425 7377 7446 -f 7446 7377 7378 -f 7446 7378 7427 -f 7427 7378 7380 -f 7427 7380 7447 -f 7447 7380 7381 -f 7447 7381 7428 -f 7428 7381 7356 -f 7428 7356 7448 -f 7448 7356 7450 -f 7448 7450 7449 -f 7449 7450 7451 -f 7449 7451 7430 -f 7430 7451 7452 -f 7430 7452 7429 -f 7429 7452 7364 -f 7429 7364 7453 -f 7453 7364 7363 -f 7453 7363 7454 -f 7454 7363 7361 -f 7454 7361 7455 -f 7455 7361 7351 -f 7455 7351 7456 -f 7456 7351 7458 -f 7456 7458 7457 -f 7457 7458 7343 -f 7457 7343 7431 -f 7431 7343 7342 -f 7431 7342 7433 -f 7433 7342 7459 -f 7433 7459 7460 -f 7460 7459 7461 -f 7460 7461 7432 -f 7432 7461 7341 -f 7432 7341 7462 -f 7462 7341 7340 -f 7462 7340 7463 -f 7463 7340 7360 -f 7463 7360 7434 -f 7434 7360 7359 -f 7434 7359 7464 -f 7464 7359 7465 -f 7464 7465 7466 -f 7466 7465 7358 -f 7466 7358 7435 -f 7435 7358 7468 -f 7435 7468 7467 -f 7467 7468 7357 -f 7467 7357 7437 -f 7437 7357 7469 -f 7437 7469 7436 -f 7436 7469 7349 -f 7436 7349 7438 -f 7438 7349 7470 -f 7438 7470 7439 -f 7439 7470 7347 -f 7474 7471 7472 -f 7525 7471 7474 -f 7474 7492 7494 -f 7491 7492 7474 -f 7472 7491 7474 -f 7474 7496 7497 -f 7473 7496 7474 -f 7494 7473 7474 -f 7474 7475 7476 -f 7477 7475 7474 -f 7497 7477 7474 -f 7474 7501 7503 -f 7500 7501 7474 -f 7476 7500 7474 -f 7474 7506 7478 -f 7504 7506 7474 -f 7503 7504 7474 -f 7474 7508 7511 -f 7479 7508 7474 -f 7478 7479 7474 -f 7474 7482 7480 -f 7481 7482 7474 -f 7511 7481 7474 -f 7474 7516 7517 -f 7483 7516 7474 -f 7480 7483 7474 -f 7474 7485 7487 -f 7484 7485 7474 -f 7517 7484 7474 -f 7474 7486 7521 -f 7488 7486 7474 -f 7487 7488 7474 -f 7474 7489 7524 -f 7522 7489 7474 -f 7521 7522 7474 -f 7524 7525 7474 -f 7525 7526 7471 -f 7471 7526 7490 -f 7471 7490 7472 -f 7472 7490 7367 -f 7472 7367 7491 -f 7491 7367 7493 -f 7491 7493 7492 -f 7492 7493 7366 -f 7492 7366 7494 -f 7494 7366 7373 -f 7494 7373 7473 -f 7473 7373 7495 -f 7473 7495 7496 -f 7496 7495 7365 -f 7496 7365 7497 -f 7497 7365 7498 -f 7497 7498 7477 -f 7477 7498 7371 -f 7477 7371 7475 -f 7475 7371 7499 -f 7475 7499 7476 -f 7476 7499 7370 -f 7476 7370 7500 -f 7500 7370 7354 -f 7500 7354 7501 -f 7501 7354 7502 -f 7501 7502 7503 -f 7503 7502 7353 -f 7503 7353 7504 -f 7504 7353 7352 -f 7504 7352 7506 -f 7506 7352 7505 -f 7506 7505 7478 -f 7478 7505 7507 -f 7478 7507 7479 -f 7479 7507 7509 -f 7479 7509 7508 -f 7508 7509 7510 -f 7508 7510 7511 -f 7511 7510 7338 -f 7511 7338 7481 -f 7481 7338 7512 -f 7481 7512 7482 -f 7482 7512 7513 -f 7482 7513 7480 -f 7480 7513 7514 -f 7480 7514 7483 -f 7483 7514 7515 -f 7483 7515 7516 -f 7516 7515 7336 -f 7516 7336 7517 -f 7517 7336 7518 -f 7517 7518 7484 -f 7484 7518 7345 -f 7484 7345 7485 -f 7485 7345 7519 -f 7485 7519 7487 -f 7487 7519 7344 -f 7487 7344 7488 -f 7488 7344 7520 -f 7488 7520 7486 -f 7486 7520 7335 -f 7486 7335 7521 -f 7521 7335 7334 -f 7521 7334 7522 -f 7522 7334 7333 -f 7522 7333 7489 -f 7489 7333 7384 -f 7489 7384 7524 -f 7524 7384 7523 -f 7524 7523 7525 -f 7525 7523 7526 -f 7527 7562 7532 -f 7532 7534 7527 -f 7527 7536 7538 -f 7534 7536 7527 -f 7538 7541 7527 -f 7527 7542 7543 -f 7541 7542 7527 -f 7543 7528 7527 -f 7529 7546 7527 -f 7528 7529 7527 -f 7530 7549 7527 -f 7546 7530 7527 -f 7527 7550 7551 -f 7549 7550 7527 -f 7527 7552 7553 -f 7551 7552 7527 -f 7527 7555 7557 -f 7553 7555 7527 -f 7557 7560 7527 -f 7560 7562 7527 -f 7562 7531 7332 -f 7562 7332 7532 -f 7532 7332 7369 -f 7532 7369 7533 -f 7532 7533 7534 -f 7534 7533 7368 -f 7534 7368 7535 -f 7534 7535 7536 -f 7536 7535 7537 -f 7536 7537 7538 -f 7538 7537 7539 -f 7538 7539 7541 -f 7541 7539 7540 -f 7541 7540 7542 -f 7542 7540 7372 -f 7542 7372 7329 -f 7542 7329 7543 -f 7543 7329 7328 -f 7543 7328 7544 -f 7543 7544 7528 -f 7528 7544 7327 -f 7528 7327 7545 -f 7528 7545 7529 -f 7529 7545 7331 -f 7529 7331 7546 -f 7546 7331 7330 -f 7546 7330 7547 -f 7546 7547 7530 -f 7530 7547 7548 -f 7530 7548 7549 -f 7549 7548 7362 -f 7549 7362 7355 -f 7549 7355 7550 -f 7550 7355 7383 -f 7550 7383 7382 -f 7550 7382 7551 -f 7551 7382 7552 -f 7552 7382 7379 -f 7552 7379 7553 -f 7553 7379 7554 -f 7553 7554 7555 -f 7555 7554 7556 -f 7555 7556 7557 -f 7557 7556 7558 -f 7557 7558 7559 -f 7557 7559 7560 -f 7560 7559 7326 -f 7560 7326 7561 -f 7560 7561 7562 -f 7562 7561 7531 -f 7565 7314 7566 -f 7569 7563 7575 -f 7010 4350 4339 -f 7302 7301 7571 -f 7571 7301 7570 -f 7304 7571 7570 -f 7010 4351 4350 -f 7304 7570 7573 -f 7306 7573 7313 -f 7306 7304 7573 -f 7306 7313 7572 -f 7572 7313 7574 -f 7572 7574 7310 -f 7575 7564 7569 -f 7564 7316 7568 -f 7568 7569 7564 -f 7568 7316 7567 -f 7316 7565 7567 -f 7565 7566 7567 -f 7579 7580 7581 -f 7581 4686 4685 -f 7576 7577 7583 -f 7577 7582 7583 -f 7577 7578 7582 -f 7578 4683 7582 -f 4683 7578 4685 -f 7578 7579 4685 -f 7579 7581 4685 -f 4677 7584 4678 -f 7584 4658 4678 -f 7584 7586 4658 -f 4674 7588 7587 -f 4658 7586 7585 -f 7585 7586 4660 -f 7586 4674 4660 -f 4660 4674 7587 -f 7587 7588 4665 -f 7588 4671 4665 -f 4671 4667 4665 -f 8811 7593 7601 -f 7601 7593 9432 -f 7589 9441 7590 -f 7590 9441 8978 -f 8981 7591 7597 -f 7597 7591 7592 -f 7597 7592 9441 -f 9441 7592 8980 -f 9441 8980 8978 -f 7593 8811 7595 -f 7595 8811 7594 -f 7595 7594 8983 -f 8983 8982 7595 -f 7595 8982 7596 -f 7595 7596 7597 -f 7597 7596 7598 -f 7597 7598 8981 -f 7599 8757 9431 -f 7599 9431 7600 -f 7601 9432 8758 -f 8758 9432 9431 -f 8758 9431 7602 -f 7602 9431 8757 -f 8717 7603 7604 -f 7604 7603 8754 -f 7604 8754 9431 -f 9431 8754 8755 -f 9431 8755 7600 -f 7606 8715 7607 -f 7607 8715 8716 -f 7607 8716 7604 -f 7604 8716 7605 -f 7604 7605 8717 -f 7606 7607 7608 -f 7606 7608 8706 -f 8703 8704 9433 -f 9433 8704 7609 -f 9433 7609 7608 -f 7608 7609 8705 -f 7608 8705 8706 -f 7614 8425 9433 -f 9433 8425 7610 -f 7610 8423 9433 -f 9433 8423 8418 -f 9433 8418 8703 -f 8119 8115 7611 -f 7611 8115 8428 -f 8428 8427 7611 -f 7611 8427 7612 -f 7611 7612 7614 -f 7614 7612 7613 -f 7614 7613 8425 -f 9054 9220 9249 -f 7615 9054 9441 -f 9254 9255 9298 -f 9251 9254 9441 -f 7589 9052 9441 -f 9441 9052 7616 -f 9441 7616 7615 -f 9054 9249 9441 -f 9441 9249 9250 -f 9441 9250 9251 -f 9300 7617 9441 -f 9441 7617 7618 -f 9441 7618 7620 -f 7622 9307 9441 -f 9441 9307 9308 -f 9441 9308 7619 -f 7619 9310 9441 -f 9441 9310 8085 -f 9441 8085 9446 -f 9254 9298 9441 -f 9441 9298 9299 -f 9441 9299 9300 -f 7620 9303 9441 -f 9441 9303 7621 -f 9441 7621 7622 -f 8912 8911 7644 -f 7632 9407 7693 -f 9030 7623 7723 -f 7723 7623 7774 -f 7723 7774 7776 -f 9179 7625 7624 -f 7624 7625 7626 -f 7624 7626 7740 -f 7740 7626 9029 -f 7627 9224 7682 -f 7682 9224 7707 -f 9238 7628 7629 -f 7629 7628 7694 -f 7629 7694 9372 -f 7691 7632 7693 -f 9336 9400 7630 -f 7630 9400 7631 -f 7630 7631 7691 -f 7691 7631 7632 -f 9336 7630 9337 -f 9337 7630 7633 -f 9337 7633 9338 -f 9338 7633 9339 -f 9339 7633 7634 -f 9339 7634 9341 -f 9341 7634 9343 -f 9343 7634 7688 -f 9343 7688 7635 -f 7635 7688 7637 -f 7635 7637 7636 -f 7636 7637 9355 -f 9355 7637 7638 -f 9355 7638 9358 -f 9358 7638 7685 -f 9358 7685 9356 -f 9208 9356 7639 -f 7639 9356 7685 -f 7639 7685 7640 -f 7640 7685 7684 -f 7640 7684 9150 -f 9150 7684 9149 -f 7645 7642 7641 -f 7641 7642 7643 -f 7641 7643 9149 -f 8911 8910 7644 -f 7644 8910 7645 -f 7644 7645 7646 -f 7725 8912 7696 -f 8779 8898 7725 -f 7725 8898 8912 -f 7724 7647 8779 -f 8583 8585 7724 -f 7724 8585 7647 -f 7713 7649 7648 -f 7648 7649 8583 -f 7723 7776 7651 -f 7723 7651 7650 -f 7651 7652 7650 -f 7650 7652 7653 -f 7650 7653 7654 -f 7653 7777 7654 -f 7654 7777 7655 -f 7654 7655 7656 -f 7655 7657 7656 -f 7656 7657 7781 -f 7656 7781 7658 -f 7781 7659 7658 -f 7658 7659 7780 -f 7658 7780 7661 -f 7780 7660 7661 -f 7661 7660 7662 -f 7661 7662 7664 -f 7662 7663 7664 -f 7664 7663 7787 -f 7664 7787 7666 -f 7787 7786 7666 -f 7666 7786 7665 -f 7666 7665 7667 -f 7665 7668 7667 -f 7667 7668 7669 -f 7667 7669 7670 -f 7669 7791 7670 -f 7670 7791 7790 -f 7670 7790 7717 -f 7790 7789 7717 -f 7717 7789 7671 -f 7717 7671 7673 -f 7671 7672 7673 -f 7673 7672 7795 -f 7673 7795 7715 -f 7645 7641 7646 -f 7646 7641 7683 -f 7646 7683 7697 -f 7697 7683 7686 -f 7697 7686 7699 -f 7699 7686 7675 -f 7699 7675 7674 -f 7674 7675 7687 -f 7674 7687 7701 -f 7701 7687 7689 -f 7701 7689 7676 -f 7676 7689 7677 -f 7676 7677 7704 -f 7704 7677 7690 -f 7704 7690 7705 -f 7705 7690 7678 -f 7705 7678 7679 -f 7679 7678 7692 -f 7679 7692 7680 -f 7680 7692 7694 -f 7680 7694 7681 -f 7681 7694 7628 -f 7681 7628 7682 -f 7682 7628 9238 -f 7682 9238 7627 -f 7641 9149 7684 -f 7641 7684 7683 -f 7683 7684 7685 -f 7683 7685 7686 -f 7686 7685 7638 -f 7686 7638 7675 -f 7675 7638 7637 -f 7675 7637 7687 -f 7687 7637 7688 -f 7687 7688 7689 -f 7689 7688 7634 -f 7689 7634 7677 -f 7677 7634 7633 -f 7677 7633 7690 -f 7690 7633 7630 -f 7690 7630 7678 -f 7678 7630 7691 -f 7678 7691 7692 -f 7692 7691 7693 -f 7692 7693 7694 -f 7694 7693 9407 -f 7694 9407 9372 -f 7795 7695 7715 -f 7715 7695 7793 -f 7715 7793 7709 -f 8912 7644 7696 -f 7696 7644 7646 -f 7696 7646 7727 -f 7727 7646 7697 -f 7727 7697 7698 -f 7698 7697 7699 -f 7698 7699 7729 -f 7729 7699 7674 -f 7729 7674 7700 -f 7700 7674 7701 -f 7700 7701 7702 -f 7702 7701 7676 -f 7702 7676 7703 -f 7703 7676 7704 -f 7703 7704 7730 -f 7730 7704 7705 -f 7730 7705 7733 -f 7733 7705 7679 -f 7733 7679 7734 -f 7734 7679 7680 -f 7734 7680 7736 -f 7736 7680 7681 -f 7736 7681 7738 -f 7738 7681 7682 -f 7738 7682 7706 -f 7706 7682 7707 -f 7706 7707 7708 -f 7708 7707 9222 -f 7708 9222 7739 -f 7793 7710 7709 -f 7709 7710 7711 -f 7709 7711 7648 -f 7648 7711 7712 -f 7648 7712 7713 -f 8583 7724 7648 -f 7648 7724 7726 -f 7648 7726 7709 -f 7709 7726 7714 -f 7709 7714 7715 -f 7715 7714 7716 -f 7715 7716 7673 -f 7673 7716 7728 -f 7673 7728 7717 -f 7717 7728 7718 -f 7717 7718 7670 -f 7670 7718 7719 -f 7670 7719 7667 -f 7667 7719 7731 -f 7667 7731 7666 -f 7666 7731 7732 -f 7666 7732 7664 -f 7664 7732 7720 -f 7664 7720 7661 -f 7661 7720 7735 -f 7661 7735 7658 -f 7658 7735 7737 -f 7658 7737 7656 -f 7656 7737 7721 -f 7656 7721 7654 -f 7654 7721 7722 -f 7654 7722 7650 -f 7650 7722 7740 -f 7650 7740 7723 -f 7723 7740 9029 -f 7723 9029 9030 -f 8779 7725 7724 -f 7724 7725 7696 -f 7724 7696 7726 -f 7726 7696 7727 -f 7726 7727 7714 -f 7714 7727 7698 -f 7714 7698 7716 -f 7716 7698 7729 -f 7716 7729 7728 -f 7728 7729 7700 -f 7728 7700 7718 -f 7718 7700 7702 -f 7718 7702 7719 -f 7719 7702 7703 -f 7719 7703 7731 -f 7731 7703 7730 -f 7731 7730 7732 -f 7732 7730 7733 -f 7732 7733 7720 -f 7720 7733 7734 -f 7720 7734 7735 -f 7735 7734 7736 -f 7735 7736 7737 -f 7737 7736 7738 -f 7737 7738 7721 -f 7721 7738 7706 -f 7721 7706 7722 -f 7722 7706 7708 -f 7722 7708 7740 -f 7740 7708 7739 -f 7740 7739 7624 -f 8940 7741 7742 -f 8485 7745 7746 -f 8487 8489 7743 -f 7823 8507 7713 -f 8489 7744 7823 -f 7823 7744 8505 -f 7823 8505 8507 -f 8487 7743 7747 -f 7746 7745 7747 -f 7746 7747 7842 -f 8482 8486 7841 -f 7841 8486 8485 -f 8482 7824 7748 -f 8479 7748 8685 -f 8685 7748 7824 -f 8685 7824 7750 -f 7750 7824 7749 -f 7752 8652 7749 -f 7749 8652 7750 -f 7829 8636 7751 -f 7751 8636 7753 -f 7751 7753 7752 -f 7752 7753 7754 -f 7752 7754 8652 -f 7830 8631 7829 -f 7829 8631 8636 -f 7758 8632 7830 -f 7830 8632 7755 -f 7830 7755 8631 -f 7831 7756 7758 -f 7758 7756 7757 -f 7758 7757 8632 -f 7833 8618 7759 -f 7759 8618 7760 -f 7759 7760 7831 -f 7831 7760 8621 -f 7831 8621 7756 -f 7761 8619 7833 -f 7833 8619 8618 -f 7761 7833 7762 -f 7762 7833 7763 -f 7762 7763 8613 -f 8613 7763 7765 -f 8613 7765 8614 -f 8614 7765 7764 -f 7764 7765 7766 -f 7764 7766 8609 -f 8609 7766 8607 -f 8607 7766 7767 -f 8607 7767 8606 -f 8606 7767 8605 -f 8605 7767 7768 -f 8605 7768 7769 -f 7769 7768 7770 -f 7769 7770 8604 -f 7840 7771 7770 -f 7770 7771 8604 -f 8795 7771 8933 -f 8933 7771 8935 -f 8935 7771 7840 -f 7772 8938 7839 -f 7772 7839 8939 -f 7775 8945 7773 -f 7776 7774 7775 -f 7775 7774 8945 -f 7779 7651 7775 -f 7775 7651 7776 -f 7778 7782 7655 -f 7655 7777 7778 -f 7778 7777 7653 -f 7778 7653 7779 -f 7779 7653 7652 -f 7779 7652 7651 -f 7820 7783 7780 -f 7780 7659 7820 -f 7820 7659 7781 -f 7820 7781 7782 -f 7782 7781 7657 -f 7782 7657 7655 -f 7818 7785 7787 -f 7787 7663 7818 -f 7818 7663 7662 -f 7818 7662 7783 -f 7783 7662 7660 -f 7783 7660 7780 -f 7784 7792 7669 -f 7669 7668 7784 -f 7784 7668 7665 -f 7784 7665 7785 -f 7785 7665 7786 -f 7785 7786 7787 -f 7788 7796 7671 -f 7671 7789 7788 -f 7788 7789 7790 -f 7788 7790 7792 -f 7792 7790 7791 -f 7792 7791 7669 -f 7794 7813 7793 -f 7793 7695 7794 -f 7794 7695 7795 -f 7794 7795 7796 -f 7796 7795 7672 -f 7796 7672 7671 -f 7747 7743 7842 -f 7842 7743 7797 -f 7842 7797 7799 -f 7799 7797 7798 -f 7799 7798 7800 -f 7800 7798 7814 -f 7800 7814 7844 -f 7844 7814 7815 -f 7844 7815 7801 -f 7801 7815 7802 -f 7801 7802 7803 -f 7803 7802 7816 -f 7803 7816 7804 -f 7804 7816 7817 -f 7804 7817 7847 -f 7847 7817 7805 -f 7847 7805 7806 -f 7806 7805 7819 -f 7806 7819 7848 -f 7848 7819 7807 -f 7848 7807 7808 -f 7808 7807 7821 -f 7808 7821 7849 -f 7849 7821 7809 -f 7849 7809 7810 -f 7810 7809 7811 -f 7810 7811 7812 -f 7812 7811 7822 -f 7812 7822 7742 -f 7742 7822 8943 -f 7742 8943 8940 -f 8489 7823 7743 -f 7743 7823 7813 -f 7743 7813 7797 -f 7797 7813 7794 -f 7797 7794 7798 -f 7798 7794 7796 -f 7798 7796 7814 -f 7814 7796 7788 -f 7814 7788 7815 -f 7815 7788 7792 -f 7815 7792 7802 -f 7802 7792 7784 -f 7802 7784 7816 -f 7816 7784 7785 -f 7816 7785 7817 -f 7817 7785 7818 -f 7817 7818 7805 -f 7805 7818 7783 -f 7805 7783 7819 -f 7819 7783 7820 -f 7819 7820 7807 -f 7807 7820 7782 -f 7807 7782 7821 -f 7821 7782 7778 -f 7821 7778 7809 -f 7809 7778 7779 -f 7809 7779 7811 -f 7811 7779 7775 -f 7811 7775 7822 -f 7822 7775 7773 -f 7822 7773 8943 -f 7713 7712 7823 -f 7823 7712 7711 -f 7823 7711 7813 -f 7813 7711 7710 -f 7813 7710 7793 -f 8482 7841 7824 -f 7824 7841 7825 -f 7824 7825 7749 -f 7749 7825 7826 -f 7749 7826 7752 -f 7752 7826 7843 -f 7752 7843 7751 -f 7751 7843 7827 -f 7751 7827 7829 -f 7829 7827 7828 -f 7829 7828 7830 -f 7830 7828 7845 -f 7830 7845 7758 -f 7758 7845 7846 -f 7758 7846 7831 -f 7831 7846 7832 -f 7831 7832 7759 -f 7759 7832 7834 -f 7759 7834 7833 -f 7833 7834 7835 -f 7833 7835 7763 -f 7763 7835 7836 -f 7763 7836 7765 -f 7765 7836 7850 -f 7765 7850 7766 -f 7766 7850 7837 -f 7766 7837 7767 -f 7767 7837 7838 -f 7767 7838 7768 -f 7768 7838 7839 -f 7768 7839 7770 -f 7770 7839 8938 -f 7770 8938 7840 -f 7840 8938 8937 -f 7840 8937 8935 -f 8485 7746 7841 -f 7841 7746 7842 -f 7841 7842 7825 -f 7825 7842 7799 -f 7825 7799 7826 -f 7826 7799 7800 -f 7826 7800 7843 -f 7843 7800 7844 -f 7843 7844 7827 -f 7827 7844 7801 -f 7827 7801 7828 -f 7828 7801 7803 -f 7828 7803 7845 -f 7845 7803 7804 -f 7845 7804 7846 -f 7846 7804 7847 -f 7846 7847 7832 -f 7832 7847 7806 -f 7832 7806 7834 -f 7834 7806 7848 -f 7834 7848 7835 -f 7835 7848 7808 -f 7835 7808 7836 -f 7836 7808 7849 -f 7836 7849 7850 -f 7850 7849 7810 -f 7850 7810 7837 -f 7837 7810 7812 -f 7837 7812 7838 -f 7838 7812 7742 -f 7838 7742 7839 -f 7839 7742 7741 -f 7839 7741 8939 -f 7887 7886 7944 -f 7853 7859 8386 -f 8358 8361 7909 -f 7909 8361 7854 -f 7909 7854 7908 -f 7908 7854 8360 -f 7908 8360 7855 -f 7904 8364 8358 -f 8364 7856 8371 -f 8371 7856 8369 -f 8369 7856 7993 -f 8369 7993 8368 -f 8368 7993 7956 -f 8368 7956 8373 -f 8373 7955 7857 -f 7857 7955 7958 -f 7857 7958 8379 -f 8379 7958 7858 -f 7858 7958 7960 -f 7858 7960 7930 -f 7930 7960 7931 -f 8386 7859 7860 -f 8386 7860 8387 -f 8387 7860 7932 -f 8387 7932 7861 -f 8389 7913 7862 -f 7862 7913 7915 -f 7862 7915 8432 -f 7864 8433 7915 -f 7915 8433 8432 -f 7863 8426 7864 -f 7864 8426 8433 -f 7917 8421 7863 -f 7863 8421 8426 -f 7865 8420 7866 -f 7866 8420 7917 -f 7917 8420 8421 -f 7918 7919 8603 -f 7865 7866 8699 -f 8699 7866 7918 -f 8699 7918 8689 -f 8689 7918 8603 -f 8689 8603 8688 -f 7919 7867 8603 -f 7852 7920 7868 -f 7868 7920 7869 -f 7943 7870 8610 -f 8610 7870 7975 -f 7871 8623 8010 -f 8010 8623 7872 -f 7990 8628 7991 -f 8628 7990 7873 -f 8628 7873 8633 -f 7954 7929 7874 -f 7874 7929 7875 -f 7874 7875 7876 -f 7878 8400 8402 -f 8402 8600 7878 -f 7878 8600 7877 -f 7877 8600 8653 -f 7877 8653 8639 -f 8400 7878 8408 -f 8408 7878 7927 -f 8408 7927 7879 -f 7879 7927 7926 -f 7879 7926 8255 -f 8255 7926 7923 -f 8255 7923 8254 -f 8254 7923 7922 -f 8254 7922 8270 -f 7882 7851 7922 -f 7922 7851 8270 -f 7921 7881 7880 -f 7880 7881 7882 -f 7882 7881 7851 -f 7883 7884 7885 -f 7885 7884 7921 -f 7886 7887 7889 -f 7887 7888 7889 -f 7889 7888 7890 -f 7889 7890 7883 -f 7883 7890 8253 -f 7883 8253 7884 -f 7892 7893 7945 -f 7945 7893 7944 -f 7977 7896 8231 -f 8231 7891 7977 -f 7977 7891 8236 -f 7977 8236 7892 -f 7892 8236 8235 -f 7892 8235 7893 -f 7899 8232 7894 -f 7894 8232 7896 -f 7896 8232 7895 -f 7896 7895 8231 -f 7902 7898 7897 -f 7897 7898 7899 -f 8223 8225 7900 -f 7900 8225 7901 -f 7900 7901 7902 -f 7902 7901 8226 -f 7902 8226 7898 -f 8223 7903 7904 -f 8223 7904 7906 -f 8358 7909 7904 -f 7904 7909 7905 -f 7904 7905 7906 -f 7855 7907 7908 -f 7907 8126 7908 -f 7908 8126 7910 -f 7908 7910 7909 -f 7909 7910 7911 -f 7909 7911 7905 -f 7861 7932 8389 -f 8389 7932 7912 -f 8389 7912 7913 -f 7913 7912 7914 -f 7913 7914 7915 -f 7915 7914 7916 -f 7915 7916 7864 -f 7864 7916 7935 -f 7864 7935 7863 -f 7863 7935 7937 -f 7863 7937 7917 -f 7917 7937 7939 -f 7917 7939 7866 -f 7866 7939 7941 -f 7866 7941 7918 -f 7918 7941 7869 -f 7918 7869 7919 -f 7919 7869 7920 -f 7919 7920 7867 -f 7921 7880 7885 -f 7885 7880 7882 -f 7885 7882 7947 -f 7947 7882 7922 -f 7947 7922 7949 -f 7949 7922 7923 -f 7949 7923 7924 -f 7924 7923 7926 -f 7924 7926 7925 -f 7925 7926 7927 -f 7925 7927 7928 -f 7928 7927 7878 -f 7928 7878 7953 -f 7953 7878 7877 -f 7953 7877 7954 -f 7954 7877 8639 -f 7954 8639 7929 -f 7930 7931 7853 -f 7853 7931 7962 -f 7853 7962 7859 -f 7859 7962 7963 -f 7859 7963 7860 -f 7860 7963 7933 -f 7860 7933 7932 -f 7932 7933 7966 -f 7932 7966 7912 -f 7912 7966 7934 -f 7912 7934 7914 -f 7914 7934 7969 -f 7914 7969 7916 -f 7916 7969 7936 -f 7916 7936 7935 -f 7935 7936 7938 -f 7935 7938 7937 -f 7937 7938 7973 -f 7937 7973 7939 -f 7939 7973 7940 -f 7939 7940 7941 -f 7941 7940 7942 -f 7941 7942 7869 -f 7869 7942 7870 -f 7869 7870 7868 -f 7868 7870 7943 -f 7868 7943 7852 -f 7944 7886 7945 -f 7945 7886 7889 -f 7945 7889 7981 -f 7981 7889 7883 -f 7981 7883 7983 -f 7983 7883 7885 -f 7983 7885 7946 -f 7946 7885 7947 -f 7946 7947 7948 -f 7948 7947 7949 -f 7948 7949 7950 -f 7950 7949 7924 -f 7950 7924 7985 -f 7985 7924 7925 -f 7985 7925 7951 -f 7951 7925 7928 -f 7951 7928 7987 -f 7987 7928 7953 -f 7987 7953 7952 -f 7952 7953 7954 -f 7952 7954 7989 -f 7989 7954 7874 -f 7989 7874 7873 -f 7873 7874 7876 -f 7873 7876 8633 -f 8373 7956 7955 -f 7955 7956 7957 -f 7955 7957 7958 -f 7958 7957 7997 -f 7958 7997 7960 -f 7960 7997 7959 -f 7960 7959 7931 -f 7931 7959 7961 -f 7931 7961 7962 -f 7962 7961 7964 -f 7962 7964 7963 -f 7963 7964 8000 -f 7963 8000 7933 -f 7933 8000 7965 -f 7933 7965 7966 -f 7966 7965 7967 -f 7966 7967 7934 -f 7934 7967 7968 -f 7934 7968 7969 -f 7969 7968 7970 -f 7969 7970 7936 -f 7936 7970 7971 -f 7936 7971 7938 -f 7938 7971 7972 -f 7938 7972 7973 -f 7973 7972 8006 -f 7973 8006 7940 -f 7940 8006 7974 -f 7940 7974 7942 -f 7942 7974 8009 -f 7942 8009 7870 -f 7870 8009 8010 -f 7870 8010 7975 -f 7975 8010 7872 -f 7975 7872 8610 -f 7899 7894 7897 -f 7897 7894 7896 -f 7897 7896 7976 -f 7976 7896 7977 -f 7976 7977 7978 -f 7978 7977 7892 -f 7978 7892 8011 -f 8011 7892 7945 -f 8011 7945 7979 -f 7979 7945 7981 -f 7979 7981 7980 -f 7980 7981 7983 -f 7980 7983 7982 -f 7982 7983 7946 -f 7982 7946 7984 -f 7984 7946 7948 -f 7984 7948 8015 -f 8015 7948 7950 -f 8015 7950 8016 -f 8016 7950 7985 -f 8016 7985 8017 -f 8017 7985 7951 -f 8017 7951 7986 -f 7986 7951 7987 -f 7986 7987 7988 -f 7988 7987 7952 -f 7988 7952 8019 -f 8019 7952 7989 -f 8019 7989 8020 -f 8020 7989 7873 -f 8020 7873 8021 -f 8021 7873 7990 -f 8021 7990 8022 -f 8022 7990 7991 -f 8022 7991 8627 -f 8364 7904 7903 -f 8364 7903 7856 -f 7856 7903 7992 -f 7856 7992 7993 -f 7993 7992 7994 -f 7993 7994 7956 -f 7956 7994 7995 -f 7956 7995 7957 -f 7957 7995 7996 -f 7957 7996 7997 -f 7997 7996 8012 -f 7997 8012 7959 -f 7959 8012 7998 -f 7959 7998 7961 -f 7961 7998 8013 -f 7961 8013 7964 -f 7964 8013 7999 -f 7964 7999 8000 -f 8000 7999 8014 -f 8000 8014 7965 -f 7965 8014 8001 -f 7965 8001 7967 -f 7967 8001 8002 -f 7967 8002 7968 -f 7968 8002 8003 -f 7968 8003 7970 -f 7970 8003 8018 -f 7970 8018 7971 -f 7971 8018 8004 -f 7971 8004 7972 -f 7972 8004 8005 -f 7972 8005 8006 -f 8006 8005 8007 -f 8006 8007 7974 -f 7974 8007 8008 -f 7974 8008 8009 -f 8009 8008 8023 -f 8009 8023 8010 -f 8010 8023 8624 -f 8010 8624 7871 -f 8223 7900 7903 -f 7903 7900 7902 -f 7903 7902 7992 -f 7992 7902 7897 -f 7992 7897 7994 -f 7994 7897 7976 -f 7994 7976 7995 -f 7995 7976 7978 -f 7995 7978 7996 -f 7996 7978 8011 -f 7996 8011 8012 -f 8012 8011 7979 -f 8012 7979 7998 -f 7998 7979 7980 -f 7998 7980 8013 -f 8013 7980 7982 -f 8013 7982 7999 -f 7999 7982 7984 -f 7999 7984 8014 -f 8014 7984 8015 -f 8014 8015 8001 -f 8001 8015 8016 -f 8001 8016 8002 -f 8002 8016 8017 -f 8002 8017 8003 -f 8003 8017 7986 -f 8003 7986 8018 -f 8018 7986 7988 -f 8018 7988 8004 -f 8004 7988 8019 -f 8004 8019 8005 -f 8005 8019 8020 -f 8005 8020 8007 -f 8007 8020 8021 -f 8007 8021 8008 -f 8008 8021 8022 -f 8008 8022 8023 -f 8023 8022 8627 -f 8023 8627 8624 -f 8039 9440 8396 -f 8396 9440 9443 -f 8455 8025 8024 -f 8396 9443 8452 -f 8452 9443 8024 -f 8452 8024 8453 -f 8453 8024 8025 -f 8026 8460 8459 -f 8459 8458 8026 -f 8026 8458 8457 -f 8026 8457 8024 -f 8024 8457 8456 -f 8024 8456 8455 -f 8468 8027 8048 -f 8048 8027 8469 -f 8048 8469 8026 -f 8026 8469 8028 -f 8026 8028 8460 -f 8287 8135 8286 -f 8286 8135 8029 -f 8286 8029 8285 -f 8285 8029 8283 -f 8283 8029 8030 -f 8030 8029 8031 -f 8030 8031 8269 -f 8269 8031 8032 -f 8032 8031 8037 -f 8032 8037 8263 -f 8263 8037 8262 -f 8262 8037 8292 -f 8262 8292 8261 -f 8033 9438 8034 -f 8034 9438 9437 -f 8034 9437 8305 -f 8033 8035 9438 -f 9438 8035 8036 -f 9438 8036 8037 -f 8037 8036 8293 -f 8037 8293 8292 -f 9436 8038 9435 -f 9435 8038 8310 -f 9435 8310 8309 -f 8309 8308 9435 -f 9435 8308 8307 -f 9435 8307 9437 -f 9437 8307 8306 -f 9437 8306 8305 -f 9436 9440 8039 -f 8039 8040 9436 -f 9436 8040 8041 -f 9436 8041 8313 -f 8313 8312 9436 -f 9436 8312 8311 -f 9436 8311 8038 -f 8835 8042 8048 -f 8048 8042 8043 -f 8045 8566 8048 -f 8048 8566 8568 -f 8048 8890 8049 -f 8043 8915 8048 -f 8048 8915 8044 -f 8048 8044 8045 -f 8568 8569 8048 -f 8048 8569 8046 -f 8048 8046 8468 -f 9447 8047 8048 -f 8048 8047 8889 -f 8048 8889 8890 -f 8854 8855 8048 -f 8048 8855 8851 -f 8851 8845 8048 -f 8048 8845 8834 -f 8048 8834 8835 -f 8049 8881 8048 -f 8048 8881 8872 -f 8048 8872 8873 -f 8873 8857 8048 -f 8048 8857 8050 -f 8048 8050 8854 -f 8051 9074 9077 -f 8051 8052 8069 -f 9077 9080 8051 -f 8051 9080 8052 -f 9074 8051 8070 -f 9074 8070 8053 -f 9197 8054 8055 -f 8055 8054 9073 -f 8055 9073 8075 -f 8075 9073 9071 -f 9311 9197 8055 -f 9311 8055 9315 -f 9315 8055 8056 -f 8057 9320 8058 -f 8057 8058 8056 -f 8056 8058 8059 -f 8056 8059 9315 -f 9324 9320 8060 -f 9324 8060 9332 -f 9413 9392 8061 -f 8061 9392 8062 -f 8063 8064 8061 -f 8061 8064 9414 -f 8061 9414 9413 -f 8063 9259 8064 -f 8064 9259 9258 -f 8064 9258 9424 -f 9424 9258 9256 -f 9424 9256 9369 -f 9261 9260 8063 -f 8063 9260 9259 -f 8074 9263 8060 -f 9263 8065 8060 -f 8060 8065 8066 -f 8060 8066 8073 -f 8073 8066 9261 -f 9266 9265 8068 -f 8068 9265 8074 -f 8074 9265 8067 -f 8074 8067 9263 -f 9266 8068 8072 -f 8072 8068 8070 -f 8069 9269 8051 -f 8051 9269 8070 -f 8070 9269 8071 -f 8070 8071 8072 -f 8073 9261 8063 -f 8073 8063 8060 -f 8060 8063 8061 -f 8060 8061 9332 -f 9332 8061 8062 -f 9320 8057 8060 -f 8060 8057 8056 -f 8060 8056 8074 -f 8074 8056 8055 -f 8074 8055 8068 -f 8068 8055 8075 -f 8068 8075 8070 -f 8070 8075 9071 -f 8070 9071 8053 -f 8078 8076 8108 -f 9192 8076 8078 -f 8080 9192 8077 -f 8077 9192 8078 -f 8079 9188 8077 -f 8077 9188 8080 -f 9442 8081 9434 -f 9434 8081 9191 -f 9434 9191 8077 -f 8077 9191 8079 -f 8082 9185 8083 -f 8082 8083 9442 -f 9442 8083 8081 -f 9185 8082 8084 -f 8084 8082 9446 -f 8084 9446 8085 -f 9085 8086 9448 -f 8087 8829 8830 -f 8774 9439 8832 -f 8832 9439 8087 -f 8832 8087 8088 -f 8088 8087 8830 -f 8090 8818 8092 -f 8092 8818 8089 -f 8092 8089 8087 -f 8087 8089 8827 -f 8087 8827 8829 -f 9448 8086 8092 -f 8997 8090 9084 -f 9084 8090 8092 -f 9084 8092 8091 -f 8091 8092 8086 -f 8097 8093 9448 -f 9448 8093 8094 -f 9448 8094 9085 -f 9093 8095 9464 -f 9464 8095 8096 -f 9464 8096 9448 -f 9448 8096 9087 -f 9448 9087 8097 -f 8098 9095 9444 -f 9444 9095 9464 -f 9464 9095 9094 -f 9464 9094 9093 -f 9100 9099 8099 -f 9099 9098 8099 -f 8099 9098 9097 -f 8099 9097 9444 -f 9444 9097 8098 -f 8100 9067 8105 -f 8105 9067 8101 -f 8105 8101 9107 -f 9107 9106 8105 -f 8105 9106 8102 -f 8105 8102 8099 -f 8099 8102 9100 -f 8103 8104 8105 -f 8105 8104 9069 -f 8105 9069 8100 -f 9076 8106 8103 -f 8103 8106 8107 -f 8103 8107 8104 -f 8078 8108 8103 -f 8103 8108 9075 -f 8103 9075 9076 -f 9449 8109 8110 -f 8110 8109 8765 -f 8765 8763 8110 -f 8110 8763 8111 -f 8110 8111 9447 -f 9447 8111 8112 -f 9447 8112 8047 -f 8770 8769 9445 -f 9445 8769 9449 -f 9449 8769 8767 -f 9449 8767 8109 -f 8772 8771 9445 -f 9445 8771 8770 -f 8774 8150 9439 -f 8150 8773 9439 -f 9439 8773 8114 -f 8773 8113 8114 -f 8114 8113 9445 -f 9445 8113 8772 -f 8395 8115 8119 -f 8116 8118 8382 -f 8382 8118 8122 -f 8382 8122 8380 -f 8116 8117 8118 -f 8118 8117 8391 -f 8118 8391 8119 -f 8119 8391 8120 -f 8119 8120 8395 -f 8366 9430 8121 -f 8121 9430 9429 -f 8121 9429 8363 -f 8366 8374 9430 -f 9430 8374 8376 -f 9430 8376 8122 -f 8122 8376 8123 -f 8122 8123 8380 -f 8125 8126 7907 -f 7907 7855 9428 -f 9428 7855 8124 -f 9428 8124 9429 -f 9429 8124 8362 -f 9429 8362 8363 -f 8125 7907 9428 -f 8221 8245 8127 -f 8127 8245 8220 -f 8127 8220 8125 -f 8125 8220 8219 -f 8125 8219 8126 -f 8221 8127 8128 -f 8128 8127 8132 -f 8128 8132 8129 -f 8237 8130 8131 -f 8131 8130 8133 -f 8131 8133 8132 -f 8132 8133 8129 -f 8237 8131 8238 -f 8238 8131 8134 -f 8238 8134 8239 -f 8287 8242 8135 -f 8135 8242 8136 -f 8135 8136 8134 -f 8134 8136 8239 -f 8149 8816 8148 -f 8154 8159 9132 -f 8137 8891 8761 -f 8137 8761 8778 -f 8891 8137 8138 -f 8138 8137 8139 -f 8138 8139 8882 -f 8157 8874 8140 -f 8157 8140 8139 -f 8139 8140 8882 -f 8142 8143 8869 -f 8142 8869 8157 -f 8157 8869 8874 -f 8153 8141 8160 -f 8160 8141 8862 -f 8160 8862 8142 -f 8142 8862 8143 -f 8145 8841 8146 -f 8144 8852 8153 -f 8153 8852 8141 -f 9151 8839 8145 -f 9151 8145 9160 -f 9145 9147 8152 -f 9160 8145 8146 -f 9160 8146 9159 -f 9159 8146 8152 -f 9159 8152 9157 -f 9157 8152 9147 -f 9157 9147 8147 -f 9132 8159 9129 -f 9129 8159 8158 -f 9129 8158 9127 -f 8148 8816 9126 -f 8148 9126 8158 -f 8158 9126 9127 -f 8156 8155 8819 -f 8156 8819 8148 -f 8148 8819 8820 -f 8148 8820 8149 -f 8150 8825 8778 -f 8778 8825 8137 -f 8825 8824 8137 -f 8137 8824 8151 -f 8137 8151 8139 -f 8139 8151 8822 -f 8139 8822 8155 -f 8841 8144 8146 -f 8146 8144 8153 -f 8146 8153 8152 -f 8152 8153 8160 -f 8152 8160 9145 -f 9145 8160 8154 -f 8155 8156 8139 -f 8139 8156 8148 -f 8139 8148 8157 -f 8157 8148 8158 -f 8157 8158 8142 -f 8142 8158 8159 -f 8142 8159 8160 -f 8160 8159 8154 -f 8184 8161 8162 -f 9139 9140 8174 -f 9121 9195 8182 -f 8164 9105 8165 -f 8164 8165 9121 -f 8163 9102 8166 -f 8166 9103 8163 -f 8163 9103 8167 -f 8171 9089 8163 -f 9089 8168 8163 -f 8163 8168 9091 -f 8163 9091 9102 -f 8169 9122 8170 -f 8170 9122 9081 -f 9081 9082 8170 -f 8170 9082 8171 -f 8169 8170 8172 -f 8172 8170 8173 -f 8172 8173 9130 -f 9140 9141 8174 -f 8174 9141 9143 -f 8174 9143 8173 -f 8173 9143 9130 -f 9205 9139 8175 -f 8175 9139 8174 -f 8175 8174 9366 -f 9366 8174 8176 -f 8177 9406 9344 -f 9345 8179 9344 -f 9344 8179 8181 -f 9344 8181 8177 -f 8178 9322 9328 -f 8178 9328 8179 -f 8179 9328 8180 -f 8179 8180 8181 -f 9121 8182 8164 -f 8164 8182 9314 -f 8164 9314 8178 -f 8178 9314 9317 -f 8178 9317 9322 -f 8170 8171 8163 -f 8170 8163 8173 -f 8173 8163 8183 -f 8173 8183 8174 -f 8174 8183 8162 -f 8174 8162 8176 -f 8176 8162 8161 -f 8167 9105 8163 -f 8163 9105 8164 -f 8163 8164 8183 -f 8183 8164 8178 -f 8183 8178 8162 -f 8162 8178 8179 -f 8162 8179 8184 -f 8184 8179 9345 -f 8190 8185 8189 -f 8189 8185 8974 -f 8189 8974 8975 -f 8975 8976 8189 -f 8189 8976 8186 -f 8189 8186 8187 -f 8187 8188 8189 -f 8189 8188 9023 -f 8189 9023 9041 -f 9041 9023 9022 -f 9041 9022 9018 -f 9043 8971 8189 -f 8189 8971 8972 -f 8189 8972 8190 -f 8971 8702 8191 -f 8191 8702 8701 -f 9043 8192 8971 -f 8971 8192 9061 -f 8971 9061 8702 -f 8702 9061 9062 -f 8712 8710 9062 -f 9062 8710 8709 -f 9062 8709 8702 -f 9065 8197 9062 -f 9062 8197 8713 -f 9062 8713 8712 -f 8194 8996 8193 -f 8193 8198 8994 -f 8193 8994 8194 -f 8193 8996 8813 -f 8193 8813 8732 -f 8723 8196 8195 -f 8732 8723 8195 -f 8722 8721 8198 -f 8198 8721 8720 -f 8198 8720 8719 -f 8732 8195 8193 -f 8193 8195 8196 -f 8193 8196 8198 -f 8198 8196 8722 -f 9065 8991 8197 -f 8197 8991 8198 -f 8197 8198 8718 -f 8718 8198 8719 -f 8563 8201 8508 -f 8199 8565 8200 -f 8415 8199 8480 -f 8480 8199 8508 -f 8508 8199 8200 -f 8508 8200 8563 -f 8201 8202 8595 -f 8510 8203 8201 -f 8201 8203 8204 -f 8201 8204 8508 -f 8208 8512 8201 -f 8201 8512 8205 -f 8201 8205 8510 -f 8595 8206 8201 -f 8201 8206 8207 -f 8201 8207 8598 -f 8598 8515 8201 -f 8201 8515 8514 -f 8201 8514 8208 -f 8565 8199 8209 -f 8209 8199 8296 -f 8209 8296 8297 -f 8297 8300 8209 -f 8209 8300 8335 -f 8209 8335 8210 -f 8210 8335 8336 -f 8210 8336 8211 -f 8211 8336 8476 -f 8476 8336 8214 -f 8214 8336 8337 -f 8214 8337 8212 -f 8212 8338 8214 -f 8214 8338 8339 -f 8214 8339 8213 -f 8213 8342 8214 -f 8214 8342 8215 -f 8215 8342 8341 -f 8215 8341 8334 -f 8473 8475 8214 -f 8214 8475 8476 -f 8215 8334 8216 -f 8215 8216 8214 -f 8214 8216 8471 -f 8471 8217 8214 -f 8217 8473 8214 -f 8242 8252 8250 -f 8232 7899 8248 -f 8218 7910 8126 -f 8126 8219 8218 -f 8218 8219 8220 -f 8218 8220 8245 -f 8223 7906 8224 -f 8224 7906 7905 -f 8224 7905 8218 -f 8218 7905 7911 -f 8218 7911 7910 -f 8221 8222 8245 -f 8223 8224 8246 -f 8223 8246 8225 -f 8225 8246 7901 -f 7901 8246 8247 -f 7901 8247 8226 -f 8221 8128 8222 -f 8222 8128 8129 -f 8222 8129 8227 -f 8227 8129 8133 -f 8227 8133 8228 -f 8248 7899 8247 -f 8247 7899 7898 -f 8247 7898 8226 -f 8228 8133 8130 -f 8228 8130 8229 -f 8229 8130 8237 -f 8229 8237 8249 -f 8230 8234 7891 -f 7891 8231 8230 -f 8230 8231 7895 -f 8230 7895 8248 -f 8248 7895 8232 -f 7944 8233 7887 -f 7887 8233 8251 -f 7887 8251 7888 -f 7944 7893 8233 -f 8233 7893 8235 -f 8233 8235 8234 -f 8234 8235 8236 -f 8234 8236 7891 -f 8237 8238 8249 -f 8249 8238 8239 -f 8249 8239 8240 -f 8240 8239 8136 -f 8240 8136 8250 -f 8250 8136 8242 -f 7888 8251 7890 -f 7890 8251 8241 -f 7890 8241 8253 -f 8242 8287 8243 -f 8242 8243 8252 -f 8252 8243 8244 -f 8218 8245 8224 -f 8224 8245 8222 -f 8224 8222 8246 -f 8246 8222 8227 -f 8246 8227 8247 -f 8247 8227 8228 -f 8247 8228 8248 -f 8248 8228 8229 -f 8248 8229 8230 -f 8230 8229 8249 -f 8230 8249 8234 -f 8234 8249 8240 -f 8234 8240 8233 -f 8233 8240 8250 -f 8233 8250 8251 -f 8251 8250 8252 -f 8251 8252 8241 -f 8241 8252 8244 -f 8241 8244 8274 -f 8253 8241 7884 -f 7884 8241 8274 -f 7884 8274 7921 -f 7921 8274 7881 -f 8268 8267 8273 -f 8351 8255 8258 -f 8260 8256 8265 -f 8265 8256 8352 -f 8265 8352 8257 -f 8257 8352 8258 -f 8258 8352 8351 -f 8261 8260 8259 -f 8262 8261 8263 -f 8255 8254 8258 -f 8258 8254 8264 -f 8258 8264 8257 -f 8257 8264 8266 -f 8257 8266 8265 -f 8265 8266 8277 -f 8261 8259 8263 -f 8263 8259 8278 -f 8263 8278 8032 -f 8254 8270 8264 -f 8264 8270 8267 -f 8264 8267 8266 -f 8266 8267 8268 -f 8266 8268 8277 -f 8277 8268 8271 -f 8032 8278 8269 -f 8269 8278 8282 -f 8269 8282 8030 -f 8272 8279 8271 -f 8267 8270 7851 -f 8267 7851 8273 -f 8273 7851 7881 -f 8280 8279 8276 -f 8276 8279 8272 -f 8276 8272 8275 -f 8271 8268 8272 -f 8272 8268 8273 -f 8272 8273 8275 -f 8275 8273 7881 -f 7881 8274 8275 -f 8275 8274 8276 -f 8276 8274 8280 -f 8280 8274 8244 -f 8260 8265 8259 -f 8259 8265 8277 -f 8259 8277 8278 -f 8278 8277 8271 -f 8278 8271 8282 -f 8282 8271 8279 -f 8282 8279 8284 -f 8284 8279 8280 -f 8284 8280 8281 -f 8281 8280 8244 -f 8281 8244 8243 -f 8030 8282 8283 -f 8283 8282 8284 -f 8283 8284 8285 -f 8285 8284 8281 -f 8285 8281 8286 -f 8286 8281 8243 -f 8286 8243 8287 -f 8347 8289 8288 -f 8349 8261 8292 -f 8289 8349 8291 -f 8348 8347 8290 -f 8349 8292 8291 -f 8291 8292 8293 -f 8291 8293 8294 -f 8294 8293 8036 -f 8294 8036 8302 -f 8415 8348 8199 -f 8199 8348 8295 -f 8199 8295 8296 -f 8296 8295 8298 -f 8296 8298 8297 -f 8297 8298 8299 -f 8297 8299 8300 -f 8300 8299 8301 -f 8300 8301 8335 -f 8036 8035 8302 -f 8302 8035 8033 -f 8302 8033 8303 -f 8303 8033 8034 -f 8303 8034 8304 -f 8034 8305 8304 -f 8304 8305 8306 -f 8304 8306 8316 -f 8316 8306 8307 -f 8307 8308 8316 -f 8316 8308 8309 -f 8316 8309 8317 -f 8317 8309 8310 -f 8317 8310 8038 -f 8317 8038 8318 -f 8038 8311 8318 -f 8318 8311 8312 -f 8318 8312 8313 -f 8318 8313 8041 -f 8318 8041 8320 -f 8320 8041 8040 -f 8289 8291 8288 -f 8288 8291 8294 -f 8288 8294 8314 -f 8314 8294 8302 -f 8314 8302 8315 -f 8315 8302 8303 -f 8315 8303 8322 -f 8322 8303 8304 -f 8322 8304 8323 -f 8323 8304 8316 -f 8323 8316 8324 -f 8324 8316 8317 -f 8324 8317 8326 -f 8326 8317 8318 -f 8326 8318 8319 -f 8319 8318 8320 -f 8319 8320 8333 -f 8040 8039 8320 -f 8320 8039 8397 -f 8320 8397 8333 -f 8333 8397 8399 -f 8333 8399 8398 -f 8347 8288 8290 -f 8290 8288 8314 -f 8290 8314 8321 -f 8321 8314 8315 -f 8321 8315 8327 -f 8327 8315 8322 -f 8327 8322 8328 -f 8328 8322 8323 -f 8328 8323 8325 -f 8325 8323 8324 -f 8325 8324 8330 -f 8330 8324 8326 -f 8330 8326 8332 -f 8332 8326 8319 -f 8332 8319 8341 -f 8341 8319 8333 -f 8348 8290 8295 -f 8295 8290 8321 -f 8295 8321 8298 -f 8298 8321 8327 -f 8298 8327 8299 -f 8299 8327 8328 -f 8299 8328 8301 -f 8301 8328 8325 -f 8301 8325 8329 -f 8329 8325 8330 -f 8329 8330 8331 -f 8331 8330 8332 -f 8331 8332 8340 -f 8340 8332 8341 -f 8341 8333 8334 -f 8334 8333 8398 -f 8335 8301 8336 -f 8336 8301 8329 -f 8336 8329 8337 -f 8337 8329 8331 -f 8337 8331 8212 -f 8212 8331 8338 -f 8338 8331 8340 -f 8338 8340 8339 -f 8339 8340 8213 -f 8213 8340 8341 -f 8213 8341 8342 -f 8343 8344 8357 -f 8260 8261 8356 -f 8350 8407 8409 -f 8350 8409 8345 -f 8345 8409 7879 -f 8412 8411 8344 -f 8344 8411 8357 -f 8357 8411 8410 -f 8412 8346 8414 -f 8414 8346 8348 -f 8414 8348 8415 -f 8346 8347 8348 -f 8356 8261 8349 -f 8260 8356 8354 -f 8352 8256 8353 -f 7879 8255 8345 -f 8345 8255 8351 -f 8345 8351 8350 -f 8350 8351 8352 -f 8346 8412 8344 -f 8346 8344 8347 -f 8347 8344 8343 -f 8347 8343 8289 -f 8289 8343 8349 -f 8256 8260 8353 -f 8353 8260 8354 -f 8353 8354 8355 -f 8410 8407 8355 -f 8355 8407 8350 -f 8355 8350 8353 -f 8353 8350 8352 -f 8356 8349 8343 -f 8356 8343 8354 -f 8354 8343 8357 -f 8354 8357 8355 -f 8355 8357 8410 -f 8358 8359 8361 -f 8361 8359 7854 -f 7855 8360 7854 -f 8124 7855 7854 -f 8124 7854 8362 -f 8362 7854 8363 -f 8358 8364 8359 -f 8359 8364 8365 -f 8364 8371 8365 -f 8365 8371 8370 -f 8121 8363 8365 -f 8121 8365 8366 -f 8366 8365 8367 -f 8366 8367 8374 -f 8368 8372 8369 -f 8369 8372 8370 -f 8369 8370 8371 -f 8368 8373 8372 -f 8372 8373 8378 -f 8374 8367 8376 -f 8376 8367 8375 -f 8376 8375 8123 -f 8123 8375 8377 -f 8123 8377 8380 -f 8373 7857 8378 -f 8378 7857 8379 -f 8378 8379 8383 -f 8380 8377 8382 -f 8382 8377 8381 -f 8382 8381 8116 -f 8116 8381 8392 -f 8116 8392 8117 -f 8379 7858 8383 -f 8383 7858 8384 -f 8384 7858 7930 -f 7930 7853 8384 -f 8384 7853 8386 -f 8384 8386 8385 -f 8385 8386 8388 -f 7854 8359 8363 -f 8363 8359 8365 -f 8365 8370 8367 -f 8367 8370 8372 -f 8367 8372 8375 -f 8375 8372 8378 -f 8375 8378 8377 -f 8377 8378 8383 -f 8377 8383 8381 -f 8381 8383 8384 -f 8381 8384 8392 -f 8392 8384 8385 -f 8392 8385 8393 -f 8393 8385 8388 -f 8393 8388 8394 -f 8386 8387 8388 -f 8388 8387 8447 -f 8387 7861 8447 -f 8447 7861 8389 -f 8447 8389 7862 -f 8388 8447 8390 -f 8388 8390 8394 -f 8394 8390 8435 -f 8117 8392 8391 -f 8391 8392 8393 -f 8391 8393 8120 -f 8120 8393 8394 -f 8120 8394 8395 -f 8395 8394 8435 -f 8395 8435 8115 -f 8471 8216 8334 -f 8039 8396 8397 -f 8397 8396 8451 -f 8471 8334 8462 -f 8462 8334 8398 -f 8462 8398 8450 -f 8450 8398 8451 -f 8451 8398 8399 -f 8451 8399 8397 -f 8401 8405 8411 -f 8400 8408 8409 -f 8600 8402 8406 -f 8402 8400 8406 -f 8406 8400 8409 -f 8406 8409 8404 -f 8404 8409 8407 -f 8404 8407 8403 -f 8403 8407 8410 -f 8412 8414 8413 -f 7879 8409 8408 -f 8405 8403 8410 -f 8405 8410 8411 -f 8411 8412 8401 -f 8401 8412 8413 -f 8480 8413 8414 -f 8480 8414 8415 -f 8428 8434 8440 -f 8416 8417 8424 -f 8424 8417 8418 -f 8418 8417 8552 -f 8418 8552 8703 -f 8422 8545 8542 -f 8420 8545 8421 -f 8421 8545 8422 -f 8421 8422 8426 -f 8426 8422 8429 -f 8418 8423 8424 -f 8424 8423 7610 -f 8424 7610 8436 -f 8436 7610 8425 -f 8436 8425 8439 -f 8430 8433 8429 -f 8429 8433 8426 -f 8425 7613 8439 -f 8439 7613 7612 -f 8439 7612 8440 -f 8440 7612 8427 -f 8440 8427 8428 -f 8542 8419 8422 -f 8422 8419 8446 -f 8422 8446 8429 -f 8429 8446 8444 -f 8429 8444 8430 -f 8430 8444 8443 -f 8430 8443 8431 -f 8431 8443 8449 -f 8431 8449 8448 -f 8448 7862 8432 -f 8448 8432 8431 -f 8431 8432 8430 -f 8430 8432 8433 -f 8428 8115 8434 -f 8434 8115 8435 -f 8434 8435 8390 -f 8416 8424 8437 -f 8437 8424 8436 -f 8437 8436 8438 -f 8438 8436 8439 -f 8438 8439 8445 -f 8445 8439 8440 -f 8445 8440 8441 -f 8441 8440 8434 -f 8441 8434 8442 -f 8442 8434 8390 -f 8390 8449 8442 -f 8442 8449 8443 -f 8442 8443 8441 -f 8441 8443 8444 -f 8441 8444 8445 -f 8445 8444 8446 -f 8445 8446 8438 -f 8438 8446 8419 -f 8438 8419 8437 -f 8437 8419 8542 -f 8437 8542 8416 -f 8447 7862 8448 -f 8447 8448 8449 -f 8447 8449 8390 -f 8450 8451 8454 -f 8451 8396 8452 -f 8450 8454 8462 -f 8471 8462 8472 -f 8451 8452 8454 -f 8454 8452 8453 -f 8454 8453 8025 -f 8454 8025 8463 -f 8463 8025 8455 -f 8463 8455 8456 -f 8463 8456 8464 -f 8456 8457 8464 -f 8464 8457 8458 -f 8464 8458 8459 -f 8464 8459 8465 -f 8465 8459 8460 -f 8465 8460 8028 -f 8465 8028 8461 -f 8462 8454 8472 -f 8472 8454 8463 -f 8472 8463 8464 -f 8472 8464 8466 -f 8466 8464 8465 -f 8466 8465 8461 -f 8466 8461 8474 -f 8474 8461 8467 -f 8474 8467 8470 -f 8027 8468 8570 -f 8028 8469 8461 -f 8461 8469 8027 -f 8461 8027 8467 -f 8467 8027 8570 -f 8467 8570 8470 -f 8471 8472 8217 -f 8217 8472 8466 -f 8217 8466 8473 -f 8473 8466 8474 -f 8473 8474 8475 -f 8475 8474 8470 -f 8475 8470 8476 -f 8477 8480 8508 -f 8477 8508 8490 -f 8479 8496 7748 -f 7748 8496 8481 -f 7748 8481 8482 -f 8482 8481 8484 -f 8482 8484 8486 -f 7747 7745 8483 -f 8483 7745 8501 -f 8501 7745 8485 -f 8501 8485 8484 -f 8484 8485 8486 -f 7747 8483 8487 -f 8487 8483 8488 -f 8487 8488 8489 -f 8489 8488 8504 -f 8489 8504 7744 -f 8478 8477 8490 -f 8478 8490 8522 -f 8522 8490 8509 -f 8522 8509 8491 -f 8491 8509 8511 -f 8491 8511 8521 -f 8521 8511 8492 -f 8521 8492 8520 -f 8520 8492 8493 -f 8520 8493 8494 -f 8494 8493 8513 -f 8494 8513 8495 -f 8495 8513 8516 -f 8495 8516 8517 -f 8496 8497 8498 -f 8496 8498 8481 -f 8481 8498 8499 -f 8481 8499 8484 -f 8484 8499 8500 -f 8484 8500 8501 -f 8501 8500 8502 -f 8501 8502 8483 -f 8483 8502 8503 -f 8483 8503 8488 -f 8488 8503 8519 -f 8488 8519 8504 -f 8504 8519 8518 -f 8504 8518 8506 -f 7744 8504 8505 -f 8505 8504 8506 -f 8505 8506 8507 -f 8508 8204 8490 -f 8490 8204 8203 -f 8490 8203 8509 -f 8509 8203 8510 -f 8509 8510 8511 -f 8511 8510 8205 -f 8511 8205 8492 -f 8492 8205 8512 -f 8492 8512 8493 -f 8493 8512 8208 -f 8493 8208 8513 -f 8513 8208 8514 -f 8513 8514 8516 -f 8516 8514 8515 -f 8515 8599 8516 -f 8516 8599 8517 -f 8517 8599 8592 -f 8592 8518 8517 -f 8517 8518 8519 -f 8517 8519 8495 -f 8495 8519 8503 -f 8495 8503 8494 -f 8494 8503 8502 -f 8494 8502 8520 -f 8520 8502 8500 -f 8520 8500 8521 -f 8521 8500 8499 -f 8521 8499 8491 -f 8491 8499 8498 -f 8491 8498 8522 -f 8522 8498 8497 -f 8522 8497 8478 -f 7713 8507 8586 -f 8586 8507 8506 -f 8586 8506 8518 -f 8586 8518 8523 -f 8523 8518 8592 -f 8524 8540 8525 -f 8671 8540 8532 -f 8671 8532 8526 -f 8533 8535 8479 -f 8479 8535 8537 -f 8479 8537 8496 -f 8537 8497 8496 -f 8497 8539 8478 -f 8541 8477 8478 -f 8480 8477 8413 -f 8413 8477 8541 -f 8413 8541 8527 -f 8528 8405 8401 -f 8528 8401 8527 -f 8527 8401 8413 -f 8405 8528 8529 -f 8405 8529 8403 -f 8403 8529 8530 -f 8403 8530 8404 -f 8404 8530 8531 -f 8404 8531 8406 -f 8406 8531 8524 -f 8406 8524 8525 -f 8406 8525 8600 -f 8526 8532 8533 -f 8533 8532 8534 -f 8533 8534 8535 -f 8535 8534 8536 -f 8535 8536 8538 -f 8535 8538 8537 -f 8537 8538 8539 -f 8537 8539 8497 -f 8540 8524 8531 -f 8540 8531 8532 -f 8532 8531 8530 -f 8532 8530 8534 -f 8534 8530 8529 -f 8534 8529 8536 -f 8536 8529 8528 -f 8536 8528 8538 -f 8538 8528 8527 -f 8538 8527 8539 -f 8539 8527 8541 -f 8539 8541 8478 -f 8694 8698 8543 -f 8698 8697 8554 -f 8544 8692 8691 -f 8544 8691 8548 -f 8548 8691 8701 -f 8694 8549 8700 -f 8700 8549 8545 -f 8700 8545 8420 -f 8549 8542 8545 -f 8703 8552 8546 -f 8546 8552 8556 -f 8734 8546 8553 -f 8734 8553 8547 -f 8547 8544 8548 -f 8549 8694 8543 -f 8549 8543 8542 -f 8542 8543 8550 -f 8542 8550 8416 -f 8416 8550 8417 -f 8543 8698 8554 -f 8543 8554 8550 -f 8550 8554 8551 -f 8550 8551 8417 -f 8417 8551 8556 -f 8417 8556 8552 -f 8697 8692 8555 -f 8555 8692 8544 -f 8555 8544 8553 -f 8553 8544 8547 -f 8554 8697 8555 -f 8554 8555 8551 -f 8551 8555 8553 -f 8551 8553 8556 -f 8556 8553 8546 -f 8570 8558 8470 -f 8211 8476 8557 -f 8557 8476 8470 -f 8470 8558 8559 -f 8559 8558 8574 -f 8559 8574 8579 -f 8579 8574 8572 -f 8579 8572 8560 -f 8560 8572 8576 -f 8560 8576 8561 -f 8201 8563 8562 -f 8562 8563 8200 -f 8562 8200 8564 -f 8564 8200 8565 -f 8564 8565 8580 -f 8580 8565 8209 -f 8580 8209 8557 -f 8557 8209 8210 -f 8557 8210 8211 -f 8045 8571 8566 -f 8566 8571 8567 -f 8566 8567 8568 -f 8568 8567 8573 -f 8568 8573 8569 -f 8569 8573 8575 -f 8569 8575 8046 -f 8046 8575 8570 -f 8046 8570 8468 -f 8045 8782 8571 -f 8571 8782 8783 -f 8783 8576 8571 -f 8571 8576 8572 -f 8571 8572 8567 -f 8567 8572 8574 -f 8567 8574 8573 -f 8573 8574 8558 -f 8573 8558 8575 -f 8575 8558 8570 -f 8783 8784 8576 -f 8576 8784 8577 -f 8576 8577 8561 -f 8561 8577 8578 -f 8561 8578 8786 -f 8470 8559 8557 -f 8557 8559 8579 -f 8557 8579 8580 -f 8580 8579 8560 -f 8580 8560 8564 -f 8564 8560 8561 -f 8564 8561 8562 -f 8562 8561 8786 -f 8202 8201 8789 -f 8789 8201 8562 -f 8789 8562 8790 -f 8790 8562 8786 -f 8780 8779 7647 -f 8595 8202 8594 -f 8581 8780 7647 -f 8581 7647 8584 -f 8584 7647 8585 -f 7649 8587 8583 -f 8583 8587 8590 -f 8583 8590 8584 -f 8583 8584 8585 -f 8791 8582 8594 -f 8594 8582 8589 -f 8594 8589 8596 -f 8596 8589 8588 -f 8596 8588 8597 -f 8597 8588 8591 -f 8597 8591 8593 -f 7649 7713 8586 -f 7649 8586 8587 -f 8587 8586 8523 -f 8523 8591 8587 -f 8587 8591 8588 -f 8587 8588 8590 -f 8590 8588 8589 -f 8590 8589 8584 -f 8584 8589 8582 -f 8584 8582 8581 -f 8581 8582 8791 -f 8581 8791 8780 -f 8523 8592 8591 -f 8591 8592 8593 -f 8593 8592 8599 -f 8595 8594 8596 -f 8595 8596 8206 -f 8206 8596 8597 -f 8206 8597 8207 -f 8207 8597 8593 -f 8207 8593 8598 -f 8598 8593 8599 -f 8598 8599 8515 -f 8617 8619 7761 -f 7762 8613 8611 -f 8688 8603 8601 -f 8654 8797 8688 -f 8684 8806 8797 -f 8795 8805 8602 -f 7771 8795 8602 -f 7771 8602 8682 -f 7771 8682 8604 -f 8601 8603 7867 -f 8601 7867 8656 -f 8656 7867 8657 -f 8604 8682 7769 -f 7769 8682 8681 -f 7769 8681 8605 -f 7867 7920 8657 -f 8657 7920 8660 -f 8660 7920 7852 -f 8605 8681 8606 -f 8606 8681 8608 -f 8606 8608 8607 -f 8660 7852 7943 -f 8660 7943 8661 -f 8607 8608 8609 -f 8609 8608 8612 -f 8609 8612 7764 -f 7943 8610 8661 -f 8661 8610 8663 -f 8611 8613 8612 -f 8612 8613 8614 -f 8612 8614 7764 -f 8610 7872 8663 -f 8663 7872 8623 -f 8663 8623 8615 -f 7762 8611 7761 -f 7761 8611 8616 -f 7761 8616 8617 -f 8620 7760 8618 -f 8620 8618 8617 -f 8617 8618 8619 -f 7760 8620 8621 -f 8621 8620 8622 -f 8621 8622 7756 -f 8615 8623 7871 -f 8615 7871 8625 -f 8625 7871 8624 -f 8625 8624 8666 -f 8666 8624 8627 -f 8666 8627 8626 -f 8626 8627 8667 -f 8627 7991 8667 -f 8667 7991 8628 -f 8667 8628 8629 -f 8630 8635 8631 -f 8631 7755 8630 -f 8630 7755 8632 -f 8630 8632 8622 -f 8622 8632 7757 -f 8622 7757 7756 -f 8629 8628 8633 -f 8629 8633 8637 -f 7754 7753 8634 -f 8634 7753 8636 -f 8634 8636 8635 -f 8635 8636 8631 -f 8633 7876 8637 -f 8637 7876 7875 -f 8637 7875 8668 -f 8668 7875 7929 -f 8653 8638 8639 -f 8639 8638 8668 -f 8639 8668 7929 -f 8797 8654 8684 -f 8684 8654 8655 -f 8684 8655 8683 -f 8683 8655 8658 -f 8683 8658 8640 -f 8640 8658 8659 -f 8640 8659 8680 -f 8680 8659 8662 -f 8680 8662 8679 -f 8679 8662 8641 -f 8679 8641 8678 -f 8678 8641 8642 -f 8678 8642 8677 -f 8677 8642 8664 -f 8677 8664 8643 -f 8643 8664 8665 -f 8643 8665 8676 -f 8676 8665 8644 -f 8676 8644 8645 -f 8645 8644 8646 -f 8645 8646 8675 -f 8675 8646 8647 -f 8675 8647 8648 -f 8648 8647 8669 -f 8648 8669 8674 -f 8674 8669 8670 -f 8674 8670 8649 -f 8649 8670 8650 -f 8649 8650 8651 -f 7754 8634 8652 -f 8652 8634 8673 -f 8652 8673 8672 -f 8652 8672 7750 -f 8525 8638 8653 -f 8525 8653 8600 -f 8688 8601 8654 -f 8654 8601 8656 -f 8654 8656 8655 -f 8655 8656 8657 -f 8655 8657 8658 -f 8658 8657 8660 -f 8658 8660 8659 -f 8659 8660 8661 -f 8659 8661 8662 -f 8662 8661 8663 -f 8662 8663 8641 -f 8641 8663 8615 -f 8641 8615 8642 -f 8642 8615 8625 -f 8642 8625 8664 -f 8664 8625 8666 -f 8664 8666 8665 -f 8665 8666 8626 -f 8665 8626 8644 -f 8644 8626 8667 -f 8644 8667 8646 -f 8646 8667 8629 -f 8646 8629 8647 -f 8647 8629 8637 -f 8647 8637 8669 -f 8669 8637 8668 -f 8669 8668 8670 -f 8670 8668 8638 -f 8670 8638 8650 -f 8650 8638 8525 -f 8650 8525 8540 -f 8650 8540 8671 -f 8650 8671 8651 -f 8651 8671 8526 -f 8526 8672 8651 -f 8651 8672 8673 -f 8651 8673 8649 -f 8649 8673 8634 -f 8649 8634 8674 -f 8674 8634 8635 -f 8674 8635 8648 -f 8648 8635 8630 -f 8648 8630 8675 -f 8675 8630 8622 -f 8675 8622 8645 -f 8645 8622 8620 -f 8645 8620 8676 -f 8676 8620 8617 -f 8676 8617 8643 -f 8643 8617 8616 -f 8643 8616 8677 -f 8677 8616 8611 -f 8677 8611 8678 -f 8678 8611 8612 -f 8678 8612 8679 -f 8679 8612 8608 -f 8679 8608 8680 -f 8680 8608 8681 -f 8680 8681 8640 -f 8640 8681 8682 -f 8640 8682 8683 -f 8683 8682 8602 -f 8683 8602 8684 -f 8684 8602 8805 -f 8684 8805 8806 -f 8526 8533 8672 -f 8672 8533 7750 -f 7750 8533 8685 -f 8685 8533 8479 -f 8686 8696 8698 -f 8687 8801 8693 -f 8688 8690 8689 -f 8689 8690 8699 -f 8701 8695 8191 -f 8691 8692 8693 -f 8687 8693 8692 -f 8687 8692 8697 -f 8694 8700 8690 -f 8701 8691 8695 -f 8695 8691 8693 -f 8695 8693 8801 -f 8696 8687 8697 -f 8696 8697 8698 -f 8698 8694 8686 -f 8686 8694 8690 -f 8699 8690 7865 -f 7865 8690 8700 -f 7865 8700 8420 -f 8546 8734 8735 -f 8701 8702 8548 -f 8548 8702 8708 -f 8734 8547 8724 -f 8724 8547 8548 -f 8703 8546 8746 -f 8703 8746 8704 -f 8704 8746 8747 -f 8704 8747 7609 -f 7609 8747 8705 -f 8705 8747 8707 -f 8705 8707 8706 -f 8706 8707 8748 -f 8706 8748 7606 -f 8702 8709 8708 -f 8708 8709 8710 -f 8708 8710 8711 -f 8711 8710 8712 -f 8711 8712 8725 -f 8725 8712 8713 -f 8725 8713 8714 -f 8714 8713 8197 -f 8714 8197 8729 -f 7606 8748 8749 -f 7606 8749 8715 -f 8715 8749 8752 -f 8715 8752 8716 -f 8716 8752 7605 -f 7605 8752 8717 -f 8717 8752 8756 -f 8717 8756 7603 -f 7603 8756 8754 -f 8197 8718 8729 -f 8729 8718 8719 -f 8729 8719 8730 -f 8730 8719 8720 -f 8730 8720 8721 -f 8730 8721 8731 -f 8731 8721 8722 -f 8731 8722 8196 -f 8731 8196 8723 -f 8548 8708 8724 -f 8724 8708 8711 -f 8724 8711 8736 -f 8736 8711 8725 -f 8736 8725 8726 -f 8726 8725 8714 -f 8726 8714 8727 -f 8727 8714 8729 -f 8727 8729 8728 -f 8728 8729 8730 -f 8728 8730 8741 -f 8741 8730 8731 -f 8741 8731 8742 -f 8742 8731 8723 -f 8742 8723 8744 -f 8744 8723 8745 -f 8723 8732 8812 -f 8723 8812 8745 -f 8745 8812 8733 -f 8745 8733 8814 -f 8734 8724 8735 -f 8735 8724 8736 -f 8735 8736 8737 -f 8737 8736 8726 -f 8737 8726 8738 -f 8738 8726 8727 -f 8738 8727 8739 -f 8739 8727 8728 -f 8739 8728 8740 -f 8740 8728 8741 -f 8740 8741 8750 -f 8750 8741 8751 -f 8751 8741 8742 -f 8751 8742 8743 -f 8743 8742 8744 -f 8546 8735 8746 -f 8746 8735 8737 -f 8746 8737 8747 -f 8747 8737 8738 -f 8747 8738 8707 -f 8707 8738 8739 -f 8707 8739 8748 -f 8748 8739 8740 -f 8748 8740 8749 -f 8749 8740 8750 -f 8749 8750 8752 -f 8752 8750 8751 -f 8752 8751 8743 -f 8752 8743 8756 -f 8756 8743 8744 -f 8756 8744 8753 -f 8753 8744 8745 -f 8753 8745 8759 -f 8759 8745 8814 -f 8759 8814 8760 -f 8754 8756 8755 -f 8755 8756 8753 -f 8755 8753 7600 -f 7600 8753 7599 -f 7599 8753 8757 -f 8757 8753 8759 -f 8757 8759 7602 -f 7602 8759 8758 -f 8758 8759 8760 -f 8758 8760 7601 -f 8762 8047 8112 -f 8777 8762 8775 -f 8762 8112 8775 -f 8775 8112 8111 -f 8111 8763 8775 -f 8775 8763 8765 -f 8775 8765 8764 -f 8764 8765 8109 -f 8764 8109 8766 -f 8109 8767 8766 -f 8766 8767 8769 -f 8761 8776 8768 -f 8761 8768 8778 -f 8766 8769 8770 -f 8766 8770 8778 -f 8778 8770 8771 -f 8778 8771 8772 -f 8778 8772 8113 -f 8150 8113 8773 -f 8777 8775 8764 -f 8776 8777 8764 -f 8776 8764 8768 -f 8768 8764 8766 -f 8768 8766 8778 -f 8778 8113 8150 -f 8783 8782 8894 -f 8791 8895 8897 -f 8791 8897 8780 -f 8920 8785 8781 -f 8894 8782 8045 -f 8894 8781 8783 -f 8783 8781 8784 -f 8784 8781 8577 -f 8577 8781 8578 -f 8578 8781 8785 -f 8578 8785 8786 -f 8920 8792 8785 -f 8785 8792 8786 -f 8787 8202 8788 -f 8788 8202 8789 -f 8788 8789 8790 -f 8791 8594 8787 -f 8787 8594 8202 -f 8895 8791 8787 -f 8895 8787 8792 -f 8792 8787 8788 -f 8792 8788 8786 -f 8786 8788 8790 -f 8807 8932 8793 -f 8930 8807 8794 -f 8930 8794 8931 -f 8805 8795 8802 -f 8931 8802 8795 -f 8806 8810 8797 -f 8796 8688 8797 -f 8690 8688 8796 -f 8690 8796 8798 -f 8799 8696 8686 -f 8799 8686 8798 -f 8798 8686 8690 -f 8696 8799 8809 -f 8696 8809 8687 -f 8687 8809 8800 -f 8687 8800 8801 -f 8695 8801 8793 -f 8695 8793 8932 -f 8695 8932 8191 -f 8931 8794 8808 -f 8931 8808 8802 -f 8802 8808 8803 -f 8802 8803 8804 -f 8802 8804 8805 -f 8805 8804 8810 -f 8805 8810 8806 -f 8807 8793 8801 -f 8807 8801 8794 -f 8794 8801 8800 -f 8794 8800 8808 -f 8808 8800 8809 -f 8808 8809 8803 -f 8803 8809 8799 -f 8803 8799 8804 -f 8804 8799 8798 -f 8804 8798 8810 -f 8810 8798 8796 -f 8810 8796 8797 -f 8811 7601 8760 -f 8732 8813 8812 -f 8812 8813 8815 -f 8811 8760 8985 -f 8985 8760 8814 -f 8985 8814 8990 -f 8990 8814 8815 -f 8815 8814 8733 -f 8815 8733 8812 -f 8825 8826 8831 -f 8090 8997 8817 -f 8817 8997 8998 -f 8090 8817 8818 -f 8818 8817 8828 -f 8818 8828 8089 -f 8155 8821 8819 -f 8819 8821 8828 -f 8819 8828 8820 -f 8820 8828 8817 -f 8820 8817 8149 -f 8149 8817 8998 -f 8149 8998 8816 -f 8821 8155 8822 -f 8821 8822 8823 -f 8823 8822 8151 -f 8823 8151 8831 -f 8831 8151 8824 -f 8831 8824 8825 -f 8825 8150 8826 -f 8089 8828 8827 -f 8827 8828 8821 -f 8827 8821 8829 -f 8829 8821 8823 -f 8829 8823 8830 -f 8830 8823 8831 -f 8830 8831 8088 -f 8088 8831 8826 -f 8088 8826 8832 -f 8832 8826 8150 -f 8832 8150 8774 -f 8841 8145 8840 -f 8834 8836 8835 -f 8145 8839 8840 -f 8840 8839 8838 -f 8840 8838 8843 -f 8843 8838 8837 -f 8843 8837 8844 -f 8844 8837 8836 -f 8844 8836 8845 -f 8845 8836 8834 -f 8842 8841 8840 -f 8842 8840 8848 -f 8848 8840 8843 -f 8848 8843 8850 -f 8850 8843 8844 -f 8850 8844 8851 -f 8851 8844 8845 -f 8144 8841 8846 -f 8846 8841 8842 -f 8846 8842 8847 -f 8847 8842 8848 -f 8847 8848 8849 -f 8849 8848 8850 -f 8849 8850 8855 -f 8855 8850 8851 -f 8852 8144 8856 -f 8856 8144 8846 -f 8856 8846 8861 -f 8861 8846 8847 -f 8861 8847 8853 -f 8853 8847 8849 -f 8853 8849 8854 -f 8854 8849 8855 -f 8862 8141 8856 -f 8856 8141 8852 -f 8050 8857 8858 -f 8858 8857 8859 -f 8858 8859 8860 -f 8860 8859 8868 -f 8860 8868 8863 -f 8863 8868 8865 -f 8854 8050 8853 -f 8853 8050 8858 -f 8853 8858 8861 -f 8861 8858 8860 -f 8861 8860 8856 -f 8856 8860 8863 -f 8856 8863 8862 -f 8862 8863 8865 -f 8862 8865 8143 -f 8869 8143 8864 -f 8864 8143 8865 -f 8864 8865 8866 -f 8866 8865 8868 -f 8866 8868 8867 -f 8867 8868 8859 -f 8867 8859 8873 -f 8873 8859 8857 -f 8874 8869 8875 -f 8875 8869 8864 -f 8875 8864 8870 -f 8870 8864 8866 -f 8870 8866 8871 -f 8871 8866 8867 -f 8871 8867 8872 -f 8872 8867 8873 -f 8140 8874 8877 -f 8877 8874 8875 -f 8877 8875 8876 -f 8876 8875 8870 -f 8876 8870 8880 -f 8880 8870 8871 -f 8880 8871 8881 -f 8881 8871 8872 -f 8882 8140 8884 -f 8884 8140 8877 -f 8884 8877 8878 -f 8878 8877 8876 -f 8878 8876 8879 -f 8879 8876 8880 -f 8879 8880 8049 -f 8049 8880 8881 -f 8138 8882 8887 -f 8887 8882 8884 -f 8887 8884 8883 -f 8883 8884 8878 -f 8883 8878 8885 -f 8885 8878 8879 -f 8885 8879 8890 -f 8890 8879 8049 -f 8891 8138 8833 -f 8833 8138 8887 -f 8833 8887 8886 -f 8886 8887 8883 -f 8886 8883 8888 -f 8888 8883 8885 -f 8888 8885 8889 -f 8889 8885 8890 -f 8761 8891 8776 -f 8776 8891 8833 -f 8776 8833 8777 -f 8777 8833 8886 -f 8777 8886 8762 -f 8762 8886 8888 -f 8762 8888 8047 -f 8047 8888 8889 -f 8781 8894 8893 -f 8920 8902 8792 -f 8895 8792 8903 -f 8897 8895 8896 -f 8926 8780 8897 -f 8780 8926 8898 -f 8780 8898 8779 -f 8898 8926 8912 -f 8912 8926 8909 -f 8781 8893 8899 -f 8899 8893 8900 -f 8899 8900 8901 -f 8901 8900 8914 -f 8901 8914 8919 -f 8919 8914 8913 -f 8919 8913 8917 -f 8792 8902 8903 -f 8903 8902 8904 -f 8903 8904 8905 -f 8905 8904 8918 -f 8905 8918 8923 -f 8923 8918 8921 -f 8923 8921 8922 -f 8895 8892 8896 -f 8896 8892 8906 -f 8896 8906 8927 -f 8927 8906 8924 -f 8927 8924 8907 -f 8907 8924 8925 -f 8907 8925 8929 -f 7642 7645 8908 -f 8908 7645 8928 -f 8928 7645 8910 -f 8928 8910 8909 -f 8909 8910 8911 -f 8909 8911 8912 -f 8042 8835 9005 -f 9005 8913 8042 -f 8042 8913 8914 -f 8042 8914 8043 -f 8043 8914 8900 -f 8043 8900 8915 -f 8915 8900 8893 -f 8915 8893 8044 -f 8044 8893 8894 -f 8044 8894 8045 -f 8913 9005 8916 -f 8913 8916 8917 -f 8917 8916 9006 -f 9006 8921 8917 -f 8917 8921 8918 -f 8917 8918 8919 -f 8919 8918 8904 -f 8919 8904 8901 -f 8901 8904 8902 -f 8901 8902 8899 -f 8899 8902 8920 -f 8899 8920 8781 -f 8921 9006 9015 -f 8921 9015 8922 -f 8895 8903 8892 -f 8892 8903 8905 -f 8892 8905 8906 -f 8906 8905 8923 -f 8906 8923 8924 -f 8924 8923 8922 -f 8924 8922 8925 -f 8925 8922 9015 -f 8925 9015 9014 -f 8925 9014 9007 -f 8925 9007 8929 -f 8897 8896 8926 -f 8926 8896 8927 -f 8926 8927 8909 -f 8909 8927 8907 -f 8909 8907 8928 -f 8928 8907 8929 -f 8928 8929 8908 -f 8908 8929 9007 -f 8908 9007 9008 -f 7643 7642 8908 -f 7643 8908 9008 -f 8795 8933 8931 -f 8932 8807 8946 -f 8946 8807 8930 -f 8931 8933 8959 -f 8959 8933 8935 -f 8959 8935 8934 -f 8934 8935 8936 -f 8935 8937 8936 -f 8936 8937 8938 -f 8936 8938 8956 -f 8938 7772 8956 -f 8956 7772 8939 -f 8956 8939 8941 -f 8941 8939 7741 -f 7741 8940 8941 -f 8941 8940 8943 -f 8941 8943 8942 -f 8942 8943 8955 -f 8955 8943 7773 -f 8955 7773 8944 -f 8944 7773 8945 -f 8930 8947 8946 -f 8946 8947 8958 -f 8946 8958 8961 -f 8961 8958 8957 -f 8961 8957 8964 -f 8964 8957 8948 -f 8964 8948 8965 -f 8965 8948 8949 -f 8965 8949 8950 -f 8950 8949 8951 -f 8950 8951 8967 -f 8967 8951 8952 -f 8967 8952 8953 -f 8953 8952 8954 -f 8953 8954 8960 -f 8945 7774 8944 -f 8944 7774 9035 -f 9035 8954 8944 -f 8944 8954 8952 -f 8944 8952 8955 -f 8955 8952 8951 -f 8955 8951 8942 -f 8942 8951 8949 -f 8942 8949 8941 -f 8941 8949 8948 -f 8941 8948 8956 -f 8956 8948 8957 -f 8956 8957 8936 -f 8936 8957 8958 -f 8936 8958 8934 -f 8934 8958 8947 -f 8934 8947 8959 -f 8959 8947 8930 -f 8959 8930 8931 -f 9035 9034 8954 -f 8954 9034 9032 -f 8954 9032 8960 -f 8960 9032 9031 -f 8932 8946 8961 -f 8932 8961 8962 -f 8962 8961 8964 -f 8962 8964 8963 -f 8963 8964 8965 -f 8963 8965 8973 -f 8973 8965 8950 -f 8973 8950 8966 -f 8966 8950 8967 -f 8966 8967 8968 -f 8968 8967 8953 -f 8968 8953 8969 -f 8969 8953 8960 -f 8969 8960 8970 -f 8970 8960 9031 -f 8191 8932 8971 -f 8971 8932 8962 -f 8971 8962 8972 -f 8972 8962 8963 -f 8972 8963 8190 -f 8190 8963 8973 -f 8190 8973 8185 -f 8185 8973 8966 -f 8185 8966 8974 -f 8974 8966 8968 -f 8974 8968 8975 -f 8975 8968 8969 -f 8975 8969 8976 -f 8976 8969 8970 -f 8976 8970 8186 -f 8186 8970 9031 -f 8186 9031 8187 -f 9055 7589 7590 -f 8992 9056 9055 -f 8991 9064 8992 -f 8992 9064 9056 -f 9055 7590 8977 -f 8977 7590 8978 -f 8977 8978 8986 -f 8986 8978 8980 -f 8986 8980 8979 -f 8979 8980 7592 -f 8979 7592 8987 -f 7592 7591 8987 -f 8987 7591 8981 -f 8987 8981 7598 -f 8987 7598 8984 -f 8984 7598 7596 -f 7596 8982 8984 -f 8984 8982 8983 -f 8984 8983 8989 -f 8989 8983 7594 -f 7594 8811 8989 -f 8989 8811 8985 -f 8989 8985 8990 -f 9055 8977 8992 -f 8992 8977 8986 -f 8992 8986 8993 -f 8993 8986 8979 -f 8993 8979 8987 -f 8993 8987 8988 -f 8988 8987 8984 -f 8988 8984 8995 -f 8995 8984 8989 -f 8995 8989 8990 -f 8995 8990 8815 -f 8991 8992 8198 -f 8198 8992 8993 -f 8198 8993 8994 -f 8994 8993 8988 -f 8994 8988 8194 -f 8194 8988 8995 -f 8194 8995 8996 -f 8996 8995 8815 -f 8996 8815 8813 -f 9000 9081 9123 -f 8998 8997 8999 -f 8816 8998 9134 -f 9134 8998 9123 -f 9123 8998 8999 -f 9123 8999 9000 -f 8837 8838 9016 -f 8838 8839 9001 -f 9008 9148 9002 -f 9008 9002 7643 -f 9011 9001 8839 -f 9004 8836 8837 -f 9004 8837 9017 -f 8835 8836 9005 -f 9005 8836 9004 -f 9005 9004 9017 -f 9006 8916 9017 -f 9017 8916 9005 -f 9014 9009 9007 -f 9008 9007 9148 -f 9148 9007 9003 -f 9003 9007 9009 -f 9003 9009 9010 -f 9010 9009 9012 -f 9010 9012 9011 -f 9011 9012 9013 -f 9011 9013 9001 -f 9001 9013 9016 -f 9001 9016 8838 -f 9009 9014 9015 -f 9009 9015 9012 -f 9012 9015 9013 -f 9013 9015 9006 -f 9013 9006 9016 -f 9016 9006 9017 -f 9016 9017 8837 -f 7626 7625 9020 -f 9019 9180 9021 -f 9020 9179 9180 -f 9020 9180 9019 -f 9179 9020 7625 -f 9027 9029 7626 -f 9027 7626 9020 -f 9027 9020 9025 -f 9025 9020 9019 -f 9025 9019 9024 -f 9024 9019 9021 -f 9024 9021 9022 -f 9022 9021 9018 -f 9022 9023 9024 -f 9024 9023 9026 -f 9024 9026 9025 -f 9025 9026 9037 -f 9025 9037 9027 -f 9027 9037 9028 -f 9027 9028 9029 -f 7623 9030 9028 -f 9028 9030 9029 -f 8187 9031 8188 -f 8188 9031 9036 -f 9036 9031 9032 -f 9036 9032 9038 -f 9038 9032 9034 -f 9038 9034 9033 -f 9033 9034 9035 -f 9023 8188 9026 -f 9026 8188 9036 -f 9026 9036 9037 -f 9037 9036 9038 -f 9037 9038 9028 -f 9028 9038 9033 -f 9028 9033 7623 -f 7623 9033 9035 -f 7623 9035 7774 -f 9172 9039 9173 -f 9040 9178 9057 -f 9057 9178 9173 -f 9018 9040 9042 -f 9041 9018 9042 -f 9041 9042 8189 -f 8189 9042 9058 -f 8189 9058 9043 -f 9043 9058 9044 -f 9043 9044 8192 -f 8192 9044 9061 -f 9173 9039 9046 -f 9046 9039 9053 -f 9046 9053 9047 -f 9047 9053 9045 -f 9047 9045 9048 -f 9048 9045 9051 -f 9048 9051 9049 -f 9173 9046 9057 -f 9057 9046 9047 -f 9057 9047 9059 -f 9059 9047 9048 -f 9059 9048 9060 -f 9060 9048 9049 -f 9060 9049 9050 -f 7589 9051 9052 -f 9052 9051 9045 -f 9052 9045 7616 -f 7616 9045 9053 -f 7616 9053 7615 -f 7615 9053 9039 -f 7615 9039 9054 -f 9054 9039 9172 -f 9054 9172 9220 -f 7589 9055 9051 -f 9051 9055 9049 -f 9049 9055 9050 -f 9050 9055 9056 -f 9040 9057 9042 -f 9042 9057 9059 -f 9042 9059 9058 -f 9058 9059 9060 -f 9058 9060 9044 -f 9044 9060 9050 -f 9044 9050 9063 -f 9063 9050 9056 -f 9063 9056 9064 -f 9061 9044 9062 -f 9062 9044 9063 -f 9062 9063 9065 -f 9065 9063 9064 -f 9065 9064 8991 -f 8106 9066 9070 -f 8101 9067 9193 -f 9193 9067 9068 -f 9193 9068 9197 -f 9197 9068 8054 -f 8054 9068 9072 -f 8054 9072 9073 -f 9067 8100 9068 -f 9068 8100 9069 -f 9068 9069 9072 -f 9072 9069 8104 -f 9072 8104 9070 -f 9070 8104 8107 -f 9070 8107 8106 -f 9066 8053 9070 -f 9070 8053 9071 -f 9070 9071 9072 -f 9072 9071 9073 -f 9077 9074 9066 -f 9066 9074 8053 -f 9079 9078 9075 -f 9075 9078 9076 -f 9075 8108 9079 -f 8106 9076 9066 -f 9066 9076 9078 -f 9066 9078 9077 -f 9077 9078 9079 -f 9077 9079 9080 -f 9080 9079 8052 -f 8999 8997 9084 -f 9000 8999 9083 -f 9000 9109 9081 -f 9081 9109 9082 -f 8999 9084 9083 -f 9083 9084 8091 -f 9083 8091 9108 -f 9108 8091 8086 -f 9108 8086 9086 -f 8086 9085 9086 -f 9086 9085 8094 -f 9086 8094 9110 -f 9110 8094 8093 -f 9110 8093 8097 -f 9110 8097 9111 -f 9111 8097 9087 -f 9111 9087 8096 -f 9111 8096 9092 -f 9082 9109 8171 -f 8171 9109 9088 -f 8171 9088 9089 -f 9089 9088 9090 -f 9089 9090 8168 -f 8168 9090 9112 -f 8168 9112 9091 -f 9091 9112 9114 -f 9091 9114 9102 -f 8096 8095 9092 -f 9092 8095 9093 -f 9092 9093 9096 -f 9096 9093 9094 -f 9096 9094 9095 -f 9096 9095 8098 -f 9096 8098 9113 -f 9113 8098 9097 -f 9113 9097 9098 -f 9113 9098 9116 -f 9116 9098 9099 -f 9116 9099 9100 -f 9116 9100 9101 -f 9101 9100 8102 -f 9102 9114 9115 -f 9102 9115 8166 -f 8166 9115 9104 -f 8166 9104 9103 -f 9103 9104 9119 -f 9103 9119 8167 -f 8167 9119 9105 -f 9101 8102 9106 -f 9101 9106 9117 -f 9117 9106 9107 -f 9117 9107 9118 -f 9107 8101 9198 -f 9107 9198 9118 -f 9118 9198 9194 -f 9000 9083 9109 -f 9109 9083 9108 -f 9109 9108 9086 -f 9109 9086 9088 -f 9088 9086 9110 -f 9088 9110 9090 -f 9090 9110 9111 -f 9090 9111 9112 -f 9112 9111 9092 -f 9112 9092 9096 -f 9112 9096 9114 -f 9114 9096 9113 -f 9114 9113 9115 -f 9115 9113 9116 -f 9115 9116 9104 -f 9104 9116 9101 -f 9104 9101 9119 -f 9119 9101 9117 -f 9119 9117 9120 -f 9120 9117 9118 -f 9120 9118 9194 -f 9105 9119 9120 -f 9105 9120 8165 -f 8165 9120 9121 -f 9121 9120 9194 -f 9121 9194 9195 -f 9123 9081 9122 -f 9134 9123 9125 -f 9134 9124 8816 -f 9123 9122 9125 -f 9125 9122 8169 -f 9125 8169 9135 -f 8816 9124 9126 -f 9126 9124 9128 -f 9126 9128 9127 -f 9127 9128 9136 -f 9127 9136 9129 -f 8169 8172 9135 -f 9135 8172 9130 -f 9135 9130 9131 -f 9131 9130 9142 -f 9129 9136 9132 -f 9132 9136 9133 -f 9132 9133 8154 -f 8154 9133 9138 -f 8154 9138 9145 -f 9134 9125 9124 -f 9124 9125 9135 -f 9124 9135 9128 -f 9128 9135 9131 -f 9128 9131 9136 -f 9136 9131 9142 -f 9136 9142 9133 -f 9133 9142 9137 -f 9133 9137 9138 -f 9138 9137 9144 -f 9138 9144 9146 -f 9205 9210 9139 -f 9139 9210 9144 -f 9139 9144 9140 -f 9140 9144 9137 -f 9140 9137 9141 -f 9141 9137 9142 -f 9141 9142 9143 -f 9143 9142 9130 -f 9144 9210 9200 -f 9144 9200 9146 -f 9145 9138 9147 -f 9147 9138 9146 -f 9147 9146 9200 -f 9147 9200 8147 -f 9152 9011 8839 -f 9153 9010 9011 -f 9163 9003 9010 -f 9167 9148 9003 -f 9002 9148 9166 -f 9149 7643 9002 -f 9149 9002 9166 -f 9149 9166 9169 -f 9149 9169 9150 -f 8839 9151 9152 -f 9152 9151 9160 -f 9152 9160 9154 -f 9154 9160 9158 -f 9011 9152 9153 -f 9153 9152 9154 -f 9153 9154 9162 -f 9162 9154 9158 -f 9162 9158 9161 -f 9003 9163 9167 -f 9167 9163 9155 -f 9167 9155 9156 -f 9156 9155 9164 -f 9156 9164 9165 -f 8147 9207 9157 -f 9157 9207 9158 -f 9157 9158 9159 -f 9159 9158 9160 -f 9158 9207 9206 -f 9158 9206 9161 -f 9161 9206 9214 -f 9214 9164 9161 -f 9161 9164 9155 -f 9161 9155 9162 -f 9162 9155 9163 -f 9162 9163 9153 -f 9153 9163 9010 -f 9164 9214 9211 -f 9164 9211 9165 -f 9211 9170 9165 -f 9165 9170 9169 -f 9165 9169 9156 -f 9156 9169 9166 -f 9156 9166 9167 -f 9167 9166 9148 -f 9211 9168 9170 -f 9150 9169 7640 -f 7640 9169 9170 -f 7640 9170 7639 -f 7639 9170 9168 -f 7639 9168 9208 -f 9172 9173 9171 -f 9182 9174 9175 -f 9217 9219 9180 -f 9177 9021 9180 -f 9176 9018 9177 -f 9177 9018 9021 -f 9176 9040 9018 -f 9173 9178 9171 -f 9171 9178 9182 -f 9171 9182 9175 -f 9179 9217 9180 -f 9180 9219 9181 -f 9177 9180 9181 -f 9177 9181 9176 -f 9176 9181 9174 -f 9176 9174 9040 -f 9040 9174 9182 -f 9040 9182 9178 -f 9190 8083 9185 -f 9185 8084 9184 -f 9184 8084 8085 -f 9184 8085 9189 -f 9185 9184 9190 -f 9191 8081 9190 -f 9190 8081 8083 -f 9183 8069 9186 -f 9186 8069 9188 -f 9188 8069 8052 -f 9191 9188 8079 -f 8080 9188 8052 -f 9297 9183 9186 -f 9297 9186 9187 -f 9187 9186 9188 -f 9189 9297 9184 -f 9184 9297 9187 -f 9184 9187 9190 -f 9190 9187 9188 -f 9190 9188 9191 -f 8080 8052 9192 -f 9192 8052 8076 -f 8076 8052 9079 -f 8076 9079 8108 -f 9198 8101 9193 -f 9193 9197 9199 -f 9195 9194 9196 -f 9196 9194 9198 -f 9196 9198 9199 -f 9199 9198 9193 -f 9209 9360 9357 -f 9360 9209 9364 -f 9364 9209 9201 -f 9364 9201 9202 -f 9364 9202 9203 -f 9203 9202 9204 -f 9203 9204 9205 -f 9205 9204 9210 -f 8147 9200 9207 -f 9207 9200 9216 -f 9207 9216 9206 -f 9168 9357 9208 -f 9357 9168 9209 -f 9201 9209 9212 -f 9201 9212 9202 -f 9202 9212 9213 -f 9202 9213 9204 -f 9204 9213 9215 -f 9204 9215 9210 -f 9210 9215 9200 -f 9168 9211 9209 -f 9209 9211 9212 -f 9212 9211 9214 -f 9212 9214 9213 -f 9213 9214 9206 -f 9213 9206 9215 -f 9215 9206 9216 -f 9215 9216 9200 -f 9221 9217 7624 -f 7624 9217 9179 -f 9181 9219 9218 -f 9174 9181 9241 -f 9229 9175 9174 -f 9248 9172 9171 -f 9249 9220 9172 -f 9222 9223 7739 -f 7739 9223 9221 -f 7739 9221 7624 -f 9222 7707 9223 -f 9223 7707 9224 -f 9223 9224 9225 -f 9224 7627 9225 -f 9225 7627 9238 -f 9225 9238 9226 -f 9181 9218 9241 -f 9241 9218 9240 -f 9241 9240 9227 -f 9227 9240 9228 -f 9227 9228 9244 -f 9244 9228 9239 -f 9244 9239 9245 -f 9174 9242 9229 -f 9229 9242 9243 -f 9229 9243 9230 -f 9230 9243 9231 -f 9230 9231 9233 -f 9233 9231 9232 -f 9233 9232 9234 -f 9171 9247 9248 -f 9248 9247 9246 -f 9248 9246 9235 -f 9235 9246 9236 -f 9235 9236 9252 -f 9252 9236 9237 -f 9252 9237 9253 -f 9372 9373 7629 -f 7629 9373 9226 -f 7629 9226 9238 -f 9226 9373 9387 -f 9387 9239 9226 -f 9226 9239 9228 -f 9226 9228 9225 -f 9225 9228 9240 -f 9225 9240 9223 -f 9223 9240 9218 -f 9223 9218 9221 -f 9221 9218 9219 -f 9221 9219 9217 -f 9239 9387 9245 -f 9245 9387 9377 -f 9174 9241 9242 -f 9242 9241 9227 -f 9242 9227 9243 -f 9243 9227 9244 -f 9243 9244 9231 -f 9231 9244 9245 -f 9231 9245 9232 -f 9232 9245 9377 -f 9232 9377 9382 -f 9232 9382 9234 -f 9234 9382 9383 -f 9383 9237 9234 -f 9234 9237 9236 -f 9234 9236 9233 -f 9233 9236 9246 -f 9233 9246 9230 -f 9230 9246 9247 -f 9230 9247 9229 -f 9229 9247 9171 -f 9229 9171 9175 -f 9383 9378 9237 -f 9237 9378 9253 -f 9253 9378 9379 -f 9172 9248 9249 -f 9249 9248 9235 -f 9249 9235 9250 -f 9250 9235 9252 -f 9250 9252 9251 -f 9251 9252 9253 -f 9251 9253 9254 -f 9254 9253 9379 -f 9254 9379 9255 -f 9257 9369 9256 -f 9257 9256 9258 -f 9257 9258 9270 -f 9270 9258 9259 -f 9270 9259 9272 -f 9272 9259 9260 -f 9272 9260 9273 -f 9273 9260 9261 -f 9273 9261 9274 -f 9274 9261 8066 -f 9274 8066 9275 -f 8066 8065 9275 -f 9275 8065 9263 -f 9275 9263 9262 -f 9262 9263 9278 -f 9263 8067 9278 -f 9278 8067 9265 -f 9278 9265 9264 -f 9264 9265 9267 -f 9265 9266 9267 -f 9267 9266 8072 -f 9267 8072 9268 -f 9268 8072 9281 -f 8069 9183 9269 -f 9269 9183 9282 -f 9269 9282 9281 -f 9269 9281 8071 -f 8071 9281 8072 -f 9385 9257 9270 -f 9385 9270 9284 -f 9284 9270 9272 -f 9284 9272 9271 -f 9271 9272 9273 -f 9271 9273 9287 -f 9287 9273 9274 -f 9287 9274 9288 -f 9288 9274 9275 -f 9288 9275 9276 -f 9276 9275 9262 -f 9276 9262 9277 -f 9277 9262 9278 -f 9277 9278 9291 -f 9291 9278 9264 -f 9291 9264 9292 -f 9292 9264 9267 -f 9292 9267 9279 -f 9279 9267 9268 -f 9279 9268 9280 -f 9280 9268 9281 -f 9280 9281 9294 -f 9294 9281 9282 -f 9294 9282 9296 -f 9296 9282 9183 -f 9296 9183 9297 -f 9283 9385 9284 -f 9283 9284 9285 -f 9285 9284 9271 -f 9285 9271 9286 -f 9286 9271 9287 -f 9286 9287 9301 -f 9301 9287 9288 -f 9301 9288 9289 -f 9289 9288 9276 -f 9289 9276 9290 -f 9290 9276 9277 -f 9290 9277 9302 -f 9302 9277 9291 -f 9302 9291 9304 -f 9304 9291 9292 -f 9304 9292 9305 -f 9305 9292 9279 -f 9305 9279 9306 -f 9306 9279 9280 -f 9306 9280 9293 -f 9293 9280 9294 -f 9293 9294 9309 -f 9309 9294 9296 -f 9309 9296 9295 -f 9295 9296 9297 -f 9295 9297 9189 -f 9255 9283 9298 -f 9298 9283 9285 -f 9298 9285 9299 -f 9299 9285 9286 -f 9299 9286 9300 -f 9300 9286 9301 -f 9300 9301 7617 -f 7617 9301 9289 -f 7617 9289 7618 -f 7618 9289 9290 -f 7618 9290 7620 -f 7620 9290 9302 -f 7620 9302 9303 -f 9303 9302 9304 -f 9303 9304 7621 -f 7621 9304 9305 -f 7621 9305 7622 -f 7622 9305 9306 -f 7622 9306 9307 -f 9307 9306 9293 -f 9307 9293 9308 -f 9308 9293 9309 -f 9308 9309 7619 -f 7619 9309 9295 -f 7619 9295 9310 -f 9310 9295 9189 -f 9310 9189 8085 -f 9197 9311 9199 -f 9199 9311 9312 -f 9199 9312 9313 -f 9199 9313 9196 -f 9195 9196 8182 -f 8182 9196 9313 -f 8182 9313 9314 -f 9314 9313 9317 -f 9316 9315 9323 -f 9316 9323 9318 -f 9318 9323 9319 -f 9311 9315 9312 -f 9312 9315 9316 -f 9312 9316 9313 -f 9313 9316 9318 -f 9313 9318 9317 -f 9317 9318 9319 -f 9317 9319 9322 -f 8059 8058 9321 -f 9321 8058 9320 -f 9328 9322 9326 -f 9326 9322 9319 -f 9326 9319 9321 -f 9321 9319 9323 -f 9321 9323 8059 -f 8059 9323 9315 -f 9320 9324 9321 -f 9321 9324 9325 -f 9321 9325 9326 -f 9326 9325 9327 -f 9326 9327 9328 -f 8177 8181 9327 -f 9327 8181 8180 -f 9327 8180 9328 -f 9392 9330 8062 -f 8062 9330 9329 -f 8062 9329 9332 -f 9329 9330 9331 -f 9331 9330 9405 -f 9324 9332 9325 -f 9325 9332 9329 -f 9325 9329 9327 -f 9327 9329 9331 -f 9327 9331 8177 -f 8177 9331 9405 -f 8177 9405 9406 -f 9400 9336 9397 -f 9397 9336 9333 -f 9397 9333 9395 -f 9394 9396 9351 -f 9406 9394 9335 -f 9336 9337 9333 -f 9333 9337 9338 -f 9333 9338 9340 -f 9338 9339 9340 -f 9340 9339 9341 -f 9340 9341 9342 -f 9341 9343 9342 -f 9342 9343 9350 -f 9344 9406 9335 -f 9344 9335 9345 -f 9345 9335 9353 -f 9345 9353 8184 -f 8184 9353 9346 -f 8184 9346 8161 -f 8161 9346 9354 -f 8161 9354 8176 -f 9395 9333 9334 -f 9334 9333 9340 -f 9334 9340 9347 -f 9347 9340 9342 -f 9347 9342 9348 -f 9348 9342 9350 -f 9348 9350 9349 -f 9349 9350 9359 -f 9349 9359 9361 -f 9394 9351 9335 -f 9335 9351 9352 -f 9335 9352 9353 -f 9353 9352 9363 -f 9353 9363 9346 -f 9346 9363 9362 -f 9346 9362 9354 -f 9354 9362 9365 -f 9354 9365 9367 -f 9358 9356 9357 -f 9343 7635 9350 -f 9350 7635 7636 -f 9350 7636 9359 -f 9359 7636 9355 -f 9359 9355 9358 -f 9208 9357 9356 -f 9358 9357 9359 -f 9359 9357 9360 -f 9359 9360 9361 -f 9361 9360 9364 -f 9364 9365 9361 -f 9361 9365 9362 -f 9361 9362 9349 -f 9349 9362 9363 -f 9349 9363 9348 -f 9348 9363 9352 -f 9348 9352 9347 -f 9347 9352 9351 -f 9347 9351 9334 -f 9334 9351 9396 -f 9334 9396 9395 -f 9365 9364 9203 -f 9365 9203 9367 -f 9367 9203 9205 -f 8176 9354 9366 -f 9366 9354 9367 -f 9366 9367 8175 -f 8175 9367 9205 -f 9283 9380 9385 -f 9283 9255 9379 -f 9373 9374 9387 -f 9376 9377 9387 -f 9375 9382 9376 -f 9376 9382 9377 -f 9378 9383 9381 -f 9378 9381 9379 -f 9379 9381 9380 -f 9379 9380 9283 -f 9385 9380 9381 -f 9382 9375 9383 -f 9383 9375 9384 -f 9383 9384 9381 -f 9381 9384 9386 -f 9381 9386 9385 -f 9385 9386 9257 -f 9387 9374 9376 -f 9376 9374 9371 -f 9376 9371 9375 -f 9375 9371 9370 -f 9375 9370 9384 -f 9384 9370 9368 -f 9384 9368 9386 -f 9386 9368 9369 -f 9386 9369 9257 -f 9405 9330 9403 -f 9398 9388 9415 -f 9427 9390 9391 -f 9427 9391 9330 -f 9427 9330 9392 -f 9406 9404 9394 -f 9394 9404 9393 -f 9402 9396 9393 -f 9393 9396 9394 -f 9398 9395 9402 -f 9402 9395 9396 -f 9398 9397 9395 -f 9388 9398 9389 -f 9389 9398 9401 -f 9389 9401 9390 -f 9390 9401 9399 -f 9390 9399 9391 -f 9391 9399 9403 -f 9391 9403 9330 -f 9415 9400 9397 -f 9415 9397 9398 -f 9401 9398 9402 -f 9401 9402 9399 -f 9399 9402 9393 -f 9399 9393 9403 -f 9403 9393 9404 -f 9403 9404 9405 -f 9405 9404 9406 -f 9423 9412 9410 -f 9372 9407 9373 -f 9373 9407 9409 -f 9374 9373 9409 -f 9371 9374 9408 -f 9369 9368 9423 -f 9423 9368 9412 -f 9412 9368 9370 -f 9407 7632 9409 -f 9409 7632 9416 -f 9421 9410 9411 -f 9411 9410 9412 -f 9411 9412 9420 -f 9420 9412 9370 -f 9420 9370 9371 -f 9425 9426 9422 -f 9413 9414 9426 -f 9426 9414 8064 -f 9426 8064 9422 -f 9422 8064 9424 -f 9400 9415 7631 -f 7631 9415 9417 -f 7631 9417 9416 -f 7631 9416 7632 -f 9374 9409 9408 -f 9408 9409 9416 -f 9408 9416 9418 -f 9418 9416 9417 -f 9418 9417 9419 -f 9419 9417 9415 -f 9415 9388 9419 -f 9371 9408 9420 -f 9420 9408 9418 -f 9420 9418 9411 -f 9411 9418 9419 -f 9411 9419 9421 -f 9421 9419 9388 -f 9421 9388 9389 -f 9421 9389 9425 -f 9421 9425 9410 -f 9410 9425 9422 -f 9410 9422 9423 -f 9423 9422 9424 -f 9423 9424 9369 -f 9389 9390 9425 -f 9425 9390 9426 -f 9426 9390 9427 -f 9426 9427 9413 -f 9413 9427 9392 -f 8135 9436 8029 -f 9429 7593 9428 -f 9436 8135 9440 -f 9430 7593 9429 -f 7593 9441 9428 -f 8122 7593 9430 -f 8132 8127 9443 -f 8118 8119 9432 -f 8122 9432 7593 -f 7611 9433 7608 -f 8119 9431 9432 -f 7614 9433 7611 -f 7608 9431 7611 -f 8131 9440 8134 -f 9442 9434 8077 -f 8037 8031 8029 -f 7607 7604 7608 -f 9436 9435 9437 -f 8037 8029 9438 -f 8135 8134 9440 -f 9447 9439 9449 -f 9431 8119 7611 -f 9436 9438 8029 -f 8131 8132 9443 -f 9436 9437 9438 -f 8127 8125 9443 -f 9432 8122 8118 -f 9449 9439 8114 -f 9440 8131 9443 -f 7595 9441 7593 -f 9443 8125 8048 -f 7597 9441 7595 -f 8125 9441 8048 -f 9441 8125 9428 -f 8026 8024 8048 -f 8048 9441 9446 -f 8048 9446 9447 -f 9447 8092 8087 -f 8099 9444 9446 -f 8078 9446 9442 -f 8105 8099 9446 -f 9446 8082 9442 -f 8078 9442 8077 -f 8078 8103 9446 -f 8024 9443 8048 -f 8105 9446 8103 -f 9447 9444 9464 -f 9445 9449 8114 -f 9444 9447 9446 -f 8087 9439 9447 -f 7608 7604 9431 -f 8092 9447 9448 -f 8110 9447 9449 -f 9450 1856 1872 -f 1953 9452 1819 -f 1834 9455 1835 -f 9476 9480 1965 -f 1955 1954 9460 -f 9452 1953 1950 -f 9451 9452 1950 -f 1814 1810 1838 -f 1835 1838 1836 -f 1953 9607 148 -f 1810 1836 1838 -f 154 148 9454 -f 148 9607 9454 -f 1862 1859 9602 -f 9600 9475 9598 -f 145 1953 148 -f 1831 9455 1834 -f 9455 9491 1853 -f 1829 9587 1831 -f 1954 9451 1950 -f 1838 1835 1853 -f 1842 1841 9456 -f 9457 9598 9475 -f 9491 1852 1853 -f 9458 9459 9460 -f 1823 9452 9451 -f 1844 9468 9473 -f 1849 1854 1852 -f 9458 1952 9459 -f 9461 1857 9602 -f 1954 1950 9460 -f 9462 1947 1948 -f 1949 1948 9465 -f 1840 9474 9466 -f 1840 9466 9456 -f 9482 9463 9483 -f 9448 9447 9464 -f 9474 1843 9466 -f 1810 1808 9583 -f 1946 9467 9609 -f 9474 9468 1843 -f 1862 9602 1857 -f 9469 9453 9603 -f 9467 1945 9470 -f 1829 1827 9587 -f 9474 1855 1846 -f 1949 9467 9470 -f 9471 9472 1956 -f 9597 9468 1844 -f 9471 1949 9472 -f 9473 9474 1846 -f 9459 1955 9460 -f 1846 1855 1847 -f 1952 9471 1956 -f 1849 1847 1854 -f 1952 1956 9459 -f 1949 9470 9472 -f 1825 9451 9546 -f 1870 9478 1871 -f 1962 9457 9475 -f 2098 1962 9475 -f 1825 1823 9451 -f 9479 9476 1965 -f 9478 1870 9593 -f 1862 9450 1863 -f 2100 9463 9477 -f 9478 9595 1871 -f 9592 9476 2100 -f 9578 7325 9579 -f 9479 1965 1964 -f 1870 1869 9593 -f 9463 1966 9477 -f 9477 9592 2100 -f 9482 9487 1868 -f 1869 1868 9487 -f 9468 9481 1843 -f 9466 1842 9456 -f 9482 1966 9463 -f 1948 1947 9465 -f 2060 9482 9483 -f 9483 9486 2060 -f 9483 9484 9486 -f 9484 1784 9486 -f 1797 9485 9484 -f 1784 9488 9486 -f 9485 1784 9484 -f 9488 161 9486 -f 166 161 9488 -f 1837 1794 9485 -f 1774 1763 9488 -f 1781 1774 9488 -f 1837 172 9489 -f 1763 1774 9506 -f 1768 1767 9493 -f 9489 170 169 -f 9493 9490 1763 -f 1837 9489 9495 -f 1849 1852 9491 -f 9492 9493 1763 -f 2611 9494 2224 -f 1795 1837 9495 -f 9587 9455 1831 -f 1797 1801 9485 -f 1794 1837 1795 -f 9485 1782 1784 -f 9485 1794 1789 -f 1785 1781 9488 -f 9485 1789 1782 -f 1784 1785 9488 -f 9504 2341 2682 -f 2682 2675 2316 -f 5257 9512 9496 -f 2270 2356 2358 -f 9496 2361 5257 -f 2270 9497 2356 -f 2361 9498 5257 -f 9509 2652 2358 -f 2270 2355 9497 -f 9499 9514 2349 -f 9500 2349 2353 -f 2353 2349 9501 -f 2349 5256 9501 -f 2665 9502 9521 -f 9504 2682 2342 -f 2342 9503 9504 -f 2328 2652 9511 -f 2341 2355 2682 -f 9516 9505 4372 -f 7032 7016 9519 -f 1763 9506 9492 -f 9507 9510 5256 -f 2270 2682 2355 -f 9507 5256 5257 -f 9498 9507 5257 -f 9508 9512 5257 -f 9522 9521 7016 -f 9512 9509 9496 -f 9508 2275 9512 -f 9512 2652 9509 -f 5256 9510 9501 -f 2326 2328 9511 -f 2275 2281 9512 -f 2652 2328 2270 -f 9515 2682 2316 -f 2665 2652 9502 -f 9518 4924 7021 -f 9523 2665 9521 -f 9513 4323 2605 -f 7020 7000 7016 -f 9523 9513 2605 -f 4323 2221 2605 -f 2605 9520 4367 -f 2652 2270 2358 -f 2605 4367 9505 -f 9519 9518 7021 -f 2652 9512 9502 -f 2349 9514 5256 -f 2682 9515 2342 -f 7000 9522 7016 -f 9516 2605 9505 -f 9517 7016 7032 -f 7016 9518 9519 -f 7020 7016 9517 -f 2605 2221 9520 -f 4372 4365 9516 -f 1835 9455 1853 -f 9523 9521 4338 -f 9521 9522 9584 -f 9513 9523 4338 -f 5879 5032 5157 -f 9533 9524 2250 -f 9569 9533 2249 -f 3289 9525 2229 -f 2248 9570 9569 -f 9534 2250 5169 -f 9526 9527 9528 -f 2250 9524 9529 -f 2263 9527 2266 -f 9526 9530 2266 -f 9611 4751 2612 -f 9531 4930 9532 -f 9610 2603 2601 -f 9534 9531 9532 -f 2229 9526 9528 -f 2249 9533 2250 -f 2248 9569 2249 -f 5177 9534 5169 -f 2229 9528 9535 -f 5177 9531 9534 -f 9580 3282 3283 -f 2503 3288 9535 -f 9561 3292 9562 -f 2504 3288 2503 -f 9536 9549 2504 -f 9567 9549 9536 -f 5870 9551 9529 -f 3288 3289 9535 -f 3289 2229 9535 -f 3277 9540 3259 -f 5159 9537 5871 -f 5158 5159 5871 -f 9548 5876 5157 -f 9580 3259 9539 -f 3261 3277 3259 -f 9580 9539 9542 -f 9538 5879 5157 -f 5032 5879 5880 -f 5849 5032 5880 -f 9539 3259 9540 -f 5880 9543 5849 -f 9547 3277 3261 -f 5876 9541 5157 -f 2501 9580 9544 -f 9580 9542 3282 -f 5880 5863 9543 -f 5169 2250 9529 -f 2502 2501 9544 -f 9577 9545 2611 -f 5863 5846 9543 -f 1827 1825 9546 -f 9547 3276 3277 -f 9538 5157 5878 -f 9568 9544 9550 -f 5878 5157 9541 -f 9548 5158 5871 -f 9568 2502 9544 -f 5876 9548 5871 -f 9549 3286 2504 -f 9549 9567 9550 -f 5871 9537 9552 -f 3286 3288 2504 -f 9537 9551 9552 -f 9524 5870 9529 -f 9551 5870 9552 -f 3228 9525 3289 -f 9566 2251 9553 -f 9527 9526 2266 -f 9524 9565 5868 -f 9556 5815 5820 -f 5868 9563 5866 -f 9558 9560 9562 -f 9562 3273 9558 -f 3273 3274 3240 -f 3273 3240 9555 -f 9525 9553 2229 -f 5815 9556 5866 -f 9532 9557 9534 -f 9554 9556 5820 -f 9564 5815 5866 -f 9558 3273 9559 -f 9559 3273 9555 -f 9560 9561 9562 -f 9563 9564 5866 -f 9561 3228 3292 -f 3228 3289 3292 -f 9533 9565 9524 -f 9565 9563 5868 -f 9525 9566 9553 -f 9570 2251 9566 -f 9567 9568 9550 -f 9569 9570 9566 -f 9566 5812 9569 -f 9566 3232 5812 -f 3232 9572 5812 -f 3232 9571 9572 -f 9571 9573 9572 -f 9571 9575 9573 -f 9575 9574 9573 -f 9575 9576 9574 -f 9576 4347 9574 -f 9576 2611 9585 -f 9576 9577 2611 -f 9574 4347 9579 -f 9582 9578 9579 -f 9579 5811 9581 -f 9579 1797 5811 -f 9545 161 2611 -f 9554 5860 9556 -f 9581 9574 9579 -f 1855 1854 1847 -f 2612 4751 2611 -f 7396 7400 9579 -f 7325 7396 9579 -f 2603 9610 2612 -f 7400 5196 9579 -f 9580 3283 9544 -f 2611 2224 4346 -f 1860 9608 1861 -f 1958 9475 9600 -f 2611 4346 9585 -f 1861 1859 1862 -f 9582 9579 4347 -f 9468 9474 9473 -f 1806 1836 9583 -f 4338 9521 9584 -f 4347 9576 9585 -f 7385 5192 5196 -f 5195 5811 1797 -f 161 9545 9586 -f 9579 5195 1797 -f 161 9586 2611 -f 9587 1827 9546 -f 9546 1851 9587 -f 9546 1942 1851 -f 1942 9588 1851 -f 1942 126 9588 -f 126 1865 9588 -f 126 9589 1865 -f 9589 1867 1865 -f 9589 1966 1867 -f 1966 9482 1867 -f 5192 9590 5196 -f 1867 9482 1868 -f 9593 1869 9487 -f 9591 9590 5190 -f 5190 9590 5192 -f 9592 9480 9476 -f 9594 9479 1964 -f 2098 9594 1964 -f 9595 1872 1871 -f 1964 1962 2098 -f 9595 9450 1872 -f 9469 9603 9457 -f 1857 1856 9450 -f 1836 1810 9583 -f 2603 2602 2601 -f 9450 1862 1857 -f 9489 169 9495 -f 9596 1857 9461 -f 9492 1768 9493 -f 9457 9603 9598 -f 1858 9461 9602 -f 9609 1949 9465 -f 9603 1959 9598 -f 9599 9600 9598 -f 9601 9602 1859 -f 9453 1960 9603 -f 9598 9604 9605 -f 9605 9599 9598 -f 9606 1859 9608 -f 7400 7385 5196 -f 1953 1819 9607 -f 1861 9608 1859 -f 9467 1949 9609 -f 9610 9611 2612 -f 4751 9612 2611 -f 9690 9619 9617 -f 9619 9690 9660 -f 9688 9614 9613 -f 9703 9694 9701 -f 9664 9614 9688 -f 9701 9694 9616 -f 9613 9660 9688 -f 9660 9690 9688 -f 9664 9688 9687 -f 9616 9694 9692 -f 9641 9615 9697 -f 9615 9692 9697 -f 9615 9616 9692 -f 9699 9700 9687 -f 9703 9695 9694 -f 9687 9617 9699 -f 9700 9664 9687 -f 9668 9667 9617 -f 9699 9617 9665 -f 9617 9667 9665 -f 9684 9683 9682 -f 9684 9682 9703 -f 9682 9695 9703 -f 9682 9625 9695 -f 9641 9695 9643 -f 9697 9695 9641 -f 9668 9620 9618 -f 9619 9668 9617 -f 9619 9620 9668 -f 9655 9654 9671 -f 9654 9651 9671 -f 9618 9669 9668 -f 9618 9655 9669 -f 9655 9670 9669 -f 9655 9671 9670 -f 9695 9644 9643 -f 9695 9625 9644 -f 9625 9621 9644 -f 9671 9651 9672 -f 9651 9622 9672 -f 9651 9648 9622 -f 9622 9648 9674 -f 9648 9647 9674 -f 9647 9677 9674 -f 9647 9623 9677 -f 9623 9678 9677 -f 9623 9679 9678 -f 9623 9624 9679 -f 9624 9625 9679 -f 9624 9621 9625 -f 9691 9663 9689 -f 9698 9686 9628 -f 9693 9642 9696 -f 9642 9626 9696 -f 9638 9702 9627 -f 9661 9663 9691 -f 9663 9662 9689 -f 9628 9686 9689 -f 9626 9638 9696 -f 9627 9685 9693 -f 9698 9632 9686 -f 9638 9704 9702 -f 9693 9685 9642 -f 9662 9628 9689 -f 9632 9698 9630 -f 9632 9666 9629 -f 9632 9630 9666 -f 9638 9681 9631 -f 9638 9631 9704 -f 9631 9683 9704 -f 9691 9632 9661 -f 9632 9659 9661 -f 9632 9658 9659 -f 9632 9629 9658 -f 9629 9657 9658 -f 9652 9653 9636 -f 9629 9656 9657 -f 9629 9633 9656 -f 9633 9634 9656 -f 9634 9653 9656 -f 9634 9635 9653 -f 9635 9636 9653 -f 9649 9650 9675 -f 9650 9673 9675 -f 9650 9652 9673 -f 9652 9636 9673 -f 9646 9649 9640 -f 9649 9676 9640 -f 9649 9675 9676 -f 9637 9639 9681 -f 9681 9645 9637 -f 9638 9645 9681 -f 9638 9626 9645 -f 9639 9680 9681 -f 9639 9646 9680 -f 9646 9640 9680 -f 9615 9641 9642 -f 9641 9626 9642 -f 9641 9643 9626 -f 9643 9645 9626 -f 9643 9644 9645 -f 9644 9637 9645 -f 9644 9621 9637 -f 9621 9624 9637 -f 9624 9639 9637 -f 9624 9623 9639 -f 9623 9646 9639 -f 9623 9647 9646 -f 9647 9649 9646 -f 9647 9648 9649 -f 9648 9650 9649 -f 9648 9651 9650 -f 9651 9652 9650 -f 9651 9654 9652 -f 9654 9653 9652 -f 9654 9655 9653 -f 9655 9656 9653 -f 9655 9618 9656 -f 9618 9657 9656 -f 9618 9620 9657 -f 9620 9658 9657 -f 9620 9619 9658 -f 9619 9659 9658 -f 9619 9660 9659 -f 9660 9661 9659 -f 9660 9613 9661 -f 9613 9663 9661 -f 9614 9662 9613 -f 9662 9663 9613 -f 9614 9628 9662 -f 9614 9664 9628 -f 9664 9698 9628 -f 9664 9700 9698 -f 9699 9698 9700 -f 9665 9666 9630 -f 9665 9629 9666 -f 9665 9667 9629 -f 9667 9668 9629 -f 9668 9633 9629 -f 9668 9669 9633 -f 9669 9634 9633 -f 9669 9670 9634 -f 9670 9635 9634 -f 9670 9671 9635 -f 9671 9636 9635 -f 9671 9672 9636 -f 9672 9673 9636 -f 9672 9622 9673 -f 9622 9675 9673 -f 9622 9674 9675 -f 9674 9676 9675 -f 9674 9677 9676 -f 9677 9640 9676 -f 9677 9678 9640 -f 9678 9680 9640 -f 9678 9679 9680 -f 9679 9681 9680 -f 9679 9625 9681 -f 9625 9631 9681 -f 9625 9682 9631 -f 9682 9683 9631 -f 9684 9704 9683 -f 9684 9703 9704 -f 9701 9702 9703 -f 9702 9704 9703 -f 9701 9627 9702 -f 9701 9616 9627 -f 9616 9685 9627 -f 9615 9642 9616 -f 9642 9685 9616 -f 9687 9689 9686 -f 9687 9688 9689 -f 9688 9691 9689 -f 9688 9690 9691 -f 9690 9617 9691 -f 9617 9632 9691 -f 9617 9687 9632 -f 9687 9686 9632 -f 9692 9627 9693 -f 9692 9694 9627 -f 9694 9638 9627 -f 9694 9695 9638 -f 9695 9697 9638 -f 9697 9696 9638 -f 9697 9692 9696 -f 9692 9693 9696 -f 9699 9630 9698 -f 9699 9665 9630 -f 9717 9828 9829 -f 9717 9705 9828 -f 9705 9706 9828 -f 9705 9719 9706 -f 9719 9708 9706 -f 9719 9707 9708 -f 9707 9826 9708 -f 9707 9721 9826 -f 9721 9827 9826 -f 9721 9709 9827 -f 9721 9710 9709 -f 9710 9711 9709 -f 9710 9712 9711 -f 9710 9722 9712 -f 9722 9825 9712 -f 9722 9723 9825 -f 9825 9723 9823 -f 9723 9725 9823 -f 9725 9822 9823 -f 9725 9726 9822 -f 9726 9821 9822 -f 9726 9727 9821 -f 9727 9820 9821 -f 9727 9819 9820 -f 9727 9728 9819 -f 9728 9713 9819 -f 9713 9832 9819 -f 9713 9830 9832 -f 9713 9716 9830 -f 9716 9857 9830 -f 9716 9854 9857 -f 9716 9717 9854 -f 9717 9829 9854 -f 9714 9713 9728 -f 9714 9715 9713 -f 9715 9716 9713 -f 9715 9737 9716 -f 9737 9717 9716 -f 9737 9718 9717 -f 9718 9738 9717 -f 9738 9705 9717 -f 9738 9731 9705 -f 9731 9719 9705 -f 9731 9736 9719 -f 9736 9707 9719 -f 9736 9720 9707 -f 9720 9721 9707 -f 9720 9765 9721 -f 9765 9735 9721 -f 9735 9734 9721 -f 9734 9710 9721 -f 9734 9767 9710 -f 9767 9722 9710 -f 9767 9730 9722 -f 9730 9723 9722 -f 9730 9724 9723 -f 9724 9725 9723 -f 9724 9733 9725 -f 9733 9726 9725 -f 9733 9732 9726 -f 9732 9727 9726 -f 9732 9729 9727 -f 9729 9714 9727 -f 9714 9728 9727 -f 9714 9729 9732 -f 9730 9767 9761 -f 9736 9731 9765 -f 9733 9724 9766 -f 9734 9735 9765 -f 9720 9736 9765 -f 9737 9715 9762 -f 9715 9714 9762 -f 9739 9775 9755 -f 9775 9749 9755 -f 9775 9788 9749 -f 9772 9773 9742 -f 9773 9745 9742 -f 9745 9780 9746 -f 9780 9783 9746 -f 9783 9747 9746 -f 9783 9740 9747 -f 9739 9755 9748 -f 9790 9770 9741 -f 9770 9754 9741 -f 9770 9771 9754 -f 9742 9745 9743 -f 9790 9741 9744 -f 9739 9748 9740 -f 9742 9743 9751 -f 9747 9740 9748 -f 9755 9749 9753 -f 9744 9750 9752 -f 9744 9741 9750 -f 9771 9742 9754 -f 9749 9752 9753 -f 9749 9744 9752 -f 9750 9741 9766 -f 9741 9754 9766 -f 9745 9746 9759 -f 9754 9742 9751 -f 9743 9745 9762 -f 9759 9746 9760 -f 9746 9747 9760 -f 9762 9745 9759 -f 9751 9743 9756 -f 9743 9762 9756 -f 9748 9755 9758 -f 9752 9757 9753 -f 9754 9751 9766 -f 9747 9748 9764 -f 9752 9750 9761 -f 9750 9768 9761 -f 9750 9766 9768 -f 9748 9758 9764 -f 9755 9763 9758 -f 9755 9753 9763 -f 9763 9753 9757 -f 9747 9764 9760 -f 9757 9752 9761 -f 9760 9764 9738 -f 9751 9756 9732 -f 9759 9760 9718 -f 9760 9738 9718 -f 9738 9764 9731 -f 9764 9758 9731 -f 9758 9765 9731 -f 9758 9763 9765 -f 9763 9757 9765 -f 9757 9761 9767 -f 9766 9732 9733 -f 9766 9751 9732 -f 9756 9762 9714 -f 9759 9737 9762 -f 9759 9718 9737 -f 9757 9734 9765 -f 9757 9767 9734 -f 9761 9768 9730 -f 9768 9724 9730 -f 9768 9766 9724 -f 9756 9714 9732 -f 9789 9744 9749 -f 9789 9769 9744 -f 9769 9790 9744 -f 9791 9770 9790 -f 9788 9789 9749 -f 9770 9792 9771 -f 9792 9772 9771 -f 9772 9742 9771 -f 9776 9739 9740 -f 9776 9774 9739 -f 9782 9783 9780 -f 9773 9777 9745 -f 9777 9778 9745 -f 9783 9776 9740 -f 9778 9779 9745 -f 9779 9780 9745 -f 9793 9876 9773 -f 9876 9777 9773 -f 9876 9875 9777 -f 9875 9778 9777 -f 9875 9873 9778 -f 9873 9779 9778 -f 9873 9871 9779 -f 9871 9780 9779 -f 9871 9781 9780 -f 9781 9782 9780 -f 9781 9874 9782 -f 9874 9783 9782 -f 9874 9784 9783 -f 9784 9776 9783 -f 9784 9785 9776 -f 9785 9774 9776 -f 9785 9870 9774 -f 9870 9739 9774 -f 9870 9775 9739 -f 9870 9786 9775 -f 9786 9788 9775 -f 9786 9787 9788 -f 9787 9789 9788 -f 9787 9865 9789 -f 9865 9864 9789 -f 9864 9769 9789 -f 9864 9863 9769 -f 9863 9790 9769 -f 9863 9867 9790 -f 9867 9791 9790 -f 9867 9770 9791 -f 9867 9868 9770 -f 9868 9866 9770 -f 9866 9792 9770 -f 9866 9772 9792 -f 9866 9862 9772 -f 9862 9793 9772 -f 9793 9773 9772 -f 9802 9844 9974 -f 9802 9976 9844 -f 9976 9848 9844 -f 9976 9794 9848 -f 9794 9835 9848 -f 9794 9977 9835 -f 9977 9795 9835 -f 9977 9966 9795 -f 9966 9796 9795 -f 9796 9842 9795 -f 9796 9980 9842 -f 9980 9834 9842 -f 9980 9797 9834 -f 9797 9833 9834 -f 9797 9845 9833 -f 9797 9967 9845 -f 9975 9846 9967 -f 9975 9840 9846 -f 9979 9798 9840 -f 9979 9978 9798 -f 9978 9799 9798 -f 9978 9839 9799 -f 9978 9968 9839 -f 9968 9838 9839 -f 9968 9973 9838 -f 9973 9841 9838 -f 9973 9969 9841 -f 9837 9970 9836 -f 9970 9800 9836 -f 9970 9972 9800 -f 9972 9843 9800 -f 9972 9971 9843 -f 9971 9847 9843 -f 9801 9974 9847 -f 9803 9842 9834 -f 9803 9795 9842 -f 9815 9835 9795 -f 9803 9845 9846 -f 9803 9833 9845 -f 9803 9834 9833 -f 9811 9838 9841 -f 9838 9811 9839 -f 9811 9799 9839 -f 9811 9846 9799 -f 9846 9798 9799 -f 9812 9843 9847 -f 9812 9836 9843 -f 9836 9800 9843 -f 9811 9841 9836 -f 9835 9815 9848 -f 9815 9816 9848 -f 9816 9844 9848 -f 9851 9805 9811 -f 9856 9859 9849 -f 9856 9813 9859 -f 9853 9809 9804 -f 9853 9852 9809 -f 9852 9811 9809 -f 9852 9851 9811 -f 9808 9806 9814 -f 9831 9812 9817 -f 9831 9804 9812 -f 9804 9809 9812 -f 9859 9810 9807 -f 9808 9814 9805 -f 9807 9803 9806 -f 9807 9810 9803 -f 9813 9815 9859 -f 9817 9816 9813 -f 9859 9815 9810 -f 9816 9817 9812 -f 9805 9814 9846 -f 9813 9816 9815 -f 9809 9836 9812 -f 9805 9846 9811 -f 9814 9806 9846 -f 9806 9803 9846 -f 9812 9847 9816 -f 9810 9815 9795 -f 9809 9811 9836 -f 9810 9795 9803 -f 9807 9855 9861 -f 9807 9806 9855 -f 9806 9808 9855 -f 9807 9861 9859 -f 9808 9805 9858 -f 9805 9850 9858 -f 9805 9851 9850 -f 9817 9860 9831 -f 9813 9856 9817 -f 9820 9819 9856 -f 9819 9818 9856 -f 9821 9820 9849 -f 9820 9856 9849 -f 9822 9821 9849 -f 9849 9824 9822 -f 9824 9823 9822 -f 9823 9824 9861 -f 9825 9823 9861 -f 9855 9712 9825 -f 9711 9712 9808 -f 9808 9709 9711 -f 9709 9808 9858 -f 9827 9709 9858 -f 9827 9858 9850 -f 9826 9827 9850 -f 9850 9851 9826 -f 9851 9708 9826 -f 9706 9708 9852 -f 9708 9851 9852 -f 9706 9853 9828 -f 9829 9828 9853 -f 9829 9853 9804 -f 9854 9829 9804 -f 9830 9857 9831 -f 9831 9860 9830 -f 9860 9832 9830 -f 9819 9832 9818 -f 9832 9860 9818 -f 9836 9969 9837 -f 9969 9836 9841 -f 9847 9974 9816 -f 9840 9798 9846 -f 9816 9974 9844 -f 9967 9846 9845 -f 9861 9855 9825 -f 9712 9855 9808 -f 9853 9706 9852 -f 9818 9860 9817 -f 9857 9854 9831 -f 9854 9804 9831 -f 9861 9824 9859 -f 9824 9849 9859 -f 9818 9817 9856 -f 9793 9862 9903 -f 9862 9866 9903 -f 9863 9864 9900 -f 9864 9865 9900 -f 9785 9784 9904 -f 9866 9868 9902 -f 9781 9871 9872 -f 9787 9786 9869 -f 9786 9870 9869 -f 9870 9785 9904 -f 9871 9873 9872 -f 9876 9793 9903 -f 9784 9874 9904 -f 9876 9903 9875 -f 9918 9885 9881 -f 9918 9910 9885 -f 9910 9882 9885 -f 9913 9877 9882 -f 9913 9915 9877 -f 9915 9919 9877 -f 9919 9911 9877 -f 9911 9894 9877 -f 9911 9912 9894 -f 9912 9878 9894 -f 9909 9880 9891 -f 9916 9881 9880 -f 9907 9891 9884 -f 9891 9880 9893 -f 9893 9880 9881 -f 9894 9878 9896 -f 9878 9879 9896 -f 9879 9883 9887 -f 9883 9884 9889 -f 9882 9886 9885 -f 9879 9887 9896 -f 9887 9883 9889 -f 9882 9877 9888 -f 9877 9894 9890 -f 9901 9884 9897 -f 9882 9888 9886 -f 9877 9890 9888 -f 9889 9884 9901 -f 9884 9891 9897 -f 9889 9901 9900 -f 9894 9896 9892 -f 9891 9893 9897 -f 9893 9881 9895 -f 9895 9881 9898 -f 9881 9885 9898 -f 9894 9892 9890 -f 9887 9899 9896 -f 9893 9895 9897 -f 9885 9886 9898 -f 9886 9872 9898 -f 9886 9888 9872 -f 9888 9890 9904 -f 9887 9889 9899 -f 9889 9900 9899 -f 9890 9892 9904 -f 9892 9896 9869 -f 9896 9899 9869 -f 9901 9897 9902 -f 9902 9897 9903 -f 9895 9898 9903 -f 9897 9895 9903 -f 9901 9868 9900 -f 9901 9902 9868 -f 9903 9898 9875 -f 9872 9888 9874 -f 9888 9904 9874 -f 9892 9869 9904 -f 9869 9899 9787 -f 9875 9898 9873 -f 9898 9872 9873 -f 9872 9874 9781 -f 9904 9869 9870 -f 9787 9899 9865 -f 9899 9900 9865 -f 9900 9867 9863 -f 9900 9868 9867 -f 9902 9903 9866 -f 9906 9905 9883 -f 9905 9923 9883 -f 9923 9884 9883 -f 9923 9924 9884 -f 9924 9907 9884 -f 9906 9883 9879 -f 9907 9908 9891 -f 9908 9909 9891 -f 9910 9913 9882 -f 9912 9914 9878 -f 9879 9878 9914 -f 9916 9918 9881 -f 9926 9990 9916 -f 9990 9918 9916 -f 9990 9917 9918 -f 9917 9910 9918 -f 9917 9984 9910 -f 9984 9913 9910 -f 9984 9989 9913 -f 9989 10012 9913 -f 10012 9915 9913 -f 10012 9920 9915 -f 9920 9919 9915 -f 9920 9988 9919 -f 9988 9911 9919 -f 9988 9912 9911 -f 9988 9987 9912 -f 9987 9921 9912 -f 9921 9914 9912 -f 9921 9986 9914 -f 9986 9879 9914 -f 9986 9985 9879 -f 9985 9906 9879 -f 9985 9922 9906 -f 9922 9905 9906 -f 9922 10016 9905 -f 10016 9923 9905 -f 10016 9981 9923 -f 9981 9924 9923 -f 9981 9983 9924 -f 9983 9907 9924 -f 9983 9982 9907 -f 9982 9908 9907 -f 9982 9925 9908 -f 9925 9909 9908 -f 9925 9880 9909 -f 9925 9926 9880 -f 9926 9916 9880 -f 10094 9947 9927 -f 10094 9928 9947 -f 9928 9955 9947 -f 9928 10090 9955 -f 10090 9946 9955 -f 10090 10095 9946 -f 10095 9954 9946 -f 10095 10096 9954 -f 10096 9963 9954 -f 10096 9929 9963 -f 9930 9961 9929 -f 9930 9965 9961 -f 10091 9953 9965 -f 10091 10087 9953 -f 10087 9931 9953 -f 10089 9960 9931 -f 10071 9959 9960 -f 9932 10093 9933 -f 10093 9964 9933 -f 10088 9958 9964 -f 10088 10072 9958 -f 10072 9934 9958 -f 10072 9935 9934 -f 9935 9957 9934 -f 9935 9936 9957 -f 9936 9962 9957 -f 9936 10092 9962 -f 10092 9956 9962 -f 10092 9927 9956 -f 9961 9946 9963 -f 9949 9953 9931 -f 9949 9959 9944 -f 9948 9942 9957 -f 9942 9934 9957 -f 9942 9958 9934 -f 9942 9944 9958 -f 9946 9950 9955 -f 9950 9947 9955 -f 9947 9948 9956 -f 9971 9937 9940 -f 9973 9938 9941 -f 9952 9797 9945 -f 9797 9943 9945 -f 9797 9951 9943 -f 9939 9950 9951 -f 9939 9940 9950 -f 9940 9937 9948 -f 9941 9942 9937 -f 9938 9952 9944 -f 9952 9949 9944 -f 9941 9938 9944 -f 9937 9942 9948 -f 9952 9945 9949 -f 9940 9948 9950 -f 9941 9944 9942 -f 9951 9961 9943 -f 9951 9946 9961 -f 9943 9961 9945 -f 9950 9946 9951 -f 9948 9947 9950 -f 9945 9953 9949 -f 9945 9965 9953 -f 9945 9961 9965 -f 9951 9797 9980 -f 9952 9975 9797 -f 9952 9979 9975 -f 9939 9966 9977 -f 9939 9951 9966 -f 9951 9796 9966 -f 9951 9980 9796 -f 9952 9978 9979 -f 9952 9938 9978 -f 9938 9968 9978 -f 9938 9973 9968 -f 9940 9801 9971 -f 9939 9976 9940 -f 9941 9937 9970 -f 9937 9972 9970 -f 9937 9971 9972 -f 9962 9956 9948 -f 9954 9963 9946 -f 9931 9960 9949 -f 9959 9932 9944 -f 9932 9933 9944 -f 9933 9964 9944 -f 9964 9958 9944 -f 9957 9962 9948 -f 9929 9961 9963 -f 9960 9959 9949 -f 9927 9947 9956 -f 9801 9847 9971 -f 9802 9974 9940 -f 9974 9801 9940 -f 9837 9941 9970 -f 9837 9969 9941 -f 9840 9975 9979 -f 9967 9797 9975 -f 9794 9976 9939 -f 9976 9802 9940 -f 9941 9969 9973 -f 9977 9794 9939 -f 9988 10013 10009 -f 9988 9920 10013 -f 9925 9982 10017 -f 9922 9985 10016 -f 9982 9983 10002 -f 9983 9981 10002 -f 10016 9985 10014 -f 9985 9986 10014 -f 9921 10009 9986 -f 9921 9987 10009 -f 9988 10009 9987 -f 9989 9984 10012 -f 9917 10010 9984 -f 9990 9926 10015 -f 9926 9925 10015 -f 9920 10012 10013 -f 9917 9990 10010 -f 10028 10004 9993 -f 10028 9991 10004 -f 9991 10027 10029 -f 10029 10026 9998 -f 10026 10021 9998 -f 10022 9995 10021 -f 10024 10019 9995 -f 9992 10036 10001 -f 10041 9994 10042 -f 10044 9993 9994 -f 10036 10039 10001 -f 10039 10042 10001 -f 9991 10029 10005 -f 10029 9998 10005 -f 9995 10019 10003 -f 10019 9992 10003 -f 9991 10005 10004 -f 10042 9997 10001 -f 10042 9994 9997 -f 9998 10021 10000 -f 9994 9993 9999 -f 10021 10006 10000 -f 9994 9999 9997 -f 9993 10004 9996 -f 10021 9995 10006 -f 9999 9993 9996 -f 9995 10014 10006 -f 9995 10003 10014 -f 10003 9992 10007 -f 9992 10001 10007 -f 9997 10002 10008 -f 10001 9997 10008 -f 9997 9999 10002 -f 10005 9998 10011 -f 9998 10013 10011 -f 10007 10001 10008 -f 10004 10010 9996 -f 10004 10005 10010 -f 9998 10000 10013 -f 10006 10014 10009 -f 9999 9996 10015 -f 10000 10006 10013 -f 10003 10007 10014 -f 10002 9999 10017 -f 9996 10010 10015 -f 10005 10011 10010 -f 9999 10015 10017 -f 10011 10013 10012 -f 10006 10009 10013 -f 10007 10008 10016 -f 10010 10011 9984 -f 10007 10016 10014 -f 9984 10011 10012 -f 10016 10008 9981 -f 10008 10002 9981 -f 10015 10010 9990 -f 10009 10014 9986 -f 10002 10017 9982 -f 10017 10015 9925 -f 10035 10036 9992 -f 10035 9992 10019 -f 10041 10018 9994 -f 10018 10044 9994 -f 10044 10025 9993 -f 10020 10022 10021 -f 10022 10023 9995 -f 10023 10024 9995 -f 10025 10028 9993 -f 10020 10021 10026 -f 10115 10116 10025 -f 10116 10028 10025 -f 10116 9991 10028 -f 10116 10117 9991 -f 10117 10027 9991 -f 10117 10118 10027 -f 10118 10119 10027 -f 10119 10029 10027 -f 10119 10030 10029 -f 10030 10026 10029 -f 10030 10020 10026 -f 10030 10031 10020 -f 10031 10113 10020 -f 10113 10022 10020 -f 10113 10023 10022 -f 10113 10032 10023 -f 10032 10024 10023 -f 10032 10111 10024 -f 10111 10019 10024 -f 10111 10033 10019 -f 10033 10035 10019 -f 10033 10034 10035 -f 10034 10037 10035 -f 10037 10036 10035 -f 10037 10038 10036 -f 10038 10039 10036 -f 10038 10040 10039 -f 10038 10108 10040 -f 10108 10039 10040 -f 10108 10042 10039 -f 10108 10043 10042 -f 10043 10041 10042 -f 10043 10109 10041 -f 10109 10018 10041 -f 10109 10112 10018 -f 10112 10044 10018 -f 10112 10110 10044 -f 10110 10025 10044 -f 10110 10115 10025 -f 10114 10045 10046 -f 10045 10074 10046 -f 10045 10083 10074 -f 10097 10047 10083 -f 10097 10098 10047 -f 10098 10085 10047 -f 10098 10099 10085 -f 10099 10048 10085 -f 10099 10104 10048 -f 10104 10100 10049 -f 10100 10101 10049 -f 10101 10073 10049 -f 10101 10105 10073 -f 10105 10080 10073 -f 10105 10107 10080 -f 10050 10051 10107 -f 10050 10079 10051 -f 10050 10052 10079 -f 10052 10053 10079 -f 10052 10106 10053 -f 10106 10081 10053 -f 10106 10078 10081 -f 10078 10054 10077 -f 10054 10103 10077 -f 10103 10076 10077 -f 10103 10082 10076 -f 10102 10086 10084 -f 10102 10075 10086 -f 10102 10114 10075 -f 10055 10085 10048 -f 10055 10065 10085 -f 10069 10068 10081 -f 10068 10051 10079 -f 10070 10080 10051 -f 10075 10076 10086 -f 10075 10067 10076 -f 10067 10069 10076 -f 10069 10081 10077 -f 9935 10063 10062 -f 9935 10072 10063 -f 10091 9930 10064 -f 9930 10056 10064 -f 10095 10057 10056 -f 10072 10058 10063 -f 10071 10060 10061 -f 10091 10064 10059 -f 10063 10058 10067 -f 10061 10069 10058 -f 10062 10063 10066 -f 10057 10062 10065 -f 10058 10069 10067 -f 10056 10065 10055 -f 10056 10057 10065 -f 10060 10070 10068 -f 10060 10059 10070 -f 10056 10055 10064 -f 10062 10066 10065 -f 10061 10060 10068 -f 10059 10064 10070 -f 10061 10068 10069 -f 10063 10067 10075 -f 10064 10055 10048 -f 10066 10075 10046 -f 10066 10063 10075 -f 10068 10070 10051 -f 10064 10073 10070 -f 10064 10048 10073 -f 10066 10074 10065 -f 10066 10046 10074 -f 10059 10087 10091 -f 10059 10060 10087 -f 10057 10095 10090 -f 10056 10096 10095 -f 10056 9930 10096 -f 10087 10060 10089 -f 10060 10071 10089 -f 10071 10093 9932 -f 10071 10061 10093 -f 10062 10092 9936 -f 10062 10094 10092 -f 10062 10057 10094 -f 10093 10061 9964 -f 10061 10058 9964 -f 10058 10088 9964 -f 10058 10072 10088 -f 10062 9936 9935 -f 10082 10084 10076 -f 10114 10046 10075 -f 10107 10051 10080 -f 10104 10049 10048 -f 10079 10053 10068 -f 10053 10081 10068 -f 10078 10077 10081 -f 10077 10076 10069 -f 10084 10086 10076 -f 10074 10083 10065 -f 10083 10047 10065 -f 10049 10073 10048 -f 10073 10080 10070 -f 10047 10085 10065 -f 9932 9959 10071 -f 9930 9929 10096 -f 9927 10092 10094 -f 9965 9930 10091 -f 9928 10057 10090 -f 9928 10094 10057 -f 10071 9960 10089 -f 9931 10087 10089 -f 10084 10082 10102 -f 10052 10050 10113 -f 10050 10032 10113 -f 10050 10107 10032 -f 10101 10100 10034 -f 10104 10038 10100 -f 10104 10099 10038 -f 10097 10083 10109 -f 10083 10112 10109 -f 10083 10045 10112 -f 10100 10037 10034 -f 10105 10111 10107 -f 10099 10108 10038 -f 10098 10109 10043 -f 10038 10037 10100 -f 10030 10054 10078 -f 10098 10043 10099 -f 10099 10043 10108 -f 10097 10109 10098 -f 10034 10033 10101 -f 10033 10105 10101 -f 10033 10111 10105 -f 10045 10110 10112 -f 10111 10032 10107 -f 10045 10114 10110 -f 10114 10115 10110 -f 10114 10116 10115 -f 10113 10031 10052 -f 10031 10106 10052 -f 10114 10102 10116 -f 10031 10030 10106 -f 10102 10082 10117 -f 10119 10054 10030 -f 10118 10117 10082 -f 10116 10102 10117 -f 10118 10103 10119 -f 10119 10103 10054 -f 10030 10078 10106 -f 10082 10103 10118 -f 10121 10200 10123 -f 10123 10172 10121 -f 10198 10173 10174 -f 10125 10209 10202 -f 10176 10198 10174 -f 10209 10124 10202 -f 10173 10198 10172 -f 10172 10198 10121 -f 10176 10127 10198 -f 10124 10206 10202 -f 10120 10205 10122 -f 10122 10205 10206 -f 10122 10206 10124 -f 10208 10127 10126 -f 10125 10202 10203 -f 10127 10208 10200 -f 10126 10127 10176 -f 10131 10200 10180 -f 10208 10177 10200 -f 10200 10177 10180 -f 10195 10193 10194 -f 10195 10125 10193 -f 10193 10125 10203 -f 10193 10203 10128 -f 10120 10156 10203 -f 10205 10120 10203 -f 10131 10129 10130 -f 10123 10200 10131 -f 10123 10131 10130 -f 10167 10134 10132 -f 10132 10134 10183 -f 10132 10183 10136 -f 10129 10131 10133 -f 10129 10133 10167 -f 10167 10133 10134 -f 10203 10156 10157 -f 10203 10157 10128 -f 10128 10157 10159 -f 10136 10183 10135 -f 10136 10135 10185 -f 10136 10185 10165 -f 10185 10187 10165 -f 10165 10187 10164 -f 10164 10187 10188 -f 10164 10188 10137 -f 10137 10188 10190 -f 10137 10190 10191 -f 10137 10191 10162 -f 10162 10191 10128 -f 10162 10128 10159 -f 10199 10197 10139 -f 10207 10175 10196 -f 10201 10204 10144 -f 10144 10204 10155 -f 10153 10142 10146 -f 10138 10199 10139 -f 10139 10197 10140 -f 10175 10197 10196 -f 10155 10204 10153 -f 10142 10201 10143 -f 10207 10196 10145 -f 10153 10146 10210 -f 10201 10144 10143 -f 10140 10197 10175 -f 10145 10178 10207 -f 10145 10147 10179 -f 10145 10179 10178 -f 10153 10141 10154 -f 10153 10210 10141 -f 10141 10210 10194 -f 10199 10138 10145 -f 10145 10138 10171 -f 10145 10171 10170 -f 10145 10170 10147 -f 10147 10170 10169 -f 10148 10184 10182 -f 10148 10182 10166 -f 10147 10169 10168 -f 10147 10168 10149 -f 10149 10168 10181 -f 10181 10168 10166 -f 10181 10166 10182 -f 10150 10186 10151 -f 10151 10186 10184 -f 10151 10184 10148 -f 10163 10189 10150 -f 10150 10189 10152 -f 10150 10152 10186 -f 10160 10154 10161 -f 10154 10160 10158 -f 10153 10154 10158 -f 10153 10158 10155 -f 10161 10154 10192 -f 10161 10192 10163 -f 10163 10192 10189 -f 10122 10144 10120 -f 10120 10144 10155 -f 10120 10155 10156 -f 10156 10155 10158 -f 10156 10158 10157 -f 10157 10158 10160 -f 10157 10160 10159 -f 10159 10160 10162 -f 10162 10160 10161 -f 10162 10161 10137 -f 10137 10161 10163 -f 10137 10163 10164 -f 10164 10163 10150 -f 10164 10150 10165 -f 10165 10150 10151 -f 10165 10151 10136 -f 10136 10151 10148 -f 10136 10148 10132 -f 10132 10148 10166 -f 10132 10166 10167 -f 10167 10166 10168 -f 10167 10168 10129 -f 10129 10168 10169 -f 10129 10169 10130 -f 10130 10169 10170 -f 10130 10170 10123 -f 10123 10170 10171 -f 10123 10171 10172 -f 10172 10171 10138 -f 10172 10138 10173 -f 10173 10138 10139 -f 10174 10173 10140 -f 10140 10173 10139 -f 10174 10140 10175 -f 10174 10175 10176 -f 10176 10175 10207 -f 10176 10207 10126 -f 10208 10126 10207 -f 10177 10178 10179 -f 10177 10179 10147 -f 10177 10147 10180 -f 10180 10147 10131 -f 10131 10147 10149 -f 10131 10149 10133 -f 10133 10149 10181 -f 10133 10181 10134 -f 10134 10181 10182 -f 10134 10182 10183 -f 10183 10182 10184 -f 10183 10184 10135 -f 10135 10184 10186 -f 10135 10186 10185 -f 10185 10186 10187 -f 10187 10186 10152 -f 10187 10152 10188 -f 10188 10152 10189 -f 10188 10189 10190 -f 10190 10189 10192 -f 10190 10192 10191 -f 10191 10192 10154 -f 10191 10154 10128 -f 10128 10154 10141 -f 10128 10141 10193 -f 10193 10141 10194 -f 10195 10194 10210 -f 10195 10210 10125 -f 10209 10125 10146 -f 10146 10125 10210 -f 10209 10146 10142 -f 10209 10142 10124 -f 10124 10142 10143 -f 10122 10124 10144 -f 10144 10124 10143 -f 10127 10196 10197 -f 10127 10197 10198 -f 10198 10197 10199 -f 10198 10199 10121 -f 10121 10199 10200 -f 10200 10199 10145 -f 10200 10145 10127 -f 10127 10145 10196 -f 10206 10201 10142 -f 10206 10142 10202 -f 10202 10142 10153 -f 10202 10153 10203 -f 10203 10153 10205 -f 10205 10153 10204 -f 10205 10204 10206 -f 10206 10204 10201 -f 10208 10207 10178 -f 10208 10178 10177 -f 10221 10342 10340 -f 10221 10340 10211 -f 10211 10340 10212 -f 10211 10212 10223 -f 10223 10212 10338 -f 10223 10338 10224 -f 10224 10338 10337 -f 10224 10337 10336 -f 10224 10336 10225 -f 10225 10336 10335 -f 10225 10335 10226 -f 10226 10335 10213 -f 10226 10213 10334 -f 10226 10334 10228 -f 10228 10334 10333 -f 10228 10333 10214 -f 10333 10332 10214 -f 10214 10332 10229 -f 10229 10332 10330 -f 10229 10330 10230 -f 10230 10330 10329 -f 10230 10329 10216 -f 10216 10329 10215 -f 10216 10215 10328 -f 10216 10328 10217 -f 10217 10328 10218 -f 10218 10328 10344 -f 10218 10344 10343 -f 10218 10343 10220 -f 10220 10343 10365 -f 10220 10365 10361 -f 10220 10361 10221 -f 10221 10361 10342 -f 10241 10217 10219 -f 10219 10217 10218 -f 10219 10218 10240 -f 10240 10218 10220 -f 10240 10220 10239 -f 10239 10220 10221 -f 10239 10221 10242 -f 10242 10221 10222 -f 10222 10221 10211 -f 10222 10211 10238 -f 10238 10211 10223 -f 10238 10223 10224 -f 10238 10224 10237 -f 10237 10224 10225 -f 10237 10225 10236 -f 10236 10225 10235 -f 10235 10225 10226 -f 10235 10226 10233 -f 10233 10226 10228 -f 10233 10228 10227 -f 10227 10228 10214 -f 10227 10214 10232 -f 10232 10214 10229 -f 10232 10229 10234 -f 10234 10229 10230 -f 10234 10230 10231 -f 10231 10230 10216 -f 10231 10216 10241 -f 10241 10216 10217 -f 10241 10257 10231 -f 10227 10262 10233 -f 10234 10259 10232 -f 10235 10266 10236 -f 10236 10266 10237 -f 10237 10266 10265 -f 10237 10265 10238 -f 10240 10264 10219 -f 10271 10251 10270 -f 10271 10270 10269 -f 10292 10247 10294 -f 10294 10247 10275 -f 10275 10248 10279 -f 10279 10248 10281 -f 10281 10248 10249 -f 10281 10249 10243 -f 10244 10245 10267 -f 10267 10245 10246 -f 10247 10255 10275 -f 10275 10255 10253 -f 10251 10256 10270 -f 10247 10254 10255 -f 10275 10253 10248 -f 10249 10250 10243 -f 10270 10256 10244 -f 10246 10254 10247 -f 10251 10243 10258 -f 10252 10254 10246 -f 10251 10258 10256 -f 10245 10263 10246 -f 10246 10263 10252 -f 10243 10250 10258 -f 10253 10260 10248 -f 10248 10260 10249 -f 10244 10262 10245 -f 10254 10257 10255 -f 10256 10266 10244 -f 10244 10266 10262 -f 10249 10261 10250 -f 10256 10258 10266 -f 10245 10262 10263 -f 10255 10264 10253 -f 10250 10261 10265 -f 10250 10265 10258 -f 10255 10257 10264 -f 10253 10264 10260 -f 10249 10260 10261 -f 10263 10259 10252 -f 10254 10259 10257 -f 10258 10265 10266 -f 10252 10259 10254 -f 10260 10222 10261 -f 10260 10242 10222 -f 10222 10238 10261 -f 10261 10238 10265 -f 10266 10233 10262 -f 10257 10241 10264 -f 10264 10241 10219 -f 10264 10240 10260 -f 10260 10240 10239 -f 10260 10239 10242 -f 10266 10235 10233 -f 10262 10227 10263 -f 10263 10227 10232 -f 10263 10232 10259 -f 10259 10234 10231 -f 10259 10231 10257 -f 10268 10270 10286 -f 10286 10270 10244 -f 10286 10244 10267 -f 10267 10246 10288 -f 10288 10246 10289 -f 10269 10270 10268 -f 10289 10246 10290 -f 10290 10246 10247 -f 10290 10247 10292 -f 10273 10243 10283 -f 10283 10243 10251 -f 10280 10279 10281 -f 10251 10271 10283 -f 10294 10275 10272 -f 10272 10275 10274 -f 10281 10243 10273 -f 10274 10275 10277 -f 10277 10275 10279 -f 10293 10294 10276 -f 10276 10294 10272 -f 10276 10272 10274 -f 10276 10274 10376 -f 10376 10274 10277 -f 10376 10277 10375 -f 10375 10277 10279 -f 10375 10279 10278 -f 10278 10279 10280 -f 10278 10280 10377 -f 10377 10280 10281 -f 10377 10281 10282 -f 10282 10281 10273 -f 10282 10273 10284 -f 10284 10273 10283 -f 10284 10283 10374 -f 10374 10283 10271 -f 10374 10271 10373 -f 10373 10271 10269 -f 10373 10269 10372 -f 10372 10269 10268 -f 10372 10268 10285 -f 10285 10268 10286 -f 10285 10286 10287 -f 10287 10286 10267 -f 10287 10267 10369 -f 10369 10267 10403 -f 10403 10267 10288 -f 10403 10288 10289 -f 10403 10289 10371 -f 10371 10289 10370 -f 10370 10289 10290 -f 10370 10290 10291 -f 10291 10290 10292 -f 10291 10292 10293 -f 10293 10292 10294 -f 10308 10472 10355 -f 10308 10355 10474 -f 10474 10355 10357 -f 10474 10357 10468 -f 10468 10357 10347 -f 10468 10347 10473 -f 10473 10347 10346 -f 10473 10346 10469 -f 10469 10346 10295 -f 10295 10346 10324 -f 10295 10324 10477 -f 10477 10324 10323 -f 10477 10323 10345 -f 10478 10345 10470 -f 10470 10345 10296 -f 10470 10296 10298 -f 10470 10298 10297 -f 10297 10298 10476 -f 10476 10298 10354 -f 10476 10354 10352 -f 10475 10352 10299 -f 10475 10299 10479 -f 10479 10299 10300 -f 10479 10300 10351 -f 10479 10351 10301 -f 10301 10351 10350 -f 10301 10350 10302 -f 10303 10302 10304 -f 10303 10304 10349 -f 10349 10348 10305 -f 10305 10348 10471 -f 10471 10348 10353 -f 10471 10353 10306 -f 10306 10353 10356 -f 10307 10356 10472 -f 10320 10346 10347 -f 10319 10299 10354 -f 10319 10354 10323 -f 10323 10354 10298 -f 10323 10298 10296 -f 10322 10304 10350 -f 10321 10350 10351 -f 10321 10351 10300 -f 10321 10300 10319 -f 10319 10300 10299 -f 10318 10356 10353 -f 10318 10353 10322 -f 10322 10353 10348 -f 10322 10348 10304 -f 10347 10357 10320 -f 10320 10357 10325 -f 10325 10357 10355 -f 10339 10310 10311 -f 10359 10312 10316 -f 10364 10358 10314 -f 10364 10314 10317 -f 10313 10310 10309 -f 10309 10310 10339 -f 10312 10311 10319 -f 10358 10368 10314 -f 10362 10327 10313 -f 10362 10313 10341 -f 10316 10315 10368 -f 10368 10315 10314 -f 10311 10310 10321 -f 10317 10314 10320 -f 10327 10317 10325 -f 10313 10322 10310 -f 10327 10318 10313 -f 10325 10318 10327 -f 10313 10318 10322 -f 10310 10322 10321 -f 10316 10312 10323 -f 10316 10323 10315 -f 10317 10320 10325 -f 10311 10321 10319 -f 10312 10319 10323 -f 10315 10323 10324 -f 10315 10324 10314 -f 10318 10325 10356 -f 10314 10346 10320 -f 10321 10322 10350 -f 10314 10324 10346 -f 10316 10368 10359 -f 10359 10366 10312 -f 10312 10366 10326 -f 10312 10326 10311 -f 10311 10326 10360 -f 10311 10360 10339 -f 10327 10362 10367 -f 10317 10327 10364 -f 10215 10364 10328 -f 10328 10364 10363 -f 10329 10358 10215 -f 10215 10358 10364 -f 10330 10358 10329 -f 10358 10330 10331 -f 10331 10330 10332 -f 10332 10368 10331 -f 10333 10368 10332 -f 10359 10333 10334 -f 10213 10366 10334 -f 10366 10213 10335 -f 10336 10326 10335 -f 10337 10360 10336 -f 10360 10337 10339 -f 10338 10339 10337 -f 10338 10212 10309 -f 10309 10212 10340 -f 10342 10341 10340 -f 10340 10341 10309 -f 10361 10341 10342 -f 10343 10362 10365 -f 10362 10343 10367 -f 10367 10343 10344 -f 10328 10363 10344 -f 10344 10363 10367 -f 10348 10349 10304 -f 10345 10323 10296 -f 10302 10350 10304 -f 10356 10325 10472 -f 10352 10354 10299 -f 10325 10355 10472 -f 10368 10333 10359 -f 10334 10366 10359 -f 10360 10326 10336 -f 10335 10326 10366 -f 10363 10327 10367 -f 10365 10362 10361 -f 10361 10362 10341 -f 10341 10313 10309 -f 10338 10309 10339 -f 10331 10368 10358 -f 10363 10364 10327 -f 10293 10405 10291 -f 10369 10401 10287 -f 10287 10401 10285 -f 10284 10397 10282 -f 10370 10291 10404 -f 10370 10404 10371 -f 10404 10403 10371 -f 10278 10396 10375 -f 10372 10398 10373 -f 10398 10397 10373 -f 10373 10397 10374 -f 10374 10397 10284 -f 10375 10396 10376 -f 10276 10405 10293 -f 10397 10402 10282 -f 10282 10402 10377 -f 10376 10405 10276 -f 10411 10383 10385 -f 10411 10385 10414 -f 10414 10385 10378 -f 10416 10378 10379 -f 10416 10379 10410 -f 10410 10379 10419 -f 10419 10379 10380 -f 10419 10380 10421 -f 10421 10380 10387 -f 10407 10395 10430 -f 10409 10430 10383 -f 10384 10381 10393 -f 10428 10384 10382 -f 10428 10382 10407 -f 10407 10382 10390 -f 10407 10390 10395 -f 10430 10395 10383 -f 10395 10399 10383 -f 10383 10399 10385 -f 10378 10385 10386 -f 10381 10387 10389 -f 10389 10393 10381 -f 10379 10388 10380 -f 10385 10392 10386 -f 10378 10386 10379 -f 10380 10388 10391 -f 10380 10391 10387 -f 10393 10394 10384 -f 10384 10394 10382 -f 10385 10399 10392 -f 10386 10402 10379 -f 10391 10398 10387 -f 10382 10394 10390 -f 10379 10397 10388 -f 10387 10398 10389 -f 10389 10398 10400 -f 10390 10404 10395 -f 10399 10405 10392 -f 10392 10396 10386 -f 10386 10396 10402 -f 10379 10402 10397 -f 10389 10400 10393 -f 10393 10400 10401 -f 10393 10401 10394 -f 10394 10404 10390 -f 10404 10405 10395 -f 10392 10405 10396 -f 10388 10397 10391 -f 10395 10405 10399 -f 10391 10397 10398 -f 10401 10403 10394 -f 10394 10403 10404 -f 10396 10377 10402 -f 10398 10372 10400 -f 10405 10376 10396 -f 10396 10278 10377 -f 10372 10285 10400 -f 10400 10285 10401 -f 10401 10369 10403 -f 10404 10291 10405 -f 10423 10381 10406 -f 10406 10381 10384 -f 10406 10384 10425 -f 10425 10384 10426 -f 10426 10384 10428 -f 10426 10428 10427 -f 10408 10387 10381 -f 10408 10381 10423 -f 10414 10378 10416 -f 10421 10387 10422 -f 10408 10422 10387 -f 10409 10383 10411 -f 10432 10409 10412 -f 10412 10409 10411 -f 10412 10411 10413 -f 10413 10411 10414 -f 10413 10414 10415 -f 10415 10414 10416 -f 10415 10416 10487 -f 10487 10416 10417 -f 10417 10416 10410 -f 10417 10410 10418 -f 10418 10410 10419 -f 10418 10419 10420 -f 10420 10419 10421 -f 10420 10421 10486 -f 10486 10421 10485 -f 10485 10421 10422 -f 10485 10422 10484 -f 10484 10422 10408 -f 10484 10408 10424 -f 10424 10408 10423 -f 10424 10423 10482 -f 10482 10423 10406 -f 10482 10406 10481 -f 10481 10406 10425 -f 10481 10425 10480 -f 10480 10425 10426 -f 10480 10426 10513 -f 10513 10426 10427 -f 10513 10427 10483 -f 10483 10427 10428 -f 10483 10428 10407 -f 10483 10407 10429 -f 10429 10407 10430 -f 10429 10430 10431 -f 10431 10430 10432 -f 10432 10430 10409 -f 10586 10433 10434 -f 10434 10459 10591 -f 10591 10459 10577 -f 10577 10459 10435 -f 10577 10435 10590 -f 10590 10435 10458 -f 10590 10458 10589 -f 10589 10458 10466 -f 10589 10466 10578 -f 10578 10463 10436 -f 10436 10463 10579 -f 10579 10464 10588 -f 10588 10464 10584 -f 10584 10464 10580 -f 10587 10580 10581 -f 10581 10580 10461 -f 10581 10461 10437 -f 10437 10467 10585 -f 10585 10467 10438 -f 10585 10438 10583 -f 10583 10438 10462 -f 10583 10462 10439 -f 10439 10440 10582 -f 10582 10440 10441 -f 10582 10441 10465 -f 10465 10460 10586 -f 10586 10460 10433 -f 10463 10466 10458 -f 10452 10458 10435 -f 10454 10580 10464 -f 10454 10464 10455 -f 10455 10464 10579 -f 10453 10438 10467 -f 10453 10467 10442 -f 10442 10461 10454 -f 10454 10461 10580 -f 10451 10441 10440 -f 10451 10440 10453 -f 10453 10440 10462 -f 10453 10462 10438 -f 10435 10459 10443 -f 10443 10460 10451 -f 10306 10450 10445 -f 10303 10446 10457 -f 10297 10448 10478 -f 10478 10448 10449 -f 10478 10449 10456 -f 10447 10454 10448 -f 10444 10443 10450 -f 10445 10451 10446 -f 10446 10453 10457 -f 10457 10442 10447 -f 10449 10448 10455 -f 10456 10452 10444 -f 10446 10451 10453 -f 10447 10442 10454 -f 10456 10449 10452 -f 10457 10453 10442 -f 10445 10450 10451 -f 10444 10452 10443 -f 10448 10454 10455 -f 10449 10463 10452 -f 10450 10443 10451 -f 10449 10455 10463 -f 10455 10579 10463 -f 10452 10463 10458 -f 10452 10435 10443 -f 10478 10470 10297 -f 10297 10476 10448 -f 10444 10473 10469 -f 10444 10469 10456 -f 10456 10469 10295 -f 10456 10295 10477 -f 10456 10477 10478 -f 10447 10448 10479 -f 10447 10479 10457 -f 10457 10479 10301 -f 10457 10301 10302 -f 10457 10302 10303 -f 10450 10306 10307 -f 10444 10450 10474 -f 10445 10446 10305 -f 10445 10305 10471 -f 10445 10471 10306 -f 10465 10451 10460 -f 10461 10442 10437 -f 10437 10442 10467 -f 10439 10462 10440 -f 10441 10451 10465 -f 10433 10443 10434 -f 10434 10443 10459 -f 10578 10466 10463 -f 10433 10460 10443 -f 10307 10306 10356 -f 10308 10450 10472 -f 10472 10450 10307 -f 10349 10305 10446 -f 10349 10446 10303 -f 10475 10479 10448 -f 10475 10448 10352 -f 10352 10448 10476 -f 10345 10478 10477 -f 10468 10444 10474 -f 10474 10450 10308 -f 10473 10444 10468 -f 10431 10511 10429 -f 10480 10512 10481 -f 10481 10512 10482 -f 10512 10424 10482 -f 10420 10485 10417 -f 10420 10417 10418 -f 10429 10511 10483 -f 10480 10513 10512 -f 10483 10511 10513 -f 10420 10486 10485 -f 10487 10417 10415 -f 10413 10415 10509 -f 10432 10514 10431 -f 10413 10509 10412 -f 10432 10412 10514 -f 10526 10488 10506 -f 10526 10506 10489 -f 10489 10528 10527 -f 10528 10491 10521 -f 10521 10491 10492 -f 10523 10492 10518 -f 10532 10490 10515 -f 10517 10500 10520 -f 10525 10493 10488 -f 10518 10499 10532 -f 10532 10499 10490 -f 10515 10490 10495 -f 10515 10495 10516 -f 10516 10495 10517 -f 10489 10504 10528 -f 10528 10504 10491 -f 10518 10494 10499 -f 10493 10500 10505 -f 10493 10505 10496 -f 10493 10496 10488 -f 10489 10506 10504 -f 10492 10494 10518 -f 10491 10501 10492 -f 10492 10501 10498 -f 10499 10502 10490 -f 10488 10496 10506 -f 10504 10497 10491 -f 10491 10497 10501 -f 10494 10510 10499 -f 10517 10503 10500 -f 10492 10498 10494 -f 10490 10502 10495 -f 10500 10503 10508 -f 10499 10510 10502 -f 10500 10508 10505 -f 10495 10503 10517 -f 10504 10507 10497 -f 10505 10514 10496 -f 10506 10496 10509 -f 10506 10509 10504 -f 10497 10417 10501 -f 10501 10417 10498 -f 10502 10512 10495 -f 10508 10514 10505 -f 10496 10514 10509 -f 10504 10509 10507 -f 10512 10513 10495 -f 10495 10513 10503 -f 10503 10511 10508 -f 10507 10417 10497 -f 10498 10417 10485 -f 10510 10424 10502 -f 10509 10415 10507 -f 10498 10485 10494 -f 10494 10485 10510 -f 10502 10424 10512 -f 10508 10511 10514 -f 10415 10417 10507 -f 10503 10513 10511 -f 10514 10412 10509 -f 10485 10484 10510 -f 10510 10484 10424 -f 10511 10431 10514 -f 10515 10516 10533 -f 10516 10517 10534 -f 10534 10517 10520 -f 10519 10518 10532 -f 10520 10500 10535 -f 10535 10500 10493 -f 10521 10492 10522 -f 10522 10492 10523 -f 10523 10518 10524 -f 10524 10518 10530 -f 10525 10488 10526 -f 10614 10525 10619 -f 10619 10525 10526 -f 10619 10526 10489 -f 10619 10489 10617 -f 10617 10489 10527 -f 10617 10527 10620 -f 10620 10527 10621 -f 10621 10527 10528 -f 10621 10528 10618 -f 10618 10528 10521 -f 10618 10521 10616 -f 10616 10521 10522 -f 10616 10522 10529 -f 10529 10522 10523 -f 10529 10523 10524 -f 10529 10524 10611 -f 10611 10524 10530 -f 10611 10530 10609 -f 10609 10530 10518 -f 10609 10518 10607 -f 10607 10518 10519 -f 10607 10519 10531 -f 10531 10519 10615 -f 10615 10519 10532 -f 10615 10532 10515 -f 10615 10515 10604 -f 10604 10515 10533 -f 10604 10533 10605 -f 10605 10533 10516 -f 10605 10516 10534 -f 10605 10534 10606 -f 10606 10534 10520 -f 10606 10520 10608 -f 10608 10520 10535 -f 10608 10535 10610 -f 10610 10535 10493 -f 10610 10493 10612 -f 10612 10493 10525 -f 10612 10525 10614 -f 10613 10568 10536 -f 10536 10568 10537 -f 10536 10537 10569 -f 10592 10569 10561 -f 10592 10561 10538 -f 10538 10561 10573 -f 10538 10573 10539 -f 10539 10573 10540 -f 10539 10540 10603 -f 10593 10600 10574 -f 10593 10574 10598 -f 10598 10574 10601 -f 10601 10560 10594 -f 10594 10560 10570 -f 10541 10594 10564 -f 10541 10564 10563 -f 10541 10563 10595 -f 10595 10563 10542 -f 10595 10542 10602 -f 10602 10542 10565 -f 10602 10565 10543 -f 10543 10562 10596 -f 10596 10562 10566 -f 10596 10566 10597 -f 10597 10566 10544 -f 10597 10544 10567 -f 10599 10571 10575 -f 10599 10575 10572 -f 10599 10572 10613 -f 10557 10540 10573 -f 10557 10573 10545 -f 10562 10565 10556 -f 10556 10563 10564 -f 10576 10575 10544 -f 10576 10544 10562 -f 10568 10572 10576 -f 10582 10550 10559 -f 10577 10547 10549 -f 10581 10546 10551 -f 10588 10551 10553 -f 10588 10553 10548 -f 10546 10559 10552 -f 10559 10550 10552 -f 10551 10556 10553 -f 10547 10557 10549 -f 10546 10555 10556 -f 10547 10548 10557 -f 10546 10552 10555 -f 10546 10556 10551 -f 10549 10557 10545 -f 10558 10554 10576 -f 10558 10576 10550 -f 10549 10545 10558 -f 10550 10576 10552 -f 10558 10545 10554 -f 10553 10570 10548 -f 10552 10562 10555 -f 10553 10556 10570 -f 10548 10540 10557 -f 10554 10568 10576 -f 10552 10576 10562 -f 10555 10562 10556 -f 10548 10574 10540 -f 10556 10564 10570 -f 10548 10570 10574 -f 10554 10545 10537 -f 10554 10537 10568 -f 10547 10436 10548 -f 10548 10436 10588 -f 10551 10588 10584 -f 10549 10591 10577 -f 10547 10577 10590 -f 10547 10590 10589 -f 10547 10589 10436 -f 10584 10587 10551 -f 10551 10587 10581 -f 10550 10465 10558 -f 10558 10465 10586 -f 10549 10558 10591 -f 10559 10546 10583 -f 10550 10582 10465 -f 10567 10544 10571 -f 10613 10572 10568 -f 10594 10570 10564 -f 10603 10540 10600 -f 10563 10556 10542 -f 10542 10556 10565 -f 10543 10565 10562 -f 10566 10562 10544 -f 10571 10544 10575 -f 10575 10576 10572 -f 10537 10545 10569 -f 10569 10545 10561 -f 10600 10540 10574 -f 10574 10570 10601 -f 10601 10570 10560 -f 10561 10545 10573 -f 10439 10582 10559 -f 10439 10559 10583 -f 10585 10546 10437 -f 10437 10546 10581 -f 10579 10588 10436 -f 10578 10436 10589 -f 10434 10591 10558 -f 10434 10558 10586 -f 10583 10546 10585 -f 10580 10587 10584 -f 10571 10599 10567 -f 10594 10598 10601 -f 10595 10529 10541 -f 10541 10529 10611 -f 10541 10611 10594 -f 10598 10531 10593 -f 10600 10593 10604 -f 10600 10604 10603 -f 10603 10604 10539 -f 10592 10608 10569 -f 10569 10608 10610 -f 10569 10610 10536 -f 10593 10531 10615 -f 10539 10604 10605 -f 10538 10606 10608 -f 10604 10593 10615 -f 10618 10543 10596 -f 10538 10539 10606 -f 10539 10605 10606 -f 10592 10538 10608 -f 10531 10598 10607 -f 10607 10594 10609 -f 10536 10610 10612 -f 10609 10594 10611 -f 10598 10594 10607 -f 10536 10612 10613 -f 10613 10612 10614 -f 10613 10614 10619 -f 10529 10595 10616 -f 10616 10595 10602 -f 10613 10619 10599 -f 10616 10602 10618 -f 10599 10617 10567 -f 10621 10618 10596 -f 10620 10567 10617 -f 10619 10617 10599 -f 10620 10621 10597 -f 10621 10596 10597 -f 10618 10602 10543 -f 10567 10620 10597 -f 10625 10624 10622 -f 10622 10624 10623 -f 10627 10629 10626 -f 10628 10627 10626 -f 10626 10629 10628 -f 10631 10633 10632 -f 10634 10632 10633 -f 10630 10631 10632 -f 10638 10635 10636 -f 10638 10636 10637 -f 10638 10639 10635 -f 10643 10642 10640 -f 10642 10641 10640 -f 10641 10642 10644 -f 10648 10645 10646 -f 10647 10645 10648 -f 10647 10648 10646 -f 10649 10722 10650 -f 10650 10722 10651 -f 10650 10651 10652 -f 10652 10651 10653 -f 10652 10653 10654 -f 10654 10653 10655 -f 10654 10655 10656 -f 10656 10655 10657 -f 10656 10657 10658 -f 10658 10657 10660 -f 10658 10660 10659 -f 10659 10660 10661 -f 10659 10661 10662 -f 10662 10661 10663 -f 10662 10663 10664 -f 10664 10663 10665 -f 10664 10665 10667 -f 10667 10665 10666 -f 10667 10666 10669 -f 10669 10666 10668 -f 10669 10668 10670 -f 10670 10668 10671 -f 10670 10671 10672 -f 10672 10671 10673 -f 10672 10673 10674 -f 10674 10673 10676 -f 10674 10676 10675 -f 10675 10676 10678 -f 10675 10678 10677 -f 10677 10678 10679 -f 10677 10679 10680 -f 10680 10679 10681 -f 10680 10681 10682 -f 10682 10681 10683 -f 10682 10683 10684 -f 10684 10683 10685 -f 10684 10685 10686 -f 10686 10685 10687 -f 10686 10687 10688 -f 10688 10687 10689 -f 10688 10689 10691 -f 10691 10689 10690 -f 10691 10690 10693 -f 10693 10690 10692 -f 10693 10692 10694 -f 10694 10692 10695 -f 10694 10695 10696 -f 10696 10695 10697 -f 10696 10697 10699 -f 10699 10697 10698 -f 10699 10698 10700 -f 10700 10698 10702 -f 10700 10702 10701 -f 10701 10702 10704 -f 10701 10704 10703 -f 10703 10704 10705 -f 10703 10705 10707 -f 10707 10705 10706 -f 10707 10706 10708 -f 10708 10706 10709 -f 10708 10709 10710 -f 10710 10709 10711 -f 10710 10711 10713 -f 10713 10711 10712 -f 10713 10712 10714 -f 10714 10712 10715 -f 10714 10715 10717 -f 10717 10715 10716 -f 10717 10716 10718 -f 10718 10716 10719 -f 10718 10719 10720 -f 10720 10719 10721 -f 10720 10721 10649 -f 10649 10721 10722 -f 10724 10727 10723 -f 10724 10723 10725 -f 10725 10723 10726 -f 10738 10848 10729 -f 10738 10729 10728 -f 10728 10729 10750 -f 10728 10750 10743 -f 10743 10750 10747 -f 10853 10859 10732 -f 10861 10862 10730 -f 10732 10733 10731 -f 10730 10805 10861 -f 10861 10805 10733 -f 10861 10733 10732 -f 10736 10734 10852 -f 10731 10735 10853 -f 10731 10853 10732 -f 10736 10852 10735 -f 10735 10757 10736 -f 10731 10757 10735 -f 10737 10851 10734 -f 10730 10862 10864 -f 10741 10819 10864 -f 10864 10819 10821 -f 10853 10744 10859 -f 10742 10739 10738 -f 10738 10739 10740 -f 10740 10739 10850 -f 10740 10850 10746 -f 10746 10850 10851 -f 10737 10746 10851 -f 10734 10851 10852 -f 10864 10821 10730 -f 10819 10741 10743 -f 10728 10857 10738 -f 10741 10857 10728 -f 10744 10853 10742 -f 10743 10741 10728 -f 10738 10857 10744 -f 10744 10742 10738 -f 10734 10745 10737 -f 10737 10745 10849 -f 10737 10849 10746 -f 10746 10849 10740 -f 10734 10736 10745 -f 10745 10736 10758 -f 10860 10755 10854 -f 10854 10749 10860 -f 10822 10748 10823 -f 10822 10823 10806 -f 10748 10860 10823 -f 10823 10860 10749 -f 10747 10752 10751 -f 10822 10863 10748 -f 10849 10856 10855 -f 10849 10855 10848 -f 10749 10854 10753 -f 10749 10753 10756 -f 10865 10750 10729 -f 10745 10758 10754 -f 10752 10747 10865 -f 10865 10747 10750 -f 10751 10752 10863 -f 10863 10820 10751 -f 10822 10820 10863 -f 10753 10758 10756 -f 10758 10753 10754 -f 10745 10754 10856 -f 10855 10858 10848 -f 10848 10858 10866 -f 10855 10860 10858 -f 10848 10866 10729 -f 10729 10866 10865 -f 10856 10849 10745 -f 10860 10855 10755 -f 10731 10749 10756 -f 10731 10756 10757 -f 10757 10756 10758 -f 10757 10758 10736 -f 10846 10759 10782 -f 10782 10759 10843 -f 10782 10843 10842 -f 10782 10842 10783 -f 10783 10842 10841 -f 10783 10841 10760 -f 10760 10841 10761 -f 10760 10761 10762 -f 10762 10761 10763 -f 10762 10763 10771 -f 10749 10731 10823 -f 10823 10731 10733 -f 10823 10733 10824 -f 10824 10733 10797 -f 10824 10797 10780 -f 10780 10797 10764 -f 10765 10767 10766 -f 10766 10767 10834 -f 10766 10834 10788 -f 10788 10834 10768 -f 10788 10768 10769 -f 10769 10768 10776 -f 10769 10776 10770 -f 10763 10772 10771 -f 10771 10772 10773 -f 10771 10773 10786 -f 10786 10773 10838 -f 10786 10838 10774 -f 10774 10838 10775 -f 10774 10775 10765 -f 10765 10775 10835 -f 10765 10835 10767 -f 10776 10833 10770 -f 10770 10833 10831 -f 10770 10831 10791 -f 10791 10831 10777 -f 10791 10777 10793 -f 10793 10777 10778 -f 10793 10778 10795 -f 10795 10778 10828 -f 10795 10828 10764 -f 10764 10828 10779 -f 10764 10779 10780 -f 10799 10782 10781 -f 10781 10782 10783 -f 10781 10783 10784 -f 10784 10783 10760 -f 10784 10760 10802 -f 10802 10760 10762 -f 10802 10762 10785 -f 10785 10762 10771 -f 10785 10771 10810 -f 10810 10771 10786 -f 10810 10786 10809 -f 10809 10786 10774 -f 10809 10774 10807 -f 10807 10774 10765 -f 10807 10765 10787 -f 10787 10765 10766 -f 10787 10766 10789 -f 10789 10766 10788 -f 10789 10788 10814 -f 10814 10788 10769 -f 10814 10769 10811 -f 10811 10769 10770 -f 10811 10770 10790 -f 10790 10770 10791 -f 10790 10791 10792 -f 10792 10791 10793 -f 10792 10793 10794 -f 10794 10793 10795 -f 10794 10795 10796 -f 10796 10795 10764 -f 10796 10764 10798 -f 10798 10764 10797 -f 10798 10797 10805 -f 10805 10797 10733 -f 10845 10847 10844 -f 10844 10847 10799 -f 10844 10799 10800 -f 10800 10799 10781 -f 10810 10801 10785 -f 10785 10801 10803 -f 10785 10803 10802 -f 10802 10803 10839 -f 10802 10839 10784 -f 10784 10839 10840 -f 10784 10840 10781 -f 10781 10840 10804 -f 10781 10804 10800 -f 10730 10822 10805 -f 10805 10822 10806 -f 10805 10806 10798 -f 10787 10817 10807 -f 10807 10817 10808 -f 10807 10808 10809 -f 10809 10808 10836 -f 10809 10836 10810 -f 10810 10836 10837 -f 10810 10837 10801 -f 10790 10832 10811 -f 10811 10832 10812 -f 10811 10812 10814 -f 10814 10812 10813 -f 10814 10813 10789 -f 10789 10813 10815 -f 10789 10815 10787 -f 10787 10815 10816 -f 10787 10816 10817 -f 10806 10825 10798 -f 10798 10825 10826 -f 10798 10826 10796 -f 10796 10826 10827 -f 10796 10827 10794 -f 10794 10827 10829 -f 10794 10829 10792 -f 10792 10829 10830 -f 10792 10830 10790 -f 10790 10830 10818 -f 10790 10818 10832 -f 10819 10751 10820 -f 10819 10820 10821 -f 10821 10820 10822 -f 10821 10822 10730 -f 10751 10819 10747 -f 10747 10819 10743 -f 10806 10823 10824 -f 10806 10824 10825 -f 10825 10824 10780 -f 10825 10780 10826 -f 10826 10780 10779 -f 10826 10779 10827 -f 10827 10779 10828 -f 10827 10828 10829 -f 10829 10828 10778 -f 10829 10778 10830 -f 10830 10778 10777 -f 10830 10777 10818 -f 10818 10777 10831 -f 10818 10831 10832 -f 10832 10831 10833 -f 10832 10833 10812 -f 10812 10833 10776 -f 10812 10776 10813 -f 10813 10776 10768 -f 10813 10768 10815 -f 10815 10768 10834 -f 10815 10834 10816 -f 10816 10834 10767 -f 10816 10767 10817 -f 10817 10767 10835 -f 10817 10835 10808 -f 10808 10835 10775 -f 10808 10775 10836 -f 10836 10775 10838 -f 10836 10838 10837 -f 10837 10838 10773 -f 10837 10773 10801 -f 10801 10773 10772 -f 10801 10772 10803 -f 10803 10772 10763 -f 10803 10763 10839 -f 10839 10763 10761 -f 10839 10761 10840 -f 10840 10761 10841 -f 10840 10841 10804 -f 10804 10841 10842 -f 10804 10842 10800 -f 10800 10842 10843 -f 10800 10843 10844 -f 10843 10759 10844 -f 10844 10759 10845 -f 10759 10846 10845 -f 10845 10846 10847 -f 10846 10782 10847 -f 10847 10782 10799 -f 10848 10738 10849 -f 10849 10738 10740 -f 10850 10856 10851 -f 10851 10856 10754 -f 10851 10754 10852 -f 10852 10754 10753 -f 10852 10753 10735 -f 10735 10753 10854 -f 10735 10854 10853 -f 10853 10854 10755 -f 10853 10755 10742 -f 10742 10755 10855 -f 10742 10855 10739 -f 10739 10855 10850 -f 10850 10855 10856 -f 10857 10866 10744 -f 10744 10866 10858 -f 10744 10858 10859 -f 10859 10858 10860 -f 10859 10860 10732 -f 10732 10860 10861 -f 10861 10860 10748 -f 10861 10748 10862 -f 10862 10748 10863 -f 10862 10863 10864 -f 10864 10863 10741 -f 10741 10863 10752 -f 10741 10752 10865 -f 10741 10865 10857 -f 10857 10865 10866 -f 10868 10921 10935 -f 10867 10935 10915 -f 10867 10915 10868 -f 10921 10868 10915 -f 10921 10917 10925 -f 10933 10929 10879 -f 10870 10883 10877 -f 10870 10877 10928 -f 10880 10871 10882 -f 10880 10882 10933 -f 10928 10872 10874 -f 10881 10871 10872 -f 10875 10883 10870 -f 10880 10879 10871 -f 10869 10870 10928 -f 10917 10935 10925 -f 10869 10928 10874 -f 10873 10872 10871 -f 10870 10869 10878 -f 10878 10869 10874 -f 10876 10871 10879 -f 10932 10931 10879 -f 10877 10886 10875 -f 10879 10874 10872 -f 10879 10872 10873 -f 10873 10871 10876 -f 10880 10878 10874 -f 10882 10876 10879 -f 10882 10879 10931 -f 10876 10881 10873 -f 10879 10880 10874 -f 10884 10886 10877 -f 10875 10870 10878 -f 10873 10881 10933 -f 10873 10933 10879 -f 10877 10875 10878 -f 10882 10881 10876 -f 10930 10882 10931 -f 10880 10928 10878 -f 10882 10871 10881 -f 10893 10884 10883 -f 10883 10884 10877 -f 10872 10933 10881 -f 10877 10878 10928 -f 10928 10880 10872 -f 10886 10883 10875 -f 10885 10890 10888 -f 10896 10890 10885 -f 10891 10889 10893 -f 10886 10893 10883 -f 10887 10892 10888 -f 10887 10888 10891 -f 10893 10889 10884 -f 10884 10891 10886 -f 10891 10888 10889 -f 10886 10891 10893 -f 10888 10896 10889 -f 10889 10885 10892 -f 10889 10887 10884 -f 10892 10885 10888 -f 10889 10892 10887 -f 10896 10895 10890 -f 10896 10885 10889 -f 10884 10887 10891 -f 10907 10899 10894 -f 10896 10902 10895 -f 10909 10898 10901 -f 10900 10911 10903 -f 10894 10895 10902 -f 10897 10905 10900 -f 10901 10907 10904 -f 10905 10908 10900 -f 10899 10909 10901 -f 10903 10911 10897 -f 10906 10900 10909 -f 10894 10899 10895 -f 10900 10903 10898 -f 10898 10903 10906 -f 10895 10899 10904 -f 10904 10894 10902 -f 10890 10902 10888 -f 10898 10906 10901 -f 10899 10901 10904 -f 10902 10896 10888 -f 10895 10904 10890 -f 10911 10905 10897 -f 10901 10906 10907 -f 10907 10909 10899 -f 10904 10902 10890 -f 10906 10909 10907 -f 10904 10907 10894 -f 10900 10908 10911 -f 10903 10897 10906 -f 10918 10919 10923 -f 10909 10900 10898 -f 10918 10923 10920 -f 10913 10924 10910 -f 10913 10926 10911 -f 10897 10900 10906 -f 10923 10921 10920 -f 10920 10921 10927 -f 10911 10926 10905 -f 10921 10915 10914 -f 10922 10916 10925 -f 10919 10912 10923 -f 10924 10920 10927 -f 10926 10913 10910 -f 10925 10916 10912 -f 10914 10917 10922 -f 10908 10926 10910 -f 10921 10919 10918 -f 10916 10914 10912 -f 10917 10921 10922 -f 10922 10921 10916 -f 10912 10922 10923 -f 10923 10935 10921 -f 10927 10918 10913 -f 10915 10917 10914 -f 10918 10924 10913 -f 10908 10913 10911 -f 10922 10925 10923 -f 10923 10925 10935 -f 10912 10914 10922 -f 10910 10927 10908 -f 10935 10917 10915 -f 10925 10919 10921 -f 10916 10921 10914 -f 10921 10918 10927 -f 10918 10920 10924 -f 10925 10912 10919 -f 10924 10927 10910 -f 10908 10927 10913 -f 10926 10908 10905 -f 10880 10933 10872 -f 10932 10879 10929 -f 10934 10933 10882 -f 10934 10882 10930 -f 10930 10931 10932 -f 10929 10933 10934 -f 10930 10932 10934 -f 10934 10932 10929 -f 10868 10935 10867 -f 10956 10992 10978 -f 10978 10992 10991 -f 10938 10940 10977 -f 10977 10940 10983 -f 10941 10988 10936 -f 10936 10988 10937 -f 10936 10937 10940 -f 10940 10937 10983 -f 10941 10943 10988 -f 10988 10943 10981 -f 10938 10953 10939 -f 10938 10939 10945 -f 10938 10945 10940 -f 10946 10936 10940 -f 10940 10945 10946 -f 10946 10941 10936 -f 10946 10942 10941 -f 10941 10942 10943 -f 10943 10942 10944 -f 10944 10980 10986 -f 10944 10986 10943 -f 10945 10982 10946 -f 10946 10982 10987 -f 10946 10987 10942 -f 10942 10987 10980 -f 10942 10980 10944 -f 10945 10939 10982 -f 10982 10939 10976 -f 10953 10954 10976 -f 10953 10976 10939 -f 10961 10952 10960 -f 10952 10951 10963 -f 10963 10948 10952 -f 10952 10948 10960 -f 10947 10951 10948 -f 10967 10964 10985 -f 10985 10964 10949 -f 10965 10973 10949 -f 10965 10949 10964 -f 10948 10951 10973 -f 10973 10951 10972 -f 10950 10972 10952 -f 10952 10972 10951 -f 10952 10961 10950 -f 10950 10961 10975 -f 10977 10975 10938 -f 10938 10975 10961 -f 10938 10961 10953 -f 10953 10961 10958 -f 10953 10958 10954 -f 10954 10958 10955 -f 10956 10978 10959 -f 10979 10957 10959 -f 10979 10959 10978 -f 10955 10957 10979 -f 10959 10966 10956 -f 10957 10955 10958 -f 10957 10958 10961 -f 10957 10961 10960 -f 10957 10960 10962 -f 10960 10965 10962 -f 10957 10962 10959 -f 10963 10947 10948 -f 10960 10948 10965 -f 10948 10973 10965 -f 10964 10967 10965 -f 10965 10967 10968 -f 10962 10965 10968 -f 10966 10959 10970 -f 10959 10962 10970 -f 10966 10970 10974 -f 10968 10969 10962 -f 10967 10985 10968 -f 10968 10985 10984 -f 10969 10968 10984 -f 10962 10969 10970 -f 10970 10969 10974 -f 10966 10974 10971 -f 10972 10950 10973 -f 10973 10950 10975 -f 10977 10976 10954 -f 10975 10949 10973 -f 10982 10976 10977 -f 10974 10978 10971 -f 10971 10978 11010 -f 11010 10978 10991 -f 10954 10985 10977 -f 10977 10985 10949 -f 10977 10949 10975 -f 10978 10974 10969 -f 10978 10969 10979 -f 10979 10969 10955 -f 10986 10980 10981 -f 10981 10980 10988 -f 10982 10977 10983 -f 10982 10983 10987 -f 10955 10969 10984 -f 10955 10984 10985 -f 10955 10985 10954 -f 11010 10991 10989 -f 10983 10937 10987 -f 11010 10989 11030 -f 10980 10987 10988 -f 10988 10987 10937 -f 11017 11030 10989 -f 11017 10989 10990 -f 10990 10989 10991 -f 10990 10991 10992 -f 11006 11025 10995 -f 10995 11025 11003 -f 10995 11003 10999 -f 10997 10996 11021 -f 10997 11021 10994 -f 11013 11001 11000 -f 11013 11000 10993 -f 10993 11000 10998 -f 10993 10998 11014 -f 11014 10998 10997 -f 11014 10997 10994 -f 10996 10997 10998 -f 10996 10998 11000 -f 11009 10999 10996 -f 11009 10996 11000 -f 11009 11000 11001 -f 11003 11005 11027 -f 11027 11005 11026 -f 11002 11063 11004 -f 11003 11006 10995 -f 11004 11005 11007 -f 11007 11005 11003 -f 11003 10995 11007 -f 10995 10999 11007 -f 11007 10999 11009 -f 11009 11001 11011 -f 11010 11015 11008 -f 11011 11001 11010 -f 11010 11001 11013 -f 11010 11013 11015 -f 11007 11009 11011 -f 11018 11012 11008 -f 11008 11015 11018 -f 11014 10994 10993 -f 11029 11018 10993 -f 11013 10993 11015 -f 11015 10993 11018 -f 10993 10994 11029 -f 11016 11018 11017 -f 11017 11018 11019 -f 11018 11029 11019 -f 11029 10994 11020 -f 11029 11020 11022 -f 11029 11022 11031 -f 10994 11021 11020 -f 11020 11021 11024 -f 11020 11024 11022 -f 11022 11024 11023 -f 11022 11023 11031 -f 11023 11024 10996 -f 11024 11021 10996 -f 10996 10999 11003 -f 11023 10996 11027 -f 11027 10996 11003 -f 11028 11027 11026 -f 11017 11019 11030 -f 11030 11029 11031 -f 11030 11031 11028 -f 11028 11031 11023 -f 11028 11023 11027 -f 11030 11019 11029 -f 11076 11039 11032 -f 11076 11032 11075 -f 11033 11034 11070 -f 11070 11034 11040 -f 11070 11040 11073 -f 11073 11040 11039 -f 11073 11039 11076 -f 11036 11037 11033 -f 11033 11037 11034 -f 11035 11060 11037 -f 11035 11037 11036 -f 11037 11060 11038 -f 11034 11037 11038 -f 11034 11038 11045 -f 11034 11045 11040 -f 11042 11039 11041 -f 11045 11043 11040 -f 11042 11032 11039 -f 11039 11040 11041 -f 11040 11043 11041 -f 11075 11042 11072 -f 11072 11042 11041 -f 11072 11041 11044 -f 11044 11041 11043 -f 11044 11043 11069 -f 11069 11043 11045 -f 11069 11045 11065 -f 11065 11045 11038 -f 11049 11046 11047 -f 11049 11068 11048 -f 11054 11047 11046 -f 11049 11047 11059 -f 11056 11047 11085 -f 11056 11085 11050 -f 11056 11050 11058 -f 11047 11056 11059 -f 11084 11085 11058 -f 11051 11054 11066 -f 11066 11054 11052 -f 11053 11085 11051 -f 11051 11085 11054 -f 11057 11058 11053 -f 11053 11058 11085 -f 11058 11055 11056 -f 11057 11055 11058 -f 11064 11059 11055 -f 11055 11059 11056 -f 11060 11035 11062 -f 11059 11064 11065 -f 11065 11038 11059 -f 11059 11038 11060 -f 11059 11060 11049 -f 11049 11060 11062 -f 11061 11048 11068 -f 11049 11062 11068 -f 11074 11063 11061 -f 11061 11063 11048 -f 11026 11005 11028 -f 11028 11005 11071 -f 11005 11004 11071 -f 11071 11004 11074 -f 11063 11074 11004 -f 11055 11057 11064 -f 11064 11057 11053 -f 11064 11051 11065 -f 11065 11051 11066 -f 11065 11066 11035 -f 11064 11053 11051 -f 11066 11062 11035 -f 11065 11035 11036 -f 11066 11067 11062 -f 11062 11067 11068 -f 11068 11067 11077 -f 11065 11036 11033 -f 11065 11033 11069 -f 11069 11033 11070 -f 11070 11044 11069 -f 11011 11028 11071 -f 11070 11072 11044 -f 11011 11071 11074 -f 11070 11073 11072 -f 11072 11073 11075 -f 11075 11073 11076 -f 11068 11077 11061 -f 11061 11077 11079 -f 11061 11079 11078 -f 11061 11078 11074 -f 11074 11078 11011 -f 11052 11083 11066 -f 11066 11083 11067 -f 11067 11082 11077 -f 11077 11081 11079 -f 11080 11078 11079 -f 11082 11067 11083 -f 11077 11082 11081 -f 11079 11081 11080 -f 11080 11081 11082 -f 11080 11082 11083 -f 11083 11054 11046 -f 11054 11083 11052 -f 11085 11084 11050 -f 11054 11085 11047 -f 11090 11116 11093 -f 11093 11116 11112 -f 11115 11087 11086 -f 11086 11087 11094 -f 11086 11094 11113 -f 11113 11094 11093 -f 11113 11093 11112 -f 11106 11095 11115 -f 11115 11095 11087 -f 11104 11103 11090 -f 11090 11103 11102 -f 11090 11102 11099 -f 11090 11099 11121 -f 11121 11099 11097 -f 11121 11097 11091 -f 11093 11088 11092 -f 11093 11092 11090 -f 11090 11092 11104 -f 11095 11104 11096 -f 11089 11087 11096 -f 11093 11094 11088 -f 11088 11094 11089 -f 11089 11094 11087 -f 11092 11096 11104 -f 11087 11095 11096 -f 11098 11097 11099 -f 11098 11099 11100 -f 11100 11099 11102 -f 11100 11102 11101 -f 11101 11102 11103 -f 11101 11103 11109 -f 11109 11103 11104 -f 11109 11104 11105 -f 11105 11104 11106 -f 11106 11104 11095 -f 11107 11110 11116 -f 11107 11116 11117 -f 11110 11112 11116 -f 11101 11109 11111 -f 11114 11115 11108 -f 11115 11086 11108 -f 11108 11086 11113 -f 11105 11111 11109 -f 11107 11098 11110 -f 11110 11098 11100 -f 11110 11100 11111 -f 11111 11100 11101 -f 11112 11108 11113 -f 11106 11114 11105 -f 11105 11114 11111 -f 11114 11106 11115 -f 11116 11090 11117 -f 11117 11090 11121 -f 11117 11121 11120 -f 11144 11136 11123 -f 11123 11136 11133 -f 11121 11123 11118 -f 11118 11119 11121 -f 11121 11119 11120 -f 11123 11122 11118 -f 11133 11122 11123 -f 11154 11132 11131 -f 11154 11131 11156 -f 11156 11131 11130 -f 11156 11130 11147 -f 11147 11130 11124 -f 11147 11124 11145 -f 11145 11124 11129 -f 11145 11129 11152 -f 11152 11129 11125 -f 11125 11129 11126 -f 11125 11126 11127 -f 11127 11126 11139 -f 11129 11124 11136 -f 11136 11124 11130 -f 11136 11130 11131 -f 11136 11131 11133 -f 11133 11131 11132 -f 11133 11132 11134 -f 11138 11128 11137 -f 11138 11137 11136 -f 11128 11138 11141 -f 11136 11137 11129 -f 11126 11129 11140 -f 11135 11139 11140 -f 11128 11141 11135 -f 11137 11140 11129 -f 11139 11126 11140 -f 11127 11139 11135 -f 11127 11135 11149 -f 11149 11135 11141 -f 11149 11141 11153 -f 11153 11141 11138 -f 11153 11138 11142 -f 11136 11144 11138 -f 11138 11144 11142 -f 11143 11155 11144 -f 11143 11144 11123 -f 11155 11148 11144 -f 11144 11148 11142 -f 11152 11146 11145 -f 11145 11146 11147 -f 11142 11148 11153 -f 11127 11149 11150 -f 11150 11125 11127 -f 11125 11150 11151 -f 11125 11151 11152 -f 11152 11151 11146 -f 11150 11149 11153 -f 11150 11153 11148 -f 11143 11154 11155 -f 11155 11154 11156 -f 11155 11156 11146 -f 11146 11156 11147 -f 11161 11159 11200 -f 11200 11159 11157 -f 11159 11160 11157 -f 11157 11160 11158 -f 11159 11161 11160 -f 11160 11161 11163 -f 11162 11204 11163 -f 11163 11204 11164 -f 11164 11206 11163 -f 11163 11206 11207 -f 11163 11207 11160 -f 11165 11216 11226 -f 11226 11216 11218 -f 11226 11218 11217 -f 11226 11217 11166 -f 11217 11211 11166 -f 11166 11211 11168 -f 11166 11168 11167 -f 11167 11168 11198 -f 11169 11232 11167 -f 11167 11232 11166 -f 11169 11167 11173 -f 11170 11171 11169 -f 11199 11177 11174 -f 11171 11172 11169 -f 11169 11172 11176 -f 11174 11181 11178 -f 11169 11173 11209 -f 11199 11174 11178 -f 11170 11169 11175 -f 11175 11169 11209 -f 11175 11209 11180 -f 11169 11176 11199 -f 11199 11176 11177 -f 11183 11179 11209 -f 11209 11179 11180 -f 11178 11181 11182 -f 11178 11182 11209 -f 11209 11182 11183 -f 11173 11167 11198 -f 11192 11186 11168 -f 11168 11186 11185 -f 11192 11193 11186 -f 11194 11195 11198 -f 11187 11189 11188 -f 11188 11189 11190 -f 11188 11190 11191 -f 11188 11191 11192 -f 11192 11191 11193 -f 11168 11185 11194 -f 11168 11194 11198 -f 11195 11196 11198 -f 11198 11196 11197 -f 11188 11184 11187 -f 11187 11184 11197 -f 11197 11184 11198 -f 11198 11184 11173 -f 11188 11192 11213 -f 11213 11192 11212 -f 11199 11168 11228 -f 11228 11168 11211 -f 11228 11211 11227 -f 11227 11211 11212 -f 11227 11212 11178 -f 11178 11212 11192 -f 11178 11192 11199 -f 11199 11192 11168 -f 11202 11233 11227 -f 11202 11227 11163 -f 11163 11227 11178 -f 11163 11178 11209 -f 11161 11200 11163 -f 11163 11200 11202 -f 11200 11157 11158 -f 11203 11201 11202 -f 11202 11201 11205 -f 11202 11205 11210 -f 11200 11158 11202 -f 11202 11158 11208 -f 11202 11208 11203 -f 11162 11210 11205 -f 11162 11205 11204 -f 11204 11205 11201 -f 11204 11201 11164 -f 11164 11201 11203 -f 11164 11203 11206 -f 11206 11203 11208 -f 11206 11208 11207 -f 11207 11208 11158 -f 11207 11158 11160 -f 11162 11163 11209 -f 11216 11165 11213 -f 11213 11165 11233 -f 11173 11184 11209 -f 11209 11184 11188 -f 11209 11188 11162 -f 11162 11188 11213 -f 11162 11213 11210 -f 11210 11213 11233 -f 11210 11233 11202 -f 11211 11225 11223 -f 11211 11223 11212 -f 11212 11223 11215 -f 11212 11215 11213 -f 11217 11219 11214 -f 11217 11214 11211 -f 11211 11214 11225 -f 11215 11221 11213 -f 11220 11216 11213 -f 11220 11213 11221 -f 11218 11216 11220 -f 11218 11220 11217 -f 11217 11220 11219 -f 11235 11220 11221 -f 11235 11221 11236 -f 11236 11221 11215 -f 11236 11215 11223 -f 11236 11223 11229 -f 11229 11223 11222 -f 11222 11223 11225 -f 11222 11225 11224 -f 11224 11225 11231 -f 11231 11225 11214 -f 11231 11214 11230 -f 11230 11214 11219 -f 11230 11219 11234 -f 11234 11219 11235 -f 11235 11219 11220 -f 11165 11226 11232 -f 11227 11229 11222 -f 11227 11222 11228 -f 11232 11226 11166 -f 11228 11222 11224 -f 11236 11229 11227 -f 11228 11224 11231 -f 11233 11236 11227 -f 11234 11233 11230 -f 11230 11233 11165 -f 11230 11165 11231 -f 11231 11165 11232 -f 11231 11232 11228 -f 11234 11235 11233 -f 11233 11235 11236 -f 11169 11199 11232 -f 11232 11199 11228 -f 11376 11389 11462 -f 11462 11389 11428 -f 11428 11389 11391 -f 11428 11391 11441 -f 11441 11391 11386 -f 11441 11386 11439 -f 11386 11239 11439 -f 11439 11239 11237 -f 11381 11240 11425 -f 11381 11425 11415 -f 11415 11425 11424 -f 11415 11424 11238 -f 11238 11424 11413 -f 11413 11424 11237 -f 11413 11237 11239 -f 11381 11242 11240 -f 11240 11242 11241 -f 11416 11453 11241 -f 11416 11241 11242 -f 11416 11243 11453 -f 11453 11243 11451 -f 11417 11461 11243 -f 11243 11461 11451 -f 11244 11436 11434 -f 11244 11434 11456 -f 11244 11456 11245 -f 11245 11456 11458 -f 11245 11458 11417 -f 11417 11458 11461 -f 11271 11483 11468 -f 11271 11468 11246 -f 11246 11468 11466 -f 11462 11247 11248 -f 11462 11248 11249 -f 11249 11248 11266 -f 11249 11266 11463 -f 11463 11266 11466 -f 11466 11266 11246 -f 11281 11469 11250 -f 11250 11469 11478 -f 11250 11478 11284 -f 11284 11478 11251 -f 11284 11251 11252 -f 11252 11251 11253 -f 11252 11253 11254 -f 11254 11253 11481 -f 11254 11481 11285 -f 11285 11481 11482 -f 11255 11256 11257 -f 11257 11256 11258 -f 11257 11258 11474 -f 11257 11474 11277 -f 11277 11474 11473 -f 11277 11473 11273 -f 11273 11473 11470 -f 11273 11470 11274 -f 11274 11470 11280 -f 11280 11470 11281 -f 11281 11470 11469 -f 11255 11259 11256 -f 11256 11259 11260 -f 11260 11259 11476 -f 11476 11259 11261 -f 11476 11261 11475 -f 11475 11261 11472 -f 11472 11261 11275 -f 11472 11275 11262 -f 11262 11275 11263 -f 11262 11263 11264 -f 11262 11264 11471 -f 11471 11264 11279 -f 11471 11279 11477 -f 11246 11266 11296 -f 11247 11265 11292 -f 11292 11293 11247 -f 11247 11293 11267 -f 11296 11266 11295 -f 11295 11266 11267 -f 11266 11248 11267 -f 11267 11248 11247 -f 11272 11270 11483 -f 11296 11271 11246 -f 11268 11290 11271 -f 11268 11289 11290 -f 11271 11296 11268 -f 11268 11296 11289 -f 11269 11285 11290 -f 11290 11285 11270 -f 11290 11270 11272 -f 11290 11272 11271 -f 11271 11272 11483 -f 11274 11280 11264 -f 11264 11280 11279 -f 11273 11263 11275 -f 11273 11275 11277 -f 11263 11273 11264 -f 11264 11273 11274 -f 11276 11275 11261 -f 11261 11259 11276 -f 11276 11259 11255 -f 11276 11255 11278 -f 11275 11276 11277 -f 11277 11276 11278 -f 11277 11278 11257 -f 11255 11257 11278 -f 11279 11280 11281 -f 11279 11281 11282 -f 11282 11281 11250 -f 11282 11250 11283 -f 11283 11250 11284 -f 11283 11284 11286 -f 11286 11284 11252 -f 11286 11252 11269 -f 11269 11252 11254 -f 11269 11254 11285 -f 11290 11291 11269 -f 11269 11291 11287 -f 11269 11287 11286 -f 11286 11287 11480 -f 11286 11480 11283 -f 11283 11480 11479 -f 11283 11479 11282 -f 11282 11479 11288 -f 11282 11288 11279 -f 11279 11288 11477 -f 11291 11290 11289 -f 11292 11297 11464 -f 11292 11464 11293 -f 11293 11464 11294 -f 11293 11294 11267 -f 11267 11294 11295 -f 11467 11295 11294 -f 11465 11296 11467 -f 11467 11296 11295 -f 11465 11289 11296 -f 11292 11265 11297 -f 11374 11297 11372 -f 11372 11297 11347 -f 11365 11299 11298 -f 11298 11299 11333 -f 11303 11300 11301 -f 11303 11301 11378 -f 11378 11301 11302 -f 11300 11303 11304 -f 11304 11303 11360 -f 11304 11360 11336 -f 11336 11360 11355 -f 11336 11355 11327 -f 11355 11305 11327 -f 11327 11305 11340 -f 11340 11305 11307 -f 11340 11307 11306 -f 11307 11308 11306 -f 11306 11308 11309 -f 11309 11308 11364 -f 11309 11364 11310 -f 11310 11364 11311 -f 11310 11311 11339 -f 11339 11311 11365 -f 11339 11365 11298 -f 11328 11329 11314 -f 11335 11326 11340 -f 11336 11327 11326 -f 11312 11297 11265 -f 11312 11265 11341 -f 11523 11347 11312 -f 11312 11347 11297 -f 11315 11313 11317 -f 11328 11314 11315 -f 11315 11314 11504 -f 11315 11504 11313 -f 11322 11316 11313 -f 11313 11316 11317 -f 11340 11326 11327 -f 11319 11318 11321 -f 11319 11321 11320 -f 11321 11322 11320 -f 11265 11300 11304 -f 11313 11323 11322 -f 11322 11323 11324 -f 11322 11324 11320 -f 11320 11324 11325 -f 11523 11330 11347 -f 11347 11330 11346 -f 11328 11332 11329 -f 11329 11332 11333 -f 11329 11333 11330 -f 11330 11333 11346 -f 11310 11338 11331 -f 11331 11309 11310 -f 11332 11334 11333 -f 11333 11334 11343 -f 11309 11331 11306 -f 11306 11331 11335 -f 11306 11335 11340 -f 11342 11336 11326 -f 11337 11338 11298 -f 11298 11338 11339 -f 11339 11338 11310 -f 11325 11341 11320 -f 11320 11341 11265 -f 11320 11265 11342 -f 11342 11265 11304 -f 11342 11304 11336 -f 11333 11343 11344 -f 11333 11344 11298 -f 11298 11344 11337 -f 11337 11344 11318 -f 11337 11318 11319 -f 11333 11299 11345 -f 11333 11345 11346 -f 11346 11345 11372 -f 11372 11347 11346 -f 11353 11308 11307 -f 11353 11307 11362 -f 11366 11350 11367 -f 11365 11367 11348 -f 11352 11378 11375 -f 11349 11378 11359 -f 11359 11378 11354 -f 11367 11350 11351 -f 11367 11351 11370 -f 11367 11370 11352 -f 11359 11354 11363 -f 11355 11360 11361 -f 11361 11360 11349 -f 11364 11308 11363 -f 11365 11356 11357 -f 11378 11358 11354 -f 11308 11353 11359 -f 11308 11359 11363 -f 11378 11349 11360 -f 11378 11360 11303 -f 11355 11361 11305 -f 11305 11361 11362 -f 11305 11362 11307 -f 11363 11311 11364 -f 11365 11357 11366 -f 11365 11366 11367 -f 11348 11368 11365 -f 11365 11368 11299 -f 11372 11345 11369 -f 11369 11345 11299 -f 11369 11299 11368 -f 11370 11371 11352 -f 11352 11371 11378 -f 11378 11371 11358 -f 11356 11365 11363 -f 11363 11365 11311 -f 11372 11369 11373 -f 11372 11373 11374 -f 11374 11373 11375 -f 11374 11375 11378 -f 11418 11412 11420 -f 11420 11412 11376 -f 11420 11376 11377 -f 11377 11376 11374 -f 11377 11374 11302 -f 11302 11374 11378 -f 11417 11379 11412 -f 11380 11376 11383 -f 11390 11389 11380 -f 11380 11389 11376 -f 11412 11379 11385 -f 11412 11385 11376 -f 11395 11396 11392 -f 11394 11388 11381 -f 11381 11388 11242 -f 11242 11388 11382 -f 11242 11382 11416 -f 11411 11383 11384 -f 11384 11383 11376 -f 11384 11376 11385 -f 11393 11404 11386 -f 11389 11390 11391 -f 11395 11386 11390 -f 11390 11386 11391 -f 11395 11392 11386 -f 11386 11392 11393 -f 11398 11394 11387 -f 11395 11397 11396 -f 11398 11387 11399 -f 11398 11399 11384 -f 11407 11400 11403 -f 11396 11397 11402 -f 11396 11402 11401 -f 11401 11402 11400 -f 11399 11403 11384 -f 11386 11404 11405 -f 11386 11405 11239 -f 11239 11405 11406 -f 11394 11381 11387 -f 11407 11408 11400 -f 11400 11408 11401 -f 11400 11409 11403 -f 11403 11409 11410 -f 11403 11410 11384 -f 11384 11410 11411 -f 11412 11244 11245 -f 11412 11245 11417 -f 11406 11414 11239 -f 11239 11414 11413 -f 11413 11414 11238 -f 11381 11415 11387 -f 11387 11415 11414 -f 11414 11415 11238 -f 11417 11416 11382 -f 11417 11243 11416 -f 11412 11418 11244 -f 11244 11418 11419 -f 11244 11419 11436 -f 11418 11420 11419 -f 11419 11420 11422 -f 11420 11377 11422 -f 11422 11377 11421 -f 11377 11302 11421 -f 11421 11302 11301 -f 11301 11300 11421 -f 11421 11300 11265 -f 11421 11265 11422 -f 11422 11265 11423 -f 11422 11423 11419 -f 11419 11423 11436 -f 11435 11436 11432 -f 11237 11430 11426 -f 11425 11449 11437 -f 11437 11424 11425 -f 11237 11426 11439 -f 11426 11427 11439 -f 11439 11427 11438 -f 11428 11442 11462 -f 11462 11442 11429 -f 11462 11429 11423 -f 11425 11240 11449 -f 11237 11437 11430 -f 11443 11440 11439 -f 11423 11429 11431 -f 11423 11431 11436 -f 11436 11431 11432 -f 11433 11434 11435 -f 11435 11434 11436 -f 11448 11240 11241 -f 11448 11241 11454 -f 11442 11428 11441 -f 11442 11441 11440 -f 11437 11237 11424 -f 11444 11443 11439 -f 11444 11439 11438 -f 11439 11440 11441 -f 11443 11444 11445 -f 11445 11444 11446 -f 11445 11446 11447 -f 11445 11447 11433 -f 11433 11447 11455 -f 11433 11456 11434 -f 11240 11448 11450 -f 11240 11450 11449 -f 11452 11460 11459 -f 11451 11452 11453 -f 11453 11452 11454 -f 11453 11454 11241 -f 11433 11455 11456 -f 11456 11455 11457 -f 11456 11457 11460 -f 11456 11460 11458 -f 11460 11452 11451 -f 11460 11451 11458 -f 11450 11459 11449 -f 11449 11459 11460 -f 11451 11461 11458 -f 11423 11247 11462 -f 11462 11249 11376 -f 11376 11249 11374 -f 11294 11463 11466 -f 11467 11294 11466 -f 11463 11294 11374 -f 11463 11374 11249 -f 11294 11464 11374 -f 11374 11464 11297 -f 11466 11465 11467 -f 11468 11483 11482 -f 11466 11468 11291 -f 11289 11465 11291 -f 11291 11465 11466 -f 11291 11468 11482 -f 11291 11482 11287 -f 11477 11478 11469 -f 11477 11469 11471 -f 11469 11470 11471 -f 11471 11470 11473 -f 11473 11472 11262 -f 11473 11262 11471 -f 11258 11256 11474 -f 11474 11256 11260 -f 11474 11260 11475 -f 11475 11472 11474 -f 11474 11472 11473 -f 11260 11476 11475 -f 11477 11288 11478 -f 11478 11288 11479 -f 11478 11479 11251 -f 11251 11479 11480 -f 11251 11480 11253 -f 11253 11480 11287 -f 11253 11287 11481 -f 11481 11287 11482 -f 11285 11482 11270 -f 11270 11482 11483 -f 11523 11526 11484 -f 11484 11526 11528 -f 11484 11528 11485 -f 11485 11528 11486 -f 11485 11486 11487 -f 11487 11486 11527 -f 11487 11527 11488 -f 11488 11527 11490 -f 11488 11490 11489 -f 11489 11490 11491 -f 11489 11491 11492 -f 11492 11491 11529 -f 11492 11529 11493 -f 11493 11529 11494 -f 11493 11494 11495 -f 11495 11494 11496 -f 11495 11496 11497 -f 11497 11496 11498 -f 11497 11498 11499 -f 11499 11498 11500 -f 11499 11500 11501 -f 11501 11500 11503 -f 11501 11503 11502 -f 11502 11503 11532 -f 11502 11532 11504 -f 11504 11532 11531 -f 11504 11531 11505 -f 11505 11531 11530 -f 11505 11530 11506 -f 11506 11530 11508 -f 11506 11508 11507 -f 11507 11508 11533 -f 11507 11533 11509 -f 11509 11533 11510 -f 11509 11510 11511 -f 11511 11510 11512 -f 11511 11512 11513 -f 11513 11512 11514 -f 11513 11514 11515 -f 11515 11514 11516 -f 11515 11516 11517 -f 11517 11516 11534 -f 11517 11534 11518 -f 11518 11534 11519 -f 11518 11519 11520 -f 11520 11519 11535 -f 11520 11535 11521 -f 11521 11535 11524 -f 11521 11524 11522 -f 11522 11524 11525 -f 11522 11525 11523 -f 11523 11525 11526 -f 11525 11524 11529 -f 11525 11529 11526 -f 11527 11486 11529 -f 11529 11486 11528 -f 11529 11528 11526 -f 11529 11491 11490 -f 11529 11490 11527 -f 11498 11496 11529 -f 11529 11496 11494 -f 11532 11503 11529 -f 11529 11503 11500 -f 11529 11500 11498 -f 11508 11530 11529 -f 11529 11530 11531 -f 11529 11531 11532 -f 11512 11510 11529 -f 11529 11510 11533 -f 11529 11533 11508 -f 11534 11516 11529 -f 11529 11516 11514 -f 11529 11514 11512 -f 11524 11535 11529 -f 11529 11535 11519 -f 11529 11519 11534 -f 11540 11557 11561 -f 11540 11561 11545 -f 11545 11561 11543 -f 11543 11561 11562 -f 11540 11542 11557 -f 11557 11542 11558 -f 11580 11579 11542 -f 11542 11579 11558 -f 11580 11542 11536 -f 11580 11536 11537 -f 11580 11537 11610 -f 11544 11541 11540 -f 11538 11554 11610 -f 11538 11610 11537 -f 11554 11538 11539 -f 11544 11540 11545 -f 11540 11541 11542 -f 11542 11541 11536 -f 11554 11539 11543 -f 11539 11544 11543 -f 11544 11545 11543 -f 11646 11631 11547 -f 11547 11631 11635 -f 11548 11646 11546 -f 11546 11646 11547 -f 11657 11548 11604 -f 11604 11548 11546 -f 11657 11604 11549 -f 11549 11604 11608 -f 11549 11608 11550 -f 11549 11550 11551 -f 11551 11550 11552 -f 11551 11552 11655 -f 11655 11552 11553 -f 11553 11552 11601 -f 11553 11601 11555 -f 11543 11562 11554 -f 11554 11562 11555 -f 11554 11555 11601 -f 11559 11558 11579 -f 11556 11557 11559 -f 11559 11557 11558 -f 11560 11563 11555 -f 11556 11562 11561 -f 11564 11648 11563 -f 11556 11561 11557 -f 11562 11556 11560 -f 11562 11560 11555 -f 11555 11563 11648 -f 11648 11564 11579 -f 11579 11564 11559 -f 11575 11565 11582 -f 11575 11582 11566 -f 11575 11569 11565 -f 11565 11569 11587 -f 11567 11590 11577 -f 11577 11590 11568 -f 11577 11568 11587 -f 11577 11587 11569 -f 11572 11578 11573 -f 11576 11575 11566 -f 11574 11567 11577 -f 11567 11574 11570 -f 11567 11570 11571 -f 11570 11572 11571 -f 11571 11572 11573 -f 11574 11569 11576 -f 11576 11569 11575 -f 11574 11577 11569 -f 11573 11578 11566 -f 11566 11578 11576 -f 11579 11580 11648 -f 11648 11580 11610 -f 11648 11610 11581 -f 11581 11610 11573 -f 11581 11573 11582 -f 11582 11573 11566 -f 11582 11583 11584 -f 11582 11584 11581 -f 11583 11582 11565 -f 11581 11584 11585 -f 11589 11586 11587 -f 11581 11585 11645 -f 11645 11585 11588 -f 11589 11587 11568 -f 11587 11586 11565 -f 11565 11586 11583 -f 11645 11588 11590 -f 11588 11589 11590 -f 11589 11568 11590 -f 11590 11567 11645 -f 11645 11567 11571 -f 11645 11571 11599 -f 11645 11599 11647 -f 11647 11599 11611 -f 11647 11611 11591 -f 11591 11611 11606 -f 11591 11606 11605 -f 11591 11605 11658 -f 11658 11605 11618 -f 11658 11618 11592 -f 11592 11618 11649 -f 11649 11618 11620 -f 11593 11649 11594 -f 11594 11649 11620 -f 11623 11593 11615 -f 11615 11593 11594 -f 11651 11616 11614 -f 11651 11614 11595 -f 11595 11614 11607 -f 11595 11607 11596 -f 11596 11607 11600 -f 11596 11600 11662 -f 11662 11600 11597 -f 11597 11600 11613 -f 11597 11613 11598 -f 11598 11613 11612 -f 11598 11612 11621 -f 11598 11621 11659 -f 11659 11621 11652 -f 11652 11621 11617 -f 11652 11617 11650 -f 11650 11617 11616 -f 11650 11616 11651 -f 11599 11571 11573 -f 11610 11611 11573 -f 11573 11611 11599 -f 11554 11601 11610 -f 11601 11552 11610 -f 11610 11552 11635 -f 11635 11552 11550 -f 11602 11604 11546 -f 11602 11546 11671 -f 11639 11618 11605 -f 11639 11605 11635 -f 11635 11605 11610 -f 11610 11605 11606 -f 11620 11600 11594 -f 11594 11600 11607 -f 11615 11616 11617 -f 11635 11550 11608 -f 11635 11664 11547 -f 11547 11664 11609 -f 11610 11606 11611 -f 11620 11612 11613 -f 11620 11613 11600 -f 11607 11614 11594 -f 11594 11614 11616 -f 11594 11616 11615 -f 11639 11615 11618 -f 11618 11615 11621 -f 11618 11621 11620 -f 11620 11621 11612 -f 11603 11666 11608 -f 11608 11666 11635 -f 11635 11666 11664 -f 11609 11619 11547 -f 11547 11619 11546 -f 11546 11619 11671 -f 11617 11621 11615 -f 11602 11669 11604 -f 11608 11622 11603 -f 11604 11669 11622 -f 11604 11622 11608 -f 11653 11623 11639 -f 11639 11623 11615 -f 11642 11638 11633 -f 11633 11638 11637 -f 11642 11633 11624 -f 11624 11633 11625 -f 11624 11625 11641 -f 11641 11625 11628 -f 11626 11641 11627 -f 11627 11641 11628 -f 11629 11626 11630 -f 11630 11626 11627 -f 11631 11632 11635 -f 11625 11634 11628 -f 11632 11633 11637 -f 11630 11627 11634 -f 11634 11627 11628 -f 11633 11632 11625 -f 11625 11632 11634 -f 11637 11636 11632 -f 11632 11636 11635 -f 11644 11635 11636 -f 11644 11636 11643 -f 11643 11636 11637 -f 11643 11637 11638 -f 11654 11653 11644 -f 11644 11653 11639 -f 11644 11639 11635 -f 11641 11626 11629 -f 11629 11640 11641 -f 11641 11640 11624 -f 11624 11640 11654 -f 11624 11654 11642 -f 11642 11654 11638 -f 11638 11654 11643 -f 11643 11654 11644 -f 11631 11549 11551 -f 11553 11555 11648 -f 11665 11657 11549 -f 11581 11645 11647 -f 11581 11647 11648 -f 11648 11647 11591 -f 11653 11652 11623 -f 11623 11652 11650 -f 11596 11662 11649 -f 11650 11651 11623 -f 11623 11651 11593 -f 11593 11651 11595 -f 11657 11668 11548 -f 11646 11665 11549 -f 11646 11549 11631 -f 11659 11652 11648 -f 11648 11652 11653 -f 11631 11551 11653 -f 11653 11551 11655 -f 11653 11655 11648 -f 11648 11655 11553 -f 11668 11656 11548 -f 11596 11649 11593 -f 11596 11593 11595 -f 11665 11667 11657 -f 11657 11667 11660 -f 11657 11660 11668 -f 11656 11670 11548 -f 11591 11658 11648 -f 11648 11658 11659 -f 11659 11658 11592 -f 11592 11597 11598 -f 11592 11598 11659 -f 11646 11663 11661 -f 11646 11661 11665 -f 11649 11662 11597 -f 11649 11597 11592 -f 11548 11670 11663 -f 11548 11663 11646 -f 11663 11619 11609 -f 11663 11609 11661 -f 11661 11609 11664 -f 11661 11664 11665 -f 11665 11664 11666 -f 11665 11666 11603 -f 11665 11603 11667 -f 11667 11603 11660 -f 11660 11603 11622 -f 11660 11622 11668 -f 11668 11622 11669 -f 11668 11669 11602 -f 11668 11602 11656 -f 11656 11602 11671 -f 11656 11671 11670 -f 11670 11671 11619 -f 11670 11619 11663 -f 11672 11674 11675 -f 11673 11675 11674 -f 11676 11737 11677 -f 11677 11737 11678 -f 11677 11678 11679 -f 11679 11678 11681 -f 11679 11681 11680 -f 11680 11681 11682 -f 11680 11682 11684 -f 11684 11682 11683 -f 11684 11683 11686 -f 11686 11683 11685 -f 11686 11685 11687 -f 11687 11685 11689 -f 11687 11689 11688 -f 11688 11689 11691 -f 11688 11691 11690 -f 11690 11691 11692 -f 11690 11692 11693 -f 11693 11692 11694 -f 11693 11694 11695 -f 11695 11694 11696 -f 11695 11696 11698 -f 11698 11696 11697 -f 11698 11697 11699 -f 11699 11697 11700 -f 11699 11700 11701 -f 11701 11700 11703 -f 11701 11703 11702 -f 11702 11703 11705 -f 11702 11705 11704 -f 11704 11705 11706 -f 11704 11706 11707 -f 11707 11706 11708 -f 11707 11708 11709 -f 11709 11708 11710 -f 11709 11710 11711 -f 11711 11710 11712 -f 11711 11712 11713 -f 11713 11712 11714 -f 11713 11714 11715 -f 11715 11714 11717 -f 11715 11717 11716 -f 11716 11717 11718 -f 11716 11718 11720 -f 11720 11718 11719 -f 11720 11719 11721 -f 11721 11719 11722 -f 11721 11722 11723 -f 11723 11722 11725 -f 11723 11725 11724 -f 11724 11725 11726 -f 11724 11726 11727 -f 11727 11726 11729 -f 11727 11729 11728 -f 11728 11729 11730 -f 11728 11730 11731 -f 11731 11730 11733 -f 11731 11733 11732 -f 11732 11733 11734 -f 11732 11734 11735 -f 11735 11734 11736 -f 11735 11736 11676 -f 11676 11736 11737 -f 11738 11741 11739 -f 11741 11740 11739 -f 11742 11743 11745 -f 11743 11744 11745 -f 11746 11745 11744 -f 11748 11747 11749 -f 11747 11751 11749 -f 11750 11749 11751 -f 11748 11749 11750 -f 11754 11753 11752 -f 11752 11757 11754 -f 11755 11753 11754 -f 11754 11757 11756 -f 11756 11757 11752 -f 11762 11761 11760 -f 11759 11760 11758 -f 11758 11760 11761 -f 11763 11836 11764 -f 11764 11836 11766 -f 11764 11766 11765 -f 11765 11766 11767 -f 11765 11767 11769 -f 11769 11767 11768 -f 11769 11768 11770 -f 11770 11768 11771 -f 11770 11771 11773 -f 11773 11771 11772 -f 11773 11772 11774 -f 11774 11772 11775 -f 11774 11775 11776 -f 11776 11775 11778 -f 11776 11778 11777 -f 11777 11778 11779 -f 11777 11779 11780 -f 11780 11779 11781 -f 11780 11781 11782 -f 11782 11781 11783 -f 11782 11783 11785 -f 11785 11783 11784 -f 11785 11784 11786 -f 11786 11784 11788 -f 11786 11788 11787 -f 11787 11788 11789 -f 11787 11789 11790 -f 11790 11789 11791 -f 11790 11791 11792 -f 11792 11791 11793 -f 11792 11793 11794 -f 11794 11793 11795 -f 11794 11795 11796 -f 11796 11795 11797 -f 11796 11797 11798 -f 11798 11797 11799 -f 11798 11799 11801 -f 11801 11799 11800 -f 11801 11800 11802 -f 11802 11800 11804 -f 11802 11804 11803 -f 11803 11804 11806 -f 11803 11806 11805 -f 11805 11806 11808 -f 11805 11808 11807 -f 11807 11808 11809 -f 11807 11809 11810 -f 11810 11809 11811 -f 11810 11811 11813 -f 11813 11811 11812 -f 11813 11812 11814 -f 11814 11812 11816 -f 11814 11816 11815 -f 11815 11816 11817 -f 11815 11817 11818 -f 11818 11817 11820 -f 11818 11820 11819 -f 11819 11820 11821 -f 11819 11821 11822 -f 11822 11821 11824 -f 11822 11824 11823 -f 11823 11824 11825 -f 11823 11825 11826 -f 11826 11825 11827 -f 11826 11827 11828 -f 11828 11827 11830 -f 11828 11830 11829 -f 11829 11830 11832 -f 11829 11832 11831 -f 11831 11832 11834 -f 11831 11834 11833 -f 11833 11834 11835 -f 11833 11835 11763 -f 11763 11835 11836 -f 11838 11837 11840 -f 11839 11838 11840 -f 11837 11839 11840 -f 11839 11841 11838 -f 11851 11861 11850 -f 11850 11861 11862 -f 11850 11862 11852 -f 11852 11862 11863 -f 11963 11970 11843 -f 11971 11972 11846 -f 11843 11905 11842 -f 11846 11844 11971 -f 11971 11844 11905 -f 11971 11905 11843 -f 11845 11855 11960 -f 11842 11962 11963 -f 11842 11963 11843 -f 11845 11960 11962 -f 11962 11868 11845 -f 11842 11868 11962 -f 11856 11958 11855 -f 11846 11972 11974 -f 11976 11849 11974 -f 11974 11849 11848 -f 11963 11854 11970 -f 11851 11966 11847 -f 11847 11966 11957 -f 11847 11957 11958 -f 11856 11847 11958 -f 11855 11958 11960 -f 11974 11848 11846 -f 11849 11976 11852 -f 11850 11853 11851 -f 11976 11853 11850 -f 11854 11963 11965 -f 11852 11976 11850 -f 11851 11853 11854 -f 11854 11965 11966 -f 11854 11966 11851 -f 11855 11865 11856 -f 11856 11865 11860 -f 11856 11860 11847 -f 11855 11845 11865 -f 11865 11845 11869 -f 11858 11857 11867 -f 11857 11866 11964 -f 11964 11867 11857 -f 11859 11858 11876 -f 11859 11876 11934 -f 11876 11858 11867 -f 11863 11975 11933 -f 11859 11973 11858 -f 11860 11968 11967 -f 11860 11967 11861 -f 11867 11964 11961 -f 11867 11961 11864 -f 11862 11861 11977 -f 11865 11869 11959 -f 11975 11863 11977 -f 11977 11863 11862 -f 11933 11975 11973 -f 11973 11932 11933 -f 11859 11932 11973 -f 11869 11864 11961 -f 11869 11961 11959 -f 11865 11959 11968 -f 11857 11969 11967 -f 11967 11969 11861 -f 11861 11969 11977 -f 11968 11860 11865 -f 11967 11866 11857 -f 11842 11867 11864 -f 11842 11864 11868 -f 11868 11864 11869 -f 11868 11869 11845 -f 11955 11870 11897 -f 11897 11870 11953 -f 11897 11953 11871 -f 11897 11871 11872 -f 11872 11871 11952 -f 11872 11952 11873 -f 11873 11952 11874 -f 11873 11874 11875 -f 11875 11874 11950 -f 11875 11950 11899 -f 11867 11842 11876 -f 11876 11842 11905 -f 11876 11905 11935 -f 11935 11905 11904 -f 11935 11904 11936 -f 11936 11904 11895 -f 11888 11877 11878 -f 11878 11877 11879 -f 11878 11879 11901 -f 11901 11879 11880 -f 11901 11880 11881 -f 11881 11880 11945 -f 11881 11945 11882 -f 11950 11883 11899 -f 11899 11883 11885 -f 11899 11885 11884 -f 11884 11885 11949 -f 11884 11949 11886 -f 11886 11949 11887 -f 11886 11887 11888 -f 11888 11887 11889 -f 11888 11889 11877 -f 11945 11943 11882 -f 11882 11943 11942 -f 11882 11942 11890 -f 11890 11942 11892 -f 11890 11892 11891 -f 11891 11892 11893 -f 11891 11893 11894 -f 11894 11893 11939 -f 11894 11939 11895 -f 11895 11939 11937 -f 11895 11937 11936 -f 11906 11897 11896 -f 11896 11897 11872 -f 11896 11872 11898 -f 11898 11872 11873 -f 11898 11873 11913 -f 11913 11873 11875 -f 11913 11875 11900 -f 11900 11875 11899 -f 11900 11899 11909 -f 11909 11899 11884 -f 11909 11884 11917 -f 11917 11884 11886 -f 11917 11886 11916 -f 11916 11886 11888 -f 11916 11888 11925 -f 11925 11888 11878 -f 11925 11878 11924 -f 11924 11878 11901 -f 11924 11901 11922 -f 11922 11901 11881 -f 11922 11881 11921 -f 11921 11881 11882 -f 11921 11882 11930 -f 11930 11882 11890 -f 11930 11890 11902 -f 11902 11890 11891 -f 11902 11891 11903 -f 11903 11891 11894 -f 11903 11894 11929 -f 11929 11894 11895 -f 11929 11895 11915 -f 11915 11895 11904 -f 11915 11904 11844 -f 11844 11904 11905 -f 11954 11956 11907 -f 11907 11956 11906 -f 11907 11906 11908 -f 11908 11906 11896 -f 11909 11910 11900 -f 11900 11910 11911 -f 11900 11911 11913 -f 11913 11911 11912 -f 11913 11912 11898 -f 11898 11912 11951 -f 11898 11951 11896 -f 11896 11951 11914 -f 11896 11914 11908 -f 11846 11859 11844 -f 11844 11859 11934 -f 11844 11934 11915 -f 11925 11947 11916 -f 11916 11947 11948 -f 11916 11948 11917 -f 11917 11948 11918 -f 11917 11918 11909 -f 11909 11918 11919 -f 11909 11919 11910 -f 11930 11944 11921 -f 11921 11944 11920 -f 11921 11920 11922 -f 11922 11920 11923 -f 11922 11923 11924 -f 11924 11923 11946 -f 11924 11946 11925 -f 11925 11946 11926 -f 11925 11926 11947 -f 11934 11927 11915 -f 11915 11927 11928 -f 11915 11928 11929 -f 11929 11928 11938 -f 11929 11938 11903 -f 11903 11938 11940 -f 11903 11940 11902 -f 11902 11940 11941 -f 11902 11941 11930 -f 11930 11941 11931 -f 11930 11931 11944 -f 11849 11933 11932 -f 11849 11932 11848 -f 11848 11932 11859 -f 11848 11859 11846 -f 11933 11849 11863 -f 11863 11849 11852 -f 11934 11876 11935 -f 11934 11935 11927 -f 11927 11935 11936 -f 11927 11936 11928 -f 11928 11936 11937 -f 11928 11937 11938 -f 11938 11937 11939 -f 11938 11939 11940 -f 11940 11939 11893 -f 11940 11893 11941 -f 11941 11893 11892 -f 11941 11892 11931 -f 11931 11892 11942 -f 11931 11942 11944 -f 11944 11942 11943 -f 11944 11943 11920 -f 11920 11943 11945 -f 11920 11945 11923 -f 11923 11945 11880 -f 11923 11880 11946 -f 11946 11880 11879 -f 11946 11879 11926 -f 11926 11879 11877 -f 11926 11877 11947 -f 11947 11877 11889 -f 11947 11889 11948 -f 11948 11889 11887 -f 11948 11887 11918 -f 11918 11887 11949 -f 11918 11949 11919 -f 11919 11949 11885 -f 11919 11885 11910 -f 11910 11885 11883 -f 11910 11883 11911 -f 11911 11883 11950 -f 11911 11950 11912 -f 11912 11950 11874 -f 11912 11874 11951 -f 11951 11874 11952 -f 11951 11952 11914 -f 11914 11952 11871 -f 11914 11871 11908 -f 11908 11871 11953 -f 11908 11953 11907 -f 11953 11870 11907 -f 11907 11870 11954 -f 11870 11955 11954 -f 11954 11955 11956 -f 11955 11897 11956 -f 11956 11897 11906 -f 11861 11851 11860 -f 11860 11851 11847 -f 11957 11968 11958 -f 11958 11968 11959 -f 11958 11959 11960 -f 11960 11959 11961 -f 11960 11961 11962 -f 11962 11961 11964 -f 11962 11964 11963 -f 11963 11964 11866 -f 11963 11866 11965 -f 11965 11866 11966 -f 11966 11866 11967 -f 11966 11967 11957 -f 11957 11967 11968 -f 11853 11969 11854 -f 11854 11969 11970 -f 11970 11969 11857 -f 11970 11857 11843 -f 11843 11857 11858 -f 11843 11858 11971 -f 11971 11858 11972 -f 11972 11858 11973 -f 11972 11973 11974 -f 11974 11973 11976 -f 11976 11973 11975 -f 11976 11975 11977 -f 11976 11977 11853 -f 11853 11977 11969 -f 12050 12049 12027 -f 11980 12049 11978 -f 12050 12027 11978 -f 11978 12023 11980 -f 11980 11979 12027 -f 12027 12049 11980 -f 11980 12023 11979 -f 11989 11981 11997 -f 11982 12045 12047 -f 12006 11996 11981 -f 11981 11989 11991 -f 11982 11986 11984 -f 11981 11985 12006 -f 11982 11993 11986 -f 11989 11997 11988 -f 11988 11997 11983 -f 11985 11992 12000 -f 11985 11981 11991 -f 11990 11991 11989 -f 11987 11988 11983 -f 11987 11983 11984 -f 11995 11984 11986 -f 12046 11993 11982 -f 11982 11987 12046 -f 11992 11985 11996 -f 11996 11985 11991 -f 11987 11984 11995 -f 11994 11986 11993 -f 11990 11989 11988 -f 12047 11987 11995 -f 11995 11986 11994 -f 11993 12046 12045 -f 12046 12044 12045 -f 11993 12045 11994 -f 11996 11991 11990 -f 11990 11988 11982 -f 11998 12000 11992 -f 11992 12006 11998 -f 12047 11995 11982 -f 11990 11982 11997 -f 11990 11997 11981 -f 11990 11981 11996 -f 11992 11996 12006 -f 11983 11995 11994 -f 12048 12047 12045 -f 11997 11982 11983 -f 11983 11982 11995 -f 11983 11994 11984 -f 11982 11984 11994 -f 11982 11994 12045 -f 12004 12008 12002 -f 12004 12002 12001 -f 11985 12000 12006 -f 12006 11999 12004 -f 12006 12004 11998 -f 12002 12003 12001 -f 12004 12001 11998 -f 12003 12008 12001 -f 12001 12008 11999 -f 11998 11999 12000 -f 12008 12007 12002 -f 12010 12022 12005 -f 12003 12017 12008 -f 12002 12007 12003 -f 12016 12005 12018 -f 12017 12018 12020 -f 12008 12004 11999 -f 11998 12001 11999 -f 12000 11999 12006 -f 12022 12025 12005 -f 12005 12025 12015 -f 12008 12017 12007 -f 12019 12026 12012 -f 12019 12012 12013 -f 12005 12015 12018 -f 12018 12015 12020 -f 12010 12005 12020 -f 12020 12005 12016 -f 12016 12018 12017 -f 12012 12014 12024 -f 12017 12020 12007 -f 12026 12033 12012 -f 12007 12020 12016 -f 12012 12033 12014 -f 12011 12022 12010 -f 12015 12025 12010 -f 12007 12016 12003 -f 12024 12014 12026 -f 12024 12026 12019 -f 12015 12010 12020 -f 12003 12016 12017 -f 12013 12009 12011 -f 12013 12012 12024 -f 12013 12024 12009 -f 12022 12013 12025 -f 12034 12028 12033 -f 12014 12035 12026 -f 12033 12028 12014 -f 12009 12024 12019 -f 12011 12019 12022 -f 12009 12019 12011 -f 12022 12019 12013 -f 12013 12011 12025 -f 12032 12023 12021 -f 12025 12011 12010 -f 12023 12039 12031 -f 12023 12031 12021 -f 11979 12037 12029 -f 12021 12027 12040 -f 12034 12038 12028 -f 12041 12034 12035 -f 12039 12030 12029 -f 12027 12032 12040 -f 12032 12038 12041 -f 12036 12027 11979 -f 12027 12023 12032 -f 12039 12029 12037 -f 12039 12037 12031 -f 12021 12031 12027 -f 12032 12021 12038 -f 12035 12034 12033 -f 12031 11978 12027 -f 12038 12021 12040 -f 12038 12040 12028 -f 12030 12037 12036 -f 12031 12037 12030 -f 12031 12030 11978 -f 12030 12036 12029 -f 11979 12023 12037 -f 11978 12030 12039 -f 12037 12023 12027 -f 11978 12039 12023 -f 12014 12028 12035 -f 12026 12035 12033 -f 12037 12027 12036 -f 12041 12038 12034 -f 12029 12036 11979 -f 12028 12040 12032 -f 12028 12032 12041 -f 12035 12028 12041 -f 11987 11982 11988 -f 12042 11987 12047 -f 12042 12047 12043 -f 12043 12047 12048 -f 12048 12045 12044 -f 12046 12042 12044 -f 12046 11987 12042 -f 12048 12044 12042 -f 12048 12042 12043 -f 12050 11978 12049 -f 12075 12105 12090 -f 12090 12105 12104 -f 12052 12054 12093 -f 12093 12054 12099 -f 12055 12097 12101 -f 12055 12101 12051 -f 12051 12101 12099 -f 12051 12099 12054 -f 12055 12058 12097 -f 12097 12058 12096 -f 12052 12074 12053 -f 12052 12053 12060 -f 12052 12060 12054 -f 12051 12060 12056 -f 12056 12055 12051 -f 12054 12060 12051 -f 12055 12056 12059 -f 12055 12059 12058 -f 12058 12059 12057 -f 12057 12091 12058 -f 12060 12098 12056 -f 12056 12098 12102 -f 12056 12102 12103 -f 12056 12103 12059 -f 12059 12103 12057 -f 12057 12103 12091 -f 12060 12053 12098 -f 12098 12053 12089 -f 12074 12061 12089 -f 12074 12089 12053 -f 12072 12070 12079 -f 12070 12071 12062 -f 12062 12080 12070 -f 12080 12079 12070 -f 12063 12071 12069 -f 12063 12069 12080 -f 12084 12066 12085 -f 12085 12066 12092 -f 12065 12080 12064 -f 12065 12079 12080 -f 12079 12065 12081 -f 12081 12065 12092 -f 12081 12092 12066 -f 12080 12069 12064 -f 12064 12069 12068 -f 12067 12068 12070 -f 12070 12068 12069 -f 12069 12071 12070 -f 12070 12072 12067 -f 12067 12072 12073 -f 12093 12073 12052 -f 12052 12073 12072 -f 12052 12072 12074 -f 12074 12072 12077 -f 12074 12077 12061 -f 12061 12077 12076 -f 12076 12078 12095 -f 12075 12090 12095 -f 12095 12078 12075 -f 12078 12076 12077 -f 12078 12077 12072 -f 12078 12072 12079 -f 12083 12075 12078 -f 12079 12081 12078 -f 12078 12081 12083 -f 12062 12063 12080 -f 12066 12084 12081 -f 12086 12083 12084 -f 12083 12081 12084 -f 12087 12083 12086 -f 12075 12083 12082 -f 12075 12082 12088 -f 12084 12085 12086 -f 12087 12086 12085 -f 12083 12087 12094 -f 12088 12083 12094 -f 12088 12082 12083 -f 12068 12067 12064 -f 12064 12067 12073 -f 12065 12064 12073 -f 12093 12089 12061 -f 12098 12089 12093 -f 12088 12090 12126 -f 12126 12090 12104 -f 12061 12085 12093 -f 12093 12085 12092 -f 12093 12092 12073 -f 12073 12092 12065 -f 12090 12088 12094 -f 12090 12094 12095 -f 12095 12094 12087 -f 12095 12087 12076 -f 12096 12091 12103 -f 12096 12103 12097 -f 12098 12093 12099 -f 12076 12087 12085 -f 12076 12085 12061 -f 12104 12100 12126 -f 12099 12101 12098 -f 12098 12101 12102 -f 12126 12100 12141 -f 12102 12101 12097 -f 12097 12103 12102 -f 12130 12141 12100 -f 12130 12100 12105 -f 12105 12100 12104 -f 12111 12138 12121 -f 12121 12138 12117 -f 12121 12117 12123 -f 12109 12115 12134 -f 12109 12134 12110 -f 12110 12134 12133 -f 12106 12116 12113 -f 12106 12113 12107 -f 12107 12113 12112 -f 12107 12112 12108 -f 12108 12112 12109 -f 12108 12109 12110 -f 12115 12109 12112 -f 12115 12112 12113 -f 12114 12123 12115 -f 12114 12115 12113 -f 12114 12113 12116 -f 12117 12120 12140 -f 12140 12120 12119 -f 12176 12118 12120 -f 12117 12111 12121 -f 12122 12120 12117 -f 12117 12121 12122 -f 12122 12121 12123 -f 12122 12123 12114 -f 12114 12116 12125 -f 12126 12128 12124 -f 12125 12116 12126 -f 12126 12116 12106 -f 12126 12106 12128 -f 12122 12114 12125 -f 12124 12129 12127 -f 12108 12110 12107 -f 12107 12110 12133 -f 12128 12132 12129 -f 12128 12129 12124 -f 12106 12107 12128 -f 12128 12107 12132 -f 12107 12133 12135 -f 12132 12131 12129 -f 12129 12131 12130 -f 12132 12107 12135 -f 12131 12132 12135 -f 12131 12135 12142 -f 12133 12134 12135 -f 12135 12134 12139 -f 12135 12139 12137 -f 12135 12137 12136 -f 12135 12136 12142 -f 12136 12137 12115 -f 12137 12139 12115 -f 12139 12134 12115 -f 12115 12123 12117 -f 12115 12117 12140 -f 12136 12115 12140 -f 12143 12140 12119 -f 12130 12131 12141 -f 12141 12131 12142 -f 12141 12142 12143 -f 12143 12142 12136 -f 12143 12136 12140 -f 12189 12152 12155 -f 12187 12149 12154 -f 12187 12154 12186 -f 12186 12154 12153 -f 12186 12153 12189 -f 12189 12153 12152 -f 12146 12148 12187 -f 12187 12148 12149 -f 12145 12144 12148 -f 12145 12148 12146 -f 12148 12144 12147 -f 12152 12153 12150 -f 12149 12148 12147 -f 12149 12147 12159 -f 12150 12153 12156 -f 12159 12151 12149 -f 12149 12151 12154 -f 12156 12153 12154 -f 12154 12151 12156 -f 12155 12150 12157 -f 12157 12150 12156 -f 12157 12156 12158 -f 12158 12156 12151 -f 12158 12151 12185 -f 12185 12151 12159 -f 12185 12159 12179 -f 12179 12159 12147 -f 12160 12161 12175 -f 12162 12160 12163 -f 12200 12174 12197 -f 12197 12174 12161 -f 12197 12161 12164 -f 12167 12174 12201 -f 12167 12201 12165 -f 12174 12167 12172 -f 12166 12201 12167 -f 12167 12201 12173 -f 12173 12201 12171 -f 12181 12168 12192 -f 12192 12168 12198 -f 12169 12171 12201 -f 12169 12201 12182 -f 12182 12201 12200 -f 12200 12168 12182 -f 12168 12181 12182 -f 12170 12173 12169 -f 12169 12173 12171 -f 12167 12178 12172 -f 12170 12178 12173 -f 12173 12178 12167 -f 12180 12174 12178 -f 12178 12174 12172 -f 12144 12145 12183 -f 12174 12180 12179 -f 12179 12147 12174 -f 12174 12147 12144 -f 12174 12144 12161 -f 12161 12144 12183 -f 12160 12190 12163 -f 12190 12160 12184 -f 12184 12160 12175 -f 12184 12175 12183 -f 12161 12183 12175 -f 12188 12176 12190 -f 12190 12176 12163 -f 12119 12120 12143 -f 12143 12120 12177 -f 12120 12118 12177 -f 12177 12118 12188 -f 12176 12188 12118 -f 12178 12170 12180 -f 12180 12170 12169 -f 12180 12182 12181 -f 12180 12181 12179 -f 12179 12181 12192 -f 12179 12192 12145 -f 12169 12182 12180 -f 12192 12183 12145 -f 12145 12146 12179 -f 12192 12194 12183 -f 12183 12194 12184 -f 12184 12194 12196 -f 12184 12196 12190 -f 12179 12146 12187 -f 12179 12187 12185 -f 12186 12158 12187 -f 12187 12158 12185 -f 12125 12143 12177 -f 12186 12157 12158 -f 12125 12177 12188 -f 12157 12186 12155 -f 12155 12186 12189 -f 12190 12196 12191 -f 12190 12191 12188 -f 12188 12191 12125 -f 12198 12193 12192 -f 12192 12193 12194 -f 12194 12193 12197 -f 12194 12197 12196 -f 12196 12195 12191 -f 12199 12191 12195 -f 12195 12196 12197 -f 12200 12197 12193 -f 12200 12193 12168 -f 12168 12193 12198 -f 12201 12166 12165 -f 12200 12201 12174 -f 12235 12223 12210 -f 12210 12223 12202 -f 12233 12204 12227 -f 12227 12204 12213 -f 12227 12213 12228 -f 12228 12213 12212 -f 12228 12212 12202 -f 12202 12212 12210 -f 12221 12203 12233 -f 12233 12203 12204 -f 12205 12220 12235 -f 12235 12220 12218 -f 12235 12218 12206 -f 12235 12206 12240 -f 12240 12206 12207 -f 12240 12207 12208 -f 12210 12209 12211 -f 12210 12211 12235 -f 12215 12213 12204 -f 12209 12210 12212 -f 12235 12211 12205 -f 12203 12205 12214 -f 12209 12212 12213 -f 12209 12213 12215 -f 12211 12214 12205 -f 12204 12203 12215 -f 12215 12203 12214 -f 12216 12207 12206 -f 12216 12206 12217 -f 12217 12206 12218 -f 12217 12218 12219 -f 12219 12218 12220 -f 12219 12220 12226 -f 12226 12220 12205 -f 12226 12205 12232 -f 12232 12205 12221 -f 12221 12205 12203 -f 12222 12229 12223 -f 12222 12223 12224 -f 12229 12225 12223 -f 12223 12225 12202 -f 12219 12226 12230 -f 12234 12228 12225 -f 12233 12227 12234 -f 12234 12227 12228 -f 12221 12234 12231 -f 12232 12230 12226 -f 12222 12216 12229 -f 12229 12216 12217 -f 12229 12217 12230 -f 12230 12217 12219 -f 12202 12225 12228 -f 12221 12231 12232 -f 12232 12231 12230 -f 12234 12221 12233 -f 12223 12235 12224 -f 12224 12235 12240 -f 12224 12240 12239 -f 12236 12237 12241 -f 12241 12237 12248 -f 12240 12241 12238 -f 12238 12239 12240 -f 12248 12238 12241 -f 12272 12247 12246 -f 12272 12246 12274 -f 12274 12246 12245 -f 12274 12245 12262 -f 12262 12245 12242 -f 12262 12242 12260 -f 12260 12242 12243 -f 12243 12242 12244 -f 12243 12244 12268 -f 12268 12244 12257 -f 12268 12257 12266 -f 12266 12257 12255 -f 12266 12255 12259 -f 12259 12255 12252 -f 12244 12242 12237 -f 12237 12242 12245 -f 12237 12245 12246 -f 12237 12246 12248 -f 12248 12246 12247 -f 12248 12247 12249 -f 12253 12252 12256 -f 12250 12253 12251 -f 12250 12251 12237 -f 12253 12250 12258 -f 12237 12251 12244 -f 12257 12244 12254 -f 12256 12252 12255 -f 12253 12258 12252 -f 12251 12254 12244 -f 12256 12255 12257 -f 12256 12257 12254 -f 12259 12252 12269 -f 12269 12252 12258 -f 12269 12258 12263 -f 12263 12258 12250 -f 12237 12236 12250 -f 12250 12236 12263 -f 12271 12273 12236 -f 12271 12236 12241 -f 12273 12264 12236 -f 12236 12264 12263 -f 12268 12261 12243 -f 12243 12261 12260 -f 12260 12261 12262 -f 12263 12264 12270 -f 12265 12259 12269 -f 12265 12269 12270 -f 12265 12266 12259 -f 12266 12265 12267 -f 12266 12267 12268 -f 12268 12267 12261 -f 12270 12269 12263 -f 12271 12272 12273 -f 12273 12272 12274 -f 12273 12274 12261 -f 12261 12274 12262 -f 12321 12276 12325 -f 12325 12276 12275 -f 12276 12277 12275 -f 12275 12277 12326 -f 12276 12321 12277 -f 12277 12321 12278 -f 12331 12279 12278 -f 12278 12279 12280 -f 12280 12330 12278 -f 12278 12330 12281 -f 12278 12281 12277 -f 12282 12334 12347 -f 12347 12334 12283 -f 12347 12283 12336 -f 12347 12336 12285 -f 12336 12284 12285 -f 12285 12284 12304 -f 12285 12304 12286 -f 12286 12304 12317 -f 12289 12348 12286 -f 12286 12348 12285 -f 12289 12286 12291 -f 12287 12288 12289 -f 12293 12297 12292 -f 12288 12290 12289 -f 12289 12290 12296 -f 12292 12300 12320 -f 12289 12291 12295 -f 12293 12292 12320 -f 12287 12289 12294 -f 12294 12289 12295 -f 12294 12295 12299 -f 12289 12296 12293 -f 12293 12296 12297 -f 12302 12298 12295 -f 12295 12298 12299 -f 12320 12300 12301 -f 12320 12301 12295 -f 12295 12301 12302 -f 12291 12286 12317 -f 12319 12306 12304 -f 12304 12306 12305 -f 12319 12312 12306 -f 12313 12307 12317 -f 12315 12309 12308 -f 12308 12309 12310 -f 12308 12310 12311 -f 12308 12311 12319 -f 12319 12311 12312 -f 12304 12305 12313 -f 12304 12313 12317 -f 12307 12314 12317 -f 12317 12314 12316 -f 12308 12303 12315 -f 12315 12303 12316 -f 12316 12303 12317 -f 12317 12303 12291 -f 12308 12319 12333 -f 12333 12319 12318 -f 12293 12304 12346 -f 12346 12304 12284 -f 12346 12284 12350 -f 12350 12284 12318 -f 12350 12318 12320 -f 12320 12318 12319 -f 12320 12319 12293 -f 12293 12319 12304 -f 12323 12352 12350 -f 12323 12350 12278 -f 12278 12350 12320 -f 12278 12320 12295 -f 12321 12325 12278 -f 12278 12325 12323 -f 12325 12275 12326 -f 12322 12329 12323 -f 12323 12329 12328 -f 12323 12328 12324 -f 12325 12326 12323 -f 12323 12326 12327 -f 12323 12327 12322 -f 12331 12324 12328 -f 12331 12328 12279 -f 12279 12328 12329 -f 12279 12329 12280 -f 12280 12329 12322 -f 12280 12322 12330 -f 12330 12322 12327 -f 12330 12327 12281 -f 12281 12327 12326 -f 12281 12326 12277 -f 12331 12278 12295 -f 12334 12282 12333 -f 12333 12282 12352 -f 12291 12303 12295 -f 12295 12303 12308 -f 12295 12308 12331 -f 12331 12308 12333 -f 12331 12333 12324 -f 12324 12333 12352 -f 12324 12352 12323 -f 12284 12341 12332 -f 12284 12332 12318 -f 12318 12332 12339 -f 12318 12339 12333 -f 12333 12339 12338 -f 12345 12343 12336 -f 12336 12343 12284 -f 12284 12343 12341 -f 12335 12334 12333 -f 12335 12333 12338 -f 12283 12334 12335 -f 12283 12335 12336 -f 12336 12335 12345 -f 12344 12335 12337 -f 12337 12335 12338 -f 12337 12338 12351 -f 12351 12338 12339 -f 12351 12339 12332 -f 12351 12332 12340 -f 12340 12332 12341 -f 12340 12341 12349 -f 12349 12341 12342 -f 12342 12341 12343 -f 12342 12343 12345 -f 12342 12345 12344 -f 12344 12345 12335 -f 12282 12347 12348 -f 12350 12340 12346 -f 12348 12347 12285 -f 12346 12340 12349 -f 12351 12340 12350 -f 12346 12349 12342 -f 12352 12337 12351 -f 12352 12351 12350 -f 12342 12352 12282 -f 12342 12282 12348 -f 12342 12348 12346 -f 12342 12344 12352 -f 12352 12344 12337 -f 12289 12293 12348 -f 12348 12293 12346 -f 12487 12353 12568 -f 12568 12353 12554 -f 12554 12353 12354 -f 12554 12354 12355 -f 12355 12354 12502 -f 12355 12502 12553 -f 12502 12515 12553 -f 12553 12515 12356 -f 12493 12548 12536 -f 12493 12536 12526 -f 12526 12536 12537 -f 12526 12537 12357 -f 12357 12537 12524 -f 12524 12537 12356 -f 12524 12356 12515 -f 12493 12494 12548 -f 12548 12494 12358 -f 12496 12561 12358 -f 12496 12358 12494 -f 12496 12528 12561 -f 12561 12528 12359 -f 12521 12360 12528 -f 12528 12360 12359 -f 12361 12546 12563 -f 12361 12563 12521 -f 12521 12563 12565 -f 12521 12565 12360 -f 12381 12590 12575 -f 12381 12575 12363 -f 12568 12377 12362 -f 12568 12362 12569 -f 12569 12362 12380 -f 12569 12380 12363 -f 12363 12380 12381 -f 12392 12371 12393 -f 12393 12371 12589 -f 12393 12589 12394 -f 12394 12589 12364 -f 12394 12364 12365 -f 12365 12364 12366 -f 12365 12366 12395 -f 12395 12366 12367 -f 12395 12367 12383 -f 12383 12367 12574 -f 12368 12583 12390 -f 12390 12583 12582 -f 12390 12582 12388 -f 12388 12582 12389 -f 12389 12582 12581 -f 12389 12581 12369 -f 12369 12581 12580 -f 12369 12580 12370 -f 12370 12580 12371 -f 12370 12371 12392 -f 12368 12372 12583 -f 12583 12372 12373 -f 12373 12372 12585 -f 12585 12372 12386 -f 12585 12386 12586 -f 12586 12386 12587 -f 12587 12386 12374 -f 12587 12374 12375 -f 12587 12375 12376 -f 12376 12375 12391 -f 12376 12391 12579 -f 12579 12391 12578 -f 12381 12380 12379 -f 12542 12443 12377 -f 12377 12443 12378 -f 12377 12378 12404 -f 12377 12404 12405 -f 12379 12380 12405 -f 12380 12362 12405 -f 12405 12362 12377 -f 12385 12383 12590 -f 12406 12381 12379 -f 12382 12384 12381 -f 12382 12403 12384 -f 12381 12406 12382 -f 12382 12406 12403 -f 12396 12383 12402 -f 12402 12383 12384 -f 12384 12383 12385 -f 12384 12385 12381 -f 12381 12385 12590 -f 12369 12370 12375 -f 12375 12370 12391 -f 12369 12375 12374 -f 12369 12374 12389 -f 12387 12374 12386 -f 12386 12372 12387 -f 12387 12372 12368 -f 12387 12368 12388 -f 12374 12387 12389 -f 12389 12387 12388 -f 12368 12390 12388 -f 12391 12370 12392 -f 12391 12392 12401 -f 12401 12392 12393 -f 12401 12393 12399 -f 12399 12393 12394 -f 12399 12394 12398 -f 12398 12394 12365 -f 12398 12365 12396 -f 12396 12365 12395 -f 12396 12395 12383 -f 12402 12576 12396 -f 12396 12576 12577 -f 12396 12577 12398 -f 12398 12577 12397 -f 12398 12397 12399 -f 12399 12397 12400 -f 12399 12400 12401 -f 12401 12400 12588 -f 12401 12588 12391 -f 12391 12588 12578 -f 12576 12402 12384 -f 12576 12384 12403 -f 12378 12417 12572 -f 12378 12572 12404 -f 12404 12572 12570 -f 12404 12570 12405 -f 12405 12570 12379 -f 12379 12570 12573 -f 12407 12406 12573 -f 12573 12406 12379 -f 12407 12403 12406 -f 12378 12443 12417 -f 12571 12417 12484 -f 12484 12417 12456 -f 12415 12481 12445 -f 12445 12481 12451 -f 12461 12408 12409 -f 12461 12409 12460 -f 12460 12409 12531 -f 12461 12410 12450 -f 12450 12410 12469 -f 12450 12469 12432 -f 12469 12411 12432 -f 12432 12411 12412 -f 12412 12411 12457 -f 12412 12457 12441 -f 12457 12465 12441 -f 12441 12465 12439 -f 12439 12465 12476 -f 12439 12476 12413 -f 12413 12476 12436 -f 12436 12476 12414 -f 12436 12414 12415 -f 12436 12415 12445 -f 12416 12434 12421 -f 12450 12432 12442 -f 12418 12417 12443 -f 12418 12443 12447 -f 12591 12456 12418 -f 12418 12456 12417 -f 12422 12419 12420 -f 12416 12421 12422 -f 12422 12421 12423 -f 12422 12423 12419 -f 12429 12424 12419 -f 12419 12424 12420 -f 12412 12431 12432 -f 12426 12425 12427 -f 12426 12427 12448 -f 12427 12429 12448 -f 12408 12461 12443 -f 12419 12428 12429 -f 12429 12428 12430 -f 12429 12430 12448 -f 12448 12430 12446 -f 12432 12431 12442 -f 12591 12433 12456 -f 12456 12433 12455 -f 12416 12435 12434 -f 12434 12435 12451 -f 12434 12451 12433 -f 12433 12451 12455 -f 12436 12444 12438 -f 12438 12413 12436 -f 12438 12439 12413 -f 12435 12437 12451 -f 12451 12437 12452 -f 12439 12438 12440 -f 12439 12440 12441 -f 12441 12440 12431 -f 12449 12450 12442 -f 12454 12444 12445 -f 12445 12444 12436 -f 12431 12412 12441 -f 12446 12447 12448 -f 12448 12447 12443 -f 12448 12443 12449 -f 12449 12443 12461 -f 12449 12461 12450 -f 12451 12452 12453 -f 12451 12453 12445 -f 12445 12453 12454 -f 12454 12453 12425 -f 12454 12425 12426 -f 12451 12481 12479 -f 12451 12479 12455 -f 12455 12479 12484 -f 12484 12456 12455 -f 12466 12465 12457 -f 12466 12457 12475 -f 12478 12462 12463 -f 12415 12463 12458 -f 12459 12460 12486 -f 12468 12460 12467 -f 12460 12468 12470 -f 12463 12462 12464 -f 12463 12464 12459 -f 12459 12464 12483 -f 12468 12467 12473 -f 12473 12467 12471 -f 12469 12410 12474 -f 12474 12410 12470 -f 12476 12465 12471 -f 12471 12477 12415 -f 12460 12472 12467 -f 12465 12466 12473 -f 12465 12473 12471 -f 12460 12470 12410 -f 12460 12410 12461 -f 12469 12474 12411 -f 12411 12474 12475 -f 12411 12475 12457 -f 12471 12414 12476 -f 12415 12477 12478 -f 12415 12478 12463 -f 12458 12482 12415 -f 12415 12482 12481 -f 12484 12479 12480 -f 12480 12479 12481 -f 12480 12481 12482 -f 12459 12483 12460 -f 12460 12483 12472 -f 12471 12415 12414 -f 12484 12480 12485 -f 12484 12485 12571 -f 12571 12485 12486 -f 12571 12486 12460 -f 12529 12500 12530 -f 12530 12500 12487 -f 12530 12487 12488 -f 12488 12487 12571 -f 12488 12571 12531 -f 12531 12571 12460 -f 12527 12489 12500 -f 12490 12487 12497 -f 12501 12353 12490 -f 12490 12353 12487 -f 12500 12489 12498 -f 12500 12498 12487 -f 12504 12505 12491 -f 12492 12499 12493 -f 12493 12499 12494 -f 12494 12499 12495 -f 12495 12496 12494 -f 12520 12497 12514 -f 12514 12497 12487 -f 12514 12487 12498 -f 12503 12516 12502 -f 12353 12501 12354 -f 12504 12502 12501 -f 12501 12502 12354 -f 12504 12491 12502 -f 12502 12491 12503 -f 12507 12492 12525 -f 12504 12506 12505 -f 12507 12525 12508 -f 12507 12508 12514 -f 12509 12513 12510 -f 12505 12506 12512 -f 12505 12512 12511 -f 12511 12512 12513 -f 12508 12510 12514 -f 12502 12516 12515 -f 12515 12516 12522 -f 12492 12493 12525 -f 12509 12517 12513 -f 12513 12517 12511 -f 12513 12518 12510 -f 12510 12518 12519 -f 12510 12519 12514 -f 12514 12519 12520 -f 12500 12361 12521 -f 12500 12521 12527 -f 12522 12523 12515 -f 12515 12523 12524 -f 12524 12523 12525 -f 12524 12525 12357 -f 12493 12526 12525 -f 12525 12526 12357 -f 12527 12496 12495 -f 12527 12528 12496 -f 12521 12528 12527 -f 12500 12529 12361 -f 12361 12529 12534 -f 12361 12534 12546 -f 12546 12534 12544 -f 12529 12530 12534 -f 12534 12530 12533 -f 12530 12488 12533 -f 12533 12488 12532 -f 12488 12531 12532 -f 12532 12531 12409 -f 12409 12408 12532 -f 12532 12408 12443 -f 12532 12443 12533 -f 12533 12443 12542 -f 12533 12542 12534 -f 12534 12542 12544 -f 12546 12544 12535 -f 12535 12544 12545 -f 12356 12541 12538 -f 12540 12537 12536 -f 12356 12538 12553 -f 12553 12538 12551 -f 12554 12549 12568 -f 12568 12549 12539 -f 12568 12539 12542 -f 12536 12548 12540 -f 12550 12552 12553 -f 12542 12539 12543 -f 12542 12543 12544 -f 12544 12543 12545 -f 12547 12546 12535 -f 12557 12548 12358 -f 12557 12358 12560 -f 12549 12554 12552 -f 12541 12356 12540 -f 12540 12356 12537 -f 12555 12550 12553 -f 12555 12553 12551 -f 12553 12552 12355 -f 12355 12552 12554 -f 12550 12555 12556 -f 12550 12556 12547 -f 12547 12556 12562 -f 12547 12563 12546 -f 12548 12557 12558 -f 12548 12558 12540 -f 12559 12566 12567 -f 12359 12559 12561 -f 12561 12559 12560 -f 12561 12560 12358 -f 12547 12562 12563 -f 12563 12562 12564 -f 12563 12564 12566 -f 12563 12566 12565 -f 12566 12559 12359 -f 12566 12359 12565 -f 12558 12567 12540 -f 12540 12567 12566 -f 12359 12360 12565 -f 12542 12377 12568 -f 12487 12568 12569 -f 12487 12569 12571 -f 12573 12569 12363 -f 12569 12573 12570 -f 12569 12570 12571 -f 12570 12572 12571 -f 12571 12572 12417 -f 12363 12407 12573 -f 12575 12590 12574 -f 12363 12575 12576 -f 12403 12407 12576 -f 12576 12407 12363 -f 12576 12575 12574 -f 12576 12574 12577 -f 12578 12589 12371 -f 12578 12371 12579 -f 12371 12580 12579 -f 12579 12580 12581 -f 12581 12587 12376 -f 12581 12376 12579 -f 12582 12583 12584 -f 12584 12583 12373 -f 12584 12373 12586 -f 12586 12587 12584 -f 12584 12587 12581 -f 12584 12581 12582 -f 12373 12585 12586 -f 12578 12588 12589 -f 12589 12588 12400 -f 12589 12400 12364 -f 12364 12400 12397 -f 12364 12397 12366 -f 12366 12397 12577 -f 12366 12577 12367 -f 12367 12577 12574 -f 12383 12574 12590 -f 12591 12630 12592 -f 12592 12630 12629 -f 12592 12629 12593 -f 12593 12629 12594 -f 12593 12594 12595 -f 12595 12594 12596 -f 12595 12596 12597 -f 12597 12596 12632 -f 12597 12632 12598 -f 12598 12632 12631 -f 12598 12631 12599 -f 12599 12631 12633 -f 12599 12633 12600 -f 12600 12633 12602 -f 12600 12602 12601 -f 12601 12602 12603 -f 12601 12603 12604 -f 12604 12603 12605 -f 12604 12605 12606 -f 12606 12605 12607 -f 12606 12607 12608 -f 12608 12607 12634 -f 12608 12634 12609 -f 12609 12634 12610 -f 12609 12610 12423 -f 12423 12610 12635 -f 12423 12635 12611 -f 12611 12635 12612 -f 12611 12612 12613 -f 12613 12612 12614 -f 12613 12614 12615 -f 12615 12614 12616 -f 12615 12616 12617 -f 12617 12616 12637 -f 12617 12637 12618 -f 12618 12637 12636 -f 12618 12636 12619 -f 12619 12636 12640 -f 12619 12640 12620 -f 12620 12640 12639 -f 12620 12639 12621 -f 12621 12639 12638 -f 12621 12638 12622 -f 12622 12638 12623 -f 12622 12623 12625 -f 12625 12623 12624 -f 12625 12624 12626 -f 12626 12624 12641 -f 12626 12641 12627 -f 12627 12641 12628 -f 12627 12628 12591 -f 12591 12628 12630 -f 12628 12641 12636 -f 12628 12636 12630 -f 12596 12594 12636 -f 12636 12594 12629 -f 12636 12629 12630 -f 12633 12631 12636 -f 12636 12631 12632 -f 12636 12632 12596 -f 12605 12603 12636 -f 12636 12603 12602 -f 12636 12602 12633 -f 12610 12634 12636 -f 12636 12634 12607 -f 12636 12607 12605 -f 12614 12612 12636 -f 12636 12612 12635 -f 12636 12635 12610 -f 12636 12637 12616 -f 12636 12616 12614 -f 12638 12639 12636 -f 12636 12639 12640 -f 12641 12624 12636 -f 12636 12624 12623 -f 12636 12623 12638 -f 12649 12665 12642 -f 12642 12665 12666 -f 12642 12666 12644 -f 12644 12666 12643 -f 12649 12654 12665 -f 12665 12654 12646 -f 12645 12671 12646 -f 12645 12646 12654 -f 12645 12654 12647 -f 12645 12647 12648 -f 12645 12648 12651 -f 12656 12653 12642 -f 12642 12653 12649 -f 12650 12652 12651 -f 12650 12651 12648 -f 12652 12650 12655 -f 12649 12653 12654 -f 12654 12653 12647 -f 12652 12655 12644 -f 12655 12656 12644 -f 12656 12642 12644 -f 12763 12756 12657 -f 12657 12756 12736 -f 12766 12763 12720 -f 12720 12763 12657 -f 12758 12766 12711 -f 12711 12766 12720 -f 12758 12711 12751 -f 12751 12711 12658 -f 12751 12658 12659 -f 12751 12659 12746 -f 12746 12659 12660 -f 12746 12660 12757 -f 12757 12660 12661 -f 12661 12660 12662 -f 12661 12662 12667 -f 12644 12643 12652 -f 12652 12643 12667 -f 12652 12667 12662 -f 12664 12665 12663 -f 12663 12665 12646 -f 12669 12643 12666 -f 12670 12667 12669 -f 12646 12671 12663 -f 12669 12666 12664 -f 12664 12666 12665 -f 12643 12669 12667 -f 12667 12670 12752 -f 12752 12670 12668 -f 12752 12668 12671 -f 12671 12668 12663 -f 12672 12692 12685 -f 12672 12685 12679 -f 12672 12681 12692 -f 12692 12681 12690 -f 12676 12673 12683 -f 12683 12673 12695 -f 12683 12695 12690 -f 12683 12690 12681 -f 12677 12674 12675 -f 12680 12676 12683 -f 12676 12680 12675 -f 12676 12675 12674 -f 12674 12677 12709 -f 12709 12677 12678 -f 12672 12679 12682 -f 12680 12681 12682 -f 12682 12681 12672 -f 12680 12683 12681 -f 12709 12678 12679 -f 12679 12678 12682 -f 12671 12645 12752 -f 12752 12645 12651 -f 12752 12651 12686 -f 12686 12651 12709 -f 12686 12709 12685 -f 12685 12709 12679 -f 12684 12685 12692 -f 12685 12684 12687 -f 12685 12687 12686 -f 12694 12691 12690 -f 12686 12687 12688 -f 12686 12688 12689 -f 12689 12688 12693 -f 12694 12690 12695 -f 12690 12691 12692 -f 12692 12691 12684 -f 12689 12693 12673 -f 12693 12694 12673 -f 12694 12695 12673 -f 12673 12676 12689 -f 12689 12676 12674 -f 12689 12674 12708 -f 12689 12708 12747 -f 12747 12708 12696 -f 12747 12696 12759 -f 12759 12696 12697 -f 12759 12697 12699 -f 12699 12697 12712 -f 12699 12712 12698 -f 12699 12698 12700 -f 12700 12698 12765 -f 12765 12698 12719 -f 12750 12765 12717 -f 12717 12765 12719 -f 12701 12750 12713 -f 12713 12750 12717 -f 12702 12707 12716 -f 12702 12716 12703 -f 12703 12716 12704 -f 12703 12704 12748 -f 12748 12704 12715 -f 12748 12715 12764 -f 12764 12715 12705 -f 12705 12715 12706 -f 12705 12706 12761 -f 12761 12706 12714 -f 12761 12714 12722 -f 12761 12722 12760 -f 12760 12722 12753 -f 12753 12722 12718 -f 12753 12718 12749 -f 12749 12718 12707 -f 12749 12707 12702 -f 12708 12674 12709 -f 12651 12696 12709 -f 12709 12696 12708 -f 12652 12662 12651 -f 12651 12662 12660 -f 12651 12660 12736 -f 12736 12660 12659 -f 12776 12711 12720 -f 12776 12720 12778 -f 12724 12698 12736 -f 12736 12698 12712 -f 12736 12712 12651 -f 12651 12712 12697 -f 12719 12715 12717 -f 12717 12715 12704 -f 12713 12707 12718 -f 12736 12659 12658 -f 12736 12769 12657 -f 12657 12769 12768 -f 12651 12697 12696 -f 12719 12714 12706 -f 12719 12706 12715 -f 12704 12716 12717 -f 12717 12716 12707 -f 12717 12707 12713 -f 12724 12713 12698 -f 12698 12713 12722 -f 12698 12722 12719 -f 12719 12722 12714 -f 12658 12710 12736 -f 12736 12710 12769 -f 12768 12721 12657 -f 12657 12721 12720 -f 12720 12721 12778 -f 12718 12722 12713 -f 12776 12773 12711 -f 12658 12723 12710 -f 12711 12773 12723 -f 12711 12723 12658 -f 12739 12701 12724 -f 12724 12701 12713 -f 12725 12743 12735 -f 12735 12743 12738 -f 12725 12735 12727 -f 12727 12735 12726 -f 12727 12726 12729 -f 12729 12726 12733 -f 12728 12729 12730 -f 12730 12729 12733 -f 12741 12728 12731 -f 12731 12728 12730 -f 12756 12732 12755 -f 12726 12734 12733 -f 12732 12735 12738 -f 12731 12730 12734 -f 12734 12730 12733 -f 12735 12732 12726 -f 12726 12732 12734 -f 12738 12737 12732 -f 12732 12737 12755 -f 12745 12736 12755 -f 12745 12755 12737 -f 12745 12737 12744 -f 12744 12737 12738 -f 12744 12738 12743 -f 12754 12739 12745 -f 12745 12739 12724 -f 12745 12724 12736 -f 12755 12736 12756 -f 12729 12728 12741 -f 12741 12742 12729 -f 12729 12742 12727 -f 12727 12742 12754 -f 12727 12754 12725 -f 12725 12754 12743 -f 12743 12754 12744 -f 12744 12754 12745 -f 12756 12751 12746 -f 12661 12667 12752 -f 12770 12758 12751 -f 12686 12689 12747 -f 12686 12747 12752 -f 12752 12747 12759 -f 12739 12753 12701 -f 12701 12753 12749 -f 12748 12764 12765 -f 12749 12702 12701 -f 12701 12702 12750 -f 12750 12702 12703 -f 12758 12774 12766 -f 12763 12770 12751 -f 12763 12751 12756 -f 12760 12753 12752 -f 12752 12753 12740 -f 12740 12753 12739 -f 12740 12739 12754 -f 12756 12746 12740 -f 12740 12746 12757 -f 12740 12757 12752 -f 12752 12757 12661 -f 12774 12775 12766 -f 12748 12765 12750 -f 12748 12750 12703 -f 12770 12771 12758 -f 12758 12771 12772 -f 12758 12772 12774 -f 12775 12777 12766 -f 12759 12699 12752 -f 12752 12699 12760 -f 12760 12699 12700 -f 12700 12705 12761 -f 12700 12761 12760 -f 12763 12762 12767 -f 12763 12767 12770 -f 12765 12764 12705 -f 12765 12705 12700 -f 12766 12777 12762 -f 12766 12762 12763 -f 12762 12721 12768 -f 12762 12768 12767 -f 12767 12768 12769 -f 12767 12769 12770 -f 12770 12769 12710 -f 12770 12710 12771 -f 12771 12710 12772 -f 12772 12710 12723 -f 12772 12723 12774 -f 12774 12723 12773 -f 12774 12773 12776 -f 12774 12776 12775 -f 12775 12776 12778 -f 12775 12778 12777 -f 12777 12778 12721 -f 12777 12721 12762 -f 12782 12781 12779 -f 12779 12781 12780 -f 12843 12844 12783 -f 12783 12844 12785 -f 12783 12785 12784 -f 12784 12785 12786 -f 12784 12786 12788 -f 12788 12786 12787 -f 12788 12787 12789 -f 12789 12787 12790 -f 12789 12790 12791 -f 12791 12790 12792 -f 12791 12792 12793 -f 12793 12792 12794 -f 12793 12794 12795 -f 12795 12794 12796 -f 12795 12796 12798 -f 12798 12796 12797 -f 12798 12797 12799 -f 12799 12797 12800 -f 12799 12800 12801 -f 12801 12800 12803 -f 12801 12803 12802 -f 12802 12803 12804 -f 12802 12804 12805 -f 12805 12804 12806 -f 12805 12806 12808 -f 12808 12806 12807 -f 12808 12807 12810 -f 12810 12807 12809 -f 12810 12809 12811 -f 12811 12809 12813 -f 12811 12813 12812 -f 12812 12813 12814 -f 12812 12814 12815 -f 12815 12814 12816 -f 12815 12816 12818 -f 12818 12816 12817 -f 12818 12817 12819 -f 12819 12817 12820 -f 12819 12820 12821 -f 12821 12820 12822 -f 12821 12822 12823 -f 12823 12822 12824 -f 12823 12824 12825 -f 12825 12824 12827 -f 12825 12827 12826 -f 12826 12827 12828 -f 12826 12828 12830 -f 12830 12828 12829 -f 12830 12829 12832 -f 12832 12829 12831 -f 12832 12831 12833 -f 12833 12831 12834 -f 12833 12834 12836 -f 12836 12834 12835 -f 12836 12835 12838 -f 12838 12835 12837 -f 12838 12837 12840 -f 12840 12837 12839 -f 12840 12839 12841 -f 12841 12839 12842 -f 12841 12842 12843 -f 12843 12842 12844 -f 12846 12848 12845 -f 12847 12846 12845 -f 12848 12847 12845 -f 12849 12847 12848 -f 12847 12850 12846 -f 12851 12853 12852 -f 12854 12853 12851 -f 12855 12852 12853 -f 12856 12857 12858 -f 12860 12859 12861 -f 12859 12862 12861 -f 12860 12861 12862 -f 12865 12864 12866 -f 12863 12865 12866 -f 12867 12865 12863 -f 12940 12941 12868 -f 12868 12941 12869 -f 12868 12869 12870 -f 12870 12869 12871 -f 12870 12871 12872 -f 12872 12871 12873 -f 12872 12873 12874 -f 12874 12873 12875 -f 12874 12875 12876 -f 12876 12875 12877 -f 12876 12877 12878 -f 12878 12877 12879 -f 12878 12879 12880 -f 12880 12879 12881 -f 12880 12881 12882 -f 12882 12881 12883 -f 12882 12883 12884 -f 12884 12883 12885 -f 12884 12885 12886 -f 12886 12885 12888 -f 12886 12888 12887 -f 12887 12888 12890 -f 12887 12890 12889 -f 12889 12890 12891 -f 12889 12891 12893 -f 12893 12891 12892 -f 12893 12892 12894 -f 12894 12892 12895 -f 12894 12895 12897 -f 12897 12895 12896 -f 12897 12896 12898 -f 12898 12896 12899 -f 12898 12899 12900 -f 12900 12899 12901 -f 12900 12901 12902 -f 12902 12901 12904 -f 12902 12904 12903 -f 12903 12904 12905 -f 12903 12905 12906 -f 12906 12905 12907 -f 12906 12907 12908 -f 12908 12907 12909 -f 12908 12909 12910 -f 12910 12909 12912 -f 12910 12912 12911 -f 12911 12912 12913 -f 12911 12913 12914 -f 12914 12913 12915 -f 12914 12915 12916 -f 12916 12915 12917 -f 12916 12917 12918 -f 12918 12917 12920 -f 12918 12920 12919 -f 12919 12920 12921 -f 12919 12921 12922 -f 12922 12921 12923 -f 12922 12923 12924 -f 12924 12923 12925 -f 12924 12925 12926 -f 12926 12925 12928 -f 12926 12928 12927 -f 12927 12928 12929 -f 12927 12929 12930 -f 12930 12929 12931 -f 12930 12931 12932 -f 12932 12931 12933 -f 12932 12933 12934 -f 12934 12933 12935 -f 12934 12935 12936 -f 12936 12935 12938 -f 12936 12938 12937 -f 12937 12938 12939 -f 12937 12939 12940 -f 12940 12939 12941 -f 12942 12943 12944 -f 12945 12942 12944 -f 12954 12971 12946 -f 12946 12971 12947 -f 12946 12947 12948 -f 12948 12947 13030 -f 13067 13074 13075 -f 13077 13078 12949 -f 13075 12950 12951 -f 12949 13012 13077 -f 13077 13012 12950 -f 13077 12950 13075 -f 12962 12959 13064 -f 12951 13066 13067 -f 12951 13067 13075 -f 12962 13064 13066 -f 13066 12973 12962 -f 12951 12973 13066 -f 12960 12952 12959 -f 12949 13078 12953 -f 12953 13027 13028 -f 13067 13073 13074 -f 12954 12955 12956 -f 12956 12955 13071 -f 12956 13071 12952 -f 12960 12956 12952 -f 12959 12952 13064 -f 12953 13028 12949 -f 13027 12953 12948 -f 12946 13072 12954 -f 12958 13072 12946 -f 13073 13067 12957 -f 12948 12953 12958 -f 12948 12958 12946 -f 12954 13072 13073 -f 13073 12957 12955 -f 13073 12955 12954 -f 12959 12969 12960 -f 12960 12969 12961 -f 12960 12961 12956 -f 12959 12962 12969 -f 12969 12962 12968 -f 13076 12963 12965 -f 12963 13069 13068 -f 13068 12965 12963 -f 13010 13076 12964 -f 13010 12964 13011 -f 12964 13076 12965 -f 13030 13080 12966 -f 13010 13079 13076 -f 12961 12967 13070 -f 12961 13070 12971 -f 12965 13068 13065 -f 12965 13065 12972 -f 12947 12971 13081 -f 12969 12968 13063 -f 13080 13030 13081 -f 13081 13030 12947 -f 12966 13080 13079 -f 13079 13029 12966 -f 13010 13029 13079 -f 13063 12968 12972 -f 13063 12972 13065 -f 12969 13063 12967 -f 12963 12970 13070 -f 13070 12970 12971 -f 12971 12970 13081 -f 12967 12961 12969 -f 13070 13069 12963 -f 12951 12965 12972 -f 12951 12972 12973 -f 12973 12972 12968 -f 12973 12968 12962 -f 13059 13058 13061 -f 13061 13058 13057 -f 13061 13057 13056 -f 13061 13056 12988 -f 12988 13056 12974 -f 12988 12974 12990 -f 12990 12974 12975 -f 12990 12975 12976 -f 12976 12975 12977 -f 12976 12977 12992 -f 12965 12951 12964 -f 12964 12951 12950 -f 12964 12950 13032 -f 13032 12950 12979 -f 13032 12979 12978 -f 12978 12979 12986 -f 12995 13045 12980 -f 12980 13045 13044 -f 12980 13044 12981 -f 12981 13044 13043 -f 12981 13043 12997 -f 12997 13043 12982 -f 12997 12982 12983 -f 12977 13053 12992 -f 12992 13053 13050 -f 12992 13050 12993 -f 12993 13050 13049 -f 12993 13049 12994 -f 12994 13049 13048 -f 12994 13048 12995 -f 12995 13048 13047 -f 12995 13047 13045 -f 12982 12984 12983 -f 12983 12984 13040 -f 12983 13040 12998 -f 12998 13040 13038 -f 12998 13038 13000 -f 13000 13038 12985 -f 13000 12985 13001 -f 13001 12985 13036 -f 13001 13036 12986 -f 12986 13036 13034 -f 12986 13034 12978 -f 13004 13061 12987 -f 12987 13061 12988 -f 12987 12988 12989 -f 12989 12988 12990 -f 12989 12990 12991 -f 12991 12990 12976 -f 12991 12976 13007 -f 13007 12976 12992 -f 13007 12992 13006 -f 13006 12992 12993 -f 13006 12993 13015 -f 13015 12993 12994 -f 13015 12994 13013 -f 13013 12994 12995 -f 13013 12995 13023 -f 13023 12995 12980 -f 13023 12980 12996 -f 12996 12980 12981 -f 12996 12981 13021 -f 13021 12981 12997 -f 13021 12997 13020 -f 13020 12997 12983 -f 13020 12983 13018 -f 13018 12983 12998 -f 13018 12998 12999 -f 12999 12998 13000 -f 12999 13000 13025 -f 13025 13000 13001 -f 13025 13001 13002 -f 13002 13001 12986 -f 13002 12986 13003 -f 13003 12986 12979 -f 13003 12979 13012 -f 13012 12979 12950 -f 13060 13062 13005 -f 13005 13062 13004 -f 13005 13004 13009 -f 13009 13004 12987 -f 13006 13051 13007 -f 13007 13051 13052 -f 13007 13052 12991 -f 12991 13052 13054 -f 12991 13054 12989 -f 12989 13054 13008 -f 12989 13008 12987 -f 12987 13008 13055 -f 12987 13055 13009 -f 12949 13010 13012 -f 13012 13010 13011 -f 13012 13011 13003 -f 13023 13046 13013 -f 13013 13046 13014 -f 13013 13014 13015 -f 13015 13014 13016 -f 13015 13016 13006 -f 13006 13016 13017 -f 13006 13017 13051 -f 13018 13019 13020 -f 13020 13019 13041 -f 13020 13041 13021 -f 13021 13041 13022 -f 13021 13022 12996 -f 12996 13022 13042 -f 12996 13042 13023 -f 13023 13042 13024 -f 13023 13024 13046 -f 13011 13031 13003 -f 13003 13031 13033 -f 13003 13033 13002 -f 13002 13033 13035 -f 13002 13035 13025 -f 13025 13035 13037 -f 13025 13037 12999 -f 12999 13037 13026 -f 12999 13026 13018 -f 13018 13026 13039 -f 13018 13039 13019 -f 13027 12966 13029 -f 13027 13029 13028 -f 13028 13029 13010 -f 13028 13010 12949 -f 12966 13027 13030 -f 13030 13027 12948 -f 13011 12964 13032 -f 13011 13032 13031 -f 13031 13032 12978 -f 13031 12978 13033 -f 13033 12978 13034 -f 13033 13034 13035 -f 13035 13034 13036 -f 13035 13036 13037 -f 13037 13036 12985 -f 13037 12985 13026 -f 13026 12985 13038 -f 13026 13038 13039 -f 13039 13038 13040 -f 13039 13040 13019 -f 13019 13040 12984 -f 13019 12984 13041 -f 13041 12984 12982 -f 13041 12982 13022 -f 13022 12982 13043 -f 13022 13043 13042 -f 13042 13043 13044 -f 13042 13044 13024 -f 13024 13044 13045 -f 13024 13045 13046 -f 13046 13045 13047 -f 13046 13047 13014 -f 13014 13047 13048 -f 13014 13048 13016 -f 13016 13048 13049 -f 13016 13049 13017 -f 13017 13049 13050 -f 13017 13050 13051 -f 13051 13050 13053 -f 13051 13053 13052 -f 13052 13053 12977 -f 13052 12977 13054 -f 13054 12977 12975 -f 13054 12975 13008 -f 13008 12975 12974 -f 13008 12974 13055 -f 13055 12974 13056 -f 13055 13056 13009 -f 13009 13056 13057 -f 13009 13057 13005 -f 13057 13058 13005 -f 13005 13058 13060 -f 13058 13059 13060 -f 13060 13059 13062 -f 13059 13061 13062 -f 13062 13061 13004 -f 12971 12954 12961 -f 12961 12954 12956 -f 13071 12967 12952 -f 12952 12967 13064 -f 13064 12967 13063 -f 13064 13063 13066 -f 13066 13063 13065 -f 13066 13065 13068 -f 13066 13068 13067 -f 13067 13068 13069 -f 13067 13069 12957 -f 12957 13069 12955 -f 12955 13069 13070 -f 12955 13070 13071 -f 13071 13070 12967 -f 13072 12970 13073 -f 13073 12970 13074 -f 13074 12970 12963 -f 13074 12963 13075 -f 13075 12963 13076 -f 13075 13076 13077 -f 13077 13076 13078 -f 13078 13076 13079 -f 13078 13079 12953 -f 12953 13079 13080 -f 12953 13080 12958 -f 12958 13080 13081 -f 12958 13081 13072 -f 13072 13081 12970 -f 13083 13129 13145 -f 13082 13139 13083 -f 13082 13083 13145 -f 13082 13145 13139 -f 13083 13146 13129 -f 13146 13083 13139 -f 13090 13147 13149 -f 13090 13149 13091 -f 13088 13096 13086 -f 13103 13101 13085 -f 13085 13101 13088 -f 13088 13101 13096 -f 13089 13088 13086 -f 13087 13086 13094 -f 13147 13091 13151 -f 13151 13091 13084 -f 13090 13089 13086 -f 13087 13094 13084 -f 13090 13086 13087 -f 13095 13085 13088 -f 13091 13089 13090 -f 13092 13087 13084 -f 13149 13148 13091 -f 13097 13103 13085 -f 13097 13085 13093 -f 13095 13093 13085 -f 13095 13088 13089 -f 13092 13084 13091 -f 13096 13089 13091 -f 13098 13087 13092 -f 13099 13091 13148 -f 13094 13098 13092 -f 13094 13092 13091 -f 13087 13098 13090 -f 13095 13101 13093 -f 13101 13095 13089 -f 13091 13099 13094 -f 13090 13098 13147 -f 13098 13094 13086 -f 13098 13086 13147 -f 13093 13101 13097 -f 13097 13101 13100 -f 13101 13089 13096 -f 13096 13091 13086 -f 13094 13099 13084 -f 13084 13099 13151 -f 13100 13117 13111 -f 13097 13105 13103 -f 13110 13123 13104 -f 13111 13109 13102 -f 13105 13100 13102 -f 13103 13100 13101 -f 13109 13111 13104 -f 13117 13110 13111 -f 13103 13105 13109 -f 13104 13100 13109 -f 13102 13109 13105 -f 13106 13122 13108 -f 13108 13116 13117 -f 13104 13117 13100 -f 13120 13124 13106 -f 13123 13107 13108 -f 13100 13111 13102 -f 13103 13109 13100 -f 13106 13125 13118 -f 13116 13122 13107 -f 13100 13105 13097 -f 13107 13115 13106 -f 13111 13110 13104 -f 13106 13124 13125 -f 13126 13127 13121 -f 13123 13108 13117 -f 13125 13120 13115 -f 13115 13120 13106 -f 13107 13106 13108 -f 13113 13127 13126 -f 13108 13122 13116 -f 13119 13112 13113 -f 13121 13127 13119 -f 13118 13115 13107 -f 13116 13107 13123 -f 13125 13114 13120 -f 13117 13116 13110 -f 13106 13118 13122 -f 13113 13133 13127 -f 13128 13119 13126 -f 13118 13125 13115 -f 13116 13123 13110 -f 13121 13114 13125 -f 13120 13114 13124 -f 13127 13112 13119 -f 13122 13118 13107 -f 13121 13128 13114 -f 13123 13117 13104 -f 13133 13112 13127 -f 13119 13113 13126 -f 13143 13135 13136 -f 13121 13119 13128 -f 13136 13135 13140 -f 13141 13140 13138 -f 13131 13138 13142 -f 13114 13128 13126 -f 13112 13131 13113 -f 13124 13114 13126 -f 13146 13145 13143 -f 13124 13126 13121 -f 13124 13121 13125 -f 13142 13141 13133 -f 13130 13146 13139 -f 13134 13139 13144 -f 13134 13144 13137 -f 13129 13132 13134 -f 13145 13137 13135 -f 13129 13134 13145 -f 13131 13142 13113 -f 13140 13146 13143 -f 13144 13132 13137 -f 13136 13140 13142 -f 13141 13138 13133 -f 13133 13138 13131 -f 13113 13142 13133 -f 13137 13129 13135 -f 13145 13134 13137 -f 13142 13140 13141 -f 13133 13131 13112 -f 13135 13129 13146 -f 13144 13130 13132 -f 13139 13145 13144 -f 13140 13143 13138 -f 13132 13130 13134 -f 13138 13136 13142 -f 13144 13146 13130 -f 13143 13145 13135 -f 13143 13136 13138 -f 13144 13145 13146 -f 13130 13139 13134 -f 13137 13132 13129 -f 13135 13146 13140 -f 13091 13147 13086 -f 13150 13151 13099 -f 13150 13099 13148 -f 13151 13148 13149 -f 13151 13150 13148 -f 13149 13147 13151 -f 13176 13212 13173 -f 13173 13212 13199 -f 13170 13154 13201 -f 13201 13154 13204 -f 13155 13208 13152 -f 13155 13152 13156 -f 13156 13152 13153 -f 13156 13153 13154 -f 13154 13153 13204 -f 13155 13157 13208 -f 13208 13157 13203 -f 13170 13171 13161 -f 13170 13161 13158 -f 13170 13158 13154 -f 13159 13156 13158 -f 13158 13156 13154 -f 13159 13155 13156 -f 13155 13159 13157 -f 13157 13159 13160 -f 13160 13200 13157 -f 13158 13205 13210 -f 13158 13210 13159 -f 13159 13210 13209 -f 13159 13209 13160 -f 13160 13209 13200 -f 13158 13161 13205 -f 13205 13161 13198 -f 13171 13198 13161 -f 13178 13169 13164 -f 13178 13164 13182 -f 13181 13162 13164 -f 13162 13182 13164 -f 13163 13164 13162 -f 13162 13164 13167 -f 13162 13167 13183 -f 13187 13184 13189 -f 13189 13184 13165 -f 13195 13182 13183 -f 13166 13182 13195 -f 13185 13166 13165 -f 13185 13165 13184 -f 13183 13167 13195 -f 13195 13167 13168 -f 13196 13168 13169 -f 13169 13168 13167 -f 13169 13167 13164 -f 13169 13178 13196 -f 13196 13178 13197 -f 13201 13197 13170 -f 13170 13197 13178 -f 13170 13178 13171 -f 13171 13178 13172 -f 13171 13172 13198 -f 13198 13172 13174 -f 13176 13173 13177 -f 13179 13177 13175 -f 13175 13177 13173 -f 13174 13179 13175 -f 13179 13174 13172 -f 13179 13172 13178 -f 13179 13178 13182 -f 13176 13177 13186 -f 13186 13177 13179 -f 13182 13185 13190 -f 13182 13190 13179 -f 13186 13180 13176 -f 13191 13186 13179 -f 13179 13190 13191 -f 13181 13163 13162 -f 13182 13166 13185 -f 13162 13183 13182 -f 13184 13187 13188 -f 13184 13188 13185 -f 13185 13188 13190 -f 13186 13191 13194 -f 13191 13190 13192 -f 13187 13189 13188 -f 13192 13190 13189 -f 13189 13190 13188 -f 13191 13192 13202 -f 13193 13194 13202 -f 13202 13194 13191 -f 13194 13193 13186 -f 13168 13196 13195 -f 13195 13196 13197 -f 13166 13195 13197 -f 13205 13198 13201 -f 13193 13173 13207 -f 13207 13173 13199 -f 13198 13189 13201 -f 13201 13189 13165 -f 13201 13165 13197 -f 13197 13165 13166 -f 13173 13193 13202 -f 13173 13202 13192 -f 13173 13192 13175 -f 13175 13192 13174 -f 13203 13200 13209 -f 13203 13209 13208 -f 13205 13201 13204 -f 13174 13192 13189 -f 13174 13189 13198 -f 13204 13153 13205 -f 13205 13153 13210 -f 13199 13206 13207 -f 13207 13206 13246 -f 13153 13152 13210 -f 13208 13209 13210 -f 13208 13210 13152 -f 13211 13246 13206 -f 13211 13206 13199 -f 13211 13199 13212 -f 13225 13213 13217 -f 13242 13241 13236 -f 13232 13236 13235 -f 13214 13215 13220 -f 13214 13220 13231 -f 13231 13220 13219 -f 13231 13219 13216 -f 13216 13219 13218 -f 13216 13218 13232 -f 13232 13218 13236 -f 13242 13236 13218 -f 13217 13213 13242 -f 13242 13218 13219 -f 13242 13219 13220 -f 13226 13217 13242 -f 13226 13242 13220 -f 13226 13220 13215 -f 13223 13222 13213 -f 13213 13222 13224 -f 13213 13224 13243 -f 13221 13275 13224 -f 13224 13222 13221 -f 13223 13225 13217 -f 13223 13217 13222 -f 13222 13217 13226 -f 13226 13215 13228 -f 13207 13230 13227 -f 13228 13215 13207 -f 13207 13215 13214 -f 13207 13214 13230 -f 13222 13226 13228 -f 13227 13233 13229 -f 13233 13227 13230 -f 13214 13231 13216 -f 13216 13232 13235 -f 13237 13230 13216 -f 13214 13216 13230 -f 13216 13235 13237 -f 13230 13234 13233 -f 13233 13234 13211 -f 13230 13237 13234 -f 13245 13234 13237 -f 13235 13236 13241 -f 13235 13241 13237 -f 13237 13241 13240 -f 13237 13240 13238 -f 13237 13238 13239 -f 13237 13239 13245 -f 13239 13238 13242 -f 13238 13240 13242 -f 13240 13241 13242 -f 13242 13213 13243 -f 13239 13242 13243 -f 13244 13243 13224 -f 13211 13234 13246 -f 13246 13245 13244 -f 13244 13245 13239 -f 13244 13239 13243 -f 13246 13234 13245 -f 13288 13252 13253 -f 13288 13253 13293 -f 13285 13251 13247 -f 13285 13247 13286 -f 13286 13247 13254 -f 13286 13254 13288 -f 13288 13254 13252 -f 13281 13249 13285 -f 13285 13249 13251 -f 13281 13248 13249 -f 13249 13248 13271 -f 13252 13254 13250 -f 13251 13249 13271 -f 13251 13271 13259 -f 13250 13254 13256 -f 13259 13258 13251 -f 13251 13258 13247 -f 13250 13253 13252 -f 13256 13254 13247 -f 13258 13255 13247 -f 13247 13255 13256 -f 13293 13250 13287 -f 13287 13250 13256 -f 13287 13256 13255 -f 13287 13255 13257 -f 13257 13255 13258 -f 13257 13258 13284 -f 13284 13258 13259 -f 13284 13259 13280 -f 13280 13259 13271 -f 13260 13262 13261 -f 13263 13272 13262 -f 13263 13262 13264 -f 13263 13264 13267 -f 13265 13264 13304 -f 13265 13304 13266 -f 13265 13266 13270 -f 13264 13265 13267 -f 13303 13304 13270 -f 13268 13301 13278 -f 13278 13301 13302 -f 13277 13304 13268 -f 13268 13304 13301 -f 13276 13270 13277 -f 13277 13270 13304 -f 13270 13269 13265 -f 13276 13269 13270 -f 13279 13267 13269 -f 13269 13267 13265 -f 13248 13281 13282 -f 13267 13279 13280 -f 13280 13271 13267 -f 13267 13271 13248 -f 13267 13248 13263 -f 13263 13248 13282 -f 13262 13272 13273 -f 13290 13261 13262 -f 13290 13262 13273 -f 13273 13272 13282 -f 13263 13282 13272 -f 13275 13221 13290 -f 13290 13221 13261 -f 13244 13224 13274 -f 13274 13224 13275 -f 13269 13276 13279 -f 13279 13276 13277 -f 13279 13268 13280 -f 13280 13268 13278 -f 13280 13278 13281 -f 13279 13277 13268 -f 13278 13282 13281 -f 13278 13283 13282 -f 13282 13283 13273 -f 13273 13283 13289 -f 13273 13289 13290 -f 13280 13281 13285 -f 13280 13285 13284 -f 13286 13257 13285 -f 13285 13257 13284 -f 13228 13244 13274 -f 13286 13287 13257 -f 13228 13274 13275 -f 13287 13286 13293 -f 13293 13286 13288 -f 13289 13295 13290 -f 13290 13295 13291 -f 13290 13291 13292 -f 13290 13292 13297 -f 13290 13297 13296 -f 13290 13296 13275 -f 13275 13296 13228 -f 13302 13283 13278 -f 13283 13300 13294 -f 13283 13294 13289 -f 13289 13294 13295 -f 13295 13294 13299 -f 13295 13299 13291 -f 13291 13299 13292 -f 13292 13299 13297 -f 13298 13296 13297 -f 13298 13297 13299 -f 13283 13302 13300 -f 13300 13302 13301 -f 13299 13294 13300 -f 13300 13301 13264 -f 13264 13301 13304 -f 13304 13303 13266 -f 13308 13338 13311 -f 13311 13338 13328 -f 13307 13312 13305 -f 13307 13305 13331 -f 13331 13305 13306 -f 13331 13306 13335 -f 13335 13306 13311 -f 13335 13311 13328 -f 13332 13317 13312 -f 13332 13312 13307 -f 13315 13324 13308 -f 13308 13324 13322 -f 13308 13322 13320 -f 13308 13320 13339 -f 13339 13320 13309 -f 13339 13309 13310 -f 13311 13313 13314 -f 13311 13314 13308 -f 13316 13305 13312 -f 13313 13311 13306 -f 13308 13314 13315 -f 13317 13315 13318 -f 13313 13306 13316 -f 13316 13306 13305 -f 13314 13318 13315 -f 13312 13317 13316 -f 13316 13317 13318 -f 13319 13309 13320 -f 13319 13320 13321 -f 13321 13320 13322 -f 13321 13322 13334 -f 13334 13322 13324 -f 13334 13324 13323 -f 13323 13324 13315 -f 13323 13315 13336 -f 13336 13315 13317 -f 13336 13317 13332 -f 13325 13333 13338 -f 13325 13338 13326 -f 13333 13327 13338 -f 13338 13327 13328 -f 13334 13323 13329 -f 13337 13332 13330 -f 13330 13332 13307 -f 13330 13331 13335 -f 13330 13335 13327 -f 13330 13307 13331 -f 13332 13337 13336 -f 13336 13329 13323 -f 13325 13319 13333 -f 13333 13319 13321 -f 13333 13321 13329 -f 13329 13321 13334 -f 13328 13327 13335 -f 13336 13337 13329 -f 13338 13308 13326 -f 13326 13308 13339 -f 13326 13339 13341 -f 13363 13354 13342 -f 13342 13354 13349 -f 13339 13342 13340 -f 13340 13341 13339 -f 13349 13340 13342 -f 13344 13350 13343 -f 13344 13343 13376 -f 13376 13343 13345 -f 13376 13345 13377 -f 13377 13345 13348 -f 13377 13348 13366 -f 13366 13348 13346 -f 13366 13346 13365 -f 13365 13346 13373 -f 13373 13346 13357 -f 13373 13357 13371 -f 13371 13357 13356 -f 13371 13356 13360 -f 13346 13348 13354 -f 13354 13348 13345 -f 13354 13345 13343 -f 13354 13343 13349 -f 13349 13343 13350 -f 13349 13350 13351 -f 13353 13347 13355 -f 13353 13355 13354 -f 13347 13353 13361 -f 13354 13355 13346 -f 13357 13346 13358 -f 13360 13356 13352 -f 13352 13356 13358 -f 13347 13361 13360 -f 13347 13360 13352 -f 13355 13358 13346 -f 13356 13357 13358 -f 13371 13360 13359 -f 13359 13360 13361 -f 13359 13361 13374 -f 13374 13361 13353 -f 13374 13353 13368 -f 13354 13363 13353 -f 13353 13363 13368 -f 13362 13375 13363 -f 13362 13363 13342 -f 13375 13364 13363 -f 13363 13364 13368 -f 13365 13367 13366 -f 13366 13367 13377 -f 13368 13364 13369 -f 13368 13369 13374 -f 13371 13359 13370 -f 13370 13359 13369 -f 13370 13373 13371 -f 13373 13370 13372 -f 13373 13372 13365 -f 13365 13372 13367 -f 13369 13359 13374 -f 13362 13344 13375 -f 13375 13344 13376 -f 13375 13376 13367 -f 13367 13376 13377 -f 13422 13378 13423 -f 13423 13378 13379 -f 13378 13433 13379 -f 13379 13433 13424 -f 13378 13422 13433 -f 13433 13422 13382 -f 13428 13380 13382 -f 13382 13380 13430 -f 13430 13381 13382 -f 13382 13381 13432 -f 13382 13432 13433 -f 13383 13440 13385 -f 13385 13440 13384 -f 13385 13384 13437 -f 13385 13437 13387 -f 13437 13438 13387 -f 13387 13438 13412 -f 13387 13412 13386 -f 13386 13412 13418 -f 13391 13446 13386 -f 13386 13446 13387 -f 13391 13386 13435 -f 13419 13396 13392 -f 13389 13391 13388 -f 13389 13390 13391 -f 13391 13390 13395 -f 13392 13400 13393 -f 13391 13435 13397 -f 13419 13392 13393 -f 13388 13391 13394 -f 13394 13391 13397 -f 13394 13397 13399 -f 13391 13395 13419 -f 13419 13395 13396 -f 13402 13398 13397 -f 13397 13398 13399 -f 13393 13400 13401 -f 13393 13401 13397 -f 13397 13401 13402 -f 13435 13386 13418 -f 13404 13405 13412 -f 13412 13405 13403 -f 13404 13411 13405 -f 13413 13406 13418 -f 13416 13407 13409 -f 13409 13407 13408 -f 13409 13408 13410 -f 13409 13410 13404 -f 13404 13410 13411 -f 13412 13403 13413 -f 13412 13413 13418 -f 13406 13414 13418 -f 13418 13414 13415 -f 13409 13417 13416 -f 13416 13417 13415 -f 13415 13417 13418 -f 13418 13417 13435 -f 13409 13404 13434 -f 13434 13404 13421 -f 13419 13412 13420 -f 13420 13412 13438 -f 13420 13438 13448 -f 13448 13438 13421 -f 13448 13421 13393 -f 13393 13421 13404 -f 13393 13404 13419 -f 13419 13404 13412 -f 13426 13451 13448 -f 13426 13448 13382 -f 13382 13448 13393 -f 13382 13393 13397 -f 13422 13423 13382 -f 13382 13423 13426 -f 13423 13379 13424 -f 13431 13429 13426 -f 13426 13429 13425 -f 13426 13425 13436 -f 13423 13424 13426 -f 13426 13424 13427 -f 13426 13427 13431 -f 13428 13436 13425 -f 13428 13425 13380 -f 13380 13425 13429 -f 13380 13429 13430 -f 13430 13429 13431 -f 13430 13431 13381 -f 13381 13431 13427 -f 13381 13427 13432 -f 13432 13427 13424 -f 13432 13424 13433 -f 13428 13382 13397 -f 13440 13383 13434 -f 13434 13383 13451 -f 13435 13417 13397 -f 13397 13417 13409 -f 13397 13409 13428 -f 13428 13409 13434 -f 13428 13434 13436 -f 13436 13434 13451 -f 13436 13451 13426 -f 13438 13439 13443 -f 13438 13443 13421 -f 13421 13443 13442 -f 13421 13442 13434 -f 13445 13444 13437 -f 13437 13444 13438 -f 13438 13444 13439 -f 13434 13442 13441 -f 13441 13440 13434 -f 13384 13440 13441 -f 13384 13441 13437 -f 13437 13441 13445 -f 13453 13441 13454 -f 13454 13441 13442 -f 13454 13442 13450 -f 13450 13442 13443 -f 13450 13443 13447 -f 13447 13443 13439 -f 13447 13439 13449 -f 13449 13439 13452 -f 13452 13439 13444 -f 13452 13444 13445 -f 13452 13445 13453 -f 13453 13445 13441 -f 13383 13385 13446 -f 13448 13447 13420 -f 13446 13385 13387 -f 13420 13447 13449 -f 13450 13447 13448 -f 13420 13449 13452 -f 13451 13454 13450 -f 13451 13450 13448 -f 13452 13451 13383 -f 13452 13383 13446 -f 13452 13446 13420 -f 13452 13453 13451 -f 13451 13453 13454 -f 13391 13419 13446 -f 13446 13419 13420 -f 13455 13601 13674 -f 13674 13601 13646 -f 13646 13601 13602 -f 13646 13602 13659 -f 13659 13602 13605 -f 13659 13605 13656 -f 13605 13618 13656 -f 13656 13618 13457 -f 13619 13648 13644 -f 13619 13644 13630 -f 13630 13644 13456 -f 13630 13456 13631 -f 13631 13456 13628 -f 13628 13456 13457 -f 13628 13457 13618 -f 13619 13461 13648 -f 13648 13461 13460 -f 13458 13459 13460 -f 13458 13460 13461 -f 13458 13632 13459 -f 13459 13632 13462 -f 13625 13673 13632 -f 13632 13673 13462 -f 13634 13653 13668 -f 13634 13668 13624 -f 13624 13668 13463 -f 13624 13463 13625 -f 13625 13463 13673 -f 13487 13485 13681 -f 13487 13681 13678 -f 13674 13480 13675 -f 13675 13480 13483 -f 13675 13483 13676 -f 13676 13483 13481 -f 13676 13481 13678 -f 13678 13481 13487 -f 13497 13465 13464 -f 13464 13465 13684 -f 13464 13684 13467 -f 13467 13684 13466 -f 13467 13466 13501 -f 13501 13466 13469 -f 13501 13469 13468 -f 13468 13469 13692 -f 13468 13692 13694 -f 13694 13692 13683 -f 13493 13474 13494 -f 13494 13474 13470 -f 13494 13470 13495 -f 13495 13470 13687 -f 13495 13687 13489 -f 13489 13687 13688 -f 13489 13688 13471 -f 13471 13688 13472 -f 13471 13472 13496 -f 13496 13472 13497 -f 13497 13472 13465 -f 13493 13473 13474 -f 13474 13473 13475 -f 13475 13473 13689 -f 13689 13473 13492 -f 13689 13492 13690 -f 13690 13492 13476 -f 13476 13492 13491 -f 13476 13491 13685 -f 13685 13491 13477 -f 13685 13477 13686 -f 13686 13477 13479 -f 13686 13479 13478 -f 13478 13479 13505 -f 13641 13640 13480 -f 13480 13640 13508 -f 13480 13508 13510 -f 13480 13510 13482 -f 13512 13487 13481 -f 13512 13481 13482 -f 13482 13481 13483 -f 13482 13483 13480 -f 13484 13694 13485 -f 13488 13487 13512 -f 13488 13507 13487 -f 13488 13486 13507 -f 13502 13694 13506 -f 13506 13694 13507 -f 13507 13694 13484 -f 13507 13484 13487 -f 13487 13484 13485 -f 13477 13496 13479 -f 13471 13477 13491 -f 13471 13491 13489 -f 13477 13471 13496 -f 13490 13491 13492 -f 13492 13473 13490 -f 13490 13473 13493 -f 13490 13493 13495 -f 13491 13490 13489 -f 13489 13490 13495 -f 13493 13494 13495 -f 13479 13496 13497 -f 13479 13497 13505 -f 13505 13497 13498 -f 13498 13497 13464 -f 13498 13464 13499 -f 13499 13464 13467 -f 13499 13467 13500 -f 13500 13467 13501 -f 13500 13501 13502 -f 13502 13501 13468 -f 13502 13468 13694 -f 13506 13682 13502 -f 13502 13682 13693 -f 13502 13693 13500 -f 13500 13693 13503 -f 13500 13503 13499 -f 13499 13503 13504 -f 13499 13504 13498 -f 13498 13504 13691 -f 13498 13691 13505 -f 13505 13691 13478 -f 13682 13506 13507 -f 13682 13507 13486 -f 13508 13679 13509 -f 13508 13509 13510 -f 13510 13509 13511 -f 13510 13511 13482 -f 13482 13511 13512 -f 13512 13511 13677 -f 13680 13512 13677 -f 13680 13488 13512 -f 13680 13486 13488 -f 13508 13640 13679 -f 13589 13679 13559 -f 13559 13679 13560 -f 13583 13558 13550 -f 13550 13558 13554 -f 13514 13638 13513 -f 13514 13513 13574 -f 13574 13513 13592 -f 13514 13579 13547 -f 13547 13579 13571 -f 13547 13571 13538 -f 13571 13515 13538 -f 13538 13515 13516 -f 13516 13515 13564 -f 13516 13564 13546 -f 13564 13576 13546 -f 13546 13576 13517 -f 13517 13576 13519 -f 13517 13519 13518 -f 13518 13519 13542 -f 13542 13519 13520 -f 13542 13520 13583 -f 13542 13583 13550 -f 13524 13521 13525 -f 13547 13538 13548 -f 13522 13679 13640 -f 13522 13640 13523 -f 13735 13560 13522 -f 13522 13560 13679 -f 13526 13528 13530 -f 13524 13525 13526 -f 13526 13525 13527 -f 13526 13527 13528 -f 13534 13529 13528 -f 13528 13529 13530 -f 13516 13537 13538 -f 13532 13531 13533 -f 13532 13533 13552 -f 13533 13534 13552 -f 13638 13514 13640 -f 13528 13535 13534 -f 13534 13535 13536 -f 13534 13536 13552 -f 13552 13536 13551 -f 13538 13537 13548 -f 13735 13541 13560 -f 13560 13541 13540 -f 13524 13539 13521 -f 13521 13539 13554 -f 13521 13554 13541 -f 13541 13554 13540 -f 13542 13549 13544 -f 13544 13518 13542 -f 13544 13517 13518 -f 13539 13543 13554 -f 13554 13543 13555 -f 13517 13544 13545 -f 13517 13545 13546 -f 13546 13545 13537 -f 13553 13547 13548 -f 13557 13549 13550 -f 13550 13549 13542 -f 13537 13516 13546 -f 13551 13523 13552 -f 13552 13523 13640 -f 13552 13640 13553 -f 13553 13640 13514 -f 13553 13514 13547 -f 13554 13555 13556 -f 13554 13556 13550 -f 13550 13556 13557 -f 13557 13556 13531 -f 13557 13531 13532 -f 13554 13558 13586 -f 13554 13586 13540 -f 13540 13586 13559 -f 13559 13560 13540 -f 13569 13576 13564 -f 13569 13564 13581 -f 13584 13566 13565 -f 13583 13565 13561 -f 13562 13574 13590 -f 13563 13574 13570 -f 13574 13563 13578 -f 13565 13566 13567 -f 13565 13567 13562 -f 13562 13567 13568 -f 13563 13570 13577 -f 13577 13570 13582 -f 13571 13579 13580 -f 13580 13579 13578 -f 13519 13576 13582 -f 13583 13572 13573 -f 13574 13575 13570 -f 13576 13569 13577 -f 13576 13577 13582 -f 13574 13578 13579 -f 13574 13579 13514 -f 13571 13580 13515 -f 13515 13580 13581 -f 13515 13581 13564 -f 13582 13520 13519 -f 13583 13573 13584 -f 13583 13584 13565 -f 13561 13585 13583 -f 13583 13585 13558 -f 13559 13586 13587 -f 13587 13586 13558 -f 13587 13558 13585 -f 13562 13568 13574 -f 13574 13568 13575 -f 13572 13583 13582 -f 13582 13583 13520 -f 13559 13587 13588 -f 13559 13588 13589 -f 13589 13588 13590 -f 13589 13590 13574 -f 13633 13591 13635 -f 13635 13591 13455 -f 13635 13455 13636 -f 13636 13455 13589 -f 13636 13589 13592 -f 13592 13589 13574 -f 13625 13593 13591 -f 13594 13455 13597 -f 13604 13601 13594 -f 13594 13601 13455 -f 13591 13593 13599 -f 13591 13599 13455 -f 13603 13608 13606 -f 13595 13600 13619 -f 13619 13600 13461 -f 13461 13600 13596 -f 13596 13458 13461 -f 13623 13597 13598 -f 13598 13597 13455 -f 13598 13455 13599 -f 13607 13617 13605 -f 13601 13604 13602 -f 13603 13605 13604 -f 13604 13605 13602 -f 13603 13606 13605 -f 13605 13606 13607 -f 13610 13595 13629 -f 13603 13609 13608 -f 13610 13629 13611 -f 13610 13611 13598 -f 13613 13612 13616 -f 13608 13609 13615 -f 13608 13615 13614 -f 13614 13615 13612 -f 13611 13616 13598 -f 13605 13617 13618 -f 13618 13617 13626 -f 13595 13619 13629 -f 13613 13620 13612 -f 13612 13620 13614 -f 13612 13621 13616 -f 13616 13621 13622 -f 13616 13622 13598 -f 13598 13622 13623 -f 13591 13634 13624 -f 13591 13624 13625 -f 13626 13627 13618 -f 13618 13627 13628 -f 13628 13627 13629 -f 13628 13629 13631 -f 13619 13630 13629 -f 13629 13630 13631 -f 13625 13458 13596 -f 13625 13632 13458 -f 13591 13633 13634 -f 13634 13633 13642 -f 13634 13642 13653 -f 13653 13642 13643 -f 13633 13635 13642 -f 13642 13635 13637 -f 13635 13636 13637 -f 13637 13636 13639 -f 13636 13592 13639 -f 13639 13592 13513 -f 13513 13638 13639 -f 13639 13638 13640 -f 13639 13640 13637 -f 13637 13640 13641 -f 13637 13641 13642 -f 13642 13641 13643 -f 13653 13643 13655 -f 13655 13643 13652 -f 13457 13650 13645 -f 13649 13456 13644 -f 13457 13645 13656 -f 13656 13645 13657 -f 13646 13660 13674 -f 13674 13660 13647 -f 13674 13647 13641 -f 13644 13648 13649 -f 13661 13658 13656 -f 13641 13647 13651 -f 13641 13651 13643 -f 13643 13651 13652 -f 13654 13653 13655 -f 13664 13648 13460 -f 13664 13460 13667 -f 13660 13646 13659 -f 13660 13659 13658 -f 13650 13457 13649 -f 13649 13457 13456 -f 13662 13661 13656 -f 13662 13656 13657 -f 13656 13658 13659 -f 13661 13662 13663 -f 13661 13663 13654 -f 13654 13663 13669 -f 13654 13668 13653 -f 13648 13664 13665 -f 13648 13665 13649 -f 13666 13672 13671 -f 13462 13666 13459 -f 13459 13666 13667 -f 13459 13667 13460 -f 13654 13669 13668 -f 13668 13669 13670 -f 13668 13670 13672 -f 13668 13672 13463 -f 13672 13666 13462 -f 13672 13462 13463 -f 13665 13671 13649 -f 13649 13671 13672 -f 13462 13673 13463 -f 13641 13480 13674 -f 13675 13455 13674 -f 13455 13675 13676 -f 13455 13676 13589 -f 13677 13676 13678 -f 13680 13677 13678 -f 13676 13677 13511 -f 13676 13511 13589 -f 13511 13509 13589 -f 13589 13509 13679 -f 13681 13485 13683 -f 13681 13682 13678 -f 13486 13680 13682 -f 13682 13680 13678 -f 13682 13681 13683 -f 13682 13683 13693 -f 13478 13684 13465 -f 13478 13465 13686 -f 13465 13472 13686 -f 13686 13472 13688 -f 13476 13685 13688 -f 13688 13685 13686 -f 13470 13474 13687 -f 13687 13474 13475 -f 13687 13475 13690 -f 13690 13476 13687 -f 13687 13476 13688 -f 13475 13689 13690 -f 13478 13691 13684 -f 13684 13691 13504 -f 13684 13504 13466 -f 13466 13504 13503 -f 13466 13503 13469 -f 13469 13503 13693 -f 13469 13693 13692 -f 13692 13693 13683 -f 13694 13683 13485 -f 13735 13736 13695 -f 13695 13736 13737 -f 13695 13737 13696 -f 13696 13737 13698 -f 13696 13698 13697 -f 13697 13698 13699 -f 13697 13699 13700 -f 13700 13699 13738 -f 13700 13738 13702 -f 13702 13738 13701 -f 13702 13701 13703 -f 13703 13701 13704 -f 13703 13704 13705 -f 13705 13704 13739 -f 13705 13739 13706 -f 13706 13739 13708 -f 13706 13708 13707 -f 13707 13708 13710 -f 13707 13710 13709 -f 13709 13710 13711 -f 13709 13711 13712 -f 13712 13711 13713 -f 13712 13713 13714 -f 13714 13713 13740 -f 13714 13740 13527 -f 13527 13740 13742 -f 13527 13742 13715 -f 13715 13742 13717 -f 13715 13717 13716 -f 13716 13717 13718 -f 13716 13718 13719 -f 13719 13718 13743 -f 13719 13743 13720 -f 13720 13743 13721 -f 13720 13721 13722 -f 13722 13721 13723 -f 13722 13723 13724 -f 13724 13723 13744 -f 13724 13744 13725 -f 13725 13744 13726 -f 13725 13726 13728 -f 13728 13726 13727 -f 13728 13727 13729 -f 13729 13727 13745 -f 13729 13745 13730 -f 13730 13745 13731 -f 13730 13731 13732 -f 13732 13731 13734 -f 13732 13734 13733 -f 13733 13734 13741 -f 13733 13741 13735 -f 13735 13741 13736 -f 13699 13698 13741 -f 13741 13698 13737 -f 13741 13737 13736 -f 13704 13701 13741 -f 13741 13701 13738 -f 13741 13738 13699 -f 13710 13708 13741 -f 13741 13708 13739 -f 13741 13739 13704 -f 13740 13713 13741 -f 13741 13713 13711 -f 13741 13711 13710 -f 13718 13717 13741 -f 13741 13717 13742 -f 13741 13742 13740 -f 13723 13721 13741 -f 13741 13721 13743 -f 13741 13743 13718 -f 13727 13726 13741 -f 13741 13726 13744 -f 13741 13744 13723 -f 13734 13731 13741 -f 13741 13731 13745 -f 13741 13745 13727 -f 13751 13762 13766 -f 13751 13766 13750 -f 13750 13766 13755 -f 13755 13766 13767 -f 13751 13752 13762 -f 13762 13752 13763 -f 13784 13765 13763 -f 13784 13763 13752 -f 13784 13752 13746 -f 13784 13746 13747 -f 13784 13747 13818 -f 13754 13748 13751 -f 13749 13759 13818 -f 13749 13818 13747 -f 13759 13749 13753 -f 13754 13751 13750 -f 13751 13748 13752 -f 13752 13748 13746 -f 13759 13753 13755 -f 13753 13754 13755 -f 13754 13750 13755 -f 13870 13859 13817 -f 13817 13859 13842 -f 13865 13870 13756 -f 13756 13870 13817 -f 13864 13865 13826 -f 13826 13865 13756 -f 13864 13826 13849 -f 13849 13826 13827 -f 13849 13827 13816 -f 13849 13816 13860 -f 13860 13816 13811 -f 13860 13811 13757 -f 13757 13811 13758 -f 13758 13811 13810 -f 13758 13810 13848 -f 13755 13767 13759 -f 13759 13767 13848 -f 13759 13848 13810 -f 13761 13762 13760 -f 13760 13762 13763 -f 13768 13769 13848 -f 13761 13767 13766 -f 13770 13764 13769 -f 13763 13765 13760 -f 13761 13766 13762 -f 13767 13761 13768 -f 13767 13768 13848 -f 13848 13769 13764 -f 13764 13770 13765 -f 13765 13770 13760 -f 13771 13786 13772 -f 13771 13772 13783 -f 13771 13778 13786 -f 13786 13778 13789 -f 13773 13794 13774 -f 13773 13774 13780 -f 13780 13774 13789 -f 13780 13789 13778 -f 13776 13781 13782 -f 13777 13773 13780 -f 13773 13777 13775 -f 13773 13775 13808 -f 13775 13776 13808 -f 13808 13776 13782 -f 13771 13783 13779 -f 13777 13778 13779 -f 13779 13778 13771 -f 13777 13780 13778 -f 13782 13781 13783 -f 13783 13781 13779 -f 13765 13784 13764 -f 13764 13784 13818 -f 13764 13818 13785 -f 13785 13818 13782 -f 13785 13782 13772 -f 13772 13782 13783 -f 13787 13772 13786 -f 13772 13787 13788 -f 13772 13788 13785 -f 13795 13792 13789 -f 13785 13788 13791 -f 13785 13791 13790 -f 13790 13791 13793 -f 13795 13789 13774 -f 13789 13792 13786 -f 13786 13792 13787 -f 13790 13793 13794 -f 13793 13795 13794 -f 13795 13774 13794 -f 13794 13773 13790 -f 13790 13773 13808 -f 13790 13808 13807 -f 13790 13807 13850 -f 13850 13807 13809 -f 13850 13809 13856 -f 13856 13809 13796 -f 13856 13796 13867 -f 13867 13796 13797 -f 13867 13797 13813 -f 13867 13813 13798 -f 13798 13813 13853 -f 13853 13813 13825 -f 13863 13853 13814 -f 13814 13853 13825 -f 13854 13863 13822 -f 13822 13863 13814 -f 13855 13815 13821 -f 13855 13821 13851 -f 13851 13821 13799 -f 13851 13799 13852 -f 13852 13799 13800 -f 13852 13800 13869 -f 13869 13800 13801 -f 13801 13800 13820 -f 13801 13820 13802 -f 13802 13820 13819 -f 13802 13819 13803 -f 13802 13803 13866 -f 13866 13803 13804 -f 13804 13803 13805 -f 13804 13805 13806 -f 13806 13805 13815 -f 13806 13815 13855 -f 13807 13808 13782 -f 13818 13809 13782 -f 13782 13809 13807 -f 13759 13810 13818 -f 13818 13810 13811 -f 13818 13811 13842 -f 13842 13811 13816 -f 13880 13826 13756 -f 13880 13756 13882 -f 13812 13813 13842 -f 13842 13813 13797 -f 13842 13797 13818 -f 13818 13797 13796 -f 13825 13800 13814 -f 13814 13800 13799 -f 13822 13815 13805 -f 13842 13816 13827 -f 13842 13823 13817 -f 13817 13823 13872 -f 13818 13796 13809 -f 13825 13819 13820 -f 13825 13820 13800 -f 13799 13821 13814 -f 13814 13821 13815 -f 13814 13815 13822 -f 13812 13822 13813 -f 13813 13822 13803 -f 13813 13803 13825 -f 13825 13803 13819 -f 13827 13875 13842 -f 13842 13875 13823 -f 13872 13824 13817 -f 13817 13824 13756 -f 13756 13824 13882 -f 13805 13803 13822 -f 13880 13879 13826 -f 13827 13877 13875 -f 13826 13879 13877 -f 13826 13877 13827 -f 13857 13854 13812 -f 13812 13854 13822 -f 13845 13846 13836 -f 13836 13846 13841 -f 13845 13836 13828 -f 13828 13836 13837 -f 13828 13837 13844 -f 13844 13837 13835 -f 13830 13844 13833 -f 13833 13844 13835 -f 13829 13830 13832 -f 13832 13830 13833 -f 13859 13831 13838 -f 13837 13834 13835 -f 13831 13836 13841 -f 13832 13833 13834 -f 13834 13833 13835 -f 13836 13831 13837 -f 13837 13831 13834 -f 13841 13840 13831 -f 13831 13840 13838 -f 13839 13842 13838 -f 13839 13838 13840 -f 13839 13840 13847 -f 13847 13840 13841 -f 13847 13841 13846 -f 13858 13857 13839 -f 13839 13857 13812 -f 13839 13812 13842 -f 13838 13842 13859 -f 13844 13830 13829 -f 13829 13843 13844 -f 13844 13843 13828 -f 13828 13843 13858 -f 13828 13858 13845 -f 13845 13858 13846 -f 13846 13858 13847 -f 13847 13858 13839 -f 13859 13849 13860 -f 13758 13848 13764 -f 13873 13864 13849 -f 13785 13790 13850 -f 13785 13850 13764 -f 13764 13850 13856 -f 13857 13804 13854 -f 13854 13804 13806 -f 13852 13869 13853 -f 13806 13855 13854 -f 13854 13855 13863 -f 13863 13855 13851 -f 13864 13878 13865 -f 13870 13873 13849 -f 13870 13849 13859 -f 13866 13804 13764 -f 13764 13804 13861 -f 13861 13804 13857 -f 13861 13857 13858 -f 13859 13860 13861 -f 13861 13860 13757 -f 13861 13757 13764 -f 13764 13757 13758 -f 13878 13862 13865 -f 13852 13853 13863 -f 13852 13863 13851 -f 13873 13874 13864 -f 13864 13874 13876 -f 13864 13876 13878 -f 13862 13881 13865 -f 13856 13867 13764 -f 13764 13867 13866 -f 13866 13867 13798 -f 13798 13801 13802 -f 13798 13802 13866 -f 13870 13871 13868 -f 13870 13868 13873 -f 13853 13869 13801 -f 13853 13801 13798 -f 13865 13881 13871 -f 13865 13871 13870 -f 13871 13824 13872 -f 13871 13872 13868 -f 13868 13872 13823 -f 13868 13823 13873 -f 13873 13823 13875 -f 13873 13875 13874 -f 13874 13875 13876 -f 13876 13875 13877 -f 13876 13877 13878 -f 13878 13877 13879 -f 13878 13879 13880 -f 13878 13880 13862 -f 13862 13880 13882 -f 13862 13882 13881 -f 13881 13882 13824 -f 13881 13824 13871 -f 13883 13897 13885 -f 13887 13903 13898 -f 13895 13899 13884 -f 13885 13895 13886 -f 13886 13895 13884 -f 13883 13885 13886 -f 13887 13898 13883 -f 13883 13898 13897 -f 13901 13903 13907 -f 13900 13901 13888 -f 13888 13901 13907 -f 13884 13899 13888 -f 13888 13899 13900 -f 13907 13903 13887 -f 13911 13915 13912 -f 13915 13913 13912 -f 13892 13889 13893 -f 13893 13889 13911 -f 13893 13911 13894 -f 13894 13911 13912 -f 13894 13912 13896 -f 13896 13912 13914 -f 13896 13914 13891 -f 13891 13914 13913 -f 13891 13913 13902 -f 13902 13913 13915 -f 13902 13915 13890 -f 13890 13915 13916 -f 13890 13916 13892 -f 13892 13916 13889 -f 13897 13892 13893 -f 13897 13893 13885 -f 13885 13893 13894 -f 13885 13894 13895 -f 13895 13894 13896 -f 13895 13896 13899 -f 13899 13896 13900 -f 13900 13896 13891 -f 13900 13891 13902 -f 13900 13902 13901 -f 13903 13902 13890 -f 13903 13890 13898 -f 13898 13890 13892 -f 13898 13892 13897 -f 13901 13902 13903 -f 13884 13888 13910 -f 13910 13888 13909 -f 13886 13884 13904 -f 13904 13884 13910 -f 13883 13886 13905 -f 13905 13886 13904 -f 13887 13883 13906 -f 13906 13883 13905 -f 13907 13887 13908 -f 13908 13887 13906 -f 13888 13907 13909 -f 13909 13907 13908 -f 13908 13906 13909 -f 13909 13906 13905 -f 13909 13905 13910 -f 13910 13905 13904 -f 13914 13912 13913 -f 13916 13915 13911 -f 13916 13911 13889 -f 13920 13935 13936 -f 13921 13940 13918 -f 13919 13937 13917 -f 13917 13937 13932 -f 13920 13936 13919 -f 13919 13936 13937 -f 13918 13940 13920 -f 13920 13940 13935 -f 13923 13939 13921 -f 13922 13938 13939 -f 13922 13939 13923 -f 13932 13938 13917 -f 13917 13938 13922 -f 13923 13921 13918 -f 13949 13948 13926 -f 13934 13947 13930 -f 13930 13947 13948 -f 13930 13948 13931 -f 13931 13948 13924 -f 13931 13924 13925 -f 13931 13925 13929 -f 13929 13925 13949 -f 13929 13949 13928 -f 13928 13949 13950 -f 13928 13950 13927 -f 13927 13950 13926 -f 13927 13926 13933 -f 13933 13926 13947 -f 13933 13947 13934 -f 13935 13934 13936 -f 13936 13934 13930 -f 13936 13930 13931 -f 13936 13931 13937 -f 13937 13931 13932 -f 13932 13931 13929 -f 13932 13929 13938 -f 13938 13929 13928 -f 13938 13928 13939 -f 13939 13928 13927 -f 13939 13927 13921 -f 13921 13927 13940 -f 13940 13927 13933 -f 13940 13933 13935 -f 13935 13933 13934 -f 13917 13922 13946 -f 13946 13922 13943 -f 13919 13917 13941 -f 13941 13917 13946 -f 13920 13919 13945 -f 13945 13919 13941 -f 13918 13920 13944 -f 13944 13920 13945 -f 13923 13918 13942 -f 13942 13918 13944 -f 13922 13923 13943 -f 13943 13923 13942 -f 13942 13944 13943 -f 13943 13944 13945 -f 13943 13945 13946 -f 13946 13945 13941 -f 13947 13926 13948 -f 13924 13948 13949 -f 13924 13949 13925 -f 13950 13949 13926 -f 13954 13972 13973 -f 13951 13967 13971 -f 13971 13972 13953 -f 13953 13972 13954 -f 13951 13971 13953 -f 13952 13976 13967 -f 13952 13967 13951 -f 13974 13975 13956 -f 13956 13975 13955 -f 13954 13973 13956 -f 13956 13973 13974 -f 13975 13976 13955 -f 13955 13976 13952 -f 13985 13960 13958 -f 13969 13985 13957 -f 13969 13957 13965 -f 13965 13957 13966 -f 13966 13957 13958 -f 13966 13958 13959 -f 13966 13959 13964 -f 13964 13959 13983 -f 13964 13983 13963 -f 13963 13983 13960 -f 13963 13960 13962 -f 13962 13960 13984 -f 13962 13984 13961 -f 13961 13984 13985 -f 13961 13985 13969 -f 13967 13969 13970 -f 13970 13969 13965 -f 13970 13965 13971 -f 13971 13965 13966 -f 13971 13966 13972 -f 13972 13966 13973 -f 13973 13966 13964 -f 13973 13964 13974 -f 13974 13964 13963 -f 13974 13963 13968 -f 13968 13963 13962 -f 13968 13962 13975 -f 13975 13962 13961 -f 13975 13961 13976 -f 13976 13961 13969 -f 13976 13969 13967 -f 13967 13970 13971 -f 13974 13968 13975 -f 13954 13956 13981 -f 13981 13956 13978 -f 13953 13954 13977 -f 13977 13954 13981 -f 13951 13953 13982 -f 13982 13953 13977 -f 13952 13951 13980 -f 13980 13951 13982 -f 13955 13952 13979 -f 13979 13952 13980 -f 13956 13955 13978 -f 13978 13955 13979 -f 13979 13980 13978 -f 13978 13980 13982 -f 13978 13982 13981 -f 13981 13982 13977 -f 13957 13985 13958 -f 13959 13958 13960 -f 13959 13960 13983 -f 13984 13960 13985 -f 13991 14102 14105 -f 13991 14105 14001 -f 14001 14105 14107 -f 14001 14107 14108 -f 14001 14108 14000 -f 14000 13986 13999 -f 13999 13986 13987 -f 13999 13987 13994 -f 13994 13987 14106 -f 13994 14106 13995 -f 13995 14106 14101 -f 13995 14101 13993 -f 13993 14101 14104 -f 13993 14104 14103 -f 13993 14103 13988 -f 13988 13989 13997 -f 13997 13989 13990 -f 13997 13990 13998 -f 13998 13990 14102 -f 13998 14102 13991 -f 14003 13998 13992 -f 13992 13998 13991 -f 13992 13991 14010 -f 13996 13993 13988 -f 13996 13988 14004 -f 13996 13995 13993 -f 14006 13994 14005 -f 14005 13994 13995 -f 14005 13995 13996 -f 14004 13988 13997 -f 14004 13997 14003 -f 14003 13997 13998 -f 14007 14000 13999 -f 14007 13999 14006 -f 14006 13999 13994 -f 14009 14001 14000 -f 14009 14000 14007 -f 14010 13991 14001 -f 14010 14001 14009 -f 13992 14014 14003 -f 14002 14003 14014 -f 14002 14004 14003 -f 14013 14004 14002 -f 14013 13996 14004 -f 14011 13996 14013 -f 13996 14011 14005 -f 14012 14005 14011 -f 14005 14012 14006 -f 14006 14012 14008 -f 14008 14007 14006 -f 14009 14007 14008 -f 13992 14010 14014 -f 14009 14017 14010 -f 14010 14017 14014 -f 14012 14015 14008 -f 14008 14017 14009 -f 14008 14015 14017 -f 14014 14017 14002 -f 14002 14016 14013 -f 14013 14016 14011 -f 14011 14015 14012 -f 14002 14017 14016 -f 14011 14016 14015 -f 14015 14016 14017 -f 14029 14028 14018 -f 14029 14018 14019 -f 14019 14018 14100 -f 14019 14100 14020 -f 14020 14021 14099 -f 14020 14099 14033 -f 14033 14099 14022 -f 14022 14099 14023 -f 14022 14023 14024 -f 14024 14023 14097 -f 14024 14097 14025 -f 14025 14097 14095 -f 14025 14095 14026 -f 14026 14096 14031 -f 14031 14096 14027 -f 14031 14027 14032 -f 14032 14027 14098 -f 14032 14098 14030 -f 14030 14098 14028 -f 14030 14028 14029 -f 14035 14030 14034 -f 14034 14030 14029 -f 14034 14029 14039 -f 14036 14026 14031 -f 14037 14025 14041 -f 14041 14025 14026 -f 14041 14026 14036 -f 14044 14022 14037 -f 14037 14022 14024 -f 14037 14024 14025 -f 14036 14031 14035 -f 14035 14031 14032 -f 14035 14032 14030 -f 14038 14033 14044 -f 14044 14033 14022 -f 14039 14020 14038 -f 14038 14020 14033 -f 14039 14029 14019 -f 14039 14019 14020 -f 14034 14047 14035 -f 14035 14047 14045 -f 14045 14036 14035 -f 14041 14040 14037 -f 14043 14038 14044 -f 14038 14046 14039 -f 14042 14039 14046 -f 14039 14042 14034 -f 14034 14042 14047 -f 14046 14038 14043 -f 14044 14037 14040 -f 14044 14040 14043 -f 14045 14049 14036 -f 14036 14049 14041 -f 14041 14049 14040 -f 14043 14048 14046 -f 14046 14048 14042 -f 14042 14048 14047 -f 14045 14047 14049 -f 14040 14049 14043 -f 14043 14049 14048 -f 14047 14048 14049 -f 14050 14063 14065 -f 14063 14050 14360 -f 14065 14358 14405 -f 14398 14053 14397 -f 14059 14405 14054 -f 14398 14061 14055 -f 14052 14356 14051 -f 14358 14054 14405 -f 14052 14051 14397 -f 14053 14398 14055 -f 14054 14060 14059 -f 14056 14057 14058 -f 14063 14358 14065 -f 14404 14059 14060 -f 14343 14360 14050 -f 14342 14051 14356 -f 14061 14349 14055 -f 14061 14062 14349 -f 14342 14356 14355 -f 14060 14364 14404 -f 14364 14064 14404 -f 14090 14381 14395 -f 14342 14355 14066 -f 14062 14351 14349 -f 14070 14067 14363 -f 14072 14343 14066 -f 14062 14071 14351 -f 14363 14067 14364 -f 14375 14076 14068 -f 14069 14072 14353 -f 14353 14073 14069 -f 14343 14342 14066 -f 14073 14361 14069 -f 14375 14373 14073 -f 14345 14056 14058 -f 14074 14070 14363 -f 14074 14361 14070 -f 14353 14056 14345 -f 14071 14058 14351 -f 14073 14353 14345 -f 14072 14066 14353 -f 14345 14385 14075 -f 14345 14386 14385 -f 14084 14079 14091 -f 14361 14073 14070 -f 14345 14075 14076 -f 14345 14077 14386 -f 14375 14073 14076 -f 14053 14052 14397 -f 14077 14387 14386 -f 14369 14375 14068 -f 14068 14331 14369 -f 14390 14087 14068 -f 14387 14077 14078 -f 14331 14371 14369 -f 14073 14345 14076 -f 14079 14084 14402 -f 14382 14387 14078 -f 14331 14083 14371 -f 14080 14087 14390 -f 14078 14391 14382 -f 14084 14082 14402 -f 14072 14360 14343 -f 14402 14082 14081 -f 14383 14382 14391 -f 14090 14333 14080 -f 14383 14391 14085 -f 14083 14372 14371 -f 14058 14057 14351 -f 14081 14082 14400 -f 14082 14086 14400 -f 14083 14330 14372 -f 14067 14064 14364 -f 14330 14088 14372 -f 14085 14381 14383 -f 14373 14091 14073 -f 14085 14394 14381 -f 14087 14331 14068 -f 14088 14330 14089 -f 14381 14394 14395 -f 14089 14400 14086 -f 14079 14073 14091 -f 14086 14088 14089 -f 14333 14087 14080 -f 14134 14132 14133 -f 14133 14132 14135 -f 14333 14090 14395 -f 14135 14131 14130 -f 14136 14135 14130 -f 14093 14136 14092 -f 14136 14130 14092 -f 14126 14129 14128 -f 14093 14092 14129 -f 14132 14131 14135 -f 14126 14093 14129 -f 14126 14128 14094 -f 14026 14095 14096 -f 14097 14023 14098 -f 14095 14097 14096 -f 14097 14027 14096 -f 14097 14098 14027 -f 14098 14023 14028 -f 14023 14099 14028 -f 14018 14028 14099 -f 14094 14128 14127 -f 14100 14018 14099 -f 14099 14021 14100 -f 14103 13989 13988 -f 13987 13986 14108 -f 13990 13989 14103 -f 14103 14104 13990 -f 14021 14020 14100 -f 14102 13990 14101 -f 14104 14101 13990 -f 14102 14101 14105 -f 14106 13987 14105 -f 14107 14105 13987 -f 14101 14106 14105 -f 14107 13987 14108 -f 14109 14114 14279 -f 14277 14276 14279 -f 14114 14277 14279 -f 14123 14161 14162 -f 14110 14292 14291 -f 14276 14219 14279 -f 14219 14280 14279 -f 14219 14282 14281 -f 14219 14284 14282 -f 14219 14111 14284 -f 14111 14110 14284 -f 14111 14292 14110 -f 14110 14291 14112 -f 14110 14112 14113 -f 13986 14000 14108 -f 14116 14287 14113 -f 14208 14206 14289 -f 14115 14116 14113 -f 14113 14117 14115 -f 14117 14289 14115 -f 14117 14209 14289 -f 14215 14214 14162 -f 14209 14208 14289 -f 14122 14211 14118 -f 14161 14217 14121 -f 14206 14122 14289 -f 14122 14118 14289 -f 14122 14212 14211 -f 14122 14119 14212 -f 14122 14120 14119 -f 14120 14161 14119 -f 14120 14217 14161 -f 14161 14121 14216 -f 14161 14216 14162 -f 14287 14110 14113 -f 14214 14123 14162 -f 14219 14281 14280 -f 14162 14124 14215 -f 14145 14093 14126 -f 14145 14126 14125 -f 14125 14126 14094 -f 14125 14094 14143 -f 14143 14094 14127 -f 14127 14128 14142 -f 14142 14128 14129 -f 14142 14129 14092 -f 14142 14092 14141 -f 14141 14092 14130 -f 14141 14130 14139 -f 14139 14130 14131 -f 14139 14131 14140 -f 14140 14131 14132 -f 14140 14132 14134 -f 14134 14133 14135 -f 14134 14135 14137 -f 14137 14135 14136 -f 14137 14136 14145 -f 14145 14136 14093 -f 14146 14137 14138 -f 14138 14137 14145 -f 14149 14140 14134 -f 14149 14134 14147 -f 14152 14139 14140 -f 14152 14140 14149 -f 14150 14142 14141 -f 14150 14141 14152 -f 14152 14141 14139 -f 14147 14134 14146 -f 14146 14134 14137 -f 14151 14127 14142 -f 14151 14142 14150 -f 14144 14143 14151 -f 14151 14143 14127 -f 14138 14145 14125 -f 14138 14125 14144 -f 14144 14125 14143 -f 14138 14154 14146 -f 14148 14146 14154 -f 14148 14147 14146 -f 14157 14147 14148 -f 14157 14149 14147 -f 14149 14157 14153 -f 14149 14153 14152 -f 14152 14156 14150 -f 14150 14156 14151 -f 14155 14144 14158 -f 14158 14144 14151 -f 14144 14155 14138 -f 14138 14155 14154 -f 14158 14151 14156 -f 14155 14159 14154 -f 14154 14159 14148 -f 14148 14160 14157 -f 14152 14153 14156 -f 14158 14159 14155 -f 14157 14160 14153 -f 14159 14160 14148 -f 14156 14159 14158 -f 14153 14160 14156 -f 14156 14160 14159 -f 14205 14218 14122 -f 14122 14218 14120 -f 14119 14161 14213 -f 14213 14161 14168 -f 14124 14162 14163 -f 14163 14162 14166 -f 14165 14218 14181 -f 14181 14218 14205 -f 14164 14218 14165 -f 14188 14163 14165 -f 14165 14163 14166 -f 14165 14166 14164 -f 14188 14167 14213 -f 14210 14167 14227 -f 14227 14167 14181 -f 14227 14181 14207 -f 14181 14205 14207 -f 14213 14168 14188 -f 14168 14169 14188 -f 14188 14169 14163 -f 14210 14213 14167 -f 14167 14188 14171 -f 14167 14171 14170 -f 14170 14171 14204 -f 14170 14204 14185 -f 14199 14198 14196 -f 14199 14196 14172 -f 14172 14196 14173 -f 14172 14173 14174 -f 14174 14173 14194 -f 14174 14194 14184 -f 14184 14194 14165 -f 14184 14165 14181 -f 14186 14195 14179 -f 14179 14195 14175 -f 14179 14175 14176 -f 14176 14175 14187 -f 14176 14187 14180 -f 14180 14187 14192 -f 14180 14192 14177 -f 14177 14192 14191 -f 14177 14191 14178 -f 14178 14191 14190 -f 14178 14190 14182 -f 14182 14190 14189 -f 14182 14189 14183 -f 14183 14189 14193 -f 14183 14193 14202 -f 14202 14193 14197 -f 14186 14179 14167 -f 14179 14176 14167 -f 14167 14176 14180 -f 14167 14180 14181 -f 14180 14177 14181 -f 14181 14177 14178 -f 14181 14178 14182 -f 14182 14183 14181 -f 14181 14183 14202 -f 14181 14202 14184 -f 14184 14202 14174 -f 14167 14170 14186 -f 14186 14170 14185 -f 14200 14199 14202 -f 14202 14199 14172 -f 14202 14172 14174 -f 14171 14188 14195 -f 14195 14188 14175 -f 14165 14193 14189 -f 14165 14192 14188 -f 14188 14192 14187 -f 14188 14187 14175 -f 14189 14190 14165 -f 14165 14190 14191 -f 14165 14191 14192 -f 14193 14165 14197 -f 14197 14165 14194 -f 14197 14194 14173 -f 14203 14204 14195 -f 14195 14204 14171 -f 14173 14196 14197 -f 14197 14196 14198 -f 14197 14198 14201 -f 14198 14199 14200 -f 14198 14200 14201 -f 14201 14200 14202 -f 14201 14202 14197 -f 14195 14186 14203 -f 14203 14186 14185 -f 14203 14185 14204 -f 14205 14122 14206 -f 14205 14206 14207 -f 14207 14206 14208 -f 14207 14208 14209 -f 14207 14209 14227 -f 14227 14209 14117 -f 14210 14289 14118 -f 14210 14118 14211 -f 14210 14211 14213 -f 14213 14211 14212 -f 14213 14212 14119 -f 14168 14161 14123 -f 14168 14123 14169 -f 14169 14123 14214 -f 14169 14214 14215 -f 14169 14215 14163 -f 14163 14215 14124 -f 14166 14162 14216 -f 14166 14216 14164 -f 14164 14216 14121 -f 14164 14121 14218 -f 14218 14121 14217 -f 14218 14217 14120 -f 14273 14224 14219 -f 14219 14224 14111 -f 14109 14279 14278 -f 14278 14279 14220 -f 14284 14110 14285 -f 14285 14110 14222 -f 14227 14117 14113 -f 14290 14227 14113 -f 14223 14224 14242 -f 14242 14224 14273 -f 14242 14273 14274 -f 14210 14223 14225 -f 14210 14225 14288 -f 14290 14293 14223 -f 14242 14274 14275 -f 14221 14285 14225 -f 14225 14285 14222 -f 14225 14222 14286 -f 14275 14278 14242 -f 14242 14278 14221 -f 14221 14278 14220 -f 14223 14293 14224 -f 14225 14286 14288 -f 14220 14226 14221 -f 14226 14283 14221 -f 14221 14283 14285 -f 14223 14227 14290 -f 14223 14210 14227 -f 14221 14225 14247 -f 14221 14247 14228 -f 14228 14247 14272 -f 14228 14272 14246 -f 14229 14256 14251 -f 14229 14251 14230 -f 14230 14251 14232 -f 14230 14232 14231 -f 14231 14232 14223 -f 14231 14223 14242 -f 14245 14253 14233 -f 14233 14253 14248 -f 14233 14248 14240 -f 14240 14248 14234 -f 14240 14234 14236 -f 14236 14234 14235 -f 14236 14235 14241 -f 14241 14235 14237 -f 14241 14237 14243 -f 14243 14237 14249 -f 14243 14249 14244 -f 14244 14249 14250 -f 14244 14250 14238 -f 14238 14250 14239 -f 14238 14239 14265 -f 14265 14239 14252 -f 14245 14233 14221 -f 14233 14240 14221 -f 14221 14240 14236 -f 14221 14236 14242 -f 14236 14241 14242 -f 14242 14241 14243 -f 14242 14243 14244 -f 14244 14238 14242 -f 14242 14238 14265 -f 14242 14265 14231 -f 14270 14268 14245 -f 14221 14228 14245 -f 14245 14228 14246 -f 14245 14246 14270 -f 14268 14267 14245 -f 14245 14267 14266 -f 14263 14257 14229 -f 14263 14229 14265 -f 14265 14229 14230 -f 14265 14230 14231 -f 14257 14263 14262 -f 14257 14262 14258 -f 14247 14225 14253 -f 14253 14225 14248 -f 14223 14235 14225 -f 14225 14235 14234 -f 14225 14234 14248 -f 14250 14249 14223 -f 14223 14249 14237 -f 14223 14237 14235 -f 14232 14252 14223 -f 14223 14252 14239 -f 14223 14239 14250 -f 14232 14251 14252 -f 14252 14251 14256 -f 14252 14256 14264 -f 14264 14256 14259 -f 14269 14271 14254 -f 14254 14271 14253 -f 14253 14271 14272 -f 14253 14272 14247 -f 14260 14261 14259 -f 14259 14261 14264 -f 14254 14255 14269 -f 14256 14229 14257 -f 14256 14257 14259 -f 14259 14257 14258 -f 14259 14258 14260 -f 14260 14258 14262 -f 14260 14262 14261 -f 14261 14262 14263 -f 14261 14263 14264 -f 14264 14263 14265 -f 14264 14265 14252 -f 14253 14245 14254 -f 14254 14245 14266 -f 14254 14266 14255 -f 14255 14266 14267 -f 14255 14267 14268 -f 14255 14268 14269 -f 14269 14268 14270 -f 14269 14270 14271 -f 14271 14270 14246 -f 14271 14246 14272 -f 14273 14219 14276 -f 14273 14276 14274 -f 14274 14276 14275 -f 14275 14276 14277 -f 14275 14277 14114 -f 14275 14114 14278 -f 14278 14114 14109 -f 14220 14279 14280 -f 14220 14280 14226 -f 14226 14280 14281 -f 14226 14281 14283 -f 14283 14281 14282 -f 14283 14282 14285 -f 14285 14282 14284 -f 14222 14110 14287 -f 14222 14287 14286 -f 14286 14287 14288 -f 14288 14287 14116 -f 14288 14116 14115 -f 14288 14115 14289 -f 14288 14289 14210 -f 14290 14113 14112 -f 14290 14112 14291 -f 14290 14291 14293 -f 14293 14291 14292 -f 14293 14292 14224 -f 14224 14292 14111 -f 14295 14307 14314 -f 14294 14313 14306 -f 14296 14307 14295 -f 14294 14306 14296 -f 14296 14306 14307 -f 14323 14318 14313 -f 14323 14313 14294 -f 14324 14316 14317 -f 14315 14316 14297 -f 14314 14315 14297 -f 14297 14316 14324 -f 14295 14314 14297 -f 14324 14317 14323 -f 14323 14317 14318 -f 14328 14298 14299 -f 14302 14298 14300 -f 14302 14300 14305 -f 14305 14300 14327 -f 14305 14327 14304 -f 14304 14327 14328 -f 14304 14328 14308 -f 14308 14328 14301 -f 14308 14301 14310 -f 14310 14301 14299 -f 14310 14299 14303 -f 14303 14299 14329 -f 14303 14329 14311 -f 14311 14329 14298 -f 14311 14298 14302 -f 14312 14302 14313 -f 14313 14302 14305 -f 14313 14305 14306 -f 14306 14305 14304 -f 14306 14304 14307 -f 14307 14304 14308 -f 14314 14308 14309 -f 14309 14308 14310 -f 14309 14310 14315 -f 14315 14310 14303 -f 14315 14303 14316 -f 14316 14303 14311 -f 14316 14311 14317 -f 14317 14311 14318 -f 14318 14311 14302 -f 14318 14302 14312 -f 14307 14308 14314 -f 14314 14309 14315 -f 14318 14312 14313 -f 14295 14297 14319 -f 14319 14297 14320 -f 14296 14295 14321 -f 14321 14295 14319 -f 14294 14296 14322 -f 14322 14296 14321 -f 14323 14294 14326 -f 14326 14294 14322 -f 14324 14323 14325 -f 14325 14323 14326 -f 14297 14324 14320 -f 14320 14324 14325 -f 14325 14326 14320 -f 14320 14326 14322 -f 14320 14322 14319 -f 14319 14322 14321 -f 14300 14298 14328 -f 14300 14328 14327 -f 14301 14328 14299 -f 14329 14299 14298 -f 15792 14089 14330 -f 15792 14330 15796 -f 14330 14083 15796 -f 15796 14083 14331 -f 15796 14331 14332 -f 14395 14396 14333 -f 14333 14396 14334 -f 14333 14334 14087 -f 14087 14334 14332 -f 14087 14332 14331 -f 14403 14064 14335 -f 14335 14064 14067 -f 14335 14067 14336 -f 14336 14067 14070 -f 14336 14070 14337 -f 14337 14070 14073 -f 14337 14073 14338 -f 14338 14073 14079 -f 14338 14079 15799 -f 15799 14079 14402 -f 14339 14050 15816 -f 15816 14050 14065 -f 15816 14065 14405 -f 15807 14397 14340 -f 14340 14397 14051 -f 14340 14051 14341 -f 14051 14342 14341 -f 14341 14342 14339 -f 14339 14342 14343 -f 14339 14343 14050 -f 15798 14078 14344 -f 14344 14078 14077 -f 14344 14077 15802 -f 15802 14077 14345 -f 15802 14345 15803 -f 15803 14345 14058 -f 15803 14058 15805 -f 15805 14058 14071 -f 15805 14071 15808 -f 15808 14071 14062 -f 14346 15809 14354 -f 14354 15809 14352 -f 14352 15809 14347 -f 14350 14347 14348 -f 14346 14356 14052 -f 14346 14052 15818 -f 15818 14052 14053 -f 15818 14053 14348 -f 14348 14053 14055 -f 14348 14055 14349 -f 14348 14349 14350 -f 14350 14349 14351 -f 14350 14351 14347 -f 14347 14351 14352 -f 14352 14351 14057 -f 14352 14057 14056 -f 14352 14056 14353 -f 14352 14353 14354 -f 14354 14353 14066 -f 14354 14066 14355 -f 14354 14355 14346 -f 14346 14355 14356 -f 14362 15810 15804 -f 14362 15804 14359 -f 14359 15804 14357 -f 14365 14060 14054 -f 14365 14054 15812 -f 15812 14054 14358 -f 15812 14358 14357 -f 14357 14358 14063 -f 14357 14063 14359 -f 14359 14063 14360 -f 14359 14360 14072 -f 14359 14072 14069 -f 14359 14069 14362 -f 14362 14069 14361 -f 14362 14361 14074 -f 14362 14074 14363 -f 14362 14363 15810 -f 15810 14363 14364 -f 15810 14364 14060 -f 15810 14060 14365 -f 14366 14374 15794 -f 15794 14374 14367 -f 14367 14374 15797 -f 15797 14374 14370 -f 15797 14370 14368 -f 15797 14368 15800 -f 14368 14088 15800 -f 15800 14088 14086 -f 14374 14375 14369 -f 14374 14369 14371 -f 14374 14371 14370 -f 14370 14371 14372 -f 14370 14372 14368 -f 14368 14372 14088 -f 14376 14084 14366 -f 14366 14084 14091 -f 14366 14091 14374 -f 14374 14091 14373 -f 14374 14373 14375 -f 15800 14086 15806 -f 15806 14086 14082 -f 15806 14082 14376 -f 14376 14082 14084 -f 14388 14389 14377 -f 14377 14389 14384 -f 14377 14384 15801 -f 15801 14384 14378 -f 15814 14383 14381 -f 15814 14381 14380 -f 14380 14381 14090 -f 14378 14387 14379 -f 14379 14387 14382 -f 14379 14382 14383 -f 14379 14383 15814 -f 14389 14076 14384 -f 14384 14076 14075 -f 14384 14075 14385 -f 14384 14385 14378 -f 14378 14385 14386 -f 14378 14386 14387 -f 14380 14090 14388 -f 14388 14090 14080 -f 14388 14080 14389 -f 14389 14080 14390 -f 14389 14390 14068 -f 14389 14068 14076 -f 14078 15798 14391 -f 14391 15798 14392 -f 14391 14392 14085 -f 14085 14392 15793 -f 14085 15793 14394 -f 15793 14393 14394 -f 14394 14393 14395 -f 14397 15807 14398 -f 15807 15817 14398 -f 14398 15817 14061 -f 14061 15817 15811 -f 14061 15811 14062 -f 15811 15808 14062 -f 14089 15792 14399 -f 14089 14399 14400 -f 14400 15791 14401 -f 14400 14401 14081 -f 14081 14401 15799 -f 14081 15799 14402 -f 14064 14403 14404 -f 14404 14403 15815 -f 14404 15815 14059 -f 14059 15815 15813 -f 14059 15813 15795 -f 14059 15795 14405 -f 14405 15795 15816 -f 14450 14413 14451 -f 14451 14413 14414 -f 14451 14414 14415 -f 14451 14415 14453 -f 14453 14415 14411 -f 14453 14411 14406 -f 14406 14411 14454 -f 14454 14411 14407 -f 14454 14407 14419 -f 14454 14419 14408 -f 14408 14419 14418 -f 14408 14418 14452 -f 14452 14418 14409 -f 14452 14409 14449 -f 14449 14409 14417 -f 14449 14417 14412 -f 14449 14412 14446 -f 14446 14412 14416 -f 14446 14416 14448 -f 14448 14416 14410 -f 14448 14410 14450 -f 14450 14410 14413 -f 14430 14411 14415 -f 14411 14430 14428 -f 14416 14421 14413 -f 14416 14413 14410 -f 14423 14412 14417 -f 14414 14430 14415 -f 14413 14430 14414 -f 14412 14423 14421 -f 14412 14421 14416 -f 14419 14428 14418 -f 14409 14423 14417 -f 14411 14428 14407 -f 14418 14428 14423 -f 14418 14423 14409 -f 14407 14428 14419 -f 14429 14430 14431 -f 14429 14431 14441 -f 14433 14420 14438 -f 14421 14420 14413 -f 14420 14421 14438 -f 14438 14421 14434 -f 14422 14434 14421 -f 14421 14424 14422 -f 14423 14424 14421 -f 14424 14423 14425 -f 14425 14436 14424 -f 14428 14425 14423 -f 14426 14425 14427 -f 14427 14425 14428 -f 14429 14427 14428 -f 14430 14429 14428 -f 14420 14431 14430 -f 14420 14430 14413 -f 14422 14437 14434 -f 14422 14424 14437 -f 14437 14424 14436 -f 14436 14425 14426 -f 14426 14427 14432 -f 14429 14432 14427 -f 14432 14429 14441 -f 14441 14431 14433 -f 14431 14420 14433 -f 14440 14434 14444 -f 14444 14436 14435 -f 14444 14437 14436 -f 14444 14434 14437 -f 14440 14433 14438 -f 14439 14441 14442 -f 14439 14432 14441 -f 14443 14432 14439 -f 14440 14438 14434 -f 14442 14433 14440 -f 14442 14441 14433 -f 14443 14426 14432 -f 14435 14436 14426 -f 14435 14426 14443 -f 14442 14477 14476 -f 14442 14476 14439 -f 14439 14476 14443 -f 14443 14476 14479 -f 14443 14479 14475 -f 14443 14475 14435 -f 14435 14475 14474 -f 14435 14474 14444 -f 14444 14474 14445 -f 14444 14445 14440 -f 14440 14445 14477 -f 14440 14477 14442 -f 14446 14464 14449 -f 14448 14447 14446 -f 14446 14447 14464 -f 14447 14448 14467 -f 14455 14450 14451 -f 14406 14458 14453 -f 14450 14467 14448 -f 14450 14455 14467 -f 14454 14458 14406 -f 14458 14408 14463 -f 14449 14464 14463 -f 14449 14463 14452 -f 14452 14463 14408 -f 14458 14455 14453 -f 14453 14455 14451 -f 14408 14458 14454 -f 14459 14469 14457 -f 14458 14463 14462 -f 14458 14462 14461 -f 14463 14471 14478 -f 14464 14447 14471 -f 14467 14455 14456 -f 14457 14456 14455 -f 14455 14458 14457 -f 14459 14457 14458 -f 14461 14460 14459 -f 14459 14458 14461 -f 14478 14462 14463 -f 14463 14464 14471 -f 14465 14471 14447 -f 14466 14465 14447 -f 14447 14467 14466 -f 14473 14466 14467 -f 14473 14467 14456 -f 14456 14457 14468 -f 14468 14457 14469 -f 14459 14460 14469 -f 14462 14470 14460 -f 14462 14460 14461 -f 14470 14462 14478 -f 14465 14466 14472 -f 14472 14466 14473 -f 14468 14473 14456 -f 14477 14473 14468 -f 14475 14478 14471 -f 14475 14471 14474 -f 14476 14469 14460 -f 14445 14472 14473 -f 14445 14473 14477 -f 14479 14460 14470 -f 14479 14470 14475 -f 14474 14471 14465 -f 14470 14478 14475 -f 14476 14460 14479 -f 14477 14468 14476 -f 14476 14468 14469 -f 14474 14465 14445 -f 14445 14465 14472 -f 14480 14512 14482 -f 14513 14512 14480 -f 14482 14512 14510 -f 14482 14510 14483 -f 14484 14507 14481 -f 14481 14507 14513 -f 14483 14510 14484 -f 14484 14510 14507 -f 14522 14489 14523 -f 14522 14524 14489 -f 14522 14495 14524 -f 14494 14521 14485 -f 14485 14521 14522 -f 14485 14522 14498 -f 14498 14522 14501 -f 14501 14522 14486 -f 14501 14486 14487 -f 14487 14486 14523 -f 14487 14523 14488 -f 14487 14488 14500 -f 14500 14488 14490 -f 14490 14488 14489 -f 14490 14489 14499 -f 14499 14489 14491 -f 14499 14491 14492 -f 14492 14491 14524 -f 14492 14524 14497 -f 14497 14524 14525 -f 14497 14525 14526 -f 14497 14526 14493 -f 14493 14526 14495 -f 14493 14495 14494 -f 14494 14495 14521 -f 14499 14503 14490 -f 14490 14503 14504 -f 14494 14496 14493 -f 14485 14506 14496 -f 14485 14496 14494 -f 14497 14502 14492 -f 14493 14502 14497 -f 14493 14496 14502 -f 14498 14506 14485 -f 14492 14502 14503 -f 14492 14503 14499 -f 14500 14504 14487 -f 14501 14505 14498 -f 14498 14505 14506 -f 14487 14504 14505 -f 14487 14505 14501 -f 14490 14504 14500 -f 14496 14511 14502 -f 14502 14514 14503 -f 14503 14514 14504 -f 14505 14509 14506 -f 14506 14511 14496 -f 14505 14504 14508 -f 14504 14514 14507 -f 14508 14504 14507 -f 14510 14508 14507 -f 14510 14509 14508 -f 14505 14508 14509 -f 14512 14509 14510 -f 14512 14506 14509 -f 14511 14506 14512 -f 14513 14511 14512 -f 14502 14511 14513 -f 14514 14502 14513 -f 14507 14514 14513 -f 14480 14482 14515 -f 14515 14482 14520 -f 14513 14480 14518 -f 14518 14480 14515 -f 14481 14513 14516 -f 14516 14513 14518 -f 14484 14481 14517 -f 14517 14481 14516 -f 14483 14484 14519 -f 14519 14484 14517 -f 14482 14483 14520 -f 14520 14483 14519 -f 14516 14518 14517 -f 14517 14518 14515 -f 14517 14515 14519 -f 14519 14515 14520 -f 14521 14495 14522 -f 14486 14522 14523 -f 14488 14523 14489 -f 14491 14489 14524 -f 14525 14524 14495 -f 14525 14495 14526 -f 14527 14551 14528 -f 14553 14527 14529 -f 14528 14551 14557 -f 14530 14557 14553 -f 14567 14565 14563 -f 14566 14565 14567 -f 14567 14570 14568 -f 14563 14570 14567 -f 14540 14563 14542 -f 14542 14563 14531 -f 14542 14531 14532 -f 14532 14531 14564 -f 14532 14564 14533 -f 14533 14564 14565 -f 14533 14565 14535 -f 14535 14565 14534 -f 14535 14534 14546 -f 14546 14534 14566 -f 14546 14566 14544 -f 14544 14566 14536 -f 14544 14536 14567 -f 14544 14567 14545 -f 14545 14567 14537 -f 14545 14537 14568 -f 14545 14568 14538 -f 14538 14568 14569 -f 14538 14569 14539 -f 14539 14569 14570 -f 14539 14570 14540 -f 14540 14570 14563 -f 14544 14554 14555 -f 14540 14547 14539 -f 14542 14549 14540 -f 14540 14549 14547 -f 14538 14541 14554 -f 14538 14554 14545 -f 14539 14541 14538 -f 14539 14547 14541 -f 14542 14543 14549 -f 14532 14543 14542 -f 14545 14554 14544 -f 14546 14555 14535 -f 14533 14548 14532 -f 14532 14548 14543 -f 14535 14555 14548 -f 14535 14548 14533 -f 14544 14555 14546 -f 14547 14552 14541 -f 14541 14552 14554 -f 14555 14553 14550 -f 14553 14557 14550 -f 14548 14555 14550 -f 14551 14550 14557 -f 14543 14548 14550 -f 14550 14551 14543 -f 14549 14543 14551 -f 14547 14549 14551 -f 14527 14547 14551 -f 14552 14547 14527 -f 14553 14552 14527 -f 14554 14552 14553 -f 14555 14554 14553 -f 14527 14528 14556 -f 14556 14528 14558 -f 14529 14527 14560 -f 14560 14527 14556 -f 14553 14529 14559 -f 14559 14529 14560 -f 14530 14553 14561 -f 14561 14553 14559 -f 14557 14530 14562 -f 14562 14530 14561 -f 14528 14557 14558 -f 14558 14557 14562 -f 14559 14560 14561 -f 14561 14560 14556 -f 14561 14556 14562 -f 14562 14556 14558 -f 14531 14563 14565 -f 14531 14565 14564 -f 14565 14566 14534 -f 14536 14566 14567 -f 14567 14568 14537 -f 14569 14568 14570 -f 14601 14596 14573 -f 14609 14578 14606 -f 14606 14611 14609 -f 14613 14611 14606 -f 14582 14605 14575 -f 14575 14605 14606 -f 14575 14606 14586 -f 14586 14606 14576 -f 14586 14576 14607 -f 14586 14607 14588 -f 14588 14607 14577 -f 14577 14607 14578 -f 14577 14578 14579 -f 14579 14578 14608 -f 14579 14608 14589 -f 14589 14608 14609 -f 14589 14609 14587 -f 14587 14609 14611 -f 14587 14611 14610 -f 14587 14610 14580 -f 14580 14610 14612 -f 14580 14612 14613 -f 14580 14613 14585 -f 14585 14613 14582 -f 14582 14613 14581 -f 14582 14581 14605 -f 14589 14590 14591 -f 14582 14584 14585 -f 14575 14583 14582 -f 14582 14583 14584 -f 14580 14584 14590 -f 14580 14590 14587 -f 14585 14584 14580 -f 14586 14593 14575 -f 14575 14593 14583 -f 14587 14590 14589 -f 14579 14591 14577 -f 14588 14592 14586 -f 14586 14592 14593 -f 14577 14591 14592 -f 14577 14592 14588 -f 14589 14591 14579 -f 14595 14590 14584 -f 14590 14597 14591 -f 14594 14591 14597 -f 14591 14594 14592 -f 14594 14597 14596 -f 14601 14594 14596 -f 14592 14594 14601 -f 14601 14571 14592 -f 14593 14592 14571 -f 14571 14583 14593 -f 14571 14572 14583 -f 14572 14584 14583 -f 14595 14584 14572 -f 14595 14572 14574 -f 14595 14574 14596 -f 14590 14595 14596 -f 14597 14590 14596 -f 14572 14571 14603 -f 14603 14571 14604 -f 14574 14572 14598 -f 14598 14572 14603 -f 14596 14574 14599 -f 14599 14574 14598 -f 14573 14596 14600 -f 14600 14596 14599 -f 14601 14573 14602 -f 14602 14573 14600 -f 14571 14601 14604 -f 14604 14601 14602 -f 14599 14598 14600 -f 14600 14598 14603 -f 14600 14603 14602 -f 14602 14603 14604 -f 14581 14606 14605 -f 14576 14606 14607 -f 14607 14606 14578 -f 14578 14609 14608 -f 14610 14611 14612 -f 14612 14611 14613 -f 14581 14613 14606 -f 14651 14650 14656 -f 14654 14652 14651 -f 14651 14621 14654 -f 14656 14621 14651 -f 14622 14657 14650 -f 14622 14650 14625 -f 14625 14650 14651 -f 14625 14651 14629 -f 14629 14651 14617 -f 14629 14617 14632 -f 14632 14617 14652 -f 14632 14652 14618 -f 14618 14652 14619 -f 14618 14619 14620 -f 14620 14619 14653 -f 14620 14653 14626 -f 14626 14653 14654 -f 14626 14654 14621 -f 14626 14621 14627 -f 14627 14621 14655 -f 14627 14655 14623 -f 14623 14655 14624 -f 14624 14655 14656 -f 14624 14656 14657 -f 14624 14657 14622 -f 14626 14628 14620 -f 14620 14628 14636 -f 14622 14634 14624 -f 14625 14631 14622 -f 14622 14631 14634 -f 14623 14634 14627 -f 14627 14634 14639 -f 14624 14634 14623 -f 14629 14631 14625 -f 14627 14639 14626 -f 14626 14639 14628 -f 14618 14636 14632 -f 14629 14630 14631 -f 14632 14636 14630 -f 14632 14630 14629 -f 14620 14636 14618 -f 14631 14633 14634 -f 14638 14634 14633 -f 14638 14639 14634 -f 14640 14628 14639 -f 14628 14640 14636 -f 14636 14640 14635 -f 14636 14635 14630 -f 14635 14637 14630 -f 14630 14637 14631 -f 14637 14633 14631 -f 14635 14640 14616 -f 14616 14615 14635 -f 14635 14615 14637 -f 14641 14637 14615 -f 14633 14637 14641 -f 14633 14641 14614 -f 14638 14633 14614 -f 14642 14638 14614 -f 14638 14642 14639 -f 14640 14639 14642 -f 14642 14644 14640 -f 14640 14644 14616 -f 14614 14641 14647 -f 14647 14641 14649 -f 14642 14614 14646 -f 14646 14614 14647 -f 14644 14642 14643 -f 14643 14642 14646 -f 14616 14644 14645 -f 14645 14644 14643 -f 14615 14616 14648 -f 14648 14616 14645 -f 14641 14615 14649 -f 14649 14615 14648 -f 14643 14646 14645 -f 14645 14646 14647 -f 14645 14647 14648 -f 14648 14647 14649 -f 14617 14651 14652 -f 14619 14652 14653 -f 14653 14652 14654 -f 14655 14621 14656 -f 14657 14656 14650 -f 14677 14673 14674 -f 14658 14670 14672 -f 14672 14673 14681 -f 14681 14673 14677 -f 14658 14672 14681 -f 14659 14676 14670 -f 14659 14670 14658 -f 14675 14661 14678 -f 14678 14661 14660 -f 14677 14674 14678 -f 14678 14674 14675 -f 14661 14676 14660 -f 14660 14676 14659 -f 14692 14690 14687 -f 14662 14692 14686 -f 14662 14686 14665 -f 14665 14686 14666 -f 14666 14686 14687 -f 14666 14687 14688 -f 14666 14688 14667 -f 14667 14688 14689 -f 14667 14689 14664 -f 14664 14689 14690 -f 14664 14690 14663 -f 14663 14690 14691 -f 14663 14691 14669 -f 14669 14691 14692 -f 14669 14692 14662 -f 14670 14662 14671 -f 14671 14662 14665 -f 14671 14665 14672 -f 14672 14665 14666 -f 14672 14666 14673 -f 14673 14666 14674 -f 14674 14666 14667 -f 14674 14667 14675 -f 14675 14667 14664 -f 14675 14664 14668 -f 14668 14664 14663 -f 14668 14663 14661 -f 14661 14663 14669 -f 14661 14669 14676 -f 14676 14669 14662 -f 14676 14662 14670 -f 14670 14671 14672 -f 14675 14668 14661 -f 14677 14678 14679 -f 14679 14678 14683 -f 14681 14677 14680 -f 14680 14677 14679 -f 14658 14681 14685 -f 14685 14681 14680 -f 14659 14658 14682 -f 14682 14658 14685 -f 14660 14659 14684 -f 14684 14659 14682 -f 14678 14660 14683 -f 14683 14660 14684 -f 14684 14682 14683 -f 14683 14682 14685 -f 14683 14685 14679 -f 14679 14685 14680 -f 14686 14692 14687 -f 14688 14687 14690 -f 14688 14690 14689 -f 14691 14690 14692 -f 14698 14709 14711 -f 14695 14705 14708 -f 14693 14709 14698 -f 14695 14708 14693 -f 14693 14708 14709 -f 14699 14694 14705 -f 14699 14705 14695 -f 14697 14714 14696 -f 14713 14714 14716 -f 14711 14713 14716 -f 14716 14714 14697 -f 14698 14711 14716 -f 14697 14696 14699 -f 14699 14696 14694 -f 14700 14728 14726 -f 14702 14728 14723 -f 14702 14723 14703 -f 14703 14723 14724 -f 14703 14724 14704 -f 14704 14724 14700 -f 14704 14700 14710 -f 14710 14700 14725 -f 14710 14725 14701 -f 14701 14725 14726 -f 14701 14726 14706 -f 14706 14726 14727 -f 14706 14727 14707 -f 14707 14727 14728 -f 14707 14728 14702 -f 14715 14702 14705 -f 14705 14702 14703 -f 14705 14703 14708 -f 14708 14703 14704 -f 14708 14704 14709 -f 14709 14704 14710 -f 14711 14710 14712 -f 14712 14710 14701 -f 14712 14701 14713 -f 14713 14701 14706 -f 14713 14706 14714 -f 14714 14706 14707 -f 14714 14707 14696 -f 14696 14707 14694 -f 14694 14707 14702 -f 14694 14702 14715 -f 14709 14710 14711 -f 14711 14712 14713 -f 14694 14715 14705 -f 14698 14716 14717 -f 14717 14716 14720 -f 14693 14698 14722 -f 14722 14698 14717 -f 14695 14693 14721 -f 14721 14693 14722 -f 14699 14695 14719 -f 14719 14695 14721 -f 14697 14699 14718 -f 14718 14699 14719 -f 14716 14697 14720 -f 14720 14697 14718 -f 14718 14719 14720 -f 14720 14719 14721 -f 14720 14721 14717 -f 14717 14721 14722 -f 14723 14728 14700 -f 14723 14700 14724 -f 14725 14700 14726 -f 14727 14726 14728 -f 14730 14748 14744 -f 14729 14741 14743 -f 14745 14746 14749 -f 14744 14745 14752 -f 14752 14745 14749 -f 14730 14744 14752 -f 14729 14743 14730 -f 14730 14743 14748 -f 14740 14741 14732 -f 14738 14740 14731 -f 14731 14740 14732 -f 14749 14746 14731 -f 14731 14746 14738 -f 14732 14741 14729 -f 14757 14760 14733 -f 14760 14758 14733 -f 14734 14762 14736 -f 14736 14762 14757 -f 14736 14757 14737 -f 14737 14757 14733 -f 14737 14733 14735 -f 14735 14733 14759 -f 14735 14759 14739 -f 14739 14759 14758 -f 14739 14758 14747 -f 14747 14758 14760 -f 14747 14760 14742 -f 14742 14760 14761 -f 14742 14761 14734 -f 14734 14761 14762 -f 14748 14734 14736 -f 14748 14736 14744 -f 14744 14736 14737 -f 14744 14737 14745 -f 14745 14737 14735 -f 14745 14735 14746 -f 14746 14735 14738 -f 14738 14735 14739 -f 14738 14739 14747 -f 14738 14747 14740 -f 14741 14747 14742 -f 14741 14742 14743 -f 14743 14742 14734 -f 14743 14734 14748 -f 14740 14747 14741 -f 14749 14731 14751 -f 14751 14731 14755 -f 14752 14749 14750 -f 14750 14749 14751 -f 14730 14752 14756 -f 14756 14752 14750 -f 14729 14730 14753 -f 14753 14730 14756 -f 14732 14729 14754 -f 14754 14729 14753 -f 14731 14732 14755 -f 14755 14732 14754 -f 14754 14753 14755 -f 14755 14753 14756 -f 14755 14756 14751 -f 14751 14756 14750 -f 14759 14733 14758 -f 14761 14760 14757 -f 14761 14757 14762 -f 14766 14785 14764 -f 14765 14781 14788 -f 14788 14781 14783 -f 14763 14782 14765 -f 14765 14782 14781 -f 14764 14785 14763 -f 14763 14785 14782 -f 14768 14784 14766 -f 14767 14779 14784 -f 14767 14784 14768 -f 14783 14779 14788 -f 14788 14779 14767 -f 14768 14766 14764 -f 14769 14794 14796 -f 14774 14793 14776 -f 14776 14793 14794 -f 14776 14794 14777 -f 14777 14794 14795 -f 14777 14795 14770 -f 14777 14770 14775 -f 14775 14770 14769 -f 14775 14769 14780 -f 14780 14769 14771 -f 14780 14771 14773 -f 14773 14771 14796 -f 14773 14796 14772 -f 14772 14796 14793 -f 14772 14793 14774 -f 14778 14774 14782 -f 14782 14774 14776 -f 14782 14776 14781 -f 14781 14776 14777 -f 14781 14777 14783 -f 14783 14777 14775 -f 14783 14775 14779 -f 14779 14775 14780 -f 14779 14780 14784 -f 14784 14780 14773 -f 14784 14773 14766 -f 14766 14773 14785 -f 14785 14773 14772 -f 14785 14772 14778 -f 14778 14772 14774 -f 14785 14778 14782 -f 14788 14767 14786 -f 14786 14767 14790 -f 14765 14788 14787 -f 14787 14788 14786 -f 14763 14765 14789 -f 14789 14765 14787 -f 14764 14763 14792 -f 14792 14763 14789 -f 14768 14764 14791 -f 14791 14764 14792 -f 14767 14768 14790 -f 14790 14768 14791 -f 14791 14792 14790 -f 14790 14792 14789 -f 14790 14789 14786 -f 14786 14789 14787 -f 14793 14796 14794 -f 14795 14794 14769 -f 14795 14769 14770 -f 14771 14769 14796 -f 14873 14797 15978 -f 15978 14797 14798 -f 15978 14798 15982 -f 14798 15939 15982 -f 15982 15939 14799 -f 15982 14799 14800 -f 14799 15908 14800 -f 14800 15908 15938 -f 14800 15938 14801 -f 14801 15938 15930 -f 14801 15930 15980 -f 15980 15930 14802 -f 15980 14802 15966 -f 15966 14802 15940 -f 15966 15940 15947 -f 15947 15940 15937 -f 15891 14803 15961 -f 15961 14803 15962 -f 15968 14883 15954 -f 15954 14883 15887 -f 15954 15887 15956 -f 15956 15887 15876 -f 15956 15876 15958 -f 15958 15876 15888 -f 15958 15888 14804 -f 14804 15888 15891 -f 14804 15891 14805 -f 14805 15891 15961 -f 14807 15981 15905 -f 15905 15981 15962 -f 15905 15962 14806 -f 14806 15962 14803 -f 14882 14881 15921 -f 15921 14881 15963 -f 15921 15963 14807 -f 14807 15963 15981 -f 15957 14809 15872 -f 15872 14809 15848 -f 15854 14808 15857 -f 15857 14808 15944 -f 15857 15944 15866 -f 15866 15944 15957 -f 15866 15957 15886 -f 15886 15957 15872 -f 15848 14809 14810 -f 14810 14809 14811 -f 14810 14811 15852 -f 15852 14811 15945 -f 15852 15945 15860 -f 15860 15945 15946 -f 15948 15861 15860 -f 15948 15860 15946 -f 15870 14812 15880 -f 15880 14812 15965 -f 15880 15965 15883 -f 14813 15924 15974 -f 15974 15924 15907 -f 15974 15907 14814 -f 15974 14814 14815 -f 14815 14814 15916 -f 14815 15916 14816 -f 14816 15916 14817 -f 14816 14817 15960 -f 15960 14817 15909 -f 15960 15909 15959 -f 15959 15909 15893 -f 15959 15893 14818 -f 14818 15893 15892 -f 14818 15892 14819 -f 14819 15892 15883 -f 14819 15883 15965 -f 14827 14828 14820 -f 14820 15898 14823 -f 14820 14823 14821 -f 14821 14823 14824 -f 14821 14824 14822 -f 14822 14824 15873 -f 14822 15873 15879 -f 14822 15879 15943 -f 15943 15879 14825 -f 15943 14825 14826 -f 15943 14826 14827 -f 14827 14826 15877 -f 14827 15877 15853 -f 14827 15853 14828 -f 14828 15853 15856 -f 14828 15856 14820 -f 14820 15856 15898 -f 14836 15868 14829 -f 14829 15868 15900 -f 14829 15900 15902 -f 14829 15902 14830 -f 14830 15902 15855 -f 14830 15855 14832 -f 14830 14832 14831 -f 14831 14832 15942 -f 15942 14832 14833 -f 15942 14833 15901 -f 15942 15901 15919 -f 15942 15919 14834 -f 14834 15919 14835 -f 14834 14835 15915 -f 14834 15915 15874 -f 14834 15874 14836 -f 14836 15874 15871 -f 14836 15871 15868 -f 14840 14837 14839 -f 14838 14839 14844 -f 14839 14847 15903 -f 14839 15903 14840 -f 14840 15903 15922 -f 14840 15922 15911 -f 14840 15911 14837 -f 14837 15911 15912 -f 14837 15912 14841 -f 14837 14841 14842 -f 14837 14842 14843 -f 14843 14842 14845 -f 14843 14845 14844 -f 14844 14845 14846 -f 14844 14846 15926 -f 14844 15926 14838 -f 14838 15926 14847 -f 14838 14847 14839 -f 15941 15917 15906 -f 15941 15906 15929 -f 15941 15929 14849 -f 14849 15929 15934 -f 14851 14852 15917 -f 14851 15917 15941 -f 14850 15918 14851 -f 14851 15918 14852 -f 14849 15934 14853 -f 14849 14853 14848 -f 14848 14853 14854 -f 14848 14854 14850 -f 14850 14854 14855 -f 14850 14855 15918 -f 15924 14813 15964 -f 15924 15964 14856 -f 14856 15964 15969 -f 14856 15969 14857 -f 14857 15969 14858 -f 14857 14858 15928 -f 15928 14858 15979 -f 15928 15979 14859 -f 14859 15979 14860 -f 14859 14860 15931 -f 15931 14860 14861 -f 15931 14861 15932 -f 15932 14861 15950 -f 15932 15950 15935 -f 15935 15950 15976 -f 15935 15976 15884 -f 15884 15976 15947 -f 15884 15947 15937 -f 15948 14862 15861 -f 15861 14862 15849 -f 15849 14862 15851 -f 15851 14862 14863 -f 15851 14863 14865 -f 15851 14865 14864 -f 14864 14865 14867 -f 14864 14867 14866 -f 14866 14867 14869 -f 14866 14869 14868 -f 14868 14869 15863 -f 14869 15983 15863 -f 15863 15983 14870 -f 15863 14870 15864 -f 15864 14870 14871 -f 15864 14871 14872 -f 14872 14871 14812 -f 14872 14812 15870 -f 14797 14873 14874 -f 14797 14874 14875 -f 14875 14874 15973 -f 14875 15973 15933 -f 15933 15973 15977 -f 15933 15977 15936 -f 15936 15977 14876 -f 15936 14876 14877 -f 14877 14876 15972 -f 14877 15972 14878 -f 14878 15972 15971 -f 14878 15971 14879 -f 14879 15971 15970 -f 14879 15970 14880 -f 14880 15970 15927 -f 15970 15951 15927 -f 15927 15951 14881 -f 15927 14881 14882 -f 14883 15968 15953 -f 14883 15953 15867 -f 15867 15953 14884 -f 15867 14884 15865 -f 15865 14884 15952 -f 15865 15952 15862 -f 15862 15952 15975 -f 15862 15975 15882 -f 15882 15975 15967 -f 15882 15967 15858 -f 15858 15967 15949 -f 15858 15949 14885 -f 14885 15949 15955 -f 14885 15955 14886 -f 14886 15955 15850 -f 15955 14887 15850 -f 15850 14887 14808 -f 15850 14808 15854 -f 15894 15835 14888 -f 15890 15829 15897 -f 15897 15829 15825 -f 15897 15825 15823 -f 15820 15859 14890 -f 14890 15859 15904 -f 14890 15904 14891 -f 14891 15904 15878 -f 14891 15878 15885 -f 15828 14906 15826 -f 15826 14906 15889 -f 15826 15889 15824 -f 14892 15914 15845 -f 14893 15925 14894 -f 14893 14894 14895 -f 14913 14896 14897 -f 14897 14896 15840 -f 14897 15840 14909 -f 14898 14899 15839 -f 15839 14899 14900 -f 15839 14900 15910 -f 15837 15910 15896 -f 15837 15896 14901 -f 15913 14903 14902 -f 14902 14903 15841 -f 14902 15841 14904 -f 15897 15823 15885 -f 15885 15823 15819 -f 15859 15820 14905 -f 15859 14905 15875 -f 15824 15889 15875 -f 15824 15875 14905 -f 14906 15828 14907 -f 15835 15894 15834 -f 15834 15894 14907 -f 15834 14907 15828 -f 15869 14889 14908 -f 15869 14908 15899 -f 15899 14908 15829 -f 15899 15829 15890 -f 14909 15840 14910 -f 14909 14910 14911 -f 14910 15838 14911 -f 14911 15838 14901 -f 14901 15838 15833 -f 14898 15839 15920 -f 15920 15839 15590 -f 15920 15590 15881 -f 15881 15590 15913 -f 15913 15590 14903 -f 14893 14895 14912 -f 14893 14912 14896 -f 14893 14896 14913 -f 15923 14904 15841 -f 15841 15843 15923 -f 15923 15843 15914 -f 15914 15843 15847 -f 15914 15847 15845 -f 14963 14921 14919 -f 14919 14921 14920 -f 15081 14914 14972 -f 14914 15081 14915 -f 14976 14916 15076 -f 14976 15076 15029 -f 15026 14958 14982 -f 15022 14958 15026 -f 15067 14927 14985 -f 14927 14926 14985 -f 15003 14929 14943 -f 15013 14933 14917 -f 14933 15013 15009 -f 15007 14918 14947 -f 15018 15017 14951 -f 15017 15001 14951 -f 14962 15030 14961 -f 14961 15030 15032 -f 14963 14919 15038 -f 15038 14919 14964 -f 14965 15040 14920 -f 14920 14921 14965 -f 15083 14974 14955 -f 15079 14922 14978 -f 15012 14922 14979 -f 14980 14983 14959 -f 14923 15084 14983 -f 14923 14983 14984 -f 15073 14931 14987 -f 15065 14929 15003 -f 14931 14930 14932 -f 14990 14934 14991 -f 14934 14935 14993 -f 14996 15008 14994 -f 14995 14994 14945 -f 14918 15007 15006 -f 15008 14996 14936 -f 14936 14996 14937 -f 14937 14997 14936 -f 14936 14997 14999 -f 14995 15056 14939 -f 14939 15056 14940 -f 14940 15002 14939 -f 14939 15002 14941 -f 14944 14929 15004 -f 15070 15073 14987 -f 15070 14987 15005 -f 15005 14987 14929 -f 15005 14929 14944 -f 15070 15005 14931 -f 14944 14942 15005 -f 14931 15005 14942 -f 14942 14944 14943 -f 14943 14944 15003 -f 14948 14918 15009 -f 15008 14995 14946 -f 14946 14995 14945 -f 14946 14945 14948 -f 14948 14945 14918 -f 15008 14946 14994 -f 14946 14948 14947 -f 14994 14946 14947 -f 14947 14948 15007 -f 15012 15079 14978 -f 15012 14978 14949 -f 14949 14978 14976 -f 14949 14976 15011 -f 15012 14977 14922 -f 15011 14916 14949 -f 14977 14949 14916 -f 15012 14949 14977 -f 14916 15011 15076 -f 14950 14933 15014 -f 15066 14990 15016 -f 15016 14990 14991 -f 15016 14991 15015 -f 15015 14991 14933 -f 15015 14933 14950 -f 15066 14992 14934 -f 14950 14917 15015 -f 15016 14917 14992 -f 15066 15016 14992 -f 14917 14950 15013 -f 15020 15001 15017 -f 15020 15017 15021 -f 14995 14938 15019 -f 15019 14938 15000 -f 15019 15000 15001 -f 15019 15001 15020 -f 15020 14951 14952 -f 15020 14952 15019 -f 15056 15019 14952 -f 14951 15020 15018 -f 14954 14926 14927 -f 14954 14927 15022 -f 15023 15068 14925 -f 15023 14925 15024 -f 15024 14925 14926 -f 15024 14926 14954 -f 15023 14953 14928 -f 15023 15024 14953 -f 14954 14924 15024 -f 14953 15024 14924 -f 14924 14954 14985 -f 14954 15022 14985 -f 14957 14914 15082 -f 15083 14955 15025 -f 15025 14955 14971 -f 15025 14971 14957 -f 14957 14971 14914 -f 15083 15025 14956 -f 15083 14956 14975 -f 14975 14956 14974 -f 14957 14972 14956 -f 14957 14956 15025 -f 15081 14957 15082 -f 14972 14957 15081 -f 15027 14958 15022 -f 15027 15022 15029 -f 15084 14980 15028 -f 15028 14980 14959 -f 15028 14959 15027 -f 15027 14959 14958 -f 14981 15028 14960 -f 14983 15028 14981 -f 15084 15028 14983 -f 14960 15027 14982 -f 14961 15033 15087 -f 14962 14961 15087 -f 15034 15035 15032 -f 15032 15030 15034 -f 15100 15099 15038 -f 15038 15099 14965 -f 14921 14963 14965 -f 14965 14963 15038 -f 14919 14920 14964 -f 14964 14920 15040 -f 15096 15039 15040 -f 15040 15039 14964 -f 14967 15050 14966 -f 14967 14966 14968 -f 14967 14968 15115 -f 14969 15041 15043 -f 15112 14970 14969 -f 15102 15041 14969 -f 15102 14969 14970 -f 15102 14970 15118 -f 14914 14971 14956 -f 14972 14914 14956 -f 14956 14955 14974 -f 14971 14955 14956 -f 15083 14973 14974 -f 14974 14973 14975 -f 14975 14973 15052 -f 14916 14976 14977 -f 14978 14922 14977 -f 14976 14978 14977 -f 14922 15078 14979 -f 14979 15078 15080 -f 14981 14959 14983 -f 14958 14959 14960 -f 14960 14959 14981 -f 14982 14958 14960 -f 14984 15084 14923 -f 14953 15068 14928 -f 14953 14925 15068 -f 14926 14925 14924 -f 14924 14925 14953 -f 14985 14926 14924 -f 15068 15069 14928 -f 14928 15069 14986 -f 14986 15069 15053 -f 15053 15023 14986 -f 14986 15023 14928 -f 14942 14987 14931 -f 14929 14987 14942 -f 14943 14929 14942 -f 15073 14988 14930 -f 15073 14930 14931 -f 14930 14988 14932 -f 14932 14988 14989 -f 14989 15070 14932 -f 14932 15070 14931 -f 14991 14934 14992 -f 14933 14991 14992 -f 14917 14933 14992 -f 14993 14935 15063 -f 15063 15066 14993 -f 14993 15066 14934 -f 14994 14995 14996 -f 14947 14945 14994 -f 14918 14945 14947 -f 14996 14998 14997 -f 14996 14997 14937 -f 14997 14998 14999 -f 14999 14998 15060 -f 15060 15008 14999 -f 14999 15008 14936 -f 14938 15056 15000 -f 14952 15000 15056 -f 14952 15001 15000 -f 14951 15001 14952 -f 15056 15058 15002 -f 15056 15002 14940 -f 15002 15058 14941 -f 14941 15058 15057 -f 15057 14995 14941 -f 14941 14995 14939 -f 14944 15004 15003 -f 15004 14929 15065 -f 14948 15009 15007 -f 15009 14918 15006 -f 14976 15029 15011 -f 15011 15029 15010 -f 15010 15076 15011 -f 14950 15014 15013 -f 14933 15009 15014 -f 15015 14917 15016 -f 15020 15021 15018 -f 15019 15056 14995 -f 14985 15022 15067 -f 14914 14915 15082 -f 15026 14982 15029 -f 15027 15029 14982 -f 15027 14960 15028 -f 15050 14967 15111 -f 15125 15126 15087 -f 15087 15126 15034 -f 15030 14962 15034 -f 15034 14962 15087 -f 15123 15031 15035 -f 15035 15031 15033 -f 14961 15032 15033 -f 15033 15032 15035 -f 15091 15090 15036 -f 15036 15090 15089 -f 15094 15092 15093 -f 15093 15092 15037 -f 15100 15038 15039 -f 15039 15038 14964 -f 15096 15040 15099 -f 15099 15040 14965 -f 15097 15041 15102 -f 15043 15041 15097 -f 15097 15042 15043 -f 15104 15108 15044 -f 14966 15106 14968 -f 15106 15104 14968 -f 14968 15104 15044 -f 14968 15044 15115 -f 15115 15044 15108 -f 15114 15045 15113 -f 15113 15045 15046 -f 15047 14969 15042 -f 15042 14969 15043 -f 15048 14970 15109 -f 15109 14970 15112 -f 15117 15118 15048 -f 15048 15118 14970 -f 15152 15117 15109 -f 15109 15117 15048 -f 15119 15139 15049 -f 15049 15139 15138 -f 15107 15136 15120 -f 15120 15136 15155 -f 15050 15086 15051 -f 15051 14966 15050 -f 15083 14975 15052 -f 15098 15074 15054 -f 15098 15054 15095 -f 15095 15054 15055 -f 15055 15018 15059 -f 15017 15018 15055 -f 15059 15018 15021 -f 15059 15021 15061 -f 15061 15021 15054 -f 15054 15021 15017 -f 15054 15017 15055 -f 14995 15057 15074 -f 15074 15057 15058 -f 15074 15058 15056 -f 15054 14938 15061 -f 15061 14938 14995 -f 15074 15056 15054 -f 15054 15056 14938 -f 15059 15006 15007 -f 15059 15007 15062 -f 15007 15009 15062 -f 15061 15009 15006 -f 15061 15006 15059 -f 15072 15008 15060 -f 15072 15060 14995 -f 14995 15060 14998 -f 14995 14998 14996 -f 15061 14995 15009 -f 15009 14995 15008 -f 15009 15008 15072 -f 15062 15009 15013 -f 15062 15013 15064 -f 15013 15014 15064 -f 15064 15014 15066 -f 15066 15014 15009 -f 15072 14934 14990 -f 15072 14935 14934 -f 15073 15066 15063 -f 15073 15063 15072 -f 15072 15063 14935 -f 15072 14990 15009 -f 15009 14990 15066 -f 15064 15003 15067 -f 15067 15003 15004 -f 15067 15004 15070 -f 15070 15004 15066 -f 15066 15004 15065 -f 15066 15065 15064 -f 15064 15065 15003 -f 15068 15070 14989 -f 15068 14989 15073 -f 15073 14989 14988 -f 15066 15073 15070 -f 15070 15022 14927 -f 15070 14927 15067 -f 15072 15023 15053 -f 15072 15053 15068 -f 15068 15053 15069 -f 15070 15068 15022 -f 15022 15068 15023 -f 15022 15023 15072 -f 15022 15026 15067 -f 15067 15026 15071 -f 15026 15029 15071 -f 15072 14983 14980 -f 15072 14984 14983 -f 15084 14984 15072 -f 15072 14980 15022 -f 15022 14980 15029 -f 15029 14980 15084 -f 15122 15084 15072 -f 15072 15068 15073 -f 15072 14995 15074 -f 15029 15076 15071 -f 15071 15076 15075 -f 15075 15076 15010 -f 15075 15010 15077 -f 15077 15010 15029 -f 15080 15078 15084 -f 15084 14922 15079 -f 15078 14922 15084 -f 14979 15080 15012 -f 15012 15080 15084 -f 15084 15079 15029 -f 15029 15079 15077 -f 15077 15079 15012 -f 15077 15012 15084 -f 14915 15081 15075 -f 15075 15081 15085 -f 15085 15081 15082 -f 15085 15082 15121 -f 15121 15082 15077 -f 15077 15082 14915 -f 15077 14915 15075 -f 15122 15083 15052 -f 15122 15052 15084 -f 15084 15052 14973 -f 15084 14973 15083 -f 15084 15083 15077 -f 15077 15083 15121 -f 15121 15083 15122 -f 15075 15085 15046 -f 15075 15046 15071 -f 15095 15055 15045 -f 15045 15055 15059 -f 15045 15059 15062 -f 15062 15064 15045 -f 15045 15064 15067 -f 15045 15067 15046 -f 15046 15067 15071 -f 15086 15050 15110 -f 15110 15050 15111 -f 15125 15087 15031 -f 15031 15087 15033 -f 15123 15035 15126 -f 15126 15035 15034 -f 15088 15122 15072 -f 15088 15072 15101 -f 15101 15072 15074 -f 15127 15159 15036 -f 15036 15159 15091 -f 15161 15127 15089 -f 15089 15127 15036 -f 15089 15090 15161 -f 15161 15090 15162 -f 15159 15162 15091 -f 15091 15162 15090 -f 15037 15092 15129 -f 15129 15092 15128 -f 15131 15128 15094 -f 15094 15128 15092 -f 15130 15131 15093 -f 15093 15131 15094 -f 15129 15130 15037 -f 15037 15130 15093 -f 15095 15045 15098 -f 15098 15045 15114 -f 15099 15042 15096 -f 15096 15042 15097 -f 15096 15097 15039 -f 15039 15097 15146 -f 15039 15146 15100 -f 15100 15146 15145 -f 15114 15047 15098 -f 15098 15047 15042 -f 15098 15042 15074 -f 15074 15042 15099 -f 15074 15099 15100 -f 15074 15100 15101 -f 15101 15100 15145 -f 15097 15102 15146 -f 15146 15102 15116 -f 15103 15104 15120 -f 15120 15104 15107 -f 15105 15136 15107 -f 15106 14966 15105 -f 15106 15105 15107 -f 15106 15107 15104 -f 15104 15150 15108 -f 14969 15047 15114 -f 15150 15152 15108 -f 15108 15152 15109 -f 15108 15109 15115 -f 15115 15109 15112 -f 15113 15110 15111 -f 15111 15112 15113 -f 15112 15111 14967 -f 15112 14969 15113 -f 15113 14969 15114 -f 15112 14967 15115 -f 15118 15116 15102 -f 15117 15049 15118 -f 15118 15049 15138 -f 15118 15138 15116 -f 15119 15049 15149 -f 15149 15049 15117 -f 15149 15153 15119 -f 15119 15153 15139 -f 15120 15155 15103 -f 15103 15155 15154 -f 15051 15156 14966 -f 14966 15156 15105 -f 15122 15088 15124 -f 15086 15110 15113 -f 15123 15121 15122 -f 15123 15122 15031 -f 15031 15122 15124 -f 15031 15124 15125 -f 15125 15124 15156 -f 15125 15156 15126 -f 15126 15156 15051 -f 15126 15051 15123 -f 15123 15051 15086 -f 15123 15086 15121 -f 15121 15086 15113 -f 15121 15113 15085 -f 15085 15113 15046 -f 15088 15101 15124 -f 15124 15101 15145 -f 15133 15158 15134 -f 15167 15174 15169 -f 15169 15174 15171 -f 15169 15171 15132 -f 15169 15132 15135 -f 15135 15133 15169 -f 15160 15137 15155 -f 15135 15157 15133 -f 15169 15133 15134 -f 15132 15171 15160 -f 15157 15135 15163 -f 15163 15160 15136 -f 15160 15171 15137 -f 15139 15151 15142 -f 15136 15160 15155 -f 15137 15171 15151 -f 15138 15142 15148 -f 15138 15139 15142 -f 15134 15158 15143 -f 15143 15144 15140 -f 15151 15171 15141 -f 15142 15151 15141 -f 15142 15141 15165 -f 15147 15148 15164 -f 15140 15147 15164 -f 15140 15164 15170 -f 15143 15140 15170 -f 15165 15141 15170 -f 15164 15165 15170 -f 15158 15144 15143 -f 15170 15141 15175 -f 15145 15146 15140 -f 15140 15146 15147 -f 15147 15146 15148 -f 15148 15146 15116 -f 15116 15138 15148 -f 15153 15151 15139 -f 15149 15117 15152 -f 15150 15104 15103 -f 15137 15151 15153 -f 15152 15150 15149 -f 15149 15150 15103 -f 15149 15103 15153 -f 15153 15103 15154 -f 15153 15154 15137 -f 15154 15155 15137 -f 15105 15163 15136 -f 15156 15157 15105 -f 15105 15157 15163 -f 15124 15133 15156 -f 15156 15133 15157 -f 15140 15144 15145 -f 15145 15144 15158 -f 15145 15158 15124 -f 15124 15158 15133 -f 15162 15159 15163 -f 15163 15159 15160 -f 15159 15127 15160 -f 15160 15127 15132 -f 15127 15161 15132 -f 15132 15161 15135 -f 15161 15162 15135 -f 15135 15162 15163 -f 15129 15128 15164 -f 15164 15128 15165 -f 15128 15131 15165 -f 15165 15131 15142 -f 15131 15130 15142 -f 15142 15130 15148 -f 15130 15129 15148 -f 15148 15129 15164 -f 15190 15166 15167 -f 15190 15167 15169 -f 15190 15169 15168 -f 15168 15169 15176 -f 15182 15170 15181 -f 15181 15170 15180 -f 15184 15183 15171 -f 15171 15174 15184 -f 15184 15174 15172 -f 15172 15174 15173 -f 15186 15187 15175 -f 15186 15175 15141 -f 15186 15141 15185 -f 15166 15173 15167 -f 15167 15173 15174 -f 15143 15170 15182 -f 15143 15182 15134 -f 15134 15182 15176 -f 15134 15176 15169 -f 15177 15166 15190 -f 15178 15190 15168 -f 15178 15168 15194 -f 15194 15168 15179 -f 15179 15168 15176 -f 15170 15175 15180 -f 15180 15175 15187 -f 15180 15198 15181 -f 15181 15198 15199 -f 15182 15181 15199 -f 15183 15185 15171 -f 15171 15185 15141 -f 15173 15189 15172 -f 15172 15189 15831 -f 15172 15831 15830 -f 15200 15183 15184 -f 15830 15184 15172 -f 15185 15201 15821 -f 15185 15821 15186 -f 15186 15188 15187 -f 15173 15166 15189 -f 15189 15166 15177 -f 15176 15182 15179 -f 15179 15182 15191 -f 15194 15179 15196 -f 15832 15177 15178 -f 15178 15177 15190 -f 15180 15187 15198 -f 15198 15187 15188 -f 15199 15198 15836 -f 15182 15822 15191 -f 15191 15822 15195 -f 15831 15189 15193 -f 15184 15830 15827 -f 15184 15827 15200 -f 15185 15183 15201 -f 15201 15183 15200 -f 15192 15821 15201 -f 15197 15188 15821 -f 15821 15188 15186 -f 15832 15193 15177 -f 15177 15193 15189 -f 15195 15196 15191 -f 15191 15196 15179 -f 15197 15836 15188 -f 15188 15836 15198 -f 15822 15182 15199 -f 15827 15192 15200 -f 15200 15192 15201 -f 15212 15202 15544 -f 15202 15545 15544 -f 15202 15213 15545 -f 15202 15212 15213 -f 15545 15529 15521 -f 15224 15519 15520 -f 15224 15520 15521 -f 15521 15544 15545 -f 15211 15315 15258 -f 15258 15315 15241 -f 15242 15325 15209 -f 15209 15325 15203 -f 15247 15246 15238 -f 15238 15246 15306 -f 15204 15310 15237 -f 15237 15310 15307 -f 15205 15312 15233 -f 15233 15312 15234 -f 15253 15314 15231 -f 15231 15314 15327 -f 15203 15255 15209 -f 15209 15255 15208 -f 15241 15242 15258 -f 15258 15242 15209 -f 15258 15259 15210 -f 15210 15211 15258 -f 15212 15544 15518 -f 15212 15518 15213 -f 15214 15261 15530 -f 15530 15529 15518 -f 15518 15529 15213 -f 15289 15274 15287 -f 15287 15274 15275 -f 15276 15372 15223 -f 15223 15372 15286 -f 15278 15361 15272 -f 15272 15361 15359 -f 15218 15356 15269 -f 15269 15356 15357 -f 15281 15350 15268 -f 15268 15350 15354 -f 15221 15222 15265 -f 15265 15222 15351 -f 15223 15286 15285 -f 15285 15284 15223 -f 15275 15276 15287 -f 15287 15276 15223 -f 15287 15373 15289 -f 15386 15383 15385 -f 15386 15385 15388 -f 15388 15385 15384 -f 15293 15391 15395 -f 15293 15395 15389 -f 15389 15395 15390 -f 15390 15395 15479 -f 15295 15225 15224 -f 15224 15225 15519 -f 15296 15297 15299 -f 15300 15226 15301 -f 15226 15300 15227 -f 15300 15303 15227 -f 15230 15298 15412 -f 15253 15326 15323 -f 15206 15324 15207 -f 15207 15324 15326 -f 15207 15326 15253 -f 15207 15253 15231 -f 15207 15231 15232 -f 15232 15231 15327 -f 15205 15324 15321 -f 15250 15252 15249 -f 15252 15324 15249 -f 15249 15324 15205 -f 15249 15205 15233 -f 15249 15233 15251 -f 15251 15233 15234 -f 15204 15322 15319 -f 15248 15319 15236 -f 15236 15319 15235 -f 15235 15322 15236 -f 15236 15322 15204 -f 15236 15204 15237 -f 15236 15237 15308 -f 15308 15237 15307 -f 15247 15318 15316 -f 15245 15316 15243 -f 15243 15316 15317 -f 15317 15318 15243 -f 15243 15318 15247 -f 15243 15247 15238 -f 15243 15238 15239 -f 15239 15238 15306 -f 15418 15416 15240 -f 15418 15240 15211 -f 15211 15240 15315 -f 15241 15315 15320 -f 15241 15320 15242 -f 15325 15242 15320 -f 15203 15325 15257 -f 15257 15325 15414 -f 15243 15239 15245 -f 15245 15239 15244 -f 15244 15246 15245 -f 15245 15246 15247 -f 15245 15247 15316 -f 15236 15308 15248 -f 15248 15308 15309 -f 15309 15310 15248 -f 15248 15310 15204 -f 15248 15204 15319 -f 15249 15251 15250 -f 15250 15251 15311 -f 15311 15312 15250 -f 15250 15312 15205 -f 15250 15205 15252 -f 15252 15205 15321 -f 15207 15232 15206 -f 15206 15232 15313 -f 15313 15314 15206 -f 15206 15314 15253 -f 15206 15253 15324 -f 15324 15253 15323 -f 15254 15208 15256 -f 15256 15208 15255 -f 15256 15255 15257 -f 15257 15255 15203 -f 15209 15208 15258 -f 15258 15208 15259 -f 15259 15415 15210 -f 15210 15415 15417 -f 15210 15417 15211 -f 15211 15417 15418 -f 15328 15329 15434 -f 15328 15434 15430 -f 15430 15434 15330 -f 15438 15331 15437 -f 15438 15437 15439 -f 15439 15437 15440 -f 15214 15260 15261 -f 15261 15260 15515 -f 15263 15291 15262 -f 15337 15345 15341 -f 15337 15341 15340 -f 15342 15339 15341 -f 15290 15339 15346 -f 15449 15375 15374 -f 15374 15375 15450 -f 15334 15374 15336 -f 15348 15264 15349 -f 15349 15264 15347 -f 15221 15363 15282 -f 15220 15282 15266 -f 15266 15282 15362 -f 15362 15363 15266 -f 15266 15363 15221 -f 15266 15221 15265 -f 15266 15265 15352 -f 15352 15265 15351 -f 15281 15368 15364 -f 15219 15364 15267 -f 15267 15364 15369 -f 15369 15368 15267 -f 15267 15368 15281 -f 15267 15281 15268 -f 15267 15268 15355 -f 15355 15268 15354 -f 15218 15370 15367 -f 15217 15365 15270 -f 15365 15370 15270 -f 15270 15370 15218 -f 15270 15218 15269 -f 15270 15269 15279 -f 15279 15269 15357 -f 15278 15371 15271 -f 15215 15370 15216 -f 15216 15370 15371 -f 15216 15371 15278 -f 15216 15278 15272 -f 15216 15272 15277 -f 15277 15272 15359 -f 15288 15453 15273 -f 15288 15273 15289 -f 15289 15273 15274 -f 15275 15274 15366 -f 15275 15366 15276 -f 15372 15276 15366 -f 15286 15372 15459 -f 15459 15372 15455 -f 15216 15277 15215 -f 15215 15277 15360 -f 15360 15361 15215 -f 15215 15361 15278 -f 15215 15278 15370 -f 15370 15278 15271 -f 15270 15279 15217 -f 15217 15279 15358 -f 15358 15356 15217 -f 15217 15356 15218 -f 15217 15218 15365 -f 15365 15218 15367 -f 15267 15355 15219 -f 15219 15355 15280 -f 15280 15350 15219 -f 15219 15350 15281 -f 15219 15281 15364 -f 15266 15352 15220 -f 15220 15352 15353 -f 15353 15222 15220 -f 15220 15222 15221 -f 15220 15221 15282 -f 15283 15284 15285 -f 15283 15285 15459 -f 15459 15285 15286 -f 15223 15284 15287 -f 15287 15284 15373 -f 15373 15458 15463 -f 15373 15463 15289 -f 15289 15463 15288 -f 15291 15263 15375 -f 15378 15466 15376 -f 15376 15292 15378 -f 15385 15475 15387 -f 15384 15396 15388 -f 15389 15394 15473 -f 15402 15398 15401 -f 15401 15398 15397 -f 15520 15225 15514 -f 15514 15225 15295 -f 15514 15295 15294 -f 15294 15295 15224 -f 15296 15406 15297 -f 15297 15406 15405 -f 15406 15296 15412 -f 15412 15296 15230 -f 15230 15296 15299 -f 15230 15299 15229 -f 15230 15229 15408 -f 15408 15229 15403 -f 15412 15298 15404 -f 15297 15405 15404 -f 15403 15229 15409 -f 15409 15229 15298 -f 15298 15229 15299 -f 15298 15299 15297 -f 15298 15297 15404 -f 15304 15303 15407 -f 15407 15303 15300 -f 15413 15300 15301 -f 15302 15301 15226 -f 15302 15226 15411 -f 15411 15226 15228 -f 15228 15226 15227 -f 15228 15227 15410 -f 15410 15227 15303 -f 15413 15411 15228 -f 15413 15228 15300 -f 15300 15228 15407 -f 15407 15228 15410 -f 15410 15303 15304 -f 15298 15230 15409 -f 15409 15230 15408 -f 15414 15327 15305 -f 15305 15327 15314 -f 15305 15314 15312 -f 15305 15312 15310 -f 15305 15310 15416 -f 15244 15240 15246 -f 15246 15240 15416 -f 15246 15416 15306 -f 15306 15416 15310 -f 15306 15310 15239 -f 15239 15310 15318 -f 15239 15318 15244 -f 15244 15318 15240 -f 15307 15310 15312 -f 15307 15312 15308 -f 15308 15312 15322 -f 15308 15322 15309 -f 15309 15322 15318 -f 15309 15318 15310 -f 15234 15312 15314 -f 15234 15314 15251 -f 15251 15314 15324 -f 15251 15324 15311 -f 15311 15324 15322 -f 15311 15322 15312 -f 15232 15327 15325 -f 15232 15325 15313 -f 15313 15325 15324 -f 15313 15324 15314 -f 15318 15315 15316 -f 15316 15315 15240 -f 15316 15240 15317 -f 15317 15240 15318 -f 15322 15235 15318 -f 15318 15235 15319 -f 15318 15319 15315 -f 15315 15319 15320 -f 15320 15319 15322 -f 15322 15252 15321 -f 15252 15322 15324 -f 15324 15320 15321 -f 15321 15320 15322 -f 15326 15325 15323 -f 15323 15325 15320 -f 15323 15320 15324 -f 15326 15324 15325 -f 15327 15414 15325 -f 15208 15254 15259 -f 15259 15254 15415 -f 15422 15425 15424 -f 15422 15424 15423 -f 15422 15423 15427 -f 15432 15330 15434 -f 15437 15435 15440 -f 15443 15442 15332 -f 15332 15495 15443 -f 15512 15507 15515 -f 15515 15507 15261 -f 15515 15260 15512 -f 15512 15260 15214 -f 15512 15446 15507 -f 15446 15512 15500 -f 15262 15333 15263 -f 15263 15333 15448 -f 15334 15449 15374 -f 15333 15262 15450 -f 15450 15262 15291 -f 15450 15291 15374 -f 15335 15450 15375 -f 15263 15448 15335 -f 15444 15336 15375 -f 15375 15263 15335 -f 15339 15337 15338 -f 15447 15346 15339 -f 15340 15338 15337 -f 15343 15340 15341 -f 15342 15290 15346 -f 15342 15346 15445 -f 15343 15341 15344 -f 15342 15341 15290 -f 15290 15341 15345 -f 15341 15339 15338 -f 15341 15338 15344 -f 15342 15447 15339 -f 15447 15445 15346 -f 15449 15444 15375 -f 15334 15336 15444 -f 15349 15347 15460 -f 15460 15347 15462 -f 15451 15462 15264 -f 15264 15462 15347 -f 15264 15348 15451 -f 15451 15348 15457 -f 15460 15457 15349 -f 15349 15457 15348 -f 15452 15455 15361 -f 15452 15361 15356 -f 15452 15356 15350 -f 15452 15350 15453 -f 15353 15273 15222 -f 15222 15273 15453 -f 15222 15453 15351 -f 15351 15453 15350 -f 15351 15350 15352 -f 15352 15350 15363 -f 15352 15363 15353 -f 15353 15363 15273 -f 15354 15350 15356 -f 15354 15356 15355 -f 15355 15356 15368 -f 15355 15368 15280 -f 15280 15368 15363 -f 15280 15363 15350 -f 15358 15368 15356 -f 15357 15356 15361 -f 15357 15361 15279 -f 15279 15361 15370 -f 15279 15370 15358 -f 15358 15370 15368 -f 15359 15361 15455 -f 15359 15455 15277 -f 15277 15455 15372 -f 15277 15372 15360 -f 15360 15372 15370 -f 15360 15370 15361 -f 15363 15274 15282 -f 15282 15274 15273 -f 15282 15273 15362 -f 15362 15273 15363 -f 15368 15369 15363 -f 15363 15369 15364 -f 15363 15364 15274 -f 15274 15364 15366 -f 15366 15364 15368 -f 15368 15365 15367 -f 15365 15368 15370 -f 15370 15366 15367 -f 15367 15366 15368 -f 15371 15372 15271 -f 15271 15372 15366 -f 15271 15366 15370 -f 15371 15370 15372 -f 15345 15337 15283 -f 15283 15337 15284 -f 15284 15337 15339 -f 15284 15339 15290 -f 15336 15374 15373 -f 15373 15374 15291 -f 15373 15291 15458 -f 15458 15291 15375 -f 15373 15284 15336 -f 15336 15284 15290 -f 15336 15290 15375 -f 15375 15290 15345 -f 15375 15345 15458 -f 15458 15345 15283 -f 15379 15466 15378 -f 15467 15376 15466 -f 15292 15376 15377 -f 15377 15376 15467 -f 15292 15377 15379 -f 15378 15292 15379 -f 15381 15380 15419 -f 15381 15419 15382 -f 15470 15472 15383 -f 15470 15383 15386 -f 15472 15474 15383 -f 15477 15384 15385 -f 15385 15383 15474 -f 15475 15385 15474 -f 15475 15470 15386 -f 15475 15386 15387 -f 15387 15386 15388 -f 15387 15388 15476 -f 15476 15388 15396 -f 15473 15394 15392 -f 15473 15471 15293 -f 15473 15293 15389 -f 15389 15390 15478 -f 15471 15468 15391 -f 15471 15391 15293 -f 15468 15392 15391 -f 15393 15479 15394 -f 15394 15479 15395 -f 15394 15395 15391 -f 15394 15391 15392 -f 15476 15477 15387 -f 15387 15477 15385 -f 15396 15384 15477 -f 15478 15393 15389 -f 15389 15393 15394 -f 15390 15479 15478 -f 15401 15397 15481 -f 15400 15401 15481 -f 15400 15399 15402 -f 15400 15402 15401 -f 15402 15399 15397 -f 15397 15398 15402 -f 15304 15408 15403 -f 15404 15405 15465 -f 15465 15405 15406 -f 15465 15406 15480 -f 15411 15407 15410 -f 15304 15407 15408 -f 15408 15407 15411 -f 15408 15411 15409 -f 15409 15411 15413 -f 15406 15301 15480 -f 15480 15301 15302 -f 15410 15294 15480 -f 15410 15480 15411 -f 15411 15480 15302 -f 15410 15304 15294 -f 15294 15304 15403 -f 15294 15403 15514 -f 15514 15403 15409 -f 15465 15514 15404 -f 15404 15514 15409 -f 15404 15409 15412 -f 15412 15409 15413 -f 15412 15413 15406 -f 15406 15413 15301 -f 15480 15421 15414 -f 15414 15421 15257 -f 15480 15414 15305 -f 15480 15305 15465 -f 15256 15257 15421 -f 15465 15305 15416 -f 15465 15416 15419 -f 15419 15416 15418 -f 15382 15415 15420 -f 15420 15415 15254 -f 15420 15254 15256 -f 15256 15421 15420 -f 15382 15419 15417 -f 15382 15417 15415 -f 15419 15418 15417 -f 15504 15502 15420 -f 15421 15504 15420 -f 15421 15506 15504 -f 15425 15422 15484 -f 15484 15422 15426 -f 15425 15484 15423 -f 15423 15424 15425 -f 15426 15422 15427 -f 15508 15482 15483 -f 15508 15483 15428 -f 15508 15428 15429 -f 15491 15490 15430 -f 15491 15430 15433 -f 15490 15486 15328 -f 15490 15328 15430 -f 15430 15330 15431 -f 15431 15330 15432 -f 15329 15328 15493 -f 15493 15328 15486 -f 15493 15491 15329 -f 15509 15432 15434 -f 15509 15434 15433 -f 15433 15434 15329 -f 15433 15329 15491 -f 15433 15430 15509 -f 15509 15430 15431 -f 15331 15438 15487 -f 15487 15438 15492 -f 15487 15489 15331 -f 15488 15435 15437 -f 15488 15437 15436 -f 15436 15437 15331 -f 15436 15331 15489 -f 15489 15485 15439 -f 15489 15439 15436 -f 15485 15492 15438 -f 15485 15438 15439 -f 15439 15440 15441 -f 15441 15440 15435 -f 15436 15439 15488 -f 15488 15439 15441 -f 15498 15499 15442 -f 15498 15442 15443 -f 15442 15499 15496 -f 15332 15442 15496 -f 15496 15495 15332 -f 15498 15443 15495 -f 15448 15333 15461 -f 15344 15444 15343 -f 15445 15447 15446 -f 15338 15340 15456 -f 15456 15340 15343 -f 15461 15456 15448 -f 15448 15456 15343 -f 15448 15343 15335 -f 15335 15343 15444 -f 15335 15444 15450 -f 15450 15444 15449 -f 15333 15450 15461 -f 15461 15450 15449 -f 15461 15449 15500 -f 15500 15449 15334 -f 15500 15334 15444 -f 15446 15500 15445 -f 15445 15500 15444 -f 15445 15444 15342 -f 15342 15444 15344 -f 15342 15344 15447 -f 15447 15344 15338 -f 15447 15338 15446 -f 15446 15338 15456 -f 15494 15454 15460 -f 15455 15452 15451 -f 15451 15452 15462 -f 15462 15452 15453 -f 15460 15454 15457 -f 15457 15454 15428 -f 15457 15428 15483 -f 15459 15455 15456 -f 15456 15455 15451 -f 15456 15451 15483 -f 15483 15451 15457 -f 15461 15458 15456 -f 15456 15458 15283 -f 15283 15459 15456 -f 15461 15288 15463 -f 15494 15460 15462 -f 15494 15462 15461 -f 15461 15462 15453 -f 15461 15453 15288 -f 15461 15463 15458 -f 15454 15511 15464 -f 15497 15511 15494 -f 15494 15511 15454 -f 15377 15514 15379 -f 15379 15514 15465 -f 15379 15465 15466 -f 15466 15465 15419 -f 15466 15419 15467 -f 15467 15419 15380 -f 15467 15380 15377 -f 15377 15380 15514 -f 15420 15468 15471 -f 15469 15381 15382 -f 15420 15502 15393 -f 15472 15470 15382 -f 15382 15470 15475 -f 15476 15396 15469 -f 15473 15474 15471 -f 15471 15474 15472 -f 15471 15472 15420 -f 15420 15472 15382 -f 15468 15420 15392 -f 15392 15420 15393 -f 15392 15393 15473 -f 15473 15393 15478 -f 15473 15478 15474 -f 15474 15478 15477 -f 15474 15477 15475 -f 15475 15477 15476 -f 15475 15476 15382 -f 15476 15469 15382 -f 15396 15477 15469 -f 15469 15477 15478 -f 15469 15478 15502 -f 15502 15478 15479 -f 15502 15479 15393 -f 15294 15400 15480 -f 15480 15400 15481 -f 15480 15481 15421 -f 15421 15481 15397 -f 15421 15397 15506 -f 15506 15397 15399 -f 15400 15294 15399 -f 15399 15294 15506 -f 15482 15484 15426 -f 15482 15426 15483 -f 15483 15426 15427 -f 15483 15427 15456 -f 15456 15427 15423 -f 15456 15423 15446 -f 15423 15484 15446 -f 15446 15484 15482 -f 15441 15509 15485 -f 15493 15486 15428 -f 15428 15486 15490 -f 15489 15487 15454 -f 15454 15487 15492 -f 15509 15429 15432 -f 15441 15485 15488 -f 15432 15429 15431 -f 15454 15464 15488 -f 15454 15488 15489 -f 15489 15488 15485 -f 15509 15441 15435 -f 15509 15435 15464 -f 15464 15435 15488 -f 15491 15509 15490 -f 15490 15509 15431 -f 15490 15431 15428 -f 15428 15431 15429 -f 15485 15509 15491 -f 15485 15491 15492 -f 15492 15491 15493 -f 15492 15493 15454 -f 15454 15493 15428 -f 15497 15494 15496 -f 15496 15494 15495 -f 15495 15494 15461 -f 15495 15461 15498 -f 15498 15461 15500 -f 15496 15499 15497 -f 15498 15500 15499 -f 15499 15500 15497 -f 15514 15380 15522 -f 15522 15380 15501 -f 15380 15381 15501 -f 15503 15501 15469 -f 15469 15501 15381 -f 15469 15502 15503 -f 15503 15502 15505 -f 15505 15504 15506 -f 15505 15502 15504 -f 15294 15224 15505 -f 15294 15505 15506 -f 15510 15507 15482 -f 15482 15507 15446 -f 15508 15510 15482 -f 15429 15510 15508 -f 15509 15464 15517 -f 15517 15464 15513 -f 15517 15510 15429 -f 15517 15429 15509 -f 15464 15511 15513 -f 15512 15513 15497 -f 15512 15497 15500 -f 15513 15511 15497 -f 15519 15225 15520 -f 15523 15522 15501 -f 15505 15528 15503 -f 15503 15528 15523 -f 15503 15523 15501 -f 15505 15224 15528 -f 15261 15507 15510 -f 15535 15516 15517 -f 15516 15510 15517 -f 15517 15513 15535 -f 15512 15214 15513 -f 15513 15214 15535 -f 15522 15520 15514 -f 15544 15520 15518 -f 15518 15520 15524 -f 15521 15520 15544 -f 15523 15520 15522 -f 15524 15520 15523 -f 15525 15524 15523 -f 15523 15528 15525 -f 15525 15528 15527 -f 15525 15527 15524 -f 15524 15527 15526 -f 15526 15528 15224 -f 15526 15527 15528 -f 15526 15224 15521 -f 15526 15521 15529 -f 15529 15530 15261 -f 15531 15529 15261 -f 15531 15261 15516 -f 15516 15261 15510 -f 15534 15533 15516 -f 15533 15531 15516 -f 15532 15533 15534 -f 15535 15534 15516 -f 15536 15532 15535 -f 15534 15535 15532 -f 15518 15532 15536 -f 15536 15535 15214 -f 15518 15536 15214 -f 15518 15214 15530 -f 15539 15842 15537 -f 15537 15538 15539 -f 15539 15538 15552 -f 15539 15552 15554 -f 15539 15554 15559 -f 15540 15563 15558 -f 15541 15578 15563 -f 15558 15560 15555 -f 15558 15555 15557 -f 15561 15562 15566 -f 15545 15213 15529 -f 15526 15529 15565 -f 15565 15529 15546 -f 15546 15529 15531 -f 15546 15531 15533 -f 15546 15533 15547 -f 15547 15533 15532 -f 15559 15524 15565 -f 15565 15524 15526 -f 15547 15518 15559 -f 15559 15518 15524 -f 15547 15532 15518 -f 15551 15581 15550 -f 15551 15550 15568 -f 15553 15551 15568 -f 15537 15548 15551 -f 15537 15551 15538 -f 15538 15551 15553 -f 15538 15553 15552 -f 15552 15553 15568 -f 15552 15568 15554 -f 15554 15568 15547 -f 15554 15547 15559 -f 15569 15537 15842 -f 15842 15539 15570 -f 15570 15539 15556 -f 15570 15556 15571 -f 15555 15571 15556 -f 15555 15556 15557 -f 15557 15556 15539 -f 15557 15539 15558 -f 15558 15539 15540 -f 15540 15539 15559 -f 15540 15559 15565 -f 15560 15558 15578 -f 15578 15558 15563 -f 15572 15578 15541 -f 15561 15541 15562 -f 15562 15541 15563 -f 15562 15563 15542 -f 15542 15563 15540 -f 15542 15540 15564 -f 15564 15540 15565 -f 15564 15565 15546 -f 15573 15561 15566 -f 15566 15562 15542 -f 15566 15542 15576 -f 15576 15542 15543 -f 15576 15543 15567 -f 15567 15543 15549 -f 15549 15543 15550 -f 15550 15543 15542 -f 15564 15568 15542 -f 15542 15568 15550 -f 15546 15547 15564 -f 15564 15547 15568 -f 15574 15549 15550 -f 15574 15550 15581 -f 15581 15551 15582 -f 15582 15551 15548 -f 15582 15548 15569 -f 15569 15548 15537 -f 15570 15571 15560 -f 15560 15571 15555 -f 15572 15541 15573 -f 15573 15541 15561 -f 15576 15567 15574 -f 15574 15567 15549 -f 15573 15587 15572 -f 15572 15587 14910 -f 15581 15843 15574 -f 15574 15843 15575 -f 15574 15575 15576 -f 15576 15575 15592 -f 15576 15592 15590 -f 15576 15590 15566 -f 15566 15590 15573 -f 15573 15590 15577 -f 15573 15577 15587 -f 15572 14910 15578 -f 15578 14910 15560 -f 15560 14910 15579 -f 15560 15579 15570 -f 15570 15579 15580 -f 15570 15580 15842 -f 15581 15582 15843 -f 15843 15582 15583 -f 15583 15582 15569 -f 15583 15569 15584 -f 15584 15569 15842 -f 15580 15585 15842 -f 15584 15842 15594 -f 15579 15586 15580 -f 15580 15586 15585 -f 15587 15588 14910 -f 15579 14910 15586 -f 15577 15591 15587 -f 15587 15591 15588 -f 15592 15589 15590 -f 15577 15590 15591 -f 15575 15593 15592 -f 15592 15593 15589 -f 15583 15844 15843 -f 15575 15843 15593 -f 15584 15594 15583 -f 15583 15594 15844 -f 15661 15613 15609 -f 15618 15616 15609 -f 15609 15616 15595 -f 15609 15595 15661 -f 15596 15620 15609 -f 15609 15620 15619 -f 15609 15619 15618 -f 15625 15624 15609 -f 15609 15624 15622 -f 15609 15622 15596 -f 15599 15597 15609 -f 15609 15597 15626 -f 15609 15626 15625 -f 15632 15631 15609 -f 15609 15631 15598 -f 15609 15598 15599 -f 15600 15601 15609 -f 15609 15601 15602 -f 15609 15602 15632 -f 15637 15636 15609 -f 15609 15636 15603 -f 15609 15603 15600 -f 15607 15639 15609 -f 15609 15639 15604 -f 15609 15604 15637 -f 15642 15605 15609 -f 15609 15605 15606 -f 15609 15606 15607 -f 15644 15608 15609 -f 15610 15611 15609 -f 15609 15611 15646 -f 15609 15646 15644 -f 15651 15650 15609 -f 15609 15650 15648 -f 15609 15648 15610 -f 15656 15612 15609 -f 15609 15612 15654 -f 15609 15654 15651 -f 15613 15659 15609 -f 15609 15659 15657 -f 15609 15657 15656 -f 15614 15595 15615 -f 15615 15595 15616 -f 15615 15616 15687 -f 15687 15616 15618 -f 15687 15618 15617 -f 15617 15618 15619 -f 15617 15619 15688 -f 15688 15619 15620 -f 15688 15620 15621 -f 15621 15620 15596 -f 15621 15596 15679 -f 15679 15596 15622 -f 15679 15622 15680 -f 15680 15622 15624 -f 15680 15624 15623 -f 15623 15624 15625 -f 15623 15625 15681 -f 15681 15625 15626 -f 15681 15626 15682 -f 15682 15626 15597 -f 15682 15597 15627 -f 15627 15597 15599 -f 15627 15599 15628 -f 15628 15599 15598 -f 15628 15598 15629 -f 15629 15598 15631 -f 15629 15631 15630 -f 15630 15631 15632 -f 15630 15632 15633 -f 15633 15632 15602 -f 15633 15602 15683 -f 15683 15602 15601 -f 15683 15601 15690 -f 15690 15601 15600 -f 15690 15600 15634 -f 15634 15600 15603 -f 15634 15603 15635 -f 15635 15603 15636 -f 15635 15636 15670 -f 15670 15636 15637 -f 15670 15637 15638 -f 15638 15637 15604 -f 15638 15604 15671 -f 15671 15604 15639 -f 15671 15639 15675 -f 15675 15639 15607 -f 15675 15607 15640 -f 15640 15607 15606 -f 15640 15606 15641 -f 15641 15606 15605 -f 15641 15605 15684 -f 15684 15605 15642 -f 15684 15642 15685 -f 15685 15642 15609 -f 15685 15609 15686 -f 15686 15609 15608 -f 15686 15608 15643 -f 15643 15608 15644 -f 15643 15644 15645 -f 15645 15644 15646 -f 15645 15646 15692 -f 15692 15646 15611 -f 15692 15611 15647 -f 15647 15611 15610 -f 15647 15610 15676 -f 15676 15610 15648 -f 15676 15648 15677 -f 15677 15648 15650 -f 15677 15650 15649 -f 15649 15650 15651 -f 15649 15651 15652 -f 15652 15651 15654 -f 15652 15654 15653 -f 15653 15654 15612 -f 15653 15612 15655 -f 15655 15612 15656 -f 15655 15656 15678 -f 15678 15656 15657 -f 15678 15657 15658 -f 15658 15657 15659 -f 15658 15659 15673 -f 15673 15659 15613 -f 15673 15613 15660 -f 15660 15613 15661 -f 15660 15661 15614 -f 15614 15661 15595 -f 15663 15666 15674 -f 15674 15666 15691 -f 15668 15663 15662 -f 15662 15663 15674 -f 15664 15668 15665 -f 15665 15668 15662 -f 15667 15664 15672 -f 15672 15664 15665 -f 15669 15667 15689 -f 15689 15667 15672 -f 15666 15669 15691 -f 15691 15669 15689 -f 15664 15667 15668 -f 15668 15667 15669 -f 15668 15669 15663 -f 15663 15669 15666 -f 15670 15638 15674 -f 15674 15638 15671 -f 15674 15671 15675 -f 15673 15660 15672 -f 15672 15660 15614 -f 15672 15614 15615 -f 15665 15678 15672 -f 15672 15678 15658 -f 15672 15658 15673 -f 15691 15628 15629 -f 15684 15662 15641 -f 15641 15662 15674 -f 15641 15674 15640 -f 15640 15674 15675 -f 15662 15647 15665 -f 15665 15647 15676 -f 15676 15677 15665 -f 15665 15677 15649 -f 15665 15649 15652 -f 15652 15653 15665 -f 15665 15653 15655 -f 15665 15655 15678 -f 15621 15679 15689 -f 15689 15679 15680 -f 15689 15680 15623 -f 15623 15681 15689 -f 15689 15681 15682 -f 15689 15682 15691 -f 15691 15682 15627 -f 15691 15627 15628 -f 15629 15630 15691 -f 15691 15630 15633 -f 15691 15633 15683 -f 15684 15685 15662 -f 15662 15685 15686 -f 15662 15686 15643 -f 15615 15687 15672 -f 15672 15687 15617 -f 15672 15617 15689 -f 15689 15617 15688 -f 15689 15688 15621 -f 15683 15690 15691 -f 15691 15690 15634 -f 15691 15634 15674 -f 15674 15634 15635 -f 15674 15635 15670 -f 15643 15645 15662 -f 15662 15645 15692 -f 15662 15692 15647 -f 15693 15694 15713 -f 15720 15718 15713 -f 15713 15718 15755 -f 15713 15755 15693 -f 15695 15722 15713 -f 15713 15722 15696 -f 15713 15696 15720 -f 15697 15698 15713 -f 15713 15698 15699 -f 15713 15699 15695 -f 15700 15725 15713 -f 15728 15726 15713 -f 15713 15726 15701 -f 15713 15701 15700 -f 15702 15729 15713 -f 15713 15729 15703 -f 15713 15703 15728 -f 15733 15704 15713 -f 15713 15704 15705 -f 15713 15705 15702 -f 15736 15706 15713 -f 15713 15706 15734 -f 15713 15734 15733 -f 15739 15707 15713 -f 15713 15707 15708 -f 15713 15708 15736 -f 15711 15741 15713 -f 15713 15741 15709 -f 15713 15709 15739 -f 15714 15710 15713 -f 15713 15710 15743 -f 15713 15743 15711 -f 15716 15712 15713 -f 15713 15712 15745 -f 15713 15745 15714 -f 15749 15747 15713 -f 15713 15747 15715 -f 15713 15715 15716 -f 15694 15751 15713 -f 15713 15751 15750 -f 15713 15750 15749 -f 15754 15755 15717 -f 15717 15755 15718 -f 15717 15718 15719 -f 15719 15718 15720 -f 15719 15720 15784 -f 15784 15720 15696 -f 15784 15696 15721 -f 15721 15696 15722 -f 15721 15722 15723 -f 15723 15722 15695 -f 15723 15695 15772 -f 15772 15695 15699 -f 15772 15699 15724 -f 15724 15699 15698 -f 15724 15698 15773 -f 15773 15698 15697 -f 15773 15697 15774 -f 15774 15697 15713 -f 15774 15713 15775 -f 15775 15713 15725 -f 15775 15725 15776 -f 15776 15725 15700 -f 15776 15700 15777 -f 15777 15700 15701 -f 15777 15701 15778 -f 15778 15701 15726 -f 15778 15726 15727 -f 15727 15726 15728 -f 15727 15728 15780 -f 15780 15728 15703 -f 15780 15703 15781 -f 15781 15703 15729 -f 15781 15729 15730 -f 15730 15729 15702 -f 15730 15702 15731 -f 15731 15702 15705 -f 15731 15705 15786 -f 15786 15705 15704 -f 15786 15704 15787 -f 15787 15704 15733 -f 15787 15733 15732 -f 15732 15733 15734 -f 15732 15734 15735 -f 15735 15734 15706 -f 15735 15706 15767 -f 15767 15706 15736 -f 15767 15736 15737 -f 15737 15736 15708 -f 15737 15708 15766 -f 15766 15708 15707 -f 15766 15707 15738 -f 15738 15707 15739 -f 15738 15739 15782 -f 15782 15739 15709 -f 15782 15709 15740 -f 15740 15709 15741 -f 15740 15741 15788 -f 15788 15741 15711 -f 15788 15711 15789 -f 15789 15711 15743 -f 15789 15743 15742 -f 15742 15743 15710 -f 15742 15710 15790 -f 15790 15710 15714 -f 15790 15714 15744 -f 15744 15714 15745 -f 15744 15745 15746 -f 15746 15745 15712 -f 15746 15712 15768 -f 15768 15712 15716 -f 15768 15716 15769 -f 15769 15716 15715 -f 15769 15715 15770 -f 15770 15715 15747 -f 15770 15747 15748 -f 15748 15747 15749 -f 15748 15749 15771 -f 15771 15749 15750 -f 15771 15750 15765 -f 15765 15750 15751 -f 15765 15751 15752 -f 15752 15751 15694 -f 15752 15694 15753 -f 15753 15694 15693 -f 15753 15693 15754 -f 15754 15693 15755 -f 15756 15760 15757 -f 15757 15760 15779 -f 15758 15756 15783 -f 15783 15756 15757 -f 15759 15758 15763 -f 15763 15758 15783 -f 15761 15759 15764 -f 15764 15759 15763 -f 15762 15761 15785 -f 15785 15761 15764 -f 15760 15762 15779 -f 15779 15762 15785 -f 15759 15761 15758 -f 15758 15761 15762 -f 15758 15762 15756 -f 15756 15762 15760 -f 15787 15732 15757 -f 15757 15732 15735 -f 15757 15735 15767 -f 15752 15753 15764 -f 15764 15753 15754 -f 15764 15754 15717 -f 15763 15771 15764 -f 15764 15771 15765 -f 15764 15765 15752 -f 15779 15777 15778 -f 15738 15783 15766 -f 15766 15783 15757 -f 15766 15757 15737 -f 15737 15757 15767 -f 15783 15790 15763 -f 15763 15790 15744 -f 15744 15746 15763 -f 15763 15746 15768 -f 15763 15768 15769 -f 15769 15770 15763 -f 15763 15770 15748 -f 15763 15748 15771 -f 15723 15772 15785 -f 15785 15772 15724 -f 15785 15724 15773 -f 15773 15774 15785 -f 15785 15774 15775 -f 15785 15775 15779 -f 15779 15775 15776 -f 15779 15776 15777 -f 15778 15727 15779 -f 15779 15727 15780 -f 15779 15780 15781 -f 15738 15782 15783 -f 15783 15782 15740 -f 15783 15740 15788 -f 15717 15719 15764 -f 15764 15719 15784 -f 15764 15784 15785 -f 15785 15784 15721 -f 15785 15721 15723 -f 15781 15730 15779 -f 15779 15730 15731 -f 15779 15731 15757 -f 15757 15731 15786 -f 15757 15786 15787 -f 15788 15789 15783 -f 15783 15789 15742 -f 15783 15742 15790 -f 14395 14393 14396 -f 15805 15808 14347 -f 14334 14393 15793 -f 15796 15802 14337 -f 15791 14399 15792 -f 14332 14334 15793 -f 15814 14380 15793 -f 15817 15807 15818 -f 14388 14377 14332 -f 15793 14392 15814 -f 15791 15800 15806 -f 14340 14341 15809 -f 15796 15791 15792 -f 14332 14380 14388 -f 15800 15796 15797 -f 14401 15791 15806 -f 14366 15794 14338 -f 15814 14392 14379 -f 14332 14377 15802 -f 14401 15806 14376 -f 15791 14400 14399 -f 15803 15805 14347 -f 15799 14401 14376 -f 14392 15798 14379 -f 14366 15799 14376 -f 14344 14379 15798 -f 14366 14338 15799 -f 15796 14332 15802 -f 15797 15796 14367 -f 15796 15800 15791 -f 14344 14378 14379 -f 15801 15802 14377 -f 14367 15796 14337 -f 15794 14367 14337 -f 14393 14334 14396 -f 15801 14378 14344 -f 15802 15801 14344 -f 15803 14337 15802 -f 15803 14336 14337 -f 14336 15809 15804 -f 15811 15817 15818 -f 14347 15809 15803 -f 14335 14336 15804 -f 15804 15810 14335 -f 15809 14336 15803 -f 15804 14341 14339 -f 14403 14335 15810 -f 14332 15793 14380 -f 15794 14337 14338 -f 15807 14340 14346 -f 15808 14348 14347 -f 14346 14340 15809 -f 14339 14357 15804 -f 15808 15811 14348 -f 15815 14403 15810 -f 15795 15813 14365 -f 14365 15815 15810 -f 15811 15818 14348 -f 14339 15816 14357 -f 14346 15818 15807 -f 15813 15815 14365 -f 15812 15816 15795 -f 15816 15812 14357 -f 14341 15804 15809 -f 14365 15812 15795 -f 14891 15885 15819 -f 15819 14890 14891 -f 15819 15820 14890 -f 15820 15823 15836 -f 14905 15820 15836 -f 14908 15828 15193 -f 15836 15823 15199 -f 15824 14905 15197 -f 15197 14905 15836 -f 15824 15197 15821 -f 15822 15199 15823 -f 15822 15823 15195 -f 15195 15823 15825 -f 15826 15824 15192 -f 15192 15824 15821 -f 15196 15195 15825 -f 15826 15192 15827 -f 15196 15825 15829 -f 15828 15826 15827 -f 15194 15196 15829 -f 15828 15827 15830 -f 15178 15194 15829 -f 15828 15830 15831 -f 15178 15829 14908 -f 15832 15178 14908 -f 15193 15832 14908 -f 15828 15831 15193 -f 15819 15823 15820 -f 15834 15828 14908 -f 14908 14889 15834 -f 15835 15834 14889 -f 15835 14889 15869 -f 15835 15869 15895 -f 15835 15895 14888 -f 15837 14901 15833 -f 15910 15837 15833 -f 15839 15910 15833 -f 15833 15838 15839 -f 15593 15841 14903 -f 15839 15838 15588 -f 15588 15838 14910 -f 15839 15588 15591 -f 15590 15839 15591 -f 15586 14910 15840 -f 14903 15590 15589 -f 14896 15585 15840 -f 15589 15593 14903 -f 15585 15586 15840 -f 15842 15585 14896 -f 15841 15593 15843 -f 15594 15842 14896 -f 15847 15843 15844 -f 15844 15594 14896 -f 15844 14896 14912 -f 15847 15844 14912 -f 14912 14895 15847 -f 15845 15847 14894 -f 14894 15847 14895 -f 15845 14894 15846 -f 15846 14894 15925 -f 15845 15846 14892 -f 15857 15855 15854 -f 15866 14832 15857 -f 15886 14832 15866 -f 15859 15872 15848 -f 14832 15855 15857 -f 15853 15852 15860 -f 15854 15855 15850 -f 15898 15861 15849 -f 15902 14886 15850 -f 15851 14864 15898 -f 14866 15898 14864 -f 15848 14810 15859 -f 14885 14886 15902 -f 15858 14885 15900 -f 14866 14868 14823 -f 14877 14878 14846 -f 15856 15853 15860 -f 15882 15858 15900 -f 15863 14824 14868 -f 15920 15891 14907 -f 15856 15860 15861 -f 15900 15868 15862 -f 14823 15898 14866 -f 15864 14824 15863 -f 14810 15852 15878 -f 14872 14824 15864 -f 15934 15935 15884 -f 15868 15867 15865 -f 15871 15867 15868 -f 14872 15873 14824 -f 15871 14883 15867 -f 15870 15873 14872 -f 14832 15886 14833 -f 15880 15873 15870 -f 14835 15889 15888 -f 14826 14825 15885 -f 15874 15887 15871 -f 15909 14817 14911 -f 15904 14810 15878 -f 15880 15879 15873 -f 15859 15875 15872 -f 15880 15883 15879 -f 15900 15862 15882 -f 14904 15903 15905 -f 15883 15892 15897 -f 15937 14853 15884 -f 14845 14797 14875 -f 14835 15919 15889 -f 15877 14826 15885 -f 15885 14825 15897 -f 15875 14833 15886 -f 15878 15877 15885 -f 14911 14901 15869 -f 14806 14803 15913 -f 15901 15875 15889 -f 15875 15886 15872 -f 15871 15887 14883 -f 15876 15915 15888 -f 14906 15888 15889 -f 15892 15890 15897 -f 15892 15899 15890 -f 14907 15891 14906 -f 14899 14898 14907 -f 15893 15899 15892 -f 15893 15909 15899 -f 15894 14900 14907 -f 14888 15910 15894 -f 15895 15896 14888 -f 15869 15896 15895 -f 14842 14798 14797 -f 15874 15915 15876 -f 15911 15914 15912 -f 14825 15879 15897 -f 15898 15856 15861 -f 14892 15846 15938 -f 14911 15869 15899 -f 14900 14899 14907 -f 15919 15901 15889 -f 14901 15896 15869 -f 15910 14900 15894 -f 15855 15902 15850 -f 14807 15905 15903 -f 15891 15888 14906 -f 14852 15918 14893 -f 15859 14810 15904 -f 14911 14817 14909 -f 15905 14806 15913 -f 14902 15905 15913 -f 15916 14897 14909 -f 14902 14904 15905 -f 15916 14913 14897 -f 14814 14913 15916 -f 15923 15922 14904 -f 14814 14852 14913 -f 15909 14911 15899 -f 15896 15910 14888 -f 15922 15903 14904 -f 15878 15852 15877 -f 15876 15887 15874 -f 15923 15914 15911 -f 14803 15881 15913 -f 14803 15891 15881 -f 15914 14892 15908 -f 15912 15914 14799 -f 15846 15925 15930 -f 15925 14893 14855 -f 15915 14835 15888 -f 15903 14847 14807 -f 15917 14852 14814 -f 14898 15920 14907 -f 14817 15916 14909 -f 15879 15883 15897 -f 15901 14833 15875 -f 14814 15907 15917 -f 15918 14855 14893 -f 15921 14807 14847 -f 15891 15920 15881 -f 15922 15923 15911 -f 15907 15906 15917 -f 15924 15906 15907 -f 14882 15921 14847 -f 15908 14892 15938 -f 15936 14877 14845 -f 15926 14882 14847 -f 14802 15925 14855 -f 15926 15927 14882 -f 14856 15906 15924 -f 15926 14880 15927 -f 14857 15906 14856 -f 15852 15853 15877 -f 14857 15929 15906 -f 14799 15914 15908 -f 15926 14879 14880 -f 15928 15929 14857 -f 14846 14879 15926 -f 14799 14841 15912 -f 14846 14878 14879 -f 14799 15939 14841 -f 14854 14853 15940 -f 15928 14859 15929 -f 14824 14823 14868 -f 14852 14893 14913 -f 15931 15929 14859 -f 14845 14877 14846 -f 14845 14842 14797 -f 15931 15934 15929 -f 15930 15925 14802 -f 15931 15932 15934 -f 15939 14798 14841 -f 15868 15865 15862 -f 14885 15902 15900 -f 14853 15934 15884 -f 15932 15935 15934 -f 15933 15936 14845 -f 14875 15933 14845 -f 14798 14842 14841 -f 15940 14853 15937 -f 15851 15898 15849 -f 15938 15846 15930 -f 14802 14855 15940 -f 14855 14854 15940 -f 14850 14851 15941 -f 14848 14850 15941 -f 14848 15941 14849 -f 14837 14844 14839 -f 14843 14844 14837 -f 14829 14830 14831 -f 14836 14831 15942 -f 14836 14829 14831 -f 14836 15942 14834 -f 14827 14820 14821 -f 14822 14827 14821 -f 14822 15943 14827 -f 15946 14869 15948 -f 15945 15965 15946 -f 14811 14819 15945 -f 14808 15954 15944 -f 14819 15965 15945 -f 15946 15965 14812 -f 14887 15955 14808 -f 15976 15979 15947 -f 15955 15954 14808 -f 14862 15948 14863 -f 15958 14809 15957 -f 14811 14809 15958 -f 14865 14863 14867 -f 15955 15949 15967 -f 15950 14860 15979 -f 15956 15958 15957 -f 15970 15973 15951 -f 14871 14870 14869 -f 14884 15967 15952 -f 14863 15948 14869 -f 15953 15968 14884 -f 14812 14871 14869 -f 15970 15972 14876 -f 14869 15946 14812 -f 15954 15955 15968 -f 15954 15956 15944 -f 15951 15973 14881 -f 15956 15957 15944 -f 14819 14811 15958 -f 14818 14819 15958 -f 14818 15958 14804 -f 15959 14818 14804 -f 15959 14804 14805 -f 15960 15959 14805 -f 15960 14805 15961 -f 14816 15960 15961 -f 14816 15961 15962 -f 15962 14801 14816 -f 15981 14800 15962 -f 14816 14801 14815 -f 14800 14801 15962 -f 15980 15966 14815 -f 15981 15963 15978 -f 15966 15969 15964 -f 15974 15966 14813 -f 15955 15967 15968 -f 15966 15974 14815 -f 15973 15963 14881 -f 15967 14884 15968 -f 15979 14858 15969 -f 15970 15971 15972 -f 15966 15964 14813 -f 15967 15975 15952 -f 15976 15950 15979 -f 15970 14876 15977 -f 14863 14869 14867 -f 14861 14860 15950 -f 15973 14874 14873 -f 15982 15981 15978 -f 15963 15973 14873 -f 15973 15970 15977 -f 15978 15963 14873 -f 15966 15979 15969 -f 15947 15979 15966 -f 14801 15980 14815 -f 14800 15981 15982 -f 14870 15983 14869 -f 2611 9612 9494 -# 30993 faces, 0 coords texture - -# End of File \ No newline at end of file +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o pelvis +v -0.005177 0.102116 0.079207 +v -0.005174 0.100563 0.077681 +v -0.005197 0.098584 0.078182 +v -0.003161 0.097403 0.083015 +v -0.003819 0.096224 0.080406 +v -0.003182 0.096225 0.078599 +v -0.003191 0.099731 0.083979 +v -0.005116 0.100100 0.082432 +v -0.005167 0.098113 0.081388 +v -0.003249 0.098157 0.076471 +v -0.003197 0.101126 0.076119 +v -0.003203 0.103542 0.078162 +v -0.003281 0.103871 0.081098 +v -0.005130 0.102030 0.081246 +v -0.003203 0.101983 0.083416 +v -0.004000 0.098608 0.080472 +v -0.004000 0.101442 0.080375 +v -0.003175 -0.007349 0.083178 +v -0.003801 -0.008381 0.081594 +v -0.003106 -0.008970 0.079934 +v -0.005199 -0.002896 0.080817 +v -0.005113 -0.005971 0.082229 +v -0.004486 -0.003489 0.082770 +v -0.003158 -0.004807 0.083984 +v -0.005257 -0.006618 0.081030 +v -0.005129 -0.007380 0.079616 +v -0.003247 -0.007872 0.077220 +v -0.004528 -0.006565 0.077306 +v -0.005213 -0.004292 0.077812 +v -0.003204 -0.004952 0.076013 +v -0.003399 -0.001989 0.077332 +v -0.005222 -0.003226 0.078837 +v -0.003187 -0.001026 0.079915 +v -0.003284 -0.001863 0.082472 +v -0.004000 -0.005619 0.078644 +v -0.004000 -0.003756 0.080782 +v -0.005169 -0.003774 -0.081871 +v -0.005044 -0.005807 -0.082392 +v -0.005114 -0.007238 -0.081012 +v -0.005011 -0.007400 -0.079228 +v -0.005165 -0.005959 -0.077821 +v -0.005071 -0.003090 -0.078527 +v -0.005064 -0.002544 -0.080563 +v -0.003162 -0.002803 -0.076573 +v -0.003735 -0.004244 -0.076300 +v -0.003207 -0.007408 -0.076776 +v -0.003206 -0.008884 -0.079353 +v -0.003177 -0.008207 -0.082425 +v -0.003229 -0.005476 -0.083928 +v -0.003233 -0.003090 -0.083526 +v -0.003232 -0.001220 -0.081169 +v -0.003128 -0.001372 -0.078307 +v -0.004000 -0.004757 -0.081470 +v -0.004000 -0.003848 -0.079055 +v -0.004000 -0.006395 -0.079475 +v -0.005252 0.101709 -0.081061 +v -0.005067 0.099806 -0.082425 +v -0.005226 0.097930 -0.080822 +v -0.005106 0.098470 -0.078224 +v -0.005147 0.100017 -0.077705 +v -0.003155 0.102469 -0.076817 +v -0.003543 0.100903 -0.076236 +v -0.003187 0.098220 -0.076426 +v -0.003410 0.096323 -0.078516 +v -0.003189 0.096157 -0.081107 +v -0.003447 0.097686 -0.083234 +v -0.003156 0.100900 -0.083929 +v -0.004624 0.102467 -0.081857 +v -0.003177 0.103208 -0.082401 +v -0.003165 0.103914 -0.079071 +v -0.005155 0.102029 -0.078674 +v -0.004000 0.099198 -0.081232 +v -0.004000 0.101287 -0.079249 +v -0.024503 -0.031640 0.067042 +v -0.002890 -0.013373 0.069345 +v -0.004400 -0.010912 0.069331 +v -0.004650 0.113138 0.069084 +v -0.015861 0.113308 0.068022 +v -0.004554 0.081419 0.069210 +v -0.000332 0.024517 0.069527 +v -0.000101 0.070522 0.069501 +v 0.000001 -0.012200 0.070218 +v -0.004386 0.011704 0.069320 +v -0.002270 0.118819 0.068007 +v -0.032096 0.120315 0.064606 +v -0.000089 0.121372 0.067288 +v 0.000000 0.131420 0.061351 +v -0.034878 0.126625 0.060793 +v -0.035710 0.131288 0.056193 +v -0.033797 0.135359 0.050247 +v 0.000002 0.139717 0.048181 +v -0.004279 0.112969 -0.069239 +v -0.004515 0.081030 -0.069199 +v -0.018059 0.113262 -0.067815 +v -0.013327 -0.026298 -0.068295 +v -0.000187 0.070469 -0.069545 +v -0.004740 0.012181 -0.069192 +v -0.004703 -0.011672 -0.069188 +v -0.000033 -0.013474 -0.069737 +v 0.000065 -0.032575 -0.069203 +v -0.000606 0.024508 -0.069566 +v -0.011728 -0.071096 -0.055330 +v -0.016409 -0.041485 -0.065787 +v -0.000001 -0.072881 -0.055576 +v -0.025821 -0.033642 -0.066623 +v -0.011705 -0.076215 0.051113 +v 0.000000 -0.079559 0.047989 +v 0.000000 -0.072930 0.055534 +v -0.011755 -0.070247 0.055717 +v -0.064732 -0.075202 0.038918 +v -0.057848 -0.071073 0.044943 +v -0.081520 -0.065222 0.036563 +v -0.085154 -0.068960 0.031363 +v -0.101026 -0.059584 0.026257 +v -0.062475 -0.079895 0.033693 +v -0.085931 -0.072045 0.026141 +v -0.104150 -0.063315 0.017719 +v -0.114305 -0.053971 0.016098 +v -0.060193 -0.082175 0.027457 +v -0.081857 -0.075355 0.022335 +v -0.103056 -0.065372 0.012809 +v -0.111723 -0.050191 0.022056 +v -0.114495 -0.056516 0.009813 +v -0.120250 -0.044325 0.009298 +v -0.118793 -0.050338 0.008334 +v -0.116779 -0.047716 0.016684 +v -0.113791 -0.057275 -0.008587 +v -0.117819 -0.052557 -0.007021 +v -0.120627 -0.045168 -0.005844 +v -0.042782 -0.076754 0.044385 +v -0.027223 -0.070922 0.053234 +v -0.113589 -0.055834 -0.014399 +v -0.118686 -0.047488 -0.012807 +v -0.114749 -0.050830 -0.018229 +v -0.084242 -0.067422 -0.033634 +v -0.066602 -0.071209 -0.041136 +v -0.063307 -0.078073 -0.036359 +v -0.079788 -0.075865 -0.025243 +v -0.062888 -0.081163 -0.029372 +v -0.102509 -0.062809 -0.021376 +v -0.094073 -0.070270 -0.016250 +v -0.105211 -0.063719 -0.014109 +v -0.101814 -0.058105 -0.026520 +v -0.111277 -0.050638 -0.022328 +v -0.040629 -0.077695 -0.043559 +v -0.048526 -0.071806 -0.047473 +v -0.028389 -0.071155 -0.052877 +v -0.011952 -0.077075 -0.049911 +v -0.039073 0.135171 0.045962 +v -0.030792 0.115840 0.065953 +v -0.038486 0.135150 -0.046932 +v -0.033313 0.135201 -0.050884 +v -0.035947 0.132008 -0.055054 +v -0.033265 0.125780 -0.061715 +v -0.037374 0.128096 -0.058492 +v -0.032342 0.120199 -0.064618 +v -0.032230 0.114761 -0.065815 +v -0.017234 0.146244 0.014044 +v -0.026295 0.142451 0.027206 +v -0.024136 0.141579 0.035620 +v -0.058078 0.120438 0.052104 +v -0.049329 0.109560 0.062323 +v -0.056023 0.114911 0.057753 +v -0.094433 0.100826 0.027437 +v -0.111644 0.084175 0.023135 +v -0.096725 0.097095 0.034630 +v -0.114117 0.079023 0.028096 +v -0.110003 0.081041 0.033958 +v -0.094849 0.092014 0.043120 +v -0.111836 0.073854 0.036821 +v -0.106945 0.072940 0.041917 +v -0.081112 0.088245 0.053505 +v -0.103367 0.069668 0.044602 +v -0.080017 0.111565 0.037107 +v -0.082767 0.104866 0.044414 +v -0.076659 0.100270 0.052930 +v -0.060089 0.124535 0.042387 +v -0.115289 0.070957 0.031237 +v -0.106068 -0.004529 0.042933 +v -0.111329 -0.004433 0.037816 +v -0.115240 -0.002646 0.031669 +v -0.112926 0.081797 -0.026018 +v -0.114932 0.073905 -0.030919 +v -0.117213 0.075469 -0.019023 +v -0.116530 0.079471 0.002250 +v -0.119526 0.073567 0.002219 +v -0.120473 0.066704 -0.011055 +v -0.120003 0.067998 0.013353 +v -0.114358 0.069259 -0.033685 +v -0.110042 0.081141 -0.033761 +v -0.108004 0.076694 -0.039571 +v -0.106438 0.070060 -0.042837 +v -0.022422 -0.039217 0.065870 +v -0.044595 -0.031904 0.063333 +v -0.115882 -0.023079 0.026184 +v -0.119054 -0.024513 0.018047 +v -0.115010 -0.002464 -0.032100 +v -0.112240 -0.005232 -0.036616 +v -0.105809 -0.004338 -0.043160 +v -0.051405 0.113963 -0.060245 +v -0.098492 0.095623 -0.034037 +v -0.096851 0.098534 -0.029005 +v -0.095453 0.092304 -0.042346 +v -0.090463 0.083404 -0.049792 +v -0.077529 0.099252 -0.052706 +v -0.076136 0.091398 -0.055090 +v -0.072309 0.109602 -0.050253 +v -0.078262 0.110424 -0.042740 +v -0.083099 0.109718 -0.033279 +v -0.054469 0.105469 -0.061196 +v -0.067940 0.120157 -0.038167 +v -0.055874 0.118603 -0.055209 +v -0.058392 0.123046 -0.048148 +v -0.040195 0.135212 -0.042828 +v -0.118476 -0.022826 -0.020583 +v -0.038556 -0.033045 -0.064508 +v -0.080845 -0.018663 -0.053448 +v -0.091612 -0.015708 -0.048645 +v -0.028175 0.140896 -0.035557 +v -0.057278 0.128717 0.000059 +v -0.075169 0.116848 0.011497 +v -0.099562 0.097340 -0.005763 +v -0.037403 0.138702 -0.002089 +v -0.018055 0.145806 -0.017250 +v -0.012106 0.147491 -0.000219 +v -0.042496 -0.086206 -0.018239 +v -0.029577 -0.088387 0.010957 +v -0.000062 -0.091673 -0.000727 +v -0.058923 -0.028171 -0.059961 +v -0.060927 -0.026997 0.059483 +v -0.083794 -0.017883 0.052371 +v 0.000000 -0.079603 -0.047923 +v 0.000002 -0.089820 -0.021267 +v 0.000000 -0.087845 0.027875 +v -0.000029 -0.032778 0.069312 +v 0.000001 0.130996 -0.061748 +v 0.000000 0.139359 -0.049003 +v -0.000105 0.121370 -0.067287 +v -0.002237 0.118842 -0.068004 +v -0.000004 0.148576 0.011578 +v 0.000000 0.146482 -0.023946 +v -0.002785 0.104368 -0.084271 +v -0.000005 0.103379 -0.086291 +v -0.002191 0.100480 -0.086526 +v -0.000001 0.095906 -0.085348 +v -0.002010 0.095676 -0.084753 +v -0.002208 0.090130 -0.077169 +v 0.000000 0.090483 -0.078039 +v -0.000001 0.080803 -0.071196 +v -0.002369 0.076298 -0.069717 +v -0.002755 0.081514 -0.071075 +v 0.000004 0.111989 -0.072970 +v -0.002771 0.113314 -0.071276 +v -0.002700 0.107833 -0.077746 +v -0.002747 -0.001295 -0.084930 +v -0.000006 -0.002584 -0.086741 +v -0.002582 -0.005377 -0.086215 +v -0.000002 -0.010856 -0.083717 +v -0.002793 -0.008414 -0.084907 +v -0.002687 -0.010801 -0.082212 +v -0.002174 -0.011468 -0.071050 +v 0.000000 -0.011626 -0.071819 +v -0.002442 0.016977 -0.070035 +v -0.000001 0.008981 -0.073846 +v -0.002228 0.009023 -0.073868 +v -0.002658 0.003405 -0.078508 +v -0.003077 0.011384 -0.070896 +v -0.003106 -0.010469 -0.070796 +v -0.002910 0.097471 -0.085177 +v -0.002938 0.091123 -0.076852 +v -0.002713 0.096323 0.084978 +v -0.000005 0.097517 0.086697 +v -0.002010 0.100457 0.086439 +v -0.000001 0.104788 0.084736 +v -0.002165 0.104518 0.084586 +v -0.002698 0.107833 0.077745 +v 0.000004 0.111912 0.073126 +v -0.001908 0.113346 0.071882 +v -0.000005 0.087710 0.075292 +v -0.002442 0.078035 0.070037 +v -0.002733 0.091688 0.078528 +v -0.002741 0.083532 0.071871 +v -0.000004 -0.010420 0.084652 +v -0.002737 -0.010833 0.081858 +v -0.002153 -0.011488 0.071012 +v -0.002850 -0.008967 0.084489 +v -0.002489 -0.006885 0.085953 +v -0.000003 -0.001770 0.086148 +v -0.002264 -0.003844 0.086212 +v -0.002764 -0.000945 0.084542 +v -0.002040 0.004842 0.077249 +v 0.000000 0.005922 0.076508 +v -0.002226 0.018994 0.069712 +v -0.002701 0.012709 0.071516 +v -0.000001 0.015649 0.070780 +v -0.002906 0.004104 0.076793 +v -0.003009 -0.010397 0.071313 +v -0.002910 0.102852 0.085143 +v -0.003105 0.113001 0.070567 +v 0.042000 -0.087417 -0.021599 +v 0.027737 -0.088543 -0.016903 +v 0.000000 -0.087576 -0.023421 +v 0.000000 -0.089086 -0.014727 +v 0.042000 -0.077809 -0.055626 +v 0.034937 -0.077425 -0.052115 +v 0.035000 -0.078062 -0.055646 +v 0.033317 -0.077695 -0.048333 +v 0.042000 -0.078980 -0.045302 +v -0.000001 0.144902 -0.055674 +v 0.000000 0.152536 -0.020745 +v 0.001809 0.143890 -0.058074 +v 0.001986 0.154187 -0.005331 +v 0.000004 0.154027 0.009718 +v 0.001834 0.154204 0.007135 +v 0.003970 0.153981 0.002393 +v 0.041999 0.154104 -0.010277 +v 0.040118 0.154147 -0.006683 +v 0.038031 0.153981 -0.002393 +v 0.004507 0.153983 -0.002230 +v 0.039132 0.153980 0.002861 +v 0.042000 0.152632 0.019893 +v 0.040000 0.152398 0.021471 +v 0.041998 0.142707 -0.060586 +v 0.038142 0.140863 -0.062288 +v 0.040206 0.144070 -0.057686 +v 0.000000 0.139457 -0.064088 +v 0.003970 0.140839 -0.062320 +v 0.010412 0.135836 -0.067503 +v 0.032567 0.136472 -0.066906 +v 0.022422 0.136578 -0.066810 +v 0.018500 0.135800 -0.067537 +v 0.042000 0.051049 -0.146556 +v 0.042000 0.046870 -0.138492 +v 0.041948 0.040694 -0.146227 +v 0.041949 0.040686 0.146224 +v 0.042000 0.046701 0.138527 +v 0.042000 0.051049 0.146556 +v 0.041904 0.041619 0.137847 +v 0.042000 0.049363 0.097061 +v 0.042000 0.043324 0.094900 +v 0.042000 0.052978 0.096079 +v 0.042000 0.049790 -0.134920 +v 0.041849 0.041472 -0.137820 +v 0.042000 0.049739 0.135109 +v 0.042000 0.065713 -0.127447 +v 0.042000 0.032846 0.093333 +v 0.041761 0.033477 0.098168 +v 0.042000 0.065478 0.127439 +v 0.041976 0.036415 0.100351 +v 0.042000 0.082217 0.117492 +v 0.042000 0.092773 0.102976 +v 0.042000 0.115126 0.086803 +v 0.042000 0.089752 0.095613 +v 0.042000 0.098672 -0.102148 +v 0.042000 0.093307 -0.101488 +v 0.042000 0.032394 -0.092985 +v 0.042000 0.043521 -0.094944 +v 0.042000 0.052874 -0.096141 +v 0.042000 0.049230 -0.096855 +v 0.042000 0.052090 0.114150 +v 0.042000 0.052146 -0.114291 +v 0.041840 0.033502 -0.098172 +v 0.041776 0.036131 -0.100210 +v 0.042000 0.088310 -0.095173 +v 0.041999 0.140440 0.063047 +v 0.041930 0.037824 -0.100010 +v 0.003853 -0.015553 -0.093224 +v 0.007151 -0.015546 -0.088861 +v 0.003967 -0.015603 -0.080362 +v 0.012444 -0.015649 -0.092151 +v 0.021656 -0.015510 -0.088532 +v 0.016754 -0.015605 -0.092725 +v 0.038031 -0.015594 -0.080502 +v 0.037999 -0.015528 -0.093369 +v 0.036069 -0.015526 -0.089168 +v 0.030489 -0.015556 -0.090533 +v 0.025094 -0.015532 -0.093496 +v 0.033847 -0.000399 -0.095466 +v 0.021799 -0.000456 -0.095359 +v 0.023387 -0.002281 -0.093930 +v 0.031363 -0.002899 -0.093171 +v 0.022966 -0.003595 -0.091087 +v 0.033641 -0.003601 -0.090206 +v 0.019648 -0.000528 -0.095139 +v 0.004614 -0.000561 -0.094823 +v 0.007513 -0.000403 -0.095427 +v 0.010320 -0.002097 -0.094169 +v 0.018363 -0.002899 -0.093171 +v 0.009965 -0.003596 -0.091087 +v 0.019640 -0.003564 -0.090788 +v 0.040154 -0.000100 -0.095339 +v 0.036726 -0.003061 -0.093010 +v 0.041994 -0.003109 -0.093140 +v 0.010121 0.045684 -0.150450 +v 0.018892 0.045534 -0.150476 +v 0.016903 0.041508 -0.150534 +v 0.012007 0.041505 -0.150519 +v 0.023683 0.045200 -0.150519 +v 0.032180 0.045725 -0.150440 +v 0.029902 0.041531 -0.150533 +v 0.025007 0.041505 -0.150519 +v 0.042016 -0.012451 -0.076540 +v 0.042000 -0.003490 -0.085466 +v 0.042000 -0.000157 -0.081589 +v 0.041898 -0.011065 -0.094411 +v 0.037961 -0.010332 -0.098580 +v 0.004056 -0.010351 -0.098589 +v 0.038113 -0.000025 -0.097182 +v 0.004105 -0.000131 -0.097244 +v 0.037932 0.011608 -0.099023 +v 0.004107 0.011704 -0.099081 +v 0.038089 0.021824 -0.104172 +v 0.004095 0.024573 -0.106164 +v 0.038050 0.030144 -0.112178 +v 0.004059 0.033567 -0.117616 +v 0.037899 0.035886 -0.123194 +v 0.004080 0.036877 -0.127216 +v 0.038103 0.037802 -0.135059 +v 0.004056 0.037778 -0.135199 +v 0.037944 0.036411 -0.145351 +v 0.004042 0.036420 -0.145334 +v 0.025037 0.082217 -0.117492 +v 0.034310 0.065889 -0.132718 +v 0.031146 0.063993 -0.134486 +v 0.025037 0.048488 -0.148944 +v 0.033926 0.061997 -0.136347 +v 0.038639 0.047308 -0.149917 +v 0.036779 0.063696 -0.134763 +v 0.023336 0.133825 -0.069367 +v 0.010151 0.065178 -0.133381 +v 0.021549 0.065831 -0.132772 +v 0.018203 0.064355 -0.134149 +v 0.020494 0.062105 -0.136423 +v 0.023806 0.063467 -0.134977 +v 0.023244 0.099293 -0.101568 +v 0.019178 0.099001 -0.101841 +v 0.023000 0.112435 -0.089313 +v 0.023010 0.101679 -0.099343 +v 0.019398 0.102282 -0.098781 +v 0.003363 0.047355 -0.149920 +v 0.000000 0.051049 -0.146556 +v 0.005761 0.099205 -0.101651 +v 0.005824 0.133823 -0.069368 +v 0.005661 0.065206 -0.133355 +v 0.006793 0.062172 -0.136184 +v 0.009980 0.062647 -0.135741 +v 0.010245 0.099279 -0.101581 +v 0.009894 0.101812 -0.099219 +v 0.006697 0.102266 -0.098796 +v 0.009109 0.132996 -0.070140 +v 0.006228 0.136512 -0.066861 +v 0.019793 0.133113 -0.070030 +v 0.035606 0.102081 -0.098968 +v 0.031395 0.101457 -0.099550 +v 0.036500 0.099957 -0.100949 +v 0.033676 0.098468 -0.102338 +v 0.035606 0.136455 -0.066914 +v 0.035845 0.133168 -0.069980 +v 0.031396 0.134242 -0.068978 +v 0.000000 -0.079749 -0.044866 +v 0.000000 -0.073156 -0.053715 +v 0.033484 -0.073979 -0.053075 +v 0.033510 -0.068065 -0.056362 +v 0.031794 -0.033103 -0.069266 +v 0.042000 -0.066816 -0.056591 +v 0.032463 -0.059569 -0.059446 +v 0.007402 -0.059772 -0.059337 +v 0.008059 -0.032943 -0.069265 +v 0.038177 -0.018830 -0.074334 +v 0.004061 -0.019091 -0.074246 +v 0.040578 0.025185 -0.104014 +v 0.005667 0.025160 -0.103926 +v 0.005676 0.015083 -0.098216 +v 0.039920 0.012704 -0.097358 +v 0.004789 0.006566 -0.095772 +v 0.042101 0.029552 -0.102989 +v 0.006140 0.028632 -0.103372 +v 0.040224 0.030321 -0.101950 +v 0.005643 0.032982 -0.098845 +v 0.040218 0.032772 -0.099328 +v 0.005097 0.031272 -0.092609 +v 0.005337 0.033199 -0.094911 +v 0.005604 0.001297 -0.081724 +v 0.005582 -0.003351 -0.085462 +v 0.005673 -0.001811 -0.082945 +v 0.006695 -0.003564 -0.090771 +v 0.002241 0.000201 -0.092056 +v 0.002394 0.014061 -0.094861 +v 0.002121 0.001103 -0.085285 +v 0.002216 0.030051 -0.095372 +v 0.002181 0.026524 -0.100574 +v 0.002000 0.053041 -0.095975 +v 0.002000 0.088481 -0.095248 +v 0.002000 0.052090 -0.114150 +v 0.002000 0.065478 -0.127439 +v 0.002000 0.093298 -0.101723 +v 0.005075 0.049298 -0.135802 +v 0.005837 0.046515 -0.138344 +v 0.006590 0.044199 -0.138583 +v 0.005566 0.049595 -0.098310 +v 0.005458 0.043048 -0.095238 +v 0.004774 0.047147 -0.095780 +v 0.040085 0.035895 -0.101894 +v 0.005987 0.031370 -0.106751 +v 0.040384 0.032888 -0.104696 +v 0.040424 0.030966 -0.109901 +v 0.005025 0.031229 -0.109902 +v 0.042077 0.032023 -0.105259 +v 0.040082 0.039597 -0.134759 +v 0.005194 0.039813 -0.134858 +v 0.039959 0.037678 -0.122262 +v 0.005644 0.038754 -0.126594 +v 0.005695 0.035848 -0.118029 +v 0.034152 0.039524 -0.135408 +v 0.036705 0.042111 -0.138104 +v 0.033947 0.044730 -0.138573 +v 0.008892 0.039667 -0.135425 +v 0.006557 0.039896 -0.135571 +v 0.021154 0.039537 -0.135397 +v 0.018219 0.042336 -0.138243 +v 0.010637 0.041829 -0.137899 +v 0.009360 0.044212 -0.138563 +v 0.021002 0.044599 -0.138559 +v 0.031274 0.041989 -0.138050 +v 0.023725 0.042508 -0.138323 +v 0.002300 0.033904 -0.108938 +v 0.002371 0.038717 -0.118347 +v 0.002263 0.044685 -0.097764 +v 0.002072 0.044092 -0.135119 +v 0.035335 -0.014472 -0.095644 +v 0.038025 -0.013815 -0.097020 +v 0.022308 -0.014474 -0.095547 +v 0.031237 -0.014951 -0.095041 +v 0.020028 -0.014485 -0.095741 +v 0.008699 -0.014393 -0.095760 +v 0.006884 -0.014467 -0.095815 +v 0.004016 -0.013591 -0.097170 +v 0.037848 0.044297 -0.150641 +v 0.004333 0.044398 -0.150642 +v 0.021747 0.039192 -0.149420 +v 0.032317 0.039653 -0.149509 +v 0.004104 0.040587 -0.150382 +v 0.008224 0.039023 -0.149348 +v 0.004025 0.037720 -0.148500 +v 0.037983 0.037839 -0.148603 +v 0.035212 0.039346 -0.149451 +v 0.037897 0.041023 -0.150468 +v 0.019322 0.039610 -0.149532 +v 0.003110 0.031991 -0.097297 +v 0.003658 0.027673 -0.102551 +v 0.003348 0.024747 -0.102277 +v 0.003383 0.000590 -0.083026 +v 0.002720 -0.001134 -0.085373 +v 0.005313 -0.002938 -0.092741 +v 0.003619 -0.002160 -0.091722 +v 0.003661 0.032768 -0.106865 +v 0.002743 0.047497 -0.098678 +v 0.002829 0.040731 -0.126298 +v 0.003238 0.041513 -0.135462 +v 0.002812 0.047600 -0.134891 +v 0.005290 0.042161 -0.137852 +v 0.003386 0.045477 -0.137155 +v 0.000003 -0.016838 -0.070974 +v 0.000002 -0.025510 -0.068032 +v 0.000002 -0.011995 -0.078076 +v 0.000065 -0.011117 -0.094348 +v 0.000177 -0.000537 -0.093331 +v 0.000193 0.019133 -0.097454 +v 0.000761 0.029472 -0.106208 +v 0.000229 0.038616 -0.118895 +v 0.000301 0.041480 -0.135295 +v 0.000013 0.040760 -0.146195 +v 0.020551 0.044686 -0.148994 +v 0.023749 0.042248 -0.148992 +v 0.018483 0.042515 -0.149045 +v 0.005318 0.041862 -0.149051 +v 0.007516 0.044694 -0.149007 +v 0.010290 0.043194 -0.149048 +v 0.010178 0.040433 -0.149021 +v 0.035169 0.044411 -0.149047 +v 0.036561 0.042048 -0.149045 +v 0.031671 0.043418 -0.148997 +v 0.020049 -0.014011 -0.090447 +v 0.018400 -0.014050 -0.093458 +v 0.023567 -0.014030 -0.092046 +v 0.007257 -0.014034 -0.090415 +v 0.005397 -0.014060 -0.092773 +v 0.010093 -0.014028 -0.091460 +v 0.010348 -0.014069 -0.094248 +v 0.031331 -0.014044 -0.093232 +v 0.033498 -0.014012 -0.090322 +v 0.036595 -0.014048 -0.092289 +v 0.006189 0.129543 -0.059660 +v 0.010245 0.129245 -0.059924 +v 0.008000 0.127030 -0.059976 +v 0.009749 0.126596 -0.062423 +v 0.006076 0.126556 -0.062431 +v 0.021000 0.127030 -0.059976 +v 0.020267 0.129880 -0.059365 +v 0.023337 0.129083 -0.060088 +v 0.021811 0.125982 -0.062918 +v 0.018263 0.127992 -0.061106 +v 0.034874 0.129939 -0.059291 +v 0.036602 0.127929 -0.061185 +v 0.034000 0.127030 -0.059976 +v 0.034541 0.126078 -0.062891 +v 0.031108 0.128145 -0.060907 +v 0.021000 0.056088 -0.126130 +v 0.021627 0.058964 -0.125499 +v 0.023673 0.057323 -0.127016 +v 0.020830 0.054953 -0.129163 +v 0.018443 0.057909 -0.126446 +v 0.021841 0.095507 -0.091413 +v 0.023716 0.093161 -0.093582 +v 0.021000 0.092656 -0.092030 +v 0.020127 0.091769 -0.094884 +v 0.018443 0.094477 -0.092346 +v 0.009046 0.058856 -0.125597 +v 0.010707 0.056800 -0.127494 +v 0.008000 0.056088 -0.126130 +v 0.006841 0.055129 -0.128995 +v 0.005860 0.058349 -0.126049 +v 0.035924 0.058571 -0.125829 +v 0.035947 0.055747 -0.128485 +v 0.034000 0.056088 -0.126130 +v 0.031868 0.055708 -0.128480 +v 0.032252 0.058560 -0.125868 +v 0.005586 0.094811 -0.091991 +v 0.010054 0.094991 -0.091880 +v 0.008000 0.092656 -0.092030 +v 0.010170 0.092620 -0.094111 +v 0.007126 0.091769 -0.094884 +v 0.035159 0.095581 -0.091273 +v 0.036437 0.093075 -0.093690 +v 0.034000 0.092656 -0.092030 +v 0.033576 0.091595 -0.095015 +v 0.031386 0.094135 -0.092688 +v 0.032392 -0.088673 -0.016177 +v 0.030867 -0.088842 -0.015537 +v 0.029271 -0.089236 -0.014563 +v 0.032112 -0.089263 -0.014600 +v 0.042000 -0.089751 -0.013713 +v 0.026830 -0.089196 -0.014673 +v 0.042000 -0.091916 -0.011906 +v 0.000000 -0.091925 -0.011902 +v 0.042000 -0.088866 0.015431 +v 0.042001 -0.091729 0.011726 +v 0.000000 -0.091916 0.011906 +v 0.000000 -0.089225 0.014444 +v 0.035106 -0.072548 -0.057457 +v 0.042000 -0.072974 -0.057443 +v 0.042000 -0.090010 -0.027383 +v 0.042000 -0.084200 -0.043313 +v 0.002775 0.143404 -0.000720 +v 0.039048 0.143447 -0.000519 +v 0.002148 0.131161 -0.058320 +v 0.039503 0.130914 -0.059478 +v 0.004974 0.130713 -0.060427 +v 0.010163 -0.055632 -0.063885 +v 0.029720 -0.055594 -0.064182 +v 0.009492 -0.057028 -0.061846 +v 0.030614 -0.057044 -0.061781 +v 0.010964 -0.052829 -0.073850 +v 0.029031 -0.052811 -0.073876 +v 0.009829 -0.036347 -0.069723 +v 0.029971 -0.037913 -0.070071 +v 0.030007 -0.052275 -0.072942 +v 0.009993 -0.052242 -0.072961 +v 0.026674 -0.082000 -0.015825 +v 0.028839 -0.082000 -0.016610 +v 0.028286 -0.082000 -0.013952 +v 0.031554 -0.080222 -0.014566 +v 0.032662 -0.080222 -0.015668 +v 0.031224 -0.080222 -0.016189 +v 0.000000 -0.090010 -0.027388 +v 0.021809 -0.086464 -0.037281 +v 0.018763 -0.087004 -0.035797 +v 0.000000 -0.084203 -0.043326 +v 0.020574 -0.087871 -0.033414 +v 0.023040 -0.087438 -0.034604 +v 0.005588 -0.086266 -0.037824 +v 0.005902 -0.088107 -0.032766 +v 0.036207 -0.086338 -0.037626 +v 0.032207 -0.086876 -0.036149 +v 0.034922 -0.088099 -0.032787 +v 0.037594 -0.087343 -0.034864 +v 0.009793 -0.087105 -0.035518 +v 0.035000 -0.076353 -0.031430 +v 0.036311 -0.076924 -0.034196 +v 0.037533 -0.077970 -0.031363 +v 0.035067 -0.078682 -0.029365 +v 0.032183 -0.077474 -0.032562 +v 0.008773 -0.076964 -0.034018 +v 0.008811 -0.078449 -0.030007 +v 0.007000 -0.076353 -0.031430 +v 0.005555 -0.078502 -0.029903 +v 0.004443 -0.077355 -0.032983 +v 0.021507 -0.077040 -0.033905 +v 0.023156 -0.077980 -0.031251 +v 0.021000 -0.076635 -0.031533 +v 0.020138 -0.078429 -0.030087 +v 0.018924 -0.077511 -0.032595 +v 0.027675 -0.088549 0.016873 +v 0.000000 -0.087521 0.023141 +v 0.042000 -0.087553 0.023366 +v 0.033283 -0.077657 0.048449 +v 0.042000 -0.077526 0.048540 +v 0.034917 -0.077406 0.051974 +v 0.042000 -0.078077 0.055640 +v 0.035000 -0.078096 0.055525 +v -0.000002 0.145015 0.055538 +v 0.001903 0.143041 0.059562 +v -0.000001 0.139508 0.064012 +v 0.004507 0.140719 0.062456 +v 0.038034 0.140841 0.062317 +v 0.034170 0.137004 0.066405 +v 0.019398 0.136465 0.066918 +v 0.023603 0.135832 0.067506 +v 0.040151 0.143671 0.058383 +v 0.042000 0.145649 0.053392 +v 0.038074 -0.015527 0.093516 +v 0.034878 -0.015527 0.088732 +v 0.038042 -0.015592 0.080485 +v 0.010290 -0.015535 0.089283 +v 0.003934 -0.015984 0.077941 +v 0.005136 -0.015550 0.089975 +v 0.004168 -0.015335 0.094651 +v 0.018926 -0.015535 0.089158 +v 0.030281 -0.015564 0.091095 +v 0.025355 -0.015665 0.091602 +v 0.017005 -0.015497 0.093679 +v 0.011981 -0.015502 0.093680 +v 0.036414 -0.003409 0.091959 +v 0.035742 -0.000750 0.095107 +v 0.041991 -0.003137 0.093069 +v 0.039615 0.001059 0.095930 +v 0.032929 -0.000451 0.095275 +v 0.004493 -0.000381 0.094836 +v 0.019935 -0.000453 0.095280 +v 0.009333 -0.000533 0.095145 +v 0.006858 -0.000460 0.095259 +v 0.010499 -0.002520 0.093678 +v 0.018560 -0.002431 0.093746 +v 0.019265 -0.003607 0.090829 +v 0.009849 -0.003557 0.091135 +v 0.006877 -0.003587 0.090593 +v 0.022335 -0.000534 0.095144 +v 0.023498 -0.002520 0.093678 +v 0.031560 -0.002431 0.093746 +v 0.031792 -0.003476 0.091625 +v 0.022849 -0.003557 0.091135 +v 0.034094 -0.003561 0.090389 +v 0.037892 0.040588 0.150381 +v 0.038258 0.046645 0.150299 +v 0.036896 0.044932 0.150548 +v 0.012096 0.041527 0.150531 +v 0.017019 0.041320 0.150502 +v 0.018317 0.045200 0.150519 +v 0.009829 0.045726 0.150446 +v 0.025106 0.041737 0.150554 +v 0.031876 0.045685 0.150453 +v 0.023108 0.045534 0.150476 +v 0.030019 0.041336 0.150500 +v 0.041929 0.028822 0.103220 +v 0.041966 0.031287 0.103808 +v 0.042072 0.031804 0.106161 +v 0.041885 -0.011027 0.094449 +v 0.042000 -0.003478 0.085351 +v 0.042000 -0.012404 0.076380 +v 0.042000 -0.000006 0.081578 +v 0.037954 0.036420 0.145336 +v 0.004057 0.036412 0.145351 +v 0.038079 0.037825 0.134980 +v 0.004270 0.037691 0.135396 +v 0.037907 0.035841 0.122986 +v 0.004135 0.036687 0.125576 +v 0.038078 0.031531 0.114253 +v 0.004132 0.031592 0.114112 +v 0.038185 0.024933 0.106446 +v 0.004041 0.023534 0.105339 +v 0.037867 0.015369 0.100383 +v 0.004093 0.012014 0.099159 +v 0.038024 -0.000731 0.097259 +v 0.004107 -0.000051 0.097217 +v 0.037943 -0.010351 0.098588 +v 0.004046 -0.010336 0.098580 +v 0.033844 0.062029 0.136318 +v 0.025038 0.048488 0.148944 +v 0.031419 0.063370 0.135067 +v 0.031592 0.099618 0.101265 +v 0.033914 0.066108 0.132514 +v 0.036604 0.063301 0.135132 +v 0.003362 0.047304 0.149918 +v 0.008274 0.062109 0.136423 +v 0.000000 0.051049 0.146556 +v 0.005905 0.062797 0.135602 +v 0.006439 0.065785 0.132815 +v 0.010854 0.063993 0.134486 +v 0.000000 0.090334 0.109923 +v 0.022150 0.133170 0.069978 +v 0.020486 0.065777 0.132822 +v 0.023163 0.065099 0.133454 +v 0.020767 0.061982 0.136361 +v 0.018207 0.064053 0.134430 +v 0.023211 0.062935 0.135473 +v 0.022641 0.102007 0.099038 +v 0.018755 0.133653 0.069527 +v 0.019394 0.102081 0.098968 +v 0.018592 0.099618 0.101265 +v 0.021226 0.098609 0.102206 +v 0.023488 0.099763 0.101130 +v 0.032561 0.102209 0.098849 +v 0.036793 0.101112 0.099872 +v 0.034532 0.098604 0.102211 +v 0.033613 0.132958 0.070175 +v 0.036604 0.134242 0.068978 +v 0.031325 0.134647 0.068600 +v 0.006242 0.101949 0.099092 +v 0.009482 0.102145 0.098909 +v 0.010120 0.099037 0.101807 +v 0.005664 0.099448 0.101423 +v 0.000000 0.115126 0.086803 +v 0.010333 0.133524 0.069647 +v 0.005207 0.134263 0.068958 +v 0.008415 0.136940 0.066461 +v 0.033253 -0.067563 0.056454 +v 0.000000 -0.072923 0.053782 +v 0.032960 -0.072717 0.053782 +v 0.000000 -0.079804 0.044778 +v 0.042000 -0.068287 0.056284 +v 0.032347 -0.059401 0.059539 +v 0.007697 -0.059487 0.059500 +v 0.008112 -0.032916 0.069294 +v 0.032723 -0.031611 0.069542 +v 0.038142 -0.018766 0.074426 +v 0.004124 -0.022882 0.072430 +v 0.039978 0.012652 0.097293 +v 0.005644 0.008406 0.096246 +v 0.005326 0.017066 0.099131 +v 0.040440 0.025105 0.104036 +v 0.005586 0.024824 0.103796 +v 0.006183 0.028528 0.103467 +v 0.005289 0.032804 0.098989 +v 0.040094 0.032583 0.099582 +v 0.040201 0.030559 0.101715 +v 0.005679 0.033458 0.095606 +v 0.004799 0.031471 0.092827 +v 0.004643 0.001923 0.082051 +v 0.005595 -0.001126 0.082415 +v 0.004724 -0.003169 0.085497 +v 0.002178 0.016154 0.095090 +v 0.002375 -0.000658 0.091807 +v 0.002308 0.000112 0.084820 +v 0.002187 0.026017 0.100620 +v 0.002171 0.029879 0.095460 +v 0.002000 0.088399 0.095229 +v 0.002000 0.052934 0.096034 +v 0.002000 0.052146 0.114291 +v 0.002000 0.065713 0.127447 +v 0.002000 0.093307 0.101488 +v 0.005769 0.046479 0.138365 +v 0.005194 0.049411 0.135582 +v 0.005460 0.049457 0.097873 +v 0.004510 0.046439 0.095577 +v 0.006217 0.042914 0.095215 +v 0.005980 0.031342 0.106792 +v 0.040153 0.033241 0.104521 +v 0.040260 0.036181 0.101451 +v 0.040529 0.030983 0.109831 +v 0.005472 0.031319 0.110358 +v 0.004784 0.035946 0.117828 +v 0.039932 0.037818 0.122692 +v 0.005608 0.038739 0.126440 +v 0.005078 0.039858 0.134944 +v 0.040160 0.039675 0.135109 +v 0.022736 0.044171 0.138606 +v 0.035058 0.044434 0.138571 +v 0.032151 0.043865 0.138557 +v 0.031502 0.041322 0.137520 +v 0.023440 0.041254 0.137431 +v 0.022065 0.039720 0.135453 +v 0.034100 0.039518 0.135405 +v 0.009054 0.039706 0.135473 +v 0.019665 0.039856 0.135534 +v 0.018502 0.041322 0.137520 +v 0.010692 0.042138 0.138102 +v 0.019151 0.043865 0.138557 +v 0.008294 0.044661 0.138577 +v 0.006619 0.039863 0.135523 +v 0.036636 0.041826 0.137909 +v 0.002086 0.045174 0.098504 +v 0.002285 0.040619 0.122564 +v 0.002406 0.033543 0.109066 +v 0.001983 0.044387 0.134580 +v 0.030818 -0.015107 0.095074 +v 0.022157 -0.014497 0.095823 +v 0.003996 -0.013828 0.097036 +v 0.009124 -0.014478 0.095813 +v 0.037983 -0.013603 0.097161 +v 0.020320 -0.014360 0.095744 +v 0.035160 -0.014478 0.095806 +v 0.004151 0.044297 0.150640 +v 0.037978 0.037761 0.148549 +v 0.003994 0.038030 0.148845 +v 0.032989 0.039110 0.149440 +v 0.022209 0.039425 0.149498 +v 0.008724 0.039199 0.149451 +v 0.004413 0.040208 0.150259 +v 0.019919 0.039262 0.149433 +v 0.003218 0.026691 0.102620 +v 0.002807 0.031679 0.096651 +v 0.002836 0.010882 0.094700 +v 0.005340 -0.002923 0.092790 +v 0.003408 0.032564 0.107528 +v 0.003707 0.043022 0.096597 +v 0.003153 0.047981 0.098492 +v 0.002781 0.042052 0.135037 +v 0.002759 0.047625 0.134460 +v 0.005254 0.042488 0.137997 +v 0.003919 0.042879 0.137397 +v 0.002825 0.045754 0.136441 +v 0.000003 -0.016838 0.070974 +v 0.000002 -0.025510 0.068032 +v 0.000002 -0.011995 0.078076 +v 0.000106 -0.011071 0.094391 +v 0.000207 0.011016 0.094439 +v 0.000732 0.019617 0.099160 +v 0.000217 0.032247 0.108477 +v 0.000727 0.038457 0.121093 +v 0.000205 0.041768 0.130789 +v 0.000019 0.040740 0.146192 +v 0.023443 0.041180 0.149058 +v 0.022971 0.043755 0.149026 +v 0.020056 0.044465 0.149043 +v 0.018418 0.042267 0.149044 +v 0.006647 0.044259 0.149052 +v 0.009848 0.043938 0.149016 +v 0.005424 0.041990 0.149061 +v 0.006684 0.039706 0.149034 +v 0.010443 0.041180 0.149058 +v 0.034515 0.039402 0.149048 +v 0.036443 0.041180 0.149058 +v 0.035971 0.043755 0.149026 +v 0.033056 0.044465 0.149043 +v 0.031418 0.042267 0.149044 +v 0.018326 -0.014057 0.093170 +v 0.020097 -0.014037 0.090521 +v 0.023486 -0.013962 0.091800 +v 0.006750 -0.014015 0.095502 +v 0.005501 -0.014054 0.092222 +v 0.008271 -0.013990 0.090243 +v 0.010581 -0.014042 0.092730 +v 0.033485 -0.014048 0.095598 +v 0.031248 -0.013989 0.092433 +v 0.034713 -0.014026 0.090417 +v 0.036581 -0.014042 0.092730 +v 0.008000 0.127030 0.059976 +v 0.008733 0.129881 0.059365 +v 0.005663 0.129084 0.060088 +v 0.006404 0.126462 0.062542 +v 0.009445 0.126464 0.062551 +v 0.010616 0.128339 0.060798 +v 0.022371 0.129694 0.059528 +v 0.018755 0.129245 0.059924 +v 0.021000 0.127030 0.059976 +v 0.019574 0.126332 0.062654 +v 0.023499 0.127125 0.061902 +v 0.033576 0.130081 0.059126 +v 0.031405 0.127402 0.061656 +v 0.034000 0.127030 0.059976 +v 0.034633 0.126134 0.062848 +v 0.036684 0.128170 0.060950 +v 0.021781 0.059045 0.125383 +v 0.018536 0.057812 0.126566 +v 0.021000 0.056088 0.126130 +v 0.019574 0.055390 0.128808 +v 0.023499 0.056184 0.128056 +v 0.022473 0.095414 0.091445 +v 0.018451 0.094398 0.092433 +v 0.021000 0.092656 0.092030 +v 0.019805 0.091910 0.094763 +v 0.023166 0.092508 0.094203 +v 0.008288 0.059004 0.125458 +v 0.005451 0.057830 0.126533 +v 0.008000 0.056088 0.126130 +v 0.007676 0.054966 0.129148 +v 0.010707 0.057399 0.126935 +v 0.034999 0.058964 0.125476 +v 0.031324 0.057669 0.126670 +v 0.034000 0.056088 0.126130 +v 0.033241 0.055217 0.128979 +v 0.036549 0.056369 0.127896 +v 0.008000 0.092656 0.092030 +v 0.008067 0.095669 0.091248 +v 0.005602 0.094362 0.092489 +v 0.006189 0.092165 0.094515 +v 0.009856 0.092248 0.094448 +v 0.010437 0.094282 0.092564 +v 0.034759 0.095559 0.091359 +v 0.032066 0.094920 0.091968 +v 0.034000 0.092656 0.092030 +v 0.031535 0.092884 0.093854 +v 0.034167 0.091775 0.094899 +v 0.036684 0.093272 0.093483 +v 0.039962 0.139421 0.059252 +v 0.039225 0.151497 0.002441 +v 0.002705 0.151516 0.002354 +v 0.002641 0.138991 0.061274 +v 0.037764 0.138836 0.062007 +v 0.027386 -0.089557 0.014022 +v 0.032796 -0.089028 0.015015 +v 0.030972 -0.089022 0.015039 +v 0.029331 -0.088873 0.015465 +v 0.031624 -0.088672 0.016249 +v 0.035134 -0.072469 0.057400 +v 0.042000 -0.072864 0.057530 +v 0.042000 -0.080482 0.044486 +v 0.042000 -0.084197 0.043329 +v 0.042000 -0.090013 0.027395 +v 0.029274 -0.056212 0.063335 +v 0.010729 -0.056208 0.063326 +v 0.029047 -0.052810 0.073865 +v 0.010975 -0.052803 0.073885 +v 0.009788 -0.035991 0.069668 +v 0.030265 -0.036235 0.069678 +v 0.030007 -0.052242 0.072961 +v 0.030171 -0.055288 0.063457 +v 0.009806 -0.055335 0.063361 +v 0.009993 -0.052275 0.072941 +v 0.029363 -0.082000 0.015164 +v 0.028026 -0.082000 0.016846 +v 0.027790 -0.082000 0.014068 +v 0.026669 -0.082000 0.015444 +v 0.031084 -0.080222 0.014807 +v 0.031855 -0.080222 0.016434 +v 0.032634 -0.080222 0.015194 +v 0.000000 -0.090001 0.027334 +v 0.021248 -0.087893 0.033353 +v 0.019134 -0.087480 0.034487 +v 0.005439 -0.086295 0.037743 +v 0.000000 -0.084221 0.043302 +v 0.019664 -0.086547 0.037051 +v 0.023234 -0.086933 0.035992 +v 0.009581 -0.086898 0.036088 +v 0.008387 -0.087933 0.033245 +v 0.005150 -0.087831 0.033525 +v 0.034423 -0.086205 0.037992 +v 0.037594 -0.086979 0.035864 +v 0.036207 -0.087985 0.033101 +v 0.032499 -0.087590 0.034185 +v 0.035000 -0.076353 0.031430 +v 0.035067 -0.076810 0.034509 +v 0.032602 -0.077442 0.032821 +v 0.033053 -0.078387 0.030196 +v 0.036708 -0.078478 0.029926 +v 0.037437 -0.077479 0.032718 +v 0.007070 -0.076752 0.034600 +v 0.004288 -0.077961 0.031318 +v 0.007000 -0.076353 0.031430 +v 0.007167 -0.078650 0.029497 +v 0.009684 -0.077931 0.031429 +v 0.021607 -0.077049 0.033880 +v 0.018960 -0.077476 0.032689 +v 0.021000 -0.076635 0.031533 +v 0.020370 -0.078475 0.029924 +v 0.023147 -0.077898 0.031532 +v 0.121573 0.044178 -0.089299 +v 0.042132 0.036540 -0.095613 +v 0.122441 0.084491 -0.089135 +v 0.042132 0.092220 -0.095505 +v 0.126563 0.036372 -0.087356 +v 0.126388 0.094247 -0.086828 +v 0.132630 0.103219 -0.082718 +v 0.042130 0.114609 -0.085465 +v 0.136610 0.111628 -0.077022 +v 0.042131 0.126861 -0.073846 +v 0.131588 0.119727 -0.069836 +v 0.042131 0.136594 -0.057718 +v 0.127047 0.125336 -0.061983 +v 0.145682 0.000495 -0.072769 +v 0.112968 -0.057865 -0.054618 +v 0.065752 -0.071763 -0.053639 +v 0.042133 -0.075449 -0.053804 +v 0.142099 -0.040768 -0.058087 +v 0.159088 0.011539 0.059239 +v 0.156502 -0.019657 0.052898 +v 0.160602 -0.006052 0.029509 +v 0.159319 0.010446 -0.057527 +v 0.159951 0.048658 -0.058026 +v 0.162472 0.034734 -0.035300 +v 0.162885 0.054728 -0.024424 +v 0.163205 0.019767 0.003107 +v 0.163521 0.048217 0.003872 +v 0.162398 0.036334 0.036370 +v 0.154245 -0.037722 0.045355 +v 0.153316 -0.050789 0.022060 +v 0.159970 -0.016335 -0.010059 +v 0.153185 -0.052896 -0.005808 +v 0.152069 -0.053657 -0.028282 +v 0.156177 -0.022976 -0.051689 +v 0.153033 -0.042644 -0.044617 +v 0.161525 0.005207 -0.028569 +v 0.159910 0.051945 0.058059 +v 0.153157 0.102240 0.066762 +v 0.156790 0.084251 0.061562 +v 0.155453 0.105920 0.047384 +v 0.158089 0.105121 0.002454 +v 0.160967 0.074600 0.034854 +v 0.161137 0.082638 -0.009974 +v 0.155642 0.105774 -0.045594 +v 0.158947 0.083378 -0.046458 +v 0.157330 0.080551 -0.060840 +v 0.153238 0.102277 -0.066582 +v 0.102512 0.137627 -0.040546 +v 0.087542 0.142928 -0.025578 +v 0.109255 0.137645 -0.019606 +v 0.139647 0.122353 -0.040989 +v 0.141804 0.115884 -0.068008 +v 0.150617 0.110749 -0.059771 +v 0.150517 0.109823 0.063873 +v 0.143757 0.118603 0.046566 +v 0.142736 0.115179 0.068093 +v 0.128296 0.125106 0.061054 +v 0.115818 0.131796 0.052200 +v 0.131855 0.127224 0.034651 +v 0.072927 0.146200 0.013186 +v 0.089069 0.142323 0.027494 +v 0.090611 0.143282 0.000800 +v 0.066008 0.147360 -0.005527 +v 0.114613 0.132380 -0.050880 +v 0.152337 0.113811 -0.027246 +v 0.152331 0.112316 0.039652 +v 0.128399 0.130089 -0.020790 +v 0.100079 0.138807 0.037323 +v 0.125212 0.132108 0.012535 +v 0.143671 0.121466 0.019699 +v 0.142136 0.123030 -0.006806 +v 0.109539 0.138035 0.005438 +v 0.151770 0.115326 0.006070 +v 0.122683 0.084229 0.089090 +v 0.042132 0.091664 0.095572 +v 0.122050 0.045398 0.089270 +v 0.042131 0.036499 0.095620 +v 0.124712 0.034870 0.087311 +v 0.042132 0.132031 0.067549 +v 0.129086 0.120837 0.069229 +v 0.042131 0.113595 0.086078 +v 0.136657 0.111875 0.076865 +v 0.131735 0.102792 0.083059 +v 0.127902 0.093492 0.086723 +v 0.146002 0.000962 0.072784 +v 0.140820 -0.040567 0.058424 +v 0.042131 -0.073957 0.054805 +v 0.065928 -0.072026 0.053468 +v 0.088280 -0.066153 0.053872 +v 0.063534 -0.076469 -0.049129 +v 0.092142 -0.068731 -0.051181 +v 0.084242 -0.080840 -0.036175 +v 0.121254 -0.073013 -0.030310 +v 0.121550 -0.058893 -0.051036 +v 0.144516 -0.061031 -0.033016 +v 0.146114 -0.052681 -0.043411 +v 0.146692 -0.043283 -0.054295 +v 0.101128 -0.082819 -0.024703 +v 0.062370 -0.076712 0.048960 +v 0.042143 -0.078638 0.049458 +v 0.042128 -0.088678 0.026185 +v 0.083498 -0.080693 0.036869 +v 0.097693 -0.084426 0.020763 +v 0.092605 -0.086948 0.003072 +v 0.042132 -0.091540 -0.005437 +v 0.093684 -0.086250 -0.012363 +v 0.042129 -0.086422 -0.032471 +v 0.042132 0.145132 -0.034255 +v 0.042135 0.149906 0.000569 +v 0.042131 0.145010 0.034852 +v 0.145307 -0.055630 0.040466 +v 0.144364 -0.042825 0.056101 +v 0.129776 -0.051773 0.054597 +v 0.099369 -0.082516 0.026237 +v 0.121010 -0.073717 0.029315 +v 0.078156 -0.073653 0.049358 +v 0.108538 -0.064055 0.050745 +v 0.145506 -0.061619 0.030307 +v 0.121147 -0.074934 0.021702 +v 0.145757 -0.063015 0.001466 +v 0.120918 -0.074671 -0.025528 +v 0.146940 -0.060925 -0.029297 +v 0.149695 0.102475 -0.072144 +v 0.155619 0.074522 -0.066442 +v 0.153063 0.003014 -0.069315 +v 0.138283 0.024194 -0.080952 +v 0.143471 0.103042 -0.077424 +v 0.133664 0.096344 -0.083930 +v 0.149467 0.099927 0.072570 +v 0.142611 0.102889 0.078080 +v 0.139510 0.022549 0.080141 +v 0.153230 0.002610 0.069106 +v 0.156773 0.067122 0.065120 +v 0.157644 0.027391 0.064061 +v 0.129000 0.036862 0.086323 +v 0.142076 0.113271 0.072830 +v 0.142581 0.107472 0.076985 +v 0.149966 0.105735 0.070064 +v 0.141863 0.113478 -0.072779 +v 0.142678 0.108610 -0.076324 +v 0.157301 0.003751 0.063073 +v 0.156060 0.110123 0.011648 +v 0.150953 0.108490 -0.065565 +v 0.156094 0.108551 -0.025774 +v 0.152185 -0.018188 0.061504 +v 0.148186 -0.042497 0.053338 +v 0.151765 -0.041011 0.049562 +v 0.158813 0.031446 -0.062184 +v 0.157299 0.003819 -0.063097 +v 0.148794 -0.058897 0.029021 +v 0.151470 -0.054984 0.027916 +v 0.151937 -0.018707 -0.061535 +v 0.151844 -0.040215 -0.050068 +v 0.150581 -0.058401 -0.002651 +v 0.012130 -0.045413 -0.072465 +v 0.013350 -0.041960 -0.071540 +v 0.011038 -0.043547 -0.071965 +v 0.011705 -0.050467 -0.073819 +v 0.012390 -0.049537 -0.073570 +v 0.009842 -0.047300 -0.072970 +v 0.011331 -0.047807 -0.073106 +v 0.012968 -0.047780 -0.073099 +v 0.009529 -0.043315 -0.071903 +v 0.010105 -0.045174 -0.072401 +v 0.015293 -0.049611 -0.073590 +v 0.014273 -0.037921 -0.070458 +v 0.017664 -0.037805 -0.070426 +v 0.019621 -0.052776 -0.074438 +v 0.022053 -0.050943 -0.073947 +v 0.023712 -0.038497 -0.070612 +v 0.027854 -0.039108 -0.070775 +v 0.020520 -0.035585 -0.070220 +v 0.026223 -0.040851 -0.071777 +v 0.026543 -0.046965 -0.072881 +v 0.029035 -0.045542 -0.072499 +v 0.026462 -0.050647 -0.073867 +v 0.011162 -0.045417 -0.073501 +v 0.011997 -0.043967 -0.073113 +v 0.012865 -0.044559 -0.073271 +v 0.009614 -0.042970 -0.072846 +v 0.010181 -0.044207 -0.073177 +v 0.009718 -0.046612 -0.073821 +v 0.011297 -0.047572 -0.074079 +v 0.013302 -0.046039 -0.073668 +v 0.012790 -0.047507 -0.074061 +v 0.011944 -0.041364 -0.072415 +v 0.016948 -0.050385 -0.074833 +v 0.012989 -0.048557 -0.074343 +v 0.011476 -0.050136 -0.074766 +v 0.011572 -0.048902 -0.074435 +v 0.014499 -0.050345 -0.074822 +v 0.015969 -0.036624 -0.071145 +v 0.020367 -0.052501 -0.075399 +v 0.015339 -0.038978 -0.071776 +v 0.020719 -0.037202 -0.071300 +v 0.025122 -0.036643 -0.071150 +v 0.027161 -0.044915 -0.073367 +v 0.029433 -0.043248 -0.072920 +v 0.023435 -0.050061 -0.074746 +v 0.026296 -0.050448 -0.074849 +v 0.011690 -0.045568 0.072506 +v 0.011034 -0.043546 0.071964 +v 0.013876 -0.040371 0.071114 +v 0.013258 -0.045826 0.073278 +v 0.010147 -0.045264 0.072425 +v 0.014531 -0.050388 0.074300 +v 0.011723 -0.050346 0.074304 +v 0.012622 -0.049177 0.073474 +v 0.009842 -0.047300 0.072970 +v 0.011112 -0.048294 0.073237 +v 0.013219 -0.047655 0.073066 +v 0.009529 -0.043315 0.071903 +v 0.018685 -0.052770 0.074436 +v 0.014980 -0.037346 0.070303 +v 0.020563 -0.037505 0.070346 +v 0.022908 -0.035803 0.069890 +v 0.026699 -0.041365 0.071380 +v 0.019975 -0.051299 0.074042 +v 0.028756 -0.041193 0.071334 +v 0.027600 -0.049809 0.073643 +v 0.025725 -0.048368 0.073257 +v 0.009614 -0.042970 0.072846 +v 0.009718 -0.046612 0.073821 +v 0.010274 -0.043970 0.073113 +v 0.011944 -0.041364 0.072415 +v 0.012209 -0.044123 0.073154 +v 0.011344 -0.045472 0.073516 +v 0.013302 -0.046039 0.073668 +v 0.012322 -0.047128 0.073960 +v 0.017312 -0.050615 0.074894 +v 0.012818 -0.048825 0.074414 +v 0.011015 -0.048444 0.074312 +v 0.015969 -0.036624 0.071145 +v 0.018982 -0.052561 0.075416 +v 0.018175 -0.037256 0.071315 +v 0.024829 -0.039059 0.071798 +v 0.027386 -0.038831 0.071737 +v 0.022142 -0.035435 0.070827 +v 0.027170 -0.045333 0.073479 +v 0.029324 -0.044153 0.073162 +v 0.026296 -0.050448 0.074849 +v 0.023383 -0.049984 0.074725 +v 0.032661 0.116806 0.098255 +v 0.039433 0.115885 0.099577 +v 0.039413 0.117024 0.098489 +v 0.032687 0.115636 0.099310 +v 0.057197 0.110746 0.090255 +v 0.059070 0.112829 0.092559 +v 0.055685 0.111659 0.092015 +v 0.056429 0.113569 0.093289 +v 0.057057 0.127903 0.079291 +v 0.059222 0.126995 0.079121 +v 0.057847 0.125153 0.077183 +v 0.055142 0.126055 0.077905 +v 0.011084 0.115410 0.100953 +v 0.010454 0.113777 0.100274 +v 0.011647 0.114975 0.099202 +v -0.000172 0.136841 0.084256 +v 0.010040 0.134806 0.080801 +v -0.000192 0.117127 0.102662 +v 0.011627 0.133608 0.081828 +v 0.013313 0.133483 0.081831 +v 0.013381 0.114887 0.099179 +v 0.031924 0.125699 0.076897 +v 0.032661 0.133636 0.082561 +v 0.039841 0.127119 0.075572 +v 0.038936 0.129537 0.075633 +v 0.013697 0.135188 0.081691 +v 0.031694 0.134407 0.080855 +v 0.039841 0.114292 0.095559 +v 0.031777 0.114747 0.095134 +v 0.039413 0.133854 0.082795 +v 0.031109 0.117069 0.098533 +v 0.013558 0.114882 0.101029 +v 0.031665 0.113852 0.099929 +v 0.018022 0.116896 0.098347 +v 0.018022 0.132569 0.083731 +v 0.031109 0.132396 0.083545 +v 0.031664 0.114718 0.099014 +v 0.031355 0.129136 0.081716 +v 0.039841 0.129970 0.080939 +v 0.032687 0.132466 0.083615 +v 0.039384 0.134329 0.082615 +v 0.033281 0.134951 0.082360 +v 0.039068 0.128707 0.076587 +v 0.039433 0.132716 0.083883 +v 0.039463 0.135195 0.081700 +v 0.031612 0.133388 0.081606 +v 0.013984 0.129336 0.075419 +v 0.014015 0.128379 0.076236 +v 0.011559 0.134692 0.082917 +v 0.013223 0.134450 0.083020 +v 0.010485 0.135765 0.081899 +v 0.000693 0.137722 0.085144 +v 0.004088 0.116027 0.102788 +v 0.000436 0.118549 0.103290 +v 0.013256 0.116013 0.100208 +v 0.033281 0.115382 0.100608 +v 0.039463 0.115606 0.099967 +v 0.039384 0.114741 0.100882 +v 0.039068 0.109119 0.094853 +v 0.038936 0.109948 0.093900 +v 0.014011 0.108793 0.094504 +v 0.013984 0.109748 0.093685 +v 0.024002 0.133778 0.085469 +v 0.023167 0.128281 0.079575 +v 0.023167 0.113049 0.093779 +v 0.024002 0.118545 0.099674 +v 0.046762 0.126444 0.078204 +v 0.046774 0.111817 0.091872 +v 0.047532 0.116904 0.097168 +v 0.048320 0.129476 0.085697 +v 0.048319 0.118942 0.095257 +v 0.047902 0.131461 0.083543 +v 0.047875 0.129153 0.085351 +v 0.047520 0.113899 0.089849 +v 0.047520 0.124301 0.080148 +v 0.059406 0.115021 0.091906 +v 0.057959 0.111769 0.088419 +v 0.052316 0.114283 0.091115 +v 0.059769 0.112080 0.091061 +v 0.057622 0.114666 0.093834 +v 0.056794 0.110711 0.089593 +v 0.052316 0.113132 0.092189 +v 0.042751 0.118033 0.096126 +v 0.042600 0.113991 0.092728 +v 0.020207 0.134324 0.087333 +v 0.018763 0.134367 0.087461 +v 0.018766 0.120343 0.100571 +v 0.020196 0.120224 0.100361 +v 0.017926 0.128607 0.080439 +v 0.018784 0.113680 0.094163 +v 0.056910 0.124355 0.076970 +v 0.052316 0.125610 0.080552 +v 0.042181 0.126883 0.080803 +v 0.052841 0.129397 0.082377 +v 0.059500 0.126058 0.081033 +v 0.059989 0.126359 0.079119 +v 0.043391 0.130020 0.085281 +v 0.042749 0.130944 0.084037 +v 0.057984 0.123074 0.077832 +v 0.029470 0.129923 0.080983 +v 0.016822 0.129968 0.080941 +v 0.016822 0.114294 0.095557 +v 0.029810 0.114861 0.095028 +v 0.037195 0.110868 0.097214 +v 0.037316 0.113146 0.099771 +v 0.036202 0.111207 0.098757 +v 0.034150 0.111121 0.097625 +v 0.034354 0.112951 0.099561 +v 0.030062 0.111705 0.098479 +v 0.028692 0.109163 0.096068 +v 0.030927 0.110252 0.096616 +v 0.061471 -0.091325 0.007558 +v 0.063411 -0.091139 0.002826 +v 0.063370 -0.091143 0.005208 +v 0.055899 -0.092213 -0.006350 +v 0.066376 -0.090854 0.002336 +v 0.060423 -0.091426 -0.006383 +v 0.055785 -0.092352 0.006350 +v 0.062166 -0.091259 -0.007837 +v 0.068613 -0.090639 -0.007250 +v 0.064483 -0.091036 -0.005879 +v 0.062954 -0.091183 -0.003490 +v 0.068666 -0.090634 0.007217 +v 0.065390 -0.090949 -0.002046 +v 0.066919 -0.090802 -0.004436 +v 0.066015 -0.090889 0.005607 +v 0.068489 -0.089120 -0.007272 +v 0.061270 -0.089814 -0.007514 +v 0.063392 -0.089610 -0.002475 +v 0.063621 -0.089588 0.002381 +v 0.061119 -0.089828 0.007389 +v 0.056001 -0.090461 -0.006350 +v 0.056252 -0.090428 0.006350 +v 0.068436 -0.089125 0.007302 +v 0.063447 -0.089604 0.005669 +v 0.066621 -0.089300 -0.002971 +v 0.063365 -0.089612 -0.005316 +v 0.066686 -0.089293 0.004595 +v 0.065708 -0.089387 -0.005666 +v 0.065837 -0.089375 0.002370 +v 0.055677 -0.095881 -0.006350 +v 0.056354 -0.098473 -0.006350 +v 0.053652 -0.093739 -0.006350 +v 0.055704 -0.095883 0.006350 +v 0.054988 -0.097333 0.006350 +v 0.057859 -0.097682 0.006350 +v 0.053621 -0.093395 0.006350 +v 0.039384 -0.102069 -0.014036 +v 0.033281 -0.102306 -0.013380 +v 0.031665 -0.100766 -0.014036 +v 0.038936 -0.093694 -0.012778 +v 0.013984 -0.093400 -0.012778 +v 0.013597 -0.100919 -0.013099 +v 0.039463 -0.101990 -0.012778 +v 0.031664 -0.100687 -0.012778 +v 0.014015 -0.093345 0.012748 +v 0.031240 -0.101033 0.012749 +v 0.013669 -0.100922 0.013387 +v 0.039068 -0.093826 0.012749 +v 0.029792 -0.092001 -0.009989 +v 0.016822 -0.092001 -0.010730 +v 0.029810 -0.092001 0.009925 +v 0.029947 -0.097869 -0.009803 +v 0.016822 -0.097869 -0.010730 +v 0.031960 -0.092001 -0.010455 +v 0.031720 -0.098070 -0.010575 +v 0.032687 -0.101530 -0.012308 +v 0.039841 -0.092001 -0.012308 +v 0.039433 -0.101895 -0.012308 +v 0.039068 -0.093826 -0.014036 +v 0.014011 -0.093348 -0.014036 +v 0.013451 -0.102443 -0.012838 +v 0.039413 -0.101876 0.012279 +v 0.032661 -0.101556 0.012279 +v 0.039433 -0.101895 0.010704 +v 0.032687 -0.101530 0.010704 +v 0.039413 -0.101876 -0.010734 +v 0.039841 -0.097869 -0.010734 +v 0.039841 -0.097869 0.010704 +v 0.039841 -0.092001 0.012279 +v 0.031626 -0.097869 0.009825 +v 0.031924 -0.092001 0.010337 +v 0.029536 -0.097869 0.010343 +v 0.016822 -0.097869 0.010701 +v 0.016822 -0.092001 0.010701 +v 0.038075 -0.098406 0.014452 +v 0.035388 -0.098238 0.015111 +v 0.035565 -0.100531 0.014505 +v 0.035867 -0.096394 0.014371 +v 0.033732 -0.098109 0.014330 +v 0.028507 -0.096761 0.015124 +v 0.030855 -0.097722 0.014516 +v 0.028503 -0.094320 0.014461 +v 0.027174 -0.097798 0.014330 +v 0.015212 -0.095860 0.014808 +v 0.017978 -0.098307 0.014544 +v 0.017473 -0.095188 0.014531 +v 0.014817 -0.098095 0.014531 +v 0.033765 -0.098807 -0.014461 +v 0.035577 -0.099972 -0.014991 +v 0.036380 -0.096324 -0.014585 +v 0.037822 -0.099152 -0.014502 +v 0.027207 -0.096712 -0.014842 +v 0.029368 -0.098664 -0.014658 +v 0.028235 -0.094598 -0.014443 +v 0.030651 -0.095413 -0.014602 +v 0.014757 -0.097087 0.013023 +v 0.016398 -0.098548 0.013024 +v 0.016653 -0.095168 0.013023 +v 0.018053 -0.097380 0.013024 +v 0.015237 -0.098517 -0.014577 +v 0.015749 -0.098517 -0.013007 +v 0.014846 -0.096579 -0.013006 +v 0.015084 -0.095870 -0.014841 +v 0.016667 -0.095246 -0.013006 +v 0.017631 -0.095294 -0.014577 +v 0.018105 -0.097554 -0.013006 +v 0.018046 -0.098103 -0.014577 +v 0.056943 -0.092100 0.010219 +v 0.055051 -0.094192 0.009818 +v 0.056971 -0.095708 0.009949 +v 0.055837 -0.095331 0.008143 +v 0.055578 -0.092620 0.008143 +v 0.057679 -0.091846 0.008143 +v 0.059303 -0.093700 0.009797 +v 0.058706 -0.095071 0.008143 +v 0.055684 -0.095105 -0.007795 +v 0.055089 -0.092850 -0.009737 +v 0.057448 -0.095987 -0.009773 +v 0.055392 -0.092771 -0.007795 +v 0.057719 -0.091995 -0.007795 +v 0.058704 -0.092376 -0.009814 +v 0.058969 -0.093836 -0.007795 +v 0.058167 -0.095557 -0.007796 +v 0.047902 -0.100791 0.010018 +v 0.047875 -0.100539 0.007097 +v 0.046439 -0.100671 0.009637 +v 0.048319 -0.100820 -0.007127 +v 0.047532 -0.100828 -0.009921 +v 0.046774 -0.093485 -0.010029 +v 0.044623 -0.094245 -0.009667 +v 0.046762 -0.093465 0.009990 +v 0.044623 -0.094245 0.009637 +v 0.042181 -0.095665 0.008539 +v 0.042749 -0.100800 0.009304 +v 0.056910 -0.091138 0.009304 +v 0.043390 -0.101079 0.007779 +v 0.018784 -0.096432 -0.010229 +v 0.020196 -0.105427 -0.009670 +v 0.018766 -0.105662 -0.009726 +v 0.017926 -0.096574 0.010047 +v 0.018763 -0.105639 0.009472 +v 0.020207 -0.105516 0.009528 +v 0.052316 -0.094614 0.007779 +v 0.057014 -0.090997 0.007779 +v 0.059655 -0.092961 0.009304 +v 0.059998 -0.094607 0.007779 +v 0.058308 -0.096502 0.009304 +v 0.052316 -0.094614 -0.007709 +v 0.052316 -0.094614 -0.009283 +v 0.042600 -0.095594 -0.009022 +v 0.043073 -0.101154 -0.009283 +v 0.043984 -0.101141 -0.007697 +v 0.058658 -0.095902 -0.009283 +v 0.059581 -0.095039 -0.007709 +v 0.059769 -0.093072 -0.009283 +v 0.057959 -0.090927 -0.007709 +v 0.056794 -0.091064 -0.009283 +v 0.047520 -0.093426 0.007097 +v 0.048320 -0.101013 0.007097 +v 0.047520 -0.093426 -0.007127 +v 0.023167 -0.095720 -0.010429 +v 0.023167 -0.095720 0.010399 +v 0.024002 -0.103780 0.010399 +v 0.024002 -0.103780 -0.010429 +v 0.011695 -0.100996 -0.012662 +v 0.011084 -0.102577 -0.013594 +v 0.004088 -0.104340 -0.014394 +v -0.000192 -0.104998 -0.013504 +v 0.010454 -0.100967 -0.014326 +v 0.000436 -0.106428 -0.012893 +v 0.000171 -0.106620 0.012001 +v -0.000172 -0.104982 0.013466 +v 0.002194 -0.105357 0.014171 +v 0.013651 -0.102447 0.014006 +v 0.013223 -0.102447 0.012561 +v 0.010744 -0.102571 0.013951 +v 0.010735 -0.100983 0.014241 +v 0.012313 -0.100953 0.012382 +v 0.013984 -0.093400 0.014005 +v 0.038936 -0.093694 0.014006 +v 0.031200 -0.101206 0.014006 +v 0.031109 -0.101430 0.010701 +v 0.032981 -0.101836 0.012749 +v 0.033169 -0.102067 0.014006 +v 0.039384 -0.102069 0.012749 +v 0.039463 -0.101990 0.014006 +v 0.031109 -0.101938 -0.010730 +v 0.018022 -0.101684 -0.010730 +v 0.018022 -0.101684 0.010701 +v 0.033957 -0.102107 -0.010734 +v 0.026942 0.111097 0.097764 +v 0.018317 0.111426 0.098141 +v 0.015237 0.111922 0.098654 +v 0.014996 0.110131 0.097139 +v 0.016923 0.109495 0.096051 +v 0.056531 -0.093810 -0.010331 +v 0.046439 0.131100 0.083715 +v 0.044623 0.112600 0.092181 +v 0.044623 0.126718 0.079015 +v 0.030121 0.111045 0.090561 +v 0.032140 0.109975 0.091559 +v 0.039841 0.109137 0.092341 +v 0.016822 0.110291 0.091265 +v 0.016822 0.125965 0.076648 +v 0.029810 0.125398 0.077178 +v 0.055676 0.114500 0.091474 +v 0.058246 0.126427 0.080893 +v 0.054987 0.125469 0.079867 +v 0.056331 0.124145 0.078447 +v 0.055570 0.112746 0.089593 +v 0.058630 0.112797 0.089648 +v 0.058817 0.124620 0.078956 +v 0.058244 0.114724 0.091714 +v 0.017079 0.132085 0.079806 +v 0.014846 0.111749 0.096165 +v 0.015749 0.113071 0.097583 +v 0.014721 0.131368 0.079036 +v 0.017635 0.130175 0.077758 +v 0.016667 0.110840 0.095190 +v 0.018105 0.112414 0.096878 +v 0.015781 0.129754 0.077306 +v 0.017978 0.133077 0.078640 +v 0.015389 0.133147 0.078328 +v 0.017473 0.130940 0.076367 +v 0.014716 0.131403 0.076864 +v 0.027131 0.132789 0.078320 +v 0.031059 0.132266 0.077982 +v 0.028879 0.130306 0.075804 +v 0.037118 0.134299 0.080030 +v 0.034450 0.134110 0.079963 +v 0.037380 0.132031 0.077653 +v 0.034095 0.132510 0.078024 +v 0.028983 0.132633 0.077314 +v 0.035983 0.133589 0.078394 +v 0.065162 0.118642 0.081414 +v 0.057277 0.112897 0.087644 +v 0.061824 0.111827 0.088098 +v 0.061967 0.122791 0.077860 +v 0.056799 0.122316 0.079122 +v 0.063356 0.120049 0.080281 +v 0.069123 0.111609 0.087582 +v 0.066611 0.112981 0.086551 +v 0.064427 0.115451 0.084463 +v 0.067587 0.119654 0.080232 +v 0.063665 0.113480 0.086376 +v 0.065385 0.121409 0.078812 +v 0.069176 0.122188 0.077713 +v 0.067077 0.115007 0.084615 +v 0.069035 0.110556 0.086484 +v 0.061802 0.110734 0.087031 +v 0.064236 0.117707 0.080288 +v 0.066772 0.114276 0.083238 +v 0.063121 0.113172 0.084627 +v 0.061650 0.121641 0.076875 +v 0.057172 0.111841 0.086511 +v 0.055639 0.121513 0.078262 +v 0.068982 0.121217 0.076548 +v 0.064453 0.120486 0.077675 +v 0.067370 0.118545 0.079198 +v 0.066280 0.111820 0.085577 +v 0.058087 0.116851 0.091884 +v 0.055071 0.116442 0.091446 +v 0.055570 0.114451 0.089311 +v 0.054268 0.113471 0.088259 +v 0.055703 0.124599 0.081571 +v 0.054299 0.125190 0.082204 +v 0.058204 0.126183 0.083269 +v 0.017465 0.133118 -0.079088 +v 0.014468 0.132427 -0.078329 +v 0.015925 0.131106 -0.076524 +v 0.018157 0.131240 -0.077074 +v 0.028081 0.132880 -0.079029 +v 0.026954 0.131005 -0.076939 +v 0.028950 0.132110 -0.077175 +v 0.029819 0.130314 -0.076279 +v 0.030946 0.132269 -0.078295 +v 0.036932 0.134179 -0.080465 +v 0.034354 0.133875 -0.080097 +v 0.036168 0.133622 -0.078782 +v 0.034150 0.132071 -0.078136 +v 0.037435 0.132019 -0.077903 +v 0.064498 0.115427 -0.084470 +v 0.055394 0.122555 -0.079803 +v 0.061174 0.122589 -0.078238 +v 0.061316 0.111609 -0.088458 +v 0.056166 0.112993 -0.088171 +v 0.062747 0.114055 -0.085985 +v 0.068456 0.121960 -0.077845 +v 0.065771 0.121186 -0.078929 +v 0.062724 0.119439 -0.080967 +v 0.066837 0.114090 -0.085401 +v 0.064896 0.112560 -0.087089 +v 0.068508 0.111375 -0.087708 +v 0.066020 0.118568 -0.081336 +v 0.068329 0.120940 -0.076720 +v 0.061962 0.121788 -0.076786 +v 0.063644 0.117490 -0.080567 +v 0.060174 0.120916 -0.077839 +v 0.065751 0.114147 -0.083401 +v 0.060960 0.110712 -0.087249 +v 0.062658 0.113586 -0.084341 +v 0.055174 0.121371 -0.078533 +v 0.054975 0.112212 -0.087333 +v 0.068275 0.110285 -0.086663 +v 0.064340 0.111540 -0.086022 +v 0.066823 0.118809 -0.078909 +v 0.063249 0.120002 -0.078277 +v 0.066373 0.112300 -0.085039 +v 0.053708 0.125108 -0.082540 +v 0.057102 0.125986 -0.083482 +v 0.055158 0.115295 -0.090640 +v 0.053776 0.115911 -0.091299 +v 0.057718 0.116834 -0.092289 +v 0.031411 0.129006 -0.081885 +v 0.031355 0.114945 -0.094998 +v 0.029512 0.129630 -0.081303 +v 0.016822 0.114113 -0.095773 +v 0.016822 0.129787 -0.081157 +v 0.039841 0.129789 -0.081155 +v 0.039841 0.114111 -0.095775 +v 0.029470 0.114158 -0.095731 +v 0.052316 0.114030 -0.091399 +v 0.056910 0.110544 -0.089897 +v 0.057984 0.111493 -0.088679 +v 0.059745 0.111925 -0.091378 +v 0.059331 0.114839 -0.092268 +v 0.057546 0.114545 -0.094187 +v 0.042798 0.117882 -0.096276 +v 0.042181 0.114191 -0.092686 +v 0.052316 0.125357 -0.080837 +v 0.052316 0.126508 -0.079763 +v 0.042600 0.126986 -0.080658 +v 0.017926 0.113708 -0.094380 +v 0.018784 0.128440 -0.080448 +v 0.018766 0.134367 -0.087541 +v 0.018763 0.120311 -0.100617 +v 0.020207 0.120186 -0.100565 +v 0.020196 0.134166 -0.087407 +v 0.051993 0.128259 -0.083949 +v 0.042713 0.130239 -0.084684 +v 0.052305 0.129308 -0.082765 +v 0.059775 0.126538 -0.079795 +v 0.059617 0.125524 -0.081016 +v 0.057959 0.122842 -0.078140 +v 0.057484 0.123982 -0.077053 +v 0.047520 0.113718 -0.090065 +v 0.048320 0.118892 -0.095614 +v 0.047520 0.124121 -0.080364 +v 0.048319 0.129164 -0.085772 +v 0.047875 0.118569 -0.095268 +v 0.046774 0.126284 -0.078429 +v 0.023167 0.128101 -0.079791 +v 0.023167 0.112868 -0.093995 +v 0.046762 0.111629 -0.092067 +v 0.024002 0.118365 -0.099890 +v 0.047902 0.116605 -0.097444 +v 0.047532 0.131212 -0.083873 +v 0.024002 0.133597 -0.085685 +v 0.013597 0.133599 -0.081772 +v 0.013984 0.128237 -0.076492 +v 0.014011 0.129120 -0.075596 +v 0.038936 0.128437 -0.076706 +v 0.039068 0.129446 -0.075945 +v 0.039463 0.134095 -0.082774 +v 0.039384 0.135068 -0.081974 +v 0.033281 0.134750 -0.082595 +v 0.031664 0.133206 -0.081821 +v 0.031665 0.134180 -0.081021 +v 0.013675 0.134809 -0.082730 +v 0.011858 0.134257 -0.083331 +v 0.011695 0.133332 -0.082125 +v 0.004088 0.136880 -0.083391 +v -0.000192 0.136677 -0.084479 +v 0.010454 0.134529 -0.080970 +v 0.010846 0.135537 -0.082273 +v 0.000436 0.137205 -0.085941 +v 0.000693 0.117766 -0.103801 +v -0.000172 0.116941 -0.102860 +v 0.013651 0.114817 -0.101374 +v 0.013223 0.115875 -0.100389 +v 0.011559 0.115755 -0.100624 +v 0.010485 0.114665 -0.101622 +v 0.010735 0.113648 -0.100464 +v 0.013669 0.114230 -0.099837 +v 0.012312 0.114986 -0.099175 +v 0.014015 0.109530 -0.093860 +v 0.013984 0.108649 -0.094758 +v 0.039068 0.109858 -0.094212 +v 0.038936 0.108848 -0.094973 +v 0.031612 0.114538 -0.099231 +v 0.031098 0.114083 -0.100587 +v 0.031109 0.116542 -0.098377 +v 0.032972 0.114390 -0.100916 +v 0.033240 0.115625 -0.100397 +v 0.039384 0.115480 -0.100241 +v 0.039463 0.114506 -0.101040 +v 0.031109 0.132562 -0.084133 +v 0.018022 0.132389 -0.083947 +v 0.018022 0.116715 -0.098563 +v 0.039433 0.116857 -0.098720 +v 0.032687 0.116607 -0.098452 +v 0.039413 0.115691 -0.099779 +v 0.039841 0.108957 -0.092557 +v 0.032661 0.115474 -0.099546 +v 0.032661 0.132304 -0.083851 +v 0.039413 0.132522 -0.084085 +v 0.032153 0.109871 -0.091704 +v 0.057140 0.111539 -0.092630 +v 0.059211 0.112247 -0.092393 +v 0.057004 0.110463 -0.090626 +v 0.056751 0.113442 -0.093675 +v 0.059181 0.126562 -0.079248 +v 0.056178 0.127607 -0.080316 +v 0.057199 0.126734 -0.078442 +v 0.057973 0.124923 -0.077518 +v 0.055414 0.125465 -0.077936 +v 0.032687 0.133437 -0.082758 +v 0.039433 0.133687 -0.083025 +v 0.029792 0.125243 -0.077370 +v 0.016822 0.125784 -0.076865 +v 0.030096 0.110884 -0.090760 +v 0.031960 0.125583 -0.077052 +v 0.039841 0.126938 -0.075788 +v 0.016822 0.110111 -0.091481 +v 0.036404 0.152743 0.004780 +v 0.039082 0.152509 0.006041 +v 0.037937 0.153072 0.003307 +v 0.035596 0.152293 0.006896 +v 0.037891 0.152001 0.008317 +v 0.034453 0.151958 0.008602 +v 0.032893 0.152495 0.005986 +v 0.034181 0.153086 0.003264 +v 0.035571 0.147530 0.006187 +v 0.036740 0.148071 0.003665 +v 0.037311 0.147807 0.005438 +v 0.034619 0.147921 0.004753 +v 0.036312 0.150622 0.007028 +v 0.037685 0.150983 0.005369 +v 0.035831 0.151283 0.003918 +v 0.035501 0.148519 0.003399 +v 0.034317 0.150871 0.005872 +v 0.039126 0.141383 0.058325 +v 0.037639 0.141852 0.056073 +v 0.036735 0.141476 0.057787 +v 0.035265 0.141106 0.059529 +v 0.037704 0.140729 0.061334 +v 0.034142 0.140782 0.061197 +v 0.034612 0.141908 0.055837 +v 0.032877 0.141370 0.058436 +v 0.036312 0.136297 0.059072 +v 0.035434 0.136978 0.056334 +v 0.037404 0.136858 0.057121 +v 0.034627 0.136549 0.057977 +v 0.035886 0.139385 0.059893 +v 0.037480 0.139600 0.058910 +v 0.036828 0.140024 0.056905 +v 0.034277 0.139789 0.057978 +v 0.006735 0.141106 0.059529 +v 0.003252 0.140962 0.060243 +v 0.006561 0.140665 0.061780 +v 0.006151 0.141983 0.055466 +v 0.003230 0.141611 0.057257 +v 0.005265 0.141476 0.057787 +v 0.009329 0.141306 0.058578 +v 0.006742 0.136325 0.058735 +v 0.004620 0.136513 0.058403 +v 0.005473 0.137000 0.056370 +v 0.007470 0.136823 0.057135 +v 0.005673 0.140061 0.056714 +v 0.004400 0.139651 0.058675 +v 0.006516 0.139380 0.059912 +v 0.007539 0.139815 0.057888 +v 0.024915 0.153649 0.007165 +v 0.025836 0.152613 0.004826 +v 0.025384 0.151555 0.009804 +v 0.025962 0.152869 0.010838 +v 0.029174 0.151212 0.011420 +v 0.031053 0.152826 0.011039 +v 0.032041 0.151760 0.008838 +v 0.031795 0.153825 0.006338 +v 0.031160 0.152549 0.005126 +v 0.027908 0.154244 0.004368 +v 0.027025 0.153967 0.005670 +v 0.026243 0.153172 0.009411 +v 0.030757 0.153737 0.006753 +v 0.029975 0.152942 0.010493 +v 0.026354 0.156453 0.007891 +v 0.027840 0.156429 0.006231 +v 0.029838 0.156507 0.006714 +v 0.030745 0.156137 0.007735 +v 0.030858 0.155272 0.009594 +v 0.029061 0.155694 0.010955 +v 0.027412 0.155721 0.010755 +v 0.026251 0.155914 0.009597 +v 0.030025 0.156898 0.009114 +v 0.028226 0.157400 0.007907 +v 0.028186 0.157063 0.009610 +v 0.010339 0.152981 0.010312 +v 0.009655 0.151793 0.008684 +v 0.013887 0.151203 0.011460 +v 0.015302 0.152749 0.011401 +v 0.016948 0.151705 0.009099 +v 0.017134 0.153409 0.008295 +v 0.016219 0.152552 0.005113 +v 0.015284 0.154189 0.004627 +v 0.011891 0.152691 0.004460 +v 0.010571 0.153940 0.005797 +v 0.010893 0.153535 0.007703 +v 0.012103 0.152990 0.010266 +v 0.015931 0.153136 0.009578 +v 0.013909 0.154048 0.005291 +v 0.011095 0.155890 0.009032 +v 0.011574 0.156296 0.007124 +v 0.013459 0.156423 0.006181 +v 0.015309 0.155823 0.006760 +v 0.015962 0.155975 0.008766 +v 0.014697 0.155362 0.010744 +v 0.012299 0.155335 0.010755 +v 0.014491 0.156927 0.009734 +v 0.012825 0.156668 0.010198 +v 0.014816 0.157087 0.007860 +v 0.012830 0.157385 0.007909 +v 0.021785 0.157113 0.009247 +v 0.020447 0.157311 0.007492 +v 0.019885 0.157110 0.009010 +v 0.007932 0.153226 0.001987 +v 0.034530 0.152993 0.002905 +v 0.037713 0.153142 0.002568 +v 0.033004 0.152214 0.006684 +v 0.008341 0.151933 0.007975 +v 0.002748 0.152854 0.004134 +v 0.002162 0.141565 0.056886 +v 0.003718 0.151872 0.008172 +v 0.036093 0.151704 0.009007 +v 0.040000 0.148389 0.024698 +v 0.039705 0.152567 0.005300 +v 0.034308 0.141738 0.055909 +v 0.038579 0.141560 0.056775 +v 0.008433 0.141608 0.056523 +v 0.033595 0.140373 0.062446 +v 0.007970 0.140598 0.061213 +v 0.039626 0.141046 0.059595 +v 0.017210 0.152011 0.007657 +v 0.020849 0.152823 0.003841 +v 0.024771 0.152071 0.007377 +v 0.023046 0.151345 0.010792 +v 0.004308 0.140550 0.061831 +v 0.019404 0.151283 0.011085 +v 0.037010 0.150895 0.012911 +v 0.036528 0.145435 0.038596 +v 0.005056 0.150908 0.012846 +v 0.005459 0.145435 0.038596 +v 0.036544 0.142629 0.051796 +v 0.005390 0.142643 0.051731 +v 0.017343 0.153286 0.008877 +v 0.019663 0.152809 0.011120 +v 0.023293 0.152799 0.011165 +v 0.024513 0.153726 0.006807 +v 0.022144 0.154112 0.004988 +v 0.018596 0.154052 0.005271 +v 0.018522 0.153642 0.007202 +v 0.019185 0.153058 0.009950 +v 0.022815 0.153852 0.006213 +v 0.023478 0.153268 0.008961 +v 0.018788 0.155982 0.007349 +v 0.020790 0.156468 0.006204 +v 0.022545 0.155984 0.006608 +v 0.023524 0.155730 0.008250 +v 0.023006 0.155875 0.009938 +v 0.020912 0.154962 0.011056 +v 0.018769 0.155250 0.009746 +v 0.021099 0.156281 0.010639 +v 0.019109 0.156353 0.009660 +v 0.022373 0.157031 0.007697 +v 0.036541 0.147391 0.039012 +v 0.036610 0.144599 0.052147 +v 0.005472 0.147391 0.039012 +v 0.005456 0.144586 0.052212 +v 0.033088 0.145094 0.049856 +v 0.033057 0.146838 0.041639 +v 0.009043 0.145087 0.049855 +v 0.009043 0.146833 0.041638 +v 0.009692 0.147214 0.050307 +v 0.009723 0.148989 0.042096 +v 0.030885 0.151638 0.042660 +v 0.030844 0.149903 0.050878 +v 0.020095 0.148734 0.042042 +v 0.022047 0.147477 0.050363 +v 0.036944 0.152865 0.013262 +v 0.004990 0.152851 0.013327 +v 0.033188 0.148189 0.035332 +v 0.033133 0.152198 0.016453 +v 0.009043 0.148174 0.035329 +v 0.009043 0.152187 0.016451 +v 0.009692 0.150301 0.035781 +v 0.009724 0.154338 0.016908 +v 0.030795 0.157003 0.017475 +v 0.030787 0.152982 0.036351 +v 0.021348 0.154468 0.016936 +v 0.023307 0.150736 0.035874 +v 0.005265 0.152333 0.006709 +v 0.002705 0.152634 0.005399 +v 0.005179 0.151867 0.008920 +v 0.005824 0.153201 0.002714 +v 0.006735 0.152703 0.004967 +v 0.008876 0.152815 0.004487 +v 0.008568 0.152166 0.007645 +v 0.005497 0.147536 0.006250 +v 0.004690 0.148025 0.004351 +v 0.006271 0.148270 0.003404 +v 0.007414 0.147792 0.005056 +v 0.006742 0.151250 0.004092 +v 0.004712 0.151155 0.004539 +v 0.004825 0.150711 0.006609 +v 0.007414 0.150734 0.006516 +v 0.038939 0.139019 0.061144 +v 0.036294 0.140465 0.062289 +v 0.021000 0.138792 0.062216 +v 0.004844 0.138842 0.061977 +v 0.039859 0.150988 0.004837 +v 0.040000 0.145841 0.029051 +v 0.015006 0.151682 0.001571 +v 0.036849 0.151645 0.001747 +v 0.003796 0.151532 0.002279 +v 0.006068 0.153248 0.002259 +v 0.002141 0.139532 0.058731 +v 0.002291 0.141106 0.059212 +v 0.002000 0.145841 0.029051 +v 0.002014 0.150761 0.005906 +v 0.007196 0.151210 0.004303 +v 0.005258 0.151269 0.003881 +v 0.004311 0.150811 0.006083 +v 0.005996 0.150584 0.007203 +v 0.007676 0.150804 0.006118 +v 0.036808 0.151255 0.003938 +v 0.034272 0.151093 0.004783 +v 0.035730 0.150540 0.007317 +v 0.037746 0.150875 0.005754 +v 0.035506 0.139352 0.060041 +v 0.037414 0.139509 0.059267 +v 0.034344 0.139906 0.057348 +v 0.037441 0.139953 0.057177 +v 0.005120 0.139401 0.059841 +v 0.007040 0.139445 0.059671 +v 0.004269 0.139809 0.057848 +v 0.006064 0.140080 0.056534 +v 0.007731 0.139784 0.057977 +v 0.034289 0.141894 -0.038076 +v 0.034377 0.147275 -0.039484 +v 0.032342 0.141427 -0.040273 +v 0.031940 0.146879 -0.041346 +v 0.030924 0.142025 -0.037460 +v 0.031127 0.147500 -0.038427 +v 0.032089 0.147907 -0.036095 +v 0.035687 0.147568 -0.037845 +v 0.035229 0.146701 -0.042042 +v 0.029109 0.147368 -0.038878 +v 0.031043 0.146447 -0.043005 +v 0.029987 0.147457 -0.036483 +v 0.028212 0.146485 -0.038361 +v 0.029892 0.146240 -0.035711 +v 0.028469 0.146261 -0.040977 +v 0.029511 0.145787 -0.042553 +v 0.034293 0.147180 -0.035619 +v 0.031957 0.146374 -0.034934 +v 0.031468 0.144615 -0.043672 +v 0.033545 0.145534 -0.043604 +v 0.035782 0.145599 -0.042420 +v 0.036892 0.146270 -0.039538 +v 0.036501 0.145997 -0.037224 +v 0.034679 0.146099 -0.035472 +v 0.027973 0.144983 -0.040721 +v 0.036063 0.144665 -0.042216 +v 0.030217 0.145572 -0.037953 +v 0.030810 0.144912 -0.041055 +v 0.034541 0.144892 -0.041153 +v 0.033819 0.145749 -0.037120 +v 0.034685 0.144083 -0.037323 +v 0.033451 0.143220 -0.041382 +v 0.030095 0.143544 -0.039856 +v 0.030981 0.144150 -0.037005 +v 0.031269 0.142484 -0.035432 +v 0.028964 0.142057 -0.037614 +v 0.035484 0.142390 -0.036256 +v 0.036181 0.141798 -0.038821 +v 0.031533 0.141109 -0.041821 +v 0.036165 0.144163 -0.036387 +v 0.034683 0.143569 -0.035028 +v 0.036918 0.142898 -0.038730 +v 0.036842 0.143282 -0.040310 +v 0.035014 0.141447 -0.041544 +v 0.035110 0.142841 -0.042513 +v 0.033189 0.141725 -0.042868 +v 0.030351 0.141797 -0.042434 +v 0.033004 0.142803 -0.043315 +v 0.028435 0.142130 -0.040052 +v 0.028110 0.143752 -0.037745 +v 0.029698 0.144475 -0.035468 +v 0.030329 0.143343 -0.035003 +v 0.032694 0.143389 -0.034516 +v 0.029462 0.143028 -0.042285 +v 0.033393 0.144645 -0.034676 +v 0.019654 0.143594 -0.055141 +v 0.021656 0.143203 -0.056346 +v 0.021317 0.143021 -0.057616 +v 0.019771 0.136151 -0.053684 +v 0.018262 0.135848 -0.055235 +v 0.019525 0.135462 -0.056814 +v 0.021323 0.135793 -0.055465 +v 0.018452 0.141832 -0.055548 +v 0.021382 0.141801 -0.055692 +v 0.019280 0.141269 -0.058194 +v 0.016840 0.141955 -0.056068 +v 0.017943 0.142219 -0.054223 +v 0.017012 0.141919 -0.057576 +v 0.019289 0.141151 -0.059553 +v 0.020336 0.142412 -0.053639 +v 0.022264 0.141470 -0.058223 +v 0.022494 0.142229 -0.055235 +v 0.018008 0.143057 -0.055312 +v 0.018243 0.143283 -0.056693 +v 0.019004 0.142882 -0.058365 +v 0.020379 0.142749 -0.058592 +v 0.010924 0.141089 -0.030328 +v 0.011128 0.140515 -0.033299 +v 0.012328 0.140847 -0.031677 +v 0.009117 0.140777 -0.031865 +v 0.009485 0.146380 -0.034151 +v 0.009768 0.146874 -0.031827 +v 0.012041 0.146847 -0.031955 +v 0.011879 0.146375 -0.034175 +v 0.013630 0.146580 -0.033903 +v 0.008164 0.147170 -0.031582 +v 0.007945 0.146491 -0.034078 +v 0.010576 0.146429 -0.036017 +v 0.010088 0.147394 -0.030267 +v 0.012421 0.146366 -0.035541 +v 0.013631 0.147090 -0.032283 +v 0.012132 0.147313 -0.030477 +v 0.008834 0.146914 -0.035079 +v 0.011589 0.148223 -0.031156 +v 0.012233 0.148365 -0.032661 +v 0.012133 0.148072 -0.034351 +v 0.009889 0.148587 -0.031984 +v 0.009073 0.148189 -0.033469 +v 0.010039 0.147937 -0.034686 +v 0.023039 0.141263 -0.029435 +v 0.020616 0.141414 -0.028965 +v 0.020383 0.141002 -0.030985 +v 0.022333 0.140877 -0.031605 +v 0.020097 0.147082 -0.030849 +v 0.022014 0.147288 -0.029881 +v 0.023304 0.146898 -0.031715 +v 0.021145 0.146636 -0.032945 +v 0.019122 0.146761 -0.033082 +v 0.018889 0.147543 -0.030248 +v 0.021970 0.146638 -0.034361 +v 0.021366 0.147844 -0.028491 +v 0.023767 0.147028 -0.033466 +v 0.024614 0.147096 -0.031774 +v 0.024058 0.147517 -0.029647 +v 0.020175 0.147180 -0.033802 +v 0.022563 0.148821 -0.030189 +v 0.023306 0.148612 -0.031681 +v 0.020399 0.148835 -0.030674 +v 0.019989 0.148448 -0.032203 +v 0.021550 0.148256 -0.033305 +v 0.012514 0.146471 -0.005073 +v 0.011154 0.146068 -0.007125 +v 0.012778 0.145804 -0.008160 +v 0.014197 0.146121 -0.006877 +v 0.011154 0.152086 -0.007306 +v 0.013372 0.152270 -0.006440 +v 0.014048 0.151770 -0.008793 +v 0.011838 0.151661 -0.009306 +v 0.015535 0.152455 -0.007125 +v 0.009642 0.152084 -0.008148 +v 0.010736 0.151628 -0.010305 +v 0.013750 0.151525 -0.010701 +v 0.011194 0.152743 -0.005440 +v 0.015239 0.151788 -0.009349 +v 0.013527 0.152780 -0.005088 +v 0.010233 0.152836 -0.006713 +v 0.014136 0.153687 -0.007780 +v 0.013232 0.153826 -0.006491 +v 0.011118 0.153781 -0.007513 +v 0.011474 0.153292 -0.009437 +v 0.012565 0.153077 -0.010070 +v 0.014226 0.153302 -0.009237 +v 0.036200 0.141973 -0.055536 +v 0.039170 0.141446 -0.057941 +v 0.036735 0.141476 -0.057787 +v 0.033320 0.141653 -0.057053 +v 0.037161 0.140658 -0.061690 +v 0.035265 0.141106 -0.059529 +v 0.033268 0.140964 -0.060324 +v 0.035887 0.136817 -0.056262 +v 0.034769 0.136465 -0.058686 +v 0.036898 0.136393 -0.058708 +v 0.037571 0.139868 -0.057613 +v 0.037374 0.137152 -0.056876 +v 0.036309 0.139381 -0.059931 +v 0.034468 0.139625 -0.058782 +v 0.035162 0.140011 -0.056964 +v 0.036404 0.152743 -0.004780 +v 0.038901 0.152779 -0.004718 +v 0.038402 0.152067 -0.007986 +v 0.035596 0.152293 -0.006896 +v 0.036352 0.153202 -0.002696 +v 0.033308 0.152877 -0.004253 +v 0.033062 0.152333 -0.006803 +v 0.034893 0.151932 -0.008736 +v 0.034622 0.147854 -0.004639 +v 0.036723 0.147536 -0.006018 +v 0.036241 0.148106 -0.003467 +v 0.036338 0.151292 -0.003869 +v 0.037434 0.148349 -0.004256 +v 0.037576 0.150868 -0.005885 +v 0.035513 0.150606 -0.007101 +v 0.035542 0.147870 -0.006452 +v 0.034451 0.151032 -0.005126 +v 0.005596 0.152743 -0.004780 +v 0.003426 0.152938 -0.004005 +v 0.005846 0.153161 -0.002824 +v 0.006404 0.152293 -0.006896 +v 0.003308 0.152161 -0.007595 +v 0.008541 0.152142 -0.007709 +v 0.006112 0.151889 -0.008865 +v 0.008725 0.152928 -0.004081 +v 0.007498 0.147807 -0.004921 +v 0.005424 0.148157 -0.003438 +v 0.005142 0.147601 -0.006124 +v 0.005905 0.150608 -0.007131 +v 0.004341 0.150998 -0.005257 +v 0.006589 0.151278 -0.003940 +v 0.007525 0.150860 -0.005921 +v 0.006735 0.141106 -0.059529 +v 0.006492 0.140620 -0.061859 +v 0.002975 0.141090 -0.059732 +v 0.009071 0.141171 -0.059275 +v 0.005265 0.141476 -0.057787 +v 0.004297 0.141892 -0.055888 +v 0.008184 0.141788 -0.056412 +v 0.006462 0.136863 -0.056359 +v 0.004572 0.136606 -0.057495 +v 0.006760 0.136334 -0.058714 +v 0.007692 0.139586 -0.058898 +v 0.005103 0.136698 -0.059047 +v 0.005184 0.139436 -0.059673 +v 0.004439 0.139797 -0.057974 +v 0.006032 0.140067 -0.056722 +v 0.007588 0.137057 -0.057273 +v 0.037289 0.144646 -0.000446 +v 0.036159 0.153230 -0.002020 +v 0.006142 0.144720 -0.000101 +v 0.005039 0.153208 -0.002251 +v 0.039658 0.132398 -0.058068 +v 0.039605 0.141080 -0.059445 +v 0.039979 0.143931 -0.003811 +v 0.039911 0.141548 -0.056965 +v 0.039563 0.152690 -0.004705 +v 0.037396 0.140522 -0.061968 +v 0.036224 0.131838 -0.060704 +v 0.005731 0.140450 -0.062395 +v 0.004535 0.131880 -0.060507 +v 0.002224 0.144167 -0.002701 +v 0.002438 0.152684 -0.004866 +v 0.002163 0.141078 -0.059324 +v 0.002011 0.132686 -0.056716 +v 0.005288 0.139341 -0.060041 +v 0.004688 0.139974 -0.056954 +v 0.006998 0.141812 -0.055417 +v 0.007277 0.139934 -0.057162 +v 0.007633 0.139545 -0.059081 +v 0.008996 0.140987 -0.059504 +v 0.037892 0.139693 -0.058310 +v 0.036020 0.139332 -0.060042 +v 0.033392 0.140814 -0.060317 +v 0.034297 0.139603 -0.058819 +v 0.033553 0.141613 -0.056502 +v 0.035450 0.140071 -0.056556 +v 0.037816 0.150915 -0.005501 +v 0.036547 0.151709 -0.008985 +v 0.036498 0.150583 -0.007110 +v 0.034707 0.150678 -0.006684 +v 0.032863 0.152227 -0.006598 +v 0.034534 0.151131 -0.004501 +v 0.036447 0.151280 -0.003865 +v 0.004652 0.150683 -0.006676 +v 0.004140 0.151847 -0.008381 +v 0.004439 0.151051 -0.004807 +v 0.006462 0.151305 -0.003704 +v 0.007567 0.150679 -0.006593 +v 0.009231 0.152073 -0.007038 +v 0.008276 0.145819 -0.036788 +v 0.008205 0.137805 -0.035176 +v 0.008204 0.142432 -0.052726 +v 0.008204 0.134437 -0.051023 +v 0.022354 0.134436 -0.051029 +v 0.022314 0.142427 -0.052747 +v 0.022306 0.137813 -0.035138 +v 0.022280 0.145821 -0.036781 +v 0.024775 0.149652 -0.011120 +v 0.026049 0.151182 -0.011557 +v 0.025370 0.149652 -0.011120 +v 0.019113 0.149652 -0.011120 +v 0.008255 0.151183 -0.011555 +v 0.016213 0.149652 -0.011120 +v 0.010113 0.149652 -0.011120 +v 0.008257 0.149602 -0.011360 +v 0.008202 0.147740 -0.027753 +v 0.008279 0.146203 -0.027346 +v 0.025994 0.146195 -0.027386 +v 0.026095 0.147738 -0.027763 +v 0.026072 0.149591 -0.011408 +v 0.011605 0.138820 -0.042289 +v 0.012231 0.139621 -0.042520 +v 0.013094 0.140051 -0.042560 +v 0.012752 0.139265 -0.044437 +v 0.013132 0.140022 -0.044665 +v 0.013247 0.140192 -0.044266 +v 0.013199 0.139121 -0.047543 +v 0.013117 0.139205 -0.047143 +v 0.011620 0.137822 -0.047002 +v 0.014103 0.143331 -0.050305 +v 0.016038 0.143751 -0.050169 +v 0.014020 0.145835 -0.050772 +v 0.014020 0.145507 -0.050889 +v 0.012990 0.145201 -0.041564 +v 0.011666 0.146803 -0.041909 +v 0.012755 0.145664 -0.041273 +v 0.012900 0.140364 -0.040134 +v 0.012928 0.140315 -0.040554 +v 0.013617 0.142909 -0.040701 +v 0.013554 0.142597 -0.041029 +v 0.011688 0.146671 -0.042485 +v 0.011541 0.139206 -0.040333 +v 0.011605 0.139243 -0.040299 +v 0.013110 0.140447 -0.041177 +v 0.012934 0.140099 -0.041536 +v 0.013495 0.141815 -0.041886 +v 0.013401 0.144053 -0.041951 +v 0.013460 0.143176 -0.042198 +v 0.013007 0.144920 -0.042554 +v 0.011593 0.146724 -0.042900 +v 0.011649 0.146485 -0.043469 +v 0.012026 0.139670 -0.041470 +v 0.011566 0.138985 -0.041279 +v 0.011645 0.146468 -0.043881 +v 0.013068 0.144603 -0.043533 +v 0.012903 0.139946 -0.042117 +v 0.013527 0.141965 -0.042552 +v 0.013542 0.142519 -0.043073 +v 0.013150 0.144421 -0.043075 +v 0.011745 0.146260 -0.044487 +v 0.013105 0.140027 -0.043161 +v 0.012913 0.139655 -0.043521 +v 0.013625 0.142603 -0.044129 +v 0.013425 0.143450 -0.043901 +v 0.011766 0.146135 -0.044902 +v 0.012599 0.139517 -0.043537 +v 0.013626 0.142377 -0.045121 +v 0.013490 0.143129 -0.044836 +v 0.011807 0.145966 -0.045801 +v 0.012567 0.144850 -0.045688 +v 0.011590 0.145539 -0.045834 +v 0.011604 0.138421 -0.044296 +v 0.011653 0.138518 -0.044878 +v 0.012883 0.139301 -0.045097 +v 0.012928 0.139282 -0.045536 +v 0.013515 0.141256 -0.045513 +v 0.013496 0.140970 -0.045861 +v 0.013371 0.143368 -0.045962 +v 0.013385 0.143002 -0.046316 +v 0.011803 0.145726 -0.046863 +v 0.011590 0.145328 -0.046827 +v 0.012943 0.139186 -0.046097 +v 0.012939 0.139043 -0.046508 +v 0.013595 0.142371 -0.046790 +v 0.013557 0.141281 -0.046982 +v 0.013016 0.143855 -0.047518 +v 0.012482 0.144737 -0.047301 +v 0.011621 0.145430 -0.048438 +v 0.011670 0.145538 -0.047867 +v 0.012210 0.138765 -0.046471 +v 0.011604 0.137989 -0.046277 +v 0.011624 0.145446 -0.048854 +v 0.012980 0.143743 -0.048529 +v 0.013482 0.142230 -0.047806 +v 0.013496 0.141644 -0.048109 +v 0.011646 0.145082 -0.048852 +v 0.011657 0.137872 -0.047318 +v 0.011562 0.146189 -0.045537 +v 0.011702 0.138617 -0.043890 +v 0.011600 0.145870 -0.047646 +v 0.011608 0.138100 -0.045883 +v 0.011608 0.139149 -0.040917 +v 0.011594 0.145943 -0.046534 +v 0.012740 0.144097 -0.048192 +v 0.011558 0.137689 -0.046888 +v 0.011605 0.138555 -0.043179 +v 0.012830 0.140753 -0.040161 +v 0.011555 0.147056 -0.041580 +v 0.011610 0.139370 -0.039920 +v 0.011688 0.139034 -0.041916 +v 0.017406 0.139064 -0.040492 +v 0.017497 0.142716 -0.041301 +v 0.018323 0.149495 -0.042657 +v 0.017465 0.141420 -0.047396 +v 0.017383 0.137753 -0.046660 +v 0.018417 0.148193 -0.048869 +v 0.011775 0.147301 -0.044934 +v 0.011552 0.137804 -0.045073 +v 0.011619 0.138244 -0.045306 +v 0.011557 0.138385 -0.042910 +v 0.020546 0.151623 -0.043176 +v 0.018889 0.151676 -0.042644 +v 0.021539 0.152544 -0.039129 +v 0.018730 0.152283 -0.039903 +v 0.020549 0.150322 -0.049400 +v 0.021526 0.149514 -0.053381 +v 0.018863 0.150149 -0.049830 +v 0.018734 0.149608 -0.052528 +v 0.021048 0.149366 -0.042687 +v 0.021693 0.139069 -0.040468 +v 0.016385 0.139664 -0.037668 +v 0.016020 0.136436 -0.049250 +v 0.015655 0.138197 -0.037357 +v 0.017532 0.140828 -0.050184 +v 0.021272 0.148028 -0.048677 +v 0.021686 0.137753 -0.046661 +v 0.011576 0.147209 -0.051540 +v 0.011590 0.135702 -0.049094 +v 0.011590 0.147920 -0.048122 +v 0.011590 0.148344 -0.046143 +v 0.011590 0.136944 -0.043253 +v 0.011594 0.149686 -0.039801 +v 0.011590 0.138197 -0.037357 +v 0.017740 0.143323 -0.038446 +v 0.011288 0.149691 -0.052189 +v 0.021725 0.150365 -0.047635 +v 0.021725 0.149938 -0.044198 +v 0.014000 0.146016 -0.039663 +v 0.011332 0.152222 -0.040262 +v 0.016038 0.145974 -0.039692 +v 0.008522 0.152429 -0.038803 +v 0.008548 0.149236 -0.053741 +v 0.022050 0.152161 -0.038547 +v 0.022079 0.148972 -0.053669 +v 0.008554 0.138003 -0.035483 +v 0.022019 0.134745 -0.050812 +v 0.022035 0.137998 -0.035505 +v 0.008515 0.134753 -0.050770 +v 0.018492 0.153657 -0.013784 +v 0.015646 0.150841 -0.026499 +v 0.015647 0.153504 -0.013986 +v 0.018648 0.150845 -0.026500 +v 0.013398 0.148757 -0.015423 +v 0.012722 0.144079 -0.013639 +v 0.013649 0.148468 -0.016384 +v 0.012824 0.145884 -0.016985 +v 0.013500 0.148310 -0.017884 +v 0.013521 0.147903 -0.018820 +v 0.012824 0.145442 -0.019063 +v 0.013509 0.147727 -0.019805 +v 0.013649 0.147533 -0.020786 +v 0.012824 0.144948 -0.021386 +v 0.013509 0.147207 -0.022250 +v 0.013649 0.147013 -0.023231 +v 0.012790 0.141952 -0.023518 +v 0.012792 0.151937 -0.014535 +v 0.012801 0.149444 -0.024842 +v 0.011194 0.151999 -0.014735 +v 0.011203 0.149745 -0.025219 +v 0.018721 0.153268 -0.014009 +v 0.022009 0.147207 -0.022250 +v 0.021324 0.144948 -0.021386 +v 0.022149 0.147013 -0.023231 +v 0.021300 0.141923 -0.023512 +v 0.021930 0.147803 -0.019821 +v 0.021324 0.145442 -0.019063 +v 0.022149 0.147533 -0.020786 +v 0.021898 0.148237 -0.017868 +v 0.021324 0.145884 -0.016985 +v 0.022019 0.148075 -0.018856 +v 0.022000 0.148830 -0.015439 +v 0.021344 0.144141 -0.013450 +v 0.022021 0.148423 -0.016374 +v 0.021267 0.151960 -0.014549 +v 0.021287 0.149435 -0.024843 +v 0.019670 0.151994 -0.014745 +v 0.019665 0.149766 -0.025201 +v 0.010979 0.149340 -0.015523 +v 0.010392 0.147942 -0.017384 +v 0.010786 0.149121 -0.017529 +v 0.015530 0.149650 -0.026122 +v 0.015531 0.152261 -0.013846 +v 0.014927 0.149302 -0.015605 +v 0.014720 0.148988 -0.017433 +v 0.015375 0.148329 -0.017356 +v 0.015341 0.147089 -0.021154 +v 0.014874 0.147675 -0.023314 +v 0.015362 0.147061 -0.023275 +v 0.014918 0.148764 -0.021717 +v 0.015149 0.148335 -0.021583 +v 0.015491 0.147460 -0.021309 +v 0.015483 0.148822 -0.023447 +v 0.015475 0.150071 -0.017559 +v 0.015498 0.150398 -0.015948 +v 0.015080 0.149122 -0.017448 +v 0.015491 0.148711 -0.015421 +v 0.012824 0.147657 -0.022346 +v 0.013288 0.147033 -0.023235 +v 0.012824 0.145198 -0.022845 +v 0.012824 0.148158 -0.020919 +v 0.012824 0.148328 -0.019421 +v 0.013288 0.147553 -0.020790 +v 0.012824 0.145718 -0.020400 +v 0.013390 0.148071 -0.017833 +v 0.012824 0.148796 -0.017220 +v 0.012824 0.146134 -0.018444 +v 0.013288 0.148488 -0.016388 +v 0.012824 0.146654 -0.015998 +v 0.011147 0.144140 -0.012977 +v 0.012824 0.148261 -0.013738 +v 0.011138 0.141882 -0.023598 +v 0.023351 0.147666 -0.023398 +v 0.023937 0.147146 -0.021135 +v 0.023544 0.148281 -0.021482 +v 0.018823 0.152371 -0.013826 +v 0.018826 0.149742 -0.026187 +v 0.019331 0.148249 -0.021556 +v 0.019275 0.148471 -0.023406 +v 0.019123 0.147034 -0.023262 +v 0.018919 0.147464 -0.021310 +v 0.019331 0.149501 -0.015668 +v 0.019435 0.148759 -0.017406 +v 0.018924 0.148306 -0.017354 +v 0.019145 0.148752 -0.015433 +v 0.018913 0.150393 -0.015947 +v 0.019493 0.149885 -0.015788 +v 0.018998 0.150152 -0.017568 +v 0.021442 0.149705 -0.016647 +v 0.021890 0.148591 -0.015388 +v 0.021324 0.149232 -0.014471 +v 0.021324 0.146654 -0.015998 +v 0.021883 0.147884 -0.018816 +v 0.021577 0.147753 -0.020696 +v 0.021324 0.146134 -0.018444 +v 0.021324 0.147860 -0.021622 +v 0.021324 0.145718 -0.020400 +v 0.021788 0.147033 -0.023235 +v 0.021324 0.145198 -0.022845 +v 0.019612 0.144136 -0.012995 +v 0.019622 0.141882 -0.023601 +v 0.018948 0.149194 -0.021852 +v 0.019528 0.147921 -0.021453 +v 0.010364 0.148371 -0.015227 +v 0.010745 0.147637 -0.023395 +v 0.010987 0.148105 -0.021428 +v 0.010354 0.147088 -0.021117 +v 0.010260 0.150018 -0.017639 +v 0.010343 0.150439 -0.015859 +v 0.010325 0.148811 -0.023538 +v 0.010268 0.149159 -0.021751 +v 0.015504 0.149831 -0.017531 +v 0.012824 0.146115 -0.023835 +v 0.021999 0.144770 -0.024945 +v 0.020723 0.144664 -0.024873 +v 0.020851 0.143353 -0.024036 +v 0.021875 0.143467 -0.024229 +v 0.020824 0.143596 -0.024388 +v 0.023965 0.146663 -0.023274 +v 0.024071 0.149145 -0.021746 +v 0.024006 0.148811 -0.023538 +v 0.023585 0.149313 -0.015514 +v 0.023343 0.148939 -0.017506 +v 0.023986 0.147856 -0.017373 +v 0.024006 0.150443 -0.015861 +v 0.024062 0.150033 -0.017641 +v 0.018908 0.144906 -0.016959 +v 0.018908 0.149831 -0.017531 +v 0.018909 0.144133 -0.020271 +v 0.018908 0.148579 -0.023419 +v 0.023997 0.144296 -0.012240 +v 0.023072 0.145994 -0.012770 +v 0.023920 0.141715 -0.024384 +v 0.023059 0.143489 -0.024558 +v 0.021324 0.146115 -0.023835 +v 0.010265 0.148343 -0.017433 +v 0.010658 0.149385 -0.015537 +v 0.010265 0.150173 -0.015778 +v 0.010658 0.148132 -0.021436 +v 0.010265 0.147091 -0.023327 +v 0.010265 0.148531 -0.023504 +v 0.015504 0.144308 -0.012184 +v 0.015504 0.141710 -0.024407 +v 0.010308 0.141724 -0.024342 +v 0.010309 0.144294 -0.012250 +v 0.010706 0.149259 -0.026105 +v 0.010219 0.149507 -0.025445 +v 0.024065 0.147531 -0.021253 +v 0.023673 0.147713 -0.023403 +v 0.024065 0.148531 -0.023504 +v 0.024065 0.150173 -0.015778 +v 0.024065 0.148785 -0.015354 +v 0.023673 0.148966 -0.017510 +v 0.018908 0.144308 -0.012184 +v 0.018908 0.141710 -0.024407 +v 0.023506 0.151939 -0.013719 +v 0.024115 0.151798 -0.014325 +v 0.013275 0.146082 -0.013065 +v 0.012183 0.146090 -0.013049 +v 0.010218 0.151766 -0.013998 +v 0.011002 0.152174 -0.013799 +v 0.013275 0.143685 -0.024315 +v 0.012183 0.143693 -0.024350 +v 0.024086 0.149237 -0.025786 +v 0.023304 0.149643 -0.026167 +v 0.024074 0.150785 -0.019935 +v 0.021897 0.146104 -0.013036 +v 0.020818 0.146067 -0.013070 +v 0.010152 0.153496 -0.013985 +v 0.010153 0.150835 -0.026499 +v 0.024148 0.150836 -0.026498 +v 0.024146 0.153495 -0.013985 +v 0.025776 0.150479 -0.028004 +v 0.008534 0.150485 -0.028008 +v 0.025788 0.153786 -0.012477 +v 0.008522 0.153776 -0.012466 +v 0.025898 0.144388 -0.010434 +v 0.008423 0.144393 -0.010413 +v 0.008402 0.141071 -0.026039 +v 0.025877 0.141067 -0.026060 +v 0.008344 0.139902 -0.025926 +v 0.008316 0.143268 -0.010089 +v 0.025984 0.139908 -0.025898 +v 0.025956 0.143274 -0.010061 +v 0.030140 0.159355 -0.020305 +v 0.029487 0.160160 -0.016515 +v 0.033093 0.160594 -0.014474 +v 0.035889 0.159834 -0.018049 +v 0.033821 0.159254 -0.020777 +v 0.035010 0.149258 -0.012973 +v 0.032103 0.149491 -0.011879 +v 0.029188 0.149005 -0.014166 +v 0.029902 0.148219 -0.017864 +v 0.032770 0.147969 -0.019040 +v 0.035867 0.148493 -0.016574 +v 0.035409 0.144614 -0.018468 +v 0.028500 0.144920 -0.017031 +v 0.036500 0.145880 -0.012513 +v 0.029591 0.146186 -0.011075 +v 0.035574 0.157034 -0.031225 +v 0.031460 0.156720 -0.032700 +v 0.029030 0.157479 -0.029131 +v 0.033627 0.158097 -0.026220 +v 0.033034 0.146955 -0.023810 +v 0.029750 0.146661 -0.025194 +v 0.029317 0.145960 -0.028491 +v 0.031926 0.145514 -0.030591 +v 0.035314 0.145819 -0.029155 +v 0.035448 0.146641 -0.025286 +v 0.030682 0.141989 -0.030822 +v 0.037227 0.143036 -0.025894 +v 0.029591 0.143691 -0.022813 +v 0.064553 0.114719 -0.076967 +v 0.063800 0.116954 -0.075062 +v 0.062637 0.115483 -0.076517 +v 0.065774 0.115876 -0.075755 +v 0.063717 0.120980 -0.079427 +v 0.066325 0.120032 -0.079979 +v 0.064366 0.118571 -0.081603 +v 0.067520 0.119061 -0.081048 +v 0.061806 0.119636 -0.081156 +v 0.063398 0.122057 -0.078647 +v 0.063961 0.117964 -0.082637 +v 0.066170 0.117937 -0.082159 +v 0.067346 0.120976 -0.079211 +v 0.062237 0.121243 -0.080122 +v 0.065801 0.122088 -0.078951 +v 0.066681 0.120648 -0.081539 +v 0.065861 0.121790 -0.080655 +v 0.063862 0.122048 -0.080730 +v 0.063269 0.120521 -0.082131 +v 0.064038 0.119945 -0.082592 +v 0.065838 0.119881 -0.082435 +v 0.065507 0.110554 -0.080700 +v 0.063224 0.110838 -0.080782 +v 0.062778 0.109611 -0.081922 +v 0.064689 0.108780 -0.082518 +v 0.063227 0.113355 -0.086574 +v 0.064685 0.115196 -0.084658 +v 0.066407 0.113454 -0.086070 +v 0.062932 0.115915 -0.084442 +v 0.061818 0.113794 -0.086466 +v 0.062977 0.112508 -0.087775 +v 0.065456 0.116316 -0.084120 +v 0.065690 0.111887 -0.087776 +v 0.067752 0.113826 -0.085745 +v 0.067010 0.115409 -0.084410 +v 0.067120 0.112835 -0.087098 +v 0.062423 0.115572 -0.085642 +v 0.066667 0.115007 -0.086795 +v 0.066065 0.115766 -0.086182 +v 0.064396 0.116291 -0.085936 +v 0.063349 0.114801 -0.087517 +v 0.064469 0.113153 -0.088220 +v 0.065848 0.113914 -0.087921 +v 0.064100 0.114869 0.087435 +v 0.065663 0.113926 0.087945 +v 0.066950 0.114383 0.087394 +v 0.065605 0.109112 0.082108 +v 0.064517 0.111352 0.080224 +v 0.066322 0.110509 0.080784 +v 0.063391 0.109875 0.081727 +v 0.064094 0.115181 0.084848 +v 0.065663 0.112875 0.086783 +v 0.066880 0.114672 0.084962 +v 0.063234 0.112984 0.087216 +v 0.062480 0.114854 0.085667 +v 0.063810 0.116244 0.084084 +v 0.064926 0.112228 0.087733 +v 0.065541 0.116526 0.083648 +v 0.067736 0.115529 0.084182 +v 0.068535 0.114029 0.085673 +v 0.066901 0.112392 0.087430 +v 0.067331 0.115232 0.086587 +v 0.066860 0.116314 0.085156 +v 0.063717 0.116032 0.085787 +v 0.065485 0.116613 0.085587 +v 0.064522 0.115402 0.085958 +v 0.063609 0.115468 0.076400 +v 0.066350 0.116352 0.075299 +v 0.065743 0.115025 0.076602 +v 0.064302 0.117188 0.074769 +v 0.063802 0.120062 0.080295 +v 0.066361 0.118864 0.081077 +v 0.066104 0.121236 0.078912 +v 0.063347 0.118757 0.081838 +v 0.062542 0.120875 0.080008 +v 0.063953 0.122111 0.078518 +v 0.065976 0.118010 0.082228 +v 0.065757 0.122443 0.078295 +v 0.067795 0.121406 0.078764 +v 0.068473 0.120148 0.079998 +v 0.067637 0.118505 0.081457 +v 0.067272 0.120668 0.081539 +v 0.065859 0.119957 0.082402 +v 0.064414 0.119278 0.082371 +v 0.064049 0.120776 0.081800 +v 0.064238 0.122085 0.080632 +v 0.066593 0.122142 0.080216 +v 0.063979 -0.085114 -0.005499 +v 0.062816 -0.085223 -0.003536 +v 0.064626 -0.085022 -0.002522 +v 0.065966 -0.084924 -0.004207 +v 0.064688 -0.090995 -0.005852 +v 0.066240 -0.090866 -0.002839 +v 0.063544 -0.091118 -0.003152 +v 0.062008 -0.091446 -0.004516 +v 0.063466 -0.091293 -0.006750 +v 0.065417 -0.091217 -0.001038 +v 0.062428 -0.091371 -0.002411 +v 0.063721 -0.091595 -0.001441 +v 0.067451 -0.090926 -0.002448 +v 0.067762 -0.091067 -0.005055 +v 0.066278 -0.090943 -0.006700 +v 0.066736 -0.092457 -0.003819 +v 0.065930 -0.092425 -0.005673 +v 0.064352 -0.092636 -0.005681 +v 0.063240 -0.092783 -0.003956 +v 0.064485 -0.092707 -0.002550 +v 0.066164 -0.092476 -0.002651 +v 0.063782 -0.092708 0.002918 +v 0.064790 -0.092565 0.002237 +v 0.066771 -0.092367 0.003242 +v 0.065100 -0.084981 0.005440 +v 0.064489 -0.085070 0.002471 +v 0.062740 -0.085204 0.004230 +v 0.065804 -0.084930 0.003600 +v 0.063876 -0.091070 0.002688 +v 0.066230 -0.090850 0.003016 +v 0.065793 -0.090906 0.005480 +v 0.063613 -0.091107 0.004837 +v 0.062111 -0.091372 0.004998 +v 0.063514 -0.091222 0.001236 +v 0.064402 -0.091393 0.006957 +v 0.066931 -0.090880 0.006308 +v 0.067663 -0.090826 0.002578 +v 0.062207 -0.091613 0.003254 +v 0.067612 -0.091332 0.004945 +v 0.066082 -0.091588 0.001493 +v 0.066602 -0.092489 0.004043 +v 0.063306 -0.092713 0.004548 +v 0.064541 -0.092668 0.005530 +v 0.065979 -0.092489 0.005491 +v 0.035596 0.112352 -0.100162 +v 0.037938 0.112274 -0.099312 +v 0.035777 0.110268 -0.097252 +v 0.033805 0.111861 -0.098778 +v 0.028985 0.110024 -0.097831 +v 0.028596 0.111927 -0.098877 +v 0.031057 0.110732 -0.097594 +v 0.028849 0.108948 -0.095827 +v 0.026879 0.110542 -0.097363 +v 0.015936 0.111495 -0.098987 +v 0.018397 0.111125 -0.098204 +v 0.016736 0.109301 -0.096229 +v 0.014450 0.110448 -0.097459 +v 0.014748 0.112276 -0.097208 +v 0.015538 0.110819 -0.095646 +v 0.018105 0.111357 -0.096223 +v 0.016984 0.112861 -0.097836 +v 0.015584 0.131779 -0.079956 +v 0.015139 0.129950 -0.077994 +v 0.017067 0.129839 -0.077875 +v 0.018071 0.131209 -0.079345 +v 0.055034 0.112056 -0.092162 +v 0.057058 0.114574 -0.092517 +v 0.055208 0.112884 -0.090704 +v 0.057276 0.111910 -0.089660 +v 0.059032 0.113012 -0.090842 +v 0.055676 0.125700 -0.081078 +v 0.055791 0.123802 -0.079043 +v 0.058522 0.123779 -0.079018 +v 0.058244 0.125924 -0.081318 +v 0.046439 0.116802 -0.097096 +v 0.044623 0.126537 -0.079232 +v 0.044623 0.112419 -0.092397 +v 0.075900 0.034990 0.102104 +v 0.075830 0.036841 0.101284 +v 0.075848 0.034370 0.105350 +v 0.075900 0.032648 0.100076 +v 0.075825 0.029811 0.100695 +v 0.075849 0.033392 0.098010 +v 0.075900 0.032063 0.103118 +v 0.075823 0.030431 0.103930 +v 0.041948 0.031334 0.102008 +v 0.042169 0.035184 0.102633 +v 0.041987 0.034192 0.100112 +v 0.042031 0.032742 0.103584 +v 0.071824 0.035111 0.100577 +v 0.071830 0.032826 0.099659 +v 0.042379 0.031822 0.100148 +v 0.071823 0.031047 0.101358 +v 0.071834 0.032000 0.103515 +v 0.071819 0.034607 0.103562 +v 0.071951 0.031924 0.098316 +v 0.071942 0.036614 0.100132 +v 0.071965 0.035937 0.103983 +v 0.071957 0.032967 0.105388 +v 0.071951 0.029609 0.102457 +v 0.072900 0.032226 0.100288 +v 0.072900 0.032458 0.103377 +v 0.072900 0.035017 0.101632 +v 0.075946 0.030509 0.169940 +v 0.075900 0.034586 0.169405 +v 0.075837 0.033402 0.171927 +v 0.075823 0.035619 0.165616 +v 0.075830 0.036788 0.169015 +v 0.075900 0.033572 0.166478 +v 0.075825 0.029811 0.167163 +v 0.075825 0.032450 0.164734 +v 0.041959 0.034905 0.169257 +v 0.042037 0.032860 0.166313 +v 0.042041 0.031255 0.168037 +v 0.042029 0.032731 0.170084 +v 0.071787 0.032517 0.170507 +v 0.071824 0.035481 0.168381 +v 0.042379 0.034852 0.166822 +v 0.071834 0.034145 0.166297 +v 0.071811 0.031410 0.166831 +v 0.071942 0.035926 0.170851 +v 0.071957 0.036180 0.166111 +v 0.071961 0.031485 0.171357 +v 0.071957 0.029612 0.167967 +v 0.071957 0.032247 0.164739 +v 0.072900 0.034845 0.169010 +v 0.072900 0.033100 0.166451 +v 0.072900 0.031756 0.169242 +v 0.080699 0.000467 0.193353 +v 0.080711 -0.001720 0.198014 +v 0.080671 -0.002621 0.194700 +v 0.080592 0.000578 0.198725 +v 0.080626 0.002569 0.197136 +v 0.080725 0.002405 0.195153 +v 0.065768 -0.001175 0.196772 +v 0.065803 0.001388 0.196221 +v 0.065787 -0.000826 0.194882 +v 0.077630 -0.001546 0.195346 +v 0.077622 -0.000819 0.197517 +v 0.066190 0.000333 0.197550 +v 0.077627 0.001510 0.196798 +v 0.077614 0.000692 0.194388 +v 0.066184 0.000626 0.194516 +v 0.077724 0.001921 0.193797 +v 0.077788 0.002568 0.197128 +v 0.077777 -0.001297 0.193549 +v 0.077751 -0.002838 0.195937 +v 0.077742 -0.000465 0.198924 +v 0.078700 -0.000503 0.197403 +v 0.078700 0.001466 0.195734 +v 0.078700 -0.000964 0.194863 +v 0.070700 -0.031491 0.100173 +v 0.071900 -0.033286 0.099419 +v 0.071900 -0.030990 0.101168 +v 0.070700 -0.035523 0.100533 +v 0.071900 -0.035675 0.101609 +v 0.070700 -0.033393 0.104244 +v 0.071900 -0.033730 0.104032 +v 0.071900 -0.030539 0.102236 +v 0.070700 -0.030934 0.102011 +v 0.070700 -0.029988 0.103511 +v 0.071900 -0.031163 0.104984 +v 0.070700 -0.034443 0.105354 +v 0.071900 -0.035578 0.104560 +v 0.070700 -0.036956 0.100704 +v 0.071900 -0.036724 0.100091 +v 0.070700 -0.032947 0.098099 +v 0.071900 -0.032705 0.098186 +v 0.071900 -0.029851 0.100439 +v 0.070700 -0.029697 0.100762 +v 0.070700 0.034827 0.103509 +v 0.071900 0.035644 0.102183 +v 0.071900 0.033485 0.104019 +v 0.070700 0.034467 0.099477 +v 0.071900 0.034101 0.099642 +v 0.071900 0.031592 0.100088 +v 0.070700 0.030679 0.101932 +v 0.071900 0.031484 0.103435 +v 0.070700 0.033180 0.104032 +v 0.070971 0.032561 0.105357 +v 0.070700 0.029448 0.101689 +v 0.071900 0.030606 0.104339 +v 0.071900 0.029770 0.100531 +v 0.070700 0.032046 0.098318 +v 0.071900 0.032299 0.098296 +v 0.071900 0.035930 0.099163 +v 0.070700 0.035210 0.098764 +v 0.070700 0.036911 0.101680 +v 0.071900 0.036634 0.103006 +v 0.070700 0.034468 0.105236 +v 0.071900 0.034093 0.105279 +v 0.075900 -0.033820 0.166544 +v 0.075900 -0.034405 0.169586 +v 0.075849 -0.036817 0.169370 +v 0.075848 -0.034370 0.164650 +v 0.075837 -0.032428 0.171842 +v 0.075900 -0.031478 0.168572 +v 0.075864 -0.029501 0.167400 +v 0.042008 -0.031819 0.166803 +v 0.041945 -0.034939 0.169130 +v 0.042061 -0.031574 0.169196 +v 0.042088 -0.034452 0.166686 +v 0.071811 -0.035481 0.168730 +v 0.042367 -0.033382 0.170412 +v 0.071787 -0.031954 0.170244 +v 0.071824 -0.031677 0.166607 +v 0.071834 -0.034132 0.166291 +v 0.071942 -0.032854 0.171969 +v 0.071961 -0.036581 0.169502 +v 0.071963 -0.036154 0.166243 +v 0.071961 -0.033281 0.164655 +v 0.071965 -0.030581 0.165957 +v 0.071961 -0.029701 0.168809 +v 0.072900 -0.031603 0.168906 +v 0.072900 -0.034865 0.167562 +v 0.070700 -0.034492 0.166287 +v 0.070700 -0.035306 0.169534 +v 0.071900 -0.034580 0.166316 +v 0.071900 -0.035128 0.169727 +v 0.070700 -0.032014 0.170275 +v 0.071900 -0.031928 0.170222 +v 0.070700 -0.030981 0.167939 +v 0.071900 -0.031003 0.167697 +v 0.070700 -0.032651 0.165981 +v 0.071900 -0.033307 0.165437 +v 0.070700 -0.032452 0.164695 +v 0.071900 -0.030761 0.165554 +v 0.070700 -0.029585 0.167559 +v 0.071900 -0.029777 0.169878 +v 0.070700 -0.032149 0.171997 +v 0.071900 -0.033567 0.171837 +v 0.071900 -0.036634 0.169721 +v 0.070700 -0.036782 0.169441 +v 0.071900 -0.036011 0.165870 +v 0.070700 -0.035784 0.165666 +v 0.071300 -0.033556 0.164715 +v 0.070700 0.031287 0.169492 +v 0.071900 0.032969 0.170703 +v 0.071900 0.030981 0.168485 +v 0.070700 0.033776 0.170464 +v 0.070700 0.035735 0.167686 +v 0.071900 0.035607 0.168387 +v 0.071900 0.034017 0.166051 +v 0.070700 0.032335 0.166032 +v 0.071900 0.031268 0.166970 +v 0.070700 0.030968 0.168180 +v 0.071194 0.029681 0.168196 +v 0.070700 0.030910 0.165423 +v 0.071900 0.030661 0.165606 +v 0.071900 0.034098 0.164720 +v 0.070700 0.034770 0.164855 +v 0.071900 0.036545 0.166773 +v 0.070700 0.036940 0.169498 +v 0.071900 0.036097 0.170652 +v 0.070700 0.032386 0.171847 +v 0.071900 0.032529 0.171758 +v 0.071900 0.029851 0.169561 +v 0.070700 0.029637 0.168853 +v 0.080673 0.039019 0.127157 +v 0.080680 0.040289 0.131579 +v 0.080618 0.038381 0.130144 +v 0.080675 0.043669 0.128473 +v 0.080619 0.041517 0.126176 +v 0.080601 0.042957 0.131039 +v 0.069779 0.040037 0.127975 +v 0.069938 0.039926 0.130175 +v 0.069885 0.041958 0.130061 +v 0.069928 0.042182 0.127908 +v 0.077591 0.041298 0.130714 +v 0.077609 0.039315 0.128998 +v 0.077598 0.041032 0.127277 +v 0.077613 0.042632 0.128830 +v 0.077762 0.043126 0.126875 +v 0.077779 0.038159 0.128755 +v 0.077775 0.039432 0.131310 +v 0.077743 0.042885 0.131293 +v 0.077766 0.039710 0.126553 +v 0.078700 0.042261 0.129756 +v 0.078700 0.039739 0.128244 +v 0.051629 0.019947 0.174418 +v 0.051200 0.016925 0.178915 +v 0.051200 0.008453 0.178112 +v 0.051200 0.030157 0.167613 +v 0.051200 0.030521 0.169930 +v 0.049000 0.030526 0.169943 +v 0.049001 0.030197 0.167468 +v 0.049000 0.016658 0.178911 +v 0.049001 0.011001 0.177757 +v 0.053465 0.022023 0.173413 +v 0.052717 0.015532 0.178786 +v 0.053200 0.008453 0.178112 +v 0.053200 0.030225 0.167099 +v 0.053200 0.030521 0.169930 +v 0.052700 0.023419 0.175315 +v 0.052200 0.030526 0.169943 +v 0.052200 0.008520 0.178110 +v 0.052200 0.030353 0.166791 +v 0.055465 0.022023 0.173413 +v 0.054717 0.015532 0.178786 +v 0.055200 0.008453 0.178112 +v 0.055200 0.030225 0.167099 +v 0.055200 0.030521 0.169930 +v 0.054700 0.023419 0.175316 +v 0.054200 0.030526 0.169943 +v 0.054200 0.007443 0.178510 +v 0.054200 0.030353 0.166791 +v 0.057465 0.022023 0.173413 +v 0.056717 0.015532 0.178786 +v 0.057200 0.008453 0.178112 +v 0.057200 0.030225 0.167099 +v 0.057200 0.030521 0.169930 +v 0.056700 0.023419 0.175315 +v 0.056200 0.030526 0.169943 +v 0.056200 0.007443 0.178510 +v 0.056200 0.030353 0.166791 +v 0.059465 0.022023 0.173413 +v 0.058717 0.015532 0.178786 +v 0.059200 0.008453 0.178112 +v 0.059200 0.030225 0.167099 +v 0.059200 0.030521 0.169930 +v 0.058700 0.023419 0.175315 +v 0.058200 0.030526 0.169943 +v 0.058200 0.007443 0.178510 +v 0.058200 0.030353 0.166791 +v 0.061200 0.022089 0.173489 +v 0.060717 0.015532 0.178786 +v 0.061200 0.008453 0.178112 +v 0.061200 0.030225 0.167099 +v 0.061200 0.030521 0.169930 +v 0.060700 0.023419 0.175315 +v 0.060200 0.030526 0.169943 +v 0.060200 0.007443 0.178510 +v 0.060200 0.030353 0.166791 +v 0.063201 0.022132 0.173440 +v 0.062717 0.015532 0.178786 +v 0.063201 0.008516 0.178079 +v 0.063200 0.030225 0.167105 +v 0.063200 0.030521 0.169930 +v 0.062700 0.023419 0.175315 +v 0.062200 0.030488 0.169969 +v 0.062200 0.029963 0.168110 +v 0.062200 0.008520 0.178110 +v 0.051200 -0.006644 0.178616 +v 0.051200 0.003031 0.181356 +v 0.051200 -0.002947 0.181431 +v 0.051200 0.042346 0.121244 +v 0.051200 0.032237 0.104805 +v 0.051200 0.034931 0.104479 +v 0.051200 0.040920 0.112548 +v 0.051200 0.046474 0.129212 +v 0.051700 0.044000 0.137428 +v 0.051200 0.034949 0.165520 +v 0.051629 0.041784 0.149344 +v 0.051200 0.043965 0.151718 +v 0.051200 0.032257 0.165260 +v 0.049001 -0.006913 0.178547 +v 0.049000 0.002884 0.181425 +v 0.049000 -0.003056 0.181362 +v 0.049000 0.037910 0.157677 +v 0.049000 0.032218 0.165204 +v 0.049000 0.034931 0.165521 +v 0.049000 0.042833 0.123575 +v 0.048376 0.043764 0.142710 +v 0.049000 0.043965 0.118282 +v 0.049000 0.031675 0.104423 +v 0.049000 0.034949 0.104480 +v 0.049000 0.046474 0.140788 +v 0.049000 0.040920 0.157451 +v 0.053200 -0.006644 0.178616 +v 0.052717 0.002969 0.181405 +v 0.052719 -0.002982 0.181408 +v 0.053200 0.042346 0.121244 +v 0.053200 0.032237 0.104805 +v 0.053200 0.034931 0.104479 +v 0.053200 0.040920 0.112548 +v 0.053200 0.046474 0.129212 +v 0.053200 0.043279 0.145457 +v 0.053200 0.034949 0.165520 +v 0.053200 0.043965 0.151718 +v 0.053200 0.032559 0.165235 +v 0.052200 -0.006835 0.178565 +v 0.052200 0.042458 0.122272 +v 0.052200 0.043965 0.118282 +v 0.052200 0.032559 0.104765 +v 0.052200 0.034949 0.104480 +v 0.052200 0.046474 0.140788 +v 0.052200 0.040920 0.157452 +v 0.052200 0.032906 0.165161 +v 0.052200 0.034931 0.165521 +v 0.055200 -0.006644 0.178616 +v 0.054717 0.002969 0.181405 +v 0.054719 -0.002982 0.181408 +v 0.055200 0.039309 0.114517 +v 0.055714 0.032010 0.104709 +v 0.055200 0.034931 0.104479 +v 0.055200 0.040920 0.112548 +v 0.055200 0.046474 0.129212 +v 0.055575 0.043749 0.129230 +v 0.055200 0.034949 0.165520 +v 0.055200 0.042709 0.147077 +v 0.055200 0.043965 0.151718 +v 0.055200 0.032559 0.165235 +v 0.054200 -0.008545 0.177920 +v 0.054200 0.038648 0.113295 +v 0.054200 0.044214 0.131865 +v 0.054200 0.043965 0.118282 +v 0.054200 0.034949 0.104480 +v 0.054200 0.031771 0.104560 +v 0.054200 0.046474 0.140788 +v 0.054200 0.041972 0.148762 +v 0.054200 0.040920 0.157452 +v 0.054200 0.032906 0.165161 +v 0.054200 0.034931 0.165521 +v 0.057200 -0.006644 0.178616 +v 0.056717 0.002969 0.181405 +v 0.056719 -0.002982 0.181408 +v 0.057200 0.040920 0.112548 +v 0.057200 0.032512 0.104874 +v 0.057200 0.034931 0.104479 +v 0.057200 0.041972 0.121237 +v 0.057200 0.046474 0.129212 +v 0.057200 0.044214 0.138135 +v 0.057200 0.034949 0.165520 +v 0.057700 0.041700 0.149575 +v 0.057200 0.043965 0.151718 +v 0.057200 0.032559 0.165235 +v 0.056200 -0.008545 0.177920 +v 0.056200 0.038648 0.113295 +v 0.056200 0.043965 0.118282 +v 0.056200 0.043379 0.144721 +v 0.056200 0.034949 0.104480 +v 0.056200 0.046474 0.140788 +v 0.056200 0.040920 0.157452 +v 0.056200 0.032906 0.165161 +v 0.056200 0.034931 0.165521 +v 0.059200 -0.006644 0.178616 +v 0.058717 0.002969 0.181405 +v 0.058719 -0.002982 0.181408 +v 0.059200 0.040920 0.112548 +v 0.059200 0.032512 0.104874 +v 0.059200 0.034931 0.104479 +v 0.059200 0.042836 0.123609 +v 0.059200 0.046474 0.129212 +v 0.059200 0.043279 0.145457 +v 0.059200 0.034949 0.165520 +v 0.059200 0.043965 0.151718 +v 0.059200 0.032559 0.165235 +v 0.058200 -0.008545 0.177920 +v 0.058200 0.038648 0.113295 +v 0.058200 0.044214 0.131865 +v 0.058200 0.043965 0.118282 +v 0.058200 0.034949 0.104480 +v 0.058200 0.031771 0.104560 +v 0.058200 0.046474 0.140788 +v 0.058200 0.040920 0.157452 +v 0.058200 0.032906 0.165161 +v 0.058200 0.034931 0.165521 +v 0.061200 -0.006644 0.178616 +v 0.060717 0.002970 0.181405 +v 0.060719 -0.002982 0.181408 +v 0.061200 0.040920 0.112548 +v 0.061200 0.032512 0.104874 +v 0.061200 0.034931 0.104479 +v 0.061678 0.042535 0.122596 +v 0.061200 0.046474 0.129212 +v 0.061200 0.043279 0.145457 +v 0.061200 0.034949 0.165520 +v 0.061200 0.043965 0.151718 +v 0.061200 0.032559 0.165235 +v 0.060200 -0.008545 0.177920 +v 0.060200 0.038648 0.113295 +v 0.060200 0.044214 0.131865 +v 0.060200 0.043965 0.118282 +v 0.060200 0.034949 0.104480 +v 0.060200 0.031771 0.104560 +v 0.060200 0.046474 0.140788 +v 0.060200 0.041972 0.148763 +v 0.060200 0.040920 0.157452 +v 0.060200 0.032906 0.165161 +v 0.060200 0.034931 0.165521 +v 0.063200 -0.006139 0.178800 +v 0.062717 0.002969 0.181405 +v 0.062719 -0.002982 0.181408 +v 0.062557 0.032199 0.165252 +v 0.063200 0.038606 0.156716 +v 0.063200 0.040582 0.116756 +v 0.063200 0.032208 0.104796 +v 0.063200 0.034931 0.104479 +v 0.063200 0.040920 0.112548 +v 0.063200 0.046474 0.129212 +v 0.063609 0.044070 0.139984 +v 0.063200 0.034949 0.165520 +v 0.063200 0.043965 0.151718 +v 0.062200 -0.006835 0.178565 +v 0.062200 0.039308 0.155483 +v 0.062200 0.034931 0.165521 +v 0.062200 0.044291 0.136748 +v 0.062200 0.043965 0.118282 +v 0.062200 0.032092 0.104681 +v 0.062200 0.034949 0.104480 +v 0.062200 0.046474 0.140788 +v 0.062200 0.040920 0.157452 +v 0.064335 0.043511 0.151264 +v 0.064389 0.037168 0.164276 +v 0.070701 0.043498 0.151265 +v 0.070788 0.037404 0.162482 +v 0.064356 0.032149 0.173711 +v 0.064325 0.019270 0.197242 +v 0.070468 0.032288 0.173657 +v 0.070701 0.018874 0.197677 +v 0.051200 0.030066 0.101991 +v 0.051629 0.010990 0.092032 +v 0.051200 0.021329 0.093484 +v 0.051200 0.004353 0.088370 +v 0.051200 -0.010207 0.091866 +v 0.051200 -0.018146 0.091605 +v 0.051200 -0.030099 0.102214 +v 0.051200 -0.030502 0.100059 +v 0.051200 0.030520 0.100051 +v 0.049000 -0.030526 0.100055 +v 0.049000 -0.030221 0.102669 +v 0.049000 -0.017519 0.094444 +v 0.048514 0.018837 0.094700 +v 0.049000 0.030457 0.100057 +v 0.049000 -0.000857 0.090673 +v 0.049000 -0.016718 0.091035 +v 0.049000 0.005788 0.088526 +v 0.049000 0.022452 0.094080 +v 0.053200 -0.030502 0.100059 +v 0.053200 -0.019392 0.095142 +v 0.053200 -0.031104 0.104176 +v 0.053200 0.030066 0.101991 +v 0.053629 0.010990 0.092032 +v 0.052671 0.021896 0.093772 +v 0.052700 0.005072 0.088435 +v 0.053867 -0.002243 0.090786 +v 0.052700 -0.010026 0.089524 +v 0.052700 -0.021896 0.093772 +v 0.053200 0.030520 0.100051 +v 0.052200 -0.030526 0.100055 +v 0.052200 -0.030226 0.102696 +v 0.052200 -0.018301 0.094799 +v 0.052200 -0.001915 0.090716 +v 0.052200 0.030314 0.102852 +v 0.052200 0.030457 0.100057 +v 0.055700 0.015719 0.093718 +v 0.055200 0.004352 0.090889 +v 0.054671 0.021895 0.093772 +v 0.054700 0.005072 0.088435 +v 0.055200 -0.012601 0.092665 +v 0.054700 -0.010025 0.089524 +v 0.054700 -0.021896 0.093772 +v 0.055200 -0.030099 0.102214 +v 0.055200 -0.030502 0.100059 +v 0.055200 0.030263 0.102594 +v 0.055200 0.030520 0.100051 +v 0.054200 -0.030488 0.100029 +v 0.054200 -0.031450 0.104527 +v 0.054200 -0.020631 0.095769 +v 0.054200 0.030164 0.102359 +v 0.054200 0.030521 0.100069 +v 0.057200 -0.030502 0.100059 +v 0.057575 -0.019957 0.095564 +v 0.057200 -0.031292 0.104404 +v 0.057600 0.017701 0.094645 +v 0.057629 0.004653 0.090985 +v 0.056671 0.021895 0.093772 +v 0.056700 0.005072 0.088435 +v 0.057700 -0.008452 0.091730 +v 0.056700 -0.010025 0.089524 +v 0.056700 -0.021896 0.093772 +v 0.057200 0.030263 0.102594 +v 0.057200 0.030520 0.100051 +v 0.056200 -0.030488 0.100029 +v 0.056200 -0.031450 0.104527 +v 0.056200 -0.020632 0.095769 +v 0.056200 -0.001915 0.090716 +v 0.056200 0.030164 0.102359 +v 0.056200 0.030521 0.100069 +v 0.059200 -0.030502 0.100059 +v 0.059200 -0.019392 0.095142 +v 0.059200 -0.031104 0.104176 +v 0.059700 0.015719 0.093718 +v 0.059200 0.001966 0.090519 +v 0.058671 0.021895 0.093772 +v 0.058700 0.005072 0.088435 +v 0.058700 -0.010026 0.089524 +v 0.058700 -0.021896 0.093772 +v 0.059200 0.030263 0.102594 +v 0.059200 0.030520 0.100051 +v 0.058200 -0.030526 0.100055 +v 0.058200 -0.030226 0.102696 +v 0.058200 0.030164 0.102359 +v 0.058200 0.030521 0.100069 +v 0.061200 -0.030502 0.100059 +v 0.061200 -0.019392 0.095142 +v 0.061200 -0.031292 0.104404 +v 0.061200 0.030066 0.101991 +v 0.061629 0.010990 0.092032 +v 0.060671 0.021895 0.093772 +v 0.060700 0.005072 0.088435 +v 0.061867 -0.002243 0.090786 +v 0.060700 -0.010026 0.089524 +v 0.060700 -0.021896 0.093772 +v 0.061200 0.030520 0.100051 +v 0.060200 -0.030488 0.100029 +v 0.060200 -0.031450 0.104527 +v 0.060200 -0.020632 0.095769 +v 0.060200 -0.001915 0.090716 +v 0.060200 0.030164 0.102359 +v 0.060200 0.030521 0.100069 +v 0.063200 -0.030502 0.100059 +v 0.063200 -0.019348 0.095155 +v 0.063200 -0.030445 0.103074 +v 0.063200 0.013181 0.092632 +v 0.062700 0.005072 0.088435 +v 0.062671 0.021896 0.093772 +v 0.063825 -0.001183 0.090852 +v 0.062700 -0.010026 0.089524 +v 0.062700 -0.021896 0.093772 +v 0.063200 0.030267 0.102612 +v 0.063200 0.030520 0.100051 +v 0.062200 -0.030488 0.100029 +v 0.062200 -0.031450 0.104527 +v 0.062200 -0.020632 0.095769 +v 0.062200 0.030164 0.102359 +v 0.062200 0.030521 0.100069 +v 0.064330 0.046344 0.139285 +v 0.070701 0.046078 0.139991 +v 0.070710 0.045936 0.128077 +v 0.064242 0.044891 0.121956 +v 0.070699 0.042934 0.117353 +v 0.064392 0.037085 0.106389 +v 0.070762 0.037174 0.107465 +v 0.064200 0.018524 0.094660 +v 0.064201 0.036572 0.109407 +v 0.064200 -0.015455 0.093524 +v 0.064198 -0.031356 0.103525 +v 0.063199 -0.032580 0.104874 +v 0.063825 -0.042652 0.122862 +v 0.063198 -0.032214 0.165204 +v 0.063644 -0.040092 0.153920 +v 0.064200 -0.028159 0.169139 +v 0.063200 -0.030056 0.167848 +v 0.063507 -0.012034 0.177722 +v 0.064201 -0.001564 0.179218 +v 0.064205 0.019249 0.175145 +v 0.064201 0.036291 0.160550 +v 0.064200 0.043831 0.129534 +v 0.061652 -0.040092 0.116080 +v 0.061700 -0.040092 0.153920 +v 0.062200 -0.031292 0.165596 +v 0.061200 -0.032206 0.165204 +v 0.061200 -0.030170 0.167602 +v 0.062200 -0.021554 0.173555 +v 0.061200 -0.011774 0.177740 +v 0.059652 -0.040092 0.116080 +v 0.060200 -0.031199 0.165815 +v 0.059200 -0.032206 0.165204 +v 0.059644 -0.040445 0.152978 +v 0.059200 -0.030170 0.167602 +v 0.060200 -0.021554 0.173555 +v 0.059200 -0.011774 0.177740 +v 0.058200 -0.032206 0.104796 +v 0.057652 -0.040092 0.116080 +v 0.057700 -0.040092 0.153920 +v 0.058200 -0.031292 0.165596 +v 0.057200 -0.032206 0.165204 +v 0.057200 -0.030170 0.167602 +v 0.058200 -0.021554 0.173554 +v 0.057200 -0.011774 0.177740 +v 0.055200 -0.032222 0.104774 +v 0.055719 -0.040445 0.117022 +v 0.055700 -0.040092 0.153920 +v 0.056200 -0.031292 0.165596 +v 0.055200 -0.032206 0.165204 +v 0.055200 -0.030170 0.167602 +v 0.056200 -0.021554 0.173555 +v 0.055200 -0.011774 0.177740 +v 0.053652 -0.040092 0.116080 +v 0.053700 -0.040092 0.153920 +v 0.054200 -0.031292 0.165596 +v 0.053200 -0.032206 0.165204 +v 0.053200 -0.030170 0.167602 +v 0.054200 -0.021554 0.173555 +v 0.053200 -0.011774 0.177740 +v 0.052200 -0.032206 0.104796 +v 0.051200 -0.032222 0.104774 +v 0.051719 -0.040445 0.117022 +v 0.051700 -0.040092 0.153920 +v 0.052200 -0.031292 0.165596 +v 0.051200 -0.032206 0.165204 +v 0.051200 -0.030170 0.167602 +v 0.052200 -0.021554 0.173555 +v 0.051200 -0.011774 0.177740 +v 0.070757 0.027511 0.097824 +v 0.064328 0.019457 0.092912 +v 0.064381 0.028460 0.097885 +v 0.070730 0.016604 0.091622 +v 0.064326 0.007602 0.089125 +v 0.070765 0.002732 0.088506 +v 0.064297 -0.005303 0.088926 +v 0.070727 -0.014844 0.090852 +v 0.064353 -0.016811 0.091627 +v 0.064377 -0.028514 0.097910 +v 0.070714 -0.027265 0.097684 +v 0.064323 -0.014660 0.200080 +v 0.070712 -0.014761 0.200096 +v 0.064363 0.014380 0.200158 +v 0.070687 0.014204 0.200152 +v 0.064475 0.034828 0.097983 +v 0.070539 0.037048 0.100799 +v 0.070559 0.034845 0.098089 +v 0.064329 0.036947 0.100420 +v 0.064403 0.036874 0.170115 +v 0.064371 -0.034847 0.098070 +v 0.064431 -0.037059 0.100771 +v 0.064408 -0.037163 0.106543 +v 0.064317 -0.042413 0.116193 +v 0.070554 0.036812 0.170166 +v 0.070577 -0.036787 0.170051 +v 0.070932 -0.030301 0.165350 +v 0.070858 -0.029363 0.168799 +v 0.070788 -0.037416 0.162614 +v 0.070835 -0.030860 0.175090 +v 0.070913 -0.030444 0.104681 +v 0.070755 -0.037181 0.107495 +v 0.070593 -0.036919 0.100343 +v 0.070471 -0.034838 0.098003 +v 0.064423 -0.046357 0.129735 +v 0.063726 -0.044047 0.137883 +v 0.064337 -0.044685 0.148467 +v 0.064289 -0.019166 0.197301 +v 0.064401 -0.037161 0.164323 +v 0.064359 -0.036821 0.170146 +v 0.064375 -0.032066 0.173852 +v 0.051200 -0.016723 0.178891 +v 0.051200 -0.030488 0.169969 +v 0.049000 -0.019742 0.174397 +v 0.049000 -0.030188 0.167393 +v 0.049000 -0.016925 0.178915 +v 0.049000 -0.030521 0.169930 +v 0.052733 -0.023419 0.175315 +v 0.052664 -0.015529 0.178792 +v 0.053200 -0.030488 0.169969 +v 0.052200 -0.030502 0.169939 +v 0.055200 -0.030465 0.170384 +v 0.054756 -0.015588 0.178821 +v 0.054200 -0.030450 0.170644 +v 0.056733 -0.023419 0.175315 +v 0.056720 -0.015494 0.178809 +v 0.057200 -0.030488 0.169969 +v 0.056200 -0.030502 0.169939 +v 0.059200 -0.030465 0.170384 +v 0.058756 -0.015588 0.178821 +v 0.058200 -0.030450 0.170644 +v 0.061200 -0.030465 0.170384 +v 0.060756 -0.015588 0.178821 +v 0.060200 -0.030450 0.170644 +v 0.063200 -0.030465 0.170384 +v 0.063200 -0.015655 0.178826 +v 0.062200 -0.030502 0.169939 +v 0.062200 -0.016925 0.178915 +v 0.051200 -0.034931 0.165521 +v 0.051200 -0.034945 0.104474 +v 0.051200 -0.043965 0.118282 +v 0.051700 -0.044332 0.135000 +v 0.051200 -0.046474 0.140788 +v 0.051200 -0.040920 0.157452 +v 0.049000 -0.034931 0.104479 +v 0.049000 -0.041228 0.118150 +v 0.049000 -0.032227 0.104797 +v 0.049002 -0.032643 0.165119 +v 0.049000 -0.043925 0.142372 +v 0.049000 -0.043965 0.151718 +v 0.049000 -0.046474 0.129212 +v 0.049000 -0.040920 0.112548 +v 0.049000 -0.034949 0.165520 +v 0.053200 -0.034931 0.165521 +v 0.053200 -0.034949 0.104480 +v 0.053200 -0.043965 0.118282 +v 0.053700 -0.044332 0.135000 +v 0.053200 -0.046474 0.140788 +v 0.053200 -0.040920 0.157451 +v 0.052200 -0.034931 0.104479 +v 0.052200 -0.034945 0.165526 +v 0.052200 -0.043965 0.151718 +v 0.052200 -0.046474 0.129212 +v 0.052200 -0.040920 0.112548 +v 0.055200 -0.034931 0.165521 +v 0.055200 -0.034945 0.104474 +v 0.055200 -0.043965 0.118282 +v 0.055700 -0.044332 0.135000 +v 0.055200 -0.046474 0.140788 +v 0.055200 -0.040920 0.157452 +v 0.054200 -0.034931 0.104479 +v 0.054200 -0.034945 0.165526 +v 0.054200 -0.043965 0.151718 +v 0.054200 -0.046474 0.129212 +v 0.054200 -0.040920 0.112548 +v 0.057200 -0.034931 0.165521 +v 0.057200 -0.034945 0.104474 +v 0.057200 -0.043965 0.118282 +v 0.057700 -0.044332 0.135000 +v 0.057200 -0.046474 0.140788 +v 0.057200 -0.040920 0.157452 +v 0.056200 -0.034931 0.104479 +v 0.056200 -0.034945 0.165526 +v 0.056200 -0.043965 0.151718 +v 0.056200 -0.046474 0.129212 +v 0.056200 -0.040920 0.112549 +v 0.059200 -0.034931 0.165521 +v 0.059200 -0.034949 0.104480 +v 0.059200 -0.043965 0.118282 +v 0.059700 -0.044332 0.135000 +v 0.059200 -0.046474 0.140788 +v 0.059200 -0.040920 0.157452 +v 0.058200 -0.034931 0.104479 +v 0.058200 -0.034945 0.165526 +v 0.058200 -0.043965 0.151718 +v 0.058200 -0.046474 0.129212 +v 0.058200 -0.040920 0.112548 +v 0.061200 -0.034931 0.165521 +v 0.061200 -0.034945 0.104474 +v 0.061200 -0.043965 0.118282 +v 0.061700 -0.044332 0.135000 +v 0.061200 -0.046474 0.140788 +v 0.061200 -0.040920 0.157452 +v 0.060200 -0.034931 0.104479 +v 0.060200 -0.034949 0.165520 +v 0.060200 -0.043965 0.151718 +v 0.060200 -0.046474 0.129212 +v 0.060200 -0.040920 0.112549 +v 0.063200 -0.034931 0.165521 +v 0.063200 -0.034945 0.104474 +v 0.063200 -0.043965 0.118282 +v 0.063200 -0.046474 0.140788 +v 0.063200 -0.040920 0.157451 +v 0.062200 -0.034931 0.104479 +v 0.062200 -0.034945 0.165526 +v 0.062200 -0.043965 0.151718 +v 0.062200 -0.046474 0.129212 +v 0.062200 -0.040920 0.112548 +v 0.070708 -0.043670 0.150654 +v 0.070700 -0.019165 0.197292 +v 0.070703 -0.044451 0.120976 +v 0.070724 -0.046326 0.138859 +v 0.102810 0.026972 0.121596 +v 0.096804 0.037071 0.109457 +v 0.096314 0.043721 0.122692 +v 0.097964 0.040692 0.125911 +v 0.096591 0.044039 0.128188 +v 0.099276 0.037943 0.128548 +v 0.097502 0.042340 0.131800 +v 0.096014 0.045217 0.137552 +v 0.099996 0.035582 0.143826 +v 0.098887 0.039184 0.131374 +v 0.095987 0.042547 0.150207 +v 0.100587 0.025528 0.158177 +v 0.096092 0.035550 0.161999 +v 0.097695 0.027535 0.165711 +v 0.087569 0.022005 0.189911 +v 0.095994 0.015611 0.177384 +v 0.092750 0.028751 0.177013 +v 0.089746 0.010205 0.190210 +v 0.082805 0.017257 0.197974 +v 0.082040 0.013002 0.199856 +v 0.083818 -0.000029 0.199217 +v 0.086078 0.003158 0.196100 +v 0.086212 -0.003157 0.195916 +v 0.082620 -0.011230 0.199704 +v 0.092152 -0.026085 0.180764 +v 0.092915 -0.028944 0.176518 +v 0.096608 -0.027264 0.168800 +v 0.100656 -0.015720 0.165926 +v 0.097481 -0.029720 0.163925 +v 0.096355 -0.034651 0.162244 +v 0.097751 -0.041858 0.131904 +v 0.095975 -0.044686 0.142224 +v 0.096718 -0.044139 0.129458 +v 0.101716 -0.030140 0.146081 +v 0.099024 -0.038827 0.131145 +v 0.096425 -0.042497 0.119109 +v 0.100968 -0.030885 0.118574 +v 0.099127 -0.038338 0.127178 +v 0.097130 -0.042648 0.126385 +v 0.096890 -0.036167 0.108595 +v 0.096877 -0.025047 0.097106 +v 0.101339 -0.010203 0.100648 +v 0.097271 -0.027132 0.099770 +v 0.097187 -0.011937 0.091333 +v 0.097323 -0.000366 0.089905 +v 0.100900 0.012677 0.100455 +v 0.097277 0.009567 0.090885 +v 0.097080 0.018353 0.093565 +v 0.097080 0.026452 0.098686 +v 0.093965 -0.003504 0.184238 +v 0.088444 0.000062 0.192832 +v 0.083324 -0.018119 0.197174 +v 0.100891 0.007767 0.167778 +v 0.104724 0.000042 0.155064 +v 0.098442 0.029250 0.105518 +v 0.104605 0.007745 0.112950 +v 0.104400 -0.013487 0.114902 +v 0.098858 -0.029039 0.106368 +v 0.104337 0.012880 0.152295 +v 0.105127 -0.010273 0.149809 +v 0.095852 -0.039558 0.157216 +v 0.104047 0.023036 0.140364 +v 0.106523 0.005974 0.125559 +v 0.106834 0.002584 0.136625 +v 0.105722 -0.016354 0.131185 +v 0.094374 0.038681 0.160721 +v 0.083218 0.020430 0.195545 +v 0.070863 0.030862 0.175095 +v 0.090339 0.029896 0.177781 +v 0.094008 0.042790 0.152967 +v 0.094002 0.046009 0.142486 +v 0.094383 0.046144 0.129765 +v 0.094244 0.044478 0.121482 +v 0.094569 0.039586 0.110463 +v 0.095057 0.025737 0.096374 +v 0.095023 0.018726 0.092482 +v 0.095139 0.010444 0.089678 +v 0.095280 -0.001748 0.088471 +v 0.095207 -0.015125 0.090974 +v 0.094760 -0.025354 0.096012 +v 0.080938 -0.013924 0.200388 +v 0.080401 0.014311 0.200330 +v 0.081689 0.018912 0.197634 +v 0.077700 0.003234 0.195300 +v 0.077700 -0.000264 0.192984 +v 0.077700 -0.000716 0.199262 +v 0.077700 -0.002899 0.194955 +v 0.077700 0.044105 0.129657 +v 0.077700 0.040056 0.132094 +v 0.077700 0.038104 0.127418 +v 0.077700 0.042335 0.126263 +v 0.070931 0.030332 0.104658 +v 0.095995 0.031257 0.105139 +v 0.096055 0.029684 0.103341 +v 0.091813 0.030716 0.173330 +v 0.093592 0.029421 0.168951 +v 0.070899 0.029183 0.167471 +v 0.094638 0.029728 0.166576 +v 0.070860 0.031520 0.164721 +v 0.095332 0.031739 0.164574 +v 0.095619 0.035519 0.106672 +v 0.095253 0.028532 0.099528 +v 0.093871 0.035346 0.163677 +v 0.095974 0.028543 0.167656 +v 0.093768 0.029219 0.173529 +v 0.094160 -0.043327 0.151927 +v 0.093775 -0.038155 0.161587 +v 0.071183 -0.038644 0.161238 +v 0.082150 -0.019554 0.197031 +v 0.090569 -0.030053 0.177461 +v 0.095052 -0.038413 0.109093 +v 0.094344 -0.042543 0.116157 +v 0.094759 -0.045247 0.124783 +v 0.094104 -0.046538 0.137600 +v 0.077700 -0.043816 0.127712 +v 0.077700 -0.040210 0.125974 +v 0.077700 -0.037984 0.128736 +v 0.077700 -0.039601 0.131778 +v 0.077700 -0.043194 0.131104 +v 0.096172 -0.029751 0.103551 +v 0.095817 -0.031291 0.105132 +v 0.095390 -0.031473 0.164688 +v 0.094956 -0.030046 0.166090 +v 0.094383 -0.029230 0.168599 +v 0.095150 -0.036095 0.106869 +v 0.095132 -0.028519 0.099465 +v 0.092107 -0.030581 0.172932 +v 0.094138 -0.034570 0.163940 +v 0.097681 -0.030135 0.105417 +v 0.064187 -0.011744 0.179530 +v 0.063699 -0.010897 0.177878 +v 0.063487 -0.010965 0.181488 +v 0.064187 -0.009589 0.179309 +v 0.064187 -0.008577 0.180901 +v 0.063703 -0.010607 0.181537 +v 0.064187 -0.006784 0.178941 +v 0.064187 -0.007540 0.179793 +v 0.064187 -0.010409 0.177903 +v 0.064187 -0.012669 0.180742 +v 0.064187 -0.014954 0.182616 +v 0.064187 -0.013464 0.179093 +v 0.063712 -0.015446 0.181303 +v 0.063687 -0.014572 0.178691 +v 0.064187 -0.019158 0.185463 +v 0.064187 -0.002550 0.186172 +v 0.064187 -0.006501 0.182946 +v 0.064187 -0.018382 0.189552 +v 0.063701 -0.019646 0.190808 +v 0.064187 -0.015686 0.196614 +v 0.064187 -0.003977 0.188049 +v 0.064187 -0.012374 0.195582 +v 0.064187 -0.005822 0.193427 +v 0.064187 -0.008391 0.197395 +v 0.064187 -0.003072 0.193030 +v 0.063187 -0.013052 0.178782 +v 0.063187 -0.011763 0.180075 +v 0.063187 -0.013120 0.180607 +v 0.063187 -0.007804 0.180133 +v 0.063187 -0.005323 0.182248 +v 0.063187 -0.006843 0.178832 +v 0.063187 -0.009555 0.180637 +v 0.063187 -0.008940 0.178818 +v 0.063187 -0.018700 0.184311 +v 0.063187 -0.002099 0.189716 +v 0.063187 -0.016036 0.183511 +v 0.063187 -0.018037 0.188401 +v 0.063187 -0.015062 0.194649 +v 0.063187 -0.015947 0.196450 +v 0.063187 -0.006804 0.197054 +v 0.063187 -0.007740 0.194795 +v 0.063187 -0.003635 0.188740 +v 0.080602 -0.041587 0.131812 +v 0.080677 -0.043663 0.129562 +v 0.080641 -0.038934 0.130807 +v 0.080700 -0.039514 0.128890 +v 0.080643 -0.042870 0.126957 +v 0.080625 -0.038374 0.127753 +v 0.080580 -0.040696 0.126259 +v 0.069779 -0.040780 0.130516 +v 0.069845 -0.039541 0.128785 +v 0.069800 -0.041512 0.127592 +v 0.077601 -0.042697 0.128903 +v 0.077608 -0.040860 0.127332 +v 0.077595 -0.039265 0.129213 +v 0.077611 -0.041250 0.130648 +v 0.070176 -0.042581 0.129252 +v 0.077749 -0.038009 0.129317 +v 0.077775 -0.043256 0.130644 +v 0.077778 -0.043538 0.127624 +v 0.077773 -0.040826 0.131815 +v 0.077759 -0.040456 0.126199 +v 0.078700 -0.041890 0.130170 +v 0.078700 -0.040110 0.127830 +v 0.075900 -0.032896 0.100010 +v 0.075830 -0.033716 0.098159 +v 0.075848 -0.029650 0.100630 +v 0.075864 -0.037056 0.101939 +v 0.075900 -0.034924 0.102351 +v 0.075864 -0.032400 0.105499 +v 0.075900 -0.031882 0.102937 +v 0.041996 -0.034608 0.103179 +v 0.042136 -0.031927 0.103298 +v 0.042012 -0.031441 0.101191 +v 0.041996 -0.034668 0.100440 +v 0.071834 -0.033413 0.099633 +v 0.042387 -0.032727 0.099713 +v 0.071827 -0.035329 0.101052 +v 0.071803 -0.033992 0.103948 +v 0.071832 -0.031448 0.102923 +v 0.071827 -0.031340 0.100620 +v 0.071961 -0.035064 0.098690 +v 0.071963 -0.036758 0.101502 +v 0.071951 -0.030901 0.098906 +v 0.071963 -0.029809 0.102638 +v 0.071957 -0.032247 0.105261 +v 0.071963 -0.035702 0.104296 +v 0.072900 -0.034712 0.102773 +v 0.072900 -0.031623 0.102542 +v 0.072900 -0.033368 0.099983 +v 0.064187 0.009753 0.180200 +v 0.064187 0.009194 0.178893 +v 0.064187 0.010601 0.181510 +v 0.064187 0.015979 0.181621 +v 0.064187 0.013224 0.180614 +v 0.063687 0.014573 0.178691 +v 0.064187 0.013218 0.179021 +v 0.063675 0.010897 0.177878 +v 0.064187 0.006719 0.182969 +v 0.064187 0.011654 0.179568 +v 0.064187 0.007770 0.180233 +v 0.064187 0.012192 0.181448 +v 0.063674 0.006070 0.181674 +v 0.064187 0.006910 0.178735 +v 0.064187 0.002411 0.185947 +v 0.064187 0.019795 0.187881 +v 0.064187 0.003635 0.188740 +v 0.063582 0.003115 0.192981 +v 0.064187 0.007740 0.194795 +v 0.064187 0.017871 0.186302 +v 0.064187 0.006931 0.196798 +v 0.064187 0.015470 0.194469 +v 0.064187 0.014255 0.197316 +v 0.063616 0.019142 0.192418 +v 0.063187 0.006784 0.178941 +v 0.063187 0.008152 0.179063 +v 0.063187 0.010409 0.177903 +v 0.063187 0.006798 0.182636 +v 0.063187 0.009767 0.180124 +v 0.063187 0.008350 0.180769 +v 0.063187 0.013749 0.179456 +v 0.063187 0.011677 0.179418 +v 0.063187 0.012514 0.180960 +v 0.063187 0.002769 0.185241 +v 0.063187 0.019263 0.185424 +v 0.063187 0.003977 0.188049 +v 0.063187 0.005822 0.193427 +v 0.063187 0.008391 0.197395 +v 0.063187 0.012807 0.195561 +v 0.063187 0.014796 0.196946 +v 0.063187 0.014954 0.182616 +v 0.063187 0.018344 0.189107 +v 0.010008 0.046890 0.168075 +v 0.009743 0.044418 0.168156 +v 0.013084 0.042431 0.168058 +v 0.005035 0.042301 0.168156 +v 0.002987 0.042193 0.168055 +v 0.004351 0.038322 0.168058 +v 0.009222 0.039282 0.168156 +v 0.011804 0.038666 0.168051 +v 0.008608 0.036981 0.168056 +v 0.004490 0.045746 0.168064 +v 0.005119 0.041800 0.142200 +v 0.010822 0.040513 0.142402 +v 0.006384 0.039289 0.142355 +v 0.009587 0.044627 0.142316 +v 0.006192 0.044300 0.142317 +v 0.010984 0.040336 0.162061 +v 0.006677 0.039035 0.162086 +v 0.004746 0.042819 0.162070 +v 0.009120 0.045228 0.162061 +v 0.009594 0.037099 0.162228 +v 0.013148 0.041167 0.162221 +v 0.006768 0.047003 0.162225 +v 0.003458 0.044209 0.162231 +v 0.011316 0.045871 0.162228 +v 0.005645 0.037577 0.162228 +v 0.003213 0.040247 0.162228 +v 0.005685 0.040123 0.163156 +v 0.005902 0.043983 0.163156 +v 0.010098 0.040017 0.163156 +v 0.010315 0.043877 0.163156 +v 0.005217 -0.033156 0.091934 +v 0.003511 -0.033056 0.090675 +v 0.006859 -0.033118 0.088048 +v 0.003246 -0.033061 0.094999 +v 0.007332 -0.033156 0.095808 +v 0.010783 -0.033156 0.094067 +v 0.006997 -0.033054 0.098025 +v 0.011624 -0.033058 0.096671 +v 0.010666 -0.033061 0.088768 +v 0.013020 -0.033061 0.091819 +v 0.007866 -0.007222 0.090011 +v 0.005307 -0.007258 0.091729 +v 0.006435 -0.007400 0.095780 +v 0.009985 -0.007291 0.095151 +v 0.010893 -0.007423 0.091899 +v 0.004841 -0.027061 0.094301 +v 0.008391 -0.027090 0.096134 +v 0.010830 -0.027088 0.094491 +v 0.010438 -0.027078 0.090779 +v 0.006511 -0.027086 0.090114 +v 0.002968 -0.027228 0.092186 +v 0.004155 -0.027228 0.096347 +v 0.013216 -0.027215 0.093844 +v 0.010136 -0.027217 0.088166 +v 0.005121 -0.027227 0.088852 +v 0.008874 -0.027223 0.098142 +v 0.006257 -0.028156 0.095418 +v 0.010965 -0.028156 0.093301 +v 0.006778 -0.028156 0.090282 +v 0.009988 0.039217 0.162156 +v 0.010974 0.040311 0.160556 +v 0.008512 0.038736 0.160556 +v 0.010820 0.044407 0.162156 +v 0.010680 0.044188 0.160556 +v 0.005626 0.044848 0.160556 +v 0.006313 0.044897 0.162156 +v 0.004494 0.041444 0.162156 +v 0.005863 0.039204 0.160556 +v 0.007866 0.038590 0.162156 +v 0.006852 0.036991 0.162156 +v 0.007887 0.036839 0.160556 +v 0.003587 0.039407 0.160556 +v 0.003342 0.040047 0.162156 +v 0.003583 0.044930 0.160556 +v 0.003394 0.044321 0.162156 +v 0.007805 0.047198 0.162156 +v 0.009206 0.047060 0.160556 +v 0.012065 0.045050 0.162156 +v 0.012857 0.043615 0.160556 +v 0.012684 0.039287 0.162156 +v 0.012125 0.038904 0.160556 +v 0.008754 0.037067 0.161138 +v 0.034240 0.045439 0.162156 +v 0.032390 0.045164 0.160556 +v 0.035914 0.044693 0.160556 +v 0.030480 0.042461 0.162156 +v 0.030668 0.041229 0.160556 +v 0.033791 0.038353 0.162156 +v 0.034172 0.038404 0.160556 +v 0.037439 0.041619 0.162156 +v 0.037482 0.042507 0.160556 +v 0.036177 0.044486 0.162156 +v 0.037379 0.045740 0.162156 +v 0.037874 0.045448 0.160556 +v 0.039157 0.041890 0.162156 +v 0.038819 0.040275 0.160556 +v 0.037202 0.038094 0.162156 +v 0.035092 0.036914 0.160556 +v 0.033091 0.036923 0.162156 +v 0.030734 0.038148 0.160556 +v 0.029206 0.040097 0.162156 +v 0.028890 0.041717 0.160556 +v 0.029631 0.044596 0.162156 +v 0.030656 0.045875 0.160556 +v 0.033128 0.047043 0.162156 +v 0.035706 0.046848 0.160556 +v 0.036909 0.046108 0.162156 +v 0.008499 -0.026090 0.096244 +v 0.011045 -0.025556 0.094642 +v 0.010894 -0.027156 0.094895 +v 0.010444 -0.027156 0.090425 +v 0.010217 -0.025556 0.090228 +v 0.005958 -0.027156 0.090207 +v 0.005728 -0.025556 0.090391 +v 0.004697 -0.027156 0.093885 +v 0.004717 -0.025556 0.093524 +v 0.007093 -0.025556 0.096318 +v 0.008308 -0.027156 0.097025 +v 0.006499 -0.025556 0.097934 +v 0.004971 -0.027156 0.097126 +v 0.003069 -0.025556 0.094231 +v 0.002785 -0.027156 0.092054 +v 0.003831 -0.025556 0.090031 +v 0.006380 -0.027156 0.088183 +v 0.007297 -0.025556 0.087998 +v 0.011813 -0.027156 0.089240 +v 0.011417 -0.025556 0.089137 +v 0.013071 -0.025556 0.093342 +v 0.012734 -0.027156 0.094946 +v 0.010043 -0.025556 0.097791 +v 0.009235 -0.027156 0.097947 +v 0.034807 -0.025556 0.089698 +v 0.031946 -0.027156 0.089980 +v 0.035914 -0.027156 0.090307 +v 0.030362 -0.025556 0.092287 +v 0.030967 -0.027156 0.094580 +v 0.033580 -0.025556 0.096478 +v 0.033946 -0.027156 0.096384 +v 0.036982 -0.027156 0.094675 +v 0.036987 -0.025556 0.094591 +v 0.036637 -0.025556 0.090809 +v 0.036695 -0.027156 0.090968 +v 0.037282 -0.026356 0.089230 +v 0.039248 -0.025556 0.093113 +v 0.039125 -0.027156 0.092417 +v 0.037371 -0.027156 0.096851 +v 0.036160 -0.025556 0.097684 +v 0.033527 -0.027156 0.098029 +v 0.030442 -0.025556 0.096928 +v 0.029972 -0.027156 0.096157 +v 0.029233 -0.027156 0.090684 +v 0.029085 -0.025556 0.091574 +v 0.032845 -0.025556 0.087880 +v 0.035025 -0.027156 0.087921 +v 0.036911 -0.025556 0.088944 +v 0.047775 0.047684 0.160484 +v 0.037345 0.046766 0.160731 +v 0.039761 0.043038 0.161938 +v 0.047739 0.038299 0.163299 +v 0.038485 0.038674 0.163165 +v 0.036939 -0.025700 0.087898 +v 0.047772 -0.025466 0.087296 +v 0.039499 -0.027807 0.095045 +v 0.047710 -0.028475 0.097018 +v 0.006981 0.047544 0.160615 +v 0.000500 0.047486 0.160690 +v 0.003958 0.045925 0.160790 +v 0.010661 0.046962 0.160763 +v 0.013706 0.043171 0.161902 +v 0.030968 0.047031 0.160719 +v 0.039453 0.007729 0.171856 +v 0.035170 0.036514 0.163756 +v 0.030757 0.037318 0.163532 +v 0.002339 0.041850 0.162270 +v 0.000075 0.007513 0.171722 +v 0.011384 0.037386 0.163513 +v 0.005437 0.036783 0.163681 +v 0.028339 0.041850 0.162270 +v 0.042209 -0.010781 0.089677 +v 0.047782 0.005323 0.088486 +v 0.047795 -0.011431 0.089677 +v 0.042127 0.003482 0.088516 +v 0.042262 0.019425 0.092708 +v 0.047836 0.020810 0.093539 +v 0.047776 0.029323 0.098640 +v 0.042172 0.029278 0.098656 +v 0.042154 -0.036314 0.164337 +v 0.047804 -0.044345 0.150073 +v 0.047799 -0.036302 0.164429 +v 0.042210 -0.042660 0.153561 +v 0.042119 -0.046268 0.139403 +v 0.047886 -0.046400 0.131605 +v 0.042232 -0.044508 0.120390 +v 0.047837 -0.042646 0.116468 +v 0.047804 -0.036286 0.105544 +v 0.042167 -0.036290 0.105607 +v 0.000214 -0.025489 0.087324 +v 0.004894 -0.025728 0.088011 +v 0.002339 -0.027186 0.092850 +v 0.031129 -0.025766 0.088065 +v 0.028339 -0.027186 0.092850 +v 0.011282 -0.025765 0.088197 +v 0.000149 -0.037526 0.130832 +v 0.004616 -0.028513 0.097614 +v 0.010563 -0.028681 0.098217 +v 0.039423 -0.037656 0.130698 +v 0.030616 -0.028513 0.097614 +v 0.035170 -0.028756 0.098486 +v 0.013661 -0.027270 0.093150 +v 0.042174 0.029453 0.171275 +v 0.047736 0.017036 0.178458 +v 0.047820 0.029395 0.171296 +v 0.042210 0.018560 0.177660 +v 0.042112 0.001998 0.181578 +v 0.047926 -0.001422 0.181675 +v 0.042210 -0.014802 0.179105 +v 0.047837 -0.018531 0.177646 +v 0.042170 -0.029460 0.171296 +v 0.047798 -0.028673 0.171647 +v 0.004024 -0.014080 0.099879 +v 0.003995 -0.005170 0.097588 +v 0.037986 -0.013736 0.099866 +v 0.038001 -0.005152 0.097588 +v 0.004027 0.007615 0.098014 +v 0.037976 0.007664 0.098025 +v 0.004003 0.017914 0.101844 +v 0.037978 0.017889 0.101838 +v 0.004021 0.025512 0.107282 +v 0.037897 0.025028 0.106827 +v 0.004027 0.032378 0.115570 +v 0.037949 0.032463 0.115752 +v 0.004024 0.036977 0.127348 +v 0.037966 0.036578 0.125955 +v 0.037972 0.037688 0.135547 +v 0.004000 0.037417 0.140123 +v 0.037959 0.036654 0.143439 +v 0.004046 0.035124 0.148676 +v 0.037985 0.035134 0.148745 +v 0.039188 -0.000444 0.172749 +v 0.000361 -0.005019 0.172424 +v 0.038886 -0.010533 0.171139 +v 0.039943 -0.017813 0.168370 +v 0.000171 -0.019071 0.167356 +v 0.039493 -0.025773 0.162696 +v 0.000085 -0.027886 0.159851 +v 0.039463 -0.031529 0.155637 +v 0.000243 -0.035094 0.148854 +v 0.040059 -0.035210 0.148997 +v 0.039846 -0.037647 0.139239 +v 0.042146 0.036262 0.105552 +v 0.042210 0.042563 0.116238 +v 0.047811 0.036306 0.105545 +v 0.047880 0.044165 0.120526 +v 0.042122 0.046539 0.132391 +v 0.047791 0.046505 0.133988 +v 0.047775 0.045332 0.146189 +v 0.042332 0.045526 0.147845 +v 0.041894 0.015783 0.096311 +v 0.041904 0.027016 0.103369 +v 0.042179 0.034594 0.098482 +v 0.042149 0.036596 0.101269 +v 0.041895 0.034899 0.112226 +v 0.041906 -0.013983 0.095733 +v 0.042059 -0.014328 0.088680 +v 0.041906 0.041831 0.137191 +v 0.041903 0.039263 0.148980 +v 0.041893 0.039725 0.122663 +v 0.041894 -0.002356 0.093165 +v 0.047934 0.028962 0.101311 +v 0.047838 0.034074 0.098443 +v 0.047762 0.036629 0.100720 +v 0.046038 0.032247 0.166729 +v 0.046038 0.032188 0.169963 +v 0.046038 0.035080 0.167670 +v 0.041874 -0.039484 0.144586 +v 0.041793 -0.030975 0.160256 +v 0.041911 0.034799 0.167190 +v 0.042110 0.034404 0.171562 +v 0.041997 0.036413 0.166489 +v 0.042016 0.033022 0.170279 +v 0.042034 -0.034683 0.102888 +v 0.042255 -0.036630 0.100383 +v 0.041833 -0.017995 0.171485 +v 0.042084 -0.033645 0.099902 +v 0.042146 -0.034169 0.098484 +v 0.042120 -0.036563 0.169036 +v 0.042202 -0.034278 0.171611 +v 0.041774 -0.039376 0.128342 +v 0.041794 0.005909 0.174670 +v 0.033145 -0.025557 0.098932 +v 0.009016 -0.025557 0.098941 +v 0.002576 -0.025556 0.095110 +v 0.047791 -0.016085 0.087308 +v 0.000185 -0.015863 0.087330 +v 0.000434 -0.013862 0.096227 +v 0.000361 -0.000869 0.093821 +v 0.000342 0.010927 0.095427 +v 0.000297 0.021709 0.100031 +v 0.000423 0.035024 0.112956 +v 0.000301 0.040109 0.126289 +v 0.000374 0.040919 0.139211 +v 0.000424 0.038759 0.148909 +v 0.013601 -0.025556 0.093835 +v 0.039487 -0.025557 0.094932 +v 0.028177 -0.025556 0.093162 +v 0.037748 -0.015294 0.098967 +v 0.040544 -0.015545 0.087658 +v 0.004453 -0.015442 0.098608 +v 0.000400 -0.015356 0.095159 +v 0.040950 -0.015362 0.095358 +v 0.031567 0.036802 0.160557 +v 0.028399 0.041165 0.160556 +v 0.037399 0.037348 0.160556 +v 0.039563 0.041513 0.160556 +v 0.047773 0.047720 0.151126 +v 0.000135 0.047784 0.160100 +v 0.000182 0.047652 0.150856 +v 0.002399 0.041165 0.160556 +v 0.005146 0.037103 0.160556 +v 0.011243 0.037075 0.160556 +v 0.013601 0.042835 0.160556 +v 0.004182 0.035917 0.150228 +v 0.041067 0.047207 0.150418 +v 0.037686 0.036042 0.150308 +v 0.000355 0.039714 0.150347 +v 0.041046 0.039327 0.150278 +v 0.047820 -0.034339 0.171531 +v 0.047758 -0.036652 0.169005 +v 0.047848 0.039751 0.114820 +v 0.047934 -0.028169 0.169263 +v 0.047862 -0.015725 0.176561 +v 0.047883 -0.036974 0.159452 +v 0.047812 -0.042791 0.146995 +v 0.047861 -0.044352 0.134592 +v 0.047852 -0.002440 0.179180 +v 0.047907 0.038893 0.156721 +v 0.047857 -0.042158 0.121337 +v 0.047856 -0.036084 0.109015 +v 0.047921 0.026747 0.170511 +v 0.047823 0.011644 0.177893 +v 0.047779 -0.036653 0.101413 +v 0.047696 -0.034913 0.098486 +v 0.042028 -0.031750 0.098599 +v 0.042494 0.036313 0.170097 +v 0.047757 0.036575 0.169472 +v 0.047702 0.033977 0.171692 +v 0.044260 -0.031892 0.103099 +v 0.044260 -0.034806 0.102741 +v 0.041247 -0.031518 0.102699 +v 0.044260 -0.031939 0.100618 +v 0.044259 -0.034034 0.100138 +v 0.041509 0.031721 0.167096 +v 0.040739 -0.029528 0.097873 +v 0.041081 -0.008081 0.173098 +v 0.040791 0.037047 0.164655 +v 0.047730 -0.030808 0.098468 +v 0.047690 0.036577 0.165601 +v 0.029123 -0.033057 0.091500 +v 0.031121 -0.033156 0.092228 +v 0.029528 -0.033056 0.095325 +v 0.038906 -0.033071 0.091301 +v 0.036108 -0.033156 0.090893 +v 0.035092 -0.033050 0.087992 +v 0.031420 -0.033056 0.088698 +v 0.034771 -0.033156 0.095879 +v 0.037821 -0.033061 0.096464 +v 0.032896 -0.033058 0.098063 +v 0.034516 -0.007204 0.090193 +v 0.031627 -0.007286 0.091200 +v 0.031448 -0.007322 0.094817 +v 0.035663 -0.007439 0.095678 +v 0.036847 -0.007321 0.091805 +v 0.035260 -0.027061 0.089824 +v 0.030654 -0.027061 0.092310 +v 0.033331 -0.027080 0.096231 +v 0.037064 -0.027078 0.094220 +v 0.032175 -0.027227 0.088292 +v 0.036143 -0.027228 0.088375 +v 0.030492 -0.027215 0.096951 +v 0.036573 -0.027221 0.097536 +v 0.039182 -0.027223 0.092406 +v 0.029115 -0.027228 0.091358 +v 0.031019 -0.028156 0.093009 +v 0.033627 -0.028156 0.095863 +v 0.034373 -0.028156 0.090137 +v 0.036981 -0.028156 0.092991 +v 0.035498 0.039423 0.168156 +v 0.031867 0.037396 0.168051 +v 0.037052 0.037684 0.168075 +v 0.031019 0.041991 0.168156 +v 0.028984 0.040804 0.168061 +v 0.034114 0.047217 0.168067 +v 0.029948 0.045028 0.168051 +v 0.035482 0.044586 0.168156 +v 0.038968 0.043720 0.168078 +v 0.034161 0.044879 0.142216 +v 0.031651 0.040029 0.142324 +v 0.031545 0.043799 0.142399 +v 0.035295 0.039268 0.142350 +v 0.037007 0.042837 0.142332 +v 0.033810 0.038589 0.162061 +v 0.030755 0.041891 0.162086 +v 0.032548 0.044851 0.162088 +v 0.035478 0.044791 0.162090 +v 0.037293 0.041820 0.162078 +v 0.029561 0.039263 0.162221 +v 0.029456 0.044310 0.162228 +v 0.037654 0.045555 0.162228 +v 0.039071 0.041087 0.162225 +v 0.035172 0.036847 0.162217 +v 0.033227 0.047094 0.162225 +v 0.034373 0.044863 0.163156 +v 0.036879 0.041228 0.163156 +v 0.031121 0.042772 0.163156 +v 0.033627 0.039137 0.163156 +v 0.047917 -0.013598 0.092670 +v 0.047825 0.044088 0.130254 +v 0.047841 0.003938 0.090623 +v 0.047944 -0.027395 0.100063 +v 0.075900 0.034990 -0.102104 +v 0.075823 0.036693 -0.102523 +v 0.075830 0.035687 -0.099078 +v 0.075837 0.034040 -0.105374 +v 0.075900 0.032648 -0.100076 +v 0.075823 0.032160 -0.098392 +v 0.075825 0.029811 -0.100695 +v 0.075900 0.032063 -0.103118 +v 0.075823 0.030431 -0.103930 +v 0.041979 0.031870 -0.103316 +v 0.041982 0.033966 -0.099972 +v 0.042064 0.034464 -0.103234 +v 0.042035 0.031562 -0.100797 +v 0.071824 0.035111 -0.100577 +v 0.042379 0.035341 -0.101352 +v 0.071830 0.032826 -0.099659 +v 0.071823 0.031047 -0.101357 +v 0.071834 0.032000 -0.103516 +v 0.071819 0.034607 -0.103562 +v 0.071929 0.030272 -0.099351 +v 0.071951 0.035567 -0.098906 +v 0.071951 0.036455 -0.103567 +v 0.071965 0.033273 -0.105262 +v 0.071961 0.030523 -0.104103 +v 0.072900 0.032226 -0.100288 +v 0.072900 0.032458 -0.103377 +v 0.072900 0.035017 -0.101632 +v 0.075900 0.031544 -0.168820 +v 0.075849 0.031219 -0.171408 +v 0.075900 0.034586 -0.169405 +v 0.075823 0.035398 -0.171037 +v 0.075837 0.036842 -0.167428 +v 0.075837 0.033066 -0.164541 +v 0.075900 0.033572 -0.166478 +v 0.075825 0.029811 -0.167163 +v 0.041965 0.031838 -0.166990 +v 0.042108 0.034448 -0.166509 +v 0.042030 0.034631 -0.169643 +v 0.042145 0.031751 -0.169757 +v 0.071787 0.032517 -0.170507 +v 0.071824 0.035481 -0.168381 +v 0.071834 0.034145 -0.166297 +v 0.071811 0.031410 -0.166831 +v 0.071961 0.036751 -0.167566 +v 0.071951 0.035123 -0.171404 +v 0.071942 0.030189 -0.170430 +v 0.071951 0.030823 -0.165440 +v 0.071963 0.034687 -0.165013 +v 0.072900 0.034845 -0.169010 +v 0.072900 0.033100 -0.166451 +v 0.072900 0.031756 -0.169242 +v 0.080714 -0.001632 -0.194015 +v 0.080626 -0.002808 -0.196091 +v 0.080724 -0.001420 -0.198144 +v 0.080601 0.000677 -0.193238 +v 0.080725 0.002405 -0.195153 +v 0.080592 0.000578 -0.198725 +v 0.080626 0.002569 -0.197136 +v 0.065840 0.000270 -0.197387 +v 0.065887 -0.001337 -0.196590 +v 0.065809 -0.000432 -0.194550 +v 0.065909 0.001489 -0.195930 +v 0.077630 -0.001546 -0.195346 +v 0.077622 -0.000819 -0.197517 +v 0.077627 0.001510 -0.196798 +v 0.077614 0.000692 -0.194388 +v 0.077724 0.001921 -0.193797 +v 0.077788 0.002568 -0.197128 +v 0.077759 -0.002260 -0.194092 +v 0.077753 0.000354 -0.198780 +v 0.077764 -0.002262 -0.197651 +v 0.078700 -0.000503 -0.197403 +v 0.078700 0.001466 -0.195734 +v 0.078700 -0.000964 -0.194863 +v 0.070700 -0.031491 -0.100173 +v 0.071900 -0.031561 -0.100079 +v 0.070700 -0.035523 -0.100533 +v 0.071900 -0.035038 -0.100216 +v 0.071900 -0.034662 -0.103844 +v 0.070700 -0.033393 -0.104244 +v 0.071900 -0.031185 -0.102849 +v 0.070700 -0.030934 -0.102011 +v 0.071194 -0.029681 -0.101804 +v 0.071900 -0.031163 -0.104984 +v 0.070700 -0.031460 -0.105111 +v 0.071900 -0.035578 -0.104560 +v 0.070700 -0.036424 -0.103881 +v 0.071900 -0.036724 -0.100091 +v 0.070700 -0.036152 -0.099625 +v 0.070700 -0.032564 -0.098079 +v 0.071900 -0.033072 -0.098198 +v 0.071900 -0.030042 -0.099968 +v 0.070700 -0.029637 -0.101147 +v 0.070700 0.034309 -0.103803 +v 0.071900 0.033485 -0.104019 +v 0.071900 0.035644 -0.102183 +v 0.070700 0.035311 -0.100268 +v 0.071900 0.034101 -0.099642 +v 0.070700 0.031533 -0.100104 +v 0.071900 0.031592 -0.100088 +v 0.071900 0.031484 -0.103435 +v 0.070700 0.031700 -0.103580 +v 0.071036 0.032924 -0.105375 +v 0.071900 0.030606 -0.104339 +v 0.070700 0.029376 -0.102080 +v 0.071900 0.029770 -0.100531 +v 0.070700 0.032046 -0.098318 +v 0.071900 0.032299 -0.098296 +v 0.071900 0.035930 -0.099163 +v 0.070700 0.035210 -0.098764 +v 0.070700 0.036911 -0.101680 +v 0.071900 0.036634 -0.103006 +v 0.070700 0.034468 -0.105236 +v 0.071900 0.034093 -0.105279 +v 0.075900 -0.033820 -0.166544 +v 0.075822 -0.036709 -0.167791 +v 0.075900 -0.034405 -0.169586 +v 0.075830 -0.035687 -0.170922 +v 0.075848 -0.034370 -0.164650 +v 0.075825 -0.031854 -0.171544 +v 0.075864 -0.029501 -0.167400 +v 0.075900 -0.031478 -0.168572 +v 0.042096 -0.032070 -0.166482 +v 0.042066 -0.031863 -0.169771 +v 0.042001 -0.034958 -0.169270 +v 0.042066 -0.034628 -0.166952 +v 0.071811 -0.035481 -0.168730 +v 0.071787 -0.031954 -0.170244 +v 0.071824 -0.031677 -0.166607 +v 0.071834 -0.034132 -0.166291 +v 0.071957 -0.033501 -0.171856 +v 0.071961 -0.036581 -0.169502 +v 0.071965 -0.036281 -0.166520 +v 0.071951 -0.033285 -0.164544 +v 0.071961 -0.029887 -0.166966 +v 0.071963 -0.030314 -0.170225 +v 0.072900 -0.031603 -0.168906 +v 0.072900 -0.034865 -0.167562 +v 0.070700 -0.034492 -0.166287 +v 0.071900 -0.034580 -0.166316 +v 0.070700 -0.035306 -0.169534 +v 0.071900 -0.035128 -0.169727 +v 0.070700 -0.032014 -0.170275 +v 0.071900 -0.031928 -0.170222 +v 0.070700 -0.030981 -0.167939 +v 0.071900 -0.031003 -0.167697 +v 0.070700 -0.032651 -0.165981 +v 0.071900 -0.033307 -0.165437 +v 0.070700 -0.032452 -0.164695 +v 0.071900 -0.030761 -0.165554 +v 0.070700 -0.029585 -0.167559 +v 0.071900 -0.029777 -0.169878 +v 0.070700 -0.032149 -0.171997 +v 0.071900 -0.033567 -0.171837 +v 0.071900 -0.036634 -0.169721 +v 0.070700 -0.036782 -0.169441 +v 0.071900 -0.036011 -0.165870 +v 0.070700 -0.035784 -0.165666 +v 0.071300 -0.033556 -0.164715 +v 0.070700 0.031287 -0.169492 +v 0.071900 0.030981 -0.168485 +v 0.071900 0.032969 -0.170703 +v 0.070700 0.035132 -0.170011 +v 0.071900 0.035607 -0.168387 +v 0.070700 0.034285 -0.166064 +v 0.071900 0.034017 -0.166051 +v 0.071900 0.031268 -0.166970 +v 0.070700 0.031115 -0.167255 +v 0.071194 0.029681 -0.168196 +v 0.071900 0.030661 -0.165606 +v 0.070700 0.030910 -0.165423 +v 0.071900 0.034098 -0.164720 +v 0.070700 0.034770 -0.164855 +v 0.071900 0.036545 -0.166773 +v 0.070700 0.036940 -0.169498 +v 0.071900 0.036097 -0.170652 +v 0.070700 0.032386 -0.171847 +v 0.071900 0.032529 -0.171758 +v 0.071900 0.029851 -0.169561 +v 0.070700 0.029637 -0.168853 +v 0.080661 0.041383 -0.126228 +v 0.080587 0.038795 -0.127274 +v 0.080689 0.038378 -0.129172 +v 0.080603 0.039420 -0.131328 +v 0.080657 0.041693 -0.131582 +v 0.080683 0.043203 -0.130503 +v 0.080609 0.043690 -0.128192 +v 0.069820 0.041864 -0.130124 +v 0.069956 0.039921 -0.130198 +v 0.069779 0.040037 -0.127974 +v 0.069972 0.042174 -0.127880 +v 0.077612 0.040757 -0.130623 +v 0.077609 0.039315 -0.128998 +v 0.077574 0.041390 -0.127249 +v 0.077610 0.042534 -0.129682 +v 0.077771 0.042114 -0.131590 +v 0.077757 0.038621 -0.130772 +v 0.077773 0.042076 -0.126425 +v 0.077768 0.043886 -0.128888 +v 0.077767 0.039052 -0.126869 +v 0.078700 0.042261 -0.129756 +v 0.078700 0.039739 -0.128244 +v 0.051629 0.019947 -0.174418 +v 0.051200 0.008453 -0.178112 +v 0.051200 0.016925 -0.178915 +v 0.051200 0.030157 -0.167613 +v 0.051200 0.030521 -0.169930 +v 0.049000 0.030526 -0.169943 +v 0.049000 0.016658 -0.178911 +v 0.049001 0.030197 -0.167468 +v 0.049001 0.011001 -0.177757 +v 0.053465 0.022023 -0.173413 +v 0.053200 0.008453 -0.178112 +v 0.052717 0.015532 -0.178786 +v 0.053200 0.030521 -0.169930 +v 0.053200 0.030225 -0.167099 +v 0.052700 0.023419 -0.175315 +v 0.052200 0.030526 -0.169943 +v 0.052200 0.008520 -0.178110 +v 0.052200 0.030353 -0.166791 +v 0.055465 0.022023 -0.173413 +v 0.055200 0.008453 -0.178112 +v 0.054717 0.015532 -0.178786 +v 0.055200 0.030521 -0.169930 +v 0.055200 0.030225 -0.167099 +v 0.054700 0.023419 -0.175316 +v 0.054200 0.030526 -0.169943 +v 0.054200 0.007443 -0.178510 +v 0.054200 0.030353 -0.166791 +v 0.057465 0.022023 -0.173413 +v 0.057200 0.008453 -0.178112 +v 0.056717 0.015532 -0.178786 +v 0.057200 0.030521 -0.169930 +v 0.057200 0.030225 -0.167099 +v 0.056700 0.023419 -0.175315 +v 0.056200 0.030526 -0.169943 +v 0.056200 0.007443 -0.178510 +v 0.056200 0.030353 -0.166791 +v 0.059465 0.022023 -0.173413 +v 0.059200 0.008453 -0.178112 +v 0.058717 0.015532 -0.178786 +v 0.059200 0.030521 -0.169930 +v 0.059200 0.030225 -0.167099 +v 0.058700 0.023419 -0.175315 +v 0.058200 0.030526 -0.169943 +v 0.058200 0.007443 -0.178510 +v 0.058200 0.030353 -0.166791 +v 0.061200 0.022089 -0.173489 +v 0.061200 0.008453 -0.178112 +v 0.060717 0.015532 -0.178786 +v 0.061200 0.030521 -0.169930 +v 0.061200 0.030225 -0.167099 +v 0.060700 0.023419 -0.175315 +v 0.060200 0.030526 -0.169943 +v 0.060200 0.007443 -0.178510 +v 0.060200 0.030353 -0.166791 +v 0.063201 0.022132 -0.173440 +v 0.063201 0.008516 -0.178079 +v 0.062717 0.015532 -0.178786 +v 0.063200 0.030521 -0.169930 +v 0.063200 0.030225 -0.167105 +v 0.062700 0.023419 -0.175315 +v 0.062200 0.030488 -0.169969 +v 0.062200 0.029963 -0.168110 +v 0.062200 0.008520 -0.178110 +v 0.051200 -0.006644 -0.178616 +v 0.051200 0.003031 -0.181356 +v 0.051200 -0.002947 -0.181431 +v 0.051200 0.042346 -0.121244 +v 0.051200 0.034931 -0.104479 +v 0.051200 0.032237 -0.104805 +v 0.051200 0.040920 -0.112548 +v 0.051200 0.046474 -0.129212 +v 0.051700 0.044000 -0.137428 +v 0.051200 0.034949 -0.165520 +v 0.051200 0.043965 -0.151718 +v 0.051629 0.041784 -0.149344 +v 0.051200 0.032257 -0.165260 +v 0.049001 -0.006913 -0.178547 +v 0.049000 0.002884 -0.181425 +v 0.049000 -0.003056 -0.181362 +v 0.049000 0.039276 -0.155558 +v 0.049000 0.034931 -0.165521 +v 0.049000 0.032218 -0.165204 +v 0.049000 0.037910 -0.112323 +v 0.049000 0.043965 -0.118282 +v 0.049000 0.043669 -0.127695 +v 0.049000 0.031338 -0.104320 +v 0.049000 0.034949 -0.104480 +v 0.049000 0.046474 -0.140788 +v 0.048405 0.044020 -0.140735 +v 0.049000 0.040920 -0.157451 +v 0.053200 -0.006644 -0.178616 +v 0.052717 0.002969 -0.181405 +v 0.052719 -0.002982 -0.181408 +v 0.053658 0.041374 -0.119277 +v 0.053200 0.034931 -0.104479 +v 0.053200 0.032237 -0.104805 +v 0.053200 0.040920 -0.112548 +v 0.053200 0.046474 -0.129212 +v 0.053700 0.044265 -0.137442 +v 0.053200 0.034949 -0.165520 +v 0.053200 0.043965 -0.151718 +v 0.053600 0.040827 -0.151583 +v 0.053200 0.032559 -0.165235 +v 0.052200 -0.006835 -0.178565 +v 0.052200 0.042458 -0.122272 +v 0.052200 0.043965 -0.118282 +v 0.052200 0.032559 -0.104765 +v 0.052200 0.034949 -0.104480 +v 0.052200 0.046474 -0.140788 +v 0.052200 0.040920 -0.157452 +v 0.052200 0.032906 -0.165161 +v 0.052200 0.034931 -0.165521 +v 0.055200 -0.006644 -0.178616 +v 0.054717 0.002969 -0.181405 +v 0.054719 -0.002982 -0.181408 +v 0.055200 0.039309 -0.114517 +v 0.055200 0.034931 -0.104479 +v 0.055714 0.032010 -0.104709 +v 0.055200 0.040920 -0.112548 +v 0.055200 0.046474 -0.129212 +v 0.055575 0.043749 -0.129230 +v 0.055200 0.034949 -0.165520 +v 0.055200 0.043965 -0.151718 +v 0.055200 0.042709 -0.147077 +v 0.055200 0.032559 -0.165235 +v 0.054200 -0.008545 -0.177920 +v 0.054200 0.043965 -0.118282 +v 0.054200 0.032092 -0.104681 +v 0.054200 0.034949 -0.104480 +v 0.054200 0.046474 -0.140788 +v 0.054200 0.040920 -0.157452 +v 0.054200 0.032906 -0.165161 +v 0.054200 0.034931 -0.165521 +v 0.057200 -0.006644 -0.178616 +v 0.056717 0.002969 -0.181405 +v 0.056719 -0.002982 -0.181408 +v 0.057200 0.040920 -0.112548 +v 0.057200 0.034931 -0.104479 +v 0.057200 0.032512 -0.104874 +v 0.057750 0.041784 -0.120656 +v 0.057200 0.046474 -0.129212 +v 0.057700 0.044265 -0.137442 +v 0.057200 0.034949 -0.165520 +v 0.057200 0.043965 -0.151718 +v 0.057600 0.040827 -0.151583 +v 0.057200 0.032559 -0.165235 +v 0.056200 -0.008545 -0.177920 +v 0.056200 0.038648 -0.113295 +v 0.056200 0.043965 -0.118282 +v 0.056200 0.043379 -0.144721 +v 0.056200 0.034949 -0.104480 +v 0.056200 0.046474 -0.140788 +v 0.056200 0.040920 -0.157452 +v 0.056200 0.032906 -0.165161 +v 0.056200 0.034931 -0.165521 +v 0.059200 -0.006644 -0.178616 +v 0.058717 0.002969 -0.181405 +v 0.058719 -0.002982 -0.181408 +v 0.059200 0.040920 -0.112548 +v 0.059200 0.034931 -0.104479 +v 0.059200 0.032512 -0.104874 +v 0.059200 0.042836 -0.123609 +v 0.059200 0.046474 -0.129212 +v 0.059200 0.043279 -0.145457 +v 0.059200 0.034949 -0.165520 +v 0.059200 0.043965 -0.151718 +v 0.059200 0.032559 -0.165235 +v 0.058200 -0.008545 -0.177920 +v 0.058200 0.043965 -0.118282 +v 0.058200 0.032092 -0.104681 +v 0.058200 0.034949 -0.104480 +v 0.058200 0.046474 -0.140788 +v 0.058200 0.040920 -0.157451 +v 0.058200 0.032906 -0.165161 +v 0.058200 0.034931 -0.165521 +v 0.061200 -0.006644 -0.178616 +v 0.060717 0.002969 -0.181405 +v 0.060719 -0.002982 -0.181408 +v 0.061200 0.040920 -0.112548 +v 0.061200 0.034931 -0.104479 +v 0.061200 0.032512 -0.104874 +v 0.061750 0.041784 -0.120656 +v 0.061200 0.046474 -0.129212 +v 0.061700 0.044265 -0.137442 +v 0.061200 0.034949 -0.165520 +v 0.061200 0.043965 -0.151718 +v 0.061854 0.039412 -0.155164 +v 0.061700 0.032351 -0.165214 +v 0.060200 -0.008545 -0.177920 +v 0.060200 0.038648 -0.113295 +v 0.060200 0.043965 -0.118282 +v 0.060200 0.044214 -0.131865 +v 0.060200 0.031771 -0.104560 +v 0.060200 0.034949 -0.104480 +v 0.060200 0.046474 -0.140788 +v 0.060200 0.041972 -0.148763 +v 0.060200 0.040920 -0.157452 +v 0.060200 0.032906 -0.165161 +v 0.060200 0.034931 -0.165521 +v 0.063200 -0.006139 -0.178800 +v 0.062717 0.002970 -0.181405 +v 0.062719 -0.002982 -0.181408 +v 0.063200 0.037895 -0.112344 +v 0.063200 0.034931 -0.104479 +v 0.063200 0.032208 -0.104796 +v 0.063200 0.040920 -0.112548 +v 0.063700 0.043728 -0.127703 +v 0.063200 0.046474 -0.129212 +v 0.063200 0.034949 -0.165520 +v 0.063200 0.043965 -0.151718 +v 0.063575 0.042732 -0.146707 +v 0.063200 0.032746 -0.165186 +v 0.062200 -0.006835 -0.178565 +v 0.062200 0.034931 -0.165521 +v 0.062200 0.043965 -0.118282 +v 0.062200 0.032092 -0.104681 +v 0.062200 0.034949 -0.104480 +v 0.062200 0.046474 -0.140788 +v 0.062200 0.040920 -0.157452 +v 0.064334 0.043511 -0.151264 +v 0.070701 0.043498 -0.151264 +v 0.064389 0.037168 -0.164276 +v 0.070788 0.037404 -0.162482 +v 0.064356 0.032149 -0.173711 +v 0.070468 0.032288 -0.173657 +v 0.064325 0.019270 -0.197242 +v 0.070701 0.018874 -0.197678 +v 0.051200 0.030066 -0.101991 +v 0.051200 0.021329 -0.093484 +v 0.051629 0.010990 -0.092032 +v 0.051200 0.004353 -0.088370 +v 0.051200 -0.010207 -0.091866 +v 0.051200 -0.018146 -0.091605 +v 0.051200 -0.030099 -0.102214 +v 0.051200 -0.030502 -0.100059 +v 0.051200 0.030520 -0.100051 +v 0.049000 -0.030526 -0.100055 +v 0.049000 -0.017520 -0.094444 +v 0.049000 -0.030221 -0.102669 +v 0.048514 0.018837 -0.094700 +v 0.049000 0.030457 -0.100057 +v 0.049000 -0.016718 -0.091035 +v 0.049000 -0.000857 -0.090673 +v 0.049000 0.005788 -0.088526 +v 0.049000 0.022452 -0.094080 +v 0.053200 -0.030502 -0.100059 +v 0.053200 -0.031104 -0.104176 +v 0.053200 -0.019392 -0.095142 +v 0.053200 0.030066 -0.101991 +v 0.052671 0.021896 -0.093772 +v 0.053629 0.010990 -0.092032 +v 0.052700 0.005072 -0.088435 +v 0.053867 -0.002243 -0.090786 +v 0.052700 -0.010026 -0.089524 +v 0.052700 -0.021896 -0.093772 +v 0.053200 0.030520 -0.100051 +v 0.052200 -0.030526 -0.100055 +v 0.052200 -0.018301 -0.094799 +v 0.052200 -0.030226 -0.102696 +v 0.052200 -0.001915 -0.090716 +v 0.052200 0.030314 -0.102852 +v 0.052200 0.030457 -0.100057 +v 0.055700 0.015719 -0.093718 +v 0.054671 0.021895 -0.093772 +v 0.055200 0.004352 -0.090889 +v 0.054700 0.005072 -0.088435 +v 0.055200 -0.012601 -0.092665 +v 0.054700 -0.010025 -0.089524 +v 0.054700 -0.021896 -0.093772 +v 0.055200 -0.030099 -0.102214 +v 0.055200 -0.030502 -0.100059 +v 0.055200 0.030263 -0.102594 +v 0.055200 0.030520 -0.100051 +v 0.054200 -0.030488 -0.100029 +v 0.054200 -0.020631 -0.095769 +v 0.054200 -0.031450 -0.104527 +v 0.054200 0.030164 -0.102359 +v 0.054200 0.030521 -0.100069 +v 0.057200 -0.030502 -0.100059 +v 0.057200 -0.031292 -0.104404 +v 0.057575 -0.019957 -0.095564 +v 0.057600 0.017701 -0.094645 +v 0.056671 0.021895 -0.093772 +v 0.057629 0.004653 -0.090985 +v 0.056700 0.005072 -0.088435 +v 0.057700 -0.008452 -0.091730 +v 0.056700 -0.010025 -0.089524 +v 0.056700 -0.021896 -0.093772 +v 0.057200 0.030263 -0.102594 +v 0.057200 0.030520 -0.100051 +v 0.056200 -0.030488 -0.100029 +v 0.056200 -0.020632 -0.095769 +v 0.056200 -0.031450 -0.104527 +v 0.056200 -0.001915 -0.090716 +v 0.056200 0.030164 -0.102359 +v 0.056200 0.030521 -0.100069 +v 0.059200 -0.030502 -0.100059 +v 0.059200 -0.031104 -0.104176 +v 0.059200 -0.019392 -0.095142 +v 0.059700 0.015719 -0.093718 +v 0.058671 0.021895 -0.093772 +v 0.059200 0.001966 -0.090519 +v 0.058700 0.005072 -0.088435 +v 0.058700 -0.010026 -0.089524 +v 0.058700 -0.021896 -0.093772 +v 0.059200 0.030263 -0.102594 +v 0.059200 0.030520 -0.100051 +v 0.058200 -0.030526 -0.100055 +v 0.058200 -0.030226 -0.102696 +v 0.058200 0.030164 -0.102359 +v 0.058200 0.030521 -0.100069 +v 0.061200 -0.030502 -0.100059 +v 0.061200 -0.031292 -0.104404 +v 0.061200 -0.019392 -0.095142 +v 0.061200 0.030066 -0.101991 +v 0.060671 0.021895 -0.093772 +v 0.061629 0.010990 -0.092032 +v 0.060700 0.005072 -0.088435 +v 0.061867 -0.002243 -0.090786 +v 0.060700 -0.010026 -0.089524 +v 0.060700 -0.021896 -0.093772 +v 0.061200 0.030520 -0.100051 +v 0.060200 -0.030488 -0.100029 +v 0.060200 -0.020632 -0.095769 +v 0.060200 -0.031450 -0.104527 +v 0.060200 -0.001915 -0.090716 +v 0.060200 0.030164 -0.102359 +v 0.060200 0.030521 -0.100069 +v 0.063200 -0.030502 -0.100059 +v 0.063200 -0.030445 -0.103074 +v 0.063200 -0.019348 -0.095155 +v 0.063200 0.013181 -0.092632 +v 0.062671 0.021896 -0.093772 +v 0.062700 0.005072 -0.088435 +v 0.063825 -0.001183 -0.090852 +v 0.062700 -0.010026 -0.089524 +v 0.062700 -0.021896 -0.093772 +v 0.063200 0.030267 -0.102612 +v 0.063200 0.030520 -0.100051 +v 0.062200 -0.030488 -0.100029 +v 0.062200 -0.020632 -0.095769 +v 0.062200 -0.031450 -0.104527 +v 0.062200 0.030164 -0.102359 +v 0.062200 0.030521 -0.100069 +v 0.064330 0.046344 -0.139285 +v 0.070701 0.046078 -0.139991 +v 0.070710 0.045936 -0.128077 +v 0.064242 0.044891 -0.121956 +v 0.070699 0.042934 -0.117353 +v 0.064391 0.037085 -0.106389 +v 0.070762 0.037174 -0.107465 +v 0.064200 0.018524 -0.094660 +v 0.064200 0.035135 -0.107757 +v 0.064200 -0.015455 -0.093524 +v 0.064198 -0.031355 -0.103525 +v 0.063199 -0.032580 -0.104874 +v 0.063700 -0.041804 -0.120649 +v 0.063198 -0.032214 -0.165204 +v 0.064200 -0.028159 -0.169139 +v 0.063644 -0.040092 -0.153920 +v 0.063200 -0.030056 -0.167848 +v 0.063507 -0.012034 -0.177722 +v 0.064201 -0.001564 -0.179218 +v 0.064205 0.019249 -0.175145 +v 0.064201 0.036291 -0.160550 +v 0.061652 -0.040092 -0.116080 +v 0.061700 -0.040092 -0.153920 +v 0.061200 -0.032206 -0.165204 +v 0.062200 -0.031292 -0.165596 +v 0.061200 -0.030170 -0.167602 +v 0.062200 -0.021554 -0.173555 +v 0.061200 -0.011774 -0.177740 +v 0.059652 -0.040092 -0.116080 +v 0.060200 -0.031199 -0.165815 +v 0.059644 -0.040445 -0.152978 +v 0.059200 -0.032206 -0.165204 +v 0.059200 -0.030170 -0.167602 +v 0.060200 -0.021554 -0.173555 +v 0.059200 -0.011774 -0.177740 +v 0.058200 -0.032206 -0.104796 +v 0.057652 -0.040092 -0.116080 +v 0.057700 -0.040092 -0.153920 +v 0.057200 -0.032206 -0.165204 +v 0.058200 -0.031292 -0.165596 +v 0.057200 -0.030170 -0.167602 +v 0.058200 -0.021554 -0.173554 +v 0.057200 -0.011774 -0.177740 +v 0.055200 -0.032222 -0.104774 +v 0.055719 -0.040445 -0.117022 +v 0.055700 -0.040092 -0.153920 +v 0.055200 -0.032206 -0.165204 +v 0.056200 -0.031292 -0.165596 +v 0.055200 -0.030170 -0.167602 +v 0.056200 -0.021554 -0.173555 +v 0.055200 -0.011774 -0.177740 +v 0.053652 -0.040092 -0.116080 +v 0.053700 -0.040092 -0.153920 +v 0.053200 -0.032206 -0.165204 +v 0.054200 -0.031292 -0.165596 +v 0.053200 -0.030170 -0.167602 +v 0.054200 -0.021554 -0.173555 +v 0.053200 -0.011774 -0.177740 +v 0.052200 -0.032206 -0.104796 +v 0.051200 -0.032222 -0.104774 +v 0.051719 -0.040445 -0.117022 +v 0.051700 -0.040092 -0.153920 +v 0.051200 -0.032206 -0.165204 +v 0.052200 -0.031292 -0.165596 +v 0.051200 -0.030170 -0.167602 +v 0.052200 -0.021554 -0.173555 +v 0.051200 -0.011774 -0.177740 +v 0.070757 0.027511 -0.097824 +v 0.064381 0.028460 -0.097885 +v 0.064326 0.015298 -0.090921 +v 0.070729 0.016605 -0.091622 +v 0.070765 0.002732 -0.088506 +v 0.064338 -0.002238 -0.088615 +v 0.070727 -0.014844 -0.090852 +v 0.064326 -0.016731 -0.091613 +v 0.064377 -0.028514 -0.097910 +v 0.070714 -0.027265 -0.097684 +v 0.064323 -0.014660 -0.200080 +v 0.064363 0.014380 -0.200158 +v 0.070712 -0.014761 -0.200096 +v 0.070687 0.014204 -0.200152 +v 0.064475 0.034828 -0.097983 +v 0.070559 0.034845 -0.098089 +v 0.070539 0.037048 -0.100799 +v 0.064329 0.036947 -0.100420 +v 0.064403 0.036874 -0.170115 +v 0.064371 -0.034847 -0.098070 +v 0.064431 -0.037059 -0.100771 +v 0.064408 -0.037163 -0.106543 +v 0.064397 -0.044165 -0.119905 +v 0.070554 0.036812 -0.170166 +v 0.070577 -0.036787 -0.170051 +v 0.070858 -0.029363 -0.168799 +v 0.070932 -0.030301 -0.165350 +v 0.070788 -0.037416 -0.162614 +v 0.070835 -0.030860 -0.175090 +v 0.070913 -0.030444 -0.104681 +v 0.070593 -0.036919 -0.100343 +v 0.070755 -0.037181 -0.107495 +v 0.070471 -0.034838 -0.098003 +v 0.063840 -0.044207 -0.136071 +v 0.064299 -0.046342 -0.133520 +v 0.064382 -0.044495 -0.149021 +v 0.064289 -0.019166 -0.197301 +v 0.064401 -0.037161 -0.164323 +v 0.064362 -0.036820 -0.170170 +v 0.064366 -0.032137 -0.173738 +v 0.051200 -0.016723 -0.178891 +v 0.051200 -0.030488 -0.169969 +v 0.049000 -0.019740 -0.174397 +v 0.049000 -0.016925 -0.178915 +v 0.049000 -0.030188 -0.167393 +v 0.049000 -0.030521 -0.169930 +v 0.052733 -0.023419 -0.175315 +v 0.052664 -0.015529 -0.178792 +v 0.053200 -0.030488 -0.169969 +v 0.052200 -0.030502 -0.169939 +v 0.055200 -0.030465 -0.170384 +v 0.054756 -0.015588 -0.178821 +v 0.054200 -0.030450 -0.170644 +v 0.056733 -0.023419 -0.175315 +v 0.056720 -0.015494 -0.178809 +v 0.057200 -0.030488 -0.169969 +v 0.056200 -0.030502 -0.169939 +v 0.059200 -0.030465 -0.170384 +v 0.058756 -0.015588 -0.178821 +v 0.058200 -0.030450 -0.170644 +v 0.061200 -0.030465 -0.170384 +v 0.060756 -0.015588 -0.178821 +v 0.060200 -0.030450 -0.170644 +v 0.063200 -0.030465 -0.170384 +v 0.063200 -0.015655 -0.178826 +v 0.062200 -0.030502 -0.169939 +v 0.062200 -0.016925 -0.178915 +v 0.051200 -0.034931 -0.165521 +v 0.051200 -0.034945 -0.104474 +v 0.051200 -0.043965 -0.118282 +v 0.051700 -0.044332 -0.135000 +v 0.051200 -0.046474 -0.140788 +v 0.051200 -0.040920 -0.157452 +v 0.049000 -0.041228 -0.151850 +v 0.049000 -0.031945 -0.165382 +v 0.049000 -0.034949 -0.165520 +v 0.049000 -0.043965 -0.151718 +v 0.049000 -0.043925 -0.127628 +v 0.049000 -0.046474 -0.129212 +v 0.049000 -0.040920 -0.112548 +v 0.049002 -0.032711 -0.104905 +v 0.049000 -0.034931 -0.104479 +v 0.053200 -0.034931 -0.165521 +v 0.053200 -0.034949 -0.104480 +v 0.053200 -0.043965 -0.118282 +v 0.053700 -0.044332 -0.135000 +v 0.053200 -0.046474 -0.140788 +v 0.053200 -0.040920 -0.157451 +v 0.052200 -0.034931 -0.104479 +v 0.052200 -0.034945 -0.165526 +v 0.052200 -0.043965 -0.151718 +v 0.052200 -0.046474 -0.129212 +v 0.052200 -0.040920 -0.112548 +v 0.055200 -0.034931 -0.165521 +v 0.055200 -0.034945 -0.104474 +v 0.055200 -0.043965 -0.118282 +v 0.055700 -0.044332 -0.135000 +v 0.055200 -0.046474 -0.140788 +v 0.055200 -0.040920 -0.157452 +v 0.054200 -0.034931 -0.104479 +v 0.054200 -0.034945 -0.165526 +v 0.054200 -0.043965 -0.151718 +v 0.054200 -0.046474 -0.129212 +v 0.054200 -0.040920 -0.112548 +v 0.057200 -0.034931 -0.165521 +v 0.057200 -0.034945 -0.104474 +v 0.057200 -0.043965 -0.118282 +v 0.057700 -0.044332 -0.135000 +v 0.057200 -0.046474 -0.140788 +v 0.057200 -0.040920 -0.157452 +v 0.056200 -0.034931 -0.104479 +v 0.056200 -0.034945 -0.165526 +v 0.056200 -0.043965 -0.151718 +v 0.056200 -0.046474 -0.129212 +v 0.056200 -0.040920 -0.112548 +v 0.059200 -0.034931 -0.165521 +v 0.059200 -0.034949 -0.104480 +v 0.059200 -0.043965 -0.118282 +v 0.059700 -0.044332 -0.135000 +v 0.059200 -0.046474 -0.140788 +v 0.059200 -0.040920 -0.157452 +v 0.058200 -0.034931 -0.104479 +v 0.058200 -0.034945 -0.165526 +v 0.058200 -0.043965 -0.151718 +v 0.058200 -0.046474 -0.129212 +v 0.058200 -0.040920 -0.112548 +v 0.061200 -0.034931 -0.165521 +v 0.061200 -0.034945 -0.104474 +v 0.061200 -0.043965 -0.118282 +v 0.061700 -0.044332 -0.135000 +v 0.061200 -0.046474 -0.140788 +v 0.061200 -0.040920 -0.157452 +v 0.060200 -0.034931 -0.104479 +v 0.060200 -0.034949 -0.165520 +v 0.060200 -0.043965 -0.151718 +v 0.060200 -0.046474 -0.129212 +v 0.060200 -0.040920 -0.112549 +v 0.063200 -0.034931 -0.165521 +v 0.063200 -0.034945 -0.104474 +v 0.063200 -0.043965 -0.118282 +v 0.063200 -0.046474 -0.140788 +v 0.063200 -0.040920 -0.157451 +v 0.062200 -0.034931 -0.104479 +v 0.062200 -0.034945 -0.165526 +v 0.062200 -0.043965 -0.151718 +v 0.062200 -0.046474 -0.129212 +v 0.062200 -0.040920 -0.112548 +v 0.070708 -0.043670 -0.150654 +v 0.070700 -0.019165 -0.197292 +v 0.070703 -0.044451 -0.120976 +v 0.070724 -0.046326 -0.138859 +v 0.102115 0.028626 -0.120240 +v 0.096314 0.043722 -0.122693 +v 0.096814 0.037222 -0.109719 +v 0.097964 0.040692 -0.125911 +v 0.096591 0.044040 -0.128188 +v 0.099276 0.037943 -0.128548 +v 0.097502 0.042340 -0.131800 +v 0.096014 0.045217 -0.137552 +v 0.099998 0.035574 -0.143831 +v 0.098887 0.039184 -0.131374 +v 0.095885 0.042810 -0.149803 +v 0.095754 0.036873 -0.161384 +v 0.086872 0.020399 -0.191805 +v 0.092822 0.029088 -0.176572 +v 0.096055 0.009968 -0.179349 +v 0.081393 0.014280 -0.200156 +v 0.082492 0.016905 -0.198430 +v 0.083810 -0.000095 -0.199283 +v 0.086078 0.003158 -0.196100 +v 0.089669 -0.010131 -0.190328 +v 0.081683 -0.012568 -0.200286 +v 0.086213 -0.003157 -0.195916 +v 0.082914 -0.017873 -0.197620 +v 0.100887 -0.025507 -0.156906 +v 0.096161 -0.036190 -0.161135 +v 0.097360 -0.028589 -0.165474 +v 0.099030 -0.039178 -0.131525 +v 0.096756 -0.043913 -0.130478 +v 0.096046 -0.045311 -0.138387 +v 0.096468 -0.042773 -0.120169 +v 0.097130 -0.042648 -0.126385 +v 0.099101 -0.038234 -0.127281 +v 0.096877 -0.025047 -0.097106 +v 0.097271 -0.027132 -0.099770 +v 0.101339 -0.010201 -0.100651 +v 0.097187 -0.011937 -0.091333 +v 0.097323 -0.000366 -0.089905 +v 0.100900 0.012669 -0.100454 +v 0.097196 0.013844 -0.091737 +v 0.088521 0.000083 -0.192825 +v 0.088032 -0.023080 -0.188570 +v 0.097048 0.026497 -0.098590 +v 0.095353 -0.012987 -0.179654 +v 0.093212 -0.028177 -0.176670 +v 0.096564 0.027402 -0.168720 +v 0.100111 0.015971 -0.166846 +v 0.100317 -0.013928 -0.167593 +v 0.097993 0.029521 -0.163211 +v 0.102745 0.000242 -0.162613 +v 0.098471 0.029537 -0.105848 +v 0.104605 0.007746 -0.112953 +v 0.104400 -0.013483 -0.114902 +v 0.098678 -0.029366 -0.106171 +v 0.104321 0.012137 -0.153021 +v 0.104759 -0.017271 -0.146540 +v 0.095876 -0.041642 -0.152837 +v 0.106304 -0.003799 -0.144381 +v 0.101008 -0.032590 -0.144290 +v 0.103796 0.023793 -0.141039 +v 0.105398 0.016256 -0.125610 +v 0.106505 0.008516 -0.135968 +v 0.106710 -0.005139 -0.127549 +v 0.103211 -0.025603 -0.123718 +v 0.096827 -0.036541 -0.108901 +v 0.093784 0.038346 -0.161410 +v 0.093862 0.042572 -0.153586 +v 0.082052 0.019503 -0.197086 +v 0.070863 0.030862 -0.175095 +v 0.090249 0.029800 -0.178053 +v 0.094002 0.046009 -0.142485 +v 0.094383 0.046144 -0.129765 +v 0.094244 0.044478 -0.121482 +v 0.094569 0.039586 -0.110463 +v 0.095424 0.026116 -0.096751 +v 0.095023 0.018726 -0.092482 +v 0.095139 0.010445 -0.089678 +v 0.095280 -0.001748 -0.088471 +v 0.095207 -0.015125 -0.090974 +v 0.094760 -0.025354 -0.096012 +v 0.080437 -0.014332 -0.200316 +v 0.077700 0.003234 -0.195300 +v 0.077700 -0.000264 -0.192984 +v 0.077700 -0.000716 -0.199262 +v 0.077700 -0.002899 -0.194955 +v 0.077700 0.044105 -0.129657 +v 0.077700 0.040056 -0.132094 +v 0.077700 0.038104 -0.127418 +v 0.077700 0.042335 -0.126263 +v 0.070931 0.030332 -0.104658 +v 0.096055 0.029684 -0.103341 +v 0.096107 0.031258 -0.105162 +v 0.093691 0.029503 -0.169408 +v 0.070899 0.029183 -0.167471 +v 0.095099 0.029299 -0.167481 +v 0.095592 0.031094 -0.164801 +v 0.070860 0.031520 -0.164721 +v 0.095619 0.035519 -0.106672 +v 0.095212 0.028567 -0.099581 +v 0.091812 0.030643 -0.173893 +v 0.094072 0.034613 -0.163932 +v 0.094109 -0.043336 -0.151964 +v 0.071183 -0.038644 -0.161238 +v 0.094341 -0.038522 -0.160899 +v 0.081547 -0.019703 -0.197007 +v 0.091059 -0.029997 -0.177312 +v 0.095051 -0.038414 -0.109093 +v 0.094377 -0.042518 -0.116111 +v 0.094262 -0.046204 -0.128906 +v 0.093971 -0.046095 -0.140978 +v 0.077700 -0.043667 -0.127231 +v 0.077700 -0.039457 -0.126337 +v 0.077700 -0.038013 -0.129000 +v 0.077700 -0.039601 -0.131778 +v 0.077700 -0.043194 -0.131104 +v 0.095907 -0.031281 -0.105139 +v 0.096063 -0.029690 -0.103355 +v 0.095388 -0.029958 -0.166095 +v 0.094704 -0.031684 -0.164712 +v 0.093682 -0.029349 -0.168626 +v 0.095211 -0.036046 -0.106850 +v 0.095132 -0.028519 -0.099465 +v 0.091541 -0.030657 -0.172756 +v 0.093891 -0.035375 -0.163660 +v 0.097610 -0.030159 -0.105334 +v 0.096449 -0.031954 -0.163701 +v 0.095501 -0.028407 -0.169267 +v 0.093374 -0.029509 -0.174281 +v 0.064187 -0.011744 -0.179530 +v 0.063487 -0.010965 -0.181488 +v 0.063699 -0.010897 -0.177878 +v 0.064187 -0.009589 -0.179309 +v 0.064187 -0.009819 -0.181468 +v 0.064187 -0.008577 -0.180901 +v 0.064187 -0.006784 -0.178941 +v 0.064187 -0.010409 -0.177903 +v 0.064187 -0.007540 -0.179793 +v 0.064187 -0.012669 -0.180742 +v 0.064187 -0.014954 -0.182616 +v 0.064187 -0.013464 -0.179093 +v 0.063712 -0.015446 -0.181303 +v 0.063687 -0.014572 -0.178691 +v 0.064187 -0.019158 -0.185463 +v 0.064187 -0.002550 -0.186172 +v 0.063507 -0.018047 -0.187729 +v 0.064187 -0.017646 -0.191131 +v 0.063701 -0.019646 -0.190808 +v 0.064187 -0.015686 -0.196614 +v 0.064187 -0.004703 -0.185245 +v 0.064187 -0.012374 -0.195582 +v 0.064187 -0.008391 -0.197395 +v 0.064187 -0.004850 -0.192559 +v 0.064187 -0.003072 -0.193030 +v 0.063187 -0.013201 -0.178891 +v 0.063187 -0.013120 -0.180607 +v 0.063187 -0.011684 -0.179920 +v 0.063187 -0.007804 -0.180133 +v 0.063187 -0.006843 -0.178832 +v 0.063187 -0.005323 -0.182248 +v 0.063187 -0.009555 -0.180637 +v 0.063187 -0.010601 -0.181510 +v 0.063187 -0.008940 -0.178818 +v 0.063187 -0.018700 -0.184311 +v 0.063187 -0.002099 -0.189716 +v 0.063187 -0.016036 -0.183511 +v 0.063187 -0.015062 -0.194649 +v 0.063187 -0.015947 -0.196450 +v 0.063187 -0.006804 -0.197054 +v 0.063187 -0.007740 -0.194795 +v 0.063187 -0.003635 -0.188740 +v 0.080700 -0.039739 -0.128244 +v 0.080623 -0.041038 -0.126156 +v 0.080677 -0.043663 -0.129562 +v 0.080583 -0.043173 -0.127301 +v 0.080652 -0.040142 -0.131625 +v 0.080588 -0.042411 -0.131353 +v 0.080599 -0.038572 -0.127609 +v 0.080594 -0.038393 -0.129949 +v 0.069857 -0.039639 -0.128419 +v 0.069845 -0.040646 -0.130512 +v 0.069759 -0.042434 -0.128945 +v 0.070195 -0.041387 -0.127388 +v 0.077600 -0.042057 -0.127604 +v 0.077602 -0.039515 -0.128146 +v 0.077599 -0.040322 -0.130591 +v 0.077613 -0.042399 -0.129858 +v 0.077775 -0.043256 -0.130644 +v 0.077778 -0.043538 -0.127624 +v 0.077749 -0.038009 -0.129317 +v 0.077773 -0.040826 -0.131815 +v 0.077759 -0.040456 -0.126199 +v 0.078700 -0.041890 -0.130170 +v 0.078700 -0.040110 -0.127830 +v 0.075900 -0.032896 -0.100010 +v 0.075830 -0.030781 -0.099078 +v 0.075823 -0.034308 -0.098392 +v 0.075900 -0.034924 -0.102351 +v 0.075849 -0.036990 -0.101608 +v 0.075825 -0.034305 -0.105189 +v 0.075900 -0.031882 -0.102937 +v 0.075848 -0.030060 -0.103781 +v 0.042064 -0.032351 -0.103475 +v 0.042200 -0.034688 -0.103253 +v 0.041953 -0.034564 -0.100201 +v 0.042088 -0.031303 -0.101039 +v 0.071834 -0.033413 -0.099633 +v 0.071827 -0.035329 -0.101052 +v 0.071803 -0.033992 -0.103948 +v 0.071832 -0.031448 -0.102923 +v 0.071827 -0.031340 -0.100620 +v 0.071963 -0.036758 -0.101502 +v 0.071951 -0.034544 -0.098316 +v 0.071961 -0.030523 -0.099429 +v 0.071942 -0.030129 -0.103876 +v 0.071951 -0.035035 -0.104987 +v 0.072900 -0.034712 -0.102773 +v 0.072900 -0.031623 -0.102542 +v 0.072900 -0.033368 -0.099983 +v 0.063530 0.010424 -0.181448 +v 0.064187 0.009323 -0.178959 +v 0.064187 0.009073 -0.180951 +v 0.064187 0.015979 -0.181621 +v 0.063687 0.014573 -0.178691 +v 0.064187 0.013224 -0.180614 +v 0.064187 0.013218 -0.179021 +v 0.064187 0.010870 -0.177887 +v 0.064187 0.011654 -0.179568 +v 0.064187 0.012192 -0.181448 +v 0.063674 0.006070 -0.181674 +v 0.064187 0.007770 -0.180233 +v 0.064187 0.006910 -0.178735 +v 0.064187 0.002411 -0.185947 +v 0.064187 0.019795 -0.187881 +v 0.064187 0.003635 -0.188740 +v 0.063582 0.003115 -0.192981 +v 0.064187 0.007740 -0.194795 +v 0.064187 0.017871 -0.186302 +v 0.064187 0.006931 -0.196798 +v 0.064187 0.015470 -0.194469 +v 0.064187 0.014255 -0.197316 +v 0.063616 0.019142 -0.192418 +v 0.063187 0.006784 -0.178941 +v 0.063187 0.010409 -0.177903 +v 0.063187 0.008152 -0.179063 +v 0.063187 0.010892 -0.181563 +v 0.063187 0.011797 -0.180385 +v 0.063187 0.014954 -0.182616 +v 0.063187 0.008350 -0.180769 +v 0.063187 0.009735 -0.179986 +v 0.063187 0.013851 -0.179743 +v 0.063187 0.012479 -0.178589 +v 0.063187 0.002769 -0.185241 +v 0.063187 0.004103 -0.185905 +v 0.063187 0.005822 -0.193427 +v 0.063187 0.008391 -0.197395 +v 0.063187 0.012807 -0.195561 +v 0.063187 0.014796 -0.196946 +v 0.063187 0.019263 -0.185424 +v 0.063187 0.018344 -0.189107 +v 0.002944 0.042415 -0.168123 +v 0.005292 0.046325 -0.168057 +v 0.006778 0.044718 -0.168156 +v 0.009222 0.039282 -0.168156 +v 0.012841 0.041345 -0.168144 +v 0.011804 0.038666 -0.168051 +v 0.008114 0.036877 -0.168054 +v 0.004452 0.038423 -0.168061 +v 0.008985 0.046938 -0.168044 +v 0.012161 0.044954 -0.168057 +v 0.009607 0.039325 -0.142277 +v 0.010774 0.043257 -0.142340 +v 0.005119 0.041800 -0.142200 +v 0.008504 0.044845 -0.142248 +v 0.006154 0.044319 -0.142373 +v 0.011150 0.041212 -0.162086 +v 0.007457 0.038627 -0.162061 +v 0.005845 0.039674 -0.142637 +v 0.004746 0.042819 -0.162070 +v 0.009120 0.045228 -0.162061 +v 0.011748 0.038544 -0.162228 +v 0.013042 0.042297 -0.162231 +v 0.006980 0.036886 -0.162221 +v 0.006387 0.046959 -0.162221 +v 0.003041 0.043179 -0.162228 +v 0.011316 0.045871 -0.162228 +v 0.003594 0.039610 -0.162232 +v 0.005217 0.043067 -0.163156 +v 0.008468 0.039056 -0.163156 +v 0.010315 0.043877 -0.163156 +v 0.005217 -0.033156 -0.091934 +v 0.006859 -0.033118 -0.088048 +v 0.003647 -0.033050 -0.090475 +v 0.010783 -0.033156 -0.094067 +v 0.013038 -0.033056 -0.092576 +v 0.011306 -0.033061 -0.089140 +v 0.003031 -0.033054 -0.094167 +v 0.007332 -0.033156 -0.095808 +v 0.005925 -0.033064 -0.097696 +v 0.011297 -0.033065 -0.097079 +v 0.007866 -0.007222 -0.090011 +v 0.006435 -0.007400 -0.095780 +v 0.005307 -0.007258 -0.091729 +v 0.009985 -0.007291 -0.095151 +v 0.010893 -0.007423 -0.091899 +v 0.004841 -0.027061 -0.094301 +v 0.008391 -0.027090 -0.096134 +v 0.010830 -0.027088 -0.094491 +v 0.010438 -0.027078 -0.090779 +v 0.006511 -0.027086 -0.090114 +v 0.003257 -0.027231 -0.094737 +v 0.003543 -0.027225 -0.090414 +v 0.006267 -0.027225 -0.097852 +v 0.010693 -0.027231 -0.088727 +v 0.013284 -0.027215 -0.093075 +v 0.007154 -0.027231 -0.088021 +v 0.010569 -0.027231 -0.097349 +v 0.006257 -0.028156 -0.095418 +v 0.010965 -0.028156 -0.093301 +v 0.006778 -0.028156 -0.090282 +v 0.010672 0.039711 -0.162156 +v 0.009578 0.038944 -0.160556 +v 0.011330 0.042601 -0.160556 +v 0.010217 0.044772 -0.162156 +v 0.008450 0.045521 -0.160556 +v 0.006313 0.044897 -0.162156 +v 0.004930 0.043423 -0.160556 +v 0.004542 0.041893 -0.162156 +v 0.005863 0.039204 -0.160556 +v 0.007380 0.038621 -0.162156 +v 0.006852 0.036991 -0.162156 +v 0.007000 0.036889 -0.160556 +v 0.002896 0.041000 -0.162156 +v 0.002603 0.042421 -0.160556 +v 0.004865 0.046150 -0.162156 +v 0.008166 0.047411 -0.160556 +v 0.011124 0.046349 -0.162156 +v 0.012857 0.043615 -0.160556 +v 0.012684 0.039287 -0.162156 +v 0.012125 0.038904 -0.160556 +v 0.008754 0.037067 -0.161138 +v 0.032299 0.045173 -0.162156 +v 0.035908 0.044689 -0.161356 +v 0.032390 0.045164 -0.160556 +v 0.030668 0.041229 -0.160556 +v 0.030746 0.040948 -0.162156 +v 0.034172 0.038404 -0.160556 +v 0.034246 0.038459 -0.162156 +v 0.037439 0.041619 -0.162156 +v 0.037482 0.042507 -0.160556 +v 0.036177 0.044486 -0.162156 +v 0.037325 0.045769 -0.161498 +v 0.039125 0.042583 -0.160556 +v 0.039157 0.041890 -0.162156 +v 0.037537 0.038351 -0.160556 +v 0.037202 0.038094 -0.162156 +v 0.032179 0.036964 -0.160556 +v 0.033091 0.036923 -0.162156 +v 0.029803 0.039240 -0.162156 +v 0.028890 0.041717 -0.160556 +v 0.028980 0.043184 -0.162156 +v 0.030656 0.045875 -0.160556 +v 0.032600 0.047009 -0.162156 +v 0.035706 0.046848 -0.160556 +v 0.036909 0.046108 -0.162156 +v 0.010672 -0.025556 -0.095289 +v 0.009310 -0.027156 -0.096176 +v 0.011352 -0.027156 -0.093038 +v 0.010217 -0.025556 -0.090228 +v 0.009845 -0.027156 -0.090121 +v 0.005174 -0.027156 -0.090685 +v 0.005728 -0.025556 -0.090391 +v 0.004717 -0.025556 -0.093524 +v 0.006108 -0.027156 -0.095921 +v 0.007093 -0.025556 -0.096318 +v 0.006499 -0.025556 -0.097934 +v 0.008294 -0.027156 -0.097983 +v 0.004971 -0.027156 -0.097126 +v 0.003069 -0.025556 -0.094231 +v 0.002932 -0.027156 -0.093376 +v 0.003831 -0.025556 -0.090031 +v 0.004729 -0.027156 -0.088956 +v 0.007297 -0.025556 -0.087998 +v 0.009686 -0.027156 -0.088168 +v 0.011417 -0.025556 -0.089137 +v 0.012607 -0.027156 -0.090930 +v 0.013071 -0.025556 -0.093342 +v 0.012734 -0.027156 -0.094946 +v 0.010043 -0.025556 -0.097791 +v 0.009235 -0.027156 -0.097947 +v 0.033961 -0.025556 -0.089520 +v 0.035914 -0.027156 -0.090307 +v 0.031946 -0.027156 -0.089980 +v 0.030726 -0.025556 -0.092143 +v 0.030967 -0.027156 -0.094580 +v 0.031947 -0.025556 -0.095839 +v 0.035536 -0.027156 -0.096374 +v 0.036615 -0.025556 -0.095401 +v 0.037026 -0.027156 -0.091451 +v 0.036637 -0.025556 -0.090809 +v 0.038520 -0.025556 -0.090518 +v 0.038078 -0.027156 -0.089774 +v 0.038619 -0.027156 -0.095205 +v 0.038165 -0.025556 -0.096042 +v 0.034570 -0.027156 -0.098170 +v 0.034389 -0.025556 -0.098036 +v 0.030135 -0.025556 -0.096481 +v 0.029972 -0.027156 -0.096157 +v 0.029233 -0.027156 -0.090684 +v 0.029085 -0.025556 -0.091574 +v 0.032845 -0.025556 -0.087880 +v 0.035025 -0.027156 -0.087921 +v 0.036911 -0.025556 -0.088944 +v 0.047775 0.047684 -0.160484 +v 0.038376 0.045717 -0.160748 +v 0.036021 0.047222 -0.160740 +v 0.047740 0.038051 -0.163430 +v 0.039129 0.039633 -0.162893 +v 0.036939 -0.025700 -0.087898 +v 0.039499 -0.027807 -0.095045 +v 0.047772 -0.025466 -0.087296 +v 0.047710 -0.028475 -0.097018 +v 0.006981 0.047544 -0.160615 +v 0.003108 0.045042 -0.161002 +v 0.000500 0.047486 -0.160690 +v 0.010662 0.046962 -0.160763 +v 0.030968 0.047031 -0.160719 +v 0.013706 0.043171 -0.161902 +v 0.003476 0.038416 -0.163226 +v 0.010068 0.036396 -0.163789 +v 0.000153 0.004280 -0.172497 +v 0.039452 0.007730 -0.171856 +v 0.028368 0.039837 -0.162830 +v 0.034721 0.036208 -0.163841 +v 0.042209 -0.010781 -0.089677 +v 0.047795 -0.011431 -0.089677 +v 0.047782 0.005323 -0.088486 +v 0.042127 0.003482 -0.088516 +v 0.042262 0.019425 -0.092708 +v 0.047836 0.020810 -0.093539 +v 0.047804 0.029454 -0.098714 +v 0.042173 0.029278 -0.098655 +v 0.042154 -0.036314 -0.164337 +v 0.047799 -0.036302 -0.164429 +v 0.047837 -0.042283 -0.154348 +v 0.042210 -0.042660 -0.153561 +v 0.047833 -0.046837 -0.135426 +v 0.042119 -0.046268 -0.139403 +v 0.042182 -0.044949 -0.122494 +v 0.047837 -0.042646 -0.116468 +v 0.042176 -0.036299 -0.105539 +v 0.047804 -0.036286 -0.105544 +v 0.000214 -0.025489 -0.087324 +v 0.002339 -0.027186 -0.092850 +v 0.004894 -0.025728 -0.088011 +v 0.031129 -0.025766 -0.088065 +v 0.011282 -0.025765 -0.088197 +v 0.028339 -0.027186 -0.092850 +v 0.000149 -0.037526 -0.130832 +v 0.010563 -0.028681 -0.098217 +v 0.004616 -0.028513 -0.097614 +v 0.039088 -0.036940 -0.127806 +v 0.035170 -0.028756 -0.098486 +v 0.030616 -0.028513 -0.097614 +v 0.013661 -0.027270 -0.093150 +v 0.042174 0.029453 -0.171275 +v 0.047811 0.029462 -0.171306 +v 0.042210 0.018560 -0.177660 +v 0.047833 0.010169 -0.180721 +v 0.042112 0.001998 -0.181578 +v 0.047840 -0.014134 -0.179616 +v 0.042210 -0.014802 -0.179104 +v 0.042170 -0.029460 -0.171296 +v 0.047798 -0.028673 -0.171647 +v 0.004058 -0.014028 -0.099893 +v 0.037969 -0.013656 -0.099872 +v 0.003995 -0.005170 -0.097588 +v 0.038001 -0.005152 -0.097588 +v 0.004004 0.005956 -0.097788 +v 0.038003 0.005988 -0.097793 +v 0.003999 0.016580 -0.101075 +v 0.038003 0.016629 -0.101100 +v 0.004023 0.026667 -0.108288 +v 0.038013 0.026850 -0.108440 +v 0.004006 0.033136 -0.117053 +v 0.037983 0.033202 -0.117198 +v 0.004024 0.036977 -0.127348 +v 0.037966 0.036578 -0.125956 +v 0.037972 0.037688 -0.135547 +v 0.004000 0.037417 -0.140123 +v 0.037958 0.036654 -0.143439 +v 0.004046 0.035124 -0.148676 +v 0.037989 0.035144 -0.149247 +v 0.039188 -0.000444 -0.172749 +v 0.038887 -0.010536 -0.171140 +v 0.000186 -0.011266 -0.170861 +v 0.039567 -0.020425 -0.166857 +v 0.000296 -0.025030 -0.163199 +v 0.039309 -0.028668 -0.159490 +v 0.039238 -0.034348 -0.150697 +v 0.000066 -0.034624 -0.150046 +v 0.039827 -0.036791 -0.143602 +v 0.039723 -0.037815 -0.135876 +v 0.042146 0.036262 -0.105552 +v 0.047811 0.036306 -0.105545 +v 0.042210 0.042563 -0.116238 +v 0.047880 0.044165 -0.120526 +v 0.042122 0.046539 -0.132391 +v 0.047791 0.046505 -0.133988 +v 0.047775 0.045332 -0.146189 +v 0.042332 0.045526 -0.147845 +v 0.041897 0.040959 -0.142299 +v 0.041860 0.039194 -0.149133 +v 0.041894 0.015783 -0.096311 +v 0.041904 0.027016 -0.103371 +v 0.042149 0.034127 -0.098451 +v 0.042184 0.036589 -0.100746 +v 0.041895 0.034899 -0.112226 +v 0.041876 -0.014145 -0.095747 +v 0.041983 -0.014533 -0.088582 +v 0.041890 0.041211 -0.127495 +v 0.041894 -0.002356 -0.093165 +v 0.046038 0.032247 -0.166729 +v 0.046038 0.035080 -0.167670 +v 0.046038 0.032188 -0.169963 +v 0.041668 -0.035742 -0.152144 +v 0.041911 0.034799 -0.167190 +v 0.041997 0.036413 -0.166489 +v 0.042110 0.034404 -0.171562 +v 0.042016 0.033022 -0.170279 +v 0.042237 -0.036679 -0.100976 +v 0.042034 -0.034683 -0.102888 +v 0.041860 -0.013771 -0.173158 +v 0.041767 -0.027854 -0.163776 +v 0.042084 -0.033645 -0.099902 +v 0.042198 -0.034463 -0.098498 +v 0.042120 -0.036563 -0.169036 +v 0.042202 -0.034278 -0.171611 +v 0.041904 -0.041007 -0.133965 +v 0.041794 0.005909 -0.174670 +v 0.033145 -0.025557 -0.098932 +v 0.002576 -0.025556 -0.095110 +v 0.009016 -0.025557 -0.098941 +v 0.047791 -0.016085 -0.087308 +v 0.000185 -0.015863 -0.087330 +v 0.000434 -0.013862 -0.096227 +v 0.000361 -0.000869 -0.093821 +v 0.000342 0.010927 -0.095427 +v 0.000297 0.021709 -0.100031 +v 0.000423 0.035024 -0.112957 +v 0.000301 0.040109 -0.126289 +v 0.000374 0.040919 -0.139211 +v 0.000421 0.038766 -0.148591 +v 0.013601 -0.025556 -0.093835 +v 0.039487 -0.025557 -0.094932 +v 0.028177 -0.025556 -0.093162 +v 0.037920 -0.015221 -0.099067 +v 0.004291 -0.015410 -0.098650 +v 0.040383 -0.015570 -0.087633 +v 0.000400 -0.015356 -0.095159 +v 0.040924 -0.015398 -0.095063 +v 0.031567 0.036802 -0.160557 +v 0.028399 0.041165 -0.160556 +v 0.039563 0.041513 -0.160556 +v 0.037399 0.037348 -0.160556 +v 0.000135 0.047784 -0.160100 +v 0.047773 0.047720 -0.151126 +v 0.000182 0.047652 -0.150856 +v 0.002399 0.041165 -0.160556 +v 0.005146 0.037103 -0.160556 +v 0.011243 0.037075 -0.160556 +v 0.013601 0.042835 -0.160556 +v 0.004148 0.035931 -0.150233 +v 0.037415 0.036505 -0.150479 +v 0.041067 0.047207 -0.150418 +v 0.000403 0.039671 -0.150302 +v 0.040911 0.039970 -0.150414 +v 0.047820 -0.034339 -0.171531 +v 0.047758 -0.036652 -0.169005 +v 0.047934 0.028962 -0.101311 +v 0.047848 0.039751 -0.114820 +v 0.047934 -0.028168 -0.169262 +v 0.047862 -0.015725 -0.176561 +v 0.047883 -0.036974 -0.159451 +v 0.047812 -0.042791 -0.146995 +v 0.047861 -0.044352 -0.134592 +v 0.047866 -0.000391 -0.179364 +v 0.047899 0.039792 -0.155313 +v 0.047857 -0.042158 -0.121337 +v 0.047856 -0.036084 -0.109015 +v 0.047921 0.026748 -0.170511 +v 0.047798 0.011863 -0.177803 +v 0.047781 -0.036634 -0.100837 +v 0.047686 -0.034340 -0.098365 +v 0.042028 -0.031750 -0.098599 +v 0.047763 0.034575 -0.098418 +v 0.047863 0.036578 -0.100846 +v 0.047757 0.036575 -0.169472 +v 0.042494 0.036313 -0.170097 +v 0.047702 0.033977 -0.171692 +v 0.044260 -0.034806 -0.102741 +v 0.044260 -0.031892 -0.103099 +v 0.041247 -0.031518 -0.102699 +v 0.044260 -0.031939 -0.100618 +v 0.044259 -0.034034 -0.100138 +v 0.041509 0.031721 -0.167096 +v 0.040739 -0.029528 -0.097873 +v 0.041276 -0.038809 -0.129111 +v 0.041081 -0.008081 -0.173097 +v 0.040649 0.037191 -0.164446 +v 0.047730 -0.030808 -0.098468 +v 0.047665 0.036586 -0.165613 +v 0.047885 0.044367 -0.131510 +v 0.038866 -0.033064 -0.094636 +v 0.038369 -0.033056 -0.090456 +v 0.036108 -0.033156 -0.090893 +v 0.035618 -0.033057 -0.097840 +v 0.034771 -0.033156 -0.095879 +v 0.031884 -0.033050 -0.097566 +v 0.035092 -0.033050 -0.087992 +v 0.031121 -0.033156 -0.092228 +v 0.029944 -0.033078 -0.089655 +v 0.029261 -0.033054 -0.094896 +v 0.036106 -0.007337 -0.095097 +v 0.033303 -0.007417 -0.095920 +v 0.030931 -0.007234 -0.093142 +v 0.036778 -0.007403 -0.091619 +v 0.033745 -0.007268 -0.089987 +v 0.036904 -0.027078 -0.091437 +v 0.033256 -0.027086 -0.089840 +v 0.030650 -0.027070 -0.093195 +v 0.033080 -0.027090 -0.096022 +v 0.036225 -0.027086 -0.095365 +v 0.034736 -0.027221 -0.087837 +v 0.039192 -0.027217 -0.092017 +v 0.030348 -0.027231 -0.089511 +v 0.036573 -0.027221 -0.097536 +v 0.030832 -0.027221 -0.097142 +v 0.028952 -0.027231 -0.092838 +v 0.031019 -0.028156 -0.093009 +v 0.033627 -0.028156 -0.095863 +v 0.034373 -0.028156 -0.090137 +v 0.036981 -0.028156 -0.092991 +v 0.032518 0.039414 -0.168156 +v 0.035181 0.037159 -0.168119 +v 0.031005 0.037868 -0.168057 +v 0.037421 0.045670 -0.168055 +v 0.039049 0.042579 -0.168061 +v 0.035482 0.044586 -0.168156 +v 0.028843 0.042030 -0.168061 +v 0.031074 0.045987 -0.168137 +v 0.034348 0.047065 -0.168047 +v 0.037917 0.038770 -0.168047 +v 0.032691 0.044623 -0.142222 +v 0.031081 0.042461 -0.142340 +v 0.031901 0.039887 -0.142328 +v 0.035882 0.039437 -0.142340 +v 0.036408 0.043990 -0.142316 +v 0.030730 0.041011 -0.162061 +v 0.032548 0.044851 -0.162088 +v 0.035478 0.044791 -0.162090 +v 0.037293 0.041820 -0.162078 +v 0.034671 0.038823 -0.162086 +v 0.029037 0.041060 -0.162231 +v 0.031207 0.037736 -0.162228 +v 0.030025 0.045278 -0.162225 +v 0.038923 0.042932 -0.162228 +v 0.037097 0.046049 -0.162228 +v 0.038205 0.039021 -0.162228 +v 0.034752 0.037046 -0.162228 +v 0.033611 0.046997 -0.162232 +v 0.034373 0.044863 -0.163156 +v 0.036879 0.041228 -0.163156 +v 0.031121 0.042772 -0.163156 +v 0.033627 0.039137 -0.163156 +v 0.047917 -0.013597 -0.092670 +v 0.047841 0.003938 -0.090623 +v 0.047944 -0.027395 -0.100063 +v 0.032594 0.107157 -0.123474 +v 0.033456 0.106755 -0.121312 +v 0.031965 0.107093 -0.122365 +v 0.032377 0.107363 -0.124811 +v 0.036365 0.106864 -0.125032 +v 0.033501 0.106634 -0.120453 +v 0.034049 0.107211 -0.125334 +v 0.034974 0.106397 -0.120133 +v 0.035772 0.106407 -0.121010 +v 0.036431 0.106961 -0.125832 +v 0.034466 0.107267 -0.126173 +v 0.035728 0.106313 -0.120257 +v 0.037949 0.106430 -0.123352 +v 0.037227 0.106462 -0.122870 +v 0.037512 0.106261 -0.121642 +v 0.037371 0.106726 -0.125002 +v 0.030420 0.091624 -0.124205 +v 0.031873 0.091239 -0.122761 +v 0.033121 0.091052 -0.122599 +v 0.034937 0.090946 -0.123617 +v 0.035506 0.091081 -0.125196 +v 0.034424 0.091514 -0.127374 +v 0.032411 0.091838 -0.127805 +v 0.030944 0.091924 -0.126982 +v 0.030250 0.091812 -0.125452 +v 0.030941 0.091787 -0.122825 +v 0.032487 0.103445 -0.121274 +v 0.031773 0.091611 -0.122330 +v 0.033319 0.103268 -0.120779 +v 0.034270 0.103115 -0.120576 +v 0.033213 0.091395 -0.122142 +v 0.033695 0.091343 -0.122236 +v 0.035241 0.103001 -0.120685 +v 0.036520 0.102927 -0.121402 +v 0.035308 0.091273 -0.123317 +v 0.036854 0.102931 -0.121766 +v 0.035965 0.091428 -0.125139 +v 0.037511 0.103086 -0.123588 +v 0.035653 0.091658 -0.126555 +v 0.037199 0.103316 -0.125004 +v 0.035087 0.091838 -0.127340 +v 0.036633 0.103496 -0.125789 +v 0.034716 0.091929 -0.127653 +v 0.033369 0.092178 -0.128180 +v 0.034915 0.103835 -0.126629 +v 0.032393 0.092303 -0.128149 +v 0.033939 0.103960 -0.126598 +v 0.030701 0.092401 -0.127200 +v 0.032247 0.104059 -0.125649 +v 0.029900 0.092272 -0.125435 +v 0.031446 0.103930 -0.123884 +v 0.029953 0.092136 -0.124461 +v 0.031500 0.103793 -0.122910 +v 0.030096 0.092055 -0.123996 +v 0.039383 0.103258 -0.126742 +v 0.028693 0.104230 -0.123390 +v 0.029747 0.103666 -0.120202 +v 0.032185 0.104497 -0.128880 +v 0.030014 0.104563 -0.127214 +v 0.029274 0.104507 -0.126051 +v 0.033067 0.102930 -0.117984 +v 0.034861 0.104209 -0.129384 +v 0.036844 0.103884 -0.128922 +v 0.036438 0.102514 -0.118215 +v 0.034423 0.102730 -0.117835 +v 0.038702 0.102418 -0.119751 +v 0.040179 0.102629 -0.122812 +v 0.028861 0.104771 -0.122463 +v 0.028780 0.104909 -0.123425 +v 0.029279 0.105157 -0.125784 +v 0.029495 0.105187 -0.126221 +v 0.032319 0.105157 -0.128812 +v 0.033714 0.105027 -0.129226 +v 0.034680 0.104909 -0.129304 +v 0.037019 0.104531 -0.128795 +v 0.037448 0.104445 -0.128579 +v 0.039502 0.103910 -0.126604 +v 0.040332 0.103436 -0.123867 +v 0.040292 0.103313 -0.122900 +v 0.038933 0.103084 -0.119826 +v 0.038602 0.103080 -0.119467 +v 0.037019 0.103140 -0.118340 +v 0.036573 0.103173 -0.118145 +v 0.033714 0.103506 -0.117795 +v 0.033239 0.103580 -0.117877 +v 0.030692 0.104089 -0.119164 +v 0.029745 0.104358 -0.120244 +v 0.031270 0.104419 -0.119008 +v 0.038482 0.103539 -0.119587 +v 0.038799 0.103543 -0.119930 +v 0.038490 0.104838 -0.120678 +v 0.038250 0.104829 -0.120371 +v 0.033586 0.104842 -0.118537 +v 0.032799 0.104979 -0.118779 +v 0.033537 0.106322 -0.119988 +v 0.033274 0.106373 -0.120107 +v 0.031726 0.105201 -0.119380 +v 0.031152 0.104902 -0.119456 +v 0.031192 0.106611 -0.121905 +v 0.030297 0.106113 -0.122098 +v 0.031031 0.106715 -0.122528 +v 0.030217 0.106174 -0.122475 +v 0.030723 0.106506 -0.125472 +v 0.030923 0.106524 -0.125805 +v 0.033993 0.106080 -0.128245 +v 0.034373 0.107093 -0.126621 +v 0.034662 0.107060 -0.126656 +v 0.034405 0.106032 -0.128295 +v 0.036613 0.106283 -0.127154 +v 0.036354 0.106796 -0.126363 +v 0.036611 0.106745 -0.126233 +v 0.037187 0.105583 -0.127691 +v 0.037536 0.105507 -0.127475 +v 0.037229 0.106156 -0.126809 +v 0.032421 0.105850 -0.123648 +v 0.033283 0.105448 -0.121486 +v 0.033875 0.105905 -0.125507 +v 0.036192 0.105557 -0.125206 +v 0.037053 0.105155 -0.123044 +v 0.035599 0.105101 -0.121184 +v 0.126880 -0.032968 -0.181461 +v 0.120239 -0.016066 -0.189411 +v 0.119395 -0.011192 -0.187106 +v 0.093104 0.024385 -0.203450 +v 0.000000 0.102973 -0.154371 +v 0.003317 0.102940 -0.154324 +v 0.036639 0.080923 -0.184610 +v 0.040273 0.080226 -0.183445 +v 0.036972 0.082097 -0.182440 +v 0.036665 0.082580 -0.181810 +v 0.037302 0.090477 -0.166692 +v 0.036958 0.081239 -0.183891 +v 0.037072 0.081639 -0.183150 +v 0.035527 0.083491 -0.180946 +v 0.033962 0.084121 -0.180788 +v 0.032387 0.084297 -0.181374 +v 0.031700 0.084186 -0.181937 +v 0.031225 0.083973 -0.182549 +v 0.030904 0.083648 -0.183264 +v 0.028457 0.082389 -0.186526 +v 0.030790 0.083243 -0.184001 +v 0.030890 0.082785 -0.184712 +v 0.031197 0.082307 -0.185344 +v 0.031765 0.081864 -0.185778 +v 0.036135 0.080712 -0.185259 +v 0.042733 0.068710 -0.199443 +v 0.032339 0.081416 -0.186218 +v 0.033908 0.080799 -0.186384 +v 0.035481 0.080618 -0.185795 +v 0.011164 0.084624 -0.188303 +v 0.011617 0.085444 -0.186898 +v 0.016299 0.083798 -0.188532 +v 0.011515 0.085893 -0.186184 +v 0.011199 0.086327 -0.185527 +v 0.010689 0.086717 -0.184972 +v 0.010021 0.087034 -0.184556 +v 0.009237 0.087256 -0.184306 +v 0.008397 0.087367 -0.184239 +v 0.006761 0.087233 -0.184661 +v 0.005218 0.086276 -0.186387 +v 0.005098 0.085840 -0.187108 +v 0.003947 0.084436 -0.189440 +v 0.005199 0.085393 -0.187822 +v 0.005518 0.084965 -0.188484 +v 0.005908 0.086911 -0.185282 +v 0.005553 0.086672 -0.185710 +v 0.006030 0.084585 -0.189044 +v 0.006699 0.084278 -0.189466 +v 0.008326 0.083957 -0.189788 +v 0.009959 0.084082 -0.189362 +v 0.062331 0.094086 -0.114355 +v 0.059496 0.095453 -0.118606 +v 0.048758 0.099374 -0.130163 +v 0.032738 0.103090 -0.140347 +v 0.026561 0.104052 -0.142875 +v 0.013838 0.105358 -0.146239 +v 0.000000 0.105832 -0.147444 +v 0.004378 0.060671 -0.221235 +v 0.018077 0.059964 -0.220229 +v 0.006327 0.059393 -0.222560 +v 0.033759 0.055616 -0.220313 +v 0.024756 0.057461 -0.221376 +v 0.042599 0.053163 -0.218978 +v 0.055420 0.048329 -0.216554 +v 0.082024 0.032227 -0.209618 +v 0.071042 0.040019 -0.212823 +v 0.090283 0.038747 -0.190021 +v 0.088970 0.026286 -0.207268 +v 0.102405 0.018229 -0.194686 +v 0.099625 0.015292 -0.202964 +v 0.111015 0.000184 -0.196803 +v 0.123966 -0.024582 -0.185316 +v 0.130543 -0.043625 -0.171227 +v 0.128934 -0.040594 -0.178135 +v 0.132282 -0.047713 -0.157939 +v 0.105039 0.042900 -0.106908 +v 0.105727 0.040612 -0.103222 +v 0.107539 0.034619 -0.097468 +v 0.106593 0.037745 -0.099994 +v 0.104307 0.045699 -0.121362 +v 0.104347 0.045638 -0.121006 +v 0.104326 0.045415 -0.115018 +v 0.104566 0.044506 -0.110869 +v 0.103131 0.047393 -0.127353 +v 0.098325 0.053720 -0.134123 +v 0.100341 0.051124 -0.132214 +v 0.102500 0.047159 -0.136365 +v 0.101880 0.049092 -0.130033 +v 0.103976 0.046201 -0.124286 +v 0.090287 0.063649 -0.136379 +v 0.093164 0.060148 -0.136326 +v 0.095962 0.056694 -0.135515 +v 0.078229 0.079445 -0.121037 +v 0.079263 0.078040 -0.123648 +v 0.080221 0.076357 -0.127919 +v 0.081416 0.074648 -0.130508 +v 0.082930 0.071083 -0.139079 +v 0.082993 0.072584 -0.132623 +v 0.084995 0.070081 -0.134370 +v 0.089535 0.059287 -0.153633 +v 0.087561 0.066950 -0.135721 +v 0.068732 0.088947 -0.114651 +v 0.071750 0.086224 -0.115490 +v 0.074428 0.083618 -0.116879 +v 0.076548 0.081390 -0.118691 +v 0.023505 0.083111 -0.187397 +v 0.024019 0.083376 -0.186776 +v 0.024463 0.084146 -0.185345 +v 0.024051 0.085059 -0.183990 +v 0.022893 0.085869 -0.183073 +v 0.021629 0.086290 -0.182823 +v 0.021298 0.086351 -0.182836 +v 0.020468 0.086423 -0.182999 +v 0.019693 0.086372 -0.183340 +v 0.019024 0.086203 -0.183835 +v 0.018508 0.085928 -0.184451 +v 0.018062 0.085146 -0.185876 +v 0.018476 0.084239 -0.187234 +v 0.018979 0.083815 -0.187771 +v 0.019637 0.083448 -0.188161 +v 0.020406 0.083164 -0.188377 +v 0.021234 0.082979 -0.188405 +v 0.022064 0.082906 -0.188241 +v 0.022838 0.082951 -0.187897 +v 0.057728 0.084476 -0.158147 +v 0.075398 0.076068 -0.146176 +v 0.081403 0.064669 -0.161295 +v 0.054760 0.065640 -0.195073 +v 0.066132 0.061834 -0.189654 +v 0.076712 0.057337 -0.183251 +v 0.086374 0.052203 -0.175940 +v 0.095003 0.046492 -0.167810 +v 0.099302 0.032778 -0.181522 +v 0.102495 0.040275 -0.158957 +v 0.107133 0.026279 -0.172269 +v 0.108761 0.033624 -0.149487 +v 0.113682 0.019327 -0.162371 +v 0.117234 0.004358 -0.174936 +v 0.113725 0.026619 -0.139514 +v 0.122585 -0.003192 -0.164186 +v 0.117328 0.019345 -0.129157 +v 0.126469 -0.011033 -0.153022 +v 0.108738 0.030973 -0.095454 +v 0.125991 -0.024138 -0.075700 +v 0.131383 -0.042315 -0.082210 +v 0.132121 -0.044325 -0.087652 +v 0.126853 -0.027296 -0.074944 +v 0.130161 -0.038449 -0.077929 +v 0.128553 -0.033147 -0.075340 +v 0.133326 -0.047400 -0.109594 +v 0.133048 -0.049553 -0.145187 +v 0.127432 -0.038575 -0.182548 +v 0.125334 -0.036271 -0.186776 +v 0.124930 -0.035901 -0.187386 +v 0.122414 -0.033596 -0.191187 +v 0.118642 -0.030849 -0.195573 +v 0.115008 -0.028871 -0.198892 +v 0.110965 -0.027355 -0.201776 +v 0.109812 -0.027042 -0.202458 +v 0.065936 -0.009906 -0.224830 +v 0.000000 0.009870 -0.237210 +v 0.036276 -0.000941 -0.233990 +v 0.041087 -0.002386 -0.232886 +v 0.018408 0.004402 -0.236707 +v -0.073131 0.017722 -0.231574 +v -0.090494 0.012499 -0.229865 +v -0.054960 0.020028 -0.233212 +v -0.042430 0.019759 -0.234283 +v -0.027536 0.017749 -0.235503 +v -0.036539 0.019267 -0.234776 +v -0.093790 0.010682 -0.229125 +v -0.092771 0.011457 -0.229431 +v -0.095309 0.009223 -0.228456 +v -0.101079 -0.001799 -0.221366 +v -0.099146 0.003747 -0.225441 +v -0.099036 0.003911 -0.225533 +v -0.095788 0.008762 -0.228245 +v -0.102352 -0.009852 -0.215003 +v -0.105772 -0.022632 -0.194537 +v -0.104858 -0.020349 -0.200296 +v -0.103961 -0.017339 -0.205785 +v -0.103103 -0.013696 -0.210826 +v -0.106841 -0.024318 -0.187686 +v -0.110449 -0.026360 -0.159145 +v -0.108079 -0.026494 -0.152638 +v -0.111931 -0.027074 -0.145487 +v -0.113436 -0.024442 -0.081413 +v -0.108756 -0.025544 -0.174745 +v -0.113675 -0.026658 -0.110546 +v -0.113391 -0.024159 -0.079881 +v -0.113364 -0.023642 -0.078411 +v -0.112162 -0.006847 -0.049710 +v -0.104292 0.072627 -0.053328 +v -0.111694 0.021464 -0.049935 +v -0.103183 0.075710 -0.053533 +v -0.101402 0.078502 -0.053978 +v -0.099268 0.080648 -0.054569 +v -0.096548 0.082397 -0.055364 +v -0.094378 0.083243 -0.056016 +v -0.070720 0.089693 -0.064225 +v -0.010930 0.101926 -0.097932 +v -0.012491 0.101020 -0.092963 +v -0.014769 0.100096 -0.088279 +v -0.017712 0.099173 -0.083984 +v -0.021255 0.098266 -0.080172 +v -0.025319 0.097393 -0.076926 +v -0.034634 0.095812 -0.072395 +v -0.029812 0.096570 -0.074315 +v 0.000000 0.104499 -0.113551 +v -0.001315 0.104484 -0.113465 +v -0.003992 0.104363 -0.112727 +v -0.006373 0.104125 -0.111282 +v -0.008259 0.103793 -0.109250 +v -0.009522 0.103390 -0.106769 +v 0.049796 0.099579 -0.113551 +v 0.033516 0.102282 -0.113551 +v 0.016795 0.103944 -0.113551 +v 0.053653 0.098527 -0.113804 +v 0.054572 0.098276 -0.113864 +v 0.059087 0.096211 -0.114151 +v 0.056363 0.097457 -0.113978 +v -0.045229 0.104893 -0.134662 +v 0.000000 0.107332 -0.136525 +v -0.094428 0.083666 -0.057765 +v -0.094428 0.083669 -0.057780 +v 0.008528 0.105253 -0.120084 +v 0.006900 0.105358 -0.120509 +v 0.006260 0.105437 -0.120987 +v 0.005708 0.105541 -0.121686 +v 0.005383 0.105647 -0.122462 +v 0.005273 0.105756 -0.123296 +v 0.005384 0.105858 -0.124132 +v 0.011671 0.105441 -0.122487 +v 0.011346 0.105355 -0.121708 +v 0.010155 0.105251 -0.120523 +v 0.005709 0.105948 -0.124910 +v 0.006902 0.106064 -0.126094 +v 0.006217 0.107228 -0.136250 +v 0.008530 0.106068 -0.126532 +v 0.011970 0.106946 -0.135496 +v 0.010157 0.105957 -0.126107 +v 0.016966 0.106543 -0.134411 +v 0.010831 0.105867 -0.125598 +v 0.011347 0.105763 -0.124933 +v 0.011672 0.105652 -0.124157 +v 0.011783 0.105542 -0.123323 +v 0.021515 0.104485 -0.120060 +v 0.019895 0.104671 -0.120476 +v 0.019157 0.104803 -0.121050 +v 0.018710 0.104913 -0.121645 +v 0.018387 0.105248 -0.124088 +v 0.018276 0.105151 -0.123253 +v 0.018386 0.105037 -0.122419 +v 0.032827 0.103335 -0.120523 +v 0.032176 0.103483 -0.121008 +v 0.024320 0.104447 -0.121702 +v 0.031647 0.103637 -0.121684 +v 0.031325 0.103777 -0.122456 +v 0.031326 0.103990 -0.124126 +v 0.023136 0.105110 -0.126094 +v 0.023807 0.104986 -0.125588 +v 0.024321 0.104856 -0.124926 +v 0.024644 0.104728 -0.124153 +v 0.031215 0.103897 -0.123289 +v 0.024754 0.104612 -0.123319 +v 0.024643 0.104516 -0.122483 +v 0.031648 0.104048 -0.124908 +v 0.022355 0.105217 -0.126408 +v 0.021517 0.105302 -0.126509 +v 0.017554 0.106495 -0.134283 +v 0.019897 0.105379 -0.126061 +v 0.018711 0.105322 -0.124869 +v 0.023134 0.104402 -0.120509 +v 0.032160 0.104067 -0.125583 +v 0.032829 0.104046 -0.126107 +v 0.034441 0.103888 -0.126565 +v 0.035503 0.103738 -0.126535 +v 0.035500 0.103723 -0.126403 +v 0.036052 0.103615 -0.126160 +v 0.037751 0.103228 -0.125034 +v 0.037231 0.103301 -0.125000 +v 0.037552 0.103157 -0.124229 +v 0.037661 0.103035 -0.123395 +v 0.037551 0.102944 -0.122559 +v 0.037229 0.102890 -0.121776 +v 0.036717 0.102877 -0.121099 +v 0.036050 0.102904 -0.120576 +v 0.034438 0.103067 -0.120117 +v -0.112219 -0.011057 -0.052111 +v -0.112154 -0.009956 -0.050846 +v -0.112136 -0.008498 -0.050014 +v -0.111467 0.034186 -0.059724 +v -0.104452 0.074277 -0.059731 +v -0.045973 0.103351 -0.145522 +v -0.090916 0.096004 -0.139797 +v -0.093618 0.077595 -0.176278 +v -0.093321 0.088150 -0.156362 +v -0.093234 0.089837 -0.152943 +v -0.092660 0.095616 -0.139493 +v -0.093058 0.063109 -0.198324 +v -0.091408 0.046426 -0.219006 +v -0.049860 0.055634 -0.221641 +v -0.048015 0.077040 -0.194799 +v -0.047881 0.087146 -0.178684 +v -0.111593 -0.013286 -0.159354 +v -0.104469 0.074601 -0.061132 +v -0.111310 0.045622 -0.078168 +v -0.113075 0.030935 -0.078233 +v -0.101283 0.008756 -0.220307 +v -0.100596 0.034991 -0.215738 +v -0.100635 0.037592 -0.214243 +v -0.101669 0.047241 -0.203297 +v -0.106150 0.045622 -0.179554 +v -0.102818 0.069584 -0.171589 +v -0.101917 0.088044 -0.131188 +v -0.101815 0.087438 -0.135783 +v -0.104299 0.082182 -0.096024 +v -0.107866 0.030935 -0.179974 +v -0.110627 0.030935 -0.159160 +v -0.111923 0.045622 -0.097890 +v -0.113504 0.030935 -0.118138 +v -0.114544 0.016186 -0.118259 +v -0.111654 0.016186 -0.159367 +v 0.040218 0.042462 -0.226289 +v 0.101829 -0.010039 -0.208665 +v 0.043823 0.008113 -0.231426 +v 0.029612 0.010513 -0.234380 +v 0.057676 0.004908 -0.227489 +v 0.091899 0.005276 -0.213519 +v 0.070884 0.013681 -0.221921 +v 0.088272 0.009836 -0.214899 +v 0.066354 0.029785 -0.221189 +v 0.059382 0.034101 -0.222754 +v 0.031960 0.044793 -0.227454 +v 0.023493 0.046537 -0.228399 +v 0.000000 0.048476 -0.229550 +v 0.006024 0.048353 -0.229472 +v -0.089876 0.034773 -0.226018 +v -0.076913 0.038448 -0.227042 +v -0.020549 0.019759 -0.235478 +v -0.091045 0.043994 -0.221378 +v -0.090310 0.038410 -0.224808 +v -0.090633 0.040964 -0.223515 +v -0.049257 0.050565 -0.225940 +v -0.014423 0.054159 -0.226811 +v 0.000000 0.052577 -0.227966 +v 0.114668 -0.023115 -0.199566 +v 0.118287 -0.019444 -0.195047 +v 0.122026 -0.027742 -0.191106 +v 0.006263 0.056174 -0.225554 +v 0.006161 0.052450 -0.227886 +v 0.024480 0.054274 -0.224400 +v 0.024054 0.050588 -0.226770 +v 0.041251 0.046428 -0.224563 +v 0.042055 0.050039 -0.222096 +v 0.054641 0.045267 -0.219804 +v 0.069938 0.037040 -0.216343 +v 0.068353 0.033580 -0.219171 +v 0.087478 0.023372 -0.211296 +v 0.085274 0.019976 -0.214542 +v 0.097922 0.012360 -0.207422 +v 0.095295 0.008955 -0.211010 +v 0.105998 -0.006376 -0.205901 +v 0.113974 -0.011023 -0.198634 +v 0.109135 -0.002885 -0.201850 +v 0.110592 -0.014592 -0.202921 +v -0.091997 0.097162 -0.129277 +v -0.092226 0.097163 -0.132922 +v -0.092431 0.096681 -0.136081 +v -0.090333 0.097465 -0.134531 +v -0.045679 0.104773 -0.140179 +v 0.000000 0.107241 -0.142075 +v 0.055532 0.097928 -0.115257 +v 0.045584 0.101402 -0.126002 +v 0.040965 0.102628 -0.129562 +v 0.024872 0.105620 -0.137825 +v 0.012963 0.106808 -0.140954 +v 0.006732 0.107124 -0.141775 +v -0.099123 0.009336 -0.224955 +v -0.095207 0.022265 -0.226622 +v -0.095331 0.009783 -0.228422 +v -0.094698 0.034664 -0.224252 +v -0.095614 0.044692 -0.217942 +v -0.095344 0.042606 -0.220005 +v -0.098684 0.040377 -0.217520 +v -0.095081 0.040009 -0.221900 +v -0.094903 0.037811 -0.223082 +v -0.098500 0.036616 -0.219910 +v -0.099855 0.091109 -0.137340 +v -0.096684 0.093943 -0.138625 +v -0.097714 0.075911 -0.175299 +v -0.100907 0.073131 -0.173672 +v -0.097209 0.061407 -0.197295 +v -0.100425 0.058670 -0.195464 +v -0.096527 0.094879 -0.135710 +v -0.094999 0.096127 -0.129110 +v -0.096368 0.095423 -0.129863 +v -0.098231 0.093885 -0.129736 +v -0.097678 0.094458 -0.129602 +v -0.101363 0.089624 -0.130634 +v -0.099824 0.092246 -0.130529 +v -0.096429 0.095340 -0.133005 +v -0.099757 0.092189 -0.132976 +v -0.102073 0.088349 -0.112301 +v -0.097438 0.082648 -0.057935 +v -0.103053 0.077397 -0.059026 +v -0.103349 0.081422 -0.076295 +v -0.102032 0.079031 -0.058665 +v -0.101055 0.084278 -0.075677 +v -0.100115 0.080954 -0.058262 +v -0.103691 0.076375 -0.059252 +v -0.102330 0.078498 -0.058723 +v -0.098830 0.081711 -0.058025 +v 0.019275 0.108532 -0.123492 +v 0.020142 0.108179 -0.121324 +v 0.018556 0.108507 -0.122889 +v 0.023745 0.108439 -0.125366 +v 0.023068 0.108445 -0.125022 +v 0.020187 0.108063 -0.120464 +v 0.020738 0.108664 -0.125341 +v 0.018810 0.108685 -0.124383 +v 0.022471 0.107960 -0.121004 +v 0.021158 0.108743 -0.126177 +v 0.022427 0.107864 -0.120251 +v 0.023934 0.108092 -0.122853 +v 0.024640 0.108135 -0.123583 +v 0.022178 0.108663 -0.126166 +v 0.024221 0.107908 -0.121623 +v 0.024597 0.108004 -0.122570 +v 0.018397 0.092774 -0.123498 +v 0.019829 0.092551 -0.122640 +v 0.021875 0.092446 -0.123021 +v 0.023076 0.092638 -0.125172 +v 0.021988 0.093010 -0.127359 +v 0.019963 0.093223 -0.127805 +v 0.018488 0.093228 -0.126994 +v 0.017790 0.093080 -0.125468 +v 0.018116 0.093167 -0.123181 +v 0.018462 0.093095 -0.122836 +v 0.019355 0.104821 -0.121288 +v 0.019298 0.092965 -0.122335 +v 0.020192 0.104691 -0.120787 +v 0.019768 0.092910 -0.122191 +v 0.021232 0.092804 -0.122226 +v 0.022125 0.104530 -0.120679 +v 0.022129 0.092789 -0.122631 +v 0.022854 0.092821 -0.123295 +v 0.023748 0.104547 -0.121747 +v 0.023515 0.093010 -0.125112 +v 0.024408 0.104737 -0.123564 +v 0.023202 0.093222 -0.126531 +v 0.024095 0.104948 -0.124983 +v 0.022633 0.093369 -0.127320 +v 0.023526 0.105095 -0.125773 +v 0.022259 0.093439 -0.127636 +v 0.020904 0.093614 -0.128174 +v 0.021798 0.105340 -0.126626 +v 0.019923 0.093685 -0.128150 +v 0.020817 0.105411 -0.126602 +v 0.019890 0.105438 -0.126271 +v 0.018221 0.093691 -0.127214 +v 0.019114 0.105418 -0.125666 +v 0.017415 0.093520 -0.125454 +v 0.018309 0.105247 -0.123906 +v 0.017469 0.093388 -0.124480 +v 0.018362 0.105114 -0.122933 +v 0.026291 0.105008 -0.126705 +v 0.015595 0.105301 -0.122751 +v 0.016237 0.104997 -0.120816 +v 0.019053 0.105849 -0.128898 +v 0.016125 0.105701 -0.126090 +v 0.018063 0.104593 -0.118815 +v 0.019938 0.104342 -0.117994 +v 0.021744 0.105708 -0.129382 +v 0.023738 0.105493 -0.128905 +v 0.023328 0.104111 -0.118199 +v 0.025606 0.104138 -0.119719 +v 0.027091 0.104427 -0.122768 +v 0.015671 0.105945 -0.122506 +v 0.015589 0.106079 -0.123468 +v 0.016092 0.106351 -0.125824 +v 0.016847 0.106458 -0.127070 +v 0.019150 0.106515 -0.128830 +v 0.021524 0.106397 -0.129303 +v 0.022010 0.106356 -0.129278 +v 0.023877 0.106148 -0.128778 +v 0.025802 0.105812 -0.127344 +v 0.026373 0.105666 -0.126567 +v 0.027168 0.105307 -0.124305 +v 0.027167 0.105116 -0.122857 +v 0.025800 0.104815 -0.119792 +v 0.025467 0.104794 -0.119436 +v 0.023426 0.104777 -0.118129 +v 0.022008 0.104839 -0.117784 +v 0.020073 0.105000 -0.117886 +v 0.018708 0.105169 -0.118378 +v 0.018286 0.105233 -0.118616 +v 0.016308 0.105657 -0.120692 +v 0.017379 0.106862 -0.127216 +v 0.025324 0.105246 -0.119557 +v 0.025642 0.105267 -0.119898 +v 0.026990 0.105673 -0.123756 +v 0.026951 0.105737 -0.124217 +v 0.025043 0.107871 -0.123672 +v 0.025067 0.107832 -0.123383 +v 0.025268 0.106542 -0.120650 +v 0.025027 0.106520 -0.120345 +v 0.023362 0.106862 -0.119452 +v 0.023032 0.106868 -0.119311 +v 0.023224 0.106088 -0.118753 +v 0.022011 0.106142 -0.118458 +v 0.020236 0.107753 -0.119998 +v 0.019972 0.107789 -0.120119 +v 0.019188 0.106424 -0.118966 +v 0.018827 0.106478 -0.119169 +v 0.016348 0.106666 -0.122062 +v 0.017029 0.107365 -0.122132 +v 0.017731 0.108006 -0.122558 +v 0.016948 0.107421 -0.122509 +v 0.017690 0.108051 -0.122879 +v 0.016182 0.106850 -0.123366 +v 0.018013 0.108278 -0.124778 +v 0.017658 0.107806 -0.125835 +v 0.018327 0.108329 -0.125348 +v 0.017325 0.107195 -0.126639 +v 0.018140 0.107850 -0.126444 +v 0.020568 0.108125 -0.127407 +v 0.021078 0.108563 -0.126626 +v 0.021368 0.108546 -0.126659 +v 0.021276 0.108085 -0.127517 +v 0.021991 0.108030 -0.127509 +v 0.024661 0.107095 -0.127208 +v 0.024971 0.107035 -0.126934 +v 0.025736 0.106542 -0.126546 +v 0.019175 0.107218 -0.123666 +v 0.020042 0.106865 -0.121497 +v 0.020638 0.107350 -0.125515 +v 0.022968 0.107131 -0.125195 +v 0.023834 0.106778 -0.123027 +v 0.022371 0.106646 -0.121178 +v 0.006145 0.109166 -0.123516 +v 0.007013 0.108856 -0.121342 +v 0.006244 0.108853 -0.121091 +v 0.009946 0.109213 -0.125026 +v 0.007612 0.109345 -0.125359 +v 0.006078 0.109366 -0.125064 +v 0.005679 0.109297 -0.124410 +v 0.008542 0.108644 -0.120142 +v 0.009347 0.108724 -0.121010 +v 0.010013 0.109313 -0.125826 +v 0.008033 0.109435 -0.126193 +v 0.010813 0.108903 -0.122852 +v 0.011521 0.108969 -0.123579 +v 0.010623 0.108677 -0.121019 +v 0.005293 0.093551 -0.124584 +v 0.006154 0.093336 -0.123153 +v 0.008139 0.093182 -0.122536 +v 0.009969 0.093239 -0.123531 +v 0.010544 0.093417 -0.125104 +v 0.010272 0.093585 -0.126335 +v 0.008694 0.093816 -0.127677 +v 0.007011 0.093876 -0.127646 +v 0.005946 0.093828 -0.126951 +v 0.005270 0.093832 -0.123538 +v 0.005719 0.105590 -0.122040 +v 0.005903 0.093713 -0.122793 +v 0.006741 0.093616 -0.122287 +v 0.007190 0.105374 -0.120789 +v 0.008193 0.093535 -0.122080 +v 0.008679 0.093527 -0.122168 +v 0.009127 0.105285 -0.120670 +v 0.010305 0.093600 -0.123229 +v 0.010753 0.105358 -0.121731 +v 0.010968 0.093806 -0.125043 +v 0.011416 0.105564 -0.123545 +v 0.010654 0.093999 -0.126465 +v 0.011102 0.105757 -0.124967 +v 0.010084 0.094122 -0.127257 +v 0.010532 0.105880 -0.125759 +v 0.008833 0.094266 -0.128013 +v 0.009281 0.106024 -0.126515 +v 0.007369 0.094333 -0.128102 +v 0.007818 0.106091 -0.126604 +v 0.006892 0.094335 -0.127976 +v 0.005663 0.094280 -0.127175 +v 0.006111 0.106038 -0.125677 +v 0.004855 0.094087 -0.125418 +v 0.005304 0.105845 -0.123920 +v 0.004909 0.093961 -0.124444 +v 0.013304 0.105891 -0.126678 +v 0.002528 0.105893 -0.123462 +v 0.002555 0.105979 -0.124147 +v 0.003590 0.105444 -0.120258 +v 0.006051 0.106452 -0.128911 +v 0.003116 0.106209 -0.126118 +v 0.004511 0.105280 -0.119246 +v 0.006934 0.105028 -0.117996 +v 0.011926 0.106137 -0.128192 +v 0.008748 0.106409 -0.129381 +v 0.013730 0.105205 -0.121416 +v 0.010332 0.104922 -0.118182 +v 0.009670 0.104922 -0.117985 +v 0.012614 0.105028 -0.119691 +v 0.014061 0.105621 -0.124779 +v 0.002553 0.106577 -0.123500 +v 0.002573 0.106638 -0.123984 +v 0.003057 0.106858 -0.125854 +v 0.003814 0.106987 -0.127097 +v 0.006123 0.107122 -0.128846 +v 0.006580 0.107127 -0.129016 +v 0.008502 0.107090 -0.129306 +v 0.012092 0.106786 -0.127996 +v 0.014075 0.106297 -0.124752 +v 0.014156 0.106234 -0.124275 +v 0.013792 0.105884 -0.121420 +v 0.012784 0.105711 -0.119766 +v 0.011699 0.105629 -0.118792 +v 0.010405 0.105592 -0.118115 +v 0.008983 0.105603 -0.117778 +v 0.007044 0.105691 -0.117890 +v 0.006118 0.105764 -0.118185 +v 0.003524 0.106133 -0.120305 +v 0.003055 0.106259 -0.121151 +v 0.011177 0.106060 -0.118693 +v 0.011572 0.106077 -0.118943 +v 0.013962 0.106595 -0.123728 +v 0.013923 0.106656 -0.124189 +v 0.011934 0.108720 -0.123664 +v 0.011958 0.108682 -0.123375 +v 0.013695 0.106945 -0.123224 +v 0.010911 0.108388 -0.120749 +v 0.010694 0.108371 -0.120554 +v 0.009354 0.106894 -0.118520 +v 0.009249 0.107664 -0.119114 +v 0.008941 0.106902 -0.118457 +v 0.008536 0.107681 -0.119037 +v 0.006102 0.108221 -0.120157 +v 0.005617 0.108294 -0.120588 +v 0.004566 0.107720 -0.120760 +v 0.005212 0.108374 -0.121094 +v 0.004192 0.107820 -0.121435 +v 0.003135 0.107426 -0.123838 +v 0.003191 0.107480 -0.124275 +v 0.003856 0.108170 -0.124078 +v 0.004193 0.108298 -0.125186 +v 0.004002 0.107708 -0.126310 +v 0.004568 0.108370 -0.125864 +v 0.004262 0.107744 -0.126667 +v 0.007674 0.109255 -0.126585 +v 0.007962 0.109251 -0.126641 +v 0.010546 0.108038 -0.127858 +v 0.009958 0.109138 -0.126357 +v 0.010217 0.109112 -0.126224 +v 0.011600 0.107914 -0.127198 +v 0.006095 0.107848 -0.123684 +v 0.006962 0.107538 -0.121510 +v 0.007561 0.108027 -0.125526 +v 0.009896 0.107895 -0.125194 +v 0.010763 0.107585 -0.123020 +v 0.009297 0.107407 -0.121178 +v 0.032884 0.085071 -0.186142 +v 0.033455 0.086122 -0.184106 +v 0.032144 0.085379 -0.186034 +v 0.032146 0.085778 -0.185377 +v 0.032681 0.084512 -0.187169 +v 0.036695 0.083623 -0.186465 +v 0.033396 0.086586 -0.183374 +v 0.034504 0.083821 -0.187321 +v 0.034774 0.086531 -0.182722 +v 0.035647 0.085923 -0.183249 +v 0.036855 0.083173 -0.187118 +v 0.035005 0.083295 -0.187915 +v 0.037267 0.084674 -0.184428 +v 0.037395 0.085303 -0.183325 +v 0.037934 0.083786 -0.185527 +v 0.028372 0.072944 -0.177246 +v 0.029597 0.073509 -0.175657 +v 0.031592 0.073148 -0.175174 +v 0.032646 0.072558 -0.175575 +v 0.033381 0.071601 -0.176750 +v 0.032600 0.070575 -0.178858 +v 0.030715 0.070656 -0.179744 +v 0.029206 0.071338 -0.179437 +v 0.028357 0.072287 -0.178335 +v 0.028774 0.073936 -0.176217 +v 0.031977 0.083693 -0.182153 +v 0.029515 0.074077 -0.175585 +v 0.032719 0.083834 -0.181522 +v 0.031352 0.073826 -0.175006 +v 0.034556 0.083583 -0.180942 +v 0.031817 0.073660 -0.175027 +v 0.033032 0.072979 -0.175491 +v 0.036236 0.082736 -0.181427 +v 0.033881 0.071876 -0.176846 +v 0.037085 0.081633 -0.182782 +v 0.033750 0.071147 -0.178114 +v 0.036954 0.080904 -0.184050 +v 0.033299 0.070806 -0.178920 +v 0.036503 0.080562 -0.184856 +v 0.032980 0.070692 -0.179278 +v 0.031747 0.070614 -0.180072 +v 0.034950 0.080371 -0.186008 +v 0.030805 0.070785 -0.180300 +v 0.034008 0.080542 -0.186236 +v 0.033537 0.080689 -0.186249 +v 0.029064 0.071572 -0.179946 +v 0.032268 0.081329 -0.185882 +v 0.031929 0.081590 -0.185636 +v 0.028084 0.072667 -0.178675 +v 0.031287 0.082424 -0.184612 +v 0.028019 0.073192 -0.177846 +v 0.031223 0.082949 -0.183782 +v 0.028101 0.073426 -0.177419 +v 0.028687 0.082748 -0.185482 +v 0.028732 0.084160 -0.183137 +v 0.032593 0.079565 -0.188606 +v 0.030306 0.080821 -0.187775 +v 0.031967 0.079835 -0.188499 +v 0.029563 0.084934 -0.181416 +v 0.032143 0.085407 -0.179246 +v 0.038124 0.079001 -0.186548 +v 0.034567 0.078978 -0.188504 +v 0.035413 0.084751 -0.178560 +v 0.037773 0.083551 -0.179257 +v 0.039670 0.080191 -0.183758 +v 0.039558 0.081639 -0.181437 +v 0.028860 0.084604 -0.183686 +v 0.028780 0.084373 -0.184108 +v 0.028854 0.083346 -0.185757 +v 0.029538 0.082242 -0.187203 +v 0.030409 0.081437 -0.188056 +v 0.032376 0.080287 -0.188884 +v 0.034683 0.079547 -0.188856 +v 0.036507 0.079338 -0.188215 +v 0.038427 0.079594 -0.186758 +v 0.039778 0.080589 -0.184394 +v 0.039877 0.080813 -0.183972 +v 0.039786 0.082094 -0.181916 +v 0.039651 0.082369 -0.181536 +v 0.038113 0.083995 -0.179694 +v 0.037751 0.084244 -0.179480 +v 0.035642 0.085289 -0.178901 +v 0.034244 0.085705 -0.178971 +v 0.032404 0.085959 -0.179546 +v 0.031971 0.085966 -0.179769 +v 0.029815 0.085525 -0.181657 +v 0.029326 0.085209 -0.182440 +v 0.034782 0.080026 -0.188854 +v 0.039323 0.083161 -0.182808 +v 0.039510 0.082820 -0.182511 +v 0.039388 0.083070 -0.182166 +v 0.039061 0.083634 -0.182173 +v 0.038629 0.084197 -0.182847 +v 0.038096 0.084804 -0.182138 +v 0.037871 0.084999 -0.181938 +v 0.034985 0.086149 -0.180239 +v 0.035182 0.086413 -0.181667 +v 0.034583 0.086250 -0.180289 +v 0.034243 0.086608 -0.181854 +v 0.033009 0.086468 -0.180781 +v 0.031620 0.086371 -0.181690 +v 0.031923 0.086478 -0.182060 +v 0.032316 0.086530 -0.183023 +v 0.031265 0.085756 -0.184862 +v 0.029511 0.084891 -0.184503 +v 0.030327 0.085304 -0.184851 +v 0.031185 0.085439 -0.185426 +v 0.030295 0.085110 -0.185187 +v 0.029474 0.084670 -0.184886 +v 0.032128 0.084428 -0.187124 +v 0.030557 0.083288 -0.187331 +v 0.030779 0.083054 -0.187596 +v 0.032458 0.084102 -0.187480 +v 0.034649 0.082955 -0.188184 +v 0.034332 0.080130 -0.188927 +v 0.034930 0.082877 -0.188160 +v 0.034874 0.080506 -0.188817 +v 0.032525 0.083977 -0.185477 +v 0.033096 0.085028 -0.183441 +v 0.034145 0.082728 -0.186656 +v 0.036336 0.082529 -0.185799 +v 0.036908 0.083580 -0.183763 +v 0.035288 0.084830 -0.182584 +v 0.019665 0.087281 -0.188219 +v 0.020248 0.088391 -0.186218 +v 0.018888 0.087663 -0.187857 +v 0.019466 0.088588 -0.186160 +v 0.019459 0.086700 -0.189233 +v 0.024271 0.085923 -0.188887 +v 0.023565 0.086162 -0.188735 +v 0.021324 0.086166 -0.189477 +v 0.021597 0.088921 -0.184905 +v 0.022490 0.088387 -0.185475 +v 0.021335 0.085784 -0.190095 +v 0.024148 0.087272 -0.186734 +v 0.024929 0.086823 -0.187204 +v 0.022835 0.085609 -0.189878 +v 0.024279 0.087918 -0.185640 +v 0.016601 0.074666 -0.179435 +v 0.017576 0.075481 -0.177783 +v 0.019134 0.075552 -0.177148 +v 0.021045 0.074868 -0.177621 +v 0.021798 0.073970 -0.178830 +v 0.021001 0.072866 -0.180892 +v 0.019073 0.072778 -0.181679 +v 0.017529 0.073331 -0.181296 +v 0.018400 0.085284 -0.185349 +v 0.016744 0.075745 -0.178426 +v 0.018790 0.085698 -0.184545 +v 0.017396 0.076029 -0.177745 +v 0.017799 0.076114 -0.177473 +v 0.019845 0.086067 -0.183593 +v 0.019193 0.076111 -0.177011 +v 0.019678 0.076025 -0.176989 +v 0.021724 0.085978 -0.183108 +v 0.021398 0.075322 -0.177558 +v 0.023443 0.085275 -0.183678 +v 0.022267 0.074286 -0.178952 +v 0.024313 0.084239 -0.185072 +v 0.022134 0.073540 -0.180210 +v 0.024180 0.083493 -0.186330 +v 0.021673 0.073155 -0.180990 +v 0.023719 0.083108 -0.187110 +v 0.021347 0.073012 -0.181332 +v 0.020086 0.072823 -0.182060 +v 0.022132 0.082776 -0.188180 +v 0.019122 0.072911 -0.182240 +v 0.021168 0.082864 -0.188359 +v 0.017341 0.073548 -0.181798 +v 0.019387 0.083502 -0.187918 +v 0.018752 0.083986 -0.187342 +v 0.016337 0.074565 -0.180481 +v 0.018383 0.084518 -0.186601 +v 0.016270 0.075089 -0.179651 +v 0.016354 0.075331 -0.179229 +v 0.026541 0.082391 -0.187332 +v 0.015636 0.085704 -0.185590 +v 0.019722 0.081753 -0.190650 +v 0.016512 0.083499 -0.188883 +v 0.016916 0.083148 -0.189320 +v 0.017037 0.087115 -0.182827 +v 0.018635 0.087543 -0.181596 +v 0.022416 0.081285 -0.190510 +v 0.024310 0.081392 -0.189702 +v 0.022598 0.087232 -0.180777 +v 0.020569 0.087584 -0.180883 +v 0.025014 0.086234 -0.181593 +v 0.026991 0.084091 -0.184417 +v 0.026842 0.084466 -0.183857 +v 0.015747 0.086249 -0.185974 +v 0.015744 0.085485 -0.187218 +v 0.016524 0.084168 -0.189098 +v 0.018155 0.082998 -0.190456 +v 0.019886 0.082305 -0.191006 +v 0.022269 0.081867 -0.190921 +v 0.024508 0.081973 -0.190000 +v 0.024903 0.082060 -0.189727 +v 0.026681 0.082983 -0.187632 +v 0.027100 0.083652 -0.186402 +v 0.027005 0.084935 -0.184348 +v 0.026230 0.085982 -0.182905 +v 0.025291 0.086702 -0.182047 +v 0.022763 0.087785 -0.181131 +v 0.021332 0.088080 -0.181129 +v 0.020853 0.088136 -0.181199 +v 0.017103 0.087658 -0.183230 +v 0.026832 0.083839 -0.187003 +v 0.026929 0.084063 -0.186605 +v 0.026142 0.085044 -0.187471 +v 0.025306 0.086557 -0.187042 +v 0.025974 0.086148 -0.186371 +v 0.025295 0.086712 -0.186794 +v 0.021555 0.088643 -0.182465 +v 0.021512 0.088946 -0.184424 +v 0.020738 0.088720 -0.182613 +v 0.021227 0.088967 -0.184486 +v 0.019136 0.088708 -0.185079 +v 0.018715 0.088512 -0.185537 +v 0.016370 0.086367 -0.187165 +v 0.016406 0.086130 -0.187538 +v 0.018000 0.085442 -0.189547 +v 0.018250 0.084064 -0.190283 +v 0.018784 0.084879 -0.190200 +v 0.018597 0.083871 -0.190480 +v 0.021214 0.085374 -0.190333 +v 0.022074 0.085216 -0.190303 +v 0.024609 0.083493 -0.189819 +v 0.025491 0.083819 -0.188995 +v 0.019436 0.086165 -0.187533 +v 0.020019 0.087276 -0.185532 +v 0.021095 0.085051 -0.188791 +v 0.023336 0.085047 -0.188049 +v 0.023919 0.086157 -0.186048 +v 0.022261 0.087272 -0.184790 +v 0.005389 0.087619 -0.190022 +v 0.005971 0.087864 -0.189597 +v 0.005257 0.088612 -0.188558 +v 0.006577 0.089108 -0.187683 +v 0.010630 0.086907 -0.190534 +v 0.009917 0.087086 -0.190342 +v 0.007640 0.086853 -0.190926 +v 0.008853 0.089341 -0.187099 +v 0.006692 0.086697 -0.191256 +v 0.009865 0.086566 -0.191121 +v 0.009219 0.089673 -0.186567 +v 0.009910 0.089454 -0.186821 +v 0.007449 0.089788 -0.186581 +v 0.010523 0.088330 -0.188428 +v 0.009167 0.086420 -0.191411 +v 0.011148 0.088506 -0.188103 +v 0.004774 0.075641 -0.179813 +v 0.006054 0.076496 -0.178408 +v 0.008521 0.076407 -0.178283 +v 0.009711 0.075687 -0.179231 +v 0.009840 0.074520 -0.180953 +v 0.009142 0.073960 -0.181858 +v 0.007183 0.073663 -0.182505 +v 0.005622 0.074087 -0.182036 +v 0.004750 0.074932 -0.180869 +v 0.005108 0.076742 -0.178875 +v 0.005796 0.086569 -0.185483 +v 0.005880 0.077044 -0.178345 +v 0.006805 0.077185 -0.178040 +v 0.007494 0.087012 -0.184648 +v 0.007788 0.077150 -0.177990 +v 0.008476 0.086976 -0.184598 +v 0.008726 0.076942 -0.178201 +v 0.009524 0.076583 -0.178652 +v 0.010213 0.086410 -0.185260 +v 0.010100 0.076110 -0.179295 +v 0.010394 0.075572 -0.180065 +v 0.011082 0.085399 -0.186673 +v 0.010376 0.075024 -0.180882 +v 0.011064 0.084850 -0.187490 +v 0.010249 0.074764 -0.181282 +v 0.009776 0.074305 -0.182013 +v 0.010465 0.084132 -0.188621 +v 0.009443 0.074118 -0.182326 +v 0.008624 0.073854 -0.182804 +v 0.009312 0.083681 -0.189412 +v 0.008364 0.083584 -0.189655 +v 0.007183 0.073775 -0.183072 +v 0.007871 0.083601 -0.189680 +v 0.005382 0.074265 -0.182531 +v 0.006071 0.084091 -0.189139 +v 0.004376 0.075240 -0.181185 +v 0.005064 0.085067 -0.187793 +v 0.004315 0.075791 -0.180372 +v 0.005003 0.085618 -0.186980 +v 0.004403 0.076058 -0.179966 +v 0.013320 0.083668 -0.189013 +v 0.002259 0.085271 -0.187782 +v 0.002937 0.087099 -0.184992 +v 0.006388 0.082265 -0.191822 +v 0.003151 0.083783 -0.189901 +v 0.005989 0.088442 -0.182677 +v 0.008434 0.082038 -0.191947 +v 0.009118 0.082053 -0.191853 +v 0.011043 0.082368 -0.191184 +v 0.009380 0.088404 -0.182381 +v 0.011820 0.087597 -0.183326 +v 0.013753 0.084378 -0.187913 +v 0.013654 0.085909 -0.185645 +v 0.002324 0.086575 -0.187047 +v 0.002311 0.085760 -0.188260 +v 0.003087 0.084442 -0.190140 +v 0.003353 0.084201 -0.190471 +v 0.005566 0.083052 -0.191949 +v 0.006476 0.082814 -0.192208 +v 0.009369 0.082626 -0.192186 +v 0.010298 0.082745 -0.191912 +v 0.011165 0.082951 -0.191516 +v 0.013385 0.084256 -0.189343 +v 0.013568 0.084500 -0.188962 +v 0.013739 0.086369 -0.186164 +v 0.013602 0.086637 -0.185780 +v 0.012021 0.088069 -0.183815 +v 0.011649 0.088262 -0.183567 +v 0.009469 0.088954 -0.182765 +v 0.007050 0.089111 -0.182784 +v 0.006110 0.089014 -0.183025 +v 0.004811 0.088706 -0.183619 +v 0.002901 0.087583 -0.185489 +v 0.013356 0.084907 -0.189133 +v 0.010651 0.083316 -0.191781 +v 0.010227 0.083227 -0.191957 +v 0.013495 0.085149 -0.188759 +v 0.012665 0.086265 -0.189221 +v 0.011316 0.088909 -0.185429 +v 0.011018 0.089064 -0.185231 +v 0.007351 0.089741 -0.184606 +v 0.006601 0.089664 -0.184799 +v 0.005159 0.089126 -0.184432 +v 0.004804 0.088995 -0.184664 +v 0.005254 0.089303 -0.185476 +v 0.003750 0.088134 -0.187371 +v 0.002898 0.087189 -0.187547 +v 0.003582 0.087718 -0.188007 +v 0.002858 0.086945 -0.187915 +v 0.003726 0.086635 -0.189602 +v 0.004480 0.087241 -0.189756 +v 0.004584 0.087063 -0.190009 +v 0.004402 0.085825 -0.190737 +v 0.005498 0.085161 -0.191610 +v 0.005967 0.086003 -0.191441 +v 0.006240 0.085891 -0.191579 +v 0.006028 0.085465 -0.191693 +v 0.009941 0.084664 -0.191887 +v 0.010632 0.084828 -0.191570 +v 0.010947 0.086542 -0.190611 +v 0.012227 0.085684 -0.190132 +v 0.011274 0.086796 -0.190198 +v 0.005893 0.086762 -0.188856 +v 0.006500 0.088006 -0.186943 +v 0.007563 0.085752 -0.190185 +v 0.009839 0.085985 -0.189601 +v 0.010446 0.087229 -0.187688 +v 0.008776 0.088240 -0.186359 +v 0.032594 0.107157 0.123474 +v 0.033456 0.106755 0.121312 +v 0.031965 0.107093 0.122365 +v 0.032377 0.107363 0.124811 +v 0.036365 0.106864 0.125032 +v 0.033501 0.106634 0.120453 +v 0.034049 0.107211 0.125334 +v 0.035772 0.106407 0.121010 +v 0.036431 0.106961 0.125832 +v 0.034466 0.107267 0.126173 +v 0.035728 0.106313 0.120257 +v 0.037949 0.106430 0.123352 +v 0.037227 0.106462 0.122870 +v 0.037512 0.106261 0.121642 +v 0.030420 0.091624 0.124205 +v 0.031873 0.091239 0.122761 +v 0.033121 0.091052 0.122599 +v 0.034937 0.090946 0.123617 +v 0.035506 0.091081 0.125196 +v 0.035236 0.091280 0.126423 +v 0.033669 0.091663 0.127743 +v 0.031612 0.091905 0.127512 +v 0.030473 0.091891 0.126271 +v 0.030941 0.091787 0.122825 +v 0.032487 0.103445 0.121274 +v 0.031773 0.091611 0.122330 +v 0.033319 0.103268 0.120779 +v 0.033213 0.091395 0.122142 +v 0.033695 0.091343 0.122236 +v 0.035241 0.103001 0.120685 +v 0.035308 0.091273 0.123317 +v 0.036854 0.102931 0.121766 +v 0.035965 0.091428 0.125139 +v 0.037511 0.103086 0.123588 +v 0.035653 0.091658 0.126555 +v 0.037199 0.103316 0.125004 +v 0.035087 0.091838 0.127340 +v 0.036633 0.103496 0.125789 +v 0.036262 0.103586 0.126102 +v 0.035845 0.103675 0.126350 +v 0.033846 0.092101 0.128078 +v 0.033369 0.092178 0.128180 +v 0.034915 0.103835 0.126629 +v 0.032393 0.092303 0.128149 +v 0.033939 0.103960 0.126598 +v 0.031472 0.092380 0.127811 +v 0.030701 0.092401 0.127200 +v 0.032247 0.104059 0.125649 +v 0.030158 0.092364 0.126380 +v 0.029900 0.092272 0.125435 +v 0.031446 0.103930 0.123884 +v 0.029953 0.092136 0.124461 +v 0.031500 0.103793 0.122910 +v 0.030096 0.092055 0.123996 +v 0.039383 0.103258 0.126742 +v 0.028693 0.104230 0.123390 +v 0.029747 0.103666 0.120202 +v 0.032185 0.104497 0.128880 +v 0.030014 0.104563 0.127214 +v 0.029274 0.104507 0.126051 +v 0.033067 0.102930 0.117984 +v 0.037451 0.103763 0.128615 +v 0.034861 0.104209 0.129384 +v 0.036844 0.103884 0.128922 +v 0.036438 0.102514 0.118215 +v 0.038702 0.102418 0.119751 +v 0.040179 0.102629 0.122812 +v 0.028861 0.104771 0.122463 +v 0.028780 0.104909 0.123425 +v 0.029279 0.105157 0.125784 +v 0.029495 0.105187 0.126221 +v 0.032319 0.105157 0.128812 +v 0.033714 0.105027 0.129226 +v 0.034680 0.104909 0.129304 +v 0.037019 0.104531 0.128795 +v 0.037448 0.104445 0.128579 +v 0.039502 0.103910 0.126604 +v 0.040332 0.103436 0.123867 +v 0.040292 0.103313 0.122900 +v 0.038933 0.103084 0.119826 +v 0.038602 0.103080 0.119467 +v 0.037019 0.103140 0.118340 +v 0.036573 0.103173 0.118145 +v 0.033714 0.103506 0.117795 +v 0.033239 0.103580 0.117877 +v 0.030692 0.104089 0.119164 +v 0.029745 0.104358 0.120244 +v 0.031270 0.104419 0.119008 +v 0.038482 0.103539 0.119587 +v 0.038799 0.103543 0.119930 +v 0.038490 0.104838 0.120678 +v 0.038250 0.104829 0.120371 +v 0.033586 0.104842 0.118537 +v 0.032799 0.104979 0.118779 +v 0.033537 0.106322 0.119988 +v 0.033274 0.106373 0.120107 +v 0.031726 0.105201 0.119380 +v 0.031152 0.104902 0.119456 +v 0.031192 0.106611 0.121905 +v 0.030297 0.106113 0.122098 +v 0.031031 0.106715 0.122528 +v 0.030217 0.106174 0.122475 +v 0.030723 0.106506 0.125472 +v 0.030923 0.106524 0.125805 +v 0.033993 0.106080 0.128245 +v 0.034373 0.107093 0.126621 +v 0.034662 0.107060 0.126656 +v 0.034405 0.106032 0.128295 +v 0.036613 0.106283 0.127154 +v 0.036354 0.106796 0.126363 +v 0.036611 0.106745 0.126233 +v 0.037187 0.105583 0.127691 +v 0.037536 0.105507 0.127475 +v 0.037229 0.106156 0.126809 +v 0.032421 0.105850 0.123648 +v 0.033283 0.105448 0.121486 +v 0.033875 0.105905 0.125507 +v 0.036192 0.105557 0.125206 +v 0.037053 0.105155 0.123044 +v 0.035599 0.105101 0.121184 +v 0.126880 -0.032968 0.181461 +v 0.120239 -0.016066 0.189411 +v 0.119395 -0.011192 0.187106 +v 0.093104 0.024385 0.203450 +v 0.000000 0.102973 0.154371 +v 0.003317 0.102940 0.154324 +v 0.036639 0.080923 0.184610 +v 0.040273 0.080226 0.183445 +v 0.036972 0.082097 0.182440 +v 0.036665 0.082580 0.181810 +v 0.037302 0.090477 0.166692 +v 0.036958 0.081239 0.183891 +v 0.037072 0.081639 0.183150 +v 0.035527 0.083491 0.180946 +v 0.033962 0.084121 0.180788 +v 0.032387 0.084297 0.181374 +v 0.031700 0.084186 0.181937 +v 0.031225 0.083973 0.182549 +v 0.030904 0.083648 0.183264 +v 0.028457 0.082389 0.186526 +v 0.030790 0.083243 0.184001 +v 0.030890 0.082785 0.184712 +v 0.031197 0.082307 0.185344 +v 0.031765 0.081864 0.185778 +v 0.036135 0.080712 0.185259 +v 0.042733 0.068710 0.199443 +v 0.032339 0.081416 0.186218 +v 0.033908 0.080799 0.186384 +v 0.035481 0.080618 0.185795 +v 0.011164 0.084624 0.188303 +v 0.011617 0.085444 0.186898 +v 0.016299 0.083798 0.188532 +v 0.011515 0.085893 0.186184 +v 0.011199 0.086327 0.185527 +v 0.010689 0.086717 0.184972 +v 0.010021 0.087034 0.184556 +v 0.009237 0.087256 0.184306 +v 0.008397 0.087367 0.184239 +v 0.006761 0.087233 0.184661 +v 0.005218 0.086276 0.186387 +v 0.005098 0.085840 0.187108 +v 0.003947 0.084436 0.189440 +v 0.005199 0.085393 0.187822 +v 0.005518 0.084965 0.188484 +v 0.005908 0.086911 0.185282 +v 0.005553 0.086672 0.185710 +v 0.006030 0.084585 0.189044 +v 0.006699 0.084278 0.189466 +v 0.008326 0.083957 0.189788 +v 0.009959 0.084082 0.189362 +v 0.062331 0.094086 0.114355 +v 0.059496 0.095453 0.118606 +v 0.048758 0.099374 0.130163 +v 0.032738 0.103090 0.140347 +v 0.026561 0.104052 0.142875 +v 0.013838 0.105358 0.146239 +v 0.000000 0.105832 0.147444 +v 0.004378 0.060671 0.221235 +v 0.018077 0.059964 0.220229 +v 0.006327 0.059393 0.222560 +v 0.033759 0.055616 0.220313 +v 0.024756 0.057461 0.221376 +v 0.042599 0.053163 0.218978 +v 0.055420 0.048329 0.216554 +v 0.082024 0.032227 0.209618 +v 0.071042 0.040019 0.212823 +v 0.090283 0.038747 0.190021 +v 0.088970 0.026286 0.207268 +v 0.102405 0.018229 0.194686 +v 0.099625 0.015292 0.202964 +v 0.111015 0.000184 0.196803 +v 0.123966 -0.024582 0.185316 +v 0.130543 -0.043625 0.171227 +v 0.128934 -0.040594 0.178135 +v 0.132282 -0.047713 0.157939 +v 0.105039 0.042900 0.106908 +v 0.105727 0.040612 0.103222 +v 0.107539 0.034619 0.097468 +v 0.106593 0.037745 0.099994 +v 0.104307 0.045699 0.121362 +v 0.104347 0.045638 0.121006 +v 0.104326 0.045415 0.115018 +v 0.104566 0.044506 0.110869 +v 0.103131 0.047393 0.127353 +v 0.098325 0.053720 0.134123 +v 0.100341 0.051124 0.132214 +v 0.102500 0.047159 0.136365 +v 0.101880 0.049092 0.130033 +v 0.103976 0.046201 0.124286 +v 0.090287 0.063649 0.136379 +v 0.093164 0.060148 0.136326 +v 0.095962 0.056694 0.135515 +v 0.078229 0.079445 0.121037 +v 0.079263 0.078040 0.123648 +v 0.080221 0.076357 0.127919 +v 0.081416 0.074648 0.130508 +v 0.082930 0.071083 0.139079 +v 0.082993 0.072584 0.132623 +v 0.084995 0.070081 0.134370 +v 0.089535 0.059287 0.153633 +v 0.087561 0.066950 0.135721 +v 0.068732 0.088947 0.114651 +v 0.071750 0.086224 0.115490 +v 0.074428 0.083618 0.116879 +v 0.076548 0.081390 0.118691 +v 0.023505 0.083111 0.187397 +v 0.024019 0.083376 0.186776 +v 0.024463 0.084146 0.185345 +v 0.024051 0.085059 0.183990 +v 0.022893 0.085869 0.183073 +v 0.021629 0.086290 0.182823 +v 0.021298 0.086351 0.182836 +v 0.020468 0.086423 0.182999 +v 0.019693 0.086372 0.183340 +v 0.019024 0.086203 0.183835 +v 0.018508 0.085928 0.184451 +v 0.018062 0.085146 0.185876 +v 0.018476 0.084239 0.187234 +v 0.018979 0.083815 0.187771 +v 0.019637 0.083448 0.188161 +v 0.020406 0.083164 0.188377 +v 0.021234 0.082979 0.188405 +v 0.022064 0.082906 0.188241 +v 0.022838 0.082951 0.187897 +v 0.057728 0.084476 0.158147 +v 0.075398 0.076068 0.146176 +v 0.081403 0.064669 0.161295 +v 0.054760 0.065640 0.195073 +v 0.066132 0.061834 0.189654 +v 0.076712 0.057337 0.183251 +v 0.086374 0.052203 0.175940 +v 0.095003 0.046492 0.167810 +v 0.099302 0.032778 0.181522 +v 0.102495 0.040275 0.158957 +v 0.107133 0.026279 0.172269 +v 0.108761 0.033624 0.149487 +v 0.113682 0.019327 0.162371 +v 0.117234 0.004358 0.174936 +v 0.113725 0.026619 0.139514 +v 0.122585 -0.003192 0.164186 +v 0.117328 0.019345 0.129157 +v 0.126469 -0.011033 0.153022 +v 0.108738 0.030973 0.095454 +v 0.125991 -0.024138 0.075700 +v 0.131383 -0.042315 0.082210 +v 0.132121 -0.044325 0.087652 +v 0.126853 -0.027296 0.074944 +v 0.130161 -0.038449 0.077929 +v 0.128553 -0.033147 0.075340 +v 0.133326 -0.047400 0.109594 +v 0.133048 -0.049553 0.145187 +v 0.127432 -0.038575 0.182548 +v 0.125334 -0.036271 0.186776 +v 0.124930 -0.035901 0.187386 +v 0.122414 -0.033596 0.191187 +v 0.118642 -0.030849 0.195573 +v 0.115008 -0.028871 0.198892 +v 0.110965 -0.027355 0.201776 +v 0.109812 -0.027042 0.202458 +v 0.065936 -0.009906 0.224830 +v 0.000000 0.009870 0.237210 +v 0.036276 -0.000941 0.233990 +v 0.041087 -0.002386 0.232886 +v 0.018408 0.004402 0.236707 +v -0.073131 0.017722 0.231574 +v -0.090494 0.012499 0.229865 +v -0.054960 0.020028 0.233212 +v -0.042430 0.019759 0.234283 +v -0.027536 0.017749 0.235503 +v -0.036539 0.019267 0.234776 +v -0.093790 0.010682 0.229125 +v -0.092771 0.011457 0.229431 +v -0.095309 0.009223 0.228456 +v -0.101079 -0.001799 0.221366 +v -0.099146 0.003747 0.225441 +v -0.099036 0.003911 0.225533 +v -0.095788 0.008762 0.228245 +v -0.102352 -0.009852 0.215003 +v -0.105772 -0.022632 0.194537 +v -0.104858 -0.020349 0.200296 +v -0.103961 -0.017339 0.205785 +v -0.103103 -0.013696 0.210826 +v -0.106841 -0.024318 0.187686 +v -0.110449 -0.026360 0.159145 +v -0.108079 -0.026494 0.152638 +v -0.111931 -0.027074 0.145487 +v -0.113436 -0.024442 0.081413 +v -0.108756 -0.025544 0.174745 +v -0.113675 -0.026658 0.110546 +v -0.113391 -0.024159 0.079881 +v -0.113364 -0.023642 0.078411 +v -0.112162 -0.006847 0.049710 +v -0.104292 0.072627 0.053328 +v -0.111694 0.021464 0.049935 +v -0.103183 0.075710 0.053533 +v -0.101402 0.078502 0.053978 +v -0.099268 0.080648 0.054569 +v -0.096548 0.082397 0.055364 +v -0.094378 0.083243 0.056016 +v -0.070720 0.089693 0.064225 +v -0.010930 0.101926 0.097932 +v -0.012491 0.101020 0.092963 +v -0.014769 0.100096 0.088279 +v -0.017712 0.099173 0.083984 +v -0.021255 0.098266 0.080172 +v -0.025319 0.097393 0.076926 +v -0.034634 0.095812 0.072395 +v -0.029812 0.096570 0.074315 +v 0.000000 0.104499 0.113551 +v -0.001315 0.104484 0.113465 +v -0.003992 0.104363 0.112727 +v -0.006373 0.104125 0.111282 +v -0.008259 0.103793 0.109250 +v -0.009522 0.103390 0.106769 +v 0.049796 0.099579 0.113551 +v 0.033516 0.102282 0.113551 +v 0.016795 0.103944 0.113551 +v 0.053653 0.098527 0.113804 +v 0.054572 0.098276 0.113864 +v 0.059087 0.096211 0.114151 +v 0.056363 0.097457 0.113978 +v -0.045229 0.104893 0.134662 +v 0.000000 0.107332 0.136525 +v -0.094428 0.083666 0.057765 +v -0.094428 0.083669 0.057780 +v 0.008528 0.105253 0.120084 +v 0.006900 0.105358 0.120509 +v 0.006260 0.105437 0.120987 +v 0.005708 0.105541 0.121686 +v 0.005383 0.105647 0.122462 +v 0.005273 0.105756 0.123296 +v 0.005384 0.105858 0.124132 +v 0.011671 0.105441 0.122487 +v 0.011346 0.105355 0.121708 +v 0.010155 0.105251 0.120523 +v 0.005709 0.105948 0.124910 +v 0.006902 0.106064 0.126094 +v 0.006217 0.107228 0.136250 +v 0.008530 0.106068 0.126532 +v 0.011970 0.106946 0.135496 +v 0.010157 0.105957 0.126107 +v 0.016966 0.106543 0.134411 +v 0.010831 0.105867 0.125598 +v 0.011347 0.105763 0.124933 +v 0.011672 0.105652 0.124157 +v 0.011783 0.105542 0.123323 +v 0.021515 0.104485 0.120060 +v 0.019895 0.104671 0.120476 +v 0.019157 0.104803 0.121050 +v 0.018710 0.104913 0.121645 +v 0.018387 0.105248 0.124088 +v 0.018276 0.105151 0.123253 +v 0.018386 0.105037 0.122419 +v 0.032827 0.103335 0.120523 +v 0.032176 0.103483 0.121008 +v 0.024320 0.104447 0.121702 +v 0.031647 0.103637 0.121684 +v 0.031325 0.103777 0.122456 +v 0.031326 0.103990 0.124126 +v 0.023136 0.105110 0.126094 +v 0.023807 0.104986 0.125588 +v 0.024321 0.104856 0.124926 +v 0.024644 0.104728 0.124153 +v 0.031215 0.103897 0.123289 +v 0.024754 0.104612 0.123319 +v 0.024643 0.104516 0.122483 +v 0.031648 0.104048 0.124908 +v 0.022355 0.105217 0.126408 +v 0.021517 0.105302 0.126509 +v 0.017554 0.106495 0.134283 +v 0.019897 0.105379 0.126061 +v 0.018711 0.105322 0.124869 +v 0.023134 0.104402 0.120509 +v 0.032160 0.104067 0.125583 +v 0.032829 0.104046 0.126107 +v 0.034441 0.103888 0.126565 +v 0.035503 0.103738 0.126535 +v 0.035500 0.103723 0.126403 +v 0.036052 0.103615 0.126160 +v 0.037751 0.103228 0.125034 +v 0.037231 0.103301 0.125000 +v 0.037552 0.103157 0.124229 +v 0.037661 0.103035 0.123395 +v 0.037551 0.102944 0.122559 +v 0.037229 0.102890 0.121776 +v 0.036717 0.102877 0.121099 +v 0.036050 0.102904 0.120576 +v 0.034438 0.103067 0.120117 +v -0.112219 -0.011057 0.052111 +v -0.112154 -0.009956 0.050846 +v -0.112136 -0.008498 0.050014 +v -0.111467 0.034186 0.059724 +v -0.104452 0.074277 0.059731 +v -0.045973 0.103351 0.145522 +v -0.090916 0.096004 0.139797 +v -0.093618 0.077595 0.176278 +v -0.093321 0.088150 0.156362 +v -0.093234 0.089837 0.152943 +v -0.092660 0.095616 0.139493 +v -0.093058 0.063109 0.198324 +v -0.091408 0.046426 0.219006 +v -0.049860 0.055634 0.221641 +v -0.048015 0.077040 0.194799 +v -0.047881 0.087146 0.178684 +v -0.111593 -0.013286 0.159354 +v -0.104469 0.074601 0.061132 +v -0.111310 0.045622 0.078168 +v -0.113075 0.030935 0.078233 +v -0.101283 0.008756 0.220307 +v -0.100596 0.034991 0.215738 +v -0.100635 0.037592 0.214243 +v -0.101669 0.047241 0.203297 +v -0.106150 0.045622 0.179554 +v -0.102818 0.069584 0.171589 +v -0.101917 0.088044 0.131188 +v -0.101815 0.087438 0.135783 +v -0.104299 0.082182 0.096024 +v -0.107866 0.030935 0.179974 +v -0.110627 0.030935 0.159160 +v -0.111923 0.045622 0.097890 +v -0.113504 0.030935 0.118138 +v -0.114544 0.016186 0.118259 +v -0.111654 0.016186 0.159367 +v 0.040218 0.042462 0.226289 +v 0.101829 -0.010039 0.208665 +v 0.043823 0.008113 0.231426 +v 0.029612 0.010513 0.234380 +v 0.057676 0.004908 0.227489 +v 0.091899 0.005276 0.213519 +v 0.070884 0.013681 0.221921 +v 0.088272 0.009836 0.214899 +v 0.066354 0.029785 0.221189 +v 0.059382 0.034101 0.222754 +v 0.031960 0.044793 0.227454 +v 0.023493 0.046537 0.228399 +v 0.000000 0.048476 0.229550 +v 0.006024 0.048353 0.229472 +v -0.089876 0.034773 0.226018 +v -0.076913 0.038448 0.227042 +v -0.020549 0.019759 0.235478 +v -0.091045 0.043994 0.221378 +v -0.090310 0.038410 0.224808 +v -0.090633 0.040964 0.223515 +v -0.049257 0.050565 0.225940 +v -0.014423 0.054159 0.226811 +v 0.000000 0.052577 0.227966 +v 0.114668 -0.023115 0.199566 +v 0.118287 -0.019444 0.195047 +v 0.122026 -0.027742 0.191106 +v 0.006263 0.056174 0.225554 +v 0.006161 0.052450 0.227886 +v 0.024480 0.054274 0.224400 +v 0.024054 0.050588 0.226770 +v 0.041251 0.046428 0.224563 +v 0.042055 0.050039 0.222096 +v 0.054641 0.045267 0.219804 +v 0.069938 0.037040 0.216343 +v 0.068353 0.033580 0.219171 +v 0.087478 0.023372 0.211296 +v 0.085274 0.019976 0.214542 +v 0.097922 0.012360 0.207422 +v 0.095295 0.008955 0.211010 +v 0.105998 -0.006376 0.205901 +v 0.113974 -0.011023 0.198634 +v 0.109135 -0.002885 0.201850 +v 0.110592 -0.014592 0.202921 +v -0.091997 0.097162 0.129277 +v -0.092226 0.097163 0.132922 +v -0.092431 0.096681 0.136081 +v -0.090333 0.097465 0.134531 +v -0.045679 0.104773 0.140179 +v 0.000000 0.107241 0.142075 +v 0.055532 0.097928 0.115257 +v 0.045584 0.101402 0.126002 +v 0.040965 0.102628 0.129562 +v 0.024872 0.105620 0.137825 +v 0.012963 0.106808 0.140954 +v 0.006732 0.107124 0.141775 +v -0.099123 0.009336 0.224955 +v -0.095207 0.022265 0.226622 +v -0.095331 0.009783 0.228422 +v -0.094698 0.034664 0.224252 +v -0.095614 0.044692 0.217942 +v -0.095344 0.042606 0.220005 +v -0.098684 0.040377 0.217520 +v -0.095081 0.040009 0.221900 +v -0.094903 0.037811 0.223082 +v -0.098500 0.036616 0.219910 +v -0.099855 0.091109 0.137340 +v -0.096684 0.093943 0.138625 +v -0.097714 0.075911 0.175299 +v -0.100907 0.073131 0.173672 +v -0.097209 0.061407 0.197295 +v -0.100425 0.058670 0.195464 +v -0.096527 0.094879 0.135710 +v -0.094999 0.096127 0.129110 +v -0.096368 0.095423 0.129863 +v -0.098231 0.093885 0.129736 +v -0.097678 0.094458 0.129602 +v -0.101363 0.089624 0.130634 +v -0.099824 0.092246 0.130529 +v -0.096429 0.095340 0.133005 +v -0.099757 0.092189 0.132976 +v -0.102073 0.088349 0.112301 +v -0.097438 0.082648 0.057935 +v -0.103053 0.077397 0.059026 +v -0.103349 0.081422 0.076295 +v -0.102032 0.079031 0.058665 +v -0.101055 0.084278 0.075677 +v -0.100115 0.080954 0.058262 +v -0.103691 0.076375 0.059252 +v -0.102330 0.078498 0.058723 +v -0.098830 0.081711 0.058025 +v 0.019275 0.108532 0.123492 +v 0.020142 0.108179 0.121324 +v 0.018556 0.108507 0.122889 +v 0.019057 0.108281 0.121465 +v 0.023745 0.108439 0.125366 +v 0.023068 0.108445 0.125022 +v 0.020187 0.108063 0.120464 +v 0.020738 0.108664 0.125341 +v 0.018810 0.108685 0.124383 +v 0.021668 0.107906 0.120133 +v 0.022471 0.107960 0.121004 +v 0.021158 0.108743 0.126177 +v 0.022427 0.107864 0.120251 +v 0.023934 0.108092 0.122853 +v 0.024640 0.108135 0.123583 +v 0.024221 0.107908 0.121623 +v 0.017961 0.092902 0.124220 +v 0.019042 0.092653 0.122953 +v 0.020677 0.092480 0.122593 +v 0.022504 0.092474 0.123597 +v 0.023076 0.092638 0.125172 +v 0.021988 0.093010 0.127359 +v 0.019963 0.093223 0.127805 +v 0.018488 0.093228 0.126994 +v 0.017790 0.093080 0.125468 +v 0.018462 0.093095 0.122836 +v 0.019355 0.104821 0.121288 +v 0.018859 0.093027 0.122552 +v 0.019298 0.092965 0.122335 +v 0.020192 0.104691 0.120787 +v 0.020747 0.092829 0.122136 +v 0.021232 0.092804 0.122226 +v 0.022125 0.104530 0.120679 +v 0.022854 0.092821 0.123295 +v 0.023748 0.104547 0.121747 +v 0.023515 0.093010 0.125112 +v 0.024408 0.104737 0.123564 +v 0.023202 0.093222 0.126531 +v 0.024095 0.104948 0.124983 +v 0.022633 0.093369 0.127320 +v 0.023526 0.105095 0.125773 +v 0.022259 0.093439 0.127636 +v 0.022733 0.105231 0.126340 +v 0.020904 0.093614 0.128174 +v 0.021798 0.105340 0.126626 +v 0.019923 0.093685 0.128150 +v 0.020817 0.105411 0.126602 +v 0.018221 0.093691 0.127214 +v 0.019114 0.105418 0.125666 +v 0.017415 0.093520 0.125454 +v 0.018309 0.105247 0.123906 +v 0.017469 0.093388 0.124480 +v 0.018362 0.105114 0.122933 +v 0.017613 0.093315 0.124014 +v 0.026291 0.105008 0.126705 +v 0.015595 0.105301 0.122751 +v 0.016237 0.104997 0.120816 +v 0.019053 0.105849 0.128898 +v 0.016125 0.105701 0.126090 +v 0.018063 0.104593 0.118815 +v 0.019938 0.104342 0.117994 +v 0.024348 0.105405 0.128593 +v 0.025894 0.105111 0.127261 +v 0.021744 0.105708 0.129382 +v 0.023738 0.105493 0.128905 +v 0.023328 0.104111 0.118199 +v 0.025606 0.104138 0.119719 +v 0.027091 0.104427 0.122768 +v 0.015671 0.105945 0.122506 +v 0.015589 0.106079 0.123468 +v 0.016092 0.106351 0.125824 +v 0.016847 0.106458 0.127070 +v 0.019150 0.106515 0.128830 +v 0.021524 0.106397 0.129303 +v 0.022010 0.106356 0.129278 +v 0.023877 0.106148 0.128778 +v 0.025802 0.105812 0.127344 +v 0.026373 0.105666 0.126567 +v 0.027168 0.105307 0.124305 +v 0.027167 0.105116 0.122857 +v 0.025800 0.104815 0.119792 +v 0.025467 0.104794 0.119436 +v 0.023426 0.104777 0.118129 +v 0.022008 0.104839 0.117784 +v 0.020073 0.105000 0.117886 +v 0.018708 0.105169 0.118378 +v 0.018286 0.105233 0.118616 +v 0.016308 0.105657 0.120692 +v 0.017379 0.106862 0.127216 +v 0.025324 0.105246 0.119557 +v 0.025642 0.105267 0.119898 +v 0.026990 0.105673 0.123756 +v 0.026951 0.105737 0.124217 +v 0.025043 0.107871 0.123672 +v 0.025067 0.107832 0.123383 +v 0.025268 0.106542 0.120650 +v 0.025027 0.106520 0.120345 +v 0.023362 0.106862 0.119452 +v 0.023032 0.106868 0.119311 +v 0.023224 0.106088 0.118753 +v 0.022011 0.106142 0.118458 +v 0.020236 0.107753 0.119998 +v 0.019972 0.107789 0.120119 +v 0.019188 0.106424 0.118966 +v 0.018827 0.106478 0.119169 +v 0.016348 0.106666 0.122062 +v 0.017029 0.107365 0.122132 +v 0.017731 0.108006 0.122558 +v 0.016948 0.107421 0.122509 +v 0.017690 0.108051 0.122879 +v 0.016182 0.106850 0.123366 +v 0.018013 0.108278 0.124778 +v 0.017658 0.107806 0.125835 +v 0.018327 0.108329 0.125348 +v 0.017325 0.107195 0.126639 +v 0.018140 0.107850 0.126444 +v 0.020568 0.108125 0.127407 +v 0.021078 0.108563 0.126626 +v 0.021368 0.108546 0.126659 +v 0.021276 0.108085 0.127517 +v 0.021991 0.108030 0.127509 +v 0.024661 0.107095 0.127208 +v 0.024971 0.107035 0.126934 +v 0.025736 0.106542 0.126546 +v 0.019175 0.107218 0.123666 +v 0.020042 0.106865 0.121497 +v 0.020638 0.107350 0.125515 +v 0.022968 0.107131 0.125195 +v 0.023834 0.106778 0.123027 +v 0.022371 0.106646 0.121178 +v 0.006145 0.109166 0.123516 +v 0.007013 0.108856 0.121342 +v 0.006244 0.108853 0.121091 +v 0.009946 0.109213 0.125026 +v 0.007612 0.109345 0.125359 +v 0.005679 0.109297 0.124410 +v 0.008542 0.108644 0.120142 +v 0.009347 0.108724 0.121010 +v 0.010013 0.109313 0.125826 +v 0.008033 0.109435 0.126193 +v 0.010813 0.108903 0.122852 +v 0.011521 0.108969 0.123579 +v 0.011330 0.109070 0.124317 +v 0.010623 0.108677 0.121019 +v 0.005606 0.093439 0.123799 +v 0.006881 0.093253 0.122715 +v 0.008139 0.093182 0.122536 +v 0.009969 0.093239 0.123531 +v 0.010544 0.093417 0.125104 +v 0.009454 0.093739 0.127298 +v 0.007851 0.093863 0.127797 +v 0.006262 0.093853 0.127238 +v 0.005246 0.093661 0.125429 +v 0.005270 0.093832 0.123538 +v 0.005719 0.105590 0.122040 +v 0.006750 0.105419 0.121008 +v 0.006741 0.093616 0.122287 +v 0.007190 0.105374 0.120789 +v 0.008193 0.093535 0.122080 +v 0.008679 0.093527 0.122168 +v 0.009127 0.105285 0.120670 +v 0.010305 0.093600 0.123229 +v 0.010753 0.105358 0.121731 +v 0.011028 0.105400 0.122139 +v 0.010968 0.093806 0.125043 +v 0.011416 0.105564 0.123545 +v 0.010654 0.093999 0.126465 +v 0.011102 0.105757 0.124967 +v 0.010084 0.094122 0.127257 +v 0.010532 0.105880 0.125759 +v 0.009710 0.094177 0.127575 +v 0.008833 0.094266 0.128013 +v 0.009281 0.106024 0.126515 +v 0.007860 0.094321 0.128151 +v 0.007369 0.094333 0.128102 +v 0.007818 0.106091 0.126604 +v 0.006028 0.094308 0.127506 +v 0.005663 0.094280 0.127175 +v 0.006111 0.106038 0.125677 +v 0.004855 0.094087 0.125418 +v 0.005304 0.105845 0.123920 +v 0.013304 0.105891 0.126678 +v 0.002528 0.105893 0.123462 +v 0.003590 0.105444 0.120258 +v 0.006051 0.106452 0.128911 +v 0.003116 0.106209 0.126118 +v 0.005056 0.105206 0.118828 +v 0.006934 0.105028 0.117996 +v 0.011926 0.106137 0.128192 +v 0.008748 0.106409 0.129381 +v 0.013730 0.105205 0.121416 +v 0.010332 0.104922 0.118182 +v 0.012614 0.105028 0.119691 +v 0.014061 0.105621 0.124779 +v 0.002553 0.106577 0.123500 +v 0.002573 0.106638 0.123984 +v 0.003057 0.106858 0.125854 +v 0.003814 0.106987 0.127097 +v 0.006123 0.107122 0.128846 +v 0.006580 0.107127 0.129016 +v 0.008502 0.107090 0.129306 +v 0.012092 0.106786 0.127996 +v 0.014075 0.106297 0.124752 +v 0.014156 0.106234 0.124275 +v 0.013792 0.105884 0.121420 +v 0.012784 0.105711 0.119766 +v 0.011699 0.105629 0.118792 +v 0.010405 0.105592 0.118115 +v 0.008983 0.105603 0.117778 +v 0.007044 0.105691 0.117890 +v 0.006118 0.105764 0.118185 +v 0.003524 0.106133 0.120305 +v 0.003055 0.106259 0.121151 +v 0.011177 0.106060 0.118693 +v 0.011572 0.106077 0.118943 +v 0.013962 0.106595 0.123728 +v 0.013923 0.106656 0.124189 +v 0.011934 0.108720 0.123664 +v 0.011958 0.108682 0.123375 +v 0.013695 0.106945 0.123224 +v 0.010911 0.108388 0.120749 +v 0.010694 0.108371 0.120554 +v 0.009354 0.106894 0.118520 +v 0.009249 0.107664 0.119114 +v 0.008941 0.106902 0.118457 +v 0.008536 0.107681 0.119037 +v 0.006102 0.108221 0.120157 +v 0.005617 0.108294 0.120588 +v 0.004566 0.107720 0.120760 +v 0.005212 0.108374 0.121094 +v 0.004192 0.107820 0.121435 +v 0.003135 0.107426 0.123838 +v 0.003191 0.107480 0.124275 +v 0.003856 0.108170 0.124078 +v 0.004193 0.108298 0.125186 +v 0.004002 0.107708 0.126310 +v 0.004568 0.108370 0.125864 +v 0.004262 0.107744 0.126667 +v 0.007674 0.109255 0.126585 +v 0.007962 0.109251 0.126641 +v 0.010546 0.108038 0.127858 +v 0.009958 0.109138 0.126357 +v 0.010217 0.109112 0.126224 +v 0.011600 0.107914 0.127198 +v 0.006095 0.107848 0.123684 +v 0.006962 0.107538 0.121510 +v 0.007561 0.108027 0.125526 +v 0.009896 0.107895 0.125194 +v 0.010763 0.107585 0.123020 +v 0.009297 0.107407 0.121178 +v 0.032884 0.085071 0.186142 +v 0.033455 0.086122 0.184106 +v 0.032146 0.085778 0.185377 +v 0.032681 0.084512 0.187169 +v 0.036695 0.083623 0.186465 +v 0.033396 0.086586 0.183374 +v 0.034504 0.083821 0.187321 +v 0.035647 0.085923 0.183249 +v 0.036855 0.083173 0.187118 +v 0.035005 0.083295 0.187915 +v 0.035996 0.086167 0.182661 +v 0.036665 0.085835 0.182845 +v 0.037267 0.084674 0.184428 +v 0.037395 0.085303 0.183325 +v 0.037934 0.083786 0.185527 +v 0.028372 0.072944 0.177246 +v 0.029597 0.073509 0.175657 +v 0.030778 0.073402 0.175196 +v 0.032646 0.072558 0.175575 +v 0.033381 0.071601 0.176750 +v 0.032600 0.070575 0.178858 +v 0.030715 0.070656 0.179744 +v 0.028669 0.071802 0.178964 +v 0.028774 0.073936 0.176217 +v 0.031977 0.083693 0.182153 +v 0.029515 0.074077 0.175585 +v 0.032719 0.083834 0.181522 +v 0.030878 0.073953 0.175053 +v 0.031352 0.073826 0.175006 +v 0.034556 0.083583 0.180942 +v 0.033032 0.072979 0.175491 +v 0.036236 0.082736 0.181427 +v 0.033881 0.071876 0.176846 +v 0.037085 0.081633 0.182782 +v 0.033750 0.071147 0.178114 +v 0.036954 0.080904 0.184050 +v 0.033299 0.070806 0.178920 +v 0.036503 0.080562 0.184856 +v 0.032980 0.070692 0.179278 +v 0.031747 0.070614 0.180072 +v 0.034950 0.080371 0.186008 +v 0.030805 0.070785 0.180300 +v 0.034008 0.080542 0.186236 +v 0.029879 0.071115 0.180257 +v 0.033082 0.080872 0.186193 +v 0.029064 0.071572 0.179946 +v 0.032268 0.081329 0.185882 +v 0.028444 0.072107 0.179400 +v 0.031648 0.081864 0.185336 +v 0.028084 0.072667 0.178675 +v 0.031287 0.082424 0.184612 +v 0.028019 0.073192 0.177846 +v 0.031223 0.082949 0.183782 +v 0.028101 0.073426 0.177419 +v 0.028687 0.082748 0.185482 +v 0.028732 0.084160 0.183137 +v 0.033902 0.079133 0.188609 +v 0.030306 0.080821 0.187775 +v 0.031967 0.079835 0.188499 +v 0.029128 0.081966 0.186529 +v 0.029563 0.084934 0.181416 +v 0.032143 0.085407 0.179246 +v 0.038124 0.079001 0.186548 +v 0.034567 0.078978 0.188504 +v 0.035413 0.084751 0.178560 +v 0.037773 0.083551 0.179257 +v 0.039670 0.080191 0.183758 +v 0.039558 0.081639 0.181437 +v 0.028860 0.084604 0.183686 +v 0.028780 0.084373 0.184108 +v 0.028854 0.083346 0.185757 +v 0.029538 0.082242 0.187203 +v 0.030409 0.081437 0.188056 +v 0.032376 0.080287 0.188884 +v 0.034683 0.079547 0.188856 +v 0.036507 0.079338 0.188215 +v 0.038427 0.079594 0.186758 +v 0.039778 0.080589 0.184394 +v 0.039877 0.080813 0.183972 +v 0.039786 0.082094 0.181916 +v 0.039651 0.082369 0.181536 +v 0.038113 0.083995 0.179694 +v 0.037751 0.084244 0.179480 +v 0.035642 0.085289 0.178901 +v 0.034244 0.085705 0.178971 +v 0.032404 0.085959 0.179546 +v 0.031971 0.085966 0.179769 +v 0.029815 0.085525 0.181657 +v 0.029326 0.085209 0.182440 +v 0.034782 0.080026 0.188854 +v 0.039323 0.083161 0.182808 +v 0.039510 0.082820 0.182511 +v 0.039388 0.083070 0.182166 +v 0.039061 0.083634 0.182173 +v 0.038629 0.084197 0.182847 +v 0.038096 0.084804 0.182138 +v 0.037871 0.084999 0.181938 +v 0.036107 0.086095 0.181691 +v 0.034985 0.086149 0.180239 +v 0.035182 0.086413 0.181667 +v 0.034583 0.086250 0.180289 +v 0.033009 0.086468 0.180781 +v 0.033098 0.086626 0.182988 +v 0.031620 0.086371 0.181690 +v 0.031923 0.086478 0.182060 +v 0.032316 0.086530 0.183023 +v 0.031265 0.085756 0.184862 +v 0.029511 0.084891 0.184503 +v 0.030327 0.085304 0.184851 +v 0.031185 0.085439 0.185426 +v 0.030295 0.085110 0.185187 +v 0.029474 0.084670 0.184886 +v 0.032128 0.084428 0.187124 +v 0.030557 0.083288 0.187331 +v 0.030779 0.083054 0.187596 +v 0.032458 0.084102 0.187480 +v 0.034649 0.082955 0.188184 +v 0.034332 0.080130 0.188927 +v 0.034930 0.082877 0.188160 +v 0.034874 0.080506 0.188817 +v 0.032525 0.083977 0.185477 +v 0.033096 0.085028 0.183441 +v 0.034145 0.082728 0.186656 +v 0.036336 0.082529 0.185799 +v 0.036908 0.083580 0.183763 +v 0.035288 0.084830 0.182584 +v 0.019665 0.087281 0.188219 +v 0.020248 0.088391 0.186218 +v 0.018888 0.087663 0.187857 +v 0.019466 0.088588 0.186160 +v 0.019459 0.086700 0.189233 +v 0.024271 0.085923 0.188887 +v 0.023565 0.086162 0.188735 +v 0.021324 0.086166 0.189477 +v 0.021597 0.088921 0.184905 +v 0.022490 0.088387 0.185475 +v 0.021335 0.085784 0.190095 +v 0.024148 0.087272 0.186734 +v 0.024929 0.086823 0.187204 +v 0.024279 0.087918 0.185640 +v 0.024832 0.086438 0.187863 +v 0.016601 0.074666 0.179435 +v 0.017576 0.075481 0.177783 +v 0.019134 0.075552 0.177148 +v 0.021045 0.074868 0.177621 +v 0.021798 0.073970 0.178830 +v 0.021001 0.072866 0.180892 +v 0.019073 0.072778 0.181679 +v 0.016979 0.073751 0.180797 +v 0.018400 0.085284 0.185349 +v 0.016744 0.075745 0.178426 +v 0.018790 0.085698 0.184545 +v 0.017041 0.075905 0.178065 +v 0.019087 0.085858 0.184185 +v 0.017396 0.076029 0.177745 +v 0.019441 0.085982 0.183865 +v 0.017799 0.076114 0.177473 +v 0.019845 0.086067 0.183593 +v 0.019193 0.076111 0.177011 +v 0.019678 0.076025 0.176989 +v 0.021724 0.085978 0.183108 +v 0.021398 0.075322 0.177558 +v 0.023443 0.085275 0.183678 +v 0.022267 0.074286 0.178952 +v 0.024313 0.084239 0.185072 +v 0.022134 0.073540 0.180210 +v 0.024180 0.083493 0.186330 +v 0.021673 0.073155 0.180990 +v 0.023719 0.083108 0.187110 +v 0.021347 0.073012 0.181332 +v 0.020086 0.072823 0.182060 +v 0.022132 0.082776 0.188180 +v 0.019122 0.072911 0.182240 +v 0.021168 0.082864 0.188359 +v 0.017341 0.073548 0.181798 +v 0.019387 0.083502 0.187918 +v 0.016707 0.074033 0.181222 +v 0.016337 0.074565 0.180481 +v 0.018383 0.084518 0.186601 +v 0.016270 0.075089 0.179651 +v 0.016354 0.075331 0.179229 +v 0.026541 0.082391 0.187332 +v 0.015636 0.085704 0.185590 +v 0.019722 0.081753 0.190650 +v 0.016512 0.083499 0.188883 +v 0.018054 0.087442 0.181955 +v 0.017037 0.087115 0.182827 +v 0.022416 0.081285 0.190510 +v 0.024310 0.081392 0.189702 +v 0.022598 0.087232 0.180777 +v 0.020569 0.087584 0.180883 +v 0.025014 0.086234 0.181593 +v 0.026842 0.084466 0.183857 +v 0.015747 0.086249 0.185974 +v 0.015744 0.085485 0.187218 +v 0.016524 0.084168 0.189098 +v 0.018155 0.082998 0.190456 +v 0.019886 0.082305 0.191006 +v 0.022269 0.081867 0.190921 +v 0.024508 0.081973 0.190000 +v 0.024903 0.082060 0.189727 +v 0.026681 0.082983 0.187632 +v 0.027100 0.083652 0.186402 +v 0.027005 0.084935 0.184348 +v 0.026230 0.085982 0.182905 +v 0.025291 0.086702 0.182047 +v 0.022763 0.087785 0.181131 +v 0.021332 0.088080 0.181129 +v 0.020853 0.088136 0.181199 +v 0.017103 0.087658 0.183230 +v 0.026832 0.083839 0.187003 +v 0.026929 0.084063 0.186605 +v 0.026142 0.085044 0.187471 +v 0.025306 0.086557 0.187042 +v 0.025974 0.086148 0.186371 +v 0.025295 0.086712 0.186794 +v 0.021555 0.088643 0.182465 +v 0.021512 0.088946 0.184424 +v 0.020738 0.088720 0.182613 +v 0.021227 0.088967 0.184486 +v 0.019136 0.088708 0.185079 +v 0.018715 0.088512 0.185537 +v 0.016370 0.086367 0.187165 +v 0.016406 0.086130 0.187538 +v 0.018000 0.085442 0.189547 +v 0.018250 0.084064 0.190283 +v 0.018784 0.084879 0.190200 +v 0.018597 0.083871 0.190480 +v 0.021214 0.085374 0.190333 +v 0.022074 0.085216 0.190303 +v 0.024609 0.083493 0.189819 +v 0.025491 0.083819 0.188995 +v 0.019436 0.086165 0.187533 +v 0.020019 0.087276 0.185532 +v 0.021095 0.085051 0.188791 +v 0.023336 0.085047 0.188049 +v 0.023919 0.086157 0.186048 +v 0.022261 0.087272 0.184790 +v 0.005389 0.087619 0.190022 +v 0.005971 0.087864 0.189597 +v 0.005257 0.088612 0.188558 +v 0.006577 0.089108 0.187683 +v 0.010630 0.086907 0.190534 +v 0.009917 0.087086 0.190342 +v 0.007640 0.086853 0.190926 +v 0.008853 0.089341 0.187099 +v 0.006692 0.086697 0.191256 +v 0.009865 0.086566 0.191121 +v 0.009910 0.089454 0.186821 +v 0.007449 0.089788 0.186581 +v 0.010523 0.088330 0.188428 +v 0.011148 0.088506 0.188103 +v 0.011206 0.087514 0.189571 +v 0.004774 0.075641 0.179813 +v 0.006054 0.076496 0.178408 +v 0.008124 0.076515 0.178164 +v 0.009212 0.076096 0.178674 +v 0.009966 0.075220 0.179898 +v 0.009142 0.073960 0.181858 +v 0.007183 0.073663 0.182505 +v 0.005622 0.074087 0.182036 +v 0.004750 0.074932 0.180869 +v 0.005108 0.076742 0.178875 +v 0.005796 0.086569 0.185483 +v 0.005880 0.077044 0.178345 +v 0.006805 0.077185 0.178040 +v 0.007494 0.087012 0.184648 +v 0.007788 0.077150 0.177990 +v 0.008476 0.086976 0.184598 +v 0.008269 0.077066 0.178064 +v 0.009524 0.076583 0.178652 +v 0.010213 0.086410 0.185260 +v 0.010394 0.075572 0.180065 +v 0.011082 0.085399 0.186673 +v 0.010376 0.075024 0.180882 +v 0.011064 0.084850 0.187490 +v 0.009776 0.074305 0.182013 +v 0.010465 0.084132 0.188621 +v 0.009443 0.074118 0.182326 +v 0.008624 0.073854 0.182804 +v 0.009312 0.083681 0.189412 +v 0.007183 0.073775 0.183072 +v 0.007871 0.083601 0.189680 +v 0.005382 0.074265 0.182531 +v 0.006071 0.084091 0.189139 +v 0.004376 0.075240 0.181185 +v 0.005064 0.085067 0.187793 +v 0.004315 0.075791 0.180372 +v 0.005003 0.085618 0.186980 +v 0.004403 0.076058 0.179966 +v 0.013320 0.083668 0.189013 +v 0.002259 0.085271 0.187782 +v 0.002937 0.087099 0.184992 +v 0.006388 0.082265 0.191822 +v 0.003151 0.083783 0.189901 +v 0.005989 0.088442 0.182677 +v 0.009118 0.082053 0.191853 +v 0.011043 0.082368 0.191184 +v 0.009380 0.088404 0.182381 +v 0.008701 0.088502 0.182305 +v 0.007324 0.088563 0.182357 +v 0.011820 0.087597 0.183326 +v 0.013753 0.084378 0.187913 +v 0.013654 0.085909 0.185645 +v 0.002324 0.086575 0.187047 +v 0.002311 0.085760 0.188260 +v 0.003087 0.084442 0.190140 +v 0.003353 0.084201 0.190471 +v 0.005566 0.083052 0.191949 +v 0.006476 0.082814 0.192208 +v 0.009369 0.082626 0.192186 +v 0.010298 0.082745 0.191912 +v 0.011165 0.082951 0.191516 +v 0.013385 0.084256 0.189343 +v 0.013568 0.084500 0.188962 +v 0.013739 0.086369 0.186164 +v 0.013602 0.086637 0.185780 +v 0.012021 0.088069 0.183815 +v 0.011649 0.088262 0.183567 +v 0.009469 0.088954 0.182765 +v 0.007050 0.089111 0.182784 +v 0.006110 0.089014 0.183025 +v 0.004811 0.088706 0.183619 +v 0.002901 0.087583 0.185489 +v 0.013356 0.084907 0.189133 +v 0.010651 0.083316 0.191781 +v 0.010227 0.083227 0.191957 +v 0.013495 0.085149 0.188759 +v 0.012665 0.086265 0.189221 +v 0.011316 0.088909 0.185429 +v 0.011018 0.089064 0.185231 +v 0.007351 0.089741 0.184606 +v 0.006601 0.089664 0.184799 +v 0.005159 0.089126 0.184432 +v 0.004804 0.088995 0.184664 +v 0.005254 0.089303 0.185476 +v 0.003750 0.088134 0.187371 +v 0.002898 0.087189 0.187547 +v 0.003582 0.087718 0.188007 +v 0.002858 0.086945 0.187915 +v 0.003726 0.086635 0.189602 +v 0.004480 0.087241 0.189756 +v 0.004584 0.087063 0.190009 +v 0.004402 0.085825 0.190737 +v 0.005498 0.085161 0.191610 +v 0.005967 0.086003 0.191441 +v 0.006240 0.085891 0.191579 +v 0.006028 0.085465 0.191693 +v 0.009941 0.084664 0.191887 +v 0.010632 0.084828 0.191570 +v 0.010947 0.086542 0.190611 +v 0.012227 0.085684 0.190132 +v 0.011274 0.086796 0.190198 +v 0.005893 0.086762 0.188856 +v 0.006500 0.088006 0.186943 +v 0.007563 0.085752 0.190185 +v 0.009839 0.085985 0.189601 +v 0.010446 0.087229 0.187688 +v 0.008776 0.088240 0.186359 +v -0.048920 0.050619 -0.224570 +v 0.000038 0.048543 -0.228159 +v -0.099987 0.037725 -0.212945 +v -0.107174 0.031108 -0.178883 +v -0.095903 0.094665 -0.134888 +v -0.099212 0.090918 -0.136508 +v -0.099114 0.091991 -0.132170 +v 0.113074 0.026818 -0.138668 +v 0.125741 -0.010606 -0.152094 +v -0.101261 0.087871 -0.130393 +v -0.111207 0.045706 -0.097297 +v -0.112778 0.031108 -0.117422 +v -0.101159 0.087269 -0.134960 +v -0.109918 0.031108 -0.158196 +v -0.102156 0.069523 -0.170549 +v -0.105469 0.045706 -0.178466 +v -0.113811 0.016449 -0.117542 +v -0.112351 0.031108 -0.077759 +v -0.090045 0.041077 -0.222160 +v -0.076408 0.038575 -0.225666 +v 0.016731 0.103674 -0.112863 +v 0.008515 0.104976 -0.119356 +v -0.103024 0.076273 -0.058893 +v -0.101375 0.078913 -0.058310 +v 0.005523 0.084810 -0.187341 +v 0.003962 0.084285 -0.188292 +v -0.100631 0.009064 -0.218972 +v -0.105093 -0.022135 -0.193358 +v 0.057416 0.084324 -0.157188 +v 0.040067 0.080100 -0.182333 +v 0.040755 0.102367 -0.128777 +v 0.035326 0.103470 -0.125768 +v 0.029471 0.010810 -0.232959 +v 0.023390 0.046616 -0.227015 +v 0.024760 0.105340 -0.136990 +v 0.017486 0.106210 -0.133469 +v 0.012923 0.106521 -0.140100 +v 0.011936 0.106658 -0.134675 +v 0.006730 0.106836 -0.140916 +v 0.016902 0.106257 -0.133596 +v -0.094591 0.022490 -0.225248 +v -0.092170 0.011748 -0.228040 +v -0.089293 0.034923 -0.224648 +v -0.089907 0.012784 -0.228472 +v 0.048501 0.099132 -0.129374 +v -0.098484 0.009640 -0.223592 +v 0.101250 -0.009617 -0.207400 +v 0.109960 -0.014143 -0.201691 +v -0.106155 -0.023810 -0.186548 +v 0.006162 0.052493 -0.226504 +v -0.100257 0.073048 -0.172619 +v -0.096581 0.061395 -0.196099 +v 0.054348 0.045353 -0.218472 +v 0.041040 0.046507 -0.223202 +v 0.067978 0.033737 -0.217842 +v -0.096059 0.093734 -0.137785 +v -0.092630 0.089653 -0.152016 +v -0.092717 0.087976 -0.155414 +v -0.097083 0.075811 -0.174237 +v 0.040012 0.042565 -0.224918 +v 0.043596 0.008424 -0.230024 +v 0.059060 0.034255 -0.221404 +v 0.036095 -0.000574 -0.232571 +v -0.101014 0.047315 -0.202065 +v -0.098047 0.040493 -0.216201 +v -0.099777 0.058675 -0.194279 +v 0.037115 0.090289 -0.165682 +v -0.014297 0.054191 -0.225436 +v -0.049519 0.055657 -0.220298 +v 0.006327 0.059393 -0.221211 +v 0.031805 0.044882 -0.226075 +v 0.023946 0.050642 -0.225395 +v -0.095746 0.095205 -0.129076 +v -0.091628 0.096934 -0.132117 +v 0.121325 -0.027213 -0.189947 +v 0.123253 -0.024073 -0.184193 +v 0.109184 -0.026517 -0.201231 +v 0.065575 -0.009485 -0.223467 +v 0.087776 0.010137 -0.213596 +v 0.091380 0.005605 -0.212225 +v 0.125266 -0.023631 -0.075241 +v 0.131358 -0.043695 -0.087121 +v 0.132557 -0.046752 -0.108930 +v 0.116655 0.019588 -0.128374 +v 0.126123 -0.026770 -0.074490 +v 0.127813 -0.032585 -0.074883 +v 0.129411 -0.037855 -0.077457 +v 0.000039 0.104226 -0.112863 +v 0.005712 0.105261 -0.120948 +v 0.080961 0.074556 -0.129717 +v 0.074979 0.075967 -0.145290 +v -0.094385 0.095905 -0.128327 +v -0.093818 0.083523 -0.057430 +v 0.089774 0.038873 -0.188869 +v 0.088470 0.026487 -0.206012 +v 0.081566 0.032392 -0.208347 +v 0.076285 0.057350 -0.182140 +v 0.005105 0.085680 -0.185974 +v 0.106522 0.026481 -0.171225 +v 0.094466 0.046571 -0.166793 +v 0.101822 0.018479 -0.193506 +v 0.110381 0.000544 -0.195610 +v 0.098738 0.032940 -0.180422 +v 0.121880 -0.002812 -0.163191 +v 0.113031 0.019571 -0.161386 +v -0.103781 0.074188 -0.059369 +v -0.102519 0.075612 -0.053209 +v 0.084519 0.070017 -0.133555 +v 0.082466 0.071013 -0.138236 +v 0.082528 0.072504 -0.131820 +v 0.049533 0.099336 -0.112863 +v 0.036533 0.102614 -0.120365 +v -0.111444 -0.006445 -0.049409 +v 0.041838 0.050096 -0.220750 +v 0.033592 0.055640 -0.218978 +v 0.024370 0.054305 -0.223040 +v -0.110979 0.021694 -0.049632 +v 0.006264 0.056195 -0.224186 +v 0.000038 0.052618 -0.226584 +v 0.024644 0.057473 -0.220034 +v 0.028322 0.082251 -0.185396 +v 0.004390 0.060664 -0.219894 +v 0.018006 0.059961 -0.218894 +v 0.021969 0.082764 -0.187100 +v 0.022738 0.082809 -0.186758 +v 0.008314 0.083808 -0.188638 +v 0.021144 0.082836 -0.187263 +v 0.009937 0.083933 -0.188214 +v 0.016239 0.083651 -0.187390 +v 0.018402 0.084089 -0.186099 +v 0.018902 0.083667 -0.186633 +v 0.020320 0.083020 -0.187235 +v 0.019557 0.083303 -0.187021 +v -0.100404 0.084128 -0.075218 +v -0.096809 0.082507 -0.057584 +v 0.068353 0.088769 -0.113956 +v 0.059174 0.095235 -0.117887 +v 0.080948 0.064637 -0.160318 +v 0.065769 0.061820 -0.188504 +v -0.101671 0.078383 -0.058367 +v -0.099470 0.080824 -0.057909 +v -0.103621 0.072548 -0.053005 +v -0.110753 0.034339 -0.059362 +v 0.089778 0.063624 -0.135552 +v 0.087069 0.066905 -0.134898 +v 0.022258 0.104940 -0.125641 +v 0.021425 0.105024 -0.125742 +v 0.032578 0.102826 -0.139497 +v 0.026438 0.103782 -0.142009 +v -0.097048 0.094246 -0.128817 +v -0.097597 0.093677 -0.128950 +v -0.089724 0.038537 -0.223445 +v 0.126698 -0.037981 -0.181441 +v 0.124612 -0.035690 -0.185644 +v -0.100710 0.089441 -0.129842 +v -0.101415 0.088174 -0.111621 +v -0.094693 0.009527 -0.227072 +v -0.094714 0.010084 -0.227038 +v -0.099181 0.092048 -0.129738 +v 0.085889 0.052247 -0.174874 +v -0.103798 0.074509 -0.060761 +v 0.013793 0.105080 -0.145353 +v 0.065990 0.029965 -0.219848 +v -0.098193 0.081576 -0.057673 +v 0.037560 0.102963 -0.124276 +v 0.034270 0.103619 -0.125798 +v 0.035323 0.103455 -0.125637 +v 0.032668 0.103776 -0.125342 +v -0.092060 0.095397 -0.138648 +v -0.093183 0.010977 -0.227736 +v 0.035872 0.103348 -0.125395 +v -0.092456 0.063087 -0.197122 +v -0.047686 0.076933 -0.193619 +v 0.079773 0.076254 -0.127143 +v -0.098507 0.004084 -0.224075 +v -0.098397 0.004248 -0.224166 +v -0.093012 0.077485 -0.175209 +v 0.033794 0.083972 -0.179692 +v 0.032229 0.084147 -0.180275 +v 0.018947 0.086041 -0.182720 +v 0.114350 -0.028336 -0.197686 +v 0.114011 -0.022614 -0.198356 +v 0.019612 0.086209 -0.182229 +v 0.022792 0.085709 -0.181963 +v 0.020382 0.086260 -0.181890 +v 0.021536 0.086127 -0.181715 +v 0.031546 0.084036 -0.180834 +v 0.006218 0.106939 -0.135424 +v 0.031074 0.083824 -0.181442 +v 0.118710 -0.010764 -0.185972 +v 0.021207 0.086188 -0.181728 +v 0.023943 0.084904 -0.182875 +v 0.030755 0.083501 -0.182153 +v 0.024353 0.083996 -0.184221 +v -0.095806 0.095122 -0.132199 +v 0.030641 0.083099 -0.182886 +v 0.030741 0.082644 -0.183592 +v 0.031047 0.082169 -0.184221 +v 0.023912 0.083231 -0.185644 +v 0.023701 0.104710 -0.124827 +v 0.024212 0.104581 -0.124169 +v 0.089030 0.059288 -0.152702 +v 0.019815 0.105100 -0.125296 +v 0.023034 0.104833 -0.125329 +v -0.099948 0.035140 -0.214431 +v 0.124211 -0.035323 -0.186251 +v 0.121710 -0.033031 -0.190028 +v 0.023401 0.082968 -0.186262 +v 0.000038 0.105551 -0.146550 +v 0.078821 0.077928 -0.122899 +v -0.100428 -0.001427 -0.220025 +v 0.035305 0.080490 -0.184668 +v 0.037363 0.102892 -0.123476 +v 0.037472 0.102771 -0.122648 +v 0.106926 0.034770 -0.096877 +v 0.108117 0.031146 -0.094875 +v 0.031495 0.103777 -0.124151 +v 0.032004 0.103797 -0.124822 +v 0.037362 0.102681 -0.121816 +v 0.037042 0.102627 -0.121038 +v 0.117961 -0.030301 -0.194387 +v 0.117608 -0.018966 -0.193864 +v -0.042135 0.020000 -0.232863 +v -0.044916 0.104618 -0.133845 +v -0.070253 0.089510 -0.063835 +v -0.034385 0.095592 -0.071956 +v -0.029593 0.096345 -0.073865 +v -0.025127 0.097163 -0.076460 +v -0.021088 0.098031 -0.079686 +v -0.017566 0.098932 -0.083475 +v -0.014641 0.099850 -0.087743 +v -0.012377 0.100768 -0.092399 +v -0.010825 0.101668 -0.097338 +v -0.009426 0.103124 -0.106122 +v -0.093817 0.083519 -0.057415 +v -0.091401 0.096934 -0.128493 +v -0.098628 0.080519 -0.054238 +v -0.095925 0.082258 -0.055028 +v -0.003929 0.104091 -0.112044 +v 0.005390 0.105577 -0.123380 +v 0.000038 0.107042 -0.135698 +v -0.006296 0.103855 -0.110607 +v 0.005279 0.105475 -0.122549 +v -0.001269 0.104212 -0.112777 +v -0.008170 0.103525 -0.108588 +v 0.037043 0.103036 -0.124242 +v 0.024533 0.104454 -0.123401 +v 0.024642 0.104339 -0.122572 +v 0.042379 0.053201 -0.217651 +v 0.069553 0.037176 -0.215031 +v 0.055123 0.048397 -0.215242 +v 0.101917 0.047234 -0.135538 +v 0.099771 0.051175 -0.131413 +v 0.101912 0.040391 -0.157993 +v 0.108140 0.033780 -0.148581 +v 0.095419 0.056711 -0.134694 +v 0.084795 0.020215 -0.213241 +v 0.097767 0.053755 -0.133310 +v 0.045346 0.101148 -0.125238 +v 0.110330 -0.026829 -0.200553 +v 0.061991 0.093876 -0.113662 +v 0.024532 0.104244 -0.121740 +v -0.102684 0.081289 -0.075833 +v -0.093768 0.083099 -0.055676 +v 0.054279 0.098041 -0.113174 +v 0.056060 0.097227 -0.113287 +v -0.089747 0.097234 -0.133716 +v 0.128191 -0.039987 -0.177055 +v 0.011639 0.105372 -0.123405 +v 0.011750 0.105263 -0.122575 +v -0.110597 0.045706 -0.077694 +v 0.011317 0.105482 -0.124176 +v 0.101301 0.049155 -0.129245 +v -0.095169 0.009070 -0.226862 +v 0.018204 0.104874 -0.122506 +v -0.027330 0.018002 -0.234075 +v -0.036279 0.019510 -0.233353 +v 0.103384 0.046282 -0.123532 +v 0.102544 0.047466 -0.126581 +v 0.058768 0.095989 -0.113459 +v 0.099060 0.015560 -0.201734 +v 0.097366 0.012646 -0.206165 +v 0.070650 0.040137 -0.211533 +v 0.036886 0.081505 -0.182040 +v -0.094086 0.034814 -0.222893 +v -0.097865 0.036754 -0.218577 +v -0.045656 0.103086 -0.144640 +v -0.090326 0.095783 -0.138949 +v -0.091832 0.096455 -0.135256 +v 0.024211 0.104174 -0.120965 +v 0.023033 0.104129 -0.119779 +v 0.086986 0.023591 -0.210015 +v -0.090816 0.046505 -0.217679 +v -0.094996 0.044782 -0.216621 +v 0.008384 0.087198 -0.183123 +v 0.006759 0.087065 -0.183542 +v -0.111500 -0.010629 -0.051795 +v -0.111436 -0.009535 -0.050537 +v 0.021423 0.104212 -0.119333 +v 0.019813 0.104397 -0.119746 +v 0.033741 0.080670 -0.185254 +v 0.042512 0.068654 -0.198234 +v 0.126149 -0.032408 -0.180361 +v 0.000038 0.102709 -0.153436 +v 0.092578 0.024597 -0.202217 +v 0.055234 0.097695 -0.114558 +v 0.019079 0.104528 -0.120317 +v 0.018635 0.104638 -0.120907 +v 0.119548 -0.015608 -0.188263 +v -0.102390 0.077289 -0.058668 +v 0.018313 0.104761 -0.121677 +v 0.010663 0.086552 -0.183851 +v 0.009998 0.086867 -0.183437 +v 0.005910 0.086745 -0.184159 +v 0.011169 0.086165 -0.184403 +v 0.018314 0.104971 -0.123336 +v 0.031174 0.103720 -0.123374 +v 0.031174 0.103509 -0.121714 +v 0.031065 0.103628 -0.122542 +v 0.009220 0.087088 -0.183189 +v -0.103628 0.082045 -0.095442 +v -0.108059 -0.025029 -0.173686 +v -0.110878 -0.012845 -0.158388 +v -0.109741 -0.025839 -0.158180 +v -0.111214 -0.026549 -0.144606 +v -0.111418 -0.008085 -0.049711 +v 0.105985 0.037876 -0.099388 +v 0.070492 0.013958 -0.220575 +v 0.000038 0.106951 -0.141214 +v 0.031494 0.103370 -0.120946 +v 0.103713 0.045783 -0.120626 +v 0.011134 0.084472 -0.187161 +v 0.011585 0.085287 -0.185766 +v 0.011484 0.085733 -0.185055 +v 0.018636 0.105044 -0.124112 +v -0.102440 -0.013253 -0.209548 +v -0.101693 -0.009432 -0.213700 +v 0.032019 0.103216 -0.120274 +v 0.033351 0.102023 -0.112863 +v 0.032666 0.103069 -0.119792 +v 0.034268 0.102803 -0.119389 +v 0.035870 0.102641 -0.119845 +v 0.005206 0.085236 -0.186684 +v 0.074016 0.083472 -0.116171 +v 0.076122 0.081257 -0.117972 +v 0.103753 0.045722 -0.120273 +v -0.054589 0.020267 -0.231798 +v 0.116562 0.004692 -0.173876 +v 0.006026 0.048421 -0.228082 +v -0.112710 -0.023934 -0.080920 +v 0.103732 0.045500 -0.114321 +v 0.071354 0.086062 -0.114790 +v -0.100749 0.078386 -0.053651 +v 0.103970 0.044596 -0.110197 +v 0.113322 -0.010595 -0.197430 +v -0.090455 0.044088 -0.220036 +v -0.094728 0.042709 -0.218671 +v -0.112665 -0.023652 -0.079397 +v 0.094756 0.009261 -0.209731 +v 0.031611 0.081728 -0.184652 +v 0.035350 0.083346 -0.179850 +v -0.020386 0.020000 -0.234051 +v 0.108512 -0.002507 -0.200627 +v -0.047553 0.086978 -0.177601 +v 0.040877 -0.002011 -0.231475 +v -0.094467 0.040127 -0.220555 +v -0.094289 0.037943 -0.221730 +v 0.105394 -0.005977 -0.204653 +v 0.032182 0.081283 -0.185089 +v 0.035955 0.080583 -0.184136 +v 0.036786 0.081960 -0.181334 +v -0.107386 -0.025973 -0.151713 +v 0.000038 0.010170 -0.235772 +v 0.036481 0.082440 -0.180708 +v -0.112948 -0.026136 -0.109876 +v 0.006898 0.105781 -0.125330 +v 0.018335 0.004736 -0.235272 +v 0.010132 0.104974 -0.119792 +v 0.006260 0.105159 -0.120253 +v 0.104441 0.043000 -0.106260 +v -0.045364 0.104499 -0.139329 +v 0.006897 0.105080 -0.119779 +v 0.054466 0.065603 -0.193890 +v 0.053367 0.098290 -0.113114 +v -0.112638 -0.023138 -0.077936 +v 0.003335 0.102676 -0.153389 +v 0.130625 -0.041698 -0.081711 +v 0.105125 0.040727 -0.102596 +v 0.010803 0.105586 -0.124837 +v 0.036456 0.080793 -0.183491 +v 0.005225 0.086114 -0.185257 +v 0.005558 0.086507 -0.184584 +v 0.129790 -0.043000 -0.170190 +v 0.057364 0.005239 -0.226110 +v -0.072649 0.017975 -0.230170 +v -0.104184 -0.019865 -0.199082 +v 0.131519 -0.047063 -0.156982 +v 0.006031 0.084433 -0.187899 +v -0.110939 0.016449 -0.158401 +v 0.036773 0.081107 -0.182776 +v 0.010134 0.105675 -0.125343 +v 0.005713 0.105666 -0.124153 +v 0.017991 0.084990 -0.184749 +v 0.018434 0.085768 -0.183333 +v 0.008516 0.105785 -0.125766 +v -0.103292 -0.016873 -0.204537 +v 0.006697 0.084128 -0.188318 +v 0.092638 0.060144 -0.135500 +v 0.005389 0.105368 -0.121719 +v 0.077793 0.079324 -0.120304 +v 0.011639 0.105162 -0.121745 +v 0.011316 0.105077 -0.120971 +v 0.132280 -0.048892 -0.144307 +v -0.048920 0.050619 0.224570 +v 0.000038 0.048543 0.228159 +v -0.099987 0.037725 0.212945 +v -0.107174 0.031108 0.178883 +v -0.095903 0.094665 0.134888 +v -0.099212 0.090918 0.136508 +v -0.099114 0.091991 0.132170 +v 0.113074 0.026818 0.138668 +v 0.125741 -0.010606 0.152094 +v -0.101261 0.087871 0.130393 +v -0.111207 0.045706 0.097297 +v -0.112778 0.031108 0.117422 +v -0.101159 0.087269 0.134960 +v -0.109918 0.031108 0.158196 +v -0.102156 0.069523 0.170549 +v -0.105469 0.045706 0.178466 +v -0.113811 0.016449 0.117542 +v -0.112351 0.031108 0.077759 +v -0.090045 0.041077 0.222160 +v -0.076408 0.038575 0.225666 +v 0.016731 0.103674 0.112863 +v 0.008515 0.104976 0.119356 +v -0.103024 0.076273 0.058893 +v -0.101375 0.078913 0.058310 +v 0.005523 0.084810 0.187341 +v 0.003962 0.084285 0.188292 +v -0.100631 0.009064 0.218972 +v -0.105093 -0.022135 0.193358 +v 0.057416 0.084324 0.157188 +v 0.040067 0.080100 0.182333 +v 0.040755 0.102367 0.128777 +v 0.035326 0.103470 0.125768 +v 0.029471 0.010810 0.232959 +v 0.023390 0.046616 0.227015 +v 0.024760 0.105340 0.136990 +v 0.017486 0.106210 0.133469 +v 0.012923 0.106521 0.140100 +v 0.011936 0.106658 0.134675 +v 0.006730 0.106836 0.140916 +v 0.016902 0.106257 0.133596 +v -0.094591 0.022490 0.225248 +v -0.092170 0.011748 0.228040 +v -0.089293 0.034923 0.224648 +v -0.089907 0.012784 0.228472 +v 0.048501 0.099132 0.129374 +v -0.098484 0.009640 0.223592 +v 0.101250 -0.009617 0.207400 +v 0.109960 -0.014143 0.201691 +v -0.106155 -0.023810 0.186548 +v 0.006162 0.052493 0.226504 +v -0.100257 0.073048 0.172619 +v -0.096581 0.061395 0.196099 +v 0.054348 0.045353 0.218472 +v 0.041040 0.046507 0.223202 +v 0.067978 0.033737 0.217842 +v -0.096059 0.093734 0.137785 +v -0.092630 0.089653 0.152016 +v -0.092717 0.087976 0.155414 +v -0.097083 0.075811 0.174237 +v 0.040012 0.042565 0.224918 +v 0.043596 0.008424 0.230024 +v 0.059060 0.034255 0.221404 +v 0.036095 -0.000574 0.232571 +v -0.101014 0.047315 0.202065 +v -0.098047 0.040493 0.216201 +v -0.099777 0.058675 0.194279 +v 0.037115 0.090289 0.165682 +v -0.014297 0.054191 0.225436 +v -0.049519 0.055657 0.220298 +v 0.006327 0.059393 0.221211 +v 0.031805 0.044882 0.226075 +v 0.023946 0.050642 0.225395 +v -0.095746 0.095205 0.129076 +v -0.091628 0.096934 0.132117 +v 0.121325 -0.027213 0.189947 +v 0.123253 -0.024073 0.184193 +v 0.109184 -0.026517 0.201231 +v 0.065575 -0.009485 0.223467 +v 0.087776 0.010137 0.213596 +v 0.091380 0.005605 0.212225 +v 0.125266 -0.023631 0.075241 +v 0.131358 -0.043695 0.087121 +v 0.132557 -0.046752 0.108930 +v 0.116655 0.019588 0.128374 +v 0.126123 -0.026770 0.074490 +v 0.127813 -0.032585 0.074883 +v 0.129411 -0.037855 0.077457 +v 0.000039 0.104226 0.112863 +v 0.005712 0.105261 0.120948 +v 0.080961 0.074556 0.129717 +v 0.074979 0.075967 0.145290 +v -0.094385 0.095905 0.128327 +v -0.093818 0.083523 0.057430 +v 0.089774 0.038873 0.188869 +v 0.088470 0.026487 0.206012 +v 0.081566 0.032392 0.208347 +v 0.076285 0.057350 0.182140 +v 0.005105 0.085680 0.185974 +v 0.106522 0.026481 0.171225 +v 0.094466 0.046571 0.166793 +v 0.101822 0.018479 0.193506 +v 0.110381 0.000544 0.195610 +v 0.098738 0.032940 0.180422 +v 0.121880 -0.002812 0.163191 +v 0.113031 0.019571 0.161386 +v -0.103781 0.074188 0.059369 +v -0.102519 0.075612 0.053209 +v 0.084519 0.070017 0.133555 +v 0.082466 0.071013 0.138236 +v 0.082528 0.072504 0.131820 +v 0.049533 0.099336 0.112863 +v 0.036533 0.102614 0.120365 +v -0.111444 -0.006445 0.049409 +v 0.041838 0.050096 0.220750 +v 0.033592 0.055640 0.218978 +v 0.024370 0.054305 0.223040 +v -0.110979 0.021694 0.049632 +v 0.006264 0.056195 0.224186 +v 0.000038 0.052618 0.226584 +v 0.024644 0.057473 0.220034 +v 0.028322 0.082251 0.185396 +v 0.004390 0.060664 0.219894 +v 0.018006 0.059961 0.218894 +v 0.021969 0.082764 0.187100 +v 0.022738 0.082809 0.186758 +v 0.008314 0.083808 0.188638 +v 0.021144 0.082836 0.187263 +v 0.009937 0.083933 0.188214 +v 0.016239 0.083651 0.187390 +v 0.018402 0.084089 0.186099 +v 0.018902 0.083667 0.186633 +v 0.020320 0.083020 0.187235 +v 0.019557 0.083303 0.187021 +v -0.100404 0.084128 0.075218 +v -0.096809 0.082507 0.057584 +v 0.068353 0.088769 0.113956 +v 0.059174 0.095235 0.117887 +v 0.080948 0.064637 0.160318 +v 0.065769 0.061820 0.188504 +v -0.101671 0.078383 0.058367 +v -0.099470 0.080824 0.057909 +v -0.103621 0.072548 0.053005 +v -0.110753 0.034339 0.059362 +v 0.089778 0.063624 0.135552 +v 0.087069 0.066905 0.134898 +v 0.022258 0.104940 0.125641 +v 0.021425 0.105024 0.125742 +v 0.032578 0.102826 0.139497 +v 0.026438 0.103782 0.142009 +v -0.097048 0.094246 0.128817 +v -0.097597 0.093677 0.128950 +v -0.089724 0.038537 0.223445 +v 0.126698 -0.037981 0.181441 +v 0.124612 -0.035690 0.185644 +v -0.100710 0.089441 0.129842 +v -0.101415 0.088174 0.111621 +v -0.094693 0.009527 0.227072 +v -0.094714 0.010084 0.227038 +v -0.099181 0.092048 0.129738 +v 0.085889 0.052247 0.174874 +v -0.103798 0.074509 0.060761 +v 0.013793 0.105080 0.145353 +v 0.065990 0.029965 0.219848 +v -0.098193 0.081576 0.057673 +v 0.037560 0.102963 0.124276 +v 0.034270 0.103619 0.125798 +v 0.035323 0.103455 0.125637 +v 0.032668 0.103776 0.125342 +v -0.092060 0.095397 0.138648 +v -0.093183 0.010977 0.227736 +v 0.035872 0.103348 0.125395 +v -0.092456 0.063087 0.197122 +v -0.047686 0.076933 0.193619 +v 0.079773 0.076254 0.127143 +v -0.098507 0.004084 0.224075 +v -0.098397 0.004248 0.224166 +v -0.093012 0.077485 0.175209 +v 0.033794 0.083972 0.179692 +v 0.032229 0.084147 0.180275 +v 0.018947 0.086041 0.182720 +v 0.114350 -0.028336 0.197686 +v 0.114011 -0.022614 0.198356 +v 0.019612 0.086209 0.182229 +v 0.022792 0.085709 0.181963 +v 0.020382 0.086260 0.181890 +v 0.021536 0.086127 0.181715 +v 0.031546 0.084036 0.180834 +v 0.006218 0.106939 0.135424 +v 0.031074 0.083824 0.181442 +v 0.118710 -0.010764 0.185972 +v 0.021207 0.086188 0.181728 +v 0.023943 0.084904 0.182875 +v 0.030755 0.083501 0.182153 +v 0.024353 0.083996 0.184221 +v -0.095806 0.095122 0.132199 +v 0.030641 0.083099 0.182886 +v 0.030741 0.082644 0.183592 +v 0.031047 0.082169 0.184221 +v 0.023912 0.083231 0.185644 +v 0.023701 0.104710 0.124827 +v 0.024212 0.104581 0.124169 +v 0.089030 0.059288 0.152702 +v 0.019815 0.105100 0.125296 +v 0.023034 0.104833 0.125329 +v -0.099948 0.035140 0.214431 +v 0.124211 -0.035323 0.186251 +v 0.121710 -0.033031 0.190028 +v 0.023401 0.082968 0.186262 +v 0.000038 0.105551 0.146550 +v 0.078821 0.077928 0.122899 +v -0.100428 -0.001427 0.220025 +v 0.035305 0.080490 0.184668 +v 0.037363 0.102892 0.123476 +v 0.037472 0.102771 0.122648 +v 0.106926 0.034770 0.096877 +v 0.108117 0.031146 0.094875 +v 0.031495 0.103777 0.124151 +v 0.032004 0.103797 0.124822 +v 0.037362 0.102681 0.121816 +v 0.037042 0.102627 0.121038 +v 0.117961 -0.030301 0.194387 +v 0.117608 -0.018966 0.193864 +v -0.042135 0.020000 0.232863 +v -0.044916 0.104618 0.133845 +v -0.070253 0.089510 0.063835 +v -0.034385 0.095592 0.071956 +v -0.029593 0.096345 0.073865 +v -0.025127 0.097163 0.076460 +v -0.021088 0.098031 0.079686 +v -0.017566 0.098932 0.083475 +v -0.014641 0.099850 0.087743 +v -0.012377 0.100768 0.092399 +v -0.010825 0.101668 0.097338 +v -0.009426 0.103124 0.106122 +v -0.093817 0.083519 0.057415 +v -0.091401 0.096934 0.128493 +v -0.098628 0.080519 0.054238 +v -0.095925 0.082258 0.055028 +v -0.003929 0.104091 0.112044 +v 0.005390 0.105577 0.123380 +v 0.000038 0.107042 0.135698 +v -0.006296 0.103855 0.110607 +v 0.005279 0.105475 0.122549 +v -0.001269 0.104212 0.112777 +v -0.008170 0.103525 0.108588 +v 0.037043 0.103036 0.124242 +v 0.024533 0.104454 0.123401 +v 0.024642 0.104339 0.122572 +v 0.042379 0.053201 0.217651 +v 0.069553 0.037176 0.215031 +v 0.055123 0.048397 0.215242 +v 0.101917 0.047234 0.135538 +v 0.099771 0.051175 0.131413 +v 0.101912 0.040391 0.157993 +v 0.108140 0.033780 0.148581 +v 0.095419 0.056711 0.134694 +v 0.084795 0.020215 0.213241 +v 0.097767 0.053755 0.133310 +v 0.045346 0.101148 0.125238 +v 0.110330 -0.026829 0.200553 +v 0.061991 0.093876 0.113662 +v 0.024532 0.104244 0.121740 +v -0.102684 0.081289 0.075833 +v -0.093768 0.083099 0.055676 +v 0.054279 0.098041 0.113174 +v 0.056060 0.097227 0.113287 +v -0.089747 0.097234 0.133716 +v 0.128191 -0.039987 0.177055 +v 0.011639 0.105372 0.123405 +v 0.011750 0.105263 0.122575 +v -0.110597 0.045706 0.077694 +v 0.011317 0.105482 0.124176 +v 0.101301 0.049155 0.129245 +v -0.095169 0.009070 0.226862 +v 0.018204 0.104874 0.122506 +v -0.027330 0.018002 0.234075 +v -0.036279 0.019510 0.233353 +v 0.103384 0.046282 0.123532 +v 0.102544 0.047466 0.126581 +v 0.058768 0.095989 0.113459 +v 0.099060 0.015560 0.201734 +v 0.097366 0.012646 0.206165 +v 0.070650 0.040137 0.211533 +v 0.036886 0.081505 0.182040 +v -0.094086 0.034814 0.222893 +v -0.097865 0.036754 0.218577 +v -0.045656 0.103086 0.144640 +v -0.090326 0.095783 0.138949 +v -0.091832 0.096455 0.135256 +v 0.024211 0.104174 0.120965 +v 0.023033 0.104129 0.119779 +v 0.086986 0.023591 0.210015 +v -0.090816 0.046505 0.217679 +v -0.094996 0.044782 0.216621 +v 0.008384 0.087198 0.183123 +v 0.006759 0.087065 0.183542 +v -0.111500 -0.010629 0.051795 +v -0.111436 -0.009535 0.050537 +v 0.021423 0.104212 0.119333 +v 0.019813 0.104397 0.119746 +v 0.033741 0.080670 0.185254 +v 0.042512 0.068654 0.198234 +v 0.126149 -0.032408 0.180361 +v 0.000038 0.102709 0.153436 +v 0.092578 0.024597 0.202217 +v 0.055234 0.097695 0.114558 +v 0.019079 0.104528 0.120317 +v 0.018635 0.104638 0.120907 +v 0.119548 -0.015608 0.188263 +v -0.102390 0.077289 0.058668 +v 0.018313 0.104761 0.121677 +v 0.010663 0.086552 0.183851 +v 0.009998 0.086867 0.183437 +v 0.005910 0.086745 0.184159 +v 0.011169 0.086165 0.184403 +v 0.018314 0.104971 0.123336 +v 0.031174 0.103720 0.123374 +v 0.031174 0.103509 0.121714 +v 0.031065 0.103628 0.122542 +v 0.009220 0.087088 0.183189 +v -0.103628 0.082045 0.095442 +v -0.108059 -0.025029 0.173686 +v -0.110878 -0.012845 0.158388 +v -0.109741 -0.025839 0.158180 +v -0.111214 -0.026549 0.144606 +v -0.111418 -0.008085 0.049711 +v 0.105985 0.037876 0.099388 +v 0.070492 0.013958 0.220575 +v 0.000038 0.106951 0.141214 +v 0.031494 0.103370 0.120946 +v 0.103713 0.045783 0.120626 +v 0.011134 0.084472 0.187161 +v 0.011585 0.085287 0.185766 +v 0.011484 0.085733 0.185055 +v 0.018636 0.105044 0.124112 +v -0.102440 -0.013253 0.209548 +v -0.101693 -0.009432 0.213700 +v 0.032019 0.103216 0.120274 +v 0.033351 0.102023 0.112863 +v 0.032666 0.103069 0.119792 +v 0.034268 0.102803 0.119389 +v 0.035870 0.102641 0.119845 +v 0.005206 0.085236 0.186684 +v 0.074016 0.083472 0.116171 +v 0.076122 0.081257 0.117972 +v 0.103753 0.045722 0.120273 +v -0.054589 0.020267 0.231798 +v 0.116562 0.004692 0.173876 +v 0.006026 0.048421 0.228082 +v -0.112710 -0.023934 0.080920 +v 0.103732 0.045500 0.114321 +v 0.071354 0.086062 0.114790 +v -0.100749 0.078386 0.053651 +v 0.103970 0.044596 0.110197 +v 0.113322 -0.010595 0.197430 +v -0.090455 0.044088 0.220036 +v -0.094728 0.042709 0.218671 +v -0.112665 -0.023652 0.079397 +v 0.094756 0.009261 0.209731 +v 0.031611 0.081728 0.184652 +v 0.035350 0.083346 0.179850 +v -0.020386 0.020000 0.234051 +v 0.108512 -0.002507 0.200627 +v -0.047553 0.086978 0.177601 +v 0.040877 -0.002011 0.231475 +v -0.094467 0.040127 0.220555 +v -0.094289 0.037943 0.221730 +v 0.105394 -0.005977 0.204653 +v 0.032182 0.081283 0.185089 +v 0.035955 0.080583 0.184136 +v 0.036786 0.081960 0.181334 +v -0.107386 -0.025973 0.151713 +v 0.000038 0.010170 0.235772 +v 0.036481 0.082440 0.180708 +v -0.112948 -0.026136 0.109876 +v 0.006898 0.105781 0.125330 +v 0.018335 0.004736 0.235272 +v 0.010132 0.104974 0.119792 +v 0.006260 0.105159 0.120253 +v 0.104441 0.043000 0.106260 +v -0.045364 0.104499 0.139329 +v 0.006897 0.105080 0.119779 +v 0.054466 0.065603 0.193890 +v 0.053367 0.098290 0.113114 +v -0.112638 -0.023138 0.077936 +v 0.003335 0.102676 0.153389 +v 0.130625 -0.041698 0.081711 +v 0.105125 0.040727 0.102596 +v 0.010803 0.105586 0.124837 +v 0.036456 0.080793 0.183491 +v 0.005225 0.086114 0.185257 +v 0.005558 0.086507 0.184584 +v 0.129790 -0.043000 0.170190 +v 0.057364 0.005239 0.226110 +v -0.072649 0.017975 0.230170 +v -0.104184 -0.019865 0.199082 +v 0.131519 -0.047063 0.156982 +v 0.006031 0.084433 0.187899 +v -0.110939 0.016449 0.158401 +v 0.036773 0.081107 0.182776 +v 0.010134 0.105675 0.125343 +v 0.005713 0.105666 0.124153 +v 0.017991 0.084990 0.184749 +v 0.018434 0.085768 0.183333 +v 0.008516 0.105785 0.125766 +v -0.103292 -0.016873 0.204537 +v 0.006697 0.084128 0.188318 +v 0.092638 0.060144 0.135500 +v 0.005389 0.105368 0.121719 +v 0.077793 0.079324 0.120304 +v 0.011639 0.105162 0.121745 +v 0.011316 0.105077 0.120971 +v 0.132280 -0.048892 0.144307 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vn -0.8871 -0.0369 0.4601 +vn -0.9999 0.0088 -0.0110 +vn -0.9383 -0.0914 0.3334 +vn 0.5862 -0.7835 0.2062 +vn -0.6423 -0.4566 0.6156 +vn -0.6335 -0.0770 0.7699 +vn -0.6841 0.0157 0.7292 +vn -0.6472 -0.4897 0.5842 +vn -0.5994 -0.6618 0.4502 +vn -0.8295 -0.5537 -0.0736 +vn -0.7311 -0.4574 -0.5062 +vn -0.7768 -0.6080 -0.1638 +vn -0.6768 -0.6418 -0.3606 +vn -0.6408 -0.3504 -0.6831 +vn -0.6364 -0.1265 -0.7609 +vn -0.6030 -0.0835 -0.7933 +vn -0.6532 0.6611 -0.3692 +vn -0.6187 0.5064 -0.6006 +vn -0.6386 0.5148 -0.5720 +vn -0.6881 0.6722 -0.2730 +vn -0.6530 0.7303 0.2007 +vn -0.6933 0.6108 0.3825 +vn -0.6311 0.4024 0.6632 +vn -0.8387 -0.0875 0.5376 +vn -0.4772 -0.8784 -0.0260 +vn -0.9103 -0.2215 -0.3497 +vn -0.6190 -0.0269 -0.7849 +vn -0.6657 0.3604 -0.6534 +vn -0.2902 0.9464 0.1418 +vn -0.6971 0.0245 0.7166 +vn 0.3092 -0.8481 0.4303 +vn -0.7627 0.6207 0.1820 +vn -0.7448 -0.2553 0.6165 +vn -0.8056 0.2658 0.5295 +vn -0.6249 -0.1148 0.7722 +vn -0.6128 -0.3877 0.6886 +vn -0.7070 -0.6407 0.2994 +vn -0.7792 -0.5439 0.3115 +vn -0.7542 -0.6442 -0.1270 +vn -0.5994 -0.7893 -0.1334 +vn -0.6219 -0.7034 -0.3441 +vn -0.8261 -0.4284 -0.3661 +vn -0.9259 -0.2090 -0.3146 +vn -0.4075 -0.3437 -0.8461 +vn -0.5321 -0.2189 -0.8179 +vn -0.5965 0.0224 -0.8023 +vn -0.6792 0.2652 -0.6844 +vn -0.6948 0.5545 -0.4579 +vn -0.6892 0.6647 -0.2885 +vn -0.6875 0.7256 -0.0292 +vn -0.6487 0.6908 0.3194 +vn -0.3540 0.4152 0.8380 +vn -0.0416 0.5031 0.8632 +vn -0.8215 -0.3988 0.4075 +vn -0.8016 -0.4383 0.4065 +vn -0.8012 -0.4391 0.4065 +vn -0.7869 -0.4652 0.4054 +vn -0.5743 -0.8064 0.1411 +vn -0.3144 -0.4034 -0.8593 +vn -0.8942 0.3850 -0.2284 +vn -0.9140 0.3926 -0.1021 +vn -0.8946 0.3714 -0.2485 +vn -0.8702 0.3965 -0.2924 +vn -0.8764 0.3718 -0.3060 +vn -0.9952 -0.0381 -0.0900 +vn -0.9880 -0.1481 0.0436 +vn -0.9994 0.0342 0.0057 +vn 0.5153 -0.0428 0.8559 +vn -0.6458 -0.7206 0.2522 +vn -0.6250 -0.4974 0.6017 +vn -0.7164 -0.2479 0.6521 +vn -0.5969 -0.7933 0.1201 +vn -0.6384 -0.7042 -0.3107 +vn -0.6039 -0.6385 -0.4770 +vn -0.5999 -0.4577 -0.6562 +vn -0.5434 -0.4127 -0.7310 +vn -0.6673 0.3668 -0.6481 +vn -0.6541 0.1246 -0.7461 +vn -0.6636 0.1353 -0.7357 +vn -0.6740 0.3902 -0.6272 +vn -0.6222 0.6056 -0.4961 +vn -0.6110 0.6203 -0.4919 +vn -0.6243 0.7221 0.2980 +vn -0.5705 0.8188 0.0642 +vn -0.6166 0.7772 0.1253 +vn -0.7216 0.5373 0.4366 +vn -0.6562 0.4966 0.5681 +vn -0.7251 0.1499 0.6721 +vn -0.1313 0.2366 0.9627 +vn -0.8822 -0.3056 0.3582 +vn -0.7869 -0.5320 0.3127 +vn -0.8052 -0.4986 0.3211 +vn -0.6722 -0.6929 0.2608 +vn 0.3083 -0.6011 -0.7373 +vn -0.8014 0.0973 -0.5901 +vn -0.1817 0.9118 -0.3683 +vn -0.8251 0.4367 0.3585 +vn -1.0000 -0.0000 0.0000 +vn -0.9179 0.1683 -0.3593 +vn -0.8479 -0.0426 -0.5285 +vn -0.9933 -0.0141 -0.1150 +vn -0.9974 -0.0450 0.0554 +vn 0.9985 0.0424 -0.0340 +vn 0.9997 -0.0230 -0.0125 +vn 0.9999 0.0048 -0.0136 +vn 0.9999 -0.0114 0.0069 +vn 0.9999 0.0154 0.0031 +vn 1.0000 -0.0042 -0.0019 +vn 0.9998 -0.0159 -0.0073 +vn 1.0000 0.0057 -0.0050 +vn 0.9997 0.0017 -0.0224 +vn 0.9998 0.0188 -0.0111 +vn 0.9995 0.0280 -0.0115 +vn 0.9999 0.0011 -0.0122 +vn 0.9999 0.0064 -0.0087 +vn 0.9966 0.0807 -0.0191 +vn 0.9996 0.0258 -0.0081 +vn 0.9855 -0.1689 -0.0179 +vn 0.9999 0.0126 0.0037 +vn 0.9977 0.0648 0.0192 +vn 0.9999 0.0142 0.0033 +vn 1.0000 -0.0086 -0.0020 +vn 1.0000 0.0066 -0.0049 +vn 1.0000 -0.0028 -0.0067 +vn 0.9998 0.0185 -0.0113 +vn 0.7567 0.0543 0.6516 +vn -0.6908 0.1639 0.7042 +vn -0.7080 0.0071 0.7061 +vn -0.6445 -0.3486 0.6805 +vn -0.7182 -0.4859 0.4980 +vn -0.6978 -0.6672 0.2607 +vn -0.7453 -0.6300 -0.2181 +vn -0.6593 -0.7261 -0.1950 +vn -0.6831 -0.4187 -0.5984 +vn -0.6216 0.1725 -0.7641 +vn -0.6942 0.3387 -0.6351 +vn -0.5114 0.4711 -0.7187 +vn -0.6283 0.7644 0.1449 +vn -0.5007 0.8472 -0.1778 +vn -0.6382 0.7635 -0.0992 +vn -0.7165 0.6049 0.3475 +vn -0.7938 0.6062 -0.0490 +vn -0.6368 0.5296 0.5604 +vn 0.2575 0.0628 0.9642 +vn -0.7884 -0.4235 0.4461 +vn -0.4869 -0.8629 0.1355 +vn -0.5887 -0.3527 -0.7274 +vn -0.7247 0.5809 -0.3706 +vn -0.8229 0.4328 -0.3681 +vn -0.7787 0.5061 -0.3708 +vn -0.8668 0.3433 -0.3616 +vn 0.9997 0.0227 -0.0108 +vn 1.0000 0.0062 -0.0020 +vn 0.9991 -0.0405 -0.0142 +vn 0.9999 0.0134 -0.0064 +vn 1.0000 -0.0030 0.0005 +vn 0.9992 -0.0394 0.0024 +vn 0.9705 -0.2209 0.0969 +vn 0.9981 0.0564 -0.0253 +vn 0.9986 -0.0383 -0.0351 +vn -0.1434 -0.0994 0.9847 +vn -0.0731 -0.0392 0.9966 +vn -0.0992 -0.0137 0.9950 +vn -0.0917 0.1237 0.9881 +vn -0.1079 0.1171 0.9872 +vn -0.1062 -0.0018 0.9943 +vn -0.0687 0.0048 0.9976 +vn -0.0631 0.0009 0.9980 +vn -0.4033 0.3718 0.8361 +vn -0.1071 0.0007 0.9942 +vn -0.1762 0.3876 0.9048 +vn -0.1897 0.3554 0.9153 +vn -0.1426 0.4626 0.8750 +vn -0.0859 0.6924 0.7164 +vn -0.2485 0.5533 0.7951 +vn -0.2847 0.7496 0.5975 +vn -0.2138 0.8844 0.4149 +vn -0.0715 0.9157 0.3955 +vn -0.0992 0.1282 -0.9868 +vn -0.0994 -0.0003 -0.9950 +vn -0.1118 0.1169 -0.9868 +vn -0.1066 -0.0270 -0.9939 +vn -0.0844 -0.0014 -0.9964 +vn -0.1154 0.0029 -0.9933 +vn -0.1072 0.0025 -0.9942 +vn -0.1003 -0.0079 -0.9949 +vn -0.0656 -0.1596 -0.9850 +vn -0.0940 0.0013 -0.9956 +vn -0.1073 -0.5043 -0.8568 +vn -0.1016 -0.2923 -0.9509 +vn -0.0677 -0.5560 -0.8284 +vn -0.1481 -0.1513 -0.9773 +vn -0.1012 -0.7396 0.6654 +vn -0.0689 -0.8542 0.5154 +vn -0.0656 -0.5523 0.8311 +vn -0.1009 -0.4645 0.8798 +vn -0.3489 -0.6629 0.6624 +vn -0.2935 -0.4877 0.8222 +vn -0.4527 -0.4196 0.7868 +vn -0.4886 -0.6306 0.6030 +vn -0.5732 -0.4869 0.6591 +vn -0.2619 -0.8714 0.4147 +vn -0.4863 -0.7891 0.3752 +vn -0.5953 -0.7254 0.3456 +vn -0.7537 -0.5111 0.4132 +vn -0.2138 -0.9635 0.1614 +vn -0.3909 -0.9083 0.1490 +vn -0.5391 -0.8358 0.1036 +vn -0.6724 -0.3339 0.6606 +vn -0.7335 -0.6664 0.1336 +vn -0.9734 -0.1376 0.1832 +vn -0.9055 -0.3988 0.1448 +vn -0.8515 -0.2559 0.4578 +vn -0.7015 -0.7074 -0.0869 +vn -0.8615 -0.4964 -0.1069 +vn -0.9825 -0.1662 -0.0847 +vn -0.1551 -0.7727 0.6155 +vn -0.1708 -0.5171 0.8387 +vn -0.7420 -0.5828 -0.3312 +vn -0.9065 -0.2654 -0.3283 +vn -0.7817 -0.3693 -0.5026 +vn -0.4838 -0.5429 -0.6864 +vn -0.3717 -0.4962 -0.7846 +vn -0.2796 -0.7946 -0.5389 +vn -0.4114 -0.8740 -0.2586 +vn -0.2395 -0.9444 -0.2252 +vn -0.5853 -0.6753 -0.4489 +vn -0.4768 -0.8647 -0.1582 +vn -0.5864 -0.7921 -0.1693 +vn -0.5721 -0.4327 -0.6968 +vn -0.6601 -0.3487 -0.6654 +vn -0.1319 -0.8291 -0.5433 +vn -0.2471 -0.5281 -0.8124 +vn -0.1668 -0.5316 -0.8304 +vn -0.0994 -0.7683 -0.6324 +vn -0.4004 0.8784 0.2609 +vn -0.1636 0.1399 0.9766 +vn -0.3753 0.8751 -0.3055 +vn -0.1825 0.8840 -0.4305 +vn -0.2779 0.7667 -0.5788 +vn -0.1998 0.5433 -0.8154 +vn -0.3367 0.6179 -0.7105 +vn -0.1946 0.3332 -0.9226 +vn -0.1882 0.1195 -0.9748 +vn -0.2246 0.9715 0.0760 +vn -0.3164 0.9435 0.0987 +vn -0.1643 0.9590 0.2310 +vn -0.4983 0.6556 0.5673 +vn -0.2908 0.1627 0.9428 +vn -0.4264 0.4249 0.7985 +vn -0.6657 0.7412 0.0868 +vn -0.7752 0.6192 0.1251 +vn -0.6924 0.6477 0.3180 +vn -0.8657 0.4249 0.2647 +vn -0.7400 0.4888 0.4620 +vn -0.6278 0.4447 0.6388 +vn -0.7831 0.2131 0.5842 +vn -0.6293 0.1702 0.7583 +vn -0.3966 0.1122 0.9111 +vn -0.4883 0.0514 0.8712 +vn -0.6045 0.7610 0.2356 +vn -0.6002 0.5949 0.5346 +vn -0.4856 0.3500 0.8011 +vn -0.5206 0.8171 0.2475 +vn -0.9216 0.1170 0.3700 +vn -0.5700 -0.1163 0.8134 +vn -0.7624 -0.1114 0.6374 +vn -0.9095 -0.0298 0.4146 +vn -0.8161 0.5455 -0.1908 +vn -0.8997 0.2376 -0.3661 +vn -0.9281 0.3447 -0.1406 +vn -0.8262 0.5634 0.0079 +vn -0.9517 0.3066 0.0174 +vn -0.9878 0.1068 -0.1136 +vn -0.9816 0.1350 0.1351 +vn -0.8742 0.0747 -0.4798 +vn -0.7618 0.4659 -0.4501 +vn -0.6914 0.2925 -0.6606 +vn -0.6007 0.0835 -0.7951 +vn -0.1344 -0.2738 0.9524 +vn -0.2356 -0.1747 0.9560 +vn -0.8408 -0.1490 0.5205 +vn -0.9623 -0.0488 0.2677 +vn -0.9130 -0.0279 -0.4070 +vn -0.7809 -0.1102 -0.6148 +vn -0.5690 -0.1041 -0.8157 +vn -0.3657 0.3407 -0.8661 +vn -0.6960 0.6410 -0.3236 +vn -0.6801 0.7247 -0.1109 +vn -0.6287 0.4650 -0.6233 +vn -0.4701 0.1605 -0.8679 +vn -0.4901 0.3292 -0.8071 +vn -0.3562 0.0965 -0.9294 +vn -0.5356 0.5372 -0.6516 +vn -0.6112 0.6778 -0.4086 +vn -0.6206 0.7708 -0.1442 +vn -0.3009 0.1210 -0.9460 +vn -0.5515 0.8161 -0.1729 +vn -0.4610 0.5521 -0.6948 +vn -0.5078 0.7499 -0.4241 +vn -0.4355 0.8898 -0.1365 +vn -0.9401 -0.0734 -0.3329 +vn -0.2143 -0.1757 -0.9608 +vn -0.3824 -0.1536 -0.9111 +vn -0.4726 -0.2127 -0.8552 +vn -0.2431 0.9533 -0.1791 +vn -0.4991 0.8665 -0.0001 +vn -0.5812 0.8135 0.0202 +vn -0.6798 0.7333 -0.0126 +vn -0.4097 0.9122 -0.0031 +vn -0.2113 0.9737 -0.0848 +vn -0.1192 0.9921 -0.0392 +vn -0.1515 -0.9819 -0.1138 +vn -0.1214 -0.9892 0.0827 +vn -0.0855 -0.9963 0.0114 +vn -0.3005 -0.1699 -0.9385 +vn -0.3118 -0.1627 0.9361 +vn -0.4082 -0.1593 0.8989 +vn -0.0705 -0.8590 -0.5071 +vn -0.0882 -0.9709 -0.2228 +vn -0.0765 -0.9613 0.2648 +vn -0.0784 -0.1728 0.9818 +vn -0.0943 -0.0437 0.9946 +vn -0.0855 0.6809 -0.7274 +vn -0.0802 0.9073 -0.4128 +vn -0.1409 0.4561 -0.8787 +vn -0.1813 0.3872 -0.9040 +vn -0.0816 0.9927 0.0884 +vn -0.0788 0.9819 -0.1724 +vn -0.4421 0.3985 -0.8036 +vn 0.2629 -0.1207 -0.9572 +vn -0.2412 -0.3440 -0.9075 +vn -0.2301 -0.3446 -0.9101 +vn -0.2369 -0.3442 -0.9085 +vn -0.0827 -0.8034 -0.5897 +vn -0.0866 -0.8026 -0.5902 +vn -0.1771 -0.6593 -0.7307 +vn -0.1534 -0.7168 -0.6801 +vn -0.1759 -0.3803 -0.9080 +vn -0.2741 -0.1669 -0.9471 +vn -0.1519 -0.4377 -0.8862 +vn -0.3118 -0.1444 -0.9391 +vn -0.1428 0.7052 -0.6945 +vn -0.1918 0.5955 -0.7801 +vn -0.2538 0.8074 -0.5327 +vn -0.1195 0.8645 -0.4883 +vn -0.0263 0.8830 -0.4686 +vn -0.4482 0.2519 -0.8577 +vn 0.1520 -0.3499 -0.9244 +vn 0.1775 -0.3378 -0.9243 +vn 0.1119 -0.3681 -0.9230 +vn 0.0428 -0.3977 -0.9165 +vn -0.3572 -0.7061 -0.6114 +vn -0.0918 -0.9942 -0.0552 +vn -0.0601 -0.9962 -0.0635 +vn -0.0871 -0.9946 -0.0564 +vn -0.0565 -0.9963 -0.0645 +vn -0.6656 0.2012 -0.7187 +vn -0.6196 0.1983 -0.7594 +vn -0.5910 0.1929 -0.7832 +vn 0.0171 0.4344 -0.9005 +vn -0.0321 0.5642 -0.8250 +vn 0.0185 0.5394 -0.8418 +vn -0.3003 0.7063 -0.6411 +vn -0.1191 0.7843 -0.6089 +vn -0.0106 0.8070 -0.5905 +vn -0.9070 0.1628 -0.3884 +vn -0.8026 0.1134 -0.5856 +vn -0.5933 0.5391 -0.5978 +vn -0.7321 -0.6812 -0.0071 +vn -0.2587 -0.3430 -0.9030 +vn -0.7914 -0.4848 -0.3723 +vn -0.7920 -0.4840 -0.3720 +vn -0.7838 -0.4364 -0.4418 +vn -0.9984 0.0232 -0.0523 +vn -0.9326 0.0636 -0.3553 +vn -0.9971 0.0274 -0.0707 +vn -0.7677 -0.4061 -0.4958 +vn -0.7368 -0.3586 -0.5732 +vn -0.4475 -0.2294 0.8643 +vn 0.1464 0.2972 0.9435 +vn 0.2493 0.2521 0.9351 +vn -0.0119 0.3707 0.9287 +vn -0.1377 0.4068 0.9031 +vn -0.1412 0.8865 0.4406 +vn -0.1941 0.8698 0.4537 +vn -0.2994 0.8054 0.5115 +vn -0.0400 0.7037 0.7094 +vn -0.0504 0.6152 0.7867 +vn -0.5794 -0.2715 0.7685 +vn -0.6545 -0.2582 0.7106 +vn -0.6380 -0.2507 0.7280 +vn -0.2430 -0.7219 0.6479 +vn -0.0031 -0.6323 0.7747 +vn -0.0636 -0.6556 0.7524 +vn -0.6930 -0.1731 0.6999 +vn -0.1050 -0.7926 0.6006 +vn -0.0124 -0.8120 0.5835 +vn 0.0248 -0.9922 0.1224 +vn -0.0009 -0.9932 0.1164 +vn -0.2403 -0.9690 0.0573 +vn -0.2998 -0.9531 0.0414 +vn -0.4130 -0.7511 0.5150 +vn -0.3784 -0.6695 0.6392 +vn -0.3586 -0.6247 0.6937 +vn -0.3070 -0.5112 0.8027 +vn 0.2407 -0.1535 0.9584 +vn 0.2637 -0.1644 0.9505 +vn 0.1970 -0.1328 0.9714 +vn 0.1130 -0.0926 0.9893 +vn -0.3601 0.4183 0.8339 +vn -0.2599 0.6079 0.7503 +vn -0.2017 0.6860 0.6991 +vn -0.1258 0.7182 0.6844 +vn -0.1019 0.6446 0.7577 +vn -0.2208 0.1603 0.9621 +vn -0.2241 0.4527 0.8630 +vn -0.1475 0.3068 0.9403 +vn -0.2706 0.1248 0.9546 +vn -0.9998 0.0048 0.0208 +vn -0.9995 -0.0003 0.0312 +vn -0.9999 0.0092 -0.0067 +vn -0.9998 0.0136 -0.0128 +vn -1.0000 0.0074 -0.0058 +vn -0.9990 0.0083 -0.0430 +vn -0.9993 0.0029 -0.0370 +vn -1.0000 -0.0000 -0.0014 +vn -0.9998 0.0065 0.0164 +vn -0.9893 0.0059 -0.1458 +vn -0.9999 0.0107 0.0105 +vn -0.9978 0.0018 0.0659 +vn -1.0000 0.0002 0.0017 +vn -0.9984 0.0011 -0.0561 +vn -1.0000 0.0067 -0.0029 +vn -0.9999 0.0009 0.0163 +vn -0.9999 -0.0103 0.0133 +vn -0.9948 -0.0325 0.0969 +vn -0.9946 -0.0140 0.1028 +vn -0.9994 0.0038 0.0344 +vn -0.9990 -0.0007 0.0447 +vn -0.9998 0.0135 -0.0169 +vn -0.9998 -0.0117 0.0155 +vn -0.6944 0.4879 0.5290 +vn -0.6700 0.3996 0.6256 +vn -0.6988 0.5100 0.5016 +vn -0.7075 0.5862 0.3949 +vn -0.9698 0.0129 0.2434 +vn -0.9363 0.0396 0.3490 +vn -0.7874 -0.6164 -0.0052 +vn -0.7024 0.4976 0.5088 +vn -0.6734 0.3766 0.6362 +vn -0.7060 0.3097 0.6369 +vn -0.6711 0.5831 0.4579 +vn -0.8530 -0.0389 0.5205 +vn -0.2236 0.3975 0.8899 +vn -0.8326 0.4702 0.2927 +vn -0.3134 -0.7311 -0.6060 +vn -0.3278 -0.7369 -0.5913 +vn -0.2784 -0.7161 -0.6400 +vn -0.3543 -0.7467 -0.5630 +vn -0.5467 -0.3125 -0.7768 +vn -0.6706 -0.0935 -0.7359 +vn -0.6447 -0.1472 -0.7501 +vn -0.6886 0.1075 -0.7172 +vn 0.0499 -0.6725 0.7384 +vn -0.5714 -0.6022 0.5575 +vn -0.6048 -0.4582 0.6514 +vn -0.5994 -0.4890 0.6337 +vn -0.6152 -0.3735 0.6943 +vn -0.8074 0.0751 0.5852 +vn -0.8171 0.0054 0.5765 +vn -0.8151 0.1277 0.5651 +vn -0.8192 0.0059 0.5734 +vn -0.8478 0.2756 -0.4531 +vn -0.8198 0.2144 0.5310 +vn -0.7430 -0.1698 0.6473 +vn -0.6698 0.1969 0.7160 +vn -0.8062 -0.3105 -0.5036 +vn -0.8227 -0.3218 -0.4687 +vn -0.7137 -0.1208 -0.6900 +vn -0.7159 -0.0946 -0.6918 +vn -0.8048 0.1825 -0.5649 +vn -0.8037 0.1712 -0.5698 +vn -0.7740 0.3762 -0.5093 +vn -0.0190 -0.9665 -0.2559 +vn 0.0116 -0.9731 -0.2299 +vn 0.0067 -0.9846 -0.1744 +vn 0.0059 -0.8870 -0.4617 +vn -0.0665 -0.9974 -0.0274 +vn -0.0677 -0.9973 -0.0270 +vn 0.0350 -0.9834 0.1780 +vn -0.0254 -0.9133 -0.4065 +vn -0.0797 -0.9792 -0.1868 +vn 0.2544 0.9448 -0.2065 +vn 0.5627 0.8109 -0.1605 +vn 0.2857 0.9366 -0.2031 +vn 0.5673 0.8079 -0.1596 +vn -0.1559 0.9865 -0.0508 +vn -0.3986 0.8900 -0.2214 +vn 0.0026 1.0000 -0.0026 +vn 0.7464 0.5435 0.3842 +vn 0.0313 0.9995 0.0098 +vn -0.3136 0.9490 -0.0312 +vn -0.0126 0.9999 0.0028 +vn 0.1023 0.9943 0.0313 +vn 0.0712 0.9972 0.0249 +vn -0.0089 0.9929 0.1186 +vn 0.0101 0.9854 0.1700 +vn -0.4114 0.9104 -0.0445 +vn -0.1069 0.8006 -0.5896 +vn -0.0910 0.7797 -0.6195 +vn -0.1794 0.8430 -0.5071 +vn -0.0130 0.7482 -0.6634 +vn 0.0087 0.7651 -0.6438 +vn 0.0033 0.7049 -0.7093 +vn -0.0012 0.7111 -0.7031 +vn -0.0009 0.7109 -0.7033 +vn -0.0045 0.6974 -0.7166 +vn -0.1955 0.8166 -0.5431 +vn -0.2435 0.8143 -0.5270 +vn 1.0000 -0.0023 -0.0012 +vn 1.0000 -0.0079 0.0028 +vn 0.9999 -0.0132 0.0038 +vn 1.0000 -0.0098 -0.0010 +vn 1.0000 -0.0059 -0.0011 +vn 1.0000 -0.0022 0.0012 +vn 0.9998 -0.0179 -0.0074 +vn 1.0000 -0.0000 0.0000 +vn 1.0000 -0.0041 0.0019 +vn 0.9996 -0.0262 0.0142 +vn 0.9999 -0.0023 0.0154 +vn 0.9997 -0.0206 0.0111 +vn 0.9982 -0.0393 -0.0454 +vn 1.0000 -0.0000 -0.0001 +vn 1.0000 -0.0016 -0.0091 +vn 1.0000 -0.0036 -0.0038 +vn 0.9994 -0.0050 -0.0339 +vn 0.9997 -0.0251 -0.0074 +vn 1.0000 0.0001 0.0002 +vn 0.9897 -0.1020 0.1010 +vn 0.0074 -1.0000 -0.0040 +vn 0.0047 -1.0000 0.0001 +vn 0.0039 -0.9666 -0.2562 +vn -0.0037 -0.9908 -0.1353 +vn -0.0002 -1.0000 -0.0024 +vn -0.0168 -0.9794 -0.2014 +vn -0.0014 -0.9699 -0.2435 +vn -0.0121 -0.9999 -0.0051 +vn -0.0032 -1.0000 -0.0071 +vn 0.0149 -0.9993 -0.0339 +vn -0.0028 -0.9732 -0.2299 +vn -0.0115 0.6698 0.7425 +vn 0.0041 0.6187 0.7856 +vn 0.0131 0.7611 0.6485 +vn -0.0144 0.8619 0.5069 +vn 0.0093 0.9937 0.1120 +vn -0.0080 0.9985 0.0533 +vn 0.0019 -0.9558 -0.2941 +vn 0.0196 0.2802 0.9597 +vn -0.0035 -0.9632 -0.2689 +vn 0.0029 0.7220 0.6919 +vn -0.0269 0.6363 0.7710 +vn -0.0133 0.5818 0.8132 +vn -0.0158 0.8466 0.5320 +vn 0.0090 0.9939 0.1095 +vn 0.0019 0.9987 0.0506 +vn 0.0194 -0.7092 0.7047 +vn -0.0035 0.6208 0.7840 +vn -0.0461 0.6500 0.7585 +vn -0.0198 0.6322 0.7746 +vn 0.0252 0.5998 0.7997 +vn -0.0300 0.9962 0.0815 +vn 0.0140 0.9789 0.2039 +vn -0.0011 0.2308 -0.9730 +vn -0.0016 0.2110 -0.9775 +vn 0.0031 -0.2462 -0.9692 +vn -0.0028 -0.2355 -0.9719 +vn 0.0012 0.0988 -0.9951 +vn 0.0048 0.2352 -0.9719 +vn 0.0088 -0.2495 -0.9683 +vn -0.0014 -0.2487 -0.9686 +vn 1.0000 -0.0004 -0.0008 +vn 1.0000 0.0010 -0.0008 +vn 1.0000 0.0006 -0.0002 +vn 1.0000 -0.0076 -0.0056 +vn 0.9999 -0.0109 -0.0074 +vn 0.0002 0.1344 -0.9909 +vn 0.0012 0.1312 -0.9914 +vn 0.0014 -0.0117 -0.9999 +vn 0.0015 -0.0114 -0.9999 +vn 0.0012 -0.3062 -0.9520 +vn 0.0056 -0.3195 -0.9476 +vn -0.0048 -0.5748 -0.8183 +vn 0.0129 -0.6458 -0.7634 +vn -0.0101 -0.7998 -0.6002 +vn 0.0119 -0.8793 -0.4760 +vn -0.0105 -0.9497 -0.3130 +vn 0.0045 -0.9761 -0.2172 +vn -0.0041 -0.9999 -0.0097 +vn 0.0005 -0.9999 0.0110 +vn 0.0010 -0.9904 -0.1383 +vn -0.0003 -0.9917 -0.1283 +vn -0.0000 0.6820 -0.7314 +vn 0.0019 0.6822 -0.7312 +vn 0.0023 0.6619 -0.7496 +vn 0.0001 0.6813 -0.7320 +vn 0.0060 0.5275 -0.8495 +vn -0.0124 0.6770 -0.7358 +vn 0.0000 0.6815 -0.7318 +vn -0.0028 0.6839 -0.7296 +vn -0.0001 0.6820 -0.7313 +vn 0.0030 0.6978 -0.7163 +vn 0.0127 0.6857 -0.7278 +vn 0.0088 0.6823 -0.7310 +vn -0.0001 0.6820 -0.7314 +vn -0.0003 0.6820 -0.7313 +vn -0.0055 0.5343 -0.8453 +vn 0.0149 0.6810 -0.7322 +vn -0.0012 0.6821 -0.7313 +vn -0.0023 0.6820 -0.7313 +vn -0.0166 0.6818 -0.7313 +vn -0.0077 0.6823 -0.7310 +vn -0.0100 0.7020 -0.7121 +vn -0.0000 0.6818 -0.7315 +vn 0.0002 0.6820 -0.7314 +vn -0.0001 0.6815 -0.7318 +vn -0.0021 0.6832 -0.7303 +vn -0.0002 0.6818 -0.7315 +vn -0.0000 0.6820 -0.7313 +vn -0.0001 0.6821 -0.7313 +vn 0.0290 0.6963 -0.7172 +vn 0.0284 0.6842 -0.7288 +vn 0.0001 0.6815 -0.7318 +vn -0.3295 0.9261 -0.1835 +vn 0.3587 0.9104 -0.2062 +vn -0.0111 -0.8099 -0.5865 +vn -0.0204 -0.6100 -0.7922 +vn -0.0015 -0.6507 -0.7593 +vn 0.0027 -0.2631 -0.9648 +vn 0.0140 -0.3422 -0.9395 +vn -0.0094 -0.1286 -0.9916 +vn 0.0098 -0.4111 -0.9115 +vn -0.0979 -0.4108 -0.9064 +vn 0.0013 0.1926 -0.9813 +vn -0.0034 0.1627 -0.9867 +vn 0.0012 0.1774 -0.9841 +vn 0.0231 -0.3417 -0.9395 +vn 0.0329 -0.3443 -0.9383 +vn -0.0237 -0.3564 -0.9340 +vn -0.2321 -0.3358 -0.9129 +vn -0.0077 -0.3483 -0.9374 +vn -0.0056 -0.3446 -0.9387 +vn 0.0087 0.4749 0.8800 +vn 0.2549 0.1653 0.9527 +vn 0.3219 0.3811 0.8667 +vn 0.0125 0.3208 0.9471 +vn 0.0058 0.1961 0.9806 +vn 0.0167 0.1529 0.9881 +vn 0.0127 0.1317 0.9912 +vn 0.0019 -0.2237 0.9747 +vn 0.1991 -0.4644 0.8630 +vn 0.0026 -0.2294 0.9733 +vn 0.0137 -0.7917 0.6108 +vn 0.0104 -0.7678 0.6406 +vn 0.2605 -0.8720 0.4144 +vn 0.0034 -0.8044 0.5940 +vn -0.0060 -0.9997 0.0234 +vn -0.0091 -0.9726 -0.2324 +vn 0.0168 -0.7676 -0.6408 +vn 0.1067 -0.9636 -0.2452 +vn -0.0097 -0.3304 -0.9438 +vn -0.0042 -0.3361 -0.9418 +vn -0.0049 -0.3354 -0.9421 +vn 0.0008 -0.3413 -0.9399 +vn -0.0194 0.9429 -0.3325 +vn 0.3125 0.9159 -0.2521 +vn 0.2625 0.6343 -0.7272 +vn -0.0086 0.7405 -0.6720 +vn 0.1824 0.3630 -0.9138 +vn 0.2068 0.9784 0.0041 +vn 0.9169 0.2552 0.3070 +vn 0.9190 0.1224 0.3747 +vn 0.9601 0.0534 -0.2746 +vn 0.9869 -0.1332 0.0906 +vn 0.9451 -0.0810 0.3167 +vn -0.0040 0.0273 -0.9996 +vn -0.0008 0.0236 -0.9997 +vn -0.0013 0.0242 -0.9997 +vn 0.0020 0.0205 -0.9998 +vn 0.0040 0.9986 -0.0523 +vn -0.0000 0.9991 -0.0434 +vn 0.0025 0.9988 -0.0490 +vn -0.0015 0.9992 -0.0401 +vn 0.0015 0.7045 0.7097 +vn -0.0024 0.6985 0.7156 +vn -0.0000 0.7021 0.7120 +vn -0.0039 0.6961 0.7179 +vn 0.0041 -0.6788 0.7343 +vn -0.0001 -0.6821 0.7312 +vn 0.0001 -0.6819 0.7315 +vn -0.0041 -0.6852 0.7283 +vn 0.0037 -0.8023 -0.5969 +vn -0.0014 -0.7865 -0.6176 +vn 0.0029 -0.8001 -0.5999 +vn -0.0022 -0.7842 -0.6205 +vn -0.0048 -0.7742 0.6329 +vn 0.0084 -0.6826 0.7308 +vn -0.0039 -0.7682 0.6402 +vn 0.0096 -0.6729 0.7396 +vn -0.0358 0.0955 0.9948 +vn 0.2388 -0.0225 0.9708 +vn 0.2357 -0.0177 0.9717 +vn 0.0131 -0.9999 0.0077 +vn 0.0021 -1.0000 -0.0033 +vn 0.0016 -1.0000 -0.0037 +vn -0.0094 -0.9998 -0.0147 +vn -0.0083 -0.3046 -0.9524 +vn 0.0097 -0.1295 -0.9915 +vn 0.0143 -0.4412 -0.8973 +vn -0.0079 -0.3436 -0.9391 +vn 0.0204 -0.7217 -0.6919 +vn 0.3416 0.6481 -0.6807 +vn 0.0090 0.6916 -0.7223 +vn 0.3089 0.7711 -0.5568 +vn 0.0196 0.6188 -0.7853 +vn 0.0012 0.6790 -0.7342 +vn -0.0026 0.6645 -0.7473 +vn -0.0078 0.9775 -0.2110 +vn 0.0074 0.9989 -0.0470 +vn 0.0063 0.9982 -0.0593 +vn -0.0086 0.9757 -0.2191 +vn 0.0233 0.5770 -0.8164 +vn 0.0055 0.9913 0.1314 +vn 0.3508 0.8889 0.2947 +vn 0.0080 0.9479 0.3185 +vn 0.0035 0.9766 0.2152 +vn -0.0006 0.9092 0.4165 +vn 0.0110 0.8773 0.4799 +vn 0.0064 0.8691 0.4945 +vn -0.0192 0.8069 0.5904 +vn -0.0022 0.7813 0.6241 +vn -0.0647 0.8672 0.4938 +vn 0.0473 0.6980 0.7145 +vn -0.0107 0.0324 0.9994 +vn -0.0421 0.1270 0.9910 +vn -0.0375 0.1377 0.9898 +vn 0.0425 0.9918 -0.1209 +vn 0.1426 0.9482 0.2838 +vn 0.0009 0.9928 -0.1198 +vn 0.0067 0.9579 -0.2871 +vn -0.0113 0.7444 0.6677 +vn 0.0060 0.7160 0.6980 +vn 0.0019 0.7228 0.6910 +vn -0.0214 0.7602 0.6493 +vn -0.0018 0.1601 0.9871 +vn -0.0011 0.2388 0.9711 +vn 0.0248 0.2806 0.9595 +vn -0.0015 0.0242 0.9997 +vn 0.0147 0.7057 0.7083 +vn 0.0013 0.7319 0.6814 +vn 0.0049 0.7249 0.6888 +vn 0.0215 0.6920 0.7216 +vn -0.0024 0.1229 0.9924 +vn -0.0211 0.2072 0.9781 +vn 1.0000 -0.0029 0.0061 +vn 0.9996 0.0285 -0.0030 +vn 0.9947 -0.1025 -0.0008 +vn 0.9706 -0.1843 0.1546 +vn 0.0038 -0.9053 -0.4247 +vn -0.0010 -0.8970 -0.4420 +vn 0.0019 -0.9033 -0.4290 +vn 0.0134 -0.9660 -0.2583 +vn 0.0121 -0.8636 -0.5041 +vn -0.0021 -0.8718 -0.4898 +vn -0.0056 -0.5052 0.8630 +vn -0.0138 -0.3566 0.9342 +vn -0.0286 -0.0417 0.9987 +vn -0.0186 -0.8572 -0.5147 +vn -0.0421 -0.8785 -0.4758 +vn -0.0618 -0.8927 -0.4464 +vn 0.0005 -0.4082 -0.9129 +vn 0.0014 -0.4012 -0.9160 +vn 0.0013 -0.4017 -0.9158 +vn 0.0005 -0.4088 -0.9126 +vn -0.0213 -0.9369 -0.3489 +vn -0.0071 -0.9467 -0.3221 +vn 0.0229 0.2280 -0.9734 +vn -0.0191 0.2312 -0.9727 +vn 0.0021 -0.4799 -0.8773 +vn 0.0025 -0.2455 -0.9694 +vn 0.0015 -0.5488 -0.8360 +vn 0.0002 -0.5278 -0.8493 +vn 0.0010 -0.5477 -0.8367 +vn -0.0059 -0.5008 -0.8655 +vn -0.0010 -0.4832 -0.8755 +vn -0.0110 -0.5056 -0.8627 +vn 0.0006 -0.3094 -0.9509 +vn -0.0003 -0.9244 -0.3813 +vn 0.0020 -0.9156 -0.4020 +vn -0.0008 -0.8834 -0.4686 +vn 0.0054 -0.8686 -0.4955 +vn 0.8051 -0.4483 0.3883 +vn 0.6441 -0.3097 0.6994 +vn 0.7105 -0.4181 -0.5661 +vn 0.7280 -0.4432 -0.5231 +vn 0.6813 -0.6180 -0.3922 +vn 0.6951 -0.6418 -0.3239 +vn 0.4061 -0.9102 0.0818 +vn 0.7070 0.2145 0.6739 +vn 0.6883 0.1365 -0.7124 +vn 0.5500 -0.2768 -0.7879 +vn 0.7440 0.3110 0.5913 +vn 0.7041 0.1249 0.6990 +vn 0.7966 0.5512 -0.2483 +vn 0.1154 0.6735 0.7301 +vn 0.7652 0.5534 0.3290 +vn 0.5931 0.6221 0.5111 +vn 0.3662 0.9254 -0.0977 +vn 0.4365 0.8995 -0.0185 +vn 0.7994 0.6008 0.0001 +vn 0.7011 0.4829 -0.5246 +vn 0.6609 0.6495 -0.3760 +vn 0.6644 0.7386 0.1142 +vn 0.6010 -0.7723 -0.2060 +vn 0.6751 -0.3395 -0.6549 +vn 0.6830 -0.6508 -0.3316 +vn 0.6201 -0.0003 -0.7845 +vn 0.7036 -0.1596 -0.6925 +vn 0.5844 0.7264 0.3617 +vn 0.6218 0.7236 0.2997 +vn 0.5782 0.7977 0.1713 +vn 0.6378 0.7467 0.1890 +vn 0.7111 0.6540 0.2581 +vn 0.9018 0.4240 0.0842 +vn 0.9853 -0.1710 -0.0022 +vn 0.8716 -0.3410 0.3523 +vn 0.5996 -0.8003 -0.0015 +vn 0.5998 -0.8002 -0.0015 +vn 0.3775 0.7227 0.5789 +vn 0.5887 0.1699 0.7903 +vn 0.5873 0.1612 0.7932 +vn 0.7103 0.2550 0.6562 +vn 0.7065 0.2304 0.6691 +vn 0.7220 -0.3823 0.5766 +vn 0.5808 -0.4876 0.6519 +vn 0.5392 -0.4827 0.6901 +vn 0.7609 -0.5670 -0.3155 +vn 0.7137 -0.6847 -0.1478 +vn 0.7197 -0.6662 -0.1955 +vn 0.7332 -0.6690 -0.1218 +vn 0.7186 -0.6848 -0.1212 +vn 0.7224 -0.0245 -0.6910 +vn 0.7217 -0.0249 -0.6918 +vn 0.7953 -0.4511 -0.4050 +vn 0.7210 -0.0256 -0.6925 +vn 0.7182 -0.0765 -0.6917 +vn 0.7291 -0.0311 -0.6837 +vn 0.6687 -0.2937 -0.6831 +vn 0.6799 -0.6657 -0.3075 +vn 0.7208 -0.6891 -0.0747 +vn 0.6834 -0.5439 -0.4870 +vn 0.7067 -0.1655 -0.6879 +vn 0.6514 -0.6173 -0.4412 +vn 0.7552 -0.4234 -0.5003 +vn 0.6346 -0.4274 -0.6439 +vn 0.6868 -0.2395 -0.6863 +vn 0.6925 -0.2055 -0.6916 +vn 0.6965 -0.0416 -0.7164 +vn 0.6626 -0.1234 -0.7388 +vn 0.7457 -0.5043 -0.4354 +vn 0.7177 -0.6945 0.0506 +vn 0.6763 -0.7324 -0.0792 +vn 0.6982 -0.7151 -0.0335 +vn 0.6896 -0.6842 -0.2373 +vn 0.6946 -0.6863 -0.2157 +vn 0.7436 0.0635 -0.6656 +vn -0.6992 -0.4293 -0.5716 +vn -0.7450 -0.4161 -0.5214 +vn -0.9702 0.0017 -0.2423 +vn -0.9951 0.0088 -0.0980 +vn -0.7241 -0.6696 -0.1652 +vn -0.7092 -0.6672 -0.2278 +vn -0.7985 -0.3879 -0.4603 +vn -0.7368 -0.6629 -0.1333 +vn -0.7204 -0.0680 -0.6902 +vn -0.6887 -0.4827 -0.5410 +vn -0.7087 -0.0196 -0.7053 +vn -0.6970 -0.0166 -0.7169 +vn -0.6782 -0.1898 -0.7099 +vn -0.7396 -0.2954 -0.6048 +vn -0.7205 -0.4509 -0.5269 +vn -0.7210 -0.5157 -0.4629 +vn -0.7117 -0.6091 -0.3501 +vn -0.7102 -0.6540 -0.2605 +vn -0.6082 -0.7851 -0.1174 +vn -0.6913 -0.7225 -0.0134 +vn -0.7083 -0.7057 -0.0164 +vn -0.7171 -0.6932 -0.0731 +vn -0.7960 -0.4417 -0.4138 +vn -0.6887 -0.5568 -0.4644 +vn -0.7081 -0.1726 -0.6847 +vn -0.7207 -0.0252 -0.6928 +vn -0.7105 -0.0360 -0.7028 +vn -0.7021 -0.0355 -0.7112 +vn 0.9268 -0.2536 -0.2770 +vn 0.9234 -0.2547 -0.2870 +vn 0.9545 -0.2215 -0.1997 +vn -0.6100 -0.7921 0.0198 +vn -0.6069 -0.7945 0.0184 +vn -0.6091 -0.7929 0.0193 +vn -0.6062 -0.7951 0.0180 +vn -0.8323 0.5521 -0.0488 +vn -0.7849 0.6191 -0.0264 +vn -0.8218 0.5681 -0.0436 +vn -0.7645 0.6444 -0.0174 +vn 0.7322 0.6749 -0.0914 +vn 0.9293 0.3693 0.0016 +vn 0.7687 0.6348 -0.0782 +vn 0.9616 0.2730 0.0280 +vn 0.7057 -0.7085 -0.0018 +vn 0.6469 -0.7621 -0.0263 +vn 0.7240 -0.6898 0.0063 +vn 0.6282 -0.7773 -0.0336 +vn 0.1706 0.9852 -0.0170 +vn 0.5517 0.2904 -0.7818 +vn -0.5602 0.4631 -0.6868 +vn -0.0664 -0.8963 -0.4385 +vn -0.3341 -0.4389 -0.8341 +vn 0.6759 -0.3884 -0.6263 +vn 0.5752 -0.4127 -0.7063 +vn 0.4697 -0.4293 -0.7714 +vn -0.8032 -0.2878 -0.5216 +vn 0.7511 -0.3631 -0.5514 +vn 0.7003 0.7127 0.0396 +vn 0.7242 0.6887 0.0339 +vn 0.8313 0.5558 0.0047 +vn 0.8772 0.4800 -0.0106 +vn 0.7890 -0.6130 0.0410 +vn 0.8365 -0.5477 0.0206 +vn 0.7979 -0.6017 0.0374 +vn 0.8456 -0.5335 0.0164 +vn 0.0050 -0.9989 -0.0470 +vn -0.4061 -0.9134 0.0295 +vn -0.0814 -0.9962 -0.0316 +vn -0.4747 -0.8791 0.0432 +vn -0.8773 -0.4789 -0.0313 +vn -0.9985 0.0409 0.0361 +vn -0.5894 0.8049 -0.0696 +vn -0.7646 0.6435 -0.0361 +vn -0.8004 0.5980 -0.0420 +vn -0.5813 0.8131 -0.0323 +vn 0.1006 0.9936 -0.0508 +vn 0.3787 0.4710 -0.7967 +vn -0.5691 0.8146 -0.1119 +vn -0.7115 -0.1204 -0.6922 +vn -0.6400 0.0184 -0.7682 +vn -0.7527 -0.2268 -0.6181 +vn 0.2178 -0.9425 -0.2534 +vn -0.2750 -0.4858 -0.8297 +vn 0.6591 -0.1990 -0.7252 +vn 0.5831 -0.2570 -0.7707 +vn 0.4545 -0.3400 -0.8233 +vn -0.7829 -0.3448 -0.5179 +vn 0.7770 -0.0892 -0.6232 +vn -0.8303 -0.5574 -0.0006 +vn -0.7170 -0.6956 -0.0456 +vn -0.6823 -0.7288 -0.0574 +vn -0.8615 -0.5075 0.0143 +vn -0.8693 0.4942 -0.0060 +vn -0.7640 0.6428 -0.0561 +vn -0.8952 0.4456 0.0092 +vn -0.7431 0.6661 -0.0645 +vn 0.6913 0.7177 -0.0834 +vn 0.9853 0.1613 0.0568 +vn 0.7080 -0.7031 -0.0661 +vn 0.2734 -0.9600 0.0611 +vn 0.1055 0.9944 -0.0046 +vn 0.5109 0.2013 -0.8357 +vn -0.6224 0.0303 -0.7821 +vn -0.6550 0.1688 -0.7365 +vn -0.5245 0.3766 -0.7636 +vn -0.6162 -0.1898 -0.7644 +vn 0.1436 -0.5474 -0.8245 +vn -0.2411 -0.9089 -0.3401 +vn -0.4979 -0.2940 -0.8158 +vn 0.8081 -0.4300 -0.4024 +vn -0.1618 -0.0153 -0.9867 +vn -0.3536 0.0416 -0.9345 +vn -0.0898 -0.0360 -0.9953 +vn 0.8769 0.0153 -0.4804 +vn 0.8820 0.0184 -0.4708 +vn 0.8779 0.0159 -0.4786 +vn 0.8835 0.0193 -0.4681 +vn 0.7980 -0.1168 0.5913 +vn 0.8363 -0.0090 0.5482 +vn 0.7642 -0.2583 0.5911 +vn 0.8433 -0.0110 0.5373 +vn -0.6903 -0.0348 0.7227 +vn -0.9231 0.0308 0.3834 +vn -0.8793 -0.0331 0.4751 +vn -0.9633 0.0281 0.2671 +vn -0.9854 -0.0416 -0.1651 +vn -0.4128 0.0598 -0.9089 +vn -0.0667 -0.0187 0.9976 +vn 0.0838 -0.0377 0.9958 +vn 0.1030 -0.0401 0.9939 +vn -0.0847 -0.0164 0.9963 +vn -0.5181 -0.8052 0.2884 +vn 0.6830 -0.4527 0.5733 +vn -0.7906 -0.2764 -0.5464 +vn -0.2221 -0.8495 -0.4786 +vn 0.6308 -0.2584 -0.7316 +vn 0.5779 -0.7563 -0.3067 +vn -0.3068 -0.0015 -0.9518 +vn -0.0965 -0.0390 -0.9946 +vn -0.1412 -0.0271 -0.9896 +vn 0.7851 0.0077 -0.6194 +vn 0.8149 0.0214 -0.5792 +vn 0.7903 0.0100 -0.6126 +vn 0.8221 0.0248 -0.5688 +vn 0.8810 -0.0061 0.4731 +vn 0.8113 -0.0449 0.5829 +vn 0.8987 0.0055 0.4386 +vn 0.7962 -0.0522 0.6028 +vn -0.9958 -0.0090 -0.0909 +vn -0.9937 -0.0025 -0.1120 +vn -0.9954 -0.0076 -0.0955 +vn -0.9933 -0.0016 -0.1152 +vn -0.3452 -0.0517 -0.9371 +vn -0.0292 -0.0263 0.9992 +vn -0.6649 0.0113 0.7469 +vn -0.4125 -0.0070 0.9109 +vn -0.4561 -0.0178 0.8898 +vn -0.6702 -0.0458 0.7408 +vn -0.5752 -0.8170 -0.0406 +vn -0.6813 0.0641 0.7292 +vn 0.5828 -0.7178 0.3809 +vn -0.3438 -0.1006 -0.9336 +vn -0.4156 -0.6376 -0.6487 +vn 0.6627 -0.5547 -0.5031 +vn 0.6616 -0.5595 -0.4992 +vn 0.6649 -0.5443 -0.5115 +vn 0.6673 -0.5328 -0.5205 +vn 0.8001 -0.0032 -0.5999 +vn 0.7948 0.0000 -0.6068 +vn 0.8021 -0.0044 -0.5972 +vn 0.7931 0.0011 -0.6091 +vn 0.9714 -0.2287 0.0642 +vn 0.9838 -0.1754 0.0368 +vn 0.9640 -0.2543 0.0774 +vn 0.6818 -0.0060 0.7315 +vn -0.6896 -0.0820 0.7195 +vn -0.9021 0.0104 0.4314 +vn -0.7330 -0.0669 0.6769 +vn -0.9370 0.0340 0.3476 +vn -0.6435 -0.0295 -0.7649 +vn -0.6681 -0.0408 -0.7429 +vn -0.5690 0.0031 -0.8224 +vn -0.5359 0.0168 -0.8441 +vn 0.1452 0.0028 0.9894 +vn -0.5669 -0.7635 0.3094 +vn 0.9399 -0.3222 0.1127 +vn -0.7937 -0.4870 -0.3644 +vn -0.2950 -0.8434 -0.4491 +vn 0.2270 -0.3165 -0.9210 +vn 0.4496 -0.8317 -0.3257 +vn 0.9992 0.0246 0.0312 +vn 0.9992 0.0246 0.0304 +vn 0.9965 0.0240 0.0805 +vn 0.9995 0.0251 -0.0212 +vn 0.5466 0.5869 0.5973 +vn 0.5089 0.5850 0.6315 +vn 0.5298 0.5863 0.6129 +vn 0.5627 0.5873 0.5818 +vn 0.6486 -0.4601 -0.6064 +vn 0.6996 -0.2361 -0.6744 +vn 0.6433 -0.4592 -0.6126 +vn 0.6907 -0.3191 -0.6489 +vn 0.7041 0.0198 -0.7098 +vn -0.0587 0.0828 -0.9948 +vn -0.5895 0.6099 -0.5295 +vn -0.0103 0.9833 -0.1818 +vn 0.6202 0.5207 -0.5866 +vn -0.0976 -0.7149 -0.6924 +vn -0.1883 -0.7306 -0.6563 +vn -0.1284 -0.7210 -0.6809 +vn -0.2173 -0.7342 -0.6433 +vn -0.9906 0.1132 0.0766 +vn -0.9599 0.1847 0.2107 +vn -0.9837 0.1356 0.1182 +vn -0.9470 0.2043 0.2479 +vn -0.0098 0.7693 0.6388 +vn 0.2548 0.6904 0.6770 +vn 0.0611 0.7541 0.6540 +vn 0.3253 0.6588 0.6783 +vn 0.9989 -0.0308 -0.0350 +vn 0.9935 -0.0585 -0.0974 +vn 0.9958 -0.0497 -0.0775 +vn 0.9996 -0.0226 -0.0164 +vn -0.1868 0.1598 -0.9693 +vn -0.6131 0.6755 -0.4096 +vn 0.3996 0.8928 -0.2079 +vn 0.4516 0.2966 -0.8415 +vn -0.9695 -0.2183 -0.1115 +vn -0.9358 0.3140 0.1606 +vn -0.2638 0.6427 0.7193 +vn 0.6046 0.6417 0.4719 +vn 0.9409 0.1978 0.2748 +vn 0.7867 -0.4066 -0.4646 +vn 0.2613 -0.7540 -0.6027 +vn -0.3300 -0.6523 -0.6824 +vn -0.4899 0.3366 -0.8042 +vn -0.4475 0.8223 -0.3516 +vn 0.4105 0.8866 -0.2134 +vn 0.3446 0.1158 -0.9316 +vn -0.8472 -0.3609 -0.3899 +vn -0.9869 -0.1518 -0.0543 +vn -0.9067 -0.3031 -0.2934 +vn -0.9948 -0.0978 0.0273 +vn -0.7716 0.5151 0.3733 +vn 0.5604 0.6229 0.5458 +vn 0.3127 0.6422 0.6998 +vn 0.4034 0.6417 0.6523 +vn 0.6391 0.6026 0.4780 +vn 0.9315 -0.3055 -0.1976 +vn 0.5368 -0.5531 -0.6371 +vn -0.0060 -0.7598 -0.6501 +vn -0.4163 0.2805 -0.8649 +vn -0.4782 0.8310 -0.2842 +vn 0.5761 0.7544 -0.3146 +vn 0.2324 0.1598 -0.9594 +vn -0.7376 -0.4949 -0.4594 +vn -0.8051 -0.4569 -0.3783 +vn -0.7579 -0.4847 -0.4367 +vn -0.8192 -0.4473 -0.3589 +vn -0.7459 0.5332 0.3991 +vn -0.5770 0.5884 0.5663 +vn -0.6985 0.5537 0.4533 +vn -0.5143 0.5989 0.6138 +vn 0.8483 0.4129 0.3316 +vn 0.8125 0.4336 0.3896 +vn 0.8257 0.4265 0.3692 +vn 0.8587 0.4059 0.3129 +vn 0.4330 -0.6600 -0.6139 +vn 0.5163 -0.6488 -0.5590 +vn 0.4937 -0.6526 -0.5748 +vn 0.4066 -0.6621 -0.6295 +vn -0.5141 0.3236 -0.7944 +vn -0.2895 0.9356 -0.2022 +vn 0.5644 0.7235 -0.3975 +vn 0.2214 0.1435 -0.9646 +vn -0.8610 -0.3319 -0.3853 +vn -0.9854 -0.1435 -0.0914 +vn -0.9027 -0.2899 -0.3179 +vn -0.9960 -0.0889 -0.0094 +vn -0.4681 0.6873 0.5554 +vn -0.1887 0.6947 0.6941 +vn -0.3854 0.6969 0.6048 +vn -0.0977 0.6833 0.7236 +vn 0.9087 0.3451 0.2348 +vn 0.9966 0.0090 0.0814 +vn 0.9533 0.2374 0.1869 +vn 0.9949 -0.0959 0.0313 +vn 0.3767 -0.6163 -0.6916 +vn -0.2221 -0.7533 -0.6190 +vn -0.4930 0.3405 -0.8007 +vn -0.3323 0.9267 -0.1758 +vn 0.6351 0.6177 -0.4637 +vn 0.1163 0.1453 -0.9825 +vn 0.1530 -0.7310 -0.6650 +vn 0.0352 -0.7658 -0.6422 +vn -0.0085 -0.7756 -0.6311 +vn -0.8582 -0.3321 -0.3915 +vn -0.9966 -0.0088 0.0816 +vn -0.5014 0.6844 0.5294 +vn -0.2800 0.7033 0.6535 +vn -0.4454 0.6938 0.5659 +vn -0.1996 0.6993 0.6864 +vn 0.9729 0.1778 0.1476 +vn 0.9647 0.1912 0.1809 +vn 0.9678 0.1864 0.1689 +vn 0.9755 0.1730 0.1358 +vn 0.2084 -0.7103 -0.6723 +vn -0.6078 0.5414 -0.5809 +vn -0.0096 0.9885 -0.1511 +vn 0.6032 0.4930 -0.6270 +vn 0.0102 0.1125 -0.9936 +vn -0.7693 -0.5196 -0.3717 +vn -0.9965 0.0530 -0.0650 +vn -0.6300 0.5209 0.5760 +vn -0.0067 0.7819 0.6233 +vn 0.6978 0.4593 0.5497 +vn 0.9909 -0.0107 -0.1339 +vn 0.6319 -0.6165 -0.4697 +vn 0.0098 -0.6843 -0.7292 +vn 0.0230 0.0439 -0.9988 +vn -0.5754 0.5453 -0.6095 +vn -0.2068 0.9505 -0.2321 +vn 0.6069 0.6871 -0.3994 +vn 0.0455 -0.6772 -0.7344 +vn -0.1303 -0.7141 -0.6879 +vn -0.0014 -0.6893 -0.7244 +vn -0.1905 -0.7211 -0.6661 +vn -0.9988 -0.0350 -0.0351 +vn -0.9948 -0.0847 -0.0570 +vn -0.9961 -0.0720 -0.0514 +vn -0.9993 -0.0215 -0.0292 +vn -0.3533 0.7001 0.6205 +vn -0.0891 0.6833 0.7247 +vn -0.2713 0.7009 0.6597 +vn -0.0226 0.6706 0.7415 +vn 0.9339 0.3188 0.1619 +vn 0.9720 -0.2202 -0.0826 +vn -0.5608 0.4086 -0.7201 +vn -0.3399 0.9003 -0.2717 +vn 0.5265 0.7747 -0.3502 +vn 0.3070 0.1226 -0.9438 +vn -0.9422 -0.2364 -0.2375 +vn -0.9554 -0.1960 -0.2210 +vn -0.9519 -0.2072 -0.2257 +vn -0.9388 -0.2460 -0.2413 +vn -0.5702 0.5986 0.5626 +vn -0.5818 0.5961 0.5534 +vn -0.5734 0.5980 0.5601 +vn -0.5849 0.5954 0.5508 +vn 0.8519 0.3623 0.3782 +vn 0.8732 0.3494 0.3398 +vn 0.8660 0.3539 0.3532 +vn 0.8432 0.3671 0.3928 +vn 0.4722 -0.6031 -0.6429 +vn 0.2703 -0.7228 -0.6360 +vn 0.4059 -0.6479 -0.6446 +vn 0.1983 -0.7544 -0.6257 +vn -0.0053 -0.9639 -0.2661 +vn 0.0079 -0.9514 -0.3077 +vn 0.0104 -0.9020 -0.4316 +vn -0.0139 -0.9315 -0.3634 +vn -0.0157 -0.8294 -0.5584 +vn -0.0034 -0.9607 -0.2775 +vn 0.0001 -0.6408 -0.7677 +vn 0.0057 -0.7027 -0.7115 +vn 1.0000 -0.0001 0.0000 +vn 1.0000 0.0001 -0.0000 +vn 1.0000 0.0004 -0.0000 +vn -1.0000 0.0001 -0.0001 +vn -1.0000 -0.0000 -0.0001 +vn -0.9997 0.0126 -0.0201 +vn -0.0268 0.1705 -0.9850 +vn 0.0170 0.2429 -0.9699 +vn 1.0000 -0.0002 -0.0001 +vn 1.0000 -0.0003 -0.0001 +vn 0.0010 -0.3343 -0.9425 +vn -0.0039 -0.3282 -0.9446 +vn -0.0173 -0.3117 -0.9500 +vn 0.0154 -0.3517 -0.9360 +vn -0.8018 -0.4482 -0.3953 +vn -0.8102 -0.4472 -0.3790 +vn -0.8164 -0.3984 -0.4179 +vn -0.8897 -0.2188 -0.4008 +vn -0.8672 -0.2794 -0.4122 +vn 0.0057 -0.1422 -0.9898 +vn 0.0038 -0.1480 -0.9890 +vn -0.0027 -0.1688 -0.9856 +vn -0.0048 -0.1756 -0.9845 +vn 0.9981 0.0583 -0.0223 +vn 0.9977 0.0627 -0.0242 +vn 0.8983 0.1127 0.4246 +vn 0.9876 0.0233 0.1553 +vn -0.9939 0.0427 0.1020 +vn -0.9917 0.0266 -0.1259 +vn -0.9847 -0.0048 -0.1742 +vn -0.9918 0.0363 0.1227 +vn -0.0280 0.2681 0.9630 +vn -0.0233 0.2534 0.9671 +vn -0.0059 0.1991 0.9800 +vn -0.0010 0.1837 0.9830 +vn -0.8847 -0.1631 -0.4367 +vn 0.7514 -0.2122 -0.6248 +vn -0.9104 -0.0077 0.4137 +vn 0.8611 0.0472 0.5063 +vn 0.6057 0.2038 0.7691 +vn -0.0041 -0.8972 -0.4416 +vn -0.0008 -0.9101 -0.4144 +vn -0.0010 -0.7392 -0.6735 +vn 0.0015 -0.7525 -0.6586 +vn 0.0006 -0.9627 -0.2707 +vn -0.0014 -0.9617 -0.2742 +vn 0.0003 0.1807 -0.9835 +vn -0.0010 0.2041 -0.9790 +vn 0.8669 -0.1810 -0.4644 +vn 0.9441 -0.1162 -0.3086 +vn 0.9995 -0.0038 0.0313 +vn -0.9998 -0.0131 0.0138 +vn -0.0016 0.2428 -0.9701 +vn 0.0007 0.2453 -0.9694 +vn 0.7806 -0.2212 -0.5846 +vn 0.5943 -0.2665 -0.7588 +vn 0.6761 -0.2458 -0.6946 +vn -0.6382 -0.2332 -0.7337 +vn -0.8833 -0.1841 -0.4311 +vn -0.6600 -0.2568 -0.7061 +vn 0.6383 0.1524 -0.7545 +vn 0.6407 -0.7247 -0.2536 +vn -0.6163 0.1511 -0.7729 +vn -0.6592 -0.7084 -0.2522 +vn 0.3392 -0.0990 0.9355 +vn 0.9144 0.0833 0.3963 +vn 0.7550 -0.0877 -0.6498 +vn 0.0463 0.0903 -0.9948 +vn -0.9725 -0.1153 -0.2023 +vn -0.8155 0.1119 0.5678 +vn 0.6096 0.0406 -0.7917 +vn -0.9863 0.0411 -0.1597 +vn -0.3403 -0.0457 0.9392 +vn 0.3813 0.0540 0.9229 +vn -0.0143 -0.9124 0.4090 +vn -0.0014 -0.8586 0.5127 +vn -0.0133 -0.9087 0.4173 +vn -0.0001 -0.8524 0.5230 +vn -0.0002 -0.9376 -0.3478 +vn -0.0013 -0.9394 -0.3429 +vn -0.0044 -0.9379 -0.3468 +vn 0.0049 -0.9413 -0.3376 +vn -0.0003 -0.9415 -0.3369 +vn 0.0007 -0.9404 -0.3400 +vn -0.0042 -0.9411 -0.3381 +vn 0.0052 -0.9376 -0.3478 +vn -0.0035 -0.9378 -0.3471 +vn -0.0020 -0.9418 -0.3362 +vn 0.0030 -0.9373 -0.3485 +vn 0.0000 -0.9397 -0.3420 +vn 0.0001 -0.9423 -0.3348 +vn 0.0091 -0.9398 -0.3416 +vn -0.0001 -0.9397 -0.3420 +vn 0.0003 -0.3561 -0.9345 +vn -0.0035 -0.3293 -0.9442 +vn 0.0000 -0.3540 -0.9353 +vn -0.0038 -0.3268 -0.9451 +vn -1.0000 0.0009 -0.0001 +vn -0.5349 -0.8412 -0.0799 +vn -0.3778 -0.6203 -0.6874 +vn 0.4914 -0.5698 -0.6586 +vn 0.2436 -0.9205 0.3055 +vn -0.9227 -0.1367 0.3605 +vn -0.9043 -0.1373 0.4042 +vn -0.9091 -0.1372 0.3934 +vn -0.9270 -0.1365 0.3494 +vn -0.6521 0.2616 -0.7116 +vn -0.6403 0.2698 -0.7192 +vn -0.6490 0.2637 -0.7136 +vn -0.6374 0.2718 -0.7210 +vn 0.7641 0.2099 -0.6100 +vn 0.7882 0.2154 -0.5765 +vn 0.7730 0.2119 -0.5979 +vn 0.7965 0.2173 -0.5642 +vn 0.3851 -0.3281 0.8626 +vn 0.3709 -0.3238 0.8704 +vn 0.3802 -0.3266 0.8653 +vn 0.3657 -0.3222 0.8732 +vn -0.6345 -0.7268 -0.2631 +vn -0.0169 -0.5716 -0.8204 +vn 0.5516 -0.6967 -0.4586 +vn 0.1631 -0.9294 0.3311 +vn -0.5001 -0.1757 0.8480 +vn -0.9950 -0.0962 -0.0262 +vn -0.5972 0.3814 -0.7055 +vn -0.0352 0.2843 -0.9581 +vn 0.9472 0.1225 -0.2963 +vn 0.9884 0.1326 -0.0737 +vn 0.9690 0.1272 -0.2117 +vn 0.9909 0.1342 -0.0127 +vn 0.2462 -0.4381 0.8646 +vn -0.5319 -0.8462 0.0308 +vn -0.2315 -0.5407 -0.8088 +vn 0.5422 -0.6696 -0.5076 +vn 0.2817 -0.9340 0.2197 +vn -0.8626 -0.1949 0.4669 +vn -0.9081 -0.1371 0.3958 +vn -0.8743 -0.1813 0.4503 +vn -0.9179 -0.1226 0.3775 +vn -0.3949 0.2935 -0.8706 +vn -0.4568 0.3022 -0.8367 +vn -0.4422 0.3003 -0.8452 +vn -0.3817 0.2914 -0.8771 +vn 0.8945 0.1394 -0.4247 +vn 0.8134 0.2264 -0.5358 +vn 0.8333 0.2075 -0.5123 +vn 0.9101 0.1185 -0.3971 +vn 0.4744 -0.2886 0.8317 +vn 0.4628 -0.2867 0.8388 +vn 0.4715 -0.2881 0.8335 +vn 0.4602 -0.2863 0.8404 +vn 0.0064 -0.8755 0.4832 +vn -0.0033 -0.9769 0.2138 +vn 0.0058 -0.9824 0.1868 +vn -0.0129 -0.9187 0.3947 +vn -0.0044 -0.9869 0.1610 +vn 0.0077 -0.8958 0.4445 +vn -0.0225 -0.9582 0.2852 +vn -0.0063 -0.9987 -0.0496 +vn -0.0363 -0.9931 -0.1116 +vn 0.0058 -0.9816 -0.1909 +vn 0.1748 0.9661 0.1900 +vn 0.4945 0.8503 0.1802 +vn 0.1983 0.9615 0.1901 +vn 0.4987 0.8479 0.1799 +vn -0.0255 0.7432 0.6686 +vn 0.0138 0.7631 0.6461 +vn -0.1955 0.8071 0.5571 +vn -0.2716 0.8070 0.5244 +vn 0.0199 0.7689 0.6390 +vn -0.0294 0.7675 0.6404 +vn -0.0055 0.7138 0.7003 +vn 0.0017 0.7095 0.7047 +vn 0.0037 0.6981 0.7160 +vn 0.2462 0.8396 0.4841 +vn 0.3221 0.8332 0.4495 +vn -0.0075 -1.0000 0.0050 +vn -0.0032 -1.0000 0.0044 +vn -0.0116 -0.9718 0.2355 +vn 0.0056 -0.9997 0.0256 +vn 0.0163 -0.8966 0.4425 +vn -0.0182 -0.9991 0.0379 +vn -0.0323 -0.9987 0.0392 +vn 0.0008 -1.0000 0.0025 +vn 0.0124 -0.9996 0.0263 +vn -0.0053 -0.9989 0.0463 +vn 0.0010 -0.9593 0.2823 +vn 0.0064 -0.9652 0.2615 +vn 0.0882 0.7702 -0.6317 +vn -0.0144 0.3936 -0.9192 +vn 0.0070 0.6598 -0.7514 +vn -0.0183 0.3343 -0.9423 +vn -0.0103 0.2394 -0.9709 +vn 0.0142 0.1541 -0.9879 +vn 0.0013 0.6122 -0.7907 +vn 0.0019 0.7889 -0.6145 +vn 0.0004 0.8461 -0.5330 +vn 0.0050 0.5983 -0.8013 +vn -0.0001 0.6129 -0.7902 +vn -0.0073 0.9266 -0.3759 +vn -0.0071 0.9268 -0.3754 +vn 0.0025 0.9973 -0.0735 +vn -0.0003 0.9854 -0.1704 +vn 0.1622 0.9867 0.0065 +vn 0.0001 -0.9866 -0.1633 +vn 0.0008 -0.9822 -0.1881 +vn 0.0008 -0.9825 -0.1860 +vn 0.0001 -0.9866 -0.1631 +vn -0.0003 0.8566 -0.5160 +vn 0.0012 0.6116 -0.7912 +vn 0.0012 0.7976 -0.6032 +vn 0.0072 0.7786 -0.6274 +vn -0.0028 0.7568 -0.6536 +vn -0.0043 0.9772 -0.2122 +vn 0.0035 0.9745 -0.2242 +vn -0.0131 0.9998 -0.0127 +vn -0.0417 0.9985 -0.0350 +vn -0.0389 0.9983 -0.0433 +vn 0.1766 0.0027 0.9843 +vn 0.0297 0.4491 0.8930 +vn 0.0931 0.0703 0.9932 +vn -0.0083 -0.2190 0.9757 +vn 0.0036 -0.2686 0.9632 +vn -0.0003 0.0935 0.9956 +vn -0.0075 0.2255 0.9742 +vn -0.0093 -0.2015 0.9794 +vn 0.0020 0.1207 0.9927 +vn 0.0006 0.1219 0.9925 +vn -0.0008 -0.2509 0.9680 +vn 0.9406 -0.2517 0.2279 +vn 0.9990 -0.0045 -0.0440 +vn 0.9348 -0.2711 0.2294 +vn 0.9999 -0.0131 0.0017 +vn 0.9999 -0.0099 0.0044 +vn 1.0000 -0.0054 0.0032 +vn 1.0000 -0.0011 0.0012 +vn 0.0002 -0.9909 -0.1344 +vn 0.0019 -0.9917 -0.1287 +vn 0.0033 -0.9999 0.0162 +vn -0.0048 -1.0000 -0.0073 +vn 0.0069 -0.9512 0.3083 +vn -0.0094 -0.9673 0.2535 +vn 0.0020 -0.8384 0.5451 +vn 0.0014 -0.8379 0.5458 +vn 0.3654 -0.6087 0.7043 +vn 0.0097 -0.6146 0.7888 +vn 0.2082 -0.4617 0.8623 +vn 0.0106 -0.4354 0.9002 +vn -0.0050 -0.2977 0.9547 +vn 0.2175 0.4498 0.8662 +vn 0.0005 0.0847 0.9964 +vn -0.0044 -0.1589 0.9873 +vn -0.0022 -0.0151 0.9999 +vn 0.0012 0.1358 0.9907 +vn -0.0002 0.1314 0.9913 +vn 0.0002 0.6800 0.7332 +vn 0.0054 0.6449 0.7643 +vn -0.0311 0.6692 0.7425 +vn -0.0001 0.6820 0.7313 +vn -0.0000 0.6820 0.7314 +vn 0.0000 0.6820 0.7313 +vn 0.0001 0.6820 0.7314 +vn -0.0072 0.5248 0.8512 +vn -0.0139 0.6891 0.7245 +vn 0.0038 0.6749 0.7379 +vn -0.0166 0.6863 0.7271 +vn -0.0002 0.6988 0.7153 +vn 0.0001 0.6816 0.7317 +vn 0.0062 0.6840 0.7295 +vn 0.0046 0.6871 0.7266 +vn 0.0027 0.6822 0.7312 +vn -0.0001 0.6820 0.7314 +vn -0.0000 0.6813 0.7320 +vn 0.0000 0.6819 0.7314 +vn 0.0010 0.6822 0.7312 +vn 0.0102 0.6842 0.7292 +vn 0.0002 0.6817 0.7317 +vn -0.0003 0.6819 0.7314 +vn -0.0004 0.6821 0.7313 +vn -0.0003 0.6818 0.7315 +vn -0.0036 0.6830 0.7304 +vn -0.0012 0.6866 0.7270 +vn -0.3748 0.9020 0.2142 +vn -0.3835 0.8984 0.2140 +vn -0.0148 -0.3906 0.9204 +vn -0.0202 -0.6065 0.7948 +vn -0.1107 -0.5337 0.8384 +vn -0.0149 -0.7971 0.6036 +vn -0.0012 -0.3487 0.9372 +vn 0.0758 -0.4273 0.9009 +vn -0.0301 -0.4458 0.8946 +vn -0.0028 -0.2341 0.9722 +vn -0.0091 -0.3270 0.9450 +vn -0.0262 -0.2748 0.9611 +vn 0.0284 -0.5157 0.8563 +vn 0.0117 -0.4456 0.8951 +vn 0.0812 -0.3373 0.9379 +vn 0.0166 0.3084 -0.9511 +vn 0.0014 0.2288 -0.9735 +vn -0.0021 0.4218 -0.9067 +vn 0.0119 0.4823 -0.8759 +vn 0.0017 0.5153 -0.8570 +vn 0.0843 -0.3744 -0.9234 +vn -0.0028 -0.4203 -0.9074 +vn -0.0043 -0.2058 -0.9786 +vn 0.1581 -0.1126 -0.9810 +vn 0.1489 -0.9146 -0.3758 +vn 0.0054 -0.8009 -0.5988 +vn 0.0035 -0.6858 -0.7277 +vn -0.0041 -0.9953 -0.0968 +vn 0.2541 -0.9465 0.1990 +vn 0.0223 -0.8166 0.5768 +vn -0.0068 -0.9876 0.1569 +vn -0.0031 -0.3395 0.9406 +vn -0.0001 -0.3426 0.9395 +vn 0.0068 -0.1442 0.9895 +vn -0.0042 -0.3147 0.9492 +vn 0.0190 0.1244 0.9921 +vn -0.0071 0.7358 0.6771 +vn 0.0078 0.8256 0.5641 +vn -0.0060 0.7426 0.6697 +vn 0.0091 0.8323 0.5543 +vn 0.4759 0.8789 0.0326 +vn -0.0241 0.9996 -0.0170 +vn 1.0000 0.0017 0.0080 +vn 0.9999 0.0133 -0.0081 +vn 0.9999 0.0111 -0.0047 +vn 0.9669 -0.1808 -0.1802 +vn 0.9871 -0.1275 -0.0968 +vn -0.0054 0.0173 0.9998 +vn -0.0104 0.0227 0.9997 +vn -0.0060 0.0179 0.9998 +vn -0.0011 0.0127 0.9999 +vn -0.0012 0.9988 0.0491 +vn 0.0008 0.9990 0.0447 +vn -0.0004 0.9989 0.0475 +vn 0.0016 0.9991 0.0431 +vn -0.0015 0.7045 -0.7097 +vn 0.0024 0.6985 -0.7156 +vn 0.0000 0.7021 -0.7120 +vn 0.0039 0.6961 -0.7179 +vn -0.0041 -0.6674 -0.7447 +vn 0.0076 -0.6768 -0.7361 +vn 0.0065 -0.6760 -0.7368 +vn 0.0179 -0.6851 -0.7282 +vn -0.0265 -0.9248 0.3795 +vn 0.0149 -0.8072 0.5901 +vn -0.0207 -0.9116 0.4104 +vn 0.0207 -0.7867 0.6169 +vn -0.0012 -0.7434 -0.6688 +vn 0.0075 -0.6876 -0.7260 +vn 0.0067 -0.6930 -0.7209 +vn -0.0019 -0.7474 -0.6643 +vn 0.0090 -0.9999 0.0099 +vn 0.0034 -1.0000 0.0045 +vn 0.0031 -1.0000 0.0042 +vn -0.0026 -1.0000 -0.0012 +vn -0.0093 -0.3553 0.9347 +vn 0.0161 -0.6086 0.7933 +vn 0.0120 -0.3868 0.9221 +vn -0.0098 -0.3231 0.9463 +vn 0.0099 -0.0974 0.9952 +vn 0.2327 0.8895 0.3933 +vn 0.0036 0.7399 0.6727 +vn 0.0900 0.6805 0.7272 +vn 0.1812 0.6955 0.6953 +vn 0.0461 0.6691 0.7418 +vn 0.3867 0.5704 0.7246 +vn -0.0043 0.9087 0.4174 +vn -0.0078 0.9789 0.2043 +vn 0.4186 0.8987 -0.1312 +vn 0.0150 0.8783 -0.4779 +vn 0.0002 0.8501 -0.5266 +vn -0.0011 0.9060 -0.4233 +vn 0.0108 0.9505 -0.3105 +vn 0.0028 0.9767 -0.2144 +vn 0.0163 0.9936 -0.1118 +vn 0.0058 0.9895 -0.1441 +vn 0.0052 0.0667 -0.9978 +vn -0.0103 0.0520 -0.9986 +vn -0.0002 0.1520 -0.9884 +vn 0.0073 0.3758 -0.9267 +vn 0.0071 0.3751 -0.9270 +vn 0.0001 0.7902 -0.6129 +vn 0.0092 0.7696 -0.6384 +vn 0.0028 0.7842 -0.6205 +vn 0.0103 0.7670 -0.6416 +vn 0.0149 0.7243 0.6893 +vn 0.0046 0.9932 0.1161 +vn 0.0285 0.9831 0.1806 +vn -0.0019 0.4872 -0.8733 +vn 0.0171 0.7415 -0.6707 +vn -0.0036 0.5831 -0.8124 +vn -0.0142 0.6312 -0.7755 +vn 0.0153 0.4608 -0.8874 +vn -0.0030 0.1789 -0.9839 +vn 0.0381 -0.0133 -0.9992 +vn 0.0619 0.9928 -0.1030 +vn -0.0487 0.8288 -0.5574 +vn -0.0097 0.7731 -0.6342 +vn -0.0227 0.7926 -0.6094 +vn 0.0204 0.7248 -0.6887 +vn -0.0018 0.2450 -0.9695 +vn -0.0387 0.1595 -0.9864 +vn -0.0399 0.1001 -0.9942 +vn 0.3740 -0.1701 -0.9117 +vn 0.9471 -0.0590 0.3154 +vn 0.9153 0.3854 -0.1169 +vn 0.9730 0.1690 0.1569 +vn 0.9734 0.0422 -0.2250 +vn 0.0001 -0.8710 0.4912 +vn -0.0112 -0.8619 0.5070 +vn 0.0176 -0.8504 0.5259 +vn 0.0206 -0.8445 0.5351 +vn 0.0066 -0.8703 0.4924 +vn 0.0341 -0.8710 0.4901 +vn 0.0374 -0.0733 -0.9966 +vn -0.0001 -0.5002 -0.8659 +vn 0.0106 -0.3486 -0.9372 +vn 0.0163 -0.8514 0.5243 +vn 0.0494 -0.8828 0.4672 +vn 0.0060 -0.8850 0.4655 +vn 0.0122 -0.8950 0.4460 +vn -0.0007 -0.4020 0.9156 +vn -0.0004 -0.4044 0.9146 +vn -0.0004 -0.4042 0.9147 +vn -0.0007 -0.4018 0.9157 +vn -0.0240 0.2274 0.9735 +vn -0.0033 -0.9085 0.4179 +vn 0.0004 -0.9228 0.3852 +vn 0.0001 -0.9218 0.3877 +vn -0.0035 -0.9074 0.4202 +vn 0.0010 -0.5434 0.8394 +vn 0.0029 -0.5438 0.8392 +vn -0.0095 -0.5551 0.8317 +vn 0.0015 -0.4443 0.8959 +vn 0.0059 -0.4763 0.8792 +vn 0.0284 -0.5481 0.8359 +vn 0.0235 -0.5335 0.8455 +vn 0.0042 -0.4672 0.8841 +vn 0.6568 -0.5370 -0.5294 +vn 0.5287 -0.5587 -0.6390 +vn 0.7262 -0.4721 -0.4998 +vn 0.8569 -0.3847 -0.3432 +vn 0.7236 -0.4653 0.5098 +vn 0.6401 -0.7325 0.2320 +vn 0.7620 -0.3713 0.5305 +vn 0.3506 -0.1388 -0.9262 +vn 0.8051 -0.1971 0.5594 +vn 0.8089 -0.1946 0.5548 +vn 0.6349 0.3824 -0.6713 +vn 0.6967 0.3131 -0.6454 +vn 0.7085 0.3511 -0.6122 +vn 0.7467 0.2207 -0.6275 +vn 0.8085 0.2872 -0.5136 +vn 0.6905 0.1632 -0.7047 +vn 0.5673 0.1362 -0.8122 +vn 0.7692 0.1056 -0.6302 +vn 0.8053 0.1137 -0.5819 +vn 0.6331 0.4280 0.6450 +vn 0.6335 0.2837 0.7198 +vn 0.6321 0.4429 0.6359 +vn 0.6149 0.5661 0.5490 +vn 0.1548 0.6502 -0.7438 +vn 0.6804 0.7076 -0.1904 +vn 0.6255 0.6050 -0.4927 +vn 0.5743 0.7864 -0.2275 +vn 0.7981 0.5997 0.0584 +vn 0.4645 0.6229 0.6295 +vn 0.3831 0.6622 0.6440 +vn 0.8720 0.3416 0.3507 +vn 0.7547 0.1912 0.6276 +vn 0.5427 0.8395 -0.0265 +vn 0.6327 0.7326 -0.2510 +vn 0.6952 -0.1934 0.6923 +vn 0.5446 -0.6096 0.5760 +vn 0.6833 -0.4641 0.5636 +vn 0.4820 0.1447 0.8641 +vn 0.5253 0.7483 -0.4050 +vn 0.6021 0.7870 -0.1345 +vn 0.8153 0.4848 -0.3168 +vn 0.6390 0.6874 -0.3451 +vn 0.5395 -0.8420 0.0028 +vn 0.5888 -0.8083 -0.0012 +vn 0.5419 -0.8405 0.0026 +vn 0.5919 -0.8060 -0.0015 +vn 0.9347 -0.3553 0.0067 +vn 0.8786 -0.3834 -0.2846 +vn 0.2387 0.7289 -0.6417 +vn 0.4114 0.6787 -0.6084 +vn 0.3195 0.0460 -0.9465 +vn 0.8630 0.1702 -0.4758 +vn 0.7834 -0.2046 -0.5869 +vn 0.5114 0.6513 -0.5605 +vn 0.4792 -0.0103 -0.8776 +vn 0.5956 -0.5280 -0.6053 +vn 0.6911 -0.7141 0.1117 +vn 0.7693 -0.5606 0.3064 +vn 0.7355 -0.6558 0.1703 +vn 0.8037 -0.3603 0.4736 +vn 0.7218 -0.6715 0.1672 +vn 0.7978 -0.4506 0.4005 +vn 0.7219 -0.0257 0.6915 +vn 0.7198 -0.0285 0.6936 +vn 0.7043 -0.1941 0.6828 +vn 0.7161 -0.0738 0.6941 +vn 0.6919 -0.4823 0.5374 +vn 0.7209 -0.6895 0.0691 +vn 0.6851 -0.5557 0.4710 +vn 0.6907 -0.7221 0.0384 +vn 0.6569 -0.7464 0.1072 +vn 0.7229 -0.6889 -0.0528 +vn 0.7461 -0.5129 0.4246 +vn 0.6151 -0.6710 0.4141 +vn 0.6861 -0.6936 0.2195 +vn 0.6968 -0.6796 0.2295 +vn 0.7468 -0.4061 0.5268 +vn 0.7245 0.0099 0.6892 +vn 0.7431 0.0654 0.6660 +vn 0.6966 -0.0908 0.7117 +vn 0.7800 -0.0971 0.6182 +vn 0.5443 -0.4488 0.7087 +vn -0.7232 -0.2279 0.6520 +vn -0.7091 -0.4301 0.5588 +vn -0.7276 -0.0067 0.6860 +vn -0.7584 0.1162 0.6414 +vn -0.7209 -0.6262 0.2969 +vn -0.6929 -0.6900 0.2092 +vn -0.7182 -0.6736 0.1745 +vn -0.7874 -0.4042 0.4655 +vn -0.7208 -0.0678 0.6898 +vn -0.7002 -0.4872 0.5219 +vn -0.6339 -0.0015 0.7734 +vn -0.7172 -0.1652 0.6770 +vn -0.7323 -0.2358 0.6389 +vn -0.7037 -0.3535 0.6164 +vn -0.6557 -0.4613 0.5977 +vn -0.6945 -0.5499 0.4640 +vn -0.6818 -0.6239 0.3819 +vn -0.6837 -0.6755 0.2763 +vn -0.6968 -0.6884 0.2014 +vn -0.7102 -0.7009 0.0663 +vn -0.7083 -0.7054 -0.0249 +vn -0.7133 -0.6999 0.0369 +vn -0.7235 -0.6874 0.0638 +vn -0.6666 -0.6809 0.3033 +vn -0.7025 -0.1135 0.7026 +vn -0.6654 -0.3122 0.6781 +vn -0.6785 -0.1995 0.7070 +vn -0.7088 -0.0559 0.7032 +vn -0.7218 -0.0250 0.6917 +vn -0.7211 -0.0258 0.6924 +vn 0.8397 -0.2998 0.4528 +vn 0.8269 -0.5170 0.2211 +vn -0.7612 0.6485 0.0075 +vn -0.7870 0.5946 0.1646 +vn -0.7454 0.6017 0.2870 +vn -0.7475 0.6643 0.0044 +vn -0.9835 -0.1801 0.0150 +vn -0.9738 -0.2273 0.0008 +vn -0.9817 -0.1899 0.0121 +vn -0.9722 -0.2341 -0.0012 +vn -0.2367 -0.9710 -0.0334 +vn -0.1725 -0.9849 -0.0166 +vn 0.0286 -0.9990 0.0355 +vn 0.0843 -0.9952 0.0497 +vn 0.9526 -0.3035 0.0203 +vn 0.8013 -0.5972 -0.0350 +vn 0.8330 -0.5527 -0.0260 +vn 0.9657 -0.2580 0.0282 +vn 0.8856 0.4638 -0.0251 +vn 0.8047 0.5937 0.0070 +vn 0.8957 0.4436 -0.0298 +vn 0.7910 0.6117 0.0117 +vn -0.0716 0.9972 0.0217 +vn 0.0443 0.9982 0.0395 +vn -0.0580 0.9980 0.0238 +vn 0.0579 0.9975 0.0416 +vn -0.6445 -0.1087 0.7569 +vn -0.6953 -0.2169 0.6852 +vn -0.7271 -0.3027 0.6162 +vn -0.6441 0.5784 0.5006 +vn 0.5400 0.3677 0.7570 +vn -0.1461 -0.6182 0.7723 +vn -0.0775 -0.7130 0.6969 +vn 0.0070 -0.8086 0.5883 +vn 0.0645 -0.8609 0.5047 +vn 0.5029 -0.3744 0.7790 +vn 0.6145 -0.3375 0.7131 +vn 0.6962 -0.3032 0.6506 +vn 0.7757 -0.2620 0.5741 +vn -0.7490 -0.3830 0.5407 +vn -0.1002 -0.9935 -0.0539 +vn 0.8335 -0.5523 -0.0165 +vn 0.6310 -0.7745 0.0446 +vn 0.5731 -0.8174 0.0587 +vn 0.8797 -0.4743 -0.0349 +vn 0.8777 0.4792 0.0071 +vn 0.8864 0.4629 0.0018 +vn 0.8756 0.4829 0.0083 +vn 0.8876 0.4605 0.0011 +vn -0.8254 0.5641 0.0232 +vn -0.7547 0.6561 0.0060 +vn -0.7669 0.6417 0.0088 +vn -0.8428 0.5375 0.0278 +vn -0.9766 -0.2113 -0.0407 +vn -0.7180 -0.6935 0.0589 +vn 0.2268 0.9733 0.0367 +vn 0.2333 0.9716 0.0397 +vn -0.6448 -0.1276 0.7536 +vn -0.7009 -0.2290 0.6756 +vn -0.7471 -0.3363 0.5734 +vn 0.2341 0.9715 0.0359 +vn -0.5919 0.6166 0.5190 +vn 0.6446 -0.0049 0.7645 +vn 0.6333 0.1510 0.7590 +vn 0.5026 0.2675 0.8221 +vn 0.6316 -0.1693 0.7566 +vn -0.0538 -0.6240 0.7795 +vn 0.2370 -0.8882 0.3937 +vn 0.5134 -0.2735 0.8134 +vn -0.7683 -0.4048 0.4959 +vn -0.6866 0.7265 0.0294 +vn -0.6778 0.7348 0.0269 +vn -0.6795 0.7331 0.0274 +vn -0.6888 0.7243 0.0300 +vn -0.9707 -0.2398 -0.0165 +vn -0.8808 -0.4725 0.0293 +vn -0.9832 -0.1806 -0.0275 +vn -0.8503 -0.5247 0.0402 +vn -0.2367 -0.9707 -0.0424 +vn -0.1667 -0.9856 -0.0289 +vn 0.1207 -0.9923 0.0260 +vn 0.1918 -0.9806 0.0396 +vn 0.8605 0.5093 -0.0128 +vn 0.6532 0.7549 0.0586 +vn 0.8964 0.4423 -0.0297 +vn 0.6073 0.7913 0.0711 +vn -0.1845 0.9827 0.0140 +vn -0.2002 0.9784 -0.0507 +vn -0.2186 0.9671 -0.1305 +vn -0.6955 -0.1187 0.7086 +vn -0.7262 -0.1538 0.6701 +vn -0.7473 -0.1796 0.6397 +vn -0.2398 0.9429 -0.2313 +vn -0.4641 0.4992 0.7317 +vn 0.5435 0.3653 0.7558 +vn -0.1384 -0.7617 0.6330 +vn -0.1244 -0.7469 0.6532 +vn -0.1630 -0.7864 0.5958 +vn -0.1958 -0.8167 0.5428 +vn 0.5165 -0.3846 0.7650 +vn 0.6215 -0.3683 0.6915 +vn 0.7179 -0.3454 0.6045 +vn 0.7772 -0.3260 0.5383 +vn -0.7619 -0.1984 0.6165 +vn 0.7491 0.0141 -0.6623 +vn 0.7906 0.0015 -0.6123 +vn 0.7858 0.0030 -0.6185 +vn 0.7322 0.0190 -0.6808 +vn 0.8615 0.0361 0.5066 +vn 0.9552 -0.0197 0.2952 +vn 0.9685 -0.0317 0.2469 +vn 0.8301 0.0498 0.5554 +vn -0.3536 0.0381 0.9346 +vn -0.1413 -0.0209 0.9897 +vn -0.2998 0.0229 0.9537 +vn -0.0845 -0.0361 0.9958 +vn -0.9638 -0.0422 0.2632 +vn -0.9382 0.0436 -0.3433 +vn -0.8234 -0.0094 -0.5674 +vn -0.9503 0.0514 -0.3071 +vn -0.7958 -0.0193 -0.6052 +vn -0.0497 -0.0361 -0.9981 +vn -0.0577 -0.0349 -0.9977 +vn 0.5429 -0.6748 -0.5000 +vn -0.6583 -0.6865 -0.3088 +vn 0.7048 -0.6250 0.3356 +vn 0.7514 -0.5748 0.3241 +vn 0.6227 -0.6995 0.3508 +vn 0.5473 -0.7555 0.3602 +vn -0.2945 -0.5069 0.8101 +vn -0.3071 -0.4850 0.8188 +vn -0.3207 -0.4605 0.8277 +vn -0.3248 -0.4530 0.8303 +vn 0.8588 -0.0160 -0.5120 +vn 0.9237 0.0239 -0.3824 +vn 0.8705 -0.0097 -0.4921 +vn 0.9339 0.0317 -0.3560 +vn 0.6215 0.0401 0.7824 +vn 0.7837 -0.0063 0.6212 +vn 0.8168 -0.0176 0.5767 +vn 0.5798 0.0503 0.8132 +vn -0.1786 -0.0570 0.9823 +vn -0.9446 -0.0161 0.3278 +vn -0.7311 0.0524 0.6802 +vn -0.7774 0.0412 0.6277 +vn -0.9657 -0.0281 0.2583 +vn -0.8946 0.0232 -0.4462 +vn -0.8088 -0.0120 -0.5879 +vn -0.9053 0.0284 -0.4238 +vn -0.7940 -0.0172 -0.6077 +vn -0.0281 -0.0211 -0.9994 +vn 0.1332 0.0175 -0.9909 +vn 0.1477 0.1384 -0.9793 +vn -0.0465 -0.0175 -0.9988 +vn 0.4938 -0.8512 -0.1779 +vn 0.1761 0.2665 -0.9476 +vn -0.5428 -0.7571 -0.3636 +vn 0.8421 -0.5019 0.1974 +vn 0.3588 -0.8028 0.4762 +vn 0.1229 -0.4029 0.9070 +vn -0.4364 -0.8116 0.3884 +vn -0.5558 -0.7447 0.3695 +vn -0.6882 -0.6428 0.3365 +vn -0.7787 -0.5491 0.3036 +vn 0.7430 0.0479 -0.6676 +vn 0.8166 0.0197 -0.5768 +vn 0.8075 0.0235 -0.5894 +vn 0.7027 0.0616 -0.7089 +vn 0.9908 -0.0414 0.1288 +vn 0.5029 0.0321 0.8638 +vn 0.4804 0.0406 0.8761 +vn 0.4983 0.0338 0.8664 +vn 0.4738 0.0431 0.8796 +vn -0.7470 0.0232 0.6644 +vn -0.6010 -0.0198 0.7990 +vn -0.5588 -0.0308 0.8287 +vn -0.7774 0.0333 0.6281 +vn -0.9086 0.0173 -0.4173 +vn -0.9685 -0.0167 -0.2483 +vn -0.9227 0.0107 -0.3855 +vn -0.9823 -0.0289 -0.1853 +vn 0.1186 -0.0184 -0.9928 +vn 0.1249 0.0404 -0.9913 +vn 0.8733 -0.4832 -0.0624 +vn 0.1499 0.1087 -0.9827 +vn 0.4024 -0.8647 -0.3005 +vn -0.5544 -0.7492 -0.3623 +vn 0.3320 -0.7102 0.6208 +vn 0.3219 -0.7200 0.6149 +vn 0.3488 -0.6936 0.6303 +vn 0.3646 -0.6773 0.6390 +vn -0.6133 -0.6186 0.4910 +vn -0.6623 -0.5651 0.4920 +vn -0.7112 -0.5039 0.4901 +vn -0.7311 -0.4765 0.4884 +vn 0.9992 0.0353 -0.0166 +vn 0.9999 -0.0052 -0.0113 +vn 0.9999 -0.0106 -0.0105 +vn 0.9991 -0.0429 -0.0062 +vn 0.7300 0.1482 -0.6672 +vn 0.5932 0.6972 -0.4024 +vn 0.6857 0.7039 -0.1855 +vn 0.5737 0.6921 -0.4381 +vn 0.4571 0.6469 -0.6104 +vn 0.6538 -0.4095 0.6362 +vn 0.5864 -0.4729 0.6576 +vn 0.7080 -0.3510 0.6128 +vn 0.5057 -0.5381 0.6744 +vn 0.1868 0.1597 0.9693 +vn 0.5837 0.6366 0.5040 +vn -0.0013 0.9765 0.2154 +vn -0.5087 0.7357 0.4472 +vn -0.4165 0.2916 0.8611 +vn 0.3303 -0.6617 0.6731 +vn 0.7472 -0.5565 0.3633 +vn 0.9754 0.2086 -0.0716 +vn 0.0583 0.6918 -0.7198 +vn 0.1923 0.6408 -0.7432 +vn 0.1564 0.6559 -0.7384 +vn 0.0016 0.7088 -0.7054 +vn -0.9077 0.3487 -0.2334 +vn -0.8045 -0.4562 0.3802 +vn -0.9194 -0.3515 0.1766 +vn -0.8970 -0.3791 0.2272 +vn -0.7453 -0.4891 0.4531 +vn 0.0936 0.1181 0.9886 +vn 0.6076 0.6273 0.4871 +vn -0.1647 0.9723 0.1657 +vn -0.5661 0.4115 0.7143 +vn -0.9251 0.2132 -0.3141 +vn -0.9480 -0.1642 0.2727 +vn 0.0748 -0.7201 0.6898 +vn -0.2008 -0.7612 0.6166 +vn -0.1235 -0.7559 0.6429 +vn 0.1630 -0.6939 0.7014 +vn 0.9923 0.1129 -0.0518 +vn 0.9848 -0.1579 0.0725 +vn 0.9966 -0.0753 0.0346 +vn 0.9774 0.1921 -0.0882 +vn -0.1776 0.7497 -0.6375 +vn 0.1908 0.6831 -0.7049 +vn 0.0864 0.7129 -0.6960 +vn -0.2675 0.7494 -0.6056 +vn 0.5488 0.2943 0.7825 +vn 0.2816 0.9319 0.2287 +vn -0.4718 0.8068 0.3557 +vn -0.4060 0.1925 0.8934 +vn 0.8359 -0.3898 0.3865 +vn 0.7490 -0.5096 0.4235 +vn 0.7804 -0.4703 0.4121 +vn 0.8611 -0.3468 0.3717 +vn 0.5241 0.6448 -0.5564 +vn 0.7100 0.4914 -0.5045 +vn 0.6642 0.5356 -0.5215 +vn 0.4739 0.6763 -0.5639 +vn -0.7534 0.5032 -0.4234 +vn -0.5055 0.5952 -0.6247 +vn -0.5747 0.5778 -0.5795 +vn -0.8038 0.4705 -0.3639 +vn -0.7038 -0.5074 0.4973 +vn -0.8388 -0.4382 0.3231 +vn -0.7994 -0.4635 0.3822 +vn -0.6472 -0.5253 0.5524 +vn 0.2822 0.1642 0.9452 +vn 0.5594 0.6794 0.4749 +vn -0.1650 0.9723 0.1656 +vn -0.5822 0.3403 0.7384 +vn -0.9400 -0.2019 0.2750 +vn -0.9995 -0.0316 -0.0101 +vn -0.9938 -0.0828 0.0748 +vn -0.9126 -0.2364 0.3336 +vn -0.3267 -0.7284 0.6023 +vn 0.4656 -0.6143 0.6370 +vn 0.6706 -0.5528 0.4947 +vn 0.5191 -0.6029 0.6058 +vn 0.7186 -0.5298 0.4505 +vn 0.9525 0.2566 -0.1638 +vn 0.7968 0.4123 -0.4416 +vn 0.9209 0.3038 -0.2442 +vn 0.7402 0.4443 -0.5047 +vn -0.2677 0.7465 -0.6092 +vn -0.4242 0.6711 -0.6080 +vn -0.3039 0.7314 -0.6106 +vn -0.4703 0.6435 -0.6039 +vn 0.2158 0.0909 0.9722 +vn 0.5538 0.7095 0.4358 +vn -0.1384 0.9691 0.2040 +vn -0.6119 0.4628 0.6414 +vn -0.9846 -0.0960 0.1463 +vn -0.9699 -0.1676 0.1769 +vn -0.9813 -0.1147 0.1544 +vn -0.9639 -0.1901 0.1864 +vn 0.2631 -0.6660 0.6980 +vn -0.0313 -0.7544 0.6557 +vn 0.0586 -0.7351 0.6754 +vn 0.3318 -0.6345 0.6981 +vn 0.9708 -0.2131 0.1104 +vn 0.9272 0.3159 -0.2015 +vn 0.4634 0.6128 -0.6401 +vn -0.2365 0.7442 -0.6247 +vn -0.5104 0.6198 -0.5962 +vn -0.2952 0.7240 -0.6235 +vn -0.5719 0.5796 -0.5805 +vn 0.2784 0.1895 0.9416 +vn 0.5667 0.7506 0.3399 +vn -0.4823 0.8367 0.2593 +vn -0.3828 0.2432 0.8912 +vn 0.4872 -0.5777 0.6549 +vn 0.9886 -0.1475 0.0313 +vn 0.8645 0.4214 -0.2741 +vn 0.4112 0.6333 -0.6556 +vn -0.7321 0.5188 -0.4414 +vn -0.7220 0.5224 -0.4536 +vn -0.7255 0.5212 -0.4495 +vn -0.7351 0.5177 -0.4377 +vn -0.6696 -0.5529 0.4959 +vn -0.5230 -0.6744 0.5213 +vn -0.6203 -0.5985 0.5070 +vn -0.4831 -0.7010 0.5247 +vn 0.2665 0.1247 0.9557 +vn 0.5265 0.7636 0.3737 +vn -0.2559 0.9414 0.2196 +vn -0.5573 0.3634 0.7466 +vn 0.4305 -0.5994 0.6748 +vn 0.8285 -0.4676 0.3081 +vn 0.8669 0.4078 -0.2867 +vn 0.6719 0.5336 -0.5136 +vn 0.8294 0.4412 -0.3427 +vn 0.6028 0.5595 -0.5688 +vn -0.4310 0.6787 -0.5946 +vn -0.5113 0.6282 -0.5864 +vn -0.4519 0.6664 -0.5930 +vn -0.5331 0.6130 -0.5832 +vn -0.9163 -0.2856 0.2806 +vn -0.8438 -0.4231 0.3303 +vn -0.8934 -0.3352 0.2990 +vn -0.8172 -0.4627 0.3436 +vn 0.3379 0.2294 0.9128 +vn 0.5562 0.6388 0.5316 +vn -0.0190 0.9834 0.1805 +vn -0.5480 0.6473 0.5298 +vn -0.3590 0.2419 0.9014 +vn 0.0823 -0.7686 0.6345 +vn 0.5898 -0.5579 0.5839 +vn 0.9924 0.1039 -0.0661 +vn 0.9850 -0.1529 0.0802 +vn 0.9943 -0.0953 0.0474 +vn 0.9805 0.1677 -0.1023 +vn 0.0118 0.7245 -0.6891 +vn 0.1251 0.6875 -0.7153 +vn 0.0907 0.6999 -0.7085 +vn -0.0290 0.7352 -0.6772 +vn -0.9784 0.1682 -0.1201 +vn -0.9946 -0.1021 0.0184 +vn -0.9928 0.0895 -0.0801 +vn -0.9863 -0.1581 0.0475 +vn -0.6273 -0.5338 0.5671 +vn 0.1768 0.1775 0.9681 +vn 0.5482 0.4869 0.6800 +vn 0.2825 0.9215 0.2665 +vn -0.3617 0.8851 0.2929 +vn -0.5068 0.3177 0.8014 +vn 0.3113 -0.6634 0.6804 +vn 0.9815 -0.1622 0.1012 +vn 0.9681 -0.1925 0.1606 +vn 0.9783 -0.1705 0.1174 +vn 0.9645 -0.1990 0.1734 +vn 0.5010 0.6386 -0.5841 +vn 0.4407 0.6485 -0.6207 +vn 0.4866 0.6413 -0.5933 +vn 0.4266 0.6503 -0.6286 +vn -0.6332 0.5812 -0.5112 +vn -0.7999 0.4038 -0.4439 +vn -0.6871 0.5323 -0.4946 +vn -0.8330 0.3564 -0.4231 +vn -0.8483 -0.3274 0.4162 +vn -0.3325 -0.7516 0.5697 +vn 0.0001 0.9782 0.2079 +vn 0.0000 0.9781 0.2079 +vn 0.0000 0.9781 -0.2079 +vn 0.0000 0.9781 -0.2080 +vn -0.0007 -0.8258 0.5639 +vn -0.0022 -0.9116 0.4112 +vn -0.0181 -0.7804 0.6250 +vn 0.0058 -0.9231 0.3844 +vn -0.0146 -0.9600 0.2796 +vn 0.0000 -0.9792 0.2030 +vn 0.0062 -0.6861 0.7275 +vn -0.9895 -0.0852 0.1171 +vn -0.9995 0.0150 0.0263 +vn -0.9398 -0.2332 0.2497 +vn 0.0119 0.2395 0.9708 +vn 0.0236 0.2214 0.9749 +vn -0.0032 0.2627 0.9649 +vn 0.0358 0.2024 0.9786 +vn -0.0147 -0.3158 0.9487 +vn -0.0271 -0.3294 0.9438 +vn -0.0244 -0.3264 0.9449 +vn -0.0374 -0.3406 0.9395 +vn -0.7826 -0.4797 0.3969 +vn -0.9085 -0.2904 0.3005 +vn -0.2428 -0.4356 0.8668 +vn -0.0024 -0.1669 0.9860 +vn -0.0029 -0.1603 0.9871 +vn -0.0126 -0.0189 0.9997 +vn -0.0133 -0.0090 0.9999 +vn 0.9726 0.2273 0.0494 +vn 0.9728 0.2265 0.0491 +vn 0.9794 0.1978 0.0410 +vn 0.9799 0.1956 0.0404 +vn -0.9981 -0.0446 0.0428 +vn -0.9989 -0.0206 0.0417 +vn -0.9946 0.0976 0.0351 +vn -0.9984 0.0537 0.0174 +vn -0.9988 0.0475 0.0153 +vn 0.0199 0.5498 -0.8351 +vn 0.0193 0.5406 -0.8411 +vn -0.0038 0.1684 -0.9857 +vn -0.0047 0.1534 -0.9882 +vn 0.8174 -0.4256 0.3882 +vn -0.8581 -0.0660 -0.5092 +vn -0.8447 0.0084 -0.5352 +vn -0.8269 0.0790 -0.5568 +vn -0.7864 0.1964 -0.5857 +vn 0.6468 -0.1939 -0.7376 +vn 0.1357 -0.7784 0.6129 +vn 0.0007 -0.8577 0.5142 +vn -0.0000 -0.9516 0.3074 +vn -0.0002 -0.9517 0.3071 +vn -0.0074 0.1628 0.9866 +vn 0.0007 0.1213 0.9926 +vn 0.9997 -0.0118 0.0210 +vn -0.9997 -0.0081 0.0221 +vn 0.0019 0.2441 0.9698 +vn 0.0012 0.2448 0.9696 +vn 0.5761 -0.2837 0.7665 +vn 0.5854 -0.2803 0.7608 +vn 0.6501 -0.3148 0.6915 +vn -0.6399 -0.3209 0.6982 +vn -0.6160 -0.2447 0.7487 +vn -0.6392 -0.2415 0.7302 +vn -0.6568 -0.3069 0.6888 +vn 0.6310 0.1461 0.7619 +vn 0.6809 -0.6925 0.2384 +vn 0.6792 -0.6941 0.2386 +vn 0.6556 -0.7156 0.2412 +vn 0.6524 -0.7184 0.2415 +vn -0.6450 0.1428 0.7508 +vn -0.6623 -0.7099 0.2397 +vn -0.6598 -0.7118 0.2407 +vn -0.6358 -0.7302 0.2500 +vn -0.6342 -0.7314 0.2506 +vn -0.4317 -0.4869 0.7594 +vn -0.7826 -0.0236 -0.6221 +vn -0.6753 0.0199 -0.7373 +vn -0.7583 -0.0130 -0.6517 +vn -0.6439 0.0314 -0.7645 +vn -0.6039 0.0377 0.7962 +vn -0.5780 0.0280 0.8156 +vn -0.5976 0.0353 0.8010 +vn -0.5715 0.0256 0.8202 +vn 0.7745 -0.0452 0.6310 +vn 0.9826 0.1199 -0.1420 +vn 0.7179 -0.0413 -0.6949 +vn 0.8853 -0.0152 -0.4648 +vn 0.9034 -0.0228 -0.4281 +vn 0.9014 -0.0219 -0.4324 +vn 0.8819 -0.0138 -0.4712 +vn -0.8332 0.0001 -0.5529 +vn -0.7369 0.0301 -0.6753 +vn -0.7196 0.0349 -0.6935 +vn -0.8468 -0.0048 -0.5320 +vn -0.2100 -0.0177 0.9775 +vn 0.0132 0.0262 0.9996 +vn -0.0162 0.0205 0.9997 +vn 0.0005 -0.8535 -0.5211 +vn 0.0020 -0.8602 -0.5099 +vn 0.0006 -0.8540 -0.5202 +vn 0.0021 -0.8607 -0.5091 +vn -0.0065 -0.9484 0.3169 +vn 0.0001 -0.9396 0.3422 +vn -0.0035 -0.9382 0.3460 +vn -0.0050 -0.9383 0.3458 +vn 0.0003 -0.9379 0.3470 +vn 0.0047 -0.9377 0.3475 +vn 0.0005 -0.9387 0.3446 +vn 0.0006 -0.9396 0.3422 +vn -0.0002 -0.9424 0.3345 +vn 0.0044 -0.9412 0.3377 +vn -0.0060 -0.9422 0.3351 +vn -0.0070 -0.9416 0.3366 +vn -0.0005 -0.9365 0.3507 +vn 0.0082 -0.9391 0.3436 +vn 0.0022 -0.9414 0.3373 +vn 0.0000 -0.9397 0.3421 +vn -0.0089 -0.8080 0.5891 +vn 0.0018 -0.2974 0.9548 +vn -0.0003 -0.3158 0.9488 +vn 0.0017 -0.2987 0.9543 +vn -0.0004 -0.3169 0.9484 +vn -1.0000 -0.0006 0.0003 +vn -1.0000 -0.0005 0.0001 +vn 0.3380 -0.9299 -0.1454 +vn 0.5521 -0.7498 0.3648 +vn 0.0478 -0.5512 0.8330 +vn -0.5511 -0.7296 0.4049 +vn -0.3587 -0.9244 -0.1294 +vn 0.5899 -0.3159 -0.7431 +vn 0.8597 -0.1150 -0.4976 +vn 0.6837 -0.2602 -0.6818 +vn 0.9001 -0.0670 -0.4305 +vn 0.9862 0.0122 0.1651 +vn 0.1287 0.3258 0.9366 +vn 0.2969 0.3647 0.8826 +vn 0.2499 0.3548 0.9009 +vn 0.0777 0.3121 0.9469 +vn -0.9609 0.0840 0.2637 +vn -0.9039 0.1776 0.3891 +vn -0.9194 0.1563 0.3609 +vn -0.9709 0.0607 0.2318 +vn -0.6277 -0.2540 -0.7358 +vn -0.5899 -0.2489 -0.7681 +vn -0.6170 -0.2526 -0.7453 +vn -0.5808 -0.2477 -0.7754 +vn 0.5100 -0.8520 -0.1185 +vn 0.3228 -0.5956 0.7356 +vn -0.3616 -0.6156 0.7002 +vn -0.5045 -0.8580 -0.0969 +vn 0.7783 -0.3124 -0.5447 +vn 0.9935 0.0662 -0.0922 +vn 0.5588 0.2271 0.7976 +vn 0.1892 0.3594 0.9138 +vn 0.4801 0.2619 0.8372 +vn 0.0916 0.3831 0.9191 +vn -0.6326 0.2170 0.7434 +vn -0.8907 0.1905 0.4128 +vn -0.7036 0.2143 0.6775 +vn -0.9286 0.1794 0.3247 +vn -0.7895 -0.2758 -0.5483 +vn -0.3897 -0.2273 -0.8925 +vn 0.2557 -0.9386 -0.2317 +vn 0.5602 -0.6456 0.5190 +vn -0.3268 -0.5562 0.7641 +vn -0.5069 -0.8617 -0.0209 +vn 0.4304 -0.3638 -0.8261 +vn 0.9804 -0.0182 -0.1960 +vn 0.9001 0.0922 0.4257 +vn 0.4953 0.3376 0.8004 +vn -0.5235 0.2480 0.8151 +vn -0.7689 0.2531 0.5872 +vn -0.5909 0.2519 0.7664 +vn -0.8152 0.2501 0.5225 +vn -0.8493 -0.2403 -0.4701 +vn -0.3000 -0.2463 -0.9216 +vn -0.2422 -0.0242 0.9699 +vn 0.0016 -1.0000 0.0054 +vn 0.0031 -1.0000 0.0028 +vn 0.0002 -1.0000 0.0079 +vn 0.0000 -1.0000 -0.0000 +vn 0.0045 -1.0000 0.0004 +vn -0.7046 -0.0408 -0.7084 +vn 0.9784 -0.0556 -0.1989 +vn 0.1990 -0.0615 -0.9781 +vn 0.0831 -0.1758 -0.9809 +vn 0.2313 0.0647 -0.9707 +vn 0.0817 0.2094 -0.9744 +vn 0.2741 -0.1562 -0.9489 +vn 0.2093 0.2171 -0.9534 +vn 0.2479 0.3653 -0.8973 +vn 0.0845 0.5567 -0.8264 +vn 0.2287 0.5940 -0.7713 +vn 0.0881 0.7762 -0.6243 +vn 0.2276 0.7974 -0.5589 +vn 0.0854 0.8980 -0.4315 +vn 0.2878 0.8929 -0.3463 +vn 0.3133 -0.2882 -0.9049 +vn 0.1632 -0.5069 -0.8464 +vn 0.1073 -0.5474 -0.8300 +vn 0.0689 -0.6620 -0.7464 +vn 0.2848 -0.4326 -0.8554 +vn 0.9722 -0.0529 0.2281 +vn 0.9390 -0.1954 0.2829 +vn 0.9923 -0.1099 0.0576 +vn 0.9804 -0.0653 -0.1858 +vn 0.9720 0.0296 -0.2330 +vn 0.9973 -0.0128 -0.0725 +vn 0.9979 0.0427 -0.0489 +vn 0.9989 -0.0463 0.0055 +vn 0.9996 0.0265 0.0096 +vn 0.9972 -0.0072 0.0749 +vn 0.9474 -0.2548 0.1936 +vn 0.9623 -0.2685 0.0432 +vn 0.9899 -0.1404 -0.0200 +vn 0.9503 -0.3111 -0.0135 +vn 0.9047 -0.4036 -0.1364 +vn 0.9412 -0.2012 -0.2714 +vn 0.8886 -0.3764 -0.2622 +vn 0.9949 -0.0831 -0.0578 +vn 0.9714 0.0253 0.2360 +vn 0.9030 0.2276 0.3644 +vn 0.9655 0.1004 0.2402 +vn 0.9328 0.3436 0.1089 +vn 0.9659 0.2590 0.0007 +vn 0.9932 0.0934 0.0692 +vn 0.9934 0.1128 -0.0198 +vn 0.9313 0.3500 -0.1007 +vn 0.9887 0.1137 -0.0980 +vn 0.9665 0.0906 -0.2402 +vn 0.9064 0.2299 -0.3543 +vn 0.1931 0.9555 -0.2232 +vn 0.1596 0.9781 -0.1335 +vn 0.3120 0.9484 -0.0561 +vn 0.5259 0.8435 -0.1090 +vn 0.5272 0.7972 -0.2941 +vn 0.7418 0.6526 -0.1543 +vn 0.7697 0.5882 0.2480 +vn 0.5732 0.8102 0.1225 +vn 0.5397 0.7877 0.2971 +vn 0.3413 0.8910 0.2994 +vn 0.2352 0.9287 0.2867 +vn 0.4491 0.8885 0.0947 +vn 0.1240 0.9886 0.0849 +vn 0.1681 0.9763 0.1362 +vn 0.2199 0.9755 0.0031 +vn 0.1111 0.9919 -0.0609 +vn 0.2432 0.9297 -0.2765 +vn 0.7261 0.6845 -0.0654 +vn 0.7541 0.6509 0.0877 +vn 0.4242 0.9037 -0.0581 +vn 0.1980 0.9586 0.2045 +vn 0.4063 0.9130 0.0360 +vn 0.5750 0.8166 0.0491 +vn 0.5565 0.8307 -0.0175 +vn 0.3082 0.9511 0.0199 +vn 0.7026 0.7115 0.0070 +vn 0.2266 0.0649 0.9718 +vn 0.0817 0.2024 0.9759 +vn 0.2189 -0.0520 0.9744 +vn 0.0839 -0.1760 0.9808 +vn 0.1776 -0.2221 0.9587 +vn 0.0832 0.8344 0.5449 +vn 0.2084 0.8023 0.5594 +vn 0.0801 0.5611 0.8239 +vn 0.2374 0.6005 0.7636 +vn 0.2385 0.3552 0.9039 +vn 0.2960 0.1617 0.9414 +vn 0.3205 -0.2853 0.9033 +vn 0.2172 -0.3941 0.8930 +vn 0.0877 -0.5665 0.8194 +vn 0.1037 -0.5595 0.8223 +vn 0.1335 -0.5188 0.8444 +vn 0.1107 -0.8158 -0.5676 +vn 0.1967 -0.6955 -0.6911 +vn 0.1600 -0.8828 -0.4416 +vn 0.3380 -0.8441 -0.4162 +vn 0.2870 -0.7038 -0.6498 +vn 0.4899 -0.7697 -0.4093 +vn 0.5640 -0.6625 -0.4930 +vn 0.5371 -0.5308 -0.6556 +vn 0.2726 -0.9235 -0.2698 +vn 0.0991 -0.8253 0.5559 +vn 0.0933 -0.8434 0.5292 +vn 0.0838 -0.9648 0.2495 +vn 0.1592 -0.8830 0.4416 +vn 0.2301 -0.9599 0.1601 +vn 0.2249 -0.9741 0.0244 +vn 0.0782 -0.9958 -0.0484 +vn 0.2243 -0.9703 -0.0911 +vn 0.0751 -0.9445 -0.3199 +vn 0.0794 0.9671 -0.2416 +vn 0.0768 0.9970 -0.0005 +vn 0.0776 0.9619 0.2622 +vn 0.5390 -0.6878 0.4862 +vn 0.4176 -0.5179 0.7466 +vn 0.2526 -0.6103 0.7508 +vn 0.2396 -0.9021 0.3590 +vn 0.3579 -0.8655 0.3505 +vn 0.1721 -0.7542 0.6337 +vn 0.2411 -0.7048 0.6672 +vn 0.5440 -0.7948 0.2690 +vn 0.4095 -0.9092 0.0757 +vn 0.5749 -0.8182 0.0061 +vn 0.4027 -0.9038 -0.1450 +vn 0.6521 -0.7322 -0.1966 +vn 0.7436 0.2032 -0.6370 +vn 0.8424 0.0311 -0.5379 +vn 0.6736 -0.1645 -0.7205 +vn 0.4469 -0.1161 -0.8870 +vn 0.5663 0.1370 -0.8127 +vn 0.4340 0.1053 -0.8947 +vn 0.7297 0.0957 0.6770 +vn 0.5465 0.1237 0.8283 +vn 0.4470 -0.1191 0.8866 +vn 0.6782 -0.1724 0.7144 +vn 0.8612 0.0320 0.5072 +vn 0.8683 -0.0071 0.4959 +vn 0.3912 -0.0751 0.9172 +vn 0.4998 0.6732 0.5450 +vn 0.5242 0.3726 0.7658 +vn 0.7587 0.3787 0.5301 +vn 0.5000 0.6768 -0.5403 +vn 0.5323 0.4197 -0.7352 +vn 0.9062 -0.1227 0.4047 +vn 0.8696 0.4925 0.0360 +vn 0.7882 0.5220 -0.3259 +vn 0.9175 0.3942 -0.0524 +vn 0.6803 -0.2959 0.6706 +vn 0.6251 -0.4958 0.6028 +vn 0.8147 -0.4048 0.4152 +vn 0.9087 -0.0107 -0.4173 +vn 0.9045 -0.1219 -0.4087 +vn 0.7495 -0.6330 0.1940 +vn 0.8902 -0.4329 0.1417 +vn 0.6802 -0.2979 -0.6697 +vn 0.7973 -0.3994 -0.4527 +vn 0.8102 -0.5862 -0.0032 +vn -1.0000 -0.0001 0.0001 +vn -1.0000 -0.0002 0.0003 +vn -1.0000 -0.0001 0.0000 +vn -1.0000 -0.0001 -0.0002 +vn -1.0000 0.0001 0.0000 +vn -1.0000 0.0009 0.0003 +vn -1.0000 0.0004 -0.0001 +vn -1.0000 -0.0065 0.0035 +vn 1.0000 0.0001 -0.0004 +vn 1.0000 0.0003 -0.0006 +vn 0.9979 0.0107 0.0639 +vn 1.0000 -0.0001 0.0001 +vn 1.0000 -0.0069 -0.0001 +vn 1.0000 -0.0003 -0.0003 +vn 1.0000 -0.0003 0.0002 +vn 0.9999 0.0155 -0.0011 +vn 1.0000 0.0000 0.0001 +vn 1.0000 -0.0018 -0.0005 +vn 0.9991 0.0274 0.0311 +vn 1.0000 -0.0001 -0.0005 +vn 1.0000 -0.0037 -0.0018 +vn 0.9999 -0.0140 -0.0086 +vn 0.9998 -0.0178 0.0117 +vn 0.9988 0.0326 -0.0378 +vn 1.0000 -0.0008 0.0002 +vn 1.0000 -0.0012 -0.0090 +vn 1.0000 0.0017 -0.0020 +vn 1.0000 -0.0001 -0.0002 +vn 1.0000 -0.0004 0.0003 +vn 1.0000 0.0006 0.0003 +vn 1.0000 -0.0004 0.0004 +vn 1.0000 -0.0001 0.0002 +vn 1.0000 -0.0001 0.0003 +vn 0.9999 0.0011 0.0109 +vn 0.9999 0.0082 0.0058 +vn -1.0000 0.0029 -0.0035 +vn 1.0000 0.0020 0.0001 +vn 1.0000 -0.0000 0.0006 +vn 1.0000 -0.0009 0.0004 +vn 1.0000 0.0008 -0.0004 +vn 1.0000 0.0021 -0.0021 +vn 1.0000 0.0011 0.0025 +vn 1.0000 -0.0018 -0.0010 +vn -1.0000 0.0012 -0.0000 +vn -1.0000 -0.0050 -0.0049 +vn -0.9999 -0.0051 -0.0100 +vn -1.0000 -0.0041 -0.0037 +vn -1.0000 0.0019 0.0008 +vn -1.0000 0.0017 0.0043 +vn -1.0000 -0.0003 0.0002 +vn -1.0000 0.0005 -0.0044 +vn -1.0000 0.0014 -0.0006 +vn -1.0000 -0.0004 -0.0002 +vn -1.0000 -0.0002 -0.0002 +vn -1.0000 -0.0021 -0.0012 +vn -1.0000 0.0021 0.0013 +vn -1.0000 -0.0003 0.0001 +vn -1.0000 -0.0020 0.0006 +vn -1.0000 0.0002 0.0002 +vn -0.9999 0.0096 0.0037 +vn -0.9999 0.0019 -0.0100 +vn -0.9997 -0.0003 0.0264 +vn -0.9999 -0.0062 0.0112 +vn -0.9998 -0.0091 0.0190 +vn -1.0000 -0.0004 -0.0035 +vn -0.9999 -0.0014 -0.0122 +vn -1.0000 -0.0025 0.0021 +vn -0.9999 0.0143 -0.0076 +vn -1.0000 0.0046 0.0061 +vn -0.9999 0.0109 -0.0033 +vn -1.0000 0.0009 -0.0010 +vn -1.0000 -0.0010 0.0008 +vn 0.9999 -0.0138 -0.0006 +vn 1.0000 0.0047 0.0049 +vn 0.9999 0.0169 -0.0020 +vn 0.0001 -0.2588 0.9659 +vn 0.0000 -0.2588 0.9659 +vn 0.0002 -0.2588 0.9659 +vn 0.0001 -0.2589 0.9659 +vn 0.0001 -0.2587 0.9660 +vn 0.0293 -0.0756 0.9967 +vn -0.0001 -0.2588 0.9659 +vn 0.0411 0.0002 0.9992 +vn -0.0011 -0.2359 0.9718 +vn -0.0007 -0.1226 0.9925 +vn -0.0000 -0.2587 0.9659 +vn -0.0001 -0.2586 0.9660 +vn 0.0123 -0.1741 0.9847 +vn -0.1084 -0.3262 0.9391 +vn 0.0150 -0.1099 0.9938 +vn -0.2444 -0.3012 0.9217 +vn -0.0208 -0.2555 0.9666 +vn -0.0003 -0.2588 0.9659 +vn -0.0002 -0.2587 0.9660 +vn 0.0002 0.2584 -0.9660 +vn 0.0002 0.2587 -0.9660 +vn 0.0004 0.2584 -0.9660 +vn 0.0004 0.2587 -0.9660 +vn 0.0001 0.2586 -0.9660 +vn 0.0004 0.2585 -0.9660 +vn -0.0000 0.2586 -0.9660 +vn 0.0001 0.2587 -0.9660 +vn -0.0002 0.2590 -0.9659 +vn -0.0008 0.2574 -0.9663 +vn 0.0001 0.2591 -0.9658 +vn 0.0000 0.2589 -0.9659 +vn 0.0020 0.2589 -0.9659 +vn 0.0010 0.2590 -0.9659 +vn 0.0001 0.2589 -0.9659 +vn 0.0066 0.3098 -0.9508 +vn 0.0000 0.2584 -0.9660 +vn -0.0001 0.2589 -0.9659 +vn -0.1980 0.1331 -0.9711 +vn 0.0003 0.4581 -0.8889 +vn -0.0366 0.2125 -0.9765 +vn 0.0030 0.5557 -0.8314 +vn -0.0205 0.2850 -0.9583 +vn -0.0900 0.2859 -0.9540 +vn 0.0002 0.2585 -0.9660 +vn 0.0002 0.2586 -0.9660 +vn 0.2422 0.2591 0.9350 +vn 0.6231 0.3624 0.6931 +vn 0.2781 0.2900 0.9157 +vn 0.6626 0.3834 0.6435 +vn 0.1625 0.9200 -0.3566 +vn -0.0448 0.7084 0.7044 +vn -0.6144 0.7549 -0.2293 +vn -0.7161 0.3579 0.5992 +vn -0.7608 0.0766 -0.6445 +vn -0.4365 -0.7275 0.5293 +vn -0.0958 -0.6307 -0.7701 +vn 0.2711 -0.9073 0.3215 +vn 0.6077 -0.4567 -0.6497 +vn 0.7610 -0.4520 0.4654 +vn 0.8314 -0.4071 0.3783 +vn 0.7464 -0.4598 0.4812 +vn 0.8476 -0.3945 0.3549 +vn -0.0591 -0.6933 0.7182 +vn 0.5569 -0.7709 -0.3090 +vn -0.7211 -0.3788 0.5801 +vn -0.9958 -0.0040 -0.0912 +vn 0.0672 0.1746 0.9823 +vn -0.5807 0.7800 0.2330 +vn -0.8611 0.4173 0.2906 +vn -0.6542 0.6562 -0.3760 +vn -0.2923 0.7173 0.6325 +vn 0.2732 0.4334 0.8588 +vn 0.5711 0.5387 -0.6194 +vn 0.7842 -0.0222 0.6202 +vn 0.7831 -0.2411 -0.5733 +vn 0.9084 -0.3322 -0.2540 +vn 0.8287 -0.2700 -0.4902 +vn 0.9141 -0.3385 -0.2231 +vn 0.3340 -0.9167 -0.2193 +vn 0.3030 -0.9514 -0.0542 +vn 0.3375 -0.9099 -0.2414 +vn 0.3000 -0.9531 -0.0399 +vn -0.3505 -0.8122 -0.4663 +vn -0.4149 -0.8976 -0.1487 +vn -0.3422 -0.7991 -0.4943 +vn -0.4180 -0.9001 -0.1232 +vn 0.7941 -0.4878 -0.3625 +vn -0.0517 -0.8765 0.4785 +vn -0.8582 -0.5125 0.0284 +vn -0.5762 0.1738 -0.7986 +vn 0.0845 0.2948 0.9518 +vn -0.3724 0.6616 -0.6509 +vn 0.8404 -0.3778 -0.3885 +vn 0.7007 0.4122 0.5823 +vn 0.1131 0.9875 -0.1095 +vn -0.7112 0.2320 0.6636 +vn -0.7821 -0.3133 -0.5387 +vn 0.1046 -0.9026 0.4176 +vn 0.9799 0.1989 0.0138 +vn 0.7681 0.5556 -0.3185 +vn -0.2115 0.6817 0.7004 +vn -0.9010 0.3609 -0.2406 +vn -0.9693 -0.2155 0.1182 +vn 0.0170 -0.9610 -0.2759 +vn 0.0346 -0.9674 -0.2510 +vn 0.0267 -0.9646 -0.2622 +vn 0.0451 -0.9707 -0.2360 +vn 0.2479 -0.3466 -0.9047 +vn 0.0003 -0.2589 -0.9659 +vn 0.0263 -0.2691 -0.9627 +vn -0.1964 -0.9779 0.0722 +vn -0.0098 -0.5739 -0.8189 +vn -0.0918 -0.5346 -0.8401 +vn -0.0828 -0.5338 -0.8415 +vn -0.0885 -0.3624 -0.9278 +vn -0.1223 -0.4088 -0.9044 +vn 0.3578 -0.3791 -0.8534 +vn 0.0002 -0.2592 -0.9658 +vn 0.0289 -0.0748 -0.9968 +vn 0.0400 -0.0031 -0.9992 +vn -0.0006 -0.2589 -0.9659 +vn -0.4826 -0.8247 0.2949 +vn -0.5221 -0.7891 0.3237 +vn -0.4899 -0.8618 -0.1313 +vn 0.0001 -0.2590 -0.9659 +vn 0.0000 -0.2589 -0.9659 +vn 0.0000 -0.2588 -0.9659 +vn -0.0001 -0.2589 -0.9659 +vn -0.0000 -0.2587 -0.9659 +vn -0.0000 -0.2587 -0.9660 +vn 0.0007 0.2584 0.9660 +vn 0.0391 0.2062 0.9777 +vn 0.0006 0.2586 0.9660 +vn 0.0001 0.2587 0.9660 +vn 0.2370 0.1978 0.9512 +vn 0.3089 0.2570 0.9157 +vn 0.0975 0.1515 0.9836 +vn -0.1049 0.3494 0.9311 +vn -0.0038 0.2622 0.9650 +vn 0.0000 0.2590 0.9659 +vn -0.0002 0.2584 0.9660 +vn -0.0000 0.2587 0.9659 +vn -0.0274 -0.0525 0.9982 +vn -0.0313 -0.0497 0.9983 +vn 0.0003 -0.0724 0.9974 +vn -0.3463 0.5356 0.7702 +vn -0.0622 -0.0274 0.9977 +vn -0.0002 0.2589 0.9659 +vn -0.4423 -0.5372 0.7182 +vn -0.4807 -0.7995 0.3603 +vn -0.0002 0.2591 0.9659 +vn 0.0000 0.2588 0.9659 +vn -0.0000 0.2587 0.9660 +vn -0.0000 0.2589 0.9659 +vn 0.0004 0.2587 0.9659 +vn 0.0003 0.2588 0.9659 +vn 0.0001 0.2588 0.9659 +vn 0.3451 0.3120 -0.8852 +vn 0.2922 0.3206 -0.9010 +vn 0.5475 0.2673 -0.7930 +vn 0.3599 0.7971 0.4849 +vn -0.0867 0.6269 -0.7743 +vn -0.3960 0.8618 0.3169 +vn -0.6617 0.3630 -0.6560 +vn -0.6838 0.2761 0.6754 +vn -0.6520 -0.4136 -0.6355 +vn -0.4355 -0.4900 0.7551 +vn -0.2260 -0.9199 -0.3205 +vn 0.2928 -0.4582 0.8392 +vn 0.4469 -0.5724 -0.6875 +vn 0.3870 0.3018 0.8713 +vn 0.0564 -0.7268 -0.6845 +vn -0.7116 -0.3833 -0.5888 +vn -0.9958 -0.0040 0.0912 +vn 0.0667 0.1752 -0.9823 +vn -0.5807 0.7800 -0.2330 +vn -0.8230 0.4219 -0.3805 +vn -0.7023 0.6647 0.2550 +vn -0.1889 0.8451 -0.5001 +vn -0.1884 0.8439 -0.5023 +vn -0.1909 0.8500 -0.4910 +vn -0.1910 0.8504 -0.4902 +vn 0.5284 0.8430 0.1009 +vn 0.5843 0.4537 -0.6728 +vn 0.8196 0.4065 0.4036 +vn 0.7040 -0.2704 -0.6567 +vn 0.7111 -0.1585 0.6849 +vn 0.2685 -0.9486 -0.1674 +vn 0.2545 -0.9409 -0.2233 +vn 0.3184 -0.9444 0.0818 +vn 0.3218 -0.9412 0.1032 +vn -0.8310 -0.3113 0.4610 +vn 0.0629 0.3456 -0.9363 +vn -0.3509 0.5387 0.7659 +vn 0.8408 -0.3162 0.4395 +vn 0.6711 0.2956 -0.6799 +vn 0.1946 0.9805 -0.0266 +vn -0.8328 0.4461 -0.3277 +vn -0.7226 -0.0496 0.6895 +vn -0.0648 -0.9215 -0.3829 +vn 0.7043 -0.7090 -0.0354 +vn 0.4787 0.8626 0.1636 +vn 0.2117 0.8999 -0.3812 +vn -0.9249 0.3767 0.0518 +vn -0.7560 -0.3661 -0.5427 +vn 0.2642 -0.6912 0.6726 +vn -0.0530 0.6712 0.7394 +vn -0.0483 0.6864 0.7256 +vn -0.0473 0.6895 0.7227 +vn -0.0540 0.6680 0.7422 +vn 0.1841 -0.7989 0.5726 +vn 0.1260 -0.6941 0.7088 +vn 0.1362 -0.7135 0.6873 +vn 0.0660 -0.5714 0.8180 +vn 0.1032 0.6236 -0.7749 +vn 0.2064 0.6319 -0.7470 +vn 0.0839 0.6213 -0.7791 +vn -0.0099 0.6065 -0.7950 +vn 0.8026 -0.4650 0.3736 +vn -0.3569 -0.6382 -0.6821 +vn -0.2522 -0.6608 -0.7069 +vn -0.2435 -0.6610 -0.7098 +vn -0.3541 -0.6380 -0.6837 +vn -0.0045 -0.6804 -0.7328 +vn -0.0445 -0.6813 -0.7306 +vn 0.0322 -0.7184 -0.6949 +vn 0.0370 -0.6417 -0.7661 +vn -0.2345 0.5790 -0.7809 +vn -0.1027 0.6727 -0.7327 +vn -0.1450 0.6449 -0.7504 +vn -0.0134 0.7508 -0.6604 +vn -0.0000 0.7312 -0.6822 +vn 0.0765 0.7799 -0.6212 +vn 0.0250 0.7634 -0.6454 +vn 0.0549 0.7990 -0.5988 +vn 0.0000 0.7314 -0.6820 +vn 0.0761 0.8222 -0.5640 +vn 0.0785 0.4082 0.9095 +vn 0.0461 0.7584 0.6502 +vn 0.0770 0.7315 0.6774 +vn -0.0190 0.8144 0.5800 +vn 0.0724 0.6793 0.7303 +vn 0.0633 0.6851 0.7257 +vn 0.0267 0.7798 0.6254 +vn 0.0191 0.7988 0.6013 +vn 0.9279 0.2714 0.2558 +vn 0.1288 -0.5296 0.8384 +vn 0.0428 -0.6709 0.7403 +vn 0.0953 -0.5880 0.8032 +vn -0.1023 -0.7248 0.6813 +vn 0.0660 -0.6437 0.7624 +vn -0.0145 -0.7108 0.7032 +vn 0.0000 -0.7313 0.6821 +vn 0.0779 0.8076 -0.5845 +vn -0.1008 0.7320 -0.6738 +vn -0.0107 -0.8911 -0.4536 +vn -0.0102 -0.8891 -0.4575 +vn 0.0586 -0.8352 -0.5468 +vn 0.0640 -0.4969 -0.8654 +vn 0.0132 -0.2164 -0.9762 +vn 0.0165 -0.1967 -0.9803 +vn 0.0694 -0.6772 0.7325 +vn 0.9979 -0.0641 0.0043 +vn 0.9947 0.0191 -0.1011 +vn 0.9932 0.0284 -0.1127 +vn 0.9972 -0.0736 0.0164 +vn 0.0450 0.7236 0.6887 +vn -0.6877 0.4657 0.5569 +vn 0.9308 0.1654 0.3261 +vn 0.0189 -0.7501 -0.6611 +vn 0.0120 -0.6525 -0.7577 +vn 0.0118 -0.6490 -0.7607 +vn 0.0191 -0.7530 -0.6578 +vn -0.9991 -0.0155 -0.0388 +vn -0.9549 0.1751 -0.2396 +vn -0.9992 -0.0397 -0.0086 +vn -0.9436 0.1903 -0.2709 +vn 0.1050 0.7406 -0.6637 +vn 0.1456 0.7057 -0.6934 +vn 0.0996 0.7450 -0.6596 +vn 0.0587 0.7766 -0.6272 +vn -0.9530 0.1956 -0.2313 +vn 0.7627 0.4200 -0.4919 +vn 0.7401 0.4094 -0.5335 +vn 0.8090 0.4411 -0.3886 +vn 0.6884 0.3847 -0.6150 +vn -0.0751 0.7456 -0.6622 +vn -0.0618 0.7620 -0.6446 +vn -0.0763 0.7440 -0.6638 +vn -0.0603 0.7638 -0.6426 +vn 0.2414 0.6538 0.7171 +vn 0.3643 0.6360 0.6803 +vn 0.1675 0.6755 0.7180 +vn 0.3687 0.6206 0.6921 +vn 0.4967 0.5931 0.6337 +vn 0.0138 0.6827 0.7306 +vn 0.4752 0.6020 0.6417 +vn 0.3265 0.6450 0.6909 +vn 0.5152 0.5852 0.6262 +vn 0.6968 0.4922 0.5218 +vn -0.9136 0.2855 0.2895 +vn -0.8265 0.3849 0.4108 +vn -0.8224 0.3887 0.4154 +vn -0.9173 0.2801 0.2830 +vn -0.1190 -0.3567 0.9266 +vn 0.1916 -0.4389 0.8779 +vn -0.2490 -0.9444 0.2146 +vn 0.3563 -0.8736 0.3316 +vn -0.0245 -0.6759 0.7366 +vn -0.9738 -0.2078 0.0926 +vn -0.9785 -0.1889 0.0832 +vn -0.9767 -0.1933 0.0929 +vn -0.6985 0.5193 0.4923 +vn 0.0451 0.7240 0.6883 +vn 0.9947 0.0192 -0.1012 +vn 0.9979 -0.0642 0.0043 +vn 0.9971 -0.0737 0.0164 +vn 0.9932 0.0285 -0.1128 +vn 0.0120 -0.6542 -0.7562 +vn 0.0187 -0.7502 -0.6609 +vn 0.0190 -0.7530 -0.6577 +vn 0.0118 -0.6507 -0.7592 +vn -0.9979 -0.0636 -0.0134 +vn -0.9985 -0.0487 -0.0239 +vn -0.9947 0.0703 0.0754 +vn 0.0171 0.7300 -0.6832 +vn 0.0168 0.7294 -0.6839 +vn 0.0156 0.7276 -0.6858 +vn 0.0218 -0.7247 0.6887 +vn 0.0232 -0.7227 0.6908 +vn 0.0180 -0.7306 0.6826 +vn 0.0167 -0.7325 0.6806 +vn -0.4096 0.6288 0.6610 +vn 0.0020 0.6739 0.7388 +vn 0.0577 0.6709 0.7393 +vn -0.4162 0.6270 0.6585 +vn 0.7276 -0.4283 -0.5359 +vn -0.9977 0.0395 0.0553 +vn -0.9957 0.0468 0.0800 +vn -0.9938 0.0521 0.0982 +vn -0.9988 0.0340 0.0364 +vn 0.1243 0.6765 0.7259 +vn 0.1243 0.6766 0.7258 +vn 0.1245 0.6767 0.7257 +vn 0.1241 0.6764 0.7260 +vn 0.0152 0.7270 -0.6864 +vn -0.0948 -0.6794 -0.7277 +vn -0.0947 -0.6793 -0.7277 +vn -0.0952 -0.6797 -0.7273 +vn -0.0942 -0.6790 -0.7281 +vn -0.0006 0.7314 -0.6820 +vn 0.9943 -0.0720 -0.0786 +vn 0.9944 -0.0717 -0.0776 +vn 0.9942 -0.0723 -0.0795 +vn 0.9945 -0.0715 -0.0767 +vn -0.0039 0.7482 -0.6634 +vn -0.0000 0.7313 -0.6820 +vn -0.0282 0.7598 -0.6496 +vn 0.0000 -0.7313 0.6820 +vn -0.0105 -0.7143 0.6998 +vn -0.0234 -0.6842 0.7289 +vn -0.1174 0.6745 -0.7289 +vn -0.1445 0.6399 -0.7547 +vn -0.5353 -0.3420 -0.7724 +vn -0.6079 -0.4988 -0.6178 +vn -0.5191 -0.3116 -0.7959 +vn -0.6212 -0.5346 -0.5730 +vn 0.5030 -0.8282 -0.2471 +vn 0.7823 0.2593 -0.5664 +vn -0.0197 -0.6493 0.7603 +vn -0.0144 -0.6431 0.7656 +vn 0.7394 -0.1000 0.6658 +vn 0.2607 0.8774 0.4028 +vn 0.0886 0.6800 0.7278 +vn 0.0848 0.6805 0.7279 +vn 0.1584 0.6702 0.7251 +vn 0.1622 0.6696 0.7248 +vn -0.9978 0.0357 0.0563 +vn -0.9991 -0.0307 0.0291 +vn -0.9992 -0.0059 0.0393 +vn -0.9958 0.0627 0.0673 +vn -0.1004 -0.6788 -0.7275 +vn -0.1177 -0.9746 0.1905 +vn -0.0578 -0.8693 0.4909 +vn -0.0919 -0.8375 0.5386 +vn 0.4740 0.8432 0.2537 +vn 0.2997 0.2245 0.9272 +vn 0.2117 0.8337 0.5100 +vn -0.0699 -0.7919 0.6066 +vn -0.0000 -0.7314 0.6819 +vn -0.0001 0.7313 -0.6820 +vn -0.0137 0.7175 -0.6964 +vn -0.0000 -0.7315 0.6819 +vn -0.0694 0.6565 -0.7511 +vn 0.5916 -0.0457 -0.8050 +vn 0.8247 -0.5519 0.1239 +vn -0.5318 -0.7322 -0.4255 +vn -0.0000 0.6815 0.7318 +vn 0.0001 0.6820 0.7313 +vn 0.5959 -0.6134 0.5183 +vn -0.0575 -0.9822 0.1788 +vn -0.1924 -0.5716 0.7977 +vn -0.3389 -0.6656 0.6649 +vn -0.1831 -0.5649 0.8046 +vn -0.0339 -0.4478 0.8935 +vn 0.0672 -0.7054 0.7056 +vn 0.0626 -0.7044 0.7071 +vn 0.1935 -0.7280 0.6577 +vn 0.1416 -0.9897 0.0192 +vn 0.1273 -0.9917 0.0181 +vn 0.0955 -0.9954 0.0001 +vn 0.1546 -0.9877 -0.0229 +vn 0.1007 -0.9949 0.0029 +vn 0.1382 -0.9900 -0.0294 +vn 0.1595 -0.9872 0.0053 +vn 0.0956 -0.9954 0.0002 +vn 0.0957 -0.9954 -0.0000 +vn 0.0957 -0.9954 0.0001 +vn 0.0954 -0.9954 0.0001 +vn 0.0956 -0.9954 0.0000 +vn 0.0913 -0.0070 -0.9958 +vn 0.0203 0.1988 -0.9798 +vn 0.0796 0.0280 -0.9964 +vn 0.0111 0.2247 -0.9744 +vn -0.0957 0.9954 0.0000 +vn -0.1094 0.9940 0.0032 +vn -0.1031 0.9947 -0.0019 +vn -0.1081 0.9941 -0.0017 +vn -0.1182 0.9930 0.0024 +vn -0.1223 0.9925 -0.0002 +vn -0.0956 0.9954 -0.0000 +vn -0.0958 0.9954 -0.0000 +vn -0.0959 0.9954 -0.0000 +vn -0.0951 0.9955 -0.0003 +vn -0.0955 0.9954 0.0000 +vn -0.0956 0.9954 -0.0001 +vn -0.6142 -0.2108 -0.7605 +vn -0.1212 -0.5266 -0.8414 +vn -0.0053 0.0003 -1.0000 +vn -0.0074 0.0004 -1.0000 +vn -0.0022 0.0001 -1.0000 +vn -0.0000 -0.0000 -1.0000 +vn 0.9997 -0.0229 -0.0021 +vn 0.9985 -0.0539 0.0065 +vn 0.9996 -0.0296 -0.0003 +vn 0.9981 -0.0604 0.0083 +vn 0.0000 -0.0000 1.0000 +vn -0.0987 0.0773 0.9921 +vn -0.1178 0.0832 0.9895 +vn -0.0557 0.0139 0.9984 +vn -0.1719 0.0417 0.9842 +vn 0.0454 -0.0275 0.9986 +vn 0.0519 -0.0483 0.9975 +vn -0.7481 0.6634 0.0131 +vn -0.8011 0.5985 -0.0119 +vn -0.7614 0.6483 0.0071 +vn -0.8127 0.5824 -0.0178 +vn -0.9268 -0.3721 -0.0506 +vn -0.8684 -0.4957 0.0113 +vn -0.8868 -0.4621 -0.0061 +vn -0.9423 -0.3271 -0.0720 +vn -0.1203 -0.9898 0.0759 +vn 0.9594 0.2506 -0.1293 +vn 0.6409 0.7677 -0.0012 +vn 0.9886 0.1505 0.0036 +vn 0.9893 0.1460 0.0032 +vn 0.9963 0.0860 -0.0032 +vn 0.9967 0.0813 -0.0037 +vn -0.8377 -0.4574 0.2985 +vn -0.5096 0.2731 0.8159 +vn 0.1663 -0.2469 0.9547 +vn 0.7622 0.3959 0.5122 +vn 0.9648 -0.2629 -0.0090 +vn 0.4394 0.3975 -0.8056 +vn -0.0964 -0.4312 -0.8971 +vn -0.8060 0.3236 -0.4957 +vn -0.8785 -0.3281 0.3473 +vn 0.0592 0.0936 0.9938 +vn 0.0069 -0.0205 0.9998 +vn 0.0978 0.1780 0.9792 +vn 0.1335 0.2566 0.9573 +vn 0.9939 -0.1022 0.0426 +vn 0.9915 -0.1194 0.0519 +vn 0.9963 -0.0803 0.0307 +vn 0.9983 -0.0551 0.0171 +vn 0.1169 0.2796 -0.9530 +vn -0.2432 -0.4444 -0.8622 +vn -0.9383 0.3311 -0.1000 +vn -0.0114 -0.0675 -0.9977 +vn -0.0774 -0.4583 -0.8854 +vn -0.0188 -0.0905 -0.9957 +vn -0.0186 -0.0301 0.9994 +vn -0.0005 -0.0426 0.9991 +vn -0.0036 -0.0318 0.9995 +vn 0.0658 -0.1125 0.9915 +vn -0.0966 -0.0061 0.9953 +vn 0.0591 -0.0615 0.9964 +vn -0.0275 -0.0617 -0.9977 +vn -0.0042 -0.0096 -0.9999 +vn -0.0367 -0.0823 -0.9959 +vn 0.0000 1.0000 0.0000 +vn -0.1567 -0.0045 -0.9876 +vn 0.0607 -0.0080 -0.9981 +vn -0.0702 -0.0294 -0.9971 +vn 0.0570 0.0000 -0.9984 +vn -0.2489 -0.0222 -0.9683 +vn -0.3958 0.0338 -0.9177 +vn -0.8326 0.0438 -0.5521 +vn -0.1392 0.1045 -0.9847 +vn -0.0980 0.0736 -0.9925 +vn -0.2256 0.1694 -0.9594 +vn -0.1011 -0.1441 -0.9844 +vn -0.0386 -0.0919 -0.9950 +vn -0.1203 -0.1564 -0.9803 +vn -0.0473 -0.9988 0.0115 +vn -0.0530 -0.9985 -0.0132 +vn -0.0483 -0.9988 0.0072 +vn -0.0540 -0.9984 -0.0174 +vn 0.9942 -0.1062 0.0139 +vn 0.9955 -0.0907 -0.0259 +vn 0.9963 -0.0301 -0.0799 +vn 0.9996 -0.0069 -0.0256 +vn 0.9742 -0.0585 0.2179 +vn 0.9996 -0.0111 0.0264 +vn 0.9976 -0.0491 0.0498 +vn 0.9990 -0.0433 0.0132 +vn -0.9589 -0.2828 -0.0205 +vn -0.9735 -0.2021 0.1069 +vn -0.9343 -0.0257 0.3555 +vn -0.9151 0.0113 0.4030 +vn 0.1485 0.0291 0.9885 +vn -0.1907 -0.0757 0.9787 +vn -0.0218 0.0088 0.9997 +vn 0.1430 0.0540 0.9883 +vn 0.0281 -0.0000 0.9996 +vn 0.0368 0.0188 0.9991 +vn 0.2178 -0.2336 0.9476 +vn 0.2448 0.3057 0.9201 +vn -0.3585 0.4264 0.8305 +vn -0.4283 -0.2616 0.8649 +vn 0.3365 0.2473 0.9086 +vn -0.6140 0.2059 0.7619 +vn -0.0289 -0.5840 0.8113 +vn 0.0513 -0.0496 0.9974 +vn 0.0529 -0.0478 0.9975 +vn 0.1149 0.0227 0.9931 +vn -0.0122 -0.1209 0.9926 +vn -0.7875 -0.6162 0.0123 +vn -0.5604 -0.8281 -0.0145 +vn -0.5441 -0.8389 -0.0161 +vn -0.7978 -0.6028 0.0137 +vn -0.6312 0.7756 -0.0099 +vn -0.6852 0.7282 -0.0178 +vn -0.6889 0.7246 -0.0184 +vn -0.6261 0.7797 -0.0092 +vn 0.8801 0.4744 -0.0174 +vn 0.6732 0.7393 0.0137 +vn 0.6913 0.7224 0.0114 +vn 0.8909 0.4537 -0.0195 +vn 0.3666 -0.9302 -0.0157 +vn 0.6463 -0.7630 0.0140 +vn 0.6322 -0.7747 0.0124 +vn 0.3464 -0.9379 -0.0176 +vn -0.6687 -0.7430 -0.0284 +vn -0.9029 0.4297 0.0049 +vn -0.9342 0.3565 0.0122 +vn -0.9326 0.3608 0.0118 +vn -0.8996 0.4367 0.0041 +vn 0.3189 0.9477 -0.0121 +vn 0.8216 0.5687 0.0393 +vn 0.9298 -0.3663 -0.0356 +vn 0.0191 -0.9993 0.0313 +vn -0.6010 -0.6753 -0.4275 +vn -0.6521 -0.7326 -0.1953 +vn -0.6662 -0.7276 -0.1637 +vn -0.9776 0.1551 0.1426 +vn -0.6810 0.6729 -0.2889 +vn -0.7039 0.7034 -0.0990 +vn -0.7072 0.6988 -0.1075 +vn -0.2638 0.9519 0.1561 +vn 0.7699 0.4871 -0.4122 +vn 0.8384 0.5306 -0.1244 +vn 0.8294 0.5245 -0.1922 +vn 0.9766 0.1587 0.1450 +vn 0.5219 -0.7395 -0.4252 +vn 0.5689 -0.8061 -0.1631 +vn 0.5585 -0.8052 -0.1991 +vn -0.0661 -0.9726 0.2230 +vn -0.8692 -0.4051 0.2835 +vn -0.8964 -0.4178 0.1479 +vn -0.8952 -0.4336 0.1031 +vn -0.9851 -0.0725 -0.1558 +vn -0.5750 0.7855 0.2289 +vn -0.5923 0.7993 0.1009 +vn -0.5888 0.8044 0.0792 +vn -0.2027 0.9671 -0.1539 +vn 0.7577 0.4721 0.4505 +vn 0.8305 0.5175 0.2059 +vn 0.8403 0.5239 0.1391 +vn 0.9854 0.1456 -0.0879 +vn 0.2919 -0.9395 0.1793 +vn 0.3743 -0.9159 0.1450 +vn 0.2977 -0.9539 0.0388 +vn 0.1456 -0.9882 -0.0475 +vn 0.0170 -0.0745 0.9971 +vn -0.1267 -0.0750 0.9891 +vn -0.0016 -0.0746 0.9972 +vn -0.6130 -0.7568 0.2269 +vn -0.9235 -0.0882 -0.3734 +vn -0.9868 -0.0961 -0.1306 +vn -0.9854 -0.0941 -0.1419 +vn -0.7306 0.5974 0.3307 +vn -0.3457 0.9383 -0.0077 +vn -0.3457 0.9383 -0.0088 +vn -0.3439 0.9390 -0.0087 +vn 0.5717 0.7651 0.2963 +vn 0.8187 0.2607 -0.5116 +vn 0.6236 -0.6975 0.3531 +vn 0.0873 -0.9628 -0.2558 +vn 0.0738 -0.9934 -0.0883 +vn 0.0900 -0.9934 -0.0710 +vn -0.7315 -0.5454 -0.4092 +vn -0.6824 -0.5071 -0.5265 +vn -0.6955 -0.5173 -0.4988 +vn -0.9798 -0.1226 0.1579 +vn -0.9909 -0.1218 0.0572 +vn -0.9887 -0.1237 0.0849 +vn -0.2358 0.9660 -0.1060 +vn -0.3163 0.9486 0.0032 +vn -0.2494 0.9637 -0.0956 +vn -0.1312 0.9605 -0.2452 +vn 0.7929 0.5384 0.2853 +vn 0.8212 0.5576 0.1214 +vn 0.8349 0.5390 0.1110 +vn 0.8799 -0.3514 -0.3197 +vn 0.8803 -0.4101 -0.2388 +vn 0.9065 -0.3825 -0.1785 +vn 0.9107 -0.3197 -0.2617 +vn -0.1724 -0.9476 0.2688 +vn -0.1612 -0.9801 0.1159 +vn -0.1784 -0.9802 0.0858 +vn 0.9063 -0.4223 -0.0178 +vn 0.9443 0.3272 0.0356 +vn 0.9521 0.3032 0.0392 +vn 0.0594 0.9946 0.0853 +vn -0.0854 0.9963 0.0019 +vn 0.0136 0.9981 0.0596 +vn 0.0539 0.9984 -0.0180 +vn 0.0145 0.9997 -0.0173 +vn 0.1554 0.0306 0.9874 +vn 0.1639 0.0409 -0.9856 +vn 0.2546 0.0359 -0.9664 +vn 0.2368 0.0369 -0.9709 +vn 0.1478 0.0418 -0.9881 +vn 0.3339 -0.9426 0.0001 +vn 0.3424 -0.9395 0.0011 +vn 0.3418 -0.9398 0.0011 +vn 0.3331 -0.9429 0.0000 +vn 0.9259 0.3759 0.0380 +vn 0.9533 0.3018 0.0108 +vn 0.9143 0.4022 0.0479 +vn 0.9623 0.2719 0.0000 +vn -0.0932 0.1366 0.9862 +vn -0.0717 0.1051 0.9919 +vn -0.0126 0.0184 0.9998 +vn -0.9205 -0.1552 -0.3585 +vn 0.0480 -0.0544 -0.9974 +vn -0.0330 -0.0663 0.9973 +vn 0.9834 0.1812 0.0125 +vn 0.9687 0.2446 0.0427 +vn 0.9747 0.2211 0.0314 +vn 0.9879 0.1551 0.0002 +vn 0.0998 0.0147 -0.9949 +vn 0.0569 -0.0424 -0.9975 +vn 0.0573 -0.0419 -0.9975 +vn 0.0145 -0.0984 -0.9950 +vn 0.0397 0.0787 -0.9961 +vn 0.0432 0.0696 -0.9966 +vn -0.0018 0.1863 -0.9825 +vn 0.0740 -0.0120 -0.9972 +vn -0.1879 0.1494 -0.9708 +vn 0.0135 0.1077 -0.9941 +vn -0.0176 0.1144 -0.9933 +vn 0.1887 0.0675 -0.9797 +vn -0.0001 -1.0000 0.0013 +vn -0.0569 -0.9984 0.0049 +vn -0.0313 -0.9995 0.0097 +vn 0.0188 -0.9998 0.0075 +vn -0.6097 0.7920 0.0316 +vn 0.6854 0.5666 -0.4574 +vn 0.5496 0.8276 0.1140 +vn 0.8036 -0.3057 0.5107 +vn -0.0711 0.0982 -0.9926 +vn -0.0919 0.1774 -0.9798 +vn -0.0570 0.2309 -0.9713 +vn 0.2558 -0.9262 0.2770 +vn 0.2897 -0.7435 -0.6028 +vn -0.1177 0.5253 -0.8428 +vn -0.1004 0.9950 0.0000 +vn -0.9978 -0.0655 -0.0123 +vn -0.9991 -0.0004 -0.0423 +vn -0.9992 -0.0247 -0.0311 +vn -0.9958 -0.0919 -0.0000 +vn 0.0886 -0.9961 0.0009 +vn 0.0848 -0.9964 0.0012 +vn 0.1586 -0.9873 -0.0044 +vn 0.1623 -0.9867 -0.0047 +vn -0.8627 -0.0967 0.4963 +vn 0.3179 -0.9361 -0.1505 +vn 0.3145 -0.9333 -0.1730 +vn 0.3495 -0.8989 0.2643 +vn 0.3495 -0.8927 0.2845 +vn 0.8798 -0.3454 -0.3265 +vn -0.0043 0.0061 -1.0000 +vn -0.0245 0.0346 -0.9991 +vn -0.0313 0.0442 -0.9985 +vn 0.8083 0.3188 0.4950 +vn 0.5031 0.7454 -0.4373 +vn -0.6212 0.7836 0.0000 +vn -0.6079 0.7920 0.0568 +vn -0.5353 0.7980 0.2768 +vn -0.5191 0.7945 0.3151 +vn -0.1209 0.1562 0.9803 +vn -0.0240 0.0321 0.9992 +vn -0.1506 0.1940 0.9694 +vn 0.0000 0.0005 1.0000 +vn 0.9945 0.1049 0.0000 +vn 0.9944 0.1057 0.0004 +vn 0.9943 0.1066 0.0010 +vn 0.9942 0.1074 0.0014 +vn -0.0947 0.9955 -0.0006 +vn -0.0943 0.9955 0.0000 +vn -0.0947 0.9955 -0.0005 +vn -0.0952 0.9955 -0.0011 +vn 0.0168 0.0026 0.9999 +vn 0.0152 0.0062 0.9999 +vn 0.0156 0.0053 0.9999 +vn 0.1241 -0.9923 -0.0005 +vn 0.1243 -0.9922 -0.0002 +vn 0.1243 -0.9922 -0.0003 +vn 0.1245 -0.9922 0.0000 +vn -0.9988 -0.0498 0.0000 +vn -0.9957 -0.0904 -0.0204 +vn -0.9977 -0.0674 -0.0088 +vn -0.9938 -0.1074 -0.0289 +vn 0.7281 0.6835 0.0522 +vn -0.4102 -0.9119 0.0091 +vn -0.4169 -0.9089 0.0094 +vn 0.0024 -0.9999 -0.0110 +vn 0.0582 -0.9982 -0.0135 +vn 0.0218 -0.0094 -0.9997 +vn 0.0180 -0.0010 -0.9998 +vn 0.0168 0.0017 -0.9999 +vn 0.0231 -0.0123 -0.9997 +vn 0.0172 0.0018 0.9999 +vn -0.9947 -0.1030 0.0000 +vn -0.9984 0.0522 -0.0193 +vn 0.0118 0.9991 0.0415 +vn 0.0188 0.9950 -0.0981 +vn 0.0120 0.9992 0.0370 +vn 0.0190 0.9946 -0.1024 +vn 0.9932 0.0631 0.0976 +vn 0.9979 0.0406 -0.0498 +vn 0.9947 0.0609 0.0829 +vn 0.9972 0.0382 -0.0650 +vn 0.0452 -0.9972 0.0598 +vn -0.6986 -0.7142 0.0443 +vn -0.2160 -0.1447 -0.9656 +vn 0.2552 0.4159 -0.8729 +vn -0.2489 0.4867 -0.8373 +vn 0.1916 -0.3431 -0.9195 +vn -0.1190 -0.4339 -0.8931 +vn -0.9135 -0.4067 -0.0129 +vn -0.9774 -0.2112 0.0005 +vn -0.9181 -0.3961 -0.0121 +vn -0.9786 -0.2057 0.0008 +vn -0.3076 -0.6693 0.6763 +vn 0.0857 -0.9956 0.0375 +vn 0.1105 -0.9927 -0.0474 +vn 0.0215 -0.9998 0.0000 +vn 0.2028 -0.9792 -0.0064 +vn 0.1634 -0.9866 0.0022 +vn 0.3942 -0.9190 -0.0085 +vn 0.4985 -0.8669 0.0019 +vn 0.3632 -0.9317 0.0008 +vn 0.5303 -0.8478 -0.0009 +vn 0.0834 -0.1786 0.9804 +vn -0.2061 0.3881 0.8982 +vn -0.9512 0.1256 0.2818 +vn -0.5720 -0.2550 0.7796 +vn 0.7584 -0.1129 0.6419 +vn 0.4410 0.3667 0.8192 +vn -0.9988 0.0437 -0.0227 +vn 0.0191 0.9946 -0.1024 +vn 0.0120 0.9992 0.0394 +vn 0.0189 0.9950 -0.0981 +vn 0.0118 0.9990 0.0440 +vn 0.9607 -0.2776 -0.0076 +vn -0.4088 -0.9039 -0.1262 +vn -0.4149 -0.8995 -0.1370 +vn -0.2451 -0.9585 -0.1459 +vn -0.1968 -0.9714 -0.1327 +vn 0.0063 -0.9994 0.0327 +vn 0.0122 -0.9980 0.0620 +vn 0.9971 0.0382 -0.0651 +vn 0.9947 0.0609 0.0830 +vn 0.9932 0.0631 0.0977 +vn -0.0796 0.1947 0.9776 +vn -0.0049 -0.0010 1.0000 +vn -0.0010 -0.0818 0.9966 +vn 0.0165 0.8513 0.5245 +vn 0.0120 0.8652 0.5014 +vn 0.0671 0.9773 0.2009 +vn 0.0422 0.9974 0.0580 +vn 0.0687 0.9835 -0.1675 +vn 0.0600 0.9964 -0.0599 +vn -0.0024 0.9796 -0.2012 +vn -0.0007 0.9817 -0.1903 +vn -0.1084 0.3130 0.9435 +vn 0.0342 -0.0669 -0.9972 +vn 0.0759 -0.1482 -0.9860 +vn 0.1042 -0.2035 -0.9735 +vn 0.9279 -0.3722 0.0241 +vn 0.0194 -0.9976 0.0671 +vn 0.0276 -0.9990 0.0346 +vn 0.1157 -0.9914 -0.0616 +vn 0.0616 -0.9740 0.2179 +vn -0.0180 -0.9276 0.3730 +vn 0.0656 -0.9439 -0.3236 +vn -0.1450 0.1090 0.9834 +vn -0.1027 0.0771 0.9917 +vn 0.0144 -0.0127 0.9998 +vn 0.0096 -0.0223 0.9997 +vn 0.0016 -0.0385 0.9993 +vn 0.0196 -0.0021 0.9998 +vn -0.2345 0.1762 0.9560 +vn -0.0219 0.9998 -0.0006 +vn -0.0039 1.0000 -0.0001 +vn -0.2418 0.9703 0.0023 +vn -0.2448 0.9696 0.0007 +vn -0.3468 0.9379 0.0029 +vn -0.3541 0.9352 -0.0003 +vn -0.0364 -0.6773 0.7348 +vn 0.0643 -0.7085 0.7027 +vn 0.0226 -0.6474 0.7618 +vn 0.0650 -0.7095 0.7017 +vn 0.1064 -0.7647 0.6355 +vn 0.8013 0.0422 -0.5968 +vn 0.1274 -0.0730 0.9892 +vn 0.3015 -0.1156 -0.9464 +vn -0.0766 0.4389 -0.8953 +vn -0.5707 -0.4211 -0.7050 +vn -0.7697 -0.4446 0.4581 +vn -0.0514 -0.9504 -0.3069 +vn 0.0250 -0.9986 -0.0476 +vn -0.0399 -0.9625 -0.2684 +vn 0.0423 -0.9990 0.0126 +vn 0.9834 -0.1144 -0.1410 +vn 0.9687 -0.1356 -0.2081 +vn 0.9747 -0.1278 -0.1832 +vn 0.9879 -0.1057 -0.1135 +vn -0.0329 0.7747 -0.6315 +vn 0.0481 -0.6923 0.7200 +vn -0.9203 -0.1568 0.3585 +vn -0.0932 0.6282 -0.7725 +vn 0.9533 -0.1980 -0.2281 +vn 0.9259 -0.2286 -0.3009 +vn 0.9623 -0.1855 -0.1989 +vn 0.9143 -0.2393 -0.3268 +vn 0.3339 0.6429 0.6893 +vn 0.3424 0.6416 0.6863 +vn 0.3418 0.6417 0.6866 +vn 0.3331 0.6431 0.6896 +vn 0.1638 -0.7488 0.6422 +vn 0.2548 -0.7312 0.6327 +vn 0.2369 -0.7352 0.6351 +vn 0.1477 -0.7512 0.6433 +vn 0.1553 0.7012 -0.6958 +vn -0.0849 -0.6781 -0.7300 +vn 0.0542 -0.6941 -0.7179 +vn 0.0148 -0.6944 -0.7194 +vn 0.0140 -0.6372 -0.7706 +vn 0.0597 -0.6160 -0.7855 +vn 0.0000 -0.6820 -0.7314 +vn -0.0001 -0.6820 -0.7314 +vn 0.0001 -0.6820 -0.7314 +vn -0.0001 -0.6820 -0.7313 +vn 0.0001 -0.6820 -0.7313 +vn -0.1476 0.7614 0.6313 +vn -0.3798 0.6026 0.7019 +vn -0.3955 0.6112 0.6856 +vn -0.8201 -0.4394 -0.3665 +vn -0.8134 -0.4907 -0.3124 +vn -0.8137 -0.4891 -0.3141 +vn -0.9980 0.0636 -0.0031 +vn -0.9990 0.0394 0.0196 +vn -0.9896 0.0509 0.1344 +vn 0.2490 -0.7491 -0.6139 +vn 0.0401 -0.5596 -0.8278 +vn 0.0242 -0.5628 -0.8262 +vn 0.2671 -0.7509 -0.6040 +vn 0.9832 0.1811 0.0224 +vn 0.9650 0.0249 0.2612 +vn 0.9627 0.0064 0.2704 +vn 0.9791 0.2033 -0.0067 +vn -0.1262 0.7475 0.6521 +vn -0.1212 0.8619 0.4924 +vn 0.3586 0.5061 0.7844 +vn 0.9291 0.3407 -0.1442 +vn 0.7982 -0.5915 -0.1141 +vn 0.0221 -0.2979 -0.9543 +vn -0.7041 -0.6597 -0.2627 +vn -0.9740 0.0394 0.2230 +vn -0.9065 0.0762 0.4152 +vn -0.3914 0.5135 0.7636 +vn 0.3734 0.8037 0.4633 +vn 0.8848 -0.1807 0.4294 +vn 0.8574 -0.1113 -0.5025 +vn 0.2506 -0.8808 -0.4018 +vn -0.3688 -0.4589 -0.8083 +vn -0.7955 -0.5605 -0.2303 +vn -0.7379 0.6604 0.1390 +vn -0.9055 0.3219 0.2765 +vn -0.9454 0.2552 0.2028 +vn -0.8948 0.4015 0.1955 +vn -0.4073 0.5992 0.6893 +vn -0.2853 0.6488 0.7055 +vn -0.4054 0.5453 0.7337 +vn -0.5858 -0.4953 -0.6416 +vn -0.5143 -0.5659 -0.6444 +vn -0.5186 -0.5637 -0.6429 +vn -0.5756 -0.5091 -0.6399 +vn 0.8485 -0.3771 -0.3712 +vn 0.8680 -0.3039 -0.3927 +vn 0.8438 -0.2796 -0.4581 +vn 0.9804 0.1559 0.1207 +vn 0.3785 0.6179 0.6892 +vn 0.3193 0.6419 0.6972 +vn 0.3770 0.6956 0.6115 +vn 0.3227 0.7143 0.6210 +vn 0.2248 0.6089 0.7607 +vn 0.8544 -0.2115 -0.4747 +vn 0.8970 -0.2624 -0.3558 +vn -0.5697 -0.4838 -0.6644 +vn -0.5433 -0.5235 -0.6563 +vn -0.9516 0.2785 0.1301 +vn -0.9879 0.0018 0.1551 +vn -0.0002 -0.7313 0.6821 +vn -0.0539 0.7807 0.6226 +vn -0.2793 0.5994 0.7501 +vn 0.8568 -0.2400 0.4564 +vn 0.9857 -0.0699 -0.1533 +vn 0.3045 -0.8192 -0.4860 +vn -0.2260 -0.3857 -0.8945 +vn -0.8392 -0.5438 -0.0068 +vn -0.9351 0.3543 0.0079 +vn 0.1220 0.6947 0.7089 +vn -0.2880 0.6406 0.7118 +vn -0.2523 0.6502 0.7167 +vn 0.1529 0.6940 0.7036 +vn 0.9390 0.2189 0.2653 +vn 0.4855 -0.6052 -0.6309 +vn 0.7873 -0.4035 -0.4662 +vn 0.8022 -0.3885 -0.4533 +vn 0.4577 -0.6173 -0.6399 +vn -0.8319 -0.3792 -0.4051 +vn -0.8961 -0.2920 -0.3344 +vn -0.8919 -0.2985 -0.3398 +vn -0.8256 -0.3866 -0.4110 +vn -0.0945 0.6768 0.7300 +vn -0.0665 0.6804 0.7298 +vn -0.0684 0.6802 0.7298 +vn -0.0963 0.6766 0.7300 +vn 0.9996 -0.0223 -0.0162 +vn 0.9975 0.0527 0.0478 +vn 0.9968 0.0592 0.0534 +vn 0.9994 -0.0288 -0.0217 +vn -0.1556 -0.6696 -0.7262 +vn -0.1789 -0.6650 -0.7251 +vn -0.1772 -0.6653 -0.7252 +vn -0.1537 -0.6700 -0.7263 +vn -0.9968 0.0528 0.0600 +vn -0.9901 0.0977 0.1006 +vn -0.9907 0.0948 0.0981 +vn -0.9971 0.0502 0.0576 +vn 0.0415 0.6853 -0.7271 +vn 0.0403 0.6847 -0.7277 +vn -0.0281 0.6490 -0.7602 +vn 0.1028 0.7132 -0.6934 +vn -0.3748 0.5164 -0.7700 +vn 0.3441 0.5002 -0.7946 +vn 0.1401 0.9845 0.1053 +vn -0.1873 0.8629 -0.4695 +vn -0.1988 0.8554 -0.4783 +vn -0.0567 0.9296 -0.3641 +vn -0.3223 0.7583 -0.5667 +vn -0.0460 0.3951 -0.9175 +vn 0.4364 0.6745 -0.5955 +vn 0.0200 0.7086 -0.7054 +vn 0.2645 0.6453 -0.7167 +vn 0.1460 0.6431 -0.7517 +vn 0.0049 0.7314 -0.6820 +vn 0.4941 0.5810 -0.6468 +vn -0.1900 0.7886 -0.5849 +vn -0.8870 0.3199 -0.3329 +vn -0.9373 0.2215 0.2690 +vn 0.9975 0.0699 0.0019 +vn 0.9996 0.0269 -0.0099 +vn 0.9990 0.0392 0.0226 +vn 0.9742 0.1992 -0.1058 +vn 0.9996 -0.0141 0.0225 +vn 0.9964 -0.0378 0.0765 +vn 0.9955 0.0429 0.0841 +vn 0.9942 0.0826 0.0682 +vn -0.0483 0.6866 0.7254 +vn -0.0532 0.6710 0.7396 +vn -0.0542 0.6677 0.7425 +vn -0.0473 0.6898 0.7224 +vn -0.0001 -0.7312 0.6822 +vn 0.0000 -0.7314 0.6820 +vn -0.0127 -0.6780 0.7349 +vn -0.0001 -0.7311 0.6823 +vn -0.0114 -0.6836 0.7297 +vn -0.0617 -0.7607 0.6461 +vn -0.1463 -0.7939 0.5902 +vn -0.0893 -0.7725 0.6287 +vn -0.6037 -0.5069 0.6153 +vn -0.7539 -0.4297 0.4970 +vn -0.7334 -0.4425 0.5161 +vn -0.9983 0.0249 0.0522 +vn -0.5834 -0.5149 0.6281 +vn -0.0073 -0.7606 0.6492 +vn 0.0390 -0.7526 0.6573 +vn -0.0788 -0.7607 0.6443 +vn 0.0727 -0.7366 0.6724 +vn 0.0773 -0.7291 0.6800 +vn 0.0034 -0.7369 0.6760 +vn 0.0045 -0.7385 0.6742 +vn -0.0129 0.7501 -0.6612 +vn 0.0001 0.7306 -0.6828 +vn 0.0704 0.7774 -0.6250 +vn 0.0659 0.8018 -0.5940 +vn -0.0964 0.7321 -0.6744 +vn 0.0000 0.7303 -0.6831 +vn -0.0773 -0.3350 0.9390 +vn 0.0746 0.6809 0.7286 +vn 0.0898 0.6750 0.7324 +vn 0.0800 0.6777 0.7310 +vn 0.0955 0.6856 0.7217 +vn 0.1051 0.6765 0.7289 +vn 0.0891 0.6798 0.7280 +vn 0.0720 0.6802 0.7295 +vn 0.0720 0.6801 0.7295 +vn 0.0709 0.6805 0.7293 +vn 0.0718 0.6802 0.7295 +vn 0.0715 0.6803 0.7295 +vn 0.0717 0.6802 0.7295 +vn 0.0719 0.6802 0.7295 +vn 0.0273 -0.7226 0.6908 +vn -0.1084 -0.6974 0.7085 +vn 0.0285 -0.7194 0.6940 +vn -0.0966 -0.6943 0.7132 +vn -0.0740 -0.6805 -0.7290 +vn -0.0718 -0.6802 -0.7295 +vn -0.0721 -0.6802 -0.7294 +vn -0.0764 -0.6792 -0.7300 +vn -0.1041 -0.6719 -0.7333 +vn -0.0967 -0.6740 -0.7323 +vn -0.1566 -0.6552 -0.7391 +vn -0.0717 -0.6802 -0.7295 +vn -0.0719 -0.6801 -0.7296 +vn -0.0719 -0.6802 -0.7295 +vn -0.0716 -0.6803 -0.7295 +vn 0.0001 -0.7313 0.6820 +vn -0.0003 -0.7314 0.6819 +vn -0.1472 -0.7139 0.6846 +vn -0.0912 -0.7243 0.6835 +vn -0.0003 -0.7315 0.6818 +vn 0.7096 -0.4747 -0.5207 +vn 0.7928 -0.3850 -0.4725 +vn 0.8123 -0.3604 -0.4585 +vn 0.9496 0.1822 0.2552 +vn 0.8313 0.3870 0.3990 +vn 0.9351 0.2170 0.2803 +vn 0.8002 0.4242 0.4240 +vn 0.0002 0.7312 -0.6822 +vn 0.0002 0.7311 -0.6823 +vn 0.0002 0.7312 -0.6821 +vn -0.1035 0.6718 -0.7334 +vn -0.1171 0.6780 -0.7257 +vn -0.0832 0.7695 -0.6333 +vn -0.0716 0.7755 -0.6273 +vn 0.0447 0.7495 -0.6604 +vn 0.0507 0.7630 -0.6444 +vn -0.6349 -0.5571 -0.5353 +vn -0.9681 -0.1130 -0.2237 +vn -0.9968 0.0390 0.0703 +vn -0.9867 -0.0725 -0.1453 +vn -0.9823 0.0881 0.1654 +vn -0.1947 0.7042 0.6828 +vn -0.2262 0.6925 0.6851 +vn -0.3260 0.6494 0.6870 +vn -0.3494 0.6379 0.6863 +vn 0.6804 -0.5017 -0.5342 +vn 0.9919 -0.0839 -0.0953 +vn 0.9925 -0.0812 -0.0917 +vn 0.9980 -0.0449 -0.0435 +vn 0.9983 -0.0420 -0.0397 +vn -0.9577 0.2806 0.0632 +vn -0.9621 0.2665 0.0574 +vn -0.9671 0.2493 0.0504 +vn -0.9702 0.2381 0.0459 +vn 0.1496 0.6101 -0.7781 +vn 0.4488 0.8458 -0.2885 +vn 0.8486 -0.4989 -0.1761 +vn 0.3929 -0.1600 0.9056 +vn -0.1713 -0.8540 0.4913 +vn -0.4291 0.7229 -0.5416 +vn -0.3976 0.6661 -0.6310 +vn -0.4625 0.7842 -0.4137 +vn -0.4848 0.8261 -0.2873 +vn 0.6429 0.2394 -0.7275 +vn 0.8523 0.3215 0.4127 +vn 0.6145 -0.7784 0.1282 +vn -0.6512 -0.2325 0.7225 +vn -0.6492 -0.3083 0.6954 +vn -0.6403 -0.4040 0.6533 +vn -0.6316 -0.4590 0.6248 +vn 0.0383 0.7748 0.6310 +vn -0.0298 0.7950 0.6059 +vn 0.0393 0.7745 0.6314 +vn 0.1168 0.7461 0.6556 +vn -0.3736 0.7815 0.4997 +vn -0.1134 0.3991 0.9099 +vn 0.3740 0.5525 0.7449 +vn 0.1136 0.9353 0.3352 +vn -0.0723 0.9562 0.2836 +vn -0.2394 0.8374 0.4914 +vn -0.1561 0.7435 0.6502 +vn -0.2208 0.6057 0.7644 +vn -0.0563 0.4454 0.8935 +vn 0.5442 0.6910 0.4757 +vn 0.1191 0.6723 -0.7306 +vn 0.1632 0.6771 -0.7176 +vn 0.1491 0.6876 -0.7106 +vn 0.1218 0.6696 -0.7327 +vn 0.1388 0.6599 -0.7384 +vn 0.1257 0.6638 -0.7373 +vn 0.0981 0.6788 -0.7278 +vn 0.0980 0.6788 -0.7277 +vn 0.0984 0.6789 -0.7276 +vn 0.0978 0.6787 -0.7279 +vn 0.0980 0.6787 -0.7278 +vn 0.0979 0.6787 -0.7278 +vn 0.0980 0.6787 -0.7279 +vn 0.0275 0.7390 0.6731 +vn 0.0984 0.8706 0.4821 +vn 0.0397 0.7645 0.6434 +vn 0.1147 0.8948 0.4314 +vn -0.0980 -0.6787 0.7278 +vn -0.1281 -0.6820 0.7201 +vn -0.0979 -0.6787 0.7278 +vn -0.1333 -0.6765 0.7243 +vn -0.1149 -0.6749 0.7289 +vn -0.1603 -0.6809 0.7146 +vn -0.1803 -0.6794 0.7112 +vn -0.0978 -0.6788 0.7278 +vn -0.0980 -0.6788 0.7278 +vn -0.0978 -0.6786 0.7280 +vn -0.0977 -0.6787 0.7279 +vn -0.0980 -0.6786 0.7279 +vn -0.0974 -0.6786 0.7280 +vn -0.0979 -0.6784 0.7281 +vn -0.6074 0.5086 0.6102 +vn -0.1056 0.2900 0.9512 +vn -0.1411 0.7362 0.6619 +vn -0.1813 0.7348 0.6536 +vn -0.0563 0.7351 0.6756 +vn 0.0002 0.7313 0.6820 +vn 0.0001 0.7313 0.6821 +vn 0.9429 -0.2860 0.1710 +vn 0.9570 0.2308 -0.1755 +vn -0.0006 -0.7311 -0.6823 +vn -0.0003 -0.7308 -0.6825 +vn -0.0006 -0.7312 -0.6822 +vn -0.1055 -0.7764 -0.6214 +vn -0.1188 -0.7688 -0.6284 +vn -0.0813 -0.6838 -0.7251 +vn -0.0697 -0.6785 -0.7313 +vn 0.0454 -0.7118 -0.7009 +vn 0.0519 -0.6969 -0.7153 +vn -0.9738 -0.1568 0.1645 +vn -0.9660 -0.1680 0.1967 +vn -0.9689 -0.1640 0.1852 +vn -0.9764 -0.1527 0.1528 +vn -0.3547 0.6434 -0.6784 +vn -0.3488 0.6437 -0.6812 +vn -0.3301 0.6443 -0.6899 +vn -0.3248 0.6444 -0.6923 +vn 0.6610 -0.4968 0.5625 +vn 0.9883 -0.1067 0.1090 +vn 0.9890 -0.1034 0.1061 +vn 0.9961 -0.0577 0.0665 +vn 0.9965 -0.0542 0.0634 +vn -0.2052 -0.0990 -0.9737 +vn 0.4439 -0.8905 0.0998 +vn 0.8941 0.3703 -0.2520 +vn 0.1792 0.2782 0.9437 +vn -0.4015 0.9149 0.0420 +vn -0.8660 -0.3805 0.3243 +vn -0.8699 0.1292 -0.4760 +vn -0.5581 -0.7808 -0.2808 +vn 0.3319 -0.3918 -0.8581 +vn 0.6921 -0.7031 -0.1631 +vn 0.8300 0.5229 0.1941 +vn 0.6184 0.3816 0.6870 +vn -0.6096 0.6022 0.5156 +vn -0.4956 0.7422 0.4512 +vn -0.6928 0.4578 0.5572 +vn -0.7515 0.3123 0.5811 +vn 0.0001 0.6820 -0.7314 +vn 0.0000 0.6816 -0.7318 +vn -0.5319 -0.3735 0.7600 +vn 0.7826 0.2809 0.5556 +vn 0.5116 -0.8356 0.2000 +vn 0.7361 -0.0999 -0.6694 +vn -0.0612 0.5776 0.8140 +vn -0.0031 0.7441 0.6680 +vn -0.0651 0.7173 0.6937 +vn -0.0851 0.6540 0.7517 +vn -0.0373 -0.7234 -0.6894 +vn -0.0490 -0.7268 -0.6851 +vn -0.0001 -0.7313 -0.6821 +vn -0.0431 -0.7014 -0.7114 +vn 0.0001 0.7314 0.6819 +vn 0.2547 0.8919 -0.3736 +vn -0.1177 0.2581 0.9589 +vn -0.3612 -0.6467 0.6718 +vn -0.3556 -0.6376 0.6833 +vn -0.1004 -0.6788 0.7274 +vn -0.9978 0.0537 -0.0396 +vn -0.9991 0.0312 0.0286 +vn -0.9992 0.0396 0.0032 +vn -0.9958 0.0627 -0.0672 +vn 0.0888 0.6786 -0.7291 +vn 0.0850 0.6786 -0.7295 +vn 0.1586 0.6766 -0.7191 +vn 0.1624 0.6763 -0.7185 +vn 0.3291 0.6652 -0.6703 +vn 0.2043 0.7054 -0.6788 +vn 0.3667 0.6463 -0.6692 +vn 0.4663 0.6437 -0.6069 +vn 0.4645 0.6508 -0.6006 +vn -0.0409 0.7306 0.6816 +vn -0.0315 0.7659 0.6422 +vn -0.0205 0.7373 0.6753 +vn -0.0196 0.7779 0.6280 +vn 0.9123 -0.3653 0.1853 +vn 0.9067 -0.3252 0.2687 +vn 0.8578 -0.2118 0.4683 +vn 0.8275 -0.1665 0.5362 +vn -0.5458 -0.6713 0.5015 +vn -0.5389 -0.6880 0.4860 +vn -0.1306 -0.7593 -0.6375 +vn -0.0447 -0.7379 -0.6735 +vn -0.1403 -0.7682 -0.6246 +vn -0.0667 -0.7332 -0.6768 +vn 0.0000 -0.7313 -0.6820 +vn 0.0000 0.7314 0.6820 +vn 0.9945 -0.0715 0.0767 +vn 0.9944 -0.0724 0.0770 +vn 0.9943 -0.0734 0.0773 +vn 0.9942 -0.0743 0.0776 +vn 0.0007 -0.7314 -0.6819 +vn -0.0947 -0.6785 0.7285 +vn -0.0943 -0.6789 0.7281 +vn -0.0947 -0.6786 0.7284 +vn -0.0952 -0.6781 0.7288 +vn 0.0168 -0.7331 -0.6800 +vn 0.0152 -0.7355 -0.6774 +vn 0.0156 -0.7349 -0.6780 +vn 0.1241 0.6771 -0.7254 +vn 0.1243 0.6769 -0.7255 +vn 0.1245 0.6767 -0.7256 +vn -0.9988 0.0340 -0.0365 +vn -0.9957 0.0766 -0.0522 +vn -0.9977 0.0525 -0.0433 +vn -0.9938 0.0944 -0.0588 +vn 0.7276 -0.5047 0.4646 +vn -0.4093 0.6156 -0.6734 +vn -0.4159 0.6133 -0.6715 +vn 0.0023 0.6900 -0.7238 +vn 0.0580 0.6907 -0.7208 +vn 0.0218 0.7376 0.6749 +vn 0.0180 0.7319 0.6811 +vn 0.0168 0.7301 0.6832 +vn 0.0232 0.7396 0.6727 +vn 0.0171 -0.7325 -0.6806 +vn -0.9947 0.0703 -0.0754 +vn -0.9985 -0.0215 0.0513 +vn 0.0117 -0.7124 0.7017 +vn 0.0187 -0.6071 0.7944 +vn 0.0120 -0.7091 0.7050 +vn 0.0190 -0.6036 0.7970 +vn 0.9932 -0.1145 -0.0205 +vn 0.9979 0.0087 0.0637 +vn 0.9947 -0.1022 -0.0121 +vn 0.9972 0.0215 0.0723 +vn 0.0452 0.6366 -0.7698 +vn -0.6986 0.4546 -0.5526 +vn -0.1522 0.7114 0.6861 +vn -0.2324 0.6129 0.7552 +vn -0.3024 0.7094 0.6367 +vn -0.2175 0.7885 0.5754 +vn -0.2490 0.2805 0.9270 +vn 0.0527 0.7821 0.6209 +vn -0.1191 0.9491 0.2916 +vn -0.9173 0.2627 -0.2992 +vn -0.8266 0.3828 -0.4125 +vn -0.9137 0.2688 -0.3049 +vn -0.8225 0.3872 -0.4166 +vn 0.0821 0.6429 -0.7616 +vn 0.1076 0.7146 -0.6912 +vn 0.0219 0.6820 -0.7310 +vn 0.0101 0.6827 -0.7306 +vn 0.0658 0.6787 -0.7314 +vn 0.2414 0.6704 -0.7017 +vn 0.2077 0.6631 -0.7192 +vn 0.3687 0.6471 -0.6673 +vn 0.4966 0.5908 -0.6359 +vn 0.3631 0.6348 -0.6820 +vn -0.0966 -0.7581 -0.6450 +vn -0.0928 -0.7536 -0.6508 +vn -0.0675 -0.7224 -0.6882 +vn -0.0655 -0.7197 -0.6912 +vn 0.7801 -0.3447 -0.5221 +vn 0.8033 -0.3507 -0.4814 +vn 0.7712 -0.3423 -0.5368 +vn -0.9513 -0.2915 -0.1002 +vn -0.5713 -0.3961 -0.7188 +vn 0.7505 -0.3367 -0.5687 +vn 0.1341 -0.8448 -0.5180 +vn -0.9988 -0.0132 0.0474 +vn 0.0191 -0.6032 0.7973 +vn 0.0120 -0.7107 0.7034 +vn 0.0189 -0.6068 0.7947 +vn 0.0117 -0.7140 0.7001 +vn 0.8101 0.3899 -0.4379 +vn -0.1983 0.9494 -0.2434 +vn -0.6951 0.4014 -0.5963 +vn 0.0325 0.3812 -0.9239 +vn -0.0188 0.6041 -0.7967 +vn 0.0243 0.4190 -0.9076 +vn -0.0261 0.6327 -0.7739 +vn 0.9971 0.0215 0.0723 +vn 0.9947 -0.1022 -0.0120 +vn 0.9979 0.0088 0.0637 +vn 0.9932 -0.1144 -0.0204 +vn -0.0797 -0.8478 -0.5243 +vn -0.0048 -0.7307 -0.6827 +vn -0.0010 -0.6731 -0.7396 +vn -0.0036 0.7372 0.6756 +vn 0.0165 -0.9642 0.2646 +vn 0.0120 -0.9568 0.2905 +vn 0.0671 -0.8136 0.5776 +vn 0.0424 -0.7227 0.6899 +vn 0.0688 -0.5481 0.8336 +vn 0.0587 -0.6297 0.7746 +vn -0.0237 -0.4000 0.9162 +vn -0.0242 -0.3971 0.9175 +vn 0.0000 -0.7314 -0.6820 +vn 0.0001 -0.7313 -0.6820 +vn -0.1078 -0.9029 -0.4162 +vn 0.0428 0.7853 0.6177 +vn 0.0953 0.8422 0.5306 +vn -0.0001 0.7314 0.6820 +vn 0.1288 0.8733 0.4699 +vn 0.9279 0.2360 -0.2885 +vn 0.0194 0.6683 -0.7437 +vn 0.0260 0.6875 -0.7257 +vn 0.1113 0.7269 -0.6777 +vn 0.0683 0.5435 -0.8366 +vn -0.0185 0.4225 -0.9062 +vn 0.0754 0.8791 -0.4706 +vn -0.0975 -0.7759 -0.6233 +vn -0.0674 -0.7633 -0.6425 +vn 0.0408 -0.6741 -0.7375 +vn 0.1223 -0.5420 -0.8314 +vn 0.0903 -0.5969 -0.7972 +vn -0.0000 -0.7313 -0.6821 +vn -0.1593 -0.7983 -0.5807 +vn -0.0221 -0.6814 0.7316 +vn -0.0040 -0.6819 0.7314 +vn -0.2418 -0.6635 0.7081 +vn -0.2449 -0.6617 0.7086 +vn -0.3467 -0.6418 0.6840 +vn -0.3541 -0.6376 0.6842 +vn 0.8197 0.3463 0.4562 +vn 0.7952 0.3399 0.5022 +vn 0.8282 0.3484 0.4390 +vn 0.8517 0.3539 0.3865 +vn 0.3358 -0.8392 -0.4278 +vn 0.2457 -0.4275 -0.8700 +vn 0.2092 0.9251 0.3170 +vn 0.1487 0.4991 0.8537 +vn 0.3567 0.5410 0.7616 +vn 0.1589 0.5017 0.8503 +vn -0.0546 0.4352 0.8987 +vn -0.3740 0.7459 0.5512 +vn -0.0541 0.6939 -0.7180 +vn -0.0483 0.6758 -0.7355 +vn -0.0531 0.6908 -0.7211 +vn -0.0473 0.6727 -0.7384 +vn -0.0113 0.7757 0.6310 +vn -0.0773 0.9602 0.2683 +vn -0.0189 0.7859 0.6181 +vn -0.0186 -0.7104 -0.7035 +vn -0.0005 -0.7017 -0.7125 +vn -0.0036 -0.7093 -0.7049 +vn 0.0658 -0.6485 -0.7584 +vn -0.0965 -0.7238 -0.6833 +vn 0.0591 -0.6868 -0.7244 +vn -0.0263 0.7727 0.6343 +vn -0.0344 0.7846 0.6190 +vn -0.0002 -0.6820 0.7314 +vn 0.0000 -0.6820 0.7313 +vn -0.0001 -0.6820 0.7313 +vn 0.2091 0.6601 0.7215 +vn 0.0461 0.7140 0.6987 +vn 0.1001 0.6823 0.7242 +vn 0.0570 0.7301 0.6810 +vn 0.4091 0.6235 0.6663 +vn -0.2086 0.7868 0.5809 +vn -0.9972 0.0625 -0.0410 +vn -0.7010 0.5420 0.4635 +vn -0.1392 0.6489 0.7480 +vn -0.0001 0.7313 0.6820 +vn -0.0981 0.6756 0.7307 +vn -0.2256 0.5862 0.7781 +vn 0.0000 0.7313 0.6820 +vn -0.0386 0.7903 0.6115 +vn -0.0471 0.6720 -0.7390 +vn -0.0532 0.6910 -0.7209 +vn -0.0481 0.6753 -0.7360 +vn -0.0542 0.6942 -0.7177 +vn 0.9942 0.0622 -0.0872 +vn 0.9955 0.0809 -0.0487 +vn 0.9964 0.0789 0.0324 +vn 0.9996 0.0234 0.0124 +vn 0.9742 -0.1195 -0.1914 +vn 0.9996 -0.0118 -0.0261 +vn 0.9975 -0.0030 -0.0699 +vn 0.9990 0.0198 -0.0407 +vn -0.9373 0.2530 -0.2397 +vn -0.8954 -0.3329 -0.2958 +vn -0.5537 -0.5129 -0.6560 +vn 0.4934 -0.6966 -0.5209 +vn 0.1640 -0.8142 -0.5569 +vn 0.2635 -0.7759 -0.5732 +vn 0.0049 -0.7314 -0.6820 +vn 0.0255 -0.7607 -0.6486 +vn -0.0024 0.9776 0.2106 +vn -0.0100 0.9780 0.2085 +vn -0.0066 0.9774 0.2115 +vn 0.0008 0.9791 0.2036 +vn -0.0044 0.9781 0.2082 +vn 0.0056 0.9805 0.1963 +vn 0.0032 0.9782 0.2077 +vn 0.0030 0.9768 0.2140 +vn 0.0054 -0.9782 -0.2074 +vn -0.0596 -0.9474 -0.3144 +vn 0.0820 -0.9816 -0.1726 +vn -0.0929 -0.9457 -0.3114 +vn 0.6743 -0.1670 0.7193 +vn 0.4171 -0.3303 0.8467 +vn 0.5597 -0.2480 0.7907 +vn 0.7763 -0.0778 0.6255 +vn 0.9400 -0.1176 -0.3203 +vn 0.6224 0.2349 -0.7466 +vn 0.4202 0.1888 -0.8876 +vn 0.5439 0.2178 -0.8104 +vn 0.2586 0.1484 -0.9545 +vn -0.7943 0.2024 -0.5728 +vn -0.8308 0.1463 -0.5369 +vn -0.8172 0.1683 -0.5513 +vn -0.8539 0.1058 -0.5095 +vn -0.8347 -0.2679 0.4811 +vn -0.5086 -0.1104 0.8539 +vn 0.5992 -0.7688 0.2236 +vn 0.5148 -0.8208 0.2475 +vn 0.6030 -0.7661 0.2224 +vn 0.6784 -0.7078 0.1970 +vn 0.7539 -0.5053 -0.4198 +vn 0.5957 -0.5995 -0.5346 +vn 0.5738 -0.6094 -0.5472 +vn 0.3865 -0.6711 -0.6326 +vn 0.0096 -0.3332 -0.9428 +vn -0.5958 -0.6272 -0.5016 +vn -0.5146 -0.6666 -0.5393 +vn -0.6158 -0.6161 -0.4911 +vn -0.6872 -0.5710 -0.4491 +vn -0.7091 -0.6422 0.2910 +vn -0.5440 -0.7699 0.3337 +vn -0.5157 -0.7868 0.3390 +vn -0.3202 -0.8746 0.3642 +vn 0.0662 -0.7208 0.6900 +vn -0.1972 -0.8428 -0.5007 +vn -0.0090 0.9779 0.2088 +vn -0.0036 0.9772 0.2125 +vn -0.0022 0.9776 0.2105 +vn 0.0074 0.9790 0.2039 +vn -0.0015 0.9790 0.2037 +vn 0.0116 0.9801 0.1982 +vn 0.0062 0.9772 0.2122 +vn 0.0133 0.9782 0.2073 +vn 0.0298 -0.9677 -0.2502 +vn 0.0299 -0.9677 -0.2503 +vn 0.0426 -0.9663 -0.2540 +vn 0.0148 -0.9692 -0.2458 +vn 0.5335 -0.1478 0.8328 +vn 0.8686 -0.2874 0.4036 +vn 0.9488 0.1538 -0.2760 +vn 0.3712 0.0042 -0.9285 +vn -0.3911 0.3394 -0.8555 +vn -0.8834 -0.0953 -0.4588 +vn -0.7000 -0.1925 0.6877 +vn -0.5502 -0.0597 0.8329 +vn -0.6544 -0.1491 0.7413 +vn -0.7654 -0.2619 0.5879 +vn -0.0377 -0.7066 0.7066 +vn 0.5791 -0.7582 0.2996 +vn 0.3445 -0.8628 0.3700 +vn 0.5829 -0.7559 0.2982 +vn 0.7517 -0.6217 0.2201 +vn 0.6438 -0.6201 -0.4484 +vn 0.6278 -0.6947 -0.3511 +vn 0.6445 -0.6148 -0.4546 +vn 0.6499 -0.5343 -0.5404 +vn 0.0619 -0.4361 -0.8978 +vn -0.0808 -0.5617 -0.8234 +vn -0.1076 -0.5831 -0.8053 +vn -0.2334 -0.6726 -0.7022 +vn -0.6949 -0.4538 -0.5578 +vn -0.7099 -0.6808 0.1803 +vn -0.6207 -0.7562 0.2072 +vn -0.5952 -0.7746 0.2140 +vn -0.4929 -0.8370 0.2375 +vn -0.0015 0.9800 0.1991 +vn 0.0035 0.9790 0.2038 +vn -0.0026 0.9814 0.1921 +vn 0.0027 0.9767 0.2144 +vn 0.0091 0.9768 0.2139 +vn 0.0043 0.9773 0.2118 +vn -0.0017 0.9788 0.2047 +vn -0.0114 -0.9631 -0.2688 +vn -0.0464 -0.9669 -0.2511 +vn -0.0140 -0.9635 -0.2675 +vn 0.0250 -0.9577 -0.2867 +vn -0.8782 0.0335 -0.4771 +vn -0.9258 0.1014 -0.3641 +vn -0.8944 0.0541 -0.4439 +vn -0.8376 -0.0114 -0.5461 +vn -0.5121 -0.1097 0.8519 +vn -0.3178 -0.2685 0.9094 +vn -0.3922 -0.2118 0.8952 +vn -0.1754 -0.3652 0.9143 +vn 0.9035 -0.1122 0.4137 +vn 0.9166 -0.0829 0.3912 +vn 0.9089 -0.1004 0.4047 +vn 0.8960 -0.1277 0.4254 +vn 0.5406 0.1936 -0.8187 +vn 0.4360 0.1261 -0.8911 +vn 0.4751 0.1510 -0.8669 +vn 0.3628 0.0806 -0.9284 +vn -0.4381 -0.4104 -0.7998 +vn -0.4929 -0.5370 -0.6847 +vn -0.6399 -0.5956 -0.4856 +vn -0.7006 -0.6426 -0.3101 +vn -0.8127 -0.5705 -0.1180 +vn -0.3417 -0.8061 0.4831 +vn -0.3579 -0.8285 0.4307 +vn -0.3349 -0.7964 0.5036 +vn -0.3214 -0.7765 0.5419 +vn 0.6399 -0.6402 0.4250 +vn 0.6356 -0.6939 0.3384 +vn 0.6280 -0.7295 0.2710 +vn 0.6027 -0.7863 0.1356 +vn 0.5982 -0.3956 -0.6969 +vn 0.5389 -0.4503 -0.7119 +vn 0.4871 -0.4933 -0.7207 +vn 0.3833 -0.5682 -0.7282 +vn -0.8947 -0.4135 -0.1691 +vn -0.9369 0.1730 0.3038 +vn -0.3830 -0.4613 0.8003 +vn -0.0357 0.2688 0.9625 +vn 0.6055 -0.5750 0.5503 +vn 0.8997 0.3758 0.2219 +vn 0.9396 -0.2128 -0.2682 +vn 0.4343 0.4973 -0.7511 +vn 0.0492 -0.3275 -0.9436 +vn -0.5989 0.6178 -0.5095 +vn -0.0000 0.9781 0.2081 +vn -0.0001 0.9782 0.2078 +vn 0.0000 0.9782 0.2077 +vn 0.0002 0.9782 0.2078 +vn -0.0000 0.9781 0.2080 +vn 0.0000 0.9782 0.2078 +vn 0.0001 0.9782 0.2077 +vn -0.6895 0.3701 -0.6226 +vn 0.2606 0.1058 -0.9596 +vn 0.2272 0.1442 -0.9631 +vn 0.2625 0.1036 -0.9594 +vn 0.2824 0.0802 -0.9560 +vn 0.7672 0.2462 -0.5923 +vn 0.9878 -0.1492 0.0455 +vn 0.9985 0.0251 -0.0490 +vn 0.9818 -0.1794 0.0621 +vn 0.9427 -0.3063 0.1320 +vn 0.6128 0.0714 0.7870 +vn 0.6204 0.2845 0.7309 +vn 0.3613 0.5325 0.7654 +vn -0.2278 -0.2975 0.9271 +vn -0.1212 -0.2034 0.9716 +vn -0.2165 -0.2876 0.9330 +vn -0.2810 -0.3436 0.8961 +vn -0.7092 -0.0457 0.7035 +vn -0.9794 0.0165 -0.2012 +vn -0.9846 -0.0605 -0.1641 +vn -0.9843 -0.0497 -0.1694 +vn -0.9800 -0.1651 -0.1113 +vn 0.4161 0.8605 0.2941 +vn 0.8541 0.4895 0.1758 +vn -0.4144 0.8256 -0.3829 +vn 0.5354 0.8260 -0.1763 +vn 0.3294 0.8934 -0.3055 +vn 0.0912 0.8524 -0.5148 +vn 0.2211 0.9584 -0.1806 +vn -0.1320 0.8853 0.4459 +vn -0.2661 0.7099 0.6521 +vn -0.4758 0.7971 0.3717 +vn -0.4768 0.8548 0.2048 +vn -0.4464 0.8797 0.1636 +vn -0.5000 -0.5860 0.6377 +vn -0.1994 0.2189 0.9552 +vn 0.5777 -0.5043 0.6418 +vn 0.8357 0.1571 0.5263 +vn 0.9536 -0.2072 -0.2184 +vn 0.8546 0.3844 -0.3493 +vn 0.1394 -0.2078 -0.9682 +vn -0.2234 0.5924 -0.7740 +vn -0.8067 -0.3221 -0.4955 +vn -0.8932 0.4470 0.0491 +vn 0.0003 0.9782 0.2078 +vn 0.0004 0.9782 0.2076 +vn 0.0004 0.9783 0.2071 +vn -0.0005 0.9782 0.2076 +vn -0.0002 0.9781 0.2080 +vn 0.0001 0.9781 0.2079 +vn -0.0001 0.9782 0.2076 +vn -0.0000 0.9782 0.2076 +vn -0.9603 0.1950 -0.1996 +vn -0.6235 -0.0102 -0.7818 +vn -0.5645 0.0833 -0.8212 +vn -0.5551 0.0970 -0.8261 +vn -0.4473 0.2383 -0.8621 +vn 0.5328 0.5757 -0.6202 +vn 0.3874 0.3870 -0.8368 +vn 0.1760 0.7146 -0.6770 +vn 0.8420 -0.2852 -0.4578 +vn 0.8856 -0.2226 -0.4077 +vn 0.9016 -0.1958 -0.3857 +vn 0.9486 -0.0966 -0.3015 +vn 0.8103 0.1529 0.5656 +vn 0.7454 0.4852 0.4571 +vn 0.7621 0.2921 0.5779 +vn 0.1200 -0.3071 0.9441 +vn 0.1807 -0.2152 0.9597 +vn 0.1011 -0.3345 0.9369 +vn 0.0093 -0.4600 0.8879 +vn -0.8753 -0.1032 0.4725 +vn -0.8260 -0.0481 0.5617 +vn -0.8746 -0.1023 0.4740 +vn -0.9062 -0.1462 0.3967 +vn 0.3974 0.8482 0.3503 +vn 0.0804 0.4804 0.8734 +vn 0.0602 0.4572 0.8873 +vn -0.0001 0.3856 0.9227 +vn 0.4888 0.7389 -0.4638 +vn 0.7752 0.5588 -0.2947 +vn -0.1013 0.8531 -0.5118 +vn 0.1437 0.5499 0.8228 +vn -0.6274 0.4978 0.5988 +vn -0.4266 0.8077 0.4070 +vn -0.6204 0.7327 0.2797 +vn -0.3169 0.9329 0.1710 +vn -0.6540 0.7565 -0.0032 +vn -0.3259 0.7706 -0.5477 +vn 0.3694 0.9183 0.1425 +vn 0.2817 0.9030 0.3244 +vn 0.0550 0.9960 0.0704 +vn -0.1221 0.9089 0.3986 +vn 0.0000 0.9773 0.2119 +vn -0.0028 0.9471 0.3208 +vn -0.0046 0.9298 0.3681 +vn 0.0007 0.9778 0.2095 +vn -0.0012 0.9780 0.2085 +vn 0.1128 0.9714 0.2091 +vn 0.0038 0.9777 0.2102 +vn 0.0704 0.9755 0.2086 +vn -0.0078 0.9778 0.2096 +vn -0.0018 0.9782 0.2078 +vn -0.0172 0.9774 0.2108 +vn -0.0005 0.9783 0.2071 +vn -0.0481 0.9774 0.2060 +vn 0.0023 0.9774 0.2114 +vn -0.0002 0.9791 0.2034 +vn 0.0020 0.9904 0.1383 +vn -0.0719 0.9762 0.2046 +vn 0.0000 -0.9781 -0.2079 +vn 0.0001 -0.9781 -0.2081 +vn 0.0001 -0.9781 -0.2080 +vn 0.0000 -0.9782 -0.2079 +vn 0.0039 0.9949 0.1004 +vn -0.0001 -0.9782 -0.2077 +vn -0.0000 -0.9781 -0.2080 +vn -0.0000 -0.9782 -0.2078 +vn -0.0000 -0.9782 -0.2076 +vn -0.8217 -0.3470 0.4522 +vn -0.6811 0.0990 0.7255 +vn -0.0125 -0.0208 0.9997 +vn 0.0124 -0.0845 0.9963 +vn 0.0573 -0.1987 0.9784 +vn 0.0818 -0.2607 0.9620 +vn 0.9143 -0.1333 0.3824 +vn 0.8844 -0.2512 0.3933 +vn 0.9296 0.1597 0.3320 +vn 0.9174 0.2498 0.3099 +vn 0.6424 -0.1204 -0.7569 +vn 0.6445 -0.1572 -0.7483 +vn 0.6322 -0.0211 -0.7745 +vn 0.6152 0.0798 -0.7843 +vn -0.0685 0.7007 -0.7101 +vn -0.6329 -0.3671 -0.6817 +vn -0.9110 0.3307 -0.2463 +vn -0.0002 0.9782 0.2077 +vn -0.0001 0.9782 0.2079 +vn -0.0002 0.9781 0.2082 +vn -0.0001 0.9782 0.2077 +vn 0.0003 0.9781 0.2081 +vn 0.0001 0.9781 0.2082 +vn -0.0003 0.9781 0.2083 +vn -0.5288 0.1130 -0.8412 +vn -0.5247 0.1220 -0.8425 +vn -0.5232 0.1254 -0.8430 +vn -0.5169 0.1390 -0.8447 +vn 0.7571 0.5851 -0.2906 +vn 0.2737 0.2086 -0.9389 +vn 0.9087 0.1854 -0.3740 +vn 0.9324 0.0379 -0.3595 +vn 0.8310 0.3357 -0.4435 +vn 0.9635 -0.0907 -0.2517 +vn 0.9555 0.0652 0.2876 +vn 0.5003 -0.2230 0.8366 +vn 0.5120 -0.2403 0.8247 +vn 0.5183 -0.2498 0.8179 +vn 0.5467 -0.2939 0.7840 +vn -0.7804 0.4652 0.4178 +vn -0.5078 0.1085 0.8546 +vn -0.5234 -0.0201 0.8518 +vn -0.4734 0.1771 0.8628 +vn -0.9662 -0.1649 0.1981 +vn -0.9900 0.0872 0.1110 +vn -0.9943 -0.0139 0.1053 +vn -0.8564 0.5013 -0.1236 +vn 0.3785 0.2298 0.8966 +vn -0.4640 0.2511 0.8495 +vn -0.8634 0.5031 0.0392 +vn -0.4076 0.3273 0.8525 +vn -0.5640 0.7429 -0.3606 +vn -0.4853 0.6667 -0.5656 +vn 0.3380 0.7046 -0.6240 +vn 0.2460 0.7916 -0.5593 +vn 0.2690 0.7717 -0.5763 +vn 0.7673 0.5185 -0.3773 +vn -0.6661 0.7431 -0.0647 +vn 0.7056 0.6910 0.1572 +vn 0.6716 0.7185 0.1810 +vn 0.5768 0.7358 0.3548 +vn 0.0656 0.8135 0.5779 +vn 0.1766 0.8445 -0.5057 +vn -0.2599 0.7685 0.5847 +vn 0.1436 0.9896 0.0022 +vn 1.0000 -0.0068 0.0052 +vn 0.9995 -0.0296 -0.0079 +vn 0.9999 -0.0090 0.0050 +vn 0.9995 -0.0321 -0.0080 +vn -1.0000 0.0041 0.0075 +vn -0.9995 0.0302 0.0048 +vn -0.9999 0.0062 0.0083 +vn -0.9995 0.0325 0.0057 +vn -0.0021 -0.2402 0.9707 +vn 0.0020 -0.1781 0.9840 +vn -0.0020 -0.2377 0.9713 +vn 0.0021 -0.1755 0.9845 +vn 0.0011 0.9778 0.2095 +vn 0.0013 0.9779 0.2090 +vn 0.0007 0.9784 0.2067 +vn 0.0014 0.9780 0.2086 +vn -0.0001 0.9781 0.2079 +vn -0.9560 0.2873 0.0589 +vn -0.9582 0.2797 0.0594 +vn -0.9578 0.2813 0.0593 +vn -0.9556 0.2889 0.0588 +vn 0.9127 0.3998 0.0841 +vn 0.9097 0.4053 0.0901 +vn 0.9114 0.4022 0.0867 +vn 0.9144 0.3966 0.0807 +vn 0.0251 0.9771 0.2113 +vn 0.0048 0.9824 0.1867 +vn -0.1178 0.9749 0.1887 +vn -0.1663 0.9685 0.1853 +vn -0.2678 0.9423 0.2011 +vn -0.2653 0.9436 0.1979 +vn 0.0000 0.2078 -0.9782 +vn 0.0000 0.2079 -0.9781 +vn 0.0000 0.2080 -0.9781 +vn 0.0000 0.2081 -0.9781 +vn 0.0000 -0.2079 0.9782 +vn 0.0001 -0.2079 0.9782 +vn 0.0000 -0.2080 0.9781 +vn 0.9993 0.0296 0.0219 +vn 0.9994 0.0277 0.0217 +vn 0.0021 0.1755 -0.9845 +vn -0.0019 0.2377 -0.9713 +vn 0.0019 0.1780 -0.9840 +vn -0.0021 0.2402 -0.9707 +vn -0.9993 -0.0359 0.0080 +vn -0.9994 -0.0341 0.0085 +vn 0.0025 0.9778 0.2096 +vn 0.0012 0.9786 0.2059 +vn 0.0014 0.9784 0.2065 +vn -0.0003 0.9782 0.2076 +vn -0.9555 0.2889 0.0603 +vn -0.9582 0.2797 0.0595 +vn -0.9580 0.2805 0.0595 +vn -0.9552 0.2896 0.0603 +vn 0.9021 0.4226 0.0877 +vn 0.8980 0.4303 0.0920 +vn 0.8989 0.4286 0.0911 +vn 0.9029 0.4209 0.0867 +vn -0.0114 0.9778 0.2091 +vn -0.0253 0.9793 0.2009 +vn -0.1352 0.9683 0.2098 +vn -0.1684 0.9649 0.2016 +vn -0.2717 0.9393 0.2094 +vn -0.2934 0.9350 0.1991 +vn 0.0000 -0.2081 0.9781 +vn 0.0001 -0.2079 0.9781 +vn 0.0014 0.9783 0.2072 +vn 0.0070 0.9774 0.2112 +vn -0.0024 0.9785 0.2061 +vn 0.0031 0.9767 0.2146 +vn -0.0014 0.9778 0.2094 +vn -0.0048 0.9784 0.2068 +vn -0.0076 0.9792 0.2027 +vn -0.0166 -0.9671 -0.2539 +vn 0.0006 -0.9684 -0.2496 +vn -0.0163 -0.9671 -0.2539 +vn -0.0315 -0.9657 -0.2576 +vn -0.2193 0.2523 -0.9425 +vn -0.4172 0.1285 -0.8997 +vn -0.3270 0.1877 -0.9262 +vn -0.5193 0.0549 -0.8528 +vn -0.9985 0.0037 0.0553 +vn -0.9605 -0.1492 0.2349 +vn -0.9837 -0.0843 0.1590 +vn -0.9154 -0.2310 0.3295 +vn 0.0366 -0.1046 0.9938 +vn 0.5253 -0.3783 0.7622 +vn 0.9630 0.1198 -0.2415 +vn 0.8981 0.0528 -0.4367 +vn 0.9274 0.0783 -0.3657 +vn 0.8225 0.0013 -0.5687 +vn -0.3585 -0.5053 -0.7849 +vn -0.1421 -0.6148 -0.7758 +vn -0.4244 -0.4633 -0.7780 +vn -0.5743 -0.3486 -0.7407 +vn -0.6239 -0.7704 -0.1312 +vn -0.7307 -0.5592 0.3916 +vn 0.1421 -0.8379 0.5270 +vn 0.0239 -0.8956 0.4443 +vn 0.1943 -0.8053 0.5602 +vn 0.2970 -0.7272 0.6188 +vn 0.7954 -0.6043 -0.0466 +vn 0.7221 -0.6711 -0.1680 +vn 0.6954 -0.6887 -0.2052 +vn 0.5979 -0.7340 -0.3220 +vn 0.4289 -0.3778 -0.8206 +vn 0.0614 -0.5552 0.8294 +vn 0.0672 -0.5409 0.8384 +vn 0.0575 -0.5648 0.8232 +vn 0.0563 -0.5677 0.8213 +vn -0.0205 0.0788 0.9967 +vn -0.0203 0.0756 0.9969 +vn -0.0174 0.0210 0.9996 +vn -0.0149 -0.0269 0.9995 +vn 0.9960 0.0896 0.0047 +vn 0.9954 0.0955 0.0054 +vn 0.9999 -0.0082 -0.0061 +vn 0.9998 0.0172 0.0130 +vn 0.9385 -0.3428 -0.0423 +vn 0.9356 -0.3504 -0.0435 +vn 0.0082 0.2950 -0.9555 +vn 0.0109 0.3423 -0.9395 +vn 0.0183 0.4680 -0.8836 +vn 0.0185 0.4726 -0.8811 +vn -0.0638 0.0729 -0.9953 +vn -0.0695 0.0411 -0.9967 +vn -0.0796 -0.0166 -0.9967 +vn -0.1377 -0.3850 -0.9126 +vn -0.9959 0.0878 0.0234 +vn -0.6568 -0.7459 -0.1108 +vn -0.9939 0.1083 0.0224 +vn -0.9618 0.2689 0.0513 +vn -0.9221 0.3804 0.0713 +vn -0.9206 0.3837 0.0719 +vn -0.0487 0.6937 0.7186 +vn 0.0213 0.7138 0.7000 +vn -0.1403 0.6613 0.7368 +vn 0.4626 0.6337 0.6200 +vn 0.3856 0.4853 0.7847 +vn 0.4698 0.6484 0.5991 +vn 0.5206 0.7633 0.3826 +vn 0.8187 0.5713 -0.0577 +vn 0.3466 0.8724 -0.3447 +vn -0.0428 0.5512 -0.8333 +vn -0.3609 0.8486 -0.3867 +vn -0.9058 0.3875 0.1711 +vn -0.9347 0.3288 0.1348 +vn -0.8536 0.4707 0.2231 +vn -0.7023 0.6322 0.3272 +vn 0.1067 0.7329 0.6719 +vn 0.1200 0.6188 0.7764 +vn 0.0604 0.5673 0.8213 +vn 0.1330 0.6294 0.7656 +vn 0.1936 0.6763 0.7108 +vn 0.8664 0.2866 0.4089 +vn 0.5406 0.8313 -0.1296 +vn 0.5488 0.7856 -0.2859 +vn 0.5438 0.7268 -0.4196 +vn 0.5248 0.6442 -0.5564 +vn -0.4639 0.7730 -0.4327 +vn -0.5372 0.7108 -0.4541 +vn -0.5993 0.6482 -0.4697 +vn -0.6351 0.6072 -0.4775 +vn -0.5438 0.6811 0.4903 +vn -0.4926 0.7066 0.5079 +vn -0.5489 0.6783 0.4884 +vn -0.6269 0.6317 0.4560 +vn -0.1618 0.9057 -0.3917 +vn -0.2088 0.8842 -0.4179 +vn -0.3873 0.8280 -0.4055 +vn 0.9833 0.1239 0.1331 +vn 0.4571 0.8893 -0.0143 +vn -0.0556 0.9024 -0.4273 +vn -0.1135 0.4352 0.8931 +vn -0.1719 0.3519 0.9201 +vn -0.0357 0.5364 0.8432 +vn 0.0340 0.6178 0.7856 +vn -0.4748 0.7731 -0.4205 +vn -0.5792 0.7989 0.1622 +vn -0.6507 0.7110 0.2666 +vn -0.6590 0.6981 0.2799 +vn -0.7108 0.5966 0.3726 +vn -0.0904 0.8359 -0.5414 +vn -0.1001 0.8434 -0.5278 +vn -0.0865 0.8327 -0.5469 +vn -0.0693 0.8185 -0.5703 +vn 0.5688 0.8206 -0.0560 +vn 0.6018 0.7892 0.1224 +vn 0.5305 0.8469 -0.0360 +vn 0.5493 0.8205 -0.1580 +vn 0.6768 0.7226 -0.1411 +vn 0.0582 -0.0830 0.9949 +vn 0.3309 0.7268 0.6019 +vn -0.6780 0.7232 -0.1318 +vn -0.8250 0.5595 -0.0798 +vn -0.8932 0.4473 -0.0466 +vn -0.9378 0.3466 -0.0179 +vn -0.4221 0.6588 0.6227 +vn -0.7807 -0.1353 0.6101 +vn -0.7753 -0.1159 0.6209 +vn -0.7902 -0.1731 0.5879 +vn -0.7963 -0.2011 0.5705 +vn -0.4497 0.5875 -0.6728 +vn -0.8892 -0.0708 -0.4519 +vn 0.5370 0.3898 0.7482 +vn 0.8081 0.2370 -0.5393 +vn 0.7894 0.1630 -0.5918 +vn 0.7402 0.0299 -0.6717 +vn 0.7131 -0.0274 -0.7005 +vn -0.7549 0.1775 0.6313 +vn -0.6616 0.1306 0.7384 +vn -0.7137 0.1562 0.6828 +vn -0.6146 0.1085 0.7813 +vn 0.8954 0.1486 0.4198 +vn 0.9462 0.0569 0.3185 +vn 0.9222 0.1050 0.3723 +vn 0.9639 0.0113 0.2661 +vn -0.1838 -0.1644 -0.9691 +vn -0.2701 -0.2111 -0.9394 +vn -0.2305 -0.1897 -0.9544 +vn -0.3153 -0.2354 -0.9193 +vn -0.0500 0.9910 -0.1239 +vn 0.0173 0.9822 -0.1872 +vn -0.0146 0.9834 -0.1810 +vn 0.0208 0.9795 -0.2002 +vn 0.3814 0.7849 -0.4883 +vn -0.4238 0.9010 -0.0926 +vn -0.0137 0.9719 -0.2348 +vn -0.1162 0.9125 -0.3922 +vn -0.5258 0.8067 0.2698 +vn -0.7662 0.6370 0.0845 +vn -0.7616 0.3885 0.5187 +vn -0.7207 0.5733 -0.3899 +vn -0.4627 0.7169 -0.5215 +vn 0.2371 0.9210 0.3090 +vn -0.1075 0.5454 0.8312 +vn 0.1509 0.3488 0.9250 +vn -0.1319 0.6056 0.7847 +vn -0.3018 0.5574 0.7735 +vn -0.3295 0.5240 0.7854 +vn -0.2021 0.2933 -0.9344 +vn -0.3688 0.2413 -0.8977 +vn -0.2701 0.2735 -0.9232 +vn -0.1096 0.3175 -0.9419 +vn 0.1737 0.6900 -0.7027 +vn 0.7280 0.4029 -0.5547 +vn 0.6484 0.7052 -0.2867 +vn 0.5490 0.8046 -0.2261 +vn 0.7591 0.5108 0.4037 +vn 0.8349 0.5122 0.2015 +vn 0.7521 0.5394 0.3787 +vn 0.6700 0.4201 0.6121 +vn 0.2097 0.2049 0.9561 +vn -0.7342 -0.5366 0.4159 +vn -0.9018 0.2849 -0.3251 +vn -0.7914 0.1908 -0.5807 +vn -0.6199 -0.3793 -0.6869 +vn 0.2612 -0.5308 -0.8062 +vn 0.4683 -0.0517 -0.8820 +vn 0.9016 0.1860 -0.3905 +vn 0.8295 -0.5534 0.0749 +vn 0.6642 0.3285 0.6716 +vn -0.0511 -0.9641 0.2607 +vn -0.0177 -0.9818 0.1893 +vn -0.0058 -0.9904 0.1383 +vn -0.0317 -0.9650 0.2603 +vn -0.0521 -0.9591 0.2782 +vn 0.0098 -0.9810 0.1936 +vn -0.0003 -0.9780 0.2085 +vn 0.0875 -0.9744 0.2073 +vn 0.0354 -0.9747 0.2207 +vn 0.0218 -0.9802 0.1968 +vn -0.0117 -0.9928 0.1193 +vn 0.8886 0.4543 0.0625 +vn 0.8380 -0.5267 -0.1428 +vn -0.0251 0.1517 -0.9881 +vn -0.4017 -0.4758 -0.7824 +vn -0.9307 0.2785 -0.2372 +vn -0.9046 -0.2615 0.3367 +vn -0.2218 0.4556 0.8621 +vn 0.0839 -0.0774 0.9935 +vn -0.1223 -0.8295 0.5449 +vn -0.1135 -0.9807 0.1590 +vn -0.0163 -0.9758 0.2181 +vn 0.0238 -0.9738 0.2263 +vn 0.0802 -0.9122 0.4018 +vn 0.0468 -0.9820 0.1831 +vn 0.0103 -0.9806 0.1959 +vn -0.1147 -0.9672 -0.2265 +vn 0.7911 -0.3116 0.5263 +vn 0.7974 -0.2662 0.5416 +vn 0.7058 -0.2214 0.6729 +vn 0.8481 -0.5158 0.1211 +vn 0.8133 -0.5815 0.0196 +vn 0.7873 -0.5400 -0.2976 +vn 0.6636 -0.5144 -0.5432 +vn 0.5752 -0.4530 -0.6811 +vn 0.0974 -0.9952 -0.0100 +vn 0.1361 -0.6539 -0.7443 +vn -0.2363 -0.3177 -0.9183 +vn 0.0489 -0.3318 -0.9421 +vn -0.3171 -0.9484 -0.0079 +vn -0.4103 -0.8884 -0.2059 +vn -0.8363 -0.3917 0.3838 +vn -0.8318 -0.3624 0.4204 +vn -0.8841 -0.4316 0.1789 +vn -0.7771 -0.1863 0.6011 +vn -0.7711 -0.2461 0.5873 +vn -0.3068 -0.6722 0.6738 +vn -0.4012 -0.7211 0.5649 +vn 0.0758 -0.7223 0.6874 +vn 0.2486 -0.6126 0.7503 +vn 0.9027 0.4260 0.0601 +vn -0.2833 -0.0890 -0.9549 +vn -0.7225 -0.4592 -0.5169 +vn -0.9123 0.2633 -0.3137 +vn -0.0582 0.1579 0.9857 +vn 0.0570 0.0992 0.9934 +vn -0.2113 0.2605 0.9421 +vn -0.2137 0.2669 0.9397 +vn 0.2506 -0.0162 0.9679 +vn 0.5316 0.3917 0.7509 +vn 0.0514 0.9781 -0.2015 +vn 0.0588 0.9728 -0.2241 +vn 0.0383 0.9743 -0.2220 +vn 0.0140 0.9795 -0.2010 +vn 0.0690 0.9788 -0.1927 +vn -0.0373 0.9759 -0.2151 +vn -0.0361 0.9712 -0.2355 +vn -0.0640 0.9796 -0.1904 +vn -0.0231 0.9790 -0.2027 +vn -0.0830 0.9750 -0.2059 +vn 0.0619 0.9702 -0.2343 +vn 0.0276 0.9758 -0.2169 +vn -0.1595 0.9620 0.2215 +vn 0.0923 0.9819 -0.1654 +vn 0.0457 0.9746 -0.2192 +vn -0.0021 -0.9766 0.2151 +vn -0.0270 -0.9758 0.2169 +vn -0.0022 -0.9766 0.2151 +vn 0.0197 -0.9768 0.2135 +vn -0.7212 0.0590 0.6902 +vn 0.0499 0.3218 0.9455 +vn 0.7555 0.0173 0.6549 +vn 0.7686 -0.0317 -0.6390 +vn 0.6643 -0.1199 -0.7378 +vn 0.7356 -0.0617 -0.6746 +vn 0.6111 -0.1585 -0.7756 +vn -0.9300 -0.0255 -0.3667 +vn -0.7893 -0.1733 -0.5890 +vn -0.8454 -0.1247 -0.5193 +vn -0.9534 0.0145 -0.3014 +vn -0.0814 -0.9694 0.2315 +vn -0.1797 -0.9747 0.1327 +vn -0.0956 -0.9906 0.0976 +vn -0.0505 -0.9637 0.2621 +vn -0.2735 -0.9618 0.0078 +vn -0.0698 -0.9939 0.0858 +vn 0.1582 -0.9508 0.2662 +vn 0.0473 -0.9510 0.3056 +vn 0.1096 -0.9822 0.1528 +vn 0.2346 -0.9259 0.2962 +vn 0.6660 0.5869 -0.4605 +vn 0.8176 0.5302 -0.2247 +vn 0.6434 0.5056 -0.5748 +vn 0.8418 0.5042 -0.1929 +vn 0.4061 0.8168 0.4097 +vn 0.4018 0.8061 0.4346 +vn 0.4031 0.8093 0.4273 +vn 0.3993 0.7998 0.4482 +vn -0.2629 0.7403 0.6188 +vn -0.2195 0.7158 0.6629 +vn -0.4567 0.8542 0.2487 +vn -0.7529 0.5425 0.3725 +vn -0.4059 0.8994 -0.1623 +vn -0.6231 0.6870 -0.3739 +vn -0.6511 0.7534 -0.0923 +vn -0.3852 0.5777 -0.7196 +vn -0.3281 0.4972 -0.8032 +vn -0.0830 0.5546 -0.8280 +vn 0.3659 0.2835 -0.8864 +vn 0.4277 0.3959 -0.8126 +vn 0.0416 0.9514 -0.3052 +vn 0.0211 0.9693 -0.2450 +vn 0.0105 -0.9817 0.1904 +vn 0.0139 -0.9816 0.1906 +vn 0.0077 -0.9817 0.1902 +vn -0.9896 0.1051 0.0982 +vn -0.6530 0.0650 0.7545 +vn 0.0574 0.2611 0.9636 +vn 0.6972 0.0664 0.7138 +vn 0.9957 0.0438 -0.0820 +vn 0.8076 -0.1871 -0.5592 +vn -0.0102 -0.1466 -0.9891 +vn -0.5818 -0.2742 -0.7657 +vn 0.0482 -0.9967 0.0654 +vn 0.1247 -0.9755 0.1815 +vn 0.1159 -0.9526 0.2812 +vn -0.0899 -0.9526 0.2905 +vn -0.1152 -0.9549 0.2737 +vn -0.0645 -0.9967 0.0486 +vn -0.0625 -0.9824 0.1760 +vn -0.0249 -0.9993 -0.0287 +vn -0.0380 -0.9471 0.3188 +vn 0.0258 -0.9995 0.0168 +vn 0.2029 -0.9350 0.2908 +vn 0.0604 -0.9530 0.2968 +vn -0.5119 -0.5279 -0.6777 +vn -0.2005 0.7517 0.6283 +vn 0.1039 0.6339 0.7664 +vn 0.0068 0.7256 0.6881 +vn 0.6606 0.7469 0.0763 +vn 0.6879 0.7241 0.0501 +vn 0.5126 0.6670 -0.5407 +vn 0.6001 0.7045 0.3790 +vn 0.6064 0.6752 0.4200 +vn 0.0434 0.9915 -0.1230 +vn 0.1363 0.9791 0.1507 +vn 0.0456 0.9950 -0.0886 +vn -0.4268 0.8006 0.4205 +vn -0.6583 0.7206 0.2175 +vn -0.6870 0.7050 -0.1761 +vn -0.7657 0.5957 -0.2426 +vn -0.4952 0.6545 -0.5713 +vn -0.2099 0.6934 -0.6893 +vn 0.0191 0.6289 -0.7773 +vn 0.4179 0.5662 -0.7105 +vn 0.7112 0.6073 -0.3540 +vn -0.0441 0.9708 -0.2360 +vn -0.0129 0.9764 -0.2155 +vn -0.0365 0.9850 -0.1686 +vn -0.0143 -0.9817 0.1898 +vn -0.0218 -0.9791 0.2022 +vn -0.0146 -0.9816 0.1903 +vn -0.0067 -0.9841 0.1773 +vn -0.4579 0.2424 0.8553 +vn 0.1957 0.1055 0.9750 +vn 0.8222 0.1799 0.5401 +vn 0.9469 -0.1578 -0.2800 +vn 0.5015 -0.0966 -0.8597 +vn -0.3073 -0.2753 -0.9109 +vn -0.8967 -0.0323 -0.4415 +vn -0.9910 -0.0494 0.1244 +vn -0.1608 -0.9440 0.2881 +vn -0.1103 -0.9838 0.1413 +vn 0.0078 -0.9992 0.0392 +vn -0.1967 -0.9280 0.3164 +vn 0.1044 -0.9928 0.0594 +vn -0.0462 -0.9278 0.3702 +vn 0.1355 -0.9864 0.0932 +vn 0.1496 -0.9888 -0.0014 +vn 0.1533 -0.9823 0.1077 +vn 0.0937 -0.9535 0.2864 +vn 0.0164 -0.9388 0.3439 +vn -0.3847 -0.4335 -0.8149 +vn 0.3581 0.6776 0.6424 +vn 0.7415 0.6500 -0.1663 +vn 0.6397 0.7470 -0.1811 +vn 0.6918 0.7108 0.1269 +vn 0.6044 0.7730 0.1927 +vn -0.3180 0.8024 0.5051 +vn -0.2592 0.8311 0.4921 +vn -0.0942 0.8902 0.4458 +vn -0.4612 0.7131 0.5280 +vn -0.7494 0.6511 -0.1203 +vn -0.6527 0.7574 -0.0167 +vn -0.6621 0.6737 -0.3283 +vn -0.7110 0.5758 -0.4037 +vn -0.3748 0.6284 -0.6816 +vn 0.0270 0.6783 -0.7342 +vn 0.1125 0.5634 -0.8185 +vn 0.4579 0.6709 -0.5833 +vn -0.0455 0.9713 -0.2336 +vn 0.0190 0.9782 -0.2069 +vn -0.0080 0.9803 -0.1975 +vn -0.0494 0.9855 -0.1626 +vn 0.0078 0.9835 -0.1809 +vn -0.0002 -0.9774 0.2112 +vn -0.0257 -0.9776 0.2090 +vn 0.0254 -0.9767 0.2132 +vn -0.8349 0.0165 0.5501 +vn -0.3697 0.2647 0.8907 +vn 0.9262 0.0984 0.3638 +vn 0.7351 0.0506 0.6760 +vn 0.8074 0.0667 0.5863 +vn 0.9612 0.1110 0.2526 +vn 0.6809 -0.2191 -0.6989 +vn 0.2306 -0.1511 -0.9613 +vn -0.5491 -0.2445 -0.7992 +vn -0.9468 -0.0097 -0.3217 +vn 0.0952 -0.9776 0.1875 +vn 0.1606 -0.9487 0.2725 +vn 0.0816 -0.9434 0.3216 +vn -0.1252 -0.9512 0.2820 +vn -0.1143 -0.9715 0.2075 +vn -0.0746 -0.9895 0.1237 +vn -0.0584 -0.9912 0.1185 +vn 0.0246 -0.9938 0.1082 +vn -0.0775 -0.9375 0.3392 +vn 0.1062 -0.9749 0.1959 +vn 0.0513 -0.9363 0.3473 +vn -0.7375 -0.4237 0.5258 +vn 0.6359 0.7671 0.0847 +vn 0.5482 0.7459 0.3783 +vn 0.6885 0.7222 0.0660 +vn 0.5466 0.7223 0.4236 +vn -0.1656 0.8294 0.5336 +vn -0.3277 0.8399 0.4326 +vn -0.2655 0.8304 0.4898 +vn -0.1043 0.7867 0.6085 +vn -0.4667 0.7838 0.4096 +vn -0.7463 0.6644 -0.0408 +vn -0.7023 0.6843 -0.1963 +vn -0.7098 0.6441 -0.2850 +vn -0.5567 0.6109 -0.5629 +vn -0.4694 0.5075 -0.7226 +vn -0.2077 0.4064 -0.8898 +vn -0.1143 0.2980 -0.9477 +vn 0.6257 0.5887 -0.5118 +vn 0.4415 0.4971 -0.7470 +vn 0.3126 0.5527 -0.7725 +vn 0.7018 0.5066 -0.5008 +vn -0.0233 0.9755 -0.2188 +vn 0.0179 0.9557 -0.2938 +vn 0.0370 0.9729 -0.2281 +vn -0.2293 0.9375 -0.2619 +vn -0.0006 0.9770 -0.2132 +vn 0.0904 0.9691 -0.2296 +vn 0.0025 0.9766 -0.2150 +vn -0.0012 0.9779 -0.2090 +vn 0.0006 0.9774 -0.2113 +vn 0.0073 0.9775 -0.2110 +vn 0.0012 0.9793 -0.2025 +vn 0.0054 0.9789 -0.2041 +vn 0.0109 0.9793 -0.2023 +vn 0.1534 -0.9610 0.2300 +vn -0.0317 -0.9869 0.1580 +vn 0.0977 -0.9730 0.2091 +vn 0.9228 -0.0587 -0.3808 +vn 0.9717 -0.1249 -0.2007 +vn 0.9390 -0.0762 -0.3354 +vn 0.8799 -0.0208 -0.4747 +vn -0.0225 -0.3825 -0.9237 +vn -0.5352 -0.0765 -0.8413 +vn -0.9259 -0.0770 0.3698 +vn -0.9072 -0.0981 0.4091 +vn -0.9135 -0.0913 0.3966 +vn -0.8965 -0.1091 0.4293 +vn 0.2655 0.2641 0.9273 +vn 0.2985 0.2439 0.9227 +vn 0.2834 0.2532 0.9250 +vn 0.3281 0.2251 0.9174 +vn 0.3314 -0.5445 0.7705 +vn 0.4063 -0.4939 0.7688 +vn 0.5372 -0.3887 0.7486 +vn 0.6656 -0.7173 -0.2059 +vn 0.6636 -0.7191 -0.2061 +vn 0.6618 -0.7208 -0.2062 +vn 0.6585 -0.7237 -0.2065 +vn -0.2834 -0.7056 -0.6495 +vn -0.3154 -0.7501 -0.5813 +vn -0.3346 -0.7756 -0.5352 +vn -0.3743 -0.8244 -0.4246 +vn -0.8094 -0.5719 0.1333 +vn -0.7413 -0.6260 0.2420 +vn -0.7287 -0.6338 0.2596 +vn -0.6249 -0.6803 0.3830 +vn -0.3931 -0.3960 0.8298 +vn 0.1653 -0.6360 0.7537 +vn 0.3226 -0.9012 0.2895 +vn -0.0012 0.9772 -0.2124 +vn -0.0088 0.9770 -0.2128 +vn -0.0026 0.9788 -0.2048 +vn 0.0042 0.9793 -0.2025 +vn -0.0006 0.9766 -0.2151 +vn 0.0067 0.9774 -0.2114 +vn 0.0079 0.9788 -0.2047 +vn 0.0061 0.9808 -0.1948 +vn -0.0740 -0.9905 0.1156 +vn -0.0039 -0.9953 0.0966 +vn 0.1585 -0.9568 0.2437 +vn 0.7777 0.2118 0.5919 +vn 0.5367 0.0895 0.8390 +vn 0.6716 0.1548 0.7246 +vn 0.8471 0.2541 0.4668 +vn 0.9348 -0.2285 -0.2718 +vn 0.5145 -0.0977 -0.8519 +vn 0.3902 -0.1657 -0.9057 +vn 0.4639 -0.1265 -0.8768 +vn 0.2815 -0.2186 -0.9343 +vn -0.8851 -0.1165 -0.4506 +vn -0.8853 -0.1162 -0.4503 +vn -0.8852 -0.1164 -0.4505 +vn -0.8850 -0.1167 -0.4507 +vn -0.5732 0.1098 0.8120 +vn -0.5932 0.0907 0.7999 +vn -0.5811 0.1022 0.8074 +vn -0.5618 0.1204 0.8185 +vn 0.5063 -0.4540 0.7332 +vn 0.5340 -0.5575 0.6356 +vn 0.5398 -0.5847 0.6055 +vn 0.5536 -0.6786 0.4827 +vn 0.8222 -0.5692 -0.0016 +vn 0.2611 -0.8224 -0.5055 +vn 0.3274 -0.8703 -0.3680 +vn 0.2342 -0.7988 -0.5541 +vn 0.1690 -0.7332 -0.6587 +vn -0.5630 -0.7333 -0.3812 +vn -0.5765 -0.7720 -0.2676 +vn -0.6786 -0.7287 -0.0920 +vn -0.6936 -0.7202 0.0158 +vn -0.7876 -0.5827 0.2003 +vn -0.3767 -0.5372 0.7547 +vn -0.3942 -0.5811 0.7120 +vn -0.3710 -0.5235 0.7670 +vn -0.3559 -0.4872 0.7975 +vn 0.3591 -0.8941 0.2676 +vn -0.2276 -0.9658 -0.1240 +vn 0.0013 0.9777 -0.2098 +vn 0.0123 0.9773 -0.2114 +vn -0.0010 0.9779 -0.2089 +vn -0.0036 0.9786 -0.2059 +vn 0.0068 0.9784 -0.2065 +vn -0.0095 0.9783 -0.2067 +vn -0.0008 0.9796 -0.2009 +vn -0.0111 0.9776 -0.2102 +vn -0.0189 -0.9787 0.2046 +vn -0.7695 -0.0185 -0.6384 +vn -0.9521 -0.2639 0.1546 +vn -0.5084 0.3185 0.8001 +vn 0.5706 -0.0815 0.8172 +vn 0.9070 0.1238 0.4024 +vn 0.6039 -0.2529 -0.7559 +vn 0.5057 -0.3385 -0.7935 +vn 0.5385 -0.3115 -0.7829 +vn 0.4463 -0.3839 -0.8083 +vn -0.3366 -0.7377 -0.5852 +vn -0.4077 -0.8086 -0.4242 +vn -0.4195 -0.8187 -0.3921 +vn -0.4723 -0.8545 -0.2164 +vn -0.8598 -0.4925 0.1349 +vn -0.3286 -0.5974 0.7315 +vn -0.3388 -0.6178 0.7096 +vn -0.3271 -0.5945 0.7346 +vn -0.3162 -0.5729 0.7562 +vn 0.3456 -0.3738 0.8607 +vn 0.7128 -0.6494 0.2649 +vn 0.5722 -0.7049 0.4191 +vn 0.7434 -0.6304 0.2236 +vn 0.8310 -0.5509 0.0772 +vn 0.3711 -0.8092 -0.4555 +vn 0.4057 -0.8362 -0.3690 +vn 0.3696 -0.8080 -0.4588 +vn 0.3349 -0.7765 -0.5337 +vn -0.0004 0.9784 -0.2065 +vn 0.0024 0.9789 -0.2044 +vn 0.0083 0.9787 -0.2049 +vn -0.0045 0.9779 -0.2092 +vn 0.0034 0.9778 -0.2093 +vn 0.0037 0.9772 -0.2122 +vn -0.0040 0.9771 -0.2128 +vn 0.1536 -0.9598 0.2350 +vn -0.0790 -0.9937 0.0800 +vn 0.0439 -0.9910 0.1261 +vn 0.2551 -0.1797 -0.9501 +vn 0.2267 -0.1536 -0.9618 +vn 0.3000 -0.2210 -0.9280 +vn -0.9188 -0.0619 -0.3897 +vn -0.9342 -0.0798 -0.3476 +vn -0.9268 -0.0708 -0.3689 +vn -0.9408 -0.0883 -0.3271 +vn -0.6248 0.0904 0.7755 +vn -0.5574 0.0500 0.8287 +vn -0.5855 0.0665 0.8079 +vn -0.5177 0.0274 0.8551 +vn 0.7403 0.2700 0.6157 +vn 0.6034 0.1693 0.7793 +vn 0.6901 0.2312 0.6858 +vn 0.7877 0.3097 0.5325 +vn 0.8867 -0.2752 -0.3715 +vn 0.1737 -0.1052 -0.9792 +vn -0.4598 -0.6361 -0.6196 +vn -0.5953 -0.7983 -0.0914 +vn -0.8241 -0.4267 0.3725 +vn -0.3900 -0.6628 0.6392 +vn 0.1183 -0.3175 0.9409 +vn 0.6032 -0.6525 0.4586 +vn 0.4845 -0.7002 0.5244 +vn 0.6362 -0.6357 0.4372 +vn 0.7458 -0.5650 0.3528 +vn 0.6076 -0.6404 -0.4699 +vn 0.4481 -0.7718 -0.4511 +vn 0.3649 -0.8231 -0.4353 +vn 0.1737 -0.9057 -0.3867 +vn -0.1894 -0.9742 -0.1225 +vn 0.3561 -0.9011 0.2475 +vn 0.0113 0.1818 0.9833 +vn 0.0082 0.1923 0.9813 +vn -0.0043 0.2342 0.9722 +vn -0.0074 0.2446 0.9696 +vn 1.0000 0.0050 -0.0070 +vn 0.7621 -0.6468 0.0280 +vn 0.9989 0.0471 -0.0034 +vn 0.0137 -0.1458 -0.9892 +vn 0.0104 -0.1571 -0.9875 +vn -0.0031 -0.2031 -0.9791 +vn -0.0064 -0.2143 -0.9767 +vn -0.9997 0.0243 -0.0003 +vn -0.9997 0.0250 -0.0003 +vn -0.9998 0.0189 0.0000 +vn -0.9998 0.0181 0.0001 +vn 0.5111 0.7365 0.4431 +vn 0.2154 0.9640 -0.1558 +vn 0.4682 0.8791 -0.0893 +vn 0.2221 0.9628 -0.1537 +vn 0.6349 -0.1672 -0.7543 +vn -0.0486 0.6760 -0.7353 +vn -0.9818 0.0288 -0.1880 +vn -0.7098 0.5373 -0.4555 +vn -0.4587 0.7545 0.4693 +vn -0.5519 0.6680 0.4992 +vn -0.3708 0.8197 0.4366 +vn -0.2328 0.8959 0.3783 +vn -0.5341 0.8318 0.1512 +vn -0.5843 0.8051 0.1019 +vn -0.4515 0.8551 0.2550 +vn -0.4044 0.8786 0.2540 +vn 0.3525 0.7331 0.5817 +vn 0.3192 0.6872 0.6526 +vn 0.3763 0.7644 0.5234 +vn 0.4163 0.8135 0.4062 +vn 0.7823 0.5725 -0.2454 +vn 0.8672 0.4788 -0.1369 +vn 0.6981 0.6365 -0.3280 +vn 0.5614 0.7058 -0.4320 +vn -0.0731 -0.0550 -0.9958 +vn -0.3029 0.7531 -0.5840 +vn -0.6526 0.7552 -0.0620 +vn -0.7183 0.5745 0.3925 +vn -0.6893 0.6105 0.3902 +vn -0.6374 0.6678 0.3844 +vn 0.1662 0.8434 0.5109 +vn 0.3347 0.7307 0.5950 +vn 0.4144 0.6597 0.6270 +vn 0.5037 0.5632 0.6551 +vn 0.6365 0.7637 -0.1080 +vn 0.8000 0.0829 -0.5942 +vn 0.1794 0.6900 -0.7012 +vn -0.6081 0.4964 -0.6196 +vn -0.4757 0.6110 -0.6328 +vn -0.4524 0.6281 -0.6331 +vn -0.3920 0.6690 -0.6315 +vn -0.7372 0.5491 0.3937 +vn 0.7144 0.6910 0.1099 +vn 0.7443 0.6341 0.2094 +vn 0.6976 0.7135 0.0645 +vn 0.6317 0.7711 -0.0798 +vn 0.3856 0.4432 -0.8092 +vn 0.4068 0.6286 -0.6629 +vn 0.4077 0.6454 -0.6459 +vn 0.4085 0.7269 -0.5520 +vn -0.1923 0.6111 0.7678 +vn -0.0931 0.7424 0.6634 +vn -0.0150 0.8237 0.5668 +vn -0.2369 0.5405 0.8073 +vn -0.7588 -0.0733 -0.6471 +vn -0.6504 0.6519 -0.3900 +vn -0.7149 0.1891 0.6732 +vn -0.6030 0.1487 0.7837 +vn -0.6715 0.1732 0.7205 +vn -0.5610 0.1340 0.8169 +vn -0.6580 -0.0733 -0.7495 +vn -0.7895 -0.1263 -0.6006 +vn -0.7186 -0.0968 -0.6886 +vn -0.8374 -0.1483 -0.5260 +vn 0.6254 0.2196 0.7487 +vn 0.7458 0.1346 0.6525 +vn 0.6759 0.1864 0.7130 +vn 0.7874 0.0995 0.6083 +vn 0.7594 -0.0974 -0.6433 +vn 0.6528 -0.1724 -0.7377 +vn 0.7226 -0.1252 -0.6798 +vn 0.6170 -0.1943 -0.7626 +vn 1.0000 -0.0094 -0.0025 +vn 1.0000 -0.0066 -0.0018 +vn 1.0000 -0.0028 -0.0008 +vn 0.0004 0.2102 0.9777 +vn 0.0008 0.2096 0.9778 +vn 0.0012 0.2090 0.9779 +vn 0.0015 0.2083 0.9781 +vn -1.0000 -0.0037 -0.0022 +vn -1.0000 -0.0042 -0.0019 +vn -1.0000 -0.0048 -0.0014 +vn -1.0000 -0.0052 -0.0010 +vn 0.0000 -0.2746 -0.9615 +vn -0.1099 -0.2275 -0.9676 +vn -0.1467 -0.2110 -0.9664 +vn -0.0001 -0.2741 -0.9617 +vn 0.0723 -0.1904 -0.9790 +vn 0.0000 -0.2733 -0.9619 +vn 0.0296 -0.2398 -0.9704 +vn 0.1305 -0.1212 -0.9840 +vn 1.0000 0.0008 -0.0035 +vn 1.0000 0.0063 -0.0022 +vn 0.9990 0.0448 -0.0084 +vn 0.9996 0.0292 -0.0047 +vn -0.0000 0.2333 0.9724 +vn 0.0006 0.2373 0.9714 +vn 0.0022 0.2550 0.9669 +vn 0.0023 0.2383 0.9712 +vn -0.9983 0.0584 -0.0080 +vn -0.9994 0.0334 -0.0022 +vn -1.0000 0.0014 -0.0016 +vn -0.9999 -0.0144 0.0002 +vn -0.3848 -0.0916 -0.9185 +vn 0.1458 -0.3776 -0.9144 +vn 0.1234 -0.3345 -0.9343 +vn 0.0654 -0.2259 -0.9720 +vn 0.8850 -0.4618 -0.0583 +vn 0.9233 -0.3683 -0.1092 +vn 0.9379 -0.3198 -0.1341 +vn 0.6648 -0.7042 0.2494 +vn 0.6653 -0.6914 0.2816 +vn 0.6352 -0.7724 -0.0006 +vn -0.1076 0.1788 0.9780 +vn 0.1902 0.2335 0.9536 +vn 0.0074 0.3153 0.9489 +vn 0.1223 -0.2529 -0.9597 +vn 0.7730 0.5869 -0.2410 +vn 0.7707 0.6127 -0.1749 +vn 0.7672 0.5756 -0.2830 +vn 0.9636 -0.2506 0.0935 +vn 0.9638 -0.2509 0.0902 +vn 0.9655 -0.2530 0.0614 +vn 0.9658 -0.2534 0.0555 +vn 0.9395 0.1392 -0.3129 +vn 0.5317 -0.0584 -0.8449 +vn 0.7777 0.6186 -0.1121 +vn 0.5837 -0.7683 -0.2628 +vn 0.6226 -0.7696 0.1419 +vn 0.6116 -0.7799 -0.1334 +vn 0.9333 -0.3327 -0.1351 +vn 0.9565 0.1476 -0.2518 +vn 0.8514 0.0509 0.5221 +vn 0.9979 0.0643 0.0099 +vn 0.9171 0.1640 -0.3634 +vn 0.8519 0.4999 -0.1563 +vn 0.9286 0.3538 -0.1120 +vn 0.7797 0.5763 0.2451 +vn 0.5302 -0.0352 -0.8471 +vn 0.7912 0.5877 -0.1690 +vn 0.0483 -0.2892 -0.9561 +vn 0.0380 -0.2258 -0.9734 +vn 0.0410 -0.2938 -0.9550 +vn 0.0491 -0.2181 -0.9747 +vn 0.0697 -0.2212 -0.9727 +vn 0.7986 0.5996 -0.0521 +vn 0.7980 0.6023 -0.0190 +vn 0.8681 0.4959 0.0207 +vn 0.9151 -0.2085 0.3451 +vn 0.9555 -0.2153 -0.2014 +vn 0.9420 0.3354 -0.0130 +vn 0.9576 0.1976 0.2098 +vn 0.7994 0.5964 -0.0728 +vn 0.0431 -0.2086 -0.9771 +vn 0.0308 -0.2088 -0.9775 +vn 0.9371 -0.2715 -0.2192 +vn 0.7967 0.3622 -0.4839 +vn 0.9929 0.1188 0.0064 +vn 0.7523 0.3310 -0.5696 +vn 0.0308 -0.1982 -0.9797 +vn 0.0350 -0.1995 -0.9793 +vn 0.2416 -0.4791 -0.8438 +vn 0.9561 -0.2346 -0.1756 +vn 0.9085 0.0059 0.4179 +vn 0.8200 0.3265 -0.4702 +vn 0.0546 -0.2009 -0.9781 +vn 0.1485 0.0010 -0.9889 +vn 0.7158 -0.6960 -0.0558 +vn 0.1446 -0.3512 -0.9251 +vn 0.9524 -0.2845 0.1099 +vn 0.9515 -0.2843 0.1178 +vn 0.9976 -0.0694 -0.0024 +vn 0.9812 -0.1700 0.0909 +vn 0.9983 0.0509 -0.0274 +vn 0.9986 0.0515 -0.0137 +vn 0.8295 0.4044 -0.3853 +vn 0.0974 -0.1413 -0.9852 +vn -0.3496 -0.1509 -0.9247 +vn -0.2020 -0.1772 -0.9632 +vn 0.0781 -0.2138 -0.9738 +vn 0.9805 -0.1885 0.0560 +vn 0.9776 -0.1841 0.1018 +vn 0.9068 -0.1452 0.3957 +vn 0.8429 -0.1217 0.5242 +vn 0.5248 -0.0664 -0.8486 +vn 0.8414 0.0652 -0.5364 +vn 0.7368 0.0141 -0.6760 +vn 0.8543 0.4558 0.2497 +vn 0.4847 -0.0795 -0.8711 +vn 0.7861 0.5915 -0.1793 +vn 0.7829 0.5275 -0.3298 +vn 0.7784 0.5663 -0.2709 +vn 0.0546 -0.2711 -0.9610 +vn 0.0362 -0.2247 -0.9738 +vn 0.0607 -0.2864 -0.9562 +vn 0.0327 -0.2157 -0.9759 +vn 0.7792 0.6261 0.0297 +vn 0.7791 0.6268 0.0150 +vn 0.8713 0.4724 0.1333 +vn 0.9786 -0.0728 0.1923 +vn 0.9747 -0.0708 0.2122 +vn 0.9796 -0.0733 0.1871 +vn 0.9409 0.1730 -0.2912 +vn 0.2248 -0.0111 -0.9743 +vn 0.0617 -0.1755 -0.9825 +vn 0.0538 -0.1832 -0.9816 +vn 0.2443 0.0094 -0.9697 +vn 0.0385 -0.2230 -0.9740 +vn -0.7216 -0.3132 0.6174 +vn -0.2581 -0.5363 -0.8036 +vn -0.5563 0.1094 0.8237 +vn -0.4820 0.0073 -0.8761 +vn 0.7885 0.5567 0.2615 +vn 0.6147 -0.4480 0.6492 +vn -0.7973 -0.5364 0.2768 +vn -0.8260 -0.4316 0.3625 +vn -0.8397 -0.2849 0.4623 +vn -0.8371 -0.2139 0.5035 +vn -0.4673 -0.2243 -0.8552 +vn -0.6069 0.5330 0.5896 +vn -0.5979 0.4542 0.6605 +vn -0.6002 0.6979 0.3907 +vn 0.7664 0.4600 -0.4484 +vn 0.7699 0.5392 -0.3414 +vn 0.6340 -0.7344 0.2422 +vn 0.6349 -0.7316 0.2483 +vn 0.6292 -0.7478 0.2118 +vn -0.8895 -0.4412 0.1187 +vn -0.4015 -0.2753 -0.8735 +vn -0.4756 0.3611 0.8021 +vn 0.8331 0.0510 0.5508 +vn 0.7650 0.5640 0.3111 +vn 0.6476 -0.6807 0.3424 +vn 0.7623 -0.6165 0.1969 +vn 0.6470 -0.6857 0.3335 +vn -0.6291 -0.3310 0.7033 +vn -0.5402 -0.3845 -0.7485 +vn -0.4979 0.3315 0.8014 +vn -0.2743 0.3342 0.9017 +vn -0.0722 0.3208 0.9444 +vn -0.0328 0.3167 0.9480 +vn -0.3843 -0.1440 -0.9119 +vn 0.9824 0.1612 0.0944 +vn 0.8031 0.5823 0.1262 +vn 0.8523 0.4687 0.2323 +vn -0.7344 -0.5408 0.4102 +vn -0.6130 -0.1628 0.7732 +vn -0.6018 -0.2115 -0.7702 +vn -0.4509 0.3884 0.8037 +vn 0.9742 -0.0705 0.2145 +vn 0.8183 0.5744 -0.0206 +vn 0.8913 0.3988 0.2158 +vn 0.5750 -0.6703 -0.4691 +vn -0.8602 -0.4763 0.1821 +vn 0.8633 0.4441 -0.2396 +vn -0.2095 0.2253 0.9515 +vn -0.3285 0.1916 0.9249 +vn -0.5921 0.0982 0.7998 +vn -0.6431 0.0762 0.7620 +vn 0.8265 0.0441 0.5612 +vn 0.6553 -0.6720 0.3449 +vn -0.5147 0.5059 -0.6922 +vn -0.7649 -0.6255 0.1537 +vn -0.8040 -0.1640 0.5716 +vn -0.5036 -0.1981 -0.8409 +vn -0.8996 0.1624 -0.4053 +vn 0.7628 0.6108 -0.2123 +vn 0.2411 0.1235 0.9626 +vn 0.1385 0.0933 0.9860 +vn 0.0690 0.2186 0.9734 +vn 0.9188 0.3319 0.2139 +vn 0.6187 -0.7745 0.1316 +vn 0.6363 -0.7389 0.2215 +vn -0.9233 -0.3841 -0.0022 +vn 0.2973 -0.2869 -0.9106 +vn -0.2951 0.2875 0.9112 +vn -0.4278 0.2768 0.8605 +vn -0.5507 0.2606 0.7930 +vn -0.5850 0.2548 0.7700 +vn -0.5475 0.7901 0.2757 +vn 0.9516 0.1964 0.2362 +vn 0.6171 -0.7779 0.1187 +vn 0.6065 -0.7917 0.0738 +vn 0.7595 -0.6259 0.1773 +vn -0.9979 -0.0217 0.0609 +vn 0.0099 -0.2093 -0.9778 +vn 0.2114 -0.2164 -0.9531 +vn -0.0723 -0.1535 -0.9855 +vn 0.1379 0.1919 0.9717 +vn 0.0069 0.2063 0.9785 +vn -0.0844 0.2768 0.9572 +vn 0.9829 0.1482 -0.1094 +vn 0.1751 -0.2894 -0.9411 +vn 0.9978 0.0370 -0.0558 +vn 0.4198 0.3698 0.8289 +vn 0.5947 -0.7708 0.2285 +vn -0.7101 0.7033 -0.0352 +vn 0.0488 0.1864 0.9813 +vn 0.6281 -0.7506 0.2051 +vn -0.5802 0.7671 0.2736 +vn 0.0023 0.2122 0.9772 +vn 0.6705 -0.7019 0.2402 +vn -0.6078 0.7535 0.2505 +vn 0.0142 0.2087 0.9779 +vn 0.3449 -0.2924 0.8919 +vn 0.6289 -0.7714 0.0978 +vn 0.5070 -0.4624 -0.7274 +vn -0.6131 0.6866 -0.3908 +vn -0.0150 0.2069 0.9782 +vn 0.6242 -0.7797 -0.0503 +vn -0.6763 0.7209 0.1511 +vn 0.0234 0.2113 0.9771 +vn 0.6681 -0.6770 -0.3087 +vn 0.2962 -0.5865 -0.7538 +vn -0.7240 0.6887 0.0402 +vn -0.7547 0.6432 -0.1293 +vn 0.0979 0.0864 0.9914 +vn 0.0615 0.2213 0.9733 +vn 0.8748 -0.4445 0.1926 +vn 0.0375 0.2136 0.9762 +vn 0.0527 0.9708 -0.2339 +vn -0.0348 0.9760 -0.2148 +vn -0.0080 0.9729 -0.2310 +vn -0.0207 0.9692 -0.2456 +vn 0.0957 0.9798 -0.1754 +vn 0.0068 0.9826 -0.1855 +vn -0.0395 0.9781 -0.2045 +vn -0.0200 0.9835 -0.1798 +vn -0.0172 -0.2091 -0.9777 +vn 0.0057 -0.2103 -0.9776 +vn -0.8991 0.4281 -0.0910 +vn -0.8874 0.3653 0.2812 +vn -0.9511 0.2515 0.1792 +vn -0.9888 0.1469 0.0279 +vn -0.9968 0.0708 -0.0371 +vn -0.0520 0.2306 0.9716 +vn -0.0091 0.2042 0.9789 +vn 0.9998 0.0091 -0.0158 +vn 0.9993 0.0349 0.0100 +vn 0.9999 0.0094 0.0136 +vn 0.9996 -0.0287 -0.0040 +vn 0.9944 -0.0197 0.1035 +vn 0.9649 -0.1912 0.1799 +vn 0.9425 -0.2413 0.2310 +vn 0.9983 0.0034 0.0574 +vn 0.9709 0.0506 0.2341 +vn 0.9992 0.0053 -0.0408 +vn 0.9993 0.0168 -0.0345 +vn 0.9892 -0.1458 0.0175 +vn 0.9394 -0.3295 0.0947 +vn 0.9964 -0.0847 0.0089 +vn 0.8779 -0.4527 0.1562 +vn 0.9968 -0.0802 -0.0050 +vn 0.9998 0.0083 0.0198 +vn 0.4886 0.2864 0.8242 +vn 0.6935 -0.1469 -0.7053 +vn 0.7949 -0.5662 0.2182 +vn 0.9950 0.0270 0.0959 +vn 0.9994 0.0340 0.0038 +vn 1.0000 0.0022 -0.0035 +vn 0.9978 0.0427 0.0506 +vn 0.9451 -0.0887 -0.3144 +vn -0.2198 0.2039 0.9540 +vn 0.9973 -0.0114 -0.0719 +vn 0.9998 0.0029 -0.0220 +vn 0.9976 -0.0102 -0.0679 +vn 0.9928 -0.0989 -0.0673 +vn 0.9763 -0.1310 -0.1724 +vn 0.9942 -0.0680 -0.0830 +vn 0.9968 -0.0797 -0.0034 +vn 0.8800 0.1164 0.4606 +vn 0.9992 0.0149 0.0359 +vn 0.9987 0.0075 -0.0503 +vn 0.9989 0.0078 -0.0470 +vn 0.9862 -0.1551 0.0572 +vn 0.7867 0.1576 0.5969 +vn 0.1736 -0.1247 -0.9769 +vn -0.3787 0.1215 0.9175 +vn 0.9982 0.0168 0.0574 +vn 0.9861 -0.0168 0.1654 +vn 0.9842 -0.0571 -0.1677 +vn 0.2185 0.3112 0.9249 +vn 0.3184 -0.2265 -0.9205 +vn 0.3776 -0.0460 0.9248 +vn 0.9992 0.0189 0.0338 +vn 0.9919 0.0666 -0.1078 +vn 0.9448 -0.1000 -0.3120 +vn 0.8546 -0.4540 0.2520 +vn 0.9078 -0.4068 0.1015 +vn 0.9805 0.0450 0.1912 +vn 0.9819 0.0435 0.1842 +vn 0.9953 0.0247 0.0937 +vn 0.9958 0.0237 0.0887 +vn 0.5695 0.2716 0.7759 +vn 0.6945 -0.1572 -0.7021 +vn 0.7905 -0.5286 0.3092 +vn 0.9999 0.0052 0.0105 +vn 0.9438 -0.2536 0.2118 +vn 0.8295 -0.5385 0.1477 +vn 0.9995 -0.0249 -0.0182 +vn 0.9947 0.0107 0.1022 +vn 0.9993 0.0161 0.0343 +vn 0.9992 -0.0182 -0.0362 +vn 0.6464 0.2475 0.7218 +vn 0.0191 -0.2804 -0.9597 +vn 0.9931 0.0937 -0.0705 +vn 0.9691 -0.1786 0.1704 +vn 0.5851 -0.7650 -0.2690 +vn 0.9999 -0.0027 0.0097 +vn 0.9996 -0.0265 -0.0043 +vn 0.9989 -0.0288 -0.0363 +vn 0.7485 -0.3791 0.5441 +vn 0.9992 -0.0035 0.0390 +vn 0.9988 0.0244 0.0429 +vn 0.9999 -0.0038 -0.0163 +vn 0.0000 0.9470 0.3211 +vn 0.3688 0.9072 -0.2022 +vn 0.4212 0.8674 -0.2649 +vn 0.4327 0.8573 -0.2789 +vn -0.1450 0.7341 -0.6634 +vn 0.2400 0.9689 -0.0606 +vn 0.5550 0.7565 0.3459 +vn -0.0881 0.9850 -0.1485 +vn 0.7972 0.1570 -0.5830 +vn 0.4573 0.8338 -0.3092 +vn -0.9721 0.2323 0.0333 +vn -0.9774 0.2087 0.0337 +vn -0.9374 0.3483 0.0057 +vn -0.9426 -0.0497 -0.3302 +vn 0.5441 0.8208 -0.1740 +vn 0.5446 0.8205 -0.1739 +vn 0.7515 0.6453 -0.1376 +vn 0.8300 0.5453 -0.1169 +vn -0.0000 0.2079 0.9781 +vn -0.1124 0.0974 0.9889 +vn -0.3651 -0.1633 0.9165 +vn -0.0625 0.1553 0.9859 +vn -0.5247 -0.2724 0.8065 +vn 0.3801 0.1896 0.9053 +vn 0.1241 0.3304 0.9357 +vn -0.0253 0.3290 0.9440 +vn -0.4363 -0.3023 0.8475 +vn -0.1714 0.2306 0.9578 +vn -0.9860 0.1651 -0.0238 +vn -0.9875 0.1553 -0.0255 +vn -0.1472 -0.0866 -0.9853 +vn 0.0000 0.9782 -0.2079 +vn -0.0001 0.9782 -0.2079 +vn -0.2520 0.9405 -0.2279 +vn -0.1658 0.9607 -0.2226 +vn -0.4097 0.8820 -0.2329 +vn -0.1416 0.3708 0.9179 +vn -0.8281 -0.0864 0.5539 +vn -0.8632 -0.2015 -0.4630 +vn -0.8579 -0.4269 -0.2859 +vn -0.8738 -0.3912 -0.2889 +vn -0.9846 0.1733 -0.0233 +vn -0.9873 0.1584 -0.0144 +vn -0.0897 -0.2179 -0.9718 +vn -0.0153 -0.2449 -0.9694 +vn -0.2485 -0.1986 -0.9480 +vn -0.0245 -0.0932 -0.9953 +vn 0.1300 -0.2449 -0.9608 +vn 0.1197 -0.0841 -0.9892 +vn 0.1264 -0.2822 -0.9510 +vn 0.0002 -0.2079 -0.9782 +vn 0.0000 -0.2074 -0.9783 +vn 0.9949 0.0987 -0.0224 +vn 0.9939 0.1071 -0.0261 +vn 0.9947 0.1000 -0.0229 +vn 0.9938 0.1083 -0.0267 +vn -0.0268 0.9802 -0.1964 +vn -0.0171 0.9850 -0.1719 +vn -0.0308 0.9741 -0.2238 +vn 0.1032 0.9641 -0.2447 +vn -0.8819 -0.4610 0.0988 +vn 0.1901 0.9702 -0.1503 +vn -0.0214 0.9689 -0.2464 +vn -0.9748 0.2232 0.0019 +vn -0.2630 0.4731 0.8409 +vn -0.8791 -0.1524 -0.4516 +vn -0.9992 -0.0384 0.0093 +vn -0.9993 -0.0182 0.0314 +vn -0.9968 0.0612 0.0512 +vn -0.9950 0.0717 0.0700 +vn -0.9833 0.1806 0.0224 +vn -0.8363 -0.5441 -0.0676 +vn -0.3022 0.0841 -0.9495 +vn -0.9618 0.2503 -0.1112 +vn 0.0063 0.8378 0.5459 +vn 0.0140 0.4803 -0.8770 +vn 0.6950 0.7038 -0.1471 +vn 0.6497 0.7434 -0.1585 +vn 0.6940 0.7047 -0.1474 +vn 0.6476 0.7452 -0.1590 +vn -0.0066 0.2175 0.9760 +vn -0.0140 0.2242 0.9744 +vn -0.0058 0.2168 0.9762 +vn -0.0008 -0.1988 -0.9800 +vn 0.0014 -0.1969 -0.9804 +vn -0.0010 -0.1990 -0.9800 +vn 0.0017 0.2100 0.9777 +vn -1.0000 0.0027 0.0020 +vn -1.0000 0.0000 0.0004 +vn -1.0000 0.0002 0.0004 +vn -1.0000 -0.0025 -0.0012 +vn -0.0032 -0.2009 -0.9796 +vn 1.0000 -0.0012 -0.0008 +vn 1.0000 -0.0025 0.0010 +vn 1.0000 -0.0024 0.0009 +vn 1.0000 -0.0037 0.0027 +vn -0.0323 0.9773 -0.2092 +vn -0.0030 0.9753 -0.2206 +vn -0.0378 0.9774 -0.2080 +vn -0.0002 0.9737 -0.2279 +vn 0.9639 -0.0388 0.2634 +vn 0.9921 -0.1251 -0.0039 +vn 0.9838 -0.1319 0.1214 +vn 0.9846 -0.1742 -0.0163 +vn 0.9670 -0.2251 0.1196 +vn 0.9646 -0.2458 0.0959 +vn 0.9867 -0.1570 0.0416 +vn 0.9566 -0.2278 0.1816 +vn 0.9543 -0.2691 0.1304 +vn 0.9842 -0.1441 0.1032 +vn 0.9583 -0.2215 0.1806 +vn 0.9582 -0.2018 0.2026 +vn 0.9901 -0.0888 0.1089 +vn 0.0670 0.9698 -0.2345 +vn 0.2138 0.9546 -0.2073 +vn 0.0820 0.9693 -0.2320 +vn 0.2276 0.9520 -0.2045 +vn 0.9232 0.3762 -0.0784 +vn 0.9870 0.1570 -0.0332 +vn 0.8268 0.5513 -0.1118 +vn 0.9853 -0.1381 0.1008 +vn 0.9582 -0.2005 0.2040 +vn 0.9915 -0.0788 0.1032 +vn 0.9519 -0.1605 0.2610 +vn 0.9902 -0.1328 0.0426 +vn 0.9566 -0.2313 0.1773 +vn 0.9844 0.0519 0.1679 +vn 0.9906 -0.1355 -0.0206 +vn 0.9870 -0.1221 0.1046 +vn 0.9916 -0.1091 0.0698 +vn 0.9938 -0.1043 -0.0388 +vn 0.9875 -0.1575 -0.0020 +vn 0.0498 0.9700 -0.2378 +vn 0.2223 0.9530 -0.2059 +vn 0.0677 0.9697 -0.2349 +vn 0.2385 0.9498 -0.2025 +vn 0.8904 -0.4515 0.0583 +vn 0.9215 -0.3884 0.0011 +vn 0.9449 -0.3226 -0.0557 +vn -0.9902 0.1381 -0.0198 +vn -0.9986 0.0530 -0.0064 +vn -0.9957 0.0909 -0.0192 +vn -0.9957 0.0908 -0.0192 +vn -0.7068 -0.6795 0.1968 +vn -0.9418 -0.3148 0.1182 +vn -0.8887 -0.4532 0.0692 +vn -0.7829 -0.6222 0.0005 +vn -0.9687 -0.1917 0.1574 +vn 0.8287 0.5231 -0.1989 +vn 0.9251 0.2819 -0.2544 +vn 0.8982 0.3704 -0.2367 +vn 0.7763 0.6059 -0.1739 +vn -0.8635 0.4274 -0.2677 +vn -0.8216 0.5609 -0.1021 +vn -0.8510 0.5227 -0.0505 +vn -0.8626 0.5051 -0.0277 +vn -0.8841 0.4668 0.0199 +vn 0.8976 0.4305 -0.0947 +vn 0.7245 0.6892 -0.0072 +vn 0.7982 0.6011 -0.0400 +vn 0.9348 0.3336 -0.1219 +vn 0.9293 0.3643 0.0606 +vn 0.4136 0.7421 0.5275 +vn -0.5552 -0.7888 0.2639 +vn -0.0115 -0.3914 -0.9202 +vn -0.0217 -0.5575 -0.8299 +vn -0.0115 -0.3917 -0.9200 +vn -0.0007 -0.2077 -0.9782 +vn -0.6787 0.1559 -0.7176 +vn 0.6095 0.7898 -0.0692 +vn 0.6184 0.7820 -0.0777 +vn 0.6214 0.7794 -0.0805 +vn 0.6288 0.7726 -0.0877 +vn -0.5486 -0.7935 0.2633 +vn -0.6090 -0.7608 0.2243 +vn -0.6675 -0.7219 0.1824 +vn -0.0007 -0.2085 -0.9780 +vn -0.0007 -0.2091 -0.9779 +vn -0.0007 -0.2082 -0.9781 +vn -0.8964 0.3494 -0.2729 +vn 0.6660 0.6894 -0.2849 +vn -0.7882 -0.6154 0.0002 +vn -0.6972 -0.7108 0.0930 +vn -0.6522 -0.7464 0.1325 +vn -0.6130 -0.7728 0.1643 +vn -0.9407 0.2893 -0.1774 +vn -0.9249 0.3212 -0.2035 +vn -0.9024 0.2873 -0.3212 +vn 0.4811 0.8663 -0.1348 +vn -0.2193 -0.9484 -0.2289 +vn -0.2584 -0.9440 -0.2054 +vn -0.0488 -0.9452 -0.3227 +vn -0.0007 -0.2078 -0.9782 +vn -0.8963 0.3496 -0.2727 +vn 0.3879 0.0124 0.9216 +vn -0.0946 0.2179 0.9714 +vn -0.0972 0.2167 0.9714 +vn -0.1084 0.2118 0.9713 +vn -0.1134 0.2096 0.9712 +vn 0.1748 -0.1759 -0.9688 +vn 0.1956 -0.1709 -0.9657 +vn 0.0735 -0.1984 -0.9774 +vn 0.0559 -0.2020 -0.9778 +vn -0.9667 0.2530 0.0397 +vn -0.9623 0.2184 0.1619 +vn -0.9666 0.2374 0.0966 +vn -0.9593 0.2104 0.1882 +vn -0.9464 0.3076 -0.0985 +vn -0.9626 0.2669 0.0457 +vn -0.5939 0.4198 0.6863 +vn 0.6431 -0.1352 0.7537 +vn -0.9475 0.2745 0.1641 +vn -0.9505 0.2981 0.0879 +vn -0.9496 0.2856 0.1289 +vn -0.9502 0.3053 0.0630 +vn -0.9505 0.3002 0.0806 +vn -0.9499 0.2874 0.1232 +vn -0.9498 0.3082 0.0528 +vn -0.8904 -0.4362 0.1303 +vn -0.9216 -0.3550 0.1571 +vn -0.9450 -0.2715 0.1823 +vn 0.9974 0.0722 -0.0042 +vn 0.9847 0.1728 -0.0223 +vn -0.9473 0.3041 -0.1011 +vn -0.9922 0.0971 -0.0785 +vn -0.9734 0.0425 -0.2252 +vn -0.8929 0.4110 -0.1839 +vn -0.6443 0.6887 -0.3325 +vn -0.9653 0.2559 0.0516 +vn 0.6686 0.7399 -0.0749 +vn 0.9129 0.3813 -0.1455 +vn 0.9719 0.2129 -0.1002 +vn 0.9249 0.3307 -0.1877 +vn -0.7372 -0.6755 0.0172 +vn -0.8588 -0.5023 -0.1010 +vn -0.8685 -0.4827 -0.1129 +vn -0.8904 -0.4324 -0.1423 +vn -0.9609 0.2750 -0.0309 +vn -0.9261 0.3238 -0.1935 +vn -0.9191 0.3106 -0.2423 +vn -0.8859 -0.4300 0.1741 +vn 0.8024 -0.5901 -0.0895 +vn 0.0078 -0.2103 -0.9776 +vn -0.9173 0.2655 -0.2968 +vn 0.4794 0.8673 -0.1339 +vn -0.3603 -0.9328 -0.0094 +vn -0.1981 -0.1169 -0.9732 +vn 0.9273 0.3695 0.0593 +vn 0.8601 0.4799 0.1728 +vn 0.8494 0.4934 0.1874 +vn 0.7818 0.5637 0.2666 +vn -0.5296 -0.8070 0.2614 +vn -0.0116 -0.3926 -0.9196 +vn -0.0218 -0.5593 -0.8287 +vn -0.0116 -0.3923 -0.9198 +vn -0.6734 0.1523 -0.7234 +vn 0.2378 0.1957 0.9514 +vn 0.2489 0.1914 0.9494 +vn 0.1494 0.1804 0.9722 +vn -0.0086 0.0936 0.9956 +vn -0.1212 0.0258 0.9923 +vn 0.9759 0.1844 -0.1169 +vn 0.9748 0.2215 -0.0257 +vn 0.1602 -0.1758 -0.9713 +vn 0.1789 -0.1714 -0.9688 +vn 0.0724 -0.1955 -0.9780 +vn 0.0568 -0.1989 -0.9784 +vn -0.9177 0.1666 0.3607 +vn -0.9615 0.2450 0.1242 +vn -0.9433 0.2007 0.2645 +vn -0.9628 0.2647 0.0546 +vn -0.9541 0.2854 -0.0912 +vn -0.9654 0.2604 0.0113 +vn -0.9612 0.2731 -0.0393 +vn -0.9668 0.2520 0.0432 +vn -0.9570 0.2886 -0.0285 +vn -0.9535 0.2108 0.2154 +vn -0.5048 0.3960 0.7671 +vn 0.7561 -0.2162 0.6178 +vn 0.7887 -0.1237 0.6022 +vn 0.8214 0.0079 0.5703 +vn 0.9917 0.1279 -0.0103 +vn 0.9101 0.4143 -0.0012 +vn 0.9230 0.3844 0.0154 +vn 0.9377 0.2685 -0.2205 +vn 0.8541 -0.5078 0.1121 +vn 0.9696 -0.2163 0.1143 +vn 0.8515 -0.5239 0.0199 +vn 0.9971 -0.0736 0.0212 +vn 0.9905 0.1300 -0.0438 +vn 0.9389 0.3240 -0.1162 +vn 0.8661 0.4776 -0.1472 +vn 0.8749 0.4651 -0.1349 +vn 0.9317 0.3104 -0.1885 +vn 0.9913 0.1004 -0.0855 +vn 0.8803 0.4581 -0.1229 +vn 0.9877 0.1547 -0.0221 +vn 0.0013 -0.1148 -0.9934 +vn 0.0015 -0.1156 -0.9933 +vn 0.0020 -0.1166 -0.9932 +vn 0.0006 -0.1160 -0.9932 +vn 0.0004 -0.1158 -0.9933 +vn 0.0051 0.3007 0.9537 +vn 0.0803 0.3296 0.9407 +vn 0.1141 0.3420 0.9327 +vn 0.1159 0.3426 0.9323 +vn 0.8844 -0.4653 0.0369 +vn 0.8953 -0.4300 0.1163 +vn 0.8717 -0.4656 0.1532 +vn 0.8848 -0.4466 0.1333 +vn 0.8535 -0.4895 0.1786 +vn 0.9966 0.0409 0.0717 +vn 1.0000 -0.0037 0.0044 +vn 0.9999 -0.0129 0.0115 +vn 0.9997 -0.0245 -0.0038 +vn 1.0000 -0.0040 -0.0037 +vn 0.9997 -0.0099 -0.0234 +vn 0.9940 -0.0284 -0.1055 +vn 0.9223 0.2565 -0.2890 +vn 0.9357 0.0825 0.3430 +vn 0.7807 -0.6193 0.0836 +vn -0.3583 -0.9228 -0.1418 +vn 0.2715 -0.6238 0.7329 +vn 0.9685 0.2424 -0.0578 +vn 0.4000 -0.8974 -0.1864 +vn -0.6956 -0.7002 0.1606 +vn 0.7976 0.5691 -0.1998 +vn 0.9999 0.0124 -0.0018 +vn 1.0000 0.0086 -0.0030 +vn 0.9999 0.0099 -0.0026 +vn 0.9999 0.0133 -0.0015 +vn 0.4059 -0.6348 0.6574 +vn 0.8733 -0.1355 -0.4680 +vn 0.9233 -0.1053 -0.3693 +vn -1.0000 0.0077 -0.0025 +vn -1.0000 0.0070 -0.0017 +vn -1.0000 0.0066 -0.0013 +vn -1.0000 0.0059 -0.0004 +vn 0.0114 0.2680 0.9634 +vn 0.0123 0.3848 0.9229 +vn 0.0617 0.5030 0.8621 +vn 0.1126 0.4703 0.8753 +vn 0.0234 -0.6951 -0.7185 +vn 0.0543 -0.5690 -0.8205 +vn -0.0152 -0.8234 -0.5673 +vn -0.8539 -0.5099 0.1040 +vn -0.8605 0.5056 -0.0630 +vn -0.8668 0.4940 -0.0674 +vn -0.8641 0.4991 -0.0655 +vn -0.8695 0.4890 -0.0693 +vn -0.9698 -0.2431 -0.0186 +vn -0.8538 -0.4830 0.1944 +vn -0.9972 -0.0740 0.0124 +vn -0.9315 0.3610 0.0454 +vn -0.9905 0.1346 0.0297 +vn -0.8801 0.4690 -0.0741 +vn -0.9892 0.1418 -0.0359 +vn 0.9826 -0.1177 0.1440 +vn 0.9930 -0.0911 0.0755 +vn 0.9997 -0.0229 0.0102 +vn -0.0006 0.2985 0.9544 +vn -0.0003 0.2984 0.9545 +vn -0.0055 0.3004 0.9538 +vn -0.0069 0.3009 0.9536 +vn 0.0012 -0.1154 -0.9933 +vn 0.0017 -0.1150 -0.9934 +vn 0.9996 -0.0283 -0.0040 +vn 0.9993 -0.0021 -0.0374 +vn 0.9729 -0.1968 -0.1213 +vn -0.0031 0.2979 0.9546 +vn -0.0003 0.2988 0.9543 +vn -0.0039 0.2975 0.9547 +vn 0.0007 0.2978 0.9546 +vn 0.0005 0.2980 0.9546 +vn -0.9316 -0.3296 0.1531 +vn -0.2773 -0.9549 -0.1062 +vn -0.2641 -0.9288 -0.2599 +vn -0.2680 -0.9374 -0.2223 +vn -0.9127 -0.3842 0.1392 +vn -0.9014 -0.4126 0.1316 +vn -0.9066 -0.3999 0.1350 +vn -0.8959 -0.4255 0.1280 +vn -0.4170 0.0560 0.9072 +vn -0.8897 -0.4427 -0.1114 +vn -0.6954 0.7031 -0.1486 +vn 0.8866 0.4513 -0.1015 +vn 0.8980 0.4301 -0.0929 +vn 0.8878 0.4490 -0.1006 +vn 0.8993 0.4275 -0.0918 +vn 1.0000 0.0029 -0.0050 +vn 0.9972 0.0016 0.0754 +vn 0.9995 -0.0168 0.0284 +vn 0.9884 -0.1519 0.0018 +vn 0.9974 -0.0702 0.0143 +vn 0.9447 -0.2694 -0.1869 +vn 0.9969 -0.0725 0.0315 +vn 0.9848 -0.1733 0.0125 +vn 0.9927 -0.0874 -0.0826 +vn 1.0000 -0.0028 -0.0026 +vn 0.9997 -0.0075 -0.0237 +vn 0.9933 -0.0276 -0.1120 +vn 0.8259 0.0334 0.5629 +vn 0.9866 0.0226 0.1618 +vn 0.9235 -0.3816 -0.0395 +vn 0.7823 -0.5560 -0.2808 +vn 0.9562 0.2915 -0.0277 +vn -0.6637 -0.6822 0.3067 +vn 0.7160 0.6378 -0.2836 +vn 0.6015 -0.6273 0.4947 +vn 0.8722 -0.1332 -0.4707 +vn 0.9220 -0.1030 -0.3731 +vn -0.9995 -0.0179 0.0267 +vn -0.9570 -0.1103 0.2684 +vn -0.9974 -0.0374 0.0614 +vn -0.9325 -0.0670 -0.3550 +vn -0.9627 -0.0010 -0.2705 +vn -0.7569 0.5969 0.2661 +vn -0.9993 -0.0054 -0.0357 +vn -0.9780 0.1525 -0.1424 +vn -0.9901 0.1177 -0.0762 +vn -0.9428 0.2080 -0.2605 +vn -0.9392 0.0813 0.3337 +vn -0.9976 -0.0611 -0.0338 +vn -0.9741 -0.1745 -0.1438 +vn -0.9983 0.0539 -0.0225 +vn -0.0012 -0.1217 -0.9926 +vn -0.9345 0.3559 -0.0019 +vn -0.8314 0.5413 -0.1252 +vn -0.8793 0.4701 -0.0761 +vn -0.9564 0.2893 0.0392 +vn -0.0007 0.2923 0.9563 +vn -0.0007 0.2925 0.9563 +vn -0.0008 0.2923 0.9563 +vn -0.0013 0.2917 0.9565 +vn -0.0014 0.2916 0.9565 +vn -0.9303 0.3667 -0.0085 +vn -0.7487 0.6341 -0.1935 +vn -0.8319 0.5407 -0.1248 +vn -0.9561 0.2903 0.0389 +vn 0.0008 0.2928 0.9562 +vn 0.0007 0.2920 0.9564 +vn 0.0008 0.2927 0.9562 +vn 0.0009 0.2935 0.9559 +vn 0.0007 -0.1207 -0.9927 +vn -0.8989 -0.4365 0.0388 +vn -0.8734 -0.4867 0.0188 +vn -0.8876 -0.4597 0.0296 +vn -0.8632 -0.5048 0.0114 +vn -0.9398 -0.3211 0.1166 +vn -0.9030 -0.4200 0.0906 +vn -0.9240 -0.3677 0.1047 +vn -0.8823 -0.4642 0.0781 +vn -0.8905 -0.3953 0.2254 +vn -0.9748 -0.1410 0.1730 +vn -0.9816 -0.0996 0.1628 +vn 0.3377 0.5582 0.7579 +vn -0.9968 -0.0735 -0.0322 +vn -0.9696 -0.2042 -0.1346 +vn -0.9994 -0.0047 -0.0344 +vn -0.9997 -0.0199 -0.0146 +vn -0.9832 0.0203 -0.1814 +vn -0.9853 0.0518 -0.1630 +vn -0.9953 0.0223 -0.0943 +vn -0.8611 -0.4479 0.2408 +vn -0.8466 -0.4710 0.2481 +vn -0.9712 0.2232 -0.0836 +vn -0.9854 -0.1474 0.0854 +vn -0.9998 0.0144 0.0134 +vn -0.9995 -0.0050 0.0301 +vn -0.9962 0.0840 -0.0239 +vn -0.9998 -0.0006 -0.0177 +vn -0.6474 -0.7248 -0.2357 +vn -0.8834 0.4677 -0.0287 +vn -0.9972 0.0741 -0.0080 +vn -0.9999 0.0059 0.0121 +vn -0.9996 0.0115 0.0265 +vn 0.0160 0.9752 -0.2210 +vn -0.0088 0.9774 -0.2110 +vn 0.0051 0.9715 -0.2371 +vn -0.0171 0.9818 -0.1894 +vn 0.0097 0.9828 -0.1846 +vn 0.0194 0.9813 -0.1916 +vn -0.0123 0.9792 -0.2025 +vn -0.0512 0.9634 -0.2631 +vn 0.8173 0.0900 0.5692 +vn 0.8225 0.2266 0.5217 +vn 0.8219 0.2425 0.5154 +vn -0.9961 -0.0867 0.0166 +vn 0.0722 -0.4856 -0.8712 +vn 0.8796 0.4600 -0.1214 +vn 0.9567 0.2472 -0.1535 +vn 0.9348 0.3252 -0.1429 +vn 0.8315 0.5454 -0.1054 +vn 0.0025 -0.1227 -0.9924 +vn 0.0023 -0.1213 -0.9926 +vn 0.0022 -0.1221 -0.9925 +vn -0.0007 -0.1211 -0.9926 +vn -0.0011 -0.1208 -0.9927 +vn 0.0011 0.2927 0.9562 +vn 0.8627 -0.4663 0.1958 +vn 0.8878 -0.4317 0.1598 +vn 0.8732 -0.4524 0.1813 +vn 0.8994 -0.4136 0.1414 +vn -0.0005 0.2937 0.9559 +vn 0.8333 0.5425 -0.1060 +vn 0.9559 0.2507 -0.1528 +vn 0.9302 0.3392 -0.1406 +vn 0.7496 0.6569 -0.0811 +vn -0.0020 -0.1220 -0.9925 +vn -0.0020 -0.1230 -0.9924 +vn -0.0020 -0.1222 -0.9925 +vn -0.0021 -0.1211 -0.9926 +vn 0.8821 -0.4561 0.1182 +vn 0.9243 -0.3778 0.0541 +vn 0.9030 -0.4205 0.0886 +vn 0.9402 -0.3398 0.0240 +vn 0.9991 -0.0416 -0.0052 +vn 0.9999 0.0101 -0.0002 +vn 0.9975 0.0660 0.0269 +vn 0.9780 -0.0854 0.1901 +vn -0.2504 -0.8952 -0.3687 +vn 0.9994 -0.0285 -0.0174 +vn 0.9990 0.0029 -0.0450 +vn 0.9496 0.1933 0.2469 +vn 0.9984 0.0427 0.0377 +vn 0.9923 0.0644 0.1055 +vn 0.9939 0.1063 0.0301 +vn 0.9972 0.0420 -0.0623 +vn 0.0044 0.9756 -0.2194 +vn 0.0015 0.9749 -0.2228 +vn 0.0059 0.9765 -0.2153 +vn -0.0071 0.9792 -0.2027 +vn -0.0046 0.9777 -0.2101 +vn -0.0181 0.9798 -0.1991 +vn -0.0374 0.9705 -0.2383 +vn 0.0009 0.9916 -0.1291 +vn -0.0060 0.9898 -0.1422 +vn -0.7145 -0.1769 -0.6769 +vn -0.7075 -0.0197 -0.7064 +vn -0.7081 -0.0252 -0.7057 +vn 0.0576 -0.2830 -0.9574 +vn 0.0203 -0.1283 -0.9915 +vn 0.1233 -0.3076 -0.9435 +vn -0.0583 -0.2727 -0.9603 +vn -0.0887 -0.3261 -0.9412 +vn 0.2172 -0.0524 -0.9747 +vn 0.1098 -0.0865 -0.9902 +vn 0.9982 -0.0393 0.0462 +vn 0.9999 0.0076 -0.0105 +vn 0.9993 0.0334 -0.0148 +vn 0.9984 -0.0362 -0.0439 +vn 0.9951 0.0956 -0.0243 +vn 0.9960 0.0517 0.0724 +vn 0.9999 -0.0010 0.0167 +vn 0.9979 -0.0207 0.0612 +vn 0.9527 -0.2135 0.2162 +vn 0.9994 -0.0072 0.0328 +vn 0.9954 0.0884 -0.0363 +vn -0.3283 0.1730 -0.9286 +vn 1.0000 0.0001 0.0010 +vn 0.9984 0.0544 -0.0154 +vn 0.0051 0.2912 0.9566 +vn 0.0607 0.1503 0.9868 +vn 0.1286 0.0991 0.9867 +vn -0.1163 0.1052 0.9876 +vn -0.1011 0.1805 0.9784 +vn -0.0309 0.2676 0.9630 +vn -0.2281 0.3235 0.9183 +vn -0.0015 0.1797 0.9837 +vn -0.0047 0.1778 0.9841 +vn 0.7014 -0.7124 -0.0218 +vn -0.2154 0.2092 0.9539 +vn 0.5276 0.3921 0.7536 +vn 0.0007 0.2635 0.9647 +vn -0.1114 0.3070 0.9452 +vn -0.9998 -0.0094 0.0190 +vn -0.9938 0.1103 -0.0150 +vn -0.9977 0.0288 -0.0609 +vn -0.9999 0.0088 -0.0080 +vn 0.3290 0.5349 0.7783 +vn -0.9987 -0.0446 -0.0267 +vn -0.9996 0.0287 -0.0050 +vn -0.9996 0.0267 -0.0119 +vn -0.9979 -0.0511 -0.0390 +vn -0.9985 -0.0169 0.0516 +vn -0.9993 -0.0223 -0.0306 +vn -0.9999 0.0133 0.0028 +vn -0.9997 0.0220 0.0085 +vn -0.9999 -0.0035 -0.0115 +vn -0.9958 0.0912 -0.0054 +vn 0.0306 -0.1538 -0.9876 +vn 0.1126 -0.2983 -0.9478 +vn 0.0944 -0.2282 -0.9690 +vn -0.0744 -0.2600 -0.9627 +vn -0.1384 -0.3215 -0.9367 +vn -0.0169 -0.1704 -0.9852 +vn -0.0000 -0.1119 -0.9937 +vn 0.0808 -0.0836 -0.9932 +vn 0.9991 0.0424 -0.0084 +vn 0.9992 0.0382 -0.0080 +vn 0.8042 0.3935 0.4455 +vn -0.0167 0.2906 0.9567 +vn -0.0003 0.2424 0.9702 +vn 0.0001 0.2730 0.9620 +vn -0.0830 0.3213 0.9433 +vn -0.9997 0.0236 0.0013 +vn -0.9993 0.0365 -0.0110 +vn -0.6783 0.1562 -0.7180 +vn 0.0056 -0.1939 -0.9810 +vn 0.0116 -0.1731 -0.9848 +vn -0.0168 0.4932 -0.8698 +vn 0.0115 0.9757 -0.2187 +vn 0.0119 0.9756 -0.2191 +vn -0.0100 0.9761 -0.2170 +vn -0.0093 0.9762 -0.2165 +vn 0.0191 0.9777 -0.2091 +vn 0.0190 0.9776 -0.2094 +vn -0.0027 0.9860 -0.1670 +vn -0.0129 0.9807 -0.1949 +vn -0.0135 0.9807 -0.1949 +vn -0.0134 0.9953 -0.0961 +vn 0.0205 0.9773 -0.2109 +vn -0.0733 0.9460 0.3157 +vn 0.0012 0.2124 0.9772 +vn 0.0010 0.2129 0.9771 +vn 0.0007 0.2133 0.9770 +vn 0.0005 0.2137 0.9769 +vn -0.9999 0.0104 -0.0009 +vn -0.9999 0.0114 -0.0018 +vn -0.9999 0.0123 -0.0026 +vn -0.9999 0.0133 -0.0036 +vn -0.0012 -0.2047 -0.9788 +vn -0.0008 -0.2039 -0.9790 +vn -0.0003 -0.2031 -0.9792 +vn 0.0002 -0.2023 -0.9793 +vn 0.9999 0.0100 -0.0035 +vn 0.9999 0.0104 -0.0034 +vn 0.9999 0.0107 -0.0032 +vn 0.9999 0.0110 -0.0031 +vn 0.9999 0.0102 -0.0004 +vn 1.0000 0.0094 -0.0005 +vn -0.0016 0.2303 0.9731 +vn 0.0014 0.2222 0.9750 +vn -0.9998 0.0172 -0.0054 +vn -1.0000 0.0061 0.0020 +vn 0.0016 -0.1967 -0.9805 +vn 0.0006 -0.1994 -0.9799 +vn -0.0018 -0.2059 -0.9786 +vn -0.0028 -0.2085 -0.9780 +vn -0.0001 0.9782 -0.2078 +vn 0.0000 0.9782 -0.2078 +vn 0.0001 0.9781 -0.2079 +vn 0.0002 0.9781 -0.2081 +vn 0.3587 0.2394 0.9022 +vn 0.3591 0.1819 0.9154 +vn 0.2961 0.1568 0.9422 +vn -0.5978 0.3531 0.7197 +vn -0.4999 0.2391 0.8324 +vn -0.5260 0.2271 0.8196 +vn -0.6135 0.3509 0.7074 +vn -0.9743 -0.1675 -0.1507 +vn -0.9858 -0.0089 -0.1679 +vn -0.9851 -0.0112 -0.1716 +vn -0.9816 -0.0829 -0.1719 +vn -0.3628 -0.0951 -0.9270 +vn -0.1300 -0.2096 -0.9691 +vn -0.1753 -0.1926 -0.9655 +vn -0.3155 -0.1883 -0.9301 +vn 0.6363 0.0691 -0.7684 +vn 0.8026 -0.1631 -0.5738 +vn 0.7698 -0.1506 -0.6203 +vn 0.6149 0.0644 -0.7860 +vn 0.9572 -0.1345 0.2564 +vn 0.8396 0.1767 0.5136 +vn 0.9523 -0.0028 0.3053 +vn 0.7913 0.2099 0.5743 +vn -0.2065 -0.3201 -0.9246 +vn -0.2900 -0.2092 -0.9339 +vn 0.5598 0.3093 -0.7688 +vn 0.8995 0.3638 -0.2421 +vn 0.9307 -0.2433 0.2732 +vn 0.2065 0.0803 0.9751 +vn 0.2768 0.1710 0.9456 +vn -0.5629 0.5728 0.5958 +vn -0.9099 0.4069 0.0802 +vn -0.9534 -0.2742 -0.1258 +vn -0.0000 -0.9781 0.2080 +vn -0.0001 -0.9781 0.2079 +vn -0.0001 0.9781 -0.2080 +vn 0.0000 0.9782 -0.2077 +vn -0.3897 0.3572 0.8488 +vn -0.5143 0.2480 0.8209 +vn -0.4086 0.4045 0.8182 +vn -0.5415 0.2554 0.8009 +vn -0.9908 0.0716 0.1149 +vn -0.9909 -0.0173 0.1338 +vn -0.9922 -0.1193 0.0364 +vn -0.6611 -0.0062 -0.7503 +vn -0.8306 -0.0515 -0.5545 +vn -0.8010 -0.0729 -0.5942 +vn -0.6222 0.0411 -0.7818 +vn 0.3911 -0.1208 -0.9124 +vn 0.3439 -0.1598 -0.9253 +vn 0.3548 -0.1630 -0.9206 +vn 0.4904 -0.2688 -0.8290 +vn 0.9842 0.1630 -0.0687 +vn 0.9577 0.1339 0.2546 +vn 0.9765 0.2150 -0.0152 +vn 0.9297 0.1742 0.3246 +vn 0.5295 0.1322 0.8379 +vn 0.5299 0.1522 0.8343 +vn 0.4618 0.0344 0.8863 +vn -0.5794 0.2552 -0.7740 +vn 0.5895 -0.4101 -0.6959 +vn 0.5071 -0.2550 -0.8233 +vn 0.8807 0.4561 -0.1274 +vn 0.3647 -0.1020 0.9255 +vn 0.4335 -0.0153 0.9010 +vn -0.3566 0.5959 0.7195 +vn -0.9552 -0.2879 -0.0689 +vn -0.9953 -0.0967 0.0094 +vn -0.0000 -0.9782 0.2079 +vn -0.0003 -0.9777 -0.2099 +vn 0.0013 -0.9779 -0.2091 +vn -0.0013 -0.9779 -0.2090 +vn 0.0588 -0.9676 -0.2456 +vn -0.0027 -0.9719 -0.2355 +vn 0.0189 -0.9690 -0.2464 +vn -0.0068 -0.9793 -0.2024 +vn 0.0294 -0.9764 -0.2140 +vn 0.0814 -0.9889 -0.1243 +vn -0.0031 -0.9681 -0.2507 +vn 0.0063 -0.9789 -0.2042 +vn 0.0310 -0.9783 -0.2049 +vn 0.0067 -0.9767 -0.2144 +vn 0.0138 -0.9791 -0.2030 +vn -0.0338 -0.9776 -0.2076 +vn -0.0305 -0.9715 -0.2353 +vn -0.0065 -0.9777 -0.2099 +vn -0.0087 -0.9771 -0.2124 +vn -0.0292 -0.9790 -0.2018 +vn 0.0384 -0.9726 -0.2293 +vn -0.0652 -0.9610 -0.2688 +vn -0.0015 -0.9817 -0.1906 +vn 0.0033 -0.9806 -0.1959 +vn 0.0211 -0.9836 -0.1791 +vn -0.0041 -0.9831 -0.1829 +vn -0.0403 -0.9743 -0.2216 +vn -0.0173 -0.9839 -0.1780 +vn -0.0102 -0.9842 -0.1769 +vn 0.0178 -0.9839 -0.1778 +vn 0.0013 -0.1997 -0.9799 +vn 0.0028 -0.1972 -0.9804 +vn 0.0020 -0.1985 -0.9801 +vn 0.0005 -0.2010 -0.9796 +vn 0.0000 0.9783 -0.2072 +vn 0.0000 0.9783 -0.2071 +vn 0.0001 0.9789 -0.2044 +vn -0.1098 0.4949 -0.8620 +vn 0.0217 0.5150 -0.8569 +vn -0.0072 0.9824 -0.1865 +vn 0.0010 0.9825 -0.1860 +vn 0.0001 0.9848 -0.1739 +vn -0.0008 0.9782 -0.2078 +vn -0.0021 0.9776 -0.2104 +vn -0.0004 0.9782 -0.2078 +vn -0.0032 0.9752 -0.2212 +vn 0.0000 0.9785 -0.2063 +vn 0.0083 0.9761 -0.2171 +vn -0.0107 0.9780 -0.2082 +vn 0.0010 0.9779 -0.2092 +vn -0.0225 0.9859 -0.1657 +vn 0.0269 0.9728 -0.2300 +vn 0.0076 0.9760 -0.2175 +vn 0.0162 0.9766 -0.2145 +vn 0.0052 0.9781 -0.2079 +vn 0.0053 0.9781 -0.2079 +vn -0.0000 0.9796 -0.2010 +vn 0.0306 0.9782 -0.2054 +vn 0.0017 0.9769 -0.2135 +vn -0.0003 0.9781 -0.2080 +vn 0.0499 0.9768 -0.2084 +vn -0.0220 0.9778 -0.2086 +vn 0.0010 0.9732 -0.2299 +vn 0.0068 0.9813 -0.1924 +vn 0.0001 0.9790 -0.2038 +vn -0.0003 0.9789 -0.2043 +vn -0.0060 0.9768 -0.2140 +vn 0.0028 0.9791 -0.2035 +vn 0.0010 0.9779 -0.2091 +vn 0.0032 0.9788 -0.2046 +vn 0.0007 0.9779 -0.2089 +vn -0.0028 0.9755 -0.2200 +vn 0.0048 0.9784 -0.2068 +vn 0.0052 0.9778 -0.2094 +vn 0.0045 0.9788 -0.2047 +vn -0.0019 0.9797 -0.2003 +vn -0.0008 0.9800 -0.1988 +vn -0.0000 -0.9781 0.2079 +vn 0.0001 -0.9781 0.2079 +vn -0.0000 -0.9782 0.2078 +vn -0.0969 -0.6643 0.7411 +vn -0.0968 -0.6643 0.7411 +vn -0.0901 -0.6635 0.7428 +vn -0.1037 -0.6652 0.7394 +vn -0.8717 0.3518 0.3411 +vn 0.4160 0.6356 0.6504 +vn 0.5393 0.6241 0.5654 +vn 0.4940 0.6301 0.5991 +vn 0.3741 0.6362 0.6748 +vn 0.7400 -0.5252 -0.4202 +vn 0.7891 -0.4632 -0.4035 +vn 0.7557 -0.5064 -0.4153 +vn 0.8074 -0.4373 -0.3959 +vn -0.4163 -0.7075 -0.5711 +vn -0.9507 0.0231 -0.3092 +vn -0.1385 -0.7728 0.6194 +vn 0.0172 -0.7143 0.6996 +vn 0.0124 -0.6722 0.7403 +vn -0.1491 -0.6226 0.7682 +vn -0.1904 -0.7012 0.6870 +vn -0.1273 -0.6062 0.7850 +vn -0.1819 -0.8152 0.5498 +vn -0.0462 -0.7297 0.6822 +vn 0.0065 -0.6348 0.7727 +vn -0.6870 -0.2538 0.6809 +vn 0.1260 -0.0565 0.9904 +vn 0.7941 0.5279 -0.3012 +vn 0.7170 0.6549 -0.2388 +vn 0.8780 0.3704 -0.3030 +vn 0.4419 0.8734 -0.2046 +vn 0.2880 0.9517 -0.1065 +vn -0.2844 0.9299 -0.2331 +vn -0.2212 0.9738 -0.0535 +vn -0.5694 0.7272 -0.3835 +vn -0.6035 0.5997 -0.5255 +vn -0.6687 0.5208 -0.5307 +vn -0.5374 0.0214 -0.8430 +vn -0.5597 0.0125 -0.8286 +vn -0.5384 0.0210 -0.8424 +vn -0.4922 0.0389 -0.8696 +vn 0.4286 0.0090 -0.9035 +vn 0.1518 -0.0446 -0.9874 +vn 0.0876 0.0192 -0.9960 +vn 0.4228 -0.0562 -0.9045 +vn 0.6503 0.0520 -0.7579 +vn 0.6668 0.1253 -0.7346 +vn 0.0507 0.6644 -0.7456 +vn 0.1014 0.6642 -0.7406 +vn 0.0833 0.6702 -0.7375 +vn 0.1569 0.6725 -0.7233 +vn 0.1070 0.6774 -0.7278 +vn 0.1171 0.6703 -0.7328 +vn -0.0921 -0.6782 0.7291 +vn -0.1084 -0.6552 0.7476 +vn -0.0925 -0.6777 0.7295 +vn -0.0796 -0.6953 0.7143 +vn -0.8830 0.4307 0.1867 +vn -0.9396 0.3141 0.1360 +vn -0.8595 0.4690 0.2034 +vn 0.0542 0.6534 0.7551 +vn 0.7931 0.4704 0.3869 +vn 0.9250 -0.3768 -0.0485 +vn 0.1405 -0.6313 -0.7627 +vn -0.4701 -0.6649 -0.5805 +vn -0.9623 0.2495 0.1079 +vn -0.0822 -0.5250 0.8471 +vn -0.1339 -0.5821 0.8020 +vn -0.1633 -0.7295 0.6642 +vn -0.1622 -0.6934 0.7020 +vn -0.1857 -0.7844 0.5918 +vn -0.0583 -0.3994 0.9149 +vn -0.0047 -0.7049 0.7093 +vn -0.0370 -0.7605 0.6483 +vn 0.0481 -0.7010 0.7116 +vn -0.0296 -0.5814 0.8131 +vn 0.3357 -0.8278 0.4495 +vn -0.9247 0.1532 0.3485 +vn 0.6562 0.1123 -0.7462 +vn 0.7712 0.4666 -0.4330 +vn 0.8242 0.4079 -0.3929 +vn 0.6434 0.7496 -0.1553 +vn 0.5201 0.8359 -0.1754 +vn 0.2189 0.9740 -0.0589 +vn -0.1240 0.9768 -0.1744 +vn -0.2783 0.9600 -0.0311 +vn -0.4797 0.7852 -0.3915 +vn -0.3346 0.5253 -0.7824 +vn -0.6739 0.3401 -0.6559 +vn -0.4917 0.1757 -0.8528 +vn -0.1658 0.2895 -0.9427 +vn 0.2679 -0.1807 -0.9464 +vn -0.0939 -0.4089 -0.9077 +vn 0.0514 -0.2860 -0.9568 +vn 0.0731 0.5817 -0.8101 +vn 0.5012 0.0394 -0.8644 +vn 0.1055 0.6741 -0.7311 +vn 0.1128 0.6775 -0.7268 +vn 0.1098 0.6860 -0.7192 +vn 0.1533 0.8573 0.4914 +vn 0.1160 0.6143 0.7805 +vn 0.1419 0.7811 0.6080 +vn -0.0929 -0.6669 -0.7393 +vn -0.0794 -0.6639 -0.7436 +vn -0.1041 -0.6693 -0.7357 +vn -0.8558 -0.1733 0.4874 +vn -0.3520 -0.7270 0.5895 +vn 0.9083 -0.3455 0.2360 +vn 0.9364 -0.2789 0.2129 +vn 0.9271 -0.3027 0.2212 +vn 0.8995 -0.3637 0.2422 +vn 0.2340 0.7375 -0.6335 +vn 0.4775 0.5897 -0.6514 +vn 0.3979 0.6462 -0.6512 +vn 0.1655 0.7670 -0.6200 +vn -0.8819 0.3203 -0.3459 +vn -0.0528 -0.7613 -0.6462 +vn -0.1700 -0.7070 -0.6865 +vn -0.1771 -0.6330 -0.7537 +vn -0.2304 -0.6580 -0.7169 +vn -0.1544 -0.6035 -0.7823 +vn -0.1050 -0.7822 -0.6142 +vn -0.0181 -0.6719 -0.7404 +vn -0.0886 -0.6113 -0.7864 +vn -0.0370 -0.6522 -0.7572 +vn 0.0270 -0.7756 -0.6307 +vn 0.7658 0.6085 0.2080 +vn 0.7668 0.6084 0.2046 +vn 0.7670 0.6084 0.2038 +vn 0.7423 0.1084 0.6613 +vn 0.7361 0.2627 0.6239 +vn 0.6373 0.0709 0.7674 +vn 0.4510 -0.0727 0.8896 +vn 0.0346 -0.0478 0.9983 +vn -0.1088 -0.0715 0.9915 +vn -0.2936 0.0160 0.9558 +vn -0.2843 0.0192 0.9585 +vn -0.6663 0.4334 0.6068 +vn -0.7145 0.2524 0.6525 +vn -0.5740 0.5112 0.6397 +vn -0.3875 0.7084 0.5900 +vn -0.3771 0.9256 0.0338 +vn -0.6913 0.7207 0.0520 +vn -0.5258 0.8471 0.0767 +vn -0.1893 0.7810 0.5952 +vn -0.0530 0.9986 -0.0019 +vn 0.0873 0.9905 -0.1059 +vn 0.3505 0.9197 -0.1772 +vn 0.4524 0.8479 -0.2765 +vn 0.1520 0.7049 0.6929 +vn 0.3304 0.8020 0.4977 +vn -0.0153 0.6636 0.7479 +vn 0.7680 0.6083 0.2004 +vn 0.7825 -0.6226 -0.0011 +vn -0.0572 0.6056 0.7937 +vn -0.2873 0.4820 0.8277 +vn 0.1610 0.9128 0.3754 +vn -0.0774 -0.6744 -0.7343 +vn -0.0774 -0.6745 -0.7342 +vn -0.0726 -0.6817 -0.7280 +vn -0.0815 -0.6683 -0.7394 +vn -0.4704 -0.5591 0.6827 +vn -0.2891 -0.6857 0.6680 +vn -0.4162 -0.6017 0.6818 +vn -0.2127 -0.7269 0.6530 +vn 1.0000 -0.0009 -0.0015 +vn 0.9438 -0.3038 0.1303 +vn 0.9777 -0.1933 0.0822 +vn 0.9965 0.0761 -0.0350 +vn 0.4133 0.5549 -0.7220 +vn -0.5980 0.6876 -0.4117 +vn -0.9598 0.2038 -0.1929 +vn -0.2140 -0.6821 -0.6992 +vn -0.1753 -0.7345 -0.6555 +vn -0.2544 -0.6478 -0.7181 +vn -0.1263 -0.5974 -0.7919 +vn -0.0332 -0.5721 -0.8195 +vn -0.0457 -0.7398 -0.6712 +vn -0.0997 -0.7828 -0.6142 +vn -0.0270 -0.4611 -0.8869 +vn -0.0026 -0.6419 -0.7668 +vn 0.0247 -0.6791 -0.7337 +vn 0.0038 -0.7205 -0.6934 +vn 0.6005 0.0381 0.7987 +vn 0.8018 0.1131 0.5868 +vn 0.6569 0.0824 0.7495 +vn 0.1707 0.2901 0.9417 +vn 0.1999 -0.1297 0.9712 +vn -0.2661 -0.0218 0.9637 +vn -0.2449 -0.4013 0.8826 +vn -0.3647 0.5018 0.7844 +vn -0.6317 0.2335 0.7392 +vn -0.6832 0.5937 0.4252 +vn -0.4346 0.8633 0.2567 +vn -0.3507 0.9346 0.0588 +vn -0.0815 0.9917 0.0989 +vn 0.0032 0.9882 0.1534 +vn 0.6346 0.7600 0.1401 +vn 0.4642 0.8835 -0.0636 +vn 0.6236 0.7674 0.1493 +vn 0.7099 0.6363 0.3019 +vn 0.7032 0.6262 0.3368 +vn 0.1166 0.6518 0.7494 +vn 0.0924 0.6758 0.7313 +vn 0.0813 0.6909 0.7183 +vn -0.0967 0.9953 -0.0097 +vn -0.1061 0.9943 -0.0077 +vn -0.0966 0.9953 -0.0098 +vn -0.0876 0.9961 -0.0117 +vn -0.8988 -0.1226 -0.4209 +vn -0.8737 -0.0917 -0.4777 +vn -0.8563 -0.0725 -0.5114 +vn 0.5338 0.1146 -0.8378 +vn 0.8883 -0.0638 -0.4548 +vn 0.7652 0.1778 0.6188 +vn -0.1072 -0.0834 0.9907 +vn -0.3957 -0.0246 0.9180 +vn -0.1894 -0.0676 0.9796 +vn -0.4885 -0.0035 0.8726 +vn -0.9097 -0.1379 -0.3917 +vn -0.1011 0.9918 -0.0778 +vn -0.1940 0.9806 -0.0272 +vn -0.1629 0.9803 0.1114 +vn -0.1733 0.9808 -0.0896 +vn -0.1333 0.9720 0.1934 +vn -0.0056 0.9976 0.0692 +vn -0.1257 0.9813 0.1457 +vn -0.2011 0.9380 0.2823 +vn 0.0340 0.9983 0.0478 +vn 0.0361 0.9990 -0.0255 +vn -0.0225 0.9996 0.0191 +vn 0.7158 -0.5693 0.4043 +vn 0.7632 -0.6436 0.0583 +vn 0.7373 -0.6287 -0.2472 +vn 0.6250 -0.6392 -0.4481 +vn 0.6014 -0.5457 -0.5836 +vn 0.0852 -0.5831 -0.8079 +vn 0.0825 -0.5867 -0.8056 +vn 0.0848 -0.5837 -0.8076 +vn 0.0867 -0.5811 -0.8092 +vn -0.5688 -0.7058 -0.4224 +vn -0.5677 -0.7064 -0.4227 +vn -0.5636 -0.7091 -0.4237 +vn -0.5720 -0.7036 -0.4215 +vn -0.5847 -0.7280 0.3580 +vn -0.7594 -0.6270 0.1739 +vn -0.6142 -0.7168 0.3301 +vn -0.4653 -0.7627 0.4492 +vn -0.4610 -0.7651 0.4496 +vn 0.2375 -0.6793 0.6943 +vn -0.0094 -0.7093 0.7048 +vn 0.0758 -0.7332 0.6758 +vn 0.4878 -0.6637 0.5671 +vn 0.0906 -0.9955 -0.0264 +vn 0.1206 -0.9923 -0.0276 +vn 0.1207 -0.9923 -0.0271 +vn -0.0011 -0.9999 -0.0168 +vn 0.1002 -0.9947 -0.0245 +vn 0.1109 -0.9935 -0.0260 +vn 0.0848 -0.9961 -0.0255 +vn 0.1170 -0.9925 -0.0352 +vn 0.1240 -0.9866 -0.1060 +vn -0.0918 0.9957 -0.0110 +vn -0.0919 0.9957 -0.0109 +vn -0.0881 0.9960 -0.0117 +vn -0.0976 0.9952 -0.0097 +vn -0.7101 0.0471 -0.7025 +vn 0.1424 -0.0503 -0.9885 +vn 0.6392 0.1209 -0.7595 +vn 0.9830 0.0534 0.1756 +vn 0.9443 0.0971 0.3143 +vn 0.9748 0.0654 0.2134 +vn 0.9272 0.1109 0.3578 +vn -0.3328 0.0285 0.9426 +vn -0.4522 -0.0469 0.8907 +vn -0.4146 -0.0226 0.9097 +vn -0.2872 0.0559 0.9562 +vn -0.9799 -0.1575 -0.1226 +vn -0.1604 0.9854 -0.0569 +vn -0.2231 0.9740 0.0388 +vn -0.1595 0.9809 0.1113 +vn -0.1805 0.9798 -0.0861 +vn -0.1477 0.9718 0.1836 +vn -0.0975 0.9891 0.1100 +vn -0.0835 0.9930 0.0835 +vn -0.0381 0.9976 -0.0580 +vn -0.0306 0.9989 -0.0343 +vn -0.4835 0.8631 -0.1459 +vn 0.7429 0.6512 0.1552 +vn 0.1681 0.6746 -0.7187 +vn 0.6923 -0.6697 -0.2687 +vn 0.7131 -0.6584 0.2408 +vn 0.6886 -0.7112 0.1413 +vn 0.7557 -0.5736 -0.3161 +vn 0.3383 -0.7111 -0.6163 +vn -0.0248 -0.7371 -0.6753 +vn -0.3160 -0.6875 -0.6538 +vn -0.4995 -0.7484 -0.4362 +vn -0.6509 -0.7272 -0.2181 +vn -0.6636 -0.7449 -0.0696 +vn -0.7367 -0.6742 0.0526 +vn -0.4718 -0.6650 0.5790 +vn -0.5018 -0.6418 0.5799 +vn -0.4797 -0.6590 0.5793 +vn -0.4333 -0.6926 0.5766 +vn 0.4169 -0.6906 0.5910 +vn 0.2246 -0.6490 0.7269 +vn 0.1097 -0.7359 0.6682 +vn 0.4765 -0.6056 0.6374 +vn 0.0791 -0.9968 0.0106 +vn 0.0315 -0.9995 0.0061 +vn 0.1106 -0.9925 -0.0520 +vn 0.1248 -0.9907 0.0537 +vn 0.0001 -0.9781 0.2080 +vn 0.0088 -0.8127 -0.5826 +vn 0.1840 -0.7937 -0.5798 +vn -0.0135 -0.8133 -0.5816 +vn -0.2133 -0.8005 -0.5600 +vn 0.2457 -0.4279 -0.8698 +vn 0.3357 -0.8392 -0.4278 +vn -0.3145 -0.6821 -0.6601 +vn -0.3146 -0.6954 -0.6461 +vn -0.3076 -0.8295 -0.4662 +vn -0.3038 -0.5059 -0.8073 +vn 0.0137 -0.7806 -0.6249 +vn 0.0868 -0.7672 -0.6355 +vn 0.0123 -0.7808 -0.6247 +vn -0.0690 -0.7904 -0.6087 +vn -0.2033 0.6614 -0.7220 +vn -0.1743 0.6496 -0.7400 +vn -0.6062 0.5233 -0.5989 +vn -0.9970 0.0634 -0.0454 +vn -0.7454 -0.4700 0.4726 +vn -0.0635 -0.6606 0.7480 +vn 0.7993 -0.4323 0.4175 +vn 0.9883 0.1231 -0.0903 +vn -0.1587 0.6668 -0.7281 +vn 0.2826 0.6330 -0.7207 +vn -0.9210 0.2756 -0.2753 +vn -0.7669 0.4313 -0.4752 +vn -0.7797 0.4218 -0.4627 +vn -0.9278 0.2652 -0.2623 +vn -0.7469 -0.4683 0.4720 +vn -0.3155 -0.6327 0.7072 +vn 0.9188 -0.2627 0.2947 +vn 0.7509 -0.4640 0.4699 +vn 0.7650 -0.4515 0.4592 +vn 0.9279 -0.2461 0.2800 +vn 0.3341 0.6510 -0.6816 +vn 0.5802 0.5452 -0.6051 +vn 0.5643 0.5540 -0.6120 +vn 0.3155 0.6566 -0.6850 +vn -0.7687 0.2083 -0.6048 +vn -0.8616 0.0715 0.5025 +vn -0.9320 -0.0973 0.3492 +vn -0.9216 -0.0966 0.3760 +vn -0.5864 -0.6490 0.4847 +vn 0.2497 -0.1691 0.9534 +vn 0.8178 -0.5451 0.1844 +vn 0.7792 0.6254 0.0416 +vn 0.3316 0.4461 -0.8313 +vn -0.3536 0.7464 -0.5638 +vn -0.3567 0.7026 -0.6157 +vn -0.3567 0.7035 -0.6147 +vn -0.8392 -0.2896 -0.4603 +vn -0.8195 -0.1471 0.5539 +vn 0.0667 -0.6990 0.7120 +vn -0.0840 -0.7141 0.6950 +vn 0.0217 -0.6877 0.7256 +vn 0.2240 -0.6092 0.7607 +vn 0.7951 -0.6061 -0.0218 +vn 0.8784 -0.4376 0.1921 +vn 0.8831 -0.4176 0.2140 +vn 0.9508 0.3072 -0.0402 +vn 0.2791 0.2146 -0.9360 +vn 0.3097 0.4581 -0.8332 +vn 0.3126 0.4952 -0.8106 +vn -0.3157 0.7870 -0.5300 +vn -0.3579 0.6733 -0.6470 +vn 0.3183 0.6204 -0.7168 +vn 0.8913 0.2946 -0.3447 +vn 0.8943 -0.2889 0.3416 +vn 0.2770 -0.6678 0.6909 +vn 0.2937 -0.6651 0.6866 +vn -0.9906 0.0832 -0.1083 +vn -0.9864 0.0999 -0.1306 +vn -0.3142 -0.6821 -0.6603 +vn -0.3143 -0.6953 -0.6464 +vn -0.3073 -0.8296 -0.4663 +vn -0.3036 -0.5056 -0.8076 +vn -0.7875 0.4779 -0.3892 +vn -0.7546 0.5579 -0.3453 +vn -0.7682 0.5790 -0.2732 +vn -0.7965 0.4857 -0.3601 +vn -0.6398 -0.5400 0.5469 +vn -0.7439 -0.5391 0.3949 +vn -0.6371 -0.4525 0.6239 +vn -0.5656 -0.4893 0.6639 +vn 0.7076 -0.5227 0.4754 +vn 0.7063 -0.5382 0.4599 +vn 0.6771 -0.5095 0.5309 +vn 0.7440 -0.5612 0.3627 +vn 0.6912 0.6197 -0.3718 +vn 0.6961 0.4972 -0.5179 +vn 0.7505 0.5401 -0.3808 +vn 0.5787 0.5012 -0.6434 +vn -0.9626 0.1688 0.2118 +vn -0.9850 0.0948 0.1441 +vn -0.9947 0.0408 0.0942 +vn -0.9501 -0.0077 -0.3119 +vn -0.1130 -0.6757 0.7284 +vn -0.0124 -0.6081 0.7938 +vn -0.0798 -0.6948 0.7148 +vn -0.2576 -0.8115 0.5246 +vn 0.8763 -0.1703 0.4506 +vn 0.9096 -0.2432 -0.3368 +vn 0.9890 -0.0278 -0.1455 +vn 0.9844 -0.0527 -0.1681 +vn 0.4304 0.7892 -0.4381 +vn -0.1196 0.3954 -0.9107 +vn -0.1263 0.6065 -0.7850 +vn -0.1256 0.5701 -0.8119 +vn -0.1267 0.7034 -0.6994 +vn 0.7569 0.4172 -0.5030 +vn 0.9954 0.0886 -0.0377 +vn 0.6767 -0.5296 0.5115 +vn -0.0124 -0.6668 0.7451 +vn -0.5678 -0.5865 0.5775 +vn -0.9986 -0.0035 0.0532 +vn -0.8007 0.3782 -0.4646 +vn -0.0002 -0.6820 0.7313 +vn 0.0001 -0.6820 0.7313 +vn 0.0595 -0.7407 0.6692 +vn -0.0852 -0.6809 0.7274 +vn 0.0137 -0.7243 0.6893 +vn 0.0540 -0.6677 0.7425 +vn 0.0146 -0.6692 0.7429 +vn 0.1556 -0.7430 -0.6509 +vn 0.1638 0.6929 0.7022 +vn 0.2549 0.6822 0.6853 +vn 0.2370 0.6848 0.6892 +vn 0.1477 0.6941 0.7045 +vn 0.3338 0.6428 -0.6895 +vn 0.3425 0.6399 -0.6879 +vn 0.3418 0.6401 -0.6880 +vn 0.3331 0.6431 -0.6896 +vn 0.9259 -0.2842 0.2490 +vn 0.9533 -0.2137 0.2134 +vn 0.9143 -0.3093 0.2615 +vn 0.9623 -0.1855 0.1989 +vn -0.0356 -0.6937 -0.7194 +vn 0.0477 0.7665 0.6404 +vn -0.0330 -0.6841 -0.7287 +vn 0.9834 -0.1327 0.1240 +vn 0.9687 -0.1981 0.1498 +vn 0.9747 -0.1738 0.1403 +vn 0.9879 -0.1059 0.1133 +vn 0.9995 0.0311 0.0055 +vn 0.9994 0.0348 -0.0066 +vn 0.9996 0.0076 0.0261 +vn 0.9996 -0.0142 -0.0232 +vn 0.9994 -0.0332 -0.0081 +vn 0.9997 0.0021 -0.0260 +vn 0.9995 -0.0227 0.0222 +vn 0.9991 -0.0354 0.0237 +vn -0.9971 -0.0215 -0.0731 +vn -0.9980 0.0515 0.0355 +vn -0.9989 -0.0154 -0.0438 +vn -0.9984 0.0570 0.0016 +vn -0.0230 0.9309 -0.3646 +vn 0.0030 0.3728 -0.9279 +vn 0.0020 0.3546 -0.9350 +vn -0.0150 0.0045 -0.9999 +vn -0.0160 -0.0178 -0.9997 +vn 0.0115 -0.6906 -0.7231 +vn -0.0149 -0.9663 -0.2570 +vn 0.0000 -0.9147 0.4041 +vn -0.0008 -0.9090 0.4167 +vn -0.0162 -0.7555 0.6549 +vn -0.0170 -0.7452 0.6666 +vn 0.0019 -0.0180 0.9998 +vn 0.0006 0.0030 1.0000 +vn -0.0208 0.3437 0.9389 +vn -0.0221 0.3639 0.9312 +vn 0.0140 0.9859 0.1665 +vn -0.9955 0.0068 -0.0942 +vn -0.9964 0.0609 -0.0590 +vn -0.9961 -0.0301 -0.0828 +vn -0.9969 0.0716 -0.0337 +vn -0.9947 0.0642 0.0797 +vn -0.9941 0.0896 0.0618 +vn -0.9958 -0.0100 0.0915 +vn -0.9934 -0.0703 0.0902 +vn -0.9957 -0.0907 0.0199 +vn -0.9925 -0.1134 -0.0458 +vn 0.1719 0.6787 -0.7140 +vn -0.2046 0.3531 -0.9129 +vn 0.1613 -0.5927 -0.7891 +vn -0.1737 -0.8596 -0.4805 +vn 0.1356 -0.9730 0.1866 +vn -0.0133 -0.5136 0.8579 +vn -0.0062 -0.5056 0.8628 +vn -0.1455 -0.6504 0.7455 +vn 0.1306 -0.3370 0.9324 +vn -0.1440 0.4235 0.8944 +vn 0.1602 0.8438 0.5121 +vn 0.0310 0.9336 0.3570 +vn 0.0357 0.9311 0.3630 +vn -0.1083 0.9790 0.1728 +vn -0.1238 0.9744 0.1874 +vn -0.0016 0.9982 0.0592 +vn 0.0017 0.9984 0.0557 +vn 0.1239 0.9895 -0.0743 +vn -0.1239 -0.6496 0.7501 +vn -0.0017 -0.5505 0.8348 +vn 0.0016 -0.5476 0.8367 +vn 0.1237 -0.4305 0.8941 +vn -0.1237 -0.3248 -0.9376 +vn -0.0015 -0.4477 -0.8942 +vn 0.0018 -0.4508 -0.8926 +vn 0.1240 -0.5590 -0.8198 +vn -0.9513 -0.1613 -0.2628 +vn 0.9994 0.0155 0.0322 +vn 0.9993 0.0315 0.0217 +vn 0.9992 0.0210 0.0348 +vn 0.9994 0.0265 -0.0244 +vn 0.9995 0.0323 0.0031 +vn 0.9995 0.0064 -0.0320 +vn 0.9991 -0.0261 -0.0342 +vn 0.9993 -0.0111 -0.0358 +vn 0.9990 -0.0266 -0.0368 +vn -0.9973 0.0501 -0.0535 +vn -0.9956 0.0624 -0.0698 +vn -0.9998 -0.0210 -0.0044 +vn -0.9995 -0.0270 0.0136 +vn 0.0115 0.5723 0.8199 +vn -0.0089 0.3738 0.9275 +vn -0.0107 0.3552 0.9347 +vn 0.0126 0.5827 0.8126 +vn -0.0200 0.9995 -0.0252 +vn 0.0106 0.8418 -0.5396 +vn 0.0069 -0.1732 -0.9849 +vn -0.0101 0.2224 -0.9749 +vn -0.0113 0.2494 -0.9683 +vn 0.0077 -0.1917 -0.9814 +vn -0.0238 -0.7317 -0.6812 +vn 0.0167 -0.9574 0.2884 +vn 0.0151 -0.9522 0.3052 +vn -0.0117 -0.8261 0.5634 +vn -0.0141 -0.8111 0.5848 +vn -0.9898 0.1426 0.0069 +vn -0.9963 0.0624 0.0594 +vn -0.9955 0.0757 -0.0565 +vn -0.9911 -0.0241 0.1311 +vn -0.9908 -0.0742 0.1127 +vn -0.9955 -0.0949 -0.0012 +vn -0.9910 -0.1064 -0.0809 +vn -0.9954 -0.0214 -0.0939 +vn -0.9943 0.0390 -0.0990 +vn 0.2086 0.6379 0.7413 +vn -0.0614 0.9902 -0.1254 +vn -0.0614 0.9902 -0.1255 +vn -0.1927 0.9799 0.0519 +vn 0.0951 0.9413 -0.3239 +vn -0.0453 0.2998 -0.9529 +vn -0.0471 0.3017 -0.9522 +vn -0.0729 0.3285 -0.9417 +vn -0.0153 0.2681 -0.9633 +vn 0.0346 -0.6768 -0.7353 +vn -0.0309 -0.7292 -0.6836 +vn -0.0317 -0.7299 -0.6829 +vn -0.0912 -0.7714 -0.6297 +vn 0.0993 -0.9661 0.2385 +vn 0.0830 -0.8281 0.5544 +vn 0.0124 -0.9195 0.3929 +vn 0.0408 -0.7656 0.6421 +vn 0.1545 -0.5554 0.8171 +vn -0.1977 0.1101 0.9741 +vn -0.1237 -0.9376 0.3248 +vn -0.0015 -0.8942 0.4477 +vn 0.0018 -0.8926 0.4508 +vn 0.1240 -0.8198 0.5590 +vn 0.1722 -0.1263 -0.9769 +vn 0.1521 -0.1046 -0.9828 +vn 0.1481 -0.1003 -0.9839 +vn 0.1239 -0.0743 -0.9895 +vn -0.1227 0.7425 0.6585 +vn 0.0223 0.8119 0.5834 +vn 0.0661 0.8278 0.5571 +vn 0.2602 0.8700 0.4189 +vn -0.9629 0.2089 -0.1706 +vn 0.9999 -0.0128 -0.0086 +vn 0.9975 0.0325 0.0620 +vn 0.9980 0.0311 0.0555 +vn 0.9983 0.0301 0.0506 +vn 0.9984 0.0295 0.0474 +vn -0.9911 0.0407 0.1264 +vn -0.9954 0.0922 0.0268 +vn -0.9888 0.0823 -0.1243 +vn 0.0024 -0.9627 0.2705 +vn -0.0460 -0.9911 -0.1250 +vn -0.0526 -0.9819 -0.1818 +vn 0.0085 -0.9482 0.3176 +vn -0.0426 -0.4486 0.8927 +vn 0.0325 0.2948 0.9550 +vn -0.0387 0.7771 0.6282 +vn 0.0059 0.9469 -0.3214 +vn 0.0043 0.9438 -0.3304 +vn -0.0075 0.9179 -0.3968 +vn -0.0099 0.9121 -0.4098 +vn 0.0104 -0.3817 -0.9242 +vn -0.0063 -0.2648 -0.9643 +vn -0.0095 -0.2420 -0.9702 +vn 0.0121 -0.3934 -0.9193 +vn -0.9935 0.0196 -0.1119 +vn -0.9916 0.1112 0.0661 +vn -0.9953 0.0694 -0.0674 +vn -0.9895 0.1320 0.0595 +vn -0.9933 -0.0997 -0.0579 +vn -0.9927 -0.0578 -0.1060 +vn -0.9940 -0.1092 -0.0009 +vn -0.9947 -0.0074 0.1023 +vn -0.9917 -0.0856 0.0959 +vn -0.1655 -0.8278 -0.5360 +vn 0.1791 -0.9499 0.2561 +vn 0.0032 -0.8824 0.4704 +vn 0.0296 -0.8972 0.4407 +vn -0.1391 -0.7756 0.6157 +vn 0.1696 -0.2833 0.9439 +vn -0.0715 0.5610 0.8247 +vn -0.0691 0.5634 0.8233 +vn -0.1260 0.5069 0.8528 +vn -0.0024 0.6238 0.7816 +vn -0.0563 0.9881 -0.1428 +vn -0.0459 0.9874 -0.1517 +vn 0.0002 0.9817 -0.1907 +vn -0.1198 0.9889 -0.0878 +vn 0.2170 0.6628 -0.7167 +vn -0.1115 0.0745 -0.9910 +vn 0.1779 -0.3948 -0.9014 +vn -0.0946 -0.5671 -0.8182 +vn -0.0538 -0.5874 -0.8075 +vn -0.0013 -0.6114 -0.7913 +vn 0.0807 -0.6445 -0.7603 +vn -0.3103 0.8603 0.4045 +vn 0.5448 0.8251 -0.1497 +vn 0.4659 -0.6055 0.6452 +vn 0.5959 -0.4277 0.6797 +vn 0.5972 -0.4255 0.6799 +vn 0.6898 -0.2443 0.6816 +vn -0.9361 0.0861 0.3409 +vn -0.9388 0.1832 -0.2917 +vn -0.4519 -0.4487 0.7710 +vn -0.3767 -0.5613 0.7369 +vn -0.4805 -0.3995 0.7807 +vn 0.6045 0.0708 0.7934 +vn -0.4987 0.5857 0.6389 +vn 0.4861 0.7579 -0.4350 +vn 0.2215 0.7848 -0.5788 +vn 0.4306 0.7700 -0.4707 +vn 0.1078 0.7753 -0.6223 +vn -0.2800 -0.4709 -0.8366 +vn 0.3388 -0.6325 -0.6965 +vn -0.1756 0.8327 -0.5251 +vn 0.5640 0.8053 0.1829 +vn -0.6051 0.3044 0.7357 +vn 0.4940 -0.0831 0.8655 +vn -0.4596 -0.7813 0.4223 +vn 0.2997 -0.9241 0.2370 +vn -0.3074 -0.5185 -0.7979 +vn 0.0751 -0.4464 -0.8917 +vn -0.2460 -0.5122 -0.8229 +vn 0.1502 -0.4235 -0.8934 +vn -0.0807 0.6207 -0.7799 +vn -0.1164 0.6272 -0.7701 +vn -0.0679 0.6182 -0.7831 +vn -0.1259 0.6288 -0.7673 +vn -0.5494 -0.2606 0.7939 +vn 0.2837 0.5169 0.8076 +vn -0.3720 -0.6013 -0.7071 +vn 0.6133 -0.7867 0.0702 +vn -0.3152 -0.8112 0.4926 +vn -0.0817 0.1744 0.9813 +vn 0.6588 0.4092 0.6313 +vn -0.5794 0.8146 0.0263 +vn 0.4668 0.5687 -0.6773 +vn 0.8674 0.4732 0.1541 +vn 0.9794 0.1753 0.1005 +vn 0.8276 0.5541 0.0896 +vn -0.6228 -0.5732 0.5325 +vn 0.4246 -0.8843 0.1941 +vn -0.3524 -0.7413 -0.5713 +vn 0.0203 -0.6914 -0.7222 +vn -0.2806 -0.7411 -0.6100 +vn 0.1249 -0.6570 -0.7435 +vn 0.0001 0.2126 -0.9771 +vn 0.1509 0.1654 -0.9746 +vn -0.0667 0.2317 -0.9705 +vn 0.2384 0.1356 -0.9617 +vn -0.3310 0.8151 -0.4755 +vn 0.3920 0.9049 -0.1658 +vn -0.3992 0.7557 0.5192 +vn 0.1787 0.6560 0.7333 +vn -0.7101 -0.6894 -0.1433 +vn -0.2847 -0.8634 0.4166 +vn -0.9986 -0.0170 0.0509 +vn -0.9994 -0.0066 0.0334 +vn -0.9855 -0.1029 0.1345 +vn -0.9821 -0.1211 0.1443 +vn 0.9722 0.1679 0.1631 +vn 0.9997 -0.0088 -0.0210 +vn 0.9995 -0.0166 0.0265 +vn 0.9997 -0.0248 0.0075 +vn 0.9997 -0.0093 -0.0247 +vn 0.9996 0.0058 0.0289 +vn 0.9997 0.0216 0.0129 +vn 0.9998 0.0191 -0.0038 +vn -0.9999 0.0095 -0.0143 +vn -0.9970 0.0103 0.0773 +vn -0.9945 0.0323 0.0997 +vn -0.9976 -0.0275 -0.0638 +vn 0.0233 -0.4056 0.9138 +vn 0.0006 -0.6198 0.7847 +vn -0.0012 -0.6354 0.7721 +vn 0.0244 -0.3942 0.9187 +vn -0.0222 0.5554 0.8313 +vn -0.0032 0.9978 0.0667 +vn 0.0147 0.9960 -0.0883 +vn 0.0163 0.9946 -0.1022 +vn -0.0042 0.9971 0.0759 +vn -0.0141 0.1229 -0.9923 +vn -0.0072 0.0485 -0.9988 +vn -0.0068 0.0442 -0.9990 +vn -0.0145 0.1276 -0.9917 +vn 0.0030 -0.8751 -0.4840 +vn 0.0018 -0.8827 -0.4699 +vn -0.0191 -0.9768 -0.2134 +vn -0.0204 -0.9803 -0.1965 +vn -0.9875 0.1039 0.1182 +vn -0.9950 -0.0965 0.0247 +vn -0.9954 -0.0016 0.0959 +vn -0.9936 -0.1017 0.0482 +vn -0.9954 -0.0778 -0.0553 +vn -0.9957 -0.0426 -0.0828 +vn -0.9957 -0.0018 -0.0923 +vn -0.9955 0.0669 -0.0664 +vn -0.9938 0.0865 -0.0698 +vn -0.9955 0.0946 0.0104 +vn 0.0348 -0.5238 0.8511 +vn 0.0456 -0.5160 0.8554 +vn -0.0052 -0.5520 0.8338 +vn 0.0818 -0.4889 0.8685 +vn 0.0422 0.7692 0.6377 +vn 0.0700 0.7846 0.6160 +vn -0.0543 0.7070 0.7051 +vn 0.1542 0.8246 0.5443 +vn -0.1536 0.9441 -0.2915 +vn 0.1650 0.4623 -0.8712 +vn 0.1642 0.4630 -0.8710 +vn 0.2085 0.4246 -0.8811 +vn 0.1353 0.4869 -0.8629 +vn -0.1354 -0.4794 -0.8671 +vn 0.2139 -0.8672 -0.4496 +vn 0.0941 -0.9437 -0.3171 +vn 0.0963 -0.9426 -0.3196 +vn -0.0645 -0.9895 -0.1297 +vn -0.0912 -0.3260 -0.9410 +vn 0.4922 0.3316 -0.8049 +vn -0.2678 0.9461 0.1819 +vn 0.1108 -0.6506 0.7513 +vn 0.2714 -0.5054 0.8191 +vn 0.2795 -0.4970 0.8215 +vn 0.4077 -0.3479 0.8443 +vn -0.9590 0.0275 0.2822 +vn 0.0586 0.9242 0.3774 +vn -0.1218 0.9770 0.1750 +vn 0.0295 0.9332 0.3582 +vn -0.1695 0.9731 0.1563 +vn 0.1234 0.2179 -0.9681 +vn -0.0148 0.1678 -0.9857 +vn 0.0866 0.2049 -0.9749 +vn -0.0545 0.1526 -0.9868 +vn 0.0476 -0.9135 -0.4040 +vn -0.0517 -0.9318 -0.3593 +vn 0.0106 -0.9216 -0.3879 +vn -0.0863 -0.9355 -0.3427 +vn 0.1161 -0.7557 0.6445 +vn -0.0215 -0.7135 0.7003 +vn 0.0690 -0.7432 0.6655 +vn -0.0591 -0.6990 0.7126 +vn -0.5205 -0.8438 -0.1306 +vn 0.5452 0.0385 -0.8374 +vn -0.4396 0.6348 -0.6354 +vn 0.5048 0.8417 -0.1915 +vn -0.6378 0.6669 0.3853 +vn 0.5514 0.3830 0.7411 +vn -0.3926 -0.4976 0.7735 +vn -0.1963 -0.4850 0.8522 +vn -0.4895 -0.4952 0.7178 +vn -0.1432 -0.4781 0.8666 +vn 0.1045 -0.9788 -0.1762 +vn -0.0854 -0.9676 -0.2376 +vn 0.1570 -0.9749 -0.1577 +vn -0.1381 -0.9575 -0.2531 +vn 0.0772 -0.4089 -0.9093 +vn 0.0496 0.8497 0.5249 +vn -0.9882 0.0662 -0.1378 +vn -0.9498 0.1355 -0.2819 +vn -0.9924 0.0532 -0.1108 +vn 0.9867 0.0483 -0.1551 +vn 0.9939 0.0327 -0.1049 +vn 0.9504 0.0926 -0.2970 +vn -0.4508 0.5488 -0.7040 +vn -0.3472 0.6983 -0.6259 +vn -0.4795 0.4978 -0.7227 +vn 0.3952 0.3342 -0.8557 +vn -0.3987 -0.7495 -0.5285 +vn 0.3459 -0.6190 -0.7051 +vn -0.3848 -0.7630 0.5194 +vn 0.5138 -0.3753 0.7715 +vn -0.4175 0.2881 0.8618 +vn 0.3138 0.8010 0.5098 +vn 0.6528 0.2594 0.7117 +vn -0.1316 -0.9148 -0.3820 +vn 0.0392 -0.2292 -0.9726 +vn -0.1411 -0.1622 -0.9766 +vn 0.0954 -0.2485 -0.9639 +vn -0.1894 -0.1430 -0.9714 +vn 0.2640 0.6199 -0.7389 +vn -0.5527 0.7550 -0.3528 +vn 0.5066 0.8565 0.0989 +vn -0.4701 0.4046 0.7844 +vn 0.0356 0.2959 0.9546 +vn 0.0483 -0.6562 0.7530 +vn -0.1961 -0.7063 0.6803 +vn 0.1318 -0.6287 0.7664 +vn -0.2586 -0.7116 0.6533 +vn -0.5682 0.2972 -0.7674 +vn 0.4821 -0.6042 -0.6345 +vn -0.9970 -0.0780 0.0016 +vn -0.9646 -0.2638 0.0056 +vn -0.9336 -0.3583 0.0075 +vn 0.9838 -0.1639 0.0729 +vn 0.9402 -0.3113 0.1385 +vn 0.9920 -0.1156 0.0514 +vn 0.9992 -0.0399 0.0099 +vn 0.9994 0.0088 -0.0326 +vn 0.9985 0.0375 0.0392 +vn -0.9993 0.0252 0.0276 +vn -0.9972 -0.0220 0.0710 +vn -0.9993 0.0226 0.0300 +vn -0.9975 0.0689 -0.0128 +vn 0.0638 -0.6527 0.7549 +vn -0.0860 -0.9953 -0.0440 +vn 0.0270 -0.7076 -0.7061 +vn -0.0857 -0.0252 -0.9960 +vn 0.0453 0.6956 -0.7170 +vn -0.0703 0.9923 0.1018 +vn -0.0553 0.9803 0.1895 +vn 0.0057 0.8615 0.5077 +vn 0.0209 0.8158 0.5779 +vn -0.0797 0.0538 0.9954 +vn -0.9848 0.0031 -0.1734 +vn -0.9712 0.2384 0.0023 +vn -0.9916 0.0943 -0.0882 +vn -0.9920 -0.1260 0.0059 +vn -0.9897 -0.1428 -0.0128 +vn -0.9909 -0.0819 0.1069 +vn -0.9855 0.0019 0.1698 +vn -0.9918 0.0871 0.0933 +vn -0.9905 -0.0721 -0.1173 +vn -0.1465 -0.8855 0.4410 +vn 0.1745 -0.9636 -0.2026 +vn 0.0476 -0.9130 -0.4051 +vn 0.0627 -0.9218 -0.3825 +vn -0.0746 -0.8155 -0.5740 +vn 0.1065 -0.3615 -0.9263 +vn -0.1875 0.0920 -0.9780 +vn 0.2346 0.7065 -0.6677 +vn -0.2107 0.9762 0.0523 +vn -0.1148 0.9815 0.1535 +vn -0.1325 0.9819 0.1352 +vn -0.0005 0.9636 0.2674 +vn 0.0817 0.2000 0.9764 +vn -0.0100 0.0984 0.9951 +vn -0.0150 0.0927 0.9956 +vn -0.0934 0.0040 0.9956 +vn 0.1035 -0.6000 0.7933 +vn 0.6338 -0.2109 0.7442 +vn 0.5539 -0.2889 0.7809 +vn 0.4668 -0.3626 0.8066 +vn 0.2740 -0.4945 0.8249 +vn 0.0040 -0.6766 -0.7363 +vn 0.7930 0.3132 -0.5225 +vn 0.1947 0.9427 -0.2710 +vn 0.9706 0.1464 0.1910 +vn 0.9949 0.0140 0.0996 +vn 0.9960 -0.0085 0.0893 +vn 0.9995 0.0200 0.0234 +vn -1.0000 -0.0002 -0.0004 +vn -1.0000 -0.0002 -0.0003 +vn 0.9604 0.1185 0.2521 +vn 0.9771 0.0572 0.2051 +vn 0.9797 0.0483 0.1947 +vn 0.9995 0.0299 -0.0031 +vn 0.9985 0.0447 0.0330 +vn 0.9497 0.1363 0.2819 +vn -0.9967 0.0707 0.0400 +vn -0.8802 0.1364 0.4545 +vn -0.9169 0.1732 0.3596 +vn -0.9572 0.0841 0.2770 +vn -0.9986 0.0527 -0.0029 +vn -0.9884 0.0594 0.1398 +vn 0.9604 0.1185 0.2520 +vn 0.9497 0.1362 0.2818 +vn -0.9931 0.1062 0.0498 +vn -0.8966 0.1661 0.4105 +vn -0.8929 0.1800 0.4126 +vn -0.9564 0.0858 0.2793 +vn -0.9964 0.0842 -0.0046 +vn -0.9887 0.0585 0.1378 +vn -0.8965 0.1662 0.4106 +vn -0.8929 0.1800 0.4128 +vn 0.9801 0.0782 0.1825 +vn 0.9855 0.0565 0.1598 +vn 0.9865 0.0526 0.1550 +vn 0.9996 0.0104 0.0247 +vn 0.9752 0.0883 0.2028 +vn 0.9805 0.0772 0.1808 +vn 0.9857 0.0564 0.1589 +vn 0.9866 0.0525 0.1542 +vn 0.9996 0.0105 0.0247 +vn 0.9757 0.0872 0.2009 +vn -0.9982 -0.0582 0.0164 +vn -0.9986 -0.0260 0.0457 +vn -0.9922 0.0487 0.1145 +vn -0.9898 0.0576 0.1302 +vn -0.0614 0.5427 0.8377 +vn -0.0001 0.5506 0.8347 +vn -0.0673 0.5418 0.8378 +vn 0.0062 0.5513 0.8343 +vn 0.0134 0.6035 0.7972 +vn 0.0134 0.6036 0.7972 +vn 0.0112 0.6037 0.7972 +vn 1.0000 0.0078 -0.0040 +vn 0.9958 0.0862 -0.0311 +vn 0.9621 0.2716 0.0258 +vn 0.9995 0.0078 0.0298 +vn 0.9896 0.1361 0.0475 +vn 0.9891 0.1340 0.0617 +vn 0.9997 -0.0025 0.0255 +vn -1.0000 -0.0000 -0.0003 +vn -1.0000 0.0000 -0.0004 +vn -0.9999 0.0011 0.0141 +vn -0.9949 -0.0982 -0.0210 +vn -0.9674 0.2461 0.0594 +vn -1.0000 0.0001 -0.0031 +vn -0.9736 0.2280 0.0054 +vn -0.9993 0.0161 0.0326 +vn 0.9868 0.0026 0.1620 +vn 0.9881 0.0051 0.1535 +vn 0.9879 0.0046 0.1552 +vn 0.9856 0.0004 0.1692 +vn -0.9851 0.0021 0.1720 +vn -0.9863 0.0043 0.1648 +vn -0.9866 0.0048 0.1629 +vn -0.9837 -0.0002 0.1799 +vn -0.9985 -0.0517 -0.0195 +vn -0.9782 0.2072 -0.0136 +vn -0.9995 0.0321 -0.0080 +vn -0.9728 0.2303 0.0247 +vn -0.9620 0.2580 0.0894 +vn -0.9875 0.1314 0.0868 +vn -0.9997 0.0179 0.0186 +vn 0.9998 0.0174 -0.0079 +vn 0.9832 0.1673 -0.0730 +vn 0.9866 0.1496 -0.0653 +vn 0.9914 0.1296 -0.0194 +vn 0.9908 0.1322 -0.0280 +vn 0.9987 -0.0500 0.0135 +vn 1.0000 0.0001 0.0023 +vn -0.9862 -0.0030 0.1657 +vn -0.9874 -0.0052 0.1582 +vn -0.9845 -0.0002 0.1754 +vn -0.9877 -0.0058 0.1562 +vn 0.9999 0.0123 0.0002 +vn 0.9993 0.0087 0.0350 +vn 0.9836 0.1771 0.0346 +vn 0.9862 0.1546 0.0586 +vn 0.9995 -0.0036 0.0298 +vn -0.9997 0.0196 -0.0132 +vn -0.9971 0.0524 -0.0559 +vn -0.9976 0.0475 -0.0506 +vn 0.0426 0.9988 0.0221 +vn -0.9877 0.1441 -0.0605 +vn -0.9853 0.1578 -0.0662 +vn -1.0000 0.0078 -0.0020 +vn -0.9942 0.1076 0.0003 +vn -0.9729 0.2191 0.0744 +vn -0.9893 0.1228 0.0793 +vn -0.9997 0.0159 0.0166 +vn 0.9922 0.1050 -0.0668 +vn 0.9998 0.0132 -0.0145 +vn 0.9729 0.2202 -0.0704 +vn 0.9917 0.1288 -0.0017 +vn 1.0000 0.0056 0.0011 +vn 0.9854 0.0036 0.1701 +vn 0.9877 0.0076 0.1564 +vn 0.9872 0.0068 0.1591 +vn 0.9835 0.0004 0.1809 +vn 0.4919 0.6757 0.5491 +vn 0.4248 0.6893 0.5869 +vn 0.5017 0.6733 0.5431 +vn 1.0000 0.0044 -0.0021 +vn 0.9957 0.0912 -0.0177 +vn 0.9620 0.2713 0.0297 +vn 0.9765 -0.1991 -0.0827 +vn 0.9999 -0.0114 -0.0016 +vn 0.9969 0.0714 0.0342 +vn 0.9716 -0.2184 -0.0907 +vn -1.0000 -0.0078 -0.0034 +vn -0.9908 -0.1241 -0.0541 +vn -0.9927 -0.1109 -0.0483 +vn -0.9590 0.2827 -0.0222 +vn -0.9670 0.2543 -0.0164 +vn -0.9871 0.1451 -0.0671 +vn -0.9996 -0.0020 -0.0280 +vn -0.9994 0.0090 -0.0326 +vn 0.0310 0.8075 0.5891 +vn 0.2377 0.8107 0.5351 +vn -0.0063 0.8030 0.5959 +vn 0.2574 0.8090 0.5285 +vn -0.4393 0.8522 0.2841 +vn 0.5036 0.8586 0.0957 +vn -0.5036 0.8586 -0.0957 +vn 0.4393 0.8523 -0.2841 +vn -0.2379 0.8106 -0.5351 +vn -0.0311 0.8075 -0.5891 +vn -0.2576 0.8089 -0.5284 +vn 0.0063 0.8030 -0.5960 +vn -0.0139 0.8029 0.5959 +vn 0.5060 0.7221 0.4717 +vn -0.7324 0.6459 0.2153 +vn 0.7886 0.6111 0.0681 +vn -0.7886 0.6111 -0.0681 +vn 0.7324 0.6459 -0.2153 +vn -0.5060 0.7221 -0.4717 +vn 0.0138 0.8029 -0.5959 +vn -0.0172 -0.0054 0.9998 +vn 0.0170 0.0074 0.9998 +vn -0.0308 -0.0106 0.9995 +vn 0.0305 0.0125 0.9995 +vn 0.0019 0.9419 0.3360 +vn 0.0161 0.9736 0.2277 +vn 0.0026 0.9374 0.3483 +vn 0.0240 0.8353 0.5493 +vn -0.0099 0.7613 0.6483 +vn 0.0160 0.8736 0.4864 +vn -0.0087 0.7577 0.6525 +vn 0.0210 0.8730 0.4873 +vn 0.9999 0.0107 -0.0110 +vn 0.9764 0.0597 -0.2078 +vn 0.9972 0.0473 -0.0583 +vn 0.9957 -0.0112 -0.0922 +vn 1.0000 -0.0013 -0.0055 +vn -0.9745 0.0805 -0.2093 +vn -0.9988 0.0479 -0.0134 +vn -0.9983 0.0531 -0.0246 +vn -1.0000 -0.0022 -0.0067 +vn -0.9986 -0.0094 -0.0530 +vn -0.9809 0.1037 -0.1644 +vn -0.0060 0.5959 -0.8030 +vn 0.0123 0.4987 -0.8667 +vn -0.0193 0.5982 -0.8011 +vn -0.0290 0.4079 -0.9126 +vn 0.0276 0.1651 -0.9859 +vn -0.0493 0.0161 -0.9987 +vn 0.1476 -0.1393 -0.9792 +vn 0.1619 -0.1404 -0.9768 +vn -0.1271 -0.5437 -0.8296 +vn -0.0059 -0.5630 -0.8264 +vn -0.1368 -0.5418 -0.8293 +vn 0.0077 -0.5647 -0.8253 +vn 0.9998 -0.0081 -0.0184 +vn 0.9769 -0.0767 -0.1996 +vn 0.9986 -0.0130 -0.0513 +vn 0.8938 0.1348 -0.4277 +vn 0.9767 0.1074 -0.1859 +vn 0.9315 0.0491 -0.3603 +vn 0.8760 -0.0363 -0.4809 +vn 0.9548 -0.0951 -0.2816 +vn 0.9757 -0.0841 -0.2024 +vn 0.9986 -0.0523 -0.0122 +vn -0.9997 -0.0089 -0.0208 +vn -0.9792 -0.0694 -0.1906 +vn -0.9851 -0.0398 -0.1675 +vn -0.9776 -0.0803 -0.1947 +vn -0.9160 -0.0022 -0.4012 +vn -0.9572 0.0017 -0.2893 +vn -0.8794 0.1331 -0.4571 +vn -0.9784 0.1112 -0.1742 +vn -0.9988 -0.0038 -0.0483 +vn -0.9986 -0.0530 -0.0027 +vn -0.0420 0.5898 -0.8065 +vn 0.0174 -0.5892 -0.8078 +vn 0.7926 0.1319 -0.5953 +vn 0.7298 0.1347 -0.6702 +vn 0.9317 0.1581 -0.3272 +vn 0.9805 0.0130 -0.1960 +vn 0.9814 0.0244 -0.1905 +vn 0.9814 0.0596 -0.1825 +vn 0.9780 -0.0629 -0.1988 +vn 0.9839 -0.0248 -0.1770 +vn 0.9901 -0.0620 -0.1258 +vn 0.9990 0.0224 -0.0374 +vn 0.9987 0.0510 -0.0095 +vn 0.9995 0.0324 0.0033 +vn 0.9984 0.0470 -0.0310 +vn -0.9998 -0.0078 -0.0180 +vn -0.9808 -0.0707 -0.1817 +vn -0.9731 -0.0684 -0.2200 +vn -0.9776 -0.0775 -0.1957 +vn -0.9261 -0.0303 -0.3761 +vn -0.9415 0.0229 -0.3362 +vn -0.8771 0.1397 -0.4595 +vn -0.9766 0.1135 -0.1826 +vn -0.9988 -0.0056 -0.0494 +vn -0.9988 -0.0490 -0.0076 +vn -0.0140 0.5891 -0.8080 +vn 0.0160 -0.5892 -0.8078 +vn 0.9981 -0.0507 -0.0357 +vn 0.9474 -0.1260 -0.2941 +vn 0.9992 -0.0385 -0.0070 +vn 0.9228 0.1188 -0.3665 +vn 0.9399 0.0438 -0.3387 +vn 0.9414 0.1430 -0.3053 +vn 0.9398 0.0461 -0.3385 +vn 0.9266 -0.0635 -0.3707 +vn 0.9296 -0.0876 -0.3581 +vn 0.9414 -0.1421 -0.3060 +vn 0.9995 0.0299 0.0030 +vn 0.9986 0.0440 -0.0304 +vn -0.9817 -0.0683 -0.1775 +vn -0.9864 -0.0401 -0.1597 +vn -0.9690 -0.0184 -0.2464 +vn -0.9753 0.0121 -0.2206 +vn -0.9090 0.1334 -0.3950 +vn -0.9651 0.1410 -0.2207 +vn -0.9986 -0.0025 -0.0524 +vn 0.9795 -0.0702 -0.1890 +vn 0.7836 0.1308 -0.6073 +vn 0.6886 0.1404 -0.7114 +vn 0.9312 0.1580 -0.3285 +vn 0.9737 -0.0044 -0.2278 +vn 0.9832 0.0385 -0.1785 +vn 0.9859 0.0521 -0.1589 +vn 0.9881 -0.0325 -0.1501 +vn -0.9966 -0.0744 -0.0363 +vn -0.9984 -0.0563 0.0064 +vn -0.9187 -0.1584 -0.3618 +vn -0.9255 -0.0805 -0.3701 +vn -0.9092 -0.1811 -0.3748 +vn -0.9243 -0.0579 -0.3773 +vn -0.9217 0.0414 -0.3857 +vn -0.9235 0.0356 -0.3820 +vn -0.9097 0.1482 -0.3880 +vn -0.9493 0.1685 -0.2654 +vn -0.9982 0.0048 -0.0594 +vn 0.0174 -0.5891 -0.8078 +vn 0.9998 -0.0080 -0.0181 +vn 0.9769 -0.0766 -0.1993 +vn 0.8938 0.1349 -0.4278 +vn 0.9767 0.1075 -0.1859 +vn -0.9864 -0.0401 -0.1596 +vn 0.9998 -0.0087 -0.0198 +vn 0.9774 -0.0753 -0.1975 +vn 0.8812 0.1037 -0.4612 +vn 0.9549 0.0622 -0.2904 +vn 0.9747 0.0861 -0.2062 +vn 0.8970 -0.0223 -0.4414 +vn 0.9634 -0.0831 -0.2549 +vn 0.9762 -0.0829 -0.2003 +vn 0.9997 0.0094 -0.0219 +vn -0.9808 -0.0708 -0.1817 +vn -0.8772 0.1397 -0.4594 +vn -0.0140 0.5891 -0.8079 +vn 0.0076 0.9962 0.0869 +vn 0.0106 0.9942 0.1066 +vn -0.0104 0.9917 -0.1281 +vn 0.0097 0.9610 -0.2763 +vn -0.0011 0.9178 -0.3970 +vn 0.0075 0.9718 -0.2358 +vn 0.0130 0.8370 -0.5471 +vn -0.6863 0.3668 -0.6280 +vn 0.7861 0.3911 -0.4787 +vn 0.0499 0.7633 -0.6441 +vn -0.1361 0.7405 -0.6581 +vn -0.1948 0.7331 -0.6516 +vn -0.6807 0.6001 -0.4202 +vn 0.7375 0.1146 -0.6655 +vn -0.6252 -0.1595 -0.7640 +vn 0.5692 -0.4378 -0.6959 +vn -0.2148 -0.6121 -0.7611 +vn -0.2178 -0.5897 -0.7777 +vn -0.1603 -0.5734 -0.8035 +vn -0.3491 -0.6039 -0.7165 +vn 0.3620 -0.8079 -0.4650 +vn 0.6639 -0.5988 0.4480 +vn 0.6718 -0.5946 0.4417 +vn 0.6002 -0.6284 0.4948 +vn 0.5474 -0.6485 0.5289 +vn -0.2228 -0.4655 0.8566 +vn 0.0623 -0.1764 0.9823 +vn 0.3162 -0.1547 0.9360 +vn 0.2120 -0.1651 0.9632 +vn 0.6325 0.1486 0.7602 +vn -0.5402 0.0414 0.8405 +vn -0.5631 0.2665 0.7822 +vn 0.8176 0.3550 0.4533 +vn 0.5123 0.5581 0.6528 +vn 0.7166 0.4412 0.5402 +vn 0.5006 0.5632 0.6574 +vn -0.5176 0.6659 0.5372 +vn 0.7876 0.5797 -0.2090 +vn -0.8625 0.5025 -0.0603 +vn -0.9539 0.2993 0.0219 +vn -0.9631 0.2675 -0.0303 +vn 0.6756 0.6958 0.2437 +vn 0.1744 0.6816 -0.7106 +vn 0.0972 0.8125 -0.5748 +vn 0.1461 0.7807 -0.6076 +vn 0.1080 0.6600 -0.7434 +vn 0.2691 0.4505 -0.8513 +vn 0.2765 -0.2467 -0.9288 +vn -0.2506 -0.5951 -0.7636 +vn -0.0312 -0.7075 -0.7061 +vn -0.2578 -0.5934 -0.7625 +vn -0.0311 -0.7291 -0.6837 +vn -0.0524 -0.7985 -0.5998 +vn 0.4536 -0.7210 0.5239 +vn 0.4625 -0.6725 0.5778 +vn 0.4399 -0.7146 0.5440 +vn 0.6117 -0.5203 0.5959 +vn 0.6446 -0.4838 0.5919 +vn -0.7258 -0.3320 0.6025 +vn 0.6296 -0.2503 0.7354 +vn 0.0354 -0.0743 0.9966 +vn -0.0121 -0.0702 0.9975 +vn -0.2092 -0.1646 0.9639 +vn -0.0083 0.1712 0.9852 +vn -0.0101 0.1802 0.9836 +vn -0.0196 0.3210 0.9469 +vn 0.8398 0.2294 0.4920 +vn -0.9945 0.0890 -0.0546 +vn 0.1800 0.7029 0.6882 +vn 0.0730 0.6186 0.7823 +vn 0.1694 0.6087 0.7751 +vn 0.2590 0.8377 -0.4808 +vn -0.8450 0.5335 -0.0350 +vn 0.7834 0.6006 0.1597 +vn -0.7895 0.5396 0.2925 +vn 0.1405 0.6615 0.7367 +vn 0.2038 0.7951 0.5712 +vn -0.0792 0.6155 -0.7841 +vn 0.1841 0.7541 -0.6304 +vn 0.3756 0.7421 -0.5551 +vn -0.0823 0.6927 -0.7165 +vn -0.1483 0.5115 -0.8464 +vn 0.6870 0.1408 -0.7129 +vn -0.5321 -0.1791 -0.8275 +vn 0.2715 -0.2508 -0.9292 +vn -0.2436 -0.5929 -0.7675 +vn 0.0054 -0.6929 -0.7210 +vn -0.2524 -0.5910 -0.7662 +vn -0.0223 -0.7430 -0.6689 +vn -0.0655 -0.7975 -0.5997 +vn 0.4167 -0.6886 0.5934 +vn 0.4115 -0.7353 0.5385 +vn 0.4314 -0.7408 0.5149 +vn 0.5626 -0.5402 0.6259 +vn 0.5998 -0.5008 0.6240 +vn 0.6505 -0.2416 0.7200 +vn 0.4167 -0.1485 0.8968 +vn 0.6215 -0.2341 0.7476 +vn 0.5017 -0.0522 0.8635 +vn 0.5303 -0.0313 0.8472 +vn -0.2764 0.1029 0.9555 +vn -0.1220 0.2570 0.9587 +vn -0.3421 0.0314 0.9391 +vn -0.0447 0.3277 0.9437 +vn 0.0409 0.6087 0.7923 +vn 0.0680 0.6182 0.7831 +vn 0.1625 0.6052 0.7793 +vn 0.3617 0.7325 -0.5767 +vn -0.7948 0.5315 -0.2929 +vn 0.7243 0.6605 -0.1980 +vn -0.7709 0.6368 -0.0129 +vn 0.6524 0.7513 0.0997 +vn -0.3915 0.8059 0.4441 +vn -0.1154 0.6948 0.7099 +vn -0.4147 0.7963 0.4403 +vn -0.0711 0.6517 0.7552 +vn -0.0361 0.6854 -0.7272 +vn 0.1870 0.7494 -0.6352 +vn 0.1339 0.7656 -0.6292 +vn -0.0734 0.6891 -0.7209 +vn -0.1449 0.5258 -0.8382 +vn -0.5547 -0.5201 -0.6494 +vn -0.4325 -0.6610 -0.6132 +vn -0.5880 -0.4852 -0.6471 +vn -0.4295 -0.7095 -0.5587 +vn -0.4525 -0.7205 -0.5255 +vn 0.4535 -0.7210 0.5239 +vn 0.6117 -0.5202 0.5959 +vn 0.6447 -0.4837 0.5919 +vn -0.7255 -0.3322 0.6027 +vn 0.6506 -0.2416 0.7199 +vn 0.4168 -0.1485 0.8968 +vn 0.6215 -0.2342 0.7476 +vn 0.0408 0.6087 0.7923 +vn -0.7391 0.5831 -0.3371 +vn 0.6705 0.7107 -0.2130 +vn -0.6362 0.7648 -0.1015 +vn 0.7292 0.6743 0.1163 +vn -0.2554 0.8385 0.4813 +vn -0.0682 0.6456 0.7607 +vn -0.1100 0.6873 0.7180 +vn -0.4885 0.8716 0.0405 +vn 0.2614 0.9222 -0.2850 +vn -0.2069 0.7796 -0.5910 +vn -0.0911 0.7501 -0.6550 +vn -0.0565 0.6905 -0.7212 +vn -0.0539 0.7258 -0.6858 +vn 0.7292 0.1349 -0.6708 +vn -0.6364 -0.0804 -0.7672 +vn 0.6704 -0.1934 -0.7163 +vn -0.7466 -0.3187 -0.5839 +vn 0.6878 -0.4567 -0.5642 +vn 0.4621 -0.6835 -0.5651 +vn 0.6547 -0.4944 -0.5718 +vn 0.4283 -0.7266 -0.5372 +vn 0.4416 -0.7361 -0.5129 +vn -0.0702 0.6491 0.7574 +vn -0.1103 0.6893 0.7161 +vn -0.2577 0.8434 0.4714 +vn 0.4313 0.8029 0.4114 +vn 0.1647 0.7109 -0.6837 +vn 0.1536 0.7829 -0.6029 +vn 0.1301 0.7877 -0.6022 +vn 0.1018 0.6561 -0.7478 +vn 0.2767 -0.2467 -0.9288 +vn -0.2430 -0.5930 -0.7676 +vn 0.0055 -0.6929 -0.7210 +vn -0.2519 -0.5911 -0.7663 +vn 0.5892 -0.2332 0.7736 +vn 0.2820 -0.2428 0.9282 +vn 0.2098 0.7682 -0.6048 +vn -0.7119 0.5982 -0.3679 +vn 0.7833 0.5955 -0.1785 +vn -0.8246 0.5653 -0.0218 +vn -0.3911 0.8061 0.4442 +vn -0.4143 0.7965 0.4403 +vn -0.0047 0.7917 -0.6108 +vn 0.4041 0.6399 -0.6537 +vn 0.3861 0.5871 -0.7114 +vn 0.5394 0.3992 -0.7414 +vn -0.8248 0.0211 -0.5650 +vn 0.6644 -0.1807 -0.7252 +vn -0.7499 -0.3053 -0.5869 +vn 0.3149 -0.5240 -0.7913 +vn 0.2789 -0.6480 -0.7087 +vn 0.1557 -0.6702 -0.7257 +vn 0.1047 -0.7809 -0.6158 +vn 0.0037 -0.7824 -0.6228 +vn 0.0256 -0.8295 -0.5580 +vn 0.3309 -0.7390 0.5868 +vn 0.4263 -0.6146 0.6637 +vn 0.6296 -0.2503 0.7355 +vn 0.0320 -0.2374 0.9709 +vn 0.2875 0.0191 0.9576 +vn -0.0077 0.1623 0.9867 +vn -0.0097 0.1736 0.9848 +vn -0.0186 0.3065 0.9517 +vn 0.4906 0.4975 0.7154 +vn 0.4187 0.6253 0.6585 +vn 0.3013 0.6449 0.7024 +vn 0.0552 0.7449 0.6649 +vn -0.2612 0.7332 -0.6278 +vn -0.1108 0.7284 -0.6761 +vn -0.0000 0.6486 -0.7611 +vn -0.2832 0.8170 -0.5024 +vn 0.3782 0.8058 -0.4556 +vn -0.0071 0.9948 -0.1014 +vn -0.4550 0.7694 0.4483 +vn -0.3488 0.6417 0.6830 +vn -0.2464 0.6750 0.6954 +vn -0.1326 0.5907 0.7959 +vn 0.0114 0.5369 -0.8436 +vn 0.0125 0.4264 -0.9044 +vn 0.0259 0.2366 -0.9713 +vn -0.0057 0.3603 -0.9328 +vn 0.0015 0.1767 -0.9843 +vn -0.0082 0.0446 -0.9990 +vn 0.0329 -0.1186 -0.9924 +vn 0.0005 -0.3130 -0.9498 +vn 0.0042 -0.3784 -0.9257 +vn 0.0138 -0.2359 -0.9717 +vn 0.0034 -0.5321 -0.8467 +vn -0.0025 -0.0027 1.0000 +vn -0.0150 -0.0023 0.9999 +vn 0.0004 -0.0020 1.0000 +vn -0.0130 0.2441 0.9697 +vn 0.0216 0.7620 -0.6472 +vn 0.0147 0.7695 -0.6384 +vn 0.0088 0.7760 -0.6307 +vn 0.0277 0.7552 -0.6550 +vn -0.9974 -0.0275 -0.0661 +vn -0.9884 -0.0405 -0.1466 +vn -0.9978 -0.0276 -0.0607 +vn -0.9582 0.2860 -0.0056 +vn -0.9906 0.1187 0.0674 +vn -0.9976 0.0607 0.0324 +vn -0.9989 -0.0206 -0.0427 +vn -0.9992 -0.0301 -0.0275 +vn -0.9891 0.1462 0.0155 +vn -0.9993 0.0319 0.0192 +vn -0.9996 -0.0203 -0.0187 +vn -0.9993 -0.0377 -0.0065 +vn -0.9998 0.0151 0.0138 +vn -0.9999 0.0081 0.0075 +vn -0.9972 -0.0608 -0.0430 +vn -0.9616 -0.2647 -0.0732 +vn -0.9869 -0.1412 -0.0779 +vn 0.0038 0.9881 0.1540 +vn -0.0973 0.9891 0.1104 +vn -0.0304 0.9898 0.1395 +vn -0.1264 0.9872 0.0975 +vn 0.1219 -0.0697 -0.9901 +vn 0.0251 -0.1054 -0.9941 +vn 0.0961 -0.0793 -0.9922 +vn -0.0031 -0.1156 -0.9933 +vn 0.1208 0.9719 0.2022 +vn 0.0495 0.9836 0.1732 +vn 0.1765 0.9584 0.2243 +vn -0.1366 0.8001 -0.5841 +vn -0.3112 0.7315 -0.6066 +vn 0.3156 -0.0239 -0.9486 +vn 0.0795 -0.1272 -0.9887 +vn 0.2609 -0.0488 -0.9641 +vn -0.0039 -0.1612 -0.9869 +vn -0.0931 0.9893 0.1123 +vn -0.0290 0.9897 0.1401 +vn -0.1212 0.9876 0.0998 +vn 0.1432 -0.1004 -0.9846 +vn 0.0436 -0.1420 -0.9889 +vn 0.1133 -0.1131 -0.9871 +vn 0.1018 -0.0250 -0.9945 +vn 0.0296 -0.0625 -0.9976 +vn 0.0816 -0.0355 -0.9960 +vn -0.0024 -0.0789 -0.9969 +vn 0.0443 0.9834 0.1759 +vn 0.2111 0.9735 0.0877 +vn -0.0599 0.9719 0.2275 +vn 0.2800 0.9587 0.0491 +vn -0.3130 0.7520 -0.5801 +vn 0.2327 0.6308 -0.7402 +vn 0.0016 -0.1184 -0.9930 +vn -0.0021 -0.1197 -0.9928 +vn 0.0003 -0.1189 -0.9929 +vn -0.0032 -0.1201 -0.9928 +vn -0.0273 0.9733 0.2278 +vn 0.3773 0.8920 -0.2489 +vn -0.0957 0.7881 -0.6080 +vn 0.1668 0.0172 -0.9858 +vn 0.0727 -0.0603 -0.9955 +vn 0.1043 -0.0345 -0.9939 +vn -0.0014 -0.1201 -0.9928 +vn 0.0028 -0.0976 0.9952 +vn 0.4143 0.6910 0.5924 +vn -0.4650 0.8520 -0.2406 +vn -0.1427 0.9798 -0.1398 +vn -0.3055 0.9326 -0.1923 +vn -0.0369 0.9939 -0.1041 +vn 0.0041 -0.1750 0.9846 +vn -0.0859 -0.1315 0.9876 +vn -0.0302 -0.1586 0.9869 +vn -0.1138 -0.1176 0.9865 +vn 0.1432 0.9882 -0.0542 +vn 0.0341 0.9951 -0.0933 +vn 0.1181 0.9910 -0.0634 +vn 0.0036 0.9946 -0.1040 +vn 0.0014 -0.1161 0.9932 +vn -0.0127 -0.1048 0.9944 +vn -0.0094 -0.1075 0.9942 +vn -0.0236 -0.0961 0.9951 +vn -0.3357 0.7050 0.6247 +vn -0.3060 0.7102 0.6341 +vn 0.0267 0.9909 -0.1317 +vn 0.0135 0.9895 -0.1440 +vn 0.0150 0.9897 -0.1425 +vn 0.0013 0.9879 -0.1552 +vn 0.0304 -0.0981 0.9947 +vn 0.0286 0.5122 0.8584 +vn 0.4189 -0.0577 0.9062 +vn -0.1909 0.5177 0.8340 +vn -0.1908 0.5176 0.8340 +vn -0.0084 -0.0953 0.9954 +vn 0.0326 0.5124 0.8581 +vn 0.0225 -0.1998 0.9796 +vn -0.2206 -0.1076 0.9694 +vn -0.0480 -0.1744 0.9835 +vn -0.2607 -0.0911 0.9611 +vn 0.3134 0.3910 0.8654 +vn 0.0664 0.4906 0.8688 +vn 0.2710 0.4108 0.8705 +vn -0.0074 0.5134 0.8581 +vn 0.0173 0.0366 -0.9992 +vn 0.0061 0.0270 -0.9996 +vn -0.0128 0.9997 -0.0207 +vn -0.0149 0.9996 -0.0230 +vn -0.0005 0.6056 0.7958 +vn -0.0038 0.6084 0.7937 +vn -0.0048 0.9979 0.0653 +vn 0.0094 0.9970 0.0771 +vn -0.0055 0.4929 0.8701 +vn -0.0248 0.6265 0.7790 +vn 0.0151 0.5122 0.8587 +vn 0.9992 -0.0347 0.0174 +vn 0.9990 -0.0325 0.0307 +vn 0.9993 -0.0354 0.0144 +vn 0.9990 -0.0322 0.0311 +vn 0.9992 -0.0388 -0.0056 +vn 0.9988 -0.0296 -0.0383 +vn 0.9992 -0.0334 -0.0239 +vn 0.9988 -0.0192 -0.0451 +vn 0.9984 -0.0200 -0.0529 +vn 0.9985 -0.0339 -0.0438 +vn -0.9737 -0.2265 -0.0259 +vn -1.0000 -0.0013 0.0054 +vn -1.0000 -0.0005 0.0063 +vn -0.9996 0.0167 0.0214 +vn -0.9365 -0.3497 0.0254 +vn -0.9729 -0.2244 0.0552 +vn -1.0000 0.0023 0.0073 +vn -0.9998 -0.0049 0.0198 +vn -0.9479 -0.2869 0.1388 +vn -0.9952 -0.0700 0.0677 +vn -0.9991 -0.0350 0.0230 +vn -0.9998 -0.0179 0.0042 +vn -0.9996 -0.0232 0.0179 +vn -0.9992 0.0029 0.0410 +vn -0.9970 0.0670 -0.0392 +vn -0.9991 -0.0386 -0.0158 +vn -0.9997 -0.0008 -0.0239 +vn -0.9508 0.3097 -0.0075 +vn -0.9990 0.0266 -0.0350 +vn -0.9978 0.0285 -0.0592 +vn -0.9998 0.0169 -0.0056 +vn -0.9979 0.0283 -0.0579 +vn -0.9937 0.0343 -0.1067 +vn -0.9771 -0.0007 -0.2129 +vn 0.9989 0.0239 0.0396 +vn 0.8540 0.0277 0.5195 +vn 0.9917 -0.0566 0.1151 +vn 0.9650 -0.0667 0.2536 +vn 0.9982 0.0599 0.0080 +vn -0.9997 -0.0095 0.0234 +vn -0.9811 -0.0779 0.1769 +vn -0.9754 -0.0880 0.2021 +vn -0.9872 -0.0542 0.1498 +vn -0.9884 -0.0490 0.1439 +vn 0.9883 -0.0558 0.1418 +vn 0.9999 -0.0048 0.0122 +vn 0.9834 -0.0665 0.1691 +vn -0.9999 -0.0046 0.0140 +vn -0.9877 -0.0487 0.1483 +vn -0.9843 -0.0561 0.1674 +vn -0.9842 -0.0563 0.1676 +vn 0.9856 -0.0714 0.1533 +vn 0.9920 -0.0562 0.1129 +vn 0.9814 -0.0760 0.1761 +vn -0.9806 -0.0761 0.1809 +vn -0.9752 -0.0861 0.2041 +vn -0.9848 -0.0577 0.1640 +vn -0.9858 -0.0534 0.1592 +vn 0.9834 -0.0666 0.1691 +vn -0.9878 -0.0487 0.1483 +vn -0.9999 -0.0046 0.0141 +vn -0.9877 -0.0488 0.1487 +vn 0.9999 -0.0157 -0.0025 +vn 0.9955 -0.0489 0.0812 +vn 0.9998 -0.0185 0.0046 +vn 0.9938 -0.0549 0.0963 +vn -0.0010 -0.5507 0.8347 +vn 0.0536 -0.5437 0.8375 +vn -0.0065 -0.5513 0.8343 +vn 0.0590 -0.5430 0.8377 +vn -0.0155 -0.6038 0.7970 +vn 0.2145 -0.4770 0.8523 +vn -0.3310 -0.5204 0.7871 +vn 0.5769 -0.4045 0.7096 +vn 0.9988 -0.0110 0.0479 +vn 0.9758 -0.2035 0.0799 +vn 0.9992 0.0048 0.0409 +vn 0.9812 -0.1693 -0.0924 +vn 0.9989 -0.0116 -0.0464 +vn 0.9992 0.0043 -0.0394 +vn 0.9838 -0.1706 -0.0552 +vn 0.9595 -0.2807 -0.0243 +vn 0.9859 -0.1652 0.0283 +vn 0.9815 -0.1625 0.1009 +vn -1.0000 0.0007 -0.0004 +vn -1.0000 0.0002 -0.0000 +vn -1.0000 0.0008 -0.0005 +vn 0.9758 -0.2035 0.0800 +vn 0.9992 -0.0032 -0.0403 +vn 0.9829 -0.1590 -0.0933 +vn 0.9988 -0.0164 -0.0462 +vn 0.9835 -0.1740 -0.0496 +vn 0.9599 -0.2792 -0.0243 +vn 0.9772 -0.2098 0.0324 +vn 0.9735 -0.2004 0.1105 +vn -0.9990 -0.0098 -0.0426 +vn -0.9765 -0.2018 -0.0757 +vn -0.9993 0.0042 -0.0365 +vn -0.9794 -0.1746 0.1019 +vn -0.9986 -0.0160 0.0501 +vn -0.9991 -0.0008 0.0434 +vn -0.9596 -0.2802 0.0244 +vn -0.9811 -0.1863 0.0518 +vn -0.9772 -0.2099 -0.0323 +vn -0.9781 -0.1819 -0.1012 +vn 0.9793 -0.1943 -0.0562 +vn 0.9735 -0.2003 0.1105 +vn -0.9984 -0.0153 -0.0540 +vn -0.9718 -0.2194 -0.0867 +vn -0.9989 0.0006 -0.0469 +vn -0.9595 -0.2805 0.0245 +vn -0.9763 -0.2140 -0.0314 +vn -0.9695 -0.2142 -0.1191 +vn 0.9829 -0.1589 -0.0933 +vn 0.9989 -0.0145 -0.0453 +vn 0.9992 -0.0008 -0.0392 +vn -0.9990 -0.0125 -0.0438 +vn -0.9768 -0.2003 -0.0755 +vn -0.9993 0.0005 -0.0381 +vn -0.9772 -0.2099 -0.0324 +vn 0.9992 -0.0090 0.0393 +vn 0.9797 -0.1876 0.0704 +vn 0.9994 0.0039 0.0337 +vn 0.9600 -0.2790 -0.0242 +vn 0.9779 -0.2064 0.0331 +vn 0.9805 -0.1719 0.0948 +vn -0.9985 -0.0120 -0.0525 +vn -0.9714 -0.2212 -0.0869 +vn -0.9990 0.0052 -0.0449 +vn -0.9989 -0.0036 0.0459 +vn -0.9789 -0.1794 0.0978 +vn -0.9985 -0.0187 0.0524 +vn -0.9591 -0.2818 0.0245 +vn -0.9772 -0.2042 0.0583 +vn 0.9991 -0.0091 0.0423 +vn 0.9802 -0.1841 0.0726 +vn 0.9993 0.0049 0.0360 +vn 1.0000 0.0004 0.0002 +vn 0.9997 -0.0186 -0.0159 +vn 0.9818 -0.1699 -0.0848 +vn 0.9524 -0.3018 -0.0434 +vn 0.9747 -0.2235 -0.0076 +vn 0.9739 -0.2245 0.0340 +vn 0.9778 -0.1840 0.1003 +vn 0.0310 -0.8075 -0.5891 +vn 0.2379 -0.8106 -0.5351 +vn -0.0065 -0.8030 -0.5960 +vn 0.2576 -0.8089 -0.5284 +vn -0.4393 -0.8523 -0.2841 +vn 0.5036 -0.8586 -0.0957 +vn -0.5036 -0.8586 0.0957 +vn 0.4393 -0.8523 0.2841 +vn -0.2379 -0.8106 0.5351 +vn -0.0311 -0.8075 0.5891 +vn -0.2576 -0.8089 0.5284 +vn 0.0063 -0.8030 0.5960 +vn -0.0139 -0.8029 -0.5959 +vn 0.5060 -0.7221 -0.4717 +vn -0.7324 -0.6459 -0.2153 +vn 0.7886 -0.6111 -0.0681 +vn -0.7886 -0.6111 0.0681 +vn 0.7325 -0.6459 0.2153 +vn -0.5056 -0.7223 0.4718 +vn 0.0142 -0.8029 0.5959 +vn -0.0142 -0.8029 -0.5959 +vn 0.7324 -0.6459 0.2153 +vn -0.5060 -0.7221 0.4717 +vn 0.5056 -0.7223 -0.4718 +vn -0.7325 -0.6459 -0.2153 +vn 0.0139 -0.8029 0.5959 +vn 0.0083 -0.9377 0.3473 +vn 0.0275 -0.9551 0.2949 +vn 0.0166 -0.9573 0.2885 +vn 0.0294 -0.9740 0.2245 +vn 0.0149 -0.9246 0.3808 +vn -0.0029 -0.7297 0.6838 +vn 0.0051 -0.7430 0.6693 +vn 0.0011 -0.7245 0.6892 +vn 0.0162 -0.8477 -0.5302 +vn 0.0249 -0.9065 -0.4215 +vn 0.0324 -0.9716 -0.2345 +vn -0.0076 -0.9547 -0.2975 +vn 0.0514 -0.9935 -0.1020 +vn -0.0186 -0.9974 0.0698 +vn -0.0129 -0.7659 -0.6428 +vn -0.0215 -0.7563 -0.6538 +vn -0.0291 -0.7477 -0.6634 +vn -0.0058 -0.7737 -0.6335 +vn -0.0048 0.0138 -0.9999 +vn 0.3096 0.1029 -0.9453 +vn 0.0911 0.0412 -0.9950 +vn 0.4692 0.1475 -0.8707 +vn -0.4204 -0.5847 -0.6938 +vn 0.5617 -0.8091 -0.1730 +vn -0.0146 -0.9997 0.0189 +vn -0.1007 -0.0137 -0.9948 +vn -0.0254 0.0079 -0.9996 +vn -0.1191 -0.0190 -0.9927 +vn 0.1277 -0.9699 -0.2074 +vn 0.0113 -0.9830 -0.1832 +vn 0.1103 -0.9727 -0.2040 +vn -0.0084 -0.9838 -0.1789 +vn 0.0031 0.1156 -0.9933 +vn -0.4691 -0.0696 -0.8804 +vn 0.3523 -0.6809 -0.6420 +vn -0.5477 -0.8279 -0.1211 +vn 0.0234 -0.9933 0.1128 +vn 0.2220 0.0783 -0.9719 +vn 0.0552 0.0309 -0.9980 +vn 0.3134 0.1040 -0.9439 +vn -0.4001 -0.7055 -0.5850 +vn 0.6420 -0.7497 -0.1603 +vn -0.0193 -0.9828 0.1838 +vn -0.0015 0.1168 -0.9932 +vn -0.0067 0.1126 -0.9936 +vn -0.0055 0.1136 -0.9935 +vn -0.0106 0.1095 -0.9939 +vn -0.0513 -0.7267 -0.6850 +vn -0.1387 -0.7247 -0.6750 +vn 0.0509 -0.9875 0.1492 +vn 0.0469 -0.9882 0.1459 +vn 0.0921 -0.9788 0.1830 +vn 0.0106 -0.9932 0.1159 +vn -0.0432 -0.9829 0.1788 +vn 0.8448 -0.5283 -0.0852 +vn -0.4232 -0.7018 0.5731 +vn 0.3511 -0.0179 0.9362 +vn 0.0865 0.0854 0.9926 +vn 0.3003 0.0027 0.9538 +vn 0.0033 0.1159 0.9933 +vn 0.0250 -0.9879 0.1532 +vn 0.7713 -0.6330 -0.0671 +vn -0.3488 -0.7144 0.6066 +vn 0.4684 -0.0693 0.8808 +vn -0.0031 0.1155 0.9933 +vn 0.0280 -0.9860 0.1645 +vn 0.7987 -0.5984 -0.0635 +vn -0.4051 -0.6970 0.5918 +vn 0.3506 -0.0179 0.9363 +vn 0.0863 0.0852 0.9926 +vn 0.2999 0.0026 0.9540 +vn 0.0034 0.1155 0.9933 +vn 0.0084 -0.9838 0.1790 +vn 0.8096 -0.5818 -0.0782 +vn -0.4051 -0.6970 0.5917 +vn 0.0172 -0.9913 -0.1301 +vn 0.0191 -0.9911 -0.1317 +vn 0.0188 -0.9911 -0.1315 +vn 0.0208 -0.9909 -0.1331 +vn 0.0092 -0.6706 0.7418 +vn -0.2843 -0.7056 0.6490 +vn -0.0720 0.1709 0.9826 +vn -0.0319 0.1396 0.9897 +vn -0.0377 0.1441 0.9888 +vn -0.0014 0.1155 0.9933 +vn 0.2356 -0.5974 0.7666 +vn -0.1017 -0.1841 0.9776 +vn 0.6163 0.0273 0.7871 +vn -0.3022 0.3013 0.9043 +vn 0.4456 -0.5050 0.7392 +vn -0.3438 -0.1581 0.9257 +vn 0.6160 0.1476 0.7738 +vn 0.6095 0.1453 0.7793 +vn 0.0238 -0.3725 0.9277 +vn 0.0736 -0.5985 0.7977 +vn 0.7903 0.0581 0.6100 +vn 0.0039 -0.5895 0.8077 +vn 0.0750 -0.3522 0.9329 +vn 0.0165 -0.5940 0.8043 +vn 0.1122 0.1752 0.9781 +vn -0.0102 0.2265 0.9740 +vn -0.0192 -0.0332 -0.9993 +vn -0.0109 -0.0252 -0.9996 +vn 0.0201 -0.9991 -0.0371 +vn 0.0108 -0.9995 -0.0283 +vn -0.0076 -0.6335 0.7737 +vn 0.0152 -0.6480 0.7615 +vn 0.0063 -0.9983 0.0583 +vn -0.0061 -0.9974 0.0717 +vn -0.0039 -0.5302 0.8479 +vn -0.0019 -0.5324 0.8465 +vn 0.9600 0.2563 -0.1130 +vn 0.7538 0.5274 -0.3920 +vn 0.7193 0.6681 -0.1905 +vn 0.9193 0.3799 -0.1023 +vn 0.9053 0.4189 -0.0699 +vn 0.9431 0.3300 -0.0414 +vn 0.9015 0.4326 0.0156 +vn 0.8849 0.4658 -0.0041 +vn 0.7124 0.7004 0.0424 +vn 0.9337 0.3440 0.0990 +vn 0.9385 0.3451 0.0145 +vn 0.7394 0.6325 0.2307 +vn 0.9416 0.2456 0.2306 +vn 0.7401 0.4536 0.4965 +vn 0.8880 0.3274 0.3230 +vn 0.8266 0.1999 0.5261 +vn 0.8973 0.1540 0.4137 +vn 0.7186 0.5524 0.4225 +vn 0.8392 0.1026 0.5341 +vn 0.6058 0.3250 0.7262 +vn 0.5604 0.1063 0.8213 +vn 0.7767 0.0977 0.6222 +vn 0.6654 0.2435 0.7056 +vn 0.8120 -0.0796 0.5783 +vn 0.4846 -0.0125 0.8747 +vn 0.6294 -0.0771 0.7733 +vn 0.7443 -0.4218 0.5177 +vn 0.7113 -0.6002 0.3659 +vn 0.8300 -0.4478 0.3326 +vn 0.9396 -0.1491 0.3080 +vn 0.9706 -0.2301 0.0701 +vn 0.7622 -0.4089 0.5019 +vn 0.9114 -0.4092 0.0435 +vn 0.7156 -0.6843 0.1399 +vn 0.7077 -0.7052 -0.0440 +vn 0.9498 -0.2894 0.1187 +vn 0.9464 -0.3224 0.0169 +vn 0.7257 -0.6470 -0.2340 +vn 0.9471 -0.2917 -0.1340 +vn 0.9425 -0.3287 -0.0614 +vn 0.8988 -0.4276 -0.0960 +vn 0.7703 -0.4754 -0.4250 +vn 0.7099 -0.4197 -0.5656 +vn 0.9473 -0.0961 -0.3056 +vn 0.7511 -0.5082 -0.4213 +vn 0.7292 -0.1704 -0.6627 +vn 0.7752 0.0117 -0.6316 +vn 0.9455 0.1225 -0.3018 +vn 0.9244 0.0741 -0.3741 +vn 0.7328 0.2882 -0.6163 +vn 0.7419 0.4723 -0.4759 +vn 0.8818 -0.0460 0.4694 +vn 0.8360 -0.0008 0.5487 +vn 0.6523 -0.3356 0.6796 +vn 0.9418 0.0705 0.3288 +vn 0.9780 0.0009 0.2084 +vn 0.8382 0.3944 -0.3767 +vn 0.9775 0.0735 -0.1975 +vn 0.9767 -0.1280 -0.1720 +vn 0.8981 -0.3205 -0.3010 +vn 0.9763 0.1299 0.1733 +vn 0.9826 -0.1133 0.1475 +vn 0.7170 -0.6056 0.3451 +vn 0.9743 0.2177 0.0585 +vn 0.9954 0.0591 -0.0748 +vn 0.9990 0.0263 0.0372 +vn 0.9865 -0.1627 -0.0195 +vn 0.3846 0.7395 0.5525 +vn -0.0189 0.8648 0.5018 +vn -0.0153 0.9912 0.1318 +vn 0.2564 0.8767 0.4070 +vn 0.2846 0.8805 0.3791 +vn 0.3162 0.9357 0.1567 +vn 0.3410 0.9364 -0.0824 +vn 0.2383 0.9232 -0.3017 +vn 0.2971 0.8010 -0.5197 +vn 0.2846 0.5820 -0.7617 +vn 0.2442 0.3951 -0.8856 +vn 0.2754 0.2097 -0.9382 +vn 0.2990 -0.0482 -0.9530 +vn 0.3086 -0.3232 -0.8946 +vn 0.2186 -0.5749 -0.7885 +vn 0.2652 -0.2399 0.9339 +vn 0.1752 0.2517 0.9518 +vn 0.2420 0.6205 0.7460 +vn 0.0034 -0.6068 0.7949 +vn 0.0285 -0.5518 0.8335 +vn -0.0369 -0.6885 0.7243 +vn -0.0697 -0.7489 0.6590 +vn 0.0683 -0.7154 -0.6954 +vn 0.0656 -0.7122 -0.6989 +vn 0.0609 -0.7069 -0.7047 +vn 0.0763 -0.7243 -0.6852 +vn 0.0778 0.8893 -0.4507 +vn 0.0273 0.8394 -0.5429 +vn -0.0100 0.7955 -0.6059 +vn -0.0830 0.6926 -0.7165 +vn -0.0068 0.5990 0.8007 +vn -0.0198 0.6290 0.7772 +vn -0.0438 0.6823 0.7298 +vn -0.0575 0.7112 0.7007 +vn -0.0357 -0.9078 -0.4180 +vn 0.0467 -0.5151 -0.8558 +vn -0.0287 0.1213 -0.9922 +vn 0.0242 0.9166 -0.3992 +vn 0.0246 0.9175 -0.3970 +vn 0.0268 0.9219 -0.3864 +vn 0.0271 0.9225 -0.3851 +vn -0.0331 0.6836 0.7291 +vn -0.0256 0.6453 0.7635 +vn 0.0303 0.3150 0.9486 +vn 0.0381 0.2632 0.9640 +vn -0.0321 -0.5712 0.8202 +vn -0.0257 -0.6100 0.7920 +vn 0.0250 -0.8575 0.5139 +vn 0.0328 -0.8862 0.4622 +vn -0.0072 0.7081 -0.7060 +vn 0.2632 0.5213 -0.8117 +vn 0.2897 0.8395 -0.4597 +vn 0.2928 0.9558 0.0285 +vn -0.0079 0.9992 -0.0397 +vn -0.0092 0.9791 -0.2031 +vn -0.0183 0.9926 0.1203 +vn 0.0062 0.7580 0.6522 +vn 0.0216 0.7039 0.7100 +vn 0.0076 0.7042 0.7100 +vn 0.0069 0.7620 0.6475 +vn 0.3473 0.5194 -0.7808 +vn 0.2684 0.8311 -0.4871 +vn -0.0146 0.3441 0.9388 +vn 0.2225 0.4672 0.8557 +vn 0.0037 0.2427 0.9701 +vn 0.5353 0.1599 -0.8294 +vn 0.5171 0.8526 -0.0754 +vn 0.4431 0.4395 0.7813 +vn 0.4197 0.4492 0.7887 +vn 0.0408 0.6978 0.7151 +vn 0.6063 0.7627 0.2251 +vn 0.7527 0.5291 0.3918 +vn 0.4315 0.8972 0.0943 +vn 0.4743 0.8220 0.3152 +vn 0.6953 0.6862 0.2138 +vn 0.7799 0.0704 0.6220 +vn 0.4706 0.6888 0.5514 +vn 0.4588 0.6983 0.5495 +vn 0.3614 -0.8754 0.3210 +vn 0.2938 -0.7072 0.6431 +vn 0.0011 -0.8263 0.5633 +vn 0.2465 -0.6787 0.6918 +vn 0.0062 -0.9613 0.2754 +vn 0.0007 -0.7865 -0.6176 +vn 0.2577 -0.8777 -0.4040 +vn 0.3533 -0.9192 -0.1741 +vn 0.3254 -0.9446 0.0430 +vn -0.0245 0.9007 0.4337 +vn 0.0354 0.4339 0.9003 +vn -0.0412 -0.1623 0.9859 +vn 0.0327 -0.7782 0.6272 +vn -0.0253 -0.9921 -0.1229 +vn -0.0212 -0.9872 -0.1579 +vn 0.0133 -0.9014 -0.4328 +vn 0.0181 -0.8829 -0.4693 +vn -0.0203 -0.2348 -0.9718 +vn -0.0162 -0.1987 -0.9799 +vn 0.0226 0.1458 -0.9891 +vn 0.0269 0.1843 -0.9825 +vn -0.0220 0.7358 -0.6769 +vn 0.0332 0.9831 -0.1803 +vn -0.0099 -0.6988 -0.7153 +vn 0.0009 -0.8612 -0.5082 +vn 0.2162 -0.5300 -0.8200 +vn 0.0061 -0.9570 0.2901 +vn -0.0144 -0.7030 0.7111 +vn -0.0080 -0.8359 0.5489 +vn 0.0012 -0.9522 0.3055 +vn 0.0077 -0.9649 0.2626 +vn 0.2896 -0.5268 -0.7992 +vn 0.2498 -0.8297 -0.4992 +vn -0.0089 -0.9707 -0.2402 +vn 0.0098 -0.9892 -0.1463 +vn 0.0029 -0.9551 -0.2963 +vn -0.0007 -0.5590 0.8292 +vn 0.2587 -0.4249 0.8675 +vn -0.0071 -0.3483 0.9373 +vn 0.0148 -0.2404 0.9706 +vn 0.4279 -0.7721 -0.4699 +vn 0.6585 -0.5319 -0.5325 +vn 0.6438 -0.6381 -0.4224 +vn 0.6145 -0.5388 0.5762 +vn 0.6251 -0.4765 0.6182 +vn 0.6372 -0.7182 0.2796 +vn -0.9759 -0.1144 -0.1857 +vn 0.6402 -0.7459 0.1840 +vn 0.5131 -0.7246 0.4601 +vn -0.7432 -0.5908 0.3139 +vn 0.8640 0.4905 0.1137 +vn 0.8113 0.5817 0.0586 +vn 0.9121 0.3507 0.2123 +vn 0.9908 -0.1162 0.0696 +vn 0.9865 -0.1245 0.1067 +vn 0.9717 -0.1892 0.1412 +vn 0.9946 -0.0896 0.0522 +vn 0.9783 0.1156 0.1717 +vn 0.9991 0.0274 0.0334 +vn 0.9303 0.0032 -0.3668 +vn 0.9655 0.0641 -0.2523 +vn 0.8455 -0.0885 -0.5266 +vn 0.9491 -0.2292 -0.2161 +vn 0.9206 -0.3676 -0.1318 +vn 0.9646 -0.2624 -0.0280 +vn 0.7861 -0.1360 -0.6030 +vn 0.9982 -0.0559 -0.0208 +vn 0.9996 -0.0205 0.0209 +vn 0.9730 -0.2237 0.0563 +vn 0.9562 -0.2789 0.0893 +vn 0.9995 -0.0286 0.0109 +vn -0.6372 -0.1645 -0.7530 +vn -0.9638 -0.2623 -0.0484 +vn -0.9619 -0.2681 -0.0543 +vn -0.9474 -0.3061 -0.0933 +vn -0.9795 0.1842 0.0819 +vn -0.9690 0.2469 0.0007 +vn -0.9904 0.0832 0.1108 +vn -0.9600 0.2507 -0.1249 +vn -0.9749 -0.2225 -0.0083 +vn -0.8083 -0.5578 -0.1886 +vn -0.8500 -0.5054 -0.1486 +vn -0.8391 -0.5201 -0.1596 +vn -0.9731 0.1630 -0.1625 +vn -0.8027 -0.3299 -0.4969 +vn -0.9999 0.0101 0.0101 +vn -0.9994 -0.0340 0.0055 +vn -0.9811 -0.1829 0.0631 +vn -0.9791 -0.1978 0.0472 +vn -0.9986 -0.0525 -0.0076 +vn -0.9991 -0.0371 -0.0182 +vn -0.8906 -0.0501 0.4520 +vn 0.7411 -0.5421 0.3961 +vn -0.0002 -0.8964 0.4433 +vn -0.4804 -0.8296 -0.2846 +vn 0.6340 -0.6401 -0.4339 +vn -0.5736 -0.2559 -0.7781 +vn 0.6603 0.0150 -0.7509 +vn -0.7798 0.4435 -0.4418 +vn 0.6277 0.7029 -0.3347 +vn -0.2125 0.8985 0.3841 +vn -0.4752 0.7908 0.3858 +vn -0.1158 0.9193 0.3762 +vn -0.4975 0.7777 0.3844 +vn 0.4211 0.3145 0.8507 +vn 0.4266 -0.6501 -0.6288 +vn -0.3023 -0.9464 -0.1139 +vn 0.1247 -0.8245 0.5519 +vn -0.1664 -0.0675 0.9837 +vn -0.3995 -0.0902 0.9123 +vn -0.1449 -0.0652 0.9873 +vn -0.4529 -0.0949 0.8865 +vn 0.5965 0.5092 0.6204 +vn -0.6961 0.6044 0.3875 +vn 0.5836 0.8097 0.0616 +vn -0.7038 0.6523 -0.2816 +vn 0.2275 0.7670 -0.6000 +vn -0.1157 0.7430 0.6592 +vn 0.7166 0.6372 -0.2835 +vn 0.0882 0.2742 -0.9576 +vn -0.6711 0.0049 -0.7414 +vn -0.8571 -0.4955 -0.1411 +vn -0.3737 -0.2284 0.8990 +vn 0.3700 -0.6579 0.6559 +vn -0.3009 -0.7581 -0.5786 +vn 0.2788 -0.3505 -0.8941 +vn -0.3284 0.8508 -0.4102 +vn 0.3715 0.9278 0.0346 +vn 0.4161 0.8614 0.2913 +vn -0.5313 -0.1948 0.8245 +vn 0.3888 -0.6972 0.6023 +vn -0.0396 -0.7295 -0.6828 +vn 0.4643 -0.2450 -0.8511 +vn -0.5644 0.6967 -0.4428 +vn 0.9994 -0.0015 0.0347 +vn 0.9988 0.0454 -0.0204 +vn 0.9986 0.0130 -0.0511 +vn 0.9989 0.0320 -0.0333 +vn 0.9987 0.0129 -0.0501 +vn 0.9972 0.0739 0.0083 +vn -0.9949 -0.0991 0.0177 +vn -0.9994 0.0320 -0.0152 +vn -0.9930 -0.1162 0.0220 +vn 0.0186 -0.6843 -0.7289 +vn -0.0245 -0.8098 -0.5862 +vn 0.0290 -0.6497 -0.7596 +vn -0.0716 0.5177 -0.8526 +vn -0.0571 0.5684 -0.8208 +vn -0.0060 0.7242 -0.6895 +vn 0.0086 0.7627 -0.6467 +vn -0.0609 0.8127 0.5794 +vn -0.0455 0.7760 0.6291 +vn 0.0078 0.6288 0.7776 +vn 0.0215 0.5858 0.8101 +vn -0.0486 -0.5809 0.8125 +vn -0.0377 -0.6153 0.7874 +vn 0.0060 -0.7396 0.6730 +vn 0.0180 -0.7697 0.6382 +vn -0.0383 -0.8441 -0.5349 +vn -0.9925 0.1198 0.0233 +vn -0.9917 -0.0134 0.1278 +vn -0.9936 0.1122 0.0137 +vn -0.9882 -0.1534 -0.0019 +vn -0.9902 -0.1119 0.0831 +vn -0.9904 -0.1172 -0.0731 +vn -0.9913 0.0201 0.1303 +vn -0.9924 0.0078 -0.1225 +vn -0.9921 0.0276 -0.1224 +vn -0.1125 -0.4176 -0.9016 +vn -0.0673 -0.3712 -0.9261 +vn -0.0648 -0.3686 -0.9273 +vn -0.0058 -0.3058 -0.9521 +vn 0.0637 0.5391 -0.8398 +vn -0.0919 0.6737 -0.7332 +vn -0.1111 0.6881 -0.7170 +vn -0.2299 0.7652 -0.6013 +vn 0.2170 0.9604 0.1750 +vn -0.1713 0.6528 0.7379 +vn -0.0445 0.5214 0.8521 +vn -0.0535 0.5315 0.8454 +vn 0.0955 0.3514 0.9313 +vn -0.1151 -0.4313 0.8948 +vn 0.0177 -0.5933 0.8048 +vn 0.0276 -0.6041 0.7964 +vn 0.1494 -0.7242 0.6732 +vn -0.1044 -0.9902 0.0924 +vn 0.0150 -0.9961 -0.0867 +vn 0.0276 -0.9941 -0.1053 +vn 0.1529 -0.9449 -0.2896 +vn 0.7997 -0.5674 0.1963 +vn 0.4873 -0.6950 -0.5287 +vn -0.0694 0.2535 -0.9648 +vn 0.8302 0.5362 0.1524 +vn 0.7620 0.5720 0.3036 +vn 0.7709 0.5687 0.2868 +vn 0.6690 0.5916 0.4500 +vn -0.2986 -0.4725 0.8292 +vn -0.9660 -0.2524 0.0563 +vn 0.9995 0.0062 -0.0311 +vn 0.9994 -0.0053 -0.0354 +vn 0.9997 0.0239 -0.0108 +vn 0.9998 -0.0190 -0.0039 +vn 0.9998 -0.0166 0.0106 +vn 0.9998 0.0051 0.0185 +vn 0.9996 0.0263 0.0144 +vn -0.9994 0.0213 0.0258 +vn -0.9964 0.0489 0.0699 +vn -0.9969 0.0419 -0.0661 +vn -0.9948 0.0278 -0.0983 +vn 0.0027 -0.5853 -0.8108 +vn -0.0099 -0.3635 -0.9315 +vn -0.0107 -0.3488 -0.9371 +vn 0.0033 -0.5952 -0.8036 +vn 0.0062 -0.9174 0.3980 +vn -0.0207 -0.9986 0.0486 +vn -0.0226 -0.9995 0.0219 +vn 0.0079 -0.9079 0.4192 +vn 0.0040 0.3518 0.9361 +vn -0.0233 -0.0198 0.9995 +vn -0.0249 -0.0430 0.9988 +vn 0.0057 0.3737 0.9276 +vn -0.0030 0.9985 0.0551 +vn -0.0124 0.9762 0.2166 +vn -0.0129 0.9742 0.2255 +vn -0.0025 0.9989 0.0469 +vn 0.0066 0.4449 -0.8956 +vn -0.0142 0.7409 -0.6715 +vn -0.0152 0.7524 -0.6585 +vn 0.0076 0.4299 -0.9028 +vn -0.9954 -0.0909 -0.0300 +vn -0.9956 -0.0468 -0.0815 +vn -0.9954 -0.0956 -0.0012 +vn -0.9943 -0.0039 -0.1067 +vn -0.9960 0.0544 -0.0708 +vn -0.9949 0.0927 -0.0389 +vn -0.9952 0.0946 0.0231 +vn -0.9953 0.0787 0.0564 +vn -0.9952 0.0327 0.0926 +vn -0.9923 -0.0429 0.1159 +vn -0.9946 -0.0796 0.0663 +vn 0.1674 -0.7381 -0.6536 +vn 0.0907 -0.7968 -0.5975 +vn 0.0937 -0.7947 -0.5998 +vn -0.0076 -0.8566 -0.5160 +vn -0.1104 -0.9297 0.3514 +vn 0.2599 -0.5865 0.7671 +vn 0.1116 -0.4539 0.8840 +vn 0.1314 -0.4727 0.8714 +vn -0.0690 -0.2685 0.9608 +vn 0.1093 0.8064 0.5812 +vn 0.1243 0.8139 0.5676 +vn -0.0128 0.7324 0.6807 +vn 0.2132 0.8510 0.4799 +vn -0.1811 0.9440 -0.2756 +vn 0.2071 0.5074 -0.8364 +vn -0.1532 0.0508 -0.9869 +vn -0.1238 0.1877 -0.9744 +vn -0.0016 0.0595 -0.9982 +vn 0.0017 0.0561 -0.9984 +vn 0.1239 -0.0740 -0.9895 +vn -0.1238 0.7500 0.6497 +vn -0.0017 0.8347 0.5506 +vn 0.0016 0.8366 0.5478 +vn 0.1238 0.8940 0.4307 +vn -0.9487 0.0761 -0.3070 +vn 0.9986 0.0179 -0.0490 +vn 0.9969 0.0606 -0.0504 +vn 0.9748 0.1862 -0.1228 +vn 0.9383 0.3459 -0.0013 +vn 0.7734 0.1345 -0.6195 +vn 0.8418 0.0774 -0.5343 +vn 0.9265 -0.0193 -0.3758 +vn 0.9636 -0.0883 -0.2524 +vn 0.4567 -0.8553 0.2448 +vn 0.9737 -0.1976 0.1135 +vn 0.9946 -0.0902 0.0518 +vn 0.9915 -0.1127 0.0647 +vn 0.4440 -0.6536 -0.6129 +vn 0.2249 -0.7266 -0.6492 +vn 0.4288 -0.6601 -0.6167 +vn 0.9922 -0.0790 0.0962 +vn 0.9993 -0.0347 0.0152 +vn 0.9796 -0.1815 0.0868 +vn 0.9812 -0.1708 0.0899 +vn 0.9977 -0.0678 0.0004 +vn 0.9997 0.0067 0.0240 +vn 0.9983 -0.0542 -0.0219 +vn 0.9876 0.1458 0.0579 +vn 0.9993 0.0340 0.0145 +vn 0.9870 0.1469 0.0656 +vn -0.9898 -0.0127 0.1418 +vn -0.9989 -0.0324 0.0350 +vn -0.9017 -0.3005 -0.3107 +vn -0.8994 0.0835 -0.4290 +vn -0.9313 0.0408 -0.3618 +vn -0.9524 0.0056 -0.3046 +vn -0.9721 -0.2285 -0.0526 +vn 0.1002 -0.8745 0.4746 +vn -0.8281 -0.3505 -0.4374 +vn -0.8805 0.1051 -0.4623 +vn -0.9997 0.0252 0.0063 +vn -0.9997 -0.0217 0.0093 +vn -0.9936 -0.1046 0.0433 +vn -0.9862 -0.1524 0.0647 +vn -0.9887 -0.1311 0.0726 +vn -0.9997 -0.0206 0.0133 +vn -0.9998 0.0208 -0.0047 +vn -0.9988 0.0283 -0.0407 +vn -0.9899 0.1208 0.0736 +vn -0.9813 0.1826 0.0613 +vn -0.5208 -0.6421 0.5626 +vn -0.6512 -0.4832 0.5852 +vn -0.4865 -0.6808 0.5476 +vn -0.6717 -0.4813 0.5631 +vn 0.6603 -0.6657 0.3477 +vn -0.7796 -0.6008 -0.1766 +vn 0.7949 -0.4605 -0.3951 +vn -0.6995 -0.0301 -0.7140 +vn 0.5989 0.2340 -0.7659 +vn -0.6340 0.6401 -0.4339 +vn 0.4804 0.8296 -0.2846 +vn -0.0273 0.8857 0.4634 +vn -0.0788 0.8798 0.4688 +vn -0.0161 0.8867 0.4621 +vn -0.0870 0.8786 0.4695 +vn -0.2731 0.3384 0.9005 +vn -0.8345 0.4320 0.3421 +vn -0.8105 0.5182 0.2730 +vn -0.8475 0.3428 0.4052 +vn 0.8385 0.4799 -0.2580 +vn -0.7645 0.6192 0.1790 +vn 0.7311 0.0471 -0.6807 +vn -0.1612 -0.2717 -0.9488 +vn 0.0670 -0.9624 -0.2634 +vn 0.1974 -0.7328 -0.6512 +vn -0.3740 -0.9255 0.0605 +vn -0.4641 -0.5886 0.6620 +vn 0.4418 -0.0633 0.8949 +vn -0.3145 0.0664 0.9469 +vn 0.1274 0.7095 0.6931 +vn -0.5596 0.8273 0.0486 +vn 0.6362 0.6588 -0.4016 +vn -0.1664 0.7243 -0.6692 +vn -0.8814 0.4666 -0.0735 +vn -0.4409 -0.8217 0.3613 +vn -0.5083 0.5902 0.6271 +vn 0.7158 -0.6421 0.2746 +vn -0.0710 -0.5477 0.8337 +vn 0.0632 -0.4135 -0.9083 +vn -0.4789 -0.0146 -0.8777 +vn 0.4574 0.8833 -0.1025 +vn -0.1328 0.3272 0.9356 +vn 0.3913 -0.0169 0.9201 +vn -0.4678 -0.8838 0.0033 +vn 0.3126 -0.7341 -0.6028 +vn -0.5632 0.4582 -0.6877 +vn 0.0914 0.8752 -0.4751 +vn 0.0108 0.0316 0.9994 +vn 0.0196 0.0224 0.9996 +vn 0.0336 0.0002 0.9994 +vn -0.0327 0.0026 0.9995 +vn -0.0493 0.0000 0.9988 +vn -0.0225 -0.0247 0.9994 +vn 0.0143 -0.0305 0.9994 +vn 0.0345 -0.0255 0.9991 +vn 0.0021 -0.0440 0.9990 +vn -0.0207 0.0252 0.9995 +vn 0.0195 -0.0101 -0.9998 +vn 0.0302 -0.0232 -0.9993 +vn 0.0242 -0.0494 -0.9985 +vn 0.0229 0.0049 -0.9997 +vn -0.0050 0.0489 -0.9988 +vn 0.2857 -0.9582 -0.0158 +vn 0.2693 -0.9630 -0.0117 +vn 0.2660 -0.9639 -0.0109 +vn 0.2890 -0.9572 -0.0166 +vn -0.8907 -0.4545 0.0074 +vn -0.8909 -0.4541 0.0073 +vn -0.8929 -0.4502 0.0064 +vn -0.8932 -0.4496 0.0063 +vn -0.9177 0.3956 -0.0375 +vn -0.4822 0.8756 0.0304 +vn -0.4441 0.8956 0.0238 +vn -0.1556 0.9875 -0.0233 +vn -0.0958 0.9949 -0.0325 +vn 0.9380 0.3467 -0.0019 +vn 0.9542 0.2990 0.0109 +vn 0.9576 0.2878 0.0139 +vn 0.9345 0.3561 -0.0045 +vn -0.0274 -0.0632 -0.9976 +vn 0.0776 -0.0506 -0.9957 +vn 0.0210 -0.0696 -0.9974 +vn 0.0763 -0.0042 -0.9971 +vn 0.0292 0.0834 -0.9961 +vn -0.0753 0.0197 -0.9970 +vn -0.0233 0.0700 -0.9973 +vn -0.0766 0.0444 -0.9961 +vn 0.0598 0.0547 -0.9967 +vn -0.0382 -0.0700 -0.9968 +vn -0.0665 -0.0278 -0.9974 +vn 0.9296 0.3621 -0.0682 +vn 0.8878 0.4601 0.0023 +vn 0.8769 0.4804 0.0175 +vn 0.8203 0.5656 0.0849 +vn 0.2400 0.9640 -0.1143 +vn 0.0415 0.9991 -0.0037 +vn -0.0217 0.9993 0.0313 +vn -0.2015 0.9708 0.1304 +vn -0.6427 0.7612 -0.0869 +vn -0.8964 0.4405 -0.0495 +vn -0.8437 0.5368 0.0078 +vn -0.9984 0.0353 0.0433 +vn -0.9442 -0.3268 -0.0403 +vn -0.8913 -0.4527 0.0245 +vn -0.7370 -0.6713 -0.0778 +vn -0.1925 -0.9813 -0.0025 +vn -0.2348 -0.9718 0.0200 +vn -0.3000 -0.9524 0.0551 +vn -0.1201 -0.9919 -0.0404 +vn 0.6648 -0.7452 -0.0518 +vn 0.7568 -0.6532 0.0223 +vn 0.4656 -0.8829 0.0609 +vn 0.8376 -0.5448 -0.0406 +vn 0.9437 -0.3210 0.0799 +vn 0.9868 -0.0555 0.1524 +vn 0.5636 0.7816 -0.2672 +vn 0.0237 0.9885 0.1495 +vn -0.9872 0.1001 -0.1238 +vn -0.9865 0.0780 -0.1440 +vn -0.9867 0.0815 -0.1408 +vn -0.9848 0.0554 -0.1644 +vn 0.3992 -0.8877 -0.2294 +vn -0.0239 -0.9942 0.1048 +vn -0.0422 -0.9991 -0.0068 +vn -0.0461 -0.9988 -0.0169 +vn -0.0391 -0.9989 -0.0263 +vn -0.0340 -0.9993 0.0158 +vn -0.0040 -0.9992 0.0402 +vn 0.0356 -0.9993 0.0137 +vn -0.0057 -0.9991 0.0420 +vn 0.0235 -0.9993 0.0300 +vn 0.0199 -0.9996 -0.0184 +vn 0.0323 -0.9994 -0.0101 +vn 0.0184 -0.9997 -0.0183 +vn 0.0189 0.9997 0.0140 +vn 0.0080 0.9994 0.0328 +vn -0.0158 0.9995 0.0269 +vn 0.0079 0.9999 0.0101 +vn 0.0779 0.9968 -0.0187 +vn -0.9612 0.0576 0.2697 +vn -0.4588 -0.0296 0.8881 +vn 0.5208 0.0005 0.8537 +vn 0.2105 0.0316 0.9771 +vn 0.1733 0.0349 0.9842 +vn 0.5587 -0.0038 0.8294 +vn 0.9977 -0.0119 -0.0660 +vn 0.9735 0.0268 0.2271 +vn 0.9630 0.0322 0.2676 +vn 0.9943 -0.0170 -0.1050 +vn 0.2088 -0.0108 -0.9779 +vn 0.4889 0.0296 -0.8718 +vn 0.5306 0.0360 -0.8469 +vn 0.1670 -0.0165 -0.9858 +vn -0.5574 0.0337 -0.8296 +vn -0.9286 -0.0262 -0.3702 +vn -0.0815 0.9962 0.0322 +vn -0.0317 0.9975 -0.0639 +vn -0.0727 0.9972 -0.0182 +vn -0.0563 0.9965 0.0625 +vn 0.0792 0.9954 -0.0541 +vn 0.0675 0.9977 0.0109 +vn 0.0260 0.9976 -0.0642 +vn 0.0624 0.9969 0.0476 +vn -0.0452 0.9971 -0.0616 +vn 0.0011 0.9978 0.0658 +vn 0.0106 0.9977 0.0675 +vn -0.8384 0.0623 -0.5414 +vn -0.7677 0.0116 -0.6408 +vn -0.7050 -0.0269 -0.7087 +vn -0.6164 -0.0749 -0.7838 +vn -0.1351 0.0947 -0.9863 +vn -0.0189 0.0305 -0.9994 +vn 0.0487 -0.0071 -0.9988 +vn 0.1864 -0.0839 -0.9789 +vn 0.7917 0.0089 -0.6108 +vn 0.8457 0.0883 -0.5263 +vn 0.8372 0.0744 -0.5419 +vn 0.8710 0.1345 -0.4725 +vn 0.9532 -0.1270 0.2743 +vn 0.6953 0.1505 0.7027 +vn 0.2791 -0.1090 0.9541 +vn -0.3540 0.0953 0.9304 +vn -0.4755 0.0214 0.8795 +vn -0.5169 -0.0056 0.8561 +vn -0.6257 -0.0818 0.7758 +vn -0.9581 0.0861 0.2733 +vn -0.9888 0.0239 0.1473 +vn -0.9975 -0.0145 0.0685 +vn -0.9952 -0.0769 -0.0611 +vn -0.4443 -0.1642 -0.8807 +vn -0.4227 -0.1408 -0.8953 +vn -0.4257 -0.1439 -0.8934 +vn -0.4070 -0.1238 -0.9050 +vn 0.8678 0.1496 -0.4738 +vn 0.9507 -0.2270 0.2113 +vn 0.9587 -0.2672 0.0973 +vn 0.9427 -0.2081 0.2608 +vn 0.9102 -0.1576 0.3831 +vn -0.8320 0.1135 0.5431 +vn -0.5477 -0.3509 0.7596 +vn -0.5235 0.8184 0.2369 +vn -0.8831 0.1416 -0.4474 +vn -0.9924 -0.0753 0.0971 +vn -0.1241 -0.9835 0.1318 +vn -0.1130 -0.9891 0.0943 +vn -0.1281 -0.9810 0.1455 +vn -0.1078 -0.9912 0.0766 +vn 0.8309 -0.4377 -0.3434 +vn 0.7817 0.0328 0.6229 +vn 0.5742 0.6784 -0.4584 +vn 0.6074 0.5873 -0.5349 +vn 0.5919 0.6340 -0.4977 +vn 0.7251 -0.4598 0.5127 +vn 0.6220 0.5323 -0.5743 +vn -0.5331 -0.8298 -0.1650 +vn -0.6257 -0.7721 0.1109 +vn -0.4974 -0.8329 -0.2426 +vn -0.6438 -0.7394 0.1972 +vn -0.9895 0.0014 -0.1448 +vn -0.9924 0.0087 -0.1229 +vn -0.9885 -0.0007 -0.1511 +vn -0.9935 0.0121 -0.1128 +vn -0.5295 0.8118 0.2464 +vn -0.3299 0.8710 -0.3640 +vn 0.4292 0.8511 0.3024 +vn 0.6550 0.6942 -0.2984 +vn 0.9243 0.0993 0.3685 +vn 0.9442 -0.1467 -0.2948 +vn 0.4835 -0.8744 0.0404 +vn -0.7474 0.1195 0.6536 +vn 0.0112 -0.4332 0.9012 +vn 0.0030 -0.1163 0.9932 +vn 0.0069 -0.2660 0.9640 +vn 0.0114 -0.2444 -0.9696 +vn 0.0033 -0.0699 -0.9976 +vn 0.0152 -0.3273 -0.9448 +vn -0.0076 -0.9093 0.4160 +vn -0.1260 -0.9431 0.3078 +vn 0.0757 -0.8711 0.4853 +vn 0.5363 -0.6772 -0.5038 +vn 0.8457 -0.3701 0.3844 +vn 0.7249 0.5843 -0.3647 +vn 0.6183 0.7669 0.1717 +vn -0.6610 0.7383 -0.1339 +vn -0.7380 0.6314 0.2381 +vn -0.6891 0.7232 -0.0461 +vn -0.7396 0.5967 0.3113 +vn -0.8883 -0.3910 -0.2409 +vn -0.6815 0.6532 -0.3300 +vn -0.7108 0.0947 -0.6970 +vn 0.8895 0.4108 0.2002 +vn 0.9167 0.1675 -0.3627 +vn 0.8573 -0.4415 0.2646 +vn 0.6349 -0.7041 -0.3181 +vn 0.2587 -0.9083 0.3287 +vn -0.2583 -0.9123 -0.3179 +vn -0.5992 -0.7334 0.3212 +vn -0.8534 -0.4409 -0.2779 +vn -0.9557 0.0903 0.2802 +vn -0.8870 0.3767 -0.2671 +vn -0.5510 0.7874 0.2765 +vn -0.1742 0.9039 -0.3908 +vn 0.2318 0.9376 0.2593 +vn 0.1986 -0.7922 0.5771 +vn 0.8139 0.0786 -0.5756 +vn -0.5177 -0.0858 -0.8513 +vn -0.9911 0.0620 0.1177 +vn -0.9837 -0.0689 0.1663 +vn -0.9890 0.1091 0.0996 +vn -0.9762 -0.1160 0.1831 +vn -0.0306 0.0684 0.9972 +vn 0.0184 -0.0621 0.9979 +vn -0.0482 0.1153 0.9922 +vn 0.0361 -0.1091 0.9934 +vn 0.9437 0.0884 0.3189 +vn 0.9476 0.0699 0.3116 +vn 0.9414 0.0982 0.3227 +vn 0.9501 0.0573 0.3066 +vn 0.7527 -0.1538 -0.6401 +vn 0.6745 0.1019 -0.7312 +vn 0.7343 -0.0735 -0.6748 +vn 0.6474 0.1626 -0.7446 +vn 0.7098 0.6543 0.2609 +vn 0.0267 -0.4708 0.8818 +vn -0.6908 0.3366 0.6399 +vn -0.8597 -0.3516 0.3705 +vn -0.9080 0.3853 -0.1647 +vn -0.6846 -0.3563 -0.6358 +vn -0.4970 0.1869 -0.8474 +vn 0.2000 -0.1827 -0.9626 +vn 0.2474 -0.0526 -0.9675 +vn 0.1864 -0.2176 -0.9581 +vn 0.2665 0.0039 -0.9638 +vn 0.9113 0.2025 -0.3585 +vn 0.9266 -0.3451 -0.1496 +vn 0.7702 0.3633 0.5242 +vn 0.6309 -0.2469 0.7356 +vn -0.7116 0.4147 0.5671 +vn -0.2016 0.9774 -0.0642 +vn -0.0420 0.9990 -0.0134 +vn -0.2528 0.9642 -0.0805 +vn -0.5181 -0.8076 -0.2816 +vn 0.0756 0.4000 0.9134 +vn -0.0782 0.3069 0.9485 +vn 0.1179 0.4234 0.8982 +vn 0.4031 -0.5988 0.6921 +vn 0.8133 0.5556 0.1731 +vn 0.6882 -0.4971 -0.5284 +vn 0.5108 0.1664 -0.8435 +vn -0.4880 -0.0561 -0.8710 +vn -0.4854 -0.0484 -0.8729 +vn -0.4896 -0.0609 -0.8698 +vn -0.4840 -0.0444 -0.8739 +vn -0.9957 0.0079 0.0921 +vn -0.9924 -0.0422 -0.1152 +vn -0.9961 -0.0014 0.0883 +vn -0.9948 -0.0451 -0.0913 +vn -0.9352 -0.0684 -0.3474 +vn 0.8720 0.1373 -0.4698 +vn 0.9059 -0.2255 0.3584 +vn 0.7855 0.3183 0.5307 +vn 0.2824 -0.2661 0.9216 +vn -0.1204 0.3946 0.9109 +vn -0.4476 -0.2781 0.8499 +vn -0.9798 0.1221 0.1584 +vn -0.9682 -0.1218 0.2187 +vn -0.9665 0.2210 0.1305 +vn -0.9454 -0.2207 0.2396 +vn -0.6651 0.3151 -0.6770 +vn -0.3676 -0.5206 -0.7706 +vn 0.2411 0.3049 -0.9214 +vn 0.2903 0.5092 0.8102 +vn 0.7030 -0.6612 -0.2619 +vn 0.0591 0.9960 -0.0670 +vn 0.2144 0.9461 -0.2429 +vn 0.2943 0.8956 -0.3335 +vn 0.2086 -0.9133 -0.3499 +vn 0.0510 -0.9950 -0.0855 +vn 0.1381 -0.9630 -0.2316 +vn 0.0037 0.2897 0.9571 +vn 0.0039 0.1453 0.9894 +vn -0.0007 0.2894 0.9572 +vn -0.0082 0.5626 0.8267 +vn 0.0043 0.4292 0.9032 +vn 0.0046 -0.9722 -0.2340 +vn -0.0011 -0.9561 -0.2929 +vn 0.0187 -0.9288 -0.3702 +vn -0.0057 -0.7950 -0.6066 +vn 0.0067 0.0135 0.9999 +vn 0.0586 0.2377 0.9696 +vn 0.0498 0.1030 0.9934 +vn -0.0079 0.1567 0.9876 +vn 0.0007 0.2794 0.9602 +vn -0.0007 0.1948 0.9808 +vn -0.3899 0.1940 0.9002 +vn -0.0021 0.2706 0.9627 +vn 0.0001 0.2702 0.9628 +vn 0.0087 0.2721 0.9622 +vn -0.0090 0.1655 0.9862 +vn -0.0011 0.2674 0.9636 +vn -0.0024 0.2653 0.9642 +vn 0.0008 0.2767 0.9610 +vn -0.1951 0.2595 0.9458 +vn 0.0137 0.0892 -0.9959 +vn -0.0301 0.1292 -0.9912 +vn -0.0241 0.1805 -0.9833 +vn -0.0230 0.0543 -0.9983 +vn 0.0194 0.3907 -0.9203 +vn 0.0269 0.4326 -0.9012 +vn -0.0046 0.5160 -0.8566 +vn -0.0066 0.5168 -0.8561 +vn 0.0070 -0.8702 0.4927 +vn -0.0427 -0.9504 0.3081 +vn -0.0061 -0.8724 0.4888 +vn -0.0032 -0.9024 0.4308 +vn 0.0308 -0.9954 0.0910 +vn -0.0477 -0.9961 -0.0736 +vn 0.0506 -0.9535 -0.2972 +vn -0.0009 -0.9029 -0.4299 +vn -0.0171 -0.8719 -0.4893 +vn -0.0048 -0.8740 -0.4859 +vn -0.0212 -0.9569 -0.2897 +vn -0.0040 -0.9762 -0.2167 +vn -0.0539 -0.9611 -0.2710 +vn -0.0012 -0.9720 -0.2351 +vn -0.0009 -0.9607 -0.2776 +vn 0.0006 -0.9920 -0.1263 +vn -0.0174 -0.9971 -0.0747 +vn -0.0073 -0.9648 -0.2628 +vn -0.0012 -0.9644 -0.2646 +vn -0.0028 -0.9914 -0.1311 +vn -0.0001 -0.9637 -0.2669 +vn -0.0004 -0.9639 -0.2663 +vn -0.0003 -0.9639 -0.2663 +vn -0.0002 -0.9603 -0.2790 +vn 0.0050 0.5024 0.8646 +vn -0.0229 0.3389 0.9406 +vn 0.0019 0.5014 0.8652 +vn -0.0226 0.3982 0.9170 +vn 0.0049 0.0740 0.9972 +vn -0.0149 -0.0517 0.9986 +vn 0.0184 -0.2947 0.9554 +vn -0.0134 -0.4047 0.9144 +vn -0.0183 -0.2222 0.9748 +vn -0.0180 -0.2972 0.9547 +vn 0.0022 -0.2490 -0.9685 +vn 0.0009 -0.1096 -0.9940 +vn 0.0005 -0.2552 -0.9669 +vn 0.0002 -0.1125 -0.9937 +vn -0.0001 0.1934 -0.9811 +vn 0.0002 0.1942 -0.9810 +vn 0.0001 0.4695 -0.8829 +vn -0.0011 0.4653 -0.8852 +vn 0.0011 0.6821 -0.7312 +vn -0.0006 0.6754 -0.7375 +vn 0.0009 0.8613 -0.5081 +vn -0.0010 0.8593 -0.5114 +vn -0.0054 0.9786 -0.2055 +vn 0.0011 0.9682 -0.2501 +vn 0.0059 1.0000 0.0066 +vn -0.0068 0.9932 0.1162 +vn 0.0038 0.9784 0.2065 +vn -0.0033 0.9654 0.2606 +vn -0.0008 0.9613 0.2754 +vn 0.0014 -0.0176 0.9998 +vn -0.0141 -0.1433 0.9896 +vn -0.2039 -0.2982 0.9325 +vn -0.0348 -0.4674 0.8834 +vn -0.0173 -0.5018 0.8648 +vn -0.0048 -0.6826 0.7308 +vn -0.0185 -0.7500 0.6612 +vn -0.0057 -0.8294 0.5587 +vn -0.0225 -0.9351 0.3536 +vn -0.0040 -0.9312 0.3645 +vn -0.0076 -0.9920 0.1256 +vn -0.0073 0.8614 -0.5079 +vn 0.0310 0.9121 -0.4087 +vn 0.0222 0.8679 -0.4962 +vn -0.0171 0.9550 -0.2962 +vn 0.0117 0.9971 -0.0752 +vn 0.0102 0.9998 -0.0150 +vn 0.0393 0.9967 0.0711 +vn 0.0552 0.9964 0.0646 +vn -0.9966 0.0314 -0.0760 +vn -0.9991 0.0246 -0.0358 +vn -0.9985 0.0124 -0.0536 +vn -0.9997 0.0140 -0.0211 +vn -0.9988 0.0059 -0.0494 +vn -0.9992 0.0326 -0.0214 +vn -0.9999 -0.0126 -0.0017 +vn -0.9984 0.0499 -0.0274 +vn -0.9994 0.0333 -0.0136 +vn -0.9988 0.0493 -0.0019 +vn -0.9990 0.0103 -0.0446 +vn -0.9989 0.0110 -0.0452 +vn -0.9985 0.0490 -0.0241 +vn -0.9982 0.0589 0.0114 +vn -0.9751 0.0260 -0.2202 +vn -0.9477 0.0334 -0.3175 +vn -0.9972 0.0704 -0.0265 +vn -0.9984 0.0220 -0.0516 +vn -0.9983 -0.0071 -0.0572 +vn 0.9989 0.0338 -0.0337 +vn 0.9999 0.0154 -0.0061 +vn 0.9997 0.0222 -0.0028 +vn -0.9978 -0.0656 0.0015 +vn -0.9986 -0.0499 0.0184 +vn -0.9988 -0.0477 0.0065 +vn -0.9989 -0.0395 0.0247 +vn -0.9989 -0.0007 0.0477 +vn -0.9990 -0.0186 0.0402 +vn -0.9997 -0.0091 0.0222 +vn -0.9964 0.0667 0.0514 +vn -0.9933 0.0814 0.0824 +vn -0.9859 0.1468 0.0801 +vn -0.9951 0.0103 0.0979 +vn -0.9366 0.0606 0.3453 +vn -0.9914 -0.1274 -0.0311 +vn -0.9885 -0.1472 -0.0336 +vn -0.9970 -0.0728 -0.0268 +vn -0.9968 -0.0285 0.0748 +vn -0.9940 -0.0839 -0.0709 +vn -0.9982 -0.0543 -0.0236 +vn -0.9995 -0.0198 0.0249 +vn -0.9994 -0.0043 0.0356 +vn -0.9993 -0.0348 0.0153 +vn -0.9140 -0.3991 -0.0732 +vn -0.9265 0.0585 0.3717 +vn -0.9987 0.0220 0.0461 +vn -0.9982 -0.0560 -0.0214 +vn -0.0012 -0.9998 0.0191 +vn 0.0018 -0.9998 0.0210 +vn -0.0122 -0.9997 0.0202 +vn -0.0005 0.0013 -1.0000 +vn -0.0005 0.0012 -1.0000 +vn -0.0006 0.0007 -1.0000 +vn -0.0006 0.0006 -1.0000 +vn 0.6966 -0.1765 -0.6954 +vn 0.6777 -0.1655 -0.7164 +vn 0.6714 -0.1017 -0.7341 +vn 0.6925 -0.0061 -0.7214 +vn 0.6753 0.1428 -0.7236 +vn 0.6701 0.2105 -0.7118 +vn 0.6796 0.3344 -0.6529 +vn 0.6653 0.4028 -0.6286 +vn 0.6196 0.5378 -0.5717 +vn 0.6881 0.6134 -0.3876 +vn 0.7055 0.6178 -0.3473 +vn 0.6696 0.7276 -0.1491 +vn 0.6619 0.7318 -0.1624 +vn 0.6809 0.7306 0.0499 +vn 0.6882 0.7205 0.0859 +vn 0.6909 0.7017 0.1740 +vn 0.7025 0.6884 0.1808 +vn -0.7194 -0.1770 -0.6717 +vn -0.7217 -0.0998 -0.6849 +vn -0.7095 -0.1701 -0.6839 +vn -0.7186 -0.0223 -0.6951 +vn -0.6715 0.1376 -0.7281 +vn -0.7081 0.2652 -0.6544 +vn -0.6843 0.3726 -0.6268 +vn -0.6985 0.4747 -0.5355 +vn -0.7003 0.4554 -0.5497 +vn -0.7041 0.5901 -0.3951 +vn -0.7098 0.6087 -0.3545 +vn -0.7024 0.6799 -0.2104 +vn -0.7009 0.6952 -0.1596 +vn -0.7135 0.7000 0.0293 +vn -0.7229 0.6909 -0.0111 +vn -0.7073 0.6906 0.1509 +vn -0.7023 0.6900 0.1750 +vn -0.7170 0.6692 0.1952 +vn -0.9067 -0.1835 0.3797 +vn -0.8613 0.1623 -0.4814 +vn -0.7601 -0.1482 -0.6327 +vn -0.8395 0.0585 -0.5403 +vn -0.7276 -0.2089 -0.6534 +vn 0.1047 0.2734 -0.9562 +vn 0.4786 -0.3512 -0.8047 +vn 0.8842 0.3300 -0.3307 +vn 0.8166 -0.5054 0.2789 +vn -0.5449 -0.1010 -0.8324 +vn -0.5609 -0.1933 -0.8050 +vn -0.5329 -0.0453 -0.8450 +vn -0.5682 -0.2504 -0.7839 +vn 0.1950 0.2554 -0.9470 +vn 0.7136 -0.3365 -0.6145 +vn 0.9070 0.1644 -0.3877 +vn 0.8651 -0.0100 0.5015 +vn -0.9402 0.0121 0.3403 +vn -0.0044 0.9997 -0.0233 +vn -0.0050 0.9997 -0.0254 +vn 0.0105 0.9992 -0.0397 +vn 0.0110 0.9991 -0.0415 +vn 0.0777 0.9947 -0.0666 +vn -0.0052 0.9997 -0.0235 +vn 0.0104 -0.9998 0.0165 +vn -0.0287 -0.9993 0.0245 +vn 0.0284 -0.9993 0.0253 +vn 0.0040 0.5815 -0.8135 +vn -0.0551 0.4935 -0.8680 +vn 0.0023 0.5650 -0.8251 +vn -0.0028 0.5046 -0.8634 +vn -0.6565 0.7543 0.0078 +vn -0.7914 0.6102 -0.0370 +vn -0.8151 0.5775 -0.0459 +vn -0.6323 0.7746 0.0149 +vn -0.6148 0.5458 -0.5693 +vn -0.6084 0.5715 -0.5506 +vn -0.6283 0.4775 -0.6142 +vn -0.6313 0.4577 -0.6261 +vn 0.2573 0.7014 -0.6648 +vn 0.2701 0.6774 -0.6842 +vn -0.0051 0.5067 -0.8621 +vn -0.0054 0.5004 -0.8658 +vn 0.6187 0.4961 -0.6092 +vn 0.6570 0.4285 -0.6203 +vn -0.0053 -0.0161 0.9999 +vn -0.0241 -0.0172 0.9996 +vn 0.0081 -0.0171 0.9998 +vn 0.0354 -0.0184 0.9992 +vn 0.0020 1.0000 0.0078 +vn 0.0017 1.0000 0.0016 +vn -0.0013 0.9838 0.1794 +vn -0.0013 0.9999 -0.0143 +vn 0.9360 -0.3143 0.1584 +vn 0.8613 0.4814 -0.1623 +vn 0.8387 0.5418 -0.0555 +vn 0.8545 0.5047 -0.1230 +vn 0.8282 0.5601 -0.0198 +vn -0.0264 0.9987 0.0443 +vn -0.0707 0.9968 -0.0383 +vn 0.0046 0.9948 0.1014 +vn -0.1032 0.9897 -0.0992 +vn -0.9275 0.3737 0.0049 +vn -0.9260 0.3773 -0.0145 +vn -0.9273 0.3744 0.0011 +vn -0.9252 0.3788 -0.0224 +vn -0.7922 -0.5747 0.2053 +vn -0.0489 -0.0331 0.9983 +vn -0.0009 -0.0132 0.9999 +vn -0.0001 0.0478 -0.9989 +vn -0.0054 0.0187 -0.9998 +vn -0.0037 0.0110 -0.9999 +vn -0.0015 0.0529 -0.9986 +vn 0.0332 0.0647 -0.9974 +vn 0.0029 -0.0115 0.9999 +vn 0.0447 -0.0183 0.9988 +vn -0.0263 0.0178 -0.9995 +vn -0.8291 0.4308 -0.3565 +vn -0.7914 -0.3508 0.5005 +vn 0.8973 -0.3983 0.1906 +vn 0.8892 0.4347 -0.1426 +vn 0.8287 0.5562 0.0624 +vn 0.8721 0.4852 -0.0638 +vn 0.8036 0.5835 0.1176 +vn 0.1838 0.9757 -0.1192 +vn -0.0033 0.9956 0.0934 +vn 0.0763 0.9971 0.0038 +vn -0.0915 0.9773 0.1910 +vn -0.5593 0.8095 -0.1786 +vn -0.9193 0.3293 0.2153 +vn -0.0002 0.8109 -0.5852 +vn 0.0023 0.7995 -0.6007 +vn -0.0623 0.8723 -0.4849 +vn 0.0011 -0.8347 -0.5507 +vn -0.0018 0.8922 0.4517 +vn -0.0440 0.8626 -0.5039 +vn -0.0999 0.8957 -0.4333 +vn -0.8902 -0.0113 -0.4554 +vn -0.8342 0.0120 -0.5514 +vn -0.6152 0.6249 -0.4807 +vn -0.6315 0.6275 -0.4554 +vn -0.6195 0.6256 -0.4742 +vn -0.6348 0.6280 -0.4501 +vn 0.0007 0.8905 -0.4550 +vn 0.0006 0.8897 -0.4566 +vn -0.0019 0.8655 -0.5009 +vn -0.0020 0.8645 -0.5026 +vn 0.6384 0.6613 -0.3939 +vn 0.6378 0.6564 -0.4028 +vn 0.6383 0.6603 -0.3957 +vn 0.6377 0.6554 -0.4047 +vn -0.0259 0.0181 0.9995 +vn 0.0149 0.0653 0.9978 +vn -0.0018 -0.7412 0.6713 +vn -0.0048 -0.7443 0.6679 +vn -0.0082 -0.7478 0.6639 +vn 0.0016 -0.7375 0.6753 +vn 0.0034 -0.9971 -0.0762 +vn -0.0052 -0.9978 -0.0660 +vn -0.0076 -0.9980 -0.0631 +vn -0.0161 -0.9985 -0.0530 +vn 0.9997 0.0225 -0.0113 +vn 1.0000 -0.0026 -0.0026 +vn 0.9992 -0.0160 0.0379 +vn 1.0000 -0.0069 0.0064 +vn 0.9986 -0.0106 0.0524 +vn 0.9992 -0.0351 0.0203 +vn 1.0000 -0.0078 0.0008 +vn 1.0000 -0.0007 0.0023 +vn 0.9996 0.0021 -0.0269 +vn 1.0000 -0.0068 0.0053 +vn 1.0000 0.0074 0.0032 +vn 0.9995 0.0043 -0.0314 +vn 0.9995 0.0234 0.0201 +vn 0.9874 0.1475 0.0572 +vn 0.9999 0.0130 -0.0034 +vn 1.0000 0.0089 0.0015 +vn 1.0000 -0.0024 -0.0034 +vn 1.0000 -0.0071 -0.0042 +vn 0.9997 -0.0191 -0.0130 +vn 0.9989 0.0232 0.0419 +vn 0.9992 0.0129 0.0371 +vn 0.9997 0.0129 0.0209 +vn 0.9995 -0.0276 0.0169 +vn 0.9997 -0.0216 -0.0109 +vn 0.9981 0.0211 0.0572 +vn 0.9998 -0.0169 0.0044 +vn -0.0207 -0.9959 0.0886 +vn -0.0100 -0.9970 0.0772 +vn -0.0075 -0.9972 0.0745 +vn 0.0014 -0.9979 0.0650 +vn -0.0241 -0.7059 -0.7079 +vn 0.0376 -0.7922 -0.6091 +vn 0.0917 -0.8548 -0.5108 +vn -0.0816 -0.6111 -0.7873 +vn 0.0068 0.0478 -0.9988 +vn 0.0123 -0.1468 -0.9891 +vn -0.0147 0.0093 -0.9998 +vn -0.0107 -0.0413 -0.9991 +vn -0.0068 -0.0372 -0.9993 +vn -0.0062 -0.0366 -0.9993 +vn -0.0026 -0.0327 -0.9995 +vn 0.0160 0.7196 -0.6942 +vn -0.0216 0.7659 -0.6426 +vn -0.0618 0.8103 -0.5827 +vn 0.0560 0.6652 -0.7446 +vn -0.0077 0.9977 0.0669 +vn -0.0038 0.9974 0.0714 +vn -0.0025 0.9973 0.0728 +vn 0.0017 0.9970 0.0777 +vn -0.0055 0.9827 0.1852 +vn -0.0457 0.9984 0.0340 +vn -0.0347 0.9993 0.0128 +vn 0.0377 0.6195 0.7841 +vn 0.0495 0.6362 0.7700 +vn 0.0580 0.6478 0.7596 +vn 0.0277 0.6051 0.7957 +vn -0.0046 -0.0862 0.9963 +vn -0.0151 -0.0735 0.9972 +vn -0.0176 -0.0705 0.9974 +vn -0.0276 -0.0582 0.9979 +vn 0.0332 0.0490 -0.9982 +vn 0.0542 0.0322 -0.9980 +vn -0.0587 0.1217 -0.9908 +vn 0.1282 -0.0273 -0.9914 +vn -0.1256 -0.9919 0.0188 +vn 0.3388 -0.6973 0.6317 +vn -0.1442 -0.2209 0.9646 +vn 0.0990 0.9453 0.3107 +vn 0.1102 0.9467 0.3027 +vn 0.0737 0.9416 0.3286 +vn 0.1393 0.9494 0.2815 +vn 0.0225 -0.1424 0.9895 +vn -0.0198 -0.2087 0.9778 +vn -0.0886 -0.3140 0.9453 +vn 0.0855 -0.0416 0.9955 +vn 0.0433 0.9730 -0.2268 +vn -0.0031 0.9877 -0.1561 +vn -0.1139 0.9933 0.0181 +vn 0.1567 0.9052 -0.3950 +vn -0.0509 -0.7444 -0.6657 +vn -0.0236 -0.7669 -0.6413 +vn 0.1164 -0.8592 -0.4982 +vn -0.1870 -0.6103 -0.7698 +vn -0.9355 -0.3293 -0.1278 +vn -0.8636 -0.4827 -0.1454 +vn -0.6648 -0.7207 -0.1963 +vn -0.6173 -0.7854 -0.0453 +vn -0.5879 -0.7794 -0.2166 +vn -0.5368 -0.1574 0.8289 +vn -0.5264 -0.0522 0.8486 +vn -0.6171 -0.5239 0.5871 +vn -0.5944 -0.7063 0.3845 +vn -0.6824 -0.5733 0.4536 +vn -0.7031 -0.7104 0.0303 +vn -0.8355 -0.2434 0.4927 +vn -0.8252 -0.2298 0.5160 +vn -0.7038 -0.6362 0.3163 +vn -0.8494 -0.1469 0.5068 +vn -0.8032 -0.5761 0.1517 +vn 0.3661 -0.1223 0.9225 +vn -0.8865 0.1183 0.4473 +vn -0.7471 0.2979 0.5942 +vn -0.5571 0.2284 0.7984 +vn -0.8530 0.1415 0.5023 +vn -0.0181 -0.2760 -0.9610 +vn 0.0422 -0.6763 -0.7354 +vn -0.0244 0.9484 0.3161 +vn 0.0134 0.7857 0.6185 +vn -0.7980 0.1682 0.5787 +vn -0.9450 0.2963 0.1384 +vn -0.0445 -0.9989 -0.0138 +vn -0.0306 -0.9995 -0.0075 +vn -0.0270 -0.9995 0.0184 +vn 0.0316 -0.9995 -0.0079 +vn 0.0223 -0.9994 -0.0261 +vn 0.0049 -0.9993 -0.0382 +vn -0.0145 -0.9994 -0.0311 +vn 0.0086 -0.9994 0.0344 +vn 0.0271 -0.9994 0.0210 +vn -0.0116 -0.9994 0.0332 +vn 0.0079 0.9995 0.0295 +vn -0.0253 0.9996 0.0087 +vn 0.0058 0.9996 0.0293 +vn 0.0211 0.9990 0.0384 +vn 0.0240 0.9990 0.0378 +vn 0.5696 0.0366 -0.8211 +vn -0.4609 -0.0229 -0.8872 +vn -0.3528 0.0003 -0.9357 +vn -0.3293 0.0052 -0.9442 +vn -0.4748 -0.0260 -0.8797 +vn -0.9977 0.0463 -0.0489 +vn -0.8254 -0.0383 0.5633 +vn -0.1985 0.0511 0.9788 +vn 0.4740 -0.0315 0.8799 +vn 0.9549 0.0463 0.2933 +vn 0.9245 -0.0362 -0.3795 +vn -0.0829 0.9965 -0.0102 +vn 0.0297 0.9969 -0.0727 +vn -0.0293 0.9974 -0.0661 +vn 0.0456 0.9952 -0.0869 +vn -0.0124 0.9957 0.0923 +vn -0.0471 0.9976 0.0506 +vn 0.0351 0.9974 0.0626 +vn 0.0824 0.9959 0.0364 +vn 0.0712 0.9974 -0.0105 +vn -0.0885 0.9956 -0.0316 +vn 0.7388 0.0119 -0.6738 +vn 0.7962 0.0759 -0.6003 +vn 0.7228 -0.0042 -0.6910 +vn 0.9751 -0.0848 0.2051 +vn 0.9393 0.0192 0.3426 +vn 0.9448 0.0075 0.3277 +vn 0.8863 0.1067 0.4507 +vn 0.3069 -0.1080 0.9456 +vn 0.0854 0.0361 0.9957 +vn 0.1162 0.0165 0.9931 +vn -0.0946 0.1484 0.9844 +vn -0.6269 -0.1112 0.7711 +vn -0.9668 0.0934 0.2378 +vn -0.9801 0.0594 0.1893 +vn -0.9845 0.0455 0.1693 +vn -0.9944 0.0012 0.1053 +vn -0.7732 -0.0165 -0.6339 +vn -0.7316 0.0217 -0.6814 +vn -0.7481 0.0070 -0.6636 +vn -0.7072 0.0424 -0.7058 +vn -0.1886 -0.0439 -0.9811 +vn -0.0533 0.0247 -0.9983 +vn -0.1124 -0.0051 -0.9936 +vn 0.0209 0.0619 -0.9979 +vn 0.6536 -0.0684 -0.7538 +vn 0.7018 0.1239 -0.7016 +vn 0.7152 0.1441 -0.6840 +vn 0.7131 0.1409 -0.6868 +vn 0.7282 0.1645 -0.6654 +vn 0.2517 0.2295 0.9402 +vn 0.6468 -0.1048 0.7554 +vn -0.7296 -0.1524 0.6667 +vn -0.9307 0.2672 -0.2496 +vn -0.6431 -0.1495 -0.7510 +vn 0.0120 -0.0257 0.9996 +vn -0.0157 -0.0309 0.9994 +vn 0.0195 -0.0291 0.9994 +vn -0.0326 0.0014 0.9995 +vn -0.0394 -0.0124 0.9991 +vn -0.0045 0.0325 0.9995 +vn -0.0277 0.0248 0.9993 +vn 0.0165 0.0309 0.9994 +vn 0.0281 0.0081 0.9996 +vn -0.0150 -0.0081 -0.9999 +vn -0.0200 -0.0119 -0.9997 +vn -0.0770 0.0177 -0.9969 +vn 0.0113 -0.0216 -0.9997 +vn 0.0276 -0.0183 -0.9995 +vn -0.7336 -0.6789 0.0307 +vn -0.9987 -0.0272 -0.0427 +vn -0.8552 0.5180 0.0159 +vn -0.0149 0.9999 0.0002 +vn -0.3481 0.9371 -0.0269 +vn -0.3832 0.9232 -0.0298 +vn 0.0205 0.9998 0.0031 +vn 0.8304 0.5571 0.0092 +vn 0.6167 0.7866 -0.0301 +vn 0.5835 0.8113 -0.0351 +vn 0.8533 0.5212 0.0145 +vn 0.7128 -0.7011 0.0185 +vn 0.8768 -0.4801 -0.0267 +vn 0.9010 -0.4324 -0.0353 +vn 0.6798 -0.7329 0.0260 +vn -0.2038 -0.9778 -0.0490 +vn -0.0785 -0.0016 -0.9969 +vn -0.0179 -0.0902 -0.9958 +vn -0.0599 -0.0379 -0.9975 +vn -0.0654 0.0344 -0.9973 +vn 0.0725 -0.0057 -0.9974 +vn 0.0532 0.0509 -0.9973 +vn 0.0749 -0.0184 -0.9970 +vn 0.0325 0.0662 -0.9973 +vn 0.0237 -0.0728 -0.9971 +vn -0.0383 0.0633 -0.9973 +vn -0.0097 0.0720 -0.9974 +vn -0.5533 -0.8316 -0.0475 +vn -0.3919 -0.9099 -0.1364 +vn -0.6097 -0.7925 -0.0127 +vn 0.0545 -0.9908 0.1241 +vn 0.7291 -0.6702 -0.1382 +vn 0.8640 -0.5035 0.0053 +vn 0.8710 -0.4910 0.0150 +vn 0.9422 -0.2991 0.1512 +vn 0.9465 0.3003 -0.1184 +vn 0.5800 0.8054 0.1224 +vn 0.4568 0.8892 0.0238 +vn 0.4808 0.8758 0.0422 +vn 0.3276 0.9422 -0.0696 +vn -0.4647 0.8840 0.0519 +vn -0.5408 0.8411 -0.0061 +vn -0.5212 0.8534 0.0093 +vn -0.5933 0.8035 -0.0490 +vn -0.9734 0.2223 0.0548 +vn -0.9965 0.0766 -0.0346 +vn -0.9930 0.1173 -0.0099 +vn -0.9955 -0.0206 -0.0929 +vn -0.7599 -0.6431 0.0946 +vn -0.8141 -0.5612 0.1495 +vn 0.4988 -0.8578 -0.1238 +vn 0.5162 -0.8443 -0.1439 +vn 0.5135 -0.8465 -0.1408 +vn 0.5335 -0.8297 -0.1643 +vn 0.4841 0.8444 -0.2295 +vn 0.8188 0.5645 0.1049 +vn -0.5345 0.8313 0.1525 +vn -0.9636 -0.0030 -0.2672 +vn 0.8208 0.5021 0.2724 +vn 0.8788 0.4369 0.1918 +vn 0.9842 0.1757 0.0237 +vn 0.9982 0.0553 0.0246 +vn 0.9988 0.0275 0.0403 +vn 0.9992 0.0324 0.0247 +vn 0.9992 0.0245 0.0323 +vn 0.9988 0.0363 -0.0316 +vn 0.9988 0.0350 -0.0341 +vn 0.9989 0.0283 -0.0371 +vn 0.9987 0.0409 -0.0302 +vn 0.9987 0.0387 -0.0341 +vn 0.6240 -0.1725 -0.7622 +vn 0.3022 -0.5516 0.7775 +vn 0.3732 -0.5167 0.7706 +vn -0.1529 -0.7120 -0.6854 +vn 0.5921 -0.6682 -0.4504 +vn -0.4493 -0.8013 -0.3950 +vn 0.7402 -0.6681 -0.0757 +vn 0.4523 -0.8814 -0.1361 +vn 0.7484 -0.6591 -0.0734 +vn -0.2084 -0.1893 0.9595 +vn -0.4242 -0.8987 0.1114 +vn 0.6635 -0.6705 0.3319 +vn 0.7719 -0.5750 0.2713 +vn 0.8156 -0.5261 0.2410 +vn 0.2663 0.2938 0.9180 +vn 0.1381 0.0436 0.9895 +vn 0.2222 0.1824 0.9578 +vn -0.1468 -0.5010 0.8529 +vn 0.6899 0.3411 0.6385 +vn 0.1864 0.7836 0.5926 +vn 0.2580 0.8056 0.5333 +vn 0.4244 0.8281 0.3662 +vn 0.4771 0.8250 0.3028 +vn 0.6968 0.7172 -0.0122 +vn 0.8344 0.4762 -0.2774 +vn -0.4707 0.6604 0.5851 +vn 0.6659 0.4343 -0.6067 +vn 0.6978 0.3384 0.6313 +vn -0.4063 -0.1077 -0.9074 +vn -0.2589 -0.4566 -0.8512 +vn 0.5250 -0.4626 -0.7144 +vn 0.5857 -0.2495 0.7712 +vn 0.6579 -0.6747 0.3346 +vn -0.4577 -0.6605 0.5952 +vn -0.1928 -0.7032 -0.6844 +vn 0.6730 0.0687 0.7364 +vn -0.4827 0.6570 0.5792 +vn -0.4569 0.8561 -0.2413 +vn -0.1615 0.7706 -0.6165 +vn 0.6945 0.1605 -0.7014 +vn 0.9319 0.0774 -0.3544 +vn 0.9268 0.1003 -0.3618 +vn 0.3279 -0.9320 -0.1544 +vn -0.9998 0.0163 -0.0077 +vn -0.9984 -0.0175 0.0538 +vn -1.0000 -0.0031 0.0022 +vn -1.0000 -0.0007 -0.0023 +vn -0.9992 -0.0376 0.0103 +vn -1.0000 -0.0005 0.0037 +vn -1.0000 0.0037 -0.0035 +vn -0.9999 0.0092 0.0118 +vn -0.9999 0.0132 0.0089 +vn -0.9997 -0.0122 -0.0233 +vn -0.9998 -0.0105 -0.0139 +vn -0.9998 -0.0215 -0.0048 +vn -1.0000 0.0062 -0.0030 +vn -0.9996 -0.0030 0.0276 +vn -0.9999 0.0047 -0.0088 +vn -1.0000 0.0029 -0.0063 +vn -1.0000 -0.0010 -0.0069 +vn -1.0000 -0.0023 -0.0080 +vn -0.9999 0.0145 0.0057 +vn -1.0000 0.0004 -0.0047 +vn -1.0000 0.0005 -0.0000 +vn 0.9988 -0.0336 -0.0370 +vn 0.9996 -0.0204 -0.0179 +vn 0.9985 0.0220 0.0508 +vn 0.9999 0.0168 0.0006 +vn 0.9985 -0.0225 -0.0499 +vn 0.9994 0.0298 0.0188 +vn 0.9947 -0.0150 -0.1013 +vn 0.9996 0.0057 0.0260 +vn 0.9948 -0.0919 -0.0439 +vn 0.9997 -0.0145 -0.0177 +vn 0.9999 0.0109 0.0096 +vn 0.9996 0.0024 -0.0271 +vn 0.9997 0.0021 -0.0245 +vn 0.9993 0.0053 -0.0364 +vn 0.9666 0.2535 0.0382 +vn 0.9959 0.0855 -0.0300 +vn 0.9999 0.0166 -0.0027 +vn 0.9997 0.0026 -0.0259 +vn 0.9999 -0.0125 0.0051 +vn 0.9998 -0.0208 0.0029 +vn 0.9460 0.1359 -0.2944 +vn 0.9969 0.0435 -0.0651 +vn 0.9995 0.0310 -0.0056 +vn 0.9990 0.0429 -0.0093 +vn 0.9995 0.0222 0.0246 +vn 0.9995 0.0073 -0.0300 +vn 0.9995 -0.0105 0.0293 +vn 0.9990 -0.0133 0.0418 +vn 0.9994 -0.0332 0.0096 +vn 0.9995 -0.0218 -0.0229 +vn 0.9991 -0.0350 -0.0243 +vn -1.0000 0.0080 -0.0041 +vn -0.9952 0.0978 0.0061 +vn -0.9936 0.1124 -0.0078 +vn -0.9994 -0.0285 0.0187 +vn 0.0038 0.3879 0.9217 +vn -0.0130 0.7102 0.7039 +vn -0.0120 0.6936 0.7202 +vn 0.0045 0.3728 0.9279 +vn 0.0004 -0.6741 0.7387 +vn -0.0223 -0.3250 0.9455 +vn -0.0212 -0.3451 0.9383 +vn 0.0017 -0.6904 0.7234 +vn 0.0002 -0.9210 -0.3895 +vn -0.0194 -0.9925 -0.1209 +vn -0.0184 -0.9906 -0.1355 +vn 0.0013 -0.9148 -0.4038 +vn -0.0066 -0.0177 -0.9998 +vn -0.0109 0.0291 -0.9995 +vn -0.0069 -0.0149 -0.9999 +vn -0.0112 0.0320 -0.9994 +vn 0.0112 0.9839 -0.1782 +vn -0.0090 0.9070 -0.4211 +vn -0.0078 0.9134 -0.4070 +vn 0.0121 0.9860 -0.1665 +vn -0.9885 -0.0117 0.1508 +vn -0.9970 -0.0597 0.0502 +vn -0.9955 0.0584 0.0740 +vn -0.9937 0.1058 0.0378 +vn -0.9958 0.0826 -0.0395 +vn -0.9946 0.0549 -0.0879 +vn -0.9952 -0.0015 -0.0975 +vn -0.9961 -0.0455 -0.0755 +vn -0.9955 -0.0732 -0.0609 +vn -0.9924 -0.1233 -0.0038 +vn -0.0694 0.9712 0.2280 +vn -0.1102 0.9764 0.1860 +vn -0.0663 0.9706 0.2312 +vn -0.0173 0.9598 0.2803 +vn 0.0376 0.1907 0.9809 +vn -0.0910 0.0467 0.9948 +vn -0.1021 0.0339 0.9942 +vn -0.2010 -0.0812 0.9762 +vn 0.1614 -0.6908 0.7048 +vn -0.0822 -0.9901 -0.1136 +vn -0.1354 -0.9894 -0.0532 +vn -0.0822 -0.9901 -0.1137 +vn -0.0150 -0.9820 -0.1882 +vn 0.0327 -0.3714 -0.9279 +vn 0.0415 -0.3797 -0.9242 +vn 0.0400 -0.3783 -0.9248 +vn 0.0502 -0.3879 -0.9203 +vn 0.0182 0.6176 -0.7862 +vn -0.1178 0.4665 -0.8767 +vn 0.0074 0.6067 -0.7949 +vn 0.1373 0.7255 -0.6744 +vn -0.1238 0.9744 -0.1874 +vn 0.0017 0.9984 -0.0557 +vn -0.0016 0.9982 -0.0592 +vn 0.1239 0.9895 0.0743 +vn -0.1239 -0.6496 -0.7501 +vn 0.0016 -0.5476 -0.8367 +vn -0.0017 -0.5505 -0.8348 +vn 0.1237 -0.4305 -0.8941 +vn -0.1237 -0.3248 0.9376 +vn 0.0018 -0.4508 0.8926 +vn -0.0015 -0.4477 0.8942 +vn 0.1240 -0.5590 0.8198 +vn -0.9546 0.2971 0.0214 +vn 0.9995 -0.0313 -0.0049 +vn 0.9996 -0.0131 -0.0233 +vn 0.9995 0.0240 -0.0211 +vn 0.9991 0.0258 -0.0343 +vn 0.9995 0.0302 0.0063 +vn 0.9995 -0.0043 0.0314 +vn 0.9996 0.0063 0.0278 +vn 0.9994 -0.0320 0.0135 +vn -0.9998 0.0086 -0.0155 +vn -0.9984 0.0496 0.0277 +vn -0.9998 0.0048 -0.0194 +vn -0.9973 -0.0373 -0.0637 +vn -0.0263 0.0385 -0.9989 +vn 0.0178 0.5826 -0.8126 +vn 0.0024 0.8588 0.5122 +vn -0.0310 0.9978 0.0590 +vn -0.0293 0.9960 0.0843 +vn 0.0047 0.8419 0.5397 +vn -0.0090 -0.1915 0.9814 +vn -0.0079 -0.1814 0.9834 +vn -0.0089 -0.1909 0.9816 +vn -0.0078 -0.1808 0.9835 +vn 0.0156 -0.9627 -0.2702 +vn -0.0145 -0.9994 0.0305 +vn -0.0121 -0.9999 0.0058 +vn 0.0174 -0.9573 -0.2884 +vn -0.9945 0.1032 -0.0192 +vn -0.9951 0.0961 0.0227 +vn -0.9956 0.0524 -0.0775 +vn -0.9715 -0.0502 -0.2317 +vn -0.9955 -0.0818 -0.0485 +vn -0.9938 -0.1016 0.0460 +vn -0.9953 -0.0591 0.0766 +vn -0.9960 0.0352 0.0822 +vn -0.9957 0.0365 0.0846 +vn -0.0741 -0.0730 -0.9946 +vn -0.0479 -0.0468 -0.9978 +vn 0.0877 0.0886 -0.9922 +vn -0.0307 0.9280 -0.3712 +vn -0.0192 0.9244 -0.3809 +vn -0.0187 0.9243 -0.3813 +vn -0.0077 0.9206 -0.3905 +vn 0.0694 0.6865 0.7238 +vn -0.0406 0.7770 0.6282 +vn 0.0676 0.6881 0.7225 +vn 0.1554 0.6000 0.7848 +vn -0.1646 -0.1078 0.9805 +vn 0.1793 -0.6176 0.7658 +vn -0.1989 -0.9722 0.1239 +vn 0.1692 -0.9357 -0.3094 +vn -0.1910 -0.1898 -0.9631 +vn -0.1237 -0.9376 -0.3248 +vn 0.0018 -0.8926 -0.4508 +vn -0.0015 -0.8942 -0.4477 +vn 0.1240 -0.8198 -0.5590 +vn -0.1238 0.1874 0.9744 +vn 0.0017 0.0557 0.9984 +vn -0.0016 0.0592 0.9982 +vn 0.1239 -0.0743 0.9895 +vn -0.1239 0.7501 -0.6496 +vn 0.0016 0.8367 -0.5476 +vn -0.0017 0.8348 -0.5505 +vn 0.1237 0.8941 -0.4305 +vn 0.9974 -0.0723 -0.0013 +vn 0.9963 0.0208 0.0832 +vn 0.9961 0.0437 -0.0761 +vn 0.9979 0.0378 -0.0526 +vn 0.9972 0.0405 -0.0632 +vn 0.9982 0.0364 -0.0468 +vn -0.9999 0.0090 -0.0087 +vn -0.9990 -0.0395 -0.0207 +vn -0.9999 0.0087 -0.0088 +vn -0.9986 0.0537 0.0024 +vn -0.0589 -0.9133 0.4029 +vn 0.0168 -0.9481 -0.3175 +vn -0.0510 -0.4449 -0.8941 +vn 0.0167 0.2949 -0.9554 +vn -0.0488 0.7672 -0.6396 +vn 0.0221 0.9467 0.3214 +vn -0.0667 0.5844 0.8087 +vn 0.0248 -0.3932 0.9191 +vn -0.9898 0.0104 0.1421 +vn -0.9952 0.0704 0.0676 +vn -0.9924 0.1103 -0.0545 +vn -0.9895 0.1338 -0.0538 +vn -0.9927 -0.1182 0.0244 +vn -0.9940 -0.0838 0.0701 +vn -0.9939 0.0214 -0.1080 +vn -0.9921 -0.0591 -0.1107 +vn -0.9926 -0.1047 -0.0621 +vn 0.1704 -0.8605 0.4802 +vn -0.1875 -0.9823 0.0003 +vn 0.1426 -0.8231 -0.5497 +vn 0.0016 -0.3352 -0.9422 +vn -0.0401 -0.3961 -0.9173 +vn -0.0089 -0.3507 -0.9364 +vn 0.0404 -0.2765 -0.9602 +vn -0.0168 0.6113 -0.7912 +vn -0.0317 0.5981 -0.8008 +vn -0.0181 0.6102 -0.7921 +vn -0.0024 0.6238 -0.7816 +vn -0.0563 0.9881 0.1428 +vn 0.0002 0.9817 0.1907 +vn -0.0459 0.9874 0.1517 +vn -0.1198 0.9889 0.0878 +vn 0.1838 0.7238 0.6651 +vn -0.1161 -0.1721 0.9782 +vn -0.2196 -0.0705 0.9730 +vn -0.1058 -0.1819 0.9776 +vn 0.0426 -0.3168 0.9475 +vn 0.0093 -0.6160 0.7877 +vn 0.0474 -0.6317 0.7738 +vn 0.0265 -0.6232 0.7816 +vn 0.0807 -0.6445 0.7603 +vn 0.2955 0.9540 0.0497 +vn 0.3853 0.9162 0.1104 +vn 0.3467 0.9342 0.0840 +vn 0.4551 0.8761 0.1590 +vn 0.3733 -0.2527 -0.8927 +vn 0.3217 -0.2908 -0.9011 +vn 0.3452 -0.2737 -0.8977 +vn 0.2736 -0.3245 -0.9054 +vn 0.0829 0.0886 -0.9926 +vn 0.1123 0.0795 -0.9905 +vn 0.2021 0.0509 -0.9781 +vn 0.2407 0.0382 -0.9698 +vn -0.3944 0.9140 0.0947 +vn 0.6006 0.6934 0.3980 +vn -0.5216 -0.2347 0.8202 +vn 0.3522 -0.6292 0.6929 +vn 0.4028 -0.5404 0.7387 +vn 0.4429 -0.4573 0.7712 +vn 0.4939 -0.3278 0.8054 +vn -0.1700 0.8782 -0.4470 +vn 0.0488 -0.1185 -0.9918 +vn 0.1280 -0.0948 -0.9872 +vn -0.2972 -0.2112 -0.9312 +vn -0.3550 -0.2249 -0.9074 +vn 0.4767 -0.8515 -0.2184 +vn -0.4111 -0.9097 0.0581 +vn 0.1657 -0.3902 0.9057 +vn 0.0997 -0.4098 0.9067 +vn -0.0469 -0.4459 0.8939 +vn -0.1062 -0.4576 0.8828 +vn 0.2866 0.4832 0.8272 +vn -0.3981 0.6637 0.6332 +vn 0.0422 -0.4647 -0.8845 +vn 0.7087 0.0514 -0.7036 +vn -0.9973 0.0719 -0.0122 +vn -0.9585 0.2811 -0.0477 +vn -0.9248 0.3751 -0.0636 +vn 0.9942 0.1071 0.0011 +vn 0.9635 0.2678 0.0028 +vn 0.9064 0.4224 0.0044 +vn -0.2941 -0.6192 0.7281 +vn 0.5747 -0.7874 0.2232 +vn -0.5089 -0.7358 -0.4468 +vn 0.4308 -0.0391 -0.9016 +vn 0.3564 0.0016 -0.9343 +vn 0.1387 0.1122 -0.9840 +vn 0.0045 0.1750 -0.9846 +vn -0.0001 0.9999 -0.0147 +vn -0.0487 0.9983 -0.0322 +vn 0.1270 0.9914 0.0312 +vn 0.1714 0.9841 0.0473 +vn 0.0780 0.8168 0.5716 +vn -0.6212 -0.5009 -0.6027 +vn 0.5129 -0.8385 -0.1841 +vn -0.4323 -0.7354 0.5219 +vn 0.1249 -0.6570 0.7435 +vn 0.0001 0.2126 0.9771 +vn -0.0667 0.2317 0.9705 +vn 0.1509 0.1654 0.9746 +vn 0.2384 0.1356 0.9617 +vn -0.3310 0.8151 0.4755 +vn 0.3920 0.9049 0.1658 +vn -0.3992 0.7557 -0.5192 +vn 0.1787 0.6560 -0.7333 +vn -0.5747 -0.8133 -0.0902 +vn -0.4455 -0.8585 -0.2541 +vn -0.4531 -0.8570 -0.2454 +vn -0.2847 -0.8634 -0.4166 +vn -0.9992 -0.0222 -0.0344 +vn -0.9607 -0.1506 -0.2334 +vn -0.9291 -0.2005 -0.3107 +vn 0.9917 0.0920 -0.0894 +vn 0.9813 0.1381 -0.1341 +vn 0.9402 0.2444 -0.2373 +vn 0.9997 -0.0099 0.0203 +vn 0.9994 -0.0342 0.0038 +vn 0.9996 -0.0184 -0.0219 +vn 0.9993 -0.0255 -0.0279 +vn 0.9996 -0.0121 0.0239 +vn 0.9994 0.0106 -0.0322 +vn 0.9998 0.0199 0.0024 +vn 0.9997 0.0211 -0.0138 +vn -0.9997 0.0163 0.0172 +vn -0.9997 0.0227 0.0105 +vn -0.9997 0.0161 0.0174 +vn -0.9996 0.0067 0.0271 +vn 0.0097 -0.3944 -0.9189 +vn -0.0141 -0.1790 -0.9837 +vn 0.0080 -0.3795 -0.9252 +vn -0.0162 -0.1594 -0.9871 +vn -0.0123 0.9977 -0.0661 +vn 0.0041 0.9980 0.0628 +vn 0.0027 0.9986 0.0521 +vn -0.0135 0.9970 -0.0758 +vn 0.0025 0.1277 0.9918 +vn -0.0178 -0.1648 0.9862 +vn 0.0013 0.1110 0.9938 +vn -0.0188 -0.1805 0.9834 +vn 0.0038 -0.8751 0.4840 +vn -0.0186 -0.9867 0.1617 +vn 0.0027 -0.8835 0.4685 +vn -0.0199 -0.9897 0.1415 +vn -0.9909 0.0697 -0.1150 +vn -0.9951 -0.0187 -0.0968 +vn -0.9952 -0.0946 -0.0236 +vn -0.9936 -0.1018 -0.0480 +vn -0.9952 -0.0830 0.0516 +vn -0.9958 -0.0483 0.0784 +vn -0.9962 -0.0017 0.0866 +vn -0.9932 0.0789 0.0860 +vn -0.9956 0.0891 0.0287 +vn -0.9927 0.1072 -0.0560 +vn 0.0355 -0.9874 -0.1541 +vn -0.0026 -0.9976 -0.0688 +vn 0.1053 -0.9454 -0.3083 +vn -0.1495 -0.6005 -0.7855 +vn 0.1462 -0.1583 -0.9765 +vn -0.1214 0.4524 -0.8835 +vn 0.1747 0.8555 -0.4874 +vn 0.0429 0.9428 -0.3306 +vn 0.0503 0.9392 -0.3398 +vn -0.1118 0.9853 -0.1292 +vn 0.0944 0.5357 0.8391 +vn 0.0331 0.5800 0.8139 +vn 0.1104 0.5235 0.8448 +vn 0.1585 0.4852 0.8599 +vn -0.0023 -0.6970 0.7170 +vn -0.1296 -0.5464 0.8275 +vn -0.0162 -0.6823 0.7309 +vn 0.1070 -0.7979 0.5933 +vn -0.0772 -0.9920 0.0999 +vn -0.0912 -0.3260 0.9410 +vn 0.4922 0.3316 0.8049 +vn -0.2678 0.9461 -0.1819 +vn 0.1108 -0.6506 -0.7513 +vn 0.2795 -0.4970 -0.8215 +vn 0.2714 -0.5054 -0.8191 +vn 0.4077 -0.3479 -0.8443 +vn 0.0586 0.9242 -0.3774 +vn 0.0295 0.9332 -0.3582 +vn -0.1218 0.9770 -0.1750 +vn -0.1695 0.9731 -0.1563 +vn 0.1234 0.2179 0.9681 +vn 0.0866 0.2049 0.9749 +vn -0.0148 0.1678 0.9857 +vn -0.0545 0.1526 0.9868 +vn 0.0476 -0.9135 0.4040 +vn 0.0106 -0.9216 0.3879 +vn -0.0517 -0.9318 0.3593 +vn -0.0863 -0.9355 0.3427 +vn 0.1161 -0.7557 -0.6445 +vn 0.0690 -0.7432 -0.6655 +vn -0.0215 -0.7135 -0.7003 +vn -0.0591 -0.6990 -0.7126 +vn -0.5205 -0.8438 0.1306 +vn 0.5452 0.0385 0.8374 +vn -0.4396 0.6348 0.6354 +vn 0.5048 0.8417 0.1915 +vn -0.6378 0.6669 -0.3853 +vn 0.5514 0.3830 -0.7411 +vn -0.3926 -0.4976 -0.7735 +vn -0.4895 -0.4952 -0.7178 +vn -0.1963 -0.4850 -0.8522 +vn -0.1432 -0.4781 -0.8666 +vn 0.1045 -0.9788 0.1762 +vn 0.1570 -0.9749 0.1577 +vn -0.0854 -0.9676 0.2376 +vn -0.1381 -0.9575 0.2531 +vn 0.0772 -0.4089 0.9093 +vn 0.0496 0.8497 -0.5249 +vn -0.9882 0.0662 0.1378 +vn -0.9924 0.0532 0.1108 +vn -0.9498 0.1355 0.2819 +vn 0.9867 0.0483 0.1551 +vn 0.9939 0.0327 0.1049 +vn 0.9504 0.0926 0.2970 +vn -0.4508 0.5488 0.7040 +vn -0.4795 0.4978 0.7227 +vn -0.3472 0.6983 0.6259 +vn 0.6306 0.1038 0.7691 +vn -0.6030 -0.5263 0.5995 +vn 0.5572 -0.8119 -0.1742 +vn -0.1758 -0.8138 -0.5539 +vn 0.1063 0.3245 -0.9399 +vn 0.0808 0.3160 -0.9453 +vn 0.1436 0.4278 -0.8924 +vn 0.1469 0.4695 -0.8706 +vn 0.1195 0.5731 -0.8107 +vn -0.1316 -0.9148 0.3820 +vn 0.0392 -0.2292 0.9726 +vn 0.0954 -0.2485 0.9639 +vn -0.1411 -0.1622 0.9766 +vn -0.1894 -0.1430 0.9714 +vn 0.2640 0.6199 0.7389 +vn -0.5527 0.7550 0.3528 +vn 0.5066 0.8565 -0.0989 +vn -0.4701 0.4046 -0.7844 +vn 0.0356 0.2959 -0.9546 +vn 0.0483 -0.6562 -0.7530 +vn 0.1318 -0.6287 -0.7664 +vn -0.1961 -0.7063 -0.6803 +vn -0.2586 -0.7116 -0.6533 +vn -0.5682 0.2972 0.7674 +vn 0.4821 -0.6042 0.6345 +vn -0.9822 -0.1867 -0.0209 +vn -0.9969 -0.0787 -0.0088 +vn -0.9516 -0.3054 -0.0342 +vn 0.9838 -0.1639 -0.0729 +vn 0.9920 -0.1156 -0.0514 +vn 0.9402 -0.3113 -0.1385 +vn 0.9963 -0.0550 0.0656 +vn 0.9981 -0.0298 -0.0542 +vn 0.9988 0.0422 0.0231 +vn -0.9999 0.0076 -0.0126 +vn -0.9949 -0.0668 -0.0757 +vn -0.9998 0.0175 -0.0042 +vn -0.9946 0.0874 0.0553 +vn 0.0448 -0.7473 -0.6630 +vn -0.0859 -0.9953 0.0451 +vn 0.0406 -0.6436 0.7643 +vn -0.0864 -0.0360 0.9956 +vn 0.0578 0.9031 0.4255 +vn -0.0776 0.9883 -0.1313 +vn 0.0099 0.4680 -0.8837 +vn -0.0005 0.4083 -0.9129 +vn -0.0488 0.1043 -0.9934 +vn -0.0591 0.0339 -0.9977 +vn -0.9887 0.1330 -0.0690 +vn -0.9902 0.0553 -0.1286 +vn -0.9864 -0.0283 -0.1617 +vn -0.9923 -0.0987 -0.0748 +vn -0.9823 0.0834 0.1678 +vn -0.9915 0.1295 0.0090 +vn -0.9868 0.0272 0.1599 +vn -0.9908 -0.0954 0.0958 +vn -0.9808 -0.1941 0.0196 +vn 0.1637 -0.8856 -0.4346 +vn -0.1410 -0.9840 0.1090 +vn -0.1068 -0.9826 0.1520 +vn -0.1108 -0.9829 0.1471 +vn -0.0586 -0.9757 0.2112 +vn 0.0982 -0.3753 0.9217 +vn -0.0052 -0.2592 0.9658 +vn -0.0049 -0.2595 0.9657 +vn -0.1018 -0.1443 0.9843 +vn 0.1035 0.6461 0.7562 +vn 0.0053 0.7341 0.6791 +vn 0.0094 0.7308 0.6826 +vn -0.0892 0.8025 0.5899 +vn -0.0138 0.9118 -0.4104 +vn 0.1164 0.9726 -0.2012 +vn 0.0350 0.8317 -0.5540 +vn -0.0399 0.7573 -0.6518 +vn 0.0866 0.5782 -0.8113 +vn -0.0775 -0.1769 -0.9812 +vn -0.0134 -0.1107 -0.9938 +vn -0.0764 -0.1757 -0.9815 +vn -0.1254 -0.2257 -0.9661 +vn 0.2787 -0.8841 -0.3750 +vn 0.7955 -0.3116 -0.5197 +vn 0.5043 -0.5078 0.6984 +vn 0.6157 0.4672 0.6345 +vn 0.6564 0.4169 0.6288 +vn 0.6433 0.4336 0.6310 +vn 0.6886 0.3729 0.6220 +vn 0.1448 0.6931 -0.7061 +vn 0.9706 0.1464 -0.1910 +vn 0.9960 -0.0085 -0.0893 +vn 0.9949 0.0140 -0.0996 +vn 0.9995 0.0200 -0.0234 +vn -1.0000 -0.0002 0.0004 +vn -1.0000 -0.0001 0.0002 +vn 0.9604 0.1185 -0.2521 +vn 0.9797 0.0483 -0.1947 +vn 0.9771 0.0572 -0.2051 +vn 0.9985 0.0447 -0.0330 +vn 0.9995 0.0299 0.0031 +vn 0.9497 0.1363 -0.2819 +vn -0.9967 0.0707 -0.0400 +vn -0.9169 0.1732 -0.3596 +vn -0.8802 0.1364 -0.4545 +vn -0.9572 0.0841 -0.2770 +vn -0.9986 0.0527 0.0029 +vn -0.9884 0.0594 -0.1398 +vn 0.9497 0.1362 -0.2818 +vn -0.9931 0.1062 -0.0498 +vn -0.8929 0.1800 -0.4126 +vn -0.8966 0.1661 -0.4105 +vn -0.9564 0.0858 -0.2793 +vn -0.9964 0.0842 0.0046 +vn -0.9887 0.0585 -0.1378 +vn -0.8929 0.1800 -0.4128 +vn -0.8966 0.1662 -0.4106 +vn -0.8965 0.1662 -0.4106 +vn 0.9801 0.0782 -0.1825 +vn 0.9865 0.0526 -0.1550 +vn 0.9855 0.0565 -0.1598 +vn 0.9996 0.0104 -0.0247 +vn 0.9752 0.0883 -0.2028 +vn 0.9805 0.0772 -0.1808 +vn 0.9866 0.0525 -0.1542 +vn 0.9857 0.0564 -0.1589 +vn 0.9996 0.0105 -0.0247 +vn 0.9757 0.0872 -0.2009 +vn -0.9982 -0.0582 -0.0164 +vn -0.9922 0.0487 -0.1145 +vn -0.9986 -0.0260 -0.0457 +vn -0.9898 0.0576 -0.1302 +vn -0.0614 0.5427 -0.8377 +vn -0.0673 0.5418 -0.8378 +vn -0.0001 0.5506 -0.8347 +vn 0.0062 0.5513 -0.8343 +vn 0.0134 0.6035 -0.7972 +vn 0.0134 0.6036 -0.7972 +vn 0.0112 0.6037 -0.7972 +vn 1.0000 0.0078 0.0040 +vn 0.9958 0.0862 0.0311 +vn 0.9621 0.2716 -0.0258 +vn 0.9995 0.0078 -0.0298 +vn 0.9891 0.1340 -0.0617 +vn 0.9896 0.1361 -0.0475 +vn 0.9997 -0.0025 -0.0255 +vn -1.0000 -0.0000 0.0003 +vn -0.9999 0.0100 -0.0048 +vn -0.9999 0.0129 0.0028 +vn -0.9762 0.2155 -0.0229 +vn -0.9714 0.2347 -0.0368 +vn 0.9868 0.0026 -0.1620 +vn 0.9879 0.0046 -0.1552 +vn 0.9881 0.0051 -0.1535 +vn 0.9856 0.0004 -0.1692 +vn 0.9743 0.2125 0.0742 +vn 0.9994 0.0078 0.0343 +vn 0.9996 -0.0036 0.0294 +vn 0.9841 0.1551 0.0866 +vn 0.9792 0.2011 0.0279 +vn 0.9467 0.3204 -0.0325 +vn 0.9995 0.0080 -0.0321 +vn 0.9859 0.1582 -0.0552 +vn 0.9911 0.1183 -0.0608 +vn 0.9996 -0.0033 -0.0273 +vn -0.9851 0.0021 -0.1720 +vn -0.9866 0.0048 -0.1629 +vn -0.9863 0.0043 -0.1648 +vn -0.9837 -0.0002 -0.1799 +vn -0.9985 -0.0517 0.0195 +vn -0.9995 0.0321 0.0080 +vn -0.9782 0.2072 0.0136 +vn -0.9728 0.2303 -0.0247 +vn -0.9620 0.2580 -0.0894 +vn -0.9875 0.1314 -0.0868 +vn -0.9997 0.0179 -0.0186 +vn 0.9998 0.0174 0.0079 +vn 0.9866 0.1496 0.0653 +vn 0.9832 0.1673 0.0730 +vn 0.9914 0.1296 0.0194 +vn 0.9908 0.1322 0.0280 +vn 1.0000 0.0001 -0.0023 +vn 0.9987 -0.0500 -0.0135 +vn -0.9862 -0.0030 -0.1657 +vn -0.9845 -0.0002 -0.1754 +vn -0.9874 -0.0052 -0.1582 +vn -0.9877 -0.0058 -0.1562 +vn -0.9830 0.1720 0.0647 +vn -0.9764 0.2047 0.0689 +vn -0.9710 0.2385 0.0143 +vn -0.9994 -0.0025 0.0355 +vn -0.9991 0.0113 0.0415 +vn -0.9712 0.2361 -0.0309 +vn -0.9658 0.2431 -0.0903 +vn -0.9825 0.1547 -0.1036 +vn -0.9995 0.0220 -0.0228 +vn 0.9887 0.1246 0.0833 +vn 0.9997 0.0171 0.0187 +vn 0.9655 0.2461 0.0852 +vn 0.9758 0.2173 0.0258 +vn 0.9459 0.3227 -0.0332 +vn 0.9911 0.1182 -0.0608 +vn -0.9997 0.0196 0.0132 +vn -0.9976 0.0475 0.0506 +vn -0.9971 0.0524 0.0559 +vn 0.0426 0.9988 -0.0221 +vn -0.9853 0.1578 0.0662 +vn -0.9877 0.1441 0.0605 +vn -0.9880 0.1481 0.0444 +vn -0.9843 0.1651 0.0628 +vn -0.9712 0.2378 0.0142 +vn -0.9996 -0.0019 0.0270 +vn -0.9995 0.0086 0.0315 +vn -0.9713 0.2361 -0.0309 +vn -0.9658 0.2432 -0.0903 +vn 0.9455 0.3240 -0.0332 +vn 0.9736 0.1806 -0.1393 +vn 0.9752 0.2135 -0.0577 +vn 0.9583 0.2449 -0.1474 +vn 0.9757 0.1718 -0.1357 +vn 0.9854 0.0036 -0.1701 +vn 0.9872 0.0068 -0.1591 +vn 0.9877 0.0076 -0.1564 +vn 0.9835 0.0004 -0.1809 +vn 0.9999 0.0007 0.0111 +vn 0.9974 0.0603 0.0399 +vn 0.9805 0.1923 0.0415 +vn 0.9741 0.2257 0.0124 +vn 0.9997 0.0052 -0.0221 +vn 0.9907 0.1265 -0.0507 +vn 0.9811 0.1919 -0.0246 +vn 0.9998 -0.0028 -0.0188 +vn -0.9883 0.1396 -0.0620 +vn -0.9799 0.1689 -0.1058 +vn -0.9782 0.1766 -0.1091 +vn -0.9726 0.2322 0.0103 +vn -0.9808 0.1924 -0.0304 +vn -0.9902 0.1210 -0.0700 +vn 0.0310 0.8075 -0.5891 +vn -0.0063 0.8030 -0.5959 +vn 0.2377 0.8107 -0.5351 +vn 0.2574 0.8090 -0.5285 +vn -0.4393 0.8522 -0.2841 +vn 0.5036 0.8586 -0.0957 +vn -0.5036 0.8586 0.0957 +vn 0.4393 0.8523 0.2841 +vn -0.2379 0.8106 0.5351 +vn -0.2576 0.8089 0.5284 +vn -0.0311 0.8075 0.5891 +vn 0.0063 0.8030 0.5960 +vn -0.0139 0.8029 -0.5959 +vn 0.5060 0.7221 -0.4717 +vn -0.7324 0.6459 -0.2153 +vn 0.7886 0.6111 -0.0681 +vn -0.7886 0.6111 0.0681 +vn 0.7324 0.6459 0.2153 +vn -0.5060 0.7221 0.4717 +vn 0.0139 0.8029 0.5959 +vn 0.5056 0.7223 -0.4718 +vn -0.7325 0.6459 -0.2153 +vn -0.0172 -0.0054 -0.9998 +vn -0.0308 -0.0106 -0.9995 +vn 0.0170 0.0074 -0.9998 +vn 0.0305 0.0125 -0.9995 +vn 0.0019 0.9418 -0.3360 +vn 0.0022 0.9375 -0.3480 +vn 0.0161 0.9736 -0.2277 +vn 0.0236 0.8350 -0.5497 +vn -0.0099 0.7613 -0.6483 +vn -0.0087 0.7577 -0.6525 +vn 0.0160 0.8736 -0.4864 +vn 0.0209 0.8730 -0.4873 +vn 0.9999 0.0107 0.0110 +vn 0.9972 0.0473 0.0583 +vn 0.9764 0.0597 0.2078 +vn 0.9957 -0.0112 0.0922 +vn 1.0000 -0.0013 0.0055 +vn -0.9747 0.0803 0.2086 +vn -0.9984 0.0516 0.0214 +vn -0.9989 0.0462 0.0095 +vn -1.0000 -0.0022 0.0067 +vn -0.9986 -0.0094 0.0530 +vn -0.9809 0.1037 0.1644 +vn -0.0060 0.5959 0.8030 +vn -0.0193 0.5982 0.8011 +vn 0.0123 0.4987 0.8667 +vn -0.0290 0.4079 0.9126 +vn 0.0276 0.1651 0.9859 +vn -0.0493 0.0161 0.9987 +vn 0.1476 -0.1393 0.9792 +vn 0.1619 -0.1404 0.9768 +vn -0.1271 -0.5437 0.8296 +vn -0.1368 -0.5418 0.8293 +vn -0.0059 -0.5630 0.8264 +vn 0.0077 -0.5647 0.8253 +vn 0.9998 -0.0081 0.0184 +vn 0.9769 -0.0767 0.1996 +vn 0.9986 -0.0130 0.0513 +vn 0.9767 0.1074 0.1859 +vn 0.8938 0.1348 0.4277 +vn 0.9315 0.0491 0.3603 +vn 0.8760 -0.0363 0.4809 +vn 0.9548 -0.0951 0.2816 +vn 0.9757 -0.0841 0.2024 +vn 0.9986 -0.0523 0.0122 +vn -0.9997 -0.0089 0.0208 +vn -0.9792 -0.0694 0.1906 +vn -0.9776 -0.0803 0.1947 +vn -0.9851 -0.0398 0.1675 +vn -0.9160 -0.0022 0.4012 +vn -0.9572 0.0017 0.2893 +vn -0.8794 0.1331 0.4571 +vn -0.9784 0.1112 0.1742 +vn -0.9988 -0.0038 0.0483 +vn -0.9986 -0.0529 0.0027 +vn -0.0420 0.5898 0.8065 +vn 0.0174 -0.5892 0.8078 +vn 0.7926 0.1319 0.5953 +vn 0.9317 0.1581 0.3272 +vn 0.7298 0.1347 0.6702 +vn 0.9805 0.0130 0.1960 +vn 0.9814 0.0596 0.1825 +vn 0.9814 0.0244 0.1905 +vn 0.9780 -0.0629 0.1988 +vn 0.9839 -0.0248 0.1770 +vn 0.9901 -0.0620 0.1258 +vn 0.9990 0.0224 0.0374 +vn 0.9987 0.0510 0.0095 +vn 0.9995 0.0324 -0.0033 +vn 0.9984 0.0470 0.0310 +vn -0.9998 -0.0078 0.0180 +vn -0.9808 -0.0707 0.1817 +vn -0.9776 -0.0775 0.1957 +vn -0.9731 -0.0684 0.2200 +vn -0.9261 -0.0303 0.3761 +vn -0.9415 0.0229 0.3362 +vn -0.8771 0.1397 0.4595 +vn -0.9766 0.1135 0.1826 +vn -0.9988 -0.0056 0.0494 +vn -0.9988 -0.0490 0.0076 +vn -0.0140 0.5891 0.8080 +vn 0.0160 -0.5892 0.8078 +vn 0.9981 -0.0507 0.0357 +vn 0.9992 -0.0385 0.0070 +vn 0.9474 -0.1260 0.2941 +vn 0.9228 0.1188 0.3665 +vn 0.9414 0.1430 0.3053 +vn 0.9399 0.0438 0.3387 +vn 0.9398 0.0461 0.3385 +vn 0.9266 -0.0635 0.3707 +vn 0.9296 -0.0876 0.3581 +vn 0.9414 -0.1421 0.3060 +vn 0.9995 0.0299 -0.0030 +vn 0.9986 0.0440 0.0304 +vn -0.9817 -0.0683 0.1775 +vn -0.9864 -0.0401 0.1597 +vn -0.9690 -0.0184 0.2464 +vn -0.9753 0.0121 0.2206 +vn -0.9090 0.1334 0.3950 +vn -0.9651 0.1410 0.2207 +vn -0.9986 -0.0025 0.0524 +vn 0.9795 -0.0702 0.1890 +vn 0.7836 0.1308 0.6073 +vn 0.9312 0.1580 0.3285 +vn 0.6886 0.1404 0.7114 +vn 0.9737 -0.0044 0.2278 +vn 0.9859 0.0521 0.1589 +vn 0.9832 0.0385 0.1785 +vn 0.9881 -0.0325 0.1501 +vn -0.9966 -0.0744 0.0363 +vn -0.9187 -0.1584 0.3618 +vn -0.9984 -0.0563 -0.0064 +vn -0.9092 -0.1811 0.3748 +vn -0.9255 -0.0805 0.3701 +vn -0.9243 -0.0579 0.3773 +vn -0.9217 0.0414 0.3857 +vn -0.9235 0.0356 0.3820 +vn -0.9097 0.1482 0.3880 +vn -0.9493 0.1685 0.2654 +vn -0.9982 0.0048 0.0594 +vn 0.0174 -0.5891 0.8078 +vn 0.9998 -0.0080 0.0181 +vn 0.9769 -0.0766 0.1993 +vn 0.9767 0.1075 0.1859 +vn 0.8938 0.1349 0.4278 +vn -0.9864 -0.0401 0.1596 +vn 0.9998 -0.0087 0.0198 +vn 0.9774 -0.0753 0.1975 +vn 0.8812 0.1037 0.4612 +vn 0.9747 0.0861 0.2062 +vn 0.9549 0.0622 0.2904 +vn 0.8970 -0.0223 0.4414 +vn 0.9634 -0.0831 0.2549 +vn 0.9762 -0.0829 0.2003 +vn 0.9997 0.0094 0.0219 +vn -0.9808 -0.0708 0.1817 +vn -0.8772 0.1397 0.4594 +vn -0.0140 0.5891 0.8079 +vn 0.0076 0.9962 -0.0869 +vn 0.0106 0.9942 -0.1066 +vn -0.0104 0.9917 0.1281 +vn 0.0097 0.9610 0.2763 +vn -0.0011 0.9178 0.3970 +vn 0.0075 0.9718 0.2359 +vn 0.0130 0.8370 0.5471 +vn -0.6863 0.3668 0.6280 +vn 0.7162 0.4321 0.5481 +vn 0.0442 0.7632 0.6446 +vn -0.4770 0.7003 0.5311 +vn -0.1698 0.7394 0.6515 +vn -0.4859 0.6981 0.5260 +vn 0.7375 0.1146 0.6655 +vn -0.6253 -0.1595 0.7640 +vn 0.5693 -0.4378 0.6959 +vn -0.2142 -0.6121 0.7612 +vn -0.1597 -0.5734 0.8035 +vn -0.2173 -0.5898 0.7778 +vn -0.3489 -0.6040 0.7166 +vn 0.3382 -0.8077 0.4830 +vn 0.6639 -0.5988 -0.4480 +vn 0.6002 -0.6284 -0.4948 +vn 0.6718 -0.5946 -0.4417 +vn 0.5474 -0.6485 -0.5289 +vn -0.2227 -0.4655 -0.8566 +vn 0.0623 -0.1764 -0.9823 +vn 0.2119 -0.1651 -0.9632 +vn 0.3162 -0.1547 -0.9360 +vn 0.6325 0.1486 -0.7602 +vn -0.5402 0.0414 -0.8405 +vn -0.5631 0.2665 -0.7822 +vn 0.8190 0.3533 -0.4520 +vn 0.7697 0.3979 -0.4992 +vn 0.5123 0.5581 -0.6528 +vn 0.5006 0.5632 -0.6574 +vn 0.8387 0.3299 -0.4333 +vn 0.6340 0.7159 0.2925 +vn -0.7135 0.6224 -0.3218 +vn 0.1744 0.6816 0.7106 +vn 0.1444 0.7782 0.6112 +vn 0.0940 0.8079 0.5818 +vn 0.1080 0.6600 0.7434 +vn 0.2691 0.4505 0.8513 +vn 0.2765 -0.2467 0.9288 +vn -0.2506 -0.5951 0.7636 +vn -0.2578 -0.5935 0.7625 +vn -0.0312 -0.7075 0.7061 +vn -0.0311 -0.7291 0.6837 +vn -0.0524 -0.7985 0.5998 +vn 0.4536 -0.7210 -0.5239 +vn 0.4399 -0.7146 -0.5440 +vn 0.4625 -0.6725 -0.5778 +vn 0.6117 -0.5203 -0.5959 +vn 0.6446 -0.4838 -0.5919 +vn -0.7258 -0.3320 -0.6025 +vn 0.6296 -0.2503 -0.7355 +vn 0.0354 -0.0743 -0.9966 +vn -0.2092 -0.1646 -0.9639 +vn -0.0121 -0.0702 -0.9975 +vn -0.0083 0.1712 -0.9852 +vn -0.0101 0.1802 -0.9836 +vn -0.0196 0.3210 -0.9469 +vn 0.8398 0.2294 -0.4920 +vn -0.7629 0.4279 -0.4846 +vn 0.1208 0.5696 -0.8130 +vn 0.3207 0.5850 -0.7449 +vn 0.1741 0.6301 -0.7568 +vn 0.2529 0.8303 0.4966 +vn -0.0792 0.6155 0.7841 +vn 0.3756 0.7421 0.5551 +vn 0.1951 0.7494 0.6328 +vn -0.0648 0.6809 0.7295 +vn -0.1483 0.5115 0.8464 +vn 0.6870 0.1408 0.7129 +vn -0.5321 -0.1791 0.8275 +vn 0.2715 -0.2508 0.9292 +vn -0.2436 -0.5929 0.7675 +vn -0.2524 -0.5910 0.7662 +vn 0.0055 -0.6929 0.7210 +vn -0.0223 -0.7430 0.6689 +vn -0.0655 -0.7975 0.5997 +vn 0.4167 -0.6886 -0.5934 +vn 0.4314 -0.7408 -0.5149 +vn 0.4115 -0.7353 -0.5385 +vn 0.5626 -0.5402 -0.6259 +vn 0.5998 -0.5008 -0.6240 +vn 0.6505 -0.2416 -0.7200 +vn 0.6214 -0.2341 -0.7477 +vn 0.4167 -0.1485 -0.8968 +vn 0.5017 -0.0522 -0.8635 +vn 0.5303 -0.0313 -0.8472 +vn -0.2764 0.1029 -0.9555 +vn -0.3421 0.0314 -0.9391 +vn -0.1220 0.2570 -0.9587 +vn -0.0447 0.3277 -0.9437 +vn 0.0615 0.6211 -0.7813 +vn 0.1625 0.6052 -0.7793 +vn 0.0680 0.6182 -0.7831 +vn 0.3617 0.7325 0.5767 +vn -0.7948 0.5315 0.2929 +vn 0.7243 0.6605 0.1980 +vn -0.7709 0.6368 0.0129 +vn 0.6524 0.7513 -0.0997 +vn -0.3915 0.8059 -0.4441 +vn -0.4147 0.7963 -0.4403 +vn -0.1023 0.6960 -0.7108 +vn -0.0711 0.6517 -0.7552 +vn -0.0451 0.6684 0.7424 +vn 0.0894 0.7713 0.6301 +vn 0.1000 0.7876 0.6081 +vn -0.0734 0.6891 0.7209 +vn -0.1449 0.5258 0.8382 +vn -0.5547 -0.5201 0.6494 +vn -0.5880 -0.4852 0.6471 +vn -0.4325 -0.6610 0.6132 +vn -0.4295 -0.7095 0.5587 +vn -0.4525 -0.7205 0.5255 +vn 0.4535 -0.7210 -0.5239 +vn 0.6117 -0.5202 -0.5959 +vn 0.6447 -0.4837 -0.5919 +vn -0.7255 -0.3322 -0.6027 +vn 0.6506 -0.2416 -0.7200 +vn 0.6215 -0.2342 -0.7476 +vn 0.4168 -0.1485 -0.8968 +vn 0.0408 0.6087 -0.7923 +vn -0.2517 0.8311 -0.4959 +vn -0.1080 0.6823 -0.7230 +vn -0.0670 0.6424 -0.7634 +vn -0.4885 0.8716 -0.0405 +vn 0.2614 0.9222 0.2850 +vn -0.2069 0.7796 0.5910 +vn -0.0429 0.7482 0.6621 +vn -0.0361 0.7120 0.7012 +vn -0.0565 0.6905 0.7212 +vn 0.7292 0.1349 0.6708 +vn -0.6364 -0.0804 0.7672 +vn 0.6704 -0.1934 0.7163 +vn -0.7466 -0.3187 0.5839 +vn 0.6878 -0.4567 0.5642 +vn 0.6547 -0.4944 0.5718 +vn 0.4621 -0.6835 0.5651 +vn 0.4283 -0.7266 0.5372 +vn 0.4416 -0.7361 0.5129 +vn -0.0702 0.6491 -0.7574 +vn -0.1103 0.6893 -0.7161 +vn -0.2577 0.8434 -0.4714 +vn 0.4313 0.8029 -0.4114 +vn 0.1554 0.6961 0.7009 +vn 0.0478 0.7906 0.6105 +vn 0.0175 0.8124 0.5828 +vn 0.1018 0.6561 0.7478 +vn 0.2767 -0.2467 0.9288 +vn -0.2431 -0.5930 0.7676 +vn -0.2519 -0.5911 0.7663 +vn 0.5892 -0.2332 -0.7736 +vn 0.2820 -0.2428 -0.9282 +vn 0.0560 0.8434 0.5343 +vn -0.0680 0.7899 0.6094 +vn 0.3641 0.5952 0.7164 +vn 0.4041 0.6399 0.6537 +vn 0.5394 0.3992 0.7414 +vn -0.8248 0.0211 0.5650 +vn 0.6644 -0.1807 0.7252 +vn -0.7499 -0.3053 0.5869 +vn 0.3149 -0.5240 0.7913 +vn 0.1557 -0.6702 0.7257 +vn 0.2789 -0.6480 0.7087 +vn 0.1047 -0.7809 0.6158 +vn 0.0286 -0.7681 0.6397 +vn 0.0256 -0.8295 0.5580 +vn 0.2955 -0.7495 -0.5924 +vn 0.4108 -0.6369 -0.6524 +vn 0.2875 0.0191 -0.9576 +vn 0.0320 -0.2374 -0.9709 +vn -0.0077 0.1623 -0.9867 +vn -0.0097 0.1736 -0.9848 +vn -0.0186 0.3065 -0.9517 +vn 0.4906 0.4975 -0.7154 +vn 0.3013 0.6449 -0.7024 +vn 0.4187 0.6254 -0.6585 +vn 0.0552 0.7449 -0.6649 +vn -0.2612 0.7332 0.6278 +vn 0.0000 0.6486 0.7611 +vn -0.1108 0.7284 0.6761 +vn -0.2832 0.8170 0.5024 +vn 0.3782 0.8058 0.4556 +vn -0.0071 0.9948 0.1014 +vn -0.4550 0.7694 -0.4483 +vn -0.2464 0.6750 -0.6954 +vn -0.3488 0.6417 -0.6830 +vn -0.1326 0.5907 -0.7959 +vn 0.0089 0.5324 0.8465 +vn 0.0247 0.2285 0.9732 +vn 0.0155 0.3242 0.9459 +vn 0.0049 0.3724 0.9281 +vn -0.0248 0.0563 0.9981 +vn 0.0052 -0.0666 0.9978 +vn -0.0060 -0.3093 0.9510 +vn -0.0026 -0.3665 0.9304 +vn 0.0132 -0.2359 0.9717 +vn 0.0034 -0.5321 0.8467 +vn -0.0025 -0.0027 -1.0000 +vn 0.0004 -0.0020 -1.0000 +vn -0.0098 -0.0005 -1.0000 +vn -0.0044 0.2446 -0.9696 +vn 0.0216 0.7620 0.6472 +vn 0.0088 0.7760 0.6307 +vn 0.0147 0.7695 0.6384 +vn 0.0277 0.7552 0.6550 +vn -0.9722 0.2339 -0.0105 +vn -0.9714 0.2058 -0.1181 +vn -0.9416 0.3252 -0.0870 +vn -0.9973 0.0649 -0.0357 +vn -0.9980 -0.0216 0.0599 +vn -0.9989 -0.0204 0.0422 +vn -0.9984 -0.0217 0.0514 +vn -0.9991 -0.0313 0.0299 +vn -0.9891 0.1462 -0.0155 +vn -0.9993 0.0319 -0.0192 +vn -0.9996 -0.0203 0.0187 +vn -0.9993 -0.0377 0.0065 +vn -0.9998 0.0151 -0.0138 +vn -0.9999 0.0081 -0.0075 +vn -0.9958 -0.0720 0.0563 +vn -0.9657 -0.2474 0.0789 +vn -0.9641 -0.2530 0.0808 +vn 0.0038 0.9881 -0.1540 +vn -0.0304 0.9898 -0.1395 +vn -0.0973 0.9891 -0.1104 +vn -0.1264 0.9872 -0.0975 +vn 0.1219 -0.0697 0.9901 +vn 0.0961 -0.0793 0.9922 +vn 0.0251 -0.1054 0.9941 +vn -0.0031 -0.1156 0.9933 +vn 0.0495 0.9836 -0.1732 +vn 0.1208 0.9719 -0.2022 +vn 0.1765 0.9584 -0.2243 +vn -0.1366 0.8001 0.5841 +vn -0.3112 0.7315 0.6066 +vn 0.3156 -0.0239 0.9486 +vn 0.2609 -0.0488 0.9641 +vn 0.0795 -0.1272 0.9887 +vn -0.0039 -0.1612 0.9869 +vn -0.0290 0.9897 -0.1401 +vn -0.0931 0.9893 -0.1123 +vn -0.1212 0.9876 -0.0998 +vn 0.2167 -0.0685 0.9738 +vn 0.1737 -0.0873 0.9809 +vn 0.0521 -0.1385 0.9890 +vn 0.1433 -0.1004 0.9846 +vn 0.1133 -0.1131 0.9871 +vn 0.0436 -0.1420 0.9889 +vn 0.0146 -0.0702 0.9974 +vn 0.0108 -0.0721 0.9973 +vn 0.0028 -0.0762 0.9971 +vn -0.0024 -0.0789 0.9969 +vn 0.0443 0.9834 -0.1759 +vn -0.0599 0.9719 -0.2275 +vn 0.2111 0.9735 -0.0877 +vn 0.2800 0.9587 -0.0491 +vn -0.3130 0.7520 0.5801 +vn 0.2327 0.6308 0.7402 +vn 0.0016 -0.1184 0.9930 +vn 0.0003 -0.1189 0.9929 +vn -0.0021 -0.1197 0.9928 +vn -0.0032 -0.1201 0.9928 +vn -0.0273 0.9733 -0.2278 +vn 0.3320 0.9238 0.1909 +vn -0.1856 0.7780 0.6002 +vn 0.1981 0.0434 0.9792 +vn 0.1295 -0.0138 0.9915 +vn 0.0870 -0.0486 0.9950 +vn -0.0014 -0.1201 0.9928 +vn 0.0031 -0.1188 -0.9929 +vn 0.0215 -0.1292 -0.9914 +vn 0.0418 -0.1407 -0.9892 +vn 0.0578 -0.1496 -0.9870 +vn -0.1431 0.5995 -0.7875 +vn 0.3617 0.7490 -0.5552 +vn -0.4650 0.8520 0.2406 +vn -0.3055 0.9326 0.1923 +vn -0.1427 0.9798 0.1398 +vn -0.0369 0.9939 0.1041 +vn 0.0041 -0.1750 -0.9846 +vn -0.0282 -0.1596 -0.9868 +vn -0.0633 -0.1426 -0.9878 +vn -0.0839 -0.1325 -0.9876 +vn 0.1432 0.9882 0.0542 +vn 0.1181 0.9910 0.0634 +vn 0.0341 0.9951 0.0933 +vn 0.0036 0.9946 0.1040 +vn -0.0302 -0.1586 -0.9869 +vn -0.0859 -0.1315 -0.9876 +vn -0.1138 -0.1176 -0.9865 +vn 0.0014 -0.1161 -0.9932 +vn -0.0094 -0.1075 -0.9942 +vn -0.0127 -0.1048 -0.9944 +vn -0.0236 -0.0961 -0.9951 +vn -0.3742 0.6986 -0.6099 +vn -0.3056 0.7103 -0.6341 +vn 0.0267 0.9909 0.1317 +vn 0.0150 0.9897 0.1425 +vn 0.0135 0.9895 0.1440 +vn 0.0013 0.9879 0.1552 +vn 0.0304 -0.0981 -0.9947 +vn 0.0286 0.5123 -0.8583 +vn 0.4189 -0.0577 -0.9062 +vn -0.1909 0.5176 -0.8340 +vn -0.0084 -0.0953 -0.9954 +vn 0.0327 0.5124 -0.8581 +vn 0.0225 -0.1998 -0.9796 +vn -0.0480 -0.1744 -0.9835 +vn -0.2206 -0.1076 -0.9694 +vn -0.2607 -0.0911 -0.9611 +vn 0.3134 0.3910 -0.8654 +vn 0.2710 0.4108 -0.8705 +vn 0.0664 0.4906 -0.8688 +vn -0.0074 0.5134 -0.8581 +vn 0.0173 0.0366 0.9992 +vn 0.0061 0.0270 0.9996 +vn -0.0128 0.9997 0.0207 +vn -0.0149 0.9996 0.0230 +vn -0.0005 0.6056 -0.7958 +vn -0.0038 0.6084 -0.7937 +vn -0.0048 0.9979 -0.0653 +vn 0.0094 0.9970 -0.0771 +vn -0.0055 0.4929 -0.8701 +vn -0.0142 0.4741 -0.8804 +vn 0.0151 0.5122 -0.8587 +vn 0.9992 -0.0347 -0.0174 +vn 0.9993 -0.0354 -0.0144 +vn 0.9990 -0.0325 -0.0307 +vn 0.9990 -0.0322 -0.0311 +vn 0.9992 -0.0388 0.0056 +vn 0.9988 -0.0296 0.0383 +vn 0.9988 -0.0192 0.0451 +vn 0.9992 -0.0334 0.0239 +vn 0.9984 -0.0200 0.0529 +vn 0.9985 -0.0339 0.0438 +vn -0.9726 -0.2320 -0.0181 +vn -0.9821 -0.1872 0.0201 +vn -1.0000 -0.0013 -0.0054 +vn -1.0000 -0.0005 -0.0063 +vn -0.9996 0.0167 -0.0214 +vn -1.0000 0.0023 -0.0073 +vn -0.9739 -0.2214 -0.0500 +vn -0.9998 -0.0048 -0.0197 +vn -0.9474 -0.2893 -0.1370 +vn -0.9991 -0.0347 -0.0224 +vn -0.9952 -0.0706 -0.0681 +vn -0.9998 -0.0182 -0.0038 +vn -0.9996 -0.0224 -0.0167 +vn -0.9992 0.0029 -0.0410 +vn -0.9979 0.0576 0.0309 +vn -0.9996 -0.0006 0.0281 +vn -0.9995 -0.0226 0.0231 +vn -0.9960 0.0888 0.0124 +vn -0.9989 0.0272 0.0378 +vn -0.9972 0.0376 0.0640 +vn -0.9893 0.1304 0.0651 +vn -0.9971 0.0319 0.0695 +vn -0.9587 0.2828 0.0290 +vn -0.9772 -0.0043 0.2122 +vn -0.9788 -0.0262 0.2032 +vn -1.0000 0.0001 0.0001 +vn 0.9989 0.0239 -0.0396 +vn 0.9917 -0.0566 -0.1151 +vn 0.8540 0.0277 -0.5195 +vn 0.9650 -0.0667 -0.2536 +vn 0.9982 0.0599 -0.0080 +vn -0.9997 -0.0095 -0.0234 +vn -0.9811 -0.0779 -0.1769 +vn -0.9872 -0.0542 -0.1498 +vn -0.9754 -0.0880 -0.2021 +vn -0.9884 -0.0490 -0.1439 +vn 0.9999 -0.0048 -0.0122 +vn 0.9883 -0.0558 -0.1418 +vn 0.9834 -0.0665 -0.1691 +vn -0.9999 -0.0046 -0.0140 +vn -0.9877 -0.0487 -0.1483 +vn -0.9843 -0.0561 -0.1674 +vn -0.9842 -0.0563 -0.1676 +vn 0.9920 -0.0562 -0.1129 +vn 0.9856 -0.0714 -0.1533 +vn 0.9814 -0.0760 -0.1761 +vn -0.9806 -0.0761 -0.1809 +vn -0.9848 -0.0577 -0.1640 +vn -0.9752 -0.0861 -0.2041 +vn -0.9858 -0.0534 -0.1592 +vn -0.9878 -0.0487 -0.1483 +vn -0.9999 -0.0046 -0.0141 +vn -0.9877 -0.0488 -0.1487 +vn 0.9999 -0.0157 0.0025 +vn 0.9998 -0.0185 -0.0046 +vn 0.9955 -0.0489 -0.0812 +vn 0.9938 -0.0549 -0.0963 +vn -0.0010 -0.5507 -0.8347 +vn -0.0065 -0.5513 -0.8343 +vn 0.0536 -0.5437 -0.8375 +vn 0.0590 -0.5430 -0.8377 +vn -0.0155 -0.6038 -0.7970 +vn 0.2144 -0.4770 -0.8524 +vn -0.3310 -0.5204 -0.7871 +vn 0.5769 -0.4045 -0.7096 +vn 0.9988 -0.0110 -0.0479 +vn 0.9992 0.0048 -0.0409 +vn 0.9758 -0.2035 -0.0799 +vn 0.9812 -0.1693 0.0924 +vn 0.9992 0.0043 0.0394 +vn 0.9989 -0.0116 0.0464 +vn 0.9838 -0.1706 0.0552 +vn 0.9595 -0.2807 0.0243 +vn 0.9859 -0.1652 -0.0283 +vn 0.9815 -0.1625 -0.1009 +vn -1.0000 0.0003 -0.0001 +vn -1.0000 0.0008 -0.0006 +vn 0.9758 -0.2035 -0.0800 +vn 0.9992 -0.0032 0.0403 +vn 0.9988 -0.0164 0.0462 +vn 0.9829 -0.1590 0.0933 +vn 0.9835 -0.1740 0.0496 +vn 0.9599 -0.2792 0.0243 +vn 0.9772 -0.2098 -0.0324 +vn 0.9735 -0.2004 -0.1105 +vn -0.9990 -0.0098 0.0426 +vn -0.9993 0.0042 0.0365 +vn -0.9765 -0.2018 0.0757 +vn -0.9794 -0.1746 -0.1019 +vn -0.9991 -0.0008 -0.0434 +vn -0.9986 -0.0160 -0.0501 +vn -0.9811 -0.1863 -0.0518 +vn -0.9596 -0.2802 -0.0244 +vn -0.9772 -0.2099 0.0323 +vn -0.9781 -0.1819 0.1012 +vn 0.9793 -0.1943 0.0562 +vn 0.9735 -0.2003 -0.1105 +vn -0.9984 -0.0153 0.0540 +vn -0.9989 0.0006 0.0469 +vn -0.9718 -0.2194 0.0867 +vn -0.9595 -0.2805 -0.0245 +vn -0.9763 -0.2140 0.0314 +vn -0.9695 -0.2142 0.1191 +vn 0.9829 -0.1589 0.0933 +vn 0.9992 -0.0008 0.0392 +vn 0.9989 -0.0145 0.0453 +vn 0.9772 -0.2098 -0.0323 +vn -0.9990 -0.0125 0.0438 +vn -0.9993 0.0005 0.0381 +vn -0.9768 -0.2003 0.0755 +vn 0.9992 -0.0090 -0.0393 +vn 0.9994 0.0039 -0.0337 +vn 0.9797 -0.1876 -0.0704 +vn 0.9600 -0.2790 0.0242 +vn 0.9779 -0.2064 -0.0331 +vn 0.9805 -0.1719 -0.0948 +vn -0.9985 -0.0120 0.0525 +vn -0.9990 0.0052 0.0449 +vn -0.9714 -0.2212 0.0869 +vn -0.9718 -0.2195 0.0867 +vn -0.9989 -0.0036 -0.0459 +vn -0.9985 -0.0187 -0.0524 +vn -0.9789 -0.1794 -0.0978 +vn -0.9772 -0.2042 -0.0583 +vn -0.9591 -0.2818 -0.0245 +vn 0.9991 -0.0091 -0.0423 +vn 0.9993 0.0049 -0.0360 +vn 0.9801 -0.1848 -0.0728 +vn 1.0000 0.0004 -0.0002 +vn 0.9832 -0.1662 0.0760 +vn 0.9998 -0.0170 0.0145 +vn 0.9850 -0.1615 0.0606 +vn 0.9519 -0.3058 0.0212 +vn 0.9700 -0.2393 -0.0431 +vn 0.9778 -0.1840 -0.1003 +vn 0.0310 -0.8075 0.5891 +vn -0.0065 -0.8030 0.5960 +vn 0.2379 -0.8106 0.5351 +vn 0.2576 -0.8089 0.5284 +vn -0.4393 -0.8523 0.2841 +vn 0.5036 -0.8586 0.0957 +vn -0.5036 -0.8586 -0.0957 +vn 0.4393 -0.8523 -0.2841 +vn -0.2379 -0.8106 -0.5351 +vn -0.2576 -0.8089 -0.5284 +vn -0.0311 -0.8075 -0.5891 +vn 0.0063 -0.8030 -0.5960 +vn -0.0138 -0.8029 0.5959 +vn 0.5060 -0.7221 0.4717 +vn -0.7324 -0.6459 0.2153 +vn 0.7886 -0.6111 0.0681 +vn -0.7886 -0.6111 -0.0681 +vn 0.7325 -0.6459 -0.2153 +vn -0.5056 -0.7223 -0.4718 +vn 0.0142 -0.8029 -0.5959 +vn -0.0142 -0.8029 0.5959 +vn 0.7324 -0.6459 -0.2153 +vn -0.5060 -0.7221 -0.4717 +vn 0.5056 -0.7223 0.4718 +vn -0.7325 -0.6459 0.2153 +vn 0.0139 -0.8029 -0.5959 +vn 0.0113 -0.9389 -0.3440 +vn 0.0210 -0.9534 -0.3011 +vn 0.0294 -0.9545 -0.2967 +vn 0.0298 -0.9737 -0.2260 +vn 0.0140 -0.9245 -0.3808 +vn -0.0012 -0.7371 -0.6758 +vn -0.0073 -0.7289 -0.6846 +vn 0.0011 -0.7245 -0.6893 +vn 0.0133 -0.8495 0.5274 +vn 0.0313 -0.9734 0.2272 +vn 0.0182 -0.9416 0.3362 +vn 0.0008 -0.9548 0.2971 +vn 0.0215 -0.9985 0.0500 +vn -0.0147 -0.9973 -0.0723 +vn -0.0129 -0.7659 0.6428 +vn -0.0291 -0.7477 0.6634 +vn -0.0215 -0.7563 0.6538 +vn -0.0058 -0.7737 0.6335 +vn -0.0048 0.0138 0.9999 +vn 0.0911 0.0412 0.9950 +vn 0.3096 0.1029 0.9453 +vn 0.4692 0.1475 0.8707 +vn -0.4204 -0.5847 0.6938 +vn 0.5617 -0.8091 0.1730 +vn -0.0146 -0.9997 -0.0189 +vn -0.0254 0.0079 0.9996 +vn -0.1007 -0.0137 0.9948 +vn -0.1191 -0.0190 0.9927 +vn 0.1277 -0.9699 0.2074 +vn 0.1103 -0.9727 0.2040 +vn 0.0113 -0.9830 0.1832 +vn -0.0084 -0.9838 0.1789 +vn 0.0031 0.1156 0.9933 +vn -0.4691 -0.0696 0.8804 +vn 0.3523 -0.6809 0.6420 +vn -0.5477 -0.8279 0.1211 +vn 0.0234 -0.9933 -0.1128 +vn 0.0551 0.0309 0.9980 +vn 0.2220 0.0783 0.9719 +vn 0.3134 0.1040 0.9439 +vn -0.4001 -0.7054 0.5850 +vn 0.6420 -0.7497 0.1603 +vn -0.0193 -0.9828 -0.1838 +vn -0.0010 0.1885 0.9821 +vn -0.0416 0.1497 0.9879 +vn -0.0478 0.1437 0.9885 +vn -0.0833 0.1091 0.9905 +vn 0.1037 -0.6645 0.7401 +vn -0.0178 -0.7339 0.6790 +vn 0.0509 -0.9875 -0.1492 +vn 0.0921 -0.9788 -0.1830 +vn 0.0469 -0.9882 -0.1459 +vn 0.0106 -0.9932 -0.1159 +vn -0.0432 -0.9829 -0.1788 +vn 0.8448 -0.5283 0.0852 +vn -0.4232 -0.7018 -0.5731 +vn 0.3511 -0.0179 -0.9362 +vn 0.3003 0.0027 -0.9538 +vn 0.0865 0.0854 -0.9926 +vn 0.0033 0.1159 -0.9933 +vn 0.0250 -0.9879 -0.1532 +vn 0.7713 -0.6330 0.0671 +vn -0.3488 -0.7144 -0.6066 +vn 0.4684 -0.0693 -0.8808 +vn -0.0031 0.1155 -0.9933 +vn 0.0280 -0.9860 -0.1645 +vn 0.7987 -0.5984 0.0635 +vn -0.4050 -0.6970 -0.5918 +vn 0.3506 -0.0179 -0.9363 +vn 0.2999 0.0026 -0.9540 +vn 0.0863 0.0852 -0.9926 +vn 0.0034 0.1155 -0.9933 +vn 0.0084 -0.9838 -0.1790 +vn 0.8096 -0.5818 0.0782 +vn 0.0172 -0.9913 0.1301 +vn 0.0188 -0.9911 0.1315 +vn 0.0191 -0.9911 0.1317 +vn 0.0208 -0.9909 0.1331 +vn -0.1871 -0.7398 -0.6463 +vn -0.1455 -0.7417 -0.6548 +vn 0.0859 0.0457 -0.9952 +vn 0.0511 0.0738 -0.9960 +vn 0.0363 0.0855 -0.9957 +vn -0.0014 0.1155 -0.9933 +vn 0.2356 -0.5974 -0.7666 +vn -0.1017 -0.1841 -0.9776 +vn 0.6163 0.0273 -0.7871 +vn -0.3022 0.3013 -0.9043 +vn 0.4456 -0.5050 -0.7392 +vn -0.3438 -0.1581 -0.9257 +vn 0.6160 0.1476 -0.7738 +vn 0.6095 0.1453 -0.7793 +vn 0.0238 -0.3725 -0.9277 +vn 0.0736 -0.5985 -0.7977 +vn 0.7903 0.0581 -0.6100 +vn 0.0039 -0.5895 -0.8077 +vn 0.0165 -0.5940 -0.8043 +vn 0.0750 -0.3522 -0.9329 +vn 0.1122 0.1752 -0.9781 +vn -0.0102 0.2265 -0.9740 +vn -0.0192 -0.0332 0.9993 +vn -0.0109 -0.0252 0.9996 +vn 0.0201 -0.9991 0.0371 +vn 0.0108 -0.9995 0.0283 +vn -0.0105 -0.6298 -0.7767 +vn 0.0180 -0.6481 -0.7614 +vn 0.0064 -0.9983 -0.0583 +vn -0.0061 -0.9974 -0.0717 +vn -0.0039 -0.5302 -0.8479 +vn -0.0061 -0.5348 -0.8449 +vn 0.9525 0.2765 0.1273 +vn 0.7173 0.6705 0.1894 +vn 0.7567 0.5292 0.3839 +vn 0.9184 0.3836 0.0967 +vn 0.9054 0.4188 0.0699 +vn 0.9484 0.3157 0.0299 +vn 0.9015 0.4325 -0.0156 +vn 0.7125 0.7004 -0.0421 +vn 0.8849 0.4657 0.0040 +vn 0.9346 0.3400 -0.1042 +vn 0.9399 0.3413 -0.0128 +vn 0.7158 0.6575 -0.2351 +vn 0.7058 0.5130 -0.4886 +vn 0.7163 0.3887 -0.5795 +vn 0.8852 0.2100 -0.4152 +vn 0.8953 0.0916 -0.4360 +vn 0.8029 0.0861 -0.5899 +vn 0.5785 0.3001 -0.7585 +vn 0.7693 0.1144 -0.6286 +vn 0.7862 0.1150 -0.6072 +vn 0.8394 -0.0970 -0.5348 +vn 0.7127 -0.1633 -0.6822 +vn 0.7792 -0.0976 -0.6192 +vn 0.7484 -0.1473 -0.6467 +vn 0.5729 -0.3717 -0.7305 +vn 0.9414 -0.2512 -0.2251 +vn 0.7584 -0.4518 -0.4698 +vn 0.9176 -0.2549 -0.3052 +vn 0.9353 -0.3539 -0.0069 +vn 0.9011 -0.4337 -0.0042 +vn 0.7017 -0.7100 -0.0597 +vn 0.7186 -0.6616 0.2143 +vn 0.8807 -0.4660 0.0844 +vn 0.9357 -0.3409 0.0910 +vn 0.7099 -0.4197 0.5656 +vn 0.7518 -0.5086 0.4197 +vn 0.9474 -0.0967 0.3052 +vn 0.7293 -0.1704 0.6627 +vn 0.7692 0.0238 0.6385 +vn 0.9450 0.1233 0.3030 +vn 0.7149 0.2185 0.6642 +vn 0.8523 0.0196 -0.5227 +vn 0.6440 -0.5039 -0.5756 +vn 0.7598 0.4533 0.4661 +vn 0.8927 -0.1144 -0.4359 +vn 0.7985 -0.4223 -0.4291 +vn 0.9068 0.2196 -0.3599 +vn 0.9356 0.1606 -0.3145 +vn 0.9389 -0.1272 -0.3199 +vn 0.9377 0.2587 -0.2317 +vn 0.9599 -0.0042 -0.2803 +vn 0.8975 0.2800 0.3407 +vn 0.9783 0.0724 0.1939 +vn 0.9753 -0.1317 0.1774 +vn 0.8869 -0.3453 0.3070 +vn 0.9747 0.1270 -0.1838 +vn 0.9793 -0.1656 -0.1165 +vn 0.7615 -0.5922 -0.2634 +vn 0.9931 -0.0354 -0.1120 +vn 0.9436 -0.3166 -0.0970 +vn 0.9689 0.2344 -0.0789 +vn 0.9847 0.1560 0.0773 +vn 0.9961 0.0834 -0.0285 +vn 0.9968 -0.0558 0.0568 +vn 0.9643 -0.2500 0.0873 +vn 0.7900 -0.4755 0.3871 +vn 0.2509 0.7385 -0.6259 +vn 0.2925 0.8717 -0.3932 +vn -0.0239 0.8832 -0.4684 +vn -0.0245 0.8831 -0.4686 +vn -0.0079 0.9918 -0.1276 +vn 0.2513 0.8657 -0.4330 +vn 0.3118 0.9373 -0.1559 +vn 0.3410 0.9365 0.0824 +vn 0.2381 0.9232 0.3017 +vn 0.2949 0.8008 0.5213 +vn 0.3211 0.5795 0.7490 +vn 0.2870 0.4128 0.8644 +vn 0.3083 0.1781 0.9345 +vn 0.3008 -0.0443 0.9527 +vn 0.3086 -0.3232 0.8946 +vn 0.2186 -0.5749 0.7885 +vn 0.0122 0.0099 -0.9999 +vn -0.0241 0.0340 -0.9991 +vn 0.0371 0.2706 -0.9620 +vn 0.3935 0.5140 -0.7623 +vn 0.0048 -0.6075 -0.7943 +vn -0.0360 -0.6908 -0.7222 +vn 0.0299 -0.5518 -0.8334 +vn -0.0694 -0.7526 -0.6549 +vn 0.0682 -0.7152 0.6956 +vn 0.0609 -0.7069 0.7047 +vn 0.0656 -0.7122 0.6989 +vn 0.0759 -0.7239 0.6857 +vn 0.0778 0.8893 0.4507 +vn -0.0026 0.8046 0.5937 +vn 0.0314 0.8438 0.5357 +vn -0.0700 0.7126 0.6980 +vn -0.0074 0.5990 -0.8007 +vn -0.0440 0.6815 -0.7305 +vn -0.0202 0.6287 -0.7774 +vn -0.0577 0.7103 -0.7015 +vn -0.0356 -0.9077 0.4182 +vn 0.0467 -0.5151 0.8558 +vn -0.0287 0.1213 0.9922 +vn 0.0242 0.9166 0.3992 +vn 0.0268 0.9219 0.3864 +vn 0.0246 0.9175 0.3970 +vn 0.0271 0.9225 0.3851 +vn -0.0331 0.6836 -0.7291 +vn 0.0303 0.3150 -0.9486 +vn -0.0256 0.6453 -0.7635 +vn 0.0381 0.2632 -0.9640 +vn -0.0321 -0.5710 -0.8203 +vn 0.0250 -0.8575 -0.5139 +vn -0.0257 -0.6099 -0.7921 +vn 0.0329 -0.8862 -0.4622 +vn -0.0074 0.7083 0.7059 +vn -0.0031 0.8726 0.4884 +vn 0.2098 0.4874 0.8476 +vn -0.0036 0.9874 0.1580 +vn 0.0041 0.9778 0.2094 +vn -0.0047 0.9941 0.1087 +vn 0.0098 0.7681 -0.6402 +vn -0.0027 0.8247 -0.5656 +vn -0.0042 0.8312 -0.5559 +vn 0.0110 0.7620 -0.6474 +vn 0.3574 0.5180 0.7772 +vn 0.2745 0.8424 0.4636 +vn 0.3364 0.9406 -0.0461 +vn 0.2389 0.4238 -0.8737 +vn -0.0140 0.3446 -0.9387 +vn 0.0010 0.2402 -0.9707 +vn 0.6123 0.7098 0.3482 +vn -0.5291 0.6494 0.5462 +vn 0.6121 0.6795 0.4046 +vn 0.5164 0.8530 0.0754 +vn 0.6599 0.5031 -0.5580 +vn 0.6644 0.4558 -0.5924 +vn 0.6028 0.6833 -0.4119 +vn 0.5954 0.7435 -0.3046 +vn 0.6241 0.7580 -0.1895 +vn 0.5305 0.7752 -0.3429 +vn 0.3847 0.0086 -0.9230 +vn -0.0013 -0.9343 -0.3566 +vn 0.0151 -0.8193 -0.5732 +vn 0.0132 -0.7856 -0.6186 +vn 0.1880 -0.7034 -0.6855 +vn 0.3364 -0.8572 -0.3899 +vn 0.0010 -0.7841 0.6206 +vn 0.2861 -0.8739 0.3931 +vn 0.3651 -0.9235 0.1175 +vn 0.2579 -0.9544 -0.1503 +vn 0.2503 -0.4305 -0.8672 +vn -0.0292 0.9691 -0.2448 +vn 0.0240 0.9976 0.0655 +vn -0.0374 0.9557 -0.2920 +vn -0.0260 -0.1436 -0.9893 +vn 0.0317 0.2076 -0.9777 +vn 0.0231 0.1554 -0.9876 +vn -0.0328 -0.1848 -0.9822 +vn 0.0292 -0.8787 -0.4765 +vn -0.0275 -0.9757 0.2175 +vn 0.0066 -0.8857 0.4642 +vn -0.0240 -0.9694 0.2443 +vn 0.0113 -0.8681 0.4962 +vn -0.0160 0.2232 0.9746 +vn -0.0239 0.1904 0.9814 +vn -0.0169 0.2195 0.9755 +vn -0.0253 0.1843 0.9825 +vn 0.0335 0.9921 0.1212 +vn -0.0099 -0.6988 0.7152 +vn 0.2178 -0.5348 0.8164 +vn 0.0001 -0.8700 0.4930 +vn -0.0088 -0.3663 -0.9305 +vn 0.3470 -0.7531 -0.5589 +vn 0.1834 -0.5095 -0.8407 +vn 0.0029 -0.9654 -0.2607 +vn 0.2492 -0.9476 -0.2001 +vn 0.0026 -0.9649 -0.2625 +vn 0.3037 -0.5230 0.7964 +vn 0.2512 -0.8303 0.4975 +vn 0.2163 -0.9755 0.0403 +vn -0.0146 -0.9704 0.2409 +vn -0.0017 -0.9531 0.3027 +vn 0.2746 -0.4831 -0.8314 +vn 0.0126 -0.5651 -0.8249 +vn 0.4191 -0.7763 0.4709 +vn 0.6269 -0.5560 0.5458 +vn 0.6312 -0.6503 0.4227 +vn 0.5166 -0.8493 0.1084 +vn 0.5945 -0.7615 -0.2584 +vn 0.6642 -0.5772 -0.4750 +vn 0.3957 -0.4960 -0.7729 +vn 0.5815 -0.6208 -0.5258 +vn -0.0931 -0.9957 -0.0021 +vn 0.4595 -0.8641 -0.2056 +vn 0.6811 -0.6967 -0.2250 +vn 0.8721 -0.3998 -0.2821 +vn -0.7432 -0.5908 -0.3139 +vn 0.8640 0.4905 -0.1137 +vn 0.9121 0.3507 -0.2123 +vn 0.8113 0.5817 -0.0586 +vn 0.9783 0.1156 -0.1717 +vn 0.9973 0.0448 -0.0590 +vn 0.9303 0.0032 0.3668 +vn 0.8455 -0.0885 0.5266 +vn 0.9655 0.0641 0.2523 +vn 0.9491 -0.2292 0.2161 +vn 0.9646 -0.2624 0.0280 +vn 0.9206 -0.3676 0.1318 +vn 0.7861 -0.1360 0.6030 +vn 0.9822 0.1042 -0.1565 +vn 0.9649 0.1472 -0.2174 +vn 0.6096 0.7639 0.2119 +vn 0.5842 0.7842 0.2092 +vn 0.7523 0.6197 0.2234 +vn 0.9744 -0.2137 -0.0695 +vn 0.9672 -0.2456 -0.0655 +vn 0.9663 -0.2467 -0.0734 +vn 0.9995 -0.0289 -0.0103 +vn -0.6980 -0.1525 0.6996 +vn -0.9622 -0.2692 0.0412 +vn -0.9393 -0.3279 0.1007 +vn -0.9593 -0.2779 0.0499 +vn -0.9793 0.1835 -0.0852 +vn -0.9906 0.0848 -0.1076 +vn -0.9636 0.2662 0.0235 +vn -0.9583 0.2458 0.1456 +vn -0.9761 -0.2172 -0.0103 +vn -0.9723 0.1311 0.1933 +vn -0.8027 -0.3299 0.4969 +vn -0.9994 0.0159 -0.0292 +vn -0.9967 0.0255 -0.0765 +vn -0.9977 0.0053 -0.0675 +vn -0.9960 -0.0883 -0.0095 +vn -0.9988 -0.0459 0.0161 +vn -0.9991 -0.0371 0.0182 +vn -0.4245 0.5802 -0.6951 +vn -0.6365 -0.4581 -0.6205 +vn 0.7681 -0.5171 -0.3778 +vn -0.7512 -0.6600 0.0133 +vn 0.7510 -0.5465 0.3705 +vn -0.7062 -0.2640 0.6570 +vn 0.6603 0.0150 0.7509 +vn -0.7145 0.4514 0.5346 +vn 0.7665 0.6018 0.2242 +vn -0.4776 0.7784 -0.4074 +vn 0.4211 0.3145 -0.8507 +vn 0.4266 -0.6501 0.6288 +vn -0.3023 -0.9464 0.1139 +vn 0.1247 -0.8245 -0.5519 +vn -0.1664 -0.0675 -0.9837 +vn -0.1449 -0.0652 -0.9873 +vn -0.3995 -0.0902 -0.9123 +vn -0.4529 -0.0949 -0.8865 +vn 0.5965 0.5092 -0.6205 +vn -0.6961 0.6043 -0.3875 +vn 0.5836 0.8097 -0.0616 +vn -0.7038 0.6523 0.2816 +vn 0.2275 0.7670 0.6000 +vn -0.1157 0.7430 -0.6592 +vn 0.7166 0.6372 0.2835 +vn 0.0882 0.2742 0.9576 +vn -0.6711 0.0049 0.7414 +vn 0.6142 -0.7785 -0.1288 +vn -0.8659 -0.4258 0.2627 +vn -0.2521 -0.2383 -0.9379 +vn 0.2777 -0.5393 -0.7950 +vn -0.2735 -0.7646 0.5836 +vn 0.3017 -0.4115 0.8601 +vn -0.3284 0.8508 0.4102 +vn 0.2627 0.9638 0.0455 +vn 0.4161 0.8614 -0.2913 +vn -0.5313 -0.1948 -0.8245 +vn 0.3888 -0.6972 -0.6023 +vn -0.0396 -0.7295 0.6828 +vn 0.4643 -0.2450 0.8511 +vn -0.5644 0.6967 0.4428 +vn 0.9987 0.0426 0.0265 +vn 0.9991 -0.0066 0.0414 +vn 0.9989 -0.0285 0.0378 +vn 0.9976 -0.0463 0.0515 +vn 0.9965 -0.0372 -0.0755 +vn 0.9971 0.0677 0.0342 +vn 0.9984 0.0527 -0.0205 +vn 0.9980 0.0609 -0.0140 +vn -0.9928 0.0124 0.1192 +vn -0.9992 0.0373 -0.0122 +vn -0.9917 0.0107 0.1278 +vn -0.0224 0.4501 0.8927 +vn 0.0473 0.2083 0.9769 +vn 0.0330 0.2601 0.9650 +vn -0.0385 0.5021 0.8639 +vn -0.0042 0.9496 -0.3134 +vn -0.0112 0.9418 -0.3360 +vn -0.0345 0.9116 -0.4096 +vn -0.0420 0.9004 -0.4330 +vn -0.0703 -0.6068 -0.7917 +vn 0.0043 -0.3328 -0.9430 +vn -0.0122 -0.3965 -0.9179 +vn -0.0844 -0.6545 -0.7514 +vn -0.0428 -0.8683 0.4941 +vn 0.0219 -0.9884 0.1501 +vn 0.0103 -0.9767 0.2143 +vn -0.0577 -0.8209 0.5682 +vn -0.9914 -0.1145 -0.0637 +vn -0.9903 -0.1123 -0.0817 +vn -0.9896 -0.1306 0.0595 +vn -0.9849 -0.0925 0.1464 +vn -0.9928 0.1190 -0.0165 +vn -0.9894 0.0011 -0.1455 +vn -0.9842 0.0895 -0.1528 +vn -0.9798 0.1604 0.1196 +vn -0.9913 0.0252 0.1291 +vn -0.0727 -0.4422 0.8939 +vn -0.0401 -0.4717 0.8809 +vn -0.0728 -0.4421 0.8940 +vn -0.0985 -0.4181 0.9030 +vn 0.0900 0.5062 0.8577 +vn -0.0838 0.6750 0.7331 +vn -0.0655 0.6593 0.7490 +vn -0.2101 0.7688 0.6040 +vn 0.1497 0.9859 0.0751 +vn -0.0673 0.6891 -0.7215 +vn -0.0910 0.6717 -0.7352 +vn -0.0899 0.6725 -0.7346 +vn -0.1075 0.6591 -0.7443 +vn 0.0940 -0.1211 -0.9882 +vn 0.0084 -0.2661 -0.9639 +vn -0.0174 -0.3081 -0.9512 +vn -0.0962 -0.4322 -0.8966 +vn 0.0997 -0.8132 -0.5734 +vn -0.1044 -0.9902 -0.0924 +vn -0.0014 -0.9981 0.0623 +vn -0.0179 -0.9991 0.0377 +vn 0.1017 -0.9714 0.2147 +vn 0.6958 -0.7143 0.0753 +vn 0.2633 -0.7678 0.5841 +vn 0.1858 0.4977 0.8472 +vn -0.2475 0.3098 -0.9180 +vn 0.6690 0.5916 -0.4500 +vn -0.9593 -0.0194 0.2817 +vn 0.9995 0.0050 0.0308 +vn 0.9994 0.0233 0.0240 +vn 0.9993 -0.0130 0.0362 +vn 0.9996 -0.0232 -0.0141 +vn 0.9997 -0.0259 0.0030 +vn 0.9994 -0.0093 -0.0326 +vn 0.9997 0.0164 -0.0168 +vn 0.9997 0.0223 -0.0135 +vn -0.9991 -0.0097 -0.0404 +vn -0.9948 -0.0653 -0.0779 +vn -0.9991 -0.0095 -0.0403 +vn -0.9992 0.0395 -0.0072 +vn 0.0077 -0.5952 0.8036 +vn 0.0092 -0.9198 -0.3922 +vn -0.0245 -0.9990 0.0386 +vn -0.0223 -0.9997 0.0095 +vn 0.0115 -0.9078 -0.4192 +vn 0.0046 0.3524 -0.9358 +vn -0.0211 -0.0958 -0.9952 +vn -0.0196 -0.0683 -0.9975 +vn 0.0059 0.3737 -0.9276 +vn 0.0007 0.9978 -0.0665 +vn -0.0205 0.9185 -0.3949 +vn -0.0195 0.9251 -0.3792 +vn 0.0019 0.9989 -0.0468 +vn -0.0323 0.4173 0.9082 +vn -0.0133 0.2494 0.9683 +vn -0.0144 0.2588 0.9658 +vn -0.0337 0.4295 0.9024 +vn -0.9949 -0.0946 0.0342 +vn -0.9952 -0.0982 0.0016 +vn -0.9964 -0.0293 0.0796 +vn -0.9957 0.0096 0.0924 +vn -0.9950 0.0735 0.0670 +vn -0.9948 0.0926 0.0424 +vn -0.9967 0.0678 -0.0452 +vn -0.9977 0.0581 -0.0347 +vn -0.9934 -0.0164 -0.1137 +vn -0.9947 -0.0546 -0.0868 +vn 0.0593 -0.7664 0.6396 +vn 0.0151 -0.7939 0.6078 +vn 0.0130 -0.7952 0.6062 +vn -0.0334 -0.8208 0.5703 +vn 0.0270 -0.8514 -0.5238 +vn -0.0655 -0.8946 -0.4421 +vn 0.0348 -0.8471 -0.5302 +vn 0.1185 -0.7941 -0.5962 +vn -0.0462 0.2603 -0.9644 +vn -0.0921 0.2198 -0.9712 +vn -0.0325 0.2722 -0.9617 +vn 0.0175 0.3147 -0.9490 +vn 0.0129 0.9930 0.1172 +vn -0.0197 0.9959 0.0883 +vn 0.0207 0.9921 0.1241 +vn 0.0521 0.9871 0.1515 +vn -0.0328 0.2307 0.9725 +vn -0.0695 0.2663 0.9614 +vn -0.0329 0.2308 0.9725 +vn 0.0076 0.1909 0.9816 +vn -0.1238 0.1877 0.9744 +vn 0.0017 0.0561 0.9984 +vn -0.0016 0.0595 0.9982 +vn 0.1239 -0.0740 0.9895 +vn -0.1239 0.7500 -0.6497 +vn 0.0016 0.8366 -0.5478 +vn -0.0017 0.8347 -0.5506 +vn 0.1238 0.8940 -0.4307 +vn 0.8887 0.4119 -0.2012 +vn 0.8104 0.5842 0.0445 +vn 0.9031 0.3452 -0.2555 +vn 0.9986 0.0179 0.0490 +vn 0.9613 0.1942 0.1953 +vn 0.9969 0.0606 0.0505 +vn 0.9467 0.2352 0.2202 +vn 0.9913 0.0571 0.1182 +vn 0.9737 -0.1976 -0.1135 +vn 0.9919 -0.1103 -0.0633 +vn 0.9944 -0.0914 -0.0525 +vn 0.4440 -0.6536 0.6129 +vn 0.4288 -0.6601 0.6167 +vn 0.2249 -0.7266 0.6492 +vn 0.9922 -0.0790 -0.0962 +vn 0.9993 -0.0347 -0.0152 +vn 0.9807 -0.1766 -0.0844 +vn 0.9812 -0.1708 -0.0899 +vn 0.9977 -0.0678 -0.0004 +vn 0.9997 0.0067 -0.0240 +vn 0.9983 -0.0542 0.0219 +vn 0.9876 0.1458 -0.0579 +vn 0.9993 0.0340 -0.0145 +vn 0.9870 0.1469 -0.0656 +vn -0.9898 -0.0127 -0.1418 +vn -0.9971 0.0718 -0.0232 +vn -0.9988 -0.0327 -0.0353 +vn -0.9018 -0.3005 0.3107 +vn -0.9886 -0.1327 0.0708 +vn -0.9799 0.1507 -0.1311 +vn -0.9864 0.1124 -0.1202 +vn -0.9828 0.1587 -0.0943 +vn -0.9721 -0.2285 0.0526 +vn -0.8870 -0.4074 0.2174 +vn -0.8281 -0.3505 0.4374 +vn -0.9104 0.3746 0.1756 +vn -0.9122 0.3672 0.1815 +vn -0.9305 0.2358 0.2804 +vn -0.9993 -0.0161 -0.0324 +vn -0.9996 -0.0125 -0.0252 +vn -0.9884 -0.1426 -0.0519 +vn -0.9891 -0.1309 -0.0669 +vn -0.9997 -0.0206 -0.0133 +vn -0.9998 0.0208 0.0047 +vn -0.9988 0.0283 0.0407 +vn -0.9899 0.1208 -0.0736 +vn -0.9997 0.0254 -0.0063 +vn -0.9813 0.1826 -0.0613 +vn 0.4009 -0.2299 -0.8868 +vn -0.6717 -0.4813 -0.5631 +vn 0.6603 -0.6657 -0.3477 +vn -0.7796 -0.6008 0.1766 +vn 0.7949 -0.4605 0.3951 +vn -0.6995 -0.0301 0.7140 +vn 0.5989 0.2340 0.7659 +vn -0.6340 0.6401 0.4339 +vn 0.7362 0.6597 0.1508 +vn -0.7782 0.5149 -0.3595 +vn 0.8625 0.2596 -0.4345 +vn 0.7697 0.6337 0.0772 +vn 0.7551 0.0606 0.6528 +vn -0.1612 -0.2717 0.9488 +vn 0.0670 -0.9624 0.2634 +vn 0.1974 -0.7328 0.6512 +vn -0.3740 -0.9255 -0.0605 +vn -0.4641 -0.5886 -0.6620 +vn 0.4418 -0.0633 -0.8949 +vn -0.3145 0.0664 -0.9469 +vn 0.1274 0.7095 -0.6931 +vn -0.5596 0.8273 -0.0486 +vn 0.6362 0.6588 0.4016 +vn -0.2383 0.7032 0.6699 +vn -0.8718 0.4829 0.0829 +vn -0.4067 0.1411 0.9026 +vn 0.7830 -0.5831 -0.2165 +vn -0.8682 -0.4377 0.2336 +vn -0.5522 0.5288 -0.6446 +vn 0.5621 -0.4166 -0.7145 +vn -0.4729 -0.8743 0.1097 +vn 0.4573 -0.4377 0.7742 +vn -0.1862 0.4742 0.8605 +vn 0.4574 0.8833 0.1025 +vn 0.3901 0.8608 -0.3269 +vn -0.5460 0.2766 -0.7908 +vn 0.1436 -0.6370 -0.7574 +vn -0.5332 -0.8460 -0.0032 +vn 0.5416 -0.2508 0.8024 +vn -0.5149 0.4753 0.7134 +vn -0.0293 0.0345 -0.9990 +vn -0.0191 0.0439 -0.9989 +vn -0.0064 0.0413 -0.9991 +vn 0.0116 -0.0438 -0.9990 +vn 0.0296 -0.0461 -0.9985 +vn 0.0290 -0.0487 -0.9984 +vn -0.0011 -0.0419 -0.9991 +vn -0.0154 -0.0252 -0.9996 +vn -0.0160 -0.0216 -0.9996 +vn 0.0110 0.0394 -0.9992 +vn 0.0171 0.0290 -0.9994 +vn 0.0172 0.0273 -0.9995 +vn -0.0104 -0.0499 0.9987 +vn 0.0254 -0.0024 0.9997 +vn -0.0369 -0.0559 0.9978 +vn 0.0058 0.0093 0.9999 +vn -0.0749 0.0989 0.9923 +vn 0.5730 -0.8189 -0.0334 +vn -0.0966 -0.9943 0.0456 +vn -0.8390 -0.5427 -0.0404 +vn -0.9349 -0.3549 -0.0046 +vn -0.8489 -0.5272 -0.0373 +vn -0.9463 -0.3234 0.0012 +vn -0.9234 0.3820 0.0369 +vn -0.4821 0.8755 -0.0322 +vn -0.2589 0.9659 0.0056 +vn -0.4628 0.8860 -0.0288 +vn -0.2190 0.9756 0.0121 +vn 0.8725 0.4881 -0.0244 +vn 0.5738 0.8183 0.0337 +vn 0.6249 0.7803 0.0256 +vn 0.8920 0.4511 -0.0297 +vn 0.9578 -0.2835 0.0476 +vn 0.0691 -0.0162 0.9975 +vn 0.0518 -0.0505 0.9974 +vn 0.0729 0.0090 0.9973 +vn -0.0097 -0.0741 0.9972 +vn -0.0176 -0.0867 0.9961 +vn 0.0287 0.0887 0.9956 +vn -0.0263 0.0672 0.9974 +vn -0.0712 0.0205 0.9973 +vn -0.0875 0.0228 0.9959 +vn 0.0591 0.0568 0.9966 +vn -0.0632 -0.0360 0.9974 +vn 0.9805 0.1863 -0.0633 +vn 0.9604 0.2780 -0.0185 +vn 0.9359 0.3519 0.0190 +vn 0.8988 0.4340 0.0620 +vn 0.5288 0.8469 -0.0566 +vn 0.2014 0.9791 -0.0265 +vn 0.3282 0.9437 0.0416 +vn 0.0858 0.9957 0.0347 +vn -0.1630 0.9837 -0.0763 +vn -0.7471 0.6612 0.0683 +vn -0.8128 0.5825 0.0005 +vn -0.7968 0.6039 0.0182 +vn -0.8557 0.5148 -0.0526 +vn -0.9876 -0.1531 0.0361 +vn -0.9576 -0.2864 -0.0307 +vn -0.9730 -0.2308 -0.0026 +vn -0.9331 -0.3535 -0.0654 +vn -0.6256 -0.7773 0.0662 +vn -0.4857 -0.8739 -0.0198 +vn -0.5443 -0.8387 0.0149 +vn -0.3877 -0.9188 -0.0740 +vn 0.3278 -0.9425 0.0652 +vn 0.3889 -0.9211 0.0210 +vn 0.3708 -0.9281 0.0342 +vn 0.4362 -0.8997 -0.0147 +vn 0.9417 -0.3361 0.0149 +vn 0.9326 -0.3609 0.0014 +vn 0.9375 -0.3480 0.0084 +vn 0.9452 -0.3259 0.0203 +vn 0.5103 -0.8513 -0.1218 +vn 0.3592 -0.9138 -0.1896 +vn 0.3021 -0.9293 -0.2125 +vn 0.4444 0.8894 0.1072 +vn 0.7116 0.5767 -0.4013 +vn -0.4059 0.7154 -0.5687 +vn -0.9266 0.3550 -0.1237 +vn -0.4773 -0.8572 0.1934 +vn 0.1512 -0.9517 -0.2671 +vn -0.1143 -0.2373 0.9647 +vn -0.0442 -0.9990 0.0062 +vn -0.0419 -0.9987 0.0275 +vn -0.0484 -0.9986 0.0205 +vn 0.0361 -0.9993 -0.0104 +vn 0.0403 -0.9992 0.0060 +vn 0.0213 -0.9996 0.0170 +vn -0.0351 -0.9993 -0.0113 +vn -0.0114 -0.9993 -0.0350 +vn -0.0183 -0.9993 -0.0326 +vn 0.0238 -0.9992 -0.0311 +vn 0.0171 -0.9997 0.0175 +vn 0.0189 0.9997 -0.0140 +vn -0.0158 0.9995 -0.0269 +vn 0.0080 0.9994 -0.0328 +vn 0.0079 0.9999 -0.0101 +vn 0.0779 0.9968 0.0187 +vn -0.9612 0.0576 -0.2697 +vn -0.4588 -0.0296 -0.8881 +vn 0.5208 0.0005 -0.8537 +vn 0.1733 0.0349 -0.9842 +vn 0.2105 0.0316 -0.9771 +vn 0.5587 -0.0038 -0.8294 +vn 0.9977 -0.0119 0.0660 +vn 0.9630 0.0322 -0.2676 +vn 0.9735 0.0268 -0.2271 +vn 0.9943 -0.0170 0.1050 +vn 0.2088 -0.0108 0.9779 +vn 0.5306 0.0360 0.8469 +vn 0.4890 0.0296 0.8718 +vn 0.1670 -0.0165 0.9858 +vn -0.5574 0.0337 0.8296 +vn -0.9286 -0.0262 0.3702 +vn -0.0771 0.9965 -0.0317 +vn -0.0974 0.9947 -0.0340 +vn -0.0610 0.9975 0.0354 +vn -0.0332 0.9973 0.0650 +vn -0.0229 0.9974 -0.0686 +vn 0.0601 0.9967 0.0544 +vn 0.0385 0.9968 0.0695 +vn 0.0667 0.9978 -0.0013 +vn 0.0648 0.9971 -0.0402 +vn -0.0085 0.9973 0.0734 +vn 0.0094 0.9974 -0.0721 +vn 0.0392 0.9971 -0.0653 +vn -0.5720 0.0074 0.8202 +vn -0.6030 -0.0191 0.7975 +vn -0.5828 -0.0017 0.8126 +vn -0.5522 0.0238 0.8334 +vn 0.1956 -0.0143 0.9806 +vn 0.2235 -0.0332 0.9741 +vn 0.2136 -0.0265 0.9766 +vn 0.2388 -0.0436 0.9701 +vn 0.8577 0.0540 0.5113 +vn 0.8779 0.0248 0.4782 +vn 0.8717 0.0342 0.4889 +vn 0.8930 0.0008 0.4501 +vn 0.9305 -0.0699 -0.3596 +vn 0.8971 -0.0023 -0.4418 +vn 0.8869 0.0147 -0.4617 +vn 0.8412 0.0802 -0.5347 +vn 0.1160 -0.0315 -0.9927 +vn 0.1148 -0.0325 -0.9929 +vn 0.1151 -0.0323 -0.9928 +vn 0.1140 -0.0332 -0.9929 +vn -0.7189 0.0236 -0.6947 +vn -0.7520 -0.0096 -0.6591 +vn -0.7424 0.0003 -0.6700 +vn -0.7729 -0.0320 -0.6337 +vn -0.9968 0.0451 0.0659 +vn -0.9921 0.0066 0.1251 +vn -0.9946 0.0217 0.1019 +vn -0.9862 -0.0193 0.1646 +vn -0.4443 -0.1642 0.8807 +vn -0.4256 -0.1439 0.8934 +vn -0.4227 -0.1408 0.8953 +vn -0.4070 -0.1238 0.9050 +vn 0.8678 0.1496 0.4738 +vn 0.9507 -0.2270 -0.2113 +vn 0.9427 -0.2081 -0.2608 +vn 0.9587 -0.2672 -0.0973 +vn 0.9102 -0.1576 -0.3831 +vn -0.8320 0.1135 -0.5431 +vn -0.5477 -0.3509 -0.7596 +vn -0.8307 0.4181 -0.3676 +vn -0.8248 0.4426 -0.3518 +vn -0.8346 0.3998 -0.3790 +vn -0.8648 -0.0777 0.4961 +vn -0.6474 -0.6385 -0.4161 +vn -0.0294 -0.9173 0.3970 +vn 0.4834 -0.8111 -0.3293 +vn 0.8302 -0.4895 0.2667 +vn 0.8926 0.1974 -0.4052 +vn 0.6817 0.5913 0.4309 +vn 0.7093 0.5101 0.4866 +vn 0.7206 0.4658 0.5135 +vn 0.9459 -0.3064 -0.1070 +vn 0.7386 0.3628 0.5681 +vn -0.7116 -0.7022 0.0211 +vn -0.7224 -0.6853 0.0923 +vn -0.7286 -0.5960 0.3375 +vn -0.7245 -0.5759 0.3788 +vn -0.8394 0.3209 -0.4387 +vn -0.5237 0.5839 0.6203 +vn -0.0258 0.8103 -0.5855 +vn 0.5282 0.6527 0.5432 +vn 0.8041 0.1776 -0.5674 +vn 0.9442 -0.1467 0.2948 +vn 0.4835 -0.8744 -0.0404 +vn -0.8189 0.4642 -0.3375 +vn -0.0666 -0.3161 -0.9464 +vn -0.0347 -0.1645 -0.9858 +vn -0.0267 -0.1266 -0.9916 +vn -0.0029 -0.1878 0.9822 +vn -0.0046 -0.2943 0.9557 +vn -0.0011 -0.0707 0.9975 +vn -0.1334 -0.9911 0.0020 +vn 0.9213 -0.3883 -0.0180 +vn 0.9148 -0.4003 -0.0543 +vn 0.9317 -0.3559 0.0724 +vn 0.9333 -0.3431 0.1058 +vn 0.6161 0.7843 -0.0721 +vn 0.6241 0.7742 -0.1055 +vn 0.5905 0.8068 0.0184 +vn 0.5787 0.8137 0.0547 +vn -0.7034 0.7107 -0.0081 +vn -0.7186 0.6909 -0.0789 +vn -0.7390 0.6210 -0.2612 +vn -0.7396 0.5967 -0.3113 +vn -0.8883 -0.3910 0.2409 +vn -0.6365 0.1856 0.7486 +vn 0.8785 0.4446 -0.1750 +vn 0.9218 -0.3710 0.1126 +vn 0.9229 -0.3463 0.1684 +vn 0.8992 -0.4346 -0.0509 +vn 0.8834 -0.4550 -0.1119 +vn 0.2528 -0.9606 0.1153 +vn 0.2493 -0.9630 0.1025 +vn 0.2640 -0.9517 0.1568 +vn 0.2696 -0.9464 0.1779 +vn -0.5506 -0.7813 -0.2938 +vn -0.7604 -0.5262 0.3807 +vn -0.9514 -0.1985 -0.2355 +vn -0.8800 0.3737 0.2932 +vn -0.6754 0.6393 -0.3676 +vn -0.1715 0.8900 0.4224 +vn 0.1961 0.9379 -0.2863 +vn 0.7493 -0.1673 0.6408 +vn 0.1108 -0.5462 -0.8303 +vn 0.0258 0.0668 -0.9974 +vn -0.0143 0.0905 -0.9958 +vn 0.3542 0.1559 -0.9221 +vn 0.2253 0.1586 -0.9613 +vn -0.0128 0.2768 0.9608 +vn -0.0053 0.1136 0.9935 +vn -0.0063 0.1369 0.9906 +vn 0.0241 -0.0474 0.9986 +vn 0.1670 -0.3288 0.9295 +vn 0.1373 -0.2704 0.9529 +vn -0.7962 0.4597 0.3933 +vn -0.8372 0.4869 0.2490 +vn -0.7752 0.3802 0.5045 +vn -0.8730 -0.4814 -0.0785 +vn -0.8750 0.1732 -0.4521 +vn 0.1009 -0.0339 -0.9943 +vn 0.1193 -0.0938 -0.9884 +vn 0.0570 0.1039 -0.9930 +vn 0.0358 0.1686 -0.9850 +vn 0.9181 -0.2634 -0.2963 +vn 0.8469 0.5099 0.1511 +vn 0.7280 -0.2946 0.6191 +vn 0.7047 -0.2712 0.6556 +vn 0.6942 -0.2609 0.6708 +vn 0.6429 0.7285 -0.2363 +vn 0.6669 -0.2351 0.7070 +vn -0.2422 -0.2430 -0.9393 +vn -0.6908 0.3366 -0.6399 +vn -0.8646 -0.1772 -0.4701 +vn -0.9684 0.1768 0.1757 +vn -0.9716 0.0830 0.2214 +vn -0.9264 -0.1757 0.3330 +vn -0.8950 -0.2579 0.3639 +vn -0.4852 0.2835 0.8272 +vn -0.1487 -0.3213 0.9352 +vn 0.2555 0.2833 0.9243 +vn 0.6575 -0.2902 0.6953 +vn 0.8957 0.2714 0.3523 +vn 0.9714 -0.2354 0.0307 +vn 0.7702 0.3633 -0.5242 +vn 0.6309 -0.2469 -0.7356 +vn -0.8479 0.5152 0.1256 +vn -0.8935 0.4475 0.0378 +vn -0.0003 0.4411 -0.8975 +vn 0.0747 0.5121 -0.8557 +vn -0.0765 0.3633 -0.9285 +vn 0.5472 -0.4951 -0.6749 +vn 0.8871 0.4212 -0.1888 +vn 0.9004 -0.3174 0.2975 +vn 0.3258 0.4533 0.8297 +vn -0.0821 -0.4768 0.8752 +vn -0.8665 0.4248 0.2622 +vn -0.9713 -0.2380 0.0047 +vn -0.1365 0.4485 0.8833 +vn -0.7813 -0.3866 0.4901 +vn 0.9865 -0.1473 0.0711 +vn 0.9700 -0.2230 0.0966 +vn 0.9850 0.1684 -0.0367 +vn 0.9682 0.2422 -0.0622 +vn 0.5595 -0.1815 -0.8087 +vn 0.5726 -0.2466 -0.7819 +vn 0.4955 0.0406 -0.8677 +vn 0.4632 0.1259 -0.8772 +vn -0.3430 0.0398 -0.9385 +vn -0.3565 -0.0020 -0.9343 +vn -0.3879 -0.1092 -0.9152 +vn -0.3969 -0.1432 -0.9066 +vn -0.9887 0.0188 -0.1487 +vn -0.9883 0.0737 -0.1334 +vn -0.9725 -0.1360 -0.1889 +vn -0.9576 -0.2026 -0.2049 +vn -0.6651 0.3151 0.6770 +vn -0.3676 -0.5206 0.7706 +vn 0.2411 0.3049 0.9214 +vn 0.1558 0.5825 -0.7978 +vn 0.7030 -0.6612 0.2619 +vn -0.0165 0.2787 -0.9602 +vn -0.0053 0.0906 -0.9959 +vn -0.0025 -0.0087 -1.0000 +vn -0.0062 0.5892 -0.8079 +vn 0.0006 0.3939 -0.9192 +vn 0.0046 -0.9722 0.2340 +vn 0.0187 -0.9288 0.3702 +vn -0.0011 -0.9561 0.2929 +vn -0.0057 -0.7950 0.6066 +vn 0.0182 0.0231 -0.9996 +vn 0.0988 0.1443 -0.9846 +vn 0.0639 0.2239 -0.9725 +vn -0.0079 0.1567 -0.9876 +vn 0.0022 0.2882 -0.9576 +vn 0.0009 0.2791 -0.9603 +vn -0.0008 0.2671 -0.9637 +vn -0.0025 0.2656 -0.9641 +vn -0.0120 0.0842 -0.9964 +vn -0.3875 0.1963 -0.9007 +vn 0.0013 0.2741 -0.9617 +vn -0.0006 0.2708 -0.9626 +vn -0.1927 0.2636 -0.9452 +vn 0.0143 0.0946 0.9954 +vn -0.0231 0.1808 0.9832 +vn -0.0301 0.1292 0.9912 +vn -0.0230 0.0543 0.9983 +vn 0.0194 0.3906 0.9204 +vn 0.0269 0.4324 0.9013 +vn -0.0050 0.5158 0.8567 +vn -0.0072 0.5167 0.8561 +vn -0.0084 -0.8605 -0.5094 +vn -0.0065 -0.8600 -0.5102 +vn 0.0085 -0.9214 -0.3884 +vn 0.0160 -0.9319 -0.3625 +vn -0.0453 -0.9990 -0.0029 +vn 0.0049 -0.9889 -0.1485 +vn 0.0581 -0.9653 0.2546 +vn -0.0381 -0.9122 0.4080 +vn -0.0308 -0.8712 0.4900 +vn 0.0024 -0.8642 0.5031 +vn -0.0212 -0.9569 0.2897 +vn -0.0539 -0.9611 0.2710 +vn -0.0040 -0.9762 0.2167 +vn -0.0012 -0.9720 0.2351 +vn 0.0006 -0.9920 0.1263 +vn -0.0009 -0.9607 0.2776 +vn -0.0171 -0.9977 0.0654 +vn -0.0017 -0.9642 0.2652 +vn -0.0073 -0.9648 0.2628 +vn 0.0014 -0.9818 0.1900 +vn -0.0012 -0.9632 0.2687 +vn 0.0000 -0.9632 0.2687 +vn -0.0023 -0.9633 0.2686 +vn -0.0002 -0.9603 0.2790 +vn -0.0056 0.5057 -0.8627 +vn 0.0400 0.4877 -0.8721 +vn 0.0784 0.4103 -0.9086 +vn -0.0425 0.2167 -0.9753 +vn 0.1046 -0.0017 -0.9945 +vn -0.0160 -0.2888 -0.9573 +vn -0.0471 -0.3266 -0.9440 +vn -0.0105 -0.2124 -0.9771 +vn -0.0207 -0.2799 -0.9598 +vn 0.0022 -0.2518 0.9678 +vn 0.0005 -0.2581 0.9661 +vn 0.0009 -0.1184 0.9930 +vn 0.0001 -0.1215 0.9926 +vn -0.0001 0.1583 0.9874 +vn 0.0002 0.1591 0.9873 +vn -0.0001 0.4442 0.8959 +vn 0.0003 0.4458 0.8951 +vn -0.0009 0.7014 0.7127 +vn 0.0005 0.7053 0.7089 +vn -0.0008 0.8795 0.4760 +vn -0.0011 0.8793 0.4763 +vn -0.0053 0.9801 0.1982 +vn 0.0015 0.9701 0.2426 +vn 0.0059 1.0000 -0.0066 +vn -0.0068 0.9932 -0.1162 +vn 0.0020 0.9807 -0.1957 +vn -0.0037 0.9661 -0.2582 +vn -0.0048 0.9678 -0.2516 +vn -0.0009 -0.0256 -0.9997 +vn -0.1994 -0.3118 -0.9290 +vn -0.0187 -0.2996 -0.9539 +vn -0.0174 -0.5320 -0.8465 +vn -0.0195 -0.6640 -0.7475 +vn 0.0003 -0.7617 -0.6479 +vn -0.0009 -0.8999 -0.4361 +vn -0.0219 -0.9236 -0.3826 +vn -0.0140 -0.9755 -0.2197 +vn -0.0105 -0.9996 -0.0252 +vn -0.0073 0.8614 0.5079 +vn 0.0222 0.8679 0.4962 +vn 0.0310 0.9121 0.4087 +vn -0.0171 0.9550 0.2962 +vn 0.0117 0.9971 0.0752 +vn 0.0102 0.9998 0.0150 +vn 0.0393 0.9967 -0.0711 +vn 0.0552 0.9964 -0.0646 +vn -0.9975 0.0696 -0.0148 +vn -0.9759 0.0276 0.2163 +vn -0.9508 0.0406 0.3070 +vn -0.9966 0.0315 0.0761 +vn -0.9984 0.0086 0.0556 +vn -0.9991 0.0237 0.0353 +vn -0.9996 0.0179 0.0208 +vn -0.9988 0.0059 0.0494 +vn -0.9998 0.0203 0.0065 +vn -0.9992 0.0351 0.0208 +vn -0.9982 0.0531 0.0267 +vn -0.9994 0.0333 0.0136 +vn -0.9987 0.0510 0.0014 +vn -0.9988 0.0189 0.0443 +vn -0.9977 0.0655 0.0184 +vn -0.9988 0.0180 0.0452 +vn -0.9979 0.0617 0.0202 +vn -0.9984 0.0219 0.0513 +vn -0.9983 -0.0068 0.0579 +vn -0.9987 -0.0492 -0.0151 +vn -0.9988 -0.0480 -0.0023 +vn -0.9969 -0.0727 -0.0317 +vn -0.9988 -0.0005 -0.0482 +vn -0.9997 -0.0091 -0.0222 +vn -0.9987 -0.0164 -0.0490 +vn -0.9964 0.0667 -0.0514 +vn -0.9859 0.1468 -0.0801 +vn -0.9933 0.0814 -0.0824 +vn -0.9951 0.0103 -0.0979 +vn -0.9366 0.0606 -0.3452 +vn -0.9919 -0.1238 0.0265 +vn -0.9968 -0.0744 0.0293 +vn -0.9889 -0.1454 0.0321 +vn -0.9968 -0.0266 -0.0759 +vn -0.9988 -0.0298 -0.0380 +vn -0.9927 -0.0885 0.0816 +vn -0.9970 -0.0634 0.0440 +vn -0.9995 -0.0235 -0.0227 +vn -0.9994 -0.0043 -0.0356 +vn -0.9993 -0.0348 -0.0153 +vn -0.9614 -0.2741 0.0230 +vn -0.9230 0.0580 -0.3804 +vn -0.9987 0.0220 -0.0461 +vn -0.9994 -0.0317 0.0133 +vn -0.0012 -0.9998 -0.0191 +vn -0.0122 -0.9997 -0.0202 +vn 0.0018 -0.9998 -0.0210 +vn -0.0005 0.0013 1.0000 +vn -0.0006 0.0007 1.0000 +vn -0.0005 0.0012 1.0000 +vn -0.0006 0.0006 1.0000 +vn 0.6960 -0.1762 0.6960 +vn 0.6694 -0.1046 0.7355 +vn 0.6772 -0.1652 0.7170 +vn 0.6871 -0.0086 0.7265 +vn 0.6775 0.1152 0.7264 +vn 0.6787 0.2000 0.7067 +vn 0.6742 0.3184 0.6663 +vn 0.6733 0.4052 0.6185 +vn 0.6197 0.5457 0.5641 +vn 0.6936 0.6084 0.3858 +vn 0.6968 0.6460 0.3117 +vn 0.6673 0.7298 0.1484 +vn 0.6619 0.7318 0.1624 +vn 0.6806 0.7308 -0.0519 +vn 0.6866 0.7217 -0.0884 +vn 0.6851 0.7066 -0.1770 +vn 0.6947 0.6957 -0.1828 +vn -0.7119 0.0760 0.6982 +vn -0.7800 0.3715 0.5036 +vn -0.7187 -0.0285 0.6948 +vn -0.6741 0.1228 0.7284 +vn -0.7061 0.2578 0.6595 +vn -0.7146 0.3247 0.6196 +vn -0.7059 -0.1211 0.6979 +vn -0.7068 0.4490 0.5466 +vn -0.7072 0.5028 0.4971 +vn -0.7056 0.5962 0.3829 +vn -0.6951 0.6435 0.3205 +vn -0.7106 0.6915 0.1298 +vn -0.7162 0.6707 0.1928 +vn -0.6901 0.7236 -0.0122 +vn -0.7131 0.6865 -0.1421 +vn -0.7015 0.7046 -0.1065 +vn -0.7059 0.6857 -0.1778 +vn -0.7084 0.6822 -0.1811 +vn -0.9067 -0.1835 -0.3797 +vn -0.8613 0.1623 0.4814 +vn -0.8395 0.0585 0.5403 +vn -0.7601 -0.1482 0.6327 +vn -0.7276 -0.2089 0.6534 +vn 0.1047 0.2734 0.9562 +vn 0.4786 -0.3512 0.8047 +vn 0.8842 0.3300 0.3307 +vn 0.8166 -0.5054 -0.2789 +vn -0.5450 -0.1010 0.8324 +vn -0.5329 -0.0453 0.8450 +vn -0.5609 -0.1933 0.8050 +vn -0.5682 -0.2504 0.7839 +vn 0.1950 0.2554 0.9470 +vn 0.7136 -0.3365 0.6145 +vn 0.9070 0.1644 0.3877 +vn 0.8651 -0.0100 -0.5015 +vn -0.9402 0.0121 -0.3403 +vn 0.0008 0.9995 0.0303 +vn 0.0096 0.9990 0.0426 +vn -0.0002 0.9995 0.0316 +vn 0.0734 0.9951 0.0665 +vn 0.0098 0.9990 0.0435 +vn 0.0256 0.9994 0.0250 +vn 0.0104 -0.9998 -0.0165 +vn -0.0287 -0.9993 -0.0245 +vn 0.0284 -0.9993 -0.0253 +vn 0.0045 0.5795 0.8150 +vn 0.0022 0.5562 0.8310 +vn -0.0566 0.4938 0.8677 +vn -0.0004 0.5305 0.8477 +vn -0.5820 0.8131 -0.0134 +vn -0.6941 0.6839 0.2246 +vn -0.5525 0.8333 -0.0209 +vn -0.6478 0.4197 0.6358 +vn 0.0055 0.6692 0.7430 +vn -0.0052 0.4653 0.8852 +vn 0.0051 0.6624 0.7491 +vn -0.0056 0.4575 0.8892 +vn 0.5317 0.6142 0.5832 +vn 0.5617 0.5746 0.5952 +vn 0.6244 0.4791 0.6169 +vn 0.6513 0.4314 0.6243 +vn -0.0053 -0.0161 -0.9999 +vn -0.0241 -0.0172 -0.9996 +vn -0.0069 -0.0178 -0.9998 +vn 0.0568 -0.0295 -0.9979 +vn 0.0078 -0.0194 -0.9998 +vn 0.0020 1.0000 -0.0078 +vn -0.0013 0.9838 -0.1794 +vn 0.0017 1.0000 -0.0016 +vn -0.0013 0.9999 0.0143 +vn 0.8788 -0.1072 0.4649 +vn 0.8050 0.5444 -0.2358 +vn 0.3031 0.9165 0.2611 +vn 0.0045 0.9783 -0.2071 +vn -0.8821 0.4083 0.2349 +vn -0.8888 0.4060 0.2126 +vn -0.9173 0.3893 0.0845 +vn -0.9252 0.3788 0.0224 +vn -0.7923 -0.5745 -0.2052 +vn -0.1322 -0.0894 -0.9872 +vn 0.0017 -0.0231 -0.9997 +vn 0.0042 0.0469 0.9989 +vn 0.0023 -0.0065 1.0000 +vn -0.0013 0.0050 1.0000 +vn 0.0020 0.0537 0.9986 +vn 0.0521 0.0706 0.9961 +vn 0.0028 -0.0115 -0.9999 +vn 0.0447 -0.0183 -0.9988 +vn -0.0196 0.0010 0.9998 +vn -0.8691 0.4516 -0.2019 +vn -0.9023 -0.2383 0.3593 +vn 0.8970 -0.3869 0.2137 +vn 0.7627 0.5539 -0.3339 +vn 0.5065 0.7910 0.3433 +vn -0.0900 0.9613 -0.2603 +vn -0.6269 0.7360 0.2556 +vn -0.0002 0.8109 0.5852 +vn -0.0623 0.8723 0.4849 +vn 0.0023 0.7995 0.6007 +vn -0.0379 0.9976 -0.0579 +vn 0.0021 0.2909 -0.9567 +vn 0.0011 -0.8346 0.5508 +vn -0.0018 0.8922 -0.4517 +vn -0.0440 0.8626 0.5039 +vn -0.0999 0.8957 0.4333 +vn -0.8857 -0.0132 0.4642 +vn -0.7983 0.0175 0.6020 +vn -0.5220 0.4856 0.7012 +vn -0.2576 0.5988 0.7583 +vn -0.5323 0.4893 0.6908 +vn -0.2507 0.5894 0.7679 +vn 0.0072 0.8876 0.4605 +vn 0.0068 0.8822 0.4708 +vn 0.6543 0.6577 0.3733 +vn 0.6654 0.6587 0.3512 +vn 0.6701 0.6590 0.3415 +vn 0.6492 0.6571 0.3831 +vn -0.0259 0.0181 -0.9995 +vn 0.0149 0.0653 -0.9978 +vn -0.0018 -0.7412 -0.6713 +vn -0.0082 -0.7478 -0.6639 +vn -0.0048 -0.7443 -0.6679 +vn 0.0016 -0.7375 -0.6753 +vn 0.0034 -0.9971 0.0762 +vn -0.0076 -0.9980 0.0631 +vn -0.0052 -0.9978 0.0660 +vn -0.0161 -0.9985 0.0530 +vn 0.9998 0.0190 0.0052 +vn 0.9990 0.0337 0.0297 +vn 1.0000 -0.0018 0.0032 +vn 0.9992 -0.0160 -0.0378 +vn 0.9985 -0.0108 -0.0530 +vn 0.9999 -0.0083 -0.0130 +vn 0.9995 -0.0262 -0.0182 +vn 0.9999 0.0143 0.0039 +vn 1.0000 -0.0065 0.0008 +vn 0.9999 -0.0110 -0.0007 +vn 1.0000 -0.0095 -0.0019 +vn 0.9999 -0.0034 -0.0096 +vn 0.9996 -0.0009 -0.0294 +vn 0.9998 0.0145 -0.0106 +vn 0.9999 0.0140 0.0035 +vn 0.9996 0.0266 -0.0024 +vn 1.0000 0.0005 0.0085 +vn 0.9999 -0.0123 0.0028 +vn 1.0000 -0.0084 0.0041 +vn 0.9997 -0.0191 0.0130 +vn 0.9989 0.0248 -0.0403 +vn 0.9997 -0.0134 0.0198 +vn 0.9995 -0.0265 -0.0168 +vn 0.9997 -0.0215 0.0107 +vn 0.9971 0.0190 -0.0730 +vn 0.9998 -0.0168 -0.0044 +vn 0.0099 -0.9972 -0.0737 +vn 0.0056 -0.9969 -0.0789 +vn 0.0066 -0.9969 -0.0778 +vn 0.0022 -0.9965 -0.0830 +vn -0.0035 -0.7411 0.6713 +vn -0.0111 -0.7332 0.6800 +vn -0.0071 -0.7374 0.6754 +vn 0.0006 -0.7454 0.6666 +vn -0.0250 0.0356 0.9991 +vn -0.0270 0.0312 0.9991 +vn 0.0023 -0.1445 0.9895 +vn -0.0013 -0.0577 0.9983 +vn 0.0057 -0.0494 0.9988 +vn 0.0046 -0.0506 0.9987 +vn 0.0118 -0.0420 0.9990 +vn 0.0127 0.7711 0.6366 +vn -0.0357 0.7119 0.7013 +vn -0.0113 0.7427 0.6695 +vn -0.0586 0.6811 0.7298 +vn -0.0077 0.9983 -0.0577 +vn -0.0030 0.9980 -0.0634 +vn -0.0039 0.9981 -0.0623 +vn 0.0007 0.9977 -0.0679 +vn -0.0043 0.9794 -0.2017 +vn -0.0356 0.9993 -0.0144 +vn -0.0457 0.9984 -0.0340 +vn 0.0377 0.6195 -0.7841 +vn 0.0580 0.6478 -0.7596 +vn 0.0495 0.6362 -0.7700 +vn 0.0277 0.6051 -0.7957 +vn -0.0053 -0.0853 -0.9963 +vn -0.0180 -0.0700 -0.9974 +vn -0.0155 -0.0729 -0.9972 +vn -0.0276 -0.0582 -0.9979 +vn 0.0332 0.0490 0.9982 +vn -0.0587 0.1217 0.9908 +vn 0.0542 0.0322 0.9980 +vn 0.1282 -0.0273 0.9914 +vn -0.1256 -0.9919 -0.0188 +vn 0.3388 -0.6973 -0.6317 +vn -0.1442 -0.2209 -0.9646 +vn 0.0990 0.9453 -0.3107 +vn 0.0737 0.9416 -0.3286 +vn 0.1102 0.9467 -0.3027 +vn 0.1393 0.9494 -0.2815 +vn 0.0225 -0.1424 -0.9895 +vn -0.0886 -0.3140 -0.9453 +vn -0.0198 -0.2087 -0.9778 +vn 0.0855 -0.0416 -0.9955 +vn 0.0433 0.9730 0.2268 +vn -0.1139 0.9933 -0.0181 +vn -0.0031 0.9877 0.1561 +vn 0.1567 0.9052 0.3950 +vn -0.0509 -0.7444 0.6657 +vn 0.1164 -0.8592 0.4982 +vn -0.0236 -0.7669 0.6413 +vn -0.1870 -0.6103 0.7698 +vn -0.9339 -0.3324 0.1317 +vn -0.8704 -0.4720 0.1400 +vn -0.6547 -0.7279 0.2038 +vn -0.7325 -0.6676 0.1331 +vn -0.5812 -0.7964 0.1672 +vn -0.5749 -0.7863 0.2264 +vn -0.5412 -0.1129 -0.8333 +vn -0.5262 -0.0522 -0.8488 +vn -0.6099 -0.6374 -0.4709 +vn -0.6959 -0.4936 -0.5216 +vn -0.6033 -0.7299 -0.3213 +vn -0.6137 -0.7076 -0.3502 +vn -0.6016 -0.7712 -0.2082 +vn -0.7993 -0.6006 -0.0219 +vn -0.5981 -0.4517 -0.6620 +vn -0.8873 -0.1167 -0.4461 +vn -0.5696 -0.4531 -0.6857 +vn -0.5471 -0.0659 -0.8345 +vn -0.8838 0.1192 -0.4524 +vn -0.7393 0.3010 -0.6024 +vn -0.8463 0.1424 -0.5134 +vn -0.5921 0.2238 -0.7742 +vn -0.0208 -0.2619 0.9649 +vn 0.0422 -0.6763 0.7354 +vn 0.0365 0.7222 -0.6907 +vn -0.0211 0.9550 -0.2958 +vn -0.7996 0.1643 -0.5776 +vn -0.9386 0.3387 -0.0656 +vn -0.9450 0.2963 -0.1384 +vn 0.0306 -0.9995 -0.0098 +vn 0.0399 -0.9990 0.0219 +vn 0.0230 -0.9994 0.0255 +vn 0.0147 -0.9989 -0.0441 +vn 0.0066 -0.9995 -0.0318 +vn -0.0185 -0.9994 -0.0305 +vn 0.0052 -0.9993 0.0383 +vn -0.0322 -0.9995 0.0041 +vn -0.0213 -0.9995 0.0223 +vn -0.0299 -0.9994 -0.0174 +vn 0.0149 0.9998 -0.0131 +vn -0.0073 0.9974 -0.0720 +vn 0.0186 0.9996 -0.0229 +vn 0.0287 0.9996 0.0007 +vn 0.0340 0.9992 -0.0195 +vn 0.4092 -0.0015 0.9125 +vn 0.4742 0.0112 0.8803 +vn 0.4650 0.0094 0.8853 +vn 0.4010 -0.0031 0.9161 +vn -0.7841 0.0114 0.6206 +vn -0.7460 0.0233 0.6656 +vn -0.7520 0.0215 0.6588 +vn -0.7897 0.0095 0.6134 +vn -0.7585 0.0120 -0.6516 +vn -0.7600 0.0125 -0.6498 +vn -0.7598 0.0124 -0.6500 +vn -0.7583 0.0120 -0.6519 +vn 0.2045 0.0028 -0.9789 +vn 0.2737 0.0135 -0.9617 +vn 0.2118 0.0039 -0.9773 +vn 0.2813 0.0147 -0.9595 +vn 0.9850 0.0052 -0.1725 +vn 0.9818 0.0085 -0.1895 +vn 0.9823 0.0080 -0.1871 +vn 0.9854 0.0047 -0.1703 +vn -0.0223 0.9973 0.0698 +vn 0.0124 0.9975 0.0696 +vn 0.0660 0.9965 0.0504 +vn 0.0704 0.9975 0.0102 +vn -0.0525 0.9973 0.0507 +vn 0.0615 0.9970 -0.0469 +vn 0.0345 0.9974 -0.0634 +vn -0.0142 0.9970 -0.0765 +vn -0.0418 0.9975 -0.0567 +vn -0.0795 0.9968 -0.0063 +vn -0.0935 0.9956 0.0040 +vn 0.6808 0.0981 0.7259 +vn 0.6511 0.0660 0.7561 +vn 0.6426 0.0571 0.7641 +vn 0.9872 -0.1077 0.1176 +vn 0.8945 0.1403 -0.4246 +vn 0.8113 0.0286 -0.5839 +vn 0.8317 0.0521 -0.5528 +vn 0.7001 -0.0776 -0.7099 +vn -0.0683 0.0630 -0.9957 +vn -0.0707 0.0611 -0.9956 +vn -0.0700 0.0617 -0.9956 +vn -0.0729 0.0593 -0.9956 +vn -0.8581 0.0338 -0.5124 +vn -0.7112 -0.0775 -0.6988 +vn -0.8075 -0.0096 -0.5897 +vn -0.9126 0.0924 -0.3984 +vn -0.9613 -0.0133 0.2752 +vn -0.9869 -0.0977 0.1282 +vn -0.9743 -0.0453 0.2205 +vn -0.9208 0.0541 0.3864 +vn -0.3564 0.0016 0.9343 +vn -0.3285 -0.0243 0.9442 +vn -0.3331 -0.0201 0.9427 +vn -0.3069 -0.0440 0.9507 +vn 0.6009 0.0155 0.7992 +vn 0.7018 0.1239 0.7016 +vn 0.7131 0.1409 0.6868 +vn 0.7152 0.1441 0.6840 +vn 0.7282 0.1645 0.6654 +vn 0.2517 0.2295 -0.9402 +vn 0.6468 -0.1048 -0.7554 +vn -0.7296 -0.1524 -0.6667 +vn -0.9307 0.2672 0.2496 +vn -0.6431 -0.1495 0.7510 +vn -0.0307 -0.0275 -0.9991 +vn -0.0220 -0.0424 -0.9989 +vn -0.0334 -0.0313 -0.9990 +vn 0.0328 0.0345 -0.9989 +vn 0.0288 -0.0001 -0.9996 +vn 0.0243 0.0310 -0.9992 +vn -0.0313 -0.0076 -0.9995 +vn 0.0113 0.0491 -0.9987 +vn 0.0145 0.0505 -0.9986 +vn -0.0282 -0.0033 -0.9996 +vn 0.0280 -0.0093 -0.9996 +vn 0.0345 -0.0139 -0.9993 +vn -0.0028 -0.0143 0.9999 +vn -0.0556 -0.0131 0.9984 +vn -0.0129 -0.0202 0.9997 +vn 0.0104 -0.0163 0.9998 +vn 0.0239 -0.0080 0.9997 +vn -0.9521 -0.3031 0.0392 +vn -0.8962 0.4437 0.0078 +vn -0.8009 0.5980 -0.0297 +vn -0.8171 0.5761 -0.0241 +vn -0.9037 0.4279 0.0114 +vn 0.0383 0.9986 0.0360 +vn 0.1681 0.9857 0.0101 +vn 0.1543 0.9879 0.0129 +vn 0.0205 0.9990 0.0395 +vn 0.8532 0.5212 -0.0190 +vn 0.9917 -0.1149 0.0570 +vn 0.7524 -0.6582 -0.0257 +vn -0.4427 -0.8966 -0.0138 +vn -0.1121 -0.9930 0.0378 +vn -0.1650 -0.9858 0.0300 +vn -0.4854 -0.8740 -0.0210 +vn -0.0787 -0.0249 0.9966 +vn -0.1003 -0.0143 0.9949 +vn -0.0366 -0.0620 0.9974 +vn 0.0142 -0.0675 0.9976 +vn -0.0553 0.0442 0.9975 +vn 0.0754 -0.0042 0.9971 +vn 0.0783 0.0196 0.9967 +vn 0.0441 0.0553 0.9975 +vn 0.0312 0.0609 0.9977 +vn 0.0564 -0.0430 0.9975 +vn 0.0115 -0.0791 0.9968 +vn -0.0314 0.0640 0.9975 +vn -0.0046 0.0756 0.9971 +vn -0.1817 -0.9830 -0.0263 +vn -0.1676 -0.9857 -0.0165 +vn -0.1759 -0.9841 -0.0223 +vn -0.1910 -0.9811 -0.0327 +vn 0.4964 -0.8679 0.0195 +vn 0.5031 -0.8641 0.0149 +vn 0.4998 -0.8660 0.0171 +vn 0.5071 -0.8618 0.0121 +vn 0.9754 -0.2203 0.0067 +vn 0.9579 -0.2848 -0.0351 +vn 0.9693 -0.2458 -0.0097 +vn 0.9831 -0.1805 0.0322 +vn 0.8628 0.5054 -0.0120 +vn 0.8772 0.4801 0.0079 +vn 0.8707 0.4919 -0.0013 +vn 0.8846 0.4659 0.0189 +vn 0.4130 0.9100 -0.0362 +vn 0.3623 0.9320 -0.0084 +vn 0.3129 0.9496 0.0180 +vn 0.2621 0.9640 0.0445 +vn -0.3935 0.9192 0.0119 +vn -0.3119 0.9497 -0.0284 +vn -0.3566 0.9342 -0.0066 +vn -0.4320 0.9013 0.0314 +vn -0.9412 0.3378 0.0026 +vn -0.8679 0.4875 -0.0955 +vn -0.9201 0.3905 -0.0310 +vn -0.9713 0.2274 0.0702 +vn -0.8595 -0.5111 -0.0103 +vn -0.8864 -0.4605 -0.0471 +vn -0.8692 -0.4939 -0.0230 +vn -0.8373 -0.5466 0.0166 +vn -0.8141 -0.5612 -0.1495 +vn -0.2604 -0.8123 -0.5219 +vn 0.5335 -0.8297 0.1643 +vn 0.9248 0.3804 0.0029 +vn 0.9688 0.2125 0.1280 +vn 0.9252 0.3795 0.0037 +vn 0.8141 0.5612 -0.1495 +vn 0.4990 0.5787 -0.6451 +vn -0.5335 0.8297 0.1643 +vn -0.9550 0.0402 0.2938 +vn 0.8208 0.5021 -0.2724 +vn 0.9842 0.1757 -0.0237 +vn 0.8788 0.4369 -0.1918 +vn 0.9988 0.0275 -0.0403 +vn 0.9982 0.0553 -0.0246 +vn 0.9992 0.0324 -0.0247 +vn 0.9992 0.0245 -0.0323 +vn 0.9988 0.0363 0.0316 +vn 0.9989 0.0283 0.0371 +vn 0.9988 0.0350 0.0341 +vn 0.9987 0.0387 0.0341 +vn 0.9987 0.0409 0.0302 +vn 0.6238 -0.1725 0.7623 +vn 0.3723 -0.5168 -0.7709 +vn -0.3677 -0.6491 0.6660 +vn -0.5734 -0.5476 0.6093 +vn -0.2150 -0.6977 0.6834 +vn 0.7250 -0.6177 0.3048 +vn 0.7249 -0.6177 0.3048 +vn 0.7238 -0.6188 0.3052 +vn 0.7233 -0.6194 0.3054 +vn -0.3088 -0.1709 -0.9356 +vn 0.7582 -0.6465 -0.0844 +vn 0.6536 -0.7522 -0.0841 +vn 0.7233 -0.6854 -0.0845 +vn -0.4814 -0.7931 -0.3731 +vn 0.2577 0.3109 -0.9148 +vn 0.1688 0.1671 -0.9714 +vn 0.0696 0.0440 -0.9966 +vn -0.1463 -0.5012 -0.8529 +vn 0.6900 0.3411 -0.6384 +vn 0.2396 0.7835 -0.5733 +vn 0.3193 0.8651 -0.3869 +vn 0.2886 0.8368 -0.4653 +vn 0.5928 0.7542 0.2825 +vn -0.1033 0.7707 0.6288 +vn 0.0148 0.7811 0.6242 +vn -0.1392 0.7653 0.6285 +vn -0.5061 0.6499 -0.5670 +vn 0.7010 0.4176 0.5781 +vn 0.6980 0.3383 -0.6312 +vn -0.4064 -0.1077 0.9073 +vn -0.2596 -0.4565 0.8510 +vn 0.5249 -0.4626 0.7144 +vn 0.5859 -0.2495 -0.7710 +vn 0.5783 -0.6727 -0.4615 +vn -0.1976 -0.7290 -0.6554 +vn -0.2291 -0.7282 -0.6459 +vn -0.1928 -0.7032 0.6844 +vn 0.8296 0.0751 -0.5532 +vn 0.6500 -0.7553 -0.0841 +vn -0.5383 0.6391 -0.5493 +vn 0.3582 0.8933 -0.2715 +vn 0.5347 0.8451 -0.0016 +vn -0.2930 0.9217 0.2543 +vn 0.0195 0.7813 0.6239 +vn 0.6945 0.1606 0.7014 +vn 0.9269 0.0995 0.3619 +vn 0.9319 0.0774 0.3544 +vn -0.5315 -0.8357 0.1382 +vn -0.9988 -0.0298 -0.0392 +vn -1.0000 0.0017 0.0005 +vn -0.9999 -0.0052 -0.0116 +vn -1.0000 0.0017 0.0018 +vn -1.0000 0.0033 0.0032 +vn -1.0000 0.0036 0.0026 +vn -0.9999 0.0092 -0.0118 +vn -0.9999 0.0132 -0.0089 +vn -0.9999 -0.0079 0.0141 +vn -0.9998 -0.0143 0.0155 +vn -0.9996 -0.0274 0.0047 +vn -1.0000 0.0048 0.0021 +vn -0.9996 -0.0030 -0.0276 +vn -1.0000 0.0085 -0.0010 +vn -1.0000 0.0029 0.0063 +vn -1.0000 -0.0010 0.0069 +vn -1.0000 -0.0023 0.0080 +vn -0.9999 0.0112 -0.0056 +vn -1.0000 -0.0011 0.0041 +vn -1.0000 0.0002 -0.0002 +vn 0.9988 -0.0335 0.0370 +vn 0.9996 -0.0194 0.0214 +vn 0.9984 0.0218 -0.0514 +vn 0.9999 0.0162 0.0042 +vn 0.9994 0.0293 -0.0167 +vn 0.9977 -0.0213 0.0644 +vn 0.9948 -0.0152 0.1010 +vn 0.9996 -0.0226 -0.0147 +vn 0.9948 -0.0919 0.0439 +vn 0.9997 -0.0145 0.0177 +vn 0.9999 0.0096 -0.0093 +vn 0.9996 0.0024 0.0271 +vn 0.9997 0.0021 0.0245 +vn 0.9993 0.0053 0.0364 +vn 0.9992 0.0395 -0.0004 +vn 0.9992 0.0395 -0.0038 +vn 0.9997 0.0026 0.0259 +vn 1.0000 -0.0038 0.0005 +vn 0.9998 -0.0208 -0.0029 +vn 0.9456 0.1346 0.2962 +vn 0.9974 0.0480 0.0537 +vn 0.9999 0.0086 0.0112 +vn 0.9989 0.0062 0.0470 +vn -0.3527 0.6806 0.6422 +vn -0.2146 0.5962 0.7736 +vn -0.2248 0.7912 0.5688 +vn 0.2764 -0.8975 0.3436 +vn 0.4785 -0.6744 0.5623 +vn 0.1711 -0.8016 0.5728 +vn -0.4286 -0.6664 0.6101 +vn -0.0373 -0.6652 0.7457 +vn -0.2043 -0.6543 0.7281 +vn -0.4600 0.5031 -0.7316 +vn -0.4528 0.2650 -0.8513 +vn -0.7747 0.1340 -0.6179 +vn -0.1304 -0.9828 0.1308 +vn -0.2701 -0.8226 0.5004 +vn -0.8385 -0.1491 0.5241 +vn -0.9481 0.0111 0.3179 +vn -0.9591 0.0236 0.2822 +vn 0.9137 0.0169 0.4059 +vn 0.6837 0.0698 0.7264 +vn 0.7386 0.0574 0.6717 +vn -0.7549 0.5386 -0.3742 +vn -0.6263 0.6795 -0.3820 +vn -0.6609 0.4896 -0.5688 +vn 0.0565 0.9972 0.0486 +vn 0.0281 0.9985 0.0466 +vn 0.0328 0.9769 0.2110 +vn 0.2101 0.9744 -0.0799 +vn 0.3214 0.9204 0.2227 +vn 0.4375 0.8846 -0.1615 +vn -0.6825 0.7299 0.0372 +vn -0.7006 0.6632 0.2631 +vn -0.6229 0.7707 0.1340 +vn 0.8854 0.1469 -0.4410 +vn 0.6604 0.3253 -0.6768 +vn 0.7626 0.2802 -0.5831 +vn 0.6883 0.5929 0.4180 +vn 0.7852 0.5827 0.2096 +vn 0.6613 0.6968 0.2778 +vn -0.4257 0.8197 -0.3833 +vn -0.3420 0.9156 -0.2113 +vn -0.0875 0.8949 -0.4377 +vn 0.4170 0.8448 -0.3352 +vn 0.2611 0.9579 -0.1192 +vn 0.6703 0.7097 -0.2166 +vn -0.1725 -0.8391 0.5159 +vn -0.0015 0.9833 0.1820 +vn 0.2159 0.9456 0.2434 +vn 0.3914 0.9123 0.1201 +vn -0.6353 0.7385 0.2261 +vn -0.4337 0.8841 0.1740 +vn -0.4457 0.8879 -0.1137 +vn 0.6613 0.6968 -0.2778 +vn 0.6773 0.5842 -0.4472 +vn 0.4500 0.7505 -0.4840 +vn 0.4318 0.6592 -0.6156 +vn 0.4401 0.7459 -0.5000 +vn 0.5204 0.7187 -0.4611 +vn 0.3987 0.8428 -0.3616 +vn 0.5684 0.7736 -0.2802 +vn -0.0117 0.3772 -0.9261 +vn 0.1969 0.3377 -0.9204 +vn 0.2097 0.1702 -0.9628 +vn -0.7341 0.4884 0.4718 +vn -0.4257 0.8197 0.3833 +vn -0.5496 0.8216 0.1515 +vn -0.1304 -0.9828 -0.1308 +vn -0.1303 -0.9828 -0.1308 +vn 0.4716 -0.0403 -0.8809 +vn 0.5393 -0.0670 -0.8395 +vn 0.4706 -0.0992 -0.8768 +vn -0.0580 -0.8284 0.5571 +vn 0.0983 0.9859 -0.1356 +vn 0.0466 0.9878 -0.1485 +vn 0.3126 0.9107 -0.2700 +vn 0.4502 0.8650 -0.2215 +vn 0.4905 0.7993 -0.3471 +vn -0.3527 0.6806 -0.6422 +vn -0.3991 0.4388 -0.8051 +vn -0.4803 0.6309 -0.6093 +vn 0.1730 0.9790 -0.1077 +vn 0.0897 0.9947 0.0494 +vn -0.7570 0.6465 -0.0949 +vn -0.7848 0.5980 -0.1628 +vn -0.8207 0.5701 0.0372 +vn 0.3528 0.4414 -0.8250 +vn 0.3444 0.5188 -0.7824 +vn 0.5616 0.4478 -0.6957 +vn 0.6176 -0.2154 0.7564 +vn 0.3719 -0.3443 0.8621 +vn 0.5732 -0.5191 0.6341 +vn -0.1725 -0.8391 -0.5159 +vn 0.0537 0.4112 -0.9100 +vn 0.2528 0.1703 -0.9524 +vn 0.0338 0.0528 -0.9980 +vn -0.9875 0.1577 -0.0042 +vn -0.9527 0.3006 -0.0437 +vn -0.9922 0.1180 -0.0389 +vn -0.5676 0.7301 0.3805 +vn -0.7128 0.6221 0.3239 +vn -0.7779 0.3136 0.5446 +vn 0.9912 -0.1050 -0.0806 +vn 0.9516 0.2899 0.1020 +vn 0.9871 -0.0818 0.1376 +vn 0.1755 -0.9842 0.0213 +vn 0.3852 -0.9197 -0.0759 +vn 0.4185 -0.9075 0.0370 +vn -0.9969 0.0662 0.0425 +vn -0.9855 0.1608 0.0534 +vn -0.1152 0.7926 -0.5987 +vn -0.4000 0.4668 -0.7887 +vn -0.3513 0.5398 -0.7650 +vn 0.6322 0.7633 -0.1331 +vn 0.5136 0.8068 0.2920 +vn 0.7165 0.6956 -0.0526 +vn -0.0753 -0.9886 0.1305 +vn 0.0503 0.1853 -0.9814 +vn -0.0092 0.2828 -0.9591 +vn 0.0539 0.2770 -0.9594 +vn 0.5616 0.4478 0.6957 +vn 0.5341 0.6213 0.5733 +vn 0.3910 0.6651 0.6362 +vn -0.9409 0.2323 -0.2465 +vn -0.7349 0.4222 -0.5307 +vn -0.7615 0.3976 -0.5119 +vn -0.4216 0.6295 -0.6526 +vn -0.2652 0.7669 -0.5844 +vn -0.0999 0.7450 -0.6596 +vn -0.6057 0.5469 0.5780 +vn -0.8202 0.5440 0.1768 +vn -0.8568 0.2790 0.4336 +vn -0.2701 -0.8226 0.5005 +vn -0.2460 -0.6205 -0.7446 +vn -0.2648 -0.5810 -0.7696 +vn 0.0153 -0.7165 -0.6975 +vn -0.2701 -0.8226 -0.5004 +vn 0.2630 -0.5440 -0.7968 +vn -0.2214 -0.1683 0.9606 +vn -0.4277 -0.1615 0.8894 +vn -0.6229 -0.0529 0.7805 +vn 0.0378 0.9913 -0.1263 +vn 0.1508 0.7965 -0.5856 +vn 0.1331 0.7443 -0.6545 +vn 0.1276 0.8220 -0.5550 +vn 0.9626 -0.0564 -0.2649 +vn 0.9893 -0.1416 0.0343 +vn 0.9309 -0.0761 -0.3573 +vn -0.7997 0.5954 -0.0778 +vn -0.5456 0.8354 -0.0665 +vn -0.5580 0.8113 -0.1744 +vn 0.8385 0.5315 -0.1199 +vn 0.8482 0.5241 -0.0769 +vn 0.8702 0.4885 -0.0647 +vn 0.9429 -0.2922 0.1601 +vn 0.9808 -0.1945 -0.0115 +vn -0.9293 -0.0116 0.3692 +vn 0.0378 0.9913 0.1263 +vn -0.2914 0.9559 0.0358 +vn -0.1943 0.9310 0.3089 +vn -0.6919 0.6956 -0.1933 +vn -0.7944 0.6067 0.0293 +vn -0.7287 0.6842 0.0295 +vn 0.2277 0.8115 -0.5381 +vn 0.2415 0.7805 -0.5766 +vn 0.2616 0.7893 -0.5556 +vn 0.3674 -0.1313 0.9207 +vn 0.5459 -0.1263 0.8283 +vn 0.2560 -0.1267 0.9583 +vn 0.6183 0.1149 -0.7775 +vn 0.6394 0.0378 -0.7680 +vn 0.5103 0.5211 -0.6842 +vn 0.7503 0.2437 -0.6145 +vn 0.5694 0.0487 -0.8206 +vn -0.9526 -0.1209 -0.2791 +vn -0.8535 -0.2483 -0.4582 +vn 0.9275 0.3648 -0.0816 +vn 0.9437 0.3289 -0.0355 +vn 0.8765 0.3487 -0.3320 +vn 0.2541 -0.1536 -0.9549 +vn 0.2797 -0.2149 -0.9357 +vn -0.0295 -0.2608 -0.9649 +vn 0.9064 -0.0647 -0.4174 +vn 0.9685 -0.0980 -0.2291 +vn -0.0899 0.9266 0.3651 +vn -0.2583 0.9661 0.0037 +vn -0.5945 0.0701 0.8011 +vn -0.3991 0.4388 0.8051 +vn -0.4803 0.6309 0.6093 +vn 0.8804 0.4672 0.0813 +vn 0.8840 0.4470 0.1370 +vn -0.6609 0.4896 0.5688 +vn -0.5271 0.6425 0.5563 +vn -0.6263 0.6795 0.3820 +vn -0.5809 0.7035 -0.4095 +vn -0.8057 0.5618 -0.1875 +vn -0.5722 0.7722 -0.2763 +vn 0.8358 0.0593 0.5459 +vn 0.9591 -0.2046 0.1958 +vn 0.9546 0.2164 0.2047 +vn 0.2468 0.8206 -0.5154 +vn -0.0634 0.6863 -0.7246 +vn -0.1122 0.7924 -0.5996 +vn 0.1136 0.7537 -0.6473 +vn 0.5027 -0.7665 0.3997 +vn 0.6075 -0.7925 0.0539 +vn 0.6078 -0.7917 0.0613 +vn -0.7285 0.4662 -0.5020 +vn -0.3800 0.5412 -0.7501 +vn -0.6151 0.5036 -0.6067 +vn -0.7170 -0.6678 0.1999 +vn -0.7061 -0.6773 0.2067 +vn -0.7195 -0.5553 0.4170 +vn 0.9736 0.0766 -0.2153 +vn 0.9743 -0.1687 0.1494 +vn 0.9736 0.0765 -0.2153 +vn 0.1778 0.9566 0.2308 +vn 0.1725 0.8391 0.5160 +vn 0.4462 0.8747 0.1889 +vn 0.4393 0.0585 -0.8964 +vn 0.2026 0.2216 -0.9539 +vn 0.4640 0.2483 -0.8503 +vn 0.9293 0.0116 0.3692 +vn 0.1125 -0.5538 0.8250 +vn -0.2933 -0.1691 -0.9409 +vn -0.0502 0.8795 -0.4733 +vn -0.0528 0.8696 -0.4909 +vn -0.1325 0.8667 -0.4810 +vn -0.7479 -0.6296 -0.2106 +vn -0.7189 -0.6674 -0.1942 +vn -0.6453 -0.7615 0.0616 +vn 0.7047 0.3612 0.6106 +vn 0.8924 0.2077 0.4006 +vn 0.7054 0.3722 0.6032 +vn 0.9022 0.3294 0.2783 +vn 0.7804 0.4054 0.4761 +vn 0.1420 -0.5594 -0.8166 +vn 0.4458 -0.5181 -0.7299 +vn 0.3761 -0.5377 -0.7546 +vn 0.2600 -0.5513 -0.7928 +vn -0.2974 0.7063 0.6425 +vn -0.3440 0.5544 0.7578 +vn -0.0485 0.6721 0.7389 +vn 0.2871 0.9523 -0.1031 +vn 0.0433 -0.3896 -0.9200 +vn -0.2214 -0.1683 -0.9606 +vn -0.1962 -0.1188 -0.9733 +vn 0.4145 0.9097 -0.0239 +vn 0.3270 0.9439 -0.0467 +vn 0.9437 0.0111 0.3307 +vn 0.7865 0.2739 0.5535 +vn 0.7310 0.1835 0.6573 +vn -0.9882 -0.0972 0.1180 +vn -0.9293 0.0822 0.3600 +vn -0.9394 0.0889 0.3312 +vn 0.6259 0.5950 -0.5041 +vn 0.2701 0.8226 -0.5005 +vn 0.2701 0.8226 -0.5004 +vn 0.1236 0.9829 0.1363 +vn 0.1107 0.9841 0.1392 +vn 0.1290 0.9566 0.2612 +vn -0.6357 0.7090 -0.3053 +vn -0.6207 0.7831 -0.0389 +vn -0.4680 0.8177 -0.3351 +vn -0.2403 0.9267 -0.2890 +vn -0.2098 0.9694 -0.1272 +vn -0.2701 -0.8226 -0.5005 +vn -0.9873 -0.0041 -0.1587 +vn -0.9929 0.0292 -0.1154 +vn -0.9844 0.0710 -0.1610 +vn 0.3518 0.7330 0.5822 +vn 0.4019 0.4884 0.7745 +vn 0.5103 0.5211 0.6842 +vn 0.9440 -0.1777 -0.2781 +vn 0.9538 -0.2860 -0.0921 +vn 0.9227 -0.3854 -0.0020 +vn -0.2583 0.9661 -0.0037 +vn -0.1330 0.9547 0.2661 +vn -0.0349 0.9994 0.0032 +vn 0.4340 0.8055 -0.4036 +vn 0.3934 0.9173 -0.0610 +vn 0.5838 0.8118 -0.0130 +vn -0.0378 -0.9913 -0.1263 +vn 0.5360 0.7342 0.4167 +vn 0.1514 0.8806 0.4489 +vn -0.0641 0.2501 -0.9661 +vn -0.0866 0.2221 -0.9712 +vn -0.1279 0.3080 -0.9428 +vn -0.2630 -0.6389 -0.7230 +vn -0.5603 -0.6221 -0.5469 +vn -0.3097 -0.6073 -0.7316 +vn -0.5811 0.7225 -0.3747 +vn -0.7779 0.3136 -0.5446 +vn -0.7128 0.6221 -0.3239 +vn -0.0141 0.8318 -0.5549 +vn 0.0122 0.8540 -0.5202 +vn 0.0330 0.8487 -0.5278 +vn -0.2006 0.8747 0.4412 +vn -0.3041 0.7718 0.5584 +vn -0.1607 0.7767 0.6091 +vn -0.9863 0.0082 -0.1649 +vn -0.9532 0.0437 -0.2993 +vn -0.9849 0.0073 -0.1729 +vn 0.0611 0.4471 -0.8924 +vn 0.1083 0.8779 -0.4665 +vn 0.1203 0.8585 -0.4986 +vn 0.1196 0.8699 -0.4786 +vn 0.6160 -0.1927 0.7638 +vn 0.3933 -0.1537 0.9065 +vn 0.3515 -0.2110 0.9121 +vn 0.4581 0.0753 -0.8857 +vn 0.4282 0.0537 -0.9021 +vn 0.1723 0.0967 -0.9803 +vn 0.7767 0.6073 0.1674 +vn 0.6019 0.7768 0.1855 +vn 0.5251 0.7195 0.4544 +vn 0.9137 0.0169 -0.4060 +vn 0.9137 0.0169 -0.4059 +vn 0.9762 -0.0096 -0.2167 +vn -0.3087 0.5905 -0.7456 +vn 0.0739 0.6689 -0.7397 +vn -0.6241 0.7738 0.1083 +vn -0.6883 0.7178 -0.1044 +vn -0.8316 0.5535 0.0462 +vn -0.1271 0.5192 0.8451 +vn 0.0537 0.4112 0.9100 +vn 0.2562 0.6365 0.7275 +vn -0.3405 -0.3216 0.8835 +vn -0.3826 -0.2240 0.8963 +vn -0.5140 -0.4179 0.7491 +vn 0.3147 -0.9433 -0.1059 +vn 0.1184 -0.8796 -0.4607 +vn 0.3831 -0.8543 -0.3513 +vn -0.3360 0.1653 -0.9272 +vn -0.5355 0.1598 -0.8293 +vn -0.2240 0.1788 -0.9580 +vn 0.4262 -0.8829 0.1973 +vn 0.3321 -0.8054 0.4910 +vn 0.2910 -0.8638 0.4112 +vn 0.7680 0.6236 0.1462 +vn 0.8711 0.4530 0.1898 +vn 0.8228 0.5605 -0.0945 +vn 0.1178 0.9031 0.4129 +vn 0.1210 0.9438 0.3076 +vn -0.0662 0.9708 0.2304 +vn 0.7214 0.1193 0.6822 +vn 0.4892 0.2865 0.8237 +vn 0.6177 0.1789 0.7658 +vn -0.9433 0.3180 -0.0954 +vn -0.8183 0.4995 -0.2844 +vn -0.9492 0.2753 -0.1523 +vn 0.7865 0.2739 -0.5535 +vn 0.7310 0.1835 -0.6573 +vn 0.6445 0.3160 -0.6962 +vn 0.5818 0.3178 0.7487 +vn 0.5968 0.0438 0.8012 +vn 0.8548 0.3013 0.4224 +vn -0.5780 0.7807 -0.2378 +vn -0.3812 0.8205 -0.4261 +vn -0.5886 0.7131 -0.3809 +vn -0.5322 0.8420 -0.0884 +vn -0.3564 0.9004 -0.2496 +vn 0.8939 0.2659 0.3608 +vn 0.8914 0.4446 0.0880 +vn 0.0851 0.4570 -0.8854 +vn 0.2284 0.5497 -0.8035 +vn 0.3399 0.1630 -0.9262 +vn 0.5031 -0.8453 -0.1798 +vn 0.4976 -0.7937 -0.3499 +vn -0.6799 0.3273 -0.6562 +vn -0.5332 0.3748 -0.7585 +vn 0.7783 -0.1881 0.5991 +vn 0.6069 -0.1839 0.7732 +vn 0.3614 -0.1746 0.9159 +vn -0.1303 -0.9828 0.1307 +vn 0.4946 0.8301 -0.2576 +vn 0.7165 0.6956 0.0526 +vn 0.7680 0.6236 -0.1462 +vn 0.0474 0.7198 -0.6926 +vn 0.0525 0.6126 -0.7886 +vn -0.0572 0.5611 -0.8258 +vn -0.3728 0.9033 0.2122 +vn -0.5436 0.8299 0.1257 +vn -0.1043 0.9136 0.3930 +vn 0.0075 0.8062 0.5916 +vn 0.1146 0.9125 0.3926 +vn -0.0264 0.9063 -0.4219 +vn 0.0635 0.9065 -0.4175 +vn 0.0183 0.8884 -0.4588 +vn 0.1250 0.8503 -0.5111 +vn 0.1419 0.8404 -0.5231 +vn -0.0823 -0.6562 -0.7501 +vn 0.9373 -0.1148 0.3290 +vn 0.7845 -0.1330 0.6057 +vn 0.8287 -0.1348 0.5432 +vn -0.6281 -0.7587 -0.1730 +vn -0.2664 -0.9403 -0.2120 +vn 0.0049 0.9846 -0.1749 +vn 0.3849 0.9156 -0.1166 +vn 0.2654 0.7844 -0.5606 +vn -0.0187 0.9987 0.0476 +vn 0.0697 0.9751 0.2106 +vn -0.4680 0.8177 0.3351 +vn 0.0643 0.9640 0.2582 +vn 0.0871 0.9856 0.1450 +vn 0.0744 0.9878 0.1371 +vn 0.6868 0.3470 -0.6387 +vn 0.4964 0.2614 -0.8278 +vn 0.6138 0.4142 -0.6721 +vn -0.0179 0.9901 -0.1390 +vn -0.1069 0.9920 0.0666 +vn -0.1900 0.8682 -0.4584 +vn -0.1607 0.7767 -0.6091 +vn -0.3041 0.7718 -0.5584 +vn 0.2867 -0.4343 -0.8540 +vn 0.1711 -0.8016 -0.5728 +vn 0.2721 -0.4439 -0.8538 +vn 0.5402 -0.4996 0.6772 +vn 0.5900 -0.4393 0.6774 +vn 0.4083 -0.4027 0.8192 +vn 0.2649 0.9141 0.3071 +vn -0.0378 -0.9913 0.1263 +vn 0.0102 0.9909 0.1341 +vn 0.0031 0.9915 0.1297 +vn 0.0146 0.9681 0.2500 +vn 0.7352 0.6343 -0.2389 +vn 0.6167 0.7457 -0.2522 +vn 0.6945 0.6908 -0.2009 +vn 0.6222 -0.2277 0.7490 +vn 0.4878 -0.2779 0.8275 +vn 0.7378 -0.2537 0.6255 +vn -0.5438 0.8344 -0.0891 +vn -0.5322 0.8420 0.0884 +vn -0.4462 0.8829 -0.1464 +vn -0.2811 0.9596 0.0136 +vn -0.0688 0.9270 -0.3687 +vn 0.0753 0.9886 -0.1305 +vn 0.0636 0.8823 -0.4664 +vn 0.2184 -0.2299 -0.9484 +vn 0.1591 -0.2728 -0.9488 +vn -0.0067 -0.2678 -0.9634 +vn -0.7460 -0.5424 0.3863 +vn -0.8176 -0.4694 0.3334 +vn -0.6799 -0.7027 0.2093 +vn 0.0284 0.8946 0.4460 +vn -0.9887 0.1182 -0.0926 +vn 0.7391 0.6735 -0.0118 +vn 0.7154 0.5764 -0.3950 +vn 0.6073 0.6945 -0.3859 +vn 0.2562 0.6365 -0.7275 +vn 0.2933 0.3331 -0.8961 +vn 0.2754 0.4163 -0.8665 +vn 0.2418 0.2544 -0.9364 +vn 0.1875 0.2845 -0.9402 +vn 0.3194 0.9412 0.1098 +vn 0.2746 0.8780 0.3920 +vn 0.4645 0.8359 0.2923 +vn 0.1212 0.8514 -0.5103 +vn 0.1220 0.8958 -0.4273 +vn 0.1063 0.8906 -0.4422 +vn 0.8953 0.2634 -0.3592 +vn 0.8210 0.1497 -0.5510 +vn 0.7997 0.2080 -0.5633 +vn -0.8387 -0.1503 -0.5234 +vn -0.5690 -0.3427 -0.7475 +vn -0.6298 -0.3150 -0.7100 +vn 0.6576 -0.1588 -0.7364 +vn 0.8501 -0.1083 -0.5153 +vn 0.6777 0.6113 -0.4088 +vn 0.9481 0.2339 -0.2155 +vn 0.7273 0.4434 -0.5239 +vn 0.7063 0.7075 0.0231 +vn 0.7852 0.5827 -0.2096 +vn -0.2133 0.9679 -0.1326 +vn 0.0015 0.9869 -0.1613 +vn -0.9255 0.1885 0.3286 +vn -0.7549 0.5386 0.3742 +vn -0.9644 0.2628 -0.0294 +vn -0.1060 0.9236 0.3685 +vn 0.0753 0.9886 0.1305 +vn 0.5492 0.7472 -0.3743 +vn 0.3131 0.7873 -0.5312 +vn -0.1042 -0.3781 0.9199 +vn 0.2229 -0.3266 0.9185 +vn -0.0164 -0.3812 0.9243 +vn 0.9831 0.0139 -0.1827 +vn 0.8168 0.5696 -0.0914 +vn 0.8341 0.5429 0.0978 +vn 0.1724 0.8391 -0.5159 +vn 0.2987 0.5895 -0.7505 +vn 0.1725 0.8391 -0.5159 +vn 0.8533 -0.3372 -0.3977 +vn 0.6176 -0.2154 -0.7564 +vn 0.8547 -0.3218 -0.4073 +vn -0.7728 -0.5995 -0.2083 +vn -0.6946 -0.6932 0.1924 +vn -0.7592 -0.6502 0.0295 +vn -0.2056 -0.9646 0.1653 +vn -0.4595 -0.8880 0.0182 +vn -0.6587 -0.7507 -0.0501 +vn 0.3195 0.9474 0.0210 +vn -0.0341 0.9687 0.2458 +vn -0.9854 0.1260 0.1143 +vn -0.9643 0.2451 0.1005 +vn 0.9408 0.1514 -0.3033 +vn 0.9485 0.1889 -0.2541 +vn 0.9680 0.1886 -0.1654 +vn 0.1464 0.1195 0.9820 +vn 0.9055 0.4210 0.0527 +vn 0.9103 0.4079 0.0709 +vn 0.9371 0.3484 0.0221 +vn 0.2523 -0.1341 0.9583 +vn 0.5450 -0.1497 0.8249 +vn 0.3671 0.6825 -0.6320 +vn 0.1747 0.7161 -0.6758 +vn 0.1959 0.8041 -0.5612 +vn -0.9571 0.2788 0.0786 +vn -0.4751 0.8710 0.1252 +vn -0.5905 0.7249 0.3547 +vn 0.8338 -0.3471 0.4293 +vn -0.7770 0.1832 0.6023 +vn -0.7770 0.1832 0.6022 +vn 0.2933 0.3331 0.8961 +vn -0.0326 0.8764 0.4804 +vn -0.2392 0.9608 0.1402 +vn -0.3368 0.8947 0.2933 +vn 0.5955 0.6397 0.4860 +vn 0.5601 0.7547 0.3416 +vn 0.2701 0.8226 0.5005 +vn 0.6259 0.5950 0.5041 +vn 0.2701 0.8226 0.5004 +vn 0.7770 -0.1832 0.6023 +vn 0.0329 0.9879 0.1517 +vn 0.0222 0.9893 0.1442 +vn 0.5251 0.7195 -0.4544 +vn 0.2788 0.6959 -0.6618 +vn 0.0580 0.8284 -0.5571 +vn 0.8629 -0.4213 -0.2791 +vn 0.4992 -0.5624 -0.6592 +vn 0.6958 -0.2893 -0.6573 +vn 0.4690 0.6890 0.5526 +vn 0.4359 0.7749 0.4577 +vn 0.9437 0.0111 -0.3307 +vn 0.8890 0.3106 -0.3365 +vn -0.8099 0.3754 0.4507 +vn -0.8614 0.0025 0.5080 +vn -0.7196 0.1587 0.6760 +vn 0.0433 -0.3896 0.9200 +vn 0.4701 0.7150 -0.5174 +vn 0.6418 0.5684 -0.5148 +vn -0.0777 0.7520 0.6546 +vn -0.4218 0.6351 0.6471 +vn -0.2261 0.6027 0.7653 +vn 0.6283 0.7756 0.0608 +vn 0.7804 0.6159 0.1079 +vn 0.7767 0.6073 -0.1674 +vn 0.1047 0.8031 -0.5865 +vn 0.5839 0.4283 -0.6896 +vn 0.1304 0.9828 0.1307 +vn 0.1304 0.9828 0.1308 +vn 0.3034 -0.7734 0.5565 +vn 0.5481 -0.7401 0.3897 +vn -0.4219 0.8170 0.3931 +vn 0.3066 0.2214 0.9257 +vn 0.3103 0.6259 0.7155 +vn 0.0121 0.5851 0.8109 +vn -0.5510 0.4087 -0.7276 +vn -0.5363 0.3123 -0.7841 +vn -0.8072 0.2121 -0.5508 +vn -0.0263 0.7629 -0.6460 +vn 0.0137 0.5879 -0.8088 +vn -0.2146 0.5962 -0.7736 +vn 0.3464 0.1694 0.9227 +vn 0.0657 0.1111 0.9916 +vn 0.1848 -0.1392 0.9729 +vn -0.5687 -0.5973 -0.5655 +vn -0.2061 -0.6337 -0.7456 +vn -0.0452 0.1975 -0.9793 +vn 0.1732 0.5937 -0.7858 +vn 0.3021 0.5692 -0.7647 +vn 0.9725 0.2316 0.0250 +vn 0.9666 0.2494 -0.0596 +vn 0.2587 0.1146 -0.9591 +vn 0.2696 0.0526 -0.9615 +vn 0.2153 0.0785 -0.9734 +vn 0.2243 -0.8898 0.3974 +vn 0.9016 -0.1287 -0.4130 +vn 0.8358 -0.0291 -0.5483 +vn -0.0753 -0.9886 -0.1305 +vn 0.3910 0.6651 -0.6362 +vn 0.5341 0.6213 -0.5733 +vn 0.5962 0.6804 0.4262 +vn 0.6888 0.6514 0.3183 +vn 0.3259 0.9343 0.1446 +vn 0.3194 0.0664 -0.9453 +vn 0.3210 0.2722 -0.9071 +vn 0.3625 0.1972 -0.9109 +vn 0.9765 0.1845 -0.1111 +vn -0.1978 -0.5366 0.8203 +vn -0.5504 -0.6417 0.5342 +vn -0.2724 -0.5922 0.7584 +vn -0.1304 -0.9828 -0.1307 +vn 0.2249 0.6206 -0.7512 +vn 0.4692 0.4441 -0.7633 +vn -0.2528 0.1971 -0.9472 +vn -0.5945 0.0701 -0.8011 +vn -0.2993 -0.5844 -0.7542 +vn -0.8316 -0.3417 -0.4378 +vn -0.5504 -0.6417 -0.5342 +vn 0.7440 0.6387 -0.1961 +vn 0.1099 0.8343 -0.5403 +vn 0.1173 0.8461 -0.5200 +vn -0.9776 0.1544 -0.1429 +vn 0.2097 0.1702 0.9628 +vn -0.0117 0.3772 0.9261 +vn -0.0452 0.1975 0.9793 +vn -0.3248 -0.7705 -0.5486 +vn -0.0131 -0.7899 -0.6131 +vn 0.0392 -0.8237 -0.5657 +vn 0.6507 -0.7573 -0.0558 +vn 0.3651 -0.9259 -0.0964 +vn 0.0284 0.8946 -0.4460 +vn 0.3518 0.7330 -0.5822 +vn 0.2170 0.6836 -0.6968 +vn 0.7770 -0.1832 -0.6023 +vn -0.9403 -0.0233 -0.3396 +vn -0.2564 0.5624 0.7861 +vn -0.1039 0.4550 -0.8844 +vn 0.0580 0.8284 0.5571 +vn 0.9373 -0.1148 -0.3290 +vn -0.0580 -0.8284 -0.5571 +vn -0.6070 0.7817 0.1430 +vn -0.6207 0.7831 0.0389 +vn -0.7620 0.6397 -0.1009 +vn -0.7570 0.6465 0.0949 +vn 0.1465 0.1195 0.9820 +vn -0.7664 0.4600 0.4484 +vn -0.8879 0.3695 0.2740 +vn -0.9456 0.3086 0.1030 +vn -0.2172 0.9218 -0.3211 +vn -0.1290 0.9320 -0.3387 +vn -0.3800 0.8342 -0.3996 +vn -0.7503 0.6208 0.2271 +vn -0.8202 0.5440 -0.1768 +vn -0.6695 -0.7185 -0.1886 +vn -0.7227 -0.6908 -0.0247 +vn -0.6884 -0.6909 -0.2208 +vn 0.8087 0.5432 -0.2258 +vn 0.7736 0.6037 -0.1925 +vn 0.7928 0.5810 -0.1841 +vn -0.6710 0.6674 0.3229 +vn -0.5751 0.7709 0.2737 +vn -0.6025 0.7702 0.2093 +vn 0.2140 0.5402 0.8139 +vn 0.4446 0.4788 0.7571 +vn 0.8914 0.4446 -0.0880 +vn -0.9017 0.1730 0.3962 +vn -0.7231 0.1975 0.6619 +vn -0.9741 0.1574 0.1623 +vn 0.9293 0.0116 -0.3692 +vn 0.0338 0.0528 0.9980 +vn -0.2296 -0.0826 0.9698 +vn 0.2684 -0.7800 0.5653 +vn 0.7507 0.2656 -0.6049 +vn 0.7473 0.4445 -0.4939 +vn 0.9022 0.3294 -0.2783 +vn 0.7767 0.4104 -0.4779 +vn -0.7323 0.1371 -0.6670 +vn -0.7814 0.1398 -0.6082 +vn -0.4761 0.1499 -0.8665 +vn -0.0043 0.4571 -0.8894 +vn -0.5200 0.6278 -0.5793 +vn -0.7229 0.2406 -0.6477 +vn 0.9319 -0.3540 -0.0788 +vn 0.4843 0.8151 -0.3181 +vn 0.6418 0.7649 -0.0550 +vn 0.6888 0.6514 -0.3183 +vn -0.2103 0.1364 -0.9681 +vn -0.4046 0.1313 -0.9050 +vn -0.4819 0.1379 -0.8653 +vn 0.3216 0.8950 0.3091 +vn 0.6039 0.7858 0.1337 +vn 0.3397 0.9343 0.1085 +vn -0.7085 -0.4227 0.5651 +vn -0.6735 -0.4710 0.5697 +vn -0.8130 0.0827 -0.5763 +vn 0.4348 0.1089 -0.8939 +vn 0.3646 0.1016 -0.9256 +vn 0.1458 0.1185 0.9822 +vn -0.2525 0.1455 0.9566 +vn 0.8260 0.3092 -0.4713 +vn 0.6941 0.2235 -0.6843 +vn -0.5438 0.8344 0.0891 +vn 0.3735 0.8785 -0.2980 +vn -0.5496 0.8216 -0.1515 +vn -0.7341 0.4884 -0.4718 +vn -0.6567 0.7382 -0.1541 +vn 0.8153 0.3683 0.4468 +vn 0.6192 0.3666 0.6944 +vn 0.5342 0.1166 0.8373 +vn 0.9432 0.3287 0.0475 +vn 0.9518 0.0530 -0.3020 +vn -0.2268 -0.9401 0.2546 +vn -0.4604 -0.8867 0.0438 +vn -0.2508 -0.9561 0.1515 +vn -0.4270 0.8860 0.1810 +vn -0.6281 0.7559 0.1848 +vn -0.5071 0.7063 0.4941 +vn 0.6958 -0.2893 0.6573 +vn 0.5000 0.2073 0.8409 +vn 0.4554 0.0751 0.8871 +vn -0.9762 0.0096 -0.2167 +vn -0.0724 0.9343 -0.3492 +vn -0.0511 0.9741 -0.2203 +vn 0.1178 0.9031 -0.4129 +vn 0.1755 0.5935 0.7854 +vn 0.4507 0.4839 -0.7501 +vn 0.3712 0.5005 -0.7821 +vn 0.2149 0.5387 -0.8146 +vn -0.1303 -0.9828 -0.1307 +vn -0.4726 0.7435 -0.4731 +vn -0.6224 0.6906 -0.3683 +vn -0.4337 0.8841 -0.1740 +vn -0.7410 0.2812 0.6097 +vn -0.6140 0.2281 0.7556 +vn -0.4295 0.1154 -0.8957 +vn -0.7075 -0.1199 -0.6964 +vn -0.9272 0.0213 -0.3740 +vn -0.4083 0.9119 0.0408 +vn -0.2703 0.8555 0.4416 +vn 0.8890 0.3106 0.3365 +vn 0.3957 0.6849 -0.6118 +vn 0.5416 0.5766 -0.6118 +vn 0.3422 0.6541 -0.6746 +vn 0.8530 0.1169 -0.5087 +vn 0.7675 0.5356 -0.3523 +vn 0.6880 0.5886 -0.4245 +vn 0.6824 0.6348 -0.3625 +vn 0.6497 0.0200 -0.7599 +vn -0.6563 -0.7541 0.0235 +vn -0.7170 -0.6942 0.0639 +vn -0.5972 -0.7713 -0.2203 +vn 0.7814 -0.1398 -0.6082 +vn 0.4977 0.4935 -0.7133 +vn 0.4349 0.3484 -0.8304 +vn 0.3157 0.8045 -0.5031 +vn 0.3764 0.7989 -0.4691 +vn 0.3243 0.7837 -0.5297 +vn 0.2170 0.6836 0.6968 +vn 0.9036 0.4219 -0.0744 +vn 0.8592 0.4880 -0.1535 +vn 0.8966 0.4428 -0.0003 +vn 0.8921 0.4514 -0.0200 +vn -0.6229 -0.0529 -0.7805 +vn -0.4277 -0.1615 -0.8894 +vn 0.1813 0.9642 -0.1937 +vn -0.1913 0.9744 -0.1185 +vn -0.2727 0.4685 -0.8403 +vn -0.2564 0.3508 -0.9007 +vn 0.9117 -0.0153 -0.4107 +vn 0.6532 0.0550 -0.7552 +vn -0.3077 0.9299 -0.2015 +vn 0.3146 0.8583 -0.4054 +vn 0.2224 0.9222 -0.3165 +vn -0.9485 0.0905 -0.3037 +vn -0.9762 0.1042 -0.1901 +vn 0.2148 0.8711 -0.4417 +vn 0.2243 0.8509 -0.4750 +vn 0.2244 0.8477 -0.4806 +vn -0.5070 0.7151 0.4812 +vn -0.6651 0.6707 0.3285 +vn -0.6524 0.5634 0.5069 +vn -0.9525 0.0564 -0.2994 +vn -0.8772 -0.2779 -0.3915 +vn -0.6619 -0.2580 -0.7038 +vn -0.3147 0.6844 -0.6577 +vn -0.5800 0.6435 -0.4995 +vn -0.3200 0.7575 -0.5690 +vn 0.9440 -0.1777 0.2781 +vn 0.9227 -0.3854 0.0020 +vn 0.9538 -0.2860 0.0921 +vn -0.7022 0.0032 0.7120 +vn -0.6764 -0.0083 0.7365 +vn -0.3405 -0.0827 0.9366 +vn 0.1831 0.1117 0.9767 +vn -0.0177 0.1943 0.9808 +vn -0.2528 0.1971 0.9472 +vn -0.3345 -0.1191 0.9349 +vn -0.1962 -0.1188 0.9733 +vn 0.7273 0.4434 0.5239 +vn 0.5866 0.3786 0.7159 +vn 0.3957 0.6849 0.6118 +vn 0.1006 0.9838 0.1484 +vn 0.9748 0.0796 0.2082 +vn -0.9219 0.0716 -0.3809 +vn -0.9272 0.0213 0.3740 +vn -0.7047 -0.3612 0.6106 +vn 0.3167 0.7661 -0.5593 +vn 0.2130 0.9741 0.0756 +vn 0.2142 0.9430 0.2548 +vn 0.2564 -0.5624 -0.7861 +vn 0.2528 0.1703 0.9524 +vn -0.8316 -0.3417 0.4378 +vn -0.7250 -0.4082 0.5548 +vn -0.9078 -0.2175 0.3587 +vn -0.3977 0.9173 -0.0180 +vn -0.1122 0.7924 0.5996 +vn -0.3826 0.5014 0.7761 +vn -0.2107 -0.1853 -0.9598 +vn -0.3877 -0.1980 -0.9003 +vn -0.1779 -0.1254 -0.9760 +vn -0.0875 0.8949 0.4377 +vn 0.1332 0.8853 0.4455 +vn -0.9450 0.1150 -0.3063 +vn 0.0583 0.9904 0.1251 +vn 0.0586 0.9897 0.1309 +vn 0.0572 0.9902 0.1273 +vn -0.9818 0.0507 -0.1828 +vn -0.9798 0.0977 0.1747 +vn -0.9798 0.0977 0.1746 +vn 0.3046 0.0414 -0.9516 +vn -0.9836 0.1741 0.0461 +vn -0.9617 0.2581 -0.0919 +vn -0.9429 0.2922 -0.1601 +vn -0.3048 -0.0970 -0.9475 +vn 0.0143 -0.1314 -0.9912 +vn -0.3022 -0.1021 -0.9478 +vn -0.1996 0.9798 -0.0110 +vn -0.2248 0.7912 -0.5688 +vn 0.0678 0.9886 0.1346 +vn 0.0612 0.9892 0.1330 +vn 0.7828 -0.1079 0.6128 +vn 0.0712 0.8927 -0.4450 +vn 0.1347 0.9314 -0.3383 +vn 0.1131 0.8916 -0.4384 +vn -0.5436 0.8299 -0.1257 +vn 0.2649 0.9141 -0.3071 +vn 0.2701 0.8225 0.5005 +vn 0.1019 0.9528 0.2860 +vn -0.6561 0.2562 -0.7098 +vn -0.8099 0.1403 -0.5695 +vn -0.4831 0.5122 -0.7101 +vn -0.2555 0.5571 -0.7902 +vn -0.1816 0.5575 -0.8101 +vn 0.3143 0.8117 -0.4923 +vn 0.3156 0.8158 -0.4846 +vn 0.1053 0.1174 0.9875 +vn -0.2463 0.1663 0.9548 +vn -0.1732 0.1524 0.9730 +vn 0.2452 0.8236 -0.5115 +vn -0.1330 0.9547 -0.2661 +vn 0.0461 0.9904 0.1303 +vn -0.9475 0.3196 0.0040 +vn -0.9615 0.2578 -0.0952 +vn -0.9093 0.3891 0.1477 +vn -0.1472 0.7702 -0.6206 +vn 0.2142 0.9430 -0.2548 +vn -0.7022 0.0032 -0.7120 +vn -0.8894 0.0582 -0.4534 +vn -0.4420 0.7685 -0.4627 +vn -0.4751 0.8710 -0.1252 +vn -0.3478 0.9060 -0.2412 +vn -0.4219 0.8170 -0.3931 +vn -0.2284 -0.1821 0.9564 +vn 0.7311 0.6305 -0.2608 +vn -0.5690 -0.3427 0.7475 +vn -0.1301 -0.4998 0.8563 +vn -0.6275 -0.3039 0.7169 +vn -0.1458 -0.1185 -0.9822 +vn -0.1369 0.7736 0.6187 +vn -0.4478 0.8890 0.0958 +vn -0.3024 0.8684 0.3929 +vn -0.8240 -0.0857 0.5601 +vn 0.9219 -0.0716 0.3809 +vn 0.0597 -0.7151 -0.6964 +vn 0.3187 -0.6471 -0.6925 +vn 0.1698 -0.8722 -0.4587 +vn 0.6604 0.3253 0.6768 +vn 0.5223 0.4119 0.7467 +vn 0.2180 0.5035 0.8360 +vn -0.3826 0.5014 -0.7761 +vn -0.4373 0.1490 -0.8869 +vn -0.6344 0.4405 -0.6353 +vn 0.3686 -0.0001 -0.9296 +vn 0.3286 -0.5634 -0.7580 +vn 0.2936 -0.5654 -0.7708 +vn -0.1262 -0.4896 -0.8628 +vn 0.2518 0.9421 -0.2215 +vn 0.0750 0.9941 0.0786 +vn 0.7161 -0.5154 -0.4707 +vn 0.5998 -0.5499 -0.5812 +vn 0.1398 -0.3001 0.9436 +vn -0.0883 -0.4220 0.9023 +vn 0.1115 -0.5387 0.8351 +vn -0.1842 -0.0213 0.9827 +vn 0.1021 0.1117 0.9885 +vn 0.0480 0.1270 0.9907 +vn 0.9647 -0.1900 -0.1821 +vn -0.1043 0.9136 -0.3930 +vn -0.1645 0.8274 -0.5369 +vn -0.0052 0.7528 -0.6583 +vn 0.0679 0.7986 -0.5980 +vn -0.9429 0.2922 0.1601 +vn -0.8047 0.4244 0.4151 +vn -0.9617 0.2581 0.0919 +vn 0.5917 0.7941 -0.1392 +vn 0.6208 0.7568 -0.2047 +vn 0.5369 0.8289 -0.1570 +vn 0.9018 0.3395 0.2673 +vn -0.2954 0.5863 -0.7543 +vn 0.2733 -0.2476 0.9295 +vn 0.1464 0.1195 -0.9820 +vn 0.1465 0.1195 -0.9820 +vn 0.0666 -0.9968 -0.0449 +vn 0.2003 -0.9793 0.0286 +vn 0.4324 -0.8953 0.1075 +vn -0.8171 0.3401 -0.4655 +vn 0.6669 0.0059 -0.7452 +vn 0.8350 -0.0868 -0.5434 +vn 0.8889 -0.4076 -0.2092 +vn 0.6941 0.2235 0.6843 +vn 0.8260 0.3092 0.4713 +vn 0.7002 -0.5319 0.4763 +vn 0.8644 -0.4777 0.1570 +vn -0.6229 0.7707 -0.1340 +vn -0.6825 0.7299 -0.0372 +vn -0.3478 0.9060 0.2412 +vn -0.9985 0.0533 -0.0105 +vn -0.9171 0.1310 0.3765 +vn -0.9462 0.1312 0.2956 +vn -0.7594 0.5048 -0.4105 +vn -0.9093 0.3891 -0.1477 +vn -0.9475 0.3196 -0.0040 +vn 0.3528 0.4414 0.8250 +vn -0.6151 0.4957 -0.6131 +vn -0.8456 0.3969 -0.3568 +vn -0.7288 0.4584 -0.5086 +vn 0.8299 0.3707 -0.4170 +vn 0.5382 0.6150 -0.5763 +vn 0.4167 0.8842 0.2110 +vn 0.6781 0.6099 0.4102 +vn 0.3136 0.8366 -0.4491 +vn 0.2760 0.8500 -0.4487 +vn 0.2549 -0.1556 -0.9544 +vn 0.0144 -0.1332 -0.9910 +vn -0.3027 -0.0814 -0.9496 +vn 0.3805 -0.9245 0.0228 +vn 0.4185 -0.9075 -0.0370 +vn 0.5102 -0.8541 0.1008 +vn 0.1086 0.9868 0.1201 +vn -0.1089 0.9744 0.1965 +vn 0.1085 0.9862 0.1251 +vn 0.2527 0.6989 -0.6691 +vn 0.3345 0.6893 -0.6426 +vn 0.6755 0.2085 0.7072 +vn 0.0987 0.5505 -0.8290 +vn 0.7828 -0.1079 -0.6128 +vn -0.1943 0.9310 -0.3089 +vn -0.2974 0.7063 -0.6425 +vn -0.4103 0.7416 -0.5307 +vn 0.2916 0.7059 0.6455 +vn 0.1491 0.6095 0.7786 +vn -0.9192 0.3119 -0.2404 +vn -0.8638 -0.0078 -0.5037 +vn 0.7626 0.2802 0.5831 +vn 0.3674 -0.1313 -0.9207 +vn 0.2560 -0.1267 -0.9583 +vn 0.7023 -0.1163 -0.7023 +vn -0.0091 0.9475 -0.3196 +vn 0.4700 -0.7183 0.5130 +vn 0.2128 -0.8725 0.4398 +vn 0.4644 -0.8172 0.3414 +vn -0.5638 0.4961 -0.6603 +vn 0.3887 0.7380 0.5516 +vn 0.2677 0.4314 0.8615 +vn 0.2144 0.3961 0.8928 +vn -0.3381 -0.0799 -0.9377 +vn -0.8176 -0.4694 -0.3334 +vn -0.7365 -0.4344 -0.5185 +vn -0.7632 -0.5136 -0.3922 +vn 0.3507 0.9351 0.0518 +vn 0.3817 -0.1638 0.9096 +vn -0.8223 0.4025 -0.4022 +vn -0.6504 0.5017 -0.5703 +vn -0.7832 0.4287 -0.4503 +vn 0.1725 0.8391 0.5159 +vn -0.5149 -0.2278 -0.8265 +vn -0.5019 -0.1799 -0.8460 +vn -0.2609 -0.1979 -0.9449 +vn -0.3945 -0.2708 0.8781 +vn -0.5767 -0.2446 0.7795 +vn -0.5350 -0.3207 0.7816 +vn 0.9749 -0.1648 -0.1495 +vn 0.9268 -0.2520 -0.2786 +vn 0.7872 -0.3759 -0.4888 +vn 0.1834 0.9535 0.2392 +vn -0.0790 0.9850 0.1533 +vn 0.7368 0.0330 -0.6753 +vn 0.5208 0.0731 -0.8505 +vn 0.1931 -0.8489 -0.4921 +vn 0.0032 -0.8353 -0.5498 +vn -0.0394 -0.7917 -0.6096 +vn 0.1557 0.4437 -0.8826 +vn 0.1209 0.9588 0.2570 +vn 0.9295 0.2177 -0.2976 +vn -0.2568 0.9444 0.2052 +vn -0.2597 0.9404 0.2196 +vn -0.1162 0.9387 0.3247 +vn -0.9825 0.1495 -0.1110 +vn 0.1544 0.8933 -0.4221 +vn 0.0450 0.9729 0.2270 +vn 0.0270 0.9722 0.2325 +vn -0.0274 0.9986 0.0461 +vn 0.2285 0.8374 -0.4965 +vn 0.2406 0.8298 -0.5035 +vn -0.3048 -0.0968 0.9475 +vn -0.4145 -0.0880 0.9058 +vn -0.1457 -0.1180 0.9823 +vn 0.1657 0.9848 0.0519 +vn 0.1639 0.9821 0.0927 +vn 0.1900 0.9788 0.0761 +vn -0.9086 0.4176 -0.0061 +vn -0.7905 0.6124 -0.0099 +vn 0.4699 0.7152 0.5174 +vn 0.4147 0.4175 0.8085 +vn 0.7087 0.3082 0.6346 +vn 0.2272 0.6770 -0.7000 +vn -0.5185 0.8533 -0.0550 +vn 0.5258 0.5887 -0.6140 +vn -0.9192 0.0592 -0.3894 +vn -0.7770 -0.1213 -0.6177 +vn -0.6208 -0.2585 -0.7401 +vn -0.5681 0.0691 -0.8200 +vn -0.4408 0.1305 -0.8881 +vn 0.2373 0.9423 0.2360 +vn 0.1714 0.9764 0.1318 +vn 0.1658 0.9762 0.1397 +vn 0.7653 0.6427 0.0357 +vn 0.7823 0.6229 -0.0016 +vn 0.1344 0.9656 0.2228 +vn 0.0764 0.9599 0.2699 +vn -0.5606 -0.6868 0.4626 +vn -0.7173 -0.6767 0.1657 +vn 0.3364 -0.5385 0.7725 +vn 0.6141 -0.5007 0.6101 +vn 0.7326 -0.4556 0.5057 +vn 0.5788 0.1990 -0.7908 +vn 0.6078 -0.7917 -0.0613 +vn 0.8228 0.5605 0.0945 +vn -0.4586 0.5446 0.7022 +vn -0.3264 0.4178 0.8479 +vn 0.5591 0.7839 0.2702 +vn -0.5070 0.7151 -0.4812 +vn -0.6651 0.6707 -0.3285 +vn -0.4780 0.8095 -0.3408 +vn -0.1015 -0.9818 -0.1605 +vn -0.1078 -0.9753 -0.1927 +vn 0.1755 -0.9842 -0.0213 +vn -0.1239 0.2982 0.9464 +vn -0.3784 0.4856 0.7880 +vn 0.8411 -0.0705 0.5363 +vn 0.3176 -0.2036 0.9261 +vn 0.1816 -0.5575 0.8101 +vn 0.3743 -0.5354 0.7572 +vn 0.4095 -0.5260 0.7454 +vn -0.2319 0.8763 -0.4222 +vn -0.3392 0.8880 -0.3105 +vn 0.1181 -0.9656 0.2315 +vn 0.3696 -0.8682 0.3312 +vn -0.6521 -0.0706 0.7549 +vn -0.3412 -0.1060 0.9340 +vn -0.3773 -0.0915 0.9216 +vn 0.9546 0.2164 -0.2047 +vn -0.9994 0.0251 -0.0240 +vn -0.1503 0.5643 -0.8118 +vn 0.0361 0.5420 -0.8396 +vn 0.8866 0.2304 -0.4011 +vn 0.5842 0.4309 0.6878 +vn 0.6244 0.3453 0.7006 +vn 0.7543 0.4022 0.5189 +vn -0.9245 -0.2400 0.2962 +vn -0.9938 0.0062 0.1108 +vn 0.1332 0.8853 -0.4455 +vn -0.2147 -0.2609 -0.9412 +vn -0.0360 -0.3411 -0.9393 +vn -0.4369 0.5679 -0.6976 +vn -0.7382 0.5106 -0.4408 +vn 0.9117 -0.0153 0.4107 +vn 0.9740 -0.0449 0.2219 +vn 0.0006 0.8582 0.5133 +vn 0.0095 0.7218 -0.6920 +vn 0.2253 0.8422 -0.4898 +vn 0.2207 0.8361 -0.5023 +vn -0.5870 0.5724 -0.5725 +vn -0.8442 0.4147 -0.3396 +vn 0.0578 0.9912 0.1192 +vn -0.0441 0.9749 0.2181 +vn -0.0941 0.9723 0.2141 +vn -0.9192 0.3119 0.2404 +vn -0.8638 -0.0078 0.5037 +vn 0.1405 0.8582 0.4938 +vn -0.0454 0.9296 0.3657 +vn -0.0548 0.7608 0.6467 +vn -0.5780 0.7807 0.2378 +vn -0.3564 0.9004 0.2496 +vn 0.4578 0.0544 -0.8874 +vn -0.4760 0.5490 0.6870 +vn -0.3346 0.4585 0.8233 +vn -0.4135 0.6258 0.6613 +vn 0.4015 0.5567 -0.7273 +vn 0.5842 0.4309 -0.6878 +vn 0.6244 0.3453 -0.7006 +vn 0.1364 0.9742 0.1797 +vn 0.1670 0.9634 0.2097 +vn -0.2630 0.5440 -0.7968 +vn 0.8272 0.1055 0.5519 +vn 0.9683 -0.1467 0.2021 +vn 0.9481 0.2340 0.2155 +vn 0.0393 0.8456 -0.5323 +vn 0.0423 0.8408 -0.5397 +vn -0.0590 0.9463 0.3179 +vn -0.0148 0.9534 0.3013 +vn 0.1901 0.8894 -0.4156 +vn -0.0242 0.8852 -0.4646 +vn 0.0230 -0.9728 -0.2304 +vn 0.1053 0.9689 0.2240 +vn -0.7828 -0.5873 -0.2056 +vn -0.6048 -0.5645 -0.5618 +vn 0.7543 0.4022 -0.5189 +vn -0.5515 -0.6043 -0.5750 +vn -0.2764 -0.5056 -0.8173 +vn -0.5656 -0.6283 -0.5342 +vn 0.8358 0.0593 -0.5459 +vn 0.9591 -0.2046 -0.1958 +vn 0.6529 0.7416 -0.1543 +vn 0.8341 0.5429 -0.0977 +vn 0.0477 0.7522 0.6572 +vn 0.8272 0.1055 -0.5519 +vn 0.4014 -0.9108 0.0962 +vn 0.5268 -0.7773 -0.3440 +vn 0.6787 -0.7327 0.0490 +vn -0.7387 -0.6740 0.0019 +vn -0.6865 -0.7090 -0.1614 +vn -0.6950 -0.7063 0.1349 +vn -0.5262 -0.3282 -0.7845 +vn -0.3945 -0.2708 -0.8781 +vn -0.1506 -0.2854 -0.9465 +vn 0.0992 -0.5521 0.8279 +vn -0.2388 -0.4749 0.8470 +vn -0.2341 -0.4824 0.8441 +vn 0.7168 0.6761 -0.1705 +vn 0.7300 0.6524 -0.2036 +vn -0.2268 -0.5953 0.7708 +vn -0.2061 -0.6337 0.7456 +vn 0.0597 -0.7151 0.6964 +vn 0.0529 -0.3836 -0.9220 +vn 0.7325 -0.0066 -0.6807 +vn -0.3203 0.8150 -0.4829 +vn -0.7770 0.1832 -0.6023 +vn -0.7770 0.1832 -0.6022 +vn 0.9219 -0.0716 -0.3809 +vn -0.6171 0.5743 -0.5380 +vn -0.7283 0.4936 -0.4753 +vn 0.9863 0.1633 -0.0253 +vn 0.9850 0.1635 -0.0553 +vn 0.1304 0.9828 -0.1308 +vn 0.1304 0.9828 -0.1307 +vn 0.6330 0.7540 -0.1755 +vn 0.1232 -0.3127 -0.9418 +vn -0.2310 -0.0578 -0.9712 +vn 0.6906 0.2705 -0.6708 +vn 0.1724 0.8391 0.5159 +vn 0.0879 0.6670 0.7399 +vn 0.4178 0.6158 0.6680 +vn 0.6066 0.2481 -0.7553 +vn -0.6286 -0.3229 -0.7075 +vn -0.5561 -0.2390 -0.7960 +vn -0.9150 0.0787 -0.3956 +vn -0.8758 0.3600 -0.3216 +vn -0.6524 0.5634 -0.5069 +vn -0.4103 0.7416 0.5307 +vn -0.5496 0.6278 0.5512 +vn -0.8833 0.4602 0.0892 +vn -0.7892 0.5954 0.1503 +vn 0.8859 0.4227 -0.1912 +vn 0.8293 0.4807 -0.2850 +vn 0.0471 0.9863 0.1579 +vn 0.0791 0.5683 -0.8190 +vn 0.9359 0.3129 -0.1620 +vn 0.8869 0.3798 -0.2629 +vn 0.7899 0.4754 -0.3875 +vn 0.7114 0.5099 -0.4835 +vn 0.1459 0.8342 -0.5317 +vn 0.1474 0.8219 -0.5503 +vn 0.1612 0.9060 -0.3914 +vn 0.3870 0.5010 -0.7741 +vn -0.9647 0.0391 0.2606 +vn -0.9798 0.0977 -0.1746 +vn -0.9798 0.0977 -0.1747 +vn -0.0129 0.9870 0.1602 +vn 0.1969 0.9732 0.1191 +vn 0.2047 0.7836 -0.5865 +vn 0.2226 0.7714 -0.5962 +vn 0.1909 0.7240 -0.6628 +vn 0.3010 -0.5436 -0.7835 +vn 0.3364 -0.5385 -0.7725 +vn 0.6141 -0.5007 -0.6101 +vn -0.2388 -0.4749 -0.8470 +vn -0.0634 0.6863 0.7246 +vn -0.9687 0.0061 -0.2482 +vn -0.8686 0.1217 -0.4804 +vn 0.6481 -0.4555 -0.6103 +vn 0.4326 0.4060 0.8050 +vn 0.2469 0.4702 0.8473 +vn -0.6101 0.7738 0.1703 +vn -0.8797 0.3542 0.3173 +vn 0.5946 0.6867 -0.4181 +vn 0.6056 0.5549 -0.5704 +vn -0.7468 0.0379 -0.6640 +vn -0.8556 0.0084 -0.5176 +vn -0.8629 0.0278 -0.5046 +vn -0.0022 0.9766 0.2151 +vn -0.0293 0.1789 -0.9834 +vn -0.0514 0.3185 -0.9465 +vn 0.7739 0.5599 -0.2959 +vn -0.5751 0.7709 -0.2737 +vn -0.4671 0.8342 -0.2933 +vn -0.4801 0.7177 -0.5044 +vn 0.5776 -0.7699 0.2712 +vn 0.6150 -0.7633 0.1979 +vn 0.6028 -0.6955 0.3911 +vn 0.1698 -0.8722 0.4587 +vn 0.4403 -0.7329 0.5187 +vn 0.3187 -0.6471 0.6925 +vn -0.2362 0.2275 -0.9447 +vn 0.4860 -0.8081 -0.3327 +vn -0.2547 0.2240 0.9407 +vn -0.4231 0.1147 0.8988 +vn 0.3200 0.8197 -0.4751 +vn 0.3324 0.8280 -0.4515 +vn -0.4612 0.5199 0.7190 +vn 0.5769 0.1405 0.8046 +vn 0.1941 0.2362 0.9521 +vn -0.1236 0.3682 0.9215 +vn -0.1823 0.2705 0.9453 +vn 0.1081 0.9842 0.1404 +vn -0.2687 0.6795 0.6828 +vn 0.8881 -0.1104 -0.4461 +vn 0.8735 0.2265 -0.4309 +vn 0.8927 0.1671 -0.4185 +vn 0.8252 0.0625 -0.5614 +vn 0.8115 0.5660 -0.1453 +vn 0.8280 0.5523 -0.0968 +vn -0.6755 -0.2085 0.7072 +vn -0.9997 -0.0039 0.0225 +vn -0.9995 0.0034 0.0300 +vn 0.1816 -0.6616 -0.7275 +vn 0.0694 0.9962 0.0533 +vn 0.1946 0.9548 0.2246 +vn 0.3017 0.9216 0.2441 +vn 0.2235 0.9466 0.2325 +vn -0.0329 0.9779 0.2065 +vn -0.3622 0.7739 -0.5195 +vn 0.2558 0.4480 0.8566 +vn 0.0142 0.4567 0.8895 +vn -0.1749 0.5376 0.8249 +vn 0.0436 0.9771 0.2082 +vn 0.2461 0.5280 0.8128 +vn -0.1047 0.3585 0.9276 +vn -0.1301 -0.4998 -0.8563 +vn -0.2600 0.5513 -0.7928 +vn 0.6066 0.2481 0.7553 +vn 0.4801 0.0809 -0.8735 +vn -0.9664 0.0471 -0.2528 +vn -0.4528 0.2650 0.8513 +vn -0.0209 0.8899 -0.4557 +vn -0.0497 0.8187 -0.5721 +vn 0.0728 0.9585 -0.2757 +vn -0.2103 -0.2868 0.9346 +vn -0.4800 -0.1783 0.8590 +vn -0.4817 -0.2405 0.8427 +vn -0.0349 0.9994 -0.0032 +vn 0.6906 0.2705 0.6708 +vn 0.6906 0.2705 0.6707 +vn 0.8889 -0.4076 0.2092 +vn 0.7256 -0.1572 0.6700 +vn 0.7503 0.2437 0.6145 +vn 0.5694 0.0487 0.8206 +vn 0.4554 0.0751 -0.8871 +vn 0.5031 0.2018 -0.8403 +vn -0.2473 0.9654 0.0831 +vn 0.0014 0.9867 0.1623 +vn 0.1085 0.9854 0.1309 +vn 0.1085 0.9855 0.1304 +vn -0.9933 -0.0329 -0.1104 +vn -0.9969 -0.0427 -0.0655 +vn 0.8775 0.1071 0.4675 +vn 0.8644 -0.4777 -0.1570 +vn -0.0093 0.9925 0.1220 +vn -0.0067 0.9927 0.1205 +vn 0.2284 0.5497 0.8035 +vn 0.0361 0.5420 0.8396 +vn -0.5788 0.5874 -0.5657 +vn -0.6710 0.6674 -0.3229 +vn -0.6054 0.6628 -0.4406 +vn -0.8201 -0.0758 0.5672 +vn -0.6181 -0.2504 0.7451 +vn 0.8888 -0.0109 0.4582 +vn 0.7530 0.0175 0.6577 +vn 0.8839 -0.0553 0.4643 +vn -0.7620 0.6397 0.1009 +vn -0.2391 0.9304 -0.2779 +vn -0.3376 0.9354 -0.1054 +vn -0.8568 0.2790 -0.4336 +vn -0.6057 0.5469 -0.5780 +vn 0.1876 -0.6238 -0.7587 +vn 0.3803 -0.7450 -0.5480 +vn 0.4664 0.8781 -0.1067 +vn 0.4397 0.8715 0.2170 +vn 0.9831 0.0139 0.1827 +vn 0.8168 0.5696 0.0914 +vn 0.3341 0.9201 0.2045 +vn 0.2699 0.9461 0.1790 +vn 0.9064 -0.0647 0.4174 +vn 0.7325 -0.0066 0.6807 +vn 0.6775 0.0046 0.7355 +vn 0.3067 0.7909 -0.5295 +vn -0.1178 0.9839 -0.1342 +vn -0.5458 0.1269 0.8282 +vn -0.2123 0.1395 0.9672 +vn -0.7323 0.1185 0.6706 +vn 0.9018 0.3395 -0.2673 +vn 0.5652 0.7123 -0.4162 +vn 0.7804 0.6159 -0.1079 +vn 0.2339 0.8653 -0.4433 +vn -0.2864 0.9572 -0.0407 +vn 0.1469 0.9792 0.1397 +vn 0.1342 0.9815 0.1363 +vn -0.1566 -0.0442 0.9867 +vn -0.2044 0.0003 0.9789 +vn -0.1554 -0.0453 0.9868 +vn -0.0571 -0.6657 0.7440 +vn 0.1104 -0.6993 0.7063 +vn 0.1703 -0.6415 0.7479 +vn 0.9886 0.0352 0.1463 +vn 0.8533 -0.3372 0.3977 +vn 0.7326 -0.4556 -0.5057 +vn 0.1222 0.9687 0.2160 +vn -0.6567 0.7382 0.1541 +vn -0.5725 -0.7608 0.3058 +vn -0.6263 -0.7093 0.3236 +vn 0.9518 0.0530 0.3020 +vn 0.8854 0.1469 0.4410 +vn 0.1647 0.1380 -0.9766 +vn 0.1089 0.1730 -0.9789 +vn 0.6192 0.3666 -0.6944 +vn 0.1491 0.6095 -0.7786 +vn 0.2916 0.7059 -0.6455 +vn -0.6062 0.1059 -0.7882 +vn -0.9293 -0.0116 -0.3692 +vn 0.4005 0.8557 -0.3275 +vn 0.6042 0.7922 -0.0862 +vn 0.0125 0.9783 0.2070 +vn -0.8042 -0.0822 -0.5886 +vn -0.9245 -0.2400 -0.2962 +vn -0.7380 0.2750 -0.6162 +vn 0.1086 0.9861 0.1255 +vn -0.2489 0.1389 -0.9585 +vn -0.4601 0.8773 0.1367 +vn -0.2588 0.9659 0.0000 +vn 0.0630 0.9745 0.2153 +vn -0.1304 -0.9828 0.1307 +vn 0.2234 0.8639 -0.4514 +vn -0.2161 0.9687 -0.1224 +vn -0.2509 0.9680 -0.0037 +vn 0.6218 0.7534 -0.2140 +vn 0.6276 0.7583 -0.1764 +vn -0.4163 -0.6106 0.6737 +vn 0.8580 0.0302 -0.5127 +vn 0.4434 -0.8340 0.3284 +vn 0.4572 -0.8245 0.3334 +vn 0.1500 -0.8588 0.4899 +vn 0.0034 -0.4172 -0.9088 +vn -0.1694 -0.2008 -0.9649 +vn -0.9078 -0.2175 -0.3587 +vn -0.7250 -0.4082 -0.5548 +vn -0.9644 0.2628 0.0294 +vn -0.7503 0.6208 -0.2271 +vn -0.3526 -0.3992 0.8464 +vn -0.0507 -0.5069 0.8605 +vn -0.5962 -0.0420 0.8017 +vn 0.0750 -0.0075 0.9972 +vn -0.4601 0.8773 -0.1367 +vn -0.3368 0.8947 -0.2933 +vn 0.9275 0.3648 0.0816 +vn 0.8765 0.3487 0.3320 +vn 0.9437 0.3289 0.0355 +vn -0.9898 -0.0884 -0.1120 +vn -0.9558 0.2865 0.0654 +vn -0.8792 0.4694 0.0818 +vn -0.0485 0.6721 -0.7389 +vn -0.9762 0.0103 0.2168 +vn -0.8583 -0.0325 0.5121 +vn -0.8577 -0.0194 0.5137 +vn -0.9628 -0.2652 0.0517 +vn -0.8446 -0.1822 0.5035 +vn -0.7723 0.1198 0.6239 +vn 0.0006 0.8582 -0.5133 +vn -0.5851 0.6712 -0.4552 +vn -0.2547 0.2240 -0.9407 +vn -0.2521 0.3969 -0.8826 +vn -0.4989 0.8240 -0.2685 +vn -0.7149 0.4411 -0.5426 +vn 0.6687 0.7309 0.1364 +vn -0.8474 0.5137 -0.1340 +vn 0.7739 0.5599 0.2959 +vn -0.5264 0.2156 -0.8224 +vn 0.0113 0.9711 0.2383 +vn 0.3010 -0.5436 0.7835 +vn 0.0407 0.8083 -0.5874 +vn 0.9432 0.3287 -0.0475 +vn 0.7212 0.5195 -0.4583 +vn -0.3254 0.8416 0.4310 +vn -0.1847 0.8966 0.4024 +vn -0.7913 0.3902 0.4708 +vn -0.9871 0.0559 -0.1498 +vn -0.5647 -0.8186 -0.1048 +vn -0.0725 -0.1969 0.9777 +vn -0.5626 0.8128 0.1511 +vn -0.0491 -0.0221 0.9985 +vn -0.4371 -0.3253 -0.8385 +vn -0.6604 -0.2146 -0.7196 +vn -0.0857 0.0925 0.9920 +vn -0.3481 0.4522 0.8212 +vn -0.4241 0.1101 0.8989 +vn 0.2764 -0.8975 -0.3436 +vn -0.1041 0.5421 -0.8338 +vn 0.1323 0.4878 -0.8629 +vn 0.2420 0.4451 -0.8622 +vn 0.3159 -0.9465 -0.0653 +vn 0.0527 -0.9965 -0.0653 +vn -0.0899 0.9266 -0.3651 +vn 0.6755 0.2085 -0.7072 +vn 0.3559 0.9320 -0.0679 +vn 0.6418 0.7649 0.0550 +vn 0.8804 0.4672 -0.0813 +vn -0.1319 0.4554 0.8805 +vn 0.8993 0.3202 -0.2978 +vn -0.5332 -0.8458 0.0160 +vn -0.9419 0.3348 0.0280 +vn -0.9625 -0.1017 -0.2515 +vn -0.7066 -0.0344 0.7068 +vn -0.9985 0.0533 0.0105 +vn -0.9904 0.1229 -0.0640 +vn -0.9462 0.1312 -0.2956 +vn 0.0121 0.9567 0.2910 +vn 0.1336 0.9677 0.2138 +vn -0.4975 -0.8648 -0.0685 +vn 0.3269 -0.2153 -0.9202 +vn 0.7491 -0.0729 0.6584 +vn 0.6419 0.3037 0.7041 +vn 0.5918 0.3091 0.7445 +vn -0.9360 0.3464 0.0624 +vn -0.9886 0.1465 -0.0334 +vn 0.7543 0.0375 -0.6555 +vn 0.1225 0.2719 -0.9545 +vn 0.3515 -0.2110 -0.9121 +vn -0.9886 -0.0514 -0.1413 +vn -0.1355 0.7124 -0.6885 +vn -0.6337 -0.7239 -0.2728 +vn -0.2512 0.1603 -0.9546 +vn 0.2209 0.1045 -0.9697 +vn 0.1842 0.1056 -0.9772 +vn 0.8621 -0.4331 0.2631 +vn 0.8881 -0.1104 0.4461 +vn 0.2936 -0.5654 0.7708 +vn 0.5998 -0.5499 0.5812 +vn 0.3286 -0.5634 0.7580 +vn -0.9765 0.1871 0.1067 +vn -0.9639 0.2534 0.0813 +vn -0.9628 -0.2652 -0.0517 +vn -0.1996 0.9798 0.0110 +vn 0.7823 0.6229 0.0016 +vn 0.2564 -0.5624 0.7861 +vn -0.6799 0.3273 0.6562 +vn 0.0992 -0.5521 -0.8279 +vn 0.1702 -0.5495 0.8180 +vn -0.5801 0.2288 -0.7818 +vn -0.0294 -0.9971 -0.0696 +vn 0.2367 -0.9700 -0.0556 +vn 0.0230 -0.9728 0.2304 +vn 0.1440 0.1134 0.9831 +vn -0.0782 -0.7891 -0.6093 +vn 0.1500 -0.8588 -0.4899 +vn -0.0298 -0.8273 -0.5610 +vn -0.6891 -0.6353 0.3486 +vn -0.9376 0.1066 0.3309 +vn 0.3526 -0.4129 -0.8397 +vn 0.0417 -0.3363 -0.9408 +vn 0.3663 -0.4021 -0.8391 +vn 0.9429 -0.2922 -0.1601 +vn 0.0417 0.9589 0.2807 +vn 0.9272 -0.0213 0.3740 +vn -0.2600 0.5513 0.7928 +vn 0.6781 0.5056 -0.5334 +vn -0.5905 0.7249 -0.3547 +vn -0.5867 0.6428 -0.4926 +vn 0.7256 -0.1572 -0.6700 +vn -0.3359 0.1389 0.9316 +vn -0.3900 0.2324 0.8910 +vn -0.5801 0.2288 0.7818 +vn 0.7505 0.5897 -0.2983 +vn 0.8363 0.5404 0.0927 +vn 0.5460 -0.6587 0.5177 +vn -0.2703 0.8555 -0.4416 +vn -0.4135 0.6258 -0.6613 +vn -0.5271 0.6425 -0.5563 +vn 0.5826 -0.1085 -0.8055 +vn 0.8550 -0.0464 -0.5166 +vn 0.9214 -0.3716 -0.1135 +vn 0.9587 -0.2780 0.0605 +vn 0.4015 0.5567 0.7273 +vn 0.5346 0.5960 0.5991 +vn 0.7023 0.2308 0.6734 +vn -0.2261 0.6027 -0.7653 +vn -0.1147 0.5216 -0.8455 +vn 0.3959 0.0231 -0.9180 +vn 0.3628 0.0884 -0.9277 +vn 0.8041 -0.4225 0.4183 +vn -0.4470 0.5400 0.7131 +vn -0.6445 0.4924 0.5849 +vn 0.9647 -0.1900 0.1821 +vn 0.5838 0.8118 0.0130 +vn 0.6288 0.7675 -0.1249 +vn 0.4700 0.8516 -0.2322 +vn -0.6430 0.7474 -0.1671 +vn 0.9014 0.4316 0.0330 +vn -0.7074 -0.0360 -0.7059 +vn -0.5224 -0.0689 -0.8499 +vn 0.1608 0.9764 0.1439 +vn 0.3034 0.1155 0.9458 +vn 0.0262 0.1256 0.9917 +vn 0.7106 0.6615 -0.2398 +vn 0.8840 0.4470 -0.1370 +vn 0.5732 -0.5191 -0.6341 +vn 0.2041 -0.5682 -0.7971 +vn 0.3719 -0.3443 -0.8621 +vn -0.6214 0.7675 0.1572 +vn -0.8074 0.5776 0.1202 +vn -0.7586 0.6346 0.1479 +vn -0.6919 0.6956 0.1933 +vn -0.5886 0.7131 0.3809 +vn -0.5901 0.7830 0.1969 +vn 0.9320 -0.1665 0.3219 +vn 0.8455 -0.1791 0.5030 +vn 0.3526 -0.4129 0.8397 +vn 0.3663 -0.4021 0.8391 +vn 0.0417 -0.3363 0.9408 +vn -0.9542 0.0386 -0.2965 +vn -0.8946 0.0097 -0.4468 +vn 0.3131 0.7873 0.5312 +vn -0.9965 -0.0312 0.0781 +vn -0.9968 -0.0297 0.0740 +vn -0.9992 -0.0017 0.0394 +vn -0.6764 -0.0083 -0.7365 +vn -0.4490 0.0587 -0.8916 +vn -0.2215 0.0304 -0.9747 +vn -0.1540 0.0362 -0.9874 +vn -0.4232 0.8822 0.2063 +vn 0.9319 -0.3540 0.0788 +vn 0.9886 0.0352 -0.1463 +vn 0.0384 0.9781 0.2045 +vn -0.8263 0.4083 0.3879 +vn -0.2706 0.5550 0.7866 +vn -0.5479 0.4819 0.6838 +vn 0.4064 0.8463 0.3443 +vn 0.1166 0.9081 -0.4022 +vn -0.9992 -0.0021 0.0407 +vn -0.9171 0.1310 -0.3765 +vn 0.1981 0.8131 0.5473 +vn 0.1236 0.3209 -0.9390 +vn 0.9137 0.0169 0.4060 +vn 0.9971 -0.0502 -0.0574 +vn 0.9989 -0.0408 -0.0213 +vn -0.3052 0.4973 0.8121 +vn -0.0753 -0.9886 0.1304 +vn -0.0180 -0.3222 0.9465 +vn 0.5431 0.8298 0.1279 +vn 0.4462 0.8747 -0.1889 +vn -0.4373 0.1490 0.8869 +vn -0.5201 -0.7835 -0.3401 +vn -0.3469 -0.7768 -0.5255 +vn 0.2130 0.9741 -0.0756 +vn 0.5605 -0.5159 0.6479 +vn 0.7322 -0.5269 0.4316 +vn 0.1341 0.5034 0.8536 +vn -0.1072 0.5371 0.8367 +vn 0.5450 -0.1504 -0.8248 +vn 0.3669 -0.1492 -0.9182 +vn 0.2559 -0.1406 -0.9564 +vn -0.5962 -0.0420 -0.8017 +vn 0.6406 0.6984 -0.3192 +vn 0.4434 -0.8340 -0.3284 +vn 0.4572 -0.8245 -0.3334 +vn -0.6171 0.5743 0.5380 +vn -0.7283 0.4936 0.4753 +vn -0.9979 -0.0303 -0.0580 +vn -0.9965 0.0394 -0.0743 +vn 0.5866 0.3786 -0.7159 +vn -0.4024 -0.3596 0.8419 +vn -0.6357 0.7090 0.3053 +vn -0.7229 0.5913 0.3575 +vn -0.1953 -0.9611 -0.1954 +vn -0.2087 -0.9475 -0.2421 +vn 0.0878 0.9724 0.2160 +vn -0.3180 -0.7712 -0.5514 +vn -0.3597 0.5377 -0.7626 +vn 0.3289 0.9429 0.0520 +vn 0.8041 -0.4225 -0.4183 +vn -0.7944 0.6067 -0.0293 +vn -0.7287 0.6842 -0.0295 +vn 0.2909 0.5734 -0.7659 +vn 0.2316 0.8341 -0.5007 +vn 0.2220 0.1157 -0.9682 +vn 0.0788 0.5735 0.8154 +vn -0.4586 0.5446 -0.7022 +vn 0.7100 0.0404 0.7030 +vn -0.7204 -0.6930 -0.0276 +vn 0.6595 0.7292 -0.1826 +vn -0.4390 -0.7907 0.4267 +vn 0.1449 0.1116 -0.9831 +vn 0.8939 0.2659 -0.3608 +vn 0.9358 -0.1009 -0.3379 +vn -0.9543 0.0383 0.2965 +vn -0.6025 0.7702 -0.2093 +vn 0.6259 -0.0541 -0.7781 +vn 0.7063 0.7075 -0.0231 +vn 0.7161 -0.5154 0.4707 +vn 0.1717 0.7901 -0.5884 +vn -0.3481 0.4522 -0.8212 +vn -0.4019 0.5686 0.7177 +vn 0.0120 0.5169 0.8560 +vn 0.1263 0.4896 0.8627 +vn -0.7204 0.5022 0.4784 +vn 0.4785 -0.6744 -0.5623 +vn -0.7372 -0.6412 0.2133 +vn -0.5634 -0.4470 -0.6949 +vn -0.7349 0.4222 0.5307 +vn -0.7615 0.3976 0.5119 +vn -0.4831 0.5122 0.7101 +vn -0.9485 0.0905 0.3037 +vn -0.8894 0.0582 0.4534 +vn 0.1165 0.9481 -0.2960 +vn 0.2959 0.8992 -0.3222 +vn -0.4726 0.7435 0.4731 +vn 0.9878 0.1553 0.0060 +vn -0.4746 0.1359 0.8696 +vn -0.4490 0.0587 0.8916 +vn -0.2215 0.0304 0.9747 +vn -0.2403 0.9267 0.2890 +vn 0.1854 0.1147 -0.9759 +vn -0.7066 -0.0347 -0.7068 +vn -0.9394 0.2262 -0.2576 +vn -0.9456 0.1725 -0.2758 +vn 0.5955 0.6397 -0.4860 +vn -0.2268 -0.5953 -0.7708 +vn 0.6965 0.6974 -0.1689 +vn 0.2234 0.9680 -0.1140 +vn -0.4612 0.5199 -0.7190 +vn -0.3052 0.4973 -0.8121 +vn 0.7154 0.5764 0.3950 +vn 0.0642 0.8896 -0.4522 +vn -0.9422 0.3230 -0.0890 +vn -0.8705 -0.1650 -0.4637 +vn -0.4083 0.9119 -0.0408 +vn -0.8124 -0.0145 0.5829 +vn -0.0283 0.9879 -0.1526 +vn 0.7106 0.6615 0.2398 +vn -0.8879 0.3695 -0.2740 +vn -0.9456 0.3086 -0.1030 +vn -0.9360 0.3464 -0.0624 +vn 0.2181 0.6806 0.6994 +vn 0.3444 0.5188 0.7824 +vn -0.6344 0.4405 0.6353 +vn -0.2486 -0.8084 -0.5336 +vn -0.3958 -0.7984 -0.4538 +vn -0.4215 -0.7504 -0.5092 +vn -0.7293 -0.6651 0.1607 +vn -0.1271 0.5192 -0.8451 +vn 0.6481 -0.4555 0.6103 +vn -0.4760 0.1506 0.8664 +vn 0.2510 -0.0090 0.9680 +vn 0.9886 -0.1252 -0.0832 +vn -0.6755 -0.2085 -0.7072 +vn -0.4801 0.7177 0.5044 +vn -0.4733 0.1783 0.8627 +vn -0.9886 0.1465 0.0334 +vn -0.9497 0.1105 0.2930 +vn -0.9319 0.3540 0.0788 +vn -0.9742 0.1515 -0.1673 +vn -0.9018 0.1723 -0.3963 +vn 0.3730 0.0704 0.9251 +vn 0.4146 0.0639 0.9077 +vn 0.8358 -0.0291 0.5483 +vn 0.8735 0.2265 0.4309 +vn 0.9683 -0.1467 -0.2021 +vn 0.2666 0.6879 0.6751 +vn 0.2019 0.9751 0.0919 +vn -0.0551 0.9647 -0.2576 +vn -0.4671 0.8342 0.2933 +vn -0.3490 0.7741 0.5282 +vn -0.1823 0.2705 -0.9453 +vn -0.1340 0.3644 -0.9216 +vn -0.6224 0.6906 0.3683 +vn -0.7006 0.6632 -0.2631 +vn -0.3900 0.2324 -0.8910 +vn 0.4403 -0.7329 -0.5187 +vn 0.4319 -0.8323 -0.3474 +vn -0.4730 0.8246 0.3105 +vn -0.3533 -0.3103 -0.8825 +vn -0.5140 -0.4179 -0.7491 +vn -0.3826 -0.2240 -0.8963 +vn -0.1803 -0.8216 0.5408 +vn -0.3513 -0.8043 0.4793 +vn -0.2521 0.3969 0.8826 +vn -0.3087 0.5905 0.7456 +vn -0.4600 0.5031 0.7316 +vn 0.0584 0.9911 0.1197 +vn -0.1072 0.5371 -0.8367 +vn -0.4119 0.5372 -0.7360 +vn 0.6591 0.7392 -0.1385 +vn 0.6532 0.7430 -0.1458 +vn -0.9293 0.0822 -0.3600 +vn -0.9394 0.0889 -0.3312 +vn -0.8500 0.1631 -0.5009 +vn -0.2630 0.5440 0.7968 +vn 0.1634 -0.2390 -0.9572 +vn 0.9087 -0.0872 -0.4082 +vn -0.5459 0.1263 -0.8283 +vn 0.1778 0.9566 -0.2308 +vn 0.1725 0.8391 -0.5160 +vn 0.9184 0.0181 0.3951 +vn -0.6101 0.7738 -0.1703 +vn -0.8943 0.4310 0.1201 +vn -0.3359 0.1389 -0.9316 +vn 0.0636 -0.8715 0.4862 +vn 0.6906 0.2705 -0.6707 +vn 0.4235 0.3653 -0.8290 +vn 0.4019 0.4884 -0.7745 +vn 0.6073 0.6945 0.3859 +vn 0.4314 0.3701 0.8228 +vn 0.3527 0.3996 0.8461 +vn 0.9392 -0.0784 0.3342 +vn -0.6054 0.6628 0.4406 +vn -0.5656 -0.6346 0.5266 +vn -0.3988 -0.6318 0.6647 +vn -0.4269 -0.5694 0.7025 +vn 0.6445 0.3160 0.6962 +vn -0.9825 0.1495 0.1110 +vn -0.9966 0.0809 0.0164 +vn -0.9409 0.2323 0.2465 +vn -0.1506 -0.2854 0.9465 +vn -0.4760 0.5490 -0.6870 +vn -0.3346 0.4585 -0.8233 +vn 0.1606 0.6809 0.7145 +vn 0.1136 0.7537 0.6473 +vn 0.7082 0.6921 0.1394 +vn 0.7282 0.5115 0.4561 +vn 0.5383 0.5335 0.6524 +vn 0.9882 0.0317 0.1500 +vn -0.9765 0.1871 -0.1067 +vn -0.9639 0.2534 -0.0813 +vn -0.0096 -0.6120 0.7908 +vn 0.4692 0.4441 0.7633 +vn -0.7229 0.2406 0.6477 +vn -0.6573 -0.2787 0.7002 +vn -0.1724 -0.8391 0.5159 +vn 0.0442 0.0756 -0.9962 +vn -0.0857 0.0925 -0.9920 +vn -0.1816 0.5575 0.8101 +vn -0.2555 0.5571 0.7902 +vn -0.9929 0.0578 -0.1043 +vn -0.1147 0.5216 0.8455 +vn 0.2510 -0.0090 -0.9680 +vn -0.0782 -0.7891 0.6093 +vn -0.0298 -0.8273 0.5610 +vn 0.5962 0.6804 -0.4262 +vn 0.1037 0.0990 0.9897 +vn -0.0918 0.1647 0.9821 +vn 0.1743 0.9766 0.1260 +vn -0.9880 0.0034 -0.1544 +vn -0.1448 -0.1116 0.9831 +vn -0.1449 -0.1116 0.9831 +vn 0.4319 -0.8323 0.3474 +vn 0.1123 0.4564 -0.8827 +vn 0.4878 -0.2779 -0.8275 +vn 0.7378 -0.2537 -0.6255 +vn -0.1324 -0.3310 -0.9343 +vn 0.9594 0.2815 0.0166 +vn 0.9605 0.2736 0.0509 +vn 0.5223 0.4119 -0.7467 +vn -0.9281 0.0840 -0.3628 +vn 0.4640 0.2483 0.8503 +vn -0.0424 0.9807 0.1910 +vn -0.5634 -0.4470 0.6949 +vn 0.2746 0.8780 -0.3920 +vn 0.2487 0.7496 -0.6134 +vn 0.5661 0.7087 0.4211 +vn 0.3836 0.8565 0.3453 +vn -0.5901 0.7830 -0.1969 +vn 0.0154 0.9903 0.1379 +vn 0.6784 -0.7335 -0.0416 +vn 0.5268 -0.7773 0.3440 +vn 0.5140 -0.7880 0.3389 +vn -0.9647 0.1901 0.1821 +vn -0.9647 0.1900 0.1821 +vn 0.0095 0.7218 0.6920 +vn 0.1747 0.7161 0.6758 +vn -0.8359 -0.3071 -0.4550 +vn -0.6678 -0.3434 -0.6603 +vn -0.8021 -0.3936 -0.4491 +vn -0.3812 0.8205 0.4261 +vn -0.1645 0.8274 0.5369 +vn 0.9601 0.2784 0.0252 +vn 0.9623 0.2703 0.0306 +vn -0.4456 -0.8006 0.4006 +vn -0.5804 -0.7805 0.2322 +vn 0.9157 0.3921 0.0881 +vn 0.9213 0.3752 0.1024 +vn -0.2243 0.0190 0.9743 +vn 0.9878 0.1553 -0.0060 +vn 0.9789 -0.0736 -0.1907 +vn -0.2098 0.9694 0.1272 +vn -0.3712 -0.5001 -0.7824 +vn -0.1783 -0.5404 -0.8223 +vn -0.1010 -0.5531 -0.8270 +vn 0.2220 -0.8389 0.4970 +vn -0.0130 -0.7899 0.6131 +vn 0.0238 -0.8403 0.5416 +vn 0.0568 0.7453 -0.6643 +vn -0.9453 0.1242 -0.3017 +vn -0.0724 0.9343 0.3492 +vn 0.0471 0.9863 -0.1579 +vn 0.1123 0.4564 0.8827 +vn -0.1303 0.8120 -0.5689 +vn 0.8833 0.4675 -0.0356 +vn -0.1303 -0.9828 0.1308 +vn -0.6448 -0.2680 0.7158 +vn 0.9242 0.3659 0.1091 +vn 0.9294 0.3502 0.1161 +vn 0.8153 0.3683 -0.4468 +vn 0.6019 0.7768 -0.1855 +vn 0.0798 0.9711 0.2250 +vn 0.2858 0.4608 0.8402 +vn -0.8473 0.3935 -0.3568 +vn 0.4801 0.0809 0.8735 +vn 0.9358 -0.1009 0.3379 +vn -0.9087 0.0867 0.4083 +vn -0.2313 -0.8515 0.4706 +vn -0.8319 -0.4703 -0.2946 +vn 0.2137 0.8138 -0.5404 +vn 0.1303 0.9828 0.1308 +vn 0.1303 0.9828 0.1307 +vn 0.1021 0.1117 -0.9885 +vn 0.0480 0.1270 -0.9907 +vn 0.7322 -0.5269 -0.4316 +vn 0.7002 -0.5319 -0.4763 +vn -0.6428 -0.3061 0.7022 +vn -0.5200 0.6278 0.5793 +vn 0.3706 0.8964 -0.2430 +vn -0.5542 -0.6486 -0.5217 +vn 0.0140 -0.1264 0.9919 +vn -0.2948 0.7764 0.5570 +vn 0.6660 0.7343 -0.1313 +vn -0.9916 -0.0140 0.1289 +vn 0.0449 0.9888 0.1426 +vn 0.0555 0.9894 0.1344 +vn 0.3678 -0.6413 0.6734 +vn -0.8556 0.0084 0.5176 +vn -0.8629 0.0278 0.5046 +vn -0.9625 -0.1017 0.2515 +vn -0.0294 -0.9971 0.0696 +vn 0.2367 -0.9700 0.0556 +vn -0.7594 0.5048 0.4105 +vn -0.4020 0.5686 0.7177 +vn 0.5346 0.5960 -0.5991 +vn -0.9938 -0.0686 0.0876 +vn 0.4393 0.0585 0.8964 +vn 0.1999 0.8781 0.4348 +vn -0.1815 -0.4132 -0.8924 +vn -0.3420 0.9156 0.2113 +vn -0.9255 0.1885 -0.3286 +vn -0.2701 -0.8225 -0.5005 +vn -0.6353 0.7385 -0.2261 +vn -0.4685 0.8165 0.3374 +vn 0.0075 0.8062 -0.5916 +vn 0.0613 0.9049 -0.4213 +vn -0.4034 0.5725 -0.7138 +vn 0.1999 0.8781 -0.4348 +vn 0.1084 0.9845 0.1381 +vn 0.9789 -0.0736 0.1907 +vn -0.9904 0.1229 0.0640 +vn -0.9996 -0.0234 -0.0174 +vn 0.1658 -0.6896 0.7050 +vn -0.7828 0.1079 -0.6128 +vn 0.2010 -0.5350 0.8206 +vn 0.4992 -0.5624 0.6592 +vn 0.4713 -0.5197 0.7126 +vn -0.5687 -0.5973 0.5655 +vn -0.8106 -0.3611 0.4610 +vn -0.6678 -0.3434 0.6603 +vn -0.9969 -0.0661 0.0417 +vn 0.4751 -0.3412 -0.8111 +vn 0.6495 -0.5338 -0.5415 +vn 0.6064 -0.5867 -0.5367 +vn -0.0119 -0.5169 -0.8560 +vn -0.5448 0.8039 0.2384 +vn -0.4255 0.9050 -0.0053 +vn -0.2391 0.9304 0.2779 +vn -0.3376 0.9354 0.1054 +vn 0.2336 0.3891 0.8911 +vn -0.9647 0.1901 -0.1821 +vn -0.9647 0.1900 -0.1821 +vn -0.9952 0.0544 0.0817 +vn -0.9870 0.0060 -0.1606 +vn -0.9876 0.0043 -0.1570 +vn 0.7421 -0.2091 -0.6368 +vn 0.6160 -0.1927 -0.7638 +vn -0.9069 0.1223 0.4032 +vn -0.1855 -0.7000 0.6896 +vn 0.3123 -0.1562 -0.9370 +vn -0.0754 -0.9886 -0.1305 +vn 0.3756 0.9245 0.0654 +vn -0.3717 0.4271 0.8243 +vn 0.2130 0.8262 -0.5215 +vn 0.2469 0.4702 -0.8473 +vn 0.4326 0.4060 -0.8050 +vn -0.1271 0.1854 -0.9744 +vn 0.9214 -0.3716 0.1135 +vn 0.7856 -0.4888 0.3794 +vn 0.7214 0.1193 -0.6822 +vn 0.6177 0.1789 -0.7658 +vn 0.4892 0.2865 -0.8237 +vn 0.9604 0.2775 0.0263 +vn 0.7082 0.6921 -0.1394 +vn -0.7828 0.1079 0.6128 +vn -0.9938 -0.0686 -0.0876 +vn 0.2684 -0.7800 -0.5653 +vn -0.4241 0.1101 -0.8989 +vn -0.7229 0.5913 -0.3575 +vn -0.5687 -0.8108 -0.1382 +vn -0.6906 -0.2705 -0.6708 +vn 0.9320 -0.1664 0.3219 +vn -0.5496 0.6278 -0.5512 +vn -0.3728 0.9033 -0.2122 +vn 0.8711 0.4530 -0.1898 +vn 0.3031 0.1091 0.9467 +vn 0.5561 0.0844 0.8268 +vn 0.9616 0.2723 0.0337 +vn -0.5328 -0.7643 -0.3633 +vn -0.3264 0.4178 -0.8479 +vn -0.2761 0.6646 -0.6943 +vn -0.7479 -0.6296 0.2106 +vn 0.5178 0.0455 -0.8543 +vn -0.6604 -0.2146 0.7196 +vn -0.6417 -0.2362 0.7297 +vn -0.0901 0.5834 -0.8072 +vn 0.0649 0.6428 -0.7633 +vn 0.3667 -0.9247 0.1024 +vn -0.1663 0.4655 -0.8693 +vn -0.0453 0.1696 -0.9845 +vn 0.4700 0.8516 0.2322 +vn 0.2134 -0.1438 0.9663 +vn -0.2564 0.5624 -0.7861 +vn -0.2795 -0.4309 -0.8580 +vn 0.6787 -0.7327 -0.0490 +vn 0.5761 -0.7190 -0.3888 +vn -0.4191 -0.4004 0.8149 +vn -0.1503 0.5643 0.8118 +vn 0.1458 0.1185 -0.9822 +vn -0.6906 -0.2705 0.6708 +vn 0.1181 -0.9656 -0.2315 +vn 0.4076 -0.9024 -0.1397 +vn 0.3159 -0.9465 0.0653 +vn -0.1464 -0.1195 0.9820 +vn 0.5918 0.3091 -0.7445 +vn 0.7491 -0.0729 -0.6584 +vn 0.2243 -0.8898 -0.3974 +vn 0.3046 0.0414 0.9516 +vn -0.8535 -0.2483 0.4582 +vn -0.9526 -0.1209 0.2791 +vn 0.8110 -0.3645 -0.4576 +vn -0.5867 0.6428 0.4926 +vn -0.1540 0.0362 0.9874 +vn -0.1449 -0.1116 -0.9831 +vn -0.7149 -0.6992 0.0055 +vn 0.0565 0.9972 -0.0486 +vn 0.0328 0.9769 -0.2110 +vn 0.0281 0.9985 -0.0466 +vn -0.0348 0.9270 -0.3734 +vn 0.6821 0.0668 -0.7282 +vn 0.2677 0.4314 -0.8615 +vn 0.2144 0.3961 -0.8928 +vn -0.1239 0.2982 -0.9464 +vn 0.4318 0.6592 0.6156 +vn 0.5204 0.7187 0.4611 +vn 0.4401 0.7459 0.5000 +vn 0.5276 0.8490 -0.0277 +vn 0.4716 -0.0403 0.8809 +vn 0.4706 -0.0992 0.8768 +vn 0.5393 -0.0670 0.8395 +vn 0.0983 0.9859 0.1356 +vn 0.0466 0.9878 0.1485 +vn 0.3126 0.9107 0.2700 +vn 0.4905 0.7993 0.3471 +vn 0.4502 0.8650 0.2215 +vn 0.1730 0.9790 0.1077 +vn 0.0897 0.9947 -0.0494 +vn 0.6419 0.3037 -0.7041 +vn 0.3515 0.2221 -0.9095 +vn 0.1449 0.1116 0.9831 +vn 0.1448 0.1116 0.9831 +vn 0.6521 0.7186 0.2417 +vn -0.9875 0.1577 0.0042 +vn -0.9922 0.1180 0.0389 +vn -0.9527 0.3006 0.0437 +vn 0.7814 -0.1398 0.6082 +vn -0.9969 0.0662 -0.0425 +vn -0.9855 0.1608 -0.0534 +vn 0.0503 0.1853 0.9814 +vn 0.0539 0.2770 0.9594 +vn -0.0092 0.2828 0.9591 +vn 0.1508 0.7965 0.5856 +vn 0.1276 0.8220 0.5550 +vn 0.1331 0.7443 0.6545 +vn 0.0499 -0.5323 -0.8451 +vn -0.7997 0.5954 0.0778 +vn -0.5580 0.8113 0.1744 +vn -0.5456 0.8354 0.0665 +vn 0.8385 0.5315 0.1199 +vn 0.8702 0.4885 0.0647 +vn 0.8482 0.5241 0.0769 +vn 0.2277 0.8115 0.5381 +vn 0.2616 0.7893 0.5556 +vn 0.2415 0.7805 0.5766 +vn 0.6394 0.0378 0.7680 +vn 0.6183 0.1149 0.7775 +vn -0.5809 0.7035 0.4095 +vn -0.5722 0.7722 0.2763 +vn -0.8057 0.5618 0.1875 +vn 0.2468 0.8206 0.5154 +vn 0.3031 0.1091 -0.9467 +vn 0.5140 -0.7880 -0.3389 +vn 0.2220 -0.8389 -0.4970 +vn -0.0502 0.8795 0.4733 +vn -0.1325 0.8667 0.4810 +vn -0.0528 0.8696 0.4909 +vn -0.4255 0.9050 0.0053 +vn -0.9824 -0.0535 0.1792 +vn 0.2871 0.9523 0.1031 +vn 0.4145 0.9097 0.0239 +vn 0.3270 0.9439 0.0467 +vn -0.2087 -0.9475 0.2421 +vn 0.9016 -0.1287 0.4130 +vn 0.6756 0.2085 -0.7072 +vn 0.1236 0.9829 -0.1363 +vn 0.1290 0.9566 -0.2612 +vn 0.1107 0.9841 -0.1392 +vn 0.2908 -0.1623 0.9429 +vn -0.9873 -0.0041 0.1587 +vn -0.9844 0.0710 0.1610 +vn -0.9929 0.0292 0.1154 +vn -0.6430 0.7474 0.1671 +vn -0.6414 -0.4523 -0.6197 +vn -0.0641 0.2501 0.9661 +vn -0.1279 0.3080 0.9428 +vn -0.0866 0.2221 0.9712 +vn -0.0141 0.8318 0.5549 +vn 0.0330 0.8487 0.5278 +vn 0.0122 0.8540 0.5202 +vn -0.9863 0.0082 0.1649 +vn -0.9849 0.0073 0.1729 +vn -0.9532 0.0437 0.2993 +vn 0.0611 0.4471 0.8924 +vn 0.1083 0.8779 0.4665 +vn 0.1196 0.8699 0.4786 +vn 0.1203 0.8585 0.4986 +vn -0.6241 0.7738 -0.1083 +vn -0.8316 0.5535 -0.0462 +vn -0.6883 0.7178 0.1044 +vn -0.3360 0.1653 0.9272 +vn -0.2240 0.1788 0.9580 +vn -0.5355 0.1598 0.8293 +vn -0.9433 0.3180 0.0954 +vn -0.9492 0.2753 0.1523 +vn -0.8183 0.4995 0.2844 +vn -0.5567 -0.2907 -0.7782 +vn 0.2600 -0.5513 0.7928 +vn 0.2701 0.8225 -0.5005 +vn 0.0474 0.7198 0.6926 +vn -0.0572 0.5611 0.8258 +vn 0.0525 0.6126 0.7886 +vn -0.0264 0.9063 0.4219 +vn 0.0183 0.8884 0.4588 +vn 0.0635 0.9065 0.4175 +vn 0.1419 0.8404 0.5231 +vn 0.1250 0.8503 0.5111 +vn 0.0697 0.9751 -0.2106 +vn -0.0187 0.9987 -0.0476 +vn 0.0643 0.9639 -0.2582 +vn 0.0744 0.9878 -0.1371 +vn 0.0871 0.9856 -0.1450 +vn 0.6868 0.3470 0.6387 +vn 0.6138 0.4142 0.6721 +vn 0.4964 0.2614 0.8278 +vn -0.0179 0.9901 0.1390 +vn -0.1069 0.9920 -0.0666 +vn -0.6435 -0.4380 0.6278 +vn 0.0102 0.9909 -0.1341 +vn 0.0146 0.9681 -0.2500 +vn 0.0031 0.9915 -0.1297 +vn 0.7352 0.6343 0.2389 +vn 0.6945 0.6908 0.2009 +vn 0.6167 0.7457 0.2522 +vn 0.3933 -0.1537 -0.9065 +vn -0.9887 0.1182 0.0926 +vn -0.3235 0.8489 -0.4180 +vn -0.4734 0.1776 -0.8627 +vn 0.2754 0.4163 0.8665 +vn 0.1875 0.2845 0.9402 +vn 0.2418 0.2544 0.9364 +vn 0.1212 0.8514 0.5103 +vn 0.1220 0.8958 0.4273 +vn 0.1063 0.8906 0.4422 +vn 0.8953 0.2634 0.3592 +vn 0.7997 0.2080 0.5633 +vn 0.8210 0.1497 0.5510 +vn 0.0442 0.0756 0.9962 +vn 0.2777 -0.6628 -0.6954 +vn 0.7421 -0.2091 0.6368 +vn -0.3027 0.3244 -0.8962 +vn -0.5362 0.4218 -0.7311 +vn 0.3211 -0.9344 0.1541 +vn -0.1480 0.0546 0.9875 +vn -0.9643 0.2451 -0.1005 +vn -0.9854 0.1260 -0.1143 +vn 0.9408 0.1514 0.3033 +vn 0.9680 0.1886 0.1654 +vn 0.9485 0.1889 0.2541 +vn 0.9055 0.4210 -0.0527 +vn 0.9371 0.3484 -0.0221 +vn 0.9103 0.4079 -0.0709 +vn 0.5342 0.1166 -0.8373 +vn -0.0663 -0.1216 0.9904 +vn -0.3754 -0.0731 0.9240 +vn -0.9571 0.2788 -0.0786 +vn 0.7884 -0.3777 0.4856 +vn 0.5420 -0.1811 -0.8207 +vn 0.3650 -0.1702 -0.9153 +vn 0.0329 0.9879 -0.1517 +vn 0.0222 0.9893 -0.1442 +vn 0.2858 0.4608 -0.8402 +vn 0.2558 0.4480 -0.8566 +vn 0.0142 0.4567 -0.8895 +vn 0.4917 0.3291 0.8062 +vn 0.1047 0.8031 0.5865 +vn -0.3513 0.5398 0.7650 +vn -0.5510 0.4087 0.7276 +vn -0.8072 0.2121 0.5508 +vn -0.5363 0.3123 0.7841 +vn -0.7382 0.5106 0.4408 +vn 0.7023 0.2308 -0.6734 +vn 0.4992 -0.7979 -0.3378 +vn 0.6507 -0.7573 0.0558 +vn 0.1732 0.5937 0.7858 +vn 0.3021 0.5692 0.7647 +vn 0.9725 0.2316 -0.0250 +vn 0.9666 0.2494 0.0596 +vn 0.2587 0.1146 0.9591 +vn 0.2153 0.0785 0.9734 +vn 0.2696 0.0526 0.9615 +vn -0.9216 0.0607 0.3833 +vn 0.3194 0.0664 0.9453 +vn 0.3625 0.1972 0.9109 +vn 0.3210 0.2722 0.9071 +vn 0.9765 0.1845 0.1111 +vn 0.8775 0.1071 -0.4675 +vn -0.8359 -0.3071 0.4550 +vn -0.8514 -0.4307 0.2995 +vn 0.7440 0.6387 0.1961 +vn 0.1173 0.8461 0.5200 +vn 0.1099 0.8343 0.5403 +vn 0.9587 -0.2780 -0.0605 +vn -0.9776 0.1544 0.1429 +vn -0.1039 0.4550 0.8844 +vn 0.1723 0.0967 0.9803 +vn 0.3560 0.0964 0.9295 +vn -0.2762 -0.9255 -0.2592 +vn -0.6070 0.7817 -0.1430 +vn 0.1448 0.1116 -0.9831 +vn -0.1601 -0.7816 0.6028 +vn 0.4499 0.0845 0.8891 +vn -0.2172 0.9218 0.3211 +vn -0.3800 0.8342 0.3996 +vn -0.1290 0.9320 0.3387 +vn 0.8087 0.5432 0.2258 +vn 0.7928 0.5810 0.1841 +vn 0.7736 0.6037 0.1925 +vn 0.0160 -0.1372 0.9904 +vn 0.1303 0.9828 -0.1307 +vn 0.1303 0.9828 -0.1308 +vn 0.7507 0.2656 0.6049 +vn 0.7473 0.4445 0.4939 +vn -0.0043 0.4571 0.8894 +vn 0.1166 0.9081 0.4022 +vn -0.8130 0.0827 0.5763 +vn 0.3646 0.1016 0.9256 +vn 0.4348 0.1089 0.8939 +vn 0.3211 -0.9344 -0.1541 +vn -0.4270 0.8860 -0.1810 +vn -0.5071 0.7063 -0.4941 +vn -0.6281 0.7559 -0.1848 +vn 0.5150 0.4532 -0.7276 +vn 0.3628 0.0884 0.9277 +vn 0.3443 0.0900 0.9345 +vn 0.2010 -0.5350 -0.8206 +vn -0.4619 -0.2969 0.8358 +vn -0.4289 -0.2521 0.8675 +vn -0.1015 -0.9818 0.1605 +vn -0.6735 -0.4710 -0.5697 +vn -0.7195 -0.5553 -0.4170 +vn -0.7085 -0.4227 -0.5651 +vn 0.8530 0.1169 0.5087 +vn 0.7675 0.5356 0.3523 +vn 0.6824 0.6348 0.3625 +vn 0.6880 0.5886 0.4245 +vn -0.7298 -0.5731 0.3727 +vn 0.0556 -0.2966 0.9534 +vn 0.4977 0.4935 0.7133 +vn 0.4349 0.3484 0.8304 +vn 0.3157 0.8045 0.5031 +vn 0.3243 0.7837 0.5297 +vn 0.3764 0.7989 0.4691 +vn -0.9818 0.0604 -0.1801 +vn 0.9036 0.4219 0.0744 +vn 0.8592 0.4880 0.1535 +vn 0.8966 0.4428 0.0003 +vn 0.8921 0.4514 0.0200 +vn -0.1913 0.9744 0.1185 +vn -0.2564 0.3508 0.9007 +vn -0.2727 0.4685 0.8403 +vn -0.3077 0.9299 0.2015 +vn 0.2224 0.9222 0.3165 +vn 0.3146 0.8583 0.4054 +vn -0.3469 -0.7768 0.5255 +vn 0.2148 0.8711 0.4417 +vn 0.2244 0.8477 0.4806 +vn 0.2243 0.8509 0.4750 +vn 0.3706 0.8964 0.2430 +vn -0.3147 0.6844 0.6577 +vn -0.3200 0.7575 0.5690 +vn -0.5800 0.6435 0.4995 +vn 0.1006 0.9838 -0.1484 +vn 0.3167 0.7661 0.5593 +vn -0.0603 0.9465 0.3171 +vn -0.3977 0.9173 0.0180 +vn -0.7047 -0.3612 -0.6106 +vn -0.9450 0.1150 0.3063 +vn 0.0583 0.9904 -0.1251 +vn 0.0572 0.9902 -0.1273 +vn 0.0586 0.9897 -0.1309 +vn -0.9219 0.0716 0.3809 +vn -0.1724 -0.8391 -0.5160 +vn 0.0678 0.9886 -0.1346 +vn 0.0612 0.9892 -0.1330 +vn 0.0712 0.8927 0.4450 +vn 0.1131 0.8916 0.4384 +vn 0.1347 0.9314 0.3383 +vn -0.8099 0.1403 0.5695 +vn -0.6561 0.2562 0.7098 +vn 0.3143 0.8117 0.4923 +vn 0.3156 0.8158 0.4846 +vn 0.1341 0.5034 -0.8536 +vn 0.2452 0.8236 0.5115 +vn 0.0461 0.9904 -0.1303 +vn -0.7483 -0.6278 -0.2141 +vn -0.7170 -0.6678 -0.1999 +vn -0.4975 -0.8648 0.0685 +vn 0.3686 -0.0001 0.9296 +vn -0.7235 -0.6524 -0.2254 +vn 0.0679 0.7986 0.5980 +vn -0.0052 0.7528 0.6583 +vn 0.5917 0.7941 0.1392 +vn 0.5369 0.8289 0.1570 +vn 0.6208 0.7568 0.2047 +vn -0.2954 0.5863 0.7543 +vn 0.0666 -0.9968 0.0449 +vn 0.4324 -0.8953 -0.1075 +vn 0.2003 -0.9793 -0.0286 +vn -0.8171 0.3401 0.4655 +vn 0.6669 0.0059 0.7452 +vn 0.8299 0.3707 0.4170 +vn 0.5382 0.6150 0.5763 +vn 0.2760 0.8500 0.4487 +vn 0.3136 0.8366 0.4491 +vn 0.1086 0.9868 -0.1201 +vn 0.1085 0.9862 -0.1251 +vn -0.1089 0.9744 -0.1965 +vn 0.2527 0.6989 0.6691 +vn 0.3345 0.6893 0.6426 +vn 0.3131 0.9426 -0.1160 +vn -0.4119 0.5372 0.7360 +vn -0.0091 0.9475 0.3196 +vn -0.5638 0.4961 0.6603 +vn -0.9966 0.0809 -0.0164 +vn 0.1834 0.9535 -0.2392 +vn -0.0790 0.9850 -0.1533 +vn -0.1078 -0.9753 0.1927 +vn 0.1557 0.4437 0.8826 +vn 0.1209 0.9588 -0.2570 +vn 0.9295 0.2177 0.2976 +vn -0.2568 0.9444 -0.2052 +vn -0.1162 0.9387 -0.3247 +vn -0.2597 0.9404 -0.2196 +vn 0.1544 0.8933 0.4221 +vn 0.0270 0.9722 -0.2325 +vn 0.0450 0.9729 -0.2270 +vn 0.2285 0.8374 0.4965 +vn 0.2406 0.8298 0.5035 +vn -0.3712 -0.5001 0.7824 +vn 0.1657 0.9848 -0.0519 +vn 0.1900 0.9788 -0.0761 +vn 0.1639 0.9821 -0.0927 +vn -0.9086 0.4176 0.0061 +vn -0.7905 0.6124 0.0099 +vn -0.5185 0.8533 0.0550 +vn -0.5681 0.0691 0.8200 +vn -0.4408 0.1305 0.8881 +vn 0.2373 0.9423 -0.2360 +vn 0.1658 0.9762 -0.1397 +vn 0.1714 0.9764 -0.1318 +vn 0.1344 0.9656 -0.2228 +vn 0.0764 0.9599 -0.2699 +vn 0.2991 0.5086 -0.8074 +vn 0.5788 0.1990 0.7908 +vn -0.2319 0.8763 0.4222 +vn -0.3392 0.8880 0.3105 +vn -0.9994 0.0251 0.0240 +vn 0.8866 0.2304 0.4011 +vn -0.7249 0.1845 0.6637 +vn 0.2253 0.8422 0.4898 +vn 0.2207 0.8361 0.5023 +vn -0.5870 0.5724 0.5725 +vn -0.8442 0.4147 0.3396 +vn 0.0578 0.9912 -0.1192 +vn -0.0941 0.9723 -0.2141 +vn -0.0441 0.9749 -0.2181 +vn 0.4578 0.0544 0.8874 +vn 0.1364 0.9742 -0.1797 +vn 0.1670 0.9634 -0.2097 +vn 0.0393 0.8456 0.5323 +vn 0.0423 0.8408 0.5397 +vn -0.9319 0.3540 -0.0788 +vn -0.6195 -0.0561 0.7830 +vn -0.0590 0.9463 -0.3179 +vn -0.0148 0.9534 -0.3013 +vn 0.1901 0.8894 0.4156 +vn -0.0242 0.8852 0.4646 +vn 0.1053 0.9689 -0.2240 +vn 0.7168 0.6761 0.1705 +vn 0.7300 0.6524 0.2036 +vn -0.3203 0.8150 0.4829 +vn 0.9850 0.1635 0.0553 +vn 0.9863 0.1633 0.0253 +vn 0.6330 0.7540 0.1755 +vn 0.5819 0.0275 0.8128 +vn -0.9762 0.1042 0.1901 +vn 0.7807 -0.1132 -0.6146 +vn -0.8833 0.4602 -0.0892 +vn -0.7892 0.5954 -0.1503 +vn 0.8859 0.4227 0.1912 +vn 0.8293 0.4807 0.2850 +vn 0.9359 0.3129 0.1620 +vn 0.8869 0.3798 0.2629 +vn 0.7114 0.5099 0.4835 +vn 0.7899 0.4754 0.3875 +vn 0.1474 0.8219 0.5503 +vn 0.1459 0.8342 0.5317 +vn 0.1612 0.9060 0.3914 +vn 0.3870 0.5010 0.7741 +vn 0.2047 0.7836 0.5865 +vn 0.2226 0.7714 0.5962 +vn 0.1909 0.7240 0.6628 +vn 0.3422 0.6541 0.6746 +vn -0.9687 0.0061 0.2482 +vn -0.8686 0.1217 0.4804 +vn 0.6056 0.5549 0.5704 +vn 0.5946 0.6867 0.4181 +vn -0.0944 0.1294 -0.9871 +vn -0.0022 0.9766 -0.2151 +vn -0.0293 0.1789 0.9834 +vn -0.0514 0.3185 0.9465 +vn -0.2362 0.2275 0.9447 +vn -0.7848 0.5980 0.1628 +vn 0.3324 0.8280 0.4515 +vn 0.3200 0.8197 0.4751 +vn -0.7235 -0.6524 0.2254 +vn 0.1081 0.9842 -0.1404 +vn 0.8927 0.1671 0.4185 +vn 0.8252 0.0625 0.5614 +vn 0.8115 0.5660 0.1453 +vn 0.8280 0.5523 0.0968 +vn 0.8547 -0.3218 0.4073 +vn -0.9997 -0.0039 -0.0225 +vn -0.9995 0.0034 -0.0300 +vn 0.0694 0.9962 -0.0533 +vn 0.1946 0.9548 -0.2246 +vn 0.3017 0.9216 -0.2441 +vn -0.0329 0.9779 -0.2065 +vn 0.2235 0.9466 -0.2325 +vn 0.9536 -0.2735 0.1260 +vn -0.9536 0.2735 -0.1260 +vn 0.0436 0.9771 -0.2082 +vn -0.9615 0.2578 0.0952 +vn -0.2473 0.9654 -0.0831 +vn 0.1085 0.9854 -0.1309 +vn 0.1085 0.9855 -0.1304 +vn -0.9933 -0.0329 0.1104 +vn -0.9969 -0.0427 0.0655 +vn 0.5629 -0.6270 0.5386 +vn -0.8415 -0.5345 0.0784 +vn -0.8333 -0.5460 0.0859 +vn -0.0093 0.9925 -0.1220 +vn -0.0067 0.9927 -0.1205 +vn -0.1741 0.1419 -0.9745 +vn 0.4664 0.8781 0.1067 +vn 0.4397 0.8715 -0.2170 +vn 0.3341 0.9201 -0.2045 +vn 0.2699 0.9461 -0.1790 +vn 0.3067 0.7909 0.5295 +vn -0.1178 0.9839 0.1342 +vn 0.9320 -0.1665 -0.3219 +vn 0.9320 -0.1664 -0.3219 +vn 0.2339 0.8653 0.4433 +vn -0.2864 0.9572 0.0407 +vn 0.1342 0.9815 -0.1363 +vn 0.1469 0.9792 -0.1397 +vn -0.1566 -0.0442 -0.9867 +vn -0.1554 -0.0453 -0.9868 +vn -0.2044 0.0003 -0.9789 +vn 0.1222 0.9687 -0.2160 +vn 0.1647 0.1380 0.9766 +vn 0.1089 0.1730 0.9789 +vn -0.6062 0.1059 0.7882 +vn 0.0125 0.9783 -0.2070 +vn 0.1086 0.9861 -0.1255 +vn -0.4878 -0.7514 0.4444 +vn 0.4803 -0.3443 -0.8067 +vn -0.3334 -0.7509 -0.5701 +vn 0.0630 0.9745 -0.2153 +vn 0.2234 0.8639 0.4514 +vn 0.8580 0.0302 0.5127 +vn 0.6218 0.7534 0.2140 +vn 0.6276 0.7583 0.1764 +vn -0.8016 0.4183 0.4271 +vn -0.7632 0.4419 0.4715 +vn -0.9898 -0.0884 0.1120 +vn -0.9558 0.2865 -0.0654 +vn -0.8792 0.4694 -0.0818 +vn -0.5851 0.6712 0.4552 +vn -0.7149 0.4411 0.5426 +vn -0.9859 0.1425 0.0881 +vn -0.8474 0.5137 0.1340 +vn -0.5264 0.2156 0.8224 +vn 0.0113 0.9711 -0.2383 +vn 0.0407 0.8083 0.5874 +vn 0.3515 0.2221 0.9095 +vn -0.3254 0.8416 -0.4310 +vn -0.1847 0.8966 -0.4024 +vn 0.5629 -0.6270 -0.5386 +vn -0.7913 0.3902 -0.4708 +vn -0.0725 -0.1969 -0.9777 +vn -0.5626 0.8128 -0.1511 +vn -0.0491 -0.0221 -0.9985 +vn 0.8924 0.2071 -0.4010 +vn -0.3784 0.4856 -0.7880 +vn -0.2706 0.5550 -0.7866 +vn 0.8993 0.3202 0.2978 +vn 0.4713 -0.5197 -0.7126 +vn -0.9419 0.3348 -0.0280 +vn 0.0121 0.9567 -0.2910 +vn 0.7856 -0.4888 -0.3794 +vn 0.1336 0.9677 -0.2138 +vn -0.6448 -0.2680 -0.7158 +vn -0.6428 -0.3061 -0.7022 +vn 0.7543 0.0375 0.6555 +vn 0.1225 0.2719 0.9545 +vn -0.9886 -0.0514 0.1413 +vn -0.1355 0.7124 0.6885 +vn -0.7468 0.0379 0.6640 +vn 0.9536 -0.2735 0.1261 +vn -0.9963 0.0406 0.0756 +vn -0.9882 -0.0972 -0.1180 +vn 0.9740 -0.0449 -0.2219 +vn -0.0581 -0.8284 0.5570 +vn 0.1606 0.6809 -0.7145 +vn -0.7809 -0.5836 -0.2225 +vn -0.7709 -0.6353 0.0472 +vn -0.5891 -0.0805 -0.8040 +vn -0.6572 -0.0797 -0.7495 +vn -0.7109 -0.0621 -0.7005 +vn 0.0599 0.4891 -0.8702 +vn 0.0417 0.9589 -0.2807 +vn -0.1842 -0.0213 -0.9827 +vn -0.1464 -0.1195 -0.9820 +vn -0.7061 -0.6773 -0.2067 +vn 0.6781 0.5056 0.5334 +vn -0.7814 0.1398 0.6082 +vn 0.7505 0.5897 0.2983 +vn 0.7047 0.3612 -0.6106 +vn -0.4122 -0.2300 -0.8816 +vn -0.6573 -0.2787 -0.7002 +vn 0.9808 -0.1945 0.0115 +vn -0.4130 -0.1046 -0.9047 +vn -0.9536 0.2735 0.1260 +vn 0.9014 0.4316 -0.0330 +vn 0.1608 0.9764 -0.1439 +vn -0.5201 -0.7835 0.3401 +vn 0.0527 -0.9965 0.0653 +vn -0.5332 0.3748 0.7585 +vn -0.6214 0.7675 -0.1572 +vn -0.7586 0.6346 -0.1479 +vn -0.8074 0.5776 -0.1202 +vn -0.6075 0.2148 -0.7647 +vn -0.9965 -0.0312 -0.0781 +vn -0.9992 -0.0017 -0.0394 +vn -0.9968 -0.0297 -0.0740 +vn 0.0384 0.9781 -0.2045 +vn 0.8870 -0.0135 -0.4616 +vn -0.9992 -0.0021 -0.0407 +vn -0.1941 -0.2128 0.9576 +vn 0.6406 0.6984 0.3192 +vn -0.8500 0.1631 0.5009 +vn -0.1724 -0.8391 -0.5159 +vn -0.5989 -0.6902 0.4061 +vn 0.3040 -0.4476 0.8410 +vn 0.4076 -0.9024 0.1397 +vn 0.0878 0.9724 -0.2160 +vn -0.7664 0.4600 -0.4484 +vn -0.5479 0.4819 -0.6838 +vn 0.6595 0.7292 0.1826 +vn 0.6259 -0.0541 0.7781 +vn 0.1717 0.7901 0.5884 +vn -0.1779 -0.1254 0.9760 +vn -0.9087 0.0867 -0.4083 +vn -0.1458 -0.1185 0.9822 +vn -0.9394 0.2262 0.2576 +vn -0.9456 0.1725 0.2758 +vn 0.6965 0.6974 0.1689 +vn 0.3696 -0.8682 -0.3312 +vn -0.3334 -0.7509 0.5701 +vn 0.0642 0.8896 0.4522 +vn 0.9272 -0.0213 -0.3740 +vn -0.0580 -0.8284 -0.5570 +vn -0.9916 -0.0140 -0.1289 +vn -0.3027 0.3244 0.8962 +vn -0.4746 0.1359 -0.8696 +vn -0.9836 0.1741 -0.0461 +vn -0.2674 -0.1071 -0.9576 +vn 0.0140 -0.1264 -0.9919 +vn 0.2630 -0.5440 0.7968 +vn 0.1386 0.5459 0.8263 +vn -0.2065 0.5462 -0.8118 +vn 0.0584 0.9911 -0.1197 +vn 0.6532 0.7430 0.1458 +vn 0.6591 0.7392 0.1385 +vn -0.8943 0.4310 -0.1201 +vn -0.6043 0.5205 0.6032 +vn -0.8072 0.1048 0.5809 +vn 0.5431 0.8298 -0.1279 +vn 0.6187 -0.6885 -0.3785 +vn 0.5223 0.0691 0.8499 +vn 0.7368 0.0330 0.6753 +vn 0.1743 0.9766 -0.1260 +vn -0.9880 0.0034 0.1544 +vn 0.9594 0.2815 -0.0166 +vn 0.9605 0.2736 -0.0509 +vn -0.0424 0.9807 -0.1910 +vn 0.0154 0.9903 -0.1379 +vn 0.9601 0.2784 -0.0252 +vn 0.9623 0.2703 -0.0306 +vn 0.9157 0.3921 -0.0881 +vn 0.9213 0.3752 -0.1024 +vn -0.2243 0.0190 -0.9743 +vn 0.5450 -0.1504 -0.8249 +vn -0.7204 0.5022 -0.4784 +vn -0.1303 0.8120 0.5689 +vn 0.8833 0.4675 0.0356 +vn 0.9242 0.3659 -0.1091 +vn 0.9294 0.3502 -0.1161 +vn 0.3090 -0.4514 0.8371 +vn -0.2527 0.1318 0.9585 +vn 0.0798 0.9711 -0.2250 +vn 0.6288 0.7675 0.1249 +vn -0.1480 0.0546 -0.9875 +vn 0.2137 0.8138 0.5404 +vn 0.9685 -0.0980 0.2291 +vn 0.6660 0.7343 0.1313 +vn 0.0449 0.9888 -0.1426 +vn 0.0555 0.9894 -0.1344 +vn -0.2700 -0.8225 0.5005 +vn 0.3957 -0.7553 -0.5225 +vn -0.7365 -0.4344 0.5185 +vn 0.1084 0.9845 -0.1381 +vn -0.9996 -0.0234 0.0174 +vn 0.9536 -0.2735 -0.1260 +vn 0.9536 -0.2735 -0.1261 +vn -0.9969 -0.0661 -0.0417 +vn -0.5448 0.8039 -0.2384 +vn 0.6222 -0.2277 -0.7490 +vn -0.9952 0.0544 -0.0817 +vn -0.9870 0.0060 0.1606 +vn -0.9876 0.0043 0.1570 +vn 0.3123 -0.1562 0.9370 +vn 0.2130 0.8262 0.5215 +vn -0.1271 0.1854 0.9744 +vn 0.9604 0.2775 -0.0263 +vn -0.1941 -0.2128 -0.9576 +vn 0.9616 0.2723 -0.0337 +vn 0.5605 -0.5159 -0.6479 +vn -0.0453 0.1696 0.9845 +vn -0.4734 0.1776 -0.8628 +vn -0.0565 -0.9972 -0.0486 +vn -0.0331 -0.9932 -0.1118 +vn -0.0281 -0.9985 -0.0466 +vn -0.4318 -0.6592 0.6156 +vn -0.5204 -0.7187 0.4611 +vn -0.4401 -0.7459 0.5000 +vn -0.4716 0.0403 0.8809 +vn -0.4706 0.0992 0.8768 +vn -0.5393 0.0670 0.8395 +vn -0.0983 -0.9859 0.1356 +vn -0.0466 -0.9878 0.1485 +vn -0.3126 -0.9107 0.2700 +vn -0.4905 -0.7993 0.3471 +vn -0.4502 -0.8650 0.2215 +vn -0.1730 -0.9790 0.1077 +vn -0.0897 -0.9947 -0.0494 +vn 0.9875 -0.1577 0.0042 +vn 0.9922 -0.1180 0.0389 +vn 0.9527 -0.3006 0.0437 +vn 0.9969 -0.0662 -0.0425 +vn 0.9855 -0.1608 -0.0534 +vn -0.0503 -0.1853 0.9814 +vn -0.0539 -0.2770 0.9594 +vn 0.0092 -0.2828 0.9591 +vn -0.1508 -0.7965 0.5856 +vn -0.1276 -0.8220 0.5550 +vn -0.1331 -0.7443 0.6545 +vn 0.7997 -0.5954 0.0778 +vn 0.5580 -0.8113 0.1744 +vn 0.5456 -0.8354 0.0665 +vn -0.8385 -0.5315 0.1199 +vn -0.8702 -0.4885 0.0647 +vn -0.8482 -0.5241 0.0769 +vn -0.2277 -0.8115 0.5381 +vn -0.2616 -0.7893 0.5556 +vn -0.2416 -0.7805 0.5766 +vn -0.6394 -0.0378 0.7680 +vn -0.6183 -0.1149 0.7775 +vn 0.5809 -0.7035 0.4095 +vn 0.5722 -0.7722 0.2763 +vn 0.8057 -0.5618 0.1875 +vn -0.2468 -0.8206 0.5154 +vn 0.0502 -0.8795 0.4733 +vn 0.1325 -0.8667 0.4810 +vn 0.0528 -0.8696 0.4909 +vn -0.2871 -0.9523 0.1031 +vn -0.4145 -0.9097 0.0239 +vn -0.3270 -0.9439 0.0467 +vn -0.0808 -0.9698 -0.2302 +vn -0.1311 -0.9809 -0.1439 +vn -0.0311 -0.9731 -0.2283 +vn 0.9873 0.0041 0.1587 +vn 0.9844 -0.0710 0.1610 +vn 0.9929 -0.0292 0.1154 +vn 0.0641 -0.2501 0.9661 +vn 0.1279 -0.3080 0.9428 +vn 0.0866 -0.2221 0.9712 +vn 0.0141 -0.8318 0.5549 +vn -0.0330 -0.8487 0.5278 +vn -0.0123 -0.8540 0.5202 +vn 0.9863 -0.0082 0.1649 +vn 0.9849 -0.0073 0.1729 +vn 0.9532 -0.0437 0.2993 +vn -0.0611 -0.4471 0.8924 +vn -0.1083 -0.8779 0.4665 +vn -0.1196 -0.8699 0.4786 +vn -0.1203 -0.8585 0.4986 +vn 0.6241 -0.7738 -0.1083 +vn 0.8316 -0.5535 -0.0462 +vn 0.6883 -0.7178 0.1044 +vn 0.3360 -0.1653 0.9272 +vn 0.2240 -0.1788 0.9580 +vn 0.5355 -0.1598 0.8293 +vn 0.9433 -0.3180 0.0954 +vn 0.9492 -0.2753 0.1523 +vn 0.8183 -0.4995 0.2844 +vn -0.0474 -0.7198 0.6926 +vn 0.0572 -0.5611 0.8258 +vn -0.0525 -0.6126 0.7886 +vn 0.0264 -0.9063 0.4219 +vn -0.0184 -0.8884 0.4588 +vn -0.0635 -0.9065 0.4175 +vn -0.1418 -0.8404 0.5231 +vn -0.1250 -0.8504 0.5111 +vn -0.0189 -0.9935 -0.1119 +vn 0.0187 -0.9987 -0.0476 +vn -0.0653 -0.9872 -0.1453 +vn -0.0314 -0.9725 -0.2309 +vn -0.0837 -0.9682 -0.2356 +vn -0.6868 -0.3470 0.6387 +vn -0.6138 -0.4142 0.6721 +vn -0.4964 -0.2614 0.8278 +vn 0.0179 -0.9901 0.1390 +vn 0.1069 -0.9920 -0.0666 +vn 0.1341 -0.9633 -0.2324 +vn -0.0072 -0.9909 -0.1345 +vn -0.0031 -0.9915 -0.1297 +vn -0.7352 -0.6343 0.2389 +vn -0.6945 -0.6908 0.2009 +vn -0.6167 -0.7457 0.2522 +vn 0.9887 -0.1182 0.0926 +vn -0.2754 -0.4163 0.8665 +vn -0.1875 -0.2845 0.9402 +vn -0.2418 -0.2544 0.9364 +vn -0.1212 -0.8514 0.5103 +vn -0.1220 -0.8959 0.4273 +vn -0.1063 -0.8906 0.4422 +vn -0.8953 -0.2634 0.3592 +vn -0.7996 -0.2080 0.5633 +vn -0.8210 -0.1497 0.5510 +vn 0.9643 -0.2451 -0.1005 +vn 0.9854 -0.1260 -0.1143 +vn -0.9408 -0.1514 0.3033 +vn -0.9680 -0.1886 0.1654 +vn -0.9485 -0.1889 0.2541 +vn -0.9055 -0.4210 -0.0527 +vn -0.9371 -0.3484 -0.0221 +vn -0.9103 -0.4079 -0.0709 +vn 0.9571 -0.2788 -0.0786 +vn -0.0326 -0.9706 -0.2386 +vn 0.0193 -0.9710 -0.2384 +vn -0.1047 -0.8031 0.5865 +vn 0.5510 -0.4087 0.7276 +vn 0.8072 -0.2121 0.5508 +vn 0.5363 -0.3123 0.7841 +vn -0.1732 -0.5937 0.7858 +vn -0.3021 -0.5692 0.7647 +vn -0.9725 -0.2316 -0.0250 +vn -0.9666 -0.2494 0.0596 +vn -0.2587 -0.1146 0.9591 +vn -0.2153 -0.0785 0.9734 +vn -0.2697 -0.0526 0.9615 +vn -0.3194 -0.0664 0.9453 +vn -0.3625 -0.1972 0.9109 +vn -0.3210 -0.2722 0.9071 +vn -0.9765 -0.1845 0.1111 +vn -0.7440 -0.6387 0.1961 +vn -0.1173 -0.8461 0.5200 +vn -0.1099 -0.8343 0.5403 +vn 0.9776 -0.1544 0.1429 +vn 0.1039 -0.4550 0.8844 +vn 0.6070 -0.7817 -0.1430 +vn 0.2172 -0.9218 0.3211 +vn 0.3800 -0.8342 0.3996 +vn 0.1290 -0.9320 0.3387 +vn -0.8087 -0.5432 0.2258 +vn -0.7928 -0.5810 0.1841 +vn -0.7736 -0.6037 0.1925 +vn -0.7507 -0.2656 0.6049 +vn -0.7473 -0.4445 0.4939 +vn 0.0043 -0.4571 0.8894 +vn 0.8130 -0.0827 0.5763 +vn -0.3646 -0.1016 0.9256 +vn -0.4348 -0.1089 0.8939 +vn 0.4270 -0.8860 -0.1810 +vn 0.5071 -0.7062 -0.4941 +vn 0.6281 -0.7559 -0.1848 +vn -0.8530 -0.1169 0.5087 +vn -0.7675 -0.5356 0.3523 +vn -0.6824 -0.6348 0.3625 +vn -0.6880 -0.5886 0.4245 +vn -0.4977 -0.4935 0.7133 +vn -0.4349 -0.3484 0.8304 +vn -0.3157 -0.8045 0.5031 +vn -0.3243 -0.7837 0.5297 +vn -0.3764 -0.7989 0.4691 +vn -0.9036 -0.4219 0.0744 +vn -0.8592 -0.4880 0.1535 +vn -0.8966 -0.4427 0.0003 +vn -0.8921 -0.4514 0.0200 +vn 0.1913 -0.9744 0.1185 +vn 0.2564 -0.3508 0.9007 +vn 0.2727 -0.4685 0.8403 +vn 0.3077 -0.9299 0.2015 +vn -0.2224 -0.9222 0.3165 +vn -0.3146 -0.8583 0.4054 +vn -0.2148 -0.8711 0.4417 +vn -0.2244 -0.8477 0.4806 +vn -0.2244 -0.8509 0.4750 +vn 0.3147 -0.6844 0.6577 +vn 0.3200 -0.7575 0.5690 +vn 0.5800 -0.6435 0.4995 +vn -0.1432 -0.9598 -0.2415 +vn -0.3167 -0.7661 0.5593 +vn 0.3977 -0.9173 0.0180 +vn 0.9450 -0.1150 0.3063 +vn -0.0583 -0.9904 -0.1251 +vn -0.0572 -0.9902 -0.1273 +vn -0.0586 -0.9897 -0.1309 +vn 0.0210 -0.9731 -0.2295 +vn 0.0756 -0.9720 -0.2226 +vn -0.0712 -0.8927 0.4450 +vn -0.1131 -0.8916 0.4384 +vn -0.1347 -0.9314 0.3383 +vn 0.8099 -0.1404 0.5695 +vn 0.6561 -0.2562 0.7098 +vn -0.3143 -0.8117 0.4923 +vn -0.3157 -0.8158 0.4846 +vn -0.2452 -0.8236 0.5115 +vn 0.1663 -0.9640 -0.2074 +vn -0.3686 0.0001 0.9296 +vn -0.0679 -0.7986 0.5980 +vn 0.0052 -0.7528 0.6583 +vn -0.5917 -0.7941 0.1392 +vn -0.5369 -0.8289 0.1570 +vn -0.6208 -0.7568 0.2047 +vn 0.2954 -0.5863 0.7543 +vn -0.0666 0.9968 0.0449 +vn 0.8171 -0.3401 0.4655 +vn -0.6669 -0.0059 0.7452 +vn -0.8299 -0.3707 0.4170 +vn -0.5382 -0.6150 0.5763 +vn -0.2761 -0.8500 0.4487 +vn -0.3136 -0.8366 0.4491 +vn -0.1086 -0.9868 -0.1201 +vn -0.1085 -0.9862 -0.1251 +vn -0.1086 -0.9869 -0.1196 +vn -0.2527 -0.6989 0.6691 +vn -0.3345 -0.6893 0.6426 +vn 0.0091 -0.9475 0.3196 +vn 0.5638 -0.4961 0.6603 +vn 0.0806 -0.9847 -0.1547 +vn 0.0790 -0.9850 -0.1533 +vn -0.1557 -0.4437 0.8826 +vn 0.0816 -0.9845 -0.1554 +vn -0.9295 -0.2177 0.2976 +vn 0.2568 -0.9443 -0.2057 +vn 0.1653 -0.9715 -0.1701 +vn 0.2597 -0.9403 -0.2200 +vn -0.1544 -0.8933 0.4221 +vn 0.0213 -0.9925 -0.1200 +vn 0.0443 -0.9923 -0.1158 +vn -0.2285 -0.8374 0.4965 +vn -0.2406 -0.8298 0.5036 +vn -0.1657 -0.9848 -0.0519 +vn -0.1900 -0.9788 -0.0761 +vn -0.2857 -0.9524 0.1063 +vn 0.9086 -0.4176 0.0061 +vn 0.7905 -0.6124 0.0099 +vn 0.5185 -0.8533 0.0550 +vn 0.5681 -0.0691 0.8200 +vn 0.4408 -0.1305 0.8881 +vn -0.2484 -0.9666 -0.0626 +vn -0.3530 -0.8960 -0.2693 +vn -0.1714 -0.9764 -0.1318 +vn 0.0700 -0.9873 -0.1428 +vn 0.0830 -0.9842 -0.1561 +vn -0.5788 -0.1990 0.7908 +vn 0.2319 -0.8764 0.4222 +vn 0.3392 -0.8880 0.3105 +vn 0.9994 -0.0251 0.0240 +vn -0.8866 -0.2304 0.4011 +vn -0.2253 -0.8422 0.4898 +vn -0.2207 -0.8361 0.5023 +vn 0.5870 -0.5724 0.5725 +vn 0.8442 -0.4147 0.3396 +vn -0.0578 -0.9912 -0.1192 +vn -0.0591 -0.9920 -0.1118 +vn -0.0542 -0.9922 -0.1121 +vn -0.4578 -0.0544 0.8874 +vn -0.1348 -0.9900 -0.0424 +vn -0.1151 -0.9899 -0.0825 +vn -0.0393 -0.8456 0.5323 +vn -0.0423 -0.8408 0.5397 +vn 0.1118 -0.9804 -0.1620 +vn 0.0899 -0.9832 -0.1586 +vn -0.1902 -0.8894 0.4156 +vn 0.0242 -0.8852 0.4646 +vn -0.1374 -0.9832 -0.1200 +vn -0.7168 -0.6761 0.1705 +vn -0.7300 -0.6524 0.2036 +vn 0.3203 -0.8150 0.4829 +vn -0.9850 -0.1635 0.0553 +vn -0.9863 -0.1633 0.0253 +vn -0.6330 -0.7540 0.1755 +vn 0.8833 -0.4602 -0.0892 +vn 0.7892 -0.5954 -0.1503 +vn -0.8859 -0.4227 0.1912 +vn -0.8293 -0.4807 0.2850 +vn -0.9359 -0.3129 0.1620 +vn -0.8869 -0.3798 0.2629 +vn -0.7114 -0.5099 0.4835 +vn -0.7899 -0.4754 0.3875 +vn -0.1474 -0.8219 0.5503 +vn -0.1459 -0.8342 0.5317 +vn -0.1612 -0.9060 0.3914 +vn -0.3870 -0.5010 0.7741 +vn -0.2047 -0.7836 0.5865 +vn -0.2226 -0.7714 0.5962 +vn -0.1909 -0.7240 0.6628 +vn 0.9687 -0.0061 0.2482 +vn 0.8686 -0.1218 0.4804 +vn -0.6056 -0.5549 0.5704 +vn -0.5946 -0.6867 0.4181 +vn -0.0454 -0.9927 -0.1117 +vn 0.0293 -0.1789 0.9834 +vn 0.0514 -0.3185 0.9465 +vn 0.2362 -0.2275 0.9447 +vn -0.3324 -0.8280 0.4515 +vn -0.3200 -0.8197 0.4751 +vn -0.2350 -0.9404 -0.2457 +vn -0.8927 -0.1671 0.4185 +vn -0.8252 -0.0625 0.5614 +vn -0.8115 -0.5660 0.1453 +vn -0.8280 -0.5523 0.0968 +vn 0.9997 0.0039 -0.0225 +vn 0.9995 -0.0034 -0.0300 +vn -0.0694 -0.9962 -0.0533 +vn -0.0588 -0.9915 -0.1161 +vn -0.1087 -0.9876 -0.1132 +vn -0.1086 -0.9877 -0.1126 +vn -0.1087 -0.9888 -0.1021 +vn -0.1065 -0.9897 -0.0957 +vn 0.2473 -0.9654 -0.0831 +vn 0.0836 -0.9764 -0.1991 +vn -0.1085 -0.9855 -0.1305 +vn 0.9933 0.0329 0.1104 +vn 0.9969 0.0427 0.0655 +vn 0.0093 -0.9925 -0.1220 +vn 0.0067 -0.9927 -0.1205 +vn -0.4664 -0.8781 0.1067 +vn -0.4584 -0.8885 0.0205 +vn -0.3050 -0.9520 0.0274 +vn -0.2589 -0.9639 0.0622 +vn -0.3066 -0.7910 0.5295 +vn 0.1178 -0.9839 0.1342 +vn -0.2339 -0.8653 0.4433 +vn 0.2864 -0.9572 0.0407 +vn -0.1305 -0.9637 -0.2329 +vn -0.1886 -0.9503 -0.2475 +vn 0.1566 0.0442 -0.9867 +vn 0.1554 0.0454 -0.9868 +vn 0.2043 -0.0003 -0.9789 +vn -0.0719 -0.9909 -0.1136 +vn -0.1647 -0.1380 0.9766 +vn -0.1089 -0.1730 0.9789 +vn 0.6062 -0.1058 0.7882 +vn -0.1087 -0.9889 -0.1009 +vn -0.1086 -0.9861 -0.1255 +vn -0.0932 -0.9902 -0.1038 +vn -0.2234 -0.8639 0.4514 +vn -0.6218 -0.7534 0.2140 +vn -0.6276 -0.7583 0.1764 +vn 0.9898 0.0884 0.1120 +vn 0.9558 -0.2865 -0.0654 +vn 0.8792 -0.4694 -0.0818 +vn 0.5851 -0.6712 0.4551 +vn 0.7149 -0.4411 0.5426 +vn 0.8474 -0.5137 0.1340 +vn 0.5264 -0.2156 0.8224 +vn 0.0093 -0.9925 -0.1221 +vn -0.0407 -0.8083 0.5874 +vn 0.4192 -0.8926 -0.1658 +vn 0.2478 -0.9401 -0.2342 +vn 0.7912 -0.3904 -0.4707 +vn 0.0725 0.1969 -0.9777 +vn 0.5626 -0.8128 -0.1511 +vn 0.0491 0.0221 -0.9985 +vn -0.8993 -0.3202 0.2978 +vn 0.9419 -0.3348 -0.0280 +vn 0.0872 -0.9836 -0.1578 +vn -0.0078 -0.9934 -0.1145 +vn -0.7543 -0.0375 0.6555 +vn -0.1225 -0.2719 0.9545 +vn 0.9886 0.0514 0.1413 +vn 0.1355 -0.7124 0.6885 +vn 0.0849 -0.9839 -0.1570 +vn -0.6781 -0.5056 0.5334 +vn -0.7505 -0.5897 0.2983 +vn -0.9014 -0.4316 -0.0330 +vn -0.2621 -0.9284 -0.2632 +vn 0.6214 -0.7675 -0.1572 +vn 0.7586 -0.6346 -0.1479 +vn 0.8074 -0.5776 -0.1202 +vn 0.9965 0.0312 -0.0781 +vn 0.9992 0.0017 -0.0394 +vn 0.9968 0.0297 -0.0739 +vn -0.1452 -0.9821 -0.1199 +vn 0.9992 0.0021 -0.0407 +vn -0.6406 -0.6984 0.3192 +vn -0.0833 -0.9905 -0.1096 +vn -0.6595 -0.7292 0.1826 +vn -0.6259 0.0541 0.7781 +vn -0.1717 -0.7901 0.5884 +vn 0.9394 -0.2262 0.2576 +vn 0.9456 -0.1725 0.2758 +vn -0.6965 -0.6974 0.1689 +vn -0.0642 -0.8896 0.4522 +vn -0.0584 -0.9911 -0.1197 +vn -0.6532 -0.7430 0.1458 +vn -0.6591 -0.7392 0.1385 +vn 0.8943 -0.4310 -0.1201 +vn -0.1743 -0.9766 -0.1260 +vn 0.9880 -0.0034 0.1544 +vn -0.9594 -0.2815 -0.0166 +vn -0.9605 -0.2736 -0.0509 +vn -0.1487 -0.9811 -0.1237 +vn 0.0733 -0.9686 -0.2377 +vn -0.9601 -0.2784 -0.0252 +vn -0.9623 -0.2703 -0.0306 +vn -0.9157 -0.3921 -0.0881 +vn -0.9213 -0.3752 -0.1024 +vn 0.2242 -0.0191 -0.9744 +vn 0.1303 -0.8120 0.5689 +vn -0.8833 -0.4675 0.0356 +vn -0.9242 -0.3659 -0.1091 +vn -0.9294 -0.3502 -0.1161 +vn 0.0550 -0.9909 -0.1229 +vn -0.2137 -0.8138 0.5404 +vn -0.6660 -0.7343 0.1314 +vn -0.0892 -0.9683 -0.2332 +vn -0.1720 -0.9576 -0.2309 +vn 0.0135 -0.9757 -0.2188 +vn 0.9996 0.0234 0.0174 +vn 0.9969 0.0661 -0.0417 +vn 0.5449 -0.8039 -0.2384 +vn 0.9952 -0.0544 -0.0817 +vn 0.9870 -0.0060 0.1606 +vn 0.9876 -0.0043 0.1570 +vn -0.6963 0.1741 -0.6963 +vn -0.2130 -0.8263 0.5215 +vn 0.1271 -0.1854 0.9744 +vn -0.9604 -0.2775 -0.0263 +vn -0.9616 -0.2723 -0.0337 +vn 0.0453 -0.1696 0.9845 +vn -0.0565 -0.9972 0.0486 +vn -0.0281 -0.9985 0.0466 +vn -0.0331 -0.9932 0.1118 +vn -0.4318 -0.6592 -0.6156 +vn -0.4401 -0.7459 -0.5000 +vn -0.5204 -0.7187 -0.4611 +vn -0.4716 0.0403 -0.8809 +vn -0.5393 0.0670 -0.8395 +vn -0.4706 0.0992 -0.8768 +vn -0.0983 -0.9859 -0.1356 +vn -0.0466 -0.9878 -0.1485 +vn -0.3126 -0.9107 -0.2700 +vn -0.4502 -0.8650 -0.2215 +vn -0.4905 -0.7993 -0.3471 +vn -0.1730 -0.9790 -0.1077 +vn -0.0897 -0.9947 0.0494 +vn 0.9875 -0.1577 -0.0042 +vn 0.9527 -0.3006 -0.0437 +vn 0.9922 -0.1180 -0.0389 +vn 0.9969 -0.0662 0.0425 +vn 0.9855 -0.1608 0.0534 +vn -0.0503 -0.1853 -0.9814 +vn 0.0092 -0.2828 -0.9591 +vn -0.0539 -0.2770 -0.9594 +vn -0.1508 -0.7965 -0.5856 +vn -0.1331 -0.7443 -0.6545 +vn -0.1276 -0.8220 -0.5550 +vn 0.7997 -0.5954 -0.0778 +vn 0.5456 -0.8354 -0.0665 +vn 0.5580 -0.8113 -0.1744 +vn -0.8385 -0.5315 -0.1199 +vn -0.8482 -0.5241 -0.0769 +vn -0.8702 -0.4885 -0.0647 +vn -0.2277 -0.8115 -0.5381 +vn -0.2416 -0.7805 -0.5766 +vn -0.2616 -0.7893 -0.5556 +vn -0.6183 -0.1149 -0.7775 +vn -0.6394 -0.0378 -0.7680 +vn 0.5809 -0.7035 -0.4095 +vn 0.8057 -0.5618 -0.1875 +vn 0.5722 -0.7722 -0.2763 +vn -0.2468 -0.8206 -0.5154 +vn 0.0502 -0.8795 -0.4733 +vn 0.0528 -0.8696 -0.4909 +vn 0.1325 -0.8667 -0.4810 +vn -0.2871 -0.9523 -0.1031 +vn -0.4145 -0.9097 -0.0239 +vn -0.3270 -0.9439 -0.0467 +vn -0.0808 -0.9698 0.2302 +vn -0.0311 -0.9731 0.2283 +vn -0.1311 -0.9809 0.1439 +vn 0.9873 0.0041 -0.1587 +vn 0.9929 -0.0292 -0.1154 +vn 0.9844 -0.0710 -0.1610 +vn 0.0641 -0.2501 -0.9661 +vn 0.0866 -0.2221 -0.9712 +vn 0.1279 -0.3080 -0.9428 +vn 0.0141 -0.8318 -0.5549 +vn -0.0122 -0.8540 -0.5202 +vn -0.0330 -0.8487 -0.5278 +vn 0.9863 -0.0082 -0.1649 +vn 0.9532 -0.0437 -0.2993 +vn 0.9849 -0.0073 -0.1729 +vn -0.0611 -0.4471 -0.8924 +vn -0.1083 -0.8779 -0.4665 +vn -0.1203 -0.8585 -0.4986 +vn -0.1196 -0.8699 -0.4786 +vn 0.6241 -0.7738 0.1083 +vn 0.6883 -0.7178 -0.1044 +vn 0.8316 -0.5535 0.0462 +vn 0.3360 -0.1653 -0.9272 +vn 0.5355 -0.1598 -0.8293 +vn 0.2240 -0.1788 -0.9580 +vn 0.9433 -0.3180 -0.0954 +vn 0.8183 -0.4995 -0.2844 +vn 0.9492 -0.2753 -0.1523 +vn -0.0474 -0.7198 -0.6926 +vn -0.0525 -0.6126 -0.7886 +vn 0.0572 -0.5611 -0.8258 +vn 0.0264 -0.9063 -0.4219 +vn -0.0635 -0.9065 -0.4175 +vn -0.0184 -0.8884 -0.4588 +vn -0.1250 -0.8504 -0.5111 +vn -0.1418 -0.8404 -0.5231 +vn 0.0187 -0.9987 0.0476 +vn -0.0189 -0.9935 0.1119 +vn -0.0653 -0.9872 0.1453 +vn -0.0837 -0.9682 0.2356 +vn -0.0314 -0.9725 0.2309 +vn -0.6868 -0.3470 -0.6387 +vn -0.4964 -0.2614 -0.8278 +vn -0.6138 -0.4142 -0.6721 +vn 0.0179 -0.9901 -0.1390 +vn 0.1069 -0.9920 0.0666 +vn 0.1341 -0.9633 0.2324 +vn -0.0031 -0.9915 0.1297 +vn -0.0072 -0.9909 0.1345 +vn -0.7352 -0.6343 -0.2389 +vn -0.6167 -0.7457 -0.2522 +vn -0.6945 -0.6908 -0.2009 +vn 0.9887 -0.1182 -0.0926 +vn -0.2754 -0.4163 -0.8665 +vn -0.2418 -0.2544 -0.9364 +vn -0.1875 -0.2845 -0.9402 +vn -0.1212 -0.8514 -0.5103 +vn -0.1220 -0.8959 -0.4273 +vn -0.1063 -0.8906 -0.4422 +vn -0.8953 -0.2634 -0.3592 +vn -0.8210 -0.1497 -0.5510 +vn -0.7996 -0.2080 -0.5633 +vn 0.9854 -0.1260 0.1143 +vn 0.9643 -0.2451 0.1005 +vn -0.9408 -0.1514 -0.3033 +vn -0.9485 -0.1889 -0.2541 +vn -0.9680 -0.1886 -0.1654 +vn -0.9055 -0.4210 0.0527 +vn -0.9103 -0.4079 0.0709 +vn -0.9371 -0.3484 0.0221 +vn 0.9571 -0.2788 0.0786 +vn -0.0326 -0.9706 0.2386 +vn 0.0193 -0.9710 0.2384 +vn -0.1047 -0.8031 -0.5865 +vn 0.5510 -0.4087 -0.7276 +vn 0.5363 -0.3123 -0.7841 +vn 0.8072 -0.2121 -0.5508 +vn -0.1732 -0.5937 -0.7858 +vn -0.3021 -0.5692 -0.7647 +vn -0.9725 -0.2316 0.0250 +vn -0.9666 -0.2494 -0.0596 +vn -0.2587 -0.1146 -0.9591 +vn -0.2697 -0.0526 -0.9615 +vn -0.2153 -0.0785 -0.9734 +vn -0.3194 -0.0664 -0.9453 +vn -0.3210 -0.2722 -0.9071 +vn -0.3625 -0.1972 -0.9109 +vn -0.9765 -0.1845 -0.1111 +vn -0.7440 -0.6387 -0.1961 +vn -0.1099 -0.8343 -0.5403 +vn -0.1173 -0.8461 -0.5200 +vn 0.9776 -0.1544 -0.1429 +vn 0.1039 -0.4550 -0.8844 +vn 0.6070 -0.7817 0.1430 +vn 0.2172 -0.9218 -0.3211 +vn 0.1290 -0.9320 -0.3387 +vn 0.3800 -0.8342 -0.3996 +vn -0.8087 -0.5432 -0.2258 +vn -0.7736 -0.6037 -0.1925 +vn -0.7928 -0.5810 -0.1841 +vn -0.7507 -0.2656 -0.6049 +vn -0.7473 -0.4445 -0.4939 +vn 0.0043 -0.4571 -0.8894 +vn 0.8130 -0.0827 -0.5763 +vn -0.4348 -0.1089 -0.8939 +vn -0.3646 -0.1016 -0.9256 +vn 0.4270 -0.8860 0.1810 +vn 0.6281 -0.7559 0.1848 +vn 0.5071 -0.7062 0.4941 +vn -0.8530 -0.1169 -0.5087 +vn -0.7675 -0.5356 -0.3523 +vn -0.6880 -0.5886 -0.4245 +vn -0.6824 -0.6348 -0.3625 +vn -0.4977 -0.4935 -0.7133 +vn -0.4349 -0.3484 -0.8304 +vn -0.3157 -0.8045 -0.5031 +vn -0.3764 -0.7989 -0.4691 +vn -0.3243 -0.7837 -0.5297 +vn -0.9036 -0.4219 -0.0744 +vn -0.8592 -0.4880 -0.1535 +vn -0.8966 -0.4427 -0.0003 +vn -0.8921 -0.4514 -0.0200 +vn 0.1913 -0.9744 -0.1185 +vn 0.2727 -0.4685 -0.8403 +vn 0.2564 -0.3508 -0.9007 +vn 0.3077 -0.9299 -0.2015 +vn -0.3146 -0.8583 -0.4054 +vn -0.2224 -0.9222 -0.3165 +vn -0.2148 -0.8711 -0.4417 +vn -0.2243 -0.8509 -0.4750 +vn -0.2244 -0.8477 -0.4806 +vn 0.3147 -0.6844 -0.6577 +vn 0.5800 -0.6435 -0.4995 +vn 0.3200 -0.7575 -0.5690 +vn -0.1432 -0.9598 0.2415 +vn -0.3167 -0.7661 -0.5593 +vn 0.3977 -0.9173 -0.0180 +vn 0.9450 -0.1150 -0.3063 +vn -0.0583 -0.9904 0.1252 +vn -0.0586 -0.9897 0.1309 +vn -0.0572 -0.9902 0.1273 +vn 0.0210 -0.9731 0.2295 +vn 0.0756 -0.9720 0.2226 +vn -0.0712 -0.8927 -0.4450 +vn -0.1347 -0.9314 -0.3383 +vn -0.1131 -0.8916 -0.4384 +vn 0.6561 -0.2562 -0.7098 +vn 0.8099 -0.1404 -0.5695 +vn -0.3143 -0.8117 -0.4923 +vn -0.3157 -0.8158 -0.4846 +vn -0.2452 -0.8236 -0.5115 +vn 0.1663 -0.9640 0.2074 +vn -0.3686 0.0001 -0.9296 +vn 0.0052 -0.7528 -0.6583 +vn -0.0679 -0.7986 -0.5980 +vn -0.5917 -0.7941 -0.1392 +vn -0.6208 -0.7568 -0.2047 +vn -0.5369 -0.8289 -0.1570 +vn 0.2954 -0.5863 -0.7543 +vn -0.0666 0.9968 -0.0449 +vn 0.8171 -0.3401 -0.4655 +vn -0.6669 -0.0059 -0.7452 +vn -0.8299 -0.3707 -0.4170 +vn -0.5382 -0.6150 -0.5763 +vn -0.3136 -0.8366 -0.4491 +vn -0.2761 -0.8500 -0.4487 +vn -0.1086 -0.9868 0.1201 +vn -0.1086 -0.9869 0.1196 +vn -0.1085 -0.9862 0.1251 +vn -0.2527 -0.6989 -0.6691 +vn -0.3345 -0.6893 -0.6426 +vn 0.0091 -0.9475 -0.3196 +vn 0.5638 -0.4961 -0.6603 +vn 0.0806 -0.9847 0.1547 +vn 0.0790 -0.9850 0.1533 +vn -0.1557 -0.4437 -0.8826 +vn 0.0816 -0.9845 0.1554 +vn -0.9295 -0.2177 -0.2976 +vn 0.2568 -0.9443 0.2056 +vn 0.2597 -0.9403 0.2199 +vn 0.1653 -0.9715 0.1701 +vn -0.1544 -0.8933 -0.4221 +vn 0.0443 -0.9923 0.1158 +vn 0.0213 -0.9925 0.1200 +vn -0.2285 -0.8374 -0.4965 +vn -0.2406 -0.8298 -0.5036 +vn -0.1657 -0.9848 0.0519 +vn -0.2861 -0.9523 -0.1064 +vn -0.1900 -0.9788 0.0761 +vn 0.9086 -0.4176 -0.0061 +vn 0.7905 -0.6124 -0.0099 +vn 0.5185 -0.8533 -0.0550 +vn 0.5681 -0.0691 -0.8200 +vn 0.4408 -0.1305 -0.8881 +vn -0.2484 -0.9666 0.0626 +vn -0.1714 -0.9764 0.1318 +vn -0.3530 -0.8960 0.2693 +vn 0.0700 -0.9873 0.1428 +vn 0.0830 -0.9842 0.1561 +vn -0.5788 -0.1990 -0.7908 +vn 0.2319 -0.8764 -0.4222 +vn 0.3392 -0.8880 -0.3105 +vn 0.9994 -0.0251 -0.0240 +vn -0.8866 -0.2304 -0.4011 +vn -0.2253 -0.8422 -0.4898 +vn -0.2207 -0.8361 -0.5023 +vn 0.5870 -0.5724 -0.5725 +vn 0.8442 -0.4147 -0.3396 +vn -0.0578 -0.9912 0.1192 +vn -0.0542 -0.9922 0.1121 +vn -0.0591 -0.9920 0.1119 +vn -0.4578 -0.0544 -0.8874 +vn -0.1348 -0.9900 0.0424 +vn -0.1151 -0.9899 0.0825 +vn -0.0393 -0.8456 -0.5323 +vn -0.0423 -0.8408 -0.5397 +vn 0.1118 -0.9804 0.1620 +vn 0.0899 -0.9832 0.1586 +vn -0.1902 -0.8894 -0.4156 +vn 0.0242 -0.8852 -0.4646 +vn -0.1374 -0.9832 0.1200 +vn -0.7168 -0.6761 -0.1705 +vn -0.7300 -0.6524 -0.2036 +vn 0.3203 -0.8150 -0.4829 +vn -0.9863 -0.1633 -0.0253 +vn -0.9850 -0.1635 -0.0553 +vn -0.6330 -0.7540 -0.1755 +vn 0.8833 -0.4602 0.0892 +vn 0.7892 -0.5954 0.1503 +vn -0.8859 -0.4227 -0.1912 +vn -0.8293 -0.4807 -0.2850 +vn -0.9359 -0.3129 -0.1620 +vn -0.8869 -0.3798 -0.2629 +vn -0.7899 -0.4754 -0.3875 +vn -0.7114 -0.5099 -0.4835 +vn -0.1459 -0.8342 -0.5317 +vn -0.1474 -0.8219 -0.5503 +vn -0.1612 -0.9060 -0.3914 +vn -0.3870 -0.5010 -0.7741 +vn -0.2047 -0.7836 -0.5865 +vn -0.2226 -0.7714 -0.5962 +vn -0.1909 -0.7240 -0.6628 +vn 0.9687 -0.0061 -0.2482 +vn 0.8686 -0.1218 -0.4804 +vn -0.5946 -0.6867 -0.4181 +vn -0.6056 -0.5549 -0.5704 +vn -0.0454 -0.9927 0.1117 +vn 0.0293 -0.1789 -0.9834 +vn 0.0514 -0.3185 -0.9465 +vn 0.2362 -0.2275 -0.9447 +vn -0.3200 -0.8197 -0.4751 +vn -0.3324 -0.8280 -0.4515 +vn -0.2350 -0.9404 0.2457 +vn -0.8927 -0.1671 -0.4185 +vn -0.8252 -0.0625 -0.5614 +vn -0.8115 -0.5660 -0.1453 +vn -0.8280 -0.5523 -0.0968 +vn 0.9997 0.0039 0.0225 +vn 0.9995 -0.0034 0.0300 +vn -0.0694 -0.9962 0.0533 +vn -0.0588 -0.9915 0.1161 +vn -0.1087 -0.9876 0.1132 +vn -0.1087 -0.9888 0.1021 +vn -0.1086 -0.9877 0.1126 +vn -0.1065 -0.9897 0.0957 +vn 0.2473 -0.9654 0.0831 +vn 0.0836 -0.9764 0.1991 +vn -0.1085 -0.9855 0.1305 +vn 0.9933 0.0329 -0.1104 +vn 0.9969 0.0427 -0.0655 +vn 0.0093 -0.9925 0.1220 +vn 0.0067 -0.9927 0.1205 +vn -0.4664 -0.8781 -0.1067 +vn -0.4584 -0.8885 -0.0205 +vn -0.3050 -0.9520 -0.0274 +vn -0.2589 -0.9639 -0.0622 +vn -0.3066 -0.7910 -0.5295 +vn 0.1178 -0.9839 -0.1342 +vn -0.2339 -0.8653 -0.4433 +vn 0.2864 -0.9572 -0.0407 +vn -0.1886 -0.9503 0.2475 +vn -0.1305 -0.9637 0.2329 +vn 0.1566 0.0442 0.9867 +vn 0.2043 -0.0003 0.9789 +vn 0.1554 0.0454 0.9868 +vn -0.0719 -0.9909 0.1136 +vn -0.1647 -0.1380 -0.9766 +vn -0.1089 -0.1730 -0.9789 +vn 0.6062 -0.1058 -0.7882 +vn -0.1087 -0.9889 0.1009 +vn -0.1086 -0.9861 0.1255 +vn -0.0932 -0.9902 0.1038 +vn -0.2234 -0.8639 -0.4514 +vn -0.6218 -0.7534 -0.2140 +vn -0.6276 -0.7583 -0.1764 +vn 0.9898 0.0884 -0.1120 +vn 0.9558 -0.2865 0.0654 +vn 0.8792 -0.4694 0.0818 +vn 0.5851 -0.6712 -0.4551 +vn 0.7149 -0.4411 -0.5426 +vn 0.8474 -0.5137 -0.1340 +vn 0.5264 -0.2156 -0.8224 +vn 0.0093 -0.9925 0.1221 +vn -0.0407 -0.8083 -0.5874 +vn 0.4192 -0.8926 0.1658 +vn 0.2478 -0.9401 0.2342 +vn 0.7912 -0.3904 0.4707 +vn 0.0725 0.1969 0.9777 +vn 0.5626 -0.8128 0.1511 +vn 0.0491 0.0221 0.9985 +vn -0.8993 -0.3202 -0.2978 +vn 0.9419 -0.3348 0.0280 +vn 0.0872 -0.9836 0.1578 +vn -0.0078 -0.9934 0.1145 +vn -0.7543 -0.0375 -0.6555 +vn -0.1225 -0.2719 -0.9545 +vn 0.9886 0.0514 -0.1413 +vn 0.1355 -0.7124 -0.6885 +vn 0.0849 -0.9839 0.1570 +vn -0.6781 -0.5056 -0.5334 +vn -0.7505 -0.5897 -0.2983 +vn -0.9014 -0.4316 0.0330 +vn -0.2621 -0.9285 0.2632 +vn 0.6214 -0.7675 0.1572 +vn 0.8074 -0.5776 0.1202 +vn 0.7586 -0.6346 0.1479 +vn 0.9965 0.0312 0.0781 +vn 0.9968 0.0297 0.0739 +vn 0.9992 0.0017 0.0394 +vn -0.1452 -0.9821 0.1199 +vn 0.9992 0.0021 0.0407 +vn -0.6406 -0.6984 -0.3192 +vn -0.0833 -0.9905 0.1096 +vn -0.6595 -0.7292 -0.1826 +vn -0.6259 0.0541 -0.7781 +vn -0.1717 -0.7901 -0.5884 +vn 0.9394 -0.2262 -0.2576 +vn 0.9456 -0.1725 -0.2758 +vn -0.6965 -0.6974 -0.1689 +vn -0.0642 -0.8896 -0.4522 +vn -0.0584 -0.9911 0.1197 +vn -0.6591 -0.7392 -0.1385 +vn -0.6532 -0.7430 -0.1458 +vn 0.8943 -0.4310 0.1201 +vn -0.1743 -0.9766 0.1260 +vn 0.9880 -0.0034 -0.1544 +vn -0.9594 -0.2815 0.0166 +vn -0.9605 -0.2736 0.0509 +vn -0.1487 -0.9811 0.1237 +vn 0.0733 -0.9686 0.2377 +vn -0.9601 -0.2784 0.0252 +vn -0.9623 -0.2703 0.0306 +vn -0.9157 -0.3921 0.0881 +vn -0.9213 -0.3752 0.1024 +vn 0.2242 -0.0191 0.9744 +vn 0.1303 -0.8120 -0.5689 +vn -0.8833 -0.4675 -0.0356 +vn -0.9242 -0.3659 0.1091 +vn -0.9294 -0.3502 0.1161 +vn 0.0550 -0.9909 0.1229 +vn -0.2137 -0.8138 -0.5404 +vn -0.6660 -0.7343 -0.1314 +vn -0.0892 -0.9683 0.2332 +vn -0.1720 -0.9576 0.2309 +vn 0.0135 -0.9757 0.2188 +vn 0.9996 0.0234 -0.0174 +vn 0.9969 0.0661 0.0417 +vn 0.5449 -0.8039 0.2384 +vn 0.9952 -0.0544 0.0817 +vn 0.9870 -0.0060 -0.1606 +vn 0.9876 -0.0043 -0.1570 +vn -0.6963 0.1741 0.6963 +vn -0.2130 -0.8263 -0.5215 +vn 0.1271 -0.1854 -0.9744 +vn -0.9604 -0.2775 0.0263 +vn -0.9616 -0.2723 0.0337 +vn 0.0453 -0.1696 -0.9845 +vn -0.6893 -0.7210 0.0699 +vn -0.6932 -0.7169 0.0747 +vn -0.7193 -0.6860 0.1096 +vn -0.7125 -0.6945 0.1002 +vn 0.8478 -0.4453 0.2881 +vn 0.8536 -0.4292 0.2954 +vn 0.7998 -0.5511 0.2380 +vn 0.7946 -0.5606 0.2332 +vn 0.7822 0.3869 -0.4884 +vn 0.8000 0.3391 -0.4950 +vn 0.8440 0.1794 -0.5055 +vn 0.8247 0.2598 -0.5023 +vn 0.5823 0.7784 -0.2347 +vn 0.4597 0.8416 -0.2837 +vn 0.3422 0.8818 -0.3246 +vn -0.2090 0.9198 -0.3322 +vn -0.0922 0.9352 -0.3418 +vn -0.6894 -0.7210 -0.0699 +vn -0.6932 -0.7169 -0.0747 +vn -0.6688 -0.7421 -0.0456 +vn -0.6650 -0.7457 -0.0414 +vn 0.2910 0.9463 0.1407 +vn 0.3092 0.9404 0.1413 +vn 0.1401 0.9811 0.1334 +vn 0.1424 0.9808 0.1335 +vn -0.4039 -0.8976 0.1769 +vn -0.4037 -0.8976 0.1770 +vn -0.3993 -0.8989 0.1801 +vn -0.3965 -0.8998 0.1819 +vn -0.6525 -0.7573 -0.0274 +vn -0.6309 -0.7759 -0.0053 +vn -0.6267 -0.7792 -0.0011 +vn 0.0915 -0.6852 0.7226 +vn -0.0106 -0.5789 0.8153 +vn -0.2326 -0.2798 0.9314 +vn -0.1532 -0.3983 0.9044 +vn 0.2936 0.9471 -0.1294 +vn 0.3306 0.9301 -0.1603 +vn 0.3800 0.9027 -0.2020 +vn 0.7040 0.5493 0.4501 +vn 0.7130 0.5334 0.4552 +vn 0.6753 0.5972 0.4329 +vn 0.6695 0.6062 0.4293 +vn -0.0053 -0.9887 -0.1497 +vn -0.0185 -0.9885 -0.1498 +vn 0.2359 -0.9611 -0.1439 +vn 0.3149 -0.9387 -0.1403 +vn 0.4399 0.8618 -0.2525 +vn 0.4631 0.8436 -0.2718 +vn 0.6263 -0.7786 -0.0396 +vn 0.7585 -0.6109 -0.2271 +vn 0.7960 -0.5254 -0.3007 +vn 0.2872 -0.8326 0.4736 +vn 0.2179 -0.7898 0.5734 +vn -0.0862 -0.9293 0.3592 +vn -0.2769 -0.8871 0.3692 +vn -0.4040 0.0551 -0.9131 +vn -0.4098 0.0786 -0.9088 +vn -0.3619 -0.0509 -0.9308 +vn -0.3299 -0.1129 -0.9372 +vn 0.4810 0.8173 -0.3172 +vn 0.5073 0.7893 -0.3459 +vn 0.4247 0.8675 -0.2591 +vn 0.3785 0.9006 -0.2136 +vn 0.4782 -0.8206 0.3131 +vn 0.4368 -0.8406 0.3204 +vn 0.7683 0.3681 0.5236 +vn 0.7422 0.4231 0.5197 +vn 0.8065 0.2688 0.5266 +vn 0.8354 0.1643 0.5245 +vn 0.2936 0.9471 0.1294 +vn 0.2127 0.9752 0.0607 +vn 0.2691 0.9570 0.1085 +vn 0.4390 0.8428 -0.3113 +vn 0.8203 0.5378 -0.1946 +vn 0.5341 0.7933 -0.2923 +vn -0.0348 -0.9841 0.1741 +vn -0.0390 -0.9838 0.1749 +vn 0.0570 -0.9867 0.1520 +vn 0.0730 -0.9863 0.1477 +vn -0.4641 0.8657 -0.1877 +vn -0.4219 0.8833 -0.2045 +vn 0.0520 -0.9370 0.3456 +vn 0.6068 0.6419 0.4688 +vn 0.6123 0.6308 0.4767 +vn 0.6433 0.5562 0.5261 +vn 0.6425 0.5586 0.5246 +vn 0.1905 0.9206 -0.3409 +vn 0.6969 0.5031 -0.5112 +vn 0.6770 0.5336 -0.5070 +vn 0.5995 0.6336 -0.4890 +vn 0.6177 0.6123 -0.4935 +vn 0.6263 -0.7786 0.0396 +vn 0.7585 -0.6109 0.2271 +vn 0.5774 -0.8163 -0.0169 +vn 0.5820 -0.8131 -0.0123 +vn -0.3865 -0.9052 0.1769 +vn -0.3846 -0.9058 0.1776 +vn 0.7908 -0.4663 0.3964 +vn 0.8420 -0.2937 0.4525 +vn 0.8003 -0.4432 0.4038 +vn 0.8594 -0.2019 0.4697 +vn 0.5208 0.7917 -0.3193 +vn 0.5105 0.8017 -0.3110 +vn 0.5606 0.7499 -0.3512 +vn 0.5646 0.7454 -0.3543 +vn 0.9434 0.2896 -0.1619 +vn 0.9848 0.0982 -0.1433 +vn 0.9481 -0.3060 -0.0865 +vn 0.9895 -0.0778 -0.1214 +vn -0.7936 0.5806 -0.1818 +vn -0.7509 0.6289 -0.2016 +vn -0.4637 0.8368 -0.2912 +vn 0.6499 -0.7581 0.0534 +vn 0.6106 -0.7918 0.0146 +vn 0.6926 -0.7147 0.0975 +vn 0.7185 -0.6841 0.1253 +vn -0.7125 -0.6945 -0.1002 +vn -0.7193 -0.6860 -0.1096 +vn 0.7945 -0.5607 -0.2332 +vn 0.7998 -0.5511 -0.2380 +vn 0.8536 -0.4292 -0.2954 +vn 0.8478 -0.4453 -0.2881 +vn 0.8247 0.2598 0.5023 +vn 0.8440 0.1794 0.5055 +vn 0.8000 0.3391 0.4950 +vn 0.7822 0.3869 0.4884 +vn 0.6016 0.7013 -0.3824 +vn 0.6018 0.7010 -0.3826 +vn 0.6683 0.4703 -0.5764 +vn 0.6667 0.4768 -0.5728 +vn 0.6433 0.5562 -0.5261 +vn 0.6425 0.5586 -0.5246 +vn 0.3422 0.8818 0.3246 +vn 0.4597 0.8416 0.2837 +vn 0.5823 0.7784 0.2347 +vn -0.0922 0.9352 0.3418 +vn -0.2090 0.9198 0.3322 +vn 0.0976 0.9277 -0.3604 +vn 0.1808 0.9198 -0.3483 +vn 0.4369 0.8156 -0.3794 +vn 0.7134 0.6017 -0.3592 +vn 0.3800 0.9027 0.2020 +vn 0.3306 0.9301 0.1603 +vn 0.0525 0.9035 0.4253 +vn 0.0949 0.9079 0.4083 +vn 0.4631 0.8436 0.2718 +vn 0.4399 0.8618 0.2525 +vn 0.0225 0.9298 -0.3673 +vn 0.0375 0.9298 -0.3662 +vn 0.8787 -0.4443 0.1744 +vn -0.2769 -0.8871 -0.3692 +vn -0.0862 -0.9293 -0.3592 +vn -0.3299 -0.1129 0.9372 +vn -0.3619 -0.0509 0.9308 +vn -0.4098 0.0786 0.9088 +vn -0.4040 0.0551 0.9131 +vn -0.2367 -0.9602 0.1484 +vn -0.2178 -0.9646 0.1488 +vn -0.3826 -0.9127 0.1439 +vn -0.4251 -0.8939 0.1419 +vn 0.1231 -0.9855 -0.1171 +vn 0.0527 -0.9904 -0.1279 +vn 0.3075 -0.9477 -0.0858 +vn 0.3963 -0.9155 -0.0691 +vn 0.4368 -0.8406 -0.3204 +vn 0.4782 -0.8206 -0.3131 +vn -0.7794 -0.5009 0.3763 +vn -0.8159 -0.4473 0.3664 +vn -0.0029 0.8931 0.4498 +vn 0.4897 -0.8471 0.2065 +vn 0.2333 -0.9286 0.2884 +vn -0.0885 0.8499 -0.5195 +vn -0.1668 0.7623 -0.6254 +vn 0.6387 0.6517 -0.4090 +vn 0.6359 0.6557 -0.4071 +vn 0.5341 0.7933 0.2923 +vn 0.8203 0.5378 0.1946 +vn 0.4390 0.8428 0.3113 +vn 0.4970 0.8510 -0.1696 +vn 0.5742 0.7999 -0.1744 +vn 0.6870 0.7043 -0.1789 +vn -0.4219 0.8833 0.2045 +vn -0.4641 0.8657 0.1877 +vn 0.0520 -0.9370 -0.3456 +vn -0.1821 0.9411 -0.2849 +vn 0.1231 -0.9855 0.1171 +vn 0.0527 -0.9904 0.1279 +vn -0.2252 -0.9602 0.1653 +vn -0.2215 -0.9611 0.1648 +vn -0.1766 0.9785 -0.1067 +vn -0.2272 0.9686 -0.1010 +vn -0.0348 0.9921 -0.1205 +vn -0.0106 0.9924 -0.1226 +vn -0.8546 0.5192 0.0145 +vn -0.7812 0.6242 -0.0059 +vn -0.6092 0.7918 -0.0436 +vn 0.1905 0.9206 0.3409 +vn 0.9538 -0.2965 0.0484 +vn 0.8723 -0.4833 0.0747 +vn 0.6972 -0.7089 0.1067 +vn 0.7845 -0.6131 0.0931 +vn 0.5820 -0.8131 0.0123 +vn 0.5774 -0.8163 0.0169 +vn -0.3857 0.8701 -0.3068 +vn 0.5646 0.7454 0.3543 +vn 0.5606 0.7499 0.3512 +vn 0.5105 0.8017 0.3110 +vn 0.5207 0.7917 0.3193 +vn -0.4637 0.8368 0.2912 +vn -0.7509 0.6289 0.2016 +vn -0.7936 0.5806 0.1818 +vn 0.9895 -0.0778 0.1214 +vn 0.9481 -0.3060 0.0865 +vn 0.9848 0.0982 0.1433 +vn 0.9434 0.2896 0.1619 +vn 0.7185 -0.6841 -0.1253 +vn 0.6926 -0.7147 -0.0975 +vn 0.6106 -0.7918 -0.0146 +vn 0.6499 -0.7581 -0.0534 +vn 0.6018 0.7010 0.3826 +vn 0.6016 0.7013 0.3824 +vn 0.6667 0.4768 0.5728 +vn 0.6683 0.4703 0.5764 +vn 0.5186 -0.8538 0.0453 +vn 0.4926 -0.8697 0.0307 +vn 0.3449 -0.9375 -0.0463 +vn 0.3688 -0.9289 -0.0345 +vn 0.3093 0.9393 -0.1486 +vn 0.2264 0.9712 -0.0741 +vn -0.1132 -0.9816 0.1535 +vn -0.1173 -0.9811 0.1538 +vn -0.2519 -0.9543 0.1610 +vn -0.2643 -0.9508 0.1615 +vn 0.7581 -0.6202 0.2014 +vn 0.7086 -0.6862 0.1646 +vn 0.7122 -0.6818 0.1671 +vn 0.1808 0.9198 0.3483 +vn 0.0976 0.9277 0.3604 +vn 0.7134 0.6017 0.3592 +vn 0.4369 0.8156 0.3794 +vn -0.8990 0.4365 -0.0353 +vn -0.7258 -0.6776 0.1184 +vn -0.7277 -0.6751 0.1213 +vn 0.6570 -0.7428 0.1289 +vn 0.8787 -0.4443 -0.1744 +vn -0.7325 0.6795 0.0416 +vn -0.8545 0.5130 0.0816 +vn -0.6120 0.7908 0.0086 +vn -0.4921 0.8703 -0.0203 +vn -0.4251 -0.8939 -0.1419 +vn -0.3826 -0.9127 -0.1439 +vn -0.2178 -0.9646 -0.1488 +vn -0.2367 -0.9602 -0.1484 +vn -0.9704 -0.2339 0.0601 +vn -0.9055 -0.4159 0.0841 +vn -0.9879 -0.1471 0.0483 +vn -0.8159 -0.4473 -0.3664 +vn -0.7794 -0.5009 -0.3762 +vn 0.2333 -0.9286 -0.2884 +vn 0.4897 -0.8471 -0.2065 +vn -0.1668 0.7623 0.6254 +vn -0.0885 0.8499 0.5195 +vn 0.6359 0.6557 0.4071 +vn 0.6388 0.6517 0.4090 +vn 0.2329 -0.9091 0.3454 +vn 0.1049 -0.9296 0.3534 +vn 0.1410 0.9094 0.3913 +vn 0.1939 0.9073 0.3732 +vn 0.7908 -0.4663 -0.3964 +vn 0.8420 -0.2937 -0.4525 +vn 0.8568 0.0339 -0.5145 +vn 0.8598 -0.1635 -0.4837 +vn -0.5871 -0.7847 -0.1988 +vn -0.5078 -0.8395 -0.1933 +vn -0.2252 -0.9602 -0.1653 +vn -0.2215 -0.9611 -0.1648 +vn -0.9305 -0.3278 0.1635 +vn -0.1821 0.9411 0.2849 +vn 0.1401 0.9811 -0.1334 +vn 0.1424 0.9808 -0.1335 +vn -0.9610 -0.2458 0.1267 +vn 0.2584 0.8996 -0.3521 +vn -0.2569 0.6230 -0.7388 +vn -0.2806 0.5772 -0.7669 +vn -0.3161 -0.9276 0.1991 +vn -0.3159 -0.9277 0.1991 +vn -0.2960 -0.9335 0.2022 +vn -0.2965 -0.9334 0.2021 +vn 0.8065 0.2688 -0.5266 +vn 0.8354 0.1643 -0.5245 +vn -0.0106 0.9924 0.1226 +vn -0.0348 0.9921 0.1205 +vn -0.2272 0.9686 0.1010 +vn -0.1766 0.9785 0.1067 +vn -0.6092 0.7919 0.0436 +vn -0.7812 0.6242 0.0059 +vn -0.8546 0.5192 -0.0145 +vn 0.7656 -0.6431 -0.0178 +vn 0.8808 -0.4702 -0.0560 +vn 0.7845 -0.6131 -0.0931 +vn 0.6972 -0.7089 -0.1067 +vn 0.8723 -0.4833 -0.0747 +vn 0.9538 -0.2965 -0.0484 +vn -0.2088 -0.9121 -0.3529 +vn -0.0326 -0.9337 -0.3565 +vn -0.3858 0.8701 0.3068 +vn 0.5608 0.7917 -0.2423 +vn 0.3295 -0.8950 0.3007 +vn 0.1719 -0.9284 0.3294 +vn 0.3688 -0.9289 0.0345 +vn 0.3449 -0.9375 0.0463 +vn 0.4926 -0.8697 -0.0307 +vn 0.5186 -0.8538 -0.0453 +vn -0.2643 -0.9508 -0.1615 +vn -0.2519 -0.9543 -0.1610 +vn -0.1173 -0.9811 -0.1538 +vn -0.1132 -0.9816 -0.1535 +vn -0.4826 0.8697 -0.1037 +vn -0.3458 0.9313 -0.1144 +vn -0.2441 0.9623 -0.1203 +vn 0.7122 -0.6818 -0.1671 +vn 0.7086 -0.6862 -0.1646 +vn 0.7581 -0.6202 -0.2014 +vn 0.8582 0.4829 -0.1738 +vn -0.0235 0.9454 -0.3251 +vn -0.8990 0.4365 0.0353 +vn -0.6166 0.7645 -0.1877 +vn -0.5719 0.7943 -0.2051 +vn -0.7277 -0.6751 -0.1213 +vn -0.7258 -0.6776 -0.1184 +vn -0.3298 0.4644 -0.8219 +vn -0.3430 0.4289 -0.8357 +vn 0.6570 -0.7428 -0.1289 +vn -0.1056 -0.9767 -0.1866 +vn -0.1095 -0.9762 -0.1872 +vn -0.2041 -0.9585 -0.1992 +vn -0.2020 -0.9590 -0.1990 +vn -0.4921 0.8703 0.0203 +vn -0.6120 0.7908 -0.0086 +vn -0.8545 0.5130 -0.0816 +vn -0.7325 0.6795 -0.0416 +vn 0.2026 -0.9735 -0.1061 +vn 0.2290 -0.9687 -0.0961 +vn -0.9879 -0.1471 -0.0483 +vn -0.9055 -0.4159 -0.0841 +vn -0.9704 -0.2339 -0.0601 +vn -0.6525 -0.7573 0.0274 +vn -0.6688 -0.7421 0.0456 +vn -0.6650 -0.7457 0.0414 +vn 0.8598 -0.1635 0.4837 +vn 0.8568 0.0339 0.5145 +vn 0.0620 0.9375 -0.3424 +vn -0.9836 -0.0540 0.1718 +vn -0.9490 -0.2513 0.1905 +vn -0.9810 0.1232 0.1497 +vn -0.9289 0.3525 0.1132 +vn 0.3093 0.9393 0.1486 +vn 0.2264 0.9712 0.0741 +vn -0.2846 0.9135 -0.2908 +vn 0.1489 0.9223 -0.3566 +vn 0.5555 -0.8303 0.0439 +vn 0.5498 -0.8336 0.0527 +vn 0.5155 -0.8489 0.1168 +vn 0.5324 -0.8422 0.0849 +vn 0.5592 0.7588 -0.3339 +vn 0.6180 0.7163 -0.3242 +vn -0.9305 -0.3278 -0.1635 +vn 0.6495 -0.7602 -0.0134 +vn 0.5322 -0.8456 -0.0409 +vn 0.7656 -0.6431 0.0178 +vn 0.8808 -0.4702 0.0560 +vn 0.5830 0.1151 -0.8042 +vn 0.6457 0.2848 -0.7085 +vn 0.6101 0.1810 -0.7714 +vn -0.0493 0.9413 -0.3340 +vn 0.0203 0.9393 -0.3424 +vn 0.2794 0.8854 -0.3715 +vn -0.2088 -0.9121 0.3529 +vn -0.4909 -0.8084 0.3249 +vn -0.9610 -0.2458 -0.1267 +vn 0.2584 0.8996 0.3521 +vn -0.5384 -0.8258 0.1677 +vn -0.4593 -0.8724 0.1673 +vn -0.6500 -0.7417 0.1657 +vn 0.8583 -0.4167 0.2995 +vn 0.8529 -0.4331 0.2915 +vn -0.2806 0.5772 0.7669 +vn -0.2569 0.6230 0.7388 +vn -0.2327 -0.2798 -0.9314 +vn -0.1533 -0.3983 -0.9044 +vn 0.6753 0.5972 -0.4329 +vn 0.6695 0.6062 -0.4293 +vn -0.2721 0.9600 -0.0662 +vn -0.3564 0.9330 -0.0496 +vn -0.0976 0.9905 -0.0973 +vn -0.0341 0.9936 -0.1077 +vn 0.4970 0.8510 0.1696 +vn 0.5742 0.7999 0.1744 +vn 0.2233 0.9642 0.1433 +vn 0.2263 0.9634 0.1436 +vn 0.4751 -0.8596 -0.1879 +vn 0.4356 -0.8642 -0.2520 +vn 0.5155 -0.8489 -0.1168 +vn 0.5324 -0.8422 -0.0849 +vn -0.3320 -0.9228 0.1956 +vn -0.3325 -0.9226 0.1955 +vn 0.5546 0.7294 -0.4006 +vn 0.5681 0.7093 -0.4173 +vn 0.8047 -0.5488 0.2264 +vn 0.7938 -0.5698 0.2127 +vn 0.8260 -0.5032 0.2541 +vn 0.8329 -0.4868 0.2634 +vn 0.5608 0.7917 0.2423 +vn -0.3320 -0.9228 -0.1956 +vn -0.3325 -0.9226 -0.1955 +vn -0.3865 -0.9052 -0.1769 +vn -0.3846 -0.9058 -0.1776 +vn 0.1719 -0.9284 -0.3294 +vn 0.3295 -0.8950 -0.3007 +vn 0.6266 -0.7716 0.1095 +vn 0.6192 -0.7782 0.1048 +vn -0.2441 0.9623 0.1203 +vn -0.3458 0.9313 0.1144 +vn -0.4826 0.8697 0.1037 +vn 0.8582 0.4829 0.1738 +vn 0.8682 -0.0660 -0.4918 +vn 0.8603 0.0777 -0.5039 +vn -0.6719 -0.7400 0.0306 +vn -0.6403 -0.7679 -0.0179 +vn -0.6059 -0.7924 -0.0707 +vn -0.6122 -0.7885 -0.0597 +vn -0.0235 0.9454 0.3251 +vn 0.6029 0.7851 -0.1423 +vn 0.6655 0.7332 -0.1398 +vn 0.9077 0.4043 -0.1123 +vn 0.7938 0.5941 -0.1300 +vn 0.0975 -0.9418 -0.3216 +vn -0.3829 0.2992 -0.8740 +vn -0.3890 0.2750 -0.8792 +vn -0.5719 0.7943 0.2051 +vn -0.6166 0.7645 0.1877 +vn -0.3430 0.4289 0.8357 +vn -0.3298 0.4644 0.8219 +vn -0.2020 -0.9590 0.1990 +vn -0.2041 -0.9585 0.1992 +vn -0.1095 -0.9762 0.1872 +vn -0.1056 -0.9767 0.1866 +vn 0.3032 0.8965 -0.3231 +vn 0.6563 -0.7259 0.2055 +vn 0.0521 0.9904 -0.1282 +vn 0.0582 0.9900 -0.1283 +vn -0.5564 -0.8201 0.1338 +vn -0.6237 -0.7710 0.1282 +vn -0.5813 -0.8049 -0.1192 +vn -0.5426 -0.8181 -0.1903 +vn -0.2847 -0.7892 -0.5443 +vn -0.4650 -0.8268 -0.3165 +vn 0.2290 -0.9687 0.0961 +vn 0.2026 -0.9735 0.1061 +vn 0.3713 0.9206 -0.1212 +vn 0.3190 0.9397 -0.1236 +vn 0.2233 0.9642 -0.1433 +vn 0.2263 0.9634 -0.1436 +vn -0.0070 -0.9392 -0.3433 +vn -0.2712 -0.9407 -0.2040 +vn -0.2704 -0.9409 -0.2040 +vn -0.2960 -0.9335 -0.2022 +vn -0.2965 -0.9334 -0.2021 +vn 0.6731 0.4001 -0.6220 +vn 0.6672 0.3688 -0.6472 +vn 0.0620 0.9375 0.3424 +vn -0.9289 0.3525 -0.1132 +vn -0.9810 0.1232 -0.1497 +vn -0.9490 -0.2513 -0.1905 +vn -0.9836 -0.0540 -0.1718 +vn 0.5201 -0.8501 -0.0830 +vn 0.4411 -0.8819 -0.1661 +vn -0.2846 0.9135 0.2908 +vn 0.1489 0.9223 0.3566 +vn 0.6179 0.7163 0.3242 +vn 0.5592 0.7588 0.3339 +vn 0.3875 -0.8632 -0.3236 +vn 0.3557 -0.8592 -0.3678 +vn 0.7156 0.6926 -0.0905 +vn 0.8013 0.5933 -0.0767 +vn 0.9604 0.2768 -0.0323 +vn 0.8894 0.4536 -0.0572 +vn 0.6101 0.1810 0.7714 +vn 0.6457 0.2848 0.7085 +vn 0.5830 0.1151 0.8043 +vn 0.0203 0.9393 0.3424 +vn -0.0493 0.9413 0.3340 +vn 0.2794 0.8854 0.3715 +vn -0.4909 -0.8084 -0.3249 +vn 0.2329 -0.9091 -0.3454 +vn -0.6500 -0.7417 -0.1656 +vn -0.4593 -0.8724 -0.1673 +vn -0.5384 -0.8258 -0.1677 +vn -0.4473 0.8915 -0.0714 +vn -0.3643 0.9275 -0.0836 +vn 0.8003 -0.4432 -0.4038 +vn 0.8594 -0.2019 -0.4697 +vn -0.4868 -0.8654 -0.1185 +vn -0.4889 -0.8645 -0.1169 +vn -0.5715 -0.8191 -0.0501 +vn -0.5677 -0.8215 -0.0535 +vn 0.6969 0.5031 0.5112 +vn 0.6770 0.5336 0.5070 +vn 0.7515 -0.6394 0.1624 +vn 0.7676 -0.6148 0.1811 +vn -0.8733 -0.4433 0.2020 +vn -0.7736 -0.5995 0.2052 +vn 0.4810 0.8173 0.3172 +vn 0.5073 0.7893 0.3459 +vn 0.5681 0.7093 0.4173 +vn 0.5546 0.7294 0.4006 +vn 0.8329 -0.4868 -0.2634 +vn 0.8259 -0.5032 -0.2541 +vn 0.7938 -0.5698 -0.2127 +vn 0.8047 -0.5488 -0.2264 +vn 0.4611 0.7602 -0.4576 +vn 0.4425 0.7737 -0.4534 +vn 0.3961 0.8048 -0.4420 +vn 0.6192 -0.7782 -0.1048 +vn 0.6266 -0.7716 -0.1095 +vn 0.8603 0.0777 0.5039 +vn 0.8682 -0.0660 0.4918 +vn 0.9946 0.1032 -0.0079 +vn 0.9922 -0.1221 0.0238 +vn -0.6122 -0.7885 0.0597 +vn -0.6059 -0.7924 0.0707 +vn -0.6403 -0.7679 0.0179 +vn -0.6719 -0.7400 -0.0306 +vn 0.7938 0.5941 0.1300 +vn 0.9077 0.4043 0.1123 +vn 0.6655 0.7332 0.1398 +vn 0.6029 0.7851 0.1423 +vn 0.8073 -0.5893 0.0312 +vn 0.6392 -0.7660 0.0677 +vn 0.3911 -0.9142 0.1059 +vn 0.4766 -0.8741 0.0942 +vn -0.3890 0.2750 0.8792 +vn -0.3829 0.2992 0.8740 +vn 0.0326 0.9377 -0.3458 +vn -0.6209 -0.7010 0.3507 +vn -0.6815 -0.6480 0.3401 +vn -0.0326 -0.9337 0.3565 +vn 0.3032 0.8965 0.3231 +vn 0.6563 -0.7259 -0.2055 +vn -0.0029 0.8931 -0.4498 +vn -0.0520 0.8782 -0.4755 +vn 0.0582 0.9900 0.1283 +vn 0.0521 0.9904 0.1282 +vn -0.8923 0.4462 0.0690 +vn -0.6237 -0.7710 -0.1282 +vn -0.5564 -0.8201 -0.1338 +vn 0.5555 -0.8303 -0.0439 +vn 0.5498 -0.8336 -0.0527 +vn -0.4650 -0.8268 0.3165 +vn -0.2847 -0.7892 0.5442 +vn -0.5426 -0.8181 0.1903 +vn -0.5813 -0.8049 0.1192 +vn 0.3190 0.9397 0.1236 +vn 0.3713 0.9206 0.1212 +vn -0.0976 0.9905 0.0973 +vn -0.0341 0.9936 0.1077 +vn 0.3785 0.9006 0.2136 +vn 0.4247 0.8675 0.2591 +vn 0.7040 0.5493 -0.4501 +vn 0.7130 0.5334 -0.4552 +vn 0.7544 0.4516 -0.4763 +vn 0.7411 0.4795 -0.4699 +vn -0.2704 -0.9409 0.2040 +vn -0.2712 -0.9407 0.2040 +vn -0.0348 -0.9841 -0.1741 +vn -0.0390 -0.9838 -0.1749 +vn -0.5871 -0.7847 0.1988 +vn -0.5078 -0.8395 0.1933 +vn -0.6309 -0.7758 0.0053 +vn -0.6267 -0.7792 0.0011 +vn -0.5498 -0.7739 0.3143 +vn -0.7379 -0.6650 0.1155 +vn -0.8219 -0.5603 0.1026 +vn -0.7024 -0.7073 0.0800 +vn -0.7136 -0.6937 0.0982 +vn 0.0570 -0.9867 -0.1520 +vn 0.0730 -0.9863 -0.1477 +vn 0.4751 -0.8596 0.1879 +vn 0.4356 -0.8642 0.2520 +vn 0.3557 -0.8592 0.3678 +vn 0.3875 -0.8632 0.3236 +vn 0.9797 0.1377 -0.1459 +vn 0.8583 -0.4167 -0.2995 +vn 0.8529 -0.4331 -0.2915 +vn 0.8894 0.4536 0.0572 +vn 0.9604 0.2768 0.0323 +vn 0.8013 0.5933 0.0767 +vn 0.7156 0.6926 0.0905 +vn 0.5386 0.6963 -0.4744 +vn 0.5302 0.7040 -0.4726 +vn 0.6731 0.4001 0.6220 +vn 0.6672 0.3688 0.6472 +vn 0.2854 -0.3493 -0.8925 +vn 0.1185 0.9195 -0.3749 +vn 0.0601 0.9276 -0.3687 +vn -0.3643 0.9275 0.0836 +vn -0.4473 0.8915 0.0714 +vn -0.5677 -0.8215 0.0535 +vn -0.5715 -0.8191 0.0501 +vn -0.4889 -0.8645 0.1169 +vn -0.4868 -0.8654 0.1185 +vn 0.7960 -0.5254 0.3007 +vn 0.1939 0.9073 -0.3732 +vn 0.1410 0.9094 -0.3913 +vn 0.0949 0.9079 -0.4083 +vn 0.7676 -0.6148 -0.1811 +vn 0.7515 -0.6394 -0.1624 +vn 0.6177 0.6123 0.4935 +vn 0.5995 0.6336 0.4891 +vn 0.3961 0.8048 0.4420 +vn 0.4425 0.7737 0.4534 +vn 0.4611 0.7602 0.4577 +vn 0.2651 0.8729 -0.4096 +vn 0.1979 0.8981 -0.3928 +vn 0.9922 -0.1221 -0.0238 +vn 0.9946 0.1032 0.0079 +vn 0.4427 0.8850 -0.1440 +vn 0.4826 0.8639 -0.1441 +vn 0.8772 -0.4800 0.0110 +vn 0.5345 0.8379 -0.1104 +vn 0.6007 0.7927 -0.1042 +vn 0.4766 -0.8741 -0.0942 +vn 0.3911 -0.9142 -0.1059 +vn 0.6392 -0.7660 -0.0677 +vn 0.8073 -0.5893 -0.0312 +vn 0.7604 0.6243 -0.1788 +vn 0.8619 0.4762 -0.1742 +vn -0.4737 -0.7846 0.4000 +vn 0.0326 0.9377 0.3458 +vn -0.6815 -0.6480 -0.3401 +vn -0.6209 -0.7010 -0.3507 +vn 0.1049 -0.9296 -0.3534 +vn 0.3191 0.8476 -0.4239 +vn 0.0375 0.9298 0.3662 +vn 0.0225 0.9298 0.3673 +vn -0.0520 0.8782 0.4755 +vn -0.2047 -0.7548 -0.6232 +vn -0.8923 0.4462 -0.0690 +vn 0.7411 0.4795 0.4699 +vn 0.7544 0.4516 0.4763 +vn -0.8733 -0.4433 -0.2020 +vn -0.7736 -0.5995 -0.2052 +vn -0.5498 -0.7739 -0.3143 +vn -0.8219 -0.5603 -0.1026 +vn -0.7379 -0.6650 -0.1155 +vn -0.7136 -0.6937 -0.0982 +vn -0.7024 -0.7073 -0.0800 +vn 0.7016 -0.6876 0.1868 +vn 0.9797 0.1377 0.1459 +vn 0.6870 0.7043 0.1788 +vn 0.6870 0.7043 0.1789 +vn 0.5302 0.7040 0.4726 +vn 0.5386 0.6963 0.4744 +vn 0.2872 -0.8326 -0.4736 +vn 0.2179 -0.7898 -0.5734 +vn 0.7521 0.5576 -0.3513 +vn 0.0464 -0.9888 0.1420 +vn 0.0204 -0.9894 0.1441 +vn 0.2854 -0.3493 0.8925 +vn 0.0525 0.9035 -0.4253 +vn 0.0601 0.9276 0.3687 +vn 0.1185 0.9195 0.3749 +vn 0.2910 0.9463 -0.1407 +vn 0.3092 0.9404 -0.1413 +vn 0.2563 0.8991 -0.3549 +vn 0.3963 -0.9155 0.0691 +vn 0.3075 -0.9477 0.0858 +vn -0.4131 0.1603 -0.8965 +vn -0.4123 0.1649 -0.8960 +vn 0.9532 0.2856 -0.0995 +vn 0.1979 0.8981 0.3928 +vn 0.2651 0.8729 0.4097 +vn 0.4826 0.8639 0.1441 +vn 0.4427 0.8850 0.1440 +vn 0.8772 -0.4800 -0.0110 +vn 0.6007 0.7927 0.1042 +vn 0.5345 0.8379 0.1104 +vn 0.6068 0.6419 -0.4688 +vn 0.6123 0.6308 -0.4767 +vn 0.8619 0.4762 0.1742 +vn 0.7604 0.6243 0.1788 +vn 0.5341 -0.8240 0.1891 +vn -0.4737 -0.7846 -0.4000 +vn 0.2492 -0.9606 0.1227 +vn 0.1957 -0.9722 0.1283 +vn 0.3191 0.8476 0.4239 +vn -0.2047 -0.7548 0.6232 +vn -0.2721 0.9600 0.0662 +vn -0.3564 0.9330 0.0496 +vn -0.1403 0.9370 -0.3200 +vn -0.0053 -0.9887 0.1497 +vn -0.0185 -0.9885 0.1498 +vn -0.4039 -0.8976 -0.1769 +vn -0.4037 -0.8976 -0.1770 +vn -0.2971 -0.8727 0.3874 +vn 0.7016 -0.6876 -0.1868 +vn 0.7521 0.5576 0.3513 +vn 0.0204 -0.9894 -0.1441 +vn 0.0464 -0.9888 -0.1420 +vn 0.2563 0.8991 0.3549 +vn -0.4123 0.1649 0.8960 +vn -0.4131 0.1603 0.8965 +vn -0.9901 0.0666 0.1234 +vn 0.9532 0.2856 0.0995 +vn 0.1010 0.9315 -0.3495 +vn 0.5341 -0.8240 -0.1891 +vn -0.3159 -0.9276 -0.1991 +vn -0.3161 -0.9276 -0.1991 +vn 0.1957 -0.9722 -0.1283 +vn 0.2492 -0.9606 -0.1227 +vn -0.1403 0.9370 0.3200 +vn -0.0070 -0.9392 0.3433 +vn -0.1394 -0.9200 0.3664 +vn -0.2971 -0.8727 -0.3875 +vn 0.5842 -0.8027 0.1202 +vn 0.4988 -0.8572 0.1281 +vn 0.2359 -0.9611 0.1439 +vn 0.3149 -0.9387 0.1403 +vn -0.9901 0.0667 -0.1234 +vn 0.2127 0.9752 -0.0607 +vn 0.2691 0.9570 -0.1085 +vn 0.5322 -0.8456 0.0409 +vn 0.6495 -0.7602 0.0134 +vn 0.1010 0.9315 0.3495 +vn -0.1394 -0.9200 -0.3664 +vn 0.9586 -0.2677 -0.0969 +vn 0.4411 -0.8819 0.1661 +vn 0.5201 -0.8501 0.0830 +vn -0.3965 -0.8998 -0.1819 +vn -0.3993 -0.8989 -0.1801 +vn 0.0975 -0.9418 0.3216 +vn -0.0106 -0.5789 -0.8153 +vn 0.0915 -0.6852 -0.7226 +vn 0.4988 -0.8572 -0.1281 +vn 0.5842 -0.8027 -0.1202 +vn 0.7422 0.4231 -0.5197 +vn 0.7683 0.3681 -0.5236 +vn 0.9586 -0.2677 0.0969 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/4 6/6/4 +f 4/4/5 7/7/6 8/8/7 +f 8/8/7 9/9/8 4/4/5 +f 5/5/9 4/4/5 9/9/8 +f 9/9/10 3/3/11 5/5/12 +f 5/5/12 3/3/11 6/6/13 +f 10/10/14 6/6/13 3/3/11 +f 3/3/11 2/2/15 10/10/14 +f 10/10/14 2/2/15 11/11/16 +f 12/12/17 11/11/18 2/2/19 +f 1/1/20 12/12/17 2/2/19 +f 12/12/17 1/1/20 13/13/21 +f 14/14/22 13/13/21 1/1/20 +f 15/15/23 13/13/21 14/14/22 +f 8/8/7 15/15/23 14/14/22 +f 7/7/6 15/15/23 8/8/7 +f 1/1/1 3/3/3 16/16/24 +f 14/14/25 1/1/25 17/17/25 +f 8/8/26 14/14/26 16/16/26 +f 16/16/27 14/14/27 17/17/27 +f 9/9/28 8/8/28 16/16/28 +f 3/3/29 9/9/29 16/16/29 +f 16/16/24 17/17/30 1/1/1 +f 18/18/31 19/19/31 20/20/31 +f 21/21/32 22/22/33 23/23/34 +f 23/23/34 22/22/33 24/24/35 +f 24/24/35 22/22/33 18/18/36 +f 19/19/37 18/18/36 22/22/33 +f 19/19/37 22/22/33 25/25/38 +f 26/26/39 19/19/37 25/25/38 +f 20/20/40 19/19/37 26/26/39 +f 20/20/40 26/26/39 27/27/41 +f 28/28/42 27/27/41 26/26/39 +f 26/26/39 29/29/43 28/28/42 +f 27/27/44 28/28/45 30/30/46 +f 28/28/45 29/29/47 30/30/46 +f 30/30/46 29/29/47 31/31/48 +f 31/31/48 29/29/47 32/32/49 +f 33/33/50 31/31/48 21/21/32 +f 21/21/32 31/31/48 32/32/49 +f 34/34/51 33/33/50 21/21/32 +f 23/23/34 34/34/51 21/21/32 +f 24/24/52 34/34/52 23/23/52 +f 29/29/53 26/26/53 35/35/53 +f 32/32/54 29/29/55 36/36/56 +f 36/36/56 29/29/55 35/35/57 +f 21/21/58 32/32/58 36/36/58 +f 22/22/59 21/21/59 36/36/59 +f 25/25/60 22/22/61 36/36/62 +f 26/26/63 25/25/60 35/35/64 +f 25/25/60 36/36/62 35/35/64 +f 37/37/65 38/38/65 39/39/65 +f 39/39/66 40/40/66 41/41/66 +f 41/41/67 42/42/67 43/43/67 +f 44/44/68 45/45/68 46/46/68 +f 40/40/69 46/46/70 41/41/71 +f 40/40/69 47/47/72 46/46/70 +f 40/40/69 39/39/73 47/47/72 +f 48/48/74 47/47/72 39/39/73 +f 38/38/75 48/48/74 39/39/73 +f 49/49/76 48/48/74 38/38/75 +f 50/50/77 49/49/78 38/38/79 +f 38/38/79 37/37/80 50/50/77 +f 43/43/81 50/50/77 37/37/80 +f 50/50/77 43/43/81 51/51/82 +f 52/52/83 51/51/84 43/43/85 +f 43/43/85 42/42/86 52/52/83 +f 44/44/87 52/52/83 42/42/86 +f 45/45/88 44/44/87 42/42/86 +f 45/45/88 42/42/86 41/41/71 +f 46/46/70 45/45/88 41/41/71 +f 37/37/89 39/39/89 53/53/89 +f 43/43/90 37/37/91 54/54/92 +f 54/54/92 37/37/91 53/53/93 +f 41/41/94 43/43/94 54/54/94 +f 55/55/95 41/41/95 54/54/95 +f 39/39/96 41/41/96 55/55/96 +f 53/53/97 39/39/97 55/55/97 +f 53/53/98 55/55/98 54/54/98 +f 56/56/99 57/57/100 58/58/101 +f 58/58/102 59/59/102 60/60/102 +f 51/51/103 52/52/104 50/50/105 +f 47/47/106 48/48/107 46/46/108 +f 50/50/105 52/52/104 44/44/109 +f 49/49/110 50/50/105 44/44/109 +f 49/49/110 44/44/109 46/46/108 +f 49/49/110 46/46/108 48/48/107 +f 34/34/111 24/24/112 31/31/113 +f 27/27/114 18/18/115 20/20/116 +f 24/24/112 30/30/117 31/31/113 +f 24/24/112 18/18/115 30/30/117 +f 27/27/114 30/30/117 18/18/115 +f 33/33/118 34/34/111 31/31/113 +f 12/12/119 13/13/120 15/15/121 +f 12/12/119 15/15/121 11/11/122 +f 15/15/121 7/7/123 11/11/122 +f 10/10/124 7/7/123 4/4/125 +f 61/61/126 62/62/126 63/63/126 +f 62/62/127 60/60/128 63/63/129 +f 59/59/130 63/63/129 60/60/128 +f 64/64/131 63/63/129 59/59/130 +f 58/58/132 64/64/131 59/59/130 +f 58/58/132 65/65/133 64/64/131 +f 66/66/134 65/65/133 58/58/132 +f 66/66/134 58/58/132 57/57/100 +f 66/66/134 57/57/100 67/67/135 +f 68/68/136 67/67/135 57/57/100 +f 57/57/100 56/56/99 68/68/136 +f 67/67/135 68/68/136 69/69/137 +f 70/70/138 69/69/139 68/68/140 +f 71/71/141 70/70/138 68/68/140 +f 71/71/141 68/68/140 56/56/142 +f 61/61/143 70/70/138 71/71/141 +f 62/62/127 61/61/143 71/71/141 +f 71/71/141 60/60/128 62/62/127 +f 56/56/144 58/58/144 72/72/144 +f 73/73/145 56/56/145 72/72/145 +f 71/71/146 56/56/146 73/73/146 +f 60/60/147 71/71/147 73/73/147 +f 58/58/148 60/60/149 72/72/150 +f 72/72/150 60/60/149 73/73/151 +f 11/11/122 7/7/123 10/10/124 +f 10/10/124 4/4/125 6/6/152 +f 70/70/153 67/67/154 69/69/155 +f 70/70/153 61/61/156 67/67/154 +f 63/63/157 64/64/158 65/65/159 +f 61/61/156 63/63/157 67/67/154 +f 66/66/160 67/67/154 63/63/157 +f 65/65/159 66/66/160 63/63/157 +f 74/74/161 75/75/162 76/76/163 +f 77/77/164 78/78/165 79/79/166 +f 80/80/167 81/81/168 79/79/166 +f 82/82/169 75/75/169 74/74/169 +f 80/80/167 79/79/166 78/78/165 +f 80/80/167 78/78/165 83/83/170 +f 74/74/161 76/76/163 83/83/170 +f 74/74/161 83/83/170 78/78/165 +f 78/78/165 77/77/164 84/84/171 +f 78/78/165 84/84/171 85/85/172 +f 85/85/172 84/84/171 86/86/173 +f 85/85/172 86/86/173 87/87/174 +f 85/85/172 87/87/174 88/88/175 +f 89/89/176 88/88/175 87/87/174 +f 90/90/177 89/89/176 87/87/174 +f 91/91/178 90/90/177 87/87/174 +f 92/92/179 93/93/180 94/94/181 +f 94/94/181 93/93/180 95/95/182 +f 95/95/182 93/93/180 96/96/183 +f 96/96/183 97/97/184 95/95/182 +f 95/95/182 97/97/184 98/98/185 +f 98/98/185 99/99/186 95/95/182 +f 95/95/182 99/99/186 100/100/187 +f 96/96/183 101/101/188 97/97/184 +f 102/102/189 103/103/190 104/104/191 +f 104/104/191 103/103/190 100/100/187 +f 95/95/182 100/100/187 105/105/192 +f 103/103/190 105/105/192 100/100/187 +f 106/106/193 107/107/194 108/108/195 +f 108/108/195 109/109/196 106/106/193 +f 110/110/197 111/111/198 112/112/199 +f 110/110/197 112/112/199 113/113/200 +f 113/113/200 112/112/199 114/114/201 +f 115/115/202 110/110/197 113/113/200 +f 115/115/202 113/113/200 116/116/203 +f 116/116/203 113/113/200 114/114/201 +f 116/116/203 114/114/201 117/117/204 +f 117/117/204 114/114/201 118/118/205 +f 119/119/206 115/115/202 120/120/207 +f 120/120/207 116/116/203 117/117/204 +f 120/120/207 117/117/204 121/121/208 +f 114/114/201 122/122/209 118/118/205 +f 117/117/204 118/118/205 123/123/210 +f 116/116/203 120/120/207 115/115/202 +f 123/123/210 121/121/208 117/117/204 +f 124/124/211 125/125/212 126/126/213 +f 126/126/213 125/125/212 118/118/205 +f 126/126/213 118/118/205 122/122/209 +f 125/125/212 123/123/210 118/118/205 +f 127/127/214 123/123/210 128/128/215 +f 123/123/210 125/125/212 128/128/215 +f 128/128/215 125/125/212 129/129/216 +f 129/129/216 125/125/212 124/124/211 +f 110/110/197 115/115/202 130/130/217 +f 131/131/218 130/130/217 106/106/193 +f 131/131/218 106/106/193 109/109/196 +f 130/130/217 131/131/218 111/111/198 +f 130/130/217 111/111/198 110/110/197 +f 132/132/219 127/127/214 128/128/215 +f 128/128/215 129/129/216 133/133/220 +f 128/128/215 133/133/220 134/134/221 +f 128/128/215 134/134/221 132/132/219 +f 135/135/222 136/136/223 137/137/224 +f 135/135/222 137/137/224 138/138/225 +f 138/138/225 137/137/224 139/139/226 +f 140/140/227 135/135/222 138/138/225 +f 138/138/225 141/141/228 142/142/229 +f 138/138/225 142/142/229 140/140/227 +f 135/135/222 140/140/227 143/143/230 +f 142/142/229 127/127/214 132/132/219 +f 140/140/227 142/142/229 132/132/219 +f 140/140/227 132/132/219 134/134/221 +f 140/140/227 134/134/221 143/143/230 +f 143/143/230 134/134/221 144/144/231 +f 145/145/232 139/139/226 137/137/224 +f 137/137/224 146/146/233 145/145/232 +f 145/145/232 146/146/233 147/147/234 +f 145/145/232 147/147/234 148/148/235 +f 146/146/233 137/137/224 136/136/223 +f 147/147/234 102/102/189 148/148/235 +f 89/89/176 90/90/177 149/149/236 +f 85/85/172 150/150/237 78/78/165 +f 151/151/238 152/152/239 153/153/240 +f 154/154/241 155/155/242 153/153/240 +f 156/156/243 94/94/181 157/157/244 +f 158/158/245 159/159/246 160/160/247 +f 160/160/247 159/159/246 149/149/236 +f 149/149/236 90/90/177 160/160/247 +f 161/161/248 88/88/175 89/89/176 +f 162/162/249 85/85/172 163/163/250 +f 163/163/250 85/85/172 88/88/175 +f 150/150/237 85/85/172 162/162/249 +f 164/164/251 165/165/252 166/166/253 +f 166/166/253 165/165/252 167/167/254 +f 166/166/253 167/167/254 168/168/255 +f 169/169/256 168/168/255 170/170/257 +f 169/169/256 170/170/257 171/171/258 +f 172/172/259 171/171/258 173/173/260 +f 166/166/253 168/168/255 169/169/256 +f 174/174/261 164/164/251 166/166/253 +f 175/175/262 166/166/253 169/169/256 +f 176/176/263 169/169/256 171/171/258 +f 176/176/263 171/171/258 172/172/259 +f 174/174/261 166/166/253 175/175/262 +f 176/176/263 175/175/262 169/169/256 +f 161/161/248 175/175/262 176/176/263 +f 177/177/264 174/174/261 161/161/248 +f 161/161/248 174/174/261 175/175/262 +f 163/163/250 161/161/248 176/176/263 +f 162/162/249 176/176/263 172/172/259 +f 162/162/249 163/163/250 176/176/263 +f 163/163/250 88/88/175 161/161/248 +f 161/161/248 89/89/176 177/177/264 +f 177/177/264 89/89/176 149/149/236 +f 168/168/255 167/167/254 170/170/257 +f 170/170/257 167/167/254 178/178/265 +f 179/179/266 173/173/260 171/171/258 +f 179/179/266 171/171/258 180/180/267 +f 180/180/267 171/171/258 170/170/257 +f 180/180/267 170/170/257 181/181/268 +f 181/181/268 170/170/257 178/178/265 +f 182/182/269 183/183/270 184/184/271 +f 167/167/254 165/165/252 185/185/272 +f 167/167/254 185/185/272 186/186/273 +f 186/186/273 185/185/272 184/184/271 +f 184/184/271 185/185/272 182/182/269 +f 184/184/271 183/183/270 187/187/274 +f 184/184/271 187/187/274 186/186/273 +f 186/186/273 187/187/274 188/188/275 +f 186/186/273 188/188/275 167/167/254 +f 167/167/254 188/188/275 178/178/265 +f 187/187/274 183/183/270 189/189/276 +f 182/182/269 190/190/277 183/183/270 +f 183/183/270 190/190/277 191/191/278 +f 183/183/270 191/191/278 189/189/276 +f 189/189/276 191/191/278 192/192/279 +f 193/193/280 74/74/161 194/194/281 +f 195/195/282 180/180/267 181/181/268 +f 122/122/209 179/179/266 195/195/282 +f 195/195/282 179/179/266 180/180/267 +f 196/196/283 195/195/282 181/181/268 +f 126/126/213 122/122/209 195/195/282 +f 126/126/213 195/195/282 124/124/211 +f 124/124/211 195/195/282 196/196/283 +f 197/197/284 189/189/276 198/198/285 +f 198/198/285 189/189/276 192/192/279 +f 198/198/285 192/192/279 199/199/286 +f 154/154/241 200/200/287 155/155/242 +f 200/200/287 154/154/241 156/156/243 +f 201/201/288 182/182/269 202/202/289 +f 190/190/277 182/182/269 201/201/288 +f 203/203/290 191/191/278 190/190/277 +f 191/191/278 204/204/291 192/192/279 +f 201/201/288 203/203/290 190/190/277 +f 205/205/292 204/204/291 191/191/278 +f 205/205/292 191/191/278 203/203/290 +f 205/205/292 206/206/293 204/204/291 +f 207/207/294 205/205/292 203/203/290 +f 207/207/294 203/203/290 208/208/295 +f 208/208/295 203/203/290 201/201/288 +f 208/208/295 201/201/288 209/209/296 +f 209/209/296 201/201/288 202/202/289 +f 210/210/297 206/206/293 205/205/292 +f 211/211/298 208/208/295 209/209/296 +f 200/200/287 210/210/297 205/205/292 +f 212/212/299 205/205/292 207/207/294 +f 213/213/300 207/207/294 208/208/295 +f 213/213/300 208/208/295 211/211/298 +f 200/200/287 205/205/292 212/212/299 +f 212/212/299 207/207/294 213/213/300 +f 151/151/238 213/213/300 211/211/298 +f 151/151/238 211/211/298 214/214/301 +f 157/157/244 210/210/297 156/156/243 +f 156/156/243 210/210/297 200/200/287 +f 155/155/242 200/200/287 212/212/299 +f 155/155/242 212/212/299 153/153/240 +f 153/153/240 212/212/299 213/213/300 +f 153/153/240 213/213/300 151/151/238 +f 215/215/302 133/133/220 129/129/216 +f 199/199/286 144/144/231 198/198/285 +f 197/197/284 198/198/285 215/215/302 +f 133/133/220 215/215/302 198/198/285 +f 133/133/220 198/198/285 134/134/221 +f 134/134/221 198/198/285 144/144/231 +f 105/105/192 103/103/190 216/216/303 +f 217/217/304 218/218/305 199/199/286 +f 219/219/306 151/151/238 214/214/301 +f 152/152/239 151/151/238 219/219/306 +f 220/220/307 177/177/264 149/149/236 +f 221/221/308 174/174/261 177/177/264 +f 164/164/251 222/222/309 165/165/252 +f 222/222/309 185/185/272 165/165/252 +f 202/202/289 182/182/269 222/222/309 +f 222/222/309 182/182/269 185/185/272 +f 220/220/307 214/214/301 211/211/298 +f 223/223/310 224/224/311 219/219/306 +f 202/202/289 222/222/309 209/209/296 +f 214/214/301 220/220/307 223/223/310 +f 214/214/301 223/223/310 219/219/306 +f 209/209/296 222/222/309 221/221/308 +f 209/209/296 221/221/308 211/211/298 +f 211/211/298 221/221/308 220/220/307 +f 224/224/311 223/223/310 158/158/245 +f 222/222/309 164/164/251 221/221/308 +f 223/223/310 159/159/246 158/158/245 +f 221/221/308 164/164/251 174/174/261 +f 220/220/307 221/221/308 177/177/264 +f 223/223/310 220/220/307 149/149/236 +f 223/223/310 149/149/236 159/159/246 +f 158/158/245 225/225/312 224/224/311 +f 123/123/210 127/127/214 121/121/208 +f 121/121/208 127/127/214 142/142/229 +f 121/121/208 142/142/229 141/141/228 +f 121/121/208 141/141/228 120/120/207 +f 139/139/226 119/119/206 138/138/225 +f 138/138/225 119/119/206 120/120/207 +f 138/138/225 120/120/207 141/141/228 +f 119/119/206 139/139/226 226/226/313 +f 119/119/206 226/226/313 227/227/314 +f 227/227/314 226/226/313 228/228/315 +f 95/95/182 105/105/192 94/94/181 +f 105/105/192 216/216/303 157/157/244 +f 94/94/181 105/105/192 157/157/244 +f 216/216/303 210/210/297 157/157/244 +f 216/216/303 229/229/316 210/210/297 +f 206/206/293 229/229/316 217/217/304 +f 229/229/316 206/206/293 210/210/297 +f 204/204/291 206/206/293 217/217/304 +f 204/204/291 217/217/304 199/199/286 +f 199/199/286 192/192/279 204/204/291 +f 78/78/165 150/150/237 74/74/161 +f 162/162/249 194/194/281 150/150/237 +f 150/150/237 194/194/281 74/74/161 +f 162/162/249 230/230/317 194/194/281 +f 162/162/249 172/172/259 230/230/317 +f 172/172/259 231/231/318 230/230/317 +f 231/231/318 172/172/259 173/173/260 +f 173/173/260 179/179/266 231/231/318 +f 216/216/303 146/146/233 229/229/316 +f 103/103/190 102/102/189 147/147/234 +f 103/103/190 147/147/234 216/216/303 +f 216/216/303 147/147/234 146/146/233 +f 229/229/316 146/146/233 136/136/223 +f 136/136/223 217/217/304 229/229/316 +f 218/218/305 217/217/304 135/135/222 +f 135/135/222 217/217/304 136/136/223 +f 143/143/230 218/218/305 135/135/222 +f 143/143/230 144/144/231 199/199/286 +f 218/218/305 143/143/230 199/199/286 +f 129/129/216 188/188/275 187/187/274 +f 187/187/274 215/215/302 129/129/216 +f 197/197/284 215/215/302 187/187/274 +f 197/197/284 187/187/274 189/189/276 +f 196/196/283 188/188/275 124/124/211 +f 124/124/211 188/188/275 129/129/216 +f 188/188/275 196/196/283 181/181/268 +f 188/188/275 181/181/268 178/178/265 +f 131/131/218 109/109/196 193/193/280 +f 131/131/218 193/193/280 194/194/281 +f 194/194/281 111/111/198 131/131/218 +f 231/231/318 112/112/199 230/230/317 +f 194/194/281 230/230/317 111/111/198 +f 230/230/317 112/112/199 111/111/198 +f 231/231/318 114/114/201 112/112/199 +f 179/179/266 122/122/209 114/114/201 +f 179/179/266 114/114/201 231/231/318 +f 104/104/191 148/148/235 102/102/189 +f 148/148/235 104/104/191 232/232/319 +f 232/232/319 145/145/232 148/148/235 +f 226/226/313 139/139/226 233/233/320 +f 233/233/320 139/139/226 145/145/232 +f 233/233/320 145/145/232 232/232/319 +f 233/233/320 228/228/315 226/226/313 +f 227/227/314 228/228/315 234/234/321 +f 115/115/202 119/119/206 234/234/321 +f 234/234/321 119/119/206 227/227/314 +f 115/115/202 234/234/321 107/107/194 +f 106/106/193 130/130/217 107/107/194 +f 107/107/194 130/130/217 115/115/202 +f 235/235/322 74/74/161 193/193/280 +f 82/82/323 74/74/161 235/235/322 +f 236/236/324 152/152/239 237/237/325 +f 152/152/239 236/236/324 153/153/240 +f 236/236/324 154/154/241 153/153/240 +f 238/238/326 156/156/243 236/236/324 +f 156/156/243 154/154/241 236/236/324 +f 238/238/326 239/239/327 156/156/243 +f 156/156/243 239/239/327 94/94/181 +f 94/94/181 239/239/327 92/92/179 +f 91/91/178 160/160/247 90/90/177 +f 158/158/245 160/160/247 240/240/328 +f 240/240/328 160/160/247 91/91/178 +f 240/240/328 225/225/312 158/158/245 +f 241/241/329 224/224/311 240/240/328 +f 240/240/328 224/224/311 225/225/312 +f 237/237/325 219/219/306 241/241/329 +f 241/241/329 219/219/306 224/224/311 +f 219/219/306 237/237/325 152/152/239 +f 109/109/196 108/108/195 193/193/280 +f 193/193/280 108/108/195 235/235/322 +f 242/242/330 243/243/330 244/244/330 +f 244/244/331 243/243/331 245/245/331 +f 244/244/332 245/245/333 246/246/334 +f 246/246/335 245/245/336 247/247/337 +f 247/247/337 245/245/336 248/248/338 +f 247/247/337 248/248/338 249/249/339 +f 250/250/340 251/251/341 249/249/339 +f 249/249/339 251/251/341 247/247/337 +f 96/96/342 250/250/340 249/249/339 +f 239/239/327 238/238/326 252/252/343 +f 252/252/343 253/253/344 239/239/327 +f 252/252/343 254/254/345 253/253/344 +f 254/254/345 252/252/343 243/243/346 +f 254/254/345 243/243/346 242/242/347 +f 255/255/348 256/256/348 257/257/348 +f 257/257/349 256/256/350 258/258/351 +f 257/257/349 258/258/351 259/259/352 +f 259/259/353 258/258/353 260/260/353 +f 261/261/354 260/260/355 262/262/356 +f 262/262/356 260/260/355 258/258/357 +f 263/263/358 101/101/359 264/264/360 +f 263/263/361 264/264/362 265/265/363 +f 264/264/362 266/266/364 265/265/363 +f 266/266/364 264/264/362 256/256/365 +f 266/266/364 256/256/365 255/255/366 +f 263/263/358 265/265/367 267/267/368 +f 267/267/369 265/265/369 266/266/369 +f 268/268/370 260/260/370 261/261/370 +f 269/269/371 244/244/332 246/246/334 +f 269/269/372 246/246/373 270/270/374 +f 242/242/375 244/244/376 269/269/377 +f 247/247/378 251/251/379 270/270/374 +f 247/247/378 270/270/374 246/246/373 +f 271/271/380 272/272/380 273/273/380 +f 273/273/381 272/272/382 274/274/383 +f 273/273/381 274/274/383 275/275/384 +f 275/275/385 274/274/386 276/276/387 +f 276/276/387 274/274/386 277/277/388 +f 86/86/173 84/84/171 277/277/388 +f 84/84/171 278/278/389 277/277/388 +f 277/277/388 278/278/389 276/276/387 +f 279/279/390 280/280/391 81/81/392 +f 281/281/393 282/282/394 279/279/395 +f 279/279/390 282/282/396 280/280/391 +f 281/281/393 279/279/395 272/272/397 +f 281/281/393 272/272/397 271/271/398 +f 283/283/399 284/284/400 82/82/401 +f 82/82/401 284/284/400 285/285/402 +f 284/284/403 283/283/404 286/286/405 +f 286/286/405 283/283/404 287/287/406 +f 287/287/407 283/283/408 288/288/409 +f 287/287/407 288/288/409 289/289/410 +f 289/289/411 288/288/412 290/290/413 +f 290/290/413 288/288/412 291/291/414 +f 291/291/414 288/288/412 292/292/415 +f 293/293/416 294/294/417 295/295/418 +f 295/295/418 294/294/417 292/292/415 +f 292/292/415 294/294/417 291/291/414 +f 80/80/419 293/293/416 295/295/418 +f 269/269/377 270/270/420 242/242/375 +f 270/270/420 251/251/421 253/253/422 +f 254/254/423 242/242/375 270/270/420 +f 254/254/423 270/270/420 253/253/422 +f 260/260/424 268/268/425 266/266/426 +f 255/255/427 259/259/428 260/260/424 +f 255/255/427 257/257/429 259/259/428 +f 255/255/427 260/260/424 266/266/426 +f 286/286/430 290/290/431 284/284/432 +f 268/268/425 267/267/433 266/266/426 +f 284/284/432 290/290/431 296/296/434 +f 297/297/435 284/284/432 296/296/434 +f 281/281/436 271/271/437 298/298/438 +f 298/298/438 276/276/439 281/281/436 +f 281/281/436 276/276/439 299/299/440 +f 297/297/435 296/296/434 294/294/441 +f 282/282/442 281/281/436 299/299/440 +f 291/291/443 294/294/444 296/296/445 +f 290/290/446 291/291/443 296/296/445 +f 287/287/447 289/289/448 290/290/431 +f 286/286/430 287/287/447 290/290/431 +f 284/284/449 297/297/449 285/285/449 +f 278/278/450 84/84/451 299/299/452 +f 276/276/453 278/278/450 299/299/452 +f 271/271/437 273/273/454 298/298/438 +f 298/298/455 273/273/381 275/275/384 +f 298/298/456 275/275/456 276/276/456 +f 99/99/457 261/261/458 262/262/459 +f 261/261/458 99/99/457 98/98/460 +f 261/261/461 98/98/462 268/268/463 +f 267/267/368 268/268/463 97/97/464 +f 97/97/464 268/268/463 98/98/462 +f 101/101/359 263/263/358 97/97/464 +f 263/263/358 267/267/368 97/97/464 +f 82/82/465 285/285/465 75/75/465 +f 297/297/466 76/76/467 285/285/468 +f 285/285/468 76/76/467 75/75/469 +f 83/83/470 76/76/471 294/294/472 +f 294/294/472 76/76/471 297/297/473 +f 293/293/474 80/80/474 83/83/474 +f 294/294/472 293/293/475 83/83/470 +f 79/79/476 81/81/392 280/280/391 +f 280/280/391 282/282/396 79/79/476 +f 77/77/477 79/79/476 299/299/452 +f 299/299/452 79/79/476 282/282/396 +f 84/84/451 77/77/477 299/299/452 +f 250/250/478 96/96/479 93/93/480 +f 250/250/478 93/93/480 251/251/481 +f 253/253/482 251/251/481 92/92/483 +f 92/92/483 251/251/481 93/93/480 +f 239/239/484 253/253/482 92/92/483 +f 300/300/485 301/301/486 302/302/487 +f 302/302/487 301/301/486 303/303/488 +f 304/304/489 305/305/490 306/306/491 +f 307/307/492 305/305/490 304/304/489 +f 308/308/493 307/307/492 304/304/489 +f 309/309/494 310/310/495 311/311/496 +f 311/311/496 310/310/495 312/312/497 +f 313/313/498 314/314/499 315/315/500 +f 316/316/501 317/317/501 318/318/501 +f 319/319/502 312/312/503 313/313/498 +f 315/315/500 319/319/502 313/313/498 +f 319/319/502 315/315/500 318/318/504 +f 318/318/504 315/315/500 320/320/505 +f 318/318/504 320/320/505 316/316/506 +f 316/316/506 320/320/505 321/321/507 +f 321/321/507 320/320/505 322/322/508 +f 313/313/498 312/312/503 310/310/509 +f 323/323/510 324/324/511 325/325/512 +f 326/326/513 327/327/514 328/328/515 +f 323/323/510 329/329/516 324/324/511 +f 324/324/511 329/329/516 330/330/517 +f 324/324/511 330/330/517 327/327/514 +f 327/327/514 330/330/517 331/331/518 +f 327/327/514 331/331/518 328/328/515 +f 311/311/519 326/326/513 309/309/520 +f 311/311/519 327/327/514 326/326/513 +f 332/332/521 333/333/522 334/334/523 +f 335/335/524 336/336/525 337/337/526 +f 336/336/525 335/335/524 338/338/527 +f 339/339/528 340/340/529 341/341/528 +f 332/332/521 342/342/528 333/333/522 +f 334/334/523 333/333/522 343/343/530 +f 337/337/526 336/336/525 344/344/528 +f 342/342/528 332/332/521 345/345/528 +f 346/346/531 340/340/529 347/347/532 +f 344/344/528 348/348/528 337/337/526 +f 349/349/533 347/347/532 340/340/529 +f 337/337/526 348/348/528 350/350/528 +f 350/350/528 348/348/528 351/351/528 +f 350/350/528 351/351/528 352/352/534 +f 352/352/534 351/351/528 353/353/528 +f 354/354/528 355/355/528 345/345/528 +f 354/354/528 345/345/528 332/332/521 +f 356/356/535 357/357/536 358/358/528 +f 358/358/528 357/357/536 359/359/528 +f 339/339/528 341/341/528 360/360/528 +f 339/339/528 360/360/528 344/344/528 +f 344/344/528 360/360/528 348/348/528 +f 342/342/528 345/345/528 361/361/528 +f 357/357/536 356/356/535 362/362/537 +f 358/358/528 359/359/528 361/361/528 +f 361/361/528 359/359/528 342/342/528 +f 357/357/536 362/362/537 363/363/538 +f 354/354/528 323/323/528 355/355/528 +f 355/355/528 323/323/528 364/364/528 +f 353/353/528 365/365/539 352/352/534 +f 363/363/538 366/366/540 357/357/536 +f 367/367/541 368/368/542 369/369/543 +f 370/370/544 371/371/545 368/368/542 +f 368/368/542 371/371/545 369/369/543 +f 371/371/545 370/370/544 372/372/546 +f 369/369/543 371/371/545 373/373/547 +f 374/374/548 373/373/547 375/375/549 +f 371/371/545 376/376/550 373/373/547 +f 373/373/547 376/376/550 375/375/549 +f 371/371/545 377/377/551 376/376/550 +f 378/378/552 379/379/553 380/380/554 +f 378/378/552 380/380/554 381/381/555 +f 381/381/555 380/380/554 382/382/556 +f 382/382/556 383/383/557 381/381/555 +f 379/379/558 378/378/558 384/384/558 +f 384/384/559 378/378/559 385/385/559 +f 384/384/560 385/385/560 386/386/560 +f 387/387/561 384/384/562 386/386/563 +f 384/384/562 387/387/561 388/388/564 +f 388/388/564 387/387/561 389/389/565 +f 389/389/565 390/390/566 388/388/564 +f 391/391/567 385/385/567 378/378/567 +f 391/391/568 378/378/569 392/392/570 +f 391/391/568 392/392/570 393/393/571 +f 393/393/572 392/392/573 383/383/557 +f 394/394/574 395/395/575 396/396/576 +f 396/396/576 397/397/577 394/394/574 +f 398/398/578 399/399/579 400/400/580 +f 400/400/580 401/401/581 398/398/578 +f 402/402/582 403/403/583 404/404/584 +f 403/403/583 402/402/582 393/393/585 +f 393/393/585 402/402/582 405/405/586 +f 406/406/587 407/407/588 408/408/589 +f 408/408/589 407/407/588 409/409/590 +f 408/408/589 409/409/590 410/410/591 +f 410/410/591 409/409/590 411/411/592 +f 410/410/591 411/411/592 412/412/593 +f 412/412/593 411/411/592 413/413/594 +f 412/412/593 413/413/594 414/414/595 +f 414/414/595 413/413/594 415/415/596 +f 414/414/595 415/415/596 416/416/597 +f 416/416/597 415/415/596 417/417/598 +f 416/416/597 417/417/598 418/418/599 +f 418/418/599 417/417/598 419/419/600 +f 418/418/599 419/419/600 420/420/601 +f 420/420/601 419/419/600 421/421/602 +f 422/422/603 423/423/603 424/424/603 +f 423/423/603 422/422/603 354/354/604 +f 425/425/605 426/426/606 427/427/607 +f 427/427/607 426/426/606 332/332/608 +f 425/425/605 424/424/603 426/426/606 +f 422/422/603 424/424/603 425/425/605 +f 332/332/608 426/426/606 428/428/603 +f 428/428/603 423/423/603 354/354/604 +f 332/332/608 428/428/603 354/354/604 +f 429/429/609 330/330/517 329/329/516 +f 430/430/610 431/431/611 432/432/612 +f 430/430/610 432/432/612 433/433/613 +f 433/433/613 434/434/614 425/425/605 +f 425/425/605 434/434/614 422/422/603 +f 422/422/603 434/434/614 431/431/611 +f 435/435/615 422/422/603 436/436/616 +f 437/437/603 438/438/615 439/439/603 +f 431/431/611 430/430/610 422/422/603 +f 422/422/603 430/430/610 436/436/616 +f 430/430/610 439/439/603 436/436/616 +f 435/435/615 438/438/615 437/437/603 +f 422/422/603 435/435/615 437/437/603 +f 440/440/617 441/441/618 442/442/619 +f 442/442/619 441/441/618 326/326/513 +f 442/442/619 326/326/513 443/443/620 +f 442/442/619 430/430/610 444/444/621 +f 440/440/617 445/445/622 433/433/613 +f 445/445/622 446/446/623 433/433/613 +f 445/445/622 440/440/617 444/444/621 +f 433/433/613 446/446/623 430/430/610 +f 442/442/619 444/444/621 440/440/617 +f 447/447/603 448/448/624 439/439/603 +f 430/430/610 442/442/619 447/447/603 +f 430/430/610 447/447/603 439/439/603 +f 443/443/620 449/449/625 442/442/619 +f 443/443/620 450/450/626 437/437/603 +f 443/443/620 437/437/603 439/439/603 +f 443/443/620 439/439/603 449/449/625 +f 449/449/625 439/439/603 448/448/624 +f 328/328/515 451/451/627 326/326/513 +f 326/326/513 451/451/627 443/443/620 +f 331/331/518 452/452/609 450/450/626 +f 331/331/518 450/450/626 328/328/515 +f 437/437/603 453/453/628 454/454/629 +f 455/455/630 453/453/628 354/354/604 +f 456/456/611 455/455/630 354/354/604 +f 422/422/603 454/454/629 456/456/611 +f 422/422/603 456/456/611 354/354/604 +f 437/437/603 454/454/629 422/422/603 +f 323/323/510 457/457/631 329/329/516 +f 429/429/609 458/458/632 354/354/604 +f 429/429/609 354/354/604 437/437/603 +f 437/437/603 354/354/604 453/453/628 +f 458/458/632 457/457/631 323/323/510 +f 429/429/609 459/459/633 458/458/632 +f 354/354/604 458/458/632 323/323/510 +f 329/329/516 459/459/633 429/429/609 +f 317/317/634 316/316/634 325/325/634 +f 325/325/635 316/316/635 323/323/635 +f 307/307/492 460/460/636 461/461/637 +f 307/307/492 461/461/637 462/462/638 +f 462/462/638 461/461/637 463/463/639 +f 464/464/640 465/465/641 466/466/642 +f 466/466/642 465/465/641 463/463/639 +f 466/466/642 463/463/639 467/467/643 +f 100/468/644 464/464/645 468/469/646 +f 465/465/641 469/470/647 402/402/648 +f 100/468/649 468/469/650 461/461/637 +f 461/461/637 468/469/650 467/467/643 +f 461/461/637 467/467/643 463/463/639 +f 100/468/651 470/471/652 464/464/640 +f 464/464/640 470/471/652 469/470/647 +f 464/464/640 469/470/647 465/465/641 +f 471/472/653 472/473/654 473/474/655 +f 471/472/653 473/474/655 474/475/656 +f 474/475/656 473/474/655 475/476/657 +f 474/475/656 475/476/657 391/391/658 +f 391/391/658 475/476/657 385/385/659 +f 472/473/654 476/477/660 477/478/661 +f 472/473/654 471/472/662 476/477/660 +f 476/477/663 478/479/664 477/478/661 +f 477/478/661 478/479/664 479/480/665 +f 479/480/665 478/479/664 480/481/666 +f 479/480/665 480/481/666 362/362/667 +f 356/356/668 481/482/669 482/483/670 +f 356/356/668 482/483/670 362/362/667 +f 362/362/667 482/483/670 479/480/665 +f 404/404/671 483/484/672 356/356/673 +f 356/356/673 483/484/672 481/482/674 +f 403/403/675 484/485/676 485/486/677 +f 403/403/675 485/486/677 404/404/678 +f 404/404/678 485/486/677 483/484/679 +f 383/383/557 403/403/675 393/393/572 +f 390/390/566 389/389/565 484/485/676 +f 484/485/676 389/389/565 486/487/680 +f 403/403/675 383/383/557 382/382/556 +f 403/403/675 382/382/556 484/485/676 +f 484/485/676 382/382/556 390/390/566 +f 487/488/681 488/489/682 489/490/683 +f 489/490/683 488/489/682 490/491/684 +f 490/491/684 488/489/682 491/492/685 +f 358/358/686 492/493/687 364/364/688 +f 364/364/688 492/493/687 493/494/689 +f 492/493/690 358/358/691 494/495/692 +f 494/495/692 358/358/691 361/361/693 +f 494/495/694 361/361/695 495/496/696 +f 495/496/696 361/361/695 345/345/697 +f 495/496/698 345/345/699 496/497/700 +f 496/497/700 345/345/699 355/355/701 +f 496/497/702 355/355/703 493/494/704 +f 493/494/704 355/355/703 364/364/705 +f 496/497/528 494/495/528 495/496/528 +f 496/497/528 493/494/528 494/495/528 +f 494/495/528 493/494/528 492/493/528 +f 342/342/706 497/498/707 333/333/708 +f 333/333/708 497/498/707 498/499/709 +f 333/333/710 498/499/711 499/500/712 +f 497/498/713 342/342/714 500/501/715 +f 500/501/715 342/342/714 359/359/716 +f 357/357/717 501/502/718 502/503/719 +f 357/357/717 502/503/719 359/359/720 +f 359/359/720 502/503/719 500/501/721 +f 501/502/722 503/504/723 504/505/724 +f 504/505/724 503/504/723 505/506/725 +f 501/502/722 366/366/726 503/504/723 +f 357/357/727 366/366/726 501/502/722 +f 506/507/728 507/508/729 504/505/730 +f 506/507/728 504/505/730 508/509/731 +f 504/505/724 505/506/725 508/509/732 +f 509/510/733 510/511/734 511/512/735 +f 511/512/735 510/511/734 512/513/736 +f 512/513/736 513/514/737 511/512/735 +f 511/512/735 513/514/737 506/507/738 +f 506/507/738 513/514/737 507/508/739 +f 343/343/740 514/515/741 509/510/742 +f 514/515/741 343/343/740 515/516/743 +f 333/333/710 516/517/744 343/343/745 +f 343/343/745 516/517/744 515/516/746 +f 510/511/734 517/518/747 518/519/748 +f 514/515/749 519/520/750 509/510/733 +f 509/510/733 519/520/750 510/511/734 +f 510/511/734 519/520/750 517/518/747 +f 517/518/751 519/520/752 520/521/753 +f 517/518/751 520/521/753 521/522/754 +f 520/521/755 522/523/756 521/522/757 +f 520/521/755 523/524/758 522/523/756 +f 519/520/759 514/515/760 524/525/761 +f 519/520/759 524/525/761 525/526/762 +f 516/517/744 523/524/758 525/526/763 +f 525/526/763 524/525/764 516/517/744 +f 522/523/756 523/524/758 499/500/712 +f 499/500/712 523/524/758 333/333/710 +f 523/524/758 516/517/744 333/333/710 +f 526/527/765 527/528/766 528/529/767 +f 527/528/766 529/530/768 528/529/767 +f 374/374/769 530/531/770 531/532/771 +f 532/533/772 531/532/771 530/531/770 +f 532/533/772 530/531/770 533/534/773 +f 531/532/771 532/533/772 534/535/774 +f 534/535/775 535/536/776 536/537/777 +f 534/535/774 536/537/778 537/538/779 +f 536/537/778 367/367/780 537/538/779 +f 534/535/774 537/538/779 531/532/771 +f 531/532/781 537/538/782 407/407/783 +f 531/532/781 407/407/783 406/406/784 +f 372/372/546 370/370/544 534/535/785 +f 534/535/785 370/370/544 535/536/786 +f 533/534/773 377/377/551 532/533/772 +f 376/376/550 377/377/551 533/534/773 +f 427/427/607 538/539/787 399/399/579 +f 440/440/617 399/399/579 395/395/575 +f 399/399/579 398/398/578 395/395/575 +f 440/440/617 395/395/575 394/394/574 +f 394/394/574 539/540/788 440/440/617 +f 427/427/607 399/399/579 440/440/617 +f 440/440/617 433/433/613 425/425/605 +f 440/440/617 425/425/605 427/427/607 +f 401/401/581 400/400/580 540/541/789 +f 540/541/789 400/400/580 541/542/790 +f 542/543/791 543/544/792 544/545/793 +f 543/544/792 540/541/789 545/546/794 +f 540/541/789 541/542/790 546/547/795 +f 540/541/789 546/547/795 545/546/794 +f 546/547/795 547/548/796 545/546/794 +f 540/541/789 543/544/792 548/549/797 +f 397/397/577 396/396/576 543/544/792 +f 543/544/792 396/396/576 548/549/797 +f 543/544/792 545/546/794 544/545/793 +f 544/545/798 545/546/799 420/420/601 +f 544/545/798 420/420/601 421/421/602 +f 369/369/543 373/373/547 469/470/800 +f 369/369/543 469/470/800 470/471/801 +f 490/491/684 491/492/685 549/550/802 +f 549/550/802 491/492/685 550/551/803 +f 549/550/802 550/551/803 479/480/665 +f 479/480/665 550/551/803 477/478/661 +f 481/482/804 490/491/805 482/483/806 +f 482/483/806 490/491/805 549/550/807 +f 482/483/670 549/550/808 479/480/665 +f 472/473/654 550/551/803 551/552/809 +f 477/478/661 550/551/803 472/473/654 +f 551/552/809 550/551/803 491/492/685 +f 489/490/683 490/491/805 552/553/810 +f 552/553/810 490/491/805 481/482/804 +f 552/553/810 481/482/804 483/484/811 +f 385/385/812 475/476/813 487/488/681 +f 487/488/681 475/476/813 488/489/682 +f 473/474/655 488/489/682 475/476/813 +f 473/474/655 472/473/654 551/552/809 +f 473/474/655 551/552/809 488/489/682 +f 488/489/682 551/552/809 491/492/685 +f 552/553/810 553/554/814 489/490/683 +f 484/485/676 553/554/814 485/486/677 +f 485/486/677 553/554/814 552/553/810 +f 485/486/677 552/553/810 483/484/679 +f 386/386/815 385/385/815 554/555/815 +f 555/556/816 554/555/817 385/385/812 +f 555/556/816 385/385/812 487/488/681 +f 487/488/681 489/490/683 553/554/814 +f 487/488/681 553/554/814 555/556/816 +f 555/556/818 553/554/814 554/555/819 +f 554/555/819 553/554/814 484/485/676 +f 554/555/819 484/485/676 486/487/680 +f 526/527/820 528/529/821 556/557/822 +f 556/557/822 528/529/821 501/502/722 +f 556/557/822 501/502/722 504/505/724 +f 507/508/823 526/527/820 556/557/822 +f 504/505/724 507/508/823 556/557/822 +f 500/501/824 502/503/825 557/558/826 +f 501/502/827 528/529/828 502/503/825 +f 557/558/826 502/503/825 528/529/828 +f 507/508/823 513/514/829 527/528/830 +f 507/508/823 527/528/830 526/527/820 +f 513/514/829 512/513/831 558/559/832 +f 513/514/829 558/559/832 527/528/830 +f 512/513/831 510/511/734 558/559/832 +f 558/559/832 510/511/734 559/560/833 +f 558/559/832 559/560/833 529/530/834 +f 558/559/832 529/530/834 527/528/830 +f 528/529/767 529/530/768 557/558/835 +f 557/558/835 529/530/768 560/561/836 +f 557/558/826 560/561/837 500/501/824 +f 500/501/824 560/561/837 497/498/838 +f 510/511/734 518/519/748 561/562/839 +f 562/563/840 561/562/841 499/500/712 +f 562/563/840 499/500/712 498/499/711 +f 562/563/840 529/530/842 561/562/841 +f 529/530/842 559/560/843 561/562/841 +f 559/560/833 510/511/734 561/562/839 +f 562/563/844 560/561/836 529/530/768 +f 497/498/845 560/561/836 562/563/844 +f 498/499/846 497/498/845 562/563/844 +f 469/470/847 373/373/848 402/402/849 +f 374/374/850 405/405/851 373/373/848 +f 373/373/848 405/405/851 402/402/849 +f 538/539/852 427/427/853 334/334/854 +f 334/334/854 427/427/853 332/332/855 +f 406/406/856 405/405/857 531/532/858 +f 531/532/859 405/405/851 374/374/850 +f 334/334/854 420/420/860 545/546/861 +f 334/334/854 545/546/861 547/548/862 +f 334/334/854 547/548/862 538/539/852 +f 414/414/863 471/472/864 412/412/865 +f 412/412/865 471/472/864 474/475/866 +f 412/412/865 474/475/866 410/410/867 +f 410/410/867 474/475/866 408/408/868 +f 408/408/868 474/475/866 391/391/869 +f 506/507/870 471/472/864 414/414/863 +f 343/343/871 509/510/872 418/418/873 +f 418/418/873 509/510/872 511/512/874 +f 418/418/873 511/512/874 416/416/875 +f 416/416/875 511/512/874 414/414/863 +f 414/414/863 511/512/874 506/507/870 +f 391/391/869 393/393/876 408/408/868 +f 408/408/868 393/393/876 405/405/857 +f 408/408/868 405/405/857 406/406/856 +f 420/420/860 334/334/854 418/418/873 +f 418/418/873 334/334/854 343/343/871 +f 563/564/877 470/471/878 564/565/879 +f 564/565/879 470/471/878 100/468/880 +f 369/369/881 470/471/878 565/566/882 +f 565/566/882 470/471/878 563/564/877 +f 566/567/883 367/367/884 369/369/881 +f 566/567/883 369/369/881 565/566/882 +f 566/567/883 407/407/885 537/538/886 +f 566/567/883 537/538/886 367/367/884 +f 407/407/885 566/567/883 409/409/887 +f 409/409/887 566/567/883 567/568/888 +f 409/409/887 567/568/888 411/411/889 +f 411/411/889 567/568/888 568/569/890 +f 411/411/889 568/569/890 413/413/891 +f 413/413/891 568/569/890 569/570/892 +f 413/413/891 569/570/892 415/415/893 +f 415/415/893 569/570/892 570/571/894 +f 415/415/893 570/571/894 417/417/895 +f 417/417/895 570/571/894 419/419/896 +f 419/419/896 570/571/894 571/572/897 +f 419/419/896 571/572/897 421/421/898 +f 421/421/898 571/572/897 572/573/899 +f 421/421/898 572/573/899 544/545/900 +f 544/545/900 572/573/899 542/543/901 +f 572/573/899 441/441/902 440/440/903 +f 572/573/899 440/440/903 539/540/904 +f 572/573/899 539/540/904 542/543/901 +f 508/509/905 471/472/864 506/507/870 +f 508/509/905 476/477/906 471/472/864 +f 570/571/907 569/570/907 568/569/907 +f 523/524/908 573/574/909 525/526/910 +f 525/526/910 573/574/909 574/575/911 +f 540/541/912 519/520/913 574/575/914 +f 574/575/914 519/520/913 525/526/915 +f 519/520/916 548/549/917 520/521/918 +f 575/576/919 520/521/918 548/549/917 +f 573/574/920 520/521/921 575/576/922 +f 573/574/920 523/524/923 520/521/921 +f 548/549/924 519/520/924 540/541/924 +f 548/549/925 396/396/925 575/576/925 +f 574/575/926 401/401/926 540/541/926 +f 573/574/927 395/395/927 398/398/927 +f 573/574/928 398/398/928 574/575/928 +f 575/576/929 395/395/930 573/574/931 +f 574/575/932 398/398/932 401/401/932 +f 575/576/929 396/396/933 395/395/930 +f 543/544/934 576/577/935 518/519/936 +f 518/519/936 576/577/935 561/562/937 +f 577/578/938 499/500/939 576/577/940 +f 576/577/940 499/500/939 561/562/941 +f 499/500/942 577/578/943 522/523/944 +f 522/523/944 577/578/943 578/579/945 +f 578/579/946 521/522/946 522/523/946 +f 579/580/947 521/522/947 578/579/947 +f 579/580/948 517/518/949 521/522/950 +f 543/544/951 517/518/949 579/580/948 +f 543/544/952 518/519/748 517/518/747 +f 543/544/953 542/543/953 576/577/953 +f 579/580/948 397/397/954 543/544/951 +f 397/397/955 579/580/956 578/579/957 +f 577/578/958 539/540/958 394/394/958 +f 577/578/959 394/394/959 578/579/959 +f 576/577/960 539/540/961 577/578/962 +f 578/579/957 394/394/963 397/397/955 +f 576/577/960 542/543/964 539/540/961 +f 580/581/965 515/516/966 516/517/967 +f 581/582/968 515/516/966 580/581/965 +f 546/547/969 515/516/970 581/582/971 +f 546/547/969 514/515/972 515/516/970 +f 514/515/973 541/542/973 524/525/973 +f 582/583/974 524/525/974 541/542/974 +f 516/517/975 524/525/975 582/583/975 +f 580/581/976 516/517/976 582/583/976 +f 541/542/977 514/515/977 546/547/977 +f 541/542/978 400/400/978 582/583/978 +f 581/582/979 547/548/980 546/547/981 +f 538/539/982 547/548/980 581/582/979 +f 582/583/983 399/399/983 580/581/983 +f 580/581/984 399/399/984 538/539/984 +f 580/581/985 538/539/982 581/582/979 +f 582/583/986 400/400/986 399/399/986 +f 382/382/987 583/584/988 390/390/989 +f 584/585/990 388/388/991 583/584/992 +f 583/584/992 388/388/991 390/390/993 +f 534/535/994 384/384/995 584/585/996 +f 584/585/996 384/384/995 388/388/997 +f 379/379/998 532/533/999 380/380/1000 +f 380/380/1000 532/533/999 585/586/1001 +f 585/586/1001 382/382/1002 380/380/1000 +f 585/586/1003 583/584/988 382/382/987 +f 534/535/1004 379/379/1005 384/384/1006 +f 532/533/1007 379/379/1005 534/535/1004 +f 532/533/1008 377/377/1008 585/586/1008 +f 584/585/996 372/372/1009 534/535/994 +f 585/586/1010 377/377/1010 371/371/1010 +f 585/586/1011 371/371/1011 583/584/1011 +f 583/584/1012 371/371/1012 372/372/1012 +f 583/584/1013 372/372/1013 584/585/1013 +f 586/587/1014 486/487/1015 389/389/1016 +f 587/588/1017 554/555/1018 586/587/1019 +f 586/587/1019 554/555/1018 486/487/1020 +f 536/537/1021 554/555/1022 587/588/1023 +f 536/537/1021 386/386/1024 554/555/1022 +f 588/589/1025 389/389/1026 589/590/1027 +f 589/590/1027 389/389/1026 387/387/1028 +f 588/589/1029 586/587/1014 389/389/1016 +f 386/386/1030 536/537/777 535/536/776 +f 589/590/1031 387/387/1032 386/386/1033 +f 589/590/1031 386/386/1033 535/536/1034 +f 589/590/1035 370/370/1035 588/589/1035 +f 589/590/1031 535/536/1034 370/370/1036 +f 587/588/1037 367/367/1037 536/537/1037 +f 588/589/1029 370/370/1038 586/587/1014 +f 586/587/1039 370/370/1039 368/368/1039 +f 586/587/1040 368/368/1041 367/367/1042 +f 586/587/1040 367/367/1042 587/588/1043 +f 590/591/1044 383/383/1045 591/592/1046 +f 590/591/1044 381/381/1047 383/383/1045 +f 533/534/1048 378/378/1049 590/591/1050 +f 590/591/1051 378/378/1051 381/381/1051 +f 378/378/1052 530/531/1053 392/392/1054 +f 392/392/1054 530/531/1053 592/593/1055 +f 383/383/1056 392/392/1057 592/593/1058 +f 591/592/1059 383/383/1056 592/593/1058 +f 530/531/1060 378/378/1060 533/534/1060 +f 592/593/1061 530/531/1061 374/374/1061 +f 533/534/1048 590/591/1050 376/376/1062 +f 592/593/1063 374/374/1063 375/375/1063 +f 592/593/1064 375/375/1064 591/592/1064 +f 591/592/1065 375/375/1065 376/376/1065 +f 591/592/1066 376/376/1066 590/591/1066 +f 503/504/1067 478/479/1068 505/506/1069 +f 480/481/1070 478/479/1068 503/504/1067 +f 476/477/1071 508/509/1072 505/506/1073 +f 476/477/1071 505/506/1073 478/479/1074 +f 480/481/1075 363/363/1076 362/362/1077 +f 503/504/1078 366/366/1079 363/363/1076 +f 363/363/1076 480/481/1075 503/504/1078 +f 593/594/1080 594/595/1080 595/596/1080 +f 595/596/1081 594/595/1081 596/597/1081 +f 596/597/1082 597/598/1082 595/596/1082 +f 597/598/1083 593/594/1083 595/596/1083 +f 593/594/1084 451/451/1085 594/595/1086 +f 594/595/1086 451/451/1085 328/328/1087 +f 594/595/1088 328/328/1089 596/597/1090 +f 596/597/1090 328/328/1089 450/450/1091 +f 596/597/1092 450/450/1093 597/598/1094 +f 597/598/1094 450/450/1093 443/443/1095 +f 597/598/1096 443/443/1097 451/451/1098 +f 597/598/1096 451/451/1098 593/594/1099 +f 598/599/1100 599/600/1100 600/601/1100 +f 598/599/1101 600/601/1101 601/602/1101 +f 598/599/1102 601/602/1102 602/603/1102 +f 598/599/1103 602/603/1103 599/600/1103 +f 600/601/1104 330/330/1104 429/429/1104 +f 600/601/1105 429/429/1105 601/602/1105 +f 601/602/1106 429/429/1106 452/452/1106 +f 601/602/1107 452/452/1107 602/603/1107 +f 602/603/1108 452/452/1108 331/331/1108 +f 602/603/1109 331/331/1109 599/600/1109 +f 599/600/1110 331/331/1110 330/330/1110 +f 599/600/1111 330/330/1111 600/601/1111 +f 603/604/1112 604/605/1112 605/606/1112 +f 604/605/1113 606/607/1113 605/606/1113 +f 606/607/1114 607/608/1114 605/606/1114 +f 607/608/1115 603/604/1115 605/606/1115 +f 603/604/1116 457/457/1117 604/605/1118 +f 604/605/1118 457/457/1117 458/458/1119 +f 604/605/1120 458/458/1120 606/607/1120 +f 606/607/1121 458/458/1122 459/459/1123 +f 606/607/1121 459/459/1123 607/608/1124 +f 607/608/1125 459/459/1125 329/329/1125 +f 607/608/1126 329/329/1126 603/604/1126 +f 603/604/1127 329/329/1127 457/457/1127 +f 608/609/1128 609/610/1128 610/611/1128 +f 610/611/1129 611/612/1129 608/609/1129 +f 611/612/1130 612/613/1130 608/609/1130 +f 608/609/1131 612/613/1131 609/610/1131 +f 609/610/1132 431/431/1133 610/611/1134 +f 610/611/1134 431/431/1133 434/434/1135 +f 610/611/1136 434/434/1137 611/612/1138 +f 611/612/1138 434/434/1137 433/433/1139 +f 611/612/1140 433/433/1141 432/432/1142 +f 611/612/1140 432/432/1142 612/613/1143 +f 612/613/1144 432/432/1145 431/431/1146 +f 612/613/1144 431/431/1146 609/610/1147 +f 613/614/1148 614/615/1148 615/616/1148 +f 614/615/1149 616/617/1149 615/616/1149 +f 616/617/1150 617/618/1150 615/616/1150 +f 615/616/1151 617/618/1151 613/614/1151 +f 613/614/1152 438/438/1153 614/615/1154 +f 614/615/1154 438/438/1153 435/435/1155 +f 614/615/1156 435/435/1157 616/617/1158 +f 616/617/1158 435/435/1157 436/436/1159 +f 616/617/1160 436/436/1161 617/618/1162 +f 617/618/1162 436/436/1161 439/439/1163 +f 617/618/1164 439/439/1164 613/614/1164 +f 613/614/1165 439/439/1165 438/438/1165 +f 618/619/1166 619/620/1166 620/621/1166 +f 619/620/1167 621/622/1167 620/621/1167 +f 621/622/1168 622/623/1168 620/621/1168 +f 622/623/1169 618/619/1169 620/621/1169 +f 618/619/1170 444/444/1171 430/430/1172 +f 618/619/1173 430/430/1173 619/620/1173 +f 619/620/1174 430/430/1174 446/446/1174 +f 619/620/1175 446/446/1176 621/622/1177 +f 621/622/1177 446/446/1176 445/445/1178 +f 621/622/1179 445/445/1180 444/444/1181 +f 621/622/1179 444/444/1181 622/623/1182 +f 622/623/1183 444/444/1171 618/619/1170 +f 623/624/1184 624/625/1184 625/626/1184 +f 624/625/1185 626/627/1185 625/626/1185 +f 625/626/1186 626/627/1186 627/628/1186 +f 627/628/1187 623/624/1187 625/626/1187 +f 623/624/1188 423/423/1188 428/428/1188 +f 623/624/1189 428/428/1189 624/625/1189 +f 624/625/1190 428/428/1190 426/426/1190 +f 624/625/1191 426/426/1191 626/627/1191 +f 626/627/1192 426/426/1192 424/424/1192 +f 626/627/1193 424/424/1193 627/628/1193 +f 627/628/1194 424/424/1194 423/423/1194 +f 627/628/1195 423/423/1195 623/624/1195 +f 628/629/1196 629/630/1196 630/631/1196 +f 629/630/1197 631/632/1197 630/631/1197 +f 631/632/1198 632/633/1198 630/631/1198 +f 632/633/1199 628/629/1199 630/631/1199 +f 628/629/1200 449/449/1201 629/630/1202 +f 629/630/1202 449/449/1201 448/448/1203 +f 629/630/1204 448/448/1205 447/447/1206 +f 629/630/1204 447/447/1206 631/632/1207 +f 631/632/1208 447/447/1209 632/633/1210 +f 632/633/1210 447/447/1209 442/442/1211 +f 632/633/1212 442/442/1212 628/629/1212 +f 628/629/1213 442/442/1213 449/449/1213 +f 633/634/1214 634/635/1214 635/636/1214 +f 635/636/1215 634/635/1215 636/637/1215 +f 636/637/1216 637/638/1216 635/636/1216 +f 637/638/1217 633/634/1217 635/636/1217 +f 633/634/1218 453/453/1219 455/455/1220 +f 633/634/1218 455/455/1220 634/635/1221 +f 634/635/1222 455/455/1223 636/637/1224 +f 636/637/1224 455/455/1223 456/456/1225 +f 636/637/1226 456/456/1227 454/454/1228 +f 636/637/1226 454/454/1228 637/638/1229 +f 637/638/1230 454/454/1231 633/634/1232 +f 633/634/1232 454/454/1231 453/453/1233 +f 300/300/485 638/639/1234 301/301/486 +f 301/301/486 638/639/1234 639/640/1235 +f 640/641/1236 301/301/486 639/640/1235 +f 640/641/1236 639/640/1235 641/642/1237 +f 641/642/1237 638/639/1234 642/643/1238 +f 642/643/1238 638/639/1234 300/300/485 +f 303/303/488 643/644/1239 640/641/1236 +f 640/641/1236 641/642/1237 642/643/1238 +f 303/303/488 301/301/486 643/644/1239 +f 644/645/1240 645/646/1241 642/643/1238 +f 642/643/1238 645/646/1241 303/303/488 +f 642/643/1238 303/303/488 640/641/1236 +f 642/643/1242 646/647/1243 647/648/1244 +f 647/648/1244 644/645/528 642/643/1242 +f 303/303/1245 645/646/98 648/649/98 +f 303/303/1245 648/649/98 649/650/1246 +f 650/651/1247 306/306/1247 305/305/1247 +f 651/652/1248 463/463/639 465/465/641 +f 651/652/1248 650/651/1249 463/463/639 +f 308/308/528 300/300/1250 652/653/528 +f 465/465/1251 304/304/528 651/652/528 +f 308/308/528 652/653/528 653/654/528 +f 651/652/1252 306/306/1253 650/651/1254 +f 304/304/1255 306/306/1253 651/652/1252 +f 305/305/1256 307/307/1257 462/462/1258 +f 463/463/1259 650/651/1260 462/462/1258 +f 462/462/1258 650/651/1260 305/305/1256 +f 654/655/1261 319/319/1262 655/656/1263 +f 655/656/1263 319/319/1262 318/318/1264 +f 312/312/1265 654/655/1266 656/657/1267 +f 656/657/1267 311/311/1268 312/312/1265 +f 657/658/1269 655/656/1270 317/317/1271 +f 657/658/1269 317/317/1271 325/325/1272 +f 657/658/1273 324/324/1274 658/659/1275 +f 658/659/1275 324/324/1274 327/327/1276 +f 317/317/1271 655/656/1270 318/318/1277 +f 319/319/1278 654/655/1278 312/312/1278 +f 324/324/1279 657/658/1269 325/325/1272 +f 311/311/1268 656/657/1267 327/327/1280 +f 658/659/1281 327/327/1280 656/657/1267 +f 659/660/1282 660/661/1283 661/662/1284 +f 661/662/1284 660/661/1283 662/663/1285 +f 467/467/643 661/662/1284 466/466/642 +f 466/466/642 661/662/1284 662/663/1285 +f 663/664/1286 664/665/1287 659/660/1282 +f 659/660/1282 664/665/1287 660/661/1283 +f 665/666/1288 464/464/645 666/667/1289 +f 464/464/645 665/666/1288 468/469/646 +f 666/667/1290 660/661/1291 667/668/1292 +f 659/660/1293 665/666/1293 668/669/1293 +f 663/664/1294 665/666/1288 664/665/1295 +f 666/667/1289 664/665/1295 665/666/1288 +f 464/464/1296 466/466/1297 662/663/1298 +f 464/464/1296 662/663/1298 666/667/1290 +f 660/661/1291 666/667/1290 662/663/1298 +f 665/666/1299 659/660/1300 468/469/650 +f 659/660/1300 661/662/1301 468/469/650 +f 468/469/650 661/662/1301 467/467/643 +f 667/668/1302 664/665/1302 666/667/1302 +f 667/668/1303 660/661/1303 664/665/1303 +f 663/664/1304 668/669/1304 665/666/1304 +f 663/664/1305 659/660/1305 668/669/1305 +f 669/670/1306 301/301/1306 670/671/1306 +f 669/670/1307 643/644/1307 301/301/1307 +f 643/644/1308 669/670/1308 671/672/1308 +f 643/644/1309 671/672/1309 640/641/1309 +f 640/641/1310 671/672/1310 670/671/1310 +f 670/671/1311 301/301/1311 640/641/1311 +f 639/640/1312 672/673/1312 641/642/1312 +f 641/642/1313 673/674/1313 638/639/1313 +f 674/675/1314 638/639/1314 673/674/1314 +f 638/639/1315 674/675/1315 639/640/1315 +f 300/300/1316 302/302/1317 652/653/1318 +f 652/653/1318 302/302/1317 675/676/1319 +f 676/677/1320 677/678/1321 678/679/1322 +f 652/653/1323 679/680/1324 680/681/1325 +f 679/680/1324 652/653/1323 675/676/1326 +f 653/654/1327 676/677/1320 678/679/1322 +f 678/679/1322 681/682/1328 675/676/1326 +f 675/676/1326 681/682/1328 682/683/1329 +f 675/676/1326 677/678/1321 679/680/1324 +f 676/677/1320 653/654/1327 683/684/1330 +f 676/677/1320 683/684/1330 684/685/1331 +f 680/681/1325 684/685/1331 685/686/1332 +f 686/687/1333 683/684/1330 653/654/1327 +f 680/681/1325 685/686/1332 652/653/1323 +f 685/686/1332 686/687/1333 652/653/1323 +f 684/685/1331 680/681/1325 676/677/1320 +f 682/683/1329 687/688/1334 677/678/1321 +f 687/688/1334 681/682/1328 677/678/1321 +f 677/678/1321 681/682/1328 678/679/1322 +f 652/653/1323 686/687/1333 653/654/1327 +f 675/676/1326 682/683/1329 677/678/1321 +f 653/654/1335 678/679/1336 308/308/1337 +f 308/308/1337 678/679/1336 460/460/1338 +f 308/308/493 460/460/636 307/307/492 +f 675/676/1339 460/460/98 678/679/98 +f 688/689/1340 689/690/1340 690/691/1340 +f 688/689/1341 690/691/1341 691/692/1341 +f 688/689/1342 691/692/1342 692/693/1342 +f 688/689/1343 692/693/1343 689/690/1343 +f 689/690/1344 683/684/1345 686/687/1346 +f 689/690/1344 686/687/1346 690/691/1347 +f 690/691/1348 686/687/1349 691/692/1350 +f 691/692/1350 686/687/1349 685/686/1351 +f 691/692/1352 685/686/1353 692/693/1354 +f 692/693/1354 685/686/1353 684/685/1355 +f 692/693/1356 684/685/1357 689/690/1358 +f 689/690/1358 684/685/1357 683/684/1359 +f 693/694/1360 694/695/1360 695/696/1360 +f 694/695/1361 696/697/1361 695/696/1361 +f 696/697/1362 697/698/1362 695/696/1362 +f 695/696/1363 697/698/1363 693/694/1363 +f 693/694/1364 681/682/1364 687/688/1364 +f 693/694/1365 687/688/1365 694/695/1365 +f 694/695/1366 687/688/1366 682/683/1366 +f 694/695/1367 682/683/1367 696/697/1367 +f 696/697/1368 682/683/1369 697/698/1370 +f 697/698/1370 682/683/1369 681/682/1371 +f 697/698/1372 681/682/1372 693/694/1372 +f 698/699/1373 699/700/1373 700/701/1373 +f 700/701/1374 699/700/1374 701/702/1374 +f 701/702/1375 702/703/1375 700/701/1375 +f 702/703/1376 698/699/1376 700/701/1376 +f 698/699/1377 676/677/1378 699/700/1379 +f 699/700/1379 676/677/1378 680/681/1380 +f 699/700/1381 680/681/1382 679/680/1383 +f 699/700/1381 679/680/1383 701/702/1384 +f 701/702/1385 679/680/1386 677/678/1387 +f 701/702/1385 677/678/1387 702/703/1388 +f 702/703/1389 677/678/1390 698/699/1391 +f 698/699/1391 677/678/1390 676/677/1392 +f 649/650/1393 703/704/1394 704/705/1395 +f 703/704/1394 646/647/1396 705/706/1397 +f 704/705/1395 703/704/1394 705/706/1397 +f 706/707/1398 707/708/1399 708/709/1400 +f 708/709/1400 707/708/1399 709/710/1401 +f 709/710/1401 710/711/1402 708/709/1400 +f 313/313/1403 711/712/1404 314/314/1405 +f 314/314/1405 711/712/1404 712/713/1406 +f 713/714/1407 714/715/1408 712/713/1409 +f 713/714/1407 712/713/1409 711/712/1410 +f 365/365/1411 715/716/1412 716/717/1413 +f 713/714/1407 717/718/1414 714/715/1408 +f 714/715/1408 717/718/1414 715/716/1412 +f 715/716/1412 717/718/1414 718/719/1415 +f 715/716/1412 718/719/1415 716/717/1413 +f 719/720/1416 715/716/1412 365/365/1411 +f 719/720/1416 365/365/1411 720/721/1417 +f 721/722/1418 722/723/1419 723/724/1420 +f 723/724/1420 724/725/1421 725/726/1422 +f 724/725/1421 726/727/1423 725/726/1422 +f 727/728/1424 725/726/1422 726/727/1423 +f 723/724/1420 728/729/1425 724/725/1421 +f 723/724/1420 722/723/1419 728/729/1425 +f 728/729/1425 722/723/1419 729/730/1426 +f 728/729/1425 729/730/1426 730/731/1427 +f 731/732/1428 732/733/1429 728/729/1425 +f 728/729/1425 732/733/1429 724/725/1421 +f 733/734/1430 734/735/1431 735/736/1432 +f 734/735/1431 736/737/1433 735/736/1432 +f 734/735/1431 737/738/1434 736/737/1433 +f 736/737/1433 737/738/1434 738/739/1435 +f 739/740/1436 740/741/1437 741/742/1438 +f 740/741/1437 739/740/1436 742/743/1439 +f 742/743/1439 739/740/1436 743/744/1440 +f 742/743/1441 743/744/1442 744/745/1443 +f 742/743/1441 744/745/1443 745/746/1444 +f 744/745/1443 746/747/1445 745/746/1444 +f 739/740/1446 741/742/1447 738/739/1448 +f 739/740/1446 738/739/1448 737/738/1449 +f 739/740/1450 737/738/1451 747/748/1452 +f 747/748/1452 737/738/1451 748/749/1453 +f 748/749/1453 737/738/1451 749/750/1454 +f 748/749/1453 749/750/1454 750/751/1455 +f 748/749/1453 750/751/1455 751/752/1456 +f 750/751/1455 744/745/1443 751/752/1456 +f 744/745/1443 750/751/1455 752/753/1457 +f 752/753/1457 733/734/1458 735/736/1459 +f 753/754/1460 754/755/1461 755/756/1462 +f 756/757/1463 757/758/1464 758/759/1465 +f 756/757/1463 758/759/1465 759/760/1466 +f 760/761/1467 761/762/1468 762/763/1469 +f 760/761/1467 763/764/1470 761/762/1468 +f 764/765/1471 765/766/1472 766/767/1473 +f 735/736/1474 767/768/1475 768/769/1476 +f 768/769/1476 767/768/1475 769/770/1477 +f 769/770/1477 770/771/528 768/769/1476 +f 771/772/1478 772/773/1479 773/774/1480 +f 773/774/1480 772/773/1479 774/775/1481 +f 773/774/1480 774/775/1481 775/776/1482 +f 775/776/1482 774/775/1481 776/777/1483 +f 775/776/1482 776/777/1483 777/778/1484 +f 777/778/1484 776/777/1483 778/779/1485 +f 777/778/1484 778/779/1485 779/780/1486 +f 779/780/1486 778/779/1485 780/781/1487 +f 779/780/1486 780/781/1487 781/782/1488 +f 781/782/1488 780/781/1487 782/783/1489 +f 781/782/1488 782/783/1489 736/737/1490 +f 736/737/1491 782/783/1491 783/784/1491 +f 783/784/1492 782/783/1493 784/785/1494 +f 783/784/1492 784/785/1494 785/786/1495 +f 785/786/1495 784/785/1494 786/787/1496 +f 754/755/1461 787/788/1497 788/789/1498 +f 337/337/1499 787/788/1497 754/755/1461 +f 788/789/1498 787/788/1497 789/790/1500 +f 790/791/1501 791/792/1500 350/350/1502 +f 337/337/1499 792/793/1503 787/788/1497 +f 789/790/1500 791/792/1500 790/791/1501 +f 350/350/1502 791/792/1500 792/793/1503 +f 788/789/1498 789/790/1500 790/791/1501 +f 350/350/1502 792/793/1503 337/337/1499 +f 793/794/1504 794/795/1505 795/796/1506 +f 795/796/1506 794/795/1505 796/797/1507 +f 797/798/1501 798/799/1508 799/800/1502 +f 795/796/1506 796/797/1507 797/798/1501 +f 795/796/1506 797/798/1501 799/800/1502 +f 716/717/1413 718/719/1415 800/801/1509 +f 790/791/1501 801/802/1501 802/803/1503 +f 798/799/1508 801/802/1501 790/791/1501 +f 788/789/1498 803/804/1510 794/795/1505 +f 794/795/1505 803/804/1510 804/805/1511 +f 798/799/1508 804/805/1511 801/802/1501 +f 788/789/1498 805/806/1512 803/804/1510 +f 790/791/1501 802/803/1503 788/789/1498 +f 788/789/1498 802/803/1503 805/806/1512 +f 806/807/1513 807/808/1514 808/809/1503 +f 809/810/1501 798/799/1508 810/811/1501 +f 790/791/1501 810/811/1501 798/799/1508 +f 798/799/1508 809/810/1501 807/808/1514 +f 807/808/1514 809/810/1501 808/809/1503 +f 790/791/1501 811/812/1515 810/811/1501 +f 806/807/1513 811/812/1515 790/791/1501 +f 812/813/1501 813/814/1502 352/352/1516 +f 350/350/1502 813/814/1502 814/815/1501 +f 350/350/1502 814/815/1501 790/791/1501 +f 790/791/1501 812/813/1501 806/807/1513 +f 352/352/1516 813/814/1502 350/350/1502 +f 352/352/1516 815/816/1501 800/801/1509 +f 352/352/1516 800/801/1509 807/808/1514 +f 352/352/1516 807/808/1514 806/807/1513 +f 352/352/1516 806/807/1513 812/813/1501 +f 365/365/1411 716/717/1413 816/817/1517 +f 352/352/1516 816/817/1517 815/816/1501 +f 365/365/1411 816/817/1517 352/352/1516 +f 800/801/1509 815/816/1501 817/818/1518 +f 800/801/1509 817/818/1518 716/717/1413 +f 818/819/1519 819/820/1503 807/808/1514 +f 798/799/1508 820/821/1502 799/800/1502 +f 799/800/1502 820/821/1502 821/822/1500 +f 807/808/1514 819/820/1503 820/821/1502 +f 794/795/1505 804/805/1511 798/799/1508 +f 798/799/1508 807/808/1514 820/821/1502 +f 799/800/1502 821/822/1500 822/823/1520 +f 822/823/1520 821/822/1500 818/819/1519 +f 807/808/1514 822/823/1520 818/819/1519 +f 807/808/1514 823/824/1521 822/823/1520 +f 822/823/1520 823/824/1521 824/825/1522 +f 713/714/1407 825/826/1523 717/718/1414 +f 824/825/1522 825/826/1523 713/714/1407 +f 717/718/1414 823/824/1521 807/808/1514 +f 825/826/1523 823/824/1521 717/718/1414 +f 822/823/1520 824/825/1522 713/714/1407 +f 321/321/507 322/322/508 720/721/1524 +f 720/721/1524 322/322/508 719/720/1525 +f 826/827/1526 827/828/1527 828/829/1528 +f 828/829/1528 827/828/1527 706/707/1398 +f 706/707/1398 827/828/1527 829/830/1529 +f 830/831/1530 831/832/1531 826/827/1526 +f 826/827/1526 831/832/1531 832/833/1532 +f 833/834/1533 235/835/1534 832/833/1532 +f 832/833/1532 235/835/1534 827/828/1527 +f 832/833/1532 827/828/1527 826/827/1526 +f 834/836/1535 835/837/1536 836/838/1537 +f 834/836/1535 836/838/1537 833/834/1533 +f 833/834/1533 836/838/1537 235/835/1534 +f 835/837/1536 830/831/1530 769/770/1538 +f 834/836/1535 831/832/1531 835/837/1536 +f 835/837/1536 831/832/1531 830/831/1530 +f 736/737/1433 738/739/1435 837/839/1539 +f 837/839/1539 738/739/1435 838/840/1540 +f 838/840/1540 839/841/1541 837/839/1539 +f 837/839/1539 839/841/1541 840/842/1542 +f 840/842/1542 839/841/1541 841/843/1543 +f 842/844/1544 764/765/1545 840/842/1546 +f 842/844/1544 840/842/1546 841/843/1547 +f 843/845/1548 844/846/1549 842/844/1544 +f 842/844/1544 844/846/1549 845/847/1550 +f 842/844/1544 845/847/1550 764/765/1545 +f 843/845/1548 347/347/1551 844/846/1549 +f 846/848/1552 347/347/1551 843/845/1548 +f 847/849/1553 346/346/1554 846/848/1552 +f 846/848/1552 346/346/1554 347/347/1551 +f 346/346/1555 847/849/1556 848/850/1557 +f 346/346/1555 848/850/1557 770/771/1558 +f 770/771/1558 848/850/1557 849/851/1559 +f 770/771/1560 849/851/1561 768/769/1562 +f 768/769/1562 849/851/1561 850/852/1563 +f 850/852/1564 746/747/1445 744/745/1443 +f 735/736/1459 768/769/1565 752/753/1457 +f 850/852/1564 744/745/1443 768/769/1565 +f 768/769/1565 744/745/1443 752/753/1457 +f 851/853/1566 852/854/1567 853/855/1568 +f 854/856/1569 851/853/1566 855/857/1570 +f 855/857/1570 851/853/1566 853/855/1568 +f 353/353/1571 856/858/1572 857/859/1573 +f 353/353/1571 857/859/1573 341/341/1574 +f 341/341/1575 857/859/1576 360/360/1577 +f 360/360/1577 857/859/1576 858/860/1578 +f 360/360/1579 858/860/1580 348/348/1581 +f 348/348/1581 858/860/1580 859/861/1582 +f 348/348/1583 859/861/1584 351/351/1585 +f 351/351/1585 859/861/1584 860/862/1586 +f 351/351/1587 860/862/1588 353/353/1589 +f 353/353/1589 860/862/1588 856/858/1590 +f 860/862/528 859/861/528 858/860/528 +f 858/860/528 857/859/528 860/862/528 +f 860/862/528 857/859/528 856/858/528 +f 336/336/1591 861/863/1592 862/864/1593 +f 336/336/1591 862/864/1593 344/344/1594 +f 344/344/1595 862/864/1596 339/339/1597 +f 339/339/1597 862/864/1596 863/865/1598 +f 339/339/1599 863/865/1600 864/866/1601 +f 339/339/1599 864/866/1601 340/340/1602 +f 340/340/1602 864/866/1601 865/867/1603 +f 866/868/1604 867/869/1605 868/870/1606 +f 866/868/1604 868/870/1606 865/867/1607 +f 865/867/1607 868/870/1606 340/340/1608 +f 340/340/1608 868/870/1606 349/349/1609 +f 867/869/1605 866/868/1604 766/767/1610 +f 866/868/1604 869/871/1611 766/767/1610 +f 869/871/1611 866/868/1604 870/872/1612 +f 869/871/1613 870/872/1614 871/873/1615 +f 869/871/1613 871/873/1615 872/874/1616 +f 872/874/1616 871/873/1615 873/875/1617 +f 872/874/1616 873/875/1617 874/876/1618 +f 872/874/1616 874/876/1618 875/877/1619 +f 876/878/1620 877/879/1621 878/880/1622 +f 876/878/1620 878/880/1622 879/881/1623 +f 876/878/1620 879/881/1623 880/882/1624 +f 880/882/1625 879/881/1626 881/883/1627 +f 881/883/1627 879/881/1626 882/884/1628 +f 881/883/1629 882/884/1629 875/877/1629 +f 881/883/1630 874/876/1618 883/885/1631 +f 881/883/1632 883/885/1633 884/886/1634 +f 884/886/1634 883/885/1633 885/887/1635 +f 885/887/1635 883/885/1633 886/888/1636 +f 885/887/1635 886/888/1636 887/889/1637 +f 888/890/1638 887/889/1637 886/888/1636 +f 888/890/1638 876/878/1620 887/889/1637 +f 874/876/1618 889/891/1639 883/885/1631 +f 875/877/1619 874/876/1618 881/883/1630 +f 875/877/1640 882/884/1641 338/338/1642 +f 338/338/1642 882/884/1641 890/892/1643 +f 890/892/1644 877/879/1621 338/338/1645 +f 338/338/1645 877/879/1621 336/336/1646 +f 336/336/1646 876/878/1620 861/863/1647 +f 876/878/1620 888/890/1638 861/863/1647 +f 336/336/1646 877/879/1621 876/878/1620 +f 891/893/1648 892/894/1649 893/895/1650 +f 892/894/1649 891/893/1648 894/896/1651 +f 730/731/1427 729/730/1426 895/897/1652 +f 730/731/1427 895/897/1652 896/898/1653 +f 897/899/1654 727/728/1655 898/900/1656 +f 898/900/1656 896/898/1653 899/901/1657 +f 896/898/1658 898/900/1659 900/902/1660 +f 896/898/1653 895/897/1652 901/903/1661 +f 896/898/1653 901/903/1661 899/901/1657 +f 901/903/1661 721/722/1662 899/901/1657 +f 900/902/1663 898/900/1664 732/733/1429 +f 900/902/1663 732/733/1429 731/732/1428 +f 785/786/1665 786/787/1666 897/899/1667 +f 785/786/1665 897/899/1667 899/901/1668 +f 899/901/1657 897/899/1654 898/900/1656 +f 793/794/1504 902/904/1669 759/760/1466 +f 754/755/1461 759/760/1466 762/763/1469 +f 762/763/1469 759/760/1466 758/759/1465 +f 754/755/1461 762/763/1469 761/762/1468 +f 761/762/1468 755/756/1462 754/755/1461 +f 793/794/1504 759/760/1466 754/755/1461 +f 754/755/1461 788/789/1498 793/794/1504 +f 793/794/1504 788/789/1498 794/795/1505 +f 772/773/1670 771/772/1671 903/905/1672 +f 772/773/1670 903/905/1672 904/906/1673 +f 903/905/1674 753/754/1675 905/907/1676 +f 906/908/1677 903/905/1674 905/907/1676 +f 907/909/1678 908/910/1679 904/906/1680 +f 906/908/1677 909/911/1681 903/905/1674 +f 909/911/1681 907/909/1678 903/905/1674 +f 903/905/1674 907/909/1678 904/906/1680 +f 907/909/1678 909/911/1681 757/758/1464 +f 907/909/1678 757/758/1464 756/757/1463 +f 763/764/1470 760/761/1467 906/908/1677 +f 763/764/1470 906/908/1677 905/907/1676 +f 723/724/1420 725/726/1422 835/837/1536 +f 835/837/1536 725/726/1422 836/838/1537 +f 843/845/1682 842/844/1683 910/912/1684 +f 843/845/1682 910/912/1684 911/913/1685 +f 911/913/1685 910/912/1684 854/856/1569 +f 911/913/1685 854/856/1569 855/857/1570 +f 847/849/1686 911/913/1687 855/857/1688 +f 843/845/1548 911/913/1687 846/848/1552 +f 847/849/1686 846/848/1552 911/913/1687 +f 841/843/1547 910/912/1689 842/844/1544 +f 848/850/1690 847/849/1686 855/857/1688 +f 848/850/1690 855/857/1688 853/855/1691 +f 841/843/1692 839/841/1693 910/912/1694 +f 910/912/1694 839/841/1693 851/853/1695 +f 910/912/1694 851/853/1695 854/856/1696 +f 839/841/1693 912/914/1697 851/853/1695 +f 839/841/1693 838/840/1698 912/914/1697 +f 838/840/1698 738/739/1699 912/914/1697 +f 912/914/1697 738/739/1699 852/854/1700 +f 912/914/1697 852/854/1700 851/853/1695 +f 849/851/1701 848/850/1702 853/855/1703 +f 850/852/1704 849/851/1701 853/855/1703 +f 738/739/1705 741/742/1705 913/915/1705 +f 852/854/1706 738/739/1707 913/915/1708 +f 746/747/1445 850/852/1564 913/915/1708 +f 913/915/1708 850/852/1564 852/854/1706 +f 852/854/1706 850/852/1564 853/855/1709 +f 866/868/1604 865/867/1607 914/916/1710 +f 914/916/1710 865/867/1607 915/917/1711 +f 914/916/1712 915/917/1713 893/895/1650 +f 893/895/1650 915/917/1713 891/893/1648 +f 866/868/1604 914/916/1714 870/872/1612 +f 870/872/1612 914/916/1714 893/895/1715 +f 915/917/1713 864/866/1716 891/893/1648 +f 863/865/1717 916/918/1718 864/866/1716 +f 891/893/1648 864/866/1716 916/918/1718 +f 915/917/1713 865/867/1719 864/866/1716 +f 874/876/1720 873/875/1721 892/894/1649 +f 874/876/1720 892/894/1649 917/919/1722 +f 894/896/1651 917/919/1722 892/894/1649 +f 873/875/1721 871/873/1723 892/894/1649 +f 871/873/1723 893/895/1715 892/894/1649 +f 871/873/1723 870/872/1612 893/895/1715 +f 863/865/1724 862/864/1725 916/918/1726 +f 916/918/1726 862/864/1725 918/920/1727 +f 916/918/1728 918/920/1729 891/893/1648 +f 891/893/1648 918/920/1729 894/896/1651 +f 889/891/1730 874/876/1720 919/921/1731 +f 861/863/1647 888/890/1638 919/921/1732 +f 920/922/1733 917/919/1722 921/923/1734 +f 921/923/1734 917/919/1722 894/896/1651 +f 920/922/1735 919/921/1731 874/876/1720 +f 920/922/1735 874/876/1720 917/919/1722 +f 861/863/1647 919/921/1732 920/922/1736 +f 921/923/1734 894/896/1651 918/920/1729 +f 862/864/1737 921/923/1734 918/920/1729 +f 861/863/1647 920/922/1736 921/923/1734 +f 861/863/1647 921/923/1734 862/864/1737 +f 723/724/1738 835/837/1739 769/770/1740 +f 767/768/1741 721/722/1742 769/770/1740 +f 769/770/1740 721/722/1742 723/724/1738 +f 335/335/1743 337/337/1744 754/755/1745 +f 335/335/1743 754/755/1745 753/754/1746 +f 767/768/1741 785/786/1747 899/901/1748 +f 767/768/1741 899/901/1748 721/722/1742 +f 771/772/1749 335/335/1743 903/905/1750 +f 903/905/1750 335/335/1743 753/754/1746 +f 773/774/1751 875/877/1752 338/338/1753 +f 779/780/1486 869/871/1754 777/778/1755 +f 777/778/1755 869/871/1754 872/874/1756 +f 777/778/1755 872/874/1756 775/776/1757 +f 775/776/1757 872/874/1756 773/774/1751 +f 773/774/1751 872/874/1756 875/877/1752 +f 840/842/1758 869/871/1754 779/780/1486 +f 783/784/1759 735/736/1760 736/737/1761 +f 736/737/1762 837/839/1762 781/782/1762 +f 781/782/1488 837/839/1763 779/780/1486 +f 779/780/1486 837/839/1763 840/842/1758 +f 335/335/1743 771/772/1749 773/774/1751 +f 335/335/1743 773/774/1751 338/338/1753 +f 785/786/1747 767/768/1741 783/784/1759 +f 783/784/1759 767/768/1741 735/736/1760 +f 836/838/1764 922/924/1765 923/925/1766 +f 923/925/1766 235/835/1767 836/838/1764 +f 922/924/1765 836/838/1764 725/726/1768 +f 922/924/1765 725/726/1768 924/926/1769 +f 727/728/1770 925/927/1771 725/726/1768 +f 725/726/1768 925/927/1771 924/926/1769 +f 786/787/1772 925/927/1771 897/899/1773 +f 897/899/1773 925/927/1771 727/728/1770 +f 925/927/1771 786/787/1772 784/785/1774 +f 925/927/1771 784/785/1774 926/928/1775 +f 926/928/1775 784/785/1774 782/783/1776 +f 926/928/1775 782/783/1776 927/929/1777 +f 927/929/1777 782/783/1776 780/781/1778 +f 927/929/1777 780/781/1778 928/930/1779 +f 928/930/1779 780/781/1778 778/779/1780 +f 928/930/1779 778/779/1780 929/931/1781 +f 929/931/1781 778/779/1780 776/777/1782 +f 929/931/1781 776/777/1782 930/932/1783 +f 930/932/1783 776/777/1782 774/775/1784 +f 930/932/1783 774/775/1784 931/933/1785 +f 931/933/1785 774/775/1784 772/773/1786 +f 931/933/1785 772/773/1786 904/906/1787 +f 931/933/1788 904/906/1789 908/910/1790 +f 931/933/1788 908/910/1790 902/904/1791 +f 902/904/1791 793/794/1792 931/933/1788 +f 931/933/1788 793/794/1792 795/796/1793 +f 764/765/1471 869/871/1754 840/842/1758 +f 764/765/1471 766/767/1473 869/871/1754 +f 926/928/1794 927/929/1794 928/930/1794 +f 928/930/1795 929/931/1795 930/932/1795 +f 881/883/1796 906/908/1797 932/934/1798 +f 881/883/1796 932/934/1798 880/882/1799 +f 933/935/1800 876/878/1801 932/934/1802 +f 932/934/1802 876/878/1801 880/882/1803 +f 933/935/1804 934/936/1805 876/878/1806 +f 934/936/1805 887/889/1807 876/878/1806 +f 887/889/1808 934/936/1809 935/937/1810 +f 887/889/1808 935/937/1810 885/887/1811 +f 909/911/1812 885/887/1813 935/937/1814 +f 909/911/1812 884/886/1815 885/887/1813 +f 906/908/1816 881/883/1817 909/911/1818 +f 909/911/1818 881/883/1817 884/886/1819 +f 932/934/1820 760/761/1821 933/935/1822 +f 932/934/1798 906/908/1797 760/761/1823 +f 935/937/1824 757/758/1824 909/911/1824 +f 933/935/1825 762/763/1826 934/936/1827 +f 934/936/1827 762/763/1826 758/759/1828 +f 934/936/1829 758/759/1830 935/937/1831 +f 935/937/1831 758/759/1830 757/758/1832 +f 933/935/1822 760/761/1821 762/763/1833 +f 936/938/1834 888/890/1834 937/939/1834 +f 936/938/1835 919/921/1836 888/890/1837 +f 938/940/1838 919/921/1836 936/938/1835 +f 939/941/1839 919/921/1840 938/940/1841 +f 939/941/1839 889/891/1842 919/921/1840 +f 883/885/1843 907/909/1844 940/942/1845 +f 883/885/1843 940/942/1845 886/888/1846 +f 937/939/1847 886/888/1847 940/942/1847 +f 888/890/1848 886/888/1848 937/939/1848 +f 939/941/1849 883/885/1631 889/891/1639 +f 907/909/1850 883/885/1631 939/941/1849 +f 940/942/1851 756/757/1852 937/939/1853 +f 939/941/1849 908/910/1854 907/909/1850 +f 940/942/1855 907/909/1855 756/757/1855 +f 938/940/1856 908/910/1857 939/941/1858 +f 902/904/1859 908/910/1857 938/940/1856 +f 937/939/1860 759/760/1860 936/938/1860 +f 936/938/1861 759/760/1861 902/904/1861 +f 936/938/1862 902/904/1859 938/940/1856 +f 937/939/1853 756/757/1852 759/760/1863 +f 882/884/1864 941/943/1865 942/944/1866 +f 882/884/1864 942/944/1866 890/892/1867 +f 943/945/1868 890/892/1869 942/944/1870 +f 943/945/1868 877/879/1871 890/892/1869 +f 943/945/1872 944/946/1873 877/879/1874 +f 944/946/1873 878/880/1875 877/879/1874 +f 878/880/1808 944/946/1809 945/947/1810 +f 878/880/1808 945/947/1810 879/881/1811 +f 905/907/1876 879/881/1877 945/947/1878 +f 905/907/1876 882/884/1879 879/881/1877 +f 882/884/1880 905/907/1881 941/943/1882 +f 942/944/1883 753/754/1884 943/945/1885 +f 941/943/1882 905/907/1881 753/754/1886 +f 941/943/1887 753/754/1887 942/944/1887 +f 945/947/1888 763/764/1888 905/907/1888 +f 943/945/1889 755/756/1890 761/762/1891 +f 943/945/1889 761/762/1891 944/946/1892 +f 944/946/1893 761/762/1894 945/947/1895 +f 945/947/1895 761/762/1894 763/764/1896 +f 943/945/1885 753/754/1884 755/756/1897 +f 739/740/1898 900/902/1899 946/948/1900 +f 739/740/1898 946/948/1900 743/744/1901 +f 946/948/1902 744/745/1903 743/744/1904 +f 946/948/1902 947/949/1905 744/745/1903 +f 948/950/1906 751/752/1907 947/949/1908 +f 947/949/1908 751/752/1907 744/745/1909 +f 751/752/1910 948/950/1910 748/749/1910 +f 896/898/1911 748/749/1912 948/950/1913 +f 896/898/1911 747/748/1914 748/749/1912 +f 747/748/1915 896/898/1658 900/902/1660 +f 900/902/1660 739/740/1916 747/748/1915 +f 946/948/1917 900/902/1917 731/732/1917 +f 948/950/1918 730/731/1918 896/898/1918 +f 946/948/1919 731/732/1920 728/729/1921 +f 946/948/1919 728/729/1921 947/949/1922 +f 947/949/1923 728/729/1924 948/950/1925 +f 948/950/1925 728/729/1924 730/731/1926 +f 741/742/1927 949/951/1928 913/915/1929 +f 949/951/1928 950/952/1930 913/915/1929 +f 950/952/1931 746/747/1932 913/915/1933 +f 951/953/1934 746/747/1932 950/952/1931 +f 951/953/1935 745/746/1935 746/747/1935 +f 745/746/1936 951/953/1937 952/954/1938 +f 745/746/1936 952/954/1938 742/743/1939 +f 898/900/1940 742/743/1941 952/954/1942 +f 898/900/1940 740/741/1943 742/743/1941 +f 740/741/1944 898/900/1945 949/951/1946 +f 949/951/1946 741/742/1947 740/741/1944 +f 949/951/1948 727/728/1948 950/952/1948 +f 949/951/1946 898/900/1945 727/728/1949 +f 952/954/1950 732/733/1950 898/900/1950 +f 950/952/1951 727/728/1951 726/727/1951 +f 950/952/1952 726/727/1952 951/953/1952 +f 951/953/1953 726/727/1953 724/725/1953 +f 951/953/1954 724/725/1955 952/954/1956 +f 952/954/1956 724/725/1955 732/733/1957 +f 737/738/1958 953/955/1959 954/956/1960 +f 737/738/1958 954/956/1960 749/750/1961 +f 954/956/1962 750/751/1962 749/750/1962 +f 955/957/1963 752/753/1964 954/956/1965 +f 954/956/1965 752/753/1964 750/751/1966 +f 955/957/1967 733/734/1968 752/753/1969 +f 733/734/1968 955/957/1967 956/958/1970 +f 901/903/1971 734/735/1972 956/958/1973 +f 956/958/1973 734/735/1972 733/734/1974 +f 734/735/1431 901/903/1975 953/955/1976 +f 953/955/1976 737/738/1434 734/735/1431 +f 954/956/1977 895/897/1977 729/730/1977 +f 953/955/1976 901/903/1975 895/897/1978 +f 953/955/1979 895/897/1979 954/956/1979 +f 956/958/1980 721/722/1980 901/903/1980 +f 954/956/1981 729/730/1982 722/723/1983 +f 954/956/1981 722/723/1983 955/957/1984 +f 955/957/1985 722/723/1986 956/958/1987 +f 956/958/1987 722/723/1986 721/722/1988 +f 845/847/1989 844/846/1990 867/869/1991 +f 868/870/1992 867/869/1991 844/846/1990 +f 764/765/1993 845/847/1993 765/766/1993 +f 867/869/1994 766/767/1995 765/766/1996 +f 765/766/1996 845/847/1997 867/869/1994 +f 347/347/1998 868/870/1999 844/846/2000 +f 868/870/1999 347/347/1998 349/349/2001 +f 957/959/2002 958/960/2002 959/961/2002 +f 957/959/2003 959/961/2003 960/962/2003 +f 960/962/2004 961/963/2004 957/959/2004 +f 961/963/2005 962/964/2005 957/959/2005 +f 957/959/2006 962/964/2006 958/960/2006 +f 958/960/2007 825/826/2007 959/961/2007 +f 959/961/2008 825/826/2008 824/825/2008 +f 959/961/2009 824/825/2009 960/962/2009 +f 960/962/2010 824/825/2011 823/824/2012 +f 960/962/2010 823/824/2012 961/963/2013 +f 961/963/2014 823/824/2014 962/964/2014 +f 962/964/2015 823/824/2016 825/826/2017 +f 962/964/2015 825/826/2017 958/960/2018 +f 963/965/2019 964/966/2019 965/967/2019 +f 965/967/2020 964/966/2020 966/968/2020 +f 965/967/2021 966/968/2021 967/969/2021 +f 967/969/2022 963/965/2022 965/967/2022 +f 967/969/2023 800/801/2023 718/719/2023 +f 967/969/2024 718/719/2024 963/965/2024 +f 963/965/2025 718/719/2026 717/718/2027 +f 963/965/2025 717/718/2027 964/966/2028 +f 964/966/2029 717/718/2030 807/808/2031 +f 964/966/2029 807/808/2031 966/968/2032 +f 966/968/2033 807/808/2034 800/801/2035 +f 966/968/2033 800/801/2035 967/969/2036 +f 968/970/2037 969/971/2037 970/972/2037 +f 969/971/2038 971/973/2038 970/972/2038 +f 971/973/2039 972/974/2039 970/972/2039 +f 970/972/2040 972/974/2040 968/970/2040 +f 968/970/2041 716/717/2042 817/818/2043 +f 968/970/2041 817/818/2043 969/971/2044 +f 969/971/2045 817/818/2046 815/816/2047 +f 969/971/2045 815/816/2047 971/973/2048 +f 971/973/2049 815/816/2050 816/817/2051 +f 971/973/2049 816/817/2051 972/974/2052 +f 972/974/2053 816/817/2054 716/717/2055 +f 972/974/2053 716/717/2055 968/970/2056 +f 973/975/2057 974/976/2057 975/977/2057 +f 975/977/2058 974/976/2058 976/978/2058 +f 975/977/2059 976/978/2059 977/979/2059 +f 977/979/2060 973/975/2060 975/977/2060 +f 977/979/2061 805/806/2062 802/803/2063 +f 977/979/2061 802/803/2063 973/975/2064 +f 973/975/2065 802/803/2065 801/802/2065 +f 973/975/2066 801/802/2067 974/976/2068 +f 974/976/2068 801/802/2067 804/805/2069 +f 974/976/2070 804/805/2071 976/978/2072 +f 976/978/2072 804/805/2071 803/804/2073 +f 976/978/2074 803/804/2075 977/979/2076 +f 977/979/2076 803/804/2075 805/806/2077 +f 978/980/2078 979/981/2078 980/982/2078 +f 979/981/2079 981/983/2079 980/982/2079 +f 980/982/2080 981/983/2080 982/984/2080 +f 982/984/2081 978/980/2081 980/982/2081 +f 982/984/2082 811/812/2083 978/980/2084 +f 978/980/2084 811/812/2083 806/807/2085 +f 978/980/2086 806/807/2087 808/809/2088 +f 978/980/2086 808/809/2088 979/981/2089 +f 979/981/2090 808/809/2090 809/810/2090 +f 979/981/2091 809/810/2091 981/983/2091 +f 981/983/2092 809/810/2092 810/811/2092 +f 981/983/2093 810/811/2094 982/984/2095 +f 982/984/2095 810/811/2094 811/812/2096 +f 983/985/2097 984/986/2097 985/987/2097 +f 984/986/2098 986/988/2098 985/987/2098 +f 986/988/2099 987/989/2099 985/987/2099 +f 987/989/2100 983/985/2100 985/987/2100 +f 983/985/2101 797/798/2101 984/986/2101 +f 984/986/2102 797/798/2102 796/797/2102 +f 984/986/2103 796/797/2103 986/988/2103 +f 986/988/2104 796/797/2104 794/795/2104 +f 986/988/2105 794/795/2106 798/799/2107 +f 986/988/2105 798/799/2107 987/989/2108 +f 987/989/2109 798/799/2110 983/985/2111 +f 983/985/2111 798/799/2110 797/798/2112 +f 988/990/2113 989/991/2113 990/992/2113 +f 989/991/2114 991/993/2114 990/992/2114 +f 991/993/2115 992/994/2115 990/992/2115 +f 992/994/2116 988/990/2116 990/992/2116 +f 988/990/2117 791/792/2117 989/991/2117 +f 989/991/2118 791/792/2118 789/790/2118 +f 989/991/2119 789/790/2120 991/993/2121 +f 991/993/2121 789/790/2120 787/788/2122 +f 991/993/2123 787/788/2124 992/994/2125 +f 992/994/2125 787/788/2124 792/793/2126 +f 992/994/2127 792/793/2128 988/990/2129 +f 988/990/2129 792/793/2128 791/792/2130 +f 993/995/2131 994/996/2131 995/997/2131 +f 995/997/2132 996/998/2132 993/995/2132 +f 996/998/2133 997/999/2133 993/995/2133 +f 997/999/2134 998/1000/2134 993/995/2134 +f 993/995/2135 998/1000/2135 994/996/2135 +f 994/996/2136 819/820/2136 818/819/2136 +f 994/996/2137 818/819/2137 995/997/2137 +f 995/997/2138 818/819/2139 821/822/2140 +f 995/997/2138 821/822/2140 996/998/2141 +f 996/998/2142 821/822/2143 820/821/2144 +f 996/998/2142 820/821/2144 997/999/2145 +f 997/999/2146 820/821/2147 998/1000/2148 +f 998/1000/2148 820/821/2147 819/820/2149 +f 998/1000/2150 819/820/2150 994/996/2150 +f 999/1001/2151 1000/1002/2151 1001/1003/2151 +f 1001/1003/2152 1000/1002/2152 1002/1004/2152 +f 1002/1004/2153 1003/1005/2153 1001/1003/2153 +f 1003/1005/2154 1004/1006/2154 1001/1003/2154 +f 1004/1006/2155 999/1001/2155 1001/1003/2155 +f 999/1001/2156 812/813/2156 1000/1002/2156 +f 1000/1002/2157 812/813/2158 1002/1004/2159 +f 1002/1004/2159 812/813/2158 790/791/2160 +f 1002/1004/2161 790/791/2162 1003/1005/2163 +f 1003/1005/2163 790/791/2162 814/815/2164 +f 1003/1005/2165 814/815/2166 1004/1006/2167 +f 1004/1006/2167 814/815/2166 813/814/2168 +f 1004/1006/2169 813/814/2169 999/1001/2169 +f 999/1001/2170 813/814/2170 812/813/2170 +f 1005/1007/2171 1006/1008/2172 1007/1009/2172 +f 1007/1009/2172 1008/1010/2172 1009/1011/2171 +f 1005/1007/2171 1007/1009/2172 1009/1011/2171 +f 657/658/2173 656/657/2173 655/656/2173 +f 656/657/2173 657/658/2173 658/659/2174 +f 656/657/2173 654/655/2173 655/656/2173 +f 437/437/603 452/452/609 429/429/609 +f 452/452/609 437/437/603 450/450/626 +f 1010/1012/2175 703/704/1394 649/650/1393 +f 646/647/1396 1011/1013/2176 1010/1012/2175 +f 646/647/1396 1010/1012/2175 647/648/2177 +f 1010/1012/2175 1011/1013/2176 1012/1014/2178 +f 1010/1012/2175 1012/1014/2178 1013/1015/2179 +f 1012/1014/2178 703/704/1394 1013/1015/2179 +f 703/704/1394 1012/1014/2178 1014/1016/2180 +f 703/704/1394 1014/1016/2180 646/647/1396 +f 646/647/1396 1014/1016/2180 1011/1013/2176 +f 647/648/2177 1010/1012/2175 649/650/1393 +f 647/648/2177 649/650/1393 648/649/2181 +f 708/709/2182 710/711/2183 1015/1017/2184 +f 830/831/2185 1015/1017/2186 1016/1018/2187 +f 826/827/2188 1015/1017/2186 830/831/2185 +f 707/708/528 830/831/528 709/710/528 +f 709/710/528 830/831/528 1016/1018/528 +f 705/706/528 707/708/528 1017/1019/528 +f 705/706/528 1017/1019/528 1018/1020/528 +f 705/706/528 1018/1020/528 1019/1021/528 +f 710/711/2189 709/710/2190 1015/1017/2191 +f 1015/1017/2191 709/710/2190 1016/1018/2192 +f 706/707/2193 708/709/2193 828/829/2193 +f 1015/1017/2184 826/827/2194 708/709/2182 +f 708/709/2195 826/827/1526 828/829/1528 +f 1006/1008/2196 320/320/2197 1007/1009/2198 +f 1007/1009/2198 320/320/2197 315/315/2199 +f 1007/1009/2200 314/314/2201 1008/1010/2202 +f 1008/1010/2202 314/314/2201 712/713/2203 +f 320/320/2204 1006/1008/2205 322/322/2206 +f 322/322/2206 1006/1008/2205 1005/1007/2207 +f 1005/1007/2207 719/720/2208 322/322/2206 +f 1008/1010/2209 714/715/2210 1009/1011/2211 +f 1009/1011/2211 714/715/2210 715/716/2212 +f 314/314/2213 1007/1009/2213 315/315/2213 +f 719/720/2214 1005/1007/2215 715/716/2216 +f 715/716/2216 1005/1007/2215 1009/1011/2217 +f 714/715/2218 1008/1010/2218 712/713/2218 +f 1020/1022/2219 1021/1023/2220 831/832/1531 +f 1021/1023/2220 832/833/1532 831/832/1531 +f 1022/1024/2221 1023/1025/2222 1020/1022/2219 +f 1020/1022/2219 1023/1025/2222 1021/1023/2220 +f 833/834/1533 1024/1026/2223 834/836/1535 +f 834/836/1535 1024/1026/2223 1025/1027/2224 +f 1026/1028/2225 1027/1029/2225 1025/1027/2225 +f 1024/1026/2226 1028/1030/2226 1029/1031/2226 +f 1024/1026/2223 1023/1025/2227 1025/1027/2224 +f 1025/1027/2224 1023/1025/2227 1022/1024/2228 +f 834/836/2229 1025/1027/2230 831/832/1531 +f 831/832/1531 1025/1027/2230 1027/1029/2231 +f 1028/1030/2232 1024/1026/2233 833/834/2234 +f 1028/1030/2232 833/834/2234 832/833/2235 +f 1022/1024/2236 1026/1028/2236 1025/1027/2236 +f 1020/1022/2237 1027/1029/2238 1022/1024/2239 +f 1022/1024/2239 1027/1029/2238 1026/1028/2240 +f 1020/1022/2219 831/832/1531 1027/1029/2231 +f 1029/1031/2241 1023/1025/2241 1024/1026/2241 +f 1028/1030/2242 1021/1023/2243 1029/1031/2244 +f 1029/1031/2244 1021/1023/2243 1023/1025/2245 +f 1021/1023/2246 1028/1030/2232 832/833/2235 +f 1030/1032/2247 1013/1015/2248 1031/1033/2249 +f 1031/1033/2249 1013/1015/2248 703/704/2250 +f 1013/1015/2251 1030/1032/2252 1010/1012/2253 +f 1010/1012/2253 1030/1032/2252 1032/1034/2254 +f 1010/1012/2255 1032/1034/2255 1033/1035/2255 +f 1033/1035/2256 703/704/2256 1010/1012/2256 +f 1033/1035/2257 1031/1033/2257 703/704/2257 +f 1012/1014/2258 1034/1036/2259 1035/1037/2260 +f 1035/1037/2260 1014/1016/2261 1012/1014/2258 +f 1035/1037/2262 1011/1013/2263 1014/1016/2264 +f 1036/1038/2265 1011/1013/2263 1035/1037/2262 +f 1034/1036/2266 1012/1014/2267 1011/1013/2268 +f 1019/1021/2269 1037/1039/2270 705/706/2271 +f 705/706/2271 1037/1039/2270 704/705/2272 +f 1038/1040/2273 1039/1041/2274 1040/1042/2275 +f 1041/1043/2276 1042/1044/2277 1018/1020/2278 +f 1018/1020/2278 1042/1044/2277 1043/1045/2279 +f 1040/1042/2275 1044/1046/2280 1038/1040/2273 +f 1045/1047/2281 1019/1021/2282 1044/1046/2280 +f 1044/1046/2280 1019/1021/2282 1038/1040/2273 +f 1019/1021/2282 1045/1047/2281 1037/1039/2283 +f 1045/1047/2281 1046/1048/2284 1037/1039/2283 +f 1043/1045/2279 1047/1049/2285 1018/1020/2278 +f 1019/1021/2282 1048/1050/2286 1049/1051/2287 +f 1038/1040/2273 1050/1052/2288 1043/1045/2279 +f 1018/1020/2278 1047/1049/2285 1048/1050/2286 +f 1018/1020/2278 1048/1050/2286 1019/1021/2282 +f 1038/1040/2273 1019/1021/2282 1049/1051/2287 +f 1038/1040/2273 1049/1051/2287 1050/1052/2288 +f 1037/1039/2283 1046/1048/2284 1041/1043/2276 +f 1041/1043/2276 1046/1048/2284 1040/1042/2275 +f 1043/1045/2279 1050/1052/2288 1047/1049/2285 +f 1039/1041/2274 1042/1044/2277 1040/1042/2275 +f 1040/1042/2275 1042/1044/2277 1041/1043/2276 +f 707/708/1399 706/707/1398 829/830/1529 +f 707/708/1399 829/830/1529 1017/1019/2289 +f 1017/1019/2290 829/830/2291 1018/1020/2292 +f 1018/1020/2292 829/830/2291 1041/1043/2293 +f 829/830/2294 704/705/2295 1037/1039/98 +f 829/830/2294 1037/1039/98 1041/1043/98 +f 1051/1053/2296 1052/1054/2296 1053/1055/2296 +f 1053/1055/2297 1054/1056/2297 1051/1053/2297 +f 1054/1056/2298 1055/1057/2298 1051/1053/2298 +f 1055/1057/2299 1056/1058/2299 1051/1053/2299 +f 1051/1053/2300 1056/1058/2300 1052/1054/2300 +f 1052/1054/2301 1047/1049/2302 1053/1055/2303 +f 1053/1055/2303 1047/1049/2302 1050/1052/2304 +f 1053/1055/2305 1050/1052/2305 1054/1056/2305 +f 1054/1056/2306 1050/1052/2307 1049/1051/2308 +f 1054/1056/2306 1049/1051/2308 1055/1057/2309 +f 1055/1057/2310 1049/1051/2311 1048/1050/2312 +f 1055/1057/2310 1048/1050/2312 1056/1058/2313 +f 1056/1058/2314 1048/1050/2315 1052/1054/2316 +f 1052/1054/2316 1048/1050/2315 1047/1049/2317 +f 1057/1059/2318 1058/1060/2318 1059/1061/2318 +f 1058/1060/2319 1060/1062/2319 1059/1061/2319 +f 1060/1062/2320 1061/1063/2320 1059/1061/2320 +f 1061/1063/2321 1057/1059/2321 1059/1061/2321 +f 1057/1059/2322 1040/1042/2322 1058/1060/2322 +f 1058/1060/2323 1040/1042/2323 1046/1048/2323 +f 1058/1060/2324 1046/1048/2325 1060/1062/2326 +f 1060/1062/2326 1046/1048/2325 1045/1047/2327 +f 1060/1062/2328 1045/1047/2329 1061/1063/2330 +f 1061/1063/2330 1045/1047/2329 1044/1046/2331 +f 1061/1063/2332 1044/1046/2332 1057/1059/2332 +f 1057/1059/2333 1044/1046/2333 1040/1042/2333 +f 1062/1064/2334 1063/1065/2334 1064/1066/2334 +f 1063/1065/2335 1065/1067/2335 1064/1066/2335 +f 1065/1067/2336 1066/1068/2336 1064/1066/2336 +f 1066/1068/2337 1062/1064/2337 1064/1066/2337 +f 1062/1064/2338 1042/1044/2338 1063/1065/2338 +f 1063/1065/2339 1042/1044/2339 1039/1041/2339 +f 1063/1065/2340 1039/1041/2340 1065/1067/2340 +f 1065/1067/2341 1039/1041/2341 1038/1040/2341 +f 1065/1067/2342 1038/1040/2343 1066/1068/2344 +f 1066/1068/2344 1038/1040/2343 1043/1045/2345 +f 1066/1068/2346 1043/1045/2346 1062/1064/2346 +f 1062/1064/2347 1043/1045/2347 1042/1044/2347 +f 1034/1036/2266 1011/1013/2268 1036/1038/2348 +f 647/648/2349 645/646/2350 644/645/2351 +f 1030/1032/2352 1031/1033/2352 1032/1034/2352 +f 647/648/2349 648/649/2353 645/646/2350 +f 1032/1034/2352 1031/1033/2352 1033/1035/2352 +f 1035/1037/2352 1034/1036/2352 1036/1038/2352 +f 673/674/2354 641/642/2354 672/673/2354 +f 672/673/2355 639/640/2355 674/675/2355 +f 673/674/2352 672/673/2352 674/675/2352 +f 671/672/2352 669/670/2352 670/671/2352 +f 1067/1069/2356 1068/1070/2357 1069/1071/2358 +f 1069/1071/2358 1068/1070/2357 1070/1072/2359 +f 1068/1070/2357 1067/1069/2356 1071/1073/2360 +f 1072/1074/2361 1069/1071/2358 1070/1072/2359 +f 1073/1075/2362 1072/1074/2361 1070/1072/2359 +f 1073/1075/2362 1070/1072/2359 1074/1076/2363 +f 1075/1077/2364 1073/1075/2362 1074/1076/2363 +f 1076/1078/2365 1077/1079/2366 1074/1076/2363 +f 1077/1079/2366 1075/1077/2364 1074/1076/2363 +f 1078/1080/2367 1079/1081/2368 1076/1078/2365 +f 1079/1081/2368 1077/1079/2366 1076/1078/2365 +f 1068/1070/2357 1071/1073/2360 1080/1082/2369 +f 1081/1083/2370 1082/1084/2371 1068/1070/2357 +f 1068/1070/2357 1082/1084/2371 1083/1085/2372 +f 1080/1082/2369 1084/1086/2373 1068/1070/2357 +f 1084/1086/2373 1081/1083/2370 1068/1070/2357 +f 1085/1087/2374 1086/1088/2375 1087/1089/2376 +f 1088/1090/2377 1089/1091/2378 1090/1092/2379 +f 1090/1092/2379 1091/1093/2380 1092/1094/2381 +f 1092/1094/2381 1091/1093/2380 1093/1095/2382 +f 1092/1094/2381 1093/1095/2382 1094/1096/2383 +f 1086/1088/2375 1095/1097/2384 1087/1089/2376 +f 1095/1097/2384 1096/1098/2385 1087/1089/2376 +f 1087/1089/2376 1096/1098/2385 1097/1099/2386 +f 1097/1099/2386 1096/1098/2385 1098/1100/2387 +f 1097/1099/2386 1098/1100/2387 1099/1101/2388 +f 1097/1099/2386 1099/1101/2388 1100/1102/2389 +f 1100/1102/2389 1099/1101/2388 1101/1103/2390 +f 1102/1104/2391 1097/1099/2386 1100/1102/2389 +f 1102/1104/2391 1100/1102/2389 1088/1090/2377 +f 1094/1096/2383 1103/1105/2392 1085/1087/2374 +f 1094/1096/2383 1085/1087/2374 1087/1089/2376 +f 1094/1096/2383 1087/1089/2376 1092/1094/2381 +f 1092/1094/2381 1102/1104/2391 1090/1092/2379 +f 1090/1092/2379 1102/1104/2391 1088/1090/2377 +f 1092/1094/2381 1087/1089/2376 1097/1099/2386 +f 1092/1094/2381 1097/1099/2386 1102/1104/2391 +f 1104/1106/2393 1105/1107/2394 1106/1108/2395 +f 1107/1109/2396 1106/1108/2395 1108/1110/2397 +f 1107/1109/2396 1109/1111/2398 1110/1112/2399 +f 1110/1112/2399 1109/1111/2398 1111/1113/2400 +f 1112/1114/2401 1113/1115/2402 1111/1113/2400 +f 1111/1113/2400 1113/1115/2402 1110/1112/2399 +f 1108/1110/2397 1093/1095/2382 1109/1111/2398 +f 1109/1111/2398 1093/1095/2382 1091/1093/2380 +f 1091/1093/2380 1089/1091/2378 1111/1113/2400 +f 1111/1113/2400 1089/1091/2378 1112/1114/2401 +f 1103/1105/2392 1094/1096/2383 1108/1110/2397 +f 1108/1110/2397 1094/1096/2383 1093/1095/2382 +f 1091/1093/2380 1090/1092/2379 1089/1091/2378 +f 1105/1107/2394 1108/1110/2397 1106/1108/2395 +f 1107/1109/2396 1108/1110/2397 1109/1111/2398 +f 1105/1107/2394 1103/1105/2392 1108/1110/2397 +f 1109/1111/2398 1091/1093/2380 1111/1113/2400 +f 1114/1116/2403 1115/1117/2404 1116/1118/2405 +f 1117/1119/2406 1118/1120/2407 1079/1081/2368 +f 1118/1120/2407 1117/1119/2406 1119/1121/2408 +f 1120/1122/2409 1121/1123/2410 1122/1124/2411 +f 1122/1124/2411 1121/1123/2410 1123/1125/2412 +f 1124/1126/2413 1123/1125/2412 1125/1127/2414 +f 1126/1128/2415 1127/1129/2416 1128/1130/2417 +f 1126/1128/2415 1128/1130/2417 1129/1131/2418 +f 1079/1081/2368 1130/1132/2419 1117/1119/2406 +f 1117/1119/2406 1131/1133/2420 1119/1121/2408 +f 1125/1127/2414 1123/1125/2412 1121/1123/2410 +f 1121/1123/2410 1120/1122/2409 1132/1134/2421 +f 1114/1116/2403 1116/1118/2405 1130/1132/2419 +f 1130/1132/2419 1116/1118/2405 1133/1135/2422 +f 1130/1132/2419 1133/1135/2422 1117/1119/2406 +f 1134/1136/2423 1124/1126/2413 1135/1137/2424 +f 1135/1137/2424 1124/1126/2413 1125/1127/2414 +f 1125/1127/2414 1121/1123/2410 1136/1138/2425 +f 1136/1138/2425 1121/1123/2410 1132/1134/2421 +f 1115/1117/2404 1128/1130/2417 1116/1118/2405 +f 1133/1135/2422 1137/1139/2426 1117/1119/2406 +f 1117/1119/2406 1137/1139/2426 1131/1133/2420 +f 1128/1130/2417 1127/1129/2416 1134/1136/2423 +f 1128/1130/2417 1134/1136/2423 1138/1140/2427 +f 1138/1140/2427 1134/1136/2423 1135/1137/2424 +f 1135/1137/2424 1125/1127/2414 1136/1138/2425 +f 1139/1141/2428 1136/1138/2425 1132/1134/2421 +f 1129/1131/2418 1128/1130/2417 1115/1117/2404 +f 1116/1118/2405 1128/1130/2417 1138/1140/2427 +f 1116/1118/2405 1138/1140/2427 1135/1137/2424 +f 1116/1118/2405 1135/1137/2424 1133/1135/2422 +f 1133/1135/2422 1135/1137/2424 1137/1139/2426 +f 1137/1139/2426 1139/1141/2428 1131/1133/2420 +f 1135/1137/2424 1136/1138/2425 1137/1139/2426 +f 1137/1139/2426 1136/1138/2425 1139/1141/2428 +f 1140/1142/2429 1141/1143/2430 1142/1144/2431 +f 1142/1144/2431 1141/1143/2430 1143/1145/2432 +f 1143/1145/2432 1144/1146/2433 1142/1144/2431 +f 1124/1126/2413 1145/1147/2434 1146/1148/2435 +f 1146/1148/2435 1145/1147/2434 1147/1149/2436 +f 1146/1148/2435 1147/1149/2436 1148/1150/2437 +f 1149/1151/2438 1147/1149/2436 1141/1143/2430 +f 1149/1151/2438 1141/1143/2430 1150/1152/2439 +f 1147/1149/2436 1149/1151/2438 1148/1150/2437 +f 1141/1143/2430 1140/1142/2429 1150/1152/2439 +f 1143/1145/2432 1151/1153/2440 1144/1146/2433 +f 1143/1145/2432 1152/1154/2441 1151/1153/2440 +f 1153/1155/2442 1154/1156/2443 1143/1145/2432 +f 1143/1145/2432 1154/1156/2443 1155/1157/2444 +f 1143/1145/2432 1155/1157/2444 1152/1154/2441 +f 1156/1158/2445 1157/1159/2446 1158/1160/2447 +f 1159/1161/2448 1160/1162/2449 1161/1163/2450 +f 1160/1162/2449 1162/1164/2451 1161/1163/2450 +f 1162/1164/2451 1160/1162/2449 1163/1165/2452 +f 1160/1162/2449 1159/1161/2448 1164/1166/2453 +f 1160/1162/2449 1164/1166/2453 1157/1159/2446 +f 1157/1159/2446 1164/1166/2453 1158/1160/2447 +f 1083/1085/2372 1082/1084/2371 1156/1158/2445 +f 1165/1167/2454 1166/1168/2455 1167/1169/2456 +f 1165/1167/2454 1167/1169/2456 1168/1170/2457 +f 1167/1169/2456 1169/1171/2458 1168/1170/2457 +f 1170/1172/2459 1169/1171/2458 1167/1169/2456 +f 1171/1173/2460 1170/1172/2459 1167/1169/2456 +f 1172/1174/2461 1170/1172/2459 1171/1173/2460 +f 1173/1175/2462 1164/1166/2453 1172/1174/2461 +f 1173/1175/2462 1172/1174/2461 1171/1173/2460 +f 1173/1175/2462 1158/1160/2447 1164/1166/2453 +f 1156/1158/2445 1158/1160/2447 1173/1175/2462 +f 1083/1085/2372 1156/1158/2445 1173/1175/2462 +f 1165/1167/2454 1154/1156/2443 1153/1155/2442 +f 1166/1168/2455 1165/1167/2454 1153/1155/2442 +f 1130/1132/2419 1079/1081/2368 1078/1080/2367 +f 1114/1116/2403 1078/1080/2367 1174/1176/2463 +f 1078/1080/2367 1114/1116/2403 1130/1132/2419 +f 1115/1117/2404 1174/1176/2463 1175/1177/2464 +f 1115/1117/2404 1175/1177/2464 1129/1131/2418 +f 1174/1176/2463 1115/1117/2404 1114/1116/2403 +f 1175/1177/2464 1126/1128/2415 1129/1131/2418 +f 1126/1128/2415 1175/1177/2464 1176/1178/2465 +f 1126/1128/2415 1176/1178/2465 1127/1129/2416 +f 1176/1178/2465 1134/1136/2423 1127/1129/2416 +f 1134/1136/2423 1176/1178/2465 1145/1147/2434 +f 1145/1147/2434 1124/1126/2413 1134/1136/2423 +f 1177/1179/2466 1178/1180/2467 1179/1181/2468 +f 1168/1170/2457 1180/1182/2469 1181/1183/2470 +f 1165/1167/2454 1168/1170/2457 1182/1184/2471 +f 1177/1179/2466 1179/1181/2468 1183/1185/2472 +f 1177/1179/2466 1183/1185/2472 1181/1183/2470 +f 1182/1184/2471 1168/1170/2457 1183/1185/2472 +f 1183/1185/2472 1168/1170/2457 1181/1183/2470 +f 1184/1186/2473 1185/1187/2474 1186/1188/2475 +f 1186/1188/2475 1187/1189/2476 1188/1190/2477 +f 1185/1187/2474 1169/1171/2458 1170/1172/2459 +f 1170/1172/2459 1172/1174/2461 1164/1166/2453 +f 1170/1172/2459 1164/1166/2453 1185/1187/2474 +f 1185/1187/2474 1164/1166/2453 1187/1189/2476 +f 1185/1187/2474 1187/1189/2476 1186/1188/2475 +f 1189/1191/2478 1190/1192/2479 1191/1193/2480 +f 1191/1193/2480 1192/1194/2481 1189/1191/2478 +f 1189/1191/2478 1192/1194/2481 1193/1195/2482 +f 1192/1194/2481 1194/1196/2483 1193/1195/2482 +f 1071/1073/2360 1194/1196/2483 1192/1194/2481 +f 1071/1073/2360 1069/1071/2358 1194/1196/2483 +f 1195/1197/2484 1196/1198/2485 1197/1199/2486 +f 1195/1197/2484 1197/1199/2486 1198/1200/2487 +f 1198/1200/2487 1199/1201/2488 1195/1197/2484 +f 1198/1200/2487 1200/1202/2489 1199/1201/2488 +f 1196/1198/2485 1150/1152/2439 1197/1199/2486 +f 1197/1199/2486 1150/1152/2439 1201/1203/2490 +f 1201/1203/2490 1150/1152/2439 1140/1142/2429 +f 1201/1203/2490 1140/1142/2429 1142/1144/2431 +f 1148/1150/2437 1202/1204/2491 1146/1148/2435 +f 1122/1124/2411 1123/1125/2412 1202/1204/2491 +f 1202/1204/2491 1123/1125/2412 1146/1148/2435 +f 1146/1148/2435 1123/1125/2412 1124/1126/2413 +f 1203/1205/2492 1148/1150/2437 1149/1151/2438 +f 1196/1198/2485 1203/1205/2492 1149/1151/2438 +f 1196/1198/2485 1149/1151/2438 1150/1152/2439 +f 1148/1150/2437 1203/1205/2492 1202/1204/2491 +f 1120/1122/2409 1122/1124/2411 1202/1204/2491 +f 1120/1122/2409 1202/1204/2491 1204/1206/2493 +f 1203/1205/2492 1196/1198/2485 1195/1197/2484 +f 1203/1205/2492 1204/1206/2493 1202/1204/2491 +f 1204/1206/2493 1203/1205/2492 1195/1197/2484 +f 1077/1079/2366 1205/1207/2494 1075/1077/2364 +f 1118/1120/2407 1205/1207/2494 1077/1079/2366 +f 1118/1120/2407 1077/1079/2366 1079/1081/2368 +f 1142/1144/2431 1144/1146/2433 1201/1203/2490 +f 1104/1106/2393 1195/1197/2484 1199/1201/2488 +f 1104/1106/2393 1199/1201/2488 1105/1107/2394 +f 1105/1107/2394 1199/1201/2488 1103/1105/2392 +f 1103/1105/2392 1199/1201/2488 1200/1202/2489 +f 1120/1122/2409 1204/1206/2493 1104/1106/2393 +f 1104/1106/2393 1204/1206/2493 1195/1197/2484 +f 1205/1207/2494 1206/1208/2495 1075/1077/2364 +f 1201/1203/2490 1144/1146/2433 1197/1199/2486 +f 1151/1153/2440 1197/1199/2486 1144/1146/2433 +f 1197/1199/2486 1151/1153/2440 1198/1200/2487 +f 1198/1200/2487 1207/1209/2496 1200/1202/2489 +f 1085/1087/2374 1103/1105/2392 1200/1202/2489 +f 1085/1087/2374 1200/1202/2489 1207/1209/2496 +f 1131/1133/2420 1139/1141/2428 1208/1210/2497 +f 1139/1141/2428 1132/1134/2421 1208/1210/2497 +f 1209/1211/2498 1119/1121/2408 1110/1112/2399 +f 1110/1112/2399 1119/1121/2408 1210/1212/2499 +f 1210/1212/2499 1208/1210/2497 1107/1109/2396 +f 1119/1121/2408 1131/1133/2420 1210/1212/2499 +f 1210/1212/2499 1131/1133/2420 1208/1210/2497 +f 1208/1210/2497 1132/1134/2421 1106/1108/2395 +f 1106/1108/2395 1132/1134/2421 1120/1122/2409 +f 1106/1108/2395 1120/1122/2409 1104/1106/2393 +f 1208/1210/2497 1106/1108/2395 1107/1109/2396 +f 1210/1212/2499 1107/1109/2396 1110/1112/2399 +f 1110/1112/2399 1113/1115/2402 1209/1211/2498 +f 1193/1195/2482 1206/1208/2495 1189/1191/2478 +f 1205/1207/2494 1118/1120/2407 1209/1211/2498 +f 1209/1211/2498 1189/1191/2478 1206/1208/2495 +f 1209/1211/2498 1206/1208/2495 1205/1207/2494 +f 1119/1121/2408 1209/1211/2498 1118/1120/2407 +f 1075/1077/2364 1206/1208/2495 1073/1075/2362 +f 1073/1075/2362 1206/1208/2495 1193/1195/2482 +f 1193/1195/2482 1194/1196/2483 1073/1075/2362 +f 1073/1075/2362 1194/1196/2483 1072/1074/2361 +f 1072/1074/2361 1194/1196/2483 1069/1071/2358 +f 1182/1184/2471 1154/1156/2443 1165/1167/2454 +f 1113/1115/2402 1189/1191/2478 1209/1211/2498 +f 1069/1071/2358 1071/1073/2360 1067/1069/2356 +f 1168/1170/2457 1169/1171/2458 1180/1182/2469 +f 1179/1181/2468 1178/1180/2467 1152/1154/2441 +f 1152/1154/2441 1155/1157/2444 1179/1181/2468 +f 1179/1181/2468 1155/1157/2444 1183/1185/2472 +f 1182/1184/2471 1183/1185/2472 1155/1157/2444 +f 1154/1156/2443 1182/1184/2471 1155/1157/2444 +f 1085/1087/2374 1207/1209/2496 1086/1088/2375 +f 1151/1153/2440 1152/1154/2441 1178/1180/2467 +f 1198/1200/2487 1211/1213/2500 1207/1209/2496 +f 1207/1209/2496 1211/1213/2500 1086/1088/2375 +f 1178/1180/2467 1211/1213/2500 1198/1200/2487 +f 1178/1180/2467 1198/1200/2487 1151/1153/2440 +f 1211/1213/2500 1178/1180/2467 1212/1214/2501 +f 1211/1213/2500 1212/1214/2501 1213/1215/2502 +f 1211/1213/2500 1213/1215/2502 1086/1088/2375 +f 1086/1088/2375 1213/1215/2502 1095/1097/2384 +f 1089/1091/2378 1214/1216/2503 1190/1192/2479 +f 1089/1091/2378 1190/1192/2479 1112/1114/2401 +f 1112/1114/2401 1190/1192/2479 1113/1115/2402 +f 1189/1191/2478 1113/1115/2402 1190/1192/2479 +f 1214/1216/2503 1088/1090/2377 1215/1217/2504 +f 1214/1216/2503 1215/1217/2504 1191/1193/2480 +f 1191/1193/2480 1190/1192/2479 1214/1216/2503 +f 1088/1090/2377 1214/1216/2503 1089/1091/2378 +f 1192/1194/2481 1080/1082/2369 1071/1073/2360 +f 1191/1193/2480 1080/1082/2369 1192/1194/2481 +f 1180/1182/2469 1169/1171/2458 1181/1183/2470 +f 1169/1171/2458 1185/1187/2474 1181/1183/2470 +f 1185/1187/2474 1184/1186/2473 1181/1183/2470 +f 1181/1183/2470 1184/1186/2473 1177/1179/2466 +f 1177/1179/2466 1212/1214/2501 1178/1180/2467 +f 1213/1215/2502 1216/1218/2505 1217/1219/2506 +f 1177/1179/2466 1184/1186/2473 1216/1218/2505 +f 1177/1179/2466 1216/1218/2505 1213/1215/2502 +f 1177/1179/2466 1213/1215/2502 1212/1214/2501 +f 1217/1219/2506 1095/1097/2384 1213/1215/2502 +f 1096/1098/2385 1095/1097/2384 1217/1219/2506 +f 1088/1090/2377 1100/1102/2389 1215/1217/2504 +f 1191/1193/2480 1215/1217/2504 1218/1220/2507 +f 1218/1220/2507 1215/1217/2504 1100/1102/2389 +f 1100/1102/2389 1101/1103/2390 1219/1221/2508 +f 1100/1102/2389 1219/1221/2508 1218/1220/2507 +f 1219/1221/2508 1163/1165/2452 1218/1220/2507 +f 1163/1165/2452 1084/1086/2373 1218/1220/2507 +f 1218/1220/2507 1084/1086/2373 1080/1082/2369 +f 1218/1220/2507 1080/1082/2369 1191/1193/2480 +f 1084/1086/2373 1163/1165/2452 1160/1162/2449 +f 1084/1086/2373 1160/1162/2449 1081/1083/2370 +f 1081/1083/2370 1160/1162/2449 1157/1159/2446 +f 1082/1084/2371 1157/1159/2446 1156/1158/2445 +f 1081/1083/2370 1157/1159/2446 1082/1084/2371 +f 1164/1166/2453 1159/1161/2448 1187/1189/2476 +f 1159/1161/2448 1161/1163/2450 1188/1190/2477 +f 1187/1189/2476 1159/1161/2448 1188/1190/2477 +f 1220/1222/2509 1099/1101/2388 1098/1100/2387 +f 1220/1222/2509 1098/1100/2387 1217/1219/2506 +f 1188/1190/2477 1220/1222/2509 1186/1188/2475 +f 1186/1188/2475 1220/1222/2509 1216/1218/2505 +f 1098/1100/2387 1096/1098/2385 1217/1219/2506 +f 1220/1222/2509 1217/1219/2506 1216/1218/2505 +f 1220/1222/2509 1188/1190/2477 1099/1101/2388 +f 1216/1218/2505 1184/1186/2473 1186/1188/2475 +f 1101/1103/2390 1162/1164/2451 1163/1165/2452 +f 1101/1103/2390 1163/1165/2452 1219/1221/2508 +f 1101/1103/2390 1099/1101/2388 1188/1190/2477 +f 1101/1103/2390 1188/1190/2477 1162/1164/2451 +f 1188/1190/2477 1161/1163/2450 1162/1164/2451 +f 1174/1176/2510 1068/1070/98 1175/1177/98 +f 1176/1178/1246 1175/1177/98 1143/1145/98 +f 1174/1176/2510 1070/1072/98 1068/1070/98 +f 1074/1076/2511 1070/1072/98 1076/1078/2512 +f 1176/1178/1246 1141/1143/98 1145/1147/98 +f 1070/1072/98 1078/1080/2510 1076/1078/2512 +f 1141/1143/98 1147/1149/2513 1145/1147/98 +f 1070/1072/98 1174/1176/2510 1078/1080/2510 +f 1141/1143/98 1176/1178/1246 1143/1145/98 +f 1175/1177/98 1068/1070/98 1143/1145/98 +f 1143/1145/98 1068/1070/98 1083/1085/2514 +f 1143/1145/98 1083/1085/2514 1153/1155/2294 +f 1173/1175/2515 1171/1173/2514 1083/1085/2514 +f 1171/1173/2514 1153/1155/2294 1083/1085/2514 +f 1167/1169/2516 1166/1168/2517 1153/1155/2294 +f 258/258/2518 256/256/2519 264/264/2520 +f 241/241/2521 249/249/2522 237/237/2523 +f 82/82/2524 295/295/2525 292/292/2526 +f 91/91/2527 86/86/2528 277/277/2529 +f 81/81/2530 91/91/2527 277/277/2529 +f 86/86/2528 91/91/2527 87/87/2531 +f 236/236/2532 237/237/2523 238/238/2533 +f 240/240/2534 249/249/2522 241/241/2521 +f 279/279/2535 81/81/2530 277/277/2529 +f 238/238/2533 237/237/2523 252/252/2536 +f 240/240/2534 91/91/2527 81/81/2530 +f 1167/1169/2516 1153/1155/2294 1171/1173/2514 +f 243/243/2518 252/252/2536 248/248/2537 +f 277/277/2529 274/274/2538 279/279/2535 +f 245/245/2539 243/243/2518 248/248/2537 +f 249/249/2522 248/248/2537 252/252/2536 +f 274/274/2538 272/272/2540 279/279/2535 +f 292/292/2526 288/288/2541 283/283/2542 +f 82/82/2524 292/292/2526 283/283/2542 +f 262/262/2543 264/264/2520 99/99/2544 +f 649/650/1246 704/705/2295 235/835/2545 +f 99/99/2544 295/295/2525 82/82/2524 +f 82/82/2524 100/100/2546 99/99/2544 +f 82/82/2524 228/228/2547 100/100/2546 +f 235/235/2548 228/228/2547 82/82/2524 +f 108/108/2549 234/234/2550 235/235/2548 +f 233/233/2551 104/104/2552 100/100/2546 +f 104/104/2552 233/233/2551 232/232/1243 +f 100/468/880 302/302/2553 303/303/1245 +f 234/234/2550 108/108/2549 107/107/528 +f 235/235/2548 234/234/2550 228/228/2547 +f 228/228/2547 233/233/2551 100/100/2546 +f 341/341/528 346/346/531 321/321/528 +f 358/358/528 323/323/528 316/316/528 +f 404/404/584 770/771/528 769/770/1477 +f 705/706/528 830/831/528 707/708/528 +f 720/721/528 365/365/539 353/353/528 +f 358/358/528 364/364/528 323/323/528 +f 720/721/528 353/353/528 341/341/528 +f 321/321/528 720/721/528 341/341/528 +f 646/647/1243 769/770/1477 830/831/528 +f 346/346/531 316/316/528 321/321/528 +f 341/341/528 340/340/529 346/346/531 +f 346/346/531 356/356/535 316/316/528 +f 404/404/584 356/356/535 770/771/528 +f 402/402/582 404/404/584 769/770/1477 +f 705/706/528 646/647/1243 830/831/528 +f 402/402/582 300/300/1250 465/465/1251 +f 465/465/1251 300/300/1250 308/308/528 +f 356/356/535 358/358/528 316/316/528 +f 356/356/535 346/346/531 770/771/528 +f 304/304/528 465/465/1251 308/308/528 +f 237/237/2523 249/249/2522 252/252/2536 +f 402/402/582 769/770/1477 642/643/1242 +f 769/770/1477 646/647/1243 642/643/1242 +f 300/300/1250 402/402/582 642/643/1242 +f 930/932/2554 795/796/2555 799/800/2556 +f 922/924/2557 926/928/2558 313/313/2559 +f 568/569/2560 563/564/2561 310/310/2562 +f 711/712/2563 313/313/2559 822/823/2564 +f 313/313/2559 926/928/2558 822/823/2564 +f 460/460/98 675/676/1339 461/461/2565 +f 310/310/2562 309/309/2566 326/326/2567 +f 713/714/2568 711/712/2563 822/823/2564 +f 565/566/2569 568/569/2560 567/568/2570 +f 568/569/2560 310/310/2562 326/326/2567 +f 572/573/2571 571/572/2572 441/441/2573 +f 326/326/2567 441/441/2573 571/572/2572 +f 326/326/2567 571/572/2572 570/571/2574 +f 931/933/2575 795/796/2555 930/932/2554 +f 326/326/2567 570/571/2574 568/569/2560 +f 930/932/2554 799/800/2556 928/930/2576 +f 799/800/2556 822/823/2564 928/930/2576 +f 822/823/2564 926/928/2558 928/930/2576 +f 565/566/2569 563/564/2561 568/569/2560 +f 563/564/2561 313/313/2559 310/310/2562 +f 924/926/2577 925/927/2578 926/928/2558 +f 565/566/2569 567/568/2570 566/567/2579 +f 922/924/2557 924/926/2577 926/928/2558 +f 922/924/2557 313/313/2559 563/564/2561 +f 563/564/2561 923/925/2580 922/924/2557 +f 563/564/2561 564/565/879 923/925/2580 +f 564/565/879 649/650/1246 923/925/2580 +f 564/565/879 100/468/880 303/303/1245 +f 923/925/2580 649/650/1246 235/835/2545 +f 461/461/2565 675/676/1339 100/468/880 +f 704/705/2295 829/830/2294 235/835/2545 +f 829/830/2294 827/828/2581 235/835/2545 +f 649/650/1246 564/565/879 303/303/1245 +f 249/249/2522 240/240/2534 81/81/2530 +f 81/81/2530 96/96/2582 249/249/2522 +f 81/81/2530 101/101/2583 96/96/2582 +f 81/81/2530 80/80/2584 101/101/2583 +f 80/80/2584 295/295/2525 101/101/2583 +f 295/295/2525 99/99/2544 101/101/2583 +f 101/101/2583 99/99/2544 264/264/2520 +f 262/262/2543 258/258/2518 264/264/2520 +f 675/676/1339 302/302/2553 100/468/880 +f 1221/1223/2585 1222/1224/2586 1223/1225/2585 +f 1224/1226/2587 1225/1227/2587 1226/1228/2588 +f 1226/1228/2588 1225/1227/2587 1227/1229/2588 +f 1228/1230/2589 1226/1228/2588 1227/1229/2588 +f 1229/1231/2590 1230/1232/2591 1223/1225/2592 +f 1228/1230/2588 1225/1227/2588 1231/1233/2585 +f 1222/1224/2586 1232/1234/2593 1223/1225/2585 +f 1222/1224/2586 1233/1235/2594 1232/1234/2593 +f 1234/1236/2595 1235/1237/2596 1231/1233/2585 +f 1236/1238/2597 1237/1239/2598 1238/1240/2599 +f 1233/1235/2594 1238/1240/2599 1232/1234/2593 +f 1233/1235/2594 1236/1238/2597 1238/1240/2599 +f 1225/1227/2588 1234/1236/2595 1231/1233/2585 +f 1236/1238/2597 1239/1241/2600 1237/1239/2598 +f 1239/1241/2600 1240/1242/2601 1237/1239/2598 +f 1237/1239/2598 1240/1242/2601 1241/1243/2602 +f 1240/1242/2601 1242/1244/2603 1241/1243/2602 +f 1240/1242/2601 1235/1237/2596 1242/1244/2603 +f 1235/1237/2596 1234/1236/2595 1242/1244/2603 +f 1243/1245/2604 1244/1246/2605 1245/1247/2606 +f 1246/1248/2607 1247/1249/2605 1248/1250/2608 +f 1249/1251/2609 1250/1252/2610 1251/1253/2611 +f 1252/1254/2612 1247/1249/2605 1246/1248/2607 +f 1245/1247/2606 1248/1250/2608 1243/1245/2604 +f 1250/1252/2610 1253/1255/2613 1251/1253/2611 +f 1253/1255/2613 1254/1256/2614 1251/1253/2611 +f 1255/1257/2615 1249/1251/2616 1256/1258/2617 +f 1247/1249/2605 1252/1254/2612 1244/1246/2605 +f 1256/1258/2617 1254/1256/2614 1255/1257/2615 +f 1254/1256/2614 1257/1259/2618 1255/1257/2615 +f 1248/1250/2608 1247/1249/2605 1243/1245/2604 +f 1244/1246/2605 1252/1254/2612 1258/1260/2619 +f 1254/1256/2614 1259/1261/2620 1257/1259/2618 +f 1244/1246/2605 1260/1262/2621 1245/1247/2606 +f 1244/1246/2605 1258/1260/2619 1260/1262/2621 +f 1239/1241/2622 1261/1263/2623 1262/1264/2624 +f 1258/1260/2619 1261/1263/2623 1260/1262/2621 +f 1258/1260/2619 1238/1240/2625 1261/1263/2623 +f 1238/1240/2625 1262/1264/2624 1261/1263/2623 +f 1263/1265/2626 1239/1241/2622 1264/1266/2627 +f 1239/1241/2622 1262/1264/2624 1264/1266/2627 +f 1265/1267/2628 1263/1265/2626 1266/1268/2629 +f 1263/1265/2626 1264/1266/2627 1266/1268/2629 +f 1253/1255/2613 1265/1267/2628 1259/1261/2620 +f 1254/1256/2614 1253/1255/2613 1259/1261/2620 +f 1265/1267/2628 1266/1268/2629 1259/1261/2620 +f 1228/1230/2630 1231/1233/2631 1250/1252/2632 +f 1231/1233/2631 1253/1255/2633 1250/1252/2632 +f 1231/1233/2634 1235/1237/2634 1253/1255/2634 +f 1235/1237/2635 1265/1267/2635 1253/1255/2635 +f 1235/1237/2636 1240/1242/2636 1265/1267/2636 +f 1240/1242/2637 1263/1265/2637 1265/1267/2637 +f 1240/1242/2638 1239/1241/2638 1263/1265/2638 +f 1236/1238/2639 1261/1263/2639 1239/1241/2639 +f 1236/1238/2640 1233/1235/2640 1261/1263/2640 +f 1233/1235/2641 1260/1262/2641 1261/1263/2641 +f 1233/1235/2642 1222/1224/2642 1260/1262/2642 +f 1222/1224/2643 1245/1247/2644 1260/1262/2645 +f 1222/1224/2643 1221/1223/2646 1245/1247/2644 +f 1230/1232/2647 1248/1250/2647 1221/1223/2647 +f 1248/1250/2648 1245/1247/2648 1221/1223/2648 +f 1230/1232/2649 1229/1231/2649 1248/1250/2649 +f 1229/1231/2650 1246/1248/2650 1248/1250/2650 +f 1223/1225/2592 1252/1254/2651 1229/1231/2590 +f 1252/1254/2652 1246/1248/2652 1229/1231/2652 +f 1223/1225/2653 1232/1234/2653 1252/1254/2653 +f 1232/1234/2654 1258/1260/2654 1252/1254/2654 +f 1232/1234/2655 1238/1240/2655 1258/1260/2655 +f 1238/1240/2656 1237/1239/2656 1262/1264/2656 +f 1237/1239/2657 1264/1266/2657 1262/1264/2657 +f 1237/1239/2658 1241/1243/2658 1264/1266/2658 +f 1241/1243/2659 1242/1244/2660 1264/1266/2661 +f 1242/1244/2660 1266/1268/2662 1264/1266/2661 +f 1242/1244/2663 1259/1261/2664 1266/1268/2665 +f 1242/1244/2663 1234/1236/2666 1259/1261/2664 +f 1234/1236/2667 1257/1259/2668 1259/1261/2669 +f 1234/1236/2667 1225/1227/2670 1257/1259/2668 +f 1224/1226/2671 1255/1257/2671 1225/1227/2671 +f 1255/1257/2672 1257/1259/2672 1225/1227/2672 +f 1224/1226/2673 1226/1228/2673 1255/1257/2673 +f 1226/1228/2674 1249/1251/2674 1255/1257/2674 +f 1228/1230/2630 1250/1252/2632 1226/1228/2675 +f 1250/1252/2676 1249/1251/2676 1226/1228/2676 +f 1223/1225/2677 1230/1232/2677 1247/1249/2677 +f 1230/1232/2678 1243/1245/2678 1247/1249/2678 +f 1230/1232/2679 1221/1223/2679 1243/1245/2679 +f 1221/1223/2680 1244/1246/2680 1243/1245/2680 +f 1221/1223/2681 1223/1225/2681 1244/1246/2681 +f 1223/1225/2682 1247/1249/2682 1244/1246/2682 +f 1227/1229/2683 1256/1258/2683 1249/1251/2683 +f 1227/1229/2684 1225/1227/2684 1256/1258/2684 +f 1225/1227/2685 1254/1256/2685 1256/1258/2685 +f 1225/1227/2686 1228/1230/2686 1254/1256/2686 +f 1228/1230/2687 1251/1253/2687 1254/1256/2687 +f 1228/1230/2688 1227/1229/2689 1251/1253/2690 +f 1227/1229/2689 1249/1251/2691 1251/1253/2690 +f 1267/1269/2692 1268/1270/2693 1269/1271/2694 +f 1267/1269/2695 1270/1272/2695 1271/1273/2695 +f 1272/1274/2696 1273/1275/2697 1274/1276/2698 +f 1273/1275/2697 1275/1277/2699 1276/1278/2700 +f 1270/1272/2701 1267/1269/2692 1269/1271/2694 +f 1277/1279/2702 1276/1278/2700 1275/1277/2699 +f 1274/1276/2698 1273/1275/2697 1276/1278/2700 +f 1278/1280/2703 1268/1270/2704 1271/1273/2705 +f 1279/1281/2706 1272/1274/2707 1274/1276/2708 +f 1269/1271/2694 1268/1270/2693 1280/1282/2709 +f 1281/1283/2710 1282/1284/2711 1283/1285/2711 +f 1269/1271/2694 1280/1282/2709 1281/1283/2710 +f 1281/1283/2710 1280/1282/2709 1282/1284/2711 +f 1274/1276/2712 1277/1279/2712 1284/1286/2713 +f 1274/1276/2712 1284/1286/2713 1279/1281/2714 +f 1282/1284/2711 1285/1287/2711 1283/1285/2711 +f 1283/1285/2711 1285/1287/2711 1286/1288/2711 +f 1283/1285/2711 1286/1288/2711 1287/1289/2711 +f 1287/1289/2711 1286/1288/2711 1284/1286/2713 +f 1284/1286/2713 1286/1288/2711 1279/1281/2714 +f 1288/1290/2715 1289/1291/2716 1290/1292/2717 +f 1291/1293/2718 1288/1290/2715 1290/1292/2717 +f 1270/1272/2719 1292/1294/2720 1293/1295/2721 +f 1270/1272/2719 1293/1295/2721 1289/1291/2716 +f 1290/1292/2717 1289/1291/2716 1293/1295/2721 +f 1294/1296/2722 1295/1297/2723 1296/1298/2724 +f 1296/1298/2724 1295/1297/2723 1297/1299/2725 +f 1291/1293/2718 1290/1292/2717 1292/1294/2726 +f 1297/1299/2727 1273/1275/2728 1272/1274/2729 +f 1295/1297/2723 1294/1296/2722 1298/1300/2730 +f 1273/1275/2728 1297/1299/2727 1298/1300/2731 +f 1292/1294/2726 1299/1301/2732 1291/1293/2718 +f 1297/1299/2733 1272/1274/2707 1300/1302/2734 +f 1299/1301/2732 1292/1294/2726 1301/1303/2735 +f 1302/1304/2736 1303/1305/2737 1304/1306/2738 +f 1299/1301/2732 1301/1303/2735 1304/1306/2738 +f 1304/1306/2738 1301/1303/2735 1302/1304/2736 +f 1305/1307/2739 1306/1308/2740 1302/1304/2736 +f 1302/1304/2736 1306/1308/2740 1303/1305/2737 +f 1305/1307/2739 1307/1309/2718 1306/1308/2740 +f 1297/1299/2725 1300/1302/2724 1296/1298/2724 +f 1296/1298/2724 1300/1302/2724 1308/1310/2741 +f 1308/1310/2741 1300/1302/2724 1307/1309/2718 +f 1308/1310/2741 1307/1309/2718 1305/1307/2739 +f 1277/1279/2742 1294/1296/2743 1296/1298/2744 +f 1277/1279/2745 1296/1298/2745 1284/1286/2745 +f 1284/1286/2746 1296/1298/2746 1308/1310/2746 +f 1284/1286/2747 1308/1310/2747 1287/1289/2747 +f 1287/1289/2748 1308/1310/2748 1305/1307/2748 +f 1287/1289/2749 1305/1307/2749 1283/1285/2749 +f 1283/1285/2750 1305/1307/2750 1302/1304/2750 +f 1283/1285/2751 1302/1304/2751 1281/1283/2751 +f 1281/1283/2752 1302/1304/2752 1301/1303/2752 +f 1281/1283/2753 1301/1303/2753 1269/1271/2753 +f 1269/1271/2754 1301/1303/2754 1292/1294/2754 +f 1269/1271/2755 1292/1294/2720 1270/1272/2719 +f 1271/1273/2756 1270/1272/2756 1289/1291/2756 +f 1271/1273/2757 1289/1291/2757 1278/1280/2757 +f 1278/1280/2758 1289/1291/2758 1288/1290/2758 +f 1268/1270/2704 1278/1280/2703 1291/1293/2759 +f 1291/1293/2760 1278/1280/2760 1288/1290/2760 +f 1268/1270/2761 1291/1293/2761 1280/1282/2761 +f 1280/1282/2762 1291/1293/2762 1299/1301/2762 +f 1280/1282/2763 1299/1301/2764 1304/1306/2765 +f 1280/1282/2763 1304/1306/2765 1282/1284/2766 +f 1282/1284/2767 1304/1306/2767 1303/1305/2767 +f 1282/1284/2768 1303/1305/2768 1285/1287/2768 +f 1285/1287/2769 1303/1305/2769 1306/1308/2769 +f 1285/1287/2770 1306/1308/2770 1286/1288/2770 +f 1286/1288/2771 1306/1308/2771 1307/1309/2771 +f 1286/1288/2772 1307/1309/2773 1300/1302/2774 +f 1286/1288/2772 1300/1302/2774 1279/1281/2775 +f 1279/1281/2706 1300/1302/2734 1272/1274/2707 +f 1273/1275/2776 1298/1300/2776 1275/1277/2776 +f 1277/1279/2742 1275/1277/2777 1294/1296/2743 +f 1294/1296/2722 1275/1277/2778 1298/1300/2730 +f 1268/1270/2779 1290/1292/2779 1271/1273/2779 +f 1271/1273/2780 1290/1292/2780 1293/1295/2780 +f 1271/1273/2781 1293/1295/2781 1267/1269/2781 +f 1267/1269/2782 1293/1295/2782 1292/1294/2782 +f 1267/1269/2783 1292/1294/2783 1268/1270/2783 +f 1268/1270/2784 1292/1294/2784 1290/1292/2784 +f 1276/1278/2785 1295/1297/2785 1298/1300/2785 +f 1276/1278/2786 1298/1300/2786 1274/1276/2786 +f 1274/1276/2787 1298/1300/2787 1297/1299/2787 +f 1274/1276/2788 1297/1299/2788 1277/1279/2788 +f 1277/1279/2789 1297/1299/2789 1295/1297/2789 +f 1277/1279/2790 1295/1297/2790 1276/1278/2790 +f 1309/1311/2791 1310/1312/2792 1311/1313/2793 +f 1312/1314/2794 1310/1312/2792 1309/1311/2791 +f 1313/1315/2795 1314/1316/2796 1315/1317/2797 +f 1315/1317/2797 1314/1316/2796 1316/1318/2798 +f 1317/1319/2799 1318/1320/2800 1319/1321/2801 +f 1319/1321/2801 1320/1322/2802 1317/1319/2799 +f 1321/1323/2803 1322/1324/2803 1323/1325/2803 +f 1324/1326/2804 1325/1327/2805 1322/1324/2806 +f 1324/1326/2804 1322/1324/2806 1326/1328/2807 +f 1325/1327/2805 1323/1325/2808 1322/1324/2806 +f 1325/1327/2805 1327/1329/2809 1323/1325/2808 +f 1323/1325/2808 1327/1329/2809 1328/1330/2810 +f 1328/1330/2810 1329/1331/2811 1323/1325/2808 +f 1330/1332/2812 1331/1333/2813 1332/1334/2814 +f 1333/1335/2815 1334/1336/2816 1335/1337/2817 +f 1336/1338/2818 1309/1311/2819 1311/1313/2820 +f 1336/1338/2818 1337/1339/2821 1309/1311/2819 +f 1338/1340/2820 1332/1334/2814 1331/1333/2813 +f 1339/1341/2822 1340/1342/2822 1341/1343/2822 +f 1342/1344/2823 1340/1342/2824 1339/1341/2825 +f 1342/1344/2823 1334/1336/2826 1340/1342/2824 +f 1343/1345/2827 1334/1336/2826 1342/1344/2823 +f 1343/1345/2827 1335/1337/2828 1334/1336/2826 +f 1344/1346/2829 1335/1337/2828 1343/1345/2827 +f 1345/1347/2830 1339/1341/2830 1341/1343/2830 +f 1346/1348/2831 1347/1349/2832 1348/1350/2833 +f 1349/1351/2834 1350/1352/2835 1351/1353/2836 +f 1347/1349/2832 1352/1354/2837 1348/1350/2833 +f 1350/1352/2838 1333/1335/2815 1335/1337/2817 +f 1350/1352/2838 1353/1355/2839 1333/1335/2815 +f 1344/1346/2840 1328/1330/2810 1354/1356/2841 +f 1343/1345/2842 1328/1330/2810 1344/1346/2840 +f 1343/1345/2842 1329/1331/2811 1328/1330/2810 +f 1342/1344/2843 1329/1331/2811 1343/1345/2842 +f 1342/1344/2843 1345/1347/2844 1329/1331/2811 +f 1339/1341/2845 1345/1347/2844 1342/1344/2843 +f 1350/1352/2835 1354/1356/2846 1351/1353/2836 +f 1334/1336/2816 1333/1335/2815 1355/1357/2816 +f 1353/1355/2847 1351/1353/2848 1333/1335/2849 +f 1349/1351/2850 1351/1353/2848 1353/1355/2847 +f 1350/1352/2851 1349/1351/2851 1353/1355/2851 +f 1335/1337/2852 1354/1356/2852 1350/1352/2852 +f 1354/1356/2853 1335/1337/2853 1344/1346/2853 +f 1333/1335/2854 1356/1358/2855 1355/1357/2856 +f 1351/1353/2857 1356/1358/2855 1333/1335/2854 +f 1356/1358/2858 1334/1336/2859 1355/1357/2860 +f 1328/1330/2861 1334/1336/2859 1356/1358/2858 +f 1327/1329/2862 1357/1359/2863 1358/1360/2864 +f 1327/1329/2862 1358/1360/2864 1328/1330/2865 +f 1358/1360/2866 1334/1336/2859 1328/1330/2861 +f 1327/1329/2867 1359/1361/2868 1357/1359/2869 +f 1325/1327/2870 1359/1361/2868 1327/1329/2867 +f 1360/1362/2871 1325/1327/2872 1324/1326/2873 +f 1359/1361/2874 1325/1327/2872 1360/1362/2871 +f 1359/1361/2875 1361/1363/2876 1321/1323/2877 +f 1360/1362/2878 1361/1363/2876 1359/1361/2875 +f 1360/1362/2878 1362/1364/2879 1361/1363/2876 +f 1321/1323/2877 1357/1359/2880 1359/1361/2875 +f 1358/1360/2881 1363/1365/2882 1340/1342/2883 +f 1357/1359/2880 1363/1365/2882 1358/1360/2881 +f 1357/1359/2880 1321/1323/2877 1363/1365/2882 +f 1340/1342/2883 1334/1336/2884 1358/1360/2881 +f 1326/1328/2885 1360/1362/2886 1324/1326/2887 +f 1362/1364/2888 1360/1362/2886 1326/1328/2885 +f 1362/1364/2889 1326/1328/2889 1361/1363/2889 +f 1361/1363/2890 1322/1324/2890 1321/1323/2890 +f 1361/1363/2891 1326/1328/2891 1322/1324/2891 +f 1323/1325/2892 1363/1365/2892 1321/1323/2892 +f 1329/1331/2893 1363/1365/2893 1323/1325/2893 +f 1329/1331/2894 1340/1342/2895 1363/1365/2896 +f 1345/1347/2897 1341/1343/2897 1364/1366/2897 +f 1365/1367/2898 1364/1366/2898 1366/1368/2898 +f 1367/1369/2899 1365/1367/2900 1366/1368/2901 +f 1368/1370/2902 1365/1367/2900 1367/1369/2899 +f 1369/1371/2903 1368/1370/2904 1367/1369/2905 +f 1370/1372/2906 1368/1370/2904 1369/1371/2903 +f 1340/1342/2895 1370/1372/2907 1369/1371/2908 +f 1329/1331/2894 1370/1372/2907 1340/1342/2895 +f 1371/1373/2909 1372/1374/2909 1373/1375/2909 +f 1374/1376/2909 1371/1373/2909 1373/1375/2909 +f 1372/1374/2910 1371/1373/2911 1375/1377/2912 +f 1376/1378/2913 1377/1379/2914 1374/1376/2915 +f 1376/1378/2913 1374/1376/2915 1373/1375/2916 +f 1378/1380/2917 1377/1379/2918 1379/1381/2919 +f 1378/1380/2917 1380/1382/2920 1377/1379/2918 +f 1378/1380/2921 1381/1383/2921 1380/1382/2921 +f 1381/1383/2922 1382/1384/2923 1379/1381/2924 +f 1383/1385/2925 1382/1384/2923 1381/1383/2922 +f 1377/1379/2926 1371/1373/2927 1374/1376/2928 +f 1380/1382/2929 1371/1373/2927 1377/1379/2926 +f 1371/1373/2911 1380/1382/2930 1375/1377/2912 +f 1376/1378/2931 1372/1374/2932 1375/1377/2933 +f 1376/1378/2931 1373/1375/2934 1372/1374/2932 +f 1378/1380/2935 1383/1385/2935 1381/1383/2935 +f 1382/1384/2936 1378/1380/2937 1379/1381/2938 +f 1383/1385/2939 1378/1380/2937 1382/1384/2936 +f 1384/1386/2940 1385/1387/2941 1386/1388/2942 +f 1387/1389/2943 1388/1390/2944 1389/1391/2943 +f 1390/1392/2945 1389/1391/2943 1388/1390/2944 +f 1391/1393/2946 1386/1388/2942 1392/1394/2947 +f 1386/1388/2942 1391/1393/2946 1384/1386/2940 +f 1389/1391/2948 1386/1388/2949 1385/1387/2950 +f 1390/1392/2951 1386/1388/2949 1389/1391/2948 +f 1385/1387/2952 1387/1389/2952 1389/1391/2952 +f 1384/1386/2953 1387/1389/2953 1385/1387/2953 +f 1390/1392/2945 1391/1393/2954 1392/1394/2955 +f 1388/1390/2944 1391/1393/2954 1390/1392/2945 +f 1384/1386/2956 1388/1390/2956 1387/1389/2956 +f 1391/1393/2957 1388/1390/2957 1384/1386/2957 +f 1393/1395/2958 1394/1396/2959 1395/1397/2960 +f 1395/1397/2960 1396/1398/2961 1393/1395/2958 +f 1397/1399/2962 1398/1400/2963 1395/1397/2964 +f 1395/1397/2964 1394/1396/2965 1397/1399/2962 +f 1386/1388/2966 1390/1392/2966 1392/1394/2966 +f 1399/1401/2967 1400/1402/2968 1401/1403/2969 +f 1402/1404/2970 1403/1405/2970 1404/1406/2970 +f 1402/1404/2971 1405/1407/2971 1403/1405/2971 +f 1406/1408/2972 1405/1407/2972 1402/1404/2972 +f 1405/1407/2973 1400/1402/2968 1403/1405/2974 +f 1402/1404/2975 1404/1406/2820 1399/1401/2976 +f 1400/1402/2968 1407/1409/2977 1403/1405/2974 +f 1406/1408/2978 1402/1404/2975 1399/1401/2976 +f 1405/1407/2973 1401/1403/2969 1400/1402/2968 +f 1404/1406/2979 1407/1409/2979 1399/1401/2979 +f 1404/1406/2980 1403/1405/2980 1407/1409/2980 +f 1400/1402/2981 1399/1401/2981 1407/1409/2981 +f 1337/1339/1501 1336/1338/1513 1346/1348/1515 +f 1408/1410/2982 1409/1411/1501 1346/1348/1515 +f 1336/1338/1513 1347/1349/1513 1346/1348/1515 +f 1410/1412/1501 1411/1413/2983 1346/1348/1515 +f 1409/1411/1501 1410/1412/1501 1346/1348/1515 +f 1411/1413/2983 1337/1339/1501 1346/1348/1515 +f 1412/1414/2984 1413/1415/2984 1414/1416/2984 +f 1415/1417/2985 1412/1414/2985 1414/1416/2985 +f 1416/1418/2986 1415/1417/2987 1414/1416/2988 +f 1413/1415/2989 1416/1418/2986 1414/1416/2988 +f 1417/1419/2990 1418/1420/2991 1419/1421/2992 +f 1420/1422/2993 1421/1423/2994 1422/1424/2995 +f 1421/1423/2994 1423/1425/2996 1424/1426/2997 +f 1424/1426/2997 1423/1425/2996 1425/1427/2998 +f 1420/1422/2993 1426/1428/2999 1421/1423/2994 +f 1421/1423/2994 1426/1428/2999 1423/1425/2996 +f 1427/1429/3000 1428/1430/3001 1429/1431/3002 +f 1425/1427/2998 1430/1432/3003 1424/1426/2997 +f 1430/1432/3003 1425/1427/2998 1429/1431/3002 +f 1429/1431/3002 1425/1427/2998 1427/1429/3000 +f 1431/1433/3002 1432/1434/3004 1433/1435/3001 +f 1431/1433/3002 1433/1435/3001 1428/1430/3001 +f 1428/1430/3001 1433/1435/3001 1429/1431/3002 +f 1420/1422/2993 1422/1424/2995 1431/1433/3002 +f 1431/1433/3002 1434/1436/3000 1424/1426/2997 +f 1424/1426/2997 1430/1432/3003 1432/1434/3004 +f 1422/1424/2995 1434/1436/3000 1431/1433/3002 +f 1424/1426/2997 1432/1434/3004 1431/1433/3002 +f 1428/1430/3005 1427/1429/3006 1435/1437/3007 +f 1435/1437/3007 1427/1429/3006 1436/1438/3008 +f 1437/1439/3009 1436/1438/3010 1438/1440/3011 +f 1439/1441/3012 1438/1440/3011 1440/1442/3013 +f 1439/1441/3012 1440/1442/3013 1441/1443/3014 +f 1440/1442/3013 1438/1440/3011 1436/1438/3010 +f 1442/1444/3015 1443/1445/3016 1439/1441/3012 +f 1439/1441/3012 1443/1445/3016 1438/1440/3011 +f 1435/1437/3015 1444/1446/3016 1442/1444/3015 +f 1436/1438/3010 1437/1439/3009 1445/1447/3017 +f 1435/1437/3015 1436/1438/3010 1445/1447/3017 +f 1443/1445/3016 1442/1444/3015 1446/1448/3018 +f 1445/1447/3017 1447/1449/3019 1435/1437/3015 +f 1444/1446/3016 1435/1437/3015 1447/1449/3019 +f 1444/1446/3016 1448/1450/3020 1442/1444/3015 +f 1442/1444/3015 1448/1450/3020 1446/1448/3018 +f 1448/1450/3020 1444/1446/3016 1438/1440/3011 +f 1438/1440/3011 1444/1446/3016 1437/1439/3009 +f 1425/1427/3021 1436/1438/3021 1427/1429/3021 +f 1436/1438/3022 1425/1427/3022 1440/1442/3022 +f 1440/1442/3023 1425/1427/3024 1423/1425/3025 +f 1449/1451/3026 1450/1452/3026 1451/1453/3026 +f 1449/1451/3026 1451/1453/3026 1423/1425/3025 +f 1423/1425/3025 1451/1453/3026 1440/1442/3023 +f 1452/1454/3027 1449/1451/3028 1426/1428/3029 +f 1426/1428/3029 1449/1451/3028 1423/1425/3030 +f 1453/1455/3031 1454/1456/3031 1452/1454/3031 +f 1452/1454/3031 1455/1457/3031 1453/1455/3031 +f 1420/1422/3032 1439/1441/3033 1426/1428/3034 +f 1426/1428/3034 1439/1441/3033 1441/1443/3035 +f 1426/1428/3034 1455/1457/3031 1452/1454/3031 +f 1426/1428/3034 1441/1443/3035 1455/1457/3031 +f 1439/1441/3033 1420/1422/3032 1442/1444/3036 +f 1442/1444/3036 1420/1422/3032 1431/1433/3037 +f 1441/1443/3038 1440/1442/3039 1455/1457/3040 +f 1455/1457/3040 1440/1442/3039 1451/1453/3041 +f 1455/1457/3042 1451/1453/3043 1450/1452/3044 +f 1455/1457/3042 1450/1452/3044 1453/1455/3045 +f 1453/1455/3046 1450/1452/3046 1454/1456/3046 +f 1450/1452/3047 1449/1451/3047 1454/1456/3047 +f 1454/1456/3048 1449/1451/3048 1452/1454/3048 +f 1442/1444/3049 1431/1433/3050 1435/1437/3051 +f 1435/1437/3051 1431/1433/3050 1428/1430/3052 +f 1433/1435/3053 1444/1446/3053 1447/1449/3053 +f 1433/1435/3054 1447/1449/3054 1429/1431/3054 +f 1429/1431/3055 1447/1449/3055 1445/1447/3055 +f 1429/1431/3056 1445/1447/3056 1430/1432/3056 +f 1430/1432/3057 1445/1447/3057 1437/1439/3057 +f 1430/1432/3058 1437/1439/3058 1432/1434/3058 +f 1432/1434/3059 1437/1439/3059 1444/1446/3059 +f 1432/1434/3060 1444/1446/3060 1433/1435/3060 +f 1424/1426/3061 1446/1448/3061 1448/1450/3061 +f 1424/1426/3062 1448/1450/3063 1438/1440/3064 +f 1424/1426/3062 1438/1440/3064 1421/1423/3065 +f 1421/1423/3066 1438/1440/3067 1443/1445/3068 +f 1421/1423/3066 1443/1445/3068 1422/1424/3069 +f 1422/1424/3070 1443/1445/3070 1434/1436/3070 +f 1434/1436/3071 1443/1445/3071 1446/1448/3071 +f 1434/1436/3072 1446/1448/3072 1424/1426/3072 +f 1456/1458/3073 1457/1459/3074 1458/1460/3075 +f 1459/1461/3076 1460/1462/3077 1461/1463/3078 +f 1457/1459/3079 1462/1464/3080 1459/1461/3076 +f 1457/1459/3079 1459/1461/3076 1463/1465/3081 +f 1459/1461/3076 1461/1463/3078 1463/1465/3081 +f 1464/1466/3082 1465/1467/3083 1466/1468/3084 +f 1467/1469/3026 1465/1467/3083 1464/1466/3082 +f 1468/1470/3085 1469/1471/3085 1470/1472/3085 +f 1471/1473/3086 1472/1474/3087 1468/1470/3088 +f 1468/1470/3088 1472/1474/3087 1469/1471/3089 +f 1471/1473/3086 1468/1470/3088 1473/1475/3090 +f 1471/1473/3086 1473/1475/3090 1474/1476/3091 +f 1475/1477/3092 1474/1476/3092 1473/1475/3092 +f 1476/1478/3093 1477/1479/3026 1475/1477/3094 +f 1475/1477/3094 1473/1475/3095 1476/1478/3093 +f 1458/1460/3075 1478/1480/3026 1456/1458/3073 +f 1461/1463/3096 1479/1481/3097 1458/1460/3075 +f 1479/1481/3097 1478/1480/3026 1458/1460/3075 +f 1458/1460/3075 1480/1482/3098 1461/1463/3096 +f 1481/1483/3099 1482/1484/3100 1483/1485/3101 +f 1483/1485/3101 1482/1484/3100 1484/1486/3102 +f 1485/1487/3103 1477/1479/3104 1486/1488/3105 +f 1486/1488/3105 1477/1479/3104 1476/1478/3106 +f 1486/1488/3105 1476/1478/3106 1487/1489/3107 +f 1487/1489/3107 1476/1478/3106 1488/1490/3108 +f 1487/1489/3107 1488/1490/3108 1483/1485/3109 +f 1483/1485/3109 1488/1490/3108 1481/1483/3110 +f 1484/1486/3111 1482/1484/3112 1489/1491/3113 +f 1489/1491/3113 1482/1484/3112 1490/1492/3114 +f 1489/1491/3115 1490/1492/3116 1470/1472/3117 +f 1489/1491/3115 1470/1472/3117 1491/1493/3118 +f 1492/1494/3119 1491/1493/3118 1493/1495/3120 +f 1493/1495/3120 1491/1493/3118 1470/1472/3117 +f 1469/1471/98 1472/1474/98 1492/1494/98 +f 1492/1494/98 1493/1495/98 1469/1471/98 +f 1494/1496/3121 1495/1497/3121 1496/1498/3121 +f 1495/1497/3122 1494/1496/3122 1497/1499/3122 +f 1495/1497/3123 1497/1499/3123 1498/1500/3123 +f 1495/1497/3124 1498/1500/3124 1496/1498/3124 +f 1499/1501/3125 1500/1502/3125 1501/1503/3125 +f 1499/1501/3126 1501/1503/3126 1502/1504/3126 +f 1499/1501/3127 1502/1504/3127 1500/1502/3127 +f 1503/1505/3128 1504/1506/3129 1505/1507/3130 +f 1503/1505/3128 1506/1508/3131 1504/1506/3129 +f 1496/1498/3132 1507/1509/3133 1508/1510/3134 +f 1507/1509/3133 1496/1498/3132 1498/1500/3135 +f 1498/1500/3136 1509/1511/3137 1507/1509/3138 +f 1509/1511/3137 1498/1500/3136 1497/1499/3139 +f 1509/1511/3140 1497/1499/3141 1494/1496/3142 +f 1494/1496/3142 1510/1512/3143 1509/1511/3140 +f 1510/1512/3144 1494/1496/3145 1496/1498/3146 +f 1496/1498/3146 1508/1510/3147 1510/1512/3144 +f 1502/1504/3148 1511/1513/3148 1512/1514/3148 +f 1511/1513/3149 1502/1504/3150 1501/1503/3151 +f 1501/1503/3151 1513/1515/3152 1511/1513/3149 +f 1501/1503/3153 1514/1516/3153 1513/1515/3153 +f 1514/1516/3154 1501/1503/3154 1500/1502/3154 +f 1500/1502/3155 1512/1514/3155 1514/1516/3155 +f 1512/1514/3156 1500/1502/3156 1502/1504/3156 +f 1506/1508/3157 1515/1517/3158 1516/1518/3159 +f 1515/1517/3160 1506/1508/3160 1503/1505/3160 +f 1503/1505/3161 1517/1519/3162 1515/1517/3163 +f 1517/1519/3164 1503/1505/3164 1505/1507/3164 +f 1505/1507/3165 1518/1520/3166 1517/1519/3167 +f 1518/1520/3168 1505/1507/3168 1504/1506/3168 +f 1504/1506/3169 1516/1518/3170 1518/1520/3171 +f 1516/1518/3172 1504/1506/3172 1506/1508/3172 +f 1519/1521/3173 1520/1522/3174 1521/1523/3175 +f 1521/1523/3176 1522/1524/3176 1519/1521/3176 +f 1522/1524/3177 1521/1523/3178 1523/1525/3179 +f 1523/1525/3180 1524/1526/3180 1522/1524/3180 +f 1524/1526/3181 1523/1525/3182 1525/1527/3183 +f 1525/1527/3184 1526/1528/3184 1524/1526/3184 +f 1526/1528/3185 1525/1527/3186 1520/1522/3187 +f 1520/1522/3187 1519/1521/3188 1526/1528/3185 +f 1520/1522/3187 1518/1520/3171 1516/1518/3170 +f 1518/1520/3171 1520/1522/3187 1525/1527/3186 +f 1525/1527/3183 1517/1519/3167 1518/1520/3166 +f 1517/1519/3167 1525/1527/3183 1523/1525/3182 +f 1521/1523/3178 1515/1517/3163 1517/1519/3162 +f 1517/1519/3162 1523/1525/3179 1521/1523/3178 +f 1521/1523/3175 1516/1518/3159 1515/1517/3158 +f 1516/1518/3159 1521/1523/3175 1520/1522/3174 +f 1527/1529/3189 1528/1530/3190 1529/1531/3191 +f 1530/1532/3192 1529/1531/3192 1528/1530/3192 +f 1528/1530/3193 1531/1533/3194 1530/1532/3195 +f 1531/1533/3196 1528/1530/3196 1527/1529/3196 +f 1527/1529/3197 1532/1534/3198 1531/1533/3199 +f 1532/1534/3200 1527/1529/3200 1533/1535/3200 +f 1533/1535/3201 1534/1536/3201 1532/1534/3201 +f 1534/1536/3202 1533/1535/3202 1529/1531/3202 +f 1529/1531/3203 1530/1532/3204 1534/1536/3205 +f 1535/1537/3206 1536/1538/3207 1537/1539/3208 +f 1536/1538/3209 1535/1537/3210 1538/1540/3211 +f 1536/1538/3212 1538/1540/3213 1539/1541/3214 +f 1539/1541/3214 1540/1542/3215 1536/1538/3212 +f 1540/1542/3216 1539/1541/3217 1541/1543/3218 +f 1540/1542/3219 1541/1543/3220 1542/1544/3221 +f 1542/1544/3221 1537/1539/3222 1540/1542/3219 +f 1537/1539/3223 1542/1544/3224 1535/1537/3225 +f 1534/1536/3226 1542/1544/3221 1541/1543/3220 +f 1541/1543/3218 1532/1534/3227 1534/1536/3228 +f 1532/1534/3227 1541/1543/3218 1539/1541/3217 +f 1539/1541/3214 1531/1533/3199 1532/1534/3198 +f 1531/1533/3199 1539/1541/3214 1538/1540/3213 +f 1535/1537/3210 1530/1532/3195 1531/1533/3194 +f 1531/1533/3194 1538/1540/3211 1535/1537/3210 +f 1542/1544/3224 1534/1536/3205 1530/1532/3204 +f 1530/1532/3204 1535/1537/3225 1542/1544/3224 +f 1470/1472/3085 1490/1492/3085 1473/1475/3085 +f 1469/1471/3085 1493/1495/3085 1470/1472/3085 +f 1476/1478/3085 1473/1475/3085 1490/1492/3085 +f 1473/1475/3085 1468/1470/3085 1470/1472/3085 +f 1488/1490/3085 1476/1478/3085 1490/1492/3085 +f 1543/1545/3229 1544/1546/3230 1545/1547/3231 +f 1544/1546/3230 1546/1548/3232 1547/1549/3233 +f 1547/1549/3233 1545/1547/3231 1544/1546/3230 +f 1547/1549/3234 1548/1550/3234 1549/1551/3234 +f 1550/1552/3235 1543/1545/3236 1545/1547/3237 +f 1545/1547/3237 1551/1553/3238 1550/1552/3235 +f 1548/1550/3239 1550/1552/3240 1551/1553/3241 +f 1551/1553/3241 1549/1551/3242 1548/1550/3239 +f 1549/1551/3243 1545/1547/3244 1547/1549/3245 +f 1545/1547/3244 1549/1551/3243 1551/1553/3246 +f 1552/1554/3247 1553/1555/3248 1554/1556/3249 +f 1553/1555/3250 1552/1554/3250 1555/1557/3250 +f 1556/1558/3251 1557/1559/3251 1558/1560/3251 +f 1559/1561/3252 1560/1562/3252 1561/1563/3252 +f 1556/1558/3253 1559/1561/3254 1561/1563/3255 +f 1561/1563/3255 1557/1559/3256 1556/1558/3253 +f 1524/1526/3257 1526/1528/3258 1522/1524/3259 +f 1526/1528/3258 1519/1521/3260 1522/1524/3259 +f 1514/1516/3261 1511/1513/3262 1513/1515/3263 +f 1511/1513/3262 1514/1516/3261 1512/1514/3264 +f 1507/1509/3265 1509/1511/3266 1508/1510/3267 +f 1508/1510/3267 1509/1511/3266 1510/1512/3268 +f 1489/1491/3269 1491/1493/2352 1471/1473/3270 +f 1489/1491/3269 1471/1473/3270 1474/1476/3271 +f 1492/1494/2352 1472/1474/2352 1491/1493/2352 +f 1472/1474/2352 1471/1473/3270 1491/1493/2352 +f 1486/1488/3272 1487/1489/2352 1489/1491/3269 +f 1474/1476/3271 1486/1488/3272 1489/1491/3269 +f 1562/1564/3273 1554/1556/3273 1563/1565/3273 +f 1564/1566/3274 1565/1567/3274 1563/1565/3274 +f 1564/1566/3275 1563/1565/3275 1554/1556/3275 +f 1566/1568/3276 1565/1567/3276 1564/1566/3276 +f 1555/1557/3277 1552/1554/3278 1562/1564/3279 +f 1553/1555/3248 1566/1568/3031 1554/1556/3249 +f 1554/1556/3249 1566/1568/3031 1564/1566/3031 +f 1562/1564/3279 1563/1565/3026 1565/1567/3026 +f 1555/1557/3277 1562/1564/3279 1565/1567/3026 +f 1553/1555/3280 1555/1557/3280 1566/1568/3280 +f 1566/1568/3281 1555/1557/3281 1565/1567/3281 +f 1554/1556/3282 1562/1564/3279 1552/1554/3278 +f 1567/1569/3283 1568/1570/3283 1569/1571/3283 +f 1559/1561/3284 1556/1558/3285 1558/1560/3286 +f 1558/1560/3286 1560/1562/3287 1559/1561/3284 +f 1561/1563/3288 1560/1562/3289 1558/1560/3290 +f 1558/1560/3290 1557/1559/3291 1561/1563/3288 +f 1570/1572/3292 1571/1573/3292 1569/1571/3292 +f 1571/1573/3293 1570/1572/3294 1572/1574/3295 +f 1571/1573/3293 1572/1574/3295 1573/1575/3296 +f 1573/1575/3297 1572/1574/3297 1574/1576/3297 +f 1568/1570/3298 1570/1572/3299 1569/1571/3300 +f 1573/1575/3301 1574/1576/3301 1575/1577/3301 +f 1575/1577/3302 1574/1576/3302 1576/1578/3302 +f 1568/1570/3303 1567/1569/3304 1576/1578/3305 +f 1576/1578/3305 1567/1569/3304 1575/1577/3306 +f 1571/1573/3307 1567/1569/3308 1569/1571/3309 +f 1571/1573/3307 1573/1575/3310 1567/1569/3308 +f 1568/1570/3298 1576/1578/3026 1572/1574/3026 +f 1574/1576/3026 1572/1574/3026 1576/1578/3026 +f 1573/1575/3310 1575/1577/3031 1567/1569/3308 +f 1572/1574/3026 1570/1572/3299 1568/1570/3298 +f 1577/1579/3311 1578/1580/3312 1579/1581/3313 +f 1579/1581/3313 1578/1580/3312 1546/1548/3314 +f 1578/1580/3031 1577/1579/3031 1544/1546/3031 +f 1548/1550/3315 1580/1582/3316 1581/1583/3317 +f 1548/1550/3315 1581/1583/3317 1550/1552/3318 +f 1582/1584/3319 1543/1545/3320 1550/1552/3321 +f 1543/1545/3322 1582/1584/3323 1547/1549/3324 +f 1547/1549/3324 1582/1584/3323 1583/1585/3325 +f 1577/1579/3326 1579/1581/3327 1544/1546/3328 +f 1544/1546/3328 1579/1581/3327 1546/1548/3329 +f 1578/1580/3330 1544/1546/3330 1543/1545/3330 +f 1578/1580/3331 1543/1545/3332 1547/1549/3333 +f 1578/1580/3331 1547/1549/3333 1546/1548/3334 +f 1548/1550/3335 1583/1585/3336 1580/1582/3337 +f 1548/1550/3335 1547/1549/3338 1583/1585/3336 +f 1581/1583/3339 1582/1584/3319 1550/1552/3321 +f 1583/1585/3340 1582/1584/3340 1580/1582/3340 +f 1582/1584/3340 1581/1583/3340 1580/1582/3340 +f 1461/1463/3341 1460/1462/3341 1479/1481/3341 +f 1460/1462/3342 1459/1461/3343 1479/1481/3344 +f 1479/1481/3344 1459/1461/3343 1478/1480/3345 +f 1459/1461/3346 1462/1464/3347 1478/1480/3348 +f 1478/1480/3348 1462/1464/3347 1456/1458/3349 +f 1462/1464/3350 1457/1459/3350 1456/1458/3350 +f 1463/1465/3351 1458/1460/3351 1457/1459/3351 +f 1461/1463/3096 1480/1482/3098 1584/1586/3352 +f 1584/1586/3353 1480/1482/3353 1585/1587/3353 +f 1586/1588/3354 1587/1589/3354 1588/1590/3354 +f 1586/1588/3355 1588/1590/3355 1585/1587/3355 +f 1589/1591/3356 1587/1589/3356 1586/1588/3356 +f 1589/1591/3357 1590/1592/3358 1587/1589/3359 +f 1587/1589/3359 1590/1592/3358 1591/1593/3360 +f 1591/1593/3361 1590/1592/3361 1592/1594/3361 +f 1480/1482/3362 1593/1595/3363 1594/1596/3364 +f 1595/1597/3365 1585/1587/3366 1480/1482/3362 +f 1595/1597/3365 1480/1482/3362 1594/1596/3364 +f 1592/1594/3367 1589/1591/3368 1586/1588/3369 +f 1592/1594/3367 1590/1592/3370 1589/1591/3368 +f 1592/1594/3367 1586/1588/3369 1595/1597/3365 +f 1595/1597/3365 1586/1588/3369 1585/1587/3366 +f 1595/1597/3371 1596/1598/3371 1592/1594/3371 +f 1592/1594/3372 1596/1598/3372 1591/1593/3372 +f 1593/1595/3373 1466/1468/3373 1594/1596/3373 +f 1594/1596/3374 1466/1468/3374 1597/1599/3374 +f 1596/1598/3375 1595/1597/3375 1597/1599/3375 +f 1597/1599/3376 1595/1597/3376 1594/1596/3376 +f 1464/1466/3377 1466/1468/3377 1598/1600/3377 +f 1467/1469/3378 1464/1466/3379 1599/1601/3380 +f 1599/1601/3380 1464/1466/3379 1598/1600/3381 +f 1465/1467/3382 1600/1602/3382 1601/1603/3382 +f 1600/1602/3383 1465/1467/3384 1602/1604/3385 +f 1600/1602/3383 1602/1604/3385 1603/1605/3386 +f 1602/1604/3385 1604/1606/3387 1603/1605/3386 +f 1603/1605/3386 1604/1606/3387 1605/1607/3388 +f 1604/1606/3389 1467/1469/3390 1605/1607/3347 +f 1605/1607/3347 1467/1469/3390 1599/1601/3391 +f 1466/1468/3392 1599/1601/3393 1598/1600/3394 +f 1606/1608/3395 1463/1465/3396 1607/1609/3397 +f 1607/1609/3397 1463/1465/3396 1461/1463/3398 +f 1607/1609/3397 1461/1463/3398 1608/1610/3399 +f 1608/1610/3399 1461/1463/3398 1466/1468/3400 +f 1608/1610/3399 1466/1468/3400 1601/1603/3401 +f 1601/1603/3401 1466/1468/3400 1465/1467/3402 +f 1599/1601/3393 1466/1468/3392 1593/1595/3403 +f 1603/1605/3031 1605/1607/3031 1599/1601/3393 +f 1487/1489/3404 1483/1485/3026 1484/1486/3405 +f 1604/1606/3026 1602/1604/3026 1467/1469/3026 +f 1489/1491/3406 1487/1489/3404 1484/1486/3405 +f 1599/1601/3393 1600/1602/3031 1603/1605/3031 +f 1602/1604/3026 1465/1467/3083 1467/1469/3026 +f 1463/1465/3407 1606/1608/3407 1458/1460/3407 +f 1601/1603/3408 1600/1602/3409 1608/1610/3410 +f 1608/1610/3410 1600/1602/3409 1593/1595/3363 +f 1608/1610/3410 1593/1595/3363 1607/1609/3411 +f 1607/1609/3411 1593/1595/3363 1480/1482/3362 +f 1607/1609/3411 1480/1482/3362 1606/1608/3412 +f 1606/1608/3413 1480/1482/3413 1458/1460/3413 +f 1481/1483/3031 1488/1490/3414 1482/1484/3415 +f 1485/1487/3416 1474/1476/3417 1609/1611/3418 +f 1486/1488/3419 1474/1476/3417 1485/1487/3416 +f 1599/1601/3393 1593/1595/3403 1600/1602/3031 +f 1490/1492/3420 1482/1484/3415 1488/1490/3414 +f 1597/1599/3421 1461/1463/3398 1584/1586/3422 +f 1461/1463/3398 1597/1599/3421 1466/1468/3400 +f 1584/1586/3422 1596/1598/3423 1597/1599/3421 +f 1596/1598/3423 1584/1586/3422 1588/1590/3424 +f 1591/1593/3425 1588/1590/3424 1587/1589/3426 +f 1418/1420/2991 1417/1419/2990 1610/1612/3427 +f 1611/1613/3428 1612/1614/3429 1613/1615/3430 +f 1614/1616/3431 1611/1613/3428 1613/1615/3430 +f 1591/1593/3425 1596/1598/3423 1588/1590/3424 +f 1585/1587/3432 1588/1590/3432 1584/1586/3432 +f 1533/1535/3433 1527/1529/3189 1529/1531/3191 +f 1615/1617/3434 1540/1542/3434 1537/1539/3434 +f 1536/1538/3435 1540/1542/3435 1615/1617/3435 +f 1537/1539/3208 1536/1538/3207 1615/1617/3436 +f 1475/1477/3437 1609/1611/3437 1474/1476/3437 +f 1475/1477/3438 1477/1479/3439 1609/1611/3440 +f 1609/1611/3440 1477/1479/3439 1485/1487/3441 +f 1398/1400/3442 1397/1399/3443 1393/1395/3444 +f 1393/1395/3444 1396/1398/3445 1398/1400/3442 +f 1397/1399/3446 1394/1396/3446 1393/1395/3446 +f 1398/1400/3447 1396/1398/3447 1395/1397/3447 +f 1406/1408/3448 1401/1403/3448 1405/1407/3448 +f 1401/1403/3449 1406/1408/2978 1399/1401/2976 +f 1616/1618/3450 1617/1619/3451 1618/1620/3452 +f 1617/1619/3451 1616/1618/3450 1377/1379/3453 +f 1376/1378/3454 1375/1377/3455 1618/1620/3456 +f 1618/1620/3456 1617/1619/3457 1376/1378/3454 +f 1375/1377/3458 1380/1382/3459 1616/1618/3460 +f 1616/1618/3460 1618/1620/3461 1375/1377/3458 +f 1377/1379/3462 1376/1378/3462 1617/1619/3462 +f 1381/1383/3463 1379/1381/3464 1377/1379/3465 +f 1377/1379/3465 1616/1618/3466 1381/1383/3463 +f 1380/1382/3467 1381/1383/3463 1616/1618/3466 +f 1619/1621/3468 1330/1332/3469 1620/1622/3470 +f 1332/1334/3471 1621/1623/3468 1330/1332/3469 +f 1621/1623/3468 1620/1622/3470 1330/1332/3469 +f 1622/1624/3468 1623/1625/3472 1624/1626/3468 +f 1624/1626/3468 1330/1332/3469 1619/1621/3468 +f 1625/1627/3473 1626/1628/3474 1627/1629/3475 +f 1625/1627/3476 1627/1629/3477 1628/1630/3478 +f 1628/1630/3479 1629/1631/3480 1625/1627/3481 +f 1628/1630/3482 1630/1632/3483 1629/1631/3484 +f 1630/1632/3483 1628/1630/3482 1631/1633/3485 +f 1630/1632/3486 1631/1633/3487 1626/1628/3488 +f 1626/1628/3488 1632/1634/3489 1630/1632/3486 +f 1626/1628/3474 1625/1627/3473 1632/1634/3490 +f 1316/1318/3491 1632/1634/3490 1625/1627/3473 +f 1632/1634/3492 1316/1318/3492 1314/1316/3492 +f 1314/1316/3493 1630/1632/3486 1632/1634/3489 +f 1630/1632/3494 1314/1316/3494 1313/1315/3494 +f 1313/1315/3495 1629/1631/3484 1630/1632/3483 +f 1629/1631/3496 1313/1315/3496 1315/1317/3496 +f 1315/1317/3497 1625/1627/3481 1629/1631/3480 +f 1625/1627/3481 1315/1317/3497 1316/1318/3498 +f 1317/1319/3499 1627/1629/3475 1626/1628/3474 +f 1626/1628/3500 1318/1320/3500 1317/1319/3500 +f 1318/1320/3501 1626/1628/3488 1631/1633/3487 +f 1631/1633/3502 1319/1321/3502 1318/1320/3502 +f 1319/1321/3503 1631/1633/3485 1628/1630/3482 +f 1628/1630/3504 1320/1322/3504 1319/1321/3504 +f 1320/1322/3505 1628/1630/3478 1627/1629/3477 +f 1627/1629/3506 1317/1319/3506 1320/1322/3506 +f 1633/1635/3507 1634/1636/3508 1635/1637/3509 +f 1634/1636/3510 1633/1635/3511 1636/1638/3512 +f 1634/1636/3513 1636/1638/3514 1637/1639/3515 +f 1637/1639/3515 1638/1640/3516 1634/1636/3513 +f 1637/1639/3517 1639/1641/3518 1638/1640/3519 +f 1639/1641/3520 1637/1639/3520 1633/1635/3520 +f 1633/1635/3521 1635/1637/3522 1639/1641/3523 +f 1611/1613/3524 1639/1641/3523 1635/1637/3522 +f 1635/1637/3522 1612/1614/3525 1611/1613/3524 +f 1614/1616/3526 1638/1640/3519 1639/1641/3518 +f 1639/1641/3518 1611/1613/3527 1614/1616/3526 +f 1613/1615/3528 1634/1636/3513 1638/1640/3516 +f 1638/1640/3516 1614/1616/3529 1613/1615/3528 +f 1612/1614/3530 1635/1637/3509 1634/1636/3508 +f 1634/1636/3508 1613/1615/3531 1612/1614/3530 +f 1637/1639/3532 1636/1638/3532 1640/1642/3532 +f 1633/1635/3511 1641/1643/3533 1642/1644/3534 +f 1642/1644/3534 1636/1638/3512 1633/1635/3511 +f 1641/1643/3535 1633/1635/3535 1637/1639/3535 +f 1637/1639/3536 1643/1645/3536 1641/1643/3536 +f 1643/1645/3537 1637/1639/3537 1640/1642/3537 +f 1640/1642/3538 1644/1646/3538 1643/1645/3538 +f 1644/1646/3539 1640/1642/3539 1636/1638/3539 +f 1636/1638/3540 1642/1644/3540 1644/1646/3540 +f 1645/1647/3541 1610/1612/3542 1417/1419/3543 +f 1417/1419/3543 1646/1648/3544 1645/1647/3541 +f 1646/1648/3545 1417/1419/3545 1419/1421/3545 +f 1419/1421/3546 1647/1649/3547 1646/1648/3548 +f 1647/1649/3547 1419/1421/3546 1418/1420/3549 +f 1610/1612/3550 1645/1647/3551 1647/1649/3552 +f 1647/1649/3552 1418/1420/3553 1610/1612/3550 +f 1413/1415/3554 1648/1650/3555 1649/1651/3556 +f 1649/1651/3556 1416/1418/3557 1413/1415/3554 +f 1413/1415/3558 1650/1652/3559 1648/1650/3560 +f 1650/1652/3559 1413/1415/3558 1412/1414/3561 +f 1415/1417/3562 1651/1653/3563 1650/1652/3564 +f 1650/1652/3564 1412/1414/3565 1415/1417/3562 +f 1416/1418/3566 1649/1651/3567 1651/1653/3568 +f 1651/1653/3568 1415/1417/3569 1416/1418/3566 +f 1642/1644/3570 1643/1645/3571 1644/1646/3572 +f 1642/1644/3570 1641/1643/3573 1643/1645/3571 +f 1652/1654/3574 1647/1649/3574 1645/1647/3574 +f 1652/1654/3575 1646/1648/3575 1647/1649/3575 +f 1646/1648/3576 1652/1654/3576 1645/1647/3576 +f 1653/1655/3577 1649/1651/3578 1648/1650/3579 +f 1649/1651/3578 1653/1655/3577 1651/1653/3580 +f 1653/1655/3581 1650/1652/3581 1651/1653/3581 +f 1650/1652/3582 1653/1655/3582 1648/1650/3582 +f 1622/1624/98 1410/1412/98 1409/1411/98 +f 1409/1411/98 1623/1625/98 1622/1624/98 +f 1623/1625/3583 1408/1410/3584 1624/1626/3585 +f 1409/1411/3586 1408/1410/3584 1623/1625/3583 +f 1346/1348/3587 1624/1626/3585 1408/1410/3584 +f 1346/1348/3588 1330/1332/3588 1624/1626/3588 +f 1346/1348/3589 1331/1333/3589 1330/1332/3589 +f 1348/1350/3590 1331/1333/3590 1346/1348/3590 +f 1352/1354/3591 1332/1334/3592 1338/1340/3593 +f 1347/1349/3594 1332/1334/3592 1352/1354/3591 +f 1347/1349/3594 1621/1623/3595 1332/1334/3592 +f 1336/1338/3596 1621/1623/3595 1347/1349/3594 +f 1336/1338/3596 1310/1312/3597 1621/1623/3595 +f 1311/1313/3598 1310/1312/3597 1336/1338/3596 +f 1352/1354/3599 1331/1333/3600 1348/1350/3601 +f 1338/1340/3602 1331/1333/3600 1352/1354/3599 +f 1369/1371/3603 1367/1369/3604 1341/1343/3605 +f 1340/1342/3606 1369/1371/3603 1341/1343/3605 +f 1341/1343/3605 1367/1369/3604 1366/1368/3607 +f 1312/1314/3608 1620/1622/3609 1621/1623/3610 +f 1621/1623/3610 1310/1312/2943 1312/1314/3608 +f 1620/1622/3611 1309/1311/3612 1337/1339/3613 +f 1312/1314/3614 1309/1311/3614 1620/1622/3614 +f 1337/1339/3613 1619/1621/3615 1620/1622/3611 +f 1411/1413/3616 1619/1621/3617 1337/1339/3618 +f 1619/1621/3617 1410/1412/3619 1622/1624/3620 +f 1411/1413/3616 1410/1412/3619 1619/1621/3617 +f 1619/1621/3468 1622/1624/3468 1624/1626/3468 +f 1351/1353/2836 1354/1356/2846 1356/1358/3621 +f 1356/1358/3621 1354/1356/2846 1328/1330/3622 +f 1368/1370/3623 1329/1331/3624 1345/1347/3625 +f 1364/1366/3626 1368/1370/3623 1345/1347/3625 +f 1364/1366/3626 1365/1367/3627 1368/1370/3623 +f 1368/1370/3623 1370/1372/3628 1329/1331/3624 +f 1366/1368/3607 1364/1366/3629 1341/1343/3605 +f 1654/1656/3630 1655/1657/3631 1656/1658/3632 +f 1657/1659/3633 1658/1660/3634 1659/1661/3635 +f 1659/1661/3635 1658/1660/3634 1655/1657/3631 +f 1659/1661/3635 1655/1657/3631 1654/1656/3630 +f 1656/1658/3632 1660/1662/3636 1661/1663/3637 +f 1662/1664/3638 1663/1665/3639 1654/1656/3630 +f 1656/1658/3632 1664/1666/3640 1654/1656/3630 +f 1654/1656/3630 1664/1666/3640 1662/1664/3638 +f 1661/1663/3637 1664/1666/3640 1656/1658/3632 +f 1665/1667/3639 1657/1659/3633 1659/1661/3635 +f 1666/1668/3641 1667/1669/3642 1660/1662/3636 +f 1660/1662/3636 1667/1669/3642 1661/1663/3637 +f 1657/1659/3633 1665/1667/3639 1666/1668/3641 +f 1666/1668/3641 1665/1667/3639 1663/1665/3639 +f 1662/1664/3638 1667/1669/3642 1663/1665/3639 +f 1663/1665/3639 1667/1669/3642 1666/1668/3641 +f 1660/1662/3643 1656/1658/3644 1668/1670/3645 +f 1668/1670/3645 1656/1658/3644 1669/1671/3646 +f 1670/1672/3647 1671/1673/3648 1672/1674/3649 +f 1672/1674/3649 1669/1671/3650 1670/1672/3647 +f 1673/1675/3651 1670/1672/3647 1674/1676/3652 +f 1673/1675/3651 1674/1676/3652 1675/1677/3653 +f 1674/1676/3652 1670/1672/3647 1669/1671/3650 +f 1676/1678/3654 1677/1679/3655 1673/1675/3651 +f 1673/1675/3651 1677/1679/3655 1670/1672/3647 +f 1668/1670/3656 1671/1673/3648 1676/1678/3654 +f 1677/1679/3655 1676/1678/3654 1678/1680/3657 +f 1668/1670/3656 1669/1671/3650 1679/1681/3656 +f 1671/1673/3648 1668/1670/3656 1679/1681/3656 +f 1669/1671/3650 1672/1674/3649 1679/1681/3656 +f 1671/1673/3648 1678/1680/3657 1676/1678/3654 +f 1671/1673/3648 1670/1672/3647 1678/1680/3657 +f 1680/1682/3658 1681/1683/2943 1682/1684/3659 +f 1669/1671/3646 1656/1658/3644 1674/1676/3660 +f 1674/1676/3660 1656/1658/3644 1655/1657/3661 +f 1682/1684/3659 1681/1683/2943 1683/1685/3662 +f 1682/1684/3659 1683/1685/3662 1655/1657/3661 +f 1655/1657/3661 1683/1685/3662 1674/1676/3660 +f 1684/1686/3663 1680/1682/3664 1682/1684/3665 +f 1684/1686/3666 1682/1684/3667 1658/1660/3668 +f 1658/1660/3668 1682/1684/3667 1655/1657/3669 +f 1685/1687/3670 1686/1688/3671 1684/1686/3672 +f 1657/1659/3673 1673/1675/3674 1658/1660/3675 +f 1658/1660/3675 1673/1675/3674 1675/1677/3676 +f 1658/1660/3675 1675/1677/3676 1684/1686/3672 +f 1684/1686/3672 1675/1677/3676 1685/1687/3670 +f 1673/1675/3674 1657/1659/3673 1676/1678/3677 +f 1676/1678/3677 1657/1659/3673 1666/1668/3678 +f 1675/1677/3679 1674/1676/3679 1683/1685/3679 +f 1675/1677/3680 1683/1685/3681 1685/1687/3682 +f 1685/1687/3682 1683/1685/3681 1681/1683/3683 +f 1681/1683/3684 1680/1682/3685 1685/1687/3686 +f 1685/1687/3686 1680/1682/3685 1686/1688/3687 +f 1686/1688/3688 1680/1682/3664 1684/1686/3663 +f 1676/1678/3689 1666/1668/3690 1668/1670/3691 +f 1668/1670/3691 1666/1668/3690 1660/1662/3692 +f 1667/1669/3693 1671/1673/3694 1661/1663/3695 +f 1661/1663/3695 1671/1673/3694 1679/1681/3696 +f 1661/1663/3697 1679/1681/3697 1664/1666/3697 +f 1664/1666/3698 1679/1681/3698 1672/1674/3698 +f 1664/1666/3699 1672/1674/3699 1662/1664/3699 +f 1662/1664/3700 1672/1674/3700 1671/1673/3700 +f 1662/1664/3701 1671/1673/3701 1667/1669/3701 +f 1663/1665/3702 1678/1680/3703 1670/1672/3704 +f 1663/1665/3702 1670/1672/3704 1654/1656/3705 +f 1654/1656/3706 1670/1672/3706 1659/1661/3706 +f 1659/1661/3707 1670/1672/3707 1677/1679/3707 +f 1659/1661/3708 1677/1679/3708 1665/1667/3708 +f 1665/1667/3709 1677/1679/3710 1663/1665/3711 +f 1663/1665/3711 1677/1679/3710 1678/1680/3712 +f 1687/1689/3713 1688/1690/3714 1689/1691/3715 +f 1690/1692/3716 1687/1689/3713 1689/1691/3715 +f 1691/1693/3717 1692/1694/3717 1693/1695/3717 +f 1692/1694/3718 1694/1696/3718 1693/1695/3718 +f 1694/1696/3719 1695/1697/3719 1693/1695/3719 +f 1695/1697/3720 1691/1693/3720 1693/1695/3720 +f 1696/1698/3721 1697/1699/3722 1698/1700/3723 +f 1697/1699/3722 1699/1701/3724 1698/1700/3723 +f 1700/1702/3725 1698/1700/3723 1699/1701/3724 +f 1700/1702/3726 1696/1698/3726 1698/1700/3726 +f 1701/1703/3727 1702/1704/3728 1703/1705/3729 +f 1704/1706/3730 1705/1707/3731 1706/1708/3732 +f 1706/1708/3732 1705/1707/3731 1702/1704/3728 +f 1706/1708/3732 1702/1704/3728 1701/1703/3727 +f 1703/1705/3729 1707/1709/3733 1708/1710/3734 +f 1709/1711/3735 1710/1712/3736 1701/1703/3727 +f 1703/1705/3729 1709/1711/3735 1701/1703/3727 +f 1709/1711/3735 1703/1705/3729 1708/1710/3734 +f 1711/1713/3737 1704/1706/3730 1706/1708/3732 +f 1712/1714/3738 1713/1715/3739 1707/1709/3733 +f 1713/1715/3739 1708/1710/3734 1707/1709/3733 +f 1704/1706/3730 1711/1713/3737 1712/1714/3738 +f 1711/1713/3737 1710/1712/3736 1712/1714/3738 +f 1710/1712/3736 1709/1711/3735 1713/1715/3739 +f 1710/1712/3736 1713/1715/3739 1712/1714/3738 +f 1707/1709/3740 1703/1705/3741 1714/1716/3742 +f 1714/1716/3742 1703/1705/3741 1715/1717/3743 +f 1716/1718/3744 1717/1719/3745 1718/1720/3746 +f 1719/1721/3747 1720/1722/3748 1721/1723/3749 +f 1719/1721/3747 1721/1723/3749 1722/1724/3750 +f 1721/1723/3749 1720/1722/3748 1717/1719/3745 +f 1717/1719/3745 1720/1722/3748 1718/1720/3746 +f 1723/1725/3751 1724/1726/3752 1719/1721/3747 +f 1714/1716/3753 1725/1727/3754 1723/1725/3751 +f 1717/1719/3745 1716/1718/3744 1726/1728/3755 +f 1724/1726/3752 1723/1725/3751 1727/1729/3756 +f 1714/1716/3753 1715/1717/3757 1726/1728/3755 +f 1720/1722/3748 1719/1721/3747 1724/1726/3752 +f 1726/1728/3755 1715/1717/3757 1717/1719/3745 +f 1714/1716/3753 1726/1728/3755 1725/1727/3754 +f 1725/1727/3754 1718/1720/3746 1723/1725/3751 +f 1718/1720/3746 1727/1729/3756 1723/1725/3751 +f 1725/1727/3754 1716/1718/3744 1718/1720/3746 +f 1703/1705/3758 1717/1719/3758 1715/1717/3758 +f 1717/1719/3759 1703/1705/3759 1721/1723/3759 +f 1721/1723/3760 1703/1705/3761 1702/1704/3762 +f 1702/1704/3762 1728/1730/3763 1721/1723/3760 +f 1729/1731/3764 1728/1730/3763 1702/1704/3762 +f 1730/1732/3765 1729/1731/3765 1702/1704/3765 +f 1730/1732/3766 1702/1704/3766 1705/1707/3766 +f 1731/1733/3767 1732/1734/3768 1730/1732/3769 +f 1704/1706/3770 1719/1721/3771 1705/1707/3772 +f 1705/1707/3772 1719/1721/3771 1722/1724/3773 +f 1705/1707/3772 1722/1724/3773 1730/1732/3769 +f 1730/1732/3769 1722/1724/3773 1731/1733/3767 +f 1719/1721/3771 1704/1706/3770 1723/1725/3774 +f 1723/1725/3774 1704/1706/3770 1712/1714/3775 +f 1722/1724/3776 1721/1723/3777 1728/1730/3778 +f 1722/1724/3776 1728/1730/3778 1731/1733/3779 +f 1728/1730/3780 1729/1731/3781 1731/1733/3782 +f 1731/1733/3782 1729/1731/3781 1732/1734/3783 +f 1732/1734/3784 1729/1731/3784 1730/1732/3784 +f 1723/1725/3785 1712/1714/3786 1714/1716/3787 +f 1714/1716/3787 1712/1714/3786 1707/1709/3788 +f 1708/1710/3789 1725/1727/3789 1726/1728/3789 +f 1708/1710/3790 1726/1728/3790 1709/1711/3790 +f 1709/1711/3791 1726/1728/3791 1716/1718/3791 +f 1709/1711/3792 1716/1718/3792 1713/1715/3792 +f 1713/1715/3793 1716/1718/3793 1725/1727/3793 +f 1713/1715/3794 1725/1727/3794 1708/1710/3794 +f 1710/1712/3795 1727/1729/3795 1718/1720/3795 +f 1710/1712/3796 1718/1720/3796 1701/1703/3796 +f 1701/1703/3797 1718/1720/3797 1720/1722/3797 +f 1701/1703/3798 1720/1722/3798 1706/1708/3798 +f 1706/1708/3799 1720/1722/3799 1724/1726/3799 +f 1706/1708/3800 1724/1726/3800 1711/1713/3800 +f 1711/1713/3801 1724/1726/3802 1727/1729/3803 +f 1711/1713/3801 1727/1729/3803 1710/1712/3804 +f 1733/1735/629 1734/1736/603 1735/1737/629 +f 1736/1738/603 1737/1739/629 1734/1736/603 +f 1737/1739/629 1735/1737/629 1734/1736/603 +f 1738/1740/629 1739/1741/3805 1734/1736/603 +f 1740/1742/3806 1736/1738/603 1734/1736/603 +f 1733/1735/629 1738/1740/629 1734/1736/603 +f 1741/1743/3807 1742/1744/3807 1743/1745/3807 +f 1744/1746/3808 1745/1747/3808 1743/1745/3808 +f 1744/1746/3809 1743/1745/3809 1742/1744/3809 +f 1746/1748/3810 1745/1747/3810 1744/1746/3810 +f 1741/1743/3811 1745/1747/3812 1747/1749/3813 +f 1747/1749/3813 1748/1750/3814 1741/1743/3811 +f 1742/1744/3815 1746/1748/3816 1744/1746/3817 +f 1742/1744/3815 1747/1749/3818 1746/1748/3816 +f 1741/1743/3811 1743/1745/3819 1745/1747/3812 +f 1746/1748/3820 1747/1749/3820 1745/1747/3820 +f 1742/1744/3821 1741/1743/3811 1748/1750/3814 +f 1749/1751/3822 1750/1752/3823 1751/1753/3824 +f 1752/1754/3825 1753/1755/3826 1754/1756/3827 +f 1754/1756/3827 1755/1757/3828 1752/1754/3825 +f 1756/1758/3829 1755/1757/3830 1754/1756/3831 +f 1754/1756/3831 1757/1759/3832 1756/1758/3829 +f 1758/1760/3833 1759/1761/3834 1760/1762/3835 +f 1758/1760/3833 1760/1762/3835 1761/1763/3836 +f 1758/1760/3833 1761/1763/3836 1762/1764/3837 +f 1760/1762/3838 1759/1761/3839 1750/1752/3840 +f 1750/1752/3840 1759/1761/3839 1751/1753/3841 +f 1762/1764/3842 1761/1763/3843 1763/1765/3844 +f 1763/1765/3844 1761/1763/3843 1764/1766/3845 +f 1750/1752/3823 1749/1751/3822 1764/1766/3846 +f 1764/1766/3846 1749/1751/3822 1763/1765/3847 +f 1759/1761/3848 1749/1751/3849 1751/1753/3850 +f 1749/1751/3849 1759/1761/3848 1758/1760/3851 +f 1758/1760/3851 1762/1764/3852 1763/1765/3852 +f 1764/1766/3853 1761/1763/3819 1760/1762/3838 +f 1750/1752/3840 1764/1766/3853 1760/1762/3838 +f 1758/1760/3851 1763/1765/3852 1749/1751/3849 +f 1765/1767/3854 1766/1768/3855 1767/1769/3856 +f 1767/1769/3856 1766/1768/3855 1768/1770/3857 +f 1766/1768/3858 1765/1767/3858 1769/1771/3858 +f 1770/1772/3859 1771/1773/3860 1772/1774/3861 +f 1770/1772/3859 1772/1774/3861 1773/1775/3862 +f 1774/1776/3863 1775/1777/3864 1773/1775/3865 +f 1775/1777/3866 1774/1776/3867 1776/1778/3867 +f 1776/1778/3867 1774/1776/3867 1777/1779/3868 +f 1765/1767/3869 1767/1769/3870 1769/1771/3871 +f 1769/1771/3871 1767/1769/3870 1768/1770/3872 +f 1766/1768/3873 1769/1771/3873 1775/1777/3873 +f 1766/1768/3874 1775/1777/3875 1776/1778/3876 +f 1766/1768/3874 1776/1778/3876 1768/1770/3877 +f 1770/1772/3878 1777/1779/3879 1771/1773/3880 +f 1770/1772/3878 1776/1778/3881 1777/1779/3879 +f 1772/1774/3882 1774/1776/3863 1773/1775/3865 +f 1777/1779/3883 1774/1776/3883 1771/1773/3883 +f 1774/1776/3883 1772/1774/3883 1771/1773/3883 +f 1778/1780/3884 1779/1781/3884 1780/1782/3884 +f 1779/1781/3885 1781/1783/3886 1780/1782/3887 +f 1780/1782/3887 1781/1783/3886 1782/1784/3888 +f 1781/1783/3889 1783/1785/3890 1782/1784/3891 +f 1782/1784/3891 1783/1785/3890 1784/1786/3892 +f 1783/1785/3893 1785/1787/3893 1784/1786/3893 +f 1786/1788/3894 1787/1789/3894 1785/1787/3894 +f 1778/1780/3895 1788/1790/3896 1789/1791/3897 +f 1778/1780/3895 1789/1791/3897 1790/1792/3898 +f 1791/1793/3899 1792/1794/3899 1793/1795/3899 +f 1791/1793/3900 1793/1795/3900 1794/1796/3900 +f 1795/1797/3901 1792/1794/3901 1791/1793/3901 +f 1795/1797/3902 1796/1798/3903 1792/1794/3904 +f 1792/1794/3904 1796/1798/3903 1797/1799/3905 +f 1788/1790/3906 1798/1800/3907 1799/1801/3908 +f 1800/1802/3909 1789/1791/3910 1799/1801/3908 +f 1799/1801/3908 1789/1791/3910 1788/1790/3906 +f 1789/1791/3910 1800/1802/3909 1801/1803/3911 +f 1801/1803/3911 1794/1796/3912 1789/1791/3910 +f 1796/1798/3913 1795/1797/3914 1791/1793/3915 +f 1796/1798/3913 1791/1793/3915 1801/1803/3911 +f 1801/1803/3911 1791/1793/3915 1794/1796/3912 +f 1801/1803/3916 1802/1804/3917 1796/1798/3918 +f 1796/1798/3918 1802/1804/3917 1797/1799/3919 +f 1802/1804/3920 1801/1803/3921 1800/1802/3922 +f 1798/1800/3923 1803/1805/3923 1799/1801/3923 +f 1799/1801/3924 1803/1805/3924 1804/1806/3924 +f 1802/1804/3920 1800/1802/3922 1804/1806/3925 +f 1804/1806/3926 1800/1802/3926 1799/1801/3926 +f 1805/1807/3927 1803/1805/3927 1806/1808/3927 +f 1807/1809/3928 1805/1807/3929 1808/1810/3930 +f 1808/1810/3930 1805/1807/3929 1806/1808/3931 +f 1809/1811/3932 1810/1812/3932 1811/1813/3932 +f 1810/1812/3933 1809/1811/3933 1812/1814/3933 +f 1812/1814/3934 1809/1811/3934 1813/1815/3934 +f 1813/1815/3935 1814/1816/3936 1812/1814/3937 +f 1812/1814/3937 1814/1816/3936 1815/1817/3938 +f 1814/1816/3939 1807/1809/3940 1815/1817/3941 +f 1815/1817/3941 1807/1809/3940 1808/1810/3942 +f 1803/1805/3943 1808/1810/3944 1806/1808/3945 +f 1813/1815/3853 1809/1811/3946 1807/1809/3853 +f 1816/1818/3947 1786/1788/3948 1817/1819/3949 +f 1817/1819/3949 1786/1788/3948 1778/1780/3950 +f 1817/1819/3949 1778/1780/3950 1818/1820/3951 +f 1818/1820/3951 1778/1780/3950 1803/1805/3952 +f 1818/1820/3951 1803/1805/3952 1811/1813/3953 +f 1811/1813/3953 1803/1805/3952 1809/1811/3954 +f 1808/1810/3944 1810/1812/3955 1812/1814/3956 +f 1808/1810/3944 1803/1805/3943 1798/1800/3957 +f 1812/1814/3956 1815/1817/3852 1808/1810/3944 +f 1739/1741/3958 1819/1821/3853 1820/1822/3959 +f 1814/1816/3960 1813/1815/3853 1807/1809/3853 +f 1734/1736/3961 1739/1741/3958 1820/1822/3959 +f 1786/1788/3962 1816/1818/3962 1787/1789/3962 +f 1811/1813/3963 1810/1812/3964 1818/1820/3965 +f 1818/1820/3965 1810/1812/3964 1798/1800/3907 +f 1818/1820/3965 1798/1800/3907 1817/1819/3966 +f 1817/1819/3966 1798/1800/3907 1788/1790/3906 +f 1817/1819/3966 1788/1790/3906 1816/1818/3967 +f 1816/1818/3968 1788/1790/3968 1787/1789/3968 +f 1821/1823/3955 1822/1824/3969 1823/1825/3970 +f 1738/1740/3971 1733/1735/3972 1824/1826/3973 +f 1738/1740/3971 1824/1826/3973 1825/1827/3974 +f 1808/1810/3944 1798/1800/3957 1810/1812/3955 +f 1826/1828/3975 1823/1825/3970 1822/1824/3969 +f 1804/1806/3976 1778/1780/3950 1790/1792/3977 +f 1778/1780/3950 1804/1806/3976 1803/1805/3952 +f 1790/1792/3977 1802/1804/3978 1804/1806/3976 +f 1802/1804/3978 1790/1792/3977 1793/1795/3979 +f 1797/1799/3980 1793/1795/3979 1792/1794/3981 +f 1797/1799/3980 1802/1804/3978 1793/1795/3979 +f 1794/1796/3982 1793/1795/3983 1790/1792/3984 +f 1794/1796/3982 1790/1792/3984 1789/1791/3985 +f 1827/1829/3986 1828/1830/3986 1829/1831/3986 +f 1827/1829/3987 1830/1832/3987 1828/1830/3987 +f 1831/1833/3988 1832/1834/3988 1833/1835/3988 +f 1834/1836/3989 1831/1833/3990 1833/1835/3991 +f 1835/1837/3992 1834/1836/3989 1833/1835/3991 +f 1835/1837/3993 1833/1835/3993 1832/1834/3993 +f 1836/1838/3994 1837/1839/3995 1824/1826/3996 +f 1824/1826/3996 1837/1839/3995 1825/1827/3997 +f 1784/1786/3998 1785/1787/3999 1787/1789/4000 +f 1781/1783/4001 1779/1781/4002 1778/1780/4003 +f 1785/1787/4004 1783/1785/4005 1781/1783/4001 +f 1785/1787/4004 1781/1783/4001 1786/1788/4006 +f 1781/1783/4001 1778/1780/4003 1786/1788/4006 +f 1805/1807/4007 1809/1811/3946 1803/1805/4008 +f 1807/1809/3853 1809/1811/3946 1805/1807/4007 +f 1838/1840/4009 1839/1841/4010 1840/1842/4011 +f 1735/1737/4012 1737/1739/4013 1838/1840/4014 +f 1838/1840/4014 1737/1739/4013 1839/1841/4015 +f 1735/1737/4012 1838/1840/4014 1733/1735/4016 +f 1733/1735/4017 1838/1840/4017 1841/1843/4017 +f 1836/1838/4018 1824/1826/4018 1841/1843/4018 +f 1841/1843/4019 1824/1826/4019 1733/1735/4019 +f 1842/1844/4020 1837/1839/4021 1836/1838/4022 +f 1836/1838/4022 1841/1843/4023 1842/1844/4020 +f 1787/1789/4000 1782/1784/4024 1784/1786/3998 +f 1778/1780/3895 1780/1782/4025 1787/1789/4000 +f 1780/1782/4025 1782/1784/4024 1787/1789/4000 +f 1787/1789/4000 1788/1790/3896 1778/1780/3895 +f 1821/1823/4026 1823/1825/4027 1819/1821/4028 +f 1819/1821/4028 1823/1825/4027 1820/1822/4029 +f 1825/1827/4030 1837/1839/4031 1738/1740/4032 +f 1738/1740/4032 1837/1839/4031 1842/1844/4033 +f 1738/1740/4032 1842/1844/4033 1739/1741/4034 +f 1739/1741/4034 1842/1844/4033 1822/1824/4035 +f 1739/1741/4034 1822/1824/4035 1819/1821/4036 +f 1819/1821/4036 1822/1824/4035 1821/1823/4037 +f 1820/1822/4038 1823/1825/4038 1734/1736/4038 +f 1734/1736/4039 1823/1825/4039 1826/1828/4039 +f 1734/1736/4040 1826/1828/4040 1840/1842/4040 +f 1734/1736/4041 1840/1842/4042 1740/1742/4043 +f 1736/1738/4044 1740/1742/4043 1843/1845/4045 +f 1843/1845/4045 1740/1742/4043 1840/1842/4042 +f 1839/1841/98 1737/1739/98 1736/1738/98 +f 1736/1738/98 1843/1845/98 1839/1841/98 +f 1844/1846/4046 1845/1847/4047 1846/1848/4048 +f 1847/1849/4049 1848/1850/4050 1845/1847/4047 +f 1847/1849/4049 1845/1847/4047 1844/1846/4046 +f 1847/1849/4049 1849/1851/4051 1848/1850/4050 +f 1847/1849/4049 1850/1852/4052 1849/1851/4051 +f 1844/1846/4046 1851/1853/4053 1847/1849/4049 +f 1847/1849/4049 1851/1853/4053 1850/1852/4052 +f 1844/1846/4046 1846/1848/4048 1851/1853/4053 +f 1852/1854/4054 1853/1855/4055 1854/1856/4056 +f 1855/1857/4057 1853/1855/4055 1852/1854/4054 +f 1856/1858/4058 1852/1854/4059 1854/1856/4060 +f 1856/1858/4058 1854/1856/4060 1857/1859/4061 +f 1857/1859/4062 1854/1856/4062 1853/1855/4062 +f 1857/1859/4063 1853/1855/4064 1858/1860/4065 +f 1858/1860/4065 1853/1855/4064 1859/1861/4066 +f 1858/1860/4067 1859/1861/4068 1860/1862/4069 +f 1860/1862/4069 1859/1861/4068 1855/1857/4070 +f 1860/1862/4071 1855/1857/4071 1852/1854/4071 +f 1860/1862/4072 1852/1854/4072 1856/1858/4072 +f 1848/1850/4073 1856/1858/4074 1857/1859/4075 +f 1848/1850/4073 1857/1859/4075 1845/1847/4076 +f 1845/1847/4077 1857/1859/4078 1846/1848/4079 +f 1846/1848/4079 1857/1859/4078 1858/1860/4080 +f 1846/1848/4081 1858/1860/4081 1851/1853/4081 +f 1851/1853/4082 1858/1860/4083 1860/1862/4084 +f 1851/1853/4082 1860/1862/4084 1850/1852/4085 +f 1850/1852/4086 1860/1862/4087 1849/1851/4088 +f 1849/1851/4088 1860/1862/4087 1856/1858/4089 +f 1849/1851/4090 1856/1858/4090 1848/1850/4090 +f 1859/1861/4091 1853/1855/4055 1855/1857/4057 +f 1861/1863/4092 1862/1864/4093 1863/1865/4094 +f 1864/1866/4095 1865/1867/4096 1863/1865/4094 +f 1863/1865/4094 1865/1867/4096 1861/1863/4092 +f 1864/1866/4095 1866/1868/4097 1865/1867/4096 +f 1863/1865/4094 1867/1869/4098 1864/1866/4095 +f 1864/1866/4095 1867/1869/4098 1868/1870/4099 +f 1863/1865/4094 1862/1864/4093 1867/1869/4098 +f 1864/1866/4095 1868/1870/4099 1866/1868/4097 +f 1869/1871/4100 1870/1872/4101 1871/1873/4102 +f 1869/1871/4100 1872/1874/4103 1870/1872/4101 +f 1873/1875/4104 1869/1871/4104 1874/1876/4104 +f 1874/1876/4105 1869/1871/4105 1871/1873/4105 +f 1874/1876/4106 1871/1873/4106 1875/1877/4106 +f 1875/1877/4107 1871/1873/4107 1870/1872/4107 +f 1875/1877/4108 1870/1872/4108 1876/1878/4108 +f 1876/1878/4109 1870/1872/4109 1872/1874/4109 +f 1876/1878/4110 1872/1874/4111 1869/1871/4112 +f 1876/1878/4110 1869/1871/4112 1873/1875/4113 +f 1866/1868/4114 1873/1875/4114 1865/1867/4114 +f 1865/1867/4115 1873/1875/4116 1874/1876/4117 +f 1865/1867/4115 1874/1876/4117 1861/1863/4118 +f 1861/1863/4119 1874/1876/4120 1875/1877/4121 +f 1861/1863/4119 1875/1877/4121 1862/1864/4122 +f 1862/1864/4123 1875/1877/4124 1867/1869/4125 +f 1867/1869/4125 1875/1877/4124 1876/1878/4126 +f 1867/1869/4127 1876/1878/4127 1868/1870/4127 +f 1868/1870/4128 1876/1878/4129 1866/1868/4130 +f 1866/1868/4130 1876/1878/4129 1873/1875/4131 +f 1877/1879/4132 1878/1880/4133 1879/1881/4134 +f 1880/1882/4135 1881/1883/4136 1882/1884/4137 +f 1882/1884/4137 1878/1880/4133 1877/1879/4132 +f 1882/1884/4137 1881/1883/4136 1878/1880/4133 +f 1877/1879/4132 1879/1881/4134 1883/1885/4138 +f 1877/1879/4132 1883/1885/4138 1882/1884/4137 +f 1882/1884/4137 1883/1885/4138 1880/1882/4135 +f 1884/1886/4139 1885/1887/4140 1886/1888/4141 +f 1886/1888/4141 1887/1889/4142 1884/1886/4139 +f 1888/1890/4143 1886/1888/4144 1885/1887/4145 +f 1888/1890/4143 1885/1887/4145 1889/1891/4146 +f 1889/1891/4147 1885/1887/4148 1890/1892/4149 +f 1890/1892/4149 1885/1887/4148 1884/1886/4150 +f 1890/1892/4151 1884/1886/4152 1887/1889/4153 +f 1890/1892/4151 1887/1889/4153 1891/1893/4154 +f 1891/1893/4155 1887/1889/4156 1888/1890/4157 +f 1888/1890/4157 1887/1889/4156 1886/1888/4158 +f 1880/1882/4159 1888/1890/4160 1881/1883/4161 +f 1881/1883/4161 1888/1890/4160 1889/1891/4162 +f 1881/1883/4161 1889/1891/4162 1878/1880/4163 +f 1878/1880/4164 1889/1891/4165 1890/1892/4166 +f 1878/1880/4164 1890/1892/4166 1879/1881/4167 +f 1879/1881/4168 1890/1892/4169 1883/1885/4170 +f 1883/1885/4170 1890/1892/4169 1891/1893/4171 +f 1883/1885/4172 1891/1893/4173 1880/1882/4174 +f 1880/1882/4174 1891/1893/4173 1888/1890/4175 +f 1892/1894/4176 1893/1895/4176 1894/1896/4176 +f 1892/1894/4177 1894/1896/4177 1895/1897/4177 +f 1895/1897/4178 1894/1896/4178 1896/1898/4178 +f 1895/1897/4179 1896/1898/4179 1897/1899/4179 +f 1897/1899/4180 1896/1898/4180 1898/1900/4180 +f 1897/1899/4181 1898/1900/4181 1899/1901/4181 +f 1899/1901/4182 1898/1900/4182 1900/1902/4182 +f 1899/1901/4183 1900/1902/4183 1901/1903/4183 +f 1901/1903/4184 1900/1902/4184 1893/1895/4184 +f 1901/1903/4185 1893/1895/4185 1892/1894/4185 +f 1902/1904/4186 1892/1894/4187 1903/1905/4188 +f 1904/1906/2171 1899/1901/4189 1901/1903/4190 +f 1904/1906/2171 1901/1903/4190 1902/1904/4186 +f 1905/1907/4191 1897/1899/4191 1904/1906/2171 +f 1904/1906/2171 1897/1899/4191 1899/1901/4189 +f 1902/1904/4186 1901/1903/4190 1892/1894/4187 +f 1903/1905/4188 1895/1897/4192 1905/1907/4191 +f 1905/1907/4191 1895/1897/4192 1897/1899/4191 +f 1903/1905/4188 1892/1894/4187 1895/1897/4192 +f 1902/1904/4193 1906/1908/4193 1907/1909/4193 +f 1902/1904/4194 1907/1909/4195 1908/1910/4196 +f 1908/1910/4196 1904/1906/4197 1902/1904/4194 +f 1909/1911/4198 1904/1906/4198 1908/1910/4198 +f 1904/1906/4199 1909/1911/4200 1910/1912/4201 +f 1904/1906/4199 1910/1912/4201 1905/1907/4202 +f 1905/1907/4203 1910/1912/4204 1911/1913/4205 +f 1905/1907/4206 1911/1913/4207 1912/1914/4208 +f 1912/1914/4208 1903/1905/4209 1905/1907/4206 +f 1913/1915/4210 1903/1905/4210 1912/1914/4210 +f 1903/1905/4211 1913/1915/4212 1902/1904/4213 +f 1902/1904/4213 1913/1915/4212 1906/1908/4214 +f 1910/1912/4204 1914/1916/4215 1911/1913/4205 +f 1909/1911/4216 1914/1916/4216 1910/1912/4216 +f 1906/1908/4217 1915/1917/4217 1907/1909/4217 +f 1909/1911/4218 1908/1910/4219 1914/1916/4215 +f 1907/1909/4220 1915/1917/4221 1908/1910/4219 +f 1911/1913/4205 1916/1918/4222 1912/1914/4223 +f 1912/1914/4223 1916/1918/4222 1913/1915/4224 +f 1913/1915/4224 1916/1918/4222 1906/1908/4225 +f 1908/1910/4219 1915/1917/4221 1914/1916/4215 +f 1911/1913/4205 1914/1916/4215 1916/1918/4222 +f 1906/1908/4225 1916/1918/4222 1915/1917/4226 +f 1914/1916/4215 1915/1917/4221 1916/1918/4222 +f 1917/1919/4227 1918/1920/4227 1919/1921/4227 +f 1917/1919/4228 1919/1921/4228 1920/1922/4228 +f 1920/1922/4229 1919/1921/4229 1921/1923/4229 +f 1920/1922/4230 1921/1923/4230 1922/1924/4230 +f 1922/1924/4231 1921/1923/4231 1923/1925/4231 +f 1922/1924/4232 1923/1925/4232 1924/1926/4232 +f 1924/1926/4233 1923/1925/4233 1925/1927/4233 +f 1924/1926/4234 1925/1927/4234 1926/1928/4234 +f 1926/1928/4235 1925/1927/4235 1918/1920/4235 +f 1926/1928/4236 1918/1920/4236 1917/1919/4236 +f 1927/1929/4237 1926/1928/4187 1917/1919/4238 +f 1927/1929/4237 1917/1919/4238 1928/1930/4239 +f 1929/1931/4240 1922/1924/4241 1924/1926/4242 +f 1929/1931/4240 1924/1926/4242 1930/1932/4243 +f 1924/1926/4242 1926/1928/4187 1930/1932/4243 +f 1930/1932/4243 1926/1928/4187 1927/1929/4237 +f 1929/1931/4240 1920/1922/4244 1922/1924/4241 +f 1928/1930/4239 1920/1922/4244 1929/1931/4240 +f 1928/1930/4239 1917/1919/4238 1920/1922/4244 +f 1927/1929/4245 1931/1933/4245 1932/1934/4245 +f 1927/1929/4246 1932/1934/4247 1930/1932/4248 +f 1933/1935/4249 1930/1932/4248 1932/1934/4247 +f 1934/1936/4250 1930/1932/4251 1933/1935/4252 +f 1930/1932/4253 1934/1936/4254 1929/1931/4255 +f 1934/1936/4254 1935/1937/4256 1929/1931/4255 +f 1929/1931/4257 1935/1937/4258 1936/1938/4259 +f 1937/1939/4260 1928/1930/4261 1929/1931/4262 +f 1937/1939/4260 1929/1931/4262 1936/1938/4263 +f 1928/1930/4264 1937/1939/4265 1931/1933/4266 +f 1928/1930/4264 1931/1933/4266 1927/1929/4267 +f 1936/1938/4259 1935/1937/4258 1938/1940/4268 +f 1936/1938/4269 1939/1941/4270 1937/1939/4271 +f 1933/1935/4252 1940/1942/4272 1934/1936/4250 +f 1934/1936/4250 1940/1942/4272 1935/1937/4273 +f 1933/1935/4252 1941/1943/4274 1940/1942/4272 +f 1936/1938/4269 1938/1940/4275 1939/1941/4270 +f 1937/1939/4276 1939/1941/4277 1931/1933/4278 +f 1931/1933/4278 1941/1943/4279 1932/1934/4280 +f 1932/1934/4281 1941/1943/4274 1933/1935/4252 +f 1940/1942/4282 1938/1940/4268 1935/1937/4258 +f 1931/1933/4278 1939/1941/4277 1941/1943/4279 +f 1939/1941/4277 1938/1940/4268 1941/1943/4279 +f 1940/1942/4282 1941/1943/4279 1938/1940/4268 +f 1942/1944/4283 1943/1945/4284 1944/1946/4285 +f 1945/1947/4286 1946/1948/4287 1947/1949/4288 +f 1948/1950/4289 1946/1948/4287 1945/1947/4286 +f 1948/1950/4289 1945/1947/4286 1949/1951/4290 +f 1950/1952/4291 1951/1953/4292 1952/1954/4293 +f 1953/1955/4294 1954/1956/4295 1955/1957/4296 +f 1953/1955/4294 1948/1950/4289 1949/1951/4290 +f 1949/1951/4290 1954/1956/4295 1953/1955/4294 +f 1949/1951/4290 1952/1954/4293 1951/1953/4292 +f 1954/1956/4295 1949/1951/4290 1951/1953/4292 +f 1956/1958/4297 1957/1959/4298 1954/1956/4295 +f 1956/1958/4297 1954/1956/4295 1958/1960/4299 +f 1958/1960/4299 1959/1961/4300 1956/1958/4297 +f 1954/1956/4295 1951/1953/4292 1958/1960/4299 +f 1960/1962/4301 1959/1961/4300 1958/1960/4299 +f 1961/1963/4302 1954/1956/4295 1957/1959/4298 +f 1962/1964/4303 1963/1965/4304 1964/1966/4305 +f 1962/1964/4303 1964/1966/4305 1965/1967/4306 +f 1959/1961/4300 1960/1962/4301 1966/1968/4307 +f 1962/1964/4303 1965/1967/4306 1967/1969/4308 +f 1918/1920/4303 1925/1927/4309 1923/1925/4306 +f 1918/1920/4303 1923/1925/4306 1921/1923/4306 +f 1919/1921/4303 1918/1920/4303 1921/1923/4306 +f 1894/1896/4310 1898/1900/4310 1896/1898/4311 +f 1898/1900/4310 1894/1896/4310 1893/1895/4303 +f 1900/1902/4303 1898/1900/4310 1893/1895/4303 +f 1968/1970/4303 1969/1971/4303 1970/1972/4303 +f 1969/1971/4303 1971/1973/4303 1970/1972/4303 +f 1969/1971/4303 1972/1974/4303 1971/1973/4303 +f 1972/1974/4303 1973/1975/4303 1971/1973/4303 +f 1974/1976/4312 1962/1964/4312 1967/1969/4312 +f 1974/1976/4313 1967/1969/4313 1975/1977/4313 +f 1975/1977/4314 1967/1969/4315 1976/1978/4316 +f 1976/1978/4316 1967/1969/4315 1965/1967/4317 +f 1976/1978/4318 1965/1967/4319 1964/1966/4320 +f 1976/1978/4318 1964/1966/4320 1977/1979/4321 +f 1977/1979/4322 1964/1966/4323 1963/1965/4324 +f 1977/1979/4322 1963/1965/4324 1978/1980/4325 +f 1978/1980/4326 1963/1965/4326 1979/1981/4326 +f 1979/1981/4327 1963/1965/4327 1962/1964/4327 +f 1979/1981/4328 1962/1964/4328 1974/1976/4328 +f 1980/1982/4329 1979/1981/4188 1974/1976/4330 +f 1980/1982/4329 1974/1976/4330 1981/1983/4331 +f 1982/1984/4332 1977/1979/4330 1978/1980/4244 +f 1983/1985/4333 1976/1978/4334 1977/1979/4330 +f 1983/1985/4333 1977/1979/4330 1982/1984/4332 +f 1978/1980/4188 1979/1981/4188 1980/1982/4329 +f 1975/1977/4334 1976/1978/4334 1983/1985/4333 +f 1981/1983/4331 1974/1976/4330 1975/1977/4335 +f 1980/1982/4336 1984/1986/4337 1978/1980/4338 +f 1985/1987/4339 1978/1980/4338 1984/1986/4337 +f 1985/1987/4340 1982/1984/4340 1978/1980/4340 +f 1982/1984/4341 1985/1987/4341 1986/1988/4341 +f 1987/1989/4342 1982/1984/4343 1986/1988/4344 +f 1982/1984/4343 1987/1989/4342 1983/1985/4345 +f 1983/1985/4346 1987/1989/4346 1988/1990/4346 +f 1983/1985/4347 1988/1990/4348 1975/1977/4349 +f 1989/1991/4350 1975/1977/4349 1988/1990/4348 +f 1989/1991/4351 1981/1983/4351 1975/1977/4351 +f 1990/1992/4352 1981/1983/4353 1989/1991/4354 +f 1981/1983/4355 1990/1992/4356 1980/1982/4357 +f 1980/1982/4357 1990/1992/4356 1984/1986/4358 +f 1989/1991/4359 1988/1990/4359 1991/1993/4359 +f 1989/1991/4354 1992/1994/4360 1990/1992/4352 +f 1990/1992/4356 1992/1994/4361 1984/1986/4358 +f 1989/1991/4354 1991/1993/4362 1992/1994/4360 +f 1984/1986/4358 1943/1945/4363 1985/1987/4364 +f 1986/1988/4365 1985/1987/4366 1993/1995/4367 +f 1986/1988/4344 1993/1995/4368 1987/1989/4342 +f 1992/1994/4361 1944/1946/4369 1984/1986/4358 +f 1984/1986/4358 1944/1946/4369 1943/1945/4363 +f 1987/1989/4370 1993/1995/4371 1988/1990/4372 +f 1988/1990/4372 1942/1944/4283 1991/1993/4373 +f 1985/1987/4366 1943/1945/4374 1993/1995/4367 +f 1993/1995/4371 1942/1944/4283 1988/1990/4372 +f 1992/1994/4375 1991/1993/4373 1944/1946/4285 +f 1991/1993/4373 1942/1944/4283 1944/1946/4285 +f 1943/1945/4284 1942/1944/4283 1993/1995/4376 +f 1994/1996/4377 1995/1997/4378 1969/1971/4379 +f 1969/1971/4379 1995/1997/4378 1972/1974/4380 +f 1971/1973/4381 1973/1975/4382 1996/1998/4383 +f 1996/1998/4383 1973/1975/4382 1997/1999/4384 +f 1973/1975/4385 1972/1974/4386 1997/1999/4387 +f 1997/1999/4387 1972/1974/4386 1995/1997/4388 +f 1998/2000/4389 1995/1997/4390 1999/2001/4391 +f 1999/2001/4391 1995/1997/4390 1994/1996/4392 +f 2000/2002/4329 1997/1999/4393 1998/2000/4389 +f 1998/2000/4389 1997/1999/4393 1995/1997/4390 +f 2000/2002/4329 2001/2003/4191 1996/1998/4393 +f 1996/1998/4393 2001/2003/4191 1994/1996/4392 +f 1994/1996/4392 2001/2003/4191 1999/2001/4391 +f 1996/1998/4393 1997/1999/4393 2000/2002/4329 +f 2001/2003/4394 2000/2002/4395 2002/2004/4396 +f 2001/2003/4394 2002/2004/4396 2003/2005/4397 +f 2004/2006/4398 2005/2007/4399 1998/2000/4400 +f 2004/2006/4398 1998/2000/4400 1999/2001/4401 +f 2003/2005/4402 2002/2004/4403 2006/2008/4404 +f 2006/2008/4404 2002/2004/4403 2007/2009/4405 +f 2006/2008/4404 2007/2009/4405 2005/2007/4406 +f 2006/2008/4404 2005/2007/4406 2004/2006/4407 +f 2003/2005/4408 2006/2008/4409 2001/2003/4408 +f 2001/2003/4408 2006/2008/4409 1999/2001/4410 +f 1999/2001/4410 2006/2008/4409 2004/2006/4411 +f 1998/2000/4412 2005/2007/4413 2007/2009/4414 +f 1998/2000/4412 2007/2009/4414 2000/2002/4412 +f 2000/2002/4412 2007/2009/4414 2002/2004/4412 +f 2008/2010/4415 1994/1996/4377 1968/1970/4416 +f 1968/1970/4416 1994/1996/4377 1969/1971/4379 +f 1968/1970/4417 1970/1972/4418 2008/2010/4419 +f 2008/2010/4419 1970/1972/4418 2009/2011/4420 +f 1970/1972/4421 1971/1973/4381 2009/2011/4422 +f 2009/2011/4422 1971/1973/4381 1996/1998/4383 +f 2010/2012/4423 1994/1996/4392 2011/2013/4424 +f 2011/2013/4424 1994/1996/4392 2008/2010/4425 +f 1996/1998/4393 2010/2012/4423 2012/2014/4426 +f 2013/2015/4191 2009/2011/2172 2012/2014/4426 +f 2012/2014/4426 2009/2011/2172 1996/1998/4393 +f 2011/2013/4424 2008/2010/4425 2013/2015/4191 +f 2013/2015/4191 2008/2010/4425 2009/2011/2172 +f 2010/2012/4423 1996/1998/4393 1994/1996/4392 +f 2013/2015/4427 2012/2014/4428 2014/2016/4429 +f 2013/2015/4427 2014/2016/4429 2015/2017/4430 +f 2016/2018/4431 2017/2019/4432 2010/2012/4433 +f 2016/2018/4431 2010/2012/4433 2011/2013/4434 +f 2015/2017/4435 2014/2016/4436 2018/2020/4437 +f 2018/2020/4437 2014/2016/4436 2019/2021/4438 +f 2018/2020/4437 2019/2021/4438 2016/2018/4439 +f 2016/2018/4439 2019/2021/4438 2017/2019/4440 +f 2013/2015/4408 2015/2017/4408 2018/2020/4410 +f 2013/2015/4408 2018/2020/4410 2011/2013/4410 +f 2018/2020/4410 2016/2018/4410 2011/2013/4410 +f 2010/2012/4414 2019/2021/4441 2012/2014/4412 +f 2012/2014/4412 2019/2021/4441 2014/2016/4412 +f 2010/2012/4414 2017/2019/4442 2019/2021/4441 +f 2020/2022/4443 2021/2023/4444 2022/2024/4445 +f 2023/2025/4446 2021/2023/4444 2024/2026/4447 +f 2024/2026/4447 2021/2023/4444 2020/2022/4443 +f 2024/2026/4447 2025/2027/4448 2023/2025/4446 +f 2024/2026/4447 2026/2028/4449 2025/2027/4448 +f 2022/2024/4445 2026/2028/4449 2020/2022/4443 +f 2020/2022/4443 2026/2028/4449 2024/2026/4447 +f 2027/2029/4450 2028/2030/4451 2029/2031/4452 +f 2027/2029/4450 2029/2031/4452 2030/2032/4453 +f 2031/2033/4454 2029/2031/4455 2032/2034/4456 +f 2032/2034/4456 2029/2031/4455 2028/2030/4457 +f 2032/2034/4458 2028/2030/4459 2033/2035/4460 +f 2033/2035/4460 2028/2030/4459 2027/2029/4461 +f 2033/2035/4462 2027/2029/4462 2034/2036/4462 +f 2034/2036/4463 2027/2029/4463 2030/2032/4463 +f 2034/2036/4464 2030/2032/4465 2031/2033/4466 +f 2031/2033/4466 2030/2032/4465 2029/2031/4467 +f 2023/2025/4468 2031/2033/4469 2032/2034/4470 +f 2023/2025/4468 2032/2034/4470 2021/2023/4471 +f 2021/2023/4472 2032/2034/4472 2033/2035/4472 +f 2021/2023/4473 2033/2035/4473 2022/2024/4473 +f 2022/2024/4474 2033/2035/4475 2034/2036/4476 +f 2022/2024/4474 2034/2036/4476 2026/2028/4477 +f 2026/2028/4478 2034/2036/4479 2025/2027/4480 +f 2025/2027/4480 2034/2036/4479 2031/2033/4481 +f 2025/2027/4482 2031/2033/4482 2023/2025/4482 +f 2035/2037/4483 2036/2038/4484 1959/1961/4485 +f 2035/2037/4483 1959/1961/4485 2037/2039/4486 +f 1966/1968/4487 2038/2040/4488 1959/1961/4489 +f 1959/1961/4489 2038/2040/4488 2037/2039/4490 +f 2039/2041/4491 1955/1957/4492 1954/1956/4493 +f 2039/2041/4491 1954/1956/4493 2040/2042/4494 +f 2040/2042/4494 1954/1956/4493 1961/1963/4495 +f 2040/2042/4494 1961/1963/4495 2035/2037/4496 +f 2041/2043/4497 1945/1947/4498 2042/2044/4499 +f 2042/2044/4499 1945/1947/4498 1947/1949/4500 +f 2043/2045/4501 2044/2046/4502 2041/2043/4503 +f 2041/2043/4503 2044/2046/4502 1945/1947/4504 +f 2045/2047/4505 2046/2048/4505 2047/2049/4505 +f 2047/2049/4506 2046/2048/4506 1951/1953/4506 +f 2047/2049/4507 1951/1953/4508 2048/2050/4509 +f 2048/2050/4509 1951/1953/4508 1950/1952/4510 +f 2049/2051/4511 2044/2046/4512 2050/2052/4513 +f 2050/2052/4514 2044/2046/4515 1950/1952/4516 +f 2050/2052/4514 1950/1952/4516 2051/2053/4517 +f 2051/2053/4518 1950/1952/4518 1952/1954/4518 +f 2051/2053/4519 1952/1954/4519 2052/2054/4519 +f 2052/2054/4520 1952/1954/4520 1949/1951/4520 +f 2052/2054/4521 1949/1951/4521 2053/2055/4521 +f 2053/2055/4522 1949/1951/4523 1945/1947/4524 +f 2053/2055/4522 1945/1947/4524 2049/2051/4525 +f 2049/2051/4511 1945/1947/4526 2044/2046/4512 +f 2054/2056/4527 1947/1949/4528 1946/1948/4529 +f 2054/2056/4527 1946/1948/4529 2055/2057/4530 +f 2055/2057/4531 1946/1948/4531 1948/1950/4531 +f 2055/2057/4532 1948/1950/4533 2056/2058/4534 +f 2056/2058/4534 1948/1950/4533 1953/1955/4535 +f 2056/2058/4536 1953/1955/4537 2057/2059/4538 +f 2057/2059/4538 1953/1955/4537 1955/1957/4539 +f 2057/2059/4540 1955/1957/4541 1947/1949/4542 +f 2057/2059/4540 1947/1949/4542 2054/2056/4543 +f 2058/2060/4544 2036/2038/4545 2059/2061/4546 +f 2060/2062/4547 1956/1958/4547 1959/1961/4547 +f 2060/2062/4548 1959/1961/4548 2058/2060/4548 +f 2058/2060/4544 1959/1961/4549 2036/2038/4545 +f 2061/2063/4550 1957/1959/4551 1956/1958/4552 +f 2061/2063/4550 1956/1958/4552 2060/2062/4553 +f 2059/2061/4546 2036/2038/4545 1961/1963/4554 +f 2059/2061/4555 1961/1963/4556 2061/2063/4557 +f 2061/2063/4557 1961/1963/4556 1957/1959/4558 +f 2062/2064/4559 1966/1968/4560 1960/1962/4561 +f 2062/2064/4559 1960/1962/4561 2063/2065/4562 +f 2064/2066/4563 1951/1953/4564 2046/2048/4565 +f 2064/2066/4563 2046/2048/4565 1966/1968/4566 +f 2064/2066/4563 1966/1968/4566 2062/2064/4567 +f 2065/2067/4568 1958/1960/4568 1951/1953/4568 +f 2065/2067/4569 1951/1953/4569 2064/2066/4569 +f 2063/2065/4570 1960/1962/4571 2066/2068/4572 +f 2066/2068/4572 1960/1962/4571 1958/1960/4573 +f 2066/2068/4574 1958/1960/4574 2065/2067/4574 +f 2046/2048/4575 2045/2047/4576 2038/2040/4577 +f 2046/2048/4575 2038/2040/4577 1966/1968/4578 +f 2044/2046/4579 2043/2045/4579 1950/1952/4579 +f 1950/1952/4580 2043/2045/4580 2048/2050/4580 +f 2036/2038/4581 2035/2037/4581 1961/1963/4581 +f 1955/1957/4582 2039/2041/4583 1947/1949/4584 +f 1947/1949/4584 2039/2041/4583 2042/2044/4585 +f 2067/2069/4586 2068/2070/4587 2069/2071/4588 +f 2069/2071/4588 2068/2070/4587 2070/2072/4589 +f 2069/2071/4590 2070/2072/4591 2071/2073/4592 +f 2071/2073/4592 2070/2072/4591 2072/2074/4593 +f 2071/2073/4594 2072/2074/4595 2067/2069/4596 +f 2067/2069/4596 2072/2074/4595 2068/2070/4597 +f 2073/2075/4598 2074/2076/4599 2072/2074/4600 +f 2072/2074/4600 2074/2076/4599 2068/2070/4601 +f 2068/2070/4601 2074/2076/4599 2075/2077/4602 +f 2072/2074/4600 2076/2078/4603 2073/2075/4598 +f 2070/2072/4604 2076/2078/4603 2072/2074/4600 +f 2070/2072/4604 2077/2079/4605 2076/2078/4603 +f 2070/2072/4604 2075/2077/4602 2077/2079/4605 +f 2068/2070/4601 2075/2077/4602 2070/2072/4604 +f 2078/2080/4606 2079/2081/4607 2080/2082/4608 +f 2081/2083/4609 2077/2079/4605 2082/2084/4610 +f 2073/2075/4611 2083/2085/4611 2074/2076/4611 +f 2084/2086/4612 2083/2085/4613 2073/2075/4614 +f 2073/2075/4614 2078/2080/4615 2084/2086/4612 +f 2084/2086/4612 2078/2080/4615 2080/2082/4616 +f 2073/2075/4598 2076/2078/4603 2078/2080/4606 +f 2076/2078/4603 2079/2081/4607 2078/2080/4606 +f 2076/2078/4603 2081/2083/4609 2079/2081/4607 +f 2076/2078/4603 2077/2079/4605 2081/2083/4609 +f 2085/2087/4617 2082/2084/4618 2077/2079/4619 +f 2086/2088/4620 2085/2087/4617 2077/2079/4619 +f 2077/2079/4605 2075/2077/4602 2086/2088/4621 +f 2086/2088/4621 2075/2077/4602 2087/2089/4622 +f 2087/2089/4622 2075/2077/4602 2088/2090/4623 +f 2074/2076/4624 2088/2090/4623 2075/2077/4602 +f 2089/2091/4625 2088/2090/4626 2074/2076/4627 +f 2083/2085/4628 2089/2091/4625 2074/2076/4627 +f 2090/2092/4629 2083/2085/4613 2084/2086/4612 +f 2079/2081/4630 2091/2093/4630 2080/2082/4630 +f 2081/2083/4609 2091/2093/4631 2079/2081/4607 +f 2082/2084/4632 2091/2093/4631 2081/2083/4609 +f 2091/2093/4633 2082/2084/4633 2085/2087/4633 +f 2085/2087/4634 2086/2088/4634 2092/2094/4634 +f 2092/2094/4635 2086/2088/4635 2087/2089/4635 +f 2088/2090/4623 2092/2094/4636 2087/2089/4622 +f 2088/2090/4637 2089/2091/4637 2092/2094/4637 +f 2090/2092/4638 2089/2091/4625 2083/2085/4628 +f 2093/2095/4639 2091/2093/4640 2094/2096/4641 +f 2084/2086/4642 2080/2082/4643 2093/2095/4639 +f 2093/2095/4639 2080/2082/4643 2091/2093/4640 +f 2095/2097/4644 2092/2094/4645 2089/2091/4646 +f 2096/2098/4647 2090/2092/4648 2084/2086/4642 +f 2096/2098/4647 2084/2086/4642 2093/2095/4639 +f 2096/2098/4647 2089/2091/4646 2090/2092/4648 +f 2095/2097/4644 2089/2091/4646 2096/2098/4647 +f 2095/2097/4644 2085/2087/4649 2092/2094/4645 +f 2094/2096/4641 2085/2087/4649 2095/2097/4644 +f 2094/2096/4641 2091/2093/4640 2085/2087/4649 +f 2096/2098/4650 2097/2099/4650 2095/2097/4650 +f 2095/2097/4651 2097/2099/4651 2098/2100/4651 +f 2095/2097/4652 2098/2100/4652 2094/2096/4652 +f 2094/2096/4653 2098/2100/4653 2099/2101/4653 +f 2094/2096/4654 2099/2101/4654 2093/2095/4654 +f 2093/2095/4655 2099/2101/4655 2100/2102/4655 +f 2093/2095/4656 2100/2102/4656 2096/2098/4656 +f 2096/2098/4657 2100/2102/4657 2097/2099/4657 +f 2101/2103/4658 2102/2104/4659 2071/2073/4660 +f 2067/2069/4661 2103/2105/4662 2071/2073/4660 +f 2071/2073/4660 2103/2105/4662 2101/2103/4658 +f 2067/2069/4661 2104/2106/4663 2103/2105/4662 +f 2069/2071/4664 2104/2106/4663 2067/2069/4661 +f 2105/2107/4665 2069/2071/4664 2071/2073/4660 +f 2071/2073/4660 2102/2104/4659 2105/2107/4665 +f 2104/2106/4663 2069/2071/4664 2105/2107/4665 +f 2103/2105/4666 2106/2108/4667 2107/2109/4668 +f 2106/2108/4667 2103/2105/4666 2108/2110/4669 +f 2108/2110/4669 2103/2105/4666 2104/2106/4670 +f 2109/2111/4671 2108/2110/4669 2104/2106/4670 +f 2110/2112/4672 2109/2111/4671 2104/2106/4670 +f 2109/2111/4671 2110/2112/4672 2111/2113/4673 +f 2104/2106/4663 2105/2107/4665 2110/2112/4674 +f 2110/2112/4672 2112/2114/4675 2111/2113/4673 +f 2105/2107/4665 2112/2114/4675 2110/2112/4674 +f 2112/2114/4675 2105/2107/4665 2113/2115/4676 +f 2112/2114/4675 2113/2115/4676 2114/2116/4677 +f 2115/2117/4678 2113/2115/4679 2105/2107/4665 +f 2102/2104/4659 2115/2117/4678 2105/2107/4665 +f 2102/2104/4680 2116/2118/4681 2115/2117/4682 +f 2117/2119/4683 2116/2118/4681 2118/2120/4684 +f 2118/2120/4684 2116/2118/4681 2102/2104/4680 +f 2118/2120/4685 2102/2104/4686 2101/2103/4658 +f 2119/2121/4687 2118/2120/4685 2101/2103/4658 +f 2103/2105/4662 2119/2121/4687 2101/2103/4658 +f 2103/2105/4662 2107/2109/4688 2119/2121/4687 +f 2106/2108/4689 2108/2110/4689 2109/2111/4689 +f 2112/2114/4675 2114/2116/4677 2111/2113/4673 +f 2113/2115/4676 2120/2122/4690 2114/2116/4677 +f 2113/2115/4691 2115/2117/4691 2120/2122/4691 +f 2120/2122/4692 2115/2117/4692 2116/2118/4692 +f 2119/2121/4693 2121/2123/4694 2118/2120/4695 +f 2118/2120/4695 2121/2123/4694 2117/2119/4696 +f 2121/2123/4694 2119/2121/4693 2107/2109/4697 +f 2121/2123/4698 2107/2109/4698 2106/2108/4698 +f 2097/2099/4699 2109/2111/4700 2098/2100/4701 +f 2097/2099/4699 2121/2123/4702 2106/2108/4703 +f 2100/2102/4704 2117/2119/4705 2121/2123/4702 +f 2100/2102/4704 2121/2123/4702 2097/2099/4699 +f 2099/2101/4706 2120/2122/4707 2116/2118/4708 +f 2109/2111/4700 2111/2113/4709 2098/2100/4701 +f 2098/2100/4701 2120/2122/4707 2099/2101/4706 +f 2098/2100/4701 2114/2116/4710 2120/2122/4707 +f 2099/2101/4706 2116/2118/4708 2100/2102/4704 +f 2100/2102/4704 2116/2118/4708 2117/2119/4705 +f 2098/2100/4701 2111/2113/4709 2114/2116/4710 +f 2097/2099/4699 2106/2108/4703 2109/2111/4700 +f 2122/2124/4711 2123/2125/4712 2124/2126/4713 +f 2125/2127/4714 2126/2128/4715 2127/2129/4716 +f 2128/2130/4717 2125/2127/4714 2127/2129/4716 +f 2129/2131/4718 2126/2128/4718 2125/2127/4718 +f 2129/2131/4719 2125/2127/4719 2130/2132/4719 +f 2130/2132/4720 2125/2127/4720 2128/2130/4720 +f 2130/2132/4721 2128/2130/4722 2131/2133/4723 +f 2131/2133/4723 2128/2130/4722 2127/2129/4724 +f 2131/2133/4725 2127/2129/4726 2126/2128/4727 +f 2131/2133/4725 2126/2128/4727 2129/2131/4728 +f 2129/2131/4729 2132/2134/4730 2131/2133/4731 +f 2129/2131/4729 2133/2135/4732 2132/2134/4730 +f 2131/2133/4731 2134/2136/4733 2135/2137/4734 +f 2132/2134/4730 2134/2136/4733 2131/2133/4731 +f 2130/2132/4735 2136/2138/4736 2129/2131/4729 +f 2129/2131/4729 2136/2138/4736 2133/2135/4732 +f 2131/2133/4731 2135/2137/4734 2137/2139/4737 +f 2131/2133/4731 2137/2139/4737 2130/2132/4735 +f 2130/2132/4735 2138/2140/4738 2136/2138/4736 +f 2130/2132/4735 2137/2139/4737 2138/2140/4738 +f 2124/2126/4739 2123/2125/4740 2137/2139/4741 +f 2138/2140/4742 2137/2139/4741 2123/2125/4740 +f 2123/2125/4743 2122/2124/4744 2138/2140/4745 +f 2122/2124/4744 2136/2138/4746 2138/2140/4745 +f 2133/2135/4747 2136/2138/4748 2122/2124/4711 +f 2122/2124/4711 2139/2141/4749 2133/2135/4747 +f 2132/2134/4750 2133/2135/4750 2139/2141/4750 +f 2122/2124/4711 2140/2142/4751 2139/2141/4749 +f 2139/2141/4749 2140/2142/4751 2134/2136/4752 +f 2139/2141/4749 2134/2136/4752 2132/2134/4753 +f 2134/2136/4752 2140/2142/4751 2141/2143/4754 +f 2135/2137/4755 2134/2136/4752 2141/2143/4754 +f 2141/2143/4754 2142/2144/4756 2135/2137/4755 +f 2137/2139/4741 2135/2137/4757 2142/2144/4758 +f 2124/2126/4739 2137/2139/4741 2142/2144/4758 +f 2142/2144/4759 2141/2143/4760 2124/2126/4713 +f 2124/2126/4713 2141/2143/4760 2140/2142/4751 +f 2124/2126/4713 2140/2142/4751 2122/2124/4711 +f 2143/2145/4761 2144/2146/4761 2145/2147/4762 +f 2146/2148/4763 2144/2146/4761 2143/2145/4761 +f 2147/2149/4764 2146/2148/4764 2148/2150/4764 +f 2148/2150/4765 2146/2148/4765 2143/2145/4765 +f 2148/2150/4766 2143/2145/4766 2149/2151/4766 +f 2149/2151/4767 2143/2145/4767 2145/2147/4767 +f 2149/2151/4768 2145/2147/4768 2150/2152/4768 +f 2150/2152/4769 2145/2147/4769 2144/2146/4769 +f 2150/2152/4770 2144/2146/4770 2147/2149/4770 +f 2147/2149/4771 2144/2146/4771 2146/2148/4771 +f 2150/2152/4772 2151/2153/4773 2149/2151/4774 +f 2148/2150/4775 2152/2154/4776 2147/2149/4777 +f 2147/2149/4777 2152/2154/4776 2153/2155/4778 +f 2147/2149/4777 2154/2156/4779 2150/2152/4772 +f 2147/2149/4777 2153/2155/4778 2154/2156/4779 +f 2148/2150/4775 2155/2157/4780 2152/2154/4776 +f 2150/2152/4772 2156/2158/4781 2151/2153/4773 +f 2150/2152/4772 2154/2156/4779 2156/2158/4781 +f 2149/2151/4774 2157/2159/4782 2158/2160/4783 +f 2149/2151/4774 2158/2160/4783 2155/2157/4780 +f 2149/2151/4774 2155/2157/4780 2148/2150/4775 +f 2149/2151/4774 2151/2153/4773 2157/2159/4782 +f 2159/2161/4784 2154/2156/4784 2153/2155/4784 +f 2155/2157/4785 2158/2160/4786 2160/2162/4787 +f 2161/2163/4788 2157/2159/4789 2162/2164/4790 +f 2161/2163/4788 2160/2162/4791 2157/2159/4789 +f 2158/2160/4792 2157/2159/4789 2160/2162/4791 +f 2163/2165/4793 2160/2162/4794 2161/2163/4795 +f 2163/2165/4796 2155/2157/4785 2160/2162/4787 +f 2155/2157/4785 2163/2165/4796 2152/2154/4797 +f 2163/2165/4796 2164/2166/4798 2152/2154/4797 +f 2152/2154/4797 2164/2166/4798 2153/2155/4799 +f 2164/2166/4798 2159/2161/4800 2153/2155/4799 +f 2164/2166/4798 2165/2167/4801 2159/2161/4800 +f 2165/2167/4801 2154/2156/4802 2159/2161/4800 +f 2162/2164/4790 2154/2156/4802 2165/2167/4801 +f 2162/2164/4790 2156/2158/4803 2154/2156/4802 +f 2151/2153/4804 2156/2158/4803 2162/2164/4790 +f 2157/2159/4789 2151/2153/4804 2162/2164/4790 +f 2164/2166/4805 2163/2165/4793 2165/2167/4806 +f 2162/2164/4807 2165/2167/4806 2161/2163/4795 +f 2161/2163/4795 2165/2167/4806 2163/2165/4793 +f 2166/2168/4808 2167/2169/4809 2168/2170/4810 +f 2166/2168/4808 2168/2170/4810 2169/2171/4811 +f 2170/2172/4812 2167/2169/4812 2171/2173/4812 +f 2171/2173/4813 2167/2169/4813 2166/2168/4813 +f 2171/2173/4814 2166/2168/4814 2172/2174/4814 +f 2172/2174/4815 2166/2168/4815 2169/2171/4815 +f 2172/2174/4816 2169/2171/4816 2173/2175/4816 +f 2173/2175/4817 2169/2171/4817 2168/2170/4817 +f 2173/2175/4818 2168/2170/4818 2170/2172/4818 +f 2170/2172/4819 2168/2170/4819 2167/2169/4819 +f 2170/2172/4820 2174/2176/4821 2173/2175/4822 +f 2170/2172/4820 2175/2177/4823 2174/2176/4821 +f 2173/2175/4822 2174/2176/4821 2176/2178/4824 +f 2170/2172/4820 2177/2179/4825 2175/2177/4823 +f 2172/2174/4826 2178/2180/4827 2179/2181/4828 +f 2173/2175/4822 2176/2178/4824 2178/2180/4827 +f 2173/2175/4822 2178/2180/4827 2172/2174/4826 +f 2172/2174/4826 2180/2182/4829 2171/2173/4830 +f 2171/2173/4830 2177/2179/4825 2170/2172/4820 +f 2171/2173/4830 2180/2182/4829 2177/2179/4825 +f 2172/2174/4826 2179/2181/4828 2180/2182/4829 +f 2181/2183/4831 2176/2178/4831 2174/2176/4831 +f 2177/2179/4832 2180/2182/4832 2182/2184/4832 +f 2179/2181/4833 2183/2185/4834 2180/2182/4835 +f 2183/2185/4834 2182/2184/4836 2180/2182/4835 +f 2184/2186/4837 2177/2179/4838 2182/2184/4839 +f 2175/2177/4840 2177/2179/4838 2184/2186/4837 +f 2175/2177/4841 2184/2186/4842 2185/2187/4843 +f 2174/2176/4844 2175/2177/4841 2185/2187/4843 +f 2181/2183/4845 2174/2176/4844 2185/2187/4843 +f 2186/2188/4846 2181/2183/4845 2185/2187/4843 +f 2176/2178/4847 2181/2183/4845 2186/2188/4846 +f 2176/2178/4847 2186/2188/4846 2178/2180/4848 +f 2186/2188/4846 2183/2185/4834 2178/2180/4848 +f 2179/2181/4833 2178/2180/4848 2183/2185/4834 +f 2185/2187/4849 2184/2186/4850 2186/2188/4851 +f 2183/2185/4852 2186/2188/4851 2182/2184/4853 +f 2182/2184/4853 2186/2188/4851 2184/2186/4850 +f 2187/2189/4854 2188/2190/4855 2189/2191/4854 +f 2189/2191/4854 2190/2192/4856 2187/2189/4854 +f 2191/2193/4857 2188/2190/4857 2187/2189/4857 +f 2191/2193/4858 2187/2189/4858 2192/2194/4858 +f 2192/2194/4859 2187/2189/4860 2190/2192/4861 +f 2192/2194/4859 2190/2192/4861 2193/2195/4862 +f 2193/2195/4863 2190/2192/4863 2189/2191/4863 +f 2193/2195/4864 2189/2191/4864 2194/2196/4864 +f 2194/2196/4865 2189/2191/4865 2188/2190/4865 +f 2194/2196/4866 2188/2190/4866 2191/2193/4866 +f 2193/2195/4867 2195/2197/4868 2192/2194/4869 +f 2191/2193/4870 2196/2198/4871 2197/2199/4872 +f 2191/2193/4870 2197/2199/4872 2194/2196/4873 +f 2194/2196/4873 2198/2200/4874 2193/2195/4867 +f 2194/2196/4873 2197/2199/4872 2198/2200/4874 +f 2191/2193/4870 2199/2201/4875 2196/2198/4871 +f 2193/2195/4867 2200/2202/4876 2195/2197/4868 +f 2193/2195/4867 2198/2200/4874 2200/2202/4876 +f 2192/2194/4869 2199/2201/4875 2191/2193/4870 +f 2192/2194/4869 2201/2203/4877 2199/2201/4875 +f 2192/2194/4869 2195/2197/4868 2201/2203/4877 +f 2202/2204/4878 2196/2198/4878 2199/2201/4878 +f 2203/2205/4879 2204/2206/4880 2195/2197/4881 +f 2201/2203/4882 2195/2197/4881 2204/2206/4880 +f 2204/2206/4883 2205/2207/4884 2199/2201/4885 +f 2204/2206/4883 2199/2201/4885 2201/2203/4886 +f 2202/2204/4887 2199/2201/4885 2205/2207/4884 +f 2202/2204/4888 2205/2207/4889 2196/2198/4890 +f 2206/2208/4891 2196/2198/4890 2205/2207/4889 +f 2197/2199/4892 2196/2198/4890 2206/2208/4891 +f 2207/2209/4893 2197/2199/4892 2206/2208/4891 +f 2198/2200/4894 2197/2199/4892 2207/2209/4893 +f 2208/2210/4895 2198/2200/4896 2207/2209/4897 +f 2200/2202/4898 2198/2200/4896 2208/2210/4895 +f 2195/2197/4881 2200/2202/4898 2208/2210/4895 +f 2195/2197/4881 2208/2210/4895 2203/2205/4879 +f 2208/2210/4899 2207/2209/4900 2206/2208/4901 +f 2203/2205/4902 2208/2210/4899 2204/2206/4903 +f 2208/2210/4899 2206/2208/4901 2204/2206/4903 +f 2204/2206/4903 2206/2208/4901 2205/2207/4904 +f 2209/2211/4905 2210/2212/4906 2211/2213/4907 +f 2211/2213/4907 2212/2214/4908 2209/2211/4905 +f 2211/2213/4907 2210/2212/4906 2213/2215/4909 +f 2211/2213/4907 2213/2215/4909 2214/2216/4910 +f 2214/2216/4910 2215/2217/4911 2212/2214/4908 +f 2213/2215/4909 2215/2217/4911 2214/2216/4910 +f 2214/2216/4910 2212/2214/4908 2211/2213/4907 +f 2216/2218/4912 2217/2219/4913 2218/2220/4914 +f 2219/2221/4915 2220/2222/4916 2218/2220/4917 +f 2219/2221/4915 2218/2220/4917 2221/2223/4918 +f 2221/2223/4919 2218/2220/4919 2217/2219/4919 +f 2221/2223/4920 2217/2219/4920 2222/2224/4920 +f 2222/2224/4921 2217/2219/4922 2223/2225/4923 +f 2223/2225/4923 2217/2219/4922 2216/2218/4924 +f 2223/2225/4925 2216/2218/4926 2219/2221/4927 +f 2219/2221/4927 2216/2218/4926 2220/2222/4928 +f 2209/2211/4929 2219/2221/4930 2210/2212/4931 +f 2210/2212/4932 2219/2221/4933 2213/2215/4934 +f 2213/2215/4934 2219/2221/4933 2221/2223/4935 +f 2213/2215/4936 2221/2223/4937 2215/2217/4938 +f 2215/2217/4938 2221/2223/4937 2222/2224/4939 +f 2215/2217/4940 2222/2224/4941 2212/2214/4942 +f 2212/2214/4942 2222/2224/4941 2223/2225/4943 +f 2212/2214/4944 2223/2225/4944 2209/2211/4944 +f 2209/2211/4929 2223/2225/4945 2219/2221/4930 +f 2220/2222/4946 2216/2218/4912 2218/2220/4914 +f 2224/2226/4947 2225/2227/4948 2226/2228/4949 +f 2224/2226/4947 2226/2228/4949 2227/2229/4950 +f 2224/2226/4947 2228/2230/4951 2225/2227/4948 +f 2224/2226/4947 2229/2231/4952 2228/2230/4951 +f 2227/2229/4950 2230/2232/4953 2229/2231/4952 +f 2227/2229/4950 2231/2233/4954 2230/2232/4953 +f 2227/2229/4950 2226/2228/4949 2231/2233/4954 +f 2227/2229/4950 2229/2231/4952 2224/2226/4947 +f 2232/2234/4955 2233/2235/4956 2234/2236/4957 +f 2235/2237/4958 2234/2236/4959 2236/2238/4960 +f 2235/2237/4958 2236/2238/4960 2237/2239/4961 +f 2237/2239/4962 2236/2238/4962 2233/2235/4962 +f 2237/2239/4963 2233/2235/4964 2238/2240/4965 +f 2238/2240/4965 2233/2235/4964 2239/2241/4966 +f 2238/2240/4967 2239/2241/4968 2232/2234/4969 +f 2238/2240/4967 2232/2234/4969 2240/2242/4970 +f 2240/2242/4971 2232/2234/4972 2234/2236/4973 +f 2240/2242/4971 2234/2236/4973 2235/2237/4974 +f 2228/2230/4975 2235/2237/4976 2225/2227/4977 +f 2225/2227/4977 2235/2237/4976 2237/2239/4978 +f 2225/2227/4979 2237/2239/4979 2226/2228/4979 +f 2226/2228/4980 2237/2239/4981 2238/2240/4982 +f 2226/2228/4980 2238/2240/4982 2231/2233/4983 +f 2231/2233/4984 2238/2240/4985 2230/2232/4986 +f 2230/2232/4986 2238/2240/4985 2240/2242/4987 +f 2230/2232/4986 2240/2242/4987 2229/2231/4988 +f 2229/2231/4989 2240/2242/4990 2235/2237/4991 +f 2229/2231/4989 2235/2237/4991 2228/2230/4992 +f 2236/2238/4993 2234/2236/4957 2233/2235/4956 +f 2239/2241/4994 2233/2235/4956 2232/2234/4955 +f 2241/2243/4995 2242/2244/4996 2243/2245/4997 +f 2244/2246/4998 2245/2247/4999 2241/2243/4995 +f 2241/2243/4995 2245/2247/4999 2242/2244/4996 +f 2246/2248/5000 2247/2249/5001 2244/2246/4998 +f 2244/2246/4998 2247/2249/5001 2245/2247/4999 +f 2248/2250/5002 2246/2248/5000 2244/2246/4998 +f 2241/2243/4995 2248/2250/5002 2244/2246/4998 +f 2241/2243/4995 2243/2245/4997 2248/2250/5002 +f 2249/2251/5003 2250/2252/5003 2251/2253/5003 +f 2252/2254/5004 2251/2253/5004 2253/2255/5004 +f 2253/2255/5005 2251/2253/5005 2250/2252/5005 +f 2253/2255/5006 2250/2252/5006 2254/2256/5006 +f 2254/2256/5007 2250/2252/5007 2249/2251/5007 +f 2254/2256/5008 2249/2251/5008 2255/2257/5008 +f 2255/2257/5009 2249/2251/5010 2252/2254/5011 +f 2252/2254/5011 2249/2251/5010 2251/2253/5012 +f 2247/2249/5013 2252/2254/5014 2245/2247/5015 +f 2245/2247/5015 2252/2254/5014 2253/2255/5016 +f 2245/2247/5017 2253/2255/5017 2242/2244/5017 +f 2242/2244/5018 2253/2255/5019 2254/2256/5020 +f 2242/2244/5018 2254/2256/5020 2243/2245/5021 +f 2243/2245/5022 2254/2256/5022 2248/2250/5022 +f 2248/2250/5023 2254/2256/5024 2255/2257/5025 +f 2248/2250/5023 2255/2257/5025 2246/2248/5026 +f 2246/2248/5027 2255/2257/5028 2252/2254/5029 +f 2246/2248/5027 2252/2254/5029 2247/2249/5030 +f 2256/2258/5031 2257/2259/5032 2258/2260/5033 +f 2259/2261/5034 2257/2259/5032 2256/2258/5031 +f 2260/2262/5035 2258/2260/5033 2261/2263/5036 +f 2256/2258/5031 2258/2260/5033 2260/2262/5035 +f 2256/2258/5031 2262/2264/5037 2259/2261/5034 +f 2260/2262/5035 2262/2264/5037 2256/2258/5031 +f 2260/2262/5035 2261/2263/5036 2262/2264/5037 +f 2263/2265/5038 2264/2266/5039 2265/2267/5040 +f 2266/2268/5041 2267/2269/5042 2268/2270/5043 +f 2268/2270/5044 2267/2269/5045 2269/2271/5046 +f 2269/2271/5046 2267/2269/5045 2264/2266/5047 +f 2269/2271/5048 2264/2266/5049 2270/2272/5050 +f 2270/2272/5050 2264/2266/5049 2263/2265/5051 +f 2270/2272/5052 2263/2265/5053 2271/2273/5054 +f 2270/2272/5052 2271/2273/5054 2266/2268/5055 +f 2266/2268/5056 2271/2273/5056 2265/2267/5056 +f 2266/2268/5041 2265/2267/5057 2267/2269/5042 +f 2257/2259/5058 2268/2270/5058 2258/2260/5058 +f 2258/2260/5059 2268/2270/5059 2269/2271/5059 +f 2258/2260/5060 2269/2271/5060 2261/2263/5060 +f 2261/2263/5061 2269/2271/5061 2270/2272/5061 +f 2261/2263/5062 2270/2272/5062 2262/2264/5062 +f 2262/2264/5063 2270/2272/5064 2266/2268/5065 +f 2262/2264/5063 2266/2268/5065 2259/2261/5066 +f 2259/2261/5067 2266/2268/5068 2257/2259/5069 +f 2257/2259/5069 2266/2268/5068 2268/2270/5070 +f 2267/2269/5071 2265/2267/5040 2264/2266/5039 +f 2271/2273/5072 2263/2265/5038 2265/2267/5040 +f 2272/2274/5073 2273/2275/5074 2274/2276/5075 +f 2274/2276/5075 2273/2275/5074 2275/2277/5076 +f 2276/2278/5077 2277/2279/5077 2278/2280/5077 +f 2278/2280/5078 2277/2279/5078 2279/2281/5078 +f 2280/2282/5079 2278/2280/5079 2279/2281/5079 +f 2281/2283/5080 2282/2284/5081 2283/2285/5082 +f 2283/2285/5082 2282/2284/5081 2284/2286/5083 +f 2285/2287/5084 2286/2288/5085 2287/2289/5086 +f 2285/2287/5084 2287/2289/5086 2288/2290/5087 +f 2289/2291/5088 2283/2285/5088 2287/2289/5088 +f 2289/2291/5089 2287/2289/5090 2290/2292/5091 +f 2290/2292/5092 2287/2289/5092 2291/2293/5092 +f 2290/2292/5093 2291/2293/5093 2292/2294/5093 +f 2292/2294/5094 2291/2293/5094 2293/2295/5094 +f 2293/2295/5095 2291/2293/5095 2294/2296/5095 +f 2293/2295/5096 2294/2296/5097 2283/2285/5098 +f 2293/2295/5096 2283/2285/5098 2289/2291/5099 +f 2295/2297/5100 2277/2279/5101 2281/2283/5102 +f 2295/2297/5100 2281/2283/5102 2296/2298/5103 +f 2296/2298/5104 2281/2283/5105 2297/2299/5106 +f 2296/2298/5104 2297/2299/5106 2298/2300/5107 +f 2298/2300/5108 2297/2299/5109 2299/2301/5110 +f 2298/2300/5108 2299/2301/5110 2300/2302/5111 +f 2300/2302/5112 2299/2301/5112 2279/2281/5112 +f 2300/2302/5113 2279/2281/5113 2295/2297/5113 +f 2295/2297/5100 2279/2281/5114 2277/2279/5101 +f 2301/2303/5115 2302/2304/5116 2303/2305/5117 +f 2303/2305/5118 2302/2304/5119 2304/2306/5120 +f 2302/2304/5119 2305/2307/5121 2304/2306/5120 +f 2304/2306/5122 2305/2307/5122 2306/2308/5122 +f 2306/2308/5123 2305/2307/5123 2273/2275/5123 +f 2306/2308/5124 2273/2275/5124 2307/2309/5124 +f 2307/2309/5125 2273/2275/5126 2301/2303/5127 +f 2301/2303/5127 2273/2275/5126 2280/2282/5128 +f 2301/2303/5115 2280/2282/5129 2302/2304/5116 +f 2308/2310/5130 2309/2311/5131 2286/2288/5132 +f 2308/2310/5130 2286/2288/5132 2310/2312/5133 +f 2310/2312/5134 2286/2288/5135 2311/2313/5136 +f 2311/2313/5136 2286/2288/5135 2275/2277/5137 +f 2312/2314/5138 2309/2311/5139 2308/2310/5140 +f 2312/2314/5138 2313/2315/5141 2309/2311/5139 +f 2311/2313/5142 2275/2277/5142 2313/2315/5142 +f 2311/2313/5143 2313/2315/5143 2312/2314/5143 +f 2286/2288/5144 2285/2287/5145 2275/2277/5146 +f 2275/2277/5146 2285/2287/5145 2274/2276/5147 +f 2283/2285/5148 2284/2286/5149 2287/2289/5150 +f 2287/2289/5150 2284/2286/5149 2288/2290/5151 +f 2273/2275/5152 2272/2274/5153 2280/2282/5154 +f 2280/2282/5154 2272/2274/5153 2278/2280/5155 +f 2277/2279/5156 2276/2278/5157 2281/2283/5158 +f 2281/2283/5158 2276/2278/5157 2282/2284/5159 +f 2314/2316/5160 2315/2317/5161 2316/2318/5162 +f 2316/2318/5162 2315/2317/5161 2317/2319/534 +f 2318/2320/5163 2319/2321/5164 2317/2319/5165 +f 2316/2318/5166 2317/2319/5165 2319/2321/5164 +f 2320/2322/5167 2321/2323/5168 2318/2320/5169 +f 2318/2320/5169 2321/2323/5168 2319/2321/5170 +f 2322/2324/5171 2323/2325/5172 2324/2326/5173 +f 2323/2325/5172 2322/2324/5171 2325/2327/5174 +f 2323/2325/5172 2325/2327/5174 2326/2328/5175 +f 2326/2328/5175 2325/2327/5174 2327/2329/5176 +f 2326/2328/5175 2327/2329/5176 2328/2330/5177 +f 2326/2328/5175 2328/2330/5177 2329/2331/5178 +f 2326/2328/5179 2329/2331/5180 2330/2332/5181 +f 2330/2332/5181 2329/2331/5180 2331/2333/5182 +f 2332/2334/5183 2333/2335/5184 2330/2332/5185 +f 2332/2334/5183 2330/2332/5185 2331/2333/5186 +f 2333/2335/5187 2332/2334/5188 2334/2336/5189 +f 2333/2335/5187 2334/2336/5189 2323/2325/5190 +f 2323/2325/5172 2334/2336/5191 2324/2326/5173 +f 2335/2337/5192 2336/2338/5193 2337/2339/5194 +f 2338/2340/5195 2339/2341/5196 2340/2342/5197 +f 2341/2343/5198 2342/2344/5199 2343/2345/5200 +f 2344/2346/5201 2345/2347/5202 2346/2348/5203 +f 2345/2347/5204 2344/2346/5204 2347/2349/5204 +f 2348/2350/5205 2349/2351/5206 2350/2352/5207 +f 2351/2353/5208 2352/2354/5209 2353/2355/5210 +f 2353/2355/5210 2352/2354/5209 2354/2356/5211 +f 2353/2355/5212 2354/2356/5212 2348/2350/5212 +f 2355/2357/5213 2348/2350/5213 2354/2356/5213 +f 2355/2357/5214 2349/2351/5206 2348/2350/5205 +f 2356/2358/5215 2352/2354/5216 2357/2359/5217 +f 2358/2360/5218 2359/2361/5218 2360/2362/5218 +f 2361/2363/5219 2360/2362/5220 2362/2364/5221 +f 2361/2363/5219 2362/2364/5221 2363/2365/5222 +f 2364/2366/5223 2355/2357/5224 2363/2365/5225 +f 2365/2367/5226 2363/2365/5226 2362/2364/5226 +f 2365/2367/5227 2364/2366/5223 2363/2365/5225 +f 2366/2368/5228 2359/2361/5229 2367/2369/5230 +f 2359/2361/5229 2366/2368/5228 2362/2364/5231 +f 2359/2361/5229 2362/2364/5231 2360/2362/5232 +f 2368/2370/5233 2365/2367/5234 2369/2371/5235 +f 2370/2372/5236 2337/2339/5236 2371/2373/5236 +f 2371/2373/5237 2337/2339/5237 2372/2374/5237 +f 2373/2375/5238 2372/2374/5239 2369/2371/5235 +f 2368/2370/5233 2369/2371/5235 2374/2376/5240 +f 2369/2371/5241 2372/2374/5242 2337/2339/5194 +f 2369/2371/5241 2337/2339/5194 2336/2338/5193 +f 2375/2377/5243 2376/2378/5243 2377/2379/5243 +f 2377/2379/5244 2374/2376/5245 2378/2380/5246 +f 2379/2381/5247 2377/2379/5248 2380/2382/5249 +f 2340/2342/5197 2339/2341/5196 2381/2383/5250 +f 2340/2342/5251 2381/2383/5251 2382/2384/5251 +f 2381/2383/5252 2383/2385/5252 2382/2384/5252 +f 2384/2386/5253 2381/2383/5253 2339/2341/5253 +f 2385/2387/5254 2383/2385/5254 2384/2386/5254 +f 2339/2341/5255 2386/2388/5255 2387/2389/5255 +f 2339/2341/5256 2338/2340/5256 2386/2388/5256 +f 2388/2390/5257 2389/2391/5258 2390/2392/5259 +f 2390/2392/5259 2389/2391/5258 2391/2393/5260 +f 2392/2394/5261 2391/2393/5260 2393/2395/5262 +f 2393/2395/5263 2394/2396/5263 2392/2394/5263 +f 2395/2397/5264 2394/2396/5264 2393/2395/5264 +f 2389/2391/5265 2393/2395/5266 2391/2393/5267 +f 2396/2398/5268 2397/2399/5269 2398/2400/5270 +f 2398/2400/5270 2397/2399/5269 2399/2401/5271 +f 2400/2402/5272 2398/2400/5273 2399/2401/5274 +f 2400/2402/5275 2401/2403/5275 2398/2400/5275 +f 2402/2404/5276 2400/2402/5272 2399/2401/5274 +f 2402/2404/5277 2403/2405/5278 2400/2402/5279 +f 2404/2406/5280 2397/2399/5281 2405/2407/5282 +f 2397/2399/5281 2404/2406/5280 2399/2401/5283 +f 2406/2408/5284 2402/2404/5285 2407/2409/5286 +f 2408/2410/5287 2341/2343/5288 2409/2411/5289 +f 2408/2410/5290 2409/2411/5290 2407/2409/5290 +f 2410/2412/5291 2407/2409/5292 2409/2411/5293 +f 2406/2408/5294 2407/2409/5292 2410/2412/5291 +f 2341/2343/5295 2411/2413/5295 2409/2411/5295 +f 2412/2414/5296 2385/2387/5296 2382/2384/5296 +f 2382/2384/5297 2385/2387/5297 2384/2386/5297 +f 2382/2384/5298 2384/2386/5298 2339/2341/5298 +f 2382/2384/5299 2339/2341/5299 2413/2415/5299 +f 2412/2414/5300 2382/2384/5300 2383/2385/5300 +f 2340/2342/5301 2413/2415/5301 2338/2340/5301 +f 2414/2416/5302 2402/2404/5303 2401/2403/5304 +f 2401/2403/5304 2402/2404/5303 2399/2401/5305 +f 2401/2403/5306 2399/2401/5306 2396/2398/5306 +f 2396/2398/5307 2399/2401/5308 2404/2406/5309 +f 2414/2416/5310 2401/2403/5311 2403/2405/5278 +f 2397/2399/5312 2396/2398/5313 2415/2417/5314 +f 2355/2357/5315 2365/2367/5315 2362/2364/5315 +f 2355/2357/5316 2362/2364/5316 2358/2360/5316 +f 2358/2360/5317 2362/2364/5317 2366/2368/5317 +f 2358/2360/5318 2360/2362/5220 2361/2363/5219 +f 2355/2357/5224 2361/2363/5319 2363/2365/5225 +f 2358/2360/5320 2416/2418/5321 2359/2361/5322 +f 2417/2419/5323 2395/2397/5323 2393/2395/5323 +f 2417/2419/5324 2393/2395/5324 2390/2392/5324 +f 2390/2392/5325 2393/2395/5326 2388/2390/5327 +f 2388/2390/5327 2393/2395/5326 2387/2389/5328 +f 2387/2389/5329 2393/2395/5266 2389/2391/5265 +f 2390/2392/5259 2391/2393/5260 2392/2394/5261 +f 2417/2419/5330 2392/2394/5331 2394/2396/5332 +f 2402/2404/5333 2410/2412/5333 2418/2420/5333 +f 2418/2420/5334 2410/2412/5334 2409/2411/5334 +f 2418/2420/5335 2409/2411/5335 2342/2344/5335 +f 2342/2344/5336 2409/2411/5336 2411/2413/5336 +f 2342/2344/5337 2341/2343/5288 2408/2410/5287 +f 2418/2420/5338 2408/2410/5339 2407/2409/5286 +f 2342/2344/5340 2419/2421/5340 2343/2345/5340 +f 2374/2376/5341 2412/2414/5341 2378/2380/5341 +f 2378/2380/5342 2412/2414/5342 2379/2381/5342 +f 2378/2380/5343 2379/2381/5344 2375/2377/5345 +f 2375/2377/5345 2379/2381/5344 2380/2382/5346 +f 2375/2377/5347 2377/2379/5347 2378/2380/5347 +f 2376/2378/5348 2375/2377/5348 2420/2422/5348 +f 2421/2423/5349 2352/2354/5349 2356/2358/5349 +f 2422/2424/5350 2355/2357/5350 2350/2352/5350 +f 2350/2352/5351 2355/2357/5351 2354/2356/5351 +f 2350/2352/5352 2354/2356/5352 2421/2423/5352 +f 2421/2423/5353 2354/2356/5353 2352/2354/5353 +f 2422/2424/5354 2350/2352/5207 2349/2351/5206 +f 2421/2423/5355 2351/2353/5356 2353/2355/5357 +f 2348/2350/5358 2350/2352/5358 2353/2355/5358 +f 2352/2354/5216 2351/2353/5359 2423/2425/5360 +f 2365/2367/5361 2374/2376/5361 2371/2373/5361 +f 2371/2373/5362 2374/2376/5362 2369/2371/5362 +f 2371/2373/5363 2369/2371/5364 2370/2372/5365 +f 2370/2372/5365 2369/2371/5364 2336/2338/5366 +f 2370/2372/5367 2336/2338/5367 2424/2426/5367 +f 2365/2367/5234 2373/2375/5238 2369/2371/5235 +f 2373/2375/5238 2371/2373/5368 2372/2374/5239 +f 2337/2339/5369 2370/2372/5370 2424/2426/5371 +f 2347/2349/5372 2344/2346/5372 2346/2348/5372 +f 2425/2427/5373 2426/2428/5374 2427/2429/5375 +f 2428/2430/5376 2429/2431/5377 2430/2432/5378 +f 2377/2379/5244 2379/2381/5379 2374/2376/5245 +f 2380/2382/5249 2377/2379/5248 2376/2378/5380 +f 2431/2433/5381 2374/2376/5245 2379/2381/5379 +f 2381/2383/5382 2384/2386/5382 2383/2385/5382 +f 2401/2403/5311 2400/2402/5279 2403/2405/5278 +f 2407/2409/5286 2402/2404/5285 2418/2420/5338 +f 2338/2340/5383 2413/2415/5383 2386/2388/5383 +f 2413/2415/5384 2339/2341/5384 2387/2389/5384 +f 2413/2415/5385 2340/2342/5385 2382/2384/5385 +f 2415/2417/5314 2405/2407/5386 2397/2399/5312 +f 2396/2398/5307 2404/2406/5309 2415/2417/5387 +f 2396/2398/5388 2398/2400/5388 2401/2403/5388 +f 2416/2418/5321 2367/2369/5389 2359/2361/5322 +f 2358/2360/5390 2366/2368/5390 2416/2418/5390 +f 2358/2360/5391 2361/2363/5391 2355/2357/5391 +f 2388/2390/5392 2387/2389/5392 2432/2434/5392 +f 2389/2391/5393 2388/2390/5393 2433/2435/5393 +f 2433/2435/5394 2388/2390/5394 2432/2434/5394 +f 2387/2389/5395 2389/2391/5395 2433/2435/5395 +f 2390/2392/5396 2392/2394/5396 2417/2419/5396 +f 2341/2343/5198 2343/2345/5200 2411/2413/5397 +f 2342/2344/5398 2411/2413/5398 2419/2421/5398 +f 2342/2344/5399 2408/2410/5399 2418/2420/5399 +f 2420/2422/5400 2375/2377/5400 2434/2436/5400 +f 2420/2422/5401 2380/2382/5249 2376/2378/5380 +f 2375/2377/5402 2380/2382/5402 2434/2436/5402 +f 2423/2425/5360 2357/2359/5217 2352/2354/5216 +f 2421/2423/5403 2356/2358/5403 2423/2425/5403 +f 2423/2425/5404 2351/2353/5356 2421/2423/5355 +f 2421/2423/5355 2353/2355/5357 2350/2352/5405 +f 2337/2339/5369 2424/2426/5371 2335/2337/5406 +f 2373/2375/5407 2365/2367/5407 2371/2373/5407 +f 2435/2437/5408 2436/2438/5409 2437/2439/5410 +f 2437/2439/5410 2436/2438/5409 2438/2440/5411 +f 2439/2441/5412 2440/2442/5413 2441/2443/5414 +f 2441/2443/5414 2440/2442/5413 2442/2444/5415 +f 2427/2429/5375 2443/2445/5416 2425/2427/5373 +f 2425/2427/5373 2443/2445/5416 2444/2446/5417 +f 2445/2447/5418 2446/2448/5418 2447/2449/5418 +f 2446/2448/5419 2429/2431/5420 2448/2450/5421 +f 2448/2450/5421 2429/2431/5420 2428/2430/5422 +f 2449/2451/5423 2430/2432/5378 2450/2452/5424 +f 2450/2452/5424 2430/2432/5378 2429/2431/5377 +f 2451/2453/5425 2406/2408/5426 2410/2412/5427 +f 2451/2453/5425 2410/2412/5427 2452/2454/5428 +f 2452/2454/5428 2411/2413/5429 2343/2345/5430 +f 2452/2454/5428 2343/2345/5430 2419/2421/5431 +f 2402/2404/5432 2419/2421/5433 2410/2412/5427 +f 2410/2412/5427 2419/2421/5433 2411/2413/5429 +f 2410/2412/5427 2411/2413/5429 2452/2454/5428 +f 2453/2455/5434 2402/2404/5435 2406/2408/5426 +f 2432/2434/5436 2405/2407/5437 2415/2417/5438 +f 2419/2421/5439 2405/2407/5437 2432/2434/5436 +f 2432/2434/5436 2415/2417/5438 2433/2435/5440 +f 2433/2435/5440 2415/2417/5438 2402/2404/5441 +f 2402/2404/5442 2415/2417/5442 2404/2406/5442 +f 2402/2404/5443 2404/2406/5443 2419/2421/5443 +f 2419/2421/5439 2404/2406/5444 2405/2407/5437 +f 2453/2455/5434 2414/2416/5445 2403/2405/5446 +f 2453/2455/5434 2403/2405/5446 2402/2404/5435 +f 2433/2435/5440 2402/2404/5441 2414/2416/5445 +f 2433/2435/5440 2414/2416/5445 2453/2455/5434 +f 2454/2456/5447 2417/2419/5330 2453/2455/5448 +f 2453/2455/5448 2417/2419/5330 2394/2396/5332 +f 2453/2455/5434 2394/2396/5449 2433/2435/5440 +f 2433/2435/5450 2394/2396/5450 2395/2397/5450 +f 2433/2435/5451 2395/2397/5452 2387/2389/5453 +f 2387/2389/5453 2395/2397/5452 2417/2419/5330 +f 2387/2389/5453 2417/2419/5330 2454/2456/5447 +f 2386/2388/5454 2413/2415/5455 2455/2457/5456 +f 2432/2434/5457 2386/2388/5454 2455/2457/5456 +f 2455/2457/5458 2413/2415/5458 2412/2414/5458 +f 2412/2414/5459 2413/2415/5460 2387/2389/5461 +f 2432/2434/5457 2387/2389/5462 2386/2388/5454 +f 2454/2456/5463 2412/2414/5463 2383/2385/5463 +f 2454/2456/5464 2383/2385/5464 2387/2389/5464 +f 2387/2389/5465 2383/2385/5465 2385/2387/5465 +f 2387/2389/5461 2385/2387/5466 2412/2414/5459 +f 2455/2457/5467 2420/2422/5467 2434/2436/5467 +f 2374/2376/5468 2434/2436/5468 2412/2414/5468 +f 2412/2414/5469 2434/2436/5469 2380/2382/5469 +f 2412/2414/5470 2380/2382/5470 2455/2457/5470 +f 2455/2457/5471 2380/2382/5471 2420/2422/5471 +f 2456/2458/5472 2374/2376/5245 2431/2433/5381 +f 2456/2458/5472 2431/2433/5381 2454/2456/5473 +f 2454/2456/5473 2431/2433/5381 2379/2381/5379 +f 2454/2456/5473 2379/2381/5379 2412/2414/5474 +f 2434/2436/5475 2335/2337/5406 2367/2369/5476 +f 2367/2369/5476 2335/2337/5406 2424/2426/5371 +f 2367/2369/5477 2424/2426/5478 2365/2367/5479 +f 2365/2367/5479 2424/2426/5478 2374/2376/5480 +f 2374/2376/5481 2424/2426/5481 2336/2338/5481 +f 2374/2376/5482 2336/2338/5482 2434/2436/5482 +f 2434/2436/5475 2336/2338/5483 2335/2337/5406 +f 2456/2458/5472 2365/2367/5484 2368/2370/5485 +f 2456/2458/5472 2368/2370/5485 2374/2376/5245 +f 2453/2455/5434 2406/2408/5426 2451/2453/5425 +f 2356/2358/5486 2367/2369/5389 2416/2418/5321 +f 2356/2358/5487 2416/2418/5488 2355/2357/5489 +f 2355/2357/5489 2416/2418/5488 2365/2367/5490 +f 2365/2367/5491 2416/2418/5491 2366/2368/5491 +f 2365/2367/5492 2366/2368/5228 2367/2369/5230 +f 2355/2357/5224 2364/2366/5223 2456/2458/5493 +f 2456/2458/5472 2364/2366/5494 2365/2367/5484 +f 2356/2358/5215 2357/2359/5217 2457/2459/5495 +f 2457/2459/5496 2357/2359/5497 2423/2425/5498 +f 2457/2459/5496 2423/2425/5498 2355/2357/5489 +f 2355/2357/5489 2423/2425/5498 2356/2358/5487 +f 2456/2458/5499 2422/2424/5499 2349/2351/5499 +f 2456/2458/5493 2349/2351/5500 2355/2357/5224 +f 2457/2459/5496 2355/2357/5489 2422/2424/5501 +f 2457/2459/5496 2422/2424/5501 2456/2458/5502 +f 2356/2358/5503 2457/2459/5503 2447/2449/5503 +f 2356/2358/5504 2447/2449/5505 2367/2369/5506 +f 2446/2448/5507 2452/2454/5507 2419/2421/5507 +f 2446/2448/5508 2419/2421/5508 2432/2434/5508 +f 2446/2448/5509 2432/2434/5509 2455/2457/5509 +f 2446/2448/5510 2455/2457/5510 2447/2449/5510 +f 2447/2449/5511 2455/2457/5511 2434/2436/5511 +f 2447/2449/5505 2434/2436/5512 2367/2369/5506 +f 2458/2460/5513 2426/2428/5514 2445/2447/5515 +f 2445/2447/5516 2426/2428/5516 2425/2427/5516 +f 2456/2458/5517 2454/2456/5518 2451/2453/5519 +f 2451/2453/5519 2454/2456/5518 2453/2455/5520 +f 2452/2454/5521 2446/2448/5521 2451/2453/5522 +f 2347/2349/5523 2448/2450/5524 2345/2347/5525 +f 2345/2347/5202 2448/2450/5526 2442/2444/5527 +f 2345/2347/5202 2442/2444/5527 2346/2348/5203 +f 2346/2348/5203 2442/2444/5527 2459/2461/5528 +f 2451/2453/5522 2446/2448/5521 2448/2450/5524 +f 2451/2453/5522 2448/2450/5524 2347/2349/5523 +f 2451/2453/5522 2347/2349/5523 2346/2348/5529 +f 2451/2453/5530 2346/2348/5203 2459/2461/5528 +f 2448/2450/5421 2428/2430/5422 2442/2444/5531 +f 2442/2444/5531 2428/2430/5422 2430/2432/5532 +f 2427/2429/5375 2435/2437/5533 2443/2445/5416 +f 2444/2446/5534 2450/2452/5534 2425/2427/5535 +f 2425/2427/5535 2450/2452/5534 2429/2431/5536 +f 2425/2427/5535 2429/2431/5536 2445/2447/5537 +f 2445/2447/5537 2429/2431/5536 2446/2448/5538 +f 2430/2432/5378 2449/2451/5423 2439/2441/5539 +f 2449/2451/5540 2460/2462/5540 2439/2441/5540 +f 2443/2445/5541 2435/2437/5542 2461/2463/5543 +f 2458/2460/5513 2438/2440/5544 2426/2428/5514 +f 2426/2428/5514 2438/2440/5544 2427/2429/5545 +f 2462/2464/5546 2457/2459/5547 2456/2458/5548 +f 2462/2464/5546 2456/2458/5548 2463/2465/5549 +f 2462/2464/5546 2463/2465/5549 2464/2466/5550 +f 2464/2466/5550 2463/2465/5549 2438/2440/5551 +f 2464/2466/5550 2438/2440/5551 2458/2460/5552 +f 2464/2466/5550 2458/2460/5552 2462/2464/5546 +f 2462/2464/5546 2458/2460/5552 2457/2459/5547 +f 2457/2459/5547 2458/2460/5552 2445/2447/5553 +f 2457/2459/5547 2445/2447/5553 2447/2449/5554 +f 2456/2458/5555 2451/2453/5556 2463/2465/5557 +f 2463/2465/5557 2451/2453/5556 2459/2461/5558 +f 2465/2467/5559 2437/2439/5410 2438/2440/5411 +f 2438/2440/5411 2463/2465/5560 2465/2467/5559 +f 2465/2467/5559 2463/2465/5560 2466/2468/5561 +f 2435/2437/5408 2437/2439/5410 2460/2462/5562 +f 2460/2462/5563 2437/2439/5563 2440/2442/5563 +f 2439/2441/5412 2460/2462/5564 2440/2442/5413 +f 2459/2461/5565 2442/2444/5415 2466/2468/5561 +f 2442/2444/5415 2440/2442/5413 2466/2468/5561 +f 2463/2465/5560 2459/2461/5565 2466/2468/5561 +f 2441/2443/5566 2442/2444/5531 2430/2432/5532 +f 2430/2432/5378 2439/2441/5539 2441/2443/5567 +f 2444/2446/5568 2443/2445/5541 2461/2463/5543 +f 2450/2452/5569 2444/2446/5570 2449/2451/5571 +f 2449/2451/5571 2444/2446/5570 2461/2463/5572 +f 2449/2451/5571 2461/2463/5572 2460/2462/5573 +f 2461/2463/5543 2435/2437/5542 2460/2462/5574 +f 2427/2429/5375 2436/2438/5575 2435/2437/5533 +f 2427/2429/5545 2438/2440/5544 2436/2438/5576 +f 2465/2467/5577 2467/2469/5577 2437/2439/5577 +f 2466/2468/5578 2440/2442/5578 2468/2470/5578 +f 2467/2469/5579 2468/2470/5580 2437/2439/5581 +f 2437/2439/5581 2468/2470/5580 2440/2442/5582 +f 2467/2469/5583 2465/2467/5584 2469/2471/5585 +f 2466/2468/5586 2468/2470/5587 2470/2472/5588 +f 2469/2471/5585 2471/2473/5589 2467/2469/5583 +f 2472/2474/5590 2469/2471/5591 2466/2468/5592 +f 2466/2468/5592 2469/2471/5591 2465/2467/5593 +f 2470/2472/5588 2472/2474/5594 2466/2468/5586 +f 2471/2473/5595 2470/2472/5596 2467/2469/5597 +f 2467/2469/5597 2470/2472/5596 2468/2470/5598 +f 2473/2475/5599 2474/2476/5600 2475/2477/5601 +f 2473/2475/5599 2476/2478/5602 2474/2476/5600 +f 2477/2479/5603 2478/2480/5604 2479/2481/5605 +f 2479/2481/5605 2478/2480/5604 2480/2482/5606 +f 2481/2483/5607 2480/2482/5606 2482/2484/5608 +f 2482/2484/5608 2480/2482/5606 2483/2485/5609 +f 2484/2486/5610 2483/2485/5609 2485/2487/5611 +f 2485/2487/5611 2483/2485/5609 2486/2488/5612 +f 2487/2489/5613 2486/2488/5612 2488/2490/5614 +f 2488/2490/5614 2486/2488/5612 2489/2491/5615 +f 2490/2492/5616 2491/2493/5617 2492/2494/5618 +f 2492/2494/5618 2491/2493/5617 2493/2495/5619 +f 2494/2496/5620 2476/2478/5621 2473/2475/5622 +f 2495/2497/5613 2496/2498/5623 2497/2499/5624 +f 2497/2499/5624 2496/2498/5623 2498/2500/5625 +f 2499/2501/5626 2500/2502/5627 2501/2503/5628 +f 2501/2503/5628 2500/2502/5627 2496/2498/5623 +f 2502/2504/5629 2503/2505/5630 2504/2506/5631 +f 2504/2506/5631 2503/2505/5630 2500/2502/5627 +f 2505/2507/5632 2506/2508/5633 2507/2509/5634 +f 2507/2509/5634 2506/2508/5633 2503/2505/5630 +f 2508/2510/5635 2509/2511/5636 2510/2512/5637 +f 2510/2512/5637 2509/2511/5636 2511/2513/5638 +f 2512/2514/5639 2513/2515/5640 2514/2516/5641 +f 2515/2517/5642 2516/2518/5643 2474/2476/5644 +f 2474/2476/5644 2516/2518/5643 2475/2477/5645 +f 2517/2519/5646 2518/2520/5646 2519/2521/5646 +f 2520/2522/5647 2521/2523/5648 2522/2524/5649 +f 2521/2523/5648 2520/2522/5647 2523/2525/5650 +f 2521/2523/5651 2524/2526/5652 2525/2527/5653 +f 2521/2523/5651 2525/2527/5653 2522/2524/5654 +f 2523/2525/5655 2526/2528/5655 2521/2523/5655 +f 2527/2529/5656 2518/2520/5657 2528/2530/5658 +f 2528/2530/5658 2518/2520/5657 2517/2519/5659 +f 2529/2531/5660 2517/2519/5661 2530/2532/5662 +f 2529/2531/5660 2530/2532/5662 2519/2521/5663 +f 2488/2490/5664 2491/2493/5664 2487/2489/5664 +f 2487/2489/5665 2491/2493/5665 2531/2533/5665 +f 2487/2489/5666 2531/2533/5666 2532/2534/5666 +f 2532/2534/5667 2491/2493/5668 2488/2490/5669 +f 2532/2534/5667 2488/2490/5669 2533/2535/5670 +f 2533/2535/5671 2488/2490/5671 2489/2491/5671 +f 2485/2487/5672 2534/2536/5673 2484/2486/5674 +f 2484/2486/5674 2534/2536/5673 2535/2537/5675 +f 2484/2486/5676 2535/2537/5677 2536/2538/5678 +f 2536/2538/5679 2534/2536/5680 2485/2487/5681 +f 2536/2538/5679 2485/2487/5681 2537/2539/5670 +f 2537/2539/5682 2485/2487/5682 2486/2488/5682 +f 2482/2484/5683 2535/2537/5683 2481/2483/5683 +f 2538/2540/5684 2539/2541/5685 2482/2484/5686 +f 2482/2484/5686 2539/2541/5685 2535/2537/5687 +f 2540/2542/5688 2482/2484/5689 2483/2485/5690 +f 2479/2481/5691 2539/2541/5691 2477/2479/5691 +f 2541/2543/5692 2539/2541/5693 2479/2481/5694 +f 2541/2543/5695 2479/2481/5695 2542/2544/5695 +f 2542/2544/5696 2479/2481/5696 2480/2482/5696 +f 2543/2545/5697 2478/2480/5697 2544/2546/5697 +f 2543/2545/5698 2544/2546/5699 2492/2494/5700 +f 2492/2494/5700 2544/2546/5699 2490/2492/5701 +f 2493/2495/5702 2491/2493/5703 2489/2491/5704 +f 2493/2495/5702 2489/2491/5704 2545/2547/5705 +f 2541/2543/5706 2542/2544/5707 2477/2479/5708 +f 2477/2479/5708 2542/2544/5707 2478/2480/5709 +f 2482/2484/5689 2540/2542/5688 2538/2540/5710 +f 2538/2540/5710 2540/2542/5688 2480/2482/5711 +f 2538/2540/5712 2480/2482/5712 2481/2483/5712 +f 2538/2540/5713 2481/2483/5713 2539/2541/5713 +f 2536/2538/5714 2537/2539/5715 2484/2486/5716 +f 2484/2486/5716 2537/2539/5715 2483/2485/5717 +f 2532/2534/5714 2533/2535/5718 2487/2489/5719 +f 2487/2489/5719 2533/2535/5718 2486/2488/5720 +f 2546/2548/5721 2547/2549/5722 2548/2550/5723 +f 2494/2496/5620 2549/2551/5724 2476/2478/5621 +f 2476/2478/5621 2549/2551/5724 2550/2552/5725 +f 2551/2553/5726 2552/2554/5727 2553/2555/5728 +f 2551/2553/5726 2553/2555/5728 2554/2556/5729 +f 2555/2557/5730 2556/2558/5730 2557/2559/5730 +f 2555/2557/5731 2557/2559/5731 2558/2560/5731 +f 2559/2561/5732 2560/2562/5732 2561/2563/5732 +f 2507/2509/5733 2562/2564/5734 2505/2507/5735 +f 2563/2565/5736 2564/2566/5737 2507/2509/5738 +f 2507/2509/5738 2564/2566/5737 2562/2564/5739 +f 2565/2567/5740 2507/2509/5741 2503/2505/5742 +f 2566/2568/5743 2502/2504/5743 2567/2569/5743 +f 2567/2569/5744 2504/2506/5744 2566/2568/5744 +f 2566/2568/5745 2504/2506/5745 2568/2570/5745 +f 2568/2570/5746 2504/2506/5746 2500/2502/5746 +f 2501/2503/5747 2569/2571/5747 2499/2501/5747 +f 2567/2569/5748 2569/2571/5748 2501/2503/5748 +f 2567/2569/5749 2501/2503/5749 2570/2572/5749 +f 2570/2572/5682 2501/2503/5682 2496/2498/5682 +f 2497/2499/5750 2509/2511/5751 2495/2497/5752 +f 2495/2497/5752 2509/2511/5751 2569/2571/5753 +f 2495/2497/5754 2569/2571/5754 2571/2573/5754 +f 2571/2573/5755 2509/2511/5756 2497/2499/5757 +f 2571/2573/5755 2497/2499/5757 2572/2574/5670 +f 2572/2574/5758 2497/2499/5758 2498/2500/5758 +f 2573/2575/5759 2506/2508/5760 2564/2566/5761 +f 2573/2575/5759 2564/2566/5761 2510/2512/5762 +f 2510/2512/5762 2564/2566/5761 2508/2510/5763 +f 2508/2510/5764 2562/2564/5734 2509/2511/5765 +f 2511/2513/5766 2509/2511/5767 2498/2500/5768 +f 2511/2513/5766 2498/2500/5768 2574/2576/5769 +f 2571/2573/5714 2572/2574/5718 2495/2497/5719 +f 2495/2497/5719 2572/2574/5718 2496/2498/5720 +f 2567/2569/5770 2570/2572/5771 2499/2501/5772 +f 2499/2501/5772 2570/2572/5771 2500/2502/5773 +f 2566/2568/5774 2568/2570/5775 2502/2504/5776 +f 2502/2504/5776 2568/2570/5775 2503/2505/5777 +f 2507/2509/5741 2565/2567/5740 2563/2565/5778 +f 2563/2565/5778 2565/2567/5740 2506/2508/5779 +f 2563/2565/5780 2506/2508/5780 2505/2507/5780 +f 2563/2565/5781 2505/2507/5782 2564/2566/5783 +f 2575/2577/5784 2576/2578/5785 2552/2554/5786 +f 2561/2563/5787 2560/2562/5787 2556/2558/5787 +f 2513/2515/5640 2512/2514/5639 2577/2579/5788 +f 2578/2580/5789 2579/2581/5790 2580/2582/5791 +f 2581/2583/5792 2582/2584/5793 2514/2516/5794 +f 2514/2516/5794 2582/2584/5793 2512/2514/5795 +f 2578/2580/5796 2583/2585/5797 2579/2581/5798 +f 2579/2581/5798 2583/2585/5797 2584/2586/5799 +f 2519/2521/5800 2518/2520/5801 2529/2531/5802 +f 2529/2531/5802 2518/2520/5801 2585/2587/5803 +f 2585/2587/5803 2518/2520/5801 2527/2529/5804 +f 2524/2526/5805 2523/2525/5806 2525/2527/5807 +f 2525/2527/5807 2523/2525/5806 2520/2522/5808 +f 2524/2526/5809 2521/2523/5809 2526/2528/5809 +f 2517/2519/5810 2529/2531/5811 2528/2530/5812 +f 2528/2530/5812 2529/2531/5811 2585/2587/5813 +f 2478/2480/5604 2489/2491/5615 2486/2488/5612 +f 2478/2480/5604 2486/2488/5612 2483/2485/5609 +f 2478/2480/5604 2483/2485/5609 2480/2482/5606 +f 2542/2544/5814 2480/2482/528 2539/2541/5815 +f 2542/2544/5814 2539/2541/5815 2478/2480/5816 +f 2478/2480/5816 2539/2541/5815 2544/2546/5817 +f 2540/2542/528 2483/2485/528 2535/2537/528 +f 2540/2542/528 2535/2537/528 2480/2482/528 +f 2480/2482/528 2535/2537/528 2539/2541/5815 +f 2537/2539/528 2486/2488/528 2531/2533/528 +f 2537/2539/528 2531/2533/528 2483/2485/528 +f 2483/2485/528 2531/2533/528 2535/2537/528 +f 2533/2535/5818 2489/2491/5819 2586/2588/5820 +f 2533/2535/5818 2586/2588/5820 2486/2488/528 +f 2486/2488/528 2586/2588/5820 2531/2533/528 +f 2539/2541/5821 2490/2492/5821 2477/2479/5821 +f 2477/2479/5822 2490/2492/5822 2544/2546/5822 +f 2477/2479/5823 2544/2546/5823 2541/2543/5823 +f 2541/2543/5692 2544/2546/5824 2539/2541/5693 +f 2490/2492/5825 2539/2541/5825 2481/2483/5825 +f 2490/2492/5826 2481/2483/5826 2491/2493/5826 +f 2491/2493/5827 2481/2483/5827 2535/2537/5827 +f 2536/2538/5678 2535/2537/5677 2531/2533/5828 +f 2536/2538/5829 2531/2533/5829 2534/2536/5829 +f 2534/2536/5830 2531/2533/5831 2491/2493/5832 +f 2534/2536/5830 2491/2493/5832 2535/2537/5833 +f 2532/2534/5834 2531/2533/5834 2586/2588/5834 +f 2532/2534/5835 2586/2588/5820 2491/2493/5836 +f 2586/2588/5820 2489/2491/5819 2491/2493/5836 +f 2493/2495/5837 2545/2547/5838 2492/2494/5839 +f 2492/2494/5839 2545/2547/5838 2543/2545/5840 +f 2587/2589/5841 2588/2590/5842 2589/2591/5843 +f 2587/2589/5841 2589/2591/5843 2590/2592/5844 +f 2591/2593/5845 2590/2592/5846 2589/2591/5847 +f 2547/2549/5722 2546/2548/5721 2592/2594/5848 +f 2593/2595/5849 2594/2596/5850 2548/2550/5851 +f 2548/2550/5851 2594/2596/5850 2546/2548/5852 +f 2595/2597/5853 2596/2598/5854 2597/2599/5855 +f 2595/2597/5856 2598/2600/5857 2596/2598/5858 +f 2596/2598/5858 2598/2600/5857 2599/2601/5859 +f 2556/2558/5860 2558/2560/5861 2600/2602/5862 +f 2560/2562/5863 2559/2561/5864 2555/2557/5865 +f 2560/2562/5863 2555/2557/5865 2558/2560/5866 +f 2556/2558/5867 2600/2602/5867 2557/2559/5867 +f 2601/2603/5868 2561/2563/5868 2556/2558/5868 +f 2602/2604/5869 2553/2555/5870 2576/2578/5871 +f 2551/2553/5872 2576/2578/5873 2575/2577/5874 +f 2602/2604/5875 2576/2578/5873 2554/2556/5876 +f 2554/2556/5876 2576/2578/5873 2551/2553/5872 +f 2575/2577/5877 2603/2605/5877 2551/2553/5877 +f 2551/2553/5878 2603/2605/5879 2552/2554/5880 +f 2559/2561/5881 2601/2603/5882 2555/2557/5883 +f 2555/2557/5883 2601/2603/5882 2556/2558/5884 +f 2604/2606/5885 2605/2607/5885 2506/2508/5885 +f 2606/2608/5886 2506/2508/5886 2607/2609/5886 +f 2607/2609/5887 2506/2508/5887 2605/2607/5887 +f 2604/2606/5888 2606/2608/5889 2605/2607/5890 +f 2605/2607/5890 2606/2608/5889 2607/2609/5891 +f 2498/2500/5625 2496/2498/5623 2500/2502/5627 +f 2498/2500/5625 2500/2502/5627 2503/2505/5630 +f 2498/2500/5625 2503/2505/5630 2506/2508/5633 +f 2506/2508/5892 2565/2567/5893 2564/2566/5894 +f 2568/2570/5895 2500/2502/5896 2567/2569/5897 +f 2568/2570/5895 2567/2569/5897 2503/2505/5898 +f 2503/2505/5898 2567/2569/5897 2565/2567/5899 +f 2570/2572/528 2496/2498/528 2569/2571/5900 +f 2570/2572/528 2569/2571/5900 2500/2502/5896 +f 2500/2502/5896 2569/2571/5900 2567/2569/5897 +f 2572/2574/5901 2498/2500/5902 2608/2610/5903 +f 2572/2574/5901 2608/2610/5903 2496/2498/528 +f 2496/2498/528 2608/2610/5903 2569/2571/5900 +f 2505/2507/5735 2562/2564/5734 2508/2510/5764 +f 2505/2507/5782 2508/2510/5904 2564/2566/5783 +f 2562/2564/5905 2564/2566/5894 2565/2567/5893 +f 2565/2567/5899 2567/2569/5897 2502/2504/5906 +f 2565/2567/5893 2502/2504/5629 2562/2564/5905 +f 2562/2564/5905 2502/2504/5629 2504/2506/5631 +f 2569/2571/5907 2509/2511/5907 2499/2501/5907 +f 2499/2501/5908 2509/2511/5765 2562/2564/5734 +f 2499/2501/5909 2562/2564/5909 2567/2569/5909 +f 2567/2569/5910 2562/2564/5910 2504/2506/5910 +f 2571/2573/5911 2569/2571/5911 2608/2610/5911 +f 2571/2573/5912 2608/2610/5903 2509/2511/5913 +f 2608/2610/5903 2498/2500/5902 2509/2511/5913 +f 2576/2578/5914 2553/2555/5915 2574/2576/5916 +f 2574/2576/5917 2553/2555/5728 2511/2513/5918 +f 2511/2513/5918 2553/2555/5728 2552/2554/5727 +f 2511/2513/5919 2552/2554/5919 2576/2578/5919 +f 2556/2558/5920 2560/2562/5921 2510/2512/5922 +f 2510/2512/5922 2560/2562/5921 2558/2560/5923 +f 2510/2512/5924 2558/2560/5924 2573/2575/5924 +f 2573/2575/5925 2558/2560/5926 2556/2558/5920 +f 2510/2512/5922 2511/2513/5927 2556/2558/5920 +f 2556/2558/5920 2511/2513/5927 2576/2578/5914 +f 2556/2558/5920 2576/2578/5914 2573/2575/5925 +f 2573/2575/5925 2576/2578/5914 2574/2576/5916 +f 2514/2516/5928 2513/2515/5928 2609/2611/5928 +f 2610/2612/5929 2514/2516/5930 2609/2611/5931 +f 2610/2612/5929 2609/2611/5931 2577/2579/5932 +f 2610/2612/5933 2577/2579/5934 2512/2514/5935 +f 2610/2612/5933 2512/2514/5935 2611/2613/5936 +f 2611/2613/5936 2512/2514/5935 2582/2584/5937 +f 2612/2614/5938 2578/2580/5939 2613/2615/5940 +f 2612/2614/5938 2613/2615/5940 2580/2582/5941 +f 2612/2614/5942 2580/2582/5943 2579/2581/5944 +f 2612/2614/5942 2579/2581/5944 2584/2586/5945 +f 2614/2616/5946 2583/2585/5946 2578/2580/5946 +f 2611/2613/5947 2581/2583/5948 2610/2612/5949 +f 2610/2612/5949 2581/2583/5948 2514/2516/5950 +f 2584/2586/5951 2614/2616/5952 2612/2614/5953 +f 2612/2614/5953 2614/2616/5952 2578/2580/5954 +f 2523/2525/5955 2585/2587/5956 2527/2529/5957 +f 2530/2532/5958 2517/2519/5958 2615/2617/5958 +f 2615/2617/5959 2517/2519/5960 2519/2521/5961 +f 2615/2617/5959 2519/2521/5961 2616/2618/5962 +f 2522/2524/5963 2524/2526/5964 2526/2528/5965 +f 2523/2525/5955 2524/2526/5966 2585/2587/5956 +f 2585/2587/5956 2524/2526/5966 2522/2524/5967 +f 2585/2587/5968 2522/2524/5969 2528/2530/5970 +f 2528/2530/5970 2522/2524/5969 2525/2527/5971 +f 2519/2521/5961 2520/2522/5972 2616/2618/5962 +f 2616/2618/5962 2520/2522/5972 2522/2524/5963 +f 2526/2528/5965 2515/2517/5973 2616/2618/5962 +f 2526/2528/5965 2616/2618/5962 2522/2524/5963 +f 2526/2528/5974 2523/2525/5974 2515/2517/5974 +f 2515/2517/5642 2523/2525/5975 2527/2529/5976 +f 2515/2517/5642 2527/2529/5976 2516/2518/5643 +f 2516/2518/5643 2527/2529/5976 2528/2530/5970 +f 2615/2617/5977 2516/2518/5643 2530/2532/5978 +f 2530/2532/5978 2516/2518/5643 2528/2530/5970 +f 2530/2532/5978 2528/2530/5970 2519/2521/5961 +f 2519/2521/5961 2528/2530/5970 2525/2527/5971 +f 2519/2521/5961 2525/2527/5971 2520/2522/5972 +f 2616/2618/5979 2617/2619/5980 2489/2491/5981 +f 2489/2491/5981 2617/2619/5980 2545/2547/5982 +f 2616/2618/5979 2489/2491/5981 2478/2480/5983 +f 2616/2618/5979 2478/2480/5983 2615/2617/5984 +f 2615/2617/5984 2478/2480/5983 2618/2620/5985 +f 2618/2620/5985 2478/2480/5983 2543/2545/5986 +f 2618/2620/5985 2543/2545/5986 2617/2619/5980 +f 2617/2619/5980 2543/2545/5986 2545/2547/5982 +f 2617/2619/5987 2619/2621/5988 2620/2622/5989 +f 2591/2593/5990 2589/2591/5990 2588/2590/5990 +f 2590/2592/5846 2591/2593/5845 2587/2589/5991 +f 2621/2623/5992 2592/2594/5993 2622/2624/5994 +f 2621/2623/5992 2622/2624/5994 2548/2550/5995 +f 2622/2624/5996 2592/2594/5997 2546/2548/5998 +f 2622/2624/5996 2546/2548/5998 2623/2625/5999 +f 2623/2625/5999 2546/2548/5998 2594/2596/6000 +f 2548/2550/6001 2547/2549/6001 2621/2623/6001 +f 2548/2550/6002 2622/2624/6003 2593/2595/6004 +f 2593/2595/6004 2622/2624/6003 2623/2625/6005 +f 2624/2626/6006 2598/2600/6006 2595/2597/6006 +f 2625/2627/6007 2597/2599/6008 2626/2628/6009 +f 2625/2627/6007 2626/2628/6009 2595/2597/6010 +f 2626/2628/6011 2597/2599/6012 2596/2598/6013 +f 2626/2628/6011 2596/2598/6013 2599/2601/6014 +f 2595/2597/6015 2626/2628/6016 2624/2626/6017 +f 2624/2626/6017 2626/2628/6016 2599/2601/6018 +f 2600/2602/5862 2558/2560/5861 2627/2629/6019 +f 2554/2556/6020 2561/2563/6021 2602/2604/5869 +f 2602/2604/5869 2561/2563/6021 2601/2603/6022 +f 2575/2577/5784 2552/2554/5786 2550/2552/5725 +f 2550/2552/6023 2552/2554/5880 2603/2605/5879 +f 2628/2630/6024 2553/2555/5870 2602/2604/5869 +f 2627/2629/6019 2628/2630/6024 2600/2602/5862 +f 2600/2602/5862 2628/2630/6024 2602/2604/5869 +f 2600/2602/5862 2602/2604/5869 2557/2559/6025 +f 2557/2559/6025 2602/2604/5869 2601/2603/6022 +f 2557/2559/6025 2601/2603/6022 2558/2560/6026 +f 2558/2560/6026 2601/2603/6022 2559/2561/6027 +f 2627/2629/6028 2558/2560/6026 2559/2561/6027 +f 2627/2629/6028 2559/2561/6027 2549/2551/5724 +f 2549/2551/5724 2559/2561/6027 2561/2563/6021 +f 2550/2552/5725 2549/2551/5724 2575/2577/5784 +f 2575/2577/5784 2549/2551/5724 2561/2563/6021 +f 2575/2577/5784 2561/2563/6021 2554/2556/6020 +f 2575/2577/5784 2554/2556/6020 2603/2605/6029 +f 2603/2605/6029 2554/2556/6020 2553/2555/5870 +f 2603/2605/6029 2553/2555/5870 2550/2552/6030 +f 2550/2552/6030 2553/2555/5870 2628/2630/6024 +f 2606/2608/6031 2498/2500/6032 2506/2508/6033 +f 2574/2576/6034 2498/2500/6032 2628/2630/6035 +f 2628/2630/6035 2498/2500/6032 2606/2608/6031 +f 2627/2629/6036 2573/2575/6037 2628/2630/6035 +f 2628/2630/6035 2573/2575/6037 2574/2576/6034 +f 2604/2606/6038 2506/2508/6039 2627/2629/6036 +f 2627/2629/6036 2506/2508/6039 2573/2575/6037 +f 2604/2606/6040 2629/2631/6041 2630/2632/6042 +f 2631/2633/6043 2516/2518/6044 2615/2617/6045 +f 2631/2633/6043 2615/2617/6045 2632/2634/6046 +f 2632/2634/6046 2615/2617/6045 2618/2620/6047 +f 2632/2634/6046 2618/2620/6047 2633/2635/6048 +f 2633/2635/6048 2634/2636/6049 2632/2634/6046 +f 2632/2634/6046 2634/2636/6049 2631/2633/6043 +f 2631/2633/6043 2634/2636/6049 2516/2518/6044 +f 2617/2619/6050 2578/2580/5789 2580/2582/5791 +f 2617/2619/6051 2620/2622/6052 2614/2616/6053 +f 2513/2515/6054 2577/2579/6055 2618/2620/6056 +f 2611/2613/6057 2582/2584/6058 2633/2635/6059 +f 2580/2582/5791 2609/2611/6060 2513/2515/6054 +f 2580/2582/5791 2513/2515/6054 2617/2619/6050 +f 2617/2619/6050 2513/2515/6054 2618/2620/6056 +f 2578/2580/6061 2617/2619/6061 2613/2615/6061 +f 2613/2615/6062 2617/2619/6051 2614/2616/6053 +f 2613/2615/6062 2614/2616/6053 2580/2582/5791 +f 2580/2582/5791 2614/2616/6053 2584/2586/5799 +f 2580/2582/5791 2584/2586/5799 2609/2611/6060 +f 2609/2611/6060 2584/2586/5799 2581/2583/5792 +f 2609/2611/6060 2581/2583/5792 2577/2579/6055 +f 2577/2579/6055 2581/2583/5792 2611/2613/6057 +f 2577/2579/6055 2611/2613/6057 2618/2620/6056 +f 2611/2613/6057 2633/2635/6059 2618/2620/6056 +f 2582/2584/5793 2581/2583/5792 2633/2635/6063 +f 2633/2635/6063 2581/2583/5792 2584/2586/5799 +f 2633/2635/6063 2584/2586/5799 2620/2622/6052 +f 2620/2622/6052 2584/2586/5799 2583/2585/5797 +f 2620/2622/6052 2583/2585/5797 2614/2616/6053 +f 2515/2517/6064 2635/2637/6065 2616/2618/6066 +f 2616/2618/6066 2635/2637/6065 2617/2619/6067 +f 2617/2619/6067 2635/2637/6065 2636/2638/6068 +f 2617/2619/6067 2636/2638/6068 2619/2621/6069 +f 2635/2637/6065 2515/2517/6064 2636/2638/6068 +f 2636/2638/6068 2515/2517/6064 2619/2621/6069 +f 2637/2639/6070 2587/2589/5841 2606/2608/6071 +f 2606/2608/6071 2587/2589/5841 2628/2630/6072 +f 2628/2630/6073 2587/2589/6073 2591/2593/6073 +f 2628/2630/6074 2591/2593/6074 2550/2552/6074 +f 2591/2593/6075 2588/2590/6075 2550/2552/6075 +f 2550/2552/6076 2588/2590/5842 2638/2640/6077 +f 2638/2640/6077 2588/2590/5842 2587/2589/5841 +f 2638/2640/6077 2587/2589/5841 2637/2639/6070 +f 2599/2601/5859 2593/2595/6078 2597/2599/5855 +f 2547/2549/6079 2592/2594/6080 2606/2608/6081 +f 2625/2627/6082 2595/2597/6082 2604/2606/6082 +f 2604/2606/6083 2595/2597/5853 2597/2599/5855 +f 2639/2641/6084 2637/2639/6085 2594/2596/6086 +f 2599/2601/5859 2597/2599/5855 2624/2626/6087 +f 2594/2596/6086 2637/2639/6085 2623/2625/6088 +f 2604/2606/6089 2630/2632/6090 2624/2626/6087 +f 2604/2606/6089 2624/2626/6087 2625/2627/6091 +f 2625/2627/6091 2624/2626/6087 2597/2599/5855 +f 2594/2596/6086 2593/2595/6078 2639/2641/6084 +f 2639/2641/6084 2593/2595/6078 2599/2601/5859 +f 2639/2641/6084 2599/2601/5859 2630/2632/6090 +f 2630/2632/6090 2599/2601/5859 2598/2600/5857 +f 2630/2632/6090 2598/2600/5857 2624/2626/6087 +f 2621/2623/6092 2593/2595/6078 2592/2594/6080 +f 2592/2594/6080 2593/2595/6078 2623/2625/6088 +f 2592/2594/6080 2623/2625/6088 2606/2608/6081 +f 2606/2608/6081 2623/2625/6088 2637/2639/6085 +f 2597/2599/5855 2593/2595/6078 2621/2623/6092 +f 2597/2599/5855 2621/2623/6092 2547/2549/6079 +f 2597/2599/5855 2547/2549/6079 2604/2606/6083 +f 2604/2606/6083 2547/2549/6079 2606/2608/6081 +f 2629/2631/6093 2604/2606/6094 2640/2642/6095 +f 2640/2642/6095 2604/2606/6094 2641/2643/6096 +f 2641/2643/6096 2604/2606/6094 2627/2629/6097 +f 2641/2643/6096 2627/2629/6097 2549/2551/6098 +f 2641/2643/6096 2549/2551/6098 2640/2642/6095 +f 2640/2642/6095 2549/2551/6098 2629/2631/6093 +f 2475/2477/6099 2516/2518/6044 2642/2644/6100 +f 2642/2644/6100 2516/2518/6044 2634/2636/6049 +f 2642/2644/6100 2634/2636/6049 2633/2635/6048 +f 2620/2622/6052 2643/2645/6101 2633/2635/6063 +f 2633/2635/6063 2643/2645/6101 2642/2644/6102 +f 2619/2621/5988 2643/2645/6103 2620/2622/5989 +f 2515/2517/6064 2474/2476/6104 2619/2621/6069 +f 2619/2621/6069 2474/2476/6104 2643/2645/6105 +f 2476/2478/6106 2550/2552/6076 2644/2646/6107 +f 2644/2646/6107 2550/2552/6076 2638/2640/6077 +f 2644/2646/6107 2638/2640/6077 2637/2639/6070 +f 2645/2647/6108 2644/2646/6109 2639/2641/6084 +f 2644/2646/6109 2637/2639/6085 2639/2641/6084 +f 2639/2641/6084 2630/2632/6090 2645/2647/6108 +f 2629/2631/6041 2645/2647/6110 2630/2632/6042 +f 2549/2551/6098 2494/2496/6111 2629/2631/6093 +f 2629/2631/6093 2494/2496/6111 2645/2647/6112 +f 2473/2475/6113 2645/2647/6113 2494/2496/6113 +f 2476/2478/5602 2644/2646/6114 2646/2648/6115 +f 2647/2649/6116 2643/2645/6117 2474/2476/5600 +f 2647/2649/6116 2474/2476/5600 2476/2478/5602 +f 2647/2649/6116 2476/2478/5602 2646/2648/6115 +f 2646/2648/6115 2644/2646/6114 2648/2650/6118 +f 2648/2650/6118 2644/2646/6114 2645/2647/6119 +f 2475/2477/6120 2642/2644/6121 2649/2651/6122 +f 2649/2651/6122 2642/2644/6121 2647/2649/6116 +f 2647/2649/6116 2642/2644/6121 2643/2645/6117 +f 2648/2650/6123 2475/2477/6120 2649/2651/6122 +f 2648/2650/6118 2645/2647/6119 2473/2475/6124 +f 2648/2650/6123 2473/2475/6125 2475/2477/6120 +f 2650/2652/6126 2648/2650/6127 2651/2653/6128 +f 2651/2653/6128 2648/2650/6127 2649/2651/6129 +f 2651/2653/6130 2649/2651/6131 2652/2654/6132 +f 2652/2654/6132 2649/2651/6131 2647/2649/6133 +f 2652/2654/6134 2647/2649/6135 2653/2655/6136 +f 2653/2655/6136 2647/2649/6135 2646/2648/6137 +f 2653/2655/6138 2646/2648/6139 2650/2652/6140 +f 2650/2652/6140 2646/2648/6139 2648/2650/6141 +f 2654/2656/6142 2331/2333/5182 2655/2657/6143 +f 2655/2657/6143 2331/2333/5182 2329/2331/5180 +f 2656/2658/6144 2332/2334/5183 2654/2656/6145 +f 2654/2656/6145 2332/2334/5183 2331/2333/5186 +f 2657/2659/6146 2334/2336/5189 2656/2658/6147 +f 2656/2658/6147 2334/2336/5189 2332/2334/5188 +f 2655/2657/6148 2329/2331/6149 2657/2659/6150 +f 2657/2659/6150 2329/2331/6149 2334/2336/6151 +f 2658/2660/2173 2659/2661/6152 2660/2662/6153 +f 2658/2660/2173 2661/2663/6154 2662/2664/6155 +f 2658/2660/2173 2660/2662/6153 2661/2663/6154 +f 2663/2665/6156 2660/2662/6157 2664/2666/6158 +f 2664/2666/6159 2660/2662/6160 2659/2661/6161 +f 2664/2666/6159 2659/2661/6161 2665/2667/6162 +f 2665/2667/6163 2659/2661/6164 2658/2660/6165 +f 2665/2667/6163 2658/2660/6165 2666/2668/6166 +f 2666/2668/6167 2658/2660/6168 2662/2664/6169 +f 2666/2668/6167 2662/2664/6169 2667/2669/6170 +f 2667/2669/6171 2662/2664/6172 2661/2663/6173 +f 2667/2669/6171 2661/2663/6173 2668/2670/6174 +f 2668/2670/6175 2661/2663/6176 2663/2665/6177 +f 2663/2665/6177 2661/2663/6176 2660/2662/6178 +f 2669/2671/6179 2670/2672/6180 2667/2669/6170 +f 2667/2669/6170 2670/2672/6180 2666/2668/6167 +f 2668/2670/6174 2669/2671/6181 2667/2669/6171 +f 2671/2673/6182 2669/2671/6182 2663/2665/6182 +f 2663/2665/6177 2669/2671/6183 2668/2670/6175 +f 2672/2674/6184 2671/2673/6185 2664/2666/6158 +f 2664/2666/6158 2671/2673/6185 2663/2665/6156 +f 2665/2667/6162 2672/2674/6186 2664/2666/6159 +f 2670/2672/6187 2672/2674/6187 2666/2668/6187 +f 2666/2668/6166 2672/2674/6188 2665/2667/6163 +f 2671/2673/6189 2672/2674/6190 2669/2671/6190 +f 2669/2671/6190 2672/2674/6190 2670/2672/6190 +f 2673/2675/5534 2674/2676/6191 2675/2677/5534 +f 2675/2677/5534 2676/2678/6192 2673/2675/5534 +f 2677/2679/6193 2676/2678/6194 2678/2680/6195 +f 2678/2680/6195 2676/2678/6194 2675/2677/6196 +f 2678/2680/6197 2675/2677/6198 2679/2681/6199 +f 2679/2681/6200 2675/2677/6201 2674/2676/6202 +f 2679/2681/6200 2674/2676/6202 2680/2682/6203 +f 2680/2682/6204 2674/2676/6205 2673/2675/6206 +f 2680/2682/6204 2673/2675/6206 2681/2683/6207 +f 2681/2683/6208 2673/2675/6209 2682/2684/6210 +f 2682/2684/6210 2673/2675/6209 2676/2678/6211 +f 2682/2684/6212 2676/2678/6213 2677/2679/6214 +f 2680/2682/6203 2683/2685/6215 2679/2681/6200 +f 2684/2686/6216 2683/2685/6217 2681/2683/6207 +f 2681/2683/6207 2683/2685/6217 2680/2682/6204 +f 2682/2684/6210 2684/2686/6218 2681/2683/6208 +f 2685/2687/6219 2684/2686/6220 2677/2679/6214 +f 2677/2679/6214 2684/2686/6220 2682/2684/6212 +f 2678/2680/6195 2685/2687/6221 2677/2679/6193 +f 2683/2685/6222 2685/2687/6223 2679/2681/6199 +f 2679/2681/6199 2685/2687/6223 2678/2680/6197 +f 2684/2686/6224 2685/2687/6224 2683/2685/6224 +f 2037/2039/6225 2047/2049/6226 2040/2042/6227 +f 2062/2064/6228 2063/2065/6229 2038/2040/6230 +f 2037/2039/6225 2063/2065/6229 2066/2068/6231 +f 2038/2040/6230 2045/2047/6232 2064/2066/6233 +f 2037/2039/6225 2066/2068/6231 2047/2049/6226 +f 2062/2064/6228 2038/2040/6230 2064/2066/6233 +f 2058/2060/6234 2037/2039/6225 2060/2062/6235 +f 2047/2049/6226 2048/2050/6236 2052/2054/6237 +f 2045/2047/6232 2065/2067/6238 2064/2066/6233 +f 2047/2049/6226 2065/2067/6238 2045/2047/6232 +f 2061/2063/6239 2040/2042/6227 2035/2037/6240 +f 2037/2039/6225 2058/2060/6234 2035/2037/6240 +f 2065/2067/6238 2047/2049/6226 2066/2068/6231 +f 2060/2062/6235 2037/2039/6225 2040/2042/6227 +f 2061/2063/6239 2060/2062/6235 2040/2042/6227 +f 2040/2042/6227 2053/2055/6241 2056/2058/6242 +f 2039/2041/6243 2040/2042/6227 2056/2058/6242 +f 2052/2054/6237 2048/2050/6236 2051/2053/6244 +f 2052/2054/6237 2053/2055/6241 2047/2049/6226 +f 2039/2041/6243 2056/2058/6242 2057/2059/6245 +f 2053/2055/6241 2040/2042/6227 2047/2049/6226 +f 2041/2043/6246 2055/2057/6247 2056/2058/6242 +f 2037/2039/6225 2038/2040/6230 2063/2065/6229 +f 2043/2045/6248 2041/2043/6246 2049/2051/6249 +f 2035/2037/6240 2059/2061/6250 2061/2063/6239 +f 2043/2045/6248 2051/2053/6244 2048/2050/6236 +f 2049/2051/6249 2041/2043/6246 2053/2055/6241 +f 2054/2056/6251 2039/2041/6243 2057/2059/6245 +f 2041/2043/6246 2042/2044/6252 2055/2057/6247 +f 2049/2051/6249 2050/2052/6253 2043/2045/6248 +f 2042/2044/6252 2039/2041/6243 2054/2056/6251 +f 2041/2043/6246 2056/2058/6242 2053/2055/6241 +f 2054/2056/6251 2055/2057/6247 2042/2044/6252 +f 2043/2045/6248 2050/2052/6253 2051/2053/6244 +f 2035/2037/6240 2058/2060/6234 2059/2061/6250 +f 2320/2322/6254 2315/2317/6255 2314/2316/6256 +f 2320/2322/6254 2314/2316/6256 2321/2323/6257 +f 2324/2326/6258 2334/2336/6259 2328/2330/6260 +f 2328/2330/6260 2334/2336/6259 2329/2331/6260 +f 2324/2326/6261 2328/2330/6262 2325/2327/3031 +f 2325/2327/3031 2328/2330/6262 2327/2329/3031 +f 2324/2326/6261 2325/2327/3031 2322/2324/3031 +f 2283/2285/6263 2297/2299/6264 2281/2283/6265 +f 2333/2335/6266 2279/2281/6267 2321/2323/6268 +f 2299/2301/6269 2297/2299/6264 2283/2285/6263 +f 2299/2301/6269 2319/2321/6270 2279/2281/6267 +f 2305/2307/6271 2302/2304/6272 2323/2325/6273 +f 2294/2296/6274 2291/2293/6275 2319/2321/6270 +f 2323/2325/6273 2302/2304/6272 2279/2281/6267 +f 2319/2321/6270 2299/2301/6269 2283/2285/6263 +f 2319/2321/6270 2291/2293/6275 2316/2318/6276 +f 2321/2323/6268 2279/2281/6267 2319/2321/6270 +f 2287/2289/6277 2314/2316/6278 2316/2318/6276 +f 2314/2316/6278 2330/2332/6279 2321/2323/6268 +f 2333/2335/6266 2323/2325/6273 2279/2281/6267 +f 2287/2289/6277 2326/2328/6280 2330/2332/6279 +f 2287/2289/6277 2309/2311/6281 2326/2328/6280 +f 2287/2289/6277 2330/2332/6279 2314/2316/6278 +f 2330/2332/6279 2333/2335/6266 2321/2323/6268 +f 2319/2321/6270 2283/2285/6263 2294/2296/6274 +f 2305/2307/6271 2323/2325/6273 2273/2275/6282 +f 2323/2325/6273 2326/2328/6280 2273/2275/6282 +f 2309/2311/6281 2313/2315/6283 2326/2328/6280 +f 2291/2293/6275 2287/2289/6277 2316/2318/6276 +f 2287/2289/6277 2286/2288/6284 2309/2311/6281 +f 2279/2281/6267 2302/2304/6272 2280/2282/6285 +f 2273/2275/6282 2326/2328/6280 2313/2315/6283 +f 2275/2277/6286 2273/2275/6282 2313/2315/6283 +f 2308/2310/6287 2310/2312/6288 2312/2314/6289 +f 2311/2313/6290 2312/2314/6289 2310/2312/6288 +f 2304/2306/6291 2301/2303/6292 2303/2305/6293 +f 2306/2308/6294 2301/2303/6292 2304/2306/6291 +f 2306/2308/6294 2307/2309/6295 2301/2303/6292 +f 2298/2300/6296 2295/2297/6296 2296/2298/6297 +f 2295/2297/6296 2298/2300/6296 2300/2302/6298 +f 2289/2291/5089 2290/2292/5091 2293/2295/6299 +f 2290/2292/5091 2292/2294/6300 2293/2295/6299 +f 2282/2284/6301 2288/2290/6301 2284/2286/6189 +f 2278/2280/6224 2282/2284/6301 2276/2278/6190 +f 2288/2290/6301 2282/2284/6301 2278/2280/6224 +f 2278/2280/6224 2274/2276/6301 2288/2290/6301 +f 2288/2290/6301 2274/2276/6301 2285/2287/6302 +f 2274/2276/6301 2278/2280/6224 2272/2274/6303 +f 2686/2688/6304 2687/2689/6305 2688/2690/6306 +f 2686/2688/6304 2689/2691/6307 2687/2689/6305 +f 2690/2692/6308 2688/2690/6308 2687/2689/6308 +f 2690/2692/6309 2687/2689/6310 2689/2691/6311 +f 2690/2692/6309 2689/2691/6311 2691/2693/6312 +f 2691/2693/6313 2689/2691/6314 2692/2694/6315 +f 2692/2694/6315 2689/2691/6314 2686/2688/6316 +f 2692/2694/6317 2686/2688/6317 2688/2690/6317 +f 2692/2694/6318 2688/2690/6318 2690/2692/6318 +f 2692/2694/6319 2693/2695/6320 2691/2693/6321 +f 2690/2692/6322 2694/2696/6323 2692/2694/6319 +f 2690/2692/6322 2695/2697/6324 2694/2696/6323 +f 2692/2694/6319 2694/2696/6323 2696/2698/6325 +f 2692/2694/6319 2697/2699/6326 2693/2695/6320 +f 2692/2694/6319 2696/2698/6325 2697/2699/6326 +f 2690/2692/6322 2698/2700/6327 2695/2697/6324 +f 2691/2693/6321 2698/2700/6327 2690/2692/6322 +f 2691/2693/6321 2693/2695/6320 2698/2700/6327 +f 2699/2701/6328 2694/2696/6328 2695/2697/6328 +f 2698/2700/6329 2700/2702/6329 2695/2697/6329 +f 2701/2703/6330 2698/2700/6331 2693/2695/6332 +f 2701/2703/6330 2702/2704/6333 2698/2700/6331 +f 2700/2702/6334 2698/2700/6331 2702/2704/6333 +f 2703/2705/6335 2700/2702/6334 2702/2704/6333 +f 2695/2697/6336 2700/2702/6334 2703/2705/6335 +f 2695/2697/6336 2703/2705/6335 2699/2701/6337 +f 2704/2706/6338 2694/2696/6339 2699/2701/6337 +f 2704/2706/6338 2699/2701/6337 2703/2705/6335 +f 2696/2698/6340 2694/2696/6341 2704/2706/6342 +f 2704/2706/6342 2705/2707/6343 2696/2698/6340 +f 2706/2708/6344 2696/2698/6345 2705/2707/6346 +f 2697/2699/6347 2696/2698/6345 2706/2708/6344 +f 2693/2695/6348 2697/2699/6347 2706/2708/6344 +f 2693/2695/6348 2706/2708/6344 2701/2703/6349 +f 2704/2706/6350 2703/2705/6351 2705/2707/6352 +f 2701/2703/6353 2706/2708/6354 2702/2704/6355 +f 2706/2708/6354 2705/2707/6352 2702/2704/6355 +f 2702/2704/6355 2705/2707/6352 2703/2705/6351 +f 2707/2709/6356 2708/2710/6357 2709/2711/6358 +f 2709/2711/6358 2710/2712/6359 2707/2709/6356 +f 2711/2713/6360 2708/2710/6361 2712/2714/6362 +f 2712/2714/6363 2708/2710/6363 2707/2709/6363 +f 2712/2714/6364 2707/2709/6364 2713/2715/6364 +f 2713/2715/6365 2707/2709/6365 2710/2712/6365 +f 2713/2715/6366 2710/2712/6366 2711/2713/6366 +f 2711/2713/6367 2710/2712/6367 2709/2711/6367 +f 2711/2713/6360 2709/2711/6368 2708/2710/6361 +f 2712/2714/6369 2714/2716/6370 2711/2713/6371 +f 2711/2713/6371 2714/2716/6370 2715/2717/6372 +f 2711/2713/6371 2715/2717/6372 2716/2718/6373 +f 2712/2714/6369 2717/2719/6374 2714/2716/6370 +f 2713/2715/6375 2718/2720/6376 2719/2721/6377 +f 2711/2713/6371 2716/2718/6373 2718/2720/6376 +f 2711/2713/6371 2718/2720/6376 2713/2715/6375 +f 2712/2714/6369 2720/2722/6378 2717/2719/6374 +f 2713/2715/6375 2720/2722/6378 2712/2714/6369 +f 2713/2715/6375 2719/2721/6377 2720/2722/6378 +f 2721/2723/6379 2719/2721/6377 2718/2720/6376 +f 2714/2716/6380 2722/2724/6380 2715/2717/6380 +f 2721/2723/6381 2723/2725/6382 2719/2721/6383 +f 2719/2721/6383 2723/2725/6382 2720/2722/6384 +f 2723/2725/6382 2724/2726/6385 2720/2722/6384 +f 2720/2722/6384 2724/2726/6385 2717/2719/6386 +f 2725/2727/6387 2717/2719/6386 2724/2726/6385 +f 2714/2716/6388 2717/2719/6386 2725/2727/6387 +f 2722/2724/6389 2714/2716/6388 2725/2727/6387 +f 2725/2727/6387 2726/2728/6390 2722/2724/6389 +f 2726/2728/6390 2715/2717/6391 2722/2724/6389 +f 2716/2718/6392 2715/2717/6391 2726/2728/6390 +f 2716/2718/6392 2726/2728/6390 2727/2729/6393 +f 2718/2720/6394 2716/2718/6395 2727/2729/6396 +f 2726/2728/6390 2728/2730/6397 2727/2729/6393 +f 2727/2729/6396 2728/2730/6398 2718/2720/6394 +f 2721/2723/6381 2718/2720/6394 2728/2730/6398 +f 2728/2730/6398 2723/2725/6382 2721/2723/6381 +f 2723/2725/6399 2728/2730/6397 2724/2726/6400 +f 2728/2730/6397 2726/2728/6390 2724/2726/6400 +f 2724/2726/6400 2726/2728/6390 2725/2727/6401 +f 2729/2731/6402 2730/2732/6403 2731/2733/6404 +f 2732/2734/6405 2733/2735/6405 2734/2736/6406 +f 2732/2734/6405 2735/2737/6407 2733/2735/6405 +f 2736/2738/6408 2735/2737/6408 2737/2739/6408 +f 2737/2739/6409 2735/2737/6409 2732/2734/6409 +f 2737/2739/6410 2732/2734/6411 2734/2736/6412 +f 2737/2739/6410 2734/2736/6412 2738/2740/6413 +f 2738/2740/6414 2734/2736/6415 2733/2735/6416 +f 2738/2740/6414 2733/2735/6416 2736/2738/6417 +f 2736/2738/6418 2733/2735/6418 2735/2737/6418 +f 2737/2739/6419 2739/2741/6420 2736/2738/6421 +f 2736/2738/6421 2739/2741/6420 2740/2742/6422 +f 2736/2738/6421 2740/2742/6422 2741/2743/6423 +f 2737/2739/6419 2742/2744/6424 2739/2741/6420 +f 2738/2740/6425 2743/2745/6426 2744/2746/6427 +f 2736/2738/6421 2741/2743/6423 2743/2745/6426 +f 2736/2738/6421 2743/2745/6426 2738/2740/6425 +f 2738/2740/6425 2745/2747/2810 2737/2739/6419 +f 2737/2739/6419 2746/2748/6428 2742/2744/6424 +f 2737/2739/6419 2745/2747/2810 2746/2748/6428 +f 2738/2740/6425 2744/2746/6427 2745/2747/2810 +f 2747/2749/6429 2745/2747/6430 2748/2750/6431 +f 2745/2747/6432 2747/2749/6433 2731/2733/6434 +f 2746/2748/6435 2745/2747/6432 2731/2733/6434 +f 2746/2748/6435 2731/2733/6434 2730/2732/6436 +f 2742/2744/6437 2746/2748/6435 2730/2732/6436 +f 2730/2732/6436 2729/2731/6438 2742/2744/6437 +f 2742/2744/6437 2729/2731/6438 2739/2741/6439 +f 2740/2742/6440 2739/2741/6441 2729/2731/6442 +f 2749/2751/6443 2740/2742/6440 2729/2731/6442 +f 2741/2743/6444 2740/2742/6445 2749/2751/6446 +f 2750/2752/6447 2749/2751/6443 2729/2731/6442 +f 2750/2752/6448 2741/2743/6444 2749/2751/6446 +f 2741/2743/6444 2750/2752/6448 2743/2745/6449 +f 2743/2745/6449 2750/2752/6448 2748/2750/6450 +f 2744/2746/6451 2743/2745/6449 2748/2750/6450 +f 2747/2749/6452 2748/2750/6453 2750/2752/6454 +f 2745/2747/6430 2744/2746/6455 2748/2750/6431 +f 2750/2752/6456 2729/2731/6456 2751/2753/6456 +f 2747/2749/6452 2750/2752/6454 2731/2733/6457 +f 2750/2752/6454 2751/2753/6458 2731/2733/6457 +f 2731/2733/6404 2751/2753/6459 2729/2731/6402 +f 2752/2754/6460 2753/2755/6461 2754/2756/6462 +f 2752/2754/6460 2755/2757/6463 2753/2755/6461 +f 2756/2758/6464 2752/2754/6465 2757/2759/6466 +f 2757/2759/6466 2752/2754/6465 2754/2756/6467 +f 2757/2759/6468 2754/2756/6469 2753/2755/6470 +f 2757/2759/6468 2753/2755/6470 2758/2760/6471 +f 2758/2760/6472 2753/2755/6472 2755/2757/6472 +f 2758/2760/6473 2755/2757/6473 2756/2758/6473 +f 2756/2758/6474 2755/2757/6474 2752/2754/6474 +f 2756/2758/6475 2759/2761/6476 2760/2762/6477 +f 2756/2758/6475 2761/2763/6478 2758/2760/6479 +f 2756/2758/6475 2760/2762/6477 2761/2763/6478 +f 2757/2759/6480 2759/2761/6476 2756/2758/6475 +f 2757/2759/6480 2762/2764/6481 2759/2761/6476 +f 2758/2760/6479 2763/2765/6482 2764/2766/6483 +f 2758/2760/6479 2761/2763/6478 2763/2765/6482 +f 2757/2759/6480 2765/2767/6484 2766/2768/6485 +f 2757/2759/6480 2766/2768/6485 2762/2764/6481 +f 2758/2760/6479 2764/2766/6483 2765/2767/6484 +f 2758/2760/6479 2765/2767/6484 2757/2759/6480 +f 2766/2768/6486 2765/2767/6487 2767/2769/6488 +f 2767/2769/6488 2768/2770/6489 2766/2768/6486 +f 2762/2764/6490 2766/2768/6486 2768/2770/6489 +f 2769/2771/6491 2762/2764/6490 2768/2770/6489 +f 2759/2761/6492 2762/2764/6490 2769/2771/6491 +f 2770/2772/6493 2769/2771/6491 2768/2770/6489 +f 2759/2761/6494 2769/2771/6491 2770/2772/6493 +f 2760/2762/6495 2759/2761/6494 2770/2772/6493 +f 2771/2773/6496 2760/2762/6495 2770/2772/6493 +f 2761/2763/6497 2760/2762/6495 2771/2773/6496 +f 2771/2773/6496 2763/2765/6498 2761/2763/6497 +f 2772/2774/6499 2763/2765/6498 2771/2773/6496 +f 2764/2766/6500 2763/2765/6501 2772/2774/6502 +f 2765/2767/6503 2764/2766/6500 2772/2774/6502 +f 2765/2767/6503 2772/2774/6502 2767/2769/6504 +f 2771/2773/6505 2770/2772/6493 2772/2774/6506 +f 2770/2772/6493 2768/2770/6489 2767/2769/6507 +f 2767/2769/6507 2772/2774/6506 2770/2772/6493 +f 2773/2775/6508 2774/2776/6509 2775/2777/6510 +f 2776/2778/6511 2773/2775/6508 2775/2777/6510 +f 2777/2779/6512 2774/2776/6513 2773/2775/6514 +f 2777/2779/6515 2773/2775/6515 2776/2778/6515 +f 2777/2779/6516 2776/2778/6516 2778/2780/6516 +f 2778/2780/6517 2776/2778/6517 2775/2777/6517 +f 2778/2780/6518 2775/2777/6519 2779/2781/6520 +f 2779/2781/6520 2775/2777/6519 2774/2776/6521 +f 2779/2781/6522 2774/2776/6513 2777/2779/6512 +f 2777/2779/6523 2780/2782/6524 2779/2781/6525 +f 2777/2779/6523 2781/2783/6526 2780/2782/6524 +f 2779/2781/6525 2782/2784/6527 2778/2780/6528 +f 2779/2781/6525 2783/2785/6529 2784/2786/6530 +f 2779/2781/6525 2784/2786/6530 2782/2784/6527 +f 2780/2782/6524 2783/2785/6529 2779/2781/6525 +f 2778/2780/6528 2782/2784/6527 2785/2787/6531 +f 2778/2780/6528 2786/2788/6532 2777/2779/6523 +f 2777/2779/6523 2786/2788/6532 2787/2789/6533 +f 2777/2779/6523 2787/2789/6533 2781/2783/6526 +f 2778/2780/6528 2785/2787/6531 2786/2788/6532 +f 2785/2787/6534 2788/2790/6535 2786/2788/6536 +f 2789/2791/6537 2786/2788/6536 2788/2790/6535 +f 2786/2788/6536 2789/2791/6537 2787/2789/6538 +f 2789/2791/6539 2790/2792/6540 2781/2783/6541 +f 2789/2791/6539 2781/2783/6541 2787/2789/6542 +f 2791/2793/6543 2781/2783/6544 2790/2792/6545 +f 2780/2782/6546 2781/2783/6544 2791/2793/6543 +f 2783/2785/6547 2780/2782/6548 2791/2793/6549 +f 2784/2786/6550 2783/2785/6547 2791/2793/6549 +f 2791/2793/6549 2792/2794/6551 2784/2786/6550 +f 2782/2784/6552 2784/2786/6553 2792/2794/6554 +f 2793/2795/6555 2782/2784/6552 2792/2794/6554 +f 2785/2787/6534 2782/2784/6552 2793/2795/6555 +f 2793/2795/6555 2788/2790/6535 2785/2787/6534 +f 2791/2793/6556 2790/2792/6557 2792/2794/6558 +f 2788/2790/6559 2793/2795/6560 2789/2791/6561 +f 2793/2795/6560 2792/2794/6558 2789/2791/6561 +f 2789/2791/6561 2792/2794/6558 2790/2792/6557 +f 2794/2796/6562 2795/2797/6563 2796/2798/6564 +f 2797/2799/6565 2798/2800/6566 2799/2801/6567 +f 2797/2799/6565 2800/2802/6568 2798/2800/6566 +f 2801/2803/6569 2799/2801/6569 2798/2800/6569 +f 2801/2803/6570 2798/2800/6570 2802/2804/6570 +f 2802/2804/6571 2798/2800/6571 2800/2802/6571 +f 2802/2804/6572 2800/2802/6573 2803/2805/6574 +f 2803/2805/6574 2800/2802/6573 2797/2799/6575 +f 2803/2805/6576 2797/2799/6577 2799/2801/6578 +f 2803/2805/6576 2799/2801/6578 2804/2806/6579 +f 2804/2806/6580 2799/2801/6580 2801/2803/6580 +f 2801/2803/6581 2805/2807/6582 2804/2806/6583 +f 2801/2803/6581 2806/2808/6584 2805/2807/6582 +f 2804/2806/6583 2807/2809/6585 2803/2805/6586 +f 2804/2806/6583 2805/2807/6582 2807/2809/6585 +f 2803/2805/6586 2807/2809/6585 2808/2810/6587 +f 2802/2804/6588 2809/2811/6589 2806/2808/6584 +f 2802/2804/6588 2806/2808/6584 2801/2803/6581 +f 2803/2805/6586 2808/2810/6587 2809/2811/6589 +f 2803/2805/6586 2809/2811/6589 2802/2804/6588 +f 2810/2812/6590 2805/2807/6582 2806/2808/6584 +f 2808/2810/6591 2811/2813/6591 2809/2811/6591 +f 2809/2811/6592 2812/2814/6592 2806/2808/6592 +f 2796/2798/6593 2811/2813/6594 2813/2815/6595 +f 2809/2811/6596 2811/2813/6594 2796/2798/6593 +f 2812/2814/6597 2809/2811/6596 2796/2798/6593 +f 2795/2797/6598 2812/2814/6597 2796/2798/6593 +f 2806/2808/6599 2812/2814/6597 2795/2797/6598 +f 2794/2796/6600 2806/2808/6599 2795/2797/6598 +f 2806/2808/6599 2794/2796/6600 2810/2812/6601 +f 2814/2816/6602 2810/2812/6601 2794/2796/6600 +f 2810/2812/6601 2814/2816/6602 2805/2807/6603 +f 2807/2809/6604 2805/2807/6605 2814/2816/6606 +f 2815/2817/6607 2807/2809/6604 2814/2816/6606 +f 2816/2818/6608 2807/2809/6609 2815/2817/6610 +f 2808/2810/6611 2807/2809/6609 2816/2818/6608 +f 2811/2813/6594 2808/2810/6611 2816/2818/6608 +f 2811/2813/6594 2816/2818/6608 2813/2815/6595 +f 2815/2817/6612 2814/2816/6613 2794/2796/6562 +f 2813/2815/6614 2816/2818/6615 2815/2817/6612 +f 2794/2796/6562 2796/2798/6564 2813/2815/6614 +f 2813/2815/6614 2815/2817/6612 2794/2796/6562 +f 2657/2659/5534 2656/2658/5534 2654/2656/5534 +f 2657/2659/5534 2654/2656/5534 2655/2657/5534 +f 2315/2317/5534 2318/2320/5534 2317/2319/5534 +f 2315/2317/5534 2320/2322/5534 2318/2320/5534 +f 2469/2471/6301 2472/2474/6616 2470/2472/6301 +f 2471/2473/6224 2469/2471/6301 2470/2472/6301 +f 2650/2652/6301 2652/2654/6301 2653/2655/6224 +f 2650/2652/6301 2651/2653/6301 2652/2654/6301 +f 2817/2819/6617 2818/2820/6618 2819/2821/6619 +f 2820/2822/6620 2817/2819/6617 2819/2821/6619 +f 2821/2823/6621 2822/2824/6621 2823/2825/6621 +f 2821/2823/6622 2823/2825/6622 2824/2826/6622 +f 2825/2827/6623 2821/2823/6624 2824/2826/6625 +f 2821/2823/6624 2825/2827/6623 2822/2824/6626 +f 2826/2828/6627 2827/2829/6628 2828/2830/6629 +f 2826/2828/6627 2828/2830/6629 2829/2831/6630 +f 1697/1699/6631 2817/2819/6632 2820/2822/6633 +f 2820/2822/6634 1699/1701/6634 1697/1699/6634 +f 1699/1701/6635 2820/2822/6635 2819/2821/6635 +f 2819/2821/6636 1700/1702/6636 1699/1701/6636 +f 1700/1702/6637 2819/2821/6637 2818/2820/6637 +f 2818/2820/6638 1696/1698/6638 1700/1702/6638 +f 1696/1698/6639 2818/2820/6640 2817/2819/6632 +f 2817/2819/6632 1697/1699/6631 1696/1698/6639 +f 1691/1693/6641 2822/2824/6642 2825/2827/6643 +f 2825/2827/6643 1692/1694/6644 1691/1693/6641 +f 1692/1694/6645 2825/2827/6645 2824/2826/6645 +f 2824/2826/6646 1694/1696/6646 1692/1694/6646 +f 1694/1696/6647 2824/2826/6648 2823/2825/6649 +f 2823/2825/6649 1695/1697/6650 1694/1696/6647 +f 1695/1697/6651 2823/2825/6652 2822/2824/6653 +f 2822/2824/6653 1691/1693/6654 1695/1697/6651 +f 2830/2832/6655 2826/2828/6655 2829/2831/6655 +f 2829/2831/6656 2831/2833/6657 2830/2832/6658 +f 2831/2833/6659 2829/2831/6659 2828/2830/6659 +f 2828/2830/6660 2832/2834/6660 2831/2833/6660 +f 2832/2834/6661 2828/2830/6661 2827/2829/6661 +f 2827/2829/6662 2833/2835/6662 2832/2834/6662 +f 2833/2835/6663 2827/2829/6663 2826/2828/6663 +f 2826/2828/6664 2830/2832/6665 2833/2835/6666 +f 1688/1690/6667 2834/2836/6667 2835/2837/6667 +f 2835/2837/6668 1689/1691/6668 1688/1690/6668 +f 1689/1691/6669 2835/2837/6670 2836/2838/6671 +f 2836/2838/6671 1690/1692/6672 1689/1691/6669 +f 1690/1692/6673 2836/2838/6674 2837/2839/6675 +f 2837/2839/6676 1687/1689/6676 1690/1692/6676 +f 1687/1689/6677 2837/2839/6678 2834/2836/6679 +f 2834/2836/6680 1688/1690/6680 1687/1689/6680 +f 2837/2839/6681 2833/2835/6666 2830/2832/6665 +f 2830/2832/6682 2834/2836/6679 2837/2839/6678 +f 2837/2839/6683 2832/2834/6683 2833/2835/6683 +f 2832/2834/6684 2837/2839/6675 2836/2838/6674 +f 2836/2838/6671 2831/2833/6685 2832/2834/6686 +f 2831/2833/6685 2836/2838/6671 2835/2837/6670 +f 2834/2836/6687 2830/2832/6658 2831/2833/6657 +f 2831/2833/6657 2835/2837/6688 2834/2836/6687 +f 2838/2840/6689 1827/1829/6690 1829/1831/6691 +f 1827/1829/6690 2838/2840/6689 1830/1832/6692 +f 2839/2841/6693 1830/1832/6694 2838/2840/6695 +f 2838/2840/6695 2840/2842/6696 2839/2841/6693 +f 2840/2842/6697 2838/2840/6698 1829/1831/6699 +f 1829/1831/6699 2841/2843/6700 2840/2842/6697 +f 1829/1831/6701 2842/2844/6702 2841/2843/6703 +f 2842/2844/6702 1829/1831/6701 1828/1830/6704 +f 1828/1830/6705 2839/2841/6706 2842/2844/6707 +f 2839/2841/6706 1828/1830/6705 1830/1832/6708 +f 1832/1834/6709 2843/2845/6710 2844/2846/6711 +f 2844/2846/6712 1835/1837/6712 1832/1834/6712 +f 1835/1837/6713 2844/2846/6714 2845/2847/6715 +f 2845/2847/6715 1834/1836/6716 1835/1837/6713 +f 2845/2847/6717 1831/1833/6717 1834/1836/6717 +f 1831/1833/6718 2845/2847/6719 2846/2848/6720 +f 2846/2848/6721 1832/1834/6721 1831/1833/6721 +f 1832/1834/6722 2846/2848/6723 2843/2845/6724 +f 2839/2841/6725 2843/2845/6724 2846/2848/6723 +f 2846/2848/6726 2842/2844/6707 2839/2841/6706 +f 2842/2844/6727 2846/2848/6720 2845/2847/6719 +f 2845/2847/6728 2841/2843/6703 2842/2844/6702 +f 2841/2843/6729 2845/2847/6715 2844/2846/6714 +f 2844/2846/6730 2840/2842/6697 2841/2843/6700 +f 2840/2842/6731 2844/2846/6711 2843/2845/6710 +f 2843/2845/6732 2839/2841/6693 2840/2842/6696 +f 1839/1841/4010 1843/1845/4010 1840/1842/4011 +f 1842/1844/4010 1841/1843/6733 1826/1828/4011 +f 1841/1843/6733 1838/1840/4009 1840/1842/4011 +f 1822/1824/6734 1842/1844/4010 1826/1828/4011 +f 1841/1843/6733 1840/1842/4011 1826/1828/4011 +f 1775/1777/6735 1769/1771/6736 2847/2849/6737 +f 1769/1771/6736 1768/1770/6738 1776/1778/6739 +f 1776/1778/6739 2847/2849/6737 1769/1771/6736 +f 1776/1778/6740 1770/1772/6740 2848/2850/6740 +f 1773/1775/6741 1775/1777/6742 2847/2849/6743 +f 2847/2849/6743 2849/2851/6744 1773/1775/6741 +f 1770/1772/6745 1773/1775/6746 2849/2851/6747 +f 2849/2851/6747 2848/2850/6748 1770/1772/6745 +f 2848/2850/6749 2847/2849/6750 1776/1778/6751 +f 2847/2849/6750 2848/2850/6749 2849/2851/6752 +f 1748/1750/6753 1747/1749/3818 1742/1744/3815 +f 1753/1755/6754 1757/1759/6754 1754/1756/6754 +f 1752/1754/6755 1755/1757/6755 1756/1758/6755 +f 1753/1755/6756 1752/1754/6757 1756/1758/6758 +f 1756/1758/6758 1757/1759/6759 1753/1755/6756 +f 2850/2852/6760 2851/2853/6761 2852/2854/6762 +f 2853/2855/6763 2854/2856/6764 2855/2857/6765 +f 2850/2852/6760 2855/2857/6765 2851/2853/6761 +f 2850/2852/6760 2853/2855/6763 2855/2857/6765 +f 2856/2858/6766 2850/2852/6760 2852/2854/6762 +f 2856/2858/6766 2852/2854/6762 2857/2859/6767 +f 2853/2855/6763 2856/2858/6766 2854/2856/6764 +f 2856/2858/6766 2857/2859/6767 2854/2856/6764 +f 2858/2860/6768 2859/2861/6769 2860/2862/6770 +f 2858/2860/6768 2861/2863/6771 2859/2861/6769 +f 2862/2864/6772 2860/2862/6772 2859/2861/6772 +f 2862/2864/6773 2863/2865/6774 2860/2862/6775 +f 2863/2865/6774 2864/2866/6776 2860/2862/6775 +f 2863/2865/6777 2865/2867/6777 2864/2866/6777 +f 2865/2867/6778 2858/2860/6778 2864/2866/6778 +f 2865/2867/6779 2866/2868/6780 2858/2860/6781 +f 2866/2868/6780 2861/2863/6782 2858/2860/6781 +f 2866/2868/6783 2867/2869/6784 2861/2863/6785 +f 2867/2869/6784 2859/2861/6786 2861/2863/6785 +f 2867/2869/6787 2862/2864/6787 2859/2861/6787 +f 2863/2865/6788 2862/2864/6789 2868/2870/6790 +f 2862/2864/6789 2869/2871/6791 2868/2870/6790 +f 2862/2864/6789 2867/2869/6792 2869/2871/6791 +f 2867/2869/6792 2870/2872/6793 2869/2871/6791 +f 2867/2869/6792 2871/2873/6794 2870/2872/6793 +f 2867/2869/6792 2866/2868/6795 2871/2873/6794 +f 2866/2868/6795 2872/2874/6796 2871/2873/6794 +f 2866/2868/6795 2865/2867/6797 2872/2874/6796 +f 2865/2867/6797 2868/2870/6790 2872/2874/6796 +f 2865/2867/6797 2863/2865/6788 2868/2870/6790 +f 2851/2853/6798 2855/2857/6798 2869/2871/6798 +f 2855/2857/6799 2868/2870/6799 2869/2871/6799 +f 2855/2857/6800 2854/2856/6800 2868/2870/6800 +f 2854/2856/6801 2872/2874/6801 2868/2870/6801 +f 2854/2856/6802 2857/2859/6802 2872/2874/6802 +f 2857/2859/6803 2871/2873/6804 2872/2874/6805 +f 2857/2859/6803 2852/2854/6806 2871/2873/6804 +f 2852/2854/6807 2870/2872/6807 2871/2873/6807 +f 2852/2854/6808 2851/2853/6809 2870/2872/6810 +f 2851/2853/6809 2869/2871/6811 2870/2872/6810 +f 2853/2855/6812 2873/2875/6813 2856/2858/6814 +f 2873/2875/6813 2874/2876/6815 2856/2858/6814 +f 2850/2852/6816 2875/2877/6817 2853/2855/6818 +f 2875/2877/6817 2873/2875/6819 2853/2855/6818 +f 2856/2858/6820 2874/2876/6821 2850/2852/6822 +f 2874/2876/6821 2875/2877/6823 2850/2852/6822 +f 2874/2876/528 2873/2875/528 2875/2877/528 +f 2864/2866/6824 2858/2860/6768 2860/2862/6770 +f 2876/2878/6825 2877/2879/6826 2878/2880/6827 +f 2877/2879/6826 2879/2881/6828 2880/2882/6829 +f 2877/2879/6826 2881/2883/6830 2879/2881/6828 +f 2877/2879/6826 2880/2882/6829 2878/2880/6827 +f 2881/2883/6830 2882/2884/6831 2883/2885/6832 +f 2881/2883/6830 2876/2878/6833 2882/2884/6831 +f 2879/2881/6828 2881/2883/6830 2883/2885/6832 +f 2884/2886/6834 2885/2887/6835 2886/2888/6836 +f 2884/2886/6834 2886/2888/6836 2887/2889/6837 +f 2888/2890/6838 2884/2886/6839 2887/2889/6840 +f 2888/2890/6838 2889/2891/6841 2884/2886/6839 +f 2889/2891/6842 2890/2892/6842 2884/2886/6842 +f 2889/2891/6843 2891/2893/6843 2890/2892/6843 +f 2891/2893/6844 2885/2887/6845 2890/2892/6846 +f 2891/2893/6844 2892/2894/6847 2885/2887/6845 +f 2892/2894/6848 2886/2888/6848 2885/2887/6848 +f 2892/2894/6849 2888/2890/6850 2886/2888/6851 +f 2888/2890/6850 2887/2889/6852 2886/2888/6851 +f 2889/2891/6853 2893/2895/6854 2894/2896/6855 +f 2889/2891/6853 2888/2890/6856 2893/2895/6854 +f 2888/2890/6856 2895/2897/6857 2893/2895/6854 +f 2888/2890/6856 2896/2898/6858 2895/2897/6857 +f 2888/2890/6856 2892/2894/6859 2896/2898/6858 +f 2892/2894/6859 2897/2899/6860 2896/2898/6858 +f 2892/2894/6859 2891/2893/6861 2897/2899/6860 +f 2891/2893/6861 2894/2896/6855 2897/2899/6860 +f 2891/2893/6861 2889/2891/6853 2894/2896/6855 +f 2878/2880/6862 2880/2882/6862 2893/2895/6862 +f 2880/2882/6863 2894/2896/6864 2893/2895/6865 +f 2880/2882/6863 2879/2881/6866 2894/2896/6864 +f 2879/2881/6867 2897/2899/6868 2894/2896/6869 +f 2879/2881/6867 2883/2885/6870 2897/2899/6868 +f 2883/2885/6871 2882/2884/6872 2897/2899/6873 +f 2882/2884/6872 2896/2898/6874 2897/2899/6873 +f 2882/2884/6875 2876/2878/6876 2896/2898/6877 +f 2876/2878/6876 2895/2897/6878 2896/2898/6877 +f 2876/2878/6876 2878/2880/6879 2895/2897/6878 +f 2878/2880/6880 2893/2895/6880 2895/2897/6880 +f 2877/2879/6881 2898/2900/6882 2881/2883/6883 +f 2898/2900/6882 2899/2901/6884 2881/2883/6883 +f 2876/2878/6885 2900/2902/6886 2877/2879/6887 +f 2900/2902/6886 2898/2900/6888 2877/2879/6887 +f 2881/2883/6889 2899/2901/6890 2876/2878/6891 +f 2899/2901/6890 2900/2902/6892 2876/2878/6891 +f 2899/2901/528 2898/2900/528 2900/2902/528 +f 2890/2892/6893 2885/2887/6835 2884/2886/6834 +f 2901/2903/6894 2902/2904/6894 2903/2905/6894 +f 2904/2906/6895 2902/2904/6896 2905/2907/6897 +f 2902/2904/6896 2906/2908/6898 2905/2907/6897 +f 2907/2909/6899 2908/2910/6900 2909/2911/6901 +f 2910/2912/6902 2907/2909/6903 2909/2911/6904 +f 2910/2912/6902 2911/2913/6905 2907/2909/6903 +f 2911/2913/6906 2912/2914/6906 2907/2909/6906 +f 2911/2913/6907 2913/2915/6907 2912/2914/6907 +f 2913/2915/6908 2908/2910/6908 2912/2914/6908 +f 2913/2915/6909 2914/2916/6910 2908/2910/6911 +f 2914/2916/6910 2915/2917/6912 2908/2910/6911 +f 2914/2916/6913 2909/2911/6914 2915/2917/6915 +f 2914/2916/6913 2910/2912/6916 2909/2911/6914 +f 2914/2916/6917 2913/2915/6918 2916/2918/6919 +f 2913/2915/6918 2917/2919/6920 2916/2918/6919 +f 2910/2912/6921 2918/2920/6922 2919/2921/6923 +f 2910/2912/6921 2914/2916/6917 2918/2920/6922 +f 2913/2915/6918 2920/2922/6924 2917/2919/6920 +f 2913/2915/6918 2911/2913/6925 2920/2922/6924 +f 2914/2916/6917 2916/2918/6919 2918/2920/6922 +f 2911/2913/6925 2910/2912/6921 2919/2921/6923 +f 2911/2913/6925 2919/2921/6923 2920/2922/6924 +f 2903/2905/6926 2919/2921/6926 2918/2920/6926 +f 2903/2905/6927 2902/2904/6928 2919/2921/6929 +f 2902/2904/6928 2920/2922/6930 2919/2921/6929 +f 2902/2904/6931 2904/2906/6931 2920/2922/6931 +f 2904/2906/6932 2917/2919/6933 2920/2922/6934 +f 2904/2906/6932 2905/2907/6935 2917/2919/6933 +f 2905/2907/6936 2916/2918/6937 2917/2919/6938 +f 2905/2907/6936 2906/2908/6939 2916/2918/6937 +f 2906/2908/6940 2901/2903/6940 2916/2918/6940 +f 2901/2903/6941 2918/2920/6941 2916/2918/6941 +f 2901/2903/6942 2903/2905/6942 2918/2920/6942 +f 2902/2904/6943 2921/2923/6944 2906/2908/6945 +f 2921/2923/6944 2922/2924/6946 2906/2908/6945 +f 2901/2903/6947 2923/2925/6947 2902/2904/6947 +f 2923/2925/6948 2921/2923/6948 2902/2904/6948 +f 2906/2908/6949 2922/2924/6950 2901/2903/6951 +f 2922/2924/6950 2923/2925/6952 2901/2903/6951 +f 2922/2924/528 2921/2923/528 2923/2925/528 +f 2912/2914/6953 2908/2910/6900 2907/2909/6899 +f 2915/2917/6954 2909/2911/6901 2908/2910/6900 +f 2924/2926/6955 2925/2927/6956 2926/2928/6957 +f 2924/2926/6958 2927/2929/6958 2925/2927/6958 +f 2927/2929/6959 2928/2930/6959 2925/2927/6959 +f 2927/2929/6960 2929/2931/6961 2928/2930/6962 +f 2929/2931/6961 2930/2932/6963 2928/2930/6962 +f 2929/2931/6964 2931/2933/6964 2930/2932/6964 +f 2929/2931/6965 2932/2934/6965 2931/2933/6965 +f 2933/2935/6966 2931/2933/6966 2932/2934/6966 +f 2933/2935/6967 2934/2936/6967 2931/2933/6967 +f 2933/2935/6968 2935/2937/6968 2934/2936/6968 +f 2935/2937/6969 2936/2938/6969 2934/2936/6969 +f 2935/2937/6970 2937/2939/6970 2936/2938/6970 +f 2937/2939/6971 2938/2940/6971 2936/2938/6971 +f 2937/2939/6972 2939/2941/6973 2938/2940/6974 +f 2939/2941/6973 2940/2942/6975 2938/2940/6974 +f 2939/2941/6976 2941/2943/6977 2940/2942/6978 +f 2939/2941/6976 2942/2944/6979 2941/2943/6977 +f 2924/2926/6955 2926/2928/6957 2942/2944/6980 +f 2926/2928/6981 2941/2943/6981 2942/2944/6981 +f 2929/2931/98 2927/2929/98 2935/2937/98 +f 2927/2929/98 2937/2939/98 2935/2937/98 +f 2924/2926/98 2942/2944/98 2939/2941/98 +f 2932/2934/98 2929/2931/98 2933/2935/98 +f 2929/2931/98 2935/2937/98 2933/2935/98 +f 2927/2929/98 2924/2926/98 2939/2941/98 +f 2927/2929/98 2939/2941/98 2937/2939/98 +f 2928/2930/528 2930/2932/528 2936/2938/528 +f 2930/2932/528 2934/2936/528 2936/2938/528 +f 2928/2930/528 2936/2938/528 2938/2940/528 +f 2925/2927/528 2928/2930/528 2938/2940/528 +f 2930/2932/528 2931/2933/528 2934/2936/528 +f 2925/2927/528 2938/2940/528 2940/2942/528 +f 2926/2928/528 2925/2927/528 2941/2943/528 +f 2925/2927/528 2940/2942/528 2941/2943/528 +f 2943/2945/6982 2944/2946/6982 2945/2947/6982 +f 2943/2945/6983 2946/2948/6983 2944/2946/6983 +f 2946/2948/6984 2947/2949/6984 2944/2946/6984 +f 2946/2948/6985 2948/2950/6985 2947/2949/6985 +f 2946/2948/6986 2949/2951/6986 2948/2950/6986 +f 2949/2951/6987 2950/2952/6987 2948/2950/6987 +f 2949/2951/6988 2951/2953/6988 2950/2952/6988 +f 2952/2954/6989 2950/2952/6990 2951/2953/6991 +f 2952/2954/6992 2953/2955/6992 2954/2956/6992 +f 2953/2955/6993 2955/2957/6993 2954/2956/6993 +f 2953/2955/6994 2956/2958/6995 2955/2957/6996 +f 2956/2958/6995 2957/2959/6997 2955/2957/6996 +f 2956/2958/6998 2958/2960/6999 2957/2959/7000 +f 2956/2958/6998 2959/2961/7001 2958/2960/6999 +f 2959/2961/7002 2960/2962/7002 2958/2960/7002 +f 2960/2962/7003 2961/2963/7003 2958/2960/7003 +f 2960/2962/7004 2962/2964/7004 2961/2963/7004 +f 2962/2964/7005 2963/2965/7005 2961/2963/7005 +f 2943/2945/7006 2945/2947/7006 2962/2964/7006 +f 2945/2947/7007 2963/2965/7007 2962/2964/7007 +f 2946/2948/98 2959/2961/98 2956/2958/98 +f 2949/2951/7008 2956/2958/98 2953/2955/7009 +f 2949/2951/7008 2946/2948/98 2956/2958/98 +f 2943/2945/98 2962/2964/98 2960/2962/98 +f 2949/2951/7008 2953/2955/7009 2952/2954/7010 +f 2951/2953/7011 2949/2951/7008 2952/2954/7010 +f 2946/2948/98 2943/2945/98 2960/2962/98 +f 2946/2948/98 2960/2962/98 2959/2961/98 +f 2948/2950/528 2955/2957/528 2957/2959/528 +f 2948/2950/528 2950/2952/6990 2955/2957/528 +f 2958/2960/528 2947/2949/528 2957/2959/528 +f 2947/2949/528 2948/2950/528 2957/2959/528 +f 2944/2946/528 2947/2949/528 2958/2960/528 +f 2950/2952/6990 2952/2954/6989 2954/2956/7012 +f 2955/2957/528 2950/2952/6990 2954/2956/7012 +f 2944/2946/528 2958/2960/528 2961/2963/528 +f 2945/2947/528 2944/2946/528 2963/2965/528 +f 2944/2946/528 2961/2963/528 2963/2965/528 +f 2964/2966/7013 2965/2967/7014 2966/2968/7015 +f 2964/2966/7013 2966/2968/7015 2967/2969/7016 +f 2968/2970/7017 2969/2971/7018 2970/2972/7019 +f 2965/2967/7014 2969/2971/7018 2968/2970/7017 +f 2965/2967/7014 2968/2970/7017 2966/2968/7015 +f 2969/2971/7018 2964/2966/7013 2970/2972/7019 +f 2964/2966/7013 2967/2969/7016 2970/2972/7019 +f 2971/2973/7020 2972/2974/7021 2973/2975/7022 +f 2972/2974/7021 2971/2973/7020 2974/2976/7023 +f 2975/2977/7024 2976/2978/7025 2972/2974/7026 +f 2975/2977/7024 2977/2979/7027 2976/2978/7025 +f 2977/2979/7028 2973/2975/7028 2976/2978/7028 +f 2977/2979/7029 2971/2973/7030 2973/2975/7031 +f 2977/2979/7029 2978/2980/7032 2971/2973/7030 +f 2978/2980/7033 2974/2976/7034 2971/2973/7035 +f 2978/2980/7033 2979/2981/7036 2974/2976/7034 +f 2979/2981/7037 2975/2977/7038 2974/2976/7039 +f 2975/2977/7038 2972/2974/7040 2974/2976/7039 +f 2977/2979/7041 2975/2977/7042 2980/2982/7043 +f 2975/2977/7042 2981/2983/7044 2980/2982/7043 +f 2975/2977/7042 2982/2984/7045 2981/2983/7044 +f 2975/2977/7042 2979/2981/7046 2982/2984/7045 +f 2979/2981/7046 2983/2985/7047 2982/2984/7045 +f 2979/2981/7046 2978/2980/7048 2983/2985/7047 +f 2978/2980/7048 2984/2986/7049 2983/2985/7047 +f 2978/2980/7048 2985/2987/7050 2984/2986/7049 +f 2978/2980/7048 2977/2979/7041 2985/2987/7050 +f 2977/2979/7041 2980/2982/7043 2985/2987/7050 +f 2966/2968/7051 2980/2982/7052 2981/2983/7053 +f 2966/2968/7051 2968/2970/7054 2980/2982/7052 +f 2968/2970/7055 2985/2987/7056 2980/2982/7057 +f 2968/2970/7055 2970/2972/7058 2985/2987/7056 +f 2970/2972/7059 2984/2986/7059 2985/2987/7059 +f 2970/2972/7060 2983/2985/7061 2984/2986/7062 +f 2970/2972/7060 2967/2969/7063 2983/2985/7061 +f 2967/2969/7064 2982/2984/7064 2983/2985/7064 +f 2967/2969/7065 2966/2968/7066 2982/2984/7067 +f 2966/2968/7066 2981/2983/7068 2982/2984/7067 +f 2965/2967/7069 2986/2988/7069 2969/2971/7069 +f 2987/2989/7070 2986/2988/7070 2965/2967/7070 +f 2964/2966/7071 2987/2989/7071 2965/2967/7071 +f 2969/2971/7072 2986/2988/7073 2964/2966/7074 +f 2986/2988/7073 2987/2989/7075 2964/2966/7074 +f 2976/2978/7076 2973/2975/7022 2972/2974/7021 +f 2988/2990/7077 2989/2991/7078 2990/2992/7079 +f 2989/2991/7078 2991/2993/7080 2990/2992/7079 +f 2989/2991/7081 2992/2994/7082 2991/2993/7083 +f 2992/2994/7082 2993/2995/7084 2991/2993/7083 +f 2992/2994/7085 2994/2996/7086 2993/2995/7087 +f 2994/2996/7086 2995/2997/7088 2993/2995/7087 +f 2994/2996/7089 2996/2998/7090 2995/2997/7091 +f 2996/2998/7090 2997/2999/7092 2995/2997/7091 +f 2998/3000/7093 2997/2999/7093 2996/2998/7093 +f 2998/3000/7094 2999/3001/7094 2997/2999/7094 +f 2998/3000/7095 3000/3002/7095 2999/3001/7095 +f 3000/3002/7096 3001/3003/7096 2999/3001/7096 +f 3000/3002/7097 3002/3004/7097 3001/3003/7097 +f 3002/3004/7098 3003/3005/7098 3001/3003/7098 +f 3002/3004/7099 3004/3006/7100 3003/3005/7101 +f 3002/3004/7099 3005/3007/7102 3004/3006/7100 +f 3005/3007/7103 3006/3008/7104 3004/3006/7105 +f 3005/3007/7103 3007/3009/7106 3006/3008/7104 +f 3007/3009/7107 3008/3010/7107 3006/3008/7107 +f 2988/2990/7077 2990/2992/7079 3008/3010/7108 +f 2989/2991/98 3005/3007/98 3002/3004/98 +f 2992/2994/98 2989/2991/98 3002/3004/98 +f 2994/2996/98 2992/2994/98 3000/3002/98 +f 2992/2994/98 3002/3004/98 3000/3002/98 +f 2988/2990/7109 3008/3010/7110 3007/3009/7111 +f 2989/2991/98 2988/2990/7109 3005/3007/98 +f 2988/2990/7109 3007/3009/7111 3005/3007/98 +f 2996/2998/98 3000/3002/98 2998/3000/98 +f 2996/2998/98 2994/2996/98 3000/3002/98 +f 2991/2993/528 2993/2995/528 3003/3005/528 +f 2993/2995/528 2995/2997/528 3001/3003/528 +f 2993/2995/528 3001/3003/528 3003/3005/528 +f 2991/2993/528 3003/3005/528 3004/3006/528 +f 2995/2997/528 2999/3001/528 3001/3003/528 +f 2995/2997/528 2997/2999/528 2999/3001/528 +f 2990/2992/7112 3004/3006/528 3006/3008/7113 +f 2990/2992/7112 2991/2993/528 3004/3006/528 +f 2990/2992/7112 3006/3008/7113 3008/3010/7114 +f 3009/3011/7115 3010/3012/7116 3011/3013/7117 +f 3009/3011/7118 3012/3014/7118 3010/3012/7118 +f 3012/3014/7119 3013/3015/7119 3010/3012/7119 +f 3013/3015/7120 3014/3016/7120 3010/3012/7120 +f 3013/3015/7121 3015/3017/7121 3014/3016/7121 +f 3013/3015/7122 3016/3018/7122 3015/3017/7122 +f 3016/3018/7123 3017/3019/7123 3015/3017/7123 +f 3016/3018/7124 3018/3020/7124 3017/3019/7124 +f 3019/3021/7125 3017/3019/7125 3018/3020/7125 +f 3019/3021/7126 3020/3022/7126 3021/3023/7126 +f 3020/3022/7127 3022/3024/7128 3021/3023/7129 +f 3020/3022/7127 3023/3025/7130 3022/3024/7128 +f 3023/3025/7131 3024/3026/7131 3022/3024/7131 +f 3023/3025/7132 3025/3027/7132 3024/3026/7132 +f 3025/3027/7133 3026/3028/7133 3024/3026/7133 +f 3025/3027/7134 3027/3029/7134 3026/3028/7134 +f 3027/3029/7135 3028/3030/7135 3026/3028/7135 +f 3027/3029/7136 3029/3031/7137 3028/3030/7138 +f 3027/3029/7136 3030/3032/7139 3029/3031/7137 +f 3009/3011/7115 3011/3013/7117 3030/3032/7140 +f 3011/3013/7141 3029/3031/7141 3030/3032/7141 +f 3013/3015/98 3012/3014/98 3025/3027/98 +f 3013/3015/98 3025/3027/98 3023/3025/98 +f 3016/3018/98 3013/3015/98 3023/3025/98 +f 3009/3011/98 3030/3032/98 3027/3029/98 +f 3012/3014/98 3009/3011/98 3027/3029/98 +f 3016/3018/98 3023/3025/98 3020/3022/7142 +f 3018/3020/7143 3020/3022/7142 3019/3021/7144 +f 3018/3020/7143 3016/3018/98 3020/3022/7142 +f 3012/3014/98 3027/3029/98 3025/3027/98 +f 3014/3016/528 3015/3017/528 3024/3026/528 +f 3015/3017/528 3017/3019/7145 3022/3024/528 +f 3024/3026/528 3015/3017/528 3022/3024/528 +f 3014/3016/528 3024/3026/528 3026/3028/528 +f 3010/3012/528 3014/3016/528 3026/3028/528 +f 3017/3019/7145 3019/3021/7146 3021/3023/7147 +f 3022/3024/528 3017/3019/7145 3021/3023/7147 +f 3010/3012/528 3026/3028/528 3028/3030/528 +f 3010/3012/528 3028/3030/528 3029/3031/528 +f 3011/3013/528 3010/3012/528 3029/3031/528 +f 3031/3033/7148 3032/3034/7148 3033/3035/7148 +f 3034/3036/7149 3031/3033/7149 3035/3037/7149 +f 3032/3034/7150 3034/3036/7150 3036/3038/7150 +f 3037/3039/7151 3038/3040/7152 3039/3041/7153 +f 3037/3039/7151 3039/3041/7153 3040/3042/7154 +f 3041/3043/7155 3038/3040/7155 3042/3044/7155 +f 3038/3040/7156 3037/3039/7156 3042/3044/7156 +f 3042/3044/7157 3037/3039/7157 3043/3045/7157 +f 3037/3039/7158 3040/3042/7158 3043/3045/7158 +f 3043/3045/7159 3040/3042/7159 3044/3046/7159 +f 3040/3042/7160 3039/3041/7161 3044/3046/7162 +f 3044/3046/7162 3039/3041/7161 3041/3043/7163 +f 3039/3041/7164 3038/3040/7164 3041/3043/7164 +f 3043/3045/7165 3044/3046/7166 3045/3047/7167 +f 3042/3044/7168 3046/3048/7169 3047/3049/7170 +f 3041/3043/7171 3047/3049/7170 3048/3050/7172 +f 3043/3045/7165 3045/3047/7167 3049/3051/7173 +f 3041/3043/7171 3042/3044/7168 3047/3049/7170 +f 3045/3047/7167 3044/3046/7166 3048/3050/7172 +f 3044/3046/7166 3041/3043/7171 3048/3050/7172 +f 3042/3044/7168 3043/3045/7165 3049/3051/7173 +f 3042/3044/7168 3049/3051/7173 3046/3048/7169 +f 3047/3049/7174 3046/3048/7174 3033/3035/7174 +f 3033/3035/7175 3046/3048/7176 3031/3033/7177 +f 3046/3048/7176 3049/3051/7178 3031/3033/7177 +f 3031/3033/7179 3049/3051/7179 3035/3037/7179 +f 3049/3051/7180 3045/3047/7180 3035/3037/7180 +f 3045/3047/7181 3034/3036/7181 3035/3037/7181 +f 3045/3047/7182 3048/3050/7183 3034/3036/7184 +f 3034/3036/7184 3048/3050/7183 3036/3038/7185 +f 3036/3038/7186 3048/3050/7187 3032/3034/7188 +f 3048/3050/7187 3047/3049/7189 3032/3034/7188 +f 3032/3034/7190 3047/3049/7190 3033/3035/7190 +f 3034/3036/7191 3050/3052/7192 3031/3033/7193 +f 3050/3052/7192 3051/3053/7194 3031/3033/7193 +f 3032/3034/7195 3050/3052/7195 3034/3036/7195 +f 3051/3053/7196 3050/3052/7196 3032/3034/7196 +f 3031/3033/7197 3051/3053/7197 3032/3034/7197 +f 3052/3054/7198 3053/3055/7199 3054/3056/7200 +f 3052/3054/7198 3055/3057/7201 3053/3055/7199 +f 3055/3057/7201 3056/3058/528 3053/3055/7199 +f 3057/3059/7202 3058/3060/7203 3059/3061/2513 +f 3058/3060/7203 3060/3062/2513 3059/3061/2513 +f 3061/3063/7204 3062/3064/7205 3063/3065/7206 +f 3061/3063/7204 3064/3066/7207 3065/3067/7208 +f 3061/3063/7204 3066/3068/7209 3062/3064/7205 +f 3061/3063/7204 3065/3067/7208 3066/3068/7209 +f 3067/3069/7210 3052/3054/7211 3066/3068/7212 +f 3052/3054/7211 3068/3070/7213 3066/3068/7212 +f 3052/3054/7211 3067/3069/7210 3069/3071/7214 +f 3066/3068/7212 3068/3070/7213 3062/3064/7215 +f 3070/3072/7216 3071/3073/7205 3072/3074/7206 +f 3070/3072/7216 3073/3075/7207 3074/3076/7208 +f 3070/3072/7216 3075/3077/7217 3071/3073/7205 +f 3070/3072/7216 3074/3076/7208 3075/3077/7217 +f 3076/3078/7218 3061/3063/7219 3075/3077/7220 +f 3061/3063/7219 3077/3079/7221 3075/3077/7220 +f 3061/3063/7219 3076/3078/7218 3078/3080/7222 +f 3075/3077/7220 3077/3079/7221 3071/3073/7223 +f 3079/3081/7204 3080/3082/7205 3081/3083/7206 +f 3079/3081/7204 3082/3084/7207 3083/3085/7208 +f 3079/3081/7204 3084/3086/7209 3080/3082/7205 +f 3079/3081/7204 3083/3085/7208 3084/3086/7209 +f 3085/3087/7218 3070/3072/7224 3084/3086/7225 +f 3070/3072/7224 3086/3088/7221 3084/3086/7225 +f 3070/3072/7224 3085/3087/7218 3087/3089/7222 +f 3084/3086/7225 3086/3088/7221 3080/3082/7223 +f 3088/3090/7204 3089/3091/7205 3090/3092/7206 +f 3088/3090/7204 3091/3093/7207 3092/3094/7208 +f 3088/3090/7204 3093/3095/7209 3089/3091/7205 +f 3088/3090/7204 3092/3094/7208 3093/3095/7209 +f 3094/3096/7218 3079/3081/7224 3093/3095/7225 +f 3079/3081/7224 3095/3097/7221 3093/3095/7225 +f 3079/3081/7224 3094/3096/7218 3096/3098/7222 +f 3093/3095/7225 3095/3097/7221 3089/3091/7223 +f 3097/3099/7226 3098/3100/7227 3099/3101/7228 +f 3097/3099/7226 3100/3102/528 3101/3103/7229 +f 3097/3099/7226 3102/3104/7230 3098/3100/7227 +f 3097/3099/7226 3101/3103/7229 3102/3104/7230 +f 3103/3105/7218 3088/3090/7224 3102/3104/7225 +f 3088/3090/7224 3104/3106/7221 3102/3104/7225 +f 3088/3090/7224 3103/3105/7218 3105/3107/7222 +f 3102/3104/7225 3104/3106/7221 3098/3100/7223 +f 3106/3108/7231 3107/3109/7232 3108/3110/7233 +f 3106/3108/7231 3109/3111/1243 3110/3112/7234 +f 3106/3108/7231 3111/3113/7235 3107/3109/7232 +f 3106/3108/7231 3110/3112/7234 3111/3113/7235 +f 3112/3114/7236 3113/3115/7237 3111/3113/7238 +f 3113/3115/7237 3114/3116/7239 3111/3113/7238 +f 3111/3113/7238 3114/3116/7239 3107/3109/7215 +f 3053/3055/7240 3057/3059/7241 3059/3061/7242 +f 3053/3055/7240 3056/3058/7243 3057/3059/7241 +f 3066/3068/7244 3065/3067/7244 3067/3069/7244 +f 3075/3077/7245 3074/3076/7245 3076/3078/7245 +f 3084/3086/7244 3083/3085/7244 3085/3087/7244 +f 3093/3095/7244 3092/3094/7244 3094/3096/7244 +f 3102/3104/7244 3101/3103/7244 3103/3105/7244 +f 3111/3113/7246 3110/3112/7246 3112/3114/7246 +f 3115/3117/528 3054/3056/528 3116/3118/528 +f 3117/3119/528 3115/3117/528 3116/3118/528 +f 3118/3120/7247 3119/3121/528 3120/3122/528 +f 3121/3123/528 3118/3120/7247 3120/3122/528 +f 3121/3123/528 3122/3124/7248 3118/3120/7247 +f 3122/3124/7248 3123/3125/7249 3118/3120/7247 +f 3124/3126/7250 3125/3127/7251 3126/3128/7252 +f 3125/3127/7251 3123/3125/7249 3126/3128/7252 +f 3123/3125/7249 3122/3124/7248 3126/3128/7252 +f 3127/3129/7253 3125/3127/7251 3124/3126/7250 +f 3128/3130/7254 3129/3131/7254 3060/3062/7254 +f 3128/3130/7254 3130/3132/7255 3129/3131/7254 +f 3131/3133/7256 3132/3134/98 3133/3135/98 +f 3134/3136/7257 3135/3137/7258 3136/3138/7259 +f 3137/3139/98 3134/3136/7257 3138/3140/98 +f 3134/3136/7257 3136/3138/7259 3138/3140/98 +f 3136/3138/7259 3135/3137/7258 3139/3141/7260 +f 3135/3137/7258 3140/3142/7261 3139/3141/7260 +f 3135/3137/7258 3131/3133/7256 3140/3142/7261 +f 3131/3133/7256 3133/3135/98 3140/3142/7261 +f 3141/3143/7262 3063/3065/7263 3142/3144/7264 +f 3143/3145/7265 3141/3143/7262 3142/3144/7264 +f 3144/3146/528 3145/3147/528 3146/3148/528 +f 3147/3149/528 3144/3146/528 3146/3148/528 +f 3147/3149/528 3148/3150/528 3144/3146/528 +f 3148/3150/528 3149/3151/528 3144/3146/528 +f 3150/3152/528 3149/3151/528 3151/3153/528 +f 3149/3151/528 3148/3150/528 3151/3153/528 +f 3152/3154/528 3149/3151/528 3150/3152/528 +f 3153/3155/7266 3142/3144/7267 3068/3070/7268 +f 3153/3155/7266 3143/3145/7269 3142/3144/7267 +f 3154/3156/7270 3123/3125/7271 3155/3157/7272 +f 3156/3158/98 3154/3156/7270 3157/3159/98 +f 3154/3156/7270 3155/3157/7272 3157/3159/98 +f 3155/3157/7272 3123/3125/7271 3158/3160/7273 +f 3123/3125/7271 3125/3127/7274 3158/3160/7273 +f 3125/3127/7274 3159/3161/7275 3158/3160/7273 +f 3125/3127/7274 3160/3162/7276 3159/3161/7275 +f 3160/3162/7276 3161/3163/98 3159/3161/7275 +f 3162/3164/7262 3072/3074/7263 3163/3165/7264 +f 3164/3166/7265 3162/3164/7262 3163/3165/7264 +f 3165/3167/7277 3166/3168/7278 3167/3169/7279 +f 3168/3170/528 3165/3167/7277 3167/3169/7279 +f 3168/3170/528 3169/3171/7280 3165/3167/7277 +f 3169/3171/7280 3170/3172/7281 3165/3167/7277 +f 3171/3173/528 3172/3174/7282 3173/3175/7283 +f 3172/3174/7282 3170/3172/7281 3173/3175/7283 +f 3170/3172/7281 3169/3171/7280 3173/3175/7283 +f 3174/3176/528 3172/3174/7282 3171/3173/528 +f 3077/3079/7284 3164/3166/7285 3163/3165/7286 +f 3077/3079/7284 3175/3177/7287 3164/3166/7285 +f 3176/3178/98 3177/3179/98 3178/3180/98 +f 3176/3178/98 3179/3181/98 3180/3182/98 +f 3176/3178/98 3178/3180/98 3179/3181/98 +f 3178/3180/98 3177/3179/98 3181/3183/98 +f 3177/3179/98 3182/3184/98 3181/3183/98 +f 3182/3184/98 3183/3185/98 3181/3183/98 +f 3182/3184/98 3184/3186/98 3183/3185/98 +f 3184/3186/98 3185/3187/98 3183/3185/98 +f 3186/3188/7262 3081/3083/7263 3187/3189/7264 +f 3188/3190/7265 3186/3188/7262 3187/3189/7264 +f 3189/3191/528 3190/3192/528 3191/3193/528 +f 3189/3191/528 3192/3194/528 3190/3192/528 +f 3189/3191/528 3193/3195/528 3192/3194/528 +f 3193/3195/528 3194/3196/7288 3192/3194/528 +f 3195/3197/7289 3196/3198/7290 3197/3199/7291 +f 3196/3198/7290 3194/3196/7288 3197/3199/7291 +f 3194/3196/7288 3193/3195/528 3197/3199/7291 +f 3198/3200/7292 3196/3198/7290 3195/3197/7289 +f 3086/3088/7284 3188/3190/7285 3187/3189/7286 +f 3086/3088/7284 3199/3201/7287 3188/3190/7285 +f 3200/3202/7293 3170/3172/7294 3201/3203/7295 +f 3170/3172/7296 3202/3204/7296 3201/3203/7296 +f 3200/3202/7293 3203/3205/7297 3166/3168/7298 +f 3200/3202/7293 3201/3203/7295 3203/3205/7297 +f 3201/3203/98 3202/3204/98 3204/3206/98 +f 3202/3204/98 3205/3207/98 3204/3206/98 +f 3202/3204/98 3206/3208/98 3205/3207/98 +f 3206/3208/98 3207/3209/98 3205/3207/98 +f 3208/3210/7262 3090/3092/7263 3209/3211/7264 +f 3210/3212/7265 3208/3210/7262 3209/3211/7264 +f 3211/3213/528 3212/3214/528 3213/3215/528 +f 3211/3213/528 3214/3216/528 3212/3214/528 +f 3211/3213/528 3215/3217/528 3214/3216/528 +f 3215/3217/528 3216/3218/528 3214/3216/528 +f 3217/3219/528 3216/3218/528 3218/3220/528 +f 3216/3218/528 3215/3217/528 3218/3220/528 +f 3219/3221/528 3216/3218/528 3217/3219/528 +f 3095/3097/7284 3210/3212/7285 3209/3211/7286 +f 3095/3097/7284 3220/3222/7287 3210/3212/7285 +f 3221/3223/98 3222/3224/7299 3223/3225/98 +f 3221/3223/98 3224/3226/98 3225/3227/98 +f 3221/3223/98 3223/3225/98 3224/3226/98 +f 3223/3225/98 3222/3224/7299 3226/3228/7300 +f 3222/3224/7299 3196/3198/7301 3226/3228/7300 +f 3196/3198/7301 3227/3229/7302 3226/3228/7300 +f 3196/3198/7301 3228/3230/7303 3227/3229/7302 +f 3228/3230/7303 3229/3231/98 3227/3229/7302 +f 3230/3232/7262 3099/3101/7263 3231/3233/7264 +f 3232/3234/7265 3230/3232/7262 3231/3233/7264 +f 3233/3235/7304 3234/3236/7305 3235/3237/528 +f 3233/3235/7304 3236/3238/7306 3234/3236/7305 +f 3233/3235/7304 3237/3239/7307 3236/3238/7306 +f 3237/3239/7307 3238/3240/7308 3236/3238/7306 +f 3239/3241/528 3238/3240/7308 3240/3242/528 +f 3238/3240/7308 3237/3239/7307 3240/3242/528 +f 3241/3243/528 3238/3240/7308 3239/3241/528 +f 3104/3106/7284 3232/3234/7285 3231/3233/7286 +f 3104/3106/7284 3242/3244/7287 3232/3234/7285 +f 3243/3245/98 3244/3246/98 3245/3247/98 +f 3243/3245/98 3246/3248/98 3247/3249/98 +f 3243/3245/98 3245/3247/98 3246/3248/98 +f 3245/3247/98 3244/3246/98 3248/3250/98 +f 3244/3246/98 3249/3251/98 3248/3250/98 +f 3249/3251/98 3250/3252/98 3248/3250/98 +f 3249/3251/98 3251/3253/98 3250/3252/98 +f 3251/3253/98 3252/3254/98 3250/3252/98 +f 3253/3255/7309 3108/3110/7310 3254/3256/7311 +f 3255/3257/7312 3253/3255/7309 3254/3256/7311 +f 3256/3258/7313 3109/3111/7314 3257/3259/7315 +f 3258/3260/7316 3259/3261/528 3260/3262/528 +f 3261/3263/528 3258/3260/7316 3260/3262/528 +f 3261/3263/528 3262/3264/7317 3258/3260/7316 +f 3262/3264/7317 3263/3265/7318 3258/3260/7316 +f 3264/3266/7319 3257/3259/7320 3265/3267/7321 +f 3257/3259/7320 3263/3265/7318 3265/3267/7321 +f 3263/3265/7318 3262/3264/7317 3265/3267/7321 +f 3257/3259/7320 3264/3266/7319 3256/3258/7322 +f 3266/3268/7266 3254/3256/7267 3114/3116/7268 +f 3266/3268/7266 3255/3257/7269 3254/3256/7267 +f 3267/3269/7323 3256/3258/7324 3268/3270/7325 +f 3236/3238/7326 3269/3271/7327 3270/3272/7328 +f 3271/3273/7329 3236/3238/7326 3272/3274/7330 +f 3236/3238/7326 3270/3272/7328 3272/3274/7330 +f 3270/3272/7328 3269/3271/7327 3273/3275/98 +f 3269/3271/7327 3267/3269/7323 3273/3275/98 +f 3267/3269/7323 3274/3276/98 3273/3275/98 +f 3267/3269/7323 3268/3270/7325 3274/3276/98 +f 3124/3126/7331 3140/3142/7332 3133/3135/7333 +f 3124/3126/7331 3126/3128/7334 3140/3142/7332 +f 3126/3128/7335 3139/3141/7335 3140/3142/7335 +f 3126/3128/7336 3122/3124/7336 3139/3141/7336 +f 3122/3124/7337 3136/3138/7337 3139/3141/7337 +f 3122/3124/7338 3121/3123/7338 3136/3138/7338 +f 3121/3123/7339 3138/3140/7340 3136/3138/7341 +f 3121/3123/7339 3120/3122/7342 3138/3140/7340 +f 3150/3152/7343 3159/3161/7343 3161/3163/7343 +f 3150/3152/7344 3151/3153/7344 3159/3161/7344 +f 3151/3153/7345 3158/3160/7273 3159/3161/7275 +f 3151/3153/7346 3148/3150/7346 3158/3160/7346 +f 3148/3150/7347 3155/3157/7272 3158/3160/7273 +f 3148/3150/7348 3147/3149/7348 3155/3157/7348 +f 3147/3149/7349 3157/3159/7349 3155/3157/7349 +f 3147/3149/7350 3146/3148/7350 3157/3159/7350 +f 3171/3173/7343 3183/3185/7343 3185/3187/7343 +f 3171/3173/7344 3173/3175/7344 3183/3185/7344 +f 3173/3175/7345 3181/3183/7345 3183/3185/7345 +f 3173/3175/7346 3169/3171/7346 3181/3183/7346 +f 3169/3171/7347 3178/3180/7347 3181/3183/7347 +f 3169/3171/7348 3168/3170/7348 3178/3180/7348 +f 3168/3170/7349 3179/3181/7349 3178/3180/7349 +f 3168/3170/7350 3167/3169/7350 3179/3181/7350 +f 3195/3197/7343 3205/3207/7343 3207/3209/7343 +f 3195/3197/7344 3197/3199/7344 3205/3207/7344 +f 3197/3199/7345 3204/3206/7345 3205/3207/7345 +f 3197/3199/7346 3193/3195/7346 3204/3206/7346 +f 3193/3195/7347 3201/3203/7347 3204/3206/7347 +f 3193/3195/7348 3189/3191/7348 3201/3203/7348 +f 3189/3191/7349 3203/3205/7349 3201/3203/7349 +f 3189/3191/7350 3191/3193/7350 3203/3205/7350 +f 3217/3219/7343 3227/3229/7343 3229/3231/7343 +f 3217/3219/7344 3218/3220/7344 3227/3229/7344 +f 3218/3220/7345 3226/3228/7300 3227/3229/7302 +f 3218/3220/7346 3215/3217/7346 3226/3228/7346 +f 3215/3217/7347 3223/3225/7347 3226/3228/7347 +f 3215/3217/7348 3211/3213/7348 3223/3225/7348 +f 3211/3213/7349 3224/3226/7349 3223/3225/7349 +f 3211/3213/7350 3213/3215/7350 3224/3226/7350 +f 3239/3241/7343 3250/3252/7343 3252/3254/7343 +f 3239/3241/7344 3240/3242/7344 3250/3252/7344 +f 3240/3242/7345 3248/3250/7345 3250/3252/7345 +f 3240/3242/7346 3237/3239/7346 3248/3250/7346 +f 3237/3239/7347 3245/3247/7347 3248/3250/7347 +f 3237/3239/7307 3233/3235/7304 3245/3247/7348 +f 3233/3235/7349 3246/3248/7349 3245/3247/7349 +f 3233/3235/7350 3235/3237/7350 3246/3248/7350 +f 3264/3266/7343 3274/3276/7343 3268/3270/7343 +f 3264/3266/7344 3265/3267/7344 3274/3276/7344 +f 3265/3267/7345 3273/3275/7345 3274/3276/7345 +f 3265/3267/7321 3262/3264/7317 3273/3275/7346 +f 3262/3264/7347 3270/3272/7347 3273/3275/7347 +f 3262/3264/7348 3261/3263/7348 3270/3272/7348 +f 3261/3263/7349 3272/3274/7349 3270/3272/7349 +f 3261/3263/7350 3260/3262/7350 3272/3274/7350 +f 3117/3119/7351 3129/3131/7352 3130/3132/7353 +f 3117/3119/7351 3116/3118/7354 3129/3131/7352 +f 3275/3277/7355 3276/3278/7356 3277/3279/7357 +f 3276/3278/7356 3278/3280/7358 3277/3279/7357 +f 3279/3281/7359 3280/3282/7360 3281/3283/7361 +f 3280/3282/7360 3282/3284/7362 3281/3283/7361 +f 3283/3285/7363 3284/3286/7364 3285/3287/7365 +f 3284/3286/7364 3286/3288/7366 3285/3287/7365 +f 3284/3286/7364 3287/3289/7367 3286/3288/7366 +f 3287/3289/7367 3288/3290/528 3286/3288/7366 +f 3287/3289/7367 3289/3291/528 3288/3290/528 +f 3289/3291/528 3290/3292/528 3288/3290/528 +f 3283/3285/7363 3285/3287/7365 3291/3293/528 +f 3292/3294/98 3293/3295/98 3294/3296/98 +f 3295/3297/7368 3137/3139/7369 3296/3298/7370 +f 3294/3296/98 3297/3299/7371 3298/3300/98 +f 3297/3299/7371 3299/3301/7372 3298/3300/98 +f 3297/3299/7371 3295/3297/7368 3299/3301/7372 +f 3295/3297/7368 3300/3302/7373 3299/3301/7372 +f 3295/3297/7368 3296/3298/7370 3300/3302/7373 +f 3294/3296/98 3298/3300/98 3292/3294/98 +f 3291/3293/7374 3300/3302/7375 3296/3298/7376 +f 3291/3293/7374 3285/3287/7377 3300/3302/7375 +f 3285/3287/7377 3299/3301/7378 3300/3302/7375 +f 3285/3287/7377 3286/3288/7379 3299/3301/7378 +f 3286/3288/7379 3298/3300/7380 3299/3301/7378 +f 3286/3288/7379 3288/3290/7381 3298/3300/7380 +f 3288/3290/7382 3292/3294/7383 3298/3300/7384 +f 3288/3290/7382 3290/3292/7385 3292/3294/7383 +f 3301/3303/7386 3302/3304/7387 3303/3305/528 +f 3304/3306/7388 3305/3307/7389 3306/3308/7390 +f 3305/3307/7389 3307/3309/7391 3306/3308/7390 +f 3305/3307/7389 3308/3310/7392 3307/3309/7391 +f 3308/3310/7392 3309/3311/7393 3307/3309/7391 +f 3308/3310/7392 3302/3304/7387 3309/3311/7393 +f 3302/3304/7387 3310/3312/7394 3309/3311/7393 +f 3302/3304/7387 3301/3303/7386 3310/3312/7394 +f 3304/3306/7388 3306/3308/7390 3311/3313/7395 +f 3312/3314/7396 3313/3315/98 3314/3316/7397 +f 3314/3316/7397 3309/3311/7398 3310/3312/7399 +f 3314/3316/7397 3315/3317/7400 3309/3311/7398 +f 3315/3317/7400 3307/3309/7401 3309/3311/7398 +f 3315/3317/7400 3284/3286/7402 3307/3309/7401 +f 3284/3286/7402 3306/3308/7403 3307/3309/7401 +f 3284/3286/7402 3316/3318/7404 3306/3308/7403 +f 3316/3318/7404 3317/3319/7405 3306/3308/7403 +f 3314/3316/7397 3310/3312/7399 3312/3314/7396 +f 3311/3313/7406 3306/3308/7406 3317/3319/7406 +f 3310/3312/7407 3301/3303/7407 3312/3314/7407 +f 3318/3320/7408 3319/3321/7409 3320/3322/7410 +f 3319/3321/7411 3321/3323/7412 3320/3322/7413 +f 3319/3321/7411 3322/3324/7414 3321/3323/7412 +f 3322/3324/7414 3323/3325/7415 3321/3323/7412 +f 3322/3324/7414 3324/3326/7416 3323/3325/7415 +f 3322/3324/7414 3325/3327/7417 3324/3326/7416 +f 3325/3327/7417 3326/3328/7418 3324/3326/7416 +f 3327/3329/7419 3318/3320/7408 3328/3330/7420 +f 3318/3320/7408 3320/3322/7410 3328/3330/7420 +f 3329/3331/7421 3330/3332/98 3331/3333/7422 +f 3331/3333/7422 3323/3325/7423 3324/3326/7424 +f 3331/3333/7422 3308/3310/7425 3323/3325/7423 +f 3308/3310/7425 3321/3323/7426 3323/3325/7423 +f 3308/3310/7425 3305/3307/7427 3321/3323/7426 +f 3305/3307/7427 3320/3322/7428 3321/3323/7426 +f 3305/3307/7427 3332/3334/7429 3320/3322/7428 +f 3332/3334/7429 3333/3335/7430 3320/3322/7428 +f 3331/3333/7422 3324/3326/7424 3329/3331/7421 +f 3328/3330/7431 3320/3322/7431 3333/3335/7431 +f 3324/3326/7432 3326/3328/7432 3329/3331/7432 +f 3334/3336/7433 3335/3337/7434 3336/3338/7435 +f 3337/3339/7436 3338/3340/7437 3339/3341/7438 +f 3338/3340/7437 3340/3342/7439 3339/3341/7438 +f 3338/3340/7437 3341/3343/7440 3340/3342/7439 +f 3341/3343/7440 3342/3344/7441 3340/3342/7439 +f 3341/3343/7440 3335/3337/7434 3342/3344/7441 +f 3335/3337/7434 3343/3345/7442 3342/3344/7441 +f 3335/3337/7434 3334/3336/7433 3343/3345/7442 +f 3344/3346/7443 3337/3339/7436 3345/3347/7444 +f 3337/3339/7436 3339/3341/7438 3345/3347/7444 +f 3346/3348/7421 3347/3349/98 3348/3350/7445 +f 3348/3350/7445 3342/3344/7446 3343/3345/7424 +f 3348/3350/7445 3349/3351/7447 3342/3344/7446 +f 3349/3351/7447 3340/3342/7448 3342/3344/7446 +f 3349/3351/7447 3318/3320/7449 3340/3342/7448 +f 3318/3320/7449 3339/3341/7450 3340/3342/7448 +f 3318/3320/7449 3350/3352/7451 3339/3341/7450 +f 3350/3352/7451 3351/3353/7430 3339/3341/7450 +f 3348/3350/7445 3343/3345/7424 3346/3348/7421 +f 3345/3347/7431 3339/3341/7431 3351/3353/7431 +f 3343/3345/7432 3334/3336/7432 3346/3348/7432 +f 3352/3354/7386 3353/3355/7452 3354/3356/528 +f 3355/3357/7453 3356/3358/7454 3357/3359/7455 +f 3356/3358/7456 3358/3360/7457 3357/3359/7458 +f 3356/3358/7456 3359/3361/7459 3358/3360/7457 +f 3356/3358/7456 3353/3355/7452 3359/3361/7459 +f 3353/3355/7452 3360/3362/7394 3359/3361/7459 +f 3353/3355/7452 3352/3354/7386 3360/3362/7394 +f 3361/3363/7419 3355/3357/7453 3362/3364/7420 +f 3355/3357/7453 3357/3359/7455 3362/3364/7420 +f 3363/3365/7460 3364/3366/7461 3335/3337/7462 +f 3335/3337/7462 3359/3361/7463 3360/3362/7464 +f 3335/3337/7462 3341/3343/7465 3359/3361/7463 +f 3341/3343/7465 3358/3360/7466 3359/3361/7463 +f 3341/3343/7465 3338/3340/7467 3358/3360/7466 +f 3338/3340/7467 3337/3339/7468 3358/3360/7466 +f 3337/3339/7468 3357/3359/7469 3358/3360/7466 +f 3337/3339/7468 3365/3367/7470 3357/3359/7469 +f 3365/3367/7470 3366/3368/7430 3357/3359/7469 +f 3335/3337/7462 3360/3362/7464 3363/3365/7460 +f 3362/3364/7431 3357/3359/7431 3366/3368/7431 +f 3360/3362/7471 3352/3354/7471 3363/3365/7471 +f 3367/3369/7472 3368/3370/7473 3369/3371/528 +f 3370/3372/7388 3371/3373/7474 3372/3374/7475 +f 3371/3373/7474 3373/3375/7391 3372/3374/7475 +f 3371/3373/7474 3374/3376/7392 3373/3375/7391 +f 3374/3376/7392 3375/3377/7393 3373/3375/7391 +f 3374/3376/7392 3368/3370/7473 3375/3377/7393 +f 3368/3370/7473 3376/3378/7394 3375/3377/7393 +f 3368/3370/7473 3367/3369/7472 3376/3378/7394 +f 3370/3372/7388 3372/3374/7475 3377/3379/7395 +f 3378/3380/7421 3379/3381/98 3380/3382/7445 +f 3380/3382/7445 3375/3377/7476 3376/3378/7424 +f 3380/3382/7445 3381/3383/7447 3375/3377/7476 +f 3381/3383/7447 3373/3375/7448 3375/3377/7476 +f 3381/3383/7447 3355/3357/7449 3373/3375/7448 +f 3355/3357/7449 3372/3374/7450 3373/3375/7448 +f 3355/3357/7449 3382/3384/7451 3372/3374/7450 +f 3382/3384/7451 3383/3385/7430 3372/3374/7450 +f 3380/3382/7445 3376/3378/7424 3378/3380/7421 +f 3377/3379/7431 3372/3374/7431 3383/3385/7431 +f 3376/3378/7432 3367/3369/7432 3378/3380/7432 +f 3384/3386/7477 3385/3387/7478 3386/3388/528 +f 3387/3389/7479 3388/3390/7480 3389/3391/7481 +f 3387/3389/7479 3390/3392/7482 3388/3390/7480 +f 3390/3392/7482 3391/3393/7483 3388/3390/7480 +f 3390/3392/7482 3385/3387/7478 3391/3393/7483 +f 3385/3387/7478 3392/3394/7484 3391/3393/7483 +f 3385/3387/7478 3384/3386/7477 3392/3394/7484 +f 3393/3395/528 3387/3389/7479 3394/3396/7485 +f 3387/3389/7479 3389/3391/7481 3394/3396/7485 +f 3395/3397/7421 3396/3398/98 3397/3399/7486 +f 3397/3399/7486 3391/3393/7423 3392/3394/7424 +f 3397/3399/7486 3374/3376/7425 3391/3393/7423 +f 3374/3376/7425 3388/3390/7426 3391/3393/7423 +f 3374/3376/7425 3371/3373/7487 3388/3390/7426 +f 3371/3373/7487 3389/3391/7428 3388/3390/7426 +f 3371/3373/7487 3398/3400/7429 3389/3391/7428 +f 3398/3400/7429 3399/3401/7430 3389/3391/7428 +f 3397/3399/7486 3392/3394/7424 3395/3397/7421 +f 3394/3396/7488 3389/3391/7488 3399/3401/7488 +f 3392/3394/7432 3384/3386/7432 3395/3397/7432 +f 3277/3279/7357 3400/3402/7489 3275/3277/7355 +f 3277/3279/7357 3401/3403/7490 3400/3402/7489 +f 3401/3403/7490 3402/3404/7491 3400/3402/7489 +f 3402/3404/7491 3403/3405/7492 3400/3402/7489 +f 3402/3404/7491 3404/3406/7493 3403/3405/7492 +f 3404/3406/7493 3405/3407/7494 3403/3405/7492 +f 3404/3406/7493 3406/3408/7495 3405/3407/7494 +f 3387/3389/7496 3393/3395/7496 3407/3409/7496 +f 3393/3395/7497 3408/3410/7497 3407/3409/7497 +f 3393/3395/7498 3259/3261/7499 3408/3410/7500 +f 3259/3261/7501 3258/3260/7501 3408/3410/7501 +f 3387/3389/7479 3407/3409/7502 3390/3392/7482 +f 3385/3387/7503 3390/3392/7503 3409/3411/7503 +f 3409/3411/7504 3410/3412/7504 3385/3387/7504 +f 3410/3412/7505 3386/3388/7506 3385/3387/7507 +f 3410/3412/7505 3411/3413/7508 3386/3388/7506 +f 3411/3413/7509 3410/3412/7509 3412/3414/7509 +f 3413/3415/7510 3414/3416/7511 3415/3417/7512 +f 3416/3418/7513 3413/3415/7510 3415/3417/7512 +f 3415/3417/7514 3417/3419/7514 3416/3418/7514 +f 3417/3419/7515 3418/3420/7516 3253/3255/7517 +f 3108/3110/7518 3418/3420/7518 3419/3421/7518 +f 3108/3110/7519 3253/3255/7519 3418/3420/7519 +f 3419/3421/7520 3106/3108/7520 3108/3110/7520 +f 3109/3111/7521 3106/3108/7522 3420/3422/7523 +f 3106/3108/7522 3419/3421/7524 3420/3422/7523 +f 3257/3259/7525 3109/3111/7525 3420/3422/7525 +f 3258/3260/7526 3421/3423/7526 3408/3410/7526 +f 3258/3260/7527 3263/3265/7528 3421/3423/7529 +f 3257/3259/7530 3420/3422/7530 3263/3265/7530 +f 3398/3400/7531 3234/3236/7532 3271/3273/7533 +f 3234/3236/7532 3398/3400/7531 3370/3372/7534 +f 3398/3400/7531 3371/3373/7535 3370/3372/7534 +f 3374/3376/7536 3397/3399/7536 3368/3370/7536 +f 3397/3399/7537 3369/3371/7538 3368/3370/7539 +f 3397/3399/7537 3396/3398/7540 3369/3371/7538 +f 3396/3398/7540 3422/3424/7541 3369/3371/7538 +f 3423/3425/7542 3424/3426/7543 3425/3427/7544 +f 3425/3427/7544 3424/3426/7543 3426/3428/7545 +f 3424/3426/7543 3427/3429/7546 3426/3428/7545 +f 3427/3429/7547 3428/3430/7547 3426/3428/7547 +f 3427/3429/7548 3266/3268/7548 3428/3430/7548 +f 3266/3268/7549 3230/3232/7550 3428/3430/7551 +f 3266/3268/7549 3099/3101/7552 3230/3232/7550 +f 3266/3268/7549 3114/3116/7553 3099/3101/7552 +f 3114/3116/7553 3097/3099/7554 3099/3101/7552 +f 3114/3116/7555 3113/3115/7555 3097/3099/7555 +f 3113/3115/7556 3256/3258/7556 3097/3099/7556 +f 3256/3258/7557 3100/3102/7558 3097/3099/7559 +f 3234/3236/7532 3236/3238/7560 3271/3273/7533 +f 3236/3238/7326 3238/3240/7561 3269/3271/7327 +f 3238/3240/7562 3267/3269/7562 3269/3271/7562 +f 3238/3240/7563 3241/3243/7563 3267/3269/7563 +f 3241/3243/7564 3256/3258/7557 3267/3269/7565 +f 3241/3243/7564 3100/3102/7558 3256/3258/7557 +f 3382/3384/7566 3212/3214/7567 3247/3249/7568 +f 3212/3214/7567 3382/3384/7566 3361/3363/7569 +f 3382/3384/7566 3355/3357/7570 3361/3363/7569 +f 3355/3357/7453 3381/3383/7571 3356/3358/7454 +f 3381/3383/7572 3353/3355/7572 3356/3358/7572 +f 3381/3383/7573 3380/3382/7573 3353/3355/7573 +f 3380/3382/7574 3354/3356/7575 3353/3355/7576 +f 3380/3382/7574 3379/3381/7577 3354/3356/7575 +f 3379/3381/7577 3429/3431/7578 3354/3356/7575 +f 3430/3432/7579 3431/3433/7580 3432/3434/7581 +f 3431/3433/7580 3430/3432/7579 3433/3435/7582 +f 3430/3432/7579 3434/3436/7583 3433/3435/7582 +f 3434/3436/7547 3435/3437/7547 3433/3435/7547 +f 3434/3436/7584 3242/3244/7585 3435/3437/7586 +f 3242/3244/7585 3208/3210/7587 3435/3437/7586 +f 3242/3244/7585 3104/3106/7588 3208/3210/7587 +f 3104/3106/7589 3090/3092/7590 3208/3210/7591 +f 3104/3106/7589 3088/3090/7592 3090/3092/7590 +f 3105/3107/7593 3091/3093/7594 3088/3090/7595 +f 3212/3214/7567 3243/3245/7596 3247/3249/7568 +f 3212/3214/7597 3214/3216/7597 3243/3245/7597 +f 3214/3216/7598 3244/3246/7598 3243/3245/7598 +f 3214/3216/7599 3216/3218/7599 3244/3246/7599 +f 3216/3218/7600 3249/3251/7600 3244/3246/7600 +f 3216/3218/7601 3251/3253/7602 3249/3251/7603 +f 3216/3218/7601 3219/3221/7604 3251/3253/7602 +f 3219/3221/7604 3105/3107/7593 3251/3253/7602 +f 3219/3221/7604 3091/3093/7594 3105/3107/7593 +f 3365/3367/7605 3190/3192/7606 3225/3227/7607 +f 3190/3192/7606 3365/3367/7605 3344/3346/7608 +f 3365/3367/7605 3337/3339/7609 3344/3346/7608 +f 3364/3366/7610 3336/3338/7611 3335/3337/7612 +f 3364/3366/7610 3436/3438/7613 3336/3338/7611 +f 3436/3438/7613 3437/3439/7614 3336/3338/7611 +f 3438/3440/7615 3439/3441/7543 3440/3442/7544 +f 3440/3442/7544 3439/3441/7543 3441/3443/7616 +f 3439/3441/7543 3442/3444/7617 3441/3443/7616 +f 3442/3444/7618 3443/3445/7618 3441/3443/7618 +f 3442/3444/7619 3220/3222/7620 3443/3445/7621 +f 3220/3222/7620 3186/3188/7587 3443/3445/7621 +f 3220/3222/7620 3095/3097/7588 3186/3188/7587 +f 3095/3097/7589 3081/3083/7590 3186/3188/7591 +f 3095/3097/7589 3079/3081/7592 3081/3083/7590 +f 3096/3098/7622 3082/3084/7594 3079/3081/7595 +f 3190/3192/7606 3221/3223/7596 3225/3227/7607 +f 3190/3192/7623 3192/3194/7623 3221/3223/7623 +f 3192/3194/7624 3222/3224/7624 3221/3223/7624 +f 3192/3194/7625 3194/3196/7625 3222/3224/7625 +f 3194/3196/7626 3196/3198/7626 3222/3224/7626 +f 3196/3198/7627 3198/3200/7628 3228/3230/7629 +f 3198/3200/7628 3096/3098/7622 3228/3230/7629 +f 3198/3200/7628 3082/3084/7594 3096/3098/7622 +f 3202/3204/7630 3170/3172/7630 3172/3174/7630 +f 3170/3172/7631 3200/3202/7631 3165/3167/7631 +f 3200/3202/7632 3166/3168/7632 3165/3167/7632 +f 3166/3168/7633 3350/3352/7634 3327/3329/7635 +f 3350/3352/7634 3318/3320/7570 3327/3329/7635 +f 3318/3320/7408 3349/3351/7636 3319/3321/7409 +f 3349/3351/7637 3322/3324/7637 3319/3321/7637 +f 3349/3351/7638 3348/3350/7638 3322/3324/7638 +f 3348/3350/7639 3325/3327/7639 3322/3324/7639 +f 3348/3350/7640 3347/3349/7641 3325/3327/7642 +f 3347/3349/7641 3444/3446/7643 3325/3327/7642 +f 3347/3349/7641 3445/3447/7644 3444/3446/7643 +f 3446/3448/7542 3447/3449/7543 3448/3450/7544 +f 3448/3450/7544 3447/3449/7543 3449/3451/7545 +f 3447/3449/7543 3450/3452/7546 3449/3451/7545 +f 3450/3452/7547 3451/3453/7547 3449/3451/7547 +f 3450/3452/7584 3199/3201/7585 3451/3453/7586 +f 3199/3201/7585 3162/3164/7587 3451/3453/7586 +f 3199/3201/7585 3086/3088/7588 3162/3164/7587 +f 3086/3088/7589 3072/3074/7590 3162/3164/7591 +f 3086/3088/7589 3070/3072/7592 3072/3074/7590 +f 3087/3089/7622 3073/3075/7594 3070/3072/7595 +f 3087/3089/7622 3174/3176/7645 3073/3075/7594 +f 3087/3089/7622 3206/3208/7646 3174/3176/7645 +f 3206/3208/7646 3172/3174/7647 3174/3176/7645 +f 3206/3208/7648 3202/3204/7648 3172/3174/7648 +f 3332/3334/7649 3145/3147/7650 3180/3182/7651 +f 3145/3147/7650 3332/3334/7649 3304/3306/7652 +f 3332/3334/7649 3305/3307/7535 3304/3306/7652 +f 3308/3310/7653 3331/3333/7653 3302/3304/7653 +f 3331/3333/7654 3303/3305/7655 3302/3304/7656 +f 3331/3333/7654 3330/3332/7577 3303/3305/7655 +f 3330/3332/7577 3452/3454/7578 3303/3305/7655 +f 3453/3455/7542 3454/3456/7543 3455/3457/7544 +f 3455/3457/7544 3454/3456/7543 3456/3458/7545 +f 3454/3456/7543 3457/3459/7546 3456/3458/7545 +f 3457/3459/7547 3458/3460/7547 3456/3458/7547 +f 3457/3459/7584 3175/3177/7585 3458/3460/7657 +f 3175/3177/7585 3141/3143/7658 3458/3460/7657 +f 3175/3177/7585 3077/3079/7588 3141/3143/7658 +f 3077/3079/7589 3063/3065/7590 3141/3143/7591 +f 3077/3079/7589 3061/3063/7592 3063/3065/7590 +f 3078/3080/7622 3064/3066/7594 3061/3063/7595 +f 3145/3147/7650 3176/3178/7659 3180/3182/7651 +f 3145/3147/7660 3144/3146/7660 3176/3178/7660 +f 3144/3146/7661 3177/3179/7661 3176/3178/7661 +f 3144/3146/7662 3149/3151/7662 3177/3179/7662 +f 3149/3151/7600 3182/3184/7600 3177/3179/7600 +f 3149/3151/7663 3184/3186/7602 3182/3184/7664 +f 3149/3151/7663 3152/3154/7604 3184/3186/7602 +f 3152/3154/7604 3078/3080/7622 3184/3186/7602 +f 3152/3154/7604 3064/3066/7594 3078/3080/7622 +f 3119/3121/7665 3316/3318/7666 3283/3285/7667 +f 3316/3318/7666 3284/3286/7668 3283/3285/7667 +f 3315/3317/7400 3287/3289/7669 3284/3286/7402 +f 3315/3317/7670 3314/3316/7670 3287/3289/7670 +f 3314/3316/7671 3289/3291/7671 3287/3289/7671 +f 3314/3316/7672 3313/3315/7673 3289/3291/7674 +f 3313/3315/7673 3459/3461/7675 3289/3291/7674 +f 3459/3461/7675 3460/3462/7676 3289/3291/7674 +f 3459/3461/7675 3461/3463/7677 3460/3462/7676 +f 3462/3464/7615 3463/3465/7543 3464/3466/7678 +f 3464/3466/7678 3463/3465/7543 3465/3467/7679 +f 3463/3465/7543 3466/3468/7546 3465/3467/7679 +f 3466/3468/7547 3467/3469/7547 3465/3467/7547 +f 3466/3468/7680 3153/3155/7680 3467/3469/7680 +f 3153/3155/7549 3115/3117/7681 3467/3469/7682 +f 3153/3155/7549 3054/3056/7683 3115/3117/7681 +f 3153/3155/7549 3068/3070/7684 3054/3056/7683 +f 3068/3070/7684 3052/3054/7685 3054/3056/7683 +f 3052/3054/7686 3069/3071/7687 3055/3057/7688 +f 3069/3071/7687 3127/3129/7689 3055/3057/7688 +f 3119/3121/7690 3156/3158/7691 3316/3318/7692 +f 3119/3121/7690 3118/3120/7693 3156/3158/7691 +f 3118/3120/7694 3154/3156/7694 3156/3158/7694 +f 3118/3120/7695 3123/3125/7695 3154/3156/7695 +f 3125/3127/7696 3127/3129/7697 3160/3162/7698 +f 3127/3129/7697 3069/3071/7699 3160/3162/7698 +f 3468/3470/7700 3469/3471/7701 3470/3472/7702 +f 3468/3470/7700 3471/3473/7703 3469/3471/7701 +f 3471/3473/7703 3472/3474/7704 3469/3471/7701 +f 3471/3473/7703 3473/3475/7705 3472/3474/7704 +f 3473/3475/7705 3474/3476/7706 3472/3474/7704 +f 3473/3475/7705 3475/3477/7707 3474/3476/7706 +f 3475/3477/7707 3476/3478/7708 3474/3476/7706 +f 3475/3477/7707 3477/3479/7709 3476/3478/7708 +f 3475/3477/7707 3478/3480/7710 3477/3479/7709 +f 3479/3481/7711 3480/3482/7712 3481/3483/7713 +f 3480/3482/7712 3482/3484/7714 3481/3483/7713 +f 3483/3485/7715 3484/3486/7716 3485/3487/7717 +f 3483/3485/7715 3486/3488/7718 3484/3486/7716 +f 3409/3411/7719 3474/3476/7720 3476/3478/7721 +f 3400/3402/7722 3263/3265/7528 3275/3277/7723 +f 3275/3277/7723 3263/3265/7528 3420/3422/7724 +f 3409/3411/7719 3476/3478/7721 3477/3479/7725 +f 3409/3411/7719 3477/3479/7725 3410/3412/7726 +f 3275/3277/7723 3420/3422/7724 3276/3278/7727 +f 3487/3489/7728 3276/3278/7727 3420/3422/7724 +f 3410/3412/7726 3477/3479/7725 3488/3490/7729 +f 3410/3412/7726 3488/3490/7729 3489/3491/7730 +f 3487/3489/7728 3420/3422/7724 3279/3281/7731 +f 3420/3422/7724 3419/3421/7732 3279/3281/7731 +f 3410/3412/7726 3489/3491/7730 3490/3492/7733 +f 3410/3412/7726 3490/3492/7733 3412/3414/7734 +f 3412/3414/7734 3490/3492/7733 3491/3493/7735 +f 3399/3401/7736 3398/3400/7737 3394/3396/7738 +f 3398/3400/7737 3393/3395/7739 3394/3396/7738 +f 3398/3400/7531 3271/3273/7533 3393/3395/7498 +f 3271/3273/7533 3259/3261/7499 3393/3395/7498 +f 3271/3273/7740 3272/3274/7741 3259/3261/7742 +f 3272/3274/7741 3260/3262/7743 3259/3261/7742 +f 3383/3385/7736 3382/3384/7744 3377/3379/7745 +f 3382/3384/7744 3370/3372/7746 3377/3379/7745 +f 3382/3384/7747 3247/3249/7748 3370/3372/7534 +f 3247/3249/7748 3234/3236/7532 3370/3372/7534 +f 3247/3249/7749 3246/3248/7750 3234/3236/7751 +f 3246/3248/7750 3235/3237/7752 3234/3236/7751 +f 3366/3368/7736 3365/3367/7753 3362/3364/7754 +f 3365/3367/7753 3361/3363/7755 3362/3364/7754 +f 3365/3367/7605 3225/3227/7607 3361/3363/7569 +f 3225/3227/7607 3212/3214/7567 3361/3363/7569 +f 3225/3227/7749 3224/3226/7750 3212/3214/7751 +f 3224/3226/7750 3213/3215/7752 3212/3214/7751 +f 3351/3353/7736 3350/3352/7753 3345/3347/7754 +f 3350/3352/7753 3344/3346/7755 3345/3347/7754 +f 3350/3352/7634 3166/3168/7633 3344/3346/7608 +f 3166/3168/7633 3190/3192/7606 3344/3346/7608 +f 3166/3168/7756 3203/3205/7757 3190/3192/7758 +f 3203/3205/7757 3191/3193/7752 3190/3192/7758 +f 3333/3335/7736 3332/3334/7753 3328/3330/7754 +f 3332/3334/7753 3327/3329/7755 3328/3330/7754 +f 3332/3334/7649 3180/3182/7651 3327/3329/7635 +f 3180/3182/7651 3166/3168/7633 3327/3329/7635 +f 3180/3182/7759 3179/3181/7760 3166/3168/7761 +f 3179/3181/7760 3167/3169/7762 3166/3168/7761 +f 3317/3319/7763 3304/3306/7764 3311/3313/7765 +f 3317/3319/7763 3316/3318/7766 3304/3306/7764 +f 3316/3318/7767 3145/3147/7650 3304/3306/7652 +f 3316/3318/7692 3156/3158/7691 3145/3147/7768 +f 3156/3158/7769 3157/3159/7770 3145/3147/7771 +f 3157/3159/7770 3146/3148/7772 3145/3147/7771 +f 3296/3298/7773 3283/3285/7773 3291/3293/7773 +f 3296/3298/7774 3137/3139/7774 3283/3285/7774 +f 3137/3139/7775 3119/3121/7665 3283/3285/7667 +f 3137/3139/7776 3138/3140/7777 3119/3121/7778 +f 3138/3140/7777 3120/3122/7779 3119/3121/7778 +f 3268/3270/7780 3256/3258/7780 3264/3266/7780 +f 3256/3258/7313 3113/3115/7781 3109/3111/7314 +f 3113/3115/7782 3112/3114/7783 3109/3111/7784 +f 3112/3114/7783 3110/3112/7785 3109/3111/7784 +f 3252/3254/7786 3251/3253/7787 3239/3241/7788 +f 3251/3253/7787 3241/3243/7789 3239/3241/7788 +f 3251/3253/7602 3105/3107/7593 3241/3243/7564 +f 3105/3107/7593 3100/3102/7558 3241/3243/7564 +f 3105/3107/7790 3103/3105/7791 3100/3102/7792 +f 3103/3105/7791 3101/3103/7793 3100/3102/7792 +f 3229/3231/7786 3228/3230/7787 3217/3219/7788 +f 3228/3230/7787 3219/3221/7789 3217/3219/7788 +f 3228/3230/7629 3096/3098/7622 3219/3221/7604 +f 3096/3098/7622 3091/3093/7594 3219/3221/7604 +f 3096/3098/7790 3094/3096/7791 3091/3093/7792 +f 3094/3096/7791 3092/3094/7793 3091/3093/7792 +f 3207/3209/7786 3206/3208/7787 3195/3197/7788 +f 3206/3208/7787 3198/3200/7789 3195/3197/7788 +f 3206/3208/7646 3087/3089/7622 3198/3200/7628 +f 3087/3089/7622 3082/3084/7594 3198/3200/7628 +f 3087/3089/7790 3085/3087/7791 3082/3084/7792 +f 3085/3087/7791 3083/3085/7793 3082/3084/7792 +f 3185/3187/7786 3184/3186/7787 3171/3173/7788 +f 3184/3186/7787 3174/3176/7789 3171/3173/7788 +f 3184/3186/7602 3078/3080/7622 3174/3176/7645 +f 3078/3080/7622 3073/3075/7594 3174/3176/7645 +f 3078/3080/7790 3076/3078/7791 3073/3075/7792 +f 3076/3078/7791 3074/3076/7793 3073/3075/7792 +f 3161/3163/7786 3160/3162/7787 3150/3152/7788 +f 3160/3162/7787 3152/3154/7789 3150/3152/7788 +f 3160/3162/7698 3069/3071/7699 3152/3154/7604 +f 3069/3071/7699 3064/3066/7594 3152/3154/7604 +f 3069/3071/7790 3067/3069/7791 3064/3066/7792 +f 3067/3069/7791 3065/3067/7793 3064/3066/7792 +f 3133/3135/7794 3132/3134/7795 3124/3126/7796 +f 3132/3134/7795 3127/3129/7797 3124/3126/7796 +f 3132/3134/7798 3058/3060/7799 3127/3129/7689 +f 3058/3060/7799 3055/3057/7688 3127/3129/7689 +f 3058/3060/7800 3057/3059/7801 3055/3057/7802 +f 3057/3059/7801 3056/3058/7803 3055/3057/7802 +f 3114/3116/7804 3108/3110/7804 3107/3109/7804 +f 3114/3116/7805 3254/3256/7805 3108/3110/7805 +f 3104/3106/7806 3099/3101/7806 3098/3100/7806 +f 3104/3106/7807 3231/3233/7807 3099/3101/7807 +f 3095/3097/7806 3090/3092/7806 3089/3091/7806 +f 3095/3097/7808 3209/3211/7808 3090/3092/7808 +f 3086/3088/7806 3081/3083/7806 3080/3082/7806 +f 3086/3088/7808 3187/3189/7808 3081/3083/7808 +f 3077/3079/7806 3072/3074/7806 3071/3073/7806 +f 3077/3079/7808 3163/3165/7808 3072/3074/7808 +f 3068/3070/7809 3063/3065/7809 3062/3064/7809 +f 3068/3070/7810 3142/3144/7810 3063/3065/7810 +f 3059/3061/7811 3060/3062/7812 3053/3055/7813 +f 3060/3062/7812 3054/3056/7814 3053/3055/7813 +f 3060/3062/7815 3129/3131/7816 3054/3056/7817 +f 3129/3131/7816 3116/3118/7818 3054/3056/7817 +f 3485/3487/7819 3468/3470/7700 3483/3485/7820 +f 3468/3470/7700 3470/3472/7702 3483/3485/7820 +f 3406/3408/7495 3484/3486/7821 3405/3407/7494 +f 3484/3486/7821 3486/3488/7822 3405/3407/7494 +f 3487/3489/7823 3279/3281/7359 3492/3494/7824 +f 3279/3281/7359 3281/3283/7361 3492/3494/7824 +f 3276/3278/7356 3487/3489/7825 3278/3280/7358 +f 3487/3489/7825 3492/3494/7826 3278/3280/7358 +f 3280/3282/7827 3482/3484/7714 3282/3284/7828 +f 3280/3282/7827 3481/3483/7829 3482/3484/7714 +f 3493/3495/7830 3494/3496/7831 3495/3497/7832 +f 3496/3498/7833 3494/3496/7831 3493/3495/7830 +f 3495/3497/7832 3497/3499/7834 3493/3495/7830 +f 3498/3500/7835 3499/3501/7836 3500/3502/7837 +f 3501/3503/7838 3478/3480/7839 3498/3500/7835 +f 3501/3503/7838 3498/3500/7835 3500/3502/7837 +f 3412/3414/7734 3491/3493/7735 3502/3504/7840 +f 3280/3282/7841 3419/3421/7732 3481/3483/7842 +f 3481/3483/7842 3419/3421/7732 3418/3420/7843 +f 3412/3414/7734 3502/3504/7840 3503/3505/7844 +f 3503/3505/7844 3502/3504/7840 3504/3506/7845 +f 3481/3483/7842 3418/3420/7843 3479/3481/7846 +f 3479/3481/7846 3418/3420/7843 3505/3507/7847 +f 3503/3505/7844 3504/3506/7845 3414/3416/7848 +f 3419/3421/7732 3280/3282/7841 3279/3281/7731 +f 3414/3416/7848 3506/3508/7849 3415/3417/7850 +f 3506/3508/7849 3507/3509/7851 3415/3417/7850 +f 3415/3417/7850 3507/3509/7851 3508/3510/7852 +f 3505/3507/7847 3417/3419/7853 3415/3417/7850 +f 3415/3417/7850 3508/3510/7852 3505/3507/7847 +f 3505/3507/7847 3418/3420/7843 3417/3419/7853 +f 3408/3410/7854 3486/3488/7855 3483/3485/7856 +f 3405/3407/7857 3486/3488/7855 3408/3410/7854 +f 3408/3410/7854 3483/3485/7856 3470/3472/7858 +f 3408/3410/7854 3470/3472/7858 3407/3409/7859 +f 3405/3407/7857 3408/3410/7854 3403/3405/7860 +f 3407/3409/7859 3470/3472/7858 3469/3471/7861 +f 3407/3409/7859 3469/3471/7861 3472/3474/7862 +f 3504/3506/7845 3506/3508/7849 3414/3416/7848 +f 3408/3410/7854 3421/3423/7529 3403/3405/7860 +f 3407/3409/7859 3472/3474/7862 3390/3392/7863 +f 3390/3392/7863 3472/3474/7862 3474/3476/7720 +f 3403/3405/7860 3421/3423/7529 3400/3402/7722 +f 3400/3402/7722 3421/3423/7529 3263/3265/7528 +f 3390/3392/7863 3474/3476/7720 3409/3411/7719 +f 3465/3467/528 3467/3469/528 3509/3511/528 +f 3465/3467/528 3509/3511/528 3510/3512/528 +f 3511/3513/98 3512/3514/98 3513/3515/1245 +f 3511/3513/98 3513/3515/1245 3128/3130/1245 +f 3513/3515/1245 3512/3514/98 3514/3516/98 +f 3456/3458/7864 3458/3460/7865 3515/3517/7866 +f 3458/3460/7865 3516/3518/7867 3515/3517/7866 +f 3456/3458/7864 3515/3517/7866 3517/3519/7868 +f 3518/3520/7869 3466/3468/7870 3463/3465/98 +f 3466/3468/7870 3515/3517/7871 3516/3518/7872 +f 3466/3468/7870 3516/3518/7872 3153/3155/7873 +f 3515/3517/7871 3466/3468/7870 3518/3520/7869 +f 3449/3451/528 3451/3453/7874 3519/3521/7875 +f 3451/3453/7874 3520/3522/7876 3519/3521/7875 +f 3521/3523/7877 3457/3459/7878 3454/3456/98 +f 3457/3459/7878 3521/3523/7877 3520/3522/7879 +f 3457/3459/7878 3520/3522/7879 3175/3177/7880 +f 3441/3443/7864 3443/3445/7881 3522/3524/7882 +f 3443/3445/7881 3523/3525/7883 3522/3524/7882 +f 3441/3443/7864 3522/3524/7882 3524/3526/7868 +f 3525/3527/7869 3450/3452/7884 3447/3449/98 +f 3450/3452/7884 3522/3524/7885 3523/3525/7886 +f 3450/3452/7884 3523/3525/7886 3199/3201/7887 +f 3522/3524/7885 3450/3452/7884 3525/3527/7869 +f 3433/3435/528 3435/3437/7874 3526/3528/7875 +f 3435/3437/7874 3527/3529/7888 3526/3528/7875 +f 3528/3530/7877 3442/3444/7889 3439/3441/98 +f 3442/3444/7889 3528/3530/7877 3527/3529/7879 +f 3442/3444/7889 3527/3529/7879 3220/3222/7880 +f 3426/3428/528 3428/3430/7874 3529/3531/7875 +f 3428/3430/7874 3530/3532/7876 3529/3531/7875 +f 3531/3533/7890 3434/3436/7891 3430/3432/98 +f 3434/3436/7891 3531/3533/7890 3530/3532/7879 +f 3434/3436/7891 3530/3532/7879 3242/3244/7880 +f 3416/3418/7892 3417/3419/7893 3532/3534/7894 +f 3417/3419/7893 3533/3535/7895 3532/3534/7894 +f 3534/3536/98 3427/3429/98 3424/3426/98 +f 3427/3429/98 3535/3537/98 3266/3268/98 +f 3535/3537/98 3427/3429/98 3534/3536/98 +f 3510/3512/7896 3513/3515/7897 3514/3516/7898 +f 3510/3512/7896 3509/3511/7899 3513/3515/7897 +f 3517/3519/7900 3515/3517/7900 3518/3520/7900 +f 3519/3521/7901 3520/3522/7901 3521/3523/7901 +f 3524/3526/7900 3522/3524/7900 3525/3527/7900 +f 3526/3528/7901 3527/3529/7901 3528/3530/7901 +f 3529/3531/7901 3530/3532/7901 3531/3533/7901 +f 3532/3534/7902 3535/3537/7902 3534/3536/7902 +f 3532/3534/7903 3533/3535/7903 3535/3537/7903 +f 3536/3538/7904 3462/3464/7905 3464/3466/7906 +f 3461/3463/7907 3537/3539/7908 3460/3462/7909 +f 3537/3539/7908 3461/3463/7907 3538/3540/7910 +f 3461/3463/7907 3539/3541/7911 3538/3540/7910 +f 3539/3541/7911 3540/3542/7912 3538/3540/7910 +f 3539/3541/7911 3462/3464/7905 3540/3542/7912 +f 3462/3464/7905 3541/3543/7913 3540/3542/7912 +f 3462/3464/7905 3536/3538/7904 3541/3543/7913 +f 3542/3544/98 3543/3545/98 3544/3546/98 +f 3545/3547/7914 3546/3548/98 3547/3549/7915 +f 3546/3548/98 3548/3550/98 3547/3549/7915 +f 3546/3548/98 3543/3545/98 3548/3550/98 +f 3543/3545/98 3549/3551/98 3548/3550/98 +f 3543/3545/98 3542/3544/98 3549/3551/98 +f 3545/3547/7914 3547/3549/7915 3550/3552/7916 +f 3551/3553/7904 3453/3455/7917 3455/3457/7906 +f 3303/3305/7918 3452/3454/7919 3552/3554/7920 +f 3552/3554/7920 3452/3454/7919 3553/3555/7921 +f 3452/3454/7919 3554/3556/7922 3553/3555/7921 +f 3554/3556/7922 3555/3557/7923 3553/3555/7921 +f 3554/3556/7922 3453/3455/7917 3555/3557/7923 +f 3453/3455/7917 3556/3558/7924 3555/3557/7923 +f 3453/3455/7917 3551/3553/7904 3556/3558/7924 +f 3557/3559/7925 3461/3463/7926 3459/3461/7927 +f 3462/3464/7928 3558/3560/7929 3463/3465/7930 +f 3462/3464/7928 3539/3541/7931 3559/3561/7932 +f 3539/3541/7931 3560/3562/7933 3559/3561/7932 +f 3539/3541/7931 3461/3463/7926 3560/3562/7933 +f 3461/3463/7926 3561/3563/7934 3560/3562/7933 +f 3461/3463/7926 3557/3559/7925 3561/3563/7934 +f 3462/3464/7928 3559/3561/7932 3558/3560/7929 +f 3562/3564/7904 3446/3448/7905 3448/3450/7906 +f 3445/3447/7907 3563/3565/7908 3444/3446/7909 +f 3563/3565/7908 3445/3447/7907 3564/3566/7935 +f 3445/3447/7907 3565/3567/7911 3564/3566/7935 +f 3565/3567/7911 3566/3568/7923 3564/3566/7935 +f 3565/3567/7911 3446/3448/7905 3566/3568/7923 +f 3446/3448/7905 3567/3569/7936 3566/3568/7923 +f 3446/3448/7905 3562/3564/7904 3567/3569/7936 +f 3568/3570/7937 3452/3454/7938 3330/3332/7939 +f 3453/3455/7928 3569/3571/7929 3454/3456/7930 +f 3453/3455/7928 3554/3556/7940 3570/3572/7932 +f 3554/3556/7940 3571/3573/7941 3570/3572/7932 +f 3554/3556/7940 3452/3454/7938 3571/3573/7941 +f 3452/3454/7938 3572/3574/7942 3571/3573/7941 +f 3452/3454/7938 3568/3570/7937 3572/3574/7942 +f 3453/3455/7928 3570/3572/7932 3569/3571/7929 +f 3573/3575/7904 3438/3440/7905 3440/3442/7906 +f 3437/3439/7943 3574/3576/7944 3336/3338/7945 +f 3574/3576/7944 3437/3439/7943 3575/3577/7921 +f 3437/3439/7943 3576/3578/7922 3575/3577/7921 +f 3576/3578/7922 3577/3579/7923 3575/3577/7921 +f 3576/3578/7922 3438/3440/7905 3577/3579/7923 +f 3438/3440/7905 3578/3580/7936 3577/3579/7923 +f 3438/3440/7905 3573/3575/7904 3578/3580/7936 +f 3579/3581/7946 3445/3447/7947 3347/3349/7948 +f 3446/3448/7928 3580/3582/7929 3447/3449/7930 +f 3446/3448/7928 3565/3567/7931 3581/3583/7932 +f 3565/3567/7931 3582/3584/7949 3581/3583/7932 +f 3565/3567/7931 3445/3447/7947 3582/3584/7949 +f 3445/3447/7947 3583/3585/7934 3582/3584/7949 +f 3445/3447/7947 3579/3581/7946 3583/3585/7934 +f 3446/3448/7928 3581/3583/7932 3580/3582/7929 +f 3584/3586/7950 3432/3434/7951 3431/3433/7952 +f 3354/3356/7918 3429/3431/7919 3585/3587/7920 +f 3585/3587/7920 3429/3431/7919 3586/3588/7921 +f 3429/3431/7919 3587/3589/7953 3586/3588/7921 +f 3587/3589/7953 3588/3590/7954 3586/3588/7921 +f 3587/3589/7953 3432/3434/7951 3588/3590/7954 +f 3432/3434/7951 3589/3591/7955 3588/3590/7954 +f 3432/3434/7951 3584/3586/7950 3589/3591/7955 +f 3590/3592/7956 3437/3439/7957 3436/3438/7958 +f 3438/3440/7928 3591/3593/7929 3439/3441/7930 +f 3438/3440/7928 3576/3578/7940 3592/3594/7932 +f 3576/3578/7940 3593/3595/7941 3592/3594/7932 +f 3576/3578/7940 3437/3439/7957 3593/3595/7941 +f 3437/3439/7957 3594/3596/7942 3593/3595/7941 +f 3437/3439/7957 3590/3592/7956 3594/3596/7942 +f 3438/3440/7928 3592/3594/7932 3591/3593/7929 +f 3595/3597/7904 3423/3425/7905 3425/3427/7906 +f 3422/3424/7943 3596/3598/7944 3369/3371/7945 +f 3596/3598/7944 3422/3424/7943 3597/3599/7921 +f 3422/3424/7943 3598/3600/7922 3597/3599/7921 +f 3598/3600/7922 3599/3601/7923 3597/3599/7921 +f 3598/3600/7922 3423/3425/7905 3599/3601/7923 +f 3423/3425/7905 3600/3602/7936 3599/3601/7923 +f 3423/3425/7905 3595/3597/7904 3600/3602/7936 +f 3601/3603/7937 3429/3431/7938 3379/3381/7939 +f 3430/3432/7959 3432/3434/7960 3602/3604/7961 +f 3432/3434/7960 3587/3589/7962 3603/3605/7963 +f 3587/3589/7962 3604/3606/7941 3603/3605/7963 +f 3587/3589/7962 3429/3431/7938 3604/3606/7941 +f 3429/3431/7938 3605/3607/7942 3604/3606/7941 +f 3429/3431/7938 3601/3603/7937 3605/3607/7942 +f 3432/3434/7960 3603/3605/7963 3602/3604/7961 +f 3606/3608/7964 3414/3416/7965 3413/3415/7966 +f 3607/3609/7967 3411/3413/7968 3608/3610/7969 +f 3411/3413/7968 3412/3414/7970 3608/3610/7969 +f 3412/3414/7970 3503/3505/7971 3608/3610/7969 +f 3503/3505/7971 3609/3611/7972 3608/3610/7969 +f 3503/3505/7971 3414/3416/7965 3609/3611/7972 +f 3414/3416/7965 3610/3612/7973 3609/3611/7972 +f 3414/3416/7965 3606/3608/7964 3610/3612/7973 +f 3611/3613/7937 3422/3424/7938 3396/3398/7939 +f 3423/3425/7928 3612/3614/7929 3424/3426/7930 +f 3423/3425/7928 3598/3600/7940 3613/3615/7932 +f 3598/3600/7940 3614/3616/7941 3613/3615/7932 +f 3598/3600/7940 3422/3424/7938 3614/3616/7941 +f 3422/3424/7938 3615/3617/7942 3614/3616/7941 +f 3422/3424/7938 3611/3613/7937 3615/3617/7942 +f 3423/3425/7928 3613/3615/7932 3612/3614/7929 +f 3537/3539/7974 3549/3551/7975 3542/3544/7976 +f 3537/3539/7974 3538/3540/7977 3549/3551/7975 +f 3538/3540/7978 3548/3550/7978 3549/3551/7978 +f 3538/3540/7979 3540/3542/7979 3548/3550/7979 +f 3540/3542/7980 3547/3549/7980 3548/3550/7980 +f 3540/3542/7981 3541/3543/7981 3547/3549/7981 +f 3541/3543/7982 3550/3552/7983 3547/3549/7984 +f 3541/3543/7982 3536/3538/7985 3550/3552/7983 +f 3552/3554/7986 3561/3563/7986 3557/3559/7986 +f 3552/3554/7987 3553/3555/7987 3561/3563/7987 +f 3553/3555/7988 3560/3562/7933 3561/3563/7934 +f 3553/3555/7921 3555/3557/7923 3560/3562/7989 +f 3555/3557/7990 3559/3561/7932 3560/3562/7933 +f 3555/3557/7923 3556/3558/7924 3559/3561/7991 +f 3556/3558/7992 3558/3560/7992 3559/3561/7992 +f 3556/3558/7993 3551/3553/7993 3558/3560/7993 +f 3563/3565/7994 3572/3574/7994 3568/3570/7994 +f 3563/3565/7987 3564/3566/7987 3572/3574/7987 +f 3564/3566/7988 3571/3573/7941 3572/3574/7942 +f 3564/3566/7935 3566/3568/7923 3571/3573/7989 +f 3566/3568/7990 3570/3572/7932 3571/3573/7941 +f 3566/3568/7923 3567/3569/7936 3570/3572/7995 +f 3567/3569/7996 3569/3571/7996 3570/3572/7996 +f 3567/3569/7993 3562/3564/7993 3569/3571/7993 +f 3574/3576/7994 3583/3585/7994 3579/3581/7994 +f 3574/3576/7997 3575/3577/7997 3583/3585/7997 +f 3575/3577/7998 3582/3584/7949 3583/3585/7934 +f 3575/3577/7921 3577/3579/7923 3582/3584/7989 +f 3577/3579/7990 3581/3583/7932 3582/3584/7949 +f 3577/3579/7923 3578/3580/7936 3581/3583/7995 +f 3578/3580/7996 3580/3582/7996 3581/3583/7996 +f 3578/3580/7993 3573/3575/7993 3580/3582/7993 +f 3585/3587/7986 3594/3596/7986 3590/3592/7986 +f 3585/3587/7987 3586/3588/7987 3594/3596/7987 +f 3586/3588/7988 3593/3595/7941 3594/3596/7942 +f 3586/3588/7921 3588/3590/7954 3593/3595/7989 +f 3588/3590/7990 3592/3594/7932 3593/3595/7941 +f 3588/3590/7954 3589/3591/7955 3592/3594/7995 +f 3589/3591/7996 3591/3593/7996 3592/3594/7996 +f 3589/3591/7993 3584/3586/7993 3591/3593/7993 +f 3596/3598/7994 3605/3607/7994 3601/3603/7994 +f 3596/3598/7997 3597/3599/7997 3605/3607/7997 +f 3597/3599/7998 3604/3606/7941 3605/3607/7942 +f 3597/3599/7921 3599/3601/7923 3604/3606/7989 +f 3599/3601/7990 3603/3605/7963 3604/3606/7941 +f 3599/3601/7923 3600/3602/7936 3603/3605/7995 +f 3600/3602/7996 3602/3604/7996 3603/3605/7996 +f 3600/3602/7999 3595/3597/7999 3602/3604/7999 +f 3607/3609/7994 3615/3617/7994 3611/3613/7994 +f 3607/3609/7987 3608/3610/7987 3615/3617/7987 +f 3608/3610/7988 3614/3616/7941 3615/3617/7942 +f 3608/3610/7969 3609/3611/7972 3614/3616/7989 +f 3609/3611/7990 3613/3615/7932 3614/3616/7941 +f 3609/3611/7972 3610/3612/7973 3613/3615/7991 +f 3610/3612/7992 3612/3614/7992 3613/3615/7992 +f 3610/3612/7993 3606/3608/7993 3612/3614/7993 +f 3616/3618/8000 3496/3498/8001 3504/3506/8002 +f 3496/3498/8001 3506/3508/8003 3504/3506/8002 +f 3497/3499/8004 3617/3619/8005 3508/3510/8006 +f 3617/3619/8005 3505/3507/8007 3508/3510/8006 +f 3499/3501/8008 3491/3493/8009 3490/3492/8010 +f 3499/3501/8008 3618/3620/8011 3491/3493/8009 +f 3618/3620/8011 3502/3504/8012 3491/3493/8009 +f 3618/3620/8011 3619/3621/8013 3502/3504/8012 +f 3619/3621/8013 3504/3506/8002 3502/3504/8012 +f 3619/3621/8013 3616/3618/8000 3504/3506/8002 +f 3489/3491/8014 3501/3503/8015 3500/3502/8016 +f 3489/3491/8014 3488/3490/8017 3501/3503/8015 +f 3611/3613/8018 3396/3398/8019 3607/3609/8020 +f 3396/3398/8019 3411/3413/8021 3607/3609/8020 +f 3396/3398/8022 3386/3388/7506 3411/3413/7508 +f 3396/3398/8023 3395/3397/8023 3386/3388/8023 +f 3395/3397/8024 3384/3386/8024 3386/3388/8024 +f 3601/3603/8018 3379/3381/8025 3596/3598/8026 +f 3379/3381/8025 3369/3371/8027 3596/3598/8026 +f 3379/3381/8028 3378/3380/8029 3369/3371/8030 +f 3378/3380/8029 3367/3369/8031 3369/3371/8030 +f 3590/3592/8032 3436/3438/8032 3585/3587/8032 +f 3436/3438/8033 3354/3356/8033 3585/3587/8033 +f 3436/3438/8034 3364/3366/8034 3354/3356/8034 +f 3364/3366/8035 3352/3354/8035 3354/3356/8035 +f 3364/3366/8036 3363/3365/8036 3352/3354/8036 +f 3579/3581/8018 3347/3349/8025 3574/3576/8026 +f 3347/3349/8025 3336/3338/8027 3574/3576/8026 +f 3347/3349/8028 3346/3348/8029 3336/3338/8030 +f 3346/3348/8029 3334/3336/8031 3336/3338/8030 +f 3568/3570/8018 3330/3332/8037 3563/3565/8038 +f 3330/3332/8037 3444/3446/8039 3563/3565/8038 +f 3330/3332/8040 3325/3327/8040 3444/3446/8040 +f 3330/3332/8041 3329/3331/8041 3325/3327/8041 +f 3329/3331/8042 3326/3328/8042 3325/3327/8042 +f 3557/3559/8032 3459/3461/8032 3552/3554/8032 +f 3459/3461/8033 3303/3305/8033 3552/3554/8033 +f 3459/3461/7675 3313/3315/7673 3303/3305/8034 +f 3313/3315/8035 3301/3303/8035 3303/3305/8035 +f 3313/3315/8036 3312/3314/8036 3301/3303/8036 +f 3542/3544/8043 3544/3546/8044 3537/3539/8045 +f 3544/3546/8044 3460/3462/8046 3537/3539/8045 +f 3544/3546/8047 3293/3295/8048 3460/3462/7676 +f 3293/3295/8048 3289/3291/7674 3460/3462/7676 +f 3293/3295/8049 3290/3292/8050 3289/3291/8051 +f 3293/3295/8049 3292/3294/8052 3290/3292/8050 +f 3534/3536/8053 3424/3426/8053 3532/3534/8053 +f 3424/3426/8054 3416/3418/8054 3532/3534/8054 +f 3424/3426/8055 3413/3415/8055 3416/3418/8055 +f 3424/3426/8056 3612/3614/8057 3413/3415/8058 +f 3612/3614/8057 3606/3608/8059 3413/3415/8058 +f 3531/3533/8060 3430/3432/8060 3529/3531/8060 +f 3430/3432/8061 3426/3428/8061 3529/3531/8061 +f 3430/3432/8062 3425/3427/8062 3426/3428/8062 +f 3430/3432/8063 3602/3604/8063 3425/3427/8063 +f 3602/3604/8064 3595/3597/8064 3425/3427/8064 +f 3528/3530/8065 3439/3441/8065 3526/3528/8065 +f 3439/3441/8066 3433/3435/8066 3526/3528/8066 +f 3439/3441/8067 3431/3433/8067 3433/3435/8067 +f 3439/3441/8068 3591/3593/8069 3431/3433/8070 +f 3591/3593/8069 3584/3586/8071 3431/3433/8070 +f 3525/3527/8072 3447/3449/8072 3524/3526/8072 +f 3447/3449/8073 3441/3443/8073 3524/3526/8073 +f 3447/3449/8074 3440/3442/8074 3441/3443/8074 +f 3447/3449/8068 3580/3582/8069 3440/3442/8070 +f 3580/3582/8069 3573/3575/8071 3440/3442/8070 +f 3521/3523/8065 3454/3456/8065 3519/3521/8065 +f 3454/3456/8066 3449/3451/8066 3519/3521/8066 +f 3454/3456/8067 3448/3450/8067 3449/3451/8067 +f 3454/3456/8068 3569/3571/8069 3448/3450/8070 +f 3569/3571/8069 3562/3564/8071 3448/3450/8070 +f 3518/3520/8072 3463/3465/8072 3517/3519/8072 +f 3463/3465/8073 3456/3458/8073 3517/3519/8073 +f 3463/3465/8074 3455/3457/8074 3456/3458/8074 +f 3463/3465/8068 3558/3560/8069 3455/3457/8070 +f 3558/3560/8069 3551/3553/8071 3455/3457/8070 +f 3514/3516/8075 3512/3514/8076 3510/3512/8077 +f 3512/3514/8076 3465/3467/8078 3510/3512/8077 +f 3512/3514/8079 3545/3547/8080 3465/3467/7679 +f 3545/3547/8080 3464/3466/7678 3465/3467/7679 +f 3545/3547/8081 3550/3552/8082 3464/3466/8083 +f 3550/3552/8082 3536/3538/8084 3464/3466/8083 +f 3266/3268/8085 3253/3255/8085 3255/3257/8085 +f 3266/3268/8086 3417/3419/7515 3253/3255/7517 +f 3266/3268/8087 3535/3537/8087 3417/3419/8087 +f 3535/3537/8088 3533/3535/8088 3417/3419/8088 +f 3242/3244/8089 3230/3232/8089 3232/3234/8089 +f 3242/3244/8090 3428/3430/7551 3230/3232/7550 +f 3242/3244/8091 3530/3532/8091 3428/3430/8091 +f 3220/3222/8089 3208/3210/8089 3210/3212/8089 +f 3220/3222/8090 3435/3437/8090 3208/3210/8090 +f 3220/3222/8091 3527/3529/8091 3435/3437/8091 +f 3199/3201/8089 3186/3188/8089 3188/3190/8089 +f 3199/3201/8090 3443/3445/8090 3186/3188/8090 +f 3199/3201/8092 3523/3525/8092 3443/3445/8092 +f 3175/3177/8089 3162/3164/8089 3164/3166/8089 +f 3175/3177/8090 3451/3453/8090 3162/3164/8090 +f 3175/3177/8091 3520/3522/8091 3451/3453/8091 +f 3153/3155/8093 3141/3143/7658 3143/3145/8094 +f 3153/3155/8093 3458/3460/7657 3141/3143/7658 +f 3153/3155/8095 3516/3518/7867 3458/3460/7865 +f 3130/3132/8096 3128/3130/8097 3117/3119/8098 +f 3128/3130/8097 3115/3117/7681 3117/3119/8098 +f 3128/3130/8097 3467/3469/7682 3115/3117/7681 +f 3128/3130/8097 3513/3515/8099 3467/3469/7682 +f 3513/3515/8099 3509/3511/8100 3467/3469/7682 +f 3478/3480/7710 3501/3503/8101 3477/3479/7709 +f 3501/3503/8101 3488/3490/8102 3477/3479/7709 +f 3500/3502/8103 3499/3501/8008 3489/3491/8104 +f 3499/3501/8008 3490/3492/8010 3489/3491/8104 +f 3508/3510/8006 3507/3509/8105 3497/3499/8004 +f 3507/3509/8105 3493/3495/8106 3497/3499/8004 +f 3507/3509/8107 3506/3508/8003 3493/3495/8108 +f 3506/3508/8003 3496/3498/8001 3493/3495/8108 +f 3479/3481/8109 3617/3619/8005 3480/3482/8110 +f 3479/3481/8109 3505/3507/8007 3617/3619/8005 +f 3620/3622/8111 3621/3623/8112 3622/3624/8113 +f 3623/3625/8114 3622/3624/8113 3624/3626/8115 +f 3620/3622/8111 3622/3624/8113 3623/3625/8114 +f 3620/3622/8111 3623/3625/8114 3625/3627/8116 +f 3626/3628/8117 3624/3626/8118 3627/3629/8119 +f 3628/3630/8120 3629/3631/8121 3626/3628/8117 +f 3627/3629/8119 3628/3630/8120 3626/3628/8117 +f 3628/3630/8120 3627/3629/8119 3630/3632/8122 +f 3631/3633/8123 3632/3634/8124 3633/3635/8125 +f 3634/3636/8126 3635/3637/8127 3636/3638/8128 +f 3637/3639/8129 3638/3640/8130 3639/3641/8131 +f 3639/3641/8131 3640/3642/8132 3637/3639/8129 +f 3640/3642/8132 3641/3643/8133 3637/3639/8129 +f 3642/3644/8134 3640/3642/8135 3643/3645/8136 +f 3644/3646/8137 3645/3647/8138 3646/3648/8139 +f 3647/3649/8140 3648/3650/8141 3649/3651/8142 +f 3647/3649/8140 3646/3648/8139 3648/3650/8141 +f 3650/3652/8143 3651/3653/8144 3652/3654/8145 +f 3653/3655/8146 3650/3652/8143 3654/3656/8147 +f 3655/3657/8148 3656/3658/8149 3657/3659/8150 +f 3655/3657/8148 3657/3659/8150 3658/3660/8151 +f 3659/3661/8152 3656/3658/8149 3655/3657/8148 +f 3660/3662/8153 3661/3663/8154 3662/3664/8155 +f 3661/3663/8154 3660/3662/8153 3663/3665/8156 +f 3661/3663/8154 3663/3665/8156 3664/3666/8157 +f 3664/3666/8157 3665/3667/8158 3661/3663/8154 +f 3664/3666/8157 3666/3668/8159 3665/3667/8158 +f 3665/3667/8158 3667/3669/8160 3668/3670/8161 +f 3642/3644/8134 3669/3671/8162 3670/3672/8163 +f 3637/3639/8129 3641/3643/8133 3670/3672/8163 +f 3638/3640/8130 3637/3639/8129 3634/3636/8126 +f 3642/3644/8134 3643/3645/8136 3669/3671/8162 +f 3643/3645/8136 3671/3673/8164 3669/3671/8162 +f 3665/3667/8158 3666/3668/8159 3667/3669/8160 +f 3670/3672/8163 3669/3671/8162 3637/3639/8129 +f 3671/3673/8164 3644/3646/8137 3669/3671/8162 +f 3634/3636/8126 3637/3639/8129 3635/3637/8127 +f 3637/3639/8129 3669/3671/8162 3635/3637/8127 +f 3636/3638/8128 3635/3637/8127 3633/3635/8125 +f 3669/3671/8162 3672/3674/8165 3635/3637/8127 +f 3669/3671/8162 3647/3649/8140 3672/3674/8165 +f 3669/3671/8162 3644/3646/8137 3647/3649/8140 +f 3635/3637/8127 3672/3674/8165 3633/3635/8125 +f 3644/3646/8137 3646/3648/8139 3647/3649/8140 +f 3633/3635/8125 3672/3674/8165 3631/3633/8123 +f 3672/3674/8165 3647/3649/8140 3673/3675/8166 +f 3620/3622/8111 3665/3667/8158 3674/3676/8167 +f 3620/3622/8111 3675/3677/8168 3665/3667/8158 +f 3675/3677/8168 3661/3663/8154 3665/3667/8158 +f 3675/3677/8168 3676/3678/8169 3661/3663/8154 +f 3676/3678/8169 3677/3679/8170 3661/3663/8154 +f 3674/3676/8167 3665/3667/8158 3668/3670/8161 +f 3677/3679/8170 3662/3664/8155 3661/3663/8154 +f 3672/3674/8165 3678/3680/8171 3631/3633/8123 +f 3672/3674/8165 3673/3675/8166 3678/3680/8171 +f 3647/3649/8140 3679/3681/8172 3673/3675/8166 +f 3647/3649/8140 3649/3651/8142 3653/3655/8146 +f 3632/3634/8124 3628/3630/8120 3630/3632/8122 +f 3632/3634/8124 3631/3633/8123 3628/3630/8120 +f 3647/3649/8140 3653/3655/8146 3679/3681/8172 +f 3649/3651/8142 3680/3682/8173 3653/3655/8146 +f 3628/3630/8120 3681/3683/8174 3629/3631/8121 +f 3681/3683/8174 3620/3622/8111 3629/3631/8121 +f 3681/3683/8174 3682/3684/8175 3620/3622/8111 +f 3681/3683/8174 3683/3685/8176 3682/3684/8175 +f 3653/3655/8146 3657/3659/8150 3684/3686/8177 +f 3653/3655/8146 3654/3656/8147 3657/3659/8150 +f 3629/3631/8121 3620/3622/8111 3625/3627/8116 +f 3683/3685/8176 3684/3686/8177 3682/3684/8175 +f 3684/3686/8177 3656/3658/8149 3676/3678/8169 +f 3684/3686/8177 3657/3659/8150 3656/3658/8149 +f 3620/3622/8111 3674/3676/8167 3621/3623/8112 +f 3656/3658/8149 3677/3679/8170 3676/3678/8169 +f 3656/3658/8149 3659/3661/8152 3677/3679/8170 +f 3631/3633/8123 3681/3683/8174 3628/3630/8120 +f 3631/3633/8123 3678/3680/8171 3681/3683/8174 +f 3680/3682/8173 3651/3653/8144 3653/3655/8146 +f 3678/3680/8171 3683/3685/8176 3681/3683/8174 +f 3678/3680/8171 3673/3675/8166 3683/3685/8176 +f 3673/3675/8166 3679/3681/8172 3683/3685/8176 +f 3679/3681/8172 3653/3655/8146 3684/3686/8177 +f 3679/3681/8172 3684/3686/8177 3683/3685/8176 +f 3651/3653/8144 3650/3652/8143 3653/3655/8146 +f 3620/3622/8111 3682/3684/8175 3675/3677/8168 +f 3682/3684/8175 3676/3678/8169 3675/3677/8168 +f 3682/3684/8175 3684/3686/8177 3676/3678/8169 +f 3685/3687/8178 3277/3279/7357 3278/3280/7358 +f 3686/3688/8179 3687/3689/8180 3282/3284/7828 +f 3687/3689/8180 3686/3688/8179 3688/3690/8181 +f 3277/3279/7357 3685/3687/8178 3689/3691/8182 +f 3277/3279/7357 3689/3691/8182 3690/3692/8183 +f 3401/3403/7490 3277/3279/7357 3690/3692/8183 +f 3402/3404/7491 3690/3692/8183 3691/3693/8184 +f 3402/3404/7491 3401/3403/7490 3690/3692/8183 +f 3402/3404/7491 3691/3693/8184 3692/3694/8185 +f 3692/3694/8185 3404/3406/7493 3402/3404/7491 +f 3404/3406/7493 3692/3694/8185 3693/3695/8186 +f 3693/3695/8186 3406/3408/7495 3404/3406/7493 +f 3694/3696/8187 3471/3473/7703 3468/3470/7700 +f 3694/3696/8187 3695/3697/8188 3471/3473/7703 +f 3471/3473/7703 3695/3697/8188 3696/3698/8189 +f 3473/3475/7705 3471/3473/7703 3696/3698/8189 +f 3696/3698/8189 3697/3699/8190 3473/3475/7705 +f 3697/3699/8190 3475/3477/7707 3473/3475/7705 +f 3697/3699/8190 3698/3700/8191 3475/3477/7707 +f 3478/3480/7710 3475/3477/7707 3699/3701/8192 +f 3475/3477/7707 3698/3700/8191 3699/3701/8192 +f 3700/3702/8193 3482/3484/7714 3480/3482/7712 +f 3482/3484/7714 3700/3702/8193 3701/3703/8194 +f 3282/3284/7828 3482/3484/7714 3701/3703/8194 +f 3282/3284/7828 3701/3703/8194 3702/3704/8195 +f 3282/3284/7828 3702/3704/8195 3686/3688/8179 +f 3703/3705/8196 3704/3706/8197 3670/3672/8198 +f 3703/3705/8196 3670/3672/8198 3641/3643/8199 +f 3641/3643/8200 3705/3707/8201 3703/3705/8202 +f 3641/3643/8200 3640/3642/8203 3705/3707/8201 +f 3706/3708/8204 3705/3707/8205 3642/3644/8206 +f 3705/3707/8205 3640/3642/8207 3642/3644/8206 +f 3704/3706/8208 3706/3708/8209 3670/3672/8210 +f 3706/3708/8209 3642/3644/8211 3670/3672/8210 +f 3707/3709/8212 3624/3626/8212 3626/3628/8212 +f 3707/3709/8213 3626/3628/8213 3708/3710/8213 +f 3626/3628/8214 3629/3631/8214 3708/3710/8214 +f 3629/3631/8215 3625/3627/8216 3708/3710/8217 +f 3625/3627/8216 3709/3711/8218 3708/3710/8217 +f 3625/3627/8219 3623/3625/8220 3709/3711/8221 +f 3623/3625/8220 3710/3712/8222 3709/3711/8221 +f 3623/3625/8223 3624/3626/8224 3710/3712/8225 +f 3707/3709/8226 3710/3712/8225 3624/3626/8224 +f 3711/3713/8227 3712/3714/8228 3713/3715/8229 +f 3714/3716/8230 3715/3717/8231 3716/3718/8232 +f 3716/3718/8232 3715/3717/8231 3717/3719/8233 +f 3718/3720/8234 3717/3719/8235 3719/3721/8236 +f 3718/3720/8234 3716/3718/8237 3717/3719/8235 +f 3406/3408/7495 3693/3695/8186 3720/3722/8238 +f 3720/3722/8238 3711/3713/8227 3406/3408/7495 +f 3720/3722/8238 3712/3714/8228 3711/3713/8227 +f 3468/3470/7700 3711/3713/8227 3721/3723/8239 +f 3711/3713/8227 3713/3715/8229 3721/3723/8239 +f 3468/3470/7700 3721/3723/8239 3694/3696/8187 +f 3714/3716/8230 3687/3689/8180 3688/3690/8181 +f 3714/3716/8230 3716/3718/8232 3687/3689/8180 +f 3278/3280/7358 3718/3720/8240 3722/3724/8241 +f 3718/3720/8240 3719/3721/8242 3722/3724/8241 +f 3278/3280/7358 3722/3724/8241 3685/3687/8178 +f 3697/3699/8190 3666/3668/8243 3664/3666/8157 +f 3697/3699/8190 3696/3698/8189 3666/3668/8243 +f 3696/3698/8189 3667/3669/8160 3666/3668/8243 +f 3664/3666/8157 3663/3665/8156 3697/3699/8190 +f 3663/3665/8156 3660/3662/8153 3698/3700/8191 +f 3667/3669/8160 3694/3696/8187 3668/3670/8161 +f 3694/3696/8187 3667/3669/8160 3695/3697/8188 +f 3695/3697/8188 3667/3669/8160 3696/3698/8189 +f 3697/3699/8190 3663/3665/8156 3698/3700/8191 +f 3698/3700/8191 3660/3662/8153 3699/3701/8192 +f 3668/3670/8161 3694/3696/8187 3721/3723/8239 +f 3721/3723/8239 3674/3676/8167 3668/3670/8161 +f 3721/3723/8239 3713/3715/8229 3674/3676/8167 +f 3712/3714/8228 3674/3676/8167 3713/3715/8229 +f 3720/3722/8238 3621/3623/8112 3674/3676/8167 +f 3720/3722/8238 3693/3695/8186 3621/3623/8112 +f 3674/3676/8167 3712/3714/8228 3720/3722/8238 +f 3627/3629/8119 3624/3626/8244 3622/3624/8113 +f 3685/3687/8178 3630/3632/8122 3689/3691/8182 +f 3630/3632/8122 3690/3692/8183 3689/3691/8182 +f 3627/3629/8119 3691/3693/8184 3690/3692/8183 +f 3627/3629/8119 3622/3624/8113 3691/3693/8184 +f 3691/3693/8184 3622/3624/8113 3692/3694/8185 +f 3622/3624/8113 3621/3623/8112 3693/3695/8186 +f 3693/3695/8186 3692/3694/8185 3622/3624/8113 +f 3627/3629/8119 3690/3692/8183 3630/3632/8122 +f 3630/3632/8122 3685/3687/8178 3632/3634/8124 +f 3719/3721/8245 3632/3634/8124 3722/3724/8241 +f 3632/3634/8124 3685/3687/8178 3722/3724/8241 +f 3633/3635/8246 3632/3634/8124 3719/3721/8245 +f 3723/3725/8247 3719/3721/8236 3717/3719/8235 +f 3723/3725/8248 3633/3635/8125 3719/3721/8249 +f 3715/3717/8250 3723/3725/8248 3717/3719/8251 +f 3715/3717/8250 3724/3726/8252 3723/3725/8248 +f 3724/3726/8252 3633/3635/8125 3723/3725/8248 +f 3724/3726/8252 3636/3638/8128 3633/3635/8125 +f 3714/3716/8230 3688/3690/8181 3636/3638/8128 +f 3724/3726/8252 3714/3716/8230 3636/3638/8128 +f 3724/3726/8252 3715/3717/8250 3714/3716/8230 +f 3634/3636/8126 3686/3688/8253 3702/3704/8195 +f 3688/3690/8181 3686/3688/8254 3636/3638/8128 +f 3636/3638/8128 3686/3688/8254 3634/3636/8255 +f 3701/3703/8194 3638/3640/8130 3702/3704/8195 +f 3639/3641/8131 3638/3640/8130 3701/3703/8194 +f 3638/3640/8130 3634/3636/8126 3702/3704/8195 +f 3700/3702/8193 3639/3641/8131 3701/3703/8194 +f 3643/3645/8136 3640/3642/8135 3700/3702/8193 +f 3639/3641/8131 3700/3702/8193 3640/3642/8135 +f 3725/3727/8256 3726/3728/8257 3727/3729/8258 +f 3617/3619/8005 3497/3499/8004 3728/3730/8259 +f 3497/3499/8004 3729/3731/8260 3728/3730/8259 +f 3730/3732/8261 3731/3733/8262 3499/3501/8008 +f 3731/3733/8262 3618/3620/8011 3499/3501/8008 +f 3618/3620/8011 3731/3733/8262 3732/3734/8263 +f 3619/3621/8013 3618/3620/8011 3733/3735/8264 +f 3618/3620/8011 3732/3734/8263 3733/3735/8264 +f 3733/3735/8264 3725/3727/8256 3619/3621/8013 +f 3725/3727/8256 3616/3618/8000 3619/3621/8013 +f 3725/3727/8256 3727/3729/8258 3616/3618/8000 +f 3728/3730/8259 3480/3482/8110 3617/3619/8005 +f 3480/3482/8110 3728/3730/8259 3700/3702/8193 +f 3652/3654/8265 3658/3660/8265 3734/3736/8265 +f 3658/3660/8266 3735/3737/8266 3734/3736/8266 +f 3658/3660/8267 3657/3659/8267 3735/3737/8267 +f 3657/3659/8268 3736/3738/8268 3735/3737/8268 +f 3657/3659/8269 3654/3656/8270 3736/3738/8271 +f 3654/3656/8270 3737/3739/8272 3736/3738/8271 +f 3654/3656/8273 3650/3652/8274 3737/3739/8275 +f 3650/3652/8274 3738/3740/8276 3737/3739/8275 +f 3650/3652/8277 3652/3654/8277 3738/3740/8277 +f 3734/3736/8278 3738/3740/8278 3652/3654/8278 +f 3498/3500/8279 3739/3741/8280 3740/3742/8281 +f 3494/3496/8282 3741/3743/8283 3742/3744/8284 +f 3494/3496/8282 3742/3744/8284 3743/3745/8285 +f 3495/3497/8286 3494/3496/8282 3743/3745/8285 +f 3499/3501/8008 3498/3500/8279 3744/3746/8287 +f 3498/3500/8279 3740/3742/8281 3744/3746/8287 +f 3499/3501/8008 3744/3746/8287 3730/3732/8261 +f 3478/3480/7710 3699/3701/8192 3745/3747/8288 +f 3498/3500/8279 3478/3480/7710 3745/3747/8288 +f 3745/3747/8288 3739/3741/8280 3498/3500/8279 +f 3497/3499/8004 3495/3497/8289 3746/3748/8290 +f 3495/3497/8289 3743/3745/8291 3746/3748/8290 +f 3729/3731/8260 3497/3499/8004 3746/3748/8290 +f 3496/3498/8292 3727/3729/8258 3726/3728/8257 +f 3496/3498/8292 3726/3728/8257 3747/3749/8293 +f 3747/3749/8293 3494/3496/8294 3496/3498/8292 +f 3747/3749/8293 3741/3743/8295 3494/3496/8294 +f 3745/3747/8288 3662/3664/8155 3739/3741/8296 +f 3745/3747/8288 3660/3662/8153 3662/3664/8155 +f 3745/3747/8288 3699/3701/8192 3660/3662/8153 +f 3748/3750/8297 3662/3664/8155 3677/3679/8170 +f 3748/3750/8297 3739/3741/8296 3662/3664/8155 +f 3739/3741/8296 3748/3750/8297 3740/3742/8281 +f 3659/3661/8152 3748/3750/8297 3677/3679/8170 +f 3744/3746/8287 3659/3661/8152 3730/3732/8298 +f 3740/3742/8281 3748/3750/8297 3744/3746/8287 +f 3748/3750/8297 3659/3661/8152 3744/3746/8287 +f 3655/3657/8148 3658/3660/8151 3652/3654/8145 +f 3725/3727/8256 3733/3735/8264 3651/3653/8144 +f 3733/3735/8264 3652/3654/8145 3651/3653/8144 +f 3733/3735/8264 3732/3734/8263 3652/3654/8145 +f 3731/3733/8262 3655/3657/8148 3732/3734/8263 +f 3655/3657/8148 3730/3732/8298 3659/3661/8152 +f 3655/3657/8148 3652/3654/8145 3732/3734/8263 +f 3651/3653/8144 3680/3682/8173 3725/3727/8256 +f 3730/3732/8298 3655/3657/8148 3731/3733/8262 +f 3680/3682/8173 3726/3728/8257 3725/3727/8256 +f 3648/3650/8299 3747/3749/8293 3649/3651/8142 +f 3726/3728/8257 3649/3651/8142 3747/3749/8293 +f 3680/3682/8173 3649/3651/8142 3726/3728/8257 +f 3741/3743/8300 3747/3749/8293 3648/3650/8299 +f 3648/3650/8299 3743/3745/8301 3741/3743/8300 +f 3743/3745/8302 3742/3744/8302 3741/3743/8302 +f 3648/3650/8299 3646/3648/8139 3743/3745/8301 +f 3746/3748/8303 3743/3745/8301 3646/3648/8139 +f 3746/3748/8303 3645/3647/8138 3729/3731/8304 +f 3646/3648/8139 3645/3647/8138 3746/3748/8303 +f 3644/3646/8137 3671/3673/8164 3728/3730/8259 +f 3645/3647/8138 3644/3646/8137 3729/3731/8304 +f 3644/3646/8137 3728/3730/8259 3729/3731/8304 +f 3671/3673/8164 3643/3645/8136 3700/3702/8193 +f 3728/3730/8259 3671/3673/8164 3700/3702/8193 +f 3727/3729/8305 3496/3498/8305 3616/3618/8305 +f 3749/3751/8306 3750/3752/8307 3751/3753/8308 +f 3752/3754/8309 3753/3755/8310 3754/3756/8311 +f 3755/3757/528 3756/3758/528 3757/3759/8312 +f 3749/3751/8306 3751/3753/8308 3758/3760/8313 +f 3751/3753/8308 3759/3761/8314 3758/3760/8313 +f 3750/3752/8315 3749/3751/8316 3760/3762/8317 +f 3757/3759/8312 3756/3758/528 3752/3754/8309 +f 3754/3756/8311 3757/3759/8312 3752/3754/8309 +f 3761/3763/8318 3762/3764/8319 3760/3762/8320 +f 3760/3762/8320 3758/3760/8313 3761/3763/8318 +f 3762/3764/8321 3750/3752/8315 3760/3762/8317 +f 3758/3760/8313 3763/3765/8322 3761/3763/8318 +f 3764/3766/528 3753/3755/8310 3756/3758/528 +f 3753/3755/8310 3765/3767/8323 3754/3756/8311 +f 3759/3761/8314 3763/3765/8322 3758/3760/8313 +f 3759/3761/8314 3766/3768/8324 3763/3765/8322 +f 3766/3768/8324 3767/3769/8325 3763/3765/8322 +f 3766/3768/8324 3768/3770/8326 3767/3769/8325 +f 3765/3767/8323 3753/3755/8310 3764/3766/528 +f 3764/3766/528 3769/3771/528 3765/3767/8323 +f 3770/3772/528 3771/3773/528 3772/3774/528 +f 3766/3768/8324 3770/3772/528 3768/3770/8326 +f 3770/3772/528 3772/3774/528 3768/3770/8326 +f 3771/3773/528 3773/3775/528 3772/3774/528 +f 3771/3773/528 3769/3771/528 3773/3775/528 +f 3764/3766/528 3773/3775/528 3769/3771/528 +f 3762/3764/8327 3774/3776/8327 3750/3752/8327 +f 3761/3763/8328 3774/3776/8329 3762/3764/8330 +f 3751/3753/8331 3775/3777/8332 3776/3778/8333 +f 3751/3753/8331 3750/3752/8334 3775/3777/8332 +f 3761/3763/8328 3776/3778/8335 3774/3776/8329 +f 3777/3779/98 3778/3780/98 3779/3781/98 +f 3780/3782/8336 3781/3783/8337 3754/3756/8338 +f 3775/3777/8332 3750/3752/8334 3774/3776/8339 +f 3776/3778/8340 3761/3763/8340 3782/3784/8340 +f 3779/3781/98 3781/3783/98 3777/3779/98 +f 3777/3779/98 3783/3785/98 3778/3780/98 +f 3776/3778/8333 3784/3786/8341 3751/3753/8331 +f 3782/3784/8342 3767/3769/8343 3785/3787/8344 +f 3776/3778/8333 3782/3784/8342 3784/3786/8341 +f 3784/3786/8341 3782/3784/8342 3785/3787/8344 +f 3767/3769/8343 3786/3788/8345 3785/3787/8344 +f 3767/3769/8343 3787/3789/8346 3786/3788/8345 +f 3787/3789/8346 3788/3790/98 3786/3788/8345 +f 3788/3790/98 3789/3791/98 3786/3788/8345 +f 3783/3785/98 3780/3782/98 3790/3792/98 +f 3777/3779/98 3780/3782/98 3783/3785/98 +f 3788/3790/98 3790/3792/98 3789/3791/98 +f 3788/3790/98 3783/3785/98 3790/3792/98 +f 3765/3767/8347 3780/3782/8347 3754/3756/8347 +f 3765/3767/8348 3790/3792/8348 3780/3782/8348 +f 3765/3767/8349 3769/3771/8349 3790/3792/8349 +f 3769/3771/8350 3771/3773/8350 3790/3792/8350 +f 3771/3773/8351 3789/3791/8351 3790/3792/8351 +f 3771/3773/8352 3770/3772/8352 3789/3791/8352 +f 3770/3772/8353 3786/3788/8353 3789/3791/8353 +f 3770/3772/8354 3766/3768/8354 3786/3788/8354 +f 3766/3768/8355 3785/3787/8355 3786/3788/8355 +f 3766/3768/8356 3784/3786/8357 3785/3787/8358 +f 3766/3768/8356 3759/3761/8359 3784/3786/8357 +f 3759/3761/8360 3751/3753/8360 3784/3786/8360 +f 3761/3763/8361 3763/3765/8361 3782/3784/8361 +f 3763/3765/8362 3767/3769/8362 3782/3784/8362 +f 3767/3769/8363 3768/3770/8363 3787/3789/8363 +f 3768/3770/8364 3788/3790/8365 3787/3789/8366 +f 3768/3770/8364 3772/3774/8367 3788/3790/8365 +f 3772/3774/8368 3773/3775/8368 3788/3790/8368 +f 3773/3775/8369 3783/3785/8369 3788/3790/8369 +f 3773/3775/8370 3764/3766/8370 3783/3785/8370 +f 3764/3766/8371 3778/3780/8371 3783/3785/8371 +f 3764/3766/8372 3756/3758/8372 3778/3780/8372 +f 3755/3757/8373 3779/3781/8373 3756/3758/8373 +f 3779/3781/8374 3778/3780/8374 3756/3758/8374 +f 3755/3757/8375 3757/3759/8375 3779/3781/8375 +f 3757/3759/8376 3781/3783/8376 3779/3781/8376 +f 3754/3756/8338 3781/3783/8337 3757/3759/8377 +f 3760/3762/8378 3749/3751/8378 3774/3776/8378 +f 3749/3751/8379 3775/3777/8379 3774/3776/8379 +f 3749/3751/8380 3758/3760/8380 3775/3777/8380 +f 3758/3760/8381 3776/3778/8381 3775/3777/8381 +f 3758/3760/8382 3760/3762/8382 3776/3778/8382 +f 3760/3762/8383 3774/3776/8383 3776/3778/8383 +f 3752/3754/8384 3781/3783/8384 3780/3782/8384 +f 3752/3754/8385 3756/3758/8385 3781/3783/8385 +f 3756/3758/8386 3777/3779/8386 3781/3783/8386 +f 3756/3758/8387 3753/3755/8387 3777/3779/8387 +f 3753/3755/8388 3780/3782/8388 3777/3779/8388 +f 3753/3755/8389 3752/3754/8389 3780/3782/8389 +f 3791/3793/8390 3792/3794/8390 3793/3795/8390 +f 3794/3796/8391 3795/3797/8392 3796/3798/8393 +f 3796/3798/8393 3795/3797/8392 3797/3799/8394 +f 3794/3796/8391 3796/3798/8393 3793/3795/8395 +f 3798/3800/8396 3799/3801/8397 3800/3802/8398 +f 3801/3803/8399 3800/3802/8400 3802/3804/8401 +f 3800/3802/8402 3799/3801/8403 3802/3804/8404 +f 3799/3801/8403 3803/3805/8405 3802/3804/8404 +f 3799/3801/8406 3798/3800/8407 3803/3805/8408 +f 3798/3800/8407 3804/3806/8409 3803/3805/8408 +f 3798/3800/8410 3805/3807/8411 3804/3806/8412 +f 3805/3807/8411 3801/3803/8413 3804/3806/8412 +f 3805/3807/8414 3800/3802/8400 3801/3803/8399 +f 3803/3805/8415 3804/3806/8416 3806/3808/8417 +f 3804/3806/8416 3801/3803/8418 3807/3809/8419 +f 3801/3803/8418 3808/3810/8420 3807/3809/8419 +f 3806/3808/8417 3804/3806/8416 3809/3811/8421 +f 3801/3803/8418 3802/3804/8422 3808/3810/8420 +f 3802/3804/8422 3810/3812/8423 3808/3810/8420 +f 3804/3806/8416 3807/3809/8419 3809/3811/8421 +f 3802/3804/8422 3803/3805/8415 3806/3808/8417 +f 3802/3804/8422 3806/3808/8417 3810/3812/8423 +f 3808/3810/8424 3810/3812/8425 3795/3797/8426 +f 3795/3797/8426 3810/3812/8425 3797/3799/8427 +f 3797/3799/8428 3810/3812/8429 3796/3798/8430 +f 3810/3812/8429 3806/3808/8431 3796/3798/8430 +f 3806/3808/8432 3793/3795/8432 3796/3798/8432 +f 3806/3808/8433 3809/3811/8434 3793/3795/8435 +f 3793/3795/8435 3809/3811/8434 3791/3793/8436 +f 3809/3811/8437 3807/3809/8438 3791/3793/8439 +f 3807/3809/8438 3792/3794/8440 3791/3793/8439 +f 3807/3809/8441 3808/3810/8442 3792/3794/8443 +f 3808/3810/8442 3795/3797/8444 3792/3794/8443 +f 3793/3795/8445 3811/3813/8445 3794/3796/8445 +f 3811/3813/8446 3812/3814/8446 3794/3796/8446 +f 3792/3794/8447 3811/3813/8447 3793/3795/8447 +f 3795/3797/8448 3812/3814/8449 3792/3794/8450 +f 3812/3814/8449 3811/3813/8451 3792/3794/8450 +f 3794/3796/8452 3812/3814/8452 3795/3797/8452 +f 3805/3807/8453 3798/3800/8396 3800/3802/8398 +f 3813/3815/8454 3814/3816/8455 3815/3817/8456 +f 3816/3818/8457 3817/3819/8458 3818/3820/8459 +f 3813/3815/8454 3816/3818/8457 3814/3816/8455 +f 3813/3815/8454 3817/3819/8458 3816/3818/8457 +f 3819/3821/8460 3813/3815/8454 3815/3817/8456 +f 3819/3821/8460 3815/3817/8456 3818/3820/8459 +f 3817/3819/8458 3819/3821/8460 3818/3820/8459 +f 3820/3822/8461 3821/3823/8462 3822/3824/8463 +f 3823/3825/8464 3820/3822/8461 3822/3824/8463 +f 3824/3826/8465 3823/3825/8466 3825/3827/8467 +f 3824/3826/8465 3826/3828/8468 3823/3825/8466 +f 3826/3828/8469 3820/3822/8470 3823/3825/8471 +f 3826/3828/8469 3827/3829/8472 3820/3822/8470 +f 3827/3829/8473 3821/3823/8474 3820/3822/8475 +f 3827/3829/8473 3828/3830/8476 3821/3823/8474 +f 3828/3830/8477 3822/3824/8478 3821/3823/8479 +f 3828/3830/8477 3829/3831/8480 3822/3824/8478 +f 3829/3831/8481 3825/3827/8482 3822/3824/8483 +f 3829/3831/8481 3824/3826/8484 3825/3827/8482 +f 3826/3828/8485 3830/3832/8486 3831/3833/8487 +f 3826/3828/8485 3824/3826/8488 3830/3832/8486 +f 3824/3826/8488 3832/3834/8489 3830/3832/8486 +f 3824/3826/8488 3829/3831/8490 3832/3834/8489 +f 3829/3831/8490 3833/3835/8491 3832/3834/8489 +f 3829/3831/8490 3828/3830/8492 3833/3835/8491 +f 3828/3830/8492 3834/3836/8493 3833/3835/8491 +f 3828/3830/8492 3827/3829/8494 3834/3836/8493 +f 3827/3829/8494 3835/3837/8495 3834/3836/8493 +f 3827/3829/8494 3831/3833/8487 3835/3837/8495 +f 3827/3829/8494 3826/3828/8485 3831/3833/8487 +f 3814/3816/8496 3816/3818/8497 3830/3832/8498 +f 3816/3818/8497 3831/3833/8499 3830/3832/8498 +f 3816/3818/8500 3835/3837/8500 3831/3833/8500 +f 3816/3818/8501 3818/3820/8502 3835/3837/8503 +f 3818/3820/8502 3834/3836/8504 3835/3837/8503 +f 3818/3820/8505 3833/3835/8506 3834/3836/8507 +f 3818/3820/8505 3815/3817/8508 3833/3835/8506 +f 3815/3817/8509 3832/3834/8509 3833/3835/8509 +f 3815/3817/8510 3814/3816/8510 3832/3834/8510 +f 3814/3816/8511 3830/3832/8511 3832/3834/8511 +f 3817/3819/8512 3836/3838/8513 3819/3821/8514 +f 3836/3838/8513 3837/3839/8515 3819/3821/8514 +f 3813/3815/8516 3838/3840/8517 3817/3819/8518 +f 3838/3840/8517 3836/3838/8519 3817/3819/8518 +f 3819/3821/6881 3837/3839/6882 3813/3815/6883 +f 3837/3839/6882 3838/3840/6884 3813/3815/6883 +f 3837/3839/528 3836/3838/528 3838/3840/528 +f 3825/3827/8520 3823/3825/8464 3822/3824/8463 +f 3839/3841/528 3840/3842/528 3841/3843/528 +f 3842/3844/8521 3843/3845/8522 3844/3846/8523 +f 3844/3846/8523 3843/3845/8522 3845/3847/8524 +f 3844/3846/8525 3845/3847/8526 3846/3848/8527 +f 3841/3843/528 3847/3849/528 3839/3841/528 +f 3848/3850/8528 3846/3848/8527 3845/3847/8526 +f 3839/3841/528 3847/3849/528 3849/3851/528 +f 3850/3852/528 3848/3850/528 3843/3845/8522 +f 3850/3852/8529 3846/3848/8529 3848/3850/8529 +f 3851/3853/8530 3852/3854/8531 3849/3851/8532 +f 3852/3854/8531 3840/3842/528 3849/3851/8532 +f 3849/3851/8533 3853/3855/8534 3851/3853/8535 +f 3842/3844/8521 3854/3856/8536 3843/3845/8522 +f 3847/3849/528 3853/3855/8537 3849/3851/528 +f 3847/3849/528 3855/3857/8538 3853/3855/8537 +f 3855/3857/8538 3856/3858/8539 3853/3855/8537 +f 3855/3857/8538 3857/3859/8540 3856/3858/8539 +f 3858/3860/8541 3843/3845/8522 3854/3856/8536 +f 3858/3860/8541 3850/3852/528 3843/3845/8522 +f 3856/3858/8539 3857/3859/8540 3859/3861/8542 +f 3857/3859/8540 3860/3862/8543 3859/3861/8542 +f 3860/3862/8543 3861/3863/8544 3859/3861/8542 +f 3860/3862/8543 3862/3864/8545 3861/3863/8544 +f 3860/3862/8543 3858/3860/8541 3862/3864/8545 +f 3858/3860/8541 3854/3856/8536 3862/3864/8545 +f 3863/3865/8546 3864/3866/8547 3865/3867/98 +f 3851/3853/8548 3864/3866/8547 3863/3865/8546 +f 3866/3868/98 3867/3869/98 3868/3870/98 +f 3869/3871/8549 3846/3848/8550 3870/3872/8551 +f 3851/3853/8548 3868/3870/8552 3864/3866/8547 +f 3870/3872/8553 3846/3848/8553 3871/3873/8553 +f 3865/3867/98 3864/3866/8547 3867/3869/98 +f 3868/3870/8552 3851/3853/8548 3872/3874/8554 +f 3844/3846/8555 3846/3848/8550 3869/3871/8549 +f 3871/3873/98 3873/3875/8556 3869/3871/98 +f 3872/3874/8557 3874/3876/8558 3866/3868/98 +f 3872/3874/8557 3856/3858/8559 3874/3876/8558 +f 3868/3870/98 3872/3874/8557 3866/3868/98 +f 3856/3858/8559 3875/3877/8560 3874/3876/8558 +f 3856/3858/8559 3876/3878/8561 3875/3877/8560 +f 3876/3878/8561 3877/3879/8562 3875/3877/8560 +f 3876/3878/8561 3878/3880/8563 3877/3879/8562 +f 3878/3880/8563 3862/3864/8564 3877/3879/8562 +f 3873/3875/8556 3879/3881/2514 3880/3882/8565 +f 3871/3873/98 3879/3881/2514 3873/3875/8556 +f 3862/3864/8564 3880/3882/8565 3877/3879/8562 +f 3862/3864/8564 3873/3875/8556 3880/3882/8565 +f 3850/3852/8566 3879/3881/8567 3871/3873/8568 +f 3850/3852/8566 3858/3860/8569 3879/3881/8567 +f 3858/3860/8570 3880/3882/8570 3879/3881/8570 +f 3858/3860/8571 3860/3862/8571 3880/3882/8571 +f 3860/3862/8572 3877/3879/8572 3880/3882/8572 +f 3860/3862/8573 3857/3859/8573 3877/3879/8573 +f 3857/3859/8574 3875/3877/8574 3877/3879/8574 +f 3857/3859/8575 3855/3857/8575 3875/3877/8575 +f 3855/3857/8576 3874/3876/8576 3875/3877/8576 +f 3855/3857/8577 3866/3868/8578 3874/3876/8579 +f 3855/3857/8577 3847/3849/8580 3866/3868/8578 +f 3847/3849/8581 3841/3843/8581 3866/3868/8581 +f 3841/3843/8582 3867/3869/8583 3866/3868/8584 +f 3840/3842/8585 3865/3867/8585 3841/3843/8585 +f 3865/3867/8586 3867/3869/8583 3841/3843/8582 +f 3840/3842/8587 3852/3854/8587 3865/3867/8587 +f 3852/3854/8588 3863/3865/8588 3865/3867/8588 +f 3851/3853/8589 3863/3865/8589 3852/3854/8589 +f 3851/3853/8535 3853/3855/8534 3872/3874/8590 +f 3853/3855/8591 3856/3858/8591 3872/3874/8591 +f 3859/3861/8592 3876/3878/8592 3856/3858/8592 +f 3859/3861/8593 3861/3863/8593 3876/3878/8593 +f 3861/3863/8594 3878/3880/8594 3876/3878/8594 +f 3861/3863/8595 3862/3864/8595 3878/3880/8595 +f 3854/3856/8596 3873/3875/8596 3862/3864/8596 +f 3854/3856/8597 3842/3844/8597 3873/3875/8597 +f 3842/3844/8598 3869/3871/8598 3873/3875/8598 +f 3844/3846/8599 3869/3871/8599 3842/3844/8599 +f 3850/3852/8566 3871/3873/8568 3846/3848/8600 +f 3849/3851/8601 3840/3842/8601 3864/3866/8601 +f 3840/3842/8602 3839/3841/8602 3864/3866/8602 +f 3839/3841/8603 3867/3869/8603 3864/3866/8603 +f 3839/3841/8604 3868/3870/8604 3867/3869/8604 +f 3839/3841/8605 3849/3851/8605 3868/3870/8605 +f 3849/3851/8606 3864/3866/8606 3868/3870/8606 +f 3848/3850/8607 3845/3847/8607 3870/3872/8607 +f 3845/3847/8608 3869/3871/8608 3870/3872/8608 +f 3845/3847/8609 3843/3845/8609 3869/3871/8609 +f 3843/3845/8610 3871/3873/8610 3869/3871/8610 +f 3843/3845/8611 3848/3850/8611 3871/3873/8611 +f 3848/3850/8612 3870/3872/8612 3871/3873/8612 +f 3881/3883/8613 3882/3884/8614 3883/3885/8615 +f 3884/3886/8616 3885/3887/8617 3886/3888/8618 +f 3882/3884/8614 3887/3889/8619 3883/3885/8615 +f 3887/3889/8619 3888/3890/8620 3883/3885/8615 +f 3887/3889/8619 3886/3888/8618 3889/3891/8621 +f 3887/3889/8619 3884/3886/8616 3886/3888/8618 +f 3888/3890/8620 3887/3889/8619 3889/3891/8621 +f 3884/3886/8616 3882/3884/8614 3890/3892/8622 +f 3882/3884/8614 3881/3883/8613 3890/3892/8622 +f 3884/3886/8616 3890/3892/8622 3885/3887/8617 +f 3891/3893/8623 3892/3894/8624 3893/3895/8625 +f 3894/3896/8626 3891/3893/8623 3895/3897/8627 +f 3892/3894/8624 3891/3893/8623 3894/3896/8626 +f 3896/3898/8628 3893/3895/8629 3892/3894/8630 +f 3896/3898/8628 3897/3899/8631 3893/3895/8629 +f 3897/3899/8632 3898/3900/8633 3893/3895/8634 +f 3898/3900/8633 3891/3893/8635 3893/3895/8634 +f 3898/3900/8636 3895/3897/8636 3891/3893/8636 +f 3898/3900/8637 3899/3901/8638 3895/3897/8639 +f 3899/3901/8638 3894/3896/8640 3895/3897/8639 +f 3899/3901/8641 3892/3894/8642 3894/3896/8643 +f 3899/3901/8641 3896/3898/8644 3892/3894/8642 +f 3897/3899/8645 3896/3898/8646 3900/3902/8647 +f 3896/3898/8646 3901/3903/8648 3900/3902/8647 +f 3899/3901/8649 3898/3900/8650 3902/3904/8651 +f 3898/3900/8650 3903/3905/8652 3902/3904/8651 +f 3899/3901/8649 3902/3904/8651 3904/3906/8653 +f 3896/3898/8646 3899/3901/8649 3901/3903/8648 +f 3899/3901/8649 3904/3906/8653 3901/3903/8648 +f 3897/3899/8645 3905/3907/8654 3906/3908/8655 +f 3897/3899/8645 3900/3902/8647 3905/3907/8654 +f 3898/3900/8650 3906/3908/8655 3903/3905/8652 +f 3898/3900/8650 3897/3899/8645 3906/3908/8655 +f 3901/3903/8656 3904/3906/8657 3883/3885/8658 +f 3904/3906/8657 3881/3883/8659 3883/3885/8658 +f 3904/3906/8660 3902/3904/8661 3881/3883/8662 +f 3902/3904/8661 3890/3892/8663 3881/3883/8662 +f 3902/3904/8664 3903/3905/8665 3890/3892/8666 +f 3890/3892/8666 3903/3905/8665 3885/3887/8667 +f 3903/3905/8665 3906/3908/8668 3885/3887/8667 +f 3885/3887/8667 3906/3908/8668 3886/3888/8669 +f 3906/3908/8668 3905/3907/8670 3886/3888/8669 +f 3905/3907/8671 3889/3891/8672 3886/3888/8673 +f 3905/3907/8671 3900/3902/8674 3889/3891/8672 +f 3900/3902/8675 3888/3890/8676 3889/3891/8677 +f 3900/3902/8675 3901/3903/8678 3888/3890/8676 +f 3901/3903/8678 3883/3885/8679 3888/3890/8676 +f 3907/3909/8680 3908/3910/8680 3884/3886/8680 +f 3887/3889/8681 3907/3909/8681 3884/3886/8681 +f 3909/3911/8682 3907/3909/8682 3887/3889/8682 +f 3882/3884/8683 3910/3912/8684 3887/3889/8685 +f 3910/3912/8684 3909/3911/8686 3887/3889/8685 +f 3884/3886/8687 3908/3910/8687 3882/3884/8687 +f 3908/3910/8688 3910/3912/8688 3882/3884/8688 +f 3910/3912/3031 3907/3909/3031 3909/3911/3031 +f 3910/3912/3031 3908/3910/3031 3907/3909/3031 +f 3911/3913/8689 3912/3914/8690 3913/3915/8691 +f 3911/3913/8689 3914/3916/8692 3912/3914/8690 +f 3915/3917/8693 3916/3918/8694 3917/3919/8695 +f 3916/3918/8694 3918/3920/8696 3917/3919/8695 +f 3911/3913/8689 3915/3917/8693 3914/3916/8692 +f 3915/3917/8693 3917/3919/8695 3914/3916/8692 +f 3916/3918/8694 3919/3921/8697 3920/3922/8698 +f 3916/3918/8694 3913/3915/8699 3919/3921/8697 +f 3916/3918/8694 3920/3922/8698 3918/3920/8696 +f 3921/3923/8700 3922/3924/8701 3923/3925/8702 +f 3924/3926/8703 3921/3923/8700 3923/3925/8702 +f 3921/3923/8700 3924/3926/8703 3925/3927/8704 +f 3926/3928/8705 3923/3925/8705 3922/3924/8705 +f 3926/3928/8706 3927/3929/8706 3923/3925/8706 +f 3927/3929/8707 3924/3926/8708 3923/3925/8709 +f 3927/3929/8707 3928/3930/8710 3924/3926/8708 +f 3928/3930/8711 3925/3927/8712 3924/3926/8713 +f 3928/3930/8711 3929/3931/8714 3925/3927/8712 +f 3929/3931/8715 3921/3923/8716 3925/3927/8717 +f 3929/3931/8715 3930/3932/8718 3921/3923/8716 +f 3930/3932/8719 3922/3924/8719 3921/3923/8719 +f 3930/3932/8720 3926/3928/8720 3922/3924/8720 +f 3926/3928/8721 3930/3932/8722 3931/3933/8723 +f 3926/3928/8721 3931/3933/8723 3932/3934/8724 +f 3929/3931/8725 3933/3935/8726 3934/3936/8727 +f 3929/3931/8725 3928/3930/8728 3933/3935/8726 +f 3930/3932/8722 3929/3931/8725 3934/3936/8727 +f 3930/3932/8722 3935/3937/8729 3931/3933/8723 +f 3930/3932/8722 3934/3936/8727 3935/3937/8729 +f 3927/3929/8730 3926/3928/8721 3936/3938/8731 +f 3926/3928/8721 3932/3934/8724 3936/3938/8731 +f 3928/3930/8728 3936/3938/8731 3933/3935/8726 +f 3928/3930/8728 3927/3929/8730 3936/3938/8731 +f 3931/3933/8732 3935/3937/8733 3912/3914/8734 +f 3935/3937/8733 3913/3915/8735 3912/3914/8734 +f 3935/3937/8736 3934/3936/8737 3913/3915/8738 +f 3934/3936/8737 3919/3921/8739 3913/3915/8738 +f 3919/3921/8740 3934/3936/8741 3920/3922/8742 +f 3934/3936/8741 3933/3935/8743 3920/3922/8742 +f 3920/3922/8744 3933/3935/8744 3918/3920/8744 +f 3933/3935/8745 3936/3938/8745 3918/3920/8745 +f 3918/3920/8746 3936/3938/8746 3917/3919/8746 +f 3936/3938/8747 3932/3934/8748 3917/3919/8749 +f 3932/3934/8748 3914/3916/8750 3917/3919/8749 +f 3932/3934/8751 3931/3933/8752 3914/3916/8753 +f 3931/3933/8752 3912/3914/8754 3914/3916/8753 +f 3915/3917/8755 3937/3939/8756 3916/3918/8757 +f 3937/3939/8756 3938/3940/8758 3916/3918/8757 +f 3911/3913/8759 3937/3939/8759 3915/3917/8759 +f 3939/3941/8760 3937/3939/8761 3911/3913/8762 +f 3913/3915/8763 3939/3941/8760 3911/3913/8762 +f 3916/3918/8764 3938/3940/8764 3913/3915/8764 +f 3938/3940/8765 3939/3941/8765 3913/3915/8765 +f 3939/3941/2352 3938/3940/2352 3937/3939/2352 +f 3940/3942/8766 3941/3943/8766 3942/3944/8766 +f 3940/3942/8767 3943/3945/8767 3941/3943/8767 +f 3943/3945/8768 3944/3946/8768 3941/3943/8768 +f 3943/3945/8769 3945/3947/8770 3944/3946/8771 +f 3943/3945/8769 3946/3948/8772 3945/3947/8770 +f 3946/3948/8773 3947/3949/8773 3945/3947/8773 +f 3947/3949/8774 3948/3950/8774 3945/3947/8774 +f 3947/3949/8775 3949/3951/8776 3948/3950/8777 +f 3950/3952/8778 3951/3953/8778 3949/3951/8778 +f 3951/3953/8779 3948/3950/8777 3949/3951/8776 +f 3950/3952/8780 3952/3954/8781 3951/3953/8782 +f 3950/3952/8780 3953/3955/8783 3952/3954/8781 +f 3953/3955/8784 3954/3956/8785 3952/3954/8786 +f 3953/3955/8784 3955/3957/8787 3954/3956/8785 +f 3955/3957/8788 3956/3958/8788 3954/3956/8788 +f 3956/3958/8789 3957/3959/8789 3954/3956/8789 +f 3956/3958/8790 3958/3960/8790 3957/3959/8790 +f 3958/3960/8791 3959/3961/8791 3957/3959/8791 +f 3958/3960/8792 3960/3962/8792 3959/3961/8792 +f 3960/3962/8793 3961/3963/8793 3959/3961/8793 +f 3960/3962/8794 3962/3964/8794 3961/3963/8794 +f 3940/3942/8795 3942/3944/8795 3962/3964/8795 +f 3962/3964/8796 3960/3962/8797 3940/3942/8798 +f 3947/3949/3031 3955/3957/3031 3953/3955/3031 +f 3947/3949/3031 3953/3955/3031 3950/3952/3031 +f 3949/3951/3031 3947/3949/3031 3950/3952/3031 +f 3946/3948/3031 3956/3958/3031 3955/3957/3031 +f 3947/3949/3031 3946/3948/3031 3955/3957/3031 +f 3943/3945/3031 3940/3942/8798 3960/3962/8797 +f 3943/3945/3031 3960/3962/8797 3958/3960/3031 +f 3943/3945/3031 3958/3960/3031 3956/3958/3031 +f 3946/3948/3031 3943/3945/3031 3956/3958/3031 +f 3945/3947/3026 3948/3950/3026 3954/3956/3026 +f 3948/3950/3026 3952/3954/3026 3954/3956/3026 +f 3948/3950/3026 3951/3953/3026 3952/3954/3026 +f 3945/3947/3026 3954/3956/3026 3957/3959/3026 +f 3944/3946/3026 3945/3947/3026 3957/3959/3026 +f 3944/3946/3026 3957/3959/3026 3959/3961/3026 +f 3942/3944/8799 3961/3963/8800 3962/3964/8801 +f 3942/3944/8799 3941/3943/3026 3961/3963/8800 +f 3941/3943/3026 3944/3946/3026 3959/3961/3026 +f 3941/3943/3026 3959/3961/3026 3961/3963/8800 +f 3963/3965/8802 3964/3966/8803 3965/3967/8804 +f 3963/3965/8805 3966/3968/8805 3964/3966/8805 +f 3966/3968/8806 3967/3969/8806 3964/3966/8806 +f 3966/3968/8807 3968/3970/8807 3967/3969/8807 +f 3968/3970/8808 3969/3971/8808 3967/3969/8808 +f 3968/3970/8809 3970/3972/8810 3969/3971/8811 +f 3970/3972/8810 3971/3973/8812 3969/3971/8811 +f 3970/3972/8813 3972/3974/8813 3971/3973/8813 +f 3973/3975/8814 3974/3976/8814 3972/3974/8814 +f 3974/3976/8815 3971/3973/8815 3972/3974/8815 +f 3973/3975/8816 3975/3977/8816 3974/3976/8816 +f 3975/3977/8817 3976/3978/8817 3974/3976/8817 +f 3975/3977/8818 3977/3979/8818 3976/3978/8818 +f 3977/3979/8819 3978/3980/8819 3976/3978/8819 +f 3977/3979/8820 3979/3981/8820 3978/3980/8820 +f 3979/3981/8821 3980/3982/8821 3978/3980/8821 +f 3979/3981/8822 3981/3983/8822 3980/3982/8822 +f 3981/3983/8823 3982/3984/8823 3980/3982/8823 +f 3981/3983/8824 3983/3985/8824 3982/3984/8824 +f 3983/3985/8825 3984/3986/8825 3982/3984/8825 +f 3983/3985/8826 3985/3987/8826 3984/3986/8826 +f 3985/3987/8827 3986/3988/8827 3984/3986/8827 +f 3985/3987/8828 3987/3989/8828 3986/3988/8828 +f 3963/3965/8802 3965/3967/8804 3987/3989/8829 +f 3965/3967/8830 3986/3988/8830 3987/3989/8830 +f 3970/3972/3031 3977/3979/3031 3975/3977/3031 +f 3970/3972/3031 3968/3970/3031 3977/3979/3031 +f 3972/3974/3031 3970/3972/3031 3973/3975/3031 +f 3970/3972/3031 3975/3977/3031 3973/3975/3031 +f 3966/3968/3031 3983/3985/3031 3981/3983/3031 +f 3968/3970/3031 3979/3981/3031 3977/3979/3031 +f 3963/3965/3031 3987/3989/3031 3985/3987/3031 +f 3966/3968/3031 3963/3965/3031 3983/3985/3031 +f 3963/3965/3031 3985/3987/3031 3983/3985/3031 +f 3968/3970/3031 3966/3968/3031 3981/3983/3031 +f 3968/3970/3031 3981/3983/3031 3979/3981/3031 +f 3969/3971/3026 3976/3978/3026 3978/3980/3026 +f 3969/3971/3026 3971/3973/3026 3976/3978/3026 +f 3971/3973/3026 3974/3976/3026 3976/3978/3026 +f 3969/3971/3026 3978/3980/3026 3980/3982/3026 +f 3967/3969/3026 3969/3971/3026 3980/3982/3026 +f 3967/3969/3026 3980/3982/3026 3982/3984/3026 +f 3964/3966/3026 3967/3969/3026 3982/3984/3026 +f 3965/3967/3026 3964/3966/3026 3986/3988/3026 +f 3964/3966/3026 3982/3984/3026 3984/3986/3026 +f 3964/3966/3026 3984/3986/3026 3986/3988/3026 +f 3988/3990/8831 3989/3991/8831 3990/3992/8831 +f 3989/3991/8832 3991/3993/8833 3990/3992/8834 +f 3989/3991/8832 3992/3994/8835 3991/3993/8833 +f 3992/3994/8836 3993/3995/8837 3991/3993/8838 +f 3992/3994/8836 3994/3996/8839 3993/3995/8837 +f 3994/3996/8840 3995/3997/8841 3993/3995/8842 +f 3994/3996/8840 3996/3998/8843 3995/3997/8841 +f 3996/3998/8844 3997/3999/8845 3995/3997/8846 +f 3997/3999/8845 3998/4000/8847 3995/3997/8846 +f 3999/4001/8848 3998/4000/8848 3997/3999/8848 +f 3999/4001/8849 4000/4002/8849 3998/4000/8849 +f 3999/4001/8850 4001/4003/8850 4000/4002/8850 +f 4001/4003/8851 4002/4004/8851 4000/4002/8851 +f 4001/4003/8852 4003/4005/8852 4002/4004/8852 +f 4003/4005/8853 4004/4006/8853 4002/4004/8853 +f 4003/4005/8854 4005/4007/8854 4004/4006/8854 +f 4005/4007/8855 4006/4008/8856 4004/4006/8857 +f 4005/4007/8855 4007/4009/8858 4006/4008/8856 +f 4007/4009/8859 4008/4010/8859 4006/4008/8859 +f 4008/4010/8860 4009/4011/8860 4006/4008/8860 +f 4008/4010/8861 4010/4012/8861 4009/4011/8861 +f 4010/4012/8862 4011/4013/8862 4009/4011/8862 +f 3988/3990/8863 4011/4013/8863 4010/4012/8863 +f 4010/4012/8864 3989/3991/8865 3988/3990/8866 +f 3997/3999/3085 4001/4003/3085 3999/4001/3085 +f 3997/3999/3085 3996/3998/3085 4001/4003/3085 +f 3996/3998/3085 4003/4005/3085 4001/4003/3085 +f 3996/3998/3085 3994/3996/3085 4003/4005/3085 +f 3989/3991/8865 4010/4012/8864 4008/4010/3085 +f 3992/3994/3085 4008/4010/3085 4007/4009/3085 +f 3992/3994/3085 3989/3991/8865 4008/4010/3085 +f 3992/3994/3085 4007/4009/3085 4005/4007/3085 +f 4003/4005/3085 3994/3996/3085 4005/4007/3085 +f 3994/3996/3085 3992/3994/3085 4005/4007/3085 +f 3995/3997/2352 4000/4002/2352 4002/4004/2352 +f 3995/3997/2352 3998/4000/2352 4000/4002/2352 +f 3993/3995/2352 3995/3997/2352 4002/4004/2352 +f 3993/3995/2352 4002/4004/2352 4004/4006/2352 +f 3991/3993/2352 4004/4006/2352 4006/4008/2352 +f 3991/3993/2352 3993/3995/2352 4004/4006/2352 +f 3988/3990/8867 3990/3992/8867 4011/4013/8867 +f 3990/3992/2352 4009/4011/2352 4011/4013/2352 +f 3990/3992/2352 3991/3993/2352 4009/4011/2352 +f 3991/3993/2352 4006/4008/2352 4009/4011/2352 +f 4012/4014/8868 4013/4015/8869 4014/4016/8870 +f 4012/4014/8871 4015/4017/8871 4013/4015/8871 +f 4015/4017/8872 4016/4018/8872 4013/4015/8872 +f 4015/4017/8873 4017/4019/8873 4016/4018/8873 +f 4017/4019/8874 4018/4020/8874 4016/4018/8874 +f 4017/4019/8875 4019/4021/8876 4018/4020/8877 +f 4017/4019/8875 4020/4022/8878 4019/4021/8876 +f 4020/4022/8879 4021/4023/8880 4019/4021/8881 +f 4021/4023/8880 4022/4024/8882 4019/4021/8881 +f 4023/4025/8883 4022/4024/8882 4021/4023/8880 +f 4023/4025/8884 4024/4026/8884 4025/4027/8884 +f 4024/4026/8885 4026/4028/8885 4025/4027/8885 +f 4024/4026/8886 4027/4029/8886 4026/4028/8886 +f 4027/4029/8887 4028/4030/8887 4026/4028/8887 +f 4027/4029/8888 4029/4031/8888 4028/4030/8888 +f 4029/4031/8889 4030/4032/8889 4028/4030/8889 +f 4029/4031/8890 4031/4033/8891 4030/4032/8892 +f 4029/4031/8890 4032/4034/8893 4031/4033/8891 +f 4032/4034/8894 4033/4035/8894 4031/4033/8894 +f 4033/4035/8895 4034/4036/8895 4031/4033/8895 +f 4033/4035/8896 4035/4037/8896 4034/4036/8896 +f 4012/4014/8868 4014/4016/8870 4035/4037/8897 +f 4014/4016/8898 4034/4036/8898 4035/4037/8898 +f 4035/4037/3085 4033/4035/3085 4012/4014/3085 +f 4020/4022/3085 4027/4029/3085 4024/4026/8899 +f 4021/4023/8900 4020/4022/3085 4024/4026/8899 +f 4021/4023/8900 4024/4026/8899 4023/4025/8901 +f 4017/4019/3085 4029/4031/3085 4027/4029/3085 +f 4020/4022/3085 4017/4019/3085 4027/4029/3085 +f 4015/4017/3085 4012/4014/3085 4033/4035/3085 +f 4015/4017/3085 4033/4035/3085 4032/4034/3085 +f 4015/4017/3085 4032/4034/3085 4029/4031/3085 +f 4017/4019/3085 4015/4017/3085 4029/4031/3085 +f 4023/4025/8902 4025/4027/8903 4022/4024/8904 +f 4019/4021/2352 4025/4027/8903 4026/4028/2352 +f 4019/4021/2352 4022/4024/8904 4025/4027/8903 +f 4018/4020/2352 4026/4028/2352 4028/4030/2352 +f 4018/4020/2352 4019/4021/2352 4026/4028/2352 +f 4016/4018/2352 4018/4020/2352 4030/4032/2352 +f 4018/4020/2352 4028/4030/2352 4030/4032/2352 +f 4016/4018/2352 4030/4032/2352 4031/4033/2352 +f 4013/4015/2352 4016/4018/2352 4031/4033/2352 +f 4014/4016/2352 4013/4015/2352 4034/4036/2352 +f 4013/4015/2352 4031/4033/2352 4034/4036/2352 +f 4036/4038/8905 4037/4039/8906 4038/4040/8907 +f 4039/4041/8908 4038/4040/8907 4040/4042/8909 +f 4039/4041/8908 4036/4038/8905 4038/4040/8907 +f 4041/4043/8910 4042/4044/8911 4043/4045/8912 +f 4042/4044/8911 4044/4046/8913 4043/4045/8912 +f 4045/4047/8914 4046/4048/8915 4047/4049/8916 +f 4048/4050/8917 4049/4051/8918 4050/4052/8919 +f 4051/4053/8920 4052/4054/8921 4053/4055/8922 +f 4046/4048/8915 4054/4056/8923 4047/4049/8916 +f 4055/4057/8924 4056/4058/8925 4057/4059/8926 +f 4055/4057/8924 4051/4053/8920 4056/4058/8925 +f 4046/4048/8915 4055/4057/8924 4054/4056/8923 +f 4055/4057/8924 4057/4059/8926 4054/4056/8923 +f 4053/4055/8922 4058/4060/8927 4056/4058/8925 +f 4058/4060/8927 4049/4051/8918 4056/4058/8925 +f 4052/4054/8921 4051/4053/8920 4040/4042/8928 +f 4056/4058/8925 4051/4053/8920 4053/4055/8922 +f 4049/4051/8918 4058/4060/8927 4050/4052/8919 +f 4059/4061/8929 4060/4062/8930 4061/4063/8931 +f 4059/4061/8929 4062/4064/8932 4060/4062/8930 +f 4062/4064/8932 4063/4065/8933 4060/4062/8930 +f 4063/4065/8933 4064/4066/8934 4060/4062/8930 +f 4063/4065/8933 4065/4067/8935 4064/4066/8934 +f 4063/4065/8933 4066/4068/8936 4065/4067/8935 +f 4067/4069/8937 4068/4070/8938 4069/4071/8939 +f 4067/4069/8937 4070/4072/8940 4068/4070/8938 +f 4070/4072/8940 4071/4073/8941 4068/4070/8938 +f 4071/4073/8941 4072/4074/8942 4068/4070/8938 +f 4071/4073/8941 4073/4075/8943 4072/4074/8942 +f 4073/4075/8943 4074/4076/8944 4072/4074/8942 +f 4073/4075/8943 4075/4077/8945 4074/4076/8944 +f 4073/4075/8943 4076/4078/8946 4075/4077/8945 +f 4077/4079/8947 4078/4080/8948 4079/4081/8949 +f 4080/4082/8950 4081/4083/8951 4082/4084/8952 +f 4083/4085/8953 4084/4086/8954 4085/4087/8955 +f 4086/4088/8956 4087/4089/8957 4088/4090/8958 +f 4086/4088/8956 4083/4085/8953 4085/4087/8955 +f 4084/4086/8954 4083/4085/8953 4079/4081/8949 +f 4083/4085/8953 4077/4079/8947 4079/4081/8949 +f 4086/4088/8956 4088/4090/8958 4043/4045/8959 +f 4082/4084/8952 4081/4083/8951 4089/4091/8960 +f 4086/4088/8956 4085/4087/8955 4087/4089/8957 +f 4081/4083/8951 4087/4089/8957 4089/4091/8960 +f 4087/4089/8957 4085/4087/8955 4089/4091/8960 +f 4090/4092/8961 4091/4093/8962 4092/4094/8963 +f 4090/4092/8961 4093/4095/8964 4091/4093/8962 +f 4093/4095/8964 4094/4096/8965 4091/4093/8962 +f 4094/4096/8965 4095/4097/8966 4091/4093/8962 +f 4094/4096/8965 4096/4098/8967 4095/4097/8966 +f 4096/4098/8967 4097/4099/8968 4095/4097/8966 +f 4096/4098/8967 4098/4100/8969 4097/4099/8968 +f 4098/4100/8969 4099/4101/8970 4097/4099/8968 +f 4100/4102/8971 4101/4103/8972 4102/4104/8973 +f 4101/4103/8972 4103/4105/8974 4102/4104/8973 +f 4101/4103/8972 4104/4106/8975 4103/4105/8974 +f 4104/4106/8975 4105/4107/8976 4103/4105/8974 +f 4104/4106/8975 4106/4108/8977 4105/4107/8976 +f 4106/4108/8977 4107/4109/8978 4105/4107/8976 +f 4106/4108/8977 4108/4110/8979 4107/4109/8978 +f 4108/4110/8979 4109/4111/8980 4107/4109/8978 +f 4108/4110/8979 4110/4112/8981 4109/4111/8980 +f 4110/4112/8981 4111/4113/8982 4109/4111/8980 +f 4110/4112/8981 4112/4114/8983 4111/4113/8982 +f 4112/4114/8983 4113/4115/8984 4111/4113/8982 +f 4112/4114/8983 4114/4116/8985 4113/4115/8984 +f 4112/4114/8983 4115/4117/8986 4114/4116/8985 +f 4115/4117/8986 4116/4118/8987 4114/4116/8985 +f 4115/4117/8986 4117/4119/8988 4116/4118/8987 +f 4117/4119/8988 4118/4120/8989 4116/4118/8987 +f 4119/4121/8990 4055/4057/8924 4120/4122/8991 +f 4119/4121/8990 4051/4053/8920 4055/4057/8924 +f 4121/4123/8992 4119/4121/8990 4120/4122/8991 +f 4122/4124/8993 4121/4123/8992 4123/4125/8994 +f 4121/4123/8992 4120/4122/8991 4123/4125/8994 +f 4123/4125/8994 4124/4126/8995 4122/4124/8993 +f 4123/4125/8994 4125/4127/8996 4124/4126/8995 +f 4126/4128/8997 4125/4127/8996 4127/4129/8998 +f 4126/4128/8997 4124/4126/8995 4125/4127/8996 +f 4127/4129/8998 4128/4130/8999 4126/4128/8997 +f 4127/4129/8998 4129/4131/9000 4128/4130/8999 +f 4086/4088/8956 4129/4131/9000 4083/4085/8953 +f 4129/4131/9000 4127/4129/8998 4083/4085/8953 +f 4130/4132/9001 4131/4133/9002 4132/4134/9003 +f 4131/4133/9002 4133/4135/9004 4132/4134/9003 +f 4131/4133/9002 4134/4136/9005 4133/4135/9004 +f 4134/4136/9005 4135/4137/9006 4133/4135/9004 +f 4134/4136/9005 4136/4138/9007 4135/4137/9006 +f 4134/4136/9005 4137/4139/9008 4136/4138/9007 +f 4138/4140/9009 4139/4141/9010 4066/4068/9011 +f 4139/4141/9010 4140/4142/9012 4066/4068/9011 +f 4062/4064/9013 4138/4140/9009 4066/4068/9011 +f 4140/4142/9012 4130/4132/9014 4141/4143/9015 +f 4130/4132/9014 4140/4142/9012 4139/4141/9010 +f 4139/4141/9010 4142/4144/9016 4130/4132/9014 +f 4131/4133/9017 4130/4132/9014 4134/4136/9018 +f 4143/4145/9019 4059/4061/9020 4144/4146/9021 +f 4145/4147/9022 4137/4139/9023 4134/4136/9018 +f 4145/4147/9022 4146/4148/9024 4137/4139/9023 +f 4134/4136/9018 4147/4149/9025 4145/4147/9022 +f 4130/4132/9014 4142/4144/9016 4147/4149/9025 +f 4130/4132/9014 4147/4149/9025 4134/4136/9018 +f 4062/4064/9013 4066/4068/9011 4063/4065/9026 +f 4143/4145/9019 4148/4150/9027 4059/4061/9020 +f 4148/4150/9027 4062/4064/9013 4059/4061/9020 +f 4148/4150/9027 4138/4140/9009 4062/4064/9013 +f 4149/4151/9028 4150/4152/9029 4151/4153/9030 +f 4152/4154/98 4153/4155/98 4154/4156/98 +f 4067/4069/9031 4155/4157/9032 4071/4073/9033 +f 4155/4157/9032 4067/4069/9031 4156/4158/9034 +f 4094/4096/9035 4098/4100/9036 4096/4098/9037 +f 4157/4159/9038 4158/4160/9039 4159/4161/9040 +f 4157/4159/9038 4160/4162/9041 4158/4160/9039 +f 4160/4162/9041 4090/4092/9042 4158/4160/9039 +f 4076/4078/9043 4161/4163/9044 4162/4164/9045 +f 4163/4165/9046 4156/4158/9034 4098/4100/9036 +f 4094/4096/9035 4163/4165/9046 4098/4100/9036 +f 4161/4163/9044 4164/4166/9047 4162/4164/9045 +f 4164/4166/9047 4165/4167/9048 4162/4164/9045 +f 4166/4168/9049 4156/4158/9034 4067/4069/9031 +f 4098/4100/9036 4166/4168/9049 4167/4169/9050 +f 4067/4069/9031 4071/4073/9033 4070/4072/9051 +f 4076/4078/9043 4168/4170/9052 4161/4163/9044 +f 4094/4096/9035 4169/4171/9053 4163/4165/9046 +f 4160/4162/9041 4169/4171/9053 4090/4092/9042 +f 4169/4171/9053 4093/4095/9054 4090/4092/9042 +f 4073/4075/9055 4168/4170/9052 4076/4078/9043 +f 4156/4158/9034 4166/4168/9049 4098/4100/9036 +f 4155/4157/9032 4168/4170/9052 4071/4073/9033 +f 4168/4170/9052 4073/4075/9055 4071/4073/9033 +f 4169/4171/9053 4094/4096/9035 4093/4095/9054 +f 4080/4082/8950 4041/4043/8910 4170/4172/9056 +f 4078/4080/8948 4171/4173/9057 4172/4174/9058 +f 4173/4175/9059 4042/4044/9060 4174/4176/9061 +f 4042/4044/9060 4077/4079/9062 4174/4176/9061 +f 4100/4102/9063 4175/4177/9064 4101/4103/9065 +f 4175/4177/9064 4176/4178/9066 4101/4103/9065 +f 4176/4178/9066 4104/4106/9067 4101/4103/9065 +f 4176/4178/9066 4177/4179/9068 4104/4106/9067 +f 4177/4179/9068 4106/4108/9069 4104/4106/9067 +f 4177/4179/9068 4178/4180/9070 4106/4108/9069 +f 4178/4180/9070 4108/4110/9071 4106/4108/9069 +f 4178/4180/9070 4179/4181/9072 4108/4110/9071 +f 4108/4110/9071 4179/4181/9072 4110/4112/9073 +f 4110/4112/9073 4179/4181/9072 4112/4114/9074 +f 4179/4181/9072 4180/4182/9075 4112/4114/9074 +f 4180/4182/9075 4181/4183/9076 4112/4114/9074 +f 4181/4183/9076 4115/4117/9077 4112/4114/9074 +f 4181/4183/9076 4182/4184/9078 4115/4117/9077 +f 4182/4184/9078 4117/4119/9079 4115/4117/9077 +f 4102/4104/9080 4103/4105/9081 4143/4145/9082 +f 4103/4105/9081 4148/4150/9083 4143/4145/9082 +f 4103/4105/9081 4105/4107/9084 4148/4150/9083 +f 4105/4107/9084 4138/4140/9085 4148/4150/9083 +f 4105/4107/9084 4107/4109/9086 4138/4140/9085 +f 4107/4109/9086 4109/4111/9087 4138/4140/9085 +f 4109/4111/9087 4139/4141/9088 4138/4140/9085 +f 4109/4111/9087 4142/4144/9089 4139/4141/9088 +f 4109/4111/9087 4111/4113/9090 4142/4144/9089 +f 4111/4113/9090 4147/4149/9091 4142/4144/9089 +f 4111/4113/9090 4113/4115/9092 4147/4149/9091 +f 4113/4115/9092 4145/4147/9093 4147/4149/9091 +f 4113/4115/9092 4114/4116/9094 4145/4147/9093 +f 4116/4118/9095 4146/4148/9096 4145/4147/9093 +f 4116/4118/9095 4118/4120/9097 4146/4148/9096 +f 4114/4116/9094 4116/4118/9095 4145/4147/9093 +f 4089/4091/9098 4183/4185/9098 4082/4084/9098 +f 4089/4091/9099 4085/4087/9100 4183/4185/9101 +f 4085/4087/9100 4171/4173/9102 4183/4185/9101 +f 4085/4087/9103 4084/4086/9103 4171/4173/9103 +f 4084/4086/9104 4172/4174/9104 4171/4173/9104 +f 4084/4086/9105 4079/4081/9105 4172/4174/9105 +f 4079/4081/9106 4078/4080/9106 4172/4174/9106 +f 4043/4045/9107 4170/4172/9108 4184/4186/9109 +f 4043/4045/9107 4088/4090/9110 4170/4172/9108 +f 4088/4090/9111 4087/4089/9111 4170/4172/9111 +f 4087/4089/9112 4185/4187/9112 4170/4172/9112 +f 4087/4089/9113 4081/4083/9113 4185/4187/9113 +f 4081/4083/9114 4080/4082/9114 4185/4187/9114 +f 4184/4186/9115 4041/4043/9115 4043/4045/9115 +f 4078/4080/8948 4082/4084/8952 4171/4173/9057 +f 4186/4188/9116 4187/4189/9117 4188/4190/9118 +f 4188/4190/9118 4174/4176/9119 4189/4191/9120 +f 4190/4192/9121 4187/4189/9117 4186/4188/9116 +f 4170/4172/9056 4041/4043/8910 4184/4186/9122 +f 4185/4187/9123 4080/4082/8950 4170/4172/9056 +f 4082/4084/8952 4183/4185/9124 4171/4173/9057 +f 4188/4190/9118 4187/4189/9117 4174/4176/9119 +f 4187/4189/9125 4173/4175/9126 4174/4176/9127 +f 4041/4043/8910 4078/4080/8948 4077/4079/8947 +f 4041/4043/8910 4080/4082/8950 4078/4080/8948 +f 4078/4080/8948 4080/4082/8950 4082/4084/8952 +f 4041/4043/8910 4077/4079/8947 4042/4044/8911 +f 4144/4146/9128 4061/4063/8931 4173/4175/9126 +f 4144/4146/9128 4059/4061/8929 4061/4063/8931 +f 4144/4146/9128 4173/4175/9126 4187/4189/9125 +f 4144/4146/9129 4190/4192/9130 4143/4145/9131 +f 4144/4146/9129 4187/4189/9132 4190/4192/9130 +f 4143/4145/9133 4190/4192/9134 4186/4188/9135 +f 4143/4145/9133 4186/4188/9135 4102/4104/9136 +f 4188/4190/9137 4100/4102/9138 4186/4188/9139 +f 4100/4102/9138 4102/4104/9140 4186/4188/9139 +f 4188/4190/9137 4189/4191/9141 4100/4102/9138 +f 4189/4191/9141 4175/4177/9142 4100/4102/9138 +f 4191/4193/9143 4050/4052/8919 4192/4194/9144 +f 4037/4039/8906 4193/4195/9145 4194/4196/9146 +f 4036/4038/9147 4195/4197/9148 4196/4198/9149 +f 4195/4197/9148 4197/4199/9150 4196/4198/9149 +f 4054/4056/9151 4198/4200/9151 4047/4049/9151 +f 4054/4056/9152 4057/4059/9153 4198/4200/9154 +f 4057/4059/9153 4199/4201/9155 4198/4200/9154 +f 4057/4059/9156 4200/4202/9157 4199/4201/9158 +f 4057/4059/9156 4056/4058/9159 4200/4202/9157 +f 4056/4058/9160 4049/4051/9161 4200/4202/9162 +f 4049/4051/9161 4201/4203/9163 4200/4202/9162 +f 4049/4051/9164 4048/4050/9164 4201/4203/9164 +f 4198/4200/9165 4199/4201/9166 4047/4049/8916 +f 4199/4201/9166 4045/4047/8914 4047/4049/8916 +f 4202/4204/9167 4203/4205/9168 4204/4206/9169 +f 4197/4199/9170 4202/4204/9167 4205/4207/9171 +f 4050/4052/8919 4193/4195/9145 4037/4039/8906 +f 4050/4052/8919 4191/4193/9143 4193/4195/9145 +f 4199/4201/9166 4200/4202/9172 4045/4047/8914 +f 4200/4202/9172 4048/4050/8917 4045/4047/8914 +f 4200/4202/9172 4201/4203/9173 4048/4050/8917 +f 4206/4208/9174 4204/4206/9169 4203/4205/9168 +f 4197/4199/9170 4203/4205/9168 4202/4204/9167 +f 4193/4195/9175 4038/4040/9175 4194/4196/9175 +f 4038/4040/9176 4037/4039/9176 4194/4196/9176 +f 4058/4060/9177 4192/4194/9177 4050/4052/9177 +f 4058/4060/9178 4053/4055/9179 4192/4194/9180 +f 4053/4055/9179 4191/4193/9181 4192/4194/9180 +f 4053/4055/9182 4052/4054/9183 4191/4193/9184 +f 4052/4054/9183 4193/4195/9185 4191/4193/9184 +f 4052/4054/9186 4040/4042/9186 4193/4195/9186 +f 4038/4040/9187 4193/4195/9187 4040/4042/9187 +f 4203/4205/9188 4197/4199/9189 4195/4197/9190 +f 4036/4038/8905 4050/4052/8919 4037/4039/8906 +f 4050/4052/8919 4045/4047/8914 4048/4050/8917 +f 4050/4052/8919 4036/4038/8905 4045/4047/8914 +f 4045/4047/9191 4036/4038/9191 4046/4048/9191 +f 4036/4038/9147 4196/4198/9149 4046/4048/9192 +f 4137/4139/9193 4195/4197/9190 4136/4138/9194 +f 4203/4205/9188 4195/4197/9190 4137/4139/9193 +f 4146/4148/9024 4203/4205/9195 4137/4139/9023 +f 4146/4148/9024 4206/4208/9196 4203/4205/9195 +f 4204/4206/9197 4206/4208/9198 4118/4120/9199 +f 4206/4208/9198 4146/4148/9200 4118/4120/9199 +f 4117/4119/9201 4202/4204/9202 4118/4120/9203 +f 4202/4204/9202 4204/4206/9204 4118/4120/9203 +f 4117/4119/9205 4182/4184/9206 4202/4204/9207 +f 4182/4184/9206 4205/4207/9208 4202/4204/9207 +f 4207/4209/9209 4098/4100/8969 4167/4169/9210 +f 4207/4209/9209 4099/4101/8970 4098/4100/8969 +f 4208/4210/9211 4167/4169/9212 4166/4168/9213 +f 4208/4210/9211 4207/4209/9214 4167/4169/9212 +f 4069/4071/9215 4208/4210/9216 4067/4069/9217 +f 4208/4210/9216 4166/4168/9218 4067/4069/9217 +f 4132/4134/9219 4209/4211/9220 4149/4151/9028 +f 4210/4212/9221 4211/4213/9222 4099/4101/9223 +f 4212/4214/9224 4068/4070/9225 4213/4215/9226 +f 4095/4097/9227 4097/4099/9228 4211/4213/9222 +f 4213/4215/9226 4068/4070/9225 4214/4216/9229 +f 4211/4213/9222 4215/4217/9230 4095/4097/9227 +f 4216/4218/9231 4136/4138/9232 4195/4197/9233 +f 4072/4074/9234 4217/4219/9235 4214/4216/9229 +f 4074/4076/9236 4218/4220/9237 4217/4219/9235 +f 4219/4221/9238 4091/4093/9239 4220/4222/9240 +f 4220/4222/9240 4095/4097/9227 4215/4217/9230 +f 4074/4076/9236 4217/4219/9235 4072/4074/9234 +f 4068/4070/9225 4212/4214/9224 4069/4071/9241 +f 4220/4222/9240 4091/4093/9239 4095/4097/9227 +f 4075/4077/9242 4218/4220/9237 4074/4076/9236 +f 4219/4221/9238 4092/4094/9243 4091/4093/9239 +f 4210/4212/9221 4069/4071/9241 4212/4214/9224 +f 4099/4101/9223 4207/4209/9244 4210/4212/9221 +f 4221/4223/9245 4075/4077/9246 4162/4164/9247 +f 4075/4077/9246 4076/4078/9248 4162/4164/9247 +f 4162/4164/9249 4222/4224/9250 4221/4223/9251 +f 4162/4164/9249 4165/4167/9252 4222/4224/9250 +f 4165/4167/9253 4223/4225/9254 4222/4224/9255 +f 4150/4152/9256 4065/4067/9257 4140/4142/9258 +f 4065/4067/9257 4066/4068/9259 4140/4142/9258 +f 4151/4153/9260 4140/4142/9261 4141/4143/9262 +f 4151/4153/9260 4150/4152/9263 4140/4142/9261 +f 4132/4134/9264 4151/4153/9265 4130/4132/9266 +f 4151/4153/9265 4141/4143/9267 4130/4132/9266 +f 4159/4161/9268 4224/4226/9269 4225/4227/9270 +f 4224/4226/9271 4226/4228/9272 4225/4227/9273 +f 4224/4226/9271 4158/4160/9274 4226/4228/9272 +f 4092/4094/9275 4226/4228/9276 4090/4092/9277 +f 4226/4228/9276 4158/4160/9278 4090/4092/9277 +f 4161/4163/9279 4227/4229/9280 4228/4230/9281 +f 4161/4163/9279 4229/4231/9282 4227/4229/9280 +f 4229/4231/9283 4230/4232/9283 4227/4229/9283 +f 4229/4231/9284 4164/4166/9284 4230/4232/9284 +f 4231/4233/9285 4230/4232/9285 4164/4166/9285 +f 4228/4230/9286 4164/4166/9287 4161/4163/9288 +f 4228/4230/9286 4231/4233/9289 4164/4166/9287 +f 4157/4159/9290 4152/4154/9291 4154/4156/9292 +f 4157/4159/9290 4232/4234/9293 4152/4154/9291 +f 4232/4234/9294 4153/4155/9295 4152/4154/9296 +f 4153/4155/9295 4232/4234/9294 4160/4162/9297 +f 4154/4156/9298 4160/4162/9299 4157/4159/9300 +f 4154/4156/9298 4153/4155/9301 4160/4162/9299 +f 4223/4225/9302 4165/4167/9048 4164/4166/9047 +f 4223/4225/9302 4164/4166/9047 4229/4231/9303 +f 4229/4231/9303 4233/4235/9304 4223/4225/9302 +f 4168/4170/9052 4229/4231/9303 4161/4163/9044 +f 4086/4088/9305 4043/4045/9306 4233/4235/9304 +f 4168/4170/9052 4233/4235/9304 4229/4231/9303 +f 4168/4170/9052 4086/4088/9305 4233/4235/9304 +f 4121/4123/8992 4122/4124/8993 4234/4236/9307 +f 4119/4121/9308 4234/4236/9307 4169/4171/9053 +f 4119/4121/9308 4121/4123/8992 4234/4236/9307 +f 4124/4126/9309 4126/4128/9310 4156/4158/9311 +f 4086/4088/9305 4168/4170/9052 4129/4131/9312 +f 4051/4053/8920 4119/4121/9308 4169/4171/9053 +f 4122/4124/9313 4124/4126/9309 4163/4165/9314 +f 4124/4126/9309 4156/4158/9311 4163/4165/9314 +f 4126/4128/9310 4128/4130/9315 4156/4158/9311 +f 4122/4124/9313 4163/4165/9314 4234/4236/9316 +f 4128/4130/9315 4129/4131/9312 4155/4157/9317 +f 4129/4131/9312 4168/4170/9052 4155/4157/9317 +f 4234/4236/9318 4163/4165/9318 4169/4171/9318 +f 4128/4130/9315 4155/4157/9317 4156/4158/9311 +f 4160/4162/9041 4232/4234/9319 4169/4171/9053 +f 4159/4161/9320 4235/4237/9321 4157/4159/9322 +f 4235/4237/9321 4232/4234/9319 4157/4159/9322 +f 4235/4237/9321 4169/4171/9053 4232/4234/9319 +f 4235/4237/9321 4051/4053/8920 4169/4171/9053 +f 4040/4042/8928 4051/4053/8920 4235/4237/9321 +f 4223/4225/9254 4236/4238/9323 4222/4224/9255 +f 4236/4238/9323 4223/4225/9254 4233/4235/9324 +f 4233/4235/9324 4044/4046/8913 4236/4238/9323 +f 4233/4235/9324 4043/4045/8912 4044/4046/8913 +f 4237/4239/9325 4039/4041/8908 4235/4237/9326 +f 4039/4041/8908 4040/4042/8909 4235/4237/9326 +f 4237/4239/9325 4235/4237/9326 4159/4161/9268 +f 4159/4161/9268 4225/4227/9270 4237/4239/9325 +f 4196/4198/9327 4055/4057/9327 4046/4048/9327 +f 4159/4161/9040 4158/4160/9039 4224/4226/9328 +f 4238/4240/9329 4239/4241/9330 4240/4242/9331 +f 4241/4243/9332 4242/4244/9333 4243/4245/9334 +f 4244/4246/9335 4239/4241/9330 4238/4240/9329 +f 4243/4245/9334 4242/4244/9333 4244/4246/9335 +f 4242/4244/9333 4239/4241/9330 4244/4246/9335 +f 4245/4247/9336 4246/4248/9337 4247/4249/9338 +f 4239/4241/9330 4247/4249/9338 4240/4242/9331 +f 4239/4241/9330 4245/4247/9336 4247/4249/9338 +f 4245/4247/9336 4241/4243/9332 4246/4248/9337 +f 4245/4247/9336 4242/4244/9333 4241/4243/9332 +f 4248/4250/9339 4249/4251/9340 4250/4252/9341 +f 4251/4253/9342 4248/4250/9339 4250/4252/9341 +f 4248/4250/9339 4251/4253/9342 4252/4254/9343 +f 4253/4255/9344 4248/4250/9344 4252/4254/9344 +f 4253/4255/9345 4249/4251/9346 4248/4250/9347 +f 4253/4255/9345 4254/4256/9348 4249/4251/9346 +f 4254/4256/9349 4250/4252/9349 4249/4251/9349 +f 4254/4256/9350 4255/4257/9350 4250/4252/9350 +f 4255/4257/9351 4251/4253/9351 4250/4252/9351 +f 4255/4257/9352 4256/4258/9352 4251/4253/9352 +f 4256/4258/9353 4252/4254/9353 4251/4253/9353 +f 4256/4258/9354 4253/4255/9354 4252/4254/9354 +f 4254/4256/9355 4253/4255/9356 4257/4259/9357 +f 4253/4255/9356 4258/4260/9358 4257/4259/9357 +f 4255/4257/9359 4259/4261/9360 4260/4262/9361 +f 4256/4258/9362 4260/4262/9361 4261/4263/9363 +f 4256/4258/9362 4255/4257/9359 4260/4262/9361 +f 4258/4260/9358 4253/4255/9356 4261/4263/9363 +f 4253/4255/9356 4256/4258/9362 4261/4263/9363 +f 4254/4256/9355 4257/4259/9357 4262/4264/9364 +f 4255/4257/9359 4254/4256/9355 4259/4261/9360 +f 4254/4256/9355 4262/4264/9364 4259/4261/9360 +f 4258/4260/9365 4261/4263/9366 4241/4243/9367 +f 4241/4243/9368 4261/4263/9369 4246/4248/9370 +f 4261/4263/9369 4260/4262/9371 4246/4248/9370 +f 4246/4248/9372 4260/4262/9373 4247/4249/9374 +f 4260/4262/9373 4259/4261/9375 4247/4249/9374 +f 4259/4261/9376 4240/4242/9376 4247/4249/9376 +f 4259/4261/9377 4262/4264/9378 4240/4242/9379 +f 4240/4242/9379 4262/4264/9378 4238/4240/9380 +f 4238/4240/9381 4262/4264/9382 4244/4246/9383 +f 4262/4264/9382 4257/4259/9384 4244/4246/9383 +f 4244/4246/9385 4257/4259/9386 4243/4245/9387 +f 4257/4259/9386 4258/4260/9388 4243/4245/9387 +f 4258/4260/9365 4241/4243/9367 4243/4245/9389 +f 4239/4241/9390 4263/4265/9391 4245/4247/9392 +f 4263/4265/9391 4264/4266/9393 4245/4247/9392 +f 4242/4244/9394 4265/4267/9394 4239/4241/9394 +f 4265/4267/9395 4263/4265/9395 4239/4241/9395 +f 4266/4268/9396 4265/4267/9396 4242/4244/9396 +f 4245/4247/9397 4266/4268/9397 4242/4244/9397 +f 4264/4266/9398 4266/4268/9398 4245/4247/9398 +f 4266/4268/2352 4263/4265/2352 4265/4267/2352 +f 4266/4268/2352 4264/4266/2352 4263/4265/2352 +f 4267/4269/9399 4268/4270/9400 4269/4271/9401 +f 4267/4269/9399 4270/4272/9402 4268/4270/9400 +f 4270/4272/9402 4271/4273/9403 4268/4270/9400 +f 4270/4272/9402 4272/4274/9404 4273/4275/9405 +f 4270/4272/9402 4274/4276/9406 4272/4274/9404 +f 4270/4272/9402 4273/4275/9405 4271/4273/9403 +f 4274/4276/9406 4267/4269/9399 4275/4277/9407 +f 4267/4269/9399 4269/4271/9401 4275/4277/9407 +f 4274/4276/9406 4275/4277/9407 4272/4274/9404 +f 4276/4278/9408 4277/4279/9409 4278/4280/9410 +f 4279/4281/9411 4276/4278/9408 4280/4282/9412 +f 4276/4278/9408 4279/4281/9411 4277/4279/9409 +f 4281/4283/9413 4282/4284/9413 4277/4279/9413 +f 4282/4284/9414 4278/4280/9414 4277/4279/9414 +f 4282/4284/9415 4283/4285/9415 4278/4280/9415 +f 4283/4285/9416 4276/4278/9417 4278/4280/9418 +f 4283/4285/9416 4284/4286/9419 4276/4278/9417 +f 4284/4286/9420 4280/4282/9421 4276/4278/9422 +f 4284/4286/9420 4285/4287/9423 4280/4282/9421 +f 4285/4287/9424 4279/4281/9425 4280/4282/9426 +f 4285/4287/9424 4281/4283/9427 4279/4281/9425 +f 4281/4283/9428 4277/4279/9428 4279/4281/9428 +f 4282/4284/9429 4281/4283/9430 4286/4288/9431 +f 4282/4284/9429 4286/4288/9431 4287/4289/9432 +f 4285/4287/9433 4288/4290/9434 4289/4291/9435 +f 4285/4287/9433 4284/4286/9436 4288/4290/9434 +f 4281/4283/9430 4285/4287/9433 4290/4292/9437 +f 4285/4287/9433 4289/4291/9435 4290/4292/9437 +f 4286/4288/9431 4281/4283/9430 4290/4292/9437 +f 4283/4285/9438 4287/4289/9432 4291/4293/9439 +f 4283/4285/9438 4282/4284/9429 4287/4289/9432 +f 4284/4286/9436 4291/4293/9439 4288/4290/9434 +f 4284/4286/9436 4283/4285/9438 4291/4293/9439 +f 4286/4288/9440 4290/4292/9441 4268/4270/9442 +f 4290/4292/9443 4269/4271/9443 4268/4270/9443 +f 4290/4292/9444 4289/4291/9445 4269/4271/9446 +f 4289/4291/9445 4275/4277/9447 4269/4271/9446 +f 4289/4291/9448 4288/4290/9448 4275/4277/9448 +f 4275/4277/9449 4288/4290/9450 4272/4274/9451 +f 4288/4290/9450 4291/4293/9452 4272/4274/9451 +f 4272/4274/9453 4291/4293/9454 4273/4275/9455 +f 4291/4293/9454 4287/4289/9456 4273/4275/9455 +f 4273/4275/9457 4287/4289/9458 4271/4273/9459 +f 4287/4289/9458 4286/4288/9460 4271/4273/9459 +f 4271/4273/9461 4286/4288/9440 4268/4270/9442 +f 4292/4294/9462 4293/4295/9462 4274/4276/9462 +f 4270/4272/9463 4294/4296/9464 4274/4276/9465 +f 4294/4296/9464 4292/4294/9466 4274/4276/9465 +f 4267/4269/9467 4295/4297/9467 4270/4272/9467 +f 4295/4297/9468 4294/4296/9468 4270/4272/9468 +f 4293/4295/9469 4295/4297/9469 4267/4269/9469 +f 4274/4276/9470 4293/4295/9470 4267/4269/9470 +f 4295/4297/3031 4293/4295/3031 4294/4296/3031 +f 4293/4295/3031 4292/4294/3031 4294/4296/3031 +f 3282/3284/9471 3687/3689/9472 3281/3283/9473 +f 3281/3283/9473 3716/3718/9474 3492/3494/9475 +f 3718/3720/9476 3492/3494/9475 3716/3718/9474 +f 3492/3494/9475 3718/3720/9476 3278/3280/9477 +f 3281/3283/9473 3687/3689/9472 3716/3718/9474 +f 3485/3487/9478 3711/3713/9479 3468/3470/9480 +f 3711/3713/9479 3484/3486/9481 3406/3408/9482 +f 3485/3487/9478 3484/3486/9481 3711/3713/9479 +f 3707/3709/528 3708/3710/528 3709/3711/528 +f 3710/3712/528 3707/3709/528 3709/3711/528 +f 3706/3708/528 3703/3705/528 3705/3707/528 +f 3703/3705/528 3706/3708/528 3704/3706/528 +f 3737/3739/528 3738/3740/528 3734/3736/528 +f 3735/3737/528 3737/3739/528 3734/3736/528 +f 3737/3739/528 3735/3737/528 3736/3738/528 +f 3294/3296/9483 4296/4298/9483 3297/3299/9483 +f 4210/4212/9484 3512/3514/8079 3511/3513/9485 +f 4218/4220/9486 3293/3295/8048 3544/3546/8047 +f 4218/4220/9487 3544/3546/9487 3543/3545/9487 +f 4218/4220/9488 3543/3545/9488 4217/4219/9488 +f 4214/4216/9489 3543/3545/9490 3546/3548/9491 +f 4211/4213/9492 3128/3130/9492 4215/4217/9492 +f 4214/4216/9493 3546/3548/9493 4213/4215/9493 +f 4213/4215/9494 3545/3547/9495 4212/4214/9496 +f 4220/4222/9497 3128/3130/9498 3060/3062/9499 +f 4210/4212/9500 3511/3513/9500 4211/4213/9500 +f 4220/4222/9497 3060/3062/9499 4219/4221/9501 +f 3132/3134/9502 3131/3133/9503 4216/4218/9504 +f 3131/3133/9503 3135/3137/9505 4216/4218/9504 +f 4297/4299/9506 3135/3137/9506 3134/3136/9506 +f 4209/4211/9507 3134/3136/9507 3137/3139/9507 +f 4219/4221/9508 3058/3060/7799 3132/3134/7798 +f 3295/3297/9509 4149/4151/9509 3137/3139/9509 +f 4219/4221/9501 3060/3062/9499 3058/3060/9510 +f 4296/4298/9511 4298/4300/9511 3297/3299/9511 +f 4299/4301/9512 4296/4298/9512 3294/3296/9512 +f 3293/3295/9513 4299/4301/9513 3294/3296/9513 +f 4211/4213/9514 3511/3513/9514 3128/3130/9514 +f 4213/4215/9494 3546/3548/9515 3545/3547/9495 +f 4212/4214/9516 3545/3547/8080 4210/4212/9484 +f 4299/4301/9517 3293/3295/8048 4218/4220/9486 +f 3512/3514/8079 4210/4212/9484 3545/3547/8080 +f 4215/4217/9518 3128/3130/9518 4220/4222/9518 +f 3132/3134/7798 4216/4218/9519 4219/4221/9508 +f 4297/4299/9520 3134/3136/9520 4209/4211/9520 +f 4209/4211/9521 3137/3139/9521 4149/4151/9521 +f 3297/3299/9522 4298/4300/9523 3295/3297/9524 +f 4217/4219/9525 3543/3545/9490 4214/4216/9489 +f 4123/4125/9526 4120/4122/9527 4125/4127/9528 +f 4125/4127/9528 4083/4085/9529 4127/4129/9530 +f 4120/4122/9527 4055/4057/9531 4125/4127/9528 +f 4055/4057/9531 4083/4085/9529 4125/4127/9528 +f 4055/4057/9531 4178/4180/9532 4083/4085/9529 +f 4077/4079/9533 4083/4085/9529 4189/4191/9534 +f 4205/4207/9535 4055/4057/9531 4196/4198/9536 +f 4197/4199/9537 4205/4207/9535 4196/4198/9536 +f 4055/4057/9531 4179/4181/9538 4178/4180/9532 +f 4189/4191/9534 4174/4176/9539 4077/4079/9533 +f 4182/4184/9540 4055/4057/9531 4205/4207/9535 +f 4083/4085/9529 4175/4177/9541 4189/4191/9534 +f 4083/4085/9529 4178/4180/9532 4177/4179/9542 +f 4083/4085/9529 4176/4178/9543 4175/4177/9541 +f 4182/4184/9540 4181/4183/9544 4055/4057/9531 +f 4083/4085/9529 4177/4179/9542 4176/4178/9543 +f 4181/4183/9544 4180/4182/9545 4055/4057/9531 +f 4180/4182/9545 4179/4181/9538 4055/4057/9531 +f 4231/4233/2568 4228/4230/5591 4227/4229/2568 +f 4231/4233/2568 4227/4229/2568 4230/4232/9546 +f 4299/4301/9547 4218/4220/9237 4075/4077/9242 +f 4221/4223/9548 4299/4301/9547 4075/4077/9242 +f 4219/4221/9238 4226/4228/9549 4092/4094/9243 +f 4219/4221/9238 4225/4227/9550 4226/4228/9549 +f 4222/4224/9551 4299/4301/9547 4221/4223/9548 +f 4219/4221/9238 4237/4239/9552 4225/4227/9550 +f 4222/4224/9551 4236/4238/9553 4299/4301/9547 +f 4216/4218/9231 4237/4239/9552 4219/4221/9238 +f 4216/4218/9231 4039/4041/9554 4237/4239/9552 +f 4044/4046/9555 4299/4301/9547 4236/4238/9553 +f 4042/4044/9556 4299/4301/9547 4044/4046/9555 +f 4216/4218/9231 4036/4038/9557 4039/4041/9554 +f 4042/4044/9556 4296/4298/9558 4299/4301/9547 +f 4216/4218/9231 4195/4197/9233 4036/4038/9557 +f 4042/4044/9556 4173/4175/9559 4296/4298/9558 +f 4173/4175/9559 4061/4063/9560 4296/4298/9558 +f 3135/3137/9561 4136/4138/9232 4216/4218/9231 +f 4214/4216/9229 4068/4070/9225 4072/4074/9234 +f 4099/4101/9223 4211/4213/9222 4097/4099/9228 +f 3135/3137/9561 4135/4137/9562 4136/4138/9232 +f 4061/4063/9560 4298/4300/9523 4296/4298/9558 +f 4297/4299/9563 4135/4137/9562 3135/3137/9561 +f 4060/4062/9564 4298/4300/9523 4061/4063/9560 +f 4297/4299/9563 4133/4135/9565 4135/4137/9562 +f 4210/4212/9221 4208/4210/9566 4069/4071/9241 +f 3295/3297/9524 4298/4300/9523 4064/4066/9567 +f 4064/4066/9567 4298/4300/9523 4060/4062/9564 +f 4133/4135/9565 4209/4211/9220 4132/4134/9219 +f 4149/4151/9028 3295/3297/9524 4065/4067/9568 +f 4210/4212/9221 4207/4209/9244 4208/4210/9566 +f 4065/4067/9568 3295/3297/9524 4064/4066/9567 +f 4065/4067/9568 4150/4152/9029 4149/4151/9028 +f 4149/4151/9028 4151/4153/9030 4132/4134/9219 +f 4133/4135/9565 4297/4299/9563 4209/4211/9220 +f 4300/4302/9569 4301/4303/9570 4302/4304/9571 +f 4300/4302/9569 4303/4305/9572 4301/4303/9570 +f 4304/4306/9573 4302/4304/9571 4305/4307/9574 +f 4304/4306/9573 4305/4307/9574 4306/4308/9575 +f 4300/4302/9569 4302/4304/9571 4304/4306/9573 +f 4307/4309/9576 4303/4305/9572 4300/4302/9569 +f 4307/4309/9576 4308/4310/9577 4303/4305/9572 +f 4304/4306/9573 4306/4308/9575 4307/4309/9576 +f 4307/4309/9576 4306/4308/9575 4308/4310/9577 +f 4309/4311/9578 4310/4312/9579 4311/4313/9580 +f 4309/4311/9578 4312/4314/9581 4310/4312/9579 +f 4313/4315/9582 4314/4316/9583 4310/4312/9584 +f 4313/4315/9582 4310/4312/9584 4315/4317/9585 +f 4315/4317/9586 4310/4312/9587 4312/4314/9588 +f 4315/4317/9586 4312/4314/9588 4316/4318/9589 +f 4316/4318/9590 4312/4314/9591 4309/4311/9592 +f 4316/4318/9590 4309/4311/9592 4317/4319/9593 +f 4317/4319/9594 4309/4311/9595 4318/4320/9596 +f 4318/4320/9596 4309/4311/9595 4311/4313/9597 +f 4318/4320/9598 4311/4313/9599 4314/4316/9600 +f 4318/4320/9598 4314/4316/9600 4313/4315/9601 +f 4315/4317/9602 4319/4321/9603 4320/4322/9604 +f 4315/4317/9602 4320/4322/9604 4313/4315/9605 +f 4313/4315/9605 4320/4322/9604 4321/4323/9606 +f 4313/4315/9605 4321/4323/9606 4318/4320/9607 +f 4318/4320/9607 4321/4323/9606 4322/4324/9608 +f 4318/4320/9607 4322/4324/9608 4317/4319/9609 +f 4317/4319/9609 4322/4324/9608 4323/4325/9610 +f 4317/4319/9609 4323/4325/9610 4316/4318/9611 +f 4316/4318/9611 4323/4325/9610 4319/4321/9603 +f 4316/4318/9611 4319/4321/9603 4315/4317/9602 +f 4301/4303/9612 4321/4323/9613 4320/4322/9614 +f 4301/4303/9612 4320/4322/9614 4302/4304/9615 +f 4302/4304/9616 4320/4322/9617 4305/4307/9618 +f 4305/4307/9618 4320/4322/9617 4319/4321/9619 +f 4305/4307/9620 4319/4321/9620 4306/4308/9620 +f 4306/4308/9621 4319/4321/9622 4323/4325/9623 +f 4306/4308/9621 4323/4325/9623 4308/4310/9624 +f 4308/4310/9625 4323/4325/9626 4303/4305/9627 +f 4303/4305/9627 4323/4325/9626 4322/4324/9628 +f 4303/4305/9629 4322/4324/9630 4321/4323/9631 +f 4303/4305/9629 4321/4323/9631 4301/4303/9632 +f 4304/4306/9633 4307/4309/9634 4324/4326/9635 +f 4324/4326/9635 4307/4309/9634 4325/4327/9636 +f 4300/4302/9637 4304/4306/9638 4326/4328/9639 +f 4326/4328/9639 4304/4306/9638 4324/4326/9640 +f 4307/4309/9641 4300/4302/9642 4325/4327/9643 +f 4325/4327/9643 4300/4302/9642 4326/4328/9644 +f 4325/4327/528 4326/4328/528 4324/4326/528 +f 4314/4316/9645 4311/4313/9580 4310/4312/9579 +f 4327/4329/9646 4328/4330/9647 4329/4331/9648 +f 4329/4331/9648 4328/4330/9647 4330/4332/9649 +f 4331/4333/9650 4332/4334/9651 4333/4335/9652 +f 4329/4331/9648 4331/4333/9650 4333/4335/9652 +f 4329/4331/9648 4330/4332/9649 4331/4333/9650 +f 4327/4329/9646 4334/4336/9653 4328/4330/9647 +f 4333/4335/9652 4332/4334/9651 4334/4336/9653 +f 4333/4335/9652 4334/4336/9653 4327/4329/9646 +f 4335/4337/9654 4336/4338/9655 4337/4339/9656 +f 4337/4339/9656 4338/4340/9657 4335/4337/9654 +f 4339/4341/9658 4338/4340/9658 4337/4339/9658 +f 4339/4341/9659 4337/4339/9659 4340/4342/9659 +f 4340/4342/9660 4337/4339/9661 4336/4338/9662 +f 4340/4342/9660 4336/4338/9662 4341/4343/9663 +f 4341/4343/9664 4336/4338/9665 4342/4344/9666 +f 4342/4344/9666 4336/4338/9665 4335/4337/9667 +f 4342/4344/9668 4335/4337/9669 4338/4340/9670 +f 4342/4344/9668 4338/4340/9670 4339/4341/9671 +f 4340/4342/9672 4343/4345/9673 4344/4346/9674 +f 4340/4342/9672 4344/4346/9674 4339/4341/9675 +f 4339/4341/9675 4344/4346/9674 4345/4347/9676 +f 4339/4341/9675 4345/4347/9676 4342/4344/9677 +f 4342/4344/9677 4345/4347/9676 4346/4348/9678 +f 4342/4344/9677 4346/4348/9678 4341/4343/9679 +f 4341/4343/9679 4346/4348/9678 4347/4349/9680 +f 4341/4343/9679 4347/4349/9680 4343/4345/9673 +f 4341/4343/9679 4343/4345/9673 4340/4342/9672 +f 4328/4330/9681 4344/4346/9682 4330/4332/9683 +f 4330/4332/9684 4344/4346/9685 4331/4333/9686 +f 4331/4333/9686 4344/4346/9685 4343/4345/9687 +f 4331/4333/9688 4343/4345/9689 4347/4349/9690 +f 4331/4333/9688 4347/4349/9690 4332/4334/9691 +f 4332/4334/9692 4347/4349/9692 4346/4348/9692 +f 4332/4334/9693 4346/4348/9693 4334/4336/9693 +f 4334/4336/9694 4346/4348/9694 4345/4347/9694 +f 4334/4336/9695 4345/4347/9695 4328/4330/9695 +f 4328/4330/9681 4345/4347/9696 4344/4346/9682 +f 4329/4331/9697 4333/4335/9698 4348/4350/9699 +f 4348/4350/9699 4333/4335/9698 4349/4351/9700 +f 4327/4329/9701 4329/4331/9702 4350/4352/9703 +f 4350/4352/9703 4329/4331/9702 4348/4350/9704 +f 4333/4335/9705 4327/4329/9706 4349/4351/9707 +f 4349/4351/9707 4327/4329/9706 4350/4352/9708 +f 4349/4351/528 4350/4352/528 4348/4350/528 +f 4351/4353/9709 4352/4354/9709 4353/4355/9709 +f 4354/4356/9710 4351/4353/9710 4355/4357/9710 +f 4356/4358/9711 4357/4359/9712 4353/4355/9713 +f 4353/4355/9713 4357/4359/9712 4355/4357/9714 +f 4358/4360/9715 4359/4361/9716 4360/4362/9717 +f 4360/4362/9717 4361/4363/9718 4358/4360/9715 +f 4362/4364/9719 4360/4362/9719 4359/4361/9719 +f 4362/4364/9720 4359/4361/9720 4363/4365/9720 +f 4363/4365/9721 4359/4361/9721 4358/4360/9721 +f 4363/4365/9722 4358/4360/9722 4364/4366/9722 +f 4364/4366/9723 4358/4360/9723 4361/4363/9723 +f 4364/4366/9724 4361/4363/9724 4365/4367/9724 +f 4365/4367/9725 4361/4363/9725 4360/4362/9725 +f 4365/4367/9726 4360/4362/9726 4362/4364/9726 +f 4365/4367/9727 4366/4368/9728 4364/4366/9729 +f 4364/4366/9729 4366/4368/9728 4367/4369/9730 +f 4362/4364/9731 4368/4370/9732 4365/4367/9727 +f 4364/4366/9729 4367/4369/9730 4369/4371/9733 +f 4364/4366/9729 4369/4371/9733 4363/4365/9734 +f 4365/4367/9727 4368/4370/9732 4366/4368/9728 +f 4363/4365/9734 4370/4372/9735 4362/4364/9731 +f 4362/4364/9731 4370/4372/9735 4368/4370/9732 +f 4363/4365/9734 4369/4371/9733 4370/4372/9735 +f 4351/4353/9736 4368/4370/9736 4352/4354/9736 +f 4352/4354/9737 4368/4370/9737 4370/4372/9737 +f 4352/4354/9738 4370/4372/9738 4353/4355/9738 +f 4353/4355/9739 4370/4372/9740 4369/4371/9741 +f 4353/4355/9739 4369/4371/9741 4356/4358/9742 +f 4356/4358/9743 4369/4371/9744 4367/4369/9745 +f 4356/4358/9743 4367/4369/9745 4357/4359/9746 +f 4357/4359/9747 4367/4369/9748 4366/4368/9749 +f 4357/4359/9747 4366/4368/9749 4355/4357/9750 +f 4355/4357/9751 4366/4368/9751 4354/4356/9751 +f 4354/4356/9752 4366/4368/9753 4368/4370/9754 +f 4354/4356/9752 4368/4370/9754 4351/4353/9755 +f 4353/4355/9756 4355/4357/9757 4371/4373/9758 +f 4371/4373/9758 4355/4357/9757 4372/4374/9759 +f 4351/4353/9760 4353/4355/9761 4373/4375/9762 +f 4373/4375/9762 4353/4355/9761 4371/4373/9763 +f 4355/4357/9764 4351/4353/9765 4372/4374/9766 +f 4372/4374/9766 4351/4353/9765 4373/4375/9767 +f 4372/4374/528 4373/4375/528 4371/4373/528 +f 4374/4376/9768 4375/4377/9769 4376/4378/9770 +f 4376/4378/9770 4375/4377/9769 4377/4379/9771 +f 4376/4378/9772 4377/4379/9772 4378/4380/9772 +f 4376/4378/9773 4378/4380/9773 4379/4381/9773 +f 4379/4381/9774 4378/4380/9774 4380/4382/9774 +f 4379/4381/9775 4380/4382/9776 4381/4383/9777 +f 4382/4384/9778 4381/4383/9777 4380/4382/9776 +f 4382/4384/9779 4383/4385/9779 4384/4386/9779 +f 4384/4386/9780 4383/4385/9781 4385/4387/9782 +f 4384/4386/9780 4385/4387/9782 4386/4388/9783 +f 4386/4388/9784 4385/4387/9784 4387/4389/9784 +f 4386/4388/9785 4387/4389/9785 4388/4390/9785 +f 4388/4390/9786 4387/4389/9787 4389/4391/9788 +f 4389/4391/9788 4387/4389/9787 4390/4392/9789 +f 4389/4391/9790 4390/4392/9790 4391/4393/9790 +f 4389/4391/9791 4391/4393/9791 4392/4394/9791 +f 4374/4376/9792 4392/4394/9792 4375/4377/9792 +f 4375/4377/9793 4392/4394/9793 4391/4393/9793 +f 4376/4378/98 4386/4388/98 4388/4390/98 +f 4379/4381/98 4386/4388/98 4376/4378/98 +f 4379/4381/98 4384/4386/9794 4386/4388/98 +f 4374/4376/98 4389/4391/98 4392/4394/98 +f 4381/4383/9795 4384/4386/9794 4379/4381/98 +f 4381/4383/9795 4382/4384/9796 4384/4386/9794 +f 4376/4378/98 4389/4391/98 4374/4376/98 +f 4376/4378/98 4388/4390/98 4389/4391/98 +f 4378/4380/528 4385/4387/528 4383/4385/9797 +f 4377/4379/528 4387/4389/528 4378/4380/528 +f 4378/4380/528 4387/4389/528 4385/4387/528 +f 4380/4382/9798 4383/4385/9797 4382/4384/9799 +f 4378/4380/528 4383/4385/9797 4380/4382/9798 +f 4375/4377/528 4390/4392/528 4377/4379/528 +f 4377/4379/528 4390/4392/528 4387/4389/528 +f 4375/4377/528 4391/4393/528 4390/4392/528 +f 4393/4395/9800 4394/4396/9800 4395/4397/9800 +f 4393/4395/9801 4395/4397/9801 4396/4398/9801 +f 4396/4398/9802 4395/4397/9802 4397/4399/9802 +f 4396/4398/9803 4397/4399/9804 4398/4400/9805 +f 4398/4400/9805 4397/4399/9804 4399/4401/9806 +f 4398/4400/9807 4399/4401/9808 4400/4402/9809 +f 4398/4400/9807 4400/4402/9809 4401/4403/9810 +f 4402/4404/9811 4401/4403/9811 4400/4402/9811 +f 4402/4404/9812 4403/4405/9812 4404/4406/9812 +f 4404/4406/9813 4403/4405/9813 4405/4407/9813 +f 4404/4406/9814 4405/4407/9814 4406/4408/9814 +f 4406/4408/9815 4405/4407/9815 4407/4409/9815 +f 4406/4408/9816 4407/4409/9817 4408/4410/9818 +f 4406/4408/9816 4408/4410/9818 4409/4411/9819 +f 4409/4411/9820 4408/4410/9820 4410/4412/9820 +f 4410/4412/9821 4408/4410/9821 4411/4413/9821 +f 4410/4412/9822 4411/4413/9822 4412/4414/9822 +f 4412/4414/9823 4411/4413/9823 4413/4415/9823 +f 4393/4395/9824 4412/4414/9825 4394/4396/9826 +f 4394/4396/9826 4412/4414/9825 4413/4415/9827 +f 4396/4398/98 4406/4408/98 4409/4411/98 +f 4398/4400/98 4406/4408/98 4396/4398/98 +f 4398/4400/98 4404/4406/9828 4406/4408/98 +f 4401/4403/9829 4404/4406/9828 4398/4400/98 +f 4396/4398/98 4410/4412/98 4393/4395/98 +f 4393/4395/98 4410/4412/98 4412/4414/98 +f 4401/4403/9829 4402/4404/9830 4404/4406/9828 +f 4396/4398/98 4409/4411/98 4410/4412/98 +f 4399/4401/528 4407/4409/528 4405/4407/528 +f 4399/4401/528 4405/4407/528 4400/4402/9831 +f 4408/4410/528 4407/4409/528 4397/4399/528 +f 4397/4399/528 4407/4409/528 4399/4401/528 +f 4395/4397/528 4408/4410/528 4397/4399/528 +f 4400/4402/9831 4403/4405/9832 4402/4404/9833 +f 4405/4407/528 4403/4405/9832 4400/4402/9831 +f 4395/4397/528 4411/4413/528 4408/4410/528 +f 4394/4396/528 4413/4415/528 4395/4397/528 +f 4395/4397/528 4413/4415/528 4411/4413/528 +f 4414/4416/9834 4415/4417/9835 4416/4418/9836 +f 4416/4418/9836 4415/4417/9835 4417/4419/9837 +f 4414/4416/9834 4418/4420/9838 4415/4417/9835 +f 4419/4421/9839 4420/4422/9840 4421/4423/9841 +f 4416/4418/9836 4417/4419/9837 4419/4421/9839 +f 4416/4418/9836 4419/4421/9839 4421/4423/9841 +f 4421/4423/9841 4420/4422/9840 4414/4416/9834 +f 4414/4416/9834 4420/4422/9840 4418/4420/9838 +f 4422/4424/9842 4423/4425/9843 4424/4426/9844 +f 4424/4426/9844 4425/4427/9845 4422/4424/9842 +f 4426/4428/9846 4424/4426/9847 4427/4429/9848 +f 4427/4429/9848 4424/4426/9847 4423/4425/9849 +f 4427/4429/9850 4423/4425/9851 4422/4424/9852 +f 4427/4429/9850 4422/4424/9852 4428/4430/9853 +f 4428/4430/9854 4422/4424/9855 4429/4431/9856 +f 4429/4431/9856 4422/4424/9855 4425/4427/9857 +f 4429/4431/9858 4425/4427/9859 4426/4428/9860 +f 4426/4428/9860 4425/4427/9859 4424/4426/9861 +f 4427/4429/9862 4430/4432/9863 4426/4428/9864 +f 4426/4428/9864 4430/4432/9863 4431/4433/9865 +f 4426/4428/9864 4431/4433/9865 4432/4434/9866 +f 4426/4428/9864 4432/4434/9866 4429/4431/9867 +f 4429/4431/9867 4432/4434/9866 4433/4435/9868 +f 4429/4431/9867 4433/4435/9868 4428/4430/9869 +f 4428/4430/9869 4433/4435/9868 4434/4436/9870 +f 4428/4430/9869 4434/4436/9870 4427/4429/9862 +f 4427/4429/9862 4434/4436/9870 4435/4437/9871 +f 4427/4429/9862 4435/4437/9871 4430/4432/9863 +f 4415/4417/9872 4431/4433/9873 4417/4419/9874 +f 4417/4419/9875 4431/4433/9875 4430/4432/9875 +f 4417/4419/9876 4430/4432/9876 4419/4421/9876 +f 4419/4421/9877 4430/4432/9877 4435/4437/9877 +f 4419/4421/9878 4435/4437/9879 4420/4422/9880 +f 4420/4422/9880 4435/4437/9879 4434/4436/9881 +f 4420/4422/9882 4434/4436/9883 4433/4435/9884 +f 4420/4422/9882 4433/4435/9884 4418/4420/9885 +f 4418/4420/9886 4433/4435/9887 4432/4434/9888 +f 4418/4420/9886 4432/4434/9888 4415/4417/9889 +f 4415/4417/9872 4432/4434/9890 4431/4433/9873 +f 4416/4418/9891 4421/4423/9891 4436/4438/9891 +f 4437/4439/9892 4416/4418/9892 4436/4438/9892 +f 4414/4416/9893 4416/4418/9893 4437/4439/9893 +f 4421/4423/9894 4414/4416/9895 4436/4438/9896 +f 4436/4438/9896 4414/4416/9895 4437/4439/9897 +f 4438/4440/9898 4439/4441/9899 4440/4442/9900 +f 4440/4442/9900 4439/4441/9899 4441/4443/9901 +f 4440/4442/9902 4441/4443/9903 4442/4444/9904 +f 4442/4444/9904 4441/4443/9903 4443/4445/9905 +f 4442/4444/9906 4443/4445/9907 4444/4446/9908 +f 4444/4446/9908 4443/4445/9907 4445/4447/9909 +f 4444/4446/9910 4445/4447/9911 4446/4448/9912 +f 4446/4448/9912 4445/4447/9911 4447/4449/9913 +f 4448/4450/9914 4446/4448/9914 4447/4449/9914 +f 4448/4450/9915 4447/4449/9915 4449/4451/9915 +f 4448/4450/9916 4449/4451/9916 4450/4452/9916 +f 4450/4452/9917 4449/4451/9917 4451/4453/9917 +f 4450/4452/9918 4451/4453/9918 4452/4454/9918 +f 4452/4454/9919 4451/4453/9919 4453/4455/9919 +f 4452/4454/9920 4453/4455/9921 4454/4456/9922 +f 4452/4454/9920 4454/4456/9922 4455/4457/9923 +f 4455/4457/9924 4454/4456/9925 4456/4458/9926 +f 4455/4457/9924 4456/4458/9926 4457/4459/9927 +f 4457/4459/9928 4456/4458/9928 4458/4460/9928 +f 4438/4440/9898 4458/4460/9929 4439/4441/9899 +f 4440/4442/98 4452/4454/98 4455/4457/98 +f 4442/4444/98 4452/4454/98 4440/4442/98 +f 4444/4446/98 4450/4452/98 4442/4444/98 +f 4442/4444/98 4450/4452/98 4452/4454/98 +f 4438/4440/9930 4457/4459/9931 4458/4460/9932 +f 4440/4442/98 4455/4457/98 4438/4440/9930 +f 4438/4440/9930 4455/4457/98 4457/4459/9931 +f 4446/4448/98 4448/4450/98 4450/4452/98 +f 4446/4448/98 4450/4452/98 4444/4446/98 +f 4441/4443/528 4453/4455/528 4443/4445/528 +f 4443/4445/528 4451/4453/528 4445/4447/528 +f 4443/4445/528 4453/4455/528 4451/4453/528 +f 4441/4443/528 4454/4456/528 4453/4455/528 +f 4445/4447/528 4451/4453/528 4449/4451/528 +f 4445/4447/528 4449/4451/528 4447/4449/528 +f 4439/4441/9933 4456/4458/9934 4454/4456/528 +f 4439/4441/9933 4454/4456/528 4441/4443/528 +f 4439/4441/9933 4458/4460/9935 4456/4458/9934 +f 4459/4461/9936 4460/4462/9937 4461/4463/9938 +f 4459/4461/9939 4461/4463/9939 4462/4464/9939 +f 4462/4464/9940 4461/4463/9940 4463/4465/9940 +f 4462/4464/9941 4463/4465/9941 4464/4466/9941 +f 4464/4466/9942 4463/4465/9942 4465/4467/9942 +f 4464/4466/9943 4465/4467/9944 4466/4468/9945 +f 4464/4466/9943 4466/4468/9945 4467/4469/9946 +f 4468/4470/9947 4467/4469/9946 4466/4468/9945 +f 4468/4470/9948 4469/4471/9948 4470/4472/9948 +f 4470/4472/9949 4469/4471/9950 4471/4473/9951 +f 4470/4472/9949 4471/4473/9951 4472/4474/9952 +f 4472/4474/9953 4471/4473/9953 4473/4475/9953 +f 4472/4474/9954 4473/4475/9954 4474/4476/9954 +f 4474/4476/9955 4473/4475/9955 4475/4477/9955 +f 4474/4476/9956 4475/4477/9956 4476/4478/9956 +f 4476/4478/9957 4475/4477/9957 4477/4479/9957 +f 4476/4478/9958 4477/4479/9959 4478/4480/9960 +f 4476/4478/9958 4478/4480/9960 4479/4481/9961 +f 4459/4461/9936 4479/4481/9962 4460/4462/9937 +f 4460/4462/9963 4479/4481/9963 4478/4480/9963 +f 4464/4466/98 4474/4476/98 4462/4464/98 +f 4464/4466/98 4472/4474/98 4474/4476/98 +f 4459/4461/98 4476/4478/98 4479/4481/98 +f 4462/4464/98 4476/4478/98 4459/4461/98 +f 4467/4469/9964 4470/4472/9965 4464/4466/98 +f 4464/4466/98 4470/4472/9965 4472/4474/98 +f 4467/4469/9964 4468/4470/9966 4470/4472/9965 +f 4462/4464/98 4474/4476/98 4476/4478/98 +f 4463/4465/528 4473/4475/528 4465/4467/528 +f 4465/4467/528 4471/4473/528 4466/4468/9967 +f 4473/4475/528 4471/4473/528 4465/4467/528 +f 4463/4465/528 4475/4477/528 4473/4475/528 +f 4461/4463/528 4475/4477/528 4463/4465/528 +f 4466/4468/9967 4469/4471/9968 4468/4470/9969 +f 4471/4473/528 4469/4471/9968 4466/4468/9967 +f 4461/4463/528 4477/4479/528 4475/4477/528 +f 4461/4463/528 4478/4480/528 4477/4479/528 +f 4460/4462/528 4478/4480/528 4461/4463/528 +f 4480/4482/9970 4481/4483/9970 4482/4484/9970 +f 4482/4484/9971 4483/4485/9971 4484/4486/9971 +f 4485/4487/9972 4486/4488/9972 4480/4482/9972 +f 4487/4489/9973 4488/4490/9974 4489/4491/9975 +f 4490/4492/9976 4487/4489/9973 4489/4491/9975 +f 4491/4493/9977 4492/4494/9977 4488/4490/9977 +f 4488/4490/9978 4492/4494/9978 4489/4491/9978 +f 4492/4494/9979 4493/4495/9979 4489/4491/9979 +f 4489/4491/9980 4493/4495/9980 4490/4492/9980 +f 4490/4492/9981 4493/4495/9981 4494/4496/9981 +f 4490/4492/9982 4494/4496/9982 4487/4489/9982 +f 4494/4496/9983 4491/4493/9984 4487/4489/9985 +f 4487/4489/9985 4491/4493/9984 4488/4490/9986 +f 4494/4496/9987 4495/4497/9988 4491/4493/9989 +f 4491/4493/9989 4495/4497/9988 4496/4498/9990 +f 4497/4499/9991 4498/4500/9992 4493/4495/9993 +f 4493/4495/9993 4498/4500/9992 4494/4496/9987 +f 4493/4495/9993 4499/4501/9994 4497/4499/9991 +f 4491/4493/9989 4496/4498/9990 4492/4494/9995 +f 4494/4496/9987 4498/4500/9992 4495/4497/9988 +f 4492/4494/9995 4499/4501/9994 4493/4495/9993 +f 4492/4494/9995 4496/4498/9990 4499/4501/9994 +f 4483/4485/9996 4482/4484/9996 4496/4498/9996 +f 4496/4498/9997 4482/4484/9998 4499/4501/9999 +f 4482/4484/9998 4481/4483/10000 4499/4501/9999 +f 4481/4483/10001 4480/4482/10002 4499/4501/10003 +f 4499/4501/10003 4480/4482/10002 4497/4499/10004 +f 4480/4482/10005 4486/4488/10006 4497/4499/10007 +f 4497/4499/10007 4486/4488/10006 4498/4500/10008 +f 4498/4500/10009 4486/4488/10010 4485/4487/10011 +f 4498/4500/10009 4485/4487/10011 4495/4497/10012 +f 4485/4487/10011 4484/4486/10013 4495/4497/10012 +f 4495/4497/10014 4484/4486/10015 4483/4485/10016 +f 4495/4497/10014 4483/4485/10016 4496/4498/10017 +f 4485/4487/10018 4480/4482/10018 4500/4502/10018 +f 4500/4502/10019 4480/4482/10019 4501/4503/10019 +f 4484/4486/10020 4485/4487/10020 4500/4502/10020 +f 4482/4484/10021 4484/4486/10022 4501/4503/10023 +f 4501/4503/10023 4484/4486/10022 4500/4502/10024 +f 4480/4482/10025 4482/4484/10025 4501/4503/10025 +f 4502/4504/10026 4503/4505/10027 4504/4506/10028 +f 4502/4504/10026 4504/4506/10028 4505/4507/10029 +f 4505/4507/10029 4504/4506/10028 4506/4508/528 +f 4507/4509/10030 4508/4510/10031 4509/4511/2511 +f 4509/4511/2511 4508/4510/10031 4510/4512/10031 +f 4511/4513/10032 4512/4514/10033 4513/4515/10034 +f 4511/4513/10032 4514/4516/10035 4515/4517/10036 +f 4511/4513/10032 4513/4515/10034 4516/4518/10037 +f 4511/4513/10032 4516/4518/10037 4514/4516/10035 +f 4517/4519/10038 4516/4518/10039 4502/4504/10040 +f 4502/4504/10040 4516/4518/10039 4518/4520/10041 +f 4502/4504/10040 4519/4521/10042 4517/4519/10038 +f 4516/4518/10039 4513/4515/10043 4518/4520/10041 +f 4520/4522/10032 4521/4523/10033 4522/4524/10034 +f 4520/4522/10032 4523/4525/10035 4524/4526/10036 +f 4520/4522/10032 4522/4524/10034 4525/4527/10044 +f 4520/4522/10032 4525/4527/10044 4523/4525/10035 +f 4526/4528/10045 4525/4527/10046 4511/4513/10047 +f 4511/4513/10047 4525/4527/10046 4527/4529/10048 +f 4511/4513/10047 4528/4530/10049 4526/4528/10045 +f 4525/4527/10046 4522/4524/10050 4527/4529/10048 +f 4529/4531/10032 4530/4532/10033 4531/4533/10034 +f 4529/4531/10032 4532/4534/10035 4533/4535/10036 +f 4529/4531/10032 4531/4533/10034 4534/4536/10037 +f 4529/4531/10032 4534/4536/10037 4532/4534/10035 +f 4535/4537/10045 4534/4536/10051 4520/4522/10052 +f 4520/4522/10052 4534/4536/10051 4536/4538/10048 +f 4520/4522/10052 4537/4539/10049 4535/4537/10045 +f 4534/4536/10051 4531/4533/10050 4536/4538/10048 +f 4538/4540/10032 4539/4541/10033 4540/4542/10034 +f 4538/4540/10032 4541/4543/10035 4542/4544/10036 +f 4538/4540/10032 4540/4542/10034 4543/4545/10037 +f 4538/4540/10032 4543/4545/10037 4541/4543/10035 +f 4544/4546/10045 4543/4545/10051 4529/4531/10053 +f 4529/4531/10053 4543/4545/10051 4545/4547/10048 +f 4529/4531/10053 4546/4548/10049 4544/4546/10045 +f 4543/4545/10051 4540/4542/10050 4545/4547/10048 +f 4547/4549/10054 4548/4550/10055 4549/4551/10056 +f 4547/4549/10054 4550/4552/10057 4551/4553/528 +f 4547/4549/10054 4549/4551/10056 4552/4554/10058 +f 4547/4549/10054 4552/4554/10058 4550/4552/10057 +f 4553/4555/10045 4552/4554/10051 4538/4540/10053 +f 4538/4540/10053 4552/4554/10051 4554/4556/10048 +f 4538/4540/10053 4555/4557/10049 4553/4555/10045 +f 4552/4554/10051 4549/4551/10050 4554/4556/10048 +f 4556/4558/10059 4557/4559/10060 4558/4560/10061 +f 4556/4558/10059 4559/4561/10062 4560/4562/1243 +f 4556/4558/10059 4558/4560/10061 4561/4563/10063 +f 4556/4558/10059 4561/4563/10063 4559/4561/10062 +f 4562/4564/10064 4561/4563/10065 4563/4565/10066 +f 4563/4565/10066 4561/4563/10065 4564/4566/10067 +f 4561/4563/10065 4558/4560/10043 4564/4566/10067 +f 4504/4506/10068 4508/4510/10069 4507/4509/10070 +f 4504/4506/10068 4507/4509/10070 4506/4508/10071 +f 4516/4518/10072 4517/4519/10072 4514/4516/10072 +f 4525/4527/10073 4526/4528/10073 4523/4525/10073 +f 4534/4536/10072 4535/4537/10072 4532/4534/10072 +f 4543/4545/10072 4544/4546/10072 4541/4543/10072 +f 4552/4554/10072 4553/4555/10072 4550/4552/10072 +f 4561/4563/10074 4562/4564/10074 4559/4561/10074 +f 4565/4567/528 4566/4568/528 4503/4505/528 +f 4567/4569/528 4566/4568/528 4565/4567/528 +f 4568/4570/10075 4569/4571/528 4570/4572/528 +f 4571/4573/528 4569/4571/528 4568/4570/10075 +f 4571/4573/528 4568/4570/10075 4572/4574/10076 +f 4572/4574/10076 4568/4570/10075 4573/4575/10077 +f 4574/4576/10078 4575/4577/10079 4576/4578/10080 +f 4576/4578/10080 4575/4577/10079 4573/4575/10077 +f 4573/4575/10077 4575/4577/10079 4572/4574/10076 +f 4577/4579/10081 4574/4576/10078 4576/4578/10080 +f 4578/4580/10082 4510/4512/10082 4579/4581/10082 +f 4578/4580/10082 4579/4581/10082 4580/4582/5591 +f 4581/4583/10083 4582/4584/98 4583/4585/98 +f 4584/4586/98 4585/4587/98 4586/4588/10084 +f 4584/4586/98 4587/4589/98 4588/4590/98 +f 4584/4586/98 4588/4590/98 4585/4587/98 +f 4585/4587/98 4589/4591/10085 4586/4588/10084 +f 4586/4588/10084 4589/4591/10085 4590/4592/10086 +f 4590/4592/10086 4589/4591/10085 4581/4583/10083 +f 4581/4583/10083 4589/4591/10085 4591/4593/98 +f 4581/4583/10083 4591/4593/98 4582/4584/98 +f 4592/4594/10087 4593/4595/10088 4512/4514/10089 +f 4594/4596/10090 4593/4595/10088 4592/4594/10087 +f 4595/4597/10091 4596/4598/10092 4597/4599/10093 +f 4598/4600/10094 4596/4598/10092 4595/4597/10091 +f 4598/4600/10094 4595/4597/10091 4599/4601/10095 +f 4599/4601/10095 4595/4597/10091 4600/4602/10096 +f 4601/4603/10097 4602/4604/10098 4603/4605/10099 +f 4603/4605/10099 4602/4604/10098 4600/4602/10096 +f 4600/4602/10096 4602/4604/10098 4599/4601/10095 +f 4604/4606/10100 4601/4603/10097 4603/4605/10099 +f 4605/4607/10101 4518/4520/10102 4593/4595/10103 +f 4605/4607/10101 4593/4595/10103 4594/4596/10104 +f 4606/4608/10105 4607/4609/10106 4573/4575/10107 +f 4608/4610/98 4609/4611/98 4606/4608/10105 +f 4606/4608/10105 4609/4611/98 4607/4609/10106 +f 4607/4609/10106 4610/4612/10108 4573/4575/10107 +f 4573/4575/10107 4610/4612/10108 4576/4578/10109 +f 4576/4578/10109 4610/4612/10108 4611/4613/10110 +f 4576/4578/10109 4611/4613/10110 4612/4614/10111 +f 4612/4614/10111 4611/4613/10110 4613/4615/98 +f 4614/4616/10087 4615/4617/10088 4521/4523/10089 +f 4616/4618/10090 4615/4617/10088 4614/4616/10087 +f 4617/4619/10112 4618/4620/10113 4619/4621/10114 +f 4620/4622/528 4618/4620/10113 4617/4619/10112 +f 4620/4622/528 4617/4619/10112 4621/4623/10115 +f 4621/4623/10115 4617/4619/10112 4622/4624/10116 +f 4623/4625/528 4624/4626/10117 4625/4627/10118 +f 4625/4627/10118 4624/4626/10117 4622/4624/10116 +f 4622/4624/10116 4624/4626/10117 4621/4623/10115 +f 4626/4628/528 4623/4625/528 4625/4627/10118 +f 4527/4529/10119 4615/4617/10120 4616/4618/10121 +f 4527/4529/10119 4616/4618/10121 4627/4629/10122 +f 4595/4597/10123 4628/4630/10124 4600/4602/10125 +f 4629/4631/10126 4630/4632/10127 4595/4597/10123 +f 4595/4597/10123 4630/4632/10127 4628/4630/10124 +f 4628/4630/10124 4631/4633/10128 4600/4602/10125 +f 4600/4602/10125 4631/4633/10128 4603/4605/10129 +f 4603/4605/10129 4631/4633/10128 4632/4634/10130 +f 4603/4605/10129 4632/4634/10130 4633/4635/10131 +f 4633/4635/10131 4632/4634/10130 4634/4636/98 +f 4635/4637/10087 4636/4638/10088 4530/4532/10089 +f 4637/4639/10090 4636/4638/10088 4635/4637/10087 +f 4638/4640/10132 4639/4641/528 4640/4642/10133 +f 4638/4640/10132 4640/4642/10133 4641/4643/10134 +f 4638/4640/10132 4641/4643/10134 4642/4644/10135 +f 4642/4644/10135 4641/4643/10134 4643/4645/10136 +f 4644/4646/10097 4645/4647/10098 4646/4648/10137 +f 4646/4648/10137 4645/4647/10098 4643/4645/10136 +f 4643/4645/10136 4645/4647/10098 4642/4644/10135 +f 4647/4649/10100 4644/4646/10097 4646/4648/10137 +f 4536/4538/10119 4636/4638/10120 4637/4639/10121 +f 4536/4538/10119 4637/4639/10121 4648/4650/10122 +f 4649/4651/10138 4650/4652/10139 4622/4624/10140 +f 4622/4624/10141 4650/4652/10141 4651/4653/10141 +f 4649/4651/10138 4619/4621/10142 4652/4654/10143 +f 4649/4651/10138 4652/4654/10143 4650/4652/10139 +f 4650/4652/98 4653/4655/98 4651/4653/98 +f 4651/4653/98 4653/4655/98 4654/4656/98 +f 4651/4653/98 4654/4656/98 4655/4657/98 +f 4655/4657/98 4654/4656/98 4656/4658/98 +f 4657/4659/10087 4658/4660/10088 4539/4541/10089 +f 4659/4661/10090 4658/4660/10088 4657/4659/10087 +f 4660/4662/528 4661/4663/528 4662/4664/528 +f 4660/4662/528 4662/4664/528 4663/4665/528 +f 4660/4662/528 4663/4665/528 4664/4666/528 +f 4664/4666/528 4663/4665/528 4665/4667/528 +f 4666/4668/528 4667/4669/528 4665/4667/528 +f 4665/4667/528 4667/4669/528 4664/4666/528 +f 4668/4670/528 4666/4668/528 4665/4667/528 +f 4545/4547/10119 4658/4660/10120 4659/4661/10121 +f 4545/4547/10119 4659/4661/10121 4669/4671/10122 +f 4641/4643/10144 4670/4672/10145 4643/4645/10146 +f 4671/4673/10147 4672/4674/10148 4641/4643/10144 +f 4641/4643/10144 4672/4674/10148 4670/4672/10145 +f 4670/4672/10145 4673/4675/10149 4643/4645/10146 +f 4643/4645/10146 4673/4675/10149 4646/4648/10150 +f 4646/4648/10150 4673/4675/10149 4674/4676/10130 +f 4646/4648/10150 4674/4676/10130 4675/4677/10131 +f 4675/4677/10131 4674/4676/10130 4676/4678/98 +f 4677/4679/10087 4678/4680/10088 4548/4550/10089 +f 4679/4681/10090 4678/4680/10088 4677/4679/10087 +f 4680/4682/10132 4681/4683/528 4682/4684/10133 +f 4680/4682/10132 4682/4684/10133 4683/4685/10134 +f 4680/4682/10132 4683/4685/10134 4684/4686/10135 +f 4684/4686/10135 4683/4685/10134 4685/4687/10151 +f 4686/4688/10152 4687/4689/10153 4688/4690/10154 +f 4688/4690/10154 4687/4689/10153 4685/4687/10151 +f 4685/4687/10151 4687/4689/10153 4684/4686/10135 +f 4689/4691/10155 4686/4688/10152 4688/4690/10154 +f 4554/4556/10119 4678/4680/10120 4679/4681/10121 +f 4554/4556/10119 4679/4681/10121 4690/4692/10122 +f 4691/4693/98 4692/4694/98 4693/4695/98 +f 4691/4693/98 4694/4696/98 4695/4697/98 +f 4691/4693/98 4695/4697/98 4692/4694/98 +f 4692/4694/98 4696/4698/98 4693/4695/98 +f 4693/4695/98 4696/4698/98 4697/4699/98 +f 4697/4699/98 4696/4698/98 4698/4700/98 +f 4697/4699/98 4698/4700/98 4699/4701/98 +f 4699/4701/98 4698/4700/98 4700/4702/98 +f 4701/4703/10156 4702/4704/10157 4557/4559/10158 +f 4703/4705/10159 4702/4704/10157 4701/4703/10156 +f 4704/4706/10160 4705/4707/528 4706/4708/528 +f 4707/4709/10161 4705/4707/528 4704/4706/10160 +f 4707/4709/10161 4704/4706/10160 4708/4710/10162 +f 4707/4709/10161 4708/4710/10162 4709/4711/10163 +f 4710/4712/10164 4711/4713/10165 4712/4714/10166 +f 4712/4714/10166 4711/4713/10165 4708/4710/10162 +f 4708/4710/10162 4711/4713/10165 4709/4711/10163 +f 4713/4715/10167 4710/4712/10164 4712/4714/10166 +f 4714/4716/10101 4564/4566/10102 4702/4704/10103 +f 4714/4716/10101 4702/4704/10103 4703/4705/10104 +f 4688/4690/10168 4715/4717/10169 4689/4691/10170 +f 4683/4685/10144 4716/4718/10145 4685/4687/10171 +f 4717/4719/10147 4718/4720/10148 4683/4685/10144 +f 4683/4685/10144 4718/4720/10148 4716/4718/10145 +f 4716/4718/10145 4719/4721/10172 4685/4687/10171 +f 4685/4687/10171 4719/4721/10172 4688/4690/10168 +f 4688/4690/10168 4719/4721/10172 4720/4722/10173 +f 4688/4690/10168 4720/4722/10173 4715/4717/10169 +f 4574/4576/10174 4582/4584/10175 4591/4593/10176 +f 4574/4576/10174 4591/4593/10176 4575/4577/10177 +f 4575/4577/10178 4591/4593/10178 4589/4591/10178 +f 4575/4577/10179 4589/4591/10179 4572/4574/10179 +f 4572/4574/10180 4589/4591/10180 4585/4587/10180 +f 4572/4574/10181 4585/4587/10181 4571/4573/10181 +f 4571/4573/10182 4585/4587/10183 4588/4590/10184 +f 4571/4573/10182 4588/4590/10184 4569/4571/10185 +f 4601/4603/10186 4613/4615/10186 4611/4613/10186 +f 4601/4603/10187 4611/4613/10187 4602/4604/10187 +f 4602/4604/10188 4611/4613/10110 4610/4612/10108 +f 4602/4604/10098 4610/4612/10189 4599/4601/10095 +f 4599/4601/10190 4610/4612/10108 4607/4609/10106 +f 4599/4601/10095 4607/4609/10191 4598/4600/10094 +f 4598/4600/10192 4607/4609/10192 4609/4611/10192 +f 4598/4600/10193 4609/4611/10193 4596/4598/10193 +f 4623/4625/10186 4634/4636/10186 4632/4634/10186 +f 4623/4625/10187 4632/4634/10187 4624/4626/10187 +f 4624/4626/10188 4632/4634/10130 4631/4633/10128 +f 4624/4626/10189 4631/4633/10189 4621/4623/10189 +f 4621/4623/10190 4631/4633/10128 4628/4630/10124 +f 4621/4623/10191 4628/4630/10191 4620/4622/10191 +f 4620/4622/10192 4628/4630/10192 4630/4632/10192 +f 4620/4622/10193 4630/4632/10193 4618/4620/10193 +f 4644/4646/10186 4656/4658/10186 4654/4656/10186 +f 4644/4646/10187 4654/4656/10187 4645/4647/10187 +f 4645/4647/10188 4654/4656/10188 4653/4655/10188 +f 4645/4647/10098 4653/4655/10189 4642/4644/10135 +f 4642/4644/10190 4653/4655/10190 4650/4652/10190 +f 4642/4644/10135 4650/4652/10191 4638/4640/10132 +f 4638/4640/10192 4650/4652/10192 4652/4654/10192 +f 4638/4640/10193 4652/4654/10193 4639/4641/10193 +f 4666/4668/10186 4676/4678/10186 4674/4676/10186 +f 4666/4668/10194 4674/4676/10194 4667/4669/10194 +f 4667/4669/10195 4674/4676/10130 4673/4675/10149 +f 4667/4669/10189 4673/4675/10189 4664/4666/10189 +f 4664/4666/10190 4673/4675/10149 4670/4672/10145 +f 4664/4666/10191 4670/4672/10191 4660/4662/10191 +f 4660/4662/10192 4670/4672/10192 4672/4674/10192 +f 4660/4662/10193 4672/4674/10193 4661/4663/10193 +f 4686/4688/10186 4700/4702/10186 4698/4700/10186 +f 4686/4688/10187 4698/4700/10187 4687/4689/10187 +f 4687/4689/10188 4698/4700/10188 4696/4698/10188 +f 4687/4689/10153 4696/4698/10189 4684/4686/10135 +f 4684/4686/10190 4696/4698/10190 4692/4694/10190 +f 4684/4686/10135 4692/4694/10191 4680/4682/10132 +f 4680/4682/10192 4692/4694/10192 4695/4697/10192 +f 4680/4682/10193 4695/4697/10193 4681/4683/10193 +f 4710/4712/10186 4715/4717/10186 4720/4722/10186 +f 4710/4712/10187 4720/4722/10187 4711/4713/10187 +f 4711/4713/10188 4720/4722/10188 4719/4721/10188 +f 4711/4713/10165 4719/4721/10189 4709/4711/10163 +f 4709/4711/10190 4719/4721/10172 4716/4718/10145 +f 4709/4711/10163 4716/4718/10191 4707/4709/10161 +f 4707/4709/10192 4716/4718/10192 4718/4720/10192 +f 4707/4709/10193 4718/4720/10193 4705/4707/10193 +f 4567/4569/10196 4580/4582/10197 4579/4581/10198 +f 4567/4569/10196 4579/4581/10198 4566/4568/10199 +f 4721/4723/10200 4722/4724/10201 4723/4725/10202 +f 4723/4725/10202 4722/4724/10201 4724/4726/10203 +f 4725/4727/10204 4726/4728/10205 4727/4729/10206 +f 4727/4729/10206 4726/4728/10205 4728/4730/10207 +f 4729/4731/10208 4730/4732/10209 4731/4733/10210 +f 4731/4733/10210 4730/4732/10209 4732/4734/10211 +f 4731/4733/10210 4732/4734/10211 4733/4735/10212 +f 4733/4735/10212 4732/4734/10211 4734/4736/528 +f 4733/4735/10212 4734/4736/528 4735/4737/528 +f 4735/4737/528 4734/4736/528 4736/4738/528 +f 4729/4731/10208 4737/4739/528 4730/4732/10209 +f 4738/4740/98 4739/4741/98 4740/4742/98 +f 4741/4743/10213 4742/4744/10214 4587/4589/10215 +f 4739/4741/98 4743/4745/98 4744/4746/10216 +f 4744/4746/10216 4743/4745/98 4745/4747/10217 +f 4744/4746/10216 4745/4747/10217 4741/4743/10213 +f 4741/4743/10213 4745/4747/10217 4746/4748/10218 +f 4741/4743/10213 4746/4748/10218 4742/4744/10214 +f 4739/4741/98 4738/4740/98 4743/4745/98 +f 4737/4739/10219 4742/4744/10220 4746/4748/10221 +f 4737/4739/10219 4746/4748/10221 4730/4732/10222 +f 4730/4732/10222 4746/4748/10221 4745/4747/10223 +f 4730/4732/10222 4745/4747/10223 4732/4734/10224 +f 4732/4734/10224 4745/4747/10223 4743/4745/10225 +f 4732/4734/10224 4743/4745/10225 4734/4736/10226 +f 4734/4736/10227 4743/4745/10228 4738/4740/10229 +f 4734/4736/10227 4738/4740/10229 4736/4738/10230 +f 4747/4749/10231 4748/4750/528 4749/4751/10232 +f 4750/4752/10233 4751/4753/10234 4752/4754/10235 +f 4752/4754/10235 4751/4753/10234 4753/4755/10236 +f 4752/4754/10235 4753/4755/10236 4754/4756/10237 +f 4754/4756/10237 4753/4755/10236 4755/4757/10238 +f 4754/4756/10237 4755/4757/10238 4749/4751/10232 +f 4749/4751/10232 4755/4757/10238 4756/4758/10239 +f 4749/4751/10232 4756/4758/10239 4747/4749/10231 +f 4750/4752/10233 4757/4759/10240 4751/4753/10234 +f 4758/4760/10241 4759/4761/10242 4760/4762/98 +f 4759/4761/10242 4756/4758/10243 4755/4757/10244 +f 4759/4761/10242 4755/4757/10244 4761/4763/10245 +f 4761/4763/10245 4755/4757/10244 4753/4755/10246 +f 4761/4763/10245 4753/4755/10246 4731/4733/10247 +f 4731/4733/10247 4753/4755/10246 4751/4753/10248 +f 4731/4733/10247 4751/4753/10248 4762/4764/10249 +f 4762/4764/10249 4751/4753/10248 4763/4765/10250 +f 4759/4761/10242 4758/4760/10241 4756/4758/10243 +f 4757/4759/10251 4763/4765/10251 4751/4753/10251 +f 4756/4758/10252 4758/4760/10252 4747/4749/10252 +f 4764/4766/10253 4765/4767/10254 4766/4768/10255 +f 4766/4768/10256 4765/4767/10257 4767/4769/10258 +f 4766/4768/10256 4767/4769/10258 4768/4770/10259 +f 4768/4770/10259 4767/4769/10258 4769/4771/10260 +f 4768/4770/10259 4769/4771/10260 4770/4772/10261 +f 4768/4770/10259 4770/4772/10261 4771/4773/10262 +f 4771/4773/10262 4770/4772/10261 4772/4774/10263 +f 4773/4775/10264 4774/4776/10265 4764/4766/10253 +f 4764/4766/10253 4774/4776/10265 4765/4767/10254 +f 4775/4777/10266 4776/4778/10267 4777/4779/98 +f 4776/4778/10267 4770/4772/10268 4769/4771/10269 +f 4776/4778/10267 4769/4771/10269 4754/4756/10270 +f 4754/4756/10270 4769/4771/10269 4767/4769/10271 +f 4754/4756/10270 4767/4769/10271 4752/4754/10272 +f 4752/4754/10272 4767/4769/10271 4765/4767/10273 +f 4752/4754/10272 4765/4767/10273 4778/4780/10274 +f 4778/4780/10274 4765/4767/10273 4779/4781/10275 +f 4776/4778/10267 4775/4777/10266 4770/4772/10268 +f 4774/4776/10276 4779/4781/10276 4765/4767/10276 +f 4770/4772/10277 4775/4777/10277 4772/4774/10277 +f 4780/4782/10278 4781/4783/10279 4782/4784/10280 +f 4783/4785/10281 4784/4786/10282 4785/4787/10283 +f 4785/4787/10283 4784/4786/10282 4786/4788/10284 +f 4785/4787/10283 4786/4788/10284 4787/4789/10285 +f 4787/4789/10285 4786/4788/10284 4788/4790/10286 +f 4787/4789/10285 4788/4790/10286 4782/4784/10280 +f 4782/4784/10280 4788/4790/10286 4789/4791/10287 +f 4782/4784/10280 4789/4791/10287 4780/4782/10278 +f 4790/4792/10288 4791/4793/10289 4783/4785/10281 +f 4783/4785/10281 4791/4793/10289 4784/4786/10282 +f 4792/4794/10266 4793/4795/10290 4794/4796/98 +f 4793/4795/10290 4789/4791/10268 4788/4790/10291 +f 4793/4795/10290 4788/4790/10291 4795/4797/10292 +f 4795/4797/10292 4788/4790/10291 4786/4788/10293 +f 4795/4797/10292 4786/4788/10293 4764/4766/10294 +f 4764/4766/10294 4786/4788/10293 4784/4786/10295 +f 4764/4766/10294 4784/4786/10295 4796/4798/10296 +f 4796/4798/10296 4784/4786/10295 4797/4799/10275 +f 4793/4795/10290 4792/4794/10266 4789/4791/10268 +f 4791/4793/10276 4797/4799/10276 4784/4786/10276 +f 4789/4791/10277 4792/4794/10277 4780/4782/10277 +f 4798/4800/10231 4799/4801/528 4800/4802/10297 +f 4801/4803/10298 4802/4804/10299 4803/4805/10300 +f 4803/4805/10301 4802/4804/10302 4804/4806/10303 +f 4803/4805/10301 4804/4806/10303 4805/4807/10304 +f 4803/4805/10301 4805/4807/10304 4800/4802/10297 +f 4800/4802/10297 4805/4807/10304 4806/4808/10239 +f 4800/4802/10297 4806/4808/10239 4798/4800/10231 +f 4807/4809/10264 4808/4810/10265 4801/4803/10298 +f 4801/4803/10298 4808/4810/10265 4802/4804/10299 +f 4809/4811/10305 4782/4784/10306 4810/4812/10307 +f 4782/4784/10306 4806/4808/10308 4805/4807/10309 +f 4782/4784/10306 4805/4807/10309 4787/4789/10310 +f 4787/4789/10310 4805/4807/10309 4804/4806/10311 +f 4787/4789/10310 4804/4806/10311 4785/4787/10312 +f 4785/4787/10312 4804/4806/10311 4783/4785/10313 +f 4783/4785/10313 4804/4806/10311 4802/4804/10314 +f 4783/4785/10313 4802/4804/10314 4811/4813/10315 +f 4811/4813/10315 4802/4804/10314 4812/4814/10275 +f 4782/4784/10306 4809/4811/10305 4806/4808/10308 +f 4808/4810/10276 4812/4814/10276 4802/4804/10276 +f 4806/4808/10316 4809/4811/10316 4798/4800/10316 +f 4813/4815/10317 4814/4816/528 4815/4817/10318 +f 4816/4818/10233 4817/4819/10319 4818/4820/10320 +f 4818/4820/10320 4817/4819/10319 4819/4821/10236 +f 4818/4820/10320 4819/4821/10236 4820/4822/10237 +f 4820/4822/10237 4819/4821/10236 4821/4823/10238 +f 4820/4822/10237 4821/4823/10238 4815/4817/10318 +f 4815/4817/10318 4821/4823/10238 4822/4824/10239 +f 4815/4817/10318 4822/4824/10239 4813/4815/10317 +f 4816/4818/10233 4823/4825/10240 4817/4819/10319 +f 4824/4826/10266 4825/4827/10290 4826/4828/98 +f 4825/4827/10290 4822/4824/10268 4821/4823/10321 +f 4825/4827/10290 4821/4823/10321 4827/4829/10292 +f 4827/4829/10292 4821/4823/10321 4819/4821/10293 +f 4827/4829/10292 4819/4821/10293 4801/4803/10294 +f 4801/4803/10294 4819/4821/10293 4817/4819/10295 +f 4801/4803/10294 4817/4819/10295 4828/4830/10296 +f 4828/4830/10296 4817/4819/10295 4829/4831/10275 +f 4825/4827/10290 4824/4826/10266 4822/4824/10268 +f 4823/4825/10276 4829/4831/10276 4817/4819/10276 +f 4822/4824/10277 4824/4826/10277 4813/4815/10277 +f 4830/4832/10322 4831/4833/528 4832/4834/10323 +f 4833/4835/10324 4834/4836/10325 4835/4837/10326 +f 4833/4835/10324 4835/4837/10326 4836/4838/10327 +f 4836/4838/10327 4835/4837/10326 4837/4839/10328 +f 4836/4838/10327 4837/4839/10328 4832/4834/10323 +f 4832/4834/10323 4837/4839/10328 4838/4840/10329 +f 4832/4834/10323 4838/4840/10329 4830/4832/10322 +f 4839/4841/528 4840/4842/10330 4833/4835/10324 +f 4833/4835/10324 4840/4842/10330 4834/4836/10325 +f 4841/4843/10266 4842/4844/10331 4843/4845/98 +f 4842/4844/10331 4838/4840/10268 4837/4839/10269 +f 4842/4844/10331 4837/4839/10269 4820/4822/10270 +f 4820/4822/10270 4837/4839/10269 4835/4837/10271 +f 4820/4822/10270 4835/4837/10271 4818/4820/10332 +f 4818/4820/10332 4835/4837/10271 4834/4836/10273 +f 4818/4820/10332 4834/4836/10273 4844/4846/10274 +f 4844/4846/10274 4834/4836/10273 4845/4847/10275 +f 4842/4844/10331 4841/4843/10266 4838/4840/10268 +f 4840/4842/10333 4845/4847/10333 4834/4836/10333 +f 4838/4840/10277 4841/4843/10277 4830/4832/10277 +f 4722/4724/10201 4721/4723/10200 4846/4848/10334 +f 4722/4724/10201 4846/4848/10334 4847/4849/10335 +f 4847/4849/10335 4846/4848/10334 4848/4850/10336 +f 4848/4850/10336 4846/4848/10334 4849/4851/10337 +f 4848/4850/10336 4849/4851/10337 4850/4852/10338 +f 4850/4852/10338 4849/4851/10337 4851/4853/10339 +f 4850/4852/10338 4851/4853/10339 4852/4854/10340 +f 4833/4835/10341 4853/4855/10341 4839/4841/10341 +f 4839/4841/10342 4853/4855/10342 4854/4856/10342 +f 4839/4841/10343 4854/4856/10344 4706/4708/10345 +f 4706/4708/10345 4854/4856/10344 4704/4706/10346 +f 4833/4835/10324 4836/4838/10327 4853/4855/10347 +f 4832/4834/10348 4855/4857/10348 4836/4838/10348 +f 4855/4857/10349 4832/4834/10349 4856/4858/10349 +f 4856/4858/10350 4832/4834/10351 4831/4833/10352 +f 4856/4858/10350 4831/4833/10352 4857/4859/10353 +f 4857/4859/10354 4858/4860/10354 4856/4858/10354 +f 4859/4861/10355 4860/4862/10356 4861/4863/10357 +f 4862/4864/10358 4860/4862/10356 4859/4861/10355 +f 4860/4862/10359 4862/4864/10359 4863/4865/10359 +f 4863/4865/10360 4701/4703/10361 4864/4866/10362 +f 4557/4559/10363 4865/4867/10363 4864/4866/10363 +f 4557/4559/10364 4864/4866/10364 4701/4703/10364 +f 4865/4867/10365 4557/4559/10365 4556/4558/10365 +f 4560/4562/10366 4866/4868/10367 4556/4558/10368 +f 4556/4558/10368 4866/4868/10367 4865/4867/10369 +f 4713/4715/10370 4866/4868/10367 4560/4562/10366 +f 4704/4706/10371 4854/4856/10371 4708/4710/10371 +f 4712/4714/10372 4866/4868/10372 4713/4715/10372 +f 4844/4846/10373 4717/4719/10374 4682/4684/10375 +f 4682/4684/10375 4816/4818/10376 4844/4846/10373 +f 4844/4846/10373 4816/4818/10376 4818/4820/10377 +f 4820/4822/10378 4815/4817/10378 4842/4844/10378 +f 4842/4844/10379 4815/4817/10380 4814/4816/10381 +f 4842/4844/10379 4814/4816/10381 4843/4845/10382 +f 4843/4845/10382 4814/4816/10381 4867/4869/10383 +f 4868/4870/10384 4869/4871/10385 4870/4872/10386 +f 4869/4871/10385 4871/4873/10387 4870/4872/10386 +f 4870/4872/10386 4871/4873/10387 4872/4874/10388 +f 4872/4874/10389 4871/4873/10389 4873/4875/10389 +f 4872/4874/10390 4873/4875/10390 4714/4716/10390 +f 4714/4716/10391 4873/4875/10392 4677/4679/10393 +f 4714/4716/10391 4677/4679/10393 4548/4550/10394 +f 4714/4716/10391 4548/4550/10394 4564/4566/10395 +f 4564/4566/10395 4548/4550/10394 4547/4549/10396 +f 4564/4566/10397 4547/4549/10397 4563/4565/10397 +f 4563/4565/10398 4547/4549/10398 4689/4691/10398 +f 4689/4691/10399 4547/4549/10400 4551/4553/10401 +f 4682/4684/10375 4717/4719/10374 4683/4685/10402 +f 4828/4830/10403 4694/4696/10404 4662/4664/10405 +f 4662/4664/10405 4807/4809/10406 4828/4830/10403 +f 4828/4830/10403 4807/4809/10406 4801/4803/10407 +f 4801/4803/10298 4803/4805/10300 4827/4829/10408 +f 4827/4829/10409 4803/4805/10409 4800/4802/10409 +f 4827/4829/10410 4800/4802/10410 4825/4827/10410 +f 4825/4827/10411 4800/4802/10412 4799/4801/10413 +f 4825/4827/10411 4799/4801/10413 4826/4828/10414 +f 4826/4828/10414 4799/4801/10413 4874/4876/10415 +f 4875/4877/10416 4876/4878/10417 4877/4879/10418 +f 4877/4879/10418 4878/4880/10419 4875/4877/10416 +f 4875/4877/10416 4878/4880/10419 4879/4881/10420 +f 4879/4881/10389 4878/4880/10389 4880/4882/10389 +f 4879/4881/10421 4880/4882/10422 4690/4692/10423 +f 4690/4692/10423 4880/4882/10422 4657/4659/10424 +f 4690/4692/10423 4657/4659/10424 4554/4556/10425 +f 4554/4556/10426 4657/4659/10427 4539/4541/10428 +f 4554/4556/10426 4539/4541/10428 4538/4540/10429 +f 4555/4557/10430 4538/4540/10431 4542/4544/10432 +f 4662/4664/10405 4694/4696/10404 4691/4693/10433 +f 4662/4664/10434 4691/4693/10434 4663/4665/10434 +f 4663/4665/10435 4691/4693/10435 4693/4695/10435 +f 4663/4665/10436 4693/4695/10436 4665/4667/10436 +f 4665/4667/10437 4693/4695/10437 4697/4699/10437 +f 4665/4667/10438 4697/4699/10439 4699/4701/10440 +f 4665/4667/10438 4699/4701/10440 4668/4670/10441 +f 4668/4670/10441 4699/4701/10440 4555/4557/10430 +f 4668/4670/10441 4555/4557/10430 4542/4544/10432 +f 4811/4813/10442 4671/4673/10443 4640/4642/10444 +f 4640/4642/10444 4790/4792/10445 4811/4813/10442 +f 4811/4813/10442 4790/4792/10445 4783/4785/10446 +f 4810/4812/10447 4782/4784/10448 4781/4783/10449 +f 4810/4812/10447 4781/4783/10449 4881/4883/10450 +f 4881/4883/10450 4781/4783/10449 4882/4884/10451 +f 4883/4885/10452 4884/4886/10385 4885/4887/10386 +f 4884/4886/10385 4886/4888/10453 4885/4887/10386 +f 4885/4887/10386 4886/4888/10453 4887/4889/10454 +f 4887/4889/10455 4886/4888/10455 4888/4890/10455 +f 4887/4889/10456 4888/4890/10457 4669/4671/10458 +f 4669/4671/10458 4888/4890/10457 4635/4637/10424 +f 4669/4671/10458 4635/4637/10424 4545/4547/10425 +f 4545/4547/10426 4635/4637/10427 4530/4532/10428 +f 4545/4547/10426 4530/4532/10428 4529/4531/10429 +f 4546/4548/10459 4529/4531/10431 4533/4535/10432 +f 4640/4642/10444 4671/4673/10443 4641/4643/10402 +f 4646/4648/10460 4675/4677/10461 4647/4649/10462 +f 4647/4649/10462 4675/4677/10461 4546/4548/10459 +f 4647/4649/10462 4546/4548/10459 4533/4535/10432 +f 4651/4653/10463 4625/4627/10463 4622/4624/10463 +f 4622/4624/10464 4617/4619/10464 4649/4651/10464 +f 4649/4651/10465 4617/4619/10465 4619/4621/10465 +f 4619/4621/10466 4773/4775/10467 4796/4798/10468 +f 4796/4798/10468 4773/4775/10467 4764/4766/10407 +f 4764/4766/10253 4766/4768/10255 4795/4797/10469 +f 4795/4797/10470 4766/4768/10470 4768/4770/10470 +f 4795/4797/10471 4768/4770/10471 4793/4795/10471 +f 4793/4795/10472 4768/4770/10472 4771/4773/10472 +f 4793/4795/10473 4771/4773/10474 4794/4796/10475 +f 4794/4796/10475 4771/4773/10474 4889/4891/10476 +f 4794/4796/10475 4889/4891/10476 4890/4892/10477 +f 4891/4893/10384 4892/4894/10385 4893/4895/10386 +f 4892/4894/10385 4894/4896/10387 4893/4895/10386 +f 4893/4895/10386 4894/4896/10387 4895/4897/10388 +f 4895/4897/10389 4894/4896/10389 4896/4898/10389 +f 4895/4897/10421 4896/4898/10422 4648/4650/10423 +f 4648/4650/10423 4896/4898/10422 4614/4616/10424 +f 4648/4650/10423 4614/4616/10424 4536/4538/10425 +f 4536/4538/10426 4614/4616/10427 4521/4523/10428 +f 4536/4538/10426 4521/4523/10428 4520/4522/10429 +f 4537/4539/10459 4520/4522/10431 4524/4526/10432 +f 4537/4539/10459 4524/4526/10432 4626/4628/10478 +f 4537/4539/10459 4626/4628/10478 4655/4657/10479 +f 4655/4657/10479 4626/4628/10478 4625/4627/10480 +f 4655/4657/10481 4625/4627/10481 4651/4653/10481 +f 4778/4780/10482 4629/4631/10483 4597/4599/10484 +f 4597/4599/10484 4750/4752/10485 4778/4780/10482 +f 4778/4780/10482 4750/4752/10485 4752/4754/10377 +f 4754/4756/10486 4749/4751/10486 4776/4778/10486 +f 4776/4778/10487 4749/4751/10488 4748/4750/10413 +f 4776/4778/10487 4748/4750/10413 4777/4779/10414 +f 4777/4779/10414 4748/4750/10413 4897/4899/10415 +f 4898/4900/10384 4899/4901/10385 4900/4902/10386 +f 4899/4901/10385 4901/4903/10387 4900/4902/10386 +f 4900/4902/10386 4901/4903/10387 4902/4904/10388 +f 4902/4904/10389 4901/4903/10389 4903/4905/10389 +f 4902/4904/10421 4903/4905/10489 4627/4629/10423 +f 4627/4629/10423 4903/4905/10489 4592/4594/10490 +f 4627/4629/10423 4592/4594/10490 4527/4529/10425 +f 4527/4529/10426 4592/4594/10427 4512/4514/10428 +f 4527/4529/10426 4512/4514/10428 4511/4513/10429 +f 4528/4530/10459 4511/4513/10431 4515/4517/10432 +f 4597/4599/10484 4629/4631/10483 4595/4597/10491 +f 4603/4605/10460 4633/4635/10461 4604/4606/10462 +f 4604/4606/10462 4633/4635/10461 4528/4530/10459 +f 4604/4606/10462 4528/4530/10459 4515/4517/10432 +f 4570/4572/10492 4729/4731/10493 4762/4764/10494 +f 4762/4764/10494 4729/4731/10493 4731/4733/10495 +f 4761/4763/10245 4731/4733/10247 4733/4735/10496 +f 4761/4763/10497 4733/4735/10497 4759/4761/10497 +f 4759/4761/10498 4733/4735/10498 4735/4737/10498 +f 4759/4761/10499 4735/4737/10500 4760/4762/10501 +f 4760/4762/10501 4735/4737/10500 4904/4906/10502 +f 4904/4906/10502 4735/4737/10500 4905/4907/10503 +f 4904/4906/10502 4905/4907/10503 4906/4908/10504 +f 4907/4909/10452 4908/4910/10505 4909/4911/10386 +f 4908/4910/10505 4910/4912/10506 4909/4911/10386 +f 4909/4911/10386 4910/4912/10506 4911/4913/10388 +f 4911/4913/10389 4910/4912/10389 4912/4914/10389 +f 4911/4913/10390 4912/4914/10390 4605/4607/10390 +f 4605/4607/10391 4912/4914/10507 4565/4567/10508 +f 4605/4607/10391 4565/4567/10508 4503/4505/10509 +f 4605/4607/10391 4503/4505/10509 4518/4520/10510 +f 4518/4520/10510 4503/4505/10509 4502/4504/10511 +f 4502/4504/10512 4505/4507/10513 4519/4521/10514 +f 4519/4521/10514 4505/4507/10513 4577/4579/10515 +f 4570/4572/10516 4762/4764/10517 4608/4610/10518 +f 4570/4572/10516 4608/4610/10518 4568/4570/10519 +f 4568/4570/10520 4608/4610/10520 4606/4608/10520 +f 4568/4570/10521 4606/4608/10521 4573/4575/10521 +f 4576/4578/10522 4612/4614/10523 4577/4579/10524 +f 4577/4579/10524 4612/4614/10523 4519/4521/10525 +f 4913/4915/10526 4914/4916/10527 4915/4917/10528 +f 4913/4915/10526 4915/4917/10528 4916/4918/10529 +f 4916/4918/10529 4915/4917/10528 4917/4919/10530 +f 4917/4919/10530 4915/4917/10528 4918/4920/10531 +f 4917/4919/10530 4918/4920/10531 4919/4921/10532 +f 4919/4921/10532 4918/4920/10531 4920/4922/10533 +f 4919/4921/10532 4920/4922/10533 4921/4923/10534 +f 4919/4921/10532 4921/4923/10534 4922/4924/10535 +f 4923/4925/10536 4924/4926/10537 4925/4927/10538 +f 4925/4927/10538 4924/4926/10537 4926/4928/10539 +f 4927/4929/10540 4928/4930/10541 4929/4931/10542 +f 4927/4929/10540 4929/4931/10542 4930/4932/10543 +f 4846/4848/10544 4721/4723/10545 4712/4714/10546 +f 4721/4723/10545 4866/4868/10547 4712/4714/10546 +f 4855/4857/10548 4921/4923/10549 4920/4922/10550 +f 4855/4857/10548 4856/4858/10551 4921/4923/10549 +f 4721/4723/10545 4723/4725/10552 4866/4868/10547 +f 4931/4933/10553 4866/4868/10547 4723/4725/10552 +f 4856/4858/10551 4932/4934/10554 4921/4923/10549 +f 4856/4858/10551 4933/4935/10555 4932/4934/10554 +f 4931/4933/10553 4725/4727/10556 4866/4868/10547 +f 4866/4868/10547 4725/4727/10556 4865/4867/10557 +f 4856/4858/10551 4934/4936/10558 4933/4935/10555 +f 4856/4858/10551 4858/4860/10559 4934/4936/10558 +f 4858/4860/10559 4935/4937/10560 4934/4936/10558 +f 4845/4847/10561 4840/4842/10562 4844/4846/10563 +f 4844/4846/10563 4840/4842/10562 4839/4841/10564 +f 4844/4846/10373 4839/4841/10343 4717/4719/10374 +f 4717/4719/10374 4839/4841/10343 4706/4708/10345 +f 4717/4719/10565 4706/4708/10566 4718/4720/10567 +f 4718/4720/10567 4706/4708/10566 4705/4707/10568 +f 4829/4831/10561 4823/4825/10569 4828/4830/10570 +f 4828/4830/10570 4823/4825/10569 4816/4818/10571 +f 4828/4830/10572 4816/4818/10376 4694/4696/10573 +f 4694/4696/10573 4816/4818/10376 4682/4684/10375 +f 4694/4696/10574 4682/4684/10575 4695/4697/10576 +f 4695/4697/10576 4682/4684/10575 4681/4683/10577 +f 4812/4814/10561 4808/4810/10578 4811/4813/10579 +f 4811/4813/10579 4808/4810/10578 4807/4809/10580 +f 4811/4813/10442 4807/4809/10406 4671/4673/10443 +f 4671/4673/10443 4807/4809/10406 4662/4664/10405 +f 4671/4673/10581 4662/4664/10582 4672/4674/10583 +f 4672/4674/10583 4662/4664/10582 4661/4663/10577 +f 4797/4799/10561 4791/4793/10578 4796/4798/10579 +f 4796/4798/10579 4791/4793/10578 4790/4792/10580 +f 4796/4798/10468 4790/4792/10445 4619/4621/10466 +f 4619/4621/10466 4790/4792/10445 4640/4642/10444 +f 4619/4621/10584 4640/4642/10585 4652/4654/10586 +f 4652/4654/10586 4640/4642/10585 4639/4641/10577 +f 4779/4781/10561 4774/4776/10578 4778/4780/10579 +f 4778/4780/10579 4774/4776/10578 4773/4775/10580 +f 4778/4780/10482 4773/4775/10467 4629/4631/10483 +f 4629/4631/10483 4773/4775/10467 4619/4621/10466 +f 4629/4631/10587 4619/4621/10588 4630/4632/10589 +f 4630/4632/10589 4619/4621/10588 4618/4620/10590 +f 4763/4765/10591 4757/4759/10592 4750/4752/10593 +f 4763/4765/10591 4750/4752/10593 4762/4764/10594 +f 4762/4764/10595 4750/4752/10485 4597/4599/10484 +f 4762/4764/10517 4597/4599/10596 4608/4610/10518 +f 4608/4610/10597 4597/4599/10598 4609/4611/10599 +f 4609/4611/10599 4597/4599/10598 4596/4598/10600 +f 4742/4744/10601 4737/4739/10601 4729/4731/10601 +f 4742/4744/10602 4729/4731/10602 4587/4589/10602 +f 4587/4589/10603 4729/4731/10493 4570/4572/10492 +f 4587/4589/10604 4570/4572/10605 4588/4590/10606 +f 4588/4590/10606 4570/4572/10605 4569/4571/10607 +f 4715/4717/10608 4710/4712/10609 4689/4691/10610 +f 4689/4691/10610 4710/4712/10609 4713/4715/10611 +f 4689/4691/10612 4713/4715/10612 4560/4562/10612 +f 4689/4691/10613 4560/4562/10613 4563/4565/10613 +f 4563/4565/10614 4560/4562/10615 4562/4564/10616 +f 4562/4564/10616 4560/4562/10615 4559/4561/10617 +f 4700/4702/10618 4686/4688/10619 4699/4701/10620 +f 4699/4701/10620 4686/4688/10619 4689/4691/10621 +f 4699/4701/10440 4689/4691/10399 4555/4557/10430 +f 4555/4557/10430 4689/4691/10399 4551/4553/10401 +f 4555/4557/10622 4551/4553/10623 4553/4555/10624 +f 4553/4555/10624 4551/4553/10623 4550/4552/10625 +f 4676/4678/10618 4666/4668/10626 4675/4677/10627 +f 4675/4677/10627 4666/4668/10626 4668/4670/10628 +f 4675/4677/10461 4668/4670/10441 4546/4548/10459 +f 4546/4548/10459 4668/4670/10441 4542/4544/10432 +f 4546/4548/10622 4542/4544/10623 4544/4546/10624 +f 4544/4546/10624 4542/4544/10623 4541/4543/10625 +f 4656/4658/10618 4644/4646/10626 4655/4657/10627 +f 4655/4657/10627 4644/4646/10626 4647/4649/10628 +f 4655/4657/10479 4647/4649/10462 4537/4539/10459 +f 4537/4539/10459 4647/4649/10462 4533/4535/10432 +f 4537/4539/10622 4533/4535/10623 4535/4537/10624 +f 4535/4537/10624 4533/4535/10623 4532/4534/10625 +f 4634/4636/10618 4623/4625/10626 4633/4635/10627 +f 4633/4635/10627 4623/4625/10626 4626/4628/10628 +f 4633/4635/10461 4626/4628/10478 4528/4530/10459 +f 4528/4530/10459 4626/4628/10478 4524/4526/10432 +f 4528/4530/10622 4524/4526/10623 4526/4528/10624 +f 4526/4528/10624 4524/4526/10623 4523/4525/10625 +f 4613/4615/10618 4601/4603/10626 4612/4614/10627 +f 4612/4614/10627 4601/4603/10626 4604/4606/10628 +f 4612/4614/10523 4604/4606/10462 4519/4521/10525 +f 4519/4521/10525 4604/4606/10462 4515/4517/10432 +f 4519/4521/10622 4515/4517/10623 4517/4519/10624 +f 4517/4519/10624 4515/4517/10623 4514/4516/10625 +f 4582/4584/10629 4574/4576/10630 4583/4585/10631 +f 4583/4585/10631 4574/4576/10630 4577/4579/10632 +f 4583/4585/10633 4577/4579/10515 4509/4511/10634 +f 4509/4511/10634 4577/4579/10515 4505/4507/10513 +f 4509/4511/10635 4505/4507/10636 4507/4509/10637 +f 4507/4509/10637 4505/4507/10636 4506/4508/10638 +f 4564/4566/10639 4558/4560/10639 4557/4559/10639 +f 4564/4566/10640 4557/4559/10640 4702/4704/10640 +f 4554/4556/10641 4549/4551/10641 4548/4550/10641 +f 4554/4556/10642 4548/4550/10642 4678/4680/10642 +f 4545/4547/10641 4540/4542/10641 4539/4541/10641 +f 4545/4547/10642 4539/4541/10642 4658/4660/10642 +f 4536/4538/10641 4531/4533/10641 4530/4532/10641 +f 4536/4538/10642 4530/4532/10642 4636/4638/10642 +f 4527/4529/10641 4522/4524/10641 4521/4523/10641 +f 4527/4529/10642 4521/4523/10642 4615/4617/10642 +f 4518/4520/10643 4513/4515/10643 4512/4514/10643 +f 4518/4520/10644 4512/4514/10644 4593/4595/10644 +f 4508/4510/10645 4504/4506/10646 4510/4512/10647 +f 4510/4512/10647 4504/4506/10646 4503/4505/10648 +f 4510/4512/10649 4503/4505/10650 4579/4581/10651 +f 4579/4581/10651 4503/4505/10650 4566/4568/10652 +f 4928/4930/10653 4927/4929/10654 4913/4915/10526 +f 4913/4915/10526 4927/4929/10654 4914/4916/10527 +f 4852/4854/10340 4851/4853/10339 4929/4931/10655 +f 4929/4931/10655 4851/4853/10339 4930/4932/10656 +f 4931/4933/10657 4936/4938/10658 4725/4727/10204 +f 4725/4727/10204 4936/4938/10658 4726/4728/10205 +f 4723/4725/10202 4724/4726/10203 4931/4933/10659 +f 4931/4933/10659 4724/4726/10203 4936/4938/10660 +f 4727/4729/10661 4728/4730/10662 4926/4928/10539 +f 4727/4729/10661 4926/4928/10539 4924/4926/10663 +f 4937/4939/10664 4938/4940/10665 4939/4941/10666 +f 4940/4942/10667 4937/4939/10664 4939/4941/10666 +f 4938/4940/10665 4937/4939/10664 4941/4943/10668 +f 4942/4944/10669 4943/4945/10670 4944/4946/10671 +f 4945/4947/10672 4942/4944/10669 4922/4924/10673 +f 4945/4947/10672 4943/4945/10670 4942/4944/10669 +f 4858/4860/10559 4946/4948/10674 4935/4937/10560 +f 4946/4948/10674 4947/4949/10675 4935/4937/10560 +f 4727/4729/10676 4924/4926/10677 4865/4867/10557 +f 4924/4926/10677 4864/4866/10678 4865/4867/10557 +f 4924/4926/10677 4923/4925/10679 4864/4866/10678 +f 4946/4948/10674 4948/4950/10680 4947/4949/10675 +f 4923/4925/10679 4949/4951/10681 4864/4866/10678 +f 4946/4948/10674 4861/4863/10682 4948/4950/10680 +f 4865/4867/10557 4725/4727/10556 4727/4729/10676 +f 4861/4863/10682 4860/4862/10683 4950/4952/10684 +f 4950/4952/10684 4860/4862/10683 4951/4953/10685 +f 4860/4862/10683 4952/4954/10686 4951/4953/10685 +f 4949/4951/10681 4860/4862/10683 4863/4865/10687 +f 4860/4862/10683 4949/4951/10681 4952/4954/10686 +f 4949/4951/10681 4863/4865/10687 4864/4866/10678 +f 4854/4856/10688 4927/4929/10689 4930/4932/10690 +f 4851/4853/10691 4854/4856/10688 4930/4932/10690 +f 4854/4856/10688 4914/4916/10692 4927/4929/10689 +f 4854/4856/10688 4853/4855/10693 4914/4916/10692 +f 4851/4853/10691 4849/4851/10694 4854/4856/10688 +f 4853/4855/10693 4915/4917/10695 4914/4916/10692 +f 4854/4856/10688 4849/4851/10694 4708/4710/10696 +f 4948/4950/10680 4861/4863/10682 4950/4952/10684 +f 4853/4855/10693 4836/4838/10697 4915/4917/10695 +f 4836/4838/10697 4918/4920/10698 4915/4917/10695 +f 4849/4851/10694 4846/4848/10544 4708/4710/10696 +f 4846/4848/10544 4712/4714/10546 4708/4710/10696 +f 4836/4838/10697 4855/4857/10548 4918/4920/10698 +f 4855/4857/10548 4920/4922/10550 4918/4920/10698 +f 4910/4912/528 4953/4955/528 4912/4914/528 +f 4910/4912/528 4954/4956/528 4953/4955/528 +f 4955/4957/98 4956/4958/10699 4957/4959/98 +f 4955/4957/98 4578/4580/10699 4956/4958/10699 +f 4956/4958/10699 4958/4960/98 4957/4959/98 +f 4901/4903/10700 4959/4961/10701 4903/4905/10702 +f 4903/4905/10702 4959/4961/10701 4960/4962/10703 +f 4901/4903/10700 4961/4963/10704 4959/4961/10701 +f 4962/4964/10705 4909/4911/98 4911/4913/10706 +f 4911/4913/10706 4960/4962/10707 4959/4961/10708 +f 4911/4913/10706 4605/4607/10709 4960/4962/10707 +f 4959/4961/10708 4962/4964/10705 4911/4913/10706 +f 4894/4896/528 4963/4965/10710 4896/4898/10711 +f 4896/4898/10711 4963/4965/10710 4964/4966/10712 +f 4965/4967/10713 4900/4902/98 4902/4904/10714 +f 4902/4904/10714 4964/4966/10715 4965/4967/10713 +f 4902/4904/10714 4627/4629/10716 4964/4966/10715 +f 4886/4888/10700 4966/4968/10717 4888/4890/10718 +f 4888/4890/10718 4966/4968/10717 4967/4969/10719 +f 4886/4888/10700 4968/4970/10704 4966/4968/10717 +f 4969/4971/10705 4893/4895/98 4895/4897/10720 +f 4895/4897/10720 4967/4969/10721 4966/4968/10722 +f 4895/4897/10720 4648/4650/10723 4967/4969/10721 +f 4966/4968/10722 4969/4971/10705 4895/4897/10720 +f 4878/4880/528 4970/4972/10710 4880/4882/10711 +f 4880/4882/10711 4970/4972/10710 4971/4973/10712 +f 4972/4974/10713 4885/4887/98 4887/4889/10724 +f 4887/4889/10724 4971/4973/10715 4972/4974/10713 +f 4887/4889/10724 4669/4671/10716 4971/4973/10715 +f 4871/4873/528 4973/4975/10710 4873/4875/10711 +f 4873/4875/10711 4973/4975/10710 4974/4976/10712 +f 4975/4977/10725 4875/4877/98 4879/4881/10726 +f 4879/4881/10726 4974/4976/10715 4975/4977/10725 +f 4879/4881/10726 4690/4692/10716 4974/4976/10715 +f 4862/4864/10727 4976/4978/10728 4863/4865/10729 +f 4863/4865/10729 4976/4978/10728 4977/4979/10730 +f 4978/4980/98 4870/4872/98 4872/4874/98 +f 4872/4874/98 4714/4716/98 4979/4981/98 +f 4979/4981/98 4978/4980/98 4872/4874/98 +f 4954/4956/10731 4958/4960/10732 4956/4958/10733 +f 4954/4956/10731 4956/4958/10733 4953/4955/10734 +f 4961/4963/10735 4962/4964/10735 4959/4961/10735 +f 4963/4965/10736 4965/4967/10736 4964/4966/10736 +f 4968/4970/10735 4969/4971/10735 4966/4968/10735 +f 4970/4972/10736 4972/4974/10736 4971/4973/10736 +f 4973/4975/10736 4975/4977/10736 4974/4976/10736 +f 4976/4978/10737 4978/4980/10737 4979/4981/10737 +f 4976/4978/10738 4979/4981/10738 4977/4979/10738 +f 4980/4982/10739 4908/4910/10740 4907/4909/10741 +f 4906/4908/10742 4905/4907/10743 4981/4983/10744 +f 4981/4983/10744 4982/4984/10745 4906/4908/10742 +f 4906/4908/10742 4982/4984/10745 4983/4985/10746 +f 4983/4985/10746 4982/4984/10745 4984/4986/10747 +f 4983/4985/10746 4984/4986/10747 4907/4909/10741 +f 4907/4909/10741 4984/4986/10747 4985/4987/10748 +f 4907/4909/10741 4985/4987/10748 4980/4982/10739 +f 4986/4988/98 4987/4989/98 4988/4990/98 +f 4986/4988/98 4989/4991/98 4990/4992/98 +f 4990/4992/98 4989/4991/98 4991/4993/98 +f 4990/4992/98 4991/4993/98 4992/4994/10749 +f 4990/4992/98 4992/4994/10749 4993/4995/7914 +f 4993/4995/7914 4992/4994/10749 4994/4996/10750 +f 4986/4988/98 4988/4990/98 4989/4991/98 +f 4995/4997/10739 4899/4901/10740 4898/4900/10751 +f 4748/4750/10752 4996/4998/10753 4897/4899/10754 +f 4996/4998/10753 4997/4999/10755 4897/4899/10754 +f 4897/4899/10754 4997/4999/10755 4998/5000/10756 +f 4998/5000/10756 4997/4999/10755 4999/5001/10757 +f 4998/5000/10756 4999/5001/10757 4898/4900/10751 +f 4898/4900/10751 4999/5001/10757 5000/5002/10758 +f 4898/4900/10751 5000/5002/10758 4995/4997/10739 +f 5001/5003/10759 4904/4906/10760 4906/4908/10761 +f 4907/4909/10762 4909/4911/10763 5002/5004/10764 +f 4907/4909/10762 5003/5005/10765 4983/4985/10766 +f 4983/4985/10766 5003/5005/10765 5004/5006/10767 +f 4983/4985/10766 5004/5006/10767 4906/4908/10761 +f 4906/4908/10761 5004/5006/10767 5005/5007/10768 +f 4906/4908/10761 5005/5007/10768 5001/5003/10759 +f 4907/4909/10762 5002/5004/10764 5003/5005/10765 +f 5006/5008/10739 4892/4894/10740 4891/4893/10741 +f 4890/4892/10742 4889/4891/10743 5007/5009/10744 +f 5007/5009/10744 5008/5010/10769 4890/4892/10742 +f 4890/4892/10742 5008/5010/10769 5009/5011/10746 +f 5009/5011/10746 5008/5010/10769 5010/5012/10757 +f 5009/5011/10746 5010/5012/10757 4891/4893/10741 +f 4891/4893/10741 5010/5012/10757 5011/5013/10770 +f 4891/4893/10741 5011/5013/10770 5006/5008/10739 +f 5012/5014/10771 4777/4779/10772 4897/4899/10773 +f 4898/4900/10762 4900/4902/10763 5013/5015/10764 +f 4898/4900/10762 5014/5016/10765 4998/5000/10774 +f 4998/5000/10774 5014/5016/10765 5015/5017/10775 +f 4998/5000/10774 5015/5017/10775 4897/4899/10773 +f 4897/4899/10773 5015/5017/10775 5016/5018/10776 +f 4897/4899/10773 5016/5018/10776 5012/5014/10771 +f 4898/4900/10762 5013/5015/10764 5014/5016/10765 +f 5017/5019/10739 4884/4886/10740 4883/4885/10741 +f 4882/4884/10777 4781/4783/10778 5018/5020/10779 +f 5018/5020/10779 5019/5021/10755 4882/4884/10777 +f 4882/4884/10777 5019/5021/10755 5020/5022/10756 +f 5020/5022/10756 5019/5021/10755 5021/5023/10780 +f 5020/5022/10756 5021/5023/10780 4883/4885/10741 +f 4883/4885/10741 5021/5023/10780 5022/5024/10770 +f 4883/4885/10741 5022/5024/10770 5017/5019/10739 +f 5023/5025/10781 4794/4796/10782 4890/4892/10783 +f 4891/4893/10762 4893/4895/10763 5024/5026/10764 +f 4891/4893/10762 5025/5027/10765 5009/5011/10766 +f 5009/5011/10766 5025/5027/10765 5026/5028/10767 +f 5009/5011/10766 5026/5028/10767 4890/4892/10783 +f 4890/4892/10783 5026/5028/10767 5027/5029/10768 +f 4890/4892/10783 5027/5029/10768 5023/5025/10781 +f 4891/4893/10762 5024/5026/10764 5025/5027/10765 +f 5028/5030/10784 4877/4879/10785 4876/4878/10786 +f 4799/4801/10752 5029/5031/10753 4874/4876/10754 +f 5029/5031/10753 5030/5032/10755 4874/4876/10754 +f 4874/4876/10754 5030/5032/10755 5031/5033/10787 +f 5031/5033/10787 5030/5032/10755 5032/5034/10788 +f 5031/5033/10787 5032/5034/10788 4876/4878/10786 +f 4876/4878/10786 5032/5034/10788 5033/5035/10789 +f 4876/4878/10786 5033/5035/10789 5028/5030/10784 +f 5034/5036/10790 4881/4883/10791 4882/4884/10792 +f 4883/4885/10762 4885/4887/10763 5035/5037/10764 +f 4883/4885/10762 5036/5038/10765 5020/5022/10774 +f 5020/5022/10774 5036/5038/10765 5037/5039/10775 +f 5020/5022/10774 5037/5039/10775 4882/4884/10792 +f 4882/4884/10792 5037/5039/10775 5038/5040/10776 +f 4882/4884/10792 5038/5040/10776 5034/5036/10790 +f 4883/4885/10762 5035/5037/10764 5036/5038/10765 +f 5039/5041/10739 4869/4871/10740 4868/4870/10741 +f 4867/4869/10777 4814/4816/10778 5040/5042/10779 +f 5040/5042/10779 5041/5043/10755 4867/4869/10777 +f 4867/4869/10777 5041/5043/10755 5042/5044/10756 +f 5042/5044/10756 5041/5043/10755 5043/5045/10780 +f 5042/5044/10756 5043/5045/10780 4868/4870/10741 +f 4868/4870/10741 5043/5045/10780 5044/5046/10770 +f 4868/4870/10741 5044/5046/10770 5039/5041/10739 +f 5045/5047/10771 4826/4828/10772 4874/4876/10793 +f 4875/4877/10794 5046/5048/10795 4876/4878/10796 +f 4876/4878/10796 5047/5049/10797 5031/5033/10798 +f 5031/5033/10798 5047/5049/10797 5048/5050/10775 +f 5031/5033/10798 5048/5050/10775 4874/4876/10793 +f 4874/4876/10793 5048/5050/10775 5049/5051/10776 +f 4874/4876/10793 5049/5051/10776 5045/5047/10771 +f 4876/4878/10796 5046/5048/10795 5047/5049/10797 +f 5050/5052/10799 4859/4861/10800 4861/4863/10801 +f 5051/5053/10802 5052/5054/10803 4857/4859/10804 +f 4857/4859/10804 5052/5054/10803 4858/4860/10805 +f 4858/4860/10805 5052/5054/10803 4946/4948/10806 +f 4946/4948/10806 5052/5054/10803 5053/5055/10807 +f 4946/4948/10806 5053/5055/10807 4861/4863/10801 +f 4861/4863/10801 5053/5055/10807 5054/5056/10808 +f 4861/4863/10801 5054/5056/10808 5050/5052/10799 +f 5055/5057/10771 4843/4845/10772 4867/4869/10773 +f 4868/4870/10762 4870/4872/10763 5056/5058/10764 +f 4868/4870/10762 5057/5059/10765 5042/5044/10774 +f 5042/5044/10774 5057/5059/10765 5058/5060/10775 +f 5042/5044/10774 5058/5060/10775 4867/4869/10773 +f 4867/4869/10773 5058/5060/10775 5059/5061/10776 +f 4867/4869/10773 5059/5061/10776 5055/5057/10771 +f 4868/4870/10762 5056/5058/10764 5057/5059/10765 +f 4981/4983/10809 4994/4996/10810 4992/4994/10811 +f 4981/4983/10809 4992/4994/10811 4982/4984/10812 +f 4982/4984/10813 4992/4994/10813 4991/4993/10813 +f 4982/4984/10814 4991/4993/10814 4984/4986/10814 +f 4984/4986/10815 4991/4993/10815 4989/4991/10815 +f 4984/4986/10816 4989/4991/10816 4985/4987/10816 +f 4985/4987/10817 4989/4991/10818 4988/4990/10819 +f 4985/4987/10817 4988/4990/10819 4980/4982/10820 +f 4996/4998/10821 5001/5003/10821 5005/5007/10821 +f 4996/4998/10822 5005/5007/10822 4997/4999/10822 +f 4997/4999/10823 5005/5007/10768 5004/5006/10767 +f 4997/4999/10755 5004/5006/10824 4999/5001/10757 +f 4999/5001/10825 5004/5006/10767 5003/5005/10765 +f 4999/5001/10757 5003/5005/10826 5000/5002/10758 +f 5000/5002/10827 5003/5005/10827 5002/5004/10827 +f 5000/5002/10828 5002/5004/10828 4995/4997/10828 +f 5007/5009/10829 5012/5014/10829 5016/5018/10829 +f 5007/5009/10822 5016/5018/10822 5008/5010/10822 +f 5008/5010/10823 5016/5018/10776 5015/5017/10775 +f 5008/5010/10769 5015/5017/10824 5010/5012/10757 +f 5010/5012/10825 5015/5017/10775 5014/5016/10765 +f 5010/5012/10757 5014/5016/10830 5011/5013/10770 +f 5011/5013/10831 5014/5016/10831 5013/5015/10831 +f 5011/5013/10828 5013/5015/10828 5006/5008/10828 +f 5018/5020/10829 5023/5025/10829 5027/5029/10829 +f 5018/5020/10822 5027/5029/10822 5019/5021/10822 +f 5019/5021/10823 5027/5029/10768 5026/5028/10767 +f 5019/5021/10755 5026/5028/10824 5021/5023/10780 +f 5021/5023/10825 5026/5028/10767 5025/5027/10765 +f 5021/5023/10780 5025/5027/10830 5022/5024/10770 +f 5022/5024/10831 5025/5027/10831 5024/5026/10831 +f 5022/5024/10828 5024/5026/10828 5017/5019/10828 +f 5029/5031/10821 5034/5036/10821 5038/5040/10821 +f 5029/5031/10822 5038/5040/10822 5030/5032/10822 +f 5030/5032/10823 5038/5040/10776 5037/5039/10775 +f 5030/5032/10755 5037/5039/10824 5032/5034/10788 +f 5032/5034/10825 5037/5039/10775 5036/5038/10765 +f 5032/5034/10788 5036/5038/10830 5033/5035/10789 +f 5033/5035/10831 5036/5038/10831 5035/5037/10831 +f 5033/5035/10828 5035/5037/10828 5028/5030/10828 +f 5040/5042/10829 5045/5047/10829 5049/5051/10829 +f 5040/5042/10832 5049/5051/10832 5041/5043/10832 +f 5041/5043/10833 5049/5051/10776 5048/5050/10775 +f 5041/5043/10755 5048/5050/10824 5043/5045/10780 +f 5043/5045/10825 5048/5050/10775 5047/5049/10797 +f 5043/5045/10780 5047/5049/10830 5044/5046/10770 +f 5044/5046/10831 5047/5049/10831 5046/5048/10831 +f 5044/5046/10834 5046/5048/10834 5039/5041/10834 +f 5051/5053/10829 5055/5057/10829 5059/5061/10829 +f 5051/5053/10822 5059/5061/10822 5052/5054/10822 +f 5052/5054/10823 5059/5061/10776 5058/5060/10775 +f 5052/5054/10803 5058/5060/10824 5053/5055/10807 +f 5053/5055/10825 5058/5060/10775 5057/5059/10765 +f 5053/5055/10807 5057/5059/10826 5054/5056/10808 +f 5054/5056/10827 5057/5059/10827 5056/5058/10827 +f 5054/5056/10828 5056/5058/10828 5050/5052/10828 +f 5060/5062/10835 4948/4950/10836 4940/4942/10837 +f 4940/4942/10837 4948/4950/10836 4950/4952/10838 +f 4941/4943/10839 4952/4954/10840 5061/5063/10841 +f 5061/5063/10841 4952/4954/10840 4949/4951/10842 +f 4944/4946/10843 4934/4936/10844 4935/4937/10845 +f 4944/4946/10843 4935/4937/10845 5062/5064/10846 +f 5062/5064/10846 4935/4937/10845 4947/4949/10847 +f 5062/5064/10846 4947/4949/10847 5063/5065/10848 +f 5063/5065/10848 4947/4949/10847 4948/4950/10836 +f 5063/5065/10848 4948/4950/10836 5060/5062/10835 +f 4933/4935/10849 4943/4945/10850 4945/4947/10851 +f 4933/4935/10849 4945/4947/10851 4932/4934/10852 +f 5055/5057/10853 5051/5053/10854 4843/4845/10855 +f 4843/4845/10855 5051/5053/10854 4857/4859/10856 +f 4843/4845/10857 4857/4859/10353 4831/4833/10352 +f 4843/4845/10858 4831/4833/10858 4841/4843/10858 +f 4841/4843/10859 4831/4833/10859 4830/4832/10859 +f 5045/5047/10853 5040/5042/10860 4826/4828/10861 +f 4826/4828/10861 5040/5042/10860 4814/4816/10862 +f 4826/4828/10863 4814/4816/10864 4824/4826/10865 +f 4824/4826/10865 4814/4816/10864 4813/4815/10866 +f 5034/5036/10867 5029/5031/10867 4881/4883/10867 +f 4881/4883/10868 5029/5031/10868 4799/4801/10868 +f 4881/4883/10869 4799/4801/10869 4810/4812/10869 +f 4810/4812/10870 4799/4801/10870 4798/4800/10870 +f 4810/4812/10871 4798/4800/10871 4809/4811/10871 +f 5023/5025/10853 5018/5020/10860 4794/4796/10861 +f 4794/4796/10861 5018/5020/10860 4781/4783/10862 +f 4794/4796/10863 4781/4783/10864 4792/4794/10865 +f 4792/4794/10865 4781/4783/10864 4780/4782/10866 +f 5012/5014/10853 5007/5009/10872 4777/4779/10873 +f 4777/4779/10873 5007/5009/10872 4889/4891/10874 +f 4777/4779/10875 4889/4891/10875 4771/4773/10875 +f 4777/4779/10876 4771/4773/10876 4775/4777/10876 +f 4775/4777/10877 4771/4773/10877 4772/4774/10877 +f 5001/5003/10867 4996/4998/10867 4904/4906/10867 +f 4904/4906/10868 4996/4998/10868 4748/4750/10868 +f 4904/4906/10502 4748/4750/10869 4760/4762/10501 +f 4760/4762/10870 4748/4750/10870 4747/4749/10870 +f 4760/4762/10871 4747/4749/10871 4758/4760/10871 +f 4994/4996/10878 4981/4983/10879 4993/4995/10880 +f 4993/4995/10880 4981/4983/10879 4905/4907/10881 +f 4993/4995/10882 4905/4907/10503 4740/4742/10883 +f 4740/4742/10883 4905/4907/10503 4735/4737/10500 +f 4740/4742/10884 4735/4737/10885 4736/4738/10886 +f 4740/4742/10884 4736/4738/10886 4738/4740/10887 +f 4978/4980/10888 4976/4978/10888 4870/4872/10888 +f 4870/4872/10889 4976/4978/10889 4862/4864/10889 +f 4870/4872/10890 4862/4864/10890 4859/4861/10890 +f 4870/4872/10891 4859/4861/10892 5056/5058/10893 +f 5056/5058/10893 4859/4861/10892 5050/5052/10894 +f 4975/4977/10895 4973/4975/10895 4875/4877/10895 +f 4875/4877/10896 4973/4975/10896 4871/4873/10896 +f 4875/4877/10897 4871/4873/10897 4869/4871/10897 +f 4875/4877/10898 4869/4871/10898 5046/5048/10898 +f 5046/5048/10899 4869/4871/10899 5039/5041/10899 +f 4972/4974/10900 4970/4972/10900 4885/4887/10900 +f 4885/4887/10901 4970/4972/10901 4878/4880/10901 +f 4885/4887/10902 4878/4880/10902 4877/4879/10902 +f 4885/4887/10903 4877/4879/10904 5035/5037/10905 +f 5035/5037/10905 4877/4879/10904 5028/5030/10906 +f 4969/4971/10907 4968/4970/10907 4893/4895/10907 +f 4893/4895/10908 4968/4970/10908 4886/4888/10908 +f 4893/4895/10902 4886/4888/10902 4884/4886/10902 +f 4893/4895/10903 4884/4886/10904 5024/5026/10905 +f 5024/5026/10905 4884/4886/10904 5017/5019/10906 +f 4965/4967/10900 4963/4965/10900 4900/4902/10900 +f 4900/4902/10901 4963/4965/10901 4894/4896/10901 +f 4900/4902/10902 4894/4896/10902 4892/4894/10902 +f 4900/4902/10903 4892/4894/10904 5013/5015/10905 +f 5013/5015/10905 4892/4894/10904 5006/5008/10906 +f 4962/4964/10907 4961/4963/10907 4909/4911/10907 +f 4909/4911/10908 4961/4963/10908 4901/4903/10908 +f 4909/4911/10902 4901/4903/10902 4899/4901/10902 +f 4909/4911/10903 4899/4901/10904 5002/5004/10905 +f 5002/5004/10905 4899/4901/10904 4995/4997/10906 +f 4958/4960/10909 4954/4956/10910 4957/4959/10911 +f 4957/4959/10911 4954/4956/10910 4910/4912/10912 +f 4957/4959/10913 4910/4912/10506 4987/4989/10914 +f 4987/4989/10914 4910/4912/10506 4908/4910/10505 +f 4987/4989/10915 4908/4910/10916 4988/4990/10917 +f 4988/4990/10917 4908/4910/10916 4980/4982/10918 +f 4714/4716/10919 4703/4705/10919 4701/4703/10919 +f 4714/4716/10920 4701/4703/10361 4863/4865/10360 +f 4714/4716/10921 4863/4865/10921 4979/4981/10921 +f 4979/4981/10922 4863/4865/10922 4977/4979/10922 +f 4690/4692/10923 4679/4681/10923 4677/4679/10923 +f 4690/4692/10924 4677/4679/10393 4873/4875/10392 +f 4690/4692/10925 4873/4875/10925 4974/4976/10925 +f 4669/4671/10923 4659/4661/10923 4657/4659/10923 +f 4669/4671/10924 4657/4659/10924 4880/4882/10924 +f 4669/4671/10925 4880/4882/10925 4971/4973/10925 +f 4648/4650/10923 4637/4639/10923 4635/4637/10923 +f 4648/4650/10924 4635/4637/10924 4888/4890/10924 +f 4648/4650/10926 4888/4890/10926 4967/4969/10926 +f 4627/4629/10923 4616/4618/10923 4614/4616/10923 +f 4627/4629/10924 4614/4616/10924 4896/4898/10924 +f 4627/4629/10925 4896/4898/10925 4964/4966/10925 +f 4605/4607/10927 4594/4596/10928 4592/4594/10490 +f 4605/4607/10927 4592/4594/10490 4903/4905/10489 +f 4605/4607/10929 4903/4905/10702 4960/4962/10703 +f 4580/4582/10930 4567/4569/10931 4578/4580/10932 +f 4578/4580/10932 4567/4569/10931 4565/4567/10508 +f 4578/4580/10932 4565/4567/10508 4912/4914/10507 +f 4578/4580/10932 4912/4914/10507 4956/4958/10933 +f 4956/4958/10933 4912/4914/10507 4953/4955/10934 +f 4922/4924/10535 4921/4923/10534 4945/4947/10935 +f 4945/4947/10935 4921/4923/10534 4932/4934/10936 +f 4943/4945/10937 4933/4935/10938 4944/4946/10843 +f 4944/4946/10843 4933/4935/10938 4934/4936/10844 +f 4952/4954/10840 4941/4943/10839 4951/4953/10939 +f 4951/4953/10939 4941/4943/10839 4937/4939/10940 +f 4951/4953/10941 4937/4939/10942 4950/4952/10838 +f 4950/4952/10838 4937/4939/10942 4940/4942/10837 +f 4923/4925/10943 4925/4927/10944 5061/5063/10841 +f 4923/4925/10943 5061/5063/10841 4949/4951/10842 +f 5064/5066/10945 5065/5067/10946 5066/5068/10947 +f 5067/5069/10948 5068/5070/10949 5065/5067/10946 +f 5064/5066/10945 5067/5069/10948 5065/5067/10946 +f 5064/5066/10945 5069/5071/10950 5067/5069/10948 +f 5070/5072/10951 5071/5073/10952 5068/5070/10953 +f 5072/5074/10954 5070/5072/10951 5073/5075/10955 +f 5071/5073/10952 5070/5072/10951 5072/5074/10954 +f 5072/5074/10954 5074/5076/10956 5071/5073/10952 +f 5072/5074/10954 5075/5077/10957 5074/5076/10956 +f 5076/5078/10958 5077/5079/10959 5078/5080/10960 +f 5076/5078/10958 5079/5081/10961 5080/5082/10962 +f 5079/5081/10961 5076/5078/10958 5081/5083/10963 +f 5081/5083/10963 5076/5078/10958 5082/5084/10964 +f 5083/5085/10965 5084/5086/10966 5081/5083/10967 +f 5083/5085/10965 5081/5083/10967 5085/5087/10968 +f 5086/5088/10969 5084/5086/10966 5083/5085/10965 +f 5087/5089/10970 5088/5090/10971 5089/5091/10972 +f 5090/5092/10973 5091/5093/10974 5092/5094/10975 +f 5093/5095/10976 5094/5096/10977 5095/5097/10978 +f 5096/5098/10979 5097/5099/10980 5098/5100/10981 +f 5098/5100/10981 5099/5101/10982 5096/5098/10979 +f 5098/5100/10981 5100/5102/10983 5099/5101/10982 +f 5100/5102/10983 5098/5100/10981 5101/5103/10984 +f 5100/5102/10983 5101/5103/10984 5102/5104/10985 +f 5085/5087/10968 5103/5105/10986 5083/5085/10965 +f 5082/5084/10964 5076/5078/10958 5103/5105/10986 +f 5086/5088/10969 5083/5085/10965 5104/5106/10987 +f 5105/5107/10988 5102/5104/10985 5101/5103/10984 +f 5076/5078/10958 5078/5080/10960 5103/5105/10986 +f 5103/5105/10986 5078/5080/10960 5083/5085/10965 +f 5083/5085/10965 5078/5080/10960 5106/5108/10989 +f 5083/5085/10965 5106/5108/10989 5104/5106/10987 +f 5104/5106/10987 5106/5108/10989 5107/5109/10990 +f 5077/5079/10959 5108/5110/10991 5078/5080/10960 +f 5078/5080/10960 5108/5110/10991 5109/5111/10992 +f 5106/5108/10989 5078/5080/10960 5110/5112/10993 +f 5106/5108/10989 5110/5112/10993 5107/5109/10990 +f 5108/5110/10991 5111/5113/10994 5109/5111/10992 +f 5078/5080/10960 5109/5111/10992 5112/5114/10995 +f 5078/5080/10960 5112/5114/10995 5110/5112/10993 +f 5107/5109/10990 5110/5112/10993 5089/5091/10972 +f 5110/5112/10993 5087/5089/10970 5089/5091/10972 +f 5064/5066/10945 5113/5115/10996 5101/5103/10984 +f 5064/5066/10945 5101/5103/10984 5114/5116/10997 +f 5114/5116/10997 5101/5103/10984 5098/5100/10981 +f 5114/5116/10997 5098/5100/10981 5115/5117/10998 +f 5115/5117/10998 5098/5100/10981 5116/5118/10999 +f 5113/5115/10996 5105/5107/10988 5101/5103/10984 +f 5116/5118/10999 5098/5100/10981 5097/5099/10980 +f 5109/5111/10992 5111/5113/10994 5117/5119/11000 +f 5109/5111/10992 5117/5119/11000 5112/5114/10995 +f 5110/5112/10993 5112/5114/10995 5118/5120/11001 +f 5110/5112/10993 5118/5120/11001 5087/5089/10970 +f 5088/5090/10971 5087/5089/10970 5119/5121/11002 +f 5075/5077/10957 5072/5074/10954 5111/5113/10994 +f 5112/5114/10995 5117/5119/11000 5120/5122/11003 +f 5112/5114/10995 5120/5122/11003 5118/5120/11001 +f 5119/5121/11002 5087/5089/10970 5121/5123/11004 +f 5072/5074/10954 5073/5075/10955 5122/5124/11005 +f 5122/5124/11005 5073/5075/10955 5064/5066/10945 +f 5122/5124/11005 5064/5066/10945 5123/5125/11006 +f 5122/5124/11005 5123/5125/11006 5124/5126/11007 +f 5124/5126/11007 5125/5127/11008 5120/5122/11003 +f 5120/5122/11003 5125/5127/11008 5118/5120/11001 +f 5118/5120/11001 5125/5127/11008 5126/5128/11009 +f 5118/5120/11001 5126/5128/11009 5121/5123/11004 +f 5121/5123/11004 5126/5128/11009 5090/5092/10973 +f 5073/5075/10955 5069/5071/10950 5064/5066/10945 +f 5124/5126/11007 5123/5125/11006 5125/5127/11008 +f 5125/5127/11008 5115/5117/10998 5126/5128/11009 +f 5090/5092/10973 5126/5128/11009 5095/5097/10978 +f 5095/5097/10978 5126/5128/11009 5093/5095/10976 +f 5064/5066/10945 5066/5068/10947 5113/5115/10996 +f 5126/5128/11009 5115/5117/10998 5116/5118/10999 +f 5126/5128/11009 5116/5118/10999 5093/5095/10976 +f 5093/5095/10976 5116/5118/10999 5127/5129/11010 +f 5111/5113/10994 5072/5074/10954 5122/5124/11005 +f 5111/5113/10994 5122/5124/11005 5117/5119/11000 +f 5087/5089/10970 5118/5120/11001 5121/5123/11004 +f 5119/5121/11002 5121/5123/11004 5092/5094/10975 +f 5117/5119/11000 5122/5124/11005 5124/5126/11007 +f 5117/5119/11000 5124/5126/11007 5120/5122/11003 +f 5121/5123/11004 5090/5092/10973 5092/5094/10975 +f 5123/5125/11006 5064/5066/10945 5114/5116/10997 +f 5123/5125/11006 5114/5116/10997 5125/5127/11008 +f 5125/5127/11008 5114/5116/10997 5115/5117/10998 +f 5128/5130/11011 4724/4726/10203 4722/4724/10201 +f 5128/5130/11011 4722/4724/10201 5129/5131/11012 +f 5130/5132/11013 4728/4730/11014 5131/5133/11015 +f 5130/5132/11013 5131/5133/11015 5132/5134/11016 +f 4722/4724/10201 5133/5135/11017 5129/5131/11012 +f 4847/4849/10335 5133/5135/11017 4722/4724/10201 +f 4848/4850/10336 5134/5136/11018 5133/5135/11017 +f 4848/4850/10336 5133/5135/11017 4847/4849/10335 +f 4848/4850/10336 5135/5137/11019 5134/5136/11018 +f 5135/5137/11019 4848/4850/10336 4850/4852/10338 +f 4850/4852/10338 5136/5138/11020 5135/5137/11019 +f 5136/5138/11020 4850/4852/10338 4852/4854/10340 +f 5137/5139/11021 4913/4915/10526 4916/4918/10529 +f 5137/5139/11021 4916/4918/10529 5138/5140/11022 +f 4916/4918/10529 5139/5141/11023 5138/5140/11022 +f 4917/4919/10530 5139/5141/11023 4916/4918/10529 +f 5139/5141/11023 4917/4919/10530 5140/5142/11024 +f 5140/5142/11024 4917/4919/10530 4919/4921/10532 +f 5140/5142/11024 4919/4921/10532 5141/5143/11025 +f 4922/4924/10535 5142/5144/11026 4919/4921/10532 +f 4919/4921/10532 5142/5144/11026 5141/5143/11025 +f 4925/4927/10538 5084/5086/11027 5143/5145/11028 +f 5084/5086/11027 4925/4927/10538 4926/4928/10539 +f 4926/4928/10539 5079/5081/11029 5084/5086/11027 +f 4728/4730/10662 5079/5081/11029 4926/4928/10539 +f 4728/4730/10662 5130/5132/11030 5079/5081/11029 +f 5144/5146/11031 5103/5105/11032 5145/5147/11033 +f 5144/5146/11031 5082/5084/11034 5103/5105/11032 +f 5082/5084/11035 5144/5146/11036 5146/5148/11037 +f 5082/5084/11035 5146/5148/11037 5081/5083/11038 +f 5147/5149/11039 5085/5087/11040 5146/5148/11041 +f 5146/5148/11041 5085/5087/11040 5081/5083/11042 +f 5145/5147/11043 5103/5105/11044 5147/5149/11045 +f 5147/5149/11045 5103/5105/11044 5085/5087/11046 +f 5148/5150/11047 5070/5072/11047 5068/5070/11047 +f 5148/5150/11048 5149/5151/11048 5070/5072/11048 +f 5070/5072/11049 5149/5151/11049 5073/5075/11049 +f 5073/5075/11050 5149/5151/11051 5069/5071/11052 +f 5069/5071/11052 5149/5151/11051 5150/5152/11053 +f 5069/5071/11054 5150/5152/11055 5067/5069/11056 +f 5067/5069/11056 5150/5152/11055 5151/5153/11057 +f 5067/5069/11058 5151/5153/11059 5068/5070/11060 +f 5148/5150/11061 5068/5070/11060 5151/5153/11059 +f 5152/5154/11062 5153/5155/11063 5154/5156/11064 +f 5155/5157/11065 5156/5158/11066 5157/5159/11067 +f 5156/5158/11068 5158/5160/11069 5157/5159/11070 +f 5159/5161/11071 5158/5160/11069 5156/5158/11068 +f 4852/4854/10340 5160/5162/11072 5136/5138/11020 +f 5160/5162/11072 4852/4854/10340 5152/5154/11062 +f 5160/5162/11072 5152/5154/11062 5154/5156/11064 +f 4913/4915/10526 5161/5163/11073 5152/5154/11062 +f 5152/5154/11062 5161/5163/11073 5153/5155/11063 +f 4913/4915/10526 5137/5139/11021 5161/5163/11073 +f 5162/5164/11074 5132/5134/11016 5131/5133/11015 +f 5162/5164/11074 5131/5133/11015 5155/5157/11065 +f 5155/5157/11065 5131/5133/11015 5156/5158/11066 +f 4724/4726/10203 5163/5165/11075 5159/5161/11076 +f 5159/5161/11076 5163/5165/11075 5158/5160/11077 +f 4724/4726/10203 5128/5130/11011 5163/5165/11075 +f 5140/5142/11024 5100/5102/10983 5102/5104/10985 +f 5140/5142/11024 5102/5104/10985 5139/5141/11023 +f 5102/5104/10985 5105/5107/10988 5137/5139/11021 +f 5100/5102/10983 5140/5142/11024 5099/5101/10982 +f 5099/5101/10982 5141/5143/11025 5096/5098/10979 +f 5137/5139/11021 5138/5140/11022 5102/5104/10985 +f 5138/5140/11022 5139/5141/11023 5102/5104/10985 +f 5140/5142/11024 5141/5143/11025 5099/5101/10982 +f 5141/5143/11025 5142/5144/11026 5096/5098/10979 +f 5137/5139/11021 5105/5107/10988 5161/5163/11073 +f 5161/5163/11073 5105/5107/10988 5153/5155/11078 +f 5154/5156/11079 5153/5155/11079 5105/5107/11079 +f 5154/5156/11080 5105/5107/11080 5113/5115/11080 +f 5154/5156/11064 5113/5115/10996 5160/5162/11072 +f 5160/5162/11072 5113/5115/10996 5066/5068/10947 +f 5160/5162/11072 5066/5068/10947 5136/5138/11020 +f 5071/5073/10952 5065/5067/10946 5068/5070/11081 +f 5075/5077/10957 5129/5131/11012 5074/5076/10956 +f 5074/5076/10956 5129/5131/11012 5133/5135/11017 +f 5071/5073/10952 5133/5135/11017 5134/5136/11018 +f 5071/5073/10952 5134/5136/11018 5065/5067/10946 +f 5134/5136/11018 5135/5137/11019 5065/5067/10946 +f 5065/5067/10946 5136/5138/11020 5066/5068/10947 +f 5136/5138/11020 5065/5067/10946 5135/5137/11019 +f 5071/5073/10952 5074/5076/10956 5133/5135/11017 +f 5129/5131/11012 5075/5077/10957 5128/5130/11011 +f 5075/5077/10957 5111/5113/11082 5158/5160/11083 +f 5158/5160/11083 5163/5165/11075 5075/5077/10957 +f 5075/5077/10957 5163/5165/11075 5128/5130/11011 +f 5157/5159/11084 5158/5160/11083 5111/5113/11082 +f 5108/5110/11085 5157/5159/11084 5111/5113/11082 +f 5155/5157/11086 5157/5159/11084 5108/5110/11085 +f 5155/5157/11086 5108/5110/11085 5077/5079/11087 +f 5162/5164/11074 5077/5079/11087 5132/5134/11016 +f 5155/5157/11086 5077/5079/11087 5162/5164/11074 +f 5080/5082/10962 5130/5132/11030 5076/5078/10958 +f 5132/5134/11016 5077/5079/11087 5076/5078/10958 +f 5132/5134/11016 5076/5078/10958 5130/5132/11030 +f 5079/5081/11029 5130/5132/11030 5080/5082/10962 +f 5079/5081/11029 5081/5083/11088 5084/5086/11027 +f 5164/5166/11089 5165/5167/11090 5166/5168/11091 +f 5061/5063/10841 5167/5169/11092 4941/4943/10839 +f 4941/4943/10839 5167/5169/11092 5168/5170/11093 +f 5169/5171/11094 4944/4946/10843 5170/5172/11095 +f 5170/5172/11095 4944/4946/10843 5062/5064/10846 +f 5062/5064/10846 5171/5173/11096 5170/5172/11095 +f 5063/5065/10848 5171/5173/11096 5062/5064/10846 +f 5063/5065/10848 5172/5174/11097 5171/5173/11096 +f 5172/5174/11097 5063/5065/10848 5164/5166/11089 +f 5164/5166/11089 5063/5065/10848 5060/5062/10835 +f 5164/5166/11089 5060/5062/10835 5165/5167/11090 +f 5167/5169/11092 5061/5063/10841 4925/4927/10944 +f 4925/4927/10944 5143/5145/11098 5167/5169/11092 +f 5091/5093/11099 5173/5175/11100 5094/5096/11101 +f 5094/5096/11102 5173/5175/11103 5174/5176/11104 +f 5094/5096/11102 5174/5176/11104 5095/5097/11105 +f 5095/5097/11106 5174/5176/11106 5175/5177/11106 +f 5095/5097/11107 5175/5177/11108 5090/5092/11109 +f 5090/5092/11109 5175/5177/11108 5176/5178/11110 +f 5090/5092/11111 5176/5178/11112 5091/5093/11113 +f 5091/5093/11113 5176/5178/11112 5177/5179/11114 +f 5173/5175/11100 5091/5093/11099 5177/5179/11115 +f 4942/4944/11116 5178/5180/11117 5179/5181/11118 +f 4939/4941/11119 5180/5182/11120 5181/5183/11121 +f 4939/4941/11122 5182/5184/11123 5180/5182/11120 +f 4938/4940/11124 5182/5184/11123 4939/4941/11122 +f 4944/4946/10843 5183/5185/11125 4942/4944/11116 +f 4942/4944/11116 5183/5185/11125 5178/5180/11117 +f 4944/4946/10843 5169/5171/11094 5183/5185/11125 +f 4922/4924/10535 5184/5186/11126 5142/5144/11026 +f 4942/4944/11116 5184/5186/11126 4922/4924/10535 +f 5184/5186/11126 4942/4944/11116 5179/5181/11118 +f 4941/4943/10839 5185/5187/11127 4938/4940/11128 +f 4938/4940/11128 5185/5187/11127 5182/5184/11129 +f 5168/5170/11093 5185/5187/11127 4941/4943/10839 +f 5166/5168/11091 5165/5167/11090 5186/5188/11130 +f 4940/4942/11131 5186/5188/11130 5165/5167/11090 +f 5186/5188/11130 4940/4942/11131 4939/4941/11119 +f 5186/5188/11130 4939/4941/11119 5181/5183/11121 +f 5184/5186/11126 5179/5181/11132 5097/5099/10980 +f 5184/5186/11126 5097/5099/10980 5096/5098/10979 +f 5184/5186/11126 5096/5098/10979 5142/5144/11026 +f 5187/5189/11133 5116/5118/10999 5097/5099/10980 +f 5187/5189/11133 5097/5099/10980 5179/5181/11132 +f 5187/5189/11133 5179/5181/11132 5178/5180/11117 +f 5127/5129/11010 5116/5118/10999 5187/5189/11133 +f 5183/5185/11125 5187/5189/11133 5178/5180/11117 +f 5183/5185/11125 5169/5171/11134 5127/5129/11010 +f 5127/5129/11010 5187/5189/11133 5183/5185/11125 +f 5092/5094/10975 5091/5093/11135 5093/5095/10976 +f 5093/5095/10976 5091/5093/11135 5094/5096/10977 +f 5119/5121/11002 5092/5094/10975 5164/5166/11136 +f 5164/5166/11136 5092/5094/10975 5172/5174/11097 +f 5172/5174/11097 5092/5094/10975 5171/5173/11096 +f 5170/5172/11095 5093/5095/10976 5169/5171/11134 +f 5127/5129/11010 5169/5171/11134 5093/5095/10976 +f 5093/5095/10976 5171/5173/11096 5092/5094/10975 +f 5170/5172/11095 5171/5173/11096 5093/5095/10976 +f 5164/5166/11136 5166/5168/11137 5119/5121/11002 +f 5119/5121/11002 5166/5168/11137 5088/5090/10971 +f 5188/5190/11138 5186/5188/11130 5181/5183/11121 +f 5166/5168/11137 5186/5188/11130 5188/5190/11138 +f 5166/5168/11137 5188/5190/11138 5088/5090/10971 +f 5089/5091/11139 5088/5090/10971 5188/5190/11138 +f 5089/5091/11139 5188/5190/11138 5180/5182/11120 +f 5180/5182/11120 5188/5190/11138 5181/5183/11121 +f 5089/5091/11140 5189/5191/11140 5107/5109/11140 +f 5180/5182/11120 5182/5184/11123 5189/5191/11141 +f 5180/5182/11120 5189/5191/11141 5089/5091/11139 +f 5190/5192/11142 5107/5109/10990 5189/5191/11143 +f 5185/5187/11127 5168/5170/11093 5190/5192/11142 +f 5190/5192/11142 5168/5170/11093 5107/5109/10990 +f 5182/5184/11123 5185/5187/11127 5189/5191/11141 +f 5189/5191/11141 5185/5187/11127 5190/5192/11142 +f 5167/5169/11092 5104/5106/10987 5168/5170/11093 +f 5104/5106/10987 5107/5109/10990 5168/5170/11093 +f 5104/5106/10987 5167/5169/11092 5086/5088/10969 +f 5167/5169/11092 5143/5145/11098 5086/5088/10969 +f 5086/5088/10969 5143/5145/11098 5084/5086/10966 +f 5165/5167/11144 5060/5062/11144 4940/4942/11144 +f 5191/5193/11145 5192/5194/11146 5193/5195/11147 +f 5194/5196/528 5195/5197/528 5196/5198/528 +f 5197/5199/528 5198/5200/528 5199/5201/528 +f 5191/5193/11145 5200/5202/11148 5192/5194/11146 +f 5192/5194/11146 5200/5202/11148 5201/5203/11149 +f 5193/5195/11150 5202/5204/11151 5191/5193/11152 +f 5198/5200/528 5194/5196/528 5199/5201/528 +f 5195/5197/528 5194/5196/528 5198/5200/528 +f 5203/5205/11153 5202/5204/11154 5204/5206/11155 +f 5202/5204/11154 5203/5205/11153 5200/5202/11148 +f 5204/5206/11156 5202/5204/11151 5193/5195/11150 +f 5200/5202/11148 5203/5205/11153 5205/5207/11157 +f 5206/5208/528 5199/5201/528 5196/5198/528 +f 5201/5203/11149 5200/5202/11148 5205/5207/11157 +f 5201/5203/11149 5205/5207/11157 5207/5209/11158 +f 5207/5209/11159 5205/5207/11160 5208/5210/11161 +f 5208/5210/11162 5205/5207/11163 5209/5211/11164 +f 5208/5210/11162 5209/5211/11164 5210/5212/11165 +f 5211/5213/528 5206/5208/528 5196/5198/528 +f 5211/5213/528 5196/5198/528 5195/5197/528 +f 5212/5214/528 5213/5215/528 5214/5216/528 +f 5208/5210/11162 5210/5212/11165 5212/5214/528 +f 5212/5214/528 5210/5212/11165 5213/5215/528 +f 5214/5216/528 5213/5215/528 5215/5217/528 +f 5206/5208/528 5211/5213/528 5214/5216/528 +f 5206/5208/528 5214/5216/528 5215/5217/528 +f 5204/5206/11166 5193/5195/11166 5216/5218/11166 +f 5203/5205/11167 5204/5206/11168 5216/5218/11169 +f 5192/5194/11170 5217/5219/11171 5218/5220/11172 +f 5192/5194/11170 5218/5220/11172 5193/5195/11173 +f 5203/5205/11167 5216/5218/11169 5217/5219/11174 +f 5219/5221/98 5220/5222/98 5221/5223/98 +f 5222/5224/98 5223/5225/98 5224/5226/98 +f 5193/5195/11173 5218/5220/11172 5216/5218/11175 +f 5217/5219/11176 5225/5227/11176 5203/5205/11176 +f 5220/5222/98 5219/5221/98 5224/5226/98 +f 5219/5221/98 5221/5223/98 5226/5228/98 +f 5217/5219/11171 5192/5194/11170 5227/5229/11177 +f 5225/5227/11178 5207/5209/11179 5209/5211/11180 +f 5217/5219/11171 5227/5229/11177 5225/5227/11178 +f 5227/5229/11177 5207/5209/11179 5225/5227/11178 +f 5209/5211/11180 5207/5209/11179 5228/5230/11181 +f 5209/5211/11180 5228/5230/11181 5229/5231/11182 +f 5229/5231/11182 5228/5230/11181 5230/5232/98 +f 5230/5232/98 5228/5230/11181 5231/5233/98 +f 5226/5228/98 5232/5234/98 5222/5224/98 +f 5219/5221/98 5226/5228/98 5222/5224/98 +f 5230/5232/98 5231/5233/98 5232/5234/98 +f 5230/5232/98 5232/5234/98 5226/5228/98 +f 5195/5197/11183 5223/5225/11183 5222/5224/11183 +f 5195/5197/11184 5222/5224/11184 5211/5213/11184 +f 5211/5213/11185 5222/5224/11185 5232/5234/11185 +f 5211/5213/11186 5232/5234/11186 5214/5216/11186 +f 5214/5216/11187 5232/5234/11187 5231/5233/11187 +f 5214/5216/11188 5231/5233/11188 5212/5214/11188 +f 5212/5214/11189 5231/5233/11189 5228/5230/11189 +f 5212/5214/11190 5228/5230/11190 5208/5210/11190 +f 5208/5210/11161 5228/5230/11191 5207/5209/11159 +f 5207/5209/11192 5227/5229/11192 5201/5203/11192 +f 5201/5203/11193 5227/5229/11193 5192/5194/11193 +f 5203/5205/11194 5225/5227/11194 5205/5207/11194 +f 5205/5207/11195 5225/5227/11195 5209/5211/11195 +f 5209/5211/11196 5229/5231/11196 5210/5212/11196 +f 5210/5212/11197 5229/5231/11198 5230/5232/11199 +f 5210/5212/11197 5230/5232/11199 5213/5215/11200 +f 5213/5215/11201 5230/5232/11201 5215/5217/11201 +f 5215/5217/11202 5230/5232/11202 5226/5228/11202 +f 5215/5217/11203 5226/5228/11203 5206/5208/11203 +f 5206/5208/11204 5226/5228/11204 5221/5223/11204 +f 5206/5208/11205 5221/5223/11205 5199/5201/11205 +f 5197/5199/11206 5199/5201/11206 5220/5222/11206 +f 5220/5222/11207 5199/5201/11207 5221/5223/11207 +f 5197/5199/11208 5220/5222/11208 5198/5200/11208 +f 5198/5200/11209 5220/5222/11209 5224/5226/11209 +f 5195/5197/11210 5198/5200/11210 5223/5225/11210 +f 5223/5225/11211 5198/5200/11211 5224/5226/11211 +f 5202/5204/11212 5216/5218/11212 5191/5193/11212 +f 5191/5193/11213 5216/5218/11213 5218/5220/11213 +f 5191/5193/11214 5218/5220/11214 5200/5202/11214 +f 5200/5202/11215 5218/5220/11215 5217/5219/11215 +f 5200/5202/11216 5217/5219/11216 5202/5204/11216 +f 5202/5204/11217 5217/5219/11217 5216/5218/11217 +f 5194/5196/11218 5222/5224/11218 5224/5226/11218 +f 5194/5196/11219 5224/5226/11219 5199/5201/11219 +f 5199/5201/11220 5224/5226/11220 5219/5221/11220 +f 5199/5201/11221 5219/5221/11221 5196/5198/11221 +f 5196/5198/11222 5219/5221/11222 5222/5224/11222 +f 5196/5198/11223 5222/5224/11223 5194/5196/11223 +f 5233/5235/11224 5234/5236/11225 5235/5237/11226 +f 5235/5237/11226 5234/5236/11225 5236/5238/11227 +f 5237/5239/11228 5235/5237/11228 5238/5240/11228 +f 5239/5241/11229 5234/5236/11225 5233/5235/11224 +f 5233/5235/11224 5237/5239/11230 5240/5242/11231 +f 5233/5235/11224 5240/5242/11231 5239/5241/11229 +f 5241/5243/11232 5242/5244/11233 5243/5245/11234 +f 5244/5246/11235 5245/5247/11236 5246/5248/11237 +f 5244/5246/11235 5246/5248/11237 5241/5243/11238 +f 5246/5248/11239 5247/5249/11240 5241/5243/11241 +f 5241/5243/11241 5247/5249/11240 5242/5244/11242 +f 5242/5244/11243 5247/5249/11244 5248/5250/11245 +f 5242/5244/11243 5248/5250/11245 5243/5245/11246 +f 5243/5245/11247 5248/5250/11248 5245/5247/11249 +f 5243/5245/11247 5245/5247/11249 5244/5246/11250 +f 5248/5250/11251 5249/5251/11252 5250/5252/11253 +f 5248/5250/11251 5250/5252/11253 5245/5247/11254 +f 5251/5253/11255 5252/5254/11256 5247/5249/11257 +f 5246/5248/11258 5251/5253/11255 5247/5249/11257 +f 5245/5247/11254 5250/5252/11253 5253/5255/11259 +f 5247/5249/11257 5252/5254/11256 5248/5250/11251 +f 5248/5250/11251 5252/5254/11256 5249/5251/11252 +f 5245/5247/11254 5253/5255/11259 5246/5248/11258 +f 5246/5248/11258 5253/5255/11259 5251/5253/11255 +f 5250/5252/11260 5236/5238/11261 5234/5236/11262 +f 5250/5252/11260 5234/5236/11262 5253/5255/11263 +f 5234/5236/11264 5239/5241/11265 5253/5255/11266 +f 5253/5255/11266 5239/5241/11265 5251/5253/11267 +f 5239/5241/11268 5240/5242/11268 5251/5253/11268 +f 5240/5242/11269 5237/5239/11270 5251/5253/11271 +f 5251/5253/11271 5237/5239/11270 5252/5254/11272 +f 5237/5239/11273 5238/5240/11274 5252/5254/11275 +f 5252/5254/11275 5238/5240/11274 5249/5251/11276 +f 5249/5251/11277 5238/5240/11277 5235/5237/11277 +f 5249/5251/11278 5235/5237/11279 5250/5252/11280 +f 5250/5252/11280 5235/5237/11279 5236/5238/11281 +f 5237/5239/11282 5233/5235/11282 5254/5256/11282 +f 5254/5256/11283 5233/5235/11283 5255/5257/11283 +f 5235/5237/11284 5237/5239/11284 5254/5256/11284 +f 5233/5235/11285 5235/5237/11285 5255/5257/11285 +f 5255/5257/11286 5235/5237/11286 5254/5256/11286 +f 5244/5246/11287 5241/5243/11232 5243/5245/11234 +f 5256/5258/11288 5257/5259/11289 5258/5260/11290 +f 5259/5261/11291 5260/5262/11292 5261/5263/11293 +f 5256/5258/11288 5258/5260/11290 5260/5262/11292 +f 5256/5258/11288 5260/5262/11292 5259/5261/11291 +f 5262/5264/11294 5263/5265/11295 5257/5259/11289 +f 5262/5264/11294 5257/5259/11289 5256/5258/11288 +f 5259/5261/11291 5261/5263/11293 5262/5264/11294 +f 5262/5264/11294 5261/5263/11293 5263/5265/11295 +f 5264/5266/11296 5265/5267/11297 5266/5268/11298 +f 5266/5268/11298 5267/5269/11299 5264/5266/11296 +f 5268/5270/11300 5266/5268/11300 5269/5271/11300 +f 5269/5271/11301 5266/5268/11302 5265/5267/11303 +f 5269/5271/11301 5265/5267/11303 5270/5272/11304 +f 5270/5272/11305 5265/5267/11306 5264/5266/11307 +f 5270/5272/11305 5264/5266/11307 5271/5273/11308 +f 5271/5273/11309 5264/5266/11310 5267/5269/11311 +f 5271/5273/11309 5267/5269/11311 5272/5274/11312 +f 5272/5274/11313 5267/5269/11314 5266/5268/11315 +f 5272/5274/11313 5266/5268/11315 5268/5270/11316 +f 5269/5271/11317 5273/5275/11318 5274/5276/11319 +f 5269/5271/11317 5274/5276/11319 5268/5270/11320 +f 5268/5270/11320 5274/5276/11319 5275/5277/11321 +f 5268/5270/11320 5275/5277/11321 5272/5274/11322 +f 5272/5274/11322 5275/5277/11321 5276/5278/11323 +f 5272/5274/11322 5276/5278/11323 5271/5273/11324 +f 5271/5273/11324 5276/5278/11323 5270/5272/11325 +f 5270/5272/11325 5276/5278/11323 5277/5279/11326 +f 5270/5272/11325 5277/5279/11326 5273/5275/11318 +f 5270/5272/11325 5273/5275/11318 5269/5271/11317 +f 5258/5260/11327 5274/5276/11328 5260/5262/11329 +f 5260/5262/11329 5274/5276/11328 5273/5275/11330 +f 5260/5262/11331 5273/5275/11332 5277/5279/11333 +f 5260/5262/11331 5277/5279/11333 5261/5263/11334 +f 5261/5263/11335 5277/5279/11336 5276/5278/11337 +f 5261/5263/11335 5276/5278/11337 5263/5265/11338 +f 5263/5265/11339 5276/5278/11340 5275/5277/11341 +f 5263/5265/11339 5275/5277/11341 5257/5259/11342 +f 5257/5259/11343 5275/5277/11344 5274/5276/11345 +f 5257/5259/11343 5274/5276/11345 5258/5260/11346 +f 5259/5261/11347 5262/5264/11348 5278/5280/11349 +f 5278/5280/11349 5262/5264/11348 5279/5281/11350 +f 5256/5258/11351 5259/5261/11352 5280/5282/11353 +f 5280/5282/11353 5259/5261/11352 5278/5280/11354 +f 5262/5264/9697 5256/5258/9698 5279/5281/9699 +f 5279/5281/9699 5256/5258/9698 5280/5282/9700 +f 5279/5281/528 5280/5282/528 5278/5280/528 +f 5281/5283/11355 5282/5284/11356 5283/5285/11357 +f 5284/5286/11358 5285/5287/11359 5286/5288/11360 +f 5285/5287/11359 5287/5289/11361 5286/5288/11360 +f 5285/5287/11359 5288/5290/11362 5287/5289/11361 +f 5289/5291/528 5287/5289/11361 5288/5290/11362 +f 5290/5292/528 5286/5288/11360 5289/5291/528 +f 5290/5292/528 5289/5291/528 5288/5290/11362 +f 5291/5293/11363 5292/5294/11364 5293/5295/11365 +f 5293/5295/11365 5292/5294/11364 5282/5284/528 +f 5292/5294/11366 5291/5293/11367 5294/5296/11368 +f 5284/5286/11358 5286/5288/11360 5295/5297/11369 +f 5283/5285/528 5292/5294/528 5294/5296/11370 +f 5283/5285/528 5294/5296/11370 5296/5298/11371 +f 5296/5298/11371 5294/5296/11370 5297/5299/11372 +f 5296/5298/11371 5297/5299/11372 5298/5300/11373 +f 5299/5301/11374 5295/5297/11369 5286/5288/11360 +f 5299/5301/11374 5286/5288/11360 5290/5292/528 +f 5297/5299/11372 5300/5302/11375 5298/5300/11373 +f 5298/5300/11373 5300/5302/11375 5301/5303/11376 +f 5301/5303/11376 5300/5302/11375 5302/5304/11377 +f 5301/5303/11376 5302/5304/11377 5303/5305/11378 +f 5301/5303/11376 5303/5305/11378 5299/5301/11374 +f 5299/5301/11374 5303/5305/11378 5295/5297/11369 +f 5304/5306/11379 5305/5307/11380 5306/5308/11381 +f 5291/5293/11382 5304/5306/11379 5306/5308/11381 +f 5307/5309/11383 5308/5310/98 5309/5311/98 +f 5281/5283/11384 5310/5312/11385 5311/5313/11386 +f 5281/5283/11384 5311/5313/11386 5305/5307/11380 +f 5309/5311/98 5308/5310/98 5312/5314/98 +f 5291/5293/11382 5306/5308/11381 5310/5312/11387 +f 5308/5310/98 5307/5309/11383 5313/5315/11388 +f 5305/5307/11380 5311/5313/11386 5306/5308/11381 +f 5310/5312/11387 5314/5316/11389 5291/5293/11382 +f 5285/5287/11390 5312/5314/11391 5313/5315/11392 +f 5310/5312/11385 5281/5283/11384 5315/5317/11393 +f 5314/5316/11394 5315/5317/11393 5297/5299/11395 +f 5310/5312/11385 5315/5317/11393 5314/5316/11394 +f 5297/5299/11395 5315/5317/11393 5316/5318/11396 +f 5297/5299/11395 5316/5318/11396 5317/5319/11397 +f 5317/5319/11397 5316/5318/11396 5318/5320/11398 +f 5317/5319/11397 5318/5320/11398 5319/5321/11399 +f 5319/5321/11399 5318/5320/11398 5303/5305/11400 +f 5320/5322/11401 5321/5323/11402 5309/5311/98 +f 5312/5314/98 5320/5322/11401 5309/5311/98 +f 5303/5305/11400 5318/5320/11398 5321/5323/11402 +f 5303/5305/11400 5321/5323/11402 5320/5322/11401 +f 5290/5292/11403 5307/5309/11403 5309/5311/11403 +f 5290/5292/11404 5309/5311/11404 5299/5301/11404 +f 5299/5301/11405 5309/5311/11405 5321/5323/11405 +f 5299/5301/11406 5321/5323/11406 5301/5303/11406 +f 5301/5303/11407 5321/5323/11407 5318/5320/11407 +f 5301/5303/11408 5318/5320/11408 5298/5300/11408 +f 5298/5300/11409 5318/5320/11409 5316/5318/11409 +f 5298/5300/11410 5316/5318/11410 5296/5298/11410 +f 5296/5298/11411 5316/5318/11411 5315/5317/11411 +f 5296/5298/11412 5315/5317/11412 5283/5285/11412 +f 5283/5285/11357 5315/5317/11413 5281/5283/11355 +f 5282/5284/11356 5281/5283/11355 5305/5307/11414 +f 5282/5284/11415 5305/5307/11415 5293/5295/11415 +f 5293/5295/11416 5305/5307/11416 5304/5306/11416 +f 5291/5293/11417 5293/5295/11417 5304/5306/11417 +f 5291/5293/11367 5314/5316/11418 5294/5296/11368 +f 5294/5296/11419 5314/5316/11419 5297/5299/11419 +f 5300/5302/11420 5297/5299/11420 5317/5319/11420 +f 5300/5302/11421 5317/5319/11421 5302/5304/11421 +f 5302/5304/11422 5317/5319/11422 5319/5321/11422 +f 5302/5304/11423 5319/5321/11423 5303/5305/11423 +f 5295/5297/11424 5303/5305/11424 5320/5322/11424 +f 5295/5297/11425 5320/5322/11425 5284/5286/11425 +f 5284/5286/11426 5320/5322/11426 5312/5314/11426 +f 5285/5287/11390 5284/5286/11427 5312/5314/11391 +f 5285/5287/11428 5313/5315/11428 5288/5290/11428 +f 5290/5292/11429 5288/5290/11429 5307/5309/11429 +f 5307/5309/11383 5288/5290/11430 5313/5315/11388 +f 5292/5294/11431 5306/5308/11431 5282/5284/11431 +f 5282/5284/11432 5306/5308/11432 5311/5313/11432 +f 5282/5284/11433 5311/5313/11433 5283/5285/11433 +f 5283/5285/11434 5311/5313/11434 5310/5312/11434 +f 5283/5285/11435 5310/5312/11435 5292/5294/11435 +f 5292/5294/11436 5310/5312/11436 5306/5308/11436 +f 5289/5291/11437 5308/5310/11437 5313/5315/11437 +f 5289/5291/11438 5313/5315/11438 5287/5289/11438 +f 5287/5289/11439 5313/5315/11439 5312/5314/11439 +f 5287/5289/11440 5312/5314/11440 5286/5288/11440 +f 5286/5288/11441 5312/5314/11441 5308/5310/11441 +f 5286/5288/11442 5308/5310/11442 5289/5291/11442 +f 5322/5324/11443 5323/5325/11444 5324/5326/11445 +f 5325/5327/11446 5326/5328/11447 5327/5329/11448 +f 5328/5330/11449 5329/5331/11450 5325/5327/11446 +f 5325/5327/11446 5329/5331/11450 5322/5324/11451 +f 5327/5329/11448 5328/5330/11449 5325/5327/11446 +f 5324/5326/11445 5323/5325/11444 5330/5332/11452 +f 5330/5332/11452 5331/5333/11453 5324/5326/11445 +f 5324/5326/11445 5331/5333/11453 5326/5328/11454 +f 5332/5334/11455 5333/5335/11456 5334/5336/11457 +f 5335/5337/11458 5336/5338/11459 5334/5336/11457 +f 5333/5335/11456 5335/5337/11458 5334/5336/11457 +f 5337/5339/11460 5332/5334/11460 5338/5340/11460 +f 5338/5340/11461 5332/5334/11461 5339/5341/11461 +f 5338/5340/11462 5339/5341/11463 5340/5342/11464 +f 5340/5342/11464 5339/5341/11463 5334/5336/11465 +f 5340/5342/11466 5334/5336/11466 5336/5338/11466 +f 5340/5342/11467 5336/5338/11468 5341/5343/11469 +f 5341/5343/11469 5336/5338/11468 5335/5337/11470 +f 5341/5343/11471 5335/5337/11472 5333/5335/11473 +f 5341/5343/11471 5333/5335/11473 5337/5339/11474 +f 5337/5339/11475 5333/5335/11475 5332/5334/11475 +f 5337/5339/11476 5342/5344/11477 5343/5345/11478 +f 5338/5340/11479 5344/5346/11480 5342/5344/11477 +f 5338/5340/11479 5342/5344/11477 5337/5339/11476 +f 5341/5343/11481 5345/5347/11482 5340/5342/11483 +f 5340/5342/11483 5345/5347/11482 5346/5348/11484 +f 5341/5343/11481 5347/5349/11485 5345/5347/11482 +f 5337/5339/11476 5343/5345/11478 5341/5343/11481 +f 5341/5343/11481 5343/5345/11478 5347/5349/11485 +f 5338/5340/11479 5348/5350/11486 5344/5346/11480 +f 5340/5342/11483 5346/5348/11484 5348/5350/11486 +f 5340/5342/11483 5348/5350/11486 5338/5340/11479 +f 5326/5328/11487 5331/5333/11488 5343/5345/11489 +f 5343/5345/11489 5331/5333/11488 5347/5349/11490 +f 5331/5333/11491 5330/5332/11492 5347/5349/11493 +f 5347/5349/11493 5330/5332/11492 5345/5347/11494 +f 5345/5347/11494 5330/5332/11492 5323/5325/11495 +f 5345/5347/11496 5323/5325/11497 5346/5348/11498 +f 5346/5348/11498 5323/5325/11497 5322/5324/11499 +f 5346/5348/11500 5322/5324/11501 5348/5350/11502 +f 5348/5350/11502 5322/5324/11501 5329/5331/11503 +f 5348/5350/11504 5329/5331/11505 5344/5346/11506 +f 5329/5331/11505 5328/5330/11507 5344/5346/11506 +f 5344/5346/11508 5328/5330/11509 5342/5344/11510 +f 5342/5344/11510 5328/5330/11509 5327/5329/11511 +f 5342/5344/11512 5327/5329/11513 5326/5328/11514 +f 5342/5344/11512 5326/5328/11514 5343/5345/11515 +f 5322/5324/11516 5324/5326/11517 5349/5351/11518 +f 5325/5327/11519 5322/5324/11519 5350/5352/11519 +f 5350/5352/11520 5322/5324/11520 5349/5351/11520 +f 5326/5328/11521 5325/5327/11521 5351/5353/11521 +f 5351/5353/11522 5325/5327/11522 5350/5352/11522 +f 5324/5326/11523 5326/5328/11523 5351/5353/11523 +f 5349/5351/11518 5324/5326/11517 5351/5353/11524 +f 5351/5353/3026 5350/5352/3026 5349/5351/3026 +f 5339/5341/11525 5332/5334/11455 5334/5336/11457 +f 5352/5354/11526 5353/5355/11527 5354/5356/11528 +f 5355/5357/11529 5356/5358/11530 5357/5359/11531 +f 5354/5356/11528 5358/5360/11532 5352/5354/11526 +f 5359/5361/11533 5360/5362/11534 5361/5363/11535 +f 5359/5361/11533 5361/5363/11535 5355/5357/11529 +f 5358/5360/11532 5360/5362/11534 5352/5354/11526 +f 5352/5354/11526 5360/5362/11534 5359/5361/11533 +f 5355/5357/11529 5357/5359/11531 5353/5355/11536 +f 5355/5357/11529 5361/5363/11535 5356/5358/11530 +f 5362/5364/11537 5363/5365/11538 5364/5366/11539 +f 5365/5367/11540 5363/5365/11538 5362/5364/11537 +f 5362/5364/11537 5366/5368/11541 5365/5367/11540 +f 5367/5369/11542 5364/5366/11542 5363/5365/11542 +f 5367/5369/11543 5363/5365/11543 5368/5370/11543 +f 5368/5370/11544 5363/5365/11545 5365/5367/11546 +f 5368/5370/11544 5365/5367/11546 5369/5371/11547 +f 5369/5371/11548 5365/5367/11549 5366/5368/11550 +f 5369/5371/11548 5366/5368/11550 5370/5372/11551 +f 5370/5372/11552 5366/5368/11553 5362/5364/11554 +f 5370/5372/11552 5362/5364/11554 5371/5373/11555 +f 5371/5373/11556 5362/5364/11556 5364/5366/11556 +f 5371/5373/11557 5364/5366/11557 5367/5369/11557 +f 5367/5369/11558 5372/5374/11559 5373/5375/11560 +f 5367/5369/11558 5373/5375/11560 5371/5373/11561 +f 5367/5369/11558 5374/5376/11562 5372/5374/11559 +f 5370/5372/11563 5375/5377/11564 5376/5378/11565 +f 5370/5372/11563 5376/5378/11565 5369/5371/11566 +f 5371/5373/11561 5377/5379/11567 5370/5372/11563 +f 5370/5372/11563 5377/5379/11567 5375/5377/11564 +f 5371/5373/11561 5373/5375/11560 5377/5379/11567 +f 5368/5370/11568 5378/5380/11569 5374/5376/11562 +f 5368/5370/11568 5374/5376/11562 5367/5369/11558 +f 5369/5371/11566 5376/5378/11565 5378/5380/11569 +f 5369/5371/11566 5378/5380/11569 5368/5370/11568 +f 5373/5375/11570 5354/5356/11571 5353/5355/11572 +f 5373/5375/11570 5353/5355/11572 5377/5379/11573 +f 5377/5379/11574 5353/5355/11575 5375/5377/11576 +f 5375/5377/11576 5353/5355/11575 5357/5359/11577 +f 5375/5377/11578 5357/5359/11579 5376/5378/11580 +f 5357/5359/11579 5356/5358/11581 5376/5378/11580 +f 5356/5358/11582 5361/5363/11583 5376/5378/11584 +f 5376/5378/11584 5361/5363/11583 5378/5380/11585 +f 5378/5380/11586 5361/5363/11587 5374/5376/11588 +f 5374/5376/11588 5361/5363/11587 5360/5362/11589 +f 5374/5376/11590 5360/5362/11591 5372/5374/11592 +f 5360/5362/11591 5358/5360/11593 5372/5374/11592 +f 5372/5374/11594 5358/5360/11595 5373/5375/11596 +f 5373/5375/11596 5358/5360/11595 5354/5356/11597 +f 5359/5361/11598 5355/5357/11599 5379/5381/11600 +f 5379/5381/11600 5355/5357/11599 5380/5382/11601 +f 5352/5354/11602 5359/5361/11602 5379/5381/11602 +f 5381/5383/11603 5352/5354/11604 5379/5381/11605 +f 5353/5355/11606 5352/5354/11604 5381/5383/11603 +f 5355/5357/11607 5353/5355/11607 5380/5382/11607 +f 5380/5382/11608 5353/5355/11608 5381/5383/11608 +f 5381/5383/2352 5379/5381/2352 5380/5382/2352 +f 5382/5384/11609 5383/5385/11610 5384/5386/11611 +f 5382/5384/11612 5384/5386/11612 5385/5387/11612 +f 5385/5387/11613 5384/5386/11613 5386/5388/11613 +f 5385/5387/11614 5386/5388/11614 5387/5389/11614 +f 5387/5389/11615 5386/5388/11615 5388/5390/11615 +f 5387/5389/11616 5388/5390/11616 5389/5391/11616 +f 5389/5391/11617 5388/5390/11617 5390/5392/11617 +f 5389/5391/11618 5390/5392/11619 5391/5393/11620 +f 5392/5394/11621 5391/5393/11621 5393/5395/11621 +f 5393/5395/11622 5391/5393/11620 5390/5392/11619 +f 5392/5394/11623 5393/5395/11624 5394/5396/11625 +f 5394/5396/11625 5393/5395/11624 5395/5397/11626 +f 5394/5396/11627 5395/5397/11627 5396/5398/11627 +f 5396/5398/11628 5395/5397/11628 5397/5399/11628 +f 5396/5398/11629 5397/5399/11629 5398/5400/11629 +f 5398/5400/11630 5397/5399/11630 5399/5401/11630 +f 5398/5400/11631 5399/5401/11631 5400/5402/11631 +f 5400/5402/11632 5399/5401/11632 5401/5403/11632 +f 5400/5402/11633 5401/5403/11633 5402/5404/11633 +f 5382/5384/11609 5402/5404/11634 5383/5385/11610 +f 5402/5404/11635 5382/5384/11636 5400/5402/11637 +f 5391/5393/3026 5392/5394/3026 5394/5396/3026 +f 5391/5393/3026 5394/5396/3026 5389/5391/3026 +f 5389/5391/3026 5394/5396/3026 5396/5398/3026 +f 5389/5391/3026 5396/5398/3026 5387/5389/3026 +f 5385/5387/3026 5398/5400/3026 5400/5402/11637 +f 5385/5387/3026 5400/5402/11637 5382/5384/11636 +f 5387/5389/3026 5396/5398/3026 5385/5387/3026 +f 5385/5387/3026 5396/5398/3026 5398/5400/3026 +f 5388/5390/3031 5395/5397/3031 5390/5392/3031 +f 5395/5397/3031 5393/5395/3031 5390/5392/3031 +f 5386/5388/3031 5397/5399/3031 5388/5390/3031 +f 5388/5390/3031 5397/5399/3031 5395/5397/3031 +f 5384/5386/3031 5399/5401/3031 5386/5388/3031 +f 5386/5388/3031 5399/5401/3031 5397/5399/3031 +f 5383/5385/11638 5402/5404/11639 5401/5403/11640 +f 5383/5385/11638 5401/5403/11640 5384/5386/3031 +f 5384/5386/3031 5401/5403/11640 5399/5401/3031 +f 5403/5405/11641 5404/5406/11641 5405/5407/11641 +f 5403/5405/11642 5405/5407/11643 5406/5408/11644 +f 5403/5405/11642 5406/5408/11644 5407/5409/11645 +f 5407/5409/11646 5406/5408/11647 5408/5410/11648 +f 5407/5409/11646 5408/5410/11648 5409/5411/11649 +f 5409/5411/11650 5408/5410/11651 5410/5412/11652 +f 5410/5412/11652 5408/5410/11651 5411/5413/11653 +f 5410/5412/11654 5411/5413/11654 5412/5414/11654 +f 5413/5415/11655 5412/5414/11655 5411/5413/11655 +f 5413/5415/11656 5414/5416/11656 5415/5417/11656 +f 5415/5417/11657 5414/5416/11658 5416/5418/11659 +f 5415/5417/11657 5416/5418/11659 5417/5419/11660 +f 5417/5419/11661 5416/5418/11662 5418/5420/11663 +f 5417/5419/11661 5418/5420/11663 5419/5421/11664 +f 5419/5421/11665 5418/5420/11665 5420/5422/11665 +f 5420/5422/11666 5418/5420/11666 5421/5423/11666 +f 5420/5422/11667 5421/5423/11667 5422/5424/11667 +f 5422/5424/11668 5421/5423/11668 5423/5425/11668 +f 5422/5424/11669 5423/5425/11669 5424/5426/11669 +f 5424/5426/11670 5423/5425/11670 5425/5427/11670 +f 5424/5426/11671 5425/5427/11671 5426/5428/11671 +f 5404/5406/11672 5426/5428/11672 5425/5427/11672 +f 5426/5428/11673 5404/5406/11673 5403/5405/11673 +f 5410/5412/11674 5415/5417/11675 5417/5419/3026 +f 5410/5412/11674 5417/5419/3026 5409/5411/3026 +f 5412/5414/11676 5413/5415/11677 5410/5412/11674 +f 5410/5412/11674 5413/5415/11677 5415/5417/11675 +f 5407/5409/3026 5422/5424/3026 5403/5405/3026 +f 5409/5411/3026 5417/5419/3026 5419/5421/3026 +f 5403/5405/3026 5424/5426/3026 5426/5428/3026 +f 5403/5405/3026 5422/5424/3026 5424/5426/3026 +f 5407/5409/3026 5420/5422/3026 5422/5424/3026 +f 5409/5411/3026 5419/5421/3026 5407/5409/3026 +f 5407/5409/3026 5419/5421/3026 5420/5422/3026 +f 5413/5415/11678 5411/5413/11679 5414/5416/11680 +f 5411/5413/11679 5416/5418/3031 5414/5416/11680 +f 5408/5410/3031 5416/5418/3031 5411/5413/11679 +f 5408/5410/3031 5418/5420/3031 5416/5418/3031 +f 5406/5408/3031 5418/5420/3031 5408/5410/3031 +f 5406/5408/3031 5421/5423/3031 5418/5420/3031 +f 5405/5407/11681 5421/5423/3031 5406/5408/3031 +f 5404/5406/11682 5425/5427/11683 5405/5407/11681 +f 5405/5407/11681 5423/5425/3031 5421/5423/3031 +f 5405/5407/11681 5425/5427/11683 5423/5425/3031 +f 5427/5429/11684 5428/5430/11685 5429/5431/11686 +f 5427/5429/11687 5429/5431/11687 5430/5432/11687 +f 5430/5432/11688 5429/5431/11688 5431/5433/11688 +f 5430/5432/11689 5431/5433/11690 5432/5434/11691 +f 5430/5432/11689 5432/5434/11691 5433/5435/11692 +f 5433/5435/11693 5432/5434/11693 5434/5436/11693 +f 5434/5436/11694 5432/5434/11694 5435/5437/11694 +f 5434/5436/11695 5435/5437/11696 5436/5438/11697 +f 5437/5439/11698 5436/5438/11698 5438/5440/11698 +f 5438/5440/11699 5436/5438/11697 5435/5437/11696 +f 5437/5439/11700 5438/5440/11700 5439/5441/11700 +f 5437/5439/11701 5439/5441/11701 5440/5442/11701 +f 5440/5442/11702 5439/5441/11702 5441/5443/11702 +f 5440/5442/11703 5441/5443/11704 5442/5444/11705 +f 5442/5444/11705 5441/5443/11704 5443/5445/11706 +f 5442/5444/11707 5443/5445/11707 5444/5446/11707 +f 5444/5446/11708 5443/5445/11708 5445/5447/11708 +f 5444/5446/11709 5445/5447/11709 5446/5448/11709 +f 5446/5448/11710 5445/5447/11710 5447/5449/11710 +f 5446/5448/11711 5447/5449/11711 5448/5450/11711 +f 5448/5450/11712 5447/5449/11712 5449/5451/11712 +f 5448/5450/11713 5449/5451/11713 5450/5452/11713 +f 5450/5452/11714 5449/5451/11714 5451/5453/11714 +f 5427/5429/11684 5450/5452/11715 5428/5430/11685 +f 5428/5430/11685 5450/5452/11715 5451/5453/11716 +f 5436/5438/3085 5437/5439/3085 5440/5442/3085 +f 5436/5438/3085 5440/5442/3085 5434/5436/3085 +f 5434/5436/3085 5440/5442/3085 5442/5444/3085 +f 5434/5436/3085 5442/5444/3085 5433/5435/3085 +f 5427/5429/3085 5448/5450/3085 5450/5452/3085 +f 5430/5432/3085 5446/5448/3085 5448/5450/3085 +f 5430/5432/3085 5448/5450/3085 5427/5429/3085 +f 5430/5432/3085 5444/5446/3085 5446/5448/3085 +f 5442/5444/3085 5444/5446/3085 5433/5435/3085 +f 5433/5435/3085 5444/5446/3085 5430/5432/3085 +f 5438/5440/2352 5435/5437/2352 5439/5441/2352 +f 5435/5437/2352 5441/5443/2352 5439/5441/2352 +f 5432/5434/2352 5441/5443/2352 5435/5437/2352 +f 5432/5434/2352 5443/5445/2352 5441/5443/2352 +f 5431/5433/2352 5445/5447/2352 5432/5434/2352 +f 5432/5434/2352 5445/5447/2352 5443/5445/2352 +f 5429/5431/2352 5447/5449/2352 5431/5433/2352 +f 5431/5433/2352 5447/5449/2352 5445/5447/2352 +f 5428/5430/2352 5451/5453/2352 5449/5451/2352 +f 5429/5431/2352 5449/5451/2352 5447/5449/2352 +f 5428/5430/2352 5449/5451/2352 5429/5431/2352 +f 5452/5454/11717 5453/5455/11718 5454/5456/11719 +f 5452/5454/11720 5454/5456/11720 5455/5457/11720 +f 5455/5457/11721 5454/5456/11721 5456/5458/11721 +f 5455/5457/11722 5456/5458/11722 5457/5459/11722 +f 5457/5459/11723 5456/5458/11723 5458/5460/11723 +f 5457/5459/11724 5458/5460/11724 5459/5461/11724 +f 5459/5461/11725 5458/5460/11725 5460/5462/11725 +f 5459/5461/11726 5460/5462/11726 5461/5463/11726 +f 5462/5464/11727 5461/5463/11727 5463/5465/11727 +f 5463/5465/11728 5461/5463/11728 5460/5462/11728 +f 5462/5464/11729 5463/5465/11730 5464/5466/11731 +f 5462/5464/11729 5464/5466/11731 5465/5467/11732 +f 5465/5467/11733 5464/5466/11734 5466/5468/11735 +f 5465/5467/11733 5466/5468/11735 5467/5469/11736 +f 5467/5469/11737 5466/5468/11738 5468/5470/11739 +f 5468/5470/11739 5466/5468/11738 5469/5471/11740 +f 5468/5470/11741 5469/5471/11742 5470/5472/11743 +f 5468/5470/11741 5470/5472/11743 5471/5473/11744 +f 5471/5473/11745 5470/5472/11745 5472/5474/11745 +f 5472/5474/11746 5470/5472/11746 5473/5475/11746 +f 5472/5474/11747 5473/5475/11747 5474/5476/11747 +f 5452/5454/11717 5474/5476/11748 5453/5455/11718 +f 5453/5455/11749 5474/5476/11749 5473/5475/11749 +f 5474/5476/3085 5452/5454/3085 5472/5474/3085 +f 5461/5463/3085 5462/5464/3085 5459/5461/3085 +f 5459/5461/3085 5462/5464/3085 5465/5467/3085 +f 5459/5461/3085 5467/5469/3085 5457/5459/3085 +f 5459/5461/3085 5465/5467/3085 5467/5469/3085 +f 5455/5457/3085 5471/5473/3085 5452/5454/3085 +f 5452/5454/3085 5471/5473/3085 5472/5474/3085 +f 5457/5459/3085 5468/5470/3085 5455/5457/3085 +f 5455/5457/3085 5468/5470/3085 5471/5473/3085 +f 5467/5469/3085 5468/5470/3085 5457/5459/3085 +f 5458/5460/2352 5464/5466/2352 5460/5462/2352 +f 5458/5460/2352 5466/5468/2352 5464/5466/2352 +f 5460/5462/2352 5464/5466/2352 5463/5465/2352 +f 5456/5458/2352 5469/5471/2352 5458/5460/2352 +f 5458/5460/2352 5469/5471/2352 5466/5468/2352 +f 5456/5458/2352 5470/5472/2352 5469/5471/2352 +f 5454/5456/2352 5470/5472/2352 5456/5458/2352 +f 5453/5455/2352 5473/5475/2352 5454/5456/2352 +f 5454/5456/2352 5473/5475/2352 5470/5472/2352 +f 5475/5477/11750 5476/5478/11751 5477/5479/11752 +f 5478/5480/11753 5479/5481/11754 5475/5477/11750 +f 5475/5477/11750 5479/5481/11754 5476/5478/11751 +f 5480/5482/11755 5481/5483/11756 5482/5484/11757 +f 5482/5484/11757 5481/5483/11756 5483/5485/11758 +f 5484/5486/11759 5485/5487/11760 5486/5488/11761 +f 5487/5489/11762 5488/5490/11763 5489/5491/11764 +f 5490/5492/11765 5491/5493/11766 5492/5494/11767 +f 5492/5494/11767 5491/5493/11766 5493/5495/11768 +f 5486/5488/11761 5485/5487/11760 5490/5492/11765 +f 5486/5488/11761 5490/5492/11765 5492/5494/11767 +f 5494/5496/11769 5495/5497/11770 5493/5495/11768 +f 5494/5496/11769 5491/5493/11766 5489/5491/11764 +f 5493/5495/11768 5495/5497/11770 5479/5481/11771 +f 5491/5493/11766 5494/5496/11769 5493/5495/11768 +f 5489/5491/11764 5488/5490/11763 5494/5496/11769 +f 5496/5498/11772 5497/5499/11773 5498/5500/11774 +f 5496/5498/11772 5498/5500/11774 5499/5501/11775 +f 5499/5501/11775 5498/5500/11774 5500/5502/11776 +f 5500/5502/11776 5498/5500/11774 5501/5503/11777 +f 5500/5502/11776 5501/5503/11777 5502/5504/11778 +f 5500/5502/11776 5502/5504/11778 5503/5505/11779 +f 5504/5506/11780 5505/5507/11781 5506/5508/11782 +f 5504/5506/11780 5506/5508/11782 5507/5509/11783 +f 5507/5509/11783 5506/5508/11782 5508/5510/11784 +f 5507/5509/11783 5508/5510/11784 5509/5511/11785 +f 5509/5511/11785 5508/5510/11784 5510/5512/11786 +f 5510/5512/11786 5508/5510/11784 5511/5513/11787 +f 5510/5512/11786 5511/5513/11787 5512/5514/11788 +f 5512/5514/11788 5511/5513/11787 5513/5515/11789 +f 5514/5516/11790 5515/5517/11791 5516/5518/11792 +f 5517/5519/11793 5518/5520/11794 5519/5521/11795 +f 5520/5522/11796 5521/5523/11797 5522/5524/11798 +f 5523/5525/11799 5524/5526/11800 5525/5527/11801 +f 5523/5525/11799 5521/5523/11797 5520/5522/11796 +f 5522/5524/11798 5515/5517/11791 5520/5522/11796 +f 5520/5522/11796 5515/5517/11791 5514/5516/11790 +f 5523/5525/11799 5481/5483/11802 5524/5526/11800 +f 5518/5520/11794 5526/5528/11803 5519/5521/11795 +f 5523/5525/11799 5525/5527/11801 5521/5523/11797 +f 5519/5521/11795 5526/5528/11803 5525/5527/11801 +f 5525/5527/11801 5526/5528/11803 5521/5523/11797 +f 5527/5529/11804 5528/5530/11805 5529/5531/11806 +f 5529/5531/11806 5528/5530/11805 5530/5532/11807 +f 5529/5531/11806 5530/5532/11807 5531/5533/11808 +f 5531/5533/11808 5530/5532/11807 5532/5534/11809 +f 5531/5533/11808 5532/5534/11809 5533/5535/11810 +f 5533/5535/11810 5532/5534/11809 5534/5536/11811 +f 5534/5536/11811 5532/5534/11809 5535/5537/11812 +f 5536/5538/11813 5537/5539/11814 5538/5540/11815 +f 5538/5540/11815 5537/5539/11814 5539/5541/11816 +f 5538/5540/11815 5539/5541/11816 5540/5542/11817 +f 5540/5542/11817 5539/5541/11816 5541/5543/11818 +f 5540/5542/11817 5541/5543/11818 5542/5544/11819 +f 5542/5544/11819 5541/5543/11818 5543/5545/11820 +f 5542/5544/11819 5543/5545/11820 5544/5546/11821 +f 5544/5546/11821 5543/5545/11820 5545/5547/11822 +f 5544/5546/11821 5545/5547/11822 5546/5548/11823 +f 5546/5548/11823 5545/5547/11822 5547/5549/11824 +f 5546/5548/11823 5547/5549/11824 5548/5550/11825 +f 5548/5550/11825 5547/5549/11824 5549/5551/11826 +f 5548/5550/11825 5549/5551/11826 5550/5552/11827 +f 5548/5550/11825 5550/5552/11827 5551/5553/11828 +f 5551/5553/11828 5550/5552/11827 5552/5554/11829 +f 5551/5553/11828 5552/5554/11829 5553/5555/11830 +f 5553/5555/11830 5552/5554/11829 5554/5556/11831 +f 5555/5557/11832 5492/5494/11767 5493/5495/11768 +f 5556/5558/11833 5557/5559/11834 5555/5557/11832 +f 5555/5557/11832 5557/5559/11834 5492/5494/11767 +f 5558/5560/11835 5557/5559/11834 5556/5558/11833 +f 5557/5559/11834 5558/5560/11835 5559/5561/11836 +f 5558/5560/11835 5560/5562/11837 5559/5561/11836 +f 5561/5563/11838 5562/5564/11839 5560/5562/11837 +f 5560/5562/11837 5562/5564/11839 5559/5561/11836 +f 5562/5564/11839 5561/5563/11838 5563/5565/11840 +f 5564/5566/11841 5520/5522/11796 5563/5565/11840 +f 5563/5565/11840 5520/5522/11796 5562/5564/11839 +f 5523/5525/11799 5520/5522/11796 5564/5566/11841 +f 5565/5567/11842 5566/5568/11843 5567/5569/11844 +f 5567/5569/11844 5566/5568/11843 5568/5570/11845 +f 5567/5569/11844 5568/5570/11845 5569/5571/11846 +f 5569/5571/11846 5568/5570/11845 5570/5572/11847 +f 5569/5571/11846 5570/5572/11847 5571/5573/11848 +f 5569/5571/11846 5571/5573/11848 5572/5574/11849 +f 5573/5575/11850 5572/5574/11851 5574/5576/11852 +f 5575/5577/11853 5503/5505/11854 5576/5578/11855 +f 5576/5578/11855 5503/5505/11854 5577/5579/11856 +f 5499/5501/11857 5503/5505/11854 5575/5577/11853 +f 5577/5579/11856 5578/5580/11858 5565/5567/11859 +f 5565/5567/11859 5576/5578/11855 5577/5579/11856 +f 5576/5578/11855 5565/5567/11859 5579/5581/11860 +f 5567/5569/11861 5569/5571/11862 5565/5567/11859 +f 5580/5582/11863 5581/5583/11864 5496/5498/11865 +f 5582/5584/11866 5569/5571/11862 5573/5575/11850 +f 5573/5575/11850 5569/5571/11862 5572/5574/11851 +f 5565/5567/11859 5582/5584/11866 5579/5581/11860 +f 5565/5567/11859 5569/5571/11862 5582/5584/11866 +f 5499/5501/11857 5500/5502/11867 5503/5505/11854 +f 5580/5582/11863 5496/5498/11865 5583/5585/11868 +f 5583/5585/11868 5496/5498/11865 5499/5501/11857 +f 5583/5585/11868 5499/5501/11857 5575/5577/11853 +f 5584/5586/98 5585/5587/98 5586/5588/98 +f 5504/5506/11869 5509/5511/11870 5587/5589/11871 +f 5531/5533/11872 5533/5535/11873 5534/5536/11874 +f 5588/5590/11875 5589/5591/11876 5590/5592/11877 +f 5588/5590/11875 5590/5592/11877 5591/5593/11878 +f 5591/5593/11878 5590/5592/11877 5527/5529/11879 +f 5512/5514/11880 5592/5594/11881 5593/5595/11882 +f 5594/5596/11883 5534/5536/11874 5595/5597/11884 +f 5531/5533/11872 5534/5536/11874 5594/5596/11883 +f 5593/5595/11882 5592/5594/11881 5596/5598/11885 +f 5596/5598/11885 5592/5594/11881 5597/5599/11886 +f 5598/5600/11887 5504/5506/11869 5595/5597/11884 +f 5534/5536/11874 5599/5601/11888 5598/5600/11887 +f 5504/5506/11869 5507/5509/11889 5509/5511/11870 +f 5512/5514/11880 5593/5595/11882 5600/5602/11890 +f 5531/5533/11872 5594/5596/11883 5601/5603/11891 +f 5509/5511/11870 5600/5602/11890 5587/5589/11871 +f 5591/5593/11878 5527/5529/11879 5601/5603/11891 +f 5601/5603/11891 5527/5529/11879 5529/5531/11892 +f 5510/5512/11893 5512/5514/11880 5600/5602/11890 +f 5595/5597/11884 5534/5536/11874 5598/5600/11887 +f 5600/5602/11890 5509/5511/11870 5510/5512/11893 +f 5601/5603/11891 5529/5531/11892 5531/5533/11872 +f 5517/5519/11793 5602/5604/11894 5480/5482/11755 +f 5516/5518/11792 5603/5605/11895 5604/5606/11896 +f 5605/5607/11897 5606/5608/11898 5482/5484/11899 +f 5482/5484/11899 5606/5608/11898 5514/5516/11900 +f 5536/5538/11901 5538/5540/11902 5607/5609/11903 +f 5607/5609/11903 5538/5540/11902 5608/5610/11904 +f 5608/5610/11904 5538/5540/11902 5540/5542/11905 +f 5608/5610/11904 5540/5542/11905 5609/5611/11906 +f 5540/5542/11905 5542/5544/11907 5609/5611/11906 +f 5609/5611/11906 5542/5544/11907 5610/5612/11908 +f 5610/5612/11908 5542/5544/11907 5544/5546/11909 +f 5610/5612/11908 5544/5546/11909 5611/5613/11910 +f 5611/5613/11910 5544/5546/11909 5546/5548/11911 +f 5546/5548/11911 5548/5550/11912 5611/5613/11910 +f 5611/5613/11910 5548/5550/11912 5612/5614/11913 +f 5612/5614/11913 5548/5550/11912 5613/5615/11914 +f 5613/5615/11914 5548/5550/11912 5551/5553/11915 +f 5613/5615/11914 5551/5553/11915 5614/5616/11916 +f 5614/5616/11916 5551/5553/11915 5553/5555/11917 +f 5537/5539/11918 5580/5582/11919 5583/5585/11920 +f 5541/5543/11921 5575/5577/11922 5543/5545/11923 +f 5539/5541/11924 5537/5539/11918 5583/5585/11920 +f 5539/5541/11924 5583/5585/11920 5541/5543/11921 +f 5541/5543/11921 5583/5585/11920 5575/5577/11922 +f 5543/5545/11923 5575/5577/11922 5576/5578/11925 +f 5543/5545/11923 5576/5578/11925 5545/5547/11926 +f 5545/5547/11926 5576/5578/11925 5579/5581/11927 +f 5545/5547/11926 5579/5581/11927 5547/5549/11928 +f 5547/5549/11928 5579/5581/11927 5582/5584/11929 +f 5547/5549/11928 5582/5584/11929 5549/5551/11930 +f 5549/5551/11930 5582/5584/11929 5550/5552/11931 +f 5552/5554/11932 5573/5575/11933 5574/5576/11934 +f 5552/5554/11932 5574/5576/11934 5554/5556/11935 +f 5550/5552/11931 5582/5584/11929 5573/5575/11933 +f 5550/5552/11931 5573/5575/11933 5552/5554/11932 +f 5526/5528/11936 5518/5520/11936 5615/5617/11936 +f 5526/5528/11937 5615/5617/11938 5521/5523/11939 +f 5521/5523/11939 5615/5617/11938 5604/5606/11940 +f 5521/5523/11941 5604/5606/11941 5522/5524/11941 +f 5522/5524/11942 5604/5606/11942 5603/5605/11942 +f 5522/5524/11943 5603/5605/11943 5515/5517/11943 +f 5515/5517/11944 5603/5605/11944 5516/5518/11944 +f 5481/5483/11945 5616/5618/11946 5602/5604/11947 +f 5481/5483/11945 5602/5604/11947 5524/5526/11948 +f 5524/5526/11949 5602/5604/11949 5525/5527/11949 +f 5525/5527/11950 5602/5604/11950 5617/5619/11950 +f 5525/5527/11951 5617/5619/11951 5519/5521/11951 +f 5519/5521/11952 5617/5619/11952 5517/5519/11952 +f 5616/5618/11953 5481/5483/11953 5480/5482/11953 +f 5516/5518/11792 5604/5606/11896 5518/5520/11794 +f 5618/5620/11954 5619/5621/11955 5620/5622/11956 +f 5619/5621/11955 5621/5623/11957 5606/5608/11958 +f 5620/5622/11956 5622/5624/11959 5618/5620/11954 +f 5602/5604/11894 5616/5618/11960 5480/5482/11755 +f 5617/5619/11961 5602/5604/11894 5517/5519/11793 +f 5518/5520/11794 5604/5606/11896 5615/5617/11962 +f 5619/5621/11955 5606/5608/11958 5620/5622/11956 +f 5620/5622/11963 5606/5608/11964 5605/5607/11965 +f 5480/5482/11755 5514/5516/11790 5516/5518/11792 +f 5480/5482/11755 5516/5518/11792 5517/5519/11793 +f 5516/5518/11792 5518/5520/11794 5517/5519/11793 +f 5480/5482/11755 5482/5484/11757 5514/5516/11790 +f 5581/5583/11966 5605/5607/11965 5497/5499/11773 +f 5581/5583/11966 5497/5499/11773 5496/5498/11772 +f 5605/5607/11965 5581/5583/11966 5620/5622/11963 +f 5581/5583/11967 5580/5582/11919 5622/5624/11968 +f 5622/5624/11968 5620/5622/11969 5581/5583/11967 +f 5618/5620/11970 5580/5582/11919 5537/5539/11918 +f 5580/5582/11919 5618/5620/11970 5622/5624/11968 +f 5619/5621/11971 5618/5620/11972 5536/5538/11973 +f 5536/5538/11973 5618/5620/11972 5537/5539/11974 +f 5619/5621/11975 5536/5538/11976 5621/5623/11977 +f 5621/5623/11977 5536/5538/11976 5607/5609/11978 +f 5623/5625/11979 5624/5626/11980 5488/5490/11981 +f 5476/5478/11751 5625/5627/11982 5626/5628/11983 +f 5475/5477/11984 5627/5629/11985 5628/5630/11986 +f 5628/5630/11986 5627/5629/11985 5629/5631/11987 +f 5485/5487/11988 5630/5632/11988 5490/5492/11988 +f 5490/5492/11989 5630/5632/11989 5631/5633/11989 +f 5490/5492/11990 5631/5633/11990 5491/5493/11990 +f 5491/5493/11991 5631/5633/11991 5632/5634/11991 +f 5491/5493/11992 5632/5634/11993 5489/5491/11994 +f 5489/5491/11994 5632/5634/11993 5633/5635/11995 +f 5489/5491/11996 5633/5635/11996 5487/5489/11996 +f 5630/5632/11997 5485/5487/11760 5631/5633/11998 +f 5631/5633/11998 5485/5487/11760 5484/5486/11759 +f 5634/5636/11999 5635/5637/12000 5636/5638/12001 +f 5629/5631/12002 5637/5639/12003 5634/5636/11999 +f 5488/5490/11981 5477/5479/11752 5626/5628/11983 +f 5488/5490/11981 5626/5628/11983 5623/5625/11979 +f 5477/5479/11752 5476/5478/11751 5626/5628/11983 +f 5631/5633/11998 5484/5486/11759 5632/5634/12004 +f 5632/5634/12004 5484/5486/11759 5487/5489/11762 +f 5632/5634/12004 5487/5489/11762 5633/5635/12005 +f 5638/5640/12006 5636/5638/12001 5635/5637/12000 +f 5629/5631/12002 5634/5636/11999 5636/5638/12001 +f 5626/5628/12007 5625/5627/12007 5479/5481/12007 +f 5479/5481/12008 5625/5627/12008 5476/5478/12008 +f 5494/5496/12009 5488/5490/12009 5624/5626/12009 +f 5494/5496/12010 5624/5626/12010 5623/5625/12010 +f 5494/5496/12011 5623/5625/12011 5495/5497/12011 +f 5495/5497/12012 5623/5625/12012 5626/5628/12012 +f 5626/5628/12013 5479/5481/12013 5495/5497/12013 +f 5636/5638/12014 5628/5630/12015 5629/5631/12016 +f 5475/5477/12017 5477/5479/12017 5488/5490/12017 +f 5488/5490/11763 5487/5489/11762 5484/5486/11759 +f 5488/5490/11763 5484/5486/11759 5475/5477/12018 +f 5484/5486/12019 5486/5488/12019 5475/5477/12019 +f 5475/5477/11984 5486/5488/12020 5627/5629/11985 +f 5572/5574/12021 5571/5573/12022 5628/5630/12015 +f 5636/5638/12014 5572/5574/12021 5628/5630/12015 +f 5574/5576/11852 5572/5574/11851 5636/5638/12023 +f 5574/5576/11852 5636/5638/12023 5638/5640/12024 +f 5638/5640/12025 5554/5556/12026 5574/5576/12027 +f 5635/5637/12028 5554/5556/12026 5638/5640/12025 +f 5553/5555/12029 5554/5556/12026 5634/5636/12030 +f 5634/5636/12030 5554/5556/12026 5635/5637/12028 +f 5553/5555/12031 5637/5639/12032 5614/5616/12033 +f 5553/5555/12031 5634/5636/12034 5637/5639/12032 +f 5639/5641/12035 5599/5601/12036 5534/5536/11811 +f 5639/5641/12035 5534/5536/11811 5535/5537/11812 +f 5640/5642/12037 5598/5600/12038 5599/5601/12039 +f 5640/5642/12037 5599/5601/12039 5639/5641/12040 +f 5505/5507/12041 5504/5506/12042 5640/5642/12043 +f 5640/5642/12043 5504/5506/12042 5598/5600/12044 +f 5587/5589/11871 5595/5597/11884 5504/5506/11869 +f 5566/5568/12045 5641/5643/12046 5642/5644/12047 +f 5643/5645/12048 5535/5537/12049 5644/5646/12050 +f 5645/5647/12051 5646/5648/12052 5506/5508/12053 +f 5646/5648/12052 5647/5649/12054 5508/5510/12055 +f 5644/5646/12050 5532/5534/12056 5648/5650/12057 +f 5649/5651/12058 5628/5630/12059 5571/5573/12060 +f 5530/5532/12061 5648/5650/12057 5532/5534/12056 +f 5508/5510/12055 5647/5649/12054 5650/5652/12062 +f 5511/5513/12063 5650/5652/12062 5651/5653/12064 +f 5652/5654/12065 5653/5655/12066 5530/5532/12061 +f 5511/5513/12063 5508/5510/12055 5650/5652/12062 +f 5506/5508/12053 5505/5507/12067 5645/5647/12051 +f 5653/5655/12066 5648/5650/12057 5530/5532/12061 +f 5513/5515/12068 5511/5513/12063 5651/5653/12064 +f 5652/5654/12065 5530/5532/12061 5528/5530/12069 +f 5643/5645/12048 5645/5647/12051 5505/5507/12067 +f 5535/5537/12049 5643/5645/12048 5639/5641/12070 +f 5654/5656/12071 5592/5594/12072 5513/5515/12073 +f 5513/5515/12073 5592/5594/12072 5512/5514/12074 +f 5592/5594/12075 5654/5656/12076 5655/5657/12077 +f 5592/5594/12075 5655/5657/12077 5597/5599/12078 +f 5597/5599/12079 5655/5657/12080 5656/5658/12081 +f 5657/5659/12082 5577/5579/12083 5502/5504/12084 +f 5502/5504/12084 5577/5579/12083 5503/5505/12085 +f 5658/5660/12086 5578/5580/12087 5657/5659/12088 +f 5657/5659/12088 5578/5580/12087 5577/5579/12089 +f 5566/5568/12090 5565/5567/12091 5658/5660/12092 +f 5658/5660/12092 5565/5567/12091 5578/5580/12093 +f 5589/5591/12094 5659/5661/12095 5660/5662/12096 +f 5660/5662/12097 5659/5661/12098 5661/5663/12099 +f 5660/5662/12097 5661/5663/12099 5590/5592/12100 +f 5528/5530/12101 5527/5529/12102 5661/5663/12103 +f 5661/5663/12103 5527/5529/12102 5590/5592/12104 +f 5593/5595/12105 5662/5664/12106 5663/5665/12107 +f 5593/5595/12105 5663/5665/12107 5664/5666/12108 +f 5664/5666/12109 5663/5665/12109 5665/5667/12109 +f 5664/5666/12110 5665/5667/12110 5596/5598/12110 +f 5666/5668/12111 5596/5598/12111 5665/5667/12111 +f 5662/5664/12112 5593/5595/12113 5596/5598/12114 +f 5662/5664/12112 5596/5598/12114 5666/5668/12115 +f 5588/5590/12116 5585/5587/12117 5584/5586/12118 +f 5588/5590/12116 5584/5586/12118 5667/5669/12119 +f 5667/5669/12120 5584/5586/12121 5586/5588/12122 +f 5586/5588/12122 5591/5593/12123 5667/5669/12120 +f 5585/5587/12124 5588/5590/12125 5591/5593/12126 +f 5585/5587/12124 5591/5593/12126 5586/5588/12127 +f 5656/5658/12128 5596/5598/11885 5597/5599/11886 +f 5656/5658/12128 5664/5666/12129 5596/5598/11885 +f 5664/5666/12129 5656/5658/12128 5668/5670/12130 +f 5600/5602/11890 5664/5666/12129 5669/5671/12131 +f 5600/5602/11890 5593/5595/11882 5664/5666/12129 +f 5669/5671/12131 5668/5670/12130 5523/5525/12132 +f 5523/5525/12132 5668/5670/12130 5481/5483/12133 +f 5669/5671/12131 5664/5666/12129 5668/5670/12130 +f 5556/5558/11833 5670/5672/12134 5558/5560/11835 +f 5555/5557/12135 5601/5603/11891 5670/5672/12134 +f 5555/5557/12135 5670/5672/12134 5556/5558/11833 +f 5560/5562/12136 5595/5597/12137 5561/5563/12138 +f 5561/5563/12138 5587/5589/12139 5563/5565/12140 +f 5564/5566/12141 5669/5671/12131 5523/5525/12132 +f 5493/5495/11768 5601/5603/11891 5555/5557/12135 +f 5558/5560/12142 5595/5597/12137 5560/5562/12136 +f 5561/5563/12138 5595/5597/12137 5587/5589/12139 +f 5558/5560/12143 5670/5672/12143 5594/5596/12143 +f 5558/5560/12142 5594/5596/12144 5595/5597/12137 +f 5563/5565/12140 5587/5589/12139 5600/5602/11890 +f 5563/5565/12140 5600/5602/11890 5564/5566/12141 +f 5564/5566/12141 5600/5602/11890 5669/5671/12131 +f 5670/5672/12134 5601/5603/11891 5594/5596/12145 +f 5591/5593/11878 5601/5603/11891 5667/5669/12146 +f 5589/5591/12147 5588/5590/12148 5671/5673/12149 +f 5671/5673/12149 5588/5590/12148 5667/5669/12146 +f 5671/5673/12149 5667/5669/12146 5601/5603/11891 +f 5671/5673/12149 5601/5603/11891 5493/5495/11768 +f 5671/5673/12149 5493/5495/11768 5479/5481/11771 +f 5656/5658/12081 5655/5657/12080 5672/5674/12150 +f 5672/5674/12150 5668/5670/12151 5656/5658/12081 +f 5668/5670/12151 5672/5674/12150 5483/5485/11758 +f 5668/5670/12151 5483/5485/11758 5481/5483/11756 +f 5479/5481/11754 5478/5480/11753 5671/5673/12152 +f 5673/5675/12153 5671/5673/12152 5478/5480/11753 +f 5673/5675/12153 5589/5591/12094 5671/5673/12152 +f 5589/5591/12094 5673/5675/12153 5659/5661/12095 +f 5627/5629/12154 5486/5488/12154 5492/5494/12154 +f 4590/4592/12155 5649/5651/12155 5674/5676/12155 +f 5589/5591/11876 5660/5662/12156 5590/5592/11877 +f 5675/5677/12157 5676/5678/12158 5677/5679/12159 +f 5678/5680/12160 5675/5677/12157 5679/5681/12161 +f 5679/5681/12161 5680/5682/12162 5678/5680/12160 +f 5676/5678/12158 5681/5683/12163 5677/5679/12159 +f 5682/5684/12164 5683/5685/12165 5684/5686/12166 +f 5681/5683/12163 5683/5685/12165 5677/5679/12159 +f 5677/5679/12159 5683/5685/12165 5682/5684/12164 +f 5682/5684/12164 5684/5686/12166 5680/5682/12162 +f 5682/5684/12164 5680/5682/12162 5679/5681/12161 +f 5679/5681/12161 5675/5677/12157 5677/5679/12159 +f 5685/5687/12167 5686/5688/12168 5687/5689/12169 +f 5687/5689/12169 5688/5690/12170 5685/5687/12167 +f 5689/5691/12171 5688/5690/12170 5687/5689/12169 +f 5690/5692/12172 5688/5690/12173 5689/5691/12174 +f 5690/5692/12172 5689/5691/12174 5691/5693/12175 +f 5691/5693/12176 5689/5691/12177 5687/5689/12178 +f 5691/5693/12176 5687/5689/12178 5692/5694/12179 +f 5692/5694/12180 5687/5689/12181 5686/5688/12182 +f 5692/5694/12180 5686/5688/12182 5693/5695/12183 +f 5693/5695/12184 5686/5688/12185 5694/5696/12186 +f 5694/5696/12186 5686/5688/12185 5685/5687/12187 +f 5694/5696/12188 5685/5687/12189 5688/5690/12190 +f 5694/5696/12188 5688/5690/12190 5690/5692/12191 +f 5691/5693/12192 5695/5697/12193 5690/5692/12194 +f 5690/5692/12194 5695/5697/12193 5696/5698/12195 +f 5691/5693/12192 5697/5699/12196 5695/5697/12193 +f 5694/5696/12197 5698/5700/12198 5693/5695/12199 +f 5693/5695/12199 5698/5700/12198 5699/5701/12200 +f 5694/5696/12197 5696/5698/12195 5698/5700/12198 +f 5690/5692/12194 5696/5698/12195 5694/5696/12197 +f 5692/5694/12201 5700/5702/12202 5697/5699/12196 +f 5692/5694/12201 5697/5699/12196 5691/5693/12192 +f 5693/5695/12199 5699/5701/12200 5692/5694/12201 +f 5692/5694/12201 5699/5701/12200 5700/5702/12202 +f 5696/5698/12203 5695/5697/12204 5676/5678/12205 +f 5696/5698/12206 5676/5678/12206 5675/5677/12206 +f 5696/5698/12207 5675/5677/12208 5698/5700/12209 +f 5675/5677/12208 5678/5680/12210 5698/5700/12209 +f 5698/5700/12211 5678/5680/12212 5699/5701/12213 +f 5678/5680/12212 5680/5682/12214 5699/5701/12213 +f 5699/5701/12215 5680/5682/12216 5684/5686/12217 +f 5699/5701/12215 5684/5686/12217 5700/5702/12218 +f 5700/5702/12219 5684/5686/12220 5683/5685/12221 +f 5700/5702/12219 5683/5685/12221 5697/5699/12222 +f 5697/5699/12223 5683/5685/12224 5695/5697/12225 +f 5683/5685/12224 5681/5683/12226 5695/5697/12225 +f 5695/5697/12204 5681/5683/12227 5676/5678/12205 +f 5682/5684/12228 5679/5681/12229 5701/5703/12230 +f 5701/5703/12230 5679/5681/12229 5702/5704/12231 +f 5677/5679/12232 5682/5684/12232 5703/5705/12232 +f 5703/5705/12233 5682/5684/12233 5701/5703/12233 +f 5704/5706/12234 5677/5679/12234 5703/5705/12234 +f 5679/5681/12235 5677/5679/12235 5704/5706/12235 +f 5702/5704/12236 5679/5681/12236 5704/5706/12236 +f 5704/5706/2352 5703/5705/2352 5701/5703/2352 +f 5704/5706/2352 5701/5703/2352 5702/5704/2352 +f 5705/5707/12237 5706/5708/12238 5707/5709/12239 +f 5708/5710/12240 5709/5711/12241 5710/5712/12242 +f 5707/5709/12239 5711/5713/12243 5705/5707/12237 +f 5710/5712/12242 5712/5714/12244 5713/5715/12245 +f 5705/5707/12237 5711/5713/12243 5712/5714/12246 +f 5710/5712/12242 5709/5711/12241 5706/5708/12247 +f 5706/5708/12247 5709/5711/12241 5714/5716/12248 +f 5713/5715/12245 5708/5710/12240 5710/5712/12242 +f 5715/5717/12249 5716/5718/12250 5717/5719/12251 +f 5718/5720/12252 5719/5721/12253 5715/5717/12249 +f 5717/5719/12251 5718/5720/12252 5715/5717/12249 +f 5720/5722/12254 5717/5719/12254 5716/5718/12254 +f 5720/5722/12255 5716/5718/12256 5715/5717/12257 +f 5720/5722/12255 5715/5717/12257 5721/5723/12258 +f 5721/5723/12259 5715/5717/12260 5719/5721/12261 +f 5721/5723/12259 5719/5721/12261 5722/5724/12262 +f 5722/5724/12263 5719/5721/12263 5723/5725/12263 +f 5723/5725/12264 5719/5721/12264 5718/5720/12264 +f 5723/5725/12265 5718/5720/12265 5724/5726/12265 +f 5724/5726/12266 5718/5720/12267 5717/5719/12268 +f 5724/5726/12266 5717/5719/12268 5720/5722/12269 +f 5720/5722/12270 5725/5727/12271 5726/5728/12272 +f 5720/5722/12270 5726/5728/12272 5724/5726/12273 +f 5720/5722/12270 5727/5729/12274 5725/5727/12271 +f 5723/5725/12275 5728/5730/12276 5729/5731/12277 +f 5723/5725/12275 5729/5731/12277 5722/5724/12278 +f 5724/5726/12273 5730/5732/12279 5723/5725/12275 +f 5723/5725/12275 5730/5732/12279 5728/5730/12276 +f 5724/5726/12273 5726/5728/12272 5731/5733/12280 +f 5724/5726/12273 5731/5733/12280 5730/5732/12279 +f 5721/5723/12281 5732/5734/12282 5727/5729/12274 +f 5721/5723/12281 5727/5729/12274 5720/5722/12270 +f 5722/5724/12278 5729/5731/12277 5732/5734/12282 +f 5722/5724/12278 5732/5734/12282 5721/5723/12281 +f 5726/5728/12283 5707/5709/12284 5706/5708/12285 +f 5726/5728/12283 5706/5708/12285 5731/5733/12286 +f 5731/5733/12287 5706/5708/12288 5730/5732/12289 +f 5706/5708/12288 5714/5716/12290 5730/5732/12289 +f 5730/5732/12291 5714/5716/12292 5709/5711/12293 +f 5730/5732/12291 5709/5711/12293 5728/5730/12294 +f 5728/5730/12295 5709/5711/12296 5729/5731/12297 +f 5709/5711/12296 5708/5710/12298 5729/5731/12297 +f 5708/5710/12299 5713/5715/12300 5729/5731/12301 +f 5729/5731/12301 5713/5715/12300 5732/5734/12302 +f 5732/5734/12303 5713/5715/12304 5712/5714/12305 +f 5732/5734/12303 5712/5714/12305 5727/5729/12306 +f 5727/5729/12307 5712/5714/12308 5711/5713/12309 +f 5727/5729/12307 5711/5713/12309 5725/5727/12310 +f 5725/5727/12311 5711/5713/12312 5707/5709/12313 +f 5725/5727/12311 5707/5709/12313 5726/5728/12314 +f 5733/5735/12315 5710/5712/12315 5734/5736/12315 +f 5712/5714/12316 5710/5712/12316 5735/5737/12316 +f 5735/5737/12317 5710/5712/12317 5733/5735/12317 +f 5705/5707/12318 5712/5714/12319 5735/5737/12320 +f 5736/5738/12321 5705/5707/12318 5735/5737/12320 +f 5706/5708/12322 5705/5707/12322 5734/5736/12322 +f 5734/5736/12323 5705/5707/12323 5736/5738/12323 +f 5710/5712/12324 5706/5708/12324 5734/5736/12324 +f 5736/5738/3026 5735/5737/3026 5734/5736/3026 +f 5734/5736/3026 5735/5737/3026 5733/5735/3026 +f 4728/4730/12325 4726/4728/12326 5131/5133/12327 +f 4726/4728/12326 4936/4938/12328 5156/5158/12329 +f 5159/5161/12330 5156/5158/12329 4936/4938/12328 +f 4936/4938/12328 4724/4726/12331 5159/5161/12330 +f 4726/4728/12326 5156/5158/12329 5131/5133/12327 +f 4928/4930/12332 4913/4915/12333 5152/5154/12334 +f 5152/5154/12334 4852/4854/12335 4929/4931/12336 +f 4928/4930/12332 5152/5154/12334 4929/4931/12336 +f 5148/5150/528 5150/5152/528 5149/5151/528 +f 5151/5153/528 5150/5152/528 5148/5150/528 +f 5147/5149/528 5146/5148/528 5144/5146/528 +f 5144/5146/528 5145/5147/528 5147/5149/528 +f 5176/5178/528 5173/5175/528 5177/5179/528 +f 5173/5175/528 5176/5178/528 5174/5176/528 +f 5176/5178/528 5175/5177/528 5174/5176/528 +f 4739/4741/12337 4744/4746/12337 5737/5739/12337 +f 5643/5645/12338 4955/4957/12338 4957/4959/12338 +f 5651/5653/12339 4993/4995/12340 4740/4742/12341 +f 4993/4995/12342 5651/5653/12343 4990/4992/12344 +f 5651/5653/12343 5650/5652/12345 4990/4992/12344 +f 5644/5646/12346 5648/5650/12346 4578/4580/12346 +f 5647/5649/12347 5646/5648/12348 4990/4992/12349 +f 5646/5648/12350 5645/5647/12350 4986/4988/12350 +f 5653/5655/12351 4510/4512/12352 4578/4580/12353 +f 5643/5645/12354 5644/5646/12354 4955/4957/12354 +f 5653/5655/12351 5652/5654/12355 4510/4512/12352 +f 4583/4585/12356 5649/5651/12357 4581/4583/12358 +f 5642/5644/12359 4584/4586/12359 4586/4588/12359 +f 5642/5644/12360 4587/4589/12361 4584/4586/12362 +f 5652/5654/12363 4583/4585/10633 4509/4511/10634 +f 4741/4743/12364 4587/4589/12364 5641/5643/12364 +f 5652/5654/12355 4509/4511/12365 4510/4512/12352 +f 5737/5739/12366 4744/4746/12366 5738/5740/12366 +f 5739/5741/12367 4739/4741/12367 5737/5739/12367 +f 4740/4742/12368 4739/4741/12368 5739/5741/12368 +f 5644/5646/12369 4578/4580/12369 4955/4957/12369 +f 5645/5647/12370 4987/4989/12370 4986/4988/12370 +f 5645/5647/12371 5643/5645/12372 4987/4989/10914 +f 5739/5741/12373 5651/5653/12339 4740/4742/12341 +f 4957/4959/10913 4987/4989/10914 5643/5645/12372 +f 5648/5650/12374 5653/5655/12374 4578/4580/12374 +f 5646/5648/12348 4986/4988/12375 4990/4992/12349 +f 4583/4585/10633 5652/5654/12363 5649/5651/12376 +f 4581/4583/12358 5649/5651/12357 4590/4592/12377 +f 4590/4592/12378 5674/5676/12378 4586/4588/12378 +f 5674/5676/12379 5642/5644/12379 4586/4588/12379 +f 5642/5644/12360 5641/5643/12380 4587/4589/12361 +f 4744/4746/12381 4741/4743/12382 5738/5740/12383 +f 5650/5652/12384 5647/5649/12384 4990/4992/12384 +f 5559/5561/12385 5562/5564/12386 5557/5559/12387 +f 5557/5559/12387 5562/5564/12386 5492/5494/12388 +f 5492/5494/12388 5562/5564/12386 5520/5522/12389 +f 5492/5494/12388 5520/5522/12389 5610/5612/12390 +f 5514/5516/12391 5621/5623/12392 5520/5522/12389 +f 5637/5639/12393 5627/5629/12394 5492/5494/12388 +f 5629/5631/12395 5627/5629/12394 5637/5639/12393 +f 5492/5494/12388 5610/5612/12390 5611/5613/12396 +f 5621/5623/12392 5514/5516/12391 5606/5608/12397 +f 5614/5616/12398 5637/5639/12393 5492/5494/12388 +f 5520/5522/12389 5621/5623/12392 5607/5609/12399 +f 5520/5522/12389 5609/5611/12400 5610/5612/12390 +f 5520/5522/12389 5607/5609/12399 5608/5610/12401 +f 5614/5616/12398 5492/5494/12388 5613/5615/12402 +f 5520/5522/12389 5608/5610/12401 5609/5611/12400 +f 5613/5615/12402 5492/5494/12388 5612/5614/12403 +f 5612/5614/12403 5492/5494/12388 5611/5613/12396 +f 5666/5668/12404 5663/5665/12404 5662/5664/7255 +f 5666/5668/12404 5665/5667/9546 5663/5665/12404 +f 5739/5741/12405 5513/5515/12068 5651/5653/12064 +f 5654/5656/12406 5513/5515/12068 5739/5741/12405 +f 5652/5654/12065 5528/5530/12069 5661/5663/12407 +f 5652/5654/12065 5661/5663/12407 5659/5661/12408 +f 5652/5654/12065 5659/5661/12408 5673/5675/12409 +f 5655/5657/12410 5739/5741/12405 5672/5674/12411 +f 5655/5657/12410 5654/5656/12406 5739/5741/12405 +f 5649/5651/12058 5652/5654/12065 5673/5675/12409 +f 5649/5651/12058 5673/5675/12409 5478/5480/12412 +f 5483/5485/12413 5672/5674/12411 5739/5741/12405 +f 5482/5484/12414 5483/5485/12413 5739/5741/12405 +f 5649/5651/12058 5478/5480/12412 5475/5477/12415 +f 5482/5484/12414 5739/5741/12405 5737/5739/12416 +f 5649/5651/12058 5475/5477/12415 5628/5630/12059 +f 5482/5484/12414 5737/5739/12416 5605/5607/12417 +f 5605/5607/12417 5737/5739/12416 5497/5499/12418 +f 5535/5537/12049 5532/5534/12056 5644/5646/12050 +f 5674/5676/12419 5649/5651/12058 5571/5573/12060 +f 5674/5676/12419 5571/5573/12060 5570/5572/12420 +f 5497/5499/12418 5737/5739/12416 5738/5740/12383 +f 5498/5500/12421 5497/5499/12418 5738/5740/12383 +f 5674/5676/12419 5570/5572/12420 5568/5570/12422 +f 5643/5645/12048 5505/5507/12067 5640/5642/12423 +f 4741/4743/12382 5501/5503/12424 5738/5740/12383 +f 5646/5648/12052 5508/5510/12055 5506/5508/12053 +f 5501/5503/12424 5498/5500/12421 5738/5740/12383 +f 5568/5570/12422 5566/5568/12045 5642/5644/12047 +f 5641/5643/12046 5502/5504/12425 4741/4743/12382 +f 5643/5645/12048 5640/5642/12423 5639/5641/12070 +f 5502/5504/12425 5501/5503/12424 4741/4743/12382 +f 5641/5643/12046 5566/5568/12045 5658/5660/12426 +f 5502/5504/12425 5641/5643/12046 5657/5659/12427 +f 5568/5570/12422 5642/5644/12047 5674/5676/12419 +f 5657/5659/12427 5641/5643/12046 5658/5660/12426 +f 5836/5742/12428 5833/5743/12429 5835/5744/12430 +f 6555/5745/12431 6553/5746/12432 6539/5747/12433 +f 7562/5748/12434 7561/5749/12435 7585/5750/12436 +f 6740/5751/12437 6741/5752/12438 6711/5753/12439 +f 6893/5754/12440 6898/5755/12440 6892/5756/12440 +f 6558/5757/12441 6561/5758/12441 6580/5759/12441 +f 7837/5760/12442 7839/5761/12443 7838/5762/12444 +f 7578/5763/12445 7580/5764/12446 7579/5765/12447 +f 6858/5766/12448 6857/5767/12449 6859/5768/12450 +f 6909/5769/12440 6944/5770/12440 6911/5771/12440 +f 6099/5772/12451 6097/5773/12452 6098/5774/12453 +f 7760/5775/12454 7671/5776/12455 7758/5777/12456 +f 5808/5778/12457 5807/5779/12458 5841/5780/12459 +f 7977/5781/12460 7962/5782/12461 7978/5783/12462 +f 7874/5784/12463 7875/5785/12464 7876/5786/12465 +f 5843/5787/12466 5743/5788/12467 5845/5789/12468 +f 5850/5790/12469 5749/5791/12470 5755/5792/12471 +f 6704/5793/12472 6705/5794/12472 6674/5795/12472 +f 6850/5796/12473 6838/5797/12474 6849/5798/12475 +f 7854/5799/12476 7882/5800/12477 7870/5801/12478 +f 6731/5802/12479 6729/5803/12480 6655/5804/12481 +f 5923/5805/12482 5987/5806/12483 5988/5807/12484 +f 7744/5808/12485 7758/5777/12456 7743/5809/12486 +f 6744/5810/12487 6745/5811/12488 6714/5812/12489 +f 6948/5813/12490 6981/5814/12491 6980/5815/12492 +f 5769/5816/12493 5804/5817/12493 5800/5818/12494 +f 6184/5819/12495 6017/5820/12496 6018/5821/12497 +f 6817/5822/12498 6818/5823/12498 6799/5824/12498 +f 6236/5825/12499 6237/5826/12500 6099/5772/12451 +f 5913/5827/12501 5912/5828/12502 5984/5829/12503 +f 6974/5830/12504 6965/5831/12505 6975/5832/12506 +f 6235/5833/12507 6236/5825/12499 6129/5834/12508 +f 7642/5835/12509 7605/5836/12510 7606/5837/12511 +f 6582/5838/12441 6579/5839/12441 6549/5840/12441 +f 7493/5841/12512 7510/5842/12513 7500/5843/12514 +f 7973/5844/12515 7972/5845/12516 7958/5846/12517 +f 7852/5847/12518 7823/5848/12518 7850/5849/12518 +f 6633/5850/12519 6636/5851/12520 6634/5852/12521 +f 6179/5853/12522 6174/5854/12523 6180/5855/12524 +f 6376/5856/12525 6375/5857/12526 6357/5858/12527 +f 6718/5859/12528 6719/5860/12529 6707/5861/12530 +f 7940/5862/12531 7919/5863/12532 7939/5864/12533 +f 6167/5865/12534 6166/5866/12535 6179/5853/12522 +f 7981/5867/12536 7956/5868/12537 7982/5869/12538 +f 7757/5870/12539 7674/5871/12540 7756/5872/12541 +f 7467/5873/12542 7463/5874/12542 7466/5875/12542 +f 6020/5876/12543 6195/5877/12544 6196/5878/12545 +f 6359/5879/12546 6366/5880/12547 6367/5881/12548 +f 7950/5882/12549 7924/5883/12550 7923/5884/12551 +f 7515/5885/12552 7513/5886/12553 7512/5887/12554 +f 6841/5888/12555 6842/5889/12556 6812/5890/12557 +f 6579/5839/12441 6547/5891/12558 6549/5840/12441 +f 5762/5892/12559 5785/5893/12560 5783/5894/12561 +f 7717/5895/12562 7705/5896/12562 7703/5897/12562 +f 6749/5898/12563 6652/5899/12563 6753/5900/12563 +f 6332/5901/12564 6355/5902/12565 6331/5903/12566 +f 7658/5904/12567 7655/5905/12567 7657/5906/12567 +f 5980/5907/12568 5918/5908/12569 5891/5909/12570 +f 7864/5910/12571 7863/5911/12572 7853/5912/12573 +f 6262/5913/12574 6261/5914/12575 6254/5915/12576 +f 5946/5916/12577 5947/5917/12578 5943/5918/12579 +f 7826/5919/12580 7824/5920/12581 7825/5921/12581 +f 6518/5922/12582 6411/5923/12582 6403/5924/12582 +f 6400/5925/12583 6406/5926/12584 6402/5927/12585 +f 6340/5928/12586 6339/5929/12587 6380/5930/12588 +f 5879/5931/12589 5886/5932/12590 5887/5933/12591 +f 6429/5934/12592 6432/5935/12593 6430/5936/12594 +f 6184/5819/12495 6222/5937/12595 6225/5938/12596 +f 7625/5939/12597 7616/5940/12598 7617/5941/12599 +f 6805/5942/12600 6804/5943/12601 6803/5944/12601 +f 6609/5945/12602 6597/5946/12603 6596/5947/12604 +f 6960/5948/12605 6942/5949/12606 6961/5950/12607 +f 5778/5951/12608 5777/5952/12609 5776/5953/12609 +f 7790/5954/12610 7881/5955/12611 7882/5800/12477 +f 5825/5956/12612 5827/5957/12613 5837/5958/12614 +f 6609/5945/12602 6610/5959/12615 6598/5960/12616 +f 8001/5961/12617 8002/5962/12618 7999/5963/12619 +f 6250/5964/12620 6248/5965/12621 6249/5966/12622 +f 5819/5967/12623 5806/5968/12624 5818/5969/12625 +f 5879/5931/12589 5883/5970/12626 5886/5932/12590 +f 5812/5971/12627 5844/5972/12628 5847/5973/12629 +f 6894/5974/12440 6898/5755/12440 6893/5754/12440 +f 6897/5975/12630 6896/5976/12631 6910/5977/12632 +f 7813/5978/12633 7818/5979/12634 7815/5980/12635 +f 6805/5942/12636 6778/5981/12637 6807/5982/12638 +f 7934/5983/12639 7935/5984/12640 7933/5985/12641 +f 7795/5986/12642 7796/5987/12643 7800/5988/12644 +f 6844/5989/12645 6867/5990/12646 6868/5991/12647 +f 7655/5905/12648 7542/5992/12648 7541/5993/12648 +f 7958/5846/12517 7972/5845/12516 7957/5994/12649 +f 6942/5949/12606 6938/5995/12650 6961/5950/12607 +f 5905/5996/12651 5899/5997/12652 6163/5998/12653 +f 6322/5999/12654 6296/6000/12655 6324/6001/12656 +f 6787/6002/12657 6789/6003/12658 6788/6004/12659 +f 7872/6005/12660 7875/5785/12464 7873/6006/12661 +f 7845/6007/12518 7836/6008/12518 7844/6009/12518 +f 6800/6010/12662 6799/5824/12663 6798/6011/12664 +f 6873/6012/12665 6757/6013/12665 6761/6014/12665 +f 6496/6015/12666 6480/6016/12667 6495/6017/12668 +f 6234/6018/12669 5913/5827/12501 6235/5833/12507 +f 7494/6019/12670 7471/6020/12671 7495/6021/12672 +f 6232/6022/12673 5912/5828/12502 6233/6023/12674 +f 7975/6024/12675 7985/6025/12676 7974/6026/12677 +f 7480/6027/12678 7469/6028/12679 7481/6029/12680 +f 6534/6030/12681 6525/6031/12682 6532/6032/12683 +f 6113/6033/12684 6114/6034/12685 6075/6035/12686 +f 7641/6036/12687 7644/6037/12688 7640/6038/12689 +f 7982/5869/12690 7993/6039/12691 7981/5867/12536 +f 7716/6040/12562 7713/6041/12562 7715/6042/12562 +f 7728/6043/12692 7692/6044/12562 7726/6045/12692 +f 6042/6046/12693 6182/6047/12694 6177/6048/12695 +f 6491/6049/12696 6483/6050/12697 6484/6051/12698 +f 7740/6052/12699 7739/6053/12700 7727/6054/12701 +f 6736/6055/12702 6734/6056/12703 6735/6057/12704 +f 6769/6058/12705 6765/6059/12706 6848/6060/12707 +f 6459/6061/12708 6462/6062/12708 6432/5935/12708 +f 6287/6063/12709 6283/6064/12710 6367/5881/12548 +f 6027/6065/12711 6026/6066/12712 6198/6067/12713 +f 6421/6068/12714 6444/6069/12715 6443/6070/12716 +f 7517/6071/12717 7498/6072/12718 7516/6073/12719 +f 5901/6074/12720 5900/6075/12721 5902/6076/12722 +f 7649/6077/12723 7609/6078/12724 7610/6079/12725 +f 6041/6080/12726 6168/6081/12727 6037/6082/12728 +f 6210/6083/12729 6196/5878/12545 6195/5877/12544 +f 6519/6084/12583 6518/5922/12583 6514/6085/12583 +f 5975/6086/12730 5893/6087/12731 5894/6088/12732 +f 7515/5885/12552 7498/6072/12718 7517/6071/12717 +f 6351/6089/12733 6352/6090/12734 6335/6091/12735 +f 6345/6092/12736 6334/6093/12737 6344/6094/12738 +f 6489/6095/12739 6488/6096/12740 6490/6097/12741 +f 6435/6098/12742 6436/6099/12743 6434/6100/12744 +f 6647/6101/12745 6653/6102/12746 6744/5810/12487 +f 6258/6103/12747 6257/6104/12748 6263/6105/12749 +f 6180/5855/12524 6167/5865/12534 6179/5853/12522 +f 7776/6106/12750 7777/6107/12751 7670/6108/12752 +f 6771/6109/12753 6781/6110/12754 6779/6111/12755 +f 5760/6112/12756 5761/6113/12757 5778/5951/12758 +f 6031/6114/12759 6239/6115/12760 6025/6116/12761 +f 6306/6117/12762 6305/6118/12763 6291/6119/12764 +f 7755/6120/12765 7751/6121/12766 7754/6122/12767 +f 6602/6123/12768 6617/6124/12769 6619/6125/12770 +f 6599/6126/12771 6600/6127/12772 6583/6128/12773 +f 6175/6129/12774 6251/6130/12775 6173/6131/12776 +f 6843/6132/12777 6832/6133/12778 6870/6134/12779 +f 6953/6135/12780 6939/6136/12781 6954/6137/12782 +f 6382/6138/12783 6385/6139/12784 6384/6140/12785 +f 6381/6141/12786 6383/6142/12787 6382/6138/12783 +f 6474/6143/12788 6485/6144/12789 6489/6095/12739 +f 7619/6145/12790 7633/6146/12791 7618/6147/12792 +f 7937/6148/12793 7919/5863/12532 7935/5984/12794 +f 6571/6149/12441 6573/6150/12441 6569/6151/12441 +f 6825/6152/12795 6859/5768/12450 6862/6153/12796 +f 5774/6154/12797 5773/6155/12798 5771/6156/12799 +f 6939/6136/12440 6917/6157/12440 6916/6158/12800 +f 6533/6159/12801 6613/6160/12802 6612/6161/12803 +f 5919/6162/12804 6209/6163/12805 6204/6164/12806 +f 6841/5888/12555 6852/6165/12807 6853/6166/12808 +f 7754/6122/12767 7756/5872/12541 7755/6120/12765 +f 7528/6167/12809 7530/6168/12810 7529/6169/12811 +f 5864/6170/12812 5865/6171/12813 5898/6172/12814 +f 5891/5909/12570 5976/6173/12815 5977/6174/12816 +f 6438/6175/12708 6440/6176/12708 6457/6177/12708 +f 7449/6178/12542 7473/6179/12542 7451/6180/12542 +f 6443/6070/12716 6441/6181/12817 6421/6068/12714 +f 6308/6182/12818 6307/6183/12819 6306/6117/12820 +f 6565/6184/12821 6541/6185/12822 6542/6186/12821 +f 7992/6187/12823 7991/6188/12824 7980/6189/12825 +f 6097/5773/12452 6082/6190/12826 6096/6191/12827 +f 6402/5927/12585 6406/5926/12584 6499/6192/12828 +f 6076/6193/12829 6106/6194/12830 6107/6195/12831 +f 6220/6196/12832 6219/6197/12833 6218/6198/12834 +f 6442/6199/12708 6445/6200/12708 6453/6201/12708 +f 6231/6202/12835 6081/6203/12836 6082/6190/12826 +f 6508/6204/12837 6469/6205/12838 6468/6206/12839 +f 7691/6207/12840 7680/6208/12841 7679/6209/12842 +f 6773/6210/12843 6789/6003/12844 6787/6002/12845 +f 6491/6049/12696 6490/6097/12741 6413/6211/12846 +f 7600/6212/12847 7586/6213/12847 7583/6214/12847 +f 6088/6215/12848 6089/6216/12849 6068/6217/12850 +f 6424/6218/12708 6427/6219/12708 6455/6220/12708 +f 5959/6221/12851 5985/6222/12852 5956/6223/12853 +f 5820/6224/12854 5821/6225/12855 5805/6226/12856 +f 7520/6227/12857 7522/6228/12858 7413/6229/12859 +f 7541/5993/12567 7546/6230/12860 7545/6231/12567 +f 7417/6232/12861 7412/6233/12862 7420/6234/12863 +f 7930/6235/12864 7916/6236/12865 7928/6237/12866 +f 6658/6238/12867 6693/6239/12868 6691/6240/12869 +f 6413/6211/12846 6407/6241/12870 6491/6049/12696 +f 6182/6047/12694 6178/6242/12871 6177/6048/12695 +f 6889/6243/12872 6968/6244/12873 6891/6245/12874 +f 7597/6246/12847 7566/6247/12847 7594/6248/12847 +f 7843/6249/12518 7839/5761/12518 7845/6007/12518 +f 6531/6250/12875 6635/6251/12876 6633/5850/12519 +f 6213/6252/12877 6183/6253/12878 6193/6254/12879 +f 6886/6255/12880 6987/6256/12881 6988/6257/12882 +f 5975/6086/12730 5892/6258/12883 5893/6087/12731 +f 5895/6259/12884 5896/6260/12885 5975/6086/12730 +f 5861/6261/12886 6207/6262/12887 6223/6263/12888 +f 6690/6264/12889 6689/6265/12890 6688/6266/12891 +f 6334/6093/12737 6346/6267/12892 6326/6268/12893 +f 7506/6269/12894 7490/6270/12895 7501/6271/12896 +f 6720/6272/12897 6719/5860/12529 6730/6273/12898 +f 6405/6274/12899 6410/6275/12900 6508/6204/12837 +f 7966/6276/12901 8000/6277/12902 7965/6278/12903 +f 6278/6279/12904 6281/6280/12905 6274/6281/12905 +f 7850/5849/12518 7823/5848/12518 7821/6282/12518 +f 5853/6283/12906 5848/6284/12907 5850/5790/12469 +f 5836/5742/12428 5837/5958/12614 5827/5957/12613 +f 6782/6285/12908 6772/6286/12909 6784/6287/12910 +f 6348/6288/12911 6362/6289/12912 6361/6290/12913 +f 6648/6291/12914 6656/6292/12915 6649/6293/12916 +f 6700/6294/12472 6668/6295/12472 6671/6296/12472 +f 6810/6297/12917 6831/6298/12918 6832/6133/12919 +f 5764/6299/12920 5756/6300/12921 5791/6301/12922 +f 7808/6302/12923 7835/6303/12924 7809/6304/12925 +f 7909/6305/12926 7992/6187/12823 7910/6306/12927 +f 6166/5866/12535 6151/6307/12928 6052/6308/12929 +f 6011/6309/12930 5860/6310/12931 5933/6311/12932 +f 7656/6312/12933 7548/6313/12933 7542/5992/12933 +f 5942/6314/12934 5935/6315/12935 6000/6316/12936 +f 6655/5804/12481 6648/6291/12914 6649/6293/12916 +f 6307/6183/12819 6304/6317/12937 6305/6118/12938 +f 6345/6092/12939 6344/6094/12940 6390/6318/12941 +f 6052/6308/12929 6152/6319/12942 6166/5866/12535 +f 5840/6320/12943 5841/5780/12459 5839/6321/12944 +f 7937/6148/12945 7935/5984/12640 7936/6322/12640 +f 6890/6323/12946 6997/6324/12946 6996/6325/12947 +f 7670/6108/12752 7777/6107/12751 7779/6326/12948 +f 7663/6327/12949 7766/6328/12950 7767/6329/12951 +f 6990/6330/12952 6954/6137/12782 6991/6331/12953 +f 7665/6332/12954 7675/6333/12955 7673/6334/12956 +f 6447/6335/12708 6451/6336/12708 6454/6337/12708 +f 6306/6117/12820 6307/6183/12819 6305/6118/12938 +f 5856/6338/12957 5746/6339/12957 5740/6340/12957 +f 6168/6081/12727 6041/6080/12726 6177/6048/12695 +f 6085/6341/12958 6086/6342/12959 6068/6217/12850 +f 7631/6343/12960 7616/5940/12598 7625/5939/12597 +f 6769/6058/12705 6758/6344/12961 6767/6345/12962 +f 6695/6346/12963 6703/6347/12964 6716/6348/12965 +f 7801/6349/12966 7874/5784/12463 7799/6350/12967 +f 7853/5912/12518 7823/5848/12518 7852/5847/12518 +f 6833/6351/12968 6843/6132/12777 6846/6352/12969 +f 7731/6353/12970 7720/6354/12971 7732/6355/12972 +f 6352/6090/12734 6353/6356/12973 6335/6091/12735 +f 6391/6357/12974 6346/6267/12975 6345/6092/12939 +f 6371/6358/12976 6374/6359/12977 6373/6360/12978 +f 7628/6361/12979 7627/6362/12980 7630/6363/12981 +f 5909/6364/12982 5891/5909/12570 5918/5908/12569 +f 6648/6291/12983 6655/5804/12481 6729/5803/12480 +f 5751/6365/12984 5754/6366/12985 5748/6367/12984 +f 6914/6368/12986 6897/5975/12630 6912/6369/12987 +f 5838/6370/12988 5840/6320/12943 5839/6321/12944 +f 5822/6371/12989 5751/6365/12990 5832/6372/12991 +f 6245/6373/12992 6246/6374/12993 6247/6375/12994 +f 6972/6376/12995 6970/6377/12996 6971/6378/12997 +f 6477/6379/12998 6478/6380/12999 6461/6381/13000 +f 6320/6382/13001 6294/6383/13002 6295/6384/13001 +f 6714/5812/12489 6713/6385/13003 6744/5810/12487 +f 6211/6386/13004 6214/6387/13005 6213/6252/12877 +f 6009/6388/13006 6001/6389/13007 6000/6316/12936 +f 6185/6390/13008 6022/6391/13009 6021/6392/13010 +f 7723/6393/13011 7736/6394/13011 7724/6395/13011 +f 7728/6043/13012 7741/6396/13013 7740/6052/12699 +f 6331/5903/13014 6328/6397/13014 6299/6398/13014 +f 7500/5843/12514 7508/6399/13015 7507/6400/13016 +f 7533/6401/13017 7534/6402/13018 7415/6403/13019 +f 6187/6404/13020 6192/6405/13021 6191/6406/13022 +f 6001/6389/13007 5932/6407/13023 5860/6310/12931 +f 7970/6408/13024 7969/6409/13025 7954/6410/13026 +f 5773/6155/13027 5805/6226/12494 5803/6411/12493 +f 6868/5991/12647 6763/6412/13028 6869/6413/13029 +f 6965/5831/12505 6962/6414/13030 6963/6415/13031 +f 6813/6416/13032 6814/6417/13033 6827/6418/13034 +f 5949/6419/13035 5959/6221/12851 5956/6223/12853 +f 5891/5909/12570 5889/6420/13036 5890/6421/13037 +f 6173/6131/12776 6172/6422/13038 6178/6242/12871 +f 7859/6423/13039 7889/6424/13040 7858/6425/13041 +f 7556/6426/13042 7569/6427/13043 7557/6428/13044 +f 6308/6182/13045 6306/6117/12762 6292/6429/13046 +f 7547/6430/13047 7632/6431/13048 7634/6432/13049 +f 6992/6433/13050 6884/6434/13050 6994/6435/13050 +f 6691/6240/13051 6690/6264/12889 6688/6266/12891 +f 6639/6436/13052 6525/6031/13052 6527/6437/13052 +f 6195/5877/12544 6198/6067/12713 6203/6438/13053 +f 7909/6305/13054 7906/6439/13054 7911/6440/13054 +f 7446/6441/13055 7445/6442/13055 7447/6443/13055 +f 7921/6444/13056 7918/6445/13056 7920/6446/13056 +f 6268/6447/13057 6258/6103/12747 6263/6105/12749 +f 6503/6448/13058 6502/6449/13059 6501/6450/13060 +f 6299/6398/13014 6301/6451/13014 6331/5903/13014 +f 7656/6312/12933 7660/6452/13061 7548/6313/12933 +f 6578/6453/13062 6606/6454/13063 6574/6455/13064 +f 6154/6456/13065 6153/6457/13066 6156/6458/13067 +f 7965/6278/12903 7998/6459/13068 7984/6460/13069 +f 7427/6461/13070 7462/6462/13071 7464/6463/13072 +f 5786/6464/12493 5801/6465/12493 5784/6466/12493 +f 6278/6279/12904 6283/6064/12710 6281/6280/12905 +f 5993/6467/13073 5950/6468/13074 5951/6469/13075 +f 7959/6470/13056 7932/6471/13056 7929/6472/13056 +f 7730/6473/13076 7768/6474/13077 7729/6475/13078 +f 6788/6004/12659 6785/6476/13079 6786/6477/13080 +f 7630/6363/12981 7627/6362/12980 7626/6478/13081 +f 6926/6479/13082 6925/6480/13083 6928/6481/13084 +f 6514/6085/13085 6401/6482/13085 6515/6483/13085 +f 7778/6484/13086 7777/6107/12751 7734/6485/13087 +f 6665/6486/12472 6664/6487/12472 6662/6488/13088 +f 6224/6489/13089 6220/6196/12832 5929/6490/13090 +f 6727/6491/13091 6728/6492/13092 6730/6273/12898 +f 6320/6382/13093 6321/6493/13094 6319/6494/13095 +f 6205/6495/13096 6210/6083/12729 6195/5877/12544 +f 6935/6496/12440 6925/6480/12440 6922/6497/12440 +f 6358/6498/13097 6341/6499/13098 6384/6140/12785 +f 6521/6500/13099 6637/6501/13099 6520/6502/13099 +f 6276/6503/13100 6363/6504/13101 6393/6505/13102 +f 6442/6199/13103 6443/6070/13104 6445/6200/13105 +f 6615/6506/13106 6614/6507/13107 6616/6508/13108 +f 6809/6509/13109 6770/6510/13110 6779/6111/12755 +f 6238/6511/13111 6247/6375/12994 6239/6115/12760 +f 6191/6406/13022 6190/6512/13112 6189/6513/13113 +f 6335/6091/13014 6332/5901/13014 6304/6317/13014 +f 7455/6514/13114 7457/6515/13115 7456/6516/13115 +f 7953/6517/13056 7949/6518/13056 7952/6519/13056 +f 6534/6030/12681 6595/6520/13116 6594/6521/13117 +f 6380/5930/12588 6379/6522/13118 6381/6141/12786 +f 7424/6523/12862 7426/6524/13119 7421/6525/12862 +f 6870/6134/12779 6831/6298/12918 6868/5991/12647 +f 5842/6526/13120 5810/6527/13121 5809/6528/13122 +f 7592/6529/13123 7612/6530/13124 7599/6531/13125 +f 7976/6532/13126 7964/6533/13127 7977/5781/12460 +f 7702/6534/13128 7704/6535/13129 7682/6536/13130 +f 6264/6537/13131 6269/6538/13132 6272/6539/13133 +f 7861/6540/13134 7891/6541/13135 7860/6542/13136 +f 7564/6543/13137 7590/6544/13137 7591/6545/13137 +f 7746/6546/13138 7762/6547/13139 7745/6548/13140 +f 7908/6549/13141 7905/6550/13054 7907/6551/13054 +f 7932/6471/13142 7930/6235/13143 7929/6472/13144 +f 5760/6112/12756 5759/6552/13145 5758/6553/13145 +f 7589/6554/12847 7596/6555/12847 7591/6545/12847 +f 6645/6556/13146 6738/6557/13147 6737/6558/13148 +f 6480/6016/12667 6481/6559/13149 6455/6220/13150 +f 7475/6560/12542 7453/6561/12542 7472/6562/12542 +f 6711/5753/12439 6712/6563/13151 6699/6564/13152 +f 7416/6565/13153 7424/6523/13153 7539/6566/13153 +f 7910/6306/12927 7996/6567/13154 7901/6568/13155 +f 7975/6024/12675 7988/6569/13156 7985/6025/12676 +f 6614/6507/13107 6533/6159/12801 6616/6508/13108 +f 5851/6570/13157 5815/6571/13158 5814/6572/13159 +f 6208/6573/13160 6207/6262/12887 5861/6261/12886 +f 5992/6574/13161 5926/6575/13162 5990/6576/13163 +f 5778/5951/12608 5781/6577/13164 5779/6578/12608 +f 6414/6579/13165 6448/6580/13166 6446/6581/13167 +f 7418/6582/13168 7537/6583/13168 7535/6584/13168 +f 6805/5942/12600 6806/6585/12600 6804/5943/12601 +f 6216/6586/13169 6219/6197/12833 6217/6587/13170 +f 5866/6588/13171 5867/6589/13172 5884/6590/13173 +f 6483/6050/12697 6491/6049/12696 6493/6591/13174 +f 6707/5861/12472 6678/6592/12472 6680/6593/12472 +f 5998/6594/13175 5995/6595/13176 5946/5916/12577 +f 5940/6596/13177 6000/6316/12936 5939/6597/13178 +f 7471/6020/12671 7470/6598/13179 7496/6599/13180 +f 5946/5916/12577 5995/6595/13176 5993/6467/13073 +f 6279/6600/12905 6277/6601/12905 6286/6602/13181 +f 6153/6457/13066 6154/6456/13065 6229/6603/13182 +f 6246/6374/12993 6202/6604/13183 6201/6605/13184 +f 6310/6606/13185 6313/6607/13186 6311/6608/13185 +f 6229/6603/13182 6154/6456/13065 6228/6609/13187 +f 5913/5827/12501 5870/6610/13188 5914/6611/13189 +f 6928/6481/13084 6930/6612/13190 6929/6613/13191 +f 5969/6614/13192 5877/6615/13193 5968/6616/13194 +f 7648/6617/13195 7646/6618/13196 7608/6619/13197 +f 6573/6150/13198 6589/6620/13199 6576/6621/13200 +f 6160/6622/13201 6252/6623/13202 6159/6624/13203 +f 6991/6331/12953 6889/6243/12872 6988/6257/12882 +f 6597/5946/13204 6584/6625/13205 6596/5947/13206 +f 5766/6626/13207 5765/6627/13208 5767/6628/13209 +f 7455/6514/13114 7456/6516/13115 7454/6629/13210 +f 5823/6630/13211 5824/6631/13212 5800/5818/13213 +f 6353/6356/12973 6354/6632/13214 6332/5901/12564 +f 6360/6633/13215 6359/5879/12546 6351/6089/13216 +f 6962/6414/13030 6971/6378/12997 6970/6377/12996 +f 6953/6135/12780 6990/6330/12952 6989/6634/13217 +f 6114/6034/12685 6132/6635/13218 6075/6035/12686 +f 6325/6636/13014 6327/6637/13014 6323/6638/13014 +f 6788/6004/12659 6789/6003/12658 6791/6639/13219 +f 6882/6640/13220 6890/6323/13220 6996/6325/13220 +f 6277/6601/13221 6398/6641/13221 6284/6642/13221 +f 7466/5875/12542 7461/6643/12542 7469/6028/12542 +f 7911/6440/13222 7906/6439/13222 8019/6644/13222 +f 5923/5805/12482 5885/6645/13223 5987/5806/12483 +f 6584/6625/12441 6585/6646/12441 6554/6647/12441 +f 6733/6648/13224 6734/6056/12703 6732/6649/13225 +f 6529/6650/13226 6642/6651/13226 6638/6652/13226 +f 7780/6653/13227 7779/6326/12948 7777/6107/12751 +f 7955/6654/13228 7968/6655/13229 7967/6656/13230 +f 6255/6657/13231 6258/6103/12747 6268/6447/13057 +f 7644/6037/12688 7641/6036/12687 7642/5835/12509 +f 6982/6658/13232 6981/5814/12491 6949/6659/13233 +f 7598/6660/13234 7621/6661/13235 7620/6662/13236 +f 6983/6663/13237 6982/6658/13232 6984/6664/13238 +f 6169/6665/13239 6247/6375/12994 6238/6511/13111 +f 6811/6666/12498 6806/6585/12498 6808/6667/12498 +f 6105/6668/13240 6092/6669/13241 6111/6670/13242 +f 7462/6462/13243 7460/6671/13244 7461/6643/13245 +f 6867/5990/12646 6844/5989/12645 6845/6672/13246 +f 7840/6673/13247 7810/6674/13248 7841/6675/13249 +f 6411/5923/12583 6408/6676/12583 6413/6211/12846 +f 7440/6677/13250 7441/6678/13251 7439/6679/13252 +f 6280/6680/13253 6275/6681/12905 6273/6682/12905 +f 7905/6550/13054 7908/6549/13141 7904/6683/13054 +f 6192/6405/13021 6183/6253/12878 6213/6252/12877 +f 6974/5830/12504 6973/6684/13254 6971/6378/12997 +f 6108/6685/13255 6109/6686/13256 6076/6193/12829 +f 6516/6687/13257 6404/6688/13257 6400/5925/13257 +f 5974/6689/13258 5915/6690/13259 5973/6691/13260 +f 7984/6460/13069 7996/6567/13154 7995/6692/13261 +f 7632/6431/13048 7554/6693/13262 7631/6343/12960 +f 7659/6694/12567 7655/5905/12567 7658/5904/12567 +f 7668/6695/13263 7666/6696/13264 7662/6697/12956 +f 6238/6511/13111 6036/6698/13265 6035/6699/13266 +f 7925/6700/13267 7927/6701/13268 7926/6702/13269 +f 5871/6703/13270 5872/6704/13271 5867/6589/13172 +f 6383/6142/12787 6381/6141/12786 6280/6680/13253 +f 7951/6705/13056 7936/6322/13056 7963/6706/13056 +f 6919/6707/13272 6922/6497/13273 6921/6708/13274 +f 5882/6709/13275 5883/5970/12626 5879/5931/12589 +f 7881/5955/12611 7879/6710/13276 7870/5801/12478 +f 6109/6686/13256 6112/6711/13277 6076/6193/12829 +f 6571/6149/13278 6570/6712/13279 6572/6713/13280 +f 6573/6150/12441 6576/6621/12441 6567/6714/12441 +f 7869/6715/13281 7879/6710/13276 7877/6716/13282 +f 6930/6612/13190 6902/6717/13283 6931/6718/13284 +f 7515/5885/12552 7414/6719/13285 7513/5886/12553 +f 6978/6720/13286 6880/6721/13287 6976/6722/13288 +f 6461/6381/13000 6478/6380/12999 6456/6723/13289 +f 5853/6283/12906 5755/5792/12471 5816/6724/13290 +f 7835/6303/13291 7834/6725/13292 7836/6008/13293 +f 6700/6294/12472 6696/6726/12472 6668/6295/12472 +f 7537/6583/13294 7416/6565/13294 7538/6727/13294 +f 6724/6728/13295 6725/6729/13296 6701/6730/13297 +f 6481/6559/13149 6452/6731/13298 6455/6220/13150 +f 6992/6433/13299 6993/6732/13299 6879/6733/13299 +f 6315/6734/13300 6314/6735/13301 6293/6736/13302 +f 6820/6737/13303 6837/6738/13304 6819/6739/13305 +f 5811/6740/13306 5797/6741/13307 5798/6742/13308 +f 7537/6583/13294 7418/6582/13294 7416/6565/13294 +f 6019/6743/13309 6189/6513/13113 6190/6512/13112 +f 6561/5758/13310 6560/6744/13311 6562/6745/13312 +f 6528/6746/13313 6618/6747/13314 6616/6508/13108 +f 6561/5758/13310 6558/5757/13315 6559/6748/13316 +f 7735/6749/13317 7717/5895/13318 7724/6395/13319 +f 6950/6750/13320 6940/6751/13321 6951/6752/13322 +f 6873/6012/13323 6755/6753/13323 6757/6013/13323 +f 6383/6142/12787 6387/6754/13324 6386/6755/13325 +f 5918/5908/12569 5917/6756/13326 5908/6757/13327 +f 6694/6758/13328 6668/6295/13329 6666/6759/13330 +f 7958/5846/13056 7941/6760/13056 7938/6761/13056 +f 5910/6762/13331 5961/6763/13332 5911/6764/13333 +f 7613/6765/13334 7612/6530/13124 7592/6529/13123 +f 6203/6438/13053 6202/6604/13183 6200/6766/13335 +f 6333/6767/13014 6334/6093/13014 6316/6768/13014 +f 6787/6002/12845 6786/6477/13336 6772/6286/12909 +f 6515/6483/13337 6408/6676/13337 6519/6084/13338 +f 6043/6769/13339 6044/6770/13340 6045/6771/13341 +f 7445/6442/12542 7478/6772/12542 7447/6443/12542 +f 6169/6665/13239 6244/6773/13342 6247/6375/12994 +f 6206/6774/13343 6225/5938/12596 6207/6262/12887 +f 5794/6775/13344 5817/6776/13345 5806/5968/12624 +f 7675/6333/12955 7737/6777/13346 7738/6778/13347 +f 7723/6393/13348 7727/6054/12701 7738/6778/13349 +f 6980/5815/12492 6979/6779/13350 6946/6780/13351 +f 5840/6320/12943 5838/6370/12988 5742/6781/13352 +f 6933/6782/13353 6937/6783/13354 6947/6784/13355 +f 7685/6785/13356 7714/6786/13357 7713/6041/13358 +f 6678/6592/12472 6707/5861/12472 6708/6787/12472 +f 6988/6257/12882 6889/6243/12872 6886/6255/12880 +f 6352/6090/13359 6351/6089/13216 6359/5879/12546 +f 7816/6788/13360 7811/6789/13361 7814/6790/13362 +f 6223/6263/12888 6224/6489/13089 5930/6791/13363 +f 5914/6611/13189 5870/6610/13188 5915/6690/13259 +f 5923/5805/12482 5988/5807/12484 5925/6792/13364 +f 6288/6793/13365 6287/6063/12709 6365/6794/13366 +f 5870/6610/13188 5873/6795/13367 5874/6796/13368 +f 6907/6797/13369 6905/6798/13370 6904/6799/13371 +f 6775/6800/13372 6797/6801/13373 6795/6802/13374 +f 6118/6803/13375 6122/6804/13376 6124/6805/13377 +f 5836/5742/12428 5835/5744/12430 5838/6370/12988 +f 6316/6768/13014 6318/6806/13014 6333/6767/13014 +f 5920/6807/13378 5922/6808/13379 6214/6387/13005 +f 6527/6437/13380 6637/6501/13380 6639/6436/13380 +f 7928/6237/13381 7927/6701/13268 7929/6472/13144 +f 7655/5905/13382 7541/5993/13382 7545/6231/13382 +f 7435/6809/12542 7433/6810/12542 7434/6811/12542 +f 7543/6812/13383 7637/6813/13384 7638/6814/13385 +f 6907/6797/12440 6942/5949/12440 6909/5769/12440 +f 7612/6530/13124 7651/6815/13386 7611/6816/13387 +f 7479/6817/13388 7498/6072/12718 7467/5873/13389 +f 6836/6818/13390 6837/6738/13304 6820/6737/13303 +f 7570/6819/13391 7571/6820/13392 7573/6821/13393 +f 5916/6822/13394 6231/6202/12835 6237/5826/12500 +f 7579/5765/13395 7560/6823/13396 7577/6824/13397 +f 5930/6791/13363 5861/6261/12886 6223/6263/12888 +f 6243/6825/13398 6160/6622/13201 6200/6766/13335 +f 7913/6826/13399 7911/6440/13054 7904/6683/13054 +f 6600/6127/12772 6601/6827/13400 6582/5838/13401 +f 6904/6799/13371 6905/6798/13370 6903/6828/13402 +f 6671/6296/12472 6674/5795/12472 6705/5794/12472 +f 7840/6673/13403 7841/6675/13404 7802/6829/13405 +f 6277/6601/12905 6284/6642/12905 6285/6830/13406 +f 6461/6381/13000 6460/6831/13407 6477/6379/12998 +f 6581/6832/12441 6580/5759/12441 6561/5758/12441 +f 6275/6681/12905 6278/6279/12904 6274/6281/12905 +f 7870/5801/13408 7846/6833/13409 7847/6834/13410 +f 7800/5988/12644 7798/6835/13411 7799/6350/12967 +f 7677/6836/13412 7686/6837/13413 7688/6838/13414 +f 6670/6839/13415 6669/6840/13416 6659/6841/13417 +f 6793/6842/13418 6794/6843/13419 6796/6844/13420 +f 6061/6845/13421 6060/6846/13422 6081/6203/12836 +f 6777/6847/12498 6776/6848/12498 6775/6800/12498 +f 6313/6607/13186 6312/6849/13423 6314/6735/13424 +f 7442/6850/13425 7429/6851/13426 7441/6678/13427 +f 6209/6163/12805 6211/6386/13004 6212/6852/13428 +f 6062/6853/13429 6061/6845/13421 6081/6203/12836 +f 5861/6261/12886 5931/6854/13430 6208/6573/13160 +f 6084/6855/13431 6083/6856/13432 6059/6857/13433 +f 7924/5883/12550 7950/5882/12549 7949/6518/13434 +f 5973/6691/13260 5915/6690/13259 5972/6858/13435 +f 6082/6190/12826 6071/6859/13436 6070/6860/13437 +f 7760/5775/12454 7762/6547/13139 7763/6861/13438 +f 5880/6862/13439 5881/6863/13440 5879/5931/12589 +f 6301/6451/13441 6300/6864/13442 6302/6865/13443 +f 6136/6866/13444 6138/6867/13445 6139/6868/13446 +f 6259/6869/13447 6263/6105/12749 6260/6870/13448 +f 7532/6871/13449 7486/6872/13450 7487/6873/13451 +f 7508/6399/13015 7510/5842/12513 7509/6874/13452 +f 6261/5914/12575 6260/6870/13448 6256/6875/13453 +f 7701/6876/12562 7724/6395/12562 7703/5897/12562 +f 6758/6344/12961 6769/6058/12705 6871/6877/13454 +f 6568/6878/13455 6567/6714/13456 6565/6184/13457 +f 6240/6879/13458 6239/6115/12760 6030/6880/13459 +f 6074/6881/13460 6143/6882/13461 6144/6883/13462 +f 5752/6884/13463 5817/6776/13464 5816/6724/13290 +f 6060/6846/13422 6073/6885/13465 6081/6203/12836 +f 6937/6783/13354 6948/5813/12490 6947/6784/13355 +f 6063/6886/13466 6062/6853/13429 6081/6203/12836 +f 7562/5748/12434 7588/6887/13467 7563/6888/13468 +f 6791/6639/12498 6822/6889/12498 6788/6004/12498 +f 7832/6890/13469 7830/6891/13470 7829/6892/13471 +f 6222/5937/12595 6221/6893/13472 6224/6489/13089 +f 5778/5951/12758 5776/5953/13473 5760/6112/12756 +f 6611/6894/13474 6612/6161/12803 6613/6160/12802 +f 7774/6895/13475 7732/6355/12972 7775/6896/13476 +f 6224/6489/13089 5929/6490/13090 5930/6791/13363 +f 6600/6127/13477 6614/6507/13107 6615/6506/13106 +f 6507/6897/13478 6505/6898/13479 6506/6899/13480 +f 6776/6848/13481 6801/6900/13482 6798/6011/13483 +f 6582/5838/13401 6602/6123/13484 6579/5839/13485 +f 6954/6137/12782 6939/6136/12781 6932/6901/13486 +f 5803/6411/13487 5805/6226/12856 5821/6225/12855 +f 6518/5922/12583 6517/6902/12583 6514/6085/12583 +f 6211/6386/13004 6209/6163/12805 5918/5908/12569 +f 7943/6903/13488 7940/5862/13489 7941/6760/13490 +f 6154/6456/13065 6156/6458/13067 6157/6904/13491 +f 6154/6456/13065 6157/6904/13491 6158/6905/13492 +f 6663/6906/13493 6679/6907/13494 6662/6488/13088 +f 7734/6485/13087 7717/5895/13318 7735/6749/13317 +f 6425/6908/13495 6426/6909/13496 6427/6219/13497 +f 6889/6243/12872 6956/6910/13498 6968/6244/12873 +f 6167/5865/12534 6180/5855/12524 6181/6911/13499 +f 7620/6662/13500 7635/6912/13501 7619/6145/12790 +f 5860/6310/12931 6011/6309/12930 6012/6913/13502 +f 5828/6914/13503 5820/6224/13504 5829/6915/13505 +f 6482/6916/13506 6450/6917/13507 6452/6731/13298 +f 5908/6757/13327 5917/6756/13326 5901/6074/12720 +f 6506/6899/13480 6405/6274/12899 6508/6204/12837 +f 5846/6918/13508 5848/6284/12907 5847/5973/12629 +f 7679/6209/12842 7678/6919/13509 7689/6920/13510 +f 7685/6785/13356 7686/6837/13511 7684/6921/13512 +f 7448/6922/13513 7446/6441/13514 7447/6443/13514 +f 7610/6079/12725 7650/6923/13515 7649/6077/12723 +f 6390/6318/12941 6344/6094/12940 6343/6924/13516 +f 5817/6776/13345 5818/5969/12625 5806/5968/12624 +f 5877/6615/13193 5878/6925/13517 5968/6616/13194 +f 5878/6925/13517 5880/6862/13439 5967/6926/13518 +f 6650/6927/12916 6649/6293/12916 6656/6292/12915 +f 6374/6359/12977 6376/5856/12525 6357/5858/12527 +f 5792/6928/12493 5795/6929/12493 5790/6930/12493 +f 6242/6931/13519 6244/6773/13342 6253/6932/13520 +f 6110/6933/13521 6102/6934/13522 6103/6935/13523 +f 6338/6936/13524 6328/6397/13525 6357/5858/12527 +f 5747/6937/13526 5745/6938/13527 5834/6939/13528 +f 7522/6228/12858 7523/6940/13529 7524/6941/13530 +f 5975/6086/12730 5915/6690/13259 5974/6689/13258 +f 6221/6893/13472 6188/6942/13531 6190/6512/13112 +f 8003/6943/13532 8006/6944/13533 7899/6945/13534 +f 6959/6946/13535 6966/6947/13536 6958/6948/13537 +f 6082/6190/12826 6081/6203/12836 6071/6859/13436 +f 6174/5854/12523 6260/6870/13448 6262/5913/12574 +f 6135/6949/13538 6129/5834/12508 6134/6950/13539 +f 7611/6816/13387 7650/6923/13515 7610/6079/12725 +f 6458/6951/12708 6457/6177/12708 6440/6176/12708 +f 7895/6952/13540 7794/6953/13540 7793/6954/13540 +f 6350/6955/13541 6337/6956/13542 6349/6957/13543 +f 5903/6958/13544 5906/6959/13545 5901/6074/12720 +f 7440/6677/12542 7471/6020/12542 7443/6960/12542 +f 6820/6737/12498 6819/6739/12498 6788/6004/12498 +f 5755/5792/12985 5749/5791/12470 5744/6961/12985 +f 6066/6962/13546 6067/6963/13547 6081/6203/12836 +f 5870/6610/13188 5969/6614/13192 5970/6964/13548 +f 7698/6965/12562 7723/6393/12562 7701/6876/12562 +f 7791/6966/13411 7787/6967/13411 7789/6968/13411 +f 5904/6969/13549 5905/5996/12651 5864/6170/12812 +f 6382/6138/12783 6384/6140/12785 6340/5928/12586 +f 6435/6098/12742 6434/6100/12744 6433/6970/12744 +f 7666/6696/13264 7760/5775/12454 7763/6861/13438 +f 7681/6971/13550 7677/6836/12692 7680/6208/12841 +f 6137/6972/13551 6138/6867/13445 6136/6866/13444 +f 5789/6973/13552 5763/6974/13553 5764/6299/12920 +f 6967/6975/13554 6968/6244/12873 6956/6910/13498 +f 6712/6563/13555 6697/6976/13556 6699/6564/13557 +f 6957/6977/13558 6956/6910/13498 6944/5770/13559 +f 7490/6270/12895 7505/6978/13560 7502/6979/13561 +f 7664/6980/13562 7661/6981/12956 7663/6327/12949 +f 7491/6982/13563 7501/6271/12896 7490/6270/12895 +f 7559/6983/13564 7572/6984/13565 7575/6985/13566 +f 6929/6613/13567 6892/5756/13568 6927/6986/13569 +f 7803/6987/13570 7817/6988/13571 7804/6989/13572 +f 7859/6423/13573 7858/6425/13574 7844/6009/13575 +f 5789/6973/13552 5787/6990/13553 5763/6974/13553 +f 6449/6991/12708 6463/6992/12708 6436/6099/12708 +f 5958/6993/13576 5960/6994/13577 5956/6223/12853 +f 7826/5919/12580 7827/6995/12580 7829/6892/13471 +f 7456/6516/13578 7433/6810/13579 7454/6629/13580 +f 7619/6145/13581 7598/6660/13234 7620/6662/13236 +f 5778/5951/12608 5780/6996/13582 5781/6577/13164 +f 6250/5964/12620 6155/6997/13583 6159/6624/13203 +f 5753/6998/13584 5858/6999/13585 5859/7000/13584 +f 6204/6164/12806 6209/6163/12805 6205/6495/13096 +f 5854/7001/13586 5741/7002/13586 5855/7003/13586 +f 6738/6557/13147 6739/7004/13587 6710/7005/13588 +f 6001/6389/13007 6010/7006/13589 5934/7007/13590 +f 6890/6323/13591 6891/6245/13591 6885/7008/13592 +f 5985/6222/12852 5911/6764/13333 5954/7009/13593 +f 6592/7010/13594 6591/7011/13595 6634/5852/12521 +f 7895/6952/13596 7893/7012/13596 7787/6967/13596 +f 7793/6954/13597 7797/7013/13598 7792/7014/13599 +f 6531/6250/12875 6530/7015/13600 6635/6251/12876 +f 7803/6987/13570 7813/5978/13601 7815/5980/13602 +f 6454/6337/13603 6466/7016/13604 6467/7017/13605 +f 6496/6015/12666 6497/7018/13606 6498/7019/13607 +f 6266/7020/13608 6267/7021/13609 6268/6447/13057 +f 5996/7022/13610 5994/7023/13611 5993/6467/13073 +f 6887/7024/13612 6882/6640/13591 6884/6434/13591 +f 7511/7025/13613 7509/6874/13452 7510/5842/12513 +f 5999/7026/13614 5997/7027/13615 5996/7022/13610 +f 5926/6575/13162 5928/7028/13616 5863/7029/13617 +f 5891/5909/12570 5978/7030/13618 5979/7031/13619 +f 5970/6964/13548 5971/7032/13620 5870/6610/13188 +f 6215/7033/13621 5922/6808/13379 5923/5805/12482 +f 6324/6001/13622 6323/6638/13623 6322/5999/13624 +f 7544/7034/12567 7550/7035/13625 7549/7036/13626 +f 6245/6373/12992 6200/6766/13335 6202/6604/13183 +f 5982/7037/13627 5983/7038/13628 5879/5931/12589 +f 5921/7039/13629 5918/5908/12569 5982/7037/13627 +f 6684/7040/13630 6685/7041/13631 6683/7042/13632 +f 6712/6563/13555 6713/6385/13633 6697/6976/13556 +f 6982/6658/13232 6949/6659/13233 6950/6750/13634 +f 6033/7043/13635 6168/6081/12727 6034/7044/13636 +f 6799/5824/12663 6796/6844/13420 6797/6801/13637 +f 6676/7045/13638 6673/7046/13639 6675/7047/13638 +f 7645/7048/13640 7607/7049/13641 7646/6618/13196 +f 5925/6792/13364 5989/7050/13642 5924/7051/13643 +f 5745/6938/13527 5835/5744/12430 5834/6939/13528 +f 5909/6364/12982 5889/6420/13036 5891/5909/12570 +f 6963/6415/13644 6934/7052/13645 6964/7053/13646 +f 5745/6938/13527 5742/6781/13352 5838/6370/12988 +f 6098/5774/12453 6100/7054/13647 6099/5772/12451 +f 6199/7055/13648 6029/7056/13649 6027/6065/12711 +f 6738/6557/13147 6645/6556/13146 6739/7004/13587 +f 6583/6128/12773 6600/6127/12772 6582/5838/13401 +f 5879/5931/12589 5921/7039/13629 5982/7037/13627 +f 6189/6513/13113 6019/6743/13309 6187/6404/13020 +f 6362/6289/12912 6348/6288/12911 6347/7057/13650 +f 6624/7058/13651 6625/7059/13652 6627/7060/13653 +f 6774/7061/13654 6794/6843/13655 6792/7062/13656 +f 7432/7063/13657 7450/7064/13658 7452/7065/13659 +f 6197/7066/13660 6201/6605/13184 6198/6067/12713 +f 6273/6682/12905 6279/6600/12905 6280/6680/13253 +f 7430/7067/13661 7429/6851/13426 7442/6850/13425 +f 7858/6425/13041 7888/7068/13662 7857/7069/13663 +f 5867/6589/13172 5868/7070/13664 5869/7071/13665 +f 6357/5858/12527 6356/7072/13666 6374/6359/12977 +f 7486/6872/13450 7472/6562/13667 7487/6873/13451 +f 8009/7073/13668 8007/7074/13669 8008/7075/13670 +f 6114/6034/12685 6115/7076/13671 6132/6635/13218 +f 7664/6980/13562 7773/7077/13672 7776/6106/12750 +f 6718/5859/12528 6717/7078/13673 6726/7079/13674 +f 6323/6638/13623 6321/6493/13094 6320/6382/13093 +f 6013/7080/13675 6014/7081/13676 6208/6573/13160 +f 6195/5877/12544 6020/5876/12543 6199/7055/13648 +f 5944/7082/13677 5945/7083/13678 5946/5916/12577 +f 7673/6334/13679 7668/6695/13679 7786/7084/13679 +f 6046/7085/13680 6050/7086/13681 6167/5865/12534 +f 6421/6068/12714 6441/6181/12817 6420/7087/13682 +f 7598/6660/12847 7568/7088/12847 7597/6246/12847 +f 6101/7089/13683 6110/6933/13521 6131/7090/13684 +f 6126/7091/13685 6133/7092/13686 6121/7093/13687 +f 7928/6237/13381 7926/6702/13269 7927/6701/13268 +f 6626/7094/13688 6627/7060/13653 6625/7059/13652 +f 6704/5793/13689 6723/7095/13690 6705/5794/13691 +f 6133/7092/13686 6134/6950/13539 6119/7096/13692 +f 6838/5797/13693 6839/7097/13694 6819/6739/13305 +f 6688/6266/12891 6689/6265/12890 6687/7098/13695 +f 7904/6683/13696 8017/7099/13696 8016/7100/13696 +f 7954/6410/13026 7969/6409/13025 7955/6654/13228 +f 7670/6108/12752 7779/6326/12948 7669/7101/13697 +f 6530/7015/13600 6593/7102/13698 6636/5851/12520 +f 6692/7103/13699 6690/6264/12889 6691/6240/13051 +f 6254/5915/12576 6228/6609/13187 6158/6905/13492 +f 7886/7104/13700 7857/7069/13663 7888/7068/13662 +f 6523/7105/13701 6522/7106/13702 6626/7094/13688 +f 5855/7003/12985 5859/7000/12984 5858/6999/12985 +f 6523/7105/13701 6526/7107/13703 6521/6500/12683 +f 6154/6456/13065 6158/6905/13492 6228/6609/13187 +f 6548/7108/13704 6546/7109/13705 6536/7110/13706 +f 7723/6393/12562 7698/6965/12562 7696/7111/12562 +f 5833/5743/12429 5827/5957/12613 5824/6631/13212 +f 6059/6857/13433 6066/6962/13546 6081/6203/12836 +f 7795/5986/12642 7880/7112/13707 7790/5954/12610 +f 7559/6983/13564 7556/6426/12847 7558/7113/12847 +f 6750/7114/13708 6650/6927/13709 6643/7115/13708 +f 6955/7116/13710 6944/5770/13559 6956/6910/13498 +f 6462/6062/13711 6475/7117/13712 6476/7118/13713 +f 6716/6348/12965 6715/7119/13714 6746/7120/13715 +f 6226/7121/13716 6084/6855/13431 6059/6857/13433 +f 6422/7122/12708 6421/6068/12708 6415/7123/12708 +f 7422/7124/13717 7524/6941/13530 7528/6167/12809 +f 6215/7033/13621 6214/6387/13005 5922/6808/13379 +f 6117/7125/13718 6125/7126/13719 6115/7076/13671 +f 6292/6429/13046 6291/6119/13014 6295/6384/13014 +f 6250/5964/12620 6159/6624/13203 6252/6623/13202 +f 6164/7127/13720 6045/6771/13721 6181/6911/13499 +f 6534/6030/12681 6533/6159/12801 6612/6161/12803 +f 6676/7045/13722 6675/7047/13722 6677/7128/13722 +f 6136/6866/13444 6129/5834/12508 6135/6949/13538 +f 6595/6520/13723 6596/5947/13206 6584/6625/13205 +f 5972/6858/13435 5870/6610/13188 5971/7032/13620 +f 6090/7129/13724 6091/7130/13725 6070/6860/13437 +f 6225/5938/12596 6206/6774/13343 6017/5820/12496 +f 6492/7131/13726 6494/7132/13727 6478/6380/12999 +f 6588/7133/13728 6587/7134/13729 6628/7135/13730 +f 5800/5818/12494 5796/7136/12493 5766/6626/12493 +f 7709/7137/13731 7708/7138/13731 7707/7139/13732 +f 7488/7140/13733 7473/6179/13734 7465/7141/13735 +f 7606/5837/12511 7643/7142/13736 7642/5835/12509 +f 7747/7143/13737 7764/7144/13738 7762/6547/13139 +f 7953/6517/13739 7983/7145/13740 7956/5868/12537 +f 6420/7087/13682 6439/7146/13741 6437/7147/13742 +f 6079/7148/13743 5911/6764/13333 6080/7149/13744 +f 7489/7150/13745 7502/6979/13561 7503/7151/13746 +f 6078/7152/13747 6232/6022/12673 6077/7153/13748 +f 6912/6369/13749 6915/7154/13750 6914/6368/13751 +f 6080/7149/13744 5911/6764/13333 6232/6022/12673 +f 5887/5933/12591 5888/7155/13752 5885/6645/13223 +f 6081/6203/12836 6230/7156/13753 6229/6603/13182 +f 7587/7157/13754 7586/6213/13755 7589/6554/13756 +f 6472/7158/13757 6513/7159/13758 6486/7160/13759 +f 5870/6610/13188 5874/6796/13368 5875/7161/13760 +f 6954/6137/12782 6932/6901/13486 6955/7116/13710 +f 5993/6467/13073 5951/6469/13075 5946/5916/12577 +f 6227/7162/13761 6261/5914/12575 6256/6875/13453 +f 6075/6035/12686 6146/7163/13762 6147/7164/13763 +f 6269/6538/13764 6271/7165/13765 6272/6539/13766 +f 6919/6707/13767 6898/5755/13768 6918/7166/13769 +f 6287/6063/12905 6288/6793/13365 6284/6642/12905 +f 7913/6826/13399 7912/7167/13054 7911/6440/13054 +f 7963/6706/13770 7975/6024/12675 7951/6705/13771 +f 6281/6280/12905 6287/6063/12905 6284/6642/12905 +f 6685/7041/13631 6682/7168/13772 6683/7042/13632 +f 6798/6011/13483 6797/6801/13373 6775/6800/13372 +f 7839/5761/12443 7837/5760/12442 7836/6008/13293 +f 6101/7089/13683 6131/7090/13684 6130/7169/13773 +f 6980/5815/12492 6947/6784/13774 6948/5813/12490 +f 6289/7170/13775 6297/7171/13776 6324/6001/12656 +f 6214/6387/13005 6215/7033/13621 6213/6252/12877 +f 6556/7172/12441 6584/6625/12441 6554/6647/12441 +f 5747/6937/13526 5751/6365/12984 5748/6367/12984 +f 5879/5931/12589 5920/6807/13378 5921/7039/13629 +f 6822/6889/13777 6835/7173/13778 6820/6737/13303 +f 6186/7174/13779 6023/7175/13780 6020/5876/12543 +f 6471/7176/13781 6470/7177/13782 6510/7178/13783 +f 6240/6879/13458 6032/7179/13784 6238/6511/13111 +f 6238/6511/13111 6032/7179/13784 6036/6698/13265 +f 6264/6537/13131 6083/6856/13432 6084/6855/13431 +f 7659/6694/13785 7658/5904/13785 7544/7034/13785 +f 6512/7180/13786 6487/7181/13787 6513/7159/13758 +f 6119/7096/13692 6120/7182/13788 6133/7092/13686 +f 7666/6696/13264 7766/6328/12950 7663/6327/12949 +f 7594/6248/13789 7623/7183/13790 7622/7184/13791 +f 6168/6081/12727 6035/6699/13266 6034/7044/13636 +f 7876/5786/12465 7875/5785/12464 7800/5988/12644 +f 6123/7185/13792 6124/6805/13377 6125/7126/13719 +f 6292/6429/13046 6306/6117/12762 6291/6119/12764 +f 6780/7186/12498 6783/7187/12498 6815/7188/12498 +f 5881/6863/13440 5882/6709/13275 5879/5931/12589 +f 6211/6386/13004 6213/6252/12877 6212/6852/13428 +f 6317/7189/13793 6320/6382/13093 6319/6494/13095 +f 6268/6447/13057 6269/6538/13132 6264/6537/13131 +f 7749/7190/13794 7766/6328/12950 7765/7191/13795 +f 6119/7096/13692 6129/5834/12508 6127/7192/13796 +f 6615/6506/13106 6617/6124/12769 6602/6123/12768 +f 6936/7193/13797 6925/6480/12440 6935/6496/12440 +f 5875/7161/13760 5876/7194/13798 5969/6614/13192 +f 6622/7195/13799 6621/7196/13800 6618/6747/13314 +f 5962/7197/13801 5963/7198/13802 5911/6764/13333 +f 6934/7052/12440 6902/6717/12440 6930/6612/12440 +f 7587/7157/13803 7588/6887/13467 7562/5748/12434 +f 7693/7199/13804 7691/6207/13804 7692/6044/13804 +f 5759/6552/13805 5774/6154/13806 5771/6156/13807 +f 6134/6950/13539 6129/5834/12508 6119/7096/13692 +f 6210/6083/12729 6209/6163/12805 6212/6852/13428 +f 6816/7200/13808 6813/6416/13032 6828/7201/13809 +f 6814/6417/13033 6825/6152/13810 6826/7202/13811 +f 5923/5805/12482 6216/6586/13169 6215/7033/13621 +f 6823/7203/13812 6842/5889/12556 6856/7204/13813 +f 7705/5896/13814 7702/6534/13815 7703/5897/13815 +f 6357/5858/12527 6331/5903/12566 6356/7072/13816 +f 5823/6630/13211 5804/5817/13817 5822/6371/12989 +f 6606/6454/13818 6622/7195/13799 6623/7205/13819 +f 7752/7206/13820 7739/6053/13821 7740/6052/13822 +f 6043/6769/13823 6045/6771/13721 6164/7127/13720 +f 6165/7207/13824 6265/7208/13825 6266/7020/13608 +f 7635/6912/13501 7636/7209/13826 7634/6432/13049 +f 6448/6580/13827 6423/7210/13828 6424/6218/13829 +f 7855/7211/13830 7845/6007/13831 7856/7212/13832 +f 6470/7177/13782 6469/6205/12838 6509/7213/13833 +f 6257/6104/12748 6258/6103/13834 6256/6875/13453 +f 6097/5773/12452 6096/6191/12827 6098/5774/12453 +f 5918/5908/12569 5919/6162/12804 5917/6756/13326 +f 6255/6657/13231 6226/7121/13716 6256/6875/13453 +f 6233/6023/12674 6074/6881/13460 6232/6022/12673 +f 6261/5914/12575 6228/6609/13187 6254/5915/12576 +f 6743/7214/13835 6741/5752/12438 6742/7215/13836 +f 6215/7033/13621 6216/6586/13169 6217/6587/13170 +f 5972/6858/13435 5915/6690/13259 5870/6610/13188 +f 6257/6104/12748 6256/6875/13453 6260/6870/13448 +f 7895/6952/13540 7793/6954/13540 7896/7216/13540 +f 7414/6719/13285 7517/6071/12717 7518/7217/13837 +f 6259/6869/13838 6260/6870/13838 6174/5854/13838 +f 6081/6203/12836 6226/7121/13716 6059/6857/13433 +f 6091/7130/13725 6082/6190/12826 6070/6860/13437 +f 6364/7218/13839 6285/6830/13406 6288/6793/13365 +f 7975/6024/12675 7963/6706/13770 7976/6532/13126 +f 6432/5935/12708 6460/6831/12708 6430/5936/12708 +f 6152/6319/12942 6270/7219/13840 6165/7207/13824 +f 6165/7207/13824 6270/7219/13840 6265/7208/13825 +f 7503/7151/13746 7488/7140/13841 7489/7150/13745 +f 6241/7220/13842 6246/6374/12993 6201/6605/13184 +f 6068/6217/12850 6090/7129/13724 6069/7221/13843 +f 5995/6595/13176 5996/7022/13610 5993/6467/13073 +f 6117/7125/13718 6123/7185/13792 6125/7126/13719 +f 6814/6417/12498 6813/6416/12498 6804/5943/12498 +f 7833/7222/13292 7831/7223/13844 7832/6890/13469 +f 5906/6959/13545 5907/7224/13845 5901/6074/12720 +f 6834/7225/13846 6847/7226/13847 6769/6058/12705 +f 6362/6289/12912 6393/6505/13102 6363/6504/13101 +f 6133/7092/13686 6120/7182/13788 6121/7093/13687 +f 6057/7227/13848 6058/7228/13849 6083/6856/13432 +f 6634/5852/12521 6591/7011/13595 6633/5850/12519 +f 6267/7021/13850 6270/7219/13850 6271/7165/13850 +f 6466/7016/13604 6454/6337/13603 6451/6336/13851 +f 6665/6486/13852 6658/6238/12867 6691/6240/12869 +f 6152/6319/13853 6271/7165/13853 6270/7219/13853 +f 6216/6586/13169 5925/6792/13364 5924/7051/13643 +f 6272/6539/13854 6057/7227/13848 6083/6856/13432 +f 6272/6539/13855 6083/6856/13855 6264/6537/13855 +f 5876/7194/13798 5877/6615/13193 5969/6614/13192 +f 6798/6011/13483 6775/6800/13372 6776/6848/13481 +f 6758/6344/12961 6763/6412/13028 6759/7229/12962 +f 6577/7230/13856 6576/6621/13200 6590/7231/13857 +f 7484/7232/13858 7483/7233/13859 7468/7234/13860 +f 8000/6277/12902 8001/5961/12617 7999/5963/12619 +f 5925/6792/13364 5988/5807/12484 5989/7050/13642 +f 6391/6357/12974 6393/6505/13102 6346/6267/12975 +f 7681/6971/13550 7680/6208/12841 7695/7235/13861 +f 6313/6607/13014 6316/6768/13014 6334/6093/13014 +f 7688/6838/13862 7690/7236/13863 7689/6920/13864 +f 6876/7237/12962 6875/7238/12962 6872/7239/12962 +f 6683/7042/13865 6663/6906/13493 6684/7040/13866 +f 6646/7240/13867 6645/6556/13146 6737/6558/13148 +f 6429/5934/12592 6431/7241/12593 6432/5935/12593 +f 7661/6981/13868 7783/7242/13868 7781/7243/13868 +f 7505/6978/13560 7425/7244/13869 7504/7245/13870 +f 7753/7246/13871 7754/6122/12767 7751/6121/12766 +f 6223/6263/12888 6225/5938/12596 6222/5937/12595 +f 6244/6773/13342 6243/6825/13398 6245/6373/12992 +f 7907/6551/13872 8009/7073/13668 7908/6549/13141 +f 5997/7027/13615 5862/7247/13873 5930/6791/13363 +f 7706/7248/13874 7682/6536/13130 7704/6535/13129 +f 6165/7207/13824 6176/7249/13875 6166/5866/12535 +f 6427/6219/12708 6430/5936/12708 6456/6723/12708 +f 6933/6782/13353 6945/7250/13876 6934/7052/13645 +f 6299/6398/13877 6300/6864/13442 6301/6451/13441 +f 7963/6706/13056 7934/5983/13056 7964/6533/13056 +f 5795/6929/13878 5808/5778/13879 5809/6528/13880 +f 6067/6963/13547 6065/7251/13881 6081/6203/12836 +f 7964/6533/13056 7932/6471/13056 7962/5782/13056 +f 6082/6190/12826 6091/7130/13725 6095/7252/13882 +f 6456/6723/12708 6455/6220/12708 6427/6219/12708 +f 5987/5806/12483 5885/6645/13223 5867/6589/13172 +f 6803/5944/13883 6801/6900/13482 6776/6848/13481 +f 7538/6727/12862 7535/6584/12862 7537/6583/12862 +f 7602/7253/13884 7598/6660/13234 7619/6145/13581 +f 6720/6272/13885 6721/7254/13886 6706/7255/13887 +f 6574/6455/13064 6586/7256/13888 6587/7134/13889 +f 6208/6573/13160 6014/7081/13676 6015/7257/13890 +f 5928/7028/13616 5929/6490/13090 5863/7029/13617 +f 7573/6821/12847 7571/6820/12847 7602/7253/12847 +f 7835/6303/13291 7833/7222/13292 7834/6725/13292 +f 6193/6254/12879 6194/7258/13891 6212/6852/13428 +f 7847/6834/12518 7812/7259/12518 7843/6249/12518 +f 6750/7114/13708 6643/7115/13708 6748/7260/13708 +f 7476/7261/13892 7471/6020/12671 7494/6019/12670 +f 6042/6046/12693 6047/7262/13893 6164/7127/13720 +f 6160/6622/13201 6159/6624/13203 6161/7263/13894 +f 6626/7094/13688 6623/7205/13819 6523/7105/13701 +f 6194/7258/13891 6193/6254/12879 6186/7174/13779 +f 7546/6230/12860 7644/6037/12688 7645/7048/13640 +f 7563/6888/13468 7564/6543/13895 7555/7264/13895 +f 7900/7265/13054 7907/6551/13054 7905/6550/13054 +f 6772/6286/12498 6771/6109/12498 6777/6847/12498 +f 5785/5893/13896 5784/6466/13897 5783/5894/13898 +f 7725/7266/12562 7690/7236/12562 7722/7267/12562 +f 5885/6645/13223 5879/5931/12589 5887/5933/12591 +f 5819/5967/12623 5805/6226/12856 5806/5968/12624 +f 7842/7268/13899 7863/5911/12572 7862/7269/13900 +f 5930/6791/13363 5929/6490/13090 5928/7028/13616 +f 6510/7178/13783 6470/7177/13782 6509/7213/13833 +f 7700/7270/13901 7699/7271/13902 7701/6876/13903 +f 6112/6711/13277 6111/6670/13242 6076/6193/12829 +f 5752/6884/12985 5755/5792/12985 5753/6998/12985 +f 6696/6726/13904 6709/7272/13905 6710/7005/13906 +f 7962/5782/13056 7932/6471/13056 7959/6470/13056 +f 7419/7273/13907 7411/7274/12862 7413/6229/12862 +f 6955/7116/13908 6956/6910/13498 6889/6243/12872 +f 5768/7275/12494 5769/5816/12493 5800/5818/12494 +f 7443/6960/12542 7476/7261/12542 7445/6442/12542 +f 5864/6170/12812 5898/6172/12814 5904/6969/13549 +f 6248/5965/12621 6262/5913/12574 6254/5915/12576 +f 6239/6115/12760 6247/6375/12994 6241/7220/13842 +f 7662/6697/13909 7786/7084/13909 7668/6695/13909 +f 7967/6656/13910 8001/5961/12617 7966/6276/12901 +f 7667/7276/12956 7670/6108/12752 7665/6332/12954 +f 6714/5812/13911 6697/6976/13556 6713/6385/13633 +f 6723/7095/13690 6724/6728/13295 6705/5794/13691 +f 6711/5753/12439 6710/7005/13588 6739/7004/13587 +f 5800/5818/12494 5766/6626/12493 5768/7275/12494 +f 6365/6794/13366 6360/6633/13215 6349/6957/13543 +f 6218/6198/12834 6216/6586/13169 5924/7051/13643 +f 6775/6800/12498 6774/7061/12498 6777/6847/12498 +f 6220/6196/12832 6218/6198/12834 5863/7029/13617 +f 5869/7071/13665 5873/6795/13367 5870/6610/13188 +f 6233/6023/12674 6234/6018/12669 6139/6868/13446 +f 7957/5994/12649 7971/7277/13912 7970/6408/13024 +f 6245/6373/12992 6243/6825/13398 6200/6766/13335 +f 6774/7061/12498 6772/6286/12498 6777/6847/12498 +f 7715/6042/12562 7711/7278/12562 7720/6354/12562 +f 6172/6422/13038 6177/6048/12695 6178/6242/12871 +f 8019/6644/13054 8014/7279/13054 8018/7280/13054 +f 6826/7202/13913 6825/6152/12795 6862/6153/12796 +f 6560/6744/13914 6559/6748/13915 6540/7281/13916 +f 5794/6775/12493 5779/6578/12493 5781/6577/12493 +f 6247/6375/12994 6246/6374/12993 6241/7220/13842 +f 6919/6707/13272 6920/7282/13917 6922/6497/13273 +f 6905/6798/13918 6906/7283/13919 6894/5974/13920 +f 6900/7284/13921 6927/6986/13569 6892/5756/13568 +f 7424/6523/12862 7416/6565/12862 7425/7244/13869 +f 6153/6457/13066 5916/6822/13394 5864/6170/12812 +f 7711/7278/13922 7708/7138/13731 7709/7137/13731 +f 7790/5954/12610 7880/7112/13707 7881/5955/12611 +f 7805/7285/13923 7820/7286/13924 7822/7287/13925 +f 6679/6907/13926 6682/7168/13772 6680/6593/13926 +f 6761/6014/12962 6764/7288/12962 6765/6059/12962 +f 6168/6081/12727 6169/6665/13239 6238/6511/13111 +f 7505/6978/13560 7490/6270/12895 7506/6269/12894 +f 6065/7251/13881 6064/7289/13927 6081/6203/12836 +f 6800/6010/12498 6816/7200/12498 6817/5822/12498 +f 7412/6233/13928 7535/6584/13928 7536/7290/13928 +f 7465/7141/12542 7447/6443/12542 7478/6772/12542 +f 7594/6248/12847 7565/7291/12847 7593/7292/12847 +f 6420/7087/12708 6419/7293/12708 6415/7123/12708 +f 6520/6502/12683 6522/7106/13702 6523/7105/13701 +f 6759/7229/13929 6874/7294/13929 6875/7238/13929 +f 5924/7051/13643 5927/7295/13930 6218/6198/12834 +f 6380/5930/12588 6339/5929/12587 6338/6936/13524 +f 7609/6078/12724 7648/6617/13195 7608/6619/13197 +f 6977/7296/13931 6975/5832/12506 6964/7053/13932 +f 7603/7297/13933 7617/5941/12599 7616/5940/12598 +f 7969/6409/13934 8005/7298/13935 7968/6655/13936 +f 7797/7013/13598 7794/6953/13411 7791/6966/13411 +f 5991/7299/13937 5992/6574/13161 5990/6576/13163 +f 6834/7225/13846 6846/6352/12969 6847/7226/13847 +f 7864/5910/13938 7875/5785/12464 7872/6005/12660 +f 5786/6464/12493 5788/7300/12493 5797/6741/12493 +f 6773/6210/12843 6774/7061/13654 6790/7301/13939 +f 6756/7302/13940 6754/7303/13941 6860/7304/13942 +f 5815/6571/13943 5816/6724/13944 5794/6775/13344 +f 7953/6517/13739 7965/6278/12903 7984/6460/13069 +f 6555/5745/13945 6554/6647/13946 6553/5746/13946 +f 6812/5890/12498 6811/6666/12498 6808/6667/12498 +f 5821/6225/13947 5828/6914/13503 5831/7305/13948 +f 7862/7269/13900 7873/6006/12661 7892/7306/13949 +f 7575/6985/13566 7577/6824/13397 7559/6983/13564 +f 7514/7307/13950 7511/7025/13613 7495/6021/13951 +f 5802/7308/13952 5814/6572/13953 5815/6571/13943 +f 7829/6892/13471 7830/6891/13470 7828/7309/13954 +f 6806/6585/12498 6814/6417/12498 6804/5943/12498 +f 6671/6296/13955 6668/6295/13329 6669/6840/13956 +f 6212/6852/13428 6213/6252/12877 6193/6254/12879 +f 7902/7310/13957 8014/7279/13957 8015/7311/13957 +f 7990/7312/13958 7978/5783/13959 7979/7313/13960 +f 7516/6073/12719 7519/7314/13961 7517/6071/12717 +f 6780/7186/12498 6812/5890/12498 6808/6667/12498 +f 7992/6187/12823 7980/6189/12825 7981/5867/12536 +f 5747/6937/13526 5748/6367/12984 5741/7002/12984 +f 5941/7315/13962 5942/6314/12934 6000/6316/12936 +f 7436/7316/13963 7440/6677/13250 7438/7317/13964 +f 6146/7163/13762 6075/6035/12686 6145/7318/13965 +f 5800/5818/13213 5804/5817/13817 5823/6630/13211 +f 7583/6214/13966 7586/6213/13755 7584/7319/13967 +f 6019/6743/13309 6022/6391/13009 6187/6404/13020 +f 5848/6284/12907 5853/6283/12906 5851/6570/13157 +f 7964/6533/13127 7962/5782/12461 7977/5781/12460 +f 7742/7320/13968 7754/6122/12767 7741/6396/13969 +f 6818/5823/13970 6817/5822/13971 6830/7321/13972 +f 6056/7322/13973 6271/7165/13974 6055/7323/13975 +f 7523/6940/13529 7481/6029/13976 7525/7324/13977 +f 6457/6177/12708 6449/6991/12708 6438/6175/12708 +f 5913/5827/12501 5984/5829/12503 5870/6610/13188 +f 7901/6568/13155 7996/6567/13154 7997/7325/13978 +f 5776/5953/13979 5775/7326/13980 5774/6154/12797 +f 6661/7327/13981 6675/7047/13982 6673/7046/13983 +f 7462/6462/13243 7463/5874/13984 7464/6463/13985 +f 6744/5810/12487 6742/7215/13836 6647/6101/12745 +f 6987/6256/12881 6984/6664/13238 6986/7328/13986 +f 6099/5772/12451 6101/7089/13683 6236/5825/12499 +f 6986/7328/13986 6988/6257/12882 6987/6256/12881 +f 6149/7329/13987 6150/7330/13988 6051/7331/13989 +f 6413/6211/12846 6490/6097/12741 6488/6096/12740 +f 6901/7332/13990 6902/6717/13283 6904/6799/13371 +f 6453/6201/13991 6469/6205/13992 6458/6951/13993 +f 6252/6623/13202 6253/6932/13520 6251/6130/12775 +f 6364/7218/13839 6288/6793/13365 6365/6794/13366 +f 6275/6681/13994 6280/6680/13253 6381/6141/12786 +f 7662/6697/13995 7661/6981/13995 7781/7243/13995 +f 6232/6022/12673 5911/6764/13333 5912/5828/12502 +f 6020/5876/12543 6194/7258/13891 6186/7174/13779 +f 6831/6298/12918 6830/7321/13972 6844/5989/12645 +f 6833/6351/12968 6834/7225/13846 6821/7333/13996 +f 6460/6831/12708 6461/6381/12708 6430/5936/12708 +f 6139/6868/13446 6138/6867/13445 6140/7334/13997 +f 6668/6295/13329 6667/7335/13998 6669/6840/13956 +f 6603/7336/13999 6604/7337/14000 6579/5839/13485 +f 6602/6123/12768 6601/6827/14001 6615/6506/13106 +f 7904/6683/13696 8016/7100/13696 7905/6550/13696 +f 7869/6715/13281 7877/6716/13282 7868/7338/14002 +f 6148/7339/14003 6051/7331/13989 6167/5865/12534 +f 6697/6976/12472 6702/7340/12472 6687/7098/12472 +f 5795/6929/13878 5809/6528/13880 5799/7341/14004 +f 7415/6403/13019 7531/7342/14005 7532/6871/13449 +f 6772/6286/12909 6773/6210/12843 6787/6002/12845 +f 6768/7343/14006 6763/6412/13028 6867/5990/12646 +f 7577/6824/14007 7575/6985/14008 7576/7344/14009 +f 6355/5902/14010 6373/6360/12978 6374/6359/12977 +f 6163/5998/12653 6155/6997/13583 6156/6458/13067 +f 7429/6851/12542 7427/6461/12542 7428/7345/14011 +f 6537/7346/14012 6548/7108/13704 6536/7110/13706 +f 6721/7254/14013 6720/6272/12897 6657/7347/14014 +f 6949/6659/13233 6935/6496/14015 6950/6750/13320 +f 6901/7332/14016 6893/5754/14017 6892/5756/13568 +f 7878/7348/14018 7879/6710/13276 7880/7112/13707 +f 7736/6394/14019 7723/6393/13348 7737/6777/14020 +f 6674/5795/14021 6671/6296/13955 6672/7349/14022 +f 7445/6442/14023 7442/6850/14024 7443/6960/14025 +f 7496/6599/13180 7470/6598/13179 7497/7350/14026 +f 5990/6576/13163 5986/7351/14027 5959/6221/12851 +f 6872/7239/12962 6873/6012/12962 6877/7352/12962 +f 5870/6610/13188 5984/5829/12503 5867/6589/13172 +f 6895/7353/14028 6906/7283/13919 6908/7354/14029 +f 7674/5871/12540 7672/7355/13263 7668/6695/13263 +f 7968/6655/13229 7955/6654/13228 7969/6409/13025 +f 7899/6945/13534 8006/6944/13533 7907/6551/13872 +f 7856/7212/13832 7884/7356/14030 7855/7211/14031 +f 6976/6722/13288 6977/7296/13931 6978/6720/13286 +f 6896/5976/12440 6894/5974/12440 6895/7353/12800 +f 7623/7183/13790 7593/7292/14032 7605/5836/14033 +f 5817/6776/13464 5752/6884/13463 5818/5969/12625 +f 7547/6430/13047 7637/6813/13384 7543/6812/13383 +f 6768/7343/12962 6762/7357/12962 6760/7358/12962 +f 7492/7359/14034 7501/6271/12896 7491/6982/13563 +f 6527/6437/12683 6525/6031/12682 6531/6250/12875 +f 7719/7360/14035 7717/5895/13318 7734/6485/13087 +f 5819/5967/12623 5818/5969/12625 5829/6915/13505 +f 6514/6085/12583 6515/6483/12583 6519/6084/12583 +f 6157/6904/13491 6156/6458/13067 6249/5966/12622 +f 7414/6719/13285 7515/5885/12552 7517/6071/12717 +f 6498/7019/13607 6500/7361/14036 6482/6916/14037 +f 5832/6372/12991 5823/6630/13211 5822/6371/12989 +f 6664/6487/14038 6686/7362/14039 6684/7040/13866 +f 7740/6052/12699 7727/6054/12701 7728/6043/13012 +f 7423/7363/12862 7421/6525/12862 7426/6524/13119 +f 6130/7169/13773 6128/7364/14040 6129/5834/12508 +f 7564/6543/13895 7567/7365/14041 7556/6426/13042 +f 6580/5759/12441 6584/6625/12441 6556/7172/12441 +f 7637/6813/13384 7636/7209/13826 7621/6661/14042 +f 6089/6216/12849 6090/7129/13724 6068/6217/12850 +f 7599/6531/12847 7580/5764/12847 7592/6529/12847 +f 7618/6147/12792 7602/7253/13884 7619/6145/13581 +f 6412/7366/14043 6413/6211/12846 6488/6096/12740 +f 6679/6907/13926 6681/7367/14044 6682/7168/13772 +f 7480/6027/14045 7521/7368/14046 7479/6817/13388 +f 6960/5948/14047 6970/6377/12996 6888/7369/14048 +f 6938/5995/12440 6902/6717/12440 6934/7052/12440 +f 6316/6768/14049 6313/6607/13186 6314/6735/13424 +f 5931/6854/13430 5861/6261/12886 5862/7247/13873 +f 6283/6064/12710 6371/6358/12976 6370/7370/14050 +f 6627/7060/13653 6630/7371/14051 6588/7133/13728 +f 5994/7023/13611 5930/6791/13363 5928/7028/13616 +f 5884/6590/13173 5867/6589/13172 5888/7155/13752 +f 6555/5745/13945 6556/7172/13945 6554/6647/13946 +f 7448/6922/13513 7449/6178/13513 7451/6180/14052 +f 7682/6536/13130 7706/7248/13874 7683/7372/14053 +f 5955/7373/14054 5956/6223/12853 5985/6222/12852 +f 6889/6243/12872 6954/6137/12782 6955/7116/13908 +f 6298/7374/14055 6297/7171/13776 6289/7170/13775 +f 5748/6367/14056 5859/7000/14056 5855/7003/14056 +f 7616/5940/12598 7615/7375/14057 7601/7376/14058 +f 7893/7012/13411 7898/7377/13411 7894/7378/13411 +f 6324/6001/13622 6325/6636/14059 6323/6638/13623 +f 6586/7256/14060 6606/6454/13818 6624/7058/13651 +f 6257/6104/12748 6260/6870/13448 6263/6105/12749 +f 6015/7257/13890 6016/7379/14061 6206/6774/13343 +f 7800/5988/12644 7875/5785/12464 7865/7380/14062 +f 6224/6489/13089 6223/6263/12888 6222/5937/12595 +f 6675/7047/13982 6661/7327/13981 6662/6488/13088 +f 7701/6876/13903 7699/7271/13902 7698/6965/14063 +f 5982/7037/13627 5918/5908/12569 5981/7381/14064 +f 6358/6498/13097 6385/6139/12784 6342/7382/14065 +f 6606/6454/13063 6586/7256/13888 6574/6455/13064 +f 6547/5891/14066 6548/7108/14067 6549/5840/14068 +f 7630/6363/12981 7615/7375/14057 7631/6343/12960 +f 6605/7383/14069 6606/6454/13063 6578/6453/13062 +f 7691/6207/12840 7693/7199/14070 7680/6208/12841 +f 7907/6551/13054 7900/7265/13054 7899/6945/13054 +f 7435/6809/14071 7462/6462/13071 7427/6461/13070 +f 6934/7052/14072 6963/6415/13031 6938/5995/12650 +f 6415/7123/12708 6414/6579/12708 6422/7122/12708 +f 6780/7186/14073 6779/6111/14074 6781/6110/14075 +f 5915/6690/13259 5975/6086/12730 5865/6171/12813 +f 5792/6928/14076 5793/7384/14077 5766/6626/13207 +f 6284/6642/12905 6288/6793/13365 6285/6830/13406 +f 6175/6129/12774 6173/6131/12776 6178/6242/12871 +f 7761/7385/14078 7760/5775/12454 7759/7386/14079 +f 7790/5954/12610 7882/5800/12477 7789/6968/14080 +f 6222/5937/12595 6184/5819/12495 6188/6942/13531 +f 7627/6362/12980 7613/6765/13334 7614/7387/14081 +f 7609/6078/14082 7595/7388/14083 7610/6079/14084 +f 6334/6093/13014 6326/6268/13014 6313/6607/13014 +f 6186/7174/13779 6021/6392/13010 6023/7175/13780 +f 7415/6403/13019 7532/6871/13449 7533/6401/13017 +f 6254/5915/12576 6249/5966/12622 6248/5965/12621 +f 7512/5887/12554 7511/7025/13613 7514/7307/13950 +f 6852/6165/12807 6841/5888/12555 6840/7389/14085 +f 6375/5857/12526 6380/5930/12588 6338/6936/13524 +f 6231/6202/12835 6230/7156/13753 6081/6203/12836 +f 6315/6734/14086 6316/6768/14049 6314/6735/13424 +f 6204/6164/12806 6205/6495/13096 6195/5877/12544 +f 7464/6463/13985 7437/7390/14087 7436/7316/13963 +f 6171/7391/14088 6170/7392/14089 6177/6048/12695 +f 5853/6283/12906 5852/7393/14090 5851/6570/13157 +f 7707/7139/13732 7708/7138/13731 7706/7248/13732 +f 6317/7189/14091 6315/6734/13300 6294/6383/13002 +f 5956/6223/12853 5957/7394/14092 5958/6993/13576 +f 7991/6188/12824 7992/6187/12823 7909/6305/12926 +f 6847/7226/13847 6846/6352/12969 6843/6132/12777 +f 5915/6690/13259 5916/6822/13394 6237/5826/12500 +f 7671/5776/12455 7760/5775/12454 7666/6696/13264 +f 6409/7395/14093 6412/7366/14043 6487/7181/13787 +f 6961/5950/12607 6938/5995/12650 6962/6414/13030 +f 7497/7350/14094 7515/5885/12552 7496/6599/14095 +f 6713/6385/13003 6712/6563/13151 6743/7214/13835 +f 7956/5868/12537 7983/7145/13740 7982/5869/12538 +f 6203/6438/13053 6198/6067/12713 6202/6604/13183 +f 5752/6884/13463 5830/7396/14096 5818/5969/12625 +f 7794/6953/13411 7797/7013/13598 7793/6954/13597 +f 5897/7397/14097 5898/6172/12814 5865/6171/12813 +f 6654/7398/12916 6657/7347/14014 6655/5804/12481 +f 6465/7399/14098 6466/7016/13604 6451/6336/13851 +f 6710/7005/13906 6711/5753/12439 6698/7400/14099 +f 6854/7401/14100 6853/6166/12808 6852/6165/12807 +f 6325/6636/14059 6297/7171/14101 6299/6398/13877 +f 6286/6602/13181 6282/7402/14102 6279/6600/12905 +f 7732/6355/12972 7774/6895/13475 7731/6353/12970 +f 6870/6134/12779 6847/7226/13847 6843/6132/12777 +f 6001/6389/13007 5998/6594/13175 6000/6316/12936 +f 6219/6197/12833 6221/6893/13472 6190/6512/13112 +f 5821/6225/12855 5822/6371/12989 5803/6411/13487 +f 6613/6160/12802 6614/6507/13107 6599/6126/14103 +f 7749/7190/14104 7716/6040/14105 7729/6475/14106 +f 6126/7091/13685 6121/7093/13687 6122/6804/13376 +f 7842/7268/12518 7825/5921/12518 7853/5912/12518 +f 6367/5881/12548 6368/7403/14107 6369/7404/14108 +f 5899/5997/12652 5901/6074/12720 6163/5998/12653 +f 6695/6346/12472 6680/6593/12472 6682/7168/12472 +f 6819/6739/12498 6815/7188/12498 6783/7187/12498 +f 6216/6586/13169 6218/6198/12834 6219/6197/12833 +f 7446/6441/13055 7444/7405/13055 7445/6442/13055 +f 6936/7193/14109 6948/5813/12490 6937/6783/13354 +f 6243/6825/13398 6242/6931/13519 6160/6622/13201 +f 7439/6679/14110 7428/7345/14111 7438/7317/14112 +f 7563/6888/13468 7588/6887/13467 7590/6544/14113 +f 6175/6129/12774 6178/6242/12871 6180/5855/12524 +f 6213/6252/12877 6217/6587/13170 6192/6405/13021 +f 5985/6222/12852 5984/5829/12503 5912/5828/12502 +f 6633/5850/12519 6591/7011/13595 6632/7406/14114 +f 7940/5862/13489 7939/5864/14115 7941/6760/13490 +f 6084/6855/13431 6226/7121/13716 6255/6657/13231 +f 7458/7407/14116 7457/6515/13115 7459/7408/14116 +f 7750/7409/14117 7780/6653/13227 7778/6484/13086 +f 6792/7062/14118 6794/6843/13419 6793/6842/13418 +f 6101/7089/13683 6129/5834/12508 6236/5825/12499 +f 6532/6032/14119 6641/7410/14119 6642/6651/14119 +f 6877/7352/12962 6876/7237/12962 6872/7239/12962 +f 6197/7066/13660 6025/6116/12761 6239/6115/12760 +f 7916/6236/13056 7918/6445/13056 7915/7411/13056 +f 7771/7412/14120 7731/6353/12970 7774/6895/13475 +f 6047/7262/13893 6043/6769/13823 6164/7127/13720 +f 6921/6708/13274 6922/6497/13273 6923/7413/14121 +f 7731/6353/12970 7730/6473/14122 7715/6042/14123 +f 6643/7115/12916 6645/6556/12916 6644/7414/12914 +f 6221/6893/13472 6220/6196/12832 6224/6489/13089 +f 6640/7415/14124 6532/6032/14124 6525/6031/14124 +f 5789/6973/14125 5790/6930/14125 5788/7300/14126 +f 6920/7282/13917 6918/7166/14127 6917/6157/14128 +f 6598/5960/14129 6599/6126/12771 6583/6128/12773 +f 6525/6031/12682 6534/6030/12681 6530/7015/12682 +f 7863/5911/12572 7871/7416/14130 7862/7269/13900 +f 6050/7086/13681 6148/7339/14003 6167/5865/12534 +f 7651/6815/13386 7650/6923/13515 7611/6816/13387 +f 6129/5834/12508 6101/7089/13683 6130/7169/13773 +f 7478/6772/14131 7489/7150/13745 7465/7141/13735 +f 5967/6926/13518 5880/6862/13439 5879/5931/12589 +f 7904/6683/13054 7903/7417/14132 7913/6826/13399 +f 6191/6406/13022 6217/6587/13170 6219/6197/12833 +f 6418/7418/12708 6417/7419/12708 6415/7123/12708 +f 6764/7288/14133 6766/7420/14134 6850/5796/12473 +f 7716/6040/14105 7730/6473/14122 7729/6475/14106 +f 6227/7162/13761 6229/6603/13182 6228/6609/13187 +f 5867/6589/13172 5885/6645/13223 5888/7155/13752 +f 7710/7421/13922 7711/7278/13922 7713/6041/13358 +f 7767/6329/12951 7769/7422/14135 7770/7423/14136 +f 6866/7424/14137 6865/7425/14138 6867/5990/12646 +f 7883/7426/14139 7882/5800/12477 7854/5799/12476 +f 6351/6089/13216 6350/6955/13541 6360/6633/13215 +f 7474/7427/12542 7455/6514/12542 7475/6560/12542 +f 6946/6780/13351 6979/6779/13350 6945/7250/14140 +f 6826/7202/13913 6862/6153/12796 6863/7428/14141 +f 6312/6849/14142 6310/6606/14143 6293/6736/13302 +f 6278/6279/12904 6275/6681/13994 6377/7429/14144 +f 7915/7411/14145 7923/5884/14146 7925/6700/14147 +f 6579/5839/13485 6604/7337/14000 6578/6453/13062 +f 6731/5802/12479 6657/7347/14014 6730/6273/12898 +f 6176/7249/13875 6165/7207/13824 6266/7020/13608 +f 6289/7170/13775 6290/7430/14148 6300/6864/14149 +f 6640/7415/14124 6641/7410/14124 6532/6032/14124 +f 7677/6836/13412 7688/6838/13414 7678/6919/13509 +f 7865/7380/14062 7875/5785/12464 7864/5910/13938 +f 6891/6245/13591 6890/6323/13591 6889/6243/13591 +f 7853/5912/12573 7863/5911/12572 7842/7268/13899 +f 7887/7431/14150 7791/6966/14151 7885/7432/14152 +f 7513/5886/12553 7414/6719/13285 7417/6232/12861 +f 6110/6933/13521 6104/7433/14153 6105/6668/13240 +f 7818/5979/12634 7819/7434/14154 7817/6988/14155 +f 5963/7198/13802 5964/7435/14156 5953/7436/14157 +f 6330/7437/14158 6340/5928/14159 6341/6499/14160 +f 6750/7114/14161 6751/7438/14161 6649/6293/14161 +f 5999/7026/13614 5931/6854/13430 5862/7247/13873 +f 6829/7439/14162 6828/7201/13809 6867/5990/12646 +f 7547/6430/13047 7548/6313/12567 7554/6693/13262 +f 6194/7258/13891 6210/6083/12729 6212/6852/13428 +f 6589/6620/13199 6590/7231/13857 6576/6621/13200 +f 7575/6985/14008 7574/7440/14163 7576/7344/14009 +f 6443/6070/13104 6444/6069/14164 6445/6200/13105 +f 6651/7441/14165 6652/5899/14166 6644/7414/12914 +f 5853/6283/12906 5850/5790/12469 5755/5792/12471 +f 8008/7075/13670 8007/7074/13669 8006/6944/13533 +f 6101/7089/13683 6100/7054/13647 6102/6934/13522 +f 6762/7357/12962 6754/7303/12962 6755/6753/12962 +f 6560/6744/13311 6561/5758/13310 6559/6748/13316 +f 6000/6316/12936 5998/6594/13175 5939/6597/13178 +f 6252/6623/13202 6251/6130/12775 6250/5964/12620 +f 7663/6327/12949 7662/6697/12956 7666/6696/13264 +f 6726/7079/13674 6727/6491/13091 6718/5859/12528 +f 6719/5860/12529 6708/6787/14167 6707/5861/12530 +f 7506/6269/12894 7501/6271/12896 7507/6400/13016 +f 6504/7442/14168 6506/6899/13480 6505/6898/13479 +f 6213/6252/12877 6215/7033/13621 6217/6587/13170 +f 7661/6981/12956 7662/6697/12956 7663/6327/12949 +f 6054/7443/14169 6271/7165/13974 6152/6319/12942 +f 7721/7444/12562 7685/6785/12562 7716/6040/12562 +f 6827/6418/14170 6863/7428/14141 6866/7424/14137 +f 6782/6285/12908 6781/6110/12754 6771/6109/12753 +f 6303/7445/14171 6290/7430/14148 6291/6119/12764 +f 7895/6952/13596 7787/6967/13596 7794/6953/14172 +f 7689/6920/13864 7692/6044/14173 7691/6207/14173 +f 7618/6147/12792 7624/7446/14174 7617/5941/12599 +f 6128/7364/14040 6127/7192/13796 6129/5834/12508 +f 6249/5966/12622 6158/6905/13492 6157/6904/13491 +f 6463/6992/12708 6434/6100/12708 6436/6099/12708 +f 5752/6884/13463 5754/6366/14175 5830/7396/14096 +f 6867/5990/12646 6845/6672/13246 6829/7439/14162 +f 6186/7174/13779 6183/6253/12878 6185/6390/13008 +f 6552/7447/14176 6549/5840/14068 6550/7448/14177 +f 6682/7168/13772 6681/7367/14044 6683/7042/13632 +f 6433/6970/14178 6434/6100/14178 6432/5935/14178 +f 7772/7449/14179 7771/7412/14120 7768/6474/13077 +f 6924/7450/14180 6899/7451/14181 6923/7413/14182 +f 5821/6225/13947 5820/6224/13504 5828/6914/13503 +f 6244/6773/13342 6170/7392/14089 6171/7391/14088 +f 6500/7361/14036 6499/6192/12828 6503/6448/13058 +f 6253/6932/13520 6244/6773/13342 6171/7391/14088 +f 7985/6025/12676 8012/7452/14183 7974/6026/12677 +f 6808/6667/14184 6807/5982/14185 6809/6509/14186 +f 6659/6841/13417 6660/7453/14187 6670/6839/13415 +f 6861/7454/14188 6754/7303/13941 6864/7455/14189 +f 6502/6449/13059 6503/6448/13058 6504/7442/14168 +f 6951/6752/14190 6985/7456/14191 6950/6750/13634 +f 6111/6670/13242 6110/6933/13521 6105/6668/13240 +f 5860/6310/12931 5931/6854/13430 6001/6389/13007 +f 7978/5783/13959 7990/7312/13958 7977/5781/14192 +f 6186/7174/13779 6193/6254/12879 6183/6253/12878 +f 7545/6231/12567 7546/6230/12860 7550/7035/13625 +f 7989/7457/14193 7913/6826/13399 8013/7458/14194 +f 6137/6972/13551 6136/6866/13444 6135/6949/13538 +f 5988/5807/12484 5987/5806/12483 5867/6589/13172 +f 5912/5828/12502 5913/5827/12501 6234/6018/12669 +f 6831/6298/12918 6818/5823/13970 6830/7321/13972 +f 6789/6003/12658 6790/7301/14195 6791/6639/13219 +f 7952/6519/13056 7947/7459/13056 7955/6654/13056 +f 6267/7021/13609 6269/6538/13132 6268/6447/13057 +f 7870/5801/13408 7843/6249/14196 7854/5799/14197 +f 5819/5967/12623 5820/6224/12854 5805/6226/12856 +f 7585/5750/12436 7561/5749/12435 7584/7319/14198 +f 6170/7392/14089 6169/6665/13239 6177/6048/12695 +f 6169/6665/13239 6170/7392/14089 6244/6773/13342 +f 6248/5965/12621 6175/6129/12774 6262/5913/12574 +f 5959/6221/12851 5986/7351/14027 5985/6222/12852 +f 6359/5879/12546 6360/6633/13215 6366/5880/12547 +f 8011/7460/14199 8012/7452/14183 8013/7458/14194 +f 6337/6956/13014 6336/7461/13014 6307/6183/13014 +f 5916/6822/13394 6153/6457/13066 6230/7156/13753 +f 6986/7328/13986 6989/6634/13217 6991/6331/12953 +f 7482/7462/14200 7469/6028/14201 7468/7234/13860 +f 6714/5812/12489 6745/5811/12488 6746/7120/13715 +f 6662/6488/13088 6661/7327/14202 6660/7453/12472 +f 6490/6097/12741 6484/6051/12698 6475/7117/13712 +f 6333/6767/14203 6343/6924/14204 6344/6094/12738 +f 7490/6270/12895 7502/6979/13561 7489/7150/13745 +f 5997/7027/13615 5999/7026/13614 5862/7247/13873 +f 5908/6757/13327 5909/6364/12982 5918/5908/12569 +f 6782/6285/14205 6785/6476/13079 6783/7187/14206 +f 6424/6218/13829 6447/6335/14207 6448/6580/13827 +f 6373/6360/12978 6354/6632/14208 6370/7370/14050 +f 7478/6772/12542 7445/6442/12542 7477/7463/12542 +f 6175/6129/12774 6248/5965/12621 6251/6130/12775 +f 6607/7464/14209 6634/5852/12521 6636/5851/12520 +f 5770/7465/14210 5758/6553/14211 5771/6156/13807 +f 6392/7466/14212 6276/6503/13100 6393/6505/13102 +f 7971/7277/14213 8009/7073/13668 7970/6408/14214 +f 6074/6881/13460 6142/7467/14215 6143/6882/13461 +f 6181/6911/13499 6046/7085/13680 6167/5865/12534 +f 6727/6491/13091 6726/7079/13674 6728/6492/13092 +f 6563/7468/12441 6564/7469/12441 6575/7470/12558 +f 7414/6719/12862 7411/7274/12862 7412/6233/12862 +f 6082/6190/12826 6095/7252/13882 6096/6191/12827 +f 5779/6578/12493 5794/6775/12493 5777/5952/12493 +f 6038/7471/14216 6042/6046/12693 6177/6048/12695 +f 6190/6512/13112 6191/6406/13022 6219/6197/12833 +f 6030/6880/13459 6239/6115/12760 6031/6114/12759 +f 5744/6961/14217 5856/6338/14218 5857/7472/14217 +f 7450/7064/13658 7432/7063/13657 7448/6922/14219 +f 7494/6019/14220 7510/5842/12513 7493/5841/12512 +f 6276/6503/13100 6392/7466/14212 6391/6357/12974 +f 6237/5826/12500 6097/5773/12452 6099/5772/12451 +f 6763/6412/13028 6758/6344/12961 6869/6413/13029 +f 6056/7322/13973 6272/6539/13854 6271/7165/13974 +f 6942/5949/12606 6959/6946/14221 6943/7473/14222 +f 7915/7411/14145 7926/6702/14223 7916/6236/12865 +f 6204/6164/12806 6203/6438/13053 6161/7263/13894 +f 7451/6180/12542 7473/6179/12542 7472/6562/12542 +f 6005/7474/14224 6009/6388/13006 6003/7475/14225 +f 7978/5783/12462 7962/5782/12461 7979/7313/14226 +f 6543/7476/12441 6542/6186/12441 6539/5747/12433 +f 6227/7162/13761 6256/6875/13453 6226/7121/13716 +f 6200/6766/13335 6160/6622/13201 6161/7263/13894 +f 7918/6445/13056 7916/6236/13056 7917/7477/13056 +f 6441/6181/12817 6439/7146/13741 6420/7087/13682 +f 6569/6151/14227 6568/6878/13455 6570/6712/13279 +f 8012/7452/14183 8010/7478/14228 7973/5844/12515 +f 6139/6868/13446 6140/7334/13997 6141/7479/14229 +f 5796/7136/14230 5800/5818/13213 5825/5956/12612 +f 6178/6242/12871 6181/6911/13499 6180/5855/12524 +f 5849/7480/14231 5848/6284/12907 5846/6918/13508 +f 6793/6842/12498 6821/7333/12498 6791/6639/12498 +f 5968/6616/13194 5878/6925/13517 5967/6926/13518 +f 7479/6817/13388 7516/6073/12719 7498/6072/12718 +f 7437/7390/12542 7463/5874/12542 7467/5873/12542 +f 7425/7244/13869 7505/6978/13560 7426/6524/13119 +f 6064/7289/13927 6063/6886/13466 6081/6203/12836 +f 6042/6046/12693 6164/7127/13720 6182/6047/12694 +f 7703/5897/13815 7702/6534/13815 7701/6876/13903 +f 7510/5842/12513 7494/6019/14220 7511/7025/13613 +f 6267/7021/13609 6266/7020/13608 6265/7208/13825 +f 5757/7481/12493 5756/6300/12493 5764/6299/12493 +f 7508/6399/13015 7509/6874/13452 7423/7363/14232 +f 6408/6676/12583 6401/6482/12583 6407/6241/12870 +f 6342/7382/14065 6341/6499/13098 6358/6498/13097 +f 7654/7482/14233 7653/7483/14234 7651/6815/13386 +f 6855/7484/14235 6856/7204/13813 6842/5889/12556 +f 6086/6342/12959 6087/7485/14236 6068/6217/12850 +f 6418/7418/14237 6431/7241/14238 6417/7419/14239 +f 7718/7486/12692 7707/7139/12562 7719/7360/12562 +f 6759/7229/14240 6876/7237/14241 6767/6345/14241 +f 6430/5936/12708 6461/6381/12708 6456/6723/12708 +f 7531/7342/14005 7484/7232/14242 7485/7487/14243 +f 7714/6786/14244 7684/6921/14245 7676/7488/14246 +f 6742/7215/13836 6740/5751/12437 6647/6101/12745 +f 6937/6783/12440 6925/6480/12440 6936/7193/13797 +f 8010/7478/14228 8011/7460/14199 7908/6549/13141 +f 7526/7489/14247 7527/7490/14248 7524/6941/13530 +f 6503/6448/13058 6501/6450/13060 6500/7361/14036 +f 6156/6458/13067 6155/6997/13583 6250/5964/12620 +f 6188/6942/13531 6184/5819/12495 6019/6743/13309 +f 7662/6697/13995 7781/7243/13995 7782/7491/13995 +f 5795/6929/12493 5799/7341/12493 5790/6930/12493 +f 6007/7492/14249 6004/7493/14250 6005/7474/14224 +f 5870/6610/13188 5875/7161/13760 5969/6614/13192 +f 6847/7226/13847 6870/6134/12779 6871/6877/13454 +f 5916/6822/13394 5915/6690/13259 5865/6171/12813 +f 6517/6902/12583 6516/6687/12583 6514/6085/12583 +f 6239/6115/12760 6240/6879/13458 6238/6511/13111 +f 5924/7051/13643 5989/7050/13642 5926/6575/13162 +f 6414/6579/13165 6415/7123/14251 6423/7210/14252 +f 5940/6596/13177 5941/7315/13962 6000/6316/12936 +f 7627/6362/12980 7654/7482/14233 7613/6765/13334 +f 5936/7494/14253 5938/7495/14254 6000/6316/12936 +f 6269/6538/13764 6267/7021/14255 6271/7165/13765 +f 6250/5964/12620 6249/5966/12622 6156/6458/13067 +f 7536/7290/13114 7540/7496/13114 7421/6525/13114 +f 6472/7158/13757 6473/7497/14256 6463/6992/14257 +f 6854/7401/14100 6851/7498/14258 6766/7420/14134 +f 6699/6564/12472 6697/6976/12472 6689/6265/12472 +f 6803/5944/14259 6802/7499/14260 6801/6900/14261 +f 6263/6105/12749 6266/7020/13608 6268/6447/13057 +f 7554/6693/13262 7632/6431/13048 7547/6430/13047 +f 7769/7422/14135 7749/7190/13794 7768/6474/13077 +f 7915/7411/13056 7922/7500/13056 7914/7501/13056 +f 6429/5934/14262 6428/7502/14263 6416/7503/14264 +f 6598/5960/12616 6610/5959/12615 6611/6894/13474 +f 5758/6553/13145 5757/7481/12493 5760/6112/12756 +f 7861/6540/13134 7892/7306/13949 7891/6541/13135 +f 5926/6575/13162 5863/7029/13617 5927/7295/13930 +f 7928/6237/12866 7916/6236/12865 7926/6702/14223 +f 6875/7238/12962 6874/7294/12962 6872/7239/12962 +f 7800/5988/12644 7877/6716/13282 7878/7348/14018 +f 6118/6803/13375 6126/7091/13685 6122/6804/13376 +f 6217/6587/13170 6191/6406/13022 6192/6405/13021 +f 6834/7225/13846 6833/6351/12968 6846/6352/12969 +f 5891/5909/12570 5977/6174/12816 5978/7030/13618 +f 6733/6648/13224 6735/6057/12704 6734/6056/12703 +f 5975/6086/12730 5976/6173/12815 5892/6258/12883 +f 5896/6260/12885 5865/6171/12813 5975/6086/12730 +f 6527/6437/12683 6524/7504/14265 6520/6502/12683 +f 6588/7133/14266 6589/6620/13199 6573/6150/13198 +f 5892/6258/12883 5976/6173/12815 5890/6421/13037 +f 5865/6171/12813 5864/6170/12812 5916/6822/13394 +f 5896/6260/12885 5897/7397/14097 5865/6171/12813 +f 5976/6173/12815 5891/5909/12570 5890/6421/13037 +f 6163/5998/12653 5864/6170/12812 5905/5996/12651 +f 6603/7336/14267 6602/6123/12768 6619/6125/12770 +f 5846/6918/13508 5845/5789/12468 5750/7505/14268 +f 6857/5767/12449 6855/7484/14235 6756/7302/13940 +f 7675/6333/12955 7739/6053/13821 7751/6121/12766 +f 6918/7166/13769 6898/5755/13768 6914/6368/12986 +f 7929/6472/13144 7930/6235/13143 7928/6237/13381 +f 6369/7404/14108 6370/7370/14050 6353/6356/14269 +f 6159/6624/13203 6155/6997/13583 6162/7506/14270 +f 7790/5954/12610 7788/7507/13597 7795/5986/12642 +f 5915/6690/13259 6236/5825/12499 6235/5833/12507 +f 5948/7508/14271 5939/6597/13178 5998/6594/13175 +f 6940/6751/12440 6920/7282/14272 6941/7509/12440 +f 7608/6619/14273 7595/7388/14083 7609/6078/14082 +f 5920/6807/13378 5879/5931/12589 5885/6645/13223 +f 7735/6749/13317 7778/6484/13086 7734/6485/13087 +f 5937/7510/14274 6002/7511/14275 6000/6316/12936 +f 6472/7158/13757 6449/6991/14276 6471/7176/13781 +f 6083/6856/13432 6058/7228/13849 6059/6857/13433 +f 5772/7512/12493 5773/6155/13027 5803/6411/12493 +f 6801/6900/14261 6800/6010/12662 6798/6011/12664 +f 7689/6920/13510 7678/6919/13509 7688/6838/13414 +f 5922/6808/13379 5920/6807/13378 5885/6645/13223 +f 7775/6896/13476 7776/6106/12750 7773/7077/13672 +f 7630/6363/12981 7631/6343/12960 7629/7513/14277 +f 5827/5957/12613 5825/5956/12612 5824/6631/13212 +f 7547/6430/13047 7542/5992/12567 7548/6313/12567 +f 6069/7221/13843 6090/7129/13724 6070/6860/13437 +f 6071/6859/13436 6081/6203/12836 6072/7514/14278 +f 7649/6077/12723 7648/6617/13195 7609/6078/12724 +f 5991/7299/13937 5994/7023/13611 5992/6574/13161 +f 6960/5948/14047 6888/7369/14048 6959/6946/13535 +f 6214/6387/13005 6211/6386/13004 5920/6807/13378 +f 7604/7515/12847 7578/5763/12847 7576/7344/12847 +f 6706/7255/13887 6721/7254/13886 6722/7516/14279 +f 5928/7028/13616 5992/6574/13161 5994/7023/13611 +f 6074/6881/13460 6077/7153/13748 6232/6022/12673 +f 6340/5928/12586 6380/5930/12588 6382/6138/12783 +f 6641/7410/12682 6640/7415/12683 6637/6501/12683 +f 6191/6406/13022 6189/6513/13113 6187/6404/13020 +f 6177/6048/12695 6172/6422/13038 6171/7391/14088 +f 6242/6931/13519 6243/6825/13398 6244/6773/13342 +f 7814/6790/13362 7811/6789/13361 7812/7259/14280 +f 6123/7185/13792 6118/6803/13375 6124/6805/13377 +f 7848/7517/12518 7832/6890/12518 7849/7518/12518 +f 5917/6756/13326 5919/6162/12804 6161/7263/13894 +f 7527/7490/14248 7526/7489/14247 7483/7233/13859 +f 6706/7255/12472 6704/5793/12472 6676/7045/12472 +f 6657/7347/14014 6733/6648/13224 6732/6649/13225 +f 7706/7248/13732 7705/5896/13814 7707/7139/13732 +f 7543/6812/13383 7542/5992/12567 7547/6430/13047 +f 6628/7135/13730 6624/7058/13651 6627/7060/13653 +f 7669/7101/13697 7780/6653/13227 7736/6394/14281 +f 7694/7519/12562 7692/6044/12562 7728/6043/12692 +f 6473/7497/14256 6474/6143/12788 6459/6061/14282 +f 7590/6544/14283 7589/6554/13756 7591/6545/14283 +f 5963/7198/13802 5954/7009/13593 5911/6764/13333 +f 7448/6922/13513 7447/6443/13514 7449/6178/13513 +f 6415/7123/14251 6416/7503/14264 6426/6909/14284 +f 7714/6786/14244 7676/7488/14246 7712/7520/14285 +f 6857/5767/12449 6756/7302/13940 6860/7304/13942 +f 5983/7038/13628 5965/7521/14286 5879/5931/12589 +f 7674/5871/12540 7755/6120/12765 7756/5872/12541 +f 6194/7258/13891 6196/5878/12545 6210/6083/12729 +f 5742/6781/14287 5741/7002/12984 5740/6340/14288 +f 5985/6222/12852 5912/5828/12502 5911/6764/13333 +f 7426/6524/13119 7424/6523/12862 7425/7244/13869 +f 7756/5872/12541 7742/7320/13968 7757/5870/12539 +f 7874/5784/12463 7873/6006/12661 7875/5785/12464 +f 5814/6572/13953 5801/6465/14289 5813/7522/14290 +f 6594/6521/14291 6595/6520/13723 6580/5759/14292 +f 6752/7523/12916 6751/7438/12916 6748/7260/12916 +f 6835/7173/13778 6836/6818/13390 6820/6737/13303 +f 7608/6619/14273 7596/6555/14293 7595/7388/14083 +f 7499/7524/14294 7526/7489/14247 7525/7324/13977 +f 5960/6994/13577 5949/6419/13035 5956/6223/12853 +f 6144/6883/13462 6145/7318/13965 6074/6881/13460 +f 7465/7141/12542 7449/6178/12542 7447/6443/12542 +f 7867/7525/14295 7877/6716/13282 7800/5988/12644 +f 6444/6069/12715 6422/7122/14296 6446/6581/13167 +f 6155/6997/13583 6163/5998/12653 6162/7506/14270 +f 6428/7502/14297 6429/5934/12592 6430/5936/12594 +f 6234/6018/12669 6233/6023/12674 5912/5828/12502 +f 7617/5941/12599 7624/7446/14174 7625/5939/12597 +f 5927/7295/13930 5924/7051/13643 5926/6575/13162 +f 6372/7526/14298 6376/5856/12525 6374/6359/12977 +f 7516/6073/12719 7479/6817/13388 7521/7368/14046 +f 6054/7443/14169 6152/6319/12942 6052/6308/12929 +f 5964/7435/14156 5952/7527/14299 5953/7436/14157 +f 6174/5854/12523 6175/6129/12774 6180/5855/12524 +f 6767/6345/12962 6761/6014/12962 6765/6059/12962 +f 6338/6936/13524 6327/6637/14300 6328/6397/13525 +f 5856/6338/12985 5854/7001/12985 5858/6999/12985 +f 5992/6574/13161 5928/7028/13616 5926/6575/13162 +f 6094/7528/14301 6076/6193/12829 6093/7529/14302 +f 6161/7263/13894 6162/7506/14270 5917/6756/13326 +f 6521/6500/12683 6520/6502/12683 6523/7105/13701 +f 7560/6823/13396 7579/5765/13395 7581/7530/14303 +f 5796/7136/14304 5826/7531/14305 5807/5779/14306 +f 5932/6407/13023 5933/6311/12932 5860/6310/12931 +f 5923/5805/12482 5925/6792/13364 6216/6586/13169 +f 6744/5810/12487 6743/7214/13835 6742/7215/13836 +f 7700/7270/14307 7681/6971/13550 7699/7271/14308 +f 6295/6384/13014 6294/6383/13014 6293/6736/13302 +f 5993/6467/13073 5994/7023/13611 5991/7299/13937 +f 6220/6196/12832 6221/6893/13472 6219/6197/12833 +f 6110/6933/13521 6101/7089/13683 6102/6934/13522 +f 6869/6413/13029 6871/6877/13454 6870/6134/12779 +f 7752/7206/13820 7740/6052/13822 7741/6396/13969 +f 6512/7180/13786 6409/7395/14093 6487/7181/13787 +f 6545/7532/14309 6546/7109/14310 6547/5891/14066 +f 6968/6244/12873 6969/7533/14311 6891/6245/12874 +f 5840/6320/12943 5742/6781/13352 5743/5788/12467 +f 6153/6457/13066 6163/5998/12653 6156/6458/13067 +f 7503/7151/13746 7504/7245/13870 7534/6402/13018 +f 6263/6105/12749 6259/6869/13447 6174/5854/12523 +f 6237/5826/12500 6236/5825/12499 5915/6690/13259 +f 7858/6425/13041 7889/6424/13040 7888/7068/13662 +f 5744/6961/14217 5746/6339/14218 5856/6338/14218 +f 7790/5954/12610 7789/6968/13411 7788/7507/13597 +f 6001/6389/13007 5999/7026/13614 5998/6594/13175 +f 7416/6565/13153 7539/6566/13153 7538/6727/13153 +f 7952/6519/14312 7955/6654/13228 7967/6656/13230 +f 6427/6219/13497 6426/6909/13496 6428/7502/14297 +f 7973/5844/12515 7986/7534/14313 7972/5845/12516 +f 6211/6386/13004 5921/7039/13629 5920/6807/13378 +f 7650/6923/13515 7651/6815/13386 7652/7535/14314 +f 5742/6781/14287 5745/6938/13527 5741/7002/12984 +f 6796/6844/12498 6810/6297/12498 6793/6842/12498 +f 6591/7011/13595 6592/7010/13594 6575/7470/14315 +f 5824/6631/13212 5823/6630/13211 5832/6372/12991 +f 6477/6379/12998 6476/7118/13713 6483/6050/12697 +f 6813/6416/12498 6816/7200/12498 6802/7499/12498 +f 6972/6376/12995 6888/7369/14048 6970/6377/12996 +f 7684/6921/13512 7714/6786/13357 7685/6785/13356 +f 6660/7453/14187 6661/7327/13981 6673/7046/13983 +f 6310/6606/14143 6308/6182/13045 6292/6429/13046 +f 6978/6720/13286 6881/7536/14316 6880/6721/13287 +f 6825/6152/12795 6824/7537/14317 6859/5768/12450 +f 5802/7308/12493 5781/6577/12493 5784/6466/12493 +f 7901/6568/13155 8002/5962/12618 7899/6945/13534 +f 5754/6366/12985 5753/6998/12985 5748/6367/12984 +f 7680/6208/12841 7677/6836/12692 7679/6209/14318 +f 6001/6389/13007 6009/6388/13006 6010/7006/13589 +f 6710/7005/13588 6709/7272/14319 6738/6557/13147 +f 7775/6896/13476 7773/7077/13672 7774/6895/13475 +f 6536/7110/12558 6535/7538/12558 6543/7476/12441 +f 7817/6988/13571 7803/6987/13570 7815/5980/13602 +f 7974/6026/12677 8012/7452/14183 7973/5844/12515 +f 7648/6617/13195 7649/6077/12723 7647/7539/14320 +f 6390/6318/12941 6389/7540/14321 6388/7541/14322 +f 7690/7236/13863 7688/6838/13862 7687/7542/14323 +f 5753/6998/13584 5859/7000/13584 5748/6367/13584 +f 6136/6866/13444 6235/5833/12507 6129/5834/12508 +f 7571/6820/12847 7568/7088/12847 7598/6660/12847 +f 7559/6983/13564 7577/6824/13397 7560/6823/13396 +f 7638/6814/13385 7640/6038/12689 7543/6812/13383 +f 6409/7395/14093 6512/7180/13786 6511/7543/14324 +f 6116/7544/14325 6117/7125/13718 6115/7076/13671 +f 7604/7515/14326 7613/6765/13334 7592/6529/13123 +f 6945/7250/13876 6933/6782/13353 6946/6780/14327 +f 6045/6771/13721 6048/7545/14328 6181/6911/13499 +f 6210/6083/12729 6205/6495/13096 6209/6163/12805 +f 6829/7439/14162 6817/5822/13971 6816/7200/13808 +f 5891/5909/12570 5979/7031/13619 5980/5907/12568 +f 7561/5749/12435 7582/7546/14329 7584/7319/14198 +f 6411/5923/14330 6518/5922/14330 6519/6084/14330 +f 5989/7050/13642 5988/5807/12484 5986/7351/14027 +f 6268/6447/13057 6264/6537/13131 6255/6657/13231 +f 5961/6763/13332 5962/7197/13801 5911/6764/13333 +f 6575/7470/12558 6581/6832/12441 6563/7468/12441 +f 6518/5922/12582 6403/5924/12582 6517/6902/12582 +f 7901/6568/13155 7902/7310/13054 7910/6306/12927 +f 5950/6468/13074 5993/6467/13073 5959/6221/12851 +f 7848/7517/14331 7849/7518/14332 7860/6542/14333 +f 7458/7407/14334 7434/6811/14334 7433/6810/13579 +f 6266/7020/13608 6263/6105/12749 6176/7249/13875 +f 6169/6665/13239 6168/6081/12727 6177/6048/12695 +f 5984/5829/12503 5985/6222/12852 5986/7351/14027 +f 6646/7240/13867 6737/6558/13148 6736/6055/12702 +f 6535/7538/14335 6536/7110/13706 6544/7547/14336 +f 6018/5821/12497 6019/6743/13309 6184/5819/12495 +f 6255/6657/13231 6264/6537/13131 6084/6855/13431 +f 6046/7085/13680 6049/7548/14337 6050/7086/13681 +f 7931/7549/14338 7933/5985/14339 7918/6445/14340 +f 5996/7022/13610 5997/7027/13615 5994/7023/13611 +f 6198/6067/12713 6195/5877/12544 6027/6065/12711 +f 6364/7218/13839 6361/6290/12913 6363/6504/13101 +f 6561/5758/13310 6562/6745/13312 6563/7468/14341 +f 6258/6103/12747 6255/6657/13231 6256/6875/14342 +f 6323/6638/13623 6320/6382/13093 6322/5999/13624 +f 6600/6127/13477 6599/6126/14103 6614/6507/13107 +f 6605/7383/14343 6604/7337/14344 6620/7550/14345 +f 6003/7475/14225 6009/6388/13006 6000/6316/12936 +f 6905/6798/13918 6894/5974/13920 6893/5754/14017 +f 6756/7302/13940 6757/6013/12962 6755/6753/12962 +f 7530/6168/12810 7484/7232/14242 7531/7342/14005 +f 6617/6124/12769 6615/6506/13106 6616/6508/13108 +f 5743/5788/12467 5750/7505/14268 5845/5789/12468 +f 5923/5805/12482 5922/6808/13379 5885/6645/13223 +f 5848/6284/12907 5851/6570/13157 5847/5973/12629 +f 6232/6022/12673 6078/7152/13747 6080/7149/13744 +f 7859/6423/13039 7891/6541/13135 7890/7551/14346 +f 6649/6293/12916 6654/7398/12916 6655/5804/12481 +f 6161/7263/13894 6203/6438/13053 6200/6766/13335 +f 5901/6074/12720 5899/5997/12652 5900/6075/12721 +f 7731/6353/12970 7772/7449/14179 7730/6473/13076 +f 7904/6683/14347 7911/6440/14348 8018/7280/14348 +f 6388/7541/14322 6286/6602/13181 6390/6318/12941 +f 6805/5942/12600 6807/5982/14185 6808/6667/14184 +f 7484/7232/14242 7527/7490/14248 7483/7233/13859 +f 7454/6629/13580 7432/7063/13657 7452/7065/13659 +f 6151/6307/12928 6053/7552/14349 6052/6308/12929 +f 6040/7553/14350 6039/7554/14351 6177/6048/12695 +f 6791/6639/13219 6790/7301/14195 6792/7062/14118 +f 7491/6982/13563 7477/7463/14352 7492/7359/14353 +f 7644/6037/12688 7642/5835/12509 7643/7142/13736 +f 7929/6472/13056 7927/6701/13056 7961/7555/13056 +f 6015/7257/13890 6206/6774/13343 6207/6262/12887 +f 5806/5968/12493 5775/7326/13027 5777/5952/12493 +f 5989/7050/13642 5990/6576/13163 5926/6575/13162 +f 7414/6719/13285 7518/7217/13837 7413/6229/12859 +f 6516/6687/13257 6400/5925/13257 6514/6085/13257 +f 7498/6072/12718 7497/7350/14026 7470/6598/13179 +f 5943/5918/12579 5948/7508/14271 5998/6594/13175 +f 6950/6750/13634 6985/7456/14191 6982/6658/13232 +f 6398/6641/12905 6397/7556/12905 6394/7557/12905 +f 5945/7083/13678 5947/5917/12578 5946/5916/12577 +f 6593/7102/13698 6592/7010/13594 6607/7464/14209 +f 5956/6223/12853 5955/7373/14054 5957/7394/14092 +f 7799/6350/12967 7798/6835/13411 7801/6349/12966 +f 5915/6690/13259 6235/5833/12507 5914/6611/13189 +f 6075/6035/12686 6132/6635/13218 6076/6193/12829 +f 7459/7408/14354 7461/6643/13245 7460/6671/13244 +f 6765/6059/12962 6769/6058/12705 6767/6345/12962 +f 6899/7451/14181 6921/6708/14355 6923/7413/14182 +f 7430/7067/12542 7433/6810/12542 7429/6851/12542 +f 7540/7496/12862 7535/6584/12862 7539/6566/12862 +f 7999/5963/12619 8002/5962/12618 7901/6568/13155 +f 6337/6956/13014 6307/6183/13014 6309/7558/13014 +f 6254/5915/12576 6158/6905/13492 6249/5966/12622 +f 5863/7029/13617 5929/6490/13090 6220/6196/12832 +f 6267/7021/14356 6265/7208/14356 6270/7219/14356 +f 6017/5820/12496 6184/5819/12495 6225/5938/12596 +f 6289/7170/13014 6296/6000/14357 6295/6384/13014 +f 7553/7559/14358 7551/7560/12567 7544/7034/12567 +f 6812/5890/12557 6815/7188/14359 6841/5888/12555 +f 5998/6594/13175 5999/7026/13614 5996/7022/13610 +f 6162/7506/14270 6161/7263/13894 6159/6624/13203 +f 6209/6163/12805 5919/6162/12804 5918/5908/12569 +f 5993/6467/13073 5991/7299/13937 5959/6221/12851 +f 5966/7561/14360 5967/6926/13518 5879/5931/12589 +f 6253/6932/13520 6252/6623/13202 6242/6931/13519 +f 7820/7286/14361 7823/5848/14362 7822/7287/14362 +f 6234/6018/12669 6235/5833/12507 6136/6866/13444 +f 6300/6864/14149 6298/7374/14055 6289/7170/13775 +f 5934/7007/13590 5932/6407/13023 6001/6389/13007 +f 6915/7154/12440 6913/7562/12440 6932/6901/12440 +f 6024/7563/14363 6197/7066/13660 6198/6067/12713 +f 5804/5817/13817 5803/6411/13487 5822/6371/12989 +f 5913/5827/12501 5914/6611/13189 6235/5833/12507 +f 7695/7235/14364 7698/6965/14063 7697/7564/14365 +f 6692/7103/12472 6666/6759/12472 6696/6726/12472 +f 6580/5759/14292 6595/6520/13723 6584/6625/13205 +f 6094/7528/14301 6085/6341/12958 6076/6193/12829 +f 7742/7320/14366 7726/6045/14367 7743/5809/14368 +f 5834/6939/13528 5833/5743/12429 5832/6372/12991 +f 6008/7565/14369 6007/7492/14249 6005/7474/14224 +f 6621/7196/13800 6620/7550/14345 6619/6125/12770 +f 6176/7249/13875 6263/6105/12749 6174/5854/12523 +f 6835/7173/14370 6769/6058/12705 6848/6060/12707 +f 7521/7368/14046 7520/6227/12857 7519/7314/13961 +f 6687/7098/12472 6702/7340/12472 6685/7041/12472 +f 7551/7560/14371 7548/6313/14371 7660/6452/14371 +f 6225/5938/12596 6223/6263/12888 6207/6262/12887 +f 6240/6879/13458 6030/6880/13459 6032/7179/13784 +f 6811/6666/14372 6824/7537/14317 6825/6152/13810 +f 6261/5914/12575 6262/5913/12574 6260/6870/13448 +f 6073/6885/13465 6072/7514/14278 6081/6203/12836 +f 6847/7226/13847 6871/6877/13454 6769/6058/12705 +f 7809/6304/12518 7806/7566/14373 7808/6302/12518 +f 6882/6640/13220 6996/6325/13220 6995/7567/13220 +f 6343/6924/14204 6333/6767/14203 6329/7568/14374 +f 7514/7307/13950 7495/6021/13951 7496/6599/14095 +f 5872/6704/13271 5868/7070/13664 5867/6589/13172 +f 7605/5836/12510 7641/6036/12687 7623/7183/14375 +f 6489/6095/12739 6490/6097/12741 6474/6143/12788 +f 6068/6217/12850 6076/6193/12829 6085/6341/12958 +f 6971/6378/12997 6965/5831/12505 6974/5830/12504 +f 6198/6067/12713 6201/6605/13184 6202/6604/13183 +f 6688/6266/14376 6665/6486/13852 6691/6240/12869 +f 6881/7536/14316 6983/6663/13237 6887/7024/13612 +f 5951/6469/13075 5944/7082/13677 5946/5916/12577 +f 6188/6942/13531 6019/6743/13309 6190/6512/13112 +f 6654/7398/14377 6753/5900/14377 6652/5899/14377 +f 7958/5846/13056 7938/6761/13056 7951/6705/13056 +f 6944/5770/12440 6909/5769/12440 6943/7473/14272 +f 6971/6378/12997 6962/6414/13030 6965/5831/12505 +f 7556/6426/13042 7567/7365/14041 7569/6427/13043 +f 5901/6074/12720 6162/7506/14270 6163/5998/12653 +f 5776/5953/13979 5777/5952/14378 5775/7326/13980 +f 6246/6374/12993 6245/6373/12992 6202/6604/13183 +f 6642/6651/12682 6641/7410/12682 6637/6501/12683 +f 6074/6881/13460 6139/6868/13446 6142/7467/14215 +f 6203/6438/13053 6204/6164/12806 6195/5877/12544 +f 6229/6603/13182 6227/7162/13761 6226/7121/13716 +f 6487/7181/13787 6488/6096/12740 6489/6095/12739 +f 6148/7339/14003 6149/7329/13987 6051/7331/13989 +f 5954/7009/13593 5955/7373/14054 5985/6222/12852 +f 7623/7183/14375 7639/7569/14379 7622/7184/13791 +f 6082/6190/12826 6097/5773/12452 6231/6202/12835 +f 6310/6606/13185 6312/6849/13423 6313/6607/13186 +f 7986/7534/14313 8010/7478/14228 8009/7073/13668 +f 6250/5964/12620 6251/6130/12775 6248/5965/12621 +f 7996/6567/13154 7994/7570/14380 7995/6692/13261 +f 6608/7571/14381 6534/6030/12681 6612/6161/12803 +f 6192/6405/13021 6187/6404/13020 6185/6390/13008 +f 6770/6510/13110 6771/6109/12753 6779/6111/12755 +f 7582/7546/14382 7581/7530/14383 7583/6214/13966 +f 5998/6594/13175 5946/5916/12577 5943/5918/12579 +f 6006/7572/14384 6008/7565/14369 6005/7474/14224 +f 6013/7080/13675 6208/6573/13160 5931/6854/13430 +f 5981/7381/14064 5918/5908/12569 5980/5907/12568 +f 7441/6678/13427 7429/6851/13426 7439/6679/14110 +f 6035/6699/13266 6168/6081/12727 6238/6511/13111 +f 6261/5914/12575 6227/7162/13761 6228/6609/13187 +f 7464/6463/13072 7436/7316/14385 7427/6461/13070 +f 6412/7366/14043 6411/5923/12583 6413/6211/12846 +f 5879/5931/12589 5965/7521/14286 5966/7561/14360 +f 6229/6603/13182 6230/7156/13753 6153/6457/13066 +f 6933/6782/12440 6930/6612/12440 6928/6481/12440 +f 6631/7573/14386 6629/7574/14387 6632/7406/14114 +f 5816/6724/13290 5815/6571/13158 5852/7393/14090 +f 6114/6034/12685 6116/7544/14325 6115/7076/13671 +f 5959/6221/12851 5991/7299/13937 5990/6576/13163 +f 7591/6545/12847 7593/7292/12847 7565/7291/12847 +f 6977/7296/13931 6964/7053/13932 6945/7250/14140 +f 6663/6906/13493 6664/6487/14038 6684/7040/13866 +f 6477/6379/12998 6483/6050/12697 6492/7131/13726 +f 6552/7447/12441 6554/6647/12441 6585/6646/12441 +f 7951/6705/13771 7973/5844/12515 7958/5846/12517 +f 5761/6113/12757 5762/5892/12559 5783/5894/12561 +f 6272/6539/13854 6056/7322/13973 6057/7227/13848 +f 7543/6812/13383 7640/6038/12689 7546/6230/12860 +f 6726/7079/13674 6717/7078/13673 6728/6492/13092 +f 6976/6722/13288 6975/5832/12506 6977/7296/13931 +f 5954/7009/13593 5963/7198/13802 5953/7436/14157 +f 7434/6811/14334 7460/6671/14388 7435/6809/14071 +f 6021/6392/13010 6186/7174/13779 6185/6390/13008 +f 6495/6017/12668 6407/6241/12870 6496/6015/12666 +f 6466/7016/13604 6502/6449/13059 6504/7442/14168 +f 6218/6198/12834 5927/7295/13930 5863/7029/13617 +f 6862/6153/12796 6861/7454/14188 6864/7455/14189 +f 6831/6298/12918 6844/5989/12645 6868/5991/12647 +f 5931/6854/13430 5999/7026/13614 6001/6389/13007 +f 6173/6131/12776 6171/7391/14088 6172/6422/13038 +f 6821/7333/13996 6810/6297/12917 6833/6351/12968 +f 6160/6622/13201 6242/6931/13519 6252/6623/13202 +f 6712/6563/13151 6711/5753/12439 6741/5752/12438 +f 7924/5883/13056 7956/5868/13056 7927/6701/13056 +f 6474/6143/12788 6473/7497/14256 6485/6144/12789 +f 5785/5893/13896 5786/6464/13896 5784/6466/13897 +f 5784/6466/13897 5781/6577/13164 5782/7575/14389 +f 7719/7360/14035 7733/7576/14390 7718/7486/14391 +f 6176/7249/13875 6179/5853/12522 6166/5866/12535 +f 6162/7506/14270 5901/6074/12720 5917/6756/13326 +f 6645/6556/12916 6646/7240/13867 6644/7414/12914 +f 6139/6868/13446 6074/6881/13460 6233/6023/12674 +f 6055/7323/13975 6271/7165/13974 6054/7443/14169 +f 6247/6375/12994 6244/6773/13342 6245/6373/12992 +f 6587/7134/13729 6586/7256/14060 6624/7058/13651 +f 6173/6131/12776 6251/6130/12775 6253/6932/13520 +f 7487/6873/13451 7473/6179/13734 7488/7140/13733 +f 6097/5773/12452 6237/5826/12500 6231/6202/12835 +f 6087/7485/14236 6088/6215/12848 6068/6217/12850 +f 7961/7555/14392 7981/5867/12536 7960/7577/14393 +f 6181/6911/13499 6182/6047/12694 6164/7127/13720 +f 6849/5798/12475 6764/7288/14133 6850/5796/12473 +f 6577/7230/13856 6590/7231/13857 6591/7011/13595 +f 5911/6764/13333 6079/7148/13743 5910/6762/13331 +f 6166/5866/12535 6167/5865/12534 6151/6307/12928 +f 7431/7578/14394 7448/6922/14219 7432/7063/13657 +f 6828/7201/13809 6866/7424/14137 6867/5990/12646 +f 6136/6866/13444 6139/6868/13446 6234/6018/12669 +f 6754/7303/13941 6762/7357/14395 6864/7455/14189 +f 6239/6115/12760 6241/7220/13842 6197/7066/13660 +f 6178/6242/12871 6182/6047/12694 6181/6911/13499 +f 6152/6319/12942 6165/7207/13824 6166/5866/12535 +f 5931/6854/13430 5860/6310/12931 6013/7080/13675 +f 6241/7220/13842 6201/6605/13184 6197/7066/13660 +f 6028/7579/14396 6029/7056/13649 6199/7055/13648 +f 7659/6694/13785 7544/7034/13785 7551/7560/13785 +f 6291/6119/12764 6305/6118/12763 6303/7445/14171 +f 6837/6738/14397 6848/6060/12707 6849/5798/12475 +f 6107/6195/12831 6108/6685/13255 6076/6193/12829 +f 7521/7368/14046 7522/6228/12858 7520/6227/12857 +f 5921/7039/13629 6211/6386/13004 5918/5908/12569 +f 7843/6249/14196 7855/7211/13830 7854/5799/14197 +f 6026/6066/12712 6024/7563/14363 6198/6067/12713 +f 5990/6576/13163 5989/7050/13642 5986/7351/14027 +f 6302/6865/13443 6303/7445/14398 6304/6317/12937 +f 6778/5981/12637 6770/6510/13110 6807/5982/12638 +f 7553/7559/14358 7654/7482/14233 7628/6361/12979 +f 7770/7423/14136 7663/6327/12949 7767/6329/12951 +f 6724/6728/13295 6732/6649/13225 6734/6056/12703 +f 6933/6782/13353 6947/6784/13355 6946/6780/14327 +f 6332/5901/13014 6331/5903/13014 6301/6451/13014 +f 6207/6262/12887 6208/6573/13160 6015/7257/13890 +f 5852/7393/14090 5853/6283/12906 5816/6724/13290 +f 6467/7017/13605 6466/7016/13604 6505/6898/13479 +f 7783/7242/14399 7667/7276/14399 7665/6332/14399 +f 6016/7379/14061 6017/5820/12496 6206/6774/13343 +f 6620/7550/14345 6621/7196/13800 6605/7383/14343 +f 7507/6400/13016 7426/6524/13119 7506/6269/12894 +f 5842/6526/13120 5808/5778/12457 5841/5780/12459 +f 6562/6745/13312 6565/6184/13457 6564/7469/14400 +f 5867/6589/13172 5866/6588/13171 5871/6703/13270 +f 7775/6896/13476 7734/6485/13087 7776/6106/12750 +f 6433/6970/14401 6418/7418/14237 6419/7293/14402 +f 6132/6635/13218 6106/6194/12830 6076/6193/12829 +f 6370/7370/14050 6369/7404/14108 6368/7403/14107 +f 6147/7164/13763 6113/6033/12684 6075/6035/12686 +f 6979/6779/13350 6980/5815/12492 6978/6720/13286 +f 6024/7563/14363 6025/6116/12761 6197/7066/13660 +f 6625/7059/13652 6624/7058/13651 6606/6454/13818 +f 7628/6361/12979 7654/7482/14233 7627/6362/12980 +f 6524/7504/14265 6632/7406/14114 6629/7574/14387 +f 7890/7551/14346 7891/6541/13135 7792/7014/13599 +f 6168/6081/12727 6033/7043/13635 6037/6082/12728 +f 7857/7069/14403 7844/6009/13575 7858/6425/13574 +f 6226/7121/13716 6081/6203/12836 6229/6603/13182 +f 7666/6696/13264 7668/6695/13263 7671/5776/12455 +f 6533/6159/12801 6528/6746/13313 6616/6508/13108 +f 6020/5876/12543 6028/7579/14396 6199/7055/13648 +f 6039/7554/14351 6038/7471/14216 6177/6048/12695 +f 6163/5998/12653 6153/6457/13066 5864/6170/12812 +f 5949/6419/13035 5950/6468/13074 5959/6221/12851 +f 6387/6754/13324 6389/7540/14321 6386/6755/13325 +f 7776/6106/12750 7670/6108/12752 7664/6980/13562 +f 6175/6129/12774 6174/5854/12523 6262/5913/12574 +f 7615/7375/14057 7626/6478/13081 7614/7387/14081 +f 6453/6201/12708 6458/6951/12708 6442/6199/12708 +f 5795/6929/13878 5796/7136/14304 5807/5779/14306 +f 7884/7356/14030 7856/7212/13832 7885/7432/14152 +f 7889/6424/13040 7887/7431/14150 7888/7068/13662 +f 6051/7331/13989 6053/7552/14349 6167/5865/12534 +f 5830/7396/14096 5754/6366/14175 5831/7305/13948 +f 6479/7580/14404 6494/7132/13727 6495/6017/12668 +f 6395/7581/14405 6274/6281/14405 6281/6280/14405 +f 5870/6610/13188 5867/6589/13172 5869/7071/13665 +f 7798/6835/14406 7898/7377/14406 7897/7582/14406 +f 6041/6080/12726 6040/7553/14350 6177/6048/12695 +f 5916/6822/13394 6230/7156/13753 6231/6202/12835 +f 6183/6253/12878 6192/6405/13021 6185/6390/13008 +f 7807/7583/14407 7828/7309/14408 7830/6891/14409 +f 6171/7391/14088 6173/6131/12776 6253/6932/13520 +f 6783/7187/12498 6785/6476/12498 6819/6739/12498 +f 7980/6189/12825 7960/7577/14393 7981/5867/12536 +f 6403/5924/14410 6516/6687/14410 6517/6902/14410 +f 6222/5937/12595 6188/6942/13531 6221/6893/13472 +f 6161/7263/13894 5919/6162/12804 6204/6164/12806 +f 6698/7400/14202 6699/6564/12472 6690/6264/12472 +f 7418/6582/13168 7535/6584/13168 7411/7274/13168 +f 7834/6725/12518 7844/6009/12518 7836/6008/12518 +f 7663/6327/12949 7773/7077/13672 7664/6980/13562 +f 6013/7080/13675 5860/6310/12931 6012/6913/13502 +f 7852/5847/14411 7865/7380/14412 7853/5912/12573 +f 6101/7089/13683 6099/5772/12451 6100/7054/13647 +f 5988/5807/12484 5984/5829/12503 5986/7351/14027 +f 6092/6669/13241 6093/7529/14302 6111/6670/13242 +f 7847/6834/12518 7846/6833/12518 7816/6788/12518 +f 6465/7399/14098 6501/6450/13060 6502/6449/13059 +f 5938/7495/14254 5937/7510/14274 6000/6316/12936 +f 5995/6595/13176 5998/6594/13175 5996/7022/13610 +f 5930/6791/13363 5994/7023/13611 5997/7027/13615 +f 6110/6933/13521 6103/6935/13523 6104/7433/14153 +f 6580/5759/14413 6581/6832/14413 6593/7102/14413 +f 6179/5853/12522 6176/7249/13875 6174/5854/12523 +f 7752/7206/13820 7741/6396/13969 7753/7246/13871 +f 6794/6843/13655 6774/7061/13654 6795/6802/13374 +f 8009/7073/13668 7971/7277/14213 7987/7584/14414 +f 8007/7074/13669 8009/7073/13668 7907/6551/13872 +f 6000/6316/12936 5935/6315/12935 5936/7494/14253 +f 7677/6836/12692 7681/6971/13550 7683/7372/12562 +f 6139/6868/13446 6141/7479/14229 6142/7467/14215 +f 6076/6193/12829 6111/6670/13242 6093/7529/14302 +f 7554/6693/13262 7629/7513/14277 7631/6343/12960 +f 6196/5878/12545 6194/7258/13891 6020/5876/12543 +f 6397/7556/12905 6396/7585/12905 6394/7557/12905 +f 6824/7537/14317 6823/7203/13812 6858/5766/12448 +f 5746/6339/12985 5750/7505/14268 5743/5788/14288 +f 6295/6384/13001 6296/6000/12655 6322/5999/12654 +f 6282/7402/14102 6280/6680/13253 6279/6600/12905 +f 6938/5995/12650 6963/6415/13031 6962/6414/13030 +f 7899/6945/13534 8002/5962/12618 8003/6943/13532 +f 7872/6005/12660 7873/6006/12661 7871/7416/14130 +f 6851/7498/14258 6854/7401/14100 6852/6165/12807 +f 7944/7586/14415 7947/7459/14416 7946/7587/14416 +f 6974/5830/12504 6976/6722/13288 6973/6684/13254 +f 6612/6161/12803 6611/6894/13474 6608/7571/14381 +f 6796/6844/13420 6795/6802/14417 6797/6801/13637 +f 6003/7475/14225 6006/7572/14384 6005/7474/14224 +f 7789/6968/14080 7884/7356/14030 7885/7432/14152 +f 5907/7224/13845 5908/6757/13327 5901/6074/12720 +f 6530/7015/13600 6534/6030/12681 6594/6521/13117 +f 5862/7247/13873 5861/6261/12886 5930/6791/13363 +f 5975/6086/12730 5894/6088/12732 5895/6259/12884 +f 5839/6321/12944 5807/5779/12458 5826/7531/14418 +f 6971/6378/12997 6973/6684/13254 6972/6376/12995 +f 6181/6911/13499 6048/7545/14328 6046/7085/13680 +f 7669/7101/13697 7737/6777/13346 7675/6333/12955 +f 5984/5829/12503 5988/5807/12484 5867/6589/13172 +f 6668/6295/12472 6696/6726/12472 6666/6759/12472 +f 6521/6500/13099 6638/6652/13099 6637/6501/13099 +f 7841/6675/13249 7812/7259/14280 7811/6789/13361 +f 6623/7205/13819 6626/7094/13688 6625/7059/13652 +f 7660/6452/12567 7655/5905/12567 7659/6694/12567 +f 6688/6266/14376 6686/7362/14039 6664/6487/14038 +f 6424/6218/13829 6425/6908/13495 6427/6219/13497 +f 6053/7552/14349 6151/6307/12928 6167/5865/12534 +f 7693/7199/13804 7692/6044/13804 7694/7519/13804 +f 6199/7055/13648 6027/6065/12711 6195/5877/12544 +f 6075/6035/12686 6074/6881/13460 6145/7318/13965 +f 6478/6380/12999 6477/6379/12998 6492/7131/13726 +f 5798/6742/13308 5799/7341/14004 5810/6527/13121 +f 5901/6074/12720 5902/6076/12722 5903/6958/13544 +f 6022/6391/13009 6185/6390/13008 6187/6404/13020 +f 6687/7098/12472 6689/6265/12472 6697/6976/12472 +f 6002/7511/14275 6003/7475/14225 6000/6316/12936 +f 6595/6520/13116 6534/6030/12681 6596/5947/12604 +f 6698/7400/14202 6690/6264/12472 6692/7103/12472 +f 7431/7578/14394 7433/6810/12542 7430/7067/12542 +f 7595/7388/14083 7600/6212/14419 7610/6079/14084 +f 6884/6434/14420 6995/7567/14420 6994/6435/14420 +f 6898/5755/12440 6894/5974/12440 6897/5975/12440 +f 7809/6304/12925 7835/6303/12924 7837/5760/14421 +f 7909/6305/13054 7911/6440/13054 7912/7167/13054 +f 7524/6941/13530 7527/7490/14248 7528/6167/12809 +f 7885/7432/14152 7856/7212/13832 7886/7104/13700 +f 6304/6317/12937 6301/6451/13441 6302/6865/13443 +f 7577/6824/14007 7576/7344/14009 7578/5763/12445 +f 7685/6785/13356 7687/7542/14323 7686/6837/13511 +f 6805/5942/12636 6777/6847/13883 6778/5981/12637 +f 6789/6003/12844 6773/6210/12843 6790/7301/13939 +f 7511/7025/13613 7420/6234/12863 7509/6874/13452 +f 7237/7588/14422 7236/7589/14423 7235/7590/14424 +f 7763/6861/13438 7765/7191/13795 7766/6328/12950 +f 6632/7406/14114 6524/7504/14265 6531/6250/12875 +f 7726/6045/14367 7741/6396/13013 7728/6043/13012 +f 6973/6684/13254 6976/6722/13288 6883/7591/14425 +f 7489/7150/13745 7478/6772/14131 7490/6270/12895 +f 5797/6741/12493 5801/6465/12493 5786/6464/12493 +f 6830/7321/13972 6829/7439/14162 6845/6672/13246 +f 6328/6397/13014 6327/6637/13014 6325/6636/13014 +f 7558/7113/12847 7556/6426/12847 7557/6428/12847 +f 7613/6765/13334 7654/7482/14233 7612/6530/13124 +f 6437/7147/14426 6438/6175/14426 6436/6099/12743 +f 7744/5808/14427 7725/7266/14428 7745/6548/14429 +f 6466/7016/13604 6465/7399/14098 6502/6449/13059 +f 7061/7592/14430 7126/7593/14431 7125/7594/14432 +f 7672/7355/14433 7758/5777/12456 7671/5776/12455 +f 5789/6973/13552 5764/6299/12920 5791/6301/12922 +f 7550/7035/13625 7652/7535/14314 7549/7036/13626 +f 7322/7595/14434 7156/7596/14435 7155/7597/14436 +f 7374/7598/14437 7237/7588/14422 7375/7599/14438 +f 7051/7600/14439 7122/7601/14440 7050/7602/14441 +f 7373/7603/14442 7267/7604/14443 7374/7598/14437 +f 6811/6666/14372 6825/6152/13810 6814/6417/13033 +f 7865/7380/14412 7852/5847/14411 7866/7605/14444 +f 6631/7573/14386 6630/7371/14051 6629/7574/14387 +f 7499/7524/14294 7525/7324/13977 7482/7462/14200 +f 6458/6951/14445 6470/7177/13782 6471/7176/13781 +f 6606/6454/13818 6621/7196/13800 6622/7195/13799 +f 6885/7008/14446 6879/6733/14447 6993/6732/14446 +f 7912/7167/14448 7989/7457/14193 7976/6532/13126 +f 6791/6639/13219 6792/7062/14118 6793/6842/13418 +f 7317/7606/14449 7318/7607/14450 7312/7608/14451 +f 6400/5925/12583 6404/6688/12583 6405/6274/12899 +f 6832/6133/12778 6831/6298/12918 6870/6134/12779 +f 6279/6600/14452 6273/6682/14452 6394/7557/14452 +f 8012/7452/14183 7985/6025/12676 7989/7457/14193 +f 7305/7609/14453 7317/7606/14449 7304/7610/14454 +f 6437/7147/14426 6436/6099/12743 6435/6098/12742 +f 7743/5809/12486 7758/5777/12456 7757/5870/12539 +f 7158/7611/14455 7334/7612/14456 7333/7613/14457 +f 6382/6138/12783 6380/5930/12588 6381/6141/12786 +f 7706/7248/13732 7704/6535/13814 7705/5896/13814 +f 7787/6967/13411 7791/6966/13411 7794/6953/13411 +f 7118/7614/14458 7029/7615/14459 7056/7616/14460 +f 6656/6292/12915 6653/6102/12746 6650/6927/12916 +f 6592/7010/13594 6581/6832/14461 6575/7470/14315 +f 7400/7617/14462 7392/7618/14463 7399/7619/14464 +f 7084/7620/14465 7081/7621/14466 7085/7622/14467 +f 6353/6356/14269 6352/6090/13359 6369/7404/14108 +f 7580/5764/12847 7578/5763/12847 7592/6529/12847 +f 7549/7036/13626 7652/7535/14314 7653/7483/14234 +f 7849/7518/14332 7861/6540/13134 7860/6542/14333 +f 6276/6503/13100 6285/6830/13406 6363/6504/13101 +f 6463/6992/14257 6473/7497/14256 6459/6061/14282 +f 7017/7623/14468 7025/7624/14469 7024/7625/14470 +f 6834/7225/13846 6835/7173/13778 6822/6889/13777 +f 7322/7595/14434 7363/7626/14471 7360/7627/14472 +f 7582/7546/14329 7560/6823/13396 7581/7530/14303 +f 6770/6510/12498 6778/5981/12498 6777/6847/12498 +f 5764/6299/12493 5763/6974/13027 5762/5892/12493 +f 7849/7518/12518 7829/6892/12518 7842/7268/12518 +f 7388/7628/14473 7387/7629/14474 7386/7630/14475 +f 7017/7623/14468 7024/7625/14470 7021/7631/14476 +f 7859/6423/13573 7844/6009/13575 7848/7517/14331 +f 6900/7284/12440 6898/5755/12440 6899/7451/12440 +f 7929/6472/13056 7961/7555/13056 7960/7577/13056 +f 6579/5839/12441 6578/6453/12441 6547/5891/12558 +f 7926/6702/14223 7915/7411/14145 7925/6700/14147 +f 7545/6231/12567 7550/7035/13625 7544/7034/12567 +f 6922/6497/12440 6920/7282/14272 6940/6751/12440 +f 6440/6176/14477 6438/6175/14426 6437/7147/14426 +f 6812/5890/12557 6842/5889/12556 6823/7203/13812 +f 7476/7261/12542 7443/6960/12542 7471/6020/12542 +f 7524/6941/13530 7419/7273/13907 7522/6228/12858 +f 6622/7195/13799 6523/7105/13701 6623/7205/13819 +f 6685/7041/12472 6703/6347/12472 6682/7168/12472 +f 7572/6984/13565 7558/7113/14478 7570/6819/14479 +f 7043/7632/14480 7301/7633/14481 7037/7634/14482 +f 6824/7537/14317 6858/5766/12448 6859/5768/12450 +f 7765/7191/13795 7748/7635/14483 7749/7190/13794 +f 6406/5926/12584 6503/6448/13058 6499/6192/12828 +f 7499/7524/14294 7483/7233/13859 7526/7489/14247 +f 6739/7004/13587 6740/5751/12437 6711/5753/12439 +f 7558/7113/14478 7557/6428/13044 7570/6819/14479 +f 7593/7292/14032 7606/5837/14484 7605/5836/14033 +f 7372/7636/14485 7373/7603/14442 7051/7600/14439 +f 7370/7637/14486 7371/7638/14487 7050/7602/14441 +f 5775/7326/13980 5773/6155/12798 5774/6154/12797 +f 7833/7222/14488 7835/6303/12924 7808/6302/12923 +f 6585/6646/14489 6597/5946/13204 6598/5960/14129 +f 6475/7117/13712 6462/6062/13711 6459/6061/14282 +f 6417/7419/14239 6429/5934/14262 6416/7503/14264 +f 5764/6299/12493 5762/5892/12493 5760/6112/12756 +f 7661/6981/13868 7667/7276/14490 7783/7242/13868 +f 7251/7639/14491 7213/7640/14492 7252/7641/14493 +f 5773/6155/12798 5772/7512/14494 5771/6156/12799 +f 6935/6496/12440 6922/6497/12440 6940/6751/12440 +f 6792/7062/13656 6790/7301/13939 6774/7061/13654 +f 7180/7642/14495 7315/7643/14496 7320/7644/14497 +f 6380/5930/12588 6378/7645/14498 6379/6522/13118 +f 6852/6165/12807 6840/7389/14085 6851/7498/14258 +f 7429/6851/13426 7428/7345/14111 7439/6679/14110 +f 6947/6784/13774 6980/5815/12492 6946/6780/13351 +f 6735/6057/12704 6733/6648/13224 6651/7441/14165 +f 7720/6354/12971 7718/7486/14391 7732/6355/12972 +f 7841/6675/13404 7811/6789/14499 7802/6829/13405 +f 7165/7646/14500 7336/7647/14501 7164/7648/14502 +f 6283/6064/12710 6287/6063/12905 6281/6280/12905 +f 6367/5881/12548 6366/5880/12547 6287/6063/12709 +f 7039/7649/14503 7040/7650/14504 7038/7651/14505 +f 7582/7546/14382 7583/6214/13966 7584/7319/13967 +f 6766/7420/14134 6764/7288/12962 6761/6014/12962 +f 7179/7652/14506 7175/7653/14507 7306/7654/14508 +f 7348/7655/14509 7333/7613/14457 7334/7612/14456 +f 7903/7417/14132 7904/6683/13054 7908/6549/13141 +f 7113/7656/14510 7032/7657/14511 7031/7658/14512 +f 7655/5905/12567 7660/6452/12567 7656/6312/12567 +f 7440/6677/13250 7436/7316/13963 7437/7390/14087 +f 7396/7659/14513 7401/7660/14514 7395/7661/14515 +f 7318/7607/14450 7317/7606/14449 7305/7609/14453 +f 6498/7019/13607 6480/6016/12667 6496/6015/12666 +f 6393/6505/13102 6391/6357/12974 6392/7466/14212 +f 7169/7662/14516 7163/7663/14517 7377/7664/14518 +f 7774/6895/13475 7770/7423/14136 7771/7412/14120 +f 7785/7665/12956 7783/7242/12956 7784/7666/12956 +f 7595/7388/12847 7589/6554/12847 7586/6213/12847 +f 7313/7667/14519 7311/7668/14520 7389/7669/14521 +f 6565/6184/13457 6566/7670/14522 6564/7469/14400 +f 7751/6121/12766 7755/6120/12765 7675/6333/12955 +f 8015/7311/14523 7906/6439/14523 7902/7310/14523 +f 7871/7416/14130 7873/6006/12661 7862/7269/13900 +f 7793/6954/13597 7792/7014/13599 7801/6349/12966 +f 6428/7502/14297 6430/5936/12594 6427/6219/13497 +f 6966/6947/13536 6967/6975/13554 6958/6948/13537 +f 6528/6746/13313 6529/6650/14524 6521/6500/12683 +f 6983/6663/13237 6981/5814/12491 6982/6658/13232 +f 6365/6794/13366 6366/5880/12547 6360/6633/13215 +f 7057/7671/14525 7342/7672/14526 7347/7673/14527 +f 7789/6968/14080 7882/5800/12477 7883/7426/14139 +f 7741/6396/13969 7754/6122/12767 7753/7246/13871 +f 7002/7674/14528 7036/7675/14529 7003/7676/14530 +f 7029/7615/14459 7115/7677/14531 7114/7678/14532 +f 7505/6978/13560 7504/7245/13870 7502/6979/13561 +f 5793/7384/14077 5765/6627/13208 5766/6626/13207 +f 7235/7590/14424 7234/7679/14533 7220/7680/14534 +f 7214/7681/14535 7245/7682/14536 7244/7683/14537 +f 6837/6738/13304 6838/5797/13693 6819/6739/13305 +f 6377/7429/14144 6378/7645/14498 6376/5856/12525 +f 7358/7684/14538 7356/7685/14539 7357/7686/14540 +f 7470/6598/12542 7437/7390/12542 7467/5873/12542 +f 6767/6345/12962 6758/6344/12961 6759/7229/12962 +f 7369/7687/14541 7220/7680/14534 7219/7688/14542 +f 7624/7446/14174 7633/6146/12791 7634/6432/13049 +f 7969/6409/13934 8008/7075/13670 8005/7298/13935 +f 6659/6841/13417 6669/6840/13416 6667/7335/14543 +f 7226/7689/14544 7206/7690/14545 7227/7691/14546 +f 7512/5887/12554 7514/7307/13950 7515/5885/12552 +f 7451/6180/12542 7472/6562/12542 7453/6561/12542 +f 7097/7692/14547 7094/7693/14548 7123/7694/14549 +f 7492/7359/14353 7476/7261/13892 7493/5841/14550 +f 5745/6938/13527 5747/6937/13526 5741/7002/12984 +f 6886/6255/12880 6889/6243/13591 6882/6640/13591 +f 6284/6642/13094 6398/6641/13094 6399/7695/13094 +f 6285/6830/13406 6276/6503/12905 6277/6601/12905 +f 6371/6358/12976 6373/6360/12978 6370/7370/14050 +f 7320/7644/14497 7315/7643/14496 7316/7696/14551 +f 7869/6715/13281 7846/6833/14552 7870/5801/12478 +f 6968/6244/12873 6967/6975/13554 6969/7533/14311 +f 5787/6990/14553 5786/6464/13896 5785/5893/13896 +f 7351/7697/14554 7331/7698/14555 7321/7699/14556 +f 6286/6602/13181 6276/6503/13100 6391/6357/12974 +f 6545/7532/14309 6571/6149/13278 6572/6713/13280 +f 7518/7217/13837 7517/6071/12717 7519/7314/13961 +f 7113/7656/14510 7031/7658/14512 7030/7700/14557 +f 7033/7701/14558 7113/7656/14510 7034/7702/14559 +f 6999/7703/14560 7361/7704/14561 7345/7705/14562 +f 7547/6430/13047 7634/6432/13049 7636/7209/13826 +f 7832/6890/12518 7829/6892/12518 7849/7518/12518 +f 7484/7232/13858 7468/7234/13860 7474/7427/14563 +f 7685/6785/12562 7713/6041/12562 7716/6040/12562 +f 7434/6811/14334 7458/7407/14334 7460/6671/14388 +f 5783/5894/12561 5782/7575/14564 5761/6113/12757 +f 6354/6632/13214 6355/5902/12565 6332/5901/12564 +f 6418/7418/14237 6433/6970/14401 6431/7241/14238 +f 6452/6731/13298 6481/6559/13149 6482/6916/13506 +f 5743/5788/14288 5742/6781/14287 5740/6340/14288 +f 7751/6121/12766 7739/6053/13821 7752/7206/13820 +f 7438/7317/13964 7440/6677/13250 7439/6679/13252 +f 6963/6415/13031 6975/5832/12506 6965/5831/12505 +f 6278/6279/12904 6372/7526/14298 6371/6358/12976 +f 6336/7461/14565 6351/6089/12733 6335/6091/12735 +f 6590/7231/14566 6589/6620/14567 6631/7573/14386 +f 6540/7281/13916 6559/6748/13915 6557/7706/14568 +f 7890/7551/14346 7797/7013/13598 7889/6424/13040 +f 7610/6079/14084 7600/6212/14419 7611/6816/14569 +f 6356/7072/13666 6355/5902/14010 6374/6359/12977 +f 7677/6836/13412 7684/6921/14245 7686/6837/13413 +f 7304/7610/14454 7190/7707/14570 7289/7708/14571 +f 7149/7709/14572 7071/7710/14573 6998/7711/14574 +f 7080/7712/14575 7138/7713/14576 7073/7714/14577 +f 6458/6951/14445 6471/7176/13781 6457/6177/14578 +f 5769/5816/14579 5768/7275/14580 5767/6628/13209 +f 7519/7314/13961 7520/6227/12857 7518/7217/13837 +f 7190/7707/14570 7304/7610/14454 7290/7715/14581 +f 8010/7478/14228 8012/7452/14183 8011/7460/14199 +f 6442/6199/13103 6440/6176/14477 6439/7146/14477 +f 5858/6999/12985 5857/7472/12985 5856/6338/12985 +f 7937/6148/12945 7936/6322/12640 7938/6761/14582 +f 6883/7591/14425 6885/7008/13592 6888/7369/14048 +f 6909/5769/14583 6906/7283/14584 6907/6797/13369 +f 6959/6946/13535 6969/7533/14311 6966/6947/13536 +f 6593/7102/13698 6607/7464/14209 6636/5851/12520 +f 6350/6955/13541 6349/6957/13543 6360/6633/13215 +f 6799/5824/12498 6800/6010/12498 6817/5822/12498 +f 7997/7325/13978 7996/6567/13154 7984/6460/13069 +f 7801/6349/12966 7873/6006/12661 7874/5784/12463 +f 7306/7654/14508 7315/7643/14496 7179/7652/14506 +f 6320/6382/13001 6317/7189/14091 6294/6383/13002 +f 7223/7716/14585 7206/7690/14545 7224/7717/14586 +f 7867/7525/14587 7850/5849/14588 7868/7338/14589 +f 6708/6787/12472 6706/7255/12472 6676/7045/12472 +f 6957/6977/13558 6967/6975/13554 6956/6910/13498 +f 7703/5897/12562 7724/6395/12562 7717/5895/12562 +f 6550/7448/14177 6551/7718/14590 6552/7447/14176 +f 7587/7157/13803 7562/5748/12434 7585/5750/12436 +f 7047/7719/14591 7056/7616/14460 7029/7615/14459 +f 6601/6827/14001 6600/6127/13477 6615/6506/13106 +f 6815/7188/14359 6840/7389/14592 6841/5888/12555 +f 7647/7539/14320 7649/6077/12723 7546/6230/12860 +f 6280/6680/13253 6282/7402/14102 6383/6142/12787 +f 6357/5858/12527 6328/6397/13525 6331/5903/12566 +f 7383/7720/14593 7385/7721/14594 7384/7722/14595 +f 6545/7532/14309 6544/7547/14596 6546/7109/14310 +f 7526/7489/14247 7524/6941/13530 7523/6940/13529 +f 7602/7253/12847 7571/6820/12847 7598/6660/12847 +f 6747/7723/14597 6648/6291/12983 6728/6492/13092 +f 7743/5809/14368 7725/7266/14428 7744/5808/14427 +f 7444/7405/14598 7446/6441/14599 7431/7578/14394 +f 6803/5944/14259 6804/5943/14259 6802/7499/14260 +f 7564/6543/13895 7556/6426/13042 7555/7264/13895 +f 7349/7724/14600 7351/7697/14554 7352/7725/14601 +f 6555/5745/13945 6558/5757/13315 6556/7172/13945 +f 7604/7515/12847 7576/7344/12847 7601/7376/12847 +f 7147/7726/14602 7138/7713/14576 7139/7727/14603 +f 7841/6675/13249 7810/6674/13248 7812/7259/14280 +f 7323/7728/14604 7159/7729/14605 7160/7730/14606 +f 7596/6555/14607 7606/5837/14484 7593/7292/14032 +f 7556/6426/12847 7563/6888/12847 7555/7264/12847 +f 7987/7584/14414 7971/7277/14213 7972/5845/12516 +f 6901/7332/13990 6904/6799/13371 6903/6828/13402 +f 6540/7281/13916 6555/5745/12431 6539/5747/12433 +f 7766/6328/12950 7666/6696/13264 7763/6861/13438 +f 7503/7151/13746 7534/6402/13018 7488/7140/13841 +f 7325/7731/14608 7329/7732/14609 7330/7733/14610 +f 7139/7727/14603 6998/7711/14574 7070/7734/14611 +f 6657/7347/14014 6654/7398/12916 6652/5899/14166 +f 7823/5848/14612 7824/5920/14612 7822/7287/14612 +f 7941/6760/13490 7939/5864/14115 7938/6761/14582 +f 6572/6713/14613 6570/6712/14614 6535/7538/14335 +f 7689/6920/13864 7690/7236/13863 7692/6044/14173 +f 7963/6706/13056 7936/6322/13056 7934/5983/13056 +f 7813/5978/13601 7803/6987/13570 7811/6789/14499 +f 7087/7735/14615 7094/7693/14548 7097/7692/14547 +f 6394/7557/12905 6395/7581/12905 6399/7695/12905 +f 7826/5919/12580 7825/5921/12581 7827/6995/12580 +f 7029/7615/14459 7028/7736/14616 7027/7737/14617 +f 7695/7235/14364 7694/7519/14618 7696/7111/14364 +f 7311/7668/14520 7316/7696/14551 7310/7738/14619 +f 6534/6030/12681 6608/7571/14381 6596/5947/12604 +f 6375/5857/12526 6376/5856/12525 6378/7645/14498 +f 5781/6577/13164 5780/6996/13582 5782/7575/14389 +f 5815/6571/13158 5851/6570/13157 5852/7393/14090 +f 6722/7516/14279 6723/7095/13690 6704/5793/13689 +f 7788/7507/13597 7789/6968/13411 7787/6967/13411 +f 7839/5761/12443 7810/6674/13248 7840/6673/13247 +f 6750/7114/14161 6649/6293/14161 6650/6927/14161 +f 7910/6306/12927 7906/6439/13054 7909/6305/13054 +f 5787/6990/13553 5762/5892/12559 5763/6974/13553 +f 7333/7613/14457 7341/7739/14620 7336/7647/14501 +f 7486/6872/13450 7485/7487/14621 7475/6560/14622 +f 6565/6184/12821 6562/6745/14623 6541/6185/12822 +f 7406/7740/14624 7401/7660/14514 7396/7659/14513 +f 8017/7099/13054 8014/7279/13054 8016/7100/13054 +f 5748/6367/14056 5855/7003/14056 5741/7002/14625 +f 6374/6359/12977 6371/6358/12976 6372/7526/14298 +f 7842/7268/13899 7861/6540/13134 7849/7518/14332 +f 6290/7430/14148 6302/6865/14626 6300/6864/14149 +f 7698/6965/14063 7699/7271/13902 7697/7564/14365 +f 7454/6629/13210 7453/6561/14627 7455/6514/13114 +f 7292/7741/14628 7294/7742/14629 7291/7743/14630 +f 5792/6928/12493 5766/6626/12493 5796/7136/12493 +f 7943/6903/13488 7942/7744/13488 7940/5862/13489 +f 5774/6154/13806 5759/6552/13805 5760/6112/12756 +f 7500/5843/12514 7507/6400/13016 7501/6271/12896 +f 6771/6109/12753 6772/6286/12909 6782/6285/12908 +f 7131/7745/14631 7089/7746/14632 7088/7747/14633 +f 7845/6007/13831 7857/7069/13663 7856/7212/13832 +f 5749/5791/12470 5750/7505/14268 5744/6961/12985 +f 5770/7465/14634 5772/7512/14494 5769/5816/14579 +f 7574/7440/12847 7603/7297/12847 7601/7376/12847 +f 6341/6499/13098 6340/5928/12586 6384/6140/12785 +f 6881/7536/14635 6878/7748/14635 6880/6721/14636 +f 7792/7014/13599 7873/6006/12661 7801/6349/12966 +f 7639/7569/14379 7637/6813/13384 7621/6661/14042 +f 7422/7124/13717 7418/6582/12862 7419/7273/13907 +f 7615/7375/14057 7630/6363/12981 7626/6478/13081 +f 6480/6016/12667 6479/7580/14404 6495/6017/12668 +f 7901/6568/13155 7900/7265/13054 7902/7310/13054 +f 7362/7749/14637 7067/7750/14638 7358/7684/14538 +f 6749/5898/12563 6644/7414/12563 6652/5899/12563 +f 7599/6531/12847 7583/6214/12847 7580/5764/12847 +f 6655/5804/12481 6657/7347/14014 6731/5802/12479 +f 5794/6775/13344 5802/7308/13952 5815/6571/13943 +f 7343/7751/14639 7333/7613/14457 7348/7655/14509 +f 6724/6728/13295 6723/7095/14640 6732/6649/13225 +f 6759/7229/14240 6875/7238/14240 6876/7237/14241 +f 6810/6297/12917 6818/5823/13970 6831/6298/12918 +f 6490/6097/12741 6491/6049/12696 6484/6051/12698 +f 6561/5758/12441 6563/7468/12441 6581/6832/12441 +f 7842/7268/12518 7829/6892/12518 7827/6995/12518 +f 6582/5838/12441 6549/5840/12441 6552/7447/12441 +f 6695/6346/12963 6717/7078/13673 6718/5859/12528 +f 7376/7752/14641 7377/7664/14518 7385/7721/14594 +f 7329/7732/14609 7327/7753/14642 7328/7754/14643 +f 6631/7573/14386 6632/7406/14114 6591/7011/13595 +f 7596/6555/12847 7589/6554/12847 7595/7388/12847 +f 5755/5792/12471 5752/6884/13463 5816/6724/13290 +f 7682/6536/13130 7681/6971/13550 7700/7270/14307 +f 7613/6765/13334 7604/7515/14326 7614/7387/14081 +f 6754/7303/13941 6861/7454/14188 6860/7304/13942 +f 6943/7473/14272 6909/5769/12440 6942/5949/12440 +f 6606/6454/13818 6623/7205/13819 6625/7059/13652 +f 7822/7287/13925 7806/7566/14373 7805/7285/13923 +f 6890/6323/12946 6885/7008/12946 6997/6324/12946 +f 7795/5986/12642 7788/7507/13597 7796/5987/12643 +f 7681/6971/13550 7697/7564/14644 7699/7271/14308 +f 6888/7369/14048 6972/6376/12995 6883/7591/14425 +f 7402/7755/14645 7410/7756/14646 7407/7757/14647 +f 7931/7549/14648 7930/6235/13143 7932/6471/13142 +f 7412/6233/12862 7417/6232/12861 7414/6719/12862 +f 6717/7078/13673 6747/7723/14597 6728/6492/13092 +f 6952/7758/14649 6940/6751/13321 6941/7509/14650 +f 7607/7049/13641 7645/7048/13640 7643/7142/13736 +f 6714/5812/13911 6702/7340/14651 6697/6976/13556 +f 6455/6220/14652 6456/6723/13289 6480/6016/14653 +f 6766/7420/14134 6851/7498/14258 6850/5796/12473 +f 7983/7145/13740 7995/6692/13261 7994/7570/14380 +f 6604/7337/14344 6619/6125/12770 6620/7550/14345 +f 7940/5862/12531 7920/6446/14654 7919/5863/12532 +f 7679/6209/14318 7677/6836/12692 7678/6919/12562 +f 7914/7501/14655 7948/7759/14656 7950/5882/14657 +f 7346/7760/14658 6999/7703/14560 7345/7705/14562 +f 7130/7761/14659 7128/7762/14660 7064/7763/14661 +f 8000/6277/12902 7999/5963/12619 7998/6459/13068 +f 6926/6479/14662 6927/6986/13569 6900/7284/13921 +f 6550/7448/14663 6548/7108/13704 6537/7346/14012 +f 6513/7159/13758 6510/7178/13783 6512/7180/13786 +f 7642/5835/12509 7641/6036/12687 7605/5836/12510 +f 7354/7764/14664 7355/7765/14665 7357/7686/14540 +f 7004/7766/14666 7022/7767/14667 7005/7768/14668 +f 6447/6335/14207 6446/6581/14669 6448/6580/13827 +f 6907/6797/12440 6904/6799/12440 6938/5995/12440 +f 7720/6354/12971 7731/6353/12970 7715/6042/14123 +f 6419/7293/14402 6420/7087/13682 6437/7147/13742 +f 7136/7769/14670 7084/7620/14465 7133/7770/14671 +f 7078/7771/14672 7077/7772/14673 7138/7713/14576 +f 7759/7386/14079 7745/6548/13140 7761/7385/14078 +f 7084/7620/14465 7131/7745/14631 7133/7770/14671 +f 6401/6482/12583 6402/5927/12585 6407/6241/12870 +f 7976/6532/13126 7989/7457/14193 7988/6569/13156 +f 7291/7743/14630 7367/7773/14674 7292/7741/14628 +f 7729/6475/13078 7768/6474/13077 7749/7190/13794 +f 7384/7722/14595 7339/7774/14675 7340/7775/14676 +f 7719/7360/12562 7705/5896/12562 7717/5895/12562 +f 7412/6233/13928 7411/7274/13928 7535/6584/13928 +f 7367/7773/14674 7366/7776/14677 7292/7741/14628 +f 7051/7600/14439 7052/7777/14678 7008/7778/14679 +f 6707/5861/12530 6695/6346/12963 6718/5859/12528 +f 5770/7465/14210 5757/7481/14680 5758/6553/14211 +f 7107/7779/14681 7106/7780/14682 7015/7781/14683 +f 6723/7095/14640 6722/7516/14684 6732/6649/13225 +f 6819/6739/13305 6839/7097/13694 6815/7188/14359 +f 6408/6676/12583 6407/6241/12870 6413/6211/12846 +f 7298/7782/14685 7297/7783/14686 7390/7784/14687 +f 7651/6815/13386 7612/6530/13124 7654/7482/14233 +f 7673/6334/13679 7786/7084/13679 7785/7665/13679 +f 7474/7427/14563 7485/7487/14621 7484/7232/13858 +f 7495/6021/13951 7511/7025/13613 7494/6019/14220 +f 7983/7145/13740 7953/6517/13739 7984/6460/13069 +f 6954/6137/12782 6990/6330/12952 6953/6135/12780 +f 7252/7641/14493 7213/7640/14492 7270/7785/14688 +f 7427/6461/13070 7436/7316/14385 7428/7345/14111 +f 6922/6497/13273 6925/6480/13083 6923/7413/14121 +f 7653/7483/14234 7654/7482/14233 7553/7559/14358 +f 6533/6159/12801 6534/6030/12681 6532/6032/12683 +f 7061/7592/14430 7125/7594/14432 7023/7786/14689 +f 7719/7360/14035 7734/6485/13087 7733/7576/14390 +f 6839/7097/14690 6850/5796/12473 6851/7498/14258 +f 7770/7423/14136 7769/7422/14135 7771/7412/14120 +f 6993/6732/13591 6996/6325/13591 6997/6324/13592 +f 7393/7787/14691 7406/7740/14624 7396/7659/14513 +f 7883/7426/14139 7884/7356/14030 7789/6968/14080 +f 6949/6659/13233 6981/5814/12491 6948/5813/12490 +f 7792/7014/13599 7891/6541/13135 7892/7306/13949 +f 6767/6345/14692 6876/7237/14692 6877/7352/14692 +f 7677/6836/12692 7683/7372/12562 7676/7488/12692 +f 7473/6179/13734 7487/6873/13451 7472/6562/13667 +f 7949/6518/13056 7947/7459/13056 7952/6519/13056 +f 7307/7788/14693 7376/7752/14641 7385/7721/14594 +f 7462/6462/13243 7461/6643/13245 7463/5874/13984 +f 7243/7789/14694 7249/7790/14695 7230/7791/14696 +f 6401/6482/12583 6400/5925/12583 6402/5927/12585 +f 7857/7069/13663 7886/7104/13700 7856/7212/13832 +f 6407/6241/12870 6402/5927/12585 6496/6015/12666 +f 6762/7357/14395 6865/7425/14138 6864/7455/14189 +f 6803/5944/13883 6776/6848/13481 6777/6847/13883 +f 7475/6560/14622 7485/7487/14621 7474/7427/14563 +f 5744/6961/14697 5857/7472/14697 5858/6999/14697 +f 7847/6834/12518 7816/6788/12518 7814/6790/14698 +f 7330/7733/14610 7351/7697/14554 7321/7699/14556 +f 7246/7792/14699 7214/7681/14535 7247/7793/14700 +f 6399/7695/12905 6398/6641/12905 6394/7557/12905 +f 7112/7794/14701 7111/7795/14702 7053/7796/14703 +f 7952/6519/14312 7965/6278/12903 7953/6517/13739 +f 7861/6540/13134 7842/7268/13899 7862/7269/13900 +f 7376/7752/14641 7173/7797/14704 7174/7798/14705 +f 6941/7509/12440 6920/7282/14272 6917/6157/12440 +f 7009/7799/14706 7005/7768/14668 7010/7800/14707 +f 7984/6460/13069 7995/6692/13261 7983/7145/13740 +f 7821/6282/14708 7819/7434/14154 7818/5979/12634 +f 6508/6204/12837 6468/6206/12839 6507/6897/13478 +f 7020/7801/14709 7017/7623/14468 7021/7631/14476 +f 7468/7234/12542 7457/6515/12542 7474/7427/12542 +f 7247/7793/14700 7214/7681/14535 7250/7802/14710 +f 6567/6714/12441 6569/6151/12441 6573/6150/12441 +f 7881/5955/12611 7880/7112/13707 7879/6710/13276 +f 6434/6100/12708 6459/6061/12708 6432/5935/12708 +f 6900/7284/13921 6899/7451/14181 6924/7450/14180 +f 7722/7267/12562 7687/7542/12692 7721/7444/12562 +f 6855/7484/14235 6857/5767/12449 6856/7204/13813 +f 7996/6567/13154 7910/6306/12927 7993/6039/12691 +f 7938/6761/14582 7939/5864/14115 7937/6148/12945 +f 6617/6124/12769 6616/6508/13108 6618/6747/13314 +f 7471/6020/12542 7440/6677/12542 7470/6598/12542 +f 7838/5762/14711 7809/6304/12925 7837/5760/14421 +f 5783/5894/13898 5784/6466/13897 5782/7575/14389 +f 6706/7255/13887 6722/7516/14279 6704/5793/13689 +f 7946/7587/14712 7921/6444/14713 7944/7586/14713 +f 7157/7803/14714 7328/7754/14643 7327/7753/14642 +f 6934/7052/13645 6945/7250/13876 6964/7053/13646 +f 5757/7481/12493 5764/6299/12493 5760/6112/12756 +f 6410/6275/12900 6404/6688/12583 6403/5924/12583 +f 7415/6403/13019 7534/6402/13018 7504/7245/13870 +f 7687/7542/14323 7688/6838/13862 7686/6837/13511 +f 6892/5756/13568 6929/6613/13567 6931/6718/14715 +f 6273/6682/12905 6275/6681/12905 6274/6281/12905 +f 6364/7218/13839 6363/6504/13101 6285/6830/13406 +f 7056/7616/14460 7046/7804/14716 7055/7805/14717 +f 7048/7806/14718 7049/7807/14719 7099/7808/14720 +f 7341/7739/14620 7338/7809/14721 7340/7775/14676 +f 6760/7358/12657 6872/7239/12657 6874/7294/12657 +f 6588/7133/14266 6573/6150/13198 6587/7134/13889 +f 7691/6207/12840 7679/6209/12842 7689/6920/13510 +f 7876/5786/12465 7799/6350/12967 7874/5784/12463 +f 6805/5942/12636 6803/5944/13883 6777/6847/13883 +f 7181/7810/14722 7183/7811/14723 7182/7812/14724 +f 7307/7788/14693 7385/7721/14594 7382/7813/14725 +f 6293/6736/13302 6292/6429/13046 6295/6384/13014 +f 7344/7814/14726 7345/7705/14562 7363/7626/14471 +f 6932/6901/13486 6944/5770/13559 6955/7116/13710 +f 7749/7190/13794 7767/6329/12951 7766/6328/12950 +f 6509/7213/13833 6410/6275/12900 6511/7543/14324 +f 6945/7250/14140 6979/6779/13350 6977/7296/13931 +f 6918/7166/14127 6920/7282/13917 6919/6707/13272 +f 5796/7136/12493 5795/6929/12493 5792/6928/12493 +f 7765/7191/13795 7762/6547/13139 7764/7144/13738 +f 6887/7024/13612 6884/6434/13591 6881/7536/14635 +f 6991/6331/12953 6989/6634/13217 6990/6330/12952 +f 7361/7704/14561 7068/7815/14727 7362/7749/14637 +f 7052/7777/14678 7053/7796/14703 7008/7778/14679 +f 7061/7592/14430 7063/7816/14728 7126/7593/14431 +f 7617/5941/12599 7603/7297/13933 7602/7253/13884 +f 7008/7778/14679 7012/7817/14729 7011/7818/14730 +f 7256/7819/14731 7262/7820/14732 7260/7821/14733 +f 6759/7229/13929 6760/7358/13929 6874/7294/13929 +f 7956/5868/13056 7924/5883/13056 7953/6517/13056 +f 7058/7822/14734 7352/7725/14601 7060/7823/14735 +f 6830/7321/13972 6845/6672/13246 6844/5989/12645 +f 6811/6666/12498 6814/6417/12498 6806/6585/12498 +f 7552/7824/14736 7629/7513/14277 7554/6693/13262 +f 6669/6840/13956 6670/6839/14737 6671/6296/13955 +f 5814/6572/13953 5802/7308/13952 5801/6465/14289 +f 7054/7825/14738 7375/7599/14438 7369/7687/14541 +f 7068/7815/14727 7361/7704/14561 6999/7703/14560 +f 7381/7826/14739 7338/7809/14721 7298/7782/14685 +f 5824/6631/13212 5832/6372/12991 5833/5743/12429 +f 6636/5851/12520 6633/5850/12519 6635/6251/12876 +f 7989/7457/14193 8013/7458/14194 8012/7452/14183 +f 6610/5959/12615 6608/7571/14381 6611/6894/13474 +f 7945/7827/13056 7943/6903/13056 7954/6410/13056 +f 6942/5949/12440 6907/6797/12440 6938/5995/12440 +f 6380/5930/12588 6375/5857/12526 6378/7645/14498 +f 6324/6001/13622 6297/7171/14101 6325/6636/14059 +f 6694/6758/13328 6667/7335/13998 6668/6295/13329 +f 7949/6518/13434 7950/5882/12549 7948/7759/14740 +f 7674/5871/12540 7668/6695/13263 7673/6334/12956 +f 7596/6555/14607 7608/6619/13197 7607/7049/13641 +f 7199/7828/14741 7219/7688/14542 7198/7829/14742 +f 7603/7297/12847 7573/6821/12847 7602/7253/12847 +f 7944/7586/14713 7920/6446/14654 7942/7744/14743 +f 7347/7673/14527 7350/7830/14744 7349/7724/14600 +f 6770/6510/13110 6809/6509/13109 6807/5982/12638 +f 7200/7831/14745 7219/7688/14542 7199/7828/14741 +f 6484/6051/12698 6476/7118/13713 6475/7117/13712 +f 6999/7703/14560 7346/7760/14658 7069/7832/14746 +f 6410/6275/12900 6509/7213/13833 6508/6204/12837 +f 7222/7833/14747 7197/7834/14748 7221/7835/14749 +f 6948/5813/12490 6936/7193/14109 6949/6659/13233 +f 5844/5972/12628 5811/6740/13306 5843/5787/12466 +f 7111/7795/14702 7110/7836/14750 7053/7796/14703 +f 7220/7680/14534 7208/7837/14751 7209/7838/14752 +f 7870/5801/13408 7847/6834/13410 7843/6249/14196 +f 7018/7839/14753 7017/7623/14468 7019/7840/14754 +f 7783/7242/12956 7782/7491/12954 7781/7243/12956 +f 7944/7586/14755 7942/7744/14755 7943/6903/14755 +f 7274/7841/14756 7277/7842/14757 7276/7843/14758 +f 7397/7844/14759 7398/7845/14760 7401/7660/14514 +f 7950/5882/14657 7923/5884/14146 7914/7501/14655 +f 7399/7619/14464 7394/7846/14761 7398/7845/14760 +f 6705/5794/12472 6701/6730/12472 6671/6296/12472 +f 7378/7847/14762 7168/7848/14763 7377/7664/14518 +f 7212/7849/14764 7282/7850/14765 7281/7851/14766 +f 7484/7232/14242 7530/6168/12810 7527/7490/14248 +f 6476/7118/13713 6460/6831/13407 6462/6062/13711 +f 7198/7829/14742 7219/7688/14542 7211/7852/14767 +f 7762/6547/13139 7746/6546/13138 7747/7143/13737 +f 7201/7853/14768 7219/7688/14542 7200/7831/14745 +f 7477/7463/12542 7445/6442/12542 7476/7261/12542 +f 7979/7313/14226 7959/6470/14769 7980/6189/12825 +f 7977/5781/14192 7990/7312/13958 7912/7167/14448 +f 7360/7627/14472 7362/7749/14637 7359/7854/14770 +f 6409/7395/14093 6403/5924/12583 6412/7366/14043 +f 7823/5848/14612 7825/5921/14612 7824/5920/14612 +f 6329/7568/13014 6319/6494/13014 6321/6493/13014 +f 7362/7749/14637 7068/7815/14727 7067/7750/14638 +f 7777/6107/12751 7776/6106/12750 7734/6485/13087 +f 6703/6347/12472 6695/6346/12472 6682/7168/12472 +f 6869/6413/13029 6758/6344/12961 6871/6877/13454 +f 7989/7457/14193 7985/6025/12676 7988/6569/13156 +f 6361/6290/12913 6362/6289/12912 6363/6504/13101 +f 7962/5782/12461 7959/6470/14769 7979/7313/14226 +f 6423/7210/13828 6425/6908/13495 6424/6218/13829 +f 7349/7724/14600 7056/7616/14460 7347/7673/14527 +f 7420/6234/12863 7511/7025/13613 7512/5887/12554 +f 7292/7741/14628 7295/7855/14771 7294/7742/14629 +f 7292/7741/14628 7296/7856/14772 7295/7855/14771 +f 6452/6731/12708 6450/6917/12708 6424/6218/12708 +f 7493/5841/12512 7500/5843/12514 7492/7359/14034 +f 6275/6681/13994 6379/6522/13118 6377/7429/14144 +f 7724/6395/12562 7701/6876/12562 7723/6393/12562 +f 7305/7609/14453 7319/7857/14773 7318/7607/14450 +f 7973/5844/12515 8010/7478/14228 7986/7534/14313 +f 6998/7711/14574 7150/7858/14774 7149/7709/14572 +f 6923/7413/14121 6925/6480/13083 6924/7450/14775 +f 6934/7052/12440 6930/6612/12440 6933/6782/12440 +f 7046/7804/14716 7039/7649/14503 7055/7805/14717 +f 7474/7427/12542 7457/6515/12542 7455/6514/12542 +f 5750/7505/14268 5749/5791/12470 5849/7480/14231 +f 7633/6146/12791 7619/6145/12790 7635/6912/13501 +f 6290/7430/13014 6289/7170/13014 6295/6384/13014 +f 6604/7337/14000 6605/7383/14069 6578/6453/13062 +f 7738/6778/13347 7739/6053/13821 7675/6333/12955 +f 5755/5792/12985 5744/6961/12985 5753/6998/12985 +f 6886/6255/12880 6882/6640/13591 6887/7024/13612 +f 7015/7781/14683 7106/7780/14682 7016/7859/14776 +f 7016/7859/14776 7105/7860/14777 7018/7839/14753 +f 6583/6128/12558 6582/5838/12441 6552/7447/12441 +f 7667/7276/12956 7664/6980/13562 7670/6108/12752 +f 6787/6002/12657 6788/6004/12659 6786/6477/13080 +f 7647/7539/14320 7546/6230/12860 7645/7048/13640 +f 7380/7861/14778 7391/7862/14779 7382/7813/14725 +f 7248/7863/14780 7241/7864/14781 7240/7865/14782 +f 7113/7656/14510 7112/7794/14701 7053/7796/14703 +f 7359/7854/14770 7328/7754/14643 7326/7866/14783 +f 6514/6085/13085 6400/5925/13085 6401/6482/13085 +f 6308/6182/12818 6309/7558/12818 6307/6183/12819 +f 6815/7188/12498 6812/5890/12498 6780/7186/12498 +f 6337/6956/13542 6326/6268/12893 6348/6288/12911 +f 7220/7680/14534 7209/7838/14752 7219/7688/14542 +f 7312/7608/14451 7400/7617/14462 7398/7845/14760 +f 7273/7867/14784 7272/7868/14785 7267/7604/14443 +f 7645/7048/13640 7646/6618/13196 7647/7539/14320 +f 6506/6899/13480 6406/5926/12584 6405/6274/12899 +f 6279/6600/14452 6394/7557/14452 6396/7585/14452 +f 7041/7869/14786 7039/7649/14503 7044/7870/14787 +f 7665/6332/14788 7785/7665/14788 7784/7666/14788 +f 6299/6398/13877 6298/7374/14789 6300/6864/13442 +f 7204/7871/14790 7219/7688/14542 7205/7872/14791 +f 7008/7778/14679 7108/7873/14792 7107/7779/14681 +f 6653/6102/12746 6647/6101/12916 6650/6927/12916 +f 7042/7874/14793 7002/7674/14528 7043/7632/14480 +f 7459/7408/14354 7460/6671/13244 7458/7407/14354 +f 6510/7178/13783 6511/7543/14324 6512/7180/13786 +f 6549/5840/14068 6548/7108/14067 6550/7448/14177 +f 7275/7875/14794 7274/7841/14756 7276/7843/14758 +f 6658/6238/12472 6665/6486/12472 6662/6488/13088 +f 6882/6640/13591 6889/6243/13591 6890/6323/13591 +f 7617/5941/12599 7602/7253/13884 7618/6147/12792 +f 5794/6775/12493 5806/5968/12493 5777/5952/12493 +f 6589/6620/14567 6588/7133/13728 6630/7371/14051 +f 7852/5847/14411 7850/5849/14588 7867/7525/14587 +f 6583/6128/12773 6585/6646/14489 6598/5960/14129 +f 7096/7876/14795 7094/7693/14548 7098/7877/14796 +f 6619/6125/12770 6604/7337/14344 6603/7336/14267 +f 7812/7259/12518 7847/6834/12518 7814/6790/14698 +f 6483/6050/12697 6493/6591/13174 6492/7131/13726 +f 6497/7018/13606 6499/6192/12828 6498/7019/13607 +f 7388/7628/14473 7297/7783/14686 7293/7878/14797 +f 6883/7591/14425 6972/6376/12995 6973/6684/13254 +f 7648/6617/13195 7647/7539/14320 7646/6618/13196 +f 7342/7672/14526 7343/7751/14639 7347/7673/14527 +f 6557/7706/14568 6555/5745/12431 6540/7281/13916 +f 7139/7727/14603 7072/7879/14798 7148/7880/14799 +f 5844/5972/12628 5812/5971/12627 5811/6740/13306 +f 7123/7694/14549 7092/7881/14800 7049/7807/14719 +f 6916/6158/14801 6914/6368/13751 6915/7154/13750 +f 7927/6701/13268 7925/6700/13267 7924/5883/12550 +f 5790/6930/14125 5791/6301/14802 5792/6928/14076 +f 7695/7235/13861 7680/6208/12841 7693/7199/14070 +f 7695/7235/14364 7693/7199/14618 7694/7519/14618 +f 6452/6731/12708 6424/6218/12708 6455/6220/12708 +f 7572/6984/14803 7574/7440/14163 7575/6985/14008 +f 6754/7303/12962 6756/7302/13940 6755/6753/12962 +f 7404/7882/14804 7406/7740/14624 7405/7883/14805 +f 7134/7884/14806 7131/7745/14631 7132/7885/14807 +f 6856/7204/13813 6858/5766/12448 6823/7203/13812 +f 7137/7886/14808 7134/7884/14806 7135/7887/14809 +f 7064/7763/14661 7001/7888/14810 7066/7889/14811 +f 7029/7615/14459 7117/7890/14812 7116/7891/14813 +f 7108/7873/14792 7008/7778/14679 7109/7892/14814 +f 7353/7893/14815 7061/7592/14430 7060/7823/14735 +f 7463/5874/13984 7437/7390/14087 7464/6463/13985 +f 7383/7720/14593 7340/7775/14676 7338/7809/14721 +f 7120/7894/14816 7017/7623/14468 7121/7895/14817 +f 7960/7577/14393 7980/6189/12825 7959/6470/14769 +f 7059/7896/14818 7120/7894/14816 7056/7616/14460 +f 6952/7758/14819 6985/7456/14191 6951/6752/14190 +f 7604/7515/14326 7601/7376/14058 7614/7387/14081 +f 7171/7897/14820 7172/7898/14821 7306/7654/14508 +f 6696/6726/12472 6698/7400/14202 6692/7103/12472 +f 6939/6136/12440 6941/7509/12440 6917/6157/12440 +f 7063/7816/14728 7062/7899/14822 7127/7900/14823 +f 6442/6199/13103 6439/7146/14477 6441/6181/14824 +f 6989/6634/13217 6985/7456/14191 6952/7758/14819 +f 7909/6305/12926 7990/7312/13958 7991/6188/12824 +f 7047/7719/14591 7029/7615/14459 7027/7737/14617 +f 6566/7670/12441 6567/6714/12441 6576/6621/12441 +f 6964/7053/13932 6975/5832/12506 6963/6415/13031 +f 7562/5748/12847 7563/6888/12847 7561/5749/12847 +f 7236/7589/14423 7237/7588/14422 7238/7901/14825 +f 7337/7902/14826 7165/7646/14500 7167/7903/14827 +f 7428/7345/14111 7436/7316/14385 7438/7317/14112 +f 7017/7623/14468 7120/7894/14816 7059/7896/14818 +f 7327/7753/14642 7325/7731/14608 7157/7803/14714 +f 7441/6678/13251 7440/6677/13250 7443/6960/14025 +f 7335/7904/14828 7336/7647/14501 7339/7774/14675 +f 5839/6321/12944 5826/7531/14418 5837/5958/12614 +f 6501/6450/13060 6464/7905/14829 6500/7361/14036 +f 7820/7286/14361 7819/7434/14154 7821/6282/14708 +f 6833/6351/12968 6832/6133/12778 6843/6132/12777 +f 7469/6028/12542 7459/7408/12542 7468/7234/12542 +f 7419/7273/13907 7524/6941/13530 7422/7124/13717 +f 7005/7768/14668 7007/7906/14830 7006/7907/14831 +f 5756/6300/12921 5793/7384/14832 5791/6301/12922 +f 7491/6982/13563 7490/6270/12895 7478/6772/14131 +f 7252/7641/14493 7270/7785/14688 7253/7908/14833 +f 6805/5942/12600 6808/6667/14184 6806/6585/12600 +f 5833/5743/12429 5836/5742/12428 5827/5957/12613 +f 6343/6924/14204 6329/7568/14374 6342/7382/14065 +f 7151/7909/14834 7346/7760/14658 7152/7910/14835 +f 6766/7420/14134 6756/7302/13940 6854/7401/14100 +f 6286/6602/13181 6391/6357/12974 6390/6318/12941 +f 7333/7613/14457 7337/7902/14826 7158/7611/14455 +f 7082/7911/14836 7084/7620/14465 7083/7912/14837 +f 7951/6705/13771 7975/6024/12675 7974/6026/14838 +f 7184/7913/14839 7305/7609/14453 7188/7914/14840 +f 7702/6534/13128 7682/6536/13130 7700/7270/14307 +f 7643/7142/13736 7645/7048/13640 7644/6037/12688 +f 7239/7915/14841 7269/7916/14842 7248/7863/14780 +f 7264/7917/14843 7259/7918/14844 7271/7919/14845 +f 6609/5945/12602 6598/5960/12616 6597/5946/12603 +f 7893/7012/14846 7788/7507/14846 7787/6967/14846 +f 7651/6815/13386 7653/7483/14234 7652/7535/14314 +f 7897/7582/14847 7896/7216/14847 7793/6954/14847 +f 7415/6403/13019 7416/6565/12862 7422/7124/13717 +f 7554/6693/13262 7548/6313/12567 7551/7560/12567 +f 6345/6092/12736 6346/6267/12892 6334/6093/12737 +f 6386/6755/13325 6342/7382/14065 6385/6139/12784 +f 7271/7919/14845 7257/7920/14848 7272/7868/14785 +f 5833/5743/12429 5834/6939/13528 5835/5744/12430 +f 7889/6424/13040 7791/6966/14151 7887/7431/14150 +f 6524/7504/14265 6522/7106/13702 6520/6502/12683 +f 7683/7372/12562 7681/6971/13550 7682/6536/12562 +f 7392/7618/14463 7296/7856/14772 7366/7776/14677 +f 5854/7001/13586 5740/6340/13586 5741/7002/13586 +f 6630/7371/14051 6631/7573/14386 6589/6620/14567 +f 7292/7741/14628 7366/7776/14677 7296/7856/14772 +f 6891/6245/12874 6969/7533/14311 6888/7369/14048 +f 7491/6982/13563 7478/6772/14131 7477/7463/14352 +f 7197/7834/14748 7219/7688/14542 7204/7871/14790 +f 6448/6580/13166 6414/6579/13165 6423/7210/14252 +f 7710/7421/13922 7713/6041/13358 7712/7520/14849 +f 7768/6474/13077 7771/7412/14120 7769/7422/14135 +f 6745/5811/12488 6653/6102/12746 6656/6292/12915 +f 7364/7921/14850 7197/7834/14748 7222/7833/14747 +f 6419/7293/12708 6418/7418/12708 6415/7123/12708 +f 6283/6064/12710 6278/6279/12904 6371/6358/12976 +f 5841/5780/12459 5840/6320/12943 5842/6526/13120 +f 6326/6268/13014 6309/7558/13014 6311/6608/13014 +f 7353/7893/14815 7060/7823/14735 7352/7725/14601 +f 7255/7922/14851 7253/7908/14833 7263/7923/14852 +f 7798/6835/14406 7796/5987/14406 7898/7377/14406 +f 7388/7628/14473 7390/7784/14687 7297/7783/14686 +f 6501/6450/13060 6465/7399/14098 6464/7905/14829 +f 7302/7924/14853 7319/7857/14773 7183/7811/14854 +f 6679/6907/13494 6677/7128/14855 6662/6488/13088 +f 6568/6878/14856 6542/6186/12821 6543/7476/14857 +f 7966/6276/12901 8001/5961/12617 8000/6277/12902 +f 7655/5905/13382 7545/6231/13382 7657/5906/13382 +f 7274/7841/14756 7273/7867/14784 7267/7604/14443 +f 7770/7423/14136 7773/7077/13672 7663/6327/12949 +f 7110/7836/14750 7109/7892/14814 7008/7778/14679 +f 7228/7925/14858 7208/7837/14751 7229/7926/14859 +f 6878/7748/14635 6879/6733/13592 6880/6721/14636 +f 7363/7626/14471 7155/7597/14436 7344/7814/14726 +f 6614/6507/13107 6613/6160/12802 6533/6159/12801 +f 6349/6957/13543 6348/6288/12911 6361/6290/12913 +f 7614/7387/14081 7626/6478/13081 7627/6362/12980 +f 6316/6768/14049 6317/7189/13793 6318/6806/14860 +f 6698/7400/14099 6696/6726/13904 6710/7005/13906 +f 7217/7927/14861 7218/7928/14862 7049/7807/14719 +f 7216/7929/14863 7215/7930/14864 7370/7637/14486 +f 7218/7928/14862 7370/7637/14486 7049/7807/14719 +f 7025/7624/14469 7023/7786/14689 7026/7931/14865 +f 7446/6441/14599 7448/6922/14219 7431/7578/14394 +f 7219/7688/14542 7367/7773/14674 7368/7932/14866 +f 6910/5977/14867 6908/7354/14867 6909/5769/14868 +f 7964/6533/13127 7976/6532/13126 7963/6706/13770 +f 7008/7778/14679 7013/7933/14869 7012/7817/14729 +f 7131/7745/14631 7084/7620/14465 7089/7746/14632 +f 7365/7934/14870 7394/7846/14761 7399/7619/14464 +f 7213/7640/14492 7285/7935/14871 7284/7936/14872 +f 7407/7757/14873 7410/7756/14874 7409/7937/14875 +f 6781/6110/14075 6782/6285/14205 6783/7187/14206 +f 7466/5875/12542 7463/5874/12542 7461/6643/12542 +f 7836/6008/12518 7845/6007/12518 7839/5761/12518 +f 6676/7045/13722 6677/7128/13722 6678/6592/13722 +f 6526/7107/13703 6622/7195/13799 6618/6747/13314 +f 7956/5868/12537 7981/5867/12536 7961/7555/14392 +f 6719/5860/12529 6718/5859/12528 6727/6491/13091 +f 7239/7915/14841 7268/7938/14876 7269/7916/14842 +f 6811/6666/14372 6812/5890/12557 6823/7203/13812 +f 7352/7725/14601 7351/7697/14554 7353/7893/14815 +f 7641/6036/12687 7640/6038/12689 7639/7569/14379 +f 7017/7623/14468 7059/7896/14818 7058/7822/14734 +f 6422/7122/14296 6414/6579/13165 6446/6581/13167 +f 7324/7939/14877 7158/7611/14455 7161/7940/14878 +f 7542/5992/12567 7543/6812/13383 7541/5993/12567 +f 7378/7847/14762 7376/7752/14641 7170/7941/14879 +f 7376/7752/14641 7174/7798/14705 7170/7941/14879 +f 7402/7755/14645 7222/7833/14747 7221/7835/14749 +f 6385/6139/12784 6382/6138/12783 6383/6142/12787 +f 7257/7920/14848 7271/7919/14845 7258/7942/14880 +f 7878/7348/14018 7877/6716/13282 7879/6710/13276 +f 7583/6214/13966 7581/7530/14383 7580/5764/12446 +f 7306/7654/14508 7172/7898/14821 7173/7797/14704 +f 6657/7347/14014 6720/6272/12897 6730/6273/12898 +f 7261/7943/14881 7263/7923/14852 7262/7820/14732 +f 6415/7123/14251 6425/6908/14882 6423/7210/14252 +f 7019/7840/14754 7017/7623/14468 7020/7801/14709 +f 7349/7724/14600 7350/7830/14744 7351/7697/14554 +f 7930/6235/12864 7917/7477/14883 7916/6236/12865 +f 6866/7424/14137 6864/7455/14189 6865/7425/14138 +f 7406/7740/14624 7402/7755/14645 7407/7757/14647 +f 6893/5754/14017 6901/7332/14016 6903/6828/14884 +f 7257/7920/14848 7265/7944/14885 7267/7604/14443 +f 6984/6664/13238 6987/6256/12881 6887/7024/13612 +f 6469/6205/12838 6508/6204/12837 6509/7213/13833 +f 7013/7933/14869 7107/7779/14681 7014/7945/14886 +f 6553/5746/14887 6554/6647/14887 6552/7447/14887 +f 6507/6897/13478 6506/6899/13480 6508/6204/12837 +f 7100/7946/14888 7049/7807/14719 7101/7947/14889 +f 7676/7488/14246 7684/6921/14245 7677/6836/13412 +f 6725/6729/14890 6696/6726/13904 6700/6294/14891 +f 6898/5755/13768 6897/5975/12630 6914/6368/12986 +f 6828/7201/13809 6827/6418/14170 6866/7424/14137 +f 6500/7361/14036 6498/7019/13607 6499/6192/12828 +f 7272/7868/14785 7257/7920/14848 7267/7604/14443 +f 7348/7655/14509 7350/7830/14744 7347/7673/14527 +f 7061/7592/14430 7353/7893/14815 7354/7764/14664 +f 8015/7311/14523 8019/6644/14523 7906/6439/14523 +f 6842/5889/12556 6853/6166/12808 6854/7401/14100 +f 6542/6186/12441 6541/6185/12441 6539/5747/12433 +f 7595/7388/12847 7586/6213/12847 7600/6212/12847 +f 6634/5852/12521 6607/7464/14209 6592/7010/13594 +f 5790/6930/14125 5789/6973/14125 5791/6301/14802 +f 7933/5985/14339 7935/5984/12794 7918/6445/14340 +f 7181/7810/14892 7302/7924/14853 7183/7811/14854 +f 7303/7948/14893 7404/7882/14804 7403/7949/14894 +f 7965/6278/12903 7952/6519/14312 7966/6276/12901 +f 7912/7167/14448 7976/6532/13126 7977/5781/14192 +f 6888/7369/14048 6969/7533/14311 6959/6946/13535 +f 6348/6288/12911 6349/6957/13543 6337/6956/13542 +f 7395/7661/14515 7394/7846/14761 7396/7659/14895 +f 7235/7590/14424 7236/7589/14423 7234/7679/14533 +f 7056/7616/14460 7055/7805/14717 7057/7671/14525 +f 7393/7787/14691 7394/7846/14761 7364/7921/14850 +f 7371/7638/14487 7370/7637/14486 7212/7849/14764 +f 7399/7619/14464 7392/7618/14463 7366/7776/14677 +f 7353/7893/14815 7355/7765/14665 7354/7764/14664 +f 7110/7836/14750 7008/7778/14679 7053/7796/14703 +f 7395/7661/14515 7398/7845/14760 7394/7846/14761 +f 6472/7158/13757 6471/7176/13781 6513/7159/13758 +f 7871/7416/14130 7863/5911/12572 7872/6005/12660 +f 7632/6431/13048 7625/5939/12597 7624/7446/14174 +f 6578/6453/12441 6574/6455/12441 6545/7532/12441 +f 7397/7844/14896 7312/7608/14896 7398/7845/14896 +f 6928/6481/13084 6929/6613/13191 6927/6986/14897 +f 7219/7688/14542 7197/7834/14748 7364/7921/14850 +f 7229/7926/14859 7208/7837/14751 7220/7680/14534 +f 6326/6268/13014 6311/6608/13014 6313/6607/13014 +f 6361/6290/12913 6364/7218/13839 6365/6794/13366 +f 7290/7715/14581 7303/7948/14893 7408/7950/14898 +f 7303/7948/14893 7403/7949/14894 7408/7950/14898 +f 7550/7035/13625 7649/6077/12723 7650/6923/13515 +f 7379/7951/14899 7339/7774/14675 7384/7722/14595 +f 7206/7690/14545 7207/7952/14900 7228/7925/14858 +f 7133/7770/14671 7131/7745/14631 7134/7884/14806 +f 7255/7922/14851 7263/7923/14852 7261/7943/14881 +f 6547/5891/12558 6578/6453/12441 6545/7532/12441 +f 7723/6393/12562 7696/7111/12562 7727/6054/12562 +f 7044/7870/14787 7039/7649/14503 7045/7953/14901 +f 7600/6212/14902 7599/6531/13125 7612/6530/13124 +f 7271/7919/14845 7259/7918/14844 7258/7942/14880 +f 7195/7954/14903 7221/7835/14749 7196/7955/14904 +f 7822/7287/13925 7824/5920/14905 7806/7566/14373 +f 8018/7280/13054 8014/7279/13054 8017/7099/13054 +f 7405/7883/14906 7409/7937/14906 7408/7950/14906 +f 7458/7407/14334 7433/6810/13579 7456/6516/13578 +f 7290/7715/14907 7408/7950/14907 7409/7937/14907 +f 7354/7764/14664 7062/7899/14822 7063/7816/14728 +f 7573/6821/13393 7574/7440/14163 7572/6984/14803 +f 7628/6361/12979 7630/6363/12981 7629/7513/14277 +f 7410/7756/14908 7221/7835/14749 7195/7954/14903 +f 7410/7756/14909 7402/7755/14909 7221/7835/14909 +f 7014/7945/14886 7107/7779/14681 7015/7781/14683 +f 5740/6340/14288 5746/6339/12985 5743/5788/14288 +f 7570/6819/14479 7557/6428/13044 7569/6427/13043 +f 6921/6708/14355 6898/5755/13768 6919/6707/13767 +f 7951/6705/13056 7938/6761/13056 7936/6322/13056 +f 7063/7816/14728 7127/7900/14823 7126/7593/14431 +f 7933/5985/12641 7932/6471/14910 7934/5983/12639 +f 7536/7290/13114 7421/6525/13114 7412/6233/13114 +f 7852/5847/14411 7867/7525/14587 7866/7605/14444 +f 7458/7407/14116 7456/6516/13115 7457/6515/13115 +f 7745/6548/14429 7722/7267/14911 7746/6546/14912 +f 7904/6683/14347 8018/7280/14348 8017/7099/14347 +f 7802/6829/13405 7838/5762/14711 7840/6673/13403 +f 7600/6212/12847 7583/6214/12847 7599/6531/12847 +f 7910/6306/12927 7902/7310/13054 7906/6439/13054 +f 7933/5985/12641 7931/7549/14910 7932/6471/14910 +f 5744/6961/14697 5858/6999/14697 5753/6998/14697 +f 6621/7196/13800 6619/6125/12770 6618/6747/13314 +f 7361/7704/14561 7360/7627/14472 7363/7626/14471 +f 7382/7813/14725 7383/7720/14593 7381/7826/14739 +f 6618/6747/13314 6528/6746/13313 6526/7107/13703 +f 7135/7887/14809 7068/7815/14727 7000/7956/14913 +f 6702/7340/14651 6715/7119/14914 6703/6347/12964 +f 7303/7948/14893 7304/7610/14454 7314/7957/14915 +f 5754/6366/12985 5752/6884/12985 5753/6998/12985 +f 6897/5975/12630 6910/5977/12632 6912/6369/12987 +f 7205/7872/14791 7219/7688/14542 7203/7958/14916 +f 6859/5768/12450 6857/5767/12449 6860/7304/13942 +f 6558/5757/13315 6557/7706/14917 6559/6748/13316 +f 7934/5983/12639 7936/6322/12640 7935/5984/12640 +f 7220/7680/14534 7233/7959/14918 7229/7926/14859 +f 6536/7110/13706 6546/7109/13705 6544/7547/14336 +f 7608/6619/13197 7646/6618/13196 7607/7049/13641 +f 7125/7594/14432 7005/7768/14668 7023/7786/14689 +f 6467/7017/14919 6453/6201/13991 6454/6337/14920 +f 6421/6068/12714 6422/7122/14296 6444/6069/12715 +f 5806/5968/12493 5805/6226/12494 5775/7326/13027 +f 6411/5923/14330 6519/6084/14330 6408/6676/14330 +f 7758/5777/12456 7759/7386/14079 7760/5775/12454 +f 7346/7760/14658 7153/7960/14921 7152/7910/14835 +f 7066/7889/14811 7001/7888/14810 7067/7750/14638 +f 7951/6705/13771 7974/6026/14838 7973/5844/12515 +f 6369/7404/14108 6359/5879/12546 6367/5881/12548 +f 7331/7698/14555 7350/7830/14744 7332/7961/14922 +f 6304/6317/12937 6303/7445/14398 6305/6118/12938 +f 6555/5745/13945 6557/7706/14917 6558/5757/13315 +f 7924/5883/12550 7925/6700/13267 7923/5884/12551 +f 7725/7266/14428 7722/7267/14911 7745/6548/14429 +f 7180/7642/14495 7302/7924/14853 7185/7962/14923 +f 7298/7782/14685 7299/7963/14924 7297/7783/14686 +f 7912/7167/14448 7990/7312/13958 7909/6305/12926 +f 5835/5744/12430 5745/6938/13527 5838/6370/12988 +f 5825/5956/14925 5826/7531/14305 5796/7136/14304 +f 7332/7961/14922 7324/7939/14877 7331/7698/14555 +f 7748/7635/14483 7764/7144/13738 7747/7143/13737 +f 6475/7117/13712 6474/6143/12788 6490/6097/12741 +f 6640/7415/12683 6639/6436/12683 6637/6501/12683 +f 7806/7566/14373 7802/6829/12518 7804/6989/12518 +f 6361/6290/12913 6365/6794/13366 6349/6957/13543 +f 7810/6674/12518 7843/6249/12518 7812/7259/12518 +f 7893/7012/14846 7894/7378/14926 7788/7507/14846 +f 5809/6528/13122 5808/5778/12457 5842/6526/13120 +f 7023/7786/14689 7025/7624/14469 7017/7623/14468 +f 7622/7184/13791 7639/7569/14379 7621/6661/14042 +f 6688/6266/14376 6664/6487/14038 6665/6486/13852 +f 5807/5779/14306 5808/5778/13879 5795/6929/13878 +f 7068/7815/14727 7066/7889/14811 7067/7750/14638 +f 7880/7112/13707 7795/5986/12642 7878/7348/14018 +f 6686/7362/13695 6685/7041/13631 6684/7040/13630 +f 6708/6787/14167 6719/5860/12529 6720/6272/13885 +f 7629/7513/14277 7552/7824/14736 7628/6361/12979 +f 7250/7802/14710 7214/7681/14535 7249/7790/14695 +f 6482/6916/13506 6464/7905/14927 6450/6917/13507 +f 6296/6000/12655 6289/7170/13775 6324/6001/12656 +f 7957/5994/13056 7941/6760/13056 7958/5846/13056 +f 6756/7302/13940 6766/7420/14134 6757/6013/12962 +f 5803/6411/12493 5804/5817/12493 5772/7512/12493 +f 7523/6940/13529 7522/6228/12858 7521/7368/14046 +f 6802/7499/14260 6800/6010/12662 6801/6900/14261 +f 7815/5980/12635 7818/5979/12634 7817/6988/14155 +f 7002/7674/14528 7042/7874/14793 7036/7675/14529 +f 7386/7630/14475 7392/7618/14463 7400/7617/14462 +f 7377/7664/14518 7379/7951/14899 7385/7721/14594 +f 6327/6637/14300 6338/6936/13524 6339/5929/14928 +f 7831/7223/13844 7830/6891/13470 7832/6890/13469 +f 6981/5814/12491 6983/6663/13237 6881/7536/14316 +f 7952/6519/14312 7967/6656/13230 7966/6276/12901 +f 6451/6336/13851 6450/6917/13507 6464/7905/14927 +f 7650/6923/13515 7652/7535/14314 7550/7035/13625 +f 5788/7300/12493 5790/6930/12493 5799/7341/12493 +f 6535/7538/14335 6570/6712/14614 6543/7476/14857 +f 6310/6606/13185 6309/7558/14929 6308/6182/14929 +f 7356/7685/14539 7062/7899/14822 7354/7764/14664 +f 6774/7061/12498 6773/6210/14930 6772/6286/12498 +f 7358/7684/14538 7001/7888/14810 7356/7685/14539 +f 7007/7906/14830 7008/7778/14679 7011/7818/14730 +f 7371/7638/14487 7277/7842/14757 7372/7636/14485 +f 6689/6265/12472 6690/6264/12472 6699/6564/12472 +f 7477/7463/14352 7476/7261/13892 7492/7359/14353 +f 7910/6306/12927 7992/6187/12823 7993/6039/12691 +f 7383/7720/14593 7338/7809/14721 7381/7826/14739 +f 6329/7568/13014 6333/6767/13014 6318/6806/13014 +f 5814/6572/13159 5813/7522/14931 5847/5973/12629 +f 7310/7738/14619 7316/7696/14551 7315/7643/14496 +f 7710/7421/14932 7683/7372/14053 7708/7138/14933 +f 7385/7721/14594 7379/7951/14899 7384/7722/14595 +f 6810/6297/12498 6821/7333/12498 6793/6842/12498 +f 7853/5912/12518 7825/5921/12518 7823/5848/12518 +f 7291/7743/14630 7002/7674/14528 7054/7825/14738 +f 8006/6944/13533 8005/7298/13935 8008/7075/13670 +f 7566/6247/14934 7564/6543/14935 7565/7291/14936 +f 6755/6753/12962 6760/7358/12962 6762/7357/12962 +f 6375/5857/12526 6338/6936/13524 6357/5858/12527 +f 6962/6414/13030 6970/6377/12996 6961/5950/14937 +f 7306/7654/14508 7376/7752/14641 7307/7788/14693 +f 7203/7958/14916 7219/7688/14542 7202/7964/14938 +f 6818/5823/12498 6810/6297/12498 6796/6844/12498 +f 6984/6664/13238 6982/6658/13232 6985/7456/14191 +f 7722/7267/12562 7690/7236/12562 7687/7542/12692 +f 6574/6455/12441 6573/6150/12441 6571/6149/12441 +f 5797/6741/13307 5812/5971/14939 5801/6465/14289 +f 7544/7034/14940 7657/5906/14940 7545/6231/14940 +f 7922/7500/14941 7948/7759/14656 7914/7501/14655 +f 6933/6782/12440 6928/6481/12440 6937/6783/12440 +f 5842/6526/13120 5840/6320/12943 5743/5788/12467 +f 7062/7899/14822 7356/7685/14539 7065/7965/14942 +f 6905/6798/13370 6907/6797/13369 6906/7283/14584 +f 7946/7587/14416 7947/7459/14416 7949/6518/13434 +f 6660/7453/12472 6659/6841/12472 6658/6238/12472 +f 7424/6523/14943 7540/7496/14943 7539/6566/14943 +f 7811/6789/13361 7816/6788/13360 7813/5978/12633 +f 7888/7068/13662 7887/7431/14150 7886/7104/13700 +f 6284/6642/13094 6399/7695/13094 6281/6280/13094 +f 7802/6829/13405 7811/6789/14499 7803/6987/13570 +f 7544/7034/14940 7658/5904/14940 7657/5906/14940 +f 6991/6331/12953 6988/6257/12882 6986/7328/13986 +f 6729/5803/12480 6730/6273/12898 6728/6492/13092 +f 5845/5789/12468 5844/5972/12628 5843/5787/12466 +f 6482/6916/14037 6481/6559/13149 6498/7019/13607 +f 6486/7160/13759 6513/7159/13758 6487/7181/13787 +f 7129/7966/14944 7128/7762/14660 7130/7761/14659 +f 7544/7034/12567 7549/7036/13626 7553/7559/14358 +f 6741/5752/12438 6743/7214/13835 6712/6563/13151 +f 6783/7187/14206 6780/7186/14073 6781/6110/14075 +f 7905/6550/14945 8014/7279/14945 7900/7265/14945 +f 7546/6230/12860 7649/6077/12723 7550/7035/13625 +f 7426/6524/13119 7505/6978/13560 7506/6269/12894 +f 5751/6365/12990 5747/6937/13526 5832/6372/12991 +f 7696/7111/12562 7694/7519/12562 7727/6054/12562 +f 7597/6246/14946 7621/6661/13235 7598/6660/13234 +f 7836/6008/13293 7837/5760/12442 7835/6303/13291 +f 6341/6499/13098 6329/7568/14374 6330/7437/14947 +f 7607/7049/13641 7643/7142/13736 7606/5837/12511 +f 6978/6720/13286 6977/7296/13931 6979/6779/13350 +f 6679/6907/13926 6678/6592/14948 6677/7128/14948 +f 6570/6712/14614 6568/6878/14856 6543/7476/14857 +f 7695/7235/14364 7696/7111/14364 7698/6965/14063 +f 7350/7830/14744 7331/7698/14555 7351/7697/14554 +f 6378/7645/14498 6377/7429/14144 6379/6522/13118 +f 7541/5993/12567 7543/6812/13383 7546/6230/12860 +f 6880/6721/14636 6879/6733/13592 6883/7591/14425 +f 6445/6200/12708 6447/6335/12708 6454/6337/12708 +f 6822/6889/12498 6820/6737/12498 6788/6004/12498 +f 7564/6543/14935 7566/6247/14934 7567/7365/14949 +f 6752/7523/14950 6654/7398/14950 6649/6293/14950 +f 7079/7967/14951 7138/7713/14576 7080/7712/14575 +f 7284/7936/14872 7283/7968/14952 7213/7640/14492 +f 7957/5994/12649 7972/5845/12516 7971/7277/13912 +f 5765/6627/14953 5756/6300/12921 5757/7481/14680 +f 6941/7509/14650 6953/6135/12780 6952/7758/14649 +f 7157/7803/14714 7325/7731/14608 7160/7730/14606 +f 6838/5797/12474 6837/6738/14397 6849/5798/12475 +f 7732/6355/12972 7718/7486/14391 7733/7576/14390 +f 6939/6136/12440 6915/7154/12440 6932/6901/12440 +f 7905/6550/14945 8016/7100/14945 8014/7279/14945 +f 6701/6730/13297 6705/5794/13691 6724/6728/13295 +f 6367/5881/12548 6283/6064/12710 6368/7403/14107 +f 6410/6275/12900 6405/6274/12899 6404/6688/12583 +f 7551/7560/14371 7660/6452/14371 7659/6694/14371 +f 7808/6302/12923 7831/7223/14954 7833/7222/14488 +f 7968/6655/13936 8004/7969/14955 7967/6656/13910 +f 7194/7970/14956 7193/7971/14957 7409/7937/14958 +f 7051/7600/14439 7008/7778/14679 7122/7601/14440 +f 6416/7503/14264 6428/7502/14263 6426/6909/14284 +f 6622/7195/13799 6526/7107/13703 6523/7105/13701 +f 7624/7446/14174 7634/6432/13049 7632/6431/13048 +f 5754/6366/14175 5751/6365/12990 5831/7305/13948 +f 7842/7268/12518 7827/6995/12518 7825/5921/12518 +f 7621/6661/14042 7597/6246/14959 7622/7184/13791 +f 6599/6126/14103 6598/5960/12616 6611/6894/13474 +f 7237/7588/14422 7374/7598/14437 7239/7915/14841 +f 6937/6783/12440 6928/6481/12440 6925/6480/12440 +f 7287/7972/14960 7189/7973/14961 7288/7974/14962 +f 7465/7141/13735 7489/7150/13745 7488/7140/13733 +f 6506/6899/13480 6504/7442/14168 6406/5926/12584 +f 6868/5991/12647 6869/6413/13029 6870/6134/12779 +f 7801/6349/12966 7798/6835/13411 7793/6954/13597 +f 6935/6496/14015 6940/6751/13321 6950/6750/13320 +f 6725/6729/13296 6736/6055/12702 6737/6558/13148 +f 7390/7784/14687 7389/7669/14521 7391/7862/14779 +f 7799/6350/12967 7876/5786/12465 7800/5988/12644 +f 7968/6655/13936 8005/7298/13935 8004/7969/14955 +f 6785/6476/12498 6788/6004/12498 6819/6739/12498 +f 7370/7637/14486 7050/7602/14441 7049/7807/14719 +f 7158/7611/14455 7324/7939/14877 7332/7961/14922 +f 7592/6529/12847 7578/5763/12847 7604/7515/12847 +f 7578/5763/12445 7579/5765/12447 7577/6824/14007 +f 6431/7241/14238 6429/5934/14262 6417/7419/14239 +f 7277/7842/14757 7278/7975/14963 7276/7843/14758 +f 7521/7368/14046 7519/7314/13961 7516/6073/12719 +f 5802/7308/12493 5794/6775/12493 5781/6577/12493 +f 7673/6334/12956 7675/6333/12955 7674/5871/12540 +f 7870/5801/12478 7879/6710/13276 7869/6715/13281 +f 6346/6267/12892 6347/7057/14964 6326/6268/12893 +f 7566/6247/12847 7565/7291/12847 7594/6248/12847 +f 7286/7976/14965 7305/7609/14453 7189/7973/14961 +f 7707/7139/12562 7705/5896/12562 7719/7360/12562 +f 6695/6346/12472 6707/5861/12472 6680/6593/12472 +f 7606/5837/14484 7596/6555/14607 7607/7049/13641 +f 7532/6871/13449 7487/6873/13451 7534/6402/13018 +f 6984/6664/13238 6985/7456/14191 6986/7328/13986 +f 7715/6042/12562 7713/6041/12562 7711/7278/12562 +f 6454/6337/12708 6453/6201/12708 6445/6200/12708 +f 7301/7633/14481 7294/7742/14629 7293/7878/14797 +f 7427/6461/12542 7429/6851/12542 7435/6809/12542 +f 6673/7046/13983 6672/7349/14966 6660/7453/14187 +f 7914/7501/14655 7923/5884/14146 7915/7411/14145 +f 7833/7222/13292 7832/6890/13469 7834/6725/13292 +f 6702/7340/14651 6714/5812/13911 6715/7119/14914 +f 7433/6810/13579 7432/7063/13657 7454/6629/13580 +f 6304/6317/13014 6332/5901/13014 6301/6451/13014 +f 6341/6499/13098 6342/7382/14065 6329/7568/14374 +f 7791/6966/14151 7889/6424/13040 7797/7013/13598 +f 7997/7325/13978 7984/6460/13069 7998/6459/13068 +f 6463/6992/12708 6459/6061/12708 6434/6100/12708 +f 6996/6325/13591 6994/6435/13591 6995/7567/13591 +f 7128/7762/14660 7097/7692/14547 7124/7977/14967 +f 7008/7778/14679 7005/7768/14668 7122/7601/14440 +f 6780/7186/14073 6808/6667/14184 6809/6509/14186 +f 7636/7209/13826 7637/6813/13384 7547/6430/13047 +f 7469/6028/12679 7482/7462/14968 7481/6029/12680 +f 7745/6548/13140 7762/6547/13139 7761/7385/14078 +f 7806/7566/14373 7804/6989/12518 7805/7285/14969 +f 7857/7069/14970 7845/6007/14970 7844/6009/14970 +f 6816/7200/12498 6800/6010/12498 6802/7499/12498 +f 6531/6250/12875 6524/7504/14265 6527/6437/12683 +f 7687/7542/12692 7685/6785/12562 7721/7444/12562 +f 6855/7484/14235 6842/5889/12556 6854/7401/14100 +f 7941/6760/13056 7957/5994/13056 7943/6903/13056 +f 6551/7718/14971 6539/5747/12433 6553/5746/12432 +f 7665/6332/14788 7673/6334/14788 7785/7665/14788 +f 7295/7855/14771 7387/7629/14474 7294/7742/14629 +f 6885/7008/14446 6993/6732/14446 6997/6324/14446 +f 6663/6906/13493 6683/7042/13865 6681/7367/14972 +f 6957/6977/13558 6944/5770/13559 6943/7473/14222 +f 6925/6480/13083 6926/6479/13082 6924/7450/14775 +f 7419/7273/13907 7418/6582/12862 7411/7274/12862 +f 6991/6331/12953 6954/6137/12782 6889/6243/12872 +f 7268/7938/14876 7267/7604/14443 7266/7978/14973 +f 7444/7405/14598 7431/7578/14394 7430/7067/13661 +f 7621/6661/14042 7636/7209/13826 7620/6662/13500 +f 7227/7691/14546 7206/7690/14545 7228/7925/14858 +f 5800/5818/13213 5824/6631/13212 5825/5956/12612 +f 7846/6833/12518 7818/5979/12518 7816/6788/12518 +f 6377/7429/14144 6376/5856/12525 6372/7526/14298 +f 7720/6354/12562 7711/7278/12562 7709/7137/12562 +f 6328/6397/13014 6325/6636/13014 6299/6398/13014 +f 7722/7267/14911 7721/7444/14974 7747/7143/14975 +f 7848/7517/14331 7860/6542/14333 7859/6423/13573 +f 7069/7832/14746 7000/7956/14913 6999/7703/14560 +f 7420/6234/12863 7421/6525/12862 7423/7363/12862 +f 6629/7574/14387 6630/7371/14051 6626/7094/13688 +f 7132/7885/14807 7066/7889/14811 7068/7815/14727 +f 7022/7767/14667 7026/7931/14865 7005/7768/14668 +f 7804/6989/12518 7802/6829/12518 7803/6987/12518 +f 7664/6980/13562 7667/7276/12956 7661/6981/12956 +f 7093/7979/14976 7123/7694/14549 7094/7693/14548 +f 7994/7570/14380 7993/6039/12691 7982/5869/12690 +f 5770/7465/14634 5771/6156/12799 5772/7512/14494 +f 7736/6394/14281 7750/7409/14117 7735/6749/13317 +f 7908/6549/13141 8011/7460/14199 7903/7417/14132 +f 6334/6093/12737 6333/6767/14203 6344/6094/12738 +f 7395/7661/14515 7401/7660/14514 7398/7845/14760 +f 7153/7960/14921 7344/7814/14726 7154/7980/14977 +f 7362/7749/14637 7360/7627/14472 7361/7704/14561 +f 7486/6872/13450 7532/6871/13449 7531/7342/14005 +f 6748/7260/12916 6749/5898/12916 6753/5900/12916 +f 7535/6584/12862 7540/7496/12862 7536/7290/12862 +f 7120/7894/14816 7119/7981/14978 7056/7616/14460 +f 6840/7389/14085 6839/7097/14690 6851/7498/14258 +f 6664/6487/12472 6663/6906/13493 6662/6488/13088 +f 6355/5902/12565 6356/7072/13816 6331/5903/12566 +f 7473/6179/12542 7449/6178/12542 7465/7141/12542 +f 6917/6157/14128 6918/7166/14127 6916/6158/14801 +f 6597/5946/13204 6585/6646/14489 6584/6625/13205 +f 8009/7073/13668 7987/7584/14414 7986/7534/14313 +f 6529/6650/13226 6638/6652/13226 6521/6500/13226 +f 7564/6543/13137 7591/6545/13137 7565/7291/13137 +f 7053/7796/14703 7003/7676/14530 7113/7656/14510 +f 6391/6357/12974 6345/6092/12939 6390/6318/12941 +f 7313/7667/14519 7316/7696/14551 7311/7668/14520 +f 6883/7591/14425 6976/6722/13288 6880/6721/13287 +f 7980/6189/12825 7991/6188/12824 7979/7313/13960 +f 7360/7627/14472 7326/7866/14783 7322/7595/14434 +f 6456/6723/13289 6479/7580/14979 6480/6016/14653 +f 7324/7939/14877 7161/7940/14878 7159/7729/14605 +f 7639/7569/14379 7623/7183/14375 7641/6036/12687 +f 6446/6581/14669 6445/6200/14980 6444/6069/14980 +f 6709/7272/14319 6725/6729/13296 6737/6558/13148 +f 7422/7124/13717 7529/6169/12811 7415/6403/13019 +f 7392/7618/14463 7386/7630/14475 7387/7629/14474 +f 7600/6212/14902 7612/6530/13124 7611/6816/13387 +f 6763/6412/13028 6868/5991/12647 6867/5990/12646 +f 7369/7687/14541 7219/7688/14542 7368/7932/14866 +f 7967/6656/13910 8004/7969/14955 8001/5961/12617 +f 7342/7672/14526 7333/7613/14457 7343/7751/14639 +f 6396/7585/14981 6277/6601/14981 6279/6600/14981 +f 7309/7982/14982 7315/7643/14496 7308/7983/14983 +f 7094/7693/14548 7096/7876/14795 7095/7984/14984 +f 6647/6101/12916 6645/6556/12916 6643/7115/12916 +f 6887/7024/13612 6987/6256/12881 6886/6255/12880 +f 7444/7405/14598 7430/7067/13661 7442/6850/13425 +f 7053/7796/14703 7375/7599/14438 7054/7825/14738 +f 7683/7372/14053 7706/7248/13874 7708/7138/14933 +f 7424/6523/14943 7421/6525/14943 7540/7496/14943 +f 7860/6542/13136 7891/6541/13135 7859/6423/13039 +f 7802/6829/12518 7806/7566/14373 7809/6304/12518 +f 6580/5759/12441 6556/7172/12441 6558/5757/12441 +f 5804/5817/12493 5769/5816/12493 5772/7512/12493 +f 7806/7566/14373 7826/5919/14985 7807/7583/14407 +f 7413/6229/12862 7411/7274/12862 7414/6719/12862 +f 6343/6924/13516 6342/7382/14065 6386/6755/13325 +f 6729/5803/12480 6731/5802/12479 6730/6273/12898 +f 7341/7739/14620 7340/7775/14676 7336/7647/14501 +f 5757/7481/14680 5767/6628/14986 5765/6627/14953 +f 6395/7581/14405 6281/6280/14405 6399/7695/14405 +f 7035/7985/14987 7003/7676/14530 7036/7675/14529 +f 5747/6937/13526 5834/6939/13528 5832/6372/12991 +f 5746/6339/12985 5744/6961/12985 5750/7505/14268 +f 6564/7469/14400 6563/7468/14341 6562/6745/13312 +f 6686/7362/13695 6687/7098/13695 6685/7041/13631 +f 6751/7438/12916 6750/7114/12916 6748/7260/12916 +f 6763/6412/13028 6768/7343/12962 6759/7229/12962 +f 7139/7727/14603 7138/7713/14576 7136/7769/14670 +f 7357/7686/14540 7328/7754/14643 7359/7854/14770 +f 7601/7376/12847 7576/7344/12847 7574/7440/12847 +f 7899/6945/13054 7900/7265/13054 7901/6568/13155 +f 7264/7917/14843 7260/7821/14733 7259/7918/14844 +f 6767/6345/14692 6877/7352/14692 6761/6014/14692 +f 6858/5766/12448 6856/7204/13813 6857/5767/12449 +f 7037/7634/14482 7301/7633/14481 7039/7649/14503 +f 6611/6894/13474 6613/6160/12802 6599/6126/14103 +f 6798/6011/12664 6799/5824/12663 6797/6801/13637 +f 7354/7764/14664 7357/7686/14540 7356/7685/14539 +f 7381/7826/14739 7298/7782/14685 7380/7861/14778 +f 6932/6901/12440 6911/5771/12440 6944/5770/12440 +f 7313/7667/14519 7318/7607/14450 7316/7696/14551 +f 7351/7697/14554 7330/7733/14610 7355/7765/14665 +f 7123/7694/14549 7050/7602/14441 7122/7601/14440 +f 6574/6455/12441 6571/6149/12441 6545/7532/12441 +f 6476/7118/13713 6484/6051/12698 6483/6050/12697 +f 7222/7833/14747 7393/7787/14691 7364/7921/14850 +f 6400/5925/12583 6405/6274/12899 6406/5926/12584 +f 6274/6281/14988 6394/7557/14988 6273/6682/14988 +f 7757/5870/12539 7672/7355/14433 7674/5871/12540 +f 7957/5994/12649 7970/6408/13024 7954/6410/13026 +f 6826/7202/13811 6827/6418/13034 6814/6417/13033 +f 7239/7915/14841 7374/7598/14437 7267/7604/14443 +f 7335/7904/14828 7377/7664/14518 7163/7663/14517 +f 6297/7171/14101 6298/7374/14789 6299/6398/13877 +f 7185/7962/14923 7302/7924/14853 7181/7810/14892 +f 7773/7077/13672 7770/7423/14136 7774/6895/13475 +f 7715/6042/14123 7730/6473/14122 7716/6040/14105 +f 7741/6396/13013 7726/6045/14367 7742/7320/14366 +f 7359/7854/14770 7362/7749/14637 7358/7684/14538 +f 7736/6394/14281 7780/6653/13227 7750/7409/14117 +f 7920/6446/13056 7918/6445/13056 7919/5863/14989 +f 7479/6817/13388 7467/5873/13389 7466/5875/14990 +f 7534/6402/13018 7533/6401/13017 7532/6871/13449 +f 7188/7914/14840 7305/7609/14453 7286/7976/14965 +f 7502/6979/13561 7504/7245/13870 7503/7151/13746 +f 7267/7604/14443 7268/7938/14876 7239/7915/14841 +f 7889/6424/13040 7859/6423/13039 7890/7551/14346 +f 6330/7437/13014 6329/7568/13014 6321/6493/13014 +f 7734/6485/13087 7775/6896/13476 7733/7576/14991 +f 6467/7017/14919 6468/6206/14992 6453/6201/13991 +f 7105/7860/14777 7017/7623/14468 7018/7839/14753 +f 6691/6240/13051 6693/6239/14993 6692/7103/13699 +f 7329/7732/14609 7357/7686/14540 7355/7765/14665 +f 6892/5756/12440 6898/5755/12440 6900/7284/12440 +f 7469/6028/12679 7480/6027/12678 7466/5875/14990 +f 7466/5875/14990 7480/6027/12678 7479/6817/13388 +f 7365/7934/14870 7366/7776/14677 7367/7773/14674 +f 7005/7768/14668 7026/7931/14865 7023/7786/14689 +f 7721/7444/14974 7716/6040/14105 7749/7190/14104 +f 7568/7088/14994 7569/6427/14995 7567/7365/14949 +f 7894/7378/14996 7898/7377/14996 7796/5987/14996 +f 7764/7144/13738 7748/7635/14483 7765/7191/13795 +f 7783/7242/14399 7665/6332/14399 7784/7666/14399 +f 6765/6059/12706 6849/5798/12475 6848/6060/12707 +f 6515/6483/13337 6401/6482/13337 6408/6676/13337 +f 6330/7437/14158 6327/6637/14300 6339/5929/14928 +f 6464/7905/14927 6465/7399/14098 6451/6336/13851 +f 6864/7455/14189 6866/7424/14137 6863/7428/14141 +f 6347/7057/13650 6346/6267/12975 6393/6505/13102 +f 6785/6476/13079 6784/6287/14997 6786/6477/13080 +f 6406/5926/12584 6504/7442/14168 6503/6448/13058 +f 5743/5788/12467 5843/5787/12466 5842/6526/13120 +f 7422/7124/13717 7416/6565/12862 7418/6582/12862 +f 6692/7103/13699 6693/6239/14993 6666/6759/13330 +f 6276/6503/12905 6286/6602/13181 6277/6601/12905 +f 7423/7363/14232 7509/6874/13452 7420/6234/12863 +f 7314/7957/14915 7404/7882/14804 7303/7948/14893 +f 7846/6833/14552 7869/6715/13281 7851/7986/14998 +f 6438/6175/12708 6449/6991/12708 6436/6099/12708 +f 6912/6369/13749 6913/7562/13749 6915/7154/13750 +f 5791/6301/14802 5793/7384/14077 5792/6928/14076 +f 6617/6124/12769 6618/6747/13314 6619/6125/12770 +f 6645/6556/13146 6740/5751/12437 6739/7004/13587 +f 7498/6072/12718 7515/5885/12552 7497/7350/14094 +f 7248/7863/14780 7243/7789/14694 7242/7987/14999 +f 5845/5789/12468 5846/6918/13508 5844/5972/12628 +f 7101/7947/14889 7091/7988/15000 7102/7989/15001 +f 7137/7886/14808 7000/7956/14913 7069/7832/14746 +f 7332/7961/14922 7350/7830/14744 7348/7655/14509 +f 6753/5900/12916 6752/7523/12916 6748/7260/12916 +f 6839/7097/13694 6840/7389/14592 6815/7188/14359 +f 7922/7500/13056 7918/6445/13056 7921/6444/13056 +f 7483/7233/13859 7499/7524/14294 7482/7462/14200 +f 7239/7915/14841 7240/7865/14782 7238/7901/14825 +f 6897/5975/12440 6894/5974/12440 6896/5976/12440 +f 7920/6446/14654 7940/5862/12531 7942/7744/14743 +f 7501/6271/12896 7492/7359/14034 7500/5843/12514 +f 7138/7713/14576 7077/7772/14673 7136/7769/14670 +f 7390/7784/14687 7388/7628/14473 7389/7669/14521 +f 6992/6433/13299 6879/6733/13299 6878/7748/13299 +f 6479/7580/14404 6478/6380/12999 6494/7132/13727 +f 6497/7018/13606 6402/5927/12585 6499/6192/12828 +f 6713/6385/13003 6743/7214/13835 6744/5810/12487 +f 6507/6897/13478 6467/7017/13605 6505/6898/13479 +f 7351/7697/14554 7355/7765/14665 7353/7893/14815 +f 6756/7302/13940 6855/7484/14235 6854/7401/14100 +f 7192/7990/15002 7290/7715/14581 7409/7937/14958 +f 7481/6029/13976 7523/6940/13529 7521/7368/14046 +f 6725/6729/14890 6700/6294/14891 6701/6730/15003 +f 6527/6437/13380 6520/6502/13380 6637/6501/13380 +f 6526/7107/13703 6528/6746/13313 6521/6500/12683 +f 7582/7546/14329 7561/5749/12435 7560/6823/13396 +f 7528/6167/12809 7527/7490/14248 7530/6168/12810 +f 7559/6983/13564 7558/7113/14478 7572/6984/13565 +f 7266/7978/14973 7267/7604/14443 7265/7944/14885 +f 7387/7629/14474 7295/7855/14771 7296/7856/14772 +f 7754/6122/12767 7742/7320/13968 7756/5872/12541 +f 7529/6169/12811 7422/7124/13717 7528/6167/12809 +f 5810/6527/13121 5842/6526/13120 5843/5787/12466 +f 7733/7576/14991 7775/6896/13476 7732/6355/12972 +f 7724/6395/13319 7736/6394/14281 7735/6749/13317 +f 7944/7586/14713 7921/6444/14713 7920/6446/14654 +f 7324/7939/14877 7323/7728/14604 7321/7699/14556 +f 6446/6581/14669 6447/6335/14207 6445/6200/14980 +f 6704/5793/12472 6674/5795/12472 6676/7045/12472 +f 7495/6021/12672 7471/6020/12671 7496/6599/13180 +f 7622/7184/13791 7597/6246/14959 7594/6248/13789 +f 7382/7813/14725 7309/7982/14982 7308/7983/14983 +f 7970/6408/14214 8009/7073/13668 8008/7075/13670 +f 7391/7862/14779 7309/7982/14982 7382/7813/14725 +f 5762/5892/12493 5761/6113/12757 5760/6112/12756 +f 6637/6501/12683 6638/6652/12683 6642/6651/12682 +f 6567/6714/13456 6566/7670/14522 6565/6184/13457 +f 6660/7453/14187 6672/7349/14966 6670/6839/13415 +f 6588/7133/13728 6628/7135/13730 6627/7060/13653 +f 7249/7790/14695 7243/7789/14694 7248/7863/14780 +f 6939/6136/12781 6953/6135/12780 6941/7509/14650 +f 6998/7711/14574 7139/7727/14603 7069/7832/14746 +f 7324/7939/14877 7321/7699/14556 7331/7698/14555 +f 6873/6012/13323 6872/7239/13323 6755/6753/13323 +f 6725/6729/14890 6709/7272/13905 6696/6726/13904 +f 6901/7332/14016 6892/5756/13568 6931/6718/14715 +f 7587/7157/13754 7589/6554/13756 7588/6887/15004 +f 7275/7875/14794 7273/7867/14784 7274/7841/14756 +f 7126/7593/14431 7005/7768/14668 7125/7594/14432 +f 7050/7602/14441 7372/7636/14485 7051/7600/14439 +f 7597/6246/12847 7568/7088/12847 7566/6247/12847 +f 6494/7132/13727 6493/6591/13174 6495/6017/12668 +f 6581/6832/14461 6592/7010/13594 6593/7102/13698 +f 5810/6527/13121 5811/6740/13306 5798/6742/13308 +f 7713/6041/13358 7714/6786/13357 7712/7520/14849 +f 6959/6946/14221 6942/5949/12606 6960/5948/12605 +f 6327/6637/13014 6330/7437/13014 6323/6638/13014 +f 6745/5811/12488 6744/5810/12487 6653/6102/12746 +f 7405/7883/14805 7406/7740/14624 7407/7757/14647 +f 7946/7587/14416 7949/6518/13434 7948/7759/14740 +f 7308/7983/14983 7315/7643/14496 7307/7788/14693 +f 7307/7788/14693 7382/7813/14725 7308/7983/14983 +f 7955/6654/13056 7945/7827/13056 7954/6410/13056 +f 7386/7630/14475 7400/7617/14462 7313/7667/14519 +f 6307/6183/13014 6336/7461/13014 6335/6091/13014 +f 7097/7692/14547 7123/7694/14549 7124/7977/14967 +f 5770/7465/14210 5767/6628/14986 5757/7481/14680 +f 6489/6095/12739 6485/6144/12789 6486/7160/13759 +f 7697/7564/14644 7681/6971/13550 7695/7235/13861 +f 7931/7549/14338 7918/6445/14340 7917/7477/14883 +f 7054/7825/14738 7368/7932/14866 7291/7743/14630 +f 6525/6031/12682 6530/7015/12682 6531/6250/12875 +f 7867/7525/14295 7800/5988/12644 7866/7605/15005 +f 7570/6819/13391 7573/6821/13393 7572/6984/14803 +f 6715/7119/13714 6714/5812/12489 6746/7120/13715 +f 7976/6532/13126 7988/6569/13156 7975/6024/12675 +f 6435/6098/15006 6419/7293/14402 6437/7147/13742 +f 7135/7887/14809 7000/7956/14913 7137/7886/14808 +f 7046/7804/14716 7056/7616/14460 7047/7719/14591 +f 7997/7325/13978 7998/6459/13068 7999/5963/12619 +f 7567/7365/14949 7566/6247/14934 7568/7088/14994 +f 6688/6266/12891 6687/7098/13695 6686/7362/13695 +f 7553/7559/14358 7628/6361/12979 7552/7824/14736 +f 6809/6509/14186 6779/6111/14074 6780/7186/14073 +f 7313/7667/14519 7389/7669/14521 7386/7630/14475 +f 7820/7286/14361 7821/6282/14708 7823/5848/14362 +f 7451/6180/14052 7452/7065/15007 7450/7064/15008 +f 7743/5809/12486 7757/5870/12539 7742/7320/13968 +f 6864/7455/14189 6863/7428/14141 6862/6153/12796 +f 7212/7849/14764 7281/7851/14766 7280/7991/15009 +f 7319/7857/14773 7305/7609/14453 7184/7913/14839 +f 6719/5860/12529 6727/6491/13091 6730/6273/12898 +f 6645/6556/13146 6647/6101/12745 6740/5751/12437 +f 6509/7213/13833 6511/7543/14324 6510/7178/13783 +f 7220/7680/14534 7234/7679/14533 7233/7959/14918 +f 6318/6806/14860 6317/7189/13793 6319/6494/13095 +f 7176/7992/15010 7315/7643/14496 7180/7642/14495 +f 7328/7754/14643 7357/7686/14540 7329/7732/14609 +f 7168/7848/14763 7169/7662/14516 7377/7664/14518 +f 5848/6284/12907 5849/7480/14231 5850/5790/12469 +f 7453/6561/14627 7452/7065/15007 7451/6180/14052 +f 7563/6888/13468 7590/6544/14113 7564/6543/13895 +f 7375/7599/14438 7237/7588/14422 7235/7590/14424 +f 6303/7445/14171 6302/6865/14626 6290/7430/14148 +f 7194/7970/14956 7409/7937/14958 7410/7756/14908 +f 5811/6740/13306 5812/5971/14939 5797/6741/13307 +f 7726/6045/14367 7725/7266/14428 7743/5809/14368 +f 7707/7139/12562 7718/7486/12692 7709/7137/12562 +f 6566/7670/12441 6577/7230/12558 6564/7469/12441 +f 7342/7672/14526 7299/7963/14924 7341/7739/14620 +f 7143/7993/15011 7141/7994/15012 7147/7726/14602 +f 7635/6912/13501 7634/6432/13049 7633/6146/12791 +f 6433/6970/14401 6419/7293/14402 6435/6098/15006 +f 6541/6185/12441 6540/7281/13916 6539/5747/12433 +f 7365/7934/14870 7364/7921/14850 7394/7846/14761 +f 7338/7809/14721 7299/7963/14924 7298/7782/14685 +f 7902/7310/13957 7900/7265/13957 8014/7279/13957 +f 6722/7516/14684 6657/7347/14014 6732/6649/13225 +f 6387/6754/13324 6388/7541/14322 6389/7540/14321 +f 6671/6296/13955 6670/6839/14737 6672/7349/14022 +f 6884/6434/14420 6882/6640/14420 6995/7567/14420 +f 6562/6745/14623 6560/6744/13914 6541/6185/12822 +f 6304/6317/13014 6307/6183/13014 6335/6091/13014 +f 6572/6713/14613 6535/7538/14335 6544/7547/14336 +f 7277/7842/14757 7279/7995/15013 7278/7975/14963 +f 6339/5929/14928 6340/5928/14159 6330/7437/14158 +f 7316/7696/14551 7318/7607/14450 7319/7857/14773 +f 5851/6570/13157 5814/6572/13159 5847/5973/12629 +f 7662/6697/13909 7782/7491/13909 7786/7084/13909 +f 7106/7780/14682 7105/7860/14777 7016/7859/14776 +f 6547/5891/14066 6546/7109/14310 6548/7108/14067 +f 7655/5905/12648 7656/6312/12648 7542/5992/12648 +f 7789/6968/14080 7885/7432/14152 7791/6966/14151 +f 6621/7196/13800 6606/6454/13818 6605/7383/14343 +f 7907/6551/13872 8006/6944/13533 8007/7074/13669 +f 6823/7203/13812 6824/7537/14317 6811/6666/14372 +f 7202/7964/14938 7219/7688/14542 7201/7853/14768 +f 7180/7642/14495 7320/7644/14497 7302/7924/14853 +f 6537/7346/12558 6536/7110/12558 6539/5747/12433 +f 8004/7969/14955 8006/6944/13533 8003/6943/13532 +f 7405/7883/14805 7403/7949/14894 7404/7882/14804 +f 5854/7001/12985 5855/7003/12985 5858/6999/12985 +f 6980/5815/12492 6881/7536/14316 6978/6720/13286 +f 7702/6534/13815 7705/5896/13814 7704/6535/13814 +f 7898/7377/13411 7893/7012/13411 7897/7582/13411 +f 6536/7110/12558 6543/7476/12441 6539/5747/12433 +f 5829/6915/13505 5818/5969/12625 5830/7396/14096 +f 7224/7717/14586 7206/7690/14545 7225/7996/15014 +f 7440/6677/12542 7437/7390/12542 7470/6598/12542 +f 7620/6662/13500 7636/7209/13826 7635/6912/13501 +f 7944/7586/14755 7943/6903/14755 7945/7827/14755 +f 7757/5870/12539 7758/5777/12456 7672/7355/14433 +f 7433/6810/12542 7431/7578/14394 7432/7063/13657 +f 6488/6096/12740 6487/7181/13787 6412/7366/14043 +f 6926/6479/13082 6928/6481/13084 6927/6986/14897 +f 6601/6827/13400 6602/6123/13484 6582/5838/13401 +f 7294/7742/14629 7388/7628/14473 7293/7878/14797 +f 7326/7866/14783 7157/7803/14714 7322/7595/14434 +f 5798/6742/13027 5797/6741/12493 5788/7300/12493 +f 7145/7997/15015 7143/7993/15011 7142/7998/15016 +f 7008/7778/14679 7107/7779/14681 7013/7933/14869 +f 7054/7825/14738 7003/7676/14530 7053/7796/14703 +f 6771/6109/12498 6770/6510/12498 6777/6847/12498 +f 7377/7664/14518 7376/7752/14641 7378/7847/14762 +f 5787/6990/13553 5785/5893/12560 5762/5892/12559 +f 7062/7899/14822 7064/7763/14661 7127/7900/14823 +f 6528/6746/13313 6533/6159/12801 6529/6650/14524 +f 7078/7771/14672 7138/7713/14576 7079/7967/14951 +f 6403/5924/14410 6404/6688/14410 6516/6687/14410 +f 7074/7999/15017 7138/7713/14576 7076/8000/15018 +f 7407/7757/14873 7409/7937/14875 7405/7883/15019 +f 7388/7628/14473 7294/7742/14629 7387/7629/14474 +f 7523/6940/13529 7525/7324/13977 7526/7489/14247 +f 7669/7101/12954 7665/6332/12954 7670/6108/12752 +f 6702/7340/12472 6703/6347/12472 6685/7041/12472 +f 6396/7585/14981 6397/7556/14981 6277/6601/14981 +f 6873/6012/12665 6761/6014/12665 6877/7352/12665 +f 6701/6730/12472 6700/6294/12472 6671/6296/12472 +f 7930/6235/12864 7931/7549/14338 7917/7477/14883 +f 7709/7137/12562 7718/7486/12692 7720/6354/12562 +f 7401/7660/14514 7406/7740/14624 7404/7882/14804 +f 6451/6336/12708 6447/6335/12708 6450/6917/12708 +f 5766/6626/13207 5767/6628/13209 5768/7275/14580 +f 5799/7341/14004 5809/6528/13880 5810/6527/13121 +f 7945/7827/13056 7955/6654/13056 7947/7459/13056 +f 7850/5849/12518 7821/6282/12518 7851/7986/12518 +f 6585/6646/12441 6583/6128/12558 6552/7447/12441 +f 6389/7540/14321 6390/6318/12941 6343/6924/13516 +f 7590/6544/14283 7588/6887/15004 7589/6554/13756 +f 7064/7763/14661 7065/7965/14942 7001/7888/14810 +f 7864/5910/13938 7872/6005/12660 7863/5911/12572 +f 7946/7587/14712 7922/7500/14941 7921/6444/14713 +f 7868/7338/14589 7851/7986/14998 7869/6715/13281 +f 7445/6442/14023 7444/7405/15020 7442/6850/14024 +f 7256/7819/14731 7260/7821/14733 7264/7917/14843 +f 7355/7765/14665 7330/7733/14610 7329/7732/14609 +f 7850/5849/14588 7851/7986/14998 7868/7338/14589 +f 7029/7615/14459 7116/7891/14813 7115/7677/14531 +f 7113/7656/14510 7030/7700/14557 7114/7678/14532 +f 7034/7702/14559 7113/7656/14510 7003/7676/14530 +f 6464/7905/14829 6482/6916/14037 6500/7361/14036 +f 7772/7449/14179 7768/6474/13077 7730/6473/13076 +f 7030/7700/14557 7028/7736/14616 7114/7678/14532 +f 7003/7676/14530 7054/7825/14738 7002/7674/14528 +f 7034/7702/14559 7003/7676/14530 7035/7985/14987 +f 7763/6861/13438 7762/6547/13139 7765/7191/13795 +f 6993/6732/13591 6994/6435/13591 6996/6325/13591 +f 7114/7678/14532 7028/7736/14616 7029/7615/14459 +f 7301/7633/14481 7043/7632/14480 7002/7674/14528 +f 6703/6347/12964 6715/7119/14914 6716/6348/12965 +f 7747/7143/14975 7721/7444/14974 7748/7635/15021 +f 7908/6549/13141 8009/7073/13668 8010/7478/14228 +f 6569/6151/14227 6570/6712/13279 6571/6149/13278 +f 6632/7406/14114 6531/6250/12875 6633/5850/12519 +f 7297/7783/14686 7300/8001/15022 7293/7878/14797 +f 7053/7796/14703 7373/7603/14442 7374/7598/14437 +f 7890/7551/14346 7792/7014/13599 7797/7013/13598 +f 7086/8002/15023 7136/7769/14670 7077/7772/14673 +f 7573/6821/12847 7603/7297/12847 7574/7440/12847 +f 7058/7822/14734 7023/7786/14689 7017/7623/14468 +f 6842/5889/12556 6841/5888/12555 6853/6166/12808 +f 6277/6601/13221 6397/7556/13221 6398/6641/13221 +f 7075/8003/15024 7138/7713/14576 7140/8004/15025 +f 5751/6365/12990 5821/6225/13947 5831/7305/13948 +f 7221/7835/14749 7197/7834/14748 7196/7955/14904 +f 7897/7582/14847 7793/6954/14847 7798/6835/14847 +f 6538/8005/15026 6550/7448/14663 6537/7346/14012 +f 7060/7823/14735 7023/7786/14689 7058/7822/14734 +f 6681/7367/14972 6679/6907/13494 6663/6906/13493 +f 6310/6606/13185 6311/6608/13185 6309/7558/14929 +f 7553/7559/14358 7552/7824/14736 7551/7560/12567 +f 7586/6213/13755 7587/7157/13754 7585/5750/15027 +f 6335/6091/12735 6353/6356/12973 6332/5901/12564 +f 7207/7952/14900 7208/7837/14751 7228/7925/14858 +f 7209/7838/14752 7210/8006/15028 7219/7688/14542 +f 7415/6403/13019 7504/7245/13870 7425/7244/13869 +f 7510/5842/12513 7508/6399/13015 7500/5843/12514 +f 6698/7400/14099 6711/5753/12439 6699/6564/13152 +f 7129/7966/14944 7130/7761/14659 7132/7885/14807 +f 7746/6546/14912 7722/7267/14911 7747/7143/14975 +f 5799/7341/12493 5798/6742/13027 5788/7300/12493 +f 7352/7725/14601 7058/7822/14734 7349/7724/14600 +f 6421/6068/12708 6420/7087/12708 6415/7123/12708 +f 6409/7395/14093 6410/6275/12900 6403/5924/12583 +f 6760/7358/12657 6755/6753/12657 6872/7239/12657 +f 7066/7889/14811 7132/7885/14807 7130/7761/14659 +f 7212/7849/14764 7370/7637/14486 7215/7930/14864 +f 7838/5762/12444 7839/5761/12443 7840/6673/13247 +f 7329/7732/14609 7325/7731/14608 7327/7753/14642 +f 7999/5963/12619 7901/6568/13155 7997/7325/13978 +f 7315/7643/14496 7309/7982/14982 7310/7738/14619 +f 7380/7861/14778 7382/7813/14725 7381/7826/14739 +f 6468/6206/12839 6467/7017/13605 6507/6897/13478 +f 7261/7943/14881 7262/7820/14732 7256/7819/14731 +f 7894/7378/14996 7796/5987/14996 7788/7507/14996 +f 6836/6818/15029 6835/7173/14370 6848/6060/12707 +f 7055/7805/14717 7299/7963/14924 7057/7671/14525 +f 7496/6599/14095 7515/5885/12552 7514/7307/13950 +f 6646/7240/13867 6736/6055/12702 6735/6057/12704 +f 5774/6154/13806 5760/6112/12756 5776/5953/13473 +f 6468/6206/14992 6469/6205/13992 6453/6201/13991 +f 6656/6292/12915 6648/6291/12983 6746/7120/13715 +f 7546/6230/12860 7640/6038/12689 7644/6037/12688 +f 7954/6410/13056 7943/6903/13056 7957/5994/13056 +f 7472/6562/13667 7486/6872/13450 7475/6560/14622 +f 7712/7520/14285 7676/7488/14246 7710/7421/14932 +f 7883/7426/14139 7855/7211/14031 7884/7356/14030 +f 6716/6348/12965 6717/7078/13673 6695/6346/12963 +f 6402/5927/12585 6497/7018/13606 6496/6015/12666 +f 6314/6735/13301 6312/6849/14142 6293/6736/13302 +f 6463/6992/14257 6449/6991/14276 6472/7158/13757 +f 7101/7947/14889 7049/7807/14719 7092/7881/14800 +f 6469/6205/13992 6470/7177/15030 6458/6951/13993 +f 6986/7328/13986 6985/7456/14191 6989/6634/13217 +f 7964/6533/13056 7934/5983/13056 7932/6471/13056 +f 6879/6733/13592 6885/7008/13592 6883/7591/14425 +f 6693/6239/14993 6694/6758/13328 6666/6759/13330 +f 6385/6139/12784 6383/6142/12787 6386/6755/13325 +f 7482/7462/14200 7525/7324/13977 7481/6029/13976 +f 7121/7895/14817 7017/7623/14468 7103/8007/15031 +f 6274/6281/14988 6395/7581/14988 6394/7557/14988 +f 7786/7084/12954 7783/7242/12956 7785/7665/12956 +f 7539/6566/12862 7535/6584/12862 7538/6727/12862 +f 7332/7961/14922 7348/7655/14509 7334/7612/14456 +f 6473/7497/14256 6486/7160/13759 6485/6144/12789 +f 7862/7269/13900 7892/7306/13949 7861/6540/13134 +f 6330/7437/13014 6321/6493/13014 6323/6638/13014 +f 7123/7694/14549 7049/7807/14719 7050/7602/14441 +f 5807/5779/12458 5839/6321/12944 5841/5780/12459 +f 7831/7223/14954 7807/7583/14407 7830/6891/14409 +f 6926/6479/14662 6900/7284/13921 6924/7450/14180 +f 6551/7718/14971 6538/8005/15026 6539/5747/12433 +f 6577/7230/13856 6591/7011/13595 6575/7470/14315 +f 6909/5769/14583 6908/7354/14583 6906/7283/14584 +f 6478/6380/12999 6479/7580/14979 6456/6723/13289 +f 7098/7877/14796 7094/7693/14548 7087/7735/14615 +f 7282/7850/14765 7212/7849/14764 7283/7968/14952 +f 6504/7442/14168 6505/6898/13479 6466/7016/13604 +f 6295/6384/13001 6322/5999/12654 6320/6382/13001 +f 7293/7878/14797 7300/8001/15022 7301/7633/14481 +f 7727/6054/12562 7694/7519/12562 7728/6043/12692 +f 7372/7636/14485 7050/7602/14441 7371/7638/14487 +f 7065/7965/14942 7064/7763/14661 7062/7899/14822 +f 7498/6072/12718 7470/6598/13179 7467/5873/13389 +f 7959/6470/13056 7929/6472/13056 7960/7577/13056 +f 6912/6369/13749 6911/5771/15032 6913/7562/13749 +f 5856/6338/12957 5740/6340/12957 5854/7001/12957 +f 5830/7396/14096 5831/7305/13948 5829/6915/13505 +f 7782/7491/12954 7783/7242/12956 7786/7084/12954 +f 7192/7990/15002 7190/7707/14570 7290/7715/14581 +f 6745/5811/12488 6656/6292/12915 6746/7120/13715 +f 7102/7989/15001 7091/7988/15000 7090/8008/15033 +f 7312/7608/14451 7318/7607/14450 7313/7667/14519 +f 6676/7045/12472 6678/6592/12472 6708/6787/12472 +f 7972/5845/12516 7986/7534/14313 7987/7584/14414 +f 7493/5841/14550 7476/7261/13892 7494/6019/12670 +f 7614/7387/14081 7601/7376/14058 7615/7375/14057 +f 6706/7255/13887 6708/6787/14167 6720/6272/13885 +f 7130/7761/14659 7064/7763/14661 7066/7889/14811 +f 6352/6090/13359 6359/5879/12546 6369/7404/14108 +f 7232/8009/15034 7231/8010/15035 7214/7681/14535 +f 7299/7963/14924 7055/7805/14717 7300/8001/15022 +f 7809/6304/12925 7838/5762/14711 7802/6829/13405 +f 6539/5747/12433 6538/8005/15036 6537/7346/12558 +f 7851/7986/12518 7818/5979/12518 7846/6833/12518 +f 6894/5974/13920 6906/7283/13919 6895/7353/14028 +f 7070/7734/14611 6998/7711/14574 7071/7710/14573 +f 7061/7592/14430 7354/7764/14664 7063/7816/14728 +f 6913/7562/12440 6911/5771/12440 6932/6901/12440 +f 6522/7106/13702 6629/7574/14387 6626/7094/13688 +f 6817/5822/13971 6829/7439/14162 6830/7321/13972 +f 7946/7587/14712 7948/7759/14656 7922/7500/14941 +f 6292/6429/13046 6293/6736/13302 6310/6606/14143 +f 7708/7138/13731 7711/7278/13922 7710/7421/13922 +f 6865/7425/14138 6762/7357/14395 6768/7343/14006 +f 7131/7745/14631 7129/7966/14944 7132/7885/14807 +f 7358/7684/14538 7357/7686/14540 7359/7854/14770 +f 7248/7863/14780 7240/7865/14782 7239/7915/14841 +f 6813/6416/12498 6802/7499/12498 6804/5943/12498 +f 5846/6918/13508 5847/5973/12629 5844/5972/12628 +f 6573/6150/13198 6574/6455/13064 6587/7134/13889 +f 6648/6291/12983 6729/5803/12480 6728/6492/13092 +f 6568/6878/14856 6565/6184/12821 6542/6186/12821 +f 6426/6909/14284 6425/6908/14882 6415/7123/14251 +f 7486/6872/13450 7531/7342/14005 7485/7487/14243 +f 7291/7743/14630 7294/7742/14629 7301/7633/14481 +f 6486/7160/13759 6473/7497/14256 6472/7158/13757 +f 7401/7660/14514 7312/7608/14451 7397/7844/14759 +f 7375/7599/14438 7053/7796/14703 7374/7598/14437 +f 7731/6353/12970 7771/7412/14120 7772/7449/14179 +f 7139/7727/14603 7136/7769/14670 7137/7886/14808 +f 6915/7154/12440 6939/6136/12440 6916/6158/12800 +f 6905/6798/13918 6893/5754/14017 6903/6828/14884 +f 6576/6621/12441 6577/7230/12558 6566/7670/12441 +f 7349/7724/14600 7058/7822/14734 7059/7896/14818 +f 6975/5832/12506 6976/6722/13288 6974/5830/12504 +f 6717/7078/13673 6716/6348/12965 6747/7723/14597 +f 6654/7398/14377 6752/7523/14377 6753/5900/14377 +f 7683/7372/14053 7710/7421/14932 7676/7488/14246 +f 7460/6671/14388 7462/6462/13071 7435/6809/14071 +f 7637/6813/13384 7639/7569/14379 7638/6814/13385 +f 6794/6843/13419 6795/6802/14417 6796/6844/13420 +f 6646/7240/13867 6651/7441/14165 6644/7414/12914 +f 6326/6268/12893 6347/7057/14964 6348/6288/12911 +f 5782/7575/14564 5780/6996/15037 5761/6113/12757 +f 6403/5924/12583 6411/5923/12583 6412/7366/14043 +f 7944/7586/14415 7945/7827/14415 7947/7459/14416 +f 6541/6185/12822 6560/6744/13914 6540/7281/13916 +f 7139/7727/14603 7148/7880/14799 7147/7726/14602 +f 6294/6383/13002 6315/6734/13300 6293/6736/13302 +f 6533/6159/12801 6532/6032/12683 6529/6650/14524 +f 7701/6876/13903 7702/6534/13815 7700/7270/13901 +f 6350/6955/13541 6336/7461/14565 6337/6956/13542 +f 7927/6701/13056 7956/5868/13056 7961/7555/13056 +f 6577/7230/12558 6575/7470/12558 6564/7469/12441 +f 6667/7335/14543 6694/6758/15038 6658/6238/12867 +f 7580/5764/12446 7581/7530/14383 7579/5765/12447 +f 6362/6289/12912 6347/7057/13650 6393/6505/13102 +f 7796/5987/12643 7798/6835/13411 7800/5988/12644 +f 7274/7841/14756 7267/7604/14443 7373/7603/14442 +f 6772/6286/12909 6786/6477/13336 6784/6287/12910 +f 7913/6826/13399 7989/7457/14193 7912/7167/14448 +f 5801/6465/12493 5802/7308/12493 5784/6466/12493 +f 7254/8011/15039 7253/7908/14833 7255/7922/14851 +f 7623/7183/13790 7594/6248/13789 7593/7292/14032 +f 7183/7811/14854 7319/7857/14773 7186/8012/15040 +f 7348/7655/14509 7347/7673/14527 7343/7751/14639 +f 7029/7615/14459 7118/7614/14458 7117/7890/14812 +f 6433/6970/14178 6432/5935/14178 6431/7241/14178 +f 7753/7246/13871 7751/6121/12766 7752/7206/13820 +f 7127/7900/14823 7124/7977/14967 7126/7593/14431 +f 7821/6282/12518 7818/5979/12518 7851/7986/12518 +f 7406/7740/14624 7393/7787/14691 7402/7755/14645 +f 6318/6806/13014 6319/6494/13014 6329/7568/13014 +f 7099/7808/14720 7049/7807/14719 7100/7946/14888 +f 6379/6522/13118 6275/6681/13994 6381/6141/12786 +f 7818/5979/12634 7813/5978/12633 7816/6788/13360 +f 6748/7260/15041 6643/7115/15041 6644/7414/15041 +f 7413/6229/12859 7522/6228/12858 7419/7273/13907 +f 5780/6996/15037 5778/5951/12758 5761/6113/12757 +f 6368/7403/14107 6283/6064/12710 6370/7370/14050 +f 7088/7747/14633 7097/7692/14547 7131/7745/14631 +f 6952/7758/14649 6951/6752/13322 6940/6751/13321 +f 5820/6224/13504 5819/5967/12623 5829/6915/13505 +f 7404/7882/14804 7314/7957/14915 7401/7660/14514 +f 7307/7788/14693 7315/7643/14496 7306/7654/14508 +f 7122/7601/14440 7124/7977/14967 7123/7694/14549 +f 6748/7260/15041 6644/7414/15041 6749/5898/15042 +f 6958/6948/13537 6967/6975/13554 6957/6977/13558 +f 6462/6062/12708 6460/6831/12708 6432/5935/12708 +f 7156/7596/14435 7322/7595/14434 7157/7803/14714 +f 7393/7787/14691 7222/7833/14747 7402/7755/14645 +f 7184/7913/14839 7188/7914/14840 7187/8013/15043 +f 6752/7523/14950 6649/6293/14950 6751/7438/14950 +f 7134/7884/14806 7132/7885/14807 7135/7887/14809 +f 7336/7647/14501 7165/7646/14500 7333/7613/14457 +f 7868/7338/14002 7877/6716/13282 7867/7525/14295 +f 7396/7659/14513 7394/7846/15044 7393/7787/14691 +f 8006/6944/13533 8004/7969/14955 8005/7298/13935 +f 6822/6889/13777 6821/7333/13996 6834/7225/13846 +f 7413/6229/12859 7518/7217/13837 7520/6227/12857 +f 7141/7994/15012 7138/7713/14576 7147/7726/14602 +f 5826/7531/14418 5825/5956/12612 5837/5958/12614 +f 6957/6977/13558 6943/7473/14222 6958/6948/15045 +f 6366/5880/12547 6365/6794/13366 6287/6063/12709 +f 7531/7342/14005 7529/6169/12811 7530/6168/12810 +f 6476/7118/13713 6477/6379/12998 6460/6831/13407 +f 6291/6119/13014 6290/7430/13014 6295/6384/13014 +f 7508/6399/13015 7426/6524/13119 7507/6400/13016 +f 7061/7592/14430 7023/7786/14689 7060/7823/14735 +f 7529/6169/12811 7531/7342/14005 7415/6403/13019 +f 6949/6659/13233 6936/7193/14109 6935/6496/14015 +f 7726/6045/12692 7692/6044/12562 7725/7266/12562 +f 7370/7637/14486 7218/7928/14862 7216/7929/14863 +f 7981/5867/12536 7993/6039/12691 7992/6187/12823 +f 7299/7963/14924 7338/7809/14721 7341/7739/14620 +f 7039/7649/14503 7038/7651/14505 7037/7634/14482 +f 7919/5863/12532 7937/6148/12793 7939/5864/12533 +f 6898/5755/13768 6921/6708/14355 6899/7451/14181 +f 7289/7708/14571 7190/7707/14570 7191/8014/15046 +f 7178/8015/15047 7315/7643/14496 7177/8016/15048 +f 6593/7102/13698 6530/7015/13600 6594/6521/13117 +f 5812/5971/14939 5813/7522/14290 5801/6465/14289 +f 6796/6844/12498 6799/5824/12498 6818/5823/12498 +f 7593/7292/12847 7591/6545/12847 7596/6555/12847 +f 7153/7960/14921 7345/7705/14562 7344/7814/14726 +f 7998/6459/13068 7965/6278/12903 8000/6277/12902 +f 7488/7140/13841 7534/6402/13018 7487/6873/13451 +f 8014/7279/13054 8019/6644/13054 8015/7311/13054 +f 7127/7900/14823 7064/7763/14661 7128/7762/14660 +f 6908/7354/14029 6896/5976/12631 6895/7353/14028 +f 7631/6343/12960 7625/5939/12597 7632/6431/13048 +f 7748/7635/15021 7721/7444/14974 7749/7190/14104 +f 7897/7582/13411 7893/7012/13411 7896/7216/13411 +f 7081/7621/14466 7136/7769/14670 7086/8002/15023 +f 6553/5746/14887 6552/7447/14887 6551/7718/14887 +f 7083/7912/14837 7084/7620/14465 7085/7622/14467 +f 5778/5951/12608 5779/6578/12608 5777/5952/12609 +f 7584/7319/13967 7586/6213/13755 7585/5750/15027 +f 7094/7693/14548 7095/7984/14984 7093/7979/14976 +f 7053/7796/14703 7052/7777/14678 7373/7603/14442 +f 7213/7640/14492 7214/7681/14535 7270/7785/14688 +f 7561/5749/12847 7563/6888/12847 7560/6823/13396 +f 7461/6643/12542 7459/7408/12542 7469/6028/12542 +f 5765/6627/14953 5793/7384/14832 5756/6300/12921 +f 5813/7522/14931 5812/5971/12627 5847/5973/12629 +f 7915/7411/13056 7918/6445/13056 7922/7500/13056 +f 5846/6918/13508 5750/7505/14268 5849/7480/14231 +f 7824/5920/14905 7826/5919/14985 7806/7566/14373 +f 7392/7618/14463 7387/7629/14474 7296/7856/14772 +f 7001/7888/14810 7358/7684/14538 7067/7750/14638 +f 7405/7883/15049 7408/7950/15049 7403/7949/15049 +f 7155/7597/14436 7363/7626/14471 7322/7595/14434 +f 7435/6809/12542 7429/6851/12542 7433/6810/12542 +f 6736/6055/12702 6725/6729/13296 6734/6056/12703 +f 7136/7769/14670 7134/7884/14806 7137/7886/14808 +f 7300/8001/15022 7297/7783/14686 7299/7963/14924 +f 7347/7673/14527 7056/7616/14460 7057/7671/14525 +f 7131/7745/14631 7097/7692/14547 7129/7966/14944 +f 7104/8017/15050 7017/7623/14468 7105/7860/14777 +f 7391/7862/14779 7380/7861/14778 7390/7784/14687 +f 6859/5768/12450 6860/7304/13942 6861/7454/14188 +f 7372/7636/14485 7274/7841/14756 7373/7603/14442 +f 6910/5977/14867 6909/5769/14868 6911/5771/14868 +f 7072/7879/14798 7139/7727/14603 7070/7734/14611 +f 7162/8018/15051 7336/7647/14501 7335/7904/14828 +f 6774/7061/13654 6775/6800/13372 6795/6802/13374 +f 7779/6326/12948 7780/6653/13227 7669/7101/13697 +f 7853/5912/12573 7865/7380/14412 7864/5910/12571 +f 7051/7600/14439 7373/7603/14442 7052/7777/14678 +f 6326/6268/13014 6337/6956/13014 6309/7558/13014 +f 7452/7065/15007 7453/6561/14627 7454/6629/13210 +f 6961/5950/14937 6970/6377/12996 6960/5948/14047 +f 7232/8009/15034 7214/7681/14535 7223/7716/14585 +f 6510/7178/13783 6513/7159/13758 6471/7176/13781 +f 7468/7234/12542 7459/7408/12542 7457/6515/12542 +f 7146/8019/15052 7143/7993/15011 7145/7997/15015 +f 7314/7957/14915 7312/7608/14451 7401/7660/14514 +f 6544/7547/14596 6545/7532/14309 6572/6713/13280 +f 6591/7011/13595 6590/7231/14566 6631/7573/14386 +f 7363/7626/14471 7345/7705/14562 7361/7704/14561 +f 7378/7847/14762 7170/7941/14879 7168/7848/14763 +f 6675/7047/13982 6662/6488/13088 6677/7128/14855 +f 7399/7619/14464 7398/7845/14760 7400/7617/14462 +f 7211/7852/14767 7219/7688/14542 7210/8006/15028 +f 7675/6333/12955 7755/6120/12765 7674/5871/12540 +f 6657/7347/14014 6651/7441/14165 6733/6648/13224 +f 7979/7313/13960 7991/6188/12824 7990/7312/13958 +f 7778/6484/13086 7735/6749/13317 7750/7409/14117 +f 6651/7441/14165 6657/7347/14014 6652/5899/14166 +f 7010/7800/14707 7005/7768/14668 7006/7907/14831 +f 7759/7386/14079 7758/5777/12456 7744/5808/12485 +f 7206/7690/14545 7223/7716/14585 7214/7681/14535 +f 7448/6922/13513 7451/6180/14052 7450/7064/15008 +f 6769/6058/12705 6835/7173/14370 6834/7225/13846 +f 7336/7647/14501 7340/7775/14676 7339/7774/14675 +f 7804/6989/13572 7820/7286/13924 7805/7285/13923 +f 7441/6678/13251 7443/6960/14025 7442/6850/14024 +f 7737/6777/14020 7723/6393/13348 7738/6778/13349 +f 7804/6989/13572 7817/6988/13571 7819/7434/15053 +f 7089/7746/14632 7084/7620/14465 7082/7911/14836 +f 7326/7866/14783 7328/7754/14643 7157/7803/14714 +f 6407/6241/12870 6495/6017/12668 6493/6591/13174 +f 7896/7216/13411 7893/7012/13411 7895/6952/13411 +f 7903/7417/14132 8013/7458/14194 7913/6826/13399 +f 6888/7369/14048 6885/7008/13592 6891/6245/13591 +f 7475/6560/12542 7455/6514/12542 7453/6561/12542 +f 6610/5959/12615 6609/5945/12602 6608/7571/14381 +f 7039/7649/14503 7301/7633/14481 7300/8001/15022 +f 6316/6768/14049 6315/6734/14086 6317/7189/13793 +f 7384/7722/14595 7340/7775/14676 7383/7720/14593 +f 7212/7849/14764 7280/7991/15009 7277/7842/14757 +f 7341/7739/14620 7333/7613/14457 7342/7672/14526 +f 7367/7773/14674 7364/7921/14850 7365/7934/14870 +f 5816/6724/13944 5817/6776/13345 5794/6775/13344 +f 6865/7425/14138 6768/7343/14006 6867/5990/12646 +f 6417/7419/12708 6416/7503/12708 6415/7123/12708 +f 7286/7976/14965 7189/7973/14961 7287/7972/14960 +f 7092/7881/14800 7123/7694/14549 7093/7979/14976 +f 7220/7680/14534 7369/7687/14541 7235/7590/14424 +f 7675/6333/12955 7665/6332/12954 7669/7101/12954 +f 7388/7628/14473 7386/7630/14475 7389/7669/14521 +f 7808/6302/12518 7806/7566/14373 7807/7583/14407 +f 6602/6123/13484 6603/7336/13999 6579/5839/13485 +f 7330/7733/14610 7323/7728/14604 7325/7731/14608 +f 6693/6239/12868 6658/6238/12867 6694/6758/15038 +f 6658/6238/12867 6659/6841/13417 6667/7335/14543 +f 7136/7769/14670 7081/7621/14466 7084/7620/14465 +f 7144/8020/15054 7143/7993/15011 7146/8019/15052 +f 7918/6445/14340 7935/5984/12794 7919/5863/12532 +f 7820/7286/13924 7804/6989/13572 7819/7434/15053 +f 7151/7909/14834 7069/7832/14746 7346/7760/14658 +f 7119/7981/14978 7118/7614/14458 7056/7616/14460 +f 7426/6524/13119 7508/6399/13015 7423/7363/14232 +f 6372/7526/14298 6278/6279/12904 6377/7429/14144 +f 7173/7797/14704 7376/7752/14641 7306/7654/14508 +f 7399/7619/14464 7366/7776/14677 7365/7934/14870 +f 6358/6498/13097 6384/6140/12785 6385/6139/12784 +f 7017/7623/14468 7104/8017/15050 7103/8007/15031 +f 7367/7773/14674 7291/7743/14630 7368/7932/14866 +f 7970/6408/14214 8008/7075/13670 7969/6409/13934 +f 6538/8005/15026 6551/7718/14971 6550/7448/14663 +f 7252/7641/14493 7253/7908/14833 7254/8011/15039 +f 7097/7692/14547 7128/7762/14660 7129/7966/14944 +f 7885/7432/14152 7886/7104/13700 7887/7431/14150 +f 6343/6924/13516 6386/6755/13325 6389/7540/14321 +f 7810/6674/12518 7839/5761/12518 7843/6249/12518 +f 6958/6948/15045 6943/7473/14222 6959/6946/14221 +f 6282/7402/14102 6387/6754/13324 6383/6142/12787 +f 7410/7756/14908 7195/7954/14903 7194/7970/14956 +f 6410/6275/12900 6409/7395/14093 6511/7543/14324 +f 6716/6348/12965 6746/7120/13715 6747/7723/14597 +f 5838/6370/12988 5839/6321/12944 5837/5958/12614 +f 7092/7881/14800 7091/7988/15000 7101/7947/14889 +f 7159/7729/14605 7323/7728/14604 7324/7939/14877 +f 6532/6032/14119 6642/6651/14119 6529/6650/14119 +f 7616/5940/12598 7631/6343/12960 7615/7375/14057 +f 6738/6557/13147 6709/7272/14319 6737/6558/13148 +f 6850/5796/12473 6839/7097/14690 6838/5797/12474 +f 7356/7685/14539 7001/7888/14810 7065/7965/14942 +f 6862/6153/12796 6859/5768/12450 6861/7454/14188 +f 8011/7460/14199 8013/7458/14194 7903/7417/14132 +f 7069/7832/14746 7139/7727/14603 7137/7886/14808 +f 7311/7668/14520 7310/7738/14619 7309/7982/14982 +f 7298/7782/14685 7390/7784/14687 7380/7861/14778 +f 6848/6060/12707 6837/6738/14397 6836/6818/15029 +f 6635/6251/12876 6530/7015/13600 6636/5851/12520 +f 6679/6907/13926 6680/6593/13926 6678/6592/14948 +f 6828/7201/13809 6829/7439/14162 6816/7200/13808 +f 7314/7957/14915 7304/7610/14454 7317/7606/14449 +f 7481/6029/13976 7521/7368/14046 7480/6027/14045 +f 7844/6009/12518 7834/6725/12518 7848/7517/12518 +f 6908/7354/14029 6910/5977/12632 6896/5976/12631 +f 7300/8001/15022 7055/7805/14717 7039/7649/14503 +f 7277/7842/14757 7371/7638/14487 7212/7849/14764 +f 7193/7971/14957 7192/7990/15002 7409/7937/14958 +f 5789/6973/14125 5788/7300/14126 5787/6990/14126 +f 7385/7721/14594 7383/7720/14593 7382/7813/14725 +f 7311/7668/14520 7391/7862/14779 7389/7669/14521 +f 6440/6176/14477 6437/7147/14426 6439/7146/14477 +f 7235/7590/14424 7369/7687/14541 7375/7599/14438 +f 7225/7996/15014 7206/7690/14545 7226/7689/14544 +f 6387/6754/13324 6282/7402/14102 6388/7541/14322 +f 6487/7181/13787 6489/6095/12739 6486/7160/13759 +f 6989/6634/13217 6952/7758/14819 6953/6135/12780 +f 7319/7857/14773 7302/7924/14853 7320/7644/14497 +f 5749/5791/12470 5850/5790/12469 5849/7480/14231 +f 7049/7807/14719 7048/7806/14718 7217/7927/14861 +f 7304/7610/14454 7289/7708/14571 7305/7609/14453 +f 5805/6226/12494 5773/6155/13027 5775/7326/13027 +f 7671/5776/12455 7668/6695/13263 7672/7355/13263 +f 6628/7135/13730 6587/7134/13729 6624/7058/13651 +f 7274/7841/14756 7372/7636/14485 7277/7842/14757 +f 6827/6418/14170 6826/7202/13913 6863/7428/14141 +f 7377/7664/14518 7335/7904/14828 7379/7951/14899 +f 7316/7696/14551 7319/7857/14773 7320/7644/14497 +f 6593/7102/15055 6594/6521/14291 6580/5759/14292 +f 7290/7715/14581 7304/7610/14454 7303/7948/14893 +f 6407/6241/12870 6493/6591/13174 6491/6049/12696 +f 7866/7605/15005 7800/5988/12644 7865/7380/14062 +f 7069/7832/14746 7151/7909/14834 6998/7711/14574 +f 7379/7951/14899 7335/7904/14828 7339/7774/14675 +f 6740/5751/12437 6742/7215/13836 6741/5752/12438 +f 7166/8021/15056 7337/7902/14826 7167/7903/14827 +f 7245/7682/14536 7214/7681/14535 7246/7792/14699 +f 5811/6740/13306 5810/6527/13121 5843/5787/12466 +f 7059/7896/14818 7056/7616/14460 7349/7724/14600 +f 6608/7571/14381 6609/5945/12602 6596/5947/12604 +f 6639/6436/13052 6640/7415/13052 6525/6031/13052 +f 7164/7648/14502 7336/7647/14501 7162/8018/15051 +f 7128/7762/14660 7124/7977/14967 7127/7900/14823 +f 6966/6947/13536 6969/7533/14311 6967/6975/13554 +f 6350/6955/13541 6351/6089/12733 6336/7461/14565 +f 5758/6553/14211 5759/6552/13805 5771/6156/13807 +f 6821/7333/12498 6822/6889/12498 6791/6639/12498 +f 6282/7402/14102 6286/6602/13181 6388/7541/14322 +f 6648/6291/12983 6747/7723/14597 6746/7120/13715 +f 6725/6729/13296 6724/6728/13295 6734/6056/12703 +f 7738/6778/13349 7727/6054/12701 7739/6053/12700 +f 6916/6158/14801 6918/7166/14127 6914/6368/13751 +f 7345/7705/14562 7153/7960/14921 7346/7760/14658 +f 7911/6440/13222 8019/6644/13222 8018/7280/13222 +f 8004/7969/14955 8003/6943/13532 8001/5961/12617 +f 6449/6991/14276 6457/6177/14578 6471/7176/13781 +f 7828/7309/14408 7807/7583/14407 7826/5919/14985 +f 7154/7980/14977 7344/7814/14726 7155/7597/14436 +f 7870/5801/12478 7882/5800/12477 7881/5955/12611 +f 7571/6820/13392 7569/6427/14995 7568/7088/14994 +f 6810/6297/12917 6832/6133/12919 6833/6351/12968 +f 6759/7229/12962 6768/7343/12962 6760/7358/12962 +f 5787/6990/14553 5788/7300/15057 5786/6464/13896 +f 7005/7768/14668 7009/7799/14706 7004/7766/14666 +f 6929/6613/13191 6930/6612/13190 6931/6718/13284 +f 6673/7046/13639 6674/5795/14021 6672/7349/14022 +f 7270/7785/14688 7214/7681/14535 7244/7683/14537 +f 7420/6234/12863 7412/6233/12862 7421/6525/12862 +f 7285/7935/14871 7213/7640/14492 7251/7639/14491 +f 6569/6151/14227 6567/6714/13456 6568/6878/13455 +f 6881/7536/14316 6980/5815/12492 6981/5814/12491 +f 7162/8018/15051 7335/7904/14828 7163/7663/14517 +f 7616/5940/12598 7601/7376/14058 7603/7297/13933 +f 6849/5798/12475 6765/6059/12706 6764/7288/14133 +f 6458/6951/12708 6440/6176/12708 6442/6199/12708 +f 6522/7106/13702 6524/7504/14265 6629/7574/14387 +f 7425/7244/13869 7416/6565/12862 7415/6403/13019 +f 7306/7654/14508 7175/7653/14507 7171/7897/14820 +f 7892/7306/13949 7873/6006/12661 7792/7014/13599 +f 7364/7921/14850 7367/7773/14674 7219/7688/14542 +f 7653/7483/14234 7553/7559/14358 7549/7036/13626 +f 6676/7045/13638 6674/5795/14021 6673/7046/13639 +f 6662/6488/13088 6660/7453/12472 6658/6238/12472 +f 7158/7611/14455 7337/7902/14826 7166/8021/15056 +f 7177/8016/15048 7315/7643/14496 7176/7992/15010 +f 7301/7633/14481 7002/7674/14528 7291/7743/14630 +f 7087/7735/14615 7097/7692/14547 7088/7747/14633 +f 7767/6329/12951 7749/7190/13794 7769/7422/14135 +f 7560/6823/13396 7556/6426/12847 7559/6983/13564 +f 5769/5816/14579 5767/6628/13209 5770/7465/14634 +f 6481/6559/13149 6480/6016/12667 6498/7019/13607 +f 7313/7667/14519 7400/7617/14462 7312/7608/14451 +f 6931/6718/13284 6902/6717/13283 6901/7332/13990 +f 8001/5961/12617 8003/6943/13532 8002/5962/12618 +f 6766/7420/14134 6761/6014/12962 6757/6013/12962 +f 7554/6693/13262 7551/7560/12567 7552/7824/14736 +f 7189/7973/14961 7305/7609/14453 7191/8014/15046 +f 5828/6914/13503 5829/6915/13505 5831/7305/13948 +f 7807/7583/14407 7831/7223/14954 7808/6302/12923 +f 7420/6234/12863 7512/5887/12554 7417/6232/12861 +f 7008/7778/14679 7007/7906/14830 7005/7768/14668 +f 6881/7536/14635 6884/6434/13591 6878/7748/14635 +f 7417/6232/12861 7512/5887/12554 7513/5886/12553 +f 7179/7652/14506 7315/7643/14496 7178/8015/15047 +f 7054/7825/14738 7369/7687/14541 7368/7932/14866 +f 5837/5958/12614 5836/5742/12428 5838/6370/12988 +f 7321/7699/14556 7323/7728/14604 7330/7733/14610 +f 7309/7982/14982 7391/7862/14779 7311/7668/14520 +f 7618/6147/12792 7633/6146/12791 7624/7446/14174 +f 6494/7132/13727 6492/7131/13726 6493/6591/13174 +f 6354/6632/14208 6353/6356/14269 6370/7370/14050 +f 7832/6890/12518 7848/7517/12518 7834/6725/12518 +f 7360/7627/14472 7359/7854/14770 7326/7866/14783 +f 7299/7963/14924 7342/7672/14526 7057/7671/14525 +f 7151/7909/14834 7150/7858/14774 6998/7711/14574 +f 6904/6799/12440 6902/6717/12440 6938/5995/12440 +f 7239/7915/14841 7238/7901/14825 7237/7588/14422 +f 7126/7593/14431 7124/7977/14967 7122/7601/14440 +f 5822/6371/12989 5821/6225/13947 5751/6365/12990 +f 7230/7791/14696 7249/7790/14695 7231/8010/15035 +f 6630/7371/14051 6627/7060/13653 6626/7094/13688 +f 7076/8000/15018 7138/7713/14576 7075/8003/15024 +f 7133/7770/14671 7134/7884/14806 7136/7769/14670 +f 7068/7815/14727 7135/7887/14809 7132/7885/14807 +f 7745/6548/13140 7759/7386/14079 7744/5808/12485 +f 7248/7863/14780 7242/7987/14999 7241/7864/14781 +f 7317/7606/14449 7312/7608/14451 7314/7957/14915 +f 6475/7117/13712 6459/6061/14282 6474/6143/12788 +f 7138/7713/14576 7074/7999/15017 7073/7714/14577 +f 7777/6107/12751 7778/6484/13086 7780/6653/13227 +f 7277/7842/14757 7280/7991/15009 7279/7995/15013 +f 7214/7681/14535 7231/8010/15035 7249/7790/14695 +f 7845/6007/13831 7855/7211/13830 7843/6249/14196 +f 7855/7211/14031 7883/7426/14139 7854/5799/12476 +f 6447/6335/12708 6424/6218/12708 6450/6917/12708 +f 7334/7612/14456 7158/7611/14455 7332/7961/14922 +f 7560/6823/13396 7563/6888/12847 7556/6426/12847 +f 7826/5919/12580 7829/6892/13471 7828/7309/13954 +f 7994/7570/14380 7982/5869/12690 7983/7145/13740 +f 7761/7385/14078 7762/6547/13139 7760/5775/12454 +f 6782/6285/14205 6784/6287/14997 6785/6476/13079 +f 6651/7441/14165 6646/7240/13867 6735/6057/12704 +f 7141/7994/15012 7143/7993/15011 7144/8020/15054 +f 7045/7953/14901 7039/7649/14503 7046/7804/14716 +f 7000/7956/14913 7068/7815/14727 6999/7703/14560 +f 7113/7656/14510 7033/7701/14558 7032/7657/14511 +f 7800/5988/12644 7878/7348/14018 7795/5986/12642 +f 7319/7857/14773 7184/7913/14839 7186/8012/15040 +f 7736/6394/14281 7737/6777/13346 7669/7101/13697 +f 7122/7601/14440 7005/7768/14668 7126/7593/14431 +f 7993/6039/12691 7994/7570/14380 7996/6567/13154 +f 7569/6427/14995 7571/6820/13392 7570/6819/13391 +f 6643/7115/12916 6650/6927/12916 6647/6101/12916 +f 6722/7516/14684 6721/7254/14013 6657/7347/14014 +f 7482/7462/14200 7468/7234/13860 7483/7233/13859 +f 6373/6360/12978 6355/5902/14010 6354/6632/14208 +f 6912/6369/13749 6910/5977/15032 6911/5771/15032 +f 7191/8014/15046 7305/7609/14453 7289/7708/14571 +f 6984/6664/13238 6887/7024/13612 6983/6663/13237 +f 7337/7902/14826 7333/7613/14457 7165/7646/14500 +f 7213/7640/14492 7283/7968/14952 7212/7849/14764 +f 6994/6435/13591 6993/6732/13591 6992/6433/13591 +f 7039/7649/14503 7041/7869/14786 7040/7650/14504 +f 7949/6518/13056 7953/6517/13056 7924/5883/13056 +f 7725/7266/12562 7692/6044/12562 7690/7236/12562 +f 7160/7730/14606 7325/7731/14608 7323/7728/14604 +f 6441/6181/14824 6443/6070/13104 6442/6199/13103 +f 6992/6433/13050 6878/7748/13050 6884/6434/13050 +f 7140/8004/15025 7138/7713/14576 7141/7994/15012 +f 7638/6814/13385 7639/7569/14379 7640/6038/12689 +f 6828/7201/13809 6813/6416/13032 6827/6418/13034 +f 8057/8022/15058 8424/8023/15059 8207/8024/15060 +f 8270/8025/15061 8158/8026/15062 8402/8027/15063 +f 8066/8028/15064 8096/8029/15065 8279/8030/15066 +f 8056/8031/15067 8057/8022/15058 8058/8032/15068 +f 8167/8033/15069 8048/8034/15070 8064/8035/15071 +f 8054/8036/15072 8055/8037/15073 8056/8031/15067 +f 8030/8038/15074 8031/8039/15075 8029/8040/15076 +f 8037/8041/15077 8030/8038/15074 8290/8042/15078 +f 8392/8043/15079 8368/8044/15080 8021/8045/15081 +f 8151/8046/15082 8148/8047/15083 8142/8048/15084 +f 8026/8049/15085 8024/8050/15086 8214/8051/15087 +f 8271/8052/15088 8298/8053/15089 8292/8054/15090 +f 8140/8055/15091 8320/8056/15092 8388/8057/15093 +f 8066/8028/15064 8067/8058/15094 8387/8059/15095 +f 8078/8060/15096 8075/8061/15097 8025/8062/15098 +f 8140/8055/15091 8388/8057/15093 8379/8063/15099 +f 8411/8064/15100 8383/8065/15101 8410/8066/15102 +f 8050/8067/15103 8054/8036/15072 8167/8033/15069 +f 8325/8068/15104 8278/8069/15105 8064/8035/15071 +f 8359/8070/15106 8358/8071/15107 8357/8072/15108 +f 8068/8073/15109 8023/8074/15110 8418/8075/15111 +f 8242/8076/15112 8039/8077/15113 8366/8078/15114 +f 8045/8079/15115 8362/8080/15116 8117/8081/15117 +f 8355/8082/15118 8356/8083/15119 8046/8084/15120 +f 8069/8085/15121 8021/8045/15081 8368/8044/15080 +f 8423/8086/15122 8331/8087/15123 8334/8088/15124 +f 8169/8089/15125 8175/8090/15126 8170/8091/15127 +f 8031/8039/15075 8030/8038/15074 8037/8041/15077 +f 8061/8092/15128 8063/8093/15129 8060/8094/15130 +f 8032/8095/15131 8034/8096/15132 8070/8097/15133 +f 8089/8098/15134 8087/8099/15135 8137/8100/15136 +f 8323/8101/15137 8315/8102/15138 8405/8103/15139 +f 8148/8047/15083 8149/8104/15140 8422/8105/15141 +f 8207/8024/15060 8395/8106/15142 8260/8107/15143 +f 8040/8108/15144 8319/8109/15145 8318/8110/15146 +f 8301/8111/15147 8311/8112/15148 8276/8113/15149 +f 8348/8114/15150 8260/8107/15143 8243/8115/15151 +f 8108/8116/15152 8107/8117/15153 8428/8118/15154 +f 8221/8119/15155 8128/8120/15156 8110/8121/15157 +f 8418/8075/15111 8023/8074/15110 8033/8122/15158 +f 8073/8123/15159 8090/8124/15160 8079/8125/15161 +f 8423/8086/15122 8334/8088/15124 8353/8126/15162 +f 8332/8127/15163 8423/8086/15122 8339/8128/15164 +f 8328/8129/15165 8374/8130/15166 8241/8131/15167 +f 8290/8042/15078 8161/8132/15168 8162/8133/15169 +f 8172/8134/15170 8287/8135/15171 8322/8136/15172 +f 8373/8137/15173 8103/8138/15174 8399/8139/15175 +f 8161/8132/15168 8290/8042/15078 8125/8140/15176 +f 8046/8084/15120 8023/8074/15110 8355/8082/15118 +f 8041/8141/15177 8107/8117/15153 8401/8142/15178 +f 8147/8143/15179 8142/8048/15084 8148/8047/15083 +f 8385/8144/15180 8305/8145/15181 8386/8146/15182 +f 8135/8147/15183 8073/8123/15159 8133/8148/15184 +f 8102/8149/15185 8103/8138/15174 8028/8150/15186 +f 8080/8151/15187 8082/8152/15188 8384/8153/15189 +f 8413/8154/15190 8182/8155/15191 8081/8156/15192 +f 8028/8150/15186 8322/8136/15172 8412/8157/15193 +f 8163/8158/15194 8128/8120/15156 8221/8119/15155 +f 8148/8047/15083 8352/8159/15195 8351/8160/15196 +f 8034/8096/15132 8033/8122/15158 8035/8161/15197 +f 8021/8045/15081 8020/8162/15198 8039/8077/15113 +f 8153/8163/15199 8175/8090/15126 8169/8089/15125 +f 8307/8164/15200 8077/8165/15201 8306/8166/15202 +f 8273/8167/15203 8275/8168/15204 8427/8169/15205 +f 8382/8170/15206 8300/8171/15207 8301/8111/15147 +f 8138/8172/15208 8021/8045/15081 8069/8085/15121 +f 8065/8173/15209 8060/8094/15130 8305/8145/15181 +f 8182/8155/15191 8347/8174/15210 8098/8175/15211 +f 8154/8176/15212 8183/8177/15213 8160/8178/15214 +f 8094/8179/15215 8328/8129/15165 8241/8131/15167 +f 8122/8180/15216 8179/8181/15217 8113/8182/15218 +f 8269/8183/15219 8074/8184/15220 8276/8113/15149 +f 8409/8185/15221 8389/8186/15222 8049/8187/15223 +f 8027/8188/15224 8271/8052/15088 8274/8189/15225 +f 8365/8190/15226 8350/8191/15227 8103/8138/15174 +f 8271/8052/15088 8273/8167/15203 8274/8189/15225 +f 8306/8166/15202 8286/8192/15228 8307/8164/15200 +f 8386/8146/15182 8171/8193/15229 8038/8194/15230 +f 8286/8192/15228 8308/8195/15231 8307/8164/15200 +f 8167/8033/15069 8168/8196/15232 8086/8197/15233 +f 8203/8198/15234 8211/8199/15235 8208/8200/15236 +f 8312/8201/15237 8191/8202/15238 8071/8203/15239 +f 8357/8072/15108 8358/8071/15107 8310/8204/15240 +f 8270/8025/15061 8402/8027/15063 8321/8205/15241 +f 8111/8206/15242 8153/8163/15199 8169/8089/15125 +f 8224/8207/15243 8065/8173/15209 8305/8145/15181 +f 8289/8208/15244 8294/8209/15245 8430/8210/15246 +f 8081/8156/15192 8073/8123/15159 8079/8125/15161 +f 8326/8211/15247 8040/8108/15144 8327/8212/15248 +f 8199/8213/15249 8202/8214/15250 8181/8215/15251 +f 8065/8173/15209 8195/8216/15252 8293/8217/15253 +f 8419/8218/15254 8049/8187/15223 8303/8219/15255 +f 8217/8220/15256 8140/8055/15091 8379/8063/15099 +f 8327/8212/15248 8040/8108/15144 8330/8221/15257 +f 8097/8222/15258 8098/8175/15211 8347/8174/15210 +f 8142/8048/15084 8145/8223/15259 8141/8224/15260 +f 8280/8225/15261 8156/8226/15262 8155/8227/15263 +f 8020/8162/15198 8375/8228/15264 8038/8194/15230 +f 8343/8229/15265 8344/8230/15265 8391/8231/15265 +f 8224/8207/15243 8305/8145/15181 8084/8232/15266 +f 8201/8233/15267 8241/8131/15167 8067/8058/15094 +f 8374/8130/15166 8121/8234/15268 8382/8170/15206 +f 8168/8196/15232 8181/8215/15251 8086/8197/15233 +f 8270/8025/15061 8302/8235/15269 8158/8026/15062 +f 8086/8197/15233 8197/8236/15270 8380/8237/15271 +f 8336/8238/15272 8267/8239/15273 8266/8240/15274 +f 8134/8241/15275 8133/8148/15184 8268/8242/15276 +f 8228/8243/15277 8058/8032/15068 8348/8114/15150 +f 8121/8234/15268 8374/8130/15166 8328/8129/15165 +f 8376/8244/15278 8375/8228/15264 8312/8201/15237 +f 8251/8245/15279 8243/8115/15151 8252/8246/15280 +f 8137/8100/15136 8091/8247/15281 8135/8147/15183 +f 8250/8248/15282 8243/8115/15151 8251/8245/15279 +f 8328/8129/15165 8094/8179/15215 8095/8249/15283 +f 8112/8250/15284 8244/8251/15285 8254/8252/15286 +f 8202/8214/15250 8204/8253/15287 8181/8215/15251 +f 8260/8107/15143 8258/8254/15288 8261/8255/15289 +f 8215/8256/15290 8140/8055/15091 8216/8257/15291 +f 8051/8258/15292 8184/8259/15293 8190/8260/15294 +f 8174/8261/15295 8178/8262/15296 8175/8090/15126 +f 8214/8051/15087 8092/8263/15297 8178/8262/15296 +f 8177/8264/15298 8189/8265/15299 8060/8094/15130 +f 8130/8266/15300 8239/8267/15301 8238/8268/15302 +f 8252/8246/15280 8243/8115/15151 8253/8269/15303 +f 8249/8270/15304 8243/8115/15151 8250/8248/15282 +f 8387/8059/15095 8382/8170/15206 8378/8271/15305 +f 8382/8170/15206 8121/8234/15268 8300/8171/15207 +f 8135/8147/15183 8142/8048/15084 8137/8100/15136 +f 8307/8164/15200 8076/8272/15306 8077/8165/15201 +f 8307/8164/15200 8188/8273/15307 8076/8272/15306 +f 8037/8041/15077 8036/8274/15308 8031/8039/15075 +f 8322/8136/15172 8173/8275/15309 8172/8134/15170 +f 8145/8223/15259 8045/8079/15115 8141/8224/15260 +f 8208/8200/15236 8211/8199/15235 8212/8276/15310 +f 8212/8276/15310 8213/8277/15311 8215/8256/15290 +f 8313/8278/15312 8085/8279/15313 8084/8232/15266 +f 8335/8280/15314 8291/8281/15315 8408/8282/15316 +f 8423/8086/15122 8199/8213/15249 8181/8215/15251 +f 8378/8271/15305 8098/8175/15211 8099/8283/15317 +f 8260/8107/15143 8261/8255/15289 8243/8115/15151 +f 8029/8040/15076 8026/8049/15085 8178/8262/15296 +f 8185/8284/15318 8187/8285/15319 8055/8037/15073 +f 8044/8286/15320 8045/8079/15115 8417/8287/15321 +f 8245/8288/15322 8243/8115/15151 8246/8289/15323 +f 8086/8197/15233 8205/8290/15324 8203/8198/15234 +f 8333/8291/15325 8323/8101/15137 8411/8064/15100 +f 8186/8292/15326 8051/8258/15292 8190/8260/15294 +f 8127/8293/15327 8128/8120/15156 8164/8294/15328 +f 8078/8060/15096 8191/8202/15238 8196/8295/15329 +f 8087/8099/15135 8138/8172/15208 8137/8100/15136 +f 8028/8150/15186 8416/8296/15330 8432/8297/15331 +f 8110/8121/15157 8193/8298/15332 8156/8226/15262 +f 8282/8299/15333 8153/8163/15199 8043/8300/15334 +f 8124/8301/15335 8273/8167/15203 8118/8302/15336 +f 8123/8303/15337 8124/8301/15335 8367/8304/15338 +f 8113/8182/15218 8324/8305/15339 8120/8306/15340 +f 8148/8047/15083 8152/8307/15341 8150/8308/15342 +f 8205/8290/15324 8086/8197/15233 8210/8309/15343 +f 8072/8310/15344 8270/8025/15061 8268/8242/15276 +f 8385/8144/15180 8038/8194/15230 8375/8228/15264 +f 8143/8311/15345 8140/8055/15091 8144/8312/15346 +f 8139/8313/15347 8143/8311/15345 8142/8048/15084 +f 8230/8314/15348 8194/8315/15349 8046/8084/15120 +f 8302/8235/15269 8115/8316/15350 8116/8317/15351 +f 8147/8143/15179 8148/8047/15083 8351/8160/15196 +f 8424/8023/15059 8057/8022/15058 8420/8318/15352 +f 8381/8319/15353 8242/8076/15112 8296/8320/15354 +f 8140/8055/15091 8143/8311/15345 8139/8313/15347 +f 8347/8174/15210 8413/8154/15190 8097/8222/15258 +f 8062/8321/15355 8039/8077/15113 8171/8193/15229 +f 8049/8187/15223 8393/8322/15356 8390/8323/15357 +f 8357/8072/15108 8310/8204/15240 8309/8324/15358 +f 8225/8325/15359 8094/8179/15215 8226/8326/15360 +f 8021/8045/15081 8381/8319/15353 8392/8043/15079 +f 8277/8327/15361 8271/8052/15088 8272/8328/15362 +f 8369/8329/15363 8037/8041/15077 8404/8330/15364 +f 8059/8331/15365 8354/8332/15366 8335/8280/15314 +f 8236/8333/15367 8220/8334/15368 8237/8335/15369 +f 8237/8335/15369 8223/8336/15370 8187/8285/15319 +f 8024/8050/15086 8188/8273/15307 8308/8195/15231 +f 8307/8164/15200 8308/8195/15231 8188/8273/15307 +f 8244/8251/15285 8243/8115/15151 8245/8288/15322 +f 8255/8337/15371 8244/8251/15285 8112/8250/15284 +f 8072/8310/15344 8268/8242/15276 8133/8148/15184 +f 8337/8338/15372 8309/8324/15358 8281/8339/15373 +f 8078/8060/15096 8071/8203/15239 8191/8202/15238 +f 8342/8340/15374 8036/8274/15308 8344/8230/15375 +f 8051/8258/15292 8185/8284/15318 8055/8037/15073 +f 8204/8253/15287 8210/8309/15343 8086/8197/15233 +f 8262/8341/15376 8258/8254/15288 8259/8342/15377 +f 8067/8058/15094 8279/8030/15066 8201/8233/15267 +f 8299/8343/15378 8285/8344/15379 8156/8226/15262 +f 8284/8345/15380 8403/8346/15381 8325/8068/15104 +f 8285/8344/15379 8325/8068/15104 8156/8226/15262 +f 8320/8056/15092 8321/8205/15241 8231/8347/15382 +f 8243/8115/15151 8286/8192/15228 8400/8348/15383 +f 8086/8197/15233 8198/8349/15384 8197/8236/15270 +f 8273/8167/15203 8271/8052/15088 8275/8168/15204 +f 8093/8350/15385 8092/8263/15297 8214/8051/15087 +f 8358/8071/15107 8360/8351/15386 8361/8352/15387 +f 8160/8178/15388 8183/8177/15389 8159/8353/15390 +f 8059/8331/15365 8222/8354/15391 8354/8332/15366 +f 8133/8148/15184 8073/8123/15159 8072/8310/15344 +f 8140/8055/15091 8139/8313/15347 8134/8241/15275 +f 8052/8355/15392 8392/8043/15079 8396/8356/15393 +f 8177/8264/15298 8065/8173/15209 8176/8357/15394 +f 8065/8173/15209 8293/8217/15253 8176/8357/15394 +f 8154/8176/15212 8112/8250/15284 8254/8252/15286 +f 8223/8336/15370 8237/8335/15369 8219/8358/15395 +f 8046/8084/15120 8194/8315/15349 8195/8216/15252 +f 8338/8359/15396 8281/8339/15373 8267/8239/15273 +f 8216/8257/15291 8140/8055/15091 8217/8220/15256 +f 8135/8147/15183 8091/8247/15281 8073/8123/15159 +f 8153/8163/15199 8154/8176/15212 8160/8178/15214 +f 8223/8336/15370 8165/8360/15397 8055/8037/15073 +f 8198/8349/15384 8203/8198/15234 8206/8361/15398 +f 8371/8362/15399 8156/8226/15262 8363/8363/15400 +f 8187/8285/15319 8223/8336/15370 8055/8037/15073 +f 8069/8085/15121 8091/8247/15281 8137/8100/15136 +f 8270/8025/15061 8072/8310/15344 8269/8183/15219 +f 8343/8229/15401 8342/8340/15374 8344/8230/15375 +f 8180/8364/15402 8282/8299/15333 8329/8365/15403 +f 8170/8091/15127 8092/8263/15297 8169/8089/15404 +f 8207/8024/15060 8424/8023/15059 8395/8106/15142 +f 8142/8048/15084 8141/8224/15260 8089/8098/15134 +f 8111/8206/15242 8092/8263/15297 8255/8337/15371 +f 8278/8069/15105 8325/8068/15104 8130/8266/15300 +f 8214/8051/15087 8024/8050/15086 8308/8195/15231 +f 8072/8310/15344 8074/8184/15220 8269/8183/15219 +f 8204/8253/15287 8086/8197/15233 8181/8215/15251 +f 8170/8091/15127 8178/8262/15296 8092/8263/15297 +f 8174/8261/15405 8029/8040/15405 8178/8262/15405 +f 8243/8115/15151 8244/8251/15285 8255/8337/15371 +f 8259/8342/15377 8258/8254/15288 8260/8107/15143 +f 8125/8140/15176 8180/8364/15402 8042/8366/15406 +f 8180/8364/15402 8329/8365/15403 8042/8366/15406 +f 8304/8367/15407 8171/8193/15229 8386/8146/15182 +f 8107/8117/15153 8263/8368/15408 8262/8341/15376 +f 8274/8189/15225 8273/8167/15203 8124/8301/15335 +f 8337/8338/15372 8281/8339/15373 8338/8359/15396 +f 8417/8287/15321 8045/8079/15115 8426/8369/15409 +f 8237/8335/15369 8220/8334/15368 8219/8358/15395 +f 8257/8370/15410 8254/8252/15286 8283/8371/15411 +f 8043/8300/15412 8159/8353/15412 8042/8366/15412 +f 8125/8140/15413 8042/8366/15413 8159/8353/15413 +f 8269/8183/15219 8115/8316/15350 8302/8235/15269 +f 8183/8177/15414 8254/8252/15286 8257/8370/15410 +f 8183/8177/15415 8154/8176/15415 8254/8252/15415 +f 8206/8361/15398 8203/8198/15234 8208/8200/15236 +f 8302/8235/15269 8116/8317/15351 8158/8026/15062 +f 8374/8130/15166 8387/8059/15095 8067/8058/15094 +f 8084/8232/15266 8385/8144/15180 8376/8244/15278 +f 8367/8304/15338 8121/8234/15268 8209/8372/15416 +f 8180/8364/15402 8290/8042/15078 8340/8373/15417 +f 8246/8289/15323 8243/8115/15151 8247/8374/15418 +f 8260/8107/15143 8421/8375/15419 8259/8342/15377 +f 8402/8027/15063 8049/8187/15223 8321/8205/15241 +f 8094/8179/15215 8240/8376/15420 8226/8326/15360 +f 8120/8306/15340 8324/8305/15339 8300/8171/15207 +f 8090/8124/15160 8091/8247/15281 8053/8377/15421 +f 8068/8073/15109 8342/8340/15374 8341/8378/15422 +f 8312/8201/15237 8088/8379/15423 8191/8202/15238 +f 8053/8377/15421 8052/8355/15392 8090/8124/15160 +f 8321/8205/15241 8320/8056/15092 8140/8055/15091 +f 8121/8234/15268 8120/8306/15340 8300/8171/15207 +f 8330/8221/15257 8040/8108/15144 8294/8209/15245 +f 8323/8101/15137 8333/8291/15325 8315/8102/15138 +f 8025/8062/15098 8024/8050/15086 8026/8049/15085 +f 8060/8094/15130 8304/8367/15407 8305/8145/15181 +f 8311/8112/15148 8115/8316/15350 8269/8183/15219 +f 8301/8111/15147 8324/8305/15339 8311/8112/15148 +f 8393/8322/15356 8086/8197/15233 8380/8237/15271 +f 8278/8069/15105 8184/8259/15293 8050/8067/15103 +f 8385/8144/15180 8375/8228/15264 8376/8244/15278 +f 8035/8161/15197 8033/8122/15158 8023/8074/15110 +f 8305/8145/15181 8304/8367/15407 8386/8146/15182 +f 8306/8166/15202 8323/8101/15137 8228/8243/15277 +f 8046/8084/15120 8065/8173/15209 8224/8207/15243 +f 8247/8374/15418 8243/8115/15151 8248/8380/15424 +f 8115/8316/15350 8311/8112/15148 8114/8381/15425 +f 8119/8382/15426 8179/8181/15217 8122/8180/15216 +f 8091/8247/15281 8090/8124/15160 8073/8123/15159 +f 8370/8383/15427 8103/8138/15174 8373/8137/15173 +f 8361/8352/15387 8131/8384/15428 8358/8071/15107 +f 8097/8222/15258 8413/8154/15190 8384/8153/15189 +f 8256/8385/15429 8372/8386/15430 8159/8353/15431 +f 8167/8033/15069 8086/8197/15233 8048/8034/15070 +f 8057/8022/15058 8056/8031/15067 8059/8331/15365 +f 8317/8387/15432 8132/8388/15433 8345/8389/15434 +f 8071/8203/15239 8070/8097/15133 8085/8279/15313 +f 8325/8068/15104 8064/8035/15071 8156/8226/15262 +f 8392/8043/15079 8052/8355/15392 8053/8377/15421 +f 8184/8259/15293 8265/8390/15435 8190/8260/15294 +f 8316/8391/15436 8037/8041/15077 8132/8388/15433 +f 8383/8065/15101 8077/8165/15201 8196/8295/15329 +f 8179/8181/15217 8221/8119/15155 8157/8392/15437 +f 8086/8197/15233 8049/8187/15223 8048/8034/15070 +f 8076/8272/15306 8075/8061/15097 8077/8165/15201 +f 8222/8354/15391 8055/8037/15073 8166/8393/15438 +f 8428/8118/15154 8107/8117/15153 8262/8341/15376 +f 8095/8249/15283 8209/8372/15416 8328/8129/15165 +f 8118/8302/15336 8120/8306/15340 8121/8234/15268 +f 8389/8186/15222 8231/8347/15382 8049/8187/15223 +f 8109/8394/15439 8110/8121/15157 8128/8120/15156 +f 8170/8091/15127 8175/8090/15126 8178/8262/15296 +f 8240/8376/15420 8201/8233/15267 8200/8395/15440 +f 8382/8170/15206 8387/8059/15095 8374/8130/15166 +f 8143/8311/15345 8146/8396/15441 8142/8048/15084 +f 8181/8215/15251 8405/8103/15139 8423/8086/15122 +f 8032/8095/15131 8033/8122/15158 8034/8096/15132 +f 8387/8059/15095 8099/8283/15317 8066/8028/15064 +f 8052/8355/15392 8396/8356/15393 8082/8152/15188 +f 8024/8050/15086 8025/8062/15098 8075/8061/15097 +f 8348/8114/15150 8243/8115/15151 8400/8348/15383 +f 8087/8099/15135 8021/8045/15081 8138/8172/15208 +f 8083/8397/15442 8023/8074/15110 8022/8398/15443 +f 8128/8120/15156 8127/8293/15327 8129/8399/15444 +f 8181/8215/15251 8058/8032/15068 8228/8243/15277 +f 8020/8162/15198 8038/8194/15230 8039/8077/15113 +f 8314/8400/15445 8405/8103/15139 8315/8102/15138 +f 8028/8150/15186 8103/8138/15174 8027/8188/15224 +f 8276/8113/15149 8098/8175/15211 8378/8271/15305 +f 8236/8333/15367 8266/8240/15274 8220/8334/15368 +f 8410/8066/15102 8383/8065/15101 8045/8079/15115 +f 8269/8183/15219 8276/8113/15149 8311/8112/15148 +f 8376/8244/15278 8312/8201/15237 8313/8278/15312 +f 8032/8095/15131 8031/8039/15075 8033/8122/15158 +f 8073/8123/15159 8081/8156/15192 8074/8184/15220 +f 8110/8121/15157 8064/8035/15071 8048/8034/15070 +f 8112/8250/15284 8111/8206/15242 8255/8337/15371 +f 8059/8331/15365 8056/8031/15067 8055/8037/15073 +f 8062/8321/15355 8060/8094/15130 8063/8093/15129 +f 8341/8378/15422 8342/8340/15374 8343/8229/15401 +f 8378/8271/15305 8382/8170/15206 8301/8111/15147 +f 8404/8330/15364 8037/8041/15077 8316/8391/15436 +f 8055/8037/15073 8222/8354/15391 8059/8331/15365 +f 8213/8277/15311 8140/8055/15091 8215/8256/15290 +f 8182/8155/15191 8276/8113/15149 8074/8184/15220 +f 8093/8350/15385 8308/8195/15231 8286/8192/15228 +f 8049/8187/15223 8231/8347/15382 8321/8205/15241 +f 8340/8373/15417 8282/8299/15333 8180/8364/15402 +f 8335/8280/15314 8289/8208/15244 8288/8401/15446 +f 8363/8363/15400 8229/8402/15447 8364/8403/15448 +f 8123/8303/15337 8209/8372/15416 8095/8249/15283 +f 8053/8377/15421 8091/8247/15281 8069/8085/15121 +f 8059/8331/15365 8408/8282/15316 8420/8318/15352 +f 8103/8138/15174 8350/8191/15227 8027/8188/15224 +f 8071/8203/15239 8078/8060/15096 8070/8097/15133 +f 8073/8123/15159 8074/8184/15220 8072/8310/15344 +f 8126/8404/15449 8125/8140/15176 8159/8353/15431 +f 8166/8393/15438 8055/8037/15073 8165/8360/15397 +f 8075/8061/15097 8076/8272/15306 8188/8273/15307 +f 8052/8355/15392 8080/8151/15187 8079/8125/15161 +f 8084/8232/15266 8083/8397/15442 8022/8398/15443 +f 8085/8279/15313 8083/8397/15442 8084/8232/15266 +f 8294/8209/15245 8289/8208/15244 8335/8280/15314 +f 8322/8136/15172 8028/8150/15186 8095/8249/15283 +f 8052/8355/15392 8079/8125/15161 8090/8124/15160 +f 8186/8292/15326 8185/8284/15318 8051/8258/15292 +f 8158/8026/15062 8049/8187/15223 8402/8027/15063 +f 8064/8035/15071 8050/8067/15103 8167/8033/15069 +f 8043/8300/15334 8153/8163/15199 8160/8178/15214 +f 8022/8398/15443 8023/8074/15110 8224/8207/15243 +f 8224/8207/15243 8084/8232/15266 8022/8398/15443 +f 8025/8062/15098 8026/8049/15085 8032/8095/15131 +f 8221/8119/15155 8110/8121/15157 8157/8392/15437 +f 8228/8243/15277 8400/8348/15383 8306/8166/15202 +f 8367/8304/15338 8209/8372/15416 8123/8303/15337 +f 8145/8223/15259 8142/8048/15084 8147/8143/15179 +f 8032/8095/15131 8070/8097/15133 8025/8062/15098 +f 8130/8266/15300 8238/8268/15302 8233/8405/15450 +f 8036/8274/15308 8037/8041/15077 8369/8329/15363 +f 8260/8107/15143 8395/8106/15142 8421/8375/15419 +f 8047/8406/15451 8023/8074/15110 8068/8073/15109 +f 8098/8175/15211 8276/8113/15149 8182/8155/15191 +f 8189/8265/15299 8061/8092/15128 8060/8094/15130 +f 8058/8032/15068 8057/8022/15058 8207/8024/15060 +f 8256/8385/15429 8159/8353/15431 8183/8177/15414 +f 8087/8099/15135 8088/8379/15423 8020/8162/15198 +f 8101/8407/15452 8100/8408/15453 8102/8149/15185 +f 8093/8350/15385 8255/8337/15371 8092/8263/15297 +f 8375/8228/15264 8088/8379/15423 8312/8201/15237 +f 8184/8259/15293 8232/8409/15454 8265/8390/15435 +f 8033/8122/15158 8031/8039/15075 8036/8274/15308 +f 8211/8199/15235 8213/8277/15311 8212/8276/15310 +f 8248/8380/15424 8243/8115/15151 8249/8270/15304 +f 8068/8073/15109 8418/8075/15111 8342/8340/15374 +f 8043/8300/15334 8329/8365/15403 8282/8299/15333 +f 8401/8142/15178 8107/8117/15153 8398/8410/15455 +f 8077/8165/15201 8078/8060/15096 8196/8295/15329 +f 8099/8283/15317 8097/8222/15258 8066/8028/15064 +f 8106/8411/15456 8101/8407/15452 8406/8412/15457 +f 8086/8197/15233 8203/8198/15234 8198/8349/15384 +f 8228/8243/15277 8405/8103/15139 8181/8215/15251 +f 8060/8094/15130 8065/8173/15209 8177/8264/15298 +f 8115/8316/15350 8113/8182/15218 8116/8317/15351 +f 8365/8190/15226 8103/8138/15174 8370/8383/15427 +f 8407/8413/15458 8103/8138/15174 8346/8414/15459 +f 8160/8178/15388 8159/8353/15390 8043/8300/15460 +f 8078/8060/15096 8077/8165/15201 8075/8061/15097 +f 8175/8090/15126 8153/8163/15199 8282/8299/15333 +f 8113/8182/15218 8114/8381/15425 8324/8305/15339 +f 8336/8238/15272 8266/8240/15274 8236/8333/15367 +f 8074/8184/15220 8081/8156/15192 8182/8155/15191 +f 8148/8047/15083 8150/8308/15342 8149/8104/15140 +f 8423/8086/15122 8353/8126/15162 8422/8105/15141 +f 8339/8128/15164 8423/8086/15122 8405/8103/15139 +f 8353/8126/15162 8352/8159/15195 8422/8105/15141 +f 8405/8103/15139 8228/8243/15277 8323/8101/15137 +f 8339/8128/15164 8405/8103/15139 8314/8400/15445 +f 8422/8105/15141 8352/8159/15195 8148/8047/15083 +f 8383/8065/15101 8411/8064/15100 8323/8101/15137 +f 8191/8202/15238 8192/8415/15461 8196/8295/15329 +f 8181/8215/15251 8054/8036/15072 8056/8031/15067 +f 8297/8416/15462 8027/8188/15224 8350/8191/15227 +f 8134/8241/15275 8321/8205/15241 8140/8055/15091 +f 8234/8417/15463 8103/8138/15174 8235/8418/15464 +f 8254/8252/15286 8244/8251/15285 8283/8371/15411 +f 8268/8242/15276 8321/8205/15241 8134/8241/15275 +f 8263/8368/15408 8258/8254/15288 8262/8341/15376 +f 8261/8255/15289 8264/8419/15465 8243/8115/15151 +f 8119/8382/15426 8122/8180/15216 8118/8302/15336 +f 8133/8148/15184 8134/8241/15275 8135/8147/15183 +f 8120/8306/15340 8118/8302/15336 8122/8180/15216 +f 8130/8266/15300 8325/8068/15104 8403/8346/15381 +f 8182/8155/15191 8413/8154/15190 8347/8174/15210 +f 8023/8074/15110 8083/8397/15442 8035/8161/15197 +f 8313/8278/15312 8084/8232/15266 8376/8244/15278 +f 8338/8359/15396 8267/8239/15273 8336/8238/15272 +f 8141/8224/15260 8088/8379/15423 8089/8098/15134 +f 8363/8363/15400 8156/8226/15262 8193/8298/15332 +f 8144/8312/15346 8140/8055/15091 8227/8420/15466 +f 8053/8377/15421 8069/8085/15121 8368/8044/15080 +f 8110/8121/15157 8156/8226/15262 8064/8035/15071 +f 8164/8294/15328 8128/8120/15156 8163/8158/15194 +f 8239/8267/15301 8130/8266/15300 8131/8384/15428 +f 8196/8295/15329 8192/8415/15461 8383/8065/15101 +f 8050/8067/15103 8064/8035/15071 8278/8069/15105 +f 8114/8381/15425 8113/8182/15218 8115/8316/15350 +f 8126/8404/15449 8161/8132/15168 8125/8140/15176 +f 8364/8403/15448 8229/8402/15447 8429/8421/15467 +f 8029/8040/15076 8031/8039/15075 8032/8095/15131 +f 8122/8180/15216 8113/8182/15218 8120/8306/15340 +f 8397/8422/15468 8431/8423/15469 8040/8108/15144 +f 8088/8379/15423 8141/8224/15260 8192/8415/15461 +f 8412/8157/15193 8322/8136/15172 8287/8135/15171 +f 8270/8025/15061 8269/8183/15219 8302/8235/15269 +f 8273/8167/15203 8119/8382/15426 8118/8302/15336 +f 8301/8111/15147 8276/8113/15149 8378/8271/15305 +f 8335/8280/15314 8408/8282/15316 8059/8331/15365 +f 8306/8166/15202 8077/8165/15201 8383/8065/15101 +f 8175/8090/15126 8029/8040/15076 8174/8261/15295 +f 8058/8032/15068 8181/8215/15251 8056/8031/15067 +f 8028/8150/15186 8027/8188/15224 8123/8303/15337 +f 8135/8147/15183 8134/8241/15275 8139/8313/15347 +f 8028/8150/15186 8432/8297/15331 8102/8149/15185 +f 8051/8258/15292 8055/8037/15073 8054/8036/15072 +f 8349/8424/15470 8309/8324/15358 8337/8338/15372 +f 8344/8230/15375 8036/8274/15308 8394/8425/15471 +f 8069/8085/15121 8137/8100/15136 8138/8172/15208 +f 8148/8047/15083 8151/8046/15082 8152/8307/15341 +f 8116/8317/15351 8157/8392/15437 8158/8026/15062 +f 8153/8163/15199 8111/8206/15242 8154/8176/15212 +f 8155/8227/15263 8156/8226/15262 8371/8362/15399 +f 8427/8169/15205 8221/8119/15155 8273/8167/15203 +f 8282/8299/15333 8340/8373/15417 8175/8090/15126 +f 8224/8207/15243 8023/8074/15110 8046/8084/15120 +f 8048/8034/15070 8157/8392/15437 8110/8121/15157 +f 8096/8029/15065 8066/8028/15064 8097/8222/15258 +f 8111/8206/15242 8112/8250/15284 8154/8176/15212 +f 8369/8329/15363 8404/8330/15364 8377/8426/15472 +f 8124/8301/15335 8118/8302/15336 8367/8304/15338 +f 8039/8077/15113 8242/8076/15112 8021/8045/15081 +f 8169/8089/15125 8092/8263/15473 8111/8206/15242 +f 8100/8408/15453 8103/8138/15174 8102/8149/15185 +f 8270/8025/15061 8321/8205/15241 8268/8242/15276 +f 8325/8068/15104 8285/8344/15379 8284/8345/15380 +f 8088/8379/15423 8375/8228/15264 8020/8162/15198 +f 8045/8079/15115 8117/8081/15117 8410/8066/15102 +f 8162/8133/15169 8161/8132/15168 8136/8427/15474 +f 8425/8428/15475 8023/8074/15110 8415/8429/15476 +f 8240/8376/15420 8241/8131/15167 8201/8233/15267 +f 8116/8317/15351 8113/8182/15218 8179/8181/15217 +f 8298/8053/15089 8027/8188/15224 8297/8416/15462 +f 8272/8328/15362 8271/8052/15088 8292/8054/15090 +f 8128/8120/15156 8129/8399/15444 8109/8394/15439 +f 8181/8215/15251 8168/8196/15232 8054/8036/15072 +f 8358/8071/15107 8040/8108/15144 8310/8204/15240 +f 8024/8050/15086 8075/8061/15097 8188/8273/15307 +f 8324/8305/15339 8301/8111/15147 8300/8171/15207 +f 8043/8300/15477 8042/8366/15477 8329/8365/15477 +f 8279/8030/15066 8067/8058/15094 8066/8028/15064 +f 8027/8188/15224 8124/8301/15335 8123/8303/15337 +f 8192/8415/15461 8191/8202/15238 8088/8379/15423 +f 8137/8100/15136 8142/8048/15084 8089/8098/15134 +f 8273/8167/15203 8221/8119/15155 8119/8382/15426 +f 8218/8430/15478 8140/8055/15091 8213/8277/15311 +f 8085/8279/15313 8313/8278/15312 8071/8203/15239 +f 8050/8067/15103 8051/8258/15292 8054/8036/15072 +f 8416/8296/15330 8028/8150/15186 8412/8157/15193 +f 8414/8431/15479 8039/8077/15113 8062/8321/15355 +f 8167/8033/15069 8054/8036/15072 8168/8196/15232 +f 8397/8422/15468 8040/8108/15144 8041/8141/15177 +f 8105/8432/15480 8101/8407/15452 8106/8411/15456 +f 8340/8373/15417 8029/8040/15076 8175/8090/15126 +f 8067/8058/15094 8241/8131/15167 8374/8130/15166 +f 8177/8264/15298 8176/8357/15394 8189/8265/15299 +f 8214/8051/15087 8178/8262/15296 8026/8049/15085 +f 8253/8269/15303 8243/8115/15151 8264/8419/15465 +f 8303/8219/15255 8049/8187/15223 8390/8323/15357 +f 8107/8117/15153 8041/8141/15177 8040/8108/15144 +f 8039/8077/15113 8038/8194/15230 8171/8193/15229 +f 8275/8168/15204 8271/8052/15088 8277/8327/15361 +f 8099/8283/15317 8098/8175/15211 8097/8222/15258 +f 8045/8079/15115 8383/8065/15101 8192/8415/15461 +f 8386/8146/15182 8038/8194/15230 8385/8144/15180 +f 8130/8266/15300 8233/8405/15450 8184/8259/15293 +f 8020/8162/15198 8021/8045/15081 8087/8099/15135 +f 8286/8192/15228 8255/8337/15371 8093/8350/15385 +f 8316/8391/15436 8132/8388/15433 8317/8387/15432 +f 8193/8298/15332 8110/8121/15157 8109/8394/15439 +f 8260/8107/15143 8348/8114/15150 8207/8024/15060 +f 8078/8060/15096 8025/8062/15098 8070/8097/15133 +f 8081/8156/15192 8080/8151/15187 8413/8154/15190 +f 8027/8188/15224 8298/8053/15089 8271/8052/15088 +f 8104/8433/15481 8101/8407/15452 8105/8432/15480 +f 8225/8325/15359 8095/8249/15283 8094/8179/15215 +f 8146/8396/15441 8151/8046/15082 8142/8048/15084 +f 8195/8216/15252 8065/8173/15209 8046/8084/15120 +f 8214/8051/15087 8308/8195/15231 8093/8350/15385 +f 8140/8055/15091 8218/8430/15478 8227/8420/15466 +f 8286/8192/15228 8306/8166/15202 8400/8348/15383 +f 8357/8072/15108 8309/8324/15358 8349/8424/15470 +f 8221/8119/15155 8179/8181/15217 8119/8382/15426 +f 8183/8177/15414 8257/8370/15410 8256/8385/15429 +f 8193/8298/15332 8229/8402/15447 8363/8363/15400 +f 8082/8152/15188 8080/8151/15187 8052/8355/15392 +f 8311/8112/15148 8324/8305/15339 8114/8381/15425 +f 8095/8249/15283 8028/8150/15186 8123/8303/15337 +f 8034/8096/15132 8035/8161/15197 8083/8397/15442 +f 8312/8201/15237 8071/8203/15239 8313/8278/15312 +f 8340/8373/15417 8290/8042/15078 8030/8038/15074 +f 8192/8415/15461 8141/8224/15260 8045/8079/15115 +f 8184/8259/15293 8278/8069/15105 8130/8266/15300 +f 8372/8386/15430 8126/8404/15449 8159/8353/15431 +f 8305/8145/15181 8385/8144/15180 8084/8232/15266 +f 8034/8096/15132 8085/8279/15313 8070/8097/15133 +f 8207/8024/15060 8348/8114/15150 8058/8032/15068 +f 8398/8410/15455 8107/8117/15153 8108/8116/15152 +f 8036/8274/15308 8342/8340/15374 8418/8075/15111 +f 8156/8226/15262 8280/8225/15261 8299/8343/15378 +f 8290/8042/15078 8162/8133/15169 8037/8041/15077 +f 8051/8258/15292 8050/8067/15103 8184/8259/15293 +f 8060/8094/15130 8062/8321/15355 8304/8367/15407 +f 8033/8122/15158 8036/8274/15308 8418/8075/15111 +f 8125/8140/15176 8290/8042/15078 8180/8364/15402 +f 8095/8249/15283 8225/8325/15359 8322/8136/15172 +f 8304/8367/15407 8062/8321/15355 8171/8193/15229 +f 8295/8434/15482 8381/8319/15353 8296/8320/15354 +f 8319/8109/15145 8040/8108/15144 8326/8211/15247 +f 8139/8313/15347 8142/8048/15084 8135/8147/15183 +f 8366/8078/15114 8039/8077/15113 8414/8431/15479 +f 8179/8181/15217 8157/8392/15437 8116/8317/15351 +f 8241/8131/15167 8240/8376/15420 8094/8179/15215 +f 8200/8395/15440 8201/8233/15267 8279/8030/15066 +f 8049/8187/15223 8419/8218/15254 8409/8185/15221 +f 8310/8204/15240 8040/8108/15144 8318/8110/15146 +f 8360/8351/15386 8358/8071/15107 8359/8070/15106 +f 8414/8431/15479 8062/8321/15355 8063/8093/15129 +f 8046/8084/15120 8356/8083/15119 8230/8314/15348 +f 8255/8337/15371 8286/8192/15228 8243/8115/15151 +f 8392/8043/15079 8381/8319/15353 8295/8434/15482 +f 8415/8429/15476 8023/8074/15110 8047/8406/15451 +f 8383/8065/15101 8323/8101/15137 8306/8166/15202 +f 8163/8158/15194 8221/8119/15155 8427/8169/15205 +f 8032/8095/15131 8026/8049/15085 8029/8040/15076 +f 8132/8388/15433 8037/8041/15077 8136/8427/15474 +f 8086/8197/15233 8393/8322/15356 8049/8187/15223 +f 8355/8082/15118 8023/8074/15110 8425/8428/15475 +f 8228/8243/15277 8348/8114/15150 8400/8348/15383 +f 8079/8125/15161 8080/8151/15187 8081/8156/15192 +f 8083/8397/15442 8085/8279/15313 8034/8096/15132 +f 8387/8059/15095 8378/8271/15305 8099/8283/15317 +f 8088/8379/15423 8087/8099/15135 8089/8098/15134 +f 8225/8325/15359 8173/8275/15309 8322/8136/15172 +f 8059/8331/15365 8420/8318/15352 8057/8022/15058 +f 8158/8026/15062 8157/8392/15437 8048/8034/15070 +f 8430/8210/15246 8294/8209/15245 8431/8423/15469 +f 8346/8414/15459 8103/8138/15174 8234/8417/15463 +f 8274/8189/15225 8124/8301/15335 8027/8188/15224 +f 8121/8234/15268 8367/8304/15338 8118/8302/15336 +f 8335/8280/15314 8288/8401/15446 8291/8281/15315 +f 8030/8038/15074 8029/8040/15076 8340/8373/15417 +f 8103/8138/15174 8407/8413/15458 8399/8139/15175 +f 8184/8259/15293 8233/8405/15450 8232/8409/15454 +f 8040/8108/15144 8431/8423/15469 8294/8209/15245 +f 8368/8044/15080 8392/8043/15079 8053/8377/15421 +f 8100/8408/15453 8101/8407/15452 8104/8433/15481 +f 8426/8369/15409 8045/8079/15115 8145/8223/15259 +f 8209/8372/15416 8121/8234/15268 8328/8129/15165 +f 8423/8086/15122 8332/8127/15163 8331/8087/15123 +f 8036/8274/15308 8369/8329/15363 8394/8425/15471 +f 8048/8034/15070 8049/8187/15223 8158/8026/15062 +f 8136/8427/15474 8037/8041/15077 8162/8133/15169 +f 8381/8319/15353 8021/8045/15081 8242/8076/15112 +f 8358/8071/15107 8131/8384/15428 8130/8266/15300 +f 8045/8079/15115 8044/8286/15320 8362/8080/15116 +f 8384/8153/15189 8413/8154/15190 8080/8151/15187 +f 8235/8418/15464 8103/8138/15174 8100/8408/15453 +f 8470/8435/15483 8620/8436/15484 8837/8437/15485 +f 8683/8438/15486 8815/8439/15487 8571/8440/15488 +f 8479/8441/15489 8692/8442/15490 8509/8443/15491 +f 8469/8444/15492 8471/8445/15493 8470/8435/15483 +f 8580/8446/15494 8477/8447/15495 8461/8448/15496 +f 8467/8449/15497 8469/8444/15492 8468/8450/15498 +f 8443/8451/15499 8442/8452/15500 8444/8453/15501 +f 8450/8454/15502 8703/8455/15503 8443/8451/15499 +f 8805/8456/15504 8434/8457/15505 8781/8458/15506 +f 8564/8459/15507 8555/8460/15508 8561/8461/15509 +f 8439/8462/15510 8627/8463/15511 8437/8464/15512 +f 8684/8465/15513 8705/8466/15514 8711/8467/15515 +f 8553/8468/15516 8801/8469/15517 8733/8470/15518 +f 8479/8441/15489 8800/8471/15519 8480/8472/15520 +f 8491/8473/15521 8438/8474/15522 8488/8475/15523 +f 8553/8468/15516 8792/8476/15524 8801/8469/15517 +f 8824/8477/15525 8823/8478/15526 8796/8479/15527 +f 8463/8480/15528 8580/8446/15494 8467/8449/15497 +f 8738/8481/15529 8477/8447/15495 8691/8482/15530 +f 8772/8483/15531 8770/8484/15532 8771/8485/15533 +f 8481/8486/15534 8831/8487/15535 8436/8488/15536 +f 8655/8489/15537 8779/8490/15538 8452/8491/15539 +f 8458/8492/15540 8530/8493/15541 8775/8494/15542 +f 8768/8495/15543 8459/8496/15544 8769/8497/15545 +f 8482/8498/15546 8781/8458/15506 8434/8457/15505 +f 8836/8499/15547 8747/8500/15548 8744/8501/15549 +f 8582/8502/15550 8583/8503/15551 8588/8504/15552 +f 8444/8453/15501 8450/8454/15502 8443/8451/15499 +f 8474/8505/15553 8473/8506/15554 8476/8507/15555 +f 8445/8508/15556 8483/8509/15557 8447/8510/15558 +f 8502/8511/15559 8550/8512/15560 8500/8513/15561 +f 8736/8514/15562 8818/8515/15563 8728/8516/15564 +f 8561/8461/15509 8835/8517/15565 8562/8518/15566 +f 8620/8436/15484 8673/8519/15567 8808/8520/15568 +f 8453/8521/15569 8731/8522/15570 8732/8523/15571 +f 8714/8524/15572 8689/8525/15573 8724/8526/15574 +f 8761/8527/15575 8656/8528/15576 8673/8519/15567 +f 8521/8529/15577 8841/8530/15578 8520/8531/15579 +f 8634/8532/15580 8523/8533/15581 8541/8534/15582 +f 8831/8487/15535 8446/8535/15583 8436/8488/15536 +f 8486/8536/15584 8492/8537/15585 8503/8538/15586 +f 8836/8499/15547 8766/8539/15587 8747/8500/15548 +f 8745/8540/15588 8752/8541/15589 8836/8499/15547 +f 8741/8542/15590 8654/8543/15591 8787/8544/15592 +f 8703/8455/15503 8575/8545/15593 8574/8546/15594 +f 8585/8547/15595 8735/8548/15596 8700/8549/15597 +f 8786/8550/15598 8812/8551/15599 8516/8552/15600 +f 8574/8546/15594 8538/8553/15601 8703/8455/15503 +f 8459/8496/15544 8768/8495/15543 8436/8488/15536 +f 8454/8554/15602 8814/8555/15603 8520/8531/15579 +f 8560/8556/15604 8561/8461/15509 8555/8460/15508 +f 8798/8557/15605 8799/8558/15606 8718/8559/15607 +f 8548/8560/15608 8546/8561/15609 8486/8536/15584 +f 8515/8562/15610 8441/8563/15611 8516/8552/15600 +f 8493/8564/15612 8797/8565/15613 8495/8566/15614 +f 8826/8567/15615 8494/8568/15616 8595/8569/15617 +f 8441/8563/15611 8825/8570/15618 8735/8548/15596 +f 8576/8571/15619 8634/8532/15580 8541/8534/15582 +f 8561/8461/15509 8764/8572/15620 8765/8573/15621 +f 8447/8510/15558 8448/8574/15622 8446/8535/15583 +f 8434/8457/15505 8452/8491/15539 8433/8575/15623 +f 8566/8576/15624 8582/8502/15550 8588/8504/15552 +f 8720/8577/15625 8719/8578/15626 8490/8579/15627 +f 8686/8580/15628 8840/8581/15629 8688/8582/15630 +f 8795/8583/15631 8714/8524/15572 8713/8584/15632 +f 8551/8585/15633 8482/8498/15546 8434/8457/15505 +f 8478/8586/15634 8718/8559/15607 8473/8506/15554 +f 8595/8569/15617 8511/8587/15635 8760/8588/15636 +f 8567/8589/15637 8573/8590/15638 8596/8591/15639 +f 8507/8592/15640 8654/8543/15591 8741/8542/15590 +f 8535/8593/15641 8526/8594/15642 8592/8595/15643 +f 8682/8596/15644 8689/8525/15573 8487/8597/15645 +f 8822/8598/15646 8462/8599/15647 8802/8600/15648 +f 8440/8601/15649 8687/8602/15650 8684/8465/15513 +f 8778/8603/15651 8516/8552/15600 8763/8604/15652 +f 8684/8465/15513 8687/8602/15650 8686/8580/15628 +f 8719/8578/15626 8720/8577/15625 8699/8605/15653 +f 8799/8558/15606 8451/8606/15654 8584/8607/15655 +f 8699/8605/15653 8720/8577/15625 8721/8608/15656 +f 8580/8446/15494 8499/8609/15657 8581/8610/15658 +f 8616/8611/15659 8621/8612/15660 8624/8613/15661 +f 8725/8614/15662 8484/8615/15663 8604/8616/15664 +f 8770/8484/15532 8723/8617/15665 8771/8485/15533 +f 8683/8438/15486 8734/8618/15666 8815/8439/15487 +f 8524/8619/15667 8582/8502/15550 8566/8576/15624 +f 8637/8620/15668 8718/8559/15607 8478/8586/15634 +f 8702/8621/15669 8843/8622/15670 8707/8623/15671 +f 8494/8568/15616 8492/8537/15585 8486/8536/15584 +f 8739/8624/15672 8740/8625/15673 8453/8521/15569 +f 8612/8626/15674 8594/8627/15675 8615/8628/15676 +f 8478/8586/15634 8706/8629/15677 8608/8630/15678 +f 8832/8631/15679 8716/8632/15680 8462/8599/15647 +f 8630/8633/15681 8792/8476/15524 8553/8468/15516 +f 8740/8625/15673 8743/8634/15682 8453/8521/15569 +f 8510/8635/15683 8760/8588/15636 8511/8587/15635 +f 8555/8460/15508 8554/8636/15684 8558/8637/15685 +f 8693/8638/15686 8568/8639/15687 8569/8640/15688 +f 8433/8575/15623 8451/8606/15654 8788/8641/15689 +f 8756/8642/15690 8804/8643/15690 8757/8644/15690 +f 8637/8620/15668 8497/8645/15691 8718/8559/15607 +f 8614/8646/15692 8480/8472/15520 8654/8543/15591 +f 8787/8544/15592 8795/8583/15631 8534/8647/15693 +f 8581/8610/15658 8499/8609/15657 8594/8627/15675 +f 8683/8438/15486 8571/8440/15488 8715/8648/15694 +f 8499/8609/15657 8793/8649/15695 8610/8650/15696 +f 8749/8651/15697 8679/8652/15698 8680/8653/15699 +f 8547/8654/15700 8681/8655/15701 8546/8561/15609 +f 8641/8656/15702 8761/8527/15575 8471/8445/15493 +f 8534/8647/15693 8741/8542/15590 8787/8544/15592 +f 8789/8657/15703 8725/8614/15662 8788/8641/15689 +f 8664/8658/15704 8665/8659/15705 8656/8528/15576 +f 8550/8512/15560 8548/8560/15608 8504/8660/15706 +f 8663/8661/15707 8664/8658/15704 8656/8528/15576 +f 8741/8542/15590 8508/8662/15708 8507/8592/15640 +f 8525/8663/15709 8667/8664/15710 8657/8665/15711 +f 8615/8628/15676 8594/8627/15675 8617/8666/15712 +f 8673/8519/15567 8674/8667/15713 8671/8668/15714 +f 8628/8669/15715 8629/8670/15716 8553/8468/15516 +f 8464/8671/15717 8603/8672/15718 8597/8673/15719 +f 8587/8674/15720 8588/8504/15552 8591/8675/15721 +f 8627/8463/15511 8591/8675/15721 8505/8676/15722 +f 8590/8677/15723 8473/8506/15554 8602/8678/15724 +f 8543/8679/15725 8651/8680/15726 8652/8681/15727 +f 8665/8659/15705 8666/8682/15728 8656/8528/15576 +f 8662/8683/15729 8663/8661/15707 8656/8528/15576 +f 8800/8471/15519 8791/8684/15730 8795/8583/15631 +f 8795/8583/15631 8713/8584/15632 8534/8647/15693 +f 8548/8560/15608 8550/8512/15560 8555/8460/15508 +f 8720/8577/15625 8490/8579/15627 8489/8685/15731 +f 8720/8577/15625 8489/8685/15731 8601/8686/15732 +f 8450/8454/15502 8444/8453/15501 8449/8687/15733 +f 8735/8548/15596 8585/8547/15595 8586/8688/15734 +f 8558/8637/15685 8554/8636/15684 8458/8492/15540 +f 8621/8612/15660 8625/8689/15735 8624/8613/15661 +f 8625/8689/15735 8628/8669/15715 8626/8690/15736 +f 8726/8691/15737 8497/8645/15691 8498/8692/15738 +f 8748/8693/15739 8821/8694/15740 8704/8695/15741 +f 8836/8499/15547 8594/8627/15675 8612/8626/15674 +f 8791/8684/15730 8512/8696/15742 8511/8587/15635 +f 8673/8519/15567 8656/8528/15576 8674/8667/15713 +f 8442/8452/15500 8591/8675/15721 8439/8462/15510 +f 8598/8697/15743 8468/8450/15498 8600/8698/15744 +f 8457/8699/15745 8830/8700/15746 8458/8492/15540 +f 8658/8701/15747 8659/8702/15748 8656/8528/15576 +f 8499/8609/15657 8616/8611/15659 8618/8703/15749 +f 8746/8704/15750 8824/8477/15525 8736/8514/15562 +f 8599/8705/15751 8603/8672/15718 8464/8671/15717 +f 8540/8706/15752 8577/8707/15753 8541/8534/15582 +f 8491/8473/15521 8609/8708/15754 8604/8616/15664 +f 8500/8513/15561 8550/8512/15560 8551/8585/15633 +f 8441/8563/15611 8845/8709/15755 8829/8710/15756 +f 8523/8533/15581 8569/8640/15688 8606/8711/15757 +f 8695/8712/15758 8456/8713/15759 8566/8576/15624 +f 8537/8714/15760 8531/8715/15761 8686/8580/15628 +f 8536/8716/15762 8780/8717/15763 8537/8714/15760 +f 8526/8594/15642 8533/8718/15764 8737/8719/15765 +f 8561/8461/15509 8563/8720/15766 8565/8721/15767 +f 8618/8703/15749 8623/8722/15768 8499/8609/15657 +f 8485/8723/15769 8681/8655/15701 8683/8438/15486 +f 8798/8557/15605 8788/8641/15689 8451/8606/15654 +f 8556/8724/15770 8557/8725/15771 8553/8468/15516 +f 8552/8726/15772 8555/8460/15508 8556/8724/15770 +f 8643/8727/15773 8459/8496/15544 8607/8728/15774 +f 8715/8648/15694 8529/8729/15775 8528/8730/15776 +f 8560/8556/15604 8764/8572/15620 8561/8461/15509 +f 8837/8437/15485 8833/8731/15777 8470/8435/15483 +f 8794/8732/15778 8709/8733/15779 8655/8489/15537 +f 8553/8468/15516 8552/8726/15772 8556/8724/15770 +f 8760/8588/15636 8510/8635/15683 8826/8567/15615 +f 8475/8734/15780 8584/8607/15655 8452/8491/15539 +f 8462/8599/15647 8803/8735/15781 8806/8736/15782 +f 8770/8484/15532 8722/8737/15783 8723/8617/15665 +f 8638/8738/15784 8639/8739/15785 8507/8592/15640 +f 8434/8457/15505 8805/8456/15504 8794/8732/15778 +f 8690/8740/15786 8685/8741/15787 8684/8465/15513 +f 8782/8742/15788 8817/8743/15789 8450/8454/15502 +f 8472/8744/15790 8748/8693/15739 8767/8745/15791 +f 8649/8746/15792 8650/8747/15793 8633/8748/15794 +f 8650/8747/15793 8600/8698/15744 8636/8749/15795 +f 8437/8464/15512 8721/8608/15656 8601/8686/15732 +f 8720/8577/15625 8601/8686/15732 8721/8608/15656 +f 8657/8665/15711 8658/8701/15747 8656/8528/15576 +f 8668/8750/15796 8525/8663/15709 8657/8665/15711 +f 8485/8723/15769 8546/8561/15609 8681/8655/15701 +f 8750/8751/15797 8694/8752/15798 8722/8737/15783 +f 8491/8473/15521 8604/8616/15664 8484/8615/15663 +f 8755/8753/15799 8757/8644/15800 8449/8687/15733 +f 8464/8671/15717 8468/8450/15498 8598/8697/15743 +f 8617/8666/15712 8499/8609/15657 8623/8722/15768 +f 8675/8754/15801 8672/8755/15802 8671/8668/15714 +f 8480/8472/15520 8614/8646/15692 8692/8442/15490 +f 8712/8756/15803 8569/8640/15688 8698/8757/15804 +f 8697/8758/15805 8738/8481/15529 8816/8759/15806 +f 8698/8757/15804 8569/8640/15688 8738/8481/15529 +f 8733/8470/15518 8644/8760/15807 8734/8618/15666 +f 8656/8528/15576 8813/8761/15808 8699/8605/15653 +f 8499/8609/15657 8610/8650/15696 8611/8762/15809 +f 8686/8580/15628 8688/8582/15630 8684/8465/15513 +f 8506/8763/15810 8627/8463/15511 8505/8676/15722 +f 8771/8485/15533 8774/8764/15811 8773/8765/15812 +f 8573/8590/15813 8572/8766/15814 8596/8591/15815 +f 8472/8744/15790 8767/8745/15791 8635/8767/15816 +f 8546/8561/15609 8485/8723/15769 8486/8536/15584 +f 8553/8468/15516 8547/8654/15700 8552/8726/15772 +f 8465/8768/15817 8809/8769/15818 8805/8456/15504 +f 8590/8677/15723 8589/8770/15819 8478/8586/15634 +f 8478/8586/15634 8589/8770/15819 8706/8629/15677 +f 8567/8589/15637 8667/8664/15710 8525/8663/15709 +f 8636/8749/15795 8632/8771/15820 8650/8747/15793 +f 8459/8496/15544 8608/8630/15678 8607/8728/15774 +f 8751/8772/15821 8680/8653/15699 8694/8752/15798 +f 8629/8670/15716 8630/8633/15681 8553/8468/15516 +f 8548/8560/15608 8486/8536/15584 8504/8660/15706 +f 8566/8576/15624 8573/8590/15638 8567/8589/15637 +f 8636/8749/15795 8468/8450/15498 8578/8773/15822 +f 8611/8762/15809 8619/8774/15823 8616/8611/15659 +f 8784/8775/15824 8776/8776/15825 8569/8640/15688 +f 8600/8698/15744 8468/8450/15498 8636/8749/15795 +f 8482/8498/15546 8550/8512/15560 8504/8660/15706 +f 8683/8438/15486 8682/8596/15644 8485/8723/15769 +f 8756/8642/15826 8757/8644/15800 8755/8753/15799 +f 8593/8777/15827 8742/8778/15828 8695/8712/15758 +f 8583/8503/15551 8582/8502/15829 8505/8676/15722 +f 8620/8436/15484 8808/8520/15568 8837/8437/15485 +f 8555/8460/15508 8502/8511/15559 8554/8636/15684 +f 8524/8619/15667 8668/8750/15796 8505/8676/15722 +f 8691/8482/15530 8543/8679/15725 8738/8481/15529 +f 8627/8463/15511 8721/8608/15656 8437/8464/15512 +f 8485/8723/15769 8682/8596/15644 8487/8597/15645 +f 8617/8666/15712 8594/8627/15675 8499/8609/15657 +f 8583/8503/15551 8505/8676/15722 8591/8675/15721 +f 8587/8674/15830 8591/8675/15830 8442/8452/15830 +f 8656/8528/15576 8668/8750/15796 8657/8665/15711 +f 8672/8755/15802 8673/8519/15567 8671/8668/15714 +f 8538/8553/15601 8455/8779/15831 8593/8777/15827 +f 8593/8777/15827 8455/8779/15831 8742/8778/15828 +f 8717/8780/15832 8799/8558/15606 8584/8607/15655 +f 8520/8531/15579 8675/8754/15801 8676/8781/15833 +f 8687/8602/15650 8537/8714/15760 8686/8580/15628 +f 8750/8751/15797 8751/8772/15821 8694/8752/15798 +f 8830/8700/15746 8839/8782/15834 8458/8492/15540 +f 8650/8747/15793 8632/8771/15820 8633/8748/15794 +f 8670/8783/15835 8696/8784/15836 8667/8664/15710 +f 8456/8713/15837 8455/8779/15837 8572/8766/15837 +f 8538/8553/15838 8572/8766/15838 8455/8779/15838 +f 8682/8596/15644 8715/8648/15694 8528/8730/15776 +f 8596/8591/15839 8670/8783/15835 8667/8664/15710 +f 8596/8591/15840 8667/8664/15840 8567/8589/15840 +f 8619/8774/15823 8621/8612/15660 8616/8611/15659 +f 8715/8648/15694 8571/8440/15488 8529/8729/15775 +f 8787/8544/15592 8480/8472/15520 8800/8471/15519 +f 8497/8645/15691 8789/8657/15703 8798/8557/15605 +f 8780/8717/15763 8622/8785/15841 8534/8647/15693 +f 8593/8777/15827 8753/8786/15842 8703/8455/15503 +f 8659/8702/15748 8660/8787/15843 8656/8528/15576 +f 8673/8519/15567 8672/8755/15802 8834/8788/15844 +f 8815/8439/15487 8734/8618/15666 8462/8599/15647 +f 8507/8592/15640 8639/8739/15785 8653/8789/15845 +f 8533/8718/15764 8713/8584/15632 8737/8719/15765 +f 8503/8538/15586 8466/8790/15846 8504/8660/15706 +f 8481/8486/15534 8754/8791/15847 8755/8753/15799 +f 8725/8614/15662 8604/8616/15664 8501/8792/15848 +f 8466/8790/15846 8503/8538/15586 8465/8768/15817 +f 8734/8618/15666 8553/8468/15516 8733/8470/15518 +f 8534/8647/15693 8713/8584/15632 8533/8718/15764 +f 8743/8634/15682 8707/8623/15671 8453/8521/15569 +f 8736/8514/15562 8728/8516/15564 8746/8704/15750 +f 8438/8474/15522 8439/8462/15510 8437/8464/15512 +f 8473/8506/15554 8718/8559/15607 8717/8780/15832 +f 8724/8526/15574 8682/8596/15644 8528/8730/15776 +f 8714/8524/15572 8724/8526/15574 8737/8719/15765 +f 8806/8736/15782 8793/8649/15695 8499/8609/15657 +f 8691/8482/15530 8463/8480/15528 8597/8673/15719 +f 8798/8557/15605 8789/8657/15703 8788/8641/15689 +f 8448/8574/15622 8436/8488/15536 8446/8535/15583 +f 8718/8559/15607 8799/8558/15606 8717/8780/15832 +f 8719/8578/15626 8641/8656/15702 8736/8514/15562 +f 8459/8496/15544 8637/8620/15668 8478/8586/15634 +f 8660/8787/15843 8661/8793/15849 8656/8528/15576 +f 8528/8730/15776 8527/8794/15850 8724/8526/15574 +f 8532/8795/15851 8535/8593/15641 8592/8595/15643 +f 8504/8660/15706 8486/8536/15584 8503/8538/15586 +f 8783/8796/15852 8786/8550/15598 8516/8552/15600 +f 8774/8764/15811 8771/8485/15533 8544/8797/15853 +f 8510/8635/15683 8797/8565/15613 8826/8567/15615 +f 8669/8798/15854 8572/8766/15855 8785/8799/15856 +f 8580/8446/15494 8461/8448/15496 8499/8609/15657 +f 8470/8435/15483 8472/8744/15790 8469/8444/15492 +f 8730/8800/15857 8758/8801/15858 8545/8802/15859 +f 8484/8615/15663 8498/8692/15738 8483/8509/15557 +f 8738/8481/15529 8569/8640/15688 8477/8447/15495 +f 8805/8456/15504 8466/8790/15846 8465/8768/15817 +f 8597/8673/15719 8603/8672/15718 8678/8803/15860 +f 8729/8804/15861 8545/8802/15859 8450/8454/15502 +f 8796/8479/15527 8609/8708/15754 8490/8579/15627 +f 8592/8595/15643 8570/8805/15862 8634/8532/15580 +f 8499/8609/15657 8461/8448/15496 8462/8599/15647 +f 8489/8685/15731 8490/8579/15627 8488/8475/15523 +f 8635/8767/15816 8579/8806/15863 8468/8450/15498 +f 8841/8530/15578 8675/8754/15801 8520/8531/15579 +f 8508/8662/15708 8741/8542/15590 8622/8785/15841 +f 8531/8715/15761 8534/8647/15693 8533/8718/15764 +f 8802/8600/15648 8462/8599/15647 8644/8760/15807 +f 8522/8807/15864 8541/8534/15582 8523/8533/15581 +f 8583/8503/15551 8591/8675/15721 8588/8504/15552 +f 8653/8789/15845 8613/8808/15865 8614/8646/15692 +f 8795/8583/15631 8787/8544/15592 8800/8471/15519 +f 8556/8724/15770 8555/8460/15508 8559/8809/15866 +f 8594/8627/15675 8836/8499/15547 8818/8515/15563 +f 8445/8508/15556 8447/8510/15558 8446/8535/15583 +f 8800/8471/15519 8479/8441/15489 8512/8696/15742 +f 8465/8768/15817 8495/8566/15614 8809/8769/15818 +f 8437/8464/15512 8488/8475/15523 8438/8474/15522 +f 8761/8527/15575 8813/8761/15808 8656/8528/15576 +f 8500/8513/15561 8551/8585/15633 8434/8457/15505 +f 8496/8810/15867 8435/8811/15868 8436/8488/15536 +f 8541/8534/15582 8542/8812/15869 8540/8706/15752 +f 8594/8627/15675 8641/8656/15702 8471/8445/15493 +f 8433/8575/15623 8452/8491/15539 8451/8606/15654 +f 8727/8813/15870 8728/8516/15564 8818/8515/15563 +f 8441/8563/15611 8440/8601/15649 8516/8552/15600 +f 8689/8525/15573 8791/8684/15730 8511/8587/15635 +f 8649/8746/15792 8633/8748/15794 8679/8652/15698 +f 8823/8478/15526 8458/8492/15540 8796/8479/15527 +f 8682/8596/15644 8724/8526/15574 8689/8525/15573 +f 8789/8657/15703 8726/8691/15737 8725/8614/15662 +f 8445/8508/15556 8446/8535/15583 8444/8453/15501 +f 8486/8536/15584 8487/8597/15645 8494/8568/15616 +f 8523/8533/15581 8461/8448/15496 8477/8447/15495 +f 8525/8663/15709 8668/8750/15796 8524/8619/15667 +f 8472/8744/15790 8468/8450/15498 8469/8444/15492 +f 8475/8734/15780 8476/8507/15555 8473/8506/15554 +f 8754/8791/15847 8756/8642/15826 8755/8753/15799 +f 8791/8684/15730 8714/8524/15572 8795/8583/15631 +f 8817/8743/15789 8729/8804/15861 8450/8454/15502 +f 8468/8450/15498 8472/8744/15790 8635/8767/15816 +f 8626/8690/15736 8628/8669/15715 8553/8468/15516 +f 8595/8569/15617 8487/8597/15645 8689/8525/15573 +f 8506/8763/15810 8699/8605/15653 8721/8608/15656 +f 8462/8599/15647 8734/8618/15666 8644/8760/15807 +f 8753/8786/15842 8593/8777/15827 8695/8712/15758 +f 8748/8693/15739 8701/8814/15871 8702/8621/15669 +f 8776/8776/15825 8777/8815/15872 8642/8816/15873 +f 8536/8716/15762 8508/8662/15708 8622/8785/15841 +f 8466/8790/15846 8482/8498/15546 8504/8660/15706 +f 8472/8744/15790 8833/8731/15777 8821/8694/15740 +f 8516/8552/15600 8440/8601/15649 8763/8604/15652 +f 8484/8615/15663 8483/8509/15557 8491/8473/15521 +f 8486/8536/15584 8485/8723/15769 8487/8597/15645 +f 8539/8817/15874 8572/8766/15855 8538/8553/15601 +f 8579/8806/15863 8578/8773/15822 8468/8450/15498 +f 8488/8475/15523 8601/8686/15732 8489/8685/15731 +f 8465/8768/15817 8492/8537/15585 8493/8564/15612 +f 8497/8645/15691 8435/8811/15868 8496/8810/15867 +f 8498/8692/15738 8497/8645/15691 8496/8810/15867 +f 8707/8623/15671 8748/8693/15739 8702/8621/15669 +f 8735/8548/15596 8508/8662/15708 8441/8563/15611 +f 8465/8768/15817 8503/8538/15586 8492/8537/15585 +f 8599/8705/15751 8464/8671/15717 8598/8697/15743 +f 8571/8440/15488 8815/8439/15487 8462/8599/15647 +f 8477/8447/15495 8580/8446/15494 8463/8480/15528 +f 8456/8713/15759 8573/8590/15638 8566/8576/15624 +f 8435/8811/15868 8637/8620/15668 8436/8488/15536 +f 8637/8620/15668 8435/8811/15868 8497/8645/15691 +f 8438/8474/15522 8445/8508/15556 8439/8462/15510 +f 8634/8532/15580 8570/8805/15862 8523/8533/15581 +f 8641/8656/15702 8719/8578/15626 8813/8761/15808 +f 8780/8717/15763 8536/8716/15762 8622/8785/15841 +f 8558/8637/15685 8560/8556/15604 8555/8460/15508 +f 8445/8508/15556 8438/8474/15522 8483/8509/15557 +f 8543/8679/15725 8646/8818/15875 8651/8680/15726 +f 8449/8687/15733 8782/8742/15788 8450/8454/15502 +f 8673/8519/15567 8834/8788/15844 8808/8520/15568 +f 8460/8819/15876 8481/8486/15534 8436/8488/15536 +f 8511/8587/15635 8595/8569/15617 8689/8525/15573 +f 8602/8678/15724 8473/8506/15554 8474/8505/15553 +f 8471/8445/15493 8620/8436/15484 8470/8435/15483 +f 8669/8798/15854 8596/8591/15839 8572/8766/15855 +f 8500/8513/15561 8433/8575/15623 8501/8792/15848 +f 8514/8820/15877 8515/8562/15610 8513/8821/15878 +f 8506/8763/15810 8505/8676/15722 8668/8750/15796 +f 8788/8641/15689 8725/8614/15662 8501/8792/15848 +f 8597/8673/15719 8678/8803/15860 8645/8822/15879 +f 8446/8535/15583 8449/8687/15733 8444/8453/15501 +f 8624/8613/15661 8625/8689/15735 8626/8690/15736 +f 8661/8793/15849 8662/8683/15729 8656/8528/15576 +f 8481/8486/15534 8755/8753/15799 8831/8487/15535 +f 8456/8713/15759 8695/8712/15758 8742/8778/15828 +f 8814/8555/15603 8811/8823/15880 8520/8531/15579 +f 8490/8579/15627 8609/8708/15754 8491/8473/15521 +f 8512/8696/15742 8479/8441/15489 8510/8635/15683 +f 8519/8824/15881 8819/8825/15882 8514/8820/15877 +f 8499/8609/15657 8611/8762/15809 8616/8611/15659 +f 8641/8656/15702 8594/8627/15675 8818/8515/15563 +f 8473/8506/15554 8590/8677/15723 8478/8586/15634 +f 8528/8730/15776 8529/8729/15775 8526/8594/15642 +f 8778/8603/15651 8783/8796/15852 8516/8552/15600 +f 8820/8826/15883 8759/8827/15884 8516/8552/15600 +f 8573/8590/15813 8456/8713/15885 8572/8766/15814 +f 8491/8473/15521 8488/8475/15523 8490/8579/15627 +f 8588/8504/15552 8695/8712/15758 8566/8576/15624 +f 8526/8594/15642 8737/8719/15765 8527/8794/15850 +f 8749/8651/15697 8649/8746/15792 8679/8652/15698 +f 8487/8597/15645 8595/8569/15617 8494/8568/15616 +f 8561/8461/15509 8562/8518/15566 8563/8720/15766 +f 8836/8499/15547 8835/8517/15565 8766/8539/15587 +f 8752/8541/15589 8818/8515/15563 8836/8499/15547 +f 8766/8539/15587 8835/8517/15565 8765/8573/15621 +f 8818/8515/15563 8736/8514/15562 8641/8656/15702 +f 8752/8541/15589 8727/8813/15870 8818/8515/15563 +f 8835/8517/15565 8561/8461/15509 8765/8573/15621 +f 8796/8479/15527 8736/8514/15562 8824/8477/15525 +f 8604/8616/15664 8609/8708/15754 8605/8828/15886 +f 8594/8627/15675 8469/8444/15492 8467/8449/15497 +f 8710/8829/15887 8763/8604/15652 8440/8601/15649 +f 8547/8654/15700 8553/8468/15516 8734/8618/15666 +f 8647/8830/15888 8648/8831/15889 8516/8552/15600 +f 8667/8664/15710 8696/8784/15836 8657/8665/15711 +f 8681/8655/15701 8547/8654/15700 8734/8618/15666 +f 8676/8781/15833 8675/8754/15801 8671/8668/15714 +f 8674/8667/15713 8656/8528/15576 8677/8832/15890 +f 8532/8795/15851 8531/8715/15761 8535/8593/15641 +f 8546/8561/15609 8548/8560/15608 8547/8654/15700 +f 8533/8718/15764 8535/8593/15641 8531/8715/15761 +f 8543/8679/15725 8816/8759/15806 8738/8481/15529 +f 8595/8569/15617 8760/8588/15636 8826/8567/15615 +f 8436/8488/15536 8448/8574/15622 8496/8810/15867 +f 8726/8691/15737 8789/8657/15703 8497/8645/15691 +f 8751/8772/15821 8749/8651/15697 8680/8653/15699 +f 8554/8636/15684 8502/8511/15559 8501/8792/15848 +f 8776/8776/15825 8606/8711/15757 8569/8640/15688 +f 8557/8725/15771 8640/8833/15891 8553/8468/15516 +f 8466/8790/15846 8781/8458/15506 8482/8498/15546 +f 8523/8533/15581 8477/8447/15495 8569/8640/15688 +f 8577/8707/15753 8576/8571/15619 8541/8534/15582 +f 8652/8681/15727 8544/8797/15853 8543/8679/15725 +f 8609/8708/15754 8796/8479/15527 8605/8828/15886 +f 8463/8480/15528 8691/8482/15530 8477/8447/15495 +f 8527/8794/15850 8528/8730/15776 8526/8594/15642 +f 8539/8817/15874 8538/8553/15601 8574/8546/15594 +f 8777/8815/15872 8842/8834/15892 8642/8816/15873 +f 8442/8452/15500 8445/8508/15556 8444/8453/15501 +f 8535/8593/15641 8533/8718/15764 8526/8594/15642 +f 8810/8835/15893 8453/8521/15569 8844/8836/15894 +f 8501/8792/15848 8605/8828/15886 8554/8636/15684 +f 8825/8570/15618 8700/8549/15597 8735/8548/15596 +f 8683/8438/15486 8715/8648/15694 8682/8596/15644 +f 8686/8580/15628 8531/8715/15761 8532/8795/15851 +f 8714/8524/15572 8791/8684/15730 8689/8525/15573 +f 8748/8693/15739 8472/8744/15790 8821/8694/15740 +f 8719/8578/15626 8796/8479/15527 8490/8579/15627 +f 8588/8504/15552 8587/8674/15720 8442/8452/15500 +f 8471/8445/15493 8469/8444/15492 8594/8627/15675 +f 8441/8563/15611 8536/8716/15762 8440/8601/15649 +f 8548/8560/15608 8552/8726/15772 8547/8654/15700 +f 8441/8563/15611 8515/8562/15610 8845/8709/15755 +f 8464/8671/15717 8467/8449/15497 8468/8450/15498 +f 8762/8837/15895 8750/8751/15797 8722/8737/15783 +f 8757/8644/15800 8807/8838/15896 8449/8687/15733 +f 8482/8498/15546 8551/8585/15633 8550/8512/15560 +f 8561/8461/15509 8565/8721/15767 8564/8459/15507 +f 8529/8729/15775 8571/8440/15488 8570/8805/15862 +f 8566/8576/15624 8567/8589/15637 8524/8619/15667 +f 8568/8639/15687 8784/8775/15824 8569/8640/15688 +f 8840/8581/15629 8686/8580/15628 8634/8532/15580 +f 8695/8712/15758 8588/8504/15552 8753/8786/15842 +f 8637/8620/15668 8459/8496/15544 8436/8488/15536 +f 8461/8448/15496 8523/8533/15581 8570/8805/15862 +f 8509/8443/15491 8510/8635/15683 8479/8441/15489 +f 8524/8619/15667 8567/8589/15637 8525/8663/15709 +f 8782/8742/15788 8790/8839/15897 8817/8743/15789 +f 8537/8714/15760 8780/8717/15763 8531/8715/15761 +f 8452/8491/15539 8434/8457/15505 8655/8489/15537 +f 8582/8502/15550 8524/8619/15667 8505/8676/15898 +f 8513/8821/15878 8515/8562/15610 8516/8552/15600 +f 8683/8438/15486 8681/8655/15701 8734/8618/15666 +f 8738/8481/15529 8697/8758/15805 8698/8757/15804 +f 8501/8792/15848 8433/8575/15623 8788/8641/15689 +f 8458/8492/15540 8823/8478/15526 8530/8493/15541 +f 8575/8545/15593 8549/8840/15899 8574/8546/15594 +f 8838/8841/15900 8828/8842/15901 8436/8488/15536 +f 8653/8789/15845 8614/8646/15692 8654/8543/15591 +f 8529/8729/15775 8592/8595/15643 8526/8594/15642 +f 8711/8467/15515 8710/8829/15887 8440/8601/15649 +f 8685/8741/15787 8705/8466/15514 8684/8465/15513 +f 8541/8534/15582 8522/8807/15864 8542/8812/15869 +f 8594/8627/15675 8467/8449/15497 8581/8610/15658 +f 8771/8485/15533 8723/8617/15665 8453/8521/15569 +f 8437/8464/15512 8601/8686/15732 8488/8475/15523 +f 8737/8719/15765 8713/8584/15632 8714/8524/15572 +f 8456/8713/15902 8742/8778/15902 8455/8779/15902 +f 8692/8442/15490 8479/8441/15489 8480/8472/15520 +f 8440/8601/15649 8536/8716/15762 8537/8714/15760 +f 8605/8828/15886 8501/8792/15848 8604/8616/15664 +f 8550/8512/15560 8502/8511/15559 8555/8460/15508 +f 8686/8580/15628 8532/8795/15851 8634/8532/15580 +f 8631/8843/15903 8626/8690/15736 8553/8468/15516 +f 8498/8692/15738 8484/8615/15663 8726/8691/15737 +f 8463/8480/15528 8467/8449/15497 8464/8671/15717 +f 8829/8710/15756 8825/8570/15618 8441/8563/15611 +f 8827/8844/15904 8475/8734/15780 8452/8491/15539 +f 8580/8446/15494 8581/8610/15658 8467/8449/15497 +f 8810/8835/15893 8454/8554/15602 8453/8521/15569 +f 8518/8845/15905 8519/8824/15881 8514/8820/15877 +f 8753/8786/15842 8588/8504/15552 8442/8452/15500 +f 8480/8472/15520 8787/8544/15592 8654/8543/15591 +f 8590/8677/15723 8602/8678/15724 8589/8770/15819 +f 8627/8463/15511 8439/8462/15510 8591/8675/15721 +f 8666/8682/15728 8677/8832/15890 8656/8528/15576 +f 8716/8632/15680 8803/8735/15781 8462/8599/15647 +f 8520/8531/15579 8453/8521/15569 8454/8554/15602 +f 8452/8491/15539 8584/8607/15655 8451/8606/15654 +f 8688/8582/15630 8690/8740/15786 8684/8465/15513 +f 8512/8696/15742 8510/8635/15683 8511/8587/15635 +f 8458/8492/15540 8605/8828/15886 8796/8479/15527 +f 8799/8558/15606 8798/8557/15605 8451/8606/15654 +f 8543/8679/15725 8597/8673/15719 8646/8818/15875 +f 8433/8575/15623 8500/8513/15561 8434/8457/15505 +f 8699/8605/15653 8506/8763/15810 8668/8750/15796 +f 8729/8804/15861 8730/8800/15857 8545/8802/15859 +f 8606/8711/15757 8522/8807/15864 8523/8533/15581 +f 8673/8519/15567 8620/8436/15484 8761/8527/15575 +f 8491/8473/15521 8483/8509/15557 8438/8474/15522 +f 8494/8568/15616 8826/8567/15615 8493/8564/15612 +f 8440/8601/15649 8684/8465/15513 8711/8467/15515 +f 8517/8846/15906 8518/8845/15905 8514/8820/15877 +f 8638/8738/15784 8507/8592/15640 8508/8662/15708 +f 8559/8809/15866 8555/8460/15508 8564/8459/15507 +f 8608/8630/15678 8459/8496/15544 8478/8586/15634 +f 8627/8463/15511 8506/8763/15810 8721/8608/15656 +f 8553/8468/15516 8640/8833/15891 8631/8843/15903 +f 8699/8605/15653 8813/8761/15808 8719/8578/15626 +f 8770/8484/15532 8762/8837/15895 8722/8737/15783 +f 8634/8532/15580 8532/8795/15851 8592/8595/15643 +f 8596/8591/15839 8669/8798/15854 8670/8783/15835 +f 8606/8711/15757 8776/8776/15825 8642/8816/15873 +f 8495/8566/15614 8465/8768/15817 8493/8564/15612 +f 8724/8526/15574 8527/8794/15850 8737/8719/15765 +f 8508/8662/15708 8536/8716/15762 8441/8563/15611 +f 8447/8510/15558 8496/8810/15867 8448/8574/15622 +f 8725/8614/15662 8726/8691/15737 8484/8615/15663 +f 8753/8786/15842 8443/8451/15499 8703/8455/15503 +f 8605/8828/15886 8458/8492/15540 8554/8636/15684 +f 8597/8673/15719 8543/8679/15725 8691/8482/15530 +f 8785/8799/15856 8572/8766/15855 8539/8817/15874 +f 8718/8559/15607 8497/8645/15691 8798/8557/15605 +f 8447/8510/15558 8483/8509/15557 8498/8692/15738 +f 8620/8436/15484 8471/8445/15493 8761/8527/15575 +f 8811/8823/15880 8521/8529/15577 8520/8531/15579 +f 8449/8687/15733 8831/8487/15535 8755/8753/15799 +f 8569/8640/15688 8712/8756/15803 8693/8638/15686 +f 8703/8455/15503 8450/8454/15502 8575/8545/15593 +f 8464/8671/15717 8597/8673/15719 8463/8480/15528 +f 8473/8506/15554 8717/8780/15832 8475/8734/15780 +f 8446/8535/15583 8831/8487/15535 8449/8687/15733 +f 8538/8553/15601 8593/8777/15827 8703/8455/15503 +f 8508/8662/15708 8735/8548/15596 8638/8738/15784 +f 8717/8780/15832 8584/8607/15655 8475/8734/15780 +f 8708/8847/15907 8709/8733/15779 8794/8732/15778 +f 8732/8523/15571 8739/8624/15672 8453/8521/15569 +f 8552/8726/15772 8548/8560/15608 8555/8460/15508 +f 8779/8490/15538 8827/8844/15904 8452/8491/15539 +f 8592/8595/15643 8529/8729/15775 8570/8805/15862 +f 8654/8543/15591 8507/8592/15640 8653/8789/15845 +f 8613/8808/15865 8692/8442/15490 8614/8646/15692 +f 8462/8599/15647 8822/8598/15646 8832/8631/15679 +f 8723/8617/15665 8731/8522/15570 8453/8521/15569 +f 8773/8765/15812 8772/8483/15531 8771/8485/15533 +f 8827/8844/15904 8476/8507/15555 8475/8734/15780 +f 8459/8496/15544 8643/8727/15773 8769/8497/15545 +f 8668/8750/15796 8656/8528/15576 8699/8605/15653 +f 8805/8456/15504 8708/8847/15907 8794/8732/15778 +f 8828/8842/15901 8460/8819/15876 8436/8488/15536 +f 8796/8479/15527 8719/8578/15626 8736/8514/15562 +f 8576/8571/15619 8840/8581/15629 8634/8532/15580 +f 8445/8508/15556 8442/8452/15500 8439/8462/15510 +f 8545/8802/15859 8549/8840/15899 8450/8454/15502 +f 8499/8609/15657 8462/8599/15647 8806/8736/15782 +f 8768/8495/15543 8838/8841/15900 8436/8488/15536 +f 8641/8656/15702 8813/8761/15808 8761/8527/15575 +f 8492/8537/15585 8494/8568/15616 8493/8564/15612 +f 8496/8810/15867 8447/8510/15558 8498/8692/15738 +f 8800/8471/15519 8512/8696/15742 8791/8684/15730 +f 8501/8792/15848 8502/8511/15559 8500/8513/15561 +f 8638/8738/15784 8735/8548/15596 8586/8688/15734 +f 8472/8744/15790 8470/8435/15483 8833/8731/15777 +f 8571/8440/15488 8461/8448/15496 8570/8805/15862 +f 8843/8622/15670 8844/8836/15894 8707/8623/15671 +f 8759/8827/15884 8647/8830/15888 8516/8552/15600 +f 8687/8602/15650 8440/8601/15649 8537/8714/15760 +f 8534/8647/15693 8531/8715/15761 8780/8717/15763 +f 8748/8693/15739 8704/8695/15741 8701/8814/15871 +f 8443/8451/15499 8753/8786/15842 8442/8452/15500 +f 8516/8552/15600 8812/8551/15599 8820/8826/15883 +f 8597/8673/15719 8645/8822/15879 8646/8818/15875 +f 8453/8521/15569 8707/8623/15671 8844/8836/15894 +f 8781/8458/15506 8466/8790/15846 8805/8456/15504 +f 8513/8821/15878 8517/8846/15906 8514/8820/15877 +f 8839/8782/15834 8558/8637/15685 8458/8492/15540 +f 8622/8785/15841 8741/8542/15590 8534/8647/15693 +f 8836/8499/15547 8744/8501/15549 8745/8540/15588 +f 8449/8687/15733 8807/8838/15896 8782/8742/15788 +f 8461/8448/15496 8571/8440/15488 8462/8599/15647 +f 8549/8840/15899 8575/8545/15593 8450/8454/15502 +f 8794/8732/15778 8655/8489/15537 8434/8457/15505 +f 8771/8485/15533 8543/8679/15725 8544/8797/15853 +f 8458/8492/15540 8775/8494/15542 8457/8699/15745 +f 8797/8565/15613 8493/8564/15612 8826/8567/15615 +f 8648/8831/15889 8513/8821/15878 8516/8552/15600 +f 7149/7709/15908 8585/8547/15909 8700/8549/15910 7071/7710/15911 +f 7171/7897/15912 8643/8727/15913 8607/8728/15914 7172/7898/15915 +f 7096/7876/15916 8540/8706/15917 8542/8812/15918 7095/7984/15919 +f 7198/7829/15920 8665/8659/15921 8664/8658/15922 7199/7828/14741 +f 7240/7865/14782 8821/8694/15923 8833/8731/15924 7238/7901/14825 +f 6011/6309/15925 8172/8134/15926 8173/8275/15927 6012/6913/15928 +f 5980/5907/15929 8151/8046/15930 8146/8396/15931 5981/7381/15932 +f 6017/5820/15933 8279/8030/15934 8096/8029/15935 6018/5821/15936 +f 6013/7080/15937 8225/8325/15937 8226/8326/15938 6014/7081/15939 +f 6149/7329/15940 8317/8387/15941 8345/8389/15942 6150/7330/15943 +f 7077/7772/15944 8763/8604/15944 8710/8829/15945 7086/8002/15946 +f 5949/6419/15947 8163/8158/15948 8427/8169/15949 5950/6468/15950 +f 5897/7397/15951 8314/8400/15952 8315/8102/15953 5898/6172/15954 +f 7086/8002/15946 8710/8829/15945 8711/8467/15955 7081/7621/15956 +f 6043/6769/15957 8343/8229/15958 8391/8231/15959 6044/6770/15959 +f 6148/7339/15960 8316/8391/15961 8317/8387/15941 6149/7329/15940 +f 7244/7683/15962 8731/8522/15570 8723/8617/15665 7270/7785/15963 +f 7191/8014/15964 8549/8840/15965 8545/8802/15966 7189/7973/15967 +f 7073/7714/15968 8812/8551/15969 8786/8550/15970 7080/7712/15971 +f 7227/7691/15972 8841/8530/15972 8521/8529/15577 7226/7689/15973 +f 5963/7198/15974 8363/8363/15975 8364/8403/15976 5964/7435/15977 +f 5939/6597/15978 8350/8191/15978 8365/8190/15979 5940/6596/15980 +f 7233/7959/14918 8834/8788/15981 8672/8755/15982 7229/7926/15983 +f 6027/6065/15984 8242/8076/15985 8366/8078/15986 6026/6066/15987 +f 7280/7991/15988 8646/8818/15988 8645/8822/15989 7279/7995/15013 +f 7245/7682/15990 8732/8523/15571 8731/8522/15570 7244/7683/15962 +f 5938/7495/15991 8346/8414/15992 8234/8417/15993 5937/7510/15994 +f 7234/7679/14533 8808/8520/15995 8834/8788/15981 7233/7959/14918 +f 7100/7946/15996 8784/8775/15997 8568/8639/15998 7099/7808/15999 +f 7181/7810/16000 8756/8642/16001 8754/8791/16002 7185/7962/16003 +f 6018/5821/15936 8096/8029/15935 8097/8222/16004 6019/6743/16005 +f 5953/7436/16006 8229/8402/16007 8193/8298/16008 5954/7009/16009 +f 7085/7622/16010 8705/8466/16011 8685/8741/16012 7083/7912/16013 +f 7019/7840/16014 8629/8670/16015 8628/8669/16016 7018/7839/16017 +f 7243/7789/16018 8702/8621/16018 8701/8814/16019 7242/7987/16020 +f 7180/7642/16021 8481/8486/16022 8460/8819/16023 7176/7992/16024 +f 5933/6311/16025 8287/8135/16026 8172/8134/15926 6011/6309/15925 +f 6034/7044/16027 8194/8315/16028 8230/8314/16029 6033/7043/16030 +f 5957/7394/16031 8129/8399/16032 8127/8293/16033 5958/6993/16034 +f 7083/7912/16013 8685/8741/16012 8690/8740/16035 7082/7911/16036 +f 7140/8004/16037 8648/8831/16038 8647/8830/16039 7075/8003/16040 +f 6061/6845/13421 8251/8245/16041 8252/8246/16042 6060/6846/16043 +f 6100/7054/13647 8420/8318/16044 8408/8282/16045 6102/6934/13522 +f 7208/7837/14751 8671/8668/16046 8674/8667/16047 7209/7838/14752 +f 7271/7919/14845 8650/8747/16048 8649/8746/16049 7264/7917/14843 +f 5948/7508/16050 8297/8416/16051 8350/8191/15978 5939/6597/15978 +f 6067/6963/13547 8246/8289/16052 8247/8374/16053 6065/7251/13881 +f 5943/5918/16054 8298/8053/16055 8297/8416/16051 5948/7508/16050 +f 7206/7690/14545 8520/8531/16056 8676/8781/16057 7207/7952/14900 +f 7228/7925/16058 8675/8754/16058 8841/8530/16058 7227/7691/16058 +f 6132/6635/16059 8310/8204/15240 8318/8110/15146 6106/6194/16060 +f 6051/7331/16061 8132/8388/16062 8136/8427/16063 6053/7552/16064 +f 7034/7702/16065 8752/8541/16066 8745/8540/16067 7033/7701/16068 +f 5875/7161/16069 8198/8349/16070 8206/8361/16071 5876/7194/16072 +f 6088/6215/16073 8108/8116/15152 8428/8118/16074 6089/6216/16074 +f 7282/7850/16075 8652/8681/15727 8651/8680/16076 7281/7851/16076 +f 6066/6962/13546 8245/8288/16077 8246/8289/16052 6067/6963/13547 +f 7255/7922/16078 8750/8751/15797 8762/8837/15895 7254/8011/16079 +f 7196/7955/14904 8696/8784/16080 8670/8783/16081 7195/7954/14903 +f 7082/7911/16036 8690/8740/16035 8688/8582/16082 7089/7746/16083 +f 6091/7130/16084 8259/8342/16085 8421/8375/16086 6095/7252/13882 +f 7024/7625/16087 8801/8469/16088 8792/8476/16089 7021/7631/16089 +f 6141/7479/14229 8232/8409/16090 8233/8405/16091 6142/7467/16091 +f 6106/6194/16060 8318/8110/15146 8319/8109/15145 6107/6195/16092 +f 7279/7995/15013 8645/8822/15989 8678/8803/16093 7278/7975/14963 +f 7013/7933/16094 8611/8762/16095 8610/8650/16096 7012/7817/16097 +f 7121/7895/16098 8557/8725/16099 8556/8724/16100 7120/7894/16101 +f 7105/7860/16102 8626/8690/16102 8631/8843/16103 7104/8017/16104 +f 6095/7252/13882 8421/8375/16086 8395/8106/16105 6096/6191/12827 +f 7037/7634/16106 8823/8478/16107 8824/8477/16108 7043/7632/16109 +f 6047/7262/16110 8341/8378/16111 8343/8229/15958 6043/6769/15957 +f 7242/7987/16020 8701/8814/16019 8704/8695/16112 7241/7864/14781 +f 5945/7083/16113 8272/8328/16114 8292/8054/16115 5947/5917/16116 +f 6104/7433/16117 8288/8401/16118 8289/8208/16119 6105/6668/16119 +f 5880/6862/16120 8215/8256/16121 8216/8257/16122 5881/6863/16123 +f 6038/7471/16124 8047/8406/16125 8068/8073/16126 6042/6046/16127 +f 5944/7082/16128 8277/8327/16129 8272/8328/16114 5945/7083/16113 +f 5937/7510/15994 8234/8417/15993 8235/8418/16130 6002/7511/16131 +f 7169/7662/16132 8474/8505/16133 8476/8507/16134 7163/7663/16135 +f 7080/7712/15971 8786/8550/15970 8783/8796/16136 7079/7967/16137 +f 7109/7892/16138 8623/8722/16139 8618/8703/16140 7108/7873/16141 +f 7173/7797/16142 8608/8630/16142 8706/8629/16143 7174/7798/16144 +f 6071/6859/13436 8261/8255/16145 8258/8254/16146 6070/6860/13437 +f 6126/7091/13685 8236/8333/16147 8237/8335/16148 6133/7092/13686 +f 7028/7736/16149 8765/8573/16149 8764/8572/16149 7027/7737/16149 +f 7071/7710/15911 8700/8549/15910 8825/8570/16150 7070/7734/16151 +f 7174/7798/16144 8706/8629/16143 8589/8770/16152 7170/7941/16152 +f 6089/6216/16153 8428/8118/16153 8262/8341/16153 6090/7129/16153 +f 7009/7799/16154 8832/8631/16155 8822/8598/16156 7004/7766/16157 +f 5895/6259/16158 8332/8127/16159 8339/8128/16160 5896/6260/16161 +f 7030/7700/16162 8766/8539/16163 8765/8573/16164 7028/7736/16164 +f 6143/6882/16165 8238/8268/16165 8239/8267/15301 6144/6883/16166 +f 6116/7544/16167 8349/8424/15470 8337/8338/15372 6117/7125/16168 +f 6057/7227/13848 8257/8370/16169 8283/8371/16170 6058/7228/13849 +f 5951/6469/16171 8275/8168/16172 8277/8327/16129 5944/7082/16128 +f 7225/7996/16173 8811/8823/15880 8814/8555/15603 7224/7717/16174 +f 6064/7289/13927 8248/8380/16175 8249/8270/16176 6063/6886/13466 +f 7091/7988/16177 8642/8816/16178 8842/8834/16179 7090/8008/16180 +f 5873/6795/16181 8380/8237/16182 8197/8236/16183 5874/6796/16184 +f 7230/7791/16185 8843/8622/16185 8702/8621/16185 7243/7789/16185 +f 6140/7334/13997 8265/8390/16186 8232/8409/16090 6141/7479/14229 +f 7120/7894/16101 8556/8724/16100 8559/8809/16187 7119/7981/16188 +f 7106/7780/16189 8624/8613/16189 8626/8690/16189 7105/7860/16189 +f 7199/7828/14741 8664/8658/15922 8663/8661/16190 7200/7831/14745 +f 7195/7954/14903 8670/8783/16081 8669/8798/16191 7194/7970/16192 +f 6021/6392/16193 8082/8152/16194 8396/8356/16195 6023/7175/16196 +f 7090/8008/16180 8842/8834/16179 8777/8815/16197 7102/7989/16198 +f 5982/7037/16199 8143/8311/16200 8144/8312/16201 5983/7038/16202 +f 5966/7561/16203 8218/8430/16204 8213/8277/16205 5967/6926/16205 +f 7018/7839/16017 8628/8669/16016 8625/8689/16206 7016/7859/16207 +f 5905/5996/16208 8411/8064/16209 8410/8066/16210 5899/5997/16211 +f 6094/7528/16212 8397/8422/15468 8041/8141/15177 6085/6341/16213 +f 6103/6935/13523 8291/8281/16214 8288/8401/16118 6104/7433/16117 +f 7211/7852/14767 8666/8682/16215 8665/8659/15921 7198/7829/15920 +f 7247/7793/16216 8740/8625/15673 8739/8624/15672 7246/7792/16217 +f 6025/6116/16218 8063/8093/16219 8061/8092/16220 6031/6114/16221 +f 5970/6964/16222 8205/8290/16223 8210/8309/16224 5971/7032/16225 +f 7027/7737/16226 8764/8572/16226 8560/8556/16227 7047/7719/16228 +f 6036/6698/16229 8293/8217/16230 8195/8216/16231 6035/6699/16231 +f 7229/7926/15983 8672/8755/15982 8675/8754/16232 7228/7925/16232 +f 7278/7975/14963 8678/8803/16093 8603/8672/16233 7276/7843/14758 +f 5889/6420/16234 8351/8160/16234 8352/8159/16234 5890/6421/16234 +f 7262/7820/16235 8680/8653/16235 8679/8652/16236 7260/7821/14733 +f 5932/6407/16237 8412/8157/16238 8287/8135/16026 5933/6311/16025 +f 7194/7970/16192 8669/8798/16191 8785/8799/16239 7193/7971/16240 +f 6032/7179/16241 8176/8357/16241 8293/8217/16230 6036/6698/16229 +f 7167/7903/16242 8709/8733/16243 8708/8847/16244 7166/8021/16245 +f 5866/6588/16246 8409/8185/16247 8419/8218/16248 5871/6703/16249 +f 7163/7663/16135 8476/8507/16134 8827/8844/16250 7162/8018/16251 +f 5890/6421/16252 8352/8159/16252 8353/8126/16253 5892/6258/16254 +f 7151/7909/16255 8638/8738/16255 8586/8688/16256 7150/7858/16257 +f 5952/7527/16258 8429/8421/16259 8229/8402/16007 5953/7436/16006 +f 7276/7843/14758 8603/8672/16233 8599/8705/16260 7275/7875/14794 +f 7006/7907/16261 8803/8735/16262 8716/8632/16263 7010/7800/16264 +f 7185/7962/16003 8754/8791/16002 8481/8486/16022 7180/7642/16021 +f 5940/6596/15980 8365/8190/15979 8370/8383/16265 5941/7315/16266 +f 7260/7821/14733 8679/8652/16236 8633/8748/16267 7259/7918/14844 +f 7275/7875/14794 8599/8705/16260 8598/8697/16268 7273/7867/14784 +f 6048/7545/16269 8394/8425/16270 8369/8329/16271 6046/7085/16272 +f 7269/7916/14842 8767/8745/16273 8748/8693/16274 7248/7863/16274 +f 6105/6668/16275 8289/8208/16275 8430/8210/16275 6092/6669/16275 +f 5877/6615/16276 8208/8200/16277 8212/8276/16278 5878/6925/16279 +f 7146/8019/16280 8518/8845/16280 8517/8846/16281 7144/8020/16282 +f 5981/7381/15932 8146/8396/15931 8143/8311/16200 5982/7037/16199 +f 7257/7920/14848 8636/8749/16283 8578/8773/16284 7265/7944/14885 +f 7273/7867/14784 8598/8697/16268 8600/8698/16285 7272/7868/14785 +f 7232/8009/16286 8810/8835/15893 8844/8836/15894 7231/8010/16287 +f 5967/6926/16288 8213/8277/16288 8211/8199/16288 5968/6616/16288 +f 6062/6853/13429 8250/8248/16289 8251/8245/16041 6061/6845/13421 +f 7107/7779/16290 8616/8611/16291 8624/8613/16292 7106/7780/16292 +f 7175/7653/16293 8769/8497/16294 8643/8727/15913 7171/7897/15912 +f 6056/7322/16295 8256/8385/16296 8257/8370/16169 6057/7227/13848 +f 7189/7973/15967 8545/8802/15966 8758/8801/16297 7288/7974/16298 +f 5964/7435/15977 8364/8403/15976 8429/8421/16259 5952/7527/16258 +f 7089/7746/16083 8688/8582/16082 8840/8581/16299 7088/7747/16300 +f 7022/7767/16301 8802/8600/16302 8644/8760/16303 7026/7931/16304 +f 5886/5932/16305 8388/8057/16306 8320/8056/16307 5887/5933/16308 +f 7187/8013/16309 8790/8839/16310 8782/8742/16311 7184/7913/16312 +f 6022/6391/16313 8384/8153/16314 8082/8152/16194 6021/6392/16193 +f 7074/7999/16315 8820/8826/16316 8812/8551/15969 7073/7714/15968 +f 7178/8015/16317 8838/8841/16318 8768/8495/16319 7179/7652/16320 +f 6060/6846/16043 8252/8246/16042 8253/8269/16321 6073/6885/13465 +f 7160/7730/16322 8797/8565/16323 8510/8635/16324 7157/7803/16325 +f 6108/6685/16326 8326/8211/15247 8327/8212/15248 6109/6686/16327 +f 7168/7848/16328 8602/8678/16329 8474/8505/16133 7169/7662/16132 +f 5909/6364/16330 8147/8143/16331 8351/8160/16332 5889/6420/16332 +f 6090/7129/16333 8262/8341/16333 8259/8342/16085 6091/7130/16084 +f 7095/7984/15919 8542/8812/15918 8522/8807/16334 7093/7979/16335 +f 7148/7880/16336 8845/8709/16337 8515/8562/16338 7147/7726/16339 +f 6138/6867/13445 8190/8260/16340 8265/8390/16186 6140/7334/13997 +f 7116/7891/16341 8563/8720/16342 8562/8518/16343 7115/7677/16344 +f 6114/6034/16345 8357/8072/15108 8349/8424/15470 6116/7544/16167 +f 7193/7971/16240 8785/8799/16239 8539/8817/16346 7192/7990/16347 +f 6122/6804/13376 8266/8240/16348 8267/8239/16349 6124/6805/16349 +f 6055/7323/16350 8372/8386/16351 8256/8385/16296 6056/7322/16295 +f 6028/7579/16352 8295/8434/16353 8296/8320/16354 6029/7056/16355 +f 7209/7838/14752 8674/8667/16047 8677/8832/16356 7210/8006/15028 +f 7250/7802/16357 8743/8634/15682 8740/8625/15673 7247/7793/16216 +f 7047/7719/16228 8560/8556/16227 8558/8637/16358 7046/7804/16359 +f 7033/7701/16068 8745/8540/16067 8744/8501/16360 7032/7657/16361 +f 7143/7993/16362 8514/8820/16363 8819/8825/16364 7142/7998/16365 +f 6024/7563/16366 8414/8431/16367 8063/8093/16219 6025/6116/16218 +f 7046/7804/16359 8558/8637/16358 8839/8782/16368 7045/7953/16369 +f 7026/7931/16304 8644/8760/16303 8733/8470/16370 7025/7624/16371 +f 6113/6033/16372 8359/8070/15106 8357/8072/15108 6114/6034/16345 +f 7158/7611/16373 8805/8456/16374 8809/8769/16375 7161/7940/16376 +f 6012/6913/15928 8173/8275/15927 8225/8325/15937 6013/7080/15937 +f 7144/8020/16282 8517/8846/16281 8513/8821/16377 7141/7994/16378 +f 7246/7792/16217 8739/8624/15672 8732/8523/15571 7245/7682/15990 +f 6137/6972/13551 8186/8292/16379 8190/8260/16340 6138/6867/13445 +f 5872/6704/16380 8303/8219/16381 8390/8323/16382 5868/7070/16383 +f 6042/6046/16127 8068/8073/16126 8341/8378/16111 6047/7262/16110 +f 7183/7811/14723 8757/8644/16384 8804/8643/16385 7182/7812/14724 +f 6121/7093/13687 8220/8334/16386 8266/8240/16348 6122/6804/13376 +f 6135/6949/13538 8185/8284/16387 8186/8292/16379 6137/6972/13551 +f 6110/6933/16388 8335/8280/16388 8354/8332/16389 6131/7090/13684 +f 7188/7914/16390 8817/8743/16391 8790/8839/16310 7187/8013/16309 +f 7166/8021/16245 8708/8847/16244 8805/8456/16374 7158/7611/16373 +f 7179/7652/16320 8768/8495/16319 8769/8497/16294 7175/7653/16293 +f 7041/7869/16392 8457/8699/16393 8775/8494/16394 7040/7650/16395 +f 6006/7572/16396 8104/8433/16397 8105/8432/16398 6008/7565/16398 +f 6127/7192/13796 8165/8360/16399 8223/8336/16400 6119/7096/13692 +f 6134/6950/13539 8187/8285/16401 8185/8284/16387 6135/6949/13538 +f 6093/7529/16402 8431/8423/15469 8397/8422/15468 6094/7528/16212 +f 6087/7485/16403 8398/8410/15455 8108/8116/15152 6088/6215/16073 +f 7141/7994/16378 8513/8821/16377 8648/8831/16038 7140/8004/16037 +f 5968/6616/16404 8211/8199/16404 8203/8198/16405 5969/6614/16406 +f 6150/7330/15943 8345/8389/15942 8132/8388/16062 6051/7331/16061 +f 5950/6468/15950 8427/8169/15949 8275/8168/16172 5951/6469/16171 +f 7104/8017/16104 8631/8843/16103 8640/8833/16407 7103/8007/16408 +f 7093/7979/16335 8522/8807/16334 8606/8711/16409 7092/7881/16410 +f 7154/7980/16411 8613/8808/16412 8653/8789/16413 7153/7960/16414 +f 5962/7197/16415 8371/8362/16416 8363/8363/15975 5963/7198/15974 +f 7172/7898/15915 8607/8728/15914 8608/8630/16142 7173/7797/16142 +f 5876/7194/16072 8206/8361/16071 8208/8200/16277 5877/6615/16276 +f 7176/7992/16024 8460/8819/16023 8828/8842/16417 7177/8016/16418 +f 7007/7906/16419 8806/8736/16420 8803/8735/16262 7006/7907/16261 +f 5935/6315/16421 8399/8139/16422 8407/8413/16423 5936/7494/16424 +f 6041/6080/16425 8355/8082/16426 8425/8428/16427 6040/7553/16428 +f 7217/7927/16429 8712/8756/16430 8698/8757/16431 7218/7928/14862 +f 6019/6743/16005 8097/8222/16004 8384/8153/16314 6022/6391/16313 +f 6031/6114/16221 8061/8092/16220 8189/8265/16432 6030/6880/16433 +f 5955/7373/16434 8109/8394/16435 8129/8399/16032 5957/7394/16031 +f 7038/7651/16436 8530/8493/16437 8823/8478/16107 7037/7634/16106 +f 6009/6388/16438 8102/8149/16439 8432/8297/16440 6010/7006/16441 +f 5977/6174/16442 8149/8104/16443 8150/8308/16444 5978/7030/16445 +f 7113/7656/16446 8836/8499/16447 8612/8626/16448 7112/7794/16449 +f 6054/7443/16450 8126/8404/16451 8372/8386/16351 6055/7323/16350 +f 7236/7589/14423 8837/8437/16452 8808/8520/15995 7234/7679/14533 +f 7253/7908/16453 8722/8737/15783 8694/8752/16454 7263/7923/16454 +f 7108/7873/16141 8618/8703/16140 8616/8611/16291 7107/7779/16290 +f 7224/7717/16174 8814/8555/15603 8454/8554/15602 7223/7716/16455 +f 6072/7514/14278 8264/8419/16456 8261/8255/16145 6071/6859/13436 +f 6109/6686/16327 8327/8212/15248 8330/8221/15257 6112/6711/16457 +f 7204/7871/14790 8658/8701/16458 8657/8665/16459 7197/7834/14748 +f 5908/6757/16460 8145/8223/16461 8147/8143/16331 5909/6364/16330 +f 7281/7851/16462 8651/8680/16462 8646/8818/16462 7280/7991/16462 +f 5894/6088/16463 8331/8087/16464 8332/8127/16159 5895/6259/16158 +f 7186/8012/16465 8807/8838/16466 8757/8644/16384 7183/7811/14723 +f 6004/7493/16467 8406/8412/16468 8101/8407/16469 6005/7474/16470 +f 7272/7868/14785 8600/8698/16285 8650/8747/16048 7271/7919/14845 +f 7147/7726/16339 8515/8562/16338 8514/8820/16363 7143/7993/16362 +f 5907/7224/16471 8426/8369/16472 8145/8223/16461 5908/6757/16460 +f 5887/5933/16308 8320/8056/16307 8231/8347/16473 5888/7155/16474 +f 5942/6314/16475 8373/8137/16476 8399/8139/16422 5935/6315/16421 +f 7087/7735/16477 8576/8571/16478 8577/8707/16479 7098/7877/16480 +f 6023/7175/16196 8396/8356/16195 8392/8043/16481 6020/5876/16482 +f 7165/7646/16483 8655/8489/16484 8709/8733/16243 7167/7903/16242 +f 6107/6195/16092 8319/8109/15145 8326/8211/15247 6108/6685/16326 +f 7011/7818/16485 8793/8649/16486 8806/8736/16420 7007/7906/16419 +f 7153/7960/16414 8653/8789/16413 8639/8739/16487 7152/7910/16488 +f 7231/8010/16287 8844/8836/15894 8843/8622/16489 7230/7791/16489 +f 7032/7657/16361 8744/8501/16360 8747/8500/16490 7031/7658/16491 +f 7070/7734/16151 8825/8570/16150 8829/8710/16492 7072/7879/16493 +f 7162/8018/16251 8827/8844/16250 8779/8490/16494 7164/7648/16495 +f 6049/7548/16496 8377/8426/16497 8404/8330/16498 6050/7086/16499 +f 7248/7863/16500 8748/8693/16500 8707/8623/16500 7249/7790/16500 +f 6037/6082/16501 8356/8083/16502 8355/8082/16426 6041/6080/16425 +f 5902/6076/16503 8362/8080/16504 8044/8286/16505 5903/6958/16506 +f 7048/7806/16507 8693/8638/16508 8712/8756/16430 7217/7927/16429 +f 6002/7511/16131 8235/8418/16130 8100/8408/16509 6003/7475/16510 +f 7145/7997/16511 8519/8824/16511 8518/8845/16511 7146/8019/16511 +f 7213/7640/14492 8771/8485/16512 8453/8521/16513 7214/7681/14535 +f 5965/7521/16514 8227/8420/16515 8218/8430/16204 5966/7561/16203 +f 5954/7009/16009 8193/8298/16008 8109/8394/16435 5955/7373/16434 +f 6015/7257/16516 8240/8376/16517 8200/8395/16518 6016/7379/16519 +f 7182/7812/16520 8804/8643/16520 8756/8642/16001 7181/7810/16000 +f 7200/7831/14745 8663/8661/16190 8662/8683/16521 7201/7853/14768 +f 6035/6699/16231 8195/8216/16231 8194/8315/16028 6034/7044/16027 +f 7202/7964/14938 8661/8793/16522 8660/8787/16523 7203/7958/14916 +f 6039/7554/16524 8415/8429/16525 8047/8406/16125 6038/7471/16124 +f 5961/6763/16526 8155/8227/16527 8371/8362/16416 5962/7197/16415 +f 6080/7149/13744 8285/8344/16528 8299/8343/16529 6079/7148/16530 +f 7010/7800/16264 8716/8632/16263 8832/8631/16155 7009/7799/16154 +f 7215/7930/14864 8816/8759/16531 8543/8679/16532 7212/7849/14764 +f 5899/5997/16211 8410/8066/16210 8117/8081/16533 5900/6075/16534 +f 7117/7890/16535 8565/8721/16536 8563/8720/16342 7116/7891/16341 +f 7114/7678/16537 8835/8517/16537 8836/8499/16447 7113/7656/16446 +f 7044/7870/16538 8830/8700/16539 8457/8699/16393 7041/7869/16392 +f 5974/6689/16540 8199/8213/16541 8423/8086/16542 5975/6086/16543 +f 7020/7801/16544 8630/8633/16545 8629/8670/16015 7019/7840/16014 +f 7283/7968/16546 8544/8797/15853 8652/8681/15727 7282/7850/16075 +f 6096/6191/12827 8395/8106/16105 8424/8023/16547 6098/5774/12453 +f 6125/7126/16548 8281/8339/16548 8309/8324/15358 6115/7076/16549 +f 5969/6614/16406 8203/8198/16405 8205/8290/16223 5970/6964/16222 +f 7072/7879/16493 8829/8710/16492 8845/8709/16337 7148/7880/16336 +f 6085/6341/16213 8041/8141/15177 8401/8142/15178 6086/6342/16550 +f 7216/7929/14863 8697/8758/16551 8816/8759/16531 7215/7930/14864 +f 7081/7621/15956 8711/8467/15955 8705/8466/16011 7085/7622/16010 +f 6069/7221/13843 8263/8368/16552 8107/8117/16553 6068/6217/12850 +f 6059/6857/13433 8244/8251/16554 8245/8288/16077 6066/6962/13546 +f 7142/7998/16365 8819/8825/16364 8519/8824/16555 7145/7997/16555 +f 7004/7766/16157 8822/8598/16156 8802/8600/16302 7022/7767/16301 +f 6142/7467/16556 8233/8405/16556 8238/8268/16556 6143/6882/16556 +f 6133/7092/13686 8237/8335/16148 8187/8285/16401 6134/6950/13539 +f 6005/7474/16470 8101/8407/16469 8102/8149/16439 6009/6388/16438 +f 5960/6994/16557 8164/8294/16558 8163/8158/15948 5949/6419/15947 +f 6029/7056/16355 8296/8320/16354 8242/8076/15985 6027/6065/15984 +f 5869/7071/16559 8393/8322/16560 8380/8237/16182 5873/6795/16181 +f 6014/7081/15939 8226/8326/15938 8240/8376/16517 6015/7257/16516 +f 7031/7658/16491 8747/8500/16490 8766/8539/16163 7030/7700/16162 +f 6092/6669/16561 8430/8210/16561 8431/8423/15469 6093/7529/16402 +f 5893/6087/16562 8334/8088/16563 8331/8087/16464 5894/6088/16463 +f 5934/7007/16564 8416/8296/16565 8412/8157/16238 5932/6407/16237 +f 7249/7790/16566 8707/8623/16566 8743/8634/15682 7250/7802/16357 +f 6026/6066/15987 8366/8078/15986 8414/8431/16367 6024/7563/16366 +f 6111/6670/16567 8294/8209/16567 8335/8280/16567 6110/6933/16567 +f 5883/5970/16568 8379/8063/16569 8388/8057/16306 5886/5932/16305 +f 6079/7148/16530 8299/8343/16529 8280/8225/16570 5910/6762/16571 +f 7286/7976/16572 8729/8804/16573 8817/8743/16391 7188/7914/16390 +f 7264/7917/14843 8649/8746/16049 8749/8651/16574 7256/7819/16574 +f 7110/7836/16575 8617/8666/16576 8623/8722/16139 7109/7892/16138 +f 6008/7565/16577 8105/8432/16577 8106/8411/16577 6007/7492/16577 +f 7203/7958/14916 8660/8787/16523 8659/8702/16578 7205/7872/14791 +f 6076/6193/12829 8040/8108/16579 8358/8071/16580 6075/6035/12686 +f 7118/7614/16581 8564/8459/16582 8565/8721/16536 7117/7890/16535 +f 5874/6796/16184 8197/8236/16183 8198/8349/16070 5875/7161/16069 +f 6063/6886/13466 8249/8270/16176 8250/8248/16289 6062/6853/13429 +f 6065/7251/13881 8247/8374/16053 8248/8380/16175 6064/7289/13927 +f 7268/7938/14876 8635/8767/16583 8767/8745/16273 7269/7916/14842 +f 7014/7945/16584 8619/8774/16585 8611/8762/16095 7013/7933/16094 +f 7190/7707/16586 8574/8546/16587 8549/8840/15965 7191/8014/15964 +f 7205/7872/14791 8659/8702/16578 8658/8701/16458 7204/7871/14790 +f 7214/7681/14535 8453/8521/16513 8520/8531/16056 7206/7690/14545 +f 7115/7677/16344 8562/8518/16343 8835/8517/16588 7114/7678/16588 +f 5871/6703/16249 8419/8218/16248 8303/8219/16381 5872/6704/16380 +f 7177/8016/16418 8828/8842/16417 8838/8841/16318 7178/8015/16317 +f 5941/7315/16266 8370/8383/16265 8373/8137/16476 5942/6314/16475 +f 6074/6881/13460 8130/8266/16589 8403/8346/16590 6077/7153/13748 +f 5978/7030/16445 8150/8308/16444 8152/8307/16591 5979/7031/16592 +f 5975/6086/16543 8423/8086/16542 8422/8105/16593 5976/6173/16593 +f 5903/6958/16506 8044/8286/16505 8417/8287/16594 5906/6959/16595 +f 7076/8000/16596 8759/8827/16597 8820/8826/16316 7074/7999/16315 +f 5881/6863/16123 8216/8257/16122 8217/8220/16598 5882/6709/16599 +f 7261/7943/16600 8751/8772/16600 8750/8751/15797 7255/7922/16078 +f 6144/6883/16166 8239/8267/15301 8131/8384/15428 6145/7318/16601 +f 7238/7901/14825 8833/8731/15924 8837/8437/16452 7236/7589/14423 +f 7270/7785/15963 8723/8617/15665 8722/8737/15783 7253/7908/16453 +f 6010/7006/16441 8432/8297/16440 8416/8296/16565 5934/7007/16564 +f 7111/7795/16602 8615/8628/16603 8617/8666/16576 7110/7836/16575 +f 5947/5917/16116 8292/8054/16115 8298/8053/16055 5943/5918/16054 +f 6077/7153/13748 8403/8346/16590 8284/8345/16604 6078/7152/13747 +f 6007/7492/16605 8106/8411/16605 8406/8412/16468 6004/7493/16467 +f 5884/6590/16606 8389/8186/16607 8409/8185/16247 5866/6588/16246 +f 7259/7918/14844 8633/8748/16267 8632/8771/16608 7258/7942/14880 +f 7035/7985/16609 8727/8813/16610 8752/8541/16066 7034/7702/16065 +f 7155/7597/16611 8692/8442/16612 8613/8808/16412 7154/7980/16411 +f 7192/7990/16347 8539/8817/16346 8574/8546/16587 7190/7707/16586 +f 5892/6258/16254 8353/8126/16253 8334/8088/16563 5893/6087/16562 +f 6086/6342/16550 8401/8142/15178 8398/8410/15455 6087/7485/16403 +f 7284/7936/16613 8774/8764/15811 8544/8797/15853 7283/7968/16546 +f 6112/6711/16457 8330/8221/15257 8294/8209/16614 6111/6670/16614 +f 6050/7086/16499 8404/8330/16498 8316/8391/15961 6148/7339/15960 +f 6118/6803/16615 8336/8238/16615 8236/8333/16147 6126/7091/13685 +f 5971/7032/16225 8210/8309/16224 8204/8253/16616 5972/6858/16617 +f 5979/7031/16592 8152/8307/16591 8151/8046/15930 5980/5907/15929 +f 7112/7794/16449 8612/8626/16448 8615/8628/16603 7111/7795/16602 +f 6131/7090/13684 8354/8332/16389 8222/8354/16618 6130/7169/13773 +f 7207/7952/14900 8676/8781/16057 8671/8668/16046 7208/7837/14751 +f 5878/6925/16279 8212/8276/16278 8215/8256/16121 5880/6862/16120 +f 7099/7808/15999 8568/8639/15998 8693/8638/16508 7048/7806/16507 +f 6053/7552/16064 8136/8427/16063 8161/8132/16619 6052/6308/16620 +f 7263/7923/16621 8694/8752/16621 8680/8653/16621 7262/7820/16621 +f 6068/6217/12850 8107/8117/16553 8040/8108/16579 6076/6193/12829 +f 5976/6173/16622 8422/8105/16622 8149/8104/16443 5977/6174/16442 +f 7201/7853/14768 8662/8683/16521 8661/8793/16522 7202/7964/14938 +f 6040/7553/16428 8425/8428/16427 8415/8429/16525 6039/7554/16524 +f 7012/7817/16097 8610/8650/16096 8793/8649/16486 7011/7818/16485 +f 7266/7978/14973 8579/8806/16623 8635/8767/16583 7268/7938/14876 +f 5936/7494/16424 8407/8413/16423 8346/8414/15992 5938/7495/15991 +f 6117/7125/16168 8337/8338/15372 8338/8359/16624 6123/7185/16624 +f 7045/7953/16369 8839/8782/16368 8830/8700/16539 7044/7870/16538 +f 6098/5774/12453 8424/8023/16547 8420/8318/16044 6100/7054/13647 +f 7161/7940/16376 8809/8769/16375 8495/8566/16625 7159/7729/16626 +f 6115/7076/16549 8309/8324/15358 8310/8204/15240 6132/6635/16059 +f 5972/6858/16617 8204/8253/16616 8202/8214/16627 5973/6691/16628 +f 7241/7864/14781 8704/8695/16112 8821/8694/15923 7240/7865/14782 +f 6120/7182/13788 8219/8358/16629 8220/8334/16386 6121/7093/13687 +f 5896/6260/16161 8339/8128/16160 8314/8400/15952 5897/7397/15951 +f 6016/7379/16519 8200/8395/16518 8279/8030/15934 6017/5820/15933 +f 7223/7716/16455 8454/8554/15602 8810/8835/15893 7232/8009/16286 +f 7258/7942/14880 8632/8771/16608 8636/8749/16283 7257/7920/14848 +f 6052/6308/16620 8161/8132/16619 8126/8404/16451 6054/7443/16450 +f 7098/7877/16480 8577/8707/16479 8540/8706/15917 7096/7876/15916 +f 7251/7639/16630 8772/8483/15531 8773/8765/15812 7285/7935/16631 +f 6145/7318/16601 8131/8384/15428 8361/8352/15387 6146/7163/16632 +f 7285/7935/16631 8773/8765/15812 8774/8764/15811 7284/7936/16613 +f 7103/8007/16408 8640/8833/16407 8557/8725/16099 7121/7895/16098 +f 5958/6993/16034 8127/8293/16033 8164/8294/16558 5960/6994/16557 +f 7170/7941/16152 8589/8770/16152 8602/8678/16329 7168/7848/16328 +f 7210/8006/15028 8677/8832/16356 8666/8682/16215 7211/7852/14767 +f 6033/7043/16030 8230/8314/16029 8356/8083/16502 6037/6082/16501 +f 5973/6691/16628 8202/8214/16627 8199/8213/16541 5974/6689/16540 +f 7265/7944/14885 8578/8773/16284 8579/8806/16623 7266/7978/14973 +f 5888/7155/16474 8231/8347/16473 8389/8186/16607 5884/6590/16606 +f 6046/7085/16272 8369/8329/16271 8377/8426/16497 6049/7548/16496 +f 6070/6860/13437 8258/8254/16146 8263/8368/16552 6069/7221/13843 +f 5910/6762/16571 8280/8225/16570 8155/8227/16527 5961/6763/16526 +f 7042/7874/16633 8746/8704/16634 8728/8516/16635 7036/7675/16636 +f 6124/6805/16637 8267/8239/16637 8281/8339/16637 6125/7126/16637 +f 7212/7849/14764 8543/8679/16532 8771/8485/16512 7213/7640/14492 +f 7040/7650/16395 8775/8494/16394 8530/8493/16437 7038/7651/16436 +f 7079/7967/16137 8783/8796/16136 8778/8603/16638 7078/7771/16639 +f 7184/7913/16312 8782/8742/16311 8807/8838/16466 7186/8012/16465 +f 7016/7859/16207 8625/8689/16206 8621/8612/16640 7015/7781/16641 +f 6130/7169/13773 8222/8354/16618 8166/8393/16642 6128/7364/14040 +f 7197/7834/14748 8657/8665/16459 8696/8784/16080 7196/7955/14904 +f 7021/7631/16089 8792/8476/16089 8630/8633/16545 7020/7801/16544 +f 7218/7928/14862 8698/8757/16431 8697/8758/16551 7216/7929/14863 +f 5906/6959/16595 8417/8287/16594 8426/8369/16472 5907/7224/16471 +f 6102/6934/13522 8408/8282/16045 8291/8281/16214 6103/6935/13523 +f 7025/7624/16371 8733/8470/16370 8801/8469/16088 7024/7625/16087 +f 7159/7729/16626 8495/8566/16625 8797/8565/16323 7160/7730/16322 +f 6119/7096/13692 8223/8336/16400 8219/8358/16629 6120/7182/13788 +f 6003/7475/16510 8100/8408/16509 8104/8433/16397 6006/7572/16396 +f 6147/7164/16643 8360/8351/15386 8359/8070/15106 6113/6033/16372 +f 7043/7632/16109 8824/8477/16108 8746/8704/16634 7042/7874/16633 +f 7256/7819/16644 8749/8651/16644 8751/8772/16644 7261/7943/16644 +f 6044/6770/13340 8391/8231/16645 8344/8230/16646 6045/6771/13341 +f 6020/5876/16482 8392/8043/16481 8295/8434/16353 6028/7579/16352 +f 6146/7163/16632 8361/8352/15387 8360/8351/15386 6147/7164/16643 +f 5983/7038/16202 8144/8312/16201 8227/8420/16515 5965/7521/16514 +f 7150/7858/16257 8586/8688/16256 8585/8547/15909 7149/7709/15908 +f 6030/6880/16433 8189/8265/16432 8176/8357/16241 6032/7179/16241 +f 7119/7981/16188 8559/8809/16187 8564/8459/16582 7118/7614/16581 +f 7156/7596/16647 8509/8443/16648 8692/8442/16612 7155/7597/16611 +f 7152/7910/16488 8639/8739/16487 8638/8738/16255 7151/7909/16255 +f 7254/8011/16079 8762/8837/15895 8770/8484/15532 7252/7641/16649 +f 7288/7974/16298 8758/8801/16297 8730/8800/16650 7287/7972/16651 +f 6073/6885/13465 8253/8269/16321 8264/8419/16456 6072/7514/14278 +f 7088/7747/16300 8840/8581/16299 8576/8571/16478 7087/7735/16477 +f 7036/7675/16636 8728/8516/16635 8727/8813/16610 7035/7985/16609 +f 6128/7364/14040 8166/8393/16642 8165/8360/16399 6127/7192/13796 +f 7287/7972/16651 8730/8800/16650 8729/8804/16573 7286/7976/16572 +f 5898/6172/15954 8315/8102/15953 8333/8291/16652 5904/6969/16653 +f 5868/7070/16383 8390/8323/16382 8393/8322/16560 5869/7071/16559 +f 7252/7641/16649 8770/8484/15532 8772/8483/15531 7251/7639/16630 +f 6075/6035/12686 8358/8071/16580 8130/8266/16589 6074/6881/13460 +f 7102/7989/16198 8777/8815/16197 8776/8776/16654 7101/7947/16655 +f 5900/6075/16534 8117/8081/16533 8362/8080/16504 5902/6076/16503 +f 7078/7771/16639 8778/8603/16638 8763/8604/15944 7077/7772/15944 +f 7164/7648/16495 8779/8490/16494 8655/8489/16484 7165/7646/16483 +f 6058/7228/13849 8283/8371/16170 8244/8251/16554 6059/6857/13433 +f 5882/6709/16599 8217/8220/16598 8379/8063/16569 5883/5970/16568 +f 6078/7152/13747 8284/8345/16604 8285/8344/16528 6080/7149/13744 +f 7075/8003/16040 8647/8830/16039 8759/8827/16597 7076/8000/16596 +f 7226/7689/15973 8521/8529/15577 8811/8823/15880 7225/7996/16173 +f 7101/7947/16655 8776/8776/16654 8784/8775/15997 7100/7946/15996 +f 7015/7781/16641 8621/8612/16640 8619/8774/16585 7014/7945/16584 +f 6045/6771/13341 8344/8230/16646 8394/8425/16270 6048/7545/16269 +f 7157/7803/16325 8510/8635/16324 8509/8443/16648 7156/7596/16647 +f 7092/7881/16410 8606/8711/16409 8642/8816/16178 7091/7988/16177 +f 5904/6969/16653 8333/8291/16652 8411/8064/16209 5905/5996/16208 +f 6123/7185/16656 8338/8359/16656 8336/8238/16656 6118/6803/16656 diff --git a/examples/Cassie/urdf/meshes/agility/plantar-rod.obj b/examples/Cassie/urdf/meshes/agility/plantar-rod.obj new file mode 100644 index 0000000000..c6e49adeec --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/plantar-rod.obj @@ -0,0 +1,5035 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o plantar-rod +v 0.006152 0.001747 -0.007140 +v 0.006727 0.003569 -0.005703 +v 0.007781 0.001608 -0.005473 +v 0.011444 -0.003567 -0.000590 +v 0.010047 -0.003567 -0.002128 +v 0.011789 -0.002975 -0.001900 +v 0.013041 -0.003173 0.000671 +v 0.010843 -0.003572 0.001406 +v 0.011444 0.003567 0.000590 +v 0.010047 0.003567 0.002128 +v 0.011789 0.002975 0.001900 +v 0.012468 0.003269 -0.000785 +v 0.010843 0.003572 -0.001406 +v 0.013508 0.003209 0.000093 +v 0.013456 -0.003177 -0.000509 +v 0.010300 -0.000185 0.004008 +v 0.011773 -0.001464 0.003216 +v 0.013072 0.000244 0.003229 +v 0.013459 -0.000891 0.003085 +v 0.013430 0.002925 0.001357 +v 0.011807 0.002912 -0.001973 +v 0.013477 -0.002811 -0.001542 +v 0.012151 -0.002727 0.002080 +v 0.013756 0.002934 -0.001301 +v 0.010324 0.002454 0.003214 +v 0.013437 0.002172 0.002362 +v 0.010423 0.002494 -0.003134 +v 0.008921 0.003571 -0.003186 +v 0.010018 -0.000988 -0.004051 +v 0.011059 0.000002 -0.003753 +v 0.011773 -0.001771 -0.003058 +v 0.013072 -0.000244 -0.003229 +v 0.010324 -0.002454 -0.003214 +v 0.013437 -0.002172 -0.002362 +v 0.010423 -0.002494 0.003134 +v 0.008311 -0.003562 0.003811 +v 0.009656 0.001026 0.004203 +v 0.011773 0.001771 0.003058 +v 0.008531 0.003570 0.003562 +v 0.013433 -0.001269 -0.002957 +v 0.008516 -0.003570 -0.003576 +v 0.007675 0.001878 0.005491 +v 0.009063 0.002360 0.004085 +v 0.013433 0.001269 0.002957 +v 0.009041 -0.002232 -0.004183 +v 0.007838 -0.001968 -0.005285 +v 0.008017 -0.000379 0.005441 +v 0.007970 -0.001925 0.005141 +v 0.009970 -0.001831 0.003779 +v 0.013635 -0.002130 0.002418 +v 0.006258 0.003569 0.006267 +v 0.008815 0.002444 -0.004212 +v 0.012787 0.002510 -0.002131 +v 0.009474 0.000724 -0.004395 +v 0.007783 -0.000712 -0.005640 +v 0.011669 0.001315 -0.003298 +v 0.013440 0.001901 -0.002593 +v 0.013459 0.000891 -0.003085 +v 0.006363 -0.003571 -0.006160 +v 0.013882 -0.002949 0.001223 +v -0.009486 -0.000631 -0.000946 +v -0.009449 -0.001249 0.000659 +v -0.009522 0.000723 0.000006 +v 0.006048 -0.001903 -0.007155 +v 0.006105 -0.000453 -0.007339 +v 0.005831 0.000113 0.007602 +v -0.000982 -0.002304 0.009227 +v -0.001647 -0.003570 0.008686 +v 0.000823 -0.003570 0.008818 +v -0.009197 -0.002484 -0.000649 +v -0.008796 -0.003571 -0.000922 +v -0.008784 -0.003567 0.001188 +v -0.008219 -0.003572 -0.003341 +v -0.008917 -0.002023 -0.002834 +v -0.004828 -0.003570 -0.007452 +v -0.006859 -0.003571 -0.005586 +v -0.006014 -0.001960 -0.007203 +v 0.003630 0.003575 -0.008065 +v 0.003064 0.001998 -0.008832 +v 0.000970 0.003571 -0.008816 +v -0.002414 0.003572 -0.008566 +v -0.004444 0.002433 -0.008098 +v -0.005061 0.003572 -0.007262 +v -0.006439 0.003571 -0.006067 +v -0.007389 0.002615 -0.005463 +v -0.007791 0.003571 -0.004210 +v -0.007916 0.003570 0.003955 +v -0.008747 0.003568 0.001514 +v -0.008875 0.001896 0.003018 +v 0.005779 -0.003566 0.006758 +v 0.005396 0.003571 -0.007027 +v 0.006118 -0.001908 0.007097 +v 0.004499 0.001945 -0.008208 +v 0.004441 -0.003566 -0.007697 +v 0.005776 0.001643 0.007454 +v 0.004944 0.003564 0.007366 +v 0.003199 0.002195 0.008752 +v 0.003607 0.003572 0.008089 +v 0.000586 0.003573 0.008860 +v 0.004535 -0.002033 0.008149 +v 0.003049 -0.003571 0.008343 +v 0.002413 -0.002119 0.009018 +v 0.000852 0.001949 -0.009337 +v -0.001716 0.001114 -0.009375 +v -0.003081 0.001552 -0.008910 +v 0.002326 0.000274 -0.009284 +v -0.005133 0.000512 -0.008047 +v 0.004480 -0.000649 -0.008420 +v -0.000169 0.000000 -0.009550 +v -0.003703 -0.000420 -0.008801 +v 0.002405 -0.001783 -0.009099 +v -0.000541 -0.001844 -0.009385 +v -0.003351 -0.001827 -0.008782 +v 0.001338 -0.003571 -0.008798 +v -0.002072 -0.003570 -0.008624 +v 0.000669 -0.001001 0.009491 +v 0.002410 0.000356 0.009250 +v 0.000942 0.001468 0.009390 +v -0.001023 0.000632 0.009508 +v -0.006116 -0.001296 0.007254 +v -0.004508 0.000570 0.008407 +v -0.005721 0.001521 0.007510 +v 0.003813 -0.000345 0.008762 +v -0.002728 0.000712 0.009124 +v -0.003446 0.002301 0.008625 +v -0.001712 0.003562 0.008709 +v -0.004226 0.003572 0.007811 +v -0.006599 0.003564 0.005969 +v -0.005993 0.001708 -0.007242 +v -0.006902 0.001137 0.006528 +v -0.006861 0.000458 -0.006667 +v -0.007826 -0.002294 -0.004985 +v -0.007796 -0.000710 -0.005484 +v -0.008195 0.001962 0.004495 +v -0.008203 0.000315 0.004903 +v -0.008199 0.001417 -0.004710 +v -0.008828 0.002454 -0.002702 +v -0.008656 0.003572 -0.001860 +v -0.008680 -0.000472 -0.003935 +v -0.008882 0.001007 -0.003372 +v -0.007156 -0.003569 0.005233 +v -0.008225 -0.001863 0.004529 +v -0.008252 -0.003570 0.003214 +v -0.005677 -0.003569 0.006800 +v -0.007020 -0.001420 0.006325 +v -0.003087 -0.001743 0.008896 +v -0.003730 -0.003571 0.008030 +v -0.004776 -0.001589 0.008126 +v -0.008964 -0.000593 0.003265 +v -0.009134 -0.001840 0.002109 +v -0.009314 -0.000571 -0.002080 +v -0.009328 0.001648 -0.001318 +v -0.008855 0.003567 -0.000241 +v -0.009329 0.001776 0.001151 +v -0.009379 0.000443 0.001756 +v -0.002263 -0.003572 0.006279 +v 0.006359 -0.003572 -0.002027 +v 0.006452 -0.003572 0.001866 +v -0.004773 -0.003572 0.004619 +v -0.003604 -0.003572 -0.005618 +v -0.005697 -0.003572 -0.003415 +v 0.000758 -0.003572 0.006598 +v 0.003983 -0.003572 0.005408 +v 0.002263 -0.003572 -0.006279 +v 0.004773 -0.003572 -0.004619 +v -0.006359 -0.003572 0.002027 +v -0.000758 -0.003572 -0.006598 +v -0.006570 -0.003572 -0.000975 +v -0.003604 0.003572 0.005618 +v -0.000758 0.003572 0.006598 +v -0.005930 0.003572 0.003063 +v -0.006641 0.003572 0.000109 +v 0.006359 0.003572 0.002027 +v 0.006452 0.003572 -0.001866 +v -0.004773 0.003572 -0.004619 +v -0.006177 0.003572 -0.002440 +v 0.004773 0.003572 0.004619 +v 0.002263 0.003572 0.006279 +v -0.002263 0.003572 -0.006279 +v 0.000758 0.003572 -0.006598 +v 0.003983 0.003572 -0.005408 +v -0.006500 -0.000543 -0.000692 +v -0.006526 0.000076 0.000676 +v -0.006531 0.000646 -0.000088 +v -0.002224 0.004763 -0.003934 +v -0.003387 0.004195 -0.003733 +v -0.003772 0.004764 -0.002504 +v -0.004896 0.004115 -0.001467 +v -0.004495 0.004761 -0.000394 +v 0.004039 0.004761 0.002003 +v 0.002844 0.004761 0.003530 +v 0.004114 0.004136 0.003002 +v 0.006494 0.000820 -0.000422 +v 0.006541 -0.000383 -0.000234 +v 0.006343 0.000575 -0.001616 +v 0.006399 -0.001389 -0.000531 +v 0.006385 -0.000806 0.001331 +v 0.006519 0.000184 0.000661 +v 0.006116 -0.002374 0.000277 +v 0.006324 -0.000603 -0.001630 +v 0.005781 0.000151 -0.003104 +v 0.005817 -0.001167 -0.002823 +v 0.006022 0.002275 0.001269 +v 0.006145 0.002283 -0.000337 +v 0.005542 0.003457 0.000749 +v 0.006399 0.001324 0.000548 +v 0.005724 0.002419 -0.002152 +v 0.006102 0.001645 -0.001772 +v 0.005576 0.001480 -0.003130 +v 0.005886 -0.002658 0.001258 +v 0.005397 -0.003746 -0.000030 +v 0.004495 -0.004761 -0.000394 +v 0.004227 -0.004756 -0.001628 +v 0.005242 -0.003656 -0.001469 +v 0.005938 -0.002442 -0.001442 +v 0.004454 -0.004753 0.000830 +v 0.004966 -0.003810 0.001993 +v 0.005979 -0.001361 0.002336 +v 0.003701 -0.004763 0.002630 +v 0.005255 -0.002726 0.002852 +v 0.004519 0.004756 0.000334 +v 0.004928 0.003902 0.001927 +v 0.005494 0.003507 -0.000832 +v 0.004334 0.004757 -0.001332 +v 0.005136 0.003520 -0.002096 +v 0.003851 0.004756 -0.002382 +v 0.004064 0.003979 -0.003271 +v 0.004114 -0.004088 0.003066 +v 0.005504 -0.001374 0.003334 +v 0.003210 -0.004738 -0.003271 +v 0.004737 -0.003577 -0.002824 +v 0.005633 0.002445 0.002313 +v 0.005590 -0.002494 -0.002362 +v 0.003946 -0.003247 0.004139 +v 0.002166 -0.004761 0.003968 +v 0.002682 -0.003789 0.004664 +v 0.004061 -0.002253 0.004660 +v 0.006096 0.000076 0.002443 +v 0.006152 0.001074 0.002069 +v 0.002826 0.004758 -0.003519 +v 0.004829 -0.000960 0.004353 +v 0.003321 0.003759 0.004236 +v 0.005189 0.002391 0.003258 +v 0.003283 0.003706 -0.004316 +v 0.005426 0.000433 0.003670 +v 0.002799 -0.002487 0.005389 +v 0.004422 0.002756 0.004020 +v 0.000658 -0.004748 0.004527 +v 0.003769 -0.000635 0.005352 +v 0.001285 -0.002854 0.005794 +v 0.000258 -0.004763 -0.004510 +v 0.001837 -0.003898 -0.004969 +v 0.002224 -0.004763 -0.003934 +v 0.003871 -0.003225 -0.004232 +v 0.001236 0.003951 -0.005121 +v -0.000149 0.004763 -0.004524 +v 0.001770 0.004761 -0.004156 +v 0.004706 0.002752 -0.003663 +v -0.001604 -0.000541 -0.006349 +v -0.000665 0.000764 -0.006490 +v 0.000470 -0.000978 -0.006494 +v 0.001420 0.000544 -0.006403 +v 0.002039 -0.001307 -0.006116 +v 0.002656 -0.000049 -0.006004 +v 0.004865 -0.000728 -0.004356 +v 0.003932 0.000082 -0.005263 +v 0.004809 0.001000 -0.004376 +v 0.003438 -0.001129 -0.005473 +v -0.000791 -0.001698 -0.006293 +v 0.003630 -0.002126 -0.005050 +v 0.000009 -0.002727 -0.005976 +v 0.001107 -0.002976 -0.005758 +v 0.005051 -0.001904 -0.003748 +v 0.002489 -0.003068 -0.005242 +v -0.000010 -0.004057 -0.005162 +v -0.001725 -0.003447 -0.005333 +v -0.001537 -0.004761 -0.004269 +v -0.001789 -0.002138 -0.005946 +v -0.001704 -0.003765 0.005133 +v -0.001877 -0.004763 0.004146 +v -0.000049 -0.003326 0.005679 +v -0.001468 -0.002516 0.005880 +v -0.000894 -0.001541 0.006316 +v 0.000677 -0.001410 0.006385 +v 0.002111 -0.000830 0.006189 +v -0.002112 -0.000828 0.006189 +v 0.000018 -0.000130 0.006575 +v 0.002516 0.000868 0.006019 +v -0.001074 0.001043 0.006402 +v 0.001319 0.000983 0.006355 +v 0.004854 0.000863 0.004339 +v 0.003797 0.001400 0.005193 +v 0.000195 0.001817 0.006312 +v -0.001405 0.002486 0.005911 +v -0.002649 0.002045 0.005677 +v 0.001165 0.002780 0.005848 +v 0.002982 0.002519 0.005286 +v -0.000518 0.003411 0.005590 +v 0.002309 0.003588 0.004982 +v -0.002061 0.003708 0.005026 +v 0.000966 0.003933 0.005182 +v 0.001391 0.004761 0.004299 +v -0.000411 0.004761 0.004505 +v -0.002166 0.004761 0.003968 +v -0.003017 0.000177 0.005836 +v -0.003133 -0.002434 0.005248 +v -0.002826 -0.004758 -0.003519 +v -0.003338 -0.003488 -0.004468 +v -0.003123 -0.002103 -0.005380 +v -0.003248 -0.000899 -0.005643 +v -0.002213 0.000517 -0.006166 +v -0.003317 0.003692 0.004310 +v -0.003321 -0.003759 0.004236 +v -0.003733 0.000338 -0.005394 +v -0.003325 0.004762 0.003035 +v -0.004061 0.002254 0.004660 +v -0.003795 0.001000 0.005260 +v -0.003560 -0.001397 0.005333 +v -0.003758 -0.004757 0.002580 +v -0.003851 -0.004756 -0.002382 +v -0.004061 -0.003979 -0.003265 +v -0.004113 0.004093 0.003067 +v -0.001048 0.003952 -0.005157 +v -0.002729 0.003552 -0.004808 +v -0.004019 0.003079 -0.004182 +v -0.001735 0.002993 -0.005575 +v 0.000541 0.003178 -0.005716 +v 0.002762 0.002629 -0.005359 +v 0.003928 0.002304 -0.004743 +v -0.002821 0.001854 -0.005660 +v -0.000799 0.002328 -0.006099 +v 0.001759 0.002153 -0.005952 +v 0.000437 0.001641 -0.006346 +v 0.003288 0.001140 -0.005566 +v -0.004086 0.001691 -0.004854 +v -0.004175 0.004748 0.001804 +v -0.004387 -0.000378 0.004867 +v -0.004317 -0.002032 0.004532 +v -0.004368 -0.003406 0.003520 +v -0.004509 -0.001888 -0.004392 +v -0.004733 0.003208 0.003238 +v -0.004618 -0.002875 -0.003679 +v -0.004560 -0.000696 -0.004666 +v -0.004691 0.003559 -0.002935 +v -0.004803 0.001010 0.004369 +v -0.004995 0.000684 -0.004213 +v -0.005106 0.001961 -0.003630 +v -0.005328 -0.002214 0.003159 +v -0.005258 -0.003496 0.001833 +v -0.004401 -0.004755 0.001087 +v -0.004427 -0.004759 -0.001051 +v -0.005134 -0.003522 -0.002094 +v -0.005484 0.003609 -0.000326 +v -0.004454 0.004753 0.000830 +v -0.005512 0.003337 0.001348 +v -0.005553 0.001344 0.003257 +v -0.005378 -0.000373 0.003776 +v -0.005473 -0.003621 0.000353 +v -0.005256 -0.003863 -0.000639 +v -0.005370 -0.000902 -0.003677 +v -0.005584 0.002143 -0.002700 +v -0.005607 0.002969 -0.001673 +v -0.005686 0.002165 0.002468 +v -0.005694 -0.002227 -0.002435 +v -0.005704 0.000496 -0.003227 +v -0.005862 -0.002245 0.001961 +v -0.005844 -0.002813 -0.001009 +v -0.005954 0.002338 0.001448 +v -0.006061 0.002285 -0.001139 +v -0.006032 -0.000441 0.002559 +v -0.006122 -0.002331 0.000410 +v -0.006169 -0.000786 -0.002121 +v -0.006140 0.000698 -0.002218 +v -0.006247 0.001974 0.000426 +v -0.006245 0.001012 0.001747 +v -0.006344 -0.001044 0.001304 +v -0.006287 -0.001719 -0.000754 +v -0.006389 0.000741 -0.001344 +v -0.006375 0.000025 0.001525 +v -0.006458 -0.001106 0.000126 +v -0.002764 -0.004762 -0.002205 +v -0.001347 -0.004762 -0.003252 +v -0.003224 -0.004762 0.001553 +v -0.001409 -0.004762 0.003258 +v -0.003460 -0.004762 -0.000631 +v 0.003224 -0.004762 0.001553 +v 0.001191 -0.004762 0.003373 +v 0.003460 -0.004762 -0.000631 +v 0.002522 -0.004762 -0.002536 +v 0.000396 -0.004762 -0.003514 +v -0.003308 0.004761 -0.001426 +v -0.003224 0.004762 0.001553 +v -0.001361 0.004762 0.003285 +v 0.001247 0.004762 0.003344 +v -0.001534 0.004762 -0.003186 +v 0.002522 0.004762 -0.002536 +v 0.000396 0.004762 -0.003514 +v 0.003460 0.004762 -0.000631 +v 0.003224 0.004762 0.001553 +v 0.000497 -0.004446 0.003155 +v 0.000026 0.004448 0.003254 +v 0.001845 -0.004443 0.002621 +v 0.001951 0.004445 0.002554 +v 0.003025 -0.004444 0.001144 +v 0.003066 0.004444 0.001005 +v 0.003130 -0.004445 -0.000600 +v 0.003094 0.004446 -0.000814 +v 0.002584 -0.004444 -0.001911 +v 0.002204 0.004440 -0.002337 +v 0.001163 -0.004444 -0.002994 +v 0.000962 0.004445 -0.003037 +v -0.000388 0.004446 -0.003182 +v -0.000432 -0.004444 -0.003168 +v -0.002078 -0.004438 -0.002473 +v -0.002101 0.004444 -0.002456 +v -0.003094 -0.004446 -0.000814 +v -0.003101 0.004441 -0.000784 +v -0.003144 -0.004446 0.000540 +v -0.003050 0.004442 0.001046 +v -0.002578 -0.004444 0.001916 +v -0.001916 0.004444 0.002578 +v -0.001150 -0.004440 0.003000 +v 0.344296 0.002059 0.007332 +v 0.344197 0.003566 0.006640 +v 0.341616 0.002856 0.004201 +v 0.338676 0.003567 -0.000590 +v 0.340140 0.003568 -0.002188 +v 0.338327 0.002976 -0.001896 +v 0.338676 -0.003567 0.000590 +v 0.340140 -0.003568 0.002188 +v 0.338418 -0.003140 0.001622 +v 0.337704 -0.003335 -0.000487 +v 0.338951 -0.003570 -0.000986 +v 0.336575 -0.002965 0.001258 +v 0.336329 -0.003206 -0.000259 +v 0.338028 0.000001 0.003430 +v 0.337008 0.001420 0.002912 +v 0.336223 0.000402 0.003190 +v 0.336636 0.003128 -0.000732 +v 0.336637 0.003190 0.000302 +v 0.338734 0.003561 0.000673 +v 0.338744 -0.002976 -0.002092 +v 0.338314 0.002910 0.001973 +v 0.339824 0.003572 0.001888 +v 0.339764 -0.000952 0.003906 +v 0.340100 0.000314 0.004145 +v 0.338364 -0.002511 0.002466 +v 0.336615 -0.002289 0.002263 +v 0.336950 -0.002998 -0.001249 +v 0.339482 0.000749 -0.003826 +v 0.337013 0.000120 -0.003240 +v 0.337649 0.001297 -0.003073 +v 0.337043 0.002559 -0.002024 +v 0.336625 0.002962 0.001226 +v 0.336371 -0.001291 0.002950 +v 0.339797 -0.002452 0.003221 +v 0.340695 -0.003568 -0.002710 +v 0.339590 0.002379 -0.003136 +v 0.339695 0.002497 0.003136 +v 0.341778 0.003569 0.003757 +v 0.338018 -0.001325 0.003164 +v 0.341702 -0.003568 0.003694 +v 0.342068 0.001790 -0.005130 +v 0.341063 0.000655 -0.004673 +v 0.336342 0.001938 -0.002568 +v 0.341763 0.003562 -0.003774 +v 0.340087 -0.002332 -0.003422 +v 0.342225 -0.003557 -0.004289 +v 0.341060 -0.001681 0.004425 +v 0.342200 -0.000916 0.005480 +v 0.343702 0.000426 0.007074 +v 0.342603 0.000866 0.005877 +v 0.341163 0.001171 0.004607 +v 0.338927 0.001676 0.003307 +v 0.336922 0.002375 0.002171 +v 0.342358 -0.002544 0.005123 +v 0.343860 -0.003569 0.006265 +v 0.341992 -0.001399 -0.005153 +v 0.343452 -0.003572 -0.005796 +v 0.337120 -0.002478 -0.002099 +v 0.339689 -0.000883 -0.003873 +v 0.337612 -0.001301 -0.003095 +v 0.343998 0.001813 -0.007120 +v 0.342323 0.000004 -0.005661 +v 0.336270 -0.001329 -0.002935 +v 0.343895 0.003569 -0.006334 +v 0.359572 -0.000916 -0.001017 +v 0.359591 0.001035 -0.000539 +v 0.359644 0.000385 0.000346 +v 0.359590 -0.000980 0.000601 +v 0.343803 -0.001724 -0.006958 +v 0.344293 -0.001608 0.007428 +v 0.351102 0.002304 0.009227 +v 0.352669 0.003571 0.008516 +v 0.349297 0.003570 0.008818 +v 0.359322 0.002495 0.000696 +v 0.358931 0.003568 -0.000891 +v 0.358817 0.003571 0.001790 +v 0.358454 0.003572 -0.002986 +v 0.359250 0.002140 -0.001870 +v 0.352540 -0.003572 -0.008564 +v 0.353911 -0.002030 -0.008546 +v 0.355181 -0.003572 -0.007260 +v 0.356617 -0.003572 -0.005997 +v 0.357332 -0.002210 -0.005821 +v 0.357879 -0.003573 -0.004258 +v 0.358964 -0.003572 0.000486 +v 0.359304 -0.002491 -0.000684 +v 0.359233 -0.002649 0.001094 +v 0.358580 -0.003558 0.002713 +v 0.344724 -0.003571 -0.007026 +v 0.345299 -0.002118 -0.007931 +v 0.346818 -0.003575 -0.008229 +v 0.345555 0.003561 -0.007597 +v 0.345178 -0.003565 0.007368 +v 0.346994 -0.002318 0.008739 +v 0.346513 -0.003572 0.008089 +v 0.349204 -0.003575 0.008808 +v 0.346983 0.003573 0.008301 +v 0.347011 0.002457 0.008713 +v 0.346660 -0.001544 -0.008772 +v 0.349150 -0.003571 -0.008816 +v 0.349177 -0.001839 -0.009354 +v 0.351766 -0.001813 -0.009244 +v 0.344300 -0.000165 -0.007606 +v 0.347006 -0.000006 -0.009046 +v 0.349918 0.000000 -0.009566 +v 0.353212 0.000378 -0.009074 +v 0.355454 -0.000646 -0.007915 +v 0.344930 0.001134 -0.007942 +v 0.346658 0.001709 -0.008746 +v 0.349177 0.001836 -0.009355 +v 0.351766 0.001817 -0.009243 +v 0.353809 0.001817 -0.008633 +v 0.347739 0.003570 -0.008549 +v 0.349954 0.003571 -0.008837 +v 0.352192 0.003570 -0.008624 +v 0.354289 0.003570 -0.007800 +v 0.356078 0.003570 -0.006564 +v 0.355957 0.002274 -0.007211 +v 0.355847 0.000604 -0.007630 +v 0.356153 -0.002145 -0.007108 +v 0.346932 0.000802 0.008993 +v 0.345586 -0.000210 0.008435 +v 0.348075 -0.000711 0.009308 +v 0.349695 0.001190 0.009491 +v 0.350399 -0.000632 0.009527 +v 0.352567 0.000631 0.009219 +v 0.352496 -0.001791 0.009104 +v 0.354484 -0.001412 0.008422 +v 0.350025 -0.002140 0.009338 +v 0.355985 -0.000309 0.007579 +v 0.355970 -0.003558 0.006687 +v 0.351977 -0.003565 0.008655 +v 0.354346 -0.003572 0.007811 +v 0.357014 -0.003566 0.005570 +v 0.357474 -0.001587 0.005899 +v 0.357397 -0.000088 0.006197 +v 0.357143 0.001776 -0.006227 +v 0.357431 -0.000021 -0.006151 +v 0.357725 0.003567 -0.004565 +v 0.358037 -0.003570 0.003951 +v 0.358366 -0.001877 0.004445 +v 0.358299 0.001513 -0.004701 +v 0.358328 -0.000693 -0.004841 +v 0.358531 -0.002171 -0.004029 +v 0.358845 -0.000136 0.003943 +v 0.359011 0.001715 -0.003057 +v 0.358739 -0.003571 -0.002080 +v 0.357832 0.003571 0.004356 +v 0.358943 0.001776 0.003256 +v 0.356634 0.003570 0.005979 +v 0.357853 0.001809 0.005328 +v 0.355164 0.003573 0.007279 +v 0.356509 0.001934 0.006837 +v 0.353199 0.002419 0.008707 +v 0.354590 0.001607 0.008309 +v 0.358960 0.000011 -0.003599 +v 0.359258 -0.001404 0.002394 +v 0.359427 0.000050 -0.002158 +v 0.359309 -0.001623 -0.002016 +v 0.359481 0.000026 0.001831 +v 0.359496 0.001307 0.001253 +v 0.343599 0.003572 0.001424 +v 0.343865 0.003572 -0.002447 +v 0.351544 0.003572 0.006521 +v 0.354614 0.003572 0.004935 +v 0.355599 0.003572 -0.003811 +v 0.348904 0.003572 0.006506 +v 0.344660 0.003572 0.003740 +v 0.346516 0.003572 0.005618 +v 0.353734 0.003572 -0.005546 +v 0.348753 0.003572 -0.006476 +v 0.346309 0.003572 -0.005480 +v 0.351300 0.003572 -0.006569 +v 0.356771 0.003572 -0.000560 +v 0.356297 0.003572 0.002440 +v 0.349559 -0.003572 0.006651 +v 0.352960 -0.003572 0.006040 +v 0.355599 -0.003572 0.003811 +v 0.356771 -0.003572 0.000561 +v 0.346704 -0.003572 0.005696 +v 0.344502 -0.003572 0.003604 +v 0.354614 -0.003572 -0.004935 +v 0.356297 -0.003572 -0.002440 +v 0.343453 -0.003572 0.000312 +v 0.344026 -0.003572 -0.002641 +v 0.352320 -0.003572 -0.006243 +v 0.349808 -0.003572 -0.006667 +v 0.346137 -0.003572 -0.005409 +v 0.356620 0.000451 0.000813 +v 0.356623 -0.000814 0.000097 +v 0.356662 0.000008 -0.000356 +v 0.350650 0.004757 0.004507 +v 0.352409 0.004208 0.004477 +v 0.352646 0.004756 0.003764 +v 0.352180 -0.004758 -0.004053 +v 0.353373 -0.004086 -0.004019 +v 0.353886 -0.004760 -0.002537 +v 0.354898 -0.004103 -0.001866 +v 0.354632 -0.004758 -0.000277 +v 0.351621 -0.003690 0.005254 +v 0.349930 -0.004758 0.004546 +v 0.352261 -0.004760 0.003987 +v 0.347981 -0.003940 0.004825 +v 0.347767 -0.004761 0.003852 +v 0.343659 -0.000393 -0.001045 +v 0.343596 -0.000629 0.000143 +v 0.343619 0.000570 -0.000660 +v 0.343685 0.001268 0.000112 +v 0.343584 0.000201 0.000352 +v 0.343749 0.001095 0.001125 +v 0.343891 0.000571 -0.002018 +v 0.344088 0.002567 0.000221 +v 0.344306 -0.000390 -0.003037 +v 0.344609 0.001055 -0.003436 +v 0.344191 -0.002438 -0.001340 +v 0.343868 -0.001305 -0.001538 +v 0.344519 -0.001916 -0.002875 +v 0.344707 0.003681 -0.000596 +v 0.344523 0.003218 0.001326 +v 0.345058 0.004002 0.001205 +v 0.343912 -0.001702 0.001291 +v 0.343785 -0.001746 -0.000057 +v 0.344187 -0.002750 0.000543 +v 0.344744 -0.003571 0.001251 +v 0.343871 0.001789 -0.000882 +v 0.344749 -0.003490 -0.001432 +v 0.344995 -0.003185 -0.002580 +v 0.345618 0.004760 -0.000349 +v 0.345943 0.004761 -0.001673 +v 0.345203 0.003855 -0.002107 +v 0.344317 0.002697 -0.001485 +v 0.344159 0.002064 0.001878 +v 0.345863 0.004761 0.001575 +v 0.345781 0.003822 0.003147 +v 0.345617 -0.004756 0.000473 +v 0.345913 -0.004756 0.001712 +v 0.344758 -0.003748 -0.000765 +v 0.345777 -0.004763 -0.001212 +v 0.345060 0.003075 0.002886 +v 0.343667 -0.000155 0.001136 +v 0.344235 0.001045 0.002741 +v 0.345686 -0.004055 -0.002596 +v 0.346646 -0.004759 -0.002915 +v 0.346609 0.004760 -0.002852 +v 0.346753 0.004751 0.003054 +v 0.345033 0.002127 0.003546 +v 0.346564 -0.004754 0.002816 +v 0.345359 -0.003504 0.002888 +v 0.344450 -0.002337 0.002363 +v 0.345741 0.002798 0.004029 +v 0.344059 -0.000399 0.002529 +v 0.345312 0.003361 -0.003006 +v 0.347440 0.004746 0.003684 +v 0.347136 0.003517 0.004649 +v 0.347600 0.004758 -0.003794 +v 0.346234 0.003389 -0.004098 +v 0.344348 0.001963 -0.002471 +v 0.344867 0.000117 0.003961 +v 0.345688 0.001361 0.004639 +v 0.346197 -0.003540 0.003887 +v 0.346904 0.002367 0.005222 +v 0.346829 -0.003511 -0.004446 +v 0.345862 -0.002991 -0.004018 +v 0.348616 0.004752 0.004292 +v 0.348858 0.002863 0.005799 +v 0.346965 0.001112 0.005647 +v 0.349807 0.004763 -0.004511 +v 0.349154 0.003860 -0.005228 +v 0.347759 0.004029 -0.004570 +v 0.348316 -0.004759 -0.004191 +v 0.346073 0.001002 -0.005075 +v 0.347527 0.000246 -0.006039 +v 0.346066 -0.000508 -0.005135 +v 0.345166 0.000252 -0.004291 +v 0.351079 0.001753 -0.006277 +v 0.352028 0.000580 -0.006283 +v 0.349599 0.000078 -0.006565 +v 0.349121 0.001263 -0.006365 +v 0.347474 0.001489 -0.005828 +v 0.345304 0.001988 -0.004008 +v 0.349264 0.002441 -0.006032 +v 0.350863 0.002970 -0.005824 +v 0.347944 0.002789 -0.005525 +v 0.346805 0.002917 -0.004863 +v 0.350644 0.003984 -0.005186 +v 0.351793 0.004763 -0.004227 +v 0.352071 0.004111 -0.004715 +v 0.352526 0.002588 -0.005530 +v 0.352299 0.003335 0.005229 +v 0.350799 0.003292 0.005637 +v 0.349718 0.003944 0.005236 +v 0.352140 0.002099 0.005887 +v 0.350641 0.002201 0.006164 +v 0.348400 0.001667 0.006117 +v 0.349835 0.000688 0.006542 +v 0.352571 0.000448 0.006088 +v 0.350961 0.000848 0.006464 +v 0.348293 0.000232 0.006306 +v 0.347149 -0.000663 0.005822 +v 0.346157 0.000345 0.005227 +v 0.351747 -0.001126 0.006291 +v 0.348255 -0.000918 0.006242 +v 0.349885 -0.000906 0.006493 +v 0.346107 -0.000844 0.005115 +v 0.350859 -0.001831 0.006275 +v 0.345424 -0.001721 0.004280 +v 0.349169 -0.002242 0.006100 +v 0.344765 -0.001741 0.003366 +v 0.347585 -0.002523 0.005524 +v 0.346361 -0.002551 0.004760 +v 0.350652 -0.003267 0.005671 +v 0.344177 -0.001398 0.002413 +v 0.349170 -0.003437 0.005507 +v 0.352697 -0.003740 0.004735 +v 0.353256 0.003638 -0.004488 +v 0.353128 -0.002383 0.005338 +v 0.353373 0.004757 -0.003154 +v 0.353557 0.001984 -0.005217 +v 0.353693 0.000322 -0.005513 +v 0.352643 -0.000823 -0.006010 +v 0.353498 -0.001228 0.005506 +v 0.353354 0.002069 0.005324 +v 0.353848 -0.004745 0.002663 +v 0.354043 -0.003580 0.003887 +v 0.354012 0.000420 0.005285 +v 0.353681 0.003185 0.004543 +v 0.353755 0.004736 0.002802 +v 0.350632 -0.003823 -0.005313 +v 0.350433 -0.004763 -0.004511 +v 0.349105 -0.003271 -0.005638 +v 0.347813 -0.003457 -0.005071 +v 0.353135 -0.003214 -0.004884 +v 0.351496 -0.003035 -0.005673 +v 0.349929 -0.002624 -0.006022 +v 0.352554 -0.001850 -0.005827 +v 0.346666 -0.001688 -0.005347 +v 0.345153 -0.001270 -0.004124 +v 0.354236 -0.002287 -0.004556 +v 0.347728 -0.001484 -0.005944 +v 0.354196 -0.001192 -0.005014 +v 0.350882 -0.001128 -0.006431 +v 0.349121 -0.001385 -0.006340 +v 0.354632 -0.002034 0.004341 +v 0.354607 -0.000713 0.004751 +v 0.354563 0.001549 0.004594 +v 0.354277 0.003174 0.003916 +v 0.354026 0.003397 0.003995 +v 0.354175 0.003703 0.003546 +v 0.354644 0.003788 -0.002922 +v 0.354469 0.002705 -0.004035 +v 0.354600 0.000237 -0.004807 +v 0.354533 -0.003158 -0.003710 +v 0.354226 0.004762 -0.001861 +v 0.354806 0.001510 -0.004342 +v 0.354774 0.003044 0.003534 +v 0.354608 0.003080 0.003623 +v 0.354608 0.003484 0.003237 +v 0.355343 -0.001492 -0.003710 +v 0.355266 -0.003023 -0.002802 +v 0.355211 -0.003944 0.001328 +v 0.354382 -0.004764 0.001527 +v 0.355309 -0.002896 0.002798 +v 0.355428 0.000440 0.003844 +v 0.355485 0.002825 0.002552 +v 0.355267 0.003807 0.001471 +v 0.354230 0.004755 0.001937 +v 0.354592 0.004754 -0.000728 +v 0.355164 0.003792 -0.001900 +v 0.355625 -0.000201 -0.003575 +v 0.355431 -0.003830 -0.000500 +v 0.355345 -0.002262 0.003321 +v 0.355782 0.001375 0.003046 +v 0.354604 0.004756 0.000576 +v 0.355543 0.003674 -0.000494 +v 0.355390 0.002811 -0.002744 +v 0.355534 0.001262 -0.003493 +v 0.355797 -0.001092 0.003122 +v 0.356014 -0.002800 -0.000805 +v 0.355877 -0.003109 0.000513 +v 0.355831 -0.002674 0.001825 +v 0.355896 0.003056 0.000671 +v 0.356024 0.002699 -0.001048 +v 0.355999 -0.001126 -0.002646 +v 0.356066 -0.002047 -0.001898 +v 0.356159 -0.001730 0.001941 +v 0.356196 -0.000073 0.002507 +v 0.356061 0.001993 -0.001949 +v 0.355921 0.001298 -0.002828 +v 0.356251 0.001522 0.001802 +v 0.356318 0.000563 -0.002108 +v 0.356407 -0.001852 0.000416 +v 0.356369 0.001974 0.000395 +v 0.356478 -0.000605 -0.001511 +v 0.356478 -0.001434 -0.000734 +v 0.356506 -0.000747 0.001288 +v 0.356560 0.001183 -0.000416 +v 0.356561 0.000670 -0.001060 +v 0.352744 0.004762 0.002344 +v 0.353562 0.004762 0.000803 +v 0.351167 0.004762 0.003390 +v 0.351288 0.004762 -0.003337 +v 0.353279 0.004761 -0.001746 +v 0.348740 0.004761 -0.003331 +v 0.346656 0.004761 0.001000 +v 0.346934 0.004762 -0.001539 +v 0.348567 0.004762 0.003224 +v 0.353513 -0.004762 -0.000921 +v 0.353562 -0.004762 0.000803 +v 0.351288 -0.004762 0.003337 +v 0.348675 -0.004761 0.003291 +v 0.352745 -0.004762 0.002345 +v 0.346687 -0.004762 -0.000829 +v 0.347534 -0.004762 -0.002382 +v 0.352620 -0.004762 -0.002501 +v 0.346835 -0.004762 0.001361 +v 0.350907 -0.004762 -0.003447 +v 0.348952 -0.004762 -0.003337 +v 0.350070 0.004448 0.003194 +v 0.348970 -0.004440 0.003000 +v 0.348756 0.004446 0.002901 +v 0.347476 -0.004446 0.001841 +v 0.347630 0.004444 0.001998 +v 0.347015 0.004446 0.000782 +v 0.346965 -0.004446 0.000450 +v 0.347089 0.004444 -0.001129 +v 0.347026 -0.004446 -0.000815 +v 0.348041 -0.004438 -0.002472 +v 0.348319 0.004444 -0.002661 +v 0.349687 -0.004444 -0.003168 +v 0.349581 0.004445 -0.003136 +v 0.350901 0.004445 -0.003118 +v 0.351207 -0.004446 -0.003016 +v 0.352224 0.004446 -0.002400 +v 0.352582 -0.004445 -0.002063 +v 0.353159 0.004442 -0.001075 +v 0.353239 -0.004444 -0.000685 +v 0.353253 0.004445 0.000635 +v 0.353243 -0.004444 0.000672 +v 0.352692 0.004446 0.001902 +v 0.352766 -0.004446 0.001776 +v 0.351885 -0.004444 0.002667 +v 0.351453 0.004445 0.002924 +v 0.350617 -0.004446 0.003155 +v 0.329256 0.004637 -0.001573 +v 0.329257 0.004737 0.001397 +v 0.329256 0.003064 0.003820 +v 0.329256 0.003495 -0.003387 +v 0.329257 0.001397 -0.004737 +v 0.329256 0.001186 0.004720 +v 0.329257 -0.001397 0.004737 +v 0.329256 -0.001186 -0.004720 +v 0.329256 -0.003064 -0.003819 +v 0.329256 -0.003495 0.003387 +v 0.329256 -0.004637 0.001573 +v 0.329257 -0.004737 -0.001397 +v 0.327060 -0.000552 0.003405 +v 0.327060 0.001139 -0.003183 +v 0.327060 -0.000851 -0.003302 +v 0.327060 0.003105 0.001427 +v 0.327060 0.003331 -0.000589 +v 0.327060 0.002580 -0.002194 +v 0.327060 0.001736 0.002906 +v 0.327060 -0.002580 -0.002194 +v 0.327060 -0.002580 0.002194 +v 0.327060 -0.003443 -0.000000 +v 0.021756 -0.001186 0.004720 +v 0.021756 -0.001776 -0.004563 +v 0.021756 -0.003820 -0.003064 +v 0.021756 0.004854 0.000349 +v 0.021756 0.002731 -0.004115 +v 0.021756 0.004115 0.002731 +v 0.021756 0.004563 -0.001776 +v 0.021756 0.001397 0.004737 +v 0.021756 0.000349 -0.004854 +v 0.021756 -0.004720 -0.001186 +v 0.021755 -0.004737 0.001397 +v 0.021756 -0.003064 0.003820 +v 0.024000 0.002793 -0.001971 +v 0.024000 0.003392 0.000314 +v 0.024000 0.002580 0.002194 +v 0.024000 0.000851 0.003302 +v 0.024000 0.001139 -0.003183 +v 0.024000 -0.000851 -0.003302 +v 0.024000 -0.001763 0.002972 +v 0.024000 -0.002580 -0.002194 +v 0.024000 -0.003049 0.001417 +v 0.024000 -0.003399 -0.000285 +v 0.320754 -0.006349 0.000553 +v 0.030258 -0.006157 -0.001647 +v 0.320754 -0.006156 -0.001652 +v 0.030258 -0.005222 -0.003654 +v 0.320754 -0.005220 -0.003657 +v 0.030258 -0.003657 -0.005220 +v 0.320754 -0.003654 -0.005222 +v 0.030258 -0.001652 -0.006156 +v 0.320754 -0.001648 -0.006157 +v 0.030258 0.000553 -0.006349 +v 0.320765 0.001117 -0.006314 +v 0.030247 0.003203 -0.005555 +v 0.320754 0.003657 -0.005220 +v 0.030258 0.005220 -0.003657 +v 0.320765 0.005555 -0.003203 +v 0.030247 0.006314 -0.001117 +v 0.320754 0.006349 -0.000553 +v 0.030258 0.006157 0.001647 +v 0.320754 0.006156 0.001652 +v 0.030258 0.005222 0.003654 +v 0.320754 0.005220 0.003657 +v 0.030258 0.003657 0.005220 +v 0.320765 0.003203 0.005555 +v 0.030247 0.001117 0.006314 +v 0.320754 0.000553 0.006349 +v 0.030258 -0.001647 0.006157 +v 0.320754 -0.001652 0.006156 +v 0.030258 -0.003654 0.005222 +v 0.320754 -0.003657 0.005220 +v 0.030258 -0.005220 0.003657 +v 0.320765 -0.005555 0.003203 +v 0.030247 -0.006314 0.001117 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vn 0.6385 0.1744 -0.7496 +vn 0.6752 0.3227 -0.6633 +vn 0.6595 0.1875 -0.7280 +vn 0.1535 -0.9820 -0.1102 +vn 0.2226 -0.9302 -0.2919 +vn 0.2564 -0.8102 -0.5271 +vn 0.1115 -0.9736 0.1990 +vn 0.1833 -0.9517 0.2463 +vn 0.1499 0.9826 0.1093 +vn 0.2226 0.9302 0.2919 +vn 0.2547 0.8087 0.5302 +vn 0.1911 0.9510 -0.2429 +vn 0.1866 0.9514 -0.2452 +vn 0.0925 0.9956 0.0172 +vn 0.0789 -0.9846 -0.1560 +vn 0.4281 -0.0311 0.9032 +vn 0.2749 -0.3932 0.8774 +vn 0.1095 0.0654 0.9918 +vn 0.0707 -0.2693 0.9605 +vn 0.0976 0.9026 0.4192 +vn 0.2636 0.8235 -0.5023 +vn 0.0886 -0.8748 -0.4763 +vn 0.2219 -0.7700 0.5982 +vn 0.0489 0.9072 -0.4178 +vn 0.4114 0.5543 0.7235 +vn 0.0911 0.6804 0.7271 +vn 0.4012 0.5693 -0.7176 +vn 0.5356 0.5776 -0.6160 +vn 0.4506 -0.1995 -0.8702 +vn 0.3508 -0.0272 -0.9360 +vn 0.2667 -0.4703 -0.8413 +vn 0.1047 -0.0705 -0.9920 +vn 0.4170 -0.5530 -0.7213 +vn 0.0902 -0.6737 -0.7335 +vn 0.4134 -0.5958 0.6886 +vn 0.5742 -0.4761 0.6661 +vn 0.5077 0.2084 0.8360 +vn 0.2650 0.4684 0.8428 +vn 0.5568 0.5158 0.6511 +vn 0.0688 -0.3907 -0.9179 +vn 0.5603 -0.5118 -0.6512 +vn 0.6673 0.2331 0.7074 +vn 0.5302 0.4298 0.7309 +vn 0.0688 0.3907 0.9179 +vn 0.5272 -0.4403 -0.7267 +vn 0.6638 -0.2682 -0.6982 +vn 0.6327 -0.0385 0.7734 +vn 0.6420 -0.2839 0.7122 +vn 0.4567 -0.3567 0.8150 +vn 0.0765 -0.6608 0.7467 +vn 0.6709 0.2895 0.6827 +vn 0.5940 0.3938 -0.7015 +vn 0.1950 0.7540 -0.6272 +vn 0.5038 0.1386 -0.8526 +vn 0.6821 -0.0782 -0.7270 +vn 0.2848 0.3512 -0.8919 +vn 0.0794 0.6140 -0.7853 +vn 0.0699 0.2659 -0.9615 +vn 0.6661 -0.3083 -0.6792 +vn 0.0234 -0.8864 0.4624 +vn -0.9932 -0.0680 -0.0945 +vn -0.9884 -0.1338 0.0725 +vn -0.9974 0.0719 -0.0015 +vn 0.6180 -0.2114 -0.7572 +vn 0.6328 -0.0266 -0.7738 +vn 0.6025 0.0110 0.7981 +vn -0.0996 -0.2313 0.9678 +vn -0.1828 -0.3278 0.9269 +vn 0.0793 -0.2978 0.9513 +vn -0.9638 -0.2578 -0.0675 +vn -0.9370 -0.3306 -0.1130 +vn -0.9470 -0.2951 0.1268 +vn -0.8783 -0.3171 -0.3579 +vn -0.9306 -0.2174 -0.2944 +vn -0.5093 -0.3017 -0.8060 +vn -0.7290 -0.3166 -0.6069 +vn -0.6267 -0.1993 -0.7533 +vn 0.3772 0.3249 -0.8673 +vn 0.3166 0.2095 -0.9251 +vn 0.0883 0.3138 -0.9454 +vn -0.2366 0.2987 -0.9246 +vn -0.4596 0.2597 -0.8493 +vn -0.5435 0.3190 -0.7764 +vn -0.6847 0.3093 -0.6599 +vn -0.7683 0.2709 -0.5799 +vn -0.8412 0.3149 -0.4397 +vn -0.8498 0.3152 0.4226 +vn -0.9375 0.3014 0.1738 +vn -0.9267 0.1982 0.3192 +vn 0.6109 -0.3091 0.7289 +vn 0.5813 0.3094 -0.7526 +vn 0.6366 -0.1930 0.7467 +vn 0.4750 0.1851 -0.8603 +vn 0.4668 -0.2745 -0.8407 +vn 0.5947 0.1758 0.7845 +vn 0.5305 0.2727 0.8026 +vn 0.3369 0.2296 0.9131 +vn 0.3759 0.3092 0.8736 +vn 0.0609 0.2739 0.9598 +vn 0.4755 -0.2191 0.8520 +vn 0.3422 -0.3117 0.8865 +vn 0.2477 -0.2146 0.9448 +vn 0.0718 0.2105 -0.9749 +vn -0.1682 0.1133 -0.9792 +vn -0.3396 0.1611 -0.9267 +vn 0.2432 0.0218 -0.9697 +vn -0.5332 0.0365 -0.8452 +vn 0.4651 -0.0680 -0.8826 +vn -0.0075 -0.0116 -0.9999 +vn -0.3850 -0.0455 -0.9218 +vn 0.2545 -0.1903 -0.9482 +vn -0.0605 -0.1940 -0.9791 +vn -0.3469 -0.1928 -0.9179 +vn 0.1400 -0.3011 -0.9433 +vn -0.2165 -0.3099 -0.9258 +vn 0.0650 -0.1066 0.9922 +vn 0.2466 0.0361 0.9684 +vn 0.0887 0.1660 0.9821 +vn -0.1097 0.0732 0.9913 +vn -0.6386 -0.1343 0.7577 +vn -0.4746 0.0491 0.8788 +vn -0.5933 0.1654 0.7878 +vn 0.4119 -0.0270 0.9108 +vn -0.2793 0.0703 0.9576 +vn -0.3496 0.2385 0.9060 +vn -0.1697 0.2624 0.9499 +vn -0.4719 0.3014 0.8285 +vn -0.7098 0.2775 0.6474 +vn -0.6304 0.1950 -0.7514 +vn -0.7283 0.1147 0.6755 +vn -0.7192 0.0428 -0.6934 +vn -0.8158 -0.2440 -0.5244 +vn -0.8145 -0.0725 -0.5756 +vn -0.8494 0.2094 0.4844 +vn -0.8550 0.0305 0.5177 +vn -0.8586 0.1378 -0.4938 +vn -0.9178 0.2644 -0.2961 +vn -0.9264 0.3191 -0.1999 +vn -0.9031 -0.0400 -0.4275 +vn -0.9302 0.0985 -0.3537 +vn -0.7650 -0.2880 0.5761 +vn -0.8579 -0.1985 0.4739 +vn -0.8907 -0.2952 0.3458 +vn -0.6191 -0.2806 0.7335 +vn -0.7398 -0.1600 0.6535 +vn -0.3130 -0.1729 0.9339 +vn -0.4065 -0.3042 0.8615 +vn -0.4977 -0.1694 0.8506 +vn -0.9382 -0.0552 0.3416 +vn -0.9535 -0.1997 0.2256 +vn -0.9737 -0.0530 -0.2217 +vn -0.9758 0.1728 -0.1338 +vn -0.9595 0.2803 -0.0276 +vn -0.9740 0.1973 0.1112 +vn -0.9811 0.0325 0.1910 +vn -0.0001 -1.0000 0.0006 +vn 0.0000 -1.0000 0.0008 +vn -0.0004 -1.0000 0.0006 +vn 0.0011 -1.0000 -0.0000 +vn 0.0016 -1.0000 0.0016 +vn -0.0010 -1.0000 0.0007 +vn -0.0013 -1.0000 0.0008 +vn -0.0002 -1.0000 -0.0005 +vn -0.0003 -1.0000 -0.0007 +vn -0.0001 -1.0000 -0.0002 +vn -0.0001 -1.0000 0.0007 +vn 0.0011 -1.0000 0.0002 +vn -0.0001 -1.0000 -0.0001 +vn -0.0001 -1.0000 0.0009 +vn 0.0018 -1.0000 0.0032 +vn 0.0021 -1.0000 0.0011 +vn 0.0026 -1.0000 0.0010 +vn -0.0003 -1.0000 -0.0009 +vn 0.0006 -1.0000 0.0007 +vn 0.0012 -1.0000 -0.0012 +vn 0.0009 -1.0000 -0.0017 +vn 0.0002 -1.0000 -0.0011 +vn -0.0015 -1.0000 0.0001 +vn -0.0009 -1.0000 0.0008 +vn -0.0011 -1.0000 -0.0000 +vn -0.0003 -1.0000 -0.0010 +vn -0.0003 -1.0000 -0.0008 +vn -0.0002 -1.0000 -0.0007 +vn -0.0007 -1.0000 0.0005 +vn -0.0004 -1.0000 0.0012 +vn -0.0015 -1.0000 0.0002 +vn 0.0006 -1.0000 -0.0007 +vn -0.0015 1.0000 0.0003 +vn -0.0007 1.0000 0.0010 +vn -0.0009 1.0000 0.0018 +vn -0.0010 1.0000 0.0043 +vn -0.0013 1.0000 0.0013 +vn -0.0005 1.0000 0.0012 +vn -0.0017 1.0000 0.0015 +vn -0.0017 1.0000 -0.0001 +vn -0.0015 1.0000 0.0005 +vn 0.0011 1.0000 0.0002 +vn 0.0005 1.0000 -0.0001 +vn -0.0025 1.0000 0.0013 +vn -0.0003 1.0000 -0.0001 +vn -0.0005 1.0000 -0.0001 +vn -0.0002 1.0000 -0.0002 +vn -0.0003 1.0000 -0.0003 +vn 0.0009 1.0000 -0.0000 +vn 0.0012 1.0000 0.0012 +vn -0.0003 1.0000 0.0019 +vn 0.0046 1.0000 0.0026 +vn -0.0016 1.0000 0.0006 +vn 0.0001 1.0000 -0.0002 +vn -0.0009 1.0000 0.0007 +vn -0.0002 1.0000 0.0000 +vn 0.0000 1.0000 -0.0007 +vn 0.0020 1.0000 0.0006 +vn 0.0001 1.0000 -0.0001 +vn -0.0000 1.0000 0.0000 +vn -0.0004 1.0000 -0.0000 +vn -0.0005 1.0000 -0.0005 +vn 0.0008 1.0000 0.0004 +vn 0.0014 1.0000 0.0006 +vn 0.0000 1.0000 0.0006 +vn 0.0008 1.0000 -0.0004 +vn 0.1117 -0.0185 -0.9936 +vn -0.1211 0.0206 -0.9924 +vn 0.3367 0.0181 -0.9414 +vn 0.5494 -0.0202 -0.8353 +vn 0.7198 0.0179 -0.6939 +vn 0.8836 -0.0195 -0.4678 +vn 0.9528 0.0168 -0.3033 +vn 0.9995 -0.0156 -0.0261 +vn 0.9904 0.0151 0.1374 +vn 0.9300 -0.0137 0.3673 +vn 0.8523 0.0158 0.5228 +vn 0.7132 -0.0163 0.7008 +vn 0.5417 0.0181 0.8404 +vn 0.3367 -0.0181 0.9414 +vn 0.1117 0.0185 0.9936 +vn -0.1211 -0.0206 0.9924 +vn -0.3354 0.0184 0.9419 +vn -0.6118 -0.0222 0.7907 +vn -0.7267 0.0090 0.6869 +vn -0.8289 -0.0206 0.5591 +vn -0.8530 -0.0007 0.5219 +vn -1.0000 -0.0046 -0.0088 +vn -0.9996 0.0125 0.0239 +vn -1.0000 0.0046 0.0088 +vn -0.9996 -0.0125 -0.0239 +vn -0.8530 0.0007 -0.5219 +vn -0.8289 0.0206 -0.5591 +vn -0.7267 -0.0090 -0.6869 +vn -0.6118 0.0222 -0.7907 +vn -0.3354 -0.0184 -0.9419 +vn -0.9904 -0.0773 -0.1142 +vn -0.9949 0.0201 0.0990 +vn -0.9932 0.1156 -0.0096 +vn -0.3479 0.6845 -0.6407 +vn -0.5148 0.6477 -0.5617 +vn -0.6098 0.6858 -0.3973 +vn -0.7342 0.6392 -0.2290 +vn -0.7314 0.6782 -0.0710 +vn 0.6447 0.6966 0.3148 +vn 0.4587 0.6713 0.5821 +vn 0.6299 0.6231 0.4637 +vn 0.9889 0.1300 -0.0717 +vn 0.9975 -0.0604 -0.0355 +vn 0.9636 0.0839 -0.2538 +vn 0.9741 -0.2131 -0.0755 +vn 0.9729 -0.1280 0.1928 +vn 0.9929 0.0301 0.1149 +vn 0.9339 -0.3559 0.0334 +vn 0.9619 -0.0996 -0.2545 +vn 0.8793 0.0235 -0.4757 +vn 0.8873 -0.1748 -0.4268 +vn 0.9173 0.3521 0.1861 +vn 0.9350 0.3502 -0.0558 +vn 0.8420 0.5282 0.1099 +vn 0.9746 0.2052 0.0895 +vn 0.8664 0.3760 -0.3285 +vn 0.9339 0.2439 -0.2613 +vn 0.8478 0.2242 -0.4806 +vn 0.8916 -0.4065 0.1995 +vn 0.8237 -0.5670 0.0007 +vn 0.7494 -0.6580 -0.0740 +vn 0.7002 -0.6564 -0.2808 +vn 0.7971 -0.5626 -0.2191 +vn 0.9058 -0.3683 -0.2096 +vn 0.7400 -0.6556 0.1504 +vn 0.7574 -0.5845 0.2913 +vn 0.9125 -0.2159 0.3475 +vn 0.5921 -0.6758 0.4391 +vn 0.7935 -0.4149 0.4453 +vn 0.7522 0.6569 0.0510 +vn 0.7536 0.5867 0.2962 +vn 0.8335 0.5395 -0.1190 +vn 0.7317 0.6488 -0.2088 +vn 0.7729 0.5427 -0.3287 +vn 0.6398 0.6588 -0.3958 +vn 0.6254 0.6011 -0.4975 +vn 0.6217 -0.6121 0.4887 +vn 0.8306 -0.2106 0.5155 +vn 0.5436 -0.6272 -0.5577 +vn 0.7152 -0.5467 -0.4354 +vn 0.8562 0.3801 0.3499 +vn 0.8447 -0.3809 -0.3760 +vn 0.6038 -0.5018 0.6194 +vn 0.3742 -0.6630 0.6484 +vn 0.4000 -0.5824 0.7077 +vn 0.6221 -0.3350 0.7076 +vn 0.9270 0.0056 0.3750 +vn 0.9330 0.1647 0.3201 +vn 0.4650 0.6674 -0.5818 +vn 0.7334 -0.1400 0.6653 +vn 0.5058 0.5700 0.6475 +vn 0.7926 0.3567 0.4945 +vn 0.4891 0.5651 -0.6643 +vn 0.8338 0.0695 0.5477 +vn 0.4250 -0.3645 0.8286 +vn 0.6672 0.4188 0.6160 +vn 0.0989 -0.6366 0.7648 +vn 0.5674 -0.0910 0.8184 +vn 0.2017 -0.4383 0.8759 +vn 0.0543 -0.6860 -0.7256 +vn 0.2832 -0.6085 -0.7413 +vn 0.3792 -0.6353 -0.6727 +vn 0.5841 -0.5007 -0.6389 +vn 0.1948 0.5994 -0.7764 +vn -0.0222 0.6749 -0.7376 +vn 0.2964 0.6622 -0.6882 +vn 0.7205 0.4182 -0.5532 +vn -0.2389 -0.0886 -0.9670 +vn -0.0999 0.1071 -0.9892 +vn 0.0695 -0.1426 -0.9873 +vn 0.2140 0.0810 -0.9735 +vn 0.3052 -0.2134 -0.9281 +vn 0.4010 0.0012 -0.9161 +vn 0.7401 -0.1103 -0.6634 +vn 0.6036 0.0114 -0.7972 +vn 0.7326 0.1521 -0.6635 +vn 0.5258 -0.1752 -0.8323 +vn -0.1157 -0.2554 -0.9599 +vn 0.5539 -0.3186 -0.7692 +vn -0.0087 -0.4132 -0.9106 +vn 0.1738 -0.4395 -0.8813 +vn 0.7612 -0.3003 -0.5748 +vn 0.3912 -0.4554 -0.7997 +vn -0.0102 -0.6114 -0.7912 +vn -0.2609 -0.5279 -0.8082 +vn -0.2607 -0.6482 -0.7154 +vn -0.2777 -0.3258 -0.9037 +vn -0.2488 -0.5767 0.7781 +vn -0.3002 -0.6777 0.6712 +vn -0.0106 -0.5108 0.8596 +vn -0.2286 -0.3798 0.8964 +vn -0.1216 -0.2357 0.9642 +vn 0.1002 -0.2224 0.9698 +vn 0.3232 -0.1295 0.9374 +vn -0.3147 -0.1213 0.9414 +vn 0.0015 -0.0150 0.9999 +vn 0.3854 0.1372 0.9125 +vn -0.1771 0.1463 0.9733 +vn 0.1978 0.1470 0.9692 +vn 0.7319 0.1343 0.6680 +vn 0.5823 0.2035 0.7871 +vn 0.0250 0.2770 0.9606 +vn -0.2054 0.3771 0.9031 +vn -0.4029 0.3072 0.8622 +vn 0.1868 0.4098 0.8928 +vn 0.4456 0.3808 0.8102 +vn -0.0761 0.5227 0.8491 +vn 0.3500 0.5533 0.7559 +vn -0.3081 0.5644 0.7659 +vn 0.1381 0.6032 0.7856 +vn 0.2378 0.6741 0.6993 +vn -0.0769 0.6619 0.7456 +vn -0.3488 0.6719 0.6533 +vn -0.4510 0.0331 0.8919 +vn -0.4612 -0.3813 0.8012 +vn -0.4632 -0.6585 -0.5932 +vn -0.4992 -0.5309 -0.6848 +vn -0.4787 -0.3285 -0.8142 +vn -0.4893 -0.1385 -0.8610 +vn -0.3366 0.0904 -0.9373 +vn -0.5083 0.5550 0.6585 +vn -0.5026 -0.5787 0.6423 +vn -0.5688 0.0545 -0.8207 +vn -0.5285 0.6818 0.5058 +vn -0.6217 0.3544 0.6985 +vn -0.5767 0.1475 0.8035 +vn -0.5351 -0.1930 0.8224 +vn -0.6229 -0.6483 0.4379 +vn -0.6417 -0.6594 -0.3917 +vn -0.6220 -0.6059 -0.4959 +vn -0.6382 0.6193 0.4574 +vn -0.1531 0.6069 -0.7799 +vn -0.4181 0.5349 -0.7342 +vn -0.6108 0.4592 -0.6450 +vn -0.2702 0.4484 -0.8520 +vn 0.0730 0.4836 -0.8722 +vn 0.4102 0.4105 -0.8144 +vn 0.6029 0.3464 -0.7187 +vn -0.4230 0.2858 -0.8599 +vn -0.1294 0.3498 -0.9278 +vn 0.2697 0.3246 -0.9066 +vn 0.0682 0.2485 -0.9662 +vn 0.4921 0.1797 -0.8518 +vn -0.6210 0.2660 -0.7373 +vn -0.7098 0.6317 0.3116 +vn -0.6658 -0.0601 0.7437 +vn -0.6670 -0.3107 0.6772 +vn -0.6693 -0.5218 0.5289 +vn -0.6829 -0.2938 -0.6689 +vn -0.7281 0.4794 0.4899 +vn -0.7120 -0.4315 -0.5539 +vn -0.6875 -0.1002 -0.7192 +vn -0.7152 0.5383 -0.4457 +vn -0.7336 0.1602 0.6604 +vn -0.7536 0.1013 -0.6495 +vn -0.7718 0.3040 -0.5586 +vn -0.8087 -0.3301 0.4869 +vn -0.7933 -0.5378 0.2853 +vn -0.7328 -0.6591 0.1689 +vn -0.7353 -0.6581 -0.1623 +vn -0.7749 -0.5423 -0.3248 +vn -0.8372 0.5458 -0.0356 +vn -0.7607 0.6362 0.1286 +vn -0.8278 0.5212 0.2075 +vn -0.8415 0.2046 0.5000 +vn -0.8175 -0.0664 0.5721 +vn -0.8284 -0.5570 0.0594 +vn -0.7945 -0.5998 -0.0948 +vn -0.8221 -0.1480 -0.5498 +vn -0.8556 0.3230 -0.4045 +vn -0.8458 0.4628 -0.2653 +vn -0.8589 0.3402 0.3827 +vn -0.8631 -0.3325 -0.3801 +vn -0.8690 0.0733 -0.4893 +vn -0.8950 -0.3362 0.2931 +vn -0.8904 -0.4285 -0.1536 +vn -0.9124 0.3483 0.2150 +vn -0.9279 0.3348 -0.1643 +vn -0.9154 -0.0693 0.3966 +vn -0.9297 -0.3613 0.0713 +vn -0.9376 -0.1229 -0.3251 +vn -0.9325 0.1164 -0.3418 +vn -0.9522 0.3003 0.0554 +vn -0.9509 0.1556 0.2675 +vn -0.9643 -0.1705 0.2026 +vn -0.9559 -0.2640 -0.1290 +vn -0.9731 0.1192 -0.1973 +vn -0.9700 0.0052 0.2429 +vn -0.9852 -0.1691 0.0290 +vn -0.0039 -1.0000 -0.0029 +vn -0.0031 -1.0000 -0.0023 +vn -0.0017 -1.0000 -0.0009 +vn -0.0040 -1.0000 0.0019 +vn -0.0053 -1.0000 0.0019 +vn 0.0012 -1.0000 0.0020 +vn 0.0019 -1.0000 -0.0001 +vn -0.0049 -1.0000 -0.0038 +vn -0.0037 -1.0000 0.0004 +vn -0.0036 -1.0000 -0.0005 +vn 0.0036 -1.0000 -0.0008 +vn 0.0100 -0.9999 0.0046 +vn 0.0013 -1.0000 -0.0011 +vn -0.0059 -1.0000 0.0011 +vn -0.0021 -1.0000 0.0075 +vn -0.0009 -1.0000 0.0097 +vn 0.0024 -1.0000 -0.0020 +vn 0.0056 -1.0000 -0.0063 +vn 0.0033 -1.0000 -0.0004 +vn 0.0128 -0.9999 -0.0083 +vn -0.0018 -1.0000 -0.0006 +vn -0.0003 -1.0000 0.0007 +vn -0.0001 -1.0000 0.0010 +vn 0.0076 -1.0000 -0.0009 +vn -0.0016 -1.0000 0.0043 +vn 0.0218 -0.9997 -0.0123 +vn 0.0013 1.0000 0.0014 +vn -0.0021 1.0000 0.0015 +vn -0.0086 1.0000 0.0022 +vn -0.0117 0.9999 0.0074 +vn -0.0135 0.9999 0.0045 +vn -0.0002 1.0000 0.0009 +vn -0.0001 1.0000 0.0009 +vn 0.0003 1.0000 0.0009 +vn -0.0002 1.0000 0.0012 +vn 0.0022 1.0000 0.0019 +vn -0.0036 1.0000 0.0000 +vn 0.0003 1.0000 0.0010 +vn 0.0007 1.0000 0.0011 +vn 0.0038 1.0000 -0.0023 +vn 0.0014 1.0000 -0.0009 +vn 0.0005 1.0000 0.0003 +vn 0.0050 1.0000 -0.0006 +vn 0.0048 1.0000 -0.0015 +vn 0.0049 1.0000 -0.0030 +vn 0.0048 1.0000 -0.0001 +vn 0.0021 1.0000 -0.0003 +vn 0.0006 1.0000 0.0007 +vn 0.0017 1.0000 -0.0008 +vn 0.0004 1.0000 0.0008 +vn 0.0046 1.0000 -0.0026 +vn -0.0420 -0.2095 -0.9769 +vn -0.0112 -0.0089 -0.9999 +vn -0.3645 -0.0083 -0.9312 +vn -0.3417 -0.0030 -0.9398 +vn -0.7813 0.0046 -0.6242 +vn -0.8077 -0.0041 -0.5896 +vn -0.7854 0.0033 -0.6189 +vn -0.8116 -0.0054 -0.5842 +vn -0.9982 0.0037 -0.0601 +vn -0.9998 -0.0034 -0.0209 +vn -0.9861 0.0042 0.1659 +vn -0.9679 -0.0080 0.2512 +vn -0.7931 0.0078 0.6090 +vn -0.7002 -0.0088 0.7139 +vn -0.3679 0.0065 0.9298 +vn -0.3021 -0.0022 0.9533 +vn 0.1454 0.0009 0.9894 +vn 0.1455 0.0008 0.9894 +vn 0.3891 -0.0005 0.9212 +vn 0.3902 -0.0008 0.9207 +vn 0.8528 0.0012 0.5223 +vn 0.8575 -0.0007 0.5145 +vn 0.9575 0.0008 0.2885 +vn 0.9668 -0.0048 0.2553 +vn 0.9851 0.0056 -0.1721 +vn 0.9458 -0.0114 -0.3246 +vn 0.7931 0.0115 -0.6090 +vn 0.5926 -0.0147 -0.8054 +vn 0.2959 -0.3935 -0.8704 +vn -0.0857 0.7227 0.6858 +vn 0.1199 0.6265 0.7701 +vn -0.2989 0.6075 0.7360 +vn -0.4918 0.7288 0.4764 +vn -0.4490 0.7467 0.4907 +vn -0.6883 0.6892 0.2265 +vn -0.6963 0.7105 0.1017 +vn -0.7290 0.6664 -0.1564 +vn -0.5746 0.7689 -0.2805 +vn -0.4691 0.8158 -0.3382 +vn -0.6325 0.3353 -0.6982 +vn -0.1808 0.8465 -0.5008 +vn 0.0222 0.1948 -0.9806 +vn 0.1781 0.8376 -0.5165 +vn 0.6232 0.4027 -0.6704 +vn 0.4709 0.8100 -0.3496 +vn 0.8615 0.5072 -0.0245 +vn 0.8615 0.5073 -0.0245 +vn 0.8611 0.5079 -0.0243 +vn 0.8609 0.5082 -0.0243 +vn 0.4566 0.8462 0.2746 +vn 0.6595 0.3506 0.6650 +vn 0.2237 0.8179 0.5300 +vn 0.2151 0.7876 0.5775 +vn -0.2080 -0.8223 -0.5297 +vn -0.6216 -0.3625 -0.6944 +vn -0.4786 -0.7906 -0.3818 +vn -0.6961 -0.6930 -0.1874 +vn -0.5965 -0.7479 -0.2913 +vn -0.7015 -0.7033 0.1153 +vn -0.6817 -0.7215 0.1213 +vn -0.6423 -0.6613 0.3875 +vn -0.4488 -0.7777 0.4402 +vn -0.3449 -0.8223 0.4526 +vn -0.3771 -0.4309 0.8198 +vn -0.0317 -0.7725 0.6342 +vn -0.0641 -0.8065 0.5878 +vn 0.1102 -0.6593 0.7438 +vn 0.2525 -0.7462 0.6160 +vn 0.4824 -0.6322 0.6063 +vn 0.5345 -0.7551 0.3797 +vn 0.6769 -0.7033 0.2171 +vn 0.7072 -0.6987 0.1082 +vn 0.7936 -0.6001 -0.1006 +vn 0.5879 -0.7842 -0.1982 +vn 0.5260 -0.8229 -0.2151 +vn 0.5977 -0.4879 -0.6362 +vn 0.5814 -0.5162 -0.6288 +vn 0.2814 -0.7067 -0.6491 +vn 0.0654 -0.5146 -0.8549 +vn -0.5882 0.2151 0.7796 +vn -0.6168 0.3117 0.7227 +vn -0.5912 0.4161 0.6909 +vn -0.1429 0.9817 -0.1256 +vn -0.2297 0.9284 -0.2922 +vn -0.2492 0.8392 -0.4833 +vn -0.1568 -0.9821 0.1049 +vn -0.2241 -0.9299 0.2917 +vn -0.2547 -0.8597 0.4428 +vn -0.1889 -0.9735 -0.1288 +vn -0.1877 -0.9653 -0.1817 +vn -0.0818 -0.9288 0.3613 +vn -0.0422 -0.9969 0.0665 +vn -0.2414 0.0182 0.9702 +vn -0.1069 0.4336 0.8947 +vn -0.0332 0.0865 0.9957 +vn -0.0873 0.9657 -0.2445 +vn -0.0946 0.9915 0.0893 +vn -0.1434 0.9798 0.1393 +vn -0.2947 -0.8077 -0.5107 +vn -0.2524 0.7931 0.5543 +vn -0.2124 0.9390 0.2705 +vn -0.3823 -0.2147 0.8987 +vn -0.4399 0.0499 0.8966 +vn -0.2743 -0.6753 0.6847 +vn -0.0794 -0.7040 0.7058 +vn -0.3605 -0.8225 -0.4399 +vn -0.3530 0.2007 -0.9138 +vn -0.1446 0.0568 -0.9879 +vn -0.2473 0.3925 -0.8859 +vn -0.1202 0.7767 -0.6183 +vn -0.0819 0.9156 0.3937 +vn -0.0558 -0.3801 0.9233 +vn -0.4133 -0.5461 0.7287 +vn -0.4851 -0.6513 -0.5835 +vn -0.3954 0.5389 -0.7438 +vn -0.4270 0.5770 0.6963 +vn -0.5683 0.5558 0.6068 +vn -0.2386 -0.3767 0.8951 +vn -0.5807 -0.4929 0.6480 +vn -0.6436 0.2556 -0.7214 +vn -0.5427 0.1037 -0.8335 +vn -0.0080 0.5288 -0.8487 +vn -0.5741 0.4829 -0.6612 +vn -0.4545 -0.4894 -0.7442 +vn -0.6333 -0.3987 -0.6633 +vn -0.5508 -0.3040 0.7773 +vn -0.6491 -0.1169 0.7517 +vn -0.6599 0.0371 0.7504 +vn -0.6987 0.1146 0.7061 +vn -0.5340 0.2250 0.8150 +vn -0.3377 0.4186 0.8431 +vn -0.1059 0.7253 0.6803 +vn -0.6686 -0.3202 0.6712 +vn -0.6719 -0.2816 0.6850 +vn -0.6340 -0.2129 -0.7434 +vn -0.7006 -0.3004 -0.6472 +vn -0.1925 -0.6778 -0.7096 +vn -0.5918 -0.6295 -0.5035 +vn -0.4013 -0.2127 -0.8909 +vn -0.1860 -0.4254 -0.8857 +vn -0.6375 0.1936 -0.7457 +vn -0.6772 -0.0026 -0.7358 +vn -0.0208 -0.4127 -0.9106 +vn -0.6570 0.2967 -0.6931 +vn 0.9914 -0.0915 -0.0939 +vn 0.9912 0.1153 -0.0643 +vn 0.9989 0.0321 0.0332 +vn 0.9919 -0.1104 0.0630 +vn -0.6543 -0.1914 -0.7316 +vn -0.6036 -0.1756 0.7777 +vn 0.1016 0.2532 0.9621 +vn 0.2697 0.3231 0.9071 +vn -0.0876 0.2993 0.9501 +vn 0.9611 0.2683 0.0656 +vn 0.9447 0.3154 -0.0902 +vn 0.9291 0.3075 0.2055 +vn 0.8965 0.2991 -0.3268 +vn 0.9564 0.2281 -0.1823 +vn 0.2408 -0.3064 -0.9209 +vn 0.4025 -0.2124 -0.8904 +vn 0.5270 -0.3146 -0.7895 +vn 0.7029 -0.3205 -0.6349 +vn 0.7621 -0.2255 -0.6070 +vn 0.8249 -0.3227 -0.4641 +vn 0.9399 -0.3394 0.0380 +vn 0.9610 -0.2677 -0.0700 +vn 0.9561 -0.2674 0.1198 +vn 0.9144 -0.2780 0.2942 +vn -0.5778 -0.2981 -0.7598 +vn -0.5037 -0.2184 -0.8358 +vn -0.3487 -0.2865 -0.8924 +vn -0.4873 0.2831 -0.8260 +vn -0.5287 -0.2687 0.8051 +vn -0.3249 -0.2396 0.9149 +vn -0.3848 -0.3041 0.8715 +vn -0.1095 -0.3166 0.9422 +vn -0.3542 0.3236 0.8774 +vn -0.3275 0.2461 0.9122 +vn -0.3619 -0.1663 -0.9173 +vn -0.0862 -0.2943 -0.9518 +vn -0.0972 -0.1986 -0.9752 +vn 0.1512 -0.1920 -0.9697 +vn -0.5986 -0.0258 -0.8006 +vn -0.3201 -0.0014 -0.9474 +vn -0.0136 -0.0002 -0.9999 +vn 0.3166 0.0234 -0.9483 +vn 0.5540 -0.0694 -0.8296 +vn -0.5200 0.1247 -0.8450 +vn -0.3617 0.1859 -0.9136 +vn -0.1008 0.1897 -0.9767 +vn 0.1559 0.1850 -0.9703 +vn 0.4018 0.2010 -0.8934 +vn -0.2587 0.2927 -0.9205 +vn -0.0068 0.3051 -0.9523 +vn 0.2211 0.3008 -0.9277 +vn 0.4502 0.3007 -0.8408 +vn 0.6461 0.3170 -0.6943 +vn 0.5965 0.2360 -0.7671 +vn 0.5963 0.0691 -0.7998 +vn 0.6325 -0.2163 -0.7437 +vn -0.3313 0.0903 0.9392 +vn -0.4741 -0.0218 0.8802 +vn -0.2098 -0.0789 0.9746 +vn -0.0535 0.1260 0.9906 +vn 0.0387 -0.0508 0.9980 +vn 0.2557 0.0564 0.9651 +vn 0.2470 -0.1843 0.9513 +vn 0.4585 -0.1441 0.8769 +vn -0.0143 -0.2334 0.9723 +vn 0.6113 -0.0411 0.7903 +vn 0.6315 -0.2404 0.7372 +vn 0.1960 -0.3174 0.9278 +vn 0.4529 -0.2787 0.8469 +vn 0.7533 -0.2824 0.5940 +vn 0.7619 -0.1726 0.6243 +vn 0.7687 -0.0003 0.6396 +vn 0.7395 0.1919 -0.6452 +vn 0.7596 -0.0103 -0.6503 +vn 0.8180 0.2838 -0.5004 +vn 0.8480 -0.2935 0.4412 +vn 0.8638 -0.1989 0.4629 +vn 0.8538 0.1631 -0.4945 +vn 0.8546 -0.0699 -0.5146 +vn 0.8806 -0.2273 -0.4157 +vn 0.9077 -0.0115 0.4194 +vn 0.9248 0.1827 -0.3337 +vn 0.9239 -0.3084 -0.2267 +vn 0.8337 0.3048 0.4605 +vn 0.9204 0.1932 0.3399 +vn 0.7037 0.3075 0.6405 +vn 0.8108 0.1862 0.5549 +vn 0.5354 0.2987 0.7901 +vn 0.6645 0.2012 0.7197 +vn 0.3317 0.2476 0.9103 +vn 0.4703 0.1625 0.8674 +vn 0.9260 -0.0060 -0.3774 +vn 0.9539 -0.1536 0.2580 +vn 0.9738 0.0076 -0.2273 +vn 0.9564 -0.1782 -0.2313 +vn 0.9790 0.0044 0.2036 +vn 0.9793 0.1418 0.1442 +vn -0.0009 1.0000 0.0001 +vn -0.0020 1.0000 -0.0013 +vn -0.0002 1.0000 0.0004 +vn 0.0003 1.0000 0.0001 +vn -0.0001 1.0000 -0.0004 +vn 0.0011 1.0000 -0.0006 +vn 0.0010 1.0000 -0.0009 +vn 0.0016 1.0000 -0.0022 +vn 0.0004 1.0000 0.0007 +vn 0.0009 1.0000 0.0003 +vn 0.0004 1.0000 0.0004 +vn -0.0012 1.0000 0.0014 +vn -0.0005 1.0000 0.0013 +vn -0.0018 1.0000 0.0012 +vn -0.0027 1.0000 -0.0033 +vn 0.0004 1.0000 -0.0008 +vn 0.0005 1.0000 -0.0007 +vn -0.0003 1.0000 0.0001 +vn -0.0003 1.0000 -0.0007 +vn -0.0017 1.0000 -0.0014 +vn -0.0014 1.0000 -0.0024 +vn 0.0003 1.0000 -0.0007 +vn 0.0010 1.0000 0.0000 +vn 0.0019 1.0000 0.0002 +vn 0.0009 1.0000 -0.0007 +vn 0.0004 1.0000 0.0002 +vn -0.0012 1.0000 -0.0024 +vn -0.0028 1.0000 -0.0042 +vn -0.0000 1.0000 -0.0006 +vn 0.0008 1.0000 -0.0002 +vn 0.0010 -1.0000 0.0001 +vn 0.0015 -1.0000 0.0016 +vn 0.0005 -1.0000 0.0016 +vn 0.0022 -1.0000 -0.0017 +vn -0.0010 -1.0000 0.0042 +vn 0.0011 -1.0000 0.0027 +vn 0.0038 -1.0000 0.0001 +vn 0.0015 -1.0000 0.0011 +vn 0.0001 -1.0000 0.0028 +vn 0.0089 -1.0000 -0.0010 +vn -0.0012 -1.0000 0.0009 +vn -0.0009 -1.0000 0.0018 +vn -0.0013 -1.0000 0.0007 +vn 0.0025 -1.0000 0.0022 +vn 0.0000 -1.0000 -0.0000 +vn -0.0002 -1.0000 -0.0000 +vn 0.0001 -1.0000 0.0002 +vn -0.0003 -1.0000 0.0003 +vn -0.0010 -1.0000 0.0002 +vn -0.0006 -1.0000 -0.0027 +vn -0.0025 -1.0000 -0.0014 +vn -0.0012 -1.0000 0.0007 +vn -0.0024 -1.0000 0.0020 +vn -0.0022 -1.0000 -0.0005 +vn 0.0013 -1.0000 -0.0012 +vn 0.0003 -1.0000 0.0002 +vn -0.0056 -1.0000 -0.0030 +vn 0.0003 -1.0000 -0.0001 +vn 0.0007 -1.0000 -0.0007 +vn -0.0003 -1.0000 0.0004 +vn -0.0007 -1.0000 -0.0000 +vn 0.0001 -1.0000 0.0005 +vn -0.0028 -1.0000 0.0003 +vn 0.0824 0.0116 -0.9965 +vn -0.2297 -0.0175 -0.9731 +vn -0.4256 0.0225 -0.9046 +vn -0.6656 -0.0202 -0.7461 +vn -0.8215 0.0224 -0.5697 +vn -0.9306 -0.0179 -0.3656 +vn -0.9954 0.0195 -0.0941 +vn -0.9954 -0.0195 0.0940 +vn -0.9306 0.0179 0.3656 +vn -0.8333 -0.0178 0.5525 +vn -0.6770 0.0154 0.7358 +vn -0.5404 -0.0140 0.8413 +vn -0.3384 0.0140 0.9409 +vn -0.1821 -0.0132 0.9832 +vn 0.0808 0.0175 0.9966 +vn 0.2171 -0.0059 0.9761 +vn 0.5903 0.0074 0.8072 +vn 0.5938 -0.0063 0.8046 +vn 0.9289 -0.0144 0.3700 +vn 0.9104 0.0093 0.4137 +vn 0.9984 0.0142 -0.0544 +vn 0.9825 -0.0151 -0.1857 +vn 0.8444 0.0137 -0.5355 +vn 0.8210 -0.0073 -0.5709 +vn 0.5390 0.0050 -0.8423 +vn 0.5119 0.0041 -0.8590 +vn 0.1901 -0.0025 -0.9818 +vn 0.9885 0.0720 0.1328 +vn 0.9930 -0.1169 0.0161 +vn 0.9986 -0.0050 -0.0529 +vn 0.1026 0.6633 0.7413 +vn 0.3299 0.6458 0.6886 +vn 0.4208 0.6634 0.6187 +vn 0.3211 -0.6549 -0.6841 +vn 0.4951 -0.6292 -0.5991 +vn 0.6154 -0.6719 -0.4121 +vn 0.7234 -0.6307 -0.2810 +vn 0.7264 -0.6858 -0.0448 +vn 0.2245 -0.5566 0.7999 +vn -0.0270 -0.6656 0.7458 +vn 0.3469 -0.6788 0.6472 +vn -0.3269 -0.6040 0.7269 +vn -0.3913 -0.6723 0.6284 +vn -0.9845 -0.0639 -0.1634 +vn -0.9945 -0.1029 0.0214 +vn -0.9905 0.0867 -0.1064 +vn -0.9786 0.2046 0.0232 +vn -0.9981 0.0357 0.0496 +vn -0.9691 0.1661 0.1826 +vn -0.9482 0.0836 -0.3063 +vn -0.9204 0.3898 0.0308 +vn -0.8867 -0.0621 -0.4581 +vn -0.8374 0.1554 -0.5240 +vn -0.9026 -0.3809 -0.2004 +vn -0.9505 -0.1952 -0.2418 +vn -0.8492 -0.2990 -0.4352 +vn -0.8213 0.5650 -0.0791 +vn -0.8485 0.4919 0.1950 +vn -0.7626 0.6225 0.1756 +vn -0.9466 -0.2568 0.1952 +vn -0.9615 -0.2743 -0.0190 +vn -0.9019 -0.4254 0.0753 +vn -0.8169 -0.5447 0.1898 +vn -0.9516 0.2732 -0.1408 +vn -0.8066 -0.5362 -0.2488 +vn -0.7841 -0.4788 -0.3949 +vn -0.7430 0.6675 -0.0492 +vn -0.6820 0.6827 -0.2625 +vn -0.7448 0.5920 -0.3078 +vn -0.8832 0.4131 -0.2220 +vn -0.9070 0.3093 0.2860 +vn -0.7003 0.6649 0.2599 +vn -0.6449 0.5955 0.4790 +vn -0.7543 -0.6533 0.0653 +vn -0.7097 -0.6426 0.2888 +vn -0.8136 -0.5724 -0.1019 +vn -0.7128 -0.6694 -0.2093 +vn -0.7780 0.4652 0.4223 +vn -0.9806 -0.0290 0.1936 +vn -0.8926 0.1583 0.4221 +vn -0.6742 -0.6227 -0.3970 +vn -0.5688 -0.6542 -0.4985 +vn -0.5899 0.6510 -0.4778 +vn -0.5684 0.6402 0.5167 +vn -0.7882 0.2923 0.5417 +vn -0.5852 -0.6487 0.4865 +vn -0.7253 -0.5275 0.4424 +vn -0.8570 -0.3759 0.3525 +vn -0.6480 0.4265 0.6310 +vn -0.9221 -0.0534 0.3833 +vn -0.7293 0.5030 -0.4638 +vn -0.4620 0.6156 0.6385 +vn -0.4406 0.5477 0.7112 +vn -0.4052 0.6544 -0.6384 +vn -0.5852 0.5212 -0.6212 +vn -0.8762 0.3018 -0.3758 +vn -0.7956 0.0164 0.6056 +vn -0.6804 0.2109 0.7018 +vn -0.5893 -0.5433 0.5979 +vn -0.4822 0.3665 0.7957 +vn -0.5002 -0.5433 -0.6742 +vn -0.6490 -0.4544 -0.6102 +vn -0.2523 0.6283 0.7360 +vn -0.1965 0.4406 0.8760 +vn -0.4730 0.1676 0.8650 +vn -0.0644 0.6873 -0.7235 +vn -0.1587 0.5879 -0.7932 +vn -0.3478 0.6100 -0.7120 +vn -0.2967 -0.6504 -0.6993 +vn -0.6098 0.1635 -0.7755 +vn -0.3891 0.0225 -0.9209 +vn -0.6099 -0.0708 -0.7893 +vn -0.7537 0.0373 -0.6562 +vn 0.1403 0.2529 -0.9573 +vn 0.2856 0.0918 -0.9539 +vn -0.0737 0.0117 -0.9972 +vn -0.1560 0.1967 -0.9680 +vn -0.4016 0.2368 -0.8846 +vn -0.7233 0.3038 -0.6202 +vn -0.1320 0.3725 -0.9186 +vn 0.1141 0.4593 -0.8809 +vn -0.3248 0.4270 -0.8439 +vn -0.5028 0.4291 -0.7504 +vn 0.0864 0.6088 -0.7886 +vn 0.2739 0.6746 -0.6855 +vn 0.2992 0.5997 -0.7422 +vn 0.3624 0.3902 -0.8464 +vn 0.3149 0.5135 0.7982 +vn 0.1096 0.5092 0.8536 +vn -0.0735 0.6033 0.7941 +vn 0.3034 0.3123 0.9002 +vn 0.0639 0.3348 0.9401 +vn -0.2553 0.2554 0.9325 +vn -0.0488 0.1004 0.9937 +vn 0.3740 0.0677 0.9250 +vn 0.1407 0.1091 0.9840 +vn -0.2728 0.0410 0.9612 +vn -0.4605 -0.1087 0.8810 +vn -0.6090 0.0497 0.7916 +vn 0.2527 -0.1710 0.9523 +vn -0.2707 -0.1500 0.9509 +vn -0.0321 -0.1203 0.9922 +vn -0.6138 -0.1400 0.7770 +vn 0.1186 -0.2995 0.9467 +vn -0.7175 -0.2613 0.6457 +vn -0.1424 -0.3416 0.9290 +vn -0.8115 -0.2644 0.5211 +vn -0.3875 -0.3750 0.8421 +vn -0.5655 -0.3893 0.7271 +vn 0.0702 -0.4927 0.8674 +vn -0.9080 -0.2029 0.3666 +vn -0.1393 -0.5295 0.8368 +vn 0.4127 -0.5667 0.7131 +vn 0.4890 0.5478 -0.6788 +vn 0.4420 -0.3730 0.8158 +vn 0.5320 0.6594 -0.5312 +vn 0.5271 0.2965 -0.7964 +vn 0.5323 0.0635 -0.8442 +vn 0.3849 -0.1173 -0.9155 +vn 0.5055 -0.1777 0.8443 +vn 0.4909 0.3012 0.8175 +vn 0.6301 -0.6283 0.4563 +vn 0.5956 -0.5460 0.5892 +vn 0.5875 0.0668 0.8065 +vn 0.5436 0.4868 0.6837 +vn 0.6256 0.6134 0.4820 +vn 0.0841 -0.5954 -0.7990 +vn 0.0391 -0.6626 -0.7479 +vn -0.1681 -0.5037 -0.8474 +vn -0.3597 -0.5127 -0.7796 +vn 0.4465 -0.4818 -0.7540 +vn 0.2174 -0.4637 -0.8589 +vn -0.0129 -0.3806 -0.9246 +vn 0.3724 -0.2903 -0.8815 +vn -0.5260 -0.2691 -0.8068 +vn -0.7490 -0.2017 -0.6311 +vn 0.6199 -0.3469 -0.7038 +vn -0.3531 -0.2288 -0.9072 +vn 0.6161 -0.1858 -0.7654 +vn 0.1197 -0.1690 -0.9783 +vn -0.1596 -0.2070 -0.9652 +vn 0.6809 -0.3138 0.6618 +vn 0.6953 -0.1023 0.7114 +vn 0.6829 0.2386 0.6905 +vn 0.6465 0.4578 0.6103 +vn 0.6075 0.5403 0.5823 +vn 0.5995 0.5859 0.5453 +vn 0.6680 0.5750 -0.4724 +vn 0.6645 0.4152 -0.6213 +vn 0.6913 0.0378 -0.7216 +vn 0.6671 -0.4871 -0.5636 +vn 0.6602 0.6832 -0.3120 +vn 0.7073 0.2465 -0.6625 +vn 0.7223 0.3471 0.5982 +vn 0.1111 0.9759 -0.1878 +vn 0.1537 0.9819 -0.1106 +vn 0.1164 0.9771 -0.1783 +vn 0.6787 0.5073 0.5310 +vn 0.6995 0.5547 0.4506 +vn 0.7903 -0.2286 -0.5684 +vn 0.7821 -0.4635 -0.4166 +vn 0.7705 -0.6022 0.2089 +vn 0.7108 -0.6587 0.2466 +vn 0.7769 -0.4654 0.4240 +vn 0.8021 0.0571 0.5944 +vn 0.1562 0.9820 -0.1060 +vn 0.8178 0.4322 0.3801 +vn 0.7790 0.5818 0.2340 +vn 0.7132 0.6145 0.3372 +vn 0.7411 0.6621 -0.1113 +vn 0.7698 0.5758 -0.2754 +vn 0.8370 -0.0270 -0.5466 +vn 0.8038 -0.5898 -0.0779 +vn 0.7972 -0.3543 0.4888 +vn 0.8555 0.2151 0.4710 +vn 0.7541 0.6508 0.0887 +vn 0.8207 0.5684 -0.0581 +vn 0.8002 0.4116 -0.4363 +vn 0.8072 0.2008 -0.5551 +vn 0.8572 -0.1635 0.4883 +vn 0.8936 -0.4287 -0.1334 +vn 0.8774 -0.4726 0.0822 +vn 0.8690 -0.4145 0.2702 +vn 0.8786 0.4648 0.1099 +vn 0.9038 0.3985 -0.1560 +vn 0.8997 -0.1654 -0.4039 +vn 0.9017 -0.3134 -0.2977 +vn 0.9181 -0.2602 0.2989 +vn 0.9269 -0.0040 0.3754 +vn 0.9115 0.3024 -0.2789 +vn 0.8809 0.1956 -0.4309 +vn 0.9340 0.2359 0.2682 +vn 0.9424 0.0720 -0.3265 +vn 0.9547 -0.2894 0.0694 +vn 0.9512 0.3017 0.0641 +vn 0.9666 -0.0942 -0.2382 +vn 0.9687 -0.2192 -0.1161 +vn 0.9741 -0.1078 0.1989 +vn 0.9781 0.1961 -0.0699 +vn 0.9790 0.1141 -0.1692 +vn 0.0121 0.9999 0.0092 +vn 0.0169 0.9997 0.0195 +vn 0.0077 0.9999 0.0100 +vn 0.0059 1.0000 0.0011 +vn 0.0018 1.0000 0.0050 +vn 0.0086 1.0000 0.0051 +vn 0.0016 1.0000 -0.0018 +vn 0.0009 1.0000 0.0009 +vn 0.0014 1.0000 -0.0005 +vn -0.0009 1.0000 -0.0017 +vn -0.0016 1.0000 -0.0007 +vn -0.0015 1.0000 -0.0027 +vn -0.0006 1.0000 0.0019 +vn -0.0011 1.0000 0.0002 +vn 0.0019 1.0000 0.0027 +vn -0.0010 1.0000 -0.0006 +vn -0.0007 1.0000 0.0009 +vn -0.0007 1.0000 0.0032 +vn 0.0047 1.0000 0.0005 +vn 0.0057 1.0000 -0.0000 +vn 0.0000 1.0000 0.0056 +vn -0.0060 0.9999 0.0096 +vn -0.0063 0.9999 0.0089 +vn -0.0010 1.0000 -0.0003 +vn 0.0011 1.0000 0.0018 +vn -0.0051 1.0000 0.0076 +vn -0.0084 0.9999 0.0143 +vn 0.0029 -1.0000 -0.0009 +vn 0.0004 -1.0000 -0.0017 +vn 0.0017 -1.0000 0.0035 +vn 0.0002 -1.0000 0.0026 +vn -0.0001 -1.0000 0.0026 +vn -0.0008 -1.0000 0.0012 +vn 0.0035 -1.0000 0.0029 +vn 0.0079 -0.9999 0.0068 +vn -0.0011 -1.0000 0.0008 +vn -0.0014 -1.0000 -0.0019 +vn -0.0021 -1.0000 -0.0021 +vn 0.0020 -1.0000 -0.0014 +vn 0.0016 -1.0000 -0.0024 +vn 0.0110 -0.9998 0.0154 +vn 0.0020 -1.0000 -0.0023 +vn 0.0006 -1.0000 0.0011 +vn -0.0044 -1.0000 0.0014 +vn -0.0051 -1.0000 0.0028 +vn -0.0041 -1.0000 0.0032 +vn -0.0054 -1.0000 0.0030 +vn -0.0014 -1.0000 -0.0022 +vn 0.0017 -1.0000 -0.0006 +vn -0.0016 -1.0000 -0.0016 +vn 0.0006 -1.0000 -0.0000 +vn -0.0019 -1.0000 -0.0021 +vn 0.0139 -0.0057 -0.9999 +vn 0.3691 0.0076 -0.9293 +vn 0.4351 -0.0011 -0.9004 +vn 0.8070 0.0061 -0.5906 +vn 0.7745 -0.0022 -0.6326 +vn 0.9770 -0.0067 -0.2130 +vn 0.9891 0.0009 -0.1473 +vn 0.9372 -0.0078 0.3488 +vn 0.9574 0.0034 0.2887 +vn 0.6512 0.0087 0.7589 +vn 0.5837 -0.0047 0.8120 +vn 0.1494 0.0070 0.9887 +vn 0.1737 -0.0015 0.9848 +vn -0.2519 -0.0045 0.9677 +vn -0.3456 0.0076 0.9384 +vn -0.6632 -0.0079 0.7484 +vn -0.7611 0.0085 0.6485 +vn -0.9449 -0.0080 0.3272 +vn -0.9757 0.0055 0.2191 +vn -0.9833 -0.0033 -0.1820 +vn -0.9794 -0.0004 -0.2022 +vn -0.7982 -0.0043 -0.6024 +vn -0.8299 0.0010 -0.5579 +vn -0.5488 0.0061 -0.8359 +vn -0.4266 -0.0074 -0.9044 +vn -0.1367 0.0092 -0.9906 +vn 0.0729 -0.6442 0.7614 +vn 0.2256 -0.7500 0.6217 +vn -0.1360 -0.7237 0.6766 +vn 0.4787 -0.6505 0.5896 +vn 0.5422 -0.7359 0.4055 +vn 0.6797 -0.7118 0.1769 +vn 0.6590 -0.7169 0.2274 +vn 0.7968 -0.5996 -0.0744 +vn 0.6114 -0.7706 -0.1801 +vn 0.5507 -0.8098 -0.2023 +vn 0.6673 -0.3875 -0.6360 +vn 0.6468 -0.4318 -0.6286 +vn 0.2842 -0.7356 -0.6150 +vn 0.1974 -0.7518 -0.6292 +vn -0.0327 -0.5713 -0.8201 +vn -0.2196 -0.7186 -0.6599 +vn -0.4268 -0.6444 -0.6345 +vn -0.5189 -0.7153 -0.4681 +vn -0.6309 -0.6759 -0.3810 +vn -0.6822 -0.7141 -0.1569 +vn -0.6744 -0.7278 -0.1244 +vn -0.6979 -0.7047 0.1280 +vn -0.6788 -0.7069 0.1988 +vn -0.5817 -0.6898 0.4310 +vn -0.4723 -0.7194 0.5093 +vn -0.3005 -0.6736 0.6752 +vn 0.0689 0.4166 -0.9065 +vn 0.2728 0.7626 -0.5865 +vn 0.2674 0.7366 -0.6212 +vn 0.4053 0.7606 -0.5071 +vn 0.7306 0.2682 -0.6279 +vn 0.5370 0.7991 -0.2703 +vn 0.6203 0.7777 -0.1023 +vn 0.6216 0.7722 -0.1320 +vn 0.7453 0.6378 0.1942 +vn 0.6275 0.6995 0.3419 +vn 0.6061 0.5218 0.6003 +vn 0.6135 0.4915 0.6181 +vn 0.1937 0.8342 0.5164 +vn -0.0118 0.5022 0.8647 +vn -0.1012 0.6427 0.7594 +vn -0.0061 0.5299 0.8480 +vn -0.2496 0.6954 0.6739 +vn -0.5392 0.4717 0.6977 +vn -0.5652 0.4240 0.7076 +vn -0.4467 0.8363 0.3178 +vn -0.8502 0.5180 0.0942 +vn -0.8412 0.5333 0.0896 +vn -0.6900 0.7079 -0.1510 +vn -0.6864 0.7207 -0.0974 +vn -0.6005 0.6899 -0.4044 +vn -0.5053 0.7154 -0.4825 +vn -0.3602 0.6699 -0.6492 +vn -0.2118 0.7427 -0.6352 +vn -0.1167 0.7864 -0.6066 +vn 0.0592 0.3717 -0.9265 +vn 1.0000 -0.0001 -0.0000 +vn 1.0000 -0.0011 -0.0003 +vn 1.0000 0.0003 0.0000 +vn 1.0000 -0.0000 -0.0000 +vn 1.0000 0.0003 0.0001 +vn 1.0000 -0.0002 -0.0001 +vn 1.0000 0.0001 -0.0000 +vn 1.0000 -0.0004 -0.0000 +vn 1.0000 0.0011 0.0003 +vn -1.0000 0.0000 0.0000 +vn -1.0000 0.0001 0.0000 +vn -1.0000 0.0011 -0.0004 +vn 0.0833 -0.9915 0.0996 +vn -0.0872 -0.9658 -0.2441 +vn 0.0828 -0.9627 -0.2574 +vn -0.0857 -0.8174 -0.5696 +vn 0.0837 -0.8159 -0.5721 +vn -0.0832 -0.5722 -0.8159 +vn 0.0858 -0.5697 -0.8174 +vn -0.0842 -0.2567 -0.9628 +vn 0.0872 -0.2442 -0.9658 +vn -0.0874 0.1019 -0.9910 +vn 0.0838 0.1713 -0.9816 +vn -0.0858 0.4956 -0.8643 +vn 0.0812 0.5725 -0.8159 +vn -0.0819 0.8159 -0.5724 +vn 0.0820 0.8631 -0.4983 +vn -0.0820 0.9815 -0.1730 +vn 0.0833 0.9915 -0.0996 +vn -0.0824 0.9664 0.2436 +vn 0.0828 0.9627 0.2574 +vn -0.0828 0.8161 0.5719 +vn 0.0825 0.8079 0.5835 +vn -0.0837 0.5611 0.8235 +vn 0.0823 0.4976 0.8635 +vn -0.0838 0.1713 0.9816 +vn 0.0836 0.1001 0.9915 +vn -0.0872 -0.2441 0.9658 +vn 0.0828 -0.2574 0.9627 +vn -0.0857 -0.5696 0.8174 +vn 0.0824 -0.5837 0.8078 +vn -0.0824 -0.8239 0.5608 +vn 0.0820 -0.8631 0.4983 +vn -0.0838 -0.9816 0.1713 +vn -0.0045 -0.9948 -0.1016 +vn -0.0057 -0.9012 0.4334 +vn -0.0047 -0.4837 0.8752 +vn -0.0038 0.9972 0.0750 +vn -0.0053 0.7608 0.6489 +vn -0.0044 0.8269 -0.5623 +vn -0.0043 0.2227 0.9749 +vn -0.0039 0.3389 -0.9408 +vn -0.0061 -0.2536 -0.9673 +vn -0.0066 -0.7622 -0.6473 +vn 0.0080 0.7632 -0.6461 +vn 0.0051 0.3263 -0.9453 +vn 0.0051 0.9094 0.4158 +vn 0.0029 0.4970 0.8678 +vn 0.0077 0.9865 -0.1638 +vn 0.0044 -0.2539 -0.9672 +vn 0.0034 -0.1612 0.9869 +vn 0.0012 -0.7619 0.6477 +vn 0.0063 -0.5437 -0.8392 +vn 0.0015 -0.9385 0.3452 +vn 0.0137 -0.9318 -0.3628 +vn 0.0130 -0.9307 -0.3656 +vn 0.0135 -0.9315 -0.3634 +vn 0.1942 0.9375 -0.2888 +vn 0.1902 0.6972 -0.6912 +vn 0.1894 0.2722 -0.9434 +vn 0.1808 -0.2243 -0.9576 +vn 0.1875 -0.6327 -0.7514 +vn 0.1977 -0.9407 -0.2758 +vn 0.1942 -0.9375 0.2888 +vn 0.1902 -0.6972 0.6912 +vn 0.1911 -0.2735 0.9427 +vn 0.1891 0.2208 0.9568 +vn 0.1933 0.6356 0.7474 +vn 0.1977 0.9407 0.2757 +vn -0.1808 -0.9577 -0.2241 +vn -0.1849 -0.7598 -0.6233 +vn -0.1883 -0.3656 -0.9115 +vn -0.1798 0.0836 -0.9801 +vn -0.1880 0.5518 -0.8125 +vn -0.1943 0.9038 -0.3812 +vn -0.1902 0.9784 0.0814 +vn -0.1976 0.8012 0.5648 +vn -0.1961 0.2983 0.9341 +vn -0.1808 -0.2241 0.9577 +vn -0.1875 -0.6326 0.7515 +vn -0.1928 -0.9388 0.2855 +vn 0.0129 -0.9305 -0.3660 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/5 6/6/6 +f 4/4/4 7/7/7 8/8/8 +f 9/9/9 10/10/10 11/11/11 +f 9/9/9 12/12/12 13/13/13 +f 9/9/9 14/14/14 12/12/12 +f 4/4/4 15/15/15 7/7/7 +f 16/16/16 17/17/17 18/18/18 +f 18/18/18 17/17/17 19/19/19 +f 9/9/9 11/11/11 20/20/20 +f 9/9/9 20/20/20 14/14/14 +f 13/13/13 12/12/12 21/21/21 +f 4/4/4 6/6/6 22/22/22 +f 4/4/4 22/22/22 15/15/15 +f 8/8/8 7/7/7 23/23/23 +f 14/14/14 24/24/24 12/12/12 +f 10/10/10 25/25/25 11/11/11 +f 11/11/11 26/26/26 20/20/20 +f 27/27/27 28/28/28 13/13/13 +f 29/29/29 30/30/30 31/31/31 +f 31/31/31 30/30/30 32/32/32 +f 5/5/5 33/33/33 6/6/6 +f 6/6/6 34/34/34 22/22/22 +f 35/35/35 36/36/36 8/8/8 +f 37/37/37 16/16/16 38/38/38 +f 38/38/38 16/16/16 18/18/18 +f 39/39/39 25/25/25 10/10/10 +f 11/11/11 38/38/38 26/26/26 +f 31/31/31 32/32/32 40/40/40 +f 41/41/41 33/33/33 5/5/5 +f 6/6/6 31/31/31 34/34/34 +f 42/42/42 37/37/37 43/43/43 +f 38/38/38 18/18/18 44/44/44 +f 39/39/39 43/43/43 25/25/25 +f 25/25/25 38/38/38 11/11/11 +f 45/45/45 29/29/29 33/33/33 +f 33/33/33 29/29/29 31/31/31 +f 41/41/41 45/45/45 33/33/33 +f 33/33/33 31/31/31 6/6/6 +f 43/43/43 37/37/37 25/25/25 +f 25/25/25 37/37/37 38/38/38 +f 39/39/39 42/42/42 43/43/43 +f 38/38/38 44/44/44 26/26/26 +f 41/41/41 46/46/46 45/45/45 +f 31/31/31 40/40/40 34/34/34 +f 47/47/47 48/48/48 16/16/16 +f 16/16/16 48/48/48 49/49/49 +f 49/49/49 35/35/35 17/17/17 +f 17/17/17 23/23/23 50/50/50 +f 37/37/37 42/42/42 47/47/47 +f 37/37/37 47/47/47 16/16/16 +f 16/16/16 49/49/49 17/17/17 +f 19/19/19 17/17/17 50/50/50 +f 42/42/42 39/39/39 51/51/51 +f 3/3/3 2/2/2 52/52/52 +f 52/52/52 2/2/2 28/28/28 +f 52/52/52 28/28/28 27/27/27 +f 27/27/27 13/13/13 21/21/21 +f 12/12/12 24/24/24 53/53/53 +f 12/12/12 53/53/53 21/21/21 +f 54/54/54 3/3/3 52/52/52 +f 53/53/53 27/27/27 21/21/21 +f 54/54/54 52/52/52 27/27/27 +f 55/55/55 3/3/3 54/54/54 +f 54/54/54 27/27/27 56/56/56 +f 56/56/56 27/27/27 53/53/53 +f 56/56/56 53/53/53 57/57/57 +f 57/57/57 53/53/53 24/24/24 +f 46/46/46 55/55/55 54/54/54 +f 30/30/30 54/54/54 56/56/56 +f 29/29/29 46/46/46 54/54/54 +f 58/58/58 56/56/56 57/57/57 +f 29/29/29 54/54/54 30/30/30 +f 59/59/59 46/46/46 41/41/41 +f 45/45/45 46/46/46 29/29/29 +f 32/32/32 30/30/30 56/56/56 +f 32/32/32 56/56/56 58/58/58 +f 49/49/49 36/36/36 35/35/35 +f 35/35/35 8/8/8 23/23/23 +f 48/48/48 36/36/36 49/49/49 +f 23/23/23 7/7/7 60/60/60 +f 17/17/17 35/35/35 23/23/23 +f 50/50/50 23/23/23 60/60/60 +f 61/61/61 62/62/62 63/63/63 +f 55/55/55 46/46/46 64/64/64 +f 3/3/3 55/55/55 65/65/65 +f 47/47/47 42/42/42 66/66/66 +f 67/67/67 68/68/68 69/69/69 +f 70/70/70 71/71/71 72/72/72 +f 73/73/73 71/71/71 74/74/74 +f 75/75/75 76/76/76 77/77/77 +f 78/78/78 79/79/79 80/80/80 +f 81/81/81 82/82/82 83/83/83 +f 84/84/84 85/85/85 86/86/86 +f 87/87/87 88/88/88 89/89/89 +f 90/90/90 36/36/36 48/48/48 +f 2/2/2 1/1/1 91/91/91 +f 90/90/90 48/48/48 92/92/92 +f 91/91/91 93/93/93 78/78/78 +f 64/64/64 46/46/46 59/59/59 +f 64/64/64 59/59/59 94/94/94 +f 95/95/95 42/42/42 51/51/51 +f 95/95/95 51/51/51 96/96/96 +f 97/97/97 96/96/96 98/98/98 +f 97/97/97 98/98/98 99/99/99 +f 90/90/90 100/100/100 101/101/101 +f 101/101/101 100/100/100 102/102/102 +f 91/91/91 1/1/1 93/93/93 +f 78/78/78 93/93/93 79/79/79 +f 80/80/80 79/79/79 103/103/103 +f 80/80/80 103/103/103 81/81/81 +f 81/81/81 103/103/103 104/104/104 +f 81/81/81 105/105/105 82/82/82 +f 81/81/81 104/104/104 105/105/105 +f 103/103/103 79/79/79 106/106/106 +f 82/82/82 105/105/105 107/107/107 +f 1/1/1 3/3/3 65/65/65 +f 93/93/93 1/1/1 108/108/108 +f 93/93/93 108/108/108 79/79/79 +f 79/79/79 108/108/108 106/106/106 +f 103/103/103 106/106/106 109/109/109 +f 103/103/103 109/109/109 104/104/104 +f 105/105/105 104/104/104 110/110/110 +f 105/105/105 110/110/110 107/107/107 +f 1/1/1 65/65/65 108/108/108 +f 106/106/106 108/108/108 111/111/111 +f 106/106/106 111/111/111 109/109/109 +f 109/109/109 111/111/111 112/112/112 +f 109/109/109 112/112/112 104/104/104 +f 104/104/104 112/112/112 113/113/113 +f 104/104/104 113/113/113 110/110/110 +f 65/65/65 55/55/55 64/64/64 +f 65/65/65 64/64/64 108/108/108 +f 108/108/108 64/64/64 94/94/94 +f 108/108/108 94/94/94 111/111/111 +f 111/111/111 94/94/94 114/114/114 +f 111/111/111 114/114/114 112/112/112 +f 112/112/112 114/114/114 115/115/115 +f 112/112/112 115/115/115 113/113/113 +f 113/113/113 115/115/115 75/75/75 +f 75/75/75 77/77/77 113/113/113 +f 113/113/113 77/77/77 110/110/110 +f 110/110/110 77/77/77 107/107/107 +f 116/116/116 117/117/117 118/118/118 +f 116/116/116 118/118/118 119/119/119 +f 120/120/120 121/121/121 122/122/122 +f 66/66/66 95/95/95 123/123/123 +f 123/123/123 95/95/95 97/97/97 +f 123/123/123 97/97/97 117/117/117 +f 121/121/121 124/124/124 125/125/125 +f 66/66/66 42/42/42 95/95/95 +f 117/117/117 97/97/97 118/118/118 +f 119/119/119 118/118/118 99/99/99 +f 119/119/119 126/126/126 124/124/124 +f 124/124/124 126/126/126 125/125/125 +f 121/121/121 125/125/125 122/122/122 +f 95/95/95 96/96/96 97/97/97 +f 118/118/118 97/97/97 99/99/99 +f 119/119/119 99/99/99 126/126/126 +f 125/125/125 126/126/126 127/127/127 +f 125/125/125 127/127/127 122/122/122 +f 122/122/122 127/127/127 128/128/128 +f 107/107/107 129/129/129 82/82/82 +f 82/82/82 129/129/129 83/83/83 +f 128/128/128 130/130/130 122/122/122 +f 77/77/77 131/131/131 107/107/107 +f 107/107/107 131/131/131 129/129/129 +f 129/129/129 84/84/84 83/83/83 +f 122/122/122 130/130/130 120/120/120 +f 129/129/129 131/131/131 85/85/85 +f 129/129/129 85/85/85 84/84/84 +f 76/76/76 132/132/132 77/77/77 +f 77/77/77 132/132/132 133/133/133 +f 77/77/77 133/133/133 131/131/131 +f 128/128/128 87/87/87 134/134/134 +f 128/128/128 134/134/134 130/130/130 +f 130/130/130 134/134/134 135/135/135 +f 73/73/73 132/132/132 76/76/76 +f 131/131/131 133/133/133 136/136/136 +f 131/131/131 136/136/136 85/85/85 +f 85/85/85 136/136/136 86/86/86 +f 87/87/87 89/89/89 134/134/134 +f 137/137/137 138/138/138 86/86/86 +f 73/73/73 74/74/74 132/132/132 +f 132/132/132 74/74/74 139/139/139 +f 132/132/132 139/139/139 133/133/133 +f 133/133/133 139/139/139 140/140/140 +f 133/133/133 140/140/140 136/136/136 +f 136/136/136 137/137/137 86/86/86 +f 141/141/141 142/142/142 143/143/143 +f 144/144/144 120/120/120 141/141/141 +f 141/141/141 120/120/120 145/145/145 +f 68/68/68 67/67/67 146/146/146 +f 68/68/68 146/146/146 147/147/147 +f 147/147/147 146/146/146 148/148/148 +f 147/147/147 148/148/148 144/144/144 +f 144/144/144 148/148/148 120/120/120 +f 141/141/141 145/145/145 142/142/142 +f 90/90/90 92/92/92 100/100/100 +f 101/101/101 102/102/102 69/69/69 +f 69/69/69 102/102/102 116/116/116 +f 69/69/69 116/116/116 67/67/67 +f 48/48/48 47/47/47 92/92/92 +f 100/100/100 123/123/123 102/102/102 +f 92/92/92 47/47/47 66/66/66 +f 92/92/92 66/66/66 100/100/100 +f 100/100/100 66/66/66 123/123/123 +f 102/102/102 123/123/123 117/117/117 +f 102/102/102 117/117/117 116/116/116 +f 67/67/67 116/116/116 119/119/119 +f 67/67/67 119/119/119 146/146/146 +f 142/142/142 145/145/145 135/135/135 +f 146/146/146 119/119/119 124/124/124 +f 146/146/146 124/124/124 121/121/121 +f 146/146/146 121/121/121 148/148/148 +f 148/148/148 121/121/121 120/120/120 +f 145/145/145 120/120/120 130/130/130 +f 145/145/145 130/130/130 135/135/135 +f 136/136/136 140/140/140 137/137/137 +f 134/134/134 89/89/89 135/135/135 +f 135/135/135 89/89/89 149/149/149 +f 135/135/135 149/149/149 142/142/142 +f 142/142/142 149/149/149 150/150/150 +f 142/142/142 150/150/150 143/143/143 +f 143/143/143 150/150/150 72/72/72 +f 71/71/71 70/70/70 74/74/74 +f 139/139/139 74/74/74 151/151/151 +f 139/139/139 151/151/151 140/140/140 +f 137/137/137 152/152/152 138/138/138 +f 138/138/138 152/152/152 153/153/153 +f 88/88/88 154/154/154 89/89/89 +f 149/149/149 155/155/155 150/150/150 +f 150/150/150 62/62/62 72/72/72 +f 72/72/72 62/62/62 70/70/70 +f 74/74/74 70/70/70 151/151/151 +f 140/140/140 151/151/151 152/152/152 +f 140/140/140 152/152/152 137/137/137 +f 153/153/153 152/152/152 154/154/154 +f 153/153/153 154/154/154 88/88/88 +f 154/154/154 155/155/155 89/89/89 +f 89/89/89 155/155/155 149/149/149 +f 155/155/155 62/62/62 150/150/150 +f 70/70/70 62/62/62 61/61/61 +f 70/70/70 61/61/61 151/151/151 +f 151/151/151 61/61/61 152/152/152 +f 152/152/152 63/63/63 154/154/154 +f 152/152/152 61/61/61 63/63/63 +f 154/154/154 63/63/63 155/155/155 +f 155/155/155 63/63/63 62/62/62 +f 156/156/156 68/68/157 147/147/158 +f 157/157/159 5/5/5 158/158/160 +f 158/158/160 5/5/5 4/4/4 +f 156/156/156 147/147/158 159/159/161 +f 159/159/161 147/147/158 144/144/162 +f 76/76/163 160/160/164 161/161/165 +f 162/162/166 68/68/157 156/156/156 +f 41/41/167 5/5/5 157/157/159 +f 161/161/165 73/73/168 76/76/163 +f 162/162/166 69/69/169 68/68/157 +f 158/158/160 36/36/170 163/163/171 +f 163/163/171 36/36/170 90/90/172 +f 8/8/8 36/36/170 158/158/160 +f 76/76/163 75/75/173 160/160/164 +f 162/162/166 101/101/174 69/69/169 +f 163/163/171 101/101/174 162/162/166 +f 163/163/171 90/90/172 101/101/174 +f 158/158/160 4/4/4 8/8/8 +f 164/164/175 94/94/176 165/165/177 +f 166/166/178 141/141/179 143/143/180 +f 159/159/161 141/141/179 166/166/178 +f 165/165/177 59/59/181 157/157/159 +f 157/157/159 59/59/181 41/41/167 +f 165/165/177 94/94/176 59/59/181 +f 75/75/173 115/115/182 160/160/164 +f 160/160/164 115/115/182 167/167/183 +f 168/168/184 73/73/168 161/161/165 +f 168/168/184 71/71/185 73/73/168 +f 168/168/184 72/72/186 71/71/185 +f 143/143/180 72/72/186 166/166/178 +f 159/159/161 144/144/162 141/141/179 +f 114/114/187 94/94/176 164/164/175 +f 167/167/183 115/115/182 114/114/187 +f 167/167/183 114/114/187 164/164/175 +f 166/166/178 72/72/186 168/168/184 +f 169/169/188 127/127/189 170/170/190 +f 170/170/190 127/127/189 126/126/191 +f 171/171/192 87/87/193 128/128/194 +f 88/88/195 171/171/192 172/172/196 +f 173/173/197 10/10/10 174/174/198 +f 174/174/198 10/10/10 9/9/9 +f 169/169/188 128/128/194 127/127/189 +f 172/172/196 153/153/199 88/88/195 +f 175/175/200 84/84/201 176/176/202 +f 176/176/202 84/84/201 86/86/203 +f 39/39/204 10/10/10 173/173/197 +f 177/177/205 51/51/206 173/173/197 +f 173/173/197 51/51/206 39/39/204 +f 177/177/205 96/96/207 51/51/206 +f 170/170/190 126/126/191 99/99/208 +f 170/170/190 99/99/208 178/178/209 +f 171/171/192 128/128/194 169/169/188 +f 171/171/192 88/88/195 87/87/193 +f 176/176/202 86/86/203 138/138/210 +f 84/84/201 175/175/200 83/83/211 +f 174/174/198 13/13/13 28/28/212 +f 174/174/198 9/9/9 13/13/13 +f 96/96/207 177/177/205 98/98/213 +f 98/98/213 177/177/205 178/178/209 +f 178/178/209 99/99/208 98/98/213 +f 172/172/196 138/138/210 153/153/199 +f 81/81/214 83/83/211 179/179/215 +f 179/179/215 83/83/211 175/175/200 +f 176/176/202 138/138/210 172/172/196 +f 180/180/216 80/80/217 81/81/214 +f 180/180/216 81/81/214 179/179/215 +f 181/181/218 91/91/219 78/78/220 +f 181/181/218 78/78/220 180/180/216 +f 180/180/216 78/78/220 80/80/217 +f 181/181/218 2/2/221 91/91/219 +f 174/174/198 28/28/212 2/2/221 +f 174/174/198 2/2/221 181/181/218 +f 170/170/222 162/162/223 156/156/224 +f 170/170/222 156/156/224 169/169/225 +f 169/169/225 156/156/224 159/159/226 +f 169/169/225 159/159/226 171/171/227 +f 171/171/227 159/159/226 166/166/228 +f 171/171/227 166/166/228 172/172/229 +f 172/172/229 166/166/228 168/168/230 +f 172/172/229 168/168/230 176/176/231 +f 176/176/231 168/168/230 161/161/232 +f 176/176/231 161/161/232 175/175/233 +f 175/175/233 161/161/232 160/160/234 +f 175/175/233 160/160/234 179/179/235 +f 179/179/235 160/160/234 167/167/236 +f 179/179/235 167/167/236 180/180/237 +f 180/180/237 167/167/236 164/164/238 +f 180/180/237 164/164/238 181/181/239 +f 181/181/239 164/164/238 165/165/240 +f 181/181/239 165/165/240 174/174/241 +f 174/174/241 165/165/240 157/157/242 +f 174/174/243 157/157/244 158/158/245 +f 174/174/243 158/158/245 173/173/246 +f 173/173/247 158/158/248 177/177/249 +f 177/177/249 158/158/248 163/163/250 +f 177/177/249 163/163/250 178/178/251 +f 178/178/251 163/163/250 162/162/223 +f 178/178/251 162/162/223 170/170/222 +f 182/182/252 183/183/253 184/184/254 +f 185/185/255 186/186/256 187/187/257 +f 187/187/257 188/188/258 189/189/259 +f 190/190/260 191/191/261 192/192/262 +f 193/193/263 194/194/264 195/195/265 +f 196/196/266 194/194/264 197/197/267 +f 198/198/268 194/194/264 193/193/263 +f 196/196/266 197/197/267 199/199/269 +f 195/195/265 194/194/264 200/200/270 +f 201/201/271 200/200/270 202/202/272 +f 203/203/273 204/204/274 205/205/275 +f 195/195/265 200/200/270 201/201/271 +f 203/203/273 206/206/276 204/204/274 +f 207/207/277 208/208/278 209/209/279 +f 199/199/269 210/210/280 211/211/281 +f 198/198/268 193/193/263 206/206/276 +f 193/193/263 195/195/265 208/208/278 +f 212/212/282 213/213/283 214/214/284 +f 211/211/281 214/214/284 215/215/285 +f 196/196/266 199/199/269 215/215/285 +f 215/215/285 199/199/269 211/211/281 +f 214/214/284 211/211/281 212/212/282 +f 199/199/269 197/197/267 210/210/280 +f 211/211/281 216/216/286 212/212/282 +f 194/194/264 198/198/268 197/197/267 +f 210/210/280 217/217/287 211/211/281 +f 211/211/281 217/217/287 216/216/286 +f 197/197/267 218/218/288 210/210/280 +f 216/216/286 217/217/287 219/219/289 +f 217/217/287 210/210/280 220/220/290 +f 221/221/291 222/222/292 205/205/275 +f 223/223/293 221/221/291 205/205/275 +f 223/223/293 205/205/275 204/204/274 +f 224/224/294 221/221/291 223/223/293 +f 225/225/295 224/224/294 223/223/293 +f 226/226/296 225/225/295 227/227/297 +f 210/210/280 218/218/288 220/220/290 +f 217/217/287 228/228/298 219/219/289 +f 229/229/299 220/220/290 218/218/288 +f 221/221/291 190/190/260 222/222/292 +f 207/207/277 223/223/293 204/204/274 +f 204/204/274 206/206/276 193/193/263 +f 204/204/274 208/208/278 207/207/277 +f 213/213/283 230/230/300 231/231/301 +f 213/213/283 231/231/301 214/214/284 +f 217/217/287 220/220/290 228/228/298 +f 190/190/260 192/192/262 222/222/292 +f 205/205/275 222/222/292 232/232/302 +f 205/205/275 232/232/302 203/203/273 +f 226/226/296 224/224/294 225/225/295 +f 207/207/277 225/225/295 223/223/293 +f 208/208/278 204/204/274 193/193/263 +f 214/214/284 233/233/303 215/215/285 +f 220/220/290 234/234/304 228/228/298 +f 214/214/284 231/231/301 233/233/303 +f 235/235/305 219/219/289 236/236/306 +f 236/236/306 219/219/289 228/228/298 +f 236/236/306 228/228/298 234/234/304 +f 234/234/304 220/220/290 237/237/307 +f 237/237/307 220/220/290 229/229/299 +f 229/229/299 218/218/288 238/238/308 +f 238/238/308 218/218/288 197/197/267 +f 206/206/276 203/203/273 239/239/309 +f 227/227/297 240/240/310 226/226/296 +f 229/229/299 241/241/311 237/237/307 +f 191/191/261 242/242/312 192/192/262 +f 222/222/292 192/192/262 243/243/313 +f 222/222/292 243/243/313 232/232/302 +f 238/238/308 197/197/267 239/239/309 +f 239/239/309 197/197/267 198/198/268 +f 244/244/314 240/240/310 227/227/297 +f 238/238/308 245/245/315 229/229/299 +f 246/246/316 236/236/306 234/234/304 +f 246/246/316 234/234/304 237/237/307 +f 241/241/311 229/229/299 245/245/315 +f 192/192/262 242/242/312 247/247/317 +f 192/192/262 247/247/317 243/243/313 +f 248/248/318 235/235/305 236/236/306 +f 249/249/319 237/237/307 241/241/311 +f 248/248/318 236/236/306 250/250/320 +f 251/251/321 252/252/322 253/253/323 +f 253/253/323 252/252/322 230/230/300 +f 230/230/300 254/254/324 231/231/301 +f 255/255/325 256/256/326 257/257/327 +f 244/244/314 257/257/327 240/240/310 +f 244/244/314 227/227/297 258/258/328 +f 259/259/329 260/260/330 261/261/331 +f 261/261/331 262/262/332 263/263/333 +f 263/263/333 262/262/332 264/264/334 +f 265/265/335 266/266/336 267/267/337 +f 268/268/338 264/264/334 266/266/336 +f 269/269/339 259/259/329 261/261/331 +f 263/263/333 264/264/334 268/268/338 +f 265/265/335 268/268/338 266/266/336 +f 202/202/272 265/265/335 201/201/271 +f 270/270/340 268/268/338 265/265/335 +f 271/271/341 269/269/339 261/261/331 +f 271/271/341 261/261/331 272/272/342 +f 272/272/342 261/261/331 263/263/333 +f 270/270/340 263/263/333 268/268/338 +f 273/273/343 270/270/340 265/265/335 +f 273/273/343 265/265/335 202/202/272 +f 272/272/342 263/263/333 274/274/344 +f 274/274/344 263/263/333 270/270/340 +f 252/252/322 272/272/342 274/274/344 +f 254/254/324 270/270/340 273/273/343 +f 275/275/345 276/276/346 271/271/341 +f 275/275/345 271/271/341 272/272/342 +f 254/254/324 274/274/344 270/270/340 +f 196/196/266 200/200/270 194/194/264 +f 275/275/345 272/272/342 252/252/322 +f 233/233/303 273/273/343 202/202/272 +f 215/215/285 202/202/272 200/200/270 +f 200/200/270 196/196/266 215/215/285 +f 273/273/343 233/233/303 231/231/301 +f 273/273/343 231/231/301 254/254/324 +f 274/274/344 254/254/324 252/252/322 +f 277/277/347 275/275/345 251/251/321 +f 251/251/321 275/275/345 252/252/322 +f 230/230/300 252/252/322 254/254/324 +f 233/233/303 202/202/272 215/215/285 +f 275/275/345 277/277/347 276/276/346 +f 271/271/341 276/276/346 278/278/348 +f 271/271/341 278/278/348 269/269/339 +f 269/269/339 278/278/348 259/259/329 +f 279/279/349 280/280/350 248/248/318 +f 281/281/351 279/279/349 248/248/318 +f 250/250/320 281/281/351 248/248/318 +f 282/282/352 279/279/349 281/281/351 +f 246/246/316 250/250/320 236/236/306 +f 283/283/353 282/282/352 281/281/351 +f 283/283/353 281/281/351 284/284/354 +f 284/284/354 281/281/351 250/250/320 +f 285/285/355 250/250/320 246/246/316 +f 286/286/356 282/282/352 283/283/353 +f 284/284/354 250/250/320 285/285/355 +f 285/285/355 246/246/316 249/249/319 +f 249/249/319 246/246/316 237/237/307 +f 287/287/357 283/283/353 284/284/354 +f 286/286/356 283/283/353 287/287/357 +f 287/287/357 284/284/354 285/285/355 +f 288/288/358 285/285/355 249/249/319 +f 289/289/359 286/286/356 287/287/357 +f 290/290/360 287/287/357 285/285/355 +f 291/291/361 249/249/319 241/241/311 +f 291/291/361 241/241/311 245/245/315 +f 290/290/360 285/285/355 288/288/358 +f 292/292/362 288/288/358 249/249/319 +f 292/292/362 249/249/319 291/291/361 +f 293/293/363 289/289/359 287/287/357 +f 293/293/363 287/287/357 290/290/360 +f 294/294/364 295/295/365 289/289/359 +f 294/294/364 289/289/359 293/293/363 +f 296/296/366 293/293/363 290/290/360 +f 296/296/366 290/290/360 288/288/358 +f 297/297/367 288/288/358 292/292/362 +f 239/239/309 245/245/315 238/238/308 +f 297/297/367 296/296/366 288/288/358 +f 247/247/317 292/292/362 291/291/361 +f 243/243/313 291/291/361 245/245/315 +f 243/243/313 245/245/315 239/239/309 +f 298/298/368 294/294/364 293/293/363 +f 298/298/368 293/293/363 296/296/366 +f 243/243/313 247/247/317 291/291/361 +f 299/299/369 296/296/366 297/297/367 +f 300/300/370 294/294/364 298/298/368 +f 301/301/371 296/296/366 299/299/369 +f 247/247/317 297/297/367 292/292/362 +f 232/232/302 243/243/313 239/239/309 +f 301/301/371 298/298/368 296/296/366 +f 242/242/312 299/299/369 297/297/367 +f 242/242/312 297/297/367 247/247/317 +f 206/206/276 239/239/309 198/198/268 +f 301/301/371 299/299/369 302/302/372 +f 301/301/371 303/303/373 298/298/368 +f 298/298/368 303/303/373 300/300/370 +f 304/304/374 300/300/370 303/303/373 +f 303/303/373 301/301/371 302/302/372 +f 191/191/261 302/302/372 299/299/369 +f 191/191/261 299/299/369 242/242/312 +f 203/203/273 232/232/302 239/239/309 +f 294/294/364 300/300/370 295/295/365 +f 289/289/359 295/295/365 305/305/375 +f 289/289/359 305/305/375 286/286/356 +f 282/282/352 286/286/356 306/306/376 +f 282/282/352 306/306/376 279/279/349 +f 277/277/347 307/307/377 308/308/378 +f 277/277/347 308/308/378 276/276/346 +f 276/276/346 309/309/379 278/278/348 +f 278/278/348 309/309/379 310/310/380 +f 278/278/348 310/310/380 259/259/329 +f 259/259/329 310/310/380 311/311/381 +f 304/304/374 312/312/382 300/300/370 +f 276/276/346 308/308/378 309/309/379 +f 279/279/349 306/306/376 313/313/383 +f 279/279/349 313/313/383 280/280/350 +f 310/310/380 314/314/384 311/311/381 +f 304/304/374 315/315/385 312/312/382 +f 300/300/370 312/312/382 295/295/365 +f 295/295/365 316/316/386 317/317/387 +f 295/295/365 317/317/387 305/305/375 +f 286/286/356 305/305/375 318/318/388 +f 286/286/356 318/318/388 306/306/376 +f 280/280/350 313/313/383 319/319/389 +f 307/307/377 320/320/390 321/321/391 +f 307/307/377 321/321/391 308/308/378 +f 315/315/385 322/322/392 312/312/382 +f 312/312/382 316/316/386 295/295/365 +f 256/256/326 323/323/393 185/185/255 +f 185/185/255 323/323/393 324/324/394 +f 185/185/255 324/324/394 186/186/256 +f 324/324/394 325/325/395 186/186/256 +f 323/323/393 256/256/326 255/255/325 +f 255/255/325 257/257/327 244/244/314 +f 326/326/396 324/324/394 323/323/393 +f 327/327/397 323/323/393 255/255/325 +f 328/328/398 255/255/325 244/244/314 +f 328/328/398 244/244/314 329/329/399 +f 329/329/399 244/244/314 258/258/328 +f 209/209/279 258/258/328 207/207/277 +f 330/330/400 325/325/395 324/324/394 +f 330/330/400 324/324/394 326/326/396 +f 331/331/401 326/326/396 323/323/393 +f 331/331/401 323/323/393 327/327/397 +f 332/332/402 327/327/397 255/255/325 +f 332/332/402 255/255/325 328/328/398 +f 267/267/337 329/329/399 258/258/328 +f 267/267/337 258/258/328 209/209/279 +f 195/195/265 209/209/279 208/208/278 +f 330/330/400 326/326/396 331/331/401 +f 333/333/403 331/331/401 327/327/397 +f 333/333/403 327/327/397 332/332/402 +f 334/334/404 328/328/398 329/329/399 +f 260/260/330 331/331/401 333/333/403 +f 334/334/404 332/332/402 328/328/398 +f 334/334/404 329/329/399 267/267/337 +f 201/201/271 209/209/279 195/195/265 +f 314/314/384 335/335/405 330/330/400 +f 311/311/381 330/330/400 331/331/401 +f 311/311/381 331/331/401 260/260/330 +f 262/262/332 333/333/403 332/332/402 +f 262/262/332 332/332/402 334/334/404 +f 266/266/336 334/334/404 267/267/337 +f 201/201/271 267/267/337 209/209/279 +f 260/260/330 333/333/403 262/262/332 +f 264/264/334 262/262/332 334/334/404 +f 334/334/404 266/266/336 264/264/334 +f 330/330/400 311/311/381 314/314/384 +f 259/259/329 311/311/381 260/260/330 +f 261/261/331 260/260/330 262/262/332 +f 265/265/335 267/267/337 201/201/271 +f 315/315/385 336/336/406 322/322/392 +f 305/305/375 317/317/387 337/337/407 +f 305/305/375 337/337/407 318/318/388 +f 318/318/388 338/338/408 306/306/376 +f 306/306/376 338/338/408 313/313/383 +f 313/313/383 338/338/408 339/339/409 +f 313/313/383 339/339/409 319/319/389 +f 308/308/378 340/340/410 309/309/379 +f 309/309/379 340/340/410 310/310/380 +f 330/330/400 335/335/405 325/325/395 +f 322/322/392 341/341/411 312/312/382 +f 312/312/382 341/341/411 316/316/386 +f 318/318/388 337/337/407 338/338/408 +f 321/321/391 342/342/412 308/308/378 +f 308/308/378 342/342/412 340/340/410 +f 340/340/410 343/343/413 310/310/380 +f 310/310/380 343/343/413 314/314/384 +f 325/325/395 344/344/414 186/186/256 +f 186/186/256 344/344/414 187/187/257 +f 316/316/386 345/345/415 317/317/387 +f 317/317/387 345/345/415 337/337/407 +f 314/314/384 343/343/413 346/346/416 +f 314/314/384 346/346/416 335/335/405 +f 344/344/414 188/188/258 187/187/257 +f 227/227/297 225/225/295 258/258/328 +f 258/258/328 225/225/295 207/207/277 +f 346/346/416 347/347/417 335/335/405 +f 335/335/405 347/347/417 325/325/395 +f 325/325/395 347/347/417 344/344/414 +f 322/322/392 336/336/406 341/341/411 +f 338/338/408 348/348/418 339/339/409 +f 339/339/409 349/349/419 319/319/389 +f 319/319/389 349/349/419 350/350/420 +f 351/351/421 352/352/422 320/320/390 +f 320/320/390 352/352/422 321/321/391 +f 321/321/391 352/352/422 342/342/412 +f 189/189/259 188/188/258 353/353/423 +f 189/189/259 353/353/423 354/354/424 +f 354/354/424 355/355/425 336/336/406 +f 336/336/406 355/355/425 341/341/411 +f 341/341/411 356/356/426 316/316/386 +f 316/316/386 356/356/426 345/345/415 +f 345/345/415 357/357/427 337/337/407 +f 337/337/407 357/357/427 338/338/408 +f 338/338/408 357/357/427 348/348/418 +f 339/339/409 348/348/418 349/349/419 +f 350/350/420 349/349/419 358/358/428 +f 350/350/420 358/358/428 351/351/421 +f 351/351/421 358/358/428 359/359/429 +f 351/351/421 359/359/429 352/352/422 +f 340/340/410 360/360/430 343/343/413 +f 343/343/413 360/360/430 346/346/416 +f 347/347/417 361/361/431 344/344/414 +f 344/344/414 362/362/432 188/188/258 +f 353/353/423 355/355/425 354/354/424 +f 341/341/411 355/355/425 363/363/433 +f 341/341/411 363/363/433 356/356/426 +f 352/352/422 364/364/434 342/342/412 +f 342/342/412 364/364/434 340/340/410 +f 340/340/410 364/364/434 360/360/430 +f 346/346/416 365/365/435 347/347/417 +f 361/361/431 362/362/432 344/344/414 +f 188/188/258 362/362/432 353/353/423 +f 345/345/415 356/356/426 357/357/427 +f 348/348/418 366/366/436 349/349/419 +f 359/359/429 367/367/437 352/352/422 +f 360/360/430 365/365/435 346/346/416 +f 347/347/417 365/365/435 361/361/431 +f 355/355/425 368/368/438 363/363/433 +f 359/359/429 358/358/428 367/367/437 +f 352/352/422 367/367/437 364/364/434 +f 361/361/431 369/369/439 362/362/432 +f 353/353/423 362/362/432 369/369/439 +f 357/357/427 356/356/426 370/370/440 +f 357/357/427 370/370/440 348/348/418 +f 348/348/418 370/370/440 366/366/436 +f 366/366/436 371/371/441 349/349/419 +f 349/349/419 371/371/441 358/358/428 +f 364/364/434 372/372/442 360/360/430 +f 360/360/430 372/372/442 365/365/435 +f 365/365/435 373/373/443 361/361/431 +f 361/361/431 373/373/443 369/369/439 +f 369/369/439 374/374/444 353/353/423 +f 353/353/423 374/374/444 355/355/425 +f 355/355/425 374/374/444 368/368/438 +f 363/363/433 375/375/445 356/356/426 +f 356/356/426 375/375/445 370/370/440 +f 358/358/428 371/371/441 367/367/437 +f 372/372/442 373/373/443 365/365/435 +f 368/368/438 375/375/445 363/363/433 +f 370/370/440 376/376/446 366/366/436 +f 371/371/441 377/377/447 367/367/437 +f 367/367/437 377/377/447 364/364/434 +f 364/364/434 377/377/447 372/372/442 +f 373/373/443 378/378/448 369/369/439 +f 368/368/438 374/374/444 375/375/445 +f 375/375/445 379/379/449 370/370/440 +f 370/370/440 379/379/449 376/376/446 +f 366/366/436 376/376/446 371/371/441 +f 372/372/442 378/378/448 373/373/443 +f 369/369/439 378/378/448 184/184/254 +f 369/369/439 184/184/254 374/374/444 +f 376/376/446 380/380/450 371/371/441 +f 371/371/441 380/380/450 377/377/447 +f 377/377/447 182/182/252 372/372/442 +f 374/374/444 184/184/254 183/183/253 +f 374/374/444 183/183/253 375/375/445 +f 375/375/445 183/183/253 379/379/449 +f 379/379/449 183/183/253 376/376/446 +f 377/377/447 380/380/450 182/182/252 +f 372/372/442 182/182/252 378/378/448 +f 378/378/448 182/182/252 184/184/254 +f 376/376/446 183/183/253 380/380/450 +f 380/380/450 183/183/253 182/182/252 +f 381/381/451 307/307/452 382/382/453 +f 319/319/454 383/383/455 384/384/456 +f 384/384/456 280/280/457 319/319/454 +f 381/381/451 320/320/458 307/307/452 +f 385/385/459 351/351/460 381/381/451 +f 381/381/451 351/351/460 320/320/458 +f 386/386/461 216/216/462 219/219/463 +f 351/351/460 385/385/459 350/350/464 +f 350/350/464 385/385/459 383/383/455 +f 319/319/454 350/350/464 383/383/455 +f 387/387/465 248/248/466 384/384/456 +f 384/384/456 248/248/466 280/280/457 +f 388/388/467 213/213/468 212/212/469 +f 389/389/470 213/213/468 388/388/467 +f 382/382/453 277/277/471 251/251/472 +f 382/382/453 251/251/472 390/390/473 +f 388/388/467 212/212/469 386/386/461 +f 386/386/461 212/212/469 216/216/462 +f 307/307/452 277/277/471 382/382/453 +f 219/219/463 387/387/465 386/386/461 +f 390/390/473 253/253/474 389/389/470 +f 387/387/465 235/235/475 248/248/466 +f 219/219/463 235/235/475 387/387/465 +f 389/389/470 230/230/476 213/213/468 +f 251/251/472 253/253/474 390/390/473 +f 389/389/470 253/253/474 230/230/476 +f 391/391/477 189/189/478 392/392/479 +f 392/392/479 189/189/478 354/354/480 +f 392/392/479 354/354/480 336/336/481 +f 393/393/482 303/303/483 394/394/484 +f 304/304/485 303/303/483 393/393/482 +f 189/189/478 391/391/477 187/187/486 +f 392/392/479 315/315/487 393/393/482 +f 393/393/482 315/315/487 304/304/485 +f 392/392/479 336/336/481 315/315/487 +f 395/395/488 185/185/489 391/391/477 +f 391/391/477 185/185/489 187/187/486 +f 396/396/490 257/257/491 397/397/492 +f 398/398/493 224/224/494 396/396/490 +f 396/396/490 224/224/494 226/226/495 +f 224/224/494 398/398/493 221/221/496 +f 399/399/497 221/221/496 398/398/493 +f 191/191/498 190/190/499 399/399/497 +f 394/394/484 303/303/483 302/302/488 +f 397/397/492 257/257/491 256/256/500 +f 190/190/499 221/221/496 399/399/497 +f 397/397/492 256/256/500 395/395/488 +f 395/395/488 256/256/500 185/185/489 +f 394/394/484 191/191/498 399/399/497 +f 394/394/484 302/302/488 191/191/498 +f 240/240/501 257/257/491 396/396/490 +f 226/226/495 240/240/501 396/396/490 +f 400/400/502 401/401/503 402/402/504 +f 402/402/504 401/401/503 403/403/505 +f 402/402/506 403/403/507 404/404/508 +f 404/404/508 403/403/507 405/405/509 +f 404/404/510 405/405/511 406/406/512 +f 406/406/512 405/405/511 407/407/513 +f 406/406/512 407/407/513 408/408/514 +f 408/408/514 407/407/513 409/409/515 +f 408/408/514 409/409/515 410/410/516 +f 410/410/516 409/409/515 411/411/517 +f 410/410/516 411/411/517 412/412/518 +f 410/410/516 412/412/518 413/413/519 +f 413/413/519 412/412/518 414/414/520 +f 414/414/520 412/412/518 415/415/521 +f 414/414/522 415/415/523 416/416/524 +f 416/416/524 415/415/523 417/417/525 +f 416/416/524 417/417/525 418/418/526 +f 418/418/526 417/417/525 419/419/527 +f 418/418/526 419/419/527 420/420/528 +f 420/420/528 419/419/527 421/421/529 +f 420/420/528 421/421/529 422/422/530 +f 422/422/530 421/421/529 401/401/503 +f 422/422/530 401/401/503 400/400/502 +f 397/397/531 412/412/532 411/411/533 +f 397/397/531 411/411/533 396/396/534 +f 396/396/534 411/411/533 409/409/535 +f 409/409/535 407/407/536 396/396/534 +f 396/396/534 407/407/536 398/398/537 +f 407/407/536 405/405/538 398/398/537 +f 398/398/537 405/405/538 399/399/539 +f 405/405/538 403/403/540 399/399/539 +f 399/399/541 403/403/541 394/394/541 +f 403/403/542 401/401/542 394/394/542 +f 394/394/543 401/401/543 393/393/543 +f 393/393/544 401/401/544 421/421/544 +f 393/393/545 421/421/545 392/392/545 +f 392/392/546 421/421/546 419/419/546 +f 392/392/547 419/419/548 391/391/549 +f 391/391/549 419/419/548 417/417/550 +f 417/417/551 415/415/551 391/391/551 +f 391/391/552 415/415/552 395/395/552 +f 415/415/553 412/412/532 395/395/554 +f 395/395/554 412/412/532 397/397/531 +f 387/387/555 400/400/555 402/402/555 +f 387/387/556 402/402/556 386/386/556 +f 402/402/557 404/404/558 386/386/559 +f 386/386/559 404/404/558 388/388/560 +f 388/388/560 404/404/558 406/406/561 +f 388/388/560 406/406/561 408/408/562 +f 388/388/560 408/408/562 389/389/563 +f 389/389/563 408/408/562 410/410/564 +f 389/389/565 410/410/565 390/390/565 +f 390/390/566 410/410/567 413/413/568 +f 390/390/566 413/413/568 382/382/569 +f 382/382/569 413/413/568 414/414/570 +f 382/382/569 414/414/570 381/381/571 +f 414/414/570 416/416/572 381/381/571 +f 381/381/571 416/416/572 385/385/573 +f 416/416/572 418/418/574 385/385/573 +f 385/385/573 418/418/574 383/383/575 +f 383/383/575 418/418/574 420/420/576 +f 383/383/577 420/420/578 384/384/579 +f 384/384/579 420/420/578 422/422/530 +f 384/384/579 422/422/530 387/387/580 +f 387/387/580 422/422/530 400/400/502 +f 423/423/581 424/424/582 425/425/583 +f 426/426/584 427/427/585 428/428/586 +f 429/429/587 430/430/588 431/431/589 +f 429/429/587 432/432/590 433/433/591 +f 434/434/592 435/435/593 432/432/590 +f 436/436/594 437/437/595 438/438/596 +f 429/429/587 434/434/592 432/432/590 +f 426/426/584 439/439/597 440/440/598 +f 426/426/584 440/440/598 441/441/599 +f 429/429/587 431/431/589 434/434/592 +f 433/433/591 432/432/590 442/442/600 +f 426/426/584 428/428/586 439/439/597 +f 441/441/599 443/443/601 444/444/602 +f 445/445/603 446/446/604 436/436/594 +f 430/430/588 447/447/605 431/431/589 +f 431/431/589 448/448/606 434/434/592 +f 435/435/593 449/449/607 432/432/590 +f 432/432/590 449/449/607 442/442/600 +f 450/450/608 451/451/609 452/452/610 +f 428/428/586 453/453/611 439/439/597 +f 440/440/598 454/454/612 441/441/599 +f 441/441/599 454/454/612 443/443/601 +f 436/436/594 438/438/596 455/455/613 +f 430/430/588 456/456/614 447/447/605 +f 431/431/589 447/447/605 448/448/606 +f 442/442/600 457/457/615 433/433/591 +f 427/427/585 458/458/616 428/428/586 +f 459/459/617 460/460/618 444/444/602 +f 445/445/603 436/436/594 461/461/619 +f 461/461/619 436/436/594 455/455/613 +f 430/430/588 462/462/620 456/456/614 +f 463/463/621 464/464/622 458/458/616 +f 458/458/616 464/464/622 450/450/608 +f 452/452/610 451/451/609 465/465/623 +f 427/427/585 466/466/624 458/458/616 +f 460/460/618 459/459/617 425/425/583 +f 467/467/625 468/468/626 457/457/615 +f 458/458/616 450/450/608 452/452/610 +f 428/428/586 458/458/616 453/453/611 +f 469/469/627 445/445/603 456/456/614 +f 456/456/614 445/445/603 461/461/619 +f 456/456/614 461/461/619 447/447/605 +f 447/447/605 461/461/619 448/448/606 +f 466/466/624 463/463/621 458/458/616 +f 458/458/616 452/452/610 453/453/611 +f 453/453/611 452/452/610 465/465/623 +f 470/470/628 471/471/629 472/472/630 +f 470/470/628 472/472/630 473/473/631 +f 474/474/632 473/473/631 459/459/617 +f 437/437/595 474/474/632 475/475/633 +f 470/470/628 473/473/631 446/446/604 +f 446/446/604 473/473/631 474/474/632 +f 469/469/627 470/470/628 446/446/604 +f 436/436/594 446/446/604 474/474/632 +f 436/436/594 474/474/632 437/437/595 +f 476/476/634 470/470/628 469/469/627 +f 469/469/627 446/446/604 445/445/603 +f 455/455/613 448/448/606 461/461/619 +f 456/456/614 462/462/620 469/469/627 +f 476/476/634 469/469/627 462/462/620 +f 476/476/634 462/462/620 477/477/635 +f 457/457/615 442/442/600 467/467/625 +f 468/468/626 478/478/636 479/479/637 +f 478/478/636 468/468/626 467/467/625 +f 480/480/638 442/442/600 449/449/607 +f 480/480/638 449/449/607 435/435/639 +f 481/481/640 478/478/636 467/467/625 +f 480/480/638 467/467/625 442/442/600 +f 481/481/640 467/467/625 480/480/638 +f 481/481/640 480/480/638 482/482/641 +f 483/483/642 484/484/643 463/463/621 +f 464/464/622 484/484/643 478/478/636 +f 482/482/641 480/480/638 485/485/644 +f 486/486/645 483/483/642 463/463/621 +f 463/463/621 484/484/643 464/464/622 +f 464/464/622 478/478/636 481/481/640 +f 450/450/608 464/464/622 481/481/640 +f 466/466/624 486/486/645 463/463/621 +f 450/450/608 481/481/640 451/451/609 +f 451/451/609 481/481/640 482/482/641 +f 451/451/609 482/482/641 485/485/644 +f 460/460/618 425/425/583 424/424/582 +f 459/459/617 444/444/602 443/443/601 +f 472/472/630 423/423/581 425/425/583 +f 472/472/630 425/425/583 473/473/631 +f 475/475/633 443/443/601 454/454/612 +f 473/473/631 425/425/583 459/459/617 +f 474/474/632 459/459/617 443/443/601 +f 474/474/632 443/443/601 475/475/633 +f 487/487/646 488/488/647 489/489/648 +f 490/490/649 487/487/646 489/489/648 +f 478/478/636 484/484/643 491/491/650 +f 471/471/629 470/470/628 492/492/651 +f 493/493/652 494/494/653 495/495/654 +f 496/496/655 497/497/656 498/498/657 +f 499/499/658 497/497/656 500/500/659 +f 501/501/660 502/502/661 503/503/662 +f 504/504/663 505/505/664 506/506/665 +f 507/507/666 508/508/667 509/509/668 +f 507/507/666 509/509/668 510/510/669 +f 476/476/634 477/477/635 470/470/628 +f 479/479/637 478/478/636 491/491/650 +f 479/479/637 491/491/650 511/511/670 +f 511/511/670 512/512/671 513/513/672 +f 483/483/642 486/486/645 514/514/673 +f 492/492/651 470/470/628 477/477/635 +f 492/492/651 477/477/635 515/515/674 +f 516/516/675 515/515/674 517/517/676 +f 516/516/675 517/517/676 518/518/677 +f 424/424/582 423/423/581 519/519/678 +f 519/519/678 423/423/581 520/520/679 +f 519/519/678 520/520/679 495/495/654 +f 511/511/670 491/491/650 512/512/671 +f 513/513/672 512/512/671 521/521/680 +f 522/522/681 513/513/672 523/523/682 +f 522/522/681 523/523/682 501/501/660 +f 501/501/660 523/523/682 524/524/683 +f 501/501/660 524/524/683 502/502/661 +f 513/513/672 521/521/680 523/523/682 +f 512/512/671 491/491/650 525/525/684 +f 512/512/671 525/525/684 521/521/680 +f 491/491/650 484/484/643 525/525/684 +f 521/521/680 525/525/684 526/526/685 +f 521/521/680 526/526/685 523/523/682 +f 523/523/682 526/526/685 527/527/686 +f 523/523/682 527/527/686 524/524/683 +f 524/524/683 527/527/686 528/528/687 +f 524/524/683 528/528/687 502/502/661 +f 502/502/661 528/528/687 529/529/688 +f 525/525/684 530/530/689 526/526/685 +f 525/525/684 483/483/642 530/530/689 +f 526/526/685 530/530/689 531/531/690 +f 526/526/685 531/531/690 532/532/691 +f 526/526/685 532/532/691 527/527/686 +f 527/527/686 532/532/691 533/533/692 +f 527/527/686 533/533/692 528/528/687 +f 528/528/687 533/533/692 534/534/693 +f 525/525/684 484/484/643 483/483/642 +f 530/530/689 514/514/673 531/531/690 +f 530/530/689 483/483/642 514/514/673 +f 531/531/690 514/514/673 535/535/694 +f 531/531/690 535/535/694 532/532/691 +f 532/532/691 535/535/694 536/536/695 +f 532/532/691 536/536/695 533/533/692 +f 533/533/692 536/536/695 537/537/696 +f 533/533/692 537/537/696 534/534/693 +f 534/534/693 537/537/696 538/538/697 +f 538/538/697 539/539/698 540/540/699 +f 538/538/697 540/540/699 534/534/693 +f 534/534/693 540/540/699 541/541/700 +f 534/534/693 541/541/700 528/528/687 +f 528/528/687 541/541/700 529/529/688 +f 502/502/661 529/529/688 542/542/701 +f 502/502/661 542/542/701 503/503/662 +f 543/543/702 544/544/703 545/545/704 +f 546/546/705 545/545/704 547/547/706 +f 548/548/707 547/547/706 549/549/708 +f 548/548/707 549/549/708 550/550/709 +f 471/471/629 492/492/651 544/544/703 +f 544/544/703 516/516/675 545/545/704 +f 545/545/704 551/551/710 547/547/706 +f 547/547/706 551/551/710 549/549/708 +f 544/544/703 492/492/651 516/516/675 +f 545/545/704 516/516/675 551/551/710 +f 492/492/651 515/515/674 516/516/675 +f 551/551/710 516/516/675 518/518/677 +f 552/552/711 550/550/709 553/553/712 +f 518/518/677 554/554/713 551/551/710 +f 551/551/710 554/554/713 549/549/708 +f 549/549/708 554/554/713 555/555/714 +f 549/549/708 555/555/714 550/550/709 +f 550/550/709 555/555/714 553/553/712 +f 503/503/662 542/542/701 504/504/663 +f 553/553/712 556/556/715 557/557/716 +f 553/553/712 557/557/716 552/552/711 +f 552/552/711 557/557/716 558/558/717 +f 539/539/698 559/559/718 540/540/699 +f 540/540/699 559/559/718 541/541/700 +f 541/541/700 559/559/718 560/560/719 +f 541/541/700 560/560/719 529/529/688 +f 529/529/688 560/560/719 542/542/701 +f 542/542/701 505/505/664 504/504/663 +f 539/539/698 561/561/720 559/559/718 +f 560/560/719 505/505/664 542/542/701 +f 556/556/715 562/562/721 563/563/722 +f 556/556/715 563/563/722 557/557/716 +f 561/561/720 564/564/723 559/559/718 +f 559/559/718 564/564/723 560/560/719 +f 560/560/719 565/565/724 505/505/664 +f 505/505/664 565/565/724 566/566/725 +f 505/505/664 566/566/725 506/506/665 +f 557/557/716 563/563/722 567/567/726 +f 557/557/716 567/567/726 558/558/717 +f 560/560/719 564/564/723 565/565/724 +f 562/562/721 510/510/669 563/563/722 +f 499/499/658 568/568/727 561/561/720 +f 561/561/720 568/568/727 564/564/723 +f 566/566/725 569/569/728 506/506/665 +f 498/498/657 570/570/729 571/571/730 +f 570/570/729 572/572/731 573/573/732 +f 570/570/729 573/573/732 571/571/730 +f 572/572/731 574/574/733 575/575/734 +f 572/572/731 575/575/734 573/573/732 +f 494/494/653 493/493/652 576/576/735 +f 494/494/653 576/576/735 574/574/733 +f 574/574/733 576/576/735 577/577/736 +f 574/574/733 577/577/736 575/575/734 +f 495/495/654 520/520/679 546/546/705 +f 495/495/654 546/546/705 493/493/652 +f 571/571/730 573/573/732 567/567/726 +f 423/423/581 472/472/630 471/471/629 +f 520/520/679 423/423/581 543/543/702 +f 520/520/679 543/543/702 546/546/705 +f 576/576/735 493/493/652 548/548/707 +f 576/576/735 548/548/707 577/577/736 +f 575/575/734 577/577/736 552/552/711 +f 573/573/732 575/575/734 558/558/717 +f 423/423/581 471/471/629 544/544/703 +f 423/423/581 544/544/703 543/543/702 +f 493/493/652 546/546/705 548/548/707 +f 575/575/734 552/552/711 558/558/717 +f 573/573/732 558/558/717 567/567/726 +f 543/543/702 545/545/704 546/546/705 +f 546/546/705 547/547/706 548/548/707 +f 577/577/736 548/548/707 550/550/709 +f 577/577/736 550/550/709 552/552/711 +f 499/499/658 500/500/659 568/568/727 +f 564/564/723 568/568/727 578/578/737 +f 564/564/723 578/578/737 565/565/724 +f 565/565/724 578/578/737 566/566/725 +f 510/510/669 579/579/738 563/563/722 +f 563/563/722 579/579/738 567/567/726 +f 578/578/737 568/568/727 580/580/739 +f 578/578/737 580/580/739 581/581/740 +f 578/578/737 581/581/740 566/566/725 +f 566/566/725 581/581/740 569/569/728 +f 569/569/728 581/581/740 508/508/667 +f 569/569/728 508/508/667 507/507/666 +f 509/509/668 579/579/738 510/510/669 +f 571/571/730 496/496/655 498/498/657 +f 567/567/726 582/582/741 571/571/730 +f 571/571/730 582/582/741 583/583/742 +f 571/571/730 583/583/742 496/496/655 +f 497/497/656 496/496/655 500/500/659 +f 568/568/727 500/500/659 580/580/739 +f 581/581/740 580/580/739 487/487/646 +f 567/567/726 579/579/738 582/582/741 +f 496/496/655 583/583/742 488/488/647 +f 496/496/655 488/488/647 500/500/659 +f 500/500/659 488/488/647 580/580/739 +f 581/581/740 487/487/646 508/508/667 +f 508/508/667 487/487/646 490/490/649 +f 508/508/667 490/490/649 509/509/668 +f 509/509/668 490/490/649 579/579/738 +f 579/579/738 490/490/649 582/582/741 +f 582/582/741 489/489/648 583/583/742 +f 583/583/742 489/489/648 488/488/647 +f 580/580/739 488/488/647 487/487/646 +f 582/582/741 490/490/649 489/489/648 +f 584/584/743 585/585/744 427/427/585 +f 586/586/220 494/494/745 587/587/746 +f 494/494/745 574/574/747 587/587/746 +f 427/427/585 426/426/584 584/584/743 +f 584/584/743 441/441/599 444/444/602 +f 539/539/748 588/588/749 561/561/750 +f 586/586/220 495/495/751 494/494/745 +f 587/587/746 572/572/752 570/570/753 +f 589/589/753 495/495/751 586/586/220 +f 590/590/754 460/460/755 424/424/756 +f 590/590/754 424/424/756 591/591/196 +f 584/584/743 460/460/755 590/590/754 +f 444/444/602 460/460/755 584/584/743 +f 585/585/744 466/466/757 427/427/585 +f 538/538/758 592/592/759 539/539/748 +f 588/588/749 539/539/748 592/592/759 +f 495/495/751 589/589/753 519/519/760 +f 591/591/196 519/519/760 589/589/753 +f 591/591/196 424/424/756 519/519/760 +f 593/593/761 535/535/762 594/594/763 +f 538/538/758 595/595/764 592/592/759 +f 596/596/765 497/497/766 499/499/767 +f 587/587/746 570/570/753 597/597/768 +f 587/587/746 574/574/747 572/572/752 +f 584/584/743 426/426/584 441/441/599 +f 585/585/744 486/486/769 466/466/757 +f 594/594/763 486/486/769 585/585/744 +f 594/594/763 514/514/770 486/486/769 +f 594/594/763 535/535/762 514/514/770 +f 536/536/771 535/535/762 593/593/761 +f 538/538/758 537/537/758 595/595/764 +f 596/596/765 499/499/767 588/588/749 +f 597/597/768 498/498/772 596/596/765 +f 570/570/753 498/498/772 597/597/768 +f 588/588/749 499/499/767 561/561/750 +f 498/498/772 497/497/766 596/596/765 +f 595/595/764 537/537/758 536/536/771 +f 595/595/764 536/536/771 593/593/761 +f 598/598/773 599/599/774 554/554/775 +f 599/599/774 555/555/776 554/554/775 +f 556/556/777 600/600/778 562/562/779 +f 562/562/779 600/600/778 601/601/780 +f 601/601/780 507/507/781 510/510/782 +f 602/602/783 477/477/784 603/603/785 +f 556/556/777 553/553/786 600/600/778 +f 600/600/778 553/553/786 599/599/774 +f 599/599/774 553/553/786 555/555/776 +f 601/601/780 510/510/782 562/562/779 +f 604/604/787 504/504/788 605/605/789 +f 605/605/789 504/504/788 506/506/790 +f 606/606/791 457/457/792 607/607/793 +f 430/430/588 429/429/587 606/606/791 +f 603/603/785 462/462/794 606/606/791 +f 606/606/791 462/462/794 430/430/588 +f 603/603/785 477/477/784 462/462/794 +f 602/602/783 515/515/795 477/477/784 +f 598/598/773 517/517/796 602/602/783 +f 598/598/773 554/554/775 518/518/797 +f 601/601/780 569/569/798 507/507/781 +f 605/605/789 506/506/790 569/569/798 +f 504/504/788 604/604/787 503/503/787 +f 608/608/787 501/501/168 604/604/787 +f 606/606/791 433/433/591 457/457/792 +f 606/606/791 429/429/587 433/433/591 +f 515/515/795 602/602/783 517/517/796 +f 598/598/773 518/518/797 517/517/796 +f 501/501/168 503/503/787 604/604/787 +f 607/607/793 457/457/792 468/468/799 +f 605/605/789 569/569/798 601/601/780 +f 609/609/800 522/522/801 501/501/168 +f 609/609/800 501/501/168 608/608/787 +f 610/610/802 511/511/803 513/513/804 +f 610/610/802 513/513/804 609/609/800 +f 609/609/800 513/513/804 522/522/801 +f 479/479/805 610/610/802 607/607/793 +f 610/610/802 479/479/805 511/511/803 +f 607/607/793 468/468/799 479/479/805 +f 598/598/806 586/586/807 599/599/808 +f 599/599/808 586/586/807 587/587/809 +f 599/599/808 587/587/809 600/600/810 +f 600/600/810 587/587/809 597/597/811 +f 600/600/810 597/597/811 601/601/812 +f 601/601/812 597/597/811 596/596/813 +f 601/601/812 596/596/813 605/605/814 +f 605/605/814 596/596/813 588/588/815 +f 605/605/814 588/588/815 604/604/816 +f 604/604/816 588/588/815 592/592/817 +f 604/604/816 592/592/817 608/608/818 +f 608/608/818 592/592/817 595/595/819 +f 608/608/818 595/595/819 609/609/820 +f 609/609/820 595/595/819 593/593/821 +f 609/609/820 593/593/821 610/610/822 +f 610/610/822 593/593/821 594/594/823 +f 610/610/822 594/594/823 585/585/824 +f 610/610/822 585/585/824 607/607/825 +f 607/607/825 585/585/824 606/606/826 +f 606/606/826 585/585/824 584/584/827 +f 606/606/826 584/584/827 603/603/828 +f 603/603/828 584/584/827 590/590/829 +f 603/603/828 590/590/829 591/591/830 +f 603/603/828 591/591/830 602/602/831 +f 602/602/831 591/591/830 598/598/806 +f 598/598/806 591/591/830 589/589/832 +f 598/598/806 589/589/832 586/586/807 +f 611/611/833 612/612/834 613/613/835 +f 614/614/836 615/615/837 616/616/838 +f 617/617/839 618/618/840 619/619/841 +f 619/619/841 620/620/842 621/621/843 +f 622/622/844 623/623/845 624/624/846 +f 623/623/845 625/625/847 626/626/848 +f 627/627/849 628/628/850 629/629/851 +f 630/630/852 631/631/853 632/632/854 +f 627/627/849 629/629/851 633/633/855 +f 630/630/852 632/632/854 634/634/856 +f 635/635/857 633/633/855 636/636/858 +f 629/629/851 631/631/853 630/630/852 +f 637/637/859 638/638/860 639/639/861 +f 640/640/862 634/634/856 641/641/863 +f 640/640/862 641/641/863 642/642/864 +f 643/643/865 644/644/866 645/645/867 +f 643/643/865 645/645/867 646/646/868 +f 647/647/869 630/630/852 634/634/856 +f 637/637/859 639/639/861 648/648/870 +f 648/648/870 639/639/861 649/649/871 +f 650/650/872 651/651/873 652/652/874 +f 653/653/875 647/647/869 634/634/856 +f 653/653/875 634/634/856 640/640/862 +f 652/652/874 640/640/862 650/650/872 +f 634/634/856 654/654/876 641/641/863 +f 642/642/864 655/655/877 650/650/872 +f 655/655/877 642/642/864 656/656/878 +f 657/657/879 658/658/880 646/646/868 +f 659/659/881 657/657/879 646/646/868 +f 659/659/881 646/646/868 645/645/867 +f 660/660/882 657/657/879 659/659/881 +f 659/659/881 645/645/867 644/644/866 +f 637/637/859 659/659/881 644/644/866 +f 644/644/866 627/627/849 638/638/860 +f 653/653/875 640/640/862 652/652/874 +f 630/630/852 647/647/869 629/629/851 +f 641/641/863 661/661/883 642/642/864 +f 642/642/864 661/661/883 656/656/878 +f 631/631/853 662/662/884 632/632/854 +f 654/654/876 661/661/883 641/641/863 +f 663/663/885 654/654/876 632/632/854 +f 659/659/881 637/637/859 648/648/870 +f 659/659/881 648/648/870 664/664/886 +f 659/659/881 664/664/886 660/660/882 +f 665/665/887 660/660/882 664/664/886 +f 638/638/860 637/637/859 644/644/866 +f 628/628/850 627/627/849 644/644/866 +f 651/651/873 666/666/888 652/652/874 +f 655/655/877 656/656/878 667/667/889 +f 661/661/883 654/654/876 668/668/890 +f 668/668/890 654/654/876 663/663/885 +f 658/658/880 669/669/891 670/670/892 +f 658/658/880 670/670/892 646/646/868 +f 646/646/868 671/671/893 643/643/865 +f 649/649/871 664/664/886 648/648/870 +f 668/668/890 672/672/894 661/661/883 +f 661/661/883 672/672/894 656/656/878 +f 663/663/885 632/632/854 673/673/895 +f 673/673/895 632/632/854 662/662/884 +f 644/644/866 643/643/865 628/628/850 +f 652/652/874 666/666/888 674/674/896 +f 675/675/897 667/667/889 676/676/898 +f 676/676/898 667/667/889 656/656/878 +f 646/646/868 670/670/892 671/671/893 +f 666/666/888 677/677/899 678/678/900 +f 666/666/888 678/678/900 674/674/896 +f 653/653/875 679/679/901 647/647/869 +f 663/663/885 680/680/902 668/668/890 +f 656/656/878 672/672/894 676/676/898 +f 681/681/903 672/672/894 668/668/890 +f 669/669/891 626/626/848 682/682/904 +f 669/669/891 682/682/904 670/670/892 +f 652/652/874 674/674/896 653/653/875 +f 683/683/905 676/676/898 672/672/894 +f 681/681/903 668/668/890 680/680/902 +f 680/680/902 663/663/885 673/673/895 +f 684/684/906 665/665/887 685/685/907 +f 685/685/907 665/665/887 664/664/886 +f 675/675/897 676/676/898 686/686/908 +f 683/683/905 672/672/894 681/681/903 +f 626/626/848 625/625/847 682/682/904 +f 687/687/909 686/686/908 676/676/898 +f 688/688/910 683/683/905 681/681/903 +f 650/650/872 640/640/862 642/642/864 +f 654/654/876 634/634/856 632/632/854 +f 677/677/899 689/689/911 690/690/912 +f 677/677/899 690/690/912 691/691/913 +f 677/677/899 691/691/913 678/678/900 +f 653/653/875 674/674/896 679/679/901 +f 647/647/869 633/633/855 629/629/851 +f 684/684/906 692/692/914 665/665/887 +f 685/685/907 664/664/886 649/649/871 +f 693/693/915 694/694/916 695/695/917 +f 693/693/915 695/695/917 696/696/918 +f 697/697/919 698/698/920 699/699/921 +f 700/700/922 699/699/921 694/694/916 +f 697/697/919 699/699/921 700/700/922 +f 701/701/923 700/700/922 694/694/916 +f 701/701/923 694/694/916 693/693/915 +f 702/702/924 693/693/915 696/696/918 +f 703/703/925 697/697/919 700/700/922 +f 702/702/924 696/696/918 636/636/858 +f 704/704/926 697/697/919 703/703/925 +f 703/703/925 700/700/922 705/705/927 +f 705/705/927 700/700/922 701/701/923 +f 705/705/927 701/701/923 706/706/928 +f 706/706/928 701/701/923 693/693/915 +f 706/706/928 693/693/915 702/702/924 +f 679/679/901 636/636/858 633/633/855 +f 690/690/912 704/704/926 703/703/925 +f 690/690/912 703/703/925 705/705/927 +f 678/678/900 706/706/928 702/702/924 +f 707/707/929 704/704/926 690/690/912 +f 702/702/924 636/636/858 679/679/901 +f 691/691/913 690/690/912 705/705/927 +f 691/691/913 705/705/927 706/706/928 +f 702/702/924 679/679/901 674/674/896 +f 702/702/924 674/674/896 678/678/900 +f 706/706/928 678/678/900 691/691/913 +f 708/708/930 707/707/929 689/689/911 +f 689/689/911 707/707/929 690/690/912 +f 647/647/869 679/679/901 633/633/855 +f 636/636/858 696/696/918 635/635/857 +f 708/708/930 709/709/931 707/707/929 +f 707/707/929 709/709/931 704/704/926 +f 704/704/926 709/709/931 710/710/932 +f 704/704/926 710/710/932 697/697/919 +f 711/711/933 615/615/837 614/614/836 +f 712/712/934 711/711/933 614/614/836 +f 712/712/934 614/614/836 713/713/935 +f 687/687/909 712/712/934 713/713/935 +f 714/714/936 711/711/933 712/712/934 +f 715/715/937 712/712/934 687/687/909 +f 715/715/937 714/714/936 712/712/934 +f 716/716/938 687/687/909 683/683/905 +f 717/717/939 715/715/937 687/687/909 +f 717/717/939 687/687/909 716/716/938 +f 688/688/910 716/716/938 683/683/905 +f 718/718/940 714/714/936 719/719/941 +f 719/719/941 714/714/936 715/715/937 +f 719/719/941 715/715/937 717/717/939 +f 720/720/942 716/716/938 688/688/910 +f 720/720/942 717/717/939 716/716/938 +f 721/721/943 720/720/942 688/688/910 +f 721/721/943 688/688/910 722/722/944 +f 723/723/945 718/718/940 719/719/941 +f 723/723/945 719/719/941 717/717/939 +f 724/724/946 717/717/939 720/720/942 +f 725/725/947 723/723/945 717/717/939 +f 725/725/947 717/717/939 724/724/946 +f 726/726/948 721/721/943 722/722/944 +f 726/726/948 722/722/944 680/680/902 +f 727/727/949 723/723/945 725/725/947 +f 724/724/946 720/720/942 721/721/943 +f 728/728/950 726/726/948 680/680/902 +f 729/729/951 727/727/949 725/725/947 +f 729/729/951 725/725/947 724/724/946 +f 730/730/952 680/680/902 673/673/895 +f 731/731/953 729/729/951 724/724/946 +f 731/731/953 724/724/946 721/721/943 +f 731/731/953 721/721/943 732/732/954 +f 732/732/954 721/721/943 726/726/948 +f 732/732/954 726/726/948 728/728/950 +f 730/730/952 728/728/950 680/680/902 +f 622/622/844 723/723/945 727/727/949 +f 622/622/844 727/727/949 733/733/955 +f 733/733/955 727/727/949 729/729/951 +f 734/734/956 730/730/952 673/673/895 +f 735/735/957 733/733/955 729/729/951 +f 735/735/957 729/729/951 731/731/953 +f 625/625/847 731/731/953 732/732/954 +f 734/734/956 673/673/895 643/643/865 +f 643/643/865 673/673/895 662/662/884 +f 625/625/847 735/735/957 731/731/953 +f 682/682/904 732/732/954 728/728/950 +f 670/670/892 728/728/950 730/730/952 +f 670/670/892 730/730/952 671/671/893 +f 622/622/844 733/733/955 623/623/845 +f 623/623/845 733/733/955 735/735/957 +f 623/623/845 735/735/957 625/625/847 +f 682/682/904 625/625/847 732/732/954 +f 670/670/892 682/682/904 728/728/950 +f 628/628/850 643/643/865 662/662/884 +f 734/734/956 671/671/893 730/730/952 +f 736/736/958 622/622/844 624/624/846 +f 643/643/865 671/671/893 734/734/956 +f 614/614/836 686/686/908 713/713/935 +f 713/713/935 686/686/908 687/687/909 +f 687/687/909 676/676/898 683/683/905 +f 688/688/910 681/681/903 722/722/944 +f 722/722/944 681/681/903 680/680/902 +f 662/662/884 631/631/853 628/628/850 +f 709/709/931 737/737/959 710/710/932 +f 697/697/919 710/710/932 698/698/920 +f 622/622/844 738/738/960 723/723/945 +f 709/709/931 708/708/930 737/737/959 +f 736/736/958 738/738/960 622/622/844 +f 708/708/930 739/739/961 737/737/959 +f 710/710/932 740/740/962 698/698/920 +f 698/698/920 741/741/963 742/742/964 +f 738/738/960 743/743/965 723/723/945 +f 723/723/945 743/743/965 718/718/940 +f 718/718/940 744/744/966 714/714/936 +f 714/714/936 744/744/966 711/711/933 +f 710/710/932 737/737/959 740/740/962 +f 740/740/962 741/741/963 698/698/920 +f 624/624/846 745/745/967 746/746/968 +f 624/624/846 746/746/968 736/736/958 +f 743/743/965 747/747/969 718/718/940 +f 718/718/940 747/747/969 744/744/966 +f 744/744/966 748/748/970 711/711/933 +f 711/711/933 748/748/970 615/615/837 +f 615/615/837 748/748/970 616/616/838 +f 736/736/958 746/746/968 738/738/960 +f 748/748/970 749/749/971 616/616/838 +f 750/750/972 617/617/839 751/751/973 +f 750/750/972 751/751/973 752/752/974 +f 752/752/974 751/751/973 692/692/914 +f 753/753/975 692/692/914 684/684/906 +f 754/754/976 618/618/840 617/617/839 +f 754/754/976 617/617/839 755/755/977 +f 755/755/977 617/617/839 750/750/972 +f 752/752/974 692/692/914 753/753/975 +f 639/639/861 685/685/907 649/649/871 +f 756/756/978 750/750/972 752/752/974 +f 757/757/979 754/754/976 755/755/977 +f 755/755/977 750/750/972 756/756/978 +f 758/758/980 753/753/975 684/684/906 +f 758/758/980 684/684/906 685/685/907 +f 759/759/981 685/685/907 639/639/861 +f 760/760/982 754/754/976 757/757/979 +f 761/761/983 752/752/974 753/753/975 +f 761/761/983 753/753/975 758/758/980 +f 758/758/980 685/685/907 759/759/981 +f 762/762/984 760/760/982 757/757/979 +f 762/762/984 757/757/979 742/742/964 +f 757/757/979 755/755/977 763/763/985 +f 763/763/985 755/755/977 756/756/978 +f 764/764/986 756/756/978 752/752/974 +f 764/764/986 752/752/974 761/761/983 +f 763/763/985 756/756/978 764/764/986 +f 695/695/917 758/758/980 759/759/981 +f 633/633/855 635/635/857 638/638/860 +f 635/635/857 759/759/981 639/639/861 +f 633/633/855 638/638/860 627/627/849 +f 741/741/963 762/762/984 742/742/964 +f 742/742/964 757/757/979 763/763/985 +f 699/699/921 763/763/985 764/764/986 +f 759/759/981 635/635/857 696/696/918 +f 759/759/981 696/696/918 695/695/917 +f 758/758/980 695/695/917 694/694/916 +f 758/758/980 694/694/916 761/761/983 +f 761/761/983 694/694/916 764/764/986 +f 764/764/986 694/694/916 699/699/921 +f 763/763/985 698/698/920 742/742/964 +f 698/698/920 763/763/985 699/699/921 +f 738/738/960 746/746/968 765/765/987 +f 738/738/960 765/765/987 743/743/965 +f 743/743/965 765/765/987 766/766/988 +f 743/743/965 766/766/988 747/747/969 +f 747/747/969 767/767/989 744/744/966 +f 744/744/966 767/767/989 748/748/970 +f 748/748/970 768/768/990 769/769/991 +f 748/748/970 769/769/991 770/770/992 +f 748/748/970 770/770/992 749/749/971 +f 739/739/961 771/771/993 737/737/959 +f 737/737/959 772/772/994 740/740/962 +f 741/741/963 773/773/995 762/762/984 +f 754/754/976 760/760/982 774/774/996 +f 754/754/976 774/774/996 618/618/840 +f 748/748/970 767/767/989 768/768/990 +f 769/769/991 768/768/990 770/770/992 +f 739/739/961 775/775/997 771/771/993 +f 737/737/959 771/771/993 772/772/994 +f 740/740/962 772/772/994 776/776/998 +f 740/740/962 776/776/998 773/773/995 +f 740/740/962 773/773/995 741/741/963 +f 618/618/840 774/774/996 619/619/841 +f 767/767/989 777/777/999 768/768/990 +f 768/768/1000 777/777/1001 778/778/1002 +f 768/768/990 778/778/1003 779/779/1004 +f 768/768/990 779/779/1004 770/770/992 +f 770/770/992 779/779/1004 749/749/971 +f 619/619/841 774/774/996 620/620/842 +f 639/639/861 638/638/860 635/635/857 +f 629/629/851 628/628/850 631/631/853 +f 762/762/984 780/780/1005 760/760/982 +f 760/760/982 780/780/1005 774/774/996 +f 774/774/996 781/781/1006 620/620/842 +f 621/621/843 782/782/1007 783/783/1008 +f 783/783/1008 782/782/1007 745/745/967 +f 745/745/967 782/782/1007 784/784/1009 +f 745/745/967 784/784/1009 746/746/968 +f 746/746/968 784/784/1009 765/765/987 +f 747/747/969 766/766/988 785/785/1010 +f 747/747/969 785/785/1010 767/767/989 +f 778/778/1002 777/777/1001 786/786/1011 +f 778/778/1003 786/786/1012 779/779/1004 +f 779/779/1004 786/786/1012 749/749/971 +f 749/749/971 786/786/1012 787/787/1013 +f 749/749/971 787/787/1013 788/788/1014 +f 775/775/997 789/789/1015 790/790/1016 +f 775/775/997 790/790/1016 771/771/993 +f 773/773/995 791/791/1017 780/780/1005 +f 773/773/995 780/780/1005 762/762/984 +f 774/774/996 780/780/1005 781/781/1006 +f 620/620/842 792/792/1018 621/621/843 +f 784/784/1009 793/793/1019 765/765/987 +f 767/767/989 794/794/1020 777/777/999 +f 777/777/999 794/794/1020 786/786/1012 +f 788/788/1014 787/787/1013 795/795/1021 +f 795/795/1021 796/796/1022 789/789/1015 +f 790/790/1016 797/797/1023 771/771/993 +f 771/771/993 797/797/1023 772/772/994 +f 772/772/994 797/797/1023 798/798/1024 +f 772/772/994 798/798/1024 776/776/998 +f 621/621/843 792/792/1018 782/782/1007 +f 793/793/1019 784/784/1009 799/799/1025 +f 793/793/1019 799/799/1025 765/765/987 +f 765/765/987 799/799/1025 766/766/988 +f 766/766/988 799/799/1025 785/785/1010 +f 767/767/989 785/785/1010 794/794/1020 +f 795/795/1021 787/787/1013 796/796/1022 +f 789/789/1015 796/796/1022 790/790/1016 +f 776/776/998 798/798/1024 773/773/995 +f 773/773/995 798/798/1024 791/791/1017 +f 620/620/842 781/781/1006 800/800/1026 +f 620/620/842 800/800/1026 792/792/1018 +f 792/792/1018 801/801/1027 782/782/1007 +f 782/782/1007 802/802/1028 784/784/1009 +f 787/787/1013 803/803/1029 796/796/1022 +f 790/790/1016 796/796/1022 804/804/1030 +f 790/790/1016 804/804/1030 797/797/1023 +f 780/780/1005 791/791/1017 805/805/1031 +f 780/780/1005 805/805/1031 806/806/1032 +f 780/780/1005 806/806/1032 781/781/1006 +f 781/781/1006 806/806/1032 800/800/1026 +f 792/792/1018 800/800/1026 801/801/1027 +f 782/782/1007 801/801/1027 802/802/1028 +f 784/784/1009 802/802/1028 807/807/1033 +f 784/784/1009 807/807/1033 799/799/1025 +f 799/799/1025 808/808/1034 785/785/1010 +f 786/786/1012 803/803/1029 787/787/1013 +f 804/804/1030 809/809/1035 797/797/1023 +f 797/797/1023 810/810/1036 798/798/1024 +f 798/798/1024 810/810/1036 791/791/1017 +f 808/808/1034 794/794/1020 785/785/1010 +f 786/786/1012 794/794/1020 811/811/1037 +f 803/803/1029 804/804/1030 796/796/1022 +f 797/797/1023 809/809/1035 810/810/1036 +f 791/791/1017 812/812/1038 805/805/1031 +f 801/801/1027 800/800/1026 813/813/1039 +f 801/801/1027 813/813/1039 802/802/1028 +f 802/802/1028 813/813/1039 807/807/1033 +f 786/786/1012 811/811/1037 803/803/1029 +f 803/803/1029 814/814/1040 804/804/1030 +f 810/810/1036 809/809/1035 812/812/1038 +f 810/810/1036 812/812/1038 791/791/1017 +f 812/812/1038 815/815/1041 805/805/1031 +f 805/805/1031 815/815/1041 806/806/1032 +f 799/799/1025 807/807/1033 808/808/1034 +f 794/794/1020 808/808/1034 811/811/1037 +f 811/811/1037 814/814/1040 803/803/1029 +f 815/815/1041 816/816/1042 806/806/1032 +f 806/806/1032 816/816/1042 800/800/1026 +f 800/800/1026 816/816/1042 813/813/1039 +f 807/807/1033 813/813/1039 817/817/1043 +f 807/807/1033 817/817/1043 808/808/1034 +f 804/804/1030 814/814/1040 818/818/1044 +f 804/804/1030 818/818/1044 819/819/1045 +f 804/804/1030 819/819/1045 809/809/1035 +f 809/809/1035 819/819/1045 812/812/1038 +f 808/808/1034 817/817/1043 611/611/833 +f 808/808/1034 611/611/833 811/811/1037 +f 811/811/1037 611/611/833 814/814/1040 +f 812/812/1038 819/819/1045 815/815/1041 +f 816/816/1042 612/612/834 813/813/1039 +f 813/813/1039 612/612/834 817/817/1043 +f 814/814/1040 611/611/833 818/818/1044 +f 815/815/1041 819/819/1045 613/613/835 +f 815/815/1041 613/613/835 816/816/1042 +f 816/816/1042 613/613/835 612/612/834 +f 817/817/1043 612/612/834 611/611/833 +f 611/611/833 613/613/835 818/818/1044 +f 818/818/1044 613/613/835 819/819/1045 +f 820/820/1046 749/749/1047 788/788/1048 +f 820/820/1046 788/788/1048 821/821/1049 +f 822/822/1050 616/616/1051 820/820/1046 +f 820/820/1046 616/616/1051 749/749/1047 +f 739/739/1052 823/823/1053 824/824/1054 +f 666/666/1055 825/825/1056 677/677/1057 +f 826/826/1058 650/650/1059 655/655/1060 +f 825/825/1056 666/666/1055 827/827/1061 +f 825/825/1056 689/689/1062 677/677/1057 +f 825/825/1056 823/823/1053 689/689/1062 +f 824/824/1054 775/775/1063 739/739/1052 +f 824/824/1054 789/789/1064 775/775/1063 +f 821/821/1049 789/789/1064 824/824/1054 +f 789/789/1064 821/821/1049 795/795/1065 +f 788/788/1048 795/795/1065 821/821/1049 +f 822/822/1050 614/614/1066 616/616/1051 +f 686/686/1067 614/614/1066 828/828/1068 +f 828/828/1068 614/614/1066 822/822/1050 +f 827/827/1061 651/651/1069 650/650/1059 +f 827/827/1061 650/650/1059 826/826/1058 +f 823/823/1053 708/708/1070 689/689/1062 +f 667/667/1071 828/828/1068 826/826/1058 +f 827/827/1061 666/666/1055 651/651/1069 +f 739/739/1052 708/708/1070 823/823/1053 +f 686/686/1067 828/828/1068 675/675/1072 +f 667/667/1071 675/675/1072 828/828/1068 +f 826/826/1058 655/655/1060 667/667/1071 +f 829/829/469 621/621/1073 830/830/1074 +f 830/830/1074 621/621/1073 783/783/1075 +f 831/831/1076 623/623/1077 832/832/1078 +f 624/624/1079 831/831/1076 833/833/1080 +f 830/830/1074 783/783/1075 833/833/1080 +f 834/834/1081 665/665/1082 835/835/1083 +f 624/624/1079 623/623/1077 831/831/1076 +f 621/621/1073 829/829/469 619/619/1084 +f 836/836/1085 619/619/1084 829/829/469 +f 833/833/1080 745/745/1086 624/624/1079 +f 833/833/1080 783/783/1075 745/745/1086 +f 836/836/1085 617/617/1087 619/619/1084 +f 834/834/1081 660/660/1088 665/665/1082 +f 660/660/1088 834/834/1081 657/657/1089 +f 837/837/1090 657/657/1089 834/834/1081 +f 669/669/1091 658/658/1092 837/837/1090 +f 832/832/1078 623/623/1077 626/626/1093 +f 617/617/1087 836/836/1085 838/838/1094 +f 838/838/1094 839/839/1095 751/751/1096 +f 839/839/1095 692/692/1097 751/751/1096 +f 658/658/1092 657/657/1089 837/837/1090 +f 832/832/1078 669/669/1091 837/837/1090 +f 838/838/1094 751/751/1096 617/617/1087 +f 835/835/1083 665/665/1082 839/839/1095 +f 832/832/1078 626/626/1093 669/669/1091 +f 665/665/1082 692/692/1097 839/839/1095 +f 840/840/1098 841/841/1099 842/842/1100 +f 842/842/1100 841/841/1099 843/843/1101 +f 842/842/1100 843/843/1101 844/844/1102 +f 844/844/1102 843/843/1101 845/845/1103 +f 845/845/1103 843/843/1101 846/846/1104 +f 845/845/1103 846/846/1104 847/847/1105 +f 847/847/1105 846/846/1104 848/848/1106 +f 847/847/1105 848/848/1106 849/849/1107 +f 847/847/1105 849/849/1107 850/850/1108 +f 850/850/1108 849/849/1107 851/851/1109 +f 850/850/1108 851/851/1109 852/852/1110 +f 852/852/1110 851/851/1109 853/853/1111 +f 853/853/1111 851/851/1109 854/854/1112 +f 853/853/1111 854/854/1112 855/855/1113 +f 855/855/1113 854/854/1112 856/856/1114 +f 855/855/1113 856/856/1114 857/857/1115 +f 857/857/1115 856/856/1114 858/858/1116 +f 857/857/1115 858/858/1116 859/859/1117 +f 859/859/1117 858/858/1116 860/860/1118 +f 859/859/1117 860/860/1118 861/861/1119 +f 861/861/1119 860/860/1118 862/862/1120 +f 861/861/1119 862/862/1120 863/863/1121 +f 861/861/1119 863/863/1121 864/864/1122 +f 864/864/1122 863/863/1121 865/865/1123 +f 864/864/1122 865/865/1123 840/840/1098 +f 840/840/1098 865/865/1123 841/841/1099 +f 851/851/1124 839/839/1125 838/838/1126 +f 839/839/1125 851/851/1124 849/849/1127 +f 839/839/1125 849/849/1127 835/835/1128 +f 835/835/1128 849/849/1127 834/834/1129 +f 849/849/1127 848/848/1130 834/834/1129 +f 848/848/1130 846/846/1131 834/834/1129 +f 834/834/1129 846/846/1131 837/837/1132 +f 846/846/1131 843/843/1133 837/837/1132 +f 837/837/1134 843/843/1135 832/832/1136 +f 832/832/1136 843/843/1135 841/841/1137 +f 832/832/1136 841/841/1137 865/865/1138 +f 832/832/1136 865/865/1138 831/831/1139 +f 831/831/1139 865/865/1138 863/863/1140 +f 831/831/1139 863/863/1140 833/833/1141 +f 833/833/1141 863/863/1140 862/862/1142 +f 833/833/1141 862/862/1142 830/830/1143 +f 830/830/1143 862/862/1142 860/860/1144 +f 830/830/1143 860/860/1144 858/858/1145 +f 830/830/1143 858/858/1145 829/829/1146 +f 829/829/1146 858/858/1145 856/856/1147 +f 829/829/1146 856/856/1147 836/836/1148 +f 856/856/1147 854/854/1149 836/836/1148 +f 836/836/1148 854/854/1149 838/838/1126 +f 838/838/1126 854/854/1149 851/851/1124 +f 840/840/1150 842/842/1151 828/828/1152 +f 828/828/1152 842/842/1151 844/844/1153 +f 828/828/1154 844/844/1154 826/826/1154 +f 844/844/1155 845/845/1156 826/826/1157 +f 826/826/1157 845/845/1156 847/847/1158 +f 826/826/1157 847/847/1158 827/827/1159 +f 827/827/1159 847/847/1158 850/850/1160 +f 827/827/1159 850/850/1160 825/825/1161 +f 825/825/1162 850/850/1162 852/852/1162 +f 852/852/1163 853/853/1164 825/825/1165 +f 825/825/1165 853/853/1164 823/823/1166 +f 853/853/1164 855/855/1167 823/823/1166 +f 823/823/1166 855/855/1167 824/824/1168 +f 824/824/1169 855/855/1169 857/857/1169 +f 824/824/1170 857/857/1171 821/821/1172 +f 857/857/1171 859/859/1173 821/821/1172 +f 859/859/1173 861/861/1174 821/821/1172 +f 821/821/1172 861/861/1174 820/820/1175 +f 861/861/1174 864/864/1176 820/820/1175 +f 820/820/1175 864/864/1176 822/822/1177 +f 822/822/1177 864/864/1176 840/840/1178 +f 822/822/1179 840/840/1150 828/828/1152 +f 866/866/1180 867/867/1181 868/868/1180 +f 869/869/1182 866/866/1180 868/868/1180 +f 868/868/1180 870/870/1183 869/869/1182 +f 871/871/1184 870/870/1183 868/868/1180 +f 871/871/1184 872/872/1183 870/870/1183 +f 872/872/1183 873/873/1185 870/870/1183 +f 872/872/1183 874/874/1186 873/873/1185 +f 872/872/1183 875/875/1187 874/874/1186 +f 875/875/1187 876/876/1186 874/874/1186 +f 876/876/1186 877/877/1188 874/874/1186 +f 878/878/1189 879/879/1189 880/880/1189 +f 881/881/1189 882/882/1190 883/883/1189 +f 884/884/1189 881/881/1189 879/879/1189 +f 884/884/1189 879/879/1189 878/878/1189 +f 881/881/1189 883/883/1189 879/879/1189 +f 878/878/1189 880/880/1189 885/885/1189 +f 886/886/1189 878/878/1189 885/885/1189 +f 886/886/1189 885/885/1189 887/887/1189 +f 888/888/1189 889/889/1189 890/890/1189 +f 891/891/1189 892/892/1189 893/893/1189 +f 891/891/1189 894/894/1189 892/892/1189 +f 895/895/1189 893/893/1189 892/892/1189 +f 895/895/1189 892/892/1189 896/896/1189 +f 897/897/1190 898/898/1191 899/899/1190 +f 895/895/1189 896/896/1189 889/889/1189 +f 895/895/1189 889/889/1189 888/888/1189 +f 899/899/1190 888/888/1189 890/890/1189 +f 897/897/1190 899/899/1190 890/890/1189 +f 900/900/1183 901/901/1183 902/902/1183 +f 900/900/1183 903/903/1183 904/904/1183 +f 900/900/1183 902/902/1183 903/903/1183 +f 905/905/1183 904/904/1183 903/903/1183 +f 905/905/1183 903/903/1183 906/906/1183 +f 907/907/1183 905/905/1183 906/906/1183 +f 907/907/1183 906/906/1183 908/908/1183 +f 907/907/1183 908/908/1183 909/909/1183 +f 910/910/1192 911/911/1193 912/912/1194 +f 912/912/1194 911/911/1193 913/913/1195 +f 912/912/1194 913/913/1195 914/914/1196 +f 914/914/1196 913/913/1195 915/915/1197 +f 914/914/1196 915/915/1197 916/916/1198 +f 916/916/1198 915/915/1197 917/917/1199 +f 916/916/1198 917/917/1199 918/918/1200 +f 918/918/1200 917/917/1199 919/919/1201 +f 918/918/1200 919/919/1201 920/920/1202 +f 920/920/1202 919/919/1201 921/921/1203 +f 920/920/1202 921/921/1203 922/922/1204 +f 922/922/1204 921/921/1203 923/923/1205 +f 922/922/1204 923/923/1205 924/924/1206 +f 924/924/1206 923/923/1205 925/925/1207 +f 924/924/1206 925/925/1207 926/926/1208 +f 926/926/1208 925/925/1207 927/927/1209 +f 926/926/1208 927/927/1209 928/928/1210 +f 928/928/1210 927/927/1209 929/929/1211 +f 928/928/1210 929/929/1211 930/930/1212 +f 930/930/1212 929/929/1211 931/931/1213 +f 930/930/1212 931/931/1213 932/932/1214 +f 932/932/1214 931/931/1213 933/933/1215 +f 932/932/1214 933/933/1215 934/934/1216 +f 934/934/1216 933/933/1215 935/935/1217 +f 934/934/1216 935/935/1217 936/936/1218 +f 936/936/1218 935/935/1217 937/937/1219 +f 936/936/1218 937/937/1219 938/938/1220 +f 938/938/1220 937/937/1219 939/939/1221 +f 938/938/1220 939/939/1221 940/940/1222 +f 940/940/1222 939/939/1221 941/941/1223 +f 940/940/1222 941/941/1223 910/910/1192 +f 910/910/1192 941/941/1223 911/911/1193 +f 909/909/1224 7/7/7 15/15/15 +f 908/908/1225 906/906/1226 50/50/50 +f 14/14/14 901/901/1227 24/24/24 +f 909/909/1224 15/15/15 22/22/22 +f 902/902/1228 901/901/1227 20/20/20 +f 20/20/20 26/26/26 902/902/1228 +f 900/900/1229 57/57/57 24/24/24 +f 26/26/26 903/903/1230 902/902/1228 +f 900/900/1229 904/904/1231 57/57/57 +f 26/26/26 44/44/44 903/903/1230 +f 904/904/1231 58/58/58 57/57/57 +f 34/34/34 905/905/1232 907/907/1233 +f 44/44/44 18/18/18 903/903/1230 +f 904/904/1231 32/32/32 58/58/58 +f 904/904/1231 905/905/1232 32/32/32 +f 18/18/18 906/906/1226 903/903/1230 +f 18/18/18 19/19/19 906/906/1226 +f 905/905/1232 40/40/40 32/32/32 +f 19/19/19 50/50/50 906/906/1226 +f 905/905/1232 34/34/34 40/40/40 +f 907/907/1233 22/22/22 34/34/34 +f 60/60/60 908/908/1225 50/50/50 +f 907/907/1233 909/909/1224 22/22/22 +f 60/60/60 7/7/7 908/908/1225 +f 901/901/1227 14/14/14 20/20/20 +f 909/909/1224 908/908/1225 7/7/7 +f 901/901/1227 900/900/1229 24/24/24 +f 883/883/1234 465/465/623 879/879/1235 +f 475/475/633 881/881/1236 884/884/1237 +f 437/437/595 884/884/1237 438/438/596 +f 879/879/1235 465/465/623 451/451/609 +f 882/882/1238 881/881/1236 440/440/598 +f 879/879/1235 451/451/609 880/880/1239 +f 438/438/596 878/878/1240 455/455/613 +f 880/880/1239 451/451/609 485/485/644 +f 455/455/613 878/878/1240 886/886/1241 +f 880/880/1239 485/485/644 885/885/1242 +f 455/455/613 886/886/1241 448/448/606 +f 885/885/1242 485/485/644 480/480/638 +f 448/448/606 886/886/1241 434/434/592 +f 887/887/1243 435/435/593 434/434/592 +f 886/886/1241 887/887/1243 434/434/592 +f 435/435/1244 887/887/1245 480/480/1246 +f 882/882/1238 439/439/597 453/453/611 +f 438/438/596 884/884/1237 878/878/1240 +f 926/926/1208 866/866/1247 924/924/1206 +f 924/924/1206 866/866/1247 869/869/1248 +f 924/924/1206 869/869/1248 922/922/1204 +f 922/922/1204 869/869/1248 870/870/1249 +f 922/922/1204 870/870/1249 920/920/1202 +f 920/920/1202 870/870/1249 873/873/1250 +f 920/920/1202 873/873/1250 918/918/1200 +f 918/918/1200 873/873/1250 874/874/1251 +f 918/918/1200 874/874/1251 916/916/1198 +f 916/916/1198 874/874/1251 914/914/1196 +f 914/914/1196 874/874/1251 877/877/1252 +f 914/914/1196 877/877/1252 912/912/1194 +f 912/912/1194 877/877/1252 910/910/1192 +f 910/910/1192 877/877/1252 876/876/1253 +f 910/910/1192 876/876/1253 940/940/1222 +f 940/940/1222 876/876/1253 875/875/1254 +f 940/940/1222 875/875/1254 938/938/1220 +f 938/938/1220 875/875/1254 872/872/1255 +f 938/938/1220 872/872/1255 936/936/1218 +f 936/936/1218 872/872/1255 934/934/1216 +f 934/934/1216 872/872/1255 871/871/1256 +f 934/934/1216 871/871/1256 932/932/1214 +f 932/932/1214 871/871/1256 868/868/1257 +f 932/932/1214 868/868/1257 930/930/1212 +f 930/930/1212 868/868/1257 867/867/1258 +f 930/930/1212 867/867/1258 928/928/1210 +f 928/928/1210 867/867/1258 926/926/1208 +f 926/926/1208 867/867/1258 866/866/1247 +f 941/941/1223 897/897/1259 911/911/1193 +f 911/911/1193 897/897/1259 890/890/1260 +f 911/911/1193 890/890/1260 913/913/1195 +f 913/913/1195 890/890/1260 915/915/1197 +f 915/915/1197 890/890/1260 889/889/1261 +f 915/915/1197 889/889/1261 917/917/1199 +f 917/917/1199 889/889/1261 896/896/1262 +f 917/917/1199 896/896/1262 919/919/1201 +f 919/919/1201 896/896/1262 892/892/1263 +f 919/919/1201 892/892/1263 921/921/1203 +f 921/921/1203 892/892/1263 923/923/1205 +f 923/923/1205 892/892/1263 894/894/1264 +f 923/923/1205 894/894/1264 925/925/1207 +f 925/925/1207 894/894/1264 891/891/1265 +f 925/925/1207 891/891/1265 927/927/1209 +f 927/927/1209 891/891/1265 893/893/1266 +f 927/927/1209 893/893/1266 929/929/1211 +f 929/929/1211 893/893/1266 931/931/1213 +f 931/931/1213 893/893/1266 895/895/1267 +f 931/931/1213 895/895/1267 933/933/1215 +f 933/933/1215 895/895/1267 888/888/1268 +f 933/933/1215 888/888/1268 935/935/1217 +f 935/935/1217 888/888/1268 899/899/1269 +f 935/935/1217 899/899/1269 937/937/1219 +f 937/937/1219 899/899/1269 939/939/1221 +f 939/939/1221 899/899/1269 898/898/1270 +f 939/939/1221 898/898/1270 941/941/1223 +f 941/941/1223 898/898/1270 897/897/1259 +f 882/882/1238 440/440/598 439/439/597 +f 440/440/598 881/881/1236 454/454/612 +f 887/887/1245 885/885/1271 480/480/1246 +f 883/883/1234 882/882/1238 453/453/611 +f 454/454/612 881/881/1236 475/475/633 +f 883/883/1234 453/453/611 465/465/623 +f 475/475/633 884/884/1237 437/437/595 diff --git a/examples/Cassie/urdf/meshes/agility/shin.obj b/examples/Cassie/urdf/meshes/agility/shin.obj new file mode 100644 index 0000000000..5a875e909c --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/shin.obj @@ -0,0 +1,22185 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o shin +v 0.129744 -0.024499 0.011348 +v 0.133890 -0.024473 0.010425 +v 0.131182 -0.024498 0.009842 +v 0.133744 -0.024492 0.013621 +v 0.130696 -0.024480 0.014080 +v 0.131838 -0.034500 0.015083 +v 0.131123 -0.025240 0.015033 +v 0.129400 -0.034500 0.013751 +v 0.129244 -0.025253 0.013293 +v 0.129031 -0.025242 0.011141 +v 0.129085 -0.034500 0.010991 +v 0.130422 -0.025250 0.009398 +v 0.131345 -0.034500 0.008884 +v 0.132630 -0.025251 0.008975 +v 0.134381 -0.034500 0.010015 +v 0.134425 -0.025247 0.010182 +v 0.135085 -0.025241 0.012480 +v 0.135032 -0.034500 0.012403 +v 0.134019 -0.034500 0.014305 +v 0.133704 -0.025250 0.014526 +v 0.133005 -0.034500 0.018792 +v 0.136215 -0.034500 0.017442 +v 0.129316 -0.034500 0.018367 +v 0.125721 -0.034500 0.015076 +v 0.125328 -0.034500 0.010214 +v 0.138886 -0.034500 0.013355 +v 0.137262 -0.034500 0.007308 +v 0.132392 -0.034500 0.005110 +v 0.127922 -0.034500 0.006365 +v 0.137710 -0.035325 0.015841 +v 0.136994 -0.035329 0.013194 +v 0.138962 -0.035325 0.011126 +v 0.137073 -0.035331 0.011036 +v 0.136060 -0.035328 0.008828 +v 0.136072 -0.035325 0.006365 +v 0.134092 -0.035326 0.007308 +v 0.132303 -0.035325 0.005165 +v 0.131723 -0.035329 0.006868 +v 0.127671 -0.035325 0.017577 +v 0.132222 -0.035330 0.017195 +v 0.133815 -0.035325 0.018785 +v 0.128888 -0.035325 0.005839 +v 0.129458 -0.035328 0.007480 +v 0.126172 -0.035325 0.008375 +v 0.127056 -0.035329 0.010261 +v 0.125051 -0.035325 0.012402 +v 0.128668 -0.035326 0.015971 +v 0.135758 -0.035332 0.015650 +v 0.127012 -0.035376 0.013451 +v 0.132021 -0.037768 0.014384 +v 0.133970 -0.037778 0.014488 +v 0.132118 -0.037797 0.015065 +v 0.130081 -0.037806 0.014456 +v 0.133897 -0.037710 0.013305 +v 0.133902 -0.037720 0.010712 +v 0.132141 -0.037780 0.009663 +v 0.133582 -0.037787 0.009300 +v 0.130114 -0.037719 0.010654 +v 0.131114 -0.037795 0.008964 +v 0.134109 -0.037686 0.011890 +v 0.135095 -0.037804 0.011661 +v 0.128866 -0.037811 0.011794 +v 0.129907 -0.037728 0.013095 +v 0.135526 -0.036808 0.014413 +v 0.128698 -0.036908 0.009439 +v 0.135801 -0.036953 0.010356 +v 0.128265 -0.037158 0.013196 +v 0.127840 -0.036816 0.011212 +v 0.136268 -0.036720 0.012489 +v 0.132432 -0.036706 0.016298 +v 0.130466 -0.036678 0.016089 +v 0.128898 -0.036706 0.015005 +v 0.131475 -0.036556 0.007609 +v 0.133172 -0.036620 0.007773 +v 0.134933 -0.036391 0.008513 +v 0.134152 -0.036443 0.015973 +v 0.129284 -0.036356 0.008307 +v 0.133997 -0.035490 0.013159 +v 0.131997 -0.035490 0.014313 +v 0.133997 -0.035490 0.010849 +v 0.129997 -0.035490 0.013159 +v 0.131997 -0.035490 0.009695 +v 0.129997 -0.035490 0.010849 +v 0.139480 -0.030000 0.010165 +v 0.139612 -0.029000 0.011687 +v 0.138920 -0.030000 0.015083 +v 0.138557 -0.029000 0.015795 +v 0.135836 -0.030000 0.018650 +v 0.135725 -0.029000 0.018625 +v 0.132072 -0.029000 0.019562 +v 0.131208 -0.030000 0.019540 +v 0.128404 -0.029000 0.018699 +v 0.126862 -0.030000 0.017709 +v 0.125242 -0.029000 0.015533 +v 0.124349 -0.030000 0.012648 +v 0.124514 -0.029000 0.010165 +v 0.126385 -0.030000 0.006624 +v 0.128614 -0.029000 0.005005 +v 0.132075 -0.030000 0.004357 +v 0.134739 -0.029000 0.004866 +v 0.136525 -0.030000 0.005903 +v 0.138220 -0.029000 0.007682 +v 0.129189 -0.029000 0.008831 +v 0.127940 -0.029000 0.012411 +v 0.133073 -0.029000 0.008050 +v 0.129478 -0.029000 0.015298 +v 0.133736 -0.029000 0.015868 +v 0.136047 -0.029000 0.012645 +v 0.135422 -0.029000 0.009793 +v 0.136127 -0.034000 0.012414 +v 0.134475 -0.034000 0.015242 +v 0.131497 -0.034000 0.016095 +v 0.129070 -0.034000 0.014793 +v 0.127887 -0.034000 0.012301 +v 0.129204 -0.034000 0.008939 +v 0.132316 -0.034000 0.007940 +v 0.134965 -0.034000 0.009179 +v 0.134053 -0.033920 0.007515 +v 0.136604 -0.034002 0.010415 +v 0.131435 -0.033865 0.007080 +v 0.135966 -0.033956 0.014958 +v 0.127130 -0.033958 0.011120 +v 0.128723 -0.033902 0.008249 +v 0.128417 -0.033931 0.015393 +v 0.131051 -0.033868 0.016908 +v 0.133627 -0.033928 0.016659 +v 0.137120 -0.030101 0.012537 +v 0.137081 -0.033514 0.012767 +v 0.136820 -0.030284 0.010490 +v 0.136255 -0.033501 0.009240 +v 0.135970 -0.030293 0.008891 +v 0.134555 -0.030264 0.007625 +v 0.132372 -0.030243 0.006931 +v 0.130122 -0.030299 0.007304 +v 0.128464 -0.030108 0.008294 +v 0.127381 -0.030295 0.009901 +v 0.126931 -0.030102 0.010810 +v 0.127044 -0.033510 0.013191 +v 0.127101 -0.030267 0.013287 +v 0.127850 -0.030113 0.014985 +v 0.129147 -0.030322 0.016176 +v 0.131098 -0.030128 0.017053 +v 0.133211 -0.030290 0.016925 +v 0.135197 -0.030344 0.015922 +v 0.136618 -0.030396 0.014045 +v 0.136612 -0.030047 0.009418 +v 0.134161 -0.030025 0.006993 +v 0.130433 -0.030038 0.006884 +v 0.126689 -0.030024 0.013091 +v 0.129705 -0.030032 0.016831 +v 0.134460 -0.030031 0.016749 +v 0.136419 -0.030039 0.014935 +v 0.126510 -0.004194 0.025529 +v 0.137526 -0.002086 0.025883 +v 0.126473 0.002805 0.025771 +v 0.137488 0.004881 0.025380 +v 0.137516 0.028720 0.018770 +v 0.126478 0.028702 0.018793 +v 0.125994 -0.019449 0.013859 +v 0.137991 -0.018947 0.014577 +v 0.138238 -0.023171 0.006579 +v 0.125769 -0.023119 0.006683 +v 0.138390 0.028464 0.000354 +v 0.125643 0.028634 0.000354 +v 0.138320 -0.028647 0.000354 +v 0.137516 -0.028702 0.018793 +v 0.126478 -0.028720 0.018770 +v 0.138291 0.022027 0.009665 +v 0.138298 0.018322 0.015538 +v 0.125995 0.021446 0.010577 +v 0.138230 0.023267 0.005940 +v 0.125598 0.015556 0.018798 +v 0.125570 0.024313 0.000376 +v 0.138100 0.023951 0.000376 +v 0.125995 0.023525 0.004063 +v 0.125995 0.014722 0.018846 +v 0.138198 0.013336 0.019943 +v 0.126005 0.006915 0.022965 +v 0.137989 0.004938 0.023496 +v 0.126004 -0.003421 0.023764 +v 0.137991 -0.003908 0.023573 +v 0.138284 -0.009244 0.022179 +v 0.125773 -0.010991 0.021314 +v 0.138209 -0.014689 0.018958 +v 0.125751 -0.015934 0.017932 +v 0.125891 -0.024038 0.000434 +v 0.138073 -0.024024 0.000414 +v 0.138499 -0.027843 0.018140 +v 0.138496 -0.020962 0.012610 +v 0.138499 0.027868 0.018108 +v 0.138577 0.005101 0.024114 +v 0.138582 -0.002424 0.024551 +v 0.125499 0.021830 0.011292 +v 0.125421 0.003757 0.024494 +v 0.125425 -0.004151 0.024239 +v 0.125497 -0.021503 0.011657 +v 0.125494 0.027843 0.018140 +v 0.125604 -0.028464 0.000354 +v 0.125494 -0.027868 0.018108 +v 0.126588 0.009916 -0.024159 +v 0.127563 0.023517 -0.015538 +v 0.130346 0.023353 -0.015643 +v 0.137439 0.010670 -0.023760 +v 0.134476 0.023045 -0.015843 +v 0.137421 0.024394 -0.014992 +v 0.126235 0.025254 -0.014223 +v 0.131948 0.025902 -0.014039 +v 0.137503 -0.001415 -0.026053 +v 0.126493 -0.002317 -0.025928 +v 0.137455 -0.011625 -0.023175 +v 0.126527 -0.011749 -0.023111 +v 0.125924 -0.023991 -0.000392 +v 0.138366 -0.028478 -0.000346 +v 0.138266 -0.023928 -0.000346 +v 0.138275 0.028667 -0.000346 +v 0.125728 0.023928 -0.000346 +v 0.138309 0.024000 -0.000346 +v 0.125627 0.028478 -0.000346 +v 0.125673 -0.028647 -0.000346 +v 0.133426 0.028478 -0.006811 +v 0.136172 0.028659 -0.006811 +v 0.137717 0.026854 -0.006811 +v 0.132105 0.026052 -0.006811 +v 0.137434 0.024371 -0.006811 +v 0.133945 0.023110 -0.006811 +v 0.137538 0.027505 -0.012800 +v 0.135663 0.028799 -0.010373 +v 0.133316 0.028327 -0.011595 +v 0.127261 0.028463 -0.006811 +v 0.130036 0.028661 -0.006811 +v 0.131649 0.027125 -0.006811 +v 0.126144 0.025535 -0.006811 +v 0.131319 0.024135 -0.006811 +v 0.127982 0.023211 -0.006811 +v 0.130926 0.028268 -0.011858 +v 0.127877 0.028682 -0.010851 +v 0.126483 0.027287 -0.012932 +v 0.126465 0.028729 -0.010858 +v 0.137492 0.028953 -0.009655 +v 0.125452 0.012090 -0.021608 +v 0.125414 0.002753 -0.024529 +v 0.125423 -0.004735 -0.024179 +v 0.125419 -0.010374 -0.022439 +v 0.125491 0.027508 -0.011438 +v 0.138503 0.027547 -0.011416 +v 0.138550 0.009979 -0.022692 +v 0.138497 -0.009693 -0.023030 +v 0.138581 -0.000544 -0.024723 +v 0.137997 0.023254 -0.005851 +v 0.138496 0.023678 -0.006427 +v 0.138250 0.019219 -0.014464 +v 0.137999 0.015969 -0.017775 +v 0.137999 0.010064 -0.021671 +v 0.137989 0.002187 -0.023852 +v 0.137992 -0.005980 -0.023130 +v 0.138495 -0.012860 -0.020962 +v 0.137992 -0.011879 -0.020692 +v 0.137992 -0.016938 -0.016850 +v 0.138270 -0.020425 -0.012652 +v 0.138265 -0.023482 -0.005184 +v 0.138503 -0.027508 -0.011438 +v 0.125497 0.023727 -0.006029 +v 0.126002 0.023232 -0.005925 +v 0.125995 -0.022337 -0.008491 +v 0.125499 -0.023535 -0.007140 +v 0.125733 -0.018318 -0.015599 +v 0.125996 -0.014340 -0.019161 +v 0.125993 -0.005756 -0.023301 +v 0.126005 0.002480 -0.023730 +v 0.126002 0.008020 -0.022472 +v 0.126003 0.014860 -0.018814 +v 0.125770 0.019966 -0.013273 +v 0.134634 -0.023051 -0.015838 +v 0.129626 -0.023044 -0.015843 +v 0.126572 -0.024393 -0.014993 +v 0.137316 -0.024290 -0.015064 +v 0.131983 -0.025621 -0.014219 +v 0.133261 -0.028416 -0.006811 +v 0.132139 -0.025569 -0.006811 +v 0.136476 -0.028563 -0.006811 +v 0.134463 -0.022972 -0.006811 +v 0.137965 -0.025329 -0.006811 +v 0.132806 -0.027805 -0.012371 +v 0.137750 -0.026759 -0.013250 +v 0.134433 -0.028808 -0.010326 +v 0.137174 -0.028074 -0.012097 +v 0.128997 -0.022925 -0.006811 +v 0.131822 -0.025248 -0.006811 +v 0.126136 -0.025335 -0.006811 +v 0.127034 -0.028153 -0.006811 +v 0.130529 -0.028658 -0.006811 +v 0.126385 -0.027207 -0.013013 +v 0.128383 -0.028854 -0.010271 +v 0.131006 -0.028038 -0.012061 +v 0.137489 -0.028968 -0.009585 +v 0.126479 -0.028844 -0.010300 +v 0.125490 -0.027546 -0.011416 +v 0.124917 -0.034000 0.009261 +v 0.124555 -0.030000 0.009999 +v 0.128953 -0.034000 0.002329 +v 0.129053 -0.030000 0.002016 +v 0.129125 -0.034000 -0.019810 +v 0.129287 -0.030000 -0.018512 +v 0.124783 -0.030000 -0.027660 +v 0.124712 -0.034000 -0.027641 +v 0.128141 -0.030000 -0.036554 +v 0.125208 -0.034000 -0.033758 +v 0.124858 -0.030000 -0.032765 +v 0.130474 -0.034000 -0.037563 +v 0.133448 -0.030000 -0.037564 +v 0.135489 -0.034000 -0.036721 +v 0.138786 -0.030000 -0.033758 +v 0.138586 -0.034000 -0.033811 +v 0.139543 -0.034000 -0.028305 +v 0.139282 -0.030000 -0.027641 +v 0.134920 -0.034000 -0.020092 +v 0.134889 -0.030000 -0.019912 +v 0.135021 -0.030000 0.002329 +v 0.134932 -0.034000 0.002021 +v 0.139282 -0.034000 0.009649 +v 0.139398 -0.030000 0.009951 +v 0.138786 -0.034000 0.015767 +v 0.139060 -0.030000 0.014751 +v 0.136211 -0.030000 0.018397 +v 0.134196 -0.034000 0.019294 +v 0.130506 -0.030000 0.019572 +v 0.128820 -0.034000 0.019009 +v 0.125457 -0.030000 0.016081 +v 0.124678 -0.034000 0.014416 +v 0.130831 0.024498 0.009945 +v 0.133441 0.024497 0.013828 +v 0.130932 0.024489 0.014161 +v 0.134322 0.024497 0.011944 +v 0.133254 0.024496 0.010027 +v 0.129672 0.024497 0.011944 +v 0.132643 0.034500 0.015095 +v 0.132788 0.025240 0.015014 +v 0.134603 0.025253 0.013569 +v 0.134930 0.034500 0.013024 +v 0.135026 0.025240 0.011289 +v 0.134701 0.034500 0.010564 +v 0.132884 0.025239 0.008979 +v 0.132788 0.034500 0.009001 +v 0.130210 0.034500 0.009491 +v 0.130227 0.025253 0.009514 +v 0.128872 0.025233 0.011761 +v 0.128874 0.034500 0.011922 +v 0.130077 0.025251 0.014430 +v 0.129975 0.034500 0.014305 +v 0.132157 0.034500 0.018932 +v 0.128159 0.034500 0.017718 +v 0.138793 0.034500 0.013496 +v 0.136295 0.034500 0.017408 +v 0.129526 0.034500 0.005530 +v 0.125124 0.034500 0.013597 +v 0.126137 0.034500 0.008352 +v 0.137882 0.034500 0.008237 +v 0.133933 0.034500 0.005376 +v 0.130528 0.035325 0.005300 +v 0.132278 0.035330 0.006829 +v 0.134467 0.035325 0.005530 +v 0.125579 0.035325 0.014618 +v 0.126978 0.035334 0.010579 +v 0.125263 0.035325 0.010681 +v 0.127262 0.035334 0.014101 +v 0.127043 0.035325 0.007159 +v 0.129028 0.035327 0.007757 +v 0.131836 0.035325 0.018990 +v 0.134497 0.035353 0.016532 +v 0.132765 0.035359 0.017115 +v 0.134714 0.035336 0.007597 +v 0.137857 0.035325 0.008352 +v 0.136432 0.035373 0.009338 +v 0.138896 0.035325 0.013114 +v 0.136413 0.035325 0.017312 +v 0.129530 0.035332 0.016631 +v 0.127919 0.035325 0.017502 +v 0.136327 0.035328 0.014801 +v 0.137178 0.035329 0.012149 +v 0.130910 0.037803 0.014973 +v 0.132215 0.037732 0.014306 +v 0.131106 0.037678 0.013921 +v 0.129926 0.037721 0.013025 +v 0.133466 0.037798 0.014725 +v 0.129897 0.037780 0.010958 +v 0.128888 0.037748 0.012794 +v 0.129041 0.037802 0.011007 +v 0.131883 0.037718 0.009642 +v 0.130469 0.037792 0.009283 +v 0.134007 0.037778 0.010818 +v 0.132805 0.037800 0.009038 +v 0.134767 0.037799 0.010550 +v 0.134078 0.037745 0.013049 +v 0.135109 0.037764 0.012659 +v 0.135391 0.037000 0.014239 +v 0.131468 0.036756 0.007727 +v 0.129032 0.036785 0.015086 +v 0.132028 0.036872 0.016173 +v 0.134659 0.036781 0.008686 +v 0.133270 0.036911 0.008082 +v 0.127820 0.036752 0.011007 +v 0.130380 0.036760 0.015977 +v 0.134496 0.036651 0.015638 +v 0.136109 0.036807 0.010912 +v 0.129841 0.036541 0.008099 +v 0.128589 0.036658 0.009305 +v 0.127590 0.036332 0.013326 +v 0.136466 0.036330 0.012982 +v 0.129997 0.035490 0.013159 +v 0.131997 0.035490 0.014313 +v 0.129997 0.035490 0.010849 +v 0.133997 0.035490 0.013159 +v 0.131997 0.035490 0.009695 +v 0.133997 0.035490 0.010849 +v 0.124514 0.030000 0.010165 +v 0.124629 0.029000 0.009525 +v 0.125351 0.029000 0.015843 +v 0.125534 0.030000 0.016200 +v 0.129128 0.029000 0.019040 +v 0.129945 0.030000 0.019344 +v 0.134784 0.029000 0.019261 +v 0.134885 0.030000 0.019085 +v 0.138453 0.030000 0.016010 +v 0.139191 0.029000 0.014678 +v 0.139632 0.030000 0.010959 +v 0.138848 0.029000 0.008330 +v 0.137142 0.030000 0.006413 +v 0.134418 0.029000 0.004802 +v 0.132401 0.030000 0.004309 +v 0.129234 0.029000 0.004810 +v 0.127469 0.030000 0.005903 +v 0.133525 0.029000 0.008177 +v 0.136048 0.029000 0.010995 +v 0.129589 0.029000 0.008557 +v 0.134713 0.029000 0.015256 +v 0.130811 0.029000 0.015926 +v 0.127843 0.029000 0.013028 +v 0.127916 0.034000 0.012408 +v 0.129369 0.034000 0.015148 +v 0.131965 0.034000 0.016063 +v 0.135021 0.034000 0.014881 +v 0.136047 0.034000 0.011241 +v 0.134464 0.034000 0.008781 +v 0.131312 0.034000 0.007886 +v 0.128622 0.034000 0.009750 +v 0.129595 0.033899 0.007644 +v 0.127742 0.033893 0.009539 +v 0.132594 0.033876 0.007082 +v 0.127034 0.033934 0.012063 +v 0.136523 0.033946 0.010090 +v 0.134898 0.033922 0.008004 +v 0.128986 0.033938 0.015875 +v 0.134978 0.033927 0.015947 +v 0.136495 0.033928 0.013985 +v 0.131093 0.033938 0.016849 +v 0.127115 0.030431 0.010702 +v 0.128030 0.030263 0.008879 +v 0.129668 0.030265 0.007461 +v 0.132159 0.030318 0.006963 +v 0.134339 0.030299 0.007478 +v 0.136351 0.030109 0.009287 +v 0.136952 0.030307 0.010937 +v 0.137064 0.033514 0.011865 +v 0.136922 0.030259 0.013201 +v 0.135807 0.030363 0.015335 +v 0.133878 0.030266 0.016714 +v 0.132954 0.033502 0.016940 +v 0.132191 0.030102 0.017125 +v 0.130302 0.030279 0.016778 +v 0.128617 0.030298 0.015762 +v 0.127638 0.033499 0.014573 +v 0.127568 0.030284 0.014424 +v 0.127042 0.030105 0.013409 +v 0.126848 0.030056 0.010697 +v 0.129155 0.030018 0.007373 +v 0.132611 0.030024 0.006617 +v 0.135186 0.030031 0.007762 +v 0.137356 0.030025 0.012323 +v 0.129084 0.030030 0.016573 +v 0.136340 0.030040 0.015039 +v 0.134497 0.030017 0.016801 +v 0.139227 0.034000 0.009577 +v 0.138943 0.030000 0.008985 +v 0.134941 0.030000 0.002016 +v 0.134827 0.034000 0.001180 +v 0.134869 0.034000 -0.019810 +v 0.134707 0.030000 -0.018512 +v 0.139211 0.030000 -0.027660 +v 0.139722 0.034000 -0.028722 +v 0.136852 0.030000 -0.035914 +v 0.138013 0.034000 -0.034664 +v 0.139305 0.030000 -0.032002 +v 0.133155 0.034000 -0.037689 +v 0.131332 0.030000 -0.037673 +v 0.126815 0.034000 -0.035700 +v 0.125911 0.030000 -0.034723 +v 0.124354 0.034000 -0.030464 +v 0.124408 0.030000 -0.028351 +v 0.125264 0.034000 -0.026618 +v 0.129073 0.034000 -0.020092 +v 0.129104 0.030000 -0.019912 +v 0.128973 0.030000 0.002329 +v 0.129156 0.034000 0.001467 +v 0.124880 0.034000 0.009313 +v 0.124917 0.030000 0.009261 +v 0.124678 0.030000 0.014416 +v 0.124681 0.034000 0.014265 +v 0.127994 0.034000 0.018531 +v 0.128141 0.030000 0.018570 +v 0.133490 0.030000 0.019572 +v 0.134088 0.034000 0.019476 +v 0.137740 0.030000 0.016949 +v 0.139029 0.034000 0.015156 +v 0.139531 0.030000 0.013104 +v 0.128882 -0.024514 -0.009811 +v 0.126988 -0.024066 -0.009702 +v 0.128904 -0.023231 -0.009679 +v 0.126221 -0.026142 -0.009694 +v 0.127556 -0.025920 -0.009811 +v 0.128293 -0.028684 -0.009682 +v 0.126801 -0.027622 -0.009736 +v 0.129112 -0.027486 -0.009811 +v 0.131550 -0.025006 -0.009712 +v 0.131601 -0.027021 -0.009700 +v 0.130438 -0.026080 -0.009811 +v 0.130414 -0.023651 -0.009736 +v 0.130022 -0.028549 -0.009733 +v 0.127871 -0.025926 0.005194 +v 0.130015 -0.026960 0.005015 +v 0.129509 -0.024982 0.005213 +v 0.129024 -0.027415 0.005013 +v 0.128282 -0.024498 0.004724 +v 0.127349 -0.025866 -0.006721 +v 0.127526 -0.026643 0.004703 +v 0.127949 -0.027208 -0.006734 +v 0.129497 -0.027563 -0.006703 +v 0.130416 -0.026862 -0.006746 +v 0.130539 -0.025435 0.004716 +v 0.130263 -0.024900 -0.006721 +v 0.128459 -0.024475 -0.006727 +v 0.130698 -0.028117 -0.006877 +v 0.131723 -0.026599 -0.006900 +v 0.127556 -0.023590 -0.006870 +v 0.126185 -0.025903 -0.006910 +v 0.128852 -0.028804 -0.006890 +v 0.126927 -0.027774 -0.006859 +v 0.131375 -0.024666 -0.006878 +v 0.130019 -0.023423 -0.006893 +v 0.130438 -0.026080 -0.007811 +v 0.128719 -0.027464 -0.007811 +v 0.129275 -0.024536 -0.007811 +v 0.127556 -0.025920 -0.007811 +v 0.132529 -0.027153 -0.009709 +v 0.132264 -0.025450 -0.009698 +v 0.133868 -0.026973 -0.009811 +v 0.133663 -0.028444 -0.009714 +v 0.137300 -0.027523 -0.009715 +v 0.135757 -0.028652 -0.009702 +v 0.136404 -0.026491 -0.009811 +v 0.136710 -0.023836 -0.009699 +v 0.134719 -0.024536 -0.009811 +v 0.134891 -0.023239 -0.009707 +v 0.133284 -0.023863 -0.009703 +v 0.137722 -0.025513 -0.009713 +v 0.133875 -0.026120 0.005194 +v 0.135615 -0.026968 0.005220 +v 0.135397 -0.024923 0.005220 +v 0.133339 -0.025712 -0.006716 +v 0.134113 -0.027328 -0.006735 +v 0.134360 -0.027473 0.004703 +v 0.135416 -0.027563 -0.006726 +v 0.136311 -0.026938 0.004695 +v 0.136458 -0.026674 -0.006729 +v 0.136518 -0.025410 -0.006714 +v 0.136304 -0.025149 0.004690 +v 0.134992 -0.024345 -0.006724 +v 0.134941 -0.024437 0.004703 +v 0.133428 -0.025578 0.004707 +v 0.132578 -0.027387 -0.006884 +v 0.134980 -0.028850 -0.006881 +v 0.137413 -0.027389 -0.006878 +v 0.137459 -0.024568 -0.006888 +v 0.132409 -0.024960 -0.006892 +v 0.134607 -0.023177 -0.006874 +v 0.135112 -0.024514 -0.007811 +v 0.136226 -0.026843 -0.007811 +v 0.133653 -0.026643 -0.007811 +v 0.137289 0.024598 -0.009756 +v 0.136196 0.023514 -0.009699 +v 0.135112 0.024514 -0.009811 +v 0.133918 0.023402 -0.009718 +v 0.134882 0.027486 -0.009811 +v 0.133572 0.028356 -0.009712 +v 0.135938 0.028664 -0.009722 +v 0.132292 0.025336 -0.009705 +v 0.132657 0.027307 -0.009764 +v 0.137737 0.026594 -0.009718 +v 0.135958 0.026590 0.005194 +v 0.134069 0.026662 0.005213 +v 0.135028 0.024845 0.005228 +v 0.135491 0.024459 0.004713 +v 0.136589 0.025774 -0.006730 +v 0.136570 0.026472 0.004716 +v 0.136223 0.027024 -0.006729 +v 0.135021 0.027646 -0.006746 +v 0.134988 0.027554 0.004696 +v 0.134140 0.027365 -0.006705 +v 0.133631 0.026785 0.004692 +v 0.133380 0.025998 -0.006721 +v 0.133693 0.025122 0.004696 +v 0.134264 0.024519 -0.006723 +v 0.135810 0.024631 -0.006729 +v 0.137174 0.024282 -0.006893 +v 0.137733 0.026161 -0.006885 +v 0.135538 0.028699 -0.006878 +v 0.133002 0.028036 -0.006873 +v 0.137105 0.027759 -0.006896 +v 0.135490 0.023305 -0.006877 +v 0.132295 0.025211 -0.006913 +v 0.133666 0.023604 -0.006865 +v 0.133556 0.026080 -0.007811 +v 0.135275 0.027464 -0.007811 +v 0.134719 0.024536 -0.007811 +v 0.136438 0.025920 -0.007811 +v 0.131319 0.027481 -0.009718 +v 0.131738 0.025512 -0.009688 +v 0.130438 0.026080 -0.009811 +v 0.128719 0.027464 -0.009811 +v 0.129600 0.028720 -0.009705 +v 0.128965 0.023239 -0.009715 +v 0.127026 0.024039 -0.009699 +v 0.129275 0.024536 -0.009811 +v 0.130712 0.023851 -0.009708 +v 0.127556 0.025920 -0.009811 +v 0.126203 0.026478 -0.009720 +v 0.127613 0.028377 -0.009703 +v 0.128263 0.027133 0.005127 +v 0.129879 0.025353 0.005197 +v 0.130290 0.026542 0.005001 +v 0.128048 0.025352 0.005220 +v 0.130276 0.027105 -0.006729 +v 0.129406 0.027510 0.004702 +v 0.128690 0.027575 -0.006729 +v 0.127561 0.026727 -0.006724 +v 0.127415 0.025859 0.004699 +v 0.127659 0.025014 -0.006722 +v 0.128424 0.024555 0.004696 +v 0.129282 0.024416 -0.006729 +v 0.130214 0.024918 0.004704 +v 0.130614 0.025637 -0.006693 +v 0.126682 0.027468 -0.006884 +v 0.126274 0.025400 -0.006872 +v 0.131745 0.026477 -0.006891 +v 0.130181 0.028546 -0.006877 +v 0.127999 0.028561 -0.006902 +v 0.127718 0.023541 -0.006882 +v 0.129886 0.023371 -0.006902 +v 0.131311 0.024562 -0.006871 +v 0.128882 0.024514 -0.007811 +v 0.127556 0.025920 -0.007811 +v 0.130438 0.026080 -0.007811 +v 0.129112 0.027486 -0.007811 +v 0.131068 -0.034000 0.007967 +v 0.128780 -0.034000 0.005184 +v 0.125562 -0.034000 0.007833 +v 0.127855 -0.034000 0.010987 +v 0.124487 -0.034000 0.013974 +v 0.132625 -0.034000 0.004389 +v 0.134690 -0.034000 0.008857 +v 0.137815 -0.034000 0.006916 +v 0.129080 -0.034000 0.014878 +v 0.128437 -0.034000 0.018796 +v 0.134777 -0.034000 0.015076 +v 0.133707 -0.034000 0.019452 +v 0.137660 -0.034000 0.017064 +v 0.131707 -0.034000 0.016069 +v 0.136092 -0.034000 0.011948 +v 0.139639 -0.034000 0.012635 +v 0.127849 -0.034500 0.012656 +v 0.129961 -0.034500 0.015534 +v 0.133331 -0.034500 0.015955 +v 0.136125 -0.034500 0.012771 +v 0.134661 -0.034500 0.008797 +v 0.131363 -0.034500 0.007979 +v 0.128975 -0.034500 0.009270 +v 0.131838 -0.034500 0.004364 +v 0.136781 -0.034500 0.018075 +v 0.139511 -0.034500 0.013248 +v 0.136460 -0.034500 0.005832 +v 0.131452 -0.034500 0.019601 +v 0.139001 -0.034500 0.009121 +v 0.127282 -0.034500 0.006023 +v 0.124878 -0.034500 0.009417 +v 0.126583 -0.034500 0.017476 +v 0.124501 -0.034500 0.013092 +v 0.133767 0.034000 0.008229 +v 0.133471 0.034000 0.004532 +v 0.137154 0.034000 0.006457 +v 0.135974 0.034000 0.011027 +v 0.139343 0.034000 0.009993 +v 0.130369 0.034000 0.008268 +v 0.128216 0.034000 0.005299 +v 0.128289 0.034000 0.010266 +v 0.124380 0.034000 0.010500 +v 0.131396 0.034000 0.016226 +v 0.125581 0.034179 0.016063 +v 0.128155 0.034000 0.013486 +v 0.128544 0.034000 0.018768 +v 0.135397 0.034000 0.014371 +v 0.139210 0.034000 0.014378 +v 0.136364 0.034000 0.018307 +v 0.132156 0.034000 0.019559 +v 0.136060 0.034500 0.011069 +v 0.135388 0.034500 0.014231 +v 0.132926 0.034500 0.016041 +v 0.129303 0.034500 0.015152 +v 0.127902 0.034500 0.012060 +v 0.129002 0.034500 0.009211 +v 0.132837 0.034500 0.007823 +v 0.124431 0.034500 0.013257 +v 0.128695 0.034500 0.005015 +v 0.125184 0.034500 0.008695 +v 0.128883 0.034500 0.018955 +v 0.133772 0.034500 0.004641 +v 0.137229 0.034500 0.006500 +v 0.139626 0.034500 0.010981 +v 0.134415 0.034500 0.019346 +v 0.138493 0.034500 0.015937 +v 0.026444 0.028161 0.023596 +v 0.038156 0.018793 0.026061 +v 0.041396 0.019765 0.024258 +v 0.045665 0.016718 0.023543 +v 0.043418 0.014397 0.026274 +v 0.046283 0.010557 0.026390 +v 0.028604 0.022920 0.025681 +v 0.014151 0.031794 0.022886 +v -0.004741 0.032043 0.021774 +v -0.004307 0.033385 0.020289 +v 0.012660 0.033443 0.020837 +v 0.043757 0.026703 0.014052 +v 0.049029 0.024817 0.009600 +v 0.035005 0.033353 0.013994 +v 0.038056 0.033182 0.008095 +v 0.048980 0.026367 0.002997 +v 0.038818 0.033439 0.003215 +v 0.048975 0.026345 -0.003629 +v 0.038671 0.033394 -0.004522 +v 0.049026 0.023971 -0.011446 +v 0.036177 0.033352 -0.011869 +v 0.035043 0.033343 -0.013992 +v 0.045462 0.025193 -0.014402 +v 0.048983 0.020394 -0.016995 +v 0.048240 0.019125 -0.019215 +v 0.049038 0.014385 -0.022388 +v 0.045873 0.016610 -0.023440 +v 0.045109 0.012447 -0.026334 +v 0.048795 0.005070 -0.026372 +v 0.048982 0.010918 0.024292 +v 0.049092 0.000444 0.026610 +v 0.048193 0.019171 0.019074 +v 0.047374 0.017038 0.021760 +v 0.048982 0.020887 0.016438 +v 0.046617 0.023603 0.015437 +v 0.091774 0.026587 0.000978 +v 0.091767 0.025272 0.008028 +v 0.091802 0.022105 0.014911 +v 0.091708 0.015934 0.021285 +v 0.091747 0.008469 0.025243 +v 0.091782 -0.000403 0.026601 +v 0.091763 -0.009373 0.024909 +v 0.049026 -0.008524 0.025161 +v 0.049015 -0.013744 0.022696 +v 0.091750 -0.017390 0.020160 +v 0.049010 -0.018278 0.019295 +v 0.049002 -0.023754 0.012164 +v 0.091750 -0.023172 0.013108 +v 0.091756 -0.026492 0.003318 +v 0.048997 -0.026766 0.000369 +v 0.091751 -0.025727 -0.006834 +v 0.048951 -0.023867 -0.011818 +v 0.091749 -0.021909 -0.015120 +v 0.049027 -0.020323 -0.017225 +v 0.091782 -0.015669 -0.021491 +v 0.049003 -0.014721 -0.022144 +v 0.091729 -0.006322 -0.025943 +v 0.049009 -0.008296 -0.025215 +v 0.049051 -0.000468 -0.026573 +v 0.091737 0.004067 -0.026312 +v 0.091774 0.012542 -0.023459 +v 0.091726 0.019691 -0.017928 +v 0.091728 0.025138 -0.009016 +v 0.046150 -0.010842 -0.026381 +v 0.044392 -0.012597 -0.026276 +v 0.021395 -0.012500 -0.025377 +v 0.020629 0.012500 -0.025265 +v -0.004518 0.012500 -0.024162 +v -0.004403 0.023585 -0.024211 +v 0.029590 0.022683 -0.025713 +v 0.039118 0.018148 -0.026096 +v -0.006185 0.023668 0.023961 +v 0.020549 0.012500 0.025331 +v 0.021542 -0.012498 0.025390 +v -0.004761 -0.012500 0.024142 +v -0.003765 -0.019577 0.024293 +v 0.045354 -0.012123 0.026120 +v 0.033127 -0.018992 0.025868 +v 0.046356 -0.010439 0.026395 +v 0.046407 -0.016090 -0.023274 +v -0.004795 0.012500 0.024135 +v -0.014444 0.012500 0.020129 +v -0.017315 0.023493 0.017715 +v -0.021457 0.012500 0.012070 +v -0.023851 0.023491 0.006684 +v -0.024516 0.012500 0.002911 +v -0.023996 0.023490 -0.006137 +v -0.023694 0.012500 -0.006674 +v -0.019970 0.012500 -0.014389 +v -0.019617 0.023471 -0.014777 +v -0.013429 0.023510 -0.020708 +v -0.012946 0.012500 -0.021015 +v 0.019083 -0.012500 -0.023325 +v 0.025364 -0.012500 -0.004085 +v 0.019093 0.012500 -0.022399 +v 0.025306 0.012500 -0.004181 +v 0.019124 0.012500 0.022280 +v 0.025097 0.012500 0.005132 +v 0.019068 -0.012500 0.023462 +v 0.025047 -0.012500 0.005215 +v 0.093998 -0.025218 0.002906 +v 0.093997 -0.021686 0.013196 +v 0.093998 -0.014205 0.021040 +v 0.093997 -0.005174 0.024783 +v 0.093997 0.003492 0.025076 +v 0.093998 0.012722 0.021968 +v 0.093998 0.021402 0.013808 +v 0.093997 0.025061 0.003569 +v 0.093997 0.024794 -0.005098 +v 0.093998 0.021098 -0.014108 +v 0.093999 0.011477 -0.022844 +v 0.093998 -0.002396 -0.025351 +v 0.093997 -0.012704 -0.021891 +v 0.093998 -0.020788 -0.014708 +v 0.093997 -0.024617 -0.005655 +v -0.004181 0.032013 -0.021839 +v 0.014328 0.031651 -0.022930 +v -0.011265 0.031998 -0.019237 +v -0.017048 0.031995 -0.014321 +v -0.020250 0.032509 -0.008536 +v -0.022029 0.031966 -0.002975 +v -0.021856 0.032019 0.004370 +v -0.019351 0.032023 0.010923 +v -0.015544 0.032254 0.015744 +v -0.011384 0.031933 0.019124 +v 0.033939 0.024647 -0.023890 +v 0.042641 0.018596 -0.024262 +v 0.023548 0.029107 -0.023467 +v -0.004194 0.033380 -0.020354 +v 0.012904 0.033178 -0.021474 +v 0.012619 0.033562 -0.019090 +v -0.008588 0.032970 -0.019554 +v -0.020768 0.033377 0.000013 +v -0.017344 0.033379 0.011454 +v -0.009174 0.033381 0.018771 +v -0.014821 0.032991 -0.015464 +v -0.020550 0.033083 0.005325 +v -0.012689 0.033433 -0.016041 +v -0.019059 0.033445 -0.007369 +v 0.044770 0.001000 -0.014231 +v 0.026528 0.001000 -0.014059 +v 0.025386 0.014500 -0.014092 +v 0.017724 0.014500 -0.014174 +v 0.017745 0.033500 -0.014147 +v 0.023386 0.001000 -0.015993 +v 0.022679 0.014500 -0.018170 +v 0.022885 0.001000 -0.020510 +v 0.023381 0.014500 -0.021405 +v 0.025894 0.001000 -0.023515 +v 0.026147 0.014500 -0.023546 +v 0.043935 0.001000 -0.024158 +v 0.047346 0.001000 -0.022140 +v 0.047716 0.001000 -0.017063 +v 0.014624 0.014500 -0.023064 +v 0.012948 0.014500 -0.018613 +v 0.012741 0.014500 -0.021240 +v 0.026583 0.014500 0.023587 +v 0.026491 0.001000 0.023580 +v 0.023733 0.014500 0.021989 +v 0.023573 0.001000 0.021787 +v 0.022732 0.014500 0.017133 +v 0.022702 0.001000 0.017744 +v 0.025378 0.001000 0.014324 +v 0.026350 0.014500 0.014025 +v 0.044449 0.001000 0.014157 +v 0.017714 0.033500 0.014185 +v 0.017788 0.014500 0.014151 +v 0.044530 0.001000 0.024089 +v 0.047665 0.001000 0.016829 +v 0.047566 0.001000 0.021492 +v 0.014615 0.014500 0.023076 +v 0.012691 0.014500 0.021126 +v 0.012983 0.014500 0.018596 +v 0.012948 0.033500 0.018621 +v -0.005050 -0.029470 0.019698 +v 0.022332 -0.029500 0.014399 +v 0.020247 -0.029500 0.018106 +v 0.020565 -0.029440 0.021128 +v 0.030758 -0.029500 0.016692 +v 0.034084 -0.029491 0.014679 +v 0.032469 -0.029321 0.019790 +v 0.027755 -0.029500 0.013756 +v 0.029427 -0.029500 -0.014663 +v 0.033783 -0.029496 -0.014918 +v 0.026875 -0.029337 -0.010800 +v 0.024945 -0.029500 -0.013523 +v 0.024064 -0.029384 -0.008080 +v 0.031236 -0.029418 -0.019828 +v 0.032478 -0.029466 -0.018961 +v 0.026122 -0.029454 0.011097 +v 0.031186 -0.029393 0.019893 +v 0.040325 -0.029334 0.013937 +v 0.043751 -0.027626 0.012139 +v 0.041198 -0.028521 0.014504 +v 0.043509 -0.024541 0.017871 +v 0.040615 -0.015658 -0.026159 +v -0.005605 -0.012500 -0.024245 +v 0.033216 -0.018986 -0.025858 +v -0.004493 -0.019684 -0.024184 +v 0.040987 -0.015375 0.026180 +v -0.012293 -0.019502 0.021413 +v -0.013443 -0.012500 0.020713 +v -0.019589 -0.019500 0.014935 +v -0.020413 -0.012500 0.013787 +v -0.023005 -0.019497 0.008558 +v -0.023722 -0.012500 0.006451 +v -0.024678 -0.019502 0.000729 +v -0.024584 -0.012500 -0.001520 +v -0.022974 -0.019499 -0.008877 +v -0.022098 -0.012500 -0.011009 +v -0.019327 -0.019497 -0.015125 +v -0.016005 -0.012500 -0.018717 +v -0.013530 -0.019502 -0.020646 +v 0.041295 -0.028397 -0.014582 +v 0.043463 -0.024663 -0.017737 +v 0.040300 -0.029343 -0.013935 +v 0.043838 -0.027569 -0.012110 +v 0.021761 -0.028136 -0.022932 +v -0.003578 -0.027963 -0.021948 +v 0.023374 -0.024532 -0.024114 +v 0.026904 -0.023524 -0.024491 +v -0.007269 -0.027792 0.021067 +v -0.002785 -0.027921 0.022051 +v -0.012122 -0.028091 0.018592 +v -0.016637 -0.027974 0.014761 +v -0.019944 -0.027919 0.009901 +v -0.021718 -0.027936 0.004743 +v -0.021942 -0.028498 0.000233 +v -0.021977 -0.027919 -0.003425 +v -0.020104 -0.028252 -0.009299 +v -0.016835 -0.028025 -0.014468 +v -0.012622 -0.027939 -0.018354 +v -0.008062 -0.028070 -0.020631 +v 0.021704 -0.028250 0.022895 +v 0.024431 -0.023305 0.024498 +v 0.036187 -0.021239 0.024394 +v 0.040159 -0.019579 0.024207 +v 0.028377 -0.024645 0.024007 +v 0.033400 -0.026086 0.022207 +v 0.030676 -0.028356 0.021509 +v 0.045494 -0.016106 0.023863 +v 0.042978 -0.021250 0.021692 +v 0.035918 -0.021539 -0.024281 +v 0.032653 -0.028421 -0.020854 +v 0.030101 -0.027112 -0.022521 +v 0.040294 -0.019493 -0.024223 +v 0.043075 -0.021472 -0.021396 +v 0.033332 -0.017500 0.022121 +v 0.032400 -0.017500 0.018617 +v 0.035964 -0.017500 0.024249 +v 0.039109 -0.017501 0.024502 +v 0.042291 -0.017500 0.022707 +v 0.043600 -0.017500 0.018678 +v 0.042115 -0.017500 0.015301 +v 0.038545 -0.017500 0.013354 +v 0.035917 -0.029295 0.013806 +v 0.034280 -0.017500 0.014899 +v 0.042158 -0.017500 -0.015143 +v 0.043530 -0.017500 -0.018876 +v 0.042889 -0.017500 -0.021728 +v 0.040180 -0.017500 -0.024206 +v 0.035787 -0.017500 -0.024291 +v 0.032876 -0.017500 -0.021247 +v 0.032653 -0.017500 -0.016627 +v 0.037359 -0.017500 -0.013391 +v 0.035483 -0.029324 -0.013971 +v 0.020503 -0.017500 0.021160 +v 0.022888 -0.017500 0.023874 +v 0.025994 -0.017500 0.024603 +v 0.028975 -0.017500 0.023579 +v 0.031257 -0.017500 0.020094 +v 0.021118 -0.017500 0.015460 +v 0.026654 -0.017500 0.013453 +v 0.030197 -0.017500 0.015749 +v 0.030943 -0.017500 -0.020962 +v 0.031094 -0.017500 -0.017563 +v 0.028856 -0.017500 -0.023634 +v 0.025940 -0.017500 -0.024599 +v 0.022470 -0.017500 -0.023657 +v 0.020473 -0.017500 -0.020883 +v 0.020977 -0.029117 -0.021887 +v 0.020102 -0.029590 -0.019694 +v 0.029184 -0.017500 -0.014688 +v 0.025621 -0.017500 -0.013424 +v 0.020770 -0.017500 -0.015947 +v 0.021563 -0.029500 -0.015243 +v -0.005014 -0.029024 0.020807 +v -0.016292 -0.029450 -0.012255 +v -0.019937 -0.029352 -0.005792 +v -0.020206 -0.029444 0.002974 +v -0.019808 -0.029382 0.006335 +v -0.017434 -0.028982 0.012476 +v -0.012779 -0.029405 0.016264 +v -0.007358 -0.029388 -0.019400 +v -0.003185 -0.029374 -0.020496 +v -0.014645 -0.028950 -0.015761 +v 0.048997 -0.017500 0.012004 +v 0.031891 -0.017500 0.011718 +v 0.033072 -0.027242 0.011920 +v 0.048997 -0.017500 -0.011996 +v 0.031836 -0.017500 -0.011684 +v 0.033886 -0.027336 -0.012008 +v 0.028333 -0.027538 0.009850 +v 0.025888 -0.017500 0.007405 +v 0.025648 -0.027369 0.007042 +v 0.024173 -0.027205 0.004214 +v 0.023661 -0.017500 0.002396 +v 0.023358 -0.027165 0.000104 +v 0.023661 -0.017500 -0.002391 +v 0.024172 -0.027206 -0.004204 +v 0.025916 -0.017500 -0.007426 +v 0.026540 -0.027200 -0.008238 +v 0.030541 -0.027321 -0.011032 +v 0.032622 -0.028639 -0.012692 +v 0.022938 -0.028262 -0.000750 +v 0.026522 -0.028265 -0.008892 +v 0.033768 -0.028684 0.012843 +v 0.030226 -0.028523 0.011624 +v 0.023693 -0.028892 0.005808 +v 0.023025 -0.028633 0.003251 +v 0.023607 -0.028556 -0.004818 +v 0.026414 -0.028968 0.009773 +v 0.021520 -0.029371 -0.001854 +v 0.022009 -0.029450 0.005109 +v 0.039107 -0.023500 0.021722 +v 0.042061 -0.023402 0.021997 +v 0.039534 -0.023374 0.023893 +v 0.033509 -0.023397 0.021235 +v 0.032968 -0.023383 0.018618 +v 0.035134 -0.023500 0.018687 +v 0.039749 -0.023500 0.016764 +v 0.041056 -0.023394 0.015094 +v 0.042731 -0.023390 0.017339 +v 0.040860 -0.023500 0.019428 +v 0.038369 -0.023398 0.014026 +v 0.036886 -0.023500 0.016393 +v 0.034671 -0.023418 0.015180 +v 0.042917 -0.023400 0.019827 +v 0.036245 -0.023500 0.021352 +v 0.035637 -0.023409 0.023574 +v 0.039943 -0.001498 0.020845 +v 0.035309 -0.001613 0.017920 +v 0.036775 -0.001488 0.021452 +v 0.038390 -0.001488 0.016399 +v 0.040731 -0.001677 0.018121 +v 0.039555 -0.001990 0.021719 +v 0.039871 -0.017416 0.021595 +v 0.040939 -0.001996 0.019855 +v 0.041011 -0.017415 0.019727 +v 0.040875 -0.017418 0.017863 +v 0.039738 -0.001996 0.016532 +v 0.039734 -0.017412 0.016518 +v 0.037735 -0.017415 0.015912 +v 0.037240 -0.001983 0.016049 +v 0.035616 -0.017418 0.017046 +v 0.034844 -0.017414 0.019432 +v 0.034951 -0.001993 0.019562 +v 0.036652 -0.001987 0.021891 +v 0.036111 -0.017419 0.021526 +v 0.037766 -0.017408 0.022133 +v 0.043046 -0.017571 0.019894 +v 0.036572 -0.017584 0.014200 +v 0.034045 -0.017566 0.016002 +v 0.041933 -0.017565 0.015875 +v 0.041062 -0.017573 0.023029 +v 0.033963 -0.017579 0.022047 +v 0.036211 -0.017564 0.023748 +v 0.038799 -0.017574 0.023975 +v 0.039451 -0.017576 0.014293 +v 0.032937 -0.017584 0.018911 +v 0.035134 -0.018500 0.018687 +v 0.036886 -0.018500 0.016393 +v 0.036245 -0.018500 0.021352 +v 0.039107 -0.018500 0.021722 +v 0.040860 -0.018500 0.019428 +v 0.039749 -0.018500 0.016764 +v 0.040466 -0.023500 -0.017554 +v 0.042956 -0.023393 -0.019781 +v 0.042566 -0.023386 -0.016926 +v 0.035467 -0.023500 -0.017659 +v 0.034731 -0.023398 -0.015172 +v 0.033047 -0.023379 -0.018106 +v 0.040244 -0.023414 -0.014522 +v 0.037936 -0.023500 -0.016163 +v 0.040527 -0.023500 -0.020440 +v 0.041571 -0.023411 -0.022630 +v 0.036624 -0.023399 -0.023875 +v 0.039039 -0.023365 -0.023949 +v 0.038058 -0.023500 -0.021936 +v 0.037464 -0.023394 -0.014087 +v 0.035528 -0.023500 -0.020545 +v 0.033684 -0.023418 -0.021787 +v 0.035812 -0.001484 -0.020660 +v 0.035542 -0.001641 -0.017536 +v 0.040166 -0.001499 -0.017624 +v 0.039231 -0.001687 -0.021728 +v 0.040607 -0.001679 -0.020294 +v 0.036997 -0.001661 -0.016228 +v 0.035587 -0.017417 -0.017072 +v 0.037389 -0.017424 -0.016013 +v 0.039462 -0.001987 -0.016276 +v 0.039228 -0.017408 -0.016182 +v 0.040708 -0.017421 -0.017553 +v 0.041017 -0.001996 -0.018517 +v 0.041089 -0.017412 -0.019480 +v 0.040318 -0.017421 -0.021081 +v 0.038736 -0.017418 -0.022067 +v 0.036693 -0.001990 -0.021874 +v 0.036381 -0.017411 -0.021759 +v 0.034989 -0.001994 -0.019748 +v 0.034865 -0.017415 -0.019441 +v 0.035145 -0.017564 -0.014834 +v 0.038611 -0.017583 -0.014069 +v 0.040657 -0.017572 -0.023327 +v 0.033322 -0.017574 -0.017326 +v 0.034779 -0.017561 -0.022996 +v 0.042672 -0.017564 -0.020874 +v 0.041584 -0.017565 -0.015478 +v 0.033041 -0.017575 -0.019833 +v 0.042951 -0.017594 -0.018325 +v 0.037810 -0.017580 -0.024050 +v 0.038058 -0.018500 -0.021936 +v 0.040527 -0.018500 -0.020440 +v 0.035528 -0.018500 -0.020545 +v 0.035467 -0.018500 -0.017659 +v 0.037936 -0.018500 -0.016163 +v 0.040466 -0.018500 -0.017554 +v 0.022825 -0.023500 -0.019232 +v 0.021299 -0.023378 -0.016487 +v 0.020750 -0.023414 -0.019734 +v 0.026989 -0.023500 -0.016463 +v 0.027869 -0.023372 -0.014448 +v 0.024289 -0.023417 -0.014209 +v 0.024108 -0.023500 -0.016646 +v 0.029869 -0.023418 -0.016339 +v 0.028587 -0.023500 -0.018867 +v 0.030164 -0.023408 -0.021283 +v 0.030746 -0.023373 -0.018714 +v 0.028588 -0.023386 -0.023158 +v 0.027304 -0.023500 -0.021453 +v 0.025241 -0.023421 -0.024125 +v 0.024423 -0.023500 -0.021636 +v 0.021944 -0.023377 -0.022417 +v 0.023441 -0.001564 -0.020821 +v 0.028660 -0.001710 -0.019249 +v 0.027223 -0.001631 -0.021568 +v 0.027862 -0.001706 -0.017043 +v 0.024188 -0.001638 -0.016526 +v 0.022777 -0.001711 -0.018714 +v 0.022795 -0.017418 -0.017845 +v 0.024500 -0.017415 -0.016171 +v 0.025790 -0.001993 -0.015963 +v 0.026741 -0.017415 -0.016105 +v 0.028321 -0.017411 -0.017392 +v 0.028794 -0.017412 -0.019872 +v 0.026967 -0.017416 -0.021912 +v 0.025455 -0.001991 -0.022150 +v 0.024718 -0.017415 -0.022004 +v 0.022894 -0.017415 -0.020470 +v 0.021596 -0.017582 -0.016096 +v 0.025125 -0.017564 -0.013963 +v 0.028737 -0.017574 -0.015053 +v 0.020728 -0.017559 -0.018943 +v 0.030353 -0.017585 -0.017201 +v 0.030626 -0.017573 -0.020243 +v 0.021229 -0.017579 -0.021321 +v 0.023801 -0.017572 -0.023769 +v 0.028145 -0.017571 -0.023550 +v 0.027304 -0.018500 -0.021453 +v 0.028587 -0.018500 -0.018867 +v 0.024423 -0.018500 -0.021636 +v 0.022825 -0.018500 -0.019232 +v 0.024108 -0.018500 -0.016646 +v 0.026989 -0.018500 -0.016463 +v 0.024930 -0.023500 0.021838 +v 0.025695 -0.023381 0.024095 +v 0.022766 -0.023390 0.023147 +v 0.020663 -0.023401 0.018527 +v 0.021942 -0.023399 0.015767 +v 0.023686 -0.023500 0.016996 +v 0.030192 -0.023396 0.021342 +v 0.028294 -0.023420 0.023328 +v 0.027726 -0.023500 0.021120 +v 0.026950 -0.023373 0.014208 +v 0.029412 -0.023417 0.015636 +v 0.026482 -0.023500 0.016277 +v 0.028502 -0.023500 0.018339 +v 0.024251 -0.023413 0.014242 +v 0.022910 -0.023500 0.019776 +v 0.021203 -0.023391 0.021198 +v 0.030700 -0.023372 0.018442 +v 0.027845 -0.001499 0.020459 +v 0.027949 -0.001479 0.017482 +v 0.025986 -0.001566 0.021921 +v 0.024501 -0.001630 0.016448 +v 0.023077 -0.001479 0.019835 +v 0.028400 -0.017416 0.020613 +v 0.028766 -0.017415 0.018439 +v 0.028403 -0.001996 0.020678 +v 0.028503 -0.001993 0.017750 +v 0.027735 -0.017417 0.016714 +v 0.026550 -0.001994 0.016087 +v 0.025946 -0.017416 0.015957 +v 0.024186 -0.017408 0.016374 +v 0.022724 -0.002012 0.018005 +v 0.022769 -0.017417 0.017917 +v 0.022806 -0.017418 0.020181 +v 0.023430 -0.001987 0.021215 +v 0.024178 -0.017411 0.021771 +v 0.026546 -0.017415 0.022092 +v 0.028919 -0.017562 0.015072 +v 0.025488 -0.017594 0.014055 +v 0.030119 -0.017573 0.021404 +v 0.030723 -0.017574 0.018589 +v 0.028016 -0.017564 0.023538 +v 0.024145 -0.017577 0.023933 +v 0.022853 -0.017564 0.014902 +v 0.020721 -0.017572 0.018036 +v 0.021338 -0.017573 0.021524 +v 0.022910 -0.018500 0.019776 +v 0.023686 -0.018500 0.016996 +v 0.024930 -0.018500 0.021838 +v 0.027726 -0.018500 0.021120 +v 0.028502 -0.018500 0.018339 +v 0.026482 -0.018500 0.016277 +v 0.034103 -0.018500 0.004910 +v 0.036500 -0.018500 0.006512 +v 0.035018 -0.018500 0.007063 +v 0.032354 -0.018500 0.002115 +v 0.032156 -0.018500 0.005310 +v 0.032323 -0.018500 -0.002350 +v 0.031607 -0.018500 0.003683 +v 0.037181 -0.018500 0.008263 +v 0.034536 -0.018500 0.009563 +v 0.034319 -0.018500 0.008343 +v 0.033913 -0.018500 0.004727 +v 0.031244 -0.018500 0.007175 +v 0.029293 -0.018500 0.004008 +v 0.030415 -0.018500 0.004737 +v 0.033620 -0.018500 0.006644 +v 0.033287 -0.018500 0.007774 +v 0.031553 -0.018500 0.007445 +v 0.030599 -0.018500 0.001437 +v 0.031594 -0.018500 -0.004640 +v 0.042176 -0.018500 0.008084 +v 0.039944 -0.018500 0.006910 +v 0.043366 -0.018500 0.005464 +v 0.041662 -0.018500 -0.006588 +v 0.044674 -0.018500 -0.007284 +v 0.045618 -0.018500 -0.002493 +v 0.047778 -0.018500 -0.002735 +v 0.047260 -0.018500 0.003857 +v 0.045631 -0.018500 0.002213 +v 0.035972 -0.018500 -0.006393 +v 0.035669 -0.018500 -0.008344 +v 0.040307 -0.018500 -0.008983 +v 0.034094 -0.017500 0.004914 +v 0.033384 -0.017500 0.006828 +v 0.034556 -0.017500 0.006660 +v 0.030677 -0.017500 0.001521 +v 0.029283 -0.017500 0.004118 +v 0.031223 -0.017500 0.003676 +v 0.030498 -0.017500 0.004779 +v 0.031551 -0.017500 0.007494 +v 0.034645 -0.017500 0.009558 +v 0.033652 -0.017500 0.008260 +v 0.033565 -0.017500 0.004502 +v 0.032350 -0.017500 0.004601 +v 0.031293 -0.017500 0.007175 +v 0.031408 -0.017500 0.005526 +v 0.037838 -0.017500 0.007019 +v 0.035017 -0.017500 0.007747 +v 0.037186 -0.017500 0.008273 +v 0.031197 -0.017500 -0.004006 +v 0.031982 -0.017500 -0.000196 +v 0.042621 -0.017500 0.007950 +v 0.033257 -0.017500 -0.003951 +v 0.036500 -0.017500 -0.008813 +v 0.036761 -0.017500 -0.006710 +v 0.045935 -0.017500 -0.000415 +v 0.048127 -0.017500 -0.000150 +v 0.044791 -0.017500 -0.003955 +v 0.046343 -0.017500 -0.005651 +v 0.041467 -0.017500 -0.006538 +v 0.042292 -0.017500 -0.008511 +v 0.042219 -0.017500 0.006163 +v 0.045133 -0.017500 0.003466 +v 0.046619 -0.017500 0.004574 +v 0.396697 0.023665 0.003755 +v 0.051997 0.023782 0.002921 +v 0.051997 0.019770 0.013775 +v 0.396697 0.020093 0.013056 +v 0.396697 0.014458 0.018991 +v 0.051997 0.010880 0.021351 +v 0.396697 0.007002 0.022918 +v 0.051997 0.002789 0.023706 +v 0.396697 -0.004655 0.023644 +v 0.051997 -0.006988 0.023062 +v 0.396697 -0.015081 0.018622 +v 0.051997 -0.018145 0.015855 +v 0.396697 -0.022201 0.009364 +v 0.051997 -0.022857 0.006866 +v 0.051997 -0.023927 -0.001247 +v 0.396697 -0.023863 -0.000292 +v 0.396697 -0.022368 -0.008585 +v 0.051997 -0.021921 -0.009432 +v 0.051997 -0.016475 -0.017577 +v 0.396697 -0.016940 -0.016940 +v 0.396697 -0.010195 -0.021574 +v 0.051997 -0.004655 -0.023636 +v 0.396697 -0.002085 -0.023865 +v 0.051997 0.005486 -0.023222 +v 0.396697 0.006060 -0.023079 +v 0.051997 0.013047 -0.020092 +v 0.396697 0.013745 -0.019621 +v 0.051997 0.020093 -0.013048 +v 0.396697 0.020539 -0.012334 +v 0.051997 0.023280 -0.005247 +v 0.396697 0.023403 -0.004668 +v 0.415846 0.006277 -0.031859 +v 0.418454 0.002430 -0.035591 +v 0.416094 -0.002123 -0.032817 +v 0.417360 0.010399 -0.032601 +v 0.420666 0.010397 -0.037513 +v 0.418387 -0.003922 -0.035446 +v 0.406653 0.010399 -0.024914 +v 0.403758 0.006809 -0.025732 +v 0.397488 0.010567 -0.024286 +v 0.419163 -0.010398 -0.035448 +v 0.415541 -0.010399 -0.030407 +v 0.413826 -0.006359 -0.030019 +v 0.409237 -0.010400 -0.025867 +v 0.413097 -0.001457 -0.030127 +v 0.409788 -0.006770 -0.027474 +v 0.406020 -0.005188 -0.026525 +v 0.413109 0.005011 -0.029799 +v 0.408508 -0.000643 -0.027738 +v 0.403280 -0.005231 -0.026158 +v 0.400297 -0.010402 -0.024196 +v 0.403693 0.001664 -0.026562 +v 0.408882 0.005545 -0.027346 +v 0.413511 0.010399 -0.028544 +v 0.421271 -0.010398 -0.037988 +v 0.428220 -0.010399 -0.041760 +v 0.428146 0.010399 -0.041691 +v 0.439297 0.010400 -0.042305 +v 0.437846 -0.010400 -0.042397 +v 0.448362 -0.010400 -0.038373 +v 0.448539 0.010400 -0.037923 +v 0.455652 0.010400 -0.029280 +v 0.456609 -0.010400 -0.026724 +v 0.457188 0.010400 -0.016108 +v 0.456762 -0.010400 -0.014501 +v 0.451293 0.010400 -0.004186 +v 0.451184 -0.010400 -0.004159 +v 0.437926 -0.010400 -0.037395 +v 0.443779 -0.010400 -0.035019 +v 0.448623 -0.010400 -0.030971 +v 0.451739 -0.010400 -0.024469 +v 0.429833 -0.010400 -0.036910 +v 0.417163 -0.010400 -0.019094 +v 0.410133 -0.010464 -0.014126 +v 0.423373 -0.010400 -0.006351 +v 0.413822 -0.010471 -0.006939 +v 0.418663 -0.010400 -0.012962 +v 0.452231 -0.010400 -0.017275 +v 0.419793 -0.010501 0.000064 +v 0.424214 -0.010400 -0.034043 +v 0.437018 -0.010400 -0.002526 +v 0.428803 -0.010474 0.009421 +v 0.448624 -0.010400 -0.009021 +v 0.443010 -0.010400 -0.004494 +v 0.430722 -0.010400 -0.002904 +v 0.428566 -0.010436 0.004706 +v 0.418861 -0.010400 -0.027940 +v 0.397869 -0.011584 -0.022407 +v 0.396953 -0.020502 -0.016973 +v 0.394172 -0.011850 -0.023818 +v 0.402533 -0.011422 -0.019505 +v 0.405920 -0.011669 -0.016006 +v 0.401296 -0.024773 -0.009725 +v 0.409061 -0.011400 -0.012125 +v 0.404833 -0.026615 -0.000927 +v 0.417210 0.010400 -0.016627 +v 0.407440 0.010479 -0.017695 +v 0.441163 0.010400 -0.003515 +v 0.428824 0.010469 0.009409 +v 0.431291 0.010400 -0.002570 +v 0.418368 0.010400 -0.026450 +v 0.430081 0.010400 -0.036977 +v 0.422948 0.010400 -0.033158 +v 0.447752 0.010400 -0.032255 +v 0.438195 0.010400 -0.037340 +v 0.452026 0.010400 -0.023429 +v 0.448449 0.010400 -0.008809 +v 0.451995 0.010400 -0.016309 +v 0.422545 0.010400 -0.007207 +v 0.419433 0.010516 -0.000221 +v 0.428527 0.010433 0.004391 +v 0.413754 0.010462 -0.007103 +v 0.404028 0.026433 -0.002612 +v 0.412869 0.011557 -0.004675 +v 0.401039 0.024557 -0.010243 +v 0.408519 0.011421 -0.012976 +v 0.402951 0.011462 -0.019172 +v 0.395639 0.018995 -0.018780 +v 0.394831 0.011818 -0.023690 +v 0.353698 -0.025855 0.006543 +v 0.353655 -0.026118 -0.005682 +v 0.419627 0.023660 0.011948 +v 0.418257 0.024527 0.010066 +v 0.353684 0.025172 0.008587 +v 0.419584 0.022331 0.014301 +v 0.353808 0.020421 0.017266 +v 0.412336 0.018674 0.018926 +v 0.353719 0.011958 0.023776 +v 0.402201 0.010161 0.024781 +v 0.353686 0.002519 0.026546 +v 0.399009 -0.000947 0.026623 +v 0.353725 -0.008363 0.025345 +v 0.402308 -0.009894 0.024719 +v 0.353728 -0.016143 0.021098 +v 0.410820 -0.017834 0.019805 +v 0.353717 -0.021955 0.015041 +v 0.419132 -0.021957 0.014853 +v 0.419800 -0.023468 0.012340 +v 0.418277 -0.024533 0.010052 +v 0.411189 -0.025874 0.005893 +v 0.353733 -0.021390 -0.015838 +v 0.353664 -0.015045 -0.021907 +v 0.353855 -0.006806 -0.025898 +v 0.398081 -0.010514 -0.024322 +v 0.353719 0.003904 -0.026320 +v 0.353638 0.014483 -0.022450 +v 0.353675 0.023487 -0.012784 +v 0.353692 0.026645 -0.001062 +v 0.409884 0.026131 0.004991 +v 0.425410 0.011783 0.005191 +v 0.421309 0.011582 0.003018 +v 0.417394 0.011546 0.000145 +v 0.412356 -0.011414 -0.005763 +v 0.415288 -0.011687 -0.001669 +v 0.420413 -0.011571 0.002518 +v 0.425372 -0.011718 0.005141 +v 0.351756 -0.025459 -0.000760 +v 0.351756 -0.023792 -0.009089 +v 0.351754 -0.018160 -0.018064 +v 0.351756 -0.009161 -0.023762 +v 0.351755 0.000213 -0.025532 +v 0.351754 0.012560 -0.022433 +v 0.351755 0.021675 -0.013499 +v 0.351755 0.025293 -0.003515 +v 0.351756 0.024744 0.006044 +v 0.351754 0.020281 0.015654 +v 0.351755 0.011164 0.022972 +v 0.351756 0.001901 0.025404 +v 0.351755 -0.008617 0.024130 +v 0.351755 -0.018394 0.017718 +v 0.351755 -0.024009 0.008706 +v 0.417195 -0.021000 -0.019129 +v 0.418749 -0.021000 -0.012648 +v 0.422388 -0.021000 -0.007535 +v 0.428930 -0.021000 -0.003249 +v 0.437595 -0.021000 -0.002614 +v 0.445387 -0.021000 -0.005829 +v 0.450931 -0.021000 -0.012927 +v 0.452312 -0.021000 -0.019704 +v 0.451259 -0.021000 -0.026218 +v 0.447354 -0.021000 -0.032273 +v 0.441400 -0.021000 -0.036333 +v 0.432479 -0.021000 -0.037580 +v 0.422945 -0.021000 -0.033268 +v 0.418079 -0.021000 -0.025658 +v 0.452274 0.021000 -0.017577 +v 0.448789 0.021000 -0.009239 +v 0.441670 0.021000 -0.003722 +v 0.432758 0.021000 -0.002427 +v 0.425911 0.021000 -0.004826 +v 0.420505 0.021000 -0.009529 +v 0.417616 0.021000 -0.016182 +v 0.417394 0.021000 -0.023344 +v 0.420313 0.021000 -0.029984 +v 0.425419 0.021000 -0.035012 +v 0.433140 0.021000 -0.037535 +v 0.441163 0.021000 -0.036477 +v 0.448449 0.021000 -0.031184 +v 0.451677 0.021000 -0.024687 +v 0.426425 0.011278 0.005497 +v 0.426708 0.011936 0.008061 +v 0.425767 0.012445 0.010350 +v 0.424033 0.013147 0.012154 +v 0.425961 -0.012409 0.009954 +v 0.424276 -0.012959 0.012015 +v 0.426848 -0.011746 0.007921 +v 0.426201 -0.011871 0.006253 +v 0.427339 0.011013 0.010201 +v 0.427718 0.010807 0.006188 +v 0.426561 -0.011352 0.010706 +v 0.426394 -0.010787 0.004326 +v 0.427849 -0.010941 0.007649 +v 0.434518 0.009812 0.015265 +v 0.435020 0.007043 0.018223 +v 0.438764 0.009583 0.013078 +v 0.441150 0.006742 0.014989 +v 0.423344 -0.007737 0.024110 +v 0.423508 -0.009724 0.021724 +v 0.429103 -0.007437 0.020897 +v 0.427665 -0.009664 0.019392 +v 0.440561 -0.007747 0.014166 +v 0.435380 -0.008563 0.005624 +v 0.435495 0.008112 0.005558 +v 0.432744 0.009858 0.012030 +v 0.434012 0.009870 0.006415 +v 0.425485 0.009820 0.016222 +v 0.420291 0.009957 0.014336 +v 0.426738 0.009964 0.019582 +v 0.423282 0.009560 0.022043 +v 0.423751 0.006742 0.025034 +v 0.418360 -0.007903 0.015451 +v 0.418531 0.008570 0.015352 +v 0.425155 -0.009930 0.016412 +v 0.419752 -0.009827 0.014648 +v 0.432771 -0.009865 0.012015 +v 0.433616 -0.009957 0.006643 +v 0.434434 -0.009773 0.015359 +v 0.438329 -0.009742 0.013146 +v 0.425664 -0.008666 0.011234 +v 0.426120 0.005833 0.010971 +v 0.428475 -0.006992 0.009611 +v 0.426299 -0.005692 0.010868 +v 0.427834 0.008988 0.009981 +v 0.425717 0.008739 0.011204 +v 0.427769 -0.009036 0.010019 +v 0.428431 0.006762 0.009637 +v 0.434681 -0.007824 0.017489 +v 0.429678 0.006756 0.021597 +v 0.428467 0.008934 0.019773 +v 0.430554 -0.008296 0.013295 +v 0.428457 -0.009187 0.014506 +v 0.431881 -0.008472 0.012529 +v 0.431681 -0.005859 0.012644 +v 0.429790 -0.005872 0.013736 +v 0.429016 -0.004119 0.014183 +v 0.427556 -0.006690 0.015026 +v 0.426234 -0.008690 0.015789 +v 0.426473 -0.005868 0.015651 +v 0.430714 -0.004528 0.020113 +v 0.432900 -0.004335 0.018866 +v 0.434564 -0.005899 0.017779 +v 0.428175 0.006078 0.014669 +v 0.429281 0.004155 0.014030 +v 0.429742 0.005874 0.013764 +v 0.431673 0.005880 0.012649 +v 0.430588 0.007408 0.013276 +v 0.429790 0.009128 0.013735 +v 0.427556 0.008310 0.015026 +v 0.431872 0.008421 0.012535 +v 0.426294 0.007266 0.015754 +v 0.427213 0.004980 0.015224 +v 0.430436 0.005023 0.021044 +v 0.433630 0.004292 0.019141 +v 0.432293 -0.009443 0.015623 +v 0.432887 -0.007077 0.015283 +v 0.431653 -0.008308 0.016125 +v 0.429484 -0.006692 0.017377 +v 0.428195 -0.008228 0.018001 +v 0.430541 -0.010207 0.016709 +v 0.429101 -0.009699 0.017470 +v 0.428342 -0.006402 0.017911 +v 0.429395 -0.005044 0.017314 +v 0.431102 -0.006195 0.016443 +v 0.431661 -0.004989 0.016013 +v 0.424188 -0.007068 0.007722 +v 0.425963 -0.006453 0.006872 +v 0.425996 -0.007638 0.006687 +v 0.424858 -0.008596 0.007329 +v 0.424627 -0.008873 0.008047 +v 0.427652 -0.007731 0.014876 +v 0.423970 -0.007418 0.008428 +v 0.428213 -0.006101 0.014542 +v 0.424943 -0.005917 0.007853 +v 0.429734 -0.006127 0.013671 +v 0.430464 -0.007678 0.013244 +v 0.426622 -0.007905 0.006892 +v 0.425879 -0.008888 0.007339 +v 0.429256 -0.009122 0.013941 +v 0.428227 -0.008788 0.014561 +v 0.427692 -0.009720 0.015043 +v 0.426799 -0.008162 0.015543 +v 0.431083 -0.005924 0.013083 +v 0.429086 -0.004660 0.014216 +v 0.427032 -0.006078 0.015414 +v 0.431445 -0.008099 0.012860 +v 0.430438 -0.009797 0.013463 +v 0.429042 -0.010218 0.014246 +v 0.430798 -0.007952 0.014309 +v 0.430102 -0.006195 0.014711 +v 0.429035 -0.008805 0.015327 +v 0.428339 -0.007048 0.015729 +v 0.428274 0.008394 0.017967 +v 0.428338 0.006209 0.017902 +v 0.429471 0.008285 0.017384 +v 0.429450 0.010016 0.017275 +v 0.430082 0.004771 0.016929 +v 0.431640 0.005085 0.015980 +v 0.430528 0.006010 0.016774 +v 0.432611 0.006180 0.015462 +v 0.432816 0.008453 0.015342 +v 0.431706 0.008205 0.016094 +v 0.431360 0.010081 0.016173 +v 0.425623 0.006629 0.006903 +v 0.424486 0.006684 0.007558 +v 0.423997 0.007933 0.008009 +v 0.425725 0.008339 0.006818 +v 0.427598 0.007586 0.014766 +v 0.425017 0.009100 0.007806 +v 0.427860 0.008480 0.014771 +v 0.428933 0.009119 0.014142 +v 0.429997 0.008614 0.013519 +v 0.426529 0.008200 0.006948 +v 0.430415 0.007469 0.013271 +v 0.426246 0.006271 0.007100 +v 0.429585 0.005958 0.013748 +v 0.424404 0.006288 0.008176 +v 0.427954 0.006435 0.014707 +v 0.427030 0.008814 0.015417 +v 0.428050 0.009958 0.014821 +v 0.426754 0.006972 0.015589 +v 0.431506 0.007929 0.012837 +v 0.430975 0.005813 0.013132 +v 0.429194 0.004681 0.014156 +v 0.430060 0.010095 0.013665 +v 0.427537 0.005465 0.015121 +v 0.430805 0.007074 0.014305 +v 0.428631 0.006476 0.015560 +v 0.429269 0.008950 0.015192 +v 0.092815 0.047249 0.010440 +v 0.093696 0.047597 0.009490 +v 0.093738 0.047373 0.010291 +v 0.090727 0.047564 0.008672 +v 0.091074 0.047523 0.008926 +v 0.091504 0.047212 0.010158 +v 0.092481 0.047093 0.010884 +v 0.093913 0.047911 0.008447 +v 0.093266 0.047907 0.008258 +v 0.091634 0.047070 0.010702 +v 0.093445 0.048023 0.007905 +v 0.091955 0.047871 0.007976 +v 0.091405 0.047871 0.007801 +v 0.090766 0.047255 0.009775 +v 0.092507 0.048044 0.007538 +v 0.094100 0.038801 0.007937 +v 0.094605 0.039064 0.007168 +v 0.094602 0.039261 0.006472 +v 0.094088 0.039438 0.005685 +v 0.093195 0.039456 0.005343 +v 0.092490 0.039357 0.005469 +v 0.091656 0.038981 0.006533 +v 0.091814 0.038737 0.007445 +v 0.092294 0.038630 0.007974 +v 0.093211 0.038634 0.008247 +v 0.094595 0.039132 0.007780 +v 0.094021 0.045592 0.009610 +v 0.094811 0.039290 0.007289 +v 0.094237 0.045750 0.009119 +v 0.094806 0.039517 0.006486 +v 0.094232 0.045977 0.008316 +v 0.094416 0.039686 0.005768 +v 0.093842 0.046146 0.007599 +v 0.094214 0.039722 0.005578 +v 0.093461 0.039756 0.005220 +v 0.092887 0.046216 0.007050 +v 0.093183 0.039742 0.005182 +v 0.092631 0.039678 0.005237 +v 0.092057 0.046137 0.007068 +v 0.092370 0.039629 0.005328 +v 0.091796 0.046088 0.007159 +v 0.092129 0.039570 0.005459 +v 0.091554 0.046030 0.007289 +v 0.091473 0.039275 0.006296 +v 0.090899 0.045735 0.008126 +v 0.091407 0.039195 0.006557 +v 0.091386 0.039117 0.006825 +v 0.090812 0.045577 0.008656 +v 0.091589 0.038913 0.007608 +v 0.091015 0.045373 0.009438 +v 0.091166 0.045321 0.009669 +v 0.092144 0.038790 0.008219 +v 0.091570 0.045249 0.010049 +v 0.092648 0.038767 0.008459 +v 0.092074 0.045226 0.010289 +v 0.093202 0.038794 0.008534 +v 0.093747 0.038871 0.008436 +v 0.093173 0.045330 0.010266 +v 0.094228 0.038987 0.008176 +v 0.094449 0.045141 0.011335 +v 0.095269 0.045436 0.010552 +v 0.090448 0.044853 0.011095 +v 0.090162 0.044903 0.010831 +v 0.093008 0.044866 0.011853 +v 0.092228 0.044797 0.011850 +v 0.095821 0.045877 0.009167 +v 0.095762 0.046191 0.008040 +v 0.089306 0.045623 0.008022 +v 0.089297 0.045303 0.009149 +v 0.094796 0.046568 0.006407 +v 0.093445 0.046665 0.005642 +v 0.090201 0.046163 0.006394 +v 0.090811 0.046347 0.005939 +v 0.091518 0.046495 0.005637 +v 0.094904 0.045663 0.011045 +v 0.094490 0.045529 0.011389 +v 0.092146 0.045162 0.011948 +v 0.091873 0.045151 0.011901 +v 0.090394 0.045224 0.011181 +v 0.089681 0.045395 0.010355 +v 0.089284 0.045643 0.009355 +v 0.089294 0.046019 0.008030 +v 0.090225 0.046551 0.006445 +v 0.091389 0.046846 0.005771 +v 0.091653 0.046890 0.005696 +v 0.093293 0.047031 0.005713 +v 0.094742 0.046939 0.006492 +v 0.095277 0.046811 0.007113 +v 0.095717 0.046571 0.008097 +v 0.095801 0.046278 0.009158 +v 0.095705 0.046121 0.009681 +v 0.095250 0.045809 0.010638 +v 0.091880 0.045421 0.011832 +v 0.090121 0.046693 0.006791 +v 0.090304 0.046760 0.006611 +v 0.091164 0.047676 0.007340 +v 0.091719 0.047428 0.006329 +v 0.091950 0.047461 0.006284 +v 0.093061 0.047687 0.006577 +v 0.093867 0.047659 0.006930 +v 0.094820 0.047360 0.007541 +v 0.094353 0.047727 0.008161 +v 0.095044 0.047265 0.007947 +v 0.094434 0.047688 0.008323 +v 0.095186 0.046770 0.009738 +v 0.094489 0.047248 0.009893 +v 0.095116 0.046702 0.009954 +v 0.094130 0.047043 0.010505 +v 0.093875 0.046948 0.010758 +v 0.092559 0.046464 0.011424 +v 0.092142 0.045431 0.011877 +v 0.091928 0.046188 0.011511 +v 0.091714 0.046185 0.011456 +v 0.090033 0.046149 0.010314 +v 0.089921 0.046196 0.010110 +v 0.089702 0.046683 0.008325 +v 0.089762 0.046750 0.008106 +v 0.092879 0.046525 0.010235 +v 0.093761 0.046873 0.009285 +v 0.091568 0.046488 0.009953 +v 0.091138 0.046799 0.008721 +v 0.092019 0.047147 0.007771 +v 0.093330 0.047184 0.008053 +v 0.352455 -0.024903 -0.000390 +v 0.353457 -0.023815 -0.000363 +v 0.353457 -0.023902 -0.000363 +v 0.319029 -0.027256 -0.001127 +v 0.257186 -0.034199 -0.001244 +v 0.259242 -0.033975 -0.001333 +v 0.277621 -0.031854 -0.001589 +v 0.289016 -0.030540 -0.001748 +v 0.288454 -0.030605 -0.001740 +v 0.198555 -0.040224 0.001039 +v 0.225092 -0.037698 0.000135 +v 0.187790 -0.041217 0.001090 +v 0.177024 -0.042209 0.001141 +v 0.172794 -0.042609 0.001010 +v 0.163052 -0.042435 0.000695 +v 0.163579 -0.043480 0.000724 +v 0.155247 -0.044371 0.000013 +v 0.152217 -0.044695 -0.000245 +v 0.117685 -0.047685 -0.003615 +v 0.109314 -0.047616 -0.003326 +v 0.109122 -0.046520 -0.003311 +v 0.109020 -0.047603 -0.003288 +v 0.107831 -0.047550 -0.003131 +v 0.101656 -0.046179 -0.002301 +v 0.127581 -0.047315 -0.003349 +v 0.132062 -0.045881 -0.003039 +v 0.135992 -0.046574 -0.002589 +v 0.137322 -0.046457 -0.002469 +v 0.101927 -0.047291 -0.002352 +v 0.100976 -0.047212 -0.002134 +v 0.093923 -0.046626 -0.000516 +v 0.050792 -0.040055 0.007288 +v 0.051124 -0.039006 0.007211 +v -0.026544 0.035661 0.013517 +v -0.026559 0.034603 0.013529 +v -0.011081 0.034178 0.001114 +v 0.002113 0.034104 -0.003233 +v 0.002917 0.035181 -0.003308 +v -0.011184 0.035244 0.001180 +v -0.008881 0.034140 -0.000164 +v -0.008449 0.034135 -0.000344 +v -0.007098 0.035183 -0.001025 +v -0.004577 0.034094 -0.001957 +v -0.005324 0.035171 -0.001607 +v -0.001917 0.034092 -0.002534 +v -0.002781 0.035155 -0.002442 +v -0.000667 0.034092 -0.002806 +v 0.014029 0.034385 -0.003377 +v 0.009917 0.034257 -0.003521 +v 0.011826 0.035380 -0.003492 +v 0.008315 0.034208 -0.003577 +v 0.009921 0.035328 -0.003525 +v 0.011091 0.035352 -0.003561 +v 0.015910 0.034461 -0.003146 +v 0.016450 0.035552 -0.003061 +v 0.020604 0.034694 -0.002056 +v 0.020993 0.035777 -0.001925 +v 0.024901 0.034961 -0.000206 +v 0.025421 0.036052 0.000074 +v 0.036450 0.036356 0.006531 +v 0.036380 0.037396 0.006499 +v 0.039824 0.036943 0.007769 +v 0.039946 0.038029 0.007801 +v 0.042880 0.037489 0.008236 +v 0.043559 0.038689 0.008257 +v 0.047318 0.038298 0.007968 +v 0.057786 0.041342 0.005577 +v 0.060280 0.041780 0.005158 +v 0.048143 0.039540 0.007833 +v 0.067152 0.042987 0.004002 +v 0.088824 0.046098 0.000697 +v 0.079657 0.044911 0.002473 +v 0.076883 0.044484 0.002812 +v 0.107834 0.046453 -0.003111 +v 0.099971 0.047145 -0.001963 +v 0.101695 0.046182 -0.002308 +v 0.099574 0.047108 -0.001868 +v 0.118817 0.046583 -0.003609 +v 0.107544 0.047541 -0.003167 +v 0.107823 0.047546 -0.003182 +v 0.109720 0.046537 -0.003357 +v 0.111006 0.047603 -0.003357 +v 0.115397 0.047681 -0.003599 +v 0.127959 0.046201 -0.003328 +v 0.161200 0.042618 0.000583 +v 0.159130 0.043934 0.000352 +v 0.162634 0.042482 0.000637 +v 0.318032 0.026263 -0.001155 +v 0.300198 0.029292 -0.001531 +v 0.302521 0.027916 -0.001598 +v 0.290138 0.030393 -0.001745 +v 0.352474 0.024884 -0.000389 +v 0.353457 0.023815 -0.000363 +v 0.353457 0.023902 -0.000363 +v 0.082735 -0.036006 0.023680 +v 0.082438 -0.038247 0.021093 +v 0.080645 -0.040822 0.017285 +v 0.072894 -0.042327 0.013190 +v 0.076944 -0.042246 0.014193 +v 0.080223 -0.041117 0.016755 +v 0.082652 -0.025507 0.030212 +v 0.082656 -0.025901 0.030068 +v 0.082678 -0.028528 0.028979 +v 0.082700 -0.031149 0.027538 +v 0.082728 -0.035032 0.024454 +v 0.049601 -0.017126 0.028319 +v 0.044253 -0.016877 0.028439 +v 0.040704 -0.016711 0.028518 +v 0.033701 -0.015935 0.029208 +v 0.028513 -0.014867 0.030205 +v 0.023496 -0.013239 0.031269 +v 0.020583 -0.011591 0.031917 +v 0.018721 -0.009891 0.032746 +v 0.018268 -0.009478 0.032948 +v 0.016408 -0.006657 0.034292 +v 0.015426 -0.003900 0.035227 +v 0.015280 -0.002816 0.035385 +v 0.015000 -0.000727 0.035688 +v 0.014986 -0.000000 0.035704 +v 0.082235 -0.023369 0.030785 +v 0.081374 -0.022100 0.030934 +v 0.081062 -0.021640 0.030988 +v 0.078968 -0.020163 0.030907 +v 0.075865 -0.019000 0.030581 +v 0.073653 -0.018582 0.030307 +v 0.070381 -0.017964 0.029903 +v 0.059358 -0.017331 0.028818 +v 0.053777 -0.017214 0.028533 +v 0.353457 -0.018679 0.014411 +v 0.353457 0.002335 0.023337 +v 0.353457 0.009943 0.021278 +v 0.353457 0.016289 0.017004 +v 0.353457 0.016228 0.017067 +v 0.353457 0.014659 0.018119 +v 0.353457 0.018103 0.015111 +v 0.353457 0.022229 0.008183 +v 0.353457 0.023786 0.000809 +v 0.353457 -0.022491 0.007467 +v 0.353457 -0.007197 0.022098 +v 0.353457 -0.012890 0.019663 +v 0.353457 -0.005584 0.022788 +v 0.059114 -0.041003 0.012791 +v 0.073631 -0.018339 0.030315 +v 0.091951 -0.015850 0.033628 +v 0.157142 -0.033295 0.039873 +v 0.157003 -0.035768 0.036591 +v 0.166463 -0.035823 0.036248 +v 0.188636 -0.037846 0.028339 +v 0.214800 -0.034535 0.031659 +v 0.268658 0.016242 0.036173 +v 0.021917 -0.000014 0.031856 +v 0.275441 0.032088 0.006896 +v 0.118368 0.048055 0.000883 +v -0.006751 0.035699 -0.000617 +v 0.000557 0.034184 0.030490 +v 0.007842 0.033816 0.030703 +v 0.011256 0.030226 0.034565 +v 0.011433 0.029968 0.034625 +v 0.014168 0.030682 0.031912 +v 0.057966 -0.040919 0.012593 +v 0.111692 -0.048168 -0.002979 +v 0.268877 -0.033362 -0.000978 +v 0.338164 -0.026032 0.000815 +v 0.351946 -0.025349 0.000647 +v 0.344045 -0.025692 -0.000080 +v 0.351946 -0.025408 0.000106 +v 0.328340 -0.026866 -0.000396 +v 0.277290 -0.032393 -0.001192 +v 0.277681 -0.032348 -0.001191 +v 0.318200 -0.027818 0.000241 +v 0.298116 -0.030016 -0.001122 +v 0.301958 -0.029578 -0.001109 +v 0.272283 -0.032970 -0.001064 +v 0.275554 -0.032075 0.006887 +v 0.249950 -0.035542 -0.000495 +v 0.213330 -0.039348 0.001132 +v 0.241842 -0.036385 -0.000135 +v 0.167715 -0.043582 0.001411 +v 0.186499 -0.041834 0.001679 +v 0.198505 -0.040722 0.001434 +v 0.163304 -0.044030 0.001118 +v 0.141943 -0.046420 -0.001297 +v 0.121430 -0.048105 -0.003069 +v 0.121488 -0.048102 -0.003066 +v 0.131610 -0.047512 -0.002577 +v 0.104182 -0.047912 -0.002235 +v 0.096402 -0.047378 -0.000642 +v 0.099850 -0.047064 0.005077 +v 0.083259 -0.045643 0.005147 +v 0.084444 -0.046068 0.002186 +v 0.056349 -0.040800 0.012314 +v 0.055876 -0.040780 0.012149 +v 0.053474 -0.040709 0.010826 +v 0.053025 -0.040694 0.010463 +v 0.051241 -0.040595 0.008402 +v 0.050875 -0.040558 0.007779 +v 0.079997 -0.043190 0.012768 +v 0.094889 -0.039020 0.021781 +v 0.093470 -0.032194 0.028341 +v 0.092440 -0.021755 0.032914 +v 0.057408 -0.016569 0.028621 +v 0.057191 -0.011607 0.028647 +v 0.018763 -0.000013 0.032899 +v 0.015192 0.015083 0.034867 +v 0.014009 0.021124 0.035429 +v 0.015068 0.021695 0.034289 +v 0.014842 0.027105 0.033572 +v 0.012936 0.027777 0.035132 +v 0.013188 0.032931 0.029551 +v 0.009336 0.032031 0.033884 +v 0.010438 0.031418 0.034288 +v 0.006672 0.033513 0.032908 +v -0.001484 0.034408 0.029683 +v -0.013215 0.035390 0.023543 +v -0.026145 0.036177 0.013863 +v -0.010907 0.035762 0.001614 +v -0.002510 0.035672 -0.001980 +v 0.010467 0.035852 -0.003065 +v 0.021165 0.036315 -0.001313 +v 0.016226 0.036064 -0.002577 +v 0.039734 0.038539 0.008296 +v 0.038892 0.038216 0.013036 +v 0.036165 0.037921 0.006997 +v 0.043515 0.039208 0.008777 +v 0.050633 0.039955 0.012715 +v 0.064382 0.041684 0.012556 +v 0.066146 0.042800 0.009269 +v 0.062710 0.042736 0.005158 +v 0.084382 0.046053 0.002195 +v 0.083253 0.045640 0.005167 +v 0.084021 0.046012 0.002279 +v 0.083342 0.045916 0.002379 +v 0.074894 0.044733 0.003623 +v 0.068928 0.043755 0.004375 +v 0.102690 0.047831 -0.001976 +v 0.118619 0.048172 -0.003099 +v 0.111020 0.048143 -0.002908 +v 0.110352 0.048141 -0.002892 +v 0.136476 0.046430 0.007719 +v 0.140079 0.046621 -0.001533 +v 0.136727 0.047017 -0.002039 +v 0.161381 0.044197 0.001102 +v 0.213891 0.039177 0.005920 +v 0.197548 0.040819 0.001570 +v 0.273228 0.032865 -0.001019 +v 0.318200 0.027818 0.000251 +v 0.288630 0.031087 -0.001237 +v 0.351946 0.024821 0.005087 +v 0.351946 0.025408 0.000116 +v 0.351947 0.023574 0.009128 +v 0.338147 0.025188 0.006324 +v 0.338133 0.023244 0.011648 +v 0.346461 0.022586 0.011689 +v 0.351955 0.019446 0.015885 +v 0.351951 0.021287 0.013521 +v 0.351960 0.017282 0.018146 +v 0.346453 0.019502 0.016319 +v 0.351957 0.018648 0.016909 +v 0.351963 0.015313 0.019929 +v 0.346437 0.010911 0.022950 +v 0.351964 0.011074 0.022520 +v 0.351960 0.005495 0.024352 +v 0.346443 0.005612 0.024717 +v 0.351960 0.006971 0.024082 +v 0.346444 -0.000005 0.025324 +v 0.351958 0.002127 0.024967 +v 0.351960 -0.007360 0.023968 +v 0.346443 -0.005623 0.024715 +v 0.351960 -0.005498 0.024339 +v 0.351958 -0.002550 0.024928 +v 0.346437 -0.010920 0.022946 +v 0.351963 -0.010752 0.022589 +v 0.351957 -0.018816 0.016725 +v 0.346453 -0.019508 0.016311 +v 0.351963 -0.015517 0.019768 +v 0.346437 -0.015596 0.020113 +v 0.351963 -0.015485 0.019798 +v 0.351964 -0.011726 0.022193 +v 0.351947 -0.023606 0.009048 +v 0.346461 -0.022591 0.011679 +v 0.351950 -0.021546 0.013115 +v 0.351955 -0.019449 0.015889 +v 0.351946 -0.024919 0.004618 +v 0.092464 -0.045679 0.008711 +v 0.092464 0.045669 0.008744 +v 0.094311 0.047188 -0.000121 +v 0.318108 -0.025553 0.011599 +v 0.318108 0.025549 0.011610 +v 0.268761 0.032217 0.012423 +v 0.061196 0.038229 0.018994 +v 0.075825 0.035170 0.023784 +v 0.017684 0.031363 0.029585 +v 0.018250 0.027875 0.031242 +v 0.021503 0.028384 0.030285 +v 0.016946 0.033488 0.027269 +v 0.057734 0.021328 0.028597 +v 0.044607 0.024346 0.028115 +v 0.045083 0.028401 0.027171 +v 0.034921 0.030504 0.027299 +v 0.035334 0.033512 0.025285 +v 0.027923 0.034153 0.025787 +v 0.027982 0.035716 0.022929 +v 0.015941 0.031050 0.030520 +v 0.016578 0.027519 0.032175 +v 0.018499 0.022414 0.031890 +v 0.011939 0.034287 0.026587 +v 0.034576 0.026862 0.028508 +v 0.027879 0.031799 0.027944 +v 0.020690 0.033909 0.026364 +v 0.016039 0.034735 0.024400 +v 0.028196 0.036286 0.019503 +v 0.036648 0.037043 0.018964 +v 0.035846 0.035859 0.022371 +v 0.046502 0.035710 0.022178 +v 0.045710 0.032366 0.025221 +v 0.059004 0.031022 0.025866 +v 0.058274 0.025951 0.027857 +v 0.074523 0.026602 0.028833 +v 0.073629 0.018320 0.030315 +v 0.338090 0.018492 0.018702 +v 0.338110 0.020301 0.016518 +v 0.317959 0.012718 0.026883 +v 0.317984 0.019100 0.022876 +v 0.318053 0.023040 0.017332 +v 0.294531 0.026673 0.018728 +v 0.091949 0.015830 0.033629 +v 0.157517 0.022607 0.047743 +v 0.167315 0.019495 0.049105 +v 0.148973 0.029710 0.042720 +v 0.141689 0.025490 0.044327 +v 0.149023 0.025940 0.045297 +v 0.141674 0.021603 0.046100 +v 0.149075 0.022079 0.047194 +v 0.141669 0.014697 0.047838 +v 0.149181 0.015120 0.049116 +v 0.112911 0.024579 0.036662 +v 0.166465 0.035808 0.036273 +v 0.157143 0.033274 0.039898 +v 0.157274 0.030098 0.043043 +v 0.157399 0.026423 0.045730 +v 0.135239 0.029018 0.040639 +v 0.113734 0.035012 0.029816 +v 0.074177 0.023587 0.029671 +v 0.092438 0.021730 0.032919 +v 0.102339 0.021123 0.035174 +v 0.093088 0.028807 0.030388 +v 0.092744 0.025195 0.031943 +v 0.059921 0.035441 0.022559 +v 0.047652 0.037689 0.018752 +v 0.141713 0.029334 0.041875 +v 0.135448 0.035331 0.034817 +v 0.135666 0.039135 0.029154 +v 0.188638 0.037839 0.028361 +v 0.189660 0.023972 0.046098 +v 0.215106 0.024201 0.042946 +v 0.189516 0.027541 0.043881 +v 0.215039 0.027504 0.040735 +v 0.214965 0.030457 0.037953 +v 0.189193 0.033534 0.037803 +v 0.214885 0.032822 0.034845 +v 0.189016 0.035547 0.034484 +v 0.148922 0.033013 0.039668 +v 0.157004 0.035752 0.036616 +v 0.148869 0.035627 0.036465 +v 0.148737 0.039009 0.030453 +v 0.165090 0.042038 0.018466 +v 0.136081 0.043939 0.018371 +v 0.136283 0.045445 0.013030 +v 0.117564 0.047448 0.005896 +v 0.338110 -0.020307 0.016510 +v 0.317984 -0.019110 0.022866 +v 0.338067 -0.011330 0.023806 +v 0.338065 -0.013970 0.022441 +v 0.294418 -0.014533 0.031213 +v 0.241884 -0.028970 0.034059 +v 0.268658 -0.016260 0.036168 +v 0.268640 -0.007790 0.037515 +v 0.189358 -0.030847 0.041012 +v 0.167006 -0.026913 0.045566 +v 0.189659 -0.023999 0.046084 +v 0.214965 -0.030477 0.037931 +v 0.215039 -0.027528 0.040716 +v 0.215106 -0.024226 0.042932 +v 0.215165 -0.020860 0.044482 +v 0.189910 -0.017119 0.048518 +v 0.268640 0.007776 0.037517 +v 0.190352 -0.000008 0.049900 +v 0.190236 -0.007763 0.049615 +v 0.167449 -0.016168 0.049926 +v 0.167314 -0.019521 0.049097 +v 0.177959 -0.023631 0.047109 +v 0.136082 -0.043945 0.018351 +v 0.136283 -0.045449 0.013010 +v 0.115935 -0.044573 0.015502 +v 0.115151 -0.042228 0.020188 +v 0.117567 -0.047451 0.005876 +v 0.136477 -0.046433 0.007699 +v 0.155039 -0.044870 0.000568 +v 0.189191 -0.033552 0.037778 +v 0.166836 -0.030471 0.042789 +v 0.157398 -0.026452 0.045712 +v 0.157516 -0.022636 0.047730 +v 0.149075 -0.022108 0.047182 +v 0.157273 -0.030124 0.043021 +v 0.149023 -0.025969 0.045280 +v 0.141674 -0.021631 0.046089 +v 0.148973 -0.029737 0.042698 +v 0.141689 -0.025519 0.044311 +v 0.190236 0.007748 0.049616 +v 0.167832 -0.007208 0.050904 +v 0.158030 -0.006920 0.050707 +v 0.157732 -0.015642 0.049833 +v 0.149181 -0.015143 0.049112 +v 0.141669 -0.014720 0.047835 +v 0.149336 -0.006659 0.049855 +v 0.167832 0.007194 0.050905 +v 0.215166 0.020835 0.044491 +v 0.141681 -0.006451 0.048432 +v 0.167450 0.016144 0.049931 +v 0.135875 -0.041869 0.023723 +v 0.102611 -0.024794 0.034075 +v 0.124001 -0.032210 0.035005 +v 0.135449 -0.035350 0.034795 +v 0.135667 -0.039146 0.029133 +v 0.102341 -0.021149 0.035168 +v 0.135151 -0.025153 0.042949 +v 0.135240 -0.029046 0.040619 +v 0.141713 -0.029361 0.041854 +v 0.141743 -0.032765 0.038910 +v 0.353457 -0.021061 0.010944 +v 0.353457 -0.022701 0.007119 +v 0.353457 -0.023724 0.002546 +v 0.353457 -0.015211 0.018085 +v 0.353457 -0.018331 0.014951 +v 0.353457 -0.018491 0.014790 +v 0.353457 -0.007579 0.022314 +v 0.353457 -0.011562 0.020568 +v 0.353457 -0.005169 0.022872 +v 0.353457 -0.003171 0.023335 +v 0.353457 0.005955 0.022793 +v 0.353457 0.001417 0.023504 +v 0.353457 0.010336 0.021200 +v 0.353457 0.016289 0.017000 +v 0.353457 0.014242 0.018844 +v 0.353457 0.017602 0.015816 +v 0.353457 0.020256 0.012331 +v 0.353457 0.022121 0.008694 +v 0.353457 0.023262 0.005046 +v 0.353457 0.023680 0.002888 +v 0.100108 -0.046078 -0.001991 +v 0.077904 -0.043599 0.002716 +v 0.058459 -0.041450 0.005607 +v 0.051124 -0.039006 0.007211 +v 0.050797 -0.040038 0.007287 +v 0.067172 -0.041914 0.003999 +v 0.063302 -0.042342 0.004545 +v 0.063087 -0.042303 0.004592 +v 0.059525 -0.040558 0.005271 +v 0.091236 -0.046389 0.000112 +v 0.080468 -0.045070 0.002352 +v 0.083525 -0.045444 0.001716 +v 0.087757 -0.044905 0.000946 +v 0.101422 -0.047233 -0.002233 +v 0.101982 -0.047279 -0.002362 +v 0.108486 -0.046500 -0.003257 +v 0.110361 -0.047639 -0.003402 +v 0.112838 -0.047636 -0.003445 +v 0.116859 -0.046607 -0.003613 +v 0.120787 -0.047627 -0.003584 +v 0.118181 -0.046593 -0.003613 +v 0.131434 -0.047024 -0.003091 +v 0.139526 -0.045097 -0.002142 +v 0.139982 -0.045052 -0.002093 +v 0.145834 -0.045444 -0.001253 +v 0.151427 -0.043678 -0.000345 +v 0.157515 -0.044087 0.000285 +v 0.281863 -0.031360 -0.001640 +v 0.281862 -0.030271 -0.001701 +v 0.279752 -0.030510 -0.001717 +v 0.262052 -0.033652 -0.001414 +v 0.249928 -0.033948 -0.000999 +v 0.157971 -0.044034 0.000345 +v 0.163052 -0.042435 0.000695 +v 0.185216 -0.041453 0.001065 +v 0.194983 -0.040553 0.001073 +v 0.196553 -0.040408 0.001074 +v 0.210643 -0.038008 0.000723 +v 0.223109 -0.037876 0.000174 +v 0.289491 -0.030478 -0.001727 +v 0.290865 -0.030319 -0.001743 +v 0.305702 -0.027566 -0.001520 +v 0.321180 -0.027031 -0.001069 +v 0.353457 -0.023902 -0.000363 +v 0.353457 -0.023815 -0.000363 +v 0.352458 -0.024901 -0.000389 +v 0.353457 0.023815 -0.000363 +v 0.353457 0.023902 -0.000363 +v 0.352448 0.024910 -0.000390 +v 0.171408 0.042737 0.001031 +v 0.162590 0.043594 0.000581 +v 0.157522 0.043028 0.000196 +v 0.157994 0.044041 0.000347 +v 0.157515 0.044097 0.000285 +v 0.129560 0.046050 -0.003169 +v 0.132097 0.046975 -0.003036 +v 0.139149 0.045149 -0.002215 +v 0.143593 0.045710 -0.001529 +v 0.152276 0.043580 -0.000238 +v 0.127959 0.046201 -0.003328 +v 0.111030 0.047663 -0.003443 +v 0.110566 0.046558 -0.003415 +v 0.076707 0.044482 0.002795 +v 0.089412 0.046167 0.000482 +v 0.081523 0.045221 0.002186 +v 0.047762 0.038380 0.007898 +v 0.048229 0.039573 0.007818 +v 0.066806 0.042962 0.004047 +v 0.061795 0.040976 0.004791 +v 0.063064 0.042290 0.004713 +v 0.058448 0.040359 0.005548 +v 0.058441 0.041459 0.005537 +v 0.053997 0.039538 0.006554 +v 0.056383 0.041089 0.005904 +v 0.048640 0.039650 0.007721 +v 0.043469 0.038714 0.008256 +v 0.042880 0.037489 0.008236 +v 0.042407 0.038528 0.008105 +v 0.040946 0.038273 0.007897 +v 0.040176 0.037006 0.007857 +v 0.039572 0.038033 0.007702 +v 0.039208 0.037971 0.007558 +v 0.036450 0.036356 0.006531 +v 0.036163 0.037451 0.006359 +v 0.035759 0.037382 0.006200 +v 0.025781 0.035025 0.000273 +v 0.024750 0.034958 -0.000202 +v 0.023650 0.035988 -0.000835 +v 0.021063 0.034719 -0.001901 +v 0.018827 0.035702 -0.002567 +v 0.016297 0.034481 -0.003053 +v 0.015181 0.034430 -0.003248 +v 0.013605 0.035466 -0.003416 +v 0.008944 0.034223 -0.003585 +v 0.007775 0.035304 -0.003486 +v 0.006066 0.034173 -0.003436 +v 0.006040 0.035256 -0.003506 +v 0.002113 0.034104 -0.003233 +v -0.000168 0.035194 -0.002872 +v 0.001320 0.034098 -0.003146 +v -0.002071 0.034094 -0.002489 +v -0.001261 0.035183 -0.002760 +v -0.003675 0.034092 -0.002178 +v -0.003651 0.035194 -0.002102 +v -0.004127 0.034091 -0.002091 +v -0.006152 0.035204 -0.001413 +v -0.008881 0.034140 -0.000164 +v -0.007357 0.035223 -0.000798 +v -0.010995 0.035278 0.001060 +v -0.010121 0.034161 0.000529 +v -0.011685 0.035296 0.001568 +v -0.017227 0.035434 0.005641 +v -0.026543 0.035709 0.013516 +v -0.026559 0.034603 0.013529 +v -0.110968 0.031561 0.037538 +v -0.112644 0.030981 0.039382 +v -0.114457 0.029571 0.041399 +v -0.115757 0.027496 0.042859 +v -0.115855 0.027109 0.042970 +v -0.116379 0.025041 0.043562 +v -0.117571 0.003752 0.045260 +v -0.117404 -0.010068 0.045022 +v -0.117390 -0.010780 0.044917 +v -0.117827 -0.017839 0.038785 +v -0.117804 -0.019458 0.034419 +v -0.117446 -0.013559 0.043862 +v -0.117612 -0.015678 0.042085 +v -0.117166 -0.020653 0.028713 +v -0.112922 -0.021697 0.016142 +v -0.115532 -0.021365 0.022287 +v -0.097765 0.032925 0.019278 +v -0.107643 0.031561 0.020245 +v -0.110238 0.031561 0.027899 +v -0.117026 0.025041 0.039115 +v -0.117010 0.025041 0.036043 +v -0.116226 0.027902 0.036027 +v -0.116986 0.025041 0.031208 +v -0.115318 0.027902 0.026803 +v -0.112343 0.027902 0.018025 +v -0.113098 0.025041 0.017661 +v -0.115451 0.025041 0.023452 +v -0.108608 0.027604 0.011400 +v -0.108864 0.026590 0.011214 +v -0.112475 0.025041 0.016127 +v -0.107189 0.029827 0.012431 +v -0.105377 0.031176 0.013747 +v -0.110177 0.030437 0.019048 +v -0.112977 0.030437 0.027308 +v -0.113831 0.030437 0.035988 +v -0.113666 0.009350 0.015505 +v -0.118439 -0.006398 0.031062 +v -0.118324 0.009350 0.031074 +v -0.116739 0.009350 0.023067 +v -0.091155 -0.025254 -0.014163 +v -0.091211 -0.025060 -0.014134 +v -0.091561 -0.024376 -0.013794 +v -0.092964 -0.023263 -0.012066 +v -0.095301 -0.022524 -0.008948 +v -0.059695 -0.033784 -0.020588 +v -0.065454 -0.033207 -0.020354 +v -0.079581 -0.031687 -0.017649 +v -0.080717 -0.031425 -0.017337 +v -0.084124 -0.030640 -0.016401 +v -0.086204 -0.030161 -0.015830 +v -0.088207 -0.028726 -0.015178 +v -0.089889 -0.027521 -0.014630 +v -0.030013 -0.035675 -0.013728 +v -0.043475 -0.035092 -0.018601 +v -0.044959 -0.034998 -0.018949 +v -0.092107 0.033045 0.012829 +v -0.084052 0.033470 0.006700 +v -0.073641 0.034210 0.002045 +v -0.063436 0.034977 0.000100 +v -0.052018 0.035727 0.000594 +v -0.043129 0.036137 0.002971 +v -0.042759 0.036144 0.003154 +v -0.038021 0.036238 0.005488 +v -0.034682 0.036305 0.007133 +v 0.033293 -0.037189 -0.007579 +v 0.047710 -0.039445 -0.006297 +v 0.049554 -0.040052 -0.001700 +v 0.044274 -0.038662 -0.009255 +v 0.039674 -0.037877 -0.010365 +v 0.035116 -0.037333 -0.009209 +v -0.013802 -0.034430 -0.003080 +v -0.010756 -0.034169 -0.001666 +v -0.010071 -0.034159 -0.001600 +v 0.353457 -0.003068 -0.023979 +v 0.353457 -0.011332 -0.021309 +v 0.353457 -0.005790 -0.023099 +v 0.353457 -0.018080 -0.015863 +v 0.353457 -0.022537 -0.008059 +v 0.353457 0.022215 -0.008944 +v 0.353457 0.017659 -0.016341 +v 0.353457 0.020396 -0.011897 +v 0.353457 0.012219 -0.020512 +v 0.353457 0.013714 -0.019832 +v 0.353457 0.005647 -0.023498 +v 0.133322 0.032898 -0.053648 +v 0.133355 0.028627 -0.054027 +v 0.345827 0.015818 -0.020580 +v 0.336741 0.016622 -0.020931 +v 0.336730 0.019205 -0.018251 +v 0.133292 -0.035731 -0.052776 +v 0.148895 -0.027978 -0.051783 +v 0.314877 -0.018617 -0.023085 +v 0.230683 -0.020059 -0.039047 +v 0.197344 -0.022789 -0.044467 +v -0.051871 -0.027101 -0.060317 +v -0.051742 -0.028345 -0.058900 +v -0.057618 -0.028482 -0.054338 +v 0.008440 -0.012104 -0.062825 +v 0.037112 -0.027880 -0.058208 +v 0.036820 -0.030582 -0.055185 +v 0.037066 0.028411 -0.057795 +v 0.013989 0.035971 -0.003866 +v 0.019774 0.036237 -0.002808 +v 0.024524 0.036526 -0.000921 +v 0.111716 0.048134 -0.007549 +v 0.083385 -0.045958 0.001292 +v 0.074782 -0.044734 0.002542 +v 0.082460 -0.045702 -0.001117 +v -0.011615 -0.035770 -0.001965 +v -0.080006 -0.031498 -0.018817 +v -0.033408 0.036162 -0.000038 +v -0.026889 0.036202 0.013189 +v -0.082940 -0.025856 -0.025389 +v -0.082423 -0.028789 -0.023517 +v -0.008319 -0.035720 -0.001331 +v 0.000283 -0.035679 -0.003012 +v 0.013158 -0.035941 -0.003453 +v 0.022915 -0.036419 -0.001689 +v 0.020340 -0.036269 -0.002140 +v 0.019063 -0.036201 -0.002507 +v 0.029226 -0.036876 -0.003613 +v 0.026233 -0.036644 -0.002111 +v 0.078699 -0.045095 -0.005832 +v 0.072700 -0.044438 0.002844 +v 0.060904 -0.042436 0.004428 +v 0.049882 -0.040391 0.005057 +v 0.050433 -0.040500 0.006843 +v 0.098938 -0.047586 -0.002264 +v 0.092480 -0.046933 -0.000738 +v 0.084709 -0.046147 0.001099 +v 0.098135 -0.047272 -0.010505 +v 0.116159 -0.048199 -0.004109 +v 0.127169 -0.047844 -0.003872 +v 0.107364 -0.048048 -0.003656 +v 0.172944 -0.043092 0.000497 +v 0.168439 -0.043511 0.000431 +v 0.185294 -0.041945 0.000677 +v 0.251883 -0.035322 -0.001578 +v 0.230893 -0.037552 -0.003932 +v 0.209062 -0.039749 0.000272 +v 0.309875 -0.028701 -0.001918 +v 0.260514 -0.034306 -0.003300 +v 0.280704 -0.031993 -0.002232 +v 0.260498 -0.034327 -0.001773 +v 0.332244 -0.026580 -0.001358 +v 0.336762 -0.026159 -0.001289 +v 0.336358 -0.026191 -0.001255 +v 0.336762 -0.026170 -0.001246 +v 0.351947 -0.025201 -0.003633 +v 0.351947 -0.024440 -0.006836 +v 0.351946 -0.025406 -0.000915 +v 0.351946 -0.025394 -0.001074 +v 0.336756 -0.022650 -0.013508 +v 0.351947 -0.023976 -0.008785 +v 0.351946 -0.018680 -0.017591 +v 0.351946 -0.021817 -0.013394 +v 0.351950 -0.012719 -0.022366 +v 0.351952 -0.014765 -0.021049 +v 0.345829 -0.015360 -0.020935 +v 0.351950 -0.012450 -0.022484 +v 0.336760 -0.012793 -0.023441 +v 0.336782 -0.006418 -0.025817 +v 0.351947 -0.007693 -0.024583 +v 0.336789 0.000294 -0.026582 +v 0.351946 -0.002308 -0.025670 +v 0.336781 0.006984 -0.025673 +v 0.351946 0.002650 -0.025636 +v 0.351947 0.007532 -0.024634 +v 0.336757 0.013350 -0.023151 +v 0.351951 0.012927 -0.022209 +v 0.351950 0.011982 -0.022775 +v 0.351950 0.015483 -0.020400 +v 0.351947 0.017567 -0.018725 +v 0.351946 0.022479 -0.011973 +v 0.345848 0.022177 -0.013159 +v 0.351945 0.020947 -0.014749 +v 0.351946 0.019406 -0.016563 +v 0.351946 0.025407 -0.000896 +v 0.351947 0.024791 -0.005947 +v 0.336774 0.025319 -0.007106 +v 0.289005 0.030252 -0.008578 +v 0.260583 0.033971 -0.008128 +v 0.094280 0.047050 -0.007517 +v 0.094949 0.047187 -0.001257 +v 0.100460 0.047691 -0.002568 +v 0.109025 0.048104 -0.003791 +v 0.078305 0.045279 0.002182 +v 0.080333 0.045543 0.001805 +v 0.075827 0.044913 -0.000319 +v 0.088234 0.046573 0.000339 +v 0.089260 0.046667 0.000095 +v 0.092453 0.046959 -0.000664 +v 0.062879 0.042788 0.004115 +v 0.045509 0.039585 0.007694 +v 0.043761 0.039267 0.007655 +v 0.051508 0.040701 0.006608 +v 0.062864 0.042786 0.004117 +v 0.037876 0.038208 0.006648 +v 0.041300 0.038819 0.007601 +v 0.042347 0.039009 0.007624 +v 0.033045 0.037420 0.004187 +v 0.024576 0.036529 -0.000900 +v 0.033081 0.037254 -0.005237 +v 0.032391 0.037307 0.001415 +v -0.005466 0.035688 -0.002174 +v -0.002234 0.035681 -0.002947 +v -0.000267 0.035677 -0.003417 +v 0.005915 0.035757 -0.003918 +v 0.007431 0.035776 -0.004040 +v -0.014804 0.035852 0.003157 +v -0.010067 0.035748 -0.000056 +v -0.007545 0.035715 -0.001217 +v -0.015920 0.035883 0.004040 +v -0.015110 0.035859 0.003364 +v 0.285500 -0.030333 -0.010345 +v 0.289083 -0.029044 -0.013081 +v 0.265438 -0.033043 -0.010249 +v 0.260670 -0.033103 -0.013671 +v 0.314753 -0.028183 -0.001838 +v 0.078589 0.045076 -0.005850 +v 0.089922 0.031362 -0.057456 +v 0.037317 0.024795 -0.059688 +v 0.008959 0.027356 -0.059462 +v -0.034217 0.030711 -0.056333 +v 0.036529 0.031862 -0.051223 +v 0.036760 0.030970 -0.054405 +v -0.018380 0.024488 -0.064088 +v -0.035097 0.029961 -0.059409 +v -0.038038 0.036267 0.005156 +v -0.035565 0.028070 -0.062894 +v -0.051117 0.030480 -0.054667 +v -0.045740 0.030309 -0.057362 +v -0.046246 0.028528 -0.061030 +v -0.040938 0.028306 -0.062385 +v -0.041121 0.025597 -0.065032 +v -0.035755 0.025299 -0.065395 +v -0.035783 0.022876 -0.066286 +v -0.035867 0.000551 -0.068838 +v -0.035815 0.014126 -0.067914 +v -0.056894 0.030635 -0.050153 +v -0.051689 0.028712 -0.058372 +v -0.046456 0.025861 -0.063785 +v -0.041140 0.023160 -0.066013 +v 0.057415 -0.019689 -0.059260 +v 0.008566 -0.018044 -0.062315 +v 0.036618 -0.031605 -0.052413 +v -0.035823 -0.012986 -0.068058 +v -0.035774 -0.024593 -0.065753 +v 0.037355 -0.023964 -0.059882 +v 0.008724 -0.023319 -0.061624 +v -0.018152 -0.027037 -0.062413 +v -0.029650 -0.029507 -0.060196 +v -0.041097 0.014323 -0.067822 +v -0.041111 0.000558 -0.068846 +v -0.041099 -0.013169 -0.067981 +v -0.041139 -0.024893 -0.065423 +v -0.046484 0.023414 -0.064825 +v -0.046379 0.014504 -0.066788 +v -0.046362 0.000564 -0.067899 +v -0.046377 -0.013336 -0.066960 +v -0.046482 -0.025158 -0.064195 +v -0.064296 0.028966 -0.046734 +v -0.064605 0.026305 -0.049314 +v -0.064602 0.023922 -0.050268 +v -0.064346 0.000577 -0.053449 +v -0.064629 -0.025624 -0.049682 +v -0.057557 0.028852 -0.053817 +v -0.057835 0.026189 -0.056540 +v -0.057845 0.023775 -0.057551 +v -0.057583 0.000573 -0.060826 +v -0.057635 -0.013588 -0.059824 +v -0.057863 -0.025498 -0.056932 +v -0.046292 -0.028159 -0.061550 +v -0.040980 -0.027929 -0.062887 +v -0.035610 -0.027681 -0.063375 +v -0.030053 -0.027439 -0.063332 +v -0.051942 0.026055 -0.061155 +v -0.051972 0.023615 -0.062200 +v -0.051814 0.014652 -0.064261 +v -0.051772 0.000569 -0.065429 +v -0.051808 -0.013474 -0.064442 +v -0.051974 -0.025355 -0.061564 +v -0.057763 -0.027233 -0.055728 +v -0.064368 -0.028593 -0.047231 +v -0.045184 -0.030798 -0.055463 +v -0.045883 -0.030039 -0.058110 +v -0.051278 -0.030211 -0.055421 +v -0.056180 -0.031124 -0.048282 +v -0.057079 -0.030364 -0.050899 +v -0.081366 -0.030713 -0.020917 +v 0.314938 -0.006677 -0.028165 +v 0.260793 -0.017545 -0.034140 +v 0.336743 -0.016088 -0.021372 +v 0.336730 -0.018829 -0.018685 +v 0.314871 -0.020694 -0.020902 +v 0.140106 -0.043906 -0.041177 +v 0.260711 -0.032481 -0.016597 +v 0.289160 -0.026578 -0.019418 +v 0.133330 -0.031369 -0.053896 +v 0.148276 0.000609 -0.053311 +v 0.148425 -0.013216 -0.052991 +v 0.119521 -0.032495 -0.055480 +v 0.119296 -0.036389 -0.054760 +v 0.126174 -0.039935 -0.051878 +v 0.125915 -0.042630 -0.049194 +v 0.125596 -0.044344 -0.046177 +v 0.132793 -0.044370 -0.043847 +v 0.117855 -0.044811 -0.044761 +v 0.139974 -0.045024 -0.034334 +v 0.118305 -0.043887 -0.048118 +v 0.119017 -0.039740 -0.053089 +v 0.314813 -0.027368 -0.007702 +v 0.314842 -0.025340 -0.013175 +v 0.132522 -0.045212 -0.040273 +v 0.104390 -0.038233 -0.054904 +v 0.103992 -0.040371 -0.053192 +v 0.103523 -0.041961 -0.050971 +v 0.102974 -0.042956 -0.047775 +v 0.336758 0.022924 -0.013028 +v 0.351946 0.023341 -0.010411 +v 0.165175 0.042834 -0.021613 +v 0.289076 0.029197 -0.012635 +v 0.260663 0.033194 -0.013206 +v 0.314841 0.025560 -0.012716 +v 0.289155 0.026931 -0.018593 +v 0.314862 0.022520 -0.018148 +v 0.289180 0.023127 -0.024775 +v 0.260745 0.031637 -0.020057 +v 0.260794 0.012994 -0.035149 +v 0.148779 0.025236 -0.052135 +v 0.148452 0.014410 -0.052931 +v 0.148966 0.029591 -0.051395 +v 0.099600 0.045966 -0.022551 +v 0.314884 0.017044 -0.024281 +v 0.289205 0.016440 -0.029290 +v 0.140149 0.031558 -0.052635 +v 0.133266 0.037157 -0.052103 +v 0.133140 0.040808 -0.049398 +v 0.126090 0.040998 -0.050989 +v 0.125813 0.043303 -0.048225 +v 0.125473 0.044750 -0.045000 +v 0.124779 0.045804 -0.038371 +v 0.102108 0.043728 -0.043207 +v 0.117245 0.045458 -0.040341 +v 0.103348 0.042394 -0.049949 +v 0.103842 0.040941 -0.052566 +v 0.104254 0.039078 -0.054326 +v 0.118909 0.040724 -0.052326 +v 0.119206 0.037600 -0.054297 +v 0.119449 0.033910 -0.055337 +v 0.119831 0.025850 -0.055388 +v 0.351952 0.014126 -0.021491 +v 0.353457 0.021446 -0.010917 +v 0.353457 0.022410 -0.008676 +v 0.353457 0.023610 -0.004092 +v 0.353457 0.016985 -0.016989 +v 0.353457 0.019065 -0.014779 +v 0.353457 0.015850 -0.018195 +v 0.353457 0.015534 -0.018531 +v 0.353457 0.014538 -0.019212 +v 0.353457 0.006741 -0.023295 +v 0.353457 0.011296 -0.021429 +v 0.353457 0.005177 -0.023575 +v 0.353457 0.001624 -0.024210 +v 0.353457 -0.012456 -0.020618 +v 0.353457 -0.003430 -0.024018 +v 0.353457 -0.009499 -0.022298 +v 0.353457 -0.008075 -0.022860 +v 0.353457 -0.017786 -0.016330 +v 0.353457 -0.013989 -0.019747 +v 0.353457 -0.020813 -0.012115 +v 0.353457 -0.023367 -0.005392 +v 0.353457 -0.022095 -0.009479 +v 0.028507 -0.036748 -0.003123 +v 0.024541 -0.036365 -0.001746 +v 0.078833 0.047137 -0.004466 +v 0.079759 0.047229 -0.005432 +v 0.079044 0.047183 -0.004115 +v 0.080064 0.047288 -0.005094 +v 0.077185 0.046825 -0.006074 +v 0.080196 0.047276 -0.005806 +v 0.077546 0.046935 -0.004787 +v 0.077405 0.046932 -0.004379 +v 0.079398 0.047119 -0.006720 +v 0.076748 0.046775 -0.005773 +v 0.079595 0.047132 -0.007082 +v 0.079234 0.047069 -0.007320 +v 0.078111 0.046917 -0.007041 +v 0.078539 0.046960 -0.007494 +v 0.077341 0.046804 -0.007060 +v 0.077053 0.046777 -0.006733 +v 0.080978 0.038457 -0.004506 +v 0.081247 0.038456 -0.005424 +v 0.081052 0.038397 -0.006118 +v 0.080348 0.038266 -0.006752 +v 0.079176 0.038095 -0.006752 +v 0.078291 0.038014 -0.005665 +v 0.078399 0.038072 -0.004717 +v 0.079271 0.038234 -0.003932 +v 0.080217 0.038372 -0.003932 +v 0.081132 0.038720 -0.004384 +v 0.080161 0.045382 -0.004680 +v 0.080401 0.045395 -0.005185 +v 0.081443 0.038719 -0.005444 +v 0.080472 0.045380 -0.005739 +v 0.081219 0.038650 -0.006244 +v 0.081063 0.038617 -0.006475 +v 0.080091 0.045279 -0.006770 +v 0.080406 0.038499 -0.006975 +v 0.080143 0.038457 -0.007064 +v 0.079172 0.045119 -0.007360 +v 0.079054 0.038302 -0.006975 +v 0.078083 0.044964 -0.007271 +v 0.078391 0.038228 -0.006475 +v 0.077420 0.044889 -0.006771 +v 0.078032 0.038209 -0.005722 +v 0.077997 0.038216 -0.005444 +v 0.077026 0.044878 -0.005740 +v 0.077089 0.044911 -0.005185 +v 0.078157 0.038276 -0.004627 +v 0.077185 0.044937 -0.004923 +v 0.078675 0.038380 -0.003982 +v 0.077703 0.045041 -0.004278 +v 0.079163 0.038462 -0.003722 +v 0.078191 0.045124 -0.004018 +v 0.080255 0.038622 -0.003722 +v 0.079284 0.045283 -0.004018 +v 0.081567 0.045617 -0.004002 +v 0.080810 0.045546 -0.003111 +v 0.076534 0.044918 -0.003217 +v 0.079419 0.045373 -0.002436 +v 0.078261 0.045206 -0.002395 +v 0.081881 0.045631 -0.004720 +v 0.081974 0.045576 -0.006271 +v 0.075564 0.044634 -0.006430 +v 0.075562 0.044703 -0.004876 +v 0.075494 0.044676 -0.005261 +v 0.081102 0.045372 -0.007986 +v 0.079801 0.045146 -0.008808 +v 0.076539 0.044702 -0.008098 +v 0.077888 0.044865 -0.008856 +v 0.080736 0.045923 -0.003113 +v 0.079250 0.045737 -0.002430 +v 0.078977 0.045699 -0.002393 +v 0.078157 0.045578 -0.002419 +v 0.076457 0.045293 -0.003253 +v 0.075453 0.045061 -0.005172 +v 0.075433 0.045022 -0.006001 +v 0.075534 0.045012 -0.006545 +v 0.076544 0.045087 -0.008170 +v 0.076987 0.045137 -0.008499 +v 0.077736 0.045231 -0.008844 +v 0.078545 0.045343 -0.008990 +v 0.079630 0.045507 -0.008862 +v 0.080611 0.045671 -0.008381 +v 0.081027 0.045748 -0.008023 +v 0.081525 0.045849 -0.007367 +v 0.081910 0.045951 -0.006337 +v 0.081812 0.046010 -0.004694 +v 0.081465 0.045993 -0.003940 +v 0.081309 0.045980 -0.003711 +v 0.075577 0.045273 -0.006260 +v 0.076719 0.045575 -0.003197 +v 0.078668 0.045889 -0.002531 +v 0.077256 0.045417 -0.008518 +v 0.077026 0.045389 -0.008388 +v 0.077204 0.046637 -0.007236 +v 0.077332 0.046652 -0.007340 +v 0.077116 0.046275 -0.007687 +v 0.077461 0.046315 -0.007901 +v 0.078469 0.046041 -0.008542 +v 0.078937 0.046110 -0.008527 +v 0.080706 0.047055 -0.005808 +v 0.079338 0.046787 -0.003444 +v 0.079131 0.046177 -0.002748 +v 0.078948 0.046735 -0.003339 +v 0.078931 0.045927 -0.002545 +v 0.076861 0.046031 -0.003482 +v 0.076683 0.045998 -0.003635 +v 0.075953 0.046002 -0.005755 +v 0.075664 0.045527 -0.005992 +v 0.075997 0.045989 -0.006194 +v 0.078942 0.046390 -0.004433 +v 0.079868 0.046482 -0.005399 +v 0.077655 0.046188 -0.004754 +v 0.077294 0.046079 -0.006041 +v 0.078220 0.046171 -0.007008 +v 0.079507 0.046373 -0.006687 +v 0.098335 0.049302 -0.009346 +v 0.099249 0.049322 -0.010328 +v 0.099264 0.049367 -0.009497 +v 0.099611 0.049361 -0.010133 +v 0.099647 0.049356 -0.010275 +v 0.096305 0.049048 -0.011190 +v 0.096644 0.049089 -0.010925 +v 0.097032 0.049185 -0.009645 +v 0.097986 0.049298 -0.008887 +v 0.099501 0.049286 -0.011409 +v 0.098860 0.049226 -0.011609 +v 0.098684 0.049181 -0.012206 +v 0.097558 0.049109 -0.011907 +v 0.097013 0.049057 -0.012091 +v 0.096307 0.049108 -0.010045 +v 0.097547 0.049087 -0.012319 +v 0.099736 0.040495 -0.009143 +v 0.100108 0.040454 -0.010496 +v 0.099209 0.040329 -0.011567 +v 0.098028 0.040238 -0.011547 +v 0.097323 0.040216 -0.010901 +v 0.097195 0.040267 -0.009725 +v 0.098178 0.040395 -0.008731 +v 0.099131 0.040468 -0.008747 +v 0.100061 0.040750 -0.009217 +v 0.099538 0.047459 -0.009564 +v 0.100353 0.040718 -0.010281 +v 0.099830 0.047427 -0.010628 +v 0.100316 0.040700 -0.010558 +v 0.099950 0.040633 -0.011305 +v 0.099427 0.047343 -0.011652 +v 0.099279 0.040556 -0.011794 +v 0.099012 0.040531 -0.011878 +v 0.098489 0.047240 -0.012225 +v 0.098181 0.040467 -0.011864 +v 0.097658 0.047176 -0.012211 +v 0.097917 0.040451 -0.011771 +v 0.097671 0.040439 -0.011636 +v 0.097148 0.047148 -0.011983 +v 0.096735 0.047135 -0.011606 +v 0.097102 0.040426 -0.011026 +v 0.096986 0.040430 -0.010771 +v 0.096463 0.047139 -0.011118 +v 0.096881 0.040450 -0.010222 +v 0.096358 0.047159 -0.010569 +v 0.096956 0.040484 -0.009669 +v 0.097058 0.040506 -0.009409 +v 0.096535 0.047215 -0.009756 +v 0.097592 0.040580 -0.008773 +v 0.097069 0.047290 -0.009119 +v 0.098089 0.040632 -0.008521 +v 0.097566 0.047341 -0.008868 +v 0.099190 0.040717 -0.008540 +v 0.098667 0.047426 -0.008887 +v 0.099887 0.040748 -0.008997 +v 0.095556 0.046990 -0.012631 +v 0.099569 0.047564 -0.007575 +v 0.100505 0.047601 -0.008278 +v 0.095912 0.047255 -0.008039 +v 0.096911 0.047364 -0.007437 +v 0.097667 0.047433 -0.007248 +v 0.101140 0.047600 -0.009263 +v 0.101333 0.047515 -0.011185 +v 0.094873 0.047009 -0.011233 +v 0.094825 0.047066 -0.010064 +v 0.100422 0.047356 -0.012884 +v 0.099095 0.047212 -0.013684 +v 0.095823 0.046996 -0.012918 +v 0.097167 0.047061 -0.013698 +v 0.099476 0.047943 -0.007564 +v 0.097589 0.047811 -0.007274 +v 0.095861 0.047634 -0.008078 +v 0.095175 0.047536 -0.008939 +v 0.094811 0.047454 -0.009978 +v 0.094867 0.047388 -0.011352 +v 0.095313 0.047370 -0.012362 +v 0.095853 0.047380 -0.012993 +v 0.097040 0.047436 -0.013687 +v 0.097306 0.047453 -0.013763 +v 0.098948 0.047582 -0.013738 +v 0.100371 0.047735 -0.012923 +v 0.100886 0.047809 -0.012277 +v 0.101293 0.047894 -0.011254 +v 0.101364 0.047928 -0.010705 +v 0.101137 0.047980 -0.009348 +v 0.100892 0.047987 -0.008851 +v 0.097363 0.048164 -0.013333 +v 0.097596 0.048180 -0.013379 +v 0.098380 0.048834 -0.012788 +v 0.098486 0.048462 -0.013187 +v 0.098701 0.048481 -0.013137 +v 0.098736 0.048867 -0.012690 +v 0.099857 0.049002 -0.011769 +v 0.099946 0.049017 -0.011607 +v 0.100061 0.048971 -0.009355 +v 0.099823 0.048969 -0.009025 +v 0.099020 0.048938 -0.008409 +v 0.098240 0.048889 -0.008186 +v 0.098037 0.048874 -0.008172 +v 0.098076 0.048508 -0.007755 +v 0.097605 0.048470 -0.007782 +v 0.095806 0.048463 -0.009122 +v 0.096311 0.048998 -0.009514 +v 0.095403 0.048014 -0.009110 +v 0.095291 0.047993 -0.009334 +v 0.095594 0.048427 -0.009507 +v 0.096090 0.048957 -0.009957 +v 0.095689 0.048525 -0.011390 +v 0.095399 0.047864 -0.012005 +v 0.095853 0.048518 -0.011762 +v 0.095528 0.047863 -0.012220 +v 0.098394 0.048550 -0.009308 +v 0.099308 0.048571 -0.010289 +v 0.097091 0.048433 -0.009606 +v 0.096702 0.048337 -0.010887 +v 0.097616 0.048357 -0.011868 +v 0.098919 0.048474 -0.011570 +v 0.092815 -0.047185 0.010440 +v 0.093696 -0.047532 0.009490 +v 0.093046 -0.047111 0.010774 +v 0.094095 -0.047554 0.009540 +v 0.090727 -0.047500 0.008672 +v 0.091074 -0.047459 0.008926 +v 0.094116 -0.047674 0.009121 +v 0.091504 -0.047148 0.010158 +v 0.093266 -0.047843 0.008258 +v 0.091634 -0.047006 0.010702 +v 0.090661 -0.047298 0.009365 +v 0.090973 -0.047103 0.010150 +v 0.091658 -0.047867 0.007668 +v 0.091955 -0.047807 0.007976 +v 0.091180 -0.047739 0.007973 +v 0.092934 -0.047992 0.007630 +v 0.094100 -0.038737 0.007937 +v 0.094605 -0.039000 0.007168 +v 0.094602 -0.039196 0.006472 +v 0.094088 -0.039374 0.005685 +v 0.093195 -0.039392 0.005343 +v 0.092094 -0.039185 0.005727 +v 0.091656 -0.038917 0.006533 +v 0.092106 -0.038592 0.007823 +v 0.093211 -0.038570 0.008247 +v 0.094595 -0.039068 0.007780 +v 0.094021 -0.045527 0.009610 +v 0.094811 -0.039226 0.007289 +v 0.094237 -0.045686 0.009119 +v 0.094280 -0.045765 0.008854 +v 0.094806 -0.039453 0.006486 +v 0.094232 -0.045913 0.008316 +v 0.094416 -0.039622 0.005768 +v 0.093842 -0.046081 0.007599 +v 0.094214 -0.039658 0.005578 +v 0.093461 -0.039692 0.005220 +v 0.092887 -0.046152 0.007050 +v 0.093183 -0.039678 0.005182 +v 0.092631 -0.039614 0.005237 +v 0.092057 -0.046073 0.007068 +v 0.092129 -0.039506 0.005459 +v 0.091554 -0.045966 0.007289 +v 0.091913 -0.039440 0.005625 +v 0.091473 -0.039211 0.006296 +v 0.090899 -0.045670 0.008126 +v 0.091407 -0.039131 0.006557 +v 0.091386 -0.039053 0.006825 +v 0.090812 -0.045513 0.008656 +v 0.091589 -0.038849 0.007608 +v 0.091015 -0.045309 0.009438 +v 0.091926 -0.038756 0.008044 +v 0.092144 -0.038725 0.008219 +v 0.091570 -0.045185 0.010049 +v 0.092648 -0.038702 0.008459 +v 0.092074 -0.045162 0.010289 +v 0.093202 -0.038730 0.008534 +v 0.093747 -0.038806 0.008436 +v 0.093173 -0.045266 0.010266 +v 0.094228 -0.038923 0.008176 +v 0.094117 -0.044993 0.011526 +v 0.095029 -0.045267 0.010845 +v 0.090448 -0.044789 0.011095 +v 0.092228 -0.044733 0.011850 +v 0.095847 -0.045922 0.008791 +v 0.095749 -0.045702 0.009536 +v 0.089306 -0.045559 0.008022 +v 0.089297 -0.045238 0.009149 +v 0.094796 -0.046504 0.006407 +v 0.095496 -0.046306 0.007325 +v 0.093445 -0.046601 0.005642 +v 0.090201 -0.046099 0.006394 +v 0.091518 -0.046431 0.005637 +v 0.094022 -0.045346 0.011661 +v 0.093511 -0.045247 0.011852 +v 0.092146 -0.045098 0.011948 +v 0.090612 -0.045132 0.011349 +v 0.090394 -0.045160 0.011181 +v 0.089832 -0.045280 0.010582 +v 0.089284 -0.045579 0.009355 +v 0.089294 -0.045955 0.008030 +v 0.090225 -0.046487 0.006445 +v 0.090653 -0.046618 0.006118 +v 0.091389 -0.046781 0.005771 +v 0.093293 -0.046967 0.005713 +v 0.094742 -0.046875 0.006492 +v 0.095277 -0.046747 0.007113 +v 0.095419 -0.046693 0.007345 +v 0.095805 -0.046365 0.008625 +v 0.095705 -0.046057 0.009681 +v 0.095395 -0.045822 0.010414 +v 0.095086 -0.045671 0.010849 +v 0.089783 -0.045590 0.010352 +v 0.090938 -0.046878 0.006168 +v 0.090713 -0.046821 0.006298 +v 0.093061 -0.047623 0.006577 +v 0.093022 -0.047929 0.007374 +v 0.093867 -0.047595 0.006930 +v 0.093607 -0.047822 0.007365 +v 0.094820 -0.047296 0.007541 +v 0.094643 -0.047447 0.007693 +v 0.095044 -0.047200 0.007947 +v 0.094852 -0.047359 0.008072 +v 0.094316 -0.047653 0.008754 +v 0.094994 -0.047256 0.008478 +v 0.095196 -0.047091 0.008383 +v 0.095272 -0.046969 0.008835 +v 0.094368 -0.047568 0.009071 +v 0.093532 -0.046552 0.011192 +v 0.093157 -0.046479 0.011332 +v 0.091375 -0.046367 0.011170 +v 0.091025 -0.046394 0.010963 +v 0.089927 -0.045541 0.010569 +v 0.090033 -0.046084 0.010314 +v 0.089921 -0.046132 0.010110 +v 0.090075 -0.046362 0.010088 +v 0.089916 -0.046462 0.009688 +v 0.089833 -0.046753 0.008633 +v 0.089702 -0.046619 0.008325 +v 0.089762 -0.046686 0.008106 +v 0.092879 -0.046461 0.010235 +v 0.093761 -0.046808 0.009285 +v 0.091568 -0.046424 0.009953 +v 0.091138 -0.046735 0.008721 +v 0.092019 -0.047083 0.007771 +v 0.093330 -0.047119 0.008053 +v 0.078833 -0.047073 -0.004466 +v 0.079759 -0.047165 -0.005432 +v 0.079757 -0.047201 -0.004601 +v 0.079044 -0.047119 -0.004115 +v 0.080064 -0.047224 -0.005094 +v 0.080152 -0.047225 -0.005372 +v 0.076854 -0.046701 -0.006345 +v 0.077185 -0.046761 -0.006074 +v 0.077546 -0.046871 -0.004787 +v 0.077405 -0.046868 -0.004379 +v 0.079398 -0.047055 -0.006720 +v 0.077019 -0.046793 -0.004806 +v 0.079595 -0.047068 -0.007082 +v 0.078111 -0.046853 -0.007041 +v 0.077574 -0.046766 -0.007234 +v 0.078683 -0.046917 -0.007483 +v 0.080978 -0.038393 -0.004506 +v 0.081247 -0.038392 -0.005424 +v 0.081052 -0.038332 -0.006118 +v 0.080348 -0.038202 -0.006752 +v 0.079176 -0.038031 -0.006752 +v 0.078291 -0.037950 -0.005665 +v 0.078399 -0.038008 -0.004717 +v 0.079271 -0.038170 -0.003932 +v 0.080217 -0.038308 -0.003932 +v 0.081132 -0.038656 -0.004384 +v 0.080161 -0.045318 -0.004680 +v 0.080459 -0.045327 -0.005459 +v 0.081443 -0.038654 -0.005444 +v 0.080472 -0.045316 -0.005739 +v 0.081219 -0.038586 -0.006244 +v 0.081063 -0.038553 -0.006475 +v 0.080091 -0.045215 -0.006770 +v 0.080406 -0.038435 -0.006975 +v 0.080143 -0.038393 -0.007064 +v 0.079172 -0.045055 -0.007360 +v 0.079054 -0.038238 -0.006975 +v 0.078083 -0.044900 -0.007271 +v 0.078391 -0.038164 -0.006475 +v 0.077420 -0.044825 -0.006771 +v 0.078032 -0.038145 -0.005722 +v 0.077997 -0.038152 -0.005444 +v 0.077026 -0.044813 -0.005740 +v 0.078157 -0.038211 -0.004627 +v 0.077185 -0.044873 -0.004923 +v 0.078675 -0.038316 -0.003982 +v 0.077703 -0.044977 -0.004278 +v 0.079163 -0.038398 -0.003722 +v 0.078191 -0.045060 -0.004018 +v 0.080255 -0.038558 -0.003722 +v 0.079284 -0.045219 -0.004018 +v 0.080810 -0.045482 -0.003111 +v 0.076534 -0.044854 -0.003217 +v 0.079419 -0.045309 -0.002436 +v 0.078261 -0.045142 -0.002395 +v 0.082019 -0.045553 -0.005490 +v 0.081881 -0.045567 -0.004720 +v 0.082019 -0.045535 -0.005882 +v 0.075564 -0.044570 -0.006430 +v 0.075494 -0.044611 -0.005261 +v 0.081102 -0.045308 -0.007986 +v 0.081748 -0.045445 -0.007019 +v 0.079801 -0.045082 -0.008808 +v 0.076539 -0.044638 -0.008098 +v 0.077888 -0.044801 -0.008856 +v 0.080736 -0.045859 -0.003113 +v 0.080035 -0.045776 -0.002677 +v 0.079250 -0.045672 -0.002430 +v 0.078157 -0.045514 -0.002419 +v 0.076888 -0.045307 -0.002913 +v 0.076457 -0.045229 -0.003253 +v 0.075676 -0.045065 -0.004375 +v 0.075453 -0.044997 -0.005172 +v 0.075433 -0.044958 -0.006001 +v 0.075534 -0.044948 -0.006545 +v 0.076544 -0.045023 -0.008170 +v 0.077477 -0.045134 -0.008750 +v 0.077736 -0.045167 -0.008844 +v 0.078545 -0.045279 -0.008990 +v 0.079630 -0.045443 -0.008862 +v 0.080826 -0.045646 -0.008211 +v 0.081027 -0.045683 -0.008023 +v 0.081653 -0.045815 -0.007123 +v 0.081969 -0.045920 -0.005787 +v 0.081812 -0.045946 -0.004694 +v 0.081309 -0.045916 -0.003711 +v 0.075577 -0.045208 -0.006260 +v 0.080995 -0.046117 -0.003601 +v 0.081162 -0.046132 -0.003807 +v 0.077341 -0.045826 -0.008238 +v 0.077555 -0.045853 -0.008337 +v 0.078469 -0.045977 -0.008542 +v 0.078937 -0.046046 -0.008527 +v 0.078782 -0.046616 -0.007939 +v 0.078963 -0.046643 -0.007910 +v 0.080419 -0.046291 -0.007876 +v 0.079770 -0.046946 -0.007261 +v 0.080749 -0.046354 -0.007540 +v 0.080001 -0.046990 -0.007026 +v 0.081174 -0.046707 -0.005584 +v 0.081112 -0.046717 -0.005147 +v 0.080776 -0.046704 -0.004333 +v 0.080153 -0.047116 -0.004701 +v 0.080513 -0.046681 -0.003978 +v 0.079955 -0.047099 -0.004435 +v 0.079845 -0.046207 -0.002973 +v 0.079242 -0.046873 -0.003657 +v 0.079614 -0.046177 -0.002878 +v 0.079066 -0.046850 -0.003602 +v 0.077551 -0.046767 -0.004001 +v 0.077277 -0.046719 -0.004182 +v 0.076666 -0.046458 -0.004537 +v 0.076495 -0.046419 -0.004863 +v 0.075664 -0.045463 -0.005992 +v 0.075965 -0.045694 -0.006677 +v 0.078942 -0.046326 -0.004433 +v 0.079868 -0.046418 -0.005399 +v 0.077655 -0.046124 -0.004754 +v 0.077294 -0.046014 -0.006041 +v 0.078220 -0.046107 -0.007008 +v 0.079507 -0.046308 -0.006687 +v 0.098335 -0.049238 -0.009346 +v 0.099249 -0.049258 -0.010328 +v 0.099434 -0.049303 -0.009734 +v 0.096305 -0.048984 -0.011190 +v 0.096644 -0.049024 -0.010925 +v 0.099682 -0.049272 -0.010709 +v 0.097032 -0.049121 -0.009645 +v 0.096898 -0.049132 -0.009235 +v 0.097986 -0.049234 -0.008887 +v 0.099501 -0.049222 -0.011409 +v 0.098860 -0.049162 -0.011609 +v 0.098684 -0.049117 -0.012206 +v 0.097558 -0.049045 -0.011907 +v 0.097547 -0.049023 -0.012319 +v 0.096678 -0.048981 -0.011811 +v 0.099736 -0.040431 -0.009143 +v 0.100108 -0.040390 -0.010496 +v 0.099209 -0.040264 -0.011567 +v 0.098028 -0.040173 -0.011547 +v 0.097323 -0.040152 -0.010901 +v 0.097195 -0.040203 -0.009725 +v 0.098178 -0.040331 -0.008731 +v 0.099131 -0.040404 -0.008747 +v 0.100061 -0.040686 -0.009217 +v 0.099538 -0.047395 -0.009564 +v 0.100353 -0.040654 -0.010281 +v 0.099830 -0.047363 -0.010628 +v 0.100316 -0.040636 -0.010558 +v 0.099950 -0.040569 -0.011305 +v 0.099427 -0.047278 -0.011652 +v 0.099005 -0.047227 -0.012015 +v 0.099279 -0.040492 -0.011794 +v 0.099012 -0.040466 -0.011878 +v 0.098489 -0.047176 -0.012225 +v 0.098213 -0.047152 -0.012265 +v 0.098181 -0.040402 -0.011864 +v 0.097658 -0.047112 -0.012211 +v 0.097917 -0.040387 -0.011771 +v 0.097671 -0.040374 -0.011636 +v 0.097148 -0.047084 -0.011983 +v 0.097102 -0.040362 -0.011026 +v 0.096986 -0.040366 -0.010771 +v 0.096463 -0.047075 -0.011118 +v 0.096881 -0.040386 -0.010222 +v 0.096358 -0.047095 -0.010569 +v 0.096956 -0.040420 -0.009669 +v 0.097058 -0.040442 -0.009409 +v 0.096535 -0.047151 -0.009756 +v 0.097592 -0.040516 -0.008773 +v 0.097069 -0.047226 -0.009119 +v 0.098089 -0.040568 -0.008521 +v 0.097566 -0.047277 -0.008868 +v 0.099190 -0.040653 -0.008540 +v 0.098667 -0.047362 -0.008887 +v 0.099887 -0.040684 -0.008997 +v 0.099569 -0.047500 -0.007575 +v 0.100505 -0.047537 -0.008278 +v 0.095912 -0.047191 -0.008039 +v 0.097667 -0.047369 -0.007248 +v 0.101140 -0.047535 -0.009263 +v 0.101333 -0.047451 -0.011185 +v 0.094873 -0.046945 -0.011233 +v 0.094825 -0.047002 -0.010064 +v 0.098328 -0.047080 -0.013828 +v 0.100422 -0.047292 -0.012884 +v 0.099095 -0.047148 -0.013684 +v 0.100128 -0.047256 -0.013142 +v 0.095823 -0.046932 -0.012918 +v 0.097167 -0.046997 -0.013698 +v 0.099476 -0.047879 -0.007564 +v 0.097589 -0.047746 -0.007274 +v 0.097050 -0.047698 -0.007397 +v 0.096074 -0.047596 -0.007903 +v 0.095861 -0.047570 -0.008078 +v 0.094950 -0.047429 -0.009443 +v 0.094811 -0.047390 -0.009978 +v 0.094867 -0.047324 -0.011352 +v 0.095313 -0.047306 -0.012362 +v 0.095853 -0.047316 -0.012993 +v 0.097040 -0.047372 -0.013687 +v 0.097306 -0.047389 -0.013763 +v 0.098948 -0.047518 -0.013738 +v 0.100371 -0.047671 -0.012923 +v 0.100886 -0.047745 -0.012277 +v 0.101293 -0.047830 -0.011254 +v 0.101364 -0.047863 -0.010705 +v 0.101137 -0.047916 -0.009348 +v 0.100892 -0.047922 -0.008851 +v 0.097343 -0.048859 -0.012501 +v 0.097136 -0.048086 -0.013268 +v 0.097363 -0.048100 -0.013333 +v 0.097502 -0.048870 -0.012547 +v 0.098380 -0.048770 -0.012788 +v 0.098486 -0.048398 -0.013187 +v 0.098701 -0.048417 -0.013137 +v 0.098736 -0.048803 -0.012690 +v 0.100247 -0.048598 -0.011972 +v 0.099946 -0.048953 -0.011607 +v 0.100443 -0.048634 -0.011578 +v 0.100022 -0.048968 -0.011438 +v 0.099020 -0.048874 -0.008409 +v 0.098240 -0.048825 -0.008186 +v 0.097632 -0.048777 -0.008195 +v 0.096309 -0.048277 -0.008320 +v 0.096081 -0.048438 -0.008777 +v 0.095957 -0.048233 -0.008635 +v 0.095588 -0.048473 -0.010995 +v 0.095689 -0.048460 -0.011390 +v 0.095399 -0.047800 -0.012004 +v 0.095853 -0.048454 -0.011762 +v 0.095528 -0.047799 -0.012220 +v 0.098394 -0.048486 -0.009308 +v 0.099308 -0.048506 -0.010289 +v 0.097091 -0.048369 -0.009606 +v 0.096702 -0.048272 -0.010887 +v 0.097616 -0.048293 -0.011868 +v 0.098919 -0.048410 -0.011570 +v 0.275776 0.033806 0.008424 +v 0.276895 0.033760 0.007686 +v 0.276326 0.033708 0.008703 +v 0.274260 0.034254 0.006169 +v 0.274524 0.034183 0.006504 +v 0.277405 0.033731 0.007417 +v 0.274591 0.034018 0.007834 +v 0.275328 0.033817 0.008788 +v 0.276828 0.033925 0.006356 +v 0.274006 0.034136 0.007421 +v 0.277101 0.033929 0.006046 +v 0.277438 0.033778 0.006984 +v 0.275643 0.034137 0.005765 +v 0.275731 0.034174 0.005364 +v 0.274541 0.034260 0.005835 +v 0.276433 0.034072 0.005513 +v 0.275264 0.024973 0.007424 +v 0.275969 0.024966 0.006778 +v 0.276162 0.025025 0.006083 +v 0.275889 0.025164 0.005177 +v 0.275124 0.025321 0.004625 +v 0.274408 0.025411 0.004584 +v 0.273571 0.025457 0.005046 +v 0.273172 0.025402 0.005913 +v 0.273511 0.025229 0.007035 +v 0.274318 0.025075 0.007523 +v 0.276835 0.031794 0.007934 +v 0.276197 0.025158 0.006915 +v 0.276991 0.031803 0.007701 +v 0.276420 0.025226 0.006114 +v 0.276406 0.025260 0.005836 +v 0.277200 0.031906 0.006622 +v 0.276105 0.025387 0.005069 +v 0.275926 0.025433 0.004857 +v 0.276720 0.032079 0.005643 +v 0.275479 0.025525 0.004534 +v 0.276273 0.032170 0.005320 +v 0.275222 0.025568 0.004431 +v 0.274673 0.025642 0.004355 +v 0.275467 0.032288 0.005141 +v 0.274396 0.025672 0.004384 +v 0.274126 0.025696 0.004458 +v 0.274919 0.032341 0.005243 +v 0.273430 0.025724 0.004917 +v 0.274224 0.032370 0.005702 +v 0.273119 0.025707 0.005381 +v 0.273913 0.032352 0.006167 +v 0.272970 0.025661 0.005918 +v 0.272998 0.025592 0.006472 +v 0.273792 0.032237 0.007258 +v 0.273361 0.025461 0.007212 +v 0.274154 0.032107 0.007998 +v 0.274293 0.025283 0.007776 +v 0.275086 0.031929 0.008561 +v 0.275384 0.025167 0.007662 +v 0.276178 0.031812 0.008447 +v 0.276195 0.031618 0.010072 +v 0.276930 0.031562 0.009805 +v 0.273016 0.032115 0.009079 +v 0.274651 0.031803 0.010064 +v 0.278119 0.031538 0.008802 +v 0.278726 0.031635 0.007373 +v 0.272543 0.032601 0.005442 +v 0.272296 0.032361 0.007722 +v 0.272196 0.032464 0.006952 +v 0.278297 0.031951 0.005130 +v 0.277209 0.032209 0.004048 +v 0.273866 0.032610 0.004031 +v 0.275351 0.032485 0.003588 +v 0.276172 0.032002 0.010132 +v 0.274805 0.032165 0.010134 +v 0.274539 0.032205 0.010065 +v 0.272969 0.032517 0.009016 +v 0.272433 0.032693 0.008066 +v 0.272351 0.032734 0.007804 +v 0.272415 0.032951 0.005904 +v 0.272634 0.032984 0.005396 +v 0.273113 0.033007 0.004719 +v 0.273981 0.032984 0.004036 +v 0.275022 0.032903 0.003674 +v 0.275295 0.032874 0.003639 +v 0.277149 0.032607 0.004032 +v 0.278000 0.032425 0.004712 +v 0.278327 0.032334 0.005150 +v 0.278813 0.032092 0.006705 +v 0.278751 0.032002 0.007528 +v 0.278205 0.031918 0.008789 +v 0.277428 0.031918 0.009574 +v 0.274610 0.032452 0.009958 +v 0.278675 0.032377 0.006480 +v 0.277922 0.032661 0.004835 +v 0.277740 0.032705 0.004647 +v 0.274877 0.033345 0.004077 +v 0.275155 0.033998 0.004930 +v 0.275123 0.033322 0.004025 +v 0.275519 0.033961 0.004868 +v 0.277201 0.033691 0.005455 +v 0.277444 0.033630 0.005728 +v 0.278397 0.032847 0.006581 +v 0.278699 0.032343 0.006742 +v 0.277874 0.033416 0.007104 +v 0.278420 0.032789 0.007051 +v 0.278024 0.033178 0.007491 +v 0.277831 0.033378 0.007470 +v 0.278233 0.032702 0.007973 +v 0.277910 0.033146 0.007881 +v 0.277898 0.032669 0.008598 +v 0.277234 0.032669 0.009269 +v 0.276828 0.032688 0.009513 +v 0.276769 0.032917 0.009367 +v 0.276547 0.033526 0.008843 +v 0.276396 0.033536 0.008910 +v 0.276567 0.032930 0.009456 +v 0.275122 0.033298 0.009407 +v 0.274362 0.032491 0.009871 +v 0.274737 0.033358 0.009290 +v 0.273164 0.033517 0.007936 +v 0.273051 0.033580 0.007514 +v 0.275687 0.033062 0.008336 +v 0.276806 0.033015 0.007598 +v 0.274502 0.033273 0.007746 +v 0.274435 0.033438 0.006416 +v 0.275554 0.033392 0.005677 +v 0.276739 0.033181 0.006268 +v 0.265800 0.035143 -0.009302 +v 0.266908 0.034875 -0.010010 +v 0.265933 0.035190 -0.008915 +v 0.264526 0.034987 -0.011239 +v 0.264125 0.035026 -0.011326 +v 0.267336 0.034821 -0.009989 +v 0.264609 0.035199 -0.009917 +v 0.264948 0.035291 -0.009102 +v 0.267426 0.034666 -0.010837 +v 0.266825 0.034663 -0.011332 +v 0.267001 0.034569 -0.011745 +v 0.265634 0.034719 -0.011946 +v 0.263999 0.035185 -0.010483 +v 0.265718 0.034641 -0.012343 +v 0.266420 0.034574 -0.012179 +v 0.265169 0.026391 -0.007787 +v 0.265865 0.026192 -0.008413 +v 0.265980 0.025981 -0.009572 +v 0.265424 0.025924 -0.010349 +v 0.264279 0.026031 -0.010628 +v 0.263185 0.026318 -0.009796 +v 0.263091 0.026489 -0.008860 +v 0.263780 0.026559 -0.007899 +v 0.265756 0.026529 -0.007910 +v 0.266640 0.033116 -0.009022 +v 0.266097 0.026412 -0.008337 +v 0.266282 0.026300 -0.008853 +v 0.267166 0.032887 -0.009964 +v 0.266292 0.026205 -0.009404 +v 0.267176 0.032793 -0.010515 +v 0.266230 0.026168 -0.009675 +v 0.265801 0.026105 -0.010387 +v 0.266685 0.032692 -0.011499 +v 0.265589 0.026103 -0.010570 +v 0.265351 0.026110 -0.010718 +v 0.266234 0.032697 -0.011830 +v 0.264544 0.026185 -0.010915 +v 0.265427 0.032772 -0.012027 +v 0.264267 0.026226 -0.010893 +v 0.263514 0.026381 -0.010570 +v 0.264397 0.032968 -0.011682 +v 0.263005 0.026557 -0.009933 +v 0.262912 0.026613 -0.009674 +v 0.263796 0.033200 -0.010786 +v 0.262897 0.026754 -0.008852 +v 0.263781 0.033341 -0.009964 +v 0.263268 0.026829 -0.008109 +v 0.264152 0.033417 -0.009221 +v 0.264349 0.033424 -0.009021 +v 0.263691 0.026834 -0.007743 +v 0.264575 0.033422 -0.008855 +v 0.265090 0.033389 -0.008639 +v 0.264759 0.026735 -0.007483 +v 0.265643 0.033322 -0.008595 +v 0.265294 0.026641 -0.007615 +v 0.266588 0.033428 -0.007215 +v 0.262786 0.033725 -0.008481 +v 0.263614 0.033753 -0.007653 +v 0.265056 0.033657 -0.007078 +v 0.264302 0.033724 -0.007281 +v 0.268120 0.033035 -0.008329 +v 0.268709 0.032719 -0.009733 +v 0.262512 0.033202 -0.011797 +v 0.262198 0.033431 -0.010692 +v 0.268253 0.032402 -0.011971 +v 0.267154 0.032364 -0.013071 +v 0.263815 0.032796 -0.013167 +v 0.265293 0.032529 -0.013572 +v 0.266723 0.033787 -0.007309 +v 0.264307 0.034102 -0.007363 +v 0.264055 0.034116 -0.007480 +v 0.262820 0.034098 -0.008568 +v 0.262545 0.034054 -0.009048 +v 0.262240 0.033824 -0.010650 +v 0.262394 0.033668 -0.011450 +v 0.262608 0.033556 -0.011949 +v 0.263936 0.033155 -0.013268 +v 0.264970 0.032960 -0.013603 +v 0.265242 0.032918 -0.013631 +v 0.266065 0.032817 -0.013578 +v 0.267098 0.032742 -0.013197 +v 0.267956 0.032745 -0.012501 +v 0.268288 0.032775 -0.012059 +v 0.268712 0.032889 -0.011045 +v 0.268740 0.033115 -0.009687 +v 0.268592 0.033223 -0.009164 +v 0.268211 0.033395 -0.008448 +v 0.262652 0.033838 -0.011686 +v 0.264767 0.033256 -0.013454 +v 0.265057 0.034163 -0.012887 +v 0.265025 0.033213 -0.013503 +v 0.265455 0.034100 -0.012945 +v 0.266494 0.033768 -0.012957 +v 0.266697 0.033755 -0.012872 +v 0.267160 0.033503 -0.012775 +v 0.267081 0.033740 -0.012653 +v 0.267578 0.033747 -0.012216 +v 0.268383 0.033667 -0.010830 +v 0.268044 0.034107 -0.010845 +v 0.268408 0.033703 -0.010596 +v 0.268070 0.034172 -0.010444 +v 0.268372 0.033698 -0.009352 +v 0.268160 0.033801 -0.008907 +v 0.266674 0.034210 -0.007665 +v 0.266438 0.034255 -0.007589 +v 0.266416 0.034443 -0.007792 +v 0.265953 0.034975 -0.008402 +v 0.265956 0.034520 -0.007705 +v 0.265770 0.035002 -0.008391 +v 0.264974 0.035198 -0.008798 +v 0.264679 0.035212 -0.008951 +v 0.263064 0.034630 -0.009352 +v 0.262973 0.034605 -0.009569 +v 0.263620 0.035042 -0.009861 +v 0.263521 0.034996 -0.010215 +v 0.262741 0.034103 -0.011428 +v 0.262828 0.034052 -0.011659 +v 0.265701 0.034405 -0.009178 +v 0.266809 0.034137 -0.009885 +v 0.264510 0.034461 -0.009793 +v 0.264427 0.034249 -0.011115 +v 0.265535 0.033981 -0.011822 +v 0.266726 0.033925 -0.011207 +v 0.285798 0.032402 -0.009453 +v 0.286885 0.032096 -0.010177 +v 0.286357 0.032387 -0.009177 +v 0.284471 0.032163 -0.011346 +v 0.284591 0.032435 -0.010038 +v 0.284952 0.032563 -0.009238 +v 0.287380 0.031847 -0.011007 +v 0.286766 0.031824 -0.011485 +v 0.284021 0.032235 -0.011290 +v 0.284075 0.032475 -0.010170 +v 0.287026 0.031722 -0.011788 +v 0.285559 0.031857 -0.012069 +v 0.285066 0.031857 -0.012370 +v 0.285631 0.031760 -0.012464 +v 0.284462 0.032019 -0.012004 +v 0.285570 0.023622 -0.007780 +v 0.286020 0.023329 -0.008835 +v 0.285550 0.023155 -0.009908 +v 0.284209 0.023246 -0.010315 +v 0.283392 0.023455 -0.009864 +v 0.283029 0.023692 -0.009011 +v 0.283150 0.023830 -0.008312 +v 0.284237 0.023879 -0.007424 +v 0.285761 0.023862 -0.007663 +v 0.285944 0.023793 -0.007865 +v 0.286820 0.030318 -0.009303 +v 0.286261 0.023587 -0.008608 +v 0.287137 0.030111 -0.010046 +v 0.286281 0.023524 -0.008881 +v 0.286256 0.023467 -0.009154 +v 0.287132 0.029992 -0.010592 +v 0.285738 0.023324 -0.010118 +v 0.286614 0.029848 -0.011557 +v 0.285279 0.023315 -0.010437 +v 0.286155 0.029840 -0.011876 +v 0.284467 0.023385 -0.010616 +v 0.285343 0.029909 -0.012054 +v 0.284191 0.023428 -0.010588 +v 0.283448 0.023602 -0.010253 +v 0.284324 0.030126 -0.011691 +v 0.283249 0.023669 -0.010067 +v 0.283960 0.030264 -0.011290 +v 0.282871 0.023878 -0.009353 +v 0.283747 0.030402 -0.010791 +v 0.282829 0.023943 -0.009083 +v 0.282969 0.024102 -0.008277 +v 0.283846 0.030626 -0.009715 +v 0.283703 0.024184 -0.007456 +v 0.284579 0.030709 -0.008894 +v 0.284223 0.024159 -0.007252 +v 0.285375 0.030655 -0.008652 +v 0.284777 0.024092 -0.007220 +v 0.285653 0.030617 -0.008658 +v 0.285308 0.023989 -0.007362 +v 0.286184 0.030514 -0.008800 +v 0.286988 0.030701 -0.007462 +v 0.282802 0.031037 -0.008487 +v 0.285497 0.030977 -0.007117 +v 0.285108 0.031024 -0.007143 +v 0.284350 0.031085 -0.007329 +v 0.288336 0.030232 -0.008768 +v 0.288692 0.029777 -0.010613 +v 0.282436 0.030363 -0.011767 +v 0.282837 0.030167 -0.012410 +v 0.282280 0.030879 -0.009524 +v 0.282154 0.030644 -0.010665 +v 0.288363 0.029578 -0.011720 +v 0.287367 0.029450 -0.012907 +v 0.283701 0.029888 -0.013150 +v 0.285167 0.029596 -0.013583 +v 0.287017 0.031077 -0.007534 +v 0.286248 0.031239 -0.007269 +v 0.285430 0.031364 -0.007202 +v 0.284883 0.031422 -0.007271 +v 0.284353 0.031458 -0.007428 +v 0.283007 0.031430 -0.008376 +v 0.282834 0.031406 -0.008592 +v 0.282198 0.031039 -0.010642 +v 0.282330 0.030846 -0.011439 +v 0.282529 0.030709 -0.011937 +v 0.283589 0.030304 -0.013131 +v 0.283820 0.030242 -0.013271 +v 0.285116 0.029982 -0.013658 +v 0.285939 0.029880 -0.013622 +v 0.287448 0.029822 -0.012966 +v 0.287661 0.029832 -0.012788 +v 0.288346 0.029930 -0.011928 +v 0.288470 0.029967 -0.011682 +v 0.288749 0.030162 -0.010632 +v 0.288365 0.030614 -0.008812 +v 0.287598 0.030099 -0.012738 +v 0.283951 0.031013 -0.012887 +v 0.285257 0.030738 -0.013337 +v 0.285961 0.030650 -0.013307 +v 0.287394 0.030088 -0.012907 +v 0.287979 0.030960 -0.011618 +v 0.287804 0.031487 -0.011012 +v 0.287837 0.031562 -0.010650 +v 0.288212 0.031161 -0.010564 +v 0.288362 0.030944 -0.009504 +v 0.287903 0.031557 -0.009829 +v 0.287719 0.031734 -0.009941 +v 0.288162 0.031069 -0.009060 +v 0.287244 0.031860 -0.008859 +v 0.286829 0.032096 -0.008845 +v 0.286478 0.031591 -0.007718 +v 0.286451 0.031770 -0.007929 +v 0.286238 0.031636 -0.007657 +v 0.286225 0.031813 -0.007872 +v 0.285058 0.031969 -0.007874 +v 0.284604 0.032000 -0.008008 +v 0.283453 0.031976 -0.008819 +v 0.283768 0.032336 -0.009620 +v 0.283174 0.031930 -0.009200 +v 0.283603 0.032286 -0.009948 +v 0.283430 0.031182 -0.012434 +v 0.283781 0.031576 -0.012257 +v 0.283918 0.031526 -0.012399 +v 0.285699 0.031671 -0.009292 +v 0.286787 0.031365 -0.010015 +v 0.284492 0.031704 -0.009877 +v 0.284373 0.031431 -0.011185 +v 0.285461 0.031126 -0.011908 +v 0.286668 0.031093 -0.011323 +v 0.275776 -0.033731 0.008424 +v 0.276895 -0.033684 0.007686 +v 0.276326 -0.033632 0.008703 +v 0.274524 -0.034107 0.006504 +v 0.274123 -0.034164 0.006426 +v 0.277405 -0.033655 0.007417 +v 0.274591 -0.033942 0.007834 +v 0.275328 -0.033741 0.008788 +v 0.276828 -0.033849 0.006356 +v 0.274006 -0.034061 0.007421 +v 0.277101 -0.033853 0.006046 +v 0.275643 -0.034061 0.005765 +v 0.275731 -0.034098 0.005364 +v 0.274895 -0.034172 0.005579 +v 0.274541 -0.034184 0.005835 +v 0.275264 -0.024898 0.007424 +v 0.275969 -0.024890 0.006778 +v 0.276162 -0.024949 0.006083 +v 0.275889 -0.025089 0.005177 +v 0.275124 -0.025245 0.004625 +v 0.274408 -0.025336 0.004584 +v 0.273571 -0.025381 0.005046 +v 0.273172 -0.025326 0.005913 +v 0.273511 -0.025153 0.007035 +v 0.274318 -0.024999 0.007523 +v 0.276197 -0.025082 0.006915 +v 0.276991 -0.031727 0.007701 +v 0.276420 -0.025150 0.006114 +v 0.276406 -0.025185 0.005836 +v 0.277200 -0.031830 0.006622 +v 0.276105 -0.025311 0.005069 +v 0.275926 -0.025358 0.004857 +v 0.276720 -0.032003 0.005643 +v 0.275479 -0.025449 0.004534 +v 0.276273 -0.032094 0.005320 +v 0.275222 -0.025492 0.004431 +v 0.274673 -0.025566 0.004355 +v 0.275467 -0.032212 0.005141 +v 0.274396 -0.025596 0.004384 +v 0.274126 -0.025620 0.004458 +v 0.274919 -0.032265 0.005243 +v 0.273430 -0.025649 0.004917 +v 0.274224 -0.032294 0.005702 +v 0.273119 -0.025631 0.005381 +v 0.273913 -0.032276 0.006167 +v 0.272970 -0.025585 0.005918 +v 0.272998 -0.025516 0.006472 +v 0.273792 -0.032162 0.007258 +v 0.273361 -0.025386 0.007212 +v 0.274154 -0.032031 0.007998 +v 0.274349 -0.031984 0.008194 +v 0.273780 -0.025293 0.007570 +v 0.274573 -0.031939 0.008356 +v 0.274293 -0.025208 0.007776 +v 0.274847 -0.025138 0.007807 +v 0.275640 -0.031783 0.008593 +v 0.275384 -0.025091 0.007662 +v 0.276178 -0.031736 0.008447 +v 0.276195 -0.031542 0.010072 +v 0.273290 -0.031974 0.009352 +v 0.273016 -0.032039 0.009079 +v 0.274651 -0.031727 0.010064 +v 0.278119 -0.031462 0.008802 +v 0.278726 -0.031559 0.007373 +v 0.272543 -0.032525 0.005442 +v 0.272296 -0.032285 0.007722 +v 0.272196 -0.032388 0.006952 +v 0.278297 -0.031875 0.005130 +v 0.278714 -0.031698 0.006210 +v 0.277209 -0.032133 0.004048 +v 0.273866 -0.032534 0.004031 +v 0.275351 -0.032409 0.003588 +v 0.276172 -0.031926 0.010132 +v 0.274805 -0.032090 0.010134 +v 0.274539 -0.032129 0.010065 +v 0.272969 -0.032441 0.009016 +v 0.272433 -0.032617 0.008066 +v 0.272351 -0.032658 0.007804 +v 0.272634 -0.032909 0.005396 +v 0.273113 -0.032932 0.004719 +v 0.273981 -0.032909 0.004036 +v 0.275022 -0.032827 0.003674 +v 0.275295 -0.032799 0.003639 +v 0.277149 -0.032531 0.004032 +v 0.278000 -0.032349 0.004712 +v 0.278327 -0.032258 0.005150 +v 0.278794 -0.031953 0.007255 +v 0.278751 -0.031926 0.007528 +v 0.278205 -0.031842 0.008789 +v 0.277428 -0.031842 0.009574 +v 0.274610 -0.032376 0.009958 +v 0.277922 -0.032586 0.004835 +v 0.277740 -0.032630 0.004647 +v 0.274877 -0.033270 0.004077 +v 0.275155 -0.033922 0.004930 +v 0.275123 -0.033246 0.004025 +v 0.275519 -0.033886 0.004868 +v 0.277201 -0.033615 0.005455 +v 0.277444 -0.033554 0.005728 +v 0.277234 -0.032593 0.009269 +v 0.276828 -0.032612 0.009513 +v 0.276769 -0.032841 0.009367 +v 0.276547 -0.033450 0.008843 +v 0.276396 -0.033460 0.008910 +v 0.276567 -0.032855 0.009456 +v 0.275122 -0.033223 0.009407 +v 0.274362 -0.032416 0.009871 +v 0.274737 -0.033282 0.009290 +v 0.273164 -0.033441 0.007936 +v 0.273051 -0.033504 0.007514 +v 0.273247 -0.033696 0.007297 +v 0.275687 -0.032986 0.008336 +v 0.276806 -0.032940 0.007598 +v 0.274502 -0.033197 0.007746 +v 0.274435 -0.033362 0.006416 +v 0.275554 -0.033316 0.005677 +v 0.276739 -0.033105 0.006268 +v 0.265800 -0.035067 -0.009302 +v 0.266908 -0.034799 -0.010010 +v 0.265933 -0.035115 -0.008915 +v 0.264526 -0.034911 -0.011239 +v 0.267336 -0.034745 -0.009989 +v 0.264609 -0.035123 -0.009917 +v 0.264948 -0.035215 -0.009102 +v 0.267426 -0.034590 -0.010837 +v 0.266825 -0.034587 -0.011332 +v 0.267249 -0.034521 -0.011386 +v 0.265634 -0.034643 -0.011946 +v 0.265150 -0.034655 -0.012260 +v 0.263999 -0.035109 -0.010483 +v 0.264535 -0.034798 -0.011904 +v 0.266420 -0.034498 -0.012179 +v 0.265169 -0.026315 -0.007787 +v 0.265865 -0.026116 -0.008413 +v 0.266049 -0.025976 -0.009098 +v 0.265765 -0.025861 -0.010004 +v 0.264994 -0.025869 -0.010571 +v 0.264279 -0.025955 -0.010628 +v 0.263185 -0.026242 -0.009796 +v 0.263091 -0.026413 -0.008860 +v 0.263780 -0.026483 -0.007899 +v 0.265756 -0.026454 -0.007910 +v 0.266640 -0.033041 -0.009022 +v 0.266097 -0.026336 -0.008337 +v 0.266282 -0.026224 -0.008853 +v 0.267166 -0.032811 -0.009964 +v 0.266309 -0.026174 -0.009127 +v 0.266292 -0.026130 -0.009404 +v 0.267176 -0.032717 -0.010515 +v 0.265982 -0.026041 -0.010173 +v 0.265801 -0.026029 -0.010387 +v 0.266685 -0.032617 -0.011499 +v 0.265351 -0.026034 -0.010718 +v 0.266234 -0.032621 -0.011830 +v 0.265093 -0.026050 -0.010827 +v 0.264544 -0.026109 -0.010915 +v 0.265427 -0.032696 -0.012027 +v 0.264267 -0.026150 -0.010893 +v 0.263514 -0.026305 -0.010570 +v 0.264397 -0.032892 -0.011682 +v 0.263005 -0.026481 -0.009933 +v 0.262912 -0.026537 -0.009674 +v 0.263796 -0.033124 -0.010786 +v 0.262897 -0.026678 -0.008852 +v 0.263781 -0.033265 -0.009964 +v 0.263268 -0.026754 -0.008109 +v 0.264152 -0.033341 -0.009221 +v 0.263691 -0.026759 -0.007743 +v 0.264575 -0.033346 -0.008855 +v 0.264759 -0.026659 -0.007483 +v 0.265643 -0.033247 -0.008595 +v 0.265294 -0.026565 -0.007615 +v 0.266178 -0.033152 -0.008727 +v 0.266588 -0.033353 -0.007215 +v 0.267592 -0.033124 -0.007774 +v 0.262786 -0.033649 -0.008481 +v 0.265444 -0.033535 -0.007044 +v 0.264302 -0.033648 -0.007281 +v 0.268499 -0.032796 -0.008994 +v 0.268746 -0.032573 -0.010117 +v 0.262512 -0.033126 -0.011797 +v 0.262294 -0.033537 -0.009538 +v 0.262198 -0.033355 -0.010692 +v 0.268253 -0.032326 -0.011971 +v 0.267154 -0.032288 -0.013071 +v 0.263815 -0.032720 -0.013167 +v 0.265293 -0.032453 -0.013572 +v 0.266723 -0.033711 -0.007309 +v 0.264307 -0.034026 -0.007363 +v 0.264055 -0.034040 -0.007480 +v 0.263170 -0.034047 -0.008139 +v 0.262820 -0.034022 -0.008568 +v 0.262234 -0.033795 -0.010376 +v 0.262240 -0.033748 -0.010650 +v 0.262608 -0.033480 -0.011949 +v 0.263270 -0.033247 -0.012802 +v 0.263936 -0.033079 -0.013268 +v 0.265242 -0.032842 -0.013631 +v 0.266065 -0.032741 -0.013578 +v 0.267098 -0.032667 -0.013197 +v 0.268288 -0.032699 -0.012059 +v 0.268638 -0.032778 -0.011310 +v 0.268798 -0.032940 -0.010230 +v 0.268592 -0.033147 -0.009164 +v 0.267660 -0.033494 -0.007852 +v 0.264052 -0.033832 -0.012845 +v 0.266075 -0.033496 -0.013227 +v 0.266530 -0.033456 -0.013101 +v 0.267843 -0.033695 -0.011863 +v 0.268327 -0.033259 -0.011536 +v 0.268046 -0.033734 -0.011472 +v 0.268414 -0.033287 -0.011302 +v 0.268372 -0.033622 -0.009352 +v 0.268160 -0.033725 -0.008907 +v 0.266674 -0.034134 -0.007665 +v 0.266438 -0.034179 -0.007589 +v 0.266416 -0.034368 -0.007792 +v 0.265953 -0.034900 -0.008402 +v 0.265956 -0.034444 -0.007705 +v 0.265770 -0.034926 -0.008391 +v 0.264390 -0.034230 -0.007532 +v 0.264767 -0.034895 -0.008336 +v 0.264974 -0.035122 -0.008798 +v 0.264679 -0.035136 -0.008951 +v 0.263521 -0.034920 -0.010215 +v 0.263483 -0.034864 -0.010580 +v 0.263684 -0.033929 -0.012563 +v 0.265701 -0.034329 -0.009178 +v 0.266809 -0.034061 -0.009885 +v 0.264510 -0.034385 -0.009793 +v 0.264427 -0.034173 -0.011115 +v 0.265535 -0.033905 -0.011822 +v 0.266726 -0.033849 -0.011207 +v 0.285798 -0.032326 -0.009453 +v 0.286885 -0.032020 -0.010177 +v 0.286357 -0.032312 -0.009177 +v 0.284471 -0.032087 -0.011346 +v 0.284591 -0.032359 -0.010038 +v 0.284952 -0.032487 -0.009238 +v 0.287380 -0.031771 -0.011007 +v 0.286766 -0.031748 -0.011485 +v 0.284021 -0.032160 -0.011290 +v 0.284075 -0.032399 -0.010170 +v 0.285559 -0.031781 -0.012069 +v 0.285066 -0.031781 -0.012370 +v 0.286595 -0.031618 -0.012178 +v 0.285570 -0.023546 -0.007780 +v 0.286020 -0.023253 -0.008835 +v 0.285550 -0.023080 -0.009908 +v 0.284209 -0.023170 -0.010315 +v 0.283139 -0.023500 -0.009469 +v 0.283150 -0.023754 -0.008312 +v 0.284237 -0.023804 -0.007424 +v 0.285761 -0.023786 -0.007663 +v 0.285944 -0.023717 -0.007865 +v 0.286820 -0.030242 -0.009303 +v 0.286261 -0.023511 -0.008608 +v 0.287137 -0.030035 -0.010046 +v 0.286281 -0.023448 -0.008881 +v 0.286256 -0.023391 -0.009154 +v 0.287132 -0.029916 -0.010592 +v 0.285738 -0.023248 -0.010118 +v 0.286614 -0.029773 -0.011557 +v 0.285279 -0.023239 -0.010437 +v 0.286155 -0.029764 -0.011876 +v 0.284467 -0.023309 -0.010616 +v 0.285343 -0.029834 -0.012054 +v 0.284191 -0.023352 -0.010588 +v 0.283448 -0.023526 -0.010253 +v 0.284324 -0.030051 -0.011691 +v 0.282957 -0.023733 -0.009611 +v 0.282871 -0.023802 -0.009353 +v 0.283747 -0.030326 -0.010791 +v 0.282969 -0.024026 -0.008277 +v 0.283846 -0.030550 -0.009715 +v 0.283703 -0.024108 -0.007456 +v 0.284579 -0.030633 -0.008894 +v 0.284223 -0.024083 -0.007252 +v 0.284777 -0.024016 -0.007220 +v 0.285653 -0.030541 -0.008658 +v 0.285308 -0.023914 -0.007362 +v 0.286184 -0.030438 -0.008800 +v 0.285884 -0.030845 -0.007137 +v 0.286988 -0.030625 -0.007462 +v 0.282802 -0.030961 -0.008487 +v 0.285497 -0.030901 -0.007117 +v 0.284350 -0.031009 -0.007329 +v 0.288336 -0.030156 -0.008768 +v 0.288692 -0.029702 -0.010613 +v 0.282436 -0.030287 -0.011767 +v 0.282154 -0.030568 -0.010665 +v 0.288363 -0.029502 -0.011720 +v 0.286690 -0.029378 -0.013302 +v 0.287367 -0.029374 -0.012907 +v 0.283701 -0.029812 -0.013150 +v 0.285167 -0.029520 -0.013583 +v 0.287017 -0.031001 -0.007534 +v 0.286248 -0.031163 -0.007269 +v 0.285430 -0.031288 -0.007202 +v 0.284883 -0.031346 -0.007271 +v 0.284353 -0.031382 -0.007428 +v 0.283007 -0.031354 -0.008376 +v 0.282834 -0.031330 -0.008592 +v 0.282342 -0.031181 -0.009569 +v 0.282198 -0.030963 -0.010642 +v 0.282330 -0.030770 -0.011439 +v 0.282529 -0.030633 -0.011937 +v 0.283820 -0.030166 -0.013271 +v 0.284844 -0.029951 -0.013624 +v 0.285116 -0.029907 -0.013658 +v 0.285939 -0.029804 -0.013622 +v 0.287448 -0.029746 -0.012966 +v 0.287661 -0.029757 -0.012788 +v 0.288346 -0.029854 -0.011928 +v 0.288470 -0.029892 -0.011682 +v 0.288749 -0.030086 -0.010632 +v 0.288365 -0.030539 -0.008812 +v 0.287598 -0.030023 -0.012738 +v 0.284647 -0.030254 -0.013484 +v 0.284356 -0.030833 -0.013109 +v 0.284720 -0.030502 -0.013381 +v 0.284796 -0.030741 -0.013261 +v 0.284963 -0.030459 -0.013432 +v 0.285961 -0.030574 -0.013307 +v 0.286479 -0.031222 -0.012675 +v 0.286640 -0.030528 -0.013105 +v 0.286806 -0.031217 -0.012500 +v 0.287394 -0.030013 -0.012907 +v 0.287434 -0.030534 -0.012593 +v 0.287979 -0.030884 -0.011618 +v 0.287804 -0.031411 -0.011012 +v 0.287837 -0.031487 -0.010650 +v 0.288212 -0.031085 -0.010564 +v 0.288362 -0.030868 -0.009504 +v 0.287903 -0.031482 -0.009829 +v 0.287719 -0.031659 -0.009941 +v 0.288162 -0.030993 -0.009060 +v 0.286829 -0.032020 -0.008845 +v 0.286478 -0.031515 -0.007718 +v 0.286451 -0.031694 -0.007929 +v 0.286238 -0.031560 -0.007657 +v 0.286225 -0.031737 -0.007872 +v 0.285058 -0.031893 -0.007874 +v 0.284604 -0.031925 -0.008008 +v 0.283768 -0.032260 -0.009620 +v 0.283174 -0.031854 -0.009200 +v 0.282773 -0.031617 -0.009514 +v 0.283603 -0.032210 -0.009948 +v 0.282884 -0.031752 -0.009840 +v 0.285699 -0.031595 -0.009292 +v 0.286787 -0.031289 -0.010015 +v 0.284492 -0.031628 -0.009877 +v 0.284373 -0.031356 -0.011185 +v 0.285461 -0.031050 -0.011908 +v 0.286668 -0.031017 -0.011323 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vn -0.0031 1.0000 -0.0027 +vn -0.0057 1.0000 0.0026 +vn -0.0078 0.9999 -0.0068 +vn -0.0021 1.0000 0.0006 +vn 0.0027 1.0000 -0.0079 +vn -0.4792 -0.0323 0.8771 +vn -0.6479 0.1609 0.7445 +vn -0.5152 -0.0227 0.8567 +vn -0.6736 0.1369 0.7263 +vn -0.9951 -0.0119 0.0984 +vn -0.9948 -0.0111 0.1012 +vn -0.9938 -0.0083 0.1112 +vn -0.9935 -0.0076 0.1134 +vn -0.6976 -0.0225 -0.7161 +vn -0.7816 0.0055 -0.6238 +vn -0.7634 -0.0009 -0.6460 +vn -0.6817 -0.0274 -0.7312 +vn -0.1880 0.0358 -0.9815 +vn 0.3488 -0.0392 -0.9364 +vn 0.5179 0.0018 -0.8555 +vn 0.3805 -0.0319 -0.9242 +vn 0.5579 0.0123 -0.8298 +vn 0.9642 -0.0027 -0.2651 +vn 0.9611 0.0004 -0.2760 +vn 0.9618 -0.0002 -0.2739 +vn 0.9648 -0.0033 -0.2630 +vn 0.8826 -0.0090 0.4701 +vn 0.8372 0.0114 0.5468 +vn 0.8745 -0.0051 0.4850 +vn 0.8287 0.0149 0.5594 +vn 0.3360 -0.0111 0.9418 +vn 0.2150 0.0154 0.9765 +vn 0.3120 -0.0057 0.9501 +vn 0.1928 0.0202 0.9810 +vn -0.2196 0.7393 -0.6365 +vn 0.1232 0.7584 -0.6400 +vn -0.3867 0.7077 -0.5913 +vn -0.5465 0.7001 -0.4596 +vn -0.5730 0.6781 -0.4604 +vn -0.7299 0.6793 0.0757 +vn -0.5854 0.7952 0.1578 +vn -0.6701 0.7337 0.1122 +vn -0.5369 0.8239 0.1814 +vn -0.6009 0.4716 0.6454 +vn 0.0928 0.7983 0.5951 +vn 0.1007 0.7896 0.6053 +vn 0.1181 0.7700 0.6271 +vn 0.1287 0.7574 0.6401 +vn 0.7013 0.5309 0.4757 +vn 0.5056 0.8623 0.0282 +vn 0.5668 0.8235 -0.0218 +vn 0.6955 0.7046 -0.1411 +vn 0.7681 0.6006 -0.2222 +vn 0.4679 0.5425 -0.6977 +vn 0.3562 0.6585 -0.6629 +vn 0.0000 1.0000 0.0000 +vn 0.0033 -1.0000 0.0017 +vn 0.0030 -1.0000 0.0008 +vn 0.0029 -1.0000 -0.0004 +vn 0.0032 -1.0000 -0.0012 +vn 0.0016 -1.0000 -0.0014 +vn 0.0005 -1.0000 -0.0010 +vn 0.0004 -1.0000 -0.0010 +vn 0.0005 -1.0000 -0.0018 +vn 0.0003 -1.0000 -0.0021 +vn -0.0007 -1.0000 0.0062 +vn -0.0004 -1.0000 0.0031 +vn 0.0006 -1.0000 0.0032 +vn -0.0010 -1.0000 -0.0017 +vn -0.0011 -1.0000 -0.0015 +vn -0.0017 -1.0000 -0.0013 +vn -0.0053 -1.0000 -0.0037 +vn -0.0194 -0.9998 -0.0037 +vn 0.0074 -1.0000 0.0052 +vn 0.0029 -1.0000 0.0028 +vn -0.0247 -0.9997 0.0075 +vn -0.8740 0.4808 0.0706 +vn -0.7173 -0.5946 0.3632 +vn -0.5687 0.5391 0.6212 +vn -0.1657 -0.4622 0.8712 +vn -0.1687 -0.4852 0.8580 +vn -0.1293 -0.2144 0.9682 +vn -0.1136 -0.1199 0.9863 +vn 0.3632 0.3493 0.8637 +vn 0.5487 -0.4145 0.7260 +vn 0.7618 0.4144 0.4979 +vn 0.8272 -0.5172 0.2196 +vn 0.7579 0.6198 -0.2035 +vn 0.7200 -0.5390 -0.4371 +vn 0.3754 0.4092 -0.8317 +vn 0.0491 -0.0449 -0.9978 +vn 0.3020 -0.0958 -0.9485 +vn 0.0399 -0.0708 -0.9967 +vn -0.2543 0.2558 -0.9327 +vn -0.2591 0.2850 -0.9228 +vn -0.6475 -0.3160 -0.6935 +vn -0.7706 0.3693 -0.5194 +vn -0.8982 -0.3616 -0.2500 +vn 0.0083 -0.9988 -0.0478 +vn -0.0301 -0.9981 -0.0531 +vn 0.0064 -0.9990 -0.0435 +vn 0.0388 -0.9974 -0.0601 +vn -0.1028 -0.9935 -0.0492 +vn -0.0987 -0.9930 0.0651 +vn -0.0014 -0.9995 0.0300 +vn -0.0155 -0.9988 0.0465 +vn 0.1756 -0.9756 0.1320 +vn 0.0082 -0.9990 0.0444 +vn -0.1187 -0.9929 0.0007 +vn -0.1217 -0.9925 0.0139 +vn 0.1019 -0.9948 0.0075 +vn 0.1253 -0.9903 -0.0602 +vn 0.5974 -0.8007 -0.0438 +vn 0.6325 -0.6643 0.3983 +vn 0.3985 -0.7751 0.4903 +vn -0.5763 -0.8148 -0.0628 +vn -0.5741 -0.6852 -0.4483 +vn -0.1909 -0.7798 -0.5962 +vn 0.3244 -0.7758 -0.5411 +vn 0.6698 -0.6783 -0.3022 +vn -0.3799 -0.7897 0.4817 +vn -0.6632 -0.7137 0.2254 +vn -0.7577 -0.6401 -0.1271 +vn 0.7583 -0.6451 0.0944 +vn 0.0849 -0.6479 0.7570 +vn 0.0208 -0.7721 0.6352 +vn -0.2722 -0.5949 0.7563 +vn -0.5775 -0.6258 0.5243 +vn -0.1067 -0.6182 -0.7787 +vn 0.1994 -0.6275 -0.7526 +vn 0.5216 -0.5848 -0.6213 +vn 0.3751 -0.5526 0.7443 +vn -0.5018 -0.5627 -0.6569 +vn -0.8068 -0.5425 0.2339 +vn 0.0312 -0.4652 0.8846 +vn -0.4350 -0.4923 -0.7539 +vn -0.0398 -0.4855 -0.8733 +vn 0.3536 -0.4735 -0.8067 +vn 0.6949 -0.4912 -0.5252 +vn 0.8369 -0.5224 -0.1634 +vn 0.8367 -0.5039 0.2145 +vn 0.6166 -0.4946 0.6125 +vn -0.5542 -0.4807 0.6796 +vn -0.8073 -0.5115 -0.2944 +vn -0.0000 -1.0000 -0.0000 +vn -0.9999 0.0076 0.0133 +vn -0.9984 -0.0199 -0.0537 +vn -0.9982 -0.0254 0.0539 +vn -0.9846 0.0314 0.1721 +vn -0.9884 0.0348 -0.1475 +vn -0.4995 -0.0344 -0.8656 +vn -0.4985 -0.0334 -0.8662 +vn -0.4976 -0.0323 -0.8668 +vn 0.5107 -0.0091 -0.8597 +vn 0.5100 -0.0081 -0.8601 +vn 0.4998 0.0047 -0.8661 +vn 0.5202 -0.0211 -0.8538 +vn 0.9992 -0.0402 0.0000 +vn 0.9991 0.0014 0.0414 +vn 0.9990 0.0047 0.0448 +vn 0.9954 0.0449 0.0846 +vn 0.4992 -0.0495 0.8651 +vn 0.4700 -0.0173 0.8825 +vn 0.4697 -0.0171 0.8826 +vn 0.4395 0.0151 0.8981 +vn -0.5046 -0.0377 0.8625 +vn -0.5048 -0.0380 0.8624 +vn -0.4995 -0.0319 0.8657 +vn -0.5102 -0.0441 0.8589 +vn 0.9508 -0.2903 0.1083 +vn 0.9625 -0.2409 0.1252 +vn 0.9666 0.1126 0.2301 +vn 0.9542 0.1719 0.2450 +vn 0.7430 -0.1877 0.6424 +vn 0.7418 -0.1565 0.6521 +vn 0.7137 0.0522 0.6985 +vn 0.7036 0.0957 0.7041 +vn 0.2382 0.0111 0.9711 +vn 0.2481 0.0517 0.9673 +vn 0.1933 -0.1560 0.9687 +vn 0.1857 -0.1817 0.9657 +vn -0.2516 0.1036 0.9623 +vn -0.2255 0.1738 0.9586 +vn -0.3569 -0.2419 0.9023 +vn -0.3705 -0.2993 0.8793 +vn -0.6589 0.3645 0.6580 +vn -0.8064 -0.4351 0.4004 +vn -0.8873 0.4452 0.1203 +vn -0.7984 -0.5383 -0.2698 +vn -0.6300 0.5938 -0.5006 +vn -0.3062 -0.5618 -0.7686 +vn -0.0197 0.4947 -0.8688 +vn 0.3054 -0.3661 -0.8790 +vn 0.5995 0.3022 -0.7411 +vn 0.7684 -0.3546 -0.5327 +vn 0.8844 0.3511 -0.3074 +vn -0.8126 0.0139 -0.5827 +vn -0.8422 -0.0310 -0.5382 +vn -0.8323 -0.0152 -0.5541 +vn -0.8617 -0.0643 -0.5034 +vn -0.0052 -0.0430 -0.9991 +vn -0.2745 0.0794 -0.9583 +vn 0.1151 0.0226 -0.9931 +vn 0.2411 -0.0571 -0.9688 +vn 0.4721 0.0504 -0.8801 +vn 0.8895 -0.0092 -0.4568 +vn 0.9030 -0.0304 -0.4287 +vn 0.8957 -0.0188 -0.4442 +vn 0.8826 0.0010 -0.4702 +vn 0.9440 -0.0173 0.3294 +vn 0.9367 -0.0008 0.3502 +vn 0.9391 -0.0061 0.3436 +vn 0.9311 0.0107 0.3647 +vn 0.2374 -0.0246 0.9711 +vn 0.3056 0.0215 0.9519 +vn 0.2606 -0.0091 0.9654 +vn 0.1969 -0.0513 0.9791 +vn -0.5422 -0.0155 0.8401 +vn -0.4233 0.0442 0.9049 +vn -0.4818 0.0155 0.8762 +vn -0.5953 -0.0441 0.8023 +vn -0.9654 0.0006 0.2609 +vn -0.9402 0.0445 0.3377 +vn -0.9546 0.0212 0.2971 +vn -0.9765 -0.0255 0.2140 +vn 0.0457 -0.9968 -0.0659 +vn 0.0288 -0.9962 -0.0821 +vn 0.0801 -0.9968 0.0066 +vn -0.0018 -0.9912 -0.1320 +vn -0.0269 -0.9914 -0.1281 +vn 0.0721 -0.9972 0.0194 +vn 0.1028 -0.9940 0.0376 +vn -0.0980 -0.9948 0.0290 +vn -0.1200 -0.9927 0.0118 +vn -0.0633 -0.9942 -0.0871 +vn -0.0640 -0.9932 -0.0968 +vn 0.0366 -0.9974 0.0613 +vn -0.0530 -0.9965 0.0642 +vn -0.1059 -0.9916 0.0750 +vn -0.0279 -0.9911 0.1304 +vn -0.0392 -0.9905 0.1321 +vn 0.0181 -0.9969 0.0767 +vn 0.9969 -0.0126 0.0777 +vn 0.9920 -0.0363 0.1211 +vn 0.9716 0.0587 -0.2290 +vn 0.8538 -0.0298 -0.5197 +vn 0.7769 0.0005 -0.6296 +vn 0.4979 -0.0279 -0.8668 +vn 0.4003 -0.0615 -0.9143 +vn 0.0784 -0.0227 -0.9967 +vn -0.1192 -0.0704 -0.9904 +vn -0.3569 -0.0301 -0.9337 +vn -0.6670 -0.0801 -0.7408 +vn -0.6987 -0.0220 -0.7151 +vn -0.8539 0.1547 -0.4969 +vn -0.9611 -0.0786 -0.2648 +vn -0.9777 -0.0471 -0.2046 +vn -0.9686 -0.0405 0.2454 +vn -0.9697 0.0098 0.2441 +vn -0.8057 -0.0375 0.5911 +vn -0.6911 -0.0724 0.7191 +vn -0.6117 -0.1403 0.7785 +vn -0.2033 -0.0639 0.9770 +vn -0.1670 -0.0248 0.9856 +vn 0.1680 0.1140 0.9792 +vn 0.3483 -0.0652 0.9351 +vn 0.6318 -0.0241 0.7748 +vn 0.7619 -0.0556 0.6453 +vn 0.9199 -0.0780 0.3843 +vn 0.0080 -0.9999 -0.0134 +vn 0.0174 -0.9997 -0.0159 +vn 0.0043 -0.9999 -0.0131 +vn 0.0286 -0.9995 -0.0115 +vn 0.0010 -0.9999 -0.0146 +vn 0.0327 -0.9995 0.0047 +vn -0.0044 -0.9997 -0.0249 +vn -0.0256 -0.9992 -0.0295 +vn -0.0203 -0.9990 -0.0393 +vn -0.0653 -0.9978 -0.0071 +vn -0.0239 -0.9997 0.0086 +vn -0.2354 -0.9710 0.0413 +vn -0.0175 -0.9996 0.0228 +vn -0.0681 -0.9738 0.2171 +vn -0.0103 -0.9990 0.0424 +vn -0.0426 -0.9955 0.0846 +vn 0.0146 -0.9998 0.0161 +vn 0.0187 -0.9998 0.0028 +vn 0.0241 -0.9996 0.0167 +vn 0.0130 -0.9997 0.0188 +vn -0.0594 -0.9980 0.0199 +vn 0.0290 0.0457 -0.9985 +vn -0.3806 -0.6323 -0.6748 +vn -0.1587 -0.7816 -0.6032 +vn -0.0732 -0.8219 -0.5649 +vn 0.4137 -0.7358 -0.5361 +vn 0.1928 -0.8693 -0.4552 +vn 0.6661 -0.3097 -0.6786 +vn 0.5352 -0.7969 -0.2800 +vn 0.9442 -0.1729 0.2805 +vn 0.2431 -0.8155 0.5253 +vn -0.1383 -0.8566 0.4971 +vn -0.6756 -0.2591 0.6903 +vn -0.5907 -0.7374 0.3275 +vn -0.5704 -0.7924 0.2165 +vn -0.7741 0.4212 -0.4726 +vn -0.4752 -0.5451 -0.6907 +vn 0.1242 -0.9000 -0.4178 +vn 0.6712 -0.2927 -0.6810 +vn 0.9763 0.1493 -0.1564 +vn 0.5216 -0.7452 0.4155 +vn 0.6421 -0.3240 0.6948 +vn 0.0789 0.2713 0.9593 +vn -0.5157 -0.8416 0.1606 +vn 0.4969 -0.8642 0.0785 +vn 0.9637 0.1432 -0.2252 +vn 0.5006 -0.7327 -0.4611 +vn -0.0036 -0.1615 0.9869 +vn 0.0112 -0.0946 0.9954 +vn -0.0117 0.1169 0.9931 +vn 0.0036 0.1790 0.9838 +vn 0.0016 0.2672 0.9636 +vn -0.0028 0.2653 0.9642 +vn -0.0862 0.7920 -0.6045 +vn 0.0538 0.7649 -0.6419 +vn -0.0029 0.9525 -0.3046 +vn 0.0014 0.9524 -0.3049 +vn 0.0041 1.0000 -0.0073 +vn 0.0133 0.9998 -0.0133 +vn 0.0082 0.9999 -0.0099 +vn -0.0089 -0.9999 -0.0097 +vn 0.0016 -1.0000 -0.0029 +vn -0.0045 -1.0000 -0.0068 +vn 0.0115 -0.9063 -0.4225 +vn 0.0116 -0.8330 -0.5532 +vn 0.0224 -0.8928 -0.4499 +vn 0.0118 -0.9734 -0.2287 +vn 0.0279 -0.8132 -0.5813 +vn -0.0178 -0.9782 -0.2070 +vn -0.0071 -0.9904 -0.1379 +vn 0.0518 -0.9719 -0.2294 +vn -0.2133 -0.1570 -0.9643 +vn 0.0174 -0.5217 -0.8529 +vn -0.0078 -0.6620 -0.7495 +vn -0.0056 -0.5372 -0.8434 +vn 0.0180 -0.2804 -0.9597 +vn -0.0079 -0.2003 -0.9797 +vn 0.0140 0.1205 -0.9926 +vn -0.0106 0.1286 -0.9916 +vn -0.0026 0.3839 -0.9234 +vn 0.0131 0.4453 -0.8953 +vn -0.0066 0.6185 -0.7857 +vn 0.0014 0.6686 -0.7436 +vn 0.0017 0.9897 -0.1430 +vn -0.0014 0.9906 -0.1370 +vn 0.9988 0.0422 -0.0239 +vn 0.9980 0.0538 -0.0341 +vn 0.9989 0.0373 -0.0274 +vn 0.9998 0.0113 -0.0148 +vn 0.9808 0.1755 -0.0854 +vn 0.9890 -0.0385 -0.1427 +vn 0.9998 -0.0197 -0.0051 +vn 0.9995 -0.0234 -0.0214 +vn 0.9974 -0.0642 -0.0312 +vn 0.9984 -0.0523 -0.0201 +vn 0.9992 -0.0373 -0.0143 +vn 0.9998 -0.0114 -0.0167 +vn 0.9985 0.0250 -0.0477 +vn 0.9228 0.0940 -0.3736 +vn 0.9841 -0.0422 -0.1727 +vn 0.8358 0.0273 -0.5483 +vn 0.8941 0.4069 -0.1873 +vn 0.1214 0.7088 -0.6949 +vn 0.6942 0.1824 -0.6963 +vn 0.7425 -0.1565 -0.6513 +vn 0.7359 -0.1599 -0.6580 +vn 0.7312 -0.2812 -0.6215 +vn 0.1094 -0.9694 -0.2198 +vn -0.7618 -0.6172 -0.1970 +vn -0.7922 -0.5563 -0.2508 +vn -0.8171 -0.4900 -0.3037 +vn -0.8336 -0.4292 -0.3478 +vn -0.6586 -0.3518 -0.6652 +vn -0.0075 -0.4346 -0.9006 +vn -0.9100 -0.0319 -0.4134 +vn -0.7093 0.0787 -0.7005 +vn -0.9030 -0.0297 -0.4287 +vn -0.7561 0.1592 -0.6348 +vn -0.9644 0.0677 -0.2556 +vn -0.1808 0.7392 -0.6488 +vn -0.8928 0.4118 -0.1826 +vn -0.9986 0.0465 -0.0268 +vn -0.9809 0.1727 -0.0891 +vn 0.7425 0.1260 0.6579 +vn 0.7447 0.1057 0.6590 +vn 0.7732 -0.0445 0.6326 +vn 0.7712 -0.0798 0.6316 +vn 0.6582 0.1941 0.7274 +vn 0.6626 0.1935 0.7236 +vn 0.6629 0.7484 0.0211 +vn -0.7616 -0.1013 0.6401 +vn -0.7646 -0.0930 0.6378 +vn -0.7193 0.1206 0.6842 +vn -0.7572 0.0372 0.6522 +vn -0.6555 0.1966 0.7292 +vn -0.6563 0.1964 0.7285 +vn -0.6677 0.7439 0.0275 +vn -0.0012 0.0170 -0.9999 +vn -0.0017 0.0182 -0.9998 +vn -0.0002 0.0141 -0.9999 +vn 0.0002 0.0130 -0.9999 +vn -0.0001 -0.0049 -1.0000 +vn -0.0001 -0.0050 -1.0000 +vn -0.0001 -0.0051 -1.0000 +vn -0.0016 -0.2657 0.9641 +vn 0.0036 -0.2635 0.9646 +vn -0.0144 -0.9998 -0.0132 +vn 0.6551 -0.1947 0.7300 +vn 0.6581 -0.1939 0.7275 +vn 0.6678 -0.7438 0.0269 +vn -0.6562 -0.1906 0.7301 +vn -0.6625 -0.1897 0.7246 +vn -0.6625 -0.7488 0.0210 +vn -0.4263 0.3119 -0.8491 +vn -0.0762 0.5377 -0.8397 +vn -0.0016 0.5358 -0.8444 +vn 0.0085 0.3767 -0.9263 +vn -0.0017 0.5376 -0.8432 +vn -0.0031 0.5384 -0.8427 +vn -0.1229 0.5376 -0.8342 +vn -0.0012 0.5331 -0.8460 +vn 0.0045 -0.0441 -0.9990 +vn -0.4242 -0.0714 -0.9028 +vn 0.0027 -0.4120 -0.9112 +vn -0.0005 -0.4183 -0.9083 +vn -0.0009 0.0077 1.0000 +vn -0.0029 0.0022 1.0000 +vn -0.0037 -0.0001 1.0000 +vn -0.0000 -0.0000 1.0000 +vn -0.0001 0.0099 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.6418 -0.7669 0.0014 +vn -0.7082 -0.7055 -0.0256 +vn -0.5297 -0.8471 0.0424 +vn -0.7588 -0.6495 -0.0479 +vn 0.1097 -0.9938 -0.0207 +vn 0.1460 -0.9893 0.0025 +vn 0.0657 -0.9967 -0.0486 +vn 0.1837 -0.9826 0.0268 +vn 0.8782 -0.4782 -0.0092 +vn 0.8753 -0.4836 -0.0066 +vn 0.8770 -0.4804 -0.0081 +vn 0.8730 -0.4877 -0.0047 +vn 0.7818 0.6231 0.0247 +vn 0.8475 0.5300 -0.0294 +vn 0.8237 0.5670 -0.0085 +vn 0.7607 0.6478 0.0401 +vn -0.3951 0.9186 -0.0055 +vn -0.3398 0.9401 -0.0267 +vn -0.3570 0.9339 -0.0202 +vn -0.4172 0.9088 0.0032 +vn -0.9927 0.1131 0.0420 +vn -0.9987 0.0503 0.0090 +vn -0.9955 0.0898 0.0297 +vn -0.9993 0.0364 0.0017 +vn -0.7519 -0.6580 -0.0413 +vn -0.8766 -0.4809 0.0167 +vn -0.9057 -0.4226 0.0340 +vn -0.6881 -0.7226 -0.0651 +vn -0.0004 -1.0000 -0.0050 +vn -0.0573 -0.9980 0.0254 +vn -0.1159 -0.9916 0.0568 +vn 0.0711 -0.9965 -0.0432 +vn 0.6599 -0.7490 0.0600 +vn 0.8930 -0.4492 -0.0272 +vn 0.9549 -0.2966 0.0140 +vn 0.9490 -0.3130 -0.0370 +vn 0.9911 -0.1318 0.0172 +vn 0.7876 0.6160 -0.0159 +vn 0.7843 0.6203 -0.0139 +vn 0.7851 0.6193 -0.0143 +vn 0.7883 0.6150 -0.0163 +vn 0.0600 0.9977 0.0321 +vn -0.2060 0.9778 -0.0394 +vn -0.0160 0.9998 0.0118 +vn -0.2664 0.9622 -0.0558 +vn -0.9787 0.2020 -0.0358 +vn -0.8967 0.4417 0.0299 +vn -0.8594 0.5089 0.0496 +vn -0.9922 0.1095 -0.0596 +vn 0.0072 0.9559 -0.2936 +vn 0.0299 0.8804 -0.4733 +vn 0.0301 0.8208 -0.5704 +vn 0.0572 0.7282 -0.6829 +vn 0.0208 0.9186 -0.3947 +vn 0.0332 0.8677 -0.4959 +vn -0.2055 0.9229 0.3256 +vn -0.0193 0.9998 -0.0111 +vn 0.0157 0.9406 -0.3392 +vn 0.0622 0.6909 -0.7203 +vn 0.3121 0.8647 -0.3935 +vn 0.0869 0.9054 -0.4156 +vn 0.5780 0.7879 -0.2124 +vn -0.7093 0.3513 -0.6111 +vn -0.5834 0.1156 -0.8039 +vn -0.7065 -0.1820 -0.6839 +vn -0.7149 -0.2602 -0.6490 +vn -0.7428 -0.3080 -0.5945 +vn -0.8051 0.3345 -0.4898 +vn -0.7021 0.6094 -0.3683 +vn 0.7662 0.3487 -0.5397 +vn 0.7623 0.3534 -0.5422 +vn 0.7639 0.3516 -0.5412 +vn 0.7479 0.2570 -0.6120 +vn 0.7461 0.2356 -0.6227 +vn 0.6132 -0.2579 -0.7466 +vn 0.7149 -0.3397 -0.6112 +vn 0.7750 -0.0360 -0.6309 +vn 0.7623 0.0430 -0.6458 +vn 0.5727 0.7687 -0.2849 +vn -0.6861 0.4990 -0.5294 +vn -0.7259 0.6641 -0.1790 +vn 0.7824 0.6211 -0.0467 +vn 0.6854 -0.7257 0.0595 +vn 0.7288 -0.6708 0.1375 +vn 0.7638 -0.6092 0.2132 +vn 0.7885 -0.5478 0.2798 +vn -0.6508 -0.5166 0.5564 +vn 0.8253 -0.3110 0.4713 +vn 0.8442 -0.2463 0.4761 +vn 0.8566 -0.1936 0.4784 +vn 0.8674 -0.1338 0.4793 +vn 0.5007 -0.1626 0.8502 +vn 0.8823 0.0418 0.4688 +vn -0.1155 0.2908 0.9498 +vn 0.7787 0.2397 0.5799 +vn 0.8026 0.2644 0.5347 +vn 0.8341 0.3003 0.4627 +vn 0.8490 0.3195 0.4208 +vn -0.5385 0.6303 0.5592 +vn 0.9994 0.0325 0.0125 +vn 0.9998 0.0220 0.0018 +vn 0.9996 0.0283 0.0084 +vn 0.9995 0.0073 0.0304 +vn 1.0000 0.0044 0.0089 +vn 0.9996 0.0131 0.0256 +vn 0.9999 -0.0134 0.0083 +vn 0.9055 0.2329 0.3547 +vn 0.9978 0.0418 0.0522 +vn 0.9990 0.0370 0.0249 +vn 0.9938 -0.0635 0.0909 +vn 0.9902 -0.0735 0.1187 +vn 0.9998 -0.0126 -0.0183 +vn 0.8930 0.2471 0.3762 +vn -0.7701 0.6363 -0.0462 +vn -0.7072 -0.6837 0.1801 +vn -0.7070 -0.6820 0.1872 +vn -0.7046 -0.7076 0.0537 +vn -0.9936 0.0895 0.0686 +vn -0.8820 0.4631 0.0868 +vn -0.9797 0.1957 0.0432 +vn -0.5644 0.7095 0.4220 +vn 0.0163 0.7713 0.6363 +vn 0.1204 0.6057 0.7865 +vn 0.2381 0.6391 0.7313 +vn -0.9057 0.1839 0.3819 +vn -0.7415 0.1730 0.6483 +vn -0.8962 0.1865 0.4025 +vn -0.8026 0.0622 0.5933 +vn -0.8153 -0.0800 0.5735 +vn -0.8117 -0.0551 0.5815 +vn -0.8191 -0.1682 0.5484 +vn 0.0060 -0.0900 0.9959 +vn -0.0488 -0.2843 0.9575 +vn -0.1066 -0.2202 0.9696 +vn -0.9031 -0.2024 0.3788 +vn 0.2089 -0.7148 0.6674 +vn 0.1068 -0.6693 0.7353 +vn 0.0015 -0.8383 0.5452 +vn -0.6974 -0.6465 0.3094 +vn 0.0272 0.9843 0.1745 +vn -0.0054 0.9958 0.0918 +vn -0.0009 0.9721 0.2346 +vn 0.0245 0.9352 0.3532 +vn -0.0084 0.8593 0.5115 +vn -0.0188 0.6925 0.7212 +vn -0.0055 0.4924 0.8703 +vn 0.0091 0.2437 0.9698 +vn -0.0094 0.2398 0.9708 +vn -0.0079 -0.0885 0.9960 +vn -0.0120 -0.4138 0.9103 +vn 0.0008 -0.6482 0.7615 +vn 0.0098 -0.8175 0.5759 +vn -0.0044 -0.9624 0.2716 +vn 0.0018 -0.9603 0.2791 +vn 0.0023 -0.9919 0.1267 +vn 0.0057 -0.9910 0.1340 +vn -0.0195 0.9994 0.0278 +vn -0.0149 0.9996 0.0227 +vn -0.0023 -0.5387 -0.8425 +vn 0.0018 -0.5392 -0.8422 +vn 0.0044 -0.5403 -0.8415 +vn -0.0061 -0.5393 -0.8421 +vn 0.0001 -0.5331 -0.8461 +vn 0.9462 0.3209 -0.0422 +vn 0.9395 0.3408 -0.0335 +vn 0.9332 0.3583 -0.0258 +vn -0.9898 -0.1287 0.0616 +vn -0.4554 -0.8901 -0.0153 +vn -0.5573 -0.8281 -0.0604 +vn -0.5282 -0.8478 -0.0472 +vn -0.4194 -0.9078 -0.0000 +vn 0.7020 -0.7119 0.0195 +vn 0.7329 -0.6804 -0.0021 +vn 0.7119 -0.7022 0.0128 +vn 0.7451 -0.6668 -0.0110 +vn 0.9301 0.3666 -0.0222 +vn 0.1627 0.9851 -0.0556 +vn 0.1524 0.9878 0.0320 +vn 0.4697 0.8809 0.0584 +vn -0.0596 0.9976 -0.0349 +vn -0.2213 0.9733 0.0608 +vn -0.9395 0.3295 -0.0936 +vn -0.9114 0.4061 -0.0665 +vn -0.9247 0.3725 -0.0786 +vn -0.9066 0.4174 -0.0624 +vn 0.9739 0.2249 -0.0288 +vn 0.9990 0.0350 0.0295 +vn 0.9983 -0.0315 0.0496 +vn 0.9514 0.3032 -0.0533 +vn 0.2167 0.9757 0.0334 +vn 0.5821 0.8107 0.0627 +vn 0.2957 0.9521 -0.0776 +vn -0.0074 0.9986 -0.0520 +vn -0.2376 0.9669 0.0926 +vn -0.9396 0.3394 -0.0453 +vn -0.9354 0.3513 -0.0396 +vn -0.9370 0.3469 -0.0417 +vn -0.9344 0.3543 -0.0381 +vn -0.6348 -0.7720 -0.0340 +vn -0.7097 -0.7045 0.0006 +vn -0.6619 -0.7493 -0.0219 +vn -0.7433 -0.6688 0.0175 +vn 0.5929 -0.8046 -0.0314 +vn 0.4695 -0.8827 0.0192 +vn 0.4132 -0.9097 0.0408 +vn 0.6433 -0.7637 -0.0536 +vn -0.0010 -0.9691 -0.2468 +vn 0.0129 -0.9557 -0.2939 +vn 0.4004 -0.9073 -0.1285 +vn 0.3891 -0.8223 -0.4153 +vn -0.0045 -0.8495 -0.5275 +vn 0.0006 -0.8010 -0.5987 +vn -0.0451 -0.6551 -0.7542 +vn -0.2743 -0.8275 -0.4898 +vn -0.3645 -0.9046 -0.2210 +vn -0.7690 -0.3459 -0.5376 +vn -0.8004 -0.3085 -0.5140 +vn -0.7871 -0.3248 -0.5244 +vn 0.5404 -0.4363 -0.7194 +vn 0.7575 -0.4127 -0.5058 +vn 0.6532 -0.6608 -0.3697 +vn -0.5970 -0.7337 -0.3243 +vn 0.7940 -0.6063 -0.0432 +vn -0.7732 -0.6322 -0.0501 +vn -0.0010 -0.9994 0.0335 +vn 0.0133 -0.9986 0.0517 +vn -0.9497 -0.0284 -0.3119 +vn -0.9781 0.0069 -0.2078 +vn -0.9623 0.0073 -0.2719 +vn -0.9695 0.0063 -0.2451 +vn -0.9614 -0.0312 0.2732 +vn -0.9844 -0.0170 0.1754 +vn -0.8783 -0.0154 0.4779 +vn -0.8711 0.0178 0.4909 +vn -0.5163 0.0114 -0.8563 +vn -0.6866 -0.0048 -0.7270 +vn -0.7523 0.0960 -0.6518 +vn -0.9977 -0.0362 -0.0567 +vn -0.9945 -0.0670 -0.0806 +vn -0.9989 -0.0182 -0.0427 +vn -0.9997 0.0177 -0.0147 +vn -0.2212 -0.0311 -0.9747 +vn 0.2135 0.0427 -0.9760 +vn 0.4764 0.0043 -0.8792 +vn 0.6353 0.0474 -0.7708 +vn 0.6846 -0.0246 -0.7285 +vn 0.9841 -0.0469 -0.1711 +vn 0.9908 0.0026 -0.1356 +vn 0.9930 0.0327 -0.1138 +vn 0.9937 0.0782 -0.0806 +vn 0.8712 -0.0246 0.4904 +vn 0.8707 -0.0223 0.4913 +vn 0.9651 -0.0056 0.2619 +vn 0.9688 -0.0054 0.2478 +vn 0.9623 -0.0014 -0.2720 +vn 0.9692 -0.0008 -0.2463 +vn 0.8675 0.0141 -0.4972 +vn 0.8671 0.0124 -0.4979 +vn 0.9961 -0.0350 0.0808 +vn 0.9962 -0.0406 0.0769 +vn 0.9962 -0.0434 0.0750 +vn 0.9963 -0.0504 0.0702 +vn 0.7112 -0.0043 0.7030 +vn 0.7839 0.1019 0.6125 +vn 0.5375 0.0183 0.8430 +vn 0.2856 -0.0307 0.9578 +vn 0.0549 -0.0188 0.9983 +vn -0.0526 -0.1174 0.9917 +vn -0.6376 0.0275 0.7699 +vn -0.5644 0.1230 0.8163 +vn -0.6816 -0.0381 0.7308 +vn -0.7360 -0.1330 0.6638 +vn -0.9959 0.0517 0.0746 +vn -0.9807 0.1305 0.1454 +vn -0.0002 -1.0000 -0.0009 +vn 0.0014 -1.0000 -0.0012 +vn 0.0015 -1.0000 -0.0022 +vn -0.0004 -1.0000 0.0002 +vn -0.0009 -1.0000 0.0010 +vn -0.0027 -1.0000 -0.0021 +vn 0.6637 0.0173 0.7478 +vn 0.6228 0.0029 0.7823 +vn 0.6327 0.0063 0.7744 +vn 0.6711 0.0199 0.7411 +vn 0.9829 -0.0240 0.1825 +vn 0.9902 -0.0158 0.1390 +vn 0.9985 0.0199 -0.0512 +vn 0.9953 0.0277 -0.0927 +vn 0.6541 0.0011 -0.7564 +vn 0.7069 -0.4207 -0.5686 +vn 0.7106 -0.1774 -0.6809 +vn 0.6327 0.0084 -0.7744 +vn -0.1867 0.0004 -0.9824 +vn -0.1955 -0.0022 -0.9807 +vn -0.1887 -0.0002 -0.9820 +vn -0.1974 -0.0028 -0.9803 +vn -0.8563 -0.0029 -0.5164 +vn -0.8601 -0.0007 -0.5100 +vn -0.8729 0.0065 -0.4878 +vn -0.8763 0.0086 -0.4816 +vn -0.9085 -0.0048 0.4179 +vn -0.9114 -0.0070 0.4115 +vn -0.9107 -0.0065 0.4129 +vn -0.9078 -0.0043 0.4194 +vn -0.2839 0.0098 0.9588 +vn -0.2168 -0.1856 0.9584 +vn -0.2705 0.0058 0.9627 +vn 0.0096 -0.5024 0.8646 +vn -0.0236 -0.7684 -0.6396 +vn 0.0190 -0.8124 -0.5827 +vn -0.1188 -0.6497 -0.7508 +vn 0.6208 -0.5753 -0.5325 +vn 0.5441 -0.7825 -0.3027 +vn 0.7798 -0.6083 0.1481 +vn 0.6134 -0.7077 0.3507 +vn 0.7228 -0.6659 0.1848 +vn 0.4293 -0.7235 0.5407 +vn -0.1197 -0.6014 0.7899 +vn -0.6098 -0.7354 0.2955 +vn -0.5911 -0.7593 0.2720 +vn -0.6475 -0.6794 0.3452 +vn -0.6719 -0.6360 0.3796 +vn -0.5921 -0.7290 -0.3436 +vn -0.5970 -0.7207 -0.3524 +vn -0.6048 -0.7072 -0.3661 +vn -0.6087 -0.7001 -0.3733 +vn -0.1631 -0.5843 -0.7950 +vn -0.0008 1.0000 -0.0020 +vn -0.0005 1.0000 -0.0034 +vn 0.0012 1.0000 -0.0050 +vn -0.0045 1.0000 0.0020 +vn -0.0045 1.0000 -0.0014 +vn -0.0053 1.0000 -0.0008 +vn -0.0046 1.0000 0.0025 +vn -0.0013 1.0000 -0.0022 +vn -0.0007 1.0000 -0.0018 +vn -0.0027 0.9999 0.0141 +vn 0.0098 0.9999 0.0136 +vn 0.0039 0.9998 0.0201 +vn 0.0041 0.9999 -0.0097 +vn 0.0187 0.9997 -0.0151 +vn 0.0175 0.9997 -0.0167 +vn 0.0041 1.0000 0.0032 +vn 0.0092 0.9999 0.0063 +vn -0.0038 1.0000 0.0055 +vn -0.0026 1.0000 0.0032 +vn 0.0048 1.0000 0.0010 +vn -0.0041 0.9999 0.0115 +vn 0.8539 0.1106 0.5086 +vn 0.8537 0.1272 0.5050 +vn 0.8441 -0.0385 0.5348 +vn 0.8414 -0.0578 0.5373 +vn 0.3437 0.0608 0.9371 +vn 0.3436 0.0599 0.9372 +vn 0.3446 0.0671 0.9363 +vn 0.3448 0.0683 0.9362 +vn -0.2859 -0.1775 0.9417 +vn -0.2948 -0.1430 0.9448 +vn -0.3462 0.1055 0.9322 +vn -0.3516 0.1401 0.9256 +vn -0.7776 -0.0989 0.6209 +vn -0.7751 -0.0608 0.6289 +vn -0.7750 -0.2610 0.5755 +vn -0.7734 -0.2784 0.5696 +vn -0.9087 0.4109 0.0729 +vn -0.8765 -0.4507 -0.1693 +vn -0.8481 0.3115 -0.4286 +vn -0.5924 -0.3782 -0.7114 +vn -0.4475 0.3096 -0.8390 +vn -0.0340 -0.2299 -0.9726 +vn -0.0251 -0.1940 -0.9807 +vn 0.0476 0.1050 -0.9933 +vn 0.0577 0.1470 -0.9875 +vn 0.5719 -0.2228 -0.7894 +vn 0.5805 -0.1928 -0.7911 +vn 0.6315 0.0853 -0.7707 +vn 0.6347 0.1255 -0.7625 +vn 0.9776 0.0295 -0.2083 +vn 0.9753 0.0592 -0.2128 +vn 0.9691 -0.1771 -0.1716 +vn 0.9658 -0.1981 -0.1673 +vn 0.0327 0.9937 -0.1068 +vn -0.0157 0.9942 -0.1063 +vn 0.0619 0.9924 -0.1064 +vn 0.0411 0.9985 -0.0363 +vn -0.0323 0.9977 -0.0597 +vn 0.0251 0.9997 0.0057 +vn 0.0264 0.9996 0.0054 +vn 0.0300 0.9992 0.0259 +vn 0.0007 0.9948 0.1017 +vn 0.0397 0.9980 0.0495 +vn -0.0245 0.9994 0.0236 +vn -0.0371 0.9970 0.0676 +vn -0.0188 0.9996 0.0200 +vn -0.0292 0.9992 -0.0260 +vn -0.0170 0.9998 0.0038 +vn 0.2792 0.7894 0.5467 +vn 0.6042 0.6935 0.3925 +vn 0.6289 0.7663 0.1315 +vn 0.1614 0.7988 -0.5795 +vn -0.1056 0.6299 -0.7694 +vn -0.3099 0.7788 -0.5454 +vn -0.6347 0.7502 0.1853 +vn -0.5556 0.6458 0.5238 +vn -0.2126 0.7962 0.5664 +vn 0.0211 0.6546 0.7557 +vn 0.5561 0.7662 -0.3221 +vn 0.4901 0.6591 -0.5704 +vn 0.2293 0.6608 -0.7147 +vn -0.6002 0.7668 -0.2276 +vn -0.7520 0.6406 -0.1554 +vn -0.2638 0.6252 0.7345 +vn 0.4339 0.6243 0.6496 +vn 0.7392 0.6426 -0.2014 +vn -0.3696 0.5927 -0.7156 +vn -0.6261 0.6093 -0.4866 +vn -0.7986 0.5663 0.2040 +vn 0.8007 0.5698 0.1848 +vn 0.0971 0.5473 0.8313 +vn 0.7213 0.5437 -0.4290 +vn -0.8004 0.4754 0.3653 +vn 0.4173 0.5157 0.7483 +vn 0.4382 0.5203 -0.7330 +vn -0.8377 0.4934 -0.2342 +vn -0.4004 0.5057 0.7642 +vn 0.7296 0.5001 0.4664 +vn 0.0350 0.5036 -0.8632 +vn -0.5057 0.4672 -0.7253 +vn 0.8676 0.4971 0.0142 +vn 0.9993 0.0380 -0.0064 +vn 0.9995 0.0318 0.0000 +vn 0.9993 0.0377 -0.0061 +vn 0.9989 0.0442 -0.0128 +vn 0.5398 0.0195 -0.8416 +vn 0.4744 -0.0080 -0.8803 +vn 0.4493 0.0230 -0.8931 +vn 0.6038 -0.0286 -0.7966 +vn 0.3293 -0.0350 -0.9436 +vn -0.4993 0.0458 -0.8652 +vn -0.5294 0.0132 -0.8483 +vn -0.5298 0.0128 -0.8480 +vn -0.5591 -0.0203 -0.8289 +vn -0.9994 0.0359 0.0000 +vn -0.9997 0.0204 0.0159 +vn -0.9997 0.0205 0.0158 +vn -0.9995 0.0048 0.0319 +vn -0.4918 0.0050 0.8707 +vn -0.4923 0.0045 0.8704 +vn -0.4998 -0.0050 0.8661 +vn -0.4846 0.0140 0.8746 +vn 0.4992 0.0461 0.8652 +vn 0.5259 0.0155 0.8504 +vn 0.5272 0.0140 0.8496 +vn 0.5520 -0.0156 0.8337 +vn -0.9803 -0.1594 0.1164 +vn -0.9766 -0.1837 0.1116 +vn -0.9825 0.0929 0.1612 +vn -0.9789 0.1201 0.1654 +vn -0.6349 -0.1105 0.7646 +vn -0.6385 -0.1525 0.7544 +vn -0.5767 0.1862 0.7954 +vn -0.5661 0.2210 0.7942 +vn -0.0297 -0.2245 0.9740 +vn -0.0377 -0.2623 0.9642 +vn 0.0408 0.1153 0.9925 +vn 0.0516 0.1680 0.9844 +vn 0.6514 0.0672 0.7558 +vn 0.6631 0.0004 0.7485 +vn 0.6746 -0.3320 0.6593 +vn 0.6713 -0.3644 0.6455 +vn 0.8992 0.3840 0.2099 +vn 0.8407 -0.5397 -0.0454 +vn 0.7602 0.4987 -0.4164 +vn 0.5709 -0.4003 -0.7168 +vn 0.3807 0.3450 -0.8579 +vn -0.0014 -0.4444 -0.8958 +vn -0.2754 0.4452 -0.8520 +vn -0.6401 -0.4465 -0.6252 +vn -0.7934 0.2608 -0.5501 +vn 0.7704 0.0348 -0.6366 +vn 0.8812 -0.0708 -0.4673 +vn 0.6494 -0.0242 -0.7600 +vn 0.2900 0.0613 -0.9551 +vn -0.0188 -0.0236 -0.9995 +vn -0.2399 0.0248 -0.9705 +vn -0.3603 -0.0477 -0.9316 +vn -0.9536 0.0363 -0.2988 +vn -0.9585 0.0239 -0.2840 +vn -0.9574 0.0268 -0.2875 +vn -0.9624 0.0132 -0.2713 +vn -0.7789 0.0306 0.6264 +vn -0.8406 -0.0268 0.5409 +vn -0.8053 0.0074 0.5929 +vn -0.7437 0.0592 0.6659 +vn -0.0338 0.0432 0.9985 +vn -0.2726 -0.0648 0.9600 +vn -0.1304 -0.0000 0.9915 +vn 0.0956 0.1000 0.9904 +vn 0.5675 -0.0856 0.8189 +vn 0.9275 0.0930 0.3622 +vn 0.9502 0.0533 0.3070 +vn 0.9419 0.0688 0.3288 +vn 0.9663 0.0177 0.2567 +vn -0.0016 1.0000 -0.0036 +vn -0.0218 0.9876 -0.1553 +vn -0.0530 0.9945 -0.0902 +vn -0.0922 0.9934 -0.0687 +vn -0.1051 0.9923 -0.0649 +vn 0.0172 0.9919 -0.1256 +vn -0.0806 0.9967 -0.0020 +vn -0.0841 0.9962 0.0244 +vn 0.0988 0.9951 -0.0015 +vn 0.0602 0.9978 -0.0280 +vn 0.0443 0.9966 -0.0700 +vn 0.0433 0.9959 -0.0794 +vn -0.0593 0.9969 0.0523 +vn -0.0514 0.9970 0.0579 +vn 0.0673 0.9959 0.0609 +vn 0.0435 0.9964 0.0731 +vn 0.0684 0.9974 0.0240 +vn 0.0147 0.9957 0.0915 +vn -0.0117 0.9975 0.0692 +vn -0.8626 0.0664 -0.5015 +vn -0.9685 0.0176 -0.2485 +vn -0.9977 0.0626 -0.0266 +vn -0.7819 0.0295 -0.6227 +vn -0.6940 0.0549 -0.7178 +vn -0.6543 0.0249 -0.7558 +vn -0.1909 0.0518 -0.9802 +vn -0.1837 0.0458 -0.9819 +vn 0.0900 0.0532 -0.9945 +vn -0.0004 0.0335 -0.9994 +vn 0.4683 0.0201 -0.8834 +vn 0.5980 0.0693 -0.7985 +vn 0.8362 0.0246 -0.5479 +vn 0.8885 0.0673 -0.4540 +vn 0.9631 -0.0952 -0.2516 +vn 0.9991 0.0371 -0.0227 +vn 0.9670 -0.0008 0.2549 +vn 0.8938 0.0561 0.4450 +vn 0.7568 0.0165 0.6535 +vn 0.6332 0.0556 0.7720 +vn 0.4084 0.0102 0.9127 +vn 0.2014 0.0534 0.9780 +vn 0.0151 0.0199 0.9997 +vn -0.2426 0.0609 0.9682 +vn -0.2685 0.0412 0.9624 +vn -0.5637 0.0552 0.8241 +vn -0.7008 0.2216 0.6781 +vn -0.8586 0.0515 0.5101 +vn -0.8240 -0.2190 0.5225 +vn -0.9700 -0.0176 0.2426 +vn -0.0273 0.9996 -0.0101 +vn -0.0179 0.9997 -0.0151 +vn -0.0053 0.9999 -0.0111 +vn -0.0020 0.9999 -0.0103 +vn 0.0001 0.9999 -0.0102 +vn 0.0009 0.9999 -0.0112 +vn 0.0126 0.9996 -0.0251 +vn 0.1591 0.9746 -0.1577 +vn 0.0467 0.9982 -0.0383 +vn 0.0253 0.9997 0.0031 +vn 0.0173 0.9998 0.0087 +vn -0.0356 0.9993 0.0114 +vn -0.0136 0.9996 0.0264 +vn 0.0022 0.9996 0.0298 +vn -0.0149 0.9997 0.0192 +vn -0.0229 0.9995 0.0212 +vn 0.0122 0.9999 0.0079 +vn 0.0131 0.9998 0.0126 +vn 0.0194 0.9998 0.0066 +vn 0.0145 0.9998 0.0164 +vn 0.8464 0.4265 0.3188 +vn 0.6350 0.6820 0.3628 +vn 0.8606 0.3965 0.3197 +vn 0.1327 0.6043 0.7856 +vn 0.2562 0.8173 0.5161 +vn 0.1725 0.6783 0.7142 +vn 0.0596 0.7974 -0.6004 +vn -0.3087 0.8155 -0.4895 +vn -0.2202 0.7002 -0.6792 +vn 0.9268 -0.2084 -0.3125 +vn 0.1336 0.8345 -0.5346 +vn -0.0821 0.7040 -0.7055 +vn -0.3427 0.8525 -0.3947 +vn -0.7909 -0.2770 -0.5457 +vn -0.7371 0.5304 -0.4188 +vn -0.8029 0.5738 -0.1617 +vn -0.7947 0.5687 -0.2123 +vn 0.6226 0.4255 0.6568 +vn 0.6326 0.5092 0.5835 +vn 0.3851 0.8587 -0.3381 +vn 0.3871 0.2989 -0.8723 +vn -0.8140 0.5789 0.0478 +vn -0.7451 -0.4735 0.4696 +vn -0.7111 0.4342 0.5530 +vn -0.2498 0.8674 0.4305 +vn -0.1758 0.0508 0.9831 +vn 0.2784 0.8490 0.4491 +vn 0.5131 0.8580 0.0250 +vn 0.1481 0.7634 0.6287 +vn -0.5210 0.8111 0.2659 +vn 0.6078 0.7941 0.0080 +vn 0.9666 0.0094 -0.2562 +vn 0.9389 -0.0158 -0.3438 +vn 0.9614 -0.0211 -0.2742 +vn 0.9782 -0.0154 -0.2071 +vn 0.9616 0.0389 0.2718 +vn 0.9844 0.0170 0.1754 +vn 0.9557 -0.0301 0.2929 +vn 0.9911 0.0056 0.1330 +vn 0.6169 -0.0242 -0.7867 +vn 0.7974 0.0561 -0.6009 +vn 0.9614 -0.0060 -0.2752 +vn 0.3953 -0.0419 -0.9176 +vn 0.3006 -0.1408 -0.9433 +vn -0.2967 0.1315 -0.9459 +vn -0.3626 0.0496 -0.9306 +vn -0.4143 -0.0190 -0.9099 +vn -0.4753 -0.1059 -0.8734 +vn -0.9005 0.1001 -0.4232 +vn -0.9362 0.0095 -0.3512 +vn -0.9930 0.0056 -0.1183 +vn -0.9845 -0.0225 0.1742 +vn -0.9119 0.0175 0.4101 +vn -0.9649 -0.0022 0.2625 +vn -0.9694 0.0067 0.2455 +vn -0.9581 -0.0076 -0.2864 +vn -0.9763 -0.0053 -0.2164 +vn -0.9610 -0.0128 -0.2762 +vn -0.9582 -0.0051 -0.2861 +vn -0.9991 -0.0042 -0.0428 +vn -0.9992 -0.0008 -0.0402 +vn -0.7896 0.0237 0.6132 +vn -0.7811 0.0052 0.6244 +vn -0.7770 -0.0035 0.6295 +vn -0.7679 -0.0220 0.6402 +vn -0.1716 0.0206 0.9850 +vn -0.1841 0.0028 0.9829 +vn -0.1644 0.0307 0.9859 +vn -0.1531 0.0466 0.9871 +vn 0.5842 0.0209 0.8113 +vn 0.5243 -0.0580 0.8495 +vn 0.7323 0.0038 0.6810 +vn 0.9040 0.0514 0.4244 +vn 0.9920 -0.0088 0.1260 +vn -0.0101 0.0698 -0.9975 +vn -0.0558 0.0566 -0.9968 +vn -0.0201 0.1027 -0.9945 +vn -0.0890 0.0101 -0.9960 +vn -0.0650 0.0103 -0.9978 +vn -0.0253 -0.0899 -0.9956 +vn -0.0470 -0.0382 -0.9982 +vn 0.0015 -0.0613 -0.9981 +vn 0.0596 0.0205 -0.9980 +vn 0.0673 -0.0280 -0.9973 +vn 0.0629 -0.0038 -0.9980 +vn 0.0248 0.0427 -0.9988 +vn 0.0224 -0.0541 -0.9983 +vn 0.0398 -0.0897 0.9952 +vn 0.1508 -0.0605 0.9867 +vn 0.2125 -0.0433 0.9762 +vn 0.0395 -0.0904 0.9951 +vn -0.9325 0.3566 0.0573 +vn -0.8061 0.5918 -0.0050 +vn -0.9407 0.3308 0.0747 +vn -0.9129 -0.4080 -0.0136 +vn -0.4623 -0.8863 0.0267 +vn -0.2458 -0.9693 0.0054 +vn -0.4411 -0.8971 0.0246 +vn -0.2236 -0.9747 0.0033 +vn 0.4170 -0.9084 0.0283 +vn 0.5968 -0.8022 0.0149 +vn 0.4293 -0.9028 0.0275 +vn 0.6068 -0.7947 0.0141 +vn 0.9471 -0.3196 0.0296 +vn 0.9989 0.0430 -0.0161 +vn 0.9585 -0.2839 0.0251 +vn 0.9967 0.0780 -0.0204 +vn 0.3834 0.9234 0.0167 +vn 0.2499 0.9682 0.0092 +vn 0.3709 0.9285 0.0163 +vn 0.2293 0.9733 0.0055 +vn -0.7816 0.6237 -0.0108 +vn 0.1122 -0.0667 0.9914 +vn 0.0625 -0.0897 0.9940 +vn 0.1266 -0.0229 0.9917 +vn -0.0296 0.1174 0.9926 +vn -0.0690 0.1076 0.9918 +vn -0.1405 0.0226 0.9898 +vn -0.1607 0.0159 0.9869 +vn 0.1529 -0.2245 0.9624 +vn -0.0037 -0.1323 0.9912 +vn -0.0679 -0.0952 0.9931 +vn -0.0925 -0.0783 0.9926 +vn 0.0954 0.0809 0.9921 +vn 0.1273 0.0593 0.9901 +vn 0.0437 0.1324 0.9902 +vn -0.9049 0.4252 0.0195 +vn -0.8963 0.4422 0.0332 +vn -0.8576 0.5069 0.0868 +vn -0.9373 0.3461 -0.0418 +vn -0.9299 -0.3672 0.0206 +vn -0.9307 -0.3653 0.0193 +vn -0.9302 -0.3664 0.0201 +vn -0.9296 -0.3681 0.0213 +vn -0.5794 -0.8149 -0.0177 +vn -0.5371 -0.8434 0.0120 +vn -0.5114 -0.8589 0.0294 +vn -0.4703 -0.8807 0.0563 +vn 0.0760 -0.9954 -0.0580 +vn 0.4114 -0.9108 -0.0338 +vn 0.2602 -0.9653 0.0205 +vn 0.6217 -0.7827 0.0295 +vn 0.7465 -0.6651 -0.0194 +vn 0.8281 -0.5585 0.0481 +vn 0.9986 0.0250 -0.0473 +vn 0.9964 0.0830 -0.0143 +vn 0.9929 0.1188 0.0062 +vn 0.9835 0.1766 0.0395 +vn 0.7083 0.7058 0.0125 +vn 0.7662 0.6419 -0.0297 +vn 0.5467 0.8370 -0.0226 +vn 0.3470 0.9366 0.0482 +vn -0.0583 0.9981 -0.0178 +vn -0.1981 0.9797 0.0302 +vn -0.3977 0.9145 -0.0740 +vn -0.7275 0.6861 0.0000 +vn -0.6745 0.7350 -0.0695 +vn -0.6762 0.7336 -0.0674 +vn -0.6217 0.7722 -0.1307 +vn -0.7033 -0.6988 0.1305 +vn -0.7531 -0.6545 0.0673 +vn -0.7515 -0.6560 0.0694 +vn -0.7988 -0.6017 0.0000 +vn 0.7275 -0.6861 0.0000 +vn 0.6745 -0.7350 -0.0695 +vn 0.6762 -0.7336 -0.0674 +vn 0.6217 -0.7722 -0.1307 +vn 0.7033 0.6988 0.1305 +vn 0.7531 0.6545 0.0673 +vn 0.7515 0.6560 0.0694 +vn 0.7988 0.6017 0.0000 +vn -0.2187 0.3613 0.9064 +vn 0.3828 0.9226 -0.0475 +vn 0.4428 0.0236 0.8963 +vn -0.3763 -0.3934 0.8388 +vn -0.9288 0.3256 0.1771 +vn -0.0726 -0.0247 -0.9971 +vn -0.0605 0.0163 -0.9980 +vn -0.0398 -0.0325 -0.9987 +vn -0.0251 -0.0623 -0.9977 +vn 0.0557 -0.0444 -0.9975 +vn 0.0144 -0.0587 -0.9982 +vn 0.0481 -0.0156 -0.9987 +vn 0.0400 0.0460 -0.9981 +vn -0.0100 0.0532 -0.9985 +vn 0.0012 0.0798 -0.9968 +vn -0.0513 0.0508 -0.9974 +vn 0.0575 0.0207 -0.9981 +vn -0.1001 -0.1754 0.9794 +vn -0.1083 -0.1923 0.9754 +vn -0.0158 -0.0017 0.9999 +vn -0.9012 -0.4331 0.0138 +vn -0.9017 -0.4321 0.0140 +vn -0.8956 -0.4397 0.0679 +vn -0.1774 -0.9841 -0.0086 +vn 0.2601 -0.9656 -0.0073 +vn 0.2393 -0.9677 0.0797 +vn 0.2851 -0.9526 0.1059 +vn 0.6490 -0.7607 -0.0092 +vn 0.9988 -0.0476 0.0118 +vn 0.9990 -0.0426 0.0124 +vn 0.9998 0.0003 0.0182 +vn 0.9998 0.0039 0.0187 +vn 0.4698 0.8763 0.1067 +vn 0.5723 0.8200 -0.0080 +vn 0.5633 0.8262 -0.0066 +vn 0.4599 0.8780 0.1326 +vn -0.6021 0.7984 0.0037 +vn -0.6337 0.7736 -0.0033 +vn -0.6063 0.7952 0.0028 +vn -0.6373 0.7706 -0.0041 +vn -0.8926 -0.4392 0.1017 +vn -0.0777 -0.1129 0.9906 +vn -0.1163 -0.0703 0.9907 +vn -0.0030 -0.1327 0.9912 +vn -0.1348 0.0278 0.9905 +vn 0.1275 -0.0448 0.9908 +vn 0.1166 -0.0639 0.9911 +vn 0.1188 0.0724 0.9903 +vn 0.1470 0.0400 0.9883 +vn 0.0467 -0.1269 0.9908 +vn -0.1346 0.0650 0.9888 +vn 0.0097 0.1266 0.9919 +vn -0.0198 0.1242 0.9921 +vn -0.7507 -0.6593 -0.0416 +vn -0.4722 -0.8814 -0.0151 +vn -0.6041 -0.7942 0.0650 +vn -0.3668 -0.9295 0.0373 +vn -0.0978 -0.9905 -0.0965 +vn 0.5130 -0.8545 0.0813 +vn 0.5536 -0.8314 0.0472 +vn 0.5433 -0.8377 0.0561 +vn 0.5905 -0.8069 0.0146 +vn 0.9783 -0.2054 -0.0293 +vn 0.9928 -0.1153 0.0319 +vn 0.9947 -0.0915 0.0479 +vn 0.9951 -0.0159 0.0980 +vn 0.8521 0.5150 -0.0929 +vn 0.4359 0.8925 0.1163 +vn 0.3778 0.9235 0.0658 +vn 0.3900 0.9176 0.0763 +vn 0.3118 0.9501 0.0105 +vn -0.3615 0.9306 -0.0566 +vn -0.6334 0.7738 -0.0066 +vn -0.5437 0.8377 0.0511 +vn -0.7140 0.6983 0.0503 +vn -0.8402 0.5399 -0.0509 +vn -0.9956 -0.0691 0.0635 +vn -0.9927 -0.1163 0.0307 +vn -0.9942 -0.0991 0.0427 +vn -0.9881 -0.1538 0.0044 +vn -0.7484 -0.6451 0.1542 +vn -0.8481 -0.5293 -0.0246 +vn -0.8254 -0.5641 0.0244 +vn -0.8913 -0.4263 -0.1544 +vn 0.9328 -0.3257 0.1540 +vn 0.8825 -0.4697 -0.0245 +vn 0.9012 -0.4327 0.0245 +vn 0.8150 -0.5586 -0.1540 +vn -0.1845 0.9706 0.1544 +vn -0.0343 0.9991 -0.0245 +vn -0.0758 0.9968 0.0246 +vn 0.0766 0.9851 -0.1543 +vn -0.8515 -0.4194 0.3147 +vn -0.3631 0.4546 0.8133 +vn -0.3608 0.4409 0.8218 +vn -0.3670 0.4783 0.7978 +vn -0.3691 0.4923 0.7883 +vn 0.4297 0.8155 0.3876 +vn 0.5366 0.0423 0.8427 +vn 0.5139 0.0548 0.8561 +vn 0.5740 0.0211 0.8186 +vn 0.6021 0.0046 0.7984 +vn 0.2546 -0.9242 0.2847 +vn -0.2076 -0.3986 0.8933 +vn 0.0283 -0.0809 -0.9963 +vn 0.0233 -0.0863 -0.9960 +vn -0.0074 -0.0670 -0.9977 +vn -0.0281 -0.0533 -0.9982 +vn 0.0062 0.0609 -0.9981 +vn -0.0236 0.0778 -0.9967 +vn 0.0241 0.0538 -0.9983 +vn -0.0447 -0.0247 -0.9987 +vn -0.0439 -0.0218 -0.9988 +vn 0.0379 0.0173 -0.9991 +vn 0.0360 0.0110 -0.9993 +vn -0.0269 0.0729 -0.9970 +vn 0.0181 0.2162 0.9762 +vn -0.3631 0.0653 0.9295 +vn -0.1950 -0.0948 0.9762 +vn 0.8771 -0.4795 0.0291 +vn 0.8335 -0.5523 0.0165 +vn 0.8809 -0.4722 0.0303 +vn 0.9596 0.2810 -0.0155 +vn 0.5502 0.8188 0.1639 +vn 0.4591 0.8879 0.0289 +vn 0.4706 0.8819 0.0267 +vn 0.5610 0.8221 0.0971 +vn -0.4837 0.8749 0.0215 +vn -0.3036 0.9528 0.0068 +vn -0.3195 0.9475 0.0081 +vn -0.4930 0.8698 0.0222 +vn -0.8738 0.4860 -0.0143 +vn -0.9990 -0.0372 0.0245 +vn -0.8796 -0.4755 -0.0124 +vn -0.9964 -0.0817 0.0211 +vn -0.8583 -0.5130 -0.0158 +vn -0.3450 -0.9332 0.1008 +vn 0.0297 -0.9995 -0.0084 +vn -0.3212 -0.9365 0.1405 +vn 0.0722 -0.9973 -0.0130 +vn 0.8262 -0.5631 0.0146 +vn 0.1281 -0.0217 0.9915 +vn 0.1101 -0.0835 0.9904 +vn 0.1374 0.0096 0.9905 +vn 0.0674 -0.1067 0.9920 +vn 0.0250 0.1233 0.9921 +vn -0.1004 0.0946 0.9904 +vn -0.0027 0.1354 0.9908 +vn -0.0601 0.1453 0.9876 +vn 0.1002 0.0834 0.9915 +vn 0.1111 0.0915 0.9896 +vn 0.0291 -0.1268 0.9915 +vn -0.1581 -0.0003 0.9874 +vn -0.1468 -0.0387 0.9884 +vn -0.0722 -0.1067 0.9917 +vn -0.0611 -0.1043 0.9927 +vn 0.7947 -0.6067 0.0189 +vn 0.8785 -0.4765 -0.0337 +vn 0.9657 -0.2595 -0.0081 +vn 0.9754 -0.2183 -0.0320 +vn 0.9291 0.3655 0.0572 +vn 0.8235 0.5652 -0.0489 +vn 0.7635 0.6457 0.0140 +vn 0.6766 0.7351 -0.0440 +vn 0.5140 0.8556 0.0618 +vn -0.2527 0.9664 -0.0474 +vn -0.1878 0.9819 0.0229 +vn -0.1987 0.9800 0.0113 +vn -0.1283 0.9880 0.0856 +vn -0.9319 0.3621 0.0199 +vn -0.7495 0.6576 -0.0764 +vn -0.9122 0.4096 -0.0132 +vn -0.9750 0.2189 0.0371 +vn -0.9832 0.1824 0.0092 +vn -0.7626 -0.6465 -0.0243 +vn -0.7652 -0.6432 -0.0280 +vn -0.7632 -0.6457 -0.0252 +vn -0.7603 -0.6493 -0.0212 +vn -0.1612 -0.9854 0.0555 +vn -0.0269 -0.9995 -0.0192 +vn 0.1750 -0.9841 0.0316 +vn 0.4100 -0.9115 -0.0336 +vn 0.0555 -0.8337 -0.5494 +vn 0.7449 0.6524 0.1392 +vn 0.7699 0.6325 0.0846 +vn 0.7630 0.6386 0.1004 +vn 0.7987 0.6016 0.0103 +vn -0.0174 0.8234 -0.5673 +vn -0.7617 -0.6321 0.1427 +vn -0.7776 -0.6195 0.1076 +vn -0.7731 -0.6233 0.1179 +vn -0.7974 -0.6006 0.0593 +vn -0.3255 -0.8735 0.3620 +vn -0.4925 -0.1665 0.8542 +vn -0.7683 -0.0271 0.6395 +vn -0.4200 0.7385 0.5275 +vn 0.0271 0.4802 0.8767 +vn 0.4984 0.7372 0.4562 +vn 0.5624 -0.2892 0.7747 +vn 0.5564 -0.2813 0.7818 +vn 0.5745 -0.3055 0.7594 +vn 0.5788 -0.3114 0.7537 +vn 0.0551 0.0357 -0.9978 +vn 0.0856 -0.0197 -0.9961 +vn 0.0663 0.0007 -0.9978 +vn -0.0118 0.0644 -0.9979 +vn 0.0175 0.0719 -0.9973 +vn -0.0071 -0.0721 -0.9974 +vn -0.0493 -0.0498 -0.9975 +vn 0.0089 -0.0594 -0.9982 +vn 0.0533 -0.0521 -0.9972 +vn -0.0593 -0.0101 -0.9982 +vn -0.0645 0.0122 -0.9978 +vn -0.0420 0.0671 -0.9969 +vn 0.0911 0.1976 0.9760 +vn 0.0611 0.0946 0.9936 +vn 0.1244 0.2205 0.9674 +vn 0.0125 0.0506 0.9986 +vn 0.9420 0.3340 0.0332 +vn 0.9659 0.2588 0.0113 +vn 0.7331 0.6793 0.0317 +vn 0.2841 0.9587 -0.0123 +vn -0.3049 0.9521 0.0245 +vn -0.5836 0.8120 0.0093 +vn -0.6112 0.7910 0.0284 +vn -0.6223 0.7828 0.0100 +vn -0.8368 0.5466 0.0308 +vn -0.9982 -0.0571 -0.0171 +vn -0.7849 -0.6076 0.1210 +vn -0.7905 -0.6118 0.0284 +vn -0.7854 -0.6080 0.1164 +vn -0.3458 -0.9382 -0.0146 +vn 0.1986 -0.9797 0.0268 +vn 0.6759 -0.7367 -0.0228 +vn 0.9981 -0.0525 0.0317 +vn 0.9794 0.2017 0.0115 +vn -0.1126 0.0624 0.9917 +vn -0.1120 0.0810 0.9904 +vn -0.1278 -0.0251 0.9915 +vn 0.1212 0.0866 0.9888 +vn 0.1162 0.0156 0.9931 +vn 0.0531 0.1226 0.9910 +vn -0.1017 -0.0806 0.9915 +vn -0.0300 0.1331 0.9906 +vn -0.0543 0.1355 0.9893 +vn -0.0554 -0.1248 0.9906 +vn 0.0241 -0.1336 0.9907 +vn 0.0443 -0.1382 0.9894 +vn 0.1123 -0.0721 0.9911 +vn 0.3045 0.0398 0.9517 +vn 0.8351 0.5494 -0.0282 +vn 0.7212 0.6921 0.0294 +vn 0.9775 0.2041 0.0532 +vn 0.5829 0.8095 -0.0700 +vn 0.0062 0.9982 0.0601 +vn -0.0988 0.9951 0.0000 +vn -0.0619 0.9979 0.0212 +vn -0.1700 0.9846 -0.0412 +vn -0.6379 0.7692 0.0374 +vn -0.7519 0.6583 -0.0361 +vn -0.8498 0.5260 0.0347 +vn -0.8889 0.4580 -0.0098 +vn -0.9763 0.1932 0.0975 +vn -0.8710 -0.4913 0.0048 +vn -0.9428 -0.3190 -0.0972 +vn -0.8933 -0.4490 -0.0215 +vn -0.7867 -0.6115 0.0851 +vn -0.1960 -0.9804 0.0182 +vn -0.3810 -0.9220 -0.0694 +vn -0.0263 -0.9990 -0.0360 +vn 0.3090 -0.9501 0.0413 +vn 0.6291 -0.7766 -0.0347 +vn 0.8502 -0.5247 0.0429 +vn 0.9833 -0.1786 -0.0345 +vn 0.6217 0.7722 0.1307 +vn 0.6762 0.7336 0.0674 +vn 0.6745 0.7350 0.0695 +vn 0.7275 0.6861 0.0000 +vn -0.7988 0.6017 0.0000 +vn -0.7515 0.6560 -0.0694 +vn -0.7531 0.6545 -0.0673 +vn -0.7033 0.6988 -0.1305 +vn -0.6217 -0.7722 0.1307 +vn -0.6762 -0.7336 0.0674 +vn -0.6745 -0.7350 0.0695 +vn -0.7275 -0.6861 0.0000 +vn 0.7988 -0.6017 0.0000 +vn 0.7515 -0.6560 -0.0694 +vn 0.7531 -0.6545 -0.0673 +vn 0.7033 -0.6988 -0.1305 +vn 0.7495 -0.1529 0.6442 +vn 0.0426 -0.6692 0.7418 +vn 0.0088 -0.7468 0.6649 +vn 0.0787 -0.5753 0.8141 +vn 0.1003 -0.5132 0.8524 +vn -0.7427 -0.5755 0.3424 +vn -0.5766 0.1119 0.8094 +vn 0.1826 0.4385 0.8800 +vn 0.6698 -0.7120 -0.2109 +vn 0.6777 0.5416 -0.4973 +vn 0.3741 -0.4234 -0.8251 +vn 0.1049 0.5324 -0.8400 +vn -0.2424 -0.6163 -0.7493 +vn -0.5277 0.7121 -0.4631 +vn -0.7557 -0.5727 -0.3177 +vn -0.8369 0.4523 0.3083 +vn -0.8461 0.4291 0.3162 +vn -0.9124 0.0535 0.4059 +vn -0.9107 0.0032 0.4131 +vn -0.2375 -0.1034 0.9659 +vn -0.2374 -0.1022 0.9660 +vn -0.2388 -0.1159 0.9641 +vn -0.2391 -0.1179 0.9638 +vn 0.4553 0.2888 0.8422 +vn 0.4921 -0.6955 0.5235 +vn 0.6570 0.7215 0.2185 +vn -0.7115 -0.6160 0.3379 +vn -0.4963 0.7670 0.4066 +vn -0.2920 -0.6835 0.6690 +vn -0.0940 0.6489 0.7551 +vn 0.1991 -0.6907 0.6952 +vn 0.3995 0.6349 0.6613 +vn 0.7676 -0.4716 0.4341 +vn 0.8822 0.2575 0.3942 +vn 0.9201 -0.3749 -0.1137 +vn 0.7012 0.6770 -0.2236 +vn 0.6122 -0.6337 -0.4730 +vn 0.3480 0.6065 -0.7148 +vn 0.2782 -0.3941 -0.8759 +vn -0.1900 0.3451 -0.9191 +vn -0.2996 -0.4830 -0.8228 +vn -0.5429 0.5199 -0.6595 +vn -0.6639 -0.5815 -0.4702 +vn -0.7687 0.6253 -0.1346 +vn -0.9835 0.1504 -0.1009 +vn -0.0092 -0.9999 0.0117 +vn -0.0103 -0.9999 0.0000 +vn -0.0308 -0.9994 0.0180 +vn -0.0240 -0.9993 0.0293 +vn -0.0191 -0.9996 -0.0214 +vn -0.9725 0.1579 -0.1714 +vn -0.9692 0.1808 -0.1672 +vn -0.9780 -0.0464 -0.2034 +vn -0.9754 -0.0756 -0.2073 +vn -0.5765 -0.2299 -0.7841 +vn -0.3047 0.6893 -0.6573 +vn 0.1612 -0.7364 -0.6570 +vn 0.4425 0.7281 -0.5235 +vn 0.7405 -0.5823 -0.3355 +vn 0.8476 0.5294 0.0353 +vn 0.8104 -0.4954 0.3129 +vn 0.6111 0.4709 0.6362 +vn 0.2602 -0.6445 0.7189 +vn 0.0088 0.6402 0.7682 +vn -0.5683 -0.5989 0.5643 +vn -0.7825 0.0827 0.6172 +vn -0.0165 0.9990 0.0425 +vn -0.0347 0.9992 0.0176 +vn -0.0654 0.9944 0.0831 +vn -0.0341 0.9994 -0.0038 +vn 0.8474 -0.5304 0.0257 +vn 0.7975 0.5752 0.1823 +vn 0.6735 -0.5553 0.4879 +vn 0.4754 0.6713 0.5687 +vn 0.2141 -0.6607 0.7195 +vn -0.0566 0.5966 0.8005 +vn -0.2089 -0.2151 0.9540 +vn -0.6584 0.1724 0.7326 +vn -0.5957 -0.7883 0.1540 +vn -0.6981 0.7066 -0.1152 +vn -0.6136 -0.6471 -0.4526 +vn -0.6928 0.2883 -0.6610 +vn -0.1330 -0.3901 -0.9111 +vn -0.0711 0.2531 -0.9648 +vn 0.4708 -0.0812 -0.8785 +vn 0.4716 -0.0927 -0.8769 +vn 0.4641 -0.0016 -0.8858 +vn 0.4632 0.0067 -0.8862 +vn 0.8474 -0.0820 -0.5246 +vn 0.8517 -0.0456 -0.5220 +vn 0.8153 0.3771 -0.4394 +vn 0.8092 0.3973 -0.4329 +vn 0.0919 0.4078 0.9084 +vn 0.1411 0.2869 0.9475 +vn 0.3457 0.4782 0.8073 +vn 0.5304 0.4335 0.7286 +vn 0.4623 0.4273 0.7770 +vn 0.5543 0.3078 0.7733 +vn 0.0380 0.2204 0.9747 +vn -0.0341 0.2551 0.9663 +vn -0.1710 0.5199 0.8369 +vn -0.0239 0.7679 0.6401 +vn -0.1082 0.7542 0.6477 +vn -0.0232 0.7705 0.6370 +vn 0.5708 0.7360 0.3641 +vn 0.5849 0.7575 0.2898 +vn 0.2314 0.9653 0.1214 +vn 0.4197 0.8937 0.1586 +vn 0.5768 0.8122 0.0871 +vn 0.3203 0.9466 0.0375 +vn 0.5755 0.8093 -0.1172 +vn 0.5676 0.8148 -0.1176 +vn 0.5843 0.7389 -0.3356 +vn 0.5695 0.7766 -0.2693 +vn 0.5672 0.7600 -0.3173 +vn 0.5696 0.7140 -0.4072 +vn 0.5568 0.6458 -0.5224 +vn 0.6639 0.5146 -0.5426 +vn 0.5822 0.4238 -0.6938 +vn 0.5220 0.4584 -0.7193 +vn 0.5314 0.3715 -0.7613 +vn 0.5972 0.3022 -0.7430 +vn 0.5816 0.3182 0.7487 +vn 0.5885 0.1806 0.7881 +vn 0.7216 0.4179 0.5519 +vn 0.6839 0.4250 0.5929 +vn 0.2704 0.7896 0.5509 +vn 0.5889 0.6909 0.4195 +vn 0.1046 0.7039 0.7025 +vn -0.0062 0.9891 -0.1470 +vn -0.0033 0.9935 0.1142 +vn 0.2689 0.9630 0.0157 +vn 0.2881 0.9106 0.2964 +vn -0.0038 0.9307 0.3658 +vn 0.2469 0.7939 0.5556 +vn 0.2778 0.5941 0.7549 +vn -0.0055 0.3871 0.9220 +vn 0.2803 0.3019 0.9112 +vn 0.0383 0.0117 0.9992 +vn 0.2701 -0.0199 0.9626 +vn 0.2769 -0.3419 0.8980 +vn 0.2809 -0.2732 0.9200 +vn -0.0027 -0.5161 0.8565 +vn 0.2747 -0.6411 0.7166 +vn 0.0003 -0.7049 0.7093 +vn -0.0028 -0.8974 0.4413 +vn 0.2498 -0.8524 0.4593 +vn 0.2586 -0.9575 0.1277 +vn -0.0115 -0.9999 0.0093 +vn 0.2652 -0.9315 -0.2491 +vn -0.0085 -0.9171 -0.3986 +vn 0.2339 -0.8036 -0.5472 +vn -0.0029 -0.7550 -0.6557 +vn 0.2770 -0.5717 -0.7723 +vn 0.0008 -0.5486 -0.8361 +vn 0.2797 -0.2442 -0.9285 +vn 0.2789 -0.2782 -0.9191 +vn -0.0008 -0.0300 -0.9995 +vn 0.3196 0.1447 -0.9364 +vn -0.0199 0.1182 -0.9928 +vn 0.2198 0.4713 -0.8542 +vn -0.0049 0.5373 -0.8434 +vn 0.2942 0.6978 -0.6530 +vn -0.0016 0.7625 -0.6470 +vn -0.0033 0.9058 -0.4236 +vn 0.2797 0.9011 -0.3314 +vn -0.0398 -0.0109 -0.9991 +vn -0.0391 -0.0206 -0.9990 +vn -0.0424 -0.0002 -0.9991 +vn -0.0488 -0.0009 -0.9988 +vn -0.2003 -0.0023 -0.9797 +vn -0.2000 0.1319 -0.9709 +vn 0.0533 0.2394 -0.9695 +vn 0.1674 0.2813 -0.9449 +vn -0.0356 -0.0045 -0.9994 +vn -0.2618 0.1323 0.9560 +vn -0.0445 0.0016 0.9990 +vn -0.0383 0.0022 0.9993 +vn -0.2091 0.0064 0.9779 +vn -0.1711 -0.1306 0.9766 +vn -0.0412 -0.0006 0.9992 +vn -0.0745 -0.0293 0.9968 +vn 0.0401 -0.2144 0.9759 +vn -0.0406 0.0071 0.9992 +vn -0.0454 -0.0014 0.9990 +vn -0.0928 -0.0583 0.9940 +vn 0.6054 -0.4011 0.6874 +vn 0.5447 -0.4302 0.7199 +vn 0.4945 -0.4154 0.7635 +vn 0.5437 -0.3604 -0.7580 +vn 0.4926 -0.4836 -0.7235 +vn 0.5452 -0.4503 -0.7071 +vn -0.2052 -0.0103 0.9787 +vn -0.5763 -0.0104 0.8172 +vn -0.6947 0.1317 0.7072 +vn -0.8678 -0.0139 0.4967 +vn -0.9551 0.1353 0.2636 +vn -0.9943 -0.0086 0.1064 +vn -0.9635 0.1330 -0.2326 +vn -0.9626 -0.0132 -0.2705 +vn -0.8083 -0.0014 -0.5888 +vn -0.7959 0.1271 -0.5919 +vn -0.5354 0.1288 -0.8347 +vn -0.5255 -0.0026 -0.8508 +vn -0.9506 -0.0111 0.3103 +vn -0.9896 -0.0030 0.1438 +vn -0.9483 -0.0053 0.3174 +vn -0.9882 -0.0017 0.1530 +vn -0.9443 -0.0134 -0.3289 +vn -0.9846 -0.0045 -0.1750 +vn -0.9479 -0.0049 -0.3184 +vn -0.9846 0.0014 -0.1748 +vn 0.5040 -0.8580 0.0988 +vn 0.4954 -0.7399 0.4551 +vn 0.4572 -0.4844 0.7459 +vn 0.4611 -0.1769 0.8695 +vn 0.4654 0.1295 0.8756 +vn 0.4668 0.4423 0.7658 +vn 0.5059 0.7251 0.4672 +vn 0.4984 0.8557 0.1390 +vn 0.4572 0.8754 -0.1568 +vn 0.4387 0.7514 -0.4929 +vn 0.4722 0.3876 -0.7917 +vn 0.4328 -0.0566 -0.8997 +vn 0.4697 -0.4195 -0.7768 +vn 0.4806 -0.7138 -0.5094 +vn 0.5068 -0.8452 -0.1697 +vn -0.1596 0.5041 -0.8488 +vn -0.0307 0.2568 -0.9660 +vn -0.4367 0.5076 -0.7427 +vn -0.6729 0.5048 -0.5408 +vn -0.8777 0.2799 -0.3891 +vn -0.8505 0.5164 -0.1002 +vn -0.8585 0.4919 0.1447 +vn -0.7559 0.5034 0.4186 +vn -0.5622 0.5973 0.5720 +vn -0.4470 0.4850 0.7517 +vn -0.9058 0.0220 0.4231 +vn -0.6443 -0.0190 0.7646 +vn -0.8902 0.0187 0.4552 +vn -0.6145 -0.0225 0.7886 +vn -0.6845 -0.0142 -0.7289 +vn -0.8813 0.0178 -0.4723 +vn -0.8683 0.0152 -0.4958 +vn -0.6637 -0.0170 -0.7478 +vn 0.1895 0.4559 -0.8696 +vn 0.3882 0.4603 -0.7984 +vn 0.0650 0.3833 -0.9213 +vn -0.0689 0.9177 -0.3912 +vn -0.0389 0.6774 -0.7346 +vn -0.0407 0.6694 -0.7418 +vn 0.0013 0.9873 -0.1589 +vn -0.0072 0.9988 -0.0477 +vn -0.2379 0.7884 -0.5673 +vn -0.4218 0.9067 -0.0011 +vn -0.3296 0.9175 0.2226 +vn -0.1899 0.8993 0.3940 +vn -0.4354 0.7789 -0.4513 +vn -0.4843 0.8479 -0.2157 +vn -0.5047 0.8493 0.1547 +vn -0.1646 0.9581 -0.2345 +vn -0.2813 0.9544 -0.1000 +vn -0.0094 -0.0068 -0.9999 +vn -0.0113 -0.0053 -0.9999 +vn -0.0184 0.0069 -0.9998 +vn -0.0047 0.0013 -1.0000 +vn -0.0100 0.0104 -0.9999 +vn 0.0107 0.0014 -0.9999 +vn 0.0094 0.0009 -1.0000 +vn 0.7921 -0.0315 -0.6096 +vn 0.5237 0.0422 -0.8508 +vn 0.8456 0.0315 -0.5329 +vn 0.9837 -0.0285 -0.1776 +vn 0.9977 0.0261 -0.0629 +vn 0.9770 -0.0218 0.2120 +vn 0.6307 -0.0039 0.7760 +vn 0.7065 0.0209 0.7074 +vn 0.6921 0.0161 0.7216 +vn 0.6121 -0.0097 0.7907 +vn -0.5940 -0.0247 0.8041 +vn -0.0480 -0.0012 0.9988 +vn -0.2421 0.0146 0.9701 +vn -0.8475 0.0270 0.5301 +vn -0.9101 -0.0219 0.4139 +vn -0.9967 0.0374 0.0726 +vn -0.8818 -0.0304 -0.4706 +vn -0.7265 0.0079 -0.6871 +vn -0.8478 -0.0207 -0.5298 +vn -0.6929 0.0147 -0.7208 +vn 0.0391 0.0050 0.9992 +vn 0.0479 -0.0018 0.9988 +vn 0.0470 -0.0011 0.9989 +vn 0.0419 0.0017 0.9991 +vn 0.0424 0.0015 0.9991 +vn 0.0563 -0.0068 0.9984 +vn 0.7148 0.0028 0.6993 +vn 0.7162 0.0025 0.6979 +vn 0.6973 0.0061 0.7167 +vn 0.9979 0.0135 -0.0629 +vn 0.9928 -0.0072 0.1198 +vn 0.9949 -0.0050 0.1010 +vn 0.6958 0.0064 0.7183 +vn 0.9968 0.0152 -0.0785 +vn 0.6808 -0.0066 -0.7325 +vn 0.6913 -0.0012 -0.7225 +vn 0.6838 -0.0050 -0.7296 +vn 0.6941 0.0003 -0.7198 +vn 0.1582 -0.0002 -0.9874 +vn 0.2872 0.0068 -0.9579 +vn 0.4945 -0.0014 -0.8692 +vn 0.5235 0.0065 -0.8520 +vn 0.9794 -0.0086 -0.2019 +vn 0.9779 -0.0110 -0.2086 +vn 0.9790 -0.0092 -0.2036 +vn 0.9775 -0.0117 -0.2106 +vn 0.6801 -0.0192 0.7328 +vn 0.7873 0.0261 0.6160 +vn 0.7613 0.0143 0.6483 +vn 0.6513 -0.0301 0.7582 +vn 0.0064 0.0038 1.0000 +vn 0.0088 0.0215 0.9997 +vn -0.3351 0.0142 0.9421 +vn -0.1187 0.0006 0.9929 +vn 0.0034 0.0007 1.0000 +vn 0.0110 -0.0017 0.9999 +vn 0.0130 -0.0035 0.9999 +vn -0.0184 -0.0014 -0.9998 +vn -0.0023 0.0086 -1.0000 +vn 0.0482 -0.0031 -0.9988 +vn 0.0483 -0.0038 -0.9988 +vn 0.0549 -0.0095 -0.9984 +vn -0.5826 -0.0096 0.8127 +vn -0.9076 0.0240 0.4191 +vn -0.9805 -0.0132 0.1962 +vn -0.8847 -0.0028 -0.4661 +vn -0.9020 0.0255 -0.4310 +vn -0.6499 0.0205 -0.7598 +vn -0.7124 0.0054 -0.7018 +vn -0.1798 -0.0212 -0.9835 +vn 0.7994 -0.0063 -0.6008 +vn 0.7118 0.0114 -0.7023 +vn 0.7210 0.0096 -0.6929 +vn 0.8056 -0.0077 -0.5924 +vn 0.9934 0.0017 0.1147 +vn 0.9918 0.0034 0.1277 +vn 0.9933 0.0018 0.1157 +vn 0.9916 0.0036 0.1290 +vn 0.6795 0.0005 0.7336 +vn 0.6813 0.0013 0.7320 +vn 0.6808 0.0011 0.7324 +vn 0.6791 0.0003 0.7341 +vn -0.0063 1.0000 0.0036 +vn -0.0035 1.0000 0.0073 +vn -0.0042 0.9997 0.0252 +vn -0.0006 1.0000 0.0009 +vn -0.0006 1.0000 0.0013 +vn 0.0082 0.9999 -0.0068 +vn 0.0091 0.9999 -0.0089 +vn 0.0092 0.9999 -0.0091 +vn -0.0619 -0.9755 0.2113 +vn 0.0001 -1.0000 -0.0060 +vn -0.0007 -1.0000 0.0081 +vn -0.0128 -0.9328 0.3600 +vn 0.0184 -0.9996 0.0195 +vn 0.0134 -0.9998 0.0140 +vn 0.0457 -0.9984 0.0325 +vn 0.0022 -0.9999 -0.0160 +vn 0.0042 -0.9996 0.0284 +vn 0.0072 -0.9793 0.2024 +vn 0.2295 -0.9269 0.2968 +vn 0.0080 -0.9995 0.0311 +vn 0.0192 -0.9997 0.0145 +vn -0.0161 -0.9998 -0.0075 +vn -0.0432 -0.9990 0.0065 +vn 0.1246 -0.9821 -0.1415 +vn 0.0581 -0.9980 0.0256 +vn 0.5589 -0.7772 0.2891 +vn 0.5567 -0.7572 0.3415 +vn 0.5816 -0.6771 0.4508 +vn 0.5618 -0.7635 0.3183 +vn 0.5665 -0.6552 0.4998 +vn 0.5575 -0.5721 0.6015 +vn 0.1420 -0.2437 -0.9594 +vn -0.2467 -0.0105 -0.9690 +vn -0.0406 0.0119 -0.9991 +vn 0.0392 -0.2193 -0.9749 +vn -0.1930 -0.1482 -0.9699 +vn 0.1508 -0.2234 0.9630 +vn -0.4962 -0.1297 0.8585 +vn -0.5518 0.0103 0.8339 +vn -0.7775 -0.1291 0.6155 +vn -0.8239 0.0158 0.5666 +vn -0.9300 -0.1297 0.3439 +vn -0.9643 0.0139 0.2643 +vn -0.9911 -0.1310 0.0220 +vn -0.9966 0.0145 -0.0810 +vn -0.9305 -0.1317 -0.3419 +vn -0.8948 0.0209 -0.4461 +vn -0.7779 -0.1313 -0.6145 +vn -0.6472 0.0309 -0.7617 +vn -0.5347 -0.1246 -0.8358 +vn 0.5580 -0.6231 -0.5480 +vn 0.5674 -0.7558 -0.3268 +vn 0.5656 -0.6680 -0.4836 +vn 0.5615 -0.7712 -0.2999 +vn 0.5690 -0.7017 -0.4288 +vn 0.5602 -0.7452 -0.3617 +vn -0.0469 -0.2874 -0.9567 +vn -0.1334 -0.5073 -0.8514 +vn -0.0413 -0.2514 -0.9670 +vn 0.0103 -0.3007 -0.9537 +vn -0.3071 -0.4633 0.8313 +vn -0.0944 -0.4896 0.8668 +vn -0.4559 -0.5433 0.7050 +vn -0.6343 -0.4916 0.5967 +vn -0.7797 -0.4984 0.3790 +vn -0.8468 -0.4983 0.1861 +vn -0.9561 -0.2920 0.0225 +vn -0.8543 -0.4983 -0.1480 +vn -0.7371 -0.5759 -0.3535 +vn -0.6708 -0.5029 -0.5450 +vn -0.4765 -0.5138 -0.7134 +vn -0.3171 -0.5124 -0.7980 +vn -0.0435 -0.2821 0.9584 +vn -0.0311 -0.2625 0.9644 +vn 0.1588 -0.4239 0.8917 +vn 0.2995 -0.4700 0.8303 +vn 0.0874 -0.3946 0.9147 +vn 0.2055 -0.5118 0.8341 +vn 0.2354 -0.7219 0.6507 +vn 0.2378 -0.6017 0.7625 +vn 0.4613 -0.4780 0.7475 +vn 0.4825 -0.5580 0.6752 +vn 0.1610 -0.4301 -0.8883 +vn 0.1792 -0.7029 -0.6884 +vn 0.1621 -0.5223 -0.8372 +vn 0.3883 -0.4553 -0.8012 +vn 0.3096 -0.4731 -0.8248 +vn 0.4922 -0.5613 -0.6653 +vn 0.9315 0.0037 -0.3638 +vn 0.9466 -0.0056 -0.3223 +vn 0.9622 -0.0166 -0.2720 +vn 0.9662 -0.0199 -0.2570 +vn 0.6287 0.0073 -0.7776 +vn 0.6229 0.0000 -0.7823 +vn 0.6247 0.0023 -0.7809 +vn 0.6205 -0.0029 -0.7842 +vn 0.0801 -0.0339 -0.9962 +vn -0.1857 -0.0190 -0.9824 +vn 0.0107 0.0205 -0.9997 +vn -0.3905 0.0205 -0.9204 +vn -0.5847 0.0144 -0.8111 +vn -0.6318 0.0926 -0.7696 +vn -0.9754 -0.0151 -0.2201 +vn -0.9472 -0.0902 -0.3077 +vn -0.9700 -0.0328 -0.2410 +vn -0.9859 0.0316 -0.1642 +vn -0.7347 -0.0199 0.6780 +vn -0.8579 0.0176 0.5135 +vn -0.9149 -0.0343 0.4023 +vn -0.5998 -0.0198 0.7999 +vn -0.4817 -0.0245 0.8760 +vn -0.5204 -0.0362 0.8532 +vn 0.2645 -0.0220 0.9641 +vn 0.2338 0.0033 0.9723 +vn -0.0293 0.0448 0.9986 +vn 0.3504 -0.0381 0.9358 +vn 0.9108 -0.0077 0.4129 +vn 0.9533 0.0353 0.3000 +vn 0.9424 0.0227 0.3338 +vn 0.8922 -0.0229 0.4511 +vn 0.4319 -0.0236 0.9016 +vn -0.7059 -0.0328 -0.7076 +vn -0.6254 0.0094 -0.7802 +vn -0.2204 0.0191 -0.9752 +vn -0.9284 0.0241 -0.3708 +vn -0.9981 -0.0233 -0.0577 +vn -0.9876 0.0141 0.1561 +vn -0.9753 -0.0273 0.2192 +vn -0.6950 0.0047 0.7190 +vn -0.6743 -0.0449 0.7371 +vn -0.6884 -0.0115 0.7252 +vn -0.7033 0.0264 0.7104 +vn -0.0171 -0.0045 0.9998 +vn -0.0156 -0.0011 0.9999 +vn -0.0142 0.0020 0.9999 +vn -0.0193 -0.0096 0.9998 +vn 0.7143 0.0152 0.6997 +vn 0.6988 0.0244 0.7149 +vn 0.7164 0.0139 0.6975 +vn 0.7227 0.0101 0.6911 +vn 0.9998 -0.0067 -0.0211 +vn 0.9918 0.0103 -0.1273 +vn 0.9971 -0.0273 0.0706 +vn 0.9987 -0.0187 0.0482 +vn 0.5659 -0.0494 -0.8230 +vn 0.5109 -0.0702 -0.8568 +vn 0.5578 -0.0525 -0.8283 +vn 0.0077 0.0478 -0.9988 +vn -0.2646 -0.0214 -0.9641 +vn 0.4911 -0.0773 -0.8676 +vn 0.9508 0.0459 -0.3065 +vn 0.9577 0.0057 -0.2877 +vn 0.9504 -0.0320 -0.3095 +vn 0.7809 0.0061 -0.6246 +vn 0.5195 -0.0256 -0.8541 +vn 0.2367 0.0279 -0.9712 +vn -0.0550 -0.0219 -0.9982 +vn -0.5463 0.0213 -0.8373 +vn -0.6146 -0.0242 -0.7885 +vn -0.9853 -0.0242 -0.1692 +vn -0.9107 0.0074 -0.4130 +vn -0.9993 0.0066 -0.0369 +vn 0.9813 0.0150 0.1920 +vn 0.9816 -0.0297 0.1886 +vn 0.8707 0.0448 0.4897 +vn 0.3404 -0.0486 0.9390 +vn 0.1812 0.0123 0.9834 +vn 0.2831 -0.0264 0.9587 +vn 0.1177 0.0359 0.9924 +vn -0.5436 -0.0287 0.8388 +vn -0.6689 0.0127 0.7432 +vn -0.5778 -0.0179 0.8160 +vn -0.6989 0.0235 0.7148 +vn -0.9712 -0.0268 0.2369 +vn -0.9877 -0.0032 0.1561 +vn -0.9390 -0.0228 0.3433 +vn -0.9979 0.0336 -0.0545 +vn -0.9632 -0.0095 -0.2687 +vn -0.8411 0.0151 0.5407 +vn -0.5758 -0.0217 0.8173 +vn -0.2440 0.0282 0.9694 +vn -0.0252 -0.0216 0.9994 +vn 0.4239 0.0166 0.9055 +vn 0.5733 -0.0196 0.8191 +vn 0.7764 -0.0106 0.6302 +vn 0.9582 -0.0247 0.2849 +vn 0.8888 -0.0010 0.4583 +vn 0.9996 0.0185 0.0212 +vn -0.9277 0.0391 -0.3713 +vn -0.8328 -0.0180 -0.5533 +vn -0.3343 -0.0087 -0.9424 +vn -0.2638 0.0159 -0.9644 +vn -0.3143 -0.0017 -0.9493 +vn -0.2464 0.0219 -0.9689 +vn 0.4613 -0.0187 -0.8870 +vn 0.4554 -0.0213 -0.8900 +vn 0.4597 -0.0194 -0.8879 +vn 0.4532 -0.0223 -0.8911 +vn 0.9928 -0.0181 -0.1187 +vn 0.9489 0.0444 -0.3124 +vn -0.1473 -0.7765 0.6126 +vn -0.0213 -0.8176 0.5753 +vn -0.2728 -0.9434 -0.1887 +vn -0.3885 -0.9157 -0.1032 +vn -0.5174 -0.8557 -0.0090 +vn -0.2987 -0.9538 0.0319 +vn -0.4044 -0.9041 0.1383 +vn -0.4889 -0.8029 0.3411 +vn -0.2460 -0.9199 0.3055 +vn -0.1417 -0.9201 -0.3651 +vn -0.0988 -0.7268 -0.6797 +vn -0.4145 -0.7845 -0.4612 +vn -0.0324 -0.7168 -0.6965 +vn -0.0325 -0.7164 -0.6969 +vn 0.0001 -1.0000 -0.0057 +vn -0.0018 -0.9774 -0.2115 +vn -0.0060 -0.9955 -0.0942 +vn 0.0911 -0.8248 0.5580 +vn 0.2774 -0.8517 -0.4445 +vn 0.1750 -0.8159 -0.5511 +vn 0.0167 -0.0256 -0.9995 +vn 0.0177 -0.0228 -0.9996 +vn 0.3052 -0.0269 -0.9519 +vn 0.0192 -0.0190 -0.9996 +vn 0.2003 0.0040 -0.9797 +vn -0.0775 0.0284 0.9966 +vn -0.0104 -0.0060 0.9999 +vn 0.0046 -0.1635 0.9865 +vn 0.3134 -0.0215 0.9494 +vn 0.1005 -0.2746 0.9563 +vn 0.5782 0.0012 -0.8159 +vn 0.7805 -0.0332 -0.6242 +vn 0.8126 0.0017 -0.5828 +vn 0.9402 0.0000 -0.3405 +vn 0.9777 -0.0240 -0.2086 +vn 0.9782 -0.2078 -0.0033 +vn 0.9775 -0.0236 0.2097 +vn 0.9094 -0.2519 0.3310 +vn 0.7755 -0.0239 0.6309 +vn 0.7170 -0.2178 0.6621 +vn 0.4088 -0.3027 0.8609 +vn 0.1755 -0.7496 0.6381 +vn -0.0273 -0.9053 0.4238 +vn 0.0343 -0.7637 0.6446 +vn 0.7826 -0.6204 0.0506 +vn 0.5530 -0.6194 0.5573 +vn 0.1928 -0.4962 -0.8465 +vn 0.0676 -0.7546 -0.6527 +vn 0.3516 -0.5677 -0.7444 +vn 0.4408 -0.5830 -0.6825 +vn 0.6731 -0.5599 -0.4832 +vn 0.5757 -0.7471 -0.3322 +vn 0.7949 -0.5379 -0.2806 +vn 0.8437 -0.5028 -0.1882 +vn 0.7116 -0.6370 0.2965 +vn 0.4280 -0.8039 -0.4130 +vn 0.5887 -0.8039 0.0849 +vn 0.5030 -0.8008 0.3252 +vn 0.5376 -0.8387 -0.0865 +vn 0.1858 -0.9791 -0.0825 +vn 0.2347 -0.8202 -0.5218 +vn 0.0176 -0.9051 -0.4248 +vn -0.0157 -0.8598 -0.5105 +vn 0.0324 -0.7617 -0.6471 +vn 0.0252 -0.7077 -0.7061 +vn -0.0005 -1.0000 -0.0003 +vn -0.0063 -0.9999 0.0153 +vn 0.0167 -0.9988 0.0450 +vn 0.0347 -0.9990 0.0297 +vn 0.0154 -0.9984 0.0549 +vn -0.0432 -0.9989 0.0173 +vn -0.0538 -0.9985 -0.0044 +vn -0.0450 -0.9990 -0.0041 +vn 0.0273 -0.9991 -0.0339 +vn 0.0316 -0.9988 -0.0387 +vn 0.0439 -0.9989 -0.0177 +vn 0.0413 -0.9991 0.0036 +vn 0.0053 -0.9990 -0.0448 +vn -0.0113 -0.9993 -0.0368 +vn -0.0275 -0.9992 -0.0291 +vn 0.0476 -0.9989 0.0050 +vn -0.0249 -0.9992 0.0302 +vn -0.0171 -0.9991 0.0398 +vn 0.1315 0.9913 0.0062 +vn -0.1462 0.9888 -0.0289 +vn -0.0751 0.9972 -0.0041 +vn 0.0090 0.9844 -0.1757 +vn 0.2194 0.9730 -0.0716 +vn 0.7983 0.1087 0.5924 +vn 0.8491 0.0008 0.5282 +vn 0.8042 0.0833 0.5886 +vn 0.8536 -0.0003 0.5209 +vn 0.9934 0.0106 -0.1140 +vn 0.9973 0.0053 -0.0728 +vn 0.9262 0.0038 -0.3769 +vn 0.9432 0.0141 -0.3319 +vn 0.8415 0.0154 -0.5401 +vn 0.7626 0.0004 -0.6469 +vn 0.1969 0.0569 -0.9788 +vn 0.2901 0.0008 -0.9570 +vn 0.2800 0.0022 -0.9600 +vn 0.1898 0.0630 -0.9798 +vn -0.6754 0.0235 -0.7371 +vn -0.4718 -0.0073 -0.8817 +vn -0.7684 -0.0028 -0.6399 +vn -0.8718 0.0176 -0.4896 +vn -0.9535 -0.0008 -0.3014 +vn -0.9774 0.0086 -0.2111 +vn -0.8076 0.0006 0.5898 +vn -0.8501 0.0157 0.5264 +vn -0.8127 0.0024 0.5826 +vn -0.8554 0.0177 0.5176 +vn 0.0308 0.0179 0.9994 +vn -0.3443 -0.0101 0.9388 +vn -0.0485 -0.0051 0.9988 +vn 0.0758 0.0180 0.9970 +vn 0.2476 -0.0027 0.9689 +vn 0.0507 0.9967 0.0635 +vn 0.0791 0.9968 0.0139 +vn 0.0747 0.9970 0.0210 +vn -0.0089 0.9966 -0.0825 +vn -0.0259 0.9963 -0.0822 +vn -0.0588 0.9970 -0.0508 +vn -0.0630 0.9968 -0.0482 +vn 0.0782 0.9966 -0.0270 +vn 0.0644 0.9967 -0.0501 +vn 0.0418 0.9969 -0.0673 +vn 0.0537 0.9965 0.0645 +vn -0.0517 0.9969 0.0585 +vn -0.0703 0.9964 0.0477 +vn -0.0309 0.9966 0.0758 +vn -0.0028 0.9969 0.0788 +vn 0.0161 0.9964 0.0836 +vn 0.0234 0.9962 -0.0840 +vn -0.0830 0.9965 0.0100 +vn -0.0880 0.9961 -0.0029 +vn 0.9878 0.0402 0.1504 +vn 0.6413 0.0305 0.7667 +vn 0.7985 -0.0166 0.6017 +vn 0.9885 -0.0236 0.1491 +vn 0.9391 -0.0108 -0.3436 +vn 0.7977 0.0369 -0.6020 +vn 0.6042 -0.0240 -0.7965 +vn 0.2984 0.0274 -0.9541 +vn 0.0486 -0.0327 -0.9983 +vn -0.2862 0.0247 -0.9578 +vn -0.6549 -0.0333 -0.7550 +vn -0.7993 0.0221 -0.6005 +vn -0.9087 -0.0192 -0.4169 +vn -0.9345 0.0130 -0.3558 +vn -0.9593 0.0183 0.2818 +vn -0.9792 -0.0155 0.2023 +vn -0.8939 -0.0173 0.4479 +vn -0.8139 0.0223 0.5805 +vn -0.7040 -0.0162 0.7100 +vn -0.6032 0.0355 0.7968 +vn -0.0852 -0.0239 0.9961 +vn -0.0814 -0.0217 0.9964 +vn 0.2726 -0.0229 0.9619 +vn 0.1342 0.0030 0.9910 +vn 0.7947 0.0000 0.6070 +vn 0.9230 0.0000 -0.3848 +vn 0.1282 0.0000 -0.9917 +vn -0.7946 0.0000 -0.6072 +vn -0.9230 0.0000 0.3849 +vn -0.1285 0.0000 0.9917 +vn 0.0965 0.8281 0.5522 +vn 0.1027 0.8466 0.5222 +vn 0.0559 0.6923 0.7194 +vn 0.0454 0.6535 0.7556 +vn -0.6570 0.5827 0.4783 +vn -0.3852 0.9140 0.1275 +vn -0.2454 0.8710 -0.4255 +vn 0.1854 0.2426 -0.9522 +vn 0.3579 0.8467 -0.3937 +vn 0.5185 0.8499 0.0942 +vn 0.7399 0.3902 0.5481 +vn 0.0394 -0.9990 0.0197 +vn 0.0475 -0.9989 -0.0028 +vn 0.0485 -0.9986 0.0191 +vn -0.0424 -0.9989 0.0192 +vn -0.0310 -0.9989 0.0349 +vn -0.0505 -0.9987 0.0090 +vn 0.0194 -0.9991 0.0368 +vn -0.0040 -0.9991 0.0411 +vn 0.0367 -0.9992 -0.0165 +vn 0.0282 -0.9990 -0.0343 +vn -0.0078 -0.9989 -0.0462 +vn 0.0129 -0.9981 -0.0607 +vn 0.0026 -0.9989 -0.0474 +vn -0.0090 -0.9988 0.0490 +vn -0.0340 -0.9993 -0.0171 +vn -0.0327 -0.9993 -0.0176 +vn -0.0189 0.9933 -0.1144 +vn -0.0297 0.9984 0.0479 +vn 0.1356 0.9871 0.0845 +vn 0.0247 0.9925 -0.1195 +vn 0.1381 0.9894 -0.0439 +vn -0.0016 0.9937 0.1117 +vn -0.5200 0.0008 0.8542 +vn -0.5067 -0.0008 0.8621 +vn -0.6560 0.0183 0.7545 +vn 0.0213 0.0142 0.9997 +vn 0.0845 0.0056 0.9964 +vn 0.0263 0.0135 0.9996 +vn 0.0915 0.0047 0.9958 +vn 0.8107 0.0780 0.5802 +vn 0.6795 -0.0058 0.7336 +vn 0.8728 -0.0055 0.4880 +vn 0.9749 0.0605 0.2143 +vn 0.9914 -0.0005 -0.1305 +vn 0.8731 0.0201 -0.4871 +vn 0.7449 0.0043 -0.6671 +vn 0.4312 0.0213 -0.9020 +vn 0.2145 -0.0004 -0.9767 +vn 0.0386 0.0176 -0.9991 +vn -0.1297 -0.0048 -0.9915 +vn -0.7799 0.0338 -0.6250 +vn -0.8310 -0.0025 -0.5562 +vn -0.7852 0.0355 -0.6182 +vn -0.8369 -0.0042 -0.5473 +vn -0.9705 0.0126 0.2406 +vn -0.9579 0.0065 0.2869 +vn -0.9692 0.0119 0.2462 +vn -0.9565 0.0058 0.2915 +vn -0.6683 0.0200 0.7437 +vn -0.0151 0.9967 0.0797 +vn -0.0412 0.9970 0.0655 +vn 0.0080 0.9960 0.0888 +vn 0.0570 0.9970 -0.0525 +vn 0.0420 0.9967 -0.0696 +vn 0.0170 0.9968 -0.0777 +vn -0.0599 0.9972 0.0451 +vn -0.0777 0.9966 0.0278 +vn -0.0366 0.9971 -0.0661 +vn -0.0507 0.9969 -0.0597 +vn -0.0779 0.9969 -0.0109 +vn 0.0814 0.9967 -0.0053 +vn 0.0766 0.9966 -0.0288 +vn 0.0298 0.9966 0.0773 +vn 0.0604 0.9966 0.0558 +vn 0.0753 0.9966 0.0340 +vn -0.0842 0.9963 -0.0150 +vn 0.0897 0.9958 0.0175 +vn -0.0023 0.9963 -0.0854 +vn -0.3688 -0.0277 0.9291 +vn -0.1134 -0.0183 0.9934 +vn -0.2608 0.0199 0.9652 +vn 0.1095 0.0343 0.9934 +vn 0.4557 -0.0275 0.8897 +vn 0.7059 0.0310 0.7076 +vn 0.9014 -0.0287 0.4320 +vn 0.9862 0.0265 0.1631 +vn 0.9873 -0.0279 -0.1566 +vn 0.9229 0.0245 -0.3841 +vn 0.7168 -0.0231 -0.6969 +vn 0.5334 0.0304 -0.8453 +vn 0.2203 -0.0191 -0.9753 +vn -0.0422 0.0301 -0.9987 +vn -0.3096 -0.0286 -0.9504 +vn -0.6386 0.0323 -0.7688 +vn -0.8469 -0.0351 -0.5306 +vn -0.9823 0.0295 -0.1848 +vn -0.9830 -0.0301 0.1810 +vn -0.9301 0.0191 0.3667 +vn -0.8501 -0.0109 0.5266 +vn -0.8069 0.0231 0.5902 +vn -0.5182 0.0000 0.8553 +vn 0.4818 0.0000 0.8763 +vn 0.9998 0.0000 0.0211 +vn 0.5182 0.0000 -0.8553 +vn -0.4818 0.0000 -0.8763 +vn -0.9998 0.0000 -0.0211 +vn -0.5292 0.8485 -0.0031 +vn -0.7727 0.1399 -0.6191 +vn -0.0822 0.8973 -0.4336 +vn 0.5272 0.8492 0.0298 +vn 0.7673 0.3597 0.5309 +vn 0.1280 0.9093 0.3960 +vn -0.0411 -0.9992 -0.0023 +vn -0.0430 -0.9988 0.0251 +vn -0.0397 -0.9992 -0.0072 +vn 0.0184 -0.9990 0.0418 +vn 0.0212 -0.9983 0.0541 +vn -0.0110 -0.9991 0.0410 +vn -0.0282 -0.9991 0.0316 +vn 0.0367 -0.9990 0.0236 +vn 0.0445 -0.9990 0.0013 +vn 0.0413 -0.9990 -0.0188 +vn 0.0586 -0.9983 0.0015 +vn 0.0298 -0.9986 -0.0444 +vn 0.0244 -0.9991 -0.0351 +vn -0.0044 -0.9992 -0.0397 +vn -0.0255 -0.9991 -0.0346 +vn -0.0375 -0.9988 -0.0329 +vn -0.0166 0.9986 -0.0495 +vn 0.0244 0.9996 0.0117 +vn 0.0037 0.9975 -0.0710 +vn 0.0310 0.9973 0.0668 +vn 0.0104 0.9956 0.0927 +vn -0.1067 0.9936 0.0357 +vn -0.8405 0.0290 0.5411 +vn -0.7165 0.0049 0.6976 +vn -0.6310 0.0222 0.7755 +vn -0.3960 -0.0039 0.9182 +vn 0.0596 0.0176 0.9981 +vn 0.3247 -0.0040 0.9458 +vn 0.4757 0.0186 0.8794 +vn 0.6316 0.0012 0.7753 +vn 0.9402 0.0199 0.3401 +vn 0.9794 0.0027 0.2018 +vn 0.9454 0.0181 0.3253 +vn 0.9823 0.0009 0.1873 +vn 0.8501 0.0281 -0.5258 +vn 0.7574 0.0052 -0.6529 +vn 0.8399 0.0253 -0.5422 +vn 0.7449 0.0025 -0.6671 +vn 0.3098 0.0157 -0.9507 +vn 0.0613 -0.0094 -0.9981 +vn 0.2889 0.0136 -0.9573 +vn 0.0409 -0.0114 -0.9991 +vn -0.5480 0.0183 -0.8363 +vn -0.6350 0.0065 -0.7725 +vn -0.5583 0.0169 -0.8294 +vn -0.6436 0.0053 -0.7653 +vn -0.9540 0.0263 -0.2988 +vn -0.9982 -0.0007 -0.0607 +vn -0.9614 0.0235 -0.2740 +vn -0.9993 -0.0032 -0.0377 +vn -0.0702 0.9970 0.0316 +vn -0.0670 0.9963 0.0539 +vn -0.0380 0.9967 0.0722 +vn 0.0276 0.9967 0.0768 +vn -0.0104 0.9968 0.0795 +vn 0.0528 0.9962 0.0689 +vn -0.0779 0.9970 0.0022 +vn -0.0689 0.9969 -0.0393 +vn 0.0724 0.9965 0.0416 +vn 0.0838 0.9960 0.0303 +vn 0.0791 0.9966 -0.0224 +vn 0.0835 0.9963 -0.0200 +vn -0.0750 0.9962 -0.0452 +vn -0.0217 0.9968 -0.0774 +vn -0.0298 0.9967 -0.0756 +vn 0.0283 0.9969 -0.0739 +vn 0.0379 0.9968 -0.0706 +vn -0.6061 -0.0226 0.7951 +vn -0.5729 0.0007 0.8197 +vn -0.5499 0.0163 0.8351 +vn -0.5170 0.0379 0.8551 +vn 0.0672 -0.0515 0.9964 +vn 0.4062 -0.0205 0.9136 +vn 0.2145 0.0198 0.9765 +vn 0.5807 0.0318 0.8135 +vn 0.8342 -0.0201 0.5511 +vn 0.9306 0.0257 0.3651 +vn 0.9974 -0.0206 0.0693 +vn 0.9612 0.0343 -0.2737 +vn 0.8878 -0.0022 -0.4602 +vn 0.7908 0.0362 -0.6110 +vn 0.7655 0.0150 -0.6433 +vn 0.2777 -0.0435 -0.9597 +vn 0.1904 0.0020 -0.9817 +vn 0.1274 0.0342 -0.9913 +vn 0.0502 0.0730 -0.9961 +vn -0.4598 -0.0593 -0.8860 +vn -0.7319 -0.0298 -0.6808 +vn -0.6173 0.0143 -0.7866 +vn -0.8775 0.0278 -0.4787 +vn -0.9922 -0.0245 -0.1225 +vn -0.9989 0.0179 0.0434 +vn -0.9789 -0.0100 0.2040 +vn -0.9561 0.0293 0.2917 +vn -0.8958 0.0000 0.4444 +vn -0.0634 0.0000 0.9980 +vn 0.8328 0.0000 0.5536 +vn 0.8958 0.0000 -0.4444 +vn 0.0634 0.0000 -0.9980 +vn -0.8328 0.0000 -0.5536 +vn -0.0601 0.9202 -0.3867 +vn 0.0706 0.9221 0.3805 +vn -0.0138 -0.9989 0.0445 +vn -0.0054 -0.9985 0.0545 +vn -0.0282 -0.9988 0.0401 +vn -0.0442 -0.9990 -0.0048 +vn -0.0376 -0.9989 -0.0287 +vn -0.0296 -0.9992 -0.0269 +vn 0.0452 -0.9989 0.0140 +vn 0.0185 -0.9992 0.0358 +vn 0.0286 -0.9993 0.0242 +vn 0.0148 -0.9982 -0.0579 +vn 0.0316 -0.9991 -0.0295 +vn 0.0114 -0.9990 -0.0436 +vn 0.0459 -0.9989 -0.0068 +vn -0.0088 -0.9991 -0.0420 +vn -0.0408 -0.9991 0.0130 +vn -0.0436 -0.9988 0.0242 +vn 0.0583 -0.9983 -0.0036 +vn -0.0316 0.9995 0.0056 +vn -0.0127 0.9954 -0.0953 +vn -0.0069 0.9999 -0.0075 +vn -0.0573 0.9905 -0.1252 +vn -0.0607 0.9957 -0.0699 +vn 0.9861 -0.0009 0.1660 +vn 0.9886 0.0014 0.1507 +vn 0.9988 0.0168 0.0461 +vn 0.9992 0.0186 0.0341 +vn 0.8583 -0.0083 -0.5130 +vn 0.6563 -0.0068 -0.7545 +vn 0.6584 0.1027 -0.7456 +vn 0.6317 0.0558 -0.7732 +vn 0.3897 -0.0075 -0.9209 +vn -0.1709 0.0150 -0.9852 +vn -0.2256 0.0096 -0.9742 +vn -0.4328 0.0162 -0.9013 +vn -0.5037 0.0064 -0.8638 +vn -0.6671 0.0155 -0.7448 +vn -0.7365 0.0017 -0.6764 +vn -0.9999 -0.0030 0.0163 +vn -0.9357 -0.0063 0.3528 +vn -0.9799 0.0057 0.1994 +vn -0.9690 0.0015 0.2469 +vn -0.7570 -0.0132 0.6533 +vn -0.2695 0.0216 0.9628 +vn -0.1484 0.0076 0.9889 +vn -0.2557 0.0200 0.9665 +vn -0.1343 0.0059 0.9909 +vn 0.4608 0.0259 0.8871 +vn 0.6070 -0.0002 0.7947 +vn 0.4759 0.0233 0.8792 +vn 0.6236 -0.0034 0.7817 +vn 0.0483 0.9974 -0.0532 +vn 0.0481 0.9969 -0.0621 +vn 0.0061 0.9960 -0.0888 +vn -0.0020 0.9957 -0.0927 +vn 0.0688 0.9969 0.0381 +vn 0.0739 0.9966 0.0371 +vn 0.0824 0.9966 -0.0074 +vn 0.0795 0.9967 -0.0167 +vn 0.0178 0.9968 0.0776 +vn 0.0364 0.9968 0.0713 +vn -0.0424 0.9966 0.0704 +vn -0.0257 0.9964 0.0807 +vn -0.0366 0.9967 -0.0725 +vn -0.0447 0.9966 -0.0686 +vn -0.0740 0.9968 -0.0301 +vn -0.0803 0.9967 -0.0149 +vn -0.0756 0.9968 0.0263 +vn -0.0736 0.9964 0.0421 +vn 0.9800 0.0046 0.1988 +vn 0.9777 0.0100 0.2098 +vn 0.9830 -0.0029 0.1834 +vn 0.9850 -0.0083 0.1725 +vn 0.8956 0.0235 -0.4442 +vn 0.9088 0.0070 -0.4173 +vn 0.9018 0.0159 -0.4319 +vn 0.8894 0.0310 -0.4561 +vn 0.3467 0.0219 -0.9377 +vn 0.5008 -0.0411 -0.8646 +vn 0.2507 -0.0204 -0.9679 +vn -0.0153 0.0314 -0.9994 +vn -0.2921 -0.0242 -0.9561 +vn -0.5963 0.0300 -0.8022 +vn -0.7606 -0.0176 -0.6489 +vn -0.8531 0.0242 -0.5211 +vn -0.9070 -0.0264 -0.4203 +vn -0.9844 0.0245 0.1741 +vn -0.9817 0.0160 0.1899 +vn -0.8724 0.0294 0.4880 +vn -0.9097 -0.0022 0.4153 +vn -0.5782 -0.0203 0.8156 +vn -0.2996 0.0380 0.9533 +vn -0.0005 -0.0208 0.9998 +vn 0.4464 0.0206 0.8946 +vn 0.5291 -0.0053 0.8485 +vn 0.7197 0.0071 0.6943 +vn 0.7123 0.0015 0.7019 +vn 0.9632 0.0000 0.2689 +vn 0.7143 0.0000 -0.6998 +vn -0.2487 0.0000 -0.9686 +vn -0.9632 0.0000 -0.2688 +vn -0.7143 0.0000 0.6998 +vn 0.2490 0.0000 0.9685 +vn 0.4162 0.7149 0.5619 +vn -0.2537 0.8849 0.3906 +vn -0.9723 -0.0928 0.2146 +vn -0.3660 0.9101 -0.1945 +vn 0.0864 0.9033 -0.4202 +vn 0.6206 0.2888 -0.7290 +vn 0.6737 0.7386 0.0238 +vn 0.6710 0.7411 0.0246 +vn 0.6614 0.7495 0.0273 +vn 0.6587 0.7519 0.0281 +vn 0.5556 0.0083 -0.8314 +vn 0.5415 -0.0390 -0.8398 +vn 0.4909 -0.1807 -0.8522 +vn 0.4793 -0.2091 -0.8524 +vn 0.1084 0.3304 -0.9376 +vn -0.1838 -0.2846 -0.9409 +vn -0.3819 0.1937 -0.9037 +vn -0.6564 -0.2572 -0.7092 +vn -0.7842 0.2941 -0.5464 +vn -0.9535 -0.2280 -0.1970 +vn -0.9548 0.2972 0.0026 +vn -0.9016 -0.3197 0.2914 +vn -0.6629 0.3880 0.6404 +vn -0.6060 -0.1572 0.7798 +vn -0.0262 -0.0064 0.9996 +vn -0.0365 -0.0570 0.9977 +vn 0.0267 0.2491 0.9681 +vn 0.0329 0.2783 0.9599 +vn 0.6017 -0.2325 0.7642 +vn 0.6941 0.3547 0.6265 +vn 0.8882 -0.3467 0.3016 +vn 0.9421 0.3353 -0.0065 +vn 0.8843 -0.3596 -0.2979 +vn 0.8446 0.1805 -0.5041 +vn 0.6756 -0.0331 0.7366 +vn 0.7096 0.3094 0.6330 +vn 0.6907 0.0422 0.7219 +vn 0.7048 0.3800 0.5990 +vn -0.8381 0.0229 0.5451 +vn -0.8349 0.0409 0.5489 +vn -0.8479 -0.0488 0.5279 +vn -0.8495 -0.0661 0.5234 +vn -0.9586 0.0758 -0.2744 +vn -0.8819 0.0562 -0.4682 +vn -0.9539 0.0912 -0.2859 +vn -0.8803 0.0432 -0.4725 +vn -0.9568 -0.2486 -0.1508 +vn -0.9480 -0.2779 -0.1552 +vn -0.6582 0.1996 -0.7259 +vn -0.6582 0.1990 -0.7261 +vn -0.6580 0.2057 -0.7243 +vn -0.6580 0.2073 -0.7239 +vn -0.1288 -0.3314 -0.9347 +vn 0.0489 0.3454 -0.9372 +vn 0.3492 -0.2695 -0.8975 +vn 0.5407 0.3482 -0.7658 +vn 0.7509 -0.4166 -0.5124 +vn 0.8624 0.4220 -0.2797 +vn 0.8734 -0.4822 0.0686 +vn 0.8868 0.3654 0.2831 +vn 0.6375 -0.1422 0.7572 +vn 0.6394 -0.1331 0.7572 +vn 0.6300 -0.1748 0.7567 +vn 0.6290 -0.1785 0.7566 +vn 0.0567 0.0952 0.9938 +vn 0.0590 0.1068 0.9925 +vn 0.2505 -0.0034 0.9681 +vn 0.2484 -0.0145 0.9685 +vn 0.4407 -0.0435 0.8966 +vn 0.4429 -0.0370 0.8958 +vn -0.5582 0.0474 0.8283 +vn -0.5538 0.0645 0.8302 +vn -0.5748 -0.0233 0.8180 +vn -0.5784 -0.0411 0.8147 +vn -0.7050 -0.0035 -0.7092 +vn -0.7107 0.0268 -0.7030 +vn -0.7063 0.0028 -0.7080 +vn -0.7118 0.0330 -0.7016 +vn 0.7691 0.0543 0.6368 +vn 0.7248 0.1319 0.6763 +vn 0.8321 -0.0920 0.5469 +vn 0.6344 -0.0202 -0.7728 +vn 0.2863 0.4020 -0.8698 +vn -0.6571 -0.3470 -0.6692 +vn -0.8765 0.3798 0.2958 +vn -0.6172 -0.2317 0.7519 +vn 0.6412 0.2513 0.7251 +vn 0.9450 0.1718 0.2785 +vn 0.9491 -0.2601 -0.1776 +vn 0.4685 0.2420 -0.8497 +vn -0.3358 -0.2981 -0.8935 +vn -0.8342 0.3108 -0.4556 +vn -0.8893 -0.2588 0.3771 +vn -0.2783 0.2456 0.9286 +vn 0.1404 -0.1470 0.9791 +vn 0.0001 0.9859 0.1672 +vn -0.0004 0.9893 0.1457 +vn -0.0010 0.8201 0.5722 +vn 0.0003 0.8458 0.5336 +vn 0.0010 0.6037 0.7972 +vn -0.0014 0.4745 0.8802 +vn 0.0014 0.2702 0.9628 +vn -0.0012 0.1085 0.9941 +vn 0.0015 -0.1922 0.9814 +vn -0.0016 -0.3140 0.9494 +vn 0.0018 -0.6302 0.7764 +vn -0.0018 -0.7385 0.6743 +vn 0.0009 -0.9162 0.4007 +vn -0.0004 -0.9535 0.3014 +vn 0.0001 -0.9985 -0.0541 +vn 0.0002 -1.0000 -0.0036 +vn 0.0003 -0.9296 -0.3686 +vn -0.0002 -0.9151 -0.4033 +vn -0.0009 -0.6656 -0.7463 +vn 0.0003 -0.7164 -0.6977 +vn 0.0010 -0.4249 -0.9052 +vn -0.0015 -0.2144 -0.9767 +vn 0.0008 -0.0891 -0.9960 +vn -0.0006 0.2152 -0.9766 +vn 0.0003 0.2566 -0.9665 +vn -0.0004 0.5554 -0.8316 +vn 0.0004 0.5823 -0.8130 +vn -0.0004 0.8328 -0.5536 +vn 0.0004 0.8505 -0.5260 +vn -0.0003 0.9749 -0.2227 +vn 0.0003 0.9812 -0.1931 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.7234 0.1231 -0.6794 +vn -0.7299 0.0230 -0.6832 +vn -0.7290 -0.0409 -0.6833 +vn -0.7789 0.1778 -0.6014 +vn -0.6416 0.0504 -0.7654 +vn -0.7339 -0.0436 -0.6779 +vn -0.2451 0.2922 -0.9244 +vn -0.1092 0.2482 -0.9625 +vn -0.0151 0.3447 -0.9386 +vn -0.7830 -0.1002 -0.6139 +vn -0.6878 -0.1504 -0.7102 +vn -0.5816 -0.1600 -0.7976 +vn -0.3661 -0.2639 -0.8924 +vn -0.5774 -0.0386 -0.8156 +vn -0.4284 -0.2286 -0.8742 +vn -0.2111 -0.1504 -0.9658 +vn -0.5610 0.1354 -0.8166 +vn -0.3605 -0.0318 -0.9322 +vn -0.0864 -0.1673 -0.9821 +vn -0.0563 -0.3256 -0.9438 +vn -0.1212 0.0451 -0.9916 +vn -0.3740 0.1836 -0.9091 +vn -0.5745 0.2052 -0.7924 +vn -0.6120 -0.0285 -0.7903 +vn -0.2772 0.0062 -0.9608 +vn -0.2790 0.0022 -0.9603 +vn 0.1896 0.0048 -0.9819 +vn 0.1398 -0.0054 -0.9902 +vn 0.6102 -0.0159 -0.7921 +vn 0.6172 0.0118 -0.7867 +vn 0.9166 0.0105 -0.3996 +vn 0.9524 -0.0176 -0.3043 +vn 0.9846 0.0154 0.1744 +vn 0.9696 -0.0088 0.2446 +vn 0.8912 0.0094 0.4536 +vn 0.8801 -0.0040 0.4747 +vn -0.0001 -1.0000 -0.0002 +vn -0.0001 -1.0000 -0.0001 +vn -0.0001 -1.0000 0.0000 +vn 0.0033 -1.0000 -0.0029 +vn 0.1825 -0.9758 -0.1206 +vn 0.0015 -1.0000 -0.0047 +vn 0.0079 -0.9999 -0.0079 +vn 0.2085 -0.9679 -0.1405 +vn 0.0079 -1.0000 -0.0042 +vn 0.2029 -0.9469 -0.2493 +vn -0.0003 -1.0000 -0.0003 +vn -0.0004 -1.0000 -0.0061 +vn -0.0001 -1.0000 -0.0011 +vn 0.2716 -0.9623 0.0112 +vn 0.0001 -1.0000 -0.0002 +vn 0.0008 -1.0000 -0.0051 +vn 0.0768 -0.9954 -0.0575 +vn -0.0001 -1.0000 -0.0003 +vn 0.3450 -0.7091 -0.6149 +vn 0.2540 -0.6888 -0.6790 +vn 0.0896 -0.5209 -0.8489 +vn 0.4066 -0.7608 -0.5059 +vn 0.6352 -0.5119 -0.5784 +vn 0.6946 -0.5142 -0.5032 +vn 0.7327 -0.5036 -0.4578 +vn 0.7137 -0.5042 -0.4863 +vn 0.0064 1.0000 -0.0037 +vn 0.0139 0.9998 -0.0140 +vn 0.0081 1.0000 0.0001 +vn -0.0001 1.0000 -0.0011 +vn -0.0004 1.0000 -0.0049 +vn 0.2226 0.9748 -0.0142 +vn 0.0004 1.0000 -0.0050 +vn -0.0001 1.0000 -0.0001 +vn -0.0002 1.0000 -0.0002 +vn -0.0001 1.0000 -0.0002 +vn -0.0003 1.0000 -0.0005 +vn -0.0002 1.0000 -0.0004 +vn -0.0002 1.0000 -0.0001 +vn 0.0114 0.9998 -0.0146 +vn 0.0079 0.9999 -0.0084 +vn 0.1925 0.9501 -0.2456 +vn 0.1010 0.9927 -0.0657 +vn 0.2185 0.9656 -0.1409 +vn 0.7295 0.4985 -0.4684 +vn 0.5649 0.7161 -0.4101 +vn 0.6859 0.5172 -0.5118 +vn 0.5816 0.7174 -0.3834 +vn 0.4430 0.6926 -0.5693 +vn 0.2219 0.6621 -0.7158 +vn 0.1315 0.5431 -0.8293 +vn 0.0029 -1.0000 0.0022 +vn -0.2736 -0.9389 0.2087 +vn -0.2882 -0.9370 -0.1973 +vn -0.0022 0.8855 0.4647 +vn 0.0001 0.9186 0.3951 +vn -0.2782 0.9040 0.3246 +vn -0.0007 0.8478 0.5303 +vn -0.2502 0.7216 0.6456 +vn 0.0025 0.7323 0.6809 +vn -0.2437 0.4497 0.8593 +vn -0.0004 0.4395 0.8983 +vn -0.2668 0.0884 0.9597 +vn 0.0073 -0.0278 0.9996 +vn -0.2473 -0.2798 0.9277 +vn 0.0042 -0.4195 0.9077 +vn -0.2935 -0.5675 0.7693 +vn 0.0020 -0.7132 0.7009 +vn -0.2926 -0.7953 0.5309 +vn 0.0016 -0.8347 0.5506 +vn -0.0007 -0.8801 0.4747 +vn -0.0022 -0.9159 0.4014 +vn 0.0026 -0.9668 0.2554 +vn 0.0067 -0.9465 -0.3227 +vn -0.2795 -0.7869 -0.5501 +vn -0.2981 -0.5356 -0.7901 +vn -0.2782 -0.2272 -0.9333 +vn 0.0030 -0.3606 -0.9327 +vn 0.0482 0.1558 -0.9866 +vn -0.2954 0.1640 -0.9412 +vn -0.2639 0.5525 -0.7906 +vn -0.2735 0.8491 -0.4519 +vn 0.0011 0.9366 -0.3504 +vn -0.2734 0.9613 -0.0347 +vn 0.0023 0.9980 -0.0634 +vn 0.0028 0.9730 0.2309 +vn 0.4379 0.4546 -0.7756 +vn 0.3643 0.7053 -0.6082 +vn 0.6162 0.5458 -0.5677 +vn 0.6168 0.5004 -0.6076 +vn 0.4806 0.6926 -0.5379 +vn 0.7283 -0.5071 -0.4609 +vn 0.5182 -0.7021 -0.4883 +vn 0.5945 -0.4978 -0.6315 +vn 0.3926 -0.6916 -0.6063 +vn 0.6216 -0.5442 -0.5634 +vn 0.4261 -0.6982 -0.5753 +vn -0.3718 -0.9283 0.0063 +vn -0.4213 -0.8304 -0.3646 +vn -0.4185 -0.6384 -0.6460 +vn -0.4877 -0.3409 -0.8037 +vn -0.4145 -0.0092 -0.9100 +vn -0.4485 0.3965 -0.8011 +vn -0.4868 0.7033 -0.5181 +vn -0.4233 0.8877 -0.1810 +vn -0.4696 0.8638 0.1824 +vn -0.4805 0.7063 0.5198 +vn -0.4896 0.3819 0.7839 +vn -0.5166 0.0320 0.8557 +vn -0.4906 -0.2976 0.8190 +vn -0.4483 -0.6413 0.6227 +vn -0.4635 -0.8215 0.3322 +vn -0.9994 0.0091 0.0345 +vn -0.9987 -0.0032 0.0500 +vn -0.9083 0.0042 0.4182 +vn -0.9107 0.0049 0.4131 +vn -0.6463 0.0099 0.7630 +vn -0.7054 -0.0136 0.7087 +vn -0.3144 -0.0118 0.9492 +vn -0.2269 0.0067 0.9739 +vn 0.1189 -0.0050 0.9929 +vn 0.1536 -0.0153 0.9880 +vn 0.4677 0.0140 0.8838 +vn 0.5994 -0.0254 0.8001 +vn 0.7930 0.0215 0.6089 +vn 0.9100 -0.0220 0.4140 +vn 0.9863 0.0222 0.1632 +vn 0.9997 -0.0186 0.0135 +vn 0.9676 0.0189 -0.2518 +vn 0.9348 -0.0141 -0.3550 +vn 0.7878 0.0118 -0.6159 +vn 0.7133 -0.0213 -0.7005 +vn 0.5187 0.0145 -0.8549 +vn 0.3686 -0.0264 -0.9292 +vn 0.1662 0.0155 -0.9860 +vn -0.1433 -0.0277 -0.9893 +vn -0.2816 0.0045 -0.9595 +vn -0.6534 -0.0240 -0.7567 +vn -0.6009 0.0135 -0.7992 +vn -0.8984 0.0142 -0.4390 +vn -0.9444 -0.0164 -0.3284 +vn 0.9739 -0.0104 0.2269 +vn 0.9879 0.0131 0.1545 +vn 0.7929 0.0103 0.6093 +vn 0.7693 -0.0065 0.6389 +vn 0.3922 0.0069 0.9199 +vn 0.3565 -0.0110 0.9342 +vn -0.0878 0.0121 0.9961 +vn -0.1896 -0.0232 0.9816 +vn -0.5000 0.0126 0.8659 +vn -0.6941 -0.0366 0.7189 +vn -0.8120 0.0043 0.5836 +vn -0.9800 -0.0265 0.1970 +vn -0.9741 0.0279 0.2242 +vn -0.9819 0.0103 -0.1891 +vn -0.9337 -0.0308 -0.3567 +vn -0.8240 0.0197 -0.5663 +vn -0.6700 -0.0246 -0.7419 +vn -0.5191 0.0205 -0.8545 +vn -0.2645 -0.0234 -0.9641 +vn -0.0925 0.0233 -0.9954 +vn 0.2131 -0.0294 -0.9766 +vn 0.3743 0.0140 -0.9272 +vn 0.7258 -0.0170 -0.6877 +vn 0.7752 0.0128 -0.6316 +vn 0.9598 0.0010 -0.2807 +vn 0.9751 -0.0147 -0.2213 +vn 0.4468 0.8208 -0.3560 +vn 0.8423 0.5358 -0.0590 +vn 0.7741 0.6323 -0.0323 +vn 0.7514 0.2629 0.6053 +vn 0.7598 0.5655 0.3209 +vn 0.6083 0.0891 0.7887 +vn 0.8054 -0.5110 0.3004 +vn 0.6411 -0.1535 0.7520 +vn 0.6926 -0.1913 0.6955 +vn 0.8279 -0.3704 0.4212 +vn 0.7393 -0.6715 -0.0498 +vn 0.7825 -0.5670 -0.2573 +vn 0.7047 -0.6151 -0.3536 +vn 0.6467 0.6725 0.3599 +vn 0.7027 0.6967 0.1443 +vn 0.4264 0.9012 -0.0774 +vn 0.3361 0.9417 -0.0166 +vn 0.3171 0.9045 -0.2852 +vn 0.2966 0.8353 -0.4630 +vn 0.6642 -0.7154 0.2169 +vn 0.2935 -0.8791 -0.3756 +vn 0.4899 -0.8698 -0.0583 +vn 0.3707 -0.8923 -0.2578 +vn 0.3849 -0.8976 -0.2146 +vn 0.2108 -0.8941 -0.3951 +vn 0.1086 -0.9586 -0.2634 +vn 0.3998 -0.8349 -0.3783 +vn -0.9999 0.0140 -0.0045 +vn -1.0000 0.0026 -0.0019 +vn -1.0000 -0.0018 -0.0061 +vn -0.9991 -0.0106 -0.0406 +vn -0.9984 -0.0114 -0.0546 +vn -0.9999 0.0169 -0.0027 +vn -0.9998 0.0145 -0.0141 +vn -0.9997 0.0213 -0.0129 +vn -0.9974 0.0652 -0.0291 +vn -0.9983 0.0540 -0.0196 +vn -1.0000 -0.0065 0.0069 +vn -0.9996 -0.0073 0.0289 +vn -0.9997 -0.0219 0.0067 +vn -0.9989 -0.0222 0.0414 +vn -0.9964 -0.0528 0.0656 +vn -0.9937 -0.0597 0.0943 +vn -0.9880 0.0845 0.1290 +vn -0.9825 0.0978 0.1587 +vn -0.9999 0.0118 0.0074 +vn -0.9985 0.0289 0.0474 +vn -1.0000 -0.0002 0.0001 +vn -1.0000 -0.0004 -0.0004 +vn -1.0000 -0.0002 0.0003 +vn -1.0000 0.0000 0.0005 +vn -1.0000 -0.0001 -0.0001 +vn -1.0000 0.0001 -0.0001 +vn -1.0000 0.0006 0.0006 +vn -1.0000 -0.0003 -0.0001 +vn 0.5057 0.0134 0.8626 +vn 0.5007 -0.0004 0.8656 +vn 0.5006 0.0004 0.8657 +vn 0.5005 0.0001 0.8657 +vn 0.4953 0.0011 0.8687 +vn 0.5058 0.0009 0.8627 +vn 0.4922 0.0000 0.8705 +vn 0.5183 -0.0009 0.8552 +vn 0.5187 -0.0016 0.8549 +vn 0.5019 -0.0034 0.8649 +vn 0.4975 0.0009 0.8675 +vn 0.3513 0.7125 0.6074 +vn 0.3534 0.7108 0.6081 +vn 0.3545 0.7100 0.6085 +vn 0.3561 0.7087 0.6090 +vn 0.3757 -0.6993 0.6082 +vn 0.3742 -0.6924 0.6169 +vn 0.3719 -0.6820 0.6297 +vn 0.3696 -0.6722 0.6415 +vn 0.8587 0.1153 -0.4993 +vn 0.8552 -0.0053 -0.5182 +vn 0.8560 -0.0064 -0.5169 +vn 0.7932 0.3651 -0.4874 +vn 0.0477 0.9988 -0.0120 +vn 0.0454 0.9990 0.0011 +vn 0.0208 0.9998 0.0021 +vn 0.0243 0.9996 0.0106 +vn 0.0318 0.9993 -0.0213 +vn -0.2410 0.9623 0.1260 +vn -0.0305 0.9989 0.0361 +vn -0.1483 0.9830 0.1082 +vn -0.8666 -0.0075 0.4989 +vn -0.8612 0.1169 0.4947 +vn -0.8719 0.0006 0.4896 +vn -0.8707 0.0819 0.4849 +vn 0.0437 -0.9977 0.0522 +vn 0.0068 -0.9991 0.0409 +vn -0.0047 -1.0000 0.0060 +vn -0.0166 -0.9998 0.0079 +vn 0.0080 -0.9999 0.0152 +vn 0.0087 -0.9998 0.0182 +vn 0.0182 -0.9996 0.0194 +vn 0.0189 -0.9996 0.0193 +vn -0.5000 -0.0004 -0.8660 +vn -0.5000 -0.0003 -0.8660 +vn -0.5000 -0.0001 -0.8660 +vn -0.5000 0.0000 -0.8661 +vn -0.5001 -0.0000 -0.8660 +vn -0.5001 0.0002 -0.8660 +vn -0.4999 0.0002 -0.8661 +vn -0.4999 -0.0001 -0.8661 +vn -0.5000 -0.0007 -0.8660 +vn -0.4999 -0.0000 -0.8661 +vn -0.5001 -0.0002 -0.8660 +vn -0.5000 -0.0000 -0.8660 +vn -0.5001 0.0001 -0.8660 +vn -0.5001 -0.0001 -0.8660 +vn 0.3533 -0.7097 0.6095 +vn 0.3532 -0.7079 0.6117 +vn 0.3533 -0.7088 0.6106 +vn 0.3534 -0.7102 0.6089 +vn 0.3530 0.7080 0.6117 +vn 0.3531 0.7081 0.6114 +vn 0.3531 0.7079 0.6117 +vn 0.3532 0.7079 0.6116 +vn 0.3535 0.7070 0.6125 +vn 0.5000 -0.0001 0.8660 +vn 0.5000 0.0001 0.8660 +vn 0.5000 -0.0002 0.8660 +vn 0.4999 -0.0000 0.8661 +vn 0.5001 -0.0000 0.8660 +vn 0.5000 0.0000 0.8660 +vn 0.4999 0.0001 0.8661 +vn 0.7878 -0.3820 -0.4832 +vn 0.8775 -0.1440 -0.4575 +vn 0.7500 -0.5264 -0.4006 +vn 0.4140 -0.8613 -0.2945 +vn 0.3809 -0.9085 -0.1717 +vn 0.0419 -0.9959 -0.0807 +vn -0.4964 -0.8157 0.2970 +vn -0.3994 -0.8693 0.2912 +vn -0.4369 -0.8502 0.2938 +vn -0.5428 -0.7850 0.2986 +vn -0.8655 -0.1256 0.4849 +vn -0.8632 -0.0959 0.4956 +vn -0.8443 -0.2098 0.4932 +vn -0.8165 -0.3444 0.4633 +vn -0.8655 -0.3398 0.3681 +vn -0.3275 -0.8802 0.3434 +vn 0.1825 -0.9421 -0.2813 +vn 0.9131 -0.2359 -0.3326 +vn 0.7321 0.3817 -0.5642 +vn 0.1765 0.9843 0.0061 +vn -0.3478 0.9337 0.0847 +vn -0.7477 0.3685 0.5524 +vn 0.4998 -0.0001 0.8661 +vn 0.5001 -0.0002 0.8660 +vn 0.5000 -0.0003 0.8660 +vn 0.4998 0.0000 0.8661 +vn 0.5000 -0.0004 0.8660 +vn 0.4998 0.0007 0.8662 +vn 0.4997 0.0007 0.8662 +vn 0.4998 -0.0001 0.8662 +vn -0.7964 0.4279 0.4275 +vn -0.8085 0.3413 0.4794 +vn -0.7368 0.5033 0.4515 +vn 0.7958 0.3501 -0.4941 +vn 0.7830 0.4609 -0.4176 +vn 0.7922 0.4209 -0.4418 +vn 0.2827 0.9452 -0.1635 +vn 0.1725 0.9737 -0.1489 +vn 0.2377 0.9584 -0.1578 +vn 0.1384 0.9798 -0.1441 +vn -0.4176 0.8455 0.3327 +vn -0.6942 0.6224 0.3615 +vn 0.8225 0.3536 -0.4455 +vn 0.8490 0.1287 -0.5125 +vn -0.7980 -0.2952 0.5254 +vn -0.7854 -0.4191 0.4555 +vn -0.7950 -0.3445 0.4993 +vn -0.7746 -0.4718 0.4212 +vn 0.1063 -0.9942 -0.0183 +vn 0.1862 -0.9709 -0.1504 +vn 0.1492 -0.9848 -0.0887 +vn 0.2241 -0.9507 -0.2145 +vn 0.8967 0.1575 -0.4138 +vn 0.8548 0.2495 -0.4551 +vn 0.8761 0.2059 -0.4360 +vn 0.8238 0.3049 -0.4780 +vn -0.1497 0.9722 0.1799 +vn 0.0690 0.9922 -0.1041 +vn -0.0330 0.9991 0.0282 +vn -0.2200 0.9370 0.2715 +vn -0.7647 0.5357 0.3582 +vn -0.7454 0.4464 0.4951 +vn -0.7144 0.5741 0.4000 +vn 0.7599 0.3420 -0.5528 +vn 0.5168 0.8252 -0.2281 +vn 0.5709 -0.7067 -0.4178 +vn 0.8653 -0.2761 -0.4183 +vn -0.7530 -0.4652 0.4654 +vn -0.7141 -0.5933 0.3715 +vn 0.7921 0.4339 -0.4292 +vn 0.5975 0.6972 -0.3961 +vn 0.6808 -0.6343 -0.3663 +vn 0.4705 -0.8247 -0.3137 +vn 0.5153 -0.7925 -0.3262 +vn 0.7073 -0.6014 -0.3716 +vn -0.5111 0.8251 0.2409 +vn -0.7760 0.3938 0.4927 +vn -0.6814 -0.6273 0.3771 +vn -0.6741 -0.6409 0.3671 +vn -0.7068 -0.5740 0.4134 +vn -0.7114 -0.5633 0.4202 +vn 0.5009 -0.0565 0.8636 +vn 0.4987 -0.0677 0.8641 +vn 0.4989 -0.0669 0.8641 +vn 0.4937 -0.0441 0.8685 +vn 0.4681 0.0578 0.8818 +vn 0.4944 -0.0478 0.8679 +vn 0.4971 -0.0641 0.8654 +vn 0.4989 -0.0698 0.8639 +vn 0.4965 -0.0789 0.8644 +vn 0.4966 -0.0621 0.8658 +vn 0.4883 -0.0354 0.8719 +vn 0.4976 -0.0747 0.8642 +vn 0.4905 -0.1006 0.8656 +vn 0.5611 -0.0491 0.8263 +vn 0.5555 0.0119 0.8314 +vn 0.5635 -0.0230 0.8258 +vn 0.4557 0.0304 0.8896 +vn 0.4523 -0.0198 0.8916 +vn 0.4606 -0.0331 0.8870 +vn 0.4557 -0.0403 0.8892 +vn 0.4298 0.0306 0.9024 +vn 0.4762 0.0593 0.8773 +vn 0.5258 0.0588 0.8486 +vn 0.5248 0.0492 0.8498 +vn 0.5453 -0.0622 0.8359 +vn -0.5002 0.1921 -0.8443 +vn -0.4840 0.2298 -0.8444 +vn -0.4778 0.0739 -0.8754 +vn -0.4953 0.0062 -0.8687 +vn -0.7755 -0.4696 0.4220 +vn -0.7463 -0.5185 0.4173 +vn -0.7794 -0.4626 0.4226 +vn -0.7982 0.3719 0.4739 +vn -0.7886 0.4089 0.4592 +vn -0.7739 0.5723 0.2712 +vn -0.7471 0.5966 0.2932 +vn 0.0256 0.9996 0.0150 +vn 0.0586 0.9982 -0.0122 +vn 0.2603 0.9486 -0.1801 +vn 0.2919 0.9338 -0.2067 +vn 0.7898 0.3745 -0.4859 +vn 0.7578 0.4787 -0.4433 +vn 0.7633 0.4636 -0.4500 +vn 0.7946 0.3538 -0.4933 +vn 0.6520 -0.6614 -0.3707 +vn 0.6327 -0.6910 -0.3497 +vn 0.6485 -0.6669 -0.3669 +vn 0.6302 -0.6946 -0.3470 +vn -0.0878 -0.9870 -0.1344 +vn -0.2056 -0.9712 0.1204 +vn -0.1173 -0.9818 -0.1492 +vn -0.2289 -0.9635 0.1391 +vn -0.7409 -0.5271 0.4163 +vn -0.5640 -0.1017 -0.8195 +vn -0.5632 -0.1008 -0.8201 +vn -0.6041 -0.0356 -0.7961 +vn -0.6028 -0.0186 -0.7976 +vn -0.4321 0.1127 -0.8948 +vn -0.3959 0.0805 -0.9148 +vn -0.3857 -0.0145 -0.9225 +vn -0.4937 0.1319 -0.8596 +vn -0.5661 0.1199 -0.8156 +vn -0.5994 0.0684 -0.7975 +vn -0.3775 -0.0356 -0.9253 +vn -0.4732 -0.1249 -0.8721 +vn -0.4215 -0.1103 -0.9001 +vn -0.5036 -0.1378 -0.8529 +vn -0.7135 -0.5692 0.4085 +vn -0.7330 -0.5490 0.4016 +vn -0.7218 -0.5607 0.4056 +vn -0.8611 0.1267 0.4924 +vn -0.8704 0.1073 0.4805 +vn -0.8670 0.1146 0.4850 +vn -0.8766 0.0938 0.4721 +vn -0.6228 0.6645 0.4130 +vn -0.5744 0.7616 0.2999 +vn -0.5497 0.7971 0.2498 +vn -0.4982 0.8530 0.1554 +vn 0.0440 0.9920 0.1186 +vn 0.3531 0.8689 -0.3469 +vn 0.6035 0.7174 -0.3480 +vn 0.6777 0.5785 -0.4539 +vn 0.8810 0.1576 -0.4461 +vn 0.8265 -0.2061 -0.5238 +vn 0.8064 -0.3953 -0.4398 +vn 0.6684 -0.5673 -0.4811 +vn 0.3283 -0.9358 -0.1286 +vn 0.2919 -0.9477 -0.1290 +vn 0.2634 -0.9560 -0.1291 +vn 0.2192 -0.9671 -0.1291 +vn -0.2568 -0.9530 0.1605 +vn -0.2552 -0.9540 0.1575 +vn -0.2560 -0.9535 0.1590 +vn -0.2543 -0.9545 0.1559 +vn -0.7017 -0.5810 0.4124 +vn -0.8874 -0.2858 0.3618 +vn -0.8426 -0.3507 0.4088 +vn -0.8441 -0.3486 0.4073 +vn -0.7875 -0.4160 0.4547 +vn -0.3375 0.4516 0.8259 +vn -0.2665 0.9144 0.3047 +vn 0.7389 0.3335 -0.5854 +vn 0.7652 0.3699 -0.5270 +vn 0.7579 0.3595 -0.5443 +vn 0.7940 0.4159 -0.4433 +vn 0.2226 -0.9664 -0.1285 +vn 0.3165 -0.9431 -0.1024 +vn 0.3137 -0.9439 -0.1033 +vn 0.3972 -0.9144 -0.0784 +vn -0.2462 -0.8750 -0.4168 +vn -0.0637 -0.4568 -0.8873 +vn -0.1201 -0.4502 -0.8848 +vn 0.0104 -0.4632 -0.8862 +vn 0.0888 -0.4672 -0.8797 +vn 0.3660 0.1535 -0.9179 +vn -0.5061 0.4178 -0.7545 +vn -0.8368 0.5474 0.0130 +vn -0.8711 -0.2811 -0.4026 +vn -0.8707 -0.2773 -0.4063 +vn -0.8719 -0.2870 -0.3969 +vn -0.8723 -0.2910 -0.3929 +vn 0.4390 0.0161 0.8983 +vn 0.4504 -0.0296 0.8923 +vn 0.4618 0.0278 0.8866 +vn 0.4825 0.0594 0.8739 +vn 0.4885 -0.0670 0.8700 +vn 0.5343 -0.0800 0.8415 +vn 0.4994 -0.0541 0.8647 +vn 0.5418 -0.0359 0.8398 +vn 0.5570 0.0243 0.8302 +vn 0.5369 0.0281 0.8432 +vn 0.5116 0.0582 0.8573 +vn -0.5422 0.0359 -0.8395 +vn -0.4913 0.1192 -0.8628 +vn -0.5637 0.1706 -0.8082 +vn -0.5846 0.1475 -0.7978 +vn -0.6606 0.6444 0.3852 +vn -0.8682 0.3081 0.3890 +vn -0.6823 0.6198 0.3878 +vn -0.8863 0.2577 0.3847 +vn -0.3900 0.8894 0.2384 +vn 0.3475 0.8882 -0.3005 +vn 0.3213 0.9253 -0.2014 +vn 0.3312 0.9198 -0.2104 +vn 0.3350 0.8811 -0.3339 +vn 0.8037 0.3906 -0.4488 +vn 0.8319 -0.1638 -0.5302 +vn 0.7667 -0.4818 -0.4244 +vn 0.8276 -0.2203 -0.5163 +vn 0.7446 -0.5350 -0.3992 +vn -0.0284 -0.9991 -0.0328 +vn -0.1752 -0.9789 0.1050 +vn -0.0570 -0.9984 -0.0061 +vn -0.2052 -0.9696 0.1333 +vn -0.8707 -0.1803 0.4575 +vn -0.8399 -0.2835 0.4629 +vn -0.8449 -0.2688 0.4625 +vn -0.8733 -0.1697 0.4567 +vn -0.5848 0.0596 -0.8090 +vn -0.5997 0.0540 -0.7984 +vn -0.5447 0.1183 -0.8303 +vn -0.5041 0.1293 -0.8539 +vn -0.5761 -0.0728 -0.8141 +vn -0.6025 -0.0176 -0.7979 +vn -0.3807 -0.0077 -0.9247 +vn -0.3707 0.0280 -0.9283 +vn -0.3971 -0.0820 -0.9141 +vn -0.4506 -0.1187 -0.8848 +vn -0.4021 0.0968 -0.9105 +vn -0.4979 -0.1269 -0.8579 +vn -0.4470 0.1227 -0.8861 +vn -0.5726 -0.1011 -0.8136 +vn -0.6410 0.6433 0.4187 +vn -0.6321 0.6695 0.3902 +vn -0.6244 0.6894 0.3672 +vn -0.6116 0.7182 0.3319 +vn -0.0614 0.9980 0.0115 +vn -0.0403 0.9991 0.0151 +vn -0.0455 0.9989 0.0142 +vn -0.0237 0.9996 0.0179 +vn 0.6205 0.7170 -0.3176 +vn 0.6348 0.6669 -0.3902 +vn 0.6366 0.6583 -0.4016 +vn 0.6445 0.6077 -0.4641 +vn 0.8462 -0.2041 -0.4922 +vn 0.8901 -0.1037 -0.4438 +vn 0.7908 -0.4350 -0.4305 +vn 0.6546 -0.6164 -0.4377 +vn 0.4147 -0.8829 -0.2201 +vn 0.3124 -0.9256 -0.2139 +vn 0.1820 -0.9829 -0.0264 +vn -0.3538 -0.9243 0.1433 +vn -0.4290 -0.8609 0.2735 +vn -0.5719 -0.7657 0.2945 +vn -0.7403 -0.4728 0.4780 +vn -0.8690 -0.1722 0.4638 +vn -0.8519 0.0371 0.5223 +vn -0.8736 0.1733 0.4547 +vn -0.8592 0.4977 0.1181 +vn -0.0258 0.9191 0.3932 +vn 0.5575 0.4467 -0.6997 +vn 0.9480 -0.2696 -0.1692 +vn -0.1891 -0.9444 -0.2691 +vn -0.4305 -0.6491 0.6272 +vn 0.0756 -0.0277 0.9968 +vn -0.9226 -0.2574 -0.2874 +vn -0.3329 -0.7812 -0.5281 +vn -0.3472 -0.7680 -0.5382 +vn -0.3107 -0.8008 -0.5121 +vn -0.3035 -0.8069 -0.5067 +vn 0.2264 -0.0754 -0.9711 +vn 0.2674 -0.0637 -0.9615 +vn 0.1696 -0.0911 -0.9813 +vn 0.1422 -0.0985 -0.9849 +vn 0.2247 0.8432 -0.4884 +vn -0.5833 0.3854 -0.7149 +vn -1.0000 -0.0008 0.0006 +vn -1.0000 -0.0005 0.0004 +vn -1.0000 0.0010 0.0010 +vn -1.0000 0.0043 0.0032 +vn -1.0000 0.0074 0.0055 +vn -0.0000 -1.0000 -0.0001 +vn -0.0002 -1.0000 -0.0010 +vn 1.0000 0.0001 0.0000 +vn 1.0000 0.0005 -0.0001 +vn -0.0348 -0.5573 -0.8296 +vn 1.0000 -0.0001 -0.0000 +vn 1.0000 0.0002 -0.0000 +vn 1.0000 0.0000 0.0001 +vn 1.0000 0.0004 0.0003 +vn -0.0000 1.0000 -0.0006 +vn -0.0000 1.0000 -0.0010 +vn -0.1300 -0.9683 0.2135 +vn -0.1178 -0.9862 -0.1166 +vn 0.0917 0.9587 0.2694 +vn 0.0759 0.9028 0.4233 +vn 0.1480 0.9125 0.3815 +vn 0.4917 0.0032 -0.8708 +vn 0.4225 0.3758 -0.8248 +vn 0.7356 0.1674 -0.6564 +vn -0.1312 0.9775 0.1650 +vn -0.1311 0.9775 0.1650 +vn -0.4011 0.2156 0.8903 +vn -0.6590 0.1455 0.7380 +vn -0.7901 0.1741 0.5877 +vn 0.8948 0.0287 0.4455 +vn 0.6753 -0.3577 0.6450 +vn 0.9277 -0.1973 0.3169 +vn 0.0852 0.9586 -0.2716 +vn 0.0130 -0.7269 0.6866 +vn 0.0067 -0.7092 0.7049 +vn 0.0080 -0.7105 0.7036 +vn 0.5751 -0.0325 0.8174 +vn 0.4370 -0.0182 0.8993 +vn 0.4502 0.0116 0.8929 +vn 0.0976 -0.0902 -0.9911 +vn 0.0931 -0.0553 -0.9941 +vn 0.1236 0.1589 -0.9795 +vn -0.0869 -0.0968 0.9915 +vn -0.0621 -0.1192 0.9909 +vn -0.0921 -0.1051 0.9902 +vn -0.7092 0.1341 -0.6922 +vn -0.2844 0.3265 0.9014 +vn -0.1598 0.6210 0.7673 +vn -0.4520 0.6677 0.5915 +vn 0.1178 -0.9862 0.1166 +vn 0.2222 -0.9002 0.3744 +vn 0.1178 -0.9862 0.1165 +vn 0.8686 0.4828 0.1114 +vn 0.7281 0.6058 0.3206 +vn 0.8949 0.3168 0.3142 +vn -0.1595 -0.2301 -0.9600 +vn 0.0198 -0.1189 -0.9927 +vn 0.2373 -0.3011 -0.9236 +vn -0.8213 0.4995 0.2757 +vn -0.8676 -0.0417 0.4954 +vn -0.7390 0.5374 0.4062 +vn 0.6056 -0.7758 0.1770 +vn 0.2823 -0.9461 0.1584 +vn 0.5894 -0.8076 0.0169 +vn -0.5437 -0.0855 -0.8349 +vn -0.6058 -0.0881 -0.7907 +vn -0.7798 -0.0914 -0.6194 +vn 0.5893 0.1214 0.7987 +vn 0.7624 0.1392 0.6319 +vn 0.5893 0.1214 0.7988 +vn 0.6701 0.2885 -0.6839 +vn 0.5308 0.0140 -0.8474 +vn 0.4855 0.4107 -0.7718 +vn 0.1397 0.6196 0.7723 +vn 0.0584 0.6674 0.7424 +vn 0.1430 0.4895 0.8602 +vn 0.2111 0.4571 -0.8640 +vn 0.0738 0.4424 -0.8938 +vn -0.0086 0.4632 -0.8862 +vn -0.4258 0.7803 0.4580 +vn -0.2445 0.7592 0.6032 +vn -0.2392 0.7974 0.5540 +vn 0.1808 0.1832 0.9663 +vn 0.5977 0.0676 0.7988 +vn 0.3892 0.4834 0.7841 +vn -0.1867 -0.0134 -0.9823 +vn -0.2096 -0.1935 -0.9585 +vn -0.1810 -0.0193 -0.9833 +vn -0.6322 -0.1636 -0.7573 +vn -0.9200 -0.0355 -0.3902 +vn -0.7493 -0.1186 -0.6515 +vn 0.8934 -0.1144 -0.4345 +vn 0.7432 -0.0829 -0.6639 +vn 0.7220 -0.0300 -0.6913 +vn 0.7356 -0.1674 -0.6564 +vn 0.8783 -0.2980 -0.3737 +vn 0.6914 -0.5867 -0.4216 +vn -0.0776 -0.9957 -0.0515 +vn -0.0776 -0.9957 -0.0514 +vn -0.1856 0.4538 -0.8716 +vn -0.1947 0.0554 -0.9793 +vn -0.4580 0.2668 -0.8480 +vn 0.7123 -0.5182 0.4735 +vn 0.7130 -0.4505 0.5372 +vn 0.6951 -0.4877 0.5283 +vn -0.2526 0.9663 -0.0500 +vn -0.3104 0.9503 -0.0233 +vn -0.1424 0.9857 -0.0898 +vn 0.0057 -0.6630 0.7486 +vn -0.0634 -0.8101 0.5828 +vn 0.2295 -0.7357 0.6373 +vn 0.4176 -0.8279 -0.3745 +vn 0.0922 -0.9389 -0.3316 +vn 0.2343 -0.7780 -0.5829 +vn 0.7533 -0.2003 -0.6265 +vn 0.7538 -0.2064 -0.6238 +vn 0.5778 -0.2105 -0.7885 +vn 0.5279 0.0846 0.8451 +vn 0.2196 0.0184 0.9754 +vn 0.0689 0.1777 0.9817 +vn -0.3459 -0.1588 0.9247 +vn -0.6841 -0.3520 0.6388 +vn -0.3706 -0.4686 0.8019 +vn 0.1446 -0.7119 0.6872 +vn 0.3309 -0.6031 0.7258 +vn 0.0587 -0.5426 0.8380 +vn 0.1075 -0.0003 0.9942 +vn 0.1039 -0.0001 0.9946 +vn 0.1637 -0.0884 0.9825 +vn -0.0724 0.7488 0.6589 +vn -0.0004 0.8417 0.5399 +vn -0.2155 0.8403 0.4975 +vn -0.3988 0.6364 -0.6603 +vn 0.0779 0.5562 -0.8274 +vn -0.1219 0.6306 -0.7665 +vn -0.4929 0.8068 0.3258 +vn -0.2683 0.9613 -0.0626 +vn -0.5479 0.8338 0.0681 +vn -0.9584 -0.1429 0.2471 +vn -0.9488 -0.2525 -0.1897 +vn -0.8167 -0.5755 0.0426 +vn 0.1786 -0.1432 0.9734 +vn -0.1216 -0.1352 0.9833 +vn 0.6626 -0.0301 0.7484 +vn 0.3847 -0.1010 0.9175 +vn 0.9918 0.1109 -0.0636 +vn 0.9918 0.1108 -0.0636 +vn 0.9918 0.1109 -0.0637 +vn -0.2217 0.0202 0.9749 +vn -0.2796 -0.0194 0.9599 +vn -0.3418 -0.0374 0.9390 +vn 0.1229 0.0611 -0.9905 +vn 0.0948 0.1576 -0.9829 +vn 0.1597 0.2195 -0.9625 +vn -0.4379 -0.0096 0.8990 +vn -0.7225 0.1863 0.6658 +vn 0.6706 0.0909 0.7362 +vn 0.8887 0.0925 0.4491 +vn 0.8291 0.0982 0.5504 +vn -0.5801 -0.7422 0.3356 +vn -0.4433 -0.8279 0.3435 +vn -0.4447 -0.6734 0.5906 +vn -0.0602 0.0839 0.9947 +vn 0.0275 0.1212 0.9922 +vn -0.0579 -0.0034 0.9983 +vn -0.9894 0.1395 0.0398 +vn -0.9894 0.1394 0.0399 +vn -0.9894 0.1394 0.0398 +vn 0.0751 -0.9866 -0.1446 +vn 0.1079 -0.9894 -0.0976 +vn 0.0666 -0.9961 -0.0584 +vn -0.6182 -0.7845 -0.0476 +vn -0.7270 -0.6821 0.0790 +vn -0.6301 -0.7459 -0.2160 +vn 0.8705 -0.1195 -0.4775 +vn 0.0904 -0.4107 0.9073 +vn 0.0550 -0.3611 0.9309 +vn 0.1072 -0.2177 0.9701 +vn -0.6823 0.7303 0.0346 +vn -0.4459 0.8685 -0.2163 +vn -0.7500 0.6110 -0.2532 +vn -0.6536 0.0074 0.7568 +vn -0.5477 -0.0778 0.8330 +vn -0.3482 -0.1525 0.9249 +vn 0.1372 0.5304 0.8366 +vn 0.1967 0.6196 0.7599 +vn 0.1868 0.2525 0.9494 +vn 0.4152 0.7458 0.5210 +vn 0.4107 0.6301 0.6590 +vn 0.5397 0.5428 0.6436 +vn 0.1442 -0.9886 0.0439 +vn -0.3197 -0.8939 -0.3141 +vn -0.5651 -0.8168 -0.1165 +vn -0.5833 -0.6970 -0.4171 +vn 0.4960 0.7796 -0.3823 +vn 0.3995 0.7609 -0.5114 +vn 0.3736 0.7834 -0.4967 +vn -0.9079 0.0870 -0.4102 +vn -0.9972 0.0737 0.0146 +vn -0.9966 0.0789 -0.0233 +vn -0.1442 0.9886 -0.0439 +vn -0.1441 0.9886 -0.0439 +vn 0.1926 -0.8290 0.5250 +vn 0.2101 -0.7299 0.6505 +vn -0.0004 -0.8417 0.5399 +vn 0.8904 0.4526 0.0479 +vn 0.8944 0.4172 -0.1615 +vn 0.7853 0.6109 -0.1004 +vn -0.6041 0.2540 -0.7554 +vn -0.6343 -0.1019 -0.7663 +vn -0.7913 -0.0995 -0.6033 +vn -0.0852 0.9586 0.2716 +vn 0.3741 -0.7803 0.5012 +vn 0.1022 -0.7076 0.6992 +vn 0.2985 -0.8560 0.4221 +vn 0.5748 0.5390 -0.6157 +vn 0.6631 0.2028 -0.7206 +vn 0.4648 0.3378 -0.8185 +vn -0.4271 0.7651 -0.4819 +vn -0.2002 0.9512 -0.2347 +vn -0.1367 0.9606 -0.2418 +vn -0.2487 -0.7287 0.6381 +vn 0.2111 0.7242 0.6565 +vn 0.3334 0.6300 0.7014 +vn 0.1719 0.7080 0.6850 +vn -0.0663 -0.8056 0.5887 +vn 0.0884 -0.6880 0.7203 +vn 0.0617 -0.3769 0.9242 +vn 0.0431 -0.1046 0.9936 +vn 0.0118 -0.1725 0.9849 +vn -0.0296 0.3126 0.9494 +vn 0.7113 -0.2271 0.6651 +vn 0.7139 -0.2721 0.6453 +vn 0.7120 -0.3405 0.6141 +vn -0.7421 0.5810 -0.3343 +vn -0.5573 0.7030 -0.4419 +vn -0.7064 0.3726 -0.6018 +vn -0.2431 0.0076 0.9700 +vn -0.6308 -0.0577 0.7738 +vn 0.0781 0.7927 0.6046 +vn 0.0361 0.8001 0.5988 +vn 0.0624 0.8573 0.5110 +vn 0.3403 -0.8517 -0.3985 +vn 0.2652 -0.9451 -0.1910 +vn 0.0315 -0.8717 -0.4891 +vn 0.0810 -0.9366 -0.3409 +vn 0.4258 -0.8530 -0.3017 +vn 0.3636 -0.8924 -0.2673 +vn -0.1300 0.9683 0.2135 +vn -0.2107 0.9558 -0.2048 +vn -0.6233 0.3316 0.7082 +vn -0.6611 -0.0682 0.7472 +vn -0.4119 0.2605 0.8732 +vn 0.8378 -0.4952 -0.2301 +vn 0.9933 -0.0246 -0.1127 +vn 0.7979 -0.1950 0.5703 +vn 0.9565 0.1333 0.2593 +vn 0.8309 -0.1715 0.5293 +vn 0.4621 0.0888 0.8824 +vn 0.6270 0.1103 0.7712 +vn 0.5966 0.0439 0.8013 +vn 0.0852 -0.9586 -0.2716 +vn -0.3211 -0.7671 -0.5554 +vn -0.1495 -0.7819 -0.6052 +vn -0.1270 -0.9366 -0.3267 +vn 0.1552 0.1095 -0.9818 +vn 0.1549 0.1943 -0.9686 +vn 0.1316 0.0418 -0.9904 +vn 0.1300 0.9683 -0.2134 +vn 0.1300 0.9683 -0.2135 +vn 0.5204 0.7247 -0.4516 +vn 0.3339 0.7406 -0.5831 +vn 0.4640 0.7564 -0.4611 +vn 0.6707 0.2101 -0.7114 +vn 0.8474 0.1964 -0.4932 +vn 0.7524 0.2017 -0.6271 +vn 1.0000 -0.0006 0.0000 +vn -0.1334 -0.0050 -0.9911 +vn -0.1682 0.0044 -0.9857 +vn 0.5893 -0.1214 0.7987 +vn 0.5893 -0.1214 0.7988 +vn 0.7360 -0.2385 -0.6335 +vn 0.3802 -0.2475 -0.8912 +vn 0.7361 -0.2385 -0.6335 +vn -0.0863 -0.1307 -0.9877 +vn 0.0258 -0.1348 -0.9905 +vn 0.0250 -0.1409 -0.9897 +vn 0.2556 -0.6530 0.7129 +vn 0.5325 -0.6390 0.5551 +vn 0.2627 -0.6527 0.7106 +vn -0.9632 0.0450 0.2652 +vn -0.8856 0.4097 0.2189 +vn -0.9162 0.3985 0.0409 +vn 0.1941 -0.2834 -0.9392 +vn 0.1312 0.9775 -0.1650 +vn 0.1311 0.9775 -0.1650 +vn 0.0180 0.9998 -0.0080 +vn 0.0177 0.9998 -0.0065 +vn 0.0010 0.9982 -0.0597 +vn 0.6790 0.6717 -0.2963 +vn 0.8148 0.5633 -0.1368 +vn 0.7122 0.5387 -0.4501 +vn 0.5140 -0.8576 -0.0148 +vn -0.1476 -0.9879 -0.0482 +vn -0.1476 -0.9879 -0.0483 +vn -0.1304 -0.9906 -0.0419 +vn 0.5853 -0.6897 -0.4263 +vn 0.6257 -0.5580 -0.5451 +vn 0.7396 -0.6096 -0.2852 +vn 0.1302 -0.9768 -0.1699 +vn 0.1475 -0.9509 -0.2721 +vn 0.0923 -0.3183 -0.9435 +vn 0.0799 -0.1046 -0.9913 +vn 0.1464 -0.1526 -0.9774 +vn -0.3641 0.1450 0.9200 +vn -0.1189 0.5215 0.8449 +vn -0.3706 0.4687 0.8019 +vn -0.2800 -0.9079 -0.3119 +vn -0.4065 -0.8730 -0.2695 +vn -0.5427 -0.7096 -0.4493 +vn 0.1638 0.0878 0.9826 +vn 0.1628 0.3560 0.9202 +vn 0.1855 0.3989 0.8980 +vn -0.2846 -0.1693 -0.9436 +vn -0.5716 -0.0963 -0.8148 +vn -0.0852 -0.1986 -0.9764 +vn 0.1063 0.2088 0.9722 +vn 0.0965 0.3235 0.9413 +vn -0.2261 0.0327 0.9736 +vn -0.9518 0.2261 0.2071 +vn -0.6738 0.6156 0.4087 +vn -0.7635 -0.2311 0.6030 +vn -0.9821 -0.1431 0.1226 +vn 0.9912 0.1262 0.0395 +vn 0.9676 0.0900 0.2360 +vn 0.9599 0.0749 0.2700 +vn 0.9540 -0.0592 -0.2940 +vn 0.7107 0.6480 -0.2740 +vn 0.8173 0.5076 -0.2729 +vn 0.6385 0.5605 -0.5275 +vn 0.1867 0.7028 -0.6864 +vn 0.1815 0.7290 -0.6601 +vn 0.1784 0.4598 -0.8699 +vn 0.0897 -0.1275 0.9878 +vn -0.7887 -0.0199 0.6144 +vn -0.8116 -0.0279 0.5836 +vn -0.6511 0.0121 0.7589 +vn 0.4304 0.8975 -0.0962 +vn 0.6533 0.7566 -0.0263 +vn 0.5434 0.8071 -0.2308 +vn 0.4726 0.5947 -0.6503 +vn 0.5493 0.6823 -0.4824 +vn -0.2957 0.5625 -0.7721 +vn -0.5387 0.5966 -0.5949 +vn -0.2943 0.6970 -0.6539 +vn 0.5979 0.6497 0.4696 +vn 0.5603 0.7963 0.2278 +vn 0.4347 0.7836 0.4439 +vn 0.4674 -0.1332 0.8739 +vn 0.1286 -0.1970 0.9719 +vn 0.0542 -0.2144 0.9752 +vn -0.1325 -0.1727 0.9760 +vn -0.0586 -0.1884 0.9803 +vn -0.0627 -0.0350 0.9974 +vn 0.8417 -0.1262 0.5250 +vn 0.8511 -0.0748 0.5196 +vn 0.7200 -0.2142 0.6601 +vn -0.0776 0.9957 -0.0515 +vn 0.4447 -0.7910 -0.4201 +vn 0.6669 -0.7185 -0.1974 +vn 0.3782 -0.9236 -0.0627 +vn 0.5370 -0.1005 0.8376 +vn 0.7005 -0.0350 0.7128 +vn 0.7005 -0.0289 0.7131 +vn 0.6808 0.0053 -0.7325 +vn 0.4879 0.0448 -0.8718 +vn 0.4190 0.0604 -0.9060 +vn -0.2277 -0.7002 -0.6766 +vn -0.2377 -0.6696 -0.7037 +vn -0.2283 -0.7234 -0.6516 +vn -0.4966 0.8678 0.0186 +vn -0.4633 0.8490 -0.2542 +vn -0.0493 -0.2489 -0.9673 +vn -0.5545 -0.0718 -0.8290 +vn -0.1556 -0.6122 -0.7752 +vn -0.3653 -0.6157 -0.6982 +vn 0.1786 -0.8955 -0.4076 +vn 0.1565 -0.9403 -0.3022 +vn 0.1467 -0.3048 -0.9410 +vn 0.0427 0.8720 0.4876 +vn 0.2341 0.9597 0.1556 +vn -0.0843 0.8995 0.4287 +vn 0.5131 0.8532 0.0938 +vn -0.1136 0.2067 0.9718 +vn -0.1310 0.0659 0.9892 +vn -0.1781 0.2069 0.9620 +vn 0.0989 0.7692 -0.6313 +vn 0.1149 0.8942 -0.4326 +vn 0.0743 0.8716 -0.4846 +vn 0.7931 0.5063 0.3388 +vn 0.6563 0.5502 0.5163 +vn 0.7361 0.4185 0.5320 +vn 0.0813 0.9406 -0.3296 +vn 0.2343 0.7758 -0.5859 +vn -0.0098 0.7895 -0.6136 +vn 0.2367 -0.9650 0.1126 +vn 0.1306 0.9732 -0.1894 +vn 0.1054 0.9910 -0.0819 +vn 0.1086 0.9882 -0.1077 +vn -0.7279 -0.0918 -0.6795 +vn -0.7279 -0.0919 -0.6795 +vn -0.0754 0.6935 0.7165 +vn 0.3192 0.6376 0.7011 +vn -0.0765 0.7288 0.6805 +vn 0.0950 0.9952 0.0221 +vn 0.1404 0.9746 -0.1744 +vn 0.0711 0.9897 0.1241 +vn 0.7031 -0.7032 0.1055 +vn 0.5795 -0.8139 0.0419 +vn 0.6751 -0.7256 -0.1335 +vn -0.2487 0.7287 0.6381 +vn 0.0057 0.6630 0.7486 +vn -0.0634 0.8102 0.5828 +vn -0.7361 0.2385 0.6335 +vn -0.7360 0.2385 0.6335 +vn -0.5557 0.2495 0.7931 +vn 0.7264 -0.3472 -0.5931 +vn 0.7095 -0.4128 -0.5712 +vn 0.7145 -0.4136 -0.5642 +vn -0.6826 0.0152 -0.7306 +vn -0.6646 0.2058 -0.7183 +vn -0.5358 0.1231 -0.8353 +vn -0.8360 0.1585 0.5254 +vn -0.6129 0.3810 0.6922 +vn -0.9781 0.1578 0.1359 +vn 0.0776 0.9957 0.0515 +vn -0.8433 -0.0038 -0.5375 +vn -0.7973 -0.0291 -0.6029 +vn -0.8273 -0.5303 -0.1851 +vn -0.7664 -0.5321 -0.3599 +vn -0.6886 -0.6830 -0.2435 +vn -0.1845 -0.8517 0.4905 +vn 0.0768 -0.8793 0.4701 +vn -0.0812 0.9285 -0.3623 +vn -0.1169 0.9785 -0.1699 +vn -0.0475 0.9865 -0.1566 +vn 0.2057 0.2081 0.9562 +vn 0.5091 -0.1876 0.8400 +vn 0.4617 0.1583 0.8728 +vn -0.0852 -0.9586 0.2716 +vn 0.3615 0.3809 0.8510 +vn 0.6510 0.0140 -0.7589 +vn 0.8614 -0.2195 -0.4580 +vn 0.6871 -0.0421 -0.7254 +vn 0.2261 -0.0327 -0.9736 +vn -0.1123 -0.5165 -0.8489 +vn 0.1709 -0.5955 -0.7850 +vn 0.0509 -0.6373 -0.7689 +vn -0.4968 -0.1695 -0.8512 +vn -0.7284 0.1249 -0.6736 +vn -0.5696 0.1879 -0.8001 +vn 0.0776 -0.9957 0.0515 +vn 0.6752 0.5976 0.4324 +vn 0.9400 0.0280 0.3400 +vn 0.9549 0.0726 0.2880 +vn 0.8561 -0.0012 0.5168 +vn 0.1442 0.9886 0.0439 +vn -0.9934 -0.0905 -0.0710 +vn -0.8850 -0.4251 -0.1898 +vn -0.8332 -0.5510 -0.0468 +vn 0.1178 0.9862 0.1166 +vn 0.2537 0.9346 -0.2493 +vn -0.2898 -0.8046 -0.5182 +vn -0.0485 -0.8900 -0.4534 +vn -0.2306 -0.8588 -0.4574 +vn 0.4519 -0.0104 -0.8920 +vn 0.1472 -0.0396 -0.9883 +vn 0.2616 -0.0244 -0.9649 +vn -0.7157 0.6791 0.1630 +vn -0.7091 0.6847 -0.1684 +vn -0.8127 0.5808 0.0471 +vn 0.5975 -0.6830 0.4201 +vn 0.4991 -0.6669 0.5533 +vn 0.3788 -0.7985 0.4679 +vn 0.9845 0.1664 0.0547 +vn -0.6647 0.1484 -0.7323 +vn -0.9024 0.0413 -0.4289 +vn -0.9187 0.0300 -0.3938 +vn 0.5278 0.8459 -0.0770 +vn 0.5708 0.1030 0.8146 +vn 0.5708 0.1029 0.8146 +vn -0.7789 0.3442 -0.5243 +vn 0.7504 -0.4061 -0.5215 +vn 0.8169 -0.4290 -0.3855 +vn 0.7158 -0.5511 -0.4289 +vn 0.0269 0.7798 -0.6254 +vn 0.0313 0.5136 -0.8575 +vn -0.0999 0.5398 -0.8358 +vn -0.1941 -0.2834 0.9392 +vn 0.7691 0.0942 -0.6322 +vn 0.9828 0.1429 -0.1173 +vn 0.8967 0.1123 -0.4282 +vn -0.4971 -0.7662 -0.4074 +vn -0.0827 -0.8816 0.4646 +vn -0.0167 -0.9165 0.3998 +vn -0.0580 -0.8619 0.5037 +vn 0.5254 -0.1214 -0.8422 +vn 0.5980 -0.3643 -0.7139 +vn 0.0707 -0.6632 0.7451 +vn 0.1152 -0.8125 0.5714 +vn 0.1308 -0.6151 0.7775 +vn 0.0939 -0.8966 0.4327 +vn -0.1095 -0.9175 0.3824 +vn -0.3318 -0.8838 0.3300 +vn -0.2742 0.7770 -0.5666 +vn -0.1103 0.6718 -0.7325 +vn 0.5708 -0.1030 0.8146 +vn 0.7196 0.6651 0.1996 +vn 0.6695 0.6805 0.2978 +vn 0.1456 -0.8269 -0.5432 +vn -0.1399 -0.8640 -0.4836 +vn 0.0596 -0.7228 -0.6884 +vn -0.7860 -0.1365 -0.6030 +vn -0.7624 -0.1392 -0.6319 +vn -0.9487 -0.1502 -0.2781 +vn 0.0766 -0.2339 -0.9692 +vn 0.0625 -0.3010 -0.9516 +vn 0.0957 -0.4428 -0.8915 +vn 0.0356 -0.7635 0.6449 +vn 0.2809 -0.8022 0.5268 +vn 0.3563 -0.3924 0.8480 +vn -0.1045 -0.6393 -0.7618 +vn 0.1408 -0.6764 -0.7229 +vn 0.0826 -0.1088 -0.9906 +vn 0.0574 -0.0411 -0.9975 +vn 0.0381 -0.2533 -0.9666 +vn 1.0000 0.0010 0.0000 +vn -0.0075 0.6029 0.7977 +vn 0.0205 0.2656 0.9639 +vn 0.2063 0.3537 0.9123 +vn -0.3528 0.8038 -0.4790 +vn -0.5334 0.7690 -0.3524 +vn -0.5054 0.8131 -0.2890 +vn 0.6751 0.7256 -0.1335 +vn 0.7145 0.6943 0.0863 +vn 0.1517 -0.9861 0.0672 +vn 0.1987 -0.9798 -0.0221 +vn 0.5790 -0.8031 0.1407 +vn -0.7636 -0.0904 -0.6393 +vn -0.2343 -0.2373 -0.9428 +vn -0.5542 -0.3441 -0.7580 +vn -0.1311 -0.9775 0.1650 +vn -0.0077 0.9070 0.4212 +vn -0.0537 0.9178 0.3934 +vn -0.1294 0.7628 0.6336 +vn -0.6665 -0.7281 0.1600 +vn -0.4973 -0.8233 0.2735 +vn -0.5983 -0.7365 0.3156 +vn 0.7279 0.0919 0.6795 +vn 0.2251 0.0735 0.9715 +vn 0.2169 0.0101 0.9762 +vn 0.2349 0.0797 0.9687 +vn -0.1679 0.6900 -0.7041 +vn -0.1178 0.9862 -0.1166 +vn -0.5708 -0.1029 -0.8146 +vn -0.1297 0.9858 0.1064 +vn -0.1199 0.9671 0.2245 +vn -0.1561 0.9852 0.0702 +vn -0.9918 -0.1108 0.0636 +vn -0.4175 0.8495 0.3227 +vn -0.5617 0.7048 0.4334 +vn -0.2659 0.6956 0.6674 +vn 0.0703 -0.6986 -0.7121 +vn 0.0261 -0.5908 -0.8064 +vn 0.0714 -0.7635 -0.6418 +vn 0.3801 -0.2475 -0.8912 +vn 0.0307 -0.2191 -0.9752 +vn -0.1442 -0.9886 -0.0439 +vn 0.0550 -0.9857 0.1593 +vn -0.0564 -0.9651 0.2556 +vn 0.0938 -0.9906 0.0998 +vn 0.1010 -0.9842 0.1457 +vn 0.0532 -0.9737 0.2216 +vn -0.1472 -0.1982 0.9691 +vn -0.1850 -0.1902 0.9642 +vn -0.2144 -0.0767 0.9737 +vn -0.5904 0.7318 -0.3405 +vn 0.6627 -0.7412 -0.1070 +vn 0.5628 -0.7872 -0.2520 +vn 0.8404 -0.4604 -0.2861 +vn -0.7683 0.4725 0.4318 +vn -0.7231 0.0806 0.6860 +vn -0.6717 0.1771 0.7193 +vn -0.7351 -0.5938 0.3272 +vn -0.5347 -0.6641 0.5225 +vn -0.6356 -0.5982 0.4880 +vn -0.3081 0.8966 -0.3180 +vn -0.5710 0.8047 -0.1623 +vn 0.3682 -0.2026 -0.9074 +vn 0.4043 -0.2031 -0.8918 +vn 0.3444 0.8116 0.4718 +vn 0.5122 0.6218 0.5924 +vn 0.5031 0.6351 0.5861 +vn 0.4714 -0.6287 -0.6184 +vn 0.2568 -0.6500 -0.7153 +vn 0.3784 -0.4248 -0.8224 +vn 0.8814 -0.1561 -0.4458 +vn 0.9755 0.1369 -0.1723 +vn 0.9831 0.1070 -0.1485 +vn -0.7442 -0.6568 0.1218 +vn -0.0037 -0.7874 -0.6164 +vn -0.0170 0.9972 0.0728 +vn -0.5224 -0.0383 0.8519 +vn -0.7482 -0.4482 -0.4893 +vn -0.6379 -0.5675 -0.5206 +vn -0.6271 0.5001 0.5972 +vn -0.5933 0.0795 0.8011 +vn -0.3391 0.4960 0.7994 +vn 0.9498 0.1835 -0.2535 +vn 0.7361 0.2385 -0.6335 +vn 0.7360 0.2385 -0.6335 +vn -0.9238 -0.1052 -0.3681 +vn -0.6937 -0.1930 -0.6939 +vn -0.7485 -0.5732 -0.3334 +vn 0.0579 -0.6152 -0.7863 +vn 0.0603 -0.6210 -0.7815 +vn 0.0678 -0.6244 -0.7781 +vn -0.0851 -0.9586 0.2716 +vn 0.4623 -0.8724 -0.1589 +vn 0.5424 -0.8390 -0.0440 +vn 0.3940 -0.6071 -0.6900 +vn 0.3337 -0.6996 -0.6318 +vn -0.1892 -0.2363 0.9531 +vn -0.5557 -0.2495 0.7931 +vn -0.4906 -0.2564 0.8328 +vn 0.2132 -0.0303 0.9766 +vn -0.1657 0.0131 0.9861 +vn -0.2320 -0.6935 0.6821 +vn -0.2721 -0.7808 -0.5624 +vn -0.2037 -0.9453 -0.2546 +vn -0.4523 -0.8379 -0.3055 +vn 0.7258 0.1363 0.6743 +vn 0.8817 0.2200 0.4175 +vn 0.9652 0.0185 0.2610 +vn -0.2683 -0.9613 -0.0626 +vn -0.3081 -0.8966 -0.3180 +vn -0.0263 -0.9306 -0.3652 +vn -0.5940 -0.7893 -0.1556 +vn -0.5491 -0.7591 -0.3497 +vn -0.5534 -0.8270 0.0988 +vn -0.1199 -0.3291 0.9366 +vn -0.0885 -0.2768 0.9568 +vn -0.3192 -0.0936 0.9431 +vn 0.0930 0.8192 -0.5659 +vn 0.0918 0.9829 -0.1595 +vn 0.1567 0.6899 -0.7068 +vn 0.9873 -0.1559 -0.0294 +vn 0.8710 -0.2658 -0.4131 +vn 0.9268 -0.2142 -0.3084 +vn -0.2294 -0.0206 0.9731 +vn -0.2221 0.1316 0.9661 +vn -0.2125 0.0746 0.9743 +vn 0.5171 -0.8533 -0.0664 +vn 0.4807 -0.8468 0.2279 +vn 0.4700 -0.7663 0.4381 +vn 0.8624 -0.3532 0.3627 +vn 0.5323 -0.6619 0.5277 +vn 0.2832 -0.8701 0.4035 +vn -0.7128 0.1407 -0.6871 +vn -0.0839 0.9771 -0.1955 +vn -0.1503 0.9851 -0.0836 +vn 0.0469 0.6831 -0.7288 +vn 0.0776 0.4275 -0.9007 +vn 0.3401 0.0293 -0.9399 +vn 0.2694 0.0147 -0.9629 +vn 0.0434 0.2909 -0.9558 +vn 0.1145 -0.0260 0.9931 +vn 0.0633 -0.0059 0.9980 +vn 0.1825 -0.1645 0.9693 +vn -0.0661 -0.5763 -0.8146 +vn -0.1702 -0.4478 -0.8778 +vn -0.0139 -0.4472 -0.8943 +vn 0.2312 -0.6828 -0.6931 +vn 0.7314 0.6609 -0.1683 +vn 0.4927 0.8097 -0.3188 +vn 0.4772 0.8778 -0.0423 +vn 0.1349 -0.9640 -0.2292 +vn 0.1204 -0.9828 -0.1403 +vn -0.6130 0.0508 -0.7884 +vn -0.6117 0.0414 -0.7900 +vn -0.8693 -0.0339 -0.4931 +vn 0.4525 0.7514 0.4802 +vn 0.5057 0.7860 0.3556 +vn 0.5246 0.8326 0.1776 +vn 0.5132 -0.8214 0.2490 +vn 0.6775 -0.6970 0.2348 +vn 0.5616 0.2719 -0.7815 +vn 0.2721 0.2846 -0.9192 +vn 0.2316 0.2920 -0.9279 +vn -0.2602 0.5470 -0.7956 +vn -0.3018 0.2886 -0.9086 +vn -0.5030 0.2661 -0.8223 +vn -0.1131 0.9377 0.3284 +vn -0.0650 0.8516 0.5202 +vn 0.0338 0.2628 -0.9643 +vn 0.0546 0.1186 -0.9914 +vn -0.1009 0.1343 -0.9858 +vn 0.2401 0.7978 0.5531 +vn -0.4930 0.1464 -0.8577 +vn -0.4228 0.1115 -0.8993 +vn -0.7226 0.2713 -0.6358 +vn -0.9973 -0.0596 -0.0433 +vn -0.9989 -0.0178 0.0431 +vn -0.9958 -0.0173 -0.0894 +vn 0.1410 -0.5564 -0.8189 +vn -0.0536 -0.6869 -0.7248 +vn -0.2447 -0.6087 -0.7547 +vn 0.9632 -0.0537 -0.2633 +vn 0.8614 0.2195 -0.4580 +vn 0.9785 0.0379 -0.2030 +vn 0.4650 0.7757 -0.4268 +vn -0.0738 0.0331 0.9967 +vn -0.1460 -0.0613 0.9874 +vn -0.1692 -0.0474 0.9844 +vn -0.6744 -0.3631 0.6429 +vn -0.8118 -0.3164 0.4908 +vn -0.6521 -0.4781 0.5884 +vn 0.3155 -0.1262 0.9405 +vn 0.1746 -0.1862 0.9669 +vn -0.2261 -0.0327 0.9736 +vn -0.6205 0.0078 0.7841 +vn -0.6205 0.0078 0.7842 +vn -0.9790 0.0970 -0.1795 +vn -0.9444 0.0519 -0.3247 +vn -0.9914 0.1294 -0.0191 +vn -0.0134 0.9785 0.2060 +vn 0.0431 0.9720 0.2309 +vn 0.5190 0.6540 0.5504 +vn 0.5602 0.7630 0.3225 +vn -0.0007 -0.7576 0.6527 +vn -0.0040 -0.6445 0.7646 +vn -0.0095 -0.6703 0.7420 +vn 0.7428 -0.3096 -0.5937 +vn 0.7272 -0.3015 -0.6167 +vn -0.4089 0.5061 -0.7594 +vn -0.5326 0.3001 -0.7914 +vn -0.3956 -0.6077 0.6886 +vn -0.5825 -0.6513 0.4863 +vn -0.7451 -0.6138 0.2609 +vn 0.7057 0.6566 0.2661 +vn 0.7093 0.5893 0.3868 +vn 0.7063 0.6018 0.3728 +vn -0.5512 -0.2813 0.7855 +vn -0.1993 0.7533 -0.6268 +vn -0.2342 0.6390 -0.7327 +vn -0.1576 0.6268 -0.7630 +vn -0.5228 0.8068 0.2752 +vn -0.6918 0.6959 0.1928 +vn -0.6746 0.5267 0.5172 +vn -0.4079 0.4893 -0.7708 +vn -0.1658 0.6334 -0.7558 +vn -0.3206 0.2153 -0.9224 +vn 0.7068 0.3394 -0.6207 +vn 0.5504 -0.0266 -0.8344 +vn 0.5905 0.2853 -0.7549 +vn 0.0484 -0.7449 -0.6655 +vn 0.0473 -0.7410 -0.6699 +vn 0.0394 -0.6585 -0.7515 +vn -0.4519 -0.6719 -0.5868 +vn -0.4985 -0.5340 -0.6829 +vn 0.0757 0.3874 0.9188 +vn -0.0392 0.3695 0.9284 +vn 0.0163 0.3348 0.9421 +vn 0.0600 0.9869 -0.1498 +vn 0.0871 0.9449 -0.3157 +vn 0.1254 0.9444 -0.3040 +vn -0.9120 0.1435 -0.3843 +vn -0.9934 0.0905 -0.0710 +vn -0.8685 0.4430 -0.2226 +vn -0.0553 0.8232 0.5651 +vn -0.0033 0.8428 0.5382 +vn 0.0243 0.0023 -0.9997 +vn 0.0269 0.0000 -0.9996 +vn 0.0218 0.0047 -0.9998 +vn 0.1236 0.7907 0.5995 +vn 0.0667 0.6834 0.7270 +vn -0.7668 -0.4628 0.4448 +vn 0.1311 -0.9775 -0.1650 +vn 0.1312 -0.9775 -0.1650 +vn -0.0256 -0.7556 0.6545 +vn -0.0379 -0.6475 0.7611 +vn -0.0874 -0.6302 0.7715 +vn -0.4170 0.8300 0.3704 +vn -0.4812 0.7547 0.4459 +vn -0.2633 0.7591 0.5953 +vn -0.4683 0.7907 0.3942 +vn -0.3108 0.8272 0.4681 +vn -0.5310 0.8145 0.2337 +vn -0.0823 0.9899 0.1152 +vn -0.1534 0.9875 0.0368 +vn -0.0894 0.9949 0.0462 +vn -0.0852 -0.9586 0.2717 +vn -0.5280 -0.7408 -0.4153 +vn -0.7263 -0.6702 -0.1527 +vn -0.7369 -0.4370 -0.5158 +vn 0.1300 -0.9683 -0.2134 +vn 0.3041 -0.8403 -0.4488 +vn 0.4223 -0.8681 -0.2609 +vn -0.4307 0.2358 0.8711 +vn -0.4527 0.0512 0.8902 +vn -0.2026 0.5669 0.7985 +vn -0.1841 0.3824 0.9055 +vn -0.2366 0.3488 0.9069 +vn 0.0794 -0.9964 0.0310 +vn 0.0424 -0.9939 0.1021 +vn 0.0689 -0.9797 0.1884 +vn -0.0675 -0.4623 -0.8842 +vn -0.1661 -0.1247 -0.9782 +vn -0.1311 -0.2555 -0.9579 +vn -0.7727 -0.2746 -0.5723 +vn -0.7310 -0.3101 -0.6079 +vn -0.0067 -0.5068 0.8620 +vn -0.1189 -0.5215 0.8449 +vn 0.1199 -0.9182 0.3776 +vn 0.1439 -0.8578 0.4934 +vn 0.0837 -0.9601 0.2668 +vn 0.1423 0.5560 -0.8189 +vn 0.7079 -0.0595 -0.7038 +vn 0.7087 0.0826 -0.7007 +vn 0.7097 0.0439 -0.7031 +vn 0.0982 0.8522 0.5140 +vn -0.0314 0.9777 0.2078 +vn 0.0634 0.9768 0.2043 +vn -0.9886 -0.1457 0.0381 +vn -0.9826 -0.1435 -0.1176 +vn 0.4167 -0.2488 -0.8743 +vn 0.4167 -0.2487 -0.8743 +vn -0.2628 0.9110 0.3179 +vn -0.5321 0.7781 0.3338 +vn -0.4202 0.5501 0.7217 +vn -0.5901 0.3387 0.7329 +vn -0.5760 0.6273 -0.5242 +vn -0.3490 0.6849 -0.6396 +vn -0.5325 0.4928 -0.6882 +vn 0.1257 0.0257 -0.9917 +vn 0.4655 -0.0292 -0.8846 +vn 0.2393 0.0030 -0.9709 +vn -0.1787 -0.9827 -0.0488 +vn -0.1827 -0.9832 -0.0038 +vn -0.1837 -0.9827 -0.0236 +vn 0.0296 0.1187 -0.9925 +vn 0.2668 0.0819 -0.9603 +vn -0.1570 0.9492 -0.2725 +vn -0.1396 0.9863 -0.0879 +vn -0.0959 0.9814 0.1660 +vn -0.6758 0.3372 0.6554 +vn -0.5172 0.7539 0.4053 +vn -0.1105 0.9939 0.0041 +vn -0.1149 0.9705 -0.2118 +vn -0.1126 0.9910 -0.0717 +vn 0.0852 -0.9586 -0.2717 +vn 0.4345 0.6617 0.6111 +vn 0.3956 0.7581 0.5184 +vn -0.2441 0.9637 -0.1085 +vn -0.2856 0.9368 -0.2018 +vn -0.5237 0.8202 -0.2304 +vn 0.7314 -0.6609 -0.1683 +vn 0.4772 -0.8778 -0.0423 +vn 0.4927 -0.8097 -0.3188 +vn -0.0064 0.0434 0.9990 +vn -0.0065 0.0434 0.9990 +vn 0.7005 0.0351 0.7128 +vn 0.5301 0.1185 0.8396 +vn 0.0799 -0.0191 -0.9966 +vn 0.2287 -0.0061 -0.9735 +vn -0.0141 0.0144 -0.9998 +vn 0.0642 -0.9949 0.0773 +vn 0.1044 -0.9926 0.0621 +vn 0.0914 -0.9866 0.1355 +vn -0.4396 0.5235 -0.7299 +vn 0.9967 0.0589 0.0561 +vn 0.9470 -0.1285 0.2945 +vn 0.9916 -0.0086 0.1288 +vn 0.0265 0.1317 -0.9909 +vn 0.8949 -0.3168 0.3142 +vn 0.7136 -0.6215 0.3233 +vn 0.8686 -0.4828 0.1114 +vn 0.9958 -0.0721 0.0568 +vn 0.9659 -0.1435 -0.2156 +vn 0.9771 -0.0235 0.2113 +vn -0.2452 -0.5293 -0.8123 +vn -0.0993 -0.5373 -0.8376 +vn -0.2537 -0.6111 -0.7498 +vn -0.6293 0.5720 -0.5261 +vn -0.3084 0.6321 -0.7108 +vn 0.2025 -0.1296 0.9707 +vn 0.2356 -0.1640 0.9579 +vn 0.1170 0.0762 0.9902 +vn -0.1485 -0.0150 0.9888 +vn -0.1383 -0.0812 0.9871 +vn -0.1122 0.1200 0.9864 +vn 0.2165 -0.3974 -0.8917 +vn 0.3858 -0.5206 -0.7617 +vn 0.3741 0.7803 0.5012 +vn 0.4784 0.6827 0.5524 +vn 0.6837 0.6497 0.3323 +vn -0.0263 0.9306 -0.3652 +vn 0.0385 -0.0027 0.9993 +vn 0.1111 0.0506 0.9925 +vn 0.0353 -0.0689 0.9970 +vn -0.5190 0.8489 -0.1000 +vn -0.6345 0.7157 -0.2919 +vn -0.6950 0.7082 -0.1238 +vn -0.4632 0.0443 -0.8851 +vn -0.5605 -0.0035 -0.8282 +vn -0.5676 0.0048 -0.8233 +vn -0.3834 -0.1023 -0.9179 +vn -0.3905 -0.0496 -0.9193 +vn -0.2491 0.1225 -0.9607 +vn -0.2908 0.0831 -0.9532 +vn -0.2308 -0.0790 -0.9698 +vn -0.2730 -0.1277 -0.9535 +vn -0.1597 0.0212 -0.9869 +vn 0.6081 0.7828 0.1321 +vn 0.7510 0.6590 -0.0412 +vn 0.7276 0.6849 -0.0395 +vn -0.0819 -0.0002 -0.9966 +vn 0.1038 0.1160 -0.9878 +vn 0.0225 -0.0179 -0.9996 +vn 0.0556 -0.0349 -0.9978 +vn -0.0216 0.0682 -0.9974 +vn -0.0111 0.0151 -0.9998 +vn -0.2075 0.3259 0.9224 +vn -0.2353 0.2440 0.9408 +vn 0.0677 -0.1084 -0.9918 +vn 0.1401 0.0186 -0.9900 +vn 0.1832 -0.0078 -0.9830 +vn 0.9523 -0.1266 -0.2778 +vn 0.0850 -0.6328 -0.7696 +vn 0.0863 -0.8136 -0.5750 +vn 0.0865 -0.6486 -0.7562 +vn -0.0235 0.9966 -0.0791 +vn -0.0203 0.9965 -0.0808 +vn -0.0101 0.9864 -0.1641 +vn 0.1134 -0.9916 0.0628 +vn 0.1134 -0.9928 -0.0372 +vn 0.1129 -0.9920 -0.0562 +vn 0.0148 0.1126 0.9935 +vn 0.0897 0.1275 0.9878 +vn -0.2280 0.0867 0.9698 +vn 0.4301 -0.0000 -0.9028 +vn 0.4755 -0.0006 -0.8797 +vn 0.4238 -0.0003 -0.9058 +vn 0.1477 0.8576 0.4927 +vn 0.1195 0.9253 0.3600 +vn 0.8116 0.0202 0.5839 +vn 0.6052 -0.0129 0.7960 +vn -0.2804 0.7039 -0.6527 +vn -0.3822 0.7059 -0.5963 +vn -0.2657 0.7026 -0.6601 +vn -0.6117 -0.0414 -0.7900 +vn -0.6130 -0.0508 -0.7884 +vn -0.8693 0.0339 -0.4931 +vn 0.6342 -0.1574 0.7570 +vn 0.8449 -0.0750 0.5296 +vn 0.8017 -0.0895 0.5910 +vn -0.9755 -0.0976 -0.1972 +vn -0.9473 -0.0799 -0.3101 +vn -0.9667 -0.1630 0.1974 +vn 0.0595 -0.4622 0.8848 +vn 0.0968 -0.6054 0.7900 +vn -0.7744 0.0078 -0.6327 +vn -0.6854 -0.1054 -0.7205 +vn -0.4283 -0.7618 -0.4859 +vn 0.0752 -0.8644 -0.4972 +vn 0.0724 -0.2155 -0.9738 +vn -0.0028 -0.5745 -0.8185 +vn 0.1825 -0.6442 0.7428 +vn 0.0824 -0.7744 0.6274 +vn 0.1161 0.6392 -0.7602 +vn 0.2656 0.0125 0.9640 +vn 0.7039 0.5565 -0.4414 +vn 0.7184 0.5152 -0.4674 +vn 0.6993 0.5355 -0.4735 +vn -0.0701 0.9968 -0.0386 +vn -0.0074 0.9999 -0.0152 +vn 0.0343 0.9994 -0.0028 +vn 0.0852 0.9586 -0.2717 +vn -0.1310 -0.0683 -0.9890 +vn -0.2113 -0.0355 -0.9768 +vn -0.1097 -0.0802 -0.9907 +vn -0.1062 -0.7721 0.6266 +vn -0.1658 -0.6632 0.7298 +vn -0.1620 -0.5715 0.8045 +vn 0.0434 -0.2909 -0.9558 +vn -0.2364 -0.1609 -0.9583 +vn 0.0279 0.1012 -0.9945 +vn -0.0351 0.0323 -0.9989 +vn -0.0461 -0.1338 -0.9899 +vn 0.5262 -0.3162 -0.7894 +vn 0.7068 -0.3394 -0.6207 +vn -0.2585 0.1264 -0.9577 +vn 0.0179 0.1687 -0.9855 +vn -0.0597 0.1500 -0.9869 +vn 0.0375 -0.1158 -0.9926 +vn 0.0974 -0.0277 -0.9949 +vn -0.0395 -0.2832 -0.9582 +vn 0.8291 -0.0982 0.5504 +vn 0.9953 -0.0799 -0.0542 +vn 0.9947 -0.0808 0.0635 +vn -0.1144 -0.0681 0.9911 +vn 0.4655 0.0292 -0.8846 +vn 0.2393 -0.0030 -0.9709 +vn 0.4912 0.8120 0.3153 +vn 0.5895 0.7895 0.1710 +vn 0.4449 0.8483 0.2872 +vn -0.9875 -0.1457 0.0598 +vn -0.9875 -0.1458 0.0598 +vn -0.1312 -0.9775 0.1650 +vn -0.2748 0.8203 0.5016 +vn 0.0647 0.9571 -0.2825 +vn 0.0971 0.8556 -0.5085 +vn 0.7157 0.0744 -0.6944 +vn 0.7320 -0.0178 -0.6811 +vn 0.5568 -0.1066 -0.8238 +vn 0.1441 0.9886 0.0439 +vn -0.9624 0.2672 0.0478 +vn -0.9998 0.0192 -0.0024 +vn 0.0805 -0.8510 -0.5190 +vn 0.0509 -0.8559 -0.5147 +vn 0.0504 -0.9453 -0.3223 +vn 0.2563 -0.8854 -0.3877 +vn 0.3158 -0.8402 -0.4408 +vn 0.4075 -0.8680 -0.2838 +vn 0.0222 -0.0041 -0.9997 +vn 0.0245 -0.0022 -0.9997 +vn -0.4319 0.2102 -0.8771 +vn 0.2038 0.9669 0.1538 +vn 0.0829 -0.4246 0.9016 +vn 0.0359 -0.1022 0.9941 +vn 0.0325 0.0710 0.9969 +vn -0.5707 -0.1029 -0.8146 +vn 0.0045 0.9431 0.3324 +vn 0.0254 0.8343 0.5508 +vn 0.0659 -0.8417 0.5358 +vn 0.0365 -0.8665 0.4979 +vn -0.0547 -0.9614 0.2698 +vn 0.1532 0.8855 0.4386 +vn 0.0497 -0.9976 -0.0472 +vn 0.0332 -0.9936 0.1076 +vn 0.8731 0.2678 -0.4075 +vn -0.1123 0.5165 -0.8489 +vn 0.0628 0.6701 -0.7396 +vn 0.4666 0.5365 -0.7032 +vn 0.4609 0.4850 -0.7432 +vn 0.2525 0.5284 -0.8106 +vn -0.2317 0.1676 -0.9582 +vn -0.2628 0.0776 -0.9617 +vn -0.4232 0.2230 -0.8782 +vn 0.5841 -0.5840 -0.5638 +vn -0.7905 -0.5091 -0.3404 +vn -0.4179 -0.8219 -0.3871 +vn -0.5101 -0.8398 -0.1856 +vn -0.0790 -0.9900 0.1172 +vn -0.0326 -0.9949 0.0952 +vn -0.0568 -0.9808 0.1863 +vn 0.7462 0.4105 -0.5240 +vn 0.6265 0.4151 -0.6597 +vn -0.6329 0.0749 -0.7706 +vn -0.9649 -0.0797 -0.2502 +vn -0.8821 -0.0152 -0.4708 +vn -0.1027 0.9923 -0.0697 +vn -0.1198 0.9921 -0.0385 +vn -0.1099 0.9501 0.2921 +vn -0.1385 0.8091 0.5711 +vn -0.1964 0.6754 -0.7108 +vn -0.2193 0.2911 -0.9312 +vn -0.1517 0.0988 -0.9835 +vn 0.0441 -0.5743 -0.8175 +vn 0.0486 -0.6268 -0.7777 +vn 0.0476 -0.6021 -0.7970 +vn 0.0805 0.0087 -0.9967 +vn 0.0131 0.3123 -0.9499 +vn 0.0062 0.2331 0.9724 +vn -0.1156 0.2203 0.9685 +vn -0.6262 -0.0006 -0.7796 +vn -0.6262 -0.0002 -0.7796 +vn 0.2433 0.6053 0.7579 +vn -0.0949 -0.8214 0.5625 +vn -0.0917 -0.6405 0.7624 +vn -0.0539 -0.6788 0.7324 +vn 0.2540 -0.0225 -0.9669 +vn 0.3255 -0.0522 -0.9441 +vn -0.6158 0.7715 0.1597 +vn -0.7740 0.4996 0.3889 +vn 0.1079 0.8076 0.5798 +vn 0.0851 0.9039 0.4193 +vn -0.3690 0.9071 0.2025 +vn -0.1159 0.9390 0.3237 +vn 0.0039 -0.0646 0.9979 +vn 0.0184 -0.0843 0.9963 +vn 0.9352 -0.3538 -0.0109 +vn 0.9954 -0.0920 0.0263 +vn -0.0381 -0.9796 -0.1974 +vn -0.0926 -0.9246 -0.3696 +vn 0.0210 -0.9075 -0.4195 +vn -0.0456 0.9889 0.1414 +vn -0.0534 0.9860 0.1578 +vn -0.0649 0.9518 0.2998 +vn -0.6273 -0.7475 0.2184 +vn -0.5315 -0.8471 0.0045 +vn -0.5310 -0.8145 0.2337 +vn 0.3754 -0.0299 0.9264 +vn 0.3324 -0.7271 0.6007 +vn 0.1963 -0.6217 0.7583 +vn 0.1436 -0.6859 0.7134 +vn 0.6959 0.1003 0.7111 +vn -0.1178 -0.9862 -0.1165 +vn 0.5968 0.2854 0.7499 +vn 0.5625 0.4998 0.6586 +vn 0.6619 0.4133 0.6253 +vn -0.2161 0.9081 -0.3586 +vn -0.1918 0.9723 -0.1337 +vn 0.2540 0.8450 0.4705 +vn 0.2933 0.8689 0.3986 +vn 0.4824 0.7136 0.5080 +vn -0.9967 0.0623 -0.0522 +vn -0.8163 0.1315 0.5625 +vn -0.9428 -0.1149 0.3130 +vn -0.5337 -0.5681 -0.6264 +vn -0.3595 -0.5077 -0.7830 +vn 0.4333 -0.1382 0.8906 +vn 0.6644 -0.0750 0.7436 +vn 0.1301 -0.9682 -0.2137 +vn -0.6442 0.7591 -0.0936 +vn 0.6381 0.7336 -0.2336 +vn -0.9372 -0.0888 -0.3374 +vn -0.8287 -0.0963 -0.5514 +vn -0.1762 0.8110 -0.5579 +vn -0.9629 -0.0947 -0.2526 +vn -0.9847 -0.1087 0.1360 +vn -0.9801 -0.0747 0.1839 +vn 0.6845 0.7278 0.0418 +vn 0.6416 0.7334 0.2245 +vn 0.7415 0.6410 0.1985 +vn 0.9434 -0.1653 -0.2875 +vn -0.0734 0.2234 -0.9720 +vn -0.1521 0.1656 -0.9744 +vn -0.3181 -0.8001 0.5085 +vn -0.4619 -0.6511 0.6023 +vn -0.4962 -0.7472 0.4420 +vn 0.5789 0.8150 0.0240 +vn 0.4196 0.8772 -0.2332 +vn -0.5556 0.7754 -0.3001 +vn -0.4513 0.8920 -0.0254 +vn 0.0764 0.7300 -0.6791 +vn 0.0765 0.7311 -0.6780 +vn 0.0699 0.5842 -0.8086 +vn 0.1427 0.1145 0.9831 +vn -0.0752 0.7250 0.6846 +vn -0.0086 0.7484 0.6632 +vn 0.1300 -0.9683 -0.2135 +vn 0.3227 0.2970 0.8987 +vn 0.3466 0.6103 0.7123 +vn 0.1113 0.9920 0.0591 +vn 0.0868 0.9368 0.3390 +vn 0.1133 0.9907 -0.0750 +vn 0.9759 -0.1637 -0.1444 +vn 0.9757 -0.1966 0.0967 +vn 0.9803 -0.1881 -0.0606 +vn -0.5603 0.8194 -0.1209 +vn -0.7950 0.4899 -0.3578 +vn -0.8421 0.5070 -0.1841 +vn -0.8089 0.3439 -0.4768 +vn -0.9629 0.0947 -0.2526 +vn -0.9737 0.1076 -0.2009 +vn 0.0095 0.8290 0.5591 +vn -0.4967 -0.5717 0.6530 +vn -0.6445 -0.5390 0.5423 +vn 0.0388 0.7254 0.6873 +vn -0.3139 -0.7804 -0.5408 +vn -0.1844 -0.7416 -0.6450 +vn -0.1642 -0.9856 -0.0406 +vn -0.1484 -0.9858 -0.0788 +vn 0.6843 0.6548 -0.3209 +vn 0.7046 0.5867 -0.3991 +vn 0.6931 0.6388 -0.3340 +vn 0.0226 0.1083 0.9939 +vn 0.0502 0.1611 0.9857 +vn -0.7800 0.2029 0.5920 +vn -0.4450 0.1987 0.8732 +vn -0.6408 0.2105 0.7383 +vn 0.6091 0.7759 0.1643 +vn 0.5140 0.8576 -0.0148 +vn 0.0725 -0.8470 0.5267 +vn 0.0171 -0.8386 0.5445 +vn 0.0384 -0.8064 0.5901 +vn 0.7095 -0.6903 0.1417 +vn 0.7070 -0.6736 0.2156 +vn 0.7053 -0.6578 0.2643 +vn 0.7229 -0.1661 0.6707 +vn 0.6044 -0.1643 0.7795 +vn 0.6601 -0.1745 0.7306 +vn -0.1133 -0.7301 0.6739 +vn -0.1541 -0.5888 0.7935 +vn -0.1952 -0.5768 0.7932 +vn -0.9954 0.0930 0.0221 +vn -0.9927 0.1050 0.0594 +vn -0.9843 0.0386 -0.1722 +vn -0.3540 0.9204 0.1663 +vn -0.5171 0.8546 -0.0475 +vn -0.1357 -0.9771 -0.1637 +vn 0.0922 0.8724 -0.4801 +vn -0.1835 -0.8141 -0.5509 +vn -0.2298 -0.7596 -0.6085 +vn -0.0179 -0.8066 -0.5909 +vn -0.3480 0.9368 0.0358 +vn -0.6239 0.7771 0.0828 +vn -0.4168 -0.2487 0.8743 +vn -0.0215 -0.0050 0.9998 +vn -0.0269 -0.0000 0.9996 +vn -0.0243 -0.0009 0.9997 +vn 0.5920 -0.4849 -0.6437 +vn 0.6611 -0.3432 -0.6672 +vn 0.0749 -0.6154 -0.7846 +vn 0.0111 -0.4311 -0.9022 +vn 0.0129 -0.0526 0.9985 +vn -0.7091 -0.7042 -0.0357 +vn -0.7673 -0.6330 0.1025 +vn -0.7938 -0.5934 0.1336 +vn -0.7204 -0.6905 -0.0653 +vn 0.7211 -0.6908 -0.0535 +vn 0.7082 -0.7057 -0.0205 +vn 0.7172 -0.6953 -0.0474 +vn 0.5565 0.7960 -0.2380 +vn 0.3952 0.8826 -0.2547 +vn 0.6315 0.7736 0.0526 +vn 0.0303 0.9991 0.0312 +vn -0.0030 0.9996 0.0292 +vn 0.0145 0.9968 0.0788 +vn -0.2620 0.6011 -0.7550 +vn 0.7108 0.5184 0.4754 +vn 0.7096 0.5160 0.4798 +vn 0.7111 0.4722 0.5209 +vn -0.2191 0.6169 0.7559 +vn -0.7047 0.5807 0.4077 +vn -0.4388 0.6448 0.6259 +vn -0.2480 0.1896 -0.9500 +vn -0.4119 0.7123 0.5683 +vn -0.4011 0.7167 0.5705 +vn -0.3735 0.6239 0.6864 +vn -0.0141 -0.9958 0.0900 +vn -0.0040 -0.9789 0.2042 +vn 0.1681 0.6194 -0.7668 +vn 0.1062 0.8604 -0.4984 +vn 0.0888 0.8283 -0.5532 +vn -0.0804 0.8327 -0.5479 +vn -0.4767 -0.5366 0.6963 +vn -0.0046 0.9382 0.3461 +vn 0.8551 0.0405 -0.5169 +vn 0.9710 0.0897 -0.2218 +vn 0.9857 0.0909 -0.1420 +vn 0.9498 -0.1835 -0.2535 +vn -0.2956 -0.8732 -0.3875 +vn -0.2819 -0.5537 -0.7835 +vn -0.0053 -0.2724 -0.9622 +vn 0.2721 -0.2846 -0.9192 +vn 0.2316 -0.2920 -0.9279 +vn 0.5790 0.0411 -0.8143 +vn 0.2433 -0.6053 0.7579 +vn -0.7580 0.1644 -0.6313 +vn -0.8752 0.0298 -0.4829 +vn -0.8675 0.0814 -0.4907 +vn 0.2984 0.0021 -0.9544 +vn -0.3113 -0.5997 -0.7372 +vn -0.5083 -0.6872 -0.5190 +vn 0.3892 -0.4834 0.7841 +vn 0.1919 -0.1748 0.9657 +vn -0.6322 -0.6859 0.3604 +vn -0.4004 -0.9115 0.0941 +vn -0.6950 0.1657 -0.6997 +vn -0.9014 0.1554 -0.4042 +vn -0.9297 0.1570 -0.3331 +vn -0.4125 0.0031 0.9109 +vn 0.1624 -0.1880 -0.9686 +vn 0.1701 -0.1463 -0.9745 +vn 0.1224 0.0007 -0.9925 +vn 0.1381 -0.0407 -0.9896 +vn 0.3636 0.8924 -0.2673 +vn 0.0810 0.9366 -0.3409 +vn -0.4806 -0.3715 -0.7944 +vn -0.6321 -0.3295 -0.7013 +vn 0.0796 0.7792 0.6217 +vn 0.0871 0.6700 0.7372 +vn -0.0401 0.7876 -0.6149 +vn -0.0593 0.8895 -0.4530 +vn 0.5467 0.5787 0.6051 +vn 0.4493 0.6046 0.6577 +vn 0.9758 0.1901 0.1077 +vn 0.9795 -0.1263 0.1568 +vn 0.8849 0.3908 -0.2533 +vn 0.6777 -0.7261 0.1162 +vn 0.6306 -0.7210 0.2873 +vn 0.0024 -0.0719 0.9974 +vn 0.0253 -0.0338 0.9991 +vn 0.0301 0.0470 0.9984 +vn -0.6239 -0.7815 0.0006 +vn -0.3808 0.7056 -0.5975 +vn -0.4303 0.7083 -0.5596 +vn 0.1224 0.1774 0.9765 +vn 0.8748 -0.3779 -0.3033 +vn 0.8346 -0.5007 -0.2296 +vn 0.7950 -0.4337 -0.4242 +vn 0.0532 -0.9940 0.0956 +vn -0.5036 0.7608 -0.4094 +vn 0.9558 0.1629 0.2446 +vn 0.4932 0.3060 0.8144 +vn -0.1177 0.9862 -0.1166 +vn -0.1177 0.9862 -0.1165 +vn 0.0359 -0.9955 0.0882 +vn -0.7248 0.1080 -0.6805 +vn -0.9136 -0.1343 -0.3838 +vn 0.1518 0.9562 0.2501 +vn -0.7775 -0.0013 0.6289 +vn -0.9632 -0.0450 0.2652 +vn -0.9077 0.0465 0.4169 +vn 0.7092 0.1341 0.6922 +vn 0.7092 0.1342 0.6922 +vn 0.9947 0.0808 0.0635 +vn 0.9539 0.0597 -0.2941 +vn 0.9953 0.0799 -0.0542 +vn -0.2588 -0.5034 -0.8244 +vn 0.4666 -0.5365 -0.7032 +vn 0.0956 -0.5298 -0.8427 +vn 0.2525 -0.5284 -0.8106 +vn 0.5745 -0.5584 0.5985 +vn 0.4107 -0.6301 0.6590 +vn 0.4319 -0.7401 0.5154 +vn -0.8098 -0.0366 -0.5856 +vn -0.8043 -0.1099 -0.5840 +vn 0.1439 -0.0027 0.9896 +vn 0.0474 -0.0051 0.9989 +vn 0.3799 -0.2901 0.8784 +vn 0.1241 0.4318 0.8934 +vn 0.0218 -0.7302 0.6829 +vn 0.0219 -0.7309 0.6822 +vn 0.0233 -0.7406 0.6715 +vn -0.0648 -0.9978 0.0140 +vn -0.0643 -0.9976 0.0264 +vn -0.0633 -0.9976 0.0293 +vn -0.0903 -0.9926 -0.0814 +vn -0.0905 -0.9954 -0.0324 +vn 0.1197 -0.6252 -0.7712 +vn 0.1255 -0.6229 -0.7722 +vn 0.1266 -0.7573 -0.6407 +vn -0.0151 -0.9933 -0.1150 +vn -0.0485 -0.9927 -0.1107 +vn 0.7167 0.3220 -0.6186 +vn 0.7094 0.2093 -0.6730 +vn 0.7078 0.3181 -0.6307 +vn 0.6544 0.7555 -0.0319 +vn 0.6580 0.7251 -0.2029 +vn -0.7493 0.1181 -0.6516 +vn -0.0342 -0.8445 -0.5344 +vn 0.1300 -0.9682 -0.2135 +vn 0.0950 -0.0375 -0.9948 +vn 0.0320 0.2605 -0.9649 +vn -0.5738 -0.8166 0.0626 +vn -0.1077 0.7330 0.6716 +vn 0.1301 -0.9683 -0.2135 +vn -0.0206 -0.9913 0.1299 +vn -0.1674 -0.9797 -0.1105 +vn 0.0076 -0.9978 -0.0656 +vn 0.0100 -0.9996 0.0269 +vn 0.0065 -0.9999 -0.0132 +vn 0.4482 -0.0784 0.8905 +vn 0.4504 -0.1157 0.8853 +vn 0.5621 0.0403 0.8261 +vn -0.6273 0.7475 0.2184 +vn 0.0406 0.0963 -0.9945 +vn -0.5040 0.1012 -0.8578 +vn -0.2485 0.0216 -0.9684 +vn 0.3609 -0.9036 0.2310 +vn -0.6358 -0.7052 -0.3138 +vn 0.0273 0.0497 -0.9984 +vn -0.2510 0.0694 -0.9655 +vn -0.1744 0.0676 -0.9823 +vn 0.5201 -0.8343 0.1828 +vn 0.6945 -0.5638 0.4470 +vn -0.1073 -0.7001 0.7059 +vn -0.0328 -0.9830 -0.1809 +vn 0.0059 -0.8914 -0.4532 +vn 0.0750 -0.9359 -0.3441 +vn -0.4765 0.2081 0.8542 +vn -0.0461 0.9445 -0.3252 +vn 0.2558 0.9420 -0.2171 +vn 0.0929 0.8830 -0.4601 +vn 0.1585 0.0136 0.9873 +vn 0.0988 -0.0963 0.9904 +vn 0.0230 0.0493 0.9985 +vn 0.1300 0.9682 -0.2135 +vn 0.1084 -0.9720 0.2084 +vn -0.9765 -0.0888 -0.1963 +vn -0.1498 0.6091 0.7788 +vn -0.0909 0.6191 0.7801 +vn 0.6484 -0.2395 -0.7227 +vn 0.9141 -0.1633 -0.3712 +vn 0.8120 -0.1552 -0.5626 +vn -0.4096 -0.5437 0.7325 +vn -0.7361 -0.2385 0.6335 +vn -0.6070 0.0834 -0.7903 +vn -0.8278 0.0926 -0.5534 +vn 0.7042 0.7078 -0.0551 +vn 0.7070 0.7071 -0.0078 +vn 0.7133 0.6992 -0.0481 +vn -0.9869 0.1299 -0.0961 +vn -0.1186 -0.9899 -0.0780 +vn 0.1325 -0.7514 -0.6464 +vn 0.1787 -0.6315 -0.7545 +vn 0.1774 0.1471 0.9731 +vn 0.0254 0.1566 0.9873 +vn 0.4089 0.0990 0.9072 +vn 0.6418 -0.6263 -0.4426 +vn 0.5048 -0.7203 -0.4757 +vn -0.9077 -0.0466 0.4169 +vn -0.0423 -0.2686 -0.9623 +vn 0.0373 0.1033 -0.9939 +vn 0.2531 0.6747 -0.6933 +vn -0.1332 0.8407 -0.5248 +vn -0.0041 -0.2005 0.9797 +vn -0.3919 -0.1991 0.8982 +vn -0.1785 -0.1493 0.9726 +vn 0.9680 0.1565 -0.1963 +vn -0.0040 -0.7639 -0.6453 +vn -0.0570 -0.7927 -0.6069 +vn -0.1092 -0.4333 -0.8946 +vn 0.0278 -0.3789 -0.9250 +vn 0.2414 -0.3010 -0.9226 +vn 0.1642 -0.4995 -0.8506 +vn 0.9857 -0.0908 -0.1420 +vn 0.9167 -0.1486 0.3709 +vn 0.9870 -0.1287 0.0962 +vn -0.9511 0.2473 -0.1850 +vn -0.7780 0.1211 -0.6165 +vn -0.9751 -0.0256 -0.2204 +vn -0.1154 0.2853 -0.9515 +vn -0.4802 -0.8761 -0.0435 +vn -0.3565 -0.9147 0.1904 +vn -0.2765 -0.4356 -0.8566 +vn -0.1820 -0.7754 -0.6046 +vn 0.5866 0.8074 -0.0624 +vn 0.5542 0.7962 -0.2427 +vn 0.1326 0.8791 -0.4579 +vn 0.3802 0.2475 -0.8912 +vn 0.0307 0.2191 -0.9752 +vn 0.3801 0.2475 -0.8912 +vn -0.9918 0.1108 0.0636 +vn -0.9918 0.1108 0.0637 +vn 0.1577 -0.8590 0.4870 +vn -0.5647 -0.3965 0.7238 +vn -0.0957 0.7873 -0.6091 +vn -0.3532 0.2200 0.9093 +vn -0.6793 0.1151 0.7247 +vn -0.5096 0.0848 0.8562 +vn -0.1662 0.3404 0.9255 +vn -0.5302 0.6812 -0.5048 +vn 0.9831 0.1800 -0.0320 +vn 0.9669 0.1865 0.1744 +vn 0.9865 0.1584 0.0424 +vn -0.1166 0.9930 -0.0183 +vn -0.1427 0.9897 -0.0066 +vn -0.1684 0.9857 -0.0096 +vn -0.1319 0.9886 -0.0722 +vn -0.8810 0.1968 0.4302 +vn -0.5929 0.2647 0.7605 +vn -0.7149 0.2485 0.6536 +vn -0.4882 0.8716 -0.0436 +vn -0.2231 0.9422 -0.2500 +vn -0.4523 0.8379 -0.3055 +vn 0.8215 0.5585 0.1152 +vn -0.3091 0.7957 -0.5209 +vn -0.0782 0.9555 -0.2846 +vn 0.0924 -0.8678 0.4883 +vn 0.2955 -0.8791 0.3740 +vn 0.9903 -0.1392 -0.0028 +vn 0.9482 -0.1416 0.2845 +vn 0.9683 -0.1496 0.2000 +vn -0.3701 0.7899 -0.4889 +vn -0.1274 0.9100 -0.3944 +vn 0.3417 -0.6692 -0.6598 +vn 0.1006 -0.9902 0.0973 +vn 0.7107 -0.7019 0.0472 +vn 0.7059 -0.7070 0.0430 +vn 0.7068 -0.7050 0.0582 +vn 0.0962 -0.9951 0.0248 +vn 0.0901 -0.9951 -0.0397 +vn 0.0697 -0.9243 0.3752 +vn -0.0776 0.9957 -0.0514 +vn 0.0520 -0.7351 -0.6759 +vn -0.0852 0.1986 -0.9764 +vn 0.5116 -0.3295 -0.7936 +vn 0.1496 -0.7496 -0.6447 +vn 0.1665 -0.7077 -0.6866 +vn 0.0997 -0.7478 -0.6564 +vn 0.2647 -0.0254 0.9640 +vn 0.2031 -0.0192 0.9790 +vn 0.4394 0.6709 0.5973 +vn 0.2948 0.6288 0.7196 +vn 0.4860 0.5352 0.6909 +vn 0.1038 -0.9852 -0.1368 +vn 0.1067 -0.9922 -0.0642 +vn -0.1071 0.7917 0.6014 +vn 0.0584 -0.5915 0.8042 +vn 0.1015 -0.7698 0.6302 +vn 0.0729 -0.7962 0.6006 +vn -0.1108 0.5010 0.8583 +vn -0.1830 0.4649 0.8663 +vn 0.4219 0.8133 0.4006 +vn 0.2122 0.8108 0.5455 +vn 0.4674 0.1332 0.8739 +vn 0.6644 0.0750 0.7436 +vn 0.7998 0.0282 0.5996 +vn 0.2679 -0.4139 0.8700 +vn 0.5301 -0.1185 0.8396 +vn 0.4572 0.3896 -0.7995 +vn 0.2750 0.5525 -0.7868 +vn 0.3767 0.5551 -0.7415 +vn -0.8968 0.1118 0.4282 +vn -0.6308 0.0577 0.7738 +vn 0.7493 -0.1181 0.6516 +vn 0.7493 -0.1180 0.6517 +vn 0.1242 -0.6854 -0.7175 +vn 0.1068 -0.6394 -0.7614 +vn 0.2514 -0.7237 -0.6427 +vn -0.9245 0.0139 0.3809 +vn -0.8493 -0.1229 0.5133 +vn -0.6360 -0.7179 0.2830 +vn -0.7328 -0.6434 0.2215 +vn -0.7735 -0.6289 0.0787 +vn -0.1207 0.3503 0.9288 +vn 0.1257 -0.0257 -0.9917 +vn -0.6717 0.5100 -0.5373 +vn -0.1780 0.9840 -0.0049 +vn -0.1790 0.9838 -0.0054 +vn -0.6685 0.1562 -0.7271 +vn -0.6183 0.1046 -0.7789 +vn 0.0912 -0.7194 0.6886 +vn 0.0076 -0.7033 0.7109 +vn -0.2191 -0.6169 0.7559 +vn 0.2222 0.9002 0.3744 +vn 0.3962 0.8920 0.2178 +vn 0.5057 -0.7860 0.3557 +vn 0.4525 -0.7514 0.4802 +vn 0.3287 -0.7156 0.6164 +vn 0.0839 0.7150 0.6941 +vn -0.1029 0.7628 0.6384 +vn 0.9523 0.1266 -0.2778 +vn 0.9523 0.1265 -0.2778 +vn 0.2318 -0.6656 -0.7094 +vn 0.0663 -0.0198 -0.9976 +vn 0.0407 -0.5202 -0.8530 +vn -0.9521 0.2892 0.0993 +vn -0.9211 0.3799 0.0858 +vn -0.8711 0.4910 0.0048 +vn -0.0404 0.2641 0.9636 +vn 0.9862 -0.1496 -0.0713 +vn 0.8148 -0.5633 -0.1368 +vn 0.1984 0.1416 0.9698 +vn -0.1216 0.1352 0.9833 +vn 0.0468 -0.6860 0.7261 +vn 0.0555 -0.9302 0.3629 +vn 0.0476 -0.6923 0.7201 +vn -0.0334 0.0566 0.9978 +vn 0.4166 0.0753 0.9060 +vn -0.4312 0.8753 0.2190 +vn -0.8032 0.2024 0.5603 +vn -0.9667 0.1630 0.1973 +vn -0.1028 -0.9787 0.1776 +vn -0.0893 -0.9898 0.1107 +vn -0.1258 -0.9829 0.1345 +vn -0.6374 0.7693 0.0423 +vn -0.7302 0.6736 -0.1141 +vn -0.7774 0.6208 0.1014 +vn -0.0134 -0.8527 0.5223 +vn -0.9755 0.0976 -0.1972 +vn -0.9473 0.0799 -0.3101 +vn 0.5616 -0.2719 -0.7815 +vn 0.0943 -0.9909 0.0960 +vn 0.7099 0.0427 0.7030 +vn 0.7087 -0.0666 0.7023 +vn 0.7099 -0.1008 0.6971 +vn -0.9523 -0.1265 0.2778 +vn -0.9187 -0.0299 -0.3938 +vn 0.0947 0.2531 -0.9628 +vn 0.0841 0.0068 -0.9964 +vn -0.1079 0.2310 0.9670 +vn -0.5235 0.2531 0.8136 +vn -0.1905 0.2343 0.9533 +vn -0.3473 -0.7791 -0.5219 +vn -0.5259 -0.8206 -0.2236 +vn 0.9862 0.1496 -0.0713 +vn -0.1441 -0.9886 -0.0439 +vn -0.2950 -0.9376 0.1839 +vn -0.1502 0.0566 0.9870 +vn -0.1498 0.0591 0.9870 +vn -0.0816 0.0240 0.9964 +vn 0.4567 -0.6993 0.5499 +vn 0.7034 -0.6175 0.3521 +vn 0.1581 0.9164 -0.3676 +vn 0.1562 0.9327 -0.3250 +vn -0.1988 -0.2773 0.9400 +vn 0.0454 -0.2679 0.9624 +vn 0.3571 -0.2122 0.9097 +vn 0.0772 0.7446 0.6630 +vn 0.2570 0.6709 0.6956 +vn 0.2101 0.7299 0.6505 +vn -0.6503 0.7571 0.0616 +vn -0.0101 0.7253 0.6884 +vn 0.0132 0.5984 0.8011 +vn 0.0089 0.7674 0.6412 +vn 0.5517 -0.6884 0.4708 +vn 0.1567 -0.8946 -0.4184 +vn 0.1257 -0.7940 -0.5948 +vn 0.6706 -0.0909 0.7362 +vn 0.6034 -0.0972 0.7915 +vn 0.0495 -0.7392 0.6717 +vn -0.8569 0.0402 0.5139 +vn -0.8945 0.0434 0.4450 +vn 0.0270 -0.6931 0.7203 +vn -0.6358 0.7052 -0.3138 +vn -0.5626 0.8147 -0.1405 +vn -0.0742 -0.8850 -0.4597 +vn -0.0278 -0.7243 -0.6889 +vn 0.0806 -0.7826 -0.6173 +vn -0.2510 0.1434 0.9573 +vn -0.5482 -0.1737 0.8181 +vn -0.0938 0.9955 -0.0118 +vn -0.4027 -0.1088 -0.9088 +vn -0.2635 -0.1392 -0.9546 +vn -0.8047 -0.0083 -0.5936 +vn 0.0118 -0.9477 0.3191 +vn 0.3192 -0.6376 0.7011 +vn -0.0754 -0.6935 0.7165 +vn 0.0562 0.2716 0.9608 +vn 0.0621 0.3551 0.9328 +vn 0.6752 -0.5977 0.4324 +vn 0.6752 -0.5976 0.4324 +vn -0.1096 0.9886 -0.1029 +vn -0.0790 0.9922 -0.0960 +vn 0.0674 0.5798 0.8119 +vn 0.1182 0.2086 0.9708 +vn 0.4063 0.3535 0.8426 +vn 0.1101 -0.9644 -0.2407 +vn 0.5748 -0.5390 -0.6157 +vn -0.1553 -0.1487 0.9766 +vn -0.1416 -0.1778 0.9738 +vn -0.5671 -0.8133 -0.1304 +vn -0.5334 -0.7690 -0.3524 +vn -0.5054 -0.8131 -0.2890 +vn -0.5728 0.7950 -0.1997 +vn -0.4245 0.7122 -0.5590 +vn -0.5743 0.7003 -0.4240 +vn 0.9870 0.1287 0.0962 +vn -0.0937 0.6332 0.7683 +vn -0.0336 0.7103 0.7031 +vn -0.0293 0.4969 0.8673 +vn -0.0170 -0.9972 0.0728 +vn 0.2341 -0.9597 0.1556 +vn 0.7546 0.4600 -0.4679 +vn -0.1319 0.9912 -0.0143 +vn -0.1245 0.9832 -0.1334 +vn -0.1587 0.9869 -0.0279 +vn -0.1069 0.2776 0.9547 +vn -0.7231 -0.1575 -0.6726 +vn -0.7085 -0.1197 -0.6955 +vn 0.7279 -0.0919 0.6795 +vn 0.7279 -0.0918 0.6795 +vn 0.8429 -0.0054 0.5380 +vn 0.7998 -0.0282 0.5996 +vn 0.9733 0.0836 0.2139 +vn 0.0048 0.9302 -0.3671 +vn -0.4883 -0.8716 -0.0436 +vn 0.1408 0.6764 -0.7229 +vn 0.0596 0.7228 -0.6884 +vn -0.5663 0.8240 -0.0198 +vn 0.6745 -0.7078 0.2101 +vn 0.7888 -0.2632 0.5554 +vn -0.2187 -0.2410 0.9456 +vn -0.1512 -0.3504 0.9243 +vn -0.1691 -0.3531 0.9202 +vn 0.5483 0.0672 0.8336 +vn 0.0518 -0.1241 -0.9909 +vn -0.4039 -0.8257 -0.3939 +vn -0.0053 0.3165 0.9486 +vn -0.1688 0.5228 0.8356 +vn -0.2895 0.3060 0.9069 +vn -0.3009 -0.1371 -0.9437 +vn -0.0990 -0.1345 -0.9860 +vn -0.0471 0.9978 0.0457 +vn 0.0492 0.9949 0.0883 +vn 0.0258 -0.4018 -0.9153 +vn 0.0378 0.8616 0.5062 +vn 0.0674 0.7434 0.6654 +vn 0.1116 0.9746 0.1944 +vn 0.8472 -0.0479 -0.5291 +vn 0.5855 0.5396 0.6050 +vn 0.7401 0.5423 0.3977 +vn 0.6258 0.5991 0.4995 +vn 0.8169 0.4290 -0.3855 +vn 0.0427 -0.9649 -0.2593 +vn 0.2154 -0.8379 -0.5015 +vn 0.3446 -0.8891 -0.3012 +vn -0.1674 0.9797 -0.1105 +vn -0.5223 0.7927 -0.3143 +vn 0.1402 0.6608 -0.7374 +vn 0.1442 -0.9886 0.0438 +vn -0.8914 -0.4527 0.0236 +vn -0.6415 -0.7297 -0.2367 +vn -0.5873 0.4767 -0.6541 +vn 0.6914 0.5867 -0.4216 +vn 0.5600 0.7780 0.2849 +vn 0.6082 0.7805 0.1446 +vn 0.5554 0.8207 0.1344 +vn 0.0623 0.6474 0.7596 +vn 0.0494 0.6608 0.7489 +vn -0.0177 0.7362 0.6765 +vn -0.2445 -0.7592 0.6032 +vn 0.1983 -0.8066 0.5569 +vn -0.9851 -0.1521 0.0807 +vn 0.6104 -0.7231 -0.3233 +vn 0.6903 -0.7187 -0.0830 +vn 0.5848 -0.8078 -0.0733 +vn -0.0591 0.0505 0.9970 +vn -0.0944 0.0075 0.9955 +vn 0.4631 -0.8254 0.3230 +vn 0.5229 -0.6674 0.5302 +vn 0.3677 0.9281 -0.0578 +vn 0.6301 0.7375 -0.2432 +vn 0.9540 0.0592 -0.2940 +vn -0.5197 0.0052 -0.8543 +vn -0.3329 0.1917 0.9233 +vn -0.1300 -0.9683 0.2134 +vn 0.0483 -0.1732 0.9837 +vn 0.0120 -0.1285 0.9916 +vn -0.5174 0.0598 -0.8536 +vn 0.7933 0.2302 -0.5636 +vn 0.7167 0.2531 -0.6499 +vn 0.1158 -0.9912 0.0639 +vn 0.9999 0.0129 0.0000 +vn -1.0000 0.0002 0.0000 +vn -0.3840 -0.7654 -0.5165 +vn 0.5004 0.4638 0.7311 +vn 0.2357 0.4621 0.8550 +vn 0.4938 0.2387 0.8362 +vn -0.1031 0.3212 0.9414 +vn -0.4199 0.0505 0.9062 +vn -0.5216 0.0401 0.8522 +vn -0.8474 0.1309 -0.5145 +vn -0.8176 0.5502 -0.1698 +vn -0.7664 0.5321 -0.3599 +vn 0.5744 0.8093 0.1233 +vn -0.1104 0.6804 0.7245 +vn -0.1195 0.7275 0.6756 +vn -0.1708 0.9847 -0.0342 +vn -0.0435 -0.9331 0.3570 +vn 0.6777 0.7261 0.1162 +vn 0.1030 -0.8808 -0.4621 +vn 0.7098 0.6823 0.1752 +vn 0.7069 0.6535 0.2706 +vn 0.8835 -0.2238 0.4116 +vn 0.7699 0.2956 0.5656 +vn 0.7522 -0.0080 0.6589 +vn 0.7615 0.0093 -0.6481 +vn -0.0581 -0.1535 -0.9864 +vn 0.9585 -0.0044 0.2851 +vn -0.0624 -0.9973 0.0398 +vn -0.0411 -0.9991 -0.0098 +vn 0.0974 -0.4018 0.9105 +vn 0.0811 -0.5421 0.8364 +vn 0.0872 -0.4933 0.8655 +vn 0.5087 0.7896 0.3431 +vn 0.4834 0.8235 0.2969 +vn -0.1814 -0.9748 -0.1295 +vn 0.5325 0.6390 0.5551 +vn 0.2556 0.6530 0.7129 +vn 0.2626 0.6527 0.7106 +vn -0.7161 0.5678 0.4059 +vn -0.7751 0.4917 0.3968 +vn 0.7153 -0.3111 0.6257 +vn 0.7102 -0.4255 0.5608 +vn -0.4146 -0.8298 0.3735 +vn -0.1826 -0.7415 0.6457 +vn -0.3459 -0.7587 0.5520 +vn 0.7011 -0.5455 0.4592 +vn 0.7086 -0.5101 0.4875 +vn 0.6930 -0.5736 0.4368 +vn 0.8017 0.0895 0.5910 +vn 0.8449 0.0750 0.5296 +vn 0.6342 0.1574 0.7570 +vn 0.1295 0.1952 0.9722 +vn 0.4333 0.1381 0.8906 +vn 0.9785 -0.0379 -0.2030 +vn 0.1482 -0.5896 -0.7940 +vn -0.5483 0.0672 -0.8336 +vn -0.0876 -0.9905 -0.1062 +vn 0.0776 0.9957 0.0514 +vn 0.0016 0.4916 -0.8708 +vn 0.0977 0.4066 -0.9084 +vn -0.1178 0.9862 -0.1165 +vn -0.0542 0.6148 -0.7868 +vn -0.1040 0.7597 -0.6419 +vn -0.0504 0.6365 -0.7696 +vn -0.1463 0.3406 0.9288 +vn -0.9618 0.0840 0.2606 +vn -0.8929 0.0538 0.4470 +vn -0.9770 0.1012 0.1876 +vn -0.0164 0.9916 0.1279 +vn 0.1301 0.9682 -0.2135 +vn 0.2367 0.9650 0.1126 +vn 0.4108 0.8598 0.3034 +vn 0.0850 0.6226 -0.7779 +vn -0.1231 -0.3532 0.9274 +vn -0.2017 -0.3221 0.9250 +vn -0.1107 -0.5020 0.8578 +vn -0.7437 0.0322 0.6677 +vn -0.1334 -0.6402 -0.7565 +vn -0.1857 -0.7433 -0.6427 +vn -0.1890 -0.7945 -0.5771 +vn 0.7027 -0.7059 0.0893 +vn -0.9966 -0.0789 -0.0233 +vn -0.9497 -0.0895 -0.3002 +vn 0.0428 0.5280 0.8482 +vn -0.0458 0.8145 0.5784 +vn -0.0145 0.7467 -0.6651 +vn -0.0359 0.6467 -0.7619 +vn 0.0726 0.4364 -0.8968 +vn -0.2243 -0.0098 -0.9745 +vn 0.3227 0.6891 0.6489 +vn 0.3325 0.6748 0.6588 +vn -0.2037 0.7963 -0.5695 +vn -0.1140 -0.9675 -0.2256 +vn -0.1836 0.9316 -0.3137 +vn 0.6466 -0.7476 0.1519 +vn 0.6613 0.4090 -0.6288 +vn 0.5517 0.6884 0.4708 +vn 0.5437 0.0855 0.8349 +vn 0.6034 0.0972 0.7915 +vn -0.9853 -0.1022 -0.1366 +vn -0.9875 -0.1458 0.0597 +vn -0.4784 0.7719 0.4188 +vn -0.1045 0.6393 -0.7618 +vn -0.3139 0.7804 -0.5408 +vn -0.1844 0.7416 -0.6450 +vn -0.2830 -0.9215 0.2662 +vn 0.1851 -0.9575 0.2213 +vn 0.0106 -0.9999 -0.0107 +vn 0.3838 -0.9214 0.0611 +vn -0.0437 -0.8530 -0.5201 +vn -0.1788 -0.2097 -0.9613 +vn -0.4158 -0.1659 -0.8942 +vn 0.2955 0.8791 0.3740 +vn 0.5221 -0.7147 0.4654 +vn -0.1510 -0.0239 0.9882 +vn 0.1425 0.9420 -0.3037 +vn -0.3242 0.6403 0.6963 +vn -0.8041 -0.1172 0.5828 +vn -0.6590 -0.1455 0.7380 +vn 0.5355 -0.3725 0.7579 +vn -0.5671 0.8133 -0.1304 +vn -0.2239 -0.6254 -0.7475 +vn -0.0949 -0.7366 -0.6696 +vn -0.0374 -0.6501 -0.7589 +vn -0.1097 -0.8232 -0.5571 +vn -0.1031 -0.8085 -0.5793 +vn 0.0011 -0.7800 -0.6258 +vn 0.0471 -0.6237 -0.7802 +vn 0.0771 -0.7835 -0.6166 +vn 0.1236 -0.6118 -0.7813 +vn 0.1557 -0.7503 -0.6425 +vn -0.2721 0.2846 0.9192 +vn -0.1988 0.2773 0.9400 +vn 0.0454 0.2679 0.9624 +vn 0.0666 -0.5161 -0.8539 +vn -0.1597 0.9676 0.1953 +vn -0.1547 0.9774 0.1442 +vn 0.1647 0.7481 0.6428 +vn 0.1142 0.6059 0.7873 +vn 0.0133 0.1804 0.9835 +vn 0.0918 -0.7385 -0.6679 +vn 0.0910 -0.7472 -0.6583 +vn 0.0678 -0.6368 -0.7681 +vn 0.0871 -0.7485 -0.6574 +vn 0.0881 -0.7533 -0.6518 +vn 0.9875 -0.1458 -0.0597 +vn -0.3145 0.6327 0.7077 +vn -0.3836 0.7256 0.5713 +vn 0.0301 0.1138 -0.9930 +vn -0.8954 -0.1149 0.4302 +vn -0.8602 -0.1033 0.4994 +vn 0.4503 0.0143 -0.8928 +vn 0.7657 -0.0232 -0.6428 +vn 0.5228 0.0019 -0.8525 +vn -0.7240 -0.5376 0.4322 +vn -0.6984 -0.5624 0.4426 +vn 0.0129 0.0526 0.9985 +vn 0.0869 0.9948 0.0530 +vn -0.9487 0.1502 -0.2781 +vn -0.7624 0.1392 -0.6319 +vn -0.7860 0.1365 -0.6030 +vn -0.2258 -0.5181 0.8250 +vn -0.9647 -0.0015 -0.2632 +vn -0.9114 -0.0034 -0.4115 +vn -0.9926 0.0883 -0.0835 +vn -0.9352 0.2040 -0.2895 +vn 0.9336 -0.1571 0.3220 +vn -0.9751 0.0256 -0.2204 +vn 0.0300 -0.4317 -0.9015 +vn -0.0539 0.9158 0.3981 +vn 0.0026 0.7830 0.6220 +vn -0.4683 -0.7907 0.3942 +vn 0.6940 0.7143 0.0902 +vn 0.7055 0.7071 0.0483 +vn 0.7144 0.6984 0.0425 +vn 0.7089 0.7034 0.0520 +vn 0.7012 0.6957 0.1558 +vn 0.1496 0.0427 -0.9878 +vn 0.1606 -0.2286 0.9602 +vn 0.1352 0.0336 0.9903 +vn 0.1586 -0.0783 0.9842 +vn 0.1526 0.9726 0.1752 +vn 0.1215 -0.0368 0.9919 +vn 0.2067 0.1218 0.9708 +vn 0.1295 -0.3318 0.9344 +vn 0.1935 -0.0843 0.9775 +vn 0.1611 -0.4486 0.8791 +vn 0.2155 0.0323 0.9760 +vn 0.1573 -0.0491 0.9863 +vn 0.3117 -0.5982 0.7382 +vn -0.1200 -0.6508 0.7497 +vn -0.1188 -0.9865 -0.1130 +vn -0.1301 0.0670 0.9892 +vn -0.1425 -0.0475 0.9886 +vn -0.1265 0.1937 0.9729 +vn -0.1132 -0.1324 0.9847 +vn -0.1020 0.0793 0.9916 +vn -0.1645 0.9859 -0.0301 +vn -0.0144 -0.1638 0.9864 +vn -0.1477 0.2580 0.9548 +vn 0.1178 0.9862 0.1165 +vn 0.7168 -0.4008 -0.5706 +vn 0.0114 -0.3218 0.9467 +vn -0.0482 -0.3816 0.9231 +vn 0.0590 -0.4235 0.9040 +vn 0.9742 -0.0590 0.2178 +vn 0.1619 -0.1736 -0.9714 +vn 0.1725 -0.3702 -0.9128 +vn 0.0318 -0.2717 0.9619 +vn -0.0039 0.0503 0.9987 +vn 0.0032 -0.0912 0.9958 +vn -0.0315 0.0894 0.9955 +vn 0.0531 -0.5307 -0.8459 +vn 0.0161 -0.0557 0.9983 +vn 0.1054 -0.0792 0.9913 +vn -0.6947 0.0095 0.7192 +vn -0.0775 -0.9957 -0.0515 +vn 0.2039 -0.0021 0.9790 +vn 0.5895 -0.8040 0.0781 +vn -0.0268 -0.5229 -0.8520 +vn 0.0679 0.7538 0.6536 +vn 0.1181 0.6294 0.7680 +vn 0.0125 0.6549 0.7556 +vn 0.0012 0.9992 0.0399 +vn 0.0119 0.9998 -0.0178 +vn 0.9894 -0.1395 -0.0398 +vn 0.9894 -0.1394 -0.0398 +vn -0.9452 -0.0350 -0.3247 +vn -0.9811 -0.0571 -0.1848 +vn 0.1115 -0.9908 -0.0766 +vn -0.0873 0.0683 0.9938 +vn -0.0890 0.1012 0.9909 +vn -0.1238 0.0230 -0.9920 +vn -0.4277 0.8611 -0.2749 +vn -0.3016 0.8268 -0.4748 +vn 0.6659 0.1655 0.7275 +vn 0.4702 0.1588 0.8682 +vn 0.4702 0.1588 0.8681 +vn -0.6185 0.7774 0.1146 +vn 0.0644 0.6903 -0.7206 +vn -0.1998 0.6844 -0.7011 +vn -0.1116 -0.0028 0.9937 +vn 0.6754 0.0472 0.7359 +vn 0.6737 0.0342 0.7382 +vn 0.8694 -0.0327 0.4930 +vn -0.4190 0.8186 -0.3928 +vn -0.5208 0.8172 -0.2468 +vn -0.5019 0.8362 -0.2210 +vn 0.1177 -0.9862 0.1166 +vn 0.0170 -0.1758 0.9843 +vn 0.0920 -0.2824 0.9549 +vn 0.7493 0.1181 0.6516 +vn 0.2102 0.0752 0.9748 +vn 0.1880 0.0247 0.9819 +vn 0.1473 0.1814 0.9723 +vn 0.9894 0.1394 -0.0398 +vn 0.9894 0.1395 -0.0398 +vn -0.1532 0.9701 -0.1884 +vn 0.9918 -0.1109 -0.0636 +vn 0.1219 0.9137 0.3877 +vn 0.1321 0.7377 0.6621 +vn -0.4048 -0.0752 -0.9113 +vn -0.2120 -0.0668 -0.9750 +vn 0.5919 0.3239 0.7381 +vn 0.6456 -0.0003 0.7637 +vn 0.6444 0.0204 0.7645 +vn -0.4217 0.1028 0.9009 +vn -0.4238 0.0478 0.9045 +vn -0.3295 -0.0574 0.9424 +vn -0.2429 0.0560 0.9684 +vn -0.1401 0.8721 -0.4688 +vn -0.7183 0.6722 -0.1794 +vn 0.1399 -0.2112 -0.9674 +vn 0.1255 -0.0770 0.9891 +vn 0.1780 0.0966 0.9793 +vn 0.1357 0.1282 0.9824 +vn 0.2176 -0.0492 0.9748 +vn 0.2549 -0.0842 0.9633 +vn 0.1882 -0.0255 0.9818 +vn -0.1381 -0.0248 0.9901 +vn 0.2541 -0.0582 0.9654 +vn 0.3682 0.0601 0.9278 +vn 0.6260 0.7620 -0.1657 +vn -0.1446 -0.4092 0.9009 +vn -0.4479 -0.3776 0.8104 +vn -0.2810 -0.5119 0.8118 +vn 0.2373 -0.9116 -0.3356 +vn 0.4224 -0.3760 -0.8247 +vn 0.0406 -0.0963 -0.9945 +vn 0.4917 -0.0032 -0.8708 +vn -0.0432 -0.5287 0.8477 +vn -0.9763 0.1636 0.1419 +vn -0.9820 0.1885 0.0125 +vn -0.0909 -0.9887 0.1190 +vn -0.0720 -0.9615 0.2653 +vn -0.0327 0.1096 0.9934 +vn -0.9713 0.2172 -0.0973 +vn -0.8987 0.2126 -0.3835 +vn -0.9232 0.2420 -0.2987 +vn -0.0369 -0.8662 0.4983 +vn -0.0763 -0.9229 0.3773 +vn -0.8127 0.1829 -0.5532 +vn -0.6664 0.6947 -0.2707 +vn -0.1108 0.9925 0.0509 +vn -0.1107 0.9796 0.1679 +vn -0.1107 0.9796 0.1678 +vn -0.6205 -0.0078 0.7842 +vn -0.6205 -0.0078 0.7841 +vn -0.2227 -0.1543 0.9626 +vn -0.4167 0.2487 0.8743 +vn -0.4168 0.2487 0.8743 +vn 0.3571 0.2122 0.9097 +vn 0.3583 0.2249 0.9061 +vn -0.5517 0.7470 -0.3711 +vn 0.2660 -0.0016 -0.9640 +vn -0.1595 -0.2509 0.9548 +vn 0.8710 0.2658 -0.4131 +vn -0.2376 0.6875 -0.6863 +vn 0.1868 -0.3923 0.9007 +vn -0.0871 0.0136 -0.9961 +vn -0.4388 -0.6448 0.6259 +vn 0.6337 0.7736 -0.0023 +vn -0.9560 0.0348 -0.2912 +vn -0.9145 -0.1834 0.3605 +vn -0.9931 -0.1014 0.0582 +vn -0.8805 -0.2031 0.4284 +vn 0.0294 -0.1358 -0.9903 +vn 0.6955 -0.6547 -0.2961 +vn 0.3694 -0.7339 -0.5700 +vn 0.5784 -0.6917 -0.4324 +vn 0.7181 -0.0740 -0.6920 +vn 0.8967 -0.1123 -0.4282 +vn 0.7691 -0.0942 -0.6322 +vn 0.3713 -0.8719 -0.3193 +vn 0.6161 0.7874 -0.0179 +vn 0.5119 0.8112 0.2826 +vn 0.5012 -0.2648 -0.8238 +vn 0.4469 -0.2232 -0.8663 +vn 0.6779 -0.3528 -0.6450 +vn -0.0775 0.9957 -0.0516 +vn 0.9190 -0.1818 -0.3498 +vn 0.0972 -0.7678 0.6332 +vn 0.0884 -0.6204 0.7793 +vn 0.9632 0.0537 -0.2633 +vn 0.6966 -0.6642 -0.2713 +vn 0.7053 -0.6038 -0.3715 +vn 0.7063 -0.6135 -0.3533 +vn -0.0551 0.0017 0.9985 +vn 0.7094 0.1662 0.6849 +vn 0.7022 0.1198 0.7018 +vn -0.1802 -0.9792 -0.0933 +vn -0.2739 -0.9545 -0.1184 +vn -0.2387 -0.9624 -0.1294 +vn -0.1503 0.2878 0.9458 +vn -0.4455 0.3765 0.8123 +vn 0.0776 -0.9957 0.0514 +vn 0.0220 -0.1635 0.9863 +vn 0.4087 -0.0983 0.9074 +vn 0.5952 0.5660 -0.5704 +vn 0.0372 -0.8675 0.4961 +vn 0.0305 -0.8359 0.5480 +vn -0.3011 0.9169 -0.2620 +vn 0.3351 0.6862 -0.6456 +vn 0.0578 -0.1737 -0.9831 +vn -0.1202 0.1491 0.9815 +vn -0.1908 0.2197 0.9567 +vn -0.0067 0.5068 0.8620 +vn -0.3952 -0.6299 -0.6686 +vn -0.2028 -0.3555 -0.9124 +vn 0.3235 0.8694 -0.3736 +vn -0.9983 0.0368 -0.0460 +vn 0.0320 0.6519 -0.7576 +vn 0.1880 0.5613 -0.8060 +vn -0.1098 0.6162 -0.7799 +vn -0.8744 -0.0288 -0.4843 +vn -0.9819 -0.1199 -0.1469 +vn -0.9815 -0.1028 -0.1618 +vn -0.5430 -0.5807 -0.6065 +vn 0.8150 0.2649 -0.5153 +vn 0.2731 0.0850 0.9582 +vn 0.7457 0.0273 -0.6657 +vn 0.9539 -0.0597 -0.2941 +vn -0.8167 -0.1379 0.5603 +vn -0.5708 0.1029 -0.8146 +vn -0.5708 0.1030 -0.8146 +vn 0.0292 -0.5007 0.8651 +vn -0.1690 -0.1357 -0.9762 +vn 0.0301 -0.1138 -0.9930 +vn 0.0296 -0.1187 -0.9925 +vn -0.0504 -0.2568 0.9651 +vn -0.0063 0.0066 1.0000 +vn -0.0352 -0.0583 0.9977 +vn -0.3602 -0.6350 -0.6835 +vn -0.2028 -0.6015 -0.7727 +vn -0.2156 -0.6503 -0.7284 +vn 0.4392 0.0146 -0.8983 +vn 0.3416 -0.0036 -0.9398 +vn -0.1448 -0.7641 -0.6286 +vn 0.0484 -0.7479 0.6620 +vn 0.0283 -0.6744 0.7378 +vn -0.5178 -0.7513 0.4091 +vn -0.6704 -0.7290 0.1381 +vn -0.8373 -0.2175 0.5017 +vn 0.8456 -0.1661 0.5073 +vn -0.4220 -0.4753 -0.7720 +vn -0.4961 -0.5979 -0.6296 +vn 0.0886 -0.9894 -0.1153 +vn 0.0699 -0.9821 -0.1749 +vn 0.0886 -0.9869 0.1352 +vn 0.0372 -0.9861 -0.1616 +vn 0.0256 -0.9726 -0.2313 +vn 0.0517 -0.9958 -0.0750 +vn 0.0531 -0.9666 -0.2507 +vn 0.0515 -0.9958 -0.0752 +vn 0.8150 -0.2648 -0.5153 +vn -0.0124 -0.4537 -0.8910 +vn 0.0434 -0.5993 -0.7994 +vn 0.0623 -0.6117 -0.7886 +vn 0.9657 0.0714 0.2495 +vn 0.9605 0.1764 -0.2154 +vn 0.0593 -0.0954 -0.9937 +vn 0.0580 0.1048 -0.9928 +vn 0.0546 0.2975 -0.9532 +vn 0.0237 0.2546 0.9668 +vn 0.0558 0.8353 -0.5469 +vn 0.0111 0.8111 -0.5848 +vn -0.0152 0.7618 -0.6476 +vn -0.1887 -0.9261 -0.3267 +vn -0.1921 0.6952 -0.6927 +vn 0.7137 0.0706 0.6969 +vn 0.1671 0.6484 -0.7427 +vn -0.0288 0.5173 -0.8553 +vn -0.3090 -0.7941 -0.5234 +vn -0.3766 0.6035 0.7029 +vn -0.6254 0.6636 0.4104 +vn -0.0618 0.0380 -0.9974 +vn -0.0792 -0.0443 -0.9959 +vn -0.7248 -0.1080 -0.6805 +vn -0.4487 0.1503 -0.8809 +vn -0.1690 0.1357 -0.9762 +vn -0.8995 -0.0255 -0.4362 +vn -0.0690 0.8113 -0.5806 +vn -0.5519 0.7237 -0.4144 +vn -0.5370 -0.1855 -0.8230 +vn -0.5040 -0.1012 -0.8578 +vn -0.2485 -0.0216 -0.9684 +vn -0.2983 0.0056 -0.9545 +vn -0.0898 0.0054 -0.9959 +vn 0.0653 -0.7044 -0.7068 +vn 0.0170 -0.6452 -0.7638 +vn 0.1847 -0.6798 -0.7098 +vn 0.0799 -0.8370 0.5414 +vn 0.1478 -0.4818 0.8637 +vn 0.1584 -0.4235 0.8919 +vn 0.1765 -0.3479 0.9208 +vn 0.6150 -0.7350 -0.2857 +vn 0.0516 -0.6182 0.7843 +vn 0.0457 -0.6154 0.7869 +vn 0.1301 0.9682 -0.2138 +vn -0.4581 -0.0227 0.8886 +vn -0.4835 -0.0646 0.8729 +vn 0.1681 0.1906 0.9672 +vn -0.1820 0.9833 -0.0024 +vn 0.3384 -0.4573 0.8224 +vn 0.1348 -0.4176 0.8986 +vn 0.7953 0.5869 0.1519 +vn 0.8519 0.5165 -0.0866 +vn 0.9400 -0.0280 0.3400 +vn 0.9909 0.1193 0.0622 +vn 0.9919 0.1252 0.0203 +vn -0.9875 0.1457 0.0598 +vn -0.9875 0.1458 0.0598 +vn -0.5610 0.6183 -0.5504 +vn -0.5765 0.5799 -0.5757 +vn -0.6693 0.6559 -0.3490 +vn 0.7633 0.0359 -0.6451 +vn -0.7100 0.6658 -0.2294 +vn 0.6393 -0.0414 0.7678 +vn 0.5372 -0.4160 0.7338 +vn 0.6438 0.7194 -0.2606 +vn -0.9645 0.2189 0.1480 +vn -0.9845 0.1208 0.1268 +vn -0.8254 0.3568 0.4374 +vn 0.6093 0.3736 0.6994 +vn -0.7363 -0.5489 0.3957 +vn -0.5035 -0.8609 0.0734 +vn 0.4939 0.0558 -0.8677 +vn -0.3432 0.2031 0.9170 +vn -0.5342 -0.8060 -0.2550 +vn 0.0110 -0.7545 0.6562 +vn 0.0260 -0.7037 0.7100 +vn 0.0250 -0.7075 0.7063 +vn 0.7167 -0.2531 -0.6499 +vn -0.3023 0.1367 -0.9434 +vn -0.7713 0.6323 0.0732 +vn 0.1217 -0.8835 -0.4522 +vn 0.2391 0.7752 -0.5848 +vn 0.2185 0.7083 -0.6712 +vn 0.1997 0.7185 -0.6663 +vn 0.8887 -0.0925 0.4491 +vn 0.8865 0.4198 -0.1947 +vn 0.8187 0.2559 -0.5140 +vn -0.6266 -0.6333 -0.4542 +vn 0.5402 0.2256 -0.8107 +vn 0.4778 0.2139 -0.8520 +vn 0.1766 0.4308 -0.8850 +vn 0.7090 -0.5268 -0.4689 +vn 0.7064 -0.5180 -0.4824 +vn 0.4486 0.8621 -0.2357 +vn 0.2340 0.8782 -0.4172 +vn 0.7016 0.7043 -0.1081 +vn 0.0555 -0.6769 0.7340 +vn 0.0177 0.9986 0.0490 +vn 0.0803 -0.4508 0.8890 +vn 0.5119 -0.8112 0.2826 +vn 0.5866 -0.8075 -0.0624 +vn 0.6161 -0.7875 -0.0179 +vn -0.2898 0.8046 -0.5183 +vn 0.6306 0.7210 0.2873 +vn -0.9731 -0.1453 0.1790 +vn -0.1943 0.7514 -0.6306 +vn -0.2026 0.7544 -0.6243 +vn -0.2343 0.6133 -0.7543 +vn 0.0156 0.8761 0.4819 +vn 0.0309 0.5665 0.8235 +vn 0.9775 -0.1403 -0.1572 +vn -0.2077 -0.0165 0.9780 +vn 0.2159 -0.4149 0.8839 +vn 0.1974 -0.2675 0.9431 +vn 0.4750 0.8004 0.3657 +vn 0.0871 0.8986 0.4300 +vn 0.0446 -0.7389 -0.6723 +vn 0.0727 -0.9225 -0.3791 +vn 0.0198 -0.2551 0.9667 +vn -0.1926 0.6637 0.7228 +vn -0.2580 0.7368 0.6250 +vn -0.1088 0.7023 0.7035 +vn -0.9623 -0.1300 0.2390 +vn -0.6547 -0.7028 -0.2783 +vn -0.4689 -0.7948 -0.3853 +vn -0.6077 -0.7472 -0.2690 +vn -0.2142 -0.0237 -0.9765 +vn -0.4225 0.2302 0.8766 +vn -0.1965 -0.0091 0.9805 +vn -0.0202 -0.9988 -0.0449 +vn -0.0468 0.3977 -0.9163 +vn -0.2678 0.4564 -0.8485 +vn -0.4411 0.2066 0.8733 +vn -0.4411 0.2066 0.8734 +vn 0.1660 -0.9614 -0.2195 +vn 0.1179 0.9874 0.1051 +vn -0.1006 -0.6499 0.7533 +vn -0.1926 -0.7653 0.6142 +vn 0.0834 0.0145 -0.9964 +vn 0.2431 -0.0076 -0.9700 +vn -0.0815 0.2008 -0.9762 +vn -0.0830 0.2750 -0.9578 +vn 0.1028 0.4075 -0.9074 +vn -0.6650 -0.6032 0.4404 +vn 0.0924 0.8678 0.4883 +vn -0.7791 -0.2045 0.5926 +vn -0.9667 -0.1630 0.1973 +vn -0.0414 -0.5681 0.8219 +vn -0.0706 -0.9786 -0.1935 +vn 0.2665 -0.7107 0.6511 +vn -0.1777 -0.9826 -0.0543 +vn -0.1601 -0.9799 -0.1192 +vn 0.1179 0.9862 0.1165 +vn -0.5893 -0.1214 -0.7988 +vn -0.5893 -0.1214 -0.7987 +vn -0.2731 -0.1499 0.9502 +vn 0.1418 -0.4895 0.8604 +vn 0.0912 0.7194 0.6886 +vn 0.0076 0.7033 0.7108 +vn 0.0331 0.1020 -0.9942 +vn 0.5910 0.1005 0.8004 +vn -0.1681 0.6685 0.7245 +vn -0.1966 0.5780 0.7920 +vn -0.1918 0.6979 0.6900 +vn 0.4166 -0.0753 0.9060 +vn -0.9434 -0.1653 0.2875 +vn -0.0732 0.0549 -0.9958 +vn -0.5893 0.1214 -0.7988 +vn 0.9710 -0.0897 -0.2218 +vn 0.8551 -0.0405 -0.5169 +vn -0.6076 0.7263 0.3214 +vn 0.5841 0.5840 -0.5638 +vn -0.5616 -0.2714 0.7816 +vn -0.7684 -0.2370 0.5945 +vn -0.5924 -0.2710 0.7587 +vn 0.4411 -0.2066 -0.8733 +vn 0.3694 0.7339 -0.5700 +vn 0.6955 0.6547 -0.2961 +vn 0.5784 0.6917 -0.4324 +vn 0.0337 -0.6193 -0.7845 +vn 0.9657 -0.0714 0.2495 +vn 0.9919 -0.1252 0.0203 +vn 0.9605 -0.1764 -0.2154 +vn 0.0186 -0.1887 -0.9819 +vn -0.1492 -0.2079 -0.9667 +vn 0.1766 -0.4308 -0.8850 +vn -0.1193 -0.7666 -0.6309 +vn 0.1132 0.1619 0.9803 +vn -0.5255 -0.7545 -0.3931 +vn -0.6225 -0.6229 -0.4738 +vn 0.0574 -0.6098 0.7905 +vn 0.0651 -0.7537 -0.6540 +vn 0.1926 0.8290 0.5250 +vn 0.3714 0.7799 0.5039 +vn -0.6567 -0.6445 0.3916 +vn -0.7466 -0.6489 0.1467 +vn 0.4161 0.0266 -0.9089 +vn -0.2157 0.6990 -0.6818 +vn -0.1531 0.7098 -0.6876 +vn 0.4527 0.0512 -0.8902 +vn 0.2552 0.4990 -0.8282 +vn 0.0309 0.6566 0.7536 +vn 0.5253 -0.8321 -0.1779 +vn -0.7399 0.4620 -0.4890 +vn -0.7451 0.6138 0.2609 +vn -0.7468 0.6650 0.0010 +vn 0.4437 -0.0799 0.8926 +vn 0.0422 -0.7213 -0.6913 +vn 0.4411 0.2066 -0.8733 +vn -0.6175 -0.6111 0.4953 +vn -0.4926 -0.1878 -0.8497 +vn -0.5769 0.1075 -0.8097 +vn -0.1651 -0.6254 -0.7627 +vn 0.3819 -0.6956 0.6085 +vn 0.8194 0.1705 0.5473 +vn 0.8309 0.1715 0.5293 +vn 0.9430 0.1792 0.2804 +vn 0.7434 0.5745 -0.3425 +vn 0.7313 0.5859 -0.3492 +vn 0.2546 0.1938 -0.9474 +vn 0.2316 0.6422 0.7307 +vn -0.9434 0.1653 0.2875 +vn -0.3680 0.9096 -0.1931 +vn 0.0456 0.7069 -0.7059 +vn -0.1101 0.6976 -0.7080 +vn 0.0456 0.7053 -0.7075 +vn 0.7037 -0.1096 -0.7020 +vn 0.3946 0.9109 -0.1206 +vn 0.3339 -0.7406 -0.5831 +vn 0.4640 -0.7564 -0.4611 +vn 0.1045 0.5997 0.7933 +vn 0.7103 0.1956 0.6762 +vn 0.7131 0.3038 0.6318 +vn 0.7102 0.3099 0.6321 +vn 0.2373 0.9116 -0.3356 +vn -0.1195 -0.7275 0.6756 +vn -0.9667 0.1630 0.1974 +vn 0.7115 0.4164 0.5661 +vn 0.9708 0.1032 -0.2164 +vn 0.1390 0.8251 -0.5476 +vn 0.1203 0.9721 -0.2016 +vn -0.0724 -0.7488 0.6589 +vn -0.2633 -0.7591 0.5953 +vn -0.2252 -0.8423 0.4897 +vn -0.7279 0.0919 -0.6795 +vn -0.7279 0.0918 -0.6795 +vn 0.7093 0.5587 0.4299 +vn 0.7092 -0.1341 0.6922 +vn 0.7092 -0.1341 0.6921 +vn 0.7092 -0.1342 0.6922 +vn 0.0597 0.6144 -0.7867 +vn 0.1048 0.4698 -0.8765 +vn -0.1922 0.6861 -0.7016 +vn -0.1140 0.6981 -0.7069 +vn 0.8556 0.1236 0.5026 +vn 0.9632 0.1593 0.2166 +vn 0.1175 -0.9423 -0.3136 +vn 0.1361 -0.9377 -0.3196 +vn -0.4027 0.1088 -0.9088 +vn -0.0009 0.0827 0.9966 +vn -0.0029 0.0620 0.9981 +vn -0.9653 -0.0882 0.2457 +vn -0.1818 0.9833 -0.0034 +vn 0.9410 -0.1134 0.3187 +vn -0.6064 -0.6909 0.3936 +vn -0.5951 -0.7129 0.3710 +vn -0.2159 0.1899 0.9578 +vn -0.4847 -0.8577 -0.1713 +vn -0.7063 -0.6935 0.1424 +vn -0.1726 -0.0643 -0.9829 +vn -0.6929 0.4223 -0.5844 +vn -0.9649 -0.0618 0.2553 +vn -0.8945 -0.0434 0.4450 +vn -0.9972 -0.0737 0.0146 +vn -0.3928 -0.8795 0.2687 +vn -0.0623 0.6471 -0.7598 +vn -0.2028 0.6015 -0.7727 +vn -0.2156 0.6503 -0.7284 +vn 0.1097 -0.6158 -0.7802 +vn -0.3221 -0.9069 -0.2715 +vn 0.1732 0.2174 -0.9606 +vn 0.1806 0.2326 -0.9557 +vn -0.9523 0.1265 0.2778 +vn 0.0009 -0.9970 -0.0778 +vn 0.0810 0.9755 0.2046 +vn 0.6645 -0.7473 -0.0031 +vn 0.0354 0.3302 0.9433 +vn 0.6027 0.7780 0.1775 +vn 0.2985 0.8560 0.4221 +vn 0.0898 0.6767 0.7308 +vn -0.1661 0.7547 0.6347 +vn -0.1860 0.7542 0.6297 +vn -0.0456 0.6319 0.7737 +vn 0.0505 0.8744 -0.4826 +vn -0.2721 -0.2846 0.9192 +vn 0.9873 0.1559 -0.0294 +vn 0.9268 0.2142 -0.3084 +vn 0.2635 -0.8925 0.3661 +vn -0.0485 0.8900 -0.4534 +vn 0.0441 0.4582 -0.8878 +vn -0.0545 -0.1557 -0.9863 +vn 0.6713 -0.6739 -0.3085 +vn 0.6416 -0.7357 -0.2170 +vn -0.2860 -0.5109 -0.8107 +vn 0.5862 -0.0099 0.8101 +vn -0.0758 0.6975 0.7126 +vn -0.0287 0.7526 0.6578 +vn 0.4527 -0.0512 -0.8902 +vn 0.5051 -0.7422 -0.4405 +vn 0.2431 0.0076 -0.9700 +vn 0.0294 0.1358 -0.9903 +vn 0.0727 0.7340 0.6752 +vn 0.0523 0.7487 0.6608 +vn -0.0023 0.0577 0.9983 +vn -0.8911 -0.3988 0.2165 +vn -0.0175 0.7002 -0.7137 +vn -0.0588 0.8284 -0.5571 +vn -0.3809 0.5906 0.7114 +vn 0.1179 -0.9862 0.1165 +vn -0.0053 0.2724 -0.9622 +vn 0.0179 0.0815 0.9965 +vn -0.3280 -0.6208 -0.7121 +vn 0.4912 0.1881 0.8505 +vn 0.7564 0.1118 0.6445 +vn 0.2638 0.0276 -0.9642 +vn 0.6737 -0.0342 0.7382 +vn 0.4088 -0.0983 0.9073 +vn 0.0728 0.9634 0.2580 +vn 0.4648 -0.3378 -0.8185 +vn -0.8945 0.3062 -0.3258 +vn 0.2285 0.0564 0.9719 +vn 0.7074 -0.6238 0.3325 +vn -0.7982 0.5547 0.2348 +vn -0.1794 0.9837 0.0141 +vn -0.0261 0.9989 0.0395 +vn 0.0025 0.9992 0.0398 +vn 0.0622 0.9966 0.0547 +vn 0.4834 -0.8235 0.2969 +vn 0.4413 0.7813 -0.4414 +vn -0.9618 -0.0841 0.2606 +vn 0.0117 -0.3804 0.9248 +vn -0.7468 -0.6650 0.0010 +vn -0.7092 -0.1341 -0.6922 +vn 0.0317 0.5603 -0.8277 +vn 0.0144 0.5138 -0.8578 +vn -0.0314 -0.1948 0.9803 +vn -0.2431 -0.0076 0.9700 +vn -0.0065 -0.0434 0.9990 +vn -0.0064 -0.0434 0.9990 +vn 0.6808 -0.0053 -0.7325 +vn 0.4190 -0.0604 -0.9060 +vn -0.5618 -0.8195 0.1128 +vn -0.3583 -0.8672 0.3457 +vn -0.9857 0.1560 0.0639 +vn 0.5095 0.6280 -0.5883 +vn 0.8508 0.4738 0.2271 +vn 0.7173 0.4913 -0.4940 +vn -0.4929 -0.8068 0.3258 +vn -0.5322 -0.7781 0.3338 +vn -0.5479 -0.8338 0.0681 +vn 0.1245 0.6305 0.7661 +vn -0.0322 -0.8682 -0.4951 +vn -0.4800 -0.7132 -0.5109 +vn -0.3745 -0.6656 -0.6455 +vn 0.7005 0.0289 0.7131 +vn 0.0355 0.1202 -0.9921 +vn 0.1070 -0.9898 0.0937 +vn -0.4527 -0.0512 0.8902 +vn 1.0000 -0.0003 0.0000 +vn -0.3621 0.1536 -0.9194 +vn -1.0000 -0.0001 0.0000 +vn 0.5413 0.8407 -0.0159 +vn 0.5055 0.8300 -0.2359 +vn -1.0000 -0.0009 0.0000 +vn 0.3791 -0.6319 0.6760 +vn -0.1666 0.5029 -0.8482 +vn 0.5391 -0.1621 0.8265 +vn -0.1104 -0.6804 0.7245 +vn 0.7493 0.1180 0.6517 +vn -0.9890 0.1424 0.0401 +vn 0.0579 0.4849 -0.8727 +vn -0.7944 -0.2098 -0.5701 +vn -0.8033 -0.1306 -0.5811 +vn 0.7019 -0.2078 -0.6813 +vn 0.2316 -0.6422 0.7307 +vn 0.4781 0.6913 0.5417 +vn 0.4768 0.6937 0.5398 +vn 0.7077 0.1340 -0.6937 +vn -0.5281 0.2746 0.8036 +vn -0.4553 -0.7138 -0.5321 +vn 0.7106 0.4244 0.5612 +vn 0.7121 0.4706 0.5210 +vn 0.7228 0.6256 -0.2935 +vn 0.6999 0.6717 -0.2428 +vn 0.0455 0.8518 0.5218 +vn 0.1487 -0.2322 0.9612 +vn 0.0915 -0.9919 0.0882 +vn 0.3715 0.7111 -0.5970 +vn 0.1607 -0.1998 0.9666 +vn 0.7047 0.4415 -0.5554 +vn 0.6632 0.5091 -0.5486 +vn 0.7182 0.4026 -0.5675 +vn 0.6980 0.4972 -0.5153 +vn 0.0042 0.9817 -0.1904 +vn 0.4822 -0.6026 0.6358 +vn 0.8033 0.2001 -0.5609 +vn -0.3159 -0.2048 0.9264 +vn 0.5274 -0.6239 -0.5767 +vn 0.5708 -0.1029 0.8146 +vn -0.5707 0.1029 -0.8147 +vn 0.0520 0.7529 0.6561 +vn -0.1115 -0.9809 0.1595 +vn 0.2120 0.7168 -0.6642 +vn -0.1787 -0.2107 0.9611 +vn -0.4307 -0.2358 0.8711 +vn -0.2486 -0.6533 0.7151 +vn -0.0241 0.5296 0.8479 +vn 0.0058 0.6347 0.7728 +vn 0.0904 0.4878 0.8683 +vn -0.0296 0.7589 0.6506 +vn -0.0228 0.7649 0.6437 +vn -0.0228 0.7648 0.6439 +vn 0.6978 -0.6983 -0.1599 +vn 0.7167 -0.6912 -0.0931 +vn 0.6970 -0.6920 -0.1880 +vn 0.0668 0.5930 0.8024 +vn -0.0162 0.7546 0.6560 +vn -0.0229 0.8130 0.5818 +vn -0.2399 -0.2596 0.9354 +vn -0.1598 0.5670 0.8081 +vn -0.3232 0.7789 0.5375 +vn -0.3173 0.7133 0.6249 +vn 0.0501 0.9761 -0.2116 +vn 0.0530 0.9155 -0.3988 +vn 0.0416 -0.6573 0.7525 +vn -0.0194 -0.7883 0.6150 +vn -0.6885 0.5742 -0.4430 +vn 0.7081 0.6881 -0.1583 +vn 0.4639 0.6073 0.6449 +vn 0.2925 0.7713 0.5653 +vn -0.0273 -0.8019 0.5968 +vn 0.0912 -0.5735 0.8141 +vn 0.2318 0.6656 -0.7094 +vn 0.0941 -0.7267 0.6805 +vn 0.0883 -0.6594 0.7466 +vn 0.0954 -0.7299 0.6768 +vn -0.3956 0.6077 0.6886 +vn -0.5825 0.6513 0.4863 +vn 0.1606 0.3333 -0.9290 +vn 0.1051 -0.7088 0.6975 +vn 0.0806 -0.6081 0.7898 +vn 0.0829 -0.5835 0.8078 +vn 0.0171 -0.5386 0.8424 +vn -0.2459 -0.2471 -0.9373 +vn 0.7280 -0.0246 0.6851 +vn -0.9926 0.1137 -0.0420 +vn 0.7697 0.0670 0.6348 +vn -0.1531 0.9092 -0.3872 +vn -0.3035 -0.6440 0.7022 +vn 0.0579 -0.4848 -0.8727 +vn -0.0068 0.1828 -0.9831 +vn -0.1179 0.1900 -0.9747 +vn 0.1963 0.6217 0.7583 +vn 0.3324 0.7271 0.6007 +vn 0.1436 0.6859 0.7134 +vn 0.5221 0.7147 0.4654 +vn 0.4834 0.7437 0.4618 +vn -0.8697 0.4877 -0.0758 +vn -0.5161 -0.1263 -0.8472 +vn 0.5086 -0.8021 0.3130 +vn 0.3583 -0.2249 0.9061 +vn 0.2518 -0.1002 -0.9626 +vn 0.1794 0.7127 -0.6781 +vn -0.6616 0.7387 -0.1289 +vn -0.2721 0.7808 -0.5624 +vn 0.0790 0.7499 0.6569 +vn -0.1422 0.9828 -0.1178 +vn -0.1615 0.9765 -0.1428 +vn -0.2846 0.1693 -0.9436 +vn -0.4679 0.5923 -0.6559 +vn 0.5966 0.6857 -0.4170 +vn 0.5448 -0.8326 0.1001 +vn 0.5483 -0.0672 0.8336 +vn 0.4609 -0.4850 -0.7432 +vn -0.6077 0.0850 -0.7896 +vn -0.1709 0.7040 -0.6893 +vn -0.8908 0.0615 -0.4503 +vn -0.8571 0.1463 -0.4939 +vn -0.9869 -0.1299 -0.0961 +vn -0.9297 -0.1570 -0.3331 +vn -0.9770 -0.1012 0.1876 +vn -0.9894 -0.1395 0.0398 +vn -0.9894 -0.1394 0.0398 +vn -0.3528 -0.8038 -0.4790 +vn -0.8187 0.5460 0.1777 +vn 0.7933 -0.2302 -0.5636 +vn 0.2265 0.8266 0.5153 +vn -0.0326 0.8376 0.5453 +vn 0.0038 -0.9954 -0.0954 +vn 0.1916 0.7534 -0.6290 +vn 0.0975 -0.4009 0.9109 +vn 0.4258 0.8530 -0.3017 +vn 0.5165 0.4453 -0.7314 +vn -0.0563 -0.0578 0.9967 +vn 0.3819 0.6956 0.6086 +vn -0.5757 -0.7381 -0.3517 +vn 0.9667 0.1630 -0.1974 +vn 0.7353 -0.6192 -0.2756 +vn 0.8019 -0.5968 0.0281 +vn 0.8020 -0.5963 0.0355 +vn 0.1441 -0.9886 0.0439 +vn -0.1941 0.2834 0.9392 +vn 0.1205 0.4524 -0.8836 +vn -0.0190 -0.2029 -0.9790 +vn -0.2338 0.5947 -0.7692 +vn -0.2721 0.8008 -0.5336 +vn 0.9488 0.1500 0.2781 +vn 0.9905 0.1376 -0.0038 +vn -0.7402 0.6668 0.0864 +vn -0.7343 0.5415 0.4093 +vn 0.4167 0.2487 -0.8743 +vn 0.2451 0.8086 0.5349 +vn 0.9918 -0.1108 -0.0637 +vn 0.5952 -0.5660 -0.5704 +vn 0.7434 -0.5745 -0.3425 +vn 0.7313 -0.5859 -0.3492 +vn 0.7276 -0.6849 -0.0395 +vn 0.7510 -0.6590 -0.0412 +vn 0.6081 -0.7828 0.1321 +vn -0.1975 0.7445 -0.6378 +vn 0.8561 0.0012 0.5168 +vn 0.9549 -0.0726 0.2880 +vn 0.2178 -0.0092 0.9759 +vn 0.1279 0.0105 0.9917 +vn 0.8088 -0.5867 0.0401 +vn 0.9359 -0.3018 -0.1818 +vn -0.9352 -0.2040 -0.2895 +vn 0.8092 0.1366 0.5714 +vn -0.1301 -0.9683 0.2135 +vn 0.1131 -0.9912 -0.0684 +vn -0.8569 -0.0402 0.5139 +vn 0.3552 -0.0043 -0.9348 +vn -0.0460 0.6328 -0.7730 +vn -0.4487 -0.1503 -0.8809 +vn 0.0414 -0.9565 -0.2888 +vn 0.5542 -0.7962 -0.2428 +vn -0.4515 0.7389 -0.5001 +vn 0.6905 -0.3004 -0.6580 +vn -0.6772 -0.7322 0.0727 +vn -0.0110 0.9997 -0.0218 +vn 0.5170 0.0070 0.8560 +vn 0.0026 0.2630 -0.9648 +vn -0.4909 0.8706 0.0324 +vn 0.9680 -0.1577 -0.1950 +vn 0.9861 -0.1457 -0.0794 +vn 0.1311 0.9775 -0.1651 +vn 0.0323 -0.3062 0.9514 +vn -0.5893 0.1214 -0.7987 +vn -0.2436 0.2443 -0.9386 +vn -0.4319 0.2101 -0.8771 +vn 0.0943 0.7049 -0.7031 +vn 0.0335 0.7197 -0.6935 +vn 0.0840 0.7052 -0.7040 +vn 0.1407 -0.8398 0.5243 +vn 1.0000 -0.0002 0.0000 +vn 0.9434 0.1653 -0.2875 +vn 0.0573 0.9980 0.0270 +vn 0.0279 0.9991 0.0326 +vn 0.0415 0.5321 -0.8457 +vn 0.0418 0.5342 -0.8443 +vn 0.0889 0.7056 -0.7030 +vn 0.7038 0.1371 0.6971 +vn 0.2978 0.7286 -0.6169 +vn -0.0171 0.6821 0.7311 +vn -0.0322 0.7591 0.6502 +vn 0.9565 0.1442 0.2535 +vn 0.9747 0.1287 0.1826 +vn 0.0971 -0.9946 -0.0362 +vn -0.1715 -0.4736 0.8639 +vn -0.8979 0.1920 0.3961 +vn 0.9909 -0.1193 0.0622 +vn -0.5423 0.6950 -0.4721 +vn 0.9600 -0.0767 0.2693 +vn 0.9755 -0.0976 0.1972 +vn -0.3602 0.6350 -0.6834 +vn 0.5246 -0.8326 0.1776 +vn -0.7364 0.2877 -0.6123 +vn -0.8680 -0.0226 -0.4961 +vn -0.2748 -0.8203 0.5015 +vn -0.5483 0.0671 -0.8336 +vn -0.0216 0.6398 -0.7683 +vn -0.1015 0.9888 -0.1093 +vn 0.0631 0.8919 0.4478 +vn -0.9734 0.1449 0.1772 +vn -0.9250 0.2096 0.3169 +vn 0.0113 0.0351 0.9993 +vn -0.0081 0.0173 0.9998 +vn 0.0107 0.0346 0.9993 +vn 0.7068 -0.2276 -0.6698 +vn -0.0771 -0.9682 -0.2379 +vn -0.7321 0.6662 -0.1419 +vn -0.6772 0.7322 0.0727 +vn 0.5437 -0.0855 0.8349 +vn 0.7100 -0.5952 0.3763 +vn -0.1423 -0.9804 -0.1359 +vn -0.9918 -0.1108 0.0637 +vn 0.7181 0.0740 -0.6920 +vn -0.2559 0.9083 0.3308 +vn 0.0465 0.9881 0.1464 +vn 0.1784 -0.7704 -0.6121 +vn -0.6950 -0.1657 -0.6997 +vn -0.0463 0.9654 0.2565 +vn -0.2585 -0.1264 -0.9577 +vn 0.8429 0.0054 0.5380 +vn 0.9733 -0.0836 0.2139 +vn -0.9540 0.0592 0.2941 +vn -0.9540 0.0592 0.2940 +vn 0.1859 -0.0070 0.9825 +vn 0.4283 0.6783 -0.5971 +vn 0.0828 0.9702 0.2276 +vn 0.0827 0.9701 0.2281 +vn -0.6392 0.6824 0.3547 +vn -0.6749 0.2596 0.6907 +vn 0.0983 -0.8568 0.5063 +vn -0.0953 -0.9933 0.0659 +vn 0.7082 -0.7060 -0.0037 +vn 0.6657 0.7244 0.1790 +vn 0.0532 0.9243 0.3779 +vn 0.0639 0.8003 0.5962 +vn 0.8559 0.0796 -0.5110 +vn 0.6351 0.6806 0.3654 +vn -0.9953 -0.0943 0.0206 +vn -0.7482 0.6595 0.0722 +vn -0.0136 -0.1858 -0.9825 +vn -0.8361 -0.5357 0.1182 +vn -0.0623 -0.6471 -0.7598 +vn 0.0677 -0.6492 0.7576 +vn -0.1172 -0.0187 -0.9929 +vn 0.0422 0.7079 -0.7051 +vn -0.6342 0.0843 -0.7686 +vn -0.4302 0.7084 -0.5595 +vn 0.9555 -0.1558 -0.2503 +vn -0.3065 0.1216 -0.9441 +vn 0.7641 0.0262 -0.6446 +vn -0.5610 -0.6183 -0.5504 +vn -0.5764 -0.5799 -0.5757 +vn 0.4527 -0.0511 -0.8902 +vn -0.0416 -0.9400 0.3387 +vn 0.3837 -0.7779 0.4976 +vn -0.0060 0.1888 -0.9820 +vn 0.8694 0.0327 0.4930 +vn -0.0765 -0.7288 0.6805 +vn -0.6567 0.6445 0.3916 +vn -0.9868 0.1422 -0.0776 +vn -0.0712 0.9971 0.0268 +vn -0.0781 0.9969 0.0132 +vn 0.2514 0.7237 -0.6427 +vn 0.1068 0.6394 -0.7614 +vn 0.1242 0.6854 -0.7175 +vn -0.7736 -0.5623 0.2921 +vn -0.3983 0.1544 -0.9042 +vn -0.9772 0.1617 0.1380 +vn 0.1784 0.7704 -0.6121 +vn 0.8518 0.1502 0.5019 +vn 0.8560 -0.1935 -0.4793 +vn 0.8322 -0.2411 -0.4993 +vn 0.8008 -0.5896 0.1056 +vn -0.1835 0.8141 -0.5509 +vn -0.2298 0.7596 -0.6085 +vn 0.0100 -0.0133 0.9999 +vn -0.4411 0.2065 0.8734 +vn -0.4475 -0.7918 0.4156 +vn 0.5391 0.1621 0.8265 +vn 0.0570 0.6254 -0.7782 +vn -0.1807 0.9829 0.0350 +vn -0.3621 -0.1536 -0.9194 +vn -0.3983 -0.1544 -0.9042 +vn -0.0151 0.6485 0.7611 +vn -0.7764 -0.5759 0.2562 +vn -0.1301 0.9683 0.2134 +vn -0.3954 0.9108 0.1190 +vn -0.2068 0.2528 -0.9452 +vn 0.3287 0.7156 0.6164 +vn -0.0574 0.9946 -0.0861 +vn 0.6093 -0.3736 0.6994 +vn -0.3731 0.0481 0.9265 +vn 0.0230 0.0111 -0.9997 +vn 0.3715 -0.7111 -0.5970 +vn 0.0402 -0.8809 0.4716 +vn -0.1104 -0.9651 0.2377 +vn 0.1653 -0.5942 0.7872 +vn -0.1803 -0.0154 -0.9835 +vn -0.3108 -0.8272 0.4681 +vn 0.1117 -0.9930 0.0391 +vn 0.1117 -0.9930 0.0378 +vn 0.7615 -0.0093 -0.6481 +vn 0.4283 -0.6783 -0.5971 +vn 0.1941 0.2834 -0.9392 +vn 0.0774 -0.6076 -0.7904 +vn 0.5595 -0.8189 -0.1277 +vn -0.7763 0.5759 0.2562 +vn -0.4444 0.8538 0.2712 +vn -0.8811 0.0414 -0.4711 +vn -0.9647 0.0015 -0.2632 +vn -0.9979 -0.0438 -0.0488 +vn 0.7128 -0.6697 -0.2083 +vn -0.0776 0.9956 -0.0515 +vn 0.4074 0.2016 -0.8907 +vn 0.2668 -0.0819 -0.9603 +vn 0.4879 -0.0448 -0.8718 +vn -0.9977 0.0017 0.0675 +vn -0.9958 -0.0151 0.0904 +vn 0.1151 0.8999 -0.4207 +vn 0.0936 -0.9907 0.0988 +vn 0.9638 0.1461 -0.2232 +vn 0.0700 0.0105 -0.9975 +vn -0.8733 -0.0309 -0.4862 +vn 0.3171 0.8790 -0.3560 +vn 0.7523 -0.6026 0.2664 +vn -0.1812 -0.9741 -0.1355 +vn -0.1107 -0.9884 -0.1045 +vn 0.7309 0.6816 -0.0347 +vn 0.4167 0.2488 -0.8743 +vn -0.0432 0.0138 0.9990 +vn -0.7100 -0.6658 -0.2294 +vn 0.5156 -0.8111 0.2762 +vn 0.9742 0.0590 0.2178 +vn -0.8324 -0.5519 -0.0502 +vn 0.9661 0.1461 -0.2127 +vn 0.5391 -0.1620 0.8265 +vn -0.5710 -0.8048 -0.1623 +vn 0.0441 0.9784 0.2020 +vn -0.4096 0.5438 0.7325 +vn 1.0000 -0.0009 0.0000 +vn -0.4411 -0.2066 0.8734 +vn 0.5538 -0.7145 0.4275 +vn 0.0217 0.0047 -0.9998 +vn 0.5156 0.8111 0.2762 +vn -0.7493 -0.1181 -0.6516 +vn -0.0310 -0.9970 -0.0712 +vn 0.0166 0.7145 -0.6995 +vn -0.0369 0.6801 -0.7322 +vn 0.1214 0.7958 -0.5932 +vn -0.0179 0.8066 -0.5909 +vn 0.9773 0.0273 0.2102 +vn 0.7123 -0.1534 0.6849 +vn 0.7047 -0.1438 0.6947 +vn -0.2258 0.5181 0.8250 +vn -0.9649 0.0617 0.2553 +vn 0.7051 0.1891 -0.6835 +vn -0.9936 -0.1123 -0.0141 +vn 0.9523 -0.1265 -0.2778 +vn 0.8399 0.0379 0.5414 +vn -0.7267 -0.4297 -0.5359 +vn 0.7092 0.1341 0.6921 +vn -0.4167 -0.2487 0.8743 +vn 0.1616 -0.1449 -0.9762 +vn -0.7812 -0.6059 -0.1504 +vn -0.7321 -0.6662 -0.1419 +vn -0.2307 -0.4281 0.8738 +vn 0.6091 -0.7759 0.1643 +vn 0.0617 0.9924 -0.1061 +vn -0.9721 -0.0539 -0.2281 +vn -0.9632 0.0031 -0.2688 +vn -0.9888 0.0641 0.1348 +vn 1.0000 0.0004 0.0000 +vn 0.1301 0.9683 -0.2135 +vn 0.5054 -0.4284 -0.7490 +vn 0.8320 -0.5495 -0.0765 +vn 0.9638 -0.1559 0.2162 +vn -0.8348 0.0367 -0.5494 +vn 0.5483 -0.0671 0.8336 +vn -0.9849 -0.0360 -0.1693 +vn 0.9152 -0.1274 -0.3824 +vn -0.4048 0.0752 -0.9113 +vn 0.4411 0.2066 -0.8734 +vn -0.0264 0.9954 0.0922 +vn 0.2261 0.0327 -0.9736 +vn -0.0628 -0.9975 0.0327 +vn -0.0540 -0.9975 0.0444 +vn 0.0505 -0.6125 -0.7888 +vn 0.7317 -0.0009 0.6817 +vn -0.0827 -0.7826 0.6169 +vn 0.1906 -0.6253 -0.7567 +vn -0.9945 0.1040 0.0148 +vn 0.1767 -0.8566 0.4848 +vn 0.4472 0.6691 -0.5935 +vn -0.9013 -0.1554 -0.4042 +vn -0.2823 -0.2382 -0.9293 +vn -0.6693 -0.6559 -0.3490 +vn 0.8109 -0.0378 -0.5839 +vn 0.7127 0.7003 0.0409 +vn -0.0010 -0.7678 0.6406 +vn 0.0961 -0.7682 0.6329 +vn -0.0412 0.9947 -0.0939 +vn -0.0221 0.9978 -0.0630 +vn -0.1257 -0.5215 0.8439 +vn 0.9540 -0.0591 -0.2940 +vn -0.1073 0.7001 0.7059 +vn 0.9156 -0.1718 -0.3636 +vn -0.0914 -0.8317 -0.5476 +vn 0.1144 -0.9933 -0.0128 +vn 1.0000 -0.0008 0.0000 +vn -0.1369 -0.3182 0.9381 +vn -0.4411 -0.2066 0.8733 +vn 0.1062 0.9899 0.0938 +vn -0.9540 -0.0592 0.2941 +vn -0.9540 -0.0592 0.2940 +vn 0.0714 0.6834 -0.7265 +vn -0.1772 -0.9827 -0.0541 +vn -0.5778 -0.6949 -0.4281 +vn 0.1177 0.9862 0.1166 +vn 0.3791 0.6319 0.6760 +vn 0.2295 0.7357 0.6373 +vn -0.9832 -0.1135 0.1432 +vn -0.5285 0.4456 0.7226 +vn 0.0307 0.9993 0.0202 +vn -0.9910 -0.0314 0.1303 +vn -0.9850 -0.0436 0.1670 +vn -0.7766 -0.4293 0.4611 +vn -0.2732 0.8080 -0.5220 +vn 0.7353 0.6192 -0.2756 +vn 0.8020 0.5963 0.0355 +vn 0.8019 0.5968 0.0281 +vn -0.7092 -0.1341 -0.6921 +vn -0.1448 0.7641 -0.6286 +vn 0.5087 -0.7896 0.3431 +vn 0.0611 -0.7978 0.5998 +vn -0.0272 0.9947 -0.0992 +vn 0.6701 -0.2885 -0.6839 +vn -0.7812 0.6059 -0.1504 +vn 0.9230 -0.1503 0.3544 +vn -0.5315 0.8471 0.0045 +vn 0.1133 -0.9910 -0.0714 +vn -0.1527 -0.0576 0.9866 +vn -0.0597 -0.6316 0.7730 +vn 0.7938 -0.6033 -0.0764 +vn -0.1328 0.9832 0.1255 +vn -0.0187 0.9965 -0.0815 +vn -0.0160 0.9960 -0.0881 +vn -0.0984 -0.9511 0.2927 +vn -0.0759 -0.8985 0.4324 +vn -0.9497 0.0895 -0.3002 +vn 0.2029 0.9498 0.2383 +vn -0.5391 -0.1621 -0.8265 +vn -0.2277 -0.6995 -0.6773 +vn 0.0602 -0.3004 -0.9519 +vn 0.0204 0.9997 -0.0131 +vn 0.9875 0.1458 -0.0597 +vn 0.0531 0.6526 0.7559 +vn 0.4900 0.0674 -0.8691 +vn 0.0446 0.9988 0.0216 +vn 0.1079 -0.9933 -0.0412 +vn 0.1927 0.6640 0.7225 +vn 0.1628 0.6644 0.7294 +vn 0.9894 0.1393 -0.0398 +vn -0.0776 -0.9956 -0.0515 +vn 0.1079 -0.9900 0.0908 +vn -0.5483 -0.0672 -0.8336 +vn -0.2267 -0.0569 -0.9723 +vn 0.7093 -0.1966 0.6769 +vn 0.0549 0.9928 -0.1066 +vn 0.0983 0.9917 0.0833 +vn 0.4765 0.2081 -0.8542 +vn 0.0484 -0.6729 0.7382 +vn 0.1214 -0.7958 -0.5932 +vn 0.5916 0.0812 0.8021 +vn 0.4527 0.0511 -0.8902 +vn -0.0225 0.9951 -0.0964 +vn 0.7232 0.3945 -0.5668 +vn 0.1363 0.5402 0.8304 +vn -0.1396 0.9902 -0.0065 +vn -0.5391 0.1621 -0.8265 +vn -0.0446 -0.9948 -0.0919 +vn 0.0792 0.4064 -0.9102 +vn 0.0936 -0.9951 -0.0317 +vn 0.0929 -0.9951 -0.0328 +vn -0.1273 -0.9895 -0.0691 +vn 0.0960 0.9899 0.1043 +vn 0.1849 -0.9199 0.3457 +vn -0.1300 0.9683 0.2134 +vn -0.5483 -0.0671 -0.8336 +vn 0.2149 0.0040 0.9766 +vn -0.0766 0.0005 -0.9971 +vn -0.1312 -0.0091 -0.9913 +vn 0.6067 -0.0455 0.7936 +vn -0.0975 0.9923 -0.0767 +vn 0.7285 -0.6831 -0.0514 +vn 0.7245 -0.6578 -0.2059 +vn -0.0176 0.9965 -0.0822 +vn -0.5390 -0.1621 -0.8265 +vn 0.0560 -0.6141 0.7873 +vn 0.0518 -0.0015 -0.9987 +vn 0.0127 -0.7299 0.6834 +vn 0.7333 -0.6642 -0.1456 +vn 0.0188 0.9997 -0.0123 +vn -0.1150 -0.5487 0.8280 +vn 0.0049 0.0563 0.9984 +vn 0.0191 -0.8875 0.4603 +vn -0.1528 -0.1630 0.9747 +vn 0.5391 0.1620 0.8265 +vn -0.0016 0.9974 -0.0723 +vn -0.9875 -0.1456 0.0598 +vn 0.0847 -0.9960 -0.0275 +vn 0.0402 -0.8809 0.4717 +vn 0.9910 0.1307 0.0298 +vn -0.0732 -0.0549 -0.9958 +vn 0.7071 0.3628 -0.6070 +vn 0.1113 0.0904 0.9897 +vn 0.1317 -0.2179 0.9671 +vn -0.3694 0.5337 -0.7607 +vn 0.5483 0.0671 0.8336 +vn -0.2071 0.1327 -0.9693 +vn -0.4411 -0.2065 0.8734 +vn -0.1981 0.0255 -0.9798 +vn 0.0321 -0.0114 -0.9994 +vn 0.7369 -0.6720 0.0729 +vn -0.2367 0.0522 -0.9702 +vn 0.0917 -0.9953 -0.0312 +vn 0.5204 -0.7247 -0.4516 +vn -0.1475 0.9831 0.1081 +vn -0.2371 0.2087 0.9488 +vn -0.5390 0.1621 -0.8265 +vn 0.8399 -0.0379 0.5414 +vn -0.9904 0.1059 0.0884 +vn 0.1180 0.0107 -0.9930 +vn 0.0602 0.8099 0.5835 +vn 0.4204 0.6068 0.6746 +vn -0.1679 -0.1174 -0.9788 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 1/1/1 4/4/4 2/2/2 +f 1/1/1 5/5/5 4/4/4 +f 6/6/6 7/7/7 8/8/8 +f 8/8/8 7/7/7 9/9/9 +f 9/9/10 10/10/11 8/8/12 +f 8/8/12 10/10/11 11/11/13 +f 11/11/14 10/10/15 12/12/16 +f 11/11/14 12/12/16 13/13/17 +f 13/13/18 12/12/18 14/14/18 +f 13/13/19 14/14/20 15/15/21 +f 14/14/20 16/16/22 15/15/21 +f 15/15/23 16/16/24 17/17/25 +f 15/15/23 17/17/25 18/18/26 +f 18/18/27 17/17/28 19/19/29 +f 19/19/29 17/17/28 20/20/30 +f 19/19/31 20/20/32 6/6/33 +f 6/6/33 20/20/32 7/7/34 +f 3/3/35 14/14/36 12/12/37 +f 3/3/35 12/12/37 1/1/38 +f 1/1/38 12/12/37 10/10/39 +f 10/10/40 9/9/41 1/1/42 +f 1/1/42 9/9/41 5/5/43 +f 5/5/44 9/9/9 7/7/7 +f 5/5/45 7/7/46 4/4/47 +f 4/4/47 7/7/46 20/20/48 +f 4/4/49 20/20/49 17/17/49 +f 4/4/50 17/17/51 2/2/52 +f 2/2/52 17/17/51 16/16/53 +f 16/16/54 14/14/36 2/2/55 +f 2/2/55 14/14/36 3/3/35 +f 6/6/56 21/21/56 19/19/56 +f 19/19/56 21/21/56 22/22/56 +f 8/8/56 23/23/56 6/6/56 +f 8/8/56 24/24/56 23/23/56 +f 11/11/56 25/25/56 24/24/56 +f 11/11/56 24/24/56 8/8/56 +f 19/19/56 26/26/56 18/18/56 +f 19/19/56 22/22/56 26/26/56 +f 6/6/56 23/23/56 21/21/56 +f 15/15/56 27/27/56 13/13/56 +f 13/13/56 27/27/56 28/28/56 +f 13/13/56 29/29/56 11/11/56 +f 11/11/56 29/29/56 25/25/56 +f 13/13/56 28/28/56 29/29/56 +f 18/18/56 26/26/56 15/15/56 +f 15/15/56 26/26/56 27/27/56 +f 30/30/57 31/31/58 32/32/59 +f 32/32/59 31/31/58 33/33/60 +f 32/32/59 33/33/60 34/34/61 +f 35/35/62 34/34/61 36/36/63 +f 35/35/62 36/36/63 37/37/64 +f 37/37/64 36/36/63 38/38/65 +f 39/39/66 40/40/67 41/41/68 +f 32/32/59 34/34/61 35/35/62 +f 37/37/64 38/38/65 42/42/69 +f 42/42/69 38/38/65 43/43/70 +f 44/44/71 45/45/72 46/46/73 +f 39/39/66 47/47/74 40/40/67 +f 41/41/68 40/40/67 48/48/75 +f 30/30/57 48/48/75 31/31/58 +f 46/46/73 49/49/76 39/39/66 +f 39/39/66 49/49/76 47/47/74 +f 41/41/68 48/48/75 30/30/57 +f 46/46/73 45/45/72 49/49/76 +f 42/42/69 43/43/70 44/44/71 +f 44/44/71 43/43/70 45/45/72 +f 25/25/77 46/46/77 24/24/77 +f 24/24/78 46/46/78 39/39/78 +f 24/24/79 39/39/79 23/23/79 +f 23/23/80 39/39/81 41/41/82 +f 23/23/80 41/41/82 21/21/83 +f 21/21/84 41/41/84 22/22/84 +f 22/22/85 41/41/85 30/30/85 +f 22/22/86 30/30/86 26/26/86 +f 26/26/87 30/30/87 32/32/87 +f 26/26/88 32/32/88 27/27/88 +f 27/27/89 32/32/89 35/35/89 +f 27/27/90 35/35/90 28/28/90 +f 28/28/91 35/35/92 37/37/93 +f 28/28/91 37/37/93 42/42/94 +f 28/28/91 42/42/94 29/29/95 +f 29/29/96 42/42/96 44/44/96 +f 29/29/97 44/44/97 25/25/97 +f 25/25/98 44/44/98 46/46/98 +f 50/50/99 51/51/100 52/52/101 +f 50/50/99 52/52/101 53/53/102 +f 54/54/103 51/51/100 50/50/99 +f 55/55/104 56/56/105 57/57/106 +f 56/56/105 58/58/107 59/59/108 +f 54/54/103 60/60/109 61/61/110 +f 55/55/104 61/61/110 60/60/109 +f 58/58/107 62/62/111 59/59/108 +f 63/63/112 62/62/111 58/58/107 +f 56/56/105 59/59/108 57/57/106 +f 61/61/110 51/51/100 54/54/103 +f 55/55/104 57/57/106 61/61/110 +f 50/50/99 53/53/102 63/63/112 +f 63/63/112 53/53/102 62/62/111 +f 61/61/113 64/64/114 51/51/115 +f 62/62/116 65/65/117 59/59/118 +f 57/57/119 66/66/120 61/61/113 +f 53/53/121 67/67/122 62/62/116 +f 62/62/116 68/68/123 65/65/117 +f 61/61/113 69/69/124 64/64/114 +f 51/51/115 70/70/125 52/52/126 +f 52/52/126 70/70/125 71/71/127 +f 52/52/126 71/71/127 53/53/121 +f 71/71/127 72/72/128 53/53/121 +f 53/53/121 72/72/128 67/67/122 +f 67/67/122 68/68/123 62/62/116 +f 59/59/118 73/73/129 74/74/130 +f 59/59/118 74/74/130 57/57/119 +f 61/61/113 66/66/120 69/69/124 +f 74/74/130 75/75/131 57/57/119 +f 57/57/119 75/75/131 66/66/120 +f 64/64/114 76/76/132 51/51/115 +f 51/51/115 76/76/132 70/70/125 +f 65/65/117 77/77/133 59/59/118 +f 59/59/118 77/77/133 73/73/129 +f 67/67/122 49/49/134 68/68/123 +f 70/70/125 40/40/135 71/71/127 +f 72/72/128 49/49/134 67/67/122 +f 77/77/133 43/43/136 73/73/129 +f 73/73/129 38/38/137 74/74/130 +f 74/74/130 36/36/138 75/75/131 +f 75/75/131 34/34/139 66/66/120 +f 66/66/120 34/34/139 33/33/140 +f 66/66/120 33/33/140 69/69/124 +f 69/69/124 33/33/140 31/31/141 +f 69/69/124 31/31/141 64/64/114 +f 64/64/114 31/31/141 48/48/142 +f 64/64/114 48/48/142 76/76/132 +f 71/71/127 47/47/143 72/72/128 +f 49/49/134 45/45/144 68/68/123 +f 68/68/123 45/45/144 65/65/117 +f 65/65/117 45/45/144 77/77/133 +f 73/73/129 43/43/136 38/38/137 +f 76/76/132 40/40/135 70/70/125 +f 72/72/128 47/47/143 49/49/134 +f 77/77/133 45/45/144 43/43/136 +f 74/74/130 38/38/137 36/36/138 +f 36/36/138 34/34/139 75/75/131 +f 76/76/132 48/48/142 40/40/135 +f 71/71/127 40/40/135 47/47/143 +f 78/78/145 79/79/145 80/80/145 +f 80/80/145 79/79/145 81/81/145 +f 80/80/145 81/81/145 82/82/145 +f 82/82/145 81/81/145 83/83/145 +f 60/60/146 78/78/147 80/80/148 +f 80/80/148 55/55/149 60/60/146 +f 60/60/146 54/54/150 78/78/147 +f 78/78/151 54/54/152 79/79/152 +f 79/79/152 54/54/152 50/50/153 +f 79/79/154 63/63/155 81/81/156 +f 79/79/154 50/50/157 63/63/155 +f 81/81/158 63/63/159 83/83/160 +f 63/63/159 58/58/161 83/83/160 +f 83/83/162 58/58/163 82/82/164 +f 82/82/164 58/58/163 56/56/165 +f 82/82/166 55/55/167 80/80/168 +f 82/82/166 56/56/169 55/55/167 +f 84/84/170 85/85/171 86/86/172 +f 86/86/172 85/85/171 87/87/173 +f 86/86/174 87/87/175 88/88/176 +f 88/88/176 87/87/175 89/89/177 +f 88/88/178 89/89/179 90/90/180 +f 88/88/178 90/90/180 91/91/181 +f 91/91/182 90/90/183 92/92/184 +f 91/91/182 92/92/184 93/93/185 +f 93/93/186 92/92/186 94/94/186 +f 93/93/187 94/94/187 95/95/187 +f 95/95/188 94/94/188 96/96/188 +f 95/95/189 96/96/189 97/97/189 +f 97/97/190 96/96/190 98/98/190 +f 97/97/191 98/98/191 99/99/191 +f 99/99/192 98/98/192 100/100/192 +f 99/99/193 100/100/193 101/101/193 +f 101/101/194 100/100/194 102/102/194 +f 101/101/195 102/102/195 84/84/195 +f 84/84/196 102/102/196 85/85/196 +f 103/103/56 96/96/56 104/104/56 +f 103/103/56 98/98/56 96/96/56 +f 105/105/56 100/100/56 98/98/56 +f 105/105/56 98/98/56 103/103/56 +f 104/104/56 94/94/56 106/106/56 +f 106/106/56 90/90/56 107/107/56 +f 96/96/56 94/94/56 104/104/56 +f 108/108/56 87/87/56 85/85/56 +f 107/107/56 89/89/56 87/87/56 +f 106/106/56 92/92/56 90/90/56 +f 106/106/56 94/94/56 92/92/56 +f 109/109/56 102/102/56 100/100/56 +f 109/109/56 100/100/56 105/105/56 +f 107/107/56 87/87/56 108/108/56 +f 107/107/56 90/90/56 89/89/56 +f 108/108/56 85/85/56 109/109/56 +f 109/109/56 85/85/56 102/102/56 +f 108/108/197 110/110/198 107/107/199 +f 107/107/199 110/110/198 111/111/200 +f 107/107/201 111/111/202 112/112/203 +f 107/107/201 112/112/203 106/106/204 +f 106/106/204 112/112/203 113/113/205 +f 106/106/206 113/113/207 114/114/208 +f 106/106/206 114/114/208 104/104/209 +f 104/104/210 114/114/211 103/103/212 +f 103/103/212 114/114/211 115/115/213 +f 103/103/214 115/115/215 116/116/216 +f 103/103/214 116/116/216 105/105/217 +f 105/105/218 116/116/219 117/117/220 +f 105/105/218 117/117/220 109/109/221 +f 109/109/222 117/117/223 110/110/224 +f 109/109/222 110/110/224 108/108/225 +f 117/117/226 118/118/227 119/119/228 +f 116/116/229 120/120/230 118/118/227 +f 116/116/229 118/118/227 117/117/226 +f 117/117/226 119/119/228 110/110/231 +f 110/110/231 119/119/228 121/121/232 +f 114/114/233 122/122/234 115/115/235 +f 122/122/234 123/123/236 115/115/235 +f 115/115/235 123/123/236 116/116/229 +f 116/116/229 123/123/236 120/120/230 +f 110/110/231 121/121/232 111/111/237 +f 113/113/238 124/124/239 114/114/233 +f 114/114/233 124/124/239 122/122/234 +f 112/112/240 125/125/241 113/113/238 +f 113/113/238 125/125/241 124/124/239 +f 111/111/237 121/121/232 126/126/242 +f 111/111/237 126/126/242 112/112/240 +f 112/112/240 126/126/242 125/125/241 +f 127/127/243 128/128/244 129/129/245 +f 130/130/246 129/129/245 128/128/244 +f 129/129/245 130/130/246 131/131/247 +f 131/131/247 130/130/246 132/132/248 +f 118/118/249 132/132/248 130/130/246 +f 118/118/249 133/133/250 132/132/248 +f 133/133/250 118/118/249 120/120/251 +f 133/133/250 120/120/251 134/134/252 +f 134/134/252 120/120/251 123/123/253 +f 123/123/253 135/135/254 134/134/252 +f 123/123/253 136/136/255 135/135/254 +f 136/136/255 123/123/253 122/122/256 +f 137/137/257 136/136/255 122/122/256 +f 137/137/257 122/122/256 138/138/258 +f 137/137/257 138/138/258 139/139/259 +f 139/139/259 138/138/258 140/140/260 +f 124/124/261 140/140/260 138/138/258 +f 140/140/260 124/124/261 141/141/262 +f 141/141/262 124/124/261 125/125/263 +f 125/125/263 142/142/264 141/141/262 +f 125/125/263 143/143/265 142/142/264 +f 143/143/265 125/125/263 126/126/266 +f 143/143/265 126/126/266 144/144/267 +f 121/121/268 144/144/267 126/126/266 +f 121/121/268 145/145/269 144/144/267 +f 145/145/269 121/121/268 128/128/244 +f 128/128/244 127/127/243 145/145/269 +f 101/101/270 146/146/271 147/147/272 +f 84/84/273 146/146/271 101/101/270 +f 101/101/270 147/147/272 99/99/274 +f 84/84/273 127/127/275 146/146/271 +f 99/99/274 148/148/276 97/97/277 +f 97/97/277 148/148/276 135/135/278 +f 147/147/272 148/148/276 99/99/274 +f 97/97/277 135/135/278 137/137/279 +f 97/97/277 137/137/279 95/95/280 +f 95/95/280 137/137/279 149/149/281 +f 93/93/282 150/150/283 91/91/284 +f 91/91/284 142/142/285 88/88/286 +f 88/88/286 142/142/285 151/151/287 +f 86/86/288 152/152/289 127/127/275 +f 86/86/288 127/127/275 84/84/273 +f 93/93/282 140/140/290 150/150/283 +f 88/88/286 151/151/287 152/152/289 +f 95/95/280 149/149/281 93/93/282 +f 93/93/282 149/149/281 140/140/290 +f 91/91/284 150/150/283 142/142/285 +f 88/88/286 152/152/289 86/86/288 +f 148/148/291 147/147/291 133/133/291 +f 134/134/292 148/148/293 133/133/294 +f 132/132/295 147/147/296 131/131/297 +f 131/131/298 146/146/298 129/129/298 +f 127/127/243 152/152/299 145/145/269 +f 151/151/300 143/143/300 144/144/300 +f 142/142/285 150/150/283 141/141/301 +f 150/150/302 140/140/260 141/141/262 +f 140/140/303 149/149/281 139/139/304 +f 135/135/254 136/136/255 137/137/305 +f 135/135/306 148/148/293 134/134/292 +f 133/133/307 147/147/296 132/132/295 +f 147/147/296 146/146/308 131/131/297 +f 127/127/243 129/129/245 146/146/309 +f 145/145/310 152/152/310 144/144/310 +f 152/152/311 151/151/311 144/144/311 +f 151/151/312 142/142/264 143/143/265 +f 149/149/281 137/137/279 139/139/304 +f 138/138/313 122/122/234 124/124/239 +f 128/128/314 121/121/232 119/119/228 +f 128/128/244 119/119/315 130/130/246 +f 130/130/316 119/119/316 118/118/316 +f 153/153/317 154/154/318 155/155/319 +f 155/155/319 154/154/318 156/156/320 +f 157/157/321 158/158/322 156/156/320 +f 156/156/320 158/158/322 155/155/319 +f 159/159/323 160/160/324 161/161/325 +f 161/161/325 162/162/326 159/159/323 +f 157/157/327 163/163/328 164/164/329 +f 165/165/330 166/166/331 167/167/332 +f 168/168/333 169/169/334 170/170/335 +f 170/170/335 171/171/336 168/168/333 +f 172/172/337 170/170/335 169/169/334 +f 173/173/338 174/174/339 175/175/340 +f 175/175/340 174/174/339 171/171/336 +f 175/175/340 171/171/336 170/170/335 +f 172/172/341 169/169/341 176/176/341 +f 176/176/342 169/169/343 177/177/344 +f 176/176/342 177/177/344 178/178/345 +f 178/178/345 177/177/344 179/179/346 +f 178/178/345 179/179/346 180/180/347 +f 180/180/347 179/179/346 181/181/348 +f 180/180/347 181/181/348 182/182/349 +f 180/180/347 182/182/349 183/183/350 +f 183/183/350 182/182/349 184/184/351 +f 183/183/350 184/184/351 185/185/352 +f 185/185/352 184/184/351 160/160/324 +f 185/185/352 160/160/324 159/159/323 +f 162/162/326 161/161/325 186/186/353 +f 186/186/353 161/161/325 187/187/354 +f 165/165/355 187/187/356 161/161/357 +f 165/165/355 161/161/357 188/188/358 +f 188/188/358 161/161/357 189/189/359 +f 177/177/360 169/169/361 190/190/362 +f 174/174/363 163/163/364 171/171/365 +f 168/168/366 190/190/362 169/169/361 +f 190/190/362 168/168/366 171/171/365 +f 190/190/362 171/171/365 163/163/364 +f 189/189/359 184/184/367 188/188/358 +f 188/188/358 184/184/367 182/182/368 +f 190/190/362 191/191/369 177/177/360 +f 188/188/358 182/182/368 192/192/370 +f 161/161/357 160/160/371 189/189/359 +f 189/189/372 160/160/324 184/184/351 +f 182/182/368 181/181/373 192/192/370 +f 181/181/373 179/179/374 192/192/370 +f 192/192/370 179/179/374 191/191/375 +f 191/191/375 179/179/374 177/177/376 +f 173/173/338 175/175/340 193/193/377 +f 175/175/378 170/170/379 193/193/380 +f 170/170/379 172/172/381 193/193/380 +f 176/176/382 178/178/382 172/172/382 +f 172/172/383 178/178/383 194/194/383 +f 178/178/384 180/180/385 194/194/386 +f 194/194/386 180/180/385 195/195/387 +f 195/195/387 180/180/385 183/183/388 +f 185/185/352 159/159/323 196/196/389 +f 159/159/390 162/162/391 196/196/392 +f 191/191/393 156/156/394 154/154/395 +f 191/191/393 154/154/395 192/192/396 +f 190/190/397 157/157/398 191/191/393 +f 191/191/393 157/157/398 156/156/394 +f 157/157/399 190/190/399 163/163/399 +f 195/195/400 153/153/401 194/194/402 +f 194/194/402 153/153/401 155/155/403 +f 158/158/404 197/197/405 155/155/403 +f 155/155/403 197/197/405 194/194/402 +f 197/197/406 158/158/406 164/164/406 +f 198/198/407 186/186/408 187/187/409 +f 165/165/410 198/198/407 187/187/409 +f 163/163/411 173/173/412 164/164/413 +f 173/173/412 163/163/411 174/174/411 +f 167/167/414 166/166/415 153/153/317 +f 153/153/317 166/166/415 154/154/318 +f 165/165/330 167/167/332 198/198/416 +f 166/166/417 188/188/418 154/154/395 +f 154/154/395 188/188/418 192/192/396 +f 188/188/419 166/166/419 165/165/419 +f 199/199/420 167/167/421 195/195/400 +f 195/195/400 167/167/421 153/153/401 +f 167/167/422 199/199/422 198/198/422 +f 200/200/423 201/201/424 202/202/425 +f 200/200/423 202/202/425 203/203/426 +f 203/203/426 204/204/427 205/205/428 +f 200/200/423 206/206/429 201/201/424 +f 202/202/425 204/204/427 203/203/426 +f 204/204/427 202/202/425 207/207/430 +f 200/200/423 203/203/426 208/208/431 +f 200/200/423 208/208/431 209/209/432 +f 209/209/432 208/208/431 210/210/433 +f 209/209/432 210/210/433 211/211/434 +f 212/212/435 213/213/436 214/214/437 +f 215/215/438 216/216/438 217/217/438 +f 216/216/438 215/215/438 218/218/438 +f 213/213/436 212/212/435 219/219/439 +f 220/220/440 221/221/440 222/222/440 +f 220/220/440 222/222/440 223/223/440 +f 223/223/440 222/222/440 224/224/440 +f 223/223/440 224/224/440 225/225/440 +f 226/226/441 221/221/442 227/227/443 +f 221/221/442 226/226/441 222/222/444 +f 220/220/445 227/227/446 221/221/447 +f 220/220/445 228/228/448 227/227/446 +f 223/223/449 207/207/450 220/220/451 +f 220/220/451 207/207/450 228/228/452 +f 207/207/453 223/223/454 225/225/455 +f 207/207/453 225/225/455 204/204/456 +f 204/204/457 225/225/458 224/224/459 +f 204/204/457 224/224/459 205/205/460 +f 222/222/461 226/226/462 224/224/463 +f 224/224/463 226/226/462 205/205/464 +f 229/229/440 230/230/440 231/231/440 +f 229/229/440 231/231/440 232/232/440 +f 232/232/440 231/231/440 233/233/440 +f 232/232/440 233/233/440 234/234/440 +f 231/231/465 235/235/466 207/207/467 +f 235/235/466 231/231/465 230/230/468 +f 230/230/469 236/236/470 235/235/471 +f 229/229/472 236/236/470 230/230/469 +f 236/236/473 229/229/474 237/237/475 +f 237/237/475 229/229/474 232/232/476 +f 232/232/476 206/206/477 237/237/475 +f 206/206/478 232/232/479 234/234/480 +f 206/206/478 234/234/480 201/201/481 +f 201/201/482 234/234/483 202/202/484 +f 202/202/484 234/234/483 233/233/485 +f 233/233/486 207/207/487 202/202/488 +f 231/231/489 207/207/487 233/233/486 +f 238/238/490 236/236/491 237/237/492 +f 235/235/493 227/227/494 228/228/495 +f 227/227/496 235/235/496 239/239/496 +f 239/239/497 235/235/498 236/236/491 +f 235/235/493 228/228/495 207/207/499 +f 226/226/500 227/227/501 239/239/502 +f 236/236/491 238/238/490 239/239/497 +f 240/240/503 200/200/423 241/241/504 +f 241/241/504 200/200/423 209/209/432 +f 241/241/504 209/209/432 242/242/505 +f 242/242/505 209/209/432 243/243/506 +f 243/243/506 209/209/432 211/211/507 +f 206/206/508 200/200/423 240/240/503 +f 206/206/508 240/240/503 244/244/509 +f 205/205/510 226/226/511 245/245/512 +f 203/203/513 205/205/510 246/246/514 +f 246/246/514 205/205/510 245/245/512 +f 247/247/515 210/210/516 208/208/517 +f 247/247/515 208/208/517 248/248/518 +f 248/248/518 208/208/517 203/203/513 +f 248/248/518 203/203/513 246/246/514 +f 245/245/519 226/226/500 239/239/502 +f 244/244/509 237/237/520 206/206/508 +f 237/237/520 244/244/509 238/238/521 +f 215/215/522 245/245/519 239/239/502 +f 217/217/523 249/249/524 250/250/525 +f 249/249/524 251/251/526 250/250/525 +f 251/251/527 252/252/527 246/246/527 +f 252/252/528 253/253/529 246/246/530 +f 253/253/529 254/254/531 246/246/530 +f 246/246/532 254/254/532 248/248/532 +f 254/254/533 255/255/533 248/248/533 +f 248/248/534 255/255/534 256/256/534 +f 255/255/535 257/257/536 256/256/537 +f 257/257/536 258/258/538 256/256/537 +f 256/256/539 258/258/539 259/259/539 +f 260/260/540 214/214/541 213/213/542 +f 217/217/543 250/250/544 215/215/545 +f 215/215/545 250/250/544 245/245/546 +f 256/256/547 259/259/548 261/261/549 +f 261/261/549 260/260/540 213/213/542 +f 250/250/544 251/251/550 245/245/546 +f 260/260/540 261/261/549 259/259/548 +f 245/245/546 251/251/550 246/246/551 +f 256/256/552 247/247/552 248/248/552 +f 247/247/553 256/256/547 261/261/549 +f 218/218/554 238/238/521 244/244/509 +f 262/262/555 263/263/556 216/216/557 +f 212/212/558 264/264/559 265/265/560 +f 264/264/561 266/266/561 265/265/561 +f 266/266/562 267/267/563 243/243/564 +f 267/267/565 268/268/566 243/243/567 +f 243/243/567 268/268/566 242/242/568 +f 242/242/568 268/268/566 241/241/569 +f 241/241/569 268/268/566 269/269/570 +f 241/241/569 269/269/570 240/240/571 +f 269/269/572 270/270/573 240/240/574 +f 270/270/575 271/271/575 240/240/575 +f 240/240/576 271/271/577 272/272/578 +f 272/272/579 263/263/556 262/262/555 +f 212/212/580 214/214/581 260/260/582 +f 212/212/580 260/260/582 264/264/583 +f 264/264/583 260/260/582 259/259/584 +f 264/264/583 259/259/584 266/266/562 +f 266/266/562 259/259/584 258/258/585 +f 266/266/562 258/258/585 267/267/563 +f 267/267/563 258/258/585 257/257/586 +f 267/267/563 257/257/586 268/268/587 +f 268/268/587 257/257/586 255/255/588 +f 268/268/587 255/255/588 254/254/589 +f 268/268/587 254/254/589 269/269/572 +f 269/269/572 254/254/589 270/270/573 +f 270/270/573 254/254/589 253/253/590 +f 270/270/573 253/253/590 271/271/577 +f 271/271/577 253/253/590 252/252/591 +f 271/271/577 252/252/591 272/272/578 +f 272/272/578 252/252/591 251/251/592 +f 272/272/578 251/251/592 263/263/593 +f 263/263/593 251/251/592 249/249/594 +f 263/263/593 249/249/594 216/216/595 +f 216/216/595 249/249/594 217/217/596 +f 239/239/497 238/238/490 215/215/597 +f 215/215/597 238/238/490 218/218/598 +f 210/210/433 273/273/599 211/211/434 +f 211/211/434 274/274/600 275/275/601 +f 210/210/433 276/276/602 273/273/599 +f 211/211/434 273/273/599 274/274/600 +f 274/274/600 273/273/599 277/277/603 +f 278/278/440 279/279/440 280/280/440 +f 279/279/440 281/281/440 282/282/440 +f 279/279/440 282/282/440 280/280/440 +f 283/283/604 277/277/605 278/278/606 +f 284/284/607 282/282/607 276/276/607 +f 276/276/608 282/282/609 281/281/610 +f 276/276/608 281/281/610 273/273/611 +f 273/273/612 281/281/613 277/277/614 +f 277/277/614 281/281/613 279/279/615 +f 278/278/606 277/277/605 279/279/616 +f 278/278/617 285/285/618 283/283/619 +f 280/280/620 285/285/618 278/278/617 +f 280/280/620 286/286/621 285/285/618 +f 286/286/622 280/280/623 284/284/624 +f 282/282/625 284/284/624 280/280/623 +f 287/287/440 288/288/440 289/289/440 +f 289/289/440 288/288/440 290/290/440 +f 288/288/440 291/291/440 290/290/440 +f 289/289/626 292/292/627 275/275/628 +f 292/292/627 289/289/626 290/290/629 +f 293/293/630 292/292/631 290/290/632 +f 291/291/633 293/293/630 290/290/632 +f 291/291/633 294/294/634 293/293/630 +f 294/294/635 291/291/636 277/277/637 +f 288/288/638 277/277/637 291/291/636 +f 287/287/639 274/274/640 288/288/641 +f 288/288/641 274/274/640 277/277/642 +f 287/287/643 275/275/644 274/274/645 +f 289/289/646 275/275/644 287/287/643 +f 293/293/647 285/285/648 295/295/649 +f 295/295/649 285/285/648 286/286/650 +f 293/293/647 294/294/651 285/285/648 +f 285/285/648 294/294/651 283/283/652 +f 277/277/653 283/283/652 294/294/651 +f 292/292/654 293/293/647 296/296/655 +f 293/293/647 295/295/649 296/296/655 +f 275/275/656 292/292/657 297/297/658 +f 211/211/507 275/275/656 243/243/506 +f 243/243/506 275/275/656 297/297/658 +f 276/276/659 210/210/516 247/247/515 +f 276/276/659 247/247/515 284/284/660 +f 284/284/660 247/247/515 261/261/661 +f 284/284/660 261/261/661 286/286/650 +f 286/286/650 261/261/661 295/295/649 +f 297/297/662 292/292/654 296/296/655 +f 261/261/661 213/213/663 295/295/649 +f 296/296/655 219/219/664 297/297/662 +f 296/296/655 295/295/649 219/219/665 +f 219/219/665 295/295/649 213/213/666 +f 298/298/667 299/299/668 300/300/669 +f 300/300/669 299/299/668 301/301/670 +f 300/300/669 301/301/670 302/302/671 +f 302/302/671 301/301/670 303/303/672 +f 304/304/673 305/305/674 302/302/671 +f 304/304/673 302/302/671 303/303/672 +f 306/306/675 307/307/676 308/308/677 +f 308/308/678 307/307/679 305/305/680 +f 308/308/678 305/305/680 304/304/681 +f 306/306/675 309/309/682 307/307/676 +f 309/309/682 306/306/675 310/310/683 +f 309/309/682 310/310/683 311/311/684 +f 311/311/684 310/310/683 312/312/685 +f 311/311/684 312/312/685 313/313/686 +f 313/313/687 312/312/688 314/314/689 +f 314/314/689 312/312/688 315/315/690 +f 314/314/691 315/315/692 316/316/693 +f 316/316/693 315/315/692 317/317/694 +f 318/318/695 319/319/696 317/317/694 +f 317/317/694 319/319/696 316/316/693 +f 319/319/696 318/318/695 320/320/697 +f 320/320/697 318/318/695 321/321/698 +f 320/320/699 321/321/700 322/322/701 +f 322/322/701 321/321/700 323/323/702 +f 322/322/703 323/323/704 324/324/705 +f 322/322/703 324/324/705 325/325/706 +f 325/325/706 324/324/705 326/326/707 +f 325/325/706 326/326/707 327/327/708 +f 327/327/709 326/326/710 328/328/711 +f 327/327/709 328/328/711 329/329/712 +f 329/329/713 328/328/714 299/299/668 +f 329/329/713 299/299/668 298/298/667 +f 330/330/715 331/331/716 332/332/717 +f 330/330/715 333/333/718 331/331/716 +f 330/330/715 334/334/719 333/333/718 +f 330/330/715 332/332/717 335/335/720 +f 336/336/721 337/337/722 338/338/723 +f 336/336/721 338/338/723 339/339/724 +f 338/338/725 340/340/726 339/339/727 +f 339/339/727 340/340/726 341/341/728 +f 341/341/729 340/340/730 342/342/731 +f 341/341/729 342/342/731 343/343/732 +f 343/343/733 342/342/734 344/344/735 +f 344/344/735 342/342/734 345/345/736 +f 345/345/737 346/346/738 344/344/739 +f 344/344/739 346/346/738 347/347/740 +f 347/347/741 346/346/742 348/348/743 +f 347/347/741 348/348/743 349/349/744 +f 349/349/745 348/348/746 336/336/747 +f 348/348/746 337/337/748 336/336/747 +f 342/342/749 334/334/750 330/330/751 +f 334/334/752 342/342/731 340/340/730 +f 334/334/752 340/340/730 333/333/753 +f 340/340/754 338/338/755 333/333/756 +f 333/333/756 338/338/755 331/331/757 +f 331/331/757 338/338/755 337/337/748 +f 331/331/757 337/337/748 332/332/758 +f 337/337/748 348/348/746 332/332/758 +f 332/332/759 348/348/760 346/346/761 +f 332/332/759 346/346/761 335/335/762 +f 335/335/763 346/346/764 330/330/765 +f 346/346/764 345/345/766 330/330/765 +f 330/330/751 345/345/767 342/342/749 +f 336/336/145 350/350/145 351/351/145 +f 336/336/145 351/351/145 349/349/145 +f 341/341/145 352/352/145 339/339/145 +f 339/339/145 353/353/145 336/336/145 +f 344/344/145 354/354/145 343/343/145 +f 349/349/145 355/355/145 347/347/145 +f 349/349/145 351/351/145 355/355/145 +f 353/353/145 350/350/145 336/336/145 +f 339/339/145 352/352/145 353/353/145 +f 347/347/145 356/356/145 344/344/145 +f 343/343/145 357/357/145 341/341/145 +f 343/343/145 354/354/145 358/358/145 +f 341/341/145 357/357/145 352/352/145 +f 343/343/145 358/358/145 357/357/145 +f 344/344/145 356/356/145 354/354/145 +f 347/347/145 355/355/145 356/356/145 +f 359/359/768 360/360/769 361/361/770 +f 362/362/771 363/363/772 364/364/773 +f 362/362/771 365/365/774 363/363/772 +f 364/364/773 363/363/772 366/366/775 +f 366/366/775 367/367/776 359/359/768 +f 359/359/768 367/367/776 360/360/769 +f 368/368/777 369/369/778 370/370/779 +f 366/366/775 363/363/772 367/367/776 +f 361/361/770 360/360/769 371/371/780 +f 372/372/781 373/373/782 374/374/783 +f 375/375/784 369/369/778 368/368/777 +f 368/368/777 376/376/785 377/377/786 +f 374/374/783 378/378/787 375/375/784 +f 375/375/784 378/378/787 369/369/778 +f 377/377/786 376/376/785 362/362/771 +f 362/362/771 376/376/785 365/365/774 +f 361/361/770 371/371/780 372/372/781 +f 373/373/782 379/379/788 374/374/783 +f 374/374/783 379/379/788 378/378/787 +f 372/372/781 371/371/780 373/373/782 +f 368/368/777 370/370/779 376/376/785 +f 352/352/789 374/374/790 375/375/791 +f 352/352/789 375/375/791 353/353/792 +f 353/353/793 375/375/794 368/368/795 +f 353/353/793 368/368/795 350/350/796 +f 350/350/797 368/368/798 351/351/799 +f 351/351/799 368/368/798 377/377/800 +f 351/351/801 377/377/802 362/362/803 +f 351/351/801 362/362/803 355/355/804 +f 355/355/805 362/362/805 364/364/805 +f 355/355/806 364/364/806 356/356/806 +f 356/356/807 364/364/807 366/366/807 +f 356/356/808 366/366/808 354/354/808 +f 354/354/809 366/366/809 359/359/809 +f 354/354/810 359/359/811 358/358/812 +f 358/358/812 359/359/811 361/361/813 +f 358/358/814 361/361/815 357/357/816 +f 357/357/816 361/361/815 372/372/817 +f 357/357/818 372/372/819 374/374/820 +f 357/357/818 374/374/820 352/352/821 +f 380/380/822 381/381/823 382/382/824 +f 383/383/825 380/380/822 382/382/824 +f 381/381/823 380/380/822 384/384/826 +f 385/385/827 386/386/828 383/383/825 +f 385/385/827 387/387/829 386/386/828 +f 388/388/830 389/389/831 387/387/829 +f 388/388/830 387/387/829 385/385/827 +f 390/390/832 391/391/833 388/388/830 +f 390/390/832 392/392/834 391/391/833 +f 393/393/835 392/392/834 390/390/832 +f 393/393/835 394/394/836 392/392/834 +f 383/383/825 386/386/828 380/380/822 +f 388/388/830 391/391/833 389/389/831 +f 381/381/823 384/384/826 393/393/835 +f 393/393/835 384/384/826 394/394/836 +f 384/384/837 395/395/838 394/394/839 +f 391/391/840 396/396/841 389/389/842 +f 386/386/843 397/397/844 380/380/845 +f 380/380/845 398/398/846 384/384/837 +f 392/392/847 399/399/848 391/391/840 +f 391/391/840 399/399/848 400/400/849 +f 387/387/850 401/401/851 386/386/843 +f 380/380/845 397/397/844 402/402/852 +f 384/384/837 403/403/853 395/395/838 +f 392/392/847 394/394/839 404/404/854 +f 391/391/840 400/400/849 396/396/841 +f 396/396/841 405/405/855 389/389/842 +f 389/389/842 406/406/856 387/387/850 +f 387/387/850 406/406/856 401/401/851 +f 402/402/852 398/398/846 380/380/845 +f 398/398/846 403/403/853 384/384/837 +f 389/389/842 405/405/855 406/406/856 +f 386/386/843 407/407/857 397/397/844 +f 404/404/854 399/399/848 392/392/847 +f 395/395/838 408/408/858 394/394/839 +f 394/394/839 408/408/858 404/404/854 +f 401/401/851 407/407/857 386/386/843 +f 398/398/846 370/370/859 403/403/853 +f 404/404/854 373/373/860 399/399/848 +f 407/407/857 365/365/861 397/397/844 +f 403/403/853 370/370/859 369/369/862 +f 400/400/849 399/399/848 371/371/863 +f 406/406/856 363/363/864 401/401/851 +f 401/401/851 363/363/864 407/407/857 +f 397/397/844 376/376/865 402/402/852 +f 403/403/853 378/378/866 395/395/838 +f 400/400/849 371/371/863 360/360/867 +f 400/400/849 360/360/867 396/396/841 +f 396/396/841 367/367/868 405/405/855 +f 402/402/852 376/376/865 398/398/846 +f 398/398/846 376/376/865 370/370/859 +f 395/395/838 378/378/866 408/408/858 +f 408/408/858 379/379/869 404/404/854 +f 373/373/860 371/371/863 399/399/848 +f 405/405/855 367/367/868 406/406/856 +f 406/406/856 367/367/868 363/363/864 +f 397/397/844 365/365/861 376/376/865 +f 378/378/866 379/379/869 408/408/858 +f 379/379/869 373/373/860 404/404/854 +f 396/396/841 360/360/867 367/367/868 +f 363/363/864 365/365/861 407/407/857 +f 369/369/862 378/378/866 403/403/853 +f 409/409/56 410/410/56 411/411/56 +f 411/411/56 410/410/56 412/412/56 +f 411/411/56 412/412/56 413/413/56 +f 413/413/56 412/412/56 414/414/56 +f 383/383/870 409/409/871 411/411/872 +f 411/411/872 385/385/873 383/383/870 +f 409/409/874 382/382/875 410/410/876 +f 409/409/874 383/383/877 382/382/875 +f 410/410/876 382/382/875 381/381/878 +f 410/410/879 381/381/880 412/412/881 +f 381/381/880 393/393/882 412/412/881 +f 412/412/883 393/393/884 414/414/885 +f 414/414/885 393/393/884 390/390/886 +f 414/414/887 388/388/888 413/413/889 +f 414/414/887 390/390/890 388/388/888 +f 413/413/891 388/388/892 411/411/893 +f 411/411/893 388/388/892 385/385/894 +f 415/415/895 416/416/896 417/417/897 +f 415/415/895 417/417/897 418/418/898 +f 418/418/899 417/417/900 419/419/901 +f 418/418/899 419/419/901 420/420/902 +f 420/420/903 419/419/904 421/421/905 +f 420/420/903 421/421/905 422/422/906 +f 422/422/907 421/421/908 423/423/909 +f 423/423/909 421/421/908 424/424/910 +f 423/423/911 424/424/911 425/425/911 +f 425/425/912 424/424/912 426/426/912 +f 425/425/913 426/426/913 427/427/913 +f 427/427/914 426/426/914 428/428/914 +f 427/427/915 428/428/915 429/429/915 +f 429/429/916 428/428/916 430/430/916 +f 429/429/917 430/430/917 431/431/917 +f 431/431/918 430/430/918 416/416/918 +f 431/431/919 416/416/919 415/415/919 +f 432/432/145 428/428/145 426/426/145 +f 432/432/145 426/426/145 433/433/145 +f 434/434/145 430/430/145 432/432/145 +f 432/432/145 430/430/145 428/428/145 +f 433/433/145 426/426/145 424/424/145 +f 435/435/145 421/421/145 436/436/145 +f 433/433/145 424/424/145 435/435/145 +f 437/437/145 417/417/145 416/416/145 +f 435/435/145 424/424/145 421/421/145 +f 434/434/145 416/416/145 430/430/145 +f 436/436/145 419/419/145 437/437/145 +f 437/437/145 419/419/145 417/417/145 +f 437/437/145 416/416/145 434/434/145 +f 436/436/145 421/421/145 419/419/145 +f 437/437/920 438/438/921 439/439/922 +f 437/437/920 439/439/922 436/436/923 +f 436/436/923 439/439/922 440/440/924 +f 436/436/923 440/440/924 435/435/925 +f 435/435/925 440/440/924 441/441/926 +f 435/435/927 441/441/928 433/433/929 +f 433/433/929 441/441/928 442/442/930 +f 433/433/931 442/442/932 443/443/933 +f 433/433/931 443/443/933 432/432/934 +f 432/432/935 443/443/936 444/444/937 +f 432/432/935 444/444/937 434/434/938 +f 434/434/939 444/444/939 445/445/939 +f 434/434/940 445/445/941 437/437/942 +f 437/437/942 445/445/941 438/438/943 +f 157/157/327 164/164/329 158/158/944 +f 444/444/945 446/446/946 445/445/947 +f 445/445/947 446/446/946 447/447/948 +f 444/444/945 448/448/949 446/446/946 +f 445/445/947 447/447/948 449/449/950 +f 445/445/947 449/449/950 438/438/951 +f 442/442/952 450/450/953 443/443/954 +f 443/443/954 450/450/953 451/451/955 +f 443/443/954 451/451/955 444/444/945 +f 444/444/945 451/451/955 448/448/949 +f 438/438/951 449/449/950 439/439/956 +f 439/439/956 449/449/950 452/452/957 +f 441/441/958 453/453/959 454/454/960 +f 441/441/958 454/454/960 442/442/952 +f 442/442/952 454/454/960 450/450/953 +f 440/440/961 455/455/962 453/453/959 +f 440/440/961 453/453/959 441/441/958 +f 439/439/956 452/452/957 455/455/962 +f 439/439/956 455/455/962 440/440/961 +f 447/447/963 456/456/964 449/449/965 +f 456/456/964 447/447/963 457/457/966 +f 457/457/966 447/447/963 446/446/967 +f 457/457/966 446/446/967 458/458/968 +f 458/458/969 446/446/970 448/448/971 +f 458/458/969 448/448/971 459/459/972 +f 459/459/972 448/448/971 460/460/973 +f 460/460/973 448/448/971 451/451/974 +f 460/460/973 451/451/974 461/461/975 +f 450/450/976 461/461/975 451/451/974 +f 450/450/976 462/462/977 461/461/975 +f 463/463/978 462/462/977 450/450/976 +f 462/462/977 463/463/978 464/464/979 +f 454/454/980 464/464/979 463/463/978 +f 464/464/979 454/454/980 465/465/981 +f 453/453/982 465/465/981 454/454/980 +f 453/453/982 466/466/983 465/465/981 +f 467/467/984 466/466/983 453/453/982 +f 466/466/983 467/467/984 468/468/985 +f 455/455/986 468/468/985 467/467/984 +f 468/468/985 455/455/986 469/469/987 +f 469/469/987 455/455/986 452/452/988 +f 452/452/988 470/470/989 469/469/987 +f 470/470/989 452/452/988 471/471/990 +f 471/471/990 472/472/991 470/470/989 +f 449/449/965 473/473/992 471/471/990 +f 471/471/990 473/473/992 472/472/991 +f 456/456/964 473/473/992 449/449/965 +f 415/415/993 474/474/994 431/431/995 +f 431/431/995 474/474/994 475/475/996 +f 431/431/995 475/475/996 429/429/997 +f 429/429/997 475/475/996 476/476/998 +f 429/429/997 476/476/998 427/427/999 +f 427/427/999 476/476/998 477/477/1000 +f 427/427/999 477/477/1000 461/461/1001 +f 427/427/999 461/461/1001 425/425/1002 +f 425/425/1002 461/461/1001 478/478/1003 +f 415/415/993 473/473/1004 474/474/994 +f 420/420/1005 468/468/1006 479/479/1007 +f 418/418/1008 473/473/1004 415/415/993 +f 425/425/1002 478/478/1003 423/423/1009 +f 423/423/1009 478/478/1003 480/480/1010 +f 423/423/1009 480/480/1010 481/481/1011 +f 423/423/1009 481/481/1011 422/422/1012 +f 420/420/1005 479/479/1007 418/418/1008 +f 422/422/1012 481/481/1011 468/468/1006 +f 422/422/1012 468/468/1006 420/420/1005 +f 418/418/1008 479/479/1007 473/473/1004 +f 464/464/1013 480/480/1014 478/478/1015 +f 468/468/1016 481/481/1017 466/466/1018 +f 476/476/1019 475/475/1020 458/458/1021 +f 462/462/977 478/478/1022 461/461/975 +f 460/460/1023 476/476/1019 459/459/1024 +f 458/458/1021 475/475/1020 457/457/1025 +f 475/475/1026 474/474/1026 457/457/1026 +f 457/457/1027 474/474/1028 456/456/1029 +f 481/481/1030 480/480/1014 465/465/1031 +f 465/465/1031 480/480/1014 464/464/1013 +f 461/461/1001 477/477/1000 460/460/1032 +f 476/476/1033 460/460/1033 477/477/1033 +f 458/458/1021 459/459/1024 476/476/1019 +f 456/456/1029 474/474/1028 473/473/1034 +f 473/473/992 479/479/1035 472/472/991 +f 472/472/991 479/479/1036 470/470/989 +f 469/469/1037 470/470/1037 479/479/1037 +f 479/479/1038 468/468/985 469/469/987 +f 465/465/1039 466/466/1018 481/481/1017 +f 464/464/1040 478/478/1040 462/462/1040 +f 467/467/1041 453/453/1041 455/455/1041 +f 471/471/1042 452/452/1042 449/449/1042 +f 463/463/1043 450/450/1043 454/454/1043 +f 482/482/1044 483/483/1045 484/484/1046 +f 482/482/1044 484/484/1046 485/485/1047 +f 485/485/1047 484/484/1046 486/486/1048 +f 486/486/1048 484/484/1046 487/487/1049 +f 488/488/1050 489/489/1051 486/486/1048 +f 488/488/1050 486/486/1048 487/487/1049 +f 490/490/1052 491/491/1053 492/492/1054 +f 492/492/1054 491/491/1053 489/489/1051 +f 492/492/1054 489/489/1051 488/488/1050 +f 490/490/1052 493/493/1055 491/491/1053 +f 493/493/1055 490/490/1052 494/494/1056 +f 493/493/1057 494/494/1058 495/495/1059 +f 495/495/1059 494/494/1058 496/496/1060 +f 495/495/1061 496/496/1062 497/497/1063 +f 497/497/1063 496/496/1062 498/498/1064 +f 497/497/1063 498/498/1064 499/499/1065 +f 499/499/1065 498/498/1064 500/500/1066 +f 500/500/1066 498/498/1064 501/501/1067 +f 502/502/1068 503/503/1069 501/501/1067 +f 501/501/1067 503/503/1069 500/500/1066 +f 503/503/1069 502/502/1068 504/504/1070 +f 504/504/1070 502/502/1068 505/505/1071 +f 504/504/1070 505/505/1071 506/506/1072 +f 504/504/1070 506/506/1072 507/507/1073 +f 507/507/1074 506/506/1075 508/508/1076 +f 508/508/1076 506/506/1075 509/509/1077 +f 508/508/1078 509/509/1079 510/510/1080 +f 508/508/1078 510/510/1080 511/511/1081 +f 511/511/1082 510/510/1083 512/512/1084 +f 511/511/1082 512/512/1084 513/513/1085 +f 513/513/1085 512/512/1084 514/514/1086 +f 513/513/1085 514/514/1086 482/482/1044 +f 482/482/1044 514/514/1086 483/483/1045 +f 326/326/56 324/324/56 328/328/56 +f 324/324/56 323/323/56 328/328/56 +f 328/328/56 323/323/56 299/299/56 +f 323/323/56 321/321/56 299/299/56 +f 304/304/56 317/317/56 315/315/56 +f 321/321/56 301/301/56 299/299/56 +f 321/321/56 318/318/56 301/301/56 +f 318/318/56 303/303/56 301/301/56 +f 318/318/56 317/317/56 303/303/56 +f 317/317/56 304/304/56 303/303/56 +f 312/312/56 310/310/56 306/306/56 +f 315/315/56 308/308/56 304/304/56 +f 315/315/56 312/312/56 308/308/56 +f 312/312/56 306/306/56 308/308/56 +f 510/510/145 509/509/145 512/512/145 +f 512/512/145 509/509/145 506/506/145 +f 514/514/145 512/512/145 506/506/145 +f 514/514/145 506/506/145 505/505/145 +f 514/514/145 505/505/145 483/483/145 +f 483/483/145 505/505/145 502/502/145 +f 483/483/145 502/502/145 484/484/145 +f 484/484/145 502/502/145 501/501/145 +f 484/484/145 501/501/145 487/487/145 +f 487/487/145 501/501/145 488/488/145 +f 488/488/145 501/501/145 498/498/145 +f 488/488/145 498/498/145 492/492/145 +f 490/490/145 492/492/145 496/496/145 +f 490/490/145 496/496/145 494/494/145 +f 498/498/145 496/496/145 492/492/145 +f 515/515/1087 516/516/1088 517/517/1089 +f 518/518/1090 516/516/1088 519/519/1091 +f 519/519/1091 516/516/1088 515/515/1087 +f 520/520/1092 521/521/1093 522/522/1094 +f 523/523/1095 524/524/1096 525/525/1097 +f 517/517/1089 526/526/1098 515/515/1087 +f 522/522/1094 527/527/1099 520/520/1092 +f 515/515/1087 526/526/1098 523/523/1095 +f 515/515/1087 523/523/1095 525/525/1097 +f 522/522/1094 521/521/1093 519/519/1091 +f 519/519/1091 521/521/1093 518/518/1090 +f 525/525/1097 524/524/1096 522/522/1094 +f 522/522/1094 524/524/1096 527/527/1099 +f 528/528/1100 529/529/1101 530/530/1102 +f 528/528/1100 531/531/1103 529/529/1101 +f 532/532/1104 533/533/1105 534/534/1106 +f 534/534/1107 533/533/1107 535/535/1107 +f 534/534/1108 535/535/1109 531/531/1110 +f 535/535/1109 536/536/1111 531/531/1110 +f 531/531/1112 536/536/1113 529/529/1114 +f 529/529/1114 536/536/1113 537/537/1115 +f 529/529/1116 537/537/1117 538/538/1118 +f 538/538/1118 537/537/1117 539/539/1119 +f 538/538/1120 539/539/1121 532/532/1122 +f 532/532/1122 539/539/1121 540/540/1123 +f 532/532/1104 540/540/1124 533/533/1105 +f 537/537/1125 541/541/1126 542/542/1127 +f 540/540/1128 543/543/1129 533/533/1130 +f 533/533/1130 543/543/1129 544/544/1131 +f 536/536/1132 545/545/1133 537/537/1125 +f 537/537/1125 545/545/1133 541/541/1126 +f 535/535/1134 546/546/1135 545/545/1133 +f 535/535/1134 545/545/1133 536/536/1132 +f 533/533/1130 544/544/1131 546/546/1135 +f 533/533/1130 546/546/1135 535/535/1134 +f 537/537/1125 542/542/1127 539/539/1136 +f 539/539/1136 547/547/1137 548/548/1138 +f 539/539/1136 548/548/1138 540/540/1128 +f 540/540/1128 548/548/1138 543/543/1129 +f 539/539/1136 542/542/1127 547/547/1137 +f 516/516/1139 544/544/1140 543/543/1141 +f 516/516/1139 518/518/1142 544/544/1140 +f 544/544/1143 518/518/1144 521/521/1145 +f 544/544/1143 521/521/1145 546/546/1146 +f 521/521/1147 520/520/1148 546/546/1149 +f 546/546/1149 520/520/1148 545/545/1150 +f 520/520/1151 527/527/1152 545/545/1153 +f 545/545/1153 527/527/1152 541/541/1154 +f 527/527/1152 524/524/1155 541/541/1154 +f 541/541/1154 524/524/1155 542/542/1156 +f 524/524/1157 523/523/1158 542/542/1159 +f 542/542/1159 523/523/1158 547/547/1160 +f 547/547/1161 523/523/1162 526/526/1163 +f 547/547/1161 526/526/1163 548/548/1164 +f 526/526/1163 517/517/1165 548/548/1164 +f 548/548/1164 517/517/1165 543/543/1166 +f 543/543/1166 517/517/1165 516/516/1167 +f 525/525/1168 522/522/1169 549/549/1170 +f 549/549/1170 522/522/1169 550/550/1171 +f 515/515/1172 525/525/1173 551/551/1174 +f 551/551/1174 525/525/1173 549/549/1175 +f 519/519/1176 515/515/1177 552/552/1178 +f 552/552/1178 515/515/1177 551/551/1179 +f 522/522/1180 519/519/1181 550/550/1182 +f 550/550/1182 519/519/1181 552/552/1183 +f 550/550/440 552/552/440 551/551/440 +f 550/550/440 551/551/440 549/549/440 +f 532/532/1184 528/528/1184 530/530/1184 +f 532/532/1122 530/530/1185 538/538/1120 +f 538/538/1186 530/530/1102 529/529/1101 +f 534/534/1187 531/531/1187 528/528/1187 +f 534/534/1106 528/528/1188 532/532/1104 +f 553/553/1189 554/554/1190 555/555/1191 +f 555/555/1191 556/556/1192 553/553/1189 +f 557/557/1193 558/558/1194 559/559/1195 +f 560/560/1196 561/561/1197 562/562/1198 +f 555/555/1191 554/554/1190 561/561/1197 +f 561/561/1197 554/554/1190 563/563/1199 +f 559/559/1195 564/564/1200 557/557/1193 +f 563/563/1199 562/562/1198 561/561/1197 +f 559/559/1195 558/558/1194 555/555/1191 +f 558/558/1194 556/556/1192 555/555/1191 +f 560/560/1196 564/564/1200 561/561/1197 +f 561/561/1197 564/564/1200 559/559/1195 +f 565/565/1201 566/566/1202 567/567/1203 +f 568/568/1204 569/569/1205 570/570/1206 +f 569/569/1207 571/571/1208 570/570/1209 +f 570/570/1209 571/571/1208 572/572/1210 +f 571/571/1208 573/573/1211 572/572/1210 +f 573/573/1212 574/574/1213 572/572/1214 +f 572/572/1214 574/574/1213 575/575/1215 +f 575/575/1216 574/574/1217 576/576/1218 +f 575/575/1216 576/576/1218 577/577/1219 +f 577/577/1220 576/576/1221 578/578/1222 +f 576/576/1221 568/568/1223 578/578/1222 +f 578/578/1224 568/568/1204 570/570/1206 +f 569/569/1225 579/579/1226 580/580/1227 +f 568/568/1228 579/579/1226 569/569/1225 +f 573/573/1229 581/581/1230 582/582/1231 +f 573/573/1229 582/582/1231 574/574/1232 +f 571/571/1233 581/581/1230 573/573/1229 +f 571/571/1233 580/580/1227 581/581/1230 +f 569/569/1225 580/580/1227 571/571/1233 +f 568/568/1228 583/583/1234 579/579/1226 +f 574/574/1232 582/582/1231 576/576/1235 +f 576/576/1235 582/582/1231 584/584/1236 +f 576/576/1235 584/584/1236 568/568/1228 +f 568/568/1228 584/584/1236 583/583/1234 +f 553/553/1237 556/556/1238 579/579/1239 +f 579/579/1239 556/556/1238 580/580/1240 +f 580/580/1240 556/556/1238 558/558/1241 +f 580/580/1242 558/558/1243 581/581/1244 +f 558/558/1243 557/557/1245 581/581/1244 +f 557/557/1246 564/564/1247 581/581/1248 +f 581/581/1248 564/564/1247 582/582/1249 +f 582/582/1250 564/564/1250 560/560/1250 +f 582/582/1251 560/560/1252 584/584/1253 +f 560/560/1252 562/562/1254 584/584/1253 +f 562/562/1255 563/563/1256 584/584/1257 +f 584/584/1257 563/563/1256 583/583/1258 +f 563/563/1256 554/554/1259 583/583/1258 +f 583/583/1260 554/554/1261 579/579/1262 +f 579/579/1262 554/554/1261 553/553/1263 +f 561/561/1264 559/559/1265 585/585/1266 +f 585/585/1266 559/559/1265 586/586/1267 +f 555/555/1268 561/561/1269 587/587/1270 +f 587/587/1270 561/561/1269 585/585/1271 +f 559/559/1272 555/555/1273 586/586/1274 +f 586/586/1274 555/555/1273 587/587/1275 +f 586/586/440 587/587/440 585/585/440 +f 570/570/1206 565/565/1276 578/578/1224 +f 578/578/1277 565/565/1278 567/567/1279 +f 578/578/1277 567/567/1279 577/577/1280 +f 577/577/1219 567/567/1281 575/575/1216 +f 575/575/1282 567/567/1283 566/566/1284 +f 575/575/1282 566/566/1284 572/572/1285 +f 572/572/1210 566/566/1286 570/570/1209 +f 570/570/1287 566/566/1202 565/565/1201 +f 588/588/1288 589/589/1289 590/590/1290 +f 590/590/1290 589/589/1289 591/591/1291 +f 592/592/1292 593/593/1293 594/594/1294 +f 590/590/1290 591/591/1291 595/595/1295 +f 590/590/1290 595/595/1295 596/596/1296 +f 592/592/1292 594/594/1294 597/597/1297 +f 592/592/1292 597/597/1297 588/588/1298 +f 596/596/1299 593/593/1293 592/592/1292 +f 598/598/1300 599/599/1301 600/600/1302 +f 601/601/1303 602/602/1304 603/603/1305 +f 602/602/1306 604/604/1306 603/603/1306 +f 603/603/1307 604/604/1308 605/605/1309 +f 603/603/1307 605/605/1309 606/606/1310 +f 606/606/1311 605/605/1312 607/607/1313 +f 606/606/1311 607/607/1313 608/608/1314 +f 608/608/1315 607/607/1315 609/609/1315 +f 608/608/1316 609/609/1317 610/610/1318 +f 610/610/1318 609/609/1317 611/611/1319 +f 610/610/1320 611/611/1321 601/601/1322 +f 601/601/1322 611/611/1321 612/612/1323 +f 601/601/1303 612/612/1324 602/602/1304 +f 602/602/1325 613/613/1326 614/614/1327 +f 612/612/1328 613/613/1326 602/602/1325 +f 615/615/1329 616/616/1330 605/605/1331 +f 605/605/1331 616/616/1330 607/607/1332 +f 604/604/1333 615/615/1329 605/605/1331 +f 604/604/1333 617/617/1334 615/615/1329 +f 602/602/1325 614/614/1327 604/604/1333 +f 604/604/1333 614/614/1327 617/617/1334 +f 612/612/1328 618/618/1335 613/613/1326 +f 607/607/1332 616/616/1330 609/609/1336 +f 609/609/1336 616/616/1330 619/619/1337 +f 609/609/1336 620/620/1338 611/611/1339 +f 611/611/1339 620/620/1338 618/618/1335 +f 611/611/1339 618/618/1335 612/612/1328 +f 609/609/1336 619/619/1337 620/620/1338 +f 613/613/1340 588/588/1341 614/614/1342 +f 588/588/1341 597/597/1343 614/614/1342 +f 614/614/1344 597/597/1345 617/617/1346 +f 617/617/1346 597/597/1345 594/594/1347 +f 617/617/1346 594/594/1347 615/615/1348 +f 615/615/1349 594/594/1350 616/616/1351 +f 594/594/1350 593/593/1352 616/616/1351 +f 616/616/1353 593/593/1354 596/596/1355 +f 616/616/1353 596/596/1355 619/619/1356 +f 596/596/1355 595/595/1357 619/619/1356 +f 619/619/1358 595/595/1359 591/591/1360 +f 619/619/1358 591/591/1360 620/620/1361 +f 620/620/1362 591/591/1363 618/618/1364 +f 618/618/1364 591/591/1363 589/589/1365 +f 618/618/1364 589/589/1365 613/613/1340 +f 589/589/1365 588/588/1341 613/613/1340 +f 596/596/1366 592/592/1366 621/621/1366 +f 621/621/1179 592/592/1179 622/622/1179 +f 590/590/1367 596/596/1368 623/623/1369 +f 623/623/1369 596/596/1368 621/621/1370 +f 588/588/1371 590/590/1371 624/624/1371 +f 624/624/1171 590/590/1171 623/623/1171 +f 592/592/1372 588/588/1373 622/622/1374 +f 622/622/1374 588/588/1373 624/624/1375 +f 622/622/440 624/624/440 623/623/440 +f 622/622/440 623/623/440 621/621/440 +f 601/601/1322 600/600/1376 610/610/1320 +f 610/610/1377 600/600/1302 599/599/1301 +f 610/610/1377 599/599/1301 608/608/1378 +f 608/608/1379 599/599/1379 606/606/1379 +f 606/606/1380 599/599/1301 598/598/1300 +f 606/606/1310 598/598/1381 603/603/1307 +f 603/603/1382 598/598/1383 600/600/1384 +f 603/603/1382 600/600/1384 601/601/1385 +f 625/625/1386 626/626/1387 627/627/1388 +f 628/628/1389 625/625/1386 627/627/1388 +f 628/628/1389 629/629/1390 625/625/1386 +f 630/630/1391 631/631/1392 632/632/1393 +f 627/627/1388 626/626/1387 633/633/1394 +f 627/627/1388 633/633/1394 632/632/1393 +f 634/634/1395 635/635/1396 628/628/1389 +f 635/635/1396 636/636/1397 628/628/1389 +f 633/633/1394 630/630/1391 632/632/1393 +f 628/628/1389 636/636/1397 629/629/1390 +f 632/632/1393 631/631/1392 634/634/1395 +f 634/634/1395 631/631/1392 635/635/1396 +f 637/637/1398 638/638/1399 639/639/1400 +f 640/640/1401 638/638/1399 637/637/1398 +f 639/639/1402 641/641/1403 642/642/1404 +f 642/642/1405 641/641/1405 643/643/1405 +f 642/642/1406 643/643/1407 637/637/1408 +f 637/637/1408 643/643/1407 644/644/1409 +f 637/637/1408 644/644/1409 645/645/1410 +f 645/645/1411 644/644/1411 646/646/1411 +f 645/645/1412 646/646/1413 647/647/1414 +f 647/647/1415 646/646/1415 648/648/1415 +f 647/647/1416 648/648/1416 649/649/1416 +f 649/649/1417 648/648/1417 650/650/1417 +f 649/649/1418 650/650/1419 639/639/1402 +f 639/639/1402 650/650/1419 641/641/1403 +f 644/644/1420 651/651/1421 652/652/1422 +f 641/641/1423 653/653/1424 654/654/1425 +f 644/644/1420 652/652/1422 646/646/1426 +f 643/643/1427 655/655/1428 644/644/1420 +f 644/644/1420 655/655/1428 651/651/1421 +f 643/643/1427 654/654/1425 655/655/1428 +f 641/641/1423 654/654/1425 643/643/1427 +f 646/646/1426 652/652/1422 656/656/1429 +f 648/648/1430 657/657/1431 658/658/1432 +f 648/648/1430 658/658/1432 650/650/1433 +f 650/650/1433 658/658/1432 641/641/1423 +f 641/641/1423 658/658/1432 653/653/1424 +f 646/646/1426 656/656/1429 648/648/1430 +f 648/648/1430 656/656/1429 657/657/1431 +f 625/625/1434 654/654/1435 653/653/1436 +f 625/625/1434 629/629/1437 654/654/1435 +f 654/654/1438 629/629/1439 655/655/1440 +f 655/655/1440 629/629/1439 636/636/1441 +f 655/655/1442 636/636/1443 651/651/1444 +f 651/651/1444 636/636/1443 635/635/1445 +f 651/651/1444 635/635/1445 652/652/1446 +f 652/652/1447 635/635/1448 631/631/1449 +f 652/652/1447 631/631/1449 656/656/1450 +f 656/656/1451 631/631/1452 630/630/1453 +f 656/656/1451 630/630/1453 657/657/1454 +f 657/657/1454 630/630/1453 633/633/1455 +f 657/657/1454 633/633/1455 658/658/1456 +f 658/658/1456 633/633/1455 626/626/1457 +f 658/658/1456 626/626/1457 653/653/1436 +f 653/653/1436 626/626/1457 625/625/1434 +f 632/632/1458 634/634/1459 659/659/1460 +f 659/659/1460 634/634/1459 660/660/1461 +f 627/627/1462 632/632/1463 661/661/1464 +f 661/661/1464 632/632/1463 659/659/1465 +f 628/628/1466 627/627/1467 662/662/1468 +f 662/662/1468 627/627/1467 661/661/1469 +f 634/634/1470 628/628/1471 660/660/1472 +f 660/660/1472 628/628/1471 662/662/1473 +f 660/660/440 662/662/440 661/661/440 +f 660/660/440 661/661/440 659/659/440 +f 639/639/1474 638/638/1474 649/649/1474 +f 649/649/1475 638/638/1476 640/640/1477 +f 649/649/1475 640/640/1477 647/647/1478 +f 647/647/1414 640/640/1479 645/645/1412 +f 645/645/1480 640/640/1480 637/637/1480 +f 642/642/1481 637/637/1398 639/639/1400 +f 663/663/56 664/664/56 665/665/56 +f 663/663/56 665/665/56 666/666/56 +f 666/666/56 665/665/56 667/667/56 +f 668/668/56 664/664/56 663/663/56 +f 669/669/56 668/668/56 663/663/56 +f 669/669/56 670/670/56 668/668/56 +f 671/671/56 667/667/56 672/672/56 +f 673/673/56 674/674/56 675/675/56 +f 676/676/56 674/674/56 673/673/56 +f 666/666/56 667/667/56 671/671/56 +f 677/677/56 670/670/56 669/669/56 +f 673/673/56 675/675/56 678/678/56 +f 673/673/56 678/678/56 677/677/56 +f 671/671/56 672/672/56 676/676/56 +f 677/677/56 678/678/56 670/670/56 +f 676/676/56 672/672/56 674/674/56 +f 679/679/1482 666/666/1482 671/671/1482 +f 679/679/1483 671/671/1483 680/680/1483 +f 680/680/1484 671/671/1484 676/676/1484 +f 680/680/1485 676/676/1485 681/681/1485 +f 681/681/1486 676/676/1486 673/673/1486 +f 681/681/1487 673/673/1487 682/682/1487 +f 682/682/1488 673/673/1488 677/677/1488 +f 682/682/1489 677/677/1490 683/683/1491 +f 683/683/1491 677/677/1490 669/669/1492 +f 683/683/1493 669/669/1494 663/663/1495 +f 683/683/1493 663/663/1495 684/684/1496 +f 684/684/1497 663/663/1497 685/685/1497 +f 685/685/1498 663/663/1498 666/666/1498 +f 685/685/1499 666/666/1499 679/679/1499 +f 684/684/145 686/686/145 683/683/145 +f 682/682/145 687/687/145 681/681/145 +f 682/682/145 688/688/145 687/687/145 +f 683/683/145 686/686/145 689/689/145 +f 681/681/145 687/687/145 690/690/145 +f 689/689/145 691/691/145 683/683/145 +f 683/683/145 691/691/145 682/682/145 +f 685/685/145 692/692/145 684/684/145 +f 684/684/145 692/692/145 686/686/145 +f 685/685/145 693/693/145 692/692/145 +f 682/682/145 691/691/145 688/688/145 +f 679/679/145 693/693/145 685/685/145 +f 681/681/145 690/690/145 680/680/145 +f 680/680/145 694/694/145 679/679/145 +f 680/680/145 690/690/145 694/694/145 +f 679/679/145 695/695/145 693/693/145 +f 679/679/145 694/694/145 695/695/145 +f 667/667/1500 695/695/1500 694/694/1500 +f 667/667/1501 694/694/1501 672/672/1501 +f 672/672/1502 694/694/1502 690/690/1502 +f 672/672/1503 690/690/1503 674/674/1503 +f 674/674/1504 690/690/1504 687/687/1504 +f 674/674/1505 687/687/1505 675/675/1505 +f 675/675/1506 687/687/1506 688/688/1506 +f 675/675/1507 688/688/1507 678/678/1507 +f 678/678/1508 688/688/1508 691/691/1508 +f 678/678/1509 691/691/1509 670/670/1509 +f 670/670/1510 691/691/1510 689/689/1510 +f 670/670/1511 689/689/1511 668/668/1511 +f 668/668/1512 689/689/1512 686/686/1512 +f 668/668/1513 686/686/1513 664/664/1513 +f 664/664/1514 686/686/1514 692/692/1514 +f 664/664/1515 692/692/1515 665/665/1515 +f 665/665/1516 692/692/1516 693/693/1516 +f 665/665/1517 693/693/1517 667/667/1517 +f 667/667/1518 693/693/1518 695/695/1518 +f 696/696/145 697/697/145 698/698/145 +f 696/696/145 698/698/145 699/699/145 +f 699/699/145 698/698/145 700/700/145 +f 701/701/145 702/702/145 697/697/145 +f 701/701/145 697/697/145 696/696/145 +f 703/703/145 704/704/1519 702/702/145 +f 705/705/1520 706/706/1521 707/707/1522 +f 705/705/1520 708/708/1523 706/706/1521 +f 703/703/145 702/702/145 701/701/145 +f 709/709/145 710/710/145 711/711/145 +f 705/705/1520 712/712/145 708/708/1523 +f 705/705/1520 711/711/145 712/712/145 +f 709/709/145 711/711/145 705/705/1520 +f 700/700/145 710/710/145 699/699/145 +f 699/699/145 710/710/145 709/709/145 +f 707/707/1522 704/704/1519 703/703/145 +f 707/707/1522 706/706/1521 704/704/1519 +f 713/713/1524 699/699/1525 709/709/1526 +f 713/713/1524 709/709/1526 714/714/1527 +f 714/714/1528 709/709/1528 715/715/1528 +f 715/715/1529 709/709/1529 705/705/1529 +f 715/715/1530 705/705/1530 716/716/1530 +f 716/716/1531 705/705/1531 707/707/1531 +f 716/716/1532 707/707/1532 717/717/1532 +f 717/717/1533 707/707/1533 703/703/1533 +f 717/717/1534 703/703/1534 718/718/1534 +f 718/718/1535 703/703/1535 701/701/1535 +f 718/718/1536 701/701/1536 719/719/1536 +f 719/719/1537 701/701/1537 696/696/1537 +f 719/719/1538 696/696/1538 713/713/1538 +f 713/713/1539 696/696/1539 699/699/1539 +f 717/717/56 720/720/1540 716/716/1541 +f 716/716/1541 720/720/1540 706/706/1542 +f 718/718/56 721/721/56 722/722/56 +f 719/719/56 721/721/56 718/718/56 +f 716/716/1541 723/723/1543 715/715/56 +f 718/718/56 722/722/56 717/717/56 +f 719/719/56 724/724/56 721/721/56 +f 719/719/56 725/725/56 724/724/56 +f 716/716/1541 706/706/1542 723/723/1543 +f 713/713/56 725/725/56 719/719/56 +f 717/717/56 722/722/56 720/720/1540 +f 713/713/56 726/726/56 725/725/56 +f 715/715/56 727/727/56 714/714/56 +f 714/714/56 727/727/56 728/728/56 +f 715/715/56 723/723/1543 727/727/56 +f 714/714/56 728/728/56 713/713/56 +f 713/713/56 728/728/56 726/726/56 +f 700/700/1544 726/726/1544 710/710/1544 +f 710/710/1545 726/726/1545 728/728/1545 +f 710/710/1546 728/728/1546 711/711/1546 +f 711/711/1547 728/728/1547 727/727/1547 +f 711/711/1548 727/727/1548 712/712/1548 +f 712/712/1549 727/727/1549 723/723/1549 +f 712/712/1550 723/723/1550 708/708/1550 +f 708/708/1551 723/723/1551 706/706/1551 +f 706/706/1552 720/720/1552 704/704/1552 +f 704/704/1553 720/720/1553 722/722/1553 +f 704/704/1554 722/722/1554 702/702/1554 +f 702/702/1555 722/722/1555 721/721/1555 +f 702/702/1556 721/721/1556 697/697/1556 +f 697/697/1557 721/721/1557 724/724/1557 +f 697/697/1558 724/724/1559 725/725/1560 +f 697/697/1558 725/725/1560 698/698/1561 +f 698/698/1562 725/725/1563 700/700/1564 +f 700/700/1564 725/725/1563 726/726/1565 +f 729/729/1566 730/730/1567 731/731/1568 +f 732/732/1569 733/733/1570 734/734/1571 +f 732/732/1569 731/731/1568 733/733/1570 +f 731/731/1568 730/730/1567 733/733/1570 +f 729/729/1566 735/735/1572 730/730/1567 +f 729/729/1566 736/736/1573 735/735/1572 +f 737/737/1574 736/736/1575 738/738/1576 +f 738/738/1576 736/736/1575 739/739/1577 +f 740/740/1578 741/741/1579 742/742/1580 +f 743/743/1581 742/742/1580 741/741/1579 +f 741/741/1579 744/744/1582 743/743/1581 +f 744/744/1582 745/745/1583 743/743/1581 +f 746/746/1584 745/745/1583 744/744/1582 +f 746/746/1584 747/747/1585 745/745/1583 +f 748/748/1586 749/749/1587 746/746/1584 +f 746/746/1584 749/749/1587 747/747/1585 +f 748/748/1586 750/750/1588 749/749/1587 +f 748/748/1586 751/751/1589 750/750/1588 +f 752/752/1590 751/751/1589 748/748/1586 +f 752/752/1590 753/753/1591 751/751/1589 +f 753/753/1591 752/752/1590 754/754/1592 +f 754/754/1592 755/755/1593 753/753/1591 +f 754/754/1592 756/756/1594 755/755/1593 +f 756/756/1594 754/754/1592 757/757/1595 +f 758/758/1596 734/734/1571 759/759/1597 +f 732/732/1569 734/734/1571 758/758/1596 +f 760/760/1598 761/761/1599 758/758/1596 +f 758/758/1596 761/761/1599 732/732/1569 +f 762/762/1600 763/763/1601 760/760/1602 +f 740/740/1578 763/763/1601 741/741/1579 +f 763/763/1601 762/762/1600 741/741/1579 +f 746/746/1603 744/744/1604 764/764/1605 +f 764/764/1605 744/744/1604 765/765/1606 +f 765/765/1606 744/744/1604 741/741/1607 +f 765/765/1606 741/741/1607 766/766/1608 +f 766/766/1608 741/741/1607 762/762/1600 +f 766/766/1608 762/762/1600 767/767/1609 +f 767/767/1609 762/762/1600 760/760/1602 +f 767/767/1609 760/760/1602 758/758/1610 +f 767/767/1609 758/758/1610 768/768/1611 +f 768/768/1611 758/758/1610 759/759/1612 +f 768/768/1611 759/759/1612 769/769/1613 +f 769/769/1613 759/759/1612 770/770/1614 +f 759/759/1612 771/771/1615 770/770/1614 +f 770/770/1614 771/771/1615 772/772/1616 +f 770/770/1614 772/772/1616 773/773/1617 +f 773/773/1617 772/772/1616 774/774/1618 +f 773/773/1617 774/774/1618 775/775/1619 +f 773/773/1617 775/775/1619 776/776/1620 +f 776/776/1620 775/775/1619 777/777/1621 +f 777/777/1621 775/775/1619 778/778/1622 +f 777/777/1621 778/778/1622 779/779/1623 +f 779/779/1623 778/778/1622 780/780/1624 +f 779/779/1623 780/780/1624 781/781/1625 +f 781/781/1625 780/780/1624 782/782/1626 +f 781/781/1625 782/782/1626 783/783/1627 +f 783/783/1627 782/782/1626 784/784/1628 +f 783/783/1627 784/784/1628 785/785/1629 +f 785/785/1629 784/784/1628 786/786/1630 +f 785/785/1629 786/786/1630 787/787/1631 +f 785/785/1629 787/787/1631 788/788/1632 +f 757/757/1633 788/788/1632 787/787/1631 +f 788/788/1632 757/757/1633 789/789/1634 +f 789/789/1634 757/757/1633 754/754/1635 +f 754/754/1635 790/790/1636 789/789/1634 +f 790/790/1636 754/754/1635 752/752/1637 +f 790/790/1636 752/752/1637 748/748/1638 +f 790/790/1636 748/748/1638 791/791/1639 +f 791/791/1639 748/748/1638 746/746/1603 +f 746/746/1603 764/764/1605 791/791/1639 +f 792/792/1640 793/793/1641 794/794/1642 +f 795/795/1643 796/796/1644 797/797/1645 +f 795/795/1643 798/798/1646 794/794/1642 +f 797/797/1645 798/798/1646 795/795/1643 +f 798/798/1646 799/799/1647 794/794/1642 +f 756/756/1648 794/794/1642 799/799/1647 +f 794/794/1642 756/756/1648 757/757/1633 +f 787/787/1631 792/792/1640 794/794/1642 +f 757/757/1633 787/787/1631 794/794/1642 +f 800/800/1649 801/801/1650 735/735/1572 +f 802/802/1651 803/803/1652 804/804/1653 +f 801/801/1650 730/730/1567 735/735/1572 +f 801/801/1650 733/733/1654 730/730/1567 +f 802/802/1651 805/805/1655 801/801/1650 +f 806/806/1656 802/802/1651 804/804/1653 +f 733/733/1654 801/801/1650 734/734/1657 +f 734/734/1657 801/801/1650 759/759/1658 +f 759/759/1658 801/801/1650 807/807/1659 +f 801/801/1650 805/805/1655 807/807/1659 +f 807/807/1660 771/771/1615 759/759/1612 +f 772/772/1661 771/771/1615 805/805/1662 +f 786/786/1630 792/792/1663 787/787/1631 +f 792/792/1663 786/786/1630 808/808/1664 +f 808/808/1664 786/786/1630 784/784/1665 +f 771/771/1615 807/807/1660 805/805/1662 +f 809/809/1666 800/800/1649 810/810/1667 +f 810/810/1667 800/800/1649 811/811/1668 +f 810/810/1667 811/811/1668 812/812/1669 +f 812/812/1669 811/811/1668 813/813/1670 +f 812/812/1669 813/813/1670 814/814/1671 +f 814/814/1671 813/813/1670 815/815/1672 +f 814/814/1671 815/815/1672 816/816/1673 +f 816/816/1673 815/815/1672 817/817/1674 +f 817/817/1674 815/815/1672 818/818/1675 +f 817/817/1674 818/818/1675 819/819/1676 +f 817/817/1674 819/819/1676 820/820/1677 +f 820/820/1677 819/819/1676 797/797/1645 +f 820/820/1677 797/797/1645 796/796/1644 +f 821/821/1678 822/822/1679 823/823/1680 +f 823/823/1680 822/822/1679 824/824/1681 +f 825/825/1682 826/826/1683 827/827/1684 +f 827/827/1684 826/826/1683 828/828/1685 +f 800/800/1649 809/809/1666 801/801/1650 +f 796/796/145 809/809/145 817/817/145 +f 801/801/145 809/809/145 825/825/145 +f 796/796/145 817/817/145 820/820/145 +f 825/825/145 809/809/145 826/826/145 +f 816/816/145 810/810/145 814/814/145 +f 826/826/145 809/809/145 824/824/145 +f 809/809/145 796/796/145 824/824/145 +f 816/816/145 809/809/145 810/810/145 +f 809/809/145 816/816/145 817/817/145 +f 796/796/145 823/823/145 824/824/145 +f 810/810/145 812/812/145 814/814/145 +f 796/796/145 795/795/145 823/823/145 +f 824/824/1681 822/822/1679 826/826/1683 +f 826/826/1683 822/822/1679 828/828/1685 +f 777/777/1621 829/829/1686 830/830/1687 +f 777/777/1621 830/830/1687 776/776/1620 +f 776/776/1620 830/830/1687 773/773/1617 +f 773/773/1617 830/830/1687 831/831/1688 +f 773/773/1617 831/831/1688 770/770/1614 +f 770/770/1614 831/831/1688 832/832/1689 +f 770/770/1614 832/832/1689 769/769/1613 +f 769/769/1613 832/832/1689 833/833/1690 +f 769/769/1613 833/833/1690 768/768/1611 +f 768/768/1611 833/833/1690 834/834/1691 +f 768/768/1611 834/834/1691 767/767/1609 +f 767/767/1609 834/834/1691 835/835/1692 +f 767/767/1609 835/835/1692 766/766/1608 +f 766/766/1608 835/835/1692 765/765/1606 +f 765/765/1606 835/835/1692 836/836/1693 +f 765/765/1606 836/836/1693 764/764/1605 +f 764/764/1605 836/836/1693 837/837/1694 +f 764/764/1605 837/837/1694 791/791/1639 +f 791/791/1639 837/837/1694 838/838/1695 +f 791/791/1639 838/838/1695 790/790/1636 +f 790/790/1636 838/838/1695 839/839/1696 +f 790/790/1636 839/839/1696 789/789/1634 +f 789/789/1634 839/839/1696 788/788/1632 +f 788/788/1632 839/839/1696 840/840/1697 +f 788/788/1632 840/840/1697 785/785/1629 +f 785/785/1629 840/840/1697 841/841/1698 +f 785/785/1629 841/841/1698 783/783/1627 +f 783/783/1627 841/841/1698 842/842/1699 +f 783/783/1627 842/842/1699 781/781/1625 +f 781/781/1625 842/842/1699 779/779/1623 +f 779/779/1623 842/842/1699 843/843/1700 +f 779/779/1623 843/843/1700 829/829/1686 +f 779/779/1623 829/829/1686 777/777/1621 +f 797/797/1645 844/844/1701 845/845/1702 +f 797/797/1645 845/845/1702 798/798/1646 +f 844/844/1701 797/797/1645 846/846/1703 +f 846/846/1703 797/797/1645 819/819/1676 +f 818/818/1675 847/847/1704 819/819/1676 +f 819/819/1676 847/847/1704 846/846/1703 +f 815/815/1672 848/848/1705 818/818/1675 +f 848/848/1705 847/847/1704 818/818/1675 +f 849/849/1706 848/848/1705 815/815/1672 +f 813/813/1670 850/850/1707 815/815/1672 +f 850/850/1707 849/849/1706 815/815/1672 +f 850/850/1707 813/813/1670 851/851/1708 +f 851/851/1708 813/813/1670 811/811/1668 +f 851/851/1708 811/811/1668 852/852/1709 +f 852/852/1709 811/811/1668 853/853/1710 +f 853/853/1710 811/811/1668 800/800/1649 +f 853/853/1710 800/800/1649 737/737/1574 +f 736/736/1573 737/737/1574 800/800/1649 +f 735/735/1572 736/736/1573 800/800/1649 +f 825/825/1711 827/827/1712 801/801/1713 +f 801/801/1713 827/827/1712 802/802/1714 +f 821/821/1715 823/823/1716 795/795/1717 +f 821/821/1715 795/795/1717 794/794/1718 +f 854/854/1719 799/799/1647 798/798/1646 +f 799/799/1647 854/854/1719 855/855/1720 +f 855/855/1720 755/755/1593 756/756/1594 +f 799/799/1647 855/855/1720 756/756/1594 +f 856/856/1721 854/854/1719 798/798/1646 +f 845/845/1702 856/856/1721 798/798/1646 +f 742/742/1580 743/743/1581 745/745/1583 +f 844/844/1701 857/857/1722 845/845/1723 +f 857/857/1722 858/858/1724 845/845/1723 +f 858/858/1725 857/857/1722 859/859/1726 +f 844/844/1701 846/846/1703 860/860/1727 +f 861/861/1728 849/849/1706 850/850/1707 +f 851/851/1708 852/852/1709 862/862/1729 +f 863/863/1730 853/853/1710 737/737/1574 +f 863/863/1730 737/737/1574 738/738/1576 +f 857/857/1722 844/844/1701 860/860/1727 +f 860/860/1727 846/846/1703 864/864/1731 +f 864/864/1731 846/846/1703 847/847/1704 +f 864/864/1731 847/847/1704 848/848/1732 +f 848/848/1732 849/849/1706 861/861/1728 +f 861/861/1728 850/850/1707 865/865/1733 +f 865/865/1733 850/850/1707 851/851/1708 +f 865/865/1733 851/851/1708 862/862/1729 +f 852/852/1709 853/853/1710 863/863/1730 +f 857/857/1722 860/860/1727 866/866/1734 +f 866/866/1734 860/860/1727 864/864/1731 +f 867/867/1735 848/848/1732 861/861/1728 +f 862/862/1729 852/852/1709 863/863/1730 +f 867/867/1735 864/864/1731 848/848/1732 +f 861/861/1728 865/865/1733 862/862/1729 +f 866/866/1734 864/864/1731 867/867/1735 +f 868/868/1736 869/869/1737 751/751/1738 +f 751/751/1738 869/869/1737 870/870/1739 +f 751/751/1738 870/870/1739 750/750/1740 +f 871/871/1741 872/872/1742 870/870/1739 +f 870/870/1739 872/872/1742 750/750/1740 +f 870/870/1743 869/869/1744 873/873/1745 +f 870/870/1743 873/873/1745 874/874/1746 +f 874/874/1746 873/873/1745 875/875/1747 +f 874/874/1746 875/875/1747 876/876/1748 +f 876/876/1749 875/875/1750 877/877/1751 +f 876/876/1749 877/877/1751 878/878/1752 +f 755/755/1753 855/855/1754 879/879/1755 +f 880/880/1756 755/755/1753 879/879/1755 +f 880/880/1756 753/753/1757 755/755/1753 +f 753/753/1757 880/880/1756 881/881/1758 +f 753/753/1759 881/881/1760 751/751/1761 +f 868/868/1762 751/751/1761 881/881/1760 +f 879/879/1755 855/855/1754 877/877/1763 +f 856/856/1764 882/882/1765 878/878/1766 +f 878/878/1766 854/854/1767 856/856/1764 +f 877/877/1763 854/854/1767 878/878/1766 +f 856/856/1764 845/845/1768 882/882/1765 +f 855/855/1754 854/854/1767 877/877/1763 +f 882/882/56 876/876/56 878/878/56 +f 883/883/56 871/871/56 874/874/56 +f 871/871/56 870/870/56 874/874/56 +f 884/884/56 883/883/56 874/874/56 +f 882/882/56 884/884/56 874/874/56 +f 876/876/56 882/882/56 874/874/56 +f 845/845/1769 858/858/1770 884/884/1771 +f 884/884/1772 858/858/1773 859/859/1774 +f 882/882/1775 845/845/1769 884/884/1771 +f 884/884/1772 859/859/1774 883/883/1776 +f 883/883/1777 859/859/1778 871/871/1779 +f 871/871/1779 859/859/1778 872/872/1780 +f 885/885/1781 886/886/1782 887/887/1783 +f 887/887/1783 886/886/1782 888/888/1784 +f 887/887/1785 888/888/1786 889/889/1787 +f 889/889/1787 888/888/1786 890/890/1788 +f 889/889/1789 890/890/1790 891/891/1791 +f 889/889/1789 891/891/1791 892/892/1792 +f 892/892/1793 891/891/1794 893/893/1795 +f 893/893/1795 740/740/1796 892/892/1793 +f 892/892/1793 740/740/1796 742/742/1797 +f 894/894/1798 895/895/1799 742/742/1797 +f 742/742/1797 895/895/1799 892/892/1793 +f 881/881/56 879/879/56 868/868/56 +f 886/886/56 896/896/56 893/893/56 +f 873/873/56 869/869/56 877/877/56 +f 877/877/56 875/875/56 873/873/56 +f 880/880/56 879/879/56 881/881/56 +f 879/879/56 877/877/56 868/868/56 +f 869/869/56 868/868/56 877/877/56 +f 896/896/56 897/897/56 893/893/56 +f 888/888/56 886/886/56 890/890/56 +f 896/896/56 898/898/56 897/897/56 +f 890/890/56 886/886/56 891/891/56 +f 893/893/56 891/891/56 886/886/56 +f 731/731/1800 896/896/1801 886/886/1782 +f 729/729/1802 885/885/1781 899/899/1803 +f 729/729/1802 731/731/1800 885/885/1781 +f 885/885/1781 731/731/1800 886/886/1782 +f 899/899/1803 736/736/1804 729/729/1802 +f 893/893/1795 763/763/1805 740/740/1796 +f 897/897/1806 763/763/1805 893/893/1795 +f 897/897/1806 760/760/1807 763/763/1805 +f 761/761/1808 760/760/1807 898/898/1809 +f 898/898/1809 760/760/1807 897/897/1806 +f 898/898/1809 896/896/1810 732/732/1811 +f 732/732/1811 761/761/1808 898/898/1809 +f 731/731/1800 732/732/1812 896/896/1801 +f 736/736/1813 899/899/1814 900/900/1815 +f 900/900/1815 739/739/1816 736/736/1813 +f 901/901/1817 902/902/1818 900/900/1819 +f 900/900/1819 902/902/1818 739/739/1820 +f 895/895/1821 894/894/1822 902/902/1823 +f 895/895/1821 902/902/1823 901/901/1824 +f 895/895/56 889/889/56 892/892/56 +f 899/899/56 885/885/56 887/887/56 +f 901/901/56 889/889/56 895/895/56 +f 901/901/56 900/900/56 889/889/56 +f 889/889/56 900/900/56 899/899/56 +f 899/899/56 887/887/56 889/889/56 +f 902/902/1825 738/738/1826 739/739/1827 +f 738/738/1826 902/902/1825 894/894/1828 +f 863/863/1730 738/738/1826 894/894/1828 +f 872/872/1829 867/867/1735 861/861/1728 +f 894/894/1828 742/742/1580 745/745/1583 +f 862/862/1729 894/894/1828 861/861/1728 +f 872/872/1829 866/866/1734 867/867/1735 +f 872/872/1829 894/894/1828 745/745/1583 +f 747/747/1830 872/872/1829 745/745/1583 +f 749/749/1831 872/872/1829 747/747/1830 +f 861/861/1728 894/894/1828 872/872/1829 +f 750/750/1832 872/872/1829 749/749/1831 +f 863/863/1730 894/894/1828 862/862/1729 +f 857/857/1722 866/866/1734 872/872/1829 +f 859/859/1726 857/857/1722 872/872/1829 +f 903/903/1833 904/904/1834 905/905/1835 +f 903/903/1833 905/905/1835 906/906/1836 +f 907/907/1837 908/908/1838 909/909/1839 +f 908/908/1838 907/907/1837 910/910/1840 +f 911/911/1841 912/912/1842 913/913/1843 +f 911/911/1841 913/913/1843 914/914/1844 +f 914/914/1844 913/913/1843 915/915/1845 +f 916/916/1846 917/917/1847 912/912/1842 +f 916/916/1846 912/912/1842 911/911/1841 +f 908/908/1838 910/910/1840 918/918/1848 +f 918/918/1848 910/910/1840 904/904/1834 +f 907/907/1837 909/909/1839 919/919/1849 +f 920/920/1850 921/921/1851 775/775/1852 +f 920/920/1850 775/775/1852 922/922/1853 +f 923/923/1854 922/922/1853 775/775/1852 +f 775/775/1852 774/774/1855 923/923/1854 +f 924/924/1856 925/925/1857 793/793/1858 +f 925/925/1857 924/924/1856 926/926/1859 +f 925/925/1857 926/926/1859 927/927/1860 +f 805/805/1655 802/802/1651 928/928/1861 +f 928/928/1861 802/802/1651 806/806/1656 +f 804/804/1653 803/803/1652 929/929/1862 +f 929/929/1862 803/803/1652 930/930/1863 +f 929/929/1862 930/930/1863 931/931/1864 +f 931/931/1864 930/930/1863 932/932/1865 +f 931/931/1864 932/932/1865 933/933/1866 +f 933/933/1866 932/932/1865 934/934/1867 +f 933/933/1866 934/934/1867 935/935/1868 +f 935/935/1868 934/934/1867 936/936/1869 +f 935/935/1868 936/936/1869 937/937/1870 +f 937/937/1870 936/936/1869 938/938/1871 +f 937/937/1870 938/938/1871 939/939/1872 +f 939/939/1872 938/938/1871 940/940/1873 +f 939/939/1872 940/940/1873 941/941/1874 +f 941/941/1874 940/940/1873 925/925/1857 +f 941/941/1874 925/925/1857 927/927/1860 +f 782/782/1875 808/808/1664 784/784/1665 +f 942/942/1876 943/943/1877 782/782/1875 +f 944/944/1878 942/942/1876 780/780/1879 +f 780/780/1879 942/942/1876 782/782/1875 +f 944/944/1878 780/780/1879 945/945/1880 +f 946/946/1881 947/947/1882 927/927/1860 +f 946/946/1881 927/927/1860 948/948/1883 +f 949/949/1884 948/948/1883 927/927/1860 +f 926/926/1859 949/949/1884 927/927/1860 +f 950/950/1885 951/951/1886 804/804/1653 +f 950/950/1885 804/804/1653 929/929/1862 +f 952/952/1887 950/950/1885 929/929/1862 +f 952/952/1887 929/929/1862 953/953/1888 +f 953/953/1888 929/929/1862 931/931/1864 +f 931/931/1864 954/954/1889 953/953/1888 +f 954/954/1889 931/931/1864 933/933/1866 +f 955/955/1890 954/954/1889 933/933/1866 +f 955/955/1890 933/933/1866 935/935/1868 +f 956/956/1891 955/955/1890 935/935/1868 +f 935/935/1868 957/957/1892 956/956/1891 +f 957/957/1892 935/935/1868 937/937/1870 +f 937/937/1870 958/958/1893 957/957/1892 +f 958/958/1893 937/937/1870 939/939/1872 +f 939/939/1872 959/959/1894 958/958/1893 +f 959/959/1894 939/939/1872 941/941/1874 +f 941/941/1874 960/960/1895 959/959/1894 +f 960/960/1895 941/941/1874 961/961/1896 +f 961/961/1896 941/941/1874 927/927/1860 +f 927/927/1860 947/947/1882 961/961/1896 +f 804/804/1653 951/951/1886 962/962/1897 +f 804/804/1653 962/962/1897 963/963/1898 +f 804/804/1653 963/963/1898 806/806/1656 +f 928/928/1861 806/806/1656 964/964/1899 +f 965/965/1900 928/928/1861 964/964/1899 +f 966/966/1901 967/967/1902 964/964/1899 +f 909/909/1903 967/967/1902 968/968/1904 +f 963/963/1898 966/966/1901 806/806/1656 +f 772/772/1661 805/805/1662 969/969/1905 +f 969/969/1905 805/805/1662 928/928/1861 +f 774/774/1855 772/772/1661 969/969/1905 +f 970/970/1906 774/774/1855 969/969/1905 +f 965/965/1900 969/969/1905 928/928/1861 +f 970/970/1906 969/969/1905 965/965/1900 +f 923/923/1854 774/774/1855 970/970/1906 +f 964/964/1899 806/806/1656 966/966/1901 +f 966/966/1901 968/968/1904 967/967/1902 +f 971/971/1907 972/972/1908 973/973/1909 +f 792/792/1663 808/808/1664 793/793/1910 +f 793/793/1910 808/808/1664 974/974/1911 +f 793/793/1910 974/974/1911 924/924/1856 +f 808/808/1664 975/975/1912 974/974/1911 +f 924/924/1856 974/974/1911 971/971/1907 +f 943/943/1877 975/975/1912 782/782/1875 +f 782/782/1875 975/975/1912 808/808/1664 +f 924/924/1856 971/971/1907 926/926/1859 +f 971/971/1907 973/973/1909 926/926/1859 +f 926/926/1859 973/973/1909 949/949/1884 +f 967/967/1913 909/909/1914 976/976/1915 +f 976/976/1915 909/909/1914 977/977/1916 +f 978/978/1917 964/964/1918 976/976/1919 +f 976/976/1919 964/964/1918 967/967/1920 +f 978/978/1921 979/979/1922 964/964/1923 +f 979/979/1922 965/965/1924 964/964/1923 +f 980/980/1925 965/965/1924 979/979/1922 +f 970/970/1926 965/965/1924 980/980/1925 +f 970/970/1927 980/980/1928 981/981/1929 +f 981/981/1929 923/923/1930 970/970/1927 +f 982/982/1931 923/923/1932 981/981/1933 +f 922/922/1934 923/923/1932 982/982/1931 +f 983/983/1935 920/920/1936 922/922/1934 +f 983/983/1935 922/922/1934 982/982/1931 +f 983/983/1937 984/984/1938 920/920/1939 +f 985/985/1940 984/984/1938 983/983/1937 +f 977/977/1941 909/909/1942 908/908/1943 +f 977/977/1941 908/908/1943 985/985/1944 +f 985/985/1940 908/908/1945 984/984/1938 +f 986/986/1946 942/942/1947 944/944/1948 +f 986/986/1946 943/943/1949 942/942/1947 +f 987/987/1950 943/943/1949 986/986/1946 +f 987/987/1950 975/975/1951 943/943/1949 +f 988/988/1952 975/975/1951 987/987/1950 +f 988/988/1953 989/989/1954 974/974/1955 +f 988/988/1953 974/974/1955 975/975/1956 +f 974/974/1957 990/990/1958 971/971/1959 +f 990/990/1958 974/974/1957 989/989/1960 +f 972/972/1961 971/971/1962 990/990/1963 +f 991/991/1964 972/972/1961 990/990/1963 +f 992/992/1965 917/917/1966 972/972/1967 +f 992/992/1965 972/972/1967 991/991/1968 +f 993/993/1969 994/994/1970 992/992/1971 +f 994/994/1972 993/993/1973 944/944/1948 +f 986/986/1946 944/944/1948 993/993/1973 +f 992/992/1971 994/994/1970 912/912/1974 +f 992/992/1965 912/912/1975 917/917/1966 +f 906/906/1976 995/995/1977 962/962/1978 +f 996/996/1979 962/962/1978 995/995/1977 +f 963/963/1980 962/962/1978 996/996/1979 +f 997/997/1981 963/963/1980 996/996/1979 +f 966/966/1982 963/963/1980 997/997/1981 +f 998/998/1983 966/966/1982 997/997/1981 +f 999/999/1984 968/968/1985 998/998/1983 +f 998/998/1983 968/968/1985 966/966/1982 +f 919/919/1986 968/968/1985 999/999/1984 +f 995/995/1977 906/906/1976 905/905/1987 +f 995/995/1977 905/905/1987 1000/1000/1988 +f 1000/1000/1988 905/905/1987 904/904/1989 +f 1000/1000/1990 904/904/1991 1001/1001/1992 +f 1001/1001/1992 904/904/1991 910/910/1993 +f 1001/1001/1994 910/910/1995 1002/1002/1996 +f 1002/1002/1996 910/910/1995 907/907/1997 +f 1002/1002/1998 907/907/1999 999/999/1984 +f 999/999/1984 907/907/1999 919/919/1986 +f 1003/1003/2000 916/916/2001 1004/1004/2002 +f 1003/1003/2000 973/973/2003 916/916/2001 +f 1005/1005/2004 973/973/2003 1003/1003/2000 +f 1005/1005/2004 949/949/2005 973/973/2003 +f 1006/1006/2006 949/949/2005 1005/1005/2004 +f 948/948/2007 949/949/2005 1006/1006/2006 +f 1007/1007/2008 948/948/2007 1006/1006/2006 +f 1007/1007/2008 946/946/2009 948/948/2007 +f 1008/1008/2010 1009/1009/2011 946/946/2009 +f 1008/1008/2010 946/946/2009 1007/1007/2008 +f 1008/1008/2010 1010/1010/2012 1009/1009/2011 +f 1004/1004/2002 916/916/2001 911/911/2013 +f 1004/1004/2002 911/911/2013 1011/1011/2014 +f 1011/1011/2015 911/911/2016 1012/1012/2017 +f 1012/1012/2017 911/911/2016 914/914/2018 +f 1012/1012/2019 914/914/2020 1013/1013/2021 +f 1013/1013/2021 914/914/2020 1014/1014/2022 +f 1013/1013/2023 1014/1014/2024 1010/1010/2012 +f 1013/1013/2023 1010/1010/2012 1008/1008/2010 +f 951/951/1886 1015/1015/2025 962/962/2026 +f 962/962/2026 1015/1015/2025 906/906/1836 +f 906/906/1836 1015/1015/2025 903/903/1833 +f 1016/1016/2027 1017/1017/2028 958/958/1893 +f 956/956/2029 1018/1018/2030 1019/1019/2031 +f 956/956/2029 1019/1019/2031 955/955/1890 +f 1019/1019/2031 1020/1020/2032 954/954/1889 +f 1019/1019/2031 1021/1021/2033 1020/1020/2032 +f 1020/1020/2032 953/953/1888 954/954/1889 +f 961/961/1896 947/947/1882 1022/1022/2034 +f 1022/1022/2034 947/947/1882 1023/1023/2035 +f 961/961/1896 1022/1022/2034 960/960/1895 +f 1024/1024/2036 960/960/1895 1022/1022/2034 +f 1022/1022/2034 1016/1016/2027 1024/1024/2036 +f 959/959/1894 960/960/1895 1024/1024/2036 +f 958/958/1893 959/959/1894 1024/1024/2036 +f 958/958/1893 1024/1024/2036 1016/1016/2027 +f 957/957/1892 958/958/1893 1017/1017/2028 +f 956/956/2029 957/957/1892 1017/1017/2028 +f 1017/1017/2028 1018/1018/2030 956/956/2029 +f 1019/1019/2031 954/954/1889 955/955/1890 +f 952/952/1887 953/953/1888 1021/1021/2033 +f 1021/1021/2033 953/953/1888 1020/1020/2032 +f 1021/1021/2033 903/903/1833 1015/1015/2025 +f 1021/1021/2033 1015/1015/2025 952/952/1887 +f 952/952/1887 1015/1015/2025 950/950/1885 +f 950/950/1885 1015/1015/2025 951/951/1886 +f 947/947/1882 946/946/2037 1023/1023/2035 +f 1023/1023/2035 946/946/2037 1009/1009/2038 +f 1023/1023/2039 1009/1009/2040 1010/1010/2041 +f 909/909/1903 968/968/1904 919/919/2042 +f 917/917/2043 916/916/2044 972/972/1908 +f 916/916/2044 973/973/1909 972/972/1908 +f 1025/1025/2045 775/775/2046 1026/1026/2047 +f 1026/1026/2047 775/775/2046 921/921/2048 +f 1026/1026/2047 921/921/2048 1027/1027/2049 +f 780/780/2050 1028/1028/2051 945/945/2052 +f 945/945/2052 1028/1028/2051 1029/1029/2053 +f 945/945/2052 1029/1029/2053 1030/1030/2054 +f 1031/1031/2055 1026/1026/2047 1027/1027/2049 +f 1031/1031/2055 1032/1032/2056 1026/1026/2047 +f 1032/1032/2056 1031/1031/2055 1033/1033/2057 +f 1032/1032/2056 1033/1033/2057 1034/1034/2058 +f 1034/1034/2058 1035/1035/2059 1032/1032/2056 +f 1036/1036/2060 1035/1035/2059 1034/1034/2058 +f 1036/1036/2060 1037/1037/2061 1035/1035/2059 +f 1038/1038/2062 1037/1037/2061 1036/1036/2060 +f 1037/1037/2061 1038/1038/2062 1039/1039/2063 +f 1039/1039/2063 1038/1038/2062 1040/1040/2064 +f 1039/1039/2063 1040/1040/2064 1029/1029/2053 +f 1041/1041/2065 1029/1029/2053 1040/1040/2064 +f 1030/1030/2054 1029/1029/2053 1041/1041/2065 +f 1042/1042/2066 994/994/2067 944/944/2068 +f 1042/1042/2066 944/944/2068 945/945/2052 +f 1042/1042/2066 945/945/2052 1030/1030/2054 +f 1036/1036/2060 1043/1043/2069 1038/1038/2062 +f 1040/1040/2064 1044/1044/2070 1041/1041/2065 +f 1027/1027/2071 1045/1045/2072 1046/1046/2073 +f 1027/1027/2071 1046/1046/2073 1031/1031/2074 +f 1033/1033/2075 1047/1047/2076 1034/1034/2077 +f 1034/1034/2077 1047/1047/2076 1048/1048/2078 +f 1034/1034/2077 1048/1048/2078 1036/1036/2060 +f 1036/1036/2060 1048/1048/2078 1043/1043/2069 +f 1043/1043/2069 1049/1049/2079 1038/1038/2062 +f 1038/1038/2062 1049/1049/2079 1040/1040/2064 +f 1040/1040/2064 1049/1049/2079 1044/1044/2070 +f 1041/1041/2065 1042/1042/2066 1030/1030/2054 +f 1042/1042/2066 1041/1041/2065 913/913/1843 +f 913/913/1843 1041/1041/2065 1044/1044/2070 +f 1047/1047/2076 1033/1033/2075 1050/1050/2080 +f 1050/1050/2080 1033/1033/2075 1031/1031/2074 +f 1046/1046/2073 1050/1050/2080 1031/1031/2074 +f 1043/1043/2069 1051/1051/2081 1049/1049/2079 +f 1049/1049/2079 915/915/2082 1044/1044/2070 +f 912/912/1842 1042/1042/2066 913/913/1843 +f 913/913/1843 1044/1044/2070 915/915/2082 +f 1051/1051/2081 1043/1043/2069 1048/1048/2083 +f 994/994/2067 1042/1042/2066 912/912/1842 +f 915/915/2082 1049/1049/2079 1051/1051/2081 +f 1051/1051/2081 1048/1048/2083 1052/1052/2084 +f 1052/1052/2084 1048/1048/2083 1047/1047/2076 +f 1052/1052/2084 1047/1047/2076 1050/1050/2080 +f 1050/1050/2080 1046/1046/2085 918/918/1848 +f 918/918/1848 1046/1046/2085 908/908/2086 +f 908/908/2086 1046/1046/2085 1045/1045/2072 +f 908/908/2086 1045/1045/2072 984/984/2087 +f 1052/1052/2084 1050/1050/2080 918/918/1848 +f 920/920/2088 984/984/2087 1045/1045/2072 +f 920/920/2088 1045/1045/2072 921/921/2089 +f 921/921/2089 1045/1045/2072 1027/1027/2071 +f 903/903/1833 1021/1021/2033 1019/1019/2031 +f 903/903/1833 1019/1019/2031 1018/1018/2030 +f 904/904/1834 903/903/1833 1052/1052/2084 +f 1052/1052/2084 903/903/1833 1051/1051/2090 +f 1016/1016/2027 1022/1022/2034 903/903/1833 +f 1018/1018/2030 1017/1017/2028 903/903/1833 +f 1017/1017/2028 1016/1016/2027 903/903/1833 +f 1022/1022/2034 1023/1023/2039 903/903/1833 +f 1023/1023/2039 1051/1051/2090 903/903/1833 +f 914/914/1844 915/915/1845 1014/1014/2091 +f 915/915/1845 1051/1051/2090 1014/1014/2091 +f 1052/1052/2084 918/918/1848 904/904/1834 +f 1051/1051/2090 1023/1023/2039 1014/1014/2091 +f 1010/1010/2041 1014/1014/2091 1023/1023/2039 +f 1035/1035/145 1037/1037/145 1029/1029/145 +f 1026/1026/145 1032/1032/145 1029/1029/145 +f 1037/1037/145 1039/1039/145 1029/1029/145 +f 1025/1025/145 1026/1026/145 1029/1029/145 +f 1029/1029/145 1028/1028/145 1025/1025/145 +f 1029/1029/145 1032/1032/145 1035/1035/145 +f 1053/1053/2092 1054/1054/2093 1055/1055/2094 +f 1056/1056/2095 1057/1057/2096 1058/1058/2097 +f 1059/1059/2098 1060/1060/2099 1061/1061/2100 +f 1059/1059/2098 1061/1061/2100 1062/1062/2101 +f 1063/1063/2102 1059/1059/2098 1064/1064/2103 +f 1058/1058/2097 1057/1057/2096 1065/1065/2104 +f 1062/1062/2101 1066/1066/2105 1054/1054/2093 +f 1065/1065/2104 1063/1063/2102 1064/1064/2103 +f 1058/1058/2097 1065/1065/2104 1064/1064/2103 +f 1067/1067/2106 1068/1068/2107 1056/1056/2095 +f 1062/1062/2101 1054/1054/2093 1053/1053/2092 +f 1061/1061/2100 1066/1066/2105 1062/1062/2101 +f 1059/1059/2098 1063/1063/2102 1060/1060/2099 +f 1067/1067/2106 1056/1056/2095 1058/1058/2097 +f 1055/1055/2094 1068/1068/2107 1053/1053/2092 +f 1053/1053/2092 1068/1068/2107 1067/1067/2106 +f 1069/1069/2108 1070/1070/2109 1071/1071/2110 +f 1072/1072/2111 1070/1070/2109 1069/1069/2108 +f 1069/1069/2108 1073/1073/2112 1072/1072/2111 +f 1074/1074/2113 1075/1075/2114 1076/1076/2115 +f 1076/1076/2115 1075/1075/2114 1077/1077/2116 +f 1076/1076/2117 1077/1077/2118 1078/1078/2119 +f 1076/1076/2117 1078/1078/2119 1073/1073/2120 +f 1073/1073/2120 1078/1078/2119 1079/1079/2121 +f 1078/1078/2119 1080/1080/2122 1079/1079/2121 +f 1079/1079/2123 1080/1080/2124 1081/1081/2125 +f 1079/1079/2123 1081/1081/2125 1082/1082/2126 +f 1082/1082/2127 1081/1081/2128 1083/1083/2129 +f 1082/1082/2127 1083/1083/2129 1070/1070/2130 +f 1070/1070/2130 1083/1083/2129 1084/1084/2131 +f 1070/1070/2130 1084/1084/2131 1085/1085/2132 +f 1085/1085/2133 1084/1084/2134 1086/1086/2135 +f 1084/1084/2134 1087/1087/2136 1086/1086/2135 +f 1086/1086/2137 1087/1087/2138 1088/1088/2139 +f 1086/1086/2137 1088/1088/2139 1074/1074/2140 +f 1074/1074/2140 1088/1088/2139 1075/1075/2141 +f 1075/1075/2142 1089/1089/2143 1077/1077/2144 +f 1081/1081/2145 1090/1090/2146 1083/1083/2147 +f 1083/1083/2147 1090/1090/2146 1091/1091/2148 +f 1078/1078/2149 1092/1092/2150 1080/1080/2151 +f 1075/1075/2142 1093/1093/2152 1089/1089/2143 +f 1087/1087/2153 1094/1094/2154 1095/1095/2155 +f 1088/1088/2156 1096/1096/2157 1075/1075/2142 +f 1075/1075/2142 1096/1096/2157 1093/1093/2152 +f 1087/1087/2153 1095/1095/2155 1088/1088/2156 +f 1088/1088/2156 1095/1095/2155 1096/1096/2157 +f 1092/1092/2150 1097/1097/2158 1080/1080/2151 +f 1080/1080/2151 1097/1097/2158 1081/1081/2145 +f 1081/1081/2145 1097/1097/2158 1090/1090/2146 +f 1077/1077/2144 1089/1089/2143 1078/1078/2149 +f 1078/1078/2149 1089/1089/2143 1092/1092/2150 +f 1084/1084/2159 1098/1098/2160 1094/1094/2154 +f 1084/1084/2159 1094/1094/2154 1087/1087/2153 +f 1083/1083/2147 1091/1091/2148 1084/1084/2159 +f 1084/1084/2159 1091/1091/2148 1098/1098/2160 +f 1089/1089/2161 1093/1093/2162 1054/1054/2163 +f 1054/1054/2163 1066/1066/2164 1089/1089/2161 +f 1089/1089/2161 1066/1066/2164 1061/1061/2165 +f 1089/1089/2161 1061/1061/2165 1092/1092/2166 +f 1061/1061/2165 1060/1060/2167 1092/1092/2166 +f 1092/1092/2166 1060/1060/2167 1097/1097/2168 +f 1060/1060/2167 1063/1063/2169 1097/1097/2168 +f 1097/1097/2168 1063/1063/2169 1090/1090/2170 +f 1063/1063/2169 1065/1065/2171 1090/1090/2170 +f 1090/1090/2170 1065/1065/2171 1091/1091/2172 +f 1091/1091/2172 1065/1065/2171 1057/1057/2173 +f 1091/1091/2172 1057/1057/2173 1098/1098/2174 +f 1098/1098/2175 1057/1057/2176 1056/1056/2177 +f 1098/1098/2175 1056/1056/2177 1094/1094/2178 +f 1094/1094/2178 1056/1056/2177 1068/1068/2179 +f 1094/1094/2178 1068/1068/2179 1095/1095/2180 +f 1095/1095/2181 1068/1068/2182 1055/1055/2183 +f 1095/1095/2181 1055/1055/2183 1096/1096/2184 +f 1096/1096/2184 1055/1055/2183 1093/1093/2162 +f 1093/1093/2162 1055/1055/2183 1054/1054/2163 +f 1058/1058/2185 1064/1064/2185 1099/1099/2185 +f 1099/1099/2185 1064/1064/2185 1100/1100/2185 +f 1067/1067/2186 1058/1058/2186 1101/1101/2186 +f 1101/1101/2186 1058/1058/2186 1099/1099/2186 +f 1053/1053/2187 1067/1067/2187 1102/1102/2187 +f 1102/1102/2187 1067/1067/2187 1101/1101/2187 +f 1062/1062/2188 1053/1053/2188 1103/1103/2188 +f 1103/1103/2188 1053/1053/2188 1102/1102/2188 +f 1059/1059/2189 1062/1062/2189 1104/1104/2189 +f 1104/1104/2189 1062/1062/2189 1103/1103/2189 +f 1064/1064/2190 1059/1059/2190 1100/1100/2190 +f 1100/1100/2190 1059/1059/2190 1104/1104/2190 +f 1103/1103/145 1102/1102/145 1104/1104/145 +f 1104/1104/145 1102/1102/145 1101/1101/145 +f 1104/1104/145 1101/1101/145 1100/1100/145 +f 1100/1100/145 1101/1101/145 1099/1099/145 +f 1074/1074/2191 1069/1069/2192 1071/1071/2193 +f 1074/1074/2191 1071/1071/2193 1086/1086/2194 +f 1086/1086/2195 1071/1071/2195 1085/1085/2195 +f 1085/1085/2196 1071/1071/2110 1070/1070/2109 +f 1082/1082/2197 1070/1070/2109 1072/1072/2111 +f 1082/1082/2126 1072/1072/2198 1079/1079/2123 +f 1079/1079/2199 1072/1072/2111 1073/1073/2112 +f 1076/1076/2200 1073/1073/2112 1069/1069/2108 +f 1076/1076/2115 1069/1069/2201 1074/1074/2113 +f 1105/1105/2202 1106/1106/2203 1107/1107/2204 +f 1108/1108/2205 1109/1109/2206 1110/1110/2207 +f 1107/1107/2204 1111/1111/2208 1105/1105/2202 +f 1105/1105/2202 1111/1111/2208 1112/1112/2209 +f 1113/1113/2210 1114/1114/2211 1106/1106/2203 +f 1106/1106/2203 1105/1105/2202 1113/1113/2210 +f 1115/1115/2212 1116/1116/2213 1117/1117/2214 +f 1116/1116/2213 1114/1114/2211 1117/1117/2214 +f 1117/1117/2214 1114/1114/2211 1113/1113/2210 +f 1118/1118/2215 1109/1109/2206 1112/1112/2209 +f 1112/1112/2209 1109/1109/2206 1108/1108/2205 +f 1112/1112/2209 1111/1111/2208 1118/1118/2215 +f 1119/1119/2216 1120/1120/2217 1117/1117/2214 +f 1117/1117/2214 1120/1120/2217 1115/1115/2212 +f 1108/1108/2205 1110/1110/2207 1119/1119/2216 +f 1119/1119/2216 1110/1110/2207 1120/1120/2217 +f 1121/1121/2218 1122/1122/2219 1123/1123/2220 +f 1123/1123/2220 1124/1124/2221 1121/1121/2218 +f 1125/1125/2222 1124/1124/2221 1123/1123/2220 +f 1122/1122/2219 1126/1126/2223 1123/1123/2220 +f 1127/1127/2224 1128/1128/2225 1126/1126/2226 +f 1126/1126/2227 1128/1128/2228 1129/1129/2229 +f 1128/1128/2228 1130/1130/2230 1129/1129/2229 +f 1129/1129/2231 1130/1130/2232 1131/1131/2233 +f 1129/1129/2231 1131/1131/2233 1132/1132/2234 +f 1132/1132/2234 1131/1131/2233 1133/1133/2235 +f 1132/1132/2234 1133/1133/2235 1125/1125/2236 +f 1125/1125/2236 1133/1133/2235 1134/1134/2237 +f 1125/1125/2236 1134/1134/2237 1124/1124/2238 +f 1134/1134/2237 1135/1135/2239 1124/1124/2238 +f 1124/1124/2238 1135/1135/2239 1136/1136/2240 +f 1135/1135/2239 1137/1137/2241 1136/1136/2240 +f 1136/1136/2242 1137/1137/2243 1138/1138/2244 +f 1138/1138/2244 1137/1137/2243 1139/1139/2245 +f 1138/1138/2246 1139/1139/2247 1122/1122/2248 +f 1122/1122/2248 1139/1139/2247 1127/1127/2249 +f 1122/1122/2250 1127/1127/2224 1126/1126/2226 +f 1128/1128/2251 1140/1140/2252 1141/1141/2253 +f 1134/1134/2254 1142/1142/2255 1135/1135/2256 +f 1127/1127/2257 1140/1140/2252 1128/1128/2251 +f 1127/1127/2257 1143/1143/2258 1140/1140/2252 +f 1137/1137/2259 1144/1144/2260 1139/1139/2261 +f 1133/1133/2262 1145/1145/2263 1134/1134/2254 +f 1134/1134/2254 1145/1145/2263 1142/1142/2255 +f 1130/1130/2264 1146/1146/2265 1131/1131/2266 +f 1139/1139/2261 1147/1147/2267 1143/1143/2258 +f 1139/1139/2261 1143/1143/2258 1127/1127/2257 +f 1144/1144/2260 1147/1147/2267 1139/1139/2261 +f 1146/1146/2265 1148/1148/2268 1131/1131/2266 +f 1131/1131/2266 1148/1148/2268 1133/1133/2262 +f 1133/1133/2262 1148/1148/2268 1145/1145/2263 +f 1128/1128/2251 1141/1141/2253 1130/1130/2264 +f 1130/1130/2264 1141/1141/2253 1146/1146/2265 +f 1135/1135/2256 1142/1142/2255 1149/1149/2269 +f 1135/1135/2256 1149/1149/2269 1137/1137/2259 +f 1137/1137/2259 1149/1149/2269 1144/1144/2260 +f 1109/1109/2270 1118/1118/2271 1140/1140/2272 +f 1140/1140/2272 1118/1118/2271 1141/1141/2273 +f 1118/1118/2271 1111/1111/2274 1141/1141/2273 +f 1141/1141/2273 1111/1111/2274 1146/1146/2275 +f 1146/1146/2275 1111/1111/2274 1107/1107/2276 +f 1146/1146/2275 1107/1107/2276 1148/1148/2277 +f 1107/1107/2276 1106/1106/2278 1148/1148/2277 +f 1148/1148/2277 1106/1106/2278 1145/1145/2279 +f 1145/1145/2279 1106/1106/2278 1114/1114/2280 +f 1145/1145/2279 1114/1114/2280 1142/1142/2281 +f 1114/1114/2280 1116/1116/2282 1142/1142/2281 +f 1142/1142/2281 1116/1116/2282 1149/1149/2283 +f 1149/1149/2283 1116/1116/2282 1115/1115/2284 +f 1149/1149/2283 1115/1115/2284 1144/1144/2285 +f 1115/1115/2284 1120/1120/2286 1144/1144/2285 +f 1144/1144/2285 1120/1120/2286 1147/1147/2287 +f 1147/1147/2287 1120/1120/2286 1110/1110/2288 +f 1147/1147/2287 1110/1110/2288 1143/1143/2289 +f 1110/1110/2288 1109/1109/2290 1143/1143/2289 +f 1143/1143/2289 1109/1109/2290 1140/1140/2291 +f 1117/1117/2292 1113/1113/2292 1150/1150/2292 +f 1150/1150/2292 1113/1113/2292 1151/1151/2292 +f 1119/1119/2293 1117/1117/2293 1152/1152/2293 +f 1152/1152/2293 1117/1117/2293 1150/1150/2293 +f 1108/1108/2294 1119/1119/2294 1153/1153/2294 +f 1153/1153/2294 1119/1119/2294 1152/1152/2294 +f 1112/1112/2295 1108/1108/2295 1154/1154/2295 +f 1154/1154/2295 1108/1108/2295 1153/1153/2295 +f 1105/1105/2296 1112/1112/2296 1155/1155/2296 +f 1155/1155/2296 1112/1112/2296 1154/1154/2296 +f 1113/1113/2297 1105/1105/2297 1151/1151/2297 +f 1151/1151/2297 1105/1105/2297 1155/1155/2297 +f 1154/1154/145 1153/1153/145 1155/1155/145 +f 1155/1155/145 1153/1153/145 1152/1152/145 +f 1155/1155/145 1152/1152/145 1151/1151/145 +f 1151/1151/145 1152/1152/145 1150/1150/145 +f 1138/1138/2298 1122/1122/2298 1121/1121/2298 +f 1138/1138/2244 1121/1121/2299 1136/1136/2242 +f 1136/1136/2300 1121/1121/2218 1124/1124/2221 +f 1132/1132/2301 1125/1125/2222 1123/1123/2220 +f 1132/1132/2234 1123/1123/2302 1129/1129/2231 +f 1129/1129/2303 1123/1123/2220 1126/1126/2223 +f 1156/1156/2304 1157/1157/2305 1158/1158/2306 +f 1159/1159/2307 1160/1160/2308 1161/1161/2309 +f 1159/1159/2307 1161/1161/2309 1162/1162/2310 +f 1163/1163/2311 1159/1159/2307 1164/1164/2312 +f 1165/1165/2313 1166/1166/2314 1164/1164/2312 +f 1161/1161/2309 1157/1157/2305 1162/1162/2310 +f 1164/1164/2312 1166/1166/2314 1163/1163/2311 +f 1167/1167/2315 1165/1165/2313 1168/1168/2316 +f 1168/1168/2316 1165/1165/2313 1164/1164/2312 +f 1169/1169/2317 1167/1167/2315 1168/1168/2316 +f 1170/1170/2318 1171/1171/2319 1169/1169/2317 +f 1162/1162/2310 1157/1157/2305 1156/1156/2304 +f 1159/1159/2307 1163/1163/2311 1160/1160/2308 +f 1170/1170/2318 1169/1169/2317 1168/1168/2316 +f 1158/1158/2306 1171/1171/2319 1156/1156/2304 +f 1156/1156/2304 1171/1171/2319 1170/1170/2318 +f 1172/1172/2320 1173/1173/2321 1174/1174/2322 +f 1172/1172/2320 1175/1175/2323 1173/1173/2321 +f 1172/1172/2320 1176/1176/2324 1175/1175/2323 +f 1177/1177/2325 1176/1176/2324 1172/1172/2320 +f 1177/1177/2326 1178/1178/2327 1176/1176/2328 +f 1178/1178/2327 1179/1179/2329 1176/1176/2328 +f 1176/1176/2328 1179/1179/2329 1180/1180/2330 +f 1179/1179/2329 1181/1181/2331 1180/1180/2330 +f 1180/1180/2330 1181/1181/2331 1175/1175/2332 +f 1181/1181/2331 1182/1182/2333 1175/1175/2332 +f 1175/1175/2334 1182/1182/2335 1173/1173/2336 +f 1173/1173/2336 1182/1182/2335 1183/1183/2337 +f 1173/1173/2338 1183/1183/2339 1174/1174/2340 +f 1183/1183/2339 1184/1184/2341 1174/1174/2340 +f 1174/1174/2342 1184/1184/2343 1185/1185/2344 +f 1184/1184/2343 1186/1186/2345 1185/1185/2344 +f 1185/1185/2346 1186/1186/2347 1172/1172/2348 +f 1172/1172/2348 1186/1186/2347 1187/1187/2349 +f 1172/1172/2350 1187/1187/2351 1177/1177/2352 +f 1177/1177/2352 1187/1187/2351 1178/1178/2353 +f 1178/1178/2354 1188/1188/2355 1179/1179/2356 +f 1181/1181/2357 1189/1189/2358 1190/1190/2359 +f 1178/1178/2354 1191/1191/2360 1188/1188/2355 +f 1187/1187/2361 1191/1191/2360 1178/1178/2354 +f 1182/1182/2362 1192/1192/2363 1183/1183/2364 +f 1183/1183/2364 1192/1192/2363 1193/1193/2365 +f 1179/1179/2356 1189/1189/2358 1181/1181/2357 +f 1187/1187/2361 1194/1194/2366 1191/1191/2360 +f 1186/1186/2367 1195/1195/2368 1187/1187/2361 +f 1187/1187/2361 1195/1195/2368 1194/1194/2366 +f 1181/1181/2357 1190/1190/2359 1182/1182/2362 +f 1182/1182/2362 1190/1190/2359 1192/1192/2363 +f 1188/1188/2355 1189/1189/2358 1179/1179/2356 +f 1184/1184/2369 1196/1196/2370 1195/1195/2368 +f 1184/1184/2369 1195/1195/2368 1186/1186/2367 +f 1183/1183/2364 1193/1193/2365 1196/1196/2370 +f 1183/1183/2364 1196/1196/2370 1184/1184/2369 +f 1157/1157/2371 1161/1161/2372 1188/1188/2373 +f 1188/1188/2373 1161/1161/2372 1189/1189/2374 +f 1161/1161/2375 1160/1160/2376 1189/1189/2377 +f 1189/1189/2377 1160/1160/2376 1190/1190/2378 +f 1190/1190/2378 1160/1160/2376 1163/1163/2379 +f 1190/1190/2378 1163/1163/2379 1192/1192/2380 +f 1192/1192/2380 1163/1163/2379 1166/1166/2381 +f 1192/1192/2380 1166/1166/2381 1193/1193/2382 +f 1193/1193/2382 1166/1166/2381 1165/1165/2383 +f 1193/1193/2382 1165/1165/2383 1196/1196/2384 +f 1196/1196/2384 1165/1165/2383 1167/1167/2385 +f 1167/1167/2386 1169/1169/2387 1196/1196/2388 +f 1196/1196/2388 1169/1169/2387 1195/1195/2389 +f 1169/1169/2390 1171/1171/2391 1195/1195/2392 +f 1195/1195/2392 1171/1171/2391 1194/1194/2393 +f 1171/1171/2391 1158/1158/2394 1194/1194/2393 +f 1194/1194/2393 1158/1158/2394 1191/1191/2395 +f 1158/1158/2394 1157/1157/2396 1191/1191/2395 +f 1191/1191/2395 1157/1157/2396 1188/1188/2397 +f 1168/1168/2398 1164/1164/2398 1197/1197/2398 +f 1197/1197/2398 1164/1164/2398 1198/1198/2398 +f 1170/1170/2399 1168/1168/2399 1199/1199/2399 +f 1199/1199/2399 1168/1168/2399 1197/1197/2399 +f 1156/1156/2400 1170/1170/2400 1200/1200/2400 +f 1200/1200/2400 1170/1170/2400 1199/1199/2400 +f 1162/1162/2401 1156/1156/2401 1201/1201/2401 +f 1201/1201/2401 1156/1156/2401 1200/1200/2401 +f 1159/1159/2402 1162/1162/2402 1202/1202/2402 +f 1202/1202/2402 1162/1162/2402 1201/1201/2402 +f 1164/1164/2403 1159/1159/2403 1198/1198/2403 +f 1198/1198/2403 1159/1159/2403 1202/1202/2403 +f 1201/1201/145 1200/1200/145 1202/1202/145 +f 1202/1202/145 1200/1200/145 1199/1199/145 +f 1202/1202/145 1199/1199/145 1198/1198/145 +f 1198/1198/145 1199/1199/145 1197/1197/145 +f 1185/1185/2404 1172/1172/2320 1174/1174/2322 +f 1180/1180/2405 1175/1175/2323 1176/1176/2324 +f 1203/1203/2406 1204/1204/2407 1205/1205/2408 +f 1206/1206/2409 1207/1207/2410 1208/1208/2411 +f 1209/1209/2412 1210/1210/2413 1211/1211/2414 +f 1212/1212/2415 1213/1213/2416 1214/1214/2417 +f 1214/1214/2417 1213/1213/2416 1215/1215/2418 +f 1208/1208/2411 1207/1207/2410 1216/1216/2419 +f 1216/1216/2419 1214/1214/2417 1208/1208/2411 +f 1217/1217/2420 1206/1206/2409 1208/1208/2411 +f 1217/1217/2420 1218/1218/2421 1206/1206/2409 +f 1219/1219/2422 1209/1209/2412 1215/1215/2418 +f 1215/1215/2418 1209/1209/2412 1211/1211/2414 +f 1215/1215/2418 1213/1213/2416 1219/1219/2422 +f 1214/1214/2417 1216/1216/2419 1212/1212/2415 +f 1203/1203/2406 1205/1205/2408 1217/1217/2420 +f 1217/1217/2420 1205/1205/2408 1218/1218/2421 +f 1211/1211/2414 1210/1210/2413 1203/1203/2406 +f 1203/1203/2406 1210/1210/2413 1204/1204/2407 +f 1220/1220/2423 1221/1221/2424 1222/1222/2425 +f 1222/1222/2425 1223/1223/2426 1224/1224/2427 +f 1222/1222/2425 1221/1221/2424 1223/1223/2426 +f 1225/1225/2428 1226/1226/2429 1227/1227/2430 +f 1227/1227/2430 1226/1226/2429 1228/1228/2431 +f 1226/1226/2432 1229/1229/2433 1228/1228/2434 +f 1228/1228/2434 1229/1229/2433 1230/1230/2435 +f 1230/1230/2435 1229/1229/2433 1231/1231/2436 +f 1230/1230/2437 1231/1231/2438 1223/1223/2439 +f 1223/1223/2439 1231/1231/2438 1232/1232/2440 +f 1223/1223/2439 1232/1232/2440 1233/1233/2441 +f 1233/1233/2441 1232/1232/2440 1234/1234/2442 +f 1234/1234/2443 1235/1235/2444 1233/1233/2445 +f 1233/1233/2445 1235/1235/2444 1236/1236/2446 +f 1235/1235/2444 1237/1237/2447 1236/1236/2446 +f 1236/1236/2448 1237/1237/2449 1222/1222/2450 +f 1237/1237/2449 1238/1238/2451 1222/1222/2450 +f 1222/1222/2452 1238/1238/2453 1227/1227/2454 +f 1227/1227/2454 1238/1238/2453 1225/1225/2455 +f 1229/1229/2456 1239/1239/2457 1231/1231/2458 +f 1231/1231/2458 1239/1239/2457 1240/1240/2459 +f 1225/1225/2460 1241/1241/2461 1242/1242/2462 +f 1225/1225/2460 1242/1242/2462 1226/1226/2463 +f 1238/1238/2464 1243/1243/2465 1225/1225/2460 +f 1225/1225/2460 1243/1243/2465 1241/1241/2461 +f 1237/1237/2466 1244/1244/2467 1238/1238/2464 +f 1232/1232/2468 1245/1245/2469 1234/1234/2470 +f 1234/1234/2470 1245/1245/2469 1246/1246/2471 +f 1238/1238/2464 1244/1244/2467 1243/1243/2465 +f 1231/1231/2458 1240/1240/2459 1245/1245/2469 +f 1231/1231/2458 1245/1245/2469 1232/1232/2468 +f 1226/1226/2463 1242/1242/2462 1239/1239/2457 +f 1226/1226/2463 1239/1239/2457 1229/1229/2456 +f 1235/1235/2472 1247/1247/2473 1237/1237/2466 +f 1237/1237/2466 1247/1247/2473 1244/1244/2467 +f 1234/1234/2470 1246/1246/2471 1235/1235/2472 +f 1235/1235/2472 1246/1246/2471 1247/1247/2473 +f 1242/1242/2474 1241/1241/2475 1209/1209/2476 +f 1242/1242/2474 1209/1209/2476 1219/1219/2477 +f 1242/1242/2478 1219/1219/2479 1213/1213/2480 +f 1242/1242/2478 1213/1213/2480 1239/1239/2481 +f 1239/1239/2482 1213/1213/2483 1212/1212/2484 +f 1239/1239/2482 1212/1212/2484 1240/1240/2485 +f 1212/1212/2484 1216/1216/2486 1240/1240/2485 +f 1240/1240/2485 1216/1216/2486 1245/1245/2487 +f 1245/1245/2487 1216/1216/2486 1207/1207/2488 +f 1245/1245/2487 1207/1207/2488 1246/1246/2489 +f 1207/1207/2488 1206/1206/2490 1246/1246/2489 +f 1246/1246/2491 1206/1206/2492 1247/1247/2493 +f 1206/1206/2492 1218/1218/2494 1247/1247/2493 +f 1247/1247/2493 1218/1218/2494 1205/1205/2495 +f 1247/1247/2493 1205/1205/2495 1244/1244/2496 +f 1205/1205/2495 1204/1204/2497 1244/1244/2496 +f 1244/1244/2496 1204/1204/2497 1243/1243/2498 +f 1243/1243/2498 1204/1204/2497 1210/1210/2499 +f 1210/1210/2499 1209/1209/2500 1243/1243/2498 +f 1243/1243/2498 1209/1209/2500 1241/1241/2501 +f 1217/1217/2502 1208/1208/2502 1248/1248/2502 +f 1248/1248/2502 1208/1208/2502 1249/1249/2502 +f 1203/1203/2503 1217/1217/2503 1250/1250/2503 +f 1250/1250/2503 1217/1217/2503 1248/1248/2503 +f 1211/1211/2504 1203/1203/2504 1251/1251/2504 +f 1251/1251/2504 1203/1203/2504 1250/1250/2504 +f 1215/1215/2505 1211/1211/2505 1252/1252/2505 +f 1252/1252/2505 1211/1211/2505 1251/1251/2505 +f 1214/1214/2506 1215/1215/2506 1253/1253/2506 +f 1253/1253/2506 1215/1215/2506 1252/1252/2506 +f 1208/1208/2507 1214/1214/2507 1249/1249/2507 +f 1249/1249/2507 1214/1214/2507 1253/1253/2507 +f 1252/1252/145 1251/1251/145 1253/1253/145 +f 1253/1253/145 1251/1251/145 1250/1250/145 +f 1253/1253/145 1250/1250/145 1249/1249/145 +f 1249/1249/145 1250/1250/145 1248/1248/145 +f 1227/1227/2508 1220/1220/2508 1222/1222/2508 +f 1236/1236/2509 1222/1222/2509 1224/1224/2509 +f 1236/1236/2446 1224/1224/2510 1233/1233/2445 +f 1233/1233/2511 1224/1224/2427 1223/1223/2426 +f 1230/1230/2512 1223/1223/2426 1221/1221/2424 +f 1230/1230/2435 1221/1221/2513 1228/1228/2434 +f 1228/1228/2514 1221/1221/2515 1227/1227/2516 +f 1227/1227/2516 1221/1221/2515 1220/1220/2517 +f 1254/1254/145 1255/1255/145 1256/1256/145 +f 1257/1257/145 1258/1258/145 1259/1259/145 +f 1259/1259/145 1258/1258/145 1260/1260/145 +f 1261/1261/145 1262/1262/145 1263/1263/145 +f 1264/1264/145 1265/1265/145 1258/1258/145 +f 1265/1265/145 1266/1266/145 1267/1267/145 +f 1265/1265/145 1267/1267/145 1258/1258/145 +f 1268/1268/145 1269/1269/145 1270/1270/145 +f 1270/1270/145 1269/1269/145 1262/1262/145 +f 1262/1262/145 1269/1269/145 1263/1263/145 +f 1264/1264/145 1258/1258/145 1257/1257/145 +f 1254/1254/145 1256/1256/145 1268/1268/145 +f 1254/1254/145 1268/1268/145 1270/1270/145 +f 1271/1271/145 1260/1260/145 1266/1266/145 +f 1267/1267/145 1266/1266/145 1260/1260/145 +f 1261/1261/145 1263/1263/145 1256/1256/145 +f 1260/1260/145 1271/1271/145 1272/1272/145 +f 1256/1256/145 1273/1273/145 1261/1261/145 +f 1260/1260/145 1272/1272/145 1259/1259/145 +f 1256/1256/145 1255/1255/145 1274/1274/145 +f 1273/1273/145 1274/1274/145 1275/1275/145 +f 1256/1256/145 1274/1274/145 1273/1273/145 +f 1276/1276/145 1277/1277/145 1278/1278/145 +f 1278/1278/145 1277/1277/145 1279/1279/145 +f 1278/1278/145 1279/1279/145 1280/1280/145 +f 1278/1278/145 1280/1280/145 1281/1281/145 +f 1282/1282/145 1283/1283/145 1276/1276/145 +f 1276/1276/145 1283/1283/145 1284/1284/145 +f 1259/1259/145 1272/1272/145 1282/1282/145 +f 1282/1282/145 1272/1272/145 1283/1283/145 +f 1273/1273/145 1275/1275/145 1280/1280/145 +f 1280/1280/145 1275/1275/145 1281/1281/145 +f 1284/1284/145 1277/1277/145 1276/1276/145 +f 1285/1285/56 1286/1286/56 1287/1287/56 +f 1288/1288/56 1289/1289/56 1290/1290/56 +f 1289/1289/56 1291/1291/56 1290/1290/56 +f 1292/1292/56 1293/1293/56 1294/1294/56 +f 1295/1295/56 1296/1296/56 1297/1297/56 +f 1296/1296/56 1298/1298/56 1297/1297/56 +f 1285/1285/56 1287/1287/56 1299/1299/56 +f 1299/1299/56 1287/1287/56 1300/1300/56 +f 1292/1292/56 1294/1294/56 1286/1286/56 +f 1300/1300/56 1293/1293/56 1301/1301/56 +f 1297/1297/56 1298/1298/56 1289/1289/56 +f 1289/1289/56 1298/1298/56 1291/1291/56 +f 1296/1296/56 1295/1295/56 1290/1290/56 +f 1294/1294/56 1293/1293/56 1300/1300/56 +f 1285/1285/56 1292/1292/56 1286/1286/56 +f 1290/1290/56 1302/1302/56 1288/1288/56 +f 1295/1295/56 1303/1303/56 1290/1290/56 +f 1304/1304/56 1300/1300/56 1301/1301/56 +f 1303/1303/56 1305/1305/56 1302/1302/56 +f 1290/1290/56 1303/1303/56 1302/1302/56 +f 1302/1302/56 1305/1305/56 1306/1306/56 +f 1306/1306/56 1305/1305/56 1307/1307/56 +f 1308/1308/56 1309/1309/56 1310/1310/56 +f 1310/1310/56 1309/1309/56 1311/1311/56 +f 1312/1312/56 1313/1313/56 1306/1306/56 +f 1312/1312/56 1306/1306/56 1307/1307/56 +f 1314/1314/56 1299/1299/56 1304/1304/56 +f 1310/1310/56 1311/1311/56 1312/1312/56 +f 1312/1312/56 1311/1311/56 1313/1313/56 +f 1300/1300/56 1304/1304/56 1299/1299/56 +f 1315/1315/56 1316/1316/56 1309/1309/56 +f 1315/1315/56 1309/1309/56 1308/1308/56 +f 1314/1314/56 1304/1304/56 1315/1315/56 +f 1315/1315/56 1304/1304/56 1316/1316/56 +f 1254/1254/2518 1285/1285/2519 1255/1255/2520 +f 1255/1255/2520 1285/1285/2519 1299/1299/2521 +f 1255/1255/2522 1299/1299/2522 1274/1274/2522 +f 1274/1274/2523 1299/1299/2523 1314/1314/2523 +f 1274/1274/2524 1314/1314/2524 1275/1275/2524 +f 1275/1275/2525 1314/1314/2525 1315/1315/2525 +f 1275/1275/2526 1315/1315/2526 1281/1281/2526 +f 1281/1281/2527 1315/1315/2527 1308/1308/2527 +f 1281/1281/2528 1308/1308/2528 1278/1278/2528 +f 1278/1278/2529 1308/1308/2529 1310/1310/2529 +f 1278/1278/2530 1310/1310/2530 1276/1276/2530 +f 1276/1276/2531 1310/1310/2531 1312/1312/2531 +f 1276/1276/2532 1312/1312/2533 1307/1307/2534 +f 1276/1276/2532 1307/1307/2534 1282/1282/2535 +f 1282/1282/2536 1307/1307/2536 1305/1305/2536 +f 1282/1282/2537 1305/1305/2537 1259/1259/2537 +f 1259/1259/2538 1305/1305/2538 1303/1303/2538 +f 1259/1259/2539 1303/1303/2539 1257/1257/2539 +f 1257/1257/2540 1303/1303/2540 1295/1295/2540 +f 1257/1257/2541 1295/1295/2541 1264/1264/2541 +f 1265/1265/2542 1264/1264/2543 1297/1297/2544 +f 1297/1297/2544 1264/1264/2543 1295/1295/2545 +f 1265/1265/2546 1297/1297/2547 1289/1289/2548 +f 1265/1265/2546 1289/1289/2548 1266/1266/2549 +f 1271/1271/2550 1266/1266/2551 1288/1288/2552 +f 1288/1288/2552 1266/1266/2551 1289/1289/2553 +f 1271/1271/2550 1288/1288/2552 1302/1302/2554 +f 1271/1271/2550 1302/1302/2554 1272/1272/2555 +f 1272/1272/2556 1302/1302/2557 1306/1306/2558 +f 1272/1272/2556 1306/1306/2558 1283/1283/2559 +f 1283/1283/2560 1306/1306/2560 1284/1284/2560 +f 1284/1284/2561 1306/1306/2561 1313/1313/2561 +f 1284/1284/2562 1313/1313/2562 1277/1277/2562 +f 1277/1277/2563 1313/1313/2563 1311/1311/2563 +f 1277/1277/2564 1311/1311/2564 1279/1279/2564 +f 1279/1279/2565 1311/1311/2565 1309/1309/2565 +f 1279/1279/2566 1309/1309/2566 1280/1280/2566 +f 1280/1280/2567 1309/1309/2567 1316/1316/2567 +f 1280/1280/2568 1316/1316/2569 1304/1304/2570 +f 1280/1280/2568 1304/1304/2570 1273/1273/2571 +f 1273/1273/2572 1304/1304/2573 1301/1301/2574 +f 1273/1273/2572 1301/1301/2574 1261/1261/2575 +f 1262/1262/2576 1261/1261/2575 1293/1293/2577 +f 1293/1293/2577 1261/1261/2575 1301/1301/2574 +f 1262/1262/2578 1293/1293/2579 1292/1292/2580 +f 1262/1262/2578 1292/1292/2580 1270/1270/2581 +f 1254/1254/2582 1270/1270/2583 1285/1285/2584 +f 1285/1285/2584 1270/1270/2583 1292/1292/2585 +f 1267/1267/2586 1290/1290/2587 1291/1291/2588 +f 1267/1267/2589 1291/1291/2589 1298/1298/2589 +f 1267/1267/2590 1298/1298/2590 1258/1258/2590 +f 1258/1258/2591 1298/1298/2591 1296/1296/2591 +f 1258/1258/2592 1296/1296/2592 1260/1260/2592 +f 1260/1260/2593 1296/1296/2593 1290/1290/2593 +f 1260/1260/2594 1290/1290/2587 1267/1267/2586 +f 1268/1268/2595 1286/1286/2595 1269/1269/2595 +f 1269/1269/2596 1286/1286/2596 1294/1294/2596 +f 1269/1269/2597 1294/1294/2597 1263/1263/2597 +f 1263/1263/2598 1294/1294/2598 1300/1300/2598 +f 1263/1263/2599 1300/1300/2599 1256/1256/2599 +f 1256/1256/2600 1300/1300/2600 1287/1287/2600 +f 1256/1256/2601 1287/1287/2601 1268/1268/2601 +f 1268/1268/2602 1287/1287/2602 1286/1286/2602 +f 1317/1317/2603 1318/1318/2604 1319/1319/2605 +f 1317/1317/2603 1319/1319/2605 1320/1320/2606 +f 1320/1320/2606 1319/1319/2605 1321/1321/2607 +f 1321/1321/2607 1319/1319/2605 1322/1322/2608 +f 1321/1321/2607 1322/1322/2608 1323/1323/2609 +f 1323/1323/2609 1322/1322/2608 1324/1324/2610 +f 1323/1323/2609 1324/1324/2610 1325/1325/2611 +f 1325/1325/2611 1324/1324/2610 1326/1326/2612 +f 1325/1325/2611 1326/1326/2612 1327/1327/2613 +f 1327/1327/2613 1326/1326/2612 1328/1328/2614 +f 1327/1327/2613 1328/1328/2614 1329/1329/2615 +f 1329/1329/2615 1328/1328/2614 1330/1330/2616 +f 1329/1329/2615 1330/1330/2616 1331/1331/2617 +f 1329/1329/2615 1331/1331/2617 1332/1332/2618 +f 1332/1332/2618 1331/1331/2617 1333/1333/2619 +f 1333/1333/2619 1331/1331/2617 1334/1334/2620 +f 1333/1333/2619 1334/1334/2620 1335/1335/2621 +f 1333/1333/2619 1335/1335/2621 1336/1336/2622 +f 1336/1336/2622 1335/1335/2621 1337/1337/2623 +f 1337/1337/2623 1335/1335/2621 1338/1338/2624 +f 1337/1337/2623 1338/1338/2624 1339/1339/2625 +f 1339/1339/2625 1338/1338/2624 1340/1340/2626 +f 1339/1339/2625 1340/1340/2626 1341/1341/2627 +f 1341/1341/2627 1340/1340/2626 1342/1342/2628 +f 1341/1341/2627 1342/1342/2628 1343/1343/2629 +f 1343/1343/2629 1342/1342/2628 1344/1344/2630 +f 1343/1343/2629 1344/1344/2630 1345/1345/2631 +f 1345/1345/2631 1344/1344/2630 1346/1346/2632 +f 1345/1345/2631 1346/1346/2632 1347/1347/2633 +f 1347/1347/2633 1346/1346/2632 1318/1318/2604 +f 1347/1347/2633 1318/1318/2604 1317/1317/2603 +f 1331/1331/2634 1330/1330/2634 1334/1334/2634 +f 1342/1342/2634 1340/1340/2634 1344/1344/2634 +f 1322/1322/2634 1319/1319/2634 1340/1340/2634 +f 1322/1322/2634 1326/1326/2634 1324/1324/2634 +f 1340/1340/2634 1319/1319/2634 1344/1344/2634 +f 1319/1319/2634 1318/1318/2634 1344/1344/2634 +f 1335/1335/2634 1326/1326/2634 1338/1338/2634 +f 1344/1344/2634 1318/1318/2634 1346/1346/2634 +f 1340/1340/2634 1326/1326/2634 1322/1322/2634 +f 1326/1326/2634 1335/1335/2634 1328/1328/2634 +f 1328/1328/2634 1335/1335/2634 1334/1334/2634 +f 1328/1328/2634 1334/1334/2634 1330/1330/2634 +f 1340/1340/2634 1338/1338/2634 1326/1326/2634 +f 1327/1327/2635 1336/1336/2635 1339/1339/2635 +f 1347/1347/2635 1317/1317/2635 1345/1345/2635 +f 1321/1321/2635 1323/1323/2635 1320/1320/2635 +f 1339/1339/2635 1341/1341/2635 1345/1345/2635 +f 1323/1323/2635 1345/1345/2635 1320/1320/2635 +f 1343/1343/2635 1345/1345/2635 1341/1341/2635 +f 1323/1323/2635 1325/1325/2635 1327/1327/2635 +f 1336/1336/2635 1329/1329/2635 1333/1333/2635 +f 1317/1317/2635 1320/1320/2635 1345/1345/2635 +f 1339/1339/2635 1323/1323/2635 1327/1327/2635 +f 1339/1339/2635 1336/1336/2635 1337/1337/2635 +f 1329/1329/2635 1336/1336/2635 1327/1327/2635 +f 1339/1339/2635 1345/1345/2635 1323/1323/2635 +f 1333/1333/2635 1329/1329/2635 1332/1332/2635 +f 1348/1348/2636 1349/1349/2637 1350/1350/2638 +f 1351/1351/2639 1352/1352/2640 1348/1348/2636 +f 1349/1349/2637 1353/1353/2641 1350/1350/2638 +f 1354/1354/2642 1355/1355/2643 1356/1356/2644 +f 1353/1353/2641 1357/1357/2645 1350/1350/2638 +f 1350/1350/2638 1357/1357/2645 1358/1358/2646 +f 1359/1359/2647 1350/1350/2638 1358/1358/2646 +f 1359/1359/2647 1358/1358/2646 1360/1360/2648 +f 1361/1361/2649 1350/1350/2638 1359/1359/2647 +f 1359/1359/2647 1360/1360/2648 1362/1362/2650 +f 1361/1361/2649 1359/1359/2647 1362/1362/2650 +f 1363/1363/2651 1362/1362/2650 1360/1360/2648 +f 1348/1348/2636 1350/1350/2638 1364/1364/2652 +f 1364/1364/2652 1350/1350/2638 1361/1361/2649 +f 1365/1365/2653 1361/1361/2649 1362/1362/2650 +f 1366/1366/2654 1363/1363/2651 1360/1360/2648 +f 1366/1366/2654 1360/1360/2648 1367/1367/2655 +f 1365/1365/2653 1362/1362/2650 1363/1363/2651 +f 1368/1368/2656 1355/1355/2643 1369/1369/2657 +f 1369/1369/2657 1354/1354/2642 1370/1370/2658 +f 1365/1365/2653 1368/1368/2656 1369/1369/2657 +f 1364/1364/2652 1369/1369/2657 1370/1370/2658 +f 1363/1363/2651 1366/1366/2654 1368/1368/2656 +f 1365/1365/2653 1369/1369/2657 1364/1364/2652 +f 1348/1348/2636 1370/1370/2658 1351/1351/2639 +f 1364/1364/2652 1361/1361/2649 1365/1365/2653 +f 1354/1354/2642 1369/1369/2657 1355/1355/2643 +f 1370/1370/2658 1348/1348/2636 1364/1364/2652 +f 1368/1368/2656 1365/1365/2653 1363/1363/2651 +f 1353/1353/2641 1349/1349/2637 1371/1371/2659 +f 1371/1371/2659 1349/1349/2637 1352/1352/2640 +f 1371/1371/2659 1352/1352/2640 1372/1372/2660 +f 1352/1352/2640 1373/1373/2661 1372/1372/2660 +f 1372/1372/2660 1373/1373/2661 1374/1374/2662 +f 1372/1372/2660 1374/1374/2662 1375/1375/2663 +f 1375/1375/2663 1374/1374/2662 1376/1376/2664 +f 1376/1376/2664 1374/1374/2662 1377/1377/2665 +f 1376/1376/2664 1377/1377/2665 1378/1378/2666 +f 1376/1376/2664 1378/1378/2666 1379/1379/2667 +f 1379/1379/2667 1378/1378/2666 1380/1380/2668 +f 1379/1379/2667 1380/1380/2668 1381/1381/2669 +f 1381/1381/2669 1380/1380/2668 1382/1382/2670 +f 1381/1381/2669 1382/1382/2670 1383/1383/2671 +f 1384/1384/145 1376/1376/145 1385/1385/145 +f 1385/1385/145 1376/1376/145 1386/1386/145 +f 1386/1386/145 1376/1376/145 1379/1379/145 +f 1386/1386/145 1379/1379/145 1387/1387/145 +f 1388/1388/2672 1372/1372/2673 1384/1384/145 +f 1384/1384/145 1372/1372/2673 1375/1375/2674 +f 1384/1384/145 1375/1375/2674 1376/1376/145 +f 1389/1389/2675 1390/1390/2676 1367/1367/2677 +f 1391/1391/2678 1392/1392/2679 1393/1393/2680 +f 1393/1393/2680 1392/1392/2679 1390/1390/2676 +f 1387/1387/145 1379/1379/145 1394/1394/145 +f 1394/1394/145 1379/1379/145 1381/1381/145 +f 1391/1391/2678 1395/1395/2681 1392/1392/2679 +f 1396/1396/2682 1371/1371/2682 1388/1388/2672 +f 1388/1388/2672 1371/1371/2682 1372/1372/2673 +f 1393/1393/2680 1390/1390/2676 1389/1389/2675 +f 1397/1397/2683 1383/1383/2684 1398/1398/2685 +f 1394/1394/145 1381/1381/145 1399/1399/145 +f 1399/1399/145 1381/1381/145 1383/1383/2684 +f 1399/1399/145 1383/1383/2684 1400/1400/145 +f 1400/1400/145 1383/1383/2684 1397/1397/2683 +f 1389/1389/2675 1367/1367/2677 1360/1360/2686 +f 1401/1401/2687 1402/1402/2688 1391/1391/2678 +f 1391/1391/2678 1402/1402/2688 1395/1395/2681 +f 1396/1396/2682 1357/1357/2682 1371/1371/2682 +f 1403/1403/2672 1357/1357/2682 1396/1396/2682 +f 1403/1403/2672 1358/1358/2689 1357/1357/2682 +f 1360/1360/2686 1358/1358/2689 1403/1403/2672 +f 1398/1398/2685 1402/1402/2688 1401/1401/2687 +f 1397/1397/2683 1398/1398/2685 1401/1401/2687 +f 1389/1389/2675 1360/1360/2686 1403/1403/2672 +f 1404/1404/2690 1405/1405/2691 1406/1406/2692 +f 1407/1407/2693 1405/1405/2691 1404/1404/2690 +f 1405/1405/2691 1407/1407/2693 1408/1408/2694 +f 1408/1408/2694 1409/1409/2695 1405/1405/2691 +f 1409/1409/2695 1408/1408/2694 1410/1410/2696 +f 1409/1409/2695 1410/1410/2696 1411/1411/2697 +f 1412/1412/2698 1356/1356/2699 1413/1413/2700 +f 1382/1382/2701 1414/1414/2702 1415/1415/2703 +f 1415/1415/2703 1414/1414/2702 1416/1416/2704 +f 1417/1417/2705 1351/1351/2706 1370/1370/2707 +f 1418/1418/2706 1352/1352/2708 1419/1419/2709 +f 1418/1418/2706 1373/1373/2710 1352/1352/2708 +f 1419/1419/2709 1351/1351/2706 1417/1417/2705 +f 1420/1420/56 1374/1374/56 1421/1421/56 +f 1421/1421/56 1374/1374/56 1418/1418/2706 +f 1418/1418/2706 1374/1374/56 1373/1373/2710 +f 1417/1417/2705 1354/1354/2711 1412/1412/2698 +f 1419/1419/2709 1352/1352/2708 1351/1351/2706 +f 1422/1422/56 1378/1378/56 1420/1420/56 +f 1420/1420/56 1378/1378/56 1377/1377/56 +f 1420/1420/56 1377/1377/56 1374/1374/56 +f 1370/1370/2707 1354/1354/2711 1417/1417/2705 +f 1423/1423/56 1380/1380/56 1424/1424/56 +f 1424/1424/56 1380/1380/56 1422/1422/56 +f 1422/1422/56 1380/1380/56 1378/1378/56 +f 1412/1412/2698 1354/1354/2711 1356/1356/2699 +f 1414/1414/2702 1382/1382/2701 1423/1423/56 +f 1423/1423/56 1382/1382/2701 1380/1380/56 +f 1425/1425/2712 1426/1426/2713 1427/1427/2714 +f 1425/1425/2712 1427/1427/2714 1416/1416/2704 +f 1425/1425/2712 1428/1428/2715 1426/1426/2713 +f 1412/1412/2698 1428/1428/2715 1425/1425/2712 +f 1416/1416/2704 1427/1427/2714 1415/1415/2703 +f 1412/1412/2698 1413/1413/2700 1428/1428/2715 +f 1429/1429/2716 1430/1430/2717 1431/1431/2718 +f 1431/1431/2718 1430/1430/2717 1432/1432/2719 +f 1431/1431/2718 1432/1432/2719 1433/1433/2720 +f 1431/1431/2718 1433/1433/2720 1434/1434/2721 +f 1434/1434/2721 1433/1433/2720 1435/1435/2722 +f 1411/1411/2723 1436/1436/2724 1437/1437/2725 +f 1438/1438/2726 1439/1439/2727 1440/1440/2728 +f 1441/1441/2729 1438/1438/2726 1442/1442/2730 +f 1442/1442/2730 1438/1438/2726 1440/1440/2728 +f 1442/1442/2730 1443/1443/2731 1441/1441/2729 +f 1442/1442/2730 1444/1444/2732 1445/1445/2733 +f 1445/1445/2733 1443/1443/2731 1442/1442/2730 +f 1444/1444/2732 1446/1446/2734 1445/1445/2733 +f 1447/1447/2735 1445/1445/2733 1446/1446/2734 +f 1448/1448/2736 1447/1447/2735 1446/1446/2734 +f 1448/1448/2736 1449/1449/2737 1447/1447/2735 +f 1450/1450/2738 1449/1449/2737 1448/1448/2736 +f 1450/1450/2738 1451/1451/2739 1449/1449/2737 +f 1452/1452/2740 1451/1451/2739 1450/1450/2738 +f 1452/1452/2740 1453/1453/2741 1451/1451/2739 +f 1452/1452/2740 1454/1454/2742 1453/1453/2741 +f 1436/1436/2724 1455/1455/2743 1452/1452/2740 +f 1452/1452/2740 1455/1455/2743 1454/1454/2742 +f 1456/1456/2744 1455/1455/2743 1436/1436/2724 +f 1411/1411/2723 1456/1456/2744 1436/1436/2724 +f 1409/1409/2745 1411/1411/2723 1437/1437/2725 +f 1409/1409/2745 1437/1437/2725 1457/1457/2746 +f 1457/1457/2746 1405/1405/2691 1409/1409/2745 +f 1458/1458/2747 1405/1405/2691 1457/1457/2746 +f 1458/1458/2747 1406/1406/2692 1405/1405/2691 +f 1459/1459/2748 1460/1460/2749 1406/1406/2692 +f 1459/1459/2748 1406/1406/2692 1458/1458/2747 +f 1367/1367/2750 1460/1460/2750 1459/1459/2750 +f 1367/1367/2655 1459/1459/2748 1366/1366/2654 +f 1461/1461/2751 1366/1366/2654 1459/1459/2748 +f 1461/1461/2751 1368/1368/2656 1366/1366/2654 +f 1368/1368/2656 1461/1461/2751 1355/1355/2643 +f 1355/1355/2643 1461/1461/2751 1462/1462/2752 +f 1355/1355/2643 1462/1462/2752 1356/1356/2644 +f 1462/1462/2752 1435/1435/2722 1356/1356/2644 +f 1434/1434/2721 1435/1435/2722 1462/1462/2752 +f 1434/1434/2721 1462/1462/2752 1463/1463/2753 +f 1434/1434/2721 1463/1463/2753 1431/1431/2754 +f 1431/1431/2754 1463/1463/2753 1464/1464/2755 +f 1431/1431/2754 1464/1464/2755 1429/1429/2756 +f 1464/1464/2755 1465/1465/2757 1429/1429/2756 +f 1440/1440/2728 1465/1465/2757 1464/1464/2755 +f 1440/1440/2728 1439/1439/2727 1465/1465/2757 +f 1466/1466/2758 1467/1467/2759 1439/1439/2760 +f 1439/1439/2760 1467/1467/2759 1465/1465/2761 +f 1465/1465/2761 1467/1467/2759 1468/1468/2762 +f 1465/1465/2761 1468/1468/2762 1430/1430/2717 +f 1465/1465/2761 1430/1430/2717 1429/1429/2716 +f 1411/1411/2697 1410/1410/2696 1469/1469/2763 +f 1470/1470/2764 1456/1456/2765 1411/1411/2697 +f 1470/1470/2764 1411/1411/2697 1469/1469/2763 +f 1456/1456/2765 1470/1470/2764 1471/1471/2766 +f 1471/1471/2766 1455/1455/2767 1456/1456/2765 +f 1455/1455/2767 1471/1471/2766 1472/1472/2768 +f 1437/1437/2725 1473/1473/2769 1474/1474/2770 +f 1437/1437/2725 1474/1474/2770 1457/1457/2746 +f 1457/1457/2746 1474/1474/2770 1475/1475/2771 +f 1457/1457/2746 1475/1475/2771 1458/1458/2747 +f 1458/1458/2747 1475/1475/2771 1476/1476/2772 +f 1458/1458/2747 1476/1476/2772 1459/1459/2748 +f 1459/1459/2748 1476/1476/2772 1477/1477/2773 +f 1459/1459/2748 1477/1477/2773 1461/1461/2751 +f 1461/1461/2751 1477/1477/2773 1478/1478/2774 +f 1461/1461/2751 1478/1478/2774 1462/1462/2752 +f 1462/1462/2752 1478/1478/2774 1479/1479/2775 +f 1462/1462/2752 1479/1479/2775 1463/1463/2753 +f 1463/1463/2753 1479/1479/2775 1480/1480/2776 +f 1463/1463/2753 1480/1480/2776 1464/1464/2755 +f 1464/1464/2755 1480/1480/2776 1481/1481/2777 +f 1464/1464/2755 1481/1481/2777 1440/1440/2728 +f 1440/1440/2728 1481/1481/2777 1482/1482/2778 +f 1440/1440/2728 1482/1482/2778 1442/1442/2730 +f 1442/1442/2730 1482/1482/2778 1483/1483/2779 +f 1442/1442/2730 1483/1483/2779 1444/1444/2732 +f 1444/1444/2732 1483/1483/2779 1446/1446/2734 +f 1446/1446/2734 1483/1483/2779 1484/1484/2780 +f 1446/1446/2734 1484/1484/2780 1485/1485/2781 +f 1446/1446/2734 1485/1485/2781 1448/1448/2736 +f 1448/1448/2736 1485/1485/2781 1450/1450/2738 +f 1450/1450/2738 1485/1485/2781 1486/1486/2782 +f 1450/1450/2738 1486/1486/2782 1452/1452/2740 +f 1452/1452/2740 1486/1486/2782 1487/1487/2783 +f 1452/1452/2740 1487/1487/2783 1436/1436/2724 +f 1436/1436/2724 1487/1487/2783 1473/1473/2769 +f 1436/1436/2724 1473/1473/2769 1437/1437/2725 +f 1389/1389/2784 1488/1488/2785 1489/1489/2786 +f 1389/1389/2784 1489/1489/2786 1393/1393/2787 +f 1393/1393/2787 1489/1489/2786 1391/1391/2788 +f 1391/1391/2788 1489/1489/2786 1490/1490/2789 +f 1391/1391/2788 1490/1490/2789 1491/1491/2790 +f 1391/1391/2788 1491/1491/2790 1401/1401/2791 +f 1401/1401/2791 1491/1491/2790 1397/1397/2792 +f 1491/1491/2790 1492/1492/2793 1397/1397/2792 +f 1397/1397/2792 1492/1492/2793 1400/1400/2794 +f 1492/1492/2793 1493/1493/2795 1400/1400/2794 +f 1400/1400/2794 1493/1493/2795 1399/1399/2796 +f 1399/1399/2796 1493/1493/2795 1494/1494/2797 +f 1399/1399/2796 1494/1494/2797 1394/1394/2798 +f 1494/1494/2797 1495/1495/2799 1394/1394/2798 +f 1394/1394/2798 1495/1495/2799 1387/1387/2800 +f 1495/1495/2799 1496/1496/2801 1387/1387/2800 +f 1387/1387/2800 1496/1496/2801 1386/1386/2802 +f 1386/1386/2802 1496/1496/2801 1497/1497/2803 +f 1386/1386/2802 1497/1497/2803 1385/1385/2804 +f 1497/1497/2803 1498/1498/2805 1385/1385/2804 +f 1385/1385/2804 1498/1498/2805 1384/1384/2806 +f 1384/1384/2806 1498/1498/2805 1499/1499/2807 +f 1384/1384/2806 1499/1499/2807 1388/1388/2808 +f 1499/1499/2807 1500/1500/2809 1388/1388/2808 +f 1388/1388/2808 1500/1500/2809 1396/1396/2810 +f 1396/1396/2810 1500/1500/2809 1403/1403/2811 +f 1500/1500/2809 1501/1501/2812 1403/1403/2811 +f 1403/1403/2811 1501/1501/2812 1389/1389/2784 +f 1501/1501/2812 1488/1488/2785 1389/1389/2784 +f 1424/1424/2813 1502/1502/2814 1503/1503/2815 +f 1424/1424/2813 1503/1503/2815 1423/1423/2816 +f 1423/1423/2816 1503/1503/2815 1504/1504/2817 +f 1423/1423/2816 1504/1504/2817 1414/1414/2818 +f 1414/1414/2818 1504/1504/2817 1505/1505/2819 +f 1414/1414/2818 1505/1505/2819 1416/1416/2820 +f 1416/1416/2820 1505/1505/2819 1506/1506/2821 +f 1416/1416/2820 1506/1506/2821 1425/1425/2822 +f 1425/1425/2822 1506/1506/2821 1507/1507/2823 +f 1425/1425/2822 1507/1507/2823 1412/1412/2824 +f 1412/1412/2824 1507/1507/2823 1508/1508/2825 +f 1412/1412/2824 1508/1508/2825 1509/1509/2826 +f 1412/1412/2824 1509/1509/2826 1417/1417/2827 +f 1417/1417/2827 1509/1509/2826 1510/1510/2828 +f 1417/1417/2827 1510/1510/2828 1419/1419/2829 +f 1419/1419/2829 1510/1510/2828 1511/1511/2830 +f 1419/1419/2829 1511/1511/2830 1418/1418/2831 +f 1418/1418/2831 1511/1511/2830 1512/1512/2832 +f 1418/1418/2831 1512/1512/2832 1421/1421/2833 +f 1421/1421/2833 1512/1512/2832 1513/1513/2834 +f 1421/1421/2833 1513/1513/2834 1420/1420/2835 +f 1420/1420/2835 1513/1513/2834 1514/1514/2836 +f 1420/1420/2835 1514/1514/2836 1515/1515/2837 +f 1420/1420/2835 1515/1515/2837 1422/1422/2838 +f 1422/1422/2838 1515/1515/2837 1502/1502/2814 +f 1422/1422/2838 1502/1502/2814 1424/1424/2813 +f 1466/1466/2758 1439/1439/2760 1516/1516/2839 +f 1516/1516/2839 1439/1439/2760 1438/1438/2840 +f 1516/1516/2839 1438/1438/2840 1517/1517/2841 +f 1517/1517/2841 1438/1438/2840 1441/1441/2842 +f 1517/1517/2841 1441/1441/2842 1518/1518/2843 +f 1518/1518/2843 1441/1441/2842 1519/1519/2844 +f 1520/1520/2845 1521/1521/2846 1453/1453/2847 +f 1520/1520/2845 1454/1454/2848 1522/1522/2849 +f 1522/1522/2849 1454/1454/2850 1523/1523/2851 +f 1520/1520/2845 1453/1453/2847 1454/1454/2848 +f 1523/1523/2851 1454/1454/2850 1455/1455/2767 +f 1523/1523/2851 1455/1455/2767 1472/1472/2768 +f 1518/1518/2843 1519/1519/2852 1524/1524/2853 +f 1427/1427/2714 1516/1516/2839 1525/1525/2854 +f 1427/1427/2714 1525/1525/2854 1415/1415/2703 +f 1525/1525/2854 1524/1524/2855 1415/1415/2703 +f 1427/1427/2714 1467/1467/2759 1516/1516/2839 +f 1467/1467/2759 1466/1466/2758 1516/1516/2839 +f 1516/1516/2839 1517/1517/2841 1525/1525/2854 +f 1525/1525/2854 1517/1517/2841 1524/1524/2853 +f 1524/1524/2853 1517/1517/2841 1518/1518/2843 +f 1430/1430/2717 1468/1468/2762 1426/1426/2713 +f 1468/1468/2762 1467/1467/2759 1426/1426/2713 +f 1426/1426/2713 1467/1467/2759 1427/1427/2714 +f 1426/1426/2713 1428/1428/2715 1430/1430/2717 +f 1428/1428/2715 1432/1432/2719 1430/1430/2717 +f 1433/1433/2720 1432/1432/2719 1413/1413/2856 +f 1433/1433/2720 1413/1413/2856 1356/1356/2857 +f 1433/1433/2720 1356/1356/2857 1435/1435/2722 +f 1432/1432/2719 1428/1428/2715 1413/1413/2856 +f 1520/1520/2845 1526/1526/2858 1521/1521/2846 +f 1472/1472/2768 1527/1527/2859 1523/1523/2851 +f 1523/1523/2851 1527/1527/2859 1522/1522/2849 +f 1520/1520/2845 1522/1522/2849 1526/1526/2858 +f 1522/1522/2849 1528/1528/2860 1526/1526/2858 +f 1527/1527/2859 1528/1528/2860 1522/1522/2849 +f 1526/1526/2858 1528/1528/2860 1398/1398/2685 +f 1528/1528/2860 1527/1527/2859 1402/1402/2688 +f 1528/1528/2860 1402/1402/2688 1398/1398/2685 +f 1527/1527/2859 1395/1395/2681 1402/1402/2688 +f 1472/1472/2768 1471/1471/2766 1527/1527/2859 +f 1527/1527/2859 1471/1471/2766 1395/1395/2681 +f 1471/1471/2766 1470/1470/2764 1395/1395/2681 +f 1392/1392/2679 1469/1469/2861 1410/1410/2862 +f 1392/1392/2679 1410/1410/2862 1390/1390/2676 +f 1395/1395/2681 1470/1470/2764 1469/1469/2861 +f 1395/1395/2681 1469/1469/2861 1392/1392/2679 +f 1404/1404/2690 1406/1406/2692 1460/1460/2863 +f 1404/1404/2690 1460/1460/2863 1407/1407/2693 +f 1407/1407/2693 1460/1460/2863 1367/1367/2864 +f 1407/1407/2693 1367/1367/2864 1408/1408/2865 +f 1408/1408/2865 1367/1367/2864 1390/1390/2676 +f 1408/1408/2865 1390/1390/2676 1410/1410/2862 +f 1371/1371/2659 1357/1357/2645 1353/1353/2641 +f 1349/1349/2637 1348/1348/2636 1352/1352/2640 +f 325/325/145 327/327/145 322/322/145 +f 322/322/145 329/329/145 320/320/145 +f 320/320/145 329/329/145 298/298/145 +f 320/320/145 298/298/145 319/319/145 +f 319/319/145 300/300/145 316/316/145 +f 316/316/145 300/300/145 302/302/145 +f 316/316/145 302/302/145 314/314/145 +f 314/314/145 305/305/145 307/307/145 +f 327/327/145 329/329/145 322/322/145 +f 314/314/145 307/307/145 313/313/145 +f 298/298/145 300/300/145 319/319/145 +f 302/302/145 305/305/145 314/314/145 +f 313/313/145 307/307/145 311/311/145 +f 311/311/145 307/307/145 309/309/145 +f 508/508/56 513/513/56 507/507/56 +f 482/482/56 504/504/56 507/507/56 +f 508/508/56 511/511/56 513/513/56 +f 482/482/56 503/503/56 504/504/56 +f 485/485/56 486/486/56 503/503/56 +f 486/486/56 500/500/56 503/503/56 +f 503/503/56 482/482/56 485/485/56 +f 486/486/56 499/499/56 500/500/56 +f 486/486/56 489/489/56 499/499/56 +f 497/497/56 499/499/56 489/489/56 +f 489/489/56 491/491/56 497/497/56 +f 491/491/56 495/495/56 497/497/56 +f 491/491/56 493/493/56 495/495/56 +f 507/507/56 513/513/56 482/482/56 +f 164/164/2866 193/193/2867 197/197/2868 +f 193/193/2867 172/172/2869 197/197/2868 +f 172/172/2869 194/194/2870 197/197/2868 +f 164/164/2866 173/173/2871 193/193/2867 +f 195/195/387 183/183/388 199/199/2872 +f 185/185/2873 199/199/2872 183/183/388 +f 196/196/392 199/199/2872 185/185/2873 +f 162/162/391 186/186/2874 198/198/2875 +f 162/162/391 199/199/2872 196/196/392 +f 262/262/2876 218/218/2877 244/244/2878 +f 216/216/2879 218/218/2877 262/262/2876 +f 262/262/2876 244/244/2878 272/272/2880 +f 272/272/2880 244/244/2878 240/240/2881 +f 266/266/2882 243/243/2883 297/297/2884 +f 265/265/560 266/266/2882 297/297/2884 +f 199/199/2872 162/162/391 198/198/2875 +f 265/265/560 297/297/2884 219/219/2885 +f 1479/1479/2634 1481/1481/2634 1480/1480/2886 +f 1479/1479/2634 1485/1485/2634 1481/1481/2634 +f 1482/1482/2887 1481/1481/2634 1483/1483/2634 +f 1483/1483/2634 1481/1481/2634 1485/1485/2634 +f 1479/1479/2634 1478/1478/2888 1477/1477/2634 +f 1485/1485/2634 1484/1484/2889 1483/1483/2634 +f 1476/1476/2890 1474/1474/2634 1477/1477/2634 +f 1486/1486/2634 1485/1485/2634 1477/1477/2634 +f 212/212/558 265/265/560 219/219/2885 +f 1485/1485/2634 1479/1479/2634 1477/1477/2634 +f 1474/1474/2634 1486/1486/2634 1477/1477/2634 +f 1486/1486/2634 1474/1474/2634 1487/1487/2891 +f 1475/1475/2892 1474/1474/2634 1476/1476/2890 +f 1487/1487/2891 1474/1474/2634 1473/1473/2893 +f 1492/1492/145 1491/1491/145 1493/1493/145 +f 1493/1493/145 1491/1491/145 1490/1490/145 +f 1493/1493/145 1490/1490/145 1489/1489/145 +f 1494/1494/145 1493/1493/145 1489/1489/145 +f 1494/1494/145 1489/1489/145 1488/1488/145 +f 1494/1494/145 1488/1488/145 1495/1495/145 +f 1488/1488/145 1496/1496/145 1495/1495/145 +f 1488/1488/145 1501/1501/145 1496/1496/145 +f 1501/1501/145 1500/1500/145 1496/1496/145 +f 1500/1500/145 1497/1497/145 1496/1496/145 +f 1500/1500/145 1498/1498/145 1497/1497/145 +f 1500/1500/145 1499/1499/145 1498/1498/145 +f 1505/1505/56 1504/1504/56 1503/1503/56 +f 1503/1503/56 1511/1511/56 1505/1505/56 +f 1507/1507/56 1506/1506/56 1505/1505/56 +f 1511/1511/56 1510/1510/56 1509/1509/56 +f 1502/1502/56 1515/1515/56 1503/1503/56 +f 1507/1507/56 1511/1511/56 1508/1508/56 +f 1514/1514/56 1513/1513/56 1515/1515/56 +f 1511/1511/56 1509/1509/56 1508/1508/56 +f 1511/1511/56 1507/1507/56 1505/1505/56 +f 1513/1513/56 1503/1503/56 1515/1515/56 +f 1511/1511/56 1513/1513/56 1512/1512/56 +f 1511/1511/56 1503/1503/56 1513/1513/56 +f 1443/1443/2894 1519/1519/2844 1441/1441/2842 +f 1443/1443/2894 1445/1445/2895 1519/1519/2844 +f 1449/1449/2896 1521/1521/2846 1519/1519/2844 +f 1445/1445/2895 1447/1447/2897 1519/1519/2844 +f 1524/1524/2898 1398/1398/2899 1415/1415/2900 +f 1382/1382/2901 1398/1398/2899 1383/1383/2902 +f 1447/1447/2897 1449/1449/2896 1519/1519/2844 +f 1398/1398/2899 1382/1382/2901 1415/1415/2900 +f 1449/1449/2896 1451/1451/2903 1521/1521/2846 +f 1398/1398/2899 1524/1524/2898 1526/1526/2904 +f 1524/1524/2898 1519/1519/2844 1526/1526/2904 +f 1519/1519/2844 1521/1521/2846 1526/1526/2904 +f 1453/1453/2847 1521/1521/2846 1451/1451/2903 +f 1529/1529/2905 1530/1530/2906 1531/1531/2907 +f 1530/1530/2906 1532/1532/2908 1531/1531/2907 +f 1533/1533/2909 1534/1534/2910 1535/1535/2911 +f 1535/1535/2911 1534/1534/2910 1536/1536/2912 +f 1532/1532/2913 1537/1537/2914 1538/1538/2915 +f 1532/1532/2913 1538/1538/2915 1539/1539/2916 +f 1529/1529/2917 1531/1531/2918 1540/1540/2919 +f 1540/1540/2919 1531/1531/2918 1541/1541/2920 +f 1540/1540/2919 1541/1541/2920 1542/1542/2921 +f 1542/1542/2921 1541/1541/2920 1543/1543/2922 +f 1542/1542/2921 1543/1543/2922 1544/1544/2923 +f 1544/1544/2923 1543/1543/2922 1545/1545/2924 +f 1533/1533/2925 1546/1546/2926 1547/1547/2927 +f 1547/1547/2927 1546/1546/2926 1548/1548/2928 +f 1536/1536/2929 1534/1534/2930 1549/1549/2931 +f 1549/1549/2931 1534/1534/2930 1550/1550/2932 +f 1549/1549/2931 1550/1550/2932 1551/1551/2933 +f 1551/1551/2933 1550/1550/2932 1552/1552/2934 +f 1551/1551/2933 1552/1552/2934 1553/1553/2935 +f 1553/1553/2935 1552/1552/2934 1554/1554/2936 +f 1555/1555/2937 1550/1550/2938 1547/1547/2939 +f 1556/1556/2940 1557/1557/2941 1558/1558/2941 +f 1541/1541/2942 1559/1559/2943 1543/1543/2944 +f 1543/1543/2944 1559/1559/2943 1560/1560/2945 +f 1560/1560/2945 1548/1548/2946 1543/1543/2944 +f 1547/1547/2939 1558/1558/2941 1555/1555/2937 +f 1550/1550/2938 1555/1555/2937 1561/1561/2939 +f 1550/1550/2938 1561/1561/2939 1552/1552/2947 +f 1562/1562/2948 1539/1539/2949 1538/1538/2950 +f 1560/1560/2945 1556/1556/2940 1548/1548/2946 +f 1548/1548/2946 1556/1556/2940 1547/1547/2939 +f 1556/1556/2940 1558/1558/2941 1547/1547/2939 +f 1552/1552/2947 1561/1561/2939 1557/1557/2941 +f 1538/1538/2950 1552/1552/2947 1557/1557/2941 +f 1562/1562/2948 1559/1559/2943 1541/1541/2942 +f 1556/1556/2940 1562/1562/2948 1557/1557/2941 +f 1557/1557/2941 1562/1562/2948 1538/1538/2950 +f 1562/1562/2948 1541/1541/2942 1539/1539/2949 +f 1553/1553/2951 1554/1554/2952 1537/1537/2953 +f 1537/1537/2953 1563/1563/2954 1553/1553/2951 +f 1546/1546/2955 1564/1564/2956 1545/1545/2957 +f 1545/1545/2957 1564/1564/2956 1565/1565/2958 +f 1545/1545/2957 1565/1565/2958 1544/1544/2959 +f 1551/1551/2960 1566/1566/2961 1567/1567/2962 +f 1566/1566/2961 1568/1568/2963 1569/1569/2961 +f 1570/1570/2964 1569/1569/2961 1571/1571/2965 +f 1566/1566/2961 1551/1551/2960 1568/1568/2963 +f 1570/1570/2964 1571/1571/2965 1572/1572/2963 +f 1566/1566/2961 1569/1569/2961 1570/1570/2964 +f 1549/1549/2963 1551/1551/2960 1567/1567/2962 +f 1567/1567/2962 1573/1573/2966 1549/1549/2963 +f 1572/1572/2963 1573/1573/2966 1567/1567/2962 +f 1571/1571/2965 1574/1574/2966 1572/1572/2963 +f 1572/1572/2963 1574/1574/2966 1573/1573/2966 +f 1535/1535/2967 1573/1573/2968 1574/1574/2969 +f 1535/1535/2967 1574/1574/2969 1575/1575/2970 +f 1575/1575/2970 1574/1574/2969 1571/1571/2971 +f 1575/1575/2970 1571/1571/2971 1576/1576/2972 +f 1576/1576/2973 1571/1571/2974 1569/1569/2975 +f 1576/1576/2973 1569/1569/2975 1577/1577/2976 +f 1577/1577/2977 1569/1569/2978 1563/1563/2979 +f 1568/1568/2980 1563/1563/2979 1569/1569/2978 +f 1557/1557/2981 1566/1566/2981 1570/1570/2981 +f 1557/1557/2982 1570/1570/2982 1558/1558/2982 +f 1558/1558/2983 1570/1570/2983 1572/1572/2983 +f 1558/1558/2984 1572/1572/2984 1555/1555/2984 +f 1555/1555/2985 1572/1572/2985 1567/1567/2985 +f 1555/1555/2986 1567/1567/2986 1561/1561/2986 +f 1561/1561/2987 1567/1567/2987 1566/1566/2987 +f 1561/1561/2988 1566/1566/2988 1557/1557/2988 +f 1578/1578/2989 1579/1579/2962 1580/1580/2990 +f 1580/1580/2990 1581/1581/2991 1582/1582/2992 +f 1583/1583/2993 1542/1542/2962 1584/1584/2961 +f 1540/1540/2994 1542/1542/2962 1583/1583/2993 +f 1582/1582/2992 1581/1581/2991 1585/1585/2995 +f 1580/1580/2990 1579/1579/2962 1581/1581/2991 +f 1584/1584/2961 1586/1586/2996 1578/1578/2989 +f 1578/1578/2989 1586/1586/2996 1587/1587/2989 +f 1582/1582/2992 1585/1585/2995 1583/1583/2993 +f 1583/1583/2993 1585/1585/2995 1540/1540/2994 +f 1578/1578/2989 1587/1587/2989 1579/1579/2962 +f 1584/1584/2961 1542/1542/2962 1586/1586/2996 +f 1530/1530/2997 1585/1585/2998 1581/1581/2999 +f 1586/1586/3000 1588/1588/3001 1587/1587/3002 +f 1587/1587/3003 1588/1588/3004 1579/1579/3005 +f 1579/1579/3005 1588/1588/3004 1589/1589/3006 +f 1579/1579/3007 1589/1589/3008 1581/1581/2999 +f 1581/1581/2999 1589/1589/3008 1530/1530/2997 +f 1586/1586/3000 1564/1564/3009 1588/1588/3001 +f 1565/1565/3010 1564/1564/3009 1586/1586/3000 +f 1562/1562/3011 1582/1582/3012 1559/1559/3013 +f 1559/1559/3013 1582/1582/3012 1583/1583/3014 +f 1559/1559/3015 1583/1583/3016 1560/1560/3017 +f 1560/1560/3017 1583/1583/3016 1584/1584/3018 +f 1560/1560/3019 1584/1584/3020 1556/1556/3021 +f 1556/1556/3021 1584/1584/3020 1578/1578/3022 +f 1556/1556/3023 1578/1578/3024 1580/1580/3025 +f 1556/1556/3023 1580/1580/3025 1562/1562/3026 +f 1562/1562/3027 1580/1580/3027 1582/1582/3027 +f 1529/1529/3028 1540/1540/3029 1585/1585/2998 +f 1529/1529/3028 1585/1585/2998 1530/1530/2997 +f 1586/1586/3000 1542/1542/3030 1565/1565/3010 +f 1542/1542/3031 1544/1544/3031 1565/1565/3031 +f 1536/1536/3032 1549/1549/3032 1573/1573/3032 +f 1536/1536/3033 1573/1573/2968 1535/1535/2967 +f 1568/1568/2980 1553/1553/3034 1563/1563/2979 +f 1551/1551/3035 1553/1553/3034 1568/1568/2980 +f 1539/1539/2916 1531/1531/3036 1532/1532/2913 +f 1541/1541/3037 1531/1531/3036 1539/1539/2916 +f 1554/1554/3038 1552/1552/3039 1538/1538/3040 +f 1554/1554/3038 1538/1538/3040 1537/1537/3041 +f 1545/1545/2924 1543/1543/2922 1548/1548/3042 +f 1545/1545/3043 1548/1548/2928 1546/1546/2926 +f 1547/1547/3044 1550/1550/3045 1534/1534/3046 +f 1547/1547/3044 1534/1534/3046 1533/1533/3047 +f 1564/1564/3048 1546/1546/3049 1588/1588/3050 +f 1532/1532/3051 1530/1530/3052 1589/1589/3053 +f 1589/1589/3053 1588/1588/3050 1575/1575/3054 +f 1576/1576/3055 1577/1577/3056 1589/1589/3053 +f 1588/1588/3050 1546/1546/3049 1575/1575/3054 +f 1533/1533/3057 1535/1535/3058 1575/1575/3054 +f 1532/1532/3051 1589/1589/3053 1577/1577/3056 +f 1546/1546/3049 1533/1533/3057 1575/1575/3054 +f 1537/1537/3059 1532/1532/3051 1577/1577/3056 +f 1575/1575/3054 1576/1576/3055 1589/1589/3053 +f 1577/1577/3056 1563/1563/3060 1537/1537/3059 +f 1590/1590/3061 1591/1591/3062 1592/1592/3063 +f 1593/1593/3064 1594/1594/3065 1595/1595/3066 +f 1595/1595/3066 1594/1594/3065 1596/1596/3067 +f 1593/1593/3064 1597/1597/3068 1594/1594/3065 +f 1598/1598/3069 1597/1597/3068 1593/1593/3064 +f 1599/1599/3070 1600/1600/3071 1593/1593/3064 +f 1593/1593/3064 1600/1600/3071 1598/1598/3069 +f 1591/1591/3062 1600/1600/3071 1592/1592/3063 +f 1592/1592/3063 1600/1600/3071 1599/1599/3070 +f 1592/1592/3063 1595/1595/3072 1590/1590/3061 +f 1601/1601/3073 1602/1602/3074 1603/1603/3075 +f 1604/1604/3076 1601/1601/3073 1603/1603/3075 +f 1605/1605/3077 1606/1606/3078 1607/1607/3079 +f 1606/1606/3080 1608/1608/3081 1607/1607/3082 +f 1607/1607/3082 1608/1608/3081 1609/1609/3083 +f 1608/1608/3084 1610/1610/3085 1609/1609/3086 +f 1609/1609/3086 1610/1610/3085 1602/1602/3087 +f 1602/1602/3088 1610/1610/3089 1611/1611/3090 +f 1602/1602/3088 1611/1611/3090 1612/1612/3091 +f 1612/1612/3092 1611/1611/3093 1613/1613/3094 +f 1613/1613/3094 1611/1611/3093 1614/1614/3095 +f 1613/1613/3096 1614/1614/3097 1605/1605/3098 +f 1614/1614/3097 1615/1615/3099 1605/1605/3098 +f 1605/1605/3077 1615/1615/3100 1606/1606/3078 +f 1615/1615/3101 1616/1616/3102 1617/1617/3103 +f 1615/1615/3101 1617/1617/3103 1606/1606/3104 +f 1610/1610/3105 1618/1618/3106 1611/1611/3107 +f 1610/1610/3105 1619/1619/3108 1618/1618/3106 +f 1608/1608/3109 1619/1619/3108 1610/1610/3105 +f 1606/1606/3104 1617/1617/3103 1620/1620/3110 +f 1611/1611/3107 1618/1618/3106 1621/1621/3111 +f 1608/1608/3109 1620/1620/3110 1619/1619/3108 +f 1606/1606/3104 1620/1620/3110 1608/1608/3109 +f 1614/1614/3112 1622/1622/3113 1623/1623/3114 +f 1614/1614/3112 1623/1623/3114 1615/1615/3101 +f 1615/1615/3101 1623/1623/3114 1616/1616/3102 +f 1611/1611/3107 1621/1621/3111 1622/1622/3113 +f 1611/1611/3107 1622/1622/3113 1614/1614/3112 +f 1594/1594/3115 1617/1617/3116 1616/1616/3117 +f 1617/1617/3118 1594/1594/3119 1620/1620/3120 +f 1620/1620/3120 1594/1594/3119 1597/1597/3121 +f 1597/1597/3122 1598/1598/3123 1620/1620/3124 +f 1620/1620/3124 1598/1598/3123 1619/1619/3125 +f 1598/1598/3126 1600/1600/3126 1619/1619/3126 +f 1619/1619/3127 1600/1600/3128 1618/1618/3129 +f 1618/1618/3129 1600/1600/3128 1591/1591/3130 +f 1618/1618/3129 1591/1591/3130 1621/1621/3131 +f 1591/1591/3130 1590/1590/3132 1621/1621/3131 +f 1621/1621/3131 1590/1590/3132 1622/1622/3133 +f 1590/1590/3134 1595/1595/3135 1622/1622/3136 +f 1622/1622/3136 1595/1595/3135 1623/1623/3137 +f 1623/1623/3138 1595/1595/3139 1616/1616/3140 +f 1595/1595/3139 1596/1596/3141 1616/1616/3140 +f 1616/1616/3117 1596/1596/3142 1594/1594/3115 +f 1592/1592/3143 1599/1599/3144 1624/1624/3145 +f 1624/1624/3145 1599/1599/3144 1625/1625/3146 +f 1595/1595/3147 1592/1592/3147 1626/1626/3147 +f 1626/1626/3148 1592/1592/3148 1624/1624/3148 +f 1593/1593/3149 1595/1595/3150 1627/1627/3151 +f 1627/1627/3151 1595/1595/3150 1626/1626/3152 +f 1599/1599/3153 1593/1593/3154 1625/1625/3155 +f 1625/1625/3155 1593/1593/3154 1627/1627/3156 +f 1625/1625/2964 1627/1627/2964 1626/1626/2964 +f 1625/1625/2964 1626/1626/2964 1624/1624/2964 +f 1605/1605/3098 1604/1604/3157 1613/1613/3096 +f 1613/1613/3158 1604/1604/3159 1603/1603/3160 +f 1613/1613/3158 1603/1603/3160 1612/1612/3161 +f 1612/1612/3162 1603/1603/3162 1602/1602/3162 +f 1609/1609/3163 1602/1602/3074 1601/1601/3073 +f 1609/1609/3083 1601/1601/3164 1607/1607/3082 +f 1607/1607/3165 1601/1601/3166 1604/1604/3167 +f 1607/1607/3165 1604/1604/3167 1605/1605/3168 +f 1628/1628/3169 1629/1629/3170 1630/1630/3171 +f 1630/1630/3171 1631/1631/3172 1628/1628/3169 +f 1632/1632/3173 1633/1633/3174 1634/1634/3175 +f 1635/1635/3176 1636/1636/3177 1637/1637/3178 +f 1634/1634/3175 1633/1633/3174 1635/1635/3176 +f 1637/1637/3178 1638/1638/3179 1631/1631/3172 +f 1637/1637/3178 1631/1631/3172 1630/1630/3171 +f 1636/1636/3177 1638/1638/3179 1637/1637/3178 +f 1634/1634/3175 1635/1635/3176 1637/1637/3178 +f 1630/1630/3171 1629/1629/3170 1634/1634/3175 +f 1634/1634/3175 1629/1629/3170 1632/1632/3173 +f 1639/1639/3180 1640/1640/3181 1641/1641/3182 +f 1641/1641/3182 1642/1642/3183 1639/1639/3180 +f 1641/1641/3184 1643/1643/3185 1644/1644/3186 +f 1643/1643/3185 1645/1645/3187 1644/1644/3186 +f 1645/1645/3188 1646/1646/3188 1644/1644/3188 +f 1644/1644/3189 1646/1646/3190 1647/1647/3191 +f 1644/1644/3189 1647/1647/3191 1648/1648/3192 +f 1647/1647/3193 1649/1649/3193 1648/1648/3193 +f 1648/1648/3194 1649/1649/3195 1650/1650/3196 +f 1650/1650/3196 1649/1649/3195 1651/1651/3197 +f 1650/1650/3198 1651/1651/3199 1652/1652/3200 +f 1652/1652/3200 1651/1651/3199 1653/1653/3201 +f 1652/1652/3202 1653/1653/3203 1643/1643/3204 +f 1652/1652/3202 1643/1643/3204 1641/1641/3205 +f 1645/1645/3206 1654/1654/3207 1655/1655/3208 +f 1645/1645/3206 1655/1655/3208 1646/1646/3209 +f 1653/1653/3210 1656/1656/3211 1645/1645/3206 +f 1645/1645/3206 1656/1656/3211 1654/1654/3207 +f 1649/1649/3212 1657/1657/3213 1658/1658/3214 +f 1649/1649/3212 1658/1658/3214 1651/1651/3215 +f 1647/1647/3216 1657/1657/3213 1649/1649/3212 +f 1651/1651/3215 1658/1658/3214 1659/1659/3217 +f 1647/1647/3216 1660/1660/3218 1657/1657/3213 +f 1646/1646/3209 1660/1660/3218 1647/1647/3216 +f 1646/1646/3209 1655/1655/3208 1660/1660/3218 +f 1653/1653/3210 1661/1661/3219 1656/1656/3211 +f 1651/1651/3215 1659/1659/3217 1653/1653/3210 +f 1653/1653/3210 1659/1659/3217 1661/1661/3219 +f 1628/1628/3220 1631/1631/3221 1654/1654/3222 +f 1654/1654/3222 1631/1631/3221 1655/1655/3223 +f 1655/1655/3224 1631/1631/3225 1660/1660/3226 +f 1660/1660/3226 1631/1631/3225 1638/1638/3227 +f 1638/1638/3228 1636/1636/3229 1660/1660/3230 +f 1660/1660/3230 1636/1636/3229 1657/1657/3231 +f 1657/1657/3232 1636/1636/3233 1635/1635/3234 +f 1657/1657/3232 1635/1635/3234 1658/1658/3235 +f 1658/1658/3235 1635/1635/3234 1633/1633/3236 +f 1658/1658/3235 1633/1633/3236 1659/1659/3237 +f 1633/1633/3236 1632/1632/3238 1659/1659/3237 +f 1659/1659/3239 1632/1632/3240 1661/1661/3241 +f 1632/1632/3240 1629/1629/3242 1661/1661/3241 +f 1661/1661/3241 1629/1629/3242 1656/1656/3243 +f 1656/1656/3243 1629/1629/3242 1628/1628/3244 +f 1656/1656/3243 1628/1628/3244 1654/1654/3245 +f 1634/1634/3246 1637/1637/3246 1662/1662/3246 +f 1663/1663/3247 1634/1634/3247 1662/1662/3247 +f 1630/1630/3248 1634/1634/3248 1663/1663/3248 +f 1664/1664/3249 1630/1630/3249 1663/1663/3249 +f 1637/1637/3250 1630/1630/3250 1664/1664/3250 +f 1662/1662/3251 1637/1637/3251 1664/1664/3251 +f 1662/1662/2960 1664/1664/2960 1663/1663/2960 +f 1645/1645/3252 1643/1643/3252 1653/1653/3252 +f 1652/1652/3253 1641/1641/3253 1640/1640/3253 +f 1652/1652/3254 1640/1640/3255 1639/1639/3256 +f 1652/1652/3254 1639/1639/3256 1650/1650/3257 +f 1650/1650/3258 1639/1639/3259 1642/1642/3260 +f 1650/1650/3258 1642/1642/3260 1648/1648/3261 +f 1648/1648/3192 1642/1642/3262 1644/1644/3189 +f 1644/1644/3263 1642/1642/3183 1641/1641/3182 +f 775/775/3264 1025/1025/3265 778/778/3266 +f 778/778/3266 1025/1025/3265 1028/1028/3267 +f 780/780/3268 778/778/3266 1028/1028/3267 +f 993/993/145 992/992/145 986/986/145 +f 988/988/145 990/990/145 989/989/145 +f 991/991/145 990/990/145 988/988/145 +f 988/988/145 987/987/145 991/991/145 +f 987/987/145 992/992/145 991/991/145 +f 986/986/145 992/992/145 987/987/145 +f 1004/1004/145 1011/1011/145 1013/1013/145 +f 1005/1005/145 1003/1003/145 1007/1007/145 +f 1008/1008/145 1007/1007/145 1003/1003/145 +f 1013/1013/145 1003/1003/145 1004/1004/145 +f 1013/1013/145 1008/1008/145 1003/1003/145 +f 1011/1011/145 1012/1012/145 1013/1013/145 +f 1005/1005/145 1007/1007/145 1006/1006/145 +f 982/982/145 985/985/145 983/983/145 +f 982/982/145 977/977/145 985/985/145 +f 981/981/145 977/977/145 982/982/145 +f 981/981/145 976/976/145 977/977/145 +f 981/981/145 980/980/3269 976/976/145 +f 980/980/3269 978/978/3269 976/976/145 +f 979/979/3270 978/978/3269 980/980/3269 +f 1002/1002/145 1000/1000/145 1001/1001/145 +f 999/999/145 1000/1000/145 1002/1002/145 +f 999/999/145 995/995/145 1000/1000/145 +f 999/999/145 998/998/145 995/995/145 +f 998/998/145 996/996/145 995/995/145 +f 998/998/145 997/997/145 996/996/145 +f 843/843/3271 830/830/2635 829/829/3272 +f 794/794/3273 793/793/3273 925/925/3273 +f 830/830/2635 843/843/3271 841/841/3274 +f 830/830/2635 841/841/3274 831/831/2635 +f 840/840/3274 831/831/2635 841/841/3274 +f 840/840/3274 832/832/2635 831/831/2635 +f 840/840/3274 833/833/2635 832/832/2635 +f 839/839/2635 833/833/2635 840/840/3274 +f 839/839/2635 834/834/3274 833/833/2635 +f 834/834/3274 839/839/2635 835/835/3271 +f 839/839/2635 837/837/3271 836/836/3275 +f 839/839/2635 838/838/3276 837/837/3271 +f 841/841/3274 843/843/3271 842/842/3277 +f 835/835/3271 839/839/2635 836/836/3275 +f 821/821/56 794/794/56 925/925/56 +f 803/803/56 827/827/3278 828/828/56 +f 925/925/56 940/940/56 938/938/56 +f 936/936/56 925/925/56 938/938/56 +f 936/936/56 934/934/56 925/925/56 +f 925/925/56 803/803/56 822/822/56 +f 803/803/56 828/828/56 822/822/56 +f 934/934/56 930/930/56 925/925/56 +f 925/925/56 930/930/56 803/803/56 +f 930/930/56 934/934/56 932/932/56 +f 827/827/3278 803/803/56 802/802/3279 +f 821/821/56 925/925/56 822/822/56 +f 3600/1665/3280 3633/1666/3280 3598/1667/3280 +f 3338/1668/3281 3337/1669/3281 3336/1670/3281 +f 2140/1671/3282 2148/1672/3283 2112/1673/3284 +f 3385/1674/3285 3400/1675/3286 3401/1676/3287 +f 3860/1677/3288 3858/1678/3289 3867/1679/3289 +f 3625/1680/3290 3641/1681/3291 3622/1682/3292 +f 3868/1683/3293 3894/1684/3294 3893/1685/3295 +f 2973/1686/3296 2974/1687/3296 2976/1688/3296 +f 2482/1689/3297 2483/1690/3298 2256/1691/3299 +f 1902/1692/3300 1901/1693/3301 1990/1694/3302 +f 1814/1695/3303 1813/1696/3304 1815/1697/3305 +f 2288/1698/3306 2287/1699/3307 2289/1700/3308 +f 3081/1701/3309 3197/1702/3309 3082/1703/3309 +f 2795/1704/3310 2814/1705/3311 2828/1706/3312 +f 3691/1707/3313 3692/1708/3314 3690/1709/3315 +f 3665/1710/3316 3668/1711/3317 3655/1712/3318 +f 3282/1713/3319 3265/1714/3320 3283/1715/3321 +f 3876/1716/3289 3875/1717/3289 3846/1718/3289 +f 1745/1719/3322 1744/1720/3323 1779/1721/3324 +f 3288/1722/3325 3204/1723/3326 3207/1724/3327 +f 2877/1725/3328 2876/1726/3329 2878/1727/3330 +f 2776/1728/3331 2752/1729/3332 2777/1730/3333 +f 3651/1731/3334 3650/1732/3335 3660/1733/3336 +f 2144/1734/3337 2143/1735/3338 2142/1736/3339 +f 3612/1737/3280 3614/1738/3280 3622/1682/3280 +f 3522/1739/3340 3521/1740/3341 3533/1741/3342 +f 3741/1742/3343 3743/1743/3344 3714/1744/3345 +f 3388/1745/3346 3406/1746/3347 3427/1747/3348 +f 1811/1748/3349 1818/1749/3350 1820/1750/3351 +f 2997/1751/3352 3000/1752/3353 2998/1753/3354 +f 3163/1754/3355 3162/1755/3356 3141/1756/3357 +f 3774/1757/3358 3775/1758/3359 3781/1759/3360 +f 3211/1760/3361 3207/1724/3362 3203/1761/3362 +f 3531/1762/3363 3520/1763/3364 3519/1764/3365 +f 2060/1765/3366 2220/1766/3367 2062/1767/3368 +f 2369/1768/3369 2351/1769/3370 2367/1770/3371 +f 3795/1771/3372 3697/1772/3373 3793/1773/3374 +f 3299/1774/3375 3213/1775/3376 3297/1776/3377 +f 3475/1777/3378 3474/1778/3379 3476/1779/3380 +f 3621/1780/3381 3637/1781/3382 3623/1782/3383 +f 3764/1783/3384 3765/1784/3385 3796/1785/3386 +f 3340/1786/3281 3338/1668/3281 3336/1670/3281 +f 2958/1787/3387 3063/1788/3388 3064/1789/3389 +f 2052/1790/3390 2174/1791/3391 2164/1792/3392 +f 3639/1793/3393 3675/1794/3394 3676/1795/3395 +f 3027/1796/3296 3026/1797/3296 2997/1751/3296 +f 2977/1798/3396 2976/1688/3397 2994/1799/3398 +f 3103/1800/3399 3102/1801/3400 3122/1802/3401 +f 3034/1803/3402 3035/1804/3403 3073/1805/3404 +f 3375/1806/3405 3388/1745/3346 3389/1807/3406 +f 3864/1808/3407 3877/1809/3408 3894/1684/3294 +f 3803/1810/3409 3696/1811/3410 3693/1812/3411 +f 3350/1813/3281 3380/1814/3281 3347/1815/3281 +f 2316/1816/3412 2317/1817/3413 2318/1818/3414 +f 2436/1819/3415 2700/1820/3416 2435/1821/3417 +f 2780/1822/3418 2795/1704/3310 2796/1823/3419 +f 2893/1824/3420 2863/1825/3421 2864/1826/3422 +f 3306/1827/3423 3209/1828/3424 3305/1829/3425 +f 2083/1830/3426 2084/1831/3427 1989/1832/3428 +f 3565/1833/3429 3561/1834/3430 3444/1835/3431 +f 2664/1836/3432 2659/1837/3433 2483/1690/3434 +f 4038/1838/3435 3993/1839/3436 3994/1840/3437 +f 3401/1676/3287 3384/1841/3438 3385/1674/3285 +f 2058/1842/3439 2059/1843/3440 2055/1844/3441 +f 2735/1845/3442 2741/1846/3443 2832/1847/3444 +f 3880/1848/3445 3879/1849/3446 3867/1679/3447 +f 2095/1850/3448 2079/1851/3449 2081/1852/3450 +f 3429/1853/3451 3428/1854/3452 3426/1855/3453 +f 2784/1856/3454 2783/1857/3454 2755/1858/3454 +f 3216/1859/3455 3205/1860/3456 3311/1861/3457 +f 2807/1862/3458 2806/1863/3459 2736/1864/3460 +f 3244/1865/3461 3246/1866/3462 3245/1867/3463 +f 2735/1845/3464 2733/1868/3465 2732/1869/3465 +f 4031/1870/3466 4030/1871/3467 4032/1872/3468 +f 3418/1873/3469 3408/1874/3470 3417/1875/3471 +f 2915/1876/3472 2906/1877/3473 2894/1878/3474 +f 1673/1879/3475 1679/1880/3475 1676/1881/3475 +f 3906/1882/3476 3908/1883/3477 3907/1884/3478 +f 1751/1885/3479 1734/1886/3480 1735/1887/3481 +f 2617/1888/3482 2590/1889/3483 2581/1890/3484 +f 3697/1772/3373 3795/1771/3372 3797/1891/3485 +f 2555/1892/3486 2342/1893/3487 2340/1894/3488 +f 3189/1895/3489 3188/1896/3490 3148/1897/3491 +f 2274/1898/3492 2271/1899/3493 2272/1900/3494 +f 2223/1901/3495 2059/1843/3496 2224/1902/3497 +f 1758/1903/3498 1759/1904/3499 1747/1905/3500 +f 2774/1906/3501 2773/1907/3502 2772/1908/3502 +f 2044/1909/3503 2041/1910/3504 2040/1911/3505 +f 3052/1912/3506 3053/1913/3507 3050/1914/3508 +f 3599/1915/3509 3597/1916/3510 3583/1917/3511 +f 3941/1918/3512 3942/1919/3512 3939/1920/3513 +f 2910/1921/3514 2897/1922/3515 2898/1923/3516 +f 3380/1814/3517 3384/1841/3438 3403/1924/3518 +f 3379/1925/3519 3404/1926/3520 3405/1927/3521 +f 2092/1928/3522 1993/1929/3523 1991/1930/3524 +f 1680/1931/3525 1689/1932/3525 1684/1933/3525 +f 3975/1934/3512 3972/1935/3512 3969/1936/3512 +f 3290/1937/3526 3293/1938/3527 3215/1939/3528 +f 2680/1940/3529 2679/1941/3530 2681/1942/3531 +f 3685/1943/3532 3689/1944/3533 3686/1945/3533 +f 3720/1946/3534 3721/1947/3535 3708/1948/3536 +f 3840/1949/3537 3839/1950/3538 3841/1951/3539 +f 2427/1952/3540 2428/1953/2635 2721/1954/2635 +f 1810/1955/3541 1816/1956/3542 1811/1748/3349 +f 3130/1957/3543 3107/1958/3544 3106/1959/3543 +f 3597/1916/3545 3600/1665/3546 3598/1667/3547 +f 2917/1960/3548 2918/1961/3549 2905/1962/3550 +f 2862/1963/3551 2893/1824/3552 2891/1964/3553 +f 3382/1965/3554 3393/1966/3555 3383/1967/3556 +f 3075/1968/3557 2963/1969/3557 3077/1970/3557 +f 3448/1971/3558 3451/1972/3559 3444/1835/3558 +f 2564/1973/3560 2560/1974/3561 2461/1975/3562 +f 3662/1976/3563 3664/1977/3564 3661/1978/3565 +f 3583/1917/3511 3597/1916/3510 3595/1979/3566 +f 2456/1980/3567 2457/1981/3568 2458/1982/3569 +f 3816/1983/3570 3898/1984/3571 3900/1985/3572 +f 2568/1986/3573 2659/1837/3433 2647/1987/3574 +f 2653/1988/3575 2652/1989/3576 2649/1990/3577 +f 3390/1991/3578 3407/1992/3579 3433/1993/3580 +f 2639/1994/3581 2640/1995/3582 2634/1996/3583 +f 2173/1997/3584 2109/1998/3585 1937/1999/3586 +f 3603/2000/3587 3605/2001/3588 3602/2002/3589 +f 2050/2003/3590 2047/2004/3591 2109/1998/3585 +f 2987/2005/3296 2985/2006/3296 3019/2007/3296 +f 2851/2008/3592 2955/2009/3592 2849/2010/3592 +f 2797/2011/3593 2796/1823/3419 2829/2012/3594 +f 1727/2013/3595 1744/1720/3323 1733/2014/3596 +f 3836/2015/3597 3834/2016/3598 3835/2017/3599 +f 3208/2018/3600 3316/2019/3600 3315/2020/3600 +f 3541/2021/3601 3540/2022/3602 3539/2023/3603 +f 2688/2024/3604 2677/2025/3605 2687/2026/3606 +f 3374/2027/3607 3372/2028/3607 3371/2029/3607 +f 3738/2030/3608 3739/2031/3609 3740/2032/3610 +f 1766/2033/3611 1767/2034/3612 1765/2035/3613 +f 3539/2023/3603 3538/2036/3614 3453/2037/3615 +f 3657/2038/3616 3681/2039/3617 3683/2040/3618 +f 2924/2041/3619 2933/2042/3620 2934/2043/3621 +f 3971/2044/3622 3968/2045/3623 3969/1936/3624 +f 3404/1926/3520 3403/1924/3518 3418/1873/3469 +f 2200/2046/3625 2199/2047/3626 2198/2048/3627 +f 1725/2049/3628 1756/2050/3629 1739/2051/3630 +f 2954/2052/3631 2953/2053/3631 2950/2054/3631 +f 3787/2055/3632 3788/2056/3633 3700/2057/3634 +f 3973/2058/3635 4006/2059/3636 3977/2060/3637 +f 3352/2061/3638 3354/2062/3639 3355/2063/3640 +f 1819/2064/3641 1818/1749/3642 1977/2065/3643 +f 3940/2066/3644 3939/1920/3513 3958/2067/3645 +f 3520/1763/3364 3510/2068/3646 3509/2069/3647 +f 3282/1713/3319 3292/2070/3648 3291/2071/3649 +f 2664/1836/3432 2657/2072/3650 2646/2073/3651 +f 1805/2074/3652 1815/1697/3305 1813/1696/3304 +f 3551/2075/3653 3445/2076/3654 3552/2077/3655 +f 1766/2033/3611 1768/2078/3656 1767/2034/3612 +f 2130/2079/3657 2106/2080/3658 2131/2081/3659 +f 2439/2082/3660 2674/2083/3661 2669/2084/3662 +f 3423/2085/3663 3425/2086/3664 3405/1927/3665 +f 2850/2087/3666 2930/2088/3667 2927/2089/3668 +f 3925/2090/3669 4031/1870/3466 4032/1872/3468 +f 2673/2091/3670 2671/2092/3671 2532/2093/3672 +f 2951/2094/3673 2839/2095/3673 2840/2096/3674 +f 3128/2097/3675 3105/2098/3676 3104/2099/3677 +f 3426/1855/3453 3406/1746/3347 3425/2086/3664 +f 2029/2100/3678 2027/2101/3679 2026/2102/3680 +f 4024/2103/3681 4025/2104/3682 4021/2105/3683 +f 3434/2106/3684 3432/2107/3685 3326/2108/3686 +f 3612/1737/3687 3611/2109/3688 3613/2110/3689 +f 2715/2111/3690 2720/2112/3691 2508/2113/3692 +f 2620/2114/3693 2619/2115/3694 2629/2116/3695 +f 3033/2117/3696 3017/2118/3697 3022/2119/3698 +f 3258/2120/3699 3261/2121/3699 3226/2122/3699 +f 3607/2123/3700 3605/2001/3588 3606/2124/3701 +f 3278/2125/3702 3310/2126/3703 3309/2127/3704 +f 3908/1883/3477 3911/2128/3705 3909/2129/3706 +f 2695/2130/3707 2693/2131/3708 2694/2132/3709 +f 1728/2133/3710 1724/2134/3711 1740/2135/3712 +f 2965/2136/3713 2963/1969/3713 2956/2137/3713 +f 2908/2138/3714 2924/2041/3619 2934/2043/3621 +f 3591/2139/3280 3621/1780/3280 3620/2140/3280 +f 2919/2141/3715 2920/2142/3716 2904/2143/3717 +f 2846/2144/3718 2839/2095/3718 2950/2054/3718 +f 1732/2145/3525 1736/2146/3525 1709/2147/3525 +f 3159/2148/3719 3160/2149/3720 3173/2150/3721 +f 3634/2151/3722 3629/2152/3723 3646/2153/3724 +f 2905/1962/3725 2904/2143/3725 2872/2154/3725 +f 3105/2098/3676 3106/1959/3726 3097/2155/3726 +f 2900/2156/3727 2923/2157/3728 2924/2041/3729 +f 3103/1800/3730 3104/2099/3730 3105/2098/3730 +f 3154/2158/3731 3167/2159/3732 3194/2160/3733 +f 3331/2161/3734 3327/2162/3734 3334/2163/3735 +f 3603/2000/3736 3601/2164/3737 3584/2165/3738 +f 2870/2166/3739 2871/2167/3740 2872/2154/3741 +f 2944/2168/3742 2946/2169/3743 2912/2170/3744 +f 3169/2171/3745 3168/2172/3746 3184/2173/3747 +f 3869/2174/3748 3868/1683/3293 3893/1685/3295 +f 1706/2175/3749 1708/2176/3750 1709/2147/3751 +f 3120/2177/3730 3118/2178/3730 3144/2179/3730 +f 2823/2180/3752 2807/1862/3458 2736/1864/3460 +f 3687/2181/3753 3688/2182/3754 3577/2183/3754 +f 3645/2184/3755 3646/2153/3724 3629/2152/3723 +f 4003/2185/3756 4004/2186/3757 4019/2187/3758 +f 2580/2188/3759 2586/2189/3760 2585/2190/3761 +f 1787/2191/3762 1676/1881/3762 1786/2192/3762 +f 2758/2193/3763 2755/1858/3764 2756/2194/3765 +f 3994/1840/3437 3931/2195/3766 4038/1838/3435 +f 2774/1906/3501 2775/2196/3501 2773/1907/3502 +f 3386/2197/3281 3387/2198/3281 3361/2199/3281 +f 2182/2200/3767 2207/2201/3768 2211/2202/3769 +f 3268/2203/3770 3284/2204/3771 3283/1715/3321 +f 2165/2205/3772 2168/2206/3773 2169/2207/3774 +f 1689/1932/3775 1718/2208/3776 1688/2209/3777 +f 3683/2040/3618 3580/2210/3778 3578/2211/3779 +f 4042/2212/3780 3926/2213/3780 3933/2214/3780 +f 1754/2215/3781 1767/2034/3612 1769/2216/3782 +f 3786/2217/3783 3784/2218/3784 3785/2219/3785 +f 2765/2220/3786 2764/2221/3787 2766/2222/3788 +f 2512/2223/3789 2513/2224/3790 2511/2225/3791 +f 3303/2226/3792 3302/2227/3793 3271/2228/3794 +f 3785/2219/3785 3771/2229/3795 3772/2230/3796 +f 2595/2231/3797 2594/2232/3798 2599/2233/3799 +f 2234/2234/2635 2233/2235/3271 1923/2236/3800 +f 2827/2237/3801 2794/2238/3802 2793/2239/3803 +f 3240/2240/3804 3242/2241/3805 3221/2242/3806 +f 3664/1977/3564 3663/2243/3807 3666/2244/3808 +f 3085/2245/3809 3086/2246/3810 3181/2247/3811 +f 3026/1797/3812 3027/1796/3813 3037/2248/3814 +f 3460/2249/3815 3459/2250/3815 3464/2251/3815 +f 2152/2252/3816 2139/2253/3817 2138/2254/3818 +f 4036/2255/3819 4035/2256/3820 3992/2257/3821 +f 2851/2008/3822 2845/2258/3822 2953/2053/3822 +f 2245/2259/3823 2240/2260/3824 2239/2261/3825 +f 3532/2262/3826 3531/1762/3363 3519/1764/3365 +f 3753/2263/3827 3758/2264/3827 3719/2265/3827 +f 3566/2266/3828 3567/2267/3828 3685/1943/3828 +f 2009/2268/3829 2012/2269/3830 2011/2270/3831 +f 3691/1707/3832 3806/2271/3832 3698/2272/3832 +f 2941/2273/3833 2940/2274/3834 2939/2275/3835 +f 1949/2276/3836 1962/2277/3837 1793/2278/3838 +f 3602/2002/3589 3599/1915/3839 3601/2164/3840 +f 3081/1701/3841 3083/2279/3842 3084/2280/3843 +f 3136/2281/3730 3110/2282/3730 3108/2283/3730 +f 1967/2284/3844 1963/2285/3845 2180/2286/3846 +f 1908/2287/3847 1987/2288/3848 1931/2289/3849 +f 3645/2184/3755 3644/2290/3850 3681/2039/3617 +f 3760/2291/3827 3754/2292/3827 3732/2293/3827 +f 3056/2294/3851 3054/2295/3852 3042/2296/3853 +f 3152/2297/3854 3151/2298/3855 3133/2299/3856 +f 3071/2300/3857 2967/2301/3858 3070/2302/3859 +f 3119/2303/3860 3121/2304/3861 3102/1801/3400 +f 1725/2049/3525 1724/2134/3525 1691/2305/3525 +f 3476/1779/3380 3477/2306/3862 3478/2307/3863 +f 2564/1973/3864 2563/2308/3865 2348/2309/3866 +f 3866/2310/3288 3860/1677/3288 3867/1679/3289 +f 4016/2311/3867 4014/2312/3868 4015/2313/3869 +f 2807/1862/3870 2808/2314/3871 2784/1856/3872 +f 3034/1803/3402 3073/1805/3404 3072/2315/3873 +f 3294/2316/3874 3297/1776/3377 3213/1775/3376 +f 3445/2076/3654 3443/2317/3559 3450/2318/3875 +f 3215/1939/3528 3213/1775/3376 3214/2319/3361 +f 3371/2029/3876 3372/2028/3876 3370/2320/3876 +f 3279/2321/3877 3312/2322/3878 3310/2126/3703 +f 1778/2323/3879 1743/2324/3880 1777/2325/3881 +f 3949/2326/3882 3952/2327/3883 3951/2328/3884 +f 3213/1775/3376 3215/1939/3528 3294/2316/3874 +f 3155/2329/3885 3156/2330/3886 3195/2331/3887 +f 1955/2332/3888 1794/2333/3889 1956/2334/3890 +f 2965/2136/3713 2967/2301/3891 2963/1969/3713 +f 3055/2335/3892 3056/2294/3851 3057/2336/3893 +f 3666/2244/3808 3665/1710/3316 3664/1977/3564 +f 3160/2149/3720 3161/2337/3894 3176/2338/3895 +f 3967/2339/3896 3965/2340/3897 3966/2341/3898 +f 3148/1897/3491 3134/2342/3899 3135/2343/3900 +f 3148/1897/3491 3149/2344/3901 3189/1895/3489 +f 3481/2345/3902 3462/2346/3903 3482/2347/3904 +f 3016/2348/3905 3045/2349/3906 3020/2350/3907 +f 2747/2351/3908 2764/2221/3909 2746/2352/3910 +f 1711/2353/3911 1686/2354/3912 1687/2355/3913 +f 1729/2356/3914 1741/2357/3915 1742/2358/3916 +f 2029/2100/3917 2031/2359/3918 1873/2360/3919 +f 3627/2361/3920 3632/2362/3921 3653/2363/3922 +f 2205/2364/3923 2121/2365/3924 2113/2366/3925 +f 3460/2249/3926 3469/2367/3927 3459/2250/3928 +f 3044/2368/3929 3045/2349/3930 2959/2369/3931 +f 3144/2179/3932 3156/2330/3886 3155/2329/3885 +f 2693/2131/3708 2575/2370/3933 2570/2371/3934 +f 2580/2188/3759 2573/2372/3935 2577/2373/3936 +f 3143/2374/3937 3160/2149/3938 3159/2148/3939 +f 2298/2375/3940 2297/2376/3941 2300/2377/3942 +f 4011/2378/3943 4010/2379/3944 4012/2380/3945 +f 3052/1912/3506 3050/1914/3508 3039/2381/3946 +f 3229/2382/3947 3230/2383/3948 3218/2384/3949 +f 2565/2385/3950 2567/2386/3951 2647/1987/3574 +f 3848/2387/3952 3849/2388/3953 3850/2389/3954 +f 3944/2390/3955 3946/2391/3956 3937/2392/3957 +f 2959/2369/3931 3062/2393/3958 3061/2394/3959 +f 1698/2395/3960 1699/2396/3961 1700/2397/3962 +f 3692/1708/3314 3697/1772/3315 3690/1709/3315 +f 2592/2398/3963 2607/2399/3964 2628/2400/3965 +f 2013/2401/3966 2012/2269/3830 2077/2402/3967 +f 2587/2403/3968 2589/2404/3969 2603/2405/3970 +f 2935/2406/3971 2908/2138/3714 2934/2043/3621 +f 3875/1717/3972 3886/2407/3973 3885/2408/3974 +f 2361/2409/3975 2360/2410/3976 2387/2411/3977 +f 3896/2412/3978 3818/2413/3979 3895/2414/3980 +f 3286/2415/3981 3285/2416/3982 3262/2417/3983 +f 3415/2418/3984 3400/1675/3286 3334/2163/3735 +f 2329/2419/3985 2328/2420/3986 2327/2421/3987 +f 3095/2422/3841 3096/2423/3841 3094/2424/3841 +f 3067/2425/3988 3047/2426/3989 3068/2427/3990 +f 3877/1809/3408 3863/2428/3991 3866/2310/3992 +f 3252/2429/3993 3250/2430/3994 3251/2431/3995 +f 3609/2432/3996 3608/2433/3997 3610/2434/3998 +f 2026/2102/3680 2156/2435/3999 2155/2436/4000 +f 3636/2437/4001 3668/1711/3317 3669/2438/4002 +f 2475/2439/4003 2474/2440/4004 2243/2441/4005 +f 2507/2442/4006 2510/2443/4007 2715/2111/3690 +f 1747/1905/3500 1748/2444/4008 1737/2445/4009 +f 3465/2446/4010 3489/2447/4011 3464/2251/4012 +f 2037/2448/4013 2042/2449/4014 2233/2235/4015 +f 3722/2450/3827 3759/2451/3827 3724/2452/3827 +f 3698/2272/3313 3701/2453/3313 3700/2057/3634 +f 1726/2454/4016 1729/2356/3914 1742/2358/3916 +f 1864/2455/4017 2073/2456/4018 2022/2457/4019 +f 3554/2458/4020 3515/2459/4021 3514/2460/4022 +f 2815/2461/4023 2821/2462/4024 2802/2463/4025 +f 4002/2464/4026 4001/2465/4027 3983/2466/4028 +f 1963/2285/4029 1798/2467/4030 1964/2468/4031 +f 3895/2414/3980 3916/2469/4032 3885/2408/4033 +f 2141/2470/4034 2114/2471/4035 2115/2472/4036 +f 2528/2473/4037 2530/2474/4038 2531/2475/4039 +f 2799/2476/4040 2798/2477/4041 2812/2478/4042 +f 3026/1797/3296 3000/1752/3296 2997/1751/3296 +f 2152/2252/3816 2151/2479/4043 2150/2480/4044 +f 1789/2481/4045 1790/2482/4046 1788/2483/4047 +f 2107/2484/4048 2043/2485/4049 2044/1909/3503 +f 3071/2300/3857 3070/2302/3859 3069/2486/4050 +f 3815/2487/4051 3817/2488/4052 3821/2489/4051 +f 1932/2490/4053 2191/2491/4054 2194/2492/4055 +f 1703/2493/3525 1705/2494/3525 1738/2495/3525 +f 3677/2496/4056 3641/1681/4057 3640/2497/4058 +f 3248/2498/4059 3250/2430/4060 3222/2499/4061 +f 2098/2500/4062 2010/2501/4063 2006/2502/4064 +f 3079/2503/3713 3080/2504/4065 3076/2505/3713 +f 3049/2506/4066 3074/2507/4067 3036/2508/4068 +f 3930/2509/4069 3935/2510/4070 3929/2511/4071 +f 3640/2497/4072 3641/1681/3291 3625/1680/3290 +f 3102/1801/3400 3121/2304/3861 3122/1802/3401 +f 3805/2512/4073 3701/2453/4073 3698/2272/4073 +f 1730/2513/3525 1725/2049/3525 1693/2514/3525 +f 2128/2515/4074 2133/2516/4075 2123/2517/4076 +f 1950/2518/4077 1951/2519/4078 2070/2520/4079 +f 1855/2521/4080 1857/2522/4081 1853/2523/4082 +f 2463/2524/4083 2616/2525/4084 2634/1996/3583 +f 3763/2526/4085 3780/2527/4086 3795/1771/3372 +f 2074/2528/4087 1936/2529/4088 1935/2530/4089 +f 2687/2026/3606 2677/2025/3605 2684/2531/4090 +f 2515/2532/4091 2517/2533/4092 2714/2534/4093 +f 2082/2535/4094 2097/2536/4095 2093/2537/4096 +f 2766/2222/3788 2767/2538/4097 2768/2539/4098 +f 3570/2540/4099 3684/2541/4100 3686/1945/4099 +f 3450/2318/3875 3553/2542/4101 3552/2077/3655 +f 3124/2543/4102 3103/1800/3399 3122/1802/3401 +f 3513/2544/4103 3514/2460/4022 3500/2545/4104 +f 2819/2546/4105 2820/2547/4106 2816/2548/4107 +f 3115/2549/4108 3114/2550/4109 3116/2551/4110 +f 2475/2439/4111 2477/2552/4112 2476/2553/4113 +f 3358/2554/4114 3355/2063/3640 3356/2555/4115 +f 2016/2556/4116 2018/2557/4117 2017/2558/4118 +f 3391/2559/4119 3434/2106/3684 3435/2560/4120 +f 2143/1735/3338 2141/2470/4034 2142/1736/3339 +f 1794/2333/4121 1792/2561/4122 1798/2467/4123 +f 1726/2454/4124 1717/2562/3525 1719/2563/3525 +f 3872/2564/3289 3871/2565/3288 3854/2566/3289 +f 2347/2567/4125 2560/1974/4126 2348/2309/3866 +f 2368/2568/4127 2382/2569/4128 2383/2570/4129 +f 2867/2571/4130 2856/2572/4131 2868/2573/4132 +f 2775/2196/3501 2776/1728/4133 2777/1730/4134 +f 3621/1780/3381 3655/1712/4135 3636/2437/4136 +f 1851/2574/4137 1850/2575/4138 1852/2576/4139 +f 1972/2577/4140 1969/2578/4141 2184/2579/4142 +f 2592/2398/3963 2628/2400/3965 2627/2580/4143 +f 1754/2215/4144 1755/2581/4145 1730/2513/4146 +f 1812/2582/4147 1813/1696/3304 1814/1695/3303 +f 4006/2059/4148 4026/2583/4149 4023/2584/4150 +f 2985/2006/4151 2986/2585/4152 2983/2586/4153 +f 1704/2587/4154 1702/2588/4155 1685/2589/4156 +f 3034/1803/3402 3072/2315/3873 3071/2300/3857 +f 2174/1791/3391 2052/1790/3390 2173/1997/3584 +f 2949/2590/4157 2925/2591/4158 2915/1876/3472 +f 2306/2592/4159 2305/2593/4160 2304/2594/4161 +f 2294/2595/4162 2293/2596/4163 2295/2597/4164 +f 3896/2412/3978 3888/2598/4165 3897/2599/4166 +f 3548/2600/4167 3546/2601/4168 3545/2602/4169 +f 2507/2442/4006 2715/2111/3690 2508/2113/3692 +f 3105/2098/3730 3097/2155/3730 3101/2603/4170 +f 2254/2604/4171 2252/2605/4172 2253/2606/4173 +f 3557/2607/4174 3558/2608/4175 3516/2609/4176 +f 1827/2610/4177 1823/2611/4178 1826/2612/4179 +f 1828/2613/4180 1829/2614/4181 1830/2615/4182 +f 1830/2615/4182 1829/2614/4181 1831/2616/4183 +f 1830/2615/4182 1831/2616/4183 1832/2617/4184 +f 1832/2617/4184 1831/2616/4183 1833/2618/4185 +f 1832/2617/4184 1833/2618/4185 1834/2619/4186 +f 2981/2620/4187 2983/2586/4188 2973/1686/4189 +f 1825/2621/4190 1834/2619/4186 1833/2618/4185 +f 1835/2622/4191 1836/2623/4192 1837/2624/4193 +f 1838/2625/4194 1825/2621/4190 1839/2626/4195 +f 2119/2627/4196 2123/2517/4076 2132/2628/4197 +f 1836/2623/4192 1840/2629/4198 1837/2624/4193 +f 1835/2622/4191 1837/2624/4193 1841/2630/4199 +f 1841/2630/4199 1837/2624/4193 1842/2631/4200 +f 3199/2632/4201 3198/2633/4201 3089/2634/4201 +f 1959/2635/4202 1795/2636/4203 1791/2637/4204 +f 2562/2638/4205 2555/1892/4206 2574/2639/4207 +f 1960/2640/4208 1955/2332/4209 1956/2334/4210 +f 3745/2641/4211 3744/2642/4212 3743/1743/4213 +f 1847/2643/4214 1846/2644/4215 1848/2645/4216 +f 3693/1812/3313 3694/2646/3313 3704/2647/3313 +f 2112/1673/3284 2111/2648/4217 2075/2649/4218 +f 1906/2650/4219 1904/2651/4220 1991/1930/3524 +f 1829/2614/4221 2003/2652/4222 1941/2653/4223 +f 3483/2654/4224 3482/2347/4225 3484/2655/4226 +f 1723/2656/4227 1690/2657/4228 1691/2305/4229 +f 3851/2658/4230 3852/2659/4231 3854/2566/4232 +f 2065/2660/4233 2058/1842/3439 2063/2661/4234 +f 2616/2525/4084 2615/2662/4235 2621/2663/4236 +f 1695/2664/3525 1730/2513/3525 1693/2514/3525 +f 2634/1996/3583 2447/2665/4237 2639/1994/3581 +f 1791/2637/4204 1954/2666/4238 1959/2635/4202 +f 2600/2667/4239 2599/2233/3799 2449/2668/4240 +f 2063/2661/4234 2158/2669/4241 2061/2670/4242 +f 2439/2082/3660 2438/2671/4243 2677/2025/3605 +f 1938/2672/4244 2081/1852/3450 2092/1928/3522 +f 2707/2673/4245 2706/2674/4246 2527/2675/4247 +f 2535/2676/4248 2536/2677/4249 2455/2678/4250 +f 2794/2238/3802 2827/2237/3801 2814/1705/3311 +f 3020/2350/3296 2985/2006/3296 2984/2679/4251 +f 1861/2680/4252 1862/2681/4253 1866/2682/4254 +f 2687/2026/3606 2435/1821/3417 2700/1820/3416 +f 2210/2683/4255 2209/2684/4256 1986/2685/4257 +f 2802/2463/4025 2803/2686/4258 2791/2687/4259 +f 1865/2688/4260 1869/2689/4261 1870/2690/4262 +f 1677/2691/3475 1668/2692/3475 1669/2693/3475 +f 3636/2437/4001 3655/1712/3318 3668/1711/3317 +f 3632/2362/3921 3633/1666/4263 3651/1731/4264 +f 3847/2694/4265 3845/2695/4266 3846/1718/4267 +f 1872/2696/4268 1873/2360/4269 1874/2697/4270 +f 3226/2122/4271 3228/2698/4272 3227/2699/4273 +f 2289/1700/3308 2290/2700/4274 2288/1698/3306 +f 2758/2193/3763 2759/2701/4275 2761/2702/4276 +f 2810/2703/4277 2809/2704/4278 2729/2705/4279 +f 4044/2706/4280 3930/2509/4281 3924/2707/4280 +f 3493/2708/3815 3494/2709/4282 3502/2710/3815 +f 3126/2711/4283 3128/2097/3675 3104/2099/3677 +f 2695/2130/3707 2691/2712/4284 2690/2713/4285 +f 3036/2508/4068 3037/2248/3814 3049/2506/4066 +f 2806/1863/4286 2788/2714/4287 2805/2715/4288 +f 3135/2343/3730 3134/2342/4289 3131/2716/3730 +f 2370/2717/4290 2360/2410/3976 2357/2718/4291 +f 2503/2719/4292 2506/2720/4293 2504/2721/4294 +f 3461/2722/4295 3476/1779/4296 3474/1778/4297 +f 1879/2723/4298 1881/2724/4046 1880/2725/4299 +f 1706/2175/3749 1707/2726/3749 1705/2494/4300 +f 1672/2727/4301 1673/1879/3475 1666/2728/3475 +f 2275/2729/4302 2267/2730/4303 2268/2731/4304 +f 3566/2266/3828 3685/1943/3828 3684/2541/4305 +f 2089/2732/4306 2097/2536/4095 2096/2733/4307 +f 2186/2734/4308 1932/2490/4053 1934/2735/4309 +f 3302/2227/3793 3303/2226/3792 3210/2736/4310 +f 1667/2737/4311 1672/2727/4301 1666/2728/3475 +f 1951/2519/4078 1950/2518/4077 1952/2738/4312 +f 1951/2519/4078 1952/2738/4312 1953/2739/4313 +f 3384/1841/3438 3402/2740/4314 3403/1924/3518 +f 2803/2686/4315 2821/2462/4024 2822/2741/4316 +f 2975/2742/4317 2990/2743/4318 2991/2744/4319 +f 3145/2745/4320 3158/2746/4321 3157/2747/4322 +f 3774/1757/3358 3781/1759/3360 3782/2748/4323 +f 3768/2749/4324 3769/2750/4325 3694/2646/4326 +f 1785/2751/3475 1784/2752/3475 1782/2753/3475 +f 1974/2754/4327 1973/2755/4328 1975/2756/4329 +f 3652/2757/4330 3651/1731/3334 3656/2758/4331 +f 3959/2759/4332 3962/2760/4333 3960/2761/4334 +f 2533/2762/4335 2570/2371/3934 2541/2763/4336 +f 2847/2764/4337 2939/2275/3835 2937/2765/4338 +f 1859/2766/4339 1858/2767/4340 1863/2768/4341 +f 1797/2769/4342 1967/2284/4343 1799/2770/4344 +f 3506/2771/3815 3505/2772/3815 3486/2773/3815 +f 2701/2774/4345 2652/1989/3576 2571/2775/4346 +f 3623/1782/3383 3638/2776/4347 3624/2777/4348 +f 1826/2612/4179 1822/2778/4349 1821/2779/4350 +f 3427/1747/3348 3431/2780/4351 3388/1745/3346 +f 1985/2781/4352 1892/2782/4353 1882/2783/4354 +f 2803/2686/4258 2804/2784/4355 2789/2785/4356 +f 2852/2786/3631 2844/2787/3631 2845/2258/3631 +f 3679/2788/4357 3642/2789/4358 3677/2496/4056 +f 3445/2076/3654 3448/1971/3558 3444/1835/3558 +f 2108/2790/4359 2044/1909/3503 2040/1911/3505 +f 2980/2791/4360 2979/2792/4361 3009/2793/4362 +f 1893/2794/4363 1989/1832/3428 1894/2795/4364 +f 3044/2368/3929 3043/2796/4365 3019/2007/4366 +f 2780/1822/3454 2771/2797/3454 2773/1907/3454 +f 2635/2798/4367 2636/2799/4368 2602/2800/4369 +f 3099/2801/3730 3100/2802/3730 3101/2603/4170 +f 2022/2457/4370 2073/2456/4371 2072/2803/4372 +f 2884/2804/4373 2882/2805/4374 2860/2806/4375 +f 1990/1694/3302 1901/1693/3301 1900/2807/4376 +f 3466/2808/4377 3497/2809/4378 3458/2810/4379 +f 1906/2650/4219 1991/1930/3524 1992/2811/4380 +f 3336/1670/3281 3335/2812/4381 3344/2813/3281 +f 1994/2814/4382 1945/2815/4383 1995/2816/4384 +f 3446/2817/3558 3447/2818/4385 3455/2819/4386 +f 1996/2820/4387 1997/2821/4388 1998/2822/4389 +f 3506/2771/4390 3499/2823/4391 3515/2459/4392 +f 3280/2824/4393 3281/2825/4394 3291/2071/3649 +f 3970/2826/4395 3971/2044/3622 3943/2827/4396 +f 3924/2707/4397 3929/2511/4071 3925/2090/3669 +f 2700/1820/3416 2436/1819/3415 2701/2774/4345 +f 3393/1966/3555 3394/2828/4398 3383/1967/3556 +f 3453/2037/3615 3451/1972/4399 3541/2021/3601 +f 2881/2829/4400 2878/1727/3330 2879/2830/4401 +f 2627/2580/4143 2583/2831/4402 2592/2398/3963 +f 2913/2832/4403 2903/2833/4404 2912/2170/4405 +f 3419/2834/4406 3422/2835/4407 3421/2836/4408 +f 2963/1969/4409 2961/2837/4409 3078/2838/4409 +f 3875/1717/3972 3876/1716/4410 3887/2839/4411 +f 3190/2840/4412 3150/2841/4413 3191/2842/4414 +f 3667/2843/4415 3663/2243/3807 3572/2844/4416 +f 2979/2792/4361 2978/2845/4417 3004/2846/4418 +f 2036/2847/4419 1879/2723/4420 1876/2848/4421 +f 2142/1736/3339 2204/2849/4422 1937/1999/3586 +f 2149/2850/4423 2125/2851/4424 2150/2480/4044 +f 4040/2852/4425 4039/2853/4425 4041/2854/4425 +f 3553/2542/4101 3450/2318/3875 3455/2819/4386 +f 2080/2855/4426 2079/1851/3449 2090/2856/4427 +f 2032/2857/4428 2033/2858/4429 2034/2859/4430 +f 3138/2860/4431 3136/2281/4432 3164/2861/4433 +f 2384/2862/4434 2375/2863/4435 2374/2864/4436 +f 3279/2321/4437 3278/2125/4438 3263/2865/4439 +f 3699/2866/3313 3694/2646/3313 3693/1812/3313 +f 1829/2614/4181 1828/2613/4180 1827/2610/4177 +f 2041/1910/3504 2042/2449/4440 2040/1911/3505 +f 3305/1829/3425 3274/2867/4441 3275/2868/4442 +f 2044/1909/3503 2043/2485/4049 2045/2869/4443 +f 3770/2870/4444 3771/2229/3795 3783/2871/4445 +f 2474/2440/4446 2475/2439/4111 2473/2872/4447 +f 3015/2873/3296 3016/2348/3296 3013/2874/3296 +f 2703/2875/4448 2526/2876/4449 2524/2877/4450 +f 2052/1790/3390 2053/2878/4451 2049/2879/4452 +f 3489/2447/4453 3492/2880/4454 3491/2881/4455 +f 3948/2882/4456 3949/2326/4457 3937/2392/3957 +f 3796/1785/3386 3765/1784/3385 3797/1891/3485 +f 2058/1842/3439 2065/2660/4233 2059/1843/3440 +f 2067/2883/4458 2068/2884/4459 2069/2885/4460 +f 2070/2520/4461 2218/2886/4462 2066/2887/4463 +f 1724/2134/3711 1725/2049/3628 1739/2051/3630 +f 3345/2888/4464 3374/2027/4465 3373/2889/4466 +f 2216/2890/4467 2215/2891/4468 2214/2892/4469 +f 3003/2893/4470 3002/2894/4471 3001/2895/4472 +f 3679/2788/4357 3678/2896/4473 3680/2897/4474 +f 2640/1995/3582 2639/1994/3581 2638/2898/4475 +f 3454/2899/3558 3456/2900/4476 3447/2818/4385 +f 3864/1808/3289 3868/1683/3289 3832/2901/3288 +f 2858/2902/4477 2875/2903/4478 2873/2904/4479 +f 3133/2299/3730 3135/2343/3730 3129/2905/3730 +f 3074/2507/4067 3035/1804/3403 3036/2508/4068 +f 2940/2274/3834 2941/2273/3833 2944/2168/3742 +f 2853/2906/4480 2945/2907/4481 2941/2273/3833 +f 2428/1953/2635 2281/2908/2635 2722/2909/2635 +f 4043/2910/4482 3933/2214/4482 3930/2509/4482 +f 2940/2274/3834 2910/1921/3514 2939/2275/3835 +f 2282/2911/4483 2280/2912/4484 2281/2908/4485 +f 4018/2913/4486 4007/2914/4487 4003/2185/3756 +f 2653/1988/3575 2661/2915/4488 2665/2916/4489 +f 3254/2917/4490 3252/2429/3993 3253/2918/3993 +f 3205/1860/3456 3209/1828/3424 3308/2919/4491 +f 3586/2920/4492 3610/2434/4493 3608/2433/4494 +f 2280/2912/4495 2282/2911/4496 2502/2921/4497 +f 2932/2922/4498 2848/2923/4499 2843/2924/4500 +f 2023/2925/4501 2024/2926/4502 1940/2927/4503 +f 2994/1799/3398 2996/2928/4504 2977/1798/3396 +f 2232/2929/4505 2045/2869/4506 2043/2485/4507 +f 3942/1919/4508 3941/1918/4509 3965/2340/4510 +f 1748/2444/4008 1738/2495/4511 1737/2445/4009 +f 2551/2930/4512 2321/2931/4513 2548/2932/4514 +f 1973/2755/4328 1948/2933/4515 2183/2934/4516 +f 3862/2935/3288 3863/2428/3289 3864/1808/3289 +f 2804/2784/4517 2803/2686/4315 2822/2741/4316 +f 3826/2936/4518 3844/2937/4519 3845/2695/4520 +f 3066/2938/4521 3068/2427/3990 3070/2302/3859 +f 2152/2252/3816 2140/1671/3282 2154/2939/4522 +f 2599/2233/3799 2653/1988/3575 2665/2916/4489 +f 3720/1946/4523 3718/2940/4524 3719/2265/4525 +f 3454/2899/3558 3457/2941/3558 3456/2900/4476 +f 3595/1979/4526 3597/1916/3545 3598/1667/3547 +f 3050/1914/3508 2968/2942/4527 3038/2943/4528 +f 2993/2944/4529 2991/2744/4530 2992/2945/4531 +f 3160/2149/3938 3143/2374/3937 3161/2337/4532 +f 3795/1771/3372 3793/1773/3374 3794/2946/4533 +f 2614/2947/4534 2386/2948/4535 2380/2949/4536 +f 3609/2432/3280 3612/1737/3280 3631/2950/3280 +f 1842/2631/4200 1843/2951/4537 1841/2630/4199 +f 4009/2952/4538 3931/2195/3766 3996/2953/4539 +f 3790/2954/4540 3762/2955/4541 3794/2946/4533 +f 3192/2956/4542 3092/2957/4543 3191/2842/4414 +f 3362/2958/4544 3364/2959/4545 3365/2960/4546 +f 2319/2961/4547 2316/1816/3412 2318/1818/3414 +f 2443/2962/4548 2444/2963/4549 2650/2964/4550 +f 2649/1990/3577 2652/1989/3576 2651/2965/4551 +f 3939/1920/3513 3938/2966/4552 3953/2967/4553 +f 2632/2968/4554 2622/2969/4555 2621/2663/4236 +f 2088/2970/4556 2087/2971/4557 2089/2732/4306 +f 2696/2972/4558 2576/2973/4559 2695/2130/3707 +f 1998/2822/4389 1944/2974/4560 1996/2820/4387 +f 1996/2820/4387 1944/2974/4560 1946/2975/4561 +f 3527/2976/4562 3504/2977/4563 3526/2978/4564 +f 2865/2979/4565 2863/1825/4566 2856/2572/4131 +f 2330/2980/4567 2331/2981/4568 2332/2982/4569 +f 2960/2983/4570 3072/2315/3873 3074/2507/4067 +f 1826/2612/4571 2002/2984/4572 2003/2652/4222 +f 2094/2985/4573 2081/1852/3450 1938/2672/4244 +f 3607/2123/3280 3629/2152/3280 3605/2001/3280 +f 3891/2986/4574 3901/2987/4575 3899/2988/4576 +f 1971/2989/4577 1972/2577/4140 2183/2934/4516 +f 2382/2569/4128 2590/1889/3483 2612/2990/4578 +f 2784/1856/3872 2808/2314/3871 2809/2704/4579 +f 2080/2855/4426 2091/2991/4580 2092/1928/3522 +f 3750/2992/3827 3749/2993/4581 3740/2032/4582 +f 2183/2934/4516 1970/2994/4583 1971/2989/4577 +f 3769/2750/4584 3768/2749/4324 3754/2292/4585 +f 1943/2995/4586 1997/2821/4388 1996/2820/4387 +f 3750/2992/4587 3755/2996/4588 3766/2997/4589 +f 2079/1851/3449 2080/2855/4426 2081/1852/3450 +f 2836/2998/4590 2837/2999/4591 2738/3000/4591 +f 2865/2979/4592 2867/2571/4593 2866/3001/4594 +f 3885/2408/4033 3886/2407/4595 3895/2414/3980 +f 1683/3002/4596 1684/1933/4597 1699/2396/4598 +f 3789/3003/4599 3791/3004/4600 3792/3005/4601 +f 2393/3006/4602 2463/2524/4083 2392/3007/4603 +f 2084/1831/3427 1896/3008/4604 1895/3009/4605 +f 3134/2342/3899 3148/1897/3491 3147/3010/4606 +f 2095/1850/3448 2086/3011/4607 2088/2970/4556 +f 2095/1850/3448 2088/2970/4556 2096/2733/4307 +f 2498/3012/4608 2501/3013/4609 2282/2911/4610 +f 2471/3014/4611 2472/3015/4612 2468/3016/4613 +f 3133/2299/3730 3129/2905/3730 3127/3017/3730 +f 2473/2872/4447 2481/3018/4614 2478/3019/4615 +f 2784/1856/3454 2755/1858/3454 2758/2193/3454 +f 1803/3020/4616 1968/3021/4617 1804/3022/4618 +f 2404/3023/4619 2405/3024/4620 2635/2798/4367 +f 2712/3025/4621 2518/3026/4622 2521/3027/4623 +f 2922/3028/4624 2921/3029/4625 2932/2922/4498 +f 1783/3030/4626 1665/3031/4626 1666/2728/4626 +f 3934/3032/4627 3933/2214/4628 3926/2213/4425 +f 2855/3033/3725 2862/1963/3725 2859/3034/3725 +f 2096/2733/4307 2079/1851/3449 2095/1850/3448 +f 2571/2775/4346 2448/3035/4629 2572/3036/4630 +f 3694/2646/4326 3800/3037/4631 3768/2749/4324 +f 3969/1936/3624 3967/2339/3896 3966/2341/3898 +f 2129/3038/4632 2139/2253/3817 2077/2402/3967 +f 3927/3039/4633 3928/3040/4634 3932/3041/4635 +f 2466/3042/4636 2465/3043/4637 2459/3044/4638 +f 2343/3045/4639 2344/3046/4640 2345/3047/4641 +f 3247/3048/4642 3248/2498/4059 3222/2499/4061 +f 3387/2198/4643 3386/2197/4644 3398/3049/4645 +f 3183/3050/4646 3085/2245/3809 3181/2247/3811 +f 1711/2353/3911 1710/3051/4647 1686/2354/3912 +f 3681/2039/3617 3657/2038/3616 3646/2153/3724 +f 3236/3052/4648 3238/3053/4649 3237/3054/4650 +f 3695/3055/4651 3778/3056/4652 3789/3003/4599 +f 3465/2446/4010 3458/2810/4379 3495/3057/4653 +f 2658/3058/4654 2660/3059/4655 2656/3060/4656 +f 3492/2880/4454 3493/2708/4657 3491/2881/4455 +f 3982/3061/3512 3985/3062/3512 3956/3063/3512 +f 3070/2302/3859 2967/2301/3858 3066/2938/4521 +f 1679/1880/4658 1675/3064/4659 1763/3065/4660 +f 2335/3066/4661 2334/3067/4662 2333/3068/4663 +f 3579/3069/3533 3578/2211/4664 3577/2183/3533 +f 2070/2520/4079 2074/2528/4087 1961/3070/4665 +f 2913/2832/4403 2902/3071/4666 2903/2833/4404 +f 2137/3072/4667 2116/3073/4668 2149/2850/4423 +f 3023/3074/4669 3024/3075/4670 3041/3076/4671 +f 3492/2880/4672 3489/2447/4011 3465/2446/4010 +f 3963/3077/4673 3964/3078/4673 3966/2341/3898 +f 3241/3079/4674 3244/1865/3461 3242/2241/4675 +f 2528/2473/4676 2285/3080/4677 2284/3081/4678 +f 1948/2933/4515 1970/2994/4583 2183/2934/4516 +f 3364/2959/4545 3366/3082/4679 3365/2960/4546 +f 2479/3083/4680 2458/1982/3569 2478/3019/4615 +f 2652/1989/3576 2594/2232/3798 2571/2775/4346 +f 2185/3084/4681 1805/2074/4682 1804/3022/4618 +f 3496/3085/4683 3495/3057/4684 3497/2809/4685 +f 3284/2204/3771 3285/2416/4686 3298/3086/4687 +f 3128/2097/3675 3130/1957/3676 3105/2098/3676 +f 3393/1966/3555 3382/1965/3554 3392/3087/4688 +f 1874/2697/4270 1878/3088/4689 1877/3089/4690 +f 1763/3065/4660 1750/3090/4691 1762/3091/4692 +f 3975/1934/4693 3976/3092/4694 3989/3093/4695 +f 3841/1951/3539 3839/1950/3538 3838/3094/4696 +f 2625/3095/4697 2624/3096/4698 2606/3097/4699 +f 3455/2819/4386 3450/2318/3875 3449/3098/3558 +f 2970/3099/3713 2961/2837/3713 2960/2983/3713 +f 3999/3100/4700 4000/3101/4701 4013/3102/4702 +f 3350/1813/4703 3347/1815/4704 3348/3103/4705 +f 1746/3104/4706 1736/2146/4707 1732/2145/4708 +f 2607/2399/3964 2585/2190/3761 2593/3105/4709 +f 4037/3106/4710 4034/3107/4711 4035/2256/3820 +f 2611/3108/4712 2624/3096/4698 2623/3109/4713 +f 3708/1948/3536 3707/3110/4714 3718/2940/4715 +f 2096/2733/4307 2082/2535/4094 2079/1851/3449 +f 3207/1724/3362 3204/1723/3326 3203/1761/3362 +f 2676/3111/4716 2677/2025/3605 2690/2713/4285 +f 3954/3112/4717 3955/3113/4718 3953/2967/4719 +f 3442/3114/4720 3438/3115/4721 3320/3116/4720 +f 2169/2207/3774 2162/3117/4722 2158/2669/4241 +f 3032/3118/4723 3033/2117/3696 3067/2425/3988 +f 1797/2769/4724 1791/2637/4724 1798/2467/4724 +f 3273/3119/4725 3259/3120/4726 3274/2867/4727 +f 2132/2628/4197 2123/2517/4076 2134/3121/4728 +f 3103/1800/3399 3124/2543/4102 3126/2711/4283 +f 3447/2818/4385 3559/3122/4729 3558/2608/4175 +f 2741/1846/3443 2735/1845/3464 2730/3123/3464 +f 3758/2264/4730 3753/2263/4731 3776/3124/4732 +f 2554/3125/4733 2551/2930/4734 2548/2932/4735 +f 2553/3126/4736 2554/3125/4733 2548/2932/4735 +f 3005/3127/4737 3008/3128/4738 3006/3129/4739 +f 3828/3130/4740 3827/3131/4741 3848/2387/4742 +f 3423/2085/3663 3404/1926/3520 3420/3132/4743 +f 2837/2999/3501 2734/3133/3501 2738/3000/3501 +f 2591/3134/4744 2581/1890/3484 2582/3135/4745 +f 1720/3136/4746 1689/1932/3775 1721/3137/4747 +f 3109/3138/4748 3106/1959/4749 3108/2283/4750 +f 2820/2547/4106 2818/3139/4751 2739/3140/4752 +f 3821/2489/4753 3818/2413/3979 3896/2412/3978 +f 3417/1875/3471 3408/1874/3470 3402/2740/4314 +f 2185/3084/4754 2180/2286/3846 2184/2579/4142 +f 1788/2483/4755 1790/2482/4756 1951/2519/4757 +f 1957/3141/4758 1954/2666/4759 1950/2518/4077 +f 2084/1831/3427 1895/3009/4605 1989/1832/3428 +f 2575/2370/3933 2695/2130/3707 2576/2973/4559 +f 2067/2883/4458 2074/2528/4087 2066/2887/4760 +f 2849/2010/4761 2850/2087/3666 2851/2008/3631 +f 2505/3142/4762 2506/2720/4293 2503/2719/4292 +f 3954/3112/4717 3956/3063/4763 3955/3113/4718 +f 3063/1788/3388 2958/1787/3387 2959/2369/3931 +f 4018/2913/4486 4017/3143/4764 4007/2914/4487 +f 2806/1863/4286 2807/1862/3870 2788/2714/4287 +f 2645/3144/4765 2442/3145/4766 2644/3146/4767 +f 1938/2672/4244 1899/3147/4768 1898/3148/4769 +f 1772/3149/4770 1773/3150/4771 1739/2051/4772 +f 2567/2386/3951 2569/3151/4773 2492/3152/4774 +f 2814/1705/3311 2826/3153/4775 2828/1706/3312 +f 2277/3154/4776 2493/3155/4777 2491/3156/4778 +f 2119/2627/4196 2118/3157/4779 2117/3158/4780 +f 2811/3159/4781 2729/2705/4279 2824/3160/4782 +f 3620/2140/4783 3589/3161/4784 3591/2139/4785 +f 3987/3162/4786 3986/3163/4787 3973/2058/3635 +f 3523/3164/4788 3535/3165/4789 3536/3166/4790 +f 2426/3167/2635 2715/2111/2635 2717/3168/2635 +f 3124/2543/4791 3127/3017/4792 3126/2711/4792 +f 2128/2515/4074 2137/3072/4667 2138/2254/3818 +f 1785/2751/4793 1786/2192/4794 1676/1881/4793 +f 3339/3169/4795 3356/2555/4796 3354/2062/4797 +f 2786/3170/4798 2780/1822/4799 2796/1823/3419 +f 3931/2195/3766 3932/3041/4635 4037/3106/4710 +f 3072/2315/3873 2966/3171/4800 3071/2300/3857 +f 3495/3057/4653 3492/2880/4672 3465/2446/4010 +f 3276/3172/4801 3277/3173/4802 3308/2919/4491 +f 2119/2627/4196 2120/3174/4803 2118/3157/4779 +f 2759/2701/4275 2760/3175/4804 2761/2702/4276 +f 2819/2546/4105 2816/2548/4107 2800/3176/4805 +f 2550/3177/4806 2545/3178/4807 2553/3126/4736 +f 3625/1680/3280 3622/1682/3280 3614/1738/3280 +f 3269/3179/4808 3280/2824/4809 3279/2321/4437 +f 3619/3180/4810 3617/3181/4811 3588/3182/4812 +f 3321/3183/4813 3324/3184/4814 3320/3116/3734 +f 3592/3185/4815 3590/3186/4816 3581/3187/4817 +f 3550/3188/4818 3551/2075/3653 3512/3189/4819 +f 2732/1869/4820 2835/3190/4820 2836/2998/4821 +f 3959/2759/3512 3979/3191/3512 3962/2760/3512 +f 3531/1762/3363 3532/2262/3826 3533/1741/3342 +f 3022/2119/3698 3035/1804/3403 3034/1803/3402 +f 3283/1715/3321 3284/2204/3771 3296/3192/4822 +f 1802/3193/4823 1791/2637/4824 1797/2769/4342 +f 2355/3194/4825 2354/3195/4826 2372/3196/4827 +f 2130/2079/3657 2104/3197/4828 2083/1830/3426 +f 4005/3198/4829 4023/2584/4150 4022/3199/4830 +f 3927/3039/4633 3932/3041/4635 3926/2213/4425 +f 3748/3200/4831 3763/2526/4832 3762/2955/4541 +f 2495/3201/4833 2497/3202/4834 2279/3203/4835 +f 2899/3204/4836 2895/3205/4837 2908/2138/3714 +f 3434/2106/3684 3326/2108/3686 3328/3206/4838 +f 3490/3207/4839 3487/3208/4840 3489/2447/4453 +f 1978/3209/4841 1979/3210/4842 1947/3211/4843 +f 1668/2692/4844 1781/3212/4845 1780/3213/4846 +f 1679/1880/3475 1677/2691/3475 1676/1881/3475 +f 1933/3214/4847 2211/2202/3769 2207/2201/3768 +f 2106/2080/3658 2083/1830/3426 1989/1832/3428 +f 3484/2655/4226 3485/3215/4848 3486/2773/4849 +f 2991/2744/4530 2990/2743/4850 2992/2945/4531 +f 2185/3084/4754 1968/3021/4851 2180/2286/3846 +f 2228/3216/4852 2057/3217/4853 2226/3218/4854 +f 1730/2513/4146 1755/2581/4145 1725/2049/3628 +f 2838/3219/4855 2727/3220/4855 2734/3133/4855 +f 3000/1752/3353 2999/3221/4856 2998/1753/3354 +f 3849/2388/3953 3848/2387/3952 3847/2694/4265 +f 2679/1941/3530 2516/3222/4857 2514/3223/4858 +f 3616/3224/4859 3614/1738/4860 3615/3225/4861 +f 3916/2469/4032 3820/3226/4862 3915/3227/4863 +f 3665/1710/3316 3654/3228/4864 3664/1977/3564 +f 3089/2634/4865 3081/1701/3841 3090/3229/4866 +f 2314/3230/4867 2315/3231/4868 2313/3232/4869 +f 3904/3233/4870 3906/1882/3476 3903/3234/4871 +f 4022/3199/4830 4019/2187/3758 4005/3198/4829 +f 2675/3235/4872 2690/2713/4285 2678/3236/4873 +f 1719/2563/4874 1720/3136/4875 1722/3237/4876 +f 3638/2776/4877 3637/1781/4878 3673/3238/4879 +f 3555/3239/4880 3557/2607/4174 3516/2609/4176 +f 2538/3240/4881 2299/3241/4882 2301/3242/4883 +f 2862/1963/3551 2855/3033/4884 2893/1824/3552 +f 2845/2258/3631 2844/2787/3631 2853/2906/4480 +f 2648/3243/4885 2646/2073/3651 2655/3244/4886 +f 3226/2122/4271 3256/3245/4887 3255/3246/4888 +f 2069/2885/4460 2060/1765/4889 2061/2670/4242 +f 3251/2431/3995 3248/2498/4890 3249/3247/4891 +f 2186/2734/4308 2165/2205/3772 2187/3248/4892 +f 2978/2845/4417 3001/2895/4893 3002/2894/4894 +f 2676/3111/4716 2674/2083/3661 2439/2082/3660 +f 2660/3059/4655 2667/3249/4895 2666/3250/4896 +f 3490/3207/3815 3499/2823/3815 3488/3251/3815 +f 3175/3252/4897 3173/2150/3721 3176/2338/3895 +f 3342/3253/3281 3341/3254/3281 3340/1786/3281 +f 3579/3069/3533 3577/2183/3533 3573/3255/3533 +f 3751/3256/4898 3749/2993/4899 3764/1783/3384 +f 1743/2324/3880 1744/1720/3323 1727/2013/3595 +f 2541/2763/4336 2534/3257/4900 2533/2762/4335 +f 2916/3258/4901 2907/3259/4902 2906/1877/3473 +f 1736/2146/4707 1747/1905/3500 1737/2445/4009 +f 2386/2948/4535 2393/3006/4602 2394/3260/4903 +f 2207/2201/3768 2182/2200/3767 2179/3261/4904 +f 2750/3262/4905 2776/1728/4905 2774/1906/4906 +f 2047/2004/3591 2051/3263/4907 2048/3264/4908 +f 2742/3265/4909 2751/3266/4910 2776/1728/4905 +f 2591/3134/4744 2582/3135/4745 2583/2831/4402 +f 3918/3267/4051 3917/3268/4051 3919/3269/4051 +f 3697/1772/3373 3692/1708/3314 3793/1773/3374 +f 2590/1889/3483 2382/2569/4128 2368/2568/4127 +f 2408/3270/4911 2409/3271/4912 2590/1889/3483 +f 2623/3109/4713 2624/3096/4698 2636/2799/4368 +f 3501/3272/4913 3498/3273/4914 3511/3274/4915 +f 2662/3275/4916 2503/2719/4292 2504/2721/4294 +f 3040/3276/4917 3054/2295/3852 3052/1912/3506 +f 1910/3277/4918 1909/3278/4919 1931/2289/3849 +f 2880/3279/4920 2879/2830/4921 2859/3034/4922 +f 2844/2787/4923 2852/2786/4924 2948/3280/4925 +f 3719/2265/4525 3718/2940/4524 3717/3281/4926 +f 2078/3282/4927 2135/3283/4928 2103/3284/4929 +f 3190/2840/4412 3191/2842/4414 3090/3229/4866 +f 3928/3040/4634 3927/3039/4633 3923/3285/4425 +f 3813/3286/4930 3807/3287/4051 3809/3288/4931 +f 3526/2978/4564 3525/3289/4932 3540/2022/3602 +f 3796/1785/3386 3797/1891/3485 3780/2527/4086 +f 1778/2323/3879 1744/1720/3323 1743/2324/3880 +f 2538/3240/4933 2540/3290/4934 2539/3291/4935 +f 2105/3292/4936 2104/3197/4828 2130/2079/3657 +f 2790/3293/4937 2799/2476/4040 2800/3176/4938 +f 3317/3294/4939 3316/2019/4940 3206/3295/4939 +f 1729/2356/3525 1726/2454/4124 1719/2563/3525 +f 3944/2390/4941 3945/3296/4942 3947/3297/4943 +f 2573/2372/3935 2580/2188/3759 2578/3298/4944 +f 2092/1928/3522 2091/2991/4580 1994/2814/4382 +f 3462/2346/3903 3463/3299/4945 3482/2347/3904 +f 3400/1675/3286 3399/3300/4946 3413/3301/4947 +f 3371/2029/3876 3370/2320/3876 3369/3302/3876 +f 2369/1768/3369 2384/2862/4434 2385/3303/4948 +f 3165/3304/4949 3166/3305/4950 3169/2171/3745 +f 2589/2404/3969 2587/2403/3968 2577/2373/3936 +f 2208/3306/4951 1889/3307/4952 1890/3308/4953 +f 3454/2899/4954 3563/3309/4954 3564/3310/4954 +f 3075/1968/3713 3077/1970/3713 3079/2503/3713 +f 2597/3311/4955 2448/3035/4629 2595/2231/3797 +f 3980/3312/3512 3974/3313/3512 3964/3078/3512 +f 3704/2647/4956 3769/2750/4325 3784/2218/3784 +f 3259/3120/3699 3253/2918/3699 3251/2431/3699 +f 1775/3314/4957 1776/3315/4958 1757/3316/4959 +f 2606/3097/4699 2610/3317/4960 2605/3318/4961 +f 3254/2917/4490 3253/2918/3993 3255/3246/4490 +f 2007/3319/4962 1942/3320/4963 2093/2537/4096 +f 2598/3321/4964 2606/3097/4699 2605/3318/4961 +f 2124/3322/4965 2146/3323/4966 2148/1672/3283 +f 2959/2369/3931 2958/1787/3713 2957/3324/3713 +f 2903/2833/3725 2902/3071/3725 2883/3325/3725 +f 2112/1673/3284 2075/2649/4218 2076/3326/4967 +f 2079/1851/3449 2082/2535/4094 2090/2856/4427 +f 1751/1885/3479 1752/3327/4968 1734/1886/3480 +f 1756/2050/4969 1755/2581/4970 1771/3328/4971 +f 3654/3228/4864 3653/2363/4972 3661/1978/3565 +f 3507/3329/4282 3504/2977/4282 3472/3330/4282 +f 3093/3331/4973 3177/3332/4974 3179/3333/4975 +f 3680/2897/4474 3575/3334/4976 3574/3335/4977 +f 3093/3331/4973 3086/2246/3810 3091/3336/3841 +f 2689/3337/4978 2688/2024/3604 2687/2026/3606 +f 2787/3338/4979 2785/3339/3454 2768/2539/4979 +f 3971/2044/3622 3970/2826/4395 3968/2045/3623 +f 3915/3227/4863 3882/3340/4980 3883/3341/4981 +f 2627/2580/4143 2619/2115/3694 2618/3342/4982 +f 3402/2740/4314 3401/1676/3287 3409/3343/4983 +f 3834/2016/4984 3836/2015/4985 3824/3344/4986 +f 2116/3073/4668 2125/2851/4424 2149/2850/4423 +f 2558/3345/4987 2333/3068/4988 2559/3346/4989 +f 3371/2029/4990 3335/2812/4991 3373/2889/4991 +f 3188/1896/3490 3147/3010/4606 3148/1897/3491 +f 2787/3338/4992 2797/2011/3593 2798/2477/4041 +f 2729/2705/3464 2731/3347/3464 2727/3220/3464 +f 1975/2756/4329 1973/2755/4328 2183/2934/4516 +f 3163/1754/4993 3164/2861/4994 3180/3348/4995 +f 1988/3349/4996 1914/3350/4997 1989/1832/3428 +f 4027/3351/4998 4026/2583/4149 3986/3163/4999 +f 3329/3352/5000 3416/3353/5001 3415/2418/3984 +f 2184/2579/4142 2183/2934/4516 1972/2577/4140 +f 2953/2053/5002 2845/2258/5002 2846/2144/5002 +f 2945/2907/4481 2844/2787/4923 2946/2169/3743 +f 1935/2530/4089 2179/3261/4904 2180/2286/3846 +f 2629/2116/3695 2630/3354/5003 2620/2114/3693 +f 2129/3038/4632 2078/3282/4927 2128/2515/4074 +f 3500/2545/4104 3502/2710/5004 3513/2544/4103 +f 3588/3182/3280 3587/3355/5005 3586/2920/3280 +f 2052/1790/3390 2056/3356/5006 2057/3217/5007 +f 2802/2463/4025 2801/3357/5008 2815/2461/4023 +f 3803/1810/3409 3693/1812/3411 3804/3358/3411 +f 1996/2820/4387 1946/2975/4561 2090/2856/4427 +f 3404/1926/3520 3418/1873/3469 3420/3132/4743 +f 1696/3359/5009 1698/2395/3960 1697/3360/5010 +f 1949/2276/5011 1960/2640/4208 1961/3070/4665 +f 1927/3361/5012 2224/1902/2635 2220/1766/2635 +f 1926/3362/5013 1928/3363/5013 2225/3364/5013 +f 3086/2246/3810 3085/2245/3809 3082/1703/3841 +f 2749/3365/3454 2748/3366/3454 2742/3265/3454 +f 3048/3367/5014 3037/2248/3814 3038/2943/4528 +f 1918/3368/2635 2229/3369/2635 2227/3370/2635 +f 3792/3005/4601 3695/3055/4651 3789/3003/4599 +f 2792/3371/5015 2811/3159/4781 2824/3160/4782 +f 3029/3372/5016 3015/2873/5017 3018/3373/5018 +f 3602/2002/3280 3605/2001/3280 3634/2151/3280 +f 3742/3374/5019 3741/1742/5020 3740/2032/3610 +f 2914/3375/5021 2913/2832/5022 2947/3376/5023 +f 2055/1844/3441 2056/3356/5006 2052/1790/3390 +f 2922/3028/4624 2842/3377/5024 2933/2042/3620 +f 3033/2117/3696 3034/1803/3402 3047/2426/3989 +f 1923/2236/3800 1924/3378/2635 2235/3379/2635 +f 3250/2430/4060 3252/2429/5025 3223/3380/5026 +f 2570/2371/3934 2553/3126/4736 2547/3381/5027 +f 3911/2128/3705 3912/3382/5028 3909/2129/3706 +f 3940/2066/3644 3941/1918/3512 3939/1920/3513 +f 3227/2699/5029 3229/2382/3947 3218/2384/3949 +f 3477/2306/5030 3476/1779/4296 3461/2722/4295 +f 3311/1861/3457 3312/2322/3878 3291/2071/3649 +f 4022/3199/4830 4024/2103/3681 4021/2105/3683 +f 2235/3379/5031 2037/2448/4013 2234/2234/5032 +f 3528/3383/5033 3529/3384/5034 3503/3385/5035 +f 3205/1860/3456 3309/2127/3704 3311/1861/3457 +f 3719/2265/4525 3722/2450/5036 3720/1946/4523 +f 2548/2932/4735 2550/3177/4806 2553/3126/4736 +f 3477/2306/3862 3480/3386/5037 3478/2307/3863 +f 3023/3074/3296 3025/3387/3296 2992/2945/3296 +f 3602/2002/3589 3600/1665/3546 3599/1915/3839 +f 2947/3376/5023 2949/2590/4157 2914/3375/5021 +f 2983/2586/4153 2984/2679/5038 2985/2006/4151 +f 1980/3388/5039 1981/3389/5040 1947/3211/4843 +f 2109/1998/5041 2047/2004/5042 2048/3264/5043 +f 3014/3390/5044 2981/2620/4187 2972/3391/5045 +f 3820/3226/4862 3819/3392/5046 3915/3227/4863 +f 3256/3245/5047 3224/3393/5048 3254/2917/5049 +f 2942/3394/5050 2911/3395/5051 2910/1921/3514 +f 2224/1902/3497 2065/2660/5052 2064/3396/5053 +f 3880/1848/5054 3910/3397/5055 3879/1849/5056 +f 2222/3398/5057 2221/3399/5058 2069/2885/5059 +f 1946/2975/4561 1944/2974/4560 1945/2815/4383 +f 2728/3400/3464 2729/2705/3464 2726/3401/3464 +f 2982/3402/5060 2981/2620/5061 3014/3390/5062 +f 3617/3181/5063 3619/3180/5064 3620/2140/4783 +f 2904/2143/3717 2920/2142/3716 2901/3403/5065 +f 2654/3404/5066 2661/2915/4488 2653/1988/3575 +f 3918/3267/5067 3808/3405/5067 3807/3287/5067 +f 2395/3406/5068 2638/2898/4475 2405/3024/4620 +f 3266/3407/3699 3268/2203/5069 3231/3408/3699 +f 1896/3008/4604 2094/2985/4573 1938/2672/4244 +f 3509/2069/3815 3510/2068/3815 3480/3386/3815 +f 2572/3036/4630 2697/3409/5070 2699/3410/5071 +f 3635/3411/3280 3600/1665/3280 3602/2002/3280 +f 3710/3412/3827 3711/3413/3827 3707/3110/5072 +f 1867/3414/5073 1866/2682/5074 2025/3415/5075 +f 3605/2001/3588 3604/3416/3828 3606/2124/3701 +f 2909/3417/5076 2910/1921/3514 2898/1923/3516 +f 3868/1683/3289 3869/2174/3288 3835/2017/3289 +f 3367/3418/5077 3370/2320/5078 3368/3419/5079 +f 3575/3334/4976 3571/3420/5080 3570/2540/5081 +f 3568/3421/5082 3670/3422/5083 3667/2843/4415 +f 2384/2862/4434 2383/2570/4129 2375/2863/4435 +f 3456/2900/4476 3534/3423/5084 3532/2262/3826 +f 2190/3424/5085 2193/3425/5086 2192/3426/5087 +f 3259/3120/4726 3275/2868/5088 3274/2867/4727 +f 3873/3427/3288 3874/3428/3288 3841/1951/3288 +f 1973/2755/5089 1817/3429/5090 1816/1956/5091 +f 1790/2482/4756 2219/3430/5092 1951/2519/4757 +f 3330/3431/3734 3329/3352/5000 3327/2162/3734 +f 2882/2805/5093 2881/2829/4400 2880/3279/5094 +f 1774/3432/5095 1671/3433/5096 1777/2325/3881 +f 3629/2152/3280 3634/2151/3280 3605/2001/3280 +f 2624/3096/4698 2625/3095/4697 2636/2799/4368 +f 1870/2690/5097 2024/2926/5098 2023/2925/5099 +f 1816/1956/3542 1817/3429/5100 1811/1748/3349 +f 2191/2491/4054 1932/2490/4053 2187/3248/4892 +f 2562/2638/5101 2344/3046/5102 2555/1892/3486 +f 2025/3415/5075 1866/2682/5074 2022/2457/4019 +f 2022/2457/4019 1866/2682/5074 1862/2681/5103 +f 3709/3434/5072 3710/3412/3827 3707/3110/5072 +f 2211/2202/3769 1933/3214/4847 2216/2890/4467 +f 3698/2272/3313 3700/2057/3634 3695/3055/4651 +f 1864/2455/4017 2022/2457/4019 1862/2681/5103 +f 2660/3059/4655 2658/3058/4654 2668/3435/5104 +f 2019/3436/5105 2018/2557/4117 2016/2556/4116 +f 3907/1884/3478 3809/3288/4931 3811/3437/5106 +f 3525/3289/4932 3524/3438/5107 3539/2023/3603 +f 3637/1781/3382 3638/2776/4347 3623/1782/3383 +f 3387/2198/3281 3385/1674/3281 3355/2063/3281 +f 3256/3245/5047 3217/3439/5108 3224/3393/5048 +f 4027/3351/4998 4024/2103/3681 4026/2583/4149 +f 2891/1964/5109 2893/1824/3420 2892/3440/5110 +f 3961/3441/5111 3964/3078/5112 3963/3077/5112 +f 2497/3202/4834 2498/3012/4608 2282/2911/4610 +f 3511/3274/4915 3503/3385/5035 3529/3384/5034 +f 3459/2250/3815 3458/2810/3815 3464/2251/3815 +f 3515/2459/4021 3554/2458/4020 3555/3239/4880 +f 1746/3104/4706 1732/2145/4708 1733/2014/3596 +f 2733/1868/5113 2735/1845/3442 2829/2012/3594 +f 3398/3049/5114 3397/3442/5115 3411/3443/5116 +f 3801/3444/3313 3803/1810/3313 3805/2512/3313 +f 1746/3104/4706 1780/3213/4846 1781/3212/4845 +f 3912/3382/5028 3913/3445/5117 3813/3286/4930 +f 2688/2024/3604 2689/3337/4978 2690/2713/4285 +f 3017/2118/3296 3018/3373/3296 3010/3446/3296 +f 3935/2510/4070 3934/3032/4627 4014/2312/3868 +f 2966/3171/3713 2961/2837/3713 2963/1969/3713 +f 3143/2374/3937 3141/1756/3357 3161/2337/4532 +f 3678/2896/4473 3677/2496/4056 3571/3420/5080 +f 2962/3447/5118 2971/3448/5119 3058/3449/5120 +f 2666/3250/4896 2450/3450/5121 2449/2668/4240 +f 3648/3451/5122 3634/2151/3722 3647/3452/5123 +f 2796/1823/3419 2797/2011/3593 2786/3170/4798 +f 2972/3391/5045 2980/2791/4360 3012/3453/5124 +f 3420/3132/4743 3419/2834/4406 3421/2836/4408 +f 3018/3373/3296 3013/2874/3296 3010/3446/3296 +f 3469/2367/3927 3468/3454/5125 3459/2250/3928 +f 2832/1847/3444 2800/3176/4805 2799/2476/4040 +f 2113/2366/3925 2106/2080/3658 1930/3455/5126 +f 3675/1794/3394 3638/2776/4877 3673/3238/4879 +f 2672/3456/5127 2676/3111/4716 2675/3235/4872 +f 2676/3111/4716 2690/2713/4285 2675/3235/4872 +f 3270/3457/3699 3269/3179/3699 3241/3079/3699 +f 2324/3458/5128 2321/2931/4513 2551/2930/4512 +f 3499/2823/4391 3514/2460/4022 3515/2459/4392 +f 3976/3092/4694 3974/3313/5129 3991/3459/5130 +f 3779/3460/5131 3762/2955/4541 3790/2954/4540 +f 3259/3120/3699 3251/2431/3699 3249/3247/5069 +f 3221/2242/3806 3242/2241/3805 3243/3461/5132 +f 1818/1749/3642 1974/2754/5133 1977/2065/3643 +f 1974/2754/5133 1818/1749/3642 1817/3429/5090 +f 1973/2755/5089 1816/1956/5091 1810/1955/5134 +f 3531/1762/3363 3533/1741/3342 3520/1763/3364 +f 1948/2933/5135 1809/3462/5136 1807/3463/5137 +f 1948/2933/5135 1807/3463/5137 1806/3464/5138 +f 1971/2989/5139 1812/2582/5140 1972/2577/5141 +f 1972/2577/5141 1812/2582/5140 1814/1695/5142 +f 3009/2793/5143 3010/3446/5144 3011/3465/5145 +f 1806/3464/5138 1971/2989/5139 1970/2994/5146 +f 2014/3466/5147 2015/3467/5148 2013/2401/3966 +f 2107/2484/4048 2110/3468/5149 2046/3469/5150 +f 2115/2472/4036 2114/2471/4035 2206/3470/5151 +f 1965/3471/5152 1803/3020/4616 1801/3472/5153 +f 2601/3473/5154 2449/2668/4240 2450/3450/5121 +f 3763/2526/4085 3764/1783/3384 3780/2527/4086 +f 1956/2334/3890 1796/3474/5155 1958/3475/5156 +f 3687/2181/5157 3570/2540/5157 3686/1945/5157 +f 2454/3476/5158 2324/3458/5128 2552/3477/5159 +f 3356/2555/4115 3357/3478/5160 3358/2554/4114 +f 2770/3479/5161 2773/1907/3502 2771/2797/5162 +f 2976/1688/3296 2977/1798/4251 2978/2845/3296 +f 3446/2817/3558 3454/2899/3558 3447/2818/4385 +f 2815/2461/4023 2820/2547/4106 2821/2462/4024 +f 1795/2636/4203 1958/3475/5156 1796/3474/5155 +f 1755/2581/4970 1769/2216/3782 1771/3328/4971 +f 3233/3480/5163 3230/2383/5164 3232/3481/5165 +f 2983/2586/4153 2981/2620/5061 2982/3402/5060 +f 3581/3187/3280 3588/3182/3280 3584/2165/3280 +f 3611/2109/5166 3586/2920/4492 3587/3355/5167 +f 2889/3482/3592 2892/3440/5168 2890/3483/3592 +f 2028/3484/5169 2027/2101/3679 1873/2360/3919 +f 3121/2304/5170 3119/2303/5171 3120/2177/5172 +f 3458/2810/4379 3497/2809/4378 3495/3057/4653 +f 3617/3181/4811 3615/3225/5173 3588/3182/4812 +f 3644/2290/5174 3628/3485/5175 3631/2950/5176 +f 3144/2179/3932 3155/2329/3885 3139/3486/5177 +f 3164/2861/4433 3136/2281/4432 3165/3304/5178 +f 3035/1804/3403 3021/3487/5179 3026/1797/3812 +f 2862/1963/3725 2861/3488/3725 2859/3034/3725 +f 2513/2224/3790 2510/2443/5180 2511/2225/3791 +f 2136/3489/5181 2101/3490/5182 2135/3283/4928 +f 2097/2536/4095 2089/2732/4306 2098/2500/4062 +f 2851/2008/3592 2954/2052/3592 2955/2009/3592 +f 3817/2488/4052 3818/2413/4052 3821/2489/4051 +f 2884/2804/4373 2860/2806/4375 2885/3491/5183 +f 2236/3492/5184 1881/2724/5185 1879/2723/5186 +f 2036/2847/5187 2035/3493/5188 2236/3492/5184 +f 3008/3128/4738 3010/3446/5144 3009/2793/5143 +f 2872/2154/3725 2874/3494/3725 2907/3259/3725 +f 3954/3112/3512 3952/2327/3512 3983/2466/3512 +f 3237/3054/4650 3234/3495/5189 3236/3052/4648 +f 2243/2441/5190 2242/3496/5191 2244/3497/5192 +f 2244/3497/5192 2242/3496/5191 2245/2259/3823 +f 3762/2955/4541 3763/2526/4085 3795/1771/3372 +f 2841/3498/5193 2847/2764/4337 2935/2406/3971 +f 2238/3499/5194 2247/3500/5195 2248/3501/5196 +f 2238/3499/5194 2248/3501/5196 2249/3502/5197 +f 2249/3502/5197 2248/3501/5196 2246/3503/5198 +f 2237/3504/5199 2251/3505/5200 2252/2605/4172 +f 2252/2605/4172 2251/3505/5200 2253/2606/4173 +f 3877/1809/5201 3878/3506/5202 3908/1883/3477 +f 3510/2068/3815 3508/3507/4282 3478/2307/4282 +f 2078/3282/4927 2077/2402/3967 2135/3283/4928 +f 3434/2106/3684 3433/1993/3580 3407/1992/3579 +f 2396/3508/5203 2638/2898/4475 2395/3406/5068 +f 2259/3509/5204 2261/3510/5205 2260/3511/5206 +f 2260/3511/5206 2261/3510/5205 2262/3512/5207 +f 2262/3512/5207 2261/3510/5205 2263/3513/5208 +f 2316/1816/3412 2313/3232/4869 2315/3231/4868 +f 2543/3514/5209 2539/3291/4935 2570/2371/3934 +f 2270/3515/5210 2263/3513/5208 2269/3516/5211 +f 3319/3517/5212 3321/3183/4813 3320/3116/3734 +f 3890/3518/5213 3891/2986/4574 3899/2988/4576 +f 2177/3519/5214 2189/3520/5215 2178/3521/5216 +f 3899/2988/4576 3900/1985/3572 3898/1984/3571 +f 3654/3228/4864 3626/3522/5217 3627/2361/3920 +f 2642/3523/5218 2511/2225/3791 2440/3524/5219 +f 1992/2811/4380 1991/1930/3524 1993/1929/3523 +f 2274/1898/3492 2273/3525/5220 2275/2729/4302 +f 3513/2544/4103 3552/2077/3655 3553/2542/4101 +f 2265/3526/5221 2277/3154/5222 2278/3527/5223 +f 1800/3528/5224 1965/3471/5152 1801/3472/5153 +f 2197/3529/5225 2175/3530/5226 2174/1791/3391 +f 3072/2315/3873 2960/2983/4570 2966/3171/4800 +f 3382/1965/3554 3377/3531/5227 3392/3087/4688 +f 3210/2736/4310 3209/1828/3361 3208/2018/5228 +f 2306/2592/4159 2307/3532/5229 2305/2593/4160 +f 3048/3367/5014 2968/2942/4527 3049/2506/4066 +f 2173/1997/3584 2052/1790/3390 2050/2003/3590 +f 3787/2055/3632 3782/2748/4323 3781/1759/3360 +f 3059/3533/5230 3057/2336/3893 3056/2294/3851 +f 3088/3534/4865 3089/2634/4865 3092/2957/4543 +f 3714/1744/3827 3705/3535/3827 3711/3413/3827 +f 3886/2407/4595 3887/2839/5231 3895/2414/3980 +f 2534/3257/5232 2300/2377/5233 2297/2376/5234 +f 2878/1727/3725 2894/1878/3725 2906/1877/3725 +f 3732/2293/3827 3754/2292/3827 3734/3536/3827 +f 2461/1975/3562 2413/3537/5235 2414/3538/5236 +f 3563/3309/5237 3449/3098/5238 3562/3539/5238 +f 2653/1988/3575 2599/2233/3799 2652/1989/3576 +f 2286/3540/3307 2287/1699/3307 2288/1698/3306 +f 2366/3541/5239 2364/3542/5240 2387/2411/3977 +f 2488/3543/5241 2567/2386/3951 2492/3152/4774 +f 2292/3544/5242 2291/3545/5243 2293/2596/4163 +f 2133/2516/4075 2128/2515/4074 2078/3282/4927 +f 1825/2621/4190 1824/3546/5244 1834/2619/4186 +f 1760/3547/5245 1762/3091/4692 1761/3548/5246 +f 2294/2595/4162 2295/2597/4164 2290/2700/4274 +f 3931/2195/3766 4037/3106/4710 4038/1838/3435 +f 3716/3549/5247 3746/3550/5248 3747/3551/5249 +f 3436/3552/5250 3393/1966/3555 3435/2560/4120 +f 2696/2972/4558 2690/2713/4285 2698/3553/5251 +f 2020/3554/5252 2019/3436/5105 1859/2766/4339 +f 1913/3555/5253 1930/3455/5126 2106/2080/3658 +f 3391/2559/4119 3390/1991/3578 3433/1993/3580 +f 3467/3556/5254 3466/2808/5255 3468/3454/5256 +f 3375/1806/3281 3378/3557/3281 3372/2028/3281 +f 3396/3558/5257 3395/3559/5258 3322/3560/5259 +f 3805/2512/3313 3806/2271/5260 3802/3561/3313 +f 3601/2164/3737 3599/1915/3509 3584/2165/3738 +f 2176/3562/5261 2172/3563/5262 2175/3530/5226 +f 3078/2838/5263 2961/2837/5263 2969/3564/5263 +f 2309/3565/5264 2308/3566/5265 2310/3567/5266 +f 3812/3568/5267 3810/3569/5268 3920/3570/5268 +f 3322/3560/5259 3333/3571/5269 3396/3558/5257 +f 3660/1733/3336 3656/2758/4331 3651/1731/3334 +f 3325/3572/5270 3440/3573/5270 3323/3574/5270 +f 2617/1888/3482 2581/1890/3484 2591/3134/4744 +f 2147/3575/5271 2145/3576/5272 2110/3468/5149 +f 3633/1666/4263 3650/1732/3335 3651/1731/4264 +f 3476/1779/3380 3478/2307/3863 3475/1777/3378 +f 1839/2626/4195 1840/2629/4198 1836/2623/4192 +f 2875/2903/5273 2876/1726/3329 2874/3494/5274 +f 2348/2309/5275 2349/3577/5276 2350/3578/5277 +f 2323/3579/5278 2324/3458/5279 2325/3580/5280 +f 2325/3580/5280 2324/3458/5279 2326/3581/5281 +f 2325/3580/5280 2326/3581/5281 2327/2421/3987 +f 2329/2419/3985 2327/2421/3987 2326/3581/5281 +f 2904/2143/3725 2901/3403/3725 2869/3582/3725 +f 2134/3121/4728 2105/3292/4936 2130/2079/3657 +f 2328/2420/3986 2329/2419/3985 2330/2980/4567 +f 3397/3442/5115 3396/3558/5257 3412/3583/5282 +f 3958/2067/3645 3960/2761/5283 3940/2066/3644 +f 2641/3584/5284 2642/3523/5218 2443/2962/4548 +f 3210/2736/4310 3204/1723/3326 3302/2227/3793 +f 2336/3585/5285 2335/3066/4661 2337/3586/5286 +f 2337/3586/5286 2335/3066/4661 2338/3587/5287 +f 2337/3586/5286 2338/3587/5287 2339/3588/5288 +f 2339/3588/5288 2338/3587/5287 2340/1894/5289 +f 1897/3589/5290 1896/3008/4604 1938/2672/4244 +f 2202/3590/5291 2121/2365/3924 2205/2364/3923 +f 2341/3591/5292 2342/1893/5293 2343/3045/4639 +f 3824/3344/3288 3825/3592/3289 3826/2936/3289 +f 2953/2053/3631 2952/3593/3631 2950/2054/3631 +f 3190/2840/4412 3189/1895/3489 3149/2344/3901 +f 2808/2314/5294 2823/2180/3752 2809/2704/4278 +f 1728/2133/3525 1729/2356/3525 1719/2563/3525 +f 3675/1794/3394 3639/1793/3393 3638/2776/4877 +f 3030/3594/5295 3031/3595/5296 3065/3596/5297 +f 2856/2572/4131 2857/3597/5298 2868/2573/4132 +f 2731/3347/3464 2736/1864/3465 2734/3133/3464 +f 3773/3598/5299 3761/3599/5300 3759/2451/5301 +f 2188/3600/5302 2192/3426/5087 2191/2491/4054 +f 3368/3419/3281 3370/2320/3281 3382/1965/3281 +f 2356/3601/5303 2355/3194/4825 2370/2717/4290 +f 2370/2717/4290 2355/3194/4825 2371/3602/5304 +f 1977/2065/5305 1974/2754/4327 2071/3603/5306 +f 2278/3527/5223 2277/3154/5222 2279/3203/5307 +f 2373/3604/5308 2372/3196/4827 2374/2864/4436 +f 2375/2863/4435 2376/3605/5309 2374/2864/4436 +f 2374/2864/4436 2376/3605/5309 2377/3606/5310 +f 1985/2781/4352 1884/3607/5311 1984/3608/5312 +f 2376/3605/5309 2379/3609/5313 2380/2949/5314 +f 1791/2637/5315 1795/2636/5316 1796/3474/5317 +f 3418/1873/3469 3417/1875/3471 3420/3132/4743 +f 2889/3482/3592 2888/3610/5318 2887/3611/5319 +f 2193/3425/5086 2200/2046/3625 2201/3612/5320 +f 2168/2206/3773 2165/2205/3772 2186/2734/4308 +f 2247/3500/5195 2242/3496/5191 2243/2441/5190 +f 3090/3229/4866 3092/2957/4543 3089/2634/4865 +f 3573/3255/5321 3577/2183/5322 3688/2182/5322 +f 3013/2874/5323 3012/3453/5324 3011/3465/5145 +f 2874/3494/3725 2877/1725/3725 2907/3259/3725 +f 2381/3613/5325 2375/2863/4435 2383/2570/4129 +f 2797/2011/3593 2787/3338/4992 2786/3170/4798 +f 3565/1833/3429 3444/1835/3431 3452/3614/3429 +f 1848/2645/4216 1849/3615/5326 1847/2643/4214 +f 1987/2288/3848 1908/2287/3847 1907/3616/5327 +f 3981/3617/5328 4002/2464/4026 3983/2466/4028 +f 2646/2073/3651 2648/3243/4885 2647/1987/3574 +f 1858/2767/5329 2073/2456/4018 1864/2455/4017 +f 2175/3530/5226 2172/3563/5262 2163/3618/5330 +f 2014/3466/5147 2072/2803/4372 2017/2558/4118 +f 3661/1978/3565 3652/2757/4330 3656/2758/4331 +f 1811/1748/3349 1808/3619/5331 1810/1955/3541 +f 3588/3182/4812 3615/3225/5173 3613/2110/5332 +f 3416/3353/5001 3330/3431/5333 3419/2834/4406 +f 3312/2322/3878 3279/2321/3877 3280/2824/4393 +f 2366/3541/5239 2389/3620/5334 2386/2948/4535 +f 3058/3449/5120 3062/2393/3958 2962/3447/5118 +f 1714/3621/5335 1711/2353/5336 1713/3622/5337 +f 3773/3598/5299 3772/2230/5338 3761/3599/5300 +f 2744/3623/5339 2745/3624/5340 2757/3625/5341 +f 3112/3626/5342 3111/3627/5343 3113/3628/5344 +f 2838/3219/3464 2837/2999/3464 2833/3629/3464 +f 2376/3605/5309 2386/2948/4535 2389/3620/5334 +f 3299/1774/3375 3211/1760/5345 3213/1775/3376 +f 3782/2748/4323 3787/2055/3632 3773/3598/5299 +f 2576/2973/4559 2574/2639/4207 2575/2370/3933 +f 3717/3281/5346 3707/3110/4714 3706/3630/5347 +f 3508/3507/5348 3523/3164/5349 3524/3438/5350 +f 2846/2144/5351 2845/2258/3631 2853/2906/4480 +f 2717/3168/2635 2718/3631/2635 2426/3167/2635 +f 3473/3632/5352 3474/1778/3379 3475/1777/3378 +f 4013/3102/4702 4015/2313/3869 4014/2312/3868 +f 2493/3155/4777 2264/3633/5353 2494/3634/5354 +f 2920/2142/3716 2921/3029/5355 2901/3403/5065 +f 2723/3635/5356 2506/2720/5357 2721/1954/5358 +f 3260/3636/5359 3259/3120/4726 3273/3119/4725 +f 2228/3216/4852 2227/3370/5360 2049/2879/5361 +f 2397/3637/5362 2398/3638/5363 2460/3639/5364 +f 3030/3594/5365 3018/3373/5018 3031/3595/5366 +f 2883/3325/3725 2886/3640/5367 2903/2833/3725 +f 3859/3641/5368 3860/1677/5368 3862/2935/5369 +f 2763/3642/3454 2791/2687/3454 2761/2702/3454 +f 2990/2743/4318 2975/2742/4317 2988/3643/5370 +f 3720/1946/3534 3708/1948/3536 3718/2940/4715 +f 2483/1690/3298 2486/3644/5371 2261/3510/5372 +f 2738/3000/3464 2740/3645/5373 2730/3123/3464 +f 3937/2392/3512 3938/2966/3512 3939/1920/3513 +f 3538/2036/3614 3536/3166/4790 3457/2941/5374 +f 3010/3446/5144 3013/2874/5323 3011/3465/5145 +f 1985/2781/4352 2211/2202/3769 2210/2683/4255 +f 3477/2306/3862 3479/3646/5375 3480/3386/5037 +f 2114/2471/4035 2120/3174/4803 2122/3647/5376 +f 3638/2776/4347 3639/1793/5377 3624/2777/4348 +f 3432/2107/3685 3407/1992/3579 3389/1807/5378 +f 2622/2969/4555 2632/2968/4554 2445/3648/5379 +f 4009/2952/4538 4008/3649/5380 4010/2379/3944 +f 1774/3432/5095 1777/2325/3881 1776/3315/4958 +f 3508/3507/4282 3507/3329/4282 3475/1777/4282 +f 1750/3090/4691 1763/3065/4660 1764/3650/5381 +f 3329/3352/5000 3334/2163/3735 3327/2162/3734 +f 3935/2510/4070 4016/2311/3867 4019/2187/3758 +f 2387/2411/3977 2388/3651/5382 2389/3620/5334 +f 2928/3652/5383 2918/1961/5384 2926/3653/5385 +f 2049/2879/4452 2051/3263/4907 2050/2003/3590 +f 2678/3236/4873 2691/2712/4284 2671/2092/3671 +f 3019/2007/3296 3024/3075/3296 2987/2005/3296 +f 3884/3654/5386 3883/3341/5387 3872/2564/5388 +f 2622/2969/4555 2445/3648/5379 2633/3655/5389 +f 4003/2185/5390 4002/2464/4026 3981/3617/5328 +f 4035/2256/3820 4036/2255/3819 4038/1838/3435 +f 3559/3122/4729 3532/2262/3826 3519/1764/3365 +f 2781/3656/5391 2793/2239/3803 2794/2238/3802 +f 3262/2417/3983 3285/2416/3982 3266/3407/5392 +f 3449/3098/3558 3446/2817/3558 3455/2819/4386 +f 3227/2699/4273 3228/2698/4272 3229/2382/5393 +f 3867/1679/3447 3865/3657/5394 3880/1848/3445 +f 3923/3285/5395 4040/2852/5395 3924/2707/5396 +f 3989/3093/4695 3988/3658/5397 3975/1934/4693 +f 3728/3659/5398 3726/3660/5399 3727/3661/5400 +f 2258/3662/5401 2257/3663/5402 2256/1691/5403 +f 3360/3664/5404 3359/3665/5405 3340/1786/5406 +f 1845/3666/5407 1844/3667/5408 1846/2644/4215 +f 2764/2221/3909 2762/3668/5409 2746/2352/3910 +f 2484/3669/5410 2482/1689/3297 2253/2606/5411 +f 3362/2958/4544 3365/2960/4546 3363/3670/4544 +f 3798/3671/5412 3799/3672/5413 3800/3037/4631 +f 3974/3313/5129 3992/2257/5414 3991/3459/5130 +f 3347/1815/4704 3346/3673/5415 3348/3103/4705 +f 3259/3120/3699 3260/3636/3699 3253/2918/3699 +f 1791/2637/5315 1794/2333/4121 1798/2467/4123 +f 3156/2330/3886 3157/2747/5416 3170/3674/5417 +f 2495/3201/5418 2496/3675/5419 2497/3202/5420 +f 2607/2399/3964 2629/2116/3695 2628/2400/3965 +f 2499/3676/5421 2496/3675/5419 2500/3677/5422 +f 2575/2370/3933 2693/2131/3708 2695/2130/3707 +f 2501/3013/5423 2498/3012/5424 2502/2921/5425 +f 3929/2511/4071 3935/2510/4070 4019/2187/3758 +f 3651/1731/4264 3652/2757/5426 3632/2362/3921 +f 2507/2442/5427 2508/2113/5428 2509/3678/5429 +f 2507/2442/5427 2509/3678/5429 2510/2443/5180 +f 3946/2391/5430 3947/3297/4943 3950/3679/5431 +f 1751/1885/3479 1735/1887/3481 1750/3090/4691 +f 2615/2662/4235 2619/2115/3694 2620/2114/3693 +f 2512/2223/3789 2515/2532/5432 2513/2224/3790 +f 2517/2533/5433 2516/3222/4857 2518/3026/5434 +f 1741/2357/5435 1740/2135/3712 1775/3314/4957 +f 2781/3656/3454 2782/3680/3454 2777/1730/3454 +f 3418/1873/3469 3403/1924/3518 3408/1874/3470 +f 2791/2687/4259 2803/2686/4258 2789/2785/4356 +f 2525/3681/5436 2526/2876/5437 2527/2675/5438 +f 2639/1994/3581 2637/3682/5439 2638/2898/4475 +f 3580/2210/3533 3574/3335/3533 3569/3683/3533 +f 1860/3684/5440 1859/2766/4339 1863/2768/4341 +f 2049/2879/5361 2053/2878/5441 2228/3216/4852 +f 3124/2543/4791 3125/3685/4791 3127/3017/4792 +f 3781/1759/3360 3775/1758/3359 3788/2056/3633 +f 3578/2211/3779 3579/3069/5442 3658/3686/5443 +f 2901/3403/3725 2900/2156/3725 2866/3001/3725 +f 2539/3291/4935 2540/3290/4934 2541/2763/4336 +f 2636/2799/4368 2637/3682/5439 2446/3687/5444 +f 2097/2536/4095 2082/2535/4094 2096/2733/4307 +f 1674/3688/5445 1678/3689/5446 1778/2323/3879 +f 1869/2689/4261 1868/3690/5447 1867/3414/5448 +f 3053/1913/3507 3052/1912/3506 3055/2335/3892 +f 3926/2213/4425 3931/2195/4425 3934/3032/4627 +f 2720/2112/2635 2715/2111/2635 2427/1952/3540 +f 1773/3150/4771 1774/3432/5095 1740/2135/3712 +f 3396/3558/5449 3397/3442/5450 3386/2197/4644 +f 1738/2495/3525 1735/1887/3525 1700/2397/3525 +f 3358/2554/4114 3357/3478/5160 3359/3665/5451 +f 3316/2019/3361 3317/3294/3361 3313/3691/3361 +f 3885/2408/3974 3884/3654/5386 3870/3692/5452 +f 2580/2188/3759 2585/2190/3761 2584/3693/5453 +f 2741/1846/3443 2740/3645/5373 2817/3694/5454 +f 2998/1753/3354 2996/2928/5455 2997/1751/3352 +f 2863/1825/4566 2893/1824/3552 2855/3033/4884 +f 2140/1671/3282 2152/2252/3816 2124/3322/4965 +f 3036/2508/4068 3026/1797/3812 3037/2248/3814 +f 3760/2291/5456 3761/3599/5300 3771/2229/5457 +f 2609/3695/5458 2603/2405/3970 2604/3696/5459 +f 2801/3357/5008 2816/2548/4107 2815/2461/4023 +f 2598/3321/4964 2601/3473/5154 2626/3697/5460 +f 3294/2316/3874 3295/3698/5461 3296/3192/4822 +f 1805/2074/4682 2185/3084/4681 1969/2578/5462 +f 3846/1718/4267 3849/2388/3953 3847/2694/4265 +f 1748/2444/4008 1759/1904/3499 1761/3548/5246 +f 3993/1839/3436 4038/1838/3435 4036/2255/3819 +f 2492/3152/5463 2569/3151/5463 2491/3156/5463 +f 2160/3699/5464 2159/3700/5465 2161/3701/5466 +f 2509/3678/5429 2508/2113/5428 2505/3142/4762 +f 2086/3011/4607 2095/1850/3448 2094/2985/4573 +f 3040/3276/4917 3041/3076/5467 3054/2295/3852 +f 2487/3702/5468 2271/1899/3493 2485/3703/5469 +f 3572/2844/4416 3573/3255/3533 3567/2267/5470 +f 2319/2961/4547 2321/2931/5471 2322/3704/5472 +f 3617/3181/5063 3618/3705/5473 3616/3224/4859 +f 2545/3178/4807 2544/3706/5474 2553/3126/4736 +f 1674/3688/3475 1671/3433/5096 1665/3031/3475 +f 3028/3707/5475 3029/3372/5476 3063/1788/3388 +f 3544/3708/5477 3527/2976/4562 3542/3709/5478 +f 3261/2121/5479 3287/3710/5480 3262/2417/3983 +f 3212/3711/3362 3211/1760/3361 3203/1761/3362 +f 3948/2882/5481 3946/2391/5430 3950/3679/5431 +f 3893/1685/3295 3894/1684/3294 3903/3234/4871 +f 3689/1944/5482 3567/2267/5482 3573/3255/5483 +f 3523/3164/4788 3522/1739/3340 3535/3165/4789 +f 3711/3413/5484 3731/3712/5485 3733/3713/5486 +f 2866/3001/4594 2867/2571/4593 2869/3582/5487 +f 3683/2040/3618 3578/2211/3779 3657/2038/3616 +f 3848/2387/4742 3850/2389/5488 3828/3130/4740 +f 3132/3714/5489 3146/3715/5490 3166/3305/4950 +f 1765/2035/3613 1752/3327/5491 1751/1885/3479 +f 2915/1876/3472 2914/3375/5021 2949/2590/4157 +f 3864/1808/3407 3863/2428/3991 3877/1809/3408 +f 3140/3716/5492 3139/3486/5177 3154/2158/3731 +f 3762/2955/4541 3779/3460/5131 3748/3200/4831 +f 3231/3408/3699 3228/2698/3699 3262/2417/3699 +f 3264/3717/5493 3276/3172/5494 3259/3120/4726 +f 2676/3111/4716 2672/3456/5127 2674/2083/3661 +f 2817/3694/5454 2818/3139/4751 2819/2546/4105 +f 2908/2138/3714 2895/3205/4837 2896/3718/5495 +f 3277/3173/4802 3278/2125/3702 3308/2919/4491 +f 2385/3303/4948 2384/2862/4434 2372/3196/4827 +f 1697/3360/3525 1700/2397/3525 1734/1886/3525 +f 3881/3719/5496 3882/3340/4980 3914/3720/5497 +f 3029/3372/5476 3064/1789/3389 3063/1788/3388 +f 3486/2773/3815 3488/3251/3815 3506/2771/3815 +f 2919/2141/3715 2904/2143/3717 2905/1962/5498 +f 3502/2710/5004 3512/3189/5499 3513/2544/4103 +f 2958/1787/3713 2965/2136/3713 2956/2137/3713 +f 2970/3099/5500 2960/2983/4570 3074/2507/4067 +f 2871/2167/3740 2874/3494/5274 2872/2154/3741 +f 2239/2261/5501 2241/3721/5502 2477/2552/5503 +f 2992/2945/4531 2990/2743/4850 2989/3722/5504 +f 2630/3354/5003 2608/3723/5505 2609/3695/5458 +f 2782/3680/3454 2780/1822/3454 2775/2196/3454 +f 2735/1845/3442 2830/3724/5506 2829/2012/3594 +f 1787/2191/3475 1786/2192/3475 1782/2753/3475 +f 1805/2074/4682 1969/2578/5462 1815/1697/5507 +f 2531/2475/4039 2674/2083/3661 2672/3456/5127 +f 1846/2644/5508 2006/2502/5509 2010/2501/5510 +f 2780/1822/3454 2786/3170/4979 2771/2797/3454 +f 2610/3317/4960 2630/3354/5003 2609/3695/5458 +f 3570/2540/4099 3566/2266/4100 3684/2541/4100 +f 3225/3725/5511 3256/3245/4887 3226/2122/4271 +f 3563/3309/3559 3562/3539/3559 3565/1833/3559 +f 3869/2174/3748 3891/2986/5512 3873/3427/5513 +f 2634/1996/3583 2464/3726/5514 2463/2524/4083 +f 3874/3428/5515 3889/3727/5516 3888/2598/5517 +f 2963/1969/4409 3078/2838/4409 3077/1970/4409 +f 1945/2815/4383 1994/2814/4382 1946/2975/4561 +f 3586/2920/3280 3585/3728/5005 3584/2165/3280 +f 2768/2539/4979 2769/3729/3454 2787/3338/4979 +f 3511/3274/4915 3529/3384/5034 3546/2601/4168 +f 2719/3730/5518 2506/2720/5357 2505/3142/5519 +f 3443/2317/3559 3449/3098/3558 3450/2318/3875 +f 3826/2936/4518 3825/3592/5520 3842/3731/5521 +f 2284/3081/4678 2705/3732/5522 2528/2473/4676 +f 3105/2098/3676 3130/1957/3676 3106/1959/3726 +f 3195/2331/3887 3167/2159/3732 3155/2329/3885 +f 2062/1767/5523 2063/2661/4234 2060/1765/4889 +f 2461/1975/3562 2579/3733/5524 2413/3537/5235 +f 2949/2590/4157 2948/3280/4925 2852/2786/4924 +f 2899/3204/3725 2898/1923/3725 2890/3483/3725 +f 2178/3521/5216 2167/3734/5525 2177/3519/5214 +f 3336/1670/5526 3337/1669/5527 3348/3103/5528 +f 3939/1920/3513 3957/3735/5529 3958/2067/3645 +f 3218/2384/3949 3217/3439/5108 3225/3725/5530 +f 1746/3104/4706 1733/2014/3596 1745/1719/5531 +f 2021/3736/5532 1857/2522/5533 2015/3467/5534 +f 2100/3737/5535 2087/2971/4557 2102/3738/5536 +f 2593/3105/4709 2585/2190/3761 2586/2189/3760 +f 3264/3717/5493 3263/2865/4439 3278/2125/4438 +f 3309/2127/3704 3308/2919/4491 3278/2125/3702 +f 3113/3628/5344 3111/3627/5343 3110/2282/5537 +f 3574/3335/3533 3575/3334/4976 3569/3683/3533 +f 2780/1822/3418 2782/3680/5538 2795/1704/3310 +f 3261/2121/3699 3228/2698/3699 3226/2122/3699 +f 2600/2667/4239 2598/3321/4964 2595/2231/3797 +f 3937/2392/3957 3949/2326/4457 3938/2966/4552 +f 2300/2377/3942 2299/3241/5539 2305/2593/5540 +f 1727/2013/4124 1733/2014/3525 1714/3621/3525 +f 3366/3082/4679 3367/3418/5077 3368/3419/5079 +f 2869/3582/3725 2901/3403/3725 2866/3001/3725 +f 2638/2898/4475 2637/3682/5439 2635/2798/4367 +f 2158/2669/4241 2063/2661/4234 2160/3699/5464 +f 1768/2078/3656 1672/2727/4301 1770/3739/5541 +f 2040/1911/3505 2039/3740/5542 2108/2790/4359 +f 1791/2637/4204 1788/2483/5543 1952/2738/5544 +f 1741/2357/3915 1729/2356/3914 1728/2133/5545 +f 3081/1701/3841 3084/2280/3843 3090/3229/4866 +f 1914/3350/4997 1913/3555/5253 1989/1832/3428 +f 2326/3581/5546 2453/3741/5547 2452/3742/5548 +f 2770/3479/5161 2771/2797/5162 2769/3729/5549 +f 3373/2889/4991 3335/2812/4991 3336/1670/5526 +f 3606/2124/5550 3604/3416/5551 3585/3728/5552 +f 4008/3649/5380 3998/3743/5553 4012/2380/3945 +f 1918/3368/2635 1921/3744/2635 2229/3369/2635 +f 2584/3693/5453 2583/2831/4402 2582/3135/4745 +f 3150/2841/5554 3149/2344/5555 3135/2343/3900 +f 1981/3389/5040 1982/3745/5556 1947/3211/4843 +f 3648/3451/5557 3647/3452/5558 3658/3686/5443 +f 3452/3614/5559 3564/3310/5560 3565/1833/5559 +f 3700/2057/3634 3702/3746/5561 3787/2055/3632 +f 2140/1671/3282 2076/3326/4967 1939/3747/5562 +f 3396/3558/5257 3333/3571/5269 3412/3583/5282 +f 2216/2890/4467 1932/2490/4053 2194/2492/4055 +f 3447/2818/4385 3558/2608/4175 3557/2607/4174 +f 3303/2226/3792 3272/3748/5563 3304/3749/5564 +f 1739/2051/4772 1756/2050/4969 1772/3149/4770 +f 1802/3193/4823 1804/3022/5565 1805/2074/3652 +f 2105/3292/4936 2134/3121/4728 2133/2516/4075 +f 2732/1869/5566 2833/3629/5566 2835/3190/5566 +f 2505/3142/4762 2644/3146/4767 2509/3678/5429 +f 2842/3377/5024 2841/3498/5193 2933/2042/3620 +f 2050/2003/3590 2109/1998/3585 2173/1997/3584 +f 3999/3100/5567 3985/3062/5568 4000/3101/5569 +f 3055/2335/3892 3054/2295/3852 3056/2294/3851 +f 2637/3682/5439 2447/2665/4237 2446/3687/5444 +f 3307/3750/5570 3305/1829/3425 3275/2868/4442 +f 2980/2791/4360 3011/3465/5571 3012/3453/5124 +f 3856/3751/5572 3853/3752/5573 3854/2566/4232 +f 2483/1690/3298 2258/3662/5574 2256/1691/3299 +f 3703/3753/5575 3704/2647/4956 3784/2218/3784 +f 3146/3715/5490 3147/3010/4606 3186/3754/5576 +f 3111/3627/5343 3109/3138/4748 3110/2282/5537 +f 2970/3099/3713 2968/2942/3713 2969/3564/3713 +f 3027/1796/3813 3038/2943/4528 3037/2248/3814 +f 2617/1888/3482 2612/2990/4578 2590/1889/3483 +f 2964/3755/3713 2962/3447/5118 2957/3324/3713 +f 1714/3621/3525 1715/3756/3525 1727/2013/4124 +f 2416/3757/5577 2418/3758/5578 2473/2872/4447 +f 3326/2108/5212 3319/3517/5212 3325/3572/5579 +f 2763/3642/5580 2762/3668/5581 2764/2221/3787 +f 3378/3557/5582 3389/1807/3406 3390/1991/3578 +f 3292/2070/3648 3295/3698/5461 3294/2316/3874 +f 3176/2338/3895 3177/3332/4974 3175/3252/4897 +f 3910/3397/5055 3911/2128/3705 3908/1883/3477 +f 3057/2336/3893 3059/3533/5230 3058/3449/5120 +f 3209/1828/3424 3304/3749/5564 3305/1829/3425 +f 3935/2510/4070 3930/2509/4069 3933/2214/4628 +f 2169/2207/3774 2170/3759/5583 2167/3734/5525 +f 3970/2826/5584 3942/1919/4508 3968/2045/5585 +f 1877/3089/4690 1878/3088/4689 1876/2848/5586 +f 3644/2290/5174 3645/2184/3755 3628/3485/5175 +f 2792/3371/5015 2781/3656/5391 2779/3760/5587 +f 2550/3177/5588 2315/3231/5589 2314/3230/5590 +f 3271/2228/3794 3257/3761/5591 3260/3636/5359 +f 1787/2191/5592 1666/2728/5592 1673/1879/5592 +f 3118/2178/5593 3117/3762/5593 3115/2549/4108 +f 3119/2303/5171 3118/2178/5594 3120/2177/5172 +f 3137/3763/3730 3108/2283/3730 3107/1958/3730 +f 3350/1813/4703 3349/3764/5595 3351/3765/5596 +f 3703/3753/5575 3702/3746/5561 3701/2453/3313 +f 3813/3286/4930 3809/3288/4931 3912/3382/5028 +f 1756/2050/4969 1771/3328/4971 1772/3149/4770 +f 3387/2198/3281 3355/2063/3281 3358/2554/3281 +f 3714/1744/3345 3713/3766/5597 3741/1742/3343 +f 2739/3140/4752 2821/2462/4024 2820/2547/4106 +f 3401/1676/3287 3400/1675/3286 3410/3767/5598 +f 3925/2090/3669 3923/3285/4425 3924/2707/4397 +f 1717/2562/5599 1715/3756/5600 1716/3768/5601 +f 3443/2317/5602 3562/3539/5602 3449/3098/5602 +f 1839/2626/4195 1836/2623/4192 1838/2625/4194 +f 3100/2802/5603 3099/2801/5604 3112/3626/5605 +f 2446/3687/5444 2445/3648/5379 2623/3109/4713 +f 2623/3109/4713 2445/3648/5379 2611/3108/4712 +f 1948/2933/5135 1810/1955/5134 1809/3462/5136 +f 3139/3486/5177 3155/2329/3885 3154/2158/3731 +f 1964/2468/4031 1792/2561/5606 1962/2277/3837 +f 2333/3068/4663 2334/3067/4662 2332/2982/4569 +f 3074/2507/4067 3073/1805/3404 3035/1804/3403 +f 3592/3185/5607 3594/3769/5608 3596/3770/5609 +f 2122/3647/5376 2119/2627/4196 2121/2365/3924 +f 3648/3451/5122 3649/3771/5610 3635/3411/5611 +f 3522/1739/5612 3523/3164/5349 3508/3507/5348 +f 3173/2150/3721 3175/3252/4897 3174/3772/5613 +f 2173/1997/3584 1937/1999/3586 2196/3773/5614 +f 3894/1684/3294 3877/1809/5201 3904/3233/4870 +f 2632/2968/4554 2611/3108/4712 2445/3648/5379 +f 3583/1917/3511 3584/2165/3738 3599/1915/3509 +f 2633/3655/5389 2447/2665/4237 2634/1996/3583 +f 2400/3774/5615 2401/3775/5616 2464/3726/5514 +f 2064/3396/5617 2063/2661/4234 2062/1767/5523 +f 1799/2770/4344 1966/3776/5618 1800/3528/5224 +f 3670/3422/5083 3674/3777/5619 3672/3778/5620 +f 2107/2484/4048 2108/2790/4359 2111/2648/4217 +f 3798/3671/5412 3766/2997/5621 3767/3779/5622 +f 3982/3061/5623 4001/2465/4027 4000/3101/4701 +f 1831/2616/5624 1941/2653/4223 2004/3780/5625 +f 2200/2046/3625 2190/3424/5085 2199/2047/3626 +f 3827/3131/4741 3826/2936/4518 3845/2695/4520 +f 3325/3572/5626 3437/3781/5626 3439/3782/5626 +f 3659/3783/5627 3658/3686/5443 3579/3069/5442 +f 3035/1804/3403 3026/1797/3812 3036/2508/4068 +f 2909/3417/5076 2908/2138/3714 2938/3784/5628 +f 2640/1995/3582 2638/2898/4475 2460/3639/5364 +f 4043/2910/4425 4044/2706/4425 4041/2854/4425 +f 3211/1760/5345 3299/1774/3375 3301/3785/5629 +f 2898/1923/3516 2899/3204/4836 2909/3417/5076 +f 4044/2706/4425 4040/2852/4425 4041/2854/4425 +f 4001/2465/4027 4017/3143/4764 4015/2313/3869 +f 2732/1869/4820 2836/2998/4821 2730/3123/4821 +f 2968/2942/3713 2971/3448/5119 2969/3564/3713 +f 2379/3609/5313 2375/2863/4435 2378/3786/5630 +f 3829/3787/5631 3828/3130/4740 3851/2658/5632 +f 3164/2861/4994 3165/3304/4949 3181/2247/3811 +f 3388/1745/3346 3375/1806/3405 3376/3788/5633 +f 1788/2483/5543 1953/2739/5634 1952/2738/5544 +f 3919/3269/5635 3917/3268/5635 3807/3287/5635 +f 2196/3773/5614 2174/1791/3391 2173/1997/3584 +f 3151/2298/5636 3192/2956/4542 3191/2842/4414 +f 1962/2277/3837 1792/2561/5606 1793/2278/3838 +f 3997/3789/5637 3984/3790/5638 3998/3743/5553 +f 3363/3670/3281 3386/2197/3281 3361/2199/3281 +f 3375/1806/3405 3389/1807/3406 3378/3557/5582 +f 3172/3791/5639 3173/2150/3721 3174/3772/5613 +f 3826/2936/3289 3827/3131/4741 3828/3130/4740 +f 3987/3162/4786 4030/1871/3467 4028/3792/5640 +f 2645/3144/4765 2655/3244/4886 2654/3404/5066 +f 3389/1807/5378 3388/1745/3346 3432/2107/3685 +f 2027/2101/3679 2029/2100/3917 1873/2360/3919 +f 2621/2663/4236 2622/2969/4555 2616/2525/4084 +f 2821/2462/4024 2803/2686/4315 2802/2463/4025 +f 2739/3140/4752 2740/3645/5373 2738/3000/3464 +f 3281/2825/4394 3282/1713/3319 3291/2071/3649 +f 3276/3172/4801 3306/1827/3423 3307/3750/5570 +f 3752/3793/5641 3778/3056/5642 3777/3794/5643 +f 3769/2750/4325 3770/2870/4444 3784/2218/3784 +f 3504/2977/4282 3503/3385/3815 3470/3795/3815 +f 2986/2585/5644 2974/1687/5645 2973/1686/4189 +f 2742/3265/4909 2776/1728/4905 2750/3262/4905 +f 3846/1718/4267 3845/2695/4266 3844/2937/5646 +f 3548/2600/4167 3547/3796/5647 3546/2601/4168 +f 3080/2504/5648 2964/3755/5648 2957/3324/5648 +f 3576/3797/3533 3579/3069/3533 3573/3255/3533 +f 3223/3380/5026 3222/2499/4061 3250/2430/4060 +f 1668/2692/4844 1677/2691/5649 1760/3547/5245 +f 2858/2902/3725 2857/3597/5298 2855/3033/3725 +f 3201/3798/3841 3197/1702/4865 3196/3799/3841 +f 2118/3157/4779 2120/3174/4803 2114/2471/4035 +f 3014/3390/5062 3012/3453/5324 3013/2874/5323 +f 2008/3800/5650 1852/2576/5651 1850/2575/5652 +f 2515/2532/4091 2714/2534/4093 2716/3801/5653 +f 1678/3689/5446 1779/1721/3324 1778/2323/3879 +f 2478/3019/4615 2458/1982/3569 2473/2872/4447 +f 2736/1864/3460 2731/3347/5654 2823/2180/3752 +f 3692/1708/3314 3695/3055/4651 3792/3005/4601 +f 2110/3468/5149 2144/1734/3337 2142/1736/3339 +f 2577/2373/3936 2587/2403/3968 2586/2189/3760 +f 3354/2062/4797 3352/2061/5655 3338/1668/5656 +f 3769/2750/4325 3704/2647/4956 3694/2646/4326 +f 2540/3290/5657 2301/3242/4883 2300/2377/5233 +f 2051/3263/5658 2229/3369/5659 2048/3264/5660 +f 3012/3453/5124 3014/3390/5044 2972/3391/5045 +f 1735/1887/3525 1734/1886/3525 1700/2397/3525 +f 3327/2162/3734 3320/3116/3734 3330/3431/3734 +f 3770/2870/4444 3783/2871/4445 3784/2218/3784 +f 3223/3380/3699 3224/3393/3699 3219/3802/5661 +f 2169/2207/3774 2158/2669/4241 2170/3759/5583 +f 2861/3488/5662 2862/1963/3551 2891/1964/3553 +f 2111/2648/4217 2147/3575/5271 2110/3468/5149 +f 3849/2388/3953 3852/2659/4231 3850/2389/3954 +f 2729/2705/3464 2727/3220/3464 2726/3401/3464 +f 3485/3215/4848 3487/3208/4840 3488/3251/5663 +f 2231/3803/5664 2048/3264/5660 2229/3369/5659 +f 1734/1886/3480 1752/3327/4968 1731/3804/5665 +f 3611/2109/5166 3610/2434/4493 3586/2920/4492 +f 2638/2898/4475 2635/2798/4367 2405/3024/4620 +f 3280/2824/4393 3291/2071/3649 3312/2322/3878 +f 2614/2947/4534 2380/2949/4536 2379/3609/5313 +f 3414/3805/5666 3332/3806/5667 3334/2163/3735 +f 3989/3093/5668 3990/3807/5669 4033/3808/5670 +f 3202/3809/5671 3314/3810/5672 3203/1761/5672 +f 2233/2235/4015 2042/2449/4014 2041/1910/5673 +f 3199/2632/5674 3088/3534/5675 3094/2424/5676 +f 3984/3790/5638 3985/3062/5568 3998/3743/5553 +f 3284/2204/3771 3298/3086/4687 3297/1776/3377 +f 2437/3811/5677 2519/3812/5678 2438/2671/4243 +f 1856/3813/5679 1852/2576/5651 2011/2270/5680 +f 3813/3286/4930 3819/3392/5046 3812/3568/4052 +f 1814/1695/5142 1969/2578/5462 1972/2577/5141 +f 2778/3814/5681 2783/1857/5682 2809/2704/4579 +f 3501/3272/4282 3494/2709/4282 3496/3085/4282 +f 3976/3092/3512 3975/1934/3512 3969/1936/3512 +f 2648/3243/4885 2663/3815/5683 2566/3816/5684 +f 3328/3206/4838 3322/3560/5259 3436/3552/5250 +f 3269/3179/4808 3281/2825/5685 3280/2824/4809 +f 3043/2796/4365 3042/2296/3853 3024/3075/4670 +f 2266/3817/5686 2267/2730/4303 2264/3633/5687 +f 3031/3595/5296 3066/2938/4521 3065/3596/5297 +f 3755/2996/4588 3767/3779/5688 3766/2997/4589 +f 2544/3706/5474 2546/3818/5689 2553/3126/4736 +f 2914/3375/5021 2915/1876/3472 2894/1878/3474 +f 2859/3034/4922 2860/2806/4375 2882/2805/4374 +f 3165/3304/5178 3137/3763/5690 3166/3305/4950 +f 3344/2813/4990 3369/3302/5691 3343/3819/5692 +f 3493/2708/4657 3492/2880/4454 3494/2709/5693 +f 3087/3820/5694 3092/2957/4543 3193/3821/5695 +f 2668/3435/5104 2658/3058/4654 2481/3018/4614 +f 3500/2545/3815 3491/2881/3815 3493/2708/3815 +f 2190/3424/5085 2189/3520/5215 2199/2047/3626 +f 2871/2167/3740 2873/2904/5696 2874/3494/5274 +f 3077/1970/3713 3078/2838/3713 3079/2503/3713 +f 2613/3822/5697 2617/1888/3482 2618/3342/4982 +f 3532/2262/3826 3534/3423/5084 3533/1741/3342 +f 1747/1905/3500 1746/3104/4706 1758/1903/3498 +f 3084/2280/3843 3189/1895/3489 3190/2840/4412 +f 2884/2804/5698 2886/3640/5699 2883/3325/5700 +f 3798/3671/5412 3800/3037/4631 3699/2866/5701 +f 3372/2028/3281 3374/2027/3281 3375/1806/3281 +f 2082/2535/4094 2093/2537/4096 1996/2820/4387 +f 3726/3660/5702 3728/3659/5703 3710/3412/5704 +f 3181/2247/3811 3180/3348/4995 3164/2861/4994 +f 1667/2737/4311 1671/3433/5096 1773/3150/4771 +f 2442/3145/4766 2643/3823/5705 2644/3146/4767 +f 2464/3726/5514 2640/1995/3582 2399/3824/5706 +f 2939/2275/3835 2938/3784/5628 2937/2765/4338 +f 2682/3825/5707 2686/3826/5708 2687/2026/3606 +f 2102/3738/5536 2101/3490/5182 2100/3737/5535 +f 3082/1703/5709 3201/3798/5709 3091/3336/5709 +f 2658/3058/4654 2482/1689/5710 2481/3018/4614 +f 2026/2102/3680 2155/2436/4000 2153/3827/5711 +f 3207/1724/3327 3287/3710/5712 3288/1722/3325 +f 3132/3714/3730 3137/3763/3730 3107/1958/3730 +f 2086/3011/4607 2094/2985/4573 2084/1831/3427 +f 3268/2203/3770 3266/3407/5392 3284/2204/3771 +f 3749/2993/4581 3751/3256/3827 3742/3374/5072 +f 3784/2218/3784 3783/2871/4445 3785/2219/3785 +f 2102/3738/5536 2087/2971/4557 2085/3828/5713 +f 3545/2602/4169 3448/1971/5714 3548/2600/4167 +f 3448/1971/5714 3549/3829/5715 3548/2600/4167 +f 2825/3830/5716 2792/3371/5015 2824/3160/4782 +f 3828/3130/4740 3829/3787/3289 3826/2936/3289 +f 3639/1793/5377 3625/1680/3290 3624/2777/4348 +f 2846/2144/3718 2950/2054/3718 2952/3593/3718 +f 3322/3560/5259 3394/2828/4398 3436/3552/5250 +f 2545/3178/5717 2312/3831/5718 2544/3706/5719 +f 2729/2705/4279 2811/3159/4781 2810/2703/4277 +f 2524/2877/5720 2526/2876/5437 2525/3681/5436 +f 1717/2562/5599 1718/2208/5721 1719/2563/4874 +f 3414/3805/5666 3334/2163/3735 3400/1675/3286 +f 3981/3617/5328 3978/3832/5722 4004/2186/5723 +f 3136/2281/4432 3137/3763/5690 3165/3304/5178 +f 3183/3050/4646 3185/3833/5724 3083/2279/3842 +f 3955/3113/5725 3957/3735/5529 3939/1920/3513 +f 2516/3222/4857 2521/3027/5726 2518/3026/5434 +f 2535/2676/4248 2455/2678/4250 2533/2762/4335 +f 3572/2844/4416 3568/3421/5082 3667/2843/4415 +f 3520/1763/3364 3521/1740/5727 3510/2068/3646 +f 3220/3834/3699 3221/2242/3699 3223/3380/3699 +f 2955/2009/3631 2954/2052/3631 2950/2054/3631 +f 3431/2780/4351 3432/2107/3685 3388/1745/3346 +f 2085/3828/5713 2086/3011/4607 2084/1831/3427 +f 2539/3291/4935 2541/2763/4336 2570/2371/3934 +f 4022/3199/4830 4021/2105/3683 4020/3835/5728 +f 3792/3005/4601 3793/1773/3374 3692/1708/3314 +f 3300/3836/5729 3298/3086/4687 3285/2416/4686 +f 3158/2746/5730 3159/2148/3719 3172/3791/5639 +f 3832/2901/3288 3862/2935/3288 3864/1808/3289 +f 3981/3617/3512 3983/2466/3512 3952/2327/3512 +f 3511/3274/4915 3498/3273/5731 3503/3385/5035 +f 2329/2419/5732 2559/3346/4989 2331/2981/5733 +f 3696/1811/5734 3803/1810/5734 3801/3444/5734 +f 3178/3837/5735 3180/3348/4995 3179/3333/4975 +f 3788/2056/3633 3787/2055/3632 3781/1759/3360 +f 3641/1681/3291 3642/2789/4358 3622/1682/3292 +f 2074/2528/4087 2180/2286/3846 1961/3070/4665 +f 2975/2742/4317 2974/1687/5645 2988/3643/5370 +f 2368/2568/4127 2369/1768/3369 2367/1770/3371 +f 3196/3799/5736 3081/1701/5736 3089/2634/5736 +f 3400/1675/3286 3387/2198/4643 3399/3300/5737 +f 3604/3416/5551 3603/2000/3736 3584/2165/3738 +f 2557/3838/5738 2335/3066/5739 2558/3345/4987 +f 3022/2119/3698 3034/1803/3402 3033/2117/3696 +f 2698/3553/5251 2697/3409/5070 2696/2972/4558 +f 2206/3470/5151 2203/3839/5740 2196/3773/5614 +f 3898/1984/3571 3890/3518/5213 3899/2988/4576 +f 2498/3012/5424 2497/3202/5420 2496/3675/5419 +f 2356/3601/5303 2370/2717/4290 2357/2718/4291 +f 2964/3755/3713 2969/3564/3713 2971/3448/5119 +f 3882/3340/4980 3881/3719/5496 3871/2565/5741 +f 3010/3446/3296 3008/3128/3296 3017/2118/3296 +f 3985/3062/5568 3999/3100/5567 3998/3743/5553 +f 2591/3134/4744 2618/3342/4982 2617/1888/3482 +f 2004/3780/5625 2005/3840/5742 1825/2621/5743 +f 2321/2931/4513 2320/3841/5744 2548/2932/4514 +f 3699/2866/3313 3693/1812/3313 3696/1811/5745 +f 1700/2397/3962 1699/2396/3961 1701/3842/5746 +f 2605/3318/4961 2609/3695/5458 2604/3696/5459 +f 2254/2604/4171 2255/3843/5747 2252/2605/4172 +f 3880/1848/5054 3881/3719/5496 3913/3445/5117 +f 3157/2747/5416 3171/3844/5748 3170/3674/5417 +f 3016/2348/3905 3028/3707/5749 3046/3845/5750 +f 3563/3309/5237 3446/2817/5237 3449/3098/5238 +f 2720/2112/3691 2505/3142/5519 2508/2113/3692 +f 3232/3481/5165 3235/3846/5751 3233/3480/5163 +f 3831/3847/5752 3861/3848/5753 3862/2935/5369 +f 2039/3740/5542 2038/3849/5754 2075/2649/4218 +f 3025/3387/5755 3040/3276/4917 3039/2381/3946 +f 2546/3818/5689 2547/3381/5027 2553/3126/4736 +f 3608/2433/4494 3606/2124/5550 3585/3728/5552 +f 2836/2998/3464 2835/3190/3464 2833/3629/3464 +f 3406/1746/3347 3426/1855/3453 3427/1747/3348 +f 3558/2608/4175 3517/3850/5756 3516/2609/4176 +f 2250/3851/5757 2251/3505/5200 2237/3504/5199 +f 2217/3852/5758 2066/2887/4463 2218/2886/4462 +f 2801/3357/5008 2791/2687/4259 2790/3293/4937 +f 3868/1683/3293 3864/1808/3407 3894/1684/3294 +f 1766/2033/3611 1765/2035/3613 1764/3650/5381 +f 2911/3395/5051 2942/3394/5050 2943/3853/5759 +f 2192/3426/5087 2188/3600/5302 2189/3520/5215 +f 2548/2932/4735 2549/3854/5760 2550/3177/4806 +f 2681/1942/3531 2701/2774/4345 2436/1819/3415 +f 2111/2648/4217 2039/3740/5542 2075/2649/4218 +f 2005/3840/5761 2004/3780/5762 2000/3855/5763 +f 2219/3430/5092 2070/2520/4461 1951/2519/4757 +f 3218/2384/3949 3230/2383/3948 3219/3802/5661 +f 2895/3205/3725 2899/3204/3725 2892/3440/3725 +f 3914/3720/5497 3819/3392/5046 3913/3445/5117 +f 1689/1932/3775 1680/1931/5764 1721/3137/4747 +f 2930/2088/3667 2850/2087/3666 2931/3856/5765 +f 3736/3857/5766 3739/2031/3609 3738/2030/3608 +f 2486/3644/5767 2485/3703/5469 2271/1899/3493 +f 1785/2751/4793 1676/1881/4793 1669/2693/4793 +f 1898/3148/4769 1897/3589/5290 1938/2672/4244 +f 1775/3314/4957 1757/3316/4959 1742/2358/3916 +f 1703/2493/3525 1738/2495/3525 1700/2397/3525 +f 3527/2976/4562 3528/3383/5033 3504/2977/4563 +f 3485/3215/5768 3463/3299/4945 3464/2251/4012 +f 2834/3858/5769 2833/3629/5769 2726/3401/5769 +f 2850/2087/3666 2848/2923/4499 2931/3856/5765 +f 3628/3485/5175 3645/2184/3755 3629/2152/3723 +f 3628/3485/3280 3629/2152/3280 3607/2123/3280 +f 2592/2398/3963 2584/3693/5453 2585/2190/3761 +f 1726/2454/4124 1727/2013/4124 1717/2562/3525 +f 2437/3811/5677 2702/3859/5770 2520/3860/5771 +f 1799/2770/4344 1800/3528/5224 1802/3193/4823 +f 2297/2376/3941 2298/2375/3940 2296/3861/5772 +f 4027/3351/4998 3925/2090/3669 4025/2104/3682 +f 3413/3301/4947 3411/3443/5116 3412/3583/5282 +f 3129/2905/5773 3131/2716/5774 3130/1957/5775 +f 2124/3322/4965 2152/2252/3816 2150/2480/4044 +f 3721/1947/5776 3722/2450/5036 3724/2452/5777 +f 3131/2716/3730 3132/3714/3730 3107/1958/3730 +f 1713/3622/5778 1688/2209/3777 1716/3768/5779 +f 3695/3055/4651 3700/2057/3634 3788/2056/3633 +f 2899/3204/4836 2908/2138/3714 2909/3417/5076 +f 3610/2434/3998 3612/1737/5780 3609/2432/3996 +f 3661/1978/3565 3656/2758/4331 3576/3797/5781 +f 3544/3708/5477 3528/3383/5782 3527/2976/4562 +f 2706/2674/4246 2523/3862/5783 2527/2675/4247 +f 2748/3366/5784 2770/3479/5785 2767/2538/5786 +f 2534/3257/5232 2542/3863/5787 2300/2377/5233 +f 1746/3104/4706 1747/1905/3500 1736/2146/4707 +f 3461/2722/4295 3462/2346/3903 3479/3646/5788 +f 2145/3576/5272 2144/1734/3337 2110/3468/5149 +f 3171/3844/5748 3172/3791/5639 3174/3772/5613 +f 3118/2178/5593 3115/2549/4108 3116/2551/4110 +f 1731/3804/3525 1730/2513/3525 1695/2664/3525 +f 1708/2176/5789 1706/2175/5790 1685/2589/4156 +f 4032/1872/3468 3989/3093/5668 4033/3808/5670 +f 3621/1780/3381 3626/3522/5791 3655/1712/4135 +f 1871/3864/5792 1865/2688/4260 1870/2690/4262 +f 1963/2285/3845 1964/2468/5793 1961/3070/4665 +f 3327/2162/5794 3331/2161/5794 3441/3865/5794 +f 2703/2875/2635 2704/3866/2635 2429/3867/5795 +f 2203/3839/5740 2122/3647/5376 2198/2048/3627 +f 2706/2674/2634 2431/3868/2634 2430/3869/2634 +f 3503/3385/3815 3467/3556/4282 3470/3795/3815 +f 3361/2199/5796 3358/2554/4114 3359/3665/5451 +f 2710/3870/5797 2433/3871/5797 2432/3872/5797 +f 2432/3872/2635 2711/3873/2635 2712/3025/2635 +f 3837/3874/5798 3839/1950/5799 3825/3592/5520 +f 2711/3873/5800 2434/3875/5800 2713/3876/5800 +f 3589/3161/5801 3581/3187/4817 3590/3186/4816 +f 2715/2111/2634 2426/3167/2634 2425/3877/2634 +f 2917/1960/5802 2925/2591/4158 2926/3653/5385 +f 3331/2161/5803 3323/3574/5803 3440/3573/5803 +f 2861/3488/5662 2891/1964/3553 2889/3482/5804 +f 3078/2838/5263 2969/3564/5263 3079/2503/5805 +f 3125/3685/4791 3124/2543/4791 3122/1802/5806 +f 2993/2944/5807 2994/1799/3398 2976/1688/3397 +f 2463/2524/4083 2390/3878/5808 2391/3879/5809 +f 2970/3099/5500 3074/2507/4067 3049/2506/4066 +f 2716/3801/5653 2513/2224/5810 2515/2532/4091 +f 2449/2668/4240 2599/2233/3799 2665/2916/4489 +f 3908/1883/3477 3906/1882/3476 3905/3880/5811 +f 2768/2539/4098 2767/2538/4097 2769/3729/5549 +f 2348/2309/3866 2462/3881/5812 2349/3577/5813 +f 2713/3876/5814 2714/2534/4093 2517/2533/4092 +f 3008/3128/4738 3009/2793/5143 3007/3882/5815 +f 2578/3298/4944 2580/2188/3759 2584/3693/5453 +f 3174/3772/5613 3095/2422/5816 3171/3844/5748 +f 2043/2485/4507 2046/3469/5817 2230/3883/5818 +f 2670/3884/5819 2704/3866/5820 2524/2877/4450 +f 2524/2877/4450 2704/3866/5820 2703/2875/4448 +f 2535/2676/5821 2534/3257/5232 2297/2376/5234 +f 3297/1776/3377 3294/2316/3874 3296/3192/4822 +f 2172/3563/5262 2177/3519/5214 2171/3885/5822 +f 1968/3021/4851 1965/3471/5823 2180/2286/3846 +f 3573/3255/5321 3688/2182/5322 3689/1944/5321 +f 3230/2383/3948 3233/3480/5824 3219/3802/5661 +f 3571/3420/5080 3575/3334/4976 3678/2896/4473 +f 3988/3658/5397 3987/3162/4786 3972/1935/5825 +f 2522/3886/5826 2709/3887/5827 2710/3870/5828 +f 2709/3887/5827 2522/3886/5826 2708/3888/5829 +f 2708/3888/5829 2522/3886/5826 2523/3862/5783 +f 2119/2627/4196 2117/3158/4780 2123/2517/4076 +f 2216/2890/4467 2209/2684/4256 2210/2683/4255 +f 2189/3520/5215 2190/3424/5085 2192/3426/5087 +f 2666/3250/4896 2449/2668/4240 2665/2916/4489 +f 2687/2026/3606 2700/1820/3416 2699/3410/5071 +f 2785/3339/3454 2790/3293/3454 2765/2220/3454 +f 2372/3196/4827 2371/3602/5304 2355/3194/4825 +f 2421/3889/5830 2422/3890/5830 2423/3891/5830 +f 3046/3845/5831 3028/3707/5475 3063/1788/3388 +f 3874/3428/5515 3873/3427/5513 3890/3518/5832 +f 3048/3367/5014 3049/2506/4066 3037/2248/3814 +f 3954/3112/4717 3951/2328/3884 3952/2327/3883 +f 3403/1924/3518 3402/2740/4314 3408/1874/3470 +f 3879/1849/3446 3878/3506/5833 3867/1679/3447 +f 3090/3229/4866 3084/2280/3843 3190/2840/4412 +f 3176/2338/3895 3161/2337/3894 3162/1755/5834 +f 1943/2995/4586 1996/2820/4387 2093/2537/4096 +f 3953/2967/4553 3955/3113/5725 3939/1920/3513 +f 4042/2212/3780 3933/2214/3780 4043/2910/5835 +f 3923/3285/5395 4039/2853/5836 4040/2852/5395 +f 2536/2677/5837 2535/2676/5821 2297/2376/5234 +f 3159/2148/3939 3158/2746/4321 3145/2745/4320 +f 3627/2361/3280 3593/3892/5005 3596/3770/5005 +f 1976/3893/5838 1947/3211/4843 1977/2065/5305 +f 2598/3321/4964 2597/3311/4955 2595/2231/3797 +f 3474/1778/4297 3460/2249/3926 3461/2722/4295 +f 1742/2358/3916 1743/2324/3880 1726/2454/4016 +f 2974/1687/5645 2986/2585/5644 2988/3643/5370 +f 2010/2501/5510 1850/2575/5652 1848/2645/5839 +f 3866/2310/5840 3867/1679/3447 3878/3506/5833 +f 3990/3807/5841 3976/3092/4694 3991/3459/5130 +f 2888/3610/3725 2890/3483/3725 2898/1923/3725 +f 3065/3596/5297 2965/2136/5842 3064/1789/3389 +f 2114/2471/4035 2141/2470/4034 2127/3894/5843 +f 3874/3428/5515 3890/3518/5832 3889/3727/5516 +f 2536/2677/5837 2297/2376/5234 2292/3544/5844 +f 3707/3110/5072 3708/1948/4581 3709/3434/5072 +f 3200/3895/5773 3094/2424/5773 3091/3336/5773 +f 2538/3240/4881 2537/3896/5845 2299/3241/4882 +f 3385/1674/3281 3353/3897/3281 3355/2063/3281 +f 3972/1935/5825 3975/1934/4693 3988/3658/5397 +f 2547/3381/5846 2308/3566/5847 2306/2592/5848 +f 2722/2909/5849 2499/3676/5850 2500/3677/5851 +f 2310/3567/5852 2308/3566/5847 2547/3381/5846 +f 2311/3898/5853 2544/3706/5719 2303/3899/5854 +f 2303/3899/5854 2544/3706/5719 2312/3831/5718 +f 1931/2289/3849 1987/2288/3848 2212/3900/5855 +f 2010/2501/5510 2008/3800/5650 1850/2575/5652 +f 2615/2662/4235 2616/2525/4084 2463/2524/4083 +f 2315/3231/5589 2550/3177/5588 2549/3854/5856 +f 2315/3231/5589 2549/3854/5856 2317/1817/5857 +f 2549/3854/5856 2318/1818/5858 2317/1817/5857 +f 2174/1791/3391 2175/3530/5226 2164/1792/3392 +f 2318/1818/5858 2548/2932/4514 2320/3841/5744 +f 2530/2474/4038 2529/3901/5859 2670/3884/5860 +f 3908/1883/3477 3909/2129/3706 3907/1884/3478 +f 2456/1980/5861 2248/3501/5196 2247/3500/5862 +f 3558/2608/4175 3530/3902/5863 3517/3850/5756 +f 1979/3210/4842 1980/3388/5039 1947/3211/4843 +f 3822/3903/3289 3823/3904/3288 3824/3344/3288 +f 2326/3581/5546 2454/3476/5158 2453/3741/5547 +f 2529/3901/5864 2704/3866/5820 2670/3884/5819 +f 2514/3223/4858 2650/2964/4550 2679/1941/3530 +f 2138/2254/3818 2129/3038/4632 2128/2515/4074 +f 2503/2719/4292 2648/3243/4885 2645/3144/4765 +f 2824/3160/4782 2826/3153/4775 2825/3830/5716 +f 2511/2225/3791 2510/2443/5180 2509/3678/5429 +f 2342/1893/3487 2555/1892/3486 2344/3046/5102 +f 3025/3387/3296 3027/1796/3296 2992/2945/3296 +f 2345/3047/5865 2561/3905/5866 2347/2567/4125 +f 2347/2567/4125 2561/3905/5866 2560/1974/4126 +f 2107/2484/4048 2044/1909/3503 2108/2790/4359 +f 2239/2261/5501 2477/2552/5503 2475/2439/4003 +f 3961/3441/5111 3962/2760/4333 3964/3078/5112 +f 3985/3062/3512 3984/3790/3512 3956/3063/3512 +f 2592/2398/3963 2583/2831/4402 2584/3693/5453 +f 3377/3531/5227 3391/2559/4119 3392/3087/4688 +f 2666/3250/4896 2655/3244/4886 2660/3059/4655 +f 4004/2186/3757 4005/3198/4829 4019/2187/3758 +f 2243/2441/4005 2474/2440/4004 2247/3500/5862 +f 3123/3906/3730 3120/2177/3730 3139/3486/3730 +f 2247/3500/5862 2457/1981/5867 2456/1980/5861 +f 2248/3501/5196 2480/3907/5868 2246/3503/5198 +f 2789/2785/4356 2804/2784/4355 2805/2715/4288 +f 1794/2333/4121 1793/2278/4122 1792/2561/4122 +f 3895/2414/3980 3820/3226/4862 3916/2469/4032 +f 1751/1885/3479 1750/3090/4691 1764/3650/5381 +f 2929/3908/5869 2927/2089/3668 2930/2088/3667 +f 2087/2971/4557 2086/3011/4607 2085/3828/5713 +f 1991/1930/3524 1904/2651/4220 1990/1694/3302 +f 2478/3019/5870 2251/3505/5871 2250/3851/5872 +f 3830/3909/5873 3829/3787/5631 3855/3910/5874 +f 3407/1992/3579 3390/1991/3578 3389/1807/5378 +f 2037/2448/4013 2233/2235/4015 2234/2234/5032 +f 2872/2154/3741 2869/3582/5487 2870/2166/3739 +f 2516/3222/4857 2685/3911/5875 2519/3812/5678 +f 1975/2756/4329 2071/3603/5306 1974/2754/4327 +f 3391/2559/4119 3433/1993/3580 3434/2106/3684 +f 2275/2729/4302 2488/3543/5876 2267/2730/5877 +f 2490/3912/5878 2275/2729/4302 2273/3525/5220 +f 2189/3520/5215 2188/3600/5302 2166/3913/5879 +f 3024/3075/3296 3023/3074/3296 2989/3722/3296 +f 2995/3914/5880 2997/1751/3352 2996/2928/5455 +f 1671/3433/5096 1667/2737/4311 1665/3031/3475 +f 3207/1724/3327 3211/1760/5345 3301/3785/5629 +f 2277/3154/4776 2491/3156/4778 2279/3203/4835 +f 3813/3286/4930 3812/3568/4052 3807/3287/4051 +f 3862/2935/5369 3832/2901/5881 3831/3847/5752 +f 3340/1786/3281 3339/3169/4381 3338/1668/3281 +f 3849/2388/3289 3870/3692/3289 3852/2659/3289 +f 3370/2320/3281 3372/2028/3281 3378/3557/3281 +f 2039/3740/5542 2111/2648/4217 2108/2790/4359 +f 3095/2422/5816 3170/3674/5417 3171/3844/5748 +f 3654/3228/4864 3655/1712/3318 3626/3522/5217 +f 3631/2950/5176 3643/3915/5882 3644/2290/5174 +f 2811/3159/5883 2792/3371/5015 2779/3760/5587 +f 2926/3653/5385 2854/3916/5884 2927/2089/3668 +f 1675/3064/3475 1679/1880/3475 1673/1879/3475 +f 1709/2147/3525 1736/2146/3525 1707/2726/3525 +f 3416/3353/5001 3329/3352/5000 3330/3431/5333 +f 3311/1861/3457 3310/2126/3703 3312/2322/3878 +f 2979/2792/3296 2972/3391/3296 2976/1688/3296 +f 3016/2348/3296 3020/2350/3296 2982/3402/3296 +f 3614/1738/3280 3616/3224/3280 3625/1680/3280 +f 3273/3119/5885 3274/2867/4441 3305/1829/3425 +f 1684/1933/4597 1701/3842/5886 1699/2396/4598 +f 1735/1887/5887 1738/2495/4511 1749/3917/5888 +f 3535/3165/4789 3522/1739/3340 3534/3423/5084 +f 3861/3848/5889 3831/3847/5890 3822/3903/5891 +f 3505/2772/3815 3509/2069/3815 3483/2654/3815 +f 3075/1968/3557 2956/2137/3557 2963/1969/3557 +f 2483/1690/3298 2261/3510/5372 2258/3662/5574 +f 3831/3847/5890 3833/3918/5892 3823/3904/5893 +f 3810/3569/4052 3820/3226/4052 3817/2488/4052 +f 2475/2439/4111 2416/3757/5577 2473/2872/4447 +f 2830/3724/5506 2831/3919/5894 2797/2011/3593 +f 2620/2114/3693 2631/3920/5895 2621/2663/4236 +f 3585/3728/5552 3604/3416/5551 3584/2165/3738 +f 1718/2208/5721 1720/3136/4875 1719/2563/4874 +f 3181/2247/3811 3182/3921/5896 3183/3050/4646 +f 1722/3237/4876 1721/3137/5897 1723/2656/4227 +f 2607/2399/3964 2592/2398/3963 2585/2190/3761 +f 2450/3450/5121 2667/3249/4895 2668/3435/5104 +f 3658/3686/5443 3659/3783/5627 3649/3771/5898 +f 3854/2566/3289 3865/3657/3289 3856/3751/3289 +f 3092/2957/4543 3087/3820/5694 3088/3534/4865 +f 3838/3094/3288 3835/2017/3289 3869/2174/3288 +f 3402/2740/4314 3416/3353/5001 3417/1875/3471 +f 3580/2210/3533 3577/2183/3533 3578/2211/4664 +f 2463/2524/4083 2391/3879/5809 2392/3007/4603 +f 4005/3198/4829 4006/2059/4148 4023/2584/4150 +f 1846/2644/5508 1844/3667/5899 2006/2502/5509 +f 3574/3335/4977 3644/2290/3850 3643/3915/5900 +f 3554/2458/4020 3514/2460/4022 3553/2542/4101 +f 2012/2269/3830 2013/2401/3966 2015/3467/5148 +f 2015/3467/5148 2011/2270/3831 2012/2269/3830 +f 3827/3131/4741 3847/2694/5901 3848/2387/4742 +f 3167/2159/3732 3154/2158/3731 3155/2329/3885 +f 3722/2450/5036 3721/1947/5776 3720/1946/4523 +f 2285/3080/5902 2528/2473/5902 2286/3540/5902 +f 2407/3922/5903 2368/2568/4127 2406/3923/5904 +f 3444/1835/3558 3451/1972/3559 3452/3614/3559 +f 3358/2554/3281 3361/2199/3281 3387/2198/3281 +f 3426/1855/3453 3425/2086/3664 3429/1853/3451 +f 3697/1772/3315 3699/2866/3313 3696/1811/5745 +f 2204/2849/4422 2141/2470/4034 2115/2472/4036 +f 2886/3640/5367 2888/3610/3725 2897/1922/3725 +f 3944/2390/4941 3947/3297/4943 3946/2391/5430 +f 3957/3735/5905 3955/3113/4718 3956/3063/4763 +f 2455/2678/4250 2536/2677/4249 2671/2092/3671 +f 2837/2999/3501 2838/3219/3501 2734/3133/3501 +f 3549/3829/5715 3551/2075/3653 3550/3188/4818 +f 1727/2013/4124 1715/3756/3525 1717/2562/3525 +f 2996/2928/4504 2998/1753/5906 2977/1798/3396 +f 3539/2023/3603 3453/2037/3615 3541/2021/3601 +f 2921/3029/4625 2920/2142/5907 2932/2922/4498 +f 2139/2253/3817 2129/3038/4632 2138/2254/3818 +f 3621/1780/3280 3618/3705/3280 3620/2140/3280 +f 3471/3924/5908 3469/2367/3927 3460/2249/3926 +f 3648/3451/5122 3635/3411/5611 3634/2151/3722 +f 4021/2105/3683 4025/2104/3682 3929/2511/4071 +f 1825/2621/4190 1838/2625/4194 1824/3546/5244 +f 2873/2904/5696 2875/2903/5273 2874/3494/5274 +f 1687/2355/3525 1686/2354/3525 1684/1933/3525 +f 3920/3570/5909 3817/2488/5909 3921/3925/5909 +f 1699/2396/4598 1698/2395/5910 1683/3002/4596 +f 2614/2947/4534 2615/2662/4235 2386/2948/4535 +f 3508/3507/4282 3475/1777/4282 3478/2307/4282 +f 3238/3053/4649 3241/3079/4674 3240/2240/5911 +f 1825/2621/5743 1833/2618/5912 2004/3780/5625 +f 3381/3926/5913 3395/3559/5914 3396/3558/5449 +f 3735/3927/5915 3734/3536/5916 3737/3928/5917 +f 3702/3746/5561 3700/2057/3634 3701/2453/3313 +f 3254/2917/5049 3223/3380/5026 3252/2429/5025 +f 3815/2487/5918 3808/3405/5919 3918/3267/5919 +f 2876/1726/5920 2875/2903/4478 2858/2902/4477 +f 3678/2896/4473 3679/2788/4357 3677/2496/4056 +f 3091/3336/3841 3086/2246/3810 3082/1703/3841 +f 3642/2789/4358 3643/3915/5900 3630/3929/5921 +f 2990/2743/4850 2988/3643/5922 2989/3722/5504 +f 1678/3689/5446 1668/2692/4844 1780/3213/4846 +f 3871/2565/5741 3872/2564/5388 3882/3340/4980 +f 3443/2317/5602 3560/3930/5602 3562/3539/5602 +f 3705/3535/5923 3714/1744/3345 3744/2642/5924 +f 2466/3042/4636 2459/3044/4638 2403/3931/5925 +f 2686/3826/5708 2680/1940/3529 2436/1819/3415 +f 2705/3732/5522 2529/3901/5864 2528/2473/4676 +f 2816/2548/4107 2801/3357/5008 2800/3176/4805 +f 3932/3041/4635 3931/2195/4425 3926/2213/4425 +f 2189/3520/5215 2166/3913/5879 2178/3521/5216 +f 3215/1939/3528 3293/1938/3527 3294/2316/3874 +f 3635/3411/3280 3633/1666/3280 3600/1665/3280 +f 3045/2349/3930 3046/3845/5831 3063/1788/3388 +f 2657/2072/3650 2656/3060/4656 2655/3244/4886 +f 1940/2927/4503 2026/2102/3680 2028/3484/5169 +f 2650/2964/4550 2651/2965/4551 2652/1989/3576 +f 2822/2741/4316 2739/3140/4752 2737/3932/5926 +f 2048/3264/5043 2142/1736/5927 2109/1998/5041 +f 2715/2111/2635 2425/3877/2635 2427/1952/3540 +f 1779/1721/3324 1678/3689/5446 1780/3213/4846 +f 3938/2966/4552 3951/2328/5928 3953/2967/4553 +f 3536/3166/4790 3538/2036/3614 3537/3933/5929 +f 2673/2091/3670 2672/3456/5127 2675/3235/4872 +f 2560/1974/4126 2564/1973/3864 2348/2309/3866 +f 3945/3296/4942 3944/2390/4941 3943/2827/4396 +f 2837/2999/3464 2836/2998/3464 2833/3629/3464 +f 3318/3934/3993 3214/2319/3993 3212/3711/3993 +f 3273/3119/4725 3272/3748/5930 3260/3636/5359 +f 2494/3634/5354 2267/2730/5877 2488/3543/5876 +f 3980/3312/3512 3964/3078/3512 3962/2760/3512 +f 3637/1781/4878 3636/2437/4001 3671/3935/5931 +f 3994/1840/3437 3995/3936/5932 3931/2195/3766 +f 3839/1950/3538 3837/3874/5933 3838/3094/4696 +f 1940/2927/4503 2156/2435/3999 2026/2102/3680 +f 2756/2194/5934 2754/3937/5935 2743/3938/5936 +f 2744/3623/3454 2743/3938/5937 2742/3265/3454 +f 3838/3094/4696 3837/3874/5933 3836/2015/3597 +f 3400/1675/3286 3413/3301/4947 3414/3805/5666 +f 2663/3815/5683 2503/2719/4292 2662/3275/4916 +f 3740/2032/4582 3749/2993/4581 3742/3374/5072 +f 3018/3373/5018 3017/2118/3697 3031/3595/5366 +f 2999/3221/4856 3000/1752/3353 3001/2895/4472 +f 2969/3564/5938 2964/3755/5938 3080/2504/5938 +f 3985/3062/5568 3982/3061/5939 4000/3101/5569 +f 3860/1677/3288 3866/2310/3288 3863/2428/3289 +f 3317/3294/4939 3206/3295/4939 3214/2319/4939 +f 2918/1961/5384 2917/1960/5802 2926/3653/5385 +f 2841/3498/5193 2842/3377/4761 2840/2096/3631 +f 2609/3695/5458 2608/3723/5505 2603/2405/3970 +f 3803/1810/3313 3804/3358/3313 3805/2512/3313 +f 3039/2381/5940 3038/2943/4528 3027/1796/3813 +f 3140/3716/3730 3125/3685/3730 3123/3906/3730 +f 2015/3467/5534 1855/2521/5941 1854/3939/5942 +f 2876/1726/3329 2877/1725/3328 2874/3494/5274 +f 3458/2810/4379 3459/2250/3928 3466/2808/4377 +f 3118/2178/3730 3116/2551/3730 3145/2745/3730 +f 2755/1858/3764 2753/3940/5943 2754/3937/5944 +f 2770/3479/5161 2772/1908/3502 2773/1907/3502 +f 3794/2946/4533 3791/3004/4600 3790/2954/4540 +f 3815/2487/5918 3918/3267/5919 3922/3941/5918 +f 3961/3441/5945 3963/3077/5946 3941/1918/4509 +f 4039/2853/5947 3927/3039/5947 4041/2854/5947 +f 2258/3662/5401 2259/3509/5204 2257/3663/5402 +f 1671/3433/5096 1774/3432/5095 1773/3150/4771 +f 3703/3753/5575 3693/1812/3313 3704/2647/3313 +f 3114/2550/4109 3112/3626/5342 3113/3628/5344 +f 2202/3590/5291 2205/2364/3923 2201/3612/5320 +f 1697/3360/5010 1698/2395/3960 1700/2397/3962 +f 2833/3629/3464 2834/3858/3465 2838/3219/3464 +f 3706/3630/5347 3705/3535/5923 3746/3550/5948 +f 3325/3572/5270 3439/3782/5949 3440/3573/5270 +f 1675/3064/4659 1672/2727/4301 1766/2033/3611 +f 2605/3318/4961 2610/3317/4960 2609/3695/5458 +f 1696/3359/5950 1694/3942/5951 1682/3943/5952 +f 3528/3383/5782 3544/3708/5477 3545/2602/4169 +f 3822/3903/5891 3831/3847/5890 3823/3904/5893 +f 3148/1897/3491 3135/2343/3900 3149/2344/5555 +f 3882/3340/4980 3915/3227/4863 3914/3720/5497 +f 1681/3944/5953 1692/3945/5954 1690/2657/5955 +f 2590/1889/3483 2461/1975/3562 2574/2639/4207 +f 1761/3548/5246 1749/3917/5956 1748/2444/4008 +f 3289/3946/5957 3288/1722/5958 3261/2121/5479 +f 2311/3898/5959 2302/3947/5960 2309/3565/5264 +f 3566/2266/3533 3570/2540/5081 3571/3420/5080 +f 2081/1852/3450 2080/2855/4426 2092/1928/3522 +f 3776/3124/5961 3775/1758/3359 3758/2264/5962 +f 3761/3599/3827 3760/2291/3827 3730/3948/3827 +f 3881/3719/5496 3880/1848/3445 3865/3657/5394 +f 3003/2893/3296 3022/2119/3296 3005/3127/3296 +f 3689/1944/3533 3688/2182/3533 3686/1945/3533 +f 2798/2477/4041 2785/3339/5963 2787/3338/4992 +f 1745/1719/3322 1779/1721/3324 1780/3213/4846 +f 1842/2631/4200 1844/3667/5408 1843/2951/4537 +f 2753/3940/5943 2752/1729/3332 2751/3266/5964 +f 4009/2952/4538 3934/3032/4627 3931/2195/3766 +f 3621/1780/3280 3623/1782/5965 3618/3705/3280 +f 2525/3681/5436 2669/2084/3662 2670/3884/5860 +f 3146/3715/5490 3132/3714/5489 3147/3010/4606 +f 1681/3944/5953 1694/3942/5951 1692/3945/5954 +f 3011/3465/5571 2980/2791/4360 3009/2793/4362 +f 3374/2027/3281 3376/3788/3281 3375/1806/3281 +f 2995/3914/3296 2992/2945/3296 3027/1796/3296 +f 1954/2666/4759 1957/3141/4758 1959/2635/5966 +f 3585/3728/5552 3586/2920/4492 3608/2433/4494 +f 2885/3491/5967 2887/3611/5319 2888/3610/5318 +f 3529/3384/5034 3528/3383/5782 3545/2602/4169 +f 3265/1714/3320 3267/3949/5968 3283/1715/3321 +f 1869/2689/5969 1867/3414/5073 2025/3415/5075 +f 3798/3671/5412 3699/2866/5701 3797/1891/3485 +f 2894/1878/3725 2881/2829/3725 2902/3071/3725 +f 3770/2870/5970 3760/2291/5456 3771/2229/5457 +f 2052/1790/3390 2049/2879/4452 2050/2003/3590 +f 3642/2789/4358 3641/1681/4057 3677/2496/4056 +f 2670/3884/5860 2669/2084/3662 2530/2474/4038 +f 2647/1987/3574 2659/1837/3433 2646/2073/3651 +f 1782/2753/3475 1783/3030/3475 1787/2191/3475 +f 2885/3491/5967 2888/3610/5318 2886/3640/5699 +f 2859/3034/4922 2879/2830/4921 2876/1726/5920 +f 3908/1883/3477 3905/3880/5811 3877/1809/5201 +f 3615/3225/4861 3617/3181/5063 3616/3224/4859 +f 2616/2525/4084 2622/2969/4555 2633/3655/5389 +f 3395/3559/5258 3394/2828/4398 3322/3560/5259 +f 3051/3950/5971 2968/2942/4527 3050/1914/3508 +f 3744/2642/5924 3746/3550/5948 3705/3535/5923 +f 3337/1669/5527 3338/1668/5656 3349/3764/5972 +f 3681/2039/3617 3682/3951/5973 3683/2040/3618 +f 3022/2119/3698 3021/3487/5179 3035/1804/3403 +f 2510/2443/4007 2513/2224/5810 2717/3168/5974 +f 2965/2136/5842 3065/3596/5297 3066/2938/4521 +f 3369/3302/5691 3367/3418/5975 3343/3819/5692 +f 3752/3793/3827 3753/2263/3827 3716/3549/3827 +f 2412/3952/5976 2579/3733/5524 2461/1975/3562 +f 2345/3047/4641 2346/3953/5977 2343/3045/4639 +f 1812/2582/4147 1806/3464/5978 1813/1696/3304 +f 2259/3509/5204 2258/3662/5401 2261/3510/5205 +f 2352/3954/5979 2351/1769/3370 2385/3303/4948 +f 3472/3330/5980 3471/3924/5981 3473/3632/5352 +f 3324/3184/4814 3422/2835/4407 3419/2834/4406 +f 3565/1833/3559 3564/3310/5982 3563/3309/3559 +f 2056/3356/5006 2055/1844/3441 2054/3955/5983 +f 2250/3851/5872 2246/3503/5198 2478/3019/5870 +f 2934/2043/3621 2841/3498/5193 2935/2406/3971 +f 2230/3883/2634 1921/3744/2634 1920/3956/2634 +f 2814/1705/3311 2825/3830/5716 2826/3153/4775 +f 1780/3213/4846 1746/3104/4706 1745/1719/3322 +f 2864/1826/3725 2896/3718/3725 2892/3440/3725 +f 1776/3315/4958 1777/2325/3881 1757/3316/4959 +f 3745/2641/3827 3742/3374/5072 3751/3256/3827 +f 3095/2422/3841 3094/2424/3841 3088/3534/4865 +f 2713/3876/3271 2434/3875/3271 2424/3957/2635 +f 3119/2303/5171 3117/3762/5984 3118/2178/5594 +f 1705/2494/4300 1702/2588/5985 1704/2587/5986 +f 2201/3612/5320 1931/2289/3849 2212/3900/5855 +f 3858/1678/3289 3856/3751/3289 3865/3657/3289 +f 3914/3720/5497 3913/3445/5117 3881/3719/5496 +f 3760/2291/5456 3770/2870/5970 3769/2750/4584 +f 3127/3017/4792 3129/2905/5773 3128/2097/5773 +f 3823/3904/5893 3834/2016/4984 3824/3344/4986 +f 1842/2631/5987 1837/2624/5988 2007/3319/5989 +f 2703/2875/4448 2707/2673/4245 2526/2876/4449 +f 3186/3754/5576 3187/3958/5990 3184/2173/3747 +f 1917/3959/5991 1918/3368/2635 2227/3370/2635 +f 1785/2751/5992 1669/2693/5992 1670/3960/5992 +f 2001/3961/5993 2000/3855/5763 1941/2653/5994 +f 1931/2289/3849 2113/2366/3925 1930/3455/5126 +f 1873/2360/5995 2032/2857/5996 1878/3088/5997 +f 3779/3460/5998 3778/3056/5642 3752/3793/5641 +f 3143/2374/3730 3145/2745/3730 3116/2551/3730 +f 2806/1863/3459 2805/2715/5999 2736/1864/3460 +f 2304/2594/6000 2543/3514/6001 2306/2592/5848 +f 3715/3962/6002 3716/3549/6003 3717/3281/4926 +f 3495/3057/4684 3496/3085/4683 3494/2709/5693 +f 3695/3055/4651 3692/1708/3314 3691/1707/3313 +f 2483/1690/3434 2659/1837/3433 2486/3644/6004 +f 2194/2492/4055 2192/3426/5087 2195/3963/6005 +f 3006/3129/4739 3004/2846/6006 3005/3127/4737 +f 1742/2358/3916 1741/2357/5435 1775/3314/4957 +f 2922/3028/6007 2923/2157/3728 2900/2156/3727 +f 2200/2046/3625 2198/2048/3627 2202/3590/5291 +f 2999/3221/6008 3001/2895/4893 2978/2845/4417 +f 3451/1972/3559 3453/2037/3559 3452/3614/3559 +f 2944/2168/3742 2912/2170/3744 2943/3853/5759 +f 2898/1923/3725 2897/1922/3725 2888/3610/3725 +f 2641/3584/5284 2443/2962/4548 2650/2964/4550 +f 2672/3456/5127 2673/2091/3670 2531/2475/4039 +f 3471/3924/5981 3470/3795/6009 3469/2367/6010 +f 3728/3659/5703 3729/3964/6011 3710/3412/5704 +f 2166/3913/5879 2188/3600/5302 2191/2491/4054 +f 3083/2279/3842 3081/1701/3841 3082/1703/3841 +f 3196/3799/3841 3198/2633/3841 3201/3798/3841 +f 3582/3965/6012 3583/1917/3511 3595/1979/3566 +f 2256/1691/5403 2257/3663/5402 2255/3843/5747 +f 3236/3052/3699 3265/1714/3699 3238/3053/3699 +f 3517/3850/5756 3518/3966/6013 3505/2772/6014 +f 3064/1789/3389 3029/3372/5476 3030/3594/5295 +f 2091/2991/4580 2090/2856/4427 1946/2975/4561 +f 3576/3797/5781 3662/1976/3563 3661/1978/3565 +f 2772/1908/6015 2770/3479/5785 2748/3366/5784 +f 3421/2836/4408 3423/2085/3663 3420/3132/4743 +f 1704/2587/5986 1706/2175/3749 1705/2494/4300 +f 2972/3391/5045 2981/2620/4187 2973/1686/4189 +f 3918/3267/5067 3807/3287/5067 3917/3268/6016 +f 2573/2372/3935 2451/3967/6017 2572/3036/4630 +f 2693/2131/3708 2570/2371/3934 2683/3968/6018 +f 3571/3420/5080 3568/3421/5082 3566/2266/3533 +f 3746/3550/5248 3744/2642/4212 3745/2641/4211 +f 3497/2809/4685 3467/3556/5254 3496/3085/4683 +f 2826/3153/4775 2824/3160/4782 2728/3400/6019 +f 2197/3529/5225 2198/2048/3627 2199/2047/3626 +f 1773/3150/4771 1772/3149/4770 1667/2737/4311 +f 2577/2373/3936 2573/2372/3935 2572/3036/4630 +f 3377/3531/5227 3378/3557/5582 3390/1991/3578 +f 2203/3839/5740 2206/3470/5151 2122/3647/5376 +f 2679/1941/3530 2680/1940/3529 2682/3825/5707 +f 2892/3440/5110 2893/1824/3420 2864/1826/3422 +f 3377/3531/3281 3382/1965/3281 3370/2320/3281 +f 1794/2333/3889 1949/2276/3836 1793/2278/3838 +f 2827/2237/3801 2793/2239/3803 2825/3830/5716 +f 2087/2971/4557 2088/2970/4556 2086/3011/4607 +f 4025/2104/3682 4024/2103/3681 4027/3351/4998 +f 4024/2103/3681 4023/2584/4150 4026/2583/4149 +f 3140/3716/5492 3153/3969/6020 3152/2297/3854 +f 3711/3413/3827 3712/3970/3827 3713/3766/3827 +f 3666/2244/3808 3669/2438/4002 3668/1711/3317 +f 3993/1839/6021 3992/2257/5414 3974/3313/5129 +f 3457/2941/3558 3452/3614/3559 3453/2037/3559 +f 3509/2069/3815 3480/3386/3815 3483/2654/3815 +f 2286/3540/6022 2283/3971/6023 2285/3080/6024 +f 2513/2224/5810 2718/3631/6025 2717/3168/5974 +f 3829/3787/3289 3822/3903/3289 3826/2936/3289 +f 2751/3266/4910 2743/3938/5936 2754/3937/5935 +f 2612/2990/4578 2378/3786/5630 2381/3613/5325 +f 2473/2872/4447 2418/3758/5578 2596/3972/6026 +f 3836/2015/3597 3835/2017/3599 3838/3094/4696 +f 3713/3766/5597 3712/3970/6027 3736/3857/6028 +f 3291/2071/3649 3290/1937/3526 3216/1859/3455 +f 3581/3187/4817 3582/3965/6012 3592/3185/4815 +f 3300/3836/5729 3301/3785/5629 3299/1774/3375 +f 3405/1927/3665 3404/1926/3520 3423/2085/3663 +f 3256/3245/4887 3254/2917/6029 3255/3246/4888 +f 2068/2884/6030 2217/3852/5758 2222/3398/5057 +f 1934/2735/4309 1933/3214/4847 2207/2201/3768 +f 3913/3445/5117 3912/3382/5028 3911/2128/3705 +f 3002/2894/4894 3004/2846/4418 2978/2845/4417 +f 2370/2717/4290 2371/3602/5304 2388/3651/5382 +f 2418/3758/5578 2419/3973/6031 2596/3972/6026 +f 3691/1707/3832 3802/3561/6032 3806/2271/3832 +f 2383/2570/4129 2384/2862/4434 2369/1768/3369 +f 2757/3625/6033 2759/2701/4275 2758/2193/3763 +f 2593/3105/4709 2608/3723/5505 2607/2399/3964 +f 3007/3882/6034 3009/2793/4362 2979/2792/4361 +f 2036/2847/6035 2033/2858/4429 2038/3849/5754 +f 3925/2090/3669 4027/3351/4998 4031/1870/3466 +f 2745/3624/5340 2746/2352/3910 2760/3175/6036 +f 3381/3926/3281 3386/2197/3281 3363/3670/3281 +f 3344/2813/3281 3343/3819/3281 3340/1786/3281 +f 2788/2714/3454 2784/1856/3454 2758/2193/3454 +f 2139/2253/3817 2152/2252/3816 2013/2401/3966 +f 1681/3944/3525 1680/1931/3525 1684/1933/3525 +f 2103/3284/4929 2102/3738/5536 2085/3828/5713 +f 3734/3536/5916 3731/3712/6037 3732/2293/6037 +f 2100/3737/5535 2099/3974/6038 2098/2500/4062 +f 2059/1843/3496 2065/2660/5052 2224/1902/3497 +f 2832/1847/3444 2830/3724/5506 2735/1845/3442 +f 3482/2347/4225 3483/2654/4224 3481/2345/6039 +f 3589/3161/4784 3590/3186/6040 3591/2139/4785 +f 3640/2497/4058 3639/1793/3393 3676/1795/3395 +f 2432/3872/2635 2434/3875/2635 2711/3873/2635 +f 2805/2715/5999 2737/3932/5926 2736/1864/3460 +f 1787/2191/3762 1673/1879/3762 1676/1881/3762 +f 3596/3770/5609 3593/3892/6041 3592/3185/5607 +f 2966/3171/4800 2967/2301/3858 3071/2300/3857 +f 1933/3214/4847 1932/2490/4053 2216/2890/4467 +f 3318/3934/6042 3203/1761/6042 3314/3810/6043 +f 2756/2194/3765 2757/3625/6033 2758/2193/3763 +f 3445/2076/3654 3450/2318/3875 3552/2077/3655 +f 2311/3898/5959 2303/3899/6044 2302/3947/5960 +f 2710/3870/3275 2708/3888/2635 2706/2674/2635 +f 3112/3626/5605 3114/2550/6045 3100/2802/5603 +f 2290/2700/6046 2289/1700/6047 2287/1699/6046 +f 3736/3857/6028 3738/2030/6048 3713/3766/5597 +f 3017/2118/3697 3032/3118/6049 3031/3595/5366 +f 1767/2034/3612 1768/2078/3656 1769/2216/3782 +f 2082/2535/4094 1996/2820/4387 2090/2856/4427 +f 2157/3975/6050 2074/2528/4087 2067/2883/4458 +f 1982/3745/5556 1983/3976/6051 1947/3211/4843 +f 2083/1830/3426 2106/2080/3658 2130/2079/3657 +f 3464/2251/3815 3463/3299/4945 3462/2346/3903 +f 2614/2947/4534 2618/3342/4982 2619/2115/3694 +f 2782/3680/3454 2775/2196/3454 2777/1730/3454 +f 1769/2216/3782 1755/2581/4970 1754/2215/3781 +f 3195/2331/3887 3194/2160/3733 3167/2159/3732 +f 3033/2117/3696 3032/3118/6049 3017/2118/3697 +f 3988/3658/5397 3989/3093/5668 4032/1872/3468 +f 1697/3360/3525 1731/3804/3525 1695/2664/3525 +f 3059/3533/5230 3060/3977/6052 3061/2394/3959 +f 2933/2042/3620 2924/2041/3619 2923/2157/6053 +f 3992/2257/3821 3993/1839/3436 4036/2255/3819 +f 2668/3435/5104 2596/3972/6026 2450/3450/5121 +f 2037/2448/6054 2038/3849/5754 2039/3740/5542 +f 2937/2765/4338 2936/3978/6055 2847/2764/4337 +f 2652/1989/3576 2599/2233/3799 2594/2232/3798 +f 2723/3635/5356 2722/2909/5849 2500/3677/5851 +f 3759/2451/5301 3757/3979/6056 3774/1757/3358 +f 3422/2835/4407 3324/3184/4814 3424/3980/6057 +f 1744/1720/3323 1778/2323/3879 1779/1721/3324 +f 1714/3621/5335 1712/3981/6058 1711/2353/5336 +f 3385/1674/3281 3384/1841/3281 3353/3897/3281 +f 1754/2215/4144 1730/2513/4146 1731/3804/5665 +f 2353/3982/6059 2385/3303/4948 2372/3196/4827 +f 3039/2381/5940 3027/1796/3813 3025/3387/6060 +f 3448/1971/5714 3445/2076/3654 3549/3829/5715 +f 3193/3821/5695 3153/3969/6061 3194/2160/3733 +f 2594/2232/3798 2448/3035/4629 2571/2775/4346 +f 2882/2805/5093 2883/3325/5700 2881/2829/4400 +f 3453/2037/3615 3538/2036/3614 3457/2941/5374 +f 3588/3182/3280 3586/2920/3280 3584/2165/3280 +f 3647/3452/5558 3646/2153/3724 3657/2038/3616 +f 3579/3069/5442 3576/3797/5781 3659/3783/5627 +f 3356/2555/4796 3339/3169/4795 3357/3478/6062 +f 3866/2310/6063 3878/3506/5202 3877/1809/5201 +f 3616/3224/3280 3624/2777/5965 3625/1680/3280 +f 1853/2523/6064 1851/2574/4137 1852/2576/4139 +f 2439/2082/3660 2525/3681/5436 2523/3862/6065 +f 2747/2351/3908 2748/3366/5784 2767/2538/5786 +f 3799/3672/5413 3798/3671/5412 3767/3779/5622 +f 2654/3404/5066 2653/1988/3575 2440/3524/5219 +f 3805/2512/4073 3698/2272/4073 3806/2271/4073 +f 3928/3040/4634 3925/2090/3669 4032/1872/3468 +f 3959/2759/4332 3958/2067/6066 3957/3735/5905 +f 1826/2612/4571 1821/2779/6067 2002/2984/4572 +f 2635/2798/4367 2596/3972/6026 2403/3931/5925 +f 3752/3793/5641 3777/3794/5643 3753/2263/4731 +f 3019/2007/4366 3043/2796/4365 3024/3075/4670 +f 2858/2902/4477 2859/3034/4922 2876/1726/5920 +f 3405/1927/3521 3406/1746/3347 3379/1925/3519 +f 4017/3143/4764 4018/2913/4486 4015/2313/3869 +f 2428/1953/2635 2723/3635/2635 2721/1954/2635 +f 2135/3283/4928 2101/3490/5182 2103/3284/4929 +f 3701/2453/3313 3693/1812/3313 3703/3753/5575 +f 2568/1986/3573 2647/1987/3574 2567/2386/3951 +f 3809/3288/4931 3909/2129/3706 3912/3382/5028 +f 3559/3122/4729 3447/2818/4385 3532/2262/3826 +f 2900/2156/3725 2896/3718/3725 2864/1826/3725 +f 3344/2813/4990 3371/2029/4990 3369/3302/5691 +f 3164/2861/4433 3163/1754/3355 3138/2860/4431 +f 2681/1942/3531 2436/1819/3415 2680/1940/3529 +f 2985/2006/4151 2987/2005/6068 2986/2585/4152 +f 3282/1713/3319 3281/2825/5685 3270/3457/6069 +f 2496/3675/5419 2499/3676/5421 2502/2921/5425 +f 3547/3796/5647 3548/2600/4167 3550/3188/4818 +f 2130/2079/3657 2131/2081/3659 2134/3121/4728 +f 3677/2496/4056 3640/2497/4058 3676/1795/3395 +f 2867/2571/4593 2868/2573/6070 2869/3582/5487 +f 2491/3156/4778 2495/3201/4833 2279/3203/4835 +f 3931/2195/3766 3995/3936/5932 3996/2953/4539 +f 1924/3378/2635 1880/2725/5991 1881/2724/5991 +f 3966/2341/3512 3976/3092/3512 3969/1936/3512 +f 3789/3003/4599 3790/2954/4540 3791/3004/4600 +f 2940/2274/3834 2942/3394/5050 2910/1921/3514 +f 3178/3837/5735 3176/2338/3895 3162/1755/5834 +f 3341/3254/6071 3362/2958/6072 3360/3664/5404 +f 2643/3823/5705 2442/3145/4766 2511/2225/3791 +f 1860/3684/5440 2021/3736/5532 2020/3554/5252 +f 3696/1811/5734 3801/3444/5734 3690/1709/6073 +f 2232/2929/4505 2233/2235/4015 2041/1910/5673 +f 1984/3608/5312 2181/3983/6074 1985/2781/4352 +f 3597/1916/3545 3599/1915/3839 3600/1665/3546 +f 3098/3984/3730 3099/2801/3730 3101/2603/4170 +f 4029/3985/6075 4031/1870/3466 4027/3351/4998 +f 3086/2246/3810 3093/3331/4973 3179/3333/4975 +f 3568/3421/5082 3572/2844/4416 3567/2267/5470 +f 2192/3426/5087 2194/2492/4055 2191/2491/4054 +f 2977/1798/3396 2999/3221/6008 2978/2845/4417 +f 2897/1922/3725 2903/2833/3725 2886/3640/5367 +f 2551/2930/4512 2552/3477/5159 2324/3458/5128 +f 3509/2069/3647 3518/3966/6013 3519/1764/3365 +f 1749/3917/5888 1750/3090/6076 1735/1887/5887 +f 3181/2247/3811 3165/3304/4949 3182/3921/5896 +f 2541/2763/5787 2540/3290/5657 2300/2377/5233 +f 1817/3429/5100 1818/1749/3350 1811/1748/3349 +f 3835/2017/3599 3834/2016/3598 3833/3918/6077 +f 1740/2135/3712 1739/2051/4772 1773/3150/4771 +f 3626/3522/3280 3591/2139/3280 3593/3892/5005 +f 2791/2687/3454 2789/2785/3454 2761/2702/3454 +f 1713/3622/5778 1687/2355/3913 1688/2209/3777 +f 2774/1906/4906 2772/1908/6015 2749/3365/6078 +f 2180/2286/3846 2074/2528/4087 1935/2530/4089 +f 3656/2758/4331 3660/1733/3336 3576/3797/5781 +f 2950/2054/3631 2951/2094/3631 2955/2009/3631 +f 2637/3682/5439 2636/2799/4368 2635/2798/4367 +f 2389/3620/5334 2377/3606/5310 2376/3605/5309 +f 2776/1728/3331 2751/3266/5964 2752/1729/3332 +f 3393/1966/3555 3392/3087/6079 3435/2560/4120 +f 2067/2883/4458 2069/2885/4460 2061/2670/4242 +f 2799/2476/4040 2812/2478/4042 2832/1847/3444 +f 2946/2169/3743 2948/3280/4925 2947/3376/5023 +f 2861/3488/3725 2860/2806/3725 2859/3034/3725 +f 2902/3071/4666 2913/2832/4403 2914/3375/5021 +f 3761/3599/3827 3730/3948/3827 3727/3661/3827 +f 2373/3604/5308 2377/3606/5310 2389/3620/5334 +f 3002/2894/4471 3003/2893/4470 3005/3127/4737 +f 3326/2108/5212 3321/3183/4813 3319/3517/5212 +f 2025/3415/5075 2024/2926/5098 1869/2689/5969 +f 3123/3906/6080 3121/2304/5170 3120/2177/5172 +f 3824/3344/4986 3837/3874/5798 3825/3592/5520 +f 3290/1937/3526 3291/2071/3649 3292/2070/3648 +f 3925/2090/3669 3928/3040/4634 3923/3285/4425 +f 3816/1983/4051 3814/3986/4051 3815/2487/4051 +f 3906/1882/3476 3907/1884/3478 3811/3437/5106 +f 3461/2722/3815 3460/2249/3815 3464/2251/3815 +f 3379/1925/3281 3345/2888/3281 3347/1815/3281 +f 2454/3476/6081 2552/3477/6082 2553/3126/4736 +f 3723/3987/6083 3725/3988/6084 3709/3434/6085 +f 3649/3771/5898 3648/3451/5557 3658/3686/5443 +f 3271/2228/3794 3272/3748/5563 3303/2226/3792 +f 2706/2674/3274 2707/2673/3274 2431/3868/2635 +f 2012/2269/3830 2009/2268/3829 2136/3489/5181 +f 2706/2674/4246 2708/3888/5829 2523/3862/5783 +f 2746/2352/3910 2762/3668/5409 2760/3175/6036 +f 1736/2146/3525 1737/2445/3525 1707/2726/3525 +f 3193/3821/5695 3152/2297/6086 3153/3969/6061 +f 3363/3670/4544 3360/3664/6087 3362/2958/4544 +f 3610/2434/3998 3611/2109/6088 3612/1737/5780 +f 4031/1870/3466 4029/3985/6075 4028/3792/5640 +f 2576/2973/4559 2578/3298/4944 2574/2639/4207 +f 3884/3654/5386 3872/2564/5388 3870/3692/5452 +f 2376/3605/5309 2380/2949/4536 2386/2948/4535 +f 2790/3293/4937 2800/3176/4938 2801/3357/5008 +f 1848/2645/4216 1850/2575/4138 1849/3615/5326 +f 2929/3908/5869 2928/3652/5383 2927/2089/3668 +f 4033/3808/5670 3928/3040/4634 4032/1872/3468 +f 2988/3643/5922 2986/2585/4152 2987/2005/6068 +f 3838/3094/3288 3873/3427/3288 3841/1951/3288 +f 3100/2802/5603 3115/2549/6089 3101/2603/4170 +f 3956/3063/3512 3954/3112/3512 3982/3061/3512 +f 2810/2703/6090 2811/3159/5883 2778/3814/5681 +f 2913/2832/5022 2912/2170/3744 2946/2169/3743 +f 3872/2564/3289 3854/2566/3289 3852/2659/3289 +f 3525/3289/6091 3507/3329/6092 3524/3438/5350 +f 3900/1985/3572 3901/2987/4575 3902/3989/6093 +f 3714/1744/3345 3743/1743/3344 3744/2642/5924 +f 2907/3259/3725 2905/1962/3725 2872/2154/3725 +f 3220/3834/6094 3239/3990/6095 3240/2240/3804 +f 1961/3070/4665 2180/2286/3846 1963/2285/3845 +f 4031/1870/3466 4028/3792/5640 4030/1871/3467 +f 3276/3172/5494 3275/2868/5088 3259/3120/4726 +f 2312/3831/6096 2302/3947/5960 2303/3899/6044 +f 3452/3614/5559 3454/2899/6097 3564/3310/5560 +f 2429/3867/5795 2431/3868/2635 2703/2875/2635 +f 2843/2924/4500 2842/3377/5024 2922/3028/4624 +f 3480/3386/5037 3479/3646/5375 3481/2345/6039 +f 3225/3725/5530 3227/2699/5029 3218/2384/3949 +f 2121/2365/3924 2119/2627/4196 2132/2628/4197 +f 3990/3807/5669 3991/3459/6098 4033/3808/5670 +f 3701/2453/6099 3804/3358/6099 3693/1812/6099 +f 3922/3941/4051 3918/3267/4051 3919/3269/4051 +f 2633/3655/5389 2445/3648/5379 2446/3687/5444 +f 2522/3886/6100 2702/3859/5770 2437/3811/5677 +f 3064/1789/3389 3030/3594/5295 3065/3596/5297 +f 3323/3574/3734 3331/2161/3734 3333/3571/5269 +f 2180/2286/3846 2071/3603/5306 2183/2934/4516 +f 2009/2268/3829 2011/2270/3831 2008/3800/6101 +f 3730/3948/6102 3729/3964/6103 3728/3659/5398 +f 2126/3991/6104 2145/3576/5272 2146/3323/4966 +f 3489/2447/4011 3487/3208/6105 3464/2251/4012 +f 3146/3715/5490 3186/3754/5576 3184/2173/3747 +f 3978/3832/3512 3981/3617/3512 3950/3679/6106 +f 3017/2118/3296 3008/3128/3296 3005/3127/3296 +f 3429/1853/3451 3431/2780/4351 3428/1854/3452 +f 2559/3346/4989 2333/3068/4988 2331/2981/5733 +f 3898/1984/3571 3821/2489/4753 3897/2599/4166 +f 3555/3239/4880 3556/3992/6107 3557/2607/4174 +f 3646/2153/3724 3645/2184/3755 3681/2039/3617 +f 3125/3685/4791 3122/1802/5806 3123/3906/6080 +f 3665/1710/3316 3666/2244/3808 3668/1711/3317 +f 2979/2792/3296 2980/2791/3296 2972/3391/3296 +f 1705/2494/4300 1703/2493/6108 1702/2588/5985 +f 3936/3993/6109 3942/1919/4508 3970/2826/5584 +f 2553/3126/4736 2575/2370/3933 2453/3741/6110 +f 3258/2120/6111 3257/3761/5591 3271/2228/3794 +f 3797/1891/3485 3795/1771/3372 3780/2527/4086 +f 3968/2045/3623 3967/2339/3896 3969/1936/3624 +f 2132/2628/4197 2131/2081/3659 2113/2366/3925 +f 3934/3032/4627 4009/2952/4538 4011/2378/3943 +f 2321/2931/5471 2319/2961/4547 2320/3841/6112 +f 3101/2603/4170 3103/1800/3730 3105/2098/3730 +f 3183/3050/4646 3182/3921/5896 3184/2173/3747 +f 1762/3091/4692 1760/3547/5245 1679/1880/4658 +f 3066/2938/4521 3032/3118/4723 3067/2425/3988 +f 3911/2128/3705 3880/1848/5054 3913/3445/5117 +f 2209/2684/4256 2216/2890/4467 2214/2892/4469 +f 1875/3994/6113 1876/2848/5586 1879/2723/4298 +f 3445/2076/3654 3444/1835/3558 3443/2317/3559 +f 3038/2943/4528 3039/2381/3946 3050/1914/3508 +f 1723/2656/4227 1691/2305/4229 1722/3237/4876 +f 3494/2709/4282 3501/3272/4282 3502/2710/3815 +f 3021/3487/3296 3022/2119/3296 3003/2893/3296 +f 3757/3979/6056 3775/1758/3359 3774/1757/3358 +f 3570/2540/5081 3569/3683/3533 3575/3334/4976 +f 2857/3597/5298 2870/2166/6114 2868/2573/4132 +f 1765/2035/3613 1751/1885/3479 1764/3650/5381 +f 2245/2259/3823 2239/2261/3825 2244/3497/5192 +f 2730/3123/3464 2735/1845/3464 2732/1869/3465 +f 2486/3644/5371 2263/3513/6115 2261/3510/5372 +f 2552/3477/6082 2551/2930/4734 2554/3125/4733 +f 3595/1979/4526 3598/1667/3547 3596/3770/5609 +f 3503/3385/3815 3498/3273/4282 3467/3556/4282 +f 1890/3308/4953 2214/2892/4469 2208/3306/4951 +f 1733/2014/3525 1712/3981/3525 1714/3621/3525 +f 2071/3603/5306 1929/3995/6116 1976/3893/5838 +f 1936/2529/4088 2157/3975/6117 2186/2734/4308 +f 3954/3112/4717 3953/2967/4719 3951/2328/3884 +f 3734/3536/3827 3756/3996/3827 3737/3928/3827 +f 1818/1749/3350 1819/2064/6118 1820/1750/3351 +f 3852/2659/4231 3851/2658/4230 3850/2389/3954 +f 2151/2479/4043 2152/2252/3816 2138/2254/3818 +f 2752/1729/3454 2753/3940/3454 2778/3814/3454 +f 2860/2806/4375 2861/3488/5662 2887/3611/6119 +f 3694/2646/4326 3699/2866/5701 3800/3037/4631 +f 2492/3152/4774 2491/3156/6120 2493/3155/6121 +f 3353/3897/6122 3350/1813/4703 3351/3765/5596 +f 3306/1827/3423 3276/3172/4801 3308/2919/4491 +f 2745/3624/5340 2759/2701/6123 2757/3625/5341 +f 2659/1837/3433 2664/1836/3432 2646/2073/3651 +f 1782/2753/6124 1784/2752/6124 1670/3960/6124 +f 2398/3638/5363 2399/3824/5706 2640/1995/3582 +f 2350/3578/5277 2346/3953/5977 2348/2309/5275 +f 4013/3102/4702 4000/3101/4701 4015/2313/3869 +f 2569/3151/6125 2495/3201/6125 2491/3156/6125 +f 3460/2249/3926 3473/3632/6126 3471/3924/5908 +f 4016/2311/3867 4018/2913/4486 4019/2187/3758 +f 1957/3141/4758 1960/2640/4208 1956/2334/4210 +f 2596/3972/6026 2635/2798/4367 2602/2800/4369 +f 3647/3452/5558 3657/2038/3616 3658/3686/5443 +f 3441/3865/3734 3440/3573/3734 3439/3782/3734 +f 2231/3803/2635 2229/3369/2635 1921/3744/2635 +f 3851/2658/5632 3853/3752/6127 3829/3787/5631 +f 3006/3129/6128 2979/2792/4361 3004/2846/4418 +f 3507/3329/4282 3472/3330/4282 3475/1777/4282 +f 3802/3561/3313 3801/3444/3313 3805/2512/3313 +f 3401/1676/3287 3402/2740/4314 3384/1841/3438 +f 2669/2084/3662 2525/3681/5436 2439/2082/3660 +f 3979/3191/6129 3995/3936/6130 3980/3312/6131 +f 2779/3760/3454 2777/1730/3454 2752/1729/3454 +f 2021/3736/5532 1860/3684/5440 1857/2522/5533 +f 3875/1717/3289 3870/3692/3289 3849/2388/3289 +f 3285/2416/4686 3286/2415/6132 3300/3836/5729 +f 3673/3238/4879 3671/3935/5931 3674/3777/5619 +f 2945/2907/4481 2946/2169/3743 2944/2168/3742 +f 2839/2095/6133 2841/3498/5193 2840/2096/3631 +f 3844/2937/5646 3843/3997/6134 3846/1718/4267 +f 3725/3988/6135 3723/3987/6136 3724/2452/5777 +f 2793/2239/3803 2792/3371/5015 2825/3830/5716 +f 3462/2346/3903 3481/2345/3902 3479/3646/5788 +f 2403/3931/5925 2404/3023/4619 2635/2798/4367 +f 1941/2653/5994 2000/3855/5763 2004/3780/5762 +f 2127/3894/5843 2118/3157/4779 2114/2471/4035 +f 2182/2200/3767 2211/2202/3769 1985/2781/4352 +f 3505/2772/3815 3483/2654/3815 3486/2773/3815 +f 2360/2410/3976 2363/3998/6137 2358/3999/6138 +f 3014/3390/5062 3013/2874/5323 2982/3402/5060 +f 1870/2690/6139 1873/2360/6139 1871/3864/6139 +f 1965/3471/5823 1966/3776/6140 2180/2286/3846 +f 3541/2021/3601 3542/3709/5478 3540/2022/3602 +f 4008/3649/5380 4012/2380/3945 4010/2379/3944 +f 3578/2211/3779 3658/3686/5443 3657/2038/3616 +f 1752/3327/4968 1753/4000/6141 1731/3804/5665 +f 3456/2900/4476 3457/2941/5374 3535/3165/4789 +f 3687/2181/3753 3577/2183/3754 3569/3683/3753 +f 2218/2886/2635 2219/3430/3271 1925/4001/3274 +f 2785/3339/3454 2765/2220/3454 2768/2539/4979 +f 3680/2897/4474 3574/3335/4977 3643/3915/5900 +f 3029/3372/5016 3028/3707/5749 3015/2873/5017 +f 2645/3144/4765 2648/3243/4885 2655/3244/4886 +f 2159/3700/5465 2058/1842/3439 2055/1844/3441 +f 2589/2404/3969 2448/3035/4629 2588/4002/6142 +f 2751/3266/4910 2742/3265/4909 2743/3938/5936 +f 3116/2551/3730 3113/3628/3730 3141/1756/3730 +f 3551/2075/3653 3549/3829/5715 3445/2076/3654 +f 1675/3064/4659 1764/3650/5381 1763/3065/4660 +f 1686/2354/3525 1685/2589/4124 1684/1933/3525 +f 3043/2796/4365 3044/2368/3929 3061/2394/3959 +f 2366/3541/5239 2386/2948/4535 2365/4003/6143 +f 3207/1724/3327 3301/3785/5629 3300/3836/5729 +f 3716/3549/5247 3715/3962/5247 3746/3550/5248 +f 3104/2099/3677 3103/1800/3399 3126/2711/4283 +f 3594/3769/5608 3595/1979/4526 3596/3770/5609 +f 3761/3599/5300 3772/2230/5338 3771/2229/5457 +f 3082/1703/5709 3197/1702/5709 3201/3798/5709 +f 2979/2792/4361 3006/3129/6128 3007/3882/6034 +f 2448/3035/4629 2597/3311/4955 2588/4002/6142 +f 3936/3993/3512 3937/2392/3512 3939/1920/3513 +f 3325/3572/5579 3323/3574/3734 3328/3206/3734 +f 2268/2731/4304 2267/2730/4303 2266/3817/5686 +f 3842/3731/5521 3825/3592/5520 3840/1949/6144 +f 3406/1746/3347 3388/1745/3346 3376/3788/5633 +f 2971/3448/5119 2962/3447/5118 2964/3755/3713 +f 3649/3771/5898 3650/1732/3335 3633/1666/4263 +f 3490/3207/4839 3488/3251/5663 3487/3208/4840 +f 2719/3730/2635 2720/2112/2635 2427/1952/3540 +f 3875/1717/3972 3887/2839/4411 3886/2407/3973 +f 1969/2578/4141 2185/3084/4754 2184/2579/4142 +f 3096/2423/3841 3091/3336/3841 3094/2424/3841 +f 2923/2157/6053 2922/3028/4624 2933/2042/3620 +f 3260/3636/3699 3255/3246/3699 3253/2918/3699 +f 2662/3275/4916 2504/2721/4294 2495/3201/5418 +f 2076/3326/4967 2075/2649/4218 1939/3747/5562 +f 2175/3530/5226 2163/3618/5330 2164/1792/3392 +f 3173/2150/3721 3172/3791/5639 3159/2148/3719 +f 3221/2242/3806 3220/3834/6094 3240/2240/3804 +f 2247/3500/5195 2238/3499/5194 2242/3496/5191 +f 2789/2785/3454 2788/2714/3454 2761/2702/3454 +f 3235/3846/5751 3234/3495/5189 3233/3480/5163 +f 2159/3700/5465 2055/1844/3441 2161/3701/5466 +f 2166/3913/5879 2169/2207/3774 2167/3734/5525 +f 3888/2598/5517 3887/2839/4411 3876/1716/4410 +f 2986/2585/5644 2973/1686/4189 2983/2586/4188 +f 1959/2635/4202 1958/3475/5156 1795/2636/4203 +f 1760/3547/5245 1677/2691/5649 1679/1880/4658 +f 3251/2431/3995 3250/2430/3994 3248/2498/4890 +f 3695/3055/4651 3776/3124/5961 3777/3794/6145 +f 3952/2327/3512 3950/3679/6106 3981/3617/3512 +f 2420/4004/6146 2415/4005/6147 2596/3972/6026 +f 2851/2008/3822 2953/2053/3822 2954/2052/3822 +f 2517/2533/4092 2518/3026/4622 2713/3876/5814 +f 3265/1714/3699 3236/3052/3699 3235/3846/3699 +f 2944/2168/3742 2943/3853/5759 2942/3394/5050 +f 2073/2456/4371 2016/2556/4116 2072/2803/4372 +f 3291/2071/3649 3216/1859/3455 3311/1861/3457 +f 3710/3412/5704 3709/3434/6085 3726/3660/5702 +f 2988/3643/5922 2987/2005/6068 2989/3722/5504 +f 2117/3158/4780 2118/3157/4779 2116/3073/4668 +f 3283/1715/3321 3296/3192/4822 3295/3698/5461 +f 3464/2251/4012 3487/3208/6105 3485/3215/5768 +f 3598/1667/3280 3632/2362/3280 3596/3770/5005 +f 3517/3850/5756 3505/2772/6014 3506/2771/4390 +f 3543/4006/6148 3448/1971/5714 3544/3708/5477 +f 2176/3562/5261 2197/3529/5225 2199/2047/3626 +f 3669/2438/4002 3670/3422/5083 3672/3778/5620 +f 2661/2915/4488 2654/3404/5066 2655/3244/4886 +f 2075/2649/4218 2038/3849/5754 1939/3747/5562 +f 2235/3379/2635 2234/2234/2635 1923/2236/3800 +f 2393/3006/4602 2615/2662/4235 2463/2524/4083 +f 3743/1743/4213 3741/1742/5020 3742/3374/5019 +f 2444/2963/4549 2443/2962/4548 2440/3524/5219 +f 1759/1904/3499 1758/1903/3498 1760/3547/5245 +f 3334/2163/3735 3329/3352/5000 3415/2418/3984 +f 1983/3976/6051 1977/2065/5305 1947/3211/4843 +f 2848/2923/3631 2850/2087/3666 2849/2010/4761 +f 2123/2517/4076 2117/3158/4780 2128/2515/4074 +f 4039/2853/5947 3923/3285/6149 3927/3039/5947 +f 2092/1928/3522 1990/1694/3302 1938/2672/4244 +f 2429/3867/5795 2705/3732/3274 2283/3971/3271 +f 1706/2175/3749 1709/2147/3751 1707/2726/3749 +f 1915/4007/6150 1988/3349/4996 1989/1832/3428 +f 3170/3674/5417 3095/2422/5816 3195/2331/3887 +f 3626/3522/3280 3621/1780/3280 3591/2139/3280 +f 2512/2223/3789 2514/3223/4858 2515/2532/5432 +f 4014/2312/3868 4016/2311/3867 3935/2510/4070 +f 3411/3443/5116 3397/3442/5115 3412/3583/5282 +f 3670/3422/5083 3669/2438/4002 3667/2843/4415 +f 3463/3299/4945 3484/2655/6151 3482/2347/3904 +f 1739/2051/3630 1740/2135/3712 1724/2134/3711 +f 3283/1715/3321 3267/3949/5968 3268/2203/3770 +f 1750/3090/4691 1749/3917/5956 1762/3091/4692 +f 3021/3487/3296 3003/2893/3296 3000/1752/3296 +f 2378/3786/5630 2375/2863/4435 2381/3613/5325 +f 2437/3811/5677 2439/2082/3660 2523/3862/6065 +f 2705/3732/3274 2284/3081/3271 2283/3971/3271 +f 3712/3970/6027 3711/3413/5484 3733/3713/5486 +f 3373/2889/4991 3336/1670/5526 3346/3673/6152 +f 4005/3198/4829 3978/3832/5722 3977/2060/6153 +f 1725/2049/3525 1691/2305/3525 1693/2514/3525 +f 3768/2749/4324 3767/3779/5622 3756/3996/6154 +f 3976/3092/4694 3990/3807/5841 3989/3093/4695 +f 1695/2664/6155 1694/3942/6155 1696/3359/5009 +f 3972/1935/5825 3987/3162/4786 3973/2058/3635 +f 2566/3816/5684 2662/3275/4916 2565/2385/3950 +f 3504/2977/4563 3528/3383/5033 3503/3385/5035 +f 3275/2868/4442 3276/3172/4801 3307/3750/5570 +f 1866/2682/4254 1867/3414/5448 1861/2680/4252 +f 2972/3391/3296 2973/1686/3296 2976/1688/3296 +f 3560/3930/3559 3561/1834/3558 3565/1833/3559 +f 3331/2161/5803 3440/3573/5803 3441/3865/6156 +f 2767/2538/5786 2766/2222/6157 2747/2351/3908 +f 4019/2187/3758 4022/3199/4830 4020/3835/5728 +f 2946/2169/3743 2844/2787/4923 2948/3280/4925 +f 1720/3136/4875 1721/3137/5897 1722/3237/4876 +f 2038/3849/5754 2035/3493/6158 2036/2847/6035 +f 2396/3508/5203 2397/3637/5362 2460/3639/5364 +f 3754/2292/3827 3756/3996/3827 3734/3536/3827 +f 3855/3910/5874 3857/4008/6159 3830/3909/5873 +f 2233/2235/3271 2232/2929/2635 1922/4009/6160 +f 3857/4008/6161 3855/3910/5572 3856/3751/5572 +f 3318/3934/3993 3317/3294/3993 3214/2319/3993 +f 3290/1937/3526 3215/1939/3528 3216/1859/3455 +f 2562/2638/5101 2561/3905/5866 2345/3047/5865 +f 3204/1723/3326 3289/3946/6162 3302/2227/3793 +f 2230/3883/5818 2232/2929/4505 2043/2485/4507 +f 1831/2616/5624 1829/2614/4221 1941/2653/4223 +f 3743/1743/4213 3742/3374/5019 3745/2641/4211 +f 2072/2803/4372 2156/2435/3999 2022/2457/4370 +f 2805/2715/5999 2804/2784/4517 2822/2741/4316 +f 1718/2208/3776 1716/3768/5779 1688/2209/3777 +f 1791/2637/6163 1789/2481/4045 1788/2483/4047 +f 3623/1782/5965 3624/2777/5965 3616/3224/3280 +f 3603/2000/3587 3604/3416/3828 3605/2001/3588 +f 3706/3630/5347 3746/3550/5948 3715/3962/6164 +f 3076/2505/6165 2957/3324/6165 2956/2137/6165 +f 3110/2282/5537 3109/3138/4748 3108/2283/4750 +f 3343/3819/3281 3342/3253/3281 3340/1786/3281 +f 2482/1689/5710 2484/3669/6166 2481/3018/4614 +f 4020/3835/5728 3929/2511/4071 4019/2187/3758 +f 3381/3926/3281 3363/3670/3281 3365/2960/3281 +f 2005/3840/5742 1840/2629/6167 1839/2626/6168 +f 3234/3495/6169 3237/3054/6170 3219/3802/5661 +f 2547/3381/5027 2543/3514/5209 2570/2371/3934 +f 1695/2664/6155 1692/3945/6171 1694/3942/6155 +f 2225/3364/6172 2226/3218/4854 2056/3356/6173 +f 3630/3929/3280 3631/2950/3280 3612/1737/3280 +f 3965/2340/4510 3967/2339/6174 3942/1919/4508 +f 2292/3544/5242 2297/2376/3941 2296/3861/5772 +f 3872/2564/5388 3883/3341/5387 3882/3340/4980 +f 3137/3763/5690 3132/3714/5489 3166/3305/4950 +f 3246/1866/3462 3249/3247/4891 3247/3048/6175 +f 1683/3002/4596 1696/3359/5950 1682/3943/5952 +f 3129/2905/5773 3130/1957/5775 3128/2097/5773 +f 4016/2311/3867 4015/2313/3869 4018/2913/4486 +f 1743/2324/3880 1757/3316/4959 1777/2325/3881 +f 3539/2023/3603 3524/3438/5107 3537/3933/5929 +f 2712/3025/4621 2711/3873/6176 2518/3026/4622 +f 3363/3670/4544 3361/2199/5796 3360/3664/6087 +f 3716/3549/6003 3719/2265/4525 3717/3281/4926 +f 2838/3219/4855 2834/3858/4855 2727/3220/4855 +f 3002/2894/4471 3005/3127/4737 3004/2846/6006 +f 3224/3393/3699 3217/3439/3699 3219/3802/5661 +f 3133/2299/3730 3127/3017/3730 3125/3685/3730 +f 2881/2829/3725 2883/3325/3725 2902/3071/3725 +f 3654/3228/4864 3627/2361/3920 3653/2363/3922 +f 3196/3799/5736 3089/2634/5736 3198/2633/5736 +f 2969/3564/3713 2961/2837/3713 2970/3099/3713 +f 3324/3184/4814 3429/1853/3451 3424/3980/6057 +f 3995/3936/6130 3994/1840/6177 3980/3312/6131 +f 2215/2891/4468 2194/2492/4055 2195/3963/6005 +f 3750/2992/3827 3740/2032/4582 3739/2031/3827 +f 3199/2632/4201 3089/2634/4201 3088/3534/6178 +f 3261/2121/5479 3258/2120/6179 3289/3946/5957 +f 2769/3729/3454 2786/3170/4979 2787/3338/4979 +f 2401/3775/5616 2402/4010/6180 2463/2524/4083 +f 3437/3781/3734 3438/3115/3734 3441/3865/3734 +f 2836/2998/4590 2738/3000/4591 2730/3123/6181 +f 4043/2910/4482 3930/2509/4482 4044/2706/6182 +f 1755/2581/4145 1756/2050/3629 1725/2049/3628 +f 3691/1707/3313 3698/2272/3313 3695/3055/4651 +f 2851/2008/3631 2852/2786/3631 2845/2258/3631 +f 3819/3392/5046 3914/3720/5497 3915/3227/4863 +f 3470/3795/6009 3467/3556/5254 3468/3454/5256 +f 3737/3928/5917 3736/3857/5766 3735/3927/5915 +f 2441/4011/6183 2649/1990/3577 2651/2965/4551 +f 3367/3418/5975 3366/3082/6184 3342/3253/6185 +f 2215/2891/4468 2213/4012/6186 2214/2892/4469 +f 3974/3313/3512 3976/3092/3512 3966/2341/3512 +f 1942/3320/4963 2007/3319/4962 2005/3840/5761 +f 3956/3063/3512 3984/3790/3512 3959/2759/3512 +f 2790/3293/3454 2791/2687/3454 2763/3642/3454 +f 3594/3769/6187 3582/3965/6012 3595/1979/3566 +f 2710/3870/3275 2709/3887/5991 2708/3888/2635 +f 2916/3258/4901 2906/1877/3473 2915/1876/3472 +f 3497/2809/4685 3466/2808/5255 3467/3556/5254 +f 1704/2587/4154 1685/2589/4156 1706/2175/5790 +f 2122/3647/5376 2120/3174/4803 2119/2627/4196 +f 3490/3207/3815 3491/2881/3815 3499/2823/3815 +f 3754/2292/4585 3760/2291/5456 3769/2750/4584 +f 3713/3766/5597 3738/2030/6048 3741/1742/3343 +f 2317/1817/3413 2316/1816/3412 2315/3231/4868 +f 1686/2354/3912 1710/3051/4647 1708/2176/5789 +f 2536/2677/4249 2292/3544/6188 2671/2092/3671 +f 3145/2745/4320 3143/2374/3937 3159/2148/3939 +f 3421/2836/4408 3424/3980/6057 3423/2085/3663 +f 2532/2093/3672 2528/2473/4037 2531/2475/4039 +f 3367/3418/5077 3369/3302/5078 3370/2320/5078 +f 3962/2760/4333 3961/3441/5111 3960/2761/4334 +f 2921/3029/5355 2922/3028/6007 2901/3403/5065 +f 3759/2451/3827 3761/3599/3827 3724/2452/3827 +f 3262/2417/3699 3266/3407/3699 3231/3408/3699 +f 3876/1716/3289 3846/1718/3289 3843/3997/3288 +f 2098/2500/4062 2099/3974/6038 2009/2268/3829 +f 3381/3926/5913 3383/1967/6189 3394/2828/6190 +f 3277/3173/6191 3276/3172/5494 3264/3717/5493 +f 3390/1991/3578 3391/2559/4119 3377/3531/5227 +f 2070/2520/4079 2066/2887/4760 2074/2528/4087 +f 3502/2710/3815 3500/2545/3815 3493/2708/3815 +f 1924/3378/2635 1881/2724/5991 2236/3492/6192 +f 3949/2326/3882 3948/2882/5481 3950/3679/5431 +f 3457/2941/3558 3454/2899/3558 3452/3614/3559 +f 2207/2201/3768 1935/2530/4089 1934/2735/4309 +f 2225/3364/2635 1928/3363/2635 1917/3959/5991 +f 3133/2299/3856 3140/3716/5492 3152/2297/3854 +f 3304/3749/5564 3273/3119/5885 3305/1829/3425 +f 1705/2494/3525 1737/2445/3525 1738/2495/3525 +f 3394/2828/6190 3395/3559/5914 3381/3926/5913 +f 2683/3968/6018 2570/2371/3934 2533/2762/4335 +f 3546/2601/4168 3529/3384/5034 3545/2602/4169 +f 3878/3506/5202 3910/3397/5055 3908/1883/3477 +f 3891/2986/5512 3890/3518/5832 3873/3427/5513 +f 2887/3611/6119 2885/3491/5183 2860/2806/4375 +f 1685/2589/4156 1686/2354/3912 1708/2176/5789 +f 1782/2753/6124 1670/3960/6124 1665/3031/6124 +f 2756/2194/5934 2743/3938/5936 2744/3623/5339 +f 3924/2707/4397 3930/2509/4069 3929/2511/4071 +f 3688/2182/3533 3687/2181/6193 3686/1945/3533 +f 3897/2599/4166 3889/3727/6194 3898/1984/3571 +f 3613/2110/5332 3587/3355/5167 3588/3182/4812 +f 3984/3790/3512 3979/3191/3512 3959/2759/3512 +f 3627/2361/3280 3626/3522/3280 3593/3892/5005 +f 3892/4013/6195 3902/3989/6093 3901/2987/4575 +f 3404/1926/3520 3380/1814/6196 3403/1924/3518 +f 3996/2953/6197 3984/3790/5638 3997/3789/5637 +f 3671/3935/5931 3672/3778/5620 3674/3777/5619 +f 3265/1714/3699 3270/3457/3699 3238/3053/3699 +f 3133/2299/3856 3150/2841/5554 3135/2343/3900 +f 1734/1886/3525 1731/3804/3525 1697/3360/3525 +f 3920/3570/5909 3810/3569/6198 3817/2488/5909 +f 3144/2179/3932 3145/2745/4320 3157/2747/4322 +f 1733/2014/3525 1732/2145/3525 1712/3981/3525 +f 3282/1713/3319 3283/1715/3321 3292/2070/3648 +f 2978/2845/3296 2979/2792/3296 2976/1688/3296 +f 3822/3903/3289 3824/3344/3288 3826/2936/3289 +f 2597/3311/4955 2605/3318/4961 2604/3696/5459 +f 3383/1967/3281 3365/2960/3281 3368/3419/3281 +f 2974/1687/3296 2975/2742/4251 2976/1688/3296 +f 2993/2944/4529 2992/2945/4531 2995/3914/5880 +f 2440/3524/5219 2511/2225/3791 2442/3145/4766 +f 3194/2160/3733 3087/3820/5694 3193/3821/5695 +f 3795/1771/3372 3794/2946/4533 3762/2955/4541 +f 2649/1990/3577 2441/4011/6183 2440/3524/5219 +f 3485/3215/4848 3488/3251/5663 3486/2773/4849 +f 3871/2565/3288 3865/3657/3289 3854/2566/3289 +f 3895/2414/3980 3887/2839/5231 3896/2412/3978 +f 1708/2176/3750 1710/3051/6199 1709/2147/3751 +f 2823/2180/3752 2731/3347/5654 2729/2705/4279 +f 3442/3114/4720 3320/3116/4720 3327/2162/4720 +f 3163/1754/3355 3142/4014/6200 3138/2860/4431 +f 3240/2240/5911 3239/3990/6201 3238/3053/4649 +f 2739/3140/4752 2822/2741/4316 2821/2462/4024 +f 2037/2448/6054 2039/3740/5542 2040/1911/3505 +f 2597/3311/4955 2604/3696/5459 2588/4002/6142 +f 3946/2391/3956 3948/2882/4456 3937/2392/3957 +f 3919/3269/5635 3807/3287/5635 3812/3568/6202 +f 3025/3387/5755 3023/3074/4669 3040/3276/4917 +f 2024/2926/4502 2025/3415/6203 1940/2927/4503 +f 3829/3787/5631 3853/3752/6127 3855/3910/5874 +f 2126/3991/6104 2146/3323/4966 2125/2851/4424 +f 3313/3691/6204 3208/2018/6204 3315/2020/6204 +f 3982/3061/3512 3954/3112/3512 3983/2466/3512 +f 3663/2243/3807 3667/2843/4415 3666/2244/3808 +f 3721/1947/5776 3724/2452/5777 3723/3987/6136 +f 2788/2714/4287 2789/2785/4356 2805/2715/4288 +f 3655/1712/3318 3654/3228/4864 3665/1710/3316 +f 1717/2562/5599 1716/3768/5601 1718/2208/5721 +f 2469/4015/6205 2470/4016/6206 2471/3014/4611 +f 2206/3470/5151 2114/2471/4035 2122/3647/5376 +f 3840/1949/3537 3841/1951/3539 3843/3997/6134 +f 2000/3855/5763 1942/3320/4963 2005/3840/5761 +f 2304/2594/6000 2537/3896/5845 2543/3514/6001 +f 3346/3673/5415 3347/1815/4704 3345/2888/4464 +f 2231/3803/5664 2046/3469/5817 2048/3264/5660 +f 3643/3915/5900 3642/2789/4358 3679/2788/4357 +f 2759/2701/6123 2745/3624/5340 2760/3175/6036 +f 1949/2276/3836 1794/2333/3889 1960/2640/6207 +f 2647/1987/3574 2648/3243/4885 2566/3816/5684 +f 2235/3379/5031 2035/3493/5188 2037/2448/4013 +f 2737/3932/3465 2739/3140/4752 2734/3133/3464 +f 3360/3664/6087 3361/2199/5796 3359/3665/5451 +f 1906/2650/4219 1905/4017/6208 1904/2651/4220 +f 1859/2766/4339 2019/3436/5105 2016/2556/4116 +f 1702/2588/4155 1701/3842/5886 1684/1933/4597 +f 2104/3197/4828 2085/3828/5713 2083/1830/3426 +f 3904/3233/4870 3905/3880/5811 3906/1882/3476 +f 3269/3179/3699 3263/2865/3699 3244/1865/3699 +f 2526/2876/4449 2707/2673/4245 2527/2675/4247 +f 3974/3313/5129 3980/3312/6131 3993/1839/6021 +f 1985/2781/4352 1882/2783/4354 1883/4018/6209 +f 2840/2096/3631 2843/2924/4761 2848/2923/3631 +f 3101/2603/4170 3102/1801/3400 3103/1800/3730 +f 1879/2723/5186 2036/2847/5187 2236/3492/5184 +f 3710/3412/5704 3729/3964/6011 3711/3413/5484 +f 3166/3305/4950 3146/3715/5490 3168/2172/3746 +f 2227/3370/2635 2228/3216/2635 1917/3959/5991 +f 2647/1987/3574 2566/3816/5684 2565/2385/3950 +f 2819/2546/4105 2800/3176/4805 2832/1847/3444 +f 2842/3377/4761 2843/2924/4761 2840/2096/3631 +f 1702/2588/5985 1703/2493/6108 1701/3842/5746 +f 2165/2205/3772 2169/2207/3774 2166/3913/5879 +f 3635/3411/6210 3649/3771/5898 3633/1666/4263 +f 2906/1877/3725 2907/3259/3725 2877/1725/3725 +f 3516/2609/6211 3506/2771/4390 3515/2459/4392 +f 3963/3077/4673 3966/2341/3898 3965/2340/3897 +f 2724/4019/6212 2472/3015/6212 2471/3014/6212 +f 3252/2429/3993 3251/2431/3995 3253/2918/3993 +f 2919/2141/6213 2918/1961/5384 2929/3908/5869 +f 2593/3105/4709 2603/2405/3970 2608/3723/5505 +f 1764/3650/5381 1675/3064/4659 1766/2033/3611 +f 2809/2704/4579 2810/2703/6090 2778/3814/5681 +f 1845/3666/5407 1843/2951/4537 1844/3667/5408 +f 2281/2908/4485 2278/3527/5223 2279/3203/5307 +f 2313/3232/4869 2312/3831/6096 2314/3230/4867 +f 3376/3788/5633 3379/1925/3519 3406/1746/3347 +f 1931/2289/3849 2201/3612/5320 2205/2364/3923 +f 2517/2533/5433 2514/3223/4858 2516/3222/4857 +f 3233/3480/5824 3234/3495/6169 3219/3802/5661 +f 1963/2285/4029 1797/2769/4342 1798/2467/4030 +f 3526/2978/4564 3540/2022/3602 3542/3709/5478 +f 3200/3895/5773 3091/3336/5773 3201/3798/5773 +f 2005/3840/5742 2007/3319/5989 1837/2624/5988 +f 3080/2504/5648 2957/3324/5648 3076/2505/5648 +f 3024/3075/3296 2989/3722/3296 2987/2005/3296 +f 2304/2594/6000 2299/3241/4882 2537/3896/5845 +f 2718/3631/2635 2716/3801/2635 2426/3167/2635 +f 3674/3777/5619 3568/3421/5082 3675/1794/3394 +f 2967/2301/3891 2966/3171/3713 2963/1969/3713 +f 3888/2598/4165 3889/3727/6194 3897/2599/4166 +f 3542/3709/5478 3543/4006/6148 3544/3708/5477 +f 2078/3282/4927 2129/3038/4632 2077/2402/3967 +f 3734/3536/5916 3733/3713/6214 3731/3712/6037 +f 3199/2632/5674 3094/2424/5676 3200/3895/5676 +f 2995/3914/5880 2996/2928/5455 2994/1799/6215 +f 2883/3325/5700 2882/2805/5093 2884/2804/5698 +f 3514/2460/4022 3513/2544/4103 3553/2542/4101 +f 3171/3844/5748 3157/2747/5416 3158/2746/5730 +f 3775/1758/3359 3757/3979/6056 3758/2264/5962 +f 3754/2292/4585 3768/2749/4324 3756/3996/6154 +f 3341/3254/6071 3342/3253/6185 3364/2959/6216 +f 2828/1706/3312 2733/1868/5113 2829/2012/3594 +f 2093/2537/4096 2097/2536/4095 2007/3319/4962 +f 2655/3244/4886 2666/3250/4896 2661/2915/4488 +f 3231/3408/6217 3230/2383/5164 3229/2382/5393 +f 1759/1904/3499 1760/3547/5245 1761/3548/5246 +f 2602/2800/4369 2625/3095/4697 2626/3697/5460 +f 2516/3222/4857 2679/1941/3530 2685/3911/5875 +f 2070/2520/4079 1957/3141/4758 1950/2518/4077 +f 1754/2215/3781 1753/4000/6218 1767/2034/3612 +f 3736/3857/5766 3737/3928/5917 3739/2031/3609 +f 2045/2869/4506 2232/2929/4505 2041/1910/5673 +f 3058/3449/5120 3053/1913/3507 3055/2335/3892 +f 2475/2439/4003 2244/3497/6219 2239/2261/5501 +f 2061/2670/4242 2060/1765/4889 2063/2661/4234 +f 2543/3514/6001 2547/3381/5846 2306/2592/5848 +f 3709/3434/6085 3708/1948/3536 3723/3987/6083 +f 2193/3425/5086 2201/3612/5320 2212/3900/5855 +f 2817/3694/5454 2819/2546/4105 2832/1847/3444 +f 2695/2130/3707 2690/2713/4285 2696/2972/4558 +f 2611/3108/4712 2631/3920/5895 2610/3317/4960 +f 2162/3117/4722 2157/3975/6050 2158/2669/4241 +f 2270/3515/5210 2262/3512/5207 2263/3513/5208 +f 2493/3155/4777 2276/4020/6220 2264/3633/5353 +f 3511/3274/4915 3546/2601/4168 3547/3796/5647 +f 2092/1928/3522 1994/2814/4382 1993/1929/3523 +f 3283/1715/3321 3295/3698/5461 3292/2070/3648 +f 1919/4021/2634 2232/2929/2634 2230/3883/2634 +f 2070/2520/4461 2219/3430/5092 2218/2886/4462 +f 3242/2241/4675 3240/2240/5911 3241/3079/4674 +f 3867/1679/3289 3858/1678/3289 3865/3657/3289 +f 3122/1802/5806 3121/2304/5170 3123/3906/6080 +f 2368/2568/4127 2367/1770/3371 2406/3923/5904 +f 2615/2662/4235 2620/2114/3693 2621/2663/4236 +f 2410/4022/6221 2411/4023/6222 2461/1975/3562 +f 2995/3914/5880 2994/1799/6215 2993/2944/4529 +f 1803/3020/4616 1965/3471/5152 1968/3021/4617 +f 3622/1682/3280 3630/3929/3280 3612/1737/3280 +f 2449/2668/4240 2601/3473/5154 2600/2667/4239 +f 3066/2938/4521 3067/2425/3988 3068/2427/3990 +f 3042/2296/3853 3043/2796/4365 3060/3977/6052 +f 2272/1900/3494 2273/3525/5220 2274/1898/3492 +f 3156/2330/3886 3144/2179/3932 3157/2747/4322 +f 2687/2026/3606 2684/2531/4090 2685/3911/5875 +f 3246/1866/3699 3264/3717/3699 3249/3247/5069 +f 2726/3401/3464 2732/1869/3465 2733/1868/3465 +f 3568/3421/5082 3567/2267/5470 3566/2266/3533 +f 3521/1740/3341 3520/1763/3364 3533/1741/3342 +f 2265/3526/5221 2266/3817/5686 2264/3633/5687 +f 2195/3963/6005 2213/4012/6186 2215/2891/4468 +f 2223/1901/2635 2224/1902/2635 1926/3362/2635 +f 2574/2639/4207 2578/3298/4944 2582/3135/4745 +f 1895/3009/4605 1894/2795/4364 1989/1832/3428 +f 1927/3361/5012 1926/3362/2635 2224/1902/2635 +f 2209/2684/4256 1890/3308/6223 1986/2685/4257 +f 3271/2228/3794 3260/3636/5359 3272/3748/5930 +f 1692/3945/6171 1693/2514/6171 1691/2305/4229 +f 3706/3630/3827 3707/3110/5072 3711/3413/3827 +f 2857/3597/5298 2858/2902/4477 2873/2904/4479 +f 3383/1967/3281 3381/3926/3281 3365/2960/3281 +f 3208/2018/3600 3206/3295/6224 3316/2019/3600 +f 1938/2672/4244 1900/2807/4376 1899/3147/4768 +f 2788/2714/4287 2807/1862/3870 2784/1856/3872 +f 3308/2919/4491 3309/2127/3704 3205/1860/3456 +f 2750/3262/4905 2774/1906/4906 2749/3365/6078 +f 3417/1875/3471 3416/3353/5001 3419/2834/4406 +f 2088/2970/4556 2089/2732/4306 2096/2733/4307 +f 3318/3934/3361 3314/3810/3361 3313/3691/3361 +f 3843/3997/3288 3841/1951/3288 3874/3428/3288 +f 3859/3641/6225 3861/3848/5889 3822/3903/5891 +f 3766/2997/4589 3765/1784/3385 3750/2992/4587 +f 3507/3329/6092 3525/3289/6091 3526/2978/6226 +f 2387/2411/3977 2364/3542/5240 2361/2409/3975 +f 3815/2487/4051 3814/3986/4051 3808/3405/4052 +f 3054/2295/3852 3041/3076/5467 3042/2296/3853 +f 3096/2423/6227 3174/3772/5613 3175/3252/4897 +f 3507/3329/6092 3508/3507/5348 3524/3438/5350 +f 1671/3433/5096 1674/3688/5445 1777/2325/3881 +f 2794/2238/3802 2795/1704/3310 2782/3680/5538 +f 3974/3313/3512 3966/2341/3512 3964/3078/3512 +f 2102/3738/5536 2103/3284/4929 2101/3490/5182 +f 3216/1859/3455 3215/1939/3528 3214/2319/3361 +f 3424/3980/6057 3421/2836/4408 3422/2835/4407 +f 2374/2864/4436 2377/3606/5310 2373/3604/5308 +f 2493/3155/6121 2494/3634/6228 2492/3152/4774 +f 3814/3986/4051 3811/3437/4052 3808/3405/4052 +f 3071/2300/3857 3069/2486/4050 3034/1803/3402 +f 3934/3032/4627 3935/2510/4070 3933/2214/4628 +f 3821/2489/4051 3816/1983/4051 3815/2487/4051 +f 3905/3880/5811 3904/3233/4870 3877/1809/5201 +f 1916/4024/6229 1927/3361/5012 2220/1766/2635 +f 3588/3182/4812 3581/3187/4817 3619/3180/4810 +f 1858/2767/5329 1859/2766/4339 2016/2556/4116 +f 2159/3700/5465 2160/3699/5464 2058/1842/3439 +f 1932/2490/4053 2186/2734/4308 2187/3248/4892 +f 2225/3364/2635 2223/1901/2635 1926/3362/2635 +f 2279/3203/5307 2282/2911/4483 2281/2908/4485 +f 3352/2061/3638 3355/2063/3640 3353/3897/6122 +f 3807/3287/4051 3808/3405/4052 3809/3288/4931 +f 1888/4025/6230 1889/3307/4952 1987/2288/3848 +f 3898/1984/3571 3816/1983/3570 3821/2489/4753 +f 2847/2764/4337 2839/2095/6133 2846/2144/5351 +f 3921/3925/6161 3815/2487/6231 3922/3941/6231 +f 3169/2171/3745 3184/2173/3747 3182/3921/5896 +f 3516/2609/4176 3515/2459/4021 3555/3239/4880 +f 2183/2934/4516 2184/2579/4142 2180/2286/3846 +f 2032/2857/4428 2031/2359/3918 2030/4026/6232 +f 2920/2142/5907 2931/3856/5765 2932/2922/4498 +f 3343/3819/5692 3367/3418/5975 3342/3253/6185 +f 3820/3226/4052 3818/2413/4052 3817/2488/4052 +f 3263/2865/3699 3264/3717/3699 3246/1866/3699 +f 3661/1978/3565 3653/2363/4972 3652/2757/4330 +f 2717/3168/5974 2715/2111/3690 2510/2443/4007 +f 2342/1893/5293 2341/3591/5292 2340/1894/5289 +f 3212/3711/3362 3214/2319/3361 3213/1775/3376 +f 3687/2181/5157 3569/3683/5157 3570/2540/5157 +f 1716/3768/5601 1715/3756/5600 1713/3622/5337 +f 3499/2823/3815 3506/2771/3815 3488/3251/3815 +f 3857/4008/6161 3856/3751/5572 3858/1678/6231 +f 2706/2674/2635 2433/3871/3275 2710/3870/3275 +f 2920/2142/5907 2919/2141/6213 2931/3856/5765 +f 3187/3958/5990 3084/2280/3843 3185/3833/5724 +f 3614/1738/4860 3613/2110/3689 3615/3225/4861 +f 3241/3079/3699 3269/3179/3699 3244/1865/3699 +f 3139/3486/3730 3140/3716/3730 3123/3906/3730 +f 3020/2350/3296 3019/2007/3296 2985/2006/3296 +f 3735/3927/5915 3733/3713/6214 3734/3536/5916 +f 3524/3438/5107 3523/3164/4788 3537/3933/5929 +f 2831/3919/5894 2798/2477/4041 2797/2011/3593 +f 3509/2069/3647 3519/1764/3365 3520/1763/3364 +f 2951/2094/6233 2849/2010/6234 2955/2009/6234 +f 2733/1868/5113 2828/1706/3312 2826/3153/4775 +f 2830/3724/5506 2832/1847/3444 2831/3919/5894 +f 3999/3100/4700 4013/3102/4702 4012/2380/3945 +f 3214/2319/3361 3206/3295/3361 3216/1859/3455 +f 3774/1757/3358 3773/3598/5299 3759/2451/5301 +f 3340/1786/3281 3336/1670/3281 3344/2813/3281 +f 3462/2346/3903 3461/2722/3815 3464/2251/3815 +f 3860/1677/3288 3863/2428/3289 3862/2935/3288 +f 3650/1732/3335 3649/3771/5898 3660/1733/3336 +f 3732/2293/6037 3731/3712/6037 3729/3964/6103 +f 4029/3985/6075 4027/3351/4998 3986/3163/4999 +f 3490/3207/4839 3489/2447/4453 3491/2881/4455 +f 3491/2881/3815 3500/2545/3815 3499/2823/3815 +f 2528/2473/4037 2529/3901/5859 2530/2474/4038 +f 2172/3563/5262 2176/3562/5261 2177/3519/5214 +f 2032/2857/5996 2034/2859/6235 1878/3088/5997 +f 2055/1844/3441 2164/1792/3392 2161/3701/5466 +f 3410/3767/5598 3409/3343/4983 3401/1676/3287 +f 1672/2727/4301 1667/2737/4311 1770/3739/5541 +f 3110/2282/3730 3138/2860/3730 3142/4014/3730 +f 3778/3056/4652 3695/3055/4651 3777/3794/6145 +f 3177/3332/4974 3093/3331/4973 3175/3252/4897 +f 2831/3919/5894 2812/2478/4042 2798/2477/4041 +f 3486/2773/4849 3483/2654/4224 3484/2655/4226 +f 3785/2219/3785 3772/2230/3796 3773/3598/5299 +f 3512/3189/4819 3511/3274/4915 3550/3188/4818 +f 3137/3763/3730 3136/2281/3730 3108/2283/3730 +f 1791/2637/5315 1796/3474/5317 1794/2333/4121 +f 1935/2530/4089 2207/2201/3768 2179/3261/4904 +f 3870/3692/3289 3872/2564/3289 3852/2659/3289 +f 1692/3945/6171 1691/2305/4229 1690/2657/4228 +f 1720/3136/4746 1718/2208/3776 1689/1932/3775 +f 3892/4013/6195 3893/1685/3295 3902/3989/6093 +f 2475/2439/4111 2476/2553/4113 2417/4027/6236 +f 2976/1688/3397 2975/2742/4317 2991/2744/4319 +f 3932/3041/4635 3928/3040/4634 4034/3107/4711 +f 2571/2775/4346 2700/1820/3416 2701/2774/4345 +f 2697/3409/5070 2451/3967/6017 2696/2972/4558 +f 3979/3191/3512 3980/3312/3512 3962/2760/3512 +f 3884/3654/6237 3885/2408/4033 3916/2469/4032 +f 2655/3244/4886 2656/3060/4656 2660/3059/4655 +f 3413/3301/4947 3412/3583/5282 3414/3805/5666 +f 2435/1821/3417 2686/3826/5708 2436/1819/3415 +f 3386/2197/4644 3397/3442/5450 3398/3049/4645 +f 2281/2908/2635 2280/2912/2635 2722/2909/2635 +f 1672/2727/4301 1675/3064/3475 1673/1879/3475 +f 2415/4005/6147 2471/3014/4611 2470/4016/6206 +f 3709/3434/6085 3725/3988/6084 3726/3660/5702 +f 2782/3680/5538 2781/3656/5391 2794/2238/3802 +f 3732/2293/6037 3729/3964/6103 3730/3948/6102 +f 3020/2350/3296 2984/2679/4251 2982/3402/3296 +f 3757/3979/3827 3759/2451/3827 3722/2450/3827 +f 2650/2964/4550 2514/3223/4858 2641/3584/5284 +f 2333/3068/4663 2332/2982/4569 2331/2981/4568 +f 3870/3692/5452 3875/1717/3972 3885/2408/3974 +f 2203/3839/5740 2197/3529/5225 2174/1791/3391 +f 1939/3747/5562 2153/3827/5711 2140/1671/3282 +f 2808/2314/5294 2807/1862/3458 2823/2180/3752 +f 2149/2850/4423 2138/2254/3818 2137/3072/4667 +f 3069/2486/4050 3068/2427/3990 3047/2426/3989 +f 3176/2338/3895 3178/3837/5735 3179/3333/4975 +f 3322/3560/6238 3328/3206/3734 3323/3574/3734 +f 2673/2091/3670 2678/3236/4873 2671/2092/3671 +f 2889/3482/3592 2890/3483/3592 2888/3610/5318 +f 1993/1929/3523 1994/2814/4382 1995/2816/4384 +f 1844/3667/5899 1842/2631/5987 2007/3319/5989 +f 2662/3275/4916 2566/3816/5684 2663/3815/5683 +f 2494/3634/5354 2264/3633/5353 2267/2730/5877 +f 2691/2712/4284 2695/2130/3707 2694/2132/3709 +f 2580/2188/3759 2577/2373/3936 2586/2189/3760 +f 3260/3636/3699 3257/3761/3699 3255/3246/3699 +f 2379/3609/5313 2376/3605/5309 2375/2863/4435 +f 3047/2426/3989 3067/2425/3988 3033/2117/3696 +f 3447/2818/4385 3456/2900/4476 3532/2262/3826 +f 2798/2477/4041 2799/2476/4040 2785/3339/5963 +f 2167/3734/5525 2170/3759/5583 2171/3885/5822 +f 3970/2826/5584 3943/2827/6239 3936/3993/6109 +f 3076/2505/3713 3075/1968/3713 3079/2503/3713 +f 3630/3929/5921 3622/1682/3292 3642/2789/4358 +f 2098/2500/4062 2009/2268/3829 2010/2501/4063 +f 2820/2547/4106 2819/2546/4105 2818/3139/4751 +f 2729/2705/4279 2728/3400/6019 2824/3160/4782 +f 1813/1696/3304 1806/3464/5978 1808/3619/5331 +f 3784/2218/3784 3786/2217/3783 3702/3746/5561 +f 3270/3457/3699 3241/3079/3699 3238/3053/3699 +f 2228/3216/2635 2226/3218/2635 1917/3959/5991 +f 4011/2378/3943 4012/2380/3945 4013/3102/4702 +f 3455/2819/4386 3447/2818/4385 3557/2607/4174 +f 3255/3246/3699 3258/2120/3699 3226/2122/3699 +f 3836/2015/4985 3837/3874/5798 3824/3344/4986 +f 1853/2523/4082 1854/3939/4080 1855/2521/4080 +f 3293/1938/3527 3290/1937/3526 3292/2070/3648 +f 3431/2780/4351 3430/4028/6240 3432/2107/3685 +f 3767/3779/5688 3755/2996/4588 3756/3996/6241 +f 2699/3410/5071 2700/1820/3416 2571/2775/4346 +f 2478/3019/5870 2484/3669/5410 2251/3505/5871 +f 2927/2089/3668 2928/3652/5383 2926/3653/5385 +f 3713/3766/3827 3714/1744/3827 3711/3413/3827 +f 3971/2044/3622 3945/3296/4942 3943/2827/4396 +f 2912/2170/3744 2911/3395/5051 2943/3853/5759 +f 3833/3918/6077 3831/3847/5752 3832/2901/5881 +f 2143/1735/3338 2145/3576/5272 2126/3991/6104 +f 3727/3661/5400 3725/3988/6135 3724/2452/5777 +f 2828/1706/3312 2829/2012/3594 2813/4029/6242 +f 2852/2786/4924 2854/3916/5884 2925/2591/4158 +f 1941/2653/5994 2003/2652/6243 2001/3961/5993 +f 2828/1706/3312 2813/4029/6242 2795/1704/3310 +f 3634/2151/3280 3635/3411/3280 3602/2002/3280 +f 3609/2432/3996 3607/2123/3700 3608/2433/3997 +f 3856/3751/5572 3855/3910/5572 3853/3752/5573 +f 2666/3250/4896 2665/2916/4489 2661/2915/4488 +f 2362/4030/6244 2359/4031/6245 2358/3999/6138 +f 2848/2923/4499 2932/2922/4498 2931/3856/5765 +f 2275/2729/4302 2490/3912/5878 2488/3543/5876 +f 2884/2804/5698 2885/3491/5967 2886/3640/5699 +f 2565/2385/3950 2662/3275/4916 2569/3151/4773 +f 3263/2865/4439 3269/3179/4808 3279/2321/4437 +f 3289/3946/6162 3258/2120/6111 3271/2228/3794 +f 2569/3151/4773 2567/2386/3951 2565/2385/3950 +f 2911/3395/6246 2912/2170/4405 2903/2833/4404 +f 3180/3348/4995 3086/2246/3810 3179/3333/4975 +f 1856/3813/6247 2015/3467/5534 1854/3939/5942 +f 2454/3476/5158 2326/3581/5546 2324/3458/5128 +f 3247/3048/6175 3245/1867/3463 3246/1866/3462 +f 3066/2938/4521 3031/3595/5296 3032/3118/4723 +f 3318/3934/6042 3212/3711/6042 3203/1761/6042 +f 1753/4000/6218 1752/3327/5491 1767/2034/3612 +f 4041/2854/4425 4042/2212/4633 4043/2910/4425 +f 2294/2595/4162 2292/3544/5242 2293/2596/4163 +f 2503/2719/4292 2663/3815/5683 2648/3243/4885 +f 3226/2122/4271 3227/2699/4273 3225/3725/5511 +f 3111/3627/6248 3098/3984/6249 3109/3138/6250 +f 2205/2364/3923 2113/2366/3925 1931/2289/3849 +f 3880/1848/5054 3911/2128/3705 3910/3397/5055 +f 3903/3234/4871 3902/3989/6093 3893/1685/3295 +f 2834/3858/5769 2726/3401/5769 2727/3220/6251 +f 3115/2549/6089 3117/3762/6252 3101/2603/4170 +f 3058/3449/5120 3055/2335/3892 3057/2336/3893 +f 2889/3482/3592 2891/1964/5168 2892/3440/5168 +f 2677/2025/3605 2438/2671/4243 2684/2531/4090 +f 1738/2495/4511 1748/2444/4008 1749/3917/5888 +f 2363/3998/6137 2362/4030/6244 2358/3999/6138 +f 3936/3993/6109 3943/2827/6239 3944/2390/3955 +f 2437/3811/5677 2520/3860/5771 2521/3027/5726 +f 3111/3627/6248 3099/2801/5604 3098/3984/6249 +f 3093/3331/4973 3096/2423/6227 3175/3252/4897 +f 3819/3392/5046 3810/3569/4052 3812/3568/4052 +f 1690/2657/5955 1723/2656/6253 1680/1931/5764 +f 2825/3830/5716 2814/1705/3311 2827/2237/3801 +f 2479/3083/6254 2478/3019/5870 2246/3503/5198 +f 2160/3699/5464 2063/2661/4234 2058/1842/3439 +f 2499/3676/5850 2722/2909/5849 2280/2912/4495 +f 3149/2344/3901 3150/2841/4413 3190/2840/4412 +f 2152/2252/3816 2154/2939/4522 2072/2803/4372 +f 1794/2333/3889 1796/3474/5155 1956/2334/3890 +f 2924/2041/3619 2908/2138/3714 2896/3718/5495 +f 2455/2678/4250 2694/2132/3709 2683/3968/6018 +f 3765/1784/3385 3766/2997/5621 3798/3671/5412 +f 3888/2598/5517 3876/1716/4410 3874/3428/5515 +f 2587/2403/3968 2603/2405/3970 2593/3105/4709 +f 3471/3924/5981 3472/3330/5980 3470/3795/6009 +f 3978/3832/5722 4005/3198/4829 4004/2186/5723 +f 3384/1841/3281 3350/1813/3281 3353/3897/3281 +f 3399/3300/5737 3387/2198/4643 3398/3049/4645 +f 3576/3797/5781 3572/2844/4416 3662/1976/3563 +f 3457/2941/5374 3536/3166/4790 3535/3165/4789 +f 3254/2917/5049 3224/3393/5048 3223/3380/5026 +f 2452/3742/5548 2559/3346/4989 2329/2419/5732 +f 2453/3741/6110 2575/2370/3933 2452/3742/6255 +f 3758/2264/3827 3757/3979/3827 3719/2265/3827 +f 1800/3528/5224 1966/3776/5618 1965/3471/5152 +f 4007/2914/4487 4002/2464/6256 4003/2185/3756 +f 3891/2986/4574 3892/4013/6195 3901/2987/4575 +f 3217/3439/3699 3218/2384/3949 3219/3802/5661 +f 2133/2516/4075 2134/3121/4728 2123/2517/4076 +f 3712/3970/6027 3735/3927/6257 3736/3857/6028 +f 1990/1694/3302 1900/2807/4376 1938/2672/4244 +f 2183/2934/4516 2071/3603/5306 1975/2756/4329 +f 3511/3274/4915 3512/3189/4819 3501/3272/4913 +f 3106/1959/4749 3107/1958/6258 3108/2283/4750 +f 2453/3741/6110 2454/3476/6081 2553/3126/4736 +f 3127/3017/4792 3128/2097/5773 3126/2711/4792 +f 3243/3461/5132 3245/1867/6259 3221/2242/3806 +f 2330/2980/4567 2329/2419/3985 2331/2981/4568 +f 3317/3294/3361 3318/3934/3361 3313/3691/3361 +f 3632/2362/3280 3627/2361/3280 3596/3770/5005 +f 3045/2349/3906 3044/2368/3929 3020/2350/3907 +f 2882/2805/4374 2880/3279/4920 2859/3034/4922 +f 3663/2243/3807 3662/1976/3563 3572/2844/4416 +f 3980/3312/6131 3994/1840/6177 3993/1839/6021 +f 3432/2107/3685 3434/2106/3684 3407/1992/3579 +f 1956/2334/4210 1958/3475/6260 1957/3141/4758 +f 1930/3455/5126 1913/3555/5253 1912/4032/6261 +f 2763/3642/5580 2764/2221/3787 2765/2220/3786 +f 2795/1704/3310 2794/2238/3802 2814/1705/3311 +f 3865/3657/5394 3871/2565/5741 3881/3719/5496 +f 3786/2217/3783 3785/2219/3785 3773/3598/5299 +f 2936/3978/6055 2937/2765/4338 2938/3784/5628 +f 2288/1698/6262 2283/3971/6262 2286/3540/6262 +f 3272/3748/5563 3273/3119/5885 3304/3749/5564 +f 3504/2977/6263 3507/3329/6263 3526/2978/6263 +f 3925/2090/3669 3929/2511/4071 4025/2104/3682 +f 3022/2119/3296 3017/2118/3296 3005/3127/3296 +f 3868/1683/3289 3835/2017/3289 3832/2901/3288 +f 2482/1689/5710 2658/3058/4654 2664/1836/3432 +f 3509/2069/3647 3505/2772/6014 3518/3966/6013 +f 2991/2744/4319 2993/2944/5807 2976/1688/3397 +f 2020/3554/6264 2014/3466/5147 2017/2558/4118 +f 2045/2869/4443 2041/1910/3504 2044/1909/3503 +f 2155/2436/4000 2154/2939/4522 2153/3827/5711 +f 2557/3838/6265 2558/3345/6266 2574/2639/4207 +f 2790/3293/3454 2763/3642/3454 2765/2220/3454 +f 2059/1843/3440 2054/3955/5983 2055/1844/3441 +f 1712/3981/3525 1732/2145/3525 1709/2147/3525 +f 3313/3691/3361 3315/2020/3361 3316/2019/3361 +f 3402/2740/4314 3409/3343/4983 3416/3353/5001 +f 3842/3731/5521 3844/2937/4519 3826/2936/4518 +f 1919/4021/2634 2230/3883/2634 1920/3956/2634 +f 1743/2324/3880 1742/2358/3916 1757/3316/4959 +f 2596/3972/6026 2668/3435/5104 2473/2872/4447 +f 2829/2012/3594 2830/3724/5506 2797/2011/3593 +f 3475/1777/3378 3472/3330/5980 3473/3632/5352 +f 1806/3464/5138 1970/2994/5146 1948/2933/5135 +f 3439/3782/3734 3437/3781/3734 3441/3865/3734 +f 2792/3371/5015 2793/2239/3803 2781/3656/5391 +f 2852/2786/4924 2925/2591/4158 2949/2590/4157 +f 3425/2086/3664 3423/2085/3663 3424/3980/6057 +f 1885/4033/6267 1984/3608/5312 1886/4034/6268 +f 2146/3323/4966 2147/3575/5271 2148/1672/3283 +f 1695/2664/6155 1696/3359/5009 1697/3360/5010 +f 2321/2931/5471 2324/3458/5279 2322/3704/5472 +f 2439/2082/3660 2677/2025/3605 2676/3111/4716 +f 2157/3975/6050 2061/2670/4242 2158/2669/4241 +f 3244/1865/3461 3243/3461/6269 3242/2241/4675 +f 1740/2135/3712 1741/2357/5435 1728/2133/3710 +f 3334/2163/3735 3332/3806/5667 3331/2161/3734 +f 2812/2478/4042 2831/3919/5894 2832/1847/3444 +f 2667/3249/4895 2660/3059/4655 2668/3435/5104 +f 1943/2995/4586 1999/4035/6270 1997/2821/4388 +f 1869/2689/4261 1865/2688/4260 1868/3690/5447 +f 3000/1752/3353 3003/2893/4470 3001/2895/4472 +f 3690/1709/6271 3802/3561/6271 3691/1707/6271 +f 2894/1878/3474 2902/3071/4666 2914/3375/5021 +f 3151/2298/5636 3152/2297/6086 3192/2956/4542 +f 3957/3735/5905 3956/3063/4763 3959/2759/4332 +f 3221/2242/3699 3222/2499/3699 3223/3380/3699 +f 3543/4006/6148 3451/1972/4399 3448/1971/5714 +f 1977/2065/3643 1983/3976/6272 1819/2064/3641 +f 4028/3792/5640 4029/3985/6075 3986/3163/4999 +f 3379/1925/3519 3380/1814/6196 3404/1926/3520 +f 3764/1783/3384 3763/2526/4832 3751/3256/4898 +f 2962/3447/5118 2959/2369/3931 2957/3324/3713 +f 2460/3639/5364 2638/2898/4475 2396/3508/5203 +f 2857/3597/5298 2856/2572/4131 2855/3033/3725 +f 2869/3582/5487 2868/2573/6070 2870/2166/3739 +f 3310/2126/3703 3311/1861/3457 3309/2127/3704 +f 2650/2964/4550 2681/1942/3531 2679/1941/3530 +f 1955/2332/3888 1960/2640/6207 1794/2333/3889 +f 2716/3801/2635 2714/2534/2635 2424/3957/2635 +f 3997/3789/5637 3998/3743/5553 4008/3649/5380 +f 3176/2338/3895 3179/3333/4975 3177/3332/4974 +f 1873/2360/6273 1870/2690/6273 2028/3484/6273 +f 2783/1857/5682 2784/1856/3872 2809/2704/4579 +f 3748/3200/4831 3751/3256/4898 3763/2526/4832 +f 3960/2761/4334 3958/2067/6066 3959/2759/4332 +f 1889/3307/4952 2208/3306/4951 1987/2288/3848 +f 2147/3575/5271 2111/2648/4217 2112/1673/3284 +f 3026/1797/3296 3021/3487/3296 3000/1752/3296 +f 3180/3348/4995 3181/2247/3811 3086/2246/3810 +f 2731/3347/3464 2734/3133/3464 2727/3220/3464 +f 2138/2254/3818 2149/2850/4423 2151/2479/4043 +f 3791/3004/4600 3794/2946/4533 3792/3005/4601 +f 1785/2751/5992 1670/3960/5992 1784/2752/5992 +f 2820/2547/4106 2815/2461/4023 2816/2548/4107 +f 3163/1754/4993 3180/3348/4995 3178/3837/5735 +f 2940/2274/3834 2944/2168/3742 2942/3394/5050 +f 2080/2855/4426 2090/2856/4427 2091/2991/4580 +f 3534/3423/5084 3456/2900/4476 3535/3165/4789 +f 2060/1765/3366 2221/3399/5058 2220/1766/3367 +f 1932/2490/4053 1933/3214/4847 1934/2735/4309 +f 3793/1773/3374 3792/3005/4601 3794/2946/4533 +f 2461/1975/3562 2414/3538/5236 2462/3881/6274 +f 2779/3760/3454 2781/3656/3454 2777/1730/3454 +f 3083/2279/3842 3082/1703/3841 3085/2245/3809 +f 3751/3256/3827 3748/3200/3827 3745/2641/3827 +f 1752/3327/5491 1765/2035/3613 1767/2034/3612 +f 2854/3916/5884 2850/2087/3666 2927/2089/3668 +f 2721/1954/2635 2719/3730/2635 2427/1952/3540 +f 3340/1786/5406 3359/3665/5405 3357/3478/6062 +f 3410/3767/5598 3400/1675/3286 3415/2418/3984 +f 3549/3829/5715 3550/3188/4818 3548/2600/4167 +f 4042/2212/6275 4041/2854/6275 3927/3039/6275 +f 2748/3366/3454 2746/2352/3910 2742/3265/3454 +f 3130/1957/3543 3131/2716/3544 3107/1958/3544 +f 2071/3603/5306 2180/2286/3846 2181/3983/6074 +f 2547/3381/5846 2546/3818/6276 2310/3567/5852 +f 3790/2954/4540 3789/3003/4599 3779/3460/5131 +f 2627/2580/4143 2628/2400/3965 2619/2115/3694 +f 2519/3812/5678 2684/2531/4090 2438/2671/4243 +f 2919/2141/3715 2905/1962/5498 2918/1961/6277 +f 2154/2939/4522 2156/2435/3999 2072/2803/4372 +f 1925/4001/3274 2219/3430/3271 1789/2481/3274 +f 2574/2639/4207 2582/3135/4745 2581/1890/3484 +f 2003/2652/6243 2002/2984/6278 2001/3961/5993 +f 3287/3710/5480 3286/2415/3981 3262/2417/3983 +f 2712/3025/2635 2710/3870/2635 2432/3872/2635 +f 3504/2977/4282 3470/3795/3815 3472/3330/4282 +f 2697/3409/5070 2698/3553/5251 2699/3410/5071 +f 3474/1778/4297 3473/3632/6126 3460/2249/3926 +f 2214/2892/4469 2213/4012/6186 2208/3306/4951 +f 3748/3200/3827 3747/3551/3827 3745/2641/3827 +f 1857/2522/5533 1860/3684/5440 1863/2768/4341 +f 2202/3590/5291 2201/3612/5320 2200/2046/3625 +f 2659/1837/3433 2568/1986/3573 2489/4036/6279 +f 2089/2732/4306 2100/3737/5535 2098/2500/4062 +f 3606/2124/3701 3608/2433/3997 3607/2123/3700 +f 3616/3224/3280 3618/3705/3280 3623/1782/5965 +f 2556/4037/6280 2338/3587/6281 2557/3838/5738 +f 2619/2115/3694 2628/2400/3965 2629/2116/3695 +f 2033/2858/4429 2032/2857/4428 1939/3747/5562 +f 2012/2269/3830 2136/3489/5181 2077/2402/3967 +f 3721/1947/3535 3723/3987/6083 3708/1948/3536 +f 2249/3502/5197 2246/3503/5198 2237/3504/5199 +f 3106/1959/3726 3109/3138/6250 3098/3984/6249 +f 3649/3771/5898 3659/3783/5627 3660/1733/3336 +f 2371/3602/5304 2373/3604/5308 2388/3651/5382 +f 1954/2666/4759 1952/2738/4312 1950/2518/4077 +f 2308/3566/5265 2307/3532/5229 2306/2592/4159 +f 2971/3448/5119 3051/3950/5971 3053/1913/3507 +f 3113/3628/3730 3110/2282/3730 3142/4014/3730 +f 1669/2693/3475 1676/1881/3475 1677/2691/3475 +f 2511/2225/3791 2641/3584/5284 2512/2223/3789 +f 2221/3399/2635 1916/4024/6229 2220/1766/2635 +f 2444/2963/4549 2441/4011/6183 2651/2965/4551 +f 3400/1675/3286 3385/1674/3285 3387/2198/4643 +f 2529/3901/5864 2705/3732/5522 2704/3866/5820 +f 2683/3968/6018 2533/2762/4335 2455/2678/4250 +f 2198/2048/3627 2197/3529/5225 2203/3839/5740 +f 3210/2736/4310 3303/2226/3792 3304/3749/5564 +f 2006/2502/4064 2007/3319/4962 2097/2536/4095 +f 2253/2606/5411 2251/3505/5871 2484/3669/5410 +f 3755/2996/3827 3739/2031/3827 3737/3928/3827 +f 2919/2141/6213 2929/3908/5869 2930/2088/3667 +f 2379/3609/5313 2378/3786/5630 2613/3822/5697 +f 2094/2985/4573 2095/1850/3448 2081/1852/3450 +f 2610/3317/4960 2631/3920/5895 2630/3354/5003 +f 2271/1899/3493 2269/3516/5211 2486/3644/5767 +f 3887/2839/5231 3888/2598/4165 3896/2412/3978 +f 3919/3269/4051 3920/3570/4052 3921/3925/4051 +f 3132/3714/5489 3134/2342/3899 3147/3010/4606 +f 3217/3439/5108 3256/3245/5047 3225/3725/5530 +f 4035/2256/3820 3991/3459/6098 3992/2257/3821 +f 3427/1747/3348 3428/1854/3452 3431/2780/4351 +f 2673/2091/3670 2675/3235/4872 2678/3236/4873 +f 2685/3911/5875 2682/3825/5707 2687/2026/3606 +f 3521/1740/5727 3522/1739/5612 3510/2068/3646 +f 2217/3852/5758 2068/2884/6030 2066/2887/4463 +f 3639/1793/5377 3640/2497/4072 3625/1680/3290 +f 2127/3894/5843 2126/3991/6104 2118/3157/4779 +f 2177/3519/5214 2167/3734/5525 2171/3885/5822 +f 3812/3568/5267 3920/3570/5268 3919/3269/6282 +f 3081/1701/3309 3196/3799/3309 3197/1702/3309 +f 2850/2087/3666 2854/3916/5884 2851/2008/3631 +f 3321/3183/4813 3430/4028/6240 3429/1853/3451 +f 3767/3779/5622 3768/2749/4324 3799/3672/5413 +f 2855/3033/4884 2856/2572/4131 2863/1825/4566 +f 2590/1889/3483 2368/2568/4127 2407/3922/5903 +f 3210/2736/4310 3208/2018/5228 3202/3809/6283 +f 1964/2468/5793 1962/2277/6284 1961/3070/4665 +f 3444/1835/6285 3561/1834/6285 3560/3930/6285 +f 2206/3470/5151 2204/2849/4422 2115/2472/4036 +f 1862/2681/4253 1863/2768/4341 1864/2455/6286 +f 3973/2058/3635 3986/3163/4787 4006/2059/3636 +f 2116/3073/4668 2137/3072/4667 2117/3158/4780 +f 2696/2972/4558 2451/3967/6017 2576/2973/4559 +f 3278/2125/3702 3279/2321/3877 3310/2126/3703 +f 2256/1691/5403 2255/3843/5747 2254/2604/4171 +f 3697/1772/3315 3696/1811/5745 3690/1709/3315 +f 3613/2110/5332 3611/2109/5166 3587/3355/5167 +f 1715/3756/5600 1714/3621/5335 1713/3622/5337 +f 3073/1805/3404 3074/2507/4067 3072/2315/3873 +f 3523/3164/4788 3536/3166/4790 3537/3933/5929 +f 3568/3421/5082 3571/3420/5080 3675/1794/3394 +f 3576/3797/5781 3660/1733/3336 3659/3783/5627 +f 3239/3990/6201 3237/3054/4650 3238/3053/4649 +f 2849/2010/4761 2840/2096/3631 2848/2923/3631 +f 2579/3733/5524 2412/3952/5976 2413/3537/5235 +f 3209/1828/3424 3306/1827/3423 3308/2919/4491 +f 3219/3802/5661 3220/3834/3699 3223/3380/3699 +f 1684/1933/3525 1683/3002/4124 1682/3943/3525 +f 2133/2516/4075 2103/3284/4929 2105/3292/4936 +f 2959/2369/3931 2962/3447/5118 3062/2393/3958 +f 3971/2044/3512 3969/1936/3512 3972/1935/3512 +f 2054/3955/6287 2059/1843/3496 2223/1901/3495 +f 2720/2112/3691 2719/3730/5518 2505/3142/5519 +f 2634/1996/3583 2616/2525/4084 2633/3655/5389 +f 3267/3949/3699 3265/1714/3699 3235/3846/3699 +f 3525/3289/4932 3539/2023/3603 3540/2022/3602 +f 2372/3196/4827 2373/3604/5308 2371/3602/5304 +f 3384/1841/3281 3380/1814/3281 3350/1813/3281 +f 3819/3392/5046 3820/3226/4052 3810/3569/4052 +f 1912/4032/6261 1931/2289/3849 1930/3455/5126 +f 3374/2027/3607 3371/2029/3607 3373/2889/3607 +f 2859/3034/3725 2858/2902/3725 2855/3033/3725 +f 1994/2814/4382 2091/2991/4580 1946/2975/4561 +f 3485/3215/5768 3484/2655/6151 3463/3299/4945 +f 3052/1912/3506 3054/2295/3852 3055/2335/3892 +f 2140/1671/3282 2124/3322/4965 2148/1672/3283 +f 2637/3682/5439 2639/1994/3581 2447/2665/4237 +f 1936/2529/4088 2074/2528/4087 2157/3975/6050 +f 1754/2215/4144 1731/3804/5665 1753/4000/6141 +f 3949/2326/4457 3951/2328/5928 3938/2966/4552 +f 2202/3590/5291 2198/2048/3627 2122/3647/5376 +f 3582/3965/6012 3594/3769/6187 3592/3185/4815 +f 3833/3918/5892 3834/2016/4984 3823/3904/5893 +f 2929/3908/5869 2918/1961/5384 2928/3652/5383 +f 2692/4038/6288 2694/2132/3709 2455/2678/4250 +f 1678/3689/3475 1674/3688/3475 1670/3960/3475 +f 2170/3759/5583 2160/3699/5464 2161/3701/5466 +f 2294/2595/6289 2290/2700/6046 2287/1699/6046 +f 3160/2149/3720 3176/2338/3895 3173/2150/3721 +f 3844/2937/5646 3842/3731/6290 3843/3997/6134 +f 2666/3250/4896 2667/3249/4895 2450/3450/5121 +f 3631/2950/3280 3628/3485/3280 3609/2432/3280 +f 3043/2796/4365 3061/2394/3959 3060/3977/6052 +f 3371/2029/4990 3344/2813/4990 3335/2812/4991 +f 2671/2092/3671 2692/4038/6288 2455/2678/4250 +f 3264/3717/3699 3259/3120/3699 3249/3247/5069 +f 1813/1696/3304 1802/3193/4823 1805/2074/3652 +f 1665/3031/3475 1670/3960/3475 1674/3688/3475 +f 2699/3410/5071 2698/3553/5251 2689/3337/4978 +f 2687/2026/3606 2699/3410/5071 2689/3337/4978 +f 2725/4039/6291 2468/3016/6291 2472/3015/6291 +f 3707/3110/4714 3717/3281/5346 3718/2940/4715 +f 2126/3991/6104 2127/3894/5843 2143/1735/3338 +f 2871/2167/6292 2870/2166/6114 2857/3597/5298 +f 2346/3953/5977 2345/3047/4641 2347/2567/6293 +f 4000/3101/4701 4001/2465/4027 4015/2313/3869 +f 3828/3130/4740 3850/2389/5488 3851/2658/5632 +f 3819/3392/5046 3813/3286/4930 3913/3445/5117 +f 1768/2078/3656 1766/2033/3611 1672/2727/4301 +f 2164/1792/3392 2055/1844/3441 2052/1790/3390 +f 2214/2892/4469 1890/3308/6223 2209/2684/4256 +f 3292/2070/3648 3294/2316/3874 3293/1938/3527 +f 2971/3448/5119 3053/1913/3507 3058/3449/5120 +f 3188/1896/3490 3186/3754/5576 3147/3010/4606 +f 3796/1785/3386 3780/2527/4086 3764/1783/3384 +f 4035/2256/3820 4034/3107/4711 4033/3808/5670 +f 1984/3608/5312 1885/4033/6267 2071/3603/5306 +f 2668/3435/5104 2481/3018/4614 2473/2872/4447 +f 2024/2926/5098 1870/2690/5097 1869/2689/5969 +f 1962/2277/6284 1949/2276/5011 1961/3070/4665 +f 3325/3572/5626 3319/3517/6294 3437/3781/5626 +f 3942/1919/4508 3967/2339/6174 3968/2045/5585 +f 3845/2695/4520 3847/2694/5901 3827/3131/4741 +f 2452/3742/6255 2575/2370/3933 2559/3346/6295 +f 3232/3481/3699 3268/2203/5069 3267/3949/3699 +f 1678/3689/3475 1670/3960/3475 1669/2693/3475 +f 2576/2973/4559 2451/3967/6017 2573/2372/3935 +f 3617/3181/5063 3620/2140/4783 3618/3705/5473 +f 1783/3030/4626 1782/2753/4626 1665/3031/4626 +f 1666/2728/3475 1665/3031/3475 1667/2737/4311 +f 3324/3184/4814 3321/3183/4813 3429/1853/3451 +f 3644/2290/3850 3574/3335/4977 3682/3951/5973 +f 1685/2589/4156 1702/2588/4155 1684/1933/4597 +f 2385/3303/4948 2353/3982/6059 2352/3954/5979 +f 3106/1959/3726 3098/3984/6249 3097/2155/3726 +f 1987/2288/3848 1907/3616/5327 1888/4025/6230 +f 3669/2438/4002 3672/3778/5620 3636/2437/4001 +f 2702/3859/6296 2522/3886/5826 2710/3870/5828 +f 3411/3443/5116 3413/3301/4947 3398/3049/5114 +f 2707/2673/3274 2703/2875/2635 2431/3868/2635 +f 2233/2235/3271 1922/4009/6160 1923/2236/3800 +f 2246/3503/5198 2480/3907/5868 2479/3083/6254 +f 2212/3900/5855 2208/3306/4951 2213/4012/6186 +f 1814/1695/5142 1815/1697/5507 1969/2578/5462 +f 2864/1826/3422 2865/2979/4592 2866/3001/4594 +f 1682/3943/3525 1681/3944/3525 1684/1933/3525 +f 3829/3787/3289 3830/3909/3289 3822/3903/3289 +f 3332/3806/5667 3333/3571/5269 3331/2161/3734 +f 2213/4012/6186 2195/3963/6005 2193/3425/5086 +f 1877/3089/4690 1876/2848/5586 1875/3994/6113 +f 2498/3012/5424 2496/3675/5419 2502/2921/5425 +f 2741/1846/3443 2817/3694/5454 2832/1847/3444 +f 2754/3937/5944 2753/3940/5943 2751/3266/5964 +f 2732/1869/5566 2726/3401/5566 2833/3629/5566 +f 2442/3145/4766 2654/3404/5066 2440/3524/5219 +f 3136/2281/3730 3138/2860/3730 3110/2282/3730 +f 3756/3996/3827 3755/2996/3827 3737/3928/3827 +f 1826/2612/4179 1829/2614/4181 1827/2610/4177 +f 2142/1736/3339 2048/3264/6297 2110/3468/5149 +f 3394/2828/4398 3393/1966/3555 3436/3552/5250 +f 1744/1720/3323 1745/1719/5531 1733/2014/3596 +f 2543/3514/5209 2537/3896/6298 2539/3291/4935 +f 3996/2953/4539 3997/3789/5637 4009/2952/4538 +f 1770/3739/5541 1769/2216/3782 1768/2078/3656 +f 3319/3517/6299 3320/3116/6299 3438/3115/6299 +f 3264/3717/5493 3278/2125/4438 3277/3173/6191 +f 2411/4023/6222 2412/3952/5976 2461/1975/3562 +f 2677/2025/3605 2688/2024/3604 2690/2713/4285 +f 2604/3696/5459 2603/2405/3970 2589/2404/3969 +f 1939/3747/5562 2038/3849/5754 2033/2858/4429 +f 2596/3972/6026 2467/4040/6300 2466/3042/4636 +f 2227/3370/5360 2051/3263/5658 2049/2879/5361 +f 2085/3828/5713 2084/1831/3427 2083/1830/3426 +f 3305/1829/3425 3307/3750/5570 3306/1827/3423 +f 2181/3983/6074 2179/3261/4904 2182/2200/3767 +f 3498/3273/4282 3496/3085/4282 3467/3556/4282 +f 2822/2741/4316 2737/3932/5926 2805/2715/5999 +f 3746/3550/5248 3745/2641/4211 3747/3551/5249 +f 2308/3566/5265 2309/3565/5264 2307/3532/5229 +f 1870/2690/5097 2023/2925/5099 2028/3484/6301 +f 2394/3260/4903 2365/4003/6143 2386/2948/4535 +f 2620/2114/3693 2630/3354/5003 2631/3920/5895 +f 2415/4005/6147 2470/4016/6206 2467/4040/6300 +f 3632/2362/3921 3652/2757/5426 3653/2363/3922 +f 2818/3139/4751 2817/3694/5454 2740/3645/5373 +f 1867/3414/5448 1868/3690/5447 1861/2680/4252 +f 3818/2413/3979 3820/3226/4862 3895/2414/3980 +f 3593/3892/6041 3590/3186/6040 3592/3185/5607 +f 2897/1922/3515 2911/3395/6246 2903/2833/4404 +f 3633/1666/3280 3632/2362/3280 3598/1667/3280 +f 3183/3050/4646 3083/2279/3842 3085/2245/3809 +f 3679/2788/4357 3680/2897/4474 3643/3915/5900 +f 3869/2174/3288 3873/3427/3288 3838/3094/3288 +f 2112/1673/3284 2148/1672/3283 2147/3575/5271 +f 3510/2068/3646 3522/1739/5612 3508/3507/5348 +f 3808/3405/4052 3811/3437/4052 3809/3288/4931 +f 2153/3827/5711 2030/4026/6232 2026/2102/3680 +f 2107/2484/4048 2046/3469/5150 2043/2485/4049 +f 3220/3834/6094 3219/3802/5661 3237/3054/6170 +f 2601/3473/5154 2602/2800/4369 2626/3697/5460 +f 3761/3599/3827 3727/3661/3827 3724/2452/3827 +f 3832/2901/5881 3835/2017/3599 3833/3918/6077 +f 3195/2331/3887 3087/3820/5694 3194/2160/3733 +f 2193/3425/5086 2195/3963/6005 2192/3426/5087 +f 3097/2155/3730 3098/3984/3730 3101/2603/4170 +f 2400/3774/5615 2464/3726/5514 2399/3824/5706 +f 1711/2353/5336 1712/3981/6058 1709/2147/3751 +f 2409/3271/4912 2410/4022/6221 2590/1889/3483 +f 3672/3778/5620 3671/3935/5931 3636/2437/4001 +f 2998/1753/5906 2999/3221/6008 2977/1798/3396 +f 2656/3060/4656 2657/2072/3650 2664/1836/3432 +f 2348/2309/5275 2346/3953/5977 2347/2567/6293 +f 2599/2233/3799 2600/2667/4239 2595/2231/3797 +f 2659/1837/3433 2489/4036/6279 2490/3912/6302 +f 3076/2505/6165 2956/2137/6165 3075/1968/6165 +f 2485/3703/6303 2486/3644/6004 2659/1837/3433 +f 3787/2055/3632 3786/2217/3783 3773/3598/5299 +f 1695/2664/6155 1693/2514/6171 1692/3945/6171 +f 3673/3238/4879 3637/1781/4878 3671/3935/5931 +f 2480/3907/6304 2456/1980/3567 2458/1982/3569 +f 2691/2712/4284 2692/4038/6288 2671/2092/3671 +f 2031/2359/3918 2032/2857/4428 1873/2360/3919 +f 2320/3841/6112 2319/2961/4547 2318/1818/3414 +f 2669/2084/3662 2674/2083/3661 2530/2474/4038 +f 2369/1768/3369 2368/2568/4127 2383/2570/4129 +f 3087/3820/5694 3095/2422/3841 3088/3534/4865 +f 2292/3544/6188 2532/2093/3672 2671/2092/3671 +f 2084/1831/3427 2094/2985/4573 1896/3008/4604 +f 3430/4028/6240 3321/3183/4813 3326/2108/3686 +f 2788/2714/3454 2758/2193/3454 2761/2702/3454 +f 3830/3909/5873 3857/4008/6159 3859/3641/6225 +f 2287/1699/6046 2286/3540/6305 2294/2595/6289 +f 3184/2173/3747 3168/2172/3746 3146/3715/5490 +f 2951/2094/6233 2840/2096/6233 2849/2010/6234 +f 2598/3321/4964 2626/3697/5460 2625/3095/4697 +f 3244/1865/3461 3245/1867/3463 3243/3461/6269 +f 2584/3693/5453 2582/3135/4745 2578/3298/4944 +f 3894/1684/3294 3904/3233/4870 3903/3234/4871 +f 2300/2377/6306 2301/3242/6306 2299/3241/6306 +f 3062/2393/3958 3058/3449/5120 3059/3533/5230 +f 2615/2662/4235 2614/2947/4534 2619/2115/3694 +f 3551/2075/3653 3552/2077/3655 3512/3189/4819 +f 3095/2422/5816 3087/3820/5694 3195/2331/3887 +f 2131/2081/3659 2132/2628/4197 2134/3121/4728 +f 3947/3297/6307 3978/3832/3512 3950/3679/6106 +f 1687/2355/3913 1713/3622/5778 1711/2353/3911 +f 2644/3146/4767 2505/3142/4762 2503/2719/4292 +f 3702/3746/5561 3786/2217/3783 3787/2055/3632 +f 2567/2386/3951 2489/4036/6279 2568/1986/3573 +f 3151/2298/3855 3150/2841/5554 3133/2299/3856 +f 3900/1985/3572 3899/2988/4576 3901/2987/4575 +f 3444/1835/6285 3560/3930/6285 3443/2317/6308 +f 3041/3076/4671 3040/3276/4917 3023/3074/4669 +f 2217/3852/2635 1925/4001/3274 1916/4024/6229 +f 3338/1668/5656 3339/3169/4795 3354/2062/4797 +f 2896/3718/3725 2895/3205/3725 2892/3440/3725 +f 2706/2674/2635 2430/3869/2635 2433/3871/3275 +f 2241/3721/6309 2239/2261/3825 2240/2260/3824 +f 3883/3341/4981 3884/3654/6237 3915/3227/4863 +f 3438/3115/3734 3442/3114/6238 3441/3865/3734 +f 3479/3646/5788 3477/2306/5030 3461/2722/4295 +f 3771/2229/3795 3785/2219/3785 3783/2871/4445 +f 2275/2729/4302 2268/2731/4304 2274/1898/3492 +f 3053/1913/3507 3051/3950/5971 3050/1914/3508 +f 1808/3619/5331 1807/3463/6310 1809/3462/6311 +f 1893/2794/4363 1915/4007/6150 1989/1832/3428 +f 2864/1826/3422 2863/1825/3421 2865/2979/4592 +f 1903/4041/6312 1902/1692/3300 1990/1694/3302 +f 2625/3095/4697 2602/2800/4369 2636/2799/4368 +f 2651/2965/4551 2650/2964/4550 2444/2963/4549 +f 3646/2153/3724 3647/3452/5123 3634/2151/3722 +f 2140/1671/3282 2112/1673/3284 2076/3326/4967 +f 3171/3844/5748 3158/2746/5730 3172/3791/5639 +f 2550/3177/5588 2314/3230/5590 2545/3178/5717 +f 4037/3106/4710 4035/2256/3820 4038/1838/3435 +f 2351/1769/3370 2369/1768/3369 2385/3303/4948 +f 1940/2927/4503 2025/3415/6203 2156/2435/3999 +f 2680/1940/3529 2686/3826/5708 2682/3825/5707 +f 1762/3091/4692 1679/1880/4658 1763/3065/4660 +f 3669/2438/4002 3666/2244/3808 3667/2843/4415 +f 3019/2007/4366 3020/2350/3907 3044/2368/3929 +f 2100/3737/5535 2089/2732/4306 2087/2971/4557 +f 2057/3217/5007 2053/2878/4451 2052/1790/3390 +f 1746/3104/4706 1781/3212/4845 1758/1903/3498 +f 1802/3193/6313 1789/2481/6313 1791/2637/6313 +f 3145/2745/3730 3144/2179/3730 3118/2178/3730 +f 2282/2911/4496 2501/3013/6314 2502/2921/4497 +f 2460/3639/5364 2398/3638/5363 2640/1995/3582 +f 2723/3635/5356 2504/2721/6315 2506/2720/5357 +f 2968/2942/4527 2970/3099/5500 3049/2506/4066 +f 3468/3454/5256 3469/2367/6010 3470/3795/6009 +f 3878/3506/5202 3879/1849/5056 3910/3397/5055 +f 3593/3892/6041 3591/2139/4785 3590/3186/6040 +f 1874/2697/4270 1873/2360/4269 1878/3088/4689 +f 2953/2053/5002 2846/2144/5002 2952/3593/5002 +f 2969/3564/5938 3080/2504/5938 3079/2503/5938 +f 2193/3425/5086 2190/3424/5085 2200/2046/3625 +f 3580/2210/3778 3683/2040/3618 3682/3951/5973 +f 2037/2448/6054 2035/3493/6158 2038/3849/5754 +f 3530/3902/5863 3558/2608/4175 3559/3122/4729 +f 2946/2169/3743 2947/3376/5023 2913/2832/5022 +f 3024/3075/4670 3042/2296/3853 3041/3076/4671 +f 3750/2992/4587 3765/1784/3385 3749/2993/4899 +f 3996/2953/6197 3979/3191/6129 3984/3790/5638 +f 3185/3833/5724 3183/3050/4646 3184/2173/3747 +f 3287/3710/5712 3207/1724/3327 3300/3836/5729 +f 2171/3885/5822 2163/3618/5330 2172/3563/5262 +f 2494/3634/6228 2488/3543/5241 2492/3152/4774 +f 3096/2423/3841 3093/3331/4973 3091/3336/3841 +f 2892/3440/3725 2899/3204/3725 2890/3483/3725 +f 3492/2880/4454 3495/3057/4684 3494/2709/5693 +f 3141/1756/3730 3143/2374/3730 3116/2551/3730 +f 2311/3898/5853 2546/3818/6276 2544/3706/5719 +f 2704/3866/2635 2705/3732/3274 2429/3867/5795 +f 2673/2091/3670 2532/2093/3672 2531/2475/4039 +f 1737/2445/3525 1705/2494/3525 1707/2726/3525 +f 2968/2942/4527 3048/3367/5014 3038/2943/4528 +f 3553/2542/4101 3455/2819/4386 3556/3992/6107 +f 3345/2888/3281 3379/1925/3281 3376/3788/3281 +f 2373/3604/5308 2389/3620/5334 2388/3651/5382 +f 2060/1765/3366 2069/2885/5059 2221/3399/5058 +f 3582/3965/3280 3581/3187/3280 3584/2165/3280 +f 2740/3645/5373 2741/1846/3443 2730/3123/3464 +f 2343/3045/4639 2342/1893/5293 2344/3046/4640 +f 2116/3073/4668 2126/3991/6104 2125/2851/4424 +f 2483/1690/3434 2482/1689/5710 2664/1836/3432 +f 2556/4037/6316 2557/3838/6265 2574/2639/4207 +f 1703/2493/6108 1700/2397/3962 1701/3842/5746 +f 2163/3618/5330 2171/3885/5822 2170/3759/5583 +f 2282/2911/4610 2279/3203/4835 2497/3202/4834 +f 3949/2326/3882 3950/3679/5431 3952/2327/3883 +f 3288/1722/5958 3287/3710/5480 3261/2121/5479 +f 2542/3863/5787 2541/2763/5787 2300/2377/5233 +f 1880/2725/4299 1875/3994/6113 1879/2723/4298 +f 3602/2002/3589 3601/2164/3840 3603/2000/3587 +f 2217/3852/2635 2218/2886/2635 1925/4001/3274 +f 3857/4008/6161 3860/1677/5368 3859/3641/5368 +f 3747/3551/3827 3752/3793/3827 3716/3549/3827 +f 3840/1949/3537 3843/3997/6134 3842/3731/6290 +f 3857/4008/6161 3858/1678/6231 3860/1677/5368 +f 2598/3321/4964 2605/3318/4961 2597/3311/4955 +f 3972/1935/3512 3973/2058/3512 3971/2044/3512 +f 2175/3530/5226 2197/3529/5225 2176/3562/5261 +f 2907/3259/4902 2916/3258/4901 2917/1960/3548 +f 1985/2781/4352 1883/4018/6209 1884/3607/5311 +f 4023/2584/4150 4024/2103/3681 4022/3199/4830 +f 2901/3403/5065 2922/3028/6007 2900/2156/3727 +f 3690/1709/6271 3801/3444/6317 3802/3561/6271 +f 3539/2023/3603 3537/3933/5929 3538/2036/3614 +f 3234/3495/5189 3235/3846/5751 3236/3052/4648 +f 3825/3592/5520 3839/1950/5799 3840/1949/6144 +f 2185/3084/4681 1804/3022/4618 1968/3021/4617 +f 3518/3966/6013 3517/3850/5756 3530/3902/5863 +f 2594/2232/3798 2595/2231/3797 2448/3035/4629 +f 3522/1739/3340 3533/1741/3342 3534/3423/5084 +f 2636/2799/4368 2446/3687/5444 2623/3109/4713 +f 2710/3870/5828 2712/3025/4621 2702/3859/6296 +f 3729/3964/6011 3731/3712/5485 3711/3413/5484 +f 2048/3264/6297 2046/3469/5150 2110/3468/5149 +f 2189/3520/5215 2177/3519/5214 2199/2047/3626 +f 2643/3823/5705 2511/2225/3791 2509/3678/5429 +f 2664/1836/3432 2658/3058/4654 2656/3060/4656 +f 3498/3273/4282 3501/3272/4282 3496/3085/4282 +f 3556/3992/6107 3555/3239/4880 3554/2458/4020 +f 2690/2713/4285 2691/2712/4284 2678/3236/4873 +f 3997/3789/5637 4008/3649/5380 4009/2952/4538 +f 3114/2550/6045 3115/2549/6089 3100/2802/5603 +f 3061/2394/3959 3044/2368/3929 2959/2369/3931 +f 1936/2529/4088 2186/2734/4308 1934/2735/4309 +f 3571/3420/5080 3676/1795/3395 3675/1794/3394 +f 2534/3257/4900 2535/2676/4248 2533/2762/4335 +f 3204/1723/3326 3202/3809/6283 3203/1761/3362 +f 2215/2891/4468 2216/2890/4467 2194/2492/4055 +f 2796/1823/3419 2813/4029/6242 2829/2012/3594 +f 3748/3200/3827 3752/3793/3827 3747/3551/3827 +f 2484/3669/6166 2478/3019/4615 2481/3018/4614 +f 2644/3146/4767 2643/3823/5705 2509/3678/5429 +f 3722/2450/3827 3719/2265/3827 3757/3979/3827 +f 2728/3400/3464 2726/3401/3464 2733/1868/3465 +f 3705/3535/3827 3706/3630/3827 3711/3413/3827 +f 2133/2516/4075 2078/3282/4927 2103/3284/4929 +f 1770/3739/5541 1771/3328/4971 1769/2216/3782 +f 3023/3074/3296 2992/2945/3296 2989/3722/3296 +f 3945/3296/3512 3977/2060/3512 3947/3297/6307 +f 3084/2280/3843 3187/3958/5990 3189/1895/3489 +f 3455/2819/4386 3557/2607/4174 3556/3992/6107 +f 3286/2415/6132 3287/3710/5712 3300/3836/5729 +f 2753/3940/3454 2783/1857/3454 2778/3814/3454 +f 2273/3525/5220 2272/1900/6318 2487/3702/5468 +f 3755/2996/3827 3750/2992/3827 3739/2031/3827 +f 2546/3818/6276 2311/3898/5853 2310/3567/5852 +f 2894/1878/3725 2878/1727/3725 2881/2829/3725 +f 1929/3995/6116 1947/3211/4843 1976/3893/5838 +f 2475/2439/4111 2417/4027/6236 2416/3757/5577 +f 1942/3320/4963 1999/4035/6270 1943/2995/4586 +f 2790/3293/4937 2785/3339/5963 2799/2476/4040 +f 2949/2590/4157 2947/3376/5023 2948/3280/4925 +f 3163/1754/3355 3141/1756/3357 3142/4014/6200 +f 2125/2851/4424 2146/3323/4966 2124/3322/4965 +f 2813/4029/6242 2796/1823/3419 2795/1704/3310 +f 2538/3240/4881 2301/3242/4883 2540/3290/5657 +f 3247/3048/4642 3222/2499/4061 3245/1867/6259 +f 3776/3124/5961 3695/3055/4651 3788/2056/3633 +f 3222/2499/4061 3221/2242/3806 3245/1867/6259 +f 1698/2395/5910 1696/3359/5950 1683/3002/4596 +f 2221/3399/2635 2222/3398/2635 1916/4024/6229 +f 2309/3565/5264 2310/3567/5266 2311/3898/5959 +f 4005/3198/4829 3977/2060/6153 4006/2059/4148 +f 1802/3193/4823 1803/3020/6319 1804/3022/5565 +f 2458/1982/3569 2474/2440/4446 2473/2872/4447 +f 2613/3822/5697 2614/2947/4534 2379/3609/5313 +f 2219/3430/3271 1790/2482/3274 1789/2481/3274 +f 2007/3319/5989 2006/2502/5509 1844/3667/5899 +f 2574/2639/4207 2558/3345/6266 2575/2370/3933 +f 2768/2539/4098 2765/2220/3786 2766/2222/3788 +f 1913/3555/5253 2106/2080/3658 1989/1832/3428 +f 2746/2352/3910 2745/3624/3454 2744/3623/3454 +f 2699/3410/5071 2571/2775/4346 2572/3036/4630 +f 3934/3032/4627 4011/2378/3943 4013/3102/4702 +f 3514/2460/4022 3499/2823/4391 3500/2545/4104 +f 2496/3675/5419 2495/3201/5418 2504/2721/4294 +f 2686/3826/5708 2435/1821/3417 2687/2026/3606 +f 2254/2604/6320 2253/2606/5411 2482/1689/3297 +f 3144/2179/3730 3139/3486/3730 3120/2177/3730 +f 3206/3295/3361 3209/1828/3361 3205/1860/3361 +f 2177/3519/5214 2176/3562/5261 2199/2047/3626 +f 1861/2680/4252 1863/2768/4341 1862/2681/4253 +f 3552/2077/3655 3513/2544/4103 3512/3189/4819 +f 3352/2061/3638 3353/3897/6122 3351/3765/5596 +f 1995/2816/4384 1992/2811/4380 1993/1929/3523 +f 3187/3958/5990 3185/3833/5724 3184/2173/3747 +f 3902/3989/6093 3814/3986/6321 3900/1985/3572 +f 3941/1918/4509 3963/3077/5946 3965/2340/4510 +f 2069/2885/5059 2068/2884/6030 2222/3398/5057 +f 3448/1971/5714 3545/2602/4169 3544/3708/5477 +f 2077/2402/3967 2136/3489/5181 2135/3283/4928 +f 2910/1921/3514 2909/3417/5076 2939/2275/3835 +f 1760/3547/5245 1758/1903/3498 1781/3212/4845 +f 3986/3163/4999 3987/3162/4786 4028/3792/5640 +f 3699/2866/5701 3697/1772/3373 3797/1891/3485 +f 3903/3234/4871 3906/1882/3476 3811/3437/5106 +f 3355/2063/3640 3354/2062/3639 3356/2555/4115 +f 2778/3814/3454 2779/3760/3454 2752/1729/3454 +f 3162/1755/5834 3163/1754/4993 3178/3837/5735 +f 3716/3549/3827 3753/2263/3827 3719/2265/3827 +f 1797/2769/4342 1799/2770/4344 1802/3193/4823 +f 4014/2312/3868 3934/3032/4627 4013/3102/4702 +f 2542/3863/2635 2534/3257/2635 2541/2763/2635 +f 2766/2222/6157 2764/2221/3909 2747/2351/3908 +f 2254/2604/6320 2482/1689/3297 2256/1691/3299 +f 2462/3881/6274 2563/2308/6322 2461/1975/3562 +f 3459/2250/3928 3468/3454/5125 3466/2808/4377 +f 2017/2558/4118 2072/2803/4372 2016/2556/4116 +f 3982/3061/5623 3983/2466/4028 4001/2465/4027 +f 2861/3488/5662 2889/3482/5804 2887/3611/6119 +f 2645/3144/4765 2654/3404/5066 2442/3145/4766 +f 3581/3187/4817 3589/3161/5801 3619/3180/4810 +f 2525/3681/5436 2527/2675/5438 2523/3862/6065 +f 3674/3777/5619 3670/3422/5083 3568/3421/5082 +f 2965/2136/5842 2958/1787/3387 3064/1789/3389 +f 2117/3158/4780 2137/3072/4667 2128/2515/4074 +f 2029/2100/3678 2026/2102/3680 2030/4026/6232 +f 1890/3308/6223 1891/4042/6323 1986/2685/4257 +f 3333/3571/5269 3332/3806/5667 3412/3583/5282 +f 2523/3862/6065 2522/3886/6100 2437/3811/5677 +f 2360/2410/3976 2388/3651/5382 2387/2411/3977 +f 2305/2593/5540 2298/2375/3940 2300/2377/3942 +f 3345/2888/3281 3376/3788/3281 3374/2027/3281 +f 3213/1775/3376 3211/1760/3361 3212/3711/3362 +f 3884/3654/6237 3916/2469/4032 3915/3227/4863 +f 2047/2004/3591 2050/2003/3590 2051/3263/4907 +f 2124/3322/4965 2150/2480/4044 2125/2851/4424 +f 3434/2106/3684 3328/3206/4838 3435/2560/4120 +f 4026/2583/4149 4006/2059/4148 3986/3163/4999 +f 2518/3026/4622 2711/3873/6176 2713/3876/5814 +f 2010/2501/5510 1848/2645/5839 1846/2644/5508 +f 2694/2132/3709 2692/4038/6288 2691/2712/4284 +f 2030/4026/6232 1939/3747/5562 2032/2857/4428 +f 3940/2066/3644 3960/2761/5283 3961/3441/5945 +f 2867/2571/4130 2865/2979/4565 2856/2572/4131 +f 3760/2291/3827 3732/2293/3827 3730/3948/3827 +f 3735/3927/6257 3712/3970/6027 3733/3713/5486 +f 2161/3701/5466 2163/3618/5330 2170/3759/5583 +f 1722/3237/3525 1728/2133/3525 1719/2563/3525 +f 2632/2968/4554 2621/2663/4236 2631/3920/5895 +f 2106/2080/3658 2113/2366/3925 2131/2081/3659 +f 3237/3054/6170 3239/3990/6095 3220/3834/6094 +f 3018/3373/5018 3030/3594/5365 3029/3372/5016 +f 3152/2297/6086 3193/3821/5695 3192/2956/4542 +f 3339/3169/4795 3340/1786/5406 3357/3478/6062 +f 2558/3345/6266 2559/3346/6295 2575/2370/3933 +f 2381/3613/5325 2383/2570/4129 2382/2569/4128 +f 2602/2800/4369 2450/3450/5121 2596/3972/6026 +f 3945/3296/3512 3971/2044/3512 3973/2058/3512 +f 3332/3806/5667 3414/3805/5666 3412/3583/5282 +f 3409/3343/4983 3410/3767/5598 3415/2418/3984 +f 2869/3582/3725 2872/2154/3725 2904/2143/3725 +f 3686/1945/3533 3684/2541/3533 3685/1943/3532 +f 2384/2862/4434 2374/2864/4436 2372/3196/4827 +f 2196/3773/5614 2203/3839/5740 2174/1791/3391 +f 2581/1890/3484 2590/1889/3483 2574/2639/4207 +f 3204/1723/3326 3210/2736/4310 3202/3809/6283 +f 2136/3489/5181 2099/3974/6038 2101/3490/5182 +f 3198/2633/3841 3199/2632/3841 3201/3798/3841 +f 1964/2468/4031 1798/2467/4030 1792/2561/5606 +f 4018/2913/4486 4003/2185/3756 4019/2187/3758 +f 3060/3977/6052 3056/2294/3851 3042/2296/3853 +f 1851/2574/4137 1849/3615/5326 1850/2575/4138 +f 3142/4014/3730 3141/1756/3730 3113/3628/3730 +f 2276/4020/6324 2277/3154/5222 2265/3526/5221 +f 2578/3298/4944 2576/2973/4559 2573/2372/3935 +f 3851/2658/4230 3854/2566/4232 3853/3752/5573 +f 2596/3972/6026 2415/4005/6147 2467/4040/6300 +f 3296/3192/4822 3284/2204/3771 3297/1776/3377 +f 1952/2738/5544 1954/2666/4238 1791/2637/4204 +f 1681/3944/5953 1682/3943/5952 1694/3942/5951 +f 3889/3727/6194 3890/3518/5213 3898/1984/3571 +f 1774/3432/5095 1776/3315/4958 1775/3314/4957 +f 1886/4034/6268 1984/3608/5312 1887/4043/6325 +f 3328/3206/4838 3436/3552/5250 3435/2560/4120 +f 3612/1737/3687 3613/2110/3689 3614/1738/4860 +f 3046/3845/5750 3045/2349/3906 3016/2348/3905 +f 3480/3386/3815 3510/2068/3815 3478/2307/4282 +f 3728/3659/5398 3727/3661/5400 3730/3948/6102 +f 3153/3969/6061 3154/2158/3731 3194/2160/3733 +f 2873/2904/4479 2871/2167/6292 2857/3597/5298 +f 2424/3957/2635 2426/3167/2635 2716/3801/2635 +f 1931/2289/3849 1911/4044/6326 1910/3277/4918 +f 3425/2086/3664 3424/3980/6057 3429/1853/3451 +f 2210/2683/4255 2211/2202/3769 2216/2890/4467 +f 2591/3134/4744 2627/2580/4143 2618/3342/4982 +f 2783/1857/3454 2753/3940/3454 2755/1858/3454 +f 2841/3498/5193 2934/2043/3621 2933/2042/3620 +f 3701/2453/6099 3805/2512/6327 3804/3358/6099 +f 2714/2534/2635 2713/3876/3271 2424/3957/2635 +f 2633/3655/5389 2446/3687/5444 2447/2665/4237 +f 3249/3247/4891 3248/2498/4890 3247/3048/6175 +f 3382/1965/3281 3383/1967/3281 3368/3419/3281 +f 3399/3300/4946 3398/3049/5114 3413/3301/4947 +f 3270/3457/6069 3265/1714/3320 3282/1713/3319 +f 2514/3223/4858 2512/2223/3789 2641/3584/5284 +f 3897/2599/4166 3821/2489/4753 3896/2412/3978 +f 3018/3373/3296 3015/2873/3296 3013/2874/3296 +f 4020/3835/5728 4021/2105/3683 3929/2511/4071 +f 3246/1866/3699 3244/1865/3699 3263/2865/3699 +f 3165/3304/4949 3169/2171/3745 3182/3921/5896 +f 3349/3764/5972 3348/3103/5528 3337/1669/5527 +f 3435/2560/4120 3392/3087/6079 3391/2559/4119 +f 3753/2263/4731 3777/3794/5643 3776/3124/4732 +f 2596/3972/6026 2466/3042/4636 2403/3931/5925 +f 2358/3999/6138 2357/2718/4291 2360/2410/3976 +f 3140/3716/3730 3133/2299/3730 3125/3685/3730 +f 3092/2957/4543 3192/2956/4542 3193/3821/5695 +f 2264/3633/5687 2276/4020/6324 2265/3526/5221 +f 2500/3677/5422 2496/3675/5419 2504/2721/4294 +f 2292/3544/6188 2294/2595/6289 2286/3540/6305 +f 3726/3660/5399 3725/3988/6135 3727/3661/5400 +f 2296/3861/5772 2291/3545/5243 2292/3544/5242 +f 3814/3986/6321 3816/1983/3570 3900/1985/3572 +f 2961/2837/3713 2966/3171/3713 2960/2983/3713 +f 2051/3263/5658 2227/3370/5360 2229/3369/5659 +f 3068/2427/3990 3069/2486/4050 3070/2302/3859 +f 2066/2887/4760 2068/2884/4459 2067/2883/4458 +f 2690/2713/4285 2689/3337/4978 2698/3553/5251 +f 3961/3441/5945 3941/1918/4509 3940/2066/3644 +f 2694/2132/3709 2693/2131/3708 2683/3968/6018 +f 4030/1871/3467 3987/3162/4786 3988/3658/5397 +f 2103/3284/4929 2085/3828/5713 2104/3197/4828 +f 2390/3878/5808 2463/2524/4083 2402/4010/6180 +f 2464/3726/5514 2401/3775/5616 2463/2524/4083 +f 1724/2134/3525 1722/3237/3525 1691/2305/3525 +f 3419/2834/4406 3420/3132/4743 3417/1875/3471 +f 2326/3581/5546 2452/3742/5548 2329/2419/5732 +f 2560/1974/3561 2561/3905/6328 2461/1975/3562 +f 2243/2441/4005 2244/3497/6219 2475/2439/4003 +f 1799/2770/4344 1967/2284/4343 1966/3776/5618 +f 3556/3992/6107 3554/2458/4020 3553/2542/4101 +f 4030/1871/3467 3988/3658/5397 4032/1872/3468 +f 2755/1858/3764 2754/3937/5944 2756/2194/3765 +f 4044/2706/4280 3924/2707/4280 4040/2852/6329 +f 2843/2924/4500 2922/3028/4624 2932/2922/4498 +f 2208/3306/4951 2212/3900/5855 1987/2288/3848 +f 2186/2734/4308 2157/3975/6330 2162/3117/4722 +f 2025/3415/6203 2022/2457/4370 2156/2435/3999 +f 3373/2889/4466 3346/3673/5415 3345/2888/4464 +f 2312/3831/6096 2313/3232/4869 2302/3947/5960 +f 3998/3743/5553 3999/3100/4700 4012/2380/3945 +f 2109/1998/3585 2142/1736/3339 1937/1999/3586 +f 2644/3146/4767 2503/2719/4292 2645/3144/4765 +f 2191/2491/4054 2187/3248/4892 2166/3913/5879 +f 2126/3991/6104 2116/3073/4668 2118/3157/4779 +f 2627/2580/4143 2591/3134/4744 2583/2831/4402 +f 3202/3809/5671 3313/3691/5671 3314/3810/5672 +f 2222/3398/2635 2217/3852/2635 1916/4024/6229 +f 2719/3730/5518 2721/1954/5358 2506/2720/5357 +f 4034/3107/4711 4037/3106/4710 3932/3041/4635 +f 2479/3083/4680 2480/3907/6304 2458/1982/3569 +f 2646/2073/3651 2657/2072/3650 2655/3244/4886 +f 2853/2906/4480 2847/2764/4337 2846/2144/5351 +f 2983/2586/4153 2982/3402/5060 2984/2679/5038 +f 3937/2392/3957 3936/3993/6109 3944/2390/3955 +f 2908/2138/3714 2935/2406/3971 2938/3784/5628 +f 2598/3321/4964 2600/2667/4239 2601/3473/5154 +f 2269/3516/6331 2263/3513/6115 2486/3644/5371 +f 2495/3201/5418 2569/3151/4773 2662/3275/4916 +f 3892/4013/6332 3891/2986/5512 3869/2174/3748 +f 2945/2907/4481 2853/2906/4480 2844/2787/4923 +f 2786/3170/4979 2769/3729/3454 2771/2797/3454 +f 2763/3642/6333 2760/3175/4804 2762/3668/6333 +f 2154/2939/4522 2140/1671/3282 2153/3827/5711 +f 3636/2437/4136 3637/1781/3382 3621/1780/3381 +f 2590/1889/3483 2407/3922/5903 2408/3270/4911 +f 1806/3464/5138 1812/2582/5140 1971/2989/5139 +f 2162/3117/4722 2168/2206/3773 2186/2734/4308 +f 2728/3400/6019 2733/1868/5113 2826/3153/4775 +f 2879/2830/4401 2880/3279/5094 2881/2829/4400 +f 2854/3916/5884 2852/2786/3631 2851/2008/3631 +f 2563/2308/6322 2564/1973/3560 2461/1975/3562 +f 2071/3603/5306 1976/3893/5838 1977/2065/5305 +f 2034/2859/6235 2036/2847/4419 1876/2848/4421 +f 3519/1764/3365 3518/3966/6013 3559/3122/4729 +f 1797/2769/4342 1963/2285/4029 1967/2284/4343 +f 2712/3025/4621 2521/3027/4623 2520/3860/6334 +f 3257/3761/3699 3258/2120/3699 3255/3246/3699 +f 3206/3295/3361 3208/2018/5228 3209/1828/3361 +f 2386/2948/4535 2615/2662/4235 2393/3006/4602 +f 3047/2426/3989 3034/1803/3402 3069/2486/4050 +f 2450/3450/5121 2602/2800/4369 2601/3473/5154 +f 3574/3335/4977 3580/2210/3778 3682/3951/5973 +f 3765/1784/3385 3764/1783/3384 3749/2993/4899 +f 1748/2444/4008 1747/1905/3500 1759/1904/3499 +f 4042/2212/6275 3927/3039/6275 3926/2213/6275 +f 1674/3688/5445 1778/2323/3879 1777/2325/3881 +f 1958/3475/6260 1959/2635/5966 1957/3141/4758 +f 3327/2162/5794 3441/3865/5794 3442/3114/5794 +f 3340/1786/5406 3341/3254/6071 3360/3664/5404 +f 1885/4033/6267 1929/3995/6116 2071/3603/5306 +f 1667/2737/4311 1772/3149/4770 1770/3739/5541 +f 2457/1981/3568 2474/2440/4446 2458/1982/3569 +f 2854/3916/5884 2926/3653/5385 2925/2591/4158 +f 3542/3709/5478 3541/2021/3601 3543/4006/6148 +f 2348/2309/3866 2563/2308/3865 2462/3881/5812 +f 2099/3974/6038 2136/3489/5181 2009/2268/3829 +f 2931/3856/5765 2919/2141/6213 2930/2088/3667 +f 2910/1921/3514 2911/3395/6246 2897/1922/3515 +f 2682/3825/5707 2685/3911/5875 2679/1941/3530 +f 3209/1828/3424 3210/2736/4310 3304/3749/5564 +f 3431/2780/4351 3429/1853/3451 3430/4028/6240 +f 2606/3097/4699 2598/3321/4964 2625/3095/4697 +f 2299/3241/6335 2304/2594/4161 2305/2593/4160 +f 2206/3470/5151 1937/1999/6336 2204/2849/4422 +f 2556/4037/6280 2340/1894/3488 2338/3587/6281 +f 1749/3917/5956 1761/3548/5246 1762/3091/4692 +f 2847/2764/4337 2841/3498/5193 2839/2095/6133 +f 3378/3557/3281 3377/3531/3281 3370/2320/3281 +f 1724/2134/3525 1728/2133/3525 1722/3237/3525 +f 2324/3458/5279 2323/3579/5278 2322/3704/5472 +f 2925/2591/4158 2917/1960/5802 2916/3258/6337 +f 2181/3983/6074 1984/3608/5312 2071/3603/5306 +f 3454/2899/4954 3446/2817/6338 3563/3309/4954 +f 3717/3281/5346 3706/3630/5347 3715/3962/6164 +f 2504/2721/6315 2723/3635/5356 2500/3677/5851 +f 2030/4026/6232 2153/3827/5711 1939/3747/5562 +f 3365/2960/4546 3366/3082/4679 3368/3419/5079 +f 3313/3691/6204 3202/3809/6204 3208/2018/6204 +f 2441/4011/6183 2444/2963/4549 2440/3524/5219 +f 2767/2538/4097 2770/3479/5161 2769/3729/5549 +f 2011/2270/6339 2015/3467/6339 1856/3813/6339 +f 2801/3357/5008 2802/2463/4025 2791/2687/4259 +f 2014/3466/5147 2013/2401/3966 2072/2803/4372 +f 3336/1670/5526 3348/3103/5528 3346/3673/6152 +f 3609/2432/3280 3628/3485/3280 3607/2123/3280 +f 2226/3218/2635 2225/3364/2635 1917/3959/5991 +f 3921/3925/6161 3817/2488/6340 3815/2487/6231 +f 2353/3982/6059 2372/3196/4827 2354/3195/4826 +f 3289/3946/6162 3271/2228/3794 3302/2227/3793 +f 2151/2479/4043 2149/2850/4423 2150/2480/4044 +f 2750/3262/3454 2749/3365/3454 2742/3265/3454 +f 2521/3027/5726 2519/3812/5678 2437/3811/5677 +f 2031/2359/3918 2029/2100/3678 2030/4026/6232 +f 1853/2523/6064 1852/2576/4139 1856/3813/6341 +f 1876/2848/4421 1878/3088/5997 2034/2859/6235 +f 3084/2280/3843 3083/2279/3842 3185/3833/5724 +f 1801/3472/6342 1803/3020/6319 1802/3193/4823 +f 2958/1787/3713 2956/2137/3713 2957/3324/3713 +f 2489/4036/6279 2567/2386/3951 2488/3543/5241 +f 2143/1735/3338 2144/1734/3337 2145/3576/5272 +f 2746/2352/3910 2744/3623/3454 2742/3265/3454 +f 2193/3425/5086 2212/3900/5855 2213/4012/6186 +f 3364/2959/6216 3362/2958/6072 3341/3254/6071 +f 2028/3484/5169 2023/2925/4501 1940/2927/4503 +f 2561/3905/6328 2562/2638/4205 2574/2639/4207 +f 3008/3128/4738 3007/3882/5815 3006/3129/4739 +f 3619/3180/5064 3589/3161/4784 3620/2140/4783 +f 1710/3051/6199 1711/2353/5336 1709/2147/3751 +f 2110/3468/5149 2107/2484/4048 2111/2648/4217 +f 2959/2369/3931 3045/2349/3930 3063/1788/3388 +f 3288/1722/3325 3289/3946/6162 3204/1723/3326 +f 3991/3459/6098 4035/2256/3820 4033/3808/5670 +f 2274/1898/3492 2270/3515/5210 2271/1899/3493 +f 2141/2470/4034 2143/1735/3338 2127/3894/5843 +f 2537/3896/6298 2538/3240/4933 2539/3291/4935 +f 3016/2348/3905 3015/2873/5017 3028/3707/5749 +f 2611/3108/4712 2606/3097/4699 2624/3096/4698 +f 3775/1758/3359 3776/3124/5961 3788/2056/3633 +f 3269/3179/4808 3270/3457/6069 3281/2825/5685 +f 3451/1972/4399 3543/4006/6148 3541/2021/3601 +f 1986/2685/4257 1891/4042/6323 1892/2782/4353 +f 2428/1953/2635 2722/2909/2635 2723/3635/2635 +f 3869/2174/3748 3893/1685/3295 3892/4013/6332 +f 3765/1784/3385 3798/3671/5412 3797/1891/3485 +f 3188/1896/3490 3189/1895/3489 3187/3958/5990 +f 1951/2519/4757 1953/2739/6343 1788/2483/4755 +f 1689/1932/3525 1688/2209/3525 1684/1933/3525 +f 1909/3278/4919 1908/2287/3847 1931/2289/3849 +f 2549/3854/5856 2548/2932/4514 2318/1818/5858 +f 2010/2501/4063 2009/2268/3829 2008/3800/6101 +f 2775/2196/3501 2774/1906/3501 2776/1728/4133 +f 1825/2621/5743 2005/3840/5742 1839/2626/6168 +f 2640/1995/3582 2464/3726/5514 2634/1996/3583 +f 3928/3040/4634 4033/3808/5670 4034/3107/4711 +f 2606/3097/4699 2611/3108/4712 2610/3317/4960 +f 2562/2638/5101 2345/3047/5865 2344/3046/5102 +f 3235/3846/3699 3232/3481/3699 3267/3949/3699 +f 1853/2523/6064 1856/3813/6341 1854/3939/6344 +f 1680/1931/5764 1723/2656/6253 1721/3137/4747 +f 1915/4007/6150 1914/3350/4997 1988/3349/4996 +f 2064/3396/5053 2062/1767/3368 2220/1766/3367 +f 2876/1726/3329 2879/2830/4401 2878/1727/3330 +f 3205/1860/3361 3216/1859/3455 3206/3295/3361 +f 3741/1742/5020 3738/2030/3608 3740/2032/3610 +f 3170/3674/5417 3195/2331/3887 3156/2330/3886 +f 2142/1736/3339 2141/2470/4034 2204/2849/4422 +f 3562/3539/3559 3560/3930/3559 3565/1833/3559 +f 2641/3584/5284 2511/2225/3791 2642/3523/5218 +f 3458/2810/3815 3465/2446/3815 3464/2251/3815 +f 3135/2343/3730 3131/2716/3730 3129/2905/3730 +f 2614/2947/4534 2613/3822/5697 2618/3342/4982 +f 3330/3431/5333 3324/3184/4814 3419/2834/4406 +f 1948/2933/5135 1973/2755/5089 1810/1955/5134 +f 1857/2522/5533 1855/2521/5941 2015/3467/5534 +f 2179/3261/4904 2181/3983/6074 2180/2286/3846 +f 3174/3772/5613 3096/2423/6227 3095/2422/5816 +f 3511/3274/4915 3547/3796/5647 3550/3188/4818 +f 3328/3206/3734 3326/2108/5212 3325/3572/5579 +f 2410/4022/6221 2461/1975/3562 2590/1889/3483 +f 1840/2629/6167 2005/3840/5742 1837/2624/5988 +f 2054/3955/6287 2223/1901/3495 2225/3364/6172 +f 2485/3703/6303 2659/1837/3433 2487/3702/6345 +f 3338/1668/5656 3351/3765/6346 3349/3764/5972 +f 2554/3125/4733 2553/3126/4736 2552/3477/6082 +f 1937/1999/3586 2206/3470/5151 2196/3773/5614 +f 2020/3554/6264 2021/3736/6347 2014/3466/5147 +f 3674/3777/5619 3675/1794/3394 3673/3238/4879 +f 2557/3838/5738 2338/3587/6281 2335/3066/5739 +f 1960/2640/4208 1957/3141/4758 1961/3070/4665 +f 2461/1975/3562 2561/3905/6328 2574/2639/4207 +f 2575/2370/3933 2553/3126/4736 2570/2371/3934 +f 2613/3822/5697 2612/2990/4578 2617/1888/3482 +f 2277/3154/4776 2276/4020/6220 2493/3155/4777 +f 2335/3066/4661 2336/3585/5285 2334/3067/4662 +f 3261/2121/3699 3262/2417/3699 3228/2698/3699 +f 2555/1892/4206 2556/4037/6316 2574/2639/4207 +f 3380/1814/3281 3379/1925/3281 3347/1815/3281 +f 3662/1976/3563 3663/2243/3807 3664/1977/3564 +f 3846/1718/3289 3875/1717/3289 3849/2388/3289 +f 1787/2191/5592 1783/3030/5592 1666/2728/5592 +f 1781/3212/4845 1668/2692/4844 1760/3547/5245 +f 2008/3800/5650 2011/2270/5680 1852/2576/5651 +f 3228/2698/4272 3231/3408/6217 3229/2382/5393 +f 3689/1944/5482 3685/1943/5482 3567/2267/5482 +f 2749/3365/6078 2772/1908/6015 2748/3366/5784 +f 3572/2844/4416 3576/3797/3533 3573/3255/3533 +f 2295/2597/4164 2288/1698/3306 2290/2700/4274 +f 3199/2632/3841 3200/3895/3841 3201/3798/3841 +f 2360/2410/3976 2370/2717/4290 2388/3651/5382 +f 3773/3598/5299 3774/1757/3358 3782/2748/4323 +f 2684/2531/4090 2519/3812/5678 2685/3911/5875 +f 3051/3950/5971 2971/3448/5119 2968/2942/4527 +f 2847/2764/4337 2941/2273/3833 2939/2275/3835 +f 1826/2612/4179 1823/2611/4178 1822/2778/4349 +f 3150/2841/4413 3151/2298/5636 3191/2842/4414 +f 3512/3189/5499 3502/2710/5004 3501/3272/6348 +f 3298/3086/4687 3300/3836/5729 3299/1774/3375 +f 2738/3000/3464 2734/3133/3464 2739/3140/4752 +f 2612/2990/4578 2381/3613/5325 2382/2569/4128 +f 3676/1795/3395 3571/3420/5080 3677/2496/4056 +f 3902/3989/6093 3811/3437/5106 3814/3986/6321 +f 1806/3464/5978 1807/3463/6310 1808/3619/5331 +f 2516/3222/4857 2519/3812/5678 2521/3027/5726 +f 3809/3288/4931 3907/1884/3478 3909/2129/3706 +f 1809/3462/6311 1810/1955/3541 1808/3619/5331 +f 3428/1854/3452 3427/1747/3348 3426/1855/3453 +f 1904/2651/4220 1903/4041/6312 1990/1694/3302 +f 3778/3056/4652 3779/3460/5131 3789/3003/4599 +f 2270/3515/5210 2269/3516/5211 2271/1899/3493 +f 1858/2767/5329 2016/2556/4116 2073/2456/4018 +f 2607/2399/3964 2608/3723/5505 2629/2116/3695 +f 3060/3977/6052 3059/3533/5230 3056/2294/3851 +f 3013/2874/3296 3016/2348/3296 2982/3402/3296 +f 2228/3216/4852 2053/2878/5441 2057/3217/4853 +f 2967/2301/3858 2965/2136/5842 3066/2938/4521 +f 2230/3883/2635 2231/3803/2635 1921/3744/2635 +f 2716/3801/5653 2718/3631/6025 2513/2224/5810 +f 2004/3780/5625 1833/2618/5912 1831/2616/5624 +f 4002/2464/6256 4007/2914/4487 4017/3143/4764 +f 3996/2953/6197 3995/3936/6130 3979/3191/6129 +f 2558/3345/4987 2335/3066/5739 2333/3068/4988 +f 3169/2171/3745 3166/3305/4950 3168/2172/3746 +f 3348/3103/4705 3349/3764/5595 3350/1813/4703 +f 2220/1766/3367 2224/1902/3497 2064/3396/5053 +f 2018/2557/4117 2019/3436/5105 2017/2558/4118 +f 2604/3696/5459 2589/2404/3969 2588/4002/6142 +f 2273/3525/5220 2487/3702/5468 2490/3912/5878 +f 3921/3925/4051 3922/3941/4051 3919/3269/4051 +f 2611/3108/4712 2632/2968/4554 2631/3920/5895 +f 2021/3736/6347 2015/3467/5148 2014/3466/5147 +f 2474/2440/4004 2457/1981/5867 2247/3500/5862 +f 2163/3618/5330 2161/3701/5466 2164/1792/3392 +f 3333/3571/5269 3322/3560/6238 3323/3574/3734 +f 3324/3184/4814 3330/3431/3734 3320/3116/3734 +f 2167/3734/5525 2178/3521/5216 2166/3913/5879 +f 1887/4043/6325 1984/3608/5312 1884/3607/5311 +f 3575/3334/4976 3680/2897/4474 3678/2896/4473 +f 1774/3432/5095 1775/3314/4957 1740/2135/3712 +f 2019/3436/5105 2020/3554/6264 2017/2558/4118 +f 2517/2533/5433 2515/2532/5432 2514/3223/4858 +f 2997/1751/3296 2995/3914/3296 3027/1796/3296 +f 1966/3776/6140 1967/2284/3844 2180/2286/3846 +f 2210/2683/4255 1892/2782/4353 1985/2781/4352 +f 2939/2275/3835 2909/3417/5076 2938/3784/5628 +f 2589/2404/3969 2577/2373/3936 2572/3036/4630 +f 3584/2165/3280 3583/1917/3280 3582/3965/3280 +f 2555/1892/3486 2340/1894/3488 2556/4037/6280 +f 2292/3544/6188 2286/3540/6305 2528/2473/4037 +f 2451/3967/6017 2697/3409/5070 2572/3036/4630 +f 3800/3037/4631 3799/3672/5413 3768/2749/4324 +f 3661/1978/3565 3664/1977/3564 3654/3228/4864 +f 2702/3859/6296 2712/3025/4621 2520/3860/6334 +f 2468/3016/4613 2469/4015/6205 2471/3014/4611 +f 2925/2591/4158 2916/3258/6337 2915/1876/3472 +f 3973/2058/3512 3977/2060/3512 3945/3296/3512 +f 2026/2102/3680 2027/2101/3679 2028/3484/5169 +f 3099/2801/5604 3111/3627/6248 3112/3626/5605 +f 2650/2964/4550 2652/1989/3576 2701/2774/4345 +f 2456/1980/5861 2480/3907/5868 2248/3501/5196 +f 2935/2406/3971 2936/3978/6055 2938/3784/5628 +f 3116/2551/4110 3114/2550/4109 3113/3628/5344 +f 2780/1822/3454 2773/1907/3454 2775/2196/3454 +f 2701/2774/4345 2681/1942/3531 2650/2964/4550 +f 4001/2465/4027 4002/2464/6256 4017/3143/4764 +f 3298/3086/4687 3299/1774/3375 3297/1776/3377 +f 3784/2218/3784 3702/3746/5561 3703/3753/5575 +f 3141/1756/3357 3162/1755/3356 3161/2337/4532 +f 3319/3517/6299 3438/3115/6299 3437/3781/6349 +f 2649/1990/3577 2440/3524/5219 2653/1988/3575 +f 2896/3718/6350 2900/2156/3727 2924/2041/3729 +f 3134/2342/4289 3132/3714/3730 3131/2716/3730 +f 2040/1911/3505 2042/2449/4440 2037/2448/6054 +f 1990/1694/3302 2092/1928/3522 1991/1930/3524 +f 2674/2083/3661 2531/2475/4039 2530/2474/4038 +f 3406/1746/3347 3405/1927/3665 3425/2086/3664 +f 2593/3105/4709 2586/2189/3760 2587/2403/3968 +f 3643/3915/5882 3631/2950/5176 3630/3929/6351 +f 2070/2520/4079 1961/3070/4665 1957/3141/4758 +f 3039/2381/3946 3040/3276/4917 3052/1912/3506 +f 3285/2416/3982 3284/2204/3771 3266/3407/5392 +f 1873/2360/4269 1872/2696/4268 1871/3864/6352 +f 2170/3759/5583 2158/2669/4241 2160/3699/5464 +f 1931/2289/3849 1912/4032/6261 1911/4044/6326 +f 2236/3492/6192 2235/3379/2635 1924/3378/2635 +f 2063/2661/4234 2064/3396/5617 2065/2660/4233 +f 1688/2209/3525 1687/2355/3525 1684/1933/3525 +f 2103/3284/4929 2104/3197/4828 2105/3292/4936 +f 2487/3702/5468 2272/1900/6318 2271/1899/3493 +f 3822/3903/5891 3830/3909/5873 3859/3641/6225 +f 2613/3822/5697 2378/3786/5630 2612/2990/4578 +f 2246/3503/5198 2250/3851/5757 2237/3504/5199 +f 3527/2976/4562 3526/2978/4564 3542/3709/5478 +f 1786/2192/3475 1785/2751/3475 1782/2753/3475 +f 2900/2156/3725 2864/1826/3725 2866/3001/3725 +f 3409/3343/4983 3415/2418/3984 3416/3353/5001 +f 3102/1801/3400 3101/2603/4170 3119/2303/3860 +f 3101/2603/4170 3117/3762/6252 3119/2303/3860 +f 2736/1864/3465 2737/3932/3465 2734/3133/3464 +f 2905/1962/3550 2907/3259/4902 2917/1960/3548 +f 2809/2704/4278 2823/2180/3752 2729/2705/4279 +f 3861/3848/5753 3859/3641/5368 3862/2935/5369 +f 1829/2614/4221 1826/2612/4571 2003/2652/4222 +f 2154/2939/4522 2155/2436/4000 2156/2435/3999 +f 2341/3591/5292 2339/3588/5288 2340/1894/5289 +f 2439/2082/3660 2437/3811/5677 2438/2671/4243 +f 2670/3884/5860 2524/2877/5720 2525/3681/5436 +f 1680/1931/5764 1681/3944/5953 1690/2657/5955 +f 2097/2536/4095 2098/2500/4062 2006/2502/4064 +f 1942/3320/4963 1943/2995/4586 2093/2537/4096 +f 3430/4028/6240 3326/2108/3686 3432/2107/3685 +f 2046/3469/5817 2231/3803/5664 2230/3883/5818 +f 2443/2962/4548 2642/3523/5218 2440/3524/5219 +f 3530/3902/5863 3559/3122/4729 3518/3966/6013 +f 2630/3354/5003 2629/2116/3695 2608/3723/5505 +f 3352/2061/5655 3351/3765/6346 3338/1668/5656 +f 2166/3913/5879 2187/3248/4892 2165/2205/3772 +f 3506/2771/4390 3516/2609/6211 3517/3850/5756 +f 2100/3737/5535 2101/3490/5182 2099/3974/6038 +f 2389/3620/5334 2366/3541/5239 2387/2411/3977 +f 2169/2207/3774 2168/2206/3773 2162/3117/4722 +f 2061/2670/4242 2157/3975/6050 2067/2883/4458 +f 2740/3645/5373 2739/3140/4752 2818/3139/4751 +f 2951/2094/3673 2950/2054/3673 2839/2095/3673 +f 2181/3983/6074 2182/2200/3767 1985/2781/4352 +f 2132/2628/4197 2113/2366/3925 2121/2365/3924 +f 2056/3356/6173 2054/3955/6287 2225/3364/6172 +f 1864/2455/6286 1863/2768/4341 1858/2767/4340 +f 2748/3366/3454 2747/2351/3908 2746/2352/3910 +f 3342/3253/6185 3366/3082/6184 3364/2959/6216 +f 2013/2401/3966 2077/2402/3967 2139/2253/3817 +f 3153/3969/6020 3140/3716/5492 3154/2158/3731 +f 3681/2039/3617 3644/2290/3850 3682/3951/5973 +f 3231/3408/6217 3232/3481/5165 3230/2383/5164 +f 2778/3814/5681 2811/3159/5883 2779/3760/5587 +f 2488/3543/5241 2490/3912/6302 2489/4036/6279 +f 4010/2379/3944 4011/2378/3943 4009/2952/4538 +f 3062/2393/3958 3059/3533/5230 3061/2394/3959 +f 2036/2847/6035 2034/2859/6353 2033/2858/4429 +f 2877/1725/3725 2878/1727/3725 2906/1877/3725 +f 2013/2401/3966 2152/2252/3816 2072/2803/4372 +f 4003/2185/5390 3981/3617/5328 4004/2186/5723 +f 2941/2273/3833 2945/2907/4481 2944/2168/3742 +f 3902/3989/6093 3903/3234/4871 3811/3437/5106 +f 3748/3200/6354 3779/3460/6354 3752/3793/6354 +f 2756/2194/5934 2744/3623/5339 2757/3625/5341 +f 2232/2929/2635 1919/4021/2635 1922/4009/6160 +f 2763/3642/6333 2761/2702/4276 2760/3175/4804 +f 2226/3218/4854 2057/3217/4853 2056/3356/6173 +f 2490/3912/6302 2487/3702/6345 2659/1837/3433 +f 1892/2782/4353 2210/2683/4255 1986/2685/4257 +f 2545/3178/5717 2314/3230/5590 2312/3831/5718 +f 2283/3971/6023 2284/3081/4484 2285/3080/6024 +f 1973/2755/5089 1974/2754/5133 1817/3429/5090 +f 1727/2013/3595 1726/2454/4016 1743/2324/3880 +f 3874/3428/3288 3876/1716/3289 3843/3997/3288 +f 2847/2764/4337 2936/3978/6055 2935/2406/3971 +f 1936/2529/4088 1934/2735/4309 1935/2530/4089 +f 3483/2654/4224 3480/3386/5037 3481/2345/6039 +f 3977/2060/3512 3978/3832/3512 3947/3297/6307 +f 3396/3558/5449 3386/2197/4644 3381/3926/5913 +f 3942/1919/3512 3936/3993/3512 3939/1920/3513 +f 3186/3754/5576 3188/1896/3490 3187/3958/5990 +f 2502/2921/4497 2499/3676/5850 2280/2912/4495 +f 2147/3575/5271 2146/3323/4966 2145/3576/5272 +f 1847/2643/4214 1845/3666/5407 1846/2644/4215 +f 1859/2766/4339 1860/3684/5440 2020/3554/5252 +f 1668/2692/3475 1678/3689/3475 1669/2693/3475 +f 2202/3590/5291 2122/3647/5376 2121/2365/3924 +f 1771/3328/4971 1770/3739/5541 1772/3149/4770 +f 1863/2768/6355 1853/2523/4082 1857/2522/4081 +f 2419/3973/6031 2420/4004/6146 2596/3972/6026 +f 1800/3528/5224 1801/3472/6342 1802/3193/4823 +f 3268/2203/5069 3232/3481/3699 3231/3408/3699 +f 2035/3493/5188 2235/3379/5031 2236/3492/5184 +f 2847/2764/4337 2853/2906/4480 2941/2273/3833 +f 3580/2210/3533 3569/3683/3533 3577/2183/3533 +f 2448/3035/4629 2589/2404/3969 2572/3036/4630 +f 2292/3544/6188 2528/2473/4037 2532/2093/3672 +f 3092/2957/4543 3090/3229/4866 3191/2842/4414 diff --git a/examples/Cassie/urdf/meshes/agility/tarsus.obj b/examples/Cassie/urdf/meshes/agility/tarsus.obj new file mode 100644 index 0000000000..fcfebf9df9 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/tarsus.obj @@ -0,0 +1,24843 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o tarsus +v 0.382000 0.017317 0.035177 +v 0.087000 0.016810 0.037235 +v 0.382000 0.014667 0.041572 +v 0.087000 0.012452 0.044447 +v 0.382000 0.008512 0.047560 +v 0.087000 0.006444 0.048285 +v 0.087000 -0.000351 0.049603 +v 0.382000 0.000454 0.049508 +v 0.382000 -0.007970 0.047845 +v 0.087000 -0.007281 0.047929 +v 0.087000 -0.013930 0.042978 +v 0.382000 -0.015069 0.041106 +v 0.087000 -0.017517 0.033773 +v 0.382000 -0.017732 0.031592 +v 0.087000 -0.015890 0.024121 +v 0.382000 -0.014686 0.022290 +v 0.087000 -0.010155 0.017731 +v 0.382000 -0.007233 0.015805 +v 0.087000 -0.002542 0.014447 +v 0.382000 0.000956 0.014512 +v 0.087000 0.007223 0.015944 +v 0.382000 0.009219 0.016848 +v 0.087000 0.013857 0.021139 +v 0.382000 0.016473 0.025425 +v 0.087000 0.017317 0.028823 +v 0.410640 -0.020505 0.032202 +v 0.379339 -0.020484 0.032902 +v 0.412232 -0.020295 0.028540 +v 0.344052 -0.020591 0.030889 +v 0.380329 0.020484 0.033577 +v 0.344020 0.020659 0.032049 +v 0.381097 0.020121 0.036653 +v 0.343995 0.019086 0.039723 +v 0.380534 0.019280 0.039206 +v 0.343982 0.015382 0.045673 +v 0.380978 0.017085 0.043550 +v 0.380521 0.013628 0.047458 +v 0.343981 0.010005 0.049985 +v 0.380553 0.009772 0.050099 +v 0.343999 0.001809 0.052638 +v 0.380734 0.005885 0.051743 +v 0.380262 0.000946 0.052546 +v 0.380314 -0.004127 0.052177 +v 0.344036 -0.007164 0.051327 +v 0.380770 -0.009303 0.050385 +v 0.343974 -0.013077 0.047886 +v 0.380355 -0.014347 0.046839 +v 0.344005 -0.017555 0.042769 +v 0.381715 -0.018312 0.041676 +v 0.380892 -0.019233 0.039377 +v 0.343994 -0.019881 0.037186 +v 0.380746 -0.020074 0.036640 +v 0.343979 -0.018993 0.024078 +v 0.407728 -0.018229 0.022710 +v 0.344013 -0.015285 0.018193 +v 0.405288 -0.016234 0.019543 +v 0.402527 -0.012620 0.016016 +v 0.343977 -0.009827 0.013920 +v 0.400716 -0.009284 0.013840 +v 0.398887 -0.005175 0.012126 +v 0.343998 -0.004148 0.011877 +v 0.343990 0.002904 0.011564 +v 0.398691 0.000227 0.011577 +v 0.398713 0.005049 0.012076 +v 0.343982 0.010144 0.014093 +v 0.401108 0.010264 0.014335 +v 0.344013 0.015486 0.018416 +v 0.403543 0.014820 0.017831 +v 0.407559 0.018344 0.022725 +v 0.343984 0.019139 0.024429 +v 0.413101 0.020276 0.029179 +v 0.408855 0.020499 0.031781 +v 0.410591 -0.012100 0.051828 +v 0.404900 -0.016592 0.052194 +v 0.410063 -0.019218 0.051792 +v 0.396871 -0.015367 0.052646 +v 0.395053 -0.014463 0.052748 +v 0.394885 -0.017999 0.052823 +v 0.403411 -0.013289 0.052277 +v 0.397694 -0.018444 0.052623 +v 0.397627 -0.012204 0.052603 +v 0.399583 -0.012735 0.052493 +v 0.403158 -0.019230 0.052204 +v 0.399801 -0.019882 0.051976 +v 0.397078 -0.020308 0.051757 +v 0.411444 -0.020425 0.050361 +v 0.401130 0.012100 0.044308 +v 0.406079 0.012100 0.048059 +v 0.397741 0.012189 0.052597 +v 0.410576 0.012100 0.051831 +v 0.395180 0.012207 0.047173 +v 0.397815 0.012064 0.034654 +v 0.403379 0.012100 0.033217 +v 0.400075 0.012100 0.038134 +v 0.385608 0.011977 0.051174 +v 0.400676 0.012100 0.043574 +v 0.412429 0.012100 0.046832 +v 0.414038 0.012100 0.034328 +v 0.418215 0.012100 0.033499 +v 0.416138 0.012100 0.041553 +v 0.403766 0.012045 0.017130 +v 0.408607 0.012100 0.031939 +v 0.419210 0.012100 0.044668 +v 0.415547 0.012100 0.049457 +v 0.420027 0.012100 0.038682 +v 0.383207 0.013598 0.048394 +v 0.383557 0.010070 0.050934 +v 0.389667 0.017989 0.049137 +v 0.383365 0.017144 0.044787 +v 0.383369 -0.015378 0.046974 +v 0.389436 -0.017760 0.049245 +v 0.385583 -0.011968 0.051187 +v 0.383721 -0.010351 0.050873 +v 0.399975 0.020500 0.038996 +v 0.394158 0.020353 0.046898 +v 0.400729 0.020500 0.043620 +v 0.402259 0.020500 0.034135 +v 0.400267 -0.020500 0.037027 +v 0.400659 -0.020500 0.043513 +v 0.394598 -0.020420 0.046674 +v 0.404855 -0.020500 0.032490 +v 0.384303 0.019204 0.042191 +v 0.382277 0.003806 0.052666 +v 0.382322 -0.004434 0.052601 +v 0.401180 0.020500 0.044182 +v 0.403010 0.020500 0.046365 +v 0.409216 0.020500 0.048285 +v 0.414937 0.020500 0.044262 +v 0.416076 0.020500 0.039563 +v 0.414426 0.020500 0.035000 +v 0.397077 0.020309 0.051754 +v 0.411851 0.020400 0.050212 +v 0.395269 0.020395 0.047129 +v 0.417224 0.020363 0.034088 +v 0.418670 0.020471 0.039032 +v 0.417044 0.020427 0.046019 +v 0.401130 -0.020500 0.044308 +v 0.406079 -0.020500 0.048059 +v 0.394250 -0.020062 0.047636 +v 0.412429 -0.020500 0.046832 +v 0.415200 -0.020500 0.036198 +v 0.418107 -0.020390 0.035595 +v 0.415941 -0.020500 0.042075 +v 0.417498 -0.020299 0.045955 +v 0.418701 -0.020426 0.041849 +v 0.400729 -0.012100 0.043619 +v 0.399975 -0.012100 0.038996 +v 0.402259 -0.012100 0.034135 +v 0.408843 -0.012100 0.031770 +v 0.414426 -0.012100 0.035000 +v 0.416076 -0.012100 0.039563 +v 0.414118 -0.012100 0.045717 +v 0.407531 -0.012100 0.048128 +v 0.403010 -0.012100 0.046365 +v 0.401180 -0.012100 0.044182 +v 0.395664 -0.009655 0.033564 +v 0.395695 0.009914 0.033594 +v 0.402414 -0.010469 0.015625 +v 0.402347 0.010204 0.015562 +v 0.397610 -0.012030 0.034621 +v 0.403937 -0.012068 0.017312 +v 0.418211 -0.012100 0.033495 +v 0.394997 -0.012231 0.047264 +v 0.420027 -0.012100 0.038685 +v 0.415544 -0.012100 0.049458 +v 0.419213 -0.012100 0.044659 +v 0.413521 -0.019529 0.050513 +v 0.415940 -0.019086 0.048991 +v 0.418229 -0.019264 0.046205 +v 0.419912 -0.019158 0.041743 +v 0.419722 -0.019232 0.037686 +v 0.418292 -0.019329 0.033784 +v 0.411468 0.018739 0.025971 +v 0.417549 0.019209 0.032824 +v 0.408994 -0.017627 0.023054 +v 0.405307 0.015267 0.018971 +v 0.395173 0.014253 0.052741 +v 0.397868 0.013553 0.052589 +v 0.394801 0.017872 0.052833 +v 0.397367 0.018382 0.052696 +v 0.409930 0.019537 0.051731 +v 0.404852 0.015370 0.052196 +v 0.403319 0.019295 0.052206 +v 0.402137 0.012735 0.052349 +v 0.414360 0.019108 0.050226 +v 0.416685 0.019607 0.048097 +v 0.419069 0.019420 0.044416 +v 0.420033 0.019193 0.040182 +v 0.419108 0.019559 0.035783 +v 0.395382 0.017834 0.048860 +v 0.397213 0.019733 0.047947 +v 0.399918 0.019813 0.051985 +v 0.399736 0.019573 0.046690 +v 0.401595 0.017244 0.045763 +v 0.400607 0.013395 0.046255 +v 0.397578 0.012686 0.047765 +v 0.395309 0.014654 0.048896 +v 0.397426 -0.019840 0.047841 +v 0.401128 -0.018633 0.045995 +v 0.394887 -0.016620 0.049106 +v 0.401099 -0.014082 0.046010 +v 0.397374 -0.012531 0.047867 +v 0.393180 0.018804 0.048169 +v 0.392573 0.014825 0.048472 +v 0.413811 -0.019672 0.028980 +v 0.419408 0.020032 0.040294 +v 0.392373 -0.015511 0.048572 +v 0.396326 -0.011202 0.033943 +v 0.396639 0.011538 0.034132 +v 0.342000 -0.019242 0.028953 +v 0.342000 -0.016668 0.022013 +v 0.341998 -0.010510 0.015433 +v 0.342000 -0.001075 0.012548 +v 0.341998 0.008597 0.014364 +v 0.342000 0.015481 0.020258 +v 0.341998 0.019291 0.028425 +v 0.341998 0.017985 0.039840 +v 0.341999 0.011784 0.047514 +v 0.342000 0.004347 0.050991 +v 0.342000 -0.003861 0.051096 +v 0.341999 -0.011384 0.047810 +v 0.341998 -0.018183 0.039596 +v 0.392202 -0.019680 0.047876 +v 0.412264 0.020500 0.045916 +v 0.410031 0.020350 0.047804 +v 0.414087 0.020476 0.045125 +v 0.415116 0.020500 0.040608 +v 0.415900 0.020445 0.039390 +v 0.402452 0.020500 0.044436 +v 0.402370 0.020404 0.045764 +v 0.406321 0.020500 0.046942 +v 0.406042 0.020426 0.047647 +v 0.413202 0.020500 0.034889 +v 0.414931 0.020390 0.036097 +v 0.412607 0.020419 0.033558 +v 0.403289 0.020500 0.034684 +v 0.402559 0.020445 0.034240 +v 0.400790 0.020500 0.039386 +v 0.400746 0.020412 0.036800 +v 0.400020 0.020393 0.040766 +v 0.408633 0.020453 0.031991 +v 0.407524 0.020500 0.032874 +v 0.401152 -0.020500 0.038111 +v 0.404273 -0.020500 0.033797 +v 0.410263 -0.020500 0.033179 +v 0.413631 -0.020500 0.035770 +v 0.415116 -0.020500 0.039392 +v 0.413202 -0.020500 0.045111 +v 0.408612 -0.020500 0.047017 +v 0.404072 -0.020500 0.046078 +v 0.401222 -0.020500 0.042013 +v 0.407535 -0.020426 0.032088 +v 0.411855 -0.020349 0.032944 +v 0.403024 -0.020436 0.046239 +v 0.400452 -0.020427 0.042495 +v 0.413456 -0.020428 0.045722 +v 0.408673 -0.020439 0.047874 +v 0.415122 -0.020425 0.036495 +v 0.415528 -0.020434 0.042526 +v 0.400110 -0.020396 0.039152 +v 0.402629 -0.020502 0.034228 +v 0.405047 -0.020001 0.047542 +v 0.411472 -0.019989 0.047271 +v 0.415522 0.020002 0.043009 +v 0.416097 -0.020001 0.039795 +v 0.405967 0.020005 0.032119 +v 0.403882 -0.020002 0.033040 +v 0.400982 -0.020002 0.035996 +v -0.017117 0.011250 0.019513 +v 0.008636 0.011250 0.022155 +v 0.000946 0.011250 0.026406 +v -0.025352 0.011250 0.003332 +v -0.014536 0.011250 -0.020039 +v -0.002324 0.011250 -0.024667 +v 0.009146 0.011250 -0.022925 +v -0.024096 0.011250 -0.005920 +v -0.021344 0.011250 -0.012224 +v 0.018325 0.011250 -0.016587 +v 0.127003 0.015579 0.020821 +v 0.127006 0.019285 0.032572 +v 0.127001 0.015499 0.043121 +v 0.127002 0.007730 0.049548 +v 0.127001 0.007690 0.014542 +v 0.127001 -0.001130 0.012957 +v 0.127001 -0.002204 0.050953 +v 0.127003 -0.010712 0.016096 +v 0.127001 -0.010657 0.047823 +v 0.127001 -0.017223 0.023796 +v 0.127001 -0.016067 0.042143 +v 0.127004 -0.019098 0.033703 +v 0.397105 0.015088 0.052377 +v 0.399001 0.014985 0.051525 +v 0.397148 0.017354 0.052358 +v 0.399717 0.017977 0.051168 +v 0.398355 0.019203 0.051757 +v 0.399312 0.012732 0.051285 +v 0.402234 0.013644 0.049815 +v 0.401679 0.015788 0.050190 +v 0.403295 0.016522 0.049305 +v 0.401393 0.019575 0.050248 +v 0.395988 0.017538 0.039686 +v 0.394931 0.014294 0.040374 +v 0.393286 0.016224 0.040947 +v 0.396181 0.015091 0.039707 +v 0.394843 0.018182 0.040413 +v 0.393230 0.015383 0.041530 +v 0.396703 0.017371 0.048110 +v 0.393625 0.017618 0.041350 +v 0.398290 0.018441 0.047308 +v 0.399962 0.017280 0.046485 +v 0.396840 0.016324 0.039747 +v 0.399998 0.015157 0.046459 +v 0.398168 0.014129 0.047377 +v 0.396610 0.015224 0.048148 +v 0.396182 0.013654 0.048534 +v 0.395262 0.016190 0.048989 +v 0.399910 0.019341 0.046686 +v 0.401286 0.017486 0.045985 +v 0.401352 0.015058 0.045959 +v 0.395848 0.018330 0.048718 +v 0.397628 0.019644 0.047809 +v 0.399255 0.012792 0.047002 +v 0.397999 0.014698 0.048672 +v 0.400395 0.016257 0.047478 +v 0.397989 0.017795 0.048677 +v 0.398644 -0.015594 0.051703 +v 0.397377 -0.014319 0.052248 +v 0.397150 -0.017563 0.052346 +v 0.399879 -0.012739 0.051014 +v 0.401621 -0.016906 0.050219 +v 0.401736 -0.019275 0.050063 +v 0.403151 -0.017114 0.049367 +v 0.399759 -0.017931 0.051147 +v 0.399076 -0.019618 0.051407 +v 0.402592 -0.013930 0.049644 +v 0.400506 -0.014569 0.050775 +v 0.393986 -0.017584 0.040615 +v 0.395867 -0.015194 0.039671 +v 0.396191 -0.017407 0.039672 +v 0.393591 -0.015158 0.040776 +v 0.393294 -0.015325 0.041517 +v 0.396683 -0.015154 0.048122 +v 0.397767 -0.014234 0.047566 +v 0.395211 -0.014142 0.040539 +v 0.399255 -0.014424 0.046831 +v 0.396773 -0.015596 0.039789 +v 0.400180 -0.015884 0.046369 +v 0.399720 -0.017684 0.046598 +v 0.395449 -0.018238 0.040448 +v 0.398391 -0.018352 0.047272 +v 0.393655 -0.017763 0.041320 +v 0.396664 -0.017452 0.048120 +v 0.395761 -0.018139 0.048755 +v 0.395258 -0.015265 0.048990 +v 0.400328 -0.013483 0.046488 +v 0.401592 -0.016227 0.045827 +v 0.397729 -0.012748 0.047747 +v 0.400298 -0.019032 0.046486 +v 0.397710 -0.019743 0.047774 +v 0.398421 -0.017931 0.048462 +v 0.400385 -0.016448 0.047483 +v 0.397204 -0.016052 0.049069 +v 0.399168 -0.014569 0.048090 +v 0.402107 0.008772 0.015842 +v 0.395411 0.008805 0.034239 +v 0.402842 0.008805 0.016145 +v 0.396146 0.008772 0.034541 +v 0.395400 -0.008772 0.034270 +v 0.396157 -0.008805 0.034510 +v 0.402096 -0.008805 0.015874 +v 0.402853 -0.008772 0.016114 +v 0.394655 0.008772 0.035000 +v 0.383426 0.008805 0.051036 +v 0.395286 0.008805 0.035482 +v 0.384057 0.008772 0.051519 +v 0.383407 -0.008772 0.051063 +v 0.384076 -0.008805 0.051491 +v 0.394636 -0.008805 0.035027 +v 0.395305 -0.008772 0.035455 +v 0.045953 0.025809 0.011372 +v 0.039076 0.025852 0.010497 +v 0.037961 0.026122 0.016960 +v 0.055626 0.025998 0.008066 +v 0.046027 0.025904 0.007082 +v 0.037301 0.025886 0.007367 +v 0.039795 0.025830 0.005109 +v 0.034185 0.025889 0.020655 +v 0.034665 0.025829 0.023462 +v 0.066104 0.025999 0.009176 +v 0.068407 0.026021 0.007977 +v 0.073409 0.025978 0.010677 +v 0.078651 0.026001 0.014897 +v 0.075709 0.026000 0.014867 +v 0.082491 0.025999 0.024837 +v 0.084060 0.025997 0.023593 +v 0.083529 0.025894 0.036907 +v 0.086074 0.025966 0.033466 +v 0.080420 0.025999 0.047449 +v 0.084372 0.025999 0.043988 +v 0.081696 0.025958 0.049036 +v 0.075963 0.026000 0.055554 +v 0.070839 0.025999 0.056798 +v 0.070700 0.026005 0.058975 +v 0.029271 0.026008 0.061940 +v 0.047126 0.025996 0.057830 +v 0.038973 0.025800 0.051157 +v 0.033304 0.025767 0.052550 +v 0.059195 0.025999 0.060022 +v 0.061208 0.026000 0.061977 +v 0.032694 0.025789 0.038414 +v 0.030479 0.025804 0.035917 +v 0.028056 0.025852 0.038977 +v 0.035191 0.025772 0.045514 +v 0.024074 0.025790 0.039971 +v -0.016105 0.025951 0.028849 +v 0.008057 0.025784 0.032837 +v 0.005807 0.025922 0.029225 +v -0.024066 0.025871 0.008721 +v -0.022535 0.025894 0.019582 +v -0.022328 0.025962 -0.006696 +v -0.010300 0.025899 -0.021190 +v -0.018878 0.025849 -0.014055 +v -0.002392 0.025912 -0.023281 +v 0.024429 0.025916 0.005167 +v 0.030258 0.025802 0.003716 +v 0.030456 0.025948 0.000734 +v 0.022972 0.025961 -0.006544 +v 0.005838 0.025922 -0.022530 +v 0.013764 0.025892 -0.019069 +v 0.032918 0.025830 0.028779 +v 0.031303 0.025823 0.028048 +v 0.007408 0.025822 0.023747 +v 0.020565 0.025789 0.013446 +v 0.014366 0.025789 0.019838 +v 0.060967 -0.026000 0.061981 +v 0.057518 -0.020676 0.061892 +v 0.055440 -0.023246 0.061977 +v 0.034747 -0.024043 0.061154 +v 0.037140 -0.026000 0.062000 +v 0.046660 -0.023696 0.061858 +v 0.036983 -0.025780 0.050264 +v 0.028829 -0.026000 0.058154 +v 0.032963 -0.025705 0.048653 +v -0.018592 -0.025946 0.022519 +v -0.017061 -0.025972 0.021260 +v -0.015057 -0.025865 0.026262 +v 0.032539 -0.025882 0.041706 +v 0.047659 -0.025734 0.058395 +v 0.084212 -0.025999 0.040544 +v 0.086359 -0.025994 0.033709 +v 0.084119 -0.026000 0.044319 +v 0.082383 -0.026033 0.020176 +v 0.084339 -0.025859 0.030529 +v 0.082180 -0.025879 0.023336 +v 0.074473 -0.025949 0.054859 +v 0.070589 -0.026007 0.059027 +v 0.064635 -0.025847 0.059752 +v 0.080064 -0.025865 0.048770 +v 0.079625 -0.025991 0.051859 +v 0.055979 -0.025778 0.060372 +v 0.075421 -0.026000 0.055923 +v 0.037159 0.011250 0.014501 +v 0.037026 -0.011250 0.014427 +v 0.033233 0.011250 0.020822 +v 0.030885 -0.011250 0.026179 +v 0.030097 0.011250 0.027299 +v -0.023592 0.011250 0.019476 +v -0.020404 0.011250 0.022827 +v -0.020660 0.011247 0.024719 +v 0.025266 0.011250 0.028619 +v 0.037947 0.011250 0.006410 +v 0.034592 0.011250 0.001986 +v 0.046916 0.011250 0.005968 +v 0.036315 0.011250 0.009822 +v 0.004841 0.011250 0.025585 +v 0.024820 0.011250 -0.006674 +v 0.047551 0.024863 0.006105 +v 0.041675 0.024434 0.004806 +v 0.033836 0.024890 0.001357 +v 0.027039 0.024411 -0.004140 +v 0.023330 0.025021 -0.008459 +v 0.069059 0.008679 0.008162 +v 0.062140 0.025084 0.006185 +v 0.065123 -0.016114 0.006849 +v 0.056822 -0.011420 0.005965 +v 0.125085 -0.020048 0.030128 +v 0.112956 -0.019594 0.037014 +v 0.113735 -0.020077 0.031881 +v 0.125150 -0.019353 0.036720 +v 0.125146 -0.003174 0.012245 +v 0.098751 -0.006932 0.013076 +v 0.092179 -0.003966 0.012247 +v 0.103726 -0.009466 0.014109 +v 0.125162 -0.009947 0.014486 +v 0.106357 -0.012259 0.015681 +v 0.110659 -0.013697 0.017039 +v 0.110978 -0.015733 0.019043 +v 0.115611 -0.016097 0.019944 +v 0.125209 -0.017040 0.021214 +v 0.115394 -0.018259 0.023520 +v 0.111656 -0.019450 0.026615 +v 0.115797 -0.011227 0.048745 +v 0.125204 -0.014175 0.046202 +v 0.125142 -0.007058 0.050820 +v 0.107896 -0.008628 0.050330 +v 0.104299 -0.004551 0.051580 +v 0.125098 0.000035 0.052071 +v 0.099546 -0.000890 0.052106 +v 0.100811 0.004303 0.051725 +v 0.125143 0.006006 0.051111 +v 0.108059 0.006968 0.050926 +v 0.113410 0.011556 0.048669 +v 0.115499 0.013606 0.047069 +v 0.125258 0.012267 0.047843 +v 0.125144 0.018229 0.040672 +v 0.116884 0.016691 0.043441 +v 0.117246 0.019085 0.038317 +v 0.111719 0.020084 0.033468 +v 0.125095 0.020019 0.032893 +v 0.113663 0.019832 0.028562 +v 0.125145 0.019193 0.025855 +v 0.111938 0.018825 0.024634 +v 0.125188 0.014777 0.018400 +v 0.115027 0.016608 0.020577 +v 0.114226 0.013944 0.017542 +v 0.110877 0.011285 0.015353 +v 0.125156 0.008671 0.013912 +v 0.101205 0.007920 0.013453 +v 0.092592 0.004123 0.012296 +v 0.125099 0.001959 0.012035 +v 0.089986 0.000256 0.011925 +v 0.125148 -0.017764 0.041173 +v -0.023280 0.024800 -0.007717 +v -0.019166 0.024498 0.027619 +v -0.020207 -0.024321 0.022748 +v -0.021610 0.025105 0.024047 +v -0.023635 0.024597 0.019410 +v 0.031541 -0.011079 0.035037 +v 0.032804 -0.011027 0.041999 +v 0.030214 -0.011250 0.039431 +v 0.008513 -0.011250 0.022199 +v 0.026473 -0.011250 0.028849 +v 0.002198 -0.011250 0.026660 +v -0.016158 -0.024786 0.026767 +v -0.014922 0.024859 0.031102 +v -0.024241 0.025200 -0.002507 +v -0.025063 0.024482 0.003943 +v -0.024787 0.024725 0.012321 +v 0.057569 0.021114 0.061887 +v 0.071590 -0.000795 0.058625 +v 0.019377 0.025180 -0.014715 +v 0.015756 0.024685 -0.018722 +v 0.010166 0.024847 -0.022255 +v 0.005212 0.024744 -0.023871 +v 0.000061 0.024812 -0.024490 +v -0.007286 0.024573 -0.023413 +v -0.014076 0.024860 -0.020028 +v -0.019807 0.024786 -0.014499 +v 0.030127 -0.025010 0.039371 +v -0.014917 -0.024487 0.019789 +v 0.055278 0.023508 0.061862 +v 0.032046 0.020738 0.062138 +v 0.034693 0.023765 0.062000 +v 0.045845 0.023974 0.061844 +v 0.031786 -0.021969 0.059893 +v 0.044338 -0.011114 0.011287 +v 0.036299 -0.011250 0.009759 +v 0.037991 -0.011250 0.006425 +v -0.019178 -0.024450 0.020994 +v -0.017172 -0.024372 0.019839 +v 0.100486 0.021511 0.030743 +v 0.109199 0.020201 0.029351 +v 0.081266 0.023259 0.053223 +v 0.075098 0.023890 0.056718 +v 0.096880 0.014373 0.050305 +v 0.096219 0.016653 0.049525 +v 0.089087 0.017996 0.051597 +v 0.087430 0.016618 0.052418 +v 0.097409 0.011306 0.050871 +v 0.098842 0.017808 0.047624 +v 0.091161 0.020958 0.048267 +v 0.088858 0.019849 0.050829 +v 0.085059 0.022863 0.050607 +v 0.081889 0.021667 0.053629 +v 0.080292 0.020645 0.054542 +v 0.089461 0.022991 0.045889 +v 0.088938 0.024253 0.041816 +v 0.102764 0.020789 0.038026 +v 0.111090 0.019261 0.039205 +v 0.104437 0.019009 0.042981 +v 0.108039 0.017013 0.045054 +v 0.105183 0.011027 0.049871 +v 0.105339 0.014441 0.048192 +v 0.090687 0.024003 0.028391 +v 0.086637 0.024175 0.020924 +v 0.083781 0.023769 0.016672 +v 0.082569 0.022035 0.013951 +v 0.108667 0.016079 0.019028 +v 0.106155 0.014137 0.016809 +v 0.101339 0.011794 0.014809 +v 0.093237 0.013490 0.014083 +v 0.105372 0.017533 0.020038 +v 0.101418 0.020688 0.025596 +v 0.100451 0.019244 0.020964 +v 0.096158 0.016394 0.016130 +v 0.096674 0.018428 0.017979 +v 0.085090 0.015840 0.012976 +v 0.087034 0.017957 0.013981 +v 0.096732 0.022398 0.035105 +v 0.096199 0.021792 0.041501 +v 0.096967 0.020090 0.045522 +v 0.089579 0.019675 0.015848 +v 0.090417 0.021029 0.017796 +v 0.093141 0.022281 0.022979 +v 0.076540 0.021785 0.011182 +v 0.082705 -0.019560 0.012987 +v 0.075616 -0.022170 0.010793 +v 0.075258 -0.016521 0.010373 +v 0.078250 -0.008717 0.010730 +v 0.074720 0.008540 0.009855 +v 0.087467 -0.016011 0.013525 +v 0.081465 0.002200 0.011129 +v 0.083794 0.008650 0.011878 +v 0.083745 -0.004551 0.011471 +v 0.095087 -0.012598 0.014145 +v 0.077282 -0.022853 0.055685 +v 0.077944 0.007167 0.056068 +v 0.078099 -0.009548 0.055978 +v 0.085619 0.009226 0.053657 +v 0.084374 0.000346 0.054300 +v 0.085631 -0.009327 0.053660 +v 0.084113 -0.019036 0.053218 +v 0.092174 -0.016140 0.051134 +v 0.092854 -0.006879 0.052349 +v 0.091251 0.000268 0.052935 +v 0.092846 0.006820 0.052342 +v 0.098717 -0.011547 0.050695 +v 0.085199 -0.021996 0.015530 +v 0.080336 -0.024897 0.015068 +v 0.077672 -0.023355 0.011991 +v 0.087310 -0.024236 0.022180 +v 0.091196 -0.023924 0.029270 +v 0.099731 -0.021776 0.033860 +v 0.093693 -0.022392 0.024085 +v 0.095208 -0.020581 0.020427 +v 0.088624 -0.022342 0.018644 +v 0.092113 -0.019230 0.016727 +v 0.086220 -0.019992 0.014600 +v 0.088701 -0.023849 0.044369 +v 0.116260 -0.017373 0.042447 +v 0.085618 -0.023532 0.049106 +v 0.083817 -0.022385 0.052212 +v 0.116222 -0.014808 0.045879 +v 0.078955 -0.024126 0.054375 +v 0.107508 -0.012054 0.049119 +v 0.109700 -0.018115 0.022282 +v 0.106408 -0.020513 0.030033 +v 0.108080 -0.016901 0.045104 +v 0.106601 -0.015143 0.047350 +v 0.103318 -0.015646 0.017420 +v 0.106931 -0.020460 0.035201 +v 0.108231 -0.018392 0.042547 +v 0.099362 -0.014692 0.049544 +v 0.101912 -0.018684 0.020575 +v 0.101805 -0.019950 0.023376 +v 0.101813 -0.020923 0.027392 +v 0.102962 -0.020486 0.039286 +v 0.100016 -0.018609 0.046126 +v 0.097917 -0.017310 0.048468 +v 0.092711 -0.016790 0.015270 +v 0.097084 -0.018690 0.018389 +v 0.100760 -0.020000 0.042895 +v 0.090377 -0.020112 0.049810 +v 0.087253 -0.019564 0.051767 +v 0.094759 -0.022207 0.041458 +v 0.092889 -0.021091 0.046703 +v 0.092785 -0.023516 0.036274 +v 0.046733 -0.008300 0.010178 +v 0.050606 -0.011013 0.008620 +v 0.056304 -0.008300 0.007686 +v 0.056523 -0.011227 0.007525 +v 0.037889 -0.008300 0.016723 +v 0.037093 -0.011075 0.017566 +v 0.034104 -0.010756 0.022939 +v 0.032442 -0.008300 0.027323 +v 0.032034 -0.011069 0.028695 +v 0.031875 -0.008300 0.037904 +v 0.034470 -0.008300 0.045726 +v 0.078250 -0.023691 0.017130 +v 0.082878 -0.008300 0.024791 +v 0.076865 -0.008300 0.015614 +v 0.070902 -0.019449 0.010930 +v 0.067994 -0.008300 0.009427 +v 0.062062 -0.014345 0.007972 +v 0.039152 -0.008300 0.052516 +v 0.041659 -0.025505 0.054653 +v 0.046882 -0.008300 0.057880 +v 0.055971 -0.008300 0.060344 +v 0.067942 -0.008300 0.058591 +v 0.068742 -0.025497 0.058046 +v 0.076796 -0.008300 0.052455 +v 0.082148 -0.008300 0.044722 +v 0.083627 -0.025497 0.040075 +v 0.084296 -0.008300 0.035542 +v 0.032609 0.024707 0.031404 +v 0.033447 0.024710 0.041072 +v 0.038339 0.024710 0.050320 +v 0.046527 0.024710 0.056831 +v 0.045450 0.025501 0.056168 +v 0.054160 0.024980 0.059084 +v 0.067027 0.024980 0.057717 +v 0.072702 0.025483 0.054804 +v 0.075584 0.024923 0.052351 +v 0.080544 0.024710 0.046029 +v 0.081048 0.025481 0.044850 +v 0.083593 0.024703 0.035397 +v 0.035473 0.024972 0.022220 +v 0.037749 0.024701 0.018542 +v 0.041021 0.025503 0.014998 +v 0.044435 0.024700 0.012341 +v 0.052800 0.024986 0.009184 +v 0.061772 0.025508 0.008722 +v 0.063410 0.024700 0.008917 +v 0.070373 0.025498 0.011728 +v 0.075065 0.024699 0.014835 +v 0.077516 0.025496 0.017502 +v 0.081748 0.024697 0.024541 +v 0.082919 0.025494 0.027926 +v 0.084729 0.024101 0.033597 +v 0.081781 0.024101 0.046030 +v 0.073331 0.024101 0.055861 +v 0.059191 0.024103 0.060800 +v 0.060722 0.024994 0.059167 +v 0.042206 0.024105 0.055866 +v 0.032951 0.024101 0.043107 +v 0.031685 0.024103 0.028383 +v 0.038575 0.024101 0.015831 +v 0.047038 0.024101 0.009806 +v 0.056926 0.024101 0.007413 +v 0.066822 0.024100 0.008950 +v 0.075663 0.024101 0.014114 +v 0.081904 0.024100 0.022419 +v -0.019767 -0.025303 0.022735 +v -0.018339 -0.025264 0.020702 +v -0.015475 -0.025602 0.020352 +v 0.028241 0.025432 -0.002266 +v 0.038276 0.024224 0.056722 +v 0.036403 0.023385 0.055889 +v 0.035453 0.021414 0.055131 +v 0.036777 -0.023446 0.055294 +v 0.034398 -0.020310 0.053804 +v 0.035028 -0.022151 0.054338 +v 0.039105 0.021772 0.054652 +v 0.037865 -0.020504 0.053381 +v 0.042648 -0.021396 0.057510 +v 0.045776 0.022023 0.059367 +v 0.048106 -0.021461 0.060273 +v 0.049939 0.022627 0.060935 +v 0.053254 -0.022578 0.061588 +v 0.045562 0.023301 0.060321 +v 0.047440 -0.022882 0.060754 +v 0.039040 0.023272 0.055499 +v 0.042045 -0.023042 0.058221 +v 0.037826 -0.022263 0.054070 +v 0.037539 0.022773 0.054889 +v 0.037053 0.020842 0.054218 +v 0.036206 -0.020504 0.053108 +v 0.008064 0.013250 0.032655 +v 0.025037 0.013250 0.040001 +v 0.007079 0.013250 0.024325 +v 0.006333 0.025485 0.026126 +v 0.006108 0.013250 0.029370 +v 0.024204 0.013250 0.005903 +v 0.019639 0.013250 0.015166 +v 0.029152 0.013250 0.003581 +v 0.026782 0.025494 0.004135 +v 0.036978 0.013250 0.007441 +v 0.039237 0.013250 0.012690 +v 0.038690 0.025525 0.014053 +v 0.030188 0.013250 0.036476 +v 0.031281 0.013250 0.027360 +v 0.034632 0.013250 0.019560 +v 0.050718 -0.026000 0.008155 +v 0.046554 -0.026000 0.007574 +v 0.045283 -0.022000 0.007610 +v 0.021626 -0.026009 -0.011499 +v 0.024740 -0.011250 -0.006048 +v 0.025708 -0.026000 -0.004790 +v 0.032822 -0.011250 0.001830 +v 0.033555 -0.026000 0.002259 +v 0.037405 -0.022000 0.004608 +v 0.043109 -0.011250 0.007018 +v 0.052641 -0.011250 0.008326 +v 0.062452 -0.026000 0.008038 +v -0.020471 -0.011250 0.013568 +v -0.016525 -0.026000 0.018712 +v -0.014805 -0.011250 0.019695 +v -0.024390 -0.011250 0.004279 +v -0.024576 -0.026000 0.001237 +v -0.022836 -0.026000 0.009059 +v -0.023427 -0.011250 -0.007760 +v -0.022701 -0.026000 -0.009971 +v -0.017103 -0.011250 -0.018073 +v -0.015788 -0.026000 -0.018889 +v -0.006648 -0.026000 -0.023743 +v -0.006166 -0.011250 -0.023820 +v 0.002821 -0.011250 -0.024454 +v 0.005899 -0.026018 -0.023942 +v 0.012459 -0.011250 -0.021288 +v 0.013938 -0.025999 -0.020225 +v 0.019309 -0.011250 -0.015181 +v 0.017996 -0.026000 -0.016625 +v 0.019460 -0.026000 -0.014885 +v 0.020446 -0.026000 -0.013463 +v 0.013095 -0.026000 0.031800 +v 0.021693 -0.026000 0.035493 +v 0.012772 -0.022000 0.031637 +v 0.022024 -0.022000 0.035579 +v 0.003472 -0.022000 0.027607 +v 0.004165 -0.026000 0.027664 +v 0.016859 -0.011250 0.033446 +v 0.030889 -0.022000 0.039531 +v 0.032705 -0.011250 0.040796 +v 0.031252 -0.026000 0.039796 +v 0.032277 -0.026000 0.040651 +v 0.032920 -0.026022 0.041480 +v 0.032260 -0.004233 0.037409 +v 0.031771 -0.011250 0.031462 +v 0.035475 -0.004293 0.047179 +v 0.032316 -0.004179 0.031067 +v 0.033729 -0.004187 0.024944 +v 0.036970 -0.004206 0.018846 +v 0.035953 -0.011250 0.019901 +v 0.050580 -0.004160 0.009124 +v 0.042913 -0.011250 0.012668 +v 0.043404 -0.004182 0.012488 +v 0.055537 -0.004537 0.007996 +v 0.041361 -0.022000 0.013857 +v 0.037705 -0.022000 0.013027 +v 0.044122 -0.022000 0.010098 +v 0.035961 -0.022000 0.009732 +v 0.037615 -0.022000 0.006517 +v 0.083165 -0.026000 0.041312 +v 0.031641 -0.026000 0.035648 +v 0.031808 -0.026014 0.035123 +v 0.031926 -0.026007 0.033662 +v 0.031282 -0.026019 0.031875 +v 0.041194 -0.026000 0.013671 +v 0.042427 -0.026000 0.013113 +v 0.041834 -0.026000 0.013444 +v 0.030589 -0.026000 0.039029 +v 0.030465 -0.026000 0.038711 +v 0.008514 -0.026000 0.022311 +v 0.062438 -0.004183 0.008522 +v 0.074709 -0.004168 0.014281 +v 0.074564 -0.026000 0.013727 +v 0.069057 -0.004242 0.010488 +v 0.079052 -0.004219 0.018851 +v 0.081749 -0.026000 0.022956 +v 0.083087 -0.004249 0.026959 +v 0.079000 -0.004229 0.049203 +v 0.081961 -0.004149 0.043633 +v 0.083777 -0.004244 0.037245 +v 0.083983 -0.026000 0.032029 +v 0.078197 -0.026000 0.050570 +v 0.073448 -0.004545 0.055073 +v 0.071114 -0.026000 0.056598 +v 0.069158 -0.004134 0.057434 +v 0.061215 -0.026000 0.060014 +v 0.062115 -0.004206 0.059581 +v 0.037582 -0.011250 0.014202 +v 0.036433 -0.011250 0.010455 +v 0.015042 -0.011250 0.024026 +v 0.032218 -0.011250 0.022811 +v 0.026080 -0.011250 0.002938 +v 0.030244 -0.011250 0.002435 +v 0.053306 -0.004181 0.059536 +v 0.050708 -0.026000 0.059067 +v 0.036114 -0.011250 0.006400 +v 0.043344 -0.004221 0.055563 +v 0.041411 -0.026000 0.054281 +v 0.035445 -0.026000 0.047050 +v 0.013404 -0.026000 0.024943 +v 0.012354 -0.026013 0.023219 +v 0.026257 -0.026000 0.030481 +v 0.037416 -0.026000 0.012687 +v 0.037944 -0.026000 0.013114 +v 0.028939 -0.026000 0.030229 +v 0.012153 -0.026003 0.029610 +v 0.012620 -0.026000 0.028779 +v 0.024692 -0.026000 0.031785 +v 0.030989 -0.026000 0.039580 +v 0.030765 -0.026000 0.039322 +v 0.036276 -0.026000 0.008954 +v 0.036189 -0.026000 0.009627 +v 0.030397 -0.026000 0.038377 +v 0.030387 -0.026000 0.038036 +v 0.030435 -0.026000 0.037698 +v 0.030540 -0.026000 0.037373 +v 0.031435 -0.026006 0.036067 +v 0.044260 -0.026000 0.008978 +v 0.044377 -0.026000 0.008672 +v 0.022523 -0.026000 0.035410 +v 0.022842 -0.026000 0.035290 +v 0.023135 -0.026000 0.035118 +v 0.023396 -0.026000 0.034899 +v 0.023616 -0.026000 0.034638 +v 0.023893 -0.026000 0.034109 +v 0.023971 -0.026000 0.033691 +v 0.026901 -0.026000 0.030245 +v 0.024101 -0.026000 0.033018 +v 0.024343 -0.026000 0.032376 +v 0.012771 -0.026000 0.031552 +v 0.012542 -0.026000 0.031299 +v 0.012298 -0.026000 0.030906 +v 0.030150 -0.026010 0.030769 +v 0.038791 -0.026000 0.013563 +v 0.039847 -0.026000 0.013786 +v 0.036438 -0.026000 0.011238 +v 0.036968 -0.026000 0.012177 +v 0.027576 -0.026000 0.030123 +v 0.013020 -0.026000 0.028228 +v 0.013321 -0.026000 0.027617 +v 0.013514 -0.026000 0.026963 +v 0.013593 -0.026000 0.026287 +v 0.025136 -0.026000 0.031263 +v 0.025118 -0.026000 0.031283 +v 0.013556 -0.026000 0.025607 +v 0.025663 -0.026000 0.030824 +v 0.028262 -0.026000 0.030117 +v 0.040525 -0.026000 0.013786 +v 0.027384 -0.026000 0.030158 +v 0.005483 -0.026039 0.026294 +v 0.006328 -0.026000 0.023854 +v 0.044542 -0.026000 0.008389 +v 0.044752 -0.026000 0.008138 +v 0.010538 -0.026000 0.022275 +v 0.006767 -0.026000 0.023333 +v 0.007288 -0.026000 0.022894 +v 0.007876 -0.026000 0.022550 +v 0.036217 -0.026000 0.010305 +v 0.042955 -0.026000 0.012686 +v 0.043403 -0.026000 0.012176 +v 0.044011 -0.026000 0.010968 +v 0.043758 -0.026000 0.011598 +v 0.044153 -0.026000 0.010304 +v 0.044181 -0.026000 0.009626 +v 0.044194 -0.026000 0.009299 +v 0.036475 -0.026000 0.008305 +v 0.045000 -0.026000 0.007924 +v 0.045279 -0.026000 0.007753 +v 0.009864 -0.026000 0.022171 +v 0.036781 -0.026000 0.007699 +v 0.045582 -0.026000 0.007630 +v 0.045902 -0.026000 0.007558 +v 0.046229 -0.026000 0.007539 +v 0.009183 -0.026000 0.022184 +v 0.037186 -0.026000 0.007154 +v 0.037381 -0.026000 0.006891 +v 0.037585 -0.026000 0.006476 +v 0.037681 -0.026000 0.005965 +v 0.037677 -0.026000 0.005637 +v 0.037618 -0.026000 0.005315 +v 0.037508 -0.026000 0.005007 +v 0.037350 -0.026000 0.004720 +v 0.037146 -0.026000 0.004464 +v 0.036903 -0.026000 0.004244 +v 0.023731 -0.022000 0.034585 +v 0.024537 -0.022000 0.031820 +v 0.027122 -0.022000 0.030126 +v 0.030466 -0.022000 0.030790 +v 0.032091 -0.022000 0.034569 +v 0.030308 -0.022000 0.037762 +v 0.005305 -0.022000 0.026797 +v 0.006176 -0.022000 0.023876 +v 0.010129 -0.022000 0.021901 +v 0.013876 -0.022000 0.025812 +v 0.012049 -0.022000 0.029754 +v 0.020757 -0.020000 0.027027 +v 0.020747 -0.011250 0.027039 +v 0.022557 -0.011250 0.029572 +v 0.024131 -0.020000 0.030900 +v 0.025163 -0.011250 0.030867 +v 0.029906 -0.020000 0.029412 +v 0.029914 -0.011250 0.029354 +v 0.032833 -0.020000 0.021322 +v 0.037538 -0.020000 0.014208 +v 0.036498 -0.020000 0.010393 +v 0.035732 -0.020000 0.006067 +v 0.029033 -0.020000 0.002016 +v 0.025450 -0.020000 0.004003 +v 0.022557 -0.011250 0.012739 +v 0.022171 -0.020000 0.013409 +v 0.015562 -0.011250 0.020456 +v 0.014842 -0.020000 0.021609 +v 0.016442 -0.020000 0.025920 +v 0.017441 -0.011250 0.026385 +v 0.012344 -0.026705 0.029287 +v 0.013421 -0.026737 0.027680 +v 0.013582 -0.026228 0.026089 +v 0.013114 -0.026700 0.023944 +v 0.010884 -0.026293 0.022340 +v 0.008868 -0.026445 0.022160 +v 0.006815 -0.026547 0.023191 +v 0.006026 -0.026013 0.024380 +v 0.012828 -0.026562 0.031634 +v 0.012532 -0.026000 0.031283 +v 0.023788 -0.026000 0.034345 +v 0.023649 -0.026745 0.034502 +v 0.022259 -0.026712 0.035501 +v 0.021733 -0.026016 0.035518 +v 0.028236 -0.026286 0.030029 +v 0.025935 -0.026175 0.030657 +v 0.025026 -0.026940 0.031100 +v 0.024147 -0.026781 0.032506 +v 0.030774 -0.026875 0.039167 +v 0.030365 -0.026021 0.038229 +v 0.030524 -0.026204 0.037246 +v 0.032178 -0.026917 0.040322 +v 0.062504 -0.026054 0.008313 +v 0.060178 -0.026920 0.008170 +v 0.054774 -0.026212 0.008105 +v 0.080291 -0.026014 0.020376 +v 0.078502 -0.026768 0.018116 +v 0.076352 -0.026035 0.015500 +v 0.083448 -0.026029 0.028272 +v 0.081986 -0.026978 0.024338 +v 0.082735 -0.026190 0.042252 +v 0.083655 -0.026822 0.037554 +v 0.084069 -0.026085 0.034777 +v 0.077240 -0.026580 0.051544 +v 0.080550 -0.026054 0.047155 +v 0.075651 -0.026004 0.053200 +v 0.073095 -0.026752 0.055106 +v 0.068570 -0.026471 0.057835 +v 0.050178 -0.026006 0.058901 +v 0.053399 -0.026653 0.059515 +v 0.057586 -0.026601 0.059984 +v 0.061773 -0.026004 0.059907 +v 0.045935 -0.026850 0.056991 +v 0.040816 -0.026039 0.053739 +v 0.034473 -0.026607 0.044962 +v 0.035983 -0.026109 0.048014 +v 0.045897 -0.026656 0.007592 +v 0.050552 -0.026004 0.008126 +v 0.044161 -0.026074 0.009278 +v 0.044685 -0.027146 0.008495 +v 0.045008 -0.026076 0.007874 +v 0.037560 -0.026124 0.006675 +v 0.036690 -0.026025 0.007864 +v 0.036074 -0.026664 0.009616 +v 0.036543 -0.026307 0.011495 +v 0.038177 -0.026740 0.013479 +v 0.039067 -0.026029 0.013659 +v 0.041272 -0.026777 0.013817 +v 0.042988 -0.026478 0.012832 +v 0.044123 -0.026313 0.010532 +v 0.037049 -0.026821 0.004487 +v 0.033436 -0.026005 0.002148 +v 0.037714 -0.026222 0.005476 +v 0.032063 -0.026754 0.001325 +v 0.026868 -0.026005 -0.003498 +v -0.014325 -0.026837 0.019737 +v -0.014236 -0.026006 0.019985 +v -0.018060 -0.026228 0.016661 +v -0.021316 -0.026016 -0.012338 +v -0.023316 -0.026901 -0.007356 +v -0.024555 -0.026130 -0.001899 +v -0.018054 -0.026643 -0.016524 +v -0.015192 -0.026001 -0.019286 +v -0.009448 -0.026073 -0.022680 +v -0.013161 -0.026977 -0.020512 +v 0.015223 -0.026292 -0.019294 +v 0.011635 -0.026031 -0.021604 +v 0.018441 -0.026928 -0.015991 +v 0.004278 -0.026028 0.027582 +v 0.003400 -0.026670 0.027497 +v 0.002872 -0.026072 0.024282 +v 0.002436 -0.026080 0.025451 +v 0.019564 -0.026000 0.016859 +v 0.002046 -0.026069 0.022993 +v -0.000011 -0.026130 0.024520 +v 0.000573 -0.026083 0.023216 +v 0.000978 -0.026121 0.025816 +v -0.021275 -0.026043 0.012382 +v -0.017863 -0.026107 0.010283 +v -0.017343 -0.026105 0.012215 +v -0.023411 -0.026035 0.007471 +v -0.020152 -0.026123 0.011168 +v -0.019184 -0.026079 0.010139 +v -0.019928 -0.026100 0.012360 +v -0.018702 -0.026111 0.013003 +v -0.024407 -0.026009 0.002731 +v -0.000793 -0.026091 -0.022401 +v -0.004022 -0.026058 -0.024271 +v -0.000477 -0.026071 -0.021027 +v 0.020875 -0.026028 -0.007100 +v 0.002197 -0.026012 -0.024505 +v 0.023356 -0.026114 -0.005567 +v 0.022182 -0.026081 -0.004663 +v 0.020868 -0.026112 -0.005196 +v 0.023353 -0.026110 -0.006793 +v 0.022230 -0.026159 -0.007628 +v 0.053854 -0.026000 0.024190 +v 0.046801 -0.026111 0.011349 +v 0.045691 -0.026116 0.010608 +v 0.045674 -0.026091 0.009274 +v 0.046929 -0.026099 0.008430 +v 0.048351 -0.026067 0.009364 +v 0.072350 -0.026637 0.012281 +v 0.067332 -0.026027 0.009649 +v 0.074984 -0.026107 0.018668 +v 0.075637 -0.026121 0.017467 +v 0.077360 -0.026099 0.017443 +v 0.077897 -0.026119 0.018942 +v 0.077152 -0.026092 0.019971 +v 0.075902 -0.026119 0.020077 +v 0.055021 -0.026084 0.056617 +v 0.055417 -0.026121 0.058092 +v 0.052506 -0.026125 0.058084 +v 0.053163 -0.026099 0.056320 +v 0.053862 -0.026093 0.059140 +v 0.034204 -0.026089 0.038110 +v 0.033668 -0.026093 0.039283 +v 0.032317 -0.026112 0.039599 +v 0.033051 -0.026112 0.036692 +v 0.031488 -0.026584 0.032124 +v 0.031333 -0.026103 0.038533 +v 0.032049 -0.026677 0.034336 +v 0.030994 -0.026009 0.031516 +v 0.031558 -0.026119 0.037319 +v 0.012105 -0.026103 0.030395 +v -0.000065 -0.026168 -0.023295 +v 0.001479 -0.026128 -0.023220 +v 0.002114 -0.026102 -0.021556 +v 0.000768 -0.026107 -0.020537 +v 0.048109 -0.026064 0.010873 +v 0.075874 -0.027444 0.015987 +v 0.056277 -0.027535 0.059201 +v 0.033400 -0.027465 0.040809 +v 0.036262 -0.027538 0.046746 +v 0.051500 -0.027387 0.058568 +v 0.039210 -0.027238 0.051362 +v 0.045332 -0.027556 0.055737 +v 0.068424 -0.027540 0.056955 +v 0.062329 -0.026977 0.059460 +v 0.075743 -0.027536 0.051759 +v 0.082341 -0.027531 0.040788 +v 0.083292 -0.027446 0.031403 +v 0.067182 -0.027492 0.010325 +v 0.079962 -0.027496 0.046671 +v 0.078874 -0.027589 0.020097 +v 0.059196 -0.027562 0.009109 +v 0.045355 -0.027184 0.008066 +v 0.047854 -0.026869 0.008021 +v 0.049982 -0.027654 0.009464 +v 0.030631 -0.026935 0.037663 +v 0.032414 -0.027432 0.035509 +v 0.029704 -0.026983 0.030141 +v 0.027701 -0.027482 0.029237 +v 0.022604 -0.027532 0.034540 +v 0.032299 -0.027548 0.031018 +v 0.024484 -0.027575 0.030268 +v 0.037174 -0.027176 0.006368 +v 0.043071 -0.027515 0.013958 +v 0.044767 -0.027505 0.011493 +v 0.034984 -0.027550 0.010615 +v 0.038146 -0.027555 0.014617 +v 0.036755 -0.027555 0.005515 +v 0.012882 -0.027521 0.030370 +v 0.023701 -0.026805 -0.007542 +v 0.027414 -0.026820 -0.002785 +v 0.024554 -0.027514 -0.005133 +v 0.029934 -0.027504 0.000738 +v 0.019907 -0.027509 -0.013054 +v 0.021878 -0.027559 -0.008883 +v -0.018055 -0.027630 0.014378 +v -0.015744 -0.027522 0.017847 +v -0.020506 -0.026969 0.012994 +v -0.000282 -0.027111 -0.024163 +v -0.005921 -0.027457 -0.023185 +v -0.014681 -0.027562 -0.018377 +v -0.022821 -0.027505 0.006902 +v 0.011329 -0.027482 -0.021045 +v 0.005525 -0.027113 -0.023566 +v 0.002770 -0.027461 -0.023687 +v -0.001927 -0.027603 -0.023129 +v -0.019365 -0.027461 -0.013975 +v -0.023015 -0.027565 -0.005204 +v -0.024259 -0.027061 0.001270 +v -0.021106 -0.027619 0.009761 +v 0.005998 -0.027468 0.022925 +v 0.014371 -0.027449 0.025900 +v 0.010614 -0.027495 0.021364 +v 0.004921 -0.027193 0.026622 +v 0.008626 -0.027389 0.021551 +v 0.013998 -0.027561 0.023393 +v 0.004189 -0.027614 0.025800 +v 0.003195 -0.027535 0.026621 +v -0.001280 -0.027537 0.024567 +v 0.000252 -0.026823 0.026067 +v 0.047226 -0.027594 0.012832 +v 0.076368 -0.027588 0.021668 +v 0.073513 -0.027593 0.018841 +v 0.052094 -0.027589 0.055296 +v 0.056439 -0.027587 0.055904 +v 0.035007 -0.027594 0.036377 +v 0.035288 -0.027596 0.039457 +v 0.000020 -0.027584 0.021751 +v 0.003527 -0.027597 0.022421 +v -0.017203 -0.027598 0.009064 +v -0.015882 -0.027597 0.011871 +v 0.002560 -0.027570 -0.019555 +v -0.001647 -0.027597 -0.020184 +v 0.022708 -0.027597 -0.003365 +v 0.019578 -0.027590 -0.004528 +v 0.019740 -0.027597 -0.007859 +v 0.022262 -0.027554 -0.005279 +v 0.024723 -0.027538 -0.006118 +v 0.023736 -0.027531 -0.004211 +v 0.021822 -0.027554 -0.007024 +v 0.021393 -0.027467 -0.008697 +v 0.023504 -0.027535 -0.008306 +v 0.022882 -0.027592 -0.006363 +v 0.019672 -0.027535 -0.007316 +v 0.021202 -0.027591 -0.005940 +v 0.019732 -0.027522 -0.004888 +v 0.021874 -0.027515 -0.003497 +v 0.022487 -0.022617 -0.006862 +v 0.021183 -0.022562 -0.006035 +v 0.022772 -0.022755 -0.005313 +v 0.022210 -0.026107 -0.007572 +v 0.022330 -0.023098 -0.007499 +v 0.023345 -0.023117 -0.006179 +v 0.023353 -0.026117 -0.006144 +v 0.022275 -0.026110 -0.004759 +v 0.021247 -0.023103 -0.005043 +v 0.020658 -0.026117 -0.006078 +v 0.020828 -0.023115 -0.006652 +v 0.031178 -0.025910 0.035595 +v 0.029726 -0.026000 0.034319 +v 0.031318 -0.025888 0.033124 +v 0.026877 -0.026000 0.035536 +v 0.027581 -0.025883 0.037622 +v 0.025241 -0.025904 0.036384 +v 0.029547 -0.025909 0.037190 +v 0.030221 -0.025883 0.031435 +v 0.024438 -0.025873 0.034153 +v 0.027961 -0.025908 0.030551 +v 0.027247 -0.026000 0.032461 +v 0.025225 -0.025911 0.031822 +v 0.026168 -0.002068 0.034661 +v 0.029355 -0.002138 0.035325 +v 0.029106 -0.001973 0.032871 +v 0.027018 -0.002163 0.035735 +v 0.026268 -0.002153 0.033180 +v 0.029912 -0.021919 0.034944 +v 0.029771 -0.021912 0.032994 +v 0.030009 -0.002502 0.033655 +v 0.027861 -0.002449 0.031913 +v 0.027695 -0.021910 0.031930 +v 0.026167 -0.021916 0.033040 +v 0.025893 -0.021913 0.034669 +v 0.027171 -0.021917 0.036077 +v 0.028322 -0.002487 0.036138 +v 0.028653 -0.021906 0.036072 +v 0.031467 -0.022076 0.033868 +v 0.024689 -0.022063 0.032639 +v 0.030491 -0.022082 0.036622 +v 0.026722 -0.022085 0.030821 +v 0.029835 -0.022069 0.030996 +v 0.027952 -0.022064 0.037608 +v 0.025062 -0.022069 0.036315 +v 0.026540 -0.023000 0.035205 +v 0.027702 -0.023000 0.032334 +v 0.029608 -0.023000 0.034776 +v 0.041756 -0.026000 0.010654 +v 0.043389 -0.025894 0.011258 +v 0.041574 -0.025887 0.013065 +v 0.043591 -0.025902 0.008901 +v 0.038660 -0.026000 0.010734 +v 0.038357 -0.025901 0.012914 +v 0.036604 -0.025911 0.009858 +v 0.040139 -0.026000 0.008012 +v 0.041813 -0.025913 0.006609 +v 0.038251 -0.025886 0.006735 +v 0.041825 -0.001995 0.009534 +v 0.038792 -0.002141 0.011126 +v 0.040741 -0.002218 0.011683 +v 0.039618 -0.002107 0.007950 +v 0.042155 -0.002507 0.010419 +v 0.041859 -0.021924 0.011094 +v 0.042262 -0.021913 0.009249 +v 0.041796 -0.002489 0.008461 +v 0.040369 -0.021906 0.007603 +v 0.038079 -0.002498 0.009288 +v 0.038424 -0.021915 0.008562 +v 0.038363 -0.021909 0.011034 +v 0.040448 -0.021913 0.011897 +v 0.042945 -0.022083 0.012034 +v 0.043670 -0.022076 0.009769 +v 0.038767 -0.022081 0.006546 +v 0.036895 -0.022083 0.008531 +v 0.039979 -0.022060 0.013400 +v 0.041143 -0.022058 0.006452 +v 0.037009 -0.022063 0.011443 +v 0.043006 -0.022083 0.007684 +v 0.038469 -0.023000 0.010302 +v 0.040608 -0.023000 0.008062 +v 0.041478 -0.023000 0.011035 +v 0.008070 -0.026000 0.027096 +v 0.007991 -0.025883 0.029339 +v 0.006159 -0.025898 0.027076 +v 0.012349 -0.025886 0.023852 +v 0.013074 -0.025890 0.026859 +v 0.011120 -0.026000 0.025228 +v 0.011213 -0.025921 0.029370 +v 0.010297 -0.026000 0.027746 +v 0.006883 -0.025898 0.023748 +v 0.008893 -0.026000 0.024579 +v 0.009783 -0.025919 0.022659 +v 0.011050 -0.002086 0.024919 +v 0.010298 -0.002218 0.028029 +v 0.011475 -0.002207 0.026491 +v 0.008346 -0.002183 0.027627 +v 0.008450 -0.001980 0.024944 +v 0.010595 -0.021911 0.028088 +v 0.011741 -0.021903 0.025754 +v 0.010586 -0.021922 0.024278 +v 0.009288 -0.002485 0.024121 +v 0.008439 -0.021912 0.024334 +v 0.007489 -0.002498 0.025650 +v 0.007469 -0.021914 0.026249 +v 0.008408 -0.021914 0.027929 +v 0.012390 -0.022071 0.028438 +v 0.012979 -0.022073 0.025009 +v 0.006739 -0.022085 0.024055 +v 0.009904 -0.022076 0.029634 +v 0.009091 -0.022082 0.022672 +v 0.011219 -0.022064 0.023081 +v 0.007382 -0.022063 0.028971 +v 0.006110 -0.022073 0.026528 +v 0.007878 -0.023000 0.026665 +v 0.008893 -0.023000 0.024579 +v 0.010297 -0.023000 0.027746 +v 0.011311 -0.023000 0.025660 +v -0.018008 -0.027304 0.012082 +v -0.016421 -0.027304 0.012791 +v -0.017955 -0.027251 0.014031 +v -0.016222 -0.027289 0.010930 +v -0.019247 -0.027342 0.012237 +v -0.021279 -0.027233 0.012132 +v -0.019449 -0.027304 0.011004 +v -0.018210 -0.027341 0.010850 +v -0.017202 -0.027202 0.009410 +v -0.019305 -0.027297 0.008973 +v -0.020971 -0.027293 0.010257 +v -0.020021 -0.027284 0.013800 +v -0.018251 -0.022366 0.010844 +v -0.019599 -0.022334 0.011537 +v -0.018225 -0.022357 0.012224 +v -0.017803 -0.025869 0.012497 +v -0.017663 -0.022848 0.012417 +v -0.019515 -0.025861 0.012681 +v -0.019431 -0.022863 0.012667 +v -0.020018 -0.022868 0.011453 +v -0.019885 -0.025865 0.010823 +v -0.019325 -0.022865 0.010373 +v -0.018599 -0.025868 0.010261 +v -0.017802 -0.022860 0.010578 +v -0.017514 -0.025863 0.010973 +v -0.000088 -0.027304 -0.022530 +v -0.001794 -0.027273 -0.021174 +v -0.001816 -0.027239 -0.022872 +v 0.001151 -0.027341 -0.022685 +v 0.001281 -0.027298 -0.024535 +v 0.002863 -0.027272 -0.023286 +v 0.001353 -0.027304 -0.021452 +v 0.003124 -0.027288 -0.021002 +v 0.001167 -0.027241 -0.019438 +v 0.000114 -0.027342 -0.021297 +v -0.000831 -0.027283 -0.019842 +v -0.000501 -0.027266 -0.024374 +v 0.000950 -0.022368 -0.022757 +v -0.000235 -0.022340 -0.021952 +v 0.001248 -0.022345 -0.021383 +v 0.001572 -0.025864 -0.021081 +v 0.001752 -0.022841 -0.021165 +v 0.000045 -0.025867 -0.020751 +v -0.000197 -0.022857 -0.020925 +v -0.000665 -0.025868 -0.022291 +v -0.000476 -0.022848 -0.022809 +v 0.000619 -0.025863 -0.023357 +v 0.001406 -0.022857 -0.023098 +v 0.001900 -0.025867 -0.022362 +v -0.001130 -0.027251 0.024883 +v -0.000979 -0.027285 0.023442 +v 0.000725 -0.027304 0.023852 +v 0.002167 -0.027304 0.024930 +v 0.003733 -0.027256 0.025611 +v 0.002100 -0.027270 0.026938 +v 0.003936 -0.027257 0.023664 +v 0.000927 -0.027342 0.025084 +v 0.000012 -0.027269 0.026551 +v 0.000516 -0.027294 0.021880 +v 0.002892 -0.027284 0.022242 +v 0.001964 -0.027341 0.023697 +v 0.000600 -0.022363 0.024208 +v 0.001740 -0.022495 0.025441 +v 0.002183 -0.022320 0.023928 +v 0.002236 -0.025865 0.025485 +v 0.002774 -0.022860 0.024552 +v 0.000616 -0.022857 0.025456 +v 0.000257 -0.025860 0.025179 +v 0.000406 -0.022833 0.023444 +v 0.000715 -0.025868 0.023263 +v 0.002131 -0.022868 0.023295 +v 0.002596 -0.025860 0.023572 +v 0.030519 -0.027257 0.039502 +v 0.030165 -0.027260 0.037832 +v 0.032005 -0.027304 0.037637 +v 0.033447 -0.027304 0.038715 +v 0.035295 -0.027253 0.038922 +v 0.033711 -0.027293 0.040554 +v 0.033244 -0.027341 0.037483 +v 0.033222 -0.027310 0.035647 +v 0.034661 -0.027260 0.036423 +v 0.032207 -0.027342 0.038870 +v 0.031248 -0.027263 0.035993 +v 0.031914 -0.027273 0.040667 +v 0.031882 -0.022303 0.038347 +v 0.033669 -0.022559 0.038879 +v 0.033204 -0.022366 0.037477 +v 0.033265 -0.025857 0.039501 +v 0.032200 -0.022860 0.039406 +v 0.031348 -0.025861 0.038405 +v 0.031409 -0.022857 0.037876 +v 0.032361 -0.025866 0.036892 +v 0.032716 -0.022863 0.036851 +v 0.033933 -0.025869 0.037531 +v 0.033862 -0.022868 0.037560 +v 0.054673 -0.027304 0.058195 +v 0.055967 -0.027264 0.059315 +v 0.054599 -0.027296 0.060144 +v 0.051624 -0.027208 0.058869 +v 0.051505 -0.027271 0.056719 +v 0.053232 -0.027304 0.057117 +v 0.056567 -0.027280 0.057634 +v 0.053434 -0.027342 0.058350 +v 0.054471 -0.027341 0.056963 +v 0.054113 -0.027299 0.055046 +v 0.055889 -0.027306 0.055924 +v 0.053189 -0.027276 0.060159 +v 0.052838 -0.027262 0.055282 +v 0.053669 -0.022366 0.058454 +v 0.054250 -0.022497 0.056562 +v 0.053137 -0.022516 0.056842 +v 0.054714 -0.022367 0.057905 +v 0.054375 -0.025866 0.058923 +v 0.055310 -0.022841 0.057965 +v 0.053828 -0.022865 0.058964 +v 0.052822 -0.025869 0.058404 +v 0.052626 -0.022857 0.057909 +v 0.052807 -0.025866 0.057070 +v 0.054110 -0.025863 0.056272 +v 0.055290 -0.025865 0.057659 +v 0.077184 -0.027304 0.019206 +v 0.078294 -0.027287 0.020507 +v 0.076942 -0.027260 0.021203 +v 0.074823 -0.027278 0.016671 +v 0.076096 -0.027292 0.016080 +v 0.075742 -0.027304 0.018128 +v 0.075945 -0.027342 0.019360 +v 0.073961 -0.027292 0.019245 +v 0.079075 -0.027314 0.018672 +v 0.076982 -0.027341 0.017973 +v 0.078631 -0.027274 0.017179 +v 0.074017 -0.027284 0.017771 +v 0.074945 -0.027268 0.020811 +v 0.076830 -0.022293 0.017897 +v 0.075382 -0.022483 0.018660 +v 0.076995 -0.022435 0.019606 +v 0.076925 -0.025866 0.019919 +v 0.075571 -0.022853 0.019698 +v 0.075419 -0.025865 0.019503 +v 0.075293 -0.025867 0.018077 +v 0.075982 -0.022860 0.017419 +v 0.076724 -0.025863 0.017312 +v 0.077748 -0.022841 0.018132 +v 0.077795 -0.025868 0.018666 +v 0.077388 -0.027097 0.016262 +v 0.047689 -0.027304 0.010444 +v 0.048928 -0.027277 0.011607 +v 0.047278 -0.027268 0.012506 +v 0.045053 -0.027279 0.011726 +v 0.044382 -0.027265 0.009906 +v 0.046248 -0.027304 0.009366 +v 0.049602 -0.027290 0.009769 +v 0.046450 -0.027342 0.010599 +v 0.045302 -0.027239 0.007827 +v 0.048134 -0.027281 0.007501 +v 0.047487 -0.027341 0.009212 +v 0.046381 -0.022515 0.010843 +v 0.048089 -0.022524 0.010077 +v 0.046218 -0.022363 0.009474 +v 0.047673 -0.022539 0.009047 +v 0.048220 -0.025869 0.010424 +v 0.047445 -0.022863 0.011142 +v 0.046734 -0.025861 0.011230 +v 0.045752 -0.025866 0.010333 +v 0.045653 -0.022863 0.009745 +v 0.046071 -0.025870 0.008816 +v 0.046624 -0.022865 0.008638 +v 0.047844 -0.025864 0.008922 +v -0.016548 0.025359 0.039065 +v -0.009487 0.020226 0.041848 +v -0.012722 0.019130 0.040307 +v -0.001529 0.024751 0.045776 +v 0.007843 0.019524 0.049604 +v 0.004602 0.018424 0.048061 +v -0.007285 0.017599 0.042641 +v -0.009933 -0.002884 0.039898 +v -0.007513 -0.000857 0.041142 +v -0.009119 -0.013791 0.039439 +v 0.016713 0.024013 0.053941 +v 0.010045 0.016897 0.050398 +v 0.025173 0.018822 0.057361 +v 0.029543 0.023062 0.059651 +v 0.027375 0.016195 0.058154 +v -0.012581 0.015155 0.040070 +v 0.021932 0.017723 0.055817 +v 0.022095 0.013739 0.055589 +v -0.007479 -0.017480 0.039899 +v 0.004415 -0.015472 0.045411 +v 0.004578 -0.019455 0.045183 +v -0.008966 0.014044 0.041615 +v 0.004765 0.014441 0.047833 +v -0.008799 0.002815 0.040840 +v 0.021962 0.001786 0.054625 +v 0.025695 0.012640 0.057128 +v 0.029801 -0.001447 0.057913 +v 0.008212 -0.014493 0.047196 +v 0.018694 -0.003699 0.052736 +v 0.021745 -0.016174 0.053168 +v 0.018757 0.001693 0.053173 +v 0.008364 0.013342 0.049371 +v -0.012908 -0.014767 0.037649 +v -0.015758 0.008825 0.038159 +v -0.012344 0.002602 0.039227 +v 0.017408 -0.000863 0.052372 +v 0.024110 -0.000738 0.055401 +v -0.012803 -0.001494 0.038710 +v 0.022364 -0.003933 0.054373 +v 0.025542 -0.015195 0.054952 +v 0.009851 -0.018182 0.047656 +v 0.027182 -0.018884 0.055412 +v -0.001804 -0.025096 0.041880 +v 0.029276 -0.026015 0.055816 +v 0.021908 -0.020157 0.052940 +v -0.009710 -0.019928 0.038709 +v 0.007621 -0.020630 0.046465 +v 0.024951 -0.021332 0.054222 +v -0.017457 -0.024465 0.034921 +v -0.012768 -0.018741 0.037420 +v 0.018175 0.001904 0.058424 +v 0.020817 -0.004120 0.059159 +v 0.021788 -0.000383 0.059879 +v -0.014195 -0.002575 0.043498 +v -0.015165 0.000402 0.043286 +v -0.011364 -0.003072 0.044736 +v -0.009609 -0.001003 0.045684 +v -0.010129 0.001553 0.045643 +v -0.012969 0.003074 0.044478 +v -0.022226 -0.024615 0.037083 +v -0.021051 0.025392 0.038956 +v -0.021483 -0.024470 0.035258 +v -0.021944 0.025240 0.041000 +v -0.021565 -0.023750 0.038545 +v -0.018762 -0.003864 0.041343 +v -0.021279 0.024155 0.042301 +v 0.027249 0.023147 0.063038 +v -0.006093 0.023512 0.049124 +v 0.013461 0.022720 0.057875 +v 0.026767 0.021960 0.063821 +v 0.028257 0.021741 0.063381 +v 0.026840 -0.001754 0.062052 +v 0.026865 -0.015043 0.060994 +v 0.027812 0.013962 0.062976 +v 0.026678 -0.022670 0.060411 +v 0.028013 -0.025013 0.059734 +v 0.027653 -0.018968 0.060359 +v 0.026517 -0.025439 0.060120 +v 0.026914 0.019301 0.063691 +v 0.027149 -0.026471 0.059230 +v -0.006356 -0.024154 0.045398 +v 0.013198 -0.024946 0.054149 +v 0.013072 0.007115 0.056519 +v 0.010145 0.019367 0.056109 +v 0.016786 0.013496 0.058667 +v -0.000706 0.017919 0.051116 +v 0.003986 0.022582 0.053576 +v 0.004415 0.009622 0.052794 +v -0.006256 0.008413 0.047907 +v 0.000312 0.012594 0.051182 +v 0.009988 0.012299 0.055509 +v 0.021079 0.009082 0.060264 +v -0.007723 0.006445 0.047097 +v -0.012139 0.010383 0.045404 +v 0.013037 -0.009471 0.055248 +v 0.015310 -0.000824 0.056927 +v 0.016681 -0.004039 0.057301 +v -0.007719 -0.007520 0.046042 +v -0.009725 -0.011515 0.044833 +v -0.014443 -0.011049 0.042741 +v 0.010882 -0.017942 0.053617 +v 0.016437 -0.016679 0.056223 +v -0.006055 -0.009315 0.046656 +v -0.000933 -0.016716 0.048399 +v 0.002003 -0.012015 0.050069 +v 0.001035 -0.022745 0.048815 +v 0.007620 -0.012224 0.052591 +v 0.007426 -0.023765 0.051626 +v -0.012712 -0.023553 0.042571 +v -0.017340 -0.020569 0.040712 +v -0.007527 -0.020890 0.045106 +v -0.018012 -0.014620 0.040858 +v -0.006916 -0.015541 0.045795 +v -0.007340 0.013006 0.047756 +v -0.015728 0.011846 0.043898 +v -0.017939 0.015322 0.043161 +v -0.016502 0.021653 0.044265 +v -0.009850 0.022631 0.047354 +v -0.006729 0.018355 0.048444 +v 0.025439 0.009938 0.062304 +v 0.021316 0.021880 0.061333 +v 0.017174 0.018337 0.059215 +v 0.023965 -0.012486 0.059940 +v 0.023600 -0.024702 0.058853 +v 0.018365 -0.023447 0.056571 +v 0.019685 -0.012726 0.057995 +v 0.014174 -0.009365 0.052470 +v -0.006404 -0.007702 0.043322 +v -0.004485 -0.009163 0.044077 +v 0.014727 0.006289 0.053904 +v -0.005920 0.008221 0.044746 +v 0.012957 0.007963 0.053233 +v 0.026153 -0.016900 0.057108 +v 0.022897 -0.015054 0.055787 +v 0.020670 -0.017345 0.054622 +v 0.021516 -0.020744 0.054728 +v 0.024419 -0.021308 0.056018 +v 0.025951 -0.020018 0.056806 +v 0.009193 -0.017720 0.049405 +v 0.007322 -0.014703 0.048806 +v 0.005002 -0.014683 0.047769 +v 0.003360 -0.016504 0.046883 +v 0.004084 -0.019903 0.046943 +v 0.007251 -0.020610 0.048326 +v -0.008255 -0.017016 0.041628 +v -0.009664 -0.014136 0.041181 +v -0.013211 -0.014389 0.039578 +v -0.013983 -0.017716 0.038973 +v -0.011598 -0.020136 0.039847 +v -0.009068 -0.019083 0.041093 +v 0.008839 0.014455 0.051690 +v 0.008621 0.018381 0.051882 +v 0.005594 0.019417 0.050609 +v 0.003685 0.017664 0.049623 +v 0.003598 0.015376 0.049406 +v 0.005673 0.013124 0.050159 +v -0.008410 0.018484 0.044212 +v -0.008452 0.015376 0.043977 +v -0.011478 0.020282 0.042957 +v -0.013716 0.018145 0.041810 +v -0.013537 0.015468 0.041694 +v -0.010820 0.013728 0.042773 +v 0.026430 0.016322 0.059763 +v 0.025030 0.018392 0.059292 +v 0.021730 0.018200 0.057772 +v 0.020848 0.014869 0.057140 +v 0.022428 0.012770 0.057698 +v 0.024691 0.012607 0.058702 +v 0.026247 0.014083 0.059524 +v -0.008265 -0.021399 0.044693 +v -0.006825 -0.017060 0.045682 +v -0.010751 -0.018585 0.043915 +v -0.014495 -0.018007 0.042272 +v -0.017998 -0.017050 0.040601 +v -0.017143 -0.020336 0.040803 +v -0.017598 -0.014545 0.041027 +v -0.014387 -0.022850 0.041855 +v -0.011757 -0.023207 0.042926 +v -0.012265 -0.014763 0.043522 +v -0.008388 -0.012992 0.045278 +v -0.011385 -0.011164 0.044051 +v -0.015157 -0.011571 0.042342 +v -0.002913 -0.017411 0.027811 +v -0.007814 -0.015905 0.025845 +v -0.007182 -0.013883 0.026256 +v -0.005974 -0.018403 0.026271 +v -0.003414 -0.013914 0.027758 +v -0.014088 -0.016521 0.038926 +v -0.007330 -0.018023 0.026253 +v -0.012447 -0.019624 0.039442 +v -0.004857 -0.018999 0.027290 +v -0.010010 -0.019740 0.040529 +v -0.008325 -0.017611 0.041449 +v -0.002735 -0.014645 0.028572 +v -0.009185 -0.014730 0.041281 +v -0.005319 -0.012773 0.027549 +v -0.011823 -0.013805 0.040161 +v -0.013254 -0.018395 0.040273 +v -0.009532 -0.017885 0.041989 +v -0.011897 -0.014599 0.041172 +v -0.007519 -0.001495 0.028897 +v -0.014397 -0.001557 0.042515 +v -0.008583 0.000964 0.028632 +v -0.014807 0.000247 0.042591 +v -0.013049 -0.002926 0.043018 +v -0.004826 -0.001989 0.030085 +v -0.010497 -0.002775 0.044192 +v -0.003111 -0.000534 0.029796 +v -0.009333 -0.000820 0.044901 +v -0.003027 0.001545 0.031180 +v -0.009578 0.001310 0.044925 +v -0.004306 0.003625 0.029568 +v -0.011397 0.002862 0.044202 +v -0.006353 0.003982 0.029849 +v -0.013686 0.002435 0.043147 +v -0.007532 0.002688 0.028071 +v -0.002839 0.000584 0.029914 +v -0.004490 -0.001520 0.028923 +v -0.006330 -0.001406 0.028109 +v -0.007782 0.000485 0.027677 +v -0.006661 0.003259 0.028265 +v -0.003163 0.002291 0.029875 +v -0.003675 0.000597 0.028922 +v -0.004705 0.002239 0.028443 +v -0.006184 0.000885 0.027689 +v -0.004722 0.000625 0.028195 +v -0.011780 -0.001030 0.044656 +v -0.012626 0.000314 0.044436 +v -0.012974 -0.001591 0.043930 +v -0.012687 0.001436 0.044291 +v -0.010851 0.000755 0.044959 +v 0.023208 -0.002079 0.041547 +v 0.016303 -0.003183 0.056220 +v 0.021983 0.000064 0.042338 +v 0.015789 -0.000620 0.056193 +v 0.023893 -0.003223 0.042928 +v 0.018117 -0.004311 0.056944 +v 0.026304 -0.002909 0.044056 +v 0.019855 -0.004094 0.057748 +v 0.027466 -0.001111 0.044728 +v 0.020938 -0.002877 0.058353 +v 0.021325 -0.001099 0.058641 +v 0.027705 0.000515 0.043772 +v 0.026890 0.001905 0.043506 +v 0.020348 0.000908 0.058367 +v 0.024514 0.002784 0.043668 +v 0.018825 0.001648 0.057728 +v 0.017084 0.001325 0.056906 +v 0.023192 0.001668 0.041815 +v 0.027139 -0.002014 0.043085 +v 0.025561 -0.002936 0.042434 +v 0.022730 -0.000486 0.041354 +v 0.024858 0.002470 0.042419 +v 0.026925 -0.000059 0.042665 +v 0.024763 -0.001535 0.041557 +v 0.024317 0.000213 0.041413 +v 0.025993 0.001047 0.042235 +v 0.025629 -0.000643 0.041788 +v 0.017393 -0.003200 0.057283 +v 0.016848 -0.000930 0.057448 +v 0.018073 -0.001893 0.058099 +v 0.018227 0.000162 0.058130 +v 0.020011 -0.000551 0.058684 +v 0.019395 -0.001525 0.058612 +v 0.018959 -0.003127 0.058067 +v 0.020353 0.014486 0.060435 +v 0.016801 0.016679 0.058869 +v 0.017778 0.012067 0.058936 +v 0.021250 0.017379 0.061058 +v 0.021779 0.021566 0.061495 +v 0.018623 0.019969 0.059955 +v 0.020404 0.009730 0.059948 +v 0.022872 0.009240 0.061131 +v 0.023438 0.013369 0.061741 +v 0.025177 0.020570 0.062883 +v 0.024336 0.016262 0.062364 +v 0.027285 0.012328 0.063270 +v 0.027992 0.015736 0.063824 +v 0.025362 0.010113 0.062185 +v 0.026875 0.018774 0.063607 +v 0.029321 0.019417 0.045106 +v 0.027929 0.014472 0.044250 +v 0.027339 0.018092 0.044197 +v 0.030636 0.014081 0.045233 +v 0.032182 0.017440 0.046300 +v 0.022262 0.018414 0.057960 +v 0.020883 0.015807 0.057139 +v 0.026753 0.016166 0.044202 +v 0.021767 0.013404 0.057358 +v 0.030487 0.013522 0.045661 +v 0.023623 0.012569 0.058132 +v 0.025481 0.013145 0.059015 +v 0.032281 0.015965 0.046678 +v 0.026573 0.015850 0.059703 +v 0.025017 0.018272 0.059191 +v 0.030597 0.019371 0.046176 +v 0.024381 0.013527 0.059649 +v 0.024980 0.016967 0.060179 +v 0.021594 0.014097 0.058436 +v 0.022193 0.017537 0.058966 +v -0.016297 0.012632 0.043682 +v -0.012677 0.010643 0.045117 +v -0.014308 0.015889 0.044921 +v -0.010564 0.015311 0.046565 +v -0.006698 0.016480 0.048201 +v -0.007201 0.019116 0.048309 +v -0.017717 0.015484 0.043170 +v -0.017047 0.020281 0.043876 +v -0.009688 0.011335 0.046593 +v -0.012078 0.019133 0.046172 +v -0.014124 0.022592 0.045396 +v -0.008771 0.021486 0.047671 +v -0.011630 0.022786 0.046526 +v -0.007579 0.013221 0.047616 +v -0.002929 0.016524 0.030306 +v -0.007188 0.016951 0.028400 +v -0.007513 0.019182 0.028626 +v -0.005179 0.015152 0.029379 +v -0.005810 0.020872 0.029497 +v -0.002355 0.018436 0.030876 +v -0.013667 0.018284 0.041755 +v -0.007389 0.016108 0.028802 +v -0.013341 0.015510 0.041695 +v -0.011774 0.014067 0.042294 +v -0.008833 0.014724 0.043669 +v -0.003248 0.015593 0.030633 +v -0.008306 0.018007 0.044152 +v -0.003605 0.020586 0.030846 +v -0.010692 0.020192 0.043245 +v -0.013067 0.015501 0.042923 +v -0.009345 0.016011 0.044638 +v -0.011710 0.019297 0.043821 +v 0.005252 0.018431 0.053928 +v 0.008766 0.020463 0.055581 +v 0.006509 0.021924 0.054651 +v 0.006767 0.014609 0.054322 +v 0.010454 0.014156 0.055790 +v 0.010290 0.018098 0.056018 +v 0.003022 0.015187 0.052678 +v -0.000454 0.015473 0.050985 +v 0.000389 0.012945 0.051249 +v -0.000113 0.018490 0.051390 +v 0.003781 0.022066 0.053360 +v 0.001293 0.020671 0.052198 +v 0.002152 0.010944 0.051806 +v 0.005834 0.009979 0.053437 +v 0.008778 0.011411 0.054878 +v 0.013532 0.014640 0.037738 +v 0.009868 0.016333 0.036174 +v 0.011281 0.019939 0.037020 +v 0.015027 0.017009 0.038596 +v 0.013216 0.019743 0.037821 +v 0.003593 0.017011 0.049442 +v 0.009737 0.018852 0.036737 +v 0.004368 0.014103 0.049569 +v 0.011236 0.014352 0.037062 +v 0.007030 0.013272 0.050708 +v 0.008639 0.014480 0.051524 +v 0.009142 0.017291 0.051959 +v 0.013726 0.019884 0.038603 +v 0.006676 0.019370 0.051009 +v 0.004736 0.018821 0.050092 +v 0.004263 0.014799 0.050679 +v 0.007985 0.015309 0.052395 +v 0.005621 0.018595 0.051578 +v 0.021919 -0.020877 0.058464 +v 0.024121 -0.024323 0.059048 +v 0.026423 -0.022597 0.060254 +v 0.020404 -0.017055 0.058071 +v 0.016604 -0.018622 0.056092 +v 0.017730 -0.021978 0.056368 +v 0.017406 -0.015257 0.056758 +v 0.020353 -0.024275 0.057385 +v 0.019840 -0.012799 0.058038 +v 0.024149 -0.017634 0.059714 +v 0.024696 -0.013119 0.060188 +v 0.027829 -0.019286 0.061143 +v 0.027049 -0.015633 0.061039 +v 0.030449 -0.019815 0.042584 +v 0.027012 -0.018265 0.041281 +v 0.028440 -0.014662 0.042127 +v 0.032117 -0.017284 0.043755 +v 0.030628 -0.014935 0.043038 +v 0.021604 -0.015978 0.055063 +v 0.026944 -0.015588 0.041882 +v 0.020643 -0.018761 0.054413 +v 0.028379 -0.020246 0.042169 +v 0.022659 -0.021223 0.055137 +v 0.025355 -0.020768 0.056391 +v 0.031225 -0.019707 0.043497 +v 0.026291 -0.018499 0.056981 +v 0.025689 -0.016403 0.056873 +v 0.030869 -0.014714 0.043710 +v 0.023643 -0.015222 0.056034 +v 0.021893 -0.012421 0.058737 +v 0.025129 -0.019289 0.057502 +v 0.022088 -0.020349 0.056051 +v 0.021071 -0.017438 0.055813 +v 0.024112 -0.016378 0.057264 +v 0.009542 -0.021274 0.052731 +v 0.010410 -0.018591 0.053319 +v 0.006818 -0.016932 0.051958 +v 0.003074 -0.016353 0.050314 +v -0.000696 -0.016938 0.048441 +v -0.000242 -0.020004 0.048423 +v 0.000635 -0.013690 0.049293 +v 0.009774 -0.014935 0.053326 +v 0.004588 -0.020175 0.050707 +v 0.001753 -0.022839 0.049082 +v 0.005106 -0.023894 0.050534 +v 0.007634 -0.023183 0.051720 +v 0.003807 -0.011706 0.050859 +v 0.007158 -0.012326 0.052346 +v 0.014266 -0.017939 0.035447 +v 0.009955 -0.017647 0.033507 +v 0.010905 -0.013954 0.034397 +v 0.012059 -0.019447 0.034510 +v 0.014070 -0.014879 0.035576 +v 0.003240 -0.017592 0.046659 +v 0.009309 -0.015669 0.033931 +v 0.009754 -0.018490 0.033909 +v 0.005189 -0.020489 0.047320 +v 0.007774 -0.020205 0.048509 +v 0.013895 -0.019005 0.035740 +v 0.009001 -0.017950 0.049233 +v 0.014800 -0.016545 0.036340 +v 0.008410 -0.015859 0.049125 +v 0.013539 -0.014012 0.035953 +v 0.006765 -0.014585 0.048480 +v 0.004647 -0.014986 0.047493 +v 0.007798 -0.018587 0.049745 +v 0.004758 -0.019647 0.048295 +v 0.003740 -0.016736 0.048057 +v 0.006781 -0.015676 0.049507 +v 0.018993 0.023920 0.054962 +v 0.022109 0.024443 0.048049 +v -0.012552 0.025847 0.032536 +v -0.015667 0.025324 0.039449 +v 0.021833 -0.025404 0.044153 +v 0.018718 -0.025927 0.051065 +v -0.012827 -0.024000 0.028640 +v -0.015942 -0.024523 0.035552 +v 0.033036 0.020794 0.052698 +v 0.029921 0.020271 0.059610 +v 0.029682 -0.023165 0.056215 +v 0.032797 -0.022642 0.049302 +v 0.007232 0.040296 0.013336 +v 0.007574 0.040297 0.013190 +v 0.008704 0.040309 0.013429 +v 0.007737 0.040303 0.013702 +v 0.008841 0.040313 0.013747 +v 0.006964 0.040289 0.012914 +v 0.007910 0.040277 0.010896 +v 0.007987 0.040281 0.011234 +v 0.007792 0.040277 0.010938 +v 0.007216 0.040283 0.012093 +v 0.009613 0.040313 0.013134 +v 0.009475 0.040307 0.012570 +v 0.006900 0.040279 0.011930 +v 0.009837 0.040306 0.012173 +v 0.009226 0.040290 0.011117 +v 0.009117 0.040293 0.011472 +v 0.008347 0.032658 0.013704 +v 0.009303 0.032662 0.013350 +v 0.009709 0.032656 0.012415 +v 0.009453 0.032647 0.011632 +v 0.008574 0.032634 0.011117 +v 0.007593 0.032629 0.011393 +v 0.007112 0.032636 0.012502 +v 0.007580 0.032648 0.013407 +v 0.008336 0.032860 0.013902 +v 0.008289 0.038659 0.013846 +v 0.009041 0.032864 0.013763 +v 0.008993 0.038664 0.013707 +v 0.009439 0.032865 0.013493 +v 0.009730 0.032863 0.013110 +v 0.009682 0.038663 0.013054 +v 0.009907 0.032858 0.012414 +v 0.009859 0.038658 0.012358 +v 0.009692 0.038649 0.011659 +v 0.009612 0.032847 0.011511 +v 0.009564 0.038646 0.011455 +v 0.009268 0.032841 0.011175 +v 0.009220 0.038640 0.011119 +v 0.008598 0.032833 0.010916 +v 0.008550 0.038632 0.010860 +v 0.007885 0.032828 0.010998 +v 0.007837 0.038627 0.010941 +v 0.007466 0.032826 0.011236 +v 0.007291 0.032827 0.011402 +v 0.007243 0.038626 0.011345 +v 0.007031 0.032828 0.011807 +v 0.006983 0.038628 0.011750 +v 0.006911 0.032834 0.012515 +v 0.006863 0.038634 0.012458 +v 0.007023 0.032840 0.012983 +v 0.006975 0.038639 0.012926 +v 0.007450 0.032849 0.013559 +v 0.007403 0.038648 0.013503 +v 0.007444 0.038664 0.015047 +v 0.005555 0.038617 0.011841 +v 0.006313 0.038647 0.014331 +v 0.005750 0.038635 0.013494 +v 0.009108 0.038678 0.015097 +v 0.010019 0.038681 0.014664 +v 0.007136 0.038610 0.009774 +v 0.008108 0.038615 0.009509 +v 0.006316 0.038609 0.010361 +v 0.011129 0.038674 0.013019 +v 0.010722 0.038680 0.013941 +v 0.011032 0.038657 0.011357 +v 0.009432 0.038628 0.009707 +v 0.010284 0.038640 0.010246 +v 0.007422 0.038994 0.015037 +v 0.007200 0.038991 0.014949 +v 0.006241 0.038976 0.014254 +v 0.005731 0.038964 0.013452 +v 0.005556 0.038947 0.011814 +v 0.005776 0.038942 0.011134 +v 0.006158 0.038939 0.010530 +v 0.006492 0.038939 0.010189 +v 0.007086 0.038940 0.009793 +v 0.008234 0.038946 0.009497 +v 0.008472 0.038948 0.009497 +v 0.009177 0.038955 0.009615 +v 0.009402 0.038958 0.009693 +v 0.010216 0.038969 0.010185 +v 0.010550 0.038975 0.010525 +v 0.011100 0.038990 0.011574 +v 0.011132 0.039004 0.012992 +v 0.010985 0.039007 0.013445 +v 0.010765 0.039010 0.013868 +v 0.009068 0.039008 0.015104 +v 0.006749 0.039146 0.010138 +v 0.006570 0.039146 0.010280 +v 0.011033 0.039198 0.011828 +v 0.010981 0.039195 0.011606 +v 0.009432 0.039888 0.010541 +v 0.010024 0.040187 0.012010 +v 0.010045 0.040189 0.012152 +v 0.007504 0.039393 0.014787 +v 0.007574 0.040054 0.014077 +v 0.007303 0.039391 0.014707 +v 0.007431 0.040052 0.014006 +v 0.006431 0.039377 0.014075 +v 0.007079 0.040177 0.013477 +v 0.006987 0.040176 0.013367 +v 0.006168 0.039372 0.013731 +v 0.006003 0.039536 0.011686 +v 0.006239 0.039532 0.011122 +v 0.007225 0.040019 0.010792 +v 0.007644 0.040020 0.010562 +v 0.007794 0.040021 0.010509 +v 0.007579 0.039647 0.013197 +v 0.008709 0.039659 0.013435 +v 0.007221 0.039633 0.012099 +v 0.007993 0.039631 0.011240 +v 0.009123 0.039643 0.011479 +v 0.009481 0.039657 0.012576 +v -0.018737 0.037668 0.002562 +v -0.018301 0.036149 0.002861 +v -0.019399 0.037391 0.002271 +v -0.019460 0.037365 0.002244 +v -0.020939 0.036745 0.001592 +v -0.020282 0.035303 0.001810 +v -0.022033 0.036110 0.001301 +v -0.021184 0.034775 0.001521 +v -0.023755 0.034688 0.000888 +v -0.024550 0.034032 0.000697 +v -0.023438 0.032903 0.000969 +v -0.025301 0.033174 0.000508 +v -0.025613 0.029684 0.000428 +v -0.023955 0.032319 0.000844 +v -0.027488 0.016000 -0.000065 +v -0.029077 0.016000 -0.000500 +v -0.026649 0.025922 0.000158 +v -0.028241 0.026028 -0.000270 +v -0.025933 0.028923 0.000346 +v -0.027508 0.029238 -0.000071 +v -0.027050 0.030354 0.000052 +v -0.016947 0.038135 0.004203 +v -0.016651 0.036588 0.004549 +v -0.016858 0.038158 0.004285 +v -0.013985 0.036913 0.008413 +v -0.013986 0.038501 0.008411 +v -0.011046 0.036957 0.011450 +v -0.011047 0.038545 0.011448 +v -0.008537 0.036963 0.013364 +v -0.008496 0.038550 0.013392 +v -0.002947 0.036983 0.016672 +v -0.002878 0.038571 0.016709 +v 0.013746 0.037130 0.023734 +v 0.013938 0.038720 0.023795 +v 0.037574 0.039025 0.029285 +v 0.046338 0.037530 0.030907 +v 0.046465 0.039118 0.030931 +v 0.078986 0.037510 0.037079 +v 0.079048 0.039097 0.037089 +v 0.096579 0.037115 0.039068 +v 0.096638 0.038702 0.039071 +v 0.113295 0.036422 0.038596 +v 0.113353 0.038009 0.038589 +v 0.120528 0.036042 0.037401 +v 0.120556 0.037630 0.037395 +v 0.155914 0.035312 0.029873 +v 0.187091 0.030794 0.030373 +v 0.183969 0.032730 0.030376 +v 0.155980 0.033714 0.029874 +v 0.155924 0.033719 0.029871 +v 0.155859 0.035316 0.029870 +v 0.142154 0.034686 0.031014 +v 0.142131 0.036278 0.031020 +v 0.147699 0.034310 0.030040 +v 0.147670 0.035903 0.030043 +v 0.225461 0.026148 0.030231 +v 0.226038 0.027675 0.030248 +v 0.237984 0.024594 0.030694 +v 0.237672 0.026231 0.030681 +v 0.262513 0.023467 0.031675 +v 0.325210 0.019364 0.031994 +v 0.320644 0.019558 0.032025 +v 0.276893 0.022134 0.032058 +v 0.277321 0.020504 0.032065 +v 0.275634 0.022250 0.032024 +v 0.342000 0.018095 0.032025 +v 0.342000 0.017507 0.032025 +v 0.340997 0.019099 0.032016 +v 0.155924 -0.033719 0.029871 +v 0.155859 -0.035316 0.029870 +v 0.155914 -0.035312 0.029873 +v 0.152808 -0.035542 0.029841 +v 0.147080 -0.035943 0.030101 +v 0.121219 -0.037593 0.037253 +v 0.037043 -0.039019 0.029186 +v 0.103669 -0.038447 0.039212 +v 0.089106 -0.038912 0.038468 +v 0.076720 -0.039126 0.036700 +v 0.017810 -0.038768 0.024954 +v 0.007407 -0.038648 0.021460 +v 0.001483 -0.038597 0.018893 +v -0.011002 -0.038545 0.011488 +v -0.008361 -0.038551 0.013484 +v -0.013985 -0.036913 0.008413 +v -0.013986 -0.038501 0.008411 +v -0.017089 -0.036490 0.004007 +v -0.017307 -0.038061 0.003764 +v -0.019104 -0.037543 0.002345 +v -0.019394 -0.037408 0.002236 +v -0.019105 -0.035852 0.002344 +v -0.029077 -0.016000 -0.000500 +v -0.027488 -0.016000 -0.000065 +v -0.028241 -0.026028 -0.000270 +v -0.026649 -0.025923 0.000158 +v -0.027443 -0.029416 -0.000053 +v -0.026143 -0.028323 0.000291 +v -0.025091 -0.033428 0.000561 +v -0.024269 -0.031923 0.000767 +v -0.024210 -0.034376 0.000782 +v -0.021350 -0.034666 0.001475 +v -0.021568 -0.036396 0.001417 +v 0.226038 -0.027675 0.030248 +v 0.226537 -0.027616 0.030268 +v 0.278739 -0.021978 0.032088 +v 0.342000 -0.017507 0.032025 +v 0.342000 -0.018095 0.032025 +v 0.340997 -0.019099 0.032016 +v 0.310340 -0.019916 0.032095 +v 0.220317 -0.028387 0.030555 +v 0.204312 0.005308 0.067616 +v 0.209123 0.006348 0.066516 +v 0.213293 0.007250 0.065563 +v 0.216972 0.009027 0.064573 +v 0.217689 0.009876 0.064290 +v 0.217876 0.010397 0.064162 +v 0.217734 0.009929 0.064273 +v 0.217796 0.011065 0.064055 +v 0.217214 0.011939 0.064000 +v 0.215794 0.013006 0.064063 +v 0.211755 0.014766 0.064493 +v 0.186195 0.004009 0.071613 +v 0.078985 0.010410 0.098840 +v 0.082525 0.007973 0.097913 +v 0.084556 0.007379 0.097350 +v 0.091609 0.005317 0.095398 +v 0.093575 0.005155 0.094857 +v 0.100385 0.004595 0.092986 +v 0.107613 0.004000 0.091000 +v 0.078108 0.012890 0.098950 +v 0.078206 0.011729 0.098995 +v 0.078675 0.014210 0.098689 +v 0.100740 0.019984 0.091507 +v 0.097899 0.019683 0.092389 +v 0.087903 0.018622 0.095489 +v 0.087862 0.018607 0.095503 +v 0.083016 0.016905 0.097140 +v 0.081084 0.016226 0.097792 +v 0.177540 0.019930 0.070938 +v 0.239543 -0.006254 0.062251 +v 0.311781 -0.002259 0.052586 +v 0.311782 0.000000 0.052636 +v 0.294463 0.000000 0.054376 +v 0.005390 0.031066 0.077232 +v -0.012727 0.024500 0.048000 +v -0.012922 0.016858 0.049017 +v -0.028968 0.016000 0.002378 +v -0.028309 0.016335 0.006454 +v -0.027708 0.026632 0.004793 +v -0.025891 0.019268 0.014737 +v -0.027179 0.017397 0.010617 +v -0.025087 0.020741 0.017026 +v -0.023730 0.023718 0.020443 +v -0.022745 0.026268 0.022576 +v -0.022397 0.027006 0.023351 +v -0.022045 0.028696 0.023750 +v -0.022025 0.027418 0.024302 +v -0.021776 0.027500 0.025000 +v -0.017208 0.029918 0.036358 +v -0.013791 0.027500 0.045000 +v -0.011444 0.030908 0.049036 +v -0.013329 0.027311 0.046048 +v -0.012954 0.026742 0.046993 +v -0.012740 0.025913 0.047646 +v -0.012693 0.024995 0.047959 +v -0.011380 0.030919 0.049176 +v -0.005080 0.031386 0.061067 +v 0.002479 0.031225 0.073179 +v 0.001081 0.031302 0.071233 +v 0.010919 0.030652 0.083332 +v 0.016838 0.030281 0.088462 +v 0.029299 0.029770 0.096008 +v 0.036495 0.029611 0.098846 +v 0.043932 0.029529 0.100814 +v 0.059457 0.029570 0.102094 +v 0.051693 0.029518 0.101916 +v 0.062966 0.029617 0.101760 +v 0.067244 0.029675 0.101354 +v 0.079016 0.029904 0.098360 +v 0.074759 0.029821 0.099746 +v 0.069942 0.029727 0.100776 +v 0.080760 0.015865 0.099587 +v 0.083422 0.017226 0.098654 +v 0.083893 0.017467 0.098489 +v 0.088906 0.018914 0.096822 +v 0.095928 0.019924 0.094601 +v 0.102910 0.020223 0.092509 +v 0.165725 0.020519 0.075407 +v 0.169415 0.020394 0.074546 +v 0.173514 0.020405 0.073490 +v 0.182393 0.020144 0.071392 +v 0.154267 0.020355 0.078448 +v 0.079544 0.010416 0.100331 +v 0.069009 -0.000000 0.102905 +v 0.078615 0.011936 0.100520 +v 0.078567 0.013079 0.100461 +v 0.079213 0.014429 0.100173 +v 0.098249 0.004508 0.095207 +v 0.079615 -0.000000 0.100594 +v 0.094005 0.005136 0.096382 +v 0.090795 0.005612 0.097270 +v 0.085314 0.007090 0.098791 +v 0.081712 0.008699 0.099775 +v 0.080399 0.009698 0.100115 +v 0.079622 0.010289 0.100316 +v 0.103509 0.004260 0.093768 +v 0.132913 0.000000 0.086054 +v 0.150581 0.004069 0.081554 +v 0.202343 0.005180 0.069668 +v 0.200830 0.004943 0.070005 +v 0.189692 0.004166 0.072460 +v 0.239543 0.006254 0.062251 +v 0.210041 0.006494 0.067942 +v 0.239590 -0.000000 0.062601 +v 0.209163 0.006249 0.068149 +v 0.217453 0.012329 0.065524 +v 0.218097 0.011384 0.065581 +v 0.218192 0.010731 0.065683 +v 0.217993 0.010132 0.065827 +v 0.217960 0.010031 0.065851 +v 0.216933 0.008994 0.066223 +v 0.214266 0.007671 0.066945 +v 0.212076 0.015143 0.066002 +v 0.215676 0.013595 0.065615 +v 0.273621 0.006094 0.056689 +v 0.247266 0.009623 0.060371 +v 0.274318 0.006018 0.056607 +v 0.296318 0.003611 0.054020 +v 0.341004 -0.000000 0.051114 +v 0.341005 0.000223 0.051114 +v 0.335040 0.000590 0.051243 +v 0.328313 -0.000000 0.051517 +v 0.316992 0.001848 0.052180 +v 0.331440 -0.000819 0.051369 +v 0.341004 -0.000222 0.051114 +v 0.312341 -0.002208 0.052532 +v 0.316456 -0.001909 0.052282 +v 0.291330 -0.004102 0.054557 +v 0.274733 -0.006019 0.056608 +v 0.241181 -0.010532 0.061287 +v 0.267086 -0.006903 0.057553 +v 0.182909 -0.020044 0.071381 +v 0.174438 -0.021469 0.072962 +v 0.165725 -0.020519 0.075407 +v 0.067240 -0.029671 0.101355 +v 0.074076 -0.029802 0.099930 +v 0.059857 -0.029574 0.102078 +v 0.044155 -0.029528 0.100859 +v 0.048037 -0.029523 0.101396 +v 0.051954 -0.029519 0.101937 +v 0.055872 -0.029546 0.102007 +v 0.029481 -0.029766 0.096093 +v 0.036581 -0.029610 0.098874 +v 0.023500 -0.029969 0.092961 +v 0.011072 -0.030641 0.083481 +v 0.005829 -0.031036 0.077774 +v 0.016984 -0.030274 0.088573 +v 0.001438 -0.031298 0.071780 +v -0.004609 -0.031392 0.061892 +v -0.011422 -0.030889 0.049025 +v -0.010972 -0.030963 0.050002 +v -0.012727 -0.024500 0.048000 +v -0.012695 -0.025405 0.047860 +v -0.012795 -0.026222 0.047457 +v -0.013013 -0.026873 0.046835 +v -0.013343 -0.027323 0.046016 +v -0.013791 -0.027500 0.045000 +v -0.016637 -0.030034 0.037714 +v -0.021776 -0.027500 0.025000 +v -0.021951 -0.028721 0.024019 +v -0.022158 -0.027310 0.023950 +v -0.022276 -0.027139 0.023662 +v -0.022534 -0.026763 0.023031 +v -0.024093 -0.022860 0.019581 +v -0.026491 -0.018317 0.012888 +v -0.025171 -0.020577 0.016797 +v -0.027681 -0.016850 0.008843 +v -0.027734 -0.026617 0.004652 +v -0.028618 -0.016136 0.004987 +v -0.028968 -0.016000 0.002378 +v -0.013781 0.010820 0.048000 +v -0.013542 0.000000 0.049005 +v -0.014016 -0.002930 0.048000 +v 0.132634 -0.014495 0.085116 +v 0.132843 -0.007265 0.085819 +v -0.002955 -0.000000 0.067844 +v 0.205472 0.016484 0.065375 +v 0.201925 0.017134 0.065984 +v 0.195442 0.018321 0.067097 +v 0.342000 0.000401 0.049511 +v 0.342000 0.016498 0.037857 +v 0.342000 0.005802 0.048525 +v 0.342000 0.004161 0.049013 +v 0.342000 0.009226 0.046884 +v 0.342000 0.014849 0.041277 +v 0.342000 0.013630 0.042990 +v 0.342000 0.010942 0.045671 +v 0.342000 0.017082 0.035835 +v 0.342000 -0.012301 0.044461 +v 0.342000 -0.015732 0.039684 +v 0.342000 -0.003895 0.049076 +v 0.342000 -0.001820 0.049421 +v 0.342000 -0.016539 0.037741 +v 0.342000 -0.017387 0.034040 +v 0.342000 -0.013706 0.042895 +v 0.342000 -0.009327 0.046821 +v 0.342000 -0.007482 0.047834 +v 0.002973 0.033476 0.072964 +v -0.000887 0.037443 0.059037 +v 0.289505 0.007602 0.054008 +v -0.023599 0.034922 0.003138 +v 0.207298 0.016390 0.066690 +v 0.330127 0.001784 0.051376 +v 0.341005 0.000601 0.051107 +v 0.341005 0.000317 0.051112 +v 0.330109 0.001350 0.051407 +v 0.234842 0.013566 0.061617 +v 0.186167 0.019937 0.070536 +v 0.181579 0.022169 0.070762 +v 0.201076 0.018015 0.067585 +v -0.027508 0.029238 -0.000071 +v -0.026530 0.031012 0.003932 +v -0.018313 0.037723 0.008555 +v 0.128781 0.029611 0.082704 +v 0.289449 0.005972 0.054499 +v 0.260368 0.009792 0.057980 +v 0.181440 0.025220 0.067930 +v 0.206916 0.022428 0.061551 +v 0.162983 0.028702 0.069925 +v 0.234728 0.018536 0.057456 +v 0.234849 0.017179 0.059117 +v 0.254587 0.015805 0.055149 +v 0.320527 0.004641 0.051486 +v 0.300964 0.008607 0.051965 +v 0.280411 0.012053 0.052940 +v 0.275676 0.012749 0.053313 +v 0.260427 0.011728 0.057118 +v 0.260354 0.015001 0.054520 +v 0.259271 0.015160 0.054605 +v 0.008477 0.035117 0.077862 +v 0.010047 0.036454 0.076605 +v -0.002928 0.036005 0.060111 +v -0.013972 0.036071 0.035728 +v 0.029658 0.033928 0.094150 +v 0.030524 0.035309 0.092425 +v 0.042879 0.034991 0.096787 +v 0.042422 0.033621 0.098622 +v 0.101900 0.034396 0.087352 +v 0.076195 0.033592 0.097383 +v 0.075672 0.034848 0.095697 +v 0.069598 0.033533 0.099055 +v 0.062664 0.034814 0.098223 +v 0.055930 0.033503 0.100295 +v 0.055974 0.034840 0.098449 +v 0.018163 0.034443 0.087100 +v 0.019408 0.035812 0.085573 +v -0.009255 0.038534 0.028938 +v 0.010994 0.037031 0.074279 +v 0.062554 0.035424 0.096193 +v 0.077509 0.035466 0.093049 +v 0.102326 0.033232 0.088941 +v 0.155064 0.027864 0.075046 +v 0.208340 0.019592 0.064703 +v -0.016027 0.033209 0.036577 +v -0.004385 0.033830 0.060844 +v 0.007356 0.033146 0.078696 +v 0.011998 0.032793 0.083598 +v 0.017275 0.032461 0.088118 +v 0.029040 0.031952 0.095312 +v 0.035491 0.031784 0.097957 +v 0.042093 0.031677 0.099874 +v 0.055893 0.031618 0.101575 +v 0.048984 0.031623 0.101098 +v 0.069846 0.031728 0.100299 +v 0.062930 0.031655 0.101307 +v 0.089662 0.031951 0.094218 +v 0.076574 0.031831 0.098586 +v 0.113901 0.034224 0.081985 +v 0.239384 0.024511 0.042037 +v 0.340998 0.017140 0.040430 +v 0.253232 0.024347 0.033770 +v 0.320641 0.019271 0.035080 +v 0.340998 0.017557 0.039270 +v 0.340997 0.018581 0.036422 +v 0.340997 0.019094 0.032458 +v 0.340999 0.014892 0.043965 +v 0.320596 0.010931 0.048537 +v 0.341001 0.012008 0.046846 +v 0.341001 0.012108 0.046780 +v 0.341003 0.006483 0.049856 +v 0.341002 0.008616 0.049057 +v 0.341004 0.004675 0.050532 +v 0.298108 0.012022 0.050064 +v 0.275678 0.013709 0.052370 +v 0.253257 0.019219 0.050504 +v 0.208266 0.024276 0.056653 +v 0.162941 0.030415 0.063563 +v -0.004933 0.038542 0.034565 +v -0.007506 0.038545 0.024582 +v -0.004939 0.038559 0.020362 +v 0.010904 0.038686 0.032399 +v 0.235444 0.021756 0.050809 +v 0.275695 0.019986 0.043043 +v 0.167122 0.031551 0.055711 +v 0.298137 0.015832 0.046122 +v 0.162875 -0.033157 0.049554 +v 0.341005 -0.002158 0.050993 +v 0.310612 -0.006651 0.051729 +v 0.280319 -0.012067 0.052946 +v 0.275676 -0.012746 0.053322 +v 0.275678 -0.013680 0.052398 +v 0.172168 -0.027456 0.067923 +v 0.162983 -0.028695 0.069927 +v 0.162942 -0.030396 0.063640 +v 0.162832 -0.034591 0.035557 +v 0.010904 -0.038686 0.032408 +v -0.007392 -0.038545 0.024591 +v -0.006863 -0.038515 0.036935 +v 0.010132 -0.037104 0.073166 +v 0.068824 -0.035423 0.095342 +v 0.053833 -0.035468 0.096296 +v 0.091273 -0.035356 0.088658 +v 0.140268 -0.031761 0.074540 +v 0.108839 -0.034579 0.083422 +v 0.201062 -0.023269 0.062530 +v 0.208266 -0.024249 0.056718 +v 0.228899 -0.019342 0.058214 +v 0.230793 -0.021535 0.053473 +v 0.253257 -0.019187 0.050560 +v 0.253269 -0.015991 0.055274 +v 0.275694 -0.017256 0.048089 +v 0.256591 -0.015534 0.054873 +v 0.260355 -0.014985 0.054562 +v 0.267936 -0.015441 0.052185 +v 0.298108 -0.011991 0.050088 +v 0.320595 -0.010900 0.048559 +v 0.323588 -0.004033 0.051406 +v 0.341004 -0.005983 0.050151 +v 0.341004 -0.005345 0.050292 +v 0.341005 -0.002239 0.050975 +v 0.341002 -0.009733 0.048444 +v 0.340999 -0.015549 0.043097 +v 0.320623 -0.014859 0.044909 +v 0.341000 -0.012926 0.046069 +v 0.341001 -0.011001 0.047501 +v 0.340998 -0.017322 0.040051 +v 0.340997 -0.018640 0.036166 +v 0.239483 -0.024513 0.041981 +v 0.230768 -0.023916 0.047824 +v 0.208231 -0.026402 0.050656 +v -0.016027 -0.033209 0.036577 +v -0.018313 -0.037723 0.008555 +v -0.023599 -0.034922 0.003138 +v -0.026530 -0.031012 0.003933 +v -0.026903 -0.030662 0.000091 +v 0.208313 -0.017770 0.065900 +v 0.316490 -0.002812 0.052144 +v 0.289449 -0.005972 0.054499 +v 0.260368 -0.009792 0.057980 +v 0.234842 -0.013566 0.061617 +v 0.154860 -0.029096 0.073463 +v 0.208259 -0.021121 0.063150 +v 0.181440 -0.025220 0.067930 +v 0.181570 -0.023859 0.069520 +v 0.234890 -0.015493 0.060542 +v 0.330127 -0.001784 0.051376 +v 0.316525 -0.003730 0.052007 +v 0.289505 -0.007602 0.054008 +v 0.260427 -0.011728 0.057118 +v -0.000887 -0.037443 0.059037 +v 0.010047 -0.036454 0.076605 +v 0.019408 -0.035812 0.085573 +v 0.030524 -0.035309 0.092425 +v 0.042880 -0.034991 0.096788 +v 0.055974 -0.034840 0.098449 +v 0.075672 -0.034848 0.095697 +v 0.101900 -0.034396 0.087352 +v 0.102326 -0.033232 0.088941 +v 0.076195 -0.033592 0.097383 +v 0.069598 -0.033533 0.099055 +v 0.055930 -0.033503 0.100295 +v 0.042422 -0.033621 0.098622 +v 0.029658 -0.033928 0.094150 +v 0.018163 -0.034443 0.087100 +v 0.008477 -0.035117 0.077863 +v -0.002928 -0.036005 0.060111 +v -0.013972 -0.036071 0.035728 +v -0.004385 -0.033830 0.060845 +v 0.007356 -0.033146 0.078696 +v 0.017275 -0.032461 0.088118 +v 0.011998 -0.032793 0.083598 +v 0.022929 -0.032180 0.092005 +v 0.029040 -0.031952 0.095312 +v 0.042093 -0.031677 0.099874 +v 0.035491 -0.031784 0.097957 +v 0.055893 -0.031618 0.101575 +v 0.048985 -0.031623 0.101098 +v 0.069846 -0.031728 0.100299 +v 0.062930 -0.031655 0.101307 +v 0.076574 -0.031831 0.098586 +v 0.102609 -0.031631 0.090131 +v 0.342000 -0.008380 0.048049 +v 0.342000 -0.014518 0.042808 +v 0.342000 -0.016568 0.039279 +v 0.342000 0.017631 0.036075 +v 0.342000 0.016281 0.039902 +v 0.342000 0.014098 0.043350 +v 0.342000 -0.011745 0.045775 +v 0.342000 0.011366 0.046059 +v 0.342000 0.011212 0.046212 +v 0.342000 -0.005056 0.049336 +v 0.342000 -0.004584 0.049519 +v 0.342000 0.007765 0.048356 +v 0.342000 -0.017650 0.035991 +v 0.342000 0.003938 0.049676 +v 0.342000 0.000567 0.050103 +v 0.262174 0.023501 0.031663 +v 0.154007 0.035454 0.029847 +v 0.147335 0.034335 0.030075 +v 0.147307 0.035928 0.030078 +v 0.141847 0.036298 0.031097 +v 0.112842 0.036445 0.038649 +v 0.112900 0.038031 0.038642 +v 0.096342 0.037123 0.039056 +v 0.096401 0.038709 0.039059 +v 0.037085 0.039019 0.029194 +v 0.005100 0.037039 0.020513 +v 0.005173 0.038627 0.020544 +v -0.011092 0.036957 0.011410 +v -0.011089 0.038545 0.011413 +v -0.023467 0.034929 0.000957 +v -0.022070 0.036086 0.001292 +v -0.021217 0.034753 0.001512 +v -0.017025 0.038123 0.004082 +v -0.027523 0.029196 -0.000075 +v -0.025948 0.028884 0.000342 +v -0.025535 0.032805 0.000447 +v -0.023982 0.032286 0.000838 +v -0.025329 0.033138 0.000501 +v 0.282900 -0.020049 0.032138 +v 0.318313 -0.019585 0.032035 +v 0.153599 -0.033887 0.029896 +v 0.147135 -0.035940 0.030095 +v 0.148997 -0.034221 0.029944 +v 0.144275 -0.036133 0.030630 +v 0.142003 -0.036287 0.031054 +v 0.144000 -0.034561 0.030574 +v 0.105412 -0.038369 0.039115 +v 0.112740 -0.038039 0.038660 +v 0.113195 -0.036420 0.038505 +v 0.113137 -0.038018 0.038595 +v 0.116890 -0.036238 0.038085 +v 0.119551 -0.037681 0.037530 +v 0.108659 -0.036643 0.039021 +v 0.103916 -0.038437 0.039208 +v 0.088770 -0.037332 0.038431 +v 0.018061 -0.038771 0.025024 +v 0.023771 -0.037259 0.026480 +v 0.006459 -0.037051 0.021079 +v -0.005880 -0.036971 0.015042 +v -0.008181 -0.038551 0.013605 +v -0.009566 -0.036960 0.012629 +v -0.010511 -0.036955 0.011805 +v -0.018784 -0.035978 0.002533 +v -0.018994 -0.037575 0.002432 +v -0.016494 -0.038220 0.004795 +v -0.016210 -0.038275 0.005156 +v -0.012664 -0.036945 0.009928 +v -0.018981 -0.035901 0.002417 +v -0.019412 -0.037403 0.002225 +v -0.021308 -0.036546 0.001487 +v -0.023660 -0.032662 0.000916 +v -0.024177 -0.034408 0.000790 +v -0.026910 -0.030640 0.000089 +v -0.026883 -0.030702 0.000096 +v -0.025511 -0.032789 0.000452 +v -0.025794 -0.029272 0.000382 +v 0.027483 0.019682 -0.013158 +v 0.030994 0.021543 -0.010090 +v 0.034808 0.022779 -0.007293 +v 0.036315 0.023073 -0.006321 +v 0.040203 0.023364 -0.004120 +v 0.043792 0.023045 -0.002442 +v 0.047638 0.022048 -0.000981 +v 0.051384 0.020331 0.000134 +v 0.054769 0.017968 0.000898 +v 0.055823 0.016941 0.001077 +v 0.057189 0.015609 0.001309 +v 0.062581 0.004560 0.001829 +v 0.062430 0.005303 0.001823 +v 0.061130 0.009372 0.001745 +v 0.059692 0.012193 0.001620 +v 0.063000 0.000096 0.001844 +v 0.062581 -0.004560 0.001829 +v 0.061413 -0.008674 0.001765 +v 0.059961 -0.011732 0.001646 +v 0.057550 -0.015192 0.001361 +v 0.055156 -0.017636 0.000971 +v 0.051818 -0.020076 0.000244 +v 0.048927 -0.021548 -0.000565 +v 0.045077 -0.022790 -0.001917 +v 0.044774 -0.022839 -0.002046 +v 0.042231 -0.023253 -0.003133 +v 0.038190 -0.023296 -0.005207 +v 0.035478 -0.022923 -0.006852 +v 0.031477 -0.021741 -0.009706 +v 0.023985 -0.017828 -0.016700 +v 0.015000 -0.016000 -0.025143 +v 0.015962 -0.016020 -0.024512 +v 0.019269 -0.016400 -0.021869 +v 0.015000 0.016000 -0.025143 +v 0.018634 0.016289 -0.022442 +v 0.023566 0.017655 -0.017159 +v 0.267514 0.016951 0.017281 +v 0.040825 0.037583 0.006232 +v 0.029084 0.036535 -0.001435 +v -0.006346 0.030850 -0.024358 +v -0.005407 0.032269 -0.022692 +v -0.002665 0.031582 -0.023613 +v -0.008118 0.027127 -0.026848 +v -0.007264 0.029112 -0.025766 +v -0.003889 0.028426 -0.026696 +v -0.014829 0.038015 -0.000497 +v -0.014895 0.038232 0.002280 +v -0.021788 0.036204 0.000122 +v -0.019531 0.037262 -0.000126 +v -0.023838 0.034709 0.000396 +v -0.023379 0.034064 -0.005931 +v -0.025168 0.032121 -0.005975 +v -0.026535 0.029920 -0.005918 +v -0.028169 0.025628 -0.003183 +v -0.027523 0.029196 -0.000075 +v 0.340993 0.001134 0.012941 +v 0.340991 0.000883 0.012925 +v 0.331223 0.003880 0.013166 +v 0.323918 0.004475 0.013299 +v 0.318584 0.007208 0.013784 +v 0.341000 0.001906 0.012990 +v 0.337824 0.003407 0.013162 +v 0.331425 0.005525 0.013529 +v 0.333259 0.005483 0.013686 +v 0.331513 0.006277 0.013887 +v 0.230181 0.025966 0.024424 +v 0.216668 0.028446 0.026785 +v 0.136482 0.036579 0.028581 +v 0.138374 0.035833 0.024730 +v 0.138408 0.036453 0.028709 +v 0.250094 0.024040 0.025170 +v 0.267879 0.019550 0.019789 +v 0.138521 0.031072 0.017866 +v 0.112789 0.031683 0.015456 +v 0.055111 0.027804 0.002892 +v 0.049624 0.031757 0.002610 +v 0.046705 0.027432 -0.000303 +v 0.077325 0.028216 0.008567 +v 0.074272 0.032088 0.009671 +v 0.065328 0.028076 0.005888 +v 0.111545 0.028065 0.013477 +v 0.038189 0.030963 -0.002938 +v 0.032974 0.030228 -0.006363 +v 0.029030 0.025057 -0.011070 +v 0.028203 0.029151 -0.010237 +v 0.023971 0.027670 -0.014493 +v 0.033889 0.026140 -0.007306 +v 0.020812 0.021718 -0.019824 +v 0.011804 0.023974 -0.025988 +v 0.013568 0.020349 -0.025792 +v 0.015398 0.024511 -0.023725 +v 0.017447 0.020967 -0.023086 +v -0.005036 0.024409 -0.028569 +v -0.000915 0.023946 -0.028988 +v -0.000257 0.019806 -0.029592 +v 0.003433 0.023680 -0.028721 +v 0.004512 0.019741 -0.029147 +v 0.009369 0.019936 -0.027794 +v 0.007762 0.023683 -0.027700 +v 0.004829 0.019754 -0.029058 +v 0.024462 0.023408 -0.015509 +v -0.013852 0.021165 -0.026127 +v -0.012604 0.025669 -0.025926 +v -0.008874 0.024984 -0.027564 +v -0.009309 0.020535 -0.028144 +v -0.017895 0.021896 -0.023375 +v -0.019252 0.027194 -0.020842 +v -0.021083 0.022586 -0.020309 +v -0.015139 0.026208 -0.024369 +v -0.027414 0.024886 -0.008044 +v -0.026000 0.024122 -0.012407 +v -0.024843 0.028981 -0.012040 +v -0.023857 0.023323 -0.016588 +v -0.022339 0.028061 -0.016912 +v -0.004794 0.020082 -0.029250 +v 0.039627 0.026899 -0.003756 +v 0.048536 0.035366 0.005399 +v 0.042501 0.035090 0.002664 +v 0.036718 0.034622 -0.000574 +v 0.007226 0.027338 -0.026056 +v 0.010718 0.027546 -0.024577 +v 0.009249 0.030485 -0.022310 +v 0.013831 0.028043 -0.022590 +v 0.015647 0.032365 -0.016356 +v 0.019177 0.034055 -0.011430 +v 0.026298 0.032797 -0.008640 +v -0.023482 0.031247 -0.011896 +v -0.021719 0.033259 -0.011552 +v -0.021259 0.035631 -0.005788 +v -0.019643 0.034896 -0.011021 +v -0.018931 0.036746 -0.005554 +v -0.017376 0.036080 -0.010337 +v -0.000282 0.027840 -0.027110 +v 0.003489 0.027447 -0.026916 +v 0.003357 0.030527 -0.024096 +v -0.007307 0.035159 -0.016296 +v -0.009954 0.033592 -0.020021 +v -0.011439 0.032229 -0.021559 +v -0.012844 0.030487 -0.022838 +v -0.014096 0.028445 -0.023788 +v -0.013008 0.034563 -0.017191 +v -0.014847 0.033258 -0.018516 +v -0.017441 0.034099 -0.015166 +v -0.016561 0.031534 -0.019604 +v -0.019376 0.032407 -0.016011 +v -0.018053 0.029474 -0.020390 +v -0.021036 0.030354 -0.016601 +v -0.014796 0.037909 -0.001852 +v -0.013921 0.037463 -0.005837 +v -0.012411 0.036894 -0.009487 +v -0.004382 0.034251 -0.018494 +v -0.000841 0.033305 -0.020098 +v 0.280665 0.017472 0.018604 +v 0.280951 0.019443 0.021311 +v 0.293425 0.015133 0.017269 +v 0.340996 0.001388 0.012957 +v 0.331324 0.004708 0.013322 +v 0.318942 0.010169 0.015062 +v 0.318766 0.008725 0.014337 +v 0.306364 0.014075 0.017191 +v 0.306135 0.012227 0.015747 +v 0.293687 0.017135 0.019444 +v 0.324583 0.009260 0.014929 +v 0.327074 0.008261 0.014448 +v 0.327734 0.007996 0.014321 +v 0.268957 0.022355 0.026167 +v 0.295953 0.018198 0.021462 +v 0.112609 0.034752 0.018401 +v 0.285993 0.011062 0.014732 +v 0.317707 0.005782 0.013435 +v 0.305892 0.010164 0.014634 +v 0.298558 0.009104 0.014194 +v 0.135151 -0.027662 0.015615 +v 0.118408 -0.024296 0.012985 +v 0.021433 -0.020539 -0.019258 +v 0.010602 -0.016000 -0.027416 +v 0.011010 -0.016000 -0.027205 +v 0.010940 -0.019426 -0.027166 +v 0.050736 -0.024908 0.000743 +v 0.069227 -0.008727 0.003597 +v 0.050736 0.024908 0.000743 +v -0.028091 0.016000 -0.007837 +v -0.028631 0.016000 -0.005366 +v -0.026470 0.016000 -0.012436 +v -0.023921 0.016000 -0.017007 +v -0.020882 0.016000 -0.020757 +v -0.016955 0.016000 -0.024173 +v -0.012889 0.016000 -0.026637 +v -0.008209 0.016000 -0.028465 +v -0.003516 0.016000 -0.029404 +v 0.001268 0.016000 -0.029548 +v 0.004886 0.016000 -0.029042 +v 0.005986 0.016000 -0.028888 +v 0.010602 0.016000 -0.027416 +v 0.025784 0.021344 -0.014488 +v 0.030802 0.022250 -0.010128 +v 0.036586 0.023190 -0.006141 +v 0.043208 0.024098 -0.002518 +v 0.059235 0.025554 0.003647 +v 0.069054 0.017402 0.004574 +v 0.059537 -0.017112 0.002188 +v 0.043208 -0.024098 -0.002518 +v 0.036586 -0.023190 -0.006141 +v 0.030802 -0.022250 -0.010128 +v 0.016541 -0.019896 -0.023869 +v 0.004848 -0.019119 -0.029091 +v 0.005986 -0.016000 -0.028888 +v 0.001268 -0.016000 -0.029548 +v 0.002134 -0.019744 -0.029474 +v -0.003516 -0.016000 -0.029404 +v -0.002530 -0.019922 -0.029513 +v -0.007929 -0.016000 -0.028521 +v -0.007368 -0.020320 -0.028719 +v -0.007892 -0.020383 -0.028539 +v -0.008209 -0.016000 -0.028465 +v -0.012889 -0.016000 -0.026637 +v -0.011504 -0.020814 -0.027295 +v -0.016955 -0.016000 -0.024173 +v -0.013842 -0.021181 -0.026035 +v -0.015381 -0.021423 -0.025207 +v -0.018903 -0.022102 -0.022508 +v -0.019054 -0.022137 -0.022347 +v -0.020882 -0.016000 -0.020757 +v -0.023536 -0.016000 -0.017482 +v -0.022079 -0.022827 -0.019118 +v -0.023921 -0.016000 -0.017007 +v -0.026470 -0.016000 -0.012436 +v -0.024551 -0.023553 -0.015409 +v -0.028091 -0.016000 -0.007837 +v -0.026571 -0.024391 -0.010909 +v -0.027790 -0.025174 -0.006235 +v -0.028567 -0.016000 -0.005658 +v -0.027842 -0.025257 -0.005658 +v -0.028631 -0.016000 -0.005366 +v -0.028249 -0.025918 -0.001104 +v 0.011165 -0.020082 -0.027041 +v 0.007935 -0.019871 -0.028217 +v 0.006825 -0.019799 -0.028622 +v 0.015410 -0.020613 -0.024625 +v 0.018906 -0.021262 -0.021797 +v 0.025665 -0.023899 -0.014263 +v 0.029645 -0.025218 -0.010548 +v 0.034684 -0.026272 -0.006763 +v 0.040539 -0.026986 -0.003260 +v 0.047543 -0.027478 0.000053 +v 0.055316 -0.027815 0.002961 +v 0.065320 -0.028076 0.005886 +v 0.068766 -0.025971 0.006196 +v 0.074563 -0.028183 0.007946 +v 0.079389 -0.026096 0.008395 +v 0.077469 -0.028216 0.008594 +v 0.091977 -0.028198 0.011028 +v 0.189437 -0.018698 0.015469 +v 0.340991 -0.000884 0.012925 +v 0.118408 0.024296 0.012985 +v 0.068766 0.025971 0.006196 +v 0.091622 0.000000 0.006896 +v 0.091571 0.008708 0.007270 +v 0.104386 0.016946 0.009851 +v 0.118628 0.016320 0.011043 +v 0.151182 -0.014607 0.012731 +v 0.091571 -0.008708 0.007270 +v 0.079824 -0.008778 0.005578 +v 0.091430 -0.038253 0.023624 +v 0.134958 -0.036668 0.028842 +v 0.005535 -0.038627 0.017852 +v 0.139061 -0.036366 0.028686 +v 0.127254 -0.037039 0.027765 +v 0.039603 -0.038650 0.010433 +v 0.037249 -0.038559 0.009058 +v 0.021571 -0.037071 -0.002872 +v 0.010504 -0.033122 -0.017206 +v -0.003807 -0.034084 -0.018829 +v 0.005618 -0.032404 -0.020293 +v -0.012086 -0.036780 -0.010095 +v -0.009478 -0.035876 -0.014011 +v -0.014905 -0.038223 0.002142 +v 0.008469 -0.038641 0.012557 +v 0.342000 -0.009191 0.017097 +v 0.342000 -0.004980 0.015213 +v 0.342000 -0.001308 0.014539 +v 0.342000 -0.005812 0.015483 +v 0.342000 -0.010947 0.018335 +v 0.342000 -0.016484 0.026102 +v 0.342000 -0.014853 0.022731 +v 0.342000 -0.013601 0.020975 +v 0.342000 -0.017082 0.028167 +v 0.342000 0.016556 0.026310 +v 0.342000 0.017387 0.029962 +v 0.342000 0.013739 0.021147 +v 0.342000 0.015732 0.024317 +v 0.342000 0.012301 0.019540 +v 0.342000 0.009372 0.017210 +v 0.342000 0.007482 0.016169 +v 0.342000 0.003945 0.014940 +v 0.342000 0.001827 0.014586 +v 0.342000 0.001806 0.013990 +v 0.342000 -0.001806 0.013990 +v 0.341000 -0.001906 0.012990 +v 0.340998 -0.001646 0.012974 +v 0.340996 -0.001388 0.012957 +v 0.341000 -0.004962 0.013607 +v 0.337535 -0.003544 0.013182 +v 0.341000 -0.005612 0.013737 +v 0.331513 -0.006279 0.013882 +v 0.327074 -0.008261 0.014448 +v 0.319098 -0.011461 0.015988 +v 0.286131 -0.019918 0.023430 +v 0.312573 -0.018825 0.025679 +v 0.268995 -0.022350 0.026161 +v 0.242681 -0.025622 0.028953 +v 0.283501 -0.021563 0.030687 +v 0.340997 -0.017995 0.025915 +v 0.340997 -0.018764 0.028436 +v 0.340998 -0.015458 0.020778 +v 0.327133 -0.016628 0.022100 +v 0.327138 -0.018127 0.025290 +v 0.340998 -0.017554 0.024472 +v 0.340999 -0.015134 0.020419 +v 0.340999 -0.012726 0.017753 +v 0.341000 -0.009403 0.015369 +v 0.342000 -0.017657 0.028041 +v 0.342000 -0.016356 0.024258 +v 0.342000 0.017882 0.029233 +v 0.342000 0.009360 0.016508 +v 0.342000 0.012535 0.018945 +v 0.342000 0.015098 0.022022 +v 0.342000 0.016928 0.025605 +v 0.342000 0.017881 0.029229 +v 0.342000 -0.014352 0.021010 +v 0.342000 -0.014246 0.020838 +v 0.342000 -0.011434 0.017969 +v 0.342000 0.005717 0.014826 +v 0.342000 0.005538 0.014788 +v 0.342000 -0.008301 0.015915 +v 0.342000 -0.004705 0.014540 +v 0.342000 -0.004543 0.014479 +v 0.341000 0.009090 0.015197 +v 0.340999 0.012483 0.017539 +v 0.341000 0.005835 0.013850 +v 0.341000 0.005430 0.013683 +v 0.327138 0.018127 0.025290 +v 0.340998 0.016859 0.023179 +v 0.340998 0.015265 0.020516 +v 0.340997 0.018785 0.029085 +v 0.312575 0.019620 0.029195 +v 0.340997 0.018662 0.027936 +v 0.340997 0.018036 0.026073 +v 0.340998 0.017325 0.023958 +v 0.283502 0.021129 0.027020 +v 0.312568 0.017474 0.022419 +v -0.018931 -0.036746 -0.005554 +v -0.006346 -0.030850 -0.024358 +v -0.007264 -0.029112 -0.025766 +v -0.003889 -0.028426 -0.026696 +v -0.023379 -0.034064 -0.005931 +v -0.021719 -0.033259 -0.011552 +v -0.019643 -0.034896 -0.011021 +v -0.012844 -0.030487 -0.022838 +v 0.230172 -0.025887 0.024236 +v 0.216668 -0.028446 0.026785 +v 0.138373 -0.035833 0.024730 +v -0.025168 -0.032121 -0.005975 +v 0.331324 -0.004708 0.013322 +v -0.026883 -0.030702 0.000096 +v -0.026535 -0.029920 -0.005918 +v -0.023838 -0.034709 0.000396 +v -0.021788 -0.036204 0.000122 +v -0.021308 -0.036546 0.001487 +v 0.241787 -0.020779 0.018747 +v 0.250395 -0.024025 0.025214 +v 0.267879 -0.019550 0.019789 +v 0.138520 -0.031072 0.017866 +v 0.112789 -0.031683 0.015456 +v 0.074272 -0.032088 0.009671 +v 0.049624 -0.031757 0.002610 +v 0.061734 -0.032056 0.006655 +v 0.038189 -0.030963 -0.002938 +v 0.032974 -0.030228 -0.006363 +v 0.028203 -0.029151 -0.010237 +v 0.015398 -0.024511 -0.023725 +v 0.011804 -0.023974 -0.025988 +v 0.018496 -0.025225 -0.021039 +v -0.000915 -0.023946 -0.028988 +v -0.005037 -0.024409 -0.028568 +v 0.003433 -0.023680 -0.028721 +v 0.007762 -0.023683 -0.027700 +v -0.012604 -0.025669 -0.025926 +v -0.008874 -0.024984 -0.027564 +v -0.019252 -0.027194 -0.020842 +v -0.022339 -0.028061 -0.016912 +v -0.015139 -0.026208 -0.024369 +v -0.024843 -0.028981 -0.012040 +v -0.014096 -0.028445 -0.023787 +v -0.008118 -0.027127 -0.026848 +v -0.023482 -0.031247 -0.011896 +v -0.021036 -0.030354 -0.016601 +v -0.018053 -0.029474 -0.020390 +v 0.047097 -0.037793 0.009144 +v -0.017441 -0.034099 -0.015166 +v -0.019376 -0.032407 -0.016011 +v -0.014847 -0.033258 -0.018516 +v -0.017376 -0.036080 -0.010337 +v -0.013008 -0.034563 -0.017191 +v -0.009954 -0.033592 -0.020021 +v -0.016561 -0.031534 -0.019604 +v -0.011439 -0.032229 -0.021559 +v -0.005407 -0.032269 -0.022692 +v 0.029084 -0.036535 -0.001435 +v 0.023829 -0.035513 -0.006190 +v 0.009249 -0.030485 -0.022310 +v 0.013969 -0.031581 -0.018574 +v 0.003357 -0.030527 -0.024096 +v -0.021259 -0.035631 -0.005788 +v -0.002665 -0.031582 -0.023613 +v 0.042501 -0.035090 0.002664 +v 0.031286 -0.033887 -0.004344 +v 0.021881 -0.031288 -0.013369 +v 0.016523 -0.028763 -0.020200 +v 0.013831 -0.028043 -0.022590 +v 0.010718 -0.027546 -0.024577 +v 0.007226 -0.027338 -0.026056 +v 0.003489 -0.027447 -0.026916 +v -0.000282 -0.027840 -0.027110 +v 0.331425 -0.005526 0.013529 +v 0.280951 -0.019443 0.021311 +v 0.280665 -0.017472 0.018605 +v 0.318942 -0.010169 0.015062 +v 0.164476 -0.032419 0.022540 +v 0.060955 -0.035550 0.009564 +v 0.267514 -0.016951 0.017281 +v 0.113573 0.037799 0.034445 +v 0.008469 0.038640 0.012548 +v 0.009731 0.040315 0.033342 +v 0.010073 0.040320 0.033196 +v 0.011202 0.040339 0.033435 +v 0.010236 0.040323 0.033708 +v 0.011339 0.040341 0.033753 +v 0.010486 0.040328 0.031239 +v 0.010290 0.040325 0.030943 +v 0.009715 0.040315 0.032098 +v 0.012111 0.040353 0.033139 +v 0.011974 0.040351 0.032576 +v 0.009347 0.040309 0.032433 +v 0.009544 0.040312 0.031589 +v 0.012271 0.040356 0.032799 +v 0.012336 0.040357 0.032178 +v 0.011724 0.040348 0.031122 +v 0.011616 0.040346 0.031478 +v 0.010905 0.040334 0.030838 +v 0.010906 0.032683 0.033634 +v 0.011861 0.032698 0.033279 +v 0.012267 0.032705 0.032344 +v 0.012012 0.032701 0.031561 +v 0.011133 0.032687 0.031046 +v 0.010152 0.032671 0.031323 +v 0.009671 0.032663 0.032431 +v 0.010138 0.032671 0.033336 +v 0.010893 0.032883 0.033833 +v 0.011134 0.032886 0.033825 +v 0.011041 0.038686 0.033827 +v 0.011995 0.032900 0.033424 +v 0.011902 0.038700 0.033425 +v 0.012383 0.032907 0.032820 +v 0.012290 0.038706 0.032821 +v 0.012464 0.032908 0.032345 +v 0.012370 0.038707 0.032347 +v 0.012297 0.038706 0.031871 +v 0.012169 0.032904 0.031442 +v 0.012076 0.038703 0.031444 +v 0.011824 0.032898 0.031107 +v 0.011731 0.038697 0.031108 +v 0.011523 0.038694 0.030986 +v 0.011155 0.032887 0.030847 +v 0.011062 0.038687 0.030849 +v 0.010674 0.032880 0.030863 +v 0.010581 0.038679 0.030865 +v 0.010023 0.032869 0.031167 +v 0.009848 0.032866 0.031333 +v 0.009755 0.038666 0.031334 +v 0.009588 0.032862 0.031738 +v 0.009495 0.038661 0.031739 +v 0.009468 0.032860 0.032446 +v 0.009375 0.038659 0.032447 +v 0.009580 0.032862 0.032914 +v 0.009487 0.038661 0.032915 +v 0.010007 0.032868 0.033491 +v 0.009914 0.038668 0.033492 +v 0.010422 0.032875 0.033734 +v 0.010329 0.038674 0.033735 +v 0.009956 0.038668 0.035036 +v 0.008066 0.038638 0.031830 +v 0.008825 0.038650 0.034320 +v 0.008262 0.038641 0.033483 +v 0.011620 0.038695 0.035086 +v 0.009647 0.038664 0.029763 +v 0.010620 0.038680 0.029498 +v 0.008828 0.038651 0.030350 +v 0.013640 0.038728 0.033008 +v 0.013233 0.038721 0.033930 +v 0.013543 0.038726 0.031346 +v 0.011944 0.038701 0.029696 +v 0.012248 0.038706 0.029842 +v 0.012796 0.038715 0.030235 +v 0.009931 0.038998 0.035029 +v 0.009291 0.038987 0.034712 +v 0.008750 0.038979 0.034246 +v 0.008342 0.038972 0.033660 +v 0.008240 0.038971 0.033444 +v 0.008066 0.038968 0.031806 +v 0.008120 0.038969 0.031574 +v 0.008667 0.038978 0.030523 +v 0.009001 0.038984 0.030181 +v 0.009595 0.038993 0.029785 +v 0.010743 0.039012 0.029489 +v 0.010981 0.039016 0.029489 +v 0.011911 0.039031 0.029685 +v 0.012725 0.039044 0.030177 +v 0.013059 0.039049 0.030517 +v 0.013609 0.039058 0.031567 +v 0.013640 0.039058 0.032984 +v 0.013494 0.039055 0.033438 +v 0.013273 0.039052 0.033861 +v 0.012241 0.039035 0.034832 +v 0.011577 0.039024 0.035096 +v 0.010745 0.039217 0.029612 +v 0.009257 0.039193 0.030132 +v 0.009078 0.039191 0.030274 +v 0.008305 0.039178 0.031389 +v 0.008235 0.039177 0.031606 +v 0.013540 0.039262 0.031822 +v 0.013488 0.039261 0.031600 +v 0.012446 0.039626 0.030489 +v 0.012595 0.039628 0.030629 +v 0.013085 0.039809 0.031908 +v 0.013121 0.039810 0.032477 +v 0.012607 0.040110 0.033074 +v 0.012539 0.040109 0.033218 +v 0.012109 0.039434 0.034604 +v 0.011915 0.039431 0.034701 +v 0.010010 0.039400 0.034783 +v 0.010075 0.040069 0.034080 +v 0.009932 0.040067 0.034009 +v 0.009429 0.039391 0.034495 +v 0.008945 0.040051 0.032459 +v 0.009011 0.040052 0.031826 +v 0.008507 0.039562 0.031684 +v 0.008364 0.039375 0.031643 +v 0.008570 0.039563 0.031490 +v 0.010973 0.039221 0.029612 +v 0.010083 0.039671 0.033196 +v 0.011213 0.039689 0.033435 +v 0.009725 0.039665 0.032098 +v 0.010496 0.039678 0.031239 +v 0.011626 0.039696 0.031478 +v 0.011984 0.039701 0.032575 +v -0.008324 0.040203 0.025516 +v -0.007194 0.040214 0.025755 +v -0.008381 0.040202 0.025907 +v -0.007550 0.040209 0.026157 +v -0.007057 0.040214 0.026073 +v -0.007909 0.040210 0.023559 +v -0.008105 0.040209 0.023263 +v -0.008681 0.040201 0.024418 +v -0.006285 0.040223 0.025459 +v -0.006422 0.040223 0.024896 +v -0.009049 0.040197 0.024752 +v -0.008784 0.040201 0.023802 +v -0.006436 0.040221 0.025660 +v -0.006671 0.040223 0.023443 +v -0.006780 0.040221 0.023798 +v -0.006146 0.040227 0.024133 +v -0.007539 0.032560 0.025942 +v -0.006583 0.032569 0.025588 +v -0.006177 0.032575 0.024653 +v -0.006432 0.032574 0.023870 +v -0.007311 0.032566 0.023354 +v -0.008292 0.032556 0.023631 +v -0.008774 0.032550 0.024739 +v -0.008307 0.032553 0.025645 +v -0.007550 0.032759 0.026142 +v -0.007309 0.032761 0.026134 +v -0.007366 0.038561 0.026144 +v -0.006448 0.032771 0.025733 +v -0.006504 0.038570 0.025743 +v -0.006060 0.032775 0.025129 +v -0.006116 0.038575 0.025139 +v -0.005979 0.032777 0.024655 +v -0.006036 0.038577 0.024665 +v -0.006274 0.032776 0.023752 +v -0.006330 0.038575 0.023762 +v -0.006618 0.032773 0.023416 +v -0.006675 0.038573 0.023426 +v -0.007288 0.032767 0.023156 +v -0.007344 0.038566 0.023166 +v -0.007769 0.032762 0.023172 +v -0.007825 0.038562 0.023182 +v -0.008419 0.032755 0.023475 +v -0.008595 0.032753 0.023641 +v -0.008651 0.038553 0.023651 +v -0.008855 0.032750 0.024046 +v -0.008911 0.038550 0.024056 +v -0.008975 0.032748 0.024754 +v -0.009032 0.038547 0.024764 +v -0.008863 0.032748 0.025222 +v -0.008920 0.038548 0.025232 +v -0.008666 0.038549 0.025641 +v -0.008436 0.032751 0.025799 +v -0.008493 0.038551 0.025809 +v -0.008021 0.032755 0.026043 +v -0.008078 0.038554 0.026053 +v -0.008764 0.038546 0.027226 +v -0.009060 0.038543 0.027062 +v -0.010340 0.038536 0.024147 +v -0.009803 0.038537 0.026381 +v -0.010145 0.038535 0.025800 +v -0.007118 0.038561 0.027473 +v -0.005614 0.038577 0.026759 +v -0.007785 0.038564 0.021815 +v -0.009329 0.038548 0.022439 +v -0.004766 0.038588 0.025327 +v -0.004863 0.038590 0.023665 +v -0.006462 0.038577 0.022014 +v -0.005610 0.038584 0.022553 +v -0.009114 0.038873 0.027030 +v -0.010165 0.038865 0.025761 +v -0.010383 0.038864 0.024836 +v -0.010339 0.038866 0.024123 +v -0.010119 0.038869 0.023443 +v -0.009403 0.038878 0.022499 +v -0.007661 0.038896 0.021807 +v -0.007422 0.038898 0.021807 +v -0.006492 0.038907 0.022004 +v -0.006274 0.038909 0.022101 +v -0.005679 0.038914 0.022496 +v -0.004795 0.038920 0.023886 +v -0.004764 0.038918 0.025303 +v -0.004911 0.038916 0.025757 +v -0.005586 0.038908 0.026730 +v -0.006164 0.038901 0.027151 +v -0.007061 0.038892 0.027464 +v -0.008012 0.038883 0.027465 +v -0.007657 0.039101 0.021930 +v -0.008217 0.039086 0.027297 +v -0.007993 0.039089 0.027344 +v -0.004863 0.039125 0.024142 +v -0.004915 0.039124 0.023919 +v -0.006330 0.039113 0.022211 +v -0.006539 0.039112 0.022118 +v -0.006711 0.039664 0.022542 +v -0.006371 0.039667 0.022711 +v -0.006006 0.040110 0.023928 +v -0.005653 0.039979 0.024455 +v -0.006243 0.039971 0.026046 +v -0.006287 0.039661 0.026548 +v -0.006493 0.039968 0.026244 +v -0.006293 0.039302 0.026923 +v -0.006488 0.039300 0.027020 +v -0.006620 0.039658 0.026731 +v -0.007543 0.039475 0.027093 +v -0.008149 0.039469 0.027017 +v -0.008556 0.039800 0.026493 +v -0.008974 0.039276 0.026813 +v -0.009150 0.039274 0.026686 +v -0.008981 0.039797 0.026185 +v -0.009362 0.039942 0.025247 +v -0.009707 0.039630 0.025360 +v -0.009917 0.039455 0.025214 +v -0.009759 0.039630 0.025177 +v -0.009452 0.039942 0.024778 +v -0.009977 0.039455 0.024811 +v -0.008253 0.039957 0.022884 +v -0.008205 0.039649 0.022480 +v -0.008102 0.039958 0.022831 +v -0.007833 0.039653 0.022401 +v -0.007429 0.039103 0.021930 +v -0.008317 0.039553 0.025514 +v -0.007188 0.039564 0.025754 +v -0.008675 0.039551 0.024417 +v -0.007903 0.039560 0.023558 +v -0.006774 0.039571 0.023797 +v -0.006416 0.039573 0.024895 +v 0.007574 -0.040268 0.013190 +v 0.008704 -0.040280 0.013429 +v 0.007737 -0.040275 0.013702 +v 0.008841 -0.040284 0.013747 +v 0.006964 -0.040260 0.012914 +v 0.007987 -0.040253 0.011234 +v 0.007792 -0.040248 0.010938 +v 0.007216 -0.040255 0.012093 +v 0.009475 -0.040278 0.012570 +v 0.007113 -0.040248 0.011477 +v 0.009837 -0.040277 0.012173 +v 0.009461 -0.040285 0.013334 +v 0.009226 -0.040262 0.011117 +v 0.009117 -0.040264 0.011472 +v 0.008407 -0.040252 0.010833 +v 0.008347 -0.032629 0.013704 +v 0.008958 -0.032633 0.013584 +v 0.009556 -0.032632 0.013018 +v 0.009709 -0.032628 0.012415 +v 0.009453 -0.032618 0.011632 +v 0.008574 -0.032606 0.011117 +v 0.007593 -0.032600 0.011393 +v 0.007112 -0.032607 0.012502 +v 0.007580 -0.032620 0.013407 +v 0.008336 -0.032831 0.013902 +v 0.008578 -0.032833 0.013894 +v 0.008530 -0.038632 0.013838 +v 0.009041 -0.032835 0.013763 +v 0.009203 -0.038635 0.013588 +v 0.009439 -0.032836 0.013493 +v 0.009391 -0.038635 0.013436 +v 0.009730 -0.032835 0.013110 +v 0.009682 -0.038634 0.013054 +v 0.009907 -0.032829 0.012414 +v 0.009859 -0.038629 0.012358 +v 0.009612 -0.032818 0.011511 +v 0.009564 -0.038618 0.011455 +v 0.009268 -0.032812 0.011175 +v 0.009220 -0.038611 0.011119 +v 0.008598 -0.032804 0.010916 +v 0.008550 -0.038603 0.010860 +v 0.007885 -0.032799 0.010998 +v 0.007837 -0.038598 0.010941 +v 0.007466 -0.032798 0.011236 +v 0.007291 -0.032798 0.011402 +v 0.007243 -0.038597 0.011345 +v 0.007031 -0.032800 0.011807 +v 0.006983 -0.038599 0.011750 +v 0.006911 -0.032806 0.012515 +v 0.006863 -0.038605 0.012458 +v 0.007023 -0.032811 0.012983 +v 0.006975 -0.038611 0.012926 +v 0.007450 -0.032820 0.013559 +v 0.007403 -0.038620 0.013503 +v 0.007865 -0.032826 0.013803 +v 0.007818 -0.038625 0.013746 +v 0.007444 -0.038635 0.015047 +v 0.005555 -0.038588 0.011841 +v 0.006313 -0.038619 0.014331 +v 0.005750 -0.038606 0.013494 +v 0.009108 -0.038649 0.015097 +v 0.010281 -0.038653 0.014452 +v 0.010019 -0.038653 0.014664 +v 0.007136 -0.038581 0.009774 +v 0.008108 -0.038587 0.009509 +v 0.006316 -0.038580 0.010361 +v 0.011129 -0.038646 0.013019 +v 0.010722 -0.038651 0.013941 +v 0.011032 -0.038629 0.011357 +v 0.009432 -0.038599 0.009707 +v 0.010284 -0.038612 0.010246 +v 0.007422 -0.038965 0.015037 +v 0.007200 -0.038962 0.014949 +v 0.006241 -0.038947 0.014254 +v 0.006088 -0.038944 0.014070 +v 0.005731 -0.038935 0.013452 +v 0.005507 -0.038922 0.012288 +v 0.005556 -0.038918 0.011814 +v 0.005776 -0.038913 0.011134 +v 0.006158 -0.038910 0.010530 +v 0.006492 -0.038910 0.010189 +v 0.007086 -0.038911 0.009793 +v 0.008234 -0.038918 0.009497 +v 0.009402 -0.038929 0.009693 +v 0.010216 -0.038941 0.010185 +v 0.010550 -0.038947 0.010525 +v 0.011100 -0.038961 0.011574 +v 0.011132 -0.038975 0.012992 +v 0.010765 -0.038981 0.013868 +v 0.010310 -0.038983 0.014419 +v 0.009068 -0.038979 0.015104 +v 0.006054 -0.039147 0.013806 +v 0.011033 -0.039169 0.011828 +v 0.010981 -0.039166 0.011606 +v 0.009432 -0.039859 0.010541 +v 0.009716 -0.039863 0.010747 +v 0.009942 -0.039528 0.010491 +v 0.010091 -0.039531 0.010631 +v 0.010024 -0.040159 0.012010 +v 0.010045 -0.040160 0.012152 +v 0.007504 -0.039364 0.014787 +v 0.007574 -0.040025 0.014077 +v 0.007303 -0.039362 0.014707 +v 0.007431 -0.040024 0.014006 +v 0.006185 -0.039150 0.013994 +v 0.006433 -0.039702 0.013557 +v 0.006590 -0.040008 0.013075 +v 0.006535 -0.040006 0.012925 +v 0.006189 -0.039695 0.013042 +v 0.006138 -0.039693 0.012859 +v 0.005792 -0.039330 0.012722 +v 0.005764 -0.039326 0.012289 +v 0.008247 -0.039508 0.009903 +v 0.008654 -0.039512 0.009920 +v 0.007579 -0.039618 0.013197 +v 0.008709 -0.039630 0.013435 +v 0.007221 -0.039605 0.012099 +v 0.007993 -0.039603 0.011240 +v 0.009123 -0.039614 0.011479 +v 0.009481 -0.039628 0.012576 +v 0.009731 -0.040286 0.033342 +v 0.010073 -0.040292 0.033196 +v 0.011202 -0.040310 0.033435 +v 0.010236 -0.040294 0.033708 +v 0.011339 -0.040312 0.033753 +v 0.010486 -0.040299 0.031239 +v 0.009715 -0.040286 0.032098 +v 0.012111 -0.040324 0.033139 +v 0.011974 -0.040322 0.032576 +v 0.009347 -0.040280 0.032433 +v 0.009544 -0.040284 0.031589 +v 0.009399 -0.040281 0.031935 +v 0.012336 -0.040328 0.032178 +v 0.011724 -0.040319 0.031122 +v 0.011616 -0.040317 0.031478 +v 0.011276 -0.040312 0.030900 +v 0.010905 -0.040306 0.030838 +v 0.010906 -0.032654 0.033634 +v 0.011861 -0.032669 0.033279 +v 0.012267 -0.032676 0.032344 +v 0.011713 -0.032668 0.031270 +v 0.010716 -0.032652 0.031060 +v 0.010152 -0.032642 0.031323 +v 0.009707 -0.032635 0.032015 +v 0.009864 -0.032637 0.033022 +v 0.010893 -0.032854 0.033833 +v 0.010800 -0.038653 0.033835 +v 0.011598 -0.032865 0.033695 +v 0.011504 -0.038664 0.033696 +v 0.011995 -0.032872 0.033424 +v 0.011902 -0.038671 0.033425 +v 0.012383 -0.032878 0.032820 +v 0.012290 -0.038677 0.032821 +v 0.012464 -0.032879 0.032345 +v 0.012370 -0.038679 0.032347 +v 0.012169 -0.032875 0.031442 +v 0.012076 -0.038674 0.031444 +v 0.011824 -0.032869 0.031107 +v 0.011731 -0.038669 0.031108 +v 0.011155 -0.032859 0.030847 +v 0.011062 -0.038658 0.030849 +v 0.010674 -0.032851 0.030863 +v 0.010581 -0.038650 0.030865 +v 0.010130 -0.038643 0.031032 +v 0.010023 -0.032840 0.031167 +v 0.009848 -0.032838 0.031333 +v 0.009755 -0.038637 0.031334 +v 0.009588 -0.032833 0.031738 +v 0.009495 -0.038633 0.031739 +v 0.009510 -0.032832 0.031966 +v 0.009468 -0.032831 0.032446 +v 0.009375 -0.038630 0.032447 +v 0.009580 -0.032833 0.032914 +v 0.009487 -0.038632 0.032915 +v 0.009691 -0.032835 0.033128 +v 0.010007 -0.032840 0.033491 +v 0.009914 -0.038639 0.033492 +v 0.009956 -0.038639 0.035036 +v 0.008066 -0.038610 0.031830 +v 0.008264 -0.038613 0.031186 +v 0.008825 -0.038621 0.034320 +v 0.008262 -0.038612 0.033483 +v 0.011620 -0.038666 0.035086 +v 0.009647 -0.038635 0.029763 +v 0.010620 -0.038651 0.029498 +v 0.008828 -0.038622 0.030350 +v 0.009351 -0.038631 0.029925 +v 0.013640 -0.038699 0.033008 +v 0.013233 -0.038692 0.033931 +v 0.013543 -0.038698 0.031346 +v 0.011944 -0.038672 0.029696 +v 0.012796 -0.038686 0.030235 +v 0.009931 -0.038969 0.035029 +v 0.009291 -0.038959 0.034712 +v 0.008750 -0.038950 0.034246 +v 0.008342 -0.038944 0.033660 +v 0.008240 -0.038942 0.033444 +v 0.008066 -0.038940 0.031806 +v 0.008120 -0.038941 0.031574 +v 0.008667 -0.038950 0.030523 +v 0.009001 -0.038955 0.030181 +v 0.009595 -0.038965 0.029785 +v 0.010743 -0.038983 0.029489 +v 0.010981 -0.038987 0.029489 +v 0.011911 -0.039002 0.029685 +v 0.012725 -0.039015 0.030177 +v 0.013059 -0.039020 0.030517 +v 0.013609 -0.039029 0.031567 +v 0.013640 -0.039029 0.032984 +v 0.013494 -0.039026 0.033438 +v 0.013273 -0.039023 0.033861 +v 0.012241 -0.039006 0.034832 +v 0.011577 -0.038995 0.035096 +v 0.010745 -0.039189 0.029612 +v 0.009257 -0.039165 0.030132 +v 0.009078 -0.039162 0.030274 +v 0.008305 -0.039149 0.031389 +v 0.008235 -0.039148 0.031606 +v 0.013540 -0.039233 0.031822 +v 0.013488 -0.039232 0.031600 +v 0.011934 -0.039923 0.030543 +v 0.012218 -0.039928 0.030749 +v 0.012446 -0.039597 0.030489 +v 0.012595 -0.039599 0.030629 +v 0.012523 -0.040213 0.032015 +v 0.012544 -0.040213 0.032156 +v 0.012361 -0.040210 0.033126 +v 0.012289 -0.040209 0.033250 +v 0.012109 -0.039405 0.034604 +v 0.011915 -0.039402 0.034701 +v 0.010010 -0.039372 0.034783 +v 0.009429 -0.039362 0.034495 +v 0.009331 -0.040028 0.033492 +v 0.009239 -0.040027 0.033361 +v 0.008766 -0.039872 0.032120 +v 0.008832 -0.039873 0.031776 +v 0.008507 -0.039533 0.031684 +v 0.008364 -0.039346 0.031643 +v 0.008570 -0.039534 0.031490 +v 0.010973 -0.039192 0.029612 +v 0.010083 -0.039642 0.033196 +v 0.011213 -0.039660 0.033435 +v 0.009725 -0.039636 0.032098 +v 0.010496 -0.039649 0.031239 +v 0.011626 -0.039667 0.031478 +v 0.011984 -0.039673 0.032575 +v -0.008666 -0.040171 0.025661 +v -0.008324 -0.040174 0.025516 +v -0.007194 -0.040185 0.025755 +v -0.008381 -0.040173 0.025907 +v -0.007550 -0.040181 0.026157 +v -0.007909 -0.040182 0.023559 +v -0.008105 -0.040180 0.023263 +v -0.008681 -0.040173 0.024418 +v -0.006285 -0.040194 0.025459 +v -0.006422 -0.040194 0.024896 +v -0.009049 -0.040169 0.024752 +v -0.008784 -0.040173 0.023802 +v -0.006436 -0.040192 0.025660 +v -0.006671 -0.040194 0.023443 +v -0.006780 -0.040192 0.023798 +v -0.007119 -0.040190 0.023220 +v -0.006146 -0.040198 0.024133 +v -0.007539 -0.032531 0.025942 +v -0.006583 -0.032541 0.025588 +v -0.006177 -0.032546 0.024653 +v -0.006432 -0.032545 0.023870 +v -0.007311 -0.032537 0.023354 +v -0.008292 -0.032527 0.023631 +v -0.008774 -0.032521 0.024739 +v -0.008307 -0.032524 0.025645 +v -0.007550 -0.032730 0.026142 +v -0.007607 -0.038530 0.026152 +v -0.006846 -0.032737 0.026004 +v -0.006902 -0.038537 0.026014 +v -0.006448 -0.032742 0.025733 +v -0.006504 -0.038542 0.025743 +v -0.006060 -0.032747 0.025129 +v -0.006116 -0.038546 0.025139 +v -0.005979 -0.032748 0.024655 +v -0.006036 -0.038548 0.024665 +v -0.006274 -0.032747 0.023752 +v -0.006330 -0.038547 0.023762 +v -0.006618 -0.032744 0.023416 +v -0.006675 -0.038544 0.023426 +v -0.006883 -0.038542 0.023304 +v -0.007288 -0.032738 0.023156 +v -0.007344 -0.038538 0.023166 +v -0.007769 -0.032733 0.023172 +v -0.007825 -0.038533 0.023182 +v -0.008419 -0.032726 0.023475 +v -0.008595 -0.032724 0.023641 +v -0.008651 -0.038524 0.023651 +v -0.008855 -0.032721 0.024046 +v -0.008911 -0.038521 0.024056 +v -0.008975 -0.032719 0.024754 +v -0.009032 -0.038519 0.024764 +v -0.008863 -0.032719 0.025222 +v -0.008920 -0.038519 0.025232 +v -0.008436 -0.032722 0.025799 +v -0.008493 -0.038522 0.025809 +v -0.008451 -0.038520 0.027353 +v -0.010340 -0.038507 0.024147 +v -0.009583 -0.038510 0.026637 +v -0.010145 -0.038506 0.025800 +v -0.006788 -0.038536 0.027404 +v -0.005877 -0.038546 0.026972 +v -0.007785 -0.038536 0.021815 +v -0.009329 -0.038520 0.022439 +v -0.004766 -0.038559 0.025327 +v -0.005174 -0.038554 0.026249 +v -0.004863 -0.038561 0.023665 +v -0.006462 -0.038548 0.022014 +v -0.006157 -0.038551 0.022160 +v -0.005610 -0.038556 0.022553 +v -0.008474 -0.038850 0.027347 +v -0.009114 -0.038844 0.027030 +v -0.009655 -0.038839 0.026563 +v -0.010165 -0.038836 0.025761 +v -0.010383 -0.038835 0.024836 +v -0.010339 -0.038837 0.024123 +v -0.010119 -0.038840 0.023443 +v -0.009403 -0.038849 0.022499 +v -0.007661 -0.038867 0.021807 +v -0.007422 -0.038869 0.021807 +v -0.006492 -0.038878 0.022004 +v -0.005679 -0.038885 0.022496 +v -0.005345 -0.038888 0.022836 +v -0.004795 -0.038891 0.023886 +v -0.004764 -0.038889 0.025303 +v -0.004911 -0.038887 0.025757 +v -0.005131 -0.038884 0.026180 +v -0.006164 -0.038872 0.027151 +v -0.006828 -0.038866 0.027414 +v -0.007298 -0.038861 0.027494 +v -0.007657 -0.039072 0.021930 +v -0.004863 -0.039096 0.024142 +v -0.004915 -0.039096 0.023919 +v -0.006464 -0.039798 0.022863 +v -0.006667 -0.040076 0.023195 +v -0.006548 -0.040077 0.023274 +v -0.006180 -0.039800 0.023069 +v -0.005953 -0.039469 0.022809 +v -0.005804 -0.039470 0.022948 +v -0.006006 -0.040081 0.023928 +v -0.005653 -0.039951 0.024455 +v -0.006287 -0.039632 0.026548 +v -0.006293 -0.039273 0.026923 +v -0.006488 -0.039271 0.027020 +v -0.006620 -0.039629 0.026732 +v -0.008974 -0.039247 0.026813 +v -0.009150 -0.039246 0.026686 +v -0.009362 -0.039913 0.025247 +v -0.009707 -0.039601 0.025360 +v -0.009917 -0.039426 0.025214 +v -0.009759 -0.039601 0.025177 +v -0.009452 -0.039913 0.024778 +v -0.009977 -0.039426 0.024811 +v -0.008253 -0.039928 0.022884 +v -0.008205 -0.039621 0.022480 +v -0.008102 -0.039930 0.022831 +v -0.007833 -0.039624 0.022401 +v -0.007429 -0.039074 0.021930 +v -0.008317 -0.039524 0.025514 +v -0.007188 -0.039535 0.025754 +v -0.008675 -0.039523 0.024417 +v -0.007903 -0.039532 0.023558 +v -0.006774 -0.039542 0.023797 +v -0.006416 -0.039544 0.024895 +v 0.249273 -0.025808 0.024904 +v 0.250005 -0.025998 0.025777 +v 0.249084 -0.025984 0.025376 +v 0.249480 -0.026087 0.025847 +v 0.250801 -0.025241 0.023745 +v 0.249671 -0.025429 0.023889 +v 0.248921 -0.025741 0.024560 +v 0.251135 -0.025810 0.025633 +v 0.249852 -0.025253 0.023415 +v 0.249525 -0.025346 0.023576 +v 0.251229 -0.025910 0.025979 +v 0.250530 -0.026065 0.026188 +v 0.251533 -0.025431 0.024617 +v 0.250338 -0.025165 0.023333 +v 0.251890 -0.025479 0.024903 +v 0.251549 -0.025194 0.023892 +v 0.251820 -0.025600 0.025252 +v 0.248646 -0.018791 0.028001 +v 0.249609 -0.018778 0.028336 +v 0.250358 -0.018592 0.028051 +v 0.250784 -0.018259 0.027187 +v 0.250656 -0.018086 0.026603 +v 0.249893 -0.017967 0.025938 +v 0.249484 -0.017994 0.025863 +v 0.248426 -0.018290 0.026366 +v 0.248205 -0.018559 0.027112 +v 0.248540 -0.019041 0.028079 +v 0.249229 -0.024520 0.026305 +v 0.248946 -0.019073 0.028335 +v 0.249634 -0.024552 0.026562 +v 0.249650 -0.019027 0.028465 +v 0.250339 -0.024506 0.026692 +v 0.250113 -0.018937 0.028369 +v 0.250802 -0.024416 0.026596 +v 0.250515 -0.018811 0.028136 +v 0.250679 -0.018739 0.027975 +v 0.251368 -0.024218 0.026202 +v 0.251007 -0.018427 0.027139 +v 0.251696 -0.023906 0.025366 +v 0.250858 -0.018228 0.026466 +v 0.250737 -0.018177 0.026263 +v 0.251426 -0.023657 0.024490 +v 0.250199 -0.018093 0.025795 +v 0.250888 -0.023573 0.024021 +v 0.249978 -0.018090 0.025698 +v 0.250667 -0.023569 0.023925 +v 0.249506 -0.018121 0.025611 +v 0.250195 -0.023600 0.023838 +v 0.249267 -0.018155 0.025623 +v 0.249956 -0.023634 0.023849 +v 0.248815 -0.018254 0.025755 +v 0.249504 -0.023734 0.023981 +v 0.248285 -0.018463 0.026192 +v 0.248974 -0.023942 0.024419 +v 0.248084 -0.018620 0.026600 +v 0.248773 -0.024099 0.024827 +v 0.248030 -0.018773 0.027053 +v 0.248130 -0.018907 0.027505 +v 0.248819 -0.024386 0.025731 +v 0.247666 -0.024736 0.026365 +v 0.248515 -0.024957 0.027377 +v 0.248336 -0.023615 0.023163 +v 0.247469 -0.024151 0.024479 +v 0.249411 -0.024994 0.027838 +v 0.250406 -0.024913 0.027978 +v 0.250841 -0.023133 0.022646 +v 0.251162 -0.023126 0.022748 +v 0.249192 -0.023357 0.022697 +v 0.250175 -0.023187 0.022553 +v 0.250510 -0.023154 0.022581 +v 0.251949 -0.024554 0.027466 +v 0.252775 -0.024137 0.026499 +v 0.252487 -0.023282 0.023744 +v 0.253001 -0.023603 0.024938 +v 0.247741 -0.025066 0.026333 +v 0.247556 -0.024951 0.025908 +v 0.247465 -0.024526 0.024559 +v 0.247519 -0.024448 0.024340 +v 0.248393 -0.023920 0.023047 +v 0.250123 -0.023510 0.022451 +v 0.251283 -0.023438 0.022680 +v 0.252264 -0.023528 0.023338 +v 0.252567 -0.023606 0.023699 +v 0.253025 -0.023890 0.024754 +v 0.253046 -0.024181 0.025659 +v 0.252857 -0.024414 0.026307 +v 0.252503 -0.024645 0.026883 +v 0.252008 -0.024859 0.027351 +v 0.251182 -0.025094 0.027758 +v 0.250488 -0.025219 0.027875 +v 0.248492 -0.025261 0.027228 +v 0.250152 -0.023741 0.022505 +v 0.247592 -0.024996 0.025387 +v 0.252178 -0.024235 0.023572 +v 0.252864 -0.024441 0.025081 +v 0.252085 -0.025303 0.024823 +v 0.252082 -0.025347 0.024959 +v 0.252838 -0.024577 0.025491 +v 0.251304 -0.025499 0.027139 +v 0.250814 -0.025969 0.026386 +v 0.250529 -0.025766 0.027094 +v 0.247697 -0.025120 0.025813 +v 0.248191 -0.025552 0.025525 +v 0.248104 -0.025448 0.025170 +v 0.248693 -0.025691 0.024703 +v 0.248702 -0.025646 0.024568 +v 0.248583 -0.024600 0.023302 +v 0.248731 -0.024540 0.023174 +v 0.249926 -0.023773 0.022515 +v 0.252042 -0.024204 0.023423 +v 0.249196 -0.025194 0.025103 +v 0.249928 -0.025384 0.025975 +v 0.249593 -0.024815 0.024087 +v 0.250723 -0.024627 0.023944 +v 0.251456 -0.024817 0.024816 +v 0.251058 -0.025196 0.025832 +v 0.238186 -0.026234 0.042494 +v 0.238540 -0.026166 0.042587 +v 0.239246 -0.025843 0.043441 +v 0.238718 -0.025879 0.043533 +v 0.239147 -0.025764 0.043764 +v 0.238252 -0.026361 0.042014 +v 0.240105 -0.026327 0.041353 +v 0.240146 -0.026418 0.041012 +v 0.238969 -0.026408 0.041543 +v 0.240382 -0.025762 0.043251 +v 0.238833 -0.026511 0.041232 +v 0.240912 -0.025723 0.043167 +v 0.239884 -0.025661 0.043821 +v 0.240812 -0.026004 0.042207 +v 0.241041 -0.026098 0.041777 +v 0.241117 -0.025824 0.042722 +v 0.237935 -0.018605 0.041290 +v 0.238888 -0.018408 0.041591 +v 0.239795 -0.018431 0.041126 +v 0.240060 -0.018720 0.039983 +v 0.239436 -0.019006 0.039229 +v 0.238839 -0.019115 0.039092 +v 0.238058 -0.019134 0.039351 +v 0.237657 -0.019050 0.039819 +v 0.237541 -0.018843 0.040607 +v 0.237823 -0.018771 0.041489 +v 0.238011 -0.018710 0.041627 +v 0.238666 -0.024259 0.043184 +v 0.238923 -0.018544 0.041837 +v 0.239578 -0.024092 0.043393 +v 0.239604 -0.018527 0.041611 +v 0.240259 -0.024075 0.043167 +v 0.239969 -0.018571 0.041300 +v 0.240624 -0.024119 0.042856 +v 0.240943 -0.024258 0.042229 +v 0.240322 -0.018770 0.040441 +v 0.240977 -0.024319 0.041997 +v 0.240274 -0.018905 0.039981 +v 0.240079 -0.019045 0.039564 +v 0.240734 -0.024593 0.041121 +v 0.240410 -0.024724 0.040790 +v 0.239555 -0.019234 0.039111 +v 0.240210 -0.024782 0.040668 +v 0.238866 -0.019359 0.038953 +v 0.238627 -0.019382 0.038974 +v 0.239282 -0.024930 0.040531 +v 0.238170 -0.019393 0.039125 +v 0.238825 -0.024942 0.040682 +v 0.237965 -0.019382 0.039252 +v 0.237626 -0.019327 0.039589 +v 0.238281 -0.024876 0.041146 +v 0.237502 -0.019285 0.039792 +v 0.237344 -0.019113 0.040471 +v 0.237999 -0.024662 0.042028 +v 0.237368 -0.019046 0.040701 +v 0.237430 -0.018976 0.040924 +v 0.238085 -0.024525 0.042481 +v 0.241377 -0.024874 0.039851 +v 0.236911 -0.024470 0.043168 +v 0.237480 -0.024184 0.043950 +v 0.237680 -0.025297 0.039899 +v 0.236772 -0.025020 0.041266 +v 0.238613 -0.023870 0.044591 +v 0.239606 -0.023725 0.044692 +v 0.241114 -0.024959 0.039657 +v 0.238552 -0.025336 0.039394 +v 0.239541 -0.025271 0.039209 +v 0.242249 -0.024032 0.042484 +v 0.241167 -0.023703 0.044114 +v 0.242155 -0.023955 0.042798 +v 0.241994 -0.024592 0.040597 +v 0.242297 -0.024299 0.041512 +v 0.237225 -0.024626 0.043712 +v 0.236982 -0.024763 0.043325 +v 0.236698 -0.025169 0.041996 +v 0.236821 -0.025346 0.041315 +v 0.237559 -0.025591 0.040130 +v 0.237736 -0.025615 0.039972 +v 0.239486 -0.025596 0.039300 +v 0.240192 -0.025498 0.039355 +v 0.241254 -0.025243 0.039815 +v 0.241896 -0.024985 0.040467 +v 0.242017 -0.024916 0.040661 +v 0.242322 -0.024640 0.041518 +v 0.242347 -0.024444 0.042204 +v 0.242106 -0.024222 0.043097 +v 0.241734 -0.024098 0.043694 +v 0.241224 -0.024020 0.044188 +v 0.240384 -0.023995 0.044632 +v 0.239685 -0.024036 0.044778 +v 0.238977 -0.024127 0.044752 +v 0.238747 -0.024167 0.044705 +v 0.237532 -0.024494 0.044052 +v 0.241705 -0.024582 0.043479 +v 0.241578 -0.024548 0.043651 +v 0.239361 -0.024967 0.044430 +v 0.238811 -0.025063 0.044318 +v 0.238430 -0.025583 0.043774 +v 0.237887 -0.025103 0.043919 +v 0.237749 -0.025158 0.043779 +v 0.238205 -0.025668 0.043564 +v 0.237370 -0.025722 0.042575 +v 0.237174 -0.025680 0.042161 +v 0.237374 -0.025875 0.042027 +v 0.238043 -0.026163 0.040721 +v 0.238336 -0.026196 0.040481 +v 0.240176 -0.025820 0.039709 +v 0.240384 -0.025781 0.039760 +v 0.238466 -0.025544 0.042413 +v 0.239173 -0.025221 0.043267 +v 0.238896 -0.025786 0.041368 +v 0.240032 -0.025705 0.041179 +v 0.240738 -0.025382 0.042033 +v 0.240309 -0.025140 0.043077 +v 0.229311 -0.027719 0.024006 +v 0.230041 -0.027972 0.024865 +v 0.229121 -0.027926 0.024464 +v 0.229515 -0.028062 0.024928 +v 0.230845 -0.027085 0.022890 +v 0.230877 -0.026951 0.022563 +v 0.230315 -0.028097 0.025260 +v 0.229714 -0.027276 0.023019 +v 0.228961 -0.027627 0.023666 +v 0.231172 -0.027782 0.024736 +v 0.229221 -0.027340 0.023028 +v 0.230016 -0.027041 0.022525 +v 0.231461 -0.027827 0.024938 +v 0.231575 -0.027338 0.023749 +v 0.231793 -0.027150 0.023344 +v 0.228723 -0.020922 0.027566 +v 0.229685 -0.020939 0.027903 +v 0.230436 -0.020738 0.027632 +v 0.230866 -0.020350 0.026794 +v 0.230503 -0.020036 0.025895 +v 0.229570 -0.019989 0.025488 +v 0.228795 -0.020169 0.025700 +v 0.228333 -0.020470 0.026312 +v 0.228311 -0.020702 0.026888 +v 0.228614 -0.021177 0.027627 +v 0.228807 -0.021210 0.027769 +v 0.229465 -0.026562 0.025632 +v 0.229724 -0.021195 0.028015 +v 0.230382 -0.026547 0.025879 +v 0.230188 -0.021103 0.027926 +v 0.230846 -0.026455 0.025789 +v 0.230591 -0.020964 0.027703 +v 0.230756 -0.020882 0.027547 +v 0.231414 -0.026233 0.025411 +v 0.230994 -0.020702 0.027169 +v 0.231652 -0.026053 0.025033 +v 0.231087 -0.020517 0.026735 +v 0.231077 -0.020428 0.026511 +v 0.231735 -0.025780 0.024374 +v 0.230668 -0.020154 0.025698 +v 0.231326 -0.025506 0.023561 +v 0.230285 -0.020088 0.025415 +v 0.230943 -0.025440 0.023278 +v 0.229592 -0.020099 0.025228 +v 0.229353 -0.020132 0.025237 +v 0.230011 -0.025484 0.023101 +v 0.228698 -0.020307 0.025473 +v 0.229356 -0.025659 0.023337 +v 0.228165 -0.020654 0.026179 +v 0.228823 -0.026006 0.024042 +v 0.228767 -0.026189 0.024484 +v 0.228139 -0.020923 0.026844 +v 0.228797 -0.026275 0.024708 +v 0.228310 -0.021071 0.027269 +v 0.228968 -0.026423 0.025132 +v 0.232089 -0.025007 0.022545 +v 0.227580 -0.026636 0.025238 +v 0.228554 -0.027031 0.026529 +v 0.228392 -0.025409 0.022414 +v 0.227425 -0.026283 0.024306 +v 0.227452 -0.026155 0.023995 +v 0.227519 -0.026025 0.023690 +v 0.229449 -0.027105 0.026988 +v 0.230444 -0.027041 0.027134 +v 0.229571 -0.025054 0.021888 +v 0.230570 -0.024923 0.021868 +v 0.231990 -0.026658 0.026651 +v 0.232821 -0.026182 0.025715 +v 0.233053 -0.025546 0.024194 +v 0.227598 -0.026921 0.025062 +v 0.227478 -0.026497 0.023962 +v 0.228116 -0.025866 0.022580 +v 0.228448 -0.025705 0.022278 +v 0.229481 -0.025385 0.021794 +v 0.229711 -0.025339 0.021749 +v 0.230655 -0.025224 0.021754 +v 0.231558 -0.025231 0.022049 +v 0.232148 -0.025316 0.022442 +v 0.232622 -0.025463 0.022956 +v 0.233076 -0.025820 0.023991 +v 0.233094 -0.026171 0.024875 +v 0.232901 -0.026446 0.025505 +v 0.232545 -0.026713 0.026064 +v 0.232047 -0.026954 0.026516 +v 0.231219 -0.027211 0.026904 +v 0.230524 -0.027340 0.027011 +v 0.228530 -0.027325 0.026360 +v 0.227816 -0.027155 0.025158 +v 0.232666 -0.025748 0.023126 +v 0.232545 -0.025689 0.022941 +v 0.232203 -0.026582 0.023131 +v 0.232351 -0.026684 0.023433 +v 0.232192 -0.026863 0.023431 +v 0.232241 -0.026915 0.023575 +v 0.232755 -0.026732 0.024585 +v 0.232215 -0.027326 0.024597 +v 0.232526 -0.027047 0.024831 +v 0.232662 -0.026889 0.024949 +v 0.231921 -0.027566 0.025108 +v 0.232175 -0.027333 0.025440 +v 0.231709 -0.027676 0.025319 +v 0.230911 -0.027859 0.025932 +v 0.230568 -0.028036 0.025508 +v 0.230564 -0.027833 0.026195 +v 0.230284 -0.028066 0.025495 +v 0.228973 -0.027821 0.025675 +v 0.228830 -0.027790 0.025553 +v 0.227738 -0.027084 0.024956 +v 0.227938 -0.027088 0.023992 +v 0.228122 -0.027232 0.023939 +v 0.228134 -0.027160 0.023763 +v 0.228230 -0.026355 0.022749 +v 0.228360 -0.026277 0.022595 +v 0.229871 -0.026677 0.022250 +v 0.230025 -0.026646 0.022220 +v 0.230966 -0.026562 0.022299 +v 0.231261 -0.026574 0.022421 +v 0.229238 -0.027120 0.024245 +v 0.229967 -0.027373 0.025104 +v 0.229640 -0.026676 0.023258 +v 0.230772 -0.026485 0.023129 +v 0.231501 -0.026739 0.023988 +v 0.231099 -0.027182 0.024975 +v 0.249273 0.025759 0.024904 +v 0.250005 0.025950 0.025777 +v 0.249084 0.025936 0.025376 +v 0.249916 0.026063 0.026092 +v 0.250801 0.025192 0.023745 +v 0.249671 0.025381 0.023889 +v 0.251135 0.025761 0.025633 +v 0.249178 0.025447 0.023903 +v 0.251229 0.025861 0.025979 +v 0.251798 0.025250 0.024312 +v 0.251533 0.025382 0.024617 +v 0.250214 0.025134 0.023338 +v 0.251549 0.025145 0.023892 +v 0.248646 0.018742 0.028001 +v 0.249609 0.018730 0.028336 +v 0.250358 0.018543 0.028051 +v 0.250784 0.018210 0.027187 +v 0.250656 0.018037 0.026603 +v 0.249893 0.017918 0.025938 +v 0.248710 0.018115 0.026088 +v 0.248205 0.018510 0.027112 +v 0.248540 0.018993 0.028079 +v 0.249229 0.024472 0.026305 +v 0.248946 0.019025 0.028335 +v 0.249634 0.024504 0.026562 +v 0.249650 0.018978 0.028465 +v 0.250339 0.024457 0.026692 +v 0.250113 0.018889 0.028369 +v 0.250802 0.024368 0.026596 +v 0.250515 0.018763 0.028136 +v 0.250679 0.018690 0.027975 +v 0.251368 0.024169 0.026202 +v 0.251007 0.018378 0.027139 +v 0.251696 0.023858 0.025366 +v 0.250858 0.018179 0.026466 +v 0.250737 0.018129 0.026263 +v 0.251426 0.023608 0.024490 +v 0.250199 0.018045 0.025795 +v 0.250888 0.023524 0.024021 +v 0.249978 0.018041 0.025698 +v 0.249267 0.018106 0.025623 +v 0.249956 0.023585 0.023849 +v 0.248815 0.018206 0.025755 +v 0.249504 0.023685 0.023981 +v 0.248614 0.018269 0.025872 +v 0.248285 0.018414 0.026192 +v 0.248974 0.023893 0.024419 +v 0.248084 0.018571 0.026600 +v 0.248773 0.024050 0.024827 +v 0.248030 0.018725 0.027053 +v 0.248130 0.018858 0.027505 +v 0.248819 0.024337 0.025731 +v 0.247445 0.024517 0.025752 +v 0.248259 0.024870 0.027160 +v 0.248886 0.023386 0.022819 +v 0.247714 0.023881 0.023891 +v 0.247378 0.024318 0.025111 +v 0.249411 0.024945 0.027838 +v 0.249095 0.024946 0.027718 +v 0.250406 0.024865 0.027978 +v 0.251162 0.023077 0.022748 +v 0.251471 0.023083 0.022886 +v 0.250175 0.023138 0.022553 +v 0.251949 0.024505 0.027466 +v 0.252775 0.024088 0.026499 +v 0.252487 0.023233 0.023744 +v 0.253001 0.023555 0.024938 +v 0.247741 0.025017 0.026333 +v 0.247492 0.024839 0.025687 +v 0.247592 0.024321 0.024126 +v 0.247793 0.024166 0.023723 +v 0.248221 0.023942 0.023196 +v 0.248983 0.023682 0.022691 +v 0.250123 0.023461 0.022451 +v 0.251283 0.023389 0.022680 +v 0.252264 0.023479 0.023338 +v 0.252567 0.023558 0.023699 +v 0.253025 0.023842 0.024754 +v 0.253071 0.024056 0.025434 +v 0.252857 0.024365 0.026307 +v 0.252008 0.024810 0.027351 +v 0.250488 0.025171 0.027875 +v 0.249547 0.025254 0.027766 +v 0.249100 0.025257 0.027601 +v 0.248313 0.025185 0.027073 +v 0.250152 0.023693 0.022505 +v 0.252178 0.024187 0.023572 +v 0.251884 0.025375 0.026563 +v 0.251783 0.025501 0.026387 +v 0.251651 0.025552 0.026491 +v 0.249598 0.025787 0.026948 +v 0.249422 0.025786 0.026876 +v 0.248125 0.025378 0.026286 +v 0.248601 0.025741 0.025890 +v 0.248887 0.025875 0.025497 +v 0.248017 0.025333 0.026103 +v 0.248378 0.025620 0.025430 +v 0.248738 0.025768 0.025110 +v 0.247983 0.024943 0.024280 +v 0.248046 0.024876 0.024097 +v 0.248731 0.025227 0.023873 +v 0.248816 0.025176 0.023748 +v 0.249018 0.025077 0.023521 +v 0.249680 0.024447 0.022839 +v 0.249926 0.023724 0.022515 +v 0.250050 0.024380 0.022777 +v 0.252042 0.024155 0.023423 +v 0.249196 0.025145 0.025103 +v 0.249928 0.025336 0.025975 +v 0.249593 0.024767 0.024087 +v 0.250723 0.024578 0.023944 +v 0.251456 0.024768 0.024816 +v 0.251058 0.025147 0.025832 +v 0.238540 0.026117 0.042587 +v 0.238464 0.025933 0.043275 +v 0.239246 0.025794 0.043441 +v 0.238216 0.026115 0.042733 +v 0.238252 0.026312 0.042014 +v 0.240105 0.026279 0.041353 +v 0.239510 0.025652 0.043838 +v 0.238969 0.026359 0.041543 +v 0.240382 0.025713 0.043251 +v 0.238476 0.026408 0.041577 +v 0.240026 0.026392 0.040983 +v 0.239285 0.026470 0.041016 +v 0.240912 0.025675 0.043167 +v 0.239884 0.025612 0.043821 +v 0.240812 0.025955 0.042207 +v 0.241041 0.026049 0.041777 +v 0.237935 0.018556 0.041290 +v 0.238888 0.018359 0.041591 +v 0.239795 0.018382 0.041126 +v 0.240060 0.018672 0.039983 +v 0.239436 0.018957 0.039229 +v 0.238839 0.019066 0.039092 +v 0.238058 0.019086 0.039351 +v 0.237657 0.019001 0.039819 +v 0.237541 0.018794 0.040607 +v 0.237823 0.018722 0.041489 +v 0.238011 0.018661 0.041627 +v 0.238666 0.024210 0.043184 +v 0.238923 0.018495 0.041837 +v 0.239578 0.024044 0.043393 +v 0.239389 0.018472 0.041721 +v 0.240044 0.024021 0.043278 +v 0.239969 0.018522 0.041300 +v 0.240624 0.024071 0.042856 +v 0.240322 0.018721 0.040441 +v 0.240977 0.024270 0.041997 +v 0.240274 0.018856 0.039981 +v 0.240079 0.018996 0.039564 +v 0.240734 0.024545 0.041121 +v 0.239555 0.019185 0.039111 +v 0.240210 0.024734 0.040668 +v 0.238866 0.019311 0.038953 +v 0.239521 0.024859 0.040509 +v 0.238627 0.019333 0.038974 +v 0.239282 0.024882 0.040531 +v 0.239048 0.024893 0.040589 +v 0.238170 0.019345 0.039125 +v 0.238825 0.024893 0.040682 +v 0.237965 0.019333 0.039252 +v 0.237626 0.019279 0.039589 +v 0.238281 0.024827 0.041146 +v 0.237502 0.019236 0.039792 +v 0.237344 0.019065 0.040471 +v 0.237999 0.024613 0.042028 +v 0.237368 0.018997 0.040701 +v 0.237430 0.018927 0.040924 +v 0.238085 0.024476 0.042481 +v 0.236911 0.024422 0.043168 +v 0.238242 0.025286 0.039529 +v 0.237035 0.025110 0.040661 +v 0.236697 0.024891 0.041586 +v 0.238005 0.023965 0.044337 +v 0.239940 0.023649 0.044650 +v 0.239270 0.023714 0.044697 +v 0.241114 0.024911 0.039657 +v 0.238552 0.025287 0.039394 +v 0.239206 0.025255 0.039233 +v 0.239541 0.025222 0.039209 +v 0.241167 0.023654 0.044114 +v 0.242155 0.023906 0.042798 +v 0.241994 0.024543 0.040597 +v 0.242297 0.024250 0.041512 +v 0.236982 0.024714 0.043325 +v 0.236810 0.024853 0.042902 +v 0.236720 0.025182 0.041767 +v 0.236901 0.025349 0.041096 +v 0.237114 0.025441 0.040680 +v 0.237926 0.025584 0.039828 +v 0.238338 0.025602 0.039589 +v 0.239486 0.025548 0.039300 +v 0.241254 0.025195 0.039815 +v 0.241896 0.024936 0.040467 +v 0.242017 0.024867 0.040661 +v 0.242322 0.024591 0.041518 +v 0.242347 0.024395 0.042204 +v 0.242106 0.024173 0.043097 +v 0.241734 0.024050 0.043694 +v 0.241224 0.023971 0.044188 +v 0.239448 0.024013 0.044788 +v 0.239212 0.024043 0.044780 +v 0.238094 0.024266 0.044454 +v 0.237707 0.024383 0.044201 +v 0.239738 0.025684 0.039473 +v 0.239511 0.025711 0.039474 +v 0.239475 0.024242 0.044725 +v 0.239702 0.024218 0.044715 +v 0.241705 0.024533 0.043479 +v 0.241357 0.025149 0.043365 +v 0.241578 0.024500 0.043651 +v 0.239899 0.025440 0.043987 +v 0.239758 0.025452 0.044005 +v 0.238089 0.024748 0.044234 +v 0.237919 0.024802 0.044112 +v 0.237269 0.025403 0.042935 +v 0.238000 0.026012 0.042748 +v 0.237188 0.025520 0.042553 +v 0.237977 0.026053 0.042612 +v 0.237347 0.025827 0.041391 +v 0.237431 0.025868 0.041209 +v 0.237597 0.025998 0.041323 +v 0.237794 0.026064 0.041005 +v 0.238454 0.026251 0.040662 +v 0.238918 0.026265 0.040416 +v 0.239751 0.025836 0.039658 +v 0.240384 0.025732 0.039760 +v 0.238466 0.025495 0.042413 +v 0.239173 0.025172 0.043267 +v 0.238896 0.025738 0.041368 +v 0.240032 0.025657 0.041179 +v 0.240738 0.025334 0.042033 +v 0.240309 0.025091 0.043077 +v 0.229311 0.027671 0.024006 +v 0.230041 0.027924 0.024865 +v 0.228991 0.027760 0.024131 +v 0.229950 0.028057 0.025171 +v 0.231109 0.026912 0.022659 +v 0.230845 0.027037 0.022890 +v 0.230315 0.028048 0.025260 +v 0.229714 0.027227 0.023019 +v 0.230930 0.027954 0.025214 +v 0.231172 0.027733 0.024736 +v 0.229221 0.027291 0.023028 +v 0.230016 0.026993 0.022525 +v 0.231575 0.027290 0.023749 +v 0.231930 0.027359 0.024031 +v 0.231419 0.026956 0.022866 +v 0.228723 0.020874 0.027566 +v 0.229685 0.020890 0.027903 +v 0.230436 0.020690 0.027632 +v 0.230866 0.020302 0.026794 +v 0.230503 0.019988 0.025895 +v 0.229979 0.019921 0.025566 +v 0.229161 0.020009 0.025534 +v 0.228509 0.020262 0.025969 +v 0.228311 0.020654 0.026888 +v 0.228614 0.021128 0.027627 +v 0.228807 0.021161 0.027769 +v 0.229465 0.026513 0.025632 +v 0.229724 0.021147 0.028015 +v 0.230382 0.026498 0.025879 +v 0.230188 0.021054 0.027926 +v 0.230846 0.026406 0.025789 +v 0.230591 0.020915 0.027703 +v 0.230756 0.020833 0.027547 +v 0.231414 0.026185 0.025411 +v 0.230994 0.020653 0.027169 +v 0.231652 0.026005 0.025033 +v 0.231087 0.020468 0.026735 +v 0.231077 0.020380 0.026511 +v 0.231735 0.025732 0.024374 +v 0.230668 0.020105 0.025698 +v 0.231326 0.025457 0.023561 +v 0.230285 0.020039 0.025415 +v 0.230943 0.025391 0.023278 +v 0.230064 0.020028 0.025318 +v 0.229353 0.020083 0.025237 +v 0.230011 0.025435 0.023101 +v 0.229120 0.020130 0.025282 +v 0.228698 0.020258 0.025473 +v 0.229356 0.025610 0.023337 +v 0.228368 0.020422 0.025783 +v 0.228165 0.020605 0.026179 +v 0.228823 0.025957 0.024042 +v 0.228139 0.020874 0.026844 +v 0.228797 0.026226 0.024708 +v 0.228865 0.026305 0.024926 +v 0.228310 0.021023 0.027269 +v 0.228968 0.026374 0.025132 +v 0.227708 0.026689 0.025533 +v 0.227580 0.026587 0.025238 +v 0.228554 0.026983 0.026529 +v 0.227873 0.026781 0.025813 +v 0.228392 0.025360 0.022414 +v 0.227943 0.025593 0.022860 +v 0.227452 0.026107 0.023995 +v 0.229449 0.027056 0.026988 +v 0.230444 0.026992 0.027134 +v 0.231223 0.024862 0.022038 +v 0.229901 0.024947 0.021844 +v 0.231990 0.026609 0.026651 +v 0.232821 0.026133 0.025715 +v 0.232545 0.025093 0.023023 +v 0.233053 0.025497 0.024194 +v 0.227598 0.026872 0.025062 +v 0.227478 0.026448 0.023962 +v 0.228116 0.025818 0.022580 +v 0.228448 0.025656 0.022278 +v 0.229481 0.025336 0.021794 +v 0.229711 0.025290 0.021749 +v 0.231342 0.025169 0.021949 +v 0.231963 0.025232 0.022296 +v 0.232622 0.025414 0.022956 +v 0.233076 0.025771 0.023991 +v 0.233094 0.026122 0.024875 +v 0.232901 0.026397 0.025505 +v 0.232047 0.026906 0.026516 +v 0.231652 0.027045 0.026743 +v 0.230524 0.027291 0.027011 +v 0.228530 0.027276 0.026359 +v 0.231914 0.025466 0.022310 +v 0.232637 0.026708 0.024140 +v 0.232613 0.026852 0.024491 +v 0.230548 0.027567 0.026621 +v 0.229558 0.027741 0.026250 +v 0.229709 0.027918 0.025832 +v 0.229640 0.027976 0.025554 +v 0.228973 0.027772 0.025675 +v 0.227965 0.027254 0.025042 +v 0.227890 0.027187 0.024850 +v 0.228691 0.026848 0.022838 +v 0.228230 0.026307 0.022749 +v 0.228360 0.026229 0.022595 +v 0.228913 0.026725 0.022596 +v 0.229871 0.026628 0.022250 +v 0.230025 0.026598 0.022220 +v 0.232092 0.025500 0.022449 +v 0.229238 0.027071 0.024245 +v 0.229967 0.027324 0.025104 +v 0.229640 0.026627 0.023258 +v 0.230772 0.026437 0.023129 +v 0.231501 0.026690 0.023988 +v 0.231099 0.027134 0.024975 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vn 0.0015 0.9882 0.1529 +vn -0.0014 0.9548 0.2973 +vn 0.0014 0.8277 0.5612 +vn -0.0016 0.7159 0.6982 +vn 0.0007 0.4827 0.8758 +vn -0.0003 0.3701 0.9290 +vn 0.0004 -0.0223 0.9998 +vn 0.0003 0.0215 0.9998 +vn 0.0014 -0.4589 0.8885 +vn -0.0007 -0.4244 0.9055 +vn -0.0012 -0.7954 0.6061 +vn 0.0016 -0.8567 0.5158 +vn -0.0017 -0.9948 0.1023 +vn 0.0017 -0.9998 -0.0216 +vn -0.0015 -0.9007 -0.4345 +vn 0.0018 -0.8333 -0.5528 +vn -0.0016 -0.5840 -0.8118 +vn 0.0019 -0.4228 -0.9062 +vn -0.0019 -0.1271 -0.9919 +vn 0.0016 0.0597 -0.9982 +vn -0.0017 0.3969 -0.9178 +vn 0.0019 0.5410 -0.8410 +vn -0.0019 0.7870 -0.6170 +vn 0.0023 0.9234 -0.3838 +vn -0.0017 0.9836 -0.1802 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0168 -0.9986 -0.0495 +vn -0.0103 -0.9991 0.0401 +vn 0.0126 -0.9910 -0.1332 +vn -0.2793 -0.9597 -0.0298 +vn -0.0103 0.9990 0.0442 +vn -0.3027 0.9528 0.0245 +vn -0.0926 0.9748 0.2029 +vn -0.2276 0.9085 0.3505 +vn -0.1102 0.9270 0.3585 +vn -0.2970 0.7198 0.6274 +vn -0.1750 0.8139 0.5540 +vn -0.1310 0.6578 0.7417 +vn -0.2732 0.4500 0.8502 +vn -0.1409 0.4729 0.8698 +vn -0.2797 0.0721 0.9574 +vn -0.1171 0.2844 0.9515 +vn -0.0549 0.0323 0.9980 +vn -0.1137 -0.2003 0.9731 +vn -0.2715 -0.3312 0.9036 +vn -0.1475 -0.4487 0.8814 +vn -0.2723 -0.6322 0.7254 +vn -0.1190 -0.6856 0.7182 +vn -0.2941 -0.7920 0.5350 +vn -0.1848 -0.8700 0.4571 +vn 0.1276 -0.9418 0.3109 +vn -0.2743 -0.9390 0.2074 +vn -0.0907 -0.9726 0.2138 +vn -0.2707 -0.8901 -0.3667 +vn 0.0024 -0.9160 -0.4012 +vn -0.2834 -0.7106 -0.6440 +vn 0.0008 -0.8029 -0.5961 +vn 0.0045 -0.6450 -0.7641 +vn -0.2395 -0.4494 -0.8606 +vn 0.0034 -0.4865 -0.8737 +vn 0.0024 -0.2626 -0.9649 +vn -0.2849 -0.2058 -0.9362 +vn -0.2965 0.1445 -0.9440 +vn 0.0037 -0.0009 -1.0000 +vn 0.0038 0.2700 -0.9628 +vn -0.2365 0.4940 -0.8367 +vn 0.3713 0.3284 -0.8685 +vn -0.2661 0.7140 -0.6477 +vn 0.1971 0.6241 -0.7561 +vn 0.2644 0.7764 -0.5721 +vn -0.2800 0.8890 -0.3624 +vn 0.3185 0.8730 -0.3693 +vn 0.0024 0.9971 -0.0756 +vn 0.2489 -0.0021 0.9685 +vn 0.0638 -0.0164 0.9978 +vn 0.2061 -0.0241 0.9782 +vn 0.0627 0.0086 0.9980 +vn 0.0605 0.0090 0.9981 +vn 0.0495 -0.1142 0.9922 +vn 0.0603 0.0127 0.9981 +vn 0.0224 -0.2889 0.9571 +vn 0.0564 0.0016 0.9984 +vn 0.0565 0.0011 0.9984 +vn 0.0596 -0.0356 0.9976 +vn 0.0470 -0.6699 0.7409 +vn 0.0003 -0.4589 0.8885 +vn 0.1331 -0.8970 0.4214 +vn 0.0942 -0.7099 0.6980 +vn 0.0506 -0.5518 0.8324 +vn -0.0097 -0.9999 0.0068 +vn -0.0050 -1.0000 0.0061 +vn -0.0104 -0.9999 0.0064 +vn -0.0018 -1.0000 0.0021 +vn -0.0160 -0.9999 0.0042 +vn 0.1603 -0.9837 0.0817 +vn 0.0053 -1.0000 0.0039 +vn 0.0093 -1.0000 0.0028 +vn 0.5000 -0.7974 0.3379 +vn 0.0077 -1.0000 -0.0009 +vn -0.0000 -1.0000 -0.0000 +vn -0.0000 -1.0000 0.0020 +vn 0.0002 -1.0000 0.0011 +vn 0.4460 -0.8782 0.1729 +vn -0.0008 -1.0000 0.0040 +vn -0.3709 0.5927 0.7149 +vn -0.3392 0.4569 0.8223 +vn -0.4844 0.5062 0.7135 +vn -0.3779 0.7833 0.4937 +vn -0.3744 0.7409 0.5575 +vn -0.3968 -0.6579 0.6401 +vn -0.4198 -0.7495 0.5118 +vn -0.5141 -0.5143 0.6864 +vn -0.3792 -0.4852 0.7879 +vn -0.0063 1.0000 0.0054 +vn -0.1129 0.9828 0.1462 +vn -0.0207 0.9998 0.0034 +vn -0.0007 1.0000 -0.0017 +vn -0.0029 -1.0000 0.0019 +vn -0.0128 -0.9999 0.0008 +vn -0.0737 -0.9934 0.0876 +vn -0.0005 -1.0000 0.0055 +vn -0.3012 0.8721 0.3856 +vn -0.2296 0.1752 0.9574 +vn -0.2198 -0.2168 0.9512 +vn 0.9870 -0.0053 -0.1609 +vn 0.9919 0.0139 -0.1264 +vn 0.9898 0.0049 -0.1425 +vn 0.9937 0.0231 -0.1098 +vn 0.9046 -0.0329 0.4250 +vn 0.8588 0.0204 0.5119 +vn 0.8790 -0.0015 0.4769 +vn 0.8290 0.0497 0.5570 +vn 0.3355 -0.0580 0.9402 +vn 0.2806 -0.0189 0.9596 +vn 0.3004 -0.0329 0.9532 +vn 0.2374 0.0113 0.9713 +vn 0.6397 0.0447 -0.7673 +vn 0.7663 -0.0142 -0.6424 +vn 0.5707 -0.0248 -0.8208 +vn 0.2383 0.0435 -0.9702 +vn -0.1581 -0.0433 -0.9865 +vn -0.5504 0.0449 -0.8337 +vn -0.8281 -0.0402 -0.5591 +vn -0.8788 0.0280 -0.4764 +vn -0.9699 -0.0629 -0.2351 +vn -0.9586 0.0589 0.2786 +vn -0.9493 0.0356 0.3124 +vn -0.9531 0.0446 0.2995 +vn -0.9403 0.0162 0.3400 +vn -0.4436 -0.0019 0.8962 +vn -0.4998 -0.0461 0.8649 +vn -0.4628 -0.0168 0.8863 +vn -0.4025 0.0291 0.9150 +vn -0.0093 0.8127 0.5826 +vn 0.1766 0.8882 0.4242 +vn 0.0037 0.9992 0.0409 +vn -0.0098 0.9997 0.0217 +vn -0.0125 0.9999 0.0105 +vn -0.0116 0.9997 0.0203 +vn 0.0304 0.9989 -0.0369 +vn 0.3743 0.8919 -0.2538 +vn 0.3576 0.9329 -0.0434 +vn 0.0111 0.9999 -0.0002 +vn 0.0192 0.9997 0.0161 +vn 0.3535 0.9098 0.2174 +vn -0.0307 -0.9995 0.0090 +vn -0.0053 -0.9994 0.0329 +vn -0.0419 -0.9991 0.0056 +vn -0.0693 -0.9975 -0.0120 +vn 0.0337 -0.9990 0.0306 +vn 0.0323 -0.9992 -0.0256 +vn 0.0333 -0.9992 -0.0216 +vn 0.0326 -0.9993 0.0203 +vn 0.4360 -0.8551 0.2805 +vn 0.0296 -0.9995 0.0145 +vn 0.9869 -0.0062 -0.1610 +vn 0.9952 0.0311 -0.0929 +vn 0.9928 -0.0209 0.1178 +vn 0.9360 0.0398 0.3498 +vn 0.6754 -0.0411 0.7363 +vn 0.3970 0.0345 0.9172 +vn 0.2345 -0.0281 0.9717 +vn 0.0497 0.0619 0.9968 +vn -0.4998 -0.0625 0.8639 +vn -0.5982 0.0027 0.8014 +vn -0.7699 -0.0298 0.6375 +vn -0.8821 0.0361 0.4697 +vn -0.9989 -0.0352 0.0318 +vn -0.9688 0.0361 -0.2454 +vn -0.9090 -0.0167 -0.4164 +vn -0.8018 0.0827 -0.5919 +vn -0.3432 -0.0555 -0.9376 +vn -0.2564 -0.0004 -0.9666 +vn -0.2818 -0.0163 -0.9593 +vn -0.1896 0.0408 -0.9810 +vn 0.3628 -0.0551 -0.9303 +vn 0.5314 0.0234 -0.8468 +vn 0.5927 -0.0132 -0.8053 +vn 0.7790 0.3247 0.5364 +vn 0.8635 0.2265 0.4506 +vn 0.8202 0.0100 0.5720 +vn 0.8174 -0.0046 0.5761 +vn 0.8862 -0.0021 0.4634 +vn 0.8176 -0.0052 0.5758 +vn 0.8671 0.3748 0.3282 +vn 0.9371 0.0010 0.3490 +vn -0.0046 1.0000 0.0056 +vn -0.0026 1.0000 0.0022 +vn 0.0000 1.0000 0.0000 +vn 0.2161 0.9699 0.1126 +vn 0.4708 0.8223 0.3197 +vn 0.0136 0.9999 0.0051 +vn 0.0081 1.0000 -0.0013 +vn 0.0113 0.9999 0.0041 +vn 0.3904 0.9082 0.1510 +vn -0.0120 0.9999 0.0056 +vn -0.0099 0.9999 0.0105 +vn 0.0001 1.0000 0.0020 +vn -0.0001 1.0000 0.0006 +vn -0.0158 0.9999 0.0050 +vn -0.0149 0.9998 0.0125 +vn 0.4413 -0.0188 0.8972 +vn 0.6279 0.0088 0.7783 +vn 0.6650 -0.0122 0.7467 +vn 0.8576 -0.0165 0.5140 +vn 0.9212 0.0147 0.3889 +vn 0.9882 -0.0228 0.1514 +vn 0.9936 0.0100 -0.1129 +vn 0.9769 -0.0119 -0.2132 +vn 0.8618 -0.0179 -0.5070 +vn 0.8617 -0.0085 -0.5073 +vn 0.7137 -0.0176 -0.7002 +vn 0.7005 -0.0684 -0.7104 +vn 0.6879 -0.1083 -0.7177 +vn 0.8594 0.0048 -0.5112 +vn 0.6223 0.4136 -0.6646 +vn 0.8186 0.0222 -0.5739 +vn 0.6391 -0.3478 -0.6860 +vn 0.7047 0.0665 -0.7063 +vn 0.7043 0.0408 -0.7087 +vn 0.5593 0.3575 -0.7479 +vn 0.7044 -0.0840 -0.7048 +vn 0.7261 0.0048 -0.6876 +vn 0.0521 -0.0164 0.9985 +vn 0.0556 -0.0046 0.9984 +vn 0.0289 0.1140 0.9931 +vn 0.0061 0.2866 0.9580 +vn 0.1916 0.0310 0.9810 +vn 0.0677 0.0108 0.9976 +vn 0.2433 0.0043 0.9699 +vn 0.0707 0.0251 0.9972 +vn 0.0595 -0.0188 0.9981 +vn 0.0565 -0.0007 0.9984 +vn 0.5128 0.0231 0.8582 +vn 0.6339 -0.0117 0.7733 +vn 0.7656 0.0226 0.6429 +vn 0.9212 -0.0025 0.3891 +vn 0.9204 0.0311 0.3897 +vn 0.9997 0.0204 0.0138 +vn 0.9943 -0.0097 -0.1062 +vn 0.9403 0.0278 -0.3392 +vn 0.4941 -0.8319 -0.2527 +vn 0.6436 -0.7304 -0.2287 +vn 0.5645 -0.7890 -0.2428 +vn 0.4158 -0.8711 -0.2613 +vn -0.0667 -0.9977 -0.0069 +vn -0.1203 -0.9902 0.0707 +vn -0.0907 -0.9955 0.0276 +vn -0.1573 -0.9796 0.1248 +vn -0.8289 -0.4294 0.3585 +vn -0.6415 -0.6646 0.3832 +vn -0.7305 -0.5696 0.3768 +vn -0.8746 -0.3425 0.3431 +vn -0.8232 0.2748 0.4968 +vn -0.6683 0.7028 0.2439 +vn 0.0475 0.9972 -0.0579 +vn -0.1564 0.9770 0.1451 +vn 0.2103 0.9762 -0.0537 +vn 0.3104 0.9322 -0.1862 +vn 0.5931 0.7855 -0.1768 +vn 0.8893 -0.0256 -0.4565 +vn 0.8571 0.0494 -0.5127 +vn 0.8617 0.0399 -0.5058 +vn 0.8315 0.0984 -0.5468 +vn -0.2395 0.9597 0.1473 +vn -0.2131 0.9648 0.1542 +vn -0.2238 0.9628 0.1514 +vn -0.1986 0.9673 0.1579 +vn 0.4848 0.8319 -0.2700 +vn 0.6463 0.7220 -0.2470 +vn 0.5900 0.7655 -0.2565 +vn 0.7175 0.6569 -0.2320 +vn 0.8150 0.2220 -0.5353 +vn -0.2789 -0.9345 0.2211 +vn -0.2089 -0.9707 0.1191 +vn -0.2375 -0.9580 0.1604 +vn -0.1419 -0.9896 0.0241 +vn 0.7284 -0.6201 -0.2913 +vn 0.6454 -0.6847 -0.3384 +vn 0.7206 -0.6269 -0.2962 +vn 0.7928 -0.5571 -0.2472 +vn -0.8667 -0.1183 0.4847 +vn -0.8664 -0.2568 0.4283 +vn -0.8465 -0.3907 0.3617 +vn -0.8532 -0.0072 0.5215 +vn -0.7929 0.5248 0.3097 +vn 0.4461 -0.0001 0.8950 +vn 0.4461 -0.0000 0.8950 +vn 0.4460 0.0003 0.8951 +vn -0.4408 -0.0047 -0.8976 +vn -0.4461 0.0001 -0.8950 +vn -0.4462 0.0008 -0.8949 +vn -0.4460 -0.0001 -0.8950 +vn -0.4415 -0.0041 -0.8972 +vn 0.4475 -0.0069 0.8942 +vn 0.4464 -0.0005 0.8948 +vn 0.4494 -0.0030 0.8934 +vn 0.6991 -0.5910 0.4025 +vn 0.7166 -0.6938 0.0714 +vn 0.7240 -0.6839 0.0900 +vn 0.6815 -0.6840 -0.2601 +vn 0.6287 -0.7756 -0.0561 +vn 0.3289 -0.7924 0.5137 +vn 0.4820 -0.6999 0.5270 +vn 0.5650 -0.7358 -0.3734 +vn 0.4365 -0.7907 -0.4293 +vn 0.4371 -0.7196 -0.5395 +vn 0.4599 -0.5860 -0.6671 +vn 0.5986 -0.2897 -0.7468 +vn 0.5851 0.0808 -0.8069 +vn 0.7226 -0.2081 -0.6592 +vn 0.5894 0.6572 -0.4697 +vn 0.6099 -0.0582 -0.7903 +vn 0.5758 0.7911 -0.2066 +vn 0.6039 0.7938 0.0719 +vn 0.8025 0.5966 0.0085 +vn 0.5305 0.8297 0.1735 +vn 0.8023 0.5774 0.1517 +vn 0.3874 0.8189 0.4235 +vn 0.3609 0.7075 0.6076 +vn 0.0982 0.7980 0.5946 +vn 0.0367 0.5862 0.8093 +vn 0.0304 0.5596 0.8282 +vn -0.5528 0.7883 0.2700 +vn -0.5769 0.7558 0.3098 +vn -0.5200 0.8257 0.2186 +vn -0.6011 0.7173 0.3523 +vn -0.9056 0.0614 0.4197 +vn -0.8938 0.0120 0.4483 +vn -0.9204 0.1673 0.3533 +vn -0.8557 -0.1008 0.5076 +vn -0.5958 -0.7595 0.2611 +vn -0.6027 -0.7485 0.2768 +vn -0.6003 -0.7523 0.2714 +vn -0.6055 -0.7436 0.2834 +vn -0.6545 0.7042 0.2753 +vn -0.6702 0.6664 0.3267 +vn -0.6609 0.6899 0.2954 +vn -0.6359 0.7389 0.2227 +vn -0.8463 0.0514 0.5302 +vn -0.7824 -0.5399 0.3105 +vn -0.7350 -0.5944 0.3264 +vn -0.8689 -0.4141 0.2711 +vn -0.5878 -0.7245 0.3601 +vn 0.6334 0.6990 0.3319 +vn 0.5478 -0.7859 0.2869 +vn 0.6038 -0.6833 0.4105 +vn 0.7382 -0.5557 0.3824 +vn 0.6633 -0.7038 0.2544 +vn -0.4894 -0.8611 -0.1376 +vn -0.4877 -0.7431 -0.4582 +vn -0.4670 -0.4830 -0.7407 +vn -0.4852 -0.0513 -0.8729 +vn -0.4621 0.3750 -0.8036 +vn -0.5094 0.6933 -0.5097 +vn -0.4378 0.8842 -0.1631 +vn -0.4853 0.8013 0.3497 +vn -0.4833 0.5378 0.6908 +vn -0.4650 0.2316 0.8545 +vn -0.4335 -0.1607 0.8867 +vn -0.5020 -0.5068 0.7008 +vn -0.4447 -0.8267 0.3447 +vn -1.0000 -0.0001 0.0001 +vn -1.0000 -0.0003 -0.0001 +vn -1.0000 -0.0004 -0.0000 +vn -1.0000 -0.0002 -0.0001 +vn -1.0000 -0.0003 0.0007 +vn -1.0000 0.0001 0.0001 +vn -1.0000 0.0001 0.0000 +vn -1.0000 -0.0005 -0.0002 +vn -1.0000 -0.0004 -0.0001 +vn 0.4461 0.0001 0.8950 +vn 0.4503 -0.0015 0.8929 +vn 0.4485 -0.0059 0.8938 +vn -0.4340 -0.0109 -0.9009 +vn 0.4458 -0.0017 0.8952 +vn 0.4379 -0.0101 0.8990 +vn 0.4465 -0.0017 0.8948 +vn 0.4538 -0.0070 0.8911 +vn 0.4524 -0.0059 0.8918 +vn 0.4622 -0.0150 0.8866 +vn -0.4411 -0.0054 -0.8974 +vn -0.4461 0.0000 -0.8950 +vn -0.4419 -0.0045 -0.8970 +vn 0.4461 -0.0002 0.8950 +vn -0.4360 -0.0109 -0.8999 +vn 0.4462 0.0002 0.8949 +vn -0.2648 -0.9158 0.3021 +vn 0.0725 0.9862 0.1491 +vn 0.0207 0.9943 0.1046 +vn 0.0862 0.9955 0.0399 +vn 0.0967 0.9951 0.0202 +vn 0.0983 0.9952 0.0012 +vn -0.1089 0.9921 0.0623 +vn -0.0643 0.9955 0.0692 +vn -0.0140 0.9952 0.0964 +vn -0.0203 0.9951 0.0964 +vn 0.1160 0.9881 -0.1007 +vn 0.0991 0.9938 -0.0513 +vn 0.0530 0.9950 -0.0843 +vn -0.0413 0.9975 -0.0568 +vn -0.0584 0.9950 -0.0809 +vn -0.1525 0.9881 -0.0181 +vn -0.0739 0.9967 -0.0327 +vn -0.1038 0.9943 0.0229 +vn -0.0145 0.9948 -0.1005 +vn -0.0326 0.9950 -0.0940 +vn 0.9962 -0.0085 0.0862 +vn 0.9538 0.0079 0.3003 +vn 0.8778 -0.0057 0.4791 +vn 0.8102 0.0068 0.5861 +vn 0.3930 -0.0105 0.9195 +vn 0.1233 0.0126 0.9923 +vn 0.0330 -0.0125 0.9994 +vn -0.2741 0.0120 0.9616 +vn -0.3533 -0.0137 0.9354 +vn -0.6097 0.0106 0.7926 +vn -0.9470 -0.0089 0.3212 +vn -0.9253 -0.0015 0.3794 +vn -0.9275 -0.0023 0.3737 +vn -0.9483 -0.0094 0.3174 +vn -0.8881 -0.0090 -0.4596 +vn -0.9483 0.0094 -0.3174 +vn -0.9432 0.0076 -0.3320 +vn -0.8808 -0.0109 -0.4733 +vn -0.1866 -0.0098 -0.9824 +vn -0.3835 0.0094 -0.9235 +vn -0.0947 0.0088 -0.9955 +vn 0.2003 -0.0117 -0.9797 +vn 0.5494 0.0093 -0.8355 +vn 0.7922 -0.0109 -0.6102 +vn 0.9508 0.0089 -0.3095 +vn -0.0151 -0.9978 -0.0648 +vn -0.0010 -0.9978 -0.0669 +vn 0.0562 -0.9832 -0.1735 +vn 0.0786 -0.9897 -0.1200 +vn 0.0965 -0.9903 -0.1002 +vn -0.0436 -0.9935 0.1047 +vn -0.0653 -0.9917 0.1109 +vn -0.0772 -0.9967 0.0265 +vn -0.0813 -0.9965 0.0210 +vn -0.1341 -0.9901 -0.0425 +vn 0.0767 -0.9942 0.0752 +vn 0.0697 -0.9937 0.0881 +vn -0.0063 -0.9936 0.1124 +vn 0.0071 -0.9975 0.0705 +vn 0.1174 -0.9923 -0.0401 +vn 0.2722 -0.9620 -0.0195 +vn 0.1065 -0.9942 0.0120 +vn -0.1428 -0.9894 -0.0277 +vn -0.0684 -0.9970 -0.0358 +vn -0.9918 0.0067 0.1275 +vn -0.9970 -0.0032 -0.0777 +vn -0.9384 -0.0060 0.3454 +vn -0.7187 0.0084 0.6953 +vn -0.7033 -0.0030 0.7109 +vn -0.3285 0.0030 0.9445 +vn -0.2515 0.0037 0.9679 +vn 0.2663 0.0037 0.9639 +vn 0.0557 -0.0001 0.9984 +vn 0.4272 -0.0014 0.9042 +vn 0.6980 0.0022 0.7161 +vn 0.7423 -0.0024 0.6701 +vn 0.9365 0.0003 0.3507 +vn 0.9217 -0.0045 0.3879 +vn 0.9992 -0.0001 -0.0401 +vn 0.9951 0.0039 -0.0988 +vn 0.8704 -0.0008 -0.4924 +vn 0.8667 -0.0008 -0.4989 +vn 0.4904 -0.0052 -0.8715 +vn 0.5686 0.0019 -0.8226 +vn 0.1717 0.0029 -0.9851 +vn -0.0224 -0.0083 -0.9997 +vn -0.2906 0.0031 -0.9568 +vn -0.5146 0.0051 -0.8574 +vn -0.6905 0.0071 -0.7233 +vn -0.8636 0.0064 -0.5041 +vn -0.9214 0.0058 -0.3886 +vn 0.2460 -0.8031 0.5427 +vn -0.1491 -0.8450 0.5136 +vn -0.5122 -0.8234 -0.2443 +vn -0.7083 0.1241 -0.6949 +vn -0.2418 -0.7766 -0.5818 +vn 0.4947 -0.8684 -0.0346 +vn -0.1689 0.8754 -0.4529 +vn 0.5105 0.8455 0.1568 +vn 1.0000 -0.0003 -0.0000 +vn 1.0000 -0.0011 0.0001 +vn 1.0000 0.0000 0.0001 +vn 1.0000 -0.0001 -0.0000 +vn 1.0000 0.0001 -0.0000 +vn 1.0000 -0.0006 0.0006 +vn 1.0000 0.0006 -0.0001 +vn 0.4093 -0.0127 0.9123 +vn 0.4257 -0.0233 0.9046 +vn 0.4152 0.0104 0.9097 +vn 0.4381 0.0309 0.8984 +vn 0.4235 0.0355 0.9052 +vn 0.4422 -0.0344 0.8962 +vn 0.4662 -0.0324 0.8841 +vn 0.4716 -0.0115 0.8818 +vn 0.4789 0.0042 0.8779 +vn 0.4596 0.0316 0.8876 +vn -0.4416 0.0244 -0.8969 +vn -0.4734 -0.1205 -0.8726 +vn -0.5774 -0.0670 -0.8137 +vn -0.4488 -0.0431 -0.8926 +vn -0.5270 0.1934 -0.8275 +vn -0.9168 0.1713 0.3607 +vn -0.8910 0.0736 0.4480 +vn -0.9096 0.1905 0.3692 +vn -0.4568 0.8568 0.2393 +vn -0.4405 0.8691 0.2249 +vn -0.3518 0.9243 0.1478 +vn -0.3319 0.9342 0.1308 +vn 0.3693 0.9033 -0.2185 +vn 0.4582 0.8559 -0.2398 +vn 0.5706 0.7552 -0.3227 +vn 0.7763 0.5033 -0.3794 +vn 0.8740 0.0633 -0.4818 +vn 0.9026 -0.0285 -0.4296 +vn 0.7954 -0.4107 -0.4457 +vn 0.4304 -0.8716 -0.2348 +vn 0.4032 -0.8908 -0.2094 +vn 0.4249 -0.8757 -0.2296 +vn 0.3989 -0.8937 -0.2055 +vn -0.4393 -0.8797 0.1823 +vn -0.4746 -0.8528 0.2179 +vn -0.4464 -0.8746 0.1894 +vn -0.4827 -0.8461 0.2262 +vn -0.8892 0.0466 0.4552 +vn -0.5264 -0.0464 -0.8490 +vn -0.5075 -0.0840 -0.8576 +vn -0.5392 0.0017 -0.8422 +vn -0.4425 0.1066 -0.8904 +vn -0.3939 0.0954 -0.9142 +vn -0.3671 0.0498 -0.9288 +vn -0.3563 0.0358 -0.9337 +vn -0.3613 -0.0581 -0.9307 +vn -0.3486 -0.0372 -0.9365 +vn -0.5223 0.0568 -0.8509 +vn -0.4563 -0.1102 -0.8830 +vn -0.5247 0.0701 -0.8484 +vn -0.4728 0.1074 -0.8746 +vn -0.4174 -0.1024 -0.9029 +vn -0.8340 0.3162 0.4522 +vn -0.9122 -0.0361 0.4081 +vn -0.8122 -0.3649 0.4551 +vn -0.7577 -0.5306 0.3800 +vn -0.5667 -0.7181 0.4041 +vn -0.2746 -0.9615 -0.0098 +vn 0.2900 -0.9569 -0.0173 +vn 0.7655 -0.5274 -0.3685 +vn 0.5769 -0.7154 -0.3943 +vn 0.8092 -0.3709 -0.4557 +vn 0.8810 -0.2474 -0.4034 +vn 0.8589 0.0288 -0.5114 +vn 0.7661 0.5694 -0.2982 +vn 0.7293 0.6070 -0.3157 +vn 0.7412 0.5952 -0.3103 +vn 0.6938 0.6397 -0.3309 +vn -0.0081 0.9991 0.0407 +vn 0.0827 0.9916 -0.0996 +vn -0.2098 0.9745 0.0795 +vn -0.4347 0.8598 0.2679 +vn -0.7357 0.5924 0.3283 +vn -0.2855 0.9584 0.0038 +vn -0.3449 0.9224 0.1738 +vn -0.3435 0.9238 0.1694 +vn -0.3916 0.8575 0.3337 +vn 0.8029 -0.2564 -0.5382 +vn 0.8886 -0.1268 -0.4408 +vn 0.8867 -0.1302 -0.4435 +vn 0.9434 0.0036 -0.3317 +vn -0.6828 -0.7022 0.2018 +vn -0.5413 -0.7958 0.2715 +vn -0.5452 -0.7937 0.2698 +vn -0.3858 -0.8613 0.3306 +vn 0.4460 -0.0000 0.8950 +vn -0.6751 -0.3894 -0.6266 +vn 0.0667 -0.0033 -0.9978 +vn -0.6676 0.3520 -0.6560 +vn -0.9672 0.1850 0.1739 +vn 0.4133 0.0081 0.9105 +vn 0.4123 0.0204 0.9108 +vn 0.4128 -0.0158 0.9107 +vn 0.4429 0.0368 0.8958 +vn 0.4771 -0.0134 0.8787 +vn 0.4663 -0.0386 0.8838 +vn 0.4854 -0.0104 0.8742 +vn 0.4332 -0.0335 0.9007 +vn 0.4330 -0.0341 0.9007 +vn 0.4746 0.0227 0.8799 +vn 0.4559 0.0311 0.8895 +vn -0.3968 -0.1508 -0.9054 +vn -0.4156 0.1242 -0.9010 +vn -0.3722 -0.1961 -0.9072 +vn -0.4313 0.1310 -0.8926 +vn -0.4884 0.8643 0.1201 +vn -0.5445 0.7979 0.2587 +vn -0.5271 0.8143 0.2429 +vn -0.4658 0.8732 0.1432 +vn 0.1130 0.9932 -0.0281 +vn 0.5283 0.7614 -0.3758 +vn 0.7062 0.6147 -0.3512 +vn 0.5410 0.7419 -0.3961 +vn 0.7348 0.5779 -0.3552 +vn 0.8563 -0.2459 -0.4542 +vn 0.8530 -0.2702 -0.4466 +vn 0.8557 -0.2507 -0.4527 +vn 0.8523 -0.2744 -0.4453 +vn 0.5470 -0.7777 -0.3098 +vn 0.3907 -0.9006 -0.1902 +vn 0.5284 -0.7960 -0.2953 +vn 0.3700 -0.9124 -0.1748 +vn -0.2194 -0.9725 0.0783 +vn -0.3465 -0.9197 0.1847 +vn -0.2465 -0.9639 0.1008 +vn -0.3710 -0.9056 0.2056 +vn -0.8990 -0.1659 0.4054 +vn -0.8940 -0.0278 0.4473 +vn -0.8995 -0.1336 0.4160 +vn -0.8898 0.0070 0.4564 +vn -0.5258 -0.0597 -0.8485 +vn -0.5384 -0.0687 -0.8399 +vn -0.5305 0.0263 -0.8473 +vn -0.3887 0.0987 -0.9161 +vn -0.3733 0.0932 -0.9230 +vn -0.3541 0.0302 -0.9347 +vn -0.3500 0.0028 -0.9367 +vn -0.3693 -0.0725 -0.9265 +vn -0.5216 0.0616 -0.8509 +vn -0.4618 0.1034 -0.8809 +vn -0.4771 0.0942 -0.8738 +vn -0.3830 -0.0925 -0.9191 +vn -0.4361 -0.1041 -0.8939 +vn -0.4632 -0.1026 -0.8803 +vn -0.8458 0.0751 0.5283 +vn -0.8900 -0.0764 0.4494 +vn -0.8798 -0.0316 0.4744 +vn -0.9051 -0.1895 0.3805 +vn -0.5997 -0.7208 0.3476 +vn -0.5691 -0.7730 0.2803 +vn -0.5804 -0.7554 0.3042 +vn -0.5455 -0.8052 0.2328 +vn 0.1220 -0.9925 -0.0117 +vn 0.1649 -0.9823 -0.0892 +vn 0.1526 -0.9860 -0.0667 +vn 0.1948 -0.9702 -0.1442 +vn 0.7350 -0.5893 -0.3355 +vn 0.7564 -0.5103 -0.4092 +vn 0.7505 -0.5362 -0.3863 +vn 0.7649 -0.4590 -0.4519 +vn 0.9150 0.1915 -0.3550 +vn 0.8337 0.3486 -0.4282 +vn 0.8583 0.3082 -0.4104 +vn 0.7510 0.4600 -0.4736 +vn 0.2844 0.9488 -0.1378 +vn 0.2521 0.9667 -0.0439 +vn 0.2771 0.9538 -0.1161 +vn 0.3055 0.9302 -0.2036 +vn -0.4150 0.8686 0.2707 +vn -0.5503 0.8008 0.2365 +vn -0.5297 0.8129 0.2423 +vn -0.6454 0.7355 0.2062 +vn -0.3956 0.8970 0.1971 +vn -0.4227 0.8669 0.2642 +vn -0.4298 0.8575 0.2826 +vn -0.4517 0.8240 0.3420 +vn 0.7387 0.4679 -0.4852 +vn 0.7357 0.5191 -0.4351 +vn 0.7340 0.5342 -0.4194 +vn 0.7250 0.5863 -0.3613 +vn 0.3956 -0.8970 -0.1971 +vn 0.4655 -0.8669 -0.1784 +vn 0.4845 -0.8575 -0.1730 +vn 0.5451 -0.8240 -0.1547 +vn -0.8322 -0.4679 0.2976 +vn -0.7903 -0.5191 0.3254 +vn -0.7768 -0.5342 0.3335 +vn -0.7251 -0.5863 0.3613 +vn 0.4462 -0.0001 0.8949 +vn -0.9149 -0.1039 -0.3901 +vn -0.9096 -0.1062 -0.4016 +vn -0.8937 -0.1127 -0.4344 +vn -0.8877 -0.1149 -0.4459 +vn -0.4116 -0.8184 -0.4010 +vn -0.3104 -0.4858 -0.8171 +vn 0.1377 0.0197 -0.9903 +vn 0.3935 0.7185 -0.5735 +vn -0.3888 0.4299 -0.8149 +vn -0.5336 0.8454 -0.0233 +vn -0.0384 0.9991 -0.0158 +vn 0.0365 0.9992 0.0150 +vn -0.0364 0.9992 -0.0150 +vn 0.0384 0.9991 0.0158 +vn -0.3800 0.0019 0.9250 +vn -0.3045 -0.0018 0.9525 +vn -0.3778 0.0018 0.9259 +vn -0.3023 -0.0019 0.9532 +vn -0.0396 -0.9991 -0.0126 +vn 0.0376 -0.9992 0.0120 +vn -0.0376 -0.9992 -0.0120 +vn 0.0396 -0.9991 0.0126 +vn 0.3811 0.0019 -0.9245 +vn 0.3045 -0.0018 -0.9525 +vn 0.3789 0.0018 -0.9254 +vn 0.3023 -0.0019 -0.9532 +vn 0.9397 -0.0000 0.3420 +vn -0.9397 -0.0000 -0.3420 +vn -0.0330 0.9991 -0.0252 +vn 0.0313 0.9992 0.0239 +vn -0.0314 0.9992 -0.0239 +vn 0.0330 0.9991 0.0252 +vn -0.6078 0.0019 0.7941 +vn -0.5410 -0.0018 0.8410 +vn -0.6059 0.0018 0.7955 +vn -0.5390 -0.0019 0.8423 +vn -0.0349 -0.9991 -0.0224 +vn 0.0332 -0.9992 0.0213 +vn -0.0332 -0.9992 -0.0213 +vn 0.0349 -0.9991 0.0224 +vn 0.6070 0.0019 -0.7947 +vn 0.5409 -0.0018 -0.8411 +vn 0.6051 0.0018 -0.7961 +vn 0.5390 -0.0019 -0.8423 +vn 0.8191 -0.0000 0.5736 +vn 0.8192 0.0000 0.5736 +vn -0.8191 0.0000 -0.5736 +vn -0.0004 1.0000 0.0088 +vn 0.0046 1.0000 -0.0084 +vn 0.0113 0.9991 -0.0398 +vn -0.0035 0.9983 -0.0587 +vn 0.0597 0.9539 -0.2940 +vn 0.0032 1.0000 -0.0014 +vn 0.0038 0.9998 -0.0206 +vn -0.2873 0.9286 -0.2350 +vn -0.0453 0.9990 0.0026 +vn 0.0280 0.9995 0.0166 +vn -0.0009 0.9999 0.0134 +vn 0.0007 0.9994 -0.0336 +vn 0.0033 1.0000 -0.0049 +vn 0.2842 0.9016 -0.3262 +vn 0.0004 1.0000 -0.0040 +vn 0.0008 1.0000 0.0020 +vn 0.2192 0.9699 -0.1057 +vn -0.0327 0.9994 -0.0062 +vn 0.1794 0.9838 0.0039 +vn 0.0102 0.9999 0.0080 +vn 0.2306 0.9682 0.0969 +vn 0.2723 0.9348 0.2281 +vn 0.0011 1.0000 0.0002 +vn -0.0009 1.0000 -0.0023 +vn -0.0012 1.0000 -0.0028 +vn -0.0062 0.9997 -0.0215 +vn -0.0010 1.0000 -0.0072 +vn -0.0042 0.9999 -0.0154 +vn -0.0081 0.9999 -0.0116 +vn -0.0002 1.0000 -0.0003 +vn -0.0002 1.0000 -0.0007 +vn 0.0107 0.9999 -0.0020 +vn 0.0071 1.0000 -0.0003 +vn 0.0007 1.0000 0.0033 +vn 0.0368 0.9989 -0.0279 +vn -0.0007 1.0000 0.0016 +vn -0.2844 0.8998 0.3309 +vn 0.0088 0.9999 -0.0115 +vn 0.0049 0.9998 0.0173 +vn -0.4848 0.8746 0.0112 +vn -0.4424 0.8875 0.1293 +vn -0.3669 0.9217 -0.1259 +vn -0.0054 0.9999 -0.0088 +vn -0.0305 0.9991 -0.0296 +vn -0.0001 1.0000 -0.0017 +vn 0.0009 0.9999 0.0110 +vn -0.0028 0.9988 0.0487 +vn -0.0003 0.9997 0.0254 +vn 0.1914 0.9679 -0.1630 +vn 0.0000 1.0000 0.0002 +vn 0.2742 0.8786 -0.3909 +vn -0.0042 1.0000 0.0054 +vn -0.0059 1.0000 0.0052 +vn 0.0118 0.9999 -0.0069 +vn -0.0002 1.0000 0.0091 +vn 0.0036 1.0000 0.0016 +vn 0.1441 0.0042 0.9896 +vn -0.0399 0.0146 0.9991 +vn -0.0459 0.0640 0.9969 +vn -0.0652 0.3277 0.9425 +vn -0.0590 0.3023 0.9514 +vn -0.0058 0.0855 0.9963 +vn -0.0008 -0.9999 -0.0144 +vn 0.0130 -0.9996 -0.0257 +vn 0.0053 -0.9997 -0.0224 +vn -0.0165 -0.9998 0.0063 +vn 0.0005 -0.9998 0.0212 +vn -0.1060 -0.9448 -0.3101 +vn -0.0072 -0.9997 0.0243 +vn 0.0264 -0.9977 -0.0623 +vn 0.0104 -0.9990 -0.0433 +vn -0.0065 -1.0000 -0.0015 +vn 0.1821 -0.9833 -0.0003 +vn 0.2191 -0.9704 0.1012 +vn -0.0199 -0.9882 -0.1520 +vn -0.1167 -0.9927 0.0321 +vn -0.2033 -0.9785 0.0346 +vn -0.0234 -0.9992 -0.0320 +vn -0.0317 -0.9983 -0.0488 +vn -0.0386 -0.9915 -0.1241 +vn -0.0155 -0.9947 -0.1014 +vn -0.0773 -0.9958 -0.0481 +vn -0.0417 -0.9981 -0.0452 +vn -0.0010 -0.9923 -0.1237 +vn -0.0213 -0.9994 -0.0289 +vn -0.8495 0.0068 -0.5276 +vn -0.8791 -0.0128 -0.4764 +vn -0.8784 -0.0047 -0.4779 +vn -0.8889 -0.0162 -0.4578 +vn -0.9000 -0.0098 -0.4358 +vn 0.0001 -1.0000 -0.0001 +vn 0.0009 -1.0000 -0.0008 +vn 0.0015 -1.0000 -0.0014 +vn 0.0804 0.3931 -0.9160 +vn 0.0617 0.0031 -0.9981 +vn 0.2686 0.2406 -0.9327 +vn 0.4972 0.0188 -0.8674 +vn 0.5252 -0.0101 -0.8509 +vn 0.7159 0.1504 -0.6818 +vn 0.7589 0.0221 -0.6509 +vn 0.8065 0.0183 -0.5910 +vn 0.7243 0.0021 -0.6895 +vn 0.3394 0.0387 -0.9398 +vn 0.2935 0.0121 -0.9559 +vn 0.1505 0.0032 -0.9886 +vn 0.2546 -0.0106 -0.9670 +vn 0.0457 -0.0058 -0.9989 +vn 0.2953 -0.9484 -0.1159 +vn 0.0844 -0.9729 0.2153 +vn 0.0395 -0.9992 -0.0097 +vn 0.2714 -0.9309 0.2445 +vn 0.2761 -0.1943 -0.9413 +vn 0.0320 -0.2483 -0.9681 +vn 0.0538 -0.1261 -0.9906 +vn 0.0571 -0.3717 -0.9266 +vn 0.2724 -0.4594 -0.8455 +vn 0.0693 -0.5069 -0.8592 +vn 0.0700 -0.6543 -0.7530 +vn 0.0960 -0.7516 -0.6526 +vn -0.1324 -0.9449 0.2992 +vn 0.3047 -0.7913 -0.5300 +vn 0.0415 -0.9142 -0.4031 +vn 0.0327 -0.8475 -0.5297 +vn 0.0763 -0.9690 -0.2350 +vn 0.0475 -0.5405 0.8400 +vn 0.3004 -0.6686 0.6803 +vn 0.3015 -0.3376 0.8917 +vn 0.0583 -0.3078 0.9497 +vn -0.1467 -0.3457 0.9268 +vn 0.2794 0.0239 0.9599 +vn 0.0747 -0.0214 0.9970 +vn 0.0606 0.1158 0.9914 +vn 0.2658 0.2643 0.9271 +vn 0.0569 0.2727 0.9604 +vn 0.0712 0.4740 0.8776 +vn 0.0814 0.6647 0.7426 +vn 0.3273 0.5903 0.7378 +vn 0.3246 0.8596 0.3946 +vn 0.0719 0.8300 0.5532 +vn 0.0298 0.9560 0.2920 +vn 0.0765 0.9953 0.0586 +vn 0.1951 0.9790 0.0585 +vn 0.0222 0.9881 -0.1523 +vn 0.3484 0.8906 -0.2923 +vn 0.0776 0.9365 -0.3419 +vn 0.2877 0.6862 -0.6681 +vn 0.0471 0.8255 -0.5624 +vn 0.0377 0.6798 -0.7325 +vn 0.0402 0.5263 -0.8494 +vn 0.2501 0.4320 -0.8665 +vn 0.0504 0.2877 -0.9564 +vn 0.0568 0.1305 -0.9898 +vn 0.2816 0.1205 -0.9519 +vn 0.0649 0.0010 -0.9979 +vn 0.4943 -0.0595 -0.8672 +vn 0.4967 0.3449 -0.7965 +vn 0.3826 0.7525 -0.5361 +vn 0.7206 0.6612 -0.2087 +vn 0.4433 0.8959 0.0278 +vn 0.6839 0.6866 0.2467 +vn 0.3444 0.7106 0.6135 +vn 0.4380 0.3706 0.8191 +vn 0.4659 -0.1089 0.8781 +vn 0.4087 -0.5003 0.7633 +vn 0.4917 -0.7379 0.4623 +vn 0.2783 -0.8650 0.4175 +vn 0.4216 -0.9022 0.0907 +vn 0.4572 -0.8227 -0.3378 +vn 0.4463 -0.5337 -0.7183 +vn -0.8496 -0.0058 -0.5273 +vn -0.9645 0.0149 -0.2636 +vn -0.9460 0.0261 -0.3231 +vn -0.7346 -0.0422 0.6772 +vn -0.8217 -0.0405 0.5685 +vn -0.7059 -0.1679 0.6881 +vn -0.8716 -0.0195 0.4898 +vn -0.9529 -0.0255 0.3023 +vn -0.9585 -0.0017 0.2852 +vn 0.0583 -0.9982 -0.0145 +vn 0.0955 -0.9954 -0.0099 +vn 0.0670 -0.9977 -0.0096 +vn 0.0168 -0.9998 0.0056 +vn -0.5325 -0.3857 0.7535 +vn -0.5142 -0.0619 0.8554 +vn -0.9996 0.0063 -0.0283 +vn -0.9880 0.0295 -0.1516 +vn -0.9987 0.0239 -0.0455 +vn -0.9947 -0.0053 0.1029 +vn -0.0178 -0.0012 0.9998 +vn 0.1443 -0.0065 0.9895 +vn 0.3821 -0.0348 0.9234 +vn 0.3892 0.0330 0.9206 +vn 0.3737 -0.0010 0.9276 +vn 0.8020 0.0197 -0.5970 +vn 0.6369 0.0104 -0.7709 +vn 0.3699 -0.0150 -0.9290 +vn 0.4315 0.0121 -0.9020 +vn 0.2059 0.0005 -0.9786 +vn -0.1002 -0.0203 -0.9948 +vn 0.0021 0.0127 -0.9999 +vn -0.2749 0.3510 -0.8951 +vn -0.5759 -0.0165 -0.8173 +vn -0.5307 0.4393 -0.7248 +vn -0.8021 0.0133 -0.5971 +vn 0.5710 0.0012 -0.8209 +vn 0.5719 -0.0050 -0.8203 +vn 0.3850 -0.0129 -0.9228 +vn 0.1945 -0.2650 -0.9444 +vn 0.3594 0.0132 -0.9331 +vn -0.2118 0.0147 -0.9772 +vn -0.0460 -0.0174 0.9988 +vn -0.0596 0.0012 0.9982 +vn -0.1425 -0.0348 0.9892 +vn 0.0106 0.0524 0.9986 +vn -0.0007 -0.0505 0.9987 +vn -0.4169 -0.1203 0.9009 +vn -0.4214 -0.1063 0.9006 +vn -0.4324 -0.0695 0.8990 +vn -0.4497 -0.0547 0.8915 +vn -0.9179 0.0360 -0.3952 +vn -0.9169 0.0367 -0.3974 +vn -0.9178 0.0361 -0.3955 +vn -0.9168 0.0367 -0.3978 +vn 0.0197 -0.9998 0.0082 +vn 0.0164 -0.9999 0.0027 +vn 0.0140 -0.9997 0.0196 +vn -0.8993 0.0032 -0.4374 +vn -0.8599 -0.1607 -0.4845 +vn -0.9910 -0.0052 -0.1341 +vn -0.7077 -0.2201 -0.6713 +vn -0.2442 -0.2363 -0.9405 +vn 0.1953 0.9796 -0.0481 +vn 0.1164 0.9856 -0.1224 +vn 0.5047 0.4195 0.7545 +vn 0.5242 0.3960 0.7540 +vn 0.4653 0.0790 0.8816 +vn 0.2374 0.3010 0.9236 +vn 0.3112 0.4556 0.8340 +vn 0.3292 0.3022 0.8946 +vn 0.2960 0.1381 0.9451 +vn 0.1587 0.1844 0.9700 +vn 0.2958 0.6961 0.6541 +vn 0.3789 0.7552 0.5348 +vn 0.4099 0.5188 0.7502 +vn 0.4646 0.6870 0.5588 +vn 0.4254 0.2864 0.8585 +vn 0.3940 0.0935 0.9143 +vn 0.4017 0.8604 0.3136 +vn 0.3639 0.9206 0.1417 +vn 0.1893 0.9695 0.1558 +vn 0.1198 0.9497 0.2895 +vn 0.2150 0.8950 0.3907 +vn 0.1800 0.7956 0.5785 +vn 0.1405 0.3679 0.9192 +vn 0.1940 0.5445 0.8160 +vn 0.3169 0.9426 -0.1056 +vn 0.3800 0.8864 -0.2644 +vn 0.4440 0.7426 -0.5015 +vn 0.4185 0.5173 -0.7465 +vn 0.4871 0.6264 -0.6085 +vn 0.1280 0.6981 -0.7045 +vn 0.1311 0.5865 -0.7992 +vn 0.1312 0.3831 -0.9143 +vn 0.1741 0.2807 -0.9439 +vn 0.1709 0.8107 -0.5600 +vn 0.1861 0.9573 -0.2211 +vn 0.2252 0.8751 -0.4284 +vn 0.2381 0.5233 -0.8182 +vn 0.2908 0.6814 -0.6717 +vn 0.2347 0.1442 -0.9613 +vn 0.2954 0.3268 -0.8978 +vn 0.2622 0.9637 0.0504 +vn 0.2897 0.9327 0.2149 +vn 0.3232 0.8381 0.4394 +vn 0.3387 0.5801 -0.7408 +vn 0.3597 0.7714 -0.5249 +vn 0.3005 0.9175 -0.2607 +vn 0.3616 0.1345 -0.9226 +vn 0.4506 0.2327 -0.8619 +vn 0.3191 -0.2306 -0.9192 +vn 0.3339 -0.1057 -0.9367 +vn 0.2944 -0.0489 -0.9544 +vn 0.2112 -0.0463 -0.9763 +vn 0.2557 0.0394 -0.9659 +vn 0.2310 -0.1876 -0.9547 +vn 0.1456 0.0137 -0.9893 +vn 0.1683 0.1009 -0.9806 +vn 0.1349 -0.0620 -0.9889 +vn 0.1480 -0.2912 -0.9452 +vn 0.4532 -0.1245 0.8827 +vn 0.3240 0.0249 0.9457 +vn 0.3205 -0.0386 0.9465 +vn 0.2525 0.0652 0.9654 +vn 0.2399 0.0017 0.9708 +vn 0.2576 -0.0728 0.9635 +vn 0.3541 -0.1137 0.9283 +vn 0.2831 -0.2459 0.9270 +vn -0.3117 -0.5190 0.7959 +vn 0.1601 -0.1011 0.9819 +vn 0.1529 0.0038 0.9882 +vn 0.1657 0.0941 0.9817 +vn 0.1595 -0.2403 0.9575 +vn 0.4282 -0.6262 -0.6516 +vn 0.4318 -0.6900 -0.5810 +vn 0.3940 -0.3591 -0.8461 +vn 0.3885 -0.8896 -0.2404 +vn 0.3181 -0.9440 -0.0879 +vn 0.2149 -0.9765 0.0191 +vn 0.2927 -0.9305 -0.2204 +vn 0.2955 -0.8664 -0.4025 +vn 0.3844 -0.8159 -0.4319 +vn 0.3281 -0.6306 -0.7034 +vn 0.3531 -0.4950 -0.7939 +vn 0.3920 -0.8923 0.2238 +vn 0.5114 -0.6753 0.5314 +vn 0.0747 -0.8768 0.4750 +vn 0.4632 -0.7668 0.4444 +vn 0.4775 -0.5508 0.6846 +vn 0.0766 -0.7114 0.6986 +vn 0.5280 -0.3605 0.7689 +vn 0.5203 -0.4287 0.7386 +vn 0.1402 -0.4380 0.8880 +vn 0.1279 -0.8837 -0.4502 +vn 0.1262 -0.9899 -0.0651 +vn 0.1791 -0.7861 0.5916 +vn 0.2018 -0.6086 0.7674 +vn 0.1624 -0.6367 -0.7538 +vn 0.1219 -0.9902 0.0678 +vn 0.1678 -0.8980 0.4068 +vn 0.2269 -0.4013 0.8874 +vn 0.2146 -0.8326 -0.5106 +vn 0.2031 -0.9255 -0.3198 +vn 0.1772 -0.9736 -0.1436 +vn 0.1961 -0.9596 0.2017 +vn 0.2777 -0.7943 0.5404 +vn 0.3036 -0.5745 0.7601 +vn 0.2754 -0.4598 -0.8442 +vn 0.2610 -0.7377 -0.6227 +vn 0.2542 -0.9027 0.3471 +vn 0.3945 -0.6413 0.6581 +vn 0.3911 -0.3704 0.8425 +vn 0.2959 -0.9330 0.2050 +vn 0.3549 -0.8344 0.4216 +vn 0.3001 -0.9512 0.0716 +vn 0.4214 -0.0694 0.9042 +vn 0.2658 -0.1290 0.9554 +vn 0.0419 -0.0817 0.9958 +vn 0.0038 -0.0546 0.9985 +vn 0.5479 -0.1081 0.8296 +vn 0.7431 -0.0480 0.6675 +vn 0.7985 -0.0467 0.6001 +vn 0.8858 -0.1577 0.4364 +vn 0.9635 -0.0609 0.2606 +vn 0.9850 -0.0775 0.1542 +vn 0.9890 -0.0314 -0.1445 +vn 0.9910 -0.1333 0.0137 +vn 0.8988 -0.0440 -0.4361 +vn 0.8839 -0.0407 -0.4660 +vn 0.8118 0.0026 -0.5840 +vn -0.7822 -0.0031 0.6230 +vn -0.9125 0.0024 0.4091 +vn -0.9352 -0.0229 0.3533 +vn -0.7195 -0.0178 0.6942 +vn -0.5367 0.0112 0.8437 +vn -0.3769 -0.0213 0.9260 +vn -0.2032 -0.0302 0.9787 +vn 0.7993 0.0030 -0.6010 +vn 0.7057 -0.0205 -0.7082 +vn 0.6071 0.0003 -0.7946 +vn 0.4216 -0.0160 -0.9067 +vn 0.3831 -0.0040 -0.9237 +vn 0.0659 -0.0203 -0.9976 +vn 0.0801 -0.0016 -0.9968 +vn -0.3676 -0.0296 -0.9295 +vn -0.2225 -0.0039 -0.9749 +vn -0.4373 0.0082 -0.8993 +vn -0.7079 -0.0299 -0.7057 +vn -0.6211 -0.0031 -0.7837 +vn -0.8398 0.0058 -0.5429 +vn -0.9153 -0.0197 -0.4022 +vn -0.9734 0.0138 -0.2285 +vn -0.9982 -0.0227 -0.0547 +vn -0.9937 0.0058 0.1120 +vn 0.8974 0.4343 -0.0779 +vn 0.9314 -0.1579 -0.3279 +vn 0.7893 0.4502 -0.4175 +vn 0.7809 0.0251 -0.6242 +vn 0.8295 -0.0558 -0.5557 +vn 0.6738 0.1644 -0.7204 +vn 0.6070 0.1892 -0.7718 +vn 0.5887 0.3212 -0.7418 +vn 0.2638 -0.3932 -0.8808 +vn 0.2751 -0.3695 -0.8876 +vn 0.2836 -0.2105 -0.9356 +vn -0.3456 0.7668 -0.5409 +vn -0.2510 0.8392 -0.4825 +vn -0.3237 0.7661 -0.5552 +vn -0.7336 -0.3810 -0.5627 +vn -0.9413 0.2023 -0.2701 +vn -0.9328 0.2350 -0.2731 +vn -0.9198 0.2839 -0.2710 +vn -0.9167 0.2935 -0.2711 +vn 0.9758 -0.2176 0.0218 +vn 0.8605 0.4239 0.2826 +vn 0.8626 0.4196 0.2826 +vn 0.8745 0.3685 0.3154 +vn 0.8801 0.2207 0.4203 +vn 0.6311 -0.6404 0.4377 +vn 0.6166 0.4219 0.6647 +vn 0.5634 0.2501 0.7874 +vn 0.5930 -0.1155 0.7969 +vn 0.5937 -0.0592 0.8025 +vn 0.3231 0.3228 0.8896 +vn 0.3231 0.3321 0.8862 +vn 0.3178 0.1590 0.9347 +vn 0.0320 0.2953 0.9549 +vn -0.3022 -0.4043 0.8633 +vn -0.3519 0.6290 0.6932 +vn -0.5227 -0.5558 0.6465 +vn -0.6953 0.5359 0.4789 +vn -0.7446 -0.5447 0.3858 +vn -0.7930 0.5941 0.1345 +vn -0.9468 -0.3122 0.0782 +vn -0.9865 -0.1462 0.0735 +vn -0.9842 -0.1606 0.0740 +vn -0.5839 -0.8051 -0.1044 +vn -0.4376 -0.8985 0.0355 +vn -0.4507 -0.8702 -0.1989 +vn -0.4291 -0.8720 -0.2356 +vn -0.6133 -0.5905 -0.5245 +vn -0.6199 -0.5761 -0.5328 +vn -0.2321 -0.9034 -0.3606 +vn -0.3091 -0.3486 -0.8848 +vn -0.1323 -0.8127 -0.5675 +vn -0.0219 -0.8689 -0.4946 +vn -0.0952 -0.8336 -0.5441 +vn 0.0079 -0.8809 -0.4733 +vn 0.2763 -0.2692 -0.9226 +vn 0.2534 -0.4181 -0.8723 +vn 0.1858 -0.9544 -0.2337 +vn 0.7925 -0.2036 -0.5748 +vn 0.3547 -0.9159 -0.1876 +vn 0.4102 -0.8963 -0.1683 +vn 0.6088 -0.7885 -0.0876 +vn 0.3858 -0.9202 0.0660 +vn 0.6207 -0.7834 -0.0332 +vn 0.3462 -0.9347 0.0810 +vn 0.8508 0.0166 0.5253 +vn 0.5757 -0.7436 0.3400 +vn 0.6298 -0.6955 0.3458 +vn 0.3131 -0.8983 0.3081 +vn 0.3877 -0.7337 0.5580 +vn 0.2024 -0.8734 0.4430 +vn 0.1585 -0.7112 0.6849 +vn -0.0006 -0.8827 0.4699 +vn -0.1102 -0.6639 0.7397 +vn -0.1188 -0.6336 0.7645 +vn -0.1667 -0.9298 0.3281 +vn -0.1713 -0.9268 0.3343 +vn -0.3508 -0.8509 0.3910 +vn -0.3567 -0.8428 0.4032 +vn -0.3901 -0.8923 0.2272 +vn -0.5759 -0.7987 0.1746 +vn 0.0001 1.0000 0.0000 +vn 0.0002 1.0000 0.0002 +vn 0.0001 1.0000 0.0003 +vn 0.0000 1.0000 -0.0003 +vn 0.0000 1.0000 -0.0001 +vn 0.3623 0.0099 -0.9320 +vn 0.3537 0.0021 -0.9354 +vn 0.3555 0.0038 -0.9347 +vn 0.3472 -0.0037 -0.9378 +vn -0.4852 0.0179 -0.8742 +vn -0.2635 -0.0240 -0.9644 +vn -0.3004 -0.0173 -0.9536 +vn -0.5176 0.0244 -0.8553 +vn -0.5409 0.0234 -0.8408 +vn -0.2062 -0.0225 -0.9783 +vn -0.4611 -0.0065 -0.8873 +vn -0.5906 0.0250 -0.8066 +vn -0.6705 0.0022 -0.7419 +vn -0.9881 0.0053 0.1539 +vn -0.9847 0.0009 0.1744 +vn -0.9876 0.0047 0.1570 +vn -0.9841 0.0002 0.1775 +vn -0.8929 -0.0016 -0.4503 +vn -0.9021 0.0018 -0.4315 +vn -0.9011 0.0014 -0.4337 +vn -0.8917 -0.0020 -0.4526 +vn -0.0244 -0.0007 -0.9997 +vn -0.0383 -0.0123 -0.9992 +vn -0.4986 -0.8668 0.0031 +vn -0.4986 -0.8668 0.0025 +vn -0.4995 -0.8663 -0.0005 +vn -0.4997 -0.8662 -0.0002 +vn -0.4999 -0.8661 0.0001 +vn -0.4993 -0.8664 0.0037 +vn -0.4949 -0.8688 0.0182 +vn -0.2879 -0.9554 0.0660 +vn -0.2220 -0.9719 0.0777 +vn 0.0441 -0.9986 0.0290 +vn 0.0578 -0.9973 0.0454 +vn -0.3197 -0.6492 0.6902 +vn -0.3770 -0.6898 0.6181 +vn -0.6045 -0.5377 0.5877 +vn -0.3878 -0.8378 0.3844 +vn -0.7077 -0.5496 -0.4440 +vn -0.4409 -0.5944 -0.6725 +vn -0.4413 -0.8182 -0.3685 +vn 0.0747 -0.7621 -0.6432 +vn 0.2392 -0.8012 -0.5485 +vn 0.0150 0.8578 -0.5138 +vn -0.2489 0.8138 0.5251 +vn -0.3091 0.7819 0.5413 +vn 0.0416 -0.9986 0.0339 +vn 0.0971 -0.9938 0.0533 +vn 0.3030 0.6035 -0.7376 +vn 0.3418 0.6764 -0.6525 +vn 0.4769 0.6920 -0.5419 +vn 0.3499 0.8246 -0.4445 +vn 0.4708 0.8236 -0.3163 +vn -0.4154 0.8691 0.2684 +vn -0.7614 0.6211 0.1857 +vn -0.5269 0.6901 0.4961 +vn -0.5712 0.7011 -0.4268 +vn -0.5885 0.6949 -0.4133 +vn -0.1053 0.6429 -0.7587 +vn 0.1719 0.7230 -0.6691 +vn 0.0253 0.7550 -0.6552 +vn 0.1325 0.7132 -0.6883 +vn 0.2563 0.7782 -0.5733 +vn -0.6229 0.7381 -0.2592 +vn -0.3516 0.5721 -0.7410 +vn 0.4948 0.6513 -0.5753 +vn 0.3203 0.9137 -0.2499 +vn -0.5049 0.8611 -0.0595 +vn -0.7739 0.6330 -0.0225 +vn -0.7093 0.6996 0.0869 +vn 0.5058 -0.8503 0.1457 +vn 0.1748 -0.9841 0.0331 +vn 0.0176 -0.9970 -0.0747 +vn 0.6172 -0.7446 0.2541 +vn 0.8792 -0.2887 0.3790 +vn 0.8726 -0.2847 0.3968 +vn -0.0343 0.9954 0.0895 +vn 0.8914 0.1512 0.4273 +vn 0.9126 0.0517 0.4056 +vn 0.7960 0.4033 0.4513 +vn 0.4808 0.8398 0.2521 +vn 0.4817 0.8389 0.2533 +vn 0.4811 0.8395 0.2525 +vn 0.4821 0.8385 0.2539 +vn -0.5844 0.0058 0.8114 +vn -0.3987 0.1572 0.9035 +vn -0.5307 0.2554 0.8082 +vn -0.4613 0.0031 0.8872 +vn -0.3131 0.2014 0.9281 +vn -0.2549 0.0010 0.9670 +vn -0.1073 0.2166 0.9704 +vn -0.3495 -0.5974 0.7218 +vn -0.0710 -0.6612 0.7468 +vn -0.3066 -0.7605 0.5724 +vn -0.2197 -0.8489 0.4808 +vn -0.0324 -0.6248 0.7801 +vn -0.3040 0.4333 0.8484 +vn -0.1706 0.8468 0.5038 +vn -0.2052 0.8432 0.4969 +vn -0.1202 0.8377 0.5327 +vn -0.2670 -0.3332 0.9043 +vn -0.2880 -0.6678 0.6864 +vn -0.1478 -0.8324 0.5341 +vn -0.1333 0.7609 0.6350 +vn -0.4285 0.6102 0.6664 +vn -0.2767 0.5801 0.7661 +vn 0.1058 -0.5613 0.8208 +vn 0.1603 -0.1588 0.9742 +vn 0.2579 -0.6656 0.7003 +vn 0.4325 -0.2655 0.8617 +vn 0.1926 0.5337 0.8235 +vn 0.1104 0.2176 0.9698 +vn 0.3711 0.1473 0.9168 +vn 0.3972 0.0135 -0.9176 +vn 0.4008 0.0194 -0.9160 +vn 0.4029 0.0229 -0.9150 +vn 0.4067 0.0290 -0.9131 +vn 0.9755 0.0273 0.2184 +vn 0.9115 -0.0049 0.4112 +vn 0.9596 0.0125 0.2811 +vn 0.9823 0.0310 0.1849 +vn 0.9862 0.0253 0.1638 +vn 0.8591 0.0146 -0.5116 +vn 0.8509 0.0094 -0.5253 +vn 0.8571 0.0132 -0.5151 +vn 0.8489 0.0081 -0.5285 +vn 0.9007 0.0000 0.4345 +vn 0.9061 0.0085 0.4230 +vn 0.8299 0.0207 0.5575 +vn 0.7733 -0.0119 0.6339 +vn 0.6059 0.0041 0.7955 +vn 0.5539 -0.0241 0.8322 +vn 0.4897 0.0272 0.8715 +vn 0.3759 0.0309 0.9261 +vn 0.1215 -0.0214 0.9924 +vn 0.2899 0.0164 0.9569 +vn 0.4223 0.0418 0.9055 +vn 0.4081 0.0457 0.9118 +vn -0.4487 0.0249 0.8933 +vn -0.4603 0.0170 0.8876 +vn -0.4535 0.0217 0.8910 +vn -0.4422 0.0293 0.8965 +vn -0.8708 0.0158 -0.4914 +vn -0.9421 -0.2091 -0.2623 +vn -0.9908 -0.0723 -0.1142 +vn -0.9171 0.0570 0.3947 +vn -0.8827 0.0333 0.4687 +vn -0.9095 0.0514 0.4125 +vn -0.8695 0.0251 0.4933 +vn -0.9934 0.0119 -0.1137 +vn -0.9944 0.0184 -0.1041 +vn -0.9719 0.0180 -0.2347 +vn -0.9661 0.0086 -0.2581 +vn -0.8849 0.0168 -0.4655 +vn -0.8749 0.0130 -0.4841 +vn -0.5063 0.0514 -0.8608 +vn -0.2418 -0.0209 -0.9701 +vn -0.5452 -0.0023 -0.8383 +vn -0.6091 0.0540 -0.7913 +vn -0.7840 -0.0095 -0.6207 +vn -0.3169 0.9103 -0.2664 +vn -0.8937 -0.4275 -0.1363 +vn 0.6913 -0.6900 0.2146 +vn 0.1439 -0.7568 0.6376 +vn 0.4882 0.8441 0.2215 +vn 0.8757 0.1711 0.4516 +vn 0.4089 0.8319 0.3753 +vn 0.5577 0.2782 0.7820 +vn 0.3172 0.1489 0.9366 +vn -0.0100 0.7538 0.6570 +vn -0.1053 0.0100 0.9944 +vn -0.1455 0.8961 0.4193 +vn -0.5094 0.0388 0.8597 +vn -0.3033 0.8758 0.3755 +vn -0.8266 -0.0239 0.5623 +vn -0.3870 0.9000 0.2007 +vn -0.9440 -0.3205 0.0784 +vn -0.9254 0.2604 -0.2755 +vn -0.4704 0.8367 -0.2804 +vn -0.6933 -0.1209 -0.7105 +vn -0.3295 0.7926 -0.5130 +vn -0.2646 0.1280 -0.9558 +vn -0.2623 0.1430 -0.9543 +vn -0.0391 0.6044 -0.7958 +vn -0.1558 0.4920 -0.8565 +vn 0.0082 0.6551 -0.7555 +vn 0.1786 0.0227 -0.9837 +vn 0.2073 0.8605 -0.4653 +vn 0.5606 0.4455 -0.6980 +vn 0.2149 0.9334 -0.2874 +vn -0.3477 0.6103 -0.7118 +vn -0.5112 -0.8240 -0.2443 +vn -0.5961 -0.7956 -0.1081 +vn -0.5646 -0.8093 -0.1620 +vn -0.6424 -0.7662 -0.0189 +vn -0.0003 1.0000 0.0004 +vn -0.0021 -0.9934 0.1147 +vn -0.4058 -0.0678 0.9115 +vn -0.4071 -0.0663 0.9110 +vn 0.0600 0.0094 -0.9982 +vn 0.1255 0.0488 -0.9909 +vn -0.1209 0.0136 -0.9926 +vn 0.8566 0.0085 -0.5159 +vn 0.7900 -0.0025 -0.6132 +vn 0.7689 0.0058 -0.6394 +vn 0.5870 -0.0162 -0.8094 +vn 0.5918 0.0092 -0.8060 +vn 0.6545 0.0073 -0.7560 +vn 0.2895 -0.0141 -0.9571 +vn -0.1001 -0.0056 -0.9950 +vn 0.2018 -0.0046 -0.9794 +vn -0.8419 0.0187 0.5393 +vn -0.6430 -0.0145 0.7657 +vn -0.5663 0.0131 0.8241 +vn -0.9870 0.0191 0.1595 +vn -0.9996 -0.0152 0.0223 +vn -0.9213 -0.0201 0.3882 +vn -0.9518 0.0210 -0.3059 +vn -0.9166 -0.0140 -0.3996 +vn -0.6791 0.0080 -0.7340 +vn -0.6333 -0.0137 -0.7738 +vn -0.2621 -0.0084 -0.9650 +vn -0.2695 0.0038 -0.9630 +vn 0.1112 0.0037 -0.9938 +vn 0.2125 -0.0186 -0.9770 +vn 0.5035 0.0135 -0.8639 +vn 0.5573 -0.0034 -0.8303 +vn 0.7726 0.0091 -0.6348 +vn 0.7120 0.0054 -0.7021 +vn 0.7947 -0.0040 -0.6069 +vn 0.8415 0.0019 -0.5402 +vn -0.4990 -0.0050 0.8666 +vn -0.1646 -0.0085 0.9863 +vn -0.5580 0.0096 0.8298 +vn -0.1912 0.0055 0.9815 +vn -0.3986 -0.0210 0.9169 +vn -0.3965 -0.0556 0.9164 +vn -0.4022 -0.0118 0.9155 +vn -0.6701 0.0028 0.7422 +vn -0.8759 0.0101 0.4823 +vn -0.6378 -0.0069 0.7702 +vn -0.7148 0.0072 0.6993 +vn -0.8595 0.0082 0.5111 +vn -0.9880 0.0484 0.1464 +vn -0.9934 0.0148 -0.1138 +vn -0.8512 0.0328 0.5239 +vn -0.9901 0.0695 -0.1217 +vn -0.9369 0.0084 -0.3495 +vn -0.7901 0.0223 -0.6126 +vn -0.8393 0.0052 -0.5437 +vn -0.3393 0.0136 -0.9406 +vn -0.5855 0.0153 -0.8105 +vn -0.5713 0.0120 -0.8206 +vn -0.0670 0.0217 -0.9975 +vn 0.0001 -1.0000 0.0001 +vn -0.0003 -1.0000 0.0028 +vn -0.0011 -0.9999 0.0112 +vn 0.0023 -1.0000 -0.0013 +vn 0.0038 -1.0000 0.0013 +vn 0.0000 -1.0000 -0.0005 +vn -0.0000 -1.0000 -0.0003 +vn -0.0002 -1.0000 -0.0005 +vn -0.0015 -1.0000 -0.0005 +vn -0.0000 -1.0000 0.0001 +vn 0.0014 -1.0000 0.0002 +vn 0.1826 0.0219 -0.9829 +vn 0.6461 0.0151 -0.7631 +vn 0.6264 -0.0160 -0.7793 +vn 0.4270 0.0107 -0.9042 +vn 0.8162 0.0138 -0.5776 +vn 0.9000 -0.0114 -0.4356 +vn 0.9651 0.0209 -0.2609 +vn 0.8165 0.0069 0.5773 +vn 0.9574 -0.0041 0.2888 +vn 0.9246 0.0105 0.3808 +vn 0.9942 0.0201 0.1058 +vn 0.9971 -0.0080 -0.0754 +vn 0.7806 -0.0062 0.6249 +vn 0.6086 0.0091 0.7934 +vn 0.4931 -0.0103 0.8699 +vn 0.3860 0.0061 0.9225 +vn 0.1219 -0.0037 0.9925 +vn 0.1493 0.0135 0.9887 +vn -0.1894 0.0176 0.9817 +vn -0.2790 -0.0059 0.9603 +vn -0.5622 0.0194 0.8268 +vn -0.6299 -0.0026 0.7766 +vn -0.8488 -0.0020 0.5287 +vn 0.0003 -1.0000 0.0024 +vn -0.0032 -1.0000 0.0075 +vn -0.0025 -1.0000 -0.0024 +vn 0.0002 -1.0000 0.0010 +vn -0.0030 -1.0000 -0.0016 +vn 0.0003 -1.0000 -0.0004 +vn 0.0005 -1.0000 -0.0019 +vn 0.0001 -1.0000 -0.0072 +vn 0.0006 -1.0000 0.0000 +vn -0.0001 -1.0000 0.0016 +vn 0.0003 -1.0000 -0.0023 +vn 0.0004 -1.0000 0.0004 +vn -0.0001 -1.0000 0.0015 +vn -0.0057 -1.0000 -0.0032 +vn 0.0001 -1.0000 -0.0008 +vn 0.0001 -1.0000 -0.0010 +vn 0.0004 -1.0000 0.0000 +vn -0.0007 -1.0000 0.0002 +vn 0.0000 -1.0000 0.0004 +vn 0.0001 -1.0000 -0.0000 +vn -0.0001 -1.0000 -0.0011 +vn 0.0004 -0.9999 -0.0164 +vn -0.0719 -0.9966 -0.0408 +vn -0.0093 -0.9999 -0.0053 +vn -0.0038 -1.0000 -0.0021 +vn -0.0010 -1.0000 -0.0019 +vn -0.0032 -1.0000 -0.0010 +vn 0.0006 -1.0000 0.0004 +vn 0.0005 -1.0000 -0.0001 +vn 0.0000 -1.0000 -0.0001 +vn -0.0008 -1.0000 0.0006 +vn 0.0010 0.9999 -0.0157 +vn 0.0020 1.0000 0.0010 +vn 0.0021 0.9999 -0.0115 +vn 0.0152 0.9998 0.0104 +vn -0.0029 1.0000 0.0002 +vn 0.0026 0.9991 0.0421 +vn -0.0031 1.0000 -0.0048 +vn 0.0126 0.9997 0.0221 +vn 0.0005 1.0000 -0.0044 +vn -0.0029 1.0000 0.0029 +vn -0.0009 1.0000 0.0068 +vn -0.8963 -0.0292 -0.4424 +vn -0.9991 -0.0100 -0.0404 +vn -0.9916 -0.0143 -0.1283 +vn -0.9523 -0.0394 -0.3027 +vn -0.8805 -0.0941 -0.4645 +vn -0.7997 -0.1286 -0.5864 +vn -0.3227 -0.0858 -0.9426 +vn -0.7079 -0.0765 -0.7021 +vn -0.5742 -0.0007 -0.8187 +vn -0.4192 0.0441 -0.9068 +vn -0.2509 0.0554 -0.9664 +vn -0.0740 0.0331 -0.9967 +vn 0.1275 -0.0307 -0.9914 +vn 0.3202 -0.0354 -0.9467 +vn 0.6087 -0.0575 -0.7913 +vn 0.5479 0.0145 -0.8364 +vn 0.6968 0.0106 -0.7172 +vn 0.8290 -0.0422 -0.5577 +vn 0.9992 -0.0395 -0.0014 +vn 0.9178 -0.0393 -0.3952 +vn 0.9885 0.0424 -0.1454 +vn 0.9974 0.0557 0.0451 +vn 0.9745 0.0336 0.2220 +vn 0.9200 -0.0214 0.3913 +vn 0.8592 -0.0258 0.5110 +vn 0.9779 -0.0023 0.2089 +vn 0.8029 0.0088 0.5961 +vn 0.7964 0.0160 0.6046 +vn 0.9783 -0.0112 0.2067 +vn 0.9405 -0.0019 0.3397 +vn 0.9662 -0.0286 0.2561 +vn 0.9051 0.0152 0.4249 +vn 0.8135 0.0264 0.5810 +vn 0.7516 0.0207 0.6593 +vn 0.7431 0.0182 0.6689 +vn 0.5584 -0.0490 0.8281 +vn 0.6400 -0.0111 0.7683 +vn 0.5668 -0.0289 0.8233 +vn 0.1919 -0.0471 0.9803 +vn 0.4349 -0.0142 0.9003 +vn 0.2649 0.0141 0.9642 +vn 0.1783 0.0195 0.9838 +vn 0.0883 0.0093 0.9961 +vn -0.1006 -0.0401 0.9941 +vn -0.6230 -0.0503 0.7806 +vn -0.2577 -0.0370 0.9655 +vn -0.5555 0.0394 0.8306 +vn -0.8560 -0.0151 0.5167 +vn -0.9972 -0.0403 -0.0631 +vn -0.9867 0.0038 0.1627 +vn -0.9783 0.0410 -0.2030 +vn -0.9227 -0.0002 -0.3856 +vn -0.8668 -0.0151 -0.4985 +vn -0.9931 -0.0007 -0.1173 +vn 0.7650 0.0301 0.6434 +vn 0.8665 -0.0130 0.4990 +vn 0.7858 -0.0300 0.6177 +vn 0.8680 0.0303 0.4957 +vn 0.6995 0.0063 0.7146 +vn 0.5424 -0.0764 0.8367 +vn -0.1504 -0.0909 0.9844 +vn 0.4519 -0.1109 0.8851 +vn 0.2901 -0.0191 0.9568 +vn 0.1158 0.0428 0.9924 +vn -0.0634 0.0714 0.9954 +vn -0.3231 0.0553 0.9448 +vn -0.6923 -0.0585 0.7192 +vn -0.7930 -0.1048 0.6002 +vn -0.9165 0.0214 0.3995 +vn -0.9726 0.0664 0.2227 +vn -0.9422 -0.0294 -0.3338 +vn -0.9956 0.0769 0.0542 +vn -0.9971 0.0661 -0.0374 +vn -0.9761 0.0263 -0.2157 +vn -0.9216 -0.0461 -0.3855 +vn -0.8711 -0.0328 -0.4901 +vn -0.8931 -0.0430 -0.4478 +vn -0.8364 0.0142 -0.5480 +vn 0.0368 0.0264 -0.9990 +vn -0.1313 -0.0074 -0.9913 +vn -0.2952 -0.0268 -0.9550 +vn -0.4514 -0.0314 -0.8917 +vn -0.5940 -0.0211 -0.8042 +vn -0.7191 0.0037 -0.6949 +vn -0.8346 0.0716 -0.5462 +vn -0.8897 0.1019 -0.4449 +vn -0.9548 0.0492 -0.2932 +vn -0.9913 0.0083 -0.1311 +vn 0.5856 0.0003 -0.8106 +vn 0.7263 -0.0223 -0.6870 +vn 0.8322 -0.0269 -0.5538 +vn 0.9138 -0.0170 -0.4059 +vn 0.9682 0.0074 -0.2501 +vn 0.9950 0.0224 -0.0973 +vn 0.9969 0.0057 0.0780 +vn 0.9490 -0.0103 0.3152 +vn 0.8505 -0.0006 0.5259 +vn -0.6963 -0.0086 0.7177 +vn -0.8112 -0.0054 0.5848 +vn -0.9042 0.0245 0.4265 +vn -0.9551 0.0324 0.2944 +vn -0.9924 -0.0031 0.1232 +vn -0.9984 -0.0233 -0.0522 +vn -0.9738 -0.0273 -0.2260 +vn -0.8928 -0.0080 -0.4503 +vn 0.2382 -0.0113 0.9712 +vn 0.4410 0.0254 0.8972 +vn 0.5674 0.0258 0.8231 +vn 0.7019 -0.0029 0.7123 +vn 0.8290 -0.0164 0.5590 +vn 0.9487 0.0008 0.3161 +vn 0.4028 0.0828 0.9115 +vn 0.6414 -0.0165 0.7670 +vn -0.8718 -0.0050 -0.4899 +vn -0.9499 0.0304 0.3109 +vn -0.9934 -0.0298 0.1112 +vn -0.9415 -0.0034 0.3371 +vn -0.8022 -0.0043 0.5970 +vn -0.6779 -0.0154 0.7349 +vn 0.7673 0.0285 -0.6407 +vn 0.8136 0.0017 -0.5814 +vn 0.6624 -0.0172 -0.7490 +vn 0.7018 0.0182 -0.7122 +vn 0.4443 -0.0558 -0.8941 +vn -0.2494 0.0258 -0.9680 +vn -0.2834 0.0059 -0.9590 +vn -0.2673 0.0153 -0.9635 +vn -0.3034 -0.0060 -0.9528 +vn -0.9432 -0.0013 -0.3321 +vn -0.9057 0.0109 -0.4237 +vn -0.9416 -0.0053 -0.3368 +vn -0.8910 0.0066 -0.4539 +vn -0.8415 0.0173 -0.5400 +vn -0.8341 0.0038 -0.5516 +vn -0.9648 0.0050 0.2630 +vn -0.9585 -0.0053 0.2850 +vn -0.9777 0.0127 0.2097 +vn -0.9823 -0.0086 0.1873 +vn -0.9943 0.0050 0.1066 +vn -0.9840 0.0363 0.1742 +vn -0.5358 0.0144 0.8442 +vn -0.5597 -0.0071 0.8286 +vn -0.5405 0.0102 0.8413 +vn -0.5172 0.0306 0.8553 +vn 0.3909 0.0350 0.9198 +vn 0.1197 -0.0640 0.9907 +vn 0.2210 -0.0281 0.9749 +vn 0.4837 0.0713 0.8723 +vn 0.9407 -0.0266 0.3381 +vn 0.8643 -0.0023 0.5030 +vn 0.9423 -0.0221 0.3341 +vn 0.8549 0.0040 0.5188 +vn 0.7434 0.0232 0.6684 +vn 0.7453 0.0265 0.6662 +vn 0.9706 0.0433 -0.2369 +vn 0.9876 -0.0623 0.1439 +vn 0.9452 -0.0346 -0.3247 +vn 0.8986 0.0494 -0.4360 +vn 0.7005 -0.0421 -0.7124 +vn 0.2484 0.0231 -0.9684 +vn 0.2099 0.0078 -0.9777 +vn 0.2358 0.0181 -0.9716 +vn 0.1941 0.0016 -0.9810 +vn 0.2430 0.9288 0.2798 +vn -0.0178 0.9221 -0.3866 +vn 0.0007 1.0000 -0.0067 +vn 0.0008 1.0000 0.0038 +vn 0.0013 1.0000 0.0009 +vn 0.0010 1.0000 -0.0014 +vn 0.0009 1.0000 0.0051 +vn 0.0001 1.0000 -0.0010 +vn 0.0003 1.0000 0.0046 +vn -0.0000 1.0000 0.0034 +vn -0.8291 -0.0747 -0.5541 +vn -0.8252 -0.0591 -0.5618 +vn -0.9205 -0.0904 -0.3802 +vn -0.8339 -0.0447 -0.5501 +vn -0.9207 -0.1555 -0.3579 +vn -0.9953 0.0401 -0.0879 +vn -0.9897 -0.0137 -0.1424 +vn -0.9606 0.2276 0.1595 +vn -0.9636 0.2073 0.1689 +vn -0.9692 0.1518 0.1937 +vn -0.9713 0.0851 0.2223 +vn -0.1298 0.1162 0.9847 +vn -0.1524 0.0391 0.9875 +vn -0.1076 0.1884 0.9762 +vn -0.1024 0.2051 0.9734 +vn 0.4284 0.0557 0.9019 +vn 0.3762 -0.0151 0.9264 +vn 0.4056 0.2007 0.8917 +vn 0.3085 0.4084 0.8591 +vn 0.8429 0.1126 0.5262 +vn 0.7905 -0.0371 0.6113 +vn 0.7609 -0.0997 0.6412 +vn 0.8542 0.1612 0.4944 +vn -0.8444 -0.2899 0.4505 +vn -0.7412 0.0227 0.6709 +vn -0.8173 -0.0755 0.5713 +vn -0.8434 -0.1166 0.5245 +vn -0.8658 -0.2755 0.4177 +vn 0.9478 -0.1353 0.2886 +vn 0.8914 -0.0720 0.4475 +vn 0.7667 -0.2655 0.5845 +vn 0.8090 -0.0707 0.5835 +vn 0.6483 -0.1747 0.7411 +vn 0.5122 -0.4560 0.7278 +vn 0.1900 0.0549 0.9803 +vn 0.3521 -0.0109 0.9359 +vn 0.2712 0.0224 0.9623 +vn 0.1335 0.0768 0.9881 +vn -0.1568 -0.2774 0.9479 +vn 0.2481 0.4993 0.8301 +vn 0.2269 0.3825 0.8956 +vn 0.1766 0.0839 0.9807 +vn 0.3285 0.2971 0.8965 +vn 0.2931 0.4125 0.8625 +vn 0.6758 -0.1686 0.7175 +vn 0.5476 -0.1771 0.8178 +vn 0.6558 -0.2028 0.7271 +vn 0.7386 -0.1978 0.6445 +vn 0.8309 -0.1032 0.5467 +vn 0.8810 -0.1333 0.4539 +vn 0.9094 -0.1348 0.3934 +vn 0.9658 -0.1000 0.2393 +vn -0.8425 -0.2204 0.4916 +vn -0.6385 -0.2256 0.7358 +vn -0.6690 -0.1764 0.7220 +vn -0.7997 -0.1127 0.5897 +vn -0.8962 -0.1222 0.4265 +vn -0.9466 -0.2042 0.2496 +vn -0.9522 -0.2087 0.2232 +vn -0.9643 -0.2564 0.0656 +vn -0.9843 -0.0773 -0.1589 +vn -0.8999 -0.2208 -0.3761 +vn -0.9196 0.2571 -0.2971 +vn -0.6198 -0.3466 0.7040 +vn -0.5808 -0.4204 0.6971 +vn 0.0248 0.0977 -0.9949 +vn 0.7772 0.0383 -0.6280 +vn 0.7678 -0.0314 -0.6399 +vn 0.6341 -0.4047 -0.6589 +vn 0.9233 0.1071 -0.3689 +vn 0.9777 0.1143 0.1761 +vn 0.7365 0.3234 0.5942 +vn 0.6247 -0.3219 0.7114 +vn 0.3651 -0.7840 0.5020 +vn 0.5569 -0.6656 0.4968 +vn 0.5035 0.3222 0.8017 +vn -0.0923 0.4590 0.8836 +vn -0.1088 0.3438 0.9327 +vn -0.0711 0.5851 0.8078 +vn -0.0697 0.5925 0.8025 +vn -0.4409 0.4129 0.7970 +vn -0.8968 0.1320 0.4222 +vn -0.1071 -0.3857 -0.9164 +vn 0.1276 -0.1546 -0.9797 +vn 0.1490 -0.2893 -0.9456 +vn -0.9316 0.3627 -0.0236 +vn -0.9732 0.2297 0.0071 +vn -0.9088 0.4156 -0.0361 +vn -0.9297 -0.3148 -0.1913 +vn -0.9162 -0.1945 -0.3503 +vn -0.8932 -0.1762 -0.4138 +vn -0.8930 -0.3134 -0.3229 +vn -0.8085 -0.1534 -0.5681 +vn -0.6922 -0.1774 -0.6995 +vn -0.6409 -0.1939 -0.7427 +vn -0.9447 0.1049 -0.3106 +vn -0.4538 -0.2426 -0.8574 +vn -0.3173 -0.0977 -0.9433 +vn -0.1383 -0.0502 -0.9891 +vn 0.0486 -0.1048 -0.9933 +vn 0.7977 0.1606 0.5812 +vn 0.7959 0.2158 0.5656 +vn 0.7956 0.2224 0.5636 +vn 0.9561 0.0014 0.2931 +vn 0.9447 0.0267 0.3269 +vn 0.8873 0.2408 0.3934 +vn 0.9404 0.0238 0.3393 +vn 0.9884 -0.0761 -0.1317 +vn 0.9846 -0.1699 -0.0407 +vn 0.9803 -0.0064 -0.1973 +vn 0.9665 0.0525 -0.2512 +vn 0.7751 0.2324 -0.5876 +vn 0.7730 0.2090 -0.5990 +vn 0.5405 -0.1893 -0.8197 +vn 0.7296 0.0186 -0.6836 +vn 0.5502 -0.2236 -0.8045 +vn 0.4108 -0.2960 -0.8623 +vn 0.1151 0.1312 -0.9847 +vn 0.1248 0.1900 -0.9738 +vn -0.0358 -0.0479 -0.9982 +vn -0.0436 -0.0816 -0.9957 +vn -0.3339 0.3262 -0.8844 +vn -0.6898 -0.1317 -0.7119 +vn -0.3104 0.3711 -0.8752 +vn -0.4593 -0.2084 -0.8635 +vn -0.1661 -0.1982 -0.9660 +vn -0.5153 -0.1048 -0.8506 +vn -0.6751 -0.2577 -0.6912 +vn -0.8609 0.3047 -0.4074 +vn -0.8358 -0.0270 -0.5484 +vn -0.8837 0.2704 -0.3820 +vn -0.9121 0.1839 -0.3663 +vn -0.9771 0.2127 0.0109 +vn 0.7601 -0.3091 -0.5715 +vn 0.5482 -0.1019 -0.8301 +vn 0.5768 -0.1358 -0.8055 +vn 0.7271 -0.1049 -0.6785 +vn 0.8324 -0.1541 -0.5323 +vn 0.9644 -0.1857 -0.1881 +vn 0.8879 0.0525 -0.4571 +vn 0.9762 0.2079 -0.0624 +vn 0.9867 -0.1125 0.1177 +vn 0.8398 -0.3966 0.3708 +vn 0.7974 0.1211 0.5912 +vn 0.6072 -0.2957 -0.7375 +vn 0.7606 -0.0883 -0.6432 +vn -0.4443 -0.5330 0.7201 +vn -0.5011 -0.1978 0.8425 +vn -0.6237 -0.5463 0.5591 +vn -0.8477 0.4635 -0.2580 +vn -0.6702 0.4505 -0.5898 +vn -0.5084 0.0235 -0.8608 +vn -0.4445 -0.5178 -0.7310 +vn -0.5971 -0.3169 -0.7369 +vn 0.4736 -0.4062 -0.7815 +vn 0.4704 -0.6290 -0.6189 +vn 0.4119 -0.4020 -0.8177 +vn 0.6938 -0.1487 -0.7046 +vn 0.7148 -0.1270 -0.6877 +vn 0.7628 -0.1554 -0.6277 +vn 0.8054 -0.2369 -0.5433 +vn 0.7806 -0.3914 -0.4872 +vn -0.3526 0.3683 0.8603 +vn -0.2346 0.2249 -0.9457 +vn -0.0202 0.9998 -0.0018 +vn -0.0141 0.9999 -0.0029 +vn -0.0162 0.9999 0.0033 +vn -0.0191 0.9998 0.0116 +vn -0.0221 0.9997 -0.0103 +vn -0.0232 0.9995 -0.0196 +vn -0.0069 0.9997 -0.0251 +vn 0.4420 0.0476 0.8958 +vn -0.3236 0.7390 -0.5909 +vn -0.0015 1.0000 -0.0002 +vn -0.0071 1.0000 0.0034 +vn -0.0146 0.9995 -0.0283 +vn -0.0100 0.9999 0.0078 +vn -0.1665 0.8801 -0.4447 +vn 0.2884 0.4383 0.8513 +vn 0.0031 1.0000 -0.0077 +vn -0.0275 0.9995 0.0121 +vn -0.0002 1.0000 0.0004 +vn 0.0638 0.9846 -0.1630 +vn -0.0063 1.0000 0.0044 +vn 0.0324 0.9993 -0.0196 +vn -0.2584 0.9371 0.2346 +vn -0.0009 1.0000 0.0035 +vn -0.0248 0.9997 -0.0021 +vn 0.0107 0.9999 0.0041 +vn 0.0261 0.9997 -0.0024 +vn 0.0066 0.9999 0.0143 +vn 0.0414 0.9979 -0.0496 +vn 0.0193 0.9994 -0.0285 +vn -0.0018 1.0000 0.0014 +vn -0.0077 1.0000 -0.0020 +vn -0.1076 0.9939 -0.0225 +vn 0.0027 0.9999 -0.0129 +vn -0.0017 1.0000 0.0085 +vn 0.0001 0.9998 0.0175 +vn 0.0024 1.0000 -0.0096 +vn 0.0069 0.9998 -0.0166 +vn -0.0036 0.9996 0.0271 +vn -0.0008 1.0000 0.0003 +vn 0.0020 1.0000 -0.0012 +vn -0.0370 0.9988 0.0319 +vn -0.0014 0.9999 0.0121 +vn -0.0050 1.0000 0.0045 +vn 0.0523 0.9984 0.0194 +vn -0.1313 0.9904 0.0426 +vn -0.1506 0.9874 0.0484 +vn 0.3390 0.9240 -0.1771 +vn 0.0355 0.9992 -0.0165 +vn -0.0919 0.9905 0.1019 +vn -0.0162 0.9998 -0.0063 +vn -0.0009 1.0000 -0.0006 +vn 0.0156 0.9992 -0.0369 +vn 0.3242 0.4612 -0.8259 +vn -0.0141 0.9989 0.0440 +vn -0.0681 0.9969 0.0403 +vn -0.0014 0.9992 0.0389 +vn 0.0289 0.9995 -0.0129 +vn -0.0152 0.9998 0.0106 +vn -0.3975 0.0840 -0.9138 +vn 0.3386 0.6107 0.7158 +vn -0.0005 1.0000 -0.0005 +vn 0.0150 0.9999 -0.0082 +vn -0.0015 1.0000 0.0001 +vn 0.4924 0.8658 -0.0889 +vn -0.1372 0.9886 0.0620 +vn -0.2681 0.9557 0.1212 +vn -0.2318 0.9671 0.1048 +vn 0.8309 -0.0430 -0.5547 +vn -0.3460 0.8569 0.3822 +vn -0.4888 0.7535 0.4396 +vn -0.3684 0.8431 0.3917 +vn -0.5988 0.6432 0.4772 +vn -0.0383 0.9979 0.0516 +vn -0.0044 0.9999 0.0125 +vn -0.0001 1.0000 -0.0055 +vn 0.0056 0.9996 0.0277 +vn -0.0030 0.9999 -0.0129 +vn -0.0382 0.9891 -0.1420 +vn -0.0963 0.9287 -0.3580 +vn 0.0598 0.9866 0.1518 +vn 0.0889 0.9701 0.2259 +vn 0.0390 0.9943 0.0990 +vn -0.0100 0.9999 -0.0031 +vn 0.0157 0.9997 -0.0180 +vn 0.0005 0.2728 -0.9621 +vn 0.0645 0.9978 0.0158 +vn 0.0614 0.9981 0.0024 +vn -0.0031 0.9935 0.1135 +vn -0.0071 0.9917 0.1281 +vn -0.1333 0.9393 0.3160 +vn -0.0719 0.8014 -0.5938 +vn 0.0844 0.9954 0.0460 +vn 0.0753 0.9967 0.0302 +vn 0.0845 0.9952 0.0485 +vn 0.1207 0.9873 0.1031 +vn 0.1256 0.9859 0.1103 +vn 0.4668 0.6701 0.5772 +vn 0.0086 0.9999 -0.0089 +vn 0.0436 0.9962 0.0758 +vn 0.0406 0.9981 0.0470 +vn 0.0442 0.9980 0.0440 +vn 0.0004 0.9965 0.0837 +vn 0.0165 0.9955 0.0936 +vn -0.0246 0.9975 0.0657 +vn 0.0015 0.9985 0.0552 +vn -0.1056 0.9926 0.0608 +vn 0.8468 0.3517 -0.3991 +vn -0.0099 0.9999 0.0062 +vn 0.0352 0.9922 0.1199 +vn 0.0517 0.9980 0.0365 +vn 0.0573 0.9980 0.0274 +vn 0.0337 0.9892 0.1429 +vn 0.0115 0.9699 0.2431 +vn -0.0139 0.9926 0.1209 +vn 0.0010 0.9940 0.1097 +vn -0.0024 0.9998 -0.0196 +vn -0.0111 0.9854 -0.1699 +vn -0.0231 0.9997 -0.0125 +vn -0.0010 0.9985 -0.0549 +vn 0.0506 0.9977 0.0443 +vn 0.0041 1.0000 -0.0037 +vn 0.0082 0.9993 0.0366 +vn -0.0921 0.9927 0.0774 +vn -0.0145 0.9999 -0.0068 +vn -0.0472 0.9989 0.0057 +vn -0.0220 0.9995 -0.0219 +vn -0.0100 0.9969 -0.0777 +vn 0.0001 1.0000 0.0060 +vn 0.0113 0.9999 -0.0108 +vn 0.0102 0.9999 -0.0058 +vn -0.0013 0.9999 0.0117 +vn 0.0100 0.9998 0.0158 +vn 0.1711 0.9195 0.3540 +vn 0.0034 0.9999 0.0112 +vn -0.0103 0.9999 -0.0037 +vn -0.0173 0.9998 -0.0040 +vn 0.0188 0.9992 -0.0361 +vn -0.0002 0.9998 0.0202 +vn -0.0026 1.0000 0.0005 +vn -0.0076 0.9993 -0.0379 +vn 0.0636 0.6757 -0.7344 +vn 0.0278 0.9974 -0.0660 +vn 0.0295 0.9977 -0.0612 +vn -0.0076 1.0000 -0.0035 +vn -0.0031 0.9999 -0.0116 +vn 0.0485 0.9968 -0.0637 +vn 0.0463 0.9986 -0.0267 +vn 0.9217 0.1946 -0.3355 +vn -0.0193 0.9998 0.0069 +vn 0.0971 0.9948 -0.0320 +vn 0.1272 0.9855 -0.1123 +vn 0.1113 0.9933 -0.0322 +vn 0.1032 0.9933 -0.0515 +vn 0.0898 0.9938 -0.0662 +vn 0.0849 0.9931 -0.0805 +vn 0.0866 0.9917 -0.0954 +vn -0.9557 0.1021 0.2759 +vn -0.9339 0.1534 0.3229 +vn -0.9199 0.1810 0.3478 +vn 0.5786 0.7024 -0.4145 +vn 0.0432 0.9974 0.0575 +vn 0.0596 0.9981 0.0151 +vn 0.0181 0.9982 0.0566 +vn 0.0021 1.0000 0.0077 +vn 0.0068 0.9997 0.0224 +vn -0.0260 0.9953 -0.0930 +vn 0.2839 0.4715 0.8349 +vn -0.0324 0.9985 -0.0450 +vn -0.0315 0.9952 0.0929 +vn -0.0884 0.9912 0.0981 +vn 0.0166 0.5275 -0.8494 +vn 0.1165 0.9931 0.0085 +vn 0.1030 0.9945 0.0179 +vn 0.0818 0.9960 0.0349 +vn 0.0950 0.9949 -0.0340 +vn -0.0557 0.9949 -0.0837 +vn 0.1465 -0.7830 0.6046 +vn -0.0590 0.9757 -0.2112 +vn -0.0426 0.9875 -0.1518 +vn -0.8325 -0.0924 0.5462 +vn -0.3866 0.9025 0.1900 +vn -0.1942 0.9763 0.0954 +vn 0.0354 0.9990 -0.0275 +vn 0.1115 0.9928 -0.0431 +vn 0.1666 0.9839 -0.0645 +vn -0.0063 0.9998 -0.0166 +vn 0.1806 0.9778 -0.1062 +vn 0.2902 0.9416 -0.1707 +vn -0.2087 0.8797 0.4274 +vn 0.0906 0.9653 -0.2448 +vn 0.4022 0.6237 0.6703 +vn -0.1126 0.9857 -0.1256 +vn -0.0676 0.9949 -0.0746 +vn -0.1546 0.6167 0.7719 +vn 0.1148 0.4408 -0.8902 +vn -0.0164 0.9920 0.1254 +vn -0.0071 0.9999 -0.0117 +vn -0.0008 1.0000 -0.0003 +vn 0.0039 0.9911 -0.1333 +vn -0.5099 0.2905 0.8097 +vn -0.5272 0.2679 0.8064 +vn -0.5133 0.2861 0.8091 +vn 0.3255 0.7274 -0.6042 +vn -0.2225 0.1186 0.9677 +vn -0.0274 0.9992 -0.0307 +vn -0.0396 0.9980 -0.0494 +vn -0.0367 0.9983 -0.0453 +vn -0.0110 0.9999 -0.0061 +vn -0.0213 0.9995 -0.0254 +vn 0.6630 -0.3462 0.6637 +vn -0.6327 0.6319 -0.4477 +vn -0.0063 0.9996 0.0286 +vn -0.0294 0.9969 0.0736 +vn -0.0729 0.9961 0.0492 +vn 0.1939 -0.9513 0.2398 +vn -0.0249 0.9995 0.0171 +vn 0.0518 0.9952 -0.0834 +vn -0.0139 0.9999 0.0017 +vn 0.5960 -0.4767 -0.6462 +vn -0.0847 -0.5678 0.8188 +vn -0.0350 -0.8088 0.5870 +vn 0.0085 -0.6275 0.7785 +vn -0.8181 -0.4835 0.3113 +vn -0.7022 -0.5639 0.4346 +vn -0.7007 -0.6288 0.3371 +vn -0.2623 -0.4821 0.8359 +vn -0.2535 -0.4493 0.8567 +vn -0.2748 -0.4659 0.8411 +vn -0.7020 -0.3478 0.6214 +vn -0.7038 -0.5238 0.4799 +vn -0.4232 -0.6838 0.5944 +vn -0.5244 -0.5664 0.6357 +vn 0.1861 -0.8915 0.4130 +vn 0.1524 -0.6585 0.7370 +vn 0.4937 -0.7022 0.5130 +vn 0.7966 -0.5559 0.2374 +vn 0.9162 -0.3907 -0.0894 +vn 0.6461 -0.7604 0.0654 +vn 0.8834 -0.4684 -0.0145 +vn 0.3512 -0.7881 -0.5056 +vn 0.3078 -0.4244 -0.8515 +vn 0.3125 -0.4270 -0.8485 +vn 0.2276 -0.4602 -0.8581 +vn -0.0098 -1.0000 0.0014 +vn -0.0136 -0.9997 0.0223 +vn -0.1754 -0.9688 0.1750 +vn -0.3046 -0.7372 0.6031 +vn 0.1344 -0.3492 0.9273 +vn 0.3031 -0.6147 0.7282 +vn 0.7585 -0.4938 0.4253 +vn 0.7716 -0.4616 0.4378 +vn 0.7878 -0.5384 0.2992 +vn 0.8594 -0.4806 -0.1747 +vn 0.8393 -0.5098 -0.1889 +vn 0.0505 -0.9986 -0.0134 +vn 0.4568 -0.8508 -0.2597 +vn 0.4110 -0.8958 -0.1692 +vn 0.7026 -0.5794 -0.4130 +vn 0.7591 -0.4786 -0.4412 +vn 0.3169 -0.8183 -0.4795 +vn 0.3812 -0.4192 -0.8240 +vn 0.2256 -0.4644 -0.8564 +vn 0.0268 -0.8380 -0.5450 +vn 0.0180 -0.9985 -0.0508 +vn -0.0127 -0.9397 -0.3417 +vn -0.8507 -0.4261 0.3078 +vn -0.5042 -0.4963 0.7067 +vn 0.0767 -0.7085 -0.7015 +vn 0.1503 -0.4209 -0.8945 +vn 0.0009 0.1178 -0.9930 +vn 0.0555 -0.4723 -0.8797 +vn 0.0427 -0.5024 -0.8636 +vn -0.0092 -0.8840 -0.4674 +vn 0.0006 -0.9718 -0.2359 +vn -0.9110 -0.3428 -0.2291 +vn -0.4952 -0.2966 -0.8166 +vn -0.5261 -0.3025 -0.7948 +vn -0.7834 -0.3323 -0.5253 +vn -0.8881 -0.3975 -0.2306 +vn -0.8873 -0.4268 -0.1746 +vn -0.9019 -0.4292 0.0478 +vn -0.9661 0.0722 0.2480 +vn -0.7801 -0.0087 0.6256 +vn -0.6776 0.1735 0.7146 +vn -0.7309 0.0225 0.6821 +vn -0.7229 -0.0600 0.6884 +vn -0.7292 -0.1025 0.6766 +vn -0.3187 -0.3223 0.8914 +vn -0.2705 -0.4315 0.8606 +vn -0.0997 -0.5157 0.8509 +vn 0.1839 -0.5986 0.7797 +vn -0.0490 -0.5178 0.8541 +vn 0.5409 -0.1652 0.8247 +vn 0.6707 -0.6744 0.3088 +vn 0.5973 -0.7852 0.1632 +vn 0.6410 -0.7371 0.2141 +vn -0.5328 -0.7776 0.3338 +vn -0.5578 -0.7835 0.2739 +vn -0.3359 -0.8181 0.4668 +vn -0.3550 -0.2206 0.9084 +vn 0.1892 -0.8361 0.5149 +vn 0.3276 -0.8418 0.4290 +vn 0.3570 -0.8182 0.4506 +vn 0.1092 0.1133 -0.9875 +vn 0.9458 -0.0234 0.3240 +vn 0.7135 -0.4245 0.5574 +vn 0.8526 -0.5046 0.1359 +vn -0.8258 -0.5346 -0.1799 +vn -0.1261 -0.5641 -0.8160 +vn -0.2455 -0.7220 -0.6469 +vn -0.2133 -0.6579 -0.7222 +vn -0.6950 -0.5846 -0.4185 +vn -0.7583 -0.5064 -0.4105 +vn -0.7096 -0.6330 -0.3096 +vn 0.6021 -0.6273 -0.4939 +vn 0.6468 -0.4933 -0.5816 +vn 0.6680 -0.3883 -0.6349 +vn 0.6262 -0.7796 -0.0082 +vn 0.6821 -0.7241 0.1020 +vn 0.6920 -0.7023 0.1671 +vn 0.0246 -0.7631 -0.6458 +vn 0.0537 -0.8125 -0.5804 +vn 0.5838 -0.6675 -0.4621 +vn 0.4584 -0.8497 0.2607 +vn 0.3160 -0.9149 0.2513 +vn 0.4644 -0.5845 0.6654 +vn 0.7992 -0.5796 -0.1591 +vn -0.3662 -0.2983 0.8815 +vn -0.2480 -0.7789 0.5761 +vn -0.2496 -0.7766 0.5785 +vn -0.2494 -0.7768 0.5783 +vn -0.2479 -0.7791 0.5758 +vn 0.7465 -0.4485 -0.4915 +vn 0.6870 -0.1599 -0.7088 +vn 0.5156 -0.7552 -0.4048 +vn 0.5687 -0.6368 -0.5206 +vn 0.5229 -0.7434 -0.4171 +vn 0.3381 -0.7998 -0.4959 +vn 0.3324 -0.8099 -0.4832 +vn 0.4151 -0.7743 -0.4777 +vn 0.5251 -0.8110 -0.2579 +vn 0.4072 -0.6701 -0.6207 +vn -0.9167 -0.3991 0.0191 +vn -0.8572 -0.4733 0.2028 +vn -0.8970 -0.4057 0.1753 +vn -0.9707 -0.2237 -0.0879 +vn -0.3999 -0.8683 0.2934 +vn -0.5915 -0.5454 0.5939 +vn -0.7646 -0.4033 0.5028 +vn 0.7820 -0.4046 -0.4742 +vn 0.0778 -0.4217 -0.9034 +vn -0.0237 -0.3009 -0.9534 +vn -0.1398 -0.4490 -0.8825 +vn -0.0258 -0.9966 -0.0777 +vn -0.2546 -0.9240 -0.2854 +vn -0.8569 -0.4442 0.2616 +vn -0.8156 -0.4084 0.4099 +vn -0.8478 -0.4475 0.2845 +vn 0.3201 -0.8787 -0.3542 +vn 0.0488 -0.9972 -0.0562 +vn 0.2622 -0.8204 -0.5080 +vn 0.2566 -0.3904 -0.8841 +vn 0.2207 -0.3987 -0.8901 +vn 0.1316 -0.8915 -0.4336 +vn 0.0284 -0.9946 -0.0998 +vn 0.0922 -0.4616 -0.8823 +vn -0.2437 -0.3999 -0.8836 +vn -0.0259 -0.8861 -0.4628 +vn -0.0311 -0.9587 -0.2828 +vn -0.3157 -0.5134 -0.7980 +vn -0.3229 -0.5391 -0.7779 +vn -0.5222 -0.6818 -0.5123 +vn -0.7066 -0.5138 -0.4865 +vn -0.7401 -0.5296 -0.4145 +vn -0.5494 -0.8102 -0.2041 +vn -0.7086 -0.6960 -0.1156 +vn -0.9534 -0.2968 0.0537 +vn -0.8292 -0.5525 -0.0849 +vn -0.3305 -0.9438 0.0100 +vn -0.0175 -0.9998 -0.0043 +vn -0.0418 -0.9991 -0.0046 +vn -0.9233 -0.3498 0.1583 +vn -0.4857 -0.8352 0.2581 +vn -0.5316 0.2620 0.8055 +vn 0.4422 -0.5890 0.6764 +vn 0.4984 -0.6178 0.6082 +vn 0.4430 -0.5883 0.6765 +vn 0.9105 -0.3118 0.2714 +vn 0.9255 -0.2766 0.2588 +vn 0.8570 -0.2798 0.4328 +vn -0.8221 -0.4881 -0.2929 +vn -0.8313 -0.4994 -0.2439 +vn -0.8413 -0.4744 -0.2593 +vn -0.7821 -0.5506 0.2918 +vn -0.6974 -0.6929 0.1828 +vn -0.7454 -0.6214 0.2411 +vn 0.0015 -0.6025 0.7981 +vn -0.0222 -0.6272 0.7786 +vn 0.1931 -0.5862 0.7868 +vn 0.8291 -0.2636 0.4930 +vn -0.4081 -0.6829 0.6059 +vn -0.5771 -0.4327 0.6926 +vn -0.5176 -0.5362 0.6668 +vn 0.2295 -0.5676 0.7907 +vn -0.5208 -0.7859 -0.3334 +vn -0.6411 -0.6927 -0.3304 +vn -0.6490 -0.7496 0.1300 +vn -0.3587 -0.7358 0.5743 +vn 0.2331 -0.9532 0.1926 +vn 0.0607 -0.9953 0.0755 +vn 0.2608 -0.8427 0.4710 +vn 0.0701 0.9792 0.1904 +vn -0.0491 -0.7614 0.6464 +vn 0.0425 -0.6438 0.7641 +vn 0.2922 -0.5070 0.8109 +vn 0.7203 -0.1589 0.6752 +vn -0.2692 -0.7369 0.6201 +vn -0.3564 -0.4378 0.8254 +vn -0.2216 -0.8516 0.4750 +vn 0.3637 -0.7365 0.5703 +vn 0.3490 -0.7389 0.5764 +vn 0.3755 -0.7344 0.5653 +vn 0.3315 -0.7415 0.5834 +vn 0.7759 -0.6277 -0.0634 +vn 0.7375 -0.6750 -0.0220 +vn 0.7836 -0.6170 -0.0723 +vn 0.8007 -0.5918 -0.0928 +vn -0.5179 -0.6363 0.5717 +vn -0.4700 -0.6704 0.5742 +vn -0.5938 -0.5748 0.5630 +vn 0.0673 -0.4038 0.9124 +vn -0.3597 -0.7365 0.5729 +vn -0.6898 -0.7158 -0.1092 +vn -0.7317 -0.3367 -0.5927 +vn -0.2141 -0.7207 -0.6594 +vn 0.4629 -0.5570 -0.6896 +vn 0.3874 -0.6218 -0.6806 +vn 0.3868 -0.6223 -0.6805 +vn 0.3424 -0.6562 -0.6724 +vn -0.8101 -0.0090 -0.5863 +vn -0.6361 -0.7477 -0.1904 +vn -0.5794 -0.7909 0.1970 +vn -0.5835 -0.2058 0.7856 +vn 0.0188 -0.7439 0.6680 +vn -0.2626 -0.6604 -0.7035 +vn -0.4389 -0.5637 -0.6997 +vn -0.2908 -0.6471 -0.7048 +vn -0.0409 -0.7400 -0.6713 +vn 0.6247 -0.5380 -0.5659 +vn 0.6181 -0.4790 -0.6233 +vn 0.6268 -0.5753 -0.5255 +vn 0.6232 -0.6649 -0.4117 +vn 0.6798 -0.6291 0.3770 +vn 0.6877 -0.5509 0.4728 +vn 0.6880 -0.5303 0.4954 +vn 0.6865 -0.4840 0.5426 +vn 0.5269 -0.6362 -0.5636 +vn 0.5050 -0.6584 -0.5581 +vn 0.4730 -0.6889 -0.5493 +vn 0.4362 -0.7211 -0.5383 +vn -0.2220 -0.4092 -0.8851 +vn -0.2867 -0.5144 -0.8082 +vn -0.3634 -0.6374 -0.6794 +vn -0.4056 -0.7040 -0.5830 +vn 0.7995 -0.5261 0.2900 +vn 0.7701 -0.5957 0.2284 +vn 0.7580 -0.6189 0.2061 +vn 0.7394 -0.6503 0.1744 +vn -0.1333 -0.4946 0.8588 +vn -0.1254 -0.5054 0.8537 +vn -0.1219 -0.5101 0.8514 +vn -0.1186 -0.5147 0.8491 +vn -0.6775 -0.7170 0.1639 +vn -0.7747 -0.6294 0.0599 +vn -0.7901 -0.6116 0.0407 +vn -0.8423 -0.5381 -0.0329 +vn 0.4226 -0.6268 0.6546 +vn 0.2748 -0.7119 0.6463 +vn 0.5192 -0.5561 0.6490 +vn 0.6323 -0.4536 0.6281 +vn 0.7364 -0.6747 0.0510 +vn 0.6826 -0.7181 0.1360 +vn 0.7468 -0.6643 0.0327 +vn 0.7887 -0.6126 -0.0506 +vn 0.4910 -0.6976 -0.5217 +vn 0.4937 -0.7368 -0.4619 +vn 0.2155 -0.7205 -0.6592 +vn 0.1879 -0.6741 -0.7144 +vn -0.2856 -0.6701 -0.6852 +vn -0.4437 -0.7113 -0.5452 +vn -0.4029 -0.6654 0.6284 +vn -0.2951 -0.5548 0.7779 +vn -0.4124 -0.6745 0.6124 +vn -0.5035 -0.7541 0.4216 +vn -0.7652 -0.6365 -0.0963 +vn -0.8405 -0.5364 0.0763 +vn -0.6986 -0.6464 -0.3070 +vn 0.6760 -0.6228 -0.3939 +vn 0.6386 -0.6559 -0.4024 +vn 0.6101 -0.6792 -0.4080 +vn 0.5531 -0.7212 -0.4171 +vn -0.0012 -0.4961 -0.8682 +vn -0.3519 -0.6682 -0.6555 +vn 0.0742 -0.4029 -0.9122 +vn -0.4055 -0.7409 -0.5354 +vn 0.7204 -0.6107 0.3287 +vn 0.7050 -0.6246 0.3359 +vn 0.7230 -0.6083 0.3275 +vn 0.7492 -0.5830 0.3145 +vn 0.1113 -0.7148 0.6904 +vn -0.0414 -0.5997 0.7991 +vn -0.0688 -0.5759 0.8146 +vn -0.1661 -0.4828 0.8598 +vn -0.5906 -0.7135 0.3768 +vn -0.7317 -0.6304 0.2591 +vn -0.7199 -0.6866 0.1013 +vn -0.6751 -0.6960 -0.2446 +vn 0.3045 -0.6328 -0.7120 +vn 0.3313 -0.6899 -0.6436 +vn 0.2948 -0.6122 -0.7337 +vn 0.5055 -0.7399 0.4439 +vn 0.8667 -0.4950 -0.0613 +vn 0.8470 -0.5257 -0.0793 +vn 0.8299 -0.5499 -0.0939 +vn 0.7772 -0.6148 -0.1342 +vn 0.2782 -0.5768 -0.7681 +vn -0.5460 -0.5895 -0.5953 +vn -0.5186 -0.6090 -0.6001 +vn -0.3529 -0.7061 -0.6140 +vn -0.1100 -0.1053 0.9883 +vn 0.1454 -0.5869 0.7965 +vn -0.8131 -0.5393 0.2194 +vn -0.7257 -0.6337 0.2680 +vn -0.7053 -0.6522 0.2777 +vn -0.6448 -0.7014 0.3037 +vn -0.6492 -0.5044 -0.5693 +vn -0.1887 -0.4824 0.8554 +vn -0.1449 -0.5373 0.8308 +vn -0.0992 -0.5906 0.8009 +vn -0.0184 -0.6748 0.7377 +vn 0.5464 -0.6475 0.5312 +vn 0.5458 -0.6466 0.5330 +vn 0.5384 -0.6344 0.5547 +vn 0.5538 -0.6599 0.5078 +vn -0.6472 -0.7173 0.2582 +vn -0.9311 -0.3603 -0.0568 +vn -0.3711 -0.7862 -0.4941 +vn 0.1776 -0.4900 -0.8534 +vn 0.1361 -0.4318 -0.8916 +vn 0.1963 -0.5157 -0.8340 +vn 0.2727 -0.6169 -0.7383 +vn 0.7386 -0.6548 -0.1603 +vn 0.7852 -0.6092 -0.1114 +vn 0.7873 -0.6069 -0.1090 +vn 0.8150 -0.5745 -0.0763 +vn -0.8939 -0.4484 0.0007 +vn -0.8192 -0.5707 0.0566 +vn -0.7994 -0.5968 0.0691 +vn -0.7700 -0.6321 0.0866 +vn -0.3268 -0.6531 0.6831 +vn -0.3395 -0.6877 0.6417 +vn -0.3655 -0.7609 0.5362 +vn -0.3038 -0.5925 0.7461 +vn -0.4927 -0.6131 -0.6175 +vn -0.5016 -0.6391 -0.5830 +vn -0.5017 -0.6394 -0.5826 +vn -0.5069 -0.6553 -0.5600 +vn 0.3257 -0.5472 -0.7711 +vn 0.2987 -0.5719 -0.7640 +vn 0.2952 -0.5750 -0.7630 +vn 0.2806 -0.5878 -0.7587 +vn 0.7472 -0.6641 -0.0266 +vn 0.7762 -0.6304 0.0086 +vn 0.7837 -0.6209 0.0181 +vn 0.8002 -0.5983 0.0402 +vn 0.2522 -0.5631 0.7869 +vn 0.2984 -0.6316 0.7156 +vn 0.2960 -0.6282 0.7195 +vn 0.3285 -0.6749 0.6608 +vn -0.0009 -0.9981 0.0615 +vn 0.0005 -0.9999 0.0110 +vn 0.0036 -1.0000 -0.0070 +vn 0.0098 -0.9998 -0.0166 +vn 0.0040 -1.0000 -0.0091 +vn -0.0032 -1.0000 -0.0048 +vn -0.0074 -1.0000 -0.0034 +vn -0.0219 -0.9995 0.0220 +vn -0.0103 -0.9999 0.0018 +vn 0.0074 -0.9999 -0.0149 +vn -0.0167 -0.9998 -0.0131 +vn -0.0021 -1.0000 0.0094 +vn 0.0015 -1.0000 0.0023 +vn 0.0015 -1.0000 0.0001 +vn 0.0015 -1.0000 -0.0053 +vn 0.0007 -1.0000 0.0020 +vn -0.0033 -0.9996 0.0283 +vn -0.0051 -0.9989 0.0455 +vn 0.0178 -0.9846 -0.1741 +vn 0.0064 -0.9999 -0.0128 +vn 0.0036 -1.0000 0.0023 +vn 0.0075 -0.9999 -0.0083 +vn 0.0003 -1.0000 -0.0050 +vn -0.0046 -1.0000 0.0080 +vn -0.0048 -0.9999 -0.0113 +vn 0.0007 -1.0000 0.0013 +vn 0.0217 -0.9993 -0.0301 +vn 0.0027 -1.0000 0.0053 +vn 0.0021 -1.0000 -0.0031 +vn -0.0020 -1.0000 0.0009 +vn 0.0007 -0.9999 0.0126 +vn 0.0038 -1.0000 0.0049 +vn -0.0072 -0.9999 0.0133 +vn -0.0060 -1.0000 -0.0020 +vn 0.0289 -0.9995 0.0119 +vn 0.0005 -1.0000 0.0070 +vn -0.0247 -0.9995 -0.0211 +vn 0.0257 -0.9992 -0.0309 +vn -0.0016 -0.9992 -0.0389 +vn -0.0005 -1.0000 -0.0024 +vn 0.0026 -1.0000 -0.0067 +vn -0.0141 -0.9988 0.0474 +vn 0.0248 -0.9995 -0.0210 +vn -0.0041 -1.0000 -0.0010 +vn 0.0017 -0.9998 0.0216 +vn 0.0220 -0.9997 0.0051 +vn 0.0055 -0.9999 0.0140 +vn -0.0084 -0.9995 -0.0316 +vn -0.0127 -0.9987 -0.0487 +vn -0.0012 -0.9995 -0.0330 +vn 0.0002 -1.0000 0.0063 +vn -0.0172 -0.9995 -0.0262 +vn -0.0004 -1.0000 0.0099 +vn -0.0229 -0.9995 0.0227 +vn -0.0054 -0.9998 0.0207 +vn 0.2613 0.9645 0.0379 +vn -0.0178 0.9554 0.2947 +vn 0.1911 0.9681 0.1619 +vn 0.7846 -0.0090 -0.6200 +vn 0.7854 0.1443 -0.6019 +vn 0.7860 0.1023 -0.6096 +vn 0.7807 -0.0052 -0.6249 +vn 0.7983 -0.0109 0.6021 +vn 0.8356 0.0086 0.5493 +vn 0.8199 0.0002 0.5725 +vn 0.7890 -0.0155 0.6142 +vn 0.1413 0.1409 0.9799 +vn -0.6254 -0.1413 0.7674 +vn -0.9628 0.1023 0.2500 +vn -0.9536 0.1720 0.2470 +vn -0.9528 0.1769 0.2468 +vn -0.6898 -0.0981 -0.7173 +vn -0.5729 -0.0126 -0.8195 +vn -0.6303 -0.0529 -0.7746 +vn -0.4911 0.0407 -0.8701 +vn 0.1677 0.5666 -0.8067 +vn 0.6054 0.7214 -0.3363 +vn 0.6176 0.6757 -0.4025 +vn 0.6186 0.6708 -0.4090 +vn 0.6285 0.5968 -0.4989 +vn 0.6150 0.6884 0.3844 +vn 0.6256 0.6120 0.4838 +vn 0.6157 0.6851 0.3893 +vn 0.6012 0.7371 0.3085 +vn 0.2932 0.5912 0.7513 +vn -0.4047 0.6723 0.6199 +vn -0.4175 0.6989 0.5807 +vn -0.4203 0.7048 0.5715 +vn -0.4329 0.7315 0.5268 +vn -0.8280 0.5605 0.0175 +vn -0.4615 0.7297 -0.5045 +vn -0.4665 0.7432 -0.4797 +vn -0.4610 0.7284 -0.5069 +vn -0.4553 0.7138 -0.5322 +vn 0.7006 0.4757 -0.5319 +vn 0.5142 0.8575 -0.0182 +vn -0.1131 0.8692 0.4813 +vn -0.9159 0.3246 0.2361 +vn -0.3081 0.7897 -0.5305 +vn -0.3060 0.7913 -0.5294 +vn -0.3031 0.7933 -0.5280 +vn -0.3004 0.7953 -0.5265 +vn 0.0452 -0.9988 0.0190 +vn 0.0381 -0.9993 -0.0008 +vn 0.0529 -0.9983 -0.0231 +vn -0.0255 -0.9992 0.0313 +vn -0.0084 -0.9982 0.0588 +vn -0.0433 -0.9986 0.0295 +vn 0.0147 -0.9991 0.0400 +vn 0.0323 -0.9988 -0.0356 +vn -0.0526 -0.9986 0.0010 +vn 0.0088 -0.9990 -0.0448 +vn -0.0128 -0.9994 -0.0327 +vn -0.0400 -0.9990 -0.0205 +vn -0.0241 0.9995 0.0207 +vn 0.1226 0.9821 0.1431 +vn 0.1018 0.9923 -0.0707 +vn 0.0185 0.9860 0.1657 +vn -0.0772 0.9880 -0.1340 +vn 0.9257 -0.0022 0.3782 +vn 0.9973 -0.0098 -0.0722 +vn 0.9408 0.0178 0.3386 +vn 0.6299 -0.0012 -0.7767 +vn 0.4723 -0.0026 -0.8814 +vn 0.6196 0.0008 -0.7849 +vn 0.4561 -0.0047 -0.8899 +vn -0.6196 0.0085 -0.7849 +vn -0.5877 0.0043 -0.8090 +vn -0.5900 0.0046 -0.8074 +vn -0.6215 0.0087 -0.7834 +vn -0.9972 0.0134 -0.0732 +vn -0.9861 0.0062 -0.1659 +vn -0.9869 0.0066 -0.1612 +vn -0.9976 0.0138 -0.0682 +vn -0.7836 0.0111 0.6212 +vn -0.7424 0.0061 0.6699 +vn -0.7812 0.0108 0.6242 +vn -0.7404 0.0059 0.6721 +vn -0.2920 0.0143 0.9563 +vn -0.0097 -0.0026 0.9999 +vn -0.2802 0.0136 0.9599 +vn 0.0034 -0.0033 1.0000 +vn 0.6168 0.0078 0.7871 +vn 0.6653 0.0046 0.7466 +vn 0.8044 0.0139 0.5939 +vn 0.1076 0.9933 0.0423 +vn 0.1172 0.9931 -0.0067 +vn 0.0995 0.9934 -0.0572 +vn -0.0821 0.9947 -0.0621 +vn -0.0961 0.9943 -0.0454 +vn -0.1159 0.9930 0.0243 +vn 0.0869 0.9929 0.0813 +vn 0.0424 0.9936 0.1044 +vn -0.0152 0.9927 -0.1193 +vn -0.0467 0.9922 -0.1156 +vn 0.0564 0.9939 -0.0943 +vn -0.0452 0.9937 0.1025 +vn -0.0006 0.9932 0.1160 +vn -0.0868 0.9941 0.0656 +vn 0.9704 0.0345 0.2390 +vn 0.9123 -0.0281 0.4086 +vn 0.9972 -0.0499 0.0561 +vn 0.8678 0.0623 -0.4930 +vn 0.8521 0.0401 -0.5219 +vn 0.8591 0.0497 -0.5094 +vn 0.8385 0.0222 -0.5445 +vn 0.1656 0.0334 -0.9856 +vn 0.3641 -0.0701 -0.9287 +vn -0.0294 -0.0344 -0.9990 +vn -0.3384 0.0447 -0.9399 +vn -0.5177 -0.0212 -0.8553 +vn -0.6648 0.0654 -0.7442 +vn -0.9979 0.0487 -0.0428 +vn -0.9458 -0.0642 -0.3183 +vn -0.9998 -0.0077 0.0200 +vn -0.9811 0.0555 0.1855 +vn -0.9404 -0.0378 0.3380 +vn -0.4315 0.0241 0.9018 +vn -0.4676 -0.0059 0.8839 +vn -0.4420 0.0154 0.8969 +vn -0.4081 0.0430 0.9119 +vn 0.3184 0.0291 0.9475 +vn 0.2144 -0.0172 0.9766 +vn 0.4620 -0.0240 0.8866 +vn 0.7100 0.0433 0.7029 +vn 0.9852 0.1238 0.1185 +vn 0.9679 -0.0016 0.2512 +vn 0.9688 0.0016 0.2478 +vn 0.9198 -0.1237 0.3723 +vn -0.3898 0.1237 -0.9125 +vn -0.2663 -0.0017 -0.9639 +vn -0.2697 0.0016 -0.9629 +vn -0.1374 -0.1239 -0.9827 +vn -0.5951 0.1239 0.7940 +vn -0.7014 -0.0016 0.7128 +vn -0.6989 0.0017 0.7152 +vn -0.7822 -0.1238 0.6105 +vn 0.0731 0.8794 0.4704 +vn -0.0963 0.9356 -0.3397 +vn 0.6267 -0.0791 -0.7752 +vn 0.5007 0.8656 0.0074 +vn 0.0338 -0.9992 0.0219 +vn 0.0544 -0.9981 0.0281 +vn 0.0157 -0.9987 0.0480 +vn 0.0422 -0.9990 -0.0120 +vn -0.0320 -0.9993 0.0202 +vn -0.0171 -0.9989 0.0434 +vn -0.0406 -0.9992 -0.0063 +vn -0.0065 -0.9991 -0.0407 +vn 0.0206 -0.9991 -0.0374 +vn -0.0306 -0.9988 -0.0394 +vn 0.1390 0.9809 0.1362 +vn -0.1034 0.9945 0.0163 +vn 0.1005 0.9832 0.1527 +vn -0.1361 0.9904 -0.0248 +vn 0.9830 0.0875 -0.1613 +vn 0.9769 -0.0075 0.2133 +vn 0.9819 -0.0060 0.1893 +vn 0.9801 0.0862 -0.1789 +vn 0.2652 0.0231 -0.9639 +vn 0.6561 -0.0149 -0.7546 +vn 0.6307 -0.0121 -0.7760 +vn 0.2326 0.0259 -0.9722 +vn -0.6544 -0.0116 -0.7561 +vn -0.4576 0.0232 -0.8888 +vn -0.6420 -0.0092 -0.7666 +vn -0.4422 0.0257 -0.8966 +vn -0.9428 0.0162 0.3329 +vn -0.9996 -0.0168 -0.0246 +vn -0.9999 -0.0146 -0.0002 +vn -0.9334 0.0186 0.3585 +vn -0.2823 0.0138 0.9592 +vn -0.3824 0.0040 0.9240 +vn -0.3756 0.0047 0.9268 +vn -0.2742 0.0145 0.9616 +vn 0.6590 0.0149 0.7520 +vn 0.4946 0.0021 0.8691 +vn 0.5058 0.0029 0.8627 +vn 0.6682 0.0157 0.7439 +vn 0.0900 0.9936 0.0680 +vn 0.0833 0.9942 0.0684 +vn 0.1039 0.9942 -0.0274 +vn 0.1126 0.9936 0.0065 +vn -0.0948 0.9935 -0.0625 +vn -0.0546 0.9929 -0.1061 +vn -0.1093 0.9933 -0.0383 +vn 0.0311 0.9938 0.1069 +vn -0.0030 0.9948 0.1021 +vn 0.0098 0.9944 -0.1052 +vn 0.0377 0.9937 -0.1058 +vn -0.0870 0.9944 0.0604 +vn -0.0994 0.9940 0.0452 +vn 0.0883 0.9938 -0.0682 +vn 0.7560 0.0464 0.6529 +vn 0.9092 -0.0342 0.4149 +vn 0.9994 0.0334 0.0018 +vn 0.9609 -0.0400 -0.2741 +vn 0.7990 0.0269 -0.6008 +vn 0.7217 -0.0307 -0.6915 +vn 0.5511 0.0619 -0.8321 +vn -0.0390 -0.0474 -0.9981 +vn -0.0369 -0.0457 -0.9983 +vn -0.0374 -0.0462 -0.9982 +vn -0.0357 -0.0448 -0.9984 +vn -0.7260 0.0645 -0.6846 +vn -0.8305 -0.0335 -0.5561 +vn -0.8053 -0.0072 -0.5928 +vn -0.8803 -0.0943 -0.4650 +vn -0.9953 0.0890 0.0384 +vn -0.9425 -0.0376 0.3322 +vn -0.9711 0.0039 0.2386 +vn -0.8617 -0.1131 0.4947 +vn -0.5459 0.1257 0.8283 +vn 0.2380 0.0142 0.9712 +vn -0.0462 -0.1062 0.9933 +vn 0.3724 -0.0413 0.9271 +vn 0.8719 0.1237 0.4738 +vn 0.8070 -0.0016 0.5906 +vn 0.8090 0.0017 0.5878 +vn 0.7177 -0.1236 0.6853 +vn -0.0256 0.1236 -0.9920 +vn 0.1081 -0.0018 -0.9941 +vn 0.1046 0.0015 -0.9945 +vn 0.2349 -0.1239 -0.9641 +vn -0.8464 0.1237 0.5180 +vn -0.9150 -0.0016 0.4034 +vn -0.9136 0.0017 0.4066 +vn -0.9524 -0.1237 0.2787 +vn -0.3008 0.9512 -0.0681 +vn 0.2501 0.8769 -0.4105 +vn 0.9352 0.3113 -0.1686 +vn 0.4518 0.8348 0.3145 +vn -0.0411 -0.9988 0.0262 +vn -0.0254 -0.9984 0.0512 +vn -0.0534 -0.9985 0.0126 +vn 0.0515 -0.9980 -0.0367 +vn 0.0497 -0.9987 0.0078 +vn 0.0456 -0.9987 -0.0206 +vn 0.0178 -0.9992 0.0353 +vn 0.0184 -0.9991 0.0382 +vn -0.0410 -0.9988 -0.0280 +vn -0.0220 -0.9991 -0.0354 +vn 0.0051 -0.9989 -0.0468 +vn 0.0387 0.9973 0.0622 +vn 0.0208 0.9987 0.0474 +vn 0.0671 0.9960 0.0585 +vn -0.0832 0.9949 0.0578 +vn -0.1401 0.9877 0.0693 +vn 0.7940 0.0138 0.6077 +vn 0.8922 -0.0032 0.4516 +vn 0.8037 0.0123 0.5949 +vn 0.8976 -0.0044 0.4407 +vn 0.9655 0.0227 -0.2593 +vn 0.7997 0.0026 -0.6003 +vn 0.7738 0.0229 -0.6330 +vn 0.4287 -0.0038 -0.9034 +vn 0.3845 0.0182 -0.9229 +vn -0.0261 -0.0098 -0.9996 +vn -0.6470 0.0507 -0.7608 +vn -0.8784 -0.0106 -0.4778 +vn -0.6632 0.0475 -0.7470 +vn -0.8920 -0.0130 -0.4518 +vn -0.9182 0.0132 0.3959 +vn -0.8763 0.0053 0.4817 +vn -0.9154 0.0126 0.4023 +vn -0.8729 0.0047 0.4879 +vn -0.2014 0.0144 0.9794 +vn -0.0808 0.0027 0.9967 +vn -0.1926 0.0135 0.9812 +vn -0.0725 0.0019 0.9974 +vn 0.0451 0.9941 0.0985 +vn 0.0884 0.9939 0.0663 +vn 0.1144 0.9933 -0.0142 +vn 0.1116 0.9930 -0.0381 +vn -0.0609 0.9933 -0.0977 +vn -0.0966 0.9929 -0.0694 +vn -0.1079 0.9942 0.0017 +vn 0.0035 0.9942 0.1077 +vn -0.0176 0.9935 -0.1123 +vn 0.0463 0.9947 -0.0916 +vn 0.0483 0.9945 -0.0924 +vn -0.0475 0.9943 0.0955 +vn -0.0604 0.9950 0.0800 +vn -0.1141 0.9934 0.0105 +vn 0.7940 0.0516 0.6057 +vn 0.9796 -0.0441 0.1959 +vn 0.9996 0.0280 0.0064 +vn 0.9682 -0.0891 -0.2336 +vn 0.7362 0.0822 -0.6717 +vn 0.5410 -0.0097 -0.8410 +vn 0.4762 0.0350 -0.8786 +vn 0.3512 -0.0284 -0.9359 +vn 0.1883 0.0373 -0.9814 +vn -0.4428 0.0034 -0.8966 +vn -0.3513 -0.0602 -0.9343 +vn -0.4137 -0.0173 -0.9103 +vn -0.5063 0.0502 -0.8609 +vn -0.9690 -0.0168 -0.2464 +vn -0.9737 -0.0331 -0.2252 +vn -0.9726 -0.0288 -0.2308 +vn -0.9762 -0.0429 -0.2124 +vn -0.8857 0.0547 0.4610 +vn -0.8237 -0.0174 0.5668 +vn -0.8468 0.0072 0.5319 +vn -0.7755 -0.0631 0.6282 +vn -0.2536 0.0526 0.9659 +vn -0.1003 -0.0267 0.9946 +vn 0.0835 0.0360 0.9959 +vn 0.4373 -0.0534 0.8977 +vn 0.9452 0.1049 0.3091 +vn 0.9294 0.0614 0.3640 +vn 0.9236 0.0481 0.3803 +vn 0.8992 0.0000 0.4375 +vn 0.2802 0.0000 -0.9599 +vn 0.3388 -0.0479 -0.9397 +vn 0.3546 -0.0611 -0.9330 +vn 0.4058 -0.1045 -0.9080 +vn -0.9453 0.1047 -0.3090 +vn -0.9295 0.0612 -0.3638 +vn -0.9237 0.0480 -0.3800 +vn -0.8994 0.0000 -0.4372 +vn -0.2798 0.0000 0.9601 +vn -0.3386 -0.0481 0.9397 +vn -0.3546 -0.0614 0.9330 +vn -0.4059 -0.1049 0.9079 +vn -0.4449 0.8941 0.0504 +vn -0.6397 0.1628 -0.7512 +vn 0.0305 0.8655 -0.5000 +vn 0.0110 -0.9998 0.0145 +vn -0.0039 -1.0000 0.0087 +vn 0.0078 -0.9994 0.0326 +vn 0.0189 -0.9995 -0.0259 +vn -0.0069 -1.0000 -0.0000 +vn -0.0416 -0.9991 0.0086 +vn -0.0209 -0.9998 -0.0017 +vn 0.0082 -0.9999 -0.0090 +vn 0.0428 -0.9969 -0.0662 +vn 0.0109 -0.9997 -0.0237 +vn -0.0138 -0.9998 0.0134 +vn -0.0198 -0.9994 0.0273 +vn -0.0888 0.9720 -0.2175 +vn -0.1439 0.9895 0.0103 +vn -0.0838 0.9761 0.2003 +vn 0.1069 0.0214 0.9940 +vn 0.1290 0.1780 0.9755 +vn 0.1182 0.0143 0.9929 +vn 0.1384 0.1018 0.9851 +vn -0.9638 -0.0549 0.2610 +vn -0.9000 0.0272 0.4351 +vn -0.9345 -0.0111 0.3558 +vn -0.9772 -0.0843 0.1948 +vn -0.8393 0.0759 -0.5383 +vn -0.3998 -0.0625 -0.9145 +vn 0.4419 -0.0226 -0.8968 +vn 0.1301 0.2003 -0.9711 +vn 0.1993 0.2319 -0.9521 +vn 0.5479 -0.0572 -0.8346 +vn 0.9952 0.0021 0.0983 +vn 0.9935 0.0853 -0.0756 +vn 0.9988 0.0480 0.0029 +vn 0.9817 -0.0406 0.1860 +vn 0.6567 0.6788 0.3287 +vn 0.4647 0.7460 0.4769 +vn 0.2013 0.6832 0.7020 +vn -0.0096 0.6911 0.7227 +vn -0.0958 0.6361 0.7656 +vn -0.6251 0.6076 0.4900 +vn -0.6421 0.7051 0.3010 +vn -0.7011 0.6945 0.1618 +vn -0.6983 0.7158 0.0044 +vn -0.7590 0.6347 -0.1450 +vn -0.4810 0.6139 -0.6260 +vn -0.3813 0.6693 -0.6376 +vn -0.1832 0.6716 -0.7179 +vn 0.0475 0.7306 -0.6812 +vn 0.4140 0.6820 -0.6029 +vn 0.6328 0.7347 -0.2444 +vn 0.7324 0.6676 -0.1337 +vn 0.1190 0.4782 0.8701 +vn -0.2053 0.8743 0.4398 +vn -0.7595 0.5385 0.3650 +vn -0.6754 0.5979 -0.4317 +vn -0.2087 0.8703 -0.4461 +vn 0.1099 0.5468 -0.8300 +vn 0.7227 0.6887 -0.0591 +vn 0.7093 0.7031 -0.0497 +vn 0.6813 0.7314 -0.0305 +vn 0.6612 0.7500 -0.0174 +vn -0.0244 -0.9996 -0.0149 +vn -0.0352 -0.9994 -0.0059 +vn -0.0343 -0.9993 -0.0166 +vn 0.0036 -1.0000 0.0038 +vn -0.0011 -0.9998 -0.0202 +vn 0.0290 -0.9996 -0.0066 +vn 0.0164 -0.9997 0.0159 +vn 0.0068 -0.9999 0.0089 +vn 0.0140 -0.9992 0.0384 +vn 0.0012 -1.0000 0.0027 +vn -0.0119 -0.9994 0.0328 +vn -0.0256 -0.9996 -0.0149 +vn 0.0107 0.9998 -0.0191 +vn -0.0925 0.9639 0.2495 +vn -0.0683 0.9801 0.1866 +vn 0.2112 0.0146 0.9773 +vn 0.1353 0.2174 0.9667 +vn 0.1788 0.0337 0.9833 +vn 0.1196 0.1511 0.9813 +vn -0.9070 -0.0487 0.4182 +vn -0.9730 0.0825 0.2157 +vn -0.9448 -0.0018 0.3276 +vn -0.9817 0.1224 0.1460 +vn -0.6359 -0.0917 -0.7663 +vn -0.1500 0.1238 -0.9809 +vn -0.1473 0.2124 -0.9660 +vn -0.1451 0.2659 -0.9530 +vn 0.6106 -0.0921 -0.7865 +vn 0.9945 0.0071 0.1049 +vn 0.9774 0.1174 -0.1759 +vn 0.9948 0.0755 -0.0680 +vn 0.9675 -0.0507 0.2478 +vn 0.6902 0.6694 0.2749 +vn 0.4753 0.7286 0.4932 +vn 0.1703 0.6707 0.7220 +vn -0.0036 0.6893 0.7244 +vn -0.1700 0.6047 0.7781 +vn -0.6065 0.6599 0.4435 +vn -0.6181 0.7020 0.3537 +vn -0.6859 0.6845 0.2470 +vn -0.6898 0.7003 0.1837 +vn -0.7704 0.6371 0.0227 +vn -0.4979 0.7013 -0.5102 +vn -0.4850 0.6535 -0.5811 +vn -0.4970 0.6977 -0.5159 +vn -0.5050 0.7332 -0.4553 +vn -0.0598 0.6167 -0.7849 +vn 0.4472 0.6832 -0.5773 +vn 0.4503 0.6814 -0.5770 +vn 0.4475 0.6830 -0.5773 +vn 0.4447 0.6846 -0.5775 +vn 0.7943 0.6013 -0.0866 +vn 0.7375 0.6741 0.0405 +vn 0.1029 0.4860 0.8679 +vn -0.1690 0.8778 0.4482 +vn -0.9659 0.2152 0.1441 +vn -0.2734 0.8592 -0.4324 +vn -0.1307 0.4822 -0.8663 +vn 0.6846 0.7134 -0.1499 +vn 0.6655 0.7298 -0.1566 +vn 0.7126 0.6875 -0.1396 +vn 0.7241 0.6763 -0.1352 +vn -0.0334 -0.9994 0.0101 +vn -0.0138 -0.9998 0.0110 +vn -0.0195 -0.9998 -0.0034 +vn 0.0242 -0.9996 0.0119 +vn 0.0262 -0.9996 0.0101 +vn 0.0141 -0.9995 0.0274 +vn 0.0378 -0.9993 0.0022 +vn -0.0058 -1.0000 0.0008 +vn -0.0272 -0.9991 0.0328 +vn -0.0087 -0.9999 -0.0135 +vn 0.0262 -0.9994 -0.0225 +vn 0.0068 -1.0000 0.0052 +vn -0.1288 0.9664 0.2225 +vn -0.1391 0.9628 0.2317 +vn -0.0070 0.9936 0.1129 +vn 0.6698 0.1082 0.7346 +vn -0.1136 -0.0516 0.9922 +vn 0.0087 0.0143 0.9999 +vn -0.0412 -0.0126 0.9991 +vn -0.1526 -0.0727 0.9856 +vn -0.9938 -0.0141 -0.1099 +vn -0.9855 0.1335 0.1045 +vn -0.9959 0.0892 0.0139 +vn -0.9692 -0.0849 -0.2313 +vn 0.0824 -0.0283 -0.9962 +vn -0.0849 0.0507 -0.9951 +vn -0.0001 0.0107 -0.9999 +vn 0.1620 -0.0660 -0.9846 +vn 0.8860 0.0957 -0.4538 +vn 0.8701 0.2088 -0.4464 +vn 0.8715 0.2012 -0.4471 +vn 0.9760 -0.1178 0.1834 +vn 0.5026 0.5975 0.6248 +vn -0.1167 0.7117 0.6928 +vn -0.1043 0.7198 0.6863 +vn -0.1172 0.7114 0.6930 +vn -0.1292 0.7032 0.6991 +vn -0.6737 0.5723 0.4675 +vn -0.6957 0.7127 -0.0897 +vn -0.6637 0.7363 -0.1317 +vn -0.6505 0.7057 -0.2808 +vn -0.6241 0.7031 -0.3407 +vn -0.5697 0.6118 -0.5488 +vn 0.1107 0.6869 -0.7182 +vn 0.1155 0.6832 -0.7210 +vn 0.1102 0.6873 -0.7180 +vn 0.1061 0.6904 -0.7156 +vn 0.6465 0.5882 -0.4858 +vn 0.7172 0.6929 0.0744 +vn 0.6932 0.7135 0.1020 +vn 0.6938 0.7130 0.1013 +vn 0.6693 0.7319 0.1279 +vn 0.5019 0.8301 0.2430 +vn -0.2821 0.8908 0.3562 +vn -0.9675 0.2307 0.1037 +vn -0.0899 0.8304 -0.5499 +vn -0.1118 0.8588 -0.4999 +vn -0.0629 0.7914 -0.6080 +vn -0.0410 0.7571 -0.6520 +vn 0.8126 0.4060 -0.4182 +vn -0.0373 -0.9992 0.0114 +vn -0.0240 -0.9997 -0.0011 +vn -0.0242 -0.9997 -0.0091 +vn 0.0216 -0.9997 0.0079 +vn 0.0278 -0.9996 -0.0016 +vn 0.0038 -1.0000 0.0054 +vn 0.0146 -0.9999 0.0077 +vn 0.0028 -0.9999 -0.0157 +vn 0.0441 -0.9990 -0.0064 +vn -0.0054 -1.0000 0.0035 +vn -0.0257 -0.9996 -0.0131 +vn -0.0128 -0.9996 0.0260 +vn 0.0466 0.9523 0.3017 +vn 0.0599 0.9632 0.2621 +vn 0.1122 0.9888 0.0989 +vn 0.3089 0.1396 0.9408 +vn -0.4907 -0.1471 0.8588 +vn -0.8839 0.0985 0.4572 +vn -0.8748 0.1731 0.4526 +vn -0.8729 0.1848 0.4516 +vn -0.8284 -0.0808 -0.5543 +vn -0.6962 0.0144 -0.7177 +vn -0.7717 -0.0365 -0.6349 +vn -0.6157 0.0621 -0.7855 +vn 0.3759 -0.0571 -0.9249 +vn 0.4876 0.1371 -0.8622 +vn 0.4177 -0.0363 -0.9079 +vn 0.5186 0.1741 -0.8371 +vn 0.9600 -0.0365 0.2777 +vn 0.9900 0.0221 0.1397 +vn 0.9774 -0.0080 0.2111 +vn 0.9455 -0.0553 0.3209 +vn 0.6909 0.6956 0.1969 +vn 0.5948 0.7036 0.3889 +vn 0.5702 0.5936 0.5680 +vn 0.0568 0.6018 0.7966 +vn -0.1733 0.7193 0.6728 +vn -0.2376 0.7122 0.6605 +vn -0.3791 0.7394 0.5564 +vn -0.4521 0.7014 0.5510 +vn -0.7854 0.5964 0.1654 +vn -0.6285 0.6835 -0.3712 +vn -0.6058 0.6985 -0.3809 +vn -0.6056 0.6987 -0.3810 +vn -0.5805 0.7142 -0.3910 +vn -0.1235 0.6047 -0.7868 +vn 0.1037 0.6842 -0.7219 +vn 0.1393 0.6805 -0.7194 +vn 0.2905 0.7040 -0.6481 +vn 0.3260 0.6875 -0.6489 +vn 0.7920 0.5759 -0.2026 +vn 0.7172 0.6968 -0.0090 +vn -0.0129 0.8834 0.4685 +vn -0.8336 0.3447 0.4316 +vn -0.3938 0.7670 -0.5066 +vn -0.3537 0.7940 -0.4944 +vn -0.3069 0.8224 -0.4790 +vn -0.2652 0.8451 -0.4642 +vn 0.4622 0.4829 -0.7437 +vn 0.6113 0.7857 -0.0946 +vn 0.0199 -0.9998 0.0079 +vn 0.0220 -0.9997 0.0103 +vn 0.0121 -0.9998 0.0165 +vn -0.0553 -0.9983 0.0179 +vn -0.0210 -0.9997 0.0081 +vn -0.0267 -0.9996 -0.0053 +vn 0.0161 -0.9998 0.0117 +vn -0.0226 -0.9997 -0.0039 +vn 0.0007 -1.0000 0.0083 +vn -0.0173 -0.9997 -0.0187 +vn 0.0167 -0.9999 -0.0030 +vn -0.0356 -0.9989 0.0316 +vn -0.0253 -0.9995 -0.0174 +vn -0.1950 0.9804 -0.0280 +vn -0.0391 0.9960 -0.0810 +vn -0.1917 0.9811 -0.0280 +vn -0.0421 0.9958 -0.0819 +vn 0.7376 -0.0142 0.6751 +vn 0.6410 0.0445 0.7662 +vn 0.5557 0.0900 0.8265 +vn -0.3161 -0.0705 0.9461 +vn -0.5835 0.1962 0.7880 +vn -0.4256 -0.0261 0.9045 +vn -0.6476 0.1845 0.7393 +vn -0.9979 -0.0631 0.0111 +vn -0.9436 0.0350 -0.3291 +vn -0.9957 -0.0361 -0.0855 +vn -0.9077 0.0612 -0.4152 +vn -0.5222 -0.0066 -0.8528 +vn -0.3192 0.0682 -0.9452 +vn -0.4679 0.0145 -0.8837 +vn -0.2444 0.0933 -0.9652 +vn 0.7744 0.0460 -0.6311 +vn 0.7999 0.0184 -0.5998 +vn 0.7882 0.0314 -0.6147 +vn 0.7603 0.0604 -0.6467 +vn 0.8084 -0.0646 0.5851 +vn 0.5652 0.6838 0.4614 +vn 0.2041 0.7505 0.6286 +vn 0.1990 0.6542 0.7297 +vn -0.2182 0.6882 0.6920 +vn -0.3384 0.6984 0.6307 +vn -0.4743 0.6358 0.6089 +vn -0.7389 0.6736 0.0166 +vn -0.7435 0.6686 0.0099 +vn -0.7393 0.6731 0.0160 +vn -0.7359 0.6767 0.0209 +vn -0.4692 0.6951 -0.5448 +vn -0.4292 0.5723 -0.6987 +vn 0.0711 0.7486 -0.6592 +vn -0.3510 0.7322 -0.5837 +vn 0.1067 0.6457 -0.7561 +vn 0.5427 0.6800 -0.4930 +vn 0.6024 0.7038 -0.3766 +vn 0.7078 0.6439 -0.2904 +vn 0.7208 0.6461 0.2511 +vn 0.6273 0.7022 0.3368 +vn 0.3836 0.6393 0.6665 +vn 0.3819 0.5721 0.7259 +vn 0.3827 0.6915 0.6127 +vn 0.3814 0.7174 0.5830 +vn -0.5736 0.4889 0.6572 +vn -0.4534 0.8888 0.0669 +vn 0.6142 0.7364 -0.2835 +vn 0.0065 -0.9998 0.0176 +vn -0.0056 -0.9998 0.0179 +vn 0.0029 -0.9995 0.0316 +vn -0.0123 -0.9999 -0.0101 +vn 0.0163 -0.9976 -0.0672 +vn -0.0148 -0.9998 -0.0107 +vn 0.0028 -1.0000 0.0037 +vn -0.0199 -0.9998 0.0033 +vn 0.0098 -1.0000 -0.0010 +vn -0.0036 -1.0000 -0.0017 +vn 0.0414 -0.9962 -0.0760 +vn -0.0098 -0.9999 -0.0086 +vn -0.0162 -0.9991 0.0398 +vn -0.0826 0.9925 0.0904 +vn -0.1598 0.9615 0.2236 +vn -0.1482 0.9678 0.2035 +vn -0.1835 -0.0103 0.9830 +vn 0.0379 0.0900 0.9952 +vn -0.0398 0.0553 0.9977 +vn -0.2660 -0.0489 0.9627 +vn -0.9940 0.0160 0.1080 +vn -0.9807 0.0371 0.1918 +vn -0.9865 0.0294 0.1613 +vn -0.9961 0.0110 0.0880 +vn -0.8831 0.1021 -0.4580 +vn -0.4696 -0.0847 -0.8788 +vn 0.3703 0.1243 -0.9205 +vn 0.3687 0.1512 -0.9172 +vn 0.3684 0.1551 -0.9166 +vn 0.7804 -0.0969 -0.6177 +vn 0.8447 0.0510 0.5327 +vn 0.8967 0.0903 0.4332 +vn 0.8764 0.0740 0.4758 +vn 0.8209 0.0352 0.5699 +vn 0.5517 0.6737 0.4918 +vn 0.2192 0.7393 0.6367 +vn 0.0978 0.6749 0.7314 +vn -0.1650 0.6847 0.7099 +vn -0.1889 0.7030 0.6856 +vn -0.6732 0.6130 0.4136 +vn -0.7193 0.6685 0.1889 +vn -0.7050 0.6931 0.1503 +vn -0.7182 0.6958 0.0113 +vn -0.7485 0.6599 0.0652 +vn -0.6147 0.6500 -0.4468 +vn -0.4272 0.7056 -0.5653 +vn -0.4417 0.6942 -0.5684 +vn -0.2189 0.7014 -0.6784 +vn -0.1776 0.6862 -0.7054 +vn 0.0087 0.6507 -0.7592 +vn 0.4841 0.7034 -0.5205 +vn 0.5089 0.7307 -0.4551 +vn 0.6034 0.7065 -0.3698 +vn 0.6671 0.7450 0.0024 +vn 0.7480 0.6623 0.0430 +vn 0.1938 -0.8805 -0.4327 +vn -0.2405 0.8996 0.3645 +vn -0.3309 0.8465 -0.4171 +vn 0.3632 0.2201 -0.9054 +vn 0.5082 0.8610 0.0225 +vn 0.0132 -0.9998 0.0157 +vn 0.0078 -0.9999 0.0149 +vn 0.0069 -0.9996 0.0288 +vn -0.0237 -0.9996 0.0156 +vn -0.0235 -0.9997 -0.0092 +vn -0.0223 -0.9996 -0.0190 +vn 0.0191 -0.9998 0.0039 +vn -0.0090 -1.0000 -0.0020 +vn -0.0229 -0.9993 -0.0282 +vn 0.0004 -0.9995 -0.0313 +vn -0.0081 -0.9999 -0.0076 +vn 0.1017 0.9712 0.2153 +vn 0.1119 0.9853 0.1291 +vn 0.0699 0.9963 0.0491 +vn 0.1036 0.9930 -0.0563 +vn 0.4746 -0.0868 0.8759 +vn -0.6012 0.0289 0.7985 +vn -0.2433 0.0861 0.9661 +vn -0.5933 0.0761 0.8014 +vn -0.7183 0.0290 0.6952 +vn -0.8420 0.0768 0.5339 +vn -0.9761 -0.0723 -0.2051 +vn -0.7480 0.0988 -0.6563 +vn -0.7310 0.2322 -0.6416 +vn -0.7367 0.1983 -0.6465 +vn 0.0598 -0.0700 -0.9958 +vn 0.2704 0.0189 -0.9626 +vn 0.1278 -0.0418 -0.9909 +vn 0.3484 0.0531 -0.9358 +vn 0.9625 0.0229 -0.2703 +vn 0.9252 0.0617 -0.3746 +vn 0.9392 0.0486 -0.3399 +vn 0.9700 0.0128 -0.2428 +vn 0.8396 0.0885 0.5359 +vn 0.3449 0.6994 0.6260 +vn 0.3440 0.6999 0.6259 +vn 0.3441 0.6998 0.6260 +vn 0.3432 0.7003 0.6259 +vn -0.2703 0.5873 0.7629 +vn -0.3725 0.6672 0.6451 +vn -0.5279 0.6685 0.5238 +vn -0.6491 0.7333 0.2023 +vn -0.7386 0.6740 -0.0164 +vn -0.7044 0.6703 -0.2335 +vn -0.7162 0.6257 -0.3091 +vn -0.0813 0.6133 -0.7857 +vn -0.0345 0.6539 -0.7558 +vn -0.0205 0.6654 -0.7462 +vn 0.0395 0.7116 -0.7015 +vn 0.6840 0.5816 -0.4404 +vn 0.6852 0.6531 -0.3226 +vn 0.7436 0.6636 -0.0814 +vn 0.7203 0.6935 0.0154 +vn 0.7495 0.6042 0.2706 +vn 0.1827 0.8995 0.3968 +vn -0.6105 0.7759 0.1588 +vn -0.6743 0.4410 -0.5923 +vn -0.0544 0.8442 -0.5333 +vn 0.2225 0.0775 -0.9718 +vn 0.4095 0.0696 -0.9096 +vn 0.4084 0.0693 -0.9102 +vn 0.4098 0.0689 -0.9096 +vn 0.4099 0.0687 -0.9095 +vn 0.4099 0.0687 -0.9096 +vn 0.4099 0.0688 -0.9095 +vn 0.4101 0.0691 -0.9094 +vn 0.4105 0.0689 -0.9092 +vn 0.4100 0.0688 -0.9095 +vn 0.4093 0.0691 -0.9098 +vn 0.4098 0.0688 -0.9096 +vn 0.4098 0.0689 -0.9095 +vn 0.4100 0.0689 -0.9095 +vn 0.4099 0.0689 -0.9095 +vn 0.4053 0.0684 -0.9116 +vn 0.4019 0.0690 -0.9131 +vn 0.4100 0.0690 -0.9095 +vn 0.4111 0.0693 -0.9089 +vn 0.4095 0.0681 -0.9098 +vn 0.4099 0.0690 -0.9095 +vn 0.4084 0.0656 -0.9104 +vn 0.1672 0.0725 -0.9832 +vn 0.4063 0.0651 -0.9114 +vn 0.0103 -0.9991 0.0413 +vn -0.8370 0.3989 -0.3745 +vn -0.8337 0.4378 -0.3365 +vn -0.8161 0.5242 -0.2433 +vn -0.8353 0.3052 -0.4573 +vn -0.5037 -0.7925 -0.3439 +vn -0.5608 -0.7586 -0.3317 +vn -0.6793 -0.6701 -0.2991 +vn -0.3899 -0.8465 -0.3624 +vn 0.8905 0.3136 0.3297 +vn 0.8889 0.0016 0.4581 +vn 0.9019 0.1268 0.4130 +vn 0.2051 0.9656 0.1600 +vn 0.2563 0.9406 0.2227 +vn 0.3147 0.9021 0.2952 +vn 0.1386 0.9872 0.0794 +vn -0.6390 0.7332 -0.2328 +vn -0.6172 0.7633 -0.1909 +vn -0.5909 0.7938 -0.1439 +vn -0.6632 0.6926 -0.2838 +vn -0.8893 -0.2489 -0.3836 +vn -0.8866 -0.2913 -0.3593 +vn -0.8895 -0.1877 -0.4165 +vn -0.8813 -0.3360 -0.3323 +vn -0.3390 -0.8826 -0.3258 +vn 0.0181 -0.9956 0.0917 +vn 0.7310 -0.6663 0.1469 +vn 0.8490 -0.1588 0.5040 +vn -0.9263 0.0358 -0.3751 +vn -0.9170 0.0364 -0.3972 +vn -0.9266 0.0358 -0.3744 +vn -0.9167 0.0364 -0.3978 +vn -0.4130 -0.0705 0.9080 +vn -0.4139 -0.0688 0.9077 +vn -0.4111 -0.0682 0.9090 +vn -0.9044 -0.0283 0.4258 +vn -0.8996 -0.0288 0.4358 +vn -0.8997 -0.0288 0.4355 +vn -0.9044 -0.0283 0.4257 +vn -0.2941 0.6113 0.7347 +vn -0.2801 0.6687 0.6887 +vn -0.2739 0.6852 0.6749 +vn -0.2842 0.6605 0.6950 +vn -0.2846 0.6596 0.6956 +vn -0.2952 0.6067 0.7381 +vn 0.3038 0.1927 0.9330 +vn 0.3142 0.1260 0.9409 +vn 0.3132 0.4310 0.8462 +vn -0.0538 -0.0762 0.9956 +vn 0.3699 -0.0754 0.9260 +vn 0.3657 -0.0701 0.9281 +vn 0.3286 -0.0846 0.9407 +vn 0.3201 -0.2356 0.9176 +vn 0.3480 -0.0760 0.9344 +vn 0.3177 -0.3010 0.8991 +vn 0.3288 -0.0612 0.9424 +vn 0.3451 -0.4828 0.8049 +vn -0.3085 -0.7142 0.6283 +vn -0.2815 -0.7647 0.5797 +vn -0.2843 -0.7598 0.5848 +vn -0.3050 -0.7224 0.6205 +vn -0.3016 -0.7348 0.6075 +vn -0.3050 -0.7222 0.6208 +vn 0.7319 -0.5653 0.3805 +vn 0.6745 0.5914 0.4420 +vn -0.0049 -0.9968 -0.0799 +vn -0.0055 -0.9969 -0.0788 +vn -0.0056 -0.9967 -0.0815 +vn 0.0213 -0.9932 -0.1143 +vn -0.0067 -0.9976 -0.0684 +vn 0.0235 -0.9927 -0.1179 +vn 0.0053 0.9969 0.0781 +vn 0.0057 0.9970 0.0773 +vn 0.0055 0.9971 0.0765 +vn 0.0034 0.9962 0.0865 +vn 0.0543 0.9980 0.0318 +vn 0.0021 0.9957 0.0924 +vn 0.0654 0.9977 0.0192 +vn 0.9437 -0.0151 0.3305 +vn 0.9141 -0.0363 0.4039 +vn 0.9467 -0.0129 0.3218 +vn 0.9441 -0.0464 0.3263 +vn 0.9471 -0.0473 0.3174 +vn -0.4099 -0.0679 0.9096 +vn -0.4107 -0.0705 0.9090 +vn -0.4126 -0.0700 0.9082 +vn -0.4086 -0.0689 0.9101 +vn -0.4101 -0.0697 0.9094 +vn -0.4087 -0.0687 0.9101 +vn -0.4097 -0.0926 0.9075 +vn -0.4097 -0.0647 0.9099 +vn -0.4100 -0.0680 0.9096 +vn -0.4096 -0.0690 0.9096 +vn -0.4114 -0.0677 0.9089 +vn -0.4099 -0.0689 0.9095 +vn -0.4098 -0.0681 0.9096 +vn -0.4099 -0.0687 0.9095 +vn -0.4098 -0.0684 0.9096 +vn -0.4099 -0.0688 0.9095 +vn -0.4098 -0.0689 0.9096 +vn -0.4098 -0.0688 0.9096 +vn -0.4100 -0.0687 0.9095 +vn -0.4098 -0.0687 0.9096 +vn -0.4100 -0.0691 0.9095 +vn -0.4101 -0.0693 0.9094 +vn -0.4101 -0.0696 0.9094 +vn -0.4099 -0.0688 0.9096 +vn -0.4098 -0.0666 0.9097 +vn -0.4138 -0.0687 0.9078 +vn -0.4081 -0.0694 0.9103 +vn -0.4098 -0.0693 0.9096 +vn -0.4085 -0.0690 0.9101 +vn -0.4094 -0.0718 0.9095 +vn -0.4104 -0.0676 0.9094 +vn -0.4090 -0.0624 0.9104 +vn -0.4105 -0.0697 0.9092 +vn -0.4101 -0.0603 0.9100 +vn -0.4112 -0.0754 0.9084 +vn -0.4126 -0.0706 0.9082 +vn -0.4154 -0.0679 0.9071 +vn -0.4120 -0.0696 0.9085 +vn -0.4120 -0.0688 0.9086 +vn -0.4150 -0.0681 0.9072 +vn -0.4104 -0.0686 0.9093 +vn -0.4127 -0.0679 0.9083 +vn -0.4103 -0.0696 0.9093 +vn -0.4115 -0.0710 0.9087 +vn -0.4134 -0.0688 0.9080 +vn -0.2816 -0.0544 0.9580 +vn -0.4134 -0.0694 0.9079 +vn -0.4106 -0.1057 0.9057 +vn -0.4135 -0.0673 0.9080 +vn -0.4096 -0.0689 0.9097 +vn -0.4035 -0.0714 0.9122 +vn -0.3973 -0.0736 0.9147 +vn -0.4106 -0.0612 0.9097 +vn -0.4091 -0.0611 0.9105 +vn -0.4122 -0.0700 0.9084 +vn -0.4125 -0.0715 0.9081 +vn 0.0192 0.0820 -0.9964 +vn -0.0833 0.0744 -0.9937 +vn -0.4099 -0.0683 0.9096 +vn 0.5622 0.7660 0.3117 +vn 0.5834 0.7534 0.3034 +vn 0.4811 0.8079 0.3405 +vn 0.6579 0.7026 0.2711 +vn 0.8272 -0.0716 0.5574 +vn 0.8887 -0.0390 0.4568 +vn 0.8181 -0.0758 0.5701 +vn 0.8990 -0.0327 0.4368 +vn 0.7717 -0.6246 0.1200 +vn -0.0321 -0.9990 0.0315 +vn 0.0406 -0.9726 -0.2288 +vn 0.0470 -0.9668 -0.2511 +vn -0.0390 -0.9976 0.0565 +vn -0.6422 -0.7473 -0.1704 +vn -0.9157 0.0644 -0.3966 +vn -0.8480 0.0459 -0.5280 +vn -0.9243 0.0671 -0.3757 +vn -0.8379 0.0435 -0.5440 +vn -0.0118 0.9987 0.0498 +vn -0.0080 0.9993 0.0365 +vn -0.0123 0.9986 0.0514 +vn -0.0076 0.9994 0.0350 +vn -0.4855 -0.7065 0.5149 +vn -0.8254 -0.3539 0.4399 +vn -0.8048 -0.4645 0.3694 +vn -0.4219 -0.7186 0.5528 +vn -0.2057 -0.8078 0.5524 +vn 0.1938 -0.5532 0.8102 +vn 0.1942 -0.5548 0.8090 +vn 0.1884 -0.5264 0.8291 +vn 0.2017 -0.5926 0.7798 +vn 0.3825 0.1421 0.9130 +vn 0.3847 0.1454 0.9115 +vn 0.3677 0.1203 0.9221 +vn 0.3935 0.1587 0.9055 +vn -0.4165 0.6452 0.6405 +vn -0.1717 0.6661 0.7259 +vn -0.1541 0.6729 0.7235 +vn -0.4580 0.6179 0.6391 +vn -0.7737 0.4374 0.4583 +vn -0.8362 0.2948 0.4624 +vn -0.9339 0.0156 0.3571 +vn -0.7877 0.1097 -0.6063 +vn -0.6782 0.7270 -0.1072 +vn -0.6464 0.7515 -0.1320 +vn -0.5771 0.7963 -0.1816 +vn -0.7192 0.6909 -0.0730 +vn 0.1996 0.9459 0.2558 +vn 0.1741 0.9840 0.0384 +vn 0.1871 0.9722 0.1405 +vn 0.2076 0.9150 0.3459 +vn 0.8524 0.0650 0.5188 +vn 0.9288 0.2400 0.2824 +vn 0.9074 0.1695 0.3845 +vn 0.8045 -0.0011 0.5939 +vn 0.7225 -0.6910 -0.0223 +vn 0.0665 -0.9277 0.3674 +vn -0.2209 -0.7945 -0.5657 +vn -0.9084 -0.4124 -0.0687 +vn -0.8374 -0.4330 0.3335 +vn -0.8391 -0.4319 0.3308 +vn -0.8471 -0.4263 0.3172 +vn -0.8247 -0.4412 0.3539 +vn -0.2686 -0.7903 0.5507 +vn -0.2680 -0.7897 0.5519 +vn -0.2729 -0.7948 0.5420 +vn -0.2602 -0.7814 0.5671 +vn 0.2551 -0.5072 0.8232 +vn 0.2431 -0.5115 0.8242 +vn 0.1533 -0.5407 0.8271 +vn 0.3124 -0.4852 0.8167 +vn 0.3584 0.1427 0.9226 +vn 0.3607 0.1471 0.9210 +vn 0.3279 0.0865 0.9407 +vn 0.3815 0.1870 0.9053 +vn -0.1821 0.6905 0.7001 +vn -0.1704 0.6630 0.7290 +vn -0.1805 0.6868 0.7041 +vn -0.1883 0.7049 0.6839 +vn -0.8367 0.3870 0.3875 +vn -0.8399 0.3858 0.3818 +vn -0.8182 0.3933 0.4194 +vn -0.8509 0.3815 0.3613 +vn -0.6953 0.6814 -0.2286 +vn -0.6758 0.6091 -0.4151 +vn -0.6872 0.6421 -0.3399 +vn -0.6950 0.7041 -0.1458 +vn 0.2146 0.9703 0.1120 +vn 0.2249 0.9491 0.2205 +vn 0.2052 0.9783 0.0303 +vn 0.2308 0.9255 0.3004 +vn 0.8543 0.0548 0.5169 +vn 0.9280 0.2032 0.3122 +vn 0.9050 0.1426 0.4008 +vn 0.8128 -0.0001 0.5825 +vn 0.7306 -0.6812 0.0461 +vn 0.0696 -0.9958 0.0595 +vn 0.0914 -0.9779 0.1879 +vn 0.1082 -0.9505 0.2911 +vn 0.0396 -0.9934 -0.1077 +vn -0.8443 -0.4528 -0.2866 +vn -0.7098 -0.5319 -0.4618 +vn -0.7698 -0.5030 -0.3929 +vn -0.8808 -0.4189 -0.2207 +vn -0.9132 -0.2259 0.3393 +vn -0.9202 -0.0571 0.3872 +vn -0.9335 0.1260 0.3357 +vn -0.8299 -0.4211 0.3660 +vn -0.8086 -0.4843 0.3341 +vn -0.0843 -0.7243 0.6843 +vn -0.2850 -0.7456 0.6023 +vn -0.3197 -0.7723 0.5489 +vn 0.0679 -0.5574 0.8274 +vn 0.3264 -0.3077 0.8937 +vn 0.3611 -0.0950 0.9277 +vn 0.4411 0.0278 0.8970 +vn 0.0873 0.5290 0.8441 +vn 0.1032 0.4263 0.8987 +vn 0.0873 0.5289 0.8442 +vn 0.0734 0.6069 0.7914 +vn -0.5619 0.6381 0.5264 +vn -0.5619 0.6380 0.5265 +vn -0.5780 0.6155 0.5357 +vn -0.5322 0.6765 0.5090 +vn -0.8698 0.2290 0.4371 +vn -0.7785 0.5586 -0.2862 +vn -0.7663 0.6105 -0.2002 +vn -0.7774 0.4256 -0.4631 +vn -0.7268 0.6853 -0.0472 +vn -0.2591 0.9302 -0.2599 +vn 0.1624 0.8873 0.4317 +vn 0.6967 0.7135 0.0742 +vn 0.9225 -0.1838 0.3395 +vn 0.8526 -0.0789 0.5165 +vn 0.7850 -0.0080 0.6195 +vn 0.9461 -0.2557 0.1987 +vn 0.1428 -0.9885 -0.0494 +vn 0.1476 -0.9812 0.1246 +vn 0.1484 -0.9658 0.2126 +vn 0.1379 -0.9789 -0.1507 +vn -0.8541 -0.4287 -0.2944 +vn -0.8365 -0.4430 -0.3225 +vn -0.8651 -0.4190 -0.2758 +vn -0.8202 -0.4551 -0.3467 +vn -0.9474 -0.0345 0.3183 +vn -0.9502 -0.0266 0.3104 +vn -0.9581 -0.0030 0.2865 +vn -0.9332 -0.0691 0.3526 +vn -0.5105 -0.7399 0.4381 +vn -0.5186 -0.7429 0.4233 +vn -0.5451 -0.7514 0.3718 +vn -0.4636 -0.7198 0.5166 +vn 0.2050 -0.6208 0.7567 +vn 0.2060 -0.6207 0.7565 +vn 0.1788 -0.6230 0.7615 +vn 0.2203 -0.6193 0.7537 +vn 0.2790 0.1748 0.9442 +vn 0.3150 -0.1015 0.9437 +vn 0.3826 0.0265 0.9235 +vn 0.2484 0.3451 0.9051 +vn 0.1137 0.5032 0.8567 +vn 0.0980 0.5756 0.8118 +vn -0.5535 0.6309 0.5437 +vn -0.5371 0.6218 0.5700 +vn -0.5512 0.6296 0.5474 +vn -0.5628 0.6358 0.5283 +vn -0.7248 -0.0066 -0.6889 +vn -0.9012 0.4328 -0.0231 +vn -0.1881 0.8999 -0.3934 +vn 0.0669 0.8792 0.4717 +vn 0.7110 0.6937 0.1152 +vn 0.8247 -0.0223 0.5652 +vn 0.8450 -0.0431 0.5330 +vn 0.8759 -0.0785 0.4760 +vn 0.8027 -0.0013 0.5963 +vn 0.6676 -0.7439 0.0300 +vn 0.1772 -0.9384 0.2967 +vn -0.1384 -0.9033 -0.4060 +vn -0.7539 -0.6532 -0.0703 +vn -0.9410 0.0341 0.3368 +vn -0.9426 0.0309 0.3324 +vn -0.9606 -0.0080 0.2777 +vn -0.9272 0.0583 0.3701 +vn -0.7126 -0.5638 0.4175 +vn -0.7005 -0.5693 0.4304 +vn -0.8047 -0.5098 0.3041 +vn -0.5789 -0.6105 0.5405 +vn 0.1698 -0.5801 0.7967 +vn -0.0282 -0.7421 0.6697 +vn -0.1050 -0.8605 0.4986 +vn 0.2878 -0.2933 0.9116 +vn 0.3598 0.0786 0.9297 +vn 0.2000 0.2822 0.9383 +vn 0.0914 0.5094 0.8557 +vn -0.0319 0.5728 0.8191 +vn -0.0658 0.6328 0.7715 +vn -0.6156 0.5954 0.5162 +vn -0.6160 0.5949 0.5164 +vn -0.5912 0.6296 0.5041 +vn -0.6490 0.5438 0.5320 +vn -0.7965 0.0563 -0.6021 +vn -0.8968 0.4392 -0.0525 +vn -0.3852 0.8372 -0.3883 +vn 0.2133 0.9145 0.3438 +vn 0.1025 0.9057 0.4113 +vn 0.3828 0.8963 0.2238 +vn 0.4983 0.8575 0.1281 +vn 0.8408 0.0178 0.5411 +vn 0.8522 0.0085 0.5231 +vn 0.8618 0.0003 0.5073 +vn 0.8244 0.0306 0.5653 +vn 0.6940 -0.7199 -0.0128 +vn 0.1579 -0.9305 0.3304 +vn -0.2899 -0.8288 -0.4786 +vn -0.7341 -0.6615 -0.1530 +vn -0.9012 -0.2162 0.3757 +vn -0.7735 -0.5153 0.3690 +vn -0.5620 -0.6555 0.5044 +vn -0.1875 -0.7542 0.6293 +vn 0.0816 -0.5589 0.8252 +vn 0.3023 -0.3847 0.8722 +vn 0.3368 -0.1944 0.9213 +vn 0.3882 -0.1343 0.9118 +vn 0.2076 0.4643 0.8610 +vn 0.0026 0.5444 0.8388 +vn 0.2045 0.3923 0.8968 +vn -0.1275 0.6286 0.7672 +vn -0.5180 0.5940 0.6154 +vn -0.6233 0.5783 0.5264 +vn -0.8478 0.2891 0.4446 +vn -0.9235 0.1243 0.3628 +vn -0.8513 0.1240 -0.5098 +vn -0.8959 0.4403 -0.0588 +vn -0.5495 0.7656 -0.3345 +vn 0.0918 0.9463 0.3101 +vn 0.0488 0.9975 0.0520 +vn 0.0744 0.9762 0.2037 +vn 0.1062 0.9098 0.4012 +vn 0.7667 0.6207 0.1641 +vn 0.7779 -0.0041 0.6284 +vn 0.9449 -0.2818 0.1664 +vn 0.1690 -0.9830 -0.0720 +vn 0.1907 -0.9738 0.1242 +vn 0.2011 -0.9467 0.2518 +vn 0.1504 -0.9673 -0.2043 +vn -0.7258 -0.6154 -0.3075 +vn -0.7242 -0.6404 -0.2558 +vn -0.7199 -0.6642 -0.2012 +vn -0.7239 -0.5760 -0.3797 +vn 0.0161 0.9981 0.0601 +vn 0.0109 0.9980 0.0618 +vn 0.0404 0.9978 0.0520 +vn -0.0116 0.9975 0.0692 +vn 0.7068 -0.6807 0.1926 +vn 0.7362 -0.6266 0.2558 +vn 0.6572 -0.7467 0.1028 +vn 0.7734 -0.5212 0.3607 +vn 0.8267 0.4073 0.3881 +vn 0.8260 0.4132 0.3835 +vn 0.8247 0.4223 0.3762 +vn 0.8277 0.3989 0.3947 +vn -0.3941 -0.0954 0.9141 +vn -0.3876 -0.0675 0.9194 +vn -0.3948 -0.0837 0.9150 +vn -0.4266 -0.0733 0.9015 +vn -0.4454 -0.0722 0.8924 +vn -0.4327 -0.0748 0.8984 +vn -0.4333 -0.0634 0.8990 +vn -0.4071 -0.0960 0.9083 +vn -0.3934 -0.1097 0.9128 +vn -0.4065 -0.0487 0.9124 +vn -0.3930 -0.0511 0.9181 +vn -0.4034 -0.0357 0.9143 +vn -0.4192 -0.0446 0.9068 +vn 0.3868 0.0800 -0.9187 +vn 0.3945 0.0899 -0.9145 +vn 0.3778 0.1332 -0.9163 +vn 0.4066 0.1457 -0.9019 +vn 0.3678 0.1364 -0.9198 +vn -0.7113 0.6565 -0.2510 +vn -0.6971 0.6555 -0.2903 +vn -0.8522 0.3461 -0.3924 +vn -0.8038 -0.4627 -0.3738 +vn -0.8607 -0.2787 -0.4260 +vn -0.8542 -0.3079 -0.4190 +vn -0.7956 -0.4818 -0.3672 +vn -0.0510 -0.9952 -0.0830 +vn -0.2727 -0.9344 -0.2290 +vn -0.2496 -0.9445 -0.2134 +vn -0.0192 -0.9978 -0.0633 +vn 0.6861 -0.6800 0.2584 +vn 0.5912 -0.7848 0.1862 +vn 0.6062 -0.7705 0.1972 +vn 0.6964 -0.6663 0.2666 +vn 0.8722 0.2301 0.4316 +vn 0.9185 -0.1587 0.3622 +vn 0.9208 -0.1083 0.3748 +vn 0.8551 0.2807 0.4359 +vn 0.2829 0.9352 0.2129 +vn 0.4880 0.8267 0.2800 +vn 0.4653 0.8443 0.2659 +vn 0.2456 0.9476 0.2042 +vn -0.6672 0.7095 -0.2267 +vn -0.4284 0.8914 -0.1480 +vn -0.2935 0.4013 -0.8677 +vn -0.2855 0.1441 -0.9475 +vn -0.3965 0.0248 -0.9177 +vn -0.2583 -0.3352 -0.9060 +vn 0.0032 -0.5200 -0.8542 +vn 0.0354 -0.6121 -0.7900 +vn 0.3856 -0.6624 -0.6423 +vn 0.5559 -0.5758 -0.5995 +vn 0.7794 -0.4512 -0.4346 +vn 0.9123 -0.0923 -0.3989 +vn 0.9433 0.0601 -0.3266 +vn 0.7382 0.5186 -0.4314 +vn 0.7697 0.5149 -0.3774 +vn 0.4068 0.7554 -0.5137 +vn 0.3535 0.7549 -0.5523 +vn 0.1697 0.8064 -0.5666 +vn -0.1922 0.5289 -0.8266 +vn -0.1854 0.5307 -0.8270 +vn 0.1845 0.9799 -0.0757 +vn -0.0948 0.9886 0.1167 +vn 0.0535 0.9985 0.0153 +vn -0.2247 0.9528 0.2041 +vn 0.8054 -0.5865 0.0852 +vn 0.7859 -0.4690 0.4030 +vn 0.8079 -0.5389 0.2386 +vn 0.7447 -0.3938 0.5388 +vn -0.7292 -0.3493 -0.5885 +vn -0.7856 -0.5354 -0.3101 +vn -0.7669 -0.4436 -0.4639 +vn -0.7808 -0.6028 -0.1643 +vn -0.0426 -0.1984 -0.9792 +vn -0.2572 -0.9301 -0.2621 +vn 0.5105 -0.3703 -0.7761 +vn 0.8087 0.1071 -0.5784 +vn 0.4504 0.8177 0.3586 +vn 0.3401 0.4132 -0.8448 +vn -0.6858 -0.4674 -0.5579 +vn -0.7962 -0.4691 -0.3821 +vn -0.8123 -0.3873 -0.4360 +vn -0.8938 -0.1859 -0.4081 +vn -0.6161 -0.7222 -0.3145 +vn -0.0354 -0.9762 -0.2141 +vn 0.0714 -0.9971 -0.0269 +vn 0.0490 -0.9980 -0.0412 +vn -0.1009 -0.9788 -0.1784 +vn 0.8102 -0.5369 0.2350 +vn 0.7582 -0.5796 0.2988 +vn 0.6537 -0.7491 0.1077 +vn 0.8857 -0.2531 0.3892 +vn 0.8972 -0.2529 0.3620 +vn 0.8977 0.0984 0.4295 +vn 0.5053 0.8213 0.2650 +vn 0.5588 0.7700 0.3079 +vn 0.6725 0.6651 0.3246 +vn 0.2019 0.9638 0.1741 +vn -0.2196 0.9740 -0.0555 +vn -0.5578 0.8108 -0.1777 +vn -0.6978 0.6087 -0.3776 +vn -0.8030 0.3275 -0.4979 +vn -0.8103 0.4885 -0.3238 +vn 0.9089 -0.2559 0.3292 +vn 0.6291 -0.7668 -0.1276 +vn 0.0964 -0.9324 -0.3484 +vn -0.0352 -0.9655 -0.2580 +vn -0.4478 -0.5114 -0.7334 +vn -0.7105 -0.4351 -0.5530 +vn -0.6981 0.2021 -0.6869 +vn -0.4802 0.8295 -0.2852 +vn 0.0977 0.8980 -0.4289 +vn 0.6873 0.6591 0.3052 +vn 0.9824 0.1866 0.0043 +vn 0.6649 -0.0232 -0.7465 +vn 0.7647 0.0096 -0.6443 +vn 0.6900 -0.1947 -0.6972 +vn 0.5107 0.4484 -0.7335 +vn 0.4559 0.3125 -0.8334 +vn 0.1907 0.3338 -0.9231 +vn 0.0245 0.2247 -0.9741 +vn 0.1641 0.0350 -0.9858 +vn 0.0070 0.0022 -1.0000 +vn 0.2591 -0.2208 -0.9403 +vn 0.4941 -0.2485 -0.8332 +vn 0.6782 0.2494 -0.6913 +vn 0.4479 -0.0530 -0.8925 +vn -0.2662 -0.2326 0.9354 +vn -0.4797 -0.0013 0.8774 +vn -0.5212 -0.3213 0.7907 +vn -0.6727 -0.0286 0.7393 +vn -0.6841 -0.2594 0.6817 +vn -0.4941 -0.4713 0.7306 +vn -0.4695 0.2293 0.8526 +vn -0.5966 0.2692 0.7561 +vn -0.2782 0.3453 0.8963 +vn -0.1407 0.0942 0.9856 +vn -0.0369 0.1452 0.9887 +vn -0.0506 -0.1623 0.9854 +vn -0.1979 -0.4006 0.8946 +vn -0.7656 -0.4986 -0.4066 +vn -0.7339 -0.5737 -0.3637 +vn -0.8463 -0.3132 -0.4309 +vn -0.8940 -0.1836 -0.4087 +vn -0.5715 -0.7539 -0.3241 +vn -0.4384 -0.8640 -0.2477 +vn 0.5335 -0.8448 0.0412 +vn 0.1343 -0.9907 -0.0216 +vn 0.1431 -0.9892 -0.0312 +vn 0.1338 -0.9908 -0.0218 +vn 0.9380 -0.2581 0.2313 +vn 0.7995 -0.5017 0.3303 +vn 0.6588 -0.7100 0.2489 +vn 0.9022 0.1048 0.4184 +vn 0.8409 0.3717 0.3934 +vn 0.7675 0.5214 0.3729 +vn 0.8022 0.4502 0.3922 +vn 0.3507 0.9328 0.0830 +vn 0.3519 0.9108 0.2160 +vn 0.3513 0.9307 0.1018 +vn -0.4223 0.8820 -0.2092 +vn -0.5020 0.8508 -0.1550 +vn -0.1846 0.9828 0.0047 +vn -0.6308 0.6855 -0.3636 +vn -0.7687 0.4229 -0.4799 +vn -0.7494 0.5946 -0.2913 +vn 0.8106 -0.5846 -0.0344 +vn 0.2987 -0.9466 -0.1211 +vn 0.3032 -0.4505 -0.8397 +vn -0.0499 -0.7812 -0.6223 +vn 0.0543 -0.3772 -0.9245 +vn -0.8329 -0.3058 -0.4613 +vn -0.6772 0.2900 -0.6762 +vn -0.3176 0.8952 -0.3125 +vn 0.3349 0.9315 -0.1419 +vn 0.9769 -0.1949 -0.0873 +vn 0.6298 0.3728 -0.6814 +vn 0.7584 0.1785 -0.6269 +vn 0.6892 0.0776 -0.7204 +vn 0.6088 -0.1584 -0.7773 +vn 0.2507 -0.2300 -0.9403 +vn 0.0744 0.3186 -0.9450 +vn 0.1548 0.1581 -0.9752 +vn 0.0135 0.0257 -0.9996 +vn 0.4876 0.3115 -0.8156 +vn 0.3183 0.4073 -0.8560 +vn 0.4450 -0.0398 -0.8946 +vn -0.6935 -0.2942 0.6577 +vn -0.4150 -0.5262 0.7422 +vn -0.5512 -0.3903 0.7375 +vn -0.6510 0.0158 0.7589 +vn -0.4334 -0.1509 0.8885 +vn -0.7595 0.0351 0.6496 +vn -0.5799 0.2986 0.7580 +vn -0.3953 0.2189 0.8921 +vn -0.3286 0.3676 0.8700 +vn -0.1229 0.2642 0.9566 +vn -0.0710 0.1093 0.9915 +vn -0.1846 -0.1058 0.9771 +vn 0.0432 -0.0390 0.9983 +vn -0.0480 -0.2690 0.9620 +vn -0.2591 -0.3838 0.8863 +vn -0.1825 -0.4564 0.8709 +vn -0.4334 -0.0783 0.8978 +vn -0.4371 -0.0663 0.8970 +vn -0.4368 -0.0897 0.8951 +vn -0.4196 -0.0496 0.9064 +vn -0.4048 -0.0402 0.9135 +vn -0.4280 -0.0498 0.9024 +vn -0.4408 -0.0961 0.8925 +vn -0.4041 -0.0881 0.9105 +vn -0.3932 -0.0842 0.9156 +vn -0.3986 -0.0326 0.9166 +vn -0.3907 -0.0579 0.9187 +vn -0.3861 -0.0873 0.9183 +vn -0.3788 -0.0723 0.9226 +vn -0.3770 -0.0972 0.9211 +vn -0.4003 -0.0482 0.9151 +vn 0.4489 0.1562 -0.8798 +vn 0.2974 0.0470 -0.9536 +vn 0.3236 0.0389 -0.9454 +vn 0.6808 -0.2116 -0.7012 +vn 0.5495 0.0832 -0.8313 +vn -0.7726 0.5606 -0.2981 +vn -0.7224 0.6186 -0.3091 +vn -0.8075 0.4989 -0.3147 +vn -0.8804 0.2668 -0.3921 +vn -0.8498 -0.3487 -0.3953 +vn -0.7610 -0.5137 -0.3963 +vn -0.8422 -0.3658 -0.3960 +vn -0.7492 -0.5313 -0.3955 +vn -0.3035 -0.9233 -0.2356 +vn -0.2462 -0.9498 -0.1931 +vn -0.2525 -0.9472 -0.1978 +vn -0.3123 -0.9186 -0.2421 +vn 0.2640 -0.9618 0.0718 +vn 0.8189 -0.4573 0.3468 +vn 0.7260 -0.6390 0.2541 +vn 0.7421 -0.6140 0.2687 +vn 0.8298 -0.4265 0.3599 +vn 0.7556 0.5339 0.3795 +vn 0.9032 0.1624 0.3973 +vn 0.8261 0.4088 0.3878 +vn 0.7383 0.5613 0.3741 +vn 0.7110 0.6064 0.3560 +vn 0.0115 0.9960 0.0890 +vn -0.0165 0.9975 0.0693 +vn 0.0091 0.9961 0.0874 +vn -0.0201 0.9976 0.0668 +vn -0.4807 0.8544 -0.1973 +vn -0.4062 -0.0992 -0.9084 +vn -0.3545 -0.1492 -0.9231 +vn -0.2786 -0.3230 -0.9045 +vn -0.1421 -0.4248 -0.8941 +vn 0.0406 -0.6172 -0.7858 +vn 0.2861 -0.6457 -0.7079 +vn 0.3521 -0.6685 -0.6551 +vn 0.7076 -0.4825 -0.5162 +vn 0.6279 -0.5741 -0.5255 +vn 0.8691 -0.3035 -0.3905 +vn 0.9155 0.1026 -0.3889 +vn 0.9428 0.0858 -0.3223 +vn 0.8260 0.4387 -0.3541 +vn 0.5916 0.6363 -0.4951 +vn 0.6018 0.6661 -0.4407 +vn 0.2132 0.7665 -0.6059 +vn -0.0174 0.6403 -0.7679 +vn -0.1827 0.5856 -0.7898 +vn -0.2796 0.4304 -0.8583 +vn -0.2770 0.4189 -0.8648 +vn -0.8647 0.3467 -0.3636 +vn -0.9279 0.2548 -0.2721 +vn -0.9077 0.2880 -0.3052 +vn -0.9555 0.1998 -0.2171 +vn 0.3319 0.9430 0.0225 +vn 0.2208 0.9711 0.0907 +vn 0.2638 0.9624 0.0648 +vn 0.1407 0.9805 0.1375 +vn 0.8647 -0.3464 0.3636 +vn 0.8334 -0.2706 0.4819 +vn 0.8465 -0.2981 0.4411 +vn 0.8077 -0.2246 0.5451 +vn -0.1840 -0.9183 -0.3505 +vn -0.1595 -0.9608 -0.2266 +vn -0.1693 -0.9466 -0.2746 +vn -0.1407 -0.9805 -0.1375 +vn 0.0258 -0.0104 -0.9996 +vn 0.1839 -0.6280 -0.7562 +vn 0.8217 -0.4680 -0.3252 +vn 0.7472 -0.1572 -0.6457 +vn 0.5869 0.4380 -0.6810 +vn -0.4281 -0.0809 0.9001 +vn -0.4164 -0.0917 0.9046 +vn -0.4300 -0.0741 0.8998 +vn -0.3947 -0.0808 0.9152 +vn -0.3645 -0.0915 0.9267 +vn -0.3870 -0.0634 0.9199 +vn -0.4496 -0.0663 0.8907 +vn -0.4355 -0.0573 0.8983 +vn -0.4060 -0.0830 0.9101 +vn -0.4103 -0.0478 0.9107 +vn -0.4209 -0.0457 0.9060 +vn -0.3962 -0.0278 0.9177 +vn -0.3990 -0.0398 0.9161 +vn -0.3753 -0.0712 0.9242 +vn 0.4746 -0.0652 -0.8778 +vn 0.4149 0.1023 -0.9041 +vn 0.3997 0.1144 -0.9095 +vn 0.4351 -0.1096 -0.8937 +vn 0.4284 0.1379 -0.8930 +vn 0.4654 0.1682 -0.8690 +vn -0.9020 -0.0920 -0.4217 +vn -0.8951 -0.0614 -0.4417 +vn -0.8883 -0.0652 -0.4546 +vn -0.9019 -0.0969 -0.4209 +vn -0.5803 -0.7559 -0.3030 +vn -0.3540 -0.9008 -0.2513 +vn -0.5561 -0.7758 -0.2981 +vn -0.3303 -0.9115 -0.2452 +vn 0.2074 -0.9780 0.0237 +vn 0.2078 -0.9779 0.0238 +vn 0.2078 -0.9779 0.0239 +vn 0.8949 -0.2156 0.3906 +vn 0.9018 -0.3091 0.3022 +vn 0.8969 -0.2945 0.3299 +vn 0.8961 -0.2020 0.3952 +vn 0.5893 0.7285 0.3494 +vn 0.7996 0.4701 0.3736 +vn 0.7745 0.5112 0.3727 +vn 0.5597 0.7540 0.3439 +vn 0.0812 0.9936 0.0780 +vn -0.4880 0.8630 -0.1306 +vn -0.6003 0.7681 -0.2226 +vn -0.5037 0.8520 -0.1430 +vn -0.6195 0.7476 -0.2393 +vn -0.4386 0.1905 -0.8783 +vn -0.3806 0.0852 -0.9208 +vn -0.3623 -0.0796 -0.9287 +vn -0.2384 -0.2725 -0.9322 +vn -0.1742 -0.4695 -0.8656 +vn 0.1518 -0.6131 -0.7753 +vn 0.2426 -0.6581 -0.7128 +vn 0.7425 -0.4256 -0.5173 +vn 0.5685 -0.6150 -0.5465 +vn 0.8386 -0.3642 -0.4051 +vn 0.9374 -0.0025 -0.3483 +vn 0.8729 0.2598 -0.4131 +vn 0.8864 0.3307 -0.3238 +vn 0.6897 0.5945 -0.4134 +vn 0.3441 0.7026 -0.6229 +vn 0.3599 0.7792 -0.5131 +vn 0.0387 0.7145 -0.6986 +vn -0.0632 0.6403 -0.7655 +vn -0.1046 0.6355 -0.7650 +vn -0.0947 0.9886 0.1167 +vn -0.2246 0.9528 0.2041 +vn 0.7859 -0.4690 0.4031 +vn 0.7447 -0.3937 0.5390 +vn -0.7293 -0.3494 -0.5883 +vn -0.7670 -0.4436 -0.4636 +vn -0.4097 -0.0687 0.9096 +vn -0.8312 -0.0651 -0.5522 +vn 0.0446 -0.4386 -0.8976 +vn 0.5578 -0.4386 -0.7046 +vn 0.9507 -0.3039 0.0621 +vn 0.5262 0.2948 -0.7976 +vn -0.4095 -0.0493 0.9110 +vn -0.3934 -0.0657 0.9170 +vn -0.4159 -0.0384 0.9086 +vn -0.3925 -0.0775 0.9165 +vn -0.3766 -0.0723 0.9236 +vn -0.3829 -0.0693 0.9212 +vn -0.4252 -0.0752 0.9019 +vn -0.4412 -0.0628 0.8952 +vn -0.4216 -0.0806 0.9032 +vn -0.4325 -0.0614 0.8995 +vn -0.4191 -0.0278 0.9075 +vn -0.4220 -0.0465 0.9054 +vn -0.4167 -0.1002 0.9035 +vn -0.4121 -0.0940 0.9063 +vn -0.3899 -0.0858 0.9168 +vn 0.3956 -0.0052 -0.9184 +vn 0.3306 0.0277 -0.9434 +vn 0.3237 0.0806 -0.9427 +vn 0.4184 0.0470 -0.9071 +vn 0.3817 -0.0092 -0.9243 +vn -0.8861 -0.2205 -0.4078 +vn -0.9019 0.0490 -0.4291 +vn -0.8456 -0.3134 -0.4321 +vn -0.8655 -0.2953 -0.4045 +vn -0.6718 -0.6349 -0.3815 +vn -0.2361 -0.9603 -0.1488 +vn 0.0923 -0.9945 -0.0503 +vn 0.1710 -0.9851 0.0177 +vn 0.5070 -0.8516 0.1334 +vn 0.7647 -0.5668 0.3065 +vn 0.7900 -0.5433 0.2841 +vn 0.8909 -0.2208 0.3970 +vn 0.5803 0.7388 0.3426 +vn 0.8483 0.3830 0.3655 +vn 0.8184 0.4423 0.3668 +vn 0.5294 0.7802 0.3332 +vn -0.2237 0.9741 -0.0340 +vn 0.0464 0.9982 -0.0370 +vn -0.2488 0.9636 -0.0981 +vn -0.5350 0.8269 -0.1733 +vn -0.5603 0.8018 -0.2079 +vn -0.7615 0.5828 -0.2838 +vn -0.3274 0.3406 -0.8814 +vn -0.3196 0.1909 -0.9281 +vn -0.3632 -0.0334 -0.9311 +vn -0.1220 -0.4235 -0.8977 +vn -0.2896 -0.3159 -0.9035 +vn -0.0310 -0.5716 -0.8200 +vn 0.4118 -0.6344 -0.6542 +vn 0.3609 -0.6693 -0.6494 +vn 0.7165 -0.5166 -0.4688 +vn 0.8198 -0.3457 -0.4565 +vn 0.9171 -0.1718 -0.3597 +vn 0.8752 0.2724 -0.3998 +vn 0.9089 0.2767 -0.3121 +vn 0.7124 0.5762 -0.4005 +vn 0.4087 0.7128 -0.5700 +vn 0.4730 0.7314 -0.4912 +vn 0.1227 0.7539 -0.6454 +vn -0.0917 0.6181 -0.7808 +vn -0.1668 0.5868 -0.7923 +vn 0.8054 -0.5866 0.0855 +vn 0.7858 -0.4692 0.4030 +vn 0.8078 -0.5390 0.2388 +vn 0.7447 -0.3940 0.5388 +vn -0.7293 -0.3497 -0.5880 +vn -0.7856 -0.5354 -0.3102 +vn -0.7669 -0.4437 -0.4636 +vn -0.7808 -0.6027 -0.1647 +vn 0.0244 0.2193 -0.9754 +vn 0.3003 -0.2098 -0.9305 +vn 0.7570 0.3439 -0.5557 +vn 0.2226 0.9237 -0.3117 +vn -0.4118 -0.0887 0.9069 +vn -0.4015 -0.1023 0.9101 +vn -0.3959 -0.0881 0.9141 +vn -0.4232 -0.0605 0.9040 +vn -0.4368 -0.0730 0.8966 +vn -0.4312 -0.0801 0.8987 +vn -0.4313 -0.0620 0.9001 +vn -0.4163 -0.0953 0.9042 +vn -0.4123 -0.0094 0.9110 +vn -0.3946 -0.0608 0.9168 +vn -0.3984 -0.0217 0.9169 +vn -0.3883 -0.0703 0.9188 +vn -0.3848 -0.0526 0.9215 +vn 0.4936 -0.0555 -0.8679 +vn 0.2997 0.0245 -0.9537 +vn 0.3168 0.0957 -0.9437 +vn 0.5045 0.0283 -0.8629 +vn 0.3796 -0.0415 -0.9242 +vn -0.8624 0.3768 -0.3382 +vn -0.8989 0.1110 -0.4239 +vn -0.8712 0.3429 -0.3512 +vn -0.8984 0.0744 -0.4329 +vn -0.6749 -0.6510 -0.3475 +vn -0.6864 -0.6336 -0.3568 +vn -0.6847 -0.6362 -0.3555 +vn -0.6734 -0.6532 -0.3462 +vn 0.1667 -0.9860 -0.0007 +vn 0.1868 -0.9824 -0.0068 +vn 0.1693 -0.9856 -0.0002 +vn 0.1917 -0.9814 -0.0124 +vn 0.8421 -0.4236 0.3338 +vn 0.8613 -0.3557 0.3628 +vn 0.8590 -0.3649 0.3591 +vn 0.8393 -0.4320 0.3300 +vn 0.8714 0.2713 0.4088 +vn 0.8348 0.3960 0.3825 +vn 0.8674 0.2883 0.4057 +vn 0.8298 0.4096 0.3791 +vn 0.3965 0.8778 0.2687 +vn 0.0357 0.9974 0.0620 +vn 0.0386 0.9940 0.1021 +vn -0.2571 0.9640 -0.0684 +vn -0.3306 0.9405 -0.0790 +vn -0.4971 0.8496 -0.1762 +vn -0.2882 0.4302 -0.8555 +vn -0.3002 -0.0494 -0.9526 +vn -0.3820 0.0480 -0.9229 +vn -0.2409 -0.3739 -0.8956 +vn 0.1102 -0.5846 -0.8038 +vn 0.0729 -0.6266 -0.7759 +vn 0.4875 -0.6467 -0.5867 +vn 0.6983 -0.4887 -0.5230 +vn 0.8026 -0.4219 -0.4217 +vn 0.9343 -0.0490 -0.3531 +vn 0.9316 -0.0152 -0.3631 +vn 0.8590 0.3835 -0.3393 +vn 0.7807 0.4761 -0.4048 +vn 0.5988 0.6709 -0.4374 +vn 0.3307 0.7272 -0.6016 +vn 0.2570 0.7444 -0.6163 +vn -0.1441 0.5496 -0.8229 +vn -0.0269 0.6750 -0.7373 +vn -0.3592 0.3533 0.8638 +vn -0.4842 0.5841 -0.6515 +vn -0.3956 0.9026 0.1698 +vn 0.9031 0.3788 0.2025 +vn 0.9199 0.3551 0.1664 +vn 0.9130 0.3653 0.1818 +vn 0.9313 0.3367 0.1389 +vn 0.0628 -0.8877 -0.4560 +vn 0.2224 -0.9483 0.2265 +vn -0.9279 -0.3372 -0.1588 +vn -0.4100 -0.0689 0.9095 +vn 0.0238 0.2196 -0.9753 +vn 0.2407 -0.2539 -0.9368 +vn 0.2166 -0.9738 -0.0689 +vn 0.7568 -0.2128 -0.6181 +vn 0.8185 0.3901 -0.4218 +vn 0.2711 0.8813 -0.3871 +vn -0.3901 -0.0838 0.9169 +vn -0.3830 -0.0737 0.9208 +vn -0.3945 -0.0623 0.9168 +vn -0.4236 -0.0556 0.9042 +vn -0.4360 -0.0646 0.8977 +vn -0.4308 -0.0798 0.8989 +vn -0.4296 -0.0477 0.9018 +vn -0.3869 -0.0577 0.9203 +vn -0.4122 -0.0893 0.9067 +vn -0.4258 -0.0957 0.8997 +vn -0.4099 -0.0993 0.9067 +vn -0.3961 -0.0935 0.9134 +vn -0.4143 -0.0428 0.9091 +vn -0.4052 -0.0470 0.9130 +vn 0.4623 -0.0805 -0.8831 +vn 0.3349 0.1037 -0.9365 +vn 0.3191 0.1254 -0.9394 +vn 0.4437 -0.0958 -0.8910 +vn 0.3644 0.0625 -0.9291 +vn -0.7698 -0.5297 -0.3560 +vn -0.8720 -0.1339 -0.4708 +vn -0.8540 -0.1826 -0.4872 +vn -0.7430 -0.5772 -0.3389 +vn 0.0724 -0.9965 -0.0422 +vn -0.3168 -0.9165 -0.2444 +vn -0.0452 -0.9921 -0.1168 +vn 0.1276 -0.9917 -0.0146 +vn 0.2240 -0.9745 0.0158 +vn 0.7828 -0.5304 0.3254 +vn 0.8797 -0.4009 0.2557 +vn 0.7920 -0.5153 0.3275 +vn 0.8769 -0.3908 0.2797 +vn 0.8677 0.2669 0.4194 +vn 0.8230 0.4449 0.3531 +vn 0.7293 0.5658 0.3848 +vn 0.8081 0.4892 0.3282 +vn 0.5036 0.8067 0.3092 +vn -0.1593 0.9872 -0.0026 +vn -0.0038 0.9990 0.0436 +vn -0.0233 0.9990 0.0379 +vn -0.1818 0.9833 -0.0094 +vn -0.7844 0.5445 -0.2971 +vn -0.6689 0.6945 -0.2649 +vn -0.6859 0.6758 -0.2698 +vn -0.7959 0.5258 -0.3001 +vn -0.2164 0.5330 -0.8180 +vn -0.3045 0.0323 -0.9520 +vn -0.3824 0.1721 -0.9078 +vn -0.3023 -0.2386 -0.9229 +vn -0.0804 -0.5171 -0.8521 +vn 0.0643 -0.5590 -0.8267 +vn 0.3035 -0.6762 -0.6713 +vn 0.6441 -0.5268 -0.5546 +vn 0.6061 -0.5962 -0.5265 +vn 0.8385 -0.3615 -0.4077 +vn 0.9247 -0.0410 -0.3786 +vn 0.9434 -0.0310 -0.3302 +vn 0.8552 0.3856 -0.3463 +vn 0.8039 0.4516 -0.3869 +vn 0.5628 0.6974 -0.4438 +vn 0.4294 0.7191 -0.5463 +vn 0.1494 0.7619 -0.6303 +vn -0.0674 0.6154 -0.7853 +vn -0.4842 0.5842 -0.6513 +vn -0.3957 0.9026 0.1697 +vn 0.9032 0.3786 0.2023 +vn 0.9198 0.3552 0.1666 +vn 0.9130 0.3652 0.1818 +vn 0.9311 0.3370 0.1394 +vn 0.0629 -0.8878 -0.4559 +vn 0.2225 -0.9482 0.2266 +vn -0.9280 -0.3372 -0.1588 +vn -0.4097 -0.0688 0.9096 +vn 0.0444 0.2232 -0.9737 +vn -0.7690 -0.1164 -0.6286 +vn 0.0512 -0.4398 -0.8966 +vn 0.5749 -0.3968 -0.7156 +vn 0.9407 -0.3373 -0.0360 +vn 0.7988 0.0763 -0.5968 +vn 0.8716 0.4599 0.1700 +vn 0.4279 0.5678 -0.7032 +vn 0.1245 0.9836 0.1305 +vn 0.0055 0.9969 0.0779 +vn 0.1136 -0.9932 -0.0240 +vn -0.0055 -0.9969 -0.0779 +vn 0.9121 -0.0369 0.4083 +vn 0.9121 -0.0369 0.4082 +vn 0.4099 0.0685 -0.9096 +vn 0.2414 0.9534 0.1809 +vn 0.2307 -0.9725 0.0304 +vn -0.9121 0.0369 -0.4082 +vn -0.9121 0.0369 -0.4083 +vn -0.1511 0.9532 -0.2618 +vn -0.3685 0.9248 -0.0942 +vn -0.0082 0.9999 -0.0097 +vn -0.2196 -0.7700 0.5990 +vn -0.4276 -0.7574 0.4934 +vn -0.0026 -0.7635 0.6459 +vn 0.6961 0.1608 -0.6997 +vn 0.6896 0.1648 -0.7052 +vn 0.7222 0.0723 -0.6878 +vn 0.1617 -0.4521 -0.8772 +vn 0.2287 -0.2922 -0.9286 +vn 0.1965 -0.3273 -0.9243 +vn -0.8757 -0.0673 0.4781 +vn -0.8532 -0.1710 0.4928 +vn -0.8217 -0.0014 0.5699 +vn 0.1134 0.9227 -0.3684 +vn 0.6904 0.7038 -0.1671 +vn 0.7342 0.6566 -0.1728 +vn 0.6782 0.7314 -0.0707 +vn -0.2198 -0.8808 -0.4193 +vn 0.2855 -0.8861 -0.3651 +vn -0.1694 -0.9507 -0.2598 +vn -0.1188 0.9447 0.3057 +vn -0.1188 0.9447 0.3058 +vn -0.2404 -0.9132 -0.3290 +vn -0.4055 -0.9139 0.0173 +vn -0.4935 -0.8436 -0.2118 +vn 0.6770 -0.7303 -0.0909 +vn 0.7592 -0.6481 0.0600 +vn 0.7406 -0.6110 0.2796 +vn -0.5501 0.6268 0.5518 +vn -0.5749 0.3720 0.7288 +vn -0.4416 0.4201 0.7928 +vn -0.9917 -0.1252 -0.0288 +vn -0.9213 -0.2025 -0.3320 +vn -0.9911 -0.1307 -0.0250 +vn -0.0082 -0.9999 -0.0097 +vn 0.0097 -1.0000 -0.0017 +vn -0.7347 -0.6554 -0.1753 +vn -0.7481 -0.6623 -0.0424 +vn -0.8291 -0.5559 0.0593 +vn 0.4521 0.0013 -0.8920 +vn 0.5093 0.0021 -0.8606 +vn 0.5091 0.0015 -0.8607 +vn 0.8085 -0.3251 -0.4905 +vn 0.5188 -0.2754 -0.8094 +vn 0.6705 -0.0758 -0.7380 +vn -0.5761 -0.8152 0.0593 +vn -0.4676 -0.8685 0.1646 +vn -0.5131 -0.8123 0.2772 +vn 0.6036 -0.7961 0.0427 +vn 0.9100 -0.3695 0.1883 +vn 0.5124 -0.7518 0.4149 +vn -0.1188 -0.9447 0.3057 +vn 0.1633 -0.9201 0.3559 +vn 0.1737 -0.8857 0.4305 +vn 0.1961 -0.8888 0.4141 +vn -0.1157 0.3935 0.9120 +vn -0.0106 0.4074 0.9132 +vn -0.2827 0.5098 0.8125 +vn 0.3976 0.7149 -0.5752 +vn 0.5170 0.7696 -0.3748 +vn 0.5989 0.7016 -0.3861 +vn -0.9744 -0.1299 -0.1835 +vn -0.9267 -0.0467 0.3729 +vn -0.9574 -0.2713 0.0985 +vn -0.7801 0.5904 -0.2068 +vn -0.7265 0.5697 -0.3842 +vn -0.8400 0.3732 -0.3940 +vn -0.0097 1.0000 0.0017 +vn -0.7010 0.7124 0.0328 +vn -0.5423 0.7952 0.2711 +vn -0.4126 0.9105 0.0264 +vn 0.0161 0.9999 -0.0003 +vn 0.0161 0.9999 -0.0002 +vn 0.0428 -0.3364 -0.9408 +vn 0.0004 -0.1239 -0.9923 +vn 0.0861 -0.2376 -0.9675 +vn -0.4132 -0.5114 0.7535 +vn -0.4611 -0.4376 0.7720 +vn -0.5924 -0.5088 0.6246 +vn -0.5248 -0.5209 0.6732 +vn -0.6457 -0.6099 0.4595 +vn -0.7154 -0.6579 0.2354 +vn -0.9063 -0.0034 0.4225 +vn -0.8035 -0.0008 0.5953 +vn -0.0547 -0.5095 0.8587 +vn -0.0476 -0.4544 0.8895 +vn -0.2976 -0.5498 0.7805 +vn 0.3658 0.5517 0.7496 +vn 0.4643 0.6795 0.5681 +vn 0.3501 0.6266 0.6963 +vn 0.0161 -0.9999 -0.0002 +vn 0.1152 0.7653 -0.6333 +vn 0.1188 0.9447 -0.3058 +vn 0.1188 0.9447 -0.3057 +vn 0.1188 0.0835 -0.9894 +vn 0.0965 -0.0045 -0.9953 +vn 0.1991 0.0570 -0.9783 +vn -0.1496 0.9882 0.0337 +vn -0.2118 0.9743 0.0771 +vn -0.0050 1.0000 0.0007 +vn 0.5193 -0.7760 0.3580 +vn 0.4603 -0.8662 0.1947 +vn 0.6325 -0.7476 0.2024 +vn -0.9072 -0.0059 0.4206 +vn -0.7310 -0.1024 0.6746 +vn -0.5456 -0.1610 0.8225 +vn -0.1134 -0.9227 0.3684 +vn -0.0175 0.4026 0.9152 +vn -0.0157 0.6968 0.7171 +vn -0.1115 0.4368 0.8926 +vn 0.7091 0.3247 0.6259 +vn 0.7097 0.2943 0.6400 +vn 0.7072 0.4371 0.5557 +vn -0.9507 0.0048 0.3102 +vn -0.6390 -0.7006 0.3176 +vn -0.7316 -0.5919 0.3383 +vn -0.7633 -0.6139 0.2013 +vn -0.2861 -0.9274 0.2411 +vn -0.0097 -1.0000 0.0017 +vn 0.1671 -0.0029 -0.9859 +vn -0.1933 0.0029 -0.9811 +vn 0.1629 0.6727 -0.7218 +vn 0.3325 0.7539 -0.5666 +vn 0.3068 0.6361 -0.7080 +vn -0.8268 -0.2480 -0.5049 +vn -0.7815 -0.2523 -0.5706 +vn 0.0938 -0.6337 0.7679 +vn -0.1837 -0.6527 0.7350 +vn 0.2115 -0.6703 0.7113 +vn -0.6323 0.7031 -0.3253 +vn -0.7347 0.6554 -0.1753 +vn -0.7481 0.6623 -0.0424 +vn -0.2280 -0.5390 -0.8109 +vn -0.0119 -0.4926 -0.8702 +vn -0.0565 -0.5224 -0.8508 +vn 0.2977 -0.7870 -0.5403 +vn 0.4501 -0.6527 -0.6094 +vn 0.2224 -0.8672 -0.4455 +vn 0.4198 -0.4840 -0.7678 +vn 0.2007 -0.7615 -0.6163 +vn 0.2285 -0.4519 -0.8623 +vn -0.5035 0.2081 -0.8386 +vn -0.2066 0.2777 -0.9382 +vn -0.2065 0.2777 -0.9382 +vn -0.9183 0.0522 0.3924 +vn -0.9744 0.1299 -0.1835 +vn -0.9574 0.2713 0.0985 +vn -0.7511 0.2498 0.6110 +vn -0.5726 -0.0134 0.8197 +vn -0.5598 0.2739 0.7821 +vn 0.0379 0.5468 -0.8364 +vn 0.0689 0.7872 -0.6129 +vn 0.0387 0.6820 -0.7303 +vn 0.0122 0.9542 -0.2988 +vn -0.0371 0.9764 -0.2126 +vn 0.1581 0.9175 -0.3650 +vn -0.1222 0.0101 -0.9925 +vn 0.1203 0.1300 -0.9842 +vn -0.1093 -0.2646 -0.9581 +vn 0.9193 0.3604 0.1583 +vn 0.9412 0.2155 -0.2602 +vn 0.8319 0.5511 -0.0647 +vn -0.8000 0.1534 -0.5800 +vn -0.8088 0.3700 -0.4571 +vn 0.8512 0.5191 -0.0779 +vn 0.6417 0.7448 -0.1832 +vn 0.6939 0.7159 0.0776 +vn -0.7010 -0.7124 0.0328 +vn -0.4126 -0.9105 0.0264 +vn -0.5423 -0.7952 0.2711 +vn 0.8490 0.0092 -0.5283 +vn 0.5405 0.0067 -0.8413 +vn -0.9813 0.0100 -0.1925 +vn -0.6562 -0.3091 0.6884 +vn -0.3876 -0.6322 0.6709 +vn -0.4743 -0.2393 0.8472 +vn -0.9102 -0.2266 0.3466 +vn -0.9917 -0.1285 0.0094 +vn -0.9370 -0.2141 0.2759 +vn -0.6495 -0.6754 -0.3492 +vn -0.6000 -0.7649 -0.2342 +vn -0.7502 -0.6489 -0.1270 +vn -0.3693 -0.3603 -0.8567 +vn -0.5515 -0.0113 -0.8341 +vn -0.3644 -0.0069 -0.9312 +vn 0.7437 -0.0061 0.6685 +vn -0.4363 0.3215 0.8404 +vn -0.2414 0.3159 0.9176 +vn -0.4495 0.3227 0.8329 +vn -0.7307 0.5317 -0.4281 +vn -0.6991 0.5634 -0.4402 +vn -0.6113 0.5304 -0.5874 +vn 0.7246 -0.0023 0.6892 +vn 0.6888 -0.0778 0.7207 +vn 0.8634 -0.1975 0.4644 +vn 0.1047 -0.7582 -0.6436 +vn 0.1231 -0.7045 -0.6989 +vn 0.3311 -0.7893 -0.5171 +vn -0.7702 -0.0126 -0.6376 +vn -0.9325 -0.0112 -0.3609 +vn -0.7179 -0.0094 -0.6961 +vn -0.1129 -0.9567 -0.2684 +vn 0.3217 -0.0171 -0.9467 +vn 0.3135 0.3618 -0.8780 +vn 0.5063 0.0740 -0.8592 +vn 0.3581 0.0194 -0.9335 +vn 0.3376 0.0096 -0.9413 +vn -0.0032 0.0279 -0.9996 +vn 0.0097 1.0000 -0.0017 +vn 0.5719 0.4907 -0.6574 +vn 0.6315 0.7450 -0.2148 +vn 0.7617 0.5508 -0.3411 +vn 0.7983 -0.3488 -0.4911 +vn 0.2848 -0.4037 -0.8695 +vn 0.5976 -0.2539 -0.7605 +vn -0.0161 -0.9999 0.0003 +vn -0.0161 -0.9999 0.0002 +vn 0.2568 -0.5758 -0.7762 +vn 0.2598 -0.5465 -0.7962 +vn 0.3976 -0.7149 -0.5752 +vn -0.9506 0.0153 0.3102 +vn -0.3899 -0.7123 -0.5835 +vn -0.1354 -0.7955 -0.5906 +vn -0.6168 0.7848 -0.0600 +vn -0.5560 0.7491 -0.3601 +vn -0.8291 0.5559 0.0593 +vn -0.8693 0.3047 0.3892 +vn -0.7633 0.6139 0.2013 +vn 0.2035 0.1888 -0.9607 +vn -0.0310 0.0431 -0.9986 +vn 0.1554 0.1843 -0.9705 +vn -0.8212 0.3258 -0.4684 +vn -0.6441 0.2830 -0.7107 +vn -0.5940 0.2396 -0.7680 +vn 0.2414 0.1769 0.9542 +vn 0.2675 -0.0419 0.9626 +vn 0.1743 0.0400 0.9839 +vn -0.7439 0.0126 -0.6681 +vn -0.1129 0.9567 -0.2684 +vn -0.4113 -0.9114 0.0158 +vn -0.4326 -0.7554 0.4921 +vn -0.5412 -0.7991 0.2618 +vn -0.3252 -0.0098 0.9456 +vn -0.0873 -0.0092 0.9961 +vn -0.3610 -0.0061 0.9325 +vn 0.2056 0.9324 -0.2973 +vn 0.4129 0.9048 -0.1043 +vn 0.5362 0.8310 0.1479 +vn 0.4596 0.8772 -0.1389 +vn -0.4973 -0.7665 -0.4064 +vn -0.3050 -0.6642 -0.6825 +vn -0.1731 -0.9132 -0.3689 +vn -0.8536 -0.0642 0.5170 +vn -0.9645 -0.0299 0.2624 +vn -0.9402 -0.0602 0.3353 +vn 0.1658 0.5151 0.8410 +vn -0.0748 0.4333 0.8981 +vn -0.0719 0.3900 0.9180 +vn 0.0903 -0.7568 -0.6474 +vn 0.3297 -0.7957 -0.5082 +vn 0.5667 -0.7382 -0.3658 +vn -0.9674 -0.0953 0.2345 +vn -0.9813 -0.0882 0.1710 +vn -0.9662 -0.1901 0.1743 +vn 0.3861 -0.7983 -0.4623 +vn 0.6122 -0.6227 -0.4873 +vn 0.6659 -0.6635 -0.3412 +vn 0.8557 -0.2713 -0.4407 +vn 0.0083 -0.9999 0.0097 +vn 0.0082 -0.9999 0.0097 +vn 0.9907 0.0765 0.1127 +vn 0.9800 0.1626 -0.1146 +vn 0.9637 0.1924 -0.1853 +vn -0.6550 0.7555 -0.0150 +vn -0.7816 0.6042 -0.1550 +vn -0.7133 0.6859 -0.1439 +vn 0.1019 -0.9852 0.1378 +vn 0.1479 -0.9408 0.3049 +vn 0.1633 -0.9606 0.2251 +vn -0.8853 -0.1718 -0.4321 +vn -0.8937 -0.3554 -0.2738 +vn -0.9812 -0.0557 -0.1849 +vn -0.5635 -0.7158 0.4124 +vn -0.6047 -0.5984 0.5256 +vn -0.7230 -0.5573 0.4083 +vn -0.8880 -0.1044 0.4479 +vn -0.8674 -0.2650 0.4212 +vn -0.4041 0.7410 -0.5363 +vn -0.5618 0.7681 -0.3074 +vn -0.6146 0.7746 -0.1493 +vn 0.6134 0.7897 -0.0079 +vn 0.7268 0.6104 -0.3148 +vn -0.2693 -0.6687 0.6931 +vn -0.3998 -0.7382 0.5434 +vn -0.8690 0.2662 0.4170 +vn -0.8952 0.2077 0.3943 +vn -0.8823 0.1007 0.4599 +vn -0.7301 -0.6460 0.2229 +vn -0.5878 -0.7594 0.2790 +vn -0.6619 -0.6512 0.3712 +vn -0.0031 1.0000 0.0008 +vn -0.0172 0.9998 0.0046 +vn -0.3679 -0.7890 0.4921 +vn -0.7379 -0.3035 0.6029 +vn -0.5196 -0.6518 0.5525 +vn -0.5347 -0.1869 0.8241 +vn 0.3292 -0.4727 0.8174 +vn 0.0746 -0.5014 0.8620 +vn 0.2664 -0.5637 0.7818 +vn 0.2893 -0.9571 -0.0146 +vn -0.0083 -0.9999 -0.0097 +vn 0.1962 -0.9271 0.3193 +vn 0.2220 -0.8148 0.5355 +vn 0.2184 -0.8505 0.4786 +vn 0.4781 -0.1812 -0.8594 +vn 0.6446 -0.1347 -0.7526 +vn 0.3754 -0.2136 -0.9019 +vn -0.5061 -0.7671 -0.3942 +vn 0.8414 0.0134 0.5402 +vn 0.9324 0.0149 0.3610 +vn -0.7815 0.2523 -0.5707 +vn -0.8268 0.2480 -0.5049 +vn -0.6119 0.2800 -0.7397 +vn -0.1635 0.3484 -0.9230 +vn 0.2317 -0.7220 0.6520 +vn 0.1966 -0.7074 0.6790 +vn 0.1154 -0.9061 0.4070 +vn 0.4921 -0.6981 0.5201 +vn 0.2351 -0.7859 0.5720 +vn 0.4458 -0.7610 0.4713 +vn -0.9177 0.1665 0.3606 +vn -0.9317 0.1336 0.3378 +vn -0.9058 0.1330 0.4023 +vn 0.4478 0.0007 -0.8941 +vn 0.9506 -0.0154 -0.3102 +vn -0.5976 -0.4468 0.6658 +vn -0.5438 -0.4042 0.7354 +vn -0.5991 -0.1180 0.7919 +vn -0.8564 -0.1377 -0.4977 +vn -0.8409 -0.3736 -0.3914 +vn -0.9241 -0.1583 -0.3478 +vn 0.3757 0.2523 -0.8917 +vn 0.3255 0.1473 -0.9340 +vn 0.3654 0.1769 -0.9139 +vn -0.6905 -0.7230 0.0209 +vn -0.5442 -0.8268 -0.1421 +vn -0.3502 -0.9355 0.0475 +vn -0.4637 -0.5235 -0.7148 +vn -0.5115 -0.4782 -0.7139 +vn -0.3258 -0.5365 -0.7784 +vn -0.4418 0.5809 -0.6837 +vn -0.2629 0.7548 -0.6009 +vn -0.3836 0.3110 -0.8696 +vn 0.2031 0.1411 0.9689 +vn 0.2081 0.2436 0.9473 +vn 0.1810 0.0043 0.9835 +vn -0.9993 -0.0161 0.0334 +vn -0.9324 -0.0149 -0.3610 +vn 0.7323 -0.4680 0.4947 +vn 0.5614 -0.5755 0.5947 +vn 0.3967 0.2371 0.8868 +vn 0.4315 0.2314 0.8719 +vn 0.0481 0.3021 0.9521 +vn -0.6394 0.7640 0.0863 +vn -0.4167 0.8988 0.1361 +vn -0.5705 0.8144 -0.1063 +vn 0.9255 -0.2164 -0.3107 +vn 0.7639 -0.2836 -0.5796 +vn 0.8337 -0.2576 -0.4885 +vn -0.4829 -0.5758 -0.6597 +vn -0.4551 -0.8614 -0.2256 +vn -0.5366 -0.7822 -0.3166 +vn 0.1129 -0.9567 0.2684 +vn -0.0988 -0.8774 0.4694 +vn 0.1130 -0.9567 0.2684 +vn -0.5736 0.0094 0.8191 +vn -0.6045 0.0066 0.7966 +vn -0.3609 0.0060 0.9326 +vn 0.1577 -0.9010 0.4042 +vn 0.1680 -0.6808 0.7129 +vn 0.1686 -0.8772 0.4495 +vn -0.9813 -0.0100 -0.1925 +vn -0.8088 -0.3700 -0.4571 +vn 0.4566 -0.7335 0.5035 +vn 0.4790 -0.6994 0.5305 +vn 0.1760 -0.7578 0.6283 +vn 0.0794 -0.4552 0.8868 +vn -0.0104 -0.6998 0.7142 +vn 0.1137 -0.7421 0.6606 +vn -0.5336 -0.6366 -0.5568 +vn -0.7712 -0.2891 -0.5672 +vn -0.5456 0.1610 0.8225 +vn -0.7310 0.1024 0.6746 +vn -0.9066 0.0047 0.4219 +vn 0.9973 0.0098 -0.0732 +vn 0.0871 0.6000 0.7952 +vn 0.1115 0.6401 0.7601 +vn 0.1340 0.5609 0.8170 +vn 0.1357 -0.3884 0.9114 +vn -0.5325 -0.5846 0.6122 +vn 0.3700 -0.2599 -0.8920 +vn 0.3041 -0.4883 -0.8180 +vn 0.4090 -0.4625 -0.7866 +vn 0.1105 0.9868 0.1187 +vn 0.0633 0.9813 0.1816 +vn 0.1285 0.9636 0.2345 +vn -0.2891 -0.6364 -0.7151 +vn -0.6527 -0.2184 -0.7255 +vn 0.1635 -0.3484 0.9230 +vn -0.6103 -0.2674 -0.7457 +vn -0.8559 -0.0006 -0.5171 +vn -0.7399 0.1220 -0.6616 +vn -0.4526 0.8302 -0.3254 +vn -0.2490 0.9295 -0.2721 +vn -0.3764 0.8236 -0.4242 +vn -0.0161 0.9999 0.0002 +vn 0.0191 0.9987 -0.0466 +vn 0.0014 0.9996 -0.0277 +vn -0.0613 0.9957 -0.0699 +vn 0.0111 -0.9951 -0.0980 +vn -0.1187 -0.9447 0.3057 +vn 0.3986 -0.0052 -0.9171 +vn 0.1654 -0.0001 -0.9862 +vn 0.5423 -0.0034 -0.8402 +vn 0.9542 0.1860 -0.2342 +vn 0.9255 0.2164 -0.3107 +vn 0.9712 0.1746 -0.1622 +vn 0.2388 -0.0309 -0.9706 +vn 0.1908 -0.0189 -0.9814 +vn 0.2083 -0.0980 -0.9731 +vn -0.1096 0.2565 -0.9603 +vn 0.1208 0.3016 -0.9457 +vn -0.0155 -0.0722 -0.9973 +vn 0.5851 -0.6685 -0.4592 +vn 0.5938 -0.3066 -0.7439 +vn 0.7851 -0.2538 -0.5650 +vn 0.7065 0.1530 0.6910 +vn 0.7165 0.1871 0.6720 +vn 0.7081 0.0508 0.7042 +vn 0.0082 0.9999 0.0097 +vn 0.2970 -0.2678 -0.9165 +vn 0.2261 -0.5250 -0.8205 +vn 0.2378 -0.0031 -0.9713 +vn 0.2473 -0.0021 -0.9689 +vn 0.2620 -0.0030 -0.9651 +vn 0.1553 -0.7573 0.6343 +vn 0.2682 -0.6314 -0.7276 +vn 0.2547 -0.7522 -0.6078 +vn 0.0733 -0.6271 -0.7755 +vn -0.9028 0.1492 -0.4033 +vn -0.9128 0.0490 -0.4054 +vn -0.9610 0.0642 -0.2691 +vn -0.7987 0.0921 -0.5947 +vn -0.9324 0.0085 -0.3614 +vn -0.9994 0.0098 0.0330 +vn 0.1457 0.2861 -0.9471 +vn 0.1890 0.0785 -0.9788 +vn 0.0096 0.0718 -0.9974 +vn 0.1665 -0.1166 -0.9791 +vn 0.1760 -0.2047 -0.9629 +vn 0.2135 -0.1889 -0.9585 +vn -0.8200 0.1224 -0.5591 +vn -0.9305 0.0314 -0.3650 +vn -0.9434 0.0197 -0.3310 +vn 0.2708 0.0302 0.9622 +vn 0.2714 0.0290 0.9620 +vn 0.2513 -0.0254 0.9676 +vn -0.4596 -0.7145 0.5276 +vn -0.5361 -0.8021 0.2631 +vn -0.0565 0.5224 -0.8508 +vn 0.2568 0.5758 -0.7762 +vn 0.2598 0.5465 -0.7962 +vn 0.9972 -0.0160 -0.0736 +vn 0.8487 -0.0138 -0.5287 +vn -0.5109 0.2907 -0.8090 +vn -0.9160 0.2837 0.2835 +vn -0.9657 0.1902 0.1767 +vn -0.9516 0.1419 0.2727 +vn 0.4308 0.1604 -0.8881 +vn 0.4505 0.2758 -0.8491 +vn 0.7828 -0.0807 -0.6170 +vn 0.0273 -0.9813 -0.1907 +vn 0.0212 -0.9954 -0.0932 +vn 0.0407 -0.9988 0.0288 +vn -0.0036 0.1081 -0.9941 +vn 0.0255 0.3976 -0.9172 +vn 0.0076 0.2210 -0.9753 +vn -0.2068 0.0078 0.9784 +vn 0.3467 -0.8465 -0.4041 +vn 0.5099 -0.8183 -0.2651 +vn 0.1723 -0.9618 -0.2125 +vn 0.7439 -0.0118 0.6682 +vn 0.0083 0.9999 0.0097 +vn 0.1802 -0.3280 -0.9273 +vn -0.1322 -0.9308 -0.3409 +vn 0.0937 -0.9401 -0.3277 +vn -0.2950 -0.9046 -0.3075 +vn -0.0767 0.9510 0.2997 +vn -0.1831 0.8456 0.5014 +vn 0.1594 0.8686 0.4691 +vn -0.8961 -0.0720 -0.4380 +vn -0.7284 0.0457 -0.6836 +vn -0.3902 -0.2944 -0.8724 +vn -0.2837 -0.2675 -0.9208 +vn -0.2194 -0.4639 -0.8583 +vn 0.2391 -0.1881 0.9526 +vn 0.2559 -0.0963 0.9619 +vn 0.2551 -0.0494 0.9656 +vn 0.4643 -0.7950 0.3903 +vn 0.5557 -0.8030 0.2153 +vn 0.6558 -0.7022 0.2770 +vn -0.2048 0.9609 0.1863 +vn -0.3850 0.9192 0.0831 +vn -0.5148 0.8033 0.2995 +vn -0.7437 0.0061 -0.6685 +vn -0.0764 -0.6643 0.7436 +vn -0.6209 0.2162 -0.7535 +vn -0.5462 0.5938 -0.5908 +vn 0.1579 0.0060 0.9874 +vn 0.2224 0.0788 0.9718 +vn -0.2519 0.0342 0.9671 +vn 0.6001 -0.7998 0.0115 +vn 0.2704 -0.9623 -0.0277 +vn 0.5576 -0.7862 0.2663 +vn 0.0318 0.3114 -0.9498 +vn 0.0319 0.3114 -0.9497 +vn 0.4694 0.7529 0.4613 +vn 0.5780 0.7842 0.2259 +vn 0.6615 0.7490 -0.0378 +vn -0.4034 -0.0160 -0.9149 +vn -0.8756 0.4587 0.1516 +vn -0.9543 0.2874 0.0817 +vn 0.6063 0.1934 -0.7713 +vn 0.5991 0.3903 -0.6992 +vn 0.8490 -0.0092 -0.5283 +vn 0.6065 -0.0073 -0.7951 +vn 0.3704 0.0533 -0.9273 +vn -0.9213 0.2021 -0.3322 +vn -0.9213 0.2020 -0.3322 +vn 0.0483 -0.0822 0.9954 +vn 0.0382 -0.1340 0.9903 +vn 0.0370 -0.0483 0.9981 +vn 0.3399 0.5542 -0.7599 +vn 0.2312 0.7823 -0.5783 +vn 0.4352 0.5790 -0.6894 +vn 0.4489 -0.6464 -0.6169 +vn 0.2691 -0.7416 -0.6145 +vn 0.3227 -0.3361 -0.8848 +vn -0.7639 0.2837 0.5796 +vn -0.0211 -0.2677 0.9633 +vn -0.4449 -0.1928 0.8746 +vn -0.0211 -0.2678 0.9633 +vn -0.2567 -0.0002 0.9665 +vn -0.2558 0.0008 0.9667 +vn -0.2531 -0.0013 0.9674 +vn 0.0986 -0.9936 0.0548 +vn 0.1181 -0.9850 0.1261 +vn 0.6572 0.0496 -0.7521 +vn 0.6216 0.1378 -0.7711 +vn -0.7439 0.0118 -0.6682 +vn -0.6323 -0.7031 -0.3253 +vn -0.6168 -0.7848 -0.0600 +vn 0.2452 0.2523 0.9361 +vn 0.0732 -0.0219 0.9971 +vn -0.1971 -0.0228 -0.9801 +vn 0.1199 0.1294 -0.9843 +vn -0.1568 -0.2711 -0.9497 +vn 0.4786 0.3021 -0.8244 +vn 0.2787 0.3443 -0.8965 +vn 0.3284 0.4420 -0.8347 +vn -0.2556 0.3753 -0.8910 +vn 0.0490 0.5089 -0.8594 +vn -0.1544 0.3603 -0.9200 +vn 0.0362 -0.9055 -0.4228 +vn 0.0701 -0.8705 -0.4871 +vn 0.0587 -0.7258 -0.6854 +vn 0.1602 0.0033 0.9871 +vn 0.2221 0.0072 0.9750 +vn 0.4291 0.0336 0.9027 +vn -0.9072 0.0114 0.4206 +vn -0.8267 0.0132 0.5624 +vn -0.4726 -0.8560 -0.2096 +vn -0.3308 -0.8706 -0.3641 +vn 0.4205 -0.1629 -0.8925 +vn 0.3959 -0.1608 -0.9041 +vn 0.7405 -0.6116 -0.2785 +vn 0.9195 -0.3636 0.1492 +vn -0.2683 0.0037 -0.9633 +vn 0.1675 0.0033 -0.9859 +vn -0.6781 -0.7228 0.1331 +vn 0.1677 0.2878 0.9429 +vn 0.4011 0.5322 0.7456 +vn 0.2691 0.5991 0.7541 +vn 0.5878 -0.4472 0.6742 +vn 0.4547 -0.4600 0.7627 +vn 0.1723 -0.4262 0.8881 +vn -0.9065 0.0095 0.4221 +vn -0.8037 0.0088 0.5949 +vn 0.0520 0.9299 -0.3642 +vn 0.4468 -0.7737 -0.4492 +vn 0.6895 -0.7243 -0.0075 +vn 0.7129 -0.7012 -0.0138 +vn 0.0678 -0.0834 0.9942 +vn 0.0752 -0.1423 0.9870 +vn -0.1222 -0.0190 -0.9923 +vn -0.0972 0.0018 -0.9953 +vn 0.1149 -0.1535 -0.9814 +vn -0.1620 0.9318 0.3250 +vn 0.1129 0.9567 0.2684 +vn -0.7828 0.0807 0.6170 +vn 0.9213 0.2020 0.3322 +vn 0.9213 0.2019 0.3322 +vn -0.3966 0.7907 -0.4664 +vn 0.1607 -0.8892 0.4284 +vn 0.0439 0.9957 -0.0811 +vn 0.0648 0.9945 -0.0820 +vn 0.0684 0.9396 -0.3352 +vn -0.5120 0.7671 -0.3866 +vn -0.2502 0.9178 -0.3083 +vn -0.4164 0.7158 -0.5606 +vn 0.2123 -0.1083 -0.9712 +vn 0.4193 -0.0007 -0.9078 +vn 0.3872 -0.0508 -0.9206 +vn -0.3172 0.6333 -0.7059 +vn -0.2211 0.7565 -0.6155 +vn -0.0970 0.7201 -0.6871 +vn 0.4330 -0.2446 -0.8676 +vn 0.5052 -0.1562 -0.8487 +vn 0.2397 -0.7114 0.6607 +vn 0.2205 -0.4540 0.8633 +vn 0.2609 -0.5657 0.7823 +vn 0.2067 0.0036 -0.9784 +vn -0.2454 -0.9452 0.2155 +vn -0.4092 0.0007 0.9124 +vn -0.4050 0.0012 0.9143 +vn -0.4642 -0.0032 0.8857 +vn -0.1402 -0.7937 -0.5919 +vn 0.0095 0.9987 -0.0502 +vn -0.6539 -0.3492 -0.6712 +vn 0.9973 -0.0098 -0.0733 +vn 0.9324 -0.0085 0.3614 +vn -0.2280 0.4602 -0.8581 +vn -0.4058 0.4980 -0.7663 +vn -0.9775 -0.0587 0.2025 +vn -0.5437 -0.5211 -0.6580 +vn -0.4390 -0.6663 -0.6028 +vn -0.5294 -0.6916 -0.4913 +vn 0.5503 0.7042 -0.4486 +vn 0.3840 0.7000 -0.6022 +vn 0.3451 0.7999 -0.4910 +vn -0.9317 0.0116 -0.3630 +vn -0.9783 0.0154 -0.2067 +vn -0.9004 0.0144 -0.4349 +vn -0.5909 0.0013 -0.8068 +vn -0.6183 0.0989 -0.7797 +vn -0.4736 0.0828 -0.8768 +vn -0.1931 0.1226 0.9735 +vn -0.1793 -0.1410 0.9736 +vn -0.1453 -0.1097 0.9833 +vn 0.2853 -0.3692 -0.8845 +vn 0.4930 -0.1788 -0.8514 +vn 0.6064 -0.5060 -0.6134 +vn -0.0402 -0.0026 0.9992 +vn -0.0283 -0.0091 0.9996 +vn -0.0433 -0.0838 0.9955 +vn -0.2330 0.9723 0.0197 +vn -0.3870 0.9186 0.0806 +vn -0.6065 0.7897 0.0925 +vn -0.6543 0.7427 -0.1423 +vn -0.8830 0.4549 0.1158 +vn -0.7899 -0.5978 -0.1365 +vn -0.8256 -0.5636 -0.0263 +vn -0.8193 -0.5385 -0.1969 +vn 0.0731 -0.9967 0.0359 +vn 0.0720 -0.9966 0.0397 +vn 0.6885 -0.0111 0.7251 +vn 0.4958 -0.0157 0.8683 +vn 0.7164 -0.0127 0.6976 +vn 0.0905 -0.8661 -0.4917 +vn 0.0668 -0.7541 -0.6534 +vn 0.1049 -0.9112 -0.3984 +vn 0.3443 0.0921 -0.9343 +vn 0.2852 0.2923 -0.9128 +vn 0.4135 0.3063 -0.8575 +vn -0.1134 0.9227 0.3684 +vn -0.1135 0.9227 0.3684 +vn 0.1752 0.1892 0.9662 +vn 0.1860 0.1861 0.9648 +vn 0.1775 0.0981 0.9792 +vn 0.2360 0.7920 0.5630 +vn -0.0445 0.7314 0.6804 +vn -0.0521 0.7086 0.7037 +vn 0.2753 0.0006 -0.9614 +vn 0.3074 -0.0038 -0.9516 +vn -0.9560 0.0256 -0.2924 +vn -0.9729 0.0565 -0.2244 +vn -0.7995 -0.0884 -0.5941 +vn 0.2781 0.1190 0.9531 +vn 0.2828 0.1213 0.9515 +vn 0.2966 0.2027 0.9333 +vn 0.1763 -0.2108 0.9615 +vn 0.1490 -0.2512 0.9564 +vn 0.1846 -0.1074 0.9769 +vn 0.4007 0.4766 -0.7825 +vn 0.2907 0.5041 -0.8133 +vn -0.1222 -0.0101 -0.9925 +vn -0.4034 -0.0100 -0.9150 +vn -0.3848 0.3396 -0.8582 +vn -0.6209 0.6815 -0.3873 +vn -0.7731 0.2511 -0.5824 +vn -0.3889 0.9032 0.1819 +vn -0.1807 0.9746 0.1319 +vn 0.0160 0.9999 -0.0003 +vn 0.7186 0.0334 -0.6946 +vn 0.7617 -0.0157 -0.6477 +vn 0.7193 0.0129 -0.6946 +vn 0.2696 -0.9597 -0.0790 +vn -0.8416 0.3629 -0.4001 +vn -0.1406 0.8797 -0.4542 +vn 0.4464 -0.7202 0.5310 +vn 0.2044 -0.7453 0.6346 +vn 0.0555 -0.6382 -0.7679 +vn 0.0294 -0.4564 -0.8893 +vn -0.4592 0.8574 -0.2323 +vn -0.3357 0.9372 -0.0950 +vn -0.2952 0.9050 -0.3063 +vn 0.0260 -0.8948 -0.4456 +vn 0.0264 -0.9554 -0.2942 +vn 0.0486 -0.9455 -0.3218 +vn 0.0317 0.6479 -0.7611 +vn 0.0185 0.4766 -0.8790 +vn 0.0585 0.5164 -0.8543 +vn 0.5658 0.3679 0.7379 +vn 0.7260 0.5077 0.4638 +vn 0.9226 0.2140 0.3210 +vn 0.5175 0.8467 0.1239 +vn 0.5871 0.7817 0.2102 +vn 0.8028 -0.5962 -0.0062 +vn 0.6821 -0.7197 -0.1296 +vn 0.8333 -0.4970 -0.2420 +vn 0.0161 -0.9999 -0.0003 +vn 0.2225 0.8348 0.5035 +vn 0.1972 0.8906 0.4098 +vn 0.1727 0.9140 0.3672 +vn 0.0003 -0.0008 1.0000 +vn -0.0143 -0.0059 0.9999 +vn -0.0203 -0.0034 0.9998 +vn 0.2807 -0.1198 -0.9523 +vn 0.2443 -0.1050 -0.9640 +vn 0.2689 -0.1493 -0.9515 +vn 0.1784 -0.7068 0.6846 +vn -0.1398 -0.6467 0.7498 +vn -0.4948 0.8429 -0.2114 +vn -0.3716 0.7299 -0.5737 +vn -0.4993 0.6617 -0.5593 +vn 0.5379 -0.8216 -0.1889 +vn 0.7311 -0.6242 -0.2755 +vn 0.8190 -0.5705 -0.0608 +vn -0.8820 0.4701 0.0338 +vn -0.8474 0.3735 0.3773 +vn -0.5550 -0.6213 0.5532 +vn -0.6695 -0.7278 0.1485 +vn -0.4578 -0.8784 0.1373 +vn 0.9507 0.0048 -0.3102 +vn -0.8193 0.5385 -0.1969 +vn -0.8193 0.5731 -0.0198 +vn -0.7899 0.5999 -0.1275 +vn 0.0358 0.7763 0.6293 +vn 0.0817 0.7528 0.6531 +vn 0.0620 0.6022 0.7959 +vn 0.0780 0.5868 -0.8060 +vn 0.0823 0.5147 -0.8534 +vn -0.1436 0.5570 -0.8180 +vn 0.0959 -0.6021 -0.7926 +vn 0.5989 -0.7016 -0.3861 +vn 0.5170 -0.7696 -0.3748 +vn -0.1549 0.1167 0.9810 +vn -0.3958 0.1219 0.9102 +vn -0.1093 0.2646 -0.9581 +vn 0.1203 -0.1300 -0.9842 +vn -0.8254 0.4712 0.3108 +vn -0.4643 -0.7123 0.5264 +vn 0.2406 0.0001 -0.9706 +vn 0.2502 -0.0002 -0.9682 +vn 0.2444 0.0007 -0.9697 +vn 0.1010 0.2577 -0.9609 +vn 0.4803 0.1839 -0.8576 +vn 0.1009 0.2577 -0.9609 +vn 0.5402 -0.0089 -0.8415 +vn -0.3234 0.5988 -0.7327 +vn -0.1016 0.9060 -0.4108 +vn -0.2209 -0.5395 0.8125 +vn 0.9738 -0.0603 -0.2194 +vn 0.9798 -0.1148 -0.1637 +vn 0.8768 -0.0143 -0.4806 +vn 0.5667 0.7382 -0.3659 +vn 0.7129 0.7012 -0.0138 +vn 0.6040 0.7049 -0.3719 +vn 0.9488 0.2146 -0.2317 +vn 0.7497 0.5935 -0.2928 +vn 0.2877 -0.2944 -0.9113 +vn 0.2494 -0.1490 -0.9569 +vn 0.3239 0.0094 -0.9460 +vn -0.7639 -0.2837 0.5796 +vn -0.5001 -0.8418 -0.2034 +vn -0.5120 -0.7671 -0.3866 +vn -0.2502 -0.9178 -0.3083 +vn 0.4497 -0.6387 -0.6244 +vn 0.5033 -0.5690 -0.6503 +vn 0.5856 -0.6693 -0.4573 +vn 0.2661 0.0759 -0.9609 +vn 0.2038 0.1562 -0.9665 +vn 0.2927 0.0568 -0.9545 +vn -0.5001 0.8418 -0.2034 +vn 0.6048 0.1838 0.7749 +vn 0.5821 0.1824 0.7924 +vn 0.8824 0.0244 0.4700 +vn -0.3194 0.7881 -0.5262 +vn -0.4390 0.6663 -0.6028 +vn 0.9680 -0.2276 -0.1060 +vn 0.9573 -0.2077 -0.2009 +vn 0.9248 -0.3129 0.2164 +vn -0.1838 -0.5481 0.8160 +vn -0.2565 -0.0004 0.9665 +vn -0.2597 -0.0006 0.9657 +vn -0.2585 -0.0002 0.9660 +vn -0.2646 0.3780 -0.8872 +vn -0.3868 0.3425 -0.8562 +vn 0.2034 0.8278 0.5229 +vn 0.9786 -0.0705 0.1934 +vn 0.1415 0.2585 0.9556 +vn 0.1415 0.1392 0.9801 +vn 0.1646 0.3098 0.9364 +vn 0.0588 0.3703 -0.9271 +vn 0.0475 0.3427 -0.9382 +vn 0.0324 0.3233 -0.9457 +vn -0.7424 -0.6634 -0.0938 +vn -0.5440 -0.7593 -0.3572 +vn 0.5331 0.2463 -0.8094 +vn 0.9324 -0.0149 0.3610 +vn 0.9325 -0.0149 0.3610 +vn -0.7035 0.1359 -0.6976 +vn -0.5954 -0.1293 -0.7929 +vn -0.8262 -0.3138 -0.4679 +vn 0.9729 0.2084 -0.1002 +vn 0.9904 -0.0592 0.1247 +vn 0.9523 -0.1133 -0.2833 +vn -0.5647 0.4543 0.6891 +vn -0.2976 0.5498 0.7805 +vn -0.5248 0.5209 0.6732 +vn 0.0735 -0.9951 -0.0662 +vn 0.0533 -0.9901 0.1299 +vn -0.8776 0.4673 -0.1070 +vn -0.8207 0.5550 -0.1359 +vn -0.6008 -0.6268 0.4961 +vn -0.4457 -0.6463 0.6194 +vn -0.4720 -0.5367 0.6994 +vn -0.3197 0.9475 0.0113 +vn 0.2108 0.1686 0.9629 +vn 0.1261 0.2067 0.9702 +vn 0.1849 0.0714 0.9802 +vn 0.1659 -0.8979 0.4076 +vn 0.1624 -0.9481 0.2733 +vn -0.3498 0.7837 0.5133 +vn -0.4177 0.8136 0.4044 +vn -0.5494 0.6355 0.5425 +vn 0.9973 0.0098 -0.0733 +vn 0.7852 -0.2462 -0.5681 +vn 0.9343 0.0029 -0.3564 +vn 0.9505 -0.2048 -0.2337 +vn 0.8759 0.0589 0.4788 +vn 0.6770 0.2005 0.7082 +vn 0.6223 0.1568 0.7669 +vn 0.9846 -0.0365 0.1707 +vn 0.9343 -0.0029 -0.3564 +vn 0.9505 0.2048 -0.2337 +vn -0.0470 -0.8261 -0.5615 +vn -0.7636 -0.6359 -0.1123 +vn -0.8232 -0.5585 -0.1020 +vn -0.7802 -0.5891 -0.2104 +vn 0.4559 -0.7128 0.5329 +vn 0.4483 -0.6210 0.6430 +vn 0.3440 -0.5747 0.7425 +vn 0.0772 0.6671 -0.7409 +vn 0.0492 0.6240 -0.7799 +vn 0.1159 0.4018 -0.9083 +vn 0.7141 -0.0762 -0.6959 +vn 0.6068 -0.1424 -0.7820 +vn 0.6749 -0.1654 -0.7192 +vn -0.3194 -0.7881 -0.5262 +vn -0.3764 -0.8236 -0.4242 +vn 0.9488 -0.2146 -0.2317 +vn -0.4351 -0.8528 0.2889 +vn -0.2785 -0.9162 0.2882 +vn -0.2806 -0.9161 0.2863 +vn 0.1209 0.8394 -0.5299 +vn 0.2283 0.6244 -0.7470 +vn -0.0296 0.7789 -0.6265 +vn -0.2635 -0.0001 0.9646 +vn -0.2601 0.0001 0.9656 +vn -0.2640 -0.0002 0.9645 +vn -0.2917 0.9406 -0.1736 +vn -0.4973 0.8446 -0.1981 +vn 0.6040 -0.7049 -0.3719 +vn 0.6945 0.6775 -0.2422 +vn 0.7039 0.5985 -0.3825 +vn 0.7211 0.6084 -0.3315 +vn -0.5398 -0.8040 0.2493 +vn -0.1951 0.3115 0.9300 +vn 0.1186 0.2788 0.9530 +vn 0.1588 0.2793 0.9470 +vn 0.4446 -0.8887 -0.1117 +vn 0.2548 -0.9311 -0.2610 +vn -0.8989 0.0630 0.4335 +vn -0.8557 0.1737 0.4874 +vn -0.9213 -0.2021 -0.3322 +vn -0.9213 -0.2020 -0.3322 +vn -0.0110 0.9999 0.0001 +vn -0.0061 1.0000 0.0003 +vn -0.0084 0.9998 0.0197 +vn 0.7439 0.0126 0.6682 +vn 0.1896 0.3548 -0.9155 +vn 0.1980 0.7005 -0.6856 +vn 0.0763 0.8756 -0.4770 +vn -0.5959 0.7527 -0.2798 +vn -0.6986 0.7083 -0.1015 +vn -0.6022 0.7783 -0.1778 +vn -0.8955 -0.3945 -0.2061 +vn -0.9659 -0.1706 -0.1948 +vn 0.2283 -0.3014 0.9258 +vn 0.2206 -0.2898 0.9313 +vn 0.0006 0.2263 0.9741 +vn -0.2864 0.0631 0.9560 +vn -0.2945 0.0025 0.9557 +vn -0.3444 0.3280 0.8796 +vn -0.6819 0.3014 0.6665 +vn 0.5443 0.3314 -0.7706 +vn 0.7266 0.6859 -0.0402 +vn 0.0903 -0.0254 0.9956 +vn 0.0637 -0.0421 0.9971 +vn 0.1116 0.0017 0.9938 +vn -0.0416 0.7404 0.6709 +vn -0.2256 0.7623 0.6066 +vn -0.0545 0.7004 0.7117 +vn 0.3100 -0.8976 0.3133 +vn 0.3527 -0.8219 0.4473 +vn 0.8435 0.0664 0.5329 +vn 0.9313 0.0009 0.3644 +vn 0.8003 0.0946 0.5921 +vn -0.4692 -0.8800 -0.0734 +vn -0.5697 -0.7886 -0.2313 +vn -0.4766 -0.7930 -0.3796 +vn 0.9324 0.0085 0.3614 +vn 0.8413 0.0073 0.5406 +vn 0.8413 0.0073 0.5405 +vn -0.1787 0.6356 0.7511 +vn 0.0938 0.6337 0.7679 +vn 0.2118 0.6701 0.7114 +vn 0.0948 0.9736 -0.2076 +vn 0.1065 0.9552 -0.2762 +vn 0.0960 0.9907 -0.0969 +vn -0.1188 -0.9447 0.3058 +vn 0.1391 0.7078 0.6926 +vn -0.1629 0.9040 -0.3952 +vn 0.1273 0.0086 -0.9918 +vn -0.3462 0.0087 -0.9381 +vn -0.3101 0.0118 -0.9506 +vn -0.4525 0.7472 -0.4868 +vn -0.6563 0.6768 -0.3334 +vn -0.3948 0.8842 -0.2497 +vn 0.3420 0.9280 0.1476 +vn 0.6413 0.7075 0.2971 +vn -0.6467 -0.5468 -0.5317 +vn -0.6005 -0.7130 -0.3621 +vn -0.7265 -0.5697 -0.3842 +vn -0.8316 0.1329 -0.5392 +vn 0.1473 -0.2887 -0.9460 +vn 0.0016 -0.9997 -0.0226 +vn -0.0038 -0.9999 -0.0131 +vn 0.0346 -0.9899 -0.1376 +vn 0.3773 0.7193 -0.5833 +vn -0.4113 0.9114 0.0158 +vn -0.4988 0.8401 -0.2132 +vn -0.7000 0.7137 0.0244 +vn 0.6846 -0.7283 -0.0295 +vn 0.7178 -0.6947 -0.0470 +vn 0.5780 -0.7842 0.2259 +vn -0.4346 0.1143 0.8933 +vn -0.5825 0.1187 0.8041 +vn -0.5021 -0.1175 0.8568 +vn 0.1427 -0.0789 0.9866 +vn 0.4318 -0.2566 0.8647 +vn -0.3889 0.7715 0.5035 +vn -0.1649 0.8523 0.4963 +vn -0.5294 0.7620 0.3730 +vn 0.8811 0.2673 0.3902 +vn -0.6452 0.4868 -0.5889 +vn -0.8883 0.3770 -0.2624 +vn 0.3677 -0.4975 0.7856 +vn -0.1477 -0.7856 0.6008 +vn -0.3962 0.8137 -0.4253 +vn 0.0628 -0.9949 -0.0793 +vn 0.0494 -0.9984 -0.0264 +vn 0.0525 -0.9929 -0.1068 +vn -0.6302 -0.2409 -0.7382 +vn -0.5104 0.8596 -0.0242 +vn -0.6340 0.7733 0.0034 +vn 0.0620 0.7947 0.6038 +vn -0.1886 0.8079 0.5583 +vn -0.9994 -0.0098 0.0330 +vn -0.9324 -0.0085 -0.3614 +vn 0.2494 0.5522 -0.7955 +vn 0.3849 0.9046 0.1833 +vn -0.0282 0.9060 0.4223 +vn 0.3769 0.8584 0.3480 +vn -0.7999 -0.2527 0.5443 +vn -0.7759 -0.4565 0.4354 +vn -0.1971 0.0228 -0.9801 +vn -0.3742 0.0837 -0.9236 +vn -0.4845 0.5027 -0.7159 +vn 0.6718 -0.0673 -0.7377 +vn 0.5261 -0.3220 -0.7871 +vn 0.5987 -0.0838 -0.7966 +vn -0.0192 0.9924 -0.1213 +vn 0.0784 0.9962 0.0375 +vn -0.0141 0.9983 -0.0566 +vn 0.5402 -0.0037 -0.8415 +vn 0.7789 0.0003 -0.6271 +vn 0.8472 -0.0032 -0.5313 +vn 0.9660 0.2457 -0.0801 +vn 0.9162 0.3017 0.2636 +vn 0.9594 -0.1047 -0.2621 +vn -0.1187 0.9447 0.3057 +vn 0.1049 0.5772 -0.8099 +vn 0.9172 0.3685 0.1512 +vn -0.9865 -0.1572 0.0458 +vn -0.8051 -0.5772 0.1368 +vn -0.9033 -0.2748 0.3294 +vn 0.1134 -0.9227 -0.3684 +vn 0.1135 -0.9227 -0.3684 +vn 0.6117 -0.3425 -0.7131 +vn 0.5562 -0.4084 -0.7238 +vn 0.1188 -0.9447 -0.3057 +vn 0.4784 0.2891 0.8292 +vn 0.2946 0.2902 0.9105 +vn 0.9995 0.0032 -0.0303 +vn 0.9999 0.0083 0.0068 +vn 0.8646 0.0186 0.5021 +vn 0.9213 -0.2020 0.3322 +vn 0.9836 -0.1459 0.1061 +vn 0.9922 -0.1199 0.0346 +vn 0.0536 0.2135 -0.9755 +vn 0.0261 0.4495 -0.8929 +vn 0.1434 -0.5122 -0.8468 +vn 0.5106 -0.4328 -0.7429 +vn 0.3816 -0.7615 -0.5239 +vn 0.0479 -0.9985 -0.0279 +vn -0.7419 0.6305 -0.2282 +vn 0.5803 -0.6784 -0.4506 +vn 0.0448 0.9874 0.1515 +vn 0.0171 0.9708 0.2394 +vn 0.0247 0.9918 0.1250 +vn -0.1538 0.6959 0.7015 +vn -0.2098 0.3945 0.8946 +vn 0.3255 0.1641 -0.9312 +vn 0.2663 0.1661 -0.9495 +vn 0.1437 -0.1489 0.9784 +vn -0.9815 -0.1202 0.1492 +vn -0.9944 0.0998 -0.0346 +vn -0.9897 0.0942 -0.1081 +vn -0.9610 -0.1084 0.2543 +vn -0.0629 0.8879 -0.4558 +vn -0.1308 0.9852 -0.1112 +vn 0.1492 0.9217 -0.3579 +vn 0.9692 -0.0104 0.2459 +vn 0.9005 -0.0117 0.4348 +vn 0.2515 0.0732 0.9651 +vn 0.2623 -0.0017 0.9650 +vn -0.0547 0.5095 0.8587 +vn 0.1639 0.5716 0.8040 +vn 0.1075 0.9125 -0.3947 +vn 0.1368 -0.7684 -0.6252 +vn 0.2376 -0.7637 -0.6002 +vn 0.1318 -0.8833 -0.4499 +vn 0.7437 0.0061 0.6685 +vn -0.2884 -0.6973 0.6562 +vn -0.4606 -0.4353 0.7736 +vn -0.4071 -0.7052 0.5805 +vn 0.1641 -0.8341 -0.5266 +vn -0.0592 0.9871 -0.1484 +vn -0.0735 0.9919 -0.1034 +vn -0.5624 -0.0083 -0.8269 +vn -0.7702 -0.0122 -0.6377 +vn -0.6901 -0.0059 -0.7237 +vn 0.0474 0.8758 0.4803 +vn 0.1143 0.8999 0.4208 +vn 0.0182 0.9833 0.1811 +vn -0.7913 -0.0044 0.6114 +vn -0.7262 -0.0078 0.6874 +vn -0.8113 -0.0184 0.5843 +vn -0.3401 0.9403 0.0127 +vn 0.0420 0.0003 -0.9991 +vn 0.1124 0.0017 -0.9937 +vn 0.0415 0.0004 -0.9991 +vn 0.2068 0.0078 -0.9784 +vn 0.2067 0.0078 -0.9784 +vn 0.0257 -0.0012 0.9997 +vn 0.0256 0.0168 0.9995 +vn 0.0507 0.1030 0.9934 +vn -0.8536 0.0642 0.5170 +vn -0.7099 0.0582 0.7019 +vn -0.9402 0.0602 0.3353 +vn 0.0599 -0.9974 -0.0409 +vn 0.0609 -0.9974 -0.0377 +vn 0.0696 -0.9924 -0.1013 +vn 0.1273 -0.7047 -0.6979 +vn 0.3359 -0.7879 -0.5161 +vn 0.1093 -0.7584 -0.6425 +vn -0.2986 0.6930 0.6562 +vn -0.4100 0.3922 0.8235 +vn -0.2936 0.4333 0.8521 +vn -0.8995 0.4343 0.0469 +vn -0.7052 0.7072 0.0504 +vn -0.6855 0.6920 0.2264 +vn -0.7948 0.5996 0.0932 +vn -0.4729 0.8361 0.2780 +vn -0.3780 0.9251 0.0374 +vn -0.2847 0.9586 0.0108 +vn -0.0161 0.9999 0.0003 +vn 0.8904 0.0532 0.4522 +vn 0.9235 0.0067 0.3836 +vn 0.5072 0.8612 -0.0318 +vn 0.6028 0.7387 0.3016 +vn 0.6168 0.7327 0.2877 +vn 0.2687 0.9306 -0.2484 +vn 0.1073 0.8991 -0.4244 +vn -0.7902 -0.1529 -0.5935 +vn -0.9513 -0.0993 -0.2918 +vn -0.0615 -0.2812 -0.9577 +vn -0.4762 -0.2923 -0.8293 +vn -0.4068 -0.2910 -0.8660 +vn 0.0589 -0.5904 0.8049 +vn 0.0337 -0.5054 0.8622 +vn 0.0403 -0.3212 0.9461 +vn -0.7700 -0.0064 -0.6380 +vn -0.6898 -0.0005 -0.7240 +vn 0.0098 1.0000 -0.0017 +vn -0.3130 0.6339 -0.7073 +vn 0.5658 -0.7413 0.3611 +vn 0.4290 -0.8026 0.4145 +vn 0.6395 -0.7438 0.1943 +vn 0.8575 0.5077 -0.0835 +vn 0.9639 -0.2044 -0.1707 +vn 0.9744 -0.2082 -0.0843 +vn 0.3134 -0.9399 -0.1353 +vn 0.6073 -0.7771 -0.1649 +vn 0.5664 -0.8239 0.0187 +vn 0.0747 -0.9524 0.2954 +vn 0.0810 -0.9490 0.3046 +vn 0.0284 -0.9688 0.2463 +vn -0.3085 0.9237 -0.2272 +vn -0.4243 0.6251 -0.6552 +vn -0.5336 0.6366 -0.5568 +vn -0.1942 0.3762 -0.9060 +vn -0.3731 0.3825 -0.8453 +vn -0.3261 0.5461 -0.7716 +vn 0.4443 -0.7322 0.5162 +vn 0.4516 -0.5968 0.6633 +vn 0.1805 -0.7486 0.6379 +vn 0.9502 -0.2089 -0.2311 +vn 0.2730 0.1504 -0.9502 +vn 0.3144 0.1544 -0.9366 +vn -0.7289 0.6774 0.0986 +vn -0.6657 0.7068 0.2395 +vn -0.4613 0.8845 0.0689 +vn -0.0077 -0.7644 0.6447 +vn -0.2247 -0.7695 0.5978 +vn 0.7102 0.5499 0.4397 +vn 0.7078 0.6332 0.3131 +vn 0.7084 0.5522 0.4395 +vn 0.0391 -0.7998 -0.5990 +vn -0.9027 -0.1111 0.4157 +vn -0.8554 -0.0675 0.5136 +vn -0.3172 -0.6333 -0.7059 +vn -0.0668 -0.7250 -0.6855 +vn -0.2211 -0.7565 -0.6155 +vn 0.2781 0.8098 -0.5167 +vn -0.1130 -0.9567 -0.2684 +vn -0.4080 -0.1164 0.9055 +vn -0.3850 -0.3977 0.8329 +vn -0.9156 -0.2832 0.2854 +vn -0.9419 -0.1225 0.3127 +vn -0.9507 -0.1428 0.2754 +vn -0.5083 0.7211 0.4707 +vn -0.1955 0.9250 0.3259 +vn -0.2849 0.9123 0.2942 +vn -0.3195 -0.4991 -0.8055 +vn -0.5106 -0.5713 -0.6426 +vn 0.2013 -0.5253 0.8268 +vn 0.2107 -0.7968 0.5664 +vn -0.0752 0.9233 0.3767 +vn -0.6912 0.1222 0.7123 +vn -0.5973 0.4463 0.6664 +vn -0.6780 0.4115 0.6090 +vn -0.2597 -0.0008 0.9657 +vn -0.2595 -0.0003 0.9658 +vn 0.8157 -0.5540 -0.1664 +vn -0.3933 0.2988 -0.8695 +vn -0.2419 0.3340 -0.9110 +vn -0.2564 -0.0005 0.9666 +vn -0.2547 0.0004 0.9670 +vn -0.2550 -0.0005 0.9669 +vn -0.5299 -0.8470 0.0414 +vn -0.6912 -0.7206 0.0549 +vn -0.8228 -0.5586 -0.1050 +vn 0.6919 0.0418 -0.7208 +vn 0.5701 -0.8215 -0.0074 +vn 0.5073 -0.8612 -0.0318 +vn 0.3735 -0.9142 -0.1572 +vn 0.0893 -0.9911 -0.0989 +vn 0.0791 -0.9939 -0.0763 +vn 0.0766 -0.9537 -0.2908 +vn -0.6522 0.7294 -0.2066 +vn -0.7213 -0.6888 -0.0723 +vn -0.7711 -0.6350 -0.0465 +vn -0.7419 -0.6305 -0.2282 +vn -0.4985 -0.4768 0.7240 +vn -0.0748 -0.4333 0.8981 +vn -0.3485 -0.4538 0.8201 +vn 0.5359 0.7197 0.4414 +vn 0.6149 0.7307 0.2966 +vn 0.0414 -0.9983 -0.0403 +vn 0.0388 -0.9924 -0.1167 +vn 0.0399 -0.9982 -0.0437 +vn 0.0215 -0.9989 -0.0410 +vn 0.9928 0.0875 -0.0817 +vn 0.9601 0.0348 -0.2775 +vn 0.9835 0.1499 0.1017 +vn -0.5412 0.7991 0.2618 +vn 0.8313 0.0585 -0.5527 +vn 0.1042 0.9886 0.1084 +vn 0.1073 0.9858 0.1295 +vn 0.1152 0.9644 0.2381 +vn -0.6005 0.7130 -0.3621 +vn -0.9560 -0.0256 -0.2924 +vn 0.8235 -0.5634 -0.0664 +vn 0.5443 -0.8154 -0.1970 +vn -0.5515 -0.7070 -0.4428 +vn -0.4481 -0.7124 -0.5401 +vn 0.5781 -0.0488 -0.8145 +vn 0.6730 -0.0735 -0.7360 +vn 0.1791 0.4173 0.8910 +vn 0.1015 0.1455 0.9841 +vn 0.6001 0.4128 0.6852 +vn 0.7545 0.4270 0.4984 +vn 0.6200 0.5910 0.5161 +vn -0.3465 -0.6653 0.6613 +vn -0.0248 -0.7726 0.6344 +vn -0.1799 -0.6777 0.7130 +vn -0.0102 0.8053 0.5927 +vn -0.2971 -0.6539 -0.6958 +vn -0.4845 -0.5027 -0.7159 +vn 0.2528 0.4357 0.8639 +vn 0.2329 0.2187 0.9476 +vn 0.1025 -0.1229 -0.9871 +vn 0.1387 -0.2683 -0.9533 +vn -0.2934 -0.4333 0.8522 +vn -0.1538 -0.6959 0.7015 +vn -0.7669 -0.1199 -0.6305 +vn -0.7547 -0.3506 -0.5546 +vn -0.9707 -0.2246 0.0849 +vn -0.6055 -0.7149 0.3496 +vn -0.8336 -0.3042 0.4612 +vn 0.7600 0.3613 -0.5402 +vn 0.6900 0.4626 -0.5567 +vn -0.0442 -0.0003 0.9990 +vn 0.0933 0.0009 0.9956 +vn 0.0925 0.0006 0.9957 +vn -0.9325 0.0112 -0.3609 +vn -0.9994 0.0079 0.0335 +vn -0.5786 0.7913 -0.1976 +vn -0.6477 0.6804 -0.3429 +vn -0.6014 0.0037 0.7989 +vn -0.5447 -0.0124 0.8385 +vn -0.4641 -0.1182 0.8779 +vn 0.6151 0.7211 0.3187 +vn 0.6418 0.6985 0.3165 +vn -0.4526 -0.8302 -0.3254 +vn -0.5641 0.0121 -0.8256 +vn -0.2305 0.0067 -0.9730 +vn -0.4931 0.0063 -0.8700 +vn -0.0743 0.9940 -0.0802 +vn -0.5952 0.0125 -0.8035 +vn -0.7179 0.0094 -0.6961 +vn -0.7702 0.0126 -0.6376 +vn 0.6800 0.7326 -0.0303 +vn 0.5729 0.7881 0.2250 +vn 0.7134 0.6991 -0.0478 +vn -0.0965 -0.0010 -0.9953 +vn -0.1631 -0.0004 -0.9866 +vn -0.1631 -0.0008 -0.9866 +vn 0.9213 0.2020 0.3321 +vn 0.6907 -0.0108 0.7230 +vn 0.6732 -0.0622 0.7368 +vn 0.8377 -0.0045 0.5461 +vn 0.7007 0.2205 -0.6786 +vn 0.7115 0.3270 -0.6219 +vn 0.7060 0.3744 -0.6011 +vn 0.7090 0.6868 0.1597 +vn 0.7082 0.6855 0.1691 +vn 0.7044 0.6688 0.2378 +vn -0.9902 -0.0675 -0.1226 +vn -0.9976 -0.0075 -0.0695 +vn -0.9083 -0.1532 -0.3892 +vn -0.0957 -0.0007 -0.9954 +vn 0.3891 -0.3778 -0.8402 +vn 0.2338 -0.3847 -0.8929 +vn -0.1240 -0.3470 -0.9296 +vn -0.6843 0.7247 0.0811 +vn -0.5557 0.8290 0.0627 +vn -0.4654 -0.2679 -0.8436 +vn -0.3766 0.0798 -0.9229 +vn 0.3464 -0.1743 -0.9217 +vn -0.9141 -0.1717 0.3674 +vn -0.9317 -0.1309 0.3388 +vn 0.0463 -0.2146 0.9756 +vn 0.0629 -0.1760 0.9824 +vn 0.5067 -0.1568 0.8477 +vn 0.1932 -0.0255 0.9808 +vn 0.0938 0.9956 -0.0025 +vn 0.0903 0.9910 0.0992 +vn 0.1417 0.7783 -0.6117 +vn 0.0526 0.7970 -0.6017 +vn 0.1011 0.9067 -0.4096 +vn -0.0166 0.0260 -0.9995 +vn 0.0045 -0.0171 -0.9998 +vn 0.0096 0.9410 0.3382 +vn 0.0168 0.9998 0.0124 +vn 0.0309 0.8187 -0.5734 +vn -0.8003 0.2473 -0.5463 +vn -0.6226 0.2189 -0.7513 +vn -0.7380 -0.0854 -0.6694 +vn 0.9193 -0.3604 0.1583 +vn 0.8319 -0.5511 -0.0647 +vn 0.7101 0.6947 -0.1148 +vn 0.6676 0.7427 -0.0520 +vn 0.7556 0.6517 0.0662 +vn -0.8936 0.3989 -0.2060 +vn -0.2513 -0.9629 0.0988 +vn -0.0935 -0.9885 0.1192 +vn -0.2751 -0.9453 0.1751 +vn -0.9855 0.1491 0.0808 +vn -0.9920 0.0845 0.0938 +vn 0.0248 0.3894 0.9208 +vn 0.0275 0.4439 0.8956 +vn -0.7140 0.0518 0.6982 +vn -0.5647 -0.4543 0.6891 +vn 0.3512 -0.7014 -0.6203 +vn 0.4710 -0.4469 -0.7605 +vn 0.1606 0.6267 0.7625 +vn 0.1647 0.6590 0.7339 +vn 0.1727 0.5091 0.8432 +vn 0.1576 0.3745 0.9137 +vn 0.1579 0.3833 0.9100 +vn -0.4765 0.6432 0.5993 +vn -0.0175 0.9080 0.4186 +vn 0.7907 -0.0242 -0.6117 +vn 0.8863 0.0059 -0.4630 +vn 0.8999 -0.0208 -0.4355 +vn 0.1943 -0.9442 -0.2658 +vn -0.3256 0.9445 0.0427 +vn -0.1203 0.7419 -0.6597 +vn 0.1211 0.7914 -0.5992 +vn -0.1510 0.7092 -0.6886 +vn 0.6207 -0.7071 0.3388 +vn 0.5430 -0.7736 0.3268 +vn 0.3474 -0.9213 0.1747 +vn 0.7658 -0.3703 0.5258 +vn 0.9738 0.0603 -0.2194 +vn 0.9812 0.0955 -0.1677 +vn -0.3052 0.1175 0.9450 +vn -0.6824 -0.7258 0.0866 +vn -0.1673 -0.2845 -0.9440 +vn -0.3782 0.6285 0.6797 +vn -0.1477 0.7856 0.6008 +vn -0.6245 -0.7773 -0.0767 +vn -0.8264 -0.4710 0.3086 +vn -0.0160 -0.9999 0.0002 +vn 0.1901 0.1635 0.9681 +vn 0.1889 0.1520 0.9702 +vn 0.1642 -0.9360 0.3114 +vn -0.0894 -0.8658 0.4924 +vn -0.0836 -0.8961 0.4360 +vn 0.1942 0.1867 0.9630 +vn -0.6852 -0.3414 0.6434 +vn -0.4909 -0.3775 0.7852 +vn -0.4222 -0.3804 0.8229 +vn 0.8337 0.2576 -0.4885 +vn 0.2068 -0.3425 0.9165 +vn 0.2060 -0.3466 0.9151 +vn 0.7054 -0.1394 -0.6950 +vn 0.0221 0.3940 -0.9188 +vn 0.0471 -0.5638 -0.8246 +vn -0.3429 -0.7797 -0.5239 +vn -0.9645 0.0299 0.2624 +vn 0.1678 -0.6839 -0.7100 +vn 0.1157 -0.9268 -0.3573 +vn 0.2735 0.0246 0.9616 +vn 0.2707 0.0252 0.9623 +vn -0.1377 0.3707 -0.9185 +vn 0.5827 -0.1678 0.7952 +vn 0.0499 -0.3249 0.9444 +vn 0.3041 -0.0512 0.9513 +vn 0.6355 -0.7237 0.2691 +vn 0.4548 0.0190 0.8904 +vn 0.3856 0.0122 0.9226 +vn 0.6877 0.0134 0.7259 +vn 0.8235 0.5634 -0.0664 +vn 0.6069 0.7944 0.0253 +vn 0.2698 -0.7402 -0.6159 +vn -0.5226 0.8479 -0.0895 +vn 0.6028 -0.7387 0.3016 +vn -0.2520 0.0316 0.9672 +vn 0.2221 -0.0072 0.9750 +vn 0.5362 -0.8310 0.1479 +vn 0.0595 0.9980 -0.0234 +vn 0.0388 0.9934 -0.1080 +vn -0.0437 -0.0003 0.9990 +vn -0.1772 0.2836 -0.9424 +vn -0.1385 0.2826 -0.9492 +vn -0.5834 -0.8103 0.0545 +vn -0.7111 -0.6908 0.1310 +vn 0.0115 -0.8056 -0.5924 +vn 0.0234 -0.9189 -0.3938 +vn -0.6991 -0.5634 -0.4402 +vn -0.6113 -0.5304 -0.5874 +vn 0.0787 0.5139 -0.8542 +vn 0.0863 0.6366 -0.7664 +vn -0.0083 0.9999 -0.0098 +vn 0.2818 0.9590 -0.0307 +vn -0.0083 0.9999 -0.0097 +vn -0.2460 0.9112 -0.3304 +vn -0.5107 0.7634 -0.3955 +vn -0.6776 -0.7312 -0.0792 +vn -0.8863 -0.4348 0.1595 +vn 0.0778 -0.9964 0.0344 +vn 0.0460 -0.8858 0.4618 +vn -0.2882 -0.9126 0.2901 +vn -0.9919 -0.0562 -0.1135 +vn -0.9936 -0.0040 -0.1132 +vn -0.8572 -0.2905 -0.4253 +vn 0.1250 0.3754 0.9184 +vn 0.9150 0.0094 0.4033 +vn 0.4158 -0.3060 -0.8564 +vn 0.4223 -0.0898 -0.9020 +vn 0.5489 -0.0952 -0.8305 +vn 0.7153 0.4428 0.5406 +vn 0.7151 0.4895 0.4990 +vn -0.9533 0.1389 0.2682 +vn -0.1278 -0.2908 -0.9482 +vn -0.0906 -0.2918 -0.9522 +vn 0.2297 -0.3252 -0.9173 +vn -0.1130 0.9567 -0.2684 +vn 0.1508 -0.5491 -0.8220 +vn -0.6682 -0.0017 0.7440 +vn 0.0677 0.9960 -0.0581 +vn 0.0754 0.9850 -0.1551 +vn 0.1385 0.2827 0.9492 +vn -0.8244 0.1680 0.5405 +vn 0.1508 0.5491 -0.8220 +vn 0.1603 0.0005 0.9871 +vn 0.1603 0.0008 0.9871 +vn 0.1385 -0.9077 -0.3960 +vn 0.0633 -0.9326 -0.3554 +vn -0.0113 -0.8323 -0.5542 +vn 0.0246 0.0016 0.9997 +vn 0.0608 -0.1283 0.9899 +vn 0.4464 -0.7883 -0.4234 +vn 0.4446 -0.6484 -0.6180 +vn -0.1589 0.8668 -0.4727 +vn -0.3429 0.7797 -0.5239 +vn -0.7099 -0.0582 0.7019 +vn -0.2519 -0.0342 0.9671 +vn -0.5325 -0.1705 0.8291 +vn -0.3486 0.4538 0.8201 +vn -0.4985 0.4767 0.7240 +vn -0.5639 0.4107 0.7165 +vn 0.5237 0.3212 -0.7890 +vn 0.7639 0.2836 -0.5796 +vn -0.1908 -0.8656 0.4629 +vn 0.1474 -0.7256 0.6722 +vn -0.0089 -1.0000 -0.0023 +vn -0.0075 -1.0000 -0.0050 +vn -0.0053 -0.9993 -0.0375 +vn 0.2358 0.7134 0.6599 +vn 0.2389 0.7477 0.6196 +vn 0.1469 0.9239 0.3534 +vn 0.1243 -0.9906 0.0567 +vn 0.1194 -0.9904 -0.0700 +vn 0.8897 0.0169 0.4562 +vn 0.9227 -0.0251 0.3847 +vn 0.7670 0.3170 -0.5579 +vn 0.7669 0.3170 -0.5579 +vn 0.7204 -0.0758 -0.6894 +vn 0.1922 0.9122 0.3619 +vn -0.1758 0.8005 -0.5730 +vn 0.1639 -0.5716 0.8040 +vn 0.0320 0.9965 -0.0775 +vn 0.0417 0.9979 -0.0485 +vn 0.0018 -0.8950 0.4461 +vn -0.6342 -0.1645 -0.7555 +vn -0.8218 -0.0793 -0.5643 +vn 0.2250 0.8714 -0.4359 +vn -0.0828 -0.9132 0.3989 +vn 0.0236 -0.9986 -0.0477 +vn -0.0682 -0.9966 -0.0467 +vn -0.0585 -0.9940 -0.0925 +vn 0.5238 0.3212 -0.7890 +vn -0.9970 0.0258 -0.0723 +vn -0.9250 -0.2327 -0.3005 +vn -0.9976 0.0075 -0.0695 +vn -0.1244 -0.6341 -0.7632 +vn -0.4108 -0.6372 -0.6521 +vn 0.8999 0.0208 -0.4355 +vn -0.9858 0.1508 0.0741 +vn -0.9657 0.0152 -0.2593 +vn -0.9804 0.1630 0.1110 +vn 0.3399 -0.5542 -0.7599 +vn -0.1738 0.5999 -0.7810 +vn -0.2582 0.2326 0.9377 +vn -0.4449 0.1928 0.8746 +vn -0.1385 -0.2826 -0.9492 +vn 0.2067 -0.0036 -0.9784 +vn 0.9637 -0.1924 -0.1853 +vn 0.7669 -0.3170 -0.5579 +vn 0.7670 -0.3170 -0.5579 +vn -0.7364 0.5672 0.3689 +vn -0.2071 -0.0037 0.9783 +vn 0.2621 0.5505 0.7927 +vn 0.0540 0.6933 -0.7186 +vn -0.0948 0.7566 -0.6470 +vn 0.7236 -0.6892 -0.0381 +vn 0.3962 0.3566 -0.8461 +vn 0.5975 0.4828 -0.6403 +vn 0.4062 -0.0347 -0.9131 +vn 0.0410 -0.5689 -0.8214 +vn 0.0243 -0.4870 -0.8731 +vn 0.0403 -0.6617 -0.7487 +vn 0.0742 -0.9803 -0.1833 +vn -0.5856 -0.6747 -0.4492 +vn -0.6126 -0.5067 -0.6066 +vn 0.1966 0.7419 0.6411 +vn 0.1692 0.8009 0.5744 +vn -0.2683 -0.0037 -0.9633 +vn -0.2323 0.0006 -0.9726 +vn -0.3942 0.7090 -0.5847 +vn -0.3577 -0.9331 -0.0360 +vn -0.5788 -0.8152 -0.0231 +vn -0.1802 0.1369 0.9741 +vn -0.1053 0.0006 0.9944 +vn -0.1203 0.0054 0.9927 +vn -0.3742 -0.0837 -0.9236 +vn -0.0082 -0.9999 -0.0098 +vn -0.1311 0.9795 -0.1530 +vn 0.7307 0.4031 0.5510 +vn 0.6351 0.7286 0.2565 +vn 0.5470 0.7421 0.3874 +vn 0.1143 -0.7128 0.6920 +vn -0.0324 0.9616 0.2725 +vn -0.5956 0.5878 0.5475 +vn -0.6979 0.2584 0.6680 +vn 0.8632 -0.0059 0.5049 +vn 0.9807 0.0103 0.1955 +vn 0.1988 -0.9502 -0.2402 +vn -0.6834 -0.6880 0.2442 +vn -0.0384 -0.9793 -0.1989 +vn 0.0755 -0.9635 -0.2568 +vn 0.0704 -0.6892 0.7211 +vn 0.0215 -0.6715 0.7407 +vn 0.0264 -0.6036 0.7969 +vn 0.8695 -0.0422 -0.4921 +vn 0.0298 -0.9940 -0.1052 +vn 0.4217 -0.3220 -0.8476 +vn 0.5237 -0.3212 -0.7890 +vn 0.0222 0.0090 0.9997 +vn -0.6434 0.3260 -0.6927 +vn -0.5145 0.3010 -0.8029 +vn 0.6842 0.6664 0.2964 +vn 0.9333 0.3229 0.1572 +vn -0.5437 0.5211 -0.6580 +vn -0.0841 -0.3605 -0.9289 +vn 0.6919 -0.0385 -0.7210 +vn 0.7832 0.2580 -0.5657 +vn 0.9343 0.0080 -0.3564 +vn -0.5901 0.7364 0.3309 +vn -0.7806 0.4534 0.4303 +vn -0.7097 0.4843 0.5116 +vn 0.1259 0.7217 0.6807 +vn -0.0370 -0.0008 0.9993 +vn -0.0516 -0.0015 0.9987 +vn -0.0334 -0.0013 0.9994 +vn 0.0590 -0.0036 -0.9983 +vn -0.1116 -0.0117 -0.9937 +vn 0.0471 0.5638 -0.8246 +vn -0.8200 -0.1217 -0.5593 +vn -0.9443 -0.0082 -0.3291 +vn -0.1108 -0.9917 -0.0651 +vn 0.2224 -0.0788 0.9718 +vn 0.7816 -0.0251 0.6233 +vn 0.5472 0.1115 0.8296 +vn 0.2572 -0.4290 0.8659 +vn 0.2467 -0.1338 0.9598 +vn -0.6669 -0.0111 0.7451 +vn -0.7791 -0.0089 0.6268 +vn -0.9073 -0.0128 0.4202 +vn -0.6917 -0.0035 0.7222 +vn -0.2520 -0.0316 0.9672 +vn -0.4743 0.2393 0.8472 +vn 0.0284 0.4940 -0.8690 +vn 0.4987 -0.5794 -0.6446 +vn 0.7832 -0.2580 -0.5657 +vn -0.2131 -0.0149 0.9769 +vn -0.9536 -0.1386 0.2674 +vn -0.9569 -0.1229 0.2631 +vn 0.1611 0.3087 -0.9374 +vn 0.4501 -0.8880 -0.0940 +vn 0.1187 -0.9447 -0.3057 +vn 0.6978 -0.6703 0.2524 +vn -0.7437 -0.0061 -0.6685 +vn -0.1899 0.9797 0.0643 +vn -0.2342 0.9717 0.0295 +vn -0.1932 0.9805 0.0354 +vn -0.2616 0.9019 0.3437 +vn -0.5441 0.8020 0.2467 +vn -0.9213 0.2025 -0.3320 +vn 0.8753 -0.4766 -0.0821 +vn 0.7924 -0.6078 0.0527 +vn 0.4048 -0.8050 0.4337 +vn -0.4967 -0.8453 -0.1969 +vn -0.0379 0.8400 -0.5413 +vn 0.5729 -0.7881 0.2249 +vn 0.4518 -0.7371 0.5026 +vn 0.6800 -0.7326 -0.0304 +vn 0.2169 0.7309 0.6471 +vn 0.4194 0.6063 0.6756 +vn -0.1287 -0.5402 -0.8316 +vn 0.8434 0.2307 -0.4852 +vn 0.9506 0.0146 -0.3102 +vn 0.9998 0.0161 0.0068 +vn 0.9975 0.0096 -0.0694 +vn 0.2544 0.7525 -0.6074 +vn -0.3000 0.9502 -0.0844 +vn 0.9345 -0.0026 -0.3561 +vn -0.1758 -0.8005 -0.5730 +vn -0.0789 0.1286 0.9886 +vn -0.0284 -0.1101 0.9935 +vn 0.0263 0.1474 0.9887 +vn -0.2460 -0.9112 -0.3304 +vn -0.3854 -0.9192 0.0811 +vn -0.4735 -0.8787 0.0614 +vn -0.3901 -0.9205 0.0230 +vn -0.2518 -0.9677 0.0154 +vn -0.7937 -0.6050 0.0634 +vn -0.6942 -0.7197 0.0134 +vn -0.6668 -0.7386 0.0993 +vn 0.6337 0.2982 -0.7138 +vn 0.1185 0.9930 -0.0007 +vn 0.0943 0.9898 0.1071 +vn 0.0960 0.9948 -0.0342 +vn 0.6343 0.1649 0.7553 +vn 0.0450 -0.9963 0.0736 +vn 0.0810 -0.9752 0.2062 +vn 0.0168 -0.9974 0.0699 +vn -0.0302 -0.7172 -0.6962 +vn -0.1436 -0.5570 -0.8180 +vn 0.7691 0.3050 -0.5617 +vn 0.4824 0.6429 -0.5949 +vn -0.5294 0.6916 -0.4913 +vn 0.1651 -0.0003 -0.9863 +vn -0.2686 0.0006 -0.9632 +vn 0.1273 0.0023 -0.9919 +vn -0.7577 -0.0250 0.6522 +vn -0.9227 -0.0096 0.3853 +vn 0.1256 -0.3703 0.9204 +vn 0.0972 -0.3951 0.9135 +vn 0.0790 -0.1950 0.9776 +vn -0.1413 -0.9837 -0.1110 +vn -0.1651 -0.9752 -0.1471 +vn 0.1709 -0.3284 0.9289 +vn 0.1727 -0.5045 0.8459 +vn 0.1311 -0.2243 0.9657 +vn 0.4677 -0.0032 -0.8839 +vn 0.4278 0.0194 -0.9037 +vn 0.4333 -0.0113 -0.9012 +vn -0.0083 0.0671 -0.9977 +vn -0.1934 -0.9265 0.3228 +vn -0.2790 -0.9146 0.2928 +vn -0.7565 0.3476 -0.5539 +vn 0.3953 0.7005 -0.5942 +vn 0.3742 0.7638 -0.5259 +vn -0.0784 0.8372 0.5413 +vn 0.1878 0.8586 0.4769 +vn 0.0823 -0.5147 -0.8534 +vn 0.4266 0.6620 0.6162 +vn 0.7579 0.3538 0.5481 +vn 0.1056 0.4853 -0.8680 +vn 0.0170 -0.4758 -0.8794 +vn -0.8208 -0.0099 0.5711 +vn -0.8231 -0.0001 0.5679 +vn -0.8225 -0.0026 0.5687 +vn -0.3970 -0.4993 -0.7701 +vn -0.0437 -0.3212 -0.9460 +vn 0.0439 -0.9979 -0.0480 +vn 0.0421 -0.9981 -0.0455 +vn 0.0917 0.9566 0.2766 +vn -0.1381 -0.9250 0.3540 +vn -0.2323 -0.0006 -0.9726 +vn -0.5621 -0.0036 -0.8271 +vn -0.9519 0.1670 -0.2569 +vn 0.5420 0.0056 -0.8404 +vn 0.3982 0.0064 -0.9173 +vn -0.5325 0.1705 0.8291 +vn -0.2554 -0.0001 0.9668 +vn 0.5724 -0.7301 -0.3732 +vn 0.6095 -0.6964 -0.3790 +vn 0.0570 -0.9390 -0.3391 +vn 0.6116 -0.0139 -0.7911 +vn 0.6733 -0.0582 -0.7371 +vn -0.1286 -0.2867 -0.9494 +vn -0.2487 -0.0846 -0.9649 +vn -0.0725 -0.0681 -0.9950 +vn 0.9849 -0.0305 0.1703 +vn 0.7828 0.0807 -0.6170 +vn -0.5299 -0.8024 0.2745 +vn -0.5949 -0.7494 0.2907 +vn 0.1134 0.0002 0.9936 +vn 0.2636 0.2445 0.9331 +vn 0.1134 0.0285 0.9931 +vn 0.7104 0.6952 0.1095 +vn 0.7360 -0.6156 -0.2817 +vn 0.4264 0.7240 -0.5422 +vn 0.1746 0.9392 -0.2957 +vn 0.5157 0.8022 -0.3009 +vn -0.9135 -0.3524 -0.2033 +vn -0.9614 0.0566 -0.2693 +vn -0.5086 0.7914 0.3390 +vn -0.6070 0.7689 0.2010 +vn -0.5743 0.7163 0.3965 +vn -0.5979 0.6550 0.4621 +vn -0.6139 0.5514 0.5648 +vn -0.3647 -0.3962 -0.8426 +vn -0.1791 -0.5140 -0.8389 +vn -0.4473 -0.4742 -0.7583 +vn -0.7347 0.1145 -0.6687 +vn -0.0529 -0.7004 0.7118 +vn -0.0454 -0.7235 0.6888 +vn -0.1345 0.9859 -0.0995 +vn -0.0909 0.9945 -0.0524 +vn -0.1132 -0.4331 0.8942 +vn -0.0605 -0.1599 0.9853 +vn -0.2075 -0.3924 0.8961 +vn 0.7163 -0.0113 0.6977 +vn 0.7163 -0.0113 0.6976 +vn 0.7056 -0.4413 -0.5544 +vn 0.7106 -0.4756 -0.5185 +vn 0.7075 -0.3534 -0.6120 +vn -0.9376 -0.3300 -0.1090 +vn -0.9839 -0.1654 -0.0681 +vn 0.2460 0.7378 0.6286 +vn -0.1571 0.8587 0.4878 +vn 0.5468 0.8080 -0.2194 +vn 0.1348 -0.5622 0.8160 +vn 0.1089 -0.6124 0.7830 +vn -0.0158 -0.0261 0.9995 +vn 0.0175 -0.8907 0.4543 +vn 0.0155 -0.9578 0.2869 +vn 0.7936 -0.4591 0.3993 +vn 0.7713 -0.5927 0.2319 +vn -0.6250 0.0107 0.7806 +vn -0.7078 -0.0114 0.7063 +vn 0.7048 -0.3251 0.6306 +vn 0.7200 -0.2370 0.6523 +vn 0.7205 -0.2190 0.6579 +vn 0.1273 -0.0086 -0.9918 +vn 0.1274 -0.0086 -0.9918 +vn 0.9508 -0.0098 -0.3098 +vn 0.0788 0.9850 -0.1535 +vn 0.0437 0.9969 -0.0655 +vn 0.0293 0.9949 -0.0968 +vn -0.1294 0.2861 -0.9494 +vn -0.1526 0.0703 -0.9858 +vn -0.3163 0.0754 -0.9457 +vn -0.3988 -0.6436 -0.6532 +vn 0.2191 -0.9607 0.1706 +vn -0.9462 -0.2925 0.1381 +vn -0.8975 -0.1476 0.4155 +vn 0.3856 -0.0060 0.9226 +vn 0.1933 -0.0029 0.9811 +vn -0.5801 0.8118 0.0666 +vn -0.8773 -0.4544 0.1543 +vn -0.8882 -0.4573 0.0445 +vn -0.4790 -0.8416 -0.2497 +vn -0.6052 -0.7655 -0.2184 +vn -0.0098 1.0000 0.0017 +vn 0.7169 0.0768 -0.6929 +vn 0.7146 -0.0695 -0.6961 +vn 0.7206 -0.0121 -0.6932 +vn 0.1164 -0.9750 0.1895 +vn 0.0929 -0.9950 0.0377 +vn 0.0565 -0.9896 0.1320 +vn 0.1675 -0.9555 0.2426 +vn 0.2646 -0.9640 0.0244 +vn 0.2120 -0.9757 0.0548 +vn 0.3043 -0.9526 0.0030 +vn 0.4018 -0.9107 0.0961 +vn 0.3760 -0.9198 0.1125 +vn 0.4305 -0.9018 0.0392 +vn 0.4842 -0.8739 -0.0429 +vn 0.5717 -0.8167 -0.0785 +vn 0.0159 0.2881 -0.9575 +vn -0.6812 0.0511 0.7303 +vn 0.3333 -0.7572 0.5618 +vn 0.9373 -0.2231 -0.2679 +vn 0.7787 -0.6049 -0.1666 +vn 0.7598 -0.6239 -0.1829 +vn 0.1204 -0.3548 -0.9272 +vn 0.9497 -0.1816 -0.2549 +vn 0.9132 0.2822 -0.2940 +vn 0.9040 0.3144 -0.2896 +vn 0.2255 0.0184 -0.9741 +vn 0.2261 0.0104 -0.9741 +vn 0.2082 0.1698 -0.9632 +vn -0.5151 -0.3023 -0.8021 +vn -0.6545 -0.1044 -0.7488 +vn -0.5274 -0.0778 -0.8461 +vn 0.4711 -0.8552 0.2163 +vn 0.4321 -0.8848 0.1744 +vn 0.4760 -0.8675 -0.1445 +vn 0.5557 0.8206 -0.1334 +vn 0.7064 0.6658 -0.2401 +vn 0.6812 0.6925 -0.2374 +vn 0.3006 0.9243 -0.2354 +vn 0.5244 0.8477 -0.0806 +vn 0.3233 0.9456 -0.0357 +vn 0.5379 0.8340 -0.1233 +vn 0.1086 0.9882 -0.1082 +vn 0.2225 0.9741 -0.0403 +vn 0.1839 0.9593 0.2143 +vn -0.3768 -0.9208 -0.1006 +vn -0.4110 -0.9079 -0.0824 +vn -0.5026 -0.8603 -0.0859 +vn 0.7815 0.2523 0.5706 +vn 0.8031 0.2513 0.5402 +vn 0.3992 0.8851 0.2393 +vn 0.2613 0.5164 -0.8155 +vn -0.0280 0.9974 -0.0669 +vn -0.0526 0.9981 0.0330 +vn -0.0709 0.9963 0.0484 +vn -0.3347 -0.6836 -0.6486 +vn -0.3020 -0.7448 -0.5950 +vn -0.2197 0.9650 -0.1429 +vn -0.1838 0.9772 -0.1060 +vn -0.1582 0.7765 0.6100 +vn -0.3301 0.9434 -0.0312 +vn -0.3804 0.9247 -0.0181 +vn -0.9315 0.3436 0.1191 +vn -0.7592 0.6486 0.0546 +vn -0.8436 0.5316 0.0753 +vn 0.4559 0.7128 0.5329 +vn 0.3440 0.5747 0.7425 +vn 0.4483 0.6210 0.6430 +vn 0.2696 0.9597 -0.0790 +vn -0.9115 -0.3294 0.2461 +vn -0.7027 -0.6541 0.2800 +vn -0.9168 -0.3112 0.2503 +vn -0.9787 0.1140 0.1707 +vn -0.9765 0.1243 0.1759 +vn -0.9606 0.1866 0.2062 +vn -0.8585 0.3774 0.3472 +vn -0.2971 0.6539 -0.6958 +vn -0.1568 0.2711 -0.9497 +vn -0.8671 0.4908 0.0850 +vn -0.1497 -0.9083 0.3905 +vn -0.1719 -0.9704 0.1697 +vn -0.2071 -0.9468 0.2465 +vn 0.5139 0.7728 0.3725 +vn -0.6405 0.1347 0.7560 +vn -0.3442 0.1979 0.9178 +vn -0.3759 0.2064 0.9034 +vn 0.2032 0.9568 0.2080 +vn 0.4953 0.7745 0.3934 +vn 0.0421 0.2453 0.9685 +vn 0.0908 0.1562 0.9835 +vn 0.0482 0.0967 0.9941 +vn 0.4820 -0.5858 -0.6515 +vn 0.4150 -0.5728 -0.7069 +vn -0.8751 0.0365 0.4827 +vn -0.8821 0.0895 0.4625 +vn 0.0776 -0.0055 0.9970 +vn 0.0075 0.9991 -0.0416 +vn 0.0281 0.9962 -0.0830 +vn 0.3692 -0.9294 -0.0032 +vn 0.1134 -0.9228 -0.3683 +vn -0.9506 -0.0153 0.3102 +vn 0.7041 0.3939 0.5908 +vn 0.0073 -0.0762 -0.9971 +vn 0.4894 0.1073 -0.8655 +vn -0.1858 0.0001 0.9826 +vn -0.1857 0.0010 0.9826 +vn 0.1278 0.3473 0.9290 +vn 0.0762 0.3401 0.9373 +vn 0.3579 0.1041 0.9279 +vn -0.3204 -0.9473 0.0006 +vn -0.1988 -0.9727 -0.1194 +vn 0.7062 -0.6919 0.1504 +vn 0.7055 -0.7043 0.0781 +vn 0.7078 -0.6899 0.1519 +vn 0.1187 0.9447 -0.3057 +vn 0.7057 -0.1818 0.6848 +vn 0.7655 -0.0952 0.6364 +vn 0.6965 -0.1661 0.6980 +vn 0.0754 0.8676 -0.4916 +vn 0.0796 0.8732 -0.4807 +vn 0.7600 -0.3613 -0.5402 +vn 0.6865 -0.4621 -0.5614 +vn 0.6120 -0.2890 -0.7361 +vn 0.3640 0.6091 -0.7046 +vn 0.6296 0.4586 -0.6272 +vn 0.6560 0.3490 -0.6692 +vn 0.0160 -0.9999 -0.0002 +vn -0.9853 -0.1519 0.0783 +vn -0.9513 -0.2984 0.0772 +vn -0.7269 -0.0940 -0.6802 +vn 0.2887 -0.5910 -0.7533 +vn 0.2787 -0.7518 -0.5975 +vn 0.1253 -0.6649 -0.7364 +vn 0.0176 -0.9674 -0.2527 +vn -0.4720 0.5367 0.6994 +vn -0.0620 0.2799 -0.9580 +vn 0.0057 0.3894 -0.9211 +vn -0.7507 0.5316 -0.3922 +vn -0.4737 0.8583 0.1972 +vn -0.3252 -0.0022 0.9457 +vn -0.3609 -0.0060 0.9326 +vn -0.0873 -0.0014 0.9962 +vn -0.4858 0.4328 -0.7594 +vn -0.4637 0.5235 -0.7148 +vn 0.6207 0.7071 0.3388 +vn 0.5430 0.7736 0.3268 +vn -0.0476 0.4544 0.8895 +vn -0.5801 0.5805 0.5713 +vn 0.4878 0.1549 -0.8591 +vn 0.7546 0.0544 0.6539 +vn 0.9226 0.0033 -0.3857 +vn 0.0704 -0.9227 -0.3792 +vn -0.9432 0.1235 0.3083 +vn -0.9402 0.1223 0.3180 +vn 0.7213 0.6264 -0.2955 +vn 0.4140 0.8442 0.3403 +vn 0.7100 -0.6690 -0.2197 +vn 0.7044 -0.6392 -0.3086 +vn 0.7070 -0.6877 -0.1648 +vn 0.1730 -0.6084 0.7745 +vn 0.2549 -0.6113 0.7492 +vn 0.4931 -0.2613 0.8298 +vn -0.6755 -0.7351 0.0579 +vn 0.6623 0.3363 -0.6695 +vn 0.8297 0.1708 -0.5314 +vn 0.7253 0.0250 -0.6879 +vn 0.3853 -0.0022 0.9228 +vn 0.7161 -0.0058 0.6979 +vn 0.0080 0.3374 -0.9413 +vn 0.0616 0.4643 -0.8835 +vn 0.6643 -0.6712 -0.3288 +vn -0.4534 -0.8911 0.0190 +vn 0.8143 0.4409 -0.3776 +vn -0.4851 -0.7592 0.4339 +vn 0.6850 -0.3053 -0.6615 +vn 0.5504 -0.3397 -0.7627 +vn -0.6797 0.0164 0.7333 +vn 0.3877 -0.8757 -0.2879 +vn 0.6316 -0.2195 0.7436 +vn 0.7482 -0.1679 0.6419 +vn 0.7968 -0.1370 0.5885 +vn -0.9246 -0.1903 -0.3301 +vn -0.4501 -0.7885 -0.4192 +vn 0.0556 -0.8972 0.4381 +vn -0.0305 -0.9720 0.2331 +vn 0.1878 -0.9700 0.1541 +vn 0.1277 -0.0029 -0.9918 +vn 0.1560 -0.7800 0.6061 +vn 0.4286 -0.6617 0.6152 +vn -0.1398 0.6467 0.7498 +vn -0.2837 0.7664 0.5763 +vn -0.4070 0.6105 0.6795 +vn -0.9313 -0.0009 -0.3643 +vn -0.9313 -0.0008 -0.3643 +vn -0.9508 0.0098 0.3098 +vn -0.9063 0.0034 0.4225 +vn -0.0708 -0.9567 0.2823 +vn -0.6456 0.6099 0.4595 +vn -0.7345 0.6319 0.2473 +vn -0.7852 0.5777 0.2230 +vn -0.9616 -0.0631 -0.2673 +vn -0.9128 -0.0455 -0.4059 +vn -0.7195 0.0001 0.6945 +vn -0.7195 0.0001 0.6944 +vn -0.6657 0.0000 0.7462 +vn 0.7093 0.2954 0.6401 +vn 0.7947 0.4565 0.4001 +vn -0.2802 0.5058 0.8158 +vn -0.9059 0.3166 0.2813 +vn 0.3947 0.5788 -0.7136 +vn 0.4071 0.5181 -0.7522 +vn 0.2472 0.5756 -0.7794 +vn 0.1933 0.0111 0.9811 +vn -0.3033 -0.1177 0.9456 +vn -0.8412 0.4685 -0.2699 +vn -0.2414 -0.0002 0.9704 +vn -0.2459 -0.0018 0.9693 +vn -0.2501 0.0004 0.9682 +vn 0.2811 0.1176 0.9524 +vn -0.4757 0.8463 0.2395 +vn -0.2248 0.9591 0.1722 +vn -0.6878 -0.1223 0.7155 +vn -0.6819 -0.3014 0.6665 +vn -0.9267 0.0124 0.3756 +vn 0.2326 0.0035 0.9726 +vn 0.1557 0.0056 0.9878 +vn 0.0346 -0.9982 -0.0488 +vn -0.9914 0.1288 -0.0244 +vn -0.2283 -0.9258 0.3014 +vn 0.9434 -0.0197 0.3310 +vn 0.2071 -0.0037 -0.9783 +vn 0.4042 0.8308 0.3827 +vn 0.6165 -0.4869 -0.6188 +vn -0.2373 0.0024 0.9714 +vn -0.2611 0.0028 0.9653 +vn -0.2379 0.0035 0.9713 +vn -0.1643 -0.9016 -0.4002 +vn -0.0934 -0.8748 -0.4753 +vn -0.6821 -0.0115 0.7312 +vn -0.7303 0.0064 0.6831 +vn -0.6574 -0.0405 0.7524 +vn -0.9959 0.0822 0.0379 +vn -0.1135 -0.9227 0.3684 +vn -0.1670 -0.2721 -0.9477 +vn 0.0479 0.5938 0.8032 +vn 0.2762 0.5773 0.7684 +vn 0.4315 -0.2314 0.8719 +vn 0.6343 -0.1649 0.7553 +vn 0.3967 -0.2371 0.8868 +vn 0.1935 0.3461 0.9180 +vn 0.2231 0.6101 0.7603 +vn 0.5851 -0.1103 0.8034 +vn 0.0537 -0.2603 0.9640 +vn 0.3061 0.0148 0.9519 +vn 0.0017 0.0064 1.0000 +vn 0.0136 -0.1509 0.9885 +vn -0.0028 -0.0049 1.0000 +vn 0.1543 -0.0873 0.9842 +vn 0.0117 -0.0221 0.9997 +vn 0.0378 0.0570 0.9977 +vn 0.1556 0.0429 0.9869 +vn -0.4987 -0.8401 -0.2132 +vn -0.5107 -0.7633 -0.3955 +vn 0.1179 -0.0969 0.9883 +vn -0.3610 0.0061 0.9325 +vn 0.1702 -0.0224 0.9851 +vn 0.1443 0.0354 0.9889 +vn 0.1669 -0.0704 0.9835 +vn 0.0976 0.0466 0.9941 +vn 0.1017 -0.1292 0.9864 +vn 0.0688 -0.0663 0.9954 +vn 0.5402 0.0037 -0.8415 +vn -0.0262 0.1649 0.9860 +vn -0.1156 0.0097 -0.9933 +vn 0.4215 -0.0109 0.9068 +vn 0.1613 -0.6272 0.7620 +vn 0.1960 -0.0495 -0.9793 +vn 0.0543 0.0051 -0.9985 +vn 0.2385 -0.0221 -0.9709 +vn 0.9849 0.0305 0.1703 +vn 0.9165 0.0725 0.3934 +vn 0.5184 -0.2313 -0.8233 +vn -0.2860 0.1607 0.9447 +vn -0.4007 -0.0133 0.9161 +vn -0.3568 0.0077 0.9341 +vn -0.3983 -0.0943 -0.9124 +vn -0.3039 -0.0840 -0.9490 +vn 0.0903 0.7568 -0.6474 +vn 0.3297 0.7957 -0.5082 +vn 0.0959 0.7131 -0.6944 +vn -0.0213 0.8409 -0.5408 +vn -0.6745 0.0382 0.7372 +vn -0.7773 -0.0116 0.6290 +vn -0.6070 0.0011 0.7947 +vn -0.6650 0.0003 0.7469 +vn -0.6732 -0.1366 0.7267 +vn -0.7638 -0.1479 0.6283 +vn -0.5076 0.0049 0.8616 +vn -0.5191 0.0068 0.8547 +vn -0.4183 -0.0005 0.9083 +vn -0.0410 0.7274 -0.6850 +vn 0.0285 -0.0300 0.9991 +vn 0.4322 0.8884 0.1549 +vn 0.1957 0.9352 0.2952 +vn 0.4875 0.8508 0.1963 +vn 0.3979 -0.7757 -0.4899 +vn -0.0387 0.5718 -0.8195 +vn 0.1124 0.0019 -0.9937 +vn 0.8466 0.0072 -0.5323 +vn 0.0480 0.2874 -0.9566 +vn 0.1106 0.1758 -0.9782 +vn -0.4253 0.9036 -0.0509 +vn -0.2747 0.9561 -0.1023 +vn -0.6082 0.7916 0.0590 +vn -0.5650 0.8234 -0.0531 +vn 0.0946 -0.9794 0.1782 +vn -0.7073 0.2687 0.6539 +vn -0.9345 -0.0181 0.3555 +vn -0.9791 0.1689 -0.1133 +vn -0.9857 0.1619 -0.0468 +vn -0.9418 0.3201 -0.1027 +vn 0.0885 -0.0746 -0.9933 +vn 0.0043 -0.2893 -0.9572 +vn -0.0121 0.0830 -0.9965 +vn -0.0184 0.0665 -0.9976 +vn -0.0152 0.1358 -0.9906 +vn -0.0014 0.1106 -0.9939 +vn -0.5544 -0.8082 0.1987 +vn -0.7978 0.1396 0.5865 +vn 0.8014 -0.5855 0.1222 +vn 0.6061 0.0099 -0.7953 +vn -0.9827 -0.1844 -0.0170 +vn -0.8916 -0.2166 0.3976 +vn 0.6733 0.0582 -0.7371 +vn 0.7994 0.5217 -0.2979 +vn 0.1006 0.0638 0.9929 +vn 0.1298 0.2335 0.9636 +vn 0.6003 -0.2103 -0.7716 +vn 0.5071 -0.0720 -0.8589 +vn 0.2523 0.2914 -0.9227 +vn -0.6876 -0.6731 0.2724 +vn 0.4847 0.4373 -0.7575 +vn 0.2414 0.4261 0.8719 +vn 0.2367 0.3778 0.8951 +vn -0.7978 -0.2162 0.5628 +vn 0.1062 -0.9492 -0.2963 +vn 0.1938 -0.8952 -0.4012 +vn 0.3269 0.3643 -0.8720 +vn 0.3238 0.3312 -0.8863 +vn -0.7138 -0.1086 -0.6919 +vn -0.6428 -0.3261 -0.6931 +vn 0.0617 -0.7853 -0.6160 +vn 0.2071 0.0037 -0.9783 +vn -0.0082 0.9999 -0.0098 +vn 0.7128 0.7011 -0.0212 +vn -0.7308 -0.5317 -0.4281 +vn 0.4009 -0.0283 -0.9157 +vn 0.3767 -0.0304 -0.9258 +vn 0.9846 0.0370 0.1706 +vn 0.9159 0.0789 0.3936 +vn 0.7332 0.6791 0.0364 +vn 0.7428 0.6544 -0.1411 +vn 0.6082 0.7899 0.0781 +vn 0.0836 0.9791 -0.1856 +vn 0.4282 0.2922 0.8551 +vn 0.0042 0.3703 0.9289 +vn 0.3933 0.2988 0.8695 +vn -0.9373 0.0151 0.3482 +vn -0.5899 -0.7330 0.3388 +vn 0.0531 0.7825 -0.6204 +vn -0.5233 -0.7146 0.4642 +vn 0.7816 0.0251 0.6233 +vn 0.7567 -0.3659 0.5418 +vn -0.6467 0.5468 -0.5317 +vn 0.4743 -0.7032 0.5296 +vn 0.1710 -0.7598 0.6272 +vn 0.0025 0.2877 -0.9577 +vn 0.4760 0.8675 -0.1445 +vn -0.3562 -0.3081 -0.8821 +vn -0.6002 -0.2318 -0.7655 +vn -0.6288 -0.2108 -0.7484 +vn -0.0641 0.9421 -0.3292 +vn 0.1609 0.9640 -0.2116 +vn -0.1838 0.5481 0.8160 +vn 0.2518 0.6867 0.6820 +vn 0.0270 -0.8404 0.5413 +vn 0.2377 -0.0020 -0.9713 +vn 0.1959 0.7076 0.6789 +vn -0.5560 -0.7491 -0.3601 +vn -0.2131 0.0149 0.9769 +vn -0.7221 -0.2919 0.6272 +vn 0.1985 0.2394 0.9504 +vn 0.1837 0.1865 0.9651 +vn -0.6156 -0.7864 0.0514 +vn 0.0641 0.7436 -0.6655 +vn -0.3255 -0.0016 0.9455 +vn -0.3613 -0.0051 0.9324 +vn 0.9162 -0.3017 0.2636 +vn 0.1380 -0.9275 0.3474 +vn -0.9382 0.0267 0.3451 +vn -0.8194 0.1498 0.5533 +vn -0.6694 0.1587 0.7257 +vn -0.7006 -0.6663 -0.2554 +vn 0.5368 0.0664 0.8411 +vn 0.5515 -0.3271 0.7674 +vn 0.7260 -0.5077 0.4638 +vn -0.9370 0.2141 0.2759 +vn -0.9917 0.1285 0.0094 +vn 0.9973 -0.0098 -0.0732 +vn -0.7844 -0.4977 -0.3701 +vn 0.7154 -0.0190 -0.6985 +vn 0.6868 0.0226 -0.7265 +vn 0.6908 -0.0128 -0.7230 +vn 0.0482 0.3393 0.9394 +vn 0.2813 0.5373 0.7951 +vn 0.9325 0.0149 0.3610 +vn 0.9508 0.0098 -0.3098 +vn 0.7968 0.1370 0.5885 +vn 0.9434 0.0197 0.3310 +vn 0.7482 0.1679 0.6419 +vn -0.3462 -0.0087 -0.9381 +vn -0.3101 -0.0118 -0.9506 +vn -0.5952 -0.0125 -0.8035 +vn -0.0096 0.9999 -0.0062 +vn 0.6134 -0.7897 -0.0079 +vn 0.4931 -0.3742 -0.7854 +vn -0.9045 -0.1333 0.4052 +vn -0.8976 -0.1271 0.4222 +vn 0.5916 0.3093 -0.7445 +vn -0.4540 0.5471 0.7033 +vn -0.2878 0.2747 -0.9174 +vn -0.3759 0.3172 -0.8707 +vn -0.6219 0.7827 0.0258 +vn 0.2340 -0.0788 0.9690 +vn 0.2407 -0.0213 0.9704 +vn -0.9857 0.0715 -0.1528 +vn 0.7243 0.0249 0.6890 +vn 0.6933 -0.1939 -0.6940 +vn 0.7053 -0.0839 -0.7039 +vn 0.2068 -0.0078 -0.9784 +vn 0.2067 -0.0078 -0.9784 +vn -0.4438 -0.0071 -0.8961 +vn -0.4952 0.2312 -0.8375 +vn -0.8429 0.1743 -0.5090 +vn -0.6535 0.0885 -0.7518 +vn -0.6399 -0.7008 -0.3151 +vn -0.7639 0.2836 0.5796 +vn 0.7101 -0.6930 -0.1247 +vn 0.1423 -0.0077 -0.9898 +vn 0.2531 0.0880 -0.9634 +vn 0.2254 0.0127 -0.9742 +vn 0.3879 0.0214 -0.9214 +vn -0.3268 -0.0010 0.9451 +vn -0.3629 0.0002 0.9318 +vn 0.5328 0.0384 -0.8454 +vn -0.1435 -0.3385 -0.9300 +vn 0.6597 0.1086 -0.7436 +vn 0.5849 0.1049 -0.8043 +vn -0.5940 -0.2396 -0.7680 +vn 0.4852 -0.0859 -0.8702 +vn -0.4150 -0.7280 0.5457 +vn -0.4254 -0.7049 0.5676 +vn 0.9754 0.1128 0.1895 +vn -0.1798 0.5079 -0.8424 +vn -0.4433 0.5147 -0.7339 +vn 0.3963 -0.0887 -0.9138 +vn 0.4442 -0.1303 -0.8864 +vn 0.4840 0.3694 -0.7933 +vn 0.4824 0.3910 -0.7839 +vn 0.4689 -0.2826 -0.8368 +vn 0.5817 -0.1034 -0.8068 +vn 0.5621 0.4101 -0.7182 +vn 0.5593 0.4268 -0.7107 +vn -0.0763 -0.6334 -0.7701 +vn 0.2494 -0.5522 -0.7955 +vn 0.4722 -0.0314 -0.8809 +vn 0.4885 -0.0906 -0.8679 +vn -0.9861 -0.1655 -0.0130 +vn -0.9928 -0.0804 -0.0889 +vn 0.5680 -0.7331 -0.3741 +vn 0.6052 -0.6997 -0.3798 +vn 0.7134 -0.6991 -0.0478 +vn -0.6502 0.7322 -0.2028 +vn -0.7052 0.7074 0.0464 +vn -0.4427 0.8963 0.0251 +vn 0.7084 0.2370 0.6648 +vn -0.1016 0.0000 -0.9948 +vn -0.0930 -0.0002 -0.9957 +vn -0.2260 0.0002 -0.9741 +vn -0.2016 0.0102 -0.9794 +vn -0.2761 0.0062 -0.9611 +vn 0.0516 -0.3786 -0.9241 +vn 0.0171 -0.3994 -0.9166 +vn -0.4499 0.0048 -0.8931 +vn -0.4609 -0.0789 -0.8840 +vn 0.7127 0.5555 -0.4284 +vn 0.7053 0.4977 -0.5048 +vn 0.7115 0.4525 -0.5376 +vn -0.5884 -0.0029 -0.8085 +vn -0.7230 -0.0131 -0.6907 +vn -0.7768 -0.0149 -0.6296 +vn -0.0052 1.0000 0.0031 +vn -0.0076 1.0000 -0.0014 +vn -0.8303 -0.0282 -0.5566 +vn 0.3220 0.0178 -0.9466 +vn -0.1265 0.3496 -0.9283 +vn 0.0758 0.3773 -0.9230 +vn 0.3890 0.3781 -0.8401 +vn -0.9748 -0.0729 -0.2108 +vn -0.9790 -0.1704 -0.1121 +vn -0.9854 -0.0792 -0.1506 +vn 0.3375 0.3906 -0.8565 +vn 0.1028 0.9529 -0.2855 +vn 0.5472 -0.1115 0.8296 +vn -0.7504 -0.5490 0.3681 +vn 0.9313 0.0009 0.3643 +vn 0.3367 -0.1742 -0.9254 +vn 0.9800 -0.1626 -0.1146 +vn 0.9907 -0.0765 0.1127 +vn -0.9927 -0.0865 0.0839 +vn -0.9959 -0.0822 0.0379 +vn -0.0342 -0.3462 -0.9375 +vn -0.6612 -0.2892 0.6923 +vn -0.4375 -0.3686 0.8202 +vn -0.5923 -0.3179 0.7404 +vn -0.7325 -0.5824 0.3525 +vn -0.6794 -0.7202 0.1404 +vn 0.7130 -0.4031 0.5737 +vn 0.7089 -0.4501 0.5430 +vn 0.2863 0.8187 0.4978 +vn 0.0874 0.9430 0.3212 +vn -0.0877 -0.0023 0.9961 +vn 0.2323 0.0006 0.9726 +vn 0.1553 0.0032 0.9879 +vn -0.0719 -0.3900 0.9180 +vn 0.7984 0.3425 -0.4953 +vn -0.0345 -0.2641 -0.9639 +vn -0.1628 -0.2406 -0.9569 +vn 0.0237 -0.2078 -0.9779 +vn 0.1408 -0.8469 0.5127 +vn -0.8021 0.5934 -0.0671 +vn -0.7206 0.6833 -0.1176 +vn 0.3501 -0.6266 0.6963 +vn 0.3658 -0.5517 0.7496 +vn 0.4099 0.1726 -0.8957 +vn 0.0296 0.6371 0.7702 +vn -0.0417 0.0636 0.9971 +vn -0.0367 0.0528 0.9979 +vn -0.0026 -0.0203 0.9998 +vn 0.5596 -0.4230 -0.7127 +vn 0.5592 -0.4272 -0.7105 +vn -0.2635 0.0001 0.9646 +vn 0.4513 0.7000 0.5534 +vn 0.5720 0.6332 0.5214 +vn -0.2802 0.8290 0.4840 +vn 0.2007 -0.3937 0.8971 +vn 0.5680 0.7331 -0.3741 +vn 0.6052 0.6997 -0.3798 +vn 0.8494 0.0539 -0.5250 +vn 0.8068 0.0693 -0.5867 +vn 0.1130 0.9566 0.2684 +vn 0.1130 0.9567 0.2684 +vn 0.2698 -0.0475 0.9618 +vn -0.2376 -0.0003 0.9714 +vn -0.2497 -0.0009 0.9683 +vn -0.2780 -0.0021 0.9606 +vn -0.6161 0.7049 0.3514 +vn -0.5826 0.6727 0.4561 +vn 0.1880 0.7448 -0.6403 +vn 0.7149 0.1955 -0.6714 +vn 0.7085 0.0870 -0.7003 +vn 0.7070 -0.3147 -0.6333 +vn 0.7137 -0.2130 -0.6673 +vn 0.7095 -0.2361 -0.6640 +vn 0.9304 0.0313 0.3651 +vn 0.9305 0.0314 0.3651 +vn -0.9915 0.1277 -0.0259 +vn -0.9775 0.0625 0.2014 +vn 0.2274 -0.0619 -0.9718 +vn -0.2456 -0.9321 -0.2661 +vn -0.5876 0.6104 -0.5311 +vn -0.7446 0.6606 -0.0960 +vn -0.3635 0.9073 -0.2115 +vn -0.2508 0.8929 -0.3739 +vn -0.6871 0.6461 0.3324 +vn -0.3631 -0.8555 0.3691 +vn -0.3479 0.0049 0.9375 +vn -0.5315 -0.7847 -0.3190 +vn 0.1345 0.9758 0.1726 +vn 0.7630 0.6052 0.2273 +vn 0.4526 -0.7805 -0.4312 +vn 0.3115 0.8821 -0.3533 +vn 0.7121 -0.5709 -0.4086 +vn 0.7182 -0.6469 -0.2564 +vn -0.6855 -0.4255 0.5907 +vn 0.0787 -0.5139 -0.8542 +vn -0.4075 -0.4992 -0.7647 +vn -0.2800 -0.0128 -0.9599 +vn 0.0155 -0.8514 0.5243 +vn -0.2071 0.0037 0.9783 +vn -0.2287 0.9543 -0.1926 +vn 0.2545 -0.9319 0.2586 +vn -0.5280 -0.8486 -0.0320 +vn -0.6501 -0.7583 -0.0488 +vn -0.6852 0.3414 0.6434 +vn -0.4222 0.3804 0.8229 +vn -0.4909 0.3775 0.7852 +vn 0.1187 0.9447 -0.3058 +vn 0.7093 -0.2954 0.6401 +vn 0.6737 0.0456 -0.7376 +vn 0.9343 -0.0080 -0.3564 +vn -0.9942 0.0712 -0.0810 +vn 0.0949 -0.0259 0.9952 +vn -0.5192 0.8161 -0.2537 +vn -0.2536 0.9103 -0.3271 +vn -0.5246 0.8083 -0.2673 +vn -0.1132 -0.0017 0.9936 +vn -0.1132 -0.0019 0.9936 +vn 0.1910 0.1696 0.9668 +vn 0.6116 0.0139 -0.7911 +vn -0.5949 0.7494 0.2907 +vn -0.3631 0.8555 0.3691 +vn -0.5299 0.8024 0.2745 +vn 0.7111 -0.6998 -0.0682 +vn -0.9747 0.0522 -0.2172 +vn 0.0886 0.4462 0.8906 +vn 0.2331 -0.1824 0.9552 +vn 0.0264 -0.7525 -0.6581 +vn 0.2714 0.4803 0.8341 +vn 0.0340 0.0758 0.9965 +vn 0.0098 -1.0000 -0.0017 +vn 0.9836 0.1766 0.0361 +vn -0.6954 -0.7181 0.0258 +vn 0.6924 -0.5396 -0.4790 +vn 0.6983 -0.5666 -0.4373 +vn 0.7111 -0.5912 -0.3806 +vn 0.6902 -0.1476 -0.7084 +vn -0.9292 0.0516 0.3661 +vn -0.0120 0.4925 -0.8702 +vn -0.2202 -0.0865 0.9716 +vn 0.0242 0.9476 -0.3185 +vn 0.0115 0.9049 -0.4254 +vn 0.0372 0.9189 -0.3928 +vn -0.0157 -0.1355 -0.9907 +vn -0.0019 -0.1124 -0.9937 +vn 0.0391 -0.1975 -0.9795 +vn 0.1009 0.8905 0.4436 +vn 0.1454 0.8439 0.5165 +vn -0.2731 0.3974 0.8760 +vn 0.0082 0.3786 -0.9255 +vn 0.0134 0.2985 -0.9543 +vn 0.3161 0.7227 -0.6147 +vn 0.2687 -0.9306 -0.2484 +vn 0.0180 0.8630 -0.5049 +vn 0.1643 0.9571 0.2389 +vn 0.1134 0.9227 -0.3683 +vn -0.4213 0.6638 -0.6180 +vn -0.9313 0.0009 -0.3643 +vn -0.9313 0.0008 -0.3643 +vn 0.4080 0.6112 0.6782 +vn 0.0513 0.9355 -0.3495 +vn 0.6971 0.7135 -0.0702 +vn 0.6744 0.7282 -0.1221 +vn 0.7118 0.1587 -0.6842 +vn 0.6946 0.2700 -0.6668 +vn -0.2608 0.9510 0.1661 +vn -0.0098 -1.0000 0.0017 +vn 0.8077 -0.0657 -0.5860 +vn 0.6928 0.6912 -0.2057 +vn 0.7427 0.5943 -0.3087 +vn -0.1738 -0.5999 -0.7810 +vn -0.0397 -0.5757 -0.8167 +vn 0.0890 -0.9243 -0.3711 +vn 0.0190 -0.1967 -0.9803 +vn -0.0187 -0.0669 -0.9976 +vn -0.7247 0.0323 0.6883 +vn -0.7711 0.0053 0.6367 +vn -0.4028 0.7002 0.5894 +vn -0.1337 0.9272 0.3499 +vn 0.7133 0.6990 0.0510 +vn -0.4330 -0.2278 -0.8721 +vn -0.5013 -0.2055 -0.8405 +vn -0.9305 0.0313 -0.3651 +vn -0.6065 -0.0073 0.7951 +vn -0.7670 -0.3170 0.5579 +vn 0.6252 -0.1061 0.7732 +vn 0.8032 -0.0055 0.5957 +vn -0.9936 -0.1067 -0.0381 +vn -0.9800 -0.1626 0.1145 +vn -0.1673 0.2845 -0.9440 +vn -0.1674 0.2845 -0.9440 +vn 0.6116 0.0012 -0.7912 +vn 0.3724 0.0182 -0.9279 +vn 0.4643 -0.6795 0.5681 +vn 0.9165 -0.0725 0.3934 +vn 0.3677 0.4975 0.7856 +vn 0.8557 0.2713 -0.4407 +vn 0.0282 0.0092 -0.9996 +vn 0.0401 0.0025 -0.9992 +vn 0.0432 0.0835 -0.9956 +vn 0.5700 0.8216 -0.0074 +vn 0.3735 0.9142 -0.1572 +vn -0.3444 -0.3280 0.8796 +vn -0.6819 -0.3014 0.6664 +vn 0.1981 0.1079 0.9742 +vn 0.1999 0.1085 0.9738 +vn 0.1135 0.9227 -0.3684 +vn -0.0250 -0.3953 0.9182 +vn 0.1148 -0.3835 -0.9164 +vn 0.1279 -0.2523 -0.9592 +vn 0.7083 -0.0391 -0.7048 +vn 0.4221 0.0026 0.9065 +vn 0.2836 -0.0014 0.9589 +vn 0.2834 0.0115 0.9589 +vn 0.5338 0.4237 -0.7318 +vn -0.6781 0.7228 0.1330 +vn -0.0489 -0.7079 0.7046 +vn 0.7178 0.6947 -0.0470 +vn -0.3613 0.6942 0.6225 +vn 0.9507 -0.0048 -0.3102 +vn -0.7213 0.6888 -0.0723 +vn -0.7711 0.6350 -0.0465 +vn -0.5243 0.4016 0.7509 +vn 0.1187 -0.9447 -0.3058 +vn -0.1402 0.7937 -0.5919 +vn -0.1019 -0.7671 -0.6333 +vn -0.7052 0.6705 0.2302 +vn -0.6526 0.7490 0.1147 +vn -0.2848 0.7463 -0.6016 +vn -0.1184 0.6279 -0.7693 +vn -0.7577 0.0250 0.6522 +vn 0.0959 -0.7131 -0.6944 +vn 0.0513 0.6464 -0.7613 +vn -0.9729 -0.0565 -0.2244 +vn 0.7071 -0.6492 0.2802 +vn -0.1781 -0.2852 -0.9418 +vn -0.9065 -0.0114 0.4220 +vn -0.6541 0.6912 0.3072 +vn 0.7081 0.6407 -0.2967 +vn -0.1398 0.9854 0.0970 +vn 0.6073 -0.1754 0.7749 +vn -0.5126 -0.2498 0.8215 +vn -0.0971 0.8711 -0.4814 +vn 0.8181 -0.2855 -0.4992 +vn 0.9050 0.0594 0.4212 +vn -0.0160 0.9999 0.0002 +vn -0.6504 -0.7304 -0.2086 +vn 0.0470 -0.3288 -0.9432 +vn 0.1854 0.0202 -0.9825 +vn 0.0268 0.0025 -0.9996 +vn 0.0082 0.9999 0.0098 +vn -0.0789 0.6660 -0.7418 +vn -0.2152 -0.2722 0.9379 +vn -0.1321 -0.2920 0.9473 +vn -0.0368 0.0010 0.9993 +vn -0.4553 0.7925 0.4058 +vn -0.0048 -0.3018 -0.9534 +vn 0.6285 -0.7451 -0.2234 +vn -0.0270 -0.0026 0.9996 +vn -0.1574 0.5085 -0.8466 +vn -0.0675 0.8917 0.4475 +vn 0.0463 0.9976 -0.0523 +vn -0.6119 -0.2800 -0.7397 +vn -0.8302 0.0316 -0.5565 +vn -0.7232 0.0143 -0.6905 +vn 0.7292 -0.3699 0.5757 +vn 0.7536 0.0054 0.6573 +vn -0.1129 -0.8183 -0.5635 +vn -0.2548 0.0004 0.9670 +vn 0.8435 -0.0664 0.5329 +vn 0.9313 -0.0009 0.3644 +vn 0.9313 -0.0008 0.3644 +vn 0.7109 -0.5620 0.4228 +vn 0.7109 -0.4832 0.5110 +vn 0.7107 -0.5767 0.4029 +vn 0.3311 0.7893 -0.5171 +vn 0.1047 0.7581 -0.6436 +vn 1.0000 0.0003 0.0000 +vn -0.9305 0.0314 -0.3651 +vn -0.5544 0.8082 0.1987 +vn -0.8432 -0.0800 -0.5317 +vn -0.7060 -0.3895 -0.5916 +vn -0.8772 -0.1408 -0.4591 +vn 0.2374 0.0994 0.9663 +vn -0.2209 0.5395 0.8125 +vn 0.6167 -0.7327 0.2877 +vn 0.2531 -0.0005 -0.9674 +vn 0.1231 0.7045 -0.6989 +vn 0.0684 -0.9975 0.0158 +vn 0.0522 -0.9960 -0.0728 +vn 0.4966 -0.0467 -0.8667 +vn -0.1507 -0.9880 0.0340 +vn -0.0171 -0.9998 0.0047 +vn -0.0104 -0.9999 0.0019 +vn -0.0113 -0.6879 0.7257 +vn -0.9102 0.2266 0.3466 +vn -0.0078 -0.9824 0.1866 +vn 0.0363 -0.9713 0.2350 +vn -0.9637 -0.1925 0.1852 +vn 0.0222 -0.8017 -0.5973 +vn -0.4336 0.7491 0.5008 +vn -0.4652 0.7055 0.5346 +vn 0.7083 0.0390 -0.7048 +vn 0.7083 0.0391 -0.7048 +vn -0.4781 -0.8299 0.2875 +vn 0.1199 -0.1294 -0.9843 +vn 0.3026 -0.0019 -0.9531 +vn 0.3521 -0.0489 -0.9347 +vn 0.5119 0.8068 -0.2952 +vn -0.6681 -0.0109 0.7440 +vn 0.4224 0.0066 0.9064 +vn 0.7480 -0.5116 -0.4228 +vn -0.2734 -0.9475 -0.1661 +vn 0.9005 0.0117 0.4348 +vn -0.1921 0.6895 0.6983 +vn -0.0961 0.5533 0.8274 +vn -0.0461 0.6365 -0.7699 +vn -0.4346 -0.2116 0.8754 +vn -0.2280 0.5390 -0.8109 +vn -0.4079 0.2894 -0.8659 +vn -0.2946 0.2901 -0.9105 +vn -0.2067 0.0078 0.9784 +vn -0.5090 -0.8511 0.1285 +vn 0.4830 0.5685 -0.6659 +vn 0.5088 0.4350 -0.7429 +vn -0.1835 -0.9469 -0.2640 +vn 0.7741 0.5476 -0.3178 +vn 0.1749 0.7798 0.6012 +vn 0.0190 0.0313 0.9993 +vn -0.6819 0.3014 0.6664 +vn -0.4272 0.0065 -0.9041 +vn -0.1000 0.0018 -0.9950 +vn -0.2513 -0.0003 0.9679 +vn -0.2449 0.0000 0.9696 +vn 0.1929 -0.0002 0.9812 +vn 0.9846 -0.1653 -0.0575 +vn -0.3148 -0.8721 0.3747 +vn -0.7700 0.0064 -0.6380 +vn -0.3899 0.7123 -0.5836 +vn -0.5061 0.7671 -0.3942 +vn 0.0398 0.9948 0.0936 +vn 0.0670 0.9976 0.0165 +vn -0.9689 0.1385 0.2049 +vn -0.1886 -0.8079 0.5583 +vn 0.6685 0.0457 -0.7423 +vn -0.2352 0.0024 0.9719 +vn -0.2473 0.0027 0.9689 +vn -0.0000 -0.0059 1.0000 +vn -0.7508 0.5574 -0.3546 +vn -0.9561 0.1250 0.2651 +vn -0.0400 0.0002 0.9992 +vn -0.0634 0.8691 0.4906 +vn 0.0148 0.2036 -0.9789 +vn -0.0035 -1.0000 0.0008 +vn -0.0067 -1.0000 -0.0013 +vn 0.7286 -0.6742 0.1208 +vn 0.4082 0.6734 -0.6163 +vn 0.2805 -0.0231 0.9596 +vn 0.3933 -0.2988 0.8695 +vn 0.0042 -0.3703 0.9289 +vn -0.7694 0.1590 0.6187 +vn 0.1453 -0.1734 0.9741 +vn -0.8062 0.0838 -0.5857 +vn -0.8572 0.2905 -0.4253 +vn -0.7269 0.0940 -0.6802 +vn 0.1010 -0.2582 -0.9608 +vn -0.7523 0.5418 0.3749 +vn 0.2256 0.2004 -0.9534 +vn -0.3477 -0.8716 -0.3456 +vn -0.2079 -0.1795 0.9615 +vn -0.2270 -0.0103 0.9738 +vn -0.2263 -0.0190 0.9739 +vn 0.3317 -0.3715 -0.8672 +vn -0.8014 0.2238 -0.5547 +vn -0.9362 0.1280 -0.3273 +vn -0.7702 0.0122 -0.6377 +vn 0.0069 0.9982 0.0598 +vn -0.9553 -0.1192 -0.2706 +vn -0.9766 0.1217 -0.1772 +vn -0.1953 -0.3786 -0.9047 +vn 0.7104 -0.6360 0.3015 +vn 0.4645 0.7565 0.4604 +vn 0.0430 0.7503 -0.6597 +vn 0.1412 0.3851 -0.9120 +vn 0.1151 0.4196 -0.9004 +vn 0.5293 0.4850 0.6961 +vn -0.0077 -0.9998 0.0184 +vn -0.3258 0.5365 -0.7784 +vn -0.9112 -0.2507 0.3268 +vn -0.2067 0.0035 0.9784 +vn -0.2067 0.0036 0.9784 +vn 0.0298 -0.1482 0.9885 +vn 0.7051 -0.7048 0.0780 +vn -0.0844 0.8262 -0.5570 +vn 0.0169 0.6846 0.7287 +vn -0.4924 0.7493 0.4427 +vn -0.0095 0.0000 1.0000 +vn -0.2326 -0.0035 -0.9726 +vn -0.7852 -0.5777 0.2230 +vn -0.8987 0.1210 0.4215 +vn -0.3088 -0.7614 0.5701 +vn -0.6803 0.7179 -0.1478 +vn 0.1657 -0.3246 -0.9312 +vn 0.0926 0.9717 -0.2173 +vn 0.0981 0.9626 -0.2524 +vn 0.9599 -0.2786 0.0302 +vn -0.8000 -0.1534 -0.5800 +vn -0.4141 0.7348 0.5372 +vn -0.0301 0.9187 -0.3938 +vn 0.9542 -0.1860 -0.2342 +vn 0.8488 -0.0019 -0.5287 +vn -0.1674 -0.2845 -0.9440 +vn 0.7085 0.6362 0.3055 +vn 0.8003 -0.0946 0.5921 +vn 0.9315 -0.2369 0.2761 +vn -0.7000 -0.7137 0.0244 +vn -0.8382 -0.2907 0.4613 +vn -0.8583 -0.2778 0.4314 +vn 0.9712 -0.1746 -0.1622 +vn 0.0076 -0.9995 -0.0318 +vn 0.4282 -0.2923 0.8551 +vn 0.0299 0.9926 -0.1179 +vn 0.0288 0.9939 -0.1065 +vn 0.0798 -0.9960 -0.0414 +vn 0.1304 -0.9748 -0.1810 +vn 0.1067 -0.9793 -0.1719 +vn 0.1989 -0.9186 0.3416 +vn 0.1137 -0.0172 0.9934 +vn -0.3942 -0.7090 -0.5848 +vn -0.9508 -0.0098 0.3098 +vn -0.9507 -0.0098 0.3098 +vn -0.7844 0.4977 -0.3701 +vn -0.1119 -0.9028 0.4152 +vn -0.1144 -0.6784 -0.7257 +vn -0.9149 0.3727 -0.1552 +vn 0.2084 0.5415 0.8145 +vn 0.2084 0.5416 0.8144 +vn 0.0049 -0.9982 0.0606 +vn 0.1487 0.9037 0.4015 +vn -0.7584 -0.6202 -0.2003 +vn -0.4245 0.7120 0.5594 +vn -0.2068 -0.0078 0.9784 +vn -0.2067 -0.0078 0.9784 +vn 0.2988 0.7315 0.6129 +vn 0.4482 0.7581 0.4738 +vn 0.1536 -0.0109 0.9881 +vn 0.7105 0.0114 0.7036 +vn -0.2833 0.0014 -0.9590 +vn -0.2315 0.0004 -0.9728 +vn -0.8203 -0.0121 0.5719 +vn -0.8766 -0.0355 0.4798 +vn -0.8944 0.0054 0.4472 +vn -0.2138 -0.4004 0.8911 +vn -0.1962 -0.5189 0.8320 +vn -0.0611 -0.3818 0.9222 +vn 0.2567 0.0078 0.9665 +vn 0.1755 0.8270 0.5342 +vn 0.1381 -0.7873 -0.6009 +vn 0.1996 0.2408 0.9498 +vn -0.0468 0.7519 0.6576 +vn -0.3084 0.8201 0.4820 +vn -0.0474 0.7079 0.7047 +vn -0.2018 -0.8603 -0.4682 +vn -0.9994 -0.0079 0.0335 +vn 0.0753 -0.4447 -0.8925 +vn -0.0227 0.8031 0.5954 +vn -0.5237 0.8221 0.2233 +vn 0.0859 -0.0133 0.9962 +vn -0.9062 -0.0147 0.4225 +vn 0.0268 0.9431 -0.3313 +vn 0.2971 -0.1667 -0.9402 +vn 0.1297 -0.9654 0.2261 +vn 0.9313 0.0008 0.3644 +vn -0.9072 -0.4072 -0.1054 +vn -0.8654 -0.4897 -0.1057 +vn 0.4221 0.3804 -0.8229 +vn -0.0503 0.3079 -0.9501 +vn 0.3582 -0.0047 -0.9336 +vn -0.7446 0.0102 -0.6674 +vn 0.9601 -0.0348 -0.2775 +vn -0.7439 -0.0118 -0.6682 +vn 0.9313 -0.0009 0.3643 +vn 0.7439 -0.0126 0.6682 +vn 0.7439 -0.0126 0.6681 +vn 0.3893 0.0383 -0.9203 +vn 0.7207 0.0121 -0.6932 +vn -0.0519 0.9976 0.0455 +vn -0.0843 0.9894 0.1181 +vn 0.0728 -0.9930 -0.0925 +vn -0.4416 -0.4201 0.7928 +vn -0.6165 -0.3539 0.7034 +vn -0.9275 0.2312 0.2938 +vn -0.8580 0.2765 0.4329 +vn -0.9305 -0.0313 -0.3651 +vn -0.9305 -0.0314 -0.3651 +vn 0.9213 -0.2019 0.3322 +vn -0.1635 -0.3484 -0.9230 +vn 0.5799 -0.2828 0.7640 +vn 0.4068 -0.2910 0.8659 +vn 0.1097 -0.9666 -0.2316 +vn 0.0789 -0.3605 0.9294 +vn -0.7948 -0.0692 -0.6028 +vn 0.1658 -0.5151 0.8410 +vn -0.1583 0.3224 0.9333 +vn 0.0656 0.2790 0.9580 +vn -0.9594 0.1124 0.2586 +vn -0.0814 0.9860 -0.1455 +vn -0.0120 0.9999 0.0065 +vn -0.0537 -0.7086 0.7036 +vn 0.1379 0.9747 -0.1761 +vn 0.1088 0.9803 -0.1650 +vn 0.8114 -0.1086 0.5744 +vn 0.0298 -0.0470 0.9984 +vn 0.0989 0.0675 0.9928 +vn 0.0748 -0.6385 -0.7660 +vn 0.2233 0.0200 0.9746 +vn 0.5428 0.8138 0.2076 +vn -0.6915 -0.7210 -0.0456 +vn 0.0320 0.9023 0.4299 +vn -0.0085 -1.0000 -0.0010 +vn 0.1184 0.9844 0.1302 +vn 0.0887 0.9903 0.1071 +vn 0.0603 0.9945 0.0861 +vn 0.9159 -0.0758 0.3942 +vn 0.2413 0.7897 0.5641 +vn 0.1918 0.1744 0.9658 +vn 0.0481 -0.3021 0.9521 +vn -0.9638 0.1004 0.2469 +vn -0.3116 -0.1419 -0.9396 +vn 0.0369 0.7998 -0.5991 +vn -0.0100 0.9986 0.0521 +vn -0.9065 0.0114 0.4220 +vn 0.2686 0.0258 0.9629 +vn -0.7639 -0.2836 0.5796 +vn 0.8034 0.0111 0.5953 +vn 0.6827 0.0954 -0.7245 +vn -0.6068 0.0016 0.7949 +vn 0.4596 -0.8772 -0.1389 +vn -0.2451 -0.9629 0.1131 +vn -0.2722 -0.9106 0.3109 +vn 0.6316 0.2195 0.7436 +vn -0.7730 -0.5348 0.3412 +vn -0.6384 -0.5286 0.5595 +vn 0.9305 -0.0314 0.3651 +vn 0.9305 -0.0313 0.3651 +vn 0.6285 0.7451 -0.2234 +vn 0.5470 0.7876 -0.2839 +vn 0.1385 -0.2827 0.9492 +vn 0.2311 -0.8405 -0.4901 +vn 0.0972 -0.9409 -0.3244 +vn -0.7670 0.3170 0.5579 +vn -0.7670 0.3171 0.5579 +vn 0.0203 0.3543 -0.9349 +vn 0.0200 -0.3046 -0.9523 +vn -0.0326 0.9559 -0.2920 +vn 0.4223 -0.0570 -0.9047 +vn 0.0052 0.0201 0.9998 +vn 0.3045 0.6983 0.6478 +vn 0.6045 -0.2309 0.7624 +vn 0.9304 0.0314 0.3651 +vn -0.0055 0.0012 1.0000 +vn -0.9411 -0.1222 0.3151 +vn 0.2410 0.0006 -0.9705 +vn 0.2365 -0.0011 -0.9716 +vn 0.2945 0.2981 -0.9079 +vn 0.5118 0.7028 0.4941 +vn -0.1939 0.9444 0.2655 +vn -0.8954 0.1135 0.4305 +vn -0.8902 0.1079 0.4426 +vn 0.1673 0.2845 0.9440 +vn 0.9304 -0.0314 0.3651 +vn -0.6601 -0.7390 -0.1348 +vn 0.0760 0.6857 0.7239 +vn -0.0014 -0.0143 -0.9999 +vn -0.0118 -0.1230 -0.9923 +vn 0.0010 -0.0073 -1.0000 +vn 0.3275 0.9447 0.0173 +vn -0.6542 -0.7517 -0.0830 +vn 0.5896 -0.7304 0.3447 +vn 0.1999 0.1086 0.9738 +vn -0.0092 -0.9995 0.0286 +vn 0.1885 0.1464 0.9711 +vn -0.4034 0.0160 -0.9149 +vn -0.6193 0.0637 -0.7826 +vn 0.7060 0.7042 -0.0755 +vn -0.0010 -0.0049 -1.0000 +vn -0.0010 -0.0048 -1.0000 +vn 0.0240 -0.8140 0.5803 +vn 0.7439 0.0118 0.6682 +vn 0.5912 0.1170 -0.7980 +vn -0.0559 -0.5496 -0.8335 +vn -0.9993 0.0128 0.0355 +vn 0.7101 -0.6947 -0.1148 +vn 0.0804 -0.9497 0.3025 +vn -0.6824 0.7258 0.0866 +vn -0.7465 0.6650 0.0228 +vn -0.7487 0.6623 0.0294 +vn -0.7730 0.5348 0.3412 +vn 0.8824 -0.2685 0.3864 +vn 0.8034 0.0131 -0.5953 +vn 0.6801 -0.0333 -0.7324 +vn 0.1579 -0.0060 0.9874 +vn -0.2554 0.0001 0.9668 +vn -0.4163 -0.7158 -0.5606 +vn -0.5178 0.4141 0.7486 +vn -0.5610 0.8278 0.0033 +vn -0.2430 0.0012 0.9700 +vn -0.2385 -0.0006 0.9711 +vn 0.2473 0.0260 0.9686 +vn 0.6642 -0.0002 -0.7475 +vn 0.6062 -0.0011 -0.7953 +vn 0.6647 -0.0000 -0.7471 +vn 0.1702 0.2919 -0.9412 +vn 0.5647 0.1087 -0.8181 +vn -0.5115 0.4782 -0.7139 +vn 0.1598 0.9571 0.2417 +vn -0.2067 -0.0035 0.9784 +vn -0.2067 -0.0036 0.9784 +vn 0.2513 0.0920 -0.9635 +vn 0.2529 0.0918 -0.9631 +vn -0.0207 -0.0012 -0.9998 +vn -0.0206 -0.0015 -0.9998 +vn 0.2656 0.0747 0.9612 +vn -0.9654 -0.1539 -0.2107 +vn 0.1114 0.9605 -0.2551 +vn 0.0512 -0.9780 0.2022 +vn -0.5723 0.0235 0.8197 +vn 0.7186 -0.0001 -0.6954 +vn 0.1140 0.7266 0.6775 +vn 0.7117 0.0048 0.7025 +vn 0.0406 0.5458 0.8369 +vn 0.0730 -0.9456 0.3169 +vn 0.0801 0.9923 0.0945 +vn 0.0038 -0.0118 0.9999 +vn -0.7842 0.0125 0.6203 +vn -0.9972 0.0160 0.0736 +vn 0.0458 0.3263 0.9441 +vn -0.0534 -0.0015 0.9986 +vn -0.6898 0.0005 -0.7240 +vn -0.5621 0.0036 -0.8271 +vn 0.0868 0.9923 -0.0880 +vn -0.9507 -0.0048 0.3102 +vn 0.5165 0.6988 0.4949 +vn 0.2726 0.1101 0.9558 +vn 0.3994 -0.3200 -0.8591 +vn 0.7183 0.6925 0.0662 +vn -0.8161 0.3008 0.4934 +vn -0.2749 -0.0005 0.9615 +vn -0.2466 0.0016 0.9691 +vn 0.0824 -0.8978 -0.4326 +vn -0.1918 0.3235 -0.9266 +vn 0.0655 -0.9951 -0.0740 +vn 0.9506 0.0154 -0.3102 +vn -0.1034 -0.3407 0.9345 +vn 0.0828 -0.2967 0.9514 +vn 0.1673 -0.2845 0.9440 +vn 0.2635 -0.3031 -0.9158 +vn -0.4272 -0.0186 0.9040 +vn -0.4701 0.0043 0.8826 +vn -0.4398 -0.0120 0.8980 +vn 0.7639 -0.2837 -0.5796 +vn -0.0120 0.9999 -0.0012 +vn 0.0105 -0.0011 0.9999 +vn -0.9768 0.0884 0.1951 +vn 0.3885 -0.0104 -0.9214 +vn 0.3884 -0.0112 -0.9214 +vn 0.7230 -0.0280 0.6903 +vn 0.1893 0.0436 0.9809 +vn 0.9482 0.1849 0.2582 +vn -0.0368 0.0008 0.9993 +vn -0.0057 1.0000 0.0005 +vn -0.3064 0.0043 0.9519 +vn 0.0862 0.9910 0.1027 +vn -0.5638 -0.4107 0.7165 +vn -0.2407 -0.9641 -0.1118 +vn 0.9213 -0.2020 0.3321 +vn 0.5843 0.2817 0.7611 +vn -0.3478 0.0057 0.9376 +vn -0.7948 0.0693 -0.6029 +vn -0.1994 -0.7789 0.5946 +vn 0.1940 0.1731 0.9656 +vn 0.2744 0.1176 0.9544 +vn 0.9305 0.0314 0.3650 +vn 0.7064 -0.7047 -0.0660 +vn 0.2260 0.3733 0.8997 +vn 0.0387 -0.5025 0.8637 +vn -0.7828 -0.0807 0.6170 +vn -0.8899 -0.1132 0.4420 +vn 0.0699 -0.9943 0.0805 +vn 0.0009 0.0065 1.0000 +vn 0.0009 0.0048 1.0000 +vn -0.2552 0.0014 0.9669 +vn 0.6060 -0.0016 -0.7955 +vn -0.5786 0.5317 -0.6184 +vn 0.5262 0.0832 -0.8463 +vn -0.2411 -0.0005 0.9705 +vn -0.2442 -0.0031 0.9697 +vn 0.0721 0.9971 0.0260 +vn 0.0318 0.9970 0.0711 +vn 0.7075 0.7066 0.0087 +vn -0.7439 -0.0126 -0.6681 +vn 0.1635 0.3484 0.9230 +vn -0.9773 0.0124 -0.2115 +vn -0.1824 -0.7697 0.6117 +vn 0.0219 -0.8141 0.5803 +vn 0.3603 -0.1635 -0.9184 +vn -0.0094 0.0000 1.0000 +vn 0.1134 0.9228 -0.3683 +vn 0.1821 0.0003 -0.9833 +vn -0.3613 0.0051 0.9324 +vn 0.2684 0.3270 -0.9061 +vn -0.4643 -0.0037 0.8857 +vn -0.0124 -0.9999 -0.0005 +vn -0.7439 -0.0126 -0.6682 +vn -0.3893 -0.0383 0.9203 +vn -0.2528 0.0013 0.9675 +vn -0.1359 -0.3542 0.9252 +vn -0.6384 0.5286 0.5595 +vn -0.7505 0.5546 0.3594 +vn 0.0726 0.9957 0.0575 +vn 0.1409 0.7382 -0.6597 +vn 0.0013 -0.0051 -1.0000 +vn 0.7639 0.2837 -0.5796 +vn 0.7125 -0.0001 0.7017 +vn -0.1134 -0.9228 0.3683 +vn 0.2352 -0.0024 -0.9719 +vn 0.0009 0.0047 1.0000 +vn 0.9506 0.0153 -0.3102 +vn 0.2272 0.0864 0.9700 +vn -0.1076 -0.4021 0.9093 +vn -0.1386 0.2826 -0.9492 +vn -0.2366 0.0010 0.9716 +vn -0.1858 0.0000 0.9826 +vn -0.0129 0.0002 0.9999 +vn -0.1076 0.4021 0.9093 +vn 0.6906 0.6795 0.2476 +vn 0.0400 -0.0002 -0.9992 +vn -0.8943 -0.1190 0.4314 +vn -0.2597 0.0002 0.9657 +vn 0.0268 -0.9936 0.1100 +vn -0.0274 0.1499 -0.9883 +vn -0.2532 0.0005 0.9674 +vn -0.1852 -0.0202 0.9825 +vn -0.1821 -0.0003 0.9833 +vn -0.2640 0.0002 0.9645 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 3/3/3 4/4/4 5/5/5 +f 5/5/5 4/4/4 6/6/6 +f 5/5/5 6/6/6 7/7/7 +f 5/5/5 7/7/7 8/8/8 +f 8/8/8 7/7/7 9/9/9 +f 9/9/9 7/7/7 10/10/10 +f 9/9/9 10/10/10 11/11/11 +f 9/9/9 11/11/11 12/12/12 +f 12/12/12 11/11/11 13/13/13 +f 12/12/12 13/13/13 14/14/14 +f 14/14/14 13/13/13 15/15/15 +f 14/14/14 15/15/15 16/16/16 +f 16/16/16 15/15/15 17/17/17 +f 16/16/16 17/17/17 18/18/18 +f 18/18/18 17/17/17 19/19/19 +f 18/18/18 19/19/19 20/20/20 +f 20/20/20 19/19/19 21/21/21 +f 20/20/20 21/21/21 22/22/22 +f 22/22/22 21/21/21 23/23/23 +f 22/22/22 23/23/23 24/24/24 +f 24/24/24 23/23/23 25/25/25 +f 24/24/24 25/25/25 1/1/1 +f 1/1/1 25/25/25 2/2/2 +f 24/24/26 3/3/26 5/5/26 +f 5/5/26 22/22/26 24/24/26 +f 1/1/26 3/3/26 24/24/26 +f 8/8/26 22/22/26 5/5/26 +f 8/8/26 18/18/26 22/22/26 +f 18/18/26 20/20/26 22/22/26 +f 9/9/26 14/14/26 18/18/26 +f 12/12/26 14/14/26 9/9/26 +f 8/8/26 9/9/26 18/18/26 +f 16/16/26 18/18/26 14/14/26 +f 25/25/27 23/23/27 4/4/27 +f 2/2/27 25/25/27 4/4/27 +f 17/17/27 15/15/27 19/19/27 +f 23/23/27 21/21/27 4/4/27 +f 21/21/27 6/6/27 4/4/27 +f 7/7/27 6/6/27 21/21/27 +f 7/7/27 21/21/27 19/19/27 +f 19/19/27 10/10/27 7/7/27 +f 19/19/27 11/11/27 10/10/27 +f 15/15/27 11/11/27 19/19/27 +f 11/11/27 15/15/27 13/13/27 +f 26/26/28 27/27/29 28/28/30 +f 28/28/30 27/27/29 29/29/31 +f 30/30/32 31/31/33 32/32/34 +f 32/32/34 31/31/33 33/33/35 +f 32/32/34 33/33/35 34/34/36 +f 35/35/37 36/36/38 33/33/35 +f 33/33/35 36/36/38 34/34/36 +f 35/35/37 37/37/39 36/36/38 +f 37/37/39 35/35/37 38/38/40 +f 37/37/39 38/38/40 39/39/41 +f 40/40/42 41/41/43 38/38/40 +f 38/38/40 41/41/43 39/39/41 +f 41/41/43 40/40/42 42/42/44 +f 42/42/44 40/40/42 43/43/45 +f 43/43/45 40/40/42 44/44/46 +f 44/44/46 45/45/47 43/43/45 +f 46/46/48 47/47/49 45/45/47 +f 46/46/48 45/45/47 44/44/46 +f 47/47/49 46/46/48 48/48/50 +f 47/47/49 48/48/50 49/49/51 +f 48/48/50 50/50/52 49/49/51 +f 50/50/52 48/48/50 51/51/53 +f 50/50/52 51/51/53 52/52/54 +f 29/29/31 27/27/29 52/52/54 +f 29/29/31 52/52/54 51/51/53 +f 53/53/55 28/28/30 29/29/31 +f 53/53/55 54/54/56 28/28/30 +f 55/55/57 56/56/58 53/53/55 +f 53/53/55 56/56/58 54/54/56 +f 55/55/57 57/57/59 56/56/58 +f 58/58/60 59/59/61 57/57/59 +f 58/58/60 57/57/59 55/55/57 +f 60/60/62 59/59/61 58/58/60 +f 61/61/63 60/60/62 58/58/60 +f 62/62/64 63/63/65 61/61/63 +f 61/61/63 63/63/65 60/60/62 +f 63/63/65 62/62/64 64/64/66 +f 65/65/67 64/64/66 62/62/64 +f 65/65/67 66/66/68 64/64/66 +f 67/67/69 66/66/68 65/65/67 +f 67/67/69 68/68/70 66/66/68 +f 69/69/71 68/68/70 67/67/69 +f 69/69/71 67/67/69 70/70/72 +f 69/69/71 70/70/72 71/71/73 +f 71/71/73 70/70/72 31/31/33 +f 30/30/32 71/71/73 31/31/33 +f 71/71/73 30/30/32 72/72/74 +f 73/73/75 74/74/76 75/75/77 +f 76/76/78 77/77/79 78/78/80 +f 79/79/81 74/74/76 73/73/75 +f 78/78/80 80/80/82 76/76/78 +f 81/81/83 82/82/84 79/79/81 +f 81/81/83 79/79/81 73/73/75 +f 75/75/77 74/74/76 83/83/85 +f 82/82/84 81/81/83 76/76/78 +f 76/76/78 81/81/83 77/77/79 +f 80/80/82 78/78/80 84/84/86 +f 84/84/86 78/78/80 85/85/87 +f 84/84/86 86/86/88 75/75/89 +f 84/84/86 75/75/89 83/83/90 +f 86/86/88 84/84/86 85/85/87 +f 87/87/91 88/88/92 89/89/93 +f 88/88/92 90/90/94 89/89/93 +f 87/87/91 89/89/93 91/91/95 +f 92/92/96 93/93/97 94/94/98 +f 92/92/96 94/94/98 95/95/99 +f 94/94/98 96/96/100 95/95/99 +f 90/90/94 88/88/92 97/97/101 +f 98/98/102 99/99/103 100/100/101 +f 99/99/103 98/98/102 101/101/104 +f 101/101/104 98/98/102 102/102/105 +f 101/101/104 102/102/105 93/93/97 +f 101/101/104 93/93/97 92/92/96 +f 100/100/101 103/103/101 97/97/101 +f 97/97/101 103/103/101 104/104/101 +f 97/97/101 104/104/101 90/90/94 +f 99/99/103 105/105/101 100/100/101 +f 100/100/101 105/105/101 103/103/101 +f 106/106/106 107/107/107 95/95/108 +f 106/106/106 108/108/109 109/109/110 +f 95/95/108 108/108/109 106/106/106 +f 110/110/111 111/111/112 112/112/113 +f 110/110/111 112/112/113 113/113/114 +f 114/114/115 115/115/116 116/116/117 +f 117/117/118 72/72/74 30/30/32 +f 30/30/32 115/115/116 114/114/115 +f 117/117/118 30/30/32 114/114/115 +f 118/118/119 119/119/120 120/120/121 +f 121/121/122 27/27/29 26/26/28 +f 27/27/29 121/121/122 118/118/119 +f 120/120/121 27/27/29 118/118/119 +f 36/36/38 122/122/123 34/34/36 +f 34/34/36 122/122/123 32/32/34 +f 107/107/107 41/41/43 123/123/124 +f 110/110/111 113/113/114 45/45/47 +f 47/47/49 110/110/111 45/45/47 +f 106/106/106 109/109/110 37/37/39 +f 37/37/39 109/109/110 36/36/38 +f 42/42/44 43/43/45 124/124/125 +f 49/49/51 110/110/111 47/47/49 +f 113/113/114 124/124/125 45/45/47 +f 45/45/47 124/124/125 43/43/45 +f 41/41/43 42/42/44 123/123/124 +f 106/106/106 37/37/39 107/107/107 +f 124/124/125 123/123/124 42/42/44 +f 107/107/107 39/39/41 41/41/43 +f 39/39/41 107/107/107 37/37/39 +f 109/109/110 122/122/123 36/36/38 +f 116/116/126 96/96/127 114/114/128 +f 114/114/128 96/96/127 94/94/129 +f 114/114/130 94/94/131 117/117/132 +f 117/117/132 94/94/131 93/93/133 +f 117/117/134 93/93/135 72/72/136 +f 72/72/136 93/93/135 102/102/137 +f 87/87/138 125/125/139 126/126/140 +f 87/87/138 126/126/140 88/88/141 +f 88/88/141 126/126/140 127/127/142 +f 88/88/141 127/127/142 97/97/143 +f 97/97/143 127/127/142 128/128/144 +f 97/97/143 128/128/144 100/100/145 +f 100/100/145 128/128/144 129/129/146 +f 100/100/147 129/129/148 98/98/149 +f 98/98/149 129/129/148 130/130/150 +f 98/98/151 130/130/152 72/72/153 +f 98/98/151 72/72/153 102/102/154 +f 131/131/155 132/132/156 127/127/157 +f 131/131/155 127/127/157 126/126/158 +f 125/125/159 133/133/160 126/126/158 +f 126/126/158 133/133/160 131/131/155 +f 71/71/73 72/72/74 130/130/161 +f 71/71/73 130/130/161 134/134/162 +f 134/134/162 130/130/161 135/135/163 +f 129/129/164 135/135/163 130/130/161 +f 128/128/165 135/135/163 129/129/164 +f 127/127/157 136/136/166 128/128/165 +f 127/127/157 132/132/156 136/136/166 +f 128/128/165 136/136/166 135/135/163 +f 137/137/167 138/138/168 85/85/169 +f 138/138/168 86/86/88 85/85/169 +f 139/139/170 137/137/167 85/85/169 +f 140/140/171 86/86/88 138/138/168 +f 26/26/28 28/28/30 141/141/172 +f 141/141/172 28/28/30 142/142/173 +f 143/143/174 144/144/175 140/140/171 +f 140/140/171 144/144/175 86/86/88 +f 143/143/174 145/145/176 144/144/175 +f 141/141/172 142/142/173 145/145/176 +f 141/141/172 145/145/176 143/143/174 +f 146/146/177 119/119/178 147/147/179 +f 147/147/179 119/119/178 118/118/180 +f 147/147/179 118/118/180 148/148/181 +f 148/148/181 118/118/180 121/121/182 +f 148/148/181 121/121/182 149/149/183 +f 121/121/182 26/26/184 149/149/183 +f 149/149/185 26/26/186 150/150/187 +f 150/150/187 26/26/186 141/141/188 +f 150/150/187 141/141/188 151/151/189 +f 151/151/189 141/141/188 143/143/190 +f 151/151/189 143/143/190 152/152/191 +f 152/152/191 143/143/190 140/140/192 +f 152/152/193 140/140/194 153/153/195 +f 153/153/195 140/140/194 138/138/196 +f 153/153/197 138/138/198 154/154/199 +f 154/154/199 138/138/198 137/137/138 +f 154/154/199 137/137/138 155/155/139 +f 113/113/200 156/156/201 124/124/202 +f 156/156/201 123/123/203 124/124/202 +f 157/157/204 107/107/205 156/156/201 +f 156/156/201 107/107/205 123/123/203 +f 158/158/206 159/159/207 156/156/201 +f 156/156/201 159/159/207 157/157/204 +f 153/153/208 73/73/209 152/152/210 +f 160/160/211 112/112/212 147/147/213 +f 112/112/212 146/146/214 147/147/213 +f 160/160/211 147/147/213 148/148/215 +f 160/160/211 148/148/215 161/161/216 +f 73/73/209 153/153/208 81/81/217 +f 81/81/217 153/153/208 154/154/218 +f 149/149/219 162/162/220 161/161/216 +f 81/81/217 154/154/218 163/163/221 +f 163/163/221 154/154/218 155/155/222 +f 161/161/216 148/148/215 149/149/219 +f 149/149/219 150/150/210 162/162/220 +f 162/162/220 150/150/210 164/164/210 +f 164/164/210 150/150/210 151/151/210 +f 152/152/210 73/73/209 165/165/210 +f 165/165/210 166/166/210 152/152/210 +f 152/152/210 166/166/210 151/151/210 +f 151/151/210 166/166/210 164/164/210 +f 73/73/75 75/75/77 167/167/223 +f 167/167/223 165/165/224 73/73/75 +f 165/165/224 167/167/223 168/168/225 +f 169/169/226 166/166/227 165/165/224 +f 169/169/226 165/165/224 168/168/225 +f 170/170/228 166/166/227 169/169/226 +f 170/170/228 164/164/229 166/166/227 +f 171/171/230 164/164/229 170/170/228 +f 172/172/231 162/162/232 164/164/229 +f 172/172/231 164/164/229 171/171/230 +f 59/59/233 158/158/234 57/57/235 +f 99/99/236 173/173/237 174/174/238 +f 172/172/231 175/175/239 162/162/232 +f 101/101/240 159/159/241 176/176/242 +f 176/176/242 159/159/241 66/66/68 +f 99/99/236 176/176/242 173/173/237 +f 101/101/240 176/176/242 99/99/236 +f 57/57/235 161/161/243 175/175/239 +f 175/175/239 161/161/243 162/162/232 +f 59/59/233 63/63/244 66/66/68 +f 59/59/233 66/66/68 159/159/241 +f 59/59/233 159/159/241 158/158/234 +f 177/177/245 178/178/246 179/179/247 +f 179/179/247 178/178/246 180/180/248 +f 181/181/249 182/182/250 90/90/251 +f 181/181/249 183/183/252 182/182/250 +f 184/184/253 89/89/254 90/90/251 +f 90/90/251 182/182/250 184/184/253 +f 178/178/246 177/177/245 89/89/254 +f 178/178/246 89/89/254 184/184/253 +f 181/181/249 90/90/251 185/185/255 +f 104/104/256 185/185/255 90/90/251 +f 185/185/255 104/104/256 186/186/257 +f 103/103/258 186/186/257 104/104/256 +f 103/103/258 187/187/259 186/186/257 +f 187/187/259 103/103/258 188/188/260 +f 105/105/261 188/188/260 103/103/258 +f 188/188/260 105/105/261 189/189/262 +f 99/99/236 189/189/262 105/105/261 +f 189/189/262 99/99/236 174/174/238 +f 180/180/263 190/190/264 191/191/265 +f 180/180/263 191/191/265 192/192/266 +f 193/193/267 183/183/268 191/191/269 +f 191/191/269 183/183/268 192/192/270 +f 183/183/271 193/193/272 194/194/273 +f 183/183/271 194/194/273 182/182/274 +f 182/182/275 194/194/275 195/195/275 +f 182/182/276 195/195/276 184/184/276 +f 184/184/277 195/195/278 196/196/279 +f 184/184/277 196/196/279 178/178/280 +f 178/178/280 196/196/279 197/197/281 +f 190/190/282 180/180/283 197/197/284 +f 197/197/284 180/180/283 178/178/285 +f 198/198/286 84/84/287 199/199/288 +f 199/199/288 84/84/287 83/83/289 +f 84/84/290 198/198/291 80/80/292 +f 80/80/292 198/198/291 200/200/293 +f 200/200/294 76/76/294 80/80/294 +f 201/201/295 79/79/296 202/202/297 +f 202/202/297 79/79/296 82/82/298 +f 202/202/299 82/82/300 76/76/301 +f 202/202/299 76/76/301 200/200/302 +f 201/201/303 74/74/304 79/79/305 +f 199/199/306 74/74/304 201/201/303 +f 83/83/307 74/74/307 199/199/307 +f 193/193/308 190/190/309 194/194/308 +f 194/194/308 190/190/309 197/197/308 +f 194/194/308 197/197/308 195/195/308 +f 193/193/308 191/191/310 190/190/309 +f 125/125/311 203/203/312 133/133/313 +f 125/125/311 204/204/314 203/203/312 +f 125/125/311 91/91/315 204/204/314 +f 116/116/316 115/115/317 108/108/318 +f 169/169/319 144/144/175 170/170/320 +f 145/145/321 142/142/322 170/170/320 +f 170/170/320 142/142/322 171/171/323 +f 86/86/88 167/167/324 75/75/89 +f 168/168/325 167/167/324 144/144/175 +f 144/144/175 167/167/324 86/86/88 +f 169/169/319 168/168/325 144/144/175 +f 170/170/320 144/144/175 145/145/321 +f 172/172/326 171/171/323 142/142/322 +f 172/172/326 142/142/322 205/205/327 +f 205/205/327 142/142/322 28/28/328 +f 66/66/68 68/68/70 176/176/242 +f 68/68/70 69/69/71 176/176/242 +f 173/173/237 69/69/71 71/71/73 +f 205/205/327 28/28/328 175/175/239 +f 175/175/239 28/28/328 54/54/329 +f 176/176/242 69/69/71 173/173/237 +f 175/175/239 54/54/329 56/56/330 +f 63/63/244 64/64/331 66/66/68 +f 172/172/231 205/205/332 175/175/239 +f 175/175/239 56/56/330 57/57/235 +f 173/173/237 71/71/73 174/174/333 +f 161/161/243 57/57/235 158/158/234 +f 59/59/233 60/60/334 63/63/244 +f 71/71/73 134/134/162 174/174/333 +f 189/189/335 135/135/163 206/206/336 +f 189/189/335 206/206/336 188/188/337 +f 189/189/335 174/174/333 134/134/162 +f 134/134/162 135/135/163 189/189/335 +f 206/206/336 135/135/163 187/187/338 +f 206/206/336 187/187/339 188/188/337 +f 136/136/166 187/187/338 135/135/163 +f 187/187/338 136/136/166 186/186/340 +f 136/136/166 132/132/156 186/186/340 +f 186/186/340 132/132/156 185/185/341 +f 132/132/156 181/181/342 185/185/341 +f 183/183/343 181/181/342 192/192/344 +f 192/192/344 181/181/342 131/131/155 +f 192/192/344 131/131/155 180/180/248 +f 180/180/248 131/131/155 179/179/247 +f 132/132/156 131/131/155 181/181/342 +f 203/203/345 131/131/346 133/133/347 +f 131/131/346 203/203/345 179/179/348 +f 204/204/349 179/179/350 203/203/351 +f 179/179/350 204/204/349 177/177/352 +f 177/177/353 204/204/354 89/89/355 +f 89/89/355 204/204/354 91/91/356 +f 81/81/357 163/163/358 207/207/359 +f 81/81/357 207/207/359 77/77/360 +f 207/207/361 78/78/361 77/77/361 +f 139/139/362 78/78/363 207/207/364 +f 85/85/365 78/78/363 139/139/362 +f 112/112/212 208/208/366 113/113/200 +f 113/113/200 208/208/366 156/156/201 +f 112/112/212 160/160/211 208/208/366 +f 158/158/206 156/156/201 208/208/366 +f 158/158/206 208/208/366 161/161/216 +f 208/208/366 160/160/211 161/161/216 +f 95/95/99 209/209/367 92/92/96 +f 209/209/367 95/95/99 107/107/368 +f 209/209/367 107/107/368 157/157/369 +f 101/101/104 92/92/96 209/209/367 +f 101/101/104 209/209/367 159/159/370 +f 159/159/370 209/209/367 157/157/369 +f 29/29/31 210/210/371 53/53/55 +f 53/53/55 210/210/371 211/211/372 +f 53/53/55 211/211/372 55/55/57 +f 55/55/57 211/211/372 212/212/373 +f 55/55/57 212/212/373 58/58/60 +f 58/58/60 212/212/373 61/61/63 +f 61/61/63 212/212/373 213/213/374 +f 61/61/63 213/213/374 62/62/64 +f 62/62/64 213/213/374 214/214/375 +f 62/62/64 214/214/375 65/65/67 +f 65/65/67 214/214/375 67/67/69 +f 67/67/69 214/214/375 215/215/376 +f 67/67/69 215/215/376 70/70/72 +f 70/70/72 215/215/376 216/216/377 +f 70/70/72 216/216/377 31/31/33 +f 31/31/33 216/216/377 217/217/378 +f 31/31/33 217/217/378 33/33/35 +f 33/33/35 217/217/378 35/35/37 +f 35/35/37 217/217/378 218/218/379 +f 35/35/37 218/218/379 38/38/40 +f 38/38/40 218/218/379 219/219/380 +f 38/38/40 219/219/380 40/40/42 +f 40/40/42 219/219/380 220/220/381 +f 40/40/42 220/220/381 44/44/46 +f 44/44/46 220/220/381 221/221/382 +f 44/44/46 221/221/382 46/46/48 +f 46/46/48 221/221/382 222/222/383 +f 46/46/48 222/222/383 48/48/50 +f 48/48/50 222/222/383 51/51/53 +f 51/51/53 222/222/383 29/29/31 +f 29/29/31 222/222/383 210/210/371 +f 215/215/384 217/217/385 216/216/386 +f 217/217/385 215/215/384 218/218/387 +f 215/215/384 219/219/27 218/218/387 +f 214/214/388 213/213/389 215/215/384 +f 219/219/27 213/213/389 220/220/390 +f 220/220/390 213/213/389 212/212/390 +f 220/220/390 212/212/390 222/222/27 +f 221/221/390 220/220/390 222/222/27 +f 222/222/27 212/212/390 211/211/391 +f 211/211/391 210/210/392 222/222/27 +f 213/213/389 219/219/27 215/215/384 +f 195/195/308 197/197/308 196/196/393 +f 95/95/394 96/96/395 108/108/318 +f 125/125/311 87/87/396 91/91/315 +f 96/96/395 116/116/316 108/108/318 +f 112/112/397 111/111/398 223/223/399 +f 146/146/400 112/112/397 223/223/399 +f 223/223/399 120/120/401 146/146/400 +f 119/119/402 146/146/400 120/120/401 +f 155/155/403 207/207/404 163/163/404 +f 155/155/403 139/139/405 207/207/404 +f 202/202/406 200/200/309 201/201/308 +f 201/201/308 200/200/309 199/199/309 +f 155/155/403 137/137/407 139/139/405 +f 199/199/309 200/200/309 198/198/408 +f 120/120/121 223/223/409 52/52/54 +f 110/110/111 49/49/51 111/111/112 +f 49/49/51 52/52/54 111/111/112 +f 111/111/112 52/52/54 223/223/409 +f 52/52/54 27/27/29 120/120/121 +f 52/52/54 49/49/51 50/50/52 +f 109/109/110 108/108/109 122/122/123 +f 115/115/116 32/32/34 122/122/123 +f 115/115/116 122/122/123 108/108/109 +f 30/30/32 32/32/34 115/115/116 +f 224/224/410 225/225/411 226/226/412 +f 224/224/410 226/226/412 227/227/413 +f 227/227/413 226/226/412 228/228/414 +f 229/229/415 230/230/416 231/231/417 +f 231/231/417 230/230/416 232/232/418 +f 231/231/417 232/232/418 225/225/411 +f 231/231/417 225/225/411 224/224/410 +f 227/227/413 228/228/414 233/233/419 +f 233/233/419 228/228/414 234/234/420 +f 233/233/419 234/234/420 235/235/421 +f 236/236/422 237/237/423 238/238/424 +f 238/238/424 237/237/423 239/239/425 +f 238/238/424 239/239/425 240/240/426 +f 238/238/424 240/240/426 229/229/415 +f 229/229/415 240/240/426 230/230/416 +f 233/233/419 235/235/421 241/241/427 +f 233/233/419 241/241/427 242/242/428 +f 242/242/428 241/241/427 236/236/422 +f 236/236/422 241/241/427 237/237/423 +f 238/238/429 243/243/430 236/236/431 +f 236/236/431 243/243/430 244/244/432 +f 236/236/433 244/244/434 242/242/435 +f 242/242/435 244/244/434 245/245/436 +f 242/242/435 245/245/436 233/233/437 +f 233/233/437 245/245/436 246/246/438 +f 233/233/439 246/246/440 247/247/441 +f 233/233/439 247/247/441 227/227/442 +f 227/227/443 247/247/444 248/248/445 +f 227/227/443 248/248/445 224/224/446 +f 224/224/447 248/248/448 249/249/449 +f 224/224/447 249/249/449 231/231/450 +f 231/231/450 249/249/449 250/250/451 +f 231/231/450 250/250/451 229/229/452 +f 229/229/452 250/250/451 251/251/453 +f 229/229/452 251/251/453 238/238/429 +f 238/238/429 251/251/453 243/243/430 +f 244/244/454 252/252/455 245/245/456 +f 245/245/456 252/252/455 253/253/457 +f 245/245/456 253/253/457 246/246/458 +f 250/250/459 254/254/460 255/255/461 +f 250/250/459 255/255/461 251/251/462 +f 251/251/462 255/255/461 243/243/463 +f 248/248/464 256/256/465 257/257/466 +f 248/248/464 257/257/466 249/249/467 +f 249/249/467 257/257/466 250/250/459 +f 250/250/459 257/257/466 254/254/460 +f 246/246/458 253/253/457 258/258/468 +f 246/246/458 258/258/468 247/247/469 +f 247/247/469 258/258/468 259/259/470 +f 247/247/469 259/259/470 248/248/464 +f 248/248/464 259/259/470 256/256/465 +f 243/243/463 255/255/461 260/260/471 +f 243/243/463 260/260/471 261/261/472 +f 243/243/463 261/261/472 244/244/454 +f 244/244/454 261/261/472 252/252/455 +f 240/240/473 260/260/474 255/255/475 +f 240/240/473 255/255/475 230/230/476 +f 230/230/476 255/255/475 254/254/477 +f 254/254/477 262/262/478 230/230/476 +f 230/230/476 262/262/478 232/232/479 +f 232/232/479 262/262/478 225/225/480 +f 262/262/478 257/257/481 225/225/480 +f 225/225/480 257/257/481 263/263/482 +f 225/225/480 263/263/482 226/226/483 +f 263/263/482 256/256/484 226/226/483 +f 226/226/483 256/256/484 264/264/485 +f 264/264/485 256/256/484 259/259/486 +f 259/259/486 265/265/487 264/264/485 +f 264/264/485 265/265/487 228/228/488 +f 228/228/488 265/265/487 234/234/489 +f 265/265/487 258/258/490 234/234/489 +f 234/234/489 258/258/490 253/253/491 +f 234/234/489 253/253/491 235/235/492 +f 235/235/492 253/253/491 241/241/493 +f 253/253/491 252/252/494 241/241/493 +f 241/241/493 252/252/494 266/266/495 +f 266/266/495 252/252/494 267/267/496 +f 266/266/495 267/267/496 237/237/497 +f 267/267/496 268/268/498 237/237/497 +f 237/237/497 268/268/498 239/239/499 +f 239/239/499 268/268/498 260/260/474 +f 239/239/499 260/260/474 240/240/473 +f 256/256/500 263/263/500 257/257/500 +f 257/257/466 262/262/501 254/254/460 +f 260/260/471 268/268/502 261/261/472 +f 261/261/503 268/268/498 267/267/496 +f 261/261/504 267/267/504 252/252/504 +f 258/258/468 265/265/505 259/259/470 +f 266/266/506 237/237/423 241/241/427 +f 264/264/507 228/228/414 226/226/412 +f 269/269/101 270/270/101 271/271/101 +f 270/270/101 269/269/101 272/272/101 +f 273/273/101 274/274/101 275/275/101 +f 270/270/101 272/272/101 276/276/101 +f 270/270/101 276/276/101 277/277/101 +f 270/270/101 277/277/101 278/278/101 +f 278/278/101 277/277/101 273/273/101 +f 278/278/101 273/273/101 275/275/101 +f 279/279/508 280/280/509 281/281/510 +f 279/279/508 281/281/510 282/282/26 +f 282/282/26 283/283/511 279/279/508 +f 282/282/26 284/284/512 283/283/511 +f 284/284/512 282/282/26 285/285/26 +f 285/285/26 286/286/512 284/284/512 +f 285/285/26 287/287/510 286/286/512 +f 286/286/512 287/287/510 288/288/511 +f 287/287/510 289/289/513 290/290/514 +f 288/288/511 287/287/510 290/290/514 +f 291/291/515 292/292/516 293/293/517 +f 293/293/517 292/292/516 294/294/518 +f 294/294/518 295/295/519 293/293/517 +f 296/296/520 297/297/521 292/292/516 +f 292/292/516 297/297/521 298/298/522 +f 292/292/516 291/291/515 296/296/520 +f 298/298/522 299/299/523 300/300/524 +f 297/297/521 299/299/523 298/298/522 +f 294/294/518 300/300/524 295/295/519 +f 298/298/522 300/300/524 294/294/518 +f 301/301/525 302/302/526 303/303/527 +f 304/304/528 302/302/526 301/301/525 +f 301/301/525 303/303/527 305/305/529 +f 306/306/530 307/307/531 308/308/532 +f 307/307/533 309/309/534 308/308/535 +f 308/308/535 309/309/534 305/305/536 +f 305/305/537 309/309/538 301/301/539 +f 301/301/539 309/309/538 310/310/540 +f 301/301/539 310/310/540 311/311/541 +f 310/310/540 312/312/542 311/311/541 +f 311/311/541 312/312/542 304/304/543 +f 304/304/544 312/312/545 302/302/546 +f 302/302/546 312/312/545 313/313/547 +f 302/302/548 313/313/549 306/306/550 +f 313/313/549 314/314/551 306/306/550 +f 306/306/530 314/314/552 307/307/531 +f 314/314/553 315/315/554 316/316/555 +f 309/309/556 317/317/557 310/310/558 +f 310/310/558 318/318/559 312/312/560 +f 312/312/560 318/318/559 319/319/561 +f 310/310/558 317/317/557 318/318/559 +f 314/314/553 316/316/555 307/307/562 +f 313/313/563 315/315/554 314/314/553 +f 307/307/562 320/320/564 321/321/565 +f 307/307/562 321/321/565 309/309/556 +f 307/307/562 316/316/555 320/320/564 +f 312/312/560 322/322/566 313/313/563 +f 309/309/556 321/321/565 317/317/557 +f 313/313/563 322/322/566 315/315/554 +f 312/312/560 319/319/561 322/322/566 +f 293/293/567 316/316/568 291/291/569 +f 291/291/569 316/316/568 315/315/570 +f 291/291/569 315/315/570 296/296/571 +f 296/296/572 315/315/572 322/322/572 +f 296/296/573 322/322/573 297/297/573 +f 297/297/574 322/322/575 319/319/576 +f 297/297/574 319/319/576 299/299/577 +f 299/299/577 319/319/576 318/318/578 +f 299/299/579 318/318/580 300/300/581 +f 300/300/581 318/318/580 317/317/582 +f 300/300/583 317/317/584 321/321/585 +f 300/300/583 321/321/585 295/295/586 +f 295/295/586 321/321/585 320/320/587 +f 295/295/586 320/320/587 293/293/567 +f 293/293/567 320/320/587 316/316/568 +f 292/292/588 298/298/589 323/323/590 +f 323/323/590 298/298/589 324/324/591 +f 294/294/592 292/292/593 325/325/594 +f 325/325/594 292/292/593 323/323/595 +f 298/298/596 294/294/597 324/324/598 +f 324/324/598 294/294/597 325/325/599 +f 324/324/600 325/325/600 323/323/600 +f 306/306/601 303/303/527 302/302/526 +f 311/311/602 304/304/602 301/301/602 +f 308/308/603 305/305/529 303/303/527 +f 308/308/532 303/303/604 306/306/530 +f 326/326/605 327/327/606 328/328/607 +f 329/329/608 327/327/606 326/326/605 +f 330/330/609 331/331/610 332/332/611 +f 333/333/612 334/334/613 331/331/610 +f 333/333/612 331/331/610 330/330/609 +f 332/332/611 335/335/614 330/330/609 +f 328/328/607 334/334/613 326/326/605 +f 326/326/605 334/334/613 333/333/612 +f 329/329/608 326/326/605 336/336/615 +f 335/335/614 329/329/608 336/336/615 +f 330/330/609 335/335/614 336/336/615 +f 337/337/616 338/338/617 339/339/618 +f 340/340/619 338/338/617 337/337/616 +f 341/341/620 342/342/621 343/343/622 +f 341/341/620 343/343/622 344/344/623 +f 344/344/624 343/343/624 345/345/624 +f 344/344/625 345/345/626 346/346/627 +f 345/345/626 347/347/628 346/346/627 +f 346/346/629 347/347/630 339/339/631 +f 347/347/630 348/348/632 339/339/631 +f 339/339/633 348/348/634 349/349/635 +f 349/349/635 348/348/634 350/350/636 +f 349/349/637 350/350/638 351/351/639 +f 351/351/639 350/350/638 352/352/640 +f 351/351/641 352/352/642 341/341/643 +f 341/341/643 352/352/642 342/342/644 +f 352/352/645 353/353/646 354/354/647 +f 345/345/648 355/355/649 347/347/650 +f 347/347/650 356/356/651 348/348/652 +f 347/347/650 355/355/649 356/356/651 +f 352/352/645 354/354/647 342/342/653 +f 342/342/653 357/357/654 343/343/655 +f 342/342/653 354/354/647 357/357/654 +f 348/348/652 358/358/656 350/350/657 +f 350/350/657 358/358/656 359/359/658 +f 343/343/655 357/357/654 345/345/648 +f 345/345/648 357/357/654 355/355/649 +f 350/350/657 359/359/658 352/352/645 +f 352/352/645 359/359/658 353/353/646 +f 356/356/651 358/358/656 348/348/652 +f 327/327/659 354/354/660 328/328/661 +f 328/328/661 354/354/660 353/353/662 +f 328/328/663 353/353/664 334/334/665 +f 334/334/665 353/353/664 359/359/666 +f 334/334/667 359/359/668 331/331/669 +f 331/331/669 359/359/668 358/358/670 +f 331/331/671 358/358/672 332/332/673 +f 332/332/673 358/358/672 356/356/674 +f 332/332/675 356/356/676 335/335/677 +f 335/335/677 356/356/676 355/355/678 +f 335/335/679 355/355/680 357/357/681 +f 335/335/679 357/357/681 329/329/682 +f 329/329/683 357/357/684 327/327/685 +f 327/327/685 357/357/684 354/354/686 +f 333/333/687 330/330/688 360/360/689 +f 360/360/689 330/330/688 361/361/690 +f 326/326/691 333/333/692 362/362/693 +f 362/362/693 333/333/692 360/360/694 +f 336/336/695 326/326/696 363/363/697 +f 363/363/697 326/326/696 362/362/698 +f 330/330/699 336/336/700 361/361/701 +f 361/361/701 336/336/700 363/363/702 +f 363/363/703 362/362/703 361/361/703 +f 361/361/703 362/362/703 360/360/703 +f 341/341/704 340/340/705 351/351/706 +f 351/351/706 340/340/705 337/337/707 +f 351/351/708 337/337/708 349/349/708 +f 349/349/709 337/337/616 339/339/618 +f 346/346/710 339/339/710 338/338/710 +f 346/346/627 338/338/711 344/344/625 +f 344/344/712 338/338/617 340/340/619 +f 344/344/623 340/340/713 341/341/620 +f 364/364/714 365/365/715 366/366/716 +f 366/366/716 365/365/715 367/367/717 +f 365/365/718 368/368/719 367/367/720 +f 367/367/720 368/368/719 369/369/721 +f 368/368/722 370/370/723 369/369/724 +f 369/369/724 370/370/723 371/371/725 +f 366/366/726 371/371/727 364/364/728 +f 364/364/728 371/371/727 370/370/729 +f 369/369/730 371/371/730 367/367/730 +f 367/367/730 371/371/730 366/366/730 +f 364/364/731 370/370/731 368/368/731 +f 368/368/731 365/365/731 364/364/731 +f 372/372/732 373/373/733 374/374/734 +f 374/374/734 373/373/733 375/375/735 +f 373/373/736 376/376/737 375/375/738 +f 375/375/738 376/376/737 377/377/739 +f 376/376/740 378/378/741 377/377/742 +f 377/377/742 378/378/741 379/379/743 +f 374/374/744 379/379/745 372/372/746 +f 372/372/746 379/379/745 378/378/747 +f 377/377/748 379/379/748 375/375/748 +f 375/375/748 379/379/748 374/374/749 +f 372/372/750 378/378/750 376/376/750 +f 376/376/750 373/373/750 372/372/750 +f 380/380/751 381/381/752 382/382/753 +f 383/383/754 384/384/755 380/380/751 +f 381/381/752 380/380/751 384/384/755 +f 381/381/752 384/384/755 385/385/756 +f 385/385/756 384/384/755 386/386/757 +f 382/382/758 387/387/759 388/388/760 +f 383/383/754 389/389/761 390/390/762 +f 391/391/763 390/390/762 389/389/761 +f 392/392/764 391/391/763 393/393/765 +f 393/393/765 391/391/763 389/389/761 +f 394/394/766 392/392/764 393/393/765 +f 394/394/766 395/395/767 392/392/764 +f 396/396/768 397/397/769 394/394/766 +f 394/394/766 397/397/769 395/395/767 +f 398/398/770 399/399/771 396/396/768 +f 399/399/771 397/397/769 396/396/768 +f 398/398/770 400/400/772 399/399/771 +f 401/401/773 400/400/772 398/398/770 +f 402/402/774 403/403/775 401/401/773 +f 402/402/774 401/401/773 398/398/770 +f 404/404/776 405/405/777 406/406/778 +f 404/404/776 406/406/778 407/407/779 +f 408/408/780 409/409/781 402/402/774 +f 402/402/774 409/409/781 403/403/775 +f 409/409/781 408/408/780 405/405/777 +f 409/409/781 405/405/777 404/404/776 +f 410/410/782 411/411/783 412/412/784 +f 410/410/782 412/412/784 413/413/785 +f 407/407/779 412/412/784 414/414/786 +f 412/412/784 407/407/779 406/406/778 +f 406/406/778 413/413/785 412/412/784 +f 415/415/787 416/416/788 417/417/789 +f 407/407/779 414/414/786 415/415/787 +f 415/415/787 414/414/786 416/416/788 +f 418/418/790 419/419/791 420/420/792 +f 420/420/792 421/421/793 422/422/794 +f 420/420/792 423/423/795 421/421/793 +f 420/420/792 424/424/796 423/423/795 +f 424/424/796 425/425/797 426/426/798 +f 424/424/796 426/426/798 427/427/799 +f 424/424/796 428/428/800 423/423/795 +f 426/426/798 425/425/797 385/385/756 +f 426/426/798 385/385/756 386/386/757 +f 424/424/796 427/427/799 429/429/801 +f 424/424/796 429/429/801 428/428/800 +f 388/388/760 387/387/759 430/430/802 +f 430/430/802 387/387/759 431/431/803 +f 430/430/802 431/431/803 410/410/782 +f 410/410/782 431/431/803 411/411/783 +f 417/417/789 432/432/804 420/420/792 +f 433/433/805 424/424/796 420/420/792 +f 420/420/792 432/432/804 434/434/806 +f 420/420/792 434/434/806 433/433/805 +f 435/435/807 436/436/808 437/437/809 +f 438/438/810 439/439/811 440/440/812 +f 435/435/807 437/437/809 440/440/812 +f 435/435/807 440/440/812 439/439/811 +f 441/441/813 439/439/814 442/442/815 +f 441/441/813 442/442/815 443/443/816 +f 444/444/817 445/445/818 446/446/819 +f 446/446/819 445/445/818 447/447/820 +f 446/446/819 447/447/820 443/443/816 +f 443/443/816 447/447/820 441/441/813 +f 441/441/813 448/448/821 439/439/814 +f 449/449/822 450/450/823 451/451/824 +f 452/452/825 450/450/823 453/453/826 +f 454/454/827 452/452/825 453/453/826 +f 455/455/828 456/456/829 457/457/830 +f 457/457/830 456/456/829 435/435/831 +f 449/449/822 451/451/824 458/458/832 +f 458/458/832 451/451/824 459/459/833 +f 439/439/814 448/448/821 460/460/834 +f 439/439/814 460/460/834 435/435/831 +f 435/435/831 460/460/834 457/457/830 +f 455/455/828 459/459/833 461/461/835 +f 458/458/832 459/459/833 455/455/828 +f 453/453/826 450/450/823 449/449/822 +f 455/455/828 461/461/835 456/456/829 +f 462/462/836 463/463/837 464/464/838 +f 464/464/838 463/463/837 465/465/839 +f 464/464/838 465/465/839 466/466/840 +f 272/272/101 269/269/101 467/467/841 +f 467/467/841 269/269/101 468/468/842 +f 467/467/841 468/468/842 469/469/843 +f 270/270/101 466/466/101 470/470/101 +f 471/471/101 472/472/101 473/473/101 +f 464/464/101 466/466/101 270/270/101 +f 270/270/101 471/471/101 474/474/101 +f 270/270/101 474/474/101 462/462/101 +f 270/270/101 475/475/101 271/271/101 +f 270/270/101 462/462/101 464/464/101 +f 270/270/101 278/278/101 476/476/101 +f 472/472/101 471/471/101 270/270/101 +f 472/472/101 270/270/101 476/476/101 +f 477/477/844 473/473/845 478/478/846 +f 472/472/847 478/478/846 473/473/845 +f 478/478/846 472/472/847 479/479/848 +f 472/472/847 480/480/849 479/479/848 +f 476/476/850 480/480/849 472/472/847 +f 480/480/849 476/476/850 481/481/851 +f 481/481/851 476/476/850 278/278/852 +f 390/390/853 482/482/854 483/483/855 +f 483/483/855 482/482/854 484/484/856 +f 484/484/856 485/485/857 483/483/855 +f 486/486/858 487/487/859 488/488/860 +f 486/486/858 489/489/861 487/487/859 +f 490/490/862 491/491/863 492/492/864 +f 493/493/865 491/491/863 494/494/866 +f 494/494/866 491/491/863 490/490/862 +f 494/494/866 495/495/867 493/493/865 +f 496/496/868 495/495/867 494/494/866 +f 497/497/869 496/496/868 494/494/866 +f 498/498/870 497/497/870 499/499/870 +f 499/499/871 497/497/869 494/494/866 +f 499/499/871 500/500/872 498/498/873 +f 486/486/858 501/501/874 500/500/872 +f 486/486/858 500/500/872 499/499/871 +f 488/488/860 501/501/874 486/486/858 +f 502/502/875 503/503/876 504/504/877 +f 504/504/877 505/505/878 502/502/875 +f 506/506/879 505/505/878 504/504/877 +f 507/507/880 506/506/879 504/504/877 +f 507/507/880 508/508/881 506/506/879 +f 507/507/880 509/509/882 508/508/881 +f 510/510/883 511/511/884 507/507/880 +f 507/507/880 511/511/884 509/509/882 +f 512/512/885 511/511/884 510/510/883 +f 513/513/886 512/512/885 514/514/887 +f 514/514/887 512/512/885 510/510/883 +f 515/515/888 516/516/889 514/514/887 +f 515/515/888 517/517/890 516/516/889 +f 518/518/891 517/517/890 519/519/892 +f 519/519/892 517/517/890 515/515/888 +f 519/519/892 520/520/893 518/518/891 +f 521/521/894 520/520/893 519/519/892 +f 522/522/895 520/520/893 521/521/894 +f 523/523/896 524/524/897 521/521/894 +f 521/521/894 524/524/897 522/522/895 +f 523/523/896 525/525/898 524/524/897 +f 523/523/896 526/526/899 525/525/898 +f 526/526/899 523/523/896 527/527/900 +f 528/528/901 526/526/899 527/527/900 +f 529/529/902 528/528/901 530/530/903 +f 528/528/901 527/527/900 530/530/903 +f 531/531/904 529/529/902 530/530/903 +f 490/490/862 492/492/864 530/530/903 +f 530/530/903 492/492/864 531/531/904 +f 284/284/905 530/530/903 283/283/906 +f 283/283/906 530/530/903 527/527/900 +f 283/283/906 527/527/900 523/523/896 +f 283/283/906 523/523/896 279/279/907 +f 523/523/896 521/521/894 279/279/907 +f 279/279/908 521/521/894 280/280/909 +f 521/521/894 519/519/892 280/280/909 +f 519/519/892 515/515/888 280/280/909 +f 280/280/909 515/515/888 281/281/910 +f 281/281/911 515/515/888 514/514/887 +f 281/281/911 514/514/887 282/282/912 +f 514/514/887 510/510/883 282/282/912 +f 282/282/912 510/510/883 507/507/880 +f 282/282/912 507/507/880 285/285/913 +f 507/507/880 504/504/877 285/285/913 +f 285/285/913 504/504/877 287/287/914 +f 287/287/914 504/504/877 503/503/876 +f 287/287/914 503/503/876 289/289/915 +f 503/503/876 532/532/916 289/289/915 +f 289/289/915 532/532/916 290/290/917 +f 532/532/916 489/489/861 290/290/917 +f 489/489/861 486/486/858 290/290/917 +f 290/290/917 486/486/858 288/288/918 +f 288/288/918 486/486/858 499/499/871 +f 288/288/918 499/499/871 286/286/919 +f 499/499/871 494/494/866 286/286/919 +f 286/286/919 494/494/866 284/284/905 +f 494/494/866 490/490/862 284/284/905 +f 284/284/905 490/490/862 530/530/903 +f 277/277/920 276/276/921 533/533/922 +f 534/534/923 469/469/924 535/535/925 +f 469/469/924 534/534/923 536/536/926 +f 469/469/924 536/536/926 467/467/927 +f 467/467/927 536/536/926 537/537/928 +f 538/538/929 539/539/930 540/540/931 +f 541/541/101 542/542/932 543/543/101 +f 534/534/923 535/535/925 544/544/933 +f 534/534/923 544/544/933 545/545/934 +f 272/272/935 546/546/936 276/276/921 +f 546/546/936 272/272/935 547/547/937 +f 547/547/937 272/272/935 548/548/938 +f 548/548/938 272/272/935 467/467/927 +f 548/548/938 467/467/927 537/537/928 +f 436/436/808 435/435/807 549/549/939 +f 409/409/940 549/549/939 435/435/807 +f 409/409/940 435/435/807 456/456/941 +f 409/409/940 456/456/941 403/403/942 +f 403/403/942 456/456/941 550/550/943 +f 481/481/851 278/278/852 551/551/944 +f 551/551/944 278/278/852 552/552/945 +f 275/275/946 553/553/947 552/552/945 +f 275/275/946 552/552/945 278/278/852 +f 553/553/947 275/275/946 554/554/948 +f 554/554/948 275/275/946 274/274/949 +f 554/554/948 274/274/949 555/555/950 +f 274/274/949 556/556/951 555/555/950 +f 556/556/951 274/274/949 273/273/952 +f 556/556/951 273/273/952 557/557/953 +f 273/273/952 558/558/954 557/557/953 +f 277/277/920 558/558/954 273/273/952 +f 558/558/954 277/277/920 533/533/922 +f 540/540/955 559/559/956 543/543/957 +f 543/543/957 559/559/956 560/560/958 +f 543/543/957 560/560/958 271/271/959 +f 271/271/959 560/560/958 269/269/960 +f 409/409/940 561/561/961 549/549/939 +f 404/404/962 562/562/963 563/563/964 +f 409/409/940 564/564/965 561/561/961 +f 404/404/962 563/563/964 564/564/965 +f 404/404/962 564/564/965 409/409/940 +f 439/439/966 438/438/967 442/442/968 +f 438/438/967 565/565/969 442/442/968 +f 442/442/968 565/565/969 562/562/963 +f 442/442/968 562/562/963 404/404/962 +f 407/407/970 443/443/971 404/404/972 +f 542/542/932 538/538/929 540/540/931 +f 404/404/972 443/443/971 442/442/973 +f 566/566/974 567/567/975 568/568/976 +f 533/533/922 276/276/921 546/546/936 +f 468/468/977 535/535/978 469/469/979 +f 569/569/980 535/535/978 468/468/977 +f 569/569/980 468/468/977 269/269/960 +f 569/569/980 269/269/960 570/570/981 +f 570/570/981 269/269/960 560/560/958 +f 571/571/982 518/518/891 572/572/983 +f 573/573/984 401/401/985 403/403/942 +f 573/573/984 403/403/942 574/574/986 +f 513/513/886 514/514/887 516/516/889 +f 575/575/987 576/576/988 577/577/989 +f 575/575/987 577/577/989 578/578/990 +f 575/575/987 578/578/990 579/579/991 +f 580/580/992 581/581/993 582/582/994 +f 580/580/992 582/582/994 576/576/988 +f 576/576/988 582/582/994 577/577/989 +f 581/581/993 583/583/995 582/582/994 +f 577/577/989 582/582/994 584/584/996 +f 577/577/989 584/584/996 578/578/990 +f 578/578/990 584/584/996 585/585/997 +f 401/401/985 573/573/984 583/583/995 +f 401/401/985 583/583/995 400/400/772 +f 399/399/771 400/400/772 586/586/998 +f 399/399/771 586/586/998 587/587/999 +f 399/399/771 587/587/999 397/397/769 +f 518/518/891 571/571/982 588/588/1000 +f 518/518/891 588/588/1000 589/589/1001 +f 589/589/1001 588/588/1000 590/590/1002 +f 589/589/1001 590/590/1002 591/591/1003 +f 592/592/1004 593/593/1005 575/575/987 +f 592/592/1004 575/575/987 579/579/991 +f 594/594/1006 395/395/767 397/397/769 +f 595/595/1007 392/392/764 395/395/767 +f 596/596/1008 392/392/764 595/595/1007 +f 597/597/1009 392/392/764 596/596/1008 +f 392/392/764 597/597/1009 391/391/1010 +f 598/598/1011 524/524/897 599/599/1012 +f 599/599/1012 524/524/897 525/525/898 +f 599/599/1012 525/525/898 526/526/899 +f 599/599/1012 526/526/899 600/600/1013 +f 600/600/1013 526/526/899 528/528/901 +f 579/579/991 511/511/884 592/592/1004 +f 592/592/1004 511/511/884 512/512/885 +f 589/589/1001 516/516/889 517/517/890 +f 589/589/1001 517/517/890 518/518/891 +f 572/572/983 518/518/891 520/520/893 +f 572/572/983 520/520/893 522/522/895 +f 601/601/1014 600/600/1013 528/528/901 +f 592/592/1004 512/512/885 593/593/1005 +f 593/593/1005 512/512/885 513/513/886 +f 593/593/1005 513/513/886 591/591/1003 +f 591/591/1003 513/513/886 516/516/889 +f 591/591/1003 516/516/889 589/589/1001 +f 602/602/1015 522/522/895 524/524/897 +f 602/602/1015 524/524/897 598/598/1011 +f 571/571/982 572/572/983 603/603/1016 +f 603/603/1016 572/572/983 522/522/895 +f 603/603/1016 522/522/895 604/604/1017 +f 604/604/1017 522/522/895 602/602/1015 +f 602/602/1015 598/598/1011 605/605/1018 +f 605/605/1018 598/598/1011 599/599/1012 +f 605/605/1018 599/599/1012 601/601/1014 +f 601/601/1014 599/599/1012 600/600/1013 +f 606/606/1019 602/602/1015 605/605/1018 +f 575/575/987 593/593/1005 576/576/988 +f 576/576/988 593/593/1005 580/580/992 +f 580/580/992 593/593/1005 591/591/1003 +f 580/580/992 591/591/1003 590/590/1002 +f 604/604/1017 602/602/1015 606/606/1019 +f 607/607/1020 608/608/1021 601/601/1014 +f 601/601/1014 608/608/1021 605/605/1018 +f 571/571/982 609/609/1022 588/588/1000 +f 588/588/1000 610/610/1023 590/590/1002 +f 590/590/1002 610/610/1023 611/611/1024 +f 590/590/1002 611/611/1024 580/580/992 +f 605/605/1018 608/608/1021 612/612/1025 +f 605/605/1018 612/612/1025 606/606/1019 +f 606/606/1019 612/612/1025 613/613/1026 +f 606/606/1019 613/613/1026 604/604/1017 +f 604/604/1017 613/613/1026 614/614/1027 +f 604/604/1017 614/614/1027 603/603/1016 +f 603/603/1016 614/614/1027 571/571/982 +f 609/609/1022 610/610/1023 588/588/1000 +f 611/611/1024 581/581/993 580/580/992 +f 607/607/1020 615/615/1028 608/608/1021 +f 608/608/1021 615/615/1028 597/597/1009 +f 608/608/1021 597/597/1009 612/612/1025 +f 612/612/1025 597/597/1009 613/613/1026 +f 614/614/1027 594/594/1006 571/571/982 +f 571/571/982 594/594/1006 609/609/1022 +f 610/610/1023 586/586/998 611/611/1024 +f 611/611/1024 586/586/998 581/581/993 +f 584/584/996 582/582/994 573/573/984 +f 573/573/984 582/582/994 583/583/995 +f 587/587/999 586/586/998 610/610/1023 +f 587/587/999 610/610/1023 397/397/769 +f 397/397/769 610/610/1023 609/609/1022 +f 397/397/769 609/609/1022 594/594/1006 +f 595/595/1007 594/594/1006 614/614/1027 +f 595/595/1007 614/614/1027 596/596/1008 +f 596/596/1008 614/614/1027 613/613/1026 +f 596/596/1008 613/613/1026 597/597/1009 +f 391/391/1029 597/597/1009 615/615/1028 +f 574/574/986 585/585/997 584/584/996 +f 574/574/986 584/584/996 573/573/984 +f 583/583/995 581/581/993 400/400/772 +f 400/400/772 581/581/993 586/586/998 +f 395/395/767 594/594/1006 595/595/1007 +f 390/390/853 391/391/1029 615/615/1028 +f 616/616/1030 617/617/1031 618/618/1032 +f 617/617/1031 484/484/856 618/618/1032 +f 482/482/854 618/618/1032 484/484/856 +f 619/619/1033 618/618/1032 482/482/854 +f 619/619/1033 482/482/854 620/620/1034 +f 621/621/1035 618/618/1032 619/619/1033 +f 622/622/1036 619/619/1033 620/620/1034 +f 622/622/1036 620/620/1034 623/623/1037 +f 621/621/1035 619/619/1033 624/624/1038 +f 624/624/1038 619/619/1033 622/622/1036 +f 625/625/1039 621/621/1035 624/624/1038 +f 482/482/854 390/390/853 615/615/1028 +f 492/492/864 625/625/1039 624/624/1038 +f 492/492/864 624/624/1038 531/531/904 +f 531/531/904 624/624/1038 622/622/1036 +f 531/531/904 622/622/1036 529/529/902 +f 529/529/902 622/622/1036 623/623/1037 +f 529/529/902 623/623/1037 601/601/1014 +f 601/601/1014 528/528/901 529/529/902 +f 492/492/864 491/491/863 625/625/1039 +f 620/620/1034 482/482/854 615/615/1028 +f 620/620/1034 615/615/1028 607/607/1020 +f 623/623/1037 620/620/1034 607/607/1020 +f 623/623/1037 607/607/1020 601/601/1014 +f 574/574/986 403/403/942 550/550/943 +f 550/550/943 456/456/941 626/626/1040 +f 585/585/997 574/574/986 627/627/1041 +f 627/627/1041 574/574/986 550/550/943 +f 627/627/1041 550/550/943 628/628/1042 +f 628/628/1042 550/550/943 626/626/1040 +f 578/578/990 585/585/997 629/629/1043 +f 629/629/1043 585/585/997 627/627/1041 +f 629/629/1043 627/627/1041 630/630/1044 +f 630/630/1044 627/627/1041 628/628/1042 +f 630/630/1044 628/628/1042 631/631/1045 +f 631/631/1045 628/628/1042 632/632/1046 +f 633/633/1047 631/631/1045 632/632/1046 +f 505/505/878 506/506/879 508/508/1048 +f 579/579/991 509/509/882 511/511/884 +f 628/628/1042 626/626/1040 632/632/1046 +f 631/631/1045 633/633/1047 634/634/1049 +f 631/631/1045 634/634/1049 630/630/1044 +f 630/630/1044 634/634/1049 635/635/1050 +f 630/630/1044 635/635/1050 629/629/1043 +f 629/629/1043 635/635/1050 636/636/1051 +f 629/629/1043 636/636/1051 578/578/990 +f 578/578/990 636/636/1051 579/579/991 +f 633/633/1047 637/637/1052 634/634/1049 +f 637/637/1052 505/505/878 634/634/1049 +f 634/634/1049 505/505/878 508/508/881 +f 634/634/1049 508/508/881 635/635/1050 +f 635/635/1050 508/508/881 509/509/882 +f 635/635/1050 509/509/882 636/636/1051 +f 636/636/1051 509/509/882 579/579/991 +f 638/638/1053 639/639/1054 640/640/1055 +f 452/452/825 641/641/1056 642/642/1057 +f 452/452/825 642/642/1057 450/450/823 +f 643/643/1058 642/642/1057 644/644/1059 +f 645/645/1060 644/644/1059 646/646/1061 +f 646/646/1061 638/638/1053 647/647/1062 +f 647/647/1062 638/638/1053 648/648/1063 +f 644/644/1059 642/642/1057 641/641/1056 +f 644/644/1059 641/641/1056 646/646/1061 +f 648/648/1063 638/638/1053 640/640/1055 +f 648/648/1063 640/640/1055 616/616/1030 +f 616/616/1030 640/640/1055 617/617/1031 +f 451/451/824 450/450/823 649/649/1064 +f 451/451/824 649/649/1064 459/459/1065 +f 489/489/861 532/532/916 650/650/1066 +f 459/459/1065 649/649/1064 651/651/1067 +f 650/650/1066 532/532/916 503/503/876 +f 459/459/1065 651/651/1067 652/652/1068 +f 650/650/1066 503/503/876 653/653/1069 +f 653/653/1069 503/503/876 502/502/875 +f 461/461/1070 459/459/1065 654/654/1071 +f 653/653/1069 502/502/875 655/655/1072 +f 655/655/1072 502/502/875 505/505/878 +f 497/497/869 498/498/873 656/656/1073 +f 656/656/1073 498/498/873 500/500/872 +f 656/656/1073 500/500/872 501/501/874 +f 657/657/1074 501/501/874 488/488/860 +f 487/487/859 489/489/861 650/650/1066 +f 658/658/1075 653/653/1069 659/659/1076 +f 659/659/1076 653/653/1069 655/655/1072 +f 625/625/1039 491/491/863 493/493/865 +f 625/625/1039 493/493/865 495/495/867 +f 495/495/867 496/496/868 660/660/1077 +f 660/660/1077 496/496/868 497/497/869 +f 657/657/1074 488/488/860 661/661/1078 +f 661/661/1078 488/488/860 487/487/859 +f 487/487/859 650/650/1066 662/662/1079 +f 662/662/1079 650/650/1066 658/658/1075 +f 658/658/1075 650/650/1066 653/653/1069 +f 659/659/1076 655/655/1072 663/663/1080 +f 625/625/1039 495/495/867 660/660/1077 +f 660/660/1077 497/497/869 664/664/1081 +f 664/664/1081 497/497/869 656/656/1073 +f 664/664/1081 656/656/1073 665/665/1082 +f 665/665/1082 656/656/1073 501/501/874 +f 665/665/1082 501/501/874 666/666/1083 +f 666/666/1083 501/501/874 657/657/1074 +f 667/667/1084 661/661/1078 487/487/859 +f 667/667/1084 487/487/859 662/662/1079 +f 668/668/1085 658/658/1075 669/669/1086 +f 669/669/1086 658/658/1075 659/659/1076 +f 669/669/1086 659/659/1076 663/663/1080 +f 621/621/1035 625/625/1039 670/670/1087 +f 670/670/1087 625/625/1039 660/660/1077 +f 670/670/1087 660/660/1077 671/671/1088 +f 671/671/1088 660/660/1077 664/664/1081 +f 657/657/1074 661/661/1078 643/643/1058 +f 643/643/1058 661/661/1078 667/667/1084 +f 667/667/1084 662/662/1079 672/672/1089 +f 672/672/1089 662/662/1079 668/668/1085 +f 668/668/1085 662/662/1079 658/658/1075 +f 669/669/1086 663/663/1080 633/633/1047 +f 647/647/1062 670/670/1087 671/671/1088 +f 671/671/1088 664/664/1081 645/645/1060 +f 645/645/1060 664/664/1081 665/665/1082 +f 666/666/1083 657/657/1074 643/643/1058 +f 673/673/1090 668/668/1085 669/669/1086 +f 673/673/1090 669/669/1086 674/674/1091 +f 674/674/1091 669/669/1086 633/633/1047 +f 674/674/1091 633/633/1047 632/632/1046 +f 618/618/1032 621/621/1035 616/616/1030 +f 616/616/1030 621/621/1035 670/670/1087 +f 616/616/1030 670/670/1087 648/648/1063 +f 648/648/1063 670/670/1087 647/647/1062 +f 647/647/1062 671/671/1088 646/646/1061 +f 646/646/1061 671/671/1088 645/645/1060 +f 644/644/1059 645/645/1060 665/665/1082 +f 644/644/1059 665/665/1082 666/666/1083 +f 644/644/1059 666/666/1083 643/643/1058 +f 675/675/1092 643/643/1058 667/667/1084 +f 675/675/1092 667/667/1084 672/672/1089 +f 675/675/1092 672/672/1089 676/676/1093 +f 676/676/1093 672/672/1089 668/668/1085 +f 676/676/1093 668/668/1085 673/673/1090 +f 677/677/1094 643/643/1058 675/675/1092 +f 649/649/1064 675/675/1092 676/676/1093 +f 677/677/1094 675/675/1092 649/649/1064 +f 649/649/1064 676/676/1093 651/651/1067 +f 651/651/1067 676/676/1093 652/652/1068 +f 652/652/1068 676/676/1093 673/673/1090 +f 652/652/1068 673/673/1090 674/674/1091 +f 652/652/1068 674/674/1091 626/626/1040 +f 626/626/1040 674/674/1091 632/632/1046 +f 655/655/1072 505/505/878 637/637/1052 +f 655/655/1072 637/637/1052 663/663/1080 +f 663/663/1080 637/637/1052 633/633/1047 +f 639/639/1054 638/638/1053 646/646/1061 +f 639/639/1054 646/646/1061 452/452/825 +f 452/452/825 646/646/1061 641/641/1056 +f 642/642/1057 677/677/1094 450/450/823 +f 450/450/823 677/677/1094 649/649/1064 +f 459/459/1065 652/652/1068 654/654/1071 +f 654/654/1071 652/652/1068 626/626/1040 +f 461/461/1070 654/654/1071 456/456/941 +f 456/456/941 654/654/1071 626/626/1040 +f 678/678/1095 679/679/1096 680/680/1097 +f 680/680/1097 679/679/1096 681/681/1098 +f 679/679/1096 678/678/1095 566/566/1099 +f 566/566/1099 678/678/1095 682/682/1100 +f 566/566/1099 682/682/1100 683/683/1101 +f 683/683/1101 682/682/1100 684/684/1102 +f 684/684/1102 682/682/1100 685/685/1103 +f 684/684/1102 685/685/1103 686/686/1104 +f 686/686/1104 685/685/1103 687/687/1105 +f 686/686/1104 687/687/1105 538/538/1106 +f 538/538/1106 687/687/1105 539/539/1107 +f 539/539/1107 687/687/1105 688/688/1108 +f 539/539/1107 688/688/1108 447/447/1109 +f 689/689/1110 454/454/1111 690/690/1112 +f 689/689/1110 690/690/1112 691/691/1113 +f 689/689/1110 691/691/1113 692/692/1114 +f 692/692/1114 691/691/1113 693/693/1115 +f 692/692/1114 693/693/1115 694/694/1116 +f 694/694/1116 693/693/1115 680/680/1097 +f 680/680/1097 681/681/1098 694/694/1116 +f 688/688/1108 441/441/1117 447/447/1109 +f 695/695/1118 441/441/1117 688/688/1108 +f 695/695/1118 696/696/1119 441/441/1117 +f 697/697/1120 696/696/1119 695/695/1118 +f 697/697/1120 448/448/1121 696/696/1119 +f 698/698/1122 448/448/1121 697/697/1120 +f 698/698/1122 460/460/1123 448/448/1121 +f 699/699/1124 457/457/1125 698/698/1122 +f 698/698/1122 457/457/1125 460/460/1123 +f 699/699/1124 700/700/1126 457/457/1125 +f 701/701/1127 455/455/1128 699/699/1124 +f 699/699/1124 455/455/1128 700/700/1126 +f 701/701/1127 458/458/1129 455/455/1128 +f 702/702/1130 458/458/1129 701/701/1127 +f 702/702/1130 703/703/1131 458/458/1129 +f 704/704/1132 703/703/1131 702/702/1130 +f 704/704/1132 453/453/1133 703/703/1131 +f 690/690/1112 453/453/1133 704/704/1132 +f 690/690/1112 454/454/1111 453/453/1133 +f 705/705/1134 410/410/1134 706/706/1134 +f 706/706/1135 410/410/1135 413/413/1135 +f 706/706/1136 413/413/1136 707/707/1136 +f 707/707/1137 413/413/1138 406/406/1139 +f 707/707/1137 406/406/1139 708/708/1140 +f 708/708/1140 406/406/1139 709/709/1141 +f 708/708/1142 709/709/1143 710/710/1144 +f 711/711/1145 712/712/1146 713/713/1147 +f 714/714/1148 713/713/1148 715/715/1148 +f 714/714/1149 715/715/1150 716/716/1151 +f 716/716/1151 715/715/1150 396/396/1152 +f 410/410/1153 705/705/1153 430/430/1153 +f 430/430/1154 705/705/1155 388/388/1156 +f 388/388/1156 705/705/1155 717/717/1157 +f 717/717/1158 718/718/1158 719/719/1158 +f 719/719/1159 718/718/1159 720/720/1159 +f 719/719/1160 720/720/1161 380/380/1162 +f 380/380/1163 720/720/1164 721/721/1165 +f 722/722/1166 721/721/1166 723/723/1166 +f 722/722/1167 723/723/1167 724/724/1167 +f 724/724/1168 723/723/1168 725/725/1168 +f 724/724/1169 725/725/1169 726/726/1169 +f 726/726/1170 725/725/1170 727/727/1170 +f 726/726/1171 727/727/1171 728/728/1171 +f 728/728/1172 727/727/1172 716/716/1172 +f 728/728/1173 716/716/1174 396/396/1175 +f 716/716/1176 729/729/1177 730/730/1178 +f 716/716/1176 730/730/1178 714/714/1179 +f 714/714/1179 730/730/1178 713/713/1180 +f 713/713/1180 730/730/1178 731/731/1181 +f 713/713/1182 731/731/1182 711/711/1182 +f 711/711/1183 731/731/1183 732/732/1183 +f 711/711/1184 732/732/1185 733/733/1186 +f 733/733/1186 732/732/1185 710/710/1187 +f 710/710/1144 732/732/1188 708/708/1142 +f 708/708/1142 732/732/1188 734/734/1189 +f 708/708/1190 734/734/1190 707/707/1190 +f 707/707/1191 734/734/1191 735/735/1191 +f 707/707/1192 735/735/1193 706/706/1194 +f 706/706/1194 735/735/1193 736/736/1195 +f 706/706/1194 736/736/1195 705/705/1196 +f 705/705/1196 736/736/1195 717/717/1197 +f 717/717/1198 736/736/1198 718/718/1198 +f 718/718/1199 736/736/1200 737/737/1201 +f 718/718/1199 737/737/1201 720/720/1202 +f 720/720/1202 737/737/1201 738/738/1203 +f 720/720/1202 738/738/1203 721/721/1204 +f 721/721/1204 738/738/1203 739/739/1205 +f 721/721/1204 739/739/1205 723/723/1206 +f 723/723/1206 739/739/1205 740/740/1207 +f 723/723/1208 740/740/1209 725/725/1210 +f 725/725/1210 740/740/1209 741/741/1211 +f 725/725/1210 741/741/1211 742/742/1212 +f 725/725/1210 742/742/1212 727/727/1213 +f 727/727/1213 742/742/1212 729/729/1177 +f 727/727/1213 729/729/1177 716/716/1176 +f 732/732/1214 731/731/1215 730/730/1214 +f 739/739/1216 738/738/210 740/740/210 +f 734/734/1217 730/730/1214 735/735/210 +f 740/740/210 738/738/210 742/742/1218 +f 730/730/1214 729/729/210 736/736/210 +f 735/735/210 730/730/1214 736/736/210 +f 470/470/1219 542/542/1220 270/270/1221 +f 270/270/1221 542/542/1220 541/541/1222 +f 542/542/1223 470/470/1224 466/466/1225 +f 542/542/1223 466/466/1225 465/465/1226 +f 543/543/1227 271/271/1228 475/475/1229 +f 543/543/1227 475/475/1229 541/541/1230 +f 541/541/1230 475/475/1229 270/270/1231 +f 463/463/1232 462/462/1233 567/567/1234 +f 567/567/1234 462/462/1233 474/474/1235 +f 567/567/1236 474/474/1237 471/471/1238 +f 567/567/1236 471/471/1238 568/568/1239 +f 473/473/845 477/477/844 483/483/855 +f 483/483/855 485/485/857 473/473/845 +f 568/568/1240 471/471/1241 485/485/857 +f 485/485/857 471/471/1241 473/473/845 +f 447/447/1109 559/559/956 540/540/955 +f 539/539/1107 447/447/1109 540/540/955 +f 452/452/825 454/454/827 689/689/1242 +f 689/689/1242 639/639/1243 452/452/825 +f 689/689/1242 640/640/1244 639/639/1243 +f 689/689/1242 617/617/1245 640/640/1244 +f 692/692/1246 617/617/1245 689/689/1242 +f 617/617/1245 692/692/1246 484/484/1247 +f 692/692/1246 694/694/1248 484/484/1247 +f 484/484/1247 694/694/1248 485/485/1249 +f 681/681/1250 485/485/1249 694/694/1248 +f 686/686/1251 542/542/932 465/465/1252 +f 542/542/932 540/540/931 543/543/101 +f 443/443/1253 544/544/933 446/446/1254 +f 544/544/933 535/535/925 743/743/1255 +f 444/444/1256 446/446/1254 743/743/1255 +f 743/743/1255 446/446/1254 544/544/933 +f 535/535/978 569/569/980 743/743/1257 +f 743/743/1257 569/569/980 744/744/1258 +f 743/743/1257 744/744/1258 444/444/1259 +f 444/444/1259 744/744/1258 445/445/818 +f 569/569/980 570/570/981 744/744/1258 +f 744/744/1258 570/570/981 745/745/1260 +f 744/744/1258 745/745/1260 445/445/818 +f 570/570/981 560/560/958 745/745/1260 +f 745/745/1260 447/447/820 445/445/818 +f 745/745/1260 559/559/1261 447/447/820 +f 560/560/958 559/559/1261 745/745/1260 +f 384/384/755 483/483/1262 477/477/844 +f 384/384/755 390/390/762 483/483/1262 +f 390/390/762 384/384/755 383/383/754 +f 407/407/1263 415/415/787 545/545/1264 +f 686/686/1251 463/463/1265 683/683/1266 +f 386/386/1267 478/478/846 479/479/1268 +f 479/479/1268 480/480/849 746/746/1269 +f 746/746/1269 480/480/849 481/481/851 +f 386/386/1267 479/479/1268 426/426/1270 +f 426/426/1270 479/479/1268 746/746/1269 +f 426/426/1270 746/746/1269 427/427/799 +f 427/427/799 746/746/1269 481/481/1271 +f 478/478/846 386/386/1267 477/477/844 +f 477/477/844 386/386/1267 384/384/755 +f 536/536/1272 419/419/791 537/537/1273 +f 415/415/787 419/419/791 536/536/1272 +f 415/415/787 536/536/1272 534/534/1274 +f 545/545/1264 415/415/787 534/534/1274 +f 420/420/792 422/422/1275 558/558/1276 +f 423/423/1277 428/428/1278 555/555/1279 +f 555/555/1279 428/428/1278 554/554/1280 +f 428/428/1278 429/429/801 553/553/1281 +f 533/533/1282 420/420/792 558/558/1276 +f 557/557/953 558/558/1276 422/422/1275 +f 557/557/953 422/422/1275 421/421/1283 +f 557/557/953 421/421/1283 556/556/951 +f 423/423/1277 556/556/951 421/421/1283 +f 556/556/951 423/423/1277 555/555/1279 +f 428/428/1278 553/553/1281 554/554/1280 +f 429/429/801 552/552/1284 553/553/1281 +f 429/429/801 551/551/1285 552/552/1284 +f 427/427/799 551/551/1285 429/429/801 +f 551/551/1285 427/427/799 481/481/1271 +f 418/418/790 420/420/792 546/546/1286 +f 418/418/790 546/546/1286 547/547/1287 +f 548/548/1288 418/418/790 547/547/1287 +f 419/419/791 418/418/790 548/548/1288 +f 419/419/791 548/548/1288 537/537/1273 +f 533/533/1282 546/546/1286 420/420/792 +f 563/563/1289 747/747/1290 564/564/1291 +f 747/747/1290 563/563/1289 748/748/1292 +f 562/562/1293 748/748/1292 563/563/1289 +f 562/562/1293 749/749/1294 748/748/1292 +f 750/750/1295 438/438/1295 440/440/1295 +f 749/749/1294 562/562/1293 751/751/1296 +f 751/751/1296 562/562/1293 565/565/1297 +f 751/751/1296 565/565/1297 752/752/1298 +f 438/438/1299 750/750/1300 565/565/1301 +f 565/565/1301 750/750/1300 752/752/1302 +f 753/753/1303 754/754/1304 755/755/1305 +f 753/753/1303 755/755/1305 756/756/1306 +f 756/756/1306 755/755/1305 757/757/1307 +f 757/757/1307 758/758/1308 756/756/1306 +f 759/759/1309 758/758/1308 757/757/1307 +f 759/759/1309 561/561/961 758/758/1308 +f 436/436/808 549/549/939 561/561/961 +f 561/561/961 759/759/1309 436/436/808 +f 437/437/809 436/436/808 759/759/1309 +f 756/756/1310 758/758/1311 760/760/1312 +f 758/758/1311 564/564/1313 760/760/1312 +f 758/758/1311 561/561/1314 564/564/1313 +f 757/757/1307 761/761/1315 759/759/1309 +f 759/759/1309 440/440/812 437/437/809 +f 761/761/1316 440/440/1317 759/759/1318 +f 753/753/1319 756/756/1310 760/760/1312 +f 753/753/1319 760/760/1312 762/762/1320 +f 762/762/1320 760/760/1312 747/747/1321 +f 747/747/1321 760/760/1312 564/564/1313 +f 750/750/1322 440/440/1317 763/763/1323 +f 755/755/1305 754/754/1304 764/764/1324 +f 763/763/1323 755/755/1305 764/764/1324 +f 755/755/1305 763/763/1323 761/761/1315 +f 755/755/1305 761/761/1315 757/757/1307 +f 763/763/1323 764/764/1324 750/750/1322 +f 761/761/1316 763/763/1323 440/440/1317 +f 753/753/1319 762/762/1320 765/765/1325 +f 753/753/1319 765/765/1325 766/766/1326 +f 762/762/1320 747/747/1321 765/765/1325 +f 765/765/1325 748/748/1327 749/749/1328 +f 765/765/1325 749/749/1328 766/766/1326 +f 747/747/1321 748/748/1327 765/765/1325 +f 752/752/1329 750/750/1322 764/764/1324 +f 764/764/1324 754/754/1304 767/767/1330 +f 752/752/1329 767/767/1330 751/751/1331 +f 767/767/1330 752/752/1329 764/764/1324 +f 749/749/1328 751/751/1331 766/766/1326 +f 766/766/1326 751/751/1331 767/767/1330 +f 766/766/1326 767/767/1330 753/753/1319 +f 753/753/1319 767/767/1330 754/754/1304 +f 768/768/1332 416/416/1333 769/769/1334 +f 769/769/1334 416/416/1333 414/414/1335 +f 770/770/1336 432/432/1337 771/771/1338 +f 770/770/1336 771/771/1338 772/772/1339 +f 772/772/1339 771/771/1338 417/417/1340 +f 772/772/1341 417/417/1342 768/768/1343 +f 768/768/1343 417/417/1342 416/416/1344 +f 773/773/1345 424/424/1346 433/433/1347 +f 773/773/1345 433/433/1347 774/774/1348 +f 774/774/1348 433/433/1347 434/434/1349 +f 774/774/1348 434/434/1349 770/770/1350 +f 770/770/1350 434/434/1349 432/432/1351 +f 775/775/1352 425/425/1353 776/776/1354 +f 775/775/1352 776/776/1354 773/773/1355 +f 773/773/1355 776/776/1354 424/424/1356 +f 777/777/1357 385/385/1358 425/425/1359 +f 777/777/1357 425/425/1359 775/775/1360 +f 778/778/1361 779/779/1362 381/381/1363 +f 778/778/1364 381/381/1365 777/777/1366 +f 777/777/1366 381/381/1365 385/385/1367 +f 780/780/1368 411/411/1369 431/431/1370 +f 780/780/1368 431/431/1370 781/781/1371 +f 781/781/1371 431/431/1370 387/387/1372 +f 781/781/1371 387/387/1372 782/782/1373 +f 782/782/1373 387/387/1372 779/779/1362 +f 782/782/1373 779/779/1362 778/778/1361 +f 769/769/1374 414/414/1375 412/412/1376 +f 769/769/1374 412/412/1376 780/780/1377 +f 780/780/1377 412/412/1376 411/411/1378 +f 769/769/210 770/770/210 768/768/210 +f 777/777/210 782/782/210 778/778/210 +f 781/781/210 774/774/210 780/780/210 +f 770/770/210 769/769/210 780/780/210 +f 774/774/210 781/781/210 782/782/210 +f 774/774/210 782/782/210 773/773/210 +f 773/773/210 782/782/210 777/777/210 +f 773/773/210 777/777/210 775/775/210 +f 770/770/210 780/780/210 774/774/210 +f 770/770/210 772/772/210 768/768/210 +f 387/387/759 382/382/758 779/779/1379 +f 779/779/1362 382/382/1380 381/381/1363 +f 771/771/1381 432/432/1381 417/417/1381 +f 776/776/1382 425/425/1382 424/424/1382 +f 683/683/1383 684/684/1383 686/686/1383 +f 388/388/1156 717/717/1157 382/382/1384 +f 717/717/1385 719/719/1385 382/382/1385 +f 382/382/1386 719/719/1160 380/380/1162 +f 380/380/1163 721/721/1165 383/383/1387 +f 721/721/1388 722/722/1388 383/383/1388 +f 383/383/1389 722/722/1389 389/389/1389 +f 722/722/1390 724/724/1390 389/389/1390 +f 389/389/1391 724/724/1391 393/393/1391 +f 724/724/1392 726/726/1392 393/393/1392 +f 393/393/1393 726/726/1393 394/394/1393 +f 726/726/1394 728/728/1394 394/394/1394 +f 394/394/1395 728/728/1173 396/396/1175 +f 396/396/1152 715/715/1150 398/398/1396 +f 715/715/1397 713/713/1397 398/398/1397 +f 398/398/1398 713/713/1398 402/402/1398 +f 713/713/1147 712/712/1146 402/402/1399 +f 712/712/1146 711/711/1145 402/402/1399 +f 402/402/1400 711/711/1401 408/408/1402 +f 408/408/1402 711/711/1401 733/733/1403 +f 733/733/1403 710/710/1404 408/408/1402 +f 408/408/1405 710/710/1405 405/405/1405 +f 710/710/1406 709/709/1406 405/405/1406 +f 405/405/1407 709/709/1141 406/406/1139 +f 441/441/1408 696/696/1408 448/448/1408 +f 457/457/1409 700/700/1409 455/455/1409 +f 458/458/1410 703/703/1411 449/449/1412 +f 703/703/1411 453/453/1413 449/449/1412 +f 734/734/1217 732/732/1214 730/730/1214 +f 736/736/210 729/729/210 742/742/1218 +f 737/737/1218 736/736/210 742/742/1218 +f 741/741/1414 740/740/210 742/742/1218 +f 738/738/210 737/737/1218 742/742/1218 +f 691/691/101 682/682/101 678/678/101 +f 695/695/101 701/701/101 697/697/101 +f 701/701/101 698/698/101 697/697/101 +f 701/701/101 695/695/101 702/702/101 +f 702/702/101 695/695/101 688/688/101 +f 698/698/101 701/701/101 699/699/101 +f 702/702/101 688/688/101 687/687/101 +f 702/702/101 687/687/101 704/704/101 +f 682/682/101 690/690/101 685/685/101 +f 704/704/101 687/687/101 685/685/101 +f 704/704/101 685/685/101 690/690/101 +f 690/690/101 682/682/101 691/691/101 +f 691/691/101 678/678/101 693/693/101 +f 693/693/101 678/678/101 680/680/101 +f 679/679/1415 568/568/976 485/485/1249 +f 686/686/1251 538/538/929 542/542/932 +f 545/545/934 544/544/933 407/407/1416 +f 566/566/974 683/683/1266 463/463/1265 +f 544/544/933 443/443/1417 407/407/1416 +f 566/566/974 463/463/1265 567/567/975 +f 568/568/976 679/679/1415 566/566/974 +f 681/681/1250 679/679/1415 485/485/1249 +f 686/686/1251 465/465/1252 463/463/1265 +f 419/419/791 415/415/787 420/420/792 +f 417/417/789 420/420/792 415/415/787 +f 783/783/1418 784/784/1419 785/785/1420 +f 786/786/1421 787/787/1422 788/788/1423 +f 788/788/1423 787/787/1422 789/789/1424 +f 788/788/1423 789/789/1424 790/790/1425 +f 790/790/1425 789/789/1424 791/791/1426 +f 791/791/1426 789/789/1424 792/792/1427 +f 791/791/1426 792/792/1427 785/785/1420 +f 793/793/1428 783/783/1418 792/792/1427 +f 792/792/1427 783/783/1418 785/785/1420 +f 793/793/1428 794/794/1429 783/783/1418 +f 795/795/1430 796/796/1431 797/797/1432 +f 798/798/1433 799/799/1434 800/800/1435 +f 798/798/1433 800/800/1435 795/795/1430 +f 795/795/1430 800/800/1435 796/796/1431 +f 799/799/1434 798/798/1433 801/801/1436 +f 799/799/1434 801/801/1436 802/802/1437 +f 802/802/1437 801/801/1436 803/803/1438 +f 802/802/1437 803/803/1438 804/804/1439 +f 804/804/1439 803/803/1438 805/805/1440 +f 805/805/1440 803/803/1438 806/806/1441 +f 805/805/1440 806/806/1441 807/807/1442 +f 805/805/1440 807/807/1442 808/808/1443 +f 808/808/1443 807/807/1442 809/809/1444 +f 808/808/1443 809/809/1444 810/810/1445 +f 810/810/1445 809/809/1444 811/811/1446 +f 810/810/1445 811/811/1446 812/812/1447 +f 812/812/1447 811/811/1446 813/813/1448 +f 813/813/1448 811/811/1446 814/814/1449 +f 814/814/1449 811/811/1446 786/786/1421 +f 786/786/1421 811/811/1446 787/787/1422 +f 815/815/1450 816/816/1451 817/817/1452 +f 817/817/1452 816/816/1451 818/818/1453 +f 797/797/1432 796/796/1431 819/819/1454 +f 819/819/1454 796/796/1431 820/820/1455 +f 821/821/1456 817/817/1452 818/818/1453 +f 821/821/1456 818/818/1453 822/822/1457 +f 821/821/1456 822/822/1457 823/823/1458 +f 817/817/1452 821/821/1456 819/819/1454 +f 819/819/1454 821/821/1456 797/797/1432 +f 822/822/1457 824/824/1459 825/825/1460 +f 826/826/1461 823/823/1458 825/825/1460 +f 825/825/1460 823/823/1458 822/822/1457 +f 827/827/1462 828/828/1463 823/823/1458 +f 827/827/1462 823/823/1458 829/829/1464 +f 830/830/1465 828/828/1463 827/827/1462 +f 831/831/1466 828/828/1463 830/830/1465 +f 832/832/1467 833/833/1468 831/831/1466 +f 831/831/1466 833/833/1468 828/828/1463 +f 834/834/1469 835/835/1470 836/836/1471 +f 836/836/1471 835/835/1470 833/833/1468 +f 836/836/1471 833/833/1468 832/832/1467 +f 837/837/1472 793/793/1428 834/834/1469 +f 834/834/1469 793/793/1428 835/835/1470 +f 794/794/1429 793/793/1428 837/837/1472 +f 838/838/101 839/839/101 840/840/101 +f 839/839/101 841/841/101 840/840/101 +f 842/842/101 785/785/101 841/841/101 +f 841/841/101 785/785/101 840/840/101 +f 791/791/101 785/785/101 842/842/101 +f 843/843/1473 844/844/1474 845/845/1475 +f 846/846/1476 847/847/1477 848/848/1478 +f 849/849/1479 846/846/1476 850/850/1480 +f 851/851/101 852/852/101 843/843/1473 +f 814/814/1481 853/853/1482 810/810/1483 +f 854/854/1484 794/794/1429 837/837/1472 +f 855/855/1485 856/856/1486 857/857/1487 +f 857/857/1487 856/856/1486 794/794/1429 +f 857/857/1487 794/794/1429 854/854/1484 +f 858/858/1488 856/856/1486 855/855/1485 +f 858/858/1488 859/859/1489 856/856/1486 +f 860/860/1490 859/859/1489 858/858/1488 +f 861/861/1491 843/843/1492 862/862/1493 +f 862/862/1493 843/843/1492 863/863/1494 +f 863/863/1494 843/843/1492 864/864/1495 +f 863/863/1494 864/864/1495 860/860/1490 +f 860/860/1490 864/864/1495 859/859/1489 +f 861/861/1491 865/865/1496 843/843/1492 +f 865/865/1496 861/861/1491 866/866/1497 +f 865/865/1496 866/866/1497 867/867/1498 +f 867/867/1498 866/866/1497 868/868/1499 +f 867/867/1498 868/868/1499 869/869/1500 +f 869/869/1500 868/868/1499 870/870/1501 +f 871/871/210 835/835/210 872/872/210 +f 793/793/210 792/792/210 835/835/210 +f 835/835/210 792/792/210 872/872/210 +f 797/797/210 787/787/210 811/811/210 +f 797/797/210 821/821/210 873/873/210 +f 871/871/210 874/874/210 833/833/210 +f 789/789/210 875/875/210 876/876/210 +f 789/789/210 787/787/210 875/875/210 +f 877/877/1502 869/869/1500 870/870/1501 +f 877/877/1502 878/878/1503 869/869/1500 +f 879/879/210 872/872/210 792/792/210 +f 880/880/1504 881/881/1505 878/878/1503 +f 880/880/1504 878/878/1503 877/877/1502 +f 829/829/1464 881/881/1505 880/880/1504 +f 823/823/1458 826/826/1461 829/829/1464 +f 829/829/1464 826/826/1461 882/882/1506 +f 829/829/1464 882/882/1506 881/881/1505 +f 869/869/101 865/865/101 867/867/101 +f 881/881/101 882/882/1507 869/869/101 +f 882/882/1507 865/865/101 869/869/101 +f 883/883/1508 884/884/1509 885/885/1510 +f 882/882/1507 843/843/1473 865/865/101 +f 886/886/101 887/887/1479 888/888/1511 +f 889/889/1512 890/890/1513 891/891/101 +f 824/824/101 843/843/1473 825/825/1514 +f 892/892/101 843/843/1473 824/824/101 +f 893/893/101 843/843/1473 892/892/101 +f 851/851/101 843/843/1473 893/893/101 +f 894/894/841 895/895/1515 884/884/1509 +f 843/843/1473 852/852/101 896/896/101 +f 843/843/1473 896/896/101 897/897/101 +f 843/843/1473 897/897/101 898/898/101 +f 843/843/1473 898/898/101 899/899/1516 +f 843/843/1473 899/899/1516 900/900/1517 +f 901/901/101 902/902/101 783/783/101 +f 903/903/101 816/816/101 904/904/101 +f 904/904/101 816/816/101 905/905/101 +f 905/905/101 816/816/101 906/906/101 +f 906/906/101 816/816/101 907/907/101 +f 907/907/101 816/816/101 908/908/101 +f 908/908/101 816/816/101 909/909/101 +f 884/884/1509 910/910/1518 885/885/1510 +f 909/909/101 816/816/101 911/911/101 +f 859/859/841 846/846/1476 849/849/1479 +f 911/911/101 816/816/101 912/912/101 +f 912/912/101 816/816/101 815/815/101 +f 912/912/101 815/815/101 891/891/101 +f 843/843/1473 900/900/1517 844/844/1474 +f 891/891/101 815/815/101 913/913/101 +f 891/891/101 913/913/101 914/914/101 +f 891/891/101 914/914/101 915/915/1519 +f 915/915/1519 889/889/1512 891/891/101 +f 916/916/1520 917/917/1521 847/847/1477 +f 917/917/1521 918/918/1522 847/847/1477 +f 919/919/1523 920/920/101 921/921/101 +f 890/890/1513 922/922/101 891/891/101 +f 888/888/1511 887/887/1479 916/916/1520 +f 922/922/101 923/923/101 891/891/101 +f 923/923/101 924/924/101 891/891/101 +f 924/924/101 925/925/101 891/891/101 +f 926/926/101 927/927/101 925/925/101 +f 925/925/101 928/928/101 926/926/101 +f 928/928/101 929/929/101 926/926/101 +f 921/921/101 920/920/101 930/930/101 +f 928/928/101 883/883/1508 929/929/101 +f 884/884/1509 919/919/1523 910/910/1518 +f 853/853/1482 805/805/1524 808/808/1525 +f 864/864/1526 846/846/1476 859/859/841 +f 931/931/1527 847/847/1477 918/918/1522 +f 825/825/1514 843/843/1473 826/826/1528 +f 932/932/101 919/919/1523 921/921/101 +f 925/925/101 927/927/101 891/891/101 +f 933/933/1529 820/820/1530 934/934/1531 +f 935/935/101 936/936/101 783/783/101 +f 843/843/1473 846/846/1476 864/864/1526 +f 930/930/101 886/886/101 888/888/1511 +f 937/937/1532 894/894/841 884/884/1509 +f 938/938/101 934/934/1531 796/796/101 +f 939/939/101 938/938/101 796/796/101 +f 940/940/101 939/939/101 796/796/101 +f 853/853/1482 940/940/101 796/796/101 +f 887/887/1479 917/917/1521 916/916/1520 +f 853/853/1482 786/786/1533 788/788/1534 +f 799/799/101 853/853/1482 800/800/101 +f 853/853/1482 799/799/101 802/802/101 +f 850/850/1480 846/846/1476 848/848/1478 +f 920/920/101 886/886/101 930/930/101 +f 941/941/1535 919/919/1523 884/884/1509 +f 849/849/1479 794/794/101 859/859/841 +f 794/794/101 856/856/101 859/859/841 +f 910/910/1518 919/919/1523 932/932/101 +f 849/849/1479 942/942/101 794/794/101 +f 942/942/101 943/943/101 783/783/101 +f 869/869/101 878/878/101 881/881/101 +f 944/944/101 783/783/101 945/945/101 +f 843/843/1473 845/845/1475 846/846/1476 +f 794/794/101 942/942/101 783/783/101 +f 946/946/101 947/947/101 783/783/101 +f 947/947/101 948/948/101 783/783/101 +f 944/944/101 946/946/101 783/783/101 +f 948/948/101 901/901/101 783/783/101 +f 894/894/841 937/937/1532 949/949/101 +f 943/943/101 945/945/101 783/783/101 +f 936/936/101 950/950/101 783/783/101 +f 902/902/101 935/935/101 783/783/101 +f 783/783/101 950/950/101 951/951/101 +f 949/949/101 952/952/101 953/953/101 +f 783/783/101 951/951/101 954/954/101 +f 783/783/101 954/954/101 784/784/101 +f 784/784/101 954/954/101 955/955/101 +f 784/784/101 955/955/101 956/956/1536 +f 941/941/1535 884/884/1509 895/895/1515 +f 952/952/101 957/957/101 953/953/101 +f 958/958/101 957/957/101 959/959/101 +f 959/959/101 957/957/101 960/960/101 +f 960/960/101 957/957/101 961/961/101 +f 961/961/101 957/957/101 962/962/101 +f 962/962/101 957/957/101 963/963/101 +f 963/963/101 957/957/101 964/964/101 +f 964/964/101 957/957/101 965/965/101 +f 965/965/101 957/957/101 966/966/101 +f 966/966/101 957/957/101 967/967/101 +f 967/967/101 957/957/101 790/790/101 +f 790/790/101 957/957/101 788/788/1534 +f 934/934/1531 820/820/1530 796/796/101 +f 853/853/1482 796/796/101 800/800/101 +f 957/957/101 853/853/1482 788/788/1534 +f 853/853/1482 802/802/101 804/804/101 +f 786/786/1533 853/853/1482 814/814/1481 +f 814/814/1481 810/810/1483 812/812/1537 +f 853/853/1482 804/804/101 805/805/1524 +f 882/882/1507 826/826/1528 843/843/1473 +f 813/813/101 814/814/1481 812/812/1537 +f 937/937/1532 952/952/101 949/949/101 +f 848/848/1478 847/847/1477 931/931/1527 +f 883/883/1508 885/885/1510 929/929/101 +f 810/810/1483 853/853/1482 808/808/1525 +f 957/957/101 958/958/101 953/953/101 +f 857/857/1538 854/854/1539 834/834/1540 +f 868/868/1541 877/877/1542 870/870/1543 +f 868/868/1541 880/880/1544 877/877/1542 +f 880/880/1544 868/868/1541 861/861/1545 +f 861/861/1545 862/862/1546 880/880/1544 +f 880/880/1544 862/862/1546 829/829/1547 +f 862/862/1546 827/827/1548 829/829/1547 +f 840/840/1549 947/947/1550 946/946/1551 +f 840/840/1549 946/946/1551 944/944/1552 +f 840/840/1549 944/944/1552 945/945/1553 +f 840/840/1549 945/945/1553 943/943/1554 +f 840/840/1549 943/943/1554 838/838/1555 +f 838/838/1555 943/943/1554 942/942/1556 +f 838/838/1555 942/942/1556 849/849/1557 +f 838/838/1555 849/849/1557 850/850/1558 +f 838/838/1555 850/850/1558 848/848/1559 +f 848/848/1559 931/931/1560 838/838/1555 +f 838/838/1555 931/931/1560 918/918/1561 +f 838/838/1555 918/918/1561 917/917/1562 +f 838/838/1555 917/917/1562 839/839/1563 +f 839/839/1563 917/917/1562 887/887/1564 +f 839/839/1563 887/887/1564 886/886/1565 +f 839/839/1563 886/886/1565 920/920/1566 +f 839/839/1563 920/920/1566 841/841/1567 +f 841/841/1567 920/920/1566 919/919/1568 +f 841/841/1567 919/919/1568 941/941/1569 +f 841/841/1567 941/941/1569 895/895/1570 +f 841/841/1567 895/895/1570 894/894/1571 +f 841/841/1567 894/894/1571 949/949/1572 +f 841/841/1567 949/949/1572 953/953/1573 +f 841/841/1567 953/953/1573 842/842/1574 +f 842/842/1574 953/953/1573 958/958/1575 +f 968/968/1576 909/909/1577 969/969/1578 +f 969/969/1578 909/909/1577 911/911/1579 +f 969/969/1578 911/911/1579 912/912/1580 +f 912/912/1580 891/891/1581 969/969/1578 +f 969/969/1578 891/891/1581 927/927/1582 +f 969/969/1578 927/927/1582 926/926/1583 +f 969/969/1584 926/926/1585 929/929/1586 +f 969/969/1584 929/929/1586 970/970/1587 +f 970/970/1587 929/929/1586 885/885/1588 +f 885/885/1588 910/910/1589 970/970/1587 +f 970/970/1587 910/910/1589 932/932/1590 +f 970/970/1587 932/932/1590 921/921/1591 +f 970/970/1587 921/921/1591 930/930/1592 +f 970/970/1587 930/930/1592 971/971/1593 +f 971/971/1593 930/930/1592 888/888/1594 +f 971/971/1593 888/888/1594 916/916/1595 +f 916/916/1595 847/847/1596 971/971/1593 +f 971/971/1593 847/847/1596 972/972/1597 +f 972/972/1597 847/847/1596 846/846/1598 +f 972/972/1597 846/846/1598 845/845/1599 +f 972/972/1597 845/845/1599 844/844/1600 +f 972/972/1597 844/844/1600 900/900/1601 +f 972/972/1597 900/900/1601 973/973/1602 +f 974/974/1603 933/933/1604 975/975/1605 +f 975/975/1605 933/933/1604 934/934/1606 +f 975/975/1605 934/934/1606 938/938/1607 +f 975/975/1605 938/938/1607 939/939/1608 +f 975/975/1605 939/939/1608 976/976/1609 +f 976/976/1609 939/939/1608 940/940/1610 +f 976/976/1609 940/940/1610 853/853/1611 +f 976/976/1609 853/853/1611 957/957/1612 +f 976/976/1609 957/957/1612 952/952/1613 +f 976/976/1609 952/952/1613 937/937/1614 +f 937/937/1614 884/884/1615 976/976/1609 +f 976/976/1609 884/884/1615 977/977/1616 +f 977/977/1616 884/884/1615 883/883/1617 +f 977/977/1616 883/883/1617 928/928/1618 +f 977/977/1619 928/928/1620 925/925/1621 +f 977/977/1619 925/925/1621 924/924/1622 +f 977/977/1619 924/924/1622 923/923/1623 +f 977/977/1619 923/923/1623 922/922/1624 +f 977/977/1619 922/922/1624 978/978/1625 +f 978/978/1625 922/922/1624 890/890/1626 +f 785/785/1420 784/784/1419 956/956/1627 +f 785/785/1420 956/956/1627 955/955/1628 +f 785/785/1420 955/955/1628 954/954/1629 +f 785/785/1420 954/954/1629 951/951/1630 +f 785/785/1420 951/951/1630 950/950/1631 +f 785/785/1420 950/950/1631 936/936/1632 +f 785/785/1420 936/936/1632 935/935/1633 +f 785/785/1420 935/935/1633 840/840/1549 +f 840/840/1549 935/935/1633 902/902/1634 +f 840/840/1549 902/902/1634 901/901/1635 +f 840/840/1549 901/901/1635 948/948/1636 +f 840/840/1549 948/948/1636 947/947/1550 +f 790/790/1425 791/791/1426 967/967/1637 +f 967/967/1637 791/791/1426 966/966/1638 +f 966/966/1638 791/791/1426 965/965/1639 +f 965/965/1639 791/791/1426 964/964/1640 +f 964/964/1640 791/791/1426 963/963/1641 +f 963/963/1641 791/791/1426 962/962/1642 +f 962/962/1642 791/791/1426 842/842/1574 +f 962/962/1642 842/842/1574 961/961/1643 +f 961/961/1643 842/842/1574 960/960/1644 +f 960/960/1644 842/842/1574 959/959/1645 +f 959/959/1645 842/842/1574 958/958/1575 +f 824/824/1459 822/822/1457 892/892/1646 +f 892/892/1646 822/822/1457 893/893/1647 +f 893/893/1647 822/822/1457 851/851/1648 +f 851/851/1648 822/822/1457 973/973/1602 +f 851/851/1648 973/973/1602 852/852/1649 +f 852/852/1649 973/973/1602 896/896/1650 +f 896/896/1650 973/973/1602 897/897/1651 +f 897/897/1651 973/973/1602 898/898/1652 +f 898/898/1652 973/973/1602 899/899/1653 +f 899/899/1653 973/973/1602 900/900/1601 +f 818/818/1453 816/816/1451 903/903/1654 +f 818/818/1453 903/903/1654 904/904/1655 +f 818/818/1453 904/904/1655 905/905/1656 +f 818/818/1453 905/905/1656 968/968/1576 +f 968/968/1576 905/905/1656 906/906/1657 +f 968/968/1576 906/906/1657 907/907/1658 +f 968/968/1576 907/907/1658 908/908/1659 +f 968/968/1576 908/908/1659 909/909/1577 +f 819/819/1660 820/820/1661 974/974/1603 +f 974/974/1603 820/820/1661 933/933/1604 +f 978/978/1625 890/890/1626 889/889/1662 +f 978/978/1663 889/889/1664 915/915/1665 +f 978/978/1663 915/915/1665 817/817/1452 +f 915/915/1665 914/914/1666 817/817/1452 +f 817/817/1452 914/914/1666 913/913/1667 +f 817/817/1452 913/913/1667 815/815/1450 +f 979/979/1668 980/980/1669 981/981/1670 +f 979/979/1668 981/981/1670 982/982/1671 +f 982/982/1671 981/981/1670 983/983/1672 +f 982/982/1673 983/983/1674 984/984/1675 +f 984/984/1675 983/983/1674 985/985/1676 +f 985/985/1677 874/874/1678 984/984/1679 +f 984/984/1679 874/874/1678 986/986/1680 +f 986/986/1680 874/874/1678 871/871/1681 +f 986/986/1680 871/871/1681 987/987/1682 +f 987/987/1683 871/871/1684 988/988/1685 +f 988/988/1685 871/871/1684 872/872/1686 +f 988/988/1685 872/872/1686 879/879/1687 +f 988/988/1685 879/879/1687 989/989/1688 +f 989/989/1689 879/879/1690 876/876/1691 +f 989/989/1689 876/876/1691 990/990/1692 +f 990/990/1693 876/876/1694 875/875/1695 +f 990/990/1693 875/875/1695 991/991/1696 +f 875/875/1697 992/992/1698 991/991/1699 +f 991/991/1699 992/992/1698 993/993/1700 +f 993/993/1700 992/992/1698 994/994/1701 +f 993/993/1700 994/994/1701 995/995/1702 +f 995/995/1703 994/994/1704 873/873/1705 +f 995/995/1703 873/873/1705 996/996/1706 +f 996/996/1706 873/873/1705 997/997/1707 +f 996/996/1708 997/997/1709 979/979/1710 +f 979/979/1710 997/997/1709 980/980/1711 +f 979/979/210 988/988/210 993/993/210 +f 988/988/210 979/979/210 987/987/210 +f 993/993/210 989/989/210 991/991/210 +f 991/991/210 989/989/210 990/990/210 +f 993/993/210 995/995/210 979/979/210 +f 988/988/210 989/989/210 993/993/210 +f 979/979/210 995/995/210 996/996/210 +f 986/986/210 987/987/210 979/979/210 +f 979/979/210 982/982/210 986/986/210 +f 982/982/210 984/984/210 986/986/210 +f 866/866/1712 861/861/1545 868/868/1541 +f 837/837/1713 834/834/1540 854/854/1539 +f 806/806/210 809/809/210 807/807/210 +f 797/797/210 809/809/210 806/806/210 +f 797/797/210 806/806/210 803/803/210 +f 809/809/210 797/797/210 811/811/210 +f 798/798/210 797/797/210 801/801/210 +f 798/798/210 795/795/210 797/797/210 +f 994/994/210 992/992/210 797/797/210 +f 968/968/101 973/973/101 822/822/101 +f 818/818/101 968/968/101 822/822/101 +f 968/968/101 969/969/101 972/972/101 +f 968/968/101 972/972/101 973/973/101 +f 972/972/101 969/969/101 971/971/101 +f 971/971/101 969/969/101 970/970/101 +f 978/978/101 817/817/101 819/819/101 +f 974/974/101 975/975/101 978/978/101 +f 975/975/101 977/977/101 978/978/101 +f 978/978/101 819/819/101 974/974/101 +f 976/976/101 977/977/101 975/975/101 +f 862/862/1546 863/863/1714 827/827/1548 +f 827/827/1548 863/863/1714 830/830/1715 +f 863/863/1714 860/860/1716 830/830/1715 +f 860/860/1716 831/831/1717 830/830/1715 +f 860/860/1716 858/858/1718 831/831/1717 +f 858/858/1718 832/832/1719 831/831/1717 +f 858/858/1718 855/855/1720 832/832/1719 +f 855/855/1720 836/836/1721 832/832/1719 +f 836/836/1721 855/855/1720 857/857/1538 +f 857/857/1538 834/834/1540 836/836/1721 +f 821/821/210 823/823/210 828/828/210 +f 828/828/210 983/983/210 821/821/210 +f 879/879/210 792/792/210 789/789/210 +f 983/983/210 981/981/210 821/821/210 +f 985/985/210 983/983/210 828/828/210 +f 821/821/210 981/981/210 980/980/210 +f 821/821/210 980/980/210 997/997/210 +f 821/821/210 997/997/210 873/873/210 +f 789/789/210 876/876/210 879/879/210 +f 985/985/210 828/828/210 874/874/210 +f 833/833/210 835/835/210 871/871/210 +f 873/873/210 994/994/210 797/797/210 +f 801/801/210 797/797/210 803/803/210 +f 828/828/210 833/833/210 874/874/210 +f 875/875/210 787/787/210 992/992/210 +f 787/787/210 797/797/210 992/992/210 +f 998/998/1722 890/890/1723 999/999/1724 +f 999/999/1724 890/890/1723 922/922/1725 +f 999/999/1724 922/922/1725 923/923/1726 +f 1000/1000/1727 999/999/1724 924/924/1728 +f 924/924/1728 999/999/1724 923/923/1726 +f 1000/1000/1729 928/928/1730 1001/1001/1731 +f 1001/1001/1731 928/928/1730 883/883/1732 +f 1002/1002/1733 937/937/1734 952/952/1735 +f 952/952/1735 1003/1003/1736 1002/1002/1733 +f 1003/1003/1737 853/853/1738 940/940/1739 +f 1003/1003/1737 940/940/1739 1004/1004/1740 +f 934/934/1741 1004/1004/1742 938/938/1743 +f 1004/1004/1742 934/934/1741 1005/1005/1744 +f 1006/1006/1745 913/913/1746 914/914/1747 +f 1006/1006/1745 914/914/1747 1007/1007/1748 +f 1006/1006/1745 1007/1007/1748 915/915/1749 +f 908/908/1750 1008/1008/1751 1009/1009/1752 +f 1009/1009/1752 1008/1008/1751 907/907/1753 +f 1009/1009/1752 907/907/1753 906/906/1754 +f 1009/1009/1752 906/906/1754 1010/1010/1755 +f 1010/1010/1756 904/904/1757 903/903/1758 +f 1010/1010/1756 903/903/1758 1011/1011/1759 +f 1012/1012/1760 888/888/1760 930/930/1760 +f 910/910/1761 1012/1012/1762 932/932/1763 +f 885/885/1764 1013/1013/1765 910/910/1761 +f 910/910/1761 1013/1013/1765 1012/1012/1762 +f 1014/1014/1766 1013/1013/1767 926/926/1768 +f 1014/1014/1766 926/926/1768 927/927/1769 +f 1014/1014/1766 927/927/1769 891/891/1770 +f 1014/1014/1766 891/891/1770 912/912/1771 +f 1014/1014/1766 912/912/1771 1015/1015/1772 +f 1015/1015/1772 912/912/1771 911/911/1773 +f 911/911/1773 908/908/1750 1015/1015/1772 +f 1016/1016/1774 824/824/1775 892/892/1776 +f 1016/1016/1774 892/892/1776 893/893/1777 +f 1016/1016/1774 893/893/1777 851/851/1778 +f 1016/1016/1774 851/851/1778 852/852/1779 +f 1016/1016/1774 852/852/1779 896/896/1780 +f 1016/1016/1774 896/896/1780 1017/1017/1781 +f 1017/1017/1781 898/898/1782 1018/1018/1783 +f 1018/1018/1783 898/898/1782 899/899/1784 +f 1019/1019/1785 826/826/1786 824/824/1775 +f 1019/1019/1785 824/824/1775 1016/1016/1774 +f 1020/1020/1787 1021/1021/1787 1022/1022/1787 +f 1023/1023/1788 1024/1024/1789 1025/1025/1790 +f 1026/1026/1791 1027/1027/1791 1023/1023/1791 +f 1028/1028/1792 1029/1029/1792 1030/1030/1792 +f 1031/1031/1793 1032/1032/1793 1033/1033/1793 +f 1033/1033/1794 1034/1034/1795 1031/1031/1796 +f 1035/1035/1797 1034/1034/1797 1033/1033/1797 +f 1036/1036/1798 1037/1037/1799 1038/1038/1800 +f 1036/1036/1798 1038/1038/1800 1039/1039/1801 +f 1040/1040/1802 1036/1036/1802 1041/1041/1802 +f 1042/1042/1803 1043/1043/1803 826/826/1803 +f 1044/1044/1804 784/784/1805 1045/1045/1806 +f 1046/1046/1807 947/947/1808 948/948/1809 +f 1046/1046/1810 901/901/1811 902/902/1812 +f 1046/1046/1810 902/902/1812 1047/1047/1813 +f 1047/1047/1813 902/902/1812 935/935/1814 +f 1047/1047/1813 935/935/1814 936/936/1815 +f 1047/1047/1813 936/936/1815 950/950/1816 +f 1047/1047/1817 950/950/1817 1048/1048/1817 +f 1048/1048/1818 954/954/1819 1044/1044/1804 +f 1044/1044/1804 954/954/1819 955/955/1820 +f 1044/1044/1804 955/955/1820 956/956/1821 +f 1044/1044/1804 956/956/1821 784/784/1805 +f 1049/1049/1822 958/958/1823 1050/1050/1824 +f 894/894/1825 1051/1051/1826 949/949/1827 +f 949/949/1827 1051/1051/1826 1050/1050/1828 +f 1051/1051/1829 895/895/1830 941/941/1831 +f 1051/1051/1829 941/941/1831 1052/1052/1832 +f 1052/1052/1833 920/920/1834 1053/1053/1835 +f 1053/1053/1835 920/920/1834 886/886/1836 +f 1053/1053/1835 886/886/1836 887/887/1837 +f 887/887/1837 1054/1054/1838 1053/1053/1835 +f 1054/1054/1839 918/918/1840 1055/1055/1841 +f 1055/1055/1841 918/918/1840 931/931/1842 +f 850/850/1843 1056/1056/1844 848/848/1845 +f 1056/1056/1846 1055/1055/1846 848/848/1846 +f 848/848/1847 1055/1055/1841 931/931/1842 +f 1056/1056/1844 850/850/1843 849/849/1848 +f 1056/1056/1844 849/849/1848 942/942/1849 +f 945/945/1850 1056/1056/1844 943/943/1851 +f 943/943/1851 1056/1056/1844 942/942/1849 +f 1056/1056/1844 945/945/1850 1057/1057/1852 +f 1057/1057/1852 945/945/1850 944/944/1853 +f 947/947/1808 1046/1046/1807 1057/1057/1854 +f 1058/1058/1855 1059/1059/1856 967/967/1857 +f 1058/1058/1855 967/967/1857 966/966/1858 +f 1058/1058/1855 966/966/1858 965/965/1859 +f 1058/1058/1855 965/965/1859 1060/1060/1860 +f 1060/1060/1860 963/963/1861 962/962/1862 +f 1060/1060/1860 962/962/1862 961/961/1863 +f 1060/1060/1860 961/961/1863 1049/1049/1864 +f 1049/1049/1822 959/959/1865 958/958/1823 +f 1061/1061/1866 1062/1062/1867 1059/1059/1856 +f 1063/1063/1868 1064/1064/1869 1065/1065/1870 +f 1066/1066/1871 1067/1067/1871 1068/1068/1871 +f 1069/1069/1872 1066/1066/1872 1070/1070/1872 +f 1071/1071/1873 1072/1072/1874 1070/1070/1875 +f 810/810/1876 1073/1073/1877 1074/1074/1878 +f 1073/1073/1879 812/812/1880 1075/1075/1881 +f 1075/1075/1881 812/812/1880 813/813/1882 +f 1075/1075/1881 813/813/1882 786/786/1883 +f 1076/1076/1884 1064/1064/1884 1077/1077/1884 +f 1078/1078/1885 938/938/1885 1004/1004/1885 +f 1079/1079/1886 933/933/1887 1078/1078/1888 +f 1078/1078/1888 933/933/1887 1005/1005/1889 +f 1078/1078/1888 1005/1005/1889 934/934/1890 +f 1078/1078/1888 934/934/1890 938/938/1891 +f 933/933/1887 1079/1079/1886 1076/1076/1892 +f 853/853/1738 1003/1003/1737 1080/1080/1893 +f 1080/1080/1894 1003/1003/1894 952/952/1894 +f 1080/1080/210 952/952/210 937/937/210 +f 1080/1080/1895 1081/1081/1896 853/853/1897 +f 853/853/1897 1081/1081/1896 1078/1078/1898 +f 853/853/1897 1078/1078/1898 940/940/1899 +f 940/940/1739 1078/1078/1900 1004/1004/1740 +f 1082/1082/1901 1083/1083/1902 1070/1070/1903 +f 1084/1084/1904 1082/1082/1901 1064/1064/1905 +f 1079/1079/1886 1084/1084/1904 1076/1076/1892 +f 1076/1076/1892 1084/1084/1904 1064/1064/1905 +f 1085/1085/1906 1065/1065/1907 1064/1064/1905 +f 1070/1070/1903 1086/1086/1908 1087/1087/1909 +f 1070/1070/1903 1087/1087/1909 1064/1064/1905 +f 1088/1088/1910 1089/1089/1911 1090/1090/1912 +f 1090/1090/1912 1086/1086/1908 1070/1070/1903 +f 1091/1091/1913 1089/1089/1911 1085/1085/1906 +f 1085/1085/1906 1089/1089/1911 1088/1088/1910 +f 1064/1064/1905 1087/1087/1909 1092/1092/1914 +f 1064/1064/1905 1092/1092/1914 1085/1085/1906 +f 1085/1085/1906 1092/1092/1914 1091/1091/1913 +f 1093/1093/1915 1066/1066/1916 1068/1068/1917 +f 1071/1071/1918 1094/1094/1919 1095/1095/1920 +f 1070/1070/1921 1096/1096/1922 1071/1071/1918 +f 1071/1071/1918 1096/1096/1922 1094/1094/1919 +f 1097/1097/1923 1074/1074/1924 808/808/1925 +f 1097/1097/1923 808/808/1925 1098/1098/1926 +f 786/786/1927 813/813/1928 1097/1097/1929 +f 1097/1097/1929 813/813/1928 812/812/1930 +f 812/812/1930 1073/1073/1931 1097/1097/1929 +f 1097/1097/1923 1073/1073/1932 810/810/1933 +f 1097/1097/1923 810/810/1933 1074/1074/1924 +f 1062/1062/1934 1099/1099/1935 1059/1059/1936 +f 1059/1059/1936 1099/1099/1935 1100/1100/1937 +f 1070/1070/1938 1100/1100/1938 1101/1101/1938 +f 1070/1070/1921 1101/1101/1939 1097/1097/1923 +f 1062/1062/1934 1102/1102/1940 1099/1099/1935 +f 1097/1097/1929 1103/1103/1941 786/786/1927 +f 1103/1103/1941 1102/1102/1940 786/786/1927 +f 786/786/1927 1102/1102/1940 1062/1062/1934 +f 1059/1059/1936 1050/1050/1942 958/958/1943 +f 895/895/1944 1051/1051/1944 1080/1080/1944 +f 1080/1080/1945 1051/1051/1945 894/894/1945 +f 1080/1080/1895 894/894/1946 1059/1059/1936 +f 1059/1059/1936 894/894/1946 949/949/1947 +f 1059/1059/1936 949/949/1947 1050/1050/1942 +f 1059/1059/1936 958/958/1943 967/967/1948 +f 967/967/1948 958/958/1943 959/959/210 +f 967/967/1949 959/959/1949 1049/1049/1949 +f 967/967/1950 1049/1049/1951 961/961/1952 +f 967/967/1950 961/961/1952 962/962/210 +f 962/962/210 963/963/210 967/967/1950 +f 967/967/1953 963/963/1861 1060/1060/1860 +f 967/967/1954 1060/1060/1955 966/966/1956 +f 966/966/1956 1060/1060/1955 965/965/1957 +f 918/918/1958 1054/1054/1959 1104/1104/1960 +f 1054/1054/1959 887/887/1961 1080/1080/1962 +f 1080/1080/1962 887/887/1961 886/886/210 +f 1080/1080/1962 886/886/210 920/920/1963 +f 920/920/1963 1052/1052/1964 1080/1080/1962 +f 1080/1080/1965 1052/1052/1966 941/941/1967 +f 1080/1080/1965 941/941/1967 895/895/210 +f 1105/1105/1968 1106/1106/1969 1104/1104/1960 +f 848/848/210 931/931/210 1104/1104/1960 +f 1104/1104/1960 931/931/210 918/918/1958 +f 1107/1107/1970 1046/1046/1970 948/948/1970 +f 1107/1107/1971 948/948/1972 947/947/1973 +f 1107/1107/1971 947/947/1973 1106/1106/1974 +f 1106/1106/1974 947/947/1973 1057/1057/1975 +f 1106/1106/1976 1057/1057/1976 944/944/1976 +f 1106/1106/1977 944/944/1978 945/945/1979 +f 1106/1106/1977 945/945/1979 943/943/1980 +f 943/943/1980 942/942/1981 1106/1106/1977 +f 1106/1106/1982 942/942/1982 849/849/1982 +f 1106/1106/1969 849/849/1983 1104/1104/1960 +f 1104/1104/1960 849/849/1983 850/850/210 +f 1104/1104/1960 850/850/210 848/848/210 +f 1107/1107/1984 950/950/1985 936/936/1986 +f 1108/1108/1987 955/955/1988 954/954/1989 +f 1108/1108/1987 954/954/1989 1107/1107/1990 +f 1107/1107/1990 954/954/1989 1048/1048/1991 +f 1107/1107/1992 1048/1048/1992 950/950/1992 +f 1108/1108/1987 1109/1109/1993 1045/1045/1994 +f 936/936/1986 935/935/1995 1107/1107/1984 +f 1107/1107/1984 935/935/1995 902/902/1996 +f 1107/1107/1984 902/902/1996 901/901/1997 +f 1107/1107/1984 901/901/1997 1046/1046/1998 +f 1108/1108/1987 784/784/1999 956/956/2000 +f 1108/1108/1987 956/956/2000 955/955/1988 +f 784/784/1999 1108/1108/1987 1045/1045/1994 +f 1020/1020/2001 1022/1022/2002 1109/1109/1993 +f 1109/1109/1993 1022/1022/2002 1045/1045/1994 +f 1104/1104/1960 1025/1025/2003 1110/1110/2004 +f 1110/1110/2004 1111/1111/2005 1104/1104/1960 +f 1104/1104/1960 1112/1112/2006 1113/1113/2007 +f 1025/1025/2003 1113/1113/2007 1114/1114/2008 +f 1025/1025/2003 1114/1114/2008 1023/1023/2009 +f 1023/1023/2009 1115/1115/2010 1116/1116/2011 +f 1104/1104/1960 1117/1117/2012 1112/1112/2006 +f 1104/1104/1960 1113/1113/2007 1025/1025/2003 +f 1115/1115/2010 1023/1023/2009 1114/1114/2008 +f 1116/1116/2011 1117/1117/2012 1023/1023/2009 +f 1023/1023/2009 1117/1117/2012 1104/1104/1960 +f 1023/1023/2009 1104/1104/1960 1026/1026/2013 +f 1032/1032/2014 1028/1028/2015 1104/1104/1960 +f 1104/1104/1960 1030/1030/2016 1026/1026/2013 +f 1104/1104/1960 1028/1028/2015 1030/1030/2016 +f 1033/1033/2017 1032/1032/2014 1104/1104/1960 +f 1035/1035/2018 1033/1033/2017 1039/1039/2019 +f 1033/1033/2017 1118/1118/2020 1039/1039/2019 +f 1039/1039/2019 1118/1118/2020 1119/1119/2021 +f 1120/1120/2022 1121/1121/2023 1041/1041/2024 +f 1119/1119/2021 1122/1122/2025 1039/1039/2019 +f 1039/1039/2026 1122/1122/2026 1036/1036/2026 +f 1122/1122/2027 1120/1120/2022 1036/1036/2028 +f 1036/1036/2028 1120/1120/2022 1041/1041/2024 +f 1033/1033/2017 1121/1121/2023 1118/1118/2020 +f 1123/1123/2029 1041/1041/2024 1104/1104/1960 +f 1041/1041/2024 1123/1123/2029 1124/1124/2030 +f 1124/1124/2030 1125/1125/2031 826/826/2032 +f 846/846/2033 1126/1126/2033 1127/1127/2033 +f 1043/1043/2034 1124/1124/2030 826/826/2032 +f 1041/1041/2024 1124/1124/2030 1043/1043/2034 +f 1128/1128/2035 896/896/2036 852/852/2037 +f 1128/1128/2035 852/852/2037 851/851/2038 +f 1128/1128/2035 851/851/2038 893/893/2039 +f 1128/1128/2035 893/893/2039 1125/1125/2031 +f 1125/1125/2031 893/893/2039 892/892/2040 +f 1125/1125/2031 892/892/2040 824/824/2041 +f 1125/1125/2031 824/824/2041 826/826/2032 +f 846/846/2042 1129/1129/2043 1126/1126/2044 +f 1126/1126/2045 1129/1129/2045 845/845/2045 +f 1126/1126/2046 845/845/2047 900/900/2048 +f 1130/1130/2049 847/847/2050 1104/1104/2051 +f 1104/1104/2052 847/847/2052 1127/1127/2052 +f 1126/1126/2053 1123/1123/2029 1104/1104/1960 +f 1126/1126/2046 900/900/2048 1131/1131/2054 +f 1131/1131/2054 900/900/2048 1018/1018/2055 +f 1131/1131/2056 1018/1018/2056 899/899/2056 +f 1131/1131/2057 899/899/2058 1128/1128/2035 +f 1128/1128/2035 899/899/2058 898/898/2059 +f 1128/1128/2035 898/898/2059 1017/1017/2060 +f 1128/1128/2035 1017/1017/2060 896/896/2036 +f 1127/1127/2061 1126/1126/2053 1104/1104/1960 +f 888/888/2062 1012/1012/2062 1104/1104/2062 +f 1012/1012/2063 916/916/2064 1104/1104/2051 +f 1104/1104/2051 916/916/2064 1130/1130/2049 +f 1012/1012/2065 930/930/2065 1080/1080/2065 +f 1080/1080/1962 930/930/210 888/888/210 +f 1013/1013/2066 885/885/2067 1080/1080/2068 +f 926/926/2069 1013/1013/2070 1080/1080/2071 +f 885/885/2067 910/910/210 1080/1080/2068 +f 1080/1080/2068 910/910/210 932/932/2072 +f 1080/1080/2068 932/932/2072 1012/1012/2073 +f 927/927/210 922/922/210 890/890/210 +f 926/926/210 883/883/210 928/928/210 +f 928/928/2074 1000/1000/2074 926/926/2074 +f 926/926/2075 1000/1000/2075 924/924/2075 +f 926/926/210 924/924/210 927/927/210 +f 927/927/210 924/924/210 923/923/210 +f 927/927/210 923/923/210 922/922/210 +f 937/937/2076 1002/1002/2076 1080/1080/2076 +f 1080/1080/2071 1002/1002/2077 884/884/2078 +f 890/890/2079 998/998/2079 927/927/2079 +f 927/927/2080 998/998/2080 889/889/2080 +f 889/889/2081 1132/1132/2082 927/927/2083 +f 927/927/2083 1132/1132/2082 915/915/2084 +f 1080/1080/2071 884/884/2078 926/926/2069 +f 926/926/2085 884/884/2086 1001/1001/2087 +f 926/926/2088 1001/1001/2088 883/883/2088 +f 927/927/2083 915/915/2084 1007/1007/210 +f 927/927/2083 1007/1007/210 891/891/210 +f 908/908/2089 913/913/2089 1006/1006/2089 +f 908/908/2090 1006/1006/2091 1011/1011/2092 +f 913/913/210 908/908/210 914/914/210 +f 914/914/210 908/908/210 911/911/210 +f 914/914/210 911/911/210 1007/1007/210 +f 1007/1007/210 911/911/210 912/912/210 +f 1007/1007/210 912/912/210 891/891/210 +f 908/908/2090 1011/1011/2092 1008/1008/2093 +f 1008/1008/2093 1011/1011/2092 903/903/2094 +f 1008/1008/2093 903/903/2094 904/904/210 +f 904/904/2095 1010/1010/2095 1008/1008/2095 +f 1008/1008/2096 1010/1010/2096 906/906/2096 +f 1008/1008/210 906/906/210 907/907/210 +f 1095/1095/1920 1094/1094/1919 1098/1098/2097 +f 1133/1133/2098 1134/1134/2099 1098/1098/1926 +f 1094/1094/2100 1133/1133/2100 1098/1098/2100 +f 1098/1098/1926 1134/1134/2099 1135/1135/2101 +f 1097/1097/1923 1136/1136/2102 1096/1096/1922 +f 1098/1098/1926 1135/1135/2101 1097/1097/1923 +f 1135/1135/2101 1136/1136/2102 1097/1097/1923 +f 1090/1090/1912 1070/1070/1903 1088/1088/1910 +f 1088/1088/1910 1070/1070/1903 1093/1093/1915 +f 1093/1093/1915 1070/1070/1903 1066/1066/1916 +f 888/888/210 1104/1104/1960 1080/1080/1962 +f 1080/1080/1962 1104/1104/1960 1054/1054/1959 +f 1080/1080/1895 1059/1059/1936 1070/1070/1903 +f 1070/1070/1903 1059/1059/1936 1100/1100/1937 +f 1081/1081/1896 1080/1080/1895 1070/1070/1903 +f 1083/1083/1902 1081/1081/1896 1070/1070/1903 +f 1064/1064/1905 1082/1082/1901 1070/1070/1903 +f 1070/1070/1921 1097/1097/1923 1096/1096/1922 +f 1121/1121/2023 1033/1033/2017 1041/1041/2024 +f 1041/1041/2024 1033/1033/2017 1104/1104/1960 +f 1137/1137/2103 1104/1104/1960 1111/1111/2005 +f 1137/1137/2103 1111/1111/2005 1109/1109/1993 +f 1109/1109/1993 1111/1111/2005 1020/1020/2001 +f 1104/1104/1960 1137/1137/2103 1105/1105/1968 +f 1024/1024/1789 1138/1138/2104 1025/1025/1790 +f 1037/1037/2105 1139/1139/2106 1038/1038/2107 +f 1140/1140/2108 1141/1141/2109 1042/1042/2110 +f 1142/1142/2111 1037/1037/2112 1036/1036/2113 +f 1141/1141/2109 1143/1143/2114 1043/1043/2115 +f 1143/1143/2114 1144/1144/2116 1041/1041/2117 +f 1139/1139/2106 1145/1145/2118 1146/1146/2119 +f 1145/1145/2118 1147/1147/2120 1034/1034/1795 +f 1148/1148/2121 1149/1149/2122 1029/1029/2123 +f 1029/1029/2123 1149/1149/2122 1030/1030/2124 +f 1138/1138/2104 1110/1110/2125 1025/1025/1790 +f 1111/1111/2126 1150/1150/2127 1020/1020/2128 +f 1043/1043/2115 1042/1042/2110 1141/1141/2109 +f 1041/1041/2117 1043/1043/2115 1143/1143/2114 +f 1141/1141/2129 1144/1144/2130 1143/1143/2131 +f 1040/1040/2132 1041/1041/2117 1144/1144/2116 +f 1144/1144/2116 1142/1142/2111 1040/1040/2132 +f 1040/1040/2132 1142/1142/2111 1036/1036/2113 +f 1139/1139/2106 1146/1146/2119 1038/1038/2107 +f 1038/1038/2107 1146/1146/2119 1039/1039/2133 +f 1035/1035/2134 1039/1039/2133 1146/1146/2119 +f 1035/1035/2134 1146/1146/2119 1145/1145/2118 +f 1035/1035/2134 1145/1145/2118 1034/1034/1795 +f 1031/1031/1796 1034/1034/1795 1147/1147/2120 +f 1151/1151/2135 1031/1031/1796 1147/1147/2120 +f 1031/1031/1796 1151/1151/2135 1032/1032/2136 +f 1028/1028/2137 1032/1032/2136 1151/1151/2135 +f 1028/1028/2137 1151/1151/2135 1148/1148/2121 +f 1029/1029/2123 1028/1028/2137 1148/1148/2121 +f 1030/1030/2124 1149/1149/2122 1026/1026/2138 +f 1027/1027/2139 1026/1026/2138 1149/1149/2122 +f 1149/1149/2140 1152/1152/2141 1027/1027/2142 +f 1027/1027/2142 1152/1152/2141 1024/1024/2143 +f 1027/1027/2142 1024/1024/2143 1023/1023/2144 +f 1110/1110/2125 1138/1138/2104 1150/1150/2145 +f 1111/1111/2126 1110/1110/2146 1150/1150/2127 +f 1021/1021/2147 1020/1020/2128 1150/1150/2127 +f 1021/1021/2148 1150/1150/2149 1153/1153/2150 +f 1140/1140/2108 1042/1042/2110 826/826/2151 +f 826/826/1786 1019/1019/1785 1140/1140/2152 +f 1154/1154/2153 1044/1044/1804 1155/1155/2154 +f 1044/1044/1804 1045/1045/1806 1155/1155/2154 +f 1045/1045/2155 1022/1022/2155 1155/1155/2155 +f 1155/1155/2156 1022/1022/2157 1153/1153/2150 +f 1155/1155/2158 1153/1153/2150 1156/1156/2159 +f 1022/1022/2157 1021/1021/2148 1153/1153/2150 +f 1018/1018/1783 1157/1157/2160 1017/1017/1781 +f 1017/1017/1781 1157/1157/2160 1016/1016/1774 +f 1044/1044/1804 1154/1154/2161 1048/1048/1818 +f 1048/1048/1818 1154/1154/2161 1047/1047/2162 +f 1015/1015/1772 908/908/1750 1009/1009/1752 +f 1018/1018/1783 900/900/2163 1158/1158/2164 +f 1158/1158/2164 900/900/2163 845/845/2165 +f 1158/1158/2164 845/845/2165 1129/1129/2166 +f 1129/1129/2043 846/846/2042 1127/1127/2167 +f 847/847/2168 1130/1130/2169 1127/1127/2170 +f 1127/1127/2170 1130/1130/2169 916/916/2171 +f 1127/1127/2170 916/916/2171 1159/1159/2172 +f 1159/1159/2173 916/916/2174 1012/1012/2175 +f 1012/1012/2175 1013/1013/2176 1160/1160/2177 +f 1018/1018/1783 1158/1158/2164 1157/1157/2160 +f 1159/1159/2173 1012/1012/2175 1160/1160/2177 +f 1160/1160/2178 1013/1013/1767 1014/1014/1766 +f 1015/1015/2179 1009/1009/2180 1161/1161/2181 +f 1158/1158/2164 1129/1129/2166 1162/1162/2182 +f 1162/1162/2182 1129/1129/2166 1127/1127/2183 +f 1162/1162/2182 1127/1127/2183 1159/1159/2184 +f 1162/1162/2185 1159/1159/2173 1160/1160/2177 +f 1160/1160/2186 1014/1014/2187 1163/1163/2188 +f 1014/1014/2187 1015/1015/2179 1163/1163/2188 +f 1163/1163/2188 1015/1015/2179 1161/1161/2181 +f 1055/1055/1841 1053/1053/2189 1054/1054/1839 +f 1051/1051/1826 1164/1164/2190 1050/1050/1828 +f 1050/1050/2191 1164/1164/2192 1049/1049/1864 +f 1057/1057/2193 1046/1046/1810 1047/1047/1813 +f 1055/1055/2194 1056/1056/2195 1165/1165/2196 +f 1165/1165/2197 1056/1056/2198 1057/1057/2193 +f 1166/1166/2199 1057/1057/2193 1047/1047/1813 +f 1057/1057/2193 1166/1166/2199 1165/1165/2197 +f 1053/1053/2200 1167/1167/2201 1052/1052/2202 +f 1052/1052/2203 1167/1167/2204 1051/1051/2205 +f 1055/1055/2194 1165/1165/2196 1168/1168/2206 +f 1055/1055/2194 1168/1168/2206 1053/1053/2207 +f 1053/1053/2200 1168/1168/2208 1167/1167/2201 +f 1051/1051/2205 1167/1167/2204 1169/1169/2209 +f 1051/1051/2205 1169/1169/2209 1164/1164/2210 +f 1010/1010/1755 1161/1161/2211 1009/1009/1752 +f 1060/1060/1860 1164/1164/2192 1169/1169/2212 +f 1060/1060/1860 1169/1169/2212 1058/1058/1855 +f 1164/1164/2192 1060/1060/1860 1049/1049/1864 +f 1011/1011/2213 1006/1006/2213 1010/1010/2213 +f 1010/1010/2214 1006/1006/2215 1170/1170/2216 +f 1010/1010/2214 1170/1170/2216 1161/1161/2217 +f 786/786/1883 1062/1062/1867 1171/1171/2218 +f 1062/1062/1867 1172/1172/2219 1171/1171/2218 +f 1171/1171/2220 1172/1172/2221 1173/1173/2222 +f 1058/1058/2223 1169/1169/2224 1174/1174/2225 +f 1175/1175/2226 1171/1171/2226 1176/1176/2226 +f 1173/1173/2222 1172/1172/2221 1174/1174/2225 +f 1172/1172/2219 1062/1062/1867 1061/1061/1866 +f 1172/1172/2221 1061/1061/2227 1174/1174/2225 +f 1061/1061/1866 1059/1059/1856 1058/1058/1855 +f 1061/1061/2227 1058/1058/2223 1174/1174/2225 +f 998/998/2228 1170/1170/2229 1132/1132/2230 +f 1132/1132/2230 1170/1170/2229 1006/1006/1745 +f 889/889/2231 998/998/2228 1132/1132/2230 +f 1132/1132/2230 1006/1006/1745 915/915/1749 +f 1177/1177/2232 1178/1178/2233 1179/1179/2234 +f 1178/1178/2233 1063/1063/1868 1065/1065/1870 +f 1175/1175/2235 1075/1075/1881 786/786/1883 +f 1098/1098/2236 1180/1180/2237 1095/1095/2238 +f 1181/1181/2239 1182/1182/2240 1072/1072/1874 +f 1183/1183/2241 1085/1085/2242 1088/1088/2243 +f 1171/1171/2218 1175/1175/2235 786/786/1883 +f 1075/1075/2244 1175/1175/2245 1184/1184/2246 +f 1075/1075/2244 1184/1184/2246 1073/1073/1877 +f 1074/1074/1878 1073/1073/1877 1184/1184/2246 +f 808/808/2247 1074/1074/1878 1184/1184/2246 +f 1184/1184/2246 1185/1185/2248 808/808/2247 +f 1185/1185/2249 1184/1184/2246 1186/1186/2250 +f 808/808/2247 1185/1185/2248 1098/1098/2236 +f 1186/1186/2251 1098/1098/2236 1185/1185/2248 +f 1186/1186/2251 1180/1180/2237 1098/1098/2236 +f 1095/1095/2238 1180/1180/2237 1181/1181/2252 +f 1181/1181/2239 1180/1180/2253 1187/1187/2254 +f 1071/1071/2255 1095/1095/2238 1181/1181/2252 +f 1181/1181/2252 1072/1072/2256 1071/1071/2255 +f 1069/1069/2257 1070/1070/1875 1072/1072/1874 +f 1069/1069/2257 1072/1072/1874 1182/1182/2240 +f 1182/1182/2240 1188/1188/2258 1069/1069/2257 +f 1066/1066/2259 1069/1069/2257 1188/1188/2258 +f 1067/1067/2260 1066/1066/2259 1188/1188/2258 +f 1188/1188/2258 1189/1189/2261 1067/1067/2260 +f 1189/1189/2261 1190/1190/2262 1067/1067/2260 +f 1067/1067/2260 1190/1190/2262 1068/1068/2263 +f 1190/1190/2264 1189/1189/2265 1183/1183/2266 +f 1068/1068/2263 1190/1190/2262 1093/1093/2267 +f 1088/1088/2243 1093/1093/2267 1190/1190/2262 +f 1088/1088/2243 1190/1190/2262 1183/1183/2241 +f 1179/1179/2234 1085/1085/2242 1183/1183/2241 +f 1179/1179/2268 1183/1183/2268 1191/1191/2268 +f 1065/1065/1870 1085/1085/2242 1179/1179/2234 +f 1065/1065/1870 1179/1179/2234 1178/1178/2233 +f 1001/1001/2087 884/884/2086 1002/1002/2269 +f 1004/1004/2270 1005/1005/2271 1192/1192/2272 +f 1192/1192/2273 1005/1005/2274 933/933/2275 +f 999/999/2276 1000/1000/2277 1193/1193/2278 +f 1000/1000/2279 1001/1001/2280 1193/1193/2281 +f 1194/1194/2282 1002/1002/2283 1003/1003/2284 +f 1192/1192/2273 933/933/2275 1195/1195/2285 +f 1001/1001/2286 1002/1002/2287 1194/1194/2288 +f 1196/1196/2289 1003/1003/2284 1004/1004/2270 +f 998/998/2290 999/999/2276 1170/1170/2291 +f 1196/1196/2289 1004/1004/2270 1192/1192/2272 +f 1170/1170/2291 999/999/2276 1193/1193/2278 +f 1193/1193/2281 1001/1001/2280 1197/1197/2292 +f 1197/1197/2293 1001/1001/2286 1194/1194/2288 +f 1194/1194/2282 1003/1003/2284 1196/1196/2289 +f 1198/1198/2294 1192/1192/2295 1195/1195/2296 +f 1194/1194/2297 1196/1196/2297 1192/1192/2297 +f 1199/1199/2298 1198/1198/2294 1195/1195/2296 +f 1077/1077/2299 1199/1199/2298 1195/1195/2296 +f 1077/1077/2299 1195/1195/2296 1076/1076/2300 +f 1076/1076/2301 1195/1195/2285 933/933/2275 +f 1200/1200/2302 1201/1201/2303 1063/1063/1868 +f 1178/1178/2304 1200/1200/2302 1063/1063/1868 +f 1063/1063/1868 1077/1077/2299 1064/1064/1869 +f 1063/1063/1868 1201/1201/2303 1077/1077/2299 +f 1077/1077/2299 1201/1201/2303 1199/1199/2298 +f 1107/1107/2305 1154/1154/2306 1108/1108/2307 +f 1107/1107/2305 1047/1047/2308 1154/1154/2306 +f 1047/1047/2309 1107/1107/2310 1106/1106/2311 +f 1047/1047/2309 1106/1106/2311 1166/1166/2312 +f 1109/1109/2313 1155/1155/2314 1156/1156/2315 +f 1108/1108/2316 1154/1154/2316 1155/1155/2316 +f 1108/1108/2317 1155/1155/2314 1109/1109/2313 +f 1109/1109/2318 1156/1156/2318 1137/1137/2318 +f 1137/1137/2319 1156/1156/2319 1202/1202/2319 +f 1137/1137/2320 1202/1202/2320 1105/1105/2320 +f 1105/1105/2321 1202/1202/2322 1106/1106/2323 +f 1106/1106/2323 1202/1202/2322 1166/1166/2324 +f 1115/1115/2325 1024/1024/2325 1116/1116/2325 +f 1116/1116/2326 1024/1024/2326 1152/1152/2326 +f 1024/1024/2327 1115/1115/2327 1114/1114/2327 +f 1024/1024/2328 1114/1114/2328 1138/1138/2328 +f 1113/1113/2329 1138/1138/2329 1114/1114/2329 +f 1116/1116/2330 1152/1152/2331 1203/1203/2332 +f 1116/1116/2330 1203/1203/2332 1117/1117/2333 +f 1117/1117/2334 1203/1203/2335 1204/1204/2336 +f 1117/1117/2334 1204/1204/2336 1112/1112/2337 +f 1112/1112/2338 1204/1204/2339 1113/1113/2340 +f 1113/1113/2340 1204/1204/2339 1138/1138/2341 +f 1142/1142/2342 1120/1120/2343 1037/1037/2344 +f 1037/1037/2344 1120/1120/2343 1122/1122/2345 +f 1037/1037/2346 1122/1122/2347 1139/1139/2348 +f 1139/1139/2348 1122/1122/2347 1119/1119/2349 +f 1120/1120/2350 1142/1142/2351 1121/1121/2352 +f 1121/1121/2352 1142/1142/2351 1205/1205/2353 +f 1121/1121/2354 1205/1205/2355 1118/1118/2356 +f 1118/1118/2356 1205/1205/2355 1206/1206/2357 +f 1118/1118/2358 1206/1206/2359 1119/1119/2360 +f 1119/1119/2360 1206/1206/2359 1139/1139/2361 +f 1158/1158/2362 1126/1126/2363 1131/1131/2364 +f 1158/1158/2362 1131/1131/2364 1157/1157/2365 +f 1157/1157/2366 1131/1131/2367 1128/1128/2368 +f 1016/1016/2369 1157/1157/2366 1128/1128/2368 +f 1016/1016/2370 1128/1128/2371 1125/1125/2372 +f 1016/1016/2370 1125/1125/2372 1019/1019/2373 +f 1140/1140/2374 1019/1019/2373 1125/1125/2372 +f 1124/1124/2375 1140/1140/2374 1125/1125/2372 +f 1126/1126/2376 1158/1158/2377 1207/1207/2378 +f 1126/1126/2376 1207/1207/2378 1123/1123/2379 +f 1123/1123/2380 1207/1207/2381 1208/1208/2382 +f 1123/1123/2380 1208/1208/2382 1124/1124/2375 +f 1124/1124/2375 1208/1208/2382 1140/1140/2374 +f 1200/1200/2383 1082/1082/2384 1201/1201/2385 +f 1201/1201/2385 1082/1082/2384 1084/1084/2386 +f 1084/1084/2387 1199/1199/2388 1201/1201/2389 +f 1079/1079/2390 1199/1199/2388 1084/1084/2387 +f 1082/1082/2391 1200/1200/2392 1209/1209/2393 +f 1082/1082/2391 1209/1209/2393 1083/1083/2394 +f 1083/1083/2395 1209/1209/2396 1081/1081/2397 +f 1081/1081/2397 1209/1209/2396 1210/1210/2398 +f 1081/1081/2399 1210/1210/2400 1078/1078/2401 +f 1078/1078/2401 1210/1210/2400 1198/1198/2402 +f 1078/1078/2401 1198/1198/2402 1079/1079/2390 +f 1079/1079/2390 1198/1198/2402 1199/1199/2388 +f 1179/1179/2403 1091/1091/2404 1092/1092/2405 +f 1089/1089/2406 1191/1191/2406 1090/1090/2406 +f 1191/1191/2407 1089/1089/2408 1179/1179/2409 +f 1179/1179/2409 1089/1089/2408 1091/1091/2410 +f 1177/1177/2411 1179/1179/2403 1092/1092/2405 +f 1087/1087/2412 1177/1177/2413 1092/1092/2414 +f 1090/1090/2415 1191/1191/2415 1086/1086/2415 +f 1086/1086/2416 1191/1191/2416 1211/1211/2416 +f 1086/1086/2417 1211/1211/2418 1087/1087/2419 +f 1087/1087/2419 1211/1211/2418 1212/1212/2420 +f 1087/1087/2412 1212/1212/2421 1177/1177/2413 +f 1186/1186/2422 1134/1134/2423 1180/1180/2424 +f 1180/1180/2424 1134/1134/2423 1133/1133/2425 +f 1133/1133/2426 1187/1187/2427 1180/1180/2428 +f 1094/1094/2429 1187/1187/2427 1133/1133/2426 +f 1134/1134/2430 1186/1186/2430 1135/1135/2430 +f 1135/1135/2431 1186/1186/2431 1213/1213/2431 +f 1135/1135/2432 1213/1213/2432 1136/1136/2432 +f 1136/1136/2433 1213/1213/2434 1214/1214/2435 +f 1136/1136/2433 1214/1214/2435 1096/1096/2436 +f 1096/1096/2437 1214/1214/2438 1094/1094/2439 +f 1094/1094/2439 1214/1214/2438 1187/1187/2440 +f 1102/1102/2441 1171/1171/2442 1099/1099/2443 +f 1099/1099/2443 1171/1171/2442 1173/1173/2444 +f 1103/1103/2445 1171/1171/2446 1102/1102/2447 +f 1171/1171/2446 1103/1103/2445 1176/1176/2448 +f 1099/1099/2449 1173/1173/2450 1100/1100/2451 +f 1100/1100/2451 1173/1173/2450 1215/1215/2452 +f 1100/1100/2453 1215/1215/2454 1101/1101/2455 +f 1101/1101/2455 1215/1215/2454 1216/1216/2456 +f 1101/1101/2457 1216/1216/2458 1097/1097/2459 +f 1097/1097/2459 1216/1216/2458 1217/1217/2460 +f 1097/1097/2461 1217/1217/2462 1103/1103/2463 +f 1103/1103/2463 1217/1217/2462 1176/1176/2464 +f 1142/1142/2465 1144/1144/2130 1205/1205/2466 +f 1217/1217/2467 1175/1175/2245 1176/1176/2468 +f 1213/1213/2469 1211/1211/2470 1214/1214/2471 +f 1193/1193/2472 1197/1197/2473 1163/1163/2474 +f 1214/1214/2471 1181/1181/2239 1187/1187/2254 +f 1165/1165/2475 1162/1162/2476 1168/1168/2477 +f 1145/1145/2118 1206/1206/2478 1147/1147/2479 +f 1147/1147/2479 1206/1206/2478 1151/1151/2480 +f 1205/1205/2466 1141/1141/2129 1140/1140/2481 +f 1151/1151/2480 1206/1206/2478 1140/1140/2481 +f 1140/1140/2481 1208/1208/2482 1151/1151/2480 +f 1208/1208/2482 1207/1207/2483 1151/1151/2480 +f 1207/1207/2483 1158/1158/2484 1148/1148/2485 +f 1162/1162/2476 1204/1204/2486 1158/1158/2484 +f 1162/1162/2476 1160/1160/2487 1168/1168/2477 +f 1161/1161/2488 1170/1170/2489 1163/1163/2474 +f 1163/1163/2474 1170/1170/2489 1193/1193/2472 +f 1194/1194/2490 1192/1192/2295 1210/1210/2491 +f 1205/1205/2466 1144/1144/2130 1141/1141/2129 +f 1149/1149/2140 1203/1203/2492 1152/1152/2141 +f 1198/1198/2294 1210/1210/2491 1192/1192/2295 +f 1209/1209/2493 1194/1194/2490 1210/1210/2491 +f 1211/1211/2470 1194/1194/2490 1209/1209/2493 +f 1194/1194/2490 1167/1167/2494 1197/1197/2473 +f 1197/1197/2473 1167/1167/2494 1160/1160/2487 +f 1178/1178/2495 1212/1212/2496 1209/1209/2493 +f 1200/1200/2497 1178/1178/2495 1209/1209/2493 +f 1206/1206/2478 1205/1205/2466 1140/1140/2481 +f 1202/1202/2498 1162/1162/2476 1165/1165/2475 +f 1204/1204/2486 1202/1202/2498 1153/1153/2150 +f 1204/1204/2486 1153/1153/2150 1150/1150/2149 +f 1167/1167/2494 1168/1168/2477 1160/1160/2487 +f 1177/1177/2499 1212/1212/2496 1178/1178/2495 +f 1217/1217/2467 1216/1216/2500 1213/1213/2469 +f 1148/1148/2485 1203/1203/2492 1149/1149/2140 +f 1165/1165/2475 1166/1166/2501 1202/1202/2498 +f 1204/1204/2486 1150/1150/2149 1138/1138/2502 +f 1202/1202/2498 1156/1156/2159 1153/1153/2150 +f 1183/1183/2266 1211/1211/2470 1191/1191/2503 +f 1204/1204/2486 1203/1203/2492 1158/1158/2484 +f 1211/1211/2470 1169/1169/2504 1194/1194/2490 +f 1158/1158/2484 1203/1203/2492 1148/1148/2485 +f 1204/1204/2486 1162/1162/2476 1202/1202/2498 +f 1189/1189/2265 1211/1211/2470 1183/1183/2266 +f 1169/1169/2504 1167/1167/2494 1194/1194/2490 +f 1207/1207/2483 1148/1148/2485 1151/1151/2480 +f 1169/1169/2504 1211/1211/2470 1174/1174/2505 +f 1216/1216/2500 1215/1215/2506 1174/1174/2505 +f 1213/1213/2469 1184/1184/2246 1217/1217/2467 +f 1174/1174/2505 1215/1215/2506 1173/1173/2507 +f 1212/1212/2496 1211/1211/2470 1209/1209/2493 +f 1216/1216/2500 1211/1211/2470 1213/1213/2469 +f 1188/1188/2508 1211/1211/2470 1189/1189/2265 +f 1174/1174/2505 1211/1211/2470 1216/1216/2500 +f 1214/1214/2471 1211/1211/2470 1188/1188/2508 +f 1182/1182/2240 1214/1214/2471 1188/1188/2508 +f 1175/1175/2245 1217/1217/2467 1184/1184/2246 +f 1197/1197/2473 1160/1160/2487 1163/1163/2474 +f 1206/1206/2478 1145/1145/2118 1139/1139/2106 +f 1182/1182/2240 1181/1181/2239 1214/1214/2471 +f 1184/1184/2246 1213/1213/2469 1186/1186/2250 +f 1218/1218/2509 1219/1219/2510 1220/1220/2511 +f 1221/1221/2512 1222/1222/2513 1223/1223/2514 +f 1224/1224/2515 1219/1219/2510 1218/1218/2509 +f 1221/1221/2512 1225/1225/2516 1222/1222/2513 +f 1226/1226/2517 1227/1227/2518 1225/1225/2516 +f 1218/1218/2509 1220/1220/2511 1228/1228/2519 +f 1223/1223/2514 1219/1219/2510 1224/1224/2515 +f 1221/1221/2512 1223/1223/2514 1224/1224/2515 +f 1226/1226/2517 1225/1225/2516 1221/1221/2512 +f 1228/1228/2519 1227/1227/2518 1218/1218/2509 +f 1218/1218/2509 1227/1227/2518 1226/1226/2517 +f 1229/1229/2520 1230/1230/2521 1231/1231/2522 +f 1232/1232/2523 1233/1233/2524 1234/1234/2525 +f 1232/1232/2523 1234/1234/2525 1235/1235/2526 +f 1235/1235/2527 1234/1234/2528 1231/1231/2529 +f 1235/1235/2527 1231/1231/2529 1236/1236/2530 +f 1236/1236/2531 1231/1231/2531 1237/1237/2531 +f 1236/1236/2532 1237/1237/2532 1238/1238/2532 +f 1238/1238/2533 1237/1237/2534 1239/1239/2535 +f 1238/1238/2536 1239/1239/2537 1232/1232/2538 +f 1232/1232/2538 1239/1239/2537 1233/1233/2539 +f 1222/1222/2540 1232/1232/2540 1223/1223/2540 +f 1223/1223/2541 1232/1232/2542 1219/1219/2543 +f 1219/1219/2543 1232/1232/2542 1235/1235/2544 +f 1219/1219/2545 1235/1235/2546 1236/1236/2547 +f 1219/1219/2545 1236/1236/2547 1220/1220/2548 +f 1220/1220/2549 1236/1236/2549 1228/1228/2549 +f 1228/1228/2550 1236/1236/2551 1227/1227/2552 +f 1227/1227/2552 1236/1236/2551 1238/1238/2553 +f 1227/1227/2554 1238/1238/2554 1225/1225/2554 +f 1225/1225/2555 1238/1238/2556 1232/1232/2557 +f 1225/1225/2555 1232/1232/2557 1222/1222/2558 +f 1226/1226/2517 1221/1221/2512 1218/1218/2509 +f 1218/1218/2509 1221/1221/2512 1224/1224/2515 +f 1233/1233/2524 1229/1229/2559 1234/1234/2525 +f 1234/1234/2560 1229/1229/2520 1231/1231/2522 +f 1237/1237/2561 1231/1231/2522 1230/1230/2521 +f 1237/1237/2534 1230/1230/2562 1239/1239/2535 +f 1239/1239/2563 1230/1230/2564 1233/1233/2565 +f 1233/1233/2565 1230/1230/2564 1229/1229/2566 +f 1240/1240/2567 1241/1241/2568 1242/1242/2569 +f 1243/1243/2570 1244/1244/2571 1245/1245/2572 +f 1240/1240/2567 1246/1246/2573 1241/1241/2568 +f 1247/1247/2574 1242/1242/2569 1241/1241/2568 +f 1245/1245/2572 1248/1248/2575 1243/1243/2570 +f 1249/1249/2576 1247/1247/2574 1250/1250/2577 +f 1250/1250/2577 1247/1247/2574 1241/1241/2568 +f 1251/1251/2578 1249/1249/2576 1250/1250/2577 +f 1241/1241/2568 1246/1246/2573 1243/1243/2570 +f 1243/1243/2570 1246/1246/2573 1244/1244/2571 +f 1243/1243/2570 1248/1248/2575 1251/1251/2578 +f 1243/1243/2570 1251/1251/2578 1250/1250/2577 +f 1252/1252/2579 1253/1253/2580 1254/1254/2581 +f 1252/1252/2579 1255/1255/2582 1253/1253/2580 +f 1252/1252/2579 1254/1254/2581 1256/1256/2583 +f 1257/1257/2584 1258/1258/2585 1259/1259/2586 +f 1259/1259/2587 1258/1258/2588 1260/1260/2589 +f 1260/1260/2589 1258/1258/2588 1261/1261/2590 +f 1260/1260/2591 1261/1261/2592 1262/1262/2593 +f 1260/1260/2591 1262/1262/2593 1256/1256/2594 +f 1256/1256/2595 1262/1262/2596 1263/1263/2597 +f 1256/1256/2595 1263/1263/2597 1252/1252/2598 +f 1252/1252/2599 1263/1263/2600 1255/1255/2601 +f 1263/1263/2600 1264/1264/2602 1255/1255/2601 +f 1255/1255/2603 1264/1264/2604 1265/1265/2605 +f 1265/1265/2605 1264/1264/2604 1266/1266/2606 +f 1265/1265/2607 1266/1266/2608 1253/1253/2609 +f 1253/1253/2609 1266/1266/2608 1257/1257/2584 +f 1253/1253/2609 1257/1257/2584 1259/1259/2586 +f 1257/1257/2610 1267/1267/2611 1258/1258/2612 +f 1262/1262/2613 1268/1268/2614 1263/1263/2615 +f 1257/1257/2610 1269/1269/2616 1267/1267/2611 +f 1266/1266/2617 1269/1269/2616 1257/1257/2610 +f 1261/1261/2618 1270/1270/2619 1268/1268/2614 +f 1261/1261/2618 1268/1268/2614 1262/1262/2613 +f 1261/1261/2618 1271/1271/2620 1270/1270/2619 +f 1264/1264/2621 1272/1272/2622 1266/1266/2617 +f 1266/1266/2617 1272/1272/2622 1269/1269/2616 +f 1264/1264/2621 1273/1273/2623 1272/1272/2622 +f 1258/1258/2612 1271/1271/2620 1261/1261/2618 +f 1258/1258/2612 1267/1267/2611 1271/1271/2620 +f 1263/1263/2615 1273/1273/2623 1264/1264/2621 +f 1263/1263/2615 1268/1268/2614 1273/1273/2623 +f 1267/1267/2624 1240/1240/2625 1242/1242/2626 +f 1267/1267/2627 1242/1242/2628 1271/1271/2629 +f 1242/1242/2628 1247/1247/2630 1271/1271/2629 +f 1271/1271/2631 1247/1247/2632 1249/1249/2633 +f 1271/1271/2631 1249/1249/2633 1270/1270/2634 +f 1270/1270/2634 1249/1249/2633 1251/1251/2635 +f 1270/1270/2634 1251/1251/2635 1268/1268/2636 +f 1268/1268/2637 1251/1251/2638 1248/1248/2639 +f 1268/1268/2637 1248/1248/2639 1273/1273/2640 +f 1248/1248/2639 1245/1245/2641 1273/1273/2640 +f 1273/1273/2642 1245/1245/2643 1244/1244/2644 +f 1273/1273/2642 1244/1244/2644 1272/1272/2645 +f 1272/1272/2646 1244/1244/2647 1246/1246/2648 +f 1272/1272/2646 1246/1246/2648 1269/1269/2649 +f 1269/1269/2649 1246/1246/2648 1240/1240/2625 +f 1269/1269/2649 1240/1240/2625 1267/1267/2624 +f 1243/1243/2650 1250/1250/2651 1274/1274/2652 +f 1274/1274/2652 1250/1250/2651 1275/1275/2653 +f 1241/1241/2654 1243/1243/2655 1276/1276/2656 +f 1276/1276/2656 1243/1243/2655 1274/1274/2657 +f 1250/1250/2658 1241/1241/2659 1275/1275/2660 +f 1275/1275/2660 1241/1241/2659 1276/1276/2661 +f 1275/1275/101 1276/1276/101 1274/1274/101 +f 1265/1265/2662 1253/1253/2580 1255/1255/2582 +f 1260/1260/2663 1256/1256/2583 1254/1254/2581 +f 1260/1260/2589 1254/1254/2664 1259/1259/2587 +f 1259/1259/2665 1254/1254/2581 1253/1253/2580 +f 1277/1277/2666 1278/1278/2667 1279/1279/2668 +f 1277/1277/2666 1280/1280/2669 1278/1278/2667 +f 1281/1281/2670 1282/1282/2671 1283/1283/2672 +f 1284/1284/2673 1285/1285/2674 1280/1280/2669 +f 1284/1284/2673 1280/1280/2669 1277/1277/2666 +f 1286/1286/2675 1285/1285/2674 1284/1284/2673 +f 1277/1277/2666 1279/1279/2668 1282/1282/2671 +f 1277/1277/2666 1282/1282/2671 1281/1281/2670 +f 1281/1281/2670 1283/1283/2672 1286/1286/2675 +f 1281/1281/2670 1286/1286/2675 1284/1284/2673 +f 1287/1287/2676 1288/1288/2677 1289/1289/2678 +f 1290/1290/2679 1288/1288/2677 1287/1287/2676 +f 1291/1291/2680 1292/1292/2681 1293/1293/2682 +f 1291/1291/2680 1293/1293/2682 1294/1294/2683 +f 1294/1294/2684 1293/1293/2685 1295/1295/2686 +f 1294/1294/2684 1295/1295/2686 1290/1290/2687 +f 1290/1290/2688 1295/1295/2689 1296/1296/2690 +f 1296/1296/2690 1295/1295/2689 1297/1297/2691 +f 1296/1296/2692 1297/1297/2693 1298/1298/2694 +f 1296/1296/2692 1298/1298/2694 1288/1288/2695 +f 1288/1288/2696 1298/1298/2697 1299/1299/2698 +f 1288/1288/2696 1299/1299/2698 1289/1289/2699 +f 1289/1289/2700 1299/1299/2701 1292/1292/2702 +f 1289/1289/2700 1292/1292/2702 1291/1291/2703 +f 1292/1292/2704 1300/1300/2705 1293/1293/2706 +f 1293/1293/2706 1300/1300/2705 1301/1301/2707 +f 1297/1297/2708 1302/1302/2709 1303/1303/2710 +f 1299/1299/2711 1304/1304/2712 1292/1292/2704 +f 1292/1292/2704 1304/1304/2712 1300/1300/2705 +f 1295/1295/2713 1302/1302/2709 1297/1297/2708 +f 1295/1295/2713 1305/1305/2714 1302/1302/2709 +f 1298/1298/2715 1304/1304/2712 1299/1299/2711 +f 1298/1298/2715 1306/1306/2716 1304/1304/2712 +f 1293/1293/2706 1307/1307/2717 1295/1295/2713 +f 1295/1295/2713 1307/1307/2717 1305/1305/2714 +f 1293/1293/2706 1301/1301/2707 1307/1307/2717 +f 1297/1297/2708 1303/1303/2710 1298/1298/2715 +f 1298/1298/2715 1303/1303/2710 1306/1306/2716 +f 1300/1300/2718 1278/1278/2719 1301/1301/2720 +f 1301/1301/2720 1278/1278/2719 1280/1280/2721 +f 1301/1301/2720 1280/1280/2721 1307/1307/2722 +f 1280/1280/2721 1285/1285/2723 1307/1307/2722 +f 1307/1307/2722 1285/1285/2723 1305/1305/2724 +f 1305/1305/2725 1285/1285/2726 1302/1302/2727 +f 1285/1285/2726 1286/1286/2728 1302/1302/2727 +f 1302/1302/2729 1286/1286/2730 1303/1303/2731 +f 1303/1303/2731 1286/1286/2730 1283/1283/2732 +f 1303/1303/2733 1283/1283/2734 1306/1306/2735 +f 1306/1306/2735 1283/1283/2734 1282/1282/2736 +f 1306/1306/2737 1282/1282/2737 1304/1304/2737 +f 1304/1304/2738 1282/1282/2739 1279/1279/2740 +f 1304/1304/2738 1279/1279/2740 1300/1300/2718 +f 1279/1279/2740 1278/1278/2719 1300/1300/2718 +f 1281/1281/2741 1284/1284/2742 1308/1308/2743 +f 1308/1308/2743 1284/1284/2742 1309/1309/2744 +f 1277/1277/2745 1281/1281/2746 1310/1310/2747 +f 1310/1310/2747 1281/1281/2746 1308/1308/2748 +f 1284/1284/2749 1277/1277/2750 1309/1309/2751 +f 1309/1309/2751 1277/1277/2750 1310/1310/2752 +f 1309/1309/101 1310/1310/101 1308/1308/101 +f 1296/1296/2753 1288/1288/2677 1290/1290/2679 +f 1294/1294/2754 1290/1290/2754 1287/1287/2754 +f 1294/1294/2683 1287/1287/2755 1291/1291/2680 +f 1291/1291/2756 1287/1287/2676 1289/1289/2678 +f 1311/1311/2757 1312/1312/2758 1313/1313/2759 +f 1314/1314/2760 1315/1315/2761 1316/1316/2762 +f 1315/1315/2761 1317/1317/2763 1316/1316/2762 +f 1316/1316/2762 1317/1317/2763 1318/1318/2764 +f 1313/1313/2759 1319/1319/2765 1311/1311/2757 +f 1320/1320/2766 1321/1321/2767 1316/1316/2762 +f 1318/1318/2764 1317/1317/2763 1311/1311/2757 +f 1311/1311/2757 1317/1317/2763 1312/1312/2758 +f 1316/1316/2762 1321/1321/2767 1314/1314/2760 +f 1311/1311/2757 1319/1319/2765 1320/1320/2766 +f 1320/1320/2766 1319/1319/2765 1321/1321/2767 +f 1322/1322/2768 1323/1323/2769 1324/1324/2770 +f 1322/1322/2768 1325/1325/2771 1323/1323/2769 +f 1322/1322/2768 1326/1326/2772 1325/1325/2771 +f 1323/1323/2773 1327/1327/2774 1324/1324/2775 +f 1327/1327/2774 1328/1328/2776 1324/1324/2775 +f 1324/1324/2777 1328/1328/2778 1322/1322/2779 +f 1328/1328/2778 1329/1329/2780 1322/1322/2779 +f 1322/1322/2779 1329/1329/2780 1330/1330/2781 +f 1330/1330/2781 1329/1329/2780 1331/1331/2782 +f 1330/1330/2783 1331/1331/2784 1332/1332/2785 +f 1331/1331/2784 1333/1333/2786 1332/1332/2785 +f 1332/1332/2787 1333/1333/2788 1325/1325/2789 +f 1333/1333/2788 1334/1334/2790 1325/1325/2789 +f 1325/1325/2791 1334/1334/2792 1323/1323/2793 +f 1323/1323/2793 1334/1334/2792 1327/1327/2794 +f 1327/1327/2795 1335/1335/2796 1328/1328/2797 +f 1328/1328/2797 1335/1335/2796 1336/1336/2798 +f 1331/1331/2799 1337/1337/2800 1333/1333/2801 +f 1327/1327/2795 1338/1338/2802 1335/1335/2796 +f 1331/1331/2799 1339/1339/2803 1337/1337/2800 +f 1329/1329/2804 1340/1340/2805 1339/1339/2803 +f 1329/1329/2804 1339/1339/2803 1331/1331/2799 +f 1334/1334/2806 1341/1341/2807 1327/1327/2795 +f 1327/1327/2795 1341/1341/2807 1338/1338/2802 +f 1329/1329/2804 1336/1336/2798 1340/1340/2805 +f 1328/1328/2797 1336/1336/2798 1329/1329/2804 +f 1333/1333/2801 1342/1342/2808 1341/1341/2807 +f 1333/1333/2801 1341/1341/2807 1334/1334/2806 +f 1333/1333/2801 1337/1337/2800 1342/1342/2808 +f 1335/1335/2809 1315/1315/2810 1336/1336/2811 +f 1315/1315/2810 1314/1314/2812 1336/1336/2811 +f 1336/1336/2813 1314/1314/2814 1340/1340/2815 +f 1340/1340/2815 1314/1314/2814 1321/1321/2816 +f 1340/1340/2815 1321/1321/2816 1339/1339/2817 +f 1339/1339/2818 1321/1321/2819 1319/1319/2820 +f 1339/1339/2818 1319/1319/2820 1337/1337/2821 +f 1337/1337/2822 1319/1319/2823 1342/1342/2824 +f 1319/1319/2823 1313/1313/2825 1342/1342/2824 +f 1342/1342/2826 1313/1313/2827 1341/1341/2828 +f 1313/1313/2827 1312/1312/2829 1341/1341/2828 +f 1341/1341/2830 1312/1312/2831 1338/1338/2832 +f 1312/1312/2831 1317/1317/2833 1338/1338/2832 +f 1338/1338/2832 1317/1317/2833 1335/1335/2809 +f 1335/1335/2809 1317/1317/2833 1315/1315/2810 +f 1311/1311/2834 1320/1320/2835 1343/1343/2836 +f 1343/1343/2836 1320/1320/2835 1344/1344/2837 +f 1318/1318/2838 1311/1311/2839 1345/1345/2840 +f 1345/1345/2840 1311/1311/2839 1343/1343/2841 +f 1316/1316/2842 1318/1318/2843 1346/1346/2844 +f 1346/1346/2844 1318/1318/2843 1345/1345/2845 +f 1320/1320/2846 1316/1316/2847 1344/1344/2848 +f 1344/1344/2848 1316/1316/2847 1346/1346/2849 +f 1344/1344/101 1346/1346/101 1345/1345/101 +f 1344/1344/101 1345/1345/101 1343/1343/101 +f 1332/1332/2850 1325/1325/2771 1326/1326/2772 +f 1332/1332/2785 1326/1326/2851 1330/1330/2783 +f 1330/1330/2852 1326/1326/2852 1322/1322/2852 +f 1347/1347/2853 1348/1348/2854 1349/1349/2855 +f 1350/1350/2856 1348/1348/2854 1347/1347/2853 +f 1351/1351/2857 1352/1352/2858 1353/1353/2859 +f 1354/1354/2860 1355/1355/2861 1350/1350/2856 +f 1354/1354/2860 1356/1356/2862 1355/1355/2861 +f 1352/1352/2858 1357/1357/2863 1353/1353/2859 +f 1358/1358/2864 1352/1352/2858 1351/1351/2857 +f 1357/1357/2863 1356/1356/2862 1353/1353/2859 +f 1347/1347/2853 1349/1349/2855 1351/1351/2857 +f 1351/1351/2857 1349/1349/2855 1358/1358/2864 +f 1354/1354/2860 1350/1350/2856 1347/1347/2853 +f 1353/1353/2859 1356/1356/2862 1354/1354/2860 +f 1359/1359/2865 1360/1360/2866 1361/1361/2867 +f 1362/1362/2868 1363/1363/2869 1364/1364/2870 +f 1364/1364/2870 1363/1363/2869 1365/1365/2871 +f 1364/1364/2872 1365/1365/2873 1366/1366/2874 +f 1364/1364/2872 1366/1366/2874 1367/1367/2875 +f 1367/1367/2876 1366/1366/2876 1368/1368/2876 +f 1367/1367/2877 1368/1368/2877 1369/1369/2877 +f 1369/1369/2878 1368/1368/2879 1370/1370/2880 +f 1369/1369/2878 1370/1370/2880 1371/1371/2881 +f 1371/1371/2882 1370/1370/2883 1363/1363/2884 +f 1371/1371/2882 1363/1363/2884 1362/1362/2885 +f 1348/1348/2886 1362/1362/2887 1349/1349/2888 +f 1349/1349/2888 1362/1362/2887 1364/1364/2889 +f 1349/1349/2888 1364/1364/2889 1358/1358/2890 +f 1358/1358/2891 1364/1364/2892 1352/1352/2893 +f 1352/1352/2893 1364/1364/2892 1367/1367/2894 +f 1352/1352/2893 1367/1367/2894 1357/1357/2895 +f 1357/1357/2896 1367/1367/2897 1356/1356/2898 +f 1356/1356/2898 1367/1367/2897 1369/1369/2899 +f 1356/1356/2898 1369/1369/2899 1355/1355/2900 +f 1355/1355/2900 1369/1369/2899 1371/1371/2901 +f 1355/1355/2900 1371/1371/2901 1350/1350/2902 +f 1350/1350/2902 1371/1371/2901 1348/1348/2886 +f 1348/1348/2886 1371/1371/2901 1362/1362/2887 +f 1354/1354/2860 1347/1347/2853 1353/1353/2859 +f 1353/1353/2859 1347/1347/2853 1351/1351/2857 +f 1363/1363/2869 1361/1361/2903 1365/1365/2871 +f 1365/1365/2904 1361/1361/2867 1360/1360/2866 +f 1365/1365/2905 1360/1360/2905 1366/1366/2905 +f 1366/1366/2906 1360/1360/2906 1368/1368/2906 +f 1368/1368/2907 1360/1360/2866 1359/1359/2865 +f 1368/1368/2879 1359/1359/2908 1370/1370/2880 +f 1370/1370/2909 1359/1359/2910 1363/1363/2911 +f 1363/1363/2911 1359/1359/2910 1361/1361/2912 +f 1372/1372/2913 1373/1373/2914 1374/1374/2915 +f 1375/1375/2916 1376/1376/2917 1377/1377/2918 +f 1378/1378/2919 1379/1379/2920 1380/1380/2921 +f 1381/1381/2922 1373/1373/2914 1372/1372/2913 +f 1382/1382/2923 1373/1373/2914 1381/1381/2922 +f 1377/1377/2918 1379/1379/2920 1378/1378/2919 +f 1374/1374/2915 1383/1383/2924 1372/1372/2913 +f 1372/1372/2913 1383/1383/2924 1376/1376/2917 +f 1378/1378/2919 1380/1380/2921 1381/1381/2922 +f 1381/1381/2922 1380/1380/2921 1382/1382/2923 +f 1375/1375/2916 1377/1377/2918 1378/1378/2919 +f 1372/1372/2913 1376/1376/2917 1375/1375/2916 +f 1384/1384/2925 1385/1385/2926 1386/1386/2927 +f 1387/1387/2928 1388/1388/2929 1389/1389/2930 +f 1389/1389/2930 1388/1388/2929 1390/1390/2931 +f 1389/1389/2932 1390/1390/2933 1391/1391/2934 +f 1391/1391/2934 1390/1390/2933 1392/1392/2935 +f 1391/1391/2936 1392/1392/2936 1393/1393/2936 +f 1393/1393/2937 1392/1392/2938 1394/1394/2939 +f 1393/1393/2940 1394/1394/2940 1395/1395/2940 +f 1395/1395/2941 1394/1394/2942 1388/1388/2943 +f 1395/1395/2941 1388/1388/2943 1387/1387/2944 +f 1379/1379/2945 1387/1387/2946 1380/1380/2947 +f 1380/1380/2947 1387/1387/2946 1389/1389/2948 +f 1380/1380/2947 1389/1389/2948 1382/1382/2949 +f 1382/1382/2950 1389/1389/2951 1373/1373/2952 +f 1373/1373/2952 1389/1389/2951 1391/1391/2953 +f 1373/1373/2952 1391/1391/2953 1374/1374/2954 +f 1374/1374/2955 1391/1391/2956 1393/1393/2957 +f 1374/1374/2955 1393/1393/2957 1383/1383/2958 +f 1383/1383/2959 1393/1393/2959 1376/1376/2959 +f 1376/1376/2960 1393/1393/2961 1395/1395/2962 +f 1376/1376/2960 1395/1395/2962 1377/1377/2963 +f 1377/1377/2964 1395/1395/2965 1379/1379/2945 +f 1379/1379/2945 1395/1395/2965 1387/1387/2946 +f 1375/1375/2916 1378/1378/2919 1372/1372/2913 +f 1372/1372/2913 1378/1378/2919 1381/1381/2922 +f 1388/1388/2929 1386/1386/2966 1390/1390/2931 +f 1390/1390/2967 1386/1386/2927 1385/1385/2926 +f 1390/1390/2933 1385/1385/2968 1392/1392/2935 +f 1392/1392/2969 1385/1385/2969 1384/1384/2969 +f 1392/1392/2938 1384/1384/2970 1394/1394/2939 +f 1394/1394/2971 1384/1384/2972 1386/1386/2973 +f 1394/1394/2971 1386/1386/2973 1388/1388/2974 +f 1396/1396/2975 1397/1397/2976 1398/1398/2977 +f 1399/1399/2978 1400/1400/2979 1401/1401/2980 +f 1399/1399/2978 1402/1402/2981 1400/1400/2979 +f 1403/1403/2982 1396/1396/2975 1398/1398/2977 +f 1403/1403/2982 1404/1404/2983 1396/1396/2975 +f 1397/1397/2976 1405/1405/2984 1398/1398/2977 +f 1399/1399/2978 1401/1401/2980 1403/1403/2982 +f 1403/1403/2982 1401/1401/2980 1404/1404/2983 +f 1406/1406/2985 1402/1402/2981 1407/1407/2986 +f 1407/1407/2986 1402/1402/2981 1399/1399/2978 +f 1398/1398/2977 1405/1405/2984 1407/1407/2986 +f 1407/1407/2986 1405/1405/2984 1406/1406/2985 +f 1408/1408/2987 1409/1409/2988 1410/1410/2989 +f 1411/1411/2990 1412/1412/2990 1409/1409/2990 +f 1411/1411/2991 1409/1409/2992 1413/1413/2993 +f 1411/1411/2991 1413/1413/2993 1414/1414/2994 +f 1414/1414/2995 1413/1413/2996 1415/1415/2997 +f 1414/1414/2995 1415/1415/2997 1416/1416/2998 +f 1416/1416/2999 1415/1415/3000 1417/1417/3001 +f 1416/1416/2999 1417/1417/3001 1418/1418/3002 +f 1418/1418/3003 1417/1417/3004 1412/1412/3005 +f 1418/1418/3006 1412/1412/3006 1411/1411/3006 +f 1400/1400/3007 1411/1411/3007 1401/1401/3007 +f 1401/1401/3008 1411/1411/3009 1414/1414/3010 +f 1401/1401/3008 1414/1414/3010 1404/1404/3011 +f 1404/1404/3012 1414/1414/3012 1396/1396/3012 +f 1396/1396/3013 1414/1414/3014 1397/1397/3015 +f 1397/1397/3015 1414/1414/3014 1416/1416/3016 +f 1397/1397/3015 1416/1416/3016 1405/1405/3017 +f 1405/1405/3018 1416/1416/3019 1418/1418/3020 +f 1405/1405/3018 1418/1418/3020 1406/1406/3021 +f 1406/1406/3022 1418/1418/3022 1402/1402/3022 +f 1402/1402/3023 1418/1418/3024 1400/1400/3025 +f 1400/1400/3025 1418/1418/3024 1411/1411/3026 +f 1407/1407/2986 1399/1399/2978 1398/1398/2977 +f 1398/1398/2977 1399/1399/2978 1403/1403/2982 +f 1412/1412/3027 1410/1410/3027 1409/1409/3027 +f 1413/1413/3028 1409/1409/2988 1408/1408/2987 +f 1413/1413/2996 1408/1408/3029 1415/1415/2997 +f 1415/1415/3030 1408/1408/3031 1410/1410/3032 +f 1415/1415/3030 1410/1410/3032 1417/1417/3033 +f 1417/1417/3004 1410/1410/3034 1412/1412/3005 +f 1419/1419/3035 1420/1420/3036 1421/1421/3037 +f 1422/1422/3038 1423/1423/3039 1424/1424/3040 +f 1425/1425/3041 1426/1426/3042 1427/1427/3043 +f 1428/1428/3044 1419/1419/3035 1421/1421/3037 +f 1421/1421/3037 1420/1420/3036 1429/1429/3045 +f 1428/1428/3044 1430/1430/3046 1419/1419/3035 +f 1427/1427/3043 1423/1423/3039 1422/1422/3038 +f 1429/1429/3045 1426/1426/3042 1421/1421/3037 +f 1424/1424/3040 1430/1430/3046 1422/1422/3038 +f 1422/1422/3038 1430/1430/3046 1428/1428/3044 +f 1425/1425/3041 1427/1427/3043 1422/1422/3038 +f 1421/1421/3037 1426/1426/3042 1425/1425/3041 +f 1431/1431/3047 1432/1432/3048 1433/1433/3049 +f 1434/1434/3050 1432/1432/3050 1435/1435/3050 +f 1434/1434/3051 1435/1435/3051 1436/1436/3051 +f 1436/1436/3052 1435/1435/3053 1437/1437/3054 +f 1436/1436/3055 1437/1437/3056 1438/1438/3057 +f 1438/1438/3057 1437/1437/3056 1439/1439/3058 +f 1438/1438/3059 1439/1439/3060 1440/1440/3061 +f 1440/1440/3061 1439/1439/3060 1441/1441/3062 +f 1440/1440/3063 1441/1441/3064 1432/1432/3065 +f 1440/1440/3063 1432/1432/3065 1434/1434/3066 +f 1423/1423/3067 1434/1434/3068 1424/1424/3069 +f 1424/1424/3070 1434/1434/3071 1430/1430/3072 +f 1430/1430/3072 1434/1434/3071 1436/1436/3073 +f 1430/1430/3072 1436/1436/3073 1419/1419/3074 +f 1419/1419/3075 1436/1436/3075 1420/1420/3075 +f 1420/1420/3076 1436/1436/3077 1429/1429/3078 +f 1429/1429/3078 1436/1436/3077 1438/1438/3079 +f 1429/1429/3080 1438/1438/3081 1426/1426/3082 +f 1426/1426/3082 1438/1438/3081 1440/1440/3083 +f 1426/1426/3082 1440/1440/3083 1427/1427/3084 +f 1427/1427/3085 1440/1440/3086 1423/1423/3067 +f 1423/1423/3067 1440/1440/3086 1434/1434/3068 +f 1425/1425/3041 1422/1422/3038 1421/1421/3037 +f 1421/1421/3037 1422/1422/3038 1428/1428/3044 +f 1435/1435/3087 1432/1432/3048 1431/1431/3047 +f 1435/1435/3053 1431/1431/3088 1437/1437/3054 +f 1437/1437/3089 1431/1431/3090 1439/1439/3091 +f 1439/1439/3091 1431/1431/3090 1433/1433/3092 +f 1439/1439/3060 1433/1433/3093 1441/1441/3062 +f 1441/1441/3094 1433/1433/3094 1432/1432/3094 +f 1442/1442/3095 1443/1443/3096 1444/1444/3097 +f 1445/1445/3098 1446/1446/3099 1447/1447/3100 +f 1443/1443/3096 1442/1442/3095 1448/1448/3101 +f 1449/1449/3102 1445/1445/3098 1447/1447/3100 +f 1450/1450/3103 1451/1451/3104 1452/1452/3105 +f 1449/1449/3102 1453/1453/3106 1445/1445/3098 +f 1452/1452/3105 1448/1448/3101 1442/1442/3095 +f 1447/1447/3100 1446/1446/3099 1454/1454/3107 +f 1454/1454/3107 1451/1451/3104 1447/1447/3100 +f 1442/1442/3095 1444/1444/3097 1449/1449/3102 +f 1449/1449/3102 1444/1444/3097 1453/1453/3106 +f 1450/1450/3103 1452/1452/3105 1442/1442/3095 +f 1447/1447/3100 1451/1451/3104 1450/1450/3103 +f 1455/1455/3108 1456/1456/3109 1457/1457/3110 +f 1455/1455/3108 1458/1458/3111 1456/1456/3109 +f 1459/1459/3112 1460/1460/3113 1461/1461/3114 +f 1459/1459/3115 1461/1461/3116 1462/1462/3117 +f 1462/1462/3117 1461/1461/3116 1463/1463/3118 +f 1462/1462/3119 1463/1463/3120 1464/1464/3121 +f 1464/1464/3121 1463/1463/3120 1457/1457/3122 +f 1464/1464/3123 1457/1457/3124 1465/1465/3125 +f 1465/1465/3125 1457/1457/3124 1456/1456/3126 +f 1465/1465/3127 1456/1456/3128 1460/1460/3129 +f 1465/1465/3127 1460/1460/3129 1466/1466/3130 +f 1466/1466/3131 1460/1460/3113 1459/1459/3112 +f 1443/1443/3132 1459/1459/3133 1444/1444/3134 +f 1444/1444/3134 1459/1459/3133 1453/1453/3135 +f 1453/1453/3135 1459/1459/3133 1462/1462/3136 +f 1453/1453/3135 1462/1462/3136 1445/1445/3137 +f 1445/1445/3138 1462/1462/3139 1464/1464/3140 +f 1445/1445/3138 1464/1464/3140 1446/1446/3141 +f 1446/1446/3142 1464/1464/3143 1465/1465/3144 +f 1446/1446/3142 1465/1465/3144 1454/1454/3145 +f 1454/1454/3145 1465/1465/3144 1451/1451/3146 +f 1451/1451/3146 1465/1465/3144 1452/1452/3147 +f 1452/1452/3147 1465/1465/3144 1466/1466/3148 +f 1452/1452/3147 1466/1466/3148 1448/1448/3149 +f 1448/1448/3150 1466/1466/3151 1443/1443/3132 +f 1443/1443/3132 1466/1466/3151 1459/1459/3133 +f 1450/1450/3103 1442/1442/3095 1447/1447/3100 +f 1447/1447/3100 1442/1442/3095 1449/1449/3102 +f 1460/1460/3152 1458/1458/3153 1455/1455/3154 +f 1460/1460/3152 1455/1455/3154 1461/1461/3155 +f 1461/1461/3116 1455/1455/3156 1463/1463/3118 +f 1463/1463/3157 1455/1455/3108 1457/1457/3110 +f 1460/1460/3158 1456/1456/3158 1458/1458/3158 +f 1467/1467/3159 1468/1468/3160 1469/1469/3161 +f 1470/1470/3162 1471/1471/3163 1472/1472/3164 +f 1473/1473/3165 1474/1474/3166 1472/1472/3164 +f 1467/1467/3159 1475/1475/3167 1468/1468/3160 +f 1476/1476/3168 1471/1471/3163 1477/1477/3169 +f 1472/1472/3164 1474/1474/3166 1478/1478/3170 +f 1473/1473/3165 1479/1479/3171 1474/1474/3166 +f 1478/1478/3170 1470/1470/3162 1472/1472/3164 +f 1467/1467/3159 1469/1469/3161 1473/1473/3165 +f 1473/1473/3165 1469/1469/3161 1479/1479/3171 +f 1477/1477/3169 1475/1475/3167 1476/1476/3168 +f 1476/1476/3168 1475/1475/3167 1467/1467/3159 +f 1472/1472/3164 1471/1471/3163 1476/1476/3168 +f 1480/1480/3172 1481/1481/3173 1482/1482/3174 +f 1483/1483/3175 1482/1482/3176 1484/1484/3177 +f 1483/1483/3175 1484/1484/3177 1485/1485/3178 +f 1485/1485/3179 1484/1484/3180 1481/1481/3181 +f 1485/1485/3179 1481/1481/3181 1486/1486/3182 +f 1486/1486/3183 1481/1481/3183 1487/1487/3183 +f 1486/1486/3184 1487/1487/3184 1488/1488/3184 +f 1488/1488/3185 1487/1487/3186 1489/1489/3187 +f 1488/1488/3188 1489/1489/3188 1490/1490/3188 +f 1490/1490/3189 1489/1489/3190 1482/1482/3191 +f 1490/1490/3189 1482/1482/3191 1483/1483/3192 +f 1468/1468/3193 1483/1483/3194 1469/1469/3195 +f 1469/1469/3195 1483/1483/3194 1479/1479/3196 +f 1479/1479/3196 1483/1483/3194 1485/1485/3197 +f 1479/1479/3198 1485/1485/3199 1474/1474/3200 +f 1474/1474/3200 1485/1485/3199 1478/1478/3201 +f 1478/1478/3201 1485/1485/3199 1486/1486/3202 +f 1478/1478/3203 1486/1486/3204 1470/1470/3205 +f 1470/1470/3205 1486/1486/3204 1488/1488/3206 +f 1470/1470/3205 1488/1488/3206 1471/1471/3207 +f 1471/1471/3207 1488/1488/3206 1491/1491/3208 +f 1491/1491/3209 1488/1488/3210 1477/1477/3211 +f 1477/1477/3211 1488/1488/3210 1490/1490/3212 +f 1477/1477/3211 1490/1490/3212 1475/1475/3213 +f 1475/1475/3213 1490/1490/3212 1468/1468/3193 +f 1468/1468/3193 1490/1490/3212 1483/1483/3194 +f 1471/1471/3163 1491/1491/3214 1477/1477/3169 +f 1476/1476/3168 1467/1467/3159 1472/1472/3164 +f 1472/1472/3164 1467/1467/3159 1473/1473/3165 +f 1484/1484/3215 1482/1482/3174 1481/1481/3173 +f 1481/1481/3216 1480/1480/3216 1487/1487/3216 +f 1487/1487/3186 1480/1480/3217 1489/1489/3187 +f 1489/1489/3218 1480/1480/3218 1482/1482/3218 +f 1492/1492/3219 1493/1493/3220 1494/1494/3221 +f 1495/1495/3222 1496/1496/3223 1497/1497/3224 +f 1493/1493/3220 1492/1492/3219 1498/1498/3225 +f 1499/1499/3226 1495/1495/3222 1497/1497/3224 +f 1497/1497/3224 1496/1496/3223 1500/1500/3227 +f 1499/1499/3226 1494/1494/3221 1495/1495/3222 +f 1500/1500/3227 1501/1501/3228 1497/1497/3224 +f 1492/1492/3219 1494/1494/3221 1499/1499/3226 +f 1501/1501/3228 1498/1498/3225 1502/1502/3229 +f 1502/1502/3229 1498/1498/3225 1492/1492/3219 +f 1497/1497/3224 1501/1501/3228 1502/1502/3229 +f 1503/1503/3230 1504/1504/3231 1505/1505/3232 +f 1505/1505/3232 1504/1504/3231 1506/1506/3233 +f 1507/1507/3234 1508/1508/3234 1509/1509/3234 +f 1509/1509/3235 1508/1508/3236 1503/1503/3237 +f 1509/1509/3235 1503/1503/3237 1510/1510/3238 +f 1510/1510/3238 1503/1503/3237 1511/1511/3239 +f 1510/1510/3240 1511/1511/3240 1512/1512/3240 +f 1512/1512/3241 1511/1511/3242 1513/1513/3243 +f 1512/1512/3244 1513/1513/3245 1514/1514/3246 +f 1514/1514/3246 1513/1513/3245 1506/1506/3247 +f 1514/1514/3248 1506/1506/3249 1504/1504/3250 +f 1514/1514/3248 1504/1504/3250 1507/1507/3251 +f 1507/1507/3252 1504/1504/3252 1508/1508/3252 +f 1493/1493/3253 1507/1507/3254 1494/1494/3255 +f 1494/1494/3255 1507/1507/3254 1509/1509/3256 +f 1494/1494/3257 1509/1509/3258 1495/1495/3259 +f 1495/1495/3259 1509/1509/3258 1510/1510/3260 +f 1495/1495/3259 1510/1510/3260 1496/1496/3261 +f 1496/1496/3261 1510/1510/3260 1512/1512/3262 +f 1496/1496/3261 1512/1512/3262 1500/1500/3263 +f 1500/1500/3264 1512/1512/3265 1501/1501/3266 +f 1501/1501/3266 1512/1512/3265 1514/1514/3267 +f 1501/1501/3268 1514/1514/3269 1498/1498/3270 +f 1498/1498/3270 1514/1514/3269 1507/1507/3271 +f 1498/1498/3270 1507/1507/3271 1493/1493/3272 +f 1502/1502/3229 1492/1492/3219 1497/1497/3224 +f 1497/1497/3224 1492/1492/3219 1499/1499/3226 +f 1508/1508/3273 1504/1504/3231 1503/1503/3230 +f 1503/1503/3274 1505/1505/3274 1511/1511/3274 +f 1511/1511/3242 1505/1505/3275 1513/1513/3243 +f 1513/1513/3276 1505/1505/3276 1506/1506/3276 +f 1515/1515/3277 1516/1516/3278 1517/1517/3279 +f 1518/1518/3280 1519/1519/3281 1520/1520/3282 +f 1516/1516/3278 1518/1518/3280 1521/1521/3283 +f 1522/1522/3284 1523/1523/3283 1524/1524/3285 +f 1519/1519/3281 1525/1525/3283 1526/1526/3283 +f 1527/1527/3283 1528/1528/3283 1529/1529/3286 +f 1521/1521/3283 1518/1518/3280 1520/1520/3282 +f 1515/1515/3277 1517/1517/3279 1530/1530/3287 +f 1526/1526/3283 1531/1531/3283 1532/1532/3283 +f 1526/1526/3283 1525/1525/3283 1531/1531/3283 +f 1533/1533/3288 1534/1534/3283 1535/1535/3289 +f 1536/1536/3283 1521/1521/3283 1537/1537/3280 +f 1537/1537/3280 1538/1538/3283 1536/1536/3283 +f 1539/1539/3290 1540/1540/3283 1541/1541/3291 +f 1542/1542/3283 1543/1543/3291 1544/1544/3288 +f 1532/1532/3283 1545/1545/3283 1546/1546/3291 +f 1546/1546/3291 1523/1523/3283 1537/1537/3280 +f 1547/1547/3292 1522/1522/3284 1524/1524/3285 +f 1530/1530/3287 1536/1536/3283 1548/1548/3293 +f 1515/1515/3277 1530/1530/3287 1548/1548/3293 +f 1540/1540/3283 1529/1529/3286 1541/1541/3291 +f 1548/1548/3293 1538/1538/3283 1549/1549/3283 +f 1545/1545/3283 1532/1532/3283 1539/1539/3290 +f 1519/1519/3281 1518/1518/3280 1525/1525/3283 +f 1550/1550/3280 1543/1543/3291 1542/1542/3283 +f 1539/1539/3290 1541/1541/3291 1551/1551/3294 +f 1521/1521/3283 1520/1520/3282 1537/1537/3280 +f 1523/1523/3283 1542/1542/3283 1534/1534/3283 +f 1548/1548/3293 1549/1549/3283 1552/1552/3295 +f 1523/1523/3283 1546/1546/3291 1550/1550/3280 +f 1532/1532/3283 1540/1540/3283 1539/1539/3290 +f 1528/1528/3283 1527/1527/3283 1525/1525/3283 +f 1547/1547/3292 1548/1548/3293 1552/1552/3295 +f 1516/1516/3278 1515/1515/3277 1518/1518/3280 +f 1532/1532/3283 1546/1546/3291 1526/1526/3283 +f 1545/1545/3283 1550/1550/3280 1546/1546/3291 +f 1523/1523/3283 1538/1538/3283 1537/1537/3280 +f 1552/1552/3295 1522/1522/3284 1547/1547/3292 +f 1553/1553/3283 1551/1551/3294 1541/1541/3291 +f 1527/1527/3283 1531/1531/3283 1525/1525/3283 +f 1529/1529/3286 1528/1528/3283 1541/1541/3291 +f 1553/1553/3283 1554/1554/3291 1544/1544/3288 +f 1534/1534/3283 1524/1524/3285 1523/1523/3283 +f 1553/1553/3283 1544/1544/3288 1543/1543/3291 +f 1533/1533/3288 1524/1524/3285 1534/1534/3283 +f 1555/1555/3291 1542/1542/3283 1544/1544/3288 +f 1554/1554/3291 1541/1541/3291 1556/1556/3283 +f 1535/1535/3289 1557/1557/3296 1533/1533/3288 +f 1541/1541/3291 1558/1558/3291 1556/1556/3283 +f 1555/1555/3291 1544/1544/3288 1559/1559/3297 +f 1559/1559/3297 1558/1558/3291 1555/1555/3291 +f 1557/1557/3296 1560/1560/3298 1533/1533/3288 +f 1558/1558/3291 1561/1561/3291 1555/1555/3291 +f 1561/1561/3291 1557/1557/3296 1535/1535/3289 +f 1562/1562/3288 1558/1558/3291 1559/1559/3297 +f 1557/1557/3296 1563/1563/3299 1560/1560/3298 +f 1560/1560/3298 1563/1563/3299 1564/1564/3300 +f 1547/1547/3292 1564/1564/3300 1563/1563/3299 +f 1562/1562/3288 1556/1556/3283 1558/1558/3291 +f 1523/1523/3283 1550/1550/3280 1542/1542/3283 +f 1553/1553/3283 1541/1541/3291 1554/1554/3291 +f 1548/1548/3293 1536/1536/3283 1538/1538/3283 +f 1558/1558/3291 1557/1557/3296 1561/1561/3291 +f 1539/1539/3301 1565/1565/3301 1545/1545/3301 +f 1566/1566/3302 1551/1551/3303 1553/1553/3304 +f 1567/1567/3305 1551/1551/3303 1566/1566/3302 +f 1567/1567/3306 1539/1539/3307 1551/1551/3308 +f 1565/1565/3309 1539/1539/3307 1567/1567/3306 +f 1568/1568/3310 1552/1552/3311 1569/1569/3312 +f 1568/1568/3313 1522/1522/3314 1552/1552/3315 +f 1570/1570/3316 1522/1522/3314 1568/1568/3313 +f 1570/1570/3317 1523/1523/3318 1522/1522/3319 +f 1571/1571/3320 1523/1523/3318 1570/1570/3317 +f 1572/1572/3321 1523/1523/3322 1571/1571/3323 +f 1572/1572/3321 1538/1538/3324 1523/1523/3322 +f 1573/1573/3325 1538/1538/3325 1572/1572/3325 +f 1573/1573/3326 1549/1549/3326 1538/1538/3326 +f 1569/1569/3327 1549/1549/3327 1573/1573/3327 +f 1569/1569/3312 1552/1552/3311 1549/1549/3328 +f 1574/1574/3329 1575/1575/3330 1576/1576/3331 +f 1574/1574/3329 1577/1577/3332 1575/1575/3330 +f 1578/1578/3333 1579/1579/3334 1580/1580/3335 +f 1578/1578/3336 1580/1580/3337 1577/1577/3338 +f 1578/1578/3336 1577/1577/3338 1574/1574/3339 +f 1581/1581/3340 1582/1582/3341 1583/1583/3342 +f 1577/1577/3343 1582/1582/3341 1581/1581/3340 +f 1580/1580/3344 1582/1582/3341 1577/1577/3343 +f 1583/1583/3342 1584/1584/3345 1581/1581/3340 +f 1584/1584/3346 1585/1585/3347 1581/1581/3348 +f 1586/1586/3349 1587/1587/3350 1588/1588/3351 +f 1589/1589/3352 1590/1590/3353 1591/1591/3354 +f 1589/1589/3352 1592/1592/3355 1590/1590/3353 +f 1588/1588/3351 1587/1587/3350 1591/1591/3354 +f 1588/1588/3351 1591/1591/3354 1590/1590/3353 +f 1593/1593/3356 1588/1588/3351 1585/1585/3347 +f 1585/1585/3347 1588/1588/3351 1590/1590/3353 +f 1584/1584/3346 1593/1593/3356 1585/1585/3347 +f 1592/1592/3355 1594/1594/3357 1590/1590/3353 +f 1595/1595/3358 1578/1578/3359 1574/1574/3360 +f 1594/1594/3361 1595/1595/3358 1574/1574/3360 +f 1594/1594/3361 1596/1596/3362 1595/1595/3358 +f 1594/1594/3361 1592/1592/3363 1596/1596/3362 +f 1594/1594/3364 1558/1558/3364 1590/1590/3364 +f 1528/1528/3365 1581/1581/3365 1585/1585/3365 +f 1563/1563/3366 1574/1574/3367 1576/1576/3368 +f 1594/1594/3369 1557/1557/3370 1558/1558/3371 +f 1574/1574/3367 1557/1557/3370 1594/1594/3369 +f 1574/1574/3367 1563/1563/3366 1557/1557/3370 +f 1577/1577/3372 1515/1515/3373 1575/1575/3374 +f 1577/1577/3372 1518/1518/3375 1515/1515/3373 +f 1581/1581/3376 1518/1518/3375 1577/1577/3372 +f 1581/1581/3376 1525/1525/3377 1518/1518/3375 +f 1581/1581/3376 1528/1528/3378 1525/1525/3377 +f 1585/1585/3379 1541/1541/3380 1528/1528/3381 +f 1590/1590/3382 1541/1541/3380 1585/1585/3379 +f 1590/1590/3382 1558/1558/3383 1541/1541/3380 +f 1597/1597/3384 1583/1583/3385 1598/1598/3386 +f 1597/1597/3384 1599/1599/3387 1583/1583/3385 +f 1582/1582/3388 1600/1600/3389 1601/1601/3390 +f 1597/1597/3384 1602/1602/3391 1603/1603/3392 +f 1603/1603/3392 1600/1600/3389 1582/1582/3388 +f 1604/1604/3393 1600/1600/3389 1603/1603/3392 +f 1603/1603/3392 1602/1602/3391 1604/1604/3393 +f 1597/1597/3384 1605/1605/3394 1602/1602/3391 +f 1582/1582/3388 1601/1601/3390 1583/1583/3385 +f 1598/1598/3386 1605/1605/3394 1597/1597/3384 +f 1601/1601/3390 1598/1598/3386 1583/1583/3385 +f 1586/1586/3349 1597/1597/3384 1565/1565/3395 +f 1606/1606/3396 1597/1597/3384 1586/1586/3349 +f 1607/1607/3397 1603/1603/3392 1608/1608/3398 +f 1609/1609/3388 1610/1610/3399 1597/1597/3384 +f 1609/1609/3388 1566/1566/3400 1611/1611/3401 +f 1586/1586/3349 1566/1566/3400 1609/1609/3388 +f 1586/1586/3349 1567/1567/3395 1566/1566/3400 +f 1586/1586/3349 1565/1565/3395 1567/1567/3395 +f 1610/1610/3399 1565/1565/3395 1597/1597/3384 +f 1609/1609/3388 1611/1611/3401 1610/1610/3399 +f 1608/1608/3398 1569/1569/3401 1573/1573/3402 +f 1579/1579/3334 1570/1570/3399 1568/1568/3403 +f 1579/1579/3334 1612/1612/3404 1570/1570/3399 +f 1579/1579/3334 1613/1613/3405 1612/1612/3404 +f 1614/1614/3406 1613/1613/3405 1579/1579/3334 +f 1608/1608/3398 1573/1573/3402 1607/1607/3397 +f 1579/1579/3334 1569/1569/3401 1608/1608/3398 +f 1568/1568/3403 1569/1569/3401 1579/1579/3334 +f 1607/1607/3397 1573/1573/3402 1572/1572/3407 +f 1612/1612/3404 1571/1571/3400 1570/1570/3399 +f 1607/1607/3397 1571/1571/3400 1612/1612/3404 +f 1572/1572/3407 1571/1571/3400 1607/1607/3397 +f 1596/1596/3408 1609/1609/3388 1615/1615/3409 +f 1596/1596/3408 1616/1616/3410 1609/1609/3388 +f 1617/1617/3411 1618/1618/3412 1619/1619/3413 +f 1595/1595/3414 1618/1618/3412 1617/1617/3411 +f 1620/1620/3415 1618/1618/3412 1595/1595/3414 +f 1609/1609/3388 1621/1621/3416 1615/1615/3409 +f 1609/1609/3388 1619/1619/3413 1621/1621/3416 +f 1617/1617/3411 1619/1619/3413 1609/1609/3388 +f 1595/1595/3414 1622/1622/3417 1620/1620/3415 +f 1596/1596/3408 1622/1622/3417 1595/1595/3414 +f 1615/1615/3409 1622/1622/3417 1596/1596/3408 +f 1613/1613/3405 1617/1617/3411 1612/1612/3404 +f 1595/1595/3414 1623/1623/3418 1578/1578/3333 +f 1624/1624/3419 1578/1578/3333 1623/1623/3418 +f 1595/1595/3414 1625/1625/3420 1623/1623/3418 +f 1578/1578/3333 1626/1626/3421 1579/1579/3334 +f 1578/1578/3333 1624/1624/3419 1626/1626/3421 +f 1579/1579/3334 1626/1626/3421 1614/1614/3406 +f 1595/1595/3414 1627/1627/3422 1625/1625/3420 +f 1617/1617/3411 1627/1627/3422 1595/1595/3414 +f 1627/1627/3422 1617/1617/3411 1613/1613/3405 +f 1603/1603/3392 1628/1628/3423 1608/1608/3398 +f 1579/1579/3334 1629/1629/3424 1630/1630/3425 +f 1608/1608/3398 1629/1629/3424 1579/1579/3334 +f 1580/1580/3335 1630/1630/3425 1631/1631/3426 +f 1579/1579/3334 1630/1630/3425 1580/1580/3335 +f 1580/1580/3335 1632/1632/3427 1582/1582/3388 +f 1580/1580/3335 1631/1631/3426 1632/1632/3427 +f 1603/1603/3392 1633/1633/3428 1628/1628/3423 +f 1582/1582/3388 1633/1633/3428 1603/1603/3392 +f 1632/1632/3427 1633/1633/3428 1582/1582/3388 +f 1634/1634/3429 1606/1606/3396 1586/1586/3349 +f 1584/1584/3430 1635/1635/3431 1593/1593/3432 +f 1583/1583/3385 1635/1635/3431 1584/1584/3430 +f 1597/1597/3384 1606/1606/3396 1599/1599/3387 +f 1583/1583/3385 1599/1599/3387 1636/1636/3433 +f 1634/1634/3429 1586/1586/3349 1588/1588/3351 +f 1636/1636/3433 1635/1635/3431 1583/1583/3385 +f 1637/1637/3434 1587/1587/3435 1586/1586/3349 +f 1596/1596/3408 1638/1638/3436 1639/1639/3437 +f 1592/1592/3438 1638/1638/3436 1596/1596/3408 +f 1609/1609/3388 1637/1637/3434 1586/1586/3349 +f 1609/1609/3388 1640/1640/3411 1637/1637/3434 +f 1592/1592/3438 1589/1589/3439 1638/1638/3436 +f 1596/1596/3408 1639/1639/3437 1616/1616/3410 +f 1616/1616/3410 1640/1640/3411 1609/1609/3388 +f 1575/1575/3440 1563/1563/3299 1576/1576/3441 +f 1515/1515/3277 1563/1563/3299 1575/1575/3440 +f 1548/1548/3293 1563/1563/3299 1515/1515/3277 +f 1548/1548/3293 1547/1547/3292 1563/1563/3299 +f 1641/1641/3399 1642/1642/3397 1643/1643/3442 +f 1644/1644/3399 1642/1642/3397 1641/1641/3399 +f 1645/1645/3395 1642/1642/3397 1644/1644/3399 +f 1645/1645/3395 1644/1644/3399 1646/1646/3399 +f 1642/1642/3443 1617/1617/3444 1643/1643/3445 +f 1642/1642/3443 1612/1612/3446 1617/1617/3444 +f 1607/1607/3447 1642/1642/3448 1645/1645/3449 +f 1612/1612/3450 1642/1642/3448 1607/1607/3447 +f 1645/1645/3451 1603/1603/3451 1607/1607/3451 +f 1603/1603/3452 1646/1646/3453 1597/1597/3454 +f 1603/1603/3452 1645/1645/3455 1646/1646/3453 +f 1644/1644/3456 1597/1597/3456 1646/1646/3456 +f 1609/1609/3457 1644/1644/3458 1641/1641/3459 +f 1597/1597/3460 1644/1644/3458 1609/1609/3457 +f 1617/1617/3461 1641/1641/3462 1643/1643/3463 +f 1609/1609/3464 1641/1641/3462 1617/1617/3461 +f 1637/1637/3465 1647/1647/3466 1587/1587/3467 +f 1648/1648/3468 1647/1647/3466 1637/1637/3465 +f 1640/1640/3469 1648/1648/3468 1637/1637/3465 +f 1616/1616/3470 1648/1648/3471 1640/1640/3472 +f 1616/1616/3470 1649/1649/3473 1648/1648/3471 +f 1616/1616/3474 1650/1650/3475 1649/1649/3476 +f 1639/1639/3477 1650/1650/3475 1616/1616/3474 +f 1638/1638/3478 1650/1650/3479 1639/1639/3480 +f 1638/1638/3478 1651/1651/3481 1650/1650/3479 +f 1589/1589/3482 1651/1651/3481 1638/1638/3478 +f 1652/1652/3483 1651/1651/3481 1589/1589/3482 +f 1591/1591/3484 1652/1652/3483 1589/1589/3482 +f 1591/1591/3484 1647/1647/3466 1652/1652/3483 +f 1587/1587/3467 1647/1647/3466 1591/1591/3484 +f 1556/1556/3485 1652/1652/3485 1647/1647/3485 +f 1652/1652/3486 1562/1562/3487 1651/1651/3488 +f 1652/1652/3486 1556/1556/3489 1562/1562/3487 +f 1650/1650/3490 1651/1651/3491 1562/1562/3492 +f 1650/1650/3490 1562/1562/3492 1559/1559/3493 +f 1649/1649/3494 1650/1650/3495 1559/1559/3496 +f 1649/1649/3494 1559/1559/3496 1544/1544/3497 +f 1648/1648/3498 1649/1649/3498 1544/1544/3498 +f 1554/1554/3499 1648/1648/3499 1544/1544/3499 +f 1554/1554/3500 1647/1647/3500 1648/1648/3500 +f 1647/1647/3501 1554/1554/3501 1556/1556/3501 +f 1621/1621/3502 1653/1653/3503 1615/1615/3504 +f 1621/1621/3502 1654/1654/3505 1653/1653/3503 +f 1619/1619/3506 1654/1654/3507 1621/1621/3508 +f 1655/1655/3509 1654/1654/3507 1619/1619/3506 +f 1619/1619/3510 1656/1656/3511 1655/1655/3512 +f 1618/1618/3513 1656/1656/3511 1619/1619/3510 +f 1618/1618/3514 1657/1657/3515 1656/1656/3516 +f 1620/1620/3517 1657/1657/3515 1618/1618/3514 +f 1658/1658/3518 1657/1657/3519 1620/1620/3520 +f 1622/1622/3521 1658/1658/3518 1620/1620/3520 +f 1622/1622/3522 1653/1653/3523 1658/1658/3524 +f 1615/1615/3525 1653/1653/3523 1622/1622/3522 +f 1658/1658/3526 1653/1653/3527 1555/1555/3528 +f 1658/1658/3526 1555/1555/3528 1561/1561/3529 +f 1561/1561/3530 1657/1657/3531 1658/1658/3532 +f 1657/1657/3531 1561/1561/3530 1535/1535/3533 +f 1656/1656/3534 1657/1657/3535 1535/1535/3536 +f 1656/1656/3534 1535/1535/3536 1534/1534/3537 +f 1534/1534/3538 1655/1655/3538 1656/1656/3538 +f 1542/1542/3539 1655/1655/3540 1534/1534/3541 +f 1542/1542/3539 1654/1654/3542 1655/1655/3540 +f 1653/1653/3543 1654/1654/3544 1542/1542/3545 +f 1653/1653/3543 1542/1542/3545 1555/1555/3546 +f 1627/1627/3547 1659/1659/3548 1625/1625/3549 +f 1660/1660/3550 1659/1659/3548 1627/1627/3547 +f 1613/1613/3551 1660/1660/3550 1627/1627/3547 +f 1614/1614/3552 1660/1660/3553 1613/1613/3554 +f 1661/1661/3555 1660/1660/3553 1614/1614/3552 +f 1661/1661/3555 1614/1614/3552 1626/1626/3556 +f 1626/1626/3556 1662/1662/3557 1661/1661/3555 +f 1624/1624/3558 1662/1662/3557 1626/1626/3556 +f 1663/1663/3559 1662/1662/3560 1624/1624/3561 +f 1623/1623/3562 1663/1663/3559 1624/1624/3561 +f 1625/1625/3563 1663/1663/3564 1623/1623/3565 +f 1625/1625/3563 1664/1664/3566 1663/1663/3564 +f 1625/1625/3549 1659/1659/3548 1664/1664/3567 +f 1533/1533/3568 1664/1664/3569 1659/1659/3570 +f 1664/1664/3569 1533/1533/3568 1560/1560/3571 +f 1663/1663/3572 1664/1664/3572 1560/1560/3572 +f 1663/1663/3573 1560/1560/3573 1564/1564/3573 +f 1564/1564/3574 1662/1662/3574 1663/1663/3574 +f 1547/1547/3575 1662/1662/3576 1564/1564/3577 +f 1661/1661/3578 1662/1662/3576 1547/1547/3575 +f 1524/1524/3579 1661/1661/3580 1547/1547/3581 +f 1524/1524/3579 1660/1660/3582 1661/1661/3580 +f 1659/1659/3583 1524/1524/3584 1533/1533/3585 +f 1660/1660/3586 1524/1524/3584 1659/1659/3583 +f 1598/1598/3587 1665/1665/3588 1605/1605/3589 +f 1598/1598/3587 1666/1666/3590 1665/1665/3588 +f 1601/1601/3591 1666/1666/3592 1598/1598/3593 +f 1667/1667/3594 1666/1666/3592 1601/1601/3591 +f 1601/1601/3595 1668/1668/3596 1667/1667/3597 +f 1600/1600/3598 1668/1668/3596 1601/1601/3595 +f 1669/1669/3599 1668/1668/3600 1600/1600/3601 +f 1604/1604/3602 1669/1669/3599 1600/1600/3601 +f 1604/1604/3602 1670/1670/3603 1669/1669/3599 +f 1602/1602/3604 1670/1670/3603 1604/1604/3602 +f 1665/1665/3605 1670/1670/3606 1602/1602/3607 +f 1605/1605/3608 1665/1665/3605 1602/1602/3607 +f 1526/1526/3609 1665/1665/3609 1666/1666/3609 +f 1546/1546/3610 1665/1665/3610 1526/1526/3610 +f 1546/1546/3611 1670/1670/3611 1665/1665/3611 +f 1670/1670/3612 1546/1546/3612 1537/1537/3612 +f 1669/1669/3613 1670/1670/3613 1537/1537/3613 +f 1669/1669/3614 1520/1520/3615 1668/1668/3616 +f 1669/1669/3614 1537/1537/3617 1520/1520/3615 +f 1520/1520/3618 1667/1667/3618 1668/1668/3618 +f 1519/1519/3619 1667/1667/3619 1520/1520/3619 +f 1667/1667/3620 1519/1519/3620 1666/1666/3620 +f 1526/1526/3621 1666/1666/3621 1519/1519/3621 +f 1628/1628/3622 1671/1671/3623 1672/1672/3624 +f 1633/1633/3625 1671/1671/3623 1628/1628/3622 +f 1632/1632/3626 1671/1671/3627 1633/1633/3628 +f 1632/1632/3626 1673/1673/3629 1671/1671/3627 +f 1631/1631/3630 1673/1673/3631 1632/1632/3632 +f 1631/1631/3630 1674/1674/3633 1673/1673/3631 +f 1630/1630/3634 1674/1674/3633 1631/1631/3630 +f 1630/1630/3634 1675/1675/3635 1674/1674/3633 +f 1629/1629/3636 1675/1675/3635 1630/1630/3634 +f 1676/1676/3637 1675/1675/3635 1629/1629/3636 +f 1608/1608/3638 1676/1676/3637 1629/1629/3636 +f 1628/1628/3639 1676/1676/3640 1608/1608/3641 +f 1672/1672/3642 1676/1676/3640 1628/1628/3639 +f 1521/1521/3643 1672/1672/3643 1671/1671/3643 +f 1536/1536/3644 1672/1672/3644 1521/1521/3644 +f 1672/1672/3645 1536/1536/3645 1676/1676/3645 +f 1676/1676/3646 1536/1536/3647 1530/1530/3648 +f 1675/1675/3649 1676/1676/3646 1530/1530/3648 +f 1517/1517/3650 1675/1675/3651 1530/1530/3652 +f 1517/1517/3650 1674/1674/3653 1675/1675/3651 +f 1673/1673/3654 1674/1674/3654 1517/1517/3654 +f 1516/1516/3655 1673/1673/3655 1517/1517/3655 +f 1671/1671/3656 1673/1673/3656 1516/1516/3656 +f 1521/1521/3657 1671/1671/3657 1516/1516/3657 +f 1677/1677/3658 1593/1593/3659 1678/1678/3660 +f 1635/1635/3661 1678/1678/3660 1593/1593/3659 +f 1635/1635/3661 1679/1679/3662 1678/1678/3660 +f 1636/1636/3663 1679/1679/3662 1635/1635/3661 +f 1636/1636/3663 1680/1680/3664 1679/1679/3662 +f 1599/1599/3665 1680/1680/3664 1636/1636/3663 +f 1599/1599/3666 1681/1681/3667 1680/1680/3668 +f 1606/1606/3669 1681/1681/3667 1599/1599/3666 +f 1606/1606/3669 1682/1682/3670 1681/1681/3667 +f 1634/1634/3671 1682/1682/3670 1606/1606/3669 +f 1634/1634/3671 1683/1683/3672 1682/1682/3670 +f 1588/1588/3673 1683/1683/3672 1634/1634/3671 +f 1588/1588/3673 1677/1677/3658 1683/1683/3672 +f 1593/1593/3659 1677/1677/3658 1588/1588/3673 +f 1529/1529/3674 1683/1683/3674 1677/1677/3674 +f 1540/1540/3675 1683/1683/3675 1529/1529/3675 +f 1683/1683/3676 1540/1540/3676 1682/1682/3676 +f 1681/1681/3677 1682/1682/3678 1540/1540/3679 +f 1681/1681/3677 1540/1540/3679 1532/1532/3680 +f 1680/1680/3681 1681/1681/3681 1532/1532/3681 +f 1680/1680/3682 1532/1532/3682 1531/1531/3682 +f 1679/1679/3683 1680/1680/3683 1531/1531/3683 +f 1527/1527/3684 1679/1679/3685 1531/1531/3686 +f 1678/1678/3687 1679/1679/3685 1527/1527/3684 +f 1529/1529/3688 1678/1678/3689 1527/1527/3690 +f 1529/1529/3688 1677/1677/3691 1678/1678/3689 +f 1543/1543/3692 1566/1566/3693 1553/1553/3694 +f 1611/1611/3695 1566/1566/3693 1543/1543/3692 +f 1610/1610/3696 1545/1545/3697 1565/1565/3698 +f 1610/1610/3696 1550/1550/3699 1545/1545/3697 +f 1610/1610/3700 1543/1543/3701 1550/1550/3702 +f 1611/1611/3703 1543/1543/3701 1610/1610/3700 +f 1684/1684/3704 1685/1685/3705 1686/1686/3706 +f 1687/1687/3707 1688/1688/3708 1689/1689/3709 +f 1687/1687/3707 1690/1690/3710 1688/1688/3708 +f 1691/1691/3711 1686/1686/3706 1687/1687/3707 +f 1691/1691/3711 1692/1692/3712 1686/1686/3706 +f 1690/1690/3710 1687/1687/3707 1693/1693/3713 +f 1694/1694/3714 1695/1695/3715 1693/1693/3713 +f 1693/1693/3713 1695/1695/3715 1696/1696/3716 +f 1686/1686/3706 1692/1692/3712 1684/1684/3704 +f 1687/1687/3707 1689/1689/3709 1691/1691/3711 +f 1693/1693/3713 1696/1696/3716 1690/1690/3710 +f 1686/1686/3706 1685/1685/3705 1694/1694/3714 +f 1686/1686/3706 1694/1694/3714 1693/1693/3713 +f 1697/1697/3717 1698/1698/3718 1699/1699/3719 +f 1697/1697/3717 1700/1700/3720 1698/1698/3718 +f 1697/1697/3717 1699/1699/3719 1701/1701/3721 +f 1702/1702/3722 1699/1699/3723 1698/1698/3724 +f 1702/1702/3725 1698/1698/3726 1703/1703/3727 +f 1702/1702/3725 1703/1703/3727 1704/1704/3728 +f 1704/1704/3729 1703/1703/3730 1705/1705/3731 +f 1704/1704/3729 1705/1705/3731 1706/1706/3732 +f 1706/1706/3733 1705/1705/3734 1697/1697/3735 +f 1706/1706/3733 1697/1697/3735 1707/1707/3736 +f 1707/1707/3737 1697/1697/3738 1708/1708/3739 +f 1707/1707/3737 1708/1708/3739 1709/1709/3740 +f 1709/1709/3741 1708/1708/3742 1710/1710/3743 +f 1709/1709/3741 1710/1710/3743 1711/1711/3744 +f 1711/1711/3745 1710/1710/3746 1699/1699/3723 +f 1711/1711/3745 1699/1699/3723 1702/1702/3722 +f 1690/1690/3747 1702/1702/3748 1688/1688/3749 +f 1688/1688/3749 1702/1702/3748 1689/1689/3750 +f 1689/1689/3750 1702/1702/3748 1704/1704/3751 +f 1689/1689/3750 1704/1704/3751 1691/1691/3752 +f 1691/1691/3752 1704/1704/3751 1692/1692/3753 +f 1692/1692/3753 1704/1704/3751 1706/1706/3754 +f 1692/1692/3753 1706/1706/3754 1684/1684/3755 +f 1684/1684/3755 1706/1706/3754 1707/1707/3756 +f 1684/1684/3755 1707/1707/3756 1685/1685/3757 +f 1685/1685/3757 1707/1707/3756 1709/1709/3758 +f 1685/1685/3757 1709/1709/3758 1694/1694/3759 +f 1694/1694/3759 1709/1709/3758 1695/1695/3760 +f 1695/1695/3760 1709/1709/3758 1711/1711/3761 +f 1695/1695/3760 1711/1711/3761 1696/1696/3762 +f 1696/1696/3763 1711/1711/3764 1702/1702/3748 +f 1696/1696/3763 1702/1702/3748 1690/1690/3747 +f 1687/1687/3765 1686/1686/3766 1712/1712/3767 +f 1712/1712/3767 1686/1686/3766 1713/1713/3768 +f 1693/1693/3769 1687/1687/3770 1714/1714/3771 +f 1714/1714/3771 1687/1687/3770 1712/1712/3772 +f 1686/1686/3773 1693/1693/3774 1713/1713/3775 +f 1713/1713/3775 1693/1693/3774 1714/1714/3776 +f 1712/1712/3395 1713/1713/3395 1714/1714/3395 +f 1703/1703/3777 1698/1698/3777 1700/1700/3777 +f 1703/1703/3730 1700/1700/3778 1705/1705/3731 +f 1705/1705/3779 1700/1700/3779 1697/1697/3779 +f 1708/1708/3780 1697/1697/3780 1701/1701/3780 +f 1708/1708/3742 1701/1701/3781 1710/1710/3743 +f 1710/1710/3782 1701/1701/3721 1699/1699/3719 +f 1715/1715/3783 1716/1716/3784 1717/1717/3785 +f 1717/1717/3785 1716/1716/3784 1718/1718/3786 +f 1715/1715/3783 1719/1719/3787 1716/1716/3784 +f 1720/1720/3788 1721/1721/3789 1719/1719/3790 +f 1720/1720/3788 1719/1719/3790 1715/1715/3791 +f 1722/1722/3792 1721/1721/3793 1720/1720/3794 +f 1722/1722/3792 1723/1723/3795 1721/1721/3793 +f 1724/1724/3796 1723/1723/3795 1722/1722/3792 +f 1724/1724/3796 1725/1725/3797 1723/1723/3795 +f 1726/1726/3798 1725/1725/3799 1724/1724/3800 +f 1726/1726/3798 1727/1727/3801 1725/1725/3799 +f 1728/1728/3802 1727/1727/3801 1726/1726/3798 +f 1728/1728/3802 1729/1729/3803 1727/1727/3801 +f 1730/1730/3804 1729/1729/3803 1728/1728/3802 +f 1717/1717/3805 1718/1718/3806 1730/1730/3804 +f 1730/1730/3804 1718/1718/3806 1729/1729/3803 +f 1722/1722/3792 1731/1731/3807 1724/1724/3796 +f 1722/1722/3792 1720/1720/3794 1732/1732/3808 +f 1732/1732/3809 1720/1720/3788 1733/1733/3810 +f 1733/1733/3810 1720/1720/3788 1715/1715/3791 +f 1733/1733/3811 1715/1715/3783 1734/1734/3812 +f 1734/1734/3812 1715/1715/3783 1717/1717/3785 +f 1734/1734/3813 1717/1717/3805 1730/1730/3804 +f 1735/1735/3814 1730/1730/3804 1728/1728/3802 +f 1735/1735/3815 1728/1728/3815 1726/1726/3815 +f 1736/1736/3816 1726/1726/3798 1724/1724/3800 +f 1736/1736/3817 1724/1724/3817 1731/1731/3817 +f 1737/1737/3818 1731/1731/3819 1722/1722/3820 +f 1726/1726/3821 1738/1738/3822 1735/1735/3823 +f 1730/1730/3824 1739/1739/3825 1734/1734/3826 +f 1730/1730/3824 1735/1735/3823 1739/1739/3825 +f 1734/1734/3826 1739/1739/3825 1733/1733/3827 +f 1722/1722/3820 1732/1732/3828 1737/1737/3818 +f 1731/1731/3819 1737/1737/3818 1736/1736/3829 +f 1736/1736/3829 1738/1738/3822 1726/1726/3821 +f 1737/1737/3818 1738/1738/3822 1736/1736/3829 +f 1733/1733/3827 1740/1740/3830 1732/1732/3828 +f 1732/1732/3828 1740/1740/3830 1737/1737/3818 +f 1738/1738/3822 1739/1739/3825 1735/1735/3823 +f 1733/1733/3827 1739/1739/3825 1740/1740/3830 +f 1738/1738/3822 1737/1737/3818 1740/1740/3830 +f 1738/1738/3822 1740/1740/3830 1739/1739/3825 +f 1741/1741/3831 1742/1742/3832 1743/1743/3833 +f 1743/1743/3833 1718/1718/3834 1716/1716/3835 +f 1716/1716/3835 1719/1719/3836 1743/1743/3833 +f 1742/1742/3832 1718/1718/3834 1743/1743/3833 +f 1744/1744/3837 1718/1718/3834 1742/1742/3832 +f 1744/1744/3837 1729/1729/3838 1718/1718/3834 +f 1727/1727/3839 1729/1729/3838 1744/1744/3837 +f 1745/1745/3840 1727/1727/3839 1744/1744/3837 +f 1745/1745/3840 1744/1744/3837 1742/1742/3832 +f 1725/1725/3841 1727/1727/3839 1745/1745/3840 +f 1741/1741/3831 1745/1745/3840 1742/1742/3832 +f 1723/1723/3842 1725/1725/3841 1745/1745/3840 +f 1723/1723/3842 1745/1745/3840 1741/1741/3831 +f 1721/1721/3843 1723/1723/3842 1741/1741/3831 +f 1743/1743/3833 1721/1721/3843 1741/1741/3831 +f 1719/1719/3836 1721/1721/3843 1743/1743/3833 +f 1746/1746/3844 1747/1747/3845 1748/1748/3846 +f 1748/1748/3846 1747/1747/3845 1749/1749/3847 +f 1750/1750/3848 1747/1747/3845 1746/1746/3844 +f 1750/1750/3848 1751/1751/3849 1747/1747/3845 +f 1752/1752/3850 1753/1753/3851 1750/1750/3852 +f 1750/1750/3852 1753/1753/3851 1751/1751/3853 +f 1754/1754/3854 1755/1755/3855 1752/1752/3850 +f 1752/1752/3850 1755/1755/3855 1753/1753/3856 +f 1754/1754/3854 1756/1756/3857 1755/1755/3855 +f 1757/1757/3858 1756/1756/3857 1754/1754/3854 +f 1758/1758/3859 1759/1759/3860 1757/1757/3858 +f 1757/1757/3858 1759/1759/3860 1756/1756/3857 +f 1760/1760/3861 1761/1761/3862 1758/1758/3863 +f 1758/1758/3863 1761/1761/3862 1759/1759/3862 +f 1760/1760/3864 1762/1762/3865 1761/1761/3866 +f 1763/1763/3867 1762/1762/3865 1760/1760/3864 +f 1748/1748/3868 1749/1749/3869 1763/1763/3867 +f 1763/1763/3867 1749/1749/3869 1762/1762/3865 +f 1764/1764/3870 1754/1754/3854 1752/1752/3850 +f 1764/1764/3870 1752/1752/3850 1765/1765/3871 +f 1765/1765/3871 1752/1752/3850 1750/1750/3852 +f 1765/1765/3872 1750/1750/3873 1746/1746/3874 +f 1766/1766/3875 1746/1746/3844 1748/1748/3846 +f 1766/1766/3876 1748/1748/3868 1763/1763/3867 +f 1763/1763/3867 1760/1760/3864 1767/1767/3877 +f 1767/1767/3878 1760/1760/3861 1758/1758/3863 +f 1754/1754/3854 1764/1764/3870 1757/1757/3879 +f 1758/1758/3880 1757/1757/3881 1768/1768/3882 +f 1757/1757/3881 1764/1764/3883 1768/1768/3882 +f 1765/1765/3872 1746/1746/3874 1769/1769/3884 +f 1763/1763/3885 1770/1770/3886 1766/1766/3887 +f 1766/1766/3887 1769/1769/3884 1746/1746/3874 +f 1758/1758/3880 1771/1771/3888 1767/1767/3889 +f 1767/1767/3889 1770/1770/3886 1763/1763/3885 +f 1766/1766/3887 1770/1770/3886 1769/1769/3884 +f 1765/1765/3872 1769/1769/3884 1764/1764/3883 +f 1758/1758/3880 1768/1768/3882 1771/1771/3888 +f 1767/1767/3889 1771/1771/3888 1770/1770/3886 +f 1769/1769/3884 1772/1772/3890 1764/1764/3883 +f 1764/1764/3883 1772/1772/3890 1768/1768/3882 +f 1769/1769/3884 1770/1770/3886 1772/1772/3890 +f 1768/1768/3882 1772/1772/3890 1771/1771/3888 +f 1771/1771/3888 1772/1772/3890 1770/1770/3886 +f 1747/1747/3891 1751/1751/3892 1773/1773/3893 +f 1774/1774/3894 1773/1773/3893 1775/1775/3895 +f 1747/1747/3891 1773/1773/3893 1774/1774/3894 +f 1749/1749/3896 1747/1747/3891 1774/1774/3894 +f 1762/1762/3897 1749/1749/3896 1774/1774/3894 +f 1776/1776/3898 1762/1762/3897 1774/1774/3894 +f 1776/1776/3898 1774/1774/3894 1775/1775/3895 +f 1761/1761/3899 1762/1762/3897 1776/1776/3898 +f 1759/1759/3900 1761/1761/3899 1776/1776/3898 +f 1777/1777/3901 1759/1759/3900 1776/1776/3898 +f 1778/1778/3902 1777/1777/3901 1776/1776/3898 +f 1778/1778/3902 1776/1776/3898 1775/1775/3895 +f 1756/1756/3903 1759/1759/3900 1777/1777/3901 +f 1756/1756/3903 1777/1777/3901 1778/1778/3902 +f 1755/1755/3904 1756/1756/3903 1778/1778/3902 +f 1779/1779/3905 1755/1755/3904 1778/1778/3902 +f 1753/1753/3906 1755/1755/3904 1779/1779/3905 +f 1779/1779/3905 1778/1778/3902 1775/1775/3895 +f 1751/1751/3892 1753/1753/3906 1779/1779/3905 +f 1773/1773/3893 1751/1751/3892 1779/1779/3905 +f 1773/1773/3893 1779/1779/3905 1775/1775/3895 +f 1780/1780/3907 1781/1781/3908 1782/1782/3909 +f 1783/1783/3910 1784/1784/3911 1785/1785/3912 +f 1786/1786/3913 1787/1787/3914 1780/1780/3907 +f 1787/1787/3914 1788/1788/3915 1780/1780/3907 +f 1781/1781/3908 1780/1780/3907 1783/1783/3910 +f 1789/1789/3916 1784/1784/3911 1790/1790/3917 +f 1790/1790/3917 1784/1784/3911 1783/1783/3910 +f 1791/1791/3918 1792/1792/3919 1790/1790/3917 +f 1788/1788/3915 1787/1787/3914 1793/1793/3920 +f 1782/1782/3909 1786/1786/3913 1780/1780/3907 +f 1783/1783/3910 1785/1785/3912 1781/1781/3908 +f 1792/1792/3919 1794/1794/3921 1790/1790/3917 +f 1790/1790/3917 1794/1794/3921 1789/1789/3916 +f 1788/1788/3915 1793/1793/3920 1791/1791/3918 +f 1788/1788/3915 1791/1791/3918 1790/1790/3917 +f 1795/1795/3922 1796/1796/3923 1797/1797/3924 +f 1798/1798/3925 1796/1796/3923 1795/1795/3922 +f 1795/1795/3922 1799/1799/3926 1798/1798/3925 +f 1800/1800/3927 1797/1797/3928 1801/1801/3929 +f 1801/1801/3929 1797/1797/3928 1802/1802/3930 +f 1801/1801/3931 1802/1802/3932 1803/1803/3933 +f 1803/1803/3933 1802/1802/3932 1796/1796/3934 +f 1803/1803/3935 1796/1796/3936 1804/1804/3937 +f 1803/1803/3935 1804/1804/3937 1805/1805/3938 +f 1805/1805/3939 1804/1804/3939 1806/1806/3939 +f 1806/1806/3940 1804/1804/3941 1807/1807/3942 +f 1806/1806/3940 1807/1807/3942 1808/1808/3943 +f 1808/1808/3944 1807/1807/3945 1799/1799/3946 +f 1808/1808/3944 1799/1799/3946 1809/1809/3947 +f 1809/1809/3947 1799/1799/3946 1810/1810/3948 +f 1809/1809/3949 1810/1810/3950 1800/1800/3951 +f 1800/1800/3951 1810/1810/3950 1795/1795/3952 +f 1800/1800/3927 1795/1795/3953 1797/1797/3928 +f 1781/1781/3954 1801/1801/3955 1782/1782/3956 +f 1782/1782/3956 1801/1801/3955 1803/1803/3957 +f 1782/1782/3956 1803/1803/3957 1786/1786/3958 +f 1786/1786/3958 1803/1803/3957 1805/1805/3959 +f 1786/1786/3958 1805/1805/3959 1787/1787/3960 +f 1787/1787/3960 1805/1805/3959 1806/1806/3961 +f 1787/1787/3960 1806/1806/3961 1793/1793/3962 +f 1793/1793/3962 1806/1806/3961 1791/1791/3963 +f 1791/1791/3963 1806/1806/3961 1808/1808/3964 +f 1791/1791/3963 1808/1808/3964 1792/1792/3965 +f 1792/1792/3965 1808/1808/3964 1794/1794/3966 +f 1794/1794/3966 1808/1808/3964 1809/1809/3967 +f 1794/1794/3966 1809/1809/3967 1789/1789/3968 +f 1789/1789/3968 1809/1809/3967 1784/1784/3969 +f 1784/1784/3969 1809/1809/3967 1800/1800/3970 +f 1784/1784/3969 1800/1800/3970 1785/1785/3971 +f 1785/1785/3971 1800/1800/3970 1781/1781/3972 +f 1781/1781/3972 1800/1800/3970 1801/1801/3973 +f 1788/1788/3974 1790/1790/3975 1811/1811/3976 +f 1811/1811/3976 1790/1790/3975 1812/1812/3977 +f 1780/1780/3978 1788/1788/3979 1813/1813/3980 +f 1813/1813/3980 1788/1788/3979 1811/1811/3981 +f 1783/1783/3982 1780/1780/3983 1814/1814/3984 +f 1814/1814/3984 1780/1780/3983 1813/1813/3985 +f 1790/1790/3986 1783/1783/3987 1812/1812/3988 +f 1812/1812/3988 1783/1783/3987 1814/1814/3989 +f 1813/1813/3399 1811/1811/3399 1812/1812/3399 +f 1813/1813/3399 1812/1812/3399 1814/1814/3399 +f 1802/1802/3990 1797/1797/3924 1796/1796/3923 +f 1796/1796/3991 1798/1798/3991 1804/1804/3991 +f 1804/1804/3992 1798/1798/3925 1807/1807/3993 +f 1807/1807/3993 1798/1798/3925 1799/1799/3926 +f 1810/1810/3994 1799/1799/3926 1795/1795/3922 +f 1815/1815/3995 1816/1816/3996 1817/1817/3997 +f 1818/1818/3998 1819/1819/3999 1820/1820/4000 +f 1817/1817/3997 1821/1821/4001 1815/1815/3995 +f 1817/1817/3997 1822/1822/4002 1821/1821/4001 +f 1816/1816/3996 1818/1818/3998 1817/1817/3997 +f 1818/1818/3998 1816/1816/3996 1823/1823/4003 +f 1824/1824/4004 1825/1825/4005 1822/1822/4002 +f 1822/1822/4002 1817/1817/3997 1824/1824/4004 +f 1824/1824/4004 1826/1826/4006 1827/1827/4007 +f 1824/1824/4004 1827/1827/4007 1825/1825/4005 +f 1818/1818/3998 1828/1828/4008 1819/1819/3999 +f 1818/1818/3998 1820/1820/4000 1824/1824/4004 +f 1820/1820/4000 1826/1826/4006 1824/1824/4004 +f 1818/1818/3998 1823/1823/4003 1828/1828/4008 +f 1829/1829/4009 1830/1830/4010 1831/1831/4011 +f 1832/1832/4012 1830/1830/4010 1829/1829/4009 +f 1829/1829/4009 1833/1833/4013 1834/1834/4014 +f 1829/1829/4009 1831/1831/4011 1833/1833/4013 +f 1835/1835/4015 1831/1831/4016 1836/1836/4017 +f 1835/1835/4015 1836/1836/4017 1837/1837/4018 +f 1837/1837/4019 1836/1836/4020 1838/1838/4021 +f 1838/1838/4021 1836/1836/4020 1832/1832/4022 +f 1838/1838/4023 1832/1832/4024 1839/1839/4023 +f 1839/1839/4023 1832/1832/4024 1840/1840/4025 +f 1839/1839/4026 1840/1840/4027 1834/1834/4028 +f 1839/1839/4026 1834/1834/4028 1841/1841/4029 +f 1841/1841/4030 1834/1834/4031 1842/1842/4032 +f 1841/1841/4030 1842/1842/4032 1843/1843/4033 +f 1843/1843/4034 1842/1842/4034 1833/1833/4034 +f 1843/1843/4035 1833/1833/4036 1835/1835/4037 +f 1835/1835/4037 1833/1833/4036 1831/1831/4038 +f 1822/1822/4039 1835/1835/4040 1821/1821/4041 +f 1821/1821/4041 1835/1835/4040 1837/1837/4042 +f 1821/1821/4041 1837/1837/4042 1815/1815/4043 +f 1815/1815/4043 1837/1837/4042 1838/1838/4044 +f 1815/1815/4043 1838/1838/4044 1816/1816/4045 +f 1816/1816/4045 1838/1838/4044 1839/1839/4046 +f 1816/1816/4045 1839/1839/4046 1823/1823/4047 +f 1823/1823/4047 1839/1839/4046 1828/1828/4048 +f 1828/1828/4048 1839/1839/4046 1819/1819/4049 +f 1819/1819/4049 1839/1839/4046 1841/1841/4050 +f 1819/1819/4049 1841/1841/4050 1820/1820/4051 +f 1820/1820/4051 1841/1841/4050 1826/1826/4052 +f 1826/1826/4052 1841/1841/4050 1843/1843/4053 +f 1826/1826/4052 1843/1843/4053 1827/1827/4054 +f 1827/1827/4054 1843/1843/4053 1825/1825/4055 +f 1825/1825/4055 1843/1843/4053 1835/1835/4056 +f 1825/1825/4055 1835/1835/4056 1822/1822/4057 +f 1817/1817/3765 1818/1818/4058 1844/1844/3767 +f 1844/1844/3767 1818/1818/4058 1845/1845/4059 +f 1824/1824/3769 1817/1817/4060 1846/1846/3771 +f 1846/1846/3771 1817/1817/4060 1844/1844/4061 +f 1818/1818/4062 1824/1824/3774 1845/1845/4063 +f 1845/1845/4063 1824/1824/3774 1846/1846/3776 +f 1844/1844/4064 1845/1845/4064 1846/1846/4064 +f 1831/1831/4016 1830/1830/4065 1836/1836/4017 +f 1836/1836/4066 1830/1830/4066 1832/1832/4066 +f 1840/1840/4067 1832/1832/4012 1829/1829/4009 +f 1840/1840/4027 1829/1829/4068 1834/1834/4028 +f 1842/1842/4069 1834/1834/4014 1833/1833/4013 +f 1847/1847/4070 1848/1848/4071 1849/1849/4072 +f 1850/1850/4073 1851/1851/4074 1852/1852/4075 +f 1853/1853/4076 1854/1854/4077 1855/1855/4078 +f 1853/1853/4076 1856/1856/4079 1854/1854/4077 +f 1847/1847/4070 1857/1857/4080 1858/1858/4081 +f 1853/1853/4076 1859/1859/4082 1860/1860/4083 +f 1860/1860/4083 1850/1850/4073 1853/1853/4076 +f 1856/1856/4079 1853/1853/4076 1847/1847/4070 +f 1847/1847/4070 1849/1849/4072 1857/1857/4080 +f 1850/1850/4073 1860/1860/4083 1861/1861/4084 +f 1855/1855/4078 1859/1859/4082 1853/1853/4076 +f 1847/1847/4070 1858/1858/4081 1856/1856/4079 +f 1850/1850/4073 1852/1852/4075 1847/1847/4070 +f 1847/1847/4070 1852/1852/4075 1848/1848/4071 +f 1850/1850/4073 1861/1861/4084 1851/1851/4074 +f 1862/1862/4085 1863/1863/4086 1864/1864/4087 +f 1864/1864/4087 1865/1865/4088 1862/1862/4085 +f 1864/1864/4087 1866/1866/4089 1865/1865/4088 +f 1867/1867/4090 1868/1868/4091 1863/1863/4092 +f 1867/1867/4090 1863/1863/4092 1869/1869/4093 +f 1869/1869/4093 1863/1863/4092 1870/1870/4094 +f 1869/1869/4095 1870/1870/4096 1871/1871/4097 +f 1871/1871/4097 1870/1870/4096 1862/1862/4098 +f 1871/1871/4097 1862/1862/4098 1872/1872/4099 +f 1872/1872/4099 1862/1862/4098 1865/1865/4100 +f 1872/1872/4099 1865/1865/4100 1873/1873/4101 +f 1873/1873/4102 1865/1865/4103 1874/1874/4104 +f 1873/1873/4102 1874/1874/4104 1875/1875/4105 +f 1875/1875/4106 1874/1874/4107 1864/1864/4108 +f 1875/1875/4106 1864/1864/4108 1876/1876/4109 +f 1876/1876/4109 1864/1864/4108 1868/1868/4110 +f 1876/1876/4109 1868/1868/4110 1867/1867/4111 +f 1856/1856/4112 1867/1867/4113 1854/1854/4114 +f 1854/1854/4114 1867/1867/4113 1869/1869/4115 +f 1854/1854/4114 1869/1869/4115 1855/1855/4116 +f 1855/1855/4116 1869/1869/4115 1859/1859/4117 +f 1859/1859/4117 1869/1869/4115 1871/1871/4118 +f 1859/1859/4117 1871/1871/4118 1860/1860/4119 +f 1860/1860/4119 1871/1871/4118 1861/1861/4120 +f 1861/1861/4120 1871/1871/4118 1872/1872/4121 +f 1861/1861/4120 1872/1872/4121 1851/1851/4122 +f 1851/1851/4122 1872/1872/4121 1873/1873/4123 +f 1851/1851/4122 1873/1873/4123 1852/1852/4124 +f 1852/1852/4124 1873/1873/4123 1848/1848/4125 +f 1848/1848/4125 1873/1873/4123 1875/1875/4126 +f 1848/1848/4125 1875/1875/4126 1849/1849/4127 +f 1849/1849/4127 1875/1875/4126 1857/1857/4128 +f 1857/1857/4128 1875/1875/4126 1876/1876/4129 +f 1857/1857/4128 1876/1876/4129 1858/1858/4130 +f 1858/1858/4130 1876/1876/4129 1867/1867/4113 +f 1858/1858/4130 1867/1867/4113 1856/1856/4112 +f 1853/1853/3765 1850/1850/3766 1877/1877/3767 +f 1877/1877/3767 1850/1850/3766 1878/1878/3768 +f 1847/1847/4131 1853/1853/4132 1879/1879/4133 +f 1879/1879/4133 1853/1853/4132 1877/1877/4134 +f 1850/1850/4135 1847/1847/4136 1878/1878/4137 +f 1878/1878/4137 1847/1847/4136 1879/1879/4138 +f 1877/1877/3399 1878/1878/3399 1879/1879/3399 +f 1868/1868/4139 1864/1864/4087 1863/1863/4086 +f 1870/1870/4140 1863/1863/4086 1862/1862/4085 +f 1874/1874/4141 1865/1865/4141 1866/1866/4141 +f 1874/1874/4107 1866/1866/4142 1864/1864/4108 +f 1880/1880/4143 1881/1881/4144 1882/1882/4145 +f 1883/1883/4146 1884/1884/4147 1885/1885/4148 +f 1884/1884/4147 1883/1883/4146 1886/1886/4149 +f 1881/1881/4144 1880/1880/4143 1887/1887/4150 +f 1883/1883/4146 1885/1885/4148 1880/1880/4143 +f 1883/1883/4146 1888/1888/4151 1886/1886/4149 +f 1889/1889/4152 1890/1890/4153 1888/1888/4151 +f 1889/1889/4152 1888/1888/4151 1883/1883/4146 +f 1885/1885/4148 1887/1887/4150 1880/1880/4143 +f 1891/1891/4154 1892/1892/4155 1889/1889/4152 +f 1889/1889/4152 1892/1892/4155 1890/1890/4153 +f 1880/1880/4143 1882/1882/4145 1889/1889/4152 +f 1889/1889/4152 1882/1882/4145 1891/1891/4154 +f 1893/1893/4156 1894/1894/4157 1895/1895/4158 +f 1895/1895/4158 1896/1896/4159 1893/1893/4156 +f 1897/1897/4160 1896/1896/4159 1895/1895/4158 +f 1898/1898/4161 1899/1899/4162 1900/1900/4163 +f 1900/1900/4163 1899/1899/4162 1894/1894/4164 +f 1900/1900/4165 1894/1894/4166 1901/1901/4167 +f 1900/1900/4165 1901/1901/4167 1902/1902/4168 +f 1902/1902/4169 1901/1901/4170 1903/1903/4171 +f 1903/1903/4171 1901/1901/4170 1904/1904/4172 +f 1903/1903/4173 1904/1904/4174 1896/1896/4175 +f 1903/1903/4173 1896/1896/4175 1905/1905/4176 +f 1905/1905/4177 1896/1896/4178 1906/1906/4179 +f 1906/1906/4179 1896/1896/4178 1907/1907/4180 +f 1906/1906/4181 1907/1907/4182 1908/1908/4183 +f 1908/1908/4183 1907/1907/4182 1895/1895/4184 +f 1908/1908/4183 1895/1895/4184 1898/1898/4185 +f 1898/1898/4185 1895/1895/4184 1899/1899/4186 +f 1886/1886/4187 1900/1900/4188 1884/1884/4189 +f 1884/1884/4189 1900/1900/4188 1885/1885/4190 +f 1885/1885/4190 1900/1900/4188 1902/1902/4191 +f 1885/1885/4190 1902/1902/4191 1887/1887/4192 +f 1887/1887/4192 1902/1902/4191 1881/1881/4193 +f 1881/1881/4193 1902/1902/4191 1903/1903/4194 +f 1881/1881/4193 1903/1903/4194 1882/1882/4195 +f 1882/1882/4195 1903/1903/4194 1891/1891/4196 +f 1891/1891/4196 1903/1903/4194 1905/1905/4197 +f 1891/1891/4196 1905/1905/4197 1892/1892/4198 +f 1892/1892/4198 1905/1905/4197 1906/1906/4199 +f 1892/1892/4198 1906/1906/4199 1890/1890/4200 +f 1890/1890/4200 1906/1906/4199 1908/1908/4201 +f 1890/1890/4200 1908/1908/4201 1909/1909/4202 +f 1909/1909/4202 1908/1908/4201 1898/1898/4203 +f 1909/1909/4202 1898/1898/4203 1888/1888/4204 +f 1888/1888/4204 1898/1898/4203 1886/1886/4187 +f 1886/1886/4187 1898/1898/4203 1900/1900/4188 +f 1890/1890/4153 1909/1909/4205 1888/1888/4151 +f 1880/1880/4206 1889/1889/4206 1910/1910/4206 +f 1911/1911/4207 1880/1880/4207 1910/1910/4207 +f 1883/1883/4208 1880/1880/4209 1912/1912/4210 +f 1912/1912/4210 1880/1880/4209 1911/1911/4211 +f 1889/1889/4212 1883/1883/4212 1913/1913/4212 +f 1913/1913/4213 1883/1883/4213 1912/1912/4213 +f 1910/1910/4214 1889/1889/4214 1913/1913/4214 +f 1911/1911/4215 1910/1910/4215 1912/1912/4215 +f 1912/1912/4215 1910/1910/4215 1913/1913/4215 +f 1899/1899/4216 1895/1895/4158 1894/1894/4157 +f 1901/1901/4217 1894/1894/4157 1893/1893/4156 +f 1901/1901/4170 1893/1893/4218 1904/1904/4172 +f 1904/1904/4219 1893/1893/4156 1896/1896/4159 +f 1896/1896/4220 1897/1897/4220 1907/1907/4220 +f 1907/1907/4221 1897/1897/4221 1895/1895/4221 +f 1914/1914/4222 1915/1915/4223 1916/1916/4224 +f 1917/1917/4225 1918/1918/4226 1919/1919/4227 +f 1918/1918/4226 1917/1917/4225 1920/1920/4228 +f 1915/1915/4223 1921/1921/4229 1916/1916/4224 +f 1922/1922/4230 1923/1923/4231 1924/1924/4232 +f 1922/1922/4230 1924/1924/4232 1925/1925/4233 +f 1917/1917/4225 1919/1919/4227 1922/1922/4230 +f 1922/1922/4230 1919/1919/4227 1923/1923/4231 +f 1917/1917/4225 1926/1926/4234 1920/1920/4228 +f 1916/1916/4224 1927/1927/4235 1926/1926/4234 +f 1916/1916/4224 1926/1926/4234 1917/1917/4225 +f 1916/1916/4224 1921/1921/4229 1927/1927/4235 +f 1922/1922/4230 1925/1925/4233 1914/1914/4222 +f 1922/1922/4230 1914/1914/4222 1916/1916/4224 +f 1928/1928/4236 1929/1929/4237 1930/1930/4238 +f 1931/1931/4239 1929/1929/4237 1928/1928/4236 +f 1930/1930/4238 1932/1932/4240 1928/1928/4236 +f 1933/1933/4241 1934/1934/4242 1935/1935/4243 +f 1933/1933/4241 1935/1935/4243 1936/1936/4244 +f 1936/1936/4245 1935/1935/4246 1931/1931/4247 +f 1936/1936/4245 1931/1931/4247 1937/1937/4248 +f 1937/1937/4248 1931/1931/4247 1938/1938/4249 +f 1937/1937/4250 1938/1938/4251 1939/1939/4252 +f 1939/1939/4252 1938/1938/4251 1940/1940/4253 +f 1939/1939/4254 1940/1940/4255 1941/1941/4256 +f 1941/1941/4256 1940/1940/4255 1942/1942/4257 +f 1941/1941/4256 1942/1942/4257 1943/1943/4258 +f 1943/1943/4259 1942/1942/4260 1930/1930/4261 +f 1943/1943/4259 1930/1930/4261 1944/1944/4262 +f 1944/1944/4263 1930/1930/4264 1934/1934/4265 +f 1944/1944/4263 1934/1934/4265 1933/1933/4266 +f 1920/1920/4267 1933/1933/4268 1918/1918/4269 +f 1918/1918/4269 1933/1933/4268 1919/1919/4270 +f 1919/1919/4270 1933/1933/4268 1923/1923/4271 +f 1923/1923/4271 1933/1933/4268 1936/1936/4272 +f 1923/1923/4271 1936/1936/4272 1924/1924/4273 +f 1924/1924/4273 1936/1936/4272 1937/1937/4274 +f 1924/1924/4273 1937/1937/4274 1925/1925/4275 +f 1925/1925/4275 1937/1937/4274 1914/1914/4276 +f 1914/1914/4276 1937/1937/4274 1939/1939/4277 +f 1914/1914/4276 1939/1939/4277 1915/1915/4278 +f 1915/1915/4278 1939/1939/4277 1921/1921/4279 +f 1921/1921/4279 1939/1939/4277 1941/1941/4280 +f 1921/1921/4279 1941/1941/4280 1927/1927/4281 +f 1927/1927/4281 1941/1941/4280 1943/1943/4282 +f 1927/1927/4281 1943/1943/4282 1926/1926/4283 +f 1926/1926/4283 1943/1943/4282 1944/1944/4284 +f 1926/1926/4283 1944/1944/4284 1920/1920/4267 +f 1920/1920/4267 1944/1944/4284 1933/1933/4268 +f 1922/1922/4285 1916/1916/4285 1945/1945/4285 +f 1946/1946/4286 1922/1922/4286 1945/1945/4286 +f 1917/1917/4287 1922/1922/4288 1947/1947/4289 +f 1947/1947/4289 1922/1922/4288 1946/1946/4290 +f 1916/1916/4291 1917/1917/4291 1948/1948/4291 +f 1948/1948/4292 1917/1917/4292 1947/1947/4292 +f 1945/1945/4293 1916/1916/4293 1948/1948/4293 +f 1946/1946/3400 1945/1945/3400 1947/1947/3400 +f 1947/1947/3400 1945/1945/3400 1948/1948/4294 +f 1934/1934/4295 1930/1930/4238 1929/1929/4237 +f 1934/1934/4242 1929/1929/4296 1935/1935/4243 +f 1935/1935/4297 1929/1929/4297 1931/1931/4297 +f 1938/1938/4298 1931/1931/4239 1928/1928/4236 +f 1938/1938/4251 1928/1928/4299 1940/1940/4253 +f 1940/1940/4300 1928/1928/4300 1932/1932/4300 +f 1940/1940/4255 1932/1932/4301 1942/1942/4257 +f 1942/1942/4302 1932/1932/4302 1930/1930/4302 +f 677/677/1094 642/642/1057 643/643/1058 +f 1949/1949/4303 1950/1950/4303 1951/1951/4304 +f 1949/1949/4303 1951/1951/4304 1952/1952/4304 +f 1953/1953/4305 1954/1954/4305 1955/1955/4306 +f 1955/1955/4306 1954/1954/4305 1956/1956/4306 +f 1957/1957/4307 1958/1958/4307 1959/1959/4308 +f 1957/1957/4307 1959/1959/4308 1960/1960/4308 +f 1955/1955/3283 1951/1951/3283 1957/1957/3283 +f 1951/1951/3283 1950/1950/4309 1957/1957/3283 +f 1957/1957/3283 1960/1960/3280 1953/1953/3283 +f 1953/1953/3283 1955/1955/3283 1957/1957/3283 +f 1952/1952/3399 1956/1956/3399 1954/1954/3399 +f 1959/1959/3399 1958/1958/3401 1949/1949/3399 +f 1954/1954/3399 1949/1949/3399 1952/1952/3399 +f 1949/1949/3399 1954/1954/3399 1959/1959/3399 +f 1950/1950/4303 1949/1949/4303 1957/1957/4310 +f 1957/1957/4310 1949/1949/4303 1958/1958/4310 +f 1960/1960/4311 1959/1959/4311 1953/1953/4305 +f 1953/1953/4305 1959/1959/4311 1954/1954/4305 +f 1952/1952/4312 1951/1951/4312 1956/1956/4313 +f 1951/1951/4312 1955/1955/4313 1956/1956/4313 +f 1969/1961/4314 1973/1962/4315 1970/1963/4316 +f 3138/1964/4317 3107/1965/4318 3100/1966/4319 +f 2737/1967/4320 2750/1968/4321 2685/1969/4322 +f 3024/1970/4323 2896/1971/4324 2898/1972/4325 +f 2334/1973/4326 2331/1974/4327 2358/1975/4328 +f 4289/1976/4329 4294/1977/4329 4296/1978/4329 +f 2978/1979/4330 2996/1980/4331 2994/1981/4332 +f 3922/1982/4333 3824/1983/4334 3827/1984/4335 +f 3721/1985/4336 3719/1986/4336 3720/1987/4337 +f 3105/1988/4338 3106/1989/4339 3130/1990/4340 +f 3831/1991/4341 3900/1992/4342 3832/1993/4343 +f 4375/1994/4344 4347/1995/4345 4352/1996/4346 +f 3869/1997/4347 3868/1998/4348 3870/1999/4349 +f 3341/2000/4350 3337/2001/4350 3339/2002/4350 +f 3273/2003/4351 3271/2004/4351 3240/2005/4351 +f 3652/2006/4352 3689/2007/4353 3651/2008/4354 +f 2104/2009/4355 2102/2010/4356 2103/2011/4357 +f 4119/2012/4358 4115/2013/4359 4129/2014/4360 +f 3439/2015/4361 3336/2016/4362 3438/2017/4363 +f 3431/2018/4364 3419/2019/4365 3343/2020/4366 +f 4090/2021/4367 4120/2022/4367 4087/2023/4367 +f 2498/2024/4368 2499/2025/4369 2497/2026/4370 +f 4256/2027/4371 4261/2028/4372 4268/2029/4373 +f 3855/2030/4374 3836/2031/4375 3854/2032/4376 +f 3263/2033/4377 3265/2034/4378 3276/2035/4379 +f 2701/2036/4380 2776/2037/4381 2761/2038/4382 +f 3326/2039/4383 3327/2040/4383 3330/2041/4383 +f 3380/2042/4384 3382/2043/4385 3354/2044/4386 +f 3500/2045/4387 3510/2046/4388 3503/2047/4388 +f 2910/2048/4389 2902/2049/4390 2823/2050/4391 +f 3915/2051/4392 3909/2052/4393 3889/2053/4394 +f 3767/2054/4337 3744/2055/4336 3773/2056/4336 +f 4067/2057/4395 4104/2058/4396 4074/2059/4397 +f 2010/2060/4398 2013/2061/4399 2011/2062/4398 +f 4068/2063/4400 4079/2064/4401 4077/2065/4402 +f 3735/2066/4403 3736/2067/4404 3720/1987/4405 +f 3144/2068/4406 3140/2069/4406 3110/2070/4406 +f 4065/2071/4407 4058/2072/4408 4066/2073/4409 +f 2907/2074/4410 2906/2075/4411 2661/2076/4412 +f 2099/2077/4413 2429/2078/4414 2471/2079/4415 +f 4014/2080/4416 4031/2081/4417 4030/2082/4418 +f 4223/2083/4419 4192/2084/4420 4194/2085/4421 +f 4306/2086/4422 4305/2087/4422 4304/2088/4422 +f 4090/2021/4367 4092/2089/4367 4119/2012/4367 +f 2444/2090/4423 2425/2091/4424 2445/2092/4425 +f 2463/2093/4426 2585/2094/4427 2582/2095/4428 +f 3340/2096/4429 3451/2097/4429 3450/2098/4429 +f 3685/2099/4430 3650/2100/4431 3686/2101/4432 +f 3578/2102/4433 3579/2103/4434 3581/2104/4434 +f 3491/2105/4435 3492/2106/4435 3494/2107/4436 +f 2039/2108/4437 2052/2109/4438 2040/2110/4439 +f 3867/2111/4440 3868/1998/4348 3866/2112/4441 +f 3544/2113/4442 3562/2114/4443 3561/2115/4444 +f 3278/2116/4445 3277/2117/4446 3320/2118/4447 +f 4210/2119/4448 4208/2120/4449 4188/2121/4450 +f 4314/2122/4422 4347/1995/4422 4344/2123/4422 +f 3061/2124/4451 3067/2125/4452 3059/2126/4453 +f 4047/2127/4454 3936/2128/4455 4046/2129/4456 +f 3752/2130/4457 3749/2131/4458 3750/2132/4459 +f 3636/2133/4460 3634/2134/4461 3651/2008/4462 +f 3264/2135/4463 3262/2136/4464 3274/2137/4465 +f 2810/2138/4466 2811/2139/4467 2809/2140/4468 +f 2785/2141/4469 2799/2142/4470 2688/2143/4471 +f 3516/2144/4472 3535/2145/4473 3534/2146/4474 +f 3286/2147/4475 3285/2148/4476 3295/2149/4477 +f 3640/2150/4478 3653/2151/4479 3634/2134/4461 +f 3180/2152/4480 3184/2153/4481 3185/2154/4482 +f 2008/2155/4483 1983/2156/4484 2010/2060/4485 +f 3239/2157/4486 3241/2158/4487 3242/2159/4487 +f 4352/1996/4422 4347/1995/4422 4314/2122/4422 +f 3651/2008/4462 3634/2134/4461 3652/2006/4488 +f 3405/2160/4489 3434/2161/4490 3404/2162/4491 +f 3758/2163/4492 3757/2164/4493 3759/2165/4494 +f 3570/2166/4495 3567/2167/4496 3568/2168/4497 +f 3533/2169/4498 3518/2170/4499 3515/2171/4500 +f 3697/2172/4501 3585/2173/4501 3583/2174/4501 +f 4112/2175/4502 4111/2176/4503 4137/2177/4504 +f 3868/1998/4505 3840/2178/4506 3866/2112/4507 +f 3288/2179/4508 3267/2180/4509 3287/2181/4510 +f 3226/2182/4511 3243/2183/4512 3241/2158/4513 +f 2004/2184/4514 2007/2185/4515 2005/2186/4516 +f 3697/2172/4434 3699/2187/4434 3695/2188/4434 +f 4238/2189/4517 4236/2190/4517 4202/2191/4517 +f 3151/2192/4518 3166/2193/4519 3152/2194/4520 +f 3401/2195/4521 3415/2196/4522 3414/2197/4523 +f 3606/2198/4524 3638/2199/4524 3608/2200/4524 +f 4302/2201/4525 4301/2202/4526 4377/2203/4527 +f 4358/2204/4528 4354/2205/4529 4367/2206/4530 +f 3457/2207/4531 3467/2208/4531 3466/2209/4532 +f 4187/2210/4533 4206/2211/4534 4204/2212/4535 +f 3576/2213/4536 3466/2209/4536 3460/2214/4536 +f 3127/2215/4537 3125/2216/4538 3105/1988/4338 +f 3319/2217/4539 3217/2218/4540 3278/2116/4445 +f 3276/2035/4541 3275/2219/4542 3317/2220/4543 +f 3766/2221/4544 3780/2222/4545 3770/2223/4546 +f 4002/2224/4547 3989/2225/4548 4003/2226/4549 +f 2147/2227/4550 2618/2228/4551 2619/2229/4552 +f 3451/2097/4553 3340/2096/4553 3333/2230/4553 +f 3839/2231/4554 3836/2031/4554 3838/2232/4554 +f 3228/2233/4555 3229/2234/4556 3254/2235/4557 +f 3387/2236/4558 3356/2237/4559 3386/2238/4560 +f 1975/2239/4561 1967/2240/4316 1968/2241/4316 +f 3950/2242/4562 3968/2243/4563 3970/2244/4564 +f 3806/2245/4565 3710/2246/4566 3707/2247/4567 +f 3157/2248/4568 3158/2249/4569 3143/2250/4570 +f 3960/2251/4571 3947/2252/4572 3958/2253/4573 +f 1981/2254/4574 1997/2255/4575 1980/2256/4576 +f 2349/2257/4577 2351/2258/4578 2350/2259/4579 +f 3945/2260/4580 4023/2261/4581 4024/2262/4582 +f 3116/2263/4406 3117/2264/4406 3150/2265/4406 +f 4130/2266/4583 4119/2012/4358 4129/2014/4360 +f 1986/2267/4584 1988/2268/4585 2018/2269/4585 +f 3967/2270/4586 3969/2271/4587 3968/2243/4588 +f 2699/2272/4589 2611/2273/4590 2083/2274/4591 +f 2478/2275/4592 2522/2276/4593 2486/2277/4594 +f 3992/2278/4595 4001/2279/4596 3991/2280/4597 +f 3437/2281/4598 3436/2282/4599 3423/2283/4600 +f 2334/1973/4326 2335/2284/4601 2333/2285/4602 +f 3474/2286/4603 3499/2287/4604 3475/2288/4605 +f 3302/2289/4606 3295/2149/4477 3296/2290/4607 +f 3914/2291/4608 3915/2051/4392 3917/2292/4609 +f 2238/2293/4610 2233/2294/4611 2237/2295/4612 +f 3528/2296/4613 3565/2297/4614 3527/2298/4615 +f 2103/2011/4616 2101/2299/4617 2471/2079/4415 +f 3139/2300/4406 3110/2070/4406 3140/2069/4406 +f 3435/2301/4618 3438/2017/4363 3336/2016/4362 +f 3649/2302/4619 3683/2303/4620 3648/2304/4621 +f 3905/2305/4622 3912/2306/4623 3829/2307/4624 +f 3342/2308/4625 3340/2096/4626 3345/2309/4350 +f 2485/2310/4627 2535/2311/4628 2533/2312/4629 +f 3858/2313/4630 3857/2314/4631 3859/2315/4632 +f 3128/2316/4633 3127/2215/4537 3105/1988/4338 +f 3112/2317/4634 3111/2318/4634 3113/2319/4635 +f 4216/2320/4636 4217/2321/4637 4215/2322/4638 +f 4053/2323/4639 3940/2324/4639 3932/2325/4639 +f 2550/2326/4640 2551/2327/4641 2548/2328/4642 +f 1989/2329/4643 1987/2330/4644 1978/2331/4645 +f 2231/2332/4646 2230/2333/4647 2232/2334/4648 +f 2104/2009/4355 2103/2011/4357 2105/2335/4649 +f 3458/2336/4650 3572/2337/4650 3453/2338/4650 +f 2563/2339/4651 2562/2340/4652 2329/2341/4653 +f 2877/2342/4654 3042/2343/4655 2879/2344/4656 +f 2726/2345/4657 2830/2346/4658 2656/2347/4659 +f 3566/2348/4660 3463/2349/4661 3461/2350/4662 +f 4189/2351/4663 4215/2322/4664 4213/2352/4665 +f 2048/2353/4666 2066/2354/4667 2036/2355/4668 +f 2282/2356/4669 2283/2357/4670 2286/2358/4671 +f 3132/2359/4672 3131/2360/4673 3130/1990/4673 +f 3832/1993/4343 3910/2361/4674 3828/2362/4675 +f 4081/2363/4676 4082/2364/4677 4080/2365/4678 +f 4149/2366/4679 4147/2367/4680 4150/2368/4681 +f 4088/2369/4682 4089/2370/4683 4090/2021/4684 +f 3894/2371/4685 3921/2372/4686 3893/2373/4687 +f 3819/2374/4688 3820/2375/4689 3818/2376/4690 +f 2027/2377/4585 1996/2378/4585 1998/2379/4585 +f 3836/2031/4554 3834/2380/4554 3835/2381/4554 +f 3507/2382/4691 3508/2383/4692 3478/2384/4693 +f 2504/2385/4694 2505/2386/4695 2502/2387/4696 +f 3263/2033/4377 3277/2117/4697 3278/2116/4698 +f 3101/2388/4699 3111/2318/4700 3109/2389/4701 +f 2571/2390/4702 2553/2391/4703 2552/2392/4704 +f 3547/2393/4705 3570/2166/4495 3531/2394/4706 +f 3844/2395/4707 3842/2396/4708 3873/2397/4709 +f 3237/2398/4710 3239/2157/4486 3240/2005/4486 +f 2406/2399/4711 2465/2400/4712 2407/2401/4713 +f 3906/2402/4714 3912/2306/4623 3905/2305/4622 +f 3917/2292/4609 3915/2051/4392 3916/2403/4715 +f 2894/2404/4716 3025/2405/4717 3027/2406/4718 +f 2139/2407/26 2140/2408/26 2938/2409/511 +f 2121/2410/4719 2432/2411/4720 2450/2412/4721 +f 3882/2413/4722 3894/2371/4685 3877/2414/4723 +f 3938/2415/4724 4051/2416/4724 4050/2417/4724 +f 4349/2418/4725 4350/2419/4726 4362/2420/4727 +f 3634/2134/4461 3653/2151/4479 3652/2006/4488 +f 2779/2421/4728 2781/2422/4729 2792/2423/4730 +f 3096/2424/4731 3097/2425/4731 3098/2426/4731 +f 2099/2077/4732 2602/2427/4733 2696/2428/4734 +f 4072/2429/4735 4071/2430/4736 4070/2431/4367 +f 3617/2432/4737 3618/2433/4738 3615/2434/4739 +f 3739/2435/4740 3740/2436/4741 3738/2437/4742 +f 3699/2187/4434 3697/2172/4434 3698/2438/4434 +f 2666/2439/4743 2665/2440/4744 2829/2441/4745 +f 4158/2442/4746 4139/2443/4747 4127/2444/4748 +f 3675/2445/4749 3658/2446/4750 3659/2447/4751 +f 2587/2448/4752 2464/2449/4753 2386/2450/4754 +f 3381/2451/4755 3379/2452/4755 3389/2453/4755 +f 2895/2454/4756 2896/1971/4324 3026/2455/4757 +f 2082/2456/4758 2080/2457/4759 2081/2458/4760 +f 2504/2385/4694 2506/2459/4761 2505/2386/4695 +f 3536/2460/4762 3552/2461/4763 3571/2462/4764 +f 2760/2463/4765 2833/2464/4766 2831/2465/4767 +f 3752/2130/4457 3753/2466/4768 3751/2467/4457 +f 4080/2365/4367 4082/2364/4367 4113/2468/4367 +f 3626/2469/4769 3627/2470/4770 3625/2471/4769 +f 2745/2472/4771 2746/2473/4772 2744/2474/4773 +f 4206/2211/4534 4188/2121/4450 4208/2120/4449 +f 2912/2475/4774 2899/2476/4775 2897/2477/4776 +f 3978/2478/4777 3980/2479/4778 3979/2480/4779 +f 2272/2481/4780 2273/2482/4781 2271/2483/4782 +f 3136/2484/4783 3134/2485/4784 3107/1965/4318 +f 3838/2232/4785 3837/2486/4786 3858/2313/4787 +f 3877/2414/4554 3864/2487/4554 3882/2413/4554 +f 3485/2488/4788 3488/2489/4789 3487/2490/4789 +f 4217/2321/4637 4214/2491/4790 4215/2322/4638 +f 2014/2492/4585 2016/2493/4585 2013/2061/4585 +f 2228/2494/4791 2221/2495/4792 2226/2496/4793 +f 2847/2497/4794 2765/2498/4795 2726/2345/4657 +f 3819/2374/4796 3818/2376/4796 3925/2499/4796 +f 2963/2500/4797 2180/2501/4798 2613/2502/4799 +f 2707/2503/4800 2808/2504/4801 2806/2505/4802 +f 1976/2506/4803 2071/2507/4803 2072/2508/4803 +f 3672/2509/4804 3676/2510/4805 3591/2511/4806 +f 3457/2207/4807 3574/2512/4807 3458/2336/4807 +f 3364/2513/4808 3398/2514/4755 3366/2515/4755 +f 2900/2516/4809 2898/1972/4325 2899/2476/4775 +f 4332/2517/4810 4308/2518/4811 4309/2519/4812 +f 4381/2520/4813 4380/2521/4814 4379/2522/4815 +f 3531/2394/4706 3511/2523/4816 3517/2524/4817 +f 3037/2525/4818 3038/2526/4819 3044/2527/4820 +f 2318/2528/4821 2356/2529/4822 2278/2530/4823 +f 3559/2531/4824 3558/2532/4825 3541/2533/4826 +f 1961/2534/4827 1966/2535/4828 2061/2536/4829 +f 3580/2537/4830 3696/2538/4830 3700/2539/4830 +f 3829/2307/4624 3912/2306/4623 3821/2540/4831 +f 2035/2541/4832 2049/2542/4833 2048/2353/4666 +f 3544/2113/4834 3514/2543/4835 3509/2544/4836 +f 3557/2545/4837 3558/2532/4825 3464/2546/4838 +f 1990/2547/4839 1989/2329/4643 1978/2331/4645 +f 3580/2537/4434 3582/2548/4434 3579/2103/4434 +f 3747/2549/4840 3748/2550/4841 3749/2131/4458 +f 2368/2551/26 2367/2552/26 2579/2553/26 +f 3470/2554/4842 3483/2555/4843 3471/2556/4844 +f 2035/2541/4832 2036/2355/4668 2020/2557/4845 +f 2221/2495/4792 2394/2558/4846 2393/2559/4847 +f 2733/2560/4848 2750/1968/4321 2735/2561/4849 +f 3613/2562/4850 3616/2563/4851 3615/2434/4739 +f 2068/2564/4316 2069/2565/4316 2072/2508/4316 +f 2018/2269/4585 2014/2492/4585 1986/2267/4584 +f 4128/2566/4852 4129/2014/4360 4115/2013/4359 +f 4175/2567/4853 4286/2568/4854 4287/2569/4853 +f 2221/2495/4792 2228/2494/4791 2394/2558/4846 +f 2538/2570/4855 2479/2571/4856 2306/2572/4857 +f 2770/2573/4858 2771/2574/4859 2772/2575/4860 +f 3674/2576/4861 3670/2577/4862 3657/2578/4863 +f 4064/2579/4864 4164/2580/4864 4165/2581/4864 +f 4196/2582/4865 4193/2583/4866 4195/2584/4867 +f 3523/2585/4388 3488/2489/4388 3521/2586/4388 +f 2169/2587/4868 2168/2588/4869 2649/2589/4870 +f 2487/2590/4871 2176/2591/4872 2478/2275/4592 +f 2684/2592/4873 2741/2593/4874 2737/1967/4320 +f 3454/2594/4875 3577/2595/4875 3460/2214/4875 +f 3689/2007/4353 3653/2151/4876 3688/2596/4877 +f 4262/2597/4878 4261/2028/4372 4255/2598/4879 +f 3639/2599/4880 3656/2600/4881 3655/2601/4882 +f 4376/2602/4883 4366/2603/4884 4292/2604/4885 +f 3340/2096/4429 3450/2098/4429 3345/2309/4429 +f 3575/2605/4532 3572/2337/4532 3574/2512/4532 +f 4232/2606/4886 4246/2607/4887 4233/2608/4888 +f 2965/2609/4889 3075/2610/4890 3076/2611/4891 +f 2047/2612/4892 2018/2269/4893 2019/2613/4894 +f 3505/2614/4895 3508/2383/4692 3506/2615/4896 +f 4335/2616/4897 4334/2617/4898 4309/2519/4812 +f 2894/2404/4716 2851/2618/4899 2674/2619/4900 +f 3669/2620/4901 3675/2445/4749 3659/2447/4751 +f 3541/2533/4826 3558/2532/4825 3540/2621/4902 +f 3246/2622/4903 3244/2623/4904 3243/2183/4904 +f 3685/2099/4430 3686/2101/4432 3687/2624/4905 +f 3290/2625/4906 3289/2626/4907 3307/2627/4908 +f 3911/2628/4909 3904/2629/4910 3829/2307/4624 +f 3112/2317/4406 3114/2630/4406 3149/2631/4406 +f 2552/2392/4704 2570/2632/4911 2571/2390/4702 +f 3630/2633/4912 3631/2634/4913 3629/2635/4912 +f 2800/2636/4914 2785/2141/4469 2688/2143/4471 +f 3670/2577/4862 3674/2576/4861 3673/2637/4915 +f 4350/2419/4422 4349/2418/4422 4336/2638/4422 +f 1979/2639/4916 1992/2640/4917 1990/2547/4839 +f 2309/2641/4918 2529/2642/4919 2538/2570/4855 +f 2021/2643/4920 2037/2644/4921 2038/2645/4922 +f 4170/2646/4923 4168/2647/4924 4167/2648/4924 +f 3823/2649/4925 3830/2650/4925 3929/2651/4925 +f 3825/2652/4926 3925/2499/4926 3818/2376/4927 +f 3435/2301/4618 3437/2281/4598 3438/2017/4363 +f 2048/2353/4666 2065/2653/4928 2066/2354/4667 +f 2522/2276/4593 2500/2654/4929 2498/2024/4368 +f 3349/2655/4755 3352/2656/4755 3348/2657/4808 +f 2717/2658/4930 2719/2659/4931 2718/2660/4932 +f 4393/2661/4329 4394/2662/4329 4397/2663/4329 +f 3376/2664/4933 3353/2665/4934 3375/2666/4935 +f 2039/2108/4936 2040/2110/4937 2026/2667/4938 +f 2788/2668/4939 2787/2669/4940 2689/2670/4941 +f 3330/2041/4383 3329/2671/4383 3328/2672/4383 +f 2893/2673/4942 2852/2674/4943 2851/2618/4899 +f 2536/2675/4944 2528/2676/4945 2573/2677/4946 +f 3085/2678/4947 3201/2679/4947 3200/2680/4947 +f 3461/2350/4662 3453/2338/4532 3452/2681/4948 +f 2599/2682/4949 2600/2683/4950 2103/2011/4951 +f 3243/2183/4512 3226/2182/4511 3245/2684/4952 +f 2696/2428/4734 2602/2427/4733 3082/2685/4953 +f 4001/2279/4596 3992/2278/4595 4002/2224/4954 +f 3612/2686/4955 3609/2687/4956 3610/2688/4956 +f 2692/2689/4957 2789/2690/4958 2788/2668/4939 +f 3870/1999/4349 3871/2691/4959 3869/1997/4347 +f 3047/2692/4960 3055/2693/4961 3050/2694/4962 +f 3183/2695/4963 3182/2696/4964 3097/2425/4965 +f 3500/2045/4966 3501/2697/4967 3499/2287/4968 +f 3828/2362/4675 3911/2628/4909 3829/2307/4624 +f 3762/2698/4336 3754/2699/4336 3752/2130/4336 +f 2836/2700/4969 2755/2701/4970 2751/2702/4971 +f 2246/2703/4972 2320/2704/4973 2321/2705/4974 +f 3896/2706/4975 3881/2707/4976 3897/2708/4977 +f 2131/2709/4978 2137/2710/4979 2589/2711/4980 +f 2099/2077/4413 2097/2712/4981 2395/2713/4982 +f 4384/2714/4983 4385/2715/4984 4360/2716/4985 +f 3569/2717/4986 3529/2718/4987 3549/2719/4988 +f 3889/2053/4394 3916/2403/4715 3915/2051/4392 +f 2146/2720/4989 2145/2721/4990 2487/2590/4871 +f 3361/2722/4991 3360/2723/4992 3362/2724/4993 +f 3078/2725/4994 3019/2726/4995 3009/2727/4996 +f 2747/2728/4997 2748/2729/4998 2738/2730/4999 +f 3985/2731/5000 3983/2732/5001 3987/2733/5000 +f 2298/2734/5002 2288/2735/5003 2284/2736/5004 +f 3605/2737/5005 3595/2738/5006 3603/2739/5007 +f 2078/2740/5008 2079/2741/5009 2081/2458/4760 +f 4101/2742/5010 4102/2743/5011 4100/2744/5012 +f 2256/2745/5013 2257/2746/5014 2251/2747/5015 +f 2312/2748/5016 2313/2749/5017 2212/2750/5018 +f 3752/2130/4457 3754/2699/4768 3753/2466/4768 +f 2731/2751/5019 2725/2752/5020 2726/2345/4657 +f 3734/2753/4336 3732/2754/4336 3765/2755/4337 +f 4210/2119/4448 4189/2351/4663 4213/2352/4665 +f 3658/2446/4750 3674/2576/4861 3657/2578/4863 +f 3146/2756/5021 3145/2757/5022 3163/2758/5023 +f 2064/2759/5024 2049/2542/4833 2034/2760/5025 +f 4383/2761/5026 4381/2520/4813 4382/2762/5027 +f 3514/2543/4388 3482/2763/4388 3480/2764/5028 +f 4247/2765/5029 4248/2766/5030 4231/2767/5031 +f 3591/2511/4806 3676/2510/4805 3594/2768/5032 +f 3992/2278/5033 3989/2225/4548 4002/2224/4547 +f 4054/2769/4408 4059/2770/4409 4061/2771/5034 +f 3421/2772/5035 3335/2773/5036 3343/2020/4366 +f 3076/2611/4891 3080/2774/5037 3077/2775/5038 +f 2005/2186/4584 2022/2776/4585 2020/2557/4585 +f 2585/2094/26 2587/2448/26 2364/2777/26 +f 4277/2778/5039 4176/2779/5040 4278/2780/5041 +f 2966/2781/5042 2962/2782/5043 2958/2783/5044 +f 2988/2784/5045 2987/2785/5046 2812/2786/5047 +f 3885/2787/5048 3903/2788/5049 3886/2789/5050 +f 3185/2154/4482 3095/2790/5051 3186/2791/5052 +f 3798/2792/5053 3797/2793/5054 3795/2794/5055 +f 3105/1988/4338 3104/2795/5056 3103/2796/4406 +f 2021/2643/4920 2020/2557/4845 2036/2355/4668 +f 2399/2797/5057 2400/2798/5058 2468/2799/5059 +f 2120/2800/5060 2129/2801/5061 2130/2802/5062 +f 2669/2803/5063 2668/2804/5064 2850/2805/5065 +f 3635/2806/4524 3630/2633/4524 3636/2133/4524 +f 3422/2807/5066 3432/2808/5067 3335/2773/5036 +f 4290/2809/5068 4298/2810/5069 4386/2811/5070 +f 3556/2812/5071 3551/2813/5072 3550/2814/5073 +f 4122/2815/5074 4121/2816/5075 4149/2366/4679 +f 4017/2817/5076 4018/2818/5077 4037/2819/5078 +f 2068/2564/5079 1970/1963/5079 1962/2820/5079 +f 3179/2821/5080 3159/2822/5081 3197/2823/5082 +f 2458/2824/5083 2477/2825/5084 2459/2826/5085 +f 3325/2827/5086 3281/2828/5087 3292/2829/5088 +f 3657/2578/4863 3670/2577/4862 3694/2830/5089 +f 4204/2212/4535 4203/2831/5090 4186/2832/5091 +f 3291/2833/5092 3274/2137/4465 3261/2834/5093 +f 4107/2835/4367 4105/2836/4367 4076/2837/4367 +f 3146/2756/5021 3164/2838/5094 3165/2839/5095 +f 2394/2558/4846 2228/2494/4791 2436/2840/5096 +f 3229/2234/4556 3257/2841/5097 3254/2235/4557 +f 2087/2842/5098 2086/2843/5099 2085/2844/5100 +f 4209/2845/5101 4207/2846/5102 4208/2120/5103 +f 3653/2151/4876 3689/2007/4353 3652/2006/4352 +f 3490/2847/5104 3491/2105/4435 3489/2848/5104 +f 4245/2849/5105 4278/2780/5041 4279/2850/5106 +f 3524/2851/5107 3562/2114/4443 3544/2113/4442 +f 4250/2852/5108 4238/2189/5109 4237/2853/5110 +f 2078/2740/5008 2081/2458/4760 2080/2457/4759 +f 3351/2854/5111 3365/2855/5112 3367/2856/5113 +f 3169/2857/5114 3181/2858/5115 3180/2152/4480 +f 3036/2859/5116 2887/2860/5117 2886/2861/5118 +f 3713/2862/5119 3815/2863/5119 3814/2864/5119 +f 2006/2865/5120 2004/2184/5121 1982/2866/5122 +f 2896/1971/4324 2895/2454/4756 2850/2805/5065 +f 3428/2867/5123 3416/2868/5124 3429/2869/5125 +f 2663/2870/5126 2849/2871/5127 2662/2872/5128 +f 3354/2044/4386 3378/2873/5129 3380/2042/4384 +f 4134/2874/5130 4117/2875/5131 4118/2876/5132 +f 3529/2718/4987 3566/2348/4660 3528/2296/4613 +f 2791/2877/5133 2788/2668/4939 2793/2878/5134 +f 4181/2879/4924 4175/2567/4924 4179/2880/4924 +f 4120/2022/5135 4131/2881/5136 4132/2882/5137 +f 3403/2883/5138 3432/2808/5067 3422/2807/5066 +f 3401/2195/4808 3370/2884/4755 3402/2885/4755 +f 2607/2886/5139 2091/2887/5140 2090/2888/5141 +f 3989/2225/4548 3995/2889/5142 4004/2890/5143 +f 4180/2891/5144 4175/2567/4924 4169/2892/4924 +f 3270/2893/5145 3286/2147/4475 3287/2181/4510 +f 2297/2894/5146 2299/2895/5147 2398/2896/5148 +f 2714/2897/5149 2713/2898/5150 2712/2899/5151 +f 3439/2015/4361 3443/2900/5152 3341/2000/5153 +f 2765/2498/4795 2847/2497/4794 2736/2901/5154 +f 3486/2902/4788 3483/2555/5155 3484/2903/5156 +f 3762/2698/5157 3779/2904/5158 3778/2905/5159 +f 3774/2906/5160 3785/2907/5161 3784/2908/5162 +f 3727/2909/5163 3729/2910/5164 3718/2911/5165 +f 2961/2912/5166 2963/2500/4797 2181/2913/5167 +f 2094/2914/5168 2609/2915/5169 2701/2036/4380 +f 3526/2916/5170 3563/2917/5171 3525/2918/5172 +f 3217/2218/4383 3216/2919/5173 3213/2920/4383 +f 3978/2478/4777 3979/2480/4779 3977/2921/4777 +f 2253/2922/5174 2250/2923/5175 2268/2924/5176 +f 2533/2312/4629 2549/2925/5177 2495/2926/5178 +f 2058/2927/5179 2060/2928/5180 2059/2929/5181 +f 3237/2398/4710 3240/2005/4486 3238/2930/5182 +f 3372/2931/4755 3370/2884/4755 3401/2195/4808 +f 2936/2932/26 2178/2933/26 2971/2934/26 +f 3417/2935/5183 3400/2936/5184 3418/2937/5185 +f 3470/2554/4388 3476/2938/4388 3469/2939/4387 +f 4357/2940/5186 4372/2941/5187 4356/2942/5188 +f 2023/2943/5189 2025/2944/5190 2043/2945/5191 +f 3895/2946/5192 3922/1982/4333 3894/2371/4685 +f 2170/2947/5193 2648/2948/5194 3012/2949/5195 +f 4322/2950/5196 4320/2951/5197 4305/2087/5198 +f 2722/2952/5199 2686/2953/5200 2730/2954/5201 +f 2679/2955/5202 2853/2956/5203 2890/2957/5204 +f 3055/2693/4961 3051/2958/5205 3049/2959/5206 +f 3539/2960/5207 3550/2814/5073 3551/2813/5072 +f 2296/2961/5208 2295/2962/5209 2193/2963/5210 +f 4280/2964/5211 4259/2965/5212 4260/2966/5213 +f 2088/2967/5214 2091/2887/5215 2089/2968/5216 +f 2933/2969/26 2936/2932/26 2971/2934/26 +f 2780/2970/5217 2779/2421/4728 2778/2971/5218 +f 1997/2255/4575 1995/2972/5219 1980/2256/4576 +f 2977/2973/5220 2976/2974/5221 2992/2975/5222 +f 3683/2303/4620 3684/2976/5223 3578/2102/4433 +f 4136/2977/5224 4113/2468/5225 4135/2978/5226 +f 4395/2979/4329 4393/2661/4329 4397/2663/4329 +f 4307/2980/5227 4308/2518/4811 4329/2981/5228 +f 2218/2982/5229 2358/1975/4328 2239/2983/5230 +f 3826/2984/5231 3929/2651/5232 3830/2650/5232 +f 2107/2985/5233 2105/2335/5234 2473/2986/5235 +f 1968/2241/5236 2070/2987/5236 2071/2507/5236 +f 2728/2988/5237 2766/2989/5238 2817/2990/5239 +f 3516/2144/4472 3533/2169/4498 3515/2171/4500 +f 4243/2991/5240 4242/2992/5241 4275/2993/5242 +f 3015/2994/5243 2880/2995/5244 2879/2344/4656 +f 2315/2996/5245 2528/2676/4945 2314/2997/5246 +f 3666/2998/5247 3633/2999/5248 3647/3000/5249 +f 4077/2065/5250 4078/3001/5250 4076/2837/5251 +f 3697/2172/4501 3583/2174/4501 3698/2438/4501 +f 2735/2561/4849 2740/3002/5252 2772/2575/4860 +f 4378/3003/5253 4377/2203/4527 4301/2202/4526 +f 2214/3004/5254 2305/3005/5255 2215/3006/5256 +f 3347/3007/5257 3386/2238/5258 3356/2237/5259 +f 4032/3008/5260 4014/2080/4416 4015/3009/5261 +f 4084/3010/5262 4087/2023/5263 4085/3011/5264 +f 3933/3012/5265 4040/3013/5266 3939/3014/5267 +f 3216/2919/5173 3206/3015/4383 3213/2920/4383 +f 3226/2182/4351 3225/3016/4351 3229/2234/4351 +f 3235/3017/5268 3234/3018/5269 3233/3019/5270 +f 3190/3020/5271 3174/3021/5272 3189/3022/5273 +f 3672/2509/4804 3673/2637/4915 3676/2510/4805 +f 2815/3023/5274 2720/3024/5275 2589/2711/5276 +f 4068/2063/5277 4067/2057/4367 4070/2431/4367 +f 2477/2825/5084 2466/3025/5278 2465/2400/4712 +f 4202/2191/4517 4236/2190/4517 4200/3026/4517 +f 2781/2422/4729 2799/2142/4470 2790/3027/5279 +f 3371/3028/5280 3374/3029/5281 3373/3030/5282 +f 4154/3031/5283 4152/3032/5284 4151/3033/5285 +f 3214/3034/5286 3287/2181/5287 3302/2289/4606 +f 3046/3035/5288 3006/3036/5289 3045/3037/5290 +f 3238/2930/5182 3235/3017/5268 3237/2398/4710 +f 2762/3038/5291 2833/2464/4766 2760/2463/4765 +f 2887/2860/5117 3036/2859/5116 3035/3039/5292 +f 2148/3040/5293 2629/3041/5294 2919/3042/5295 +f 4246/2607/4887 4259/2965/5212 4281/3043/5296 +f 3601/3044/5297 3625/2471/5298 3627/2470/5299 +f 3396/3045/4808 3374/3029/4755 3372/2931/4755 +f 3102/3046/5300 3115/3047/5301 3113/2319/5302 +f 4118/2876/4367 4085/3011/4367 4087/2023/4367 +f 2244/3048/5303 2243/3049/5304 2326/3050/5305 +f 3055/2693/4961 3049/2959/5206 3050/2694/4962 +f 3290/2625/4906 3266/3051/5306 3289/2626/5307 +f 3192/3052/5308 3086/3053/5309 3083/3054/5310 +f 3886/2789/5050 3903/2788/5049 3902/3055/5311 +f 4387/3056/5312 4362/2420/4727 4361/3057/5313 +f 4320/2951/5197 4319/3058/5314 4305/2087/5198 +f 3433/3059/5315 3434/2161/4490 3435/2301/4618 +f 4076/2837/4367 4078/3001/4367 4112/2175/4367 +f 3938/2415/4724 3935/3060/4724 4051/2416/4724 +f 2297/2894/5146 2284/2736/5004 2299/2895/5147 +f 4245/2849/5105 4244/3061/5316 4278/2780/5041 +f 2914/3062/5317 2147/2227/5318 2917/3063/5319 +f 3532/3064/5320 3518/2170/4499 3533/2169/4498 +f 3264/2135/4351 3265/2034/4351 3255/3065/4351 +f 4276/3066/5321 4275/2993/5242 4274/3067/5322 +f 4374/3068/5323 4375/1994/4344 4352/1996/5324 +f 3252/3069/5325 3251/3070/5326 3250/3071/5326 +f 4375/1994/4344 4383/2761/5026 4384/2714/4983 +f 2738/2730/4999 2769/3072/5327 2770/2573/4858 +f 4062/3073/5328 4144/3074/5329 4143/3075/5330 +f 2330/3076/5331 2331/1974/4327 2560/3077/5332 +f 3268/3078/5333 3269/3079/5334 3279/3080/5335 +f 2889/3081/5336 3030/3082/5337 2854/3083/5338 +f 2201/3084/5339 2278/2530/5340 2280/3085/5341 +f 3689/2007/4353 3687/2624/4905 3686/2101/4432 +f 4177/3086/4924 4172/3087/4924 4182/3088/4924 +f 1998/2379/5342 1996/2378/5343 1995/2972/5344 +f 3999/3089/5345 4011/3090/5346 4010/3091/5347 +f 3744/2055/4336 3767/2054/4337 3746/3092/5348 +f 2817/2990/5239 2722/2952/5199 2723/3093/5349 +f 2023/2943/5189 2043/2945/5191 2044/3094/5350 +f 3015/2994/5243 2879/2344/4656 3042/2343/4655 +f 3408/3095/5351 3442/3096/5352 3407/3097/5353 +f 3942/3098/5354 3935/3060/5354 3938/2415/5355 +f 3032/3099/5356 3029/3100/5357 3067/2125/4452 +f 3815/2863/5358 3812/3101/5358 3814/2864/5358 +f 3265/2034/4351 3263/2033/4351 3253/3102/4351 +f 3847/3103/5359 3845/3104/5360 3846/3105/5360 +f 1992/2640/5361 1993/3106/5362 1991/3107/5363 +f 4199/3108/5364 4201/3109/5365 4202/2191/5366 +f 2904/3110/5367 2730/2954/5201 2818/3111/5368 +f 3714/3112/5369 3810/3113/5370 3716/3114/5371 +f 2780/2970/5217 2781/2422/4729 2779/2421/4728 +f 2147/2227/5318 2625/3115/5372 2917/3063/5319 +f 3869/1997/5373 3840/2178/4506 3868/1998/4505 +f 3271/2004/4351 3238/2930/4351 3240/2005/4351 +f 3556/2812/5071 3555/3116/5374 3551/2813/5072 +f 2454/3117/5375 2456/3118/5376 2457/3119/5377 +f 2551/2327/4641 2550/2326/4640 2573/2677/4946 +f 2419/3120/5378 2443/3121/5379 2445/2092/4425 +f 2657/3122/5380 2830/2346/4658 2848/3123/5381 +f 2313/2749/5017 2311/3124/5382 2212/2750/5018 +f 4240/3125/5383 4241/3126/5384 4227/3127/5385 +f 2347/3128/5386 2349/2257/4577 2350/2259/4579 +f 3747/2549/5387 3724/3129/5388 3723/3130/5389 +f 3365/2855/5390 3364/2513/5391 3366/2515/5390 +f 3637/3131/5392 3666/2998/5247 3665/3132/5393 +f 2178/2933/26 2179/3133/26 2971/2934/26 +f 3719/1986/5394 3733/3134/5395 3720/1987/4405 +f 2243/3049/5304 2329/2341/4653 2326/3050/5305 +f 2722/2952/5199 2817/2990/5239 2715/3135/5396 +f 3062/3136/5397 3060/3137/5398 2923/3138/5399 +f 3329/2671/5400 3213/2920/5400 3328/2672/5400 +f 2555/3139/5401 2564/3140/5402 2556/3141/5403 +f 3923/3142/5404 3922/1982/4333 3895/2946/5192 +f 2798/3143/5405 2797/3144/5406 3082/2685/4953 +f 3266/3051/4351 3261/2834/4351 3260/3145/4351 +f 3127/2215/5407 3128/2316/5408 3129/3146/5409 +f 4110/3147/4367 4109/3148/4367 4102/2743/4367 +f 2424/3149/5410 2422/3150/5411 2431/3151/5412 +f 2793/2878/5134 2792/2423/4730 2791/2877/5133 +f 2157/3152/5413 2159/3153/5414 2639/3154/5415 +f 3434/2161/4490 3437/2281/4598 3435/2301/4618 +f 2978/1979/26 2973/3155/26 2938/2409/511 +f 4148/3156/5416 4151/3033/5285 4150/2368/4681 +f 3143/2250/4406 3133/3157/4406 3135/3158/5056 +f 2113/3159/5417 2112/3160/5418 2114/3161/5419 +f 3446/3162/5420 3447/3163/5421 3333/2230/5420 +f 2303/3164/5422 2387/3165/5423 2388/3166/5424 +f 3527/2298/5425 3512/3167/5426 3513/3168/5427 +f 2617/3169/5428 2618/2228/5429 2916/3170/5430 +f 3509/2544/4388 3478/2384/4388 3508/2383/4388 +f 3146/2756/5021 3163/2758/5023 3164/2838/5094 +f 3123/3171/5431 3120/3172/5432 3104/2795/5433 +f 2416/3173/5434 2441/3174/5435 2442/3175/5436 +f 2393/2559/4847 2394/2558/4846 2094/2914/5437 +f 2082/2456/5438 2083/2274/5439 2394/2558/4846 +f 2083/2274/5439 2085/2844/5440 2394/2558/4846 +f 1968/2241/5236 1970/1963/5236 2070/2987/5236 +f 2074/3176/5441 2076/3177/5442 2095/3178/5443 +f 3098/2426/4731 3099/3179/5444 3088/3180/5444 +f 3785/2907/5161 3772/3181/5445 3786/3182/5446 +f 3722/3183/5447 3721/1985/5448 3738/2437/5449 +f 3630/2633/4912 3632/3184/4913 3631/2634/4913 +f 3723/3130/5389 3743/3185/5450 3745/3186/5451 +f 3877/2414/4723 3893/2373/5452 3878/3187/5453 +f 3862/3188/5454 3864/2487/5455 3863/3189/5456 +f 2508/3190/5457 2513/3191/5458 2510/3192/5459 +f 3248/3193/5460 3251/3070/5326 3249/3194/5461 +f 3640/2150/4524 3626/2469/4524 3624/3195/5462 +f 4061/2771/5034 4065/2071/4407 4156/3196/5463 +f 2900/2516/4809 3024/1970/4323 2898/1972/4325 +f 3788/3197/5464 3799/3198/5465 3787/3199/5466 +f 4370/3200/5467 4377/2203/4527 4378/3003/5253 +f 4369/3201/5468 4359/3202/5469 4358/2204/4528 +f 3943/3203/5470 4026/3204/5471 4029/3205/5472 +f 2262/3206/5473 2261/3207/5474 2211/3208/5475 +f 3094/3209/5476 3176/3210/5477 3177/3211/5478 +f 3814/2864/5358 3812/3101/5358 3813/3212/5358 +f 4364/3213/5479 4363/3214/5480 4389/3215/5481 +f 3678/3216/5482 3679/3217/5483 3681/3218/5484 +f 3669/2620/4901 3659/2447/4751 3660/3219/5485 +f 2659/3220/5486 2658/3221/5487 2848/3123/5381 +f 4274/3067/5322 4241/3126/5488 4272/3222/5489 +f 2077/3223/5490 2395/2713/4982 2076/3177/5442 +f 4192/2084/4420 4193/2583/4866 4194/2085/4421 +f 1982/2866/5122 1981/2254/4585 1984/3224/4585 +f 3229/2234/4556 3222/3225/5491 3259/3226/5492 +f 2579/2553/5493 2452/3227/5494 2458/2824/5495 +f 3064/3228/5496 3062/3136/5397 2923/3138/5399 +f 4224/3229/5497 4239/3230/5498 4240/3125/5383 +f 3008/3231/5499 3002/3232/5500 3056/3233/5501 +f 3822/3234/4688 3825/2652/4690 3818/2376/4690 +f 2771/2574/4859 2773/3235/5502 2772/2575/4860 +f 2522/2276/4593 2498/2024/4368 2497/2026/4370 +f 4207/2846/5503 4209/2845/5503 4234/3236/4517 +f 2324/3237/5504 2326/3050/5305 2565/3238/5505 +f 2342/3239/5506 2344/3240/5507 2345/3241/5508 +f 2618/2228/5429 2147/2227/5318 2914/3062/5317 +f 2412/3242/5509 2428/3243/5510 2413/3244/5511 +f 3808/3245/5512 3807/3246/5513 3779/2904/5158 +f 2537/3247/5514 2534/3248/5515 2505/2386/4695 +f 2416/3173/5434 2419/3120/5378 2418/3249/5516 +f 2242/3250/5517 2439/3251/5518 2438/3252/5519 +f 2580/3253/26 2371/3254/26 2378/3255/26 +f 2167/3256/5520 2166/3257/5521 2169/2587/4868 +f 4024/2262/4582 4025/3258/5522 4026/3204/5471 +f 3978/2478/5523 3977/2921/5523 3975/3259/5524 +f 2093/3260/5525 2092/3261/5526 2094/2914/5527 +f 3803/3262/5528 3802/3263/5529 3793/3264/5530 +f 3658/2446/4750 3646/3265/5531 3659/2447/4751 +f 4088/2369/5532 4071/2430/5533 4089/2370/5534 +f 2144/3266/5535 2143/3267/5536 3011/3268/5537 +f 2700/3269/5538 2776/2037/4381 2701/2036/4380 +f 4191/3270/5539 4221/3271/5540 4219/3272/5541 +f 2017/3273/4585 2015/3274/4585 2009/3275/4585 +f 4303/3276/5542 4304/2088/5543 4313/3277/5544 +f 4134/2874/5545 4141/3278/5546 4143/3075/5330 +f 2781/2422/4729 2780/2970/5217 2798/3143/5405 +f 2917/3063/5319 2623/3279/5547 2913/3280/5548 +f 2627/3281/5549 2150/3282/5550 2913/3280/5548 +f 3742/3283/4336 3773/2056/4336 3744/2055/4336 +f 3146/2756/4406 3151/2192/4406 3124/3284/4406 +f 3853/3285/5551 3854/2032/5552 3852/3286/5553 +f 3629/2635/5554 3601/3044/5297 3627/2470/5299 +f 4368/3287/5555 4358/2204/4528 4367/2206/4530 +f 4359/3202/4422 4323/3288/4422 4326/3289/4422 +f 2453/3290/5556 2132/3291/5557 2451/3292/5558 +f 2778/2971/5218 2779/2421/4728 2777/3293/5559 +f 3754/2699/4768 3755/3294/5560 3753/2466/4768 +f 3424/3295/5561 3431/2018/4364 3430/3296/5562 +f 3411/3297/5563 3412/3298/5564 3341/2000/5153 +f 2854/3083/5338 2681/3299/5565 2682/3300/5566 +f 2250/2923/5175 2446/3301/5567 2249/3302/5568 +f 4265/3303/5569 4263/3304/5570 4264/3305/5571 +f 3882/2413/4554 3864/2487/4554 3862/3188/4554 +f 3682/3306/5572 3582/2548/5573 3647/3000/5574 +f 4173/3307/5575 4169/2892/4924 4168/2647/4924 +f 3655/2601/4882 3691/3308/5576 3654/3309/5577 +f 2449/3310/5578 2253/2922/5174 2252/3311/5579 +f 2899/2476/4775 2911/3312/5580 2901/3313/5581 +f 2567/3314/5582 2555/3139/5401 2554/3315/5583 +f 2874/3316/5584 3040/3317/5585 2877/2342/4654 +f 4307/2980/4422 4306/2086/4422 4309/2519/4422 +f 3891/3318/5586 3918/3319/5587 3890/3320/5588 +f 4130/2266/5589 4129/2014/4360 4140/3321/5590 +f 3584/3322/4434 3583/2174/4434 3589/3323/4434 +f 2596/3324/5591 2594/3325/5592 2595/3326/5593 +f 3379/2452/5594 3380/2042/5595 3378/2873/5594 +f 3195/3327/5596 3094/3209/5476 3198/3328/5597 +f 2634/3329/5598 2633/3330/5599 2632/3331/5600 +f 3365/2855/5112 3349/2655/5601 3363/3332/5602 +f 3050/2694/4962 3007/3333/5603 3006/3036/5289 +f 2020/2557/4585 2021/2643/4584 2002/3334/4585 +f 3496/3335/5604 3493/3336/5605 3495/3337/5606 +f 2695/3338/5607 2696/2428/4734 3082/2685/4953 +f 3375/2666/5608 3377/3339/5609 3376/2664/5610 +f 3597/3340/5611 3609/2687/5612 3611/3341/5613 +f 2115/3342/5614 2118/3343/5615 2117/3344/5616 +f 3825/2652/4926 3927/3345/5617 3925/2499/4926 +f 3393/3346/5618 3421/2772/5619 3399/3347/5620 +f 4356/2942/4422 4318/3348/4422 4321/3349/4422 +f 2982/3350/5621 2987/2785/5622 2974/3351/5623 +f 2577/3352/5624 2456/3118/5625 2455/3353/5626 +f 3141/3354/5627 3159/2822/5628 3160/3355/5629 +f 2116/3356/5630 2115/3342/5614 2113/3159/5417 +f 4330/3357/5631 4331/3358/5632 4333/3359/5633 +f 2394/2558/4846 2383/3360/5634 2082/2456/5438 +f 2082/2456/5438 2383/3360/5634 2080/2457/5635 +f 4127/2444/4748 4108/3361/5636 4126/3362/5637 +f 4358/2204/4422 4359/3202/4422 4326/3289/4422 +f 2828/3363/5638 2894/2404/4716 2674/2619/4900 +f 2342/3239/5506 2340/3364/5639 2341/3365/5640 +f 2510/3192/5459 2511/3366/5641 2509/3367/5642 +f 3421/2772/5619 3394/3368/5643 3422/2807/5644 +f 2133/3369/5645 2453/3290/5556 2138/3370/5646 +f 2784/3371/5647 2691/3372/5648 2801/3373/5649 +f 2706/3374/5650 2903/3375/5651 2707/2503/4800 +f 2455/3353/5652 2456/3118/5376 2454/3117/5375 +f 2141/3376/5653 2134/3377/5653 2457/3119/5653 +f 2457/3119/5654 2134/3377/5654 2135/3378/5654 +f 3161/3379/5655 3162/3380/5656 3147/3381/5657 +f 3661/3382/5658 3668/3383/5659 3660/3219/5485 +f 4249/3384/5660 4182/3088/5661 4250/2852/5662 +f 2094/2914/5168 2701/2036/4380 2702/3385/5663 +f 2490/3386/5664 2491/3387/5665 2542/3388/5666 +f 2091/2887/5667 2219/3389/5668 2221/2495/4792 +f 2459/2826/5085 2462/3390/5669 2463/2093/5670 +f 3649/2302/4619 3635/2806/5671 3636/2133/4460 +f 4075/3391/5672 4067/2057/4395 4077/2065/4402 +f 3066/3392/5673 3029/3100/5357 3028/3393/5674 +f 2408/3394/5675 2410/3395/5676 2409/3396/5677 +f 2466/3025/5278 2404/3397/5678 2411/3398/5679 +f 3113/2319/5302 3101/2388/4699 3102/3046/5300 +f 3193/3399/5680 3192/3052/5308 3083/3054/5310 +f 2798/3143/5405 2799/2142/4470 2781/2422/4729 +f 2418/3249/5516 2425/2091/4424 2426/3400/5681 +f 3898/3401/5682 3887/3402/5683 3899/3403/5684 +f 3634/2134/4524 3626/2469/4524 3640/2150/4524 +f 3345/2309/4350 3346/3404/4350 3344/3405/5685 +f 3093/3406/5686 3094/3209/5476 3195/3327/5596 +f 2314/2997/5246 2312/2748/5016 2212/2750/5018 +f 3473/3407/5687 3491/2105/5688 3493/3336/5689 +f 4324/3408/5690 4322/2950/5196 4306/2086/5691 +f 3678/3216/5482 3586/3409/5692 3663/3410/5693 +f 3900/1992/5694 3887/3402/5683 3888/3411/5695 +f 2324/3237/5504 2245/3412/5696 2244/3048/5303 +f 3826/2984/4688 3832/1993/4690 3828/2362/4688 +f 4222/3413/5697 4221/3271/5540 4191/3270/5539 +f 4060/3414/5698 4166/3415/5698 4162/3416/5698 +f 2057/3417/5699 2056/3418/5700 2058/2927/5179 +f 4309/2519/4812 4310/3419/5701 4335/2616/4897 +f 3374/3029/5281 3375/2666/5608 3373/3030/5282 +f 2523/3420/5702 2560/3077/5332 2333/2285/4602 +f 3463/2349/5703 3458/2336/5703 3461/2350/4662 +f 4186/2832/4517 4185/3421/4517 4184/3422/4517 +f 2292/3423/5704 2293/3424/5705 2284/2736/5004 +f 4197/3425/5706 4195/2584/5707 4184/3422/5708 +f 2284/2736/5004 2288/2735/5003 2289/3426/5709 +f 3955/3427/5710 3957/3428/5711 3956/3429/5712 +f 3742/3283/5713 3740/2436/4741 3739/2435/4740 +f 2262/3206/5714 2263/3430/5715 2251/2747/5015 +f 3487/2490/4789 3488/2489/4789 3490/2847/5104 +f 3874/3431/5716 3897/2708/4977 3881/2707/4976 +f 2818/3111/5368 2686/2953/5200 2820/3432/5717 +f 3062/3136/5397 3064/3228/5496 3073/3433/5718 +f 3691/3308/5576 3690/3434/5719 3654/3309/5577 +f 3527/2298/5425 3513/3168/5427 3528/2296/5720 +f 3079/3435/5721 3078/2725/4994 3011/3268/5537 +f 3048/3436/5722 3079/3435/5721 3011/3268/5537 +f 2274/3437/5723 2275/3438/5724 2271/2483/4782 +f 4004/2890/5143 3995/2889/5142 4005/3439/5725 +f 3222/3225/4351 3229/2234/4351 3225/3016/4351 +f 3997/3440/5726 3994/3441/5727 4015/3009/5728 +f 3663/3410/5693 3586/3409/5692 3662/3442/5729 +f 1988/2268/5730 1987/2330/5731 1989/2329/5732 +f 3636/2133/4524 3628/3443/4524 3634/2134/4524 +f 2050/3444/5733 2054/3445/5734 2044/3094/5350 +f 3065/3446/5735 3027/2406/4718 3025/2405/4717 +f 2697/3447/5736 2700/3269/5538 2699/2272/4589 +f 4088/2369/5532 4070/2431/5737 4071/2430/5533 +f 3388/3448/5738 3422/2807/5644 3392/3449/5739 +f 2511/3366/5641 2512/3450/5641 2509/3367/5642 +f 3981/3451/5001 3980/2479/5000 3991/2280/5000 +f 3516/2144/4472 3534/2146/4474 3533/2169/4498 +f 4325/3452/5740 4324/3408/5690 4306/2086/5691 +f 2593/3453/5741 2719/2659/4931 3081/3454/5742 +f 3141/3354/5627 3158/2249/4569 3159/2822/5628 +f 2596/3324/5591 2595/3326/5593 2597/3455/5743 +f 4210/2119/5744 4211/3456/5745 4209/2845/5101 +f 3269/3079/4351 3268/3078/4351 3246/2622/4351 +f 2565/3238/5505 2564/3140/5402 2555/3139/5401 +f 3920/3457/5746 3918/3319/5587 3919/3458/5747 +f 2964/3459/5748 2967/3460/5749 2965/2609/4889 +f 3683/2303/4620 3685/2099/4430 3684/2976/5223 +f 4189/2351/4663 4190/3461/5750 4216/2320/5751 +f 4217/2321/4517 4225/3462/5503 4214/2491/4517 +f 3151/2192/4406 3152/2194/4406 3122/3463/4406 +f 3166/2193/4519 3165/2839/5752 3199/3464/5753 +f 1971/3465/5754 1974/3466/5755 1972/3467/5756 +f 3625/2471/5298 3600/3468/5757 3623/3469/5758 +f 4001/2279/4596 4038/3470/5759 4000/3471/5760 +f 3918/3319/5587 3916/2403/4715 3890/3320/5588 +f 3550/2814/5073 3557/2545/4837 3556/2812/5071 +f 3712/3472/5761 3801/3473/5762 3704/3474/5763 +f 2015/3274/5764 2032/3475/5765 2033/3476/5766 +f 2407/2401/4713 2408/3394/5675 2382/3477/5767 +f 4132/2882/5137 4133/3478/5768 4118/2876/5132 +f 3638/2199/4524 3606/2198/4524 3637/3131/4524 +f 3514/2543/4388 3478/2384/4388 3509/2544/4388 +f 3031/3479/5769 2885/3480/5770 2888/3481/5771 +f 2533/2312/4629 2536/2675/4944 2550/2326/4640 +f 2461/3482/5772 2581/3483/5773 2579/2553/5493 +f 2225/3484/5774 2226/2496/4793 2221/2495/4792 +f 2026/2667/4584 2027/2377/4585 1998/2379/4585 +f 4094/3485/5775 4095/3486/5776 4093/3487/5777 +f 3838/2232/4554 3836/2031/4554 3837/2486/5778 +f 1971/3465/5754 1972/3467/5756 1963/3488/4316 +f 3072/3489/5779 3062/3136/5397 3073/3433/5718 +f 4233/2608/4517 4209/2845/5503 4211/3456/5503 +f 3384/3490/5780 3385/3491/5780 3387/2236/4558 +f 2592/3492/5781 2590/3493/5782 2719/2659/4931 +f 3928/3494/5783 3825/2652/5783 3823/2649/5783 +f 2241/3495/5784 2239/2983/5230 2358/1975/4328 +f 2748/2729/4998 2745/2472/4771 2783/3496/5785 +f 4351/3497/4422 4350/2419/4422 4339/3498/4422 +f 2118/3343/5786 2594/3325/5592 2117/3344/5787 +f 3400/2936/4755 3366/2515/4755 3398/2514/4755 +f 3060/3137/5398 3061/2124/4451 2921/3499/5788 +f 2922/3500/5789 3057/3501/5790 3064/3228/5496 +f 2301/3502/5791 2304/3503/5792 2306/2572/4857 +f 2771/2574/4859 2770/2573/4858 2769/3072/5327 +f 2064/2759/5024 2065/2653/4928 2049/2542/4833 +f 3042/2343/4655 3012/2949/5195 3015/2994/5243 +f 3555/3116/5374 3553/3504/5793 3554/3505/5794 +f 3217/2218/4540 3212/3506/5795 3321/3507/5796 +f 3142/3508/5797 3140/2069/5798 3155/3509/5799 +f 3956/3429/5800 3946/3510/5801 3955/3427/5802 +f 3742/3283/5713 3743/3185/5803 3741/3511/5804 +f 3335/2773/5036 3433/3059/5315 3334/3512/5805 +f 2505/2386/4695 2506/2459/4761 2483/3513/5806 +f 2153/3514/5807 2915/3515/5808 2927/3516/5809 +f 2433/3517/5810 2434/3518/5811 2420/3519/5812 +f 2182/3520/5813 2175/3521/5814 2176/2591/4872 +f 4011/3090/5346 3998/3522/5815 4012/3523/5816 +f 3971/3524/5817 3970/2244/5818 3968/2243/4588 +f 2679/2955/5202 2890/2957/5204 2824/3525/5819 +f 3432/2808/5067 3434/2161/4490 3433/3059/5315 +f 2401/3526/5820 2450/2412/4721 2420/3519/5812 +f 3353/2665/4934 3373/3030/5821 3375/2666/4935 +f 4081/2363/5822 4079/2064/4401 4068/2063/4400 +f 2597/3455/5823 2595/3326/5824 3081/3454/5742 +f 3113/2319/5302 3111/2318/4700 3101/2388/4699 +f 3720/1987/4405 3733/3134/5395 3735/2066/4403 +f 2548/2328/4642 2552/2392/4704 2547/3527/5825 +f 4098/3528/5826 4099/3529/5827 4100/2744/5012 +f 2774/3530/5828 2773/3235/5502 2801/3373/5649 +f 3153/3531/4406 3150/2265/4406 3119/3532/4406 +f 2553/2391/4703 2546/3533/5829 2547/3527/5825 +f 2158/3534/5830 2639/3154/5831 2926/3535/5832 +f 3742/3283/5713 3744/2055/5833 3743/3185/5803 +f 3510/2046/5834 3530/3536/5835 3529/2718/5836 +f 3545/3537/5837 3546/3538/5838 3533/2169/4498 +f 4248/2766/5030 4249/3384/5839 4237/2853/5110 +f 3133/3157/4406 3141/3354/4406 3131/2360/4406 +f 4341/3539/5840 4338/3540/5841 4340/3541/5842 +f 3098/2426/4731 3092/3542/4731 3096/2424/4731 +f 3030/3082/5337 3070/3543/5843 3031/3479/5769 +f 1991/3107/4585 1993/3106/4585 2023/2943/4585 +f 2788/2668/4939 2689/2670/4941 2693/3544/5844 +f 3846/3105/5845 3845/3104/5845 3843/3545/5846 +f 3926/3546/5847 3826/2984/5847 3819/2374/5847 +f 3454/2594/5848 3572/2337/5848 3573/3547/5848 +f 3454/2594/5848 3453/2338/5848 3572/2337/5848 +f 4325/3452/5849 4327/3548/5850 4328/3549/5851 +f 4241/3126/5488 4240/3125/5852 4272/3222/5489 +f 3220/3550/5853 3329/2671/5853 3330/2041/5853 +f 2434/3518/5811 2433/3517/5810 2396/3551/5854 +f 2052/2109/4438 2038/2645/5855 2067/3552/5856 +f 4026/3204/5471 4025/3258/5522 4027/3553/5857 +f 3767/2054/5858 3782/3554/5859 3781/3555/5860 +f 2015/3274/4585 2007/2185/4585 2009/3275/4585 +f 2956/3556/5861 2970/3557/5862 2969/3558/5863 +f 2975/3559/26 2941/3560/26 2942/3561/26 +f 2916/3170/5430 2143/3267/5536 2145/2721/5864 +f 4041/3562/5865 4001/2279/4596 4042/3563/5866 +f 3050/2694/4962 3049/2959/5206 3007/3333/5603 +f 2403/3564/5867 2410/3395/5676 2404/3397/5868 +f 3618/2433/4738 3621/3565/5869 3620/3566/5870 +f 3623/3469/5758 3600/3468/5757 3622/3567/5871 +f 4073/3568/5872 4074/2059/4397 4099/3529/5873 +f 2148/3040/5874 2150/3282/5875 2628/3569/5876 +f 3654/3309/5577 3640/2150/5877 3639/2599/4880 +f 3339/2002/4350 3332/3570/5878 3336/2016/4350 +f 4054/2769/4408 4061/2771/5034 4056/3571/5879 +f 2046/3572/5880 2045/3573/5881 1971/3465/5882 +f 2504/2385/4694 2503/3574/5883 2506/2459/4761 +f 4057/3575/5884 4056/3571/5879 4148/3156/5416 +f 4137/2177/4504 4138/3576/5885 4107/2835/5886 +f 3870/1999/4349 3868/1998/4348 3867/2111/4440 +f 3420/3577/5887 3419/2019/4365 3398/2514/5888 +f 3464/2546/4838 3466/2209/4532 3465/3578/5889 +f 3440/3579/5890 3407/3097/5353 3442/3096/5352 +f 2919/3042/5295 2924/3580/5891 2920/3581/5892 +f 2515/3582/5893 2516/3583/5894 2517/3584/5895 +f 2930/3585/26 2929/3586/26 2986/3587/26 +f 3856/3588/5896 3854/2032/5552 3853/3285/5551 +f 3617/2432/4737 3615/2434/4739 3616/2563/4851 +f 2913/3280/5548 2918/3589/5897 3048/3436/5722 +f 3945/2260/4580 3943/3203/5470 3944/3590/5354 +f 4092/2089/5898 4091/3591/5899 4093/3487/5777 +f 3151/2192/4518 3146/2756/5021 3165/2839/5095 +f 4050/2417/5354 4052/3592/5354 4048/3593/5354 +f 2302/3594/5900 2387/3165/5423 2303/3164/5422 +f 3781/3555/5860 3766/2221/4544 3767/2054/5858 +f 4230/3595/4517 4228/3596/4517 4194/2085/4517 +f 2755/2701/4970 2756/3597/5901 2758/3598/5902 +f 3171/3599/5903 3170/3600/5904 3185/2154/4482 +f 3566/2348/4660 3565/2297/4614 3528/2296/4613 +f 2793/2878/5134 2789/2690/4958 2795/3601/5905 +f 4331/3358/5632 4332/2517/5906 4333/3359/5633 +f 3153/3531/5907 3168/3602/5908 3150/2265/5909 +f 2414/3603/5910 2437/3604/5911 2380/3605/5912 +f 2424/3149/5410 2423/3606/5913 2422/3150/5411 +f 2119/3607/5914 2123/3608/5915 2122/3609/5916 +f 3376/2664/5610 3377/3339/5609 3379/2452/5594 +f 2241/3495/5784 2380/3605/5912 2437/3604/5911 +f 4118/2876/5132 4120/2022/5135 4132/2882/5137 +f 2744/2474/4773 2840/3610/5917 2839/3611/5918 +f 2745/2472/4771 2782/3612/5919 2783/3496/5785 +f 4337/3613/5920 4338/3540/5841 4339/3498/5921 +f 3689/2007/4353 3688/2596/4877 3687/2624/4905 +f 2639/3154/5831 2638/3614/5922 2926/3535/5832 +f 3144/2068/5923 3149/2631/5924 3173/3615/5925 +f 2572/3616/5926 2315/2996/5245 2316/3617/5927 +f 3257/2841/5928 3256/3618/5929 3254/2235/5930 +f 2016/2493/5931 2014/2492/5932 2029/3619/5933 +f 2420/3519/5812 2422/3150/5411 2433/3517/5810 +f 2965/2609/4889 2958/2783/5044 3075/2610/4890 +f 2807/3620/5934 2809/2140/4468 2988/2784/5045 +f 3555/3116/5374 3537/3621/5935 3538/3622/5936 +f 3388/3448/5738 3403/2883/5937 3422/2807/5644 +f 2346/3623/5938 2348/3624/5939 2350/2259/4579 +f 2730/2954/5201 2904/3110/5367 2727/3625/5940 +f 3717/3626/5941 3708/3627/5358 3713/2862/5942 +f 4014/2080/4416 4030/2082/4418 4013/3628/5943 +f 3207/3629/5944 3215/3630/5944 3331/3631/5944 +f 2287/3632/5945 2285/3633/5946 2184/3634/5947 +f 4138/3576/5885 4145/3635/5948 4146/3636/5949 +f 4217/2321/4637 4216/2320/4636 4218/3637/5950 +f 4011/3090/5951 4028/3638/5952 4025/3258/5522 +f 3586/3409/5692 3678/3216/5482 3590/3639/5953 +f 3063/3640/5954 3006/3036/5289 3007/3333/5603 +f 2478/2275/4592 2495/2926/5178 2487/2590/4871 +f 1969/1961/4314 1967/2240/5955 2067/3552/5856 +f 3235/3017/5956 3223/3641/5957 3224/3642/5958 +f 3308/3643/5959 3307/2627/4908 3306/3644/5960 +f 3836/2031/4375 3855/2030/4374 3837/2486/4786 +f 2070/2987/4316 2068/2564/4316 2072/2508/4316 +f 3147/3381/4406 3129/3146/4406 3131/2360/4406 +f 3124/3284/4406 3151/2192/4406 3122/3463/4406 +f 3710/2246/4566 3808/3245/5512 3709/3645/5961 +f 4010/3091/5347 4009/3646/5962 3999/3089/5345 +f 3117/2264/5963 3116/2263/5964 3115/3047/5965 +f 3689/2007/4353 3686/2101/4432 3651/2008/4354 +f 2767/3647/5966 2766/2989/5238 2725/2752/5020 +f 2697/3447/5736 2698/3648/5967 2778/2971/5218 +f 3515/2171/4388 3494/2107/4388 3516/2144/4388 +f 3646/3265/5531 3643/3649/5968 3659/2447/4751 +f 2927/3516/5809 2919/3042/5295 2629/3041/5294 +f 1981/2254/4574 1982/2866/5122 2001/3650/5969 +f 2248/3651/5970 2323/3652/5971 2247/3653/5972 +f 1989/2329/5732 1991/3107/5363 1988/2268/5730 +f 3226/2182/4511 3227/3654/5973 3245/2684/4952 +f 3511/2523/4816 3530/3536/5835 3510/2046/5834 +f 2524/3655/5974 2162/3656/5975 2161/3657/5976 +f 2524/3655/5974 2161/3657/5976 2160/3658/5977 +f 2170/2947/5978 2172/3659/5979 2525/3660/5980 +f 4302/2201/4525 4392/3661/5981 4376/2602/4883 +f 2272/2481/5982 2200/3662/5983 2199/3663/5984 +f 4082/2364/4677 4081/2363/4676 4083/3664/5985 +f 2149/3665/5986 2494/3666/5987 2150/3282/5988 +f 2022/2776/4585 2005/2186/4584 2007/2185/4585 +f 3476/2938/4388 3474/2286/4388 3475/2288/4388 +f 3273/2003/4351 3240/2005/4351 3242/2159/4351 +f 3694/2830/5089 3693/3667/5989 3667/3668/5990 +f 3141/3354/5627 3143/2250/4570 3158/2249/4569 +f 3517/2524/4817 3532/3064/5320 3531/2394/4706 +f 2052/2109/4438 2042/3669/5991 2041/3670/5992 +f 2795/3601/5905 2794/3671/5993 2793/2878/5134 +f 3181/2858/5115 3168/3602/5908 3183/2695/4963 +f 3123/3171/5994 3126/3672/5995 3124/3284/5996 +f 3142/3508/5797 3156/3673/5997 3157/2248/4568 +f 3253/3102/5325 3254/2235/5930 3255/3065/5998 +f 4149/2366/4679 4121/2816/5075 4146/3636/5949 +f 4205/3674/4517 4207/2846/5503 4231/2767/5503 +f 2540/3675/5999 2480/3676/6000 2539/3677/6001 +f 2160/3658/6002 2637/3678/6003 2926/3535/5832 +f 2531/3679/6004 2541/3680/6005 2530/3681/6006 +f 2075/3682/6007 2079/2741/6008 2077/3223/6009 +f 2707/2503/4800 2806/2505/4802 2705/3683/6010 +f 2544/3684/6011 2543/3685/6012 2491/3387/5665 +f 2776/2037/4381 2763/3686/6013 2761/2038/4382 +f 3627/2470/4770 3630/2633/4912 3629/2635/4912 +f 4382/2762/5027 4290/2809/5068 4383/2761/5026 +f 3489/2848/6014 3491/2105/5688 3472/3687/6015 +f 4136/2977/6016 4135/2978/6017 4144/3074/5329 +f 3657/2578/4863 3694/2830/5089 3656/2600/6018 +f 3079/3435/5721 3026/2455/4757 3024/1970/4323 +f 3188/3688/6019 3173/3615/5925 3172/3689/6020 +f 4139/2443/4747 4159/3690/6021 4128/2566/4852 +f 3936/2128/4455 4045/3691/6022 4046/2129/4456 +f 3461/2350/4662 3565/2297/4614 3566/2348/4660 +f 2096/3692/6023 2098/3693/6024 2099/2077/6025 +f 4349/2418/4725 4364/3213/6026 4355/3694/6027 +f 3472/3687/6015 3491/2105/5688 3473/3407/5687 +f 2621/3695/6028 2620/3696/6029 2913/3280/5548 +f 3467/2208/4531 3457/2207/4531 3468/3697/4531 +f 2973/3155/26 2139/2407/26 2938/2409/511 +f 4081/2363/4676 4080/2365/4678 4079/2064/4678 +f 4379/2522/4815 4294/1977/6030 4381/2520/4813 +f 2286/2358/4671 2212/2750/5018 2311/3124/5382 +f 2556/3141/5403 2544/3684/6011 2545/3698/6031 +f 3246/2622/4903 3245/2684/6032 3247/3699/6033 +f 3170/3600/5904 3169/2857/5114 3180/2152/4480 +f 3081/3454/5742 2717/2658/4930 2718/2660/4932 +f 3364/2513/4808 3362/2724/4755 3399/3347/4755 +f 2759/3700/6034 2761/2038/4382 2760/2463/4765 +f 3120/3172/6035 3123/3171/5994 3122/3463/6036 +f 2422/3150/5411 2420/3519/5812 2432/2411/4720 +f 2541/3680/6005 2537/3247/5514 2505/2386/4695 +f 3509/2544/4836 3525/2918/6037 3524/2851/6038 +f 3103/2796/6039 3118/3701/6040 3115/3047/5301 +f 3953/3702/5000 3949/3703/5000 3952/3704/5000 +f 3591/2511/4806 3592/3705/4434 3593/3706/6041 +f 2041/3670/6042 2027/2377/6043 2026/2667/4938 +f 3034/3707/6044 2862/3708/6045 2860/3709/6046 +f 3169/2857/5114 3170/3600/5904 3148/3710/6047 +f 3285/2148/4476 3296/2290/4607 3295/2149/4477 +f 4119/2012/4367 4120/2022/4367 4090/2021/4367 +f 2556/3141/5403 2545/3698/6031 2555/3139/5401 +f 2215/3006/5256 2286/2358/4671 2311/3124/5382 +f 4282/3711/6048 4167/2648/6048 4169/2892/6048 +f 4183/3712/6049 4192/2084/6050 4222/3413/5697 +f 2592/3492/6051 2593/3453/6052 2591/3713/6053 +f 4371/3714/6054 4370/3200/5467 4378/3003/5253 +f 2941/3560/26 2975/3559/26 2939/3715/26 +f 3430/3296/5562 3425/3716/6055 3424/3295/5561 +f 3300/3717/6056 3219/3718/6057 3301/3719/6058 +f 3777/3720/6059 3763/3721/6060 3778/2905/5159 +f 3476/2938/6061 3504/3722/6062 3506/2615/6063 +f 4270/3723/6064 4240/3125/5852 4239/3230/6065 +f 4003/2226/6066 4044/3724/6067 4043/3725/6068 +f 2757/3726/6069 2763/3686/6013 2756/3597/5901 +f 1987/2330/4644 1985/3727/6070 1977/3728/6071 +f 3046/3035/5288 3050/2694/4962 3006/3036/5289 +f 2606/3729/6072 2097/2712/6073 2696/2428/4734 +f 2569/3730/6074 2323/3652/5971 2322/3731/6075 +f 2570/2632/4911 2572/3616/5926 2318/2528/4821 +f 3993/3732/5000 3959/3733/5000 3957/3428/5000 +f 3520/3734/4388 3482/2763/4388 3514/2543/4388 +f 2566/3735/6076 2321/2705/4974 2320/2704/4973 +f 4180/2891/5144 4179/2880/4924 4175/2567/4924 +f 2629/3041/5294 2153/3514/5807 2927/3516/5809 +f 3654/3309/5577 3639/2599/4880 3655/2601/4882 +f 3482/2763/6077 3483/2555/5155 3481/3736/6078 +f 2981/3737/6079 2969/3558/6080 2970/3557/6081 +f 3015/2994/5243 2168/2588/6082 2884/3738/6083 +f 1965/3739/6084 1964/3740/6085 2056/3418/5700 +f 2050/3444/5733 2053/3741/6086 2054/3445/5734 +f 2481/3742/6087 2483/3513/5806 2507/3743/6088 +f 3124/3284/4406 3126/3672/4406 3146/2756/4406 +f 1964/3740/6085 2058/2927/5179 2056/3418/5700 +f 2122/3609/5916 2120/2800/5060 2121/2410/6089 +f 4055/3744/4409 4054/2769/4408 4056/3571/5879 +f 2390/3745/6090 2263/3430/6091 2211/3208/5475 +f 3902/3055/6092 3910/2361/4674 3901/3746/6093 +f 2637/3678/6094 2160/3658/6095 2159/3153/5414 +f 2574/3747/6096 2583/3748/6097 2510/3192/6098 +f 1999/3749/6099 2000/3750/6100 1998/2379/5342 +f 2462/3390/5669 2459/2826/5085 2406/2399/4711 +f 2120/2800/5060 2130/2802/5062 2121/2410/6089 +f 3718/2911/4336 3723/3130/4336 3726/3751/4336 +f 3695/2188/6101 3579/2103/6101 3585/2173/6101 +f 2999/3752/6102 2995/3753/6103 2996/1980/6104 +f 2742/3754/6105 2764/3755/6106 2754/3756/6107 +f 4043/3725/6068 3941/3757/6108 4042/3563/5866 +f 3459/3758/6109 3454/2594/4532 3460/2214/4532 +f 3763/3721/6060 3776/3759/6110 3760/3760/6111 +f 3246/2622/4903 3243/2183/4904 3245/2684/6032 +f 3766/2221/4337 3746/3092/5348 3767/2054/4337 +f 3479/3761/6112 3477/3762/6113 3478/2384/6113 +f 3702/3763/5804 3811/3764/5804 3812/3101/5804 +f 3475/2288/4605 3502/3765/6114 3476/2938/6061 +f 3597/3340/4524 3599/3766/4524 3595/2738/4524 +f 2170/2947/5978 2526/3767/6115 2527/3768/6116 +f 3580/2537/4830 3700/2539/4830 3587/3769/4830 +f 1975/2239/4561 1968/2241/4316 1976/2506/4316 +f 3805/3770/6117 3804/3771/6118 3777/3720/6059 +f 3874/3431/4554 3856/3588/5778 3887/3402/4554 +f 3327/2040/4383 3331/3631/6119 3330/2041/4383 +f 2946/3772/6120 2947/3773/6121 2903/3375/6122 +f 4117/2875/5131 4135/2978/5226 4113/2468/5225 +f 2515/3582/5893 2508/3190/5457 2507/3743/6088 +f 2206/3774/6123 2205/3775/6124 2259/3776/6125 +f 2206/3774/6123 2258/3777/6126 2207/3778/6127 +f 2258/3777/6126 2257/2746/6128 2207/3778/6127 +f 2257/2746/6128 2208/3779/6129 2207/3778/6127 +f 2208/3779/6129 2256/2745/6130 2209/3780/6131 +f 2209/3780/6131 2256/2745/6130 2255/3781/6132 +f 2209/3780/6131 2255/3781/6132 2210/3782/6133 +f 2210/3782/6133 2255/3781/6132 2254/3783/6134 +f 2709/3784/6135 2808/2504/4801 2707/2503/4800 +f 2155/3785/6136 2633/3330/5599 2634/3329/5598 +f 3799/3198/5465 3788/3197/5464 3789/3786/6137 +f 2268/2924/6138 2204/3787/6139 2269/3788/6140 +f 4136/2977/5224 4137/2177/4504 4111/2176/4503 +f 3781/3555/5860 3792/3789/6141 3780/2222/4545 +f 2202/3790/6142 2267/3791/6143 2203/3792/6144 +f 3376/2664/5610 3379/2452/5594 3378/2873/5594 +f 2106/3793/6145 2107/2985/6146 2108/3794/6147 +f 3041/3795/6148 2870/3796/6149 2869/3797/6150 +f 4199/3108/6151 4185/3421/6152 4201/3109/6153 +f 2276/3798/6154 2195/3799/6155 2277/3800/6156 +f 3335/2773/5878 3333/2230/5878 3343/2020/4626 +f 2196/3801/6157 2276/3798/6154 2275/3438/6158 +f 2196/3801/6157 2275/3438/6158 2197/3802/6159 +f 3185/2154/4482 3096/2424/6160 3095/2790/5051 +f 1972/3467/5756 1974/3466/5755 1976/2506/4316 +f 2198/3803/6161 2273/2482/6162 2199/3663/5984 +f 4134/2874/5130 4118/2876/5132 4133/3478/5768 +f 2200/3662/5983 2272/2481/5982 2270/3804/6163 +f 2642/3805/6164 3018/3806/6165 3017/3807/6166 +f 3723/3130/4336 3721/1985/4336 3722/3183/5348 +f 3850/3808/6167 3849/3809/6168 3847/3103/5359 +f 4301/2202/4526 4296/1978/6169 4378/3003/5253 +f 3282/3810/6170 3281/2828/5087 3325/2827/5086 +f 3394/3368/5643 3421/2772/5619 3393/3346/5618 +f 3949/3703/5000 3947/2252/5000 3948/3811/5000 +f 2194/3812/6171 2283/2357/6172 2282/2356/6173 +f 3413/3813/6174 3338/3814/6175 3412/3298/5564 +f 2183/3815/6176 2281/3816/6177 2184/3634/5947 +f 3191/3817/6178 3190/3020/5271 3189/3022/5273 +f 2185/3818/6179 2285/3633/5946 2294/3819/6180 +f 2291/3820/6181 2187/3821/6182 2292/3423/6183 +f 3384/3490/5780 3387/2236/4558 3386/2238/4560 +f 2958/2783/5044 2963/2500/4797 2961/2912/5166 +f 2780/2970/5217 2698/3648/5967 2797/3144/5406 +f 2068/2564/5079 2070/2987/5079 1970/1963/5079 +f 3965/3822/6184 3948/3811/6185 3963/3823/6186 +f 3215/3630/6119 3221/3824/6187 3220/3550/4383 +f 2778/2971/5218 2777/3293/5559 2700/3269/5538 +f 2289/3426/6188 2191/3825/6189 2190/3826/6190 +f 2290/3827/6191 2190/3826/6190 2188/3828/6192 +f 4360/2716/4985 4346/3829/6193 4345/3830/6194 +f 3322/3831/6195 3292/2829/5088 3280/3832/6196 +f 2623/3279/5547 2621/3695/6028 2913/3280/5548 +f 2291/3820/6181 2189/3833/6197 2187/3821/6182 +f 3385/3491/4755 3388/3448/4755 3387/2236/4755 +f 2360/3834/6198 2359/3835/6199 2384/3836/6200 +f 3172/3689/6020 3171/3599/5903 3187/3837/6201 +f 3701/3838/5358 3707/2247/4567 3706/3839/5358 +f 3844/2395/5778 3873/2397/4554 3876/3840/4554 +f 3909/2052/6202 3908/3841/6203 3879/3842/6204 +f 2829/2441/4745 2665/2440/4744 2912/2475/4774 +f 3214/3034/5286 3218/3843/6205 3303/3844/6206 +f 2464/2449/6207 2405/3845/6208 2385/3846/6209 +f 3068/3847/6210 3069/3848/6211 3030/3082/5337 +f 2353/3849/6212 2218/2982/5229 2217/3850/6213 +f 4367/2206/4530 4376/2602/4883 4392/3661/5981 +f 2000/3750/4585 2026/2667/4584 1998/2379/4585 +f 2271/2483/4782 2266/3851/6214 2318/2528/4821 +f 2110/3852/6215 2112/3160/6216 3082/2685/4953 +f 2065/2653/4928 2048/2353/4666 2049/2542/4833 +f 3040/3317/5585 3046/3035/5288 3045/3037/5290 +f 2536/2675/4944 2533/2312/4629 2535/2311/4628 +f 3474/2286/4603 3473/3407/5687 3493/3336/5689 +f 2779/2421/4728 2794/3671/5993 2777/3293/5559 +f 3717/3626/5941 3787/3199/5466 3711/3853/6217 +f 3933/3012/5355 3932/2325/5354 3934/3854/6218 +f 4184/3422/5708 4185/3421/6152 4197/3425/5706 +f 3092/3542/6219 3204/3855/6219 3205/3856/6219 +f 2581/3483/5773 2461/3482/5772 2460/3857/6220 +f 2581/3483/5773 2460/3857/6220 2582/2095/4428 +f 2950/3858/6221 2911/3312/5580 2906/2075/4411 +f 2739/3859/6222 2740/3002/5252 2741/2593/4874 +f 3840/2178/4554 3836/2031/4554 3839/2231/4554 +f 2110/3852/6223 2111/3860/6224 2112/3160/6224 +f 4374/3068/6225 4353/3861/6226 4373/3862/6227 +f 3585/2173/4434 3579/2103/4434 3588/3863/6228 +f 3703/3864/6229 3702/3763/5358 3704/3474/5358 +f 2519/3865/6230 2179/3133/6231 2586/3866/6232 +f 4066/2073/4409 4058/2072/4408 4064/2579/6233 +f 2509/3367/5642 2479/2571/4856 2538/2570/4855 +f 2584/3867/6234 2512/3450/6235 2511/3366/6236 +f 2584/3867/6234 2511/3366/6236 2583/3748/6097 +f 2816/3868/6237 2803/3869/6238 2815/3023/5274 +f 3783/3870/6239 3794/3871/6240 3782/3554/6241 +f 4007/3872/6242 3986/3873/6243 4008/3874/6244 +f 3830/2650/4690 3832/1993/4690 3826/2984/4688 +f 3121/3875/6245 3122/3463/4406 3152/2194/4406 +f 3551/2813/5072 3538/3622/5936 3539/2960/5207 +f 2350/2259/4579 2166/3257/6246 2168/2588/6247 +f 3656/2600/6018 3667/3668/5990 3655/2601/4882 +f 2022/2776/6248 2015/3274/5764 2033/3476/5766 +f 3950/2242/5001 3952/3704/5000 3949/3703/5000 +f 2593/3453/5741 2592/3492/5781 2719/2659/4931 +f 3415/2196/6249 3426/3876/6250 3445/3877/6251 +f 2925/3878/6252 2922/3500/5789 2921/3499/5788 +f 3797/2793/5054 3798/2792/5053 3717/3626/5941 +f 4119/2012/4358 4130/2266/4583 4131/2881/5136 +f 3190/3020/5271 3193/3399/5680 3155/3509/6253 +f 3518/2170/4499 3532/3064/5320 3517/2524/4817 +f 3599/3766/4524 3597/3340/4524 3598/3879/4524 +f 2814/3880/6254 2813/3881/6255 2987/2785/5046 +f 2813/3881/6255 2812/2786/5047 2987/2785/5046 +f 2814/3880/6254 2987/2785/5046 2714/2897/5149 +f 4123/3882/6256 4122/2815/5074 4152/3032/5284 +f 2078/2740/6257 2080/2457/5635 2383/3360/5634 +f 2004/2184/4514 2006/2865/4515 2007/2185/4515 +f 3139/2300/6258 3138/1964/6259 3108/3883/6260 +f 4363/3214/5480 4388/3884/6261 4389/3215/5481 +f 3840/2178/4506 3839/2231/6262 3866/2112/4507 +f 3967/2270/6263 3949/3703/6264 3965/3822/6184 +f 3719/1986/5394 3729/2910/5164 3731/3885/6265 +f 4211/3456/5503 4212/3886/4517 4232/2606/5503 +f 2246/2703/4972 2445/2092/4425 2443/3121/5379 +f 3184/2153/4481 3180/2152/4480 3181/2858/5115 +f 2342/3239/5506 2350/2259/4579 2526/3767/6115 +f 3275/2219/4542 3274/2137/4465 3313/3887/6266 +f 2847/2497/4794 2846/3888/6267 2736/2901/5154 +f 3850/3808/6167 3847/3103/5359 3848/3889/5359 +f 2542/3388/5666 2524/3655/5974 2490/3386/5664 +f 3772/3181/5445 3787/3199/6268 3786/3182/5446 +f 2820/3432/5717 2810/2138/4466 2709/3784/6135 +f 3837/2486/4786 3855/2030/4374 3858/2313/4787 +f 3595/2738/4524 3601/3044/5297 3602/3890/4524 +f 1995/2972/5344 1996/2378/5343 1994/3891/6269 +f 3150/2265/4406 3117/2264/4406 3119/3532/4406 +f 2958/2783/5044 2957/3892/6270 3075/2610/4890 +f 2228/2494/4791 2227/3893/6271 2229/3894/6272 +f 2481/3742/6087 2480/3676/6000 2540/3675/5999 +f 2051/3895/6273 2042/3669/5991 2053/3741/6086 +f 2923/3138/5399 2922/3500/5789 3064/3228/5496 +f 4379/2522/4815 4374/3068/5323 4373/3862/6274 +f 2962/2782/6275 2972/3896/6276 2971/2934/6277 +f 3665/3132/6278 3680/3897/6279 3664/3898/6280 +f 3441/3899/6281 3439/2015/4361 3440/3579/5890 +f 3284/3900/6282 3271/2004/6283 3273/2003/6284 +f 3605/2737/6285 3606/2198/6285 3608/2200/6286 +f 4365/3901/6287 4364/3213/5479 4391/3902/6288 +f 3794/3871/6240 3796/3903/6289 3716/3114/5371 +f 3822/3234/6290 3920/3457/5746 3921/2372/4686 +f 3137/3904/4406 3139/2300/4406 3140/2069/4406 +f 3105/1988/4338 3125/2216/4538 3104/2795/5433 +f 4370/3200/5467 4369/3201/6291 4377/2203/4527 +f 3417/2935/5183 3429/2869/5125 3416/2868/5124 +f 3564/3905/6292 3527/2298/4615 3565/2297/4614 +f 2025/2944/4585 1994/3891/4585 1996/2378/4585 +f 2246/2703/4972 2248/3651/5970 2445/2092/4425 +f 4009/3646/5962 4020/3906/6293 4008/3874/6294 +f 3404/2162/4491 3390/3907/6295 3405/2160/4489 +f 3715/3908/6296 3797/2793/5054 3717/3626/5941 +f 3962/3909/6297 3964/3910/6298 3963/3823/6299 +f 3891/3318/5586 3878/3187/5453 3892/3911/6300 +f 3821/2540/4831 3914/2291/4608 3820/2375/4689 +f 4100/2744/4367 4102/2743/4367 4109/3148/4367 +f 3567/2167/4496 3570/2166/4495 3462/3912/6301 +f 3107/1965/4318 3134/2485/4784 3106/1989/4339 +f 4034/3913/6302 4035/3914/6303 4033/3915/6304 +f 2453/3290/5556 2133/3369/5645 2132/3291/5557 +f 2737/1967/4320 2741/2593/4874 2740/3002/5252 +f 3595/2738/4524 3599/3766/4524 3601/3044/5297 +f 3536/2460/4762 3554/3505/5794 3552/2461/4763 +f 3289/2626/4907 3306/3644/5960 3307/2627/4908 +f 3824/1983/4688 3823/2649/4688 3827/1984/4690 +f 3280/3832/6196 3279/3080/5335 3322/3831/6195 +f 3804/3771/6118 3805/3770/6117 3803/3262/5528 +f 3618/2433/4738 3617/2432/4737 3619/3916/6305 +f 3456/3917/6306 3560/3918/6307 3561/2115/4444 +f 2055/3919/6308 2057/3417/5699 2029/3619/5933 +f 4162/3416/4409 4166/3415/4409 4164/2580/4409 +f 3311/3920/6309 3313/3887/6266 3312/3921/6310 +f 2692/2689/4957 2788/2668/4939 2693/3544/5844 +f 4166/3415/6311 4060/3414/6311 4064/2579/6312 +f 3699/2187/6313 3587/3769/6313 3700/2539/6313 +f 3382/2043/6314 3385/3491/5780 3384/3490/5780 +f 2211/3208/5475 2361/3922/6315 2390/3745/6090 +f 3758/2163/6316 3726/3751/6317 3757/2164/6318 +f 2879/2344/4656 2878/3923/6319 2876/3924/6320 +f 3171/3599/5903 3186/2791/5052 3187/3837/6201 +f 2099/2077/6321 2098/3693/6322 2601/3925/6323 +f 4253/3926/6324 4252/3927/6325 4263/3304/5570 +f 3998/3522/5815 4011/3090/5346 3999/3089/5345 +f 2248/3651/5970 2247/3653/5972 2444/2090/4423 +f 3312/3921/6310 3274/2137/4465 3293/3928/6326 +f 3506/2615/4896 3508/2383/4692 3507/2382/4691 +f 3398/2514/5888 3418/2937/5185 3400/2936/5184 +f 2015/3274/5764 2031/3929/6327 2032/3475/5765 +f 3297/3930/6328 3283/3931/6329 3298/3932/6330 +f 1987/2330/5731 1986/2267/6331 1985/3727/6331 +f 2325/3933/6332 2320/2704/4973 2246/2703/4972 +f 3160/3355/6333 3159/2822/5081 3179/2821/5080 +f 2610/3934/6334 2609/2915/6335 2086/2843/6336 +f 2257/2746/5014 2258/3777/6337 2251/2747/5015 +f 2784/3371/5647 2783/3496/5785 2782/3612/5919 +f 4273/3935/6338 4171/3936/6339 4276/3066/5321 +f 2563/2339/4651 2329/2341/4653 2327/3937/6340 +f 2148/3040/5293 2919/3042/5295 2918/3589/5897 +f 2499/2025/4369 2500/2654/4929 2502/2387/4696 +f 3758/2163/4492 3759/2165/4494 3728/3938/6341 +f 3650/2100/6342 3636/2133/4460 3651/2008/4462 +f 4074/2059/4367 4073/3568/5872 4070/2431/4367 +f 3108/3883/6260 3109/2389/6343 3110/2070/6344 +f 2155/3785/6345 2158/3534/5830 2926/3535/5832 +f 3206/3015/4383 3209/3939/6119 3207/3629/6119 +f 3593/3706/6041 3583/2174/4434 3584/3322/4434 +f 4220/3940/6346 4217/2321/4637 4218/3637/5950 +f 3100/1966/4319 3101/2388/4699 3109/2389/4701 +f 3918/3319/5587 3920/3457/5746 3817/3941/6347 +f 3963/3823/6299 3964/3910/6298 3966/3942/6348 +f 3695/2188/6349 3580/2537/6349 3579/2103/6349 +f 2509/3367/5642 2538/2570/4855 2539/3677/6001 +f 3095/2790/5051 3091/3943/6350 3186/2791/5052 +f 4008/3874/6294 4021/3944/6351 4047/2127/4454 +f 2084/3945/6352 2605/3946/6353 2603/3947/6354 +f 2925/3878/6252 3053/3948/6355 3054/3949/6356 +f 2075/3682/6357 2606/3729/6358 2074/3176/6359 +f 2089/2968/6360 2219/3389/5668 2091/2887/5667 +f 3883/3950/4554 3859/2315/4554 3881/2707/4554 +f 3576/2213/4536 3460/2214/4536 3577/2595/4536 +f 4303/3276/4422 4311/3951/6361 4309/2519/4422 +f 1991/3107/4585 2019/2613/4585 1988/2268/4585 +f 3779/2904/5158 3809/3952/6362 3808/3245/5512 +f 4267/3953/6363 4266/3954/6364 4180/2891/5144 +f 2290/3827/6191 2289/3426/6188 2190/3826/6190 +f 3734/2753/6365 3735/2066/6366 3733/3134/6367 +f 2389/3955/6368 2409/3396/5677 2435/3956/6369 +f 3771/3957/6370 3765/2755/6371 3789/3786/6372 +f 3457/2207/4531 3458/2336/5703 3462/3912/4532 +f 4385/2715/4984 4290/2809/5068 4361/3057/5313 +f 3640/2150/4524 3621/3565/4524 3639/2599/4524 +f 2150/3282/5550 2148/3040/5293 2913/3280/5548 +f 2181/2913/6373 2613/2502/6374 2178/2933/6375 +f 3142/3508/4406 3135/3158/5056 3137/3904/4406 +f 3504/3722/6062 3476/2938/6061 3502/3765/6114 +f 2615/3958/6376 2614/3959/6377 2616/3960/6378 +f 2615/3958/6376 2616/3960/6378 2617/3169/6379 +f 3250/3071/6380 3248/3193/6381 3227/3654/5973 +f 3149/2631/4406 3144/2068/4406 3112/2317/4406 +f 3388/3448/5738 3404/2162/4491 3403/2883/5937 +f 2311/3124/5382 2310/3961/6382 2215/3006/5256 +f 2012/3962/6383 1986/2267/6383 2013/2061/6383 +f 2624/3963/6384 2623/3279/6385 2625/3115/6386 +f 3473/3407/4388 3476/2938/4388 3472/3687/4388 +f 3675/2445/4749 3676/2510/4805 3673/2637/4915 +f 2622/3964/6387 2626/3965/6388 2620/3696/6389 +f 3694/2830/5089 3667/3668/5990 3656/2600/6018 +f 3371/3028/5280 3369/3966/6390 3370/2884/6390 +f 2627/3281/6391 2626/3965/6388 2628/3569/5876 +f 4314/2122/4422 4316/3967/4422 4352/1996/4422 +f 2862/3708/6045 2859/3968/6392 2860/3709/6046 +f 4176/2779/5040 4277/2778/5039 4276/3066/5321 +f 3359/3969/6393 3360/2723/4992 3361/2722/4991 +f 2482/3970/6394 2540/3675/5999 2541/3680/6005 +f 2914/3062/5317 2916/3170/5430 2618/2228/5429 +f 3103/2796/6039 3115/3047/5301 3102/3046/5300 +f 3458/2336/4650 3574/2512/4650 3572/2337/4650 +f 2855/3971/6395 2857/3972/6396 2856/3973/6397 +f 3540/2621/4902 3519/3974/6398 3541/2533/6399 +f 2852/2674/4943 2893/2673/4942 2892/3975/6400 +f 2194/3812/6171 2201/3084/5339 2280/3085/5341 +f 4048/3593/5817 3932/2325/5817 3931/3976/5817 +f 2238/2293/4610 2436/2840/5096 2233/2294/4611 +f 2253/2922/5174 2446/3301/5567 2250/2923/5175 +f 2629/3041/6401 2631/3977/6402 2153/3514/6403 +f 3038/2526/4819 2866/3978/6404 2863/3979/6405 +f 3352/2656/6406 3369/3966/6407 3371/3028/6408 +f 3746/3092/5348 3766/2221/4337 3770/2223/4337 +f 2801/3373/5649 2691/3372/5648 2690/3980/6409 +f 3936/2128/4455 4047/2127/4454 3945/2260/4580 +f 2155/3785/6136 2635/3981/6410 2158/3534/6411 +f 2102/2010/6412 2602/2427/6413 2601/3925/6323 +f 2418/3249/5516 2426/3400/5681 2431/3151/5412 +f 2640/3982/6414 2158/3534/6411 2635/3981/6410 +f 2328/3983/6415 2327/3937/6340 2242/3250/5517 +f 2637/3678/6094 2641/3984/6416 2161/3657/6417 +f 2161/3657/6417 2641/3984/6416 2163/3985/6418 +f 3325/2827/5086 3292/2829/5088 3324/3986/6419 +f 2731/2751/5019 2765/2498/4795 2736/2901/5154 +f 2479/2571/4856 2307/3987/6420 2306/2572/4857 +f 3193/3399/5680 3190/3020/5271 3192/3052/5308 +f 3835/2381/6421 3847/3103/6422 3849/3809/6423 +f 3896/2706/4975 3924/3988/6424 3923/3142/5404 +f 3378/2873/5129 3353/2665/4934 3376/2664/4933 +f 2689/2670/4941 2690/3980/6409 2691/3372/5648 +f 2692/2689/4957 2693/3544/5844 2694/3989/6425 +f 2113/3159/5417 2111/3860/6426 2112/3160/5418 +f 3118/3701/6427 3117/2264/5963 3115/3047/5965 +f 2958/2783/5044 2962/2782/5043 2963/2500/4797 +f 2055/3919/6308 1965/3739/6084 2056/3418/5700 +f 2904/3110/5367 2909/3990/6428 2908/3991/6429 +f 2698/3648/5967 2078/2740/6430 2076/3177/6431 +f 2699/2272/4589 2603/3947/6432 2697/3447/5736 +f 2697/3447/5736 2603/3947/6432 2604/3992/6433 +f 2522/2276/4593 2478/2275/4592 2520/3993/6434 +f 2609/2915/5169 2611/2273/4590 2700/3269/5538 +f 2700/3269/5538 2701/2036/4380 2609/2915/5169 +f 2030/3994/6435 2031/3929/6327 2017/3273/6436 +f 2703/3995/6437 2091/2887/6438 2704/3996/6439 +f 2858/3997/6440 3033/3998/6441 2860/3709/6046 +f 2702/3385/5663 2704/3996/6439 2094/2914/5168 +f 2707/2503/4800 2708/3999/6442 2709/3784/6135 +f 2805/4000/6443 2711/4001/6444 2710/4002/6445 +f 4047/2127/4454 4021/3944/6351 3945/2260/4580 +f 2559/4003/6446 2525/3660/5980 2524/3655/5974 +f 3628/3443/4524 3636/2133/4524 3630/2633/4524 +f 3897/2708/4977 3874/3431/5716 3898/3401/5682 +f 2240/4004/6447 2380/3605/5912 2241/3495/5784 +f 3057/3501/5790 3054/3949/6356 3056/3233/5501 +f 2040/2110/4439 2052/2109/4438 2041/3670/5992 +f 3918/3319/5587 3891/3318/5586 3919/3458/5747 +f 2730/2954/5201 2723/3093/5349 2722/2952/5199 +f 2572/3616/5926 2570/2632/4911 2552/2392/4704 +f 4028/3638/5952 4012/3523/6448 4030/2082/4418 +f 3121/3875/6449 3120/3172/6035 3122/3463/6036 +f 4001/2279/4596 3990/4005/6450 3991/2280/4597 +f 4282/3711/6048 4169/2892/6048 4283/4006/6048 +f 3780/2222/4545 3809/3952/6362 3779/2904/5158 +f 2332/4007/6451 2340/3364/5639 2523/3420/5702 +f 3402/2885/6452 3400/2936/5184 3417/2935/5183 +f 2203/3792/6144 2265/4008/6453 2195/3799/6155 +f 3362/2724/4993 3363/3332/5391 3361/2722/4991 +f 3998/3522/5000 3966/3942/5000 3964/3910/5000 +f 2299/2895/5147 2300/4009/6454 2397/4010/6455 +f 3029/3100/5357 2890/2957/5204 2891/4011/6456 +f 3657/2578/4863 3645/4012/6457 3658/2446/4750 +f 2728/2988/5237 2727/3625/5940 2729/4013/6458 +f 3971/3524/5000 3986/3873/5000 3973/4014/5000 +f 4293/4015/4329 4292/2604/4329 4299/4016/4329 +f 2289/3426/6188 2288/2735/6459 2191/3825/6189 +f 2732/4017/6460 2731/2751/5019 2736/2901/5154 +f 3382/2043/6314 3383/4018/6314 3385/3491/5780 +f 2391/4019/6461 2396/3551/5854 2263/3430/6462 +f 2398/2896/5148 2389/3955/6368 2298/2734/5002 +f 3406/4020/6463 3423/2283/4600 3436/2282/4599 +f 3020/4021/6464 2958/2783/5044 2961/2912/5166 +f 4277/2778/5039 4243/2991/5240 4275/2993/5242 +f 3065/3446/5735 3048/3436/5722 3058/4022/6465 +f 2311/3124/5382 2530/3681/6006 2310/3961/6382 +f 3084/4023/4731 3086/3053/4731 3085/2678/4731 +f 4387/3056/5312 4388/3884/6261 4362/2420/4727 +f 4246/2607/4887 4247/2765/6466 4231/2767/6467 +f 2027/2377/6043 2042/3669/5991 2025/2944/5190 +f 2871/4024/6468 2870/3796/6149 3039/4025/6469 +f 2932/4026/26 2935/4027/512 2981/3737/26 +f 4028/3638/5952 4030/2082/4418 4027/3553/5857 +f 4339/3498/4422 4341/3539/4422 4351/3497/4422 +f 3021/4028/6470 3076/2611/4891 3075/2610/4890 +f 3207/3629/6471 3327/2040/6471 3326/2039/6471 +f 1970/1963/4316 1966/2535/4828 1962/2820/6472 +f 3351/2854/5111 3350/4029/6473 3365/2855/5112 +f 4190/3461/5750 4218/3637/6474 4216/2320/5751 +f 2827/4030/6475 2856/3973/6397 2825/4031/6476 +f 2797/3144/5406 2695/3338/5607 3082/2685/4953 +f 3641/4032/6477 3662/3442/6478 3661/3382/5658 +f 4055/3744/4409 4056/3571/5879 4057/3575/4409 +f 4133/3478/6479 4132/2882/6480 4142/4033/6481 +f 2590/3493/5782 2124/4034/6482 2718/2660/4932 +f 4318/3348/6483 4315/4035/6484 4317/4036/6485 +f 3504/3722/6486 3505/2614/4895 3506/2615/4896 +f 4186/2832/5091 4187/2210/4533 4204/2212/4535 +f 3716/3114/5371 3810/3113/5370 3794/3871/6240 +f 4261/2028/4372 4262/2597/4878 4267/3953/6363 +f 2560/3077/5332 2559/4003/6446 2558/4037/6487 +f 2221/2495/4792 2393/2559/4847 2091/2887/5667 +f 2285/3633/5946 2185/3818/6179 2184/3634/5947 +f 3437/2281/4598 3434/2161/4490 3436/2282/4599 +f 2617/3169/6379 2619/2229/4552 2618/2228/4551 +f 3265/2034/4378 3264/2135/4463 3275/2219/4542 +f 2721/4038/6488 2686/2953/5200 2715/3135/5396 +f 2693/3544/5844 2689/2670/4941 2694/3989/6425 +f 2557/4039/6489 2544/3684/6011 2556/3141/5403 +f 3541/2533/6399 3520/3734/6490 3542/4040/6491 +f 2777/3293/5559 2796/4041/6492 2776/2037/4381 +f 4084/3010/5262 4085/3011/5264 4083/3664/5985 +f 3223/3641/5957 3233/3019/6493 3231/4042/6494 +f 2564/3140/5402 2329/2341/4653 2562/2340/4652 +f 3256/3618/5929 3255/3065/5998 3254/2235/5930 +f 2701/2036/4380 2761/2038/4382 2702/3385/5663 +f 2774/3530/5828 2801/3373/5649 2800/2636/4914 +f 2743/4043/6495 2744/2474/4773 2764/3755/6106 +f 3036/2859/5116 3072/3489/5779 3035/3039/5292 +f 3836/2031/4375 3852/3286/6496 3854/2032/4376 +f 4334/2617/6497 4335/2616/6498 4336/2638/6499 +f 3922/1982/4333 3921/2372/4686 3894/2371/4685 +f 3819/2374/4796 3925/2499/4796 3926/3546/4796 +f 3813/3212/5358 3812/3101/5358 3811/3764/5358 +f 3951/4044/6500 3950/2242/4562 3972/4045/6501 +f 2028/4046/6502 2047/2612/6503 2055/3919/6308 +f 3025/2405/4717 2894/2404/4716 2895/2454/4756 +f 2345/3241/5508 2346/3623/5938 2350/2259/4579 +f 2503/3574/5883 2518/4047/6504 2515/3582/5893 +f 2918/3589/5897 2919/3042/5295 3048/3436/5722 +f 3277/2117/4446 3276/2035/4541 3320/2118/4447 +f 3334/3512/5805 3433/3059/5315 3435/2301/4618 +f 2081/2458/4760 2084/3945/6505 2082/2456/4758 +f 2478/2275/4592 2486/2277/4594 2495/2926/5178 +f 2422/3150/5411 2421/4048/6506 2433/3517/5810 +f 3589/3323/6507 3654/3309/5577 3690/3434/5719 +f 2014/2492/5932 2047/2612/4892 2028/4046/6508 +f 2931/4049/26 2928/4050/26 2984/4051/26 +f 2745/2472/4771 2744/2474/4773 2743/4043/6495 +f 2974/3351/26 2942/3561/26 2943/4052/26 +f 2947/3773/26 2946/3772/26 2930/3585/26 +f 4258/4053/6509 4239/3230/5498 4224/3229/5497 +f 2298/2734/5002 2295/2962/6510 2296/2961/6511 +f 2397/4010/6455 2398/2896/5148 2299/2895/5147 +f 4101/2742/6512 4099/3529/5873 4074/2059/4397 +f 3510/2046/5834 3528/2296/5720 3513/3168/5427 +f 2812/2786/5047 2807/3620/5934 2988/2784/5045 +f 4127/2444/4748 4126/3362/5637 4158/2442/4746 +f 2802/4054/6513 2721/4038/6488 2803/3869/6238 +f 2712/2899/5151 2813/3881/6255 2814/3880/6254 +f 3420/3577/5887 3398/2514/5888 3399/3347/5620 +f 2327/3937/6340 2243/3049/5304 2242/3250/5517 +f 3518/2170/4388 3495/3337/4388 3515/2171/4388 +f 4012/3523/6448 4028/3638/5952 4011/3090/5951 +f 3260/3145/6514 3257/2841/5928 3259/3226/6515 +f 3119/3532/4406 3121/3875/6245 3153/3531/4406 +f 2406/2399/4711 2407/2401/4713 2382/3477/5767 +f 3522/4055/4388 3490/2847/4388 3523/2585/4388 +f 3472/3687/4388 3470/2554/4388 3471/2556/4388 +f 2811/2139/4467 2816/3868/6237 2809/2140/4468 +f 4359/3202/5469 4369/3201/5468 4370/3200/6516 +f 2521/4056/6517 2522/2276/4593 2520/3993/6434 +f 3875/4057/6518 3889/2053/6519 3876/3840/6520 +f 2983/4058/26 2943/4052/26 2944/4059/26 +f 4038/3470/5759 4039/4060/6521 4018/2818/5077 +f 4254/4061/6522 4235/4062/6523 4253/3926/6524 +f 4105/2836/6525 4102/2743/5011 4103/4063/6526 +f 3611/3341/6527 3614/4064/4850 3613/2562/4850 +f 3569/2717/4986 3549/2719/4988 3548/4065/6528 +f 3781/3555/5860 3714/3112/5369 3792/3789/6141 +f 2096/3692/6529 2075/3682/6530 2095/3178/6531 +f 1968/2241/4316 1967/2240/4316 1969/1961/4314 +f 3551/2813/5072 3555/3116/5374 3538/3622/5936 +f 3880/4066/6532 3905/2305/6533 3885/2787/5048 +f 2745/2472/4771 2743/4043/6495 2782/3612/5919 +f 2303/3164/5422 2304/3503/5792 2301/3502/5791 +f 4112/2175/4502 4137/2177/4504 4107/2835/5886 +f 3112/2317/4634 3113/2319/4635 3114/2630/6534 +f 3206/3015/6535 3328/2672/6535 3213/2920/6535 +f 4363/3214/5480 4362/2420/4727 4388/3884/6261 +f 4320/2951/6536 4323/3288/6537 4321/3349/6538 +f 2002/3334/6539 2001/3650/6540 2003/4067/6541 +f 2243/3049/5304 2439/3251/5518 2242/3250/5517 +f 2805/4000/6443 2705/3683/6010 2806/2505/4802 +f 3933/3012/5265 4018/2818/5077 4040/3013/5266 +f 2110/3852/6215 3082/2685/4953 2598/4068/6542 +f 3769/4069/4336 3750/2132/4336 3748/2550/4336 +f 2231/2332/4646 2228/2494/4791 2230/2333/4647 +f 3586/3409/5692 3677/4070/6543 3662/3442/5729 +f 3954/4071/5000 3949/3703/5000 3953/3702/5000 +f 4374/3068/5323 4379/2522/4815 4380/2521/4814 +f 2049/2542/4833 2035/2541/4832 2034/2760/5025 +f 2290/3827/6191 2189/3833/6197 2291/3820/6181 +f 3787/3199/5466 3799/3198/5465 3711/3853/6217 +f 2348/3624/5939 2347/3128/5386 2350/2259/4579 +f 3771/3957/4336 3734/2753/4336 3765/2755/4337 +f 4329/2981/6544 4328/3549/5851 4327/3548/5850 +f 2425/2091/4424 2419/3120/5378 2445/2092/4425 +f 2339/4072/6545 2332/4007/6451 2338/4073/6546 +f 3396/3045/4808 3372/2931/4755 3401/2195/4808 +f 4254/4061/6522 4265/3303/5569 4264/3305/5571 +f 3182/2696/4964 3183/2695/4963 3167/4074/6547 +f 2480/3676/6000 2508/3190/5457 2510/3192/5459 +f 3150/2265/4406 3148/3710/4406 3116/2263/4406 +f 3060/3137/5398 3070/3543/5843 3069/3848/6211 +f 4190/3461/5750 4191/3270/5539 4219/3272/5541 +f 4329/2981/6544 4330/3357/5631 4328/3549/5851 +f 4270/3723/6064 4239/3230/6065 4269/4075/6548 +f 2692/2689/4957 2742/3754/6105 2753/4076/6549 +f 2692/2689/4957 2753/4076/6549 2789/2690/4958 +f 2789/2690/4958 2753/4076/6549 2752/4077/6550 +f 2789/2690/4958 2752/4077/6550 2758/3598/5902 +f 3147/3381/5657 3162/3380/5656 3145/2757/5022 +f 2186/4078/6551 2292/3423/6183 2187/3821/6182 +f 2854/3083/5338 2682/3300/5566 2824/3525/5819 +f 2357/4079/6552 2212/2750/5018 2279/4080/6553 +f 2412/3242/5509 2414/3603/5910 2380/3605/5912 +f 2832/4081/6554 2759/3700/6034 2831/2465/4767 +f 3252/3069/5325 3253/3102/5325 3251/3070/5326 +f 2760/2463/4765 2831/2465/4767 2759/3700/6034 +f 2587/2448/4752 2386/2450/4754 2588/4082/6555 +f 2986/3587/6556 2948/4083/6557 2947/3773/6121 +f 3092/3542/4731 3095/2790/4731 3096/2424/4731 +f 3526/2916/5170 3564/3905/6292 3563/2917/5171 +f 1963/3488/6558 2069/2565/6559 2068/2564/6558 +f 2836/2700/4969 2751/2702/4971 2837/4084/6560 +f 4225/3462/6561 4226/4085/6562 4244/3061/6563 +f 3410/4086/6564 3411/3297/5563 3341/2000/5153 +f 4064/2579/4864 4058/2072/6565 4164/2580/4864 +f 2971/2934/6277 2963/2500/6566 2962/2782/6275 +f 2746/2473/4772 2840/3610/5917 2744/2474/4773 +f 2841/4087/6567 2746/2473/4772 2749/4088/6568 +f 2841/4087/6567 2749/4088/6568 2842/4089/6569 +f 2842/4089/6569 2747/2728/4997 2843/4090/6570 +f 2052/2109/4438 1975/2239/4561 2053/3741/6086 +f 2739/3859/6222 2843/4090/6570 2747/2728/4997 +f 2643/4091/6571 2642/3805/6572 2163/3985/6418 +f 4148/3156/5416 4150/2368/4681 4147/2367/4680 +f 2395/2713/4982 2095/3178/5443 2076/3177/5442 +f 2741/2593/4874 2683/4092/6573 2739/3859/6222 +f 4386/2811/5070 4387/3056/5312 4361/3057/5313 +f 4364/3213/6026 4365/3901/6574 4355/3694/6027 +f 2650/4093/6575 2733/2560/4848 2845/4094/6576 +f 4362/2420/4727 4363/3214/6577 4349/2418/4725 +f 2654/4095/6578 2846/3888/6267 2847/2497/4794 +f 1984/3224/6579 1985/3727/6070 2012/3962/6580 +f 3902/3055/5311 3884/4096/6581 3886/2789/5050 +f 2530/3681/6006 2540/3675/5999 2529/2642/4919 +f 4157/4097/6582 4125/4098/6583 4156/3196/5463 +f 2712/2899/5151 2806/2505/4802 2813/3881/6255 +f 2828/3363/5638 2674/2619/4900 2673/4099/6584 +f 2675/4100/6585 2851/2618/4899 2676/4101/6586 +f 2676/4101/6586 2851/2618/4899 2852/2674/6587 +f 2677/4102/6588 2676/4101/6588 2852/2674/6588 +f 2853/2956/5203 2678/4103/6589 2677/4102/6590 +f 2853/2956/5203 2677/4102/6590 2852/2674/6591 +f 3941/3757/6108 4044/3724/6067 3942/3098/6592 +f 2398/2896/5148 2298/2734/5002 2284/2736/5004 +f 3644/4104/4524 3619/3916/4524 3617/2432/4524 +f 2976/2974/26 2940/4105/26 2939/3715/26 +f 3070/3543/5843 3060/3137/5398 3071/4106/6593 +f 4262/2597/4878 4254/4061/6522 4266/3954/6364 +f 2854/3083/5338 2826/4107/6594 2680/4108/6595 +f 2884/3738/6083 2166/3257/6596 2164/4109/6597 +f 3225/3016/6598 3239/2157/6599 3237/2398/6600 +f 3753/2466/6601 3755/3294/6602 3725/4110/6603 +f 3397/4111/4755 3379/2452/4755 3377/3339/4808 +f 4232/2606/5503 4212/3886/4517 4214/2491/4517 +f 2462/3390/6604 2587/2448/4752 2585/2094/4427 +f 3035/3039/5292 3072/3489/5779 3073/3433/5718 +f 2128/4112/6605 2127/4113/6606 2125/4114/6607 +f 2861/4115/6608 2862/3708/6045 2863/3979/6405 +f 2861/4115/6608 2863/3979/6405 2864/4116/6609 +f 2954/4117/6610 2970/3557/5862 2955/4118/6611 +f 2866/3978/6404 2864/4116/6609 2863/3979/6405 +f 2865/4119/6612 2866/3978/6404 2868/4120/6613 +f 3416/2868/5124 3428/2867/5123 3415/2196/6249 +f 4344/2123/4422 4345/3830/4422 4342/4121/4422 +f 2993/4122/6614 2975/3559/6615 2988/2784/6616 +f 2867/4123/6617 2869/3797/6150 2870/3796/6149 +f 2872/4124/6618 2874/3316/5584 2873/4125/6619 +f 2103/2011/6620 2600/2683/6621 3082/2685/4953 +f 2874/3316/5584 2875/4126/6622 2873/4125/6619 +f 3644/4104/6623 3656/2600/4881 3639/2599/4880 +f 3976/4127/6624 3974/4128/6625 3973/4014/6626 +f 2539/3677/6001 2538/2570/4855 2529/2642/4919 +f 2879/2344/4656 2876/3924/6320 2877/2342/4654 +f 2228/2494/4791 2231/2332/4646 2436/2840/5096 +f 2881/4129/6627 2880/2995/5244 2882/4130/6628 +f 2881/4129/6627 2882/4130/6628 2883/4131/6629 +f 3277/2117/4697 3263/2033/4377 3276/2035/4379 +f 2827/4030/6475 2886/2861/5118 2855/3971/6395 +f 2855/3971/6395 2886/2861/5118 2887/2860/6630 +f 2827/4030/6475 2825/4031/6476 2826/4107/6594 +f 3075/2610/4890 3020/4021/6464 3021/4028/6470 +f 2824/3525/5819 2889/3081/5336 2854/3083/5338 +f 2523/3420/5702 2526/3767/6115 2525/3660/5980 +f 2687/4132/6631 3081/3454/5742 2817/2990/5239 +f 3514/2543/4835 3543/4133/6632 3520/3734/6490 +f 3802/3263/5529 3803/3262/5528 3775/4134/6633 +f 3566/2348/4660 3568/2168/4497 3567/2167/4496 +f 4163/4135/5263 4054/2769/6634 4161/4136/6634 +f 3087/4137/4731 3091/3943/4731 3085/2678/4731 +f 3936/2128/4455 3935/3060/5354 3942/3098/5354 +f 2671/4138/6635 2895/2454/4756 2828/3363/5638 +f 3547/2393/4705 3531/2394/4706 3532/3064/5320 +f 4326/3289/6636 4323/3288/6537 4324/3408/6637 +f 4043/3725/6068 4044/3724/6067 3941/3757/6108 +f 2352/4139/6638 2164/4109/6639 2166/3257/6246 +f 2558/4037/6487 2543/3685/6012 2557/4039/6489 +f 4044/3724/6067 4005/3439/6640 4045/3691/6022 +f 3791/4140/6641 3764/4141/6642 3761/4142/6643 +f 4114/4143/5277 4115/2013/5277 4092/2089/4367 +f 4311/3951/6644 4338/3540/6645 4310/3419/5701 +f 3714/3112/5369 3781/3555/5860 3810/3113/5370 +f 3829/2307/4688 3826/2984/4688 3828/2362/4688 +f 3733/3134/5395 3719/1986/5394 3731/3885/6265 +f 2517/3584/6646 2580/3253/6647 2574/3747/6096 +f 3762/2698/4336 3752/2130/4336 3768/4144/4336 +f 3305/4145/6648 3218/3843/6205 3210/4146/6649 +f 3454/2594/4532 3459/3758/6109 3456/3917/4532 +f 3230/4147/6650 3231/4042/6651 3232/4148/6652 +f 4304/2088/5543 4315/4035/6653 4313/3277/5544 +f 4244/3061/5316 4243/2991/5240 4277/2778/5039 +f 3782/3554/5859 3767/2054/5858 3773/2056/6654 +f 3895/2946/6655 3882/2413/6656 3883/3950/6657 +f 2502/2387/4696 2500/2654/4929 2501/4149/6658 +f 2032/3475/6659 2031/3929/6327 2063/4150/6660 +f 2735/2561/4849 2737/1967/4320 2740/3002/5252 +f 2526/3767/6115 2170/2947/5978 2525/3660/5980 +f 4069/4151/6661 4083/3664/6662 4081/2363/5822 +f 2655/4152/6663 2847/2497/4794 2726/2345/4657 +f 2459/2826/5085 2461/3482/6664 2458/2824/5083 +f 2175/3521/6665 2177/4153/6666 2612/4154/6667 +f 2652/4155/6668 2845/4094/6669 2846/3888/6267 +f 2744/2474/4773 2839/3611/5918 2764/3755/6106 +f 2424/3149/5410 2426/3400/5681 2425/2091/4424 +f 2167/3256/5520 2165/4156/6670 2166/3257/5521 +f 1982/2866/5122 1983/2156/4484 2006/2865/5120 +f 2880/2995/5244 2881/4129/6627 2878/3923/6319 +f 3303/3844/6206 3304/4157/6671 3288/2179/6672 +f 4144/3074/5329 4137/2177/6673 4136/2977/6016 +f 2254/3783/6134 2269/3788/6140 2204/3787/6139 +f 2531/3679/6004 2312/2748/5016 2532/4158/6674 +f 3598/3879/6675 3611/3341/5613 3613/2562/6676 +f 4207/2846/5102 4205/3674/6677 4204/2212/6678 +f 2743/4043/6495 2764/3755/6106 2742/3754/6105 +f 4176/2779/6679 4171/3936/6339 4174/4159/6680 +f 2270/3804/6681 2272/2481/4780 2271/2483/4782 +f 2645/4160/6682 2174/4161/6683 2173/4162/6684 +f 3080/2774/5037 3021/4028/6470 3019/2726/4995 +f 3083/3054/5310 3157/2248/6685 3156/3673/6686 +f 3299/4163/6687 3300/3717/6056 3297/3930/6328 +f 3923/3142/5404 3895/2946/5192 3896/2706/4975 +f 2015/3274/4585 2022/2776/4585 2007/2185/4585 +f 2990/4164/6688 2946/3772/6120 2710/4002/6689 +f 1999/3749/6099 2001/3650/6540 2002/3334/6539 +f 2984/4051/6690 2953/4165/6691 2985/4166/6692 +f 3820/2375/4689 3819/2374/4688 3821/2540/4688 +f 4395/2979/6693 4295/4167/6693 4288/4168/6694 +f 4219/3272/6695 4221/3271/6696 4223/2083/4419 +f 2667/4169/6697 2666/2439/4743 2829/2441/4745 +f 2240/4004/6447 2241/3495/5784 2358/1975/4328 +f 3049/2959/5206 3053/3948/6355 3052/4170/6698 +f 4153/4171/6699 4152/3032/5284 4154/3031/5283 +f 3039/4025/6469 3046/3035/5288 3040/3317/5585 +f 3198/3328/5597 3196/4172/6700 3195/3327/5596 +f 3751/2467/6701 3724/3129/5388 3749/2131/6702 +f 2860/3709/6046 2857/3972/6396 2858/3997/6440 +f 3782/3554/6241 3794/3871/6240 3810/3113/5370 +f 1966/2535/4828 2063/4150/6660 2062/4173/6703 +f 4184/3422/5708 4195/2584/5707 4193/2583/6704 +f 2106/3793/6705 2600/2683/4950 2599/2682/4949 +f 4099/3529/5873 4098/3528/6706 4073/3568/5872 +f 2505/2386/4695 2534/3248/5515 2502/2387/4696 +f 2031/3929/6327 2030/3994/6435 2062/4173/6703 +f 3322/3831/6195 3279/3080/5335 3321/3507/5796 +f 4080/2365/4367 4111/2176/4367 4078/3001/4367 +f 2588/4082/26 2374/4174/26 2362/4175/26 +f 2121/2410/4719 2450/2412/4721 2476/4176/6707 +f 4251/4177/6708 4250/2852/5662 4182/3088/5661 +f 3429/2869/5125 3427/4178/6709 3428/2867/5123 +f 3640/2150/4524 3624/3195/5462 3621/3565/4524 +f 4279/2850/5106 4177/3086/6710 4280/2964/5211 +f 3947/2252/4572 3960/2251/4571 3948/3811/6185 +f 2964/3459/6711 2972/3896/6276 2967/3460/6712 +f 2396/3551/5854 2391/4019/6461 2434/3518/5811 +f 2560/3077/5332 2557/4039/6489 2561/4179/6713 +f 4332/2517/5906 4334/2617/6497 4333/3359/5633 +f 3545/3537/5837 3535/2145/6714 3571/2462/4764 +f 2060/2928/5180 2061/2536/4829 2059/2929/5181 +f 4196/2582/4865 4194/2085/4421 4193/2583/4866 +f 3695/2188/4434 3699/2187/4434 3696/2538/4434 +f 3510/2046/4388 3500/2045/4387 3511/2523/4388 +f 3764/4141/4336 3730/4180/4337 3761/4142/4336 +f 4188/2121/4450 4189/2351/4663 4210/2119/4448 +f 3037/2525/4818 3044/2527/4820 3043/4181/6715 +f 4363/3214/6577 4364/3213/6026 4349/2418/4725 +f 3212/3506/4383 3217/2218/4383 3211/4182/4383 +f 3795/2794/5055 3794/3871/6240 3784/2908/5162 +f 4075/3391/5672 4104/2058/4396 4067/2057/4395 +f 4147/2367/4680 4146/3636/5949 4145/3635/5948 +f 2754/3756/6107 2838/4183/6716 2837/4084/6560 +f 2929/3586/26 2931/4049/26 2985/4166/26 +f 4016/4184/6717 4034/3913/6302 4015/3009/5261 +f 2642/3805/6572 2161/3657/6417 2163/3985/6418 +f 3149/2631/5924 3172/3689/6020 3173/3615/5925 +f 3592/3705/6718 3699/2187/6718 3698/2438/6718 +f 2695/3338/5607 2074/3176/6719 2696/2428/4734 +f 3387/2236/4755 3388/3448/4755 3358/4185/4755 +f 3800/4186/6720 3799/3198/5465 3801/3473/5762 +f 4209/2845/5503 4233/2608/4517 4234/3236/4517 +f 2174/4161/6721 3016/4187/6722 3017/3807/6166 +f 2911/3312/5580 2950/3858/6221 2910/2048/4389 +f 4018/2818/5077 4000/3471/5760 4038/3470/5759 +f 2898/1972/4325 2897/2477/4776 2899/2476/4775 +f 3212/3506/4383 3211/4182/4383 3219/3718/6057 +f 4312/4188/6723 4313/3277/6724 4314/2122/6725 +f 4068/2063/4400 4069/4151/6661 4081/2363/5822 +f 4062/3073/4408 4060/3414/6726 4055/3744/4409 +f 4070/2431/4367 4069/4151/5277 4068/2063/5277 +f 1983/2156/4484 1984/3224/6579 2010/2060/4485 +f 3556/2812/5071 3553/3504/5793 3555/3116/5374 +f 3903/2788/6727 3910/2361/4674 3902/3055/6092 +f 3523/2585/6728 3521/2586/6729 3538/3622/5936 +f 2089/2968/6730 2091/2887/6438 2703/3995/6437 +f 3426/3876/6250 3415/2196/6249 3428/2867/5123 +f 2530/3681/6006 2213/4189/6731 2310/3961/6382 +f 3637/3131/4524 3604/4190/4524 3633/2999/4524 +f 4108/3361/4367 4116/4191/4367 4095/3486/4367 +f 4151/3033/5285 4148/3156/5416 4056/3571/5879 +f 3952/3704/6732 3975/3259/6733 3977/2921/6734 +f 2112/3160/6735 2111/3860/6736 2596/3324/5591 +f 2291/3820/6737 2292/3423/5704 2284/2736/5004 +f 3416/2868/6738 3415/2196/4522 3401/2195/4521 +f 3152/2194/4406 3153/3531/4406 3121/3875/6245 +f 3842/2396/6739 3843/3545/6740 3833/4192/6741 +f 2179/3133/6742 2963/2500/6566 2971/2934/6277 +f 3204/3855/4731 3203/4193/5444 3202/4194/4731 +f 4169/2892/4924 4167/2648/4924 4168/2647/4924 +f 4346/3829/6193 4361/3057/5313 4351/3497/6743 +f 2425/2091/4424 2444/2090/4423 2447/4195/6744 +f 2262/3206/5714 2251/2747/5015 2260/4196/6745 +f 3588/3863/6228 3684/2976/5223 3688/2596/4877 +f 1973/1962/4315 1966/2535/4828 1970/1963/4316 +f 2537/3247/5514 2531/3679/6004 2532/4158/6674 +f 3239/2157/4486 3242/2159/4487 3240/2005/4486 +f 2964/3459/5748 2965/2609/4889 2968/4197/6746 +f 2448/4198/6747 2449/3310/5578 2251/2747/5015 +f 2791/2877/5133 2787/2669/4940 2788/2668/4939 +f 1978/2331/4584 1977/3728/4585 1980/2256/4585 +f 2386/2450/6748 2464/2449/6207 2385/3846/6209 +f 2029/3619/5933 2028/4046/6502 2055/3919/6308 +f 3612/2686/4955 3611/3341/6527 3609/2687/4956 +f 2034/2760/5025 2022/2776/6248 2033/3476/5766 +f 3225/3016/4351 3224/3642/6749 3223/3641/4351 +f 3888/3411/5695 3901/3746/6750 3900/1992/5694 +f 3134/2485/4784 3132/2359/6751 3106/1989/4339 +f 3407/3097/5353 3440/3579/5890 3423/2283/4600 +f 3341/2000/5153 3443/2900/5152 3410/4086/6564 +f 3660/3219/5485 3668/3383/5659 3669/2620/4901 +f 3681/3218/5484 3679/3217/5483 3680/3897/6279 +f 4120/2022/4367 4118/2876/4367 4087/2023/4367 +f 2968/4197/6752 2980/4199/6753 2979/4200/6754 +f 2463/2093/4426 2582/2095/4428 2460/3857/6220 +f 2951/4201/6755 2986/3587/6556 2985/4166/6692 +f 4151/3033/5285 4056/3571/5879 4061/2771/5034 +f 3391/4202/6756 3408/3095/5351 3407/3097/5353 +f 2979/4200/6754 2964/3459/6711 2968/4197/6752 +f 3838/2232/4785 3858/2313/4787 3860/4203/6757 +f 2629/3041/6401 2148/3040/5874 2630/4204/6758 +f 2997/4205/6759 2998/4206/6760 2991/4207/6761 +f 2481/3742/6087 2482/3970/6394 2483/3513/5806 +f 2442/3175/5436 2441/3174/5435 2244/3048/5303 +f 2952/4208/6762 2948/4083/6763 2951/4201/6764 +f 2475/4209/6765 2467/4210/6766 2477/2825/5084 +f 4257/4211/6767 4256/2027/4371 4268/2029/4373 +f 4354/2205/4422 4358/2204/4422 4328/3549/4422 +f 2714/2897/5149 2989/4212/6768 2713/2898/5150 +f 2713/2898/5150 2989/4212/6768 2990/4164/6769 +f 4316/3967/6484 4313/3277/6724 4315/4035/6484 +f 2893/2673/4942 2851/2618/4899 2894/2404/4716 +f 2768/4213/6770 2731/2751/5019 2732/4017/6460 +f 4091/3591/6771 4089/2370/5534 4071/2430/5533 +f 1963/3488/6558 2068/2564/6558 1962/2820/6558 +f 2991/4207/6761 2998/4206/6760 2992/2975/6772 +f 2401/3526/5820 2468/2799/5059 2469/4214/6773 +f 2984/4051/6690 2970/3557/6081 2953/4165/6691 +f 4289/1976/4329 4288/4168/6774 4290/2809/6774 +f 4061/2771/5034 4155/4215/6775 4154/3031/5283 +f 3844/2395/5778 3879/3842/4554 3846/3105/4554 +f 3221/3824/6187 3214/3034/5286 3302/2289/4606 +f 1999/3749/6099 2002/3334/6539 2000/3750/6100 +f 4344/2123/4422 4348/4216/4422 4345/3830/4422 +f 3816/4217/6776 3815/2863/6777 3713/2862/6777 +f 3431/2018/4364 3343/2020/4366 3342/2308/4625 +f 3085/2678/4947 3200/2680/4947 3084/4023/4947 +f 3817/3941/6347 3920/3457/5746 3822/3234/6290 +f 2661/2076/4412 2662/2872/5128 2849/2871/5127 +f 4179/2880/6778 4180/2891/5144 4266/3954/6364 +f 3170/3600/5904 3180/2152/4480 3185/2154/4482 +f 3519/3974/6398 3520/3734/6490 3541/2533/6399 +f 2991/4207/6761 3000/4218/6779 2999/3752/6102 +f 2310/3961/6382 2213/4189/6731 2215/3006/5256 +f 3472/3687/4388 3476/2938/4388 3470/2554/4388 +f 2382/3477/5767 2397/4010/6455 2405/3845/6208 +f 2994/1981/4332 2139/2407/6780 2973/3155/6781 +f 2978/1979/4330 2994/1981/4332 2973/3155/6781 +f 2983/4058/6782 2990/4164/6688 2989/4212/6783 +f 2983/4058/6782 2989/4212/6783 2982/3350/5621 +f 2395/2713/4982 2381/4219/6784 2429/2078/4414 +f 2869/3797/6150 3037/2525/4818 3041/3795/6148 +f 3696/2538/4434 3699/2187/4434 3700/2539/6785 +f 3157/2248/4568 3143/2250/4570 3142/3508/5797 +f 3855/2030/6786 3857/2314/4631 3858/2313/4630 +f 2703/3995/6437 2702/3385/5663 2759/3700/6034 +f 1981/2254/4585 1980/2256/4585 1984/3224/4585 +f 2997/4205/6787 2977/2973/5220 2998/4206/6788 +f 2978/1979/4330 2997/4205/6787 2996/1980/4331 +f 3106/1989/4339 3132/2359/6751 3130/1990/4340 +f 2870/3796/6149 2871/4024/6468 2872/4124/6618 +f 3002/3232/5500 3003/4220/6789 3004/4221/6790 +f 4308/2518/4811 4331/3358/6791 4329/2981/5228 +f 4286/2568/4924 4285/4222/4924 4282/3711/4924 +f 3107/1965/4406 3105/1988/4338 3103/2796/4406 +f 4324/3408/6637 4325/3452/5849 4326/3289/6636 +f 3485/2488/4788 3486/2902/4788 3488/2489/4789 +f 3013/4223/6792 2950/3858/6221 2949/4224/6793 +f 3821/2540/4688 3819/2374/4688 3829/2307/4688 +f 3676/2510/4805 3675/2445/4749 3669/2620/4901 +f 3659/2447/4751 3643/3649/5968 3660/3219/5485 +f 2168/2588/6082 2166/3257/6596 2884/3738/6083 +f 2606/3729/6358 2096/3692/6794 2097/2712/6795 +f 2427/4225/6796 2417/4226/6797 2428/3243/5510 +f 3676/2510/4805 3669/2620/4901 3677/4070/6543 +f 2457/3119/6798 2456/3118/5625 2577/3352/5624 +f 4096/4227/6799 4098/3528/5826 4097/4228/6800 +f 4052/3592/6801 3940/2324/6801 4053/2323/6801 +f 3870/1999/4554 3867/2111/5778 3878/3187/5778 +f 3942/3098/6592 4045/3691/6022 3936/2128/4455 +f 4155/4215/6775 4125/4098/6583 4153/4171/6699 +f 2556/3141/5403 2563/2339/4651 2557/4039/6489 +f 3260/3145/6514 3258/4229/6802 3257/2841/5928 +f 2782/3612/5919 2694/3989/6425 2691/3372/5648 +f 3365/2855/5390 3363/3332/5391 3364/2513/5391 +f 3651/2008/4354 3686/2101/4432 3650/2100/4431 +f 3935/3060/6803 4052/3592/6803 4051/2416/6803 +f 3638/2199/6804 3663/3410/5693 3642/4230/6805 +f 3712/3472/5761 3708/3627/5358 3711/3853/6217 +f 3979/2480/4779 3981/3451/6806 3982/4231/6807 +f 3708/3627/6808 3702/3763/6809 3812/3101/6808 +f 3537/3621/6810 3522/4055/6811 3523/2585/6728 +f 4069/4151/6661 4070/2431/5737 4084/3010/6812 +f 3148/3710/6047 3170/3600/5904 3171/3599/6813 +f 3963/3823/6186 3948/3811/6185 3962/3909/6814 +f 2625/3115/5372 2623/3279/5547 2917/3063/5319 +f 2497/2026/4370 2534/3248/5515 2535/2311/4628 +f 3628/3443/4524 3626/2469/4524 3634/2134/4524 +f 2757/3726/6069 2762/3038/5291 2763/3686/6013 +f 3691/3308/5576 3667/3668/5990 3693/3667/5989 +f 3600/3468/5757 3625/2471/5298 3601/3044/5297 +f 3782/3554/5859 3773/2056/6654 3783/3870/6815 +f 2928/4050/26 2932/4026/26 2981/3737/26 +f 3284/3900/6282 3283/3931/6329 3297/3930/6328 +f 2890/2957/5204 3032/3099/5356 2889/3081/5336 +f 2352/4139/6638 2166/3257/6246 2350/2259/4579 +f 2137/2710/6816 2131/2709/6817 2133/3369/6818 +f 2999/3752/6102 3000/4218/6779 2815/3023/5274 +f 3740/2436/6819 3741/3511/6820 3722/3183/5447 +f 3809/3952/6362 3780/2222/4545 3792/3789/6141 +f 3911/2628/4909 3828/2362/4675 3910/2361/4674 +f 3728/3938/6341 3729/2910/6821 3727/2909/6822 +f 4247/2765/6466 4246/2607/4887 4281/3043/5296 +f 2285/3633/6823 2287/3632/6824 2286/2358/4671 +f 4295/4167/6825 4299/4016/4329 4298/2810/6825 +f 4207/2846/5102 4204/2212/6678 4206/2211/5102 +f 3037/2525/4818 2868/4120/6613 3038/2526/4819 +f 2553/2391/4703 2568/4232/6826 2569/3730/6074 +f 4224/3229/4517 4227/3127/4517 4220/3940/4517 +f 3023/4233/6827 3078/2725/6828 3079/3435/5721 +f 2947/3773/6121 2950/3858/6829 2903/3375/6122 +f 3708/3627/6808 3812/3101/6808 3816/4217/6808 +f 3143/2250/4406 3141/3354/4406 3133/3157/4406 +f 3747/2549/5387 3723/3130/5389 3745/3186/5451 +f 3231/4042/6651 3233/3019/6830 3234/3018/6830 +f 3986/3873/6243 4009/3646/5962 4008/3874/6244 +f 2593/3453/6052 2118/3343/6831 2117/3344/6832 +f 3077/2775/5038 2955/4118/6611 2956/3556/5861 +f 3044/2527/4820 3038/2526/4819 3034/3707/6044 +f 2733/2560/4848 2734/4234/6833 2736/2901/5154 +f 3632/3184/4524 3630/2633/4524 3635/2806/4524 +f 3484/2903/4388 3482/2763/4388 3520/3734/4388 +f 3320/2118/4447 3318/4235/6834 3319/2217/4539 +f 3043/4181/6715 3041/3795/6148 3037/2525/4818 +f 2254/3783/6134 2204/3787/6139 2210/3782/6133 +f 2982/3350/5621 2989/4212/6783 2987/2785/5622 +f 2981/3737/6079 2970/3557/6081 2984/4051/6690 +f 3100/1966/4319 3108/3883/6835 3138/1964/4317 +f 3471/2556/4844 3483/2555/4843 3485/2488/6836 +f 4173/3307/5575 4168/2647/6837 4268/2029/4373 +f 3339/2002/6838 3448/4236/6838 3446/3162/6838 +f 3248/3193/5460 3250/3071/5326 3251/3070/5326 +f 4135/2978/6017 4134/2874/5545 4143/3075/5330 +f 3841/4237/6839 3869/1997/5373 3871/2691/6840 +f 3645/4012/4524 3616/2563/4524 3646/3265/4524 +f 2243/3049/5304 2441/3174/5435 2440/4238/6841 +f 3812/3101/5358 3815/2863/5358 3816/4217/6842 +f 3057/3501/5790 3002/3232/5500 3004/4221/6790 +f 2945/4239/26 2946/3772/26 2944/4059/26 +f 3981/3451/6806 3979/2480/4779 3980/2479/4778 +f 3600/3468/5757 3620/3566/6843 3622/3567/5871 +f 3546/3538/5838 3545/3537/5837 3468/3697/6844 +f 3158/2249/6845 3157/2248/6685 3194/4240/6846 +f 3089/4241/6847 3175/4242/6848 3163/2758/5023 +f 3526/2916/6849 3525/2918/6037 3512/3167/5426 +f 2001/3650/5969 1999/3749/6850 1981/2254/4574 +f 2811/2139/4467 2804/4243/6851 2803/3869/6238 +f 4063/4244/6233 4066/2073/4409 4064/2579/6233 +f 3611/3341/6527 3612/2686/4955 3614/4064/4850 +f 2924/3580/5891 3053/3948/6355 2925/3878/6252 +f 3759/2165/4494 3757/2164/4493 3756/4245/6852 +f 3417/2935/5183 3425/3716/6055 3429/2869/5125 +f 2576/4246/6853 2519/3865/6230 2586/3866/6232 +f 2747/2728/4997 2738/2730/4999 2739/3859/6222 +f 2067/3552/5856 2066/2354/4667 1969/1961/4314 +f 3862/3188/5454 3863/3189/5456 3861/4247/6854 +f 2753/4076/6549 2751/2702/4971 2752/4077/6550 +f 2756/3597/5901 2796/4041/6492 2795/3601/5905 +f 3004/4221/6790 3064/3228/5496 3057/3501/5790 +f 3522/4055/6811 3535/2145/4473 3516/2144/4472 +f 4221/3271/6696 4222/3413/6855 4223/2083/4419 +f 3474/2286/4388 3476/2938/4388 3473/3407/4388 +f 4001/2279/4596 4039/4060/6521 4038/3470/5759 +f 2921/3499/5788 3061/2124/4451 3059/2126/4453 +f 2911/3312/5580 2823/2050/4391 2901/3313/5581 +f 3275/2219/4542 3313/3887/6266 3316/4248/6856 +f 4132/2882/6480 4063/4244/6857 4142/4033/6481 +f 4297/4249/4329 4296/1978/4329 4301/2202/4329 +f 2697/3447/5736 2604/3992/6433 2078/2740/6430 +f 2211/3208/5475 2263/3430/6091 2262/3206/5473 +f 2620/3696/6029 2627/3281/5549 2913/3280/5548 +f 2968/4197/6746 3076/2611/4891 2969/3558/5863 +f 3594/2768/5032 3592/3705/4434 3591/2511/4806 +f 4294/1977/6030 4291/4250/6858 4382/2762/5027 +f 3787/3199/6268 3771/3957/6370 3788/3197/6859 +f 3994/3441/5000 3959/3733/5000 3993/3732/5000 +f 4158/2442/4746 4126/3362/5637 4157/4097/6582 +f 4224/3229/5497 4228/3596/6860 4258/4053/6509 +f 2786/4251/6861 2791/2877/5133 2790/3027/5279 +f 4009/3646/5962 4019/4252/6862 4020/3906/6293 +f 4361/3057/5313 4362/2420/4727 4350/2419/4726 +f 4370/3200/6516 4371/3714/6863 4357/2940/5186 +f 3275/2219/4542 3264/2135/4463 3274/2137/4465 +f 3687/2624/4905 3688/2596/4877 3684/2976/5223 +f 3094/3209/5476 3093/3406/5686 3090/4253/6864 +f 3017/3807/6166 3005/4254/6865 3063/3640/5954 +f 3664/3898/6280 3637/3131/5392 3665/3132/5393 +f 3074/4255/6866 2955/4118/6611 3077/2775/5038 +f 2170/2947/5193 3005/4254/6865 3016/4187/6722 +f 3196/4172/6700 3198/3328/5597 3197/2823/5082 +f 2926/3535/5832 2924/3580/5891 2927/3516/5809 +f 2109/4256/6867 2106/3793/6145 2108/3794/6147 +f 3267/2180/4509 3270/2893/5145 3287/2181/4510 +f 2133/3369/6818 2138/3370/6868 2137/2710/6816 +f 3395/4257/6869 3374/3029/4755 3396/3045/4808 +f 4337/3613/5920 4339/3498/5921 4336/2638/6499 +f 3763/3721/4336 3754/2699/4336 3762/2698/4336 +f 3645/4012/6457 3657/2578/4863 3644/4104/6623 +f 3683/2303/4620 3649/2302/4619 3685/2099/4430 +f 2067/3552/5856 2038/2645/5855 2037/2644/6870 +f 3003/4220/6789 3044/2527/4820 3004/4221/6790 +f 2742/3754/6105 2692/2689/4957 2694/3989/6425 +f 4256/2027/6871 4230/3595/6872 4255/2598/4879 +f 4018/2818/5077 4017/2817/5076 4000/3471/5760 +f 3045/3037/5290 3005/4254/6865 3012/2949/5195 +f 3789/3786/6137 3801/3473/5762 3799/3198/5465 +f 2480/3676/6000 2510/3192/5459 2509/3367/5642 +f 4171/3936/6339 4170/2646/4923 4167/2648/4924 +f 2132/3291/6873 2130/2802/5062 2129/2801/5061 +f 2686/2953/5200 2722/2952/5199 2715/3135/5396 +f 4271/4258/6874 4272/3222/5489 4270/3723/6064 +f 3140/2069/4406 3142/3508/4406 3137/3904/4406 +f 2687/4132/6631 2112/3160/6216 3081/3454/5742 +f 4127/2444/4748 4116/4191/6875 4108/3361/5636 +f 3336/2016/4350 3332/3570/5878 3334/3512/5878 +f 3898/3401/6876 3831/1991/4341 3897/2708/4977 +f 4224/3229/4517 4220/3940/4517 4223/2083/4517 +f 4260/2966/5213 4246/2607/4887 4245/2849/5105 +f 3537/3621/5935 3554/3505/5794 3536/2460/4762 +f 2569/3730/6074 2554/3315/5583 2553/2391/4703 +f 2987/2785/5046 2989/4212/6768 2714/2897/5149 +f 1973/1962/4315 1969/1961/4314 2065/2653/4928 +f 3287/2181/5287 3286/2147/4475 3302/2289/4606 +f 2137/2710/4979 2136/4259/6877 2589/2711/4980 +f 4390/4260/6878 4391/3902/6288 4364/3213/5479 +f 3390/3907/6295 3406/4020/6463 3405/2160/4489 +f 3779/2904/5158 3807/3246/5513 3778/2905/5159 +f 3516/2144/4388 3492/2106/4388 3522/4055/4388 +f 3834/2380/6879 3847/3103/6422 3835/2381/6421 +f 2595/3326/5824 2118/3343/6880 3081/3454/5742 +f 4190/3461/4517 4186/2832/4517 4184/3422/4517 +f 3438/2017/4363 3440/3579/5890 3439/2015/4361 +f 2740/3002/5252 2770/2573/4858 2772/2575/4860 +f 3865/4261/6881 3867/2111/4440 3866/2112/4441 +f 3128/2316/5408 3130/1990/4673 3131/2360/4673 +f 2834/4262/6882 2757/3726/6069 2835/4263/6883 +f 3989/2225/4548 4004/2890/5143 4003/2226/4549 +f 3305/4145/6648 3303/3844/6206 3218/3843/6205 +f 2014/2492/4585 2013/2061/4585 1986/2267/4584 +f 2574/3747/6096 2513/3191/6884 2517/3584/6646 +f 3998/3522/5815 4013/3628/6885 4012/3523/5816 +f 3693/3667/5989 3692/4264/6886 3691/3308/5576 +f 2719/2659/4931 2717/2658/4930 3081/3454/5742 +f 2988/2784/6616 2975/3559/6615 2974/3351/5623 +f 2607/2886/5139 2090/2888/5141 2608/4265/6887 +f 3218/3843/6205 3207/3629/6119 3210/4146/6649 +f 3823/2649/4688 3831/1991/4690 3830/2650/4690 +f 4231/2767/5031 4248/2766/5030 4237/2853/5110 +f 3976/4127/5000 3973/4014/5000 3996/4266/5000 +f 3557/2545/4837 3540/2621/4902 3558/2532/4825 +f 3285/2148/4476 3286/2147/4475 3270/2893/5145 +f 2713/2898/5150 2711/4001/6444 2712/2899/5151 +f 3711/3853/6217 3708/3627/5358 3717/3626/5941 +f 4289/1976/5851 4393/2661/5851 4288/4168/5851 +f 3978/2478/5523 3975/3259/5524 3976/4127/6624 +f 3590/3639/5953 3681/3218/5484 3582/2548/5573 +f 3736/2067/6888 3739/2435/6889 3738/2437/6890 +f 2539/3677/6001 2480/3676/6000 2509/3367/5642 +f 3054/3949/6356 3051/2958/5205 3056/3233/5501 +f 3462/3912/4532 3458/2336/5703 3463/2349/5703 +f 3797/2793/5054 3715/3908/6296 3796/3903/6289 +f 2409/3396/5677 2398/2896/5148 2382/3477/5767 +f 2787/2669/4940 2690/3980/6409 2689/2670/4941 +f 2575/4267/6891 2516/3583/6892 2514/4268/6893 +f 3343/2020/4626 3340/2096/4626 3342/2308/4625 +f 2384/3836/6200 2193/2963/5210 2295/2962/5209 +f 4368/3287/5555 4367/2206/4530 4392/3661/5981 +f 4225/3462/5503 4232/2606/5503 4214/2491/4517 +f 3389/2453/4755 3379/2452/4755 3397/4111/4755 +f 3531/2394/4706 3570/2166/4495 3548/4065/6528 +f 2058/2927/5179 1964/3740/6085 2060/2928/5180 +f 4083/3664/6662 4069/4151/6661 4084/3010/6812 +f 2575/4267/26 2576/4246/26 2372/4269/26 +f 3274/2137/4465 3262/2136/4464 3261/2834/5093 +f 3560/3918/6307 3559/2531/4824 3542/4040/6491 +f 3598/3879/6675 3615/2434/6894 3599/3766/6895 +f 3533/2169/4498 3546/3538/5838 3532/3064/5320 +f 2370/4270/512 2140/2408/26 2139/2407/26 +f 2982/3350/6896 2974/3351/26 2943/4052/26 +f 3637/3131/5392 3664/3898/6280 3638/2199/6804 +f 4388/3884/6261 4386/2811/5070 4389/3215/5481 +f 4052/3592/6801 3944/3590/6897 3940/2324/6801 +f 2395/2713/4982 2415/4271/6898 2381/4219/6784 +f 3944/3590/5354 3943/3203/5470 3940/2324/5354 +f 1980/2256/4576 1995/2972/5219 1992/2640/4917 +f 4202/2191/4517 4205/3674/4517 4238/2189/4517 +f 3301/3719/6058 3302/2289/4606 3296/2290/4607 +f 3768/4144/4336 3750/2132/4336 3769/4069/4336 +f 3169/2857/5114 3148/3710/6047 3150/2265/5909 +f 3784/2908/5162 3783/3870/6815 3773/2056/6654 +f 3792/3789/6141 3714/3112/5369 3809/3952/6362 +f 3694/2830/5089 3670/2577/4862 3693/3667/5989 +f 3195/3327/5596 3194/4240/6846 3093/3406/5686 +f 3909/2052/6202 3879/3842/6204 3876/3840/6520 +f 4124/4272/6899 4125/4098/6900 4109/3148/6901 +f 2906/2075/4411 2911/3312/5580 2912/2475/4774 +f 2269/3788/6902 2252/3311/5579 2253/2922/5174 +f 4117/2875/5131 4134/2874/5130 4135/2978/5226 +f 3154/4273/6903 3174/3021/5272 3190/3020/5271 +f 3394/3368/4808 3393/3346/4808 3362/2724/4755 +f 4088/2369/5532 4086/4274/6904 4070/2431/5737 +f 2253/2922/5174 2449/3310/5578 2446/3301/5567 +f 4097/4228/5277 4108/3361/4367 4095/3486/4367 +f 2086/2843/5099 2094/2914/6905 2085/2844/5100 +f 3987/2733/5000 3983/2732/5001 3990/4005/5001 +f 3618/2433/6906 3620/3566/6843 3599/3766/6895 +f 1980/2256/4576 1992/2640/4917 1979/2639/4916 +f 3261/2834/4351 3262/2136/4351 3260/3145/4351 +f 3287/2181/5287 3214/3034/5286 3303/3844/6206 +f 2177/4153/6907 2181/2913/6908 2520/3993/6434 +f 3283/3931/6909 3284/3900/6282 3273/2003/6284 +f 3284/3900/6282 3285/2148/4476 3271/2004/6283 +f 2158/3534/6910 2155/3785/6911 2489/4275/6912 +f 3166/2193/4519 3199/3464/5753 3182/2696/4964 +f 3582/2548/5573 3681/3218/5484 3666/2998/6913 +f 3827/1984/4335 3921/2372/4686 3922/1982/4333 +f 3997/3440/5000 3961/4276/5000 3994/3441/5000 +f 3258/4229/4351 3260/3145/4351 3262/2136/4351 +f 4103/4063/6526 4104/2058/6914 4105/2836/6525 +f 2547/3527/5825 2493/4277/6915 2492/4278/6916 +f 3353/2665/4934 3378/2873/5129 3354/2044/4386 +f 3982/4231/6807 3981/3451/6806 3983/2732/6917 +f 3214/3034/5286 3221/3824/6187 3215/3630/6119 +f 3445/3877/6251 3426/3876/6250 3346/3404/6918 +f 3992/2278/5000 3980/2479/5000 3989/2225/5001 +f 3217/2218/4540 3321/3507/5796 3279/3080/5335 +f 2920/3581/5892 3058/4022/6465 2919/3042/5295 +f 3355/4279/6919 3382/2043/4385 3384/3490/6920 +f 4380/2521/4814 4383/2761/5026 4375/1994/4344 +f 3288/2179/6672 3287/2181/5287 3303/3844/6206 +f 2705/3683/6921 2805/4000/6922 2946/3772/6120 +f 2288/2735/6459 2192/4280/6923 2191/3825/6189 +f 3051/2958/5205 3008/3231/5499 3056/3233/5501 +f 3495/3337/5606 3493/3336/5605 3494/2107/4436 +f 3371/3028/5280 3372/2931/5280 3374/3029/5281 +f 3219/3718/6057 3221/3824/6187 3301/3719/6058 +f 2404/3397/5868 2466/3025/5278 2467/4210/6766 +f 4057/3575/4409 4062/3073/4408 4055/3744/4409 +f 3390/3907/4755 3383/4018/4755 3391/4202/4755 +f 2003/4067/6541 2004/2184/4514 2005/2186/4516 +f 4216/2320/5751 4215/2322/4664 4189/2351/4663 +f 3281/2828/6924 3282/3810/6925 3272/4281/6926 +f 3339/2002/6838 3446/3162/6838 3332/3570/6838 +f 2612/4154/6667 2177/4153/6666 2181/2913/6373 +f 2023/2943/4585 2024/4282/4584 1991/3107/4585 +f 3432/2808/5067 3433/3059/5315 3335/2773/5036 +f 4117/2875/4367 4082/2364/4367 4085/3011/4367 +f 3160/3355/5629 3161/3379/5655 3147/3381/5657 +f 3824/1983/4334 3897/2708/4977 3831/1991/4341 +f 3479/3761/6112 3478/2384/6113 3480/2764/6112 +f 3471/2556/4844 3487/2490/6927 3472/3687/6015 +f 3329/2671/5400 3211/4182/5400 3213/2920/5400 +f 4332/2517/4810 4331/3358/6791 4308/2518/4811 +f 3128/2316/5408 3131/2360/4673 3129/3146/5409 +f 3139/2300/6258 3136/2484/6928 3138/1964/6259 +f 3819/2374/4688 3826/2984/4688 3829/2307/4688 +f 4330/3357/6361 4333/3359/4422 4354/2205/4422 +f 4242/2992/5241 4274/3067/5322 4275/2993/5242 +f 3112/2317/6929 3110/2070/6344 3109/2389/6343 +f 3803/3262/5528 3793/3264/5530 3804/3771/6118 +f 4025/3258/5522 4022/4283/6930 4010/3091/5347 +f 3486/2902/4788 3485/2488/4788 3483/2555/5155 +f 3296/2290/4607 3285/2148/4476 3284/3900/6282 +f 3001/4284/6931 2642/3805/6164 3017/3807/6166 +f 1989/2329/5732 1990/2547/6932 1991/3107/5363 +f 3997/3440/5726 4013/3628/6885 3998/3522/5815 +f 3310/4285/6933 3293/3928/6326 3294/4286/6934 +f 3657/2578/4863 3656/2600/4881 3644/4104/6623 +f 4391/3902/6288 4390/4260/6878 4299/4016/6935 +f 2575/4267/6891 2580/3253/6647 2516/3583/6892 +f 2505/2386/4695 2482/3970/6394 2541/3680/6005 +f 4228/3596/6860 4257/4211/6936 4258/4053/6509 +f 3498/4287/4388 3511/2523/4388 3500/2045/4387 +f 2829/2441/4745 2668/2804/5064 2667/4169/6697 +f 3860/4203/6757 3861/4247/6937 3838/2232/4785 +f 4097/4228/6800 4098/3528/5826 4100/2744/5012 +f 3773/2056/4336 3742/3283/4336 3774/2906/4336 +f 4213/2352/6938 4214/2491/4790 4212/3886/6939 +f 2587/2448/26 2588/4082/26 2362/4175/26 +f 4273/3935/6338 4271/4258/6874 4170/2646/4923 +f 4031/2081/4417 4032/3008/5260 3943/3203/5470 +f 1976/2506/4803 1968/2241/6940 2071/2507/4803 +f 2174/4161/6941 2525/3660/5980 2172/3659/5979 +f 2041/3670/6042 2042/3669/5991 2027/2377/6043 +f 4142/4033/6481 4141/3278/5546 4133/3478/6479 +f 4065/2071/4407 4066/2073/6942 4160/4288/6943 +f 3882/2413/4554 3862/3188/4554 3883/3950/4554 +f 2576/4246/26 2586/3866/26 2375/4289/26 +f 3945/2260/4580 4026/3204/5471 3943/3203/5470 +f 4072/2429/4735 4073/3568/5872 4094/3485/6944 +f 3354/2044/4386 3352/2656/4755 3353/2665/4934 +f 2834/4262/6882 2762/3038/5291 2757/3726/6069 +f 3834/2380/4554 3840/2178/4554 3833/4192/4554 +f 2397/4010/6455 2385/3846/6209 2405/3845/6208 +f 3193/3399/5680 3083/3054/5310 3156/3673/6686 +f 2526/3767/6115 2168/2588/6247 2527/3768/6116 +f 3772/3181/5445 3785/2907/5161 3774/2906/5160 +f 3756/4245/6852 3757/2164/4493 3755/3294/5560 +f 3227/3654/5973 3226/2182/4351 3229/2234/4351 +f 2562/2340/4652 2563/2339/4651 2556/3141/5403 +f 4039/4060/6521 4001/2279/4596 4041/3562/5865 +f 4131/2881/6945 4130/2266/5589 4140/3321/5590 +f 2582/2095/512 2585/2094/26 2366/4290/26 +f 2764/3755/6106 2838/4183/6716 2754/3756/6107 +f 3197/2823/5082 3159/2822/5081 3196/4172/6700 +f 4067/2057/4367 4074/2059/4367 4070/2431/4367 +f 4145/3635/5948 4144/3074/5329 4057/3575/5884 +f 4295/4167/6825 4293/4015/4329 4299/4016/4329 +f 3087/4137/6946 3086/3053/5309 3191/3817/6178 +f 2590/3493/6947 2592/3492/6051 2591/3713/6053 +f 4168/2647/6837 4271/4258/6874 4270/3723/6064 +f 4104/2058/6914 4075/3391/6948 4076/2837/5251 +f 3413/3813/6949 3396/3045/6950 3414/2197/4523 +f 2122/3609/5916 2121/2410/6089 2119/3607/5914 +f 4297/4249/4329 4289/1976/4329 4296/1978/4329 +f 3725/4110/6603 3755/3294/6602 3726/3751/6317 +f 4066/2073/6942 4140/3321/5590 4160/4288/6943 +f 2283/2357/6172 2194/3812/6171 2280/3085/5341 +f 2647/4291/6951 2171/4292/6952 2649/2589/4870 +f 3605/2737/6285 3603/2739/6953 3604/4190/6953 +f 2977/2973/26 2978/1979/26 2937/4293/26 +f 2118/3343/6880 2593/3453/5741 3081/3454/5742 +f 2555/3139/5401 2545/3698/6031 2546/3533/5829 +f 3220/3550/5853 3211/4182/5853 3329/2671/5853 +f 3597/3340/4524 3595/2738/4524 3596/4294/4524 +f 2892/3975/6400 3028/3393/5674 2891/4011/6456 +f 3285/2148/4476 3270/2893/5145 3271/2004/6954 +f 1980/2256/4585 1979/2639/4584 1978/2331/4584 +f 4210/2119/5744 4213/2352/6938 4212/3886/6939 +f 4095/3486/5776 4092/2089/5898 4093/3487/5777 +f 3791/4140/6955 3803/3262/5528 3704/3474/5763 +f 4101/2742/5010 4100/2744/5012 4099/3529/5827 +f 4353/3861/4422 4316/3967/4422 4318/3348/4422 +f 2682/3300/5566 2679/2955/5202 2824/3525/5819 +f 3938/2415/5355 3941/3757/5355 3942/3098/5354 +f 3626/2469/4769 3625/2471/4769 3623/3469/6956 +f 3496/3335/6957 3497/4295/6958 3474/2286/4603 +f 3418/2937/5185 3424/3295/5561 3425/3716/6055 +f 4188/2121/4517 4187/2210/5503 4186/2832/4517 +f 4183/3712/4517 4191/3270/5503 4190/3461/4517 +f 4021/3944/6351 4020/3906/6293 4019/4252/6862 +f 4333/3359/5633 4334/2617/6497 4336/2638/6499 +f 3092/3542/6219 3098/2426/6219 3204/3855/6219 +f 2135/3378/6959 2136/4259/6960 2454/3117/5375 +f 2908/3991/6429 2849/2871/5127 2727/3625/5940 +f 4121/2816/5075 4122/2815/5074 4106/4296/6961 +f 3543/4133/6632 3514/2543/4835 3544/2113/4834 +f 4275/2993/5242 4276/3066/5321 4277/2778/5039 +f 4016/4184/6717 3993/3732/6962 4017/2817/5076 +f 2075/3682/6530 2074/3176/6963 2095/3178/6531 +f 3484/2903/4388 3519/3974/4388 3486/2902/4388 +f 2603/3947/6354 2083/2274/6964 2084/3945/6352 +f 2647/4291/6951 2648/2948/6965 2171/4292/6952 +f 2799/2142/4470 2785/2141/4469 2790/3027/5279 +f 3776/3759/6110 3793/3264/5530 3802/3263/5529 +f 2613/2502/6374 2180/2501/6966 2178/2933/6375 +f 3827/1984/4690 3823/2649/4688 3825/2652/4690 +f 2305/3005/5255 2397/4010/6455 2300/4009/6454 +f 2064/2759/5024 2033/3476/6967 2063/4150/6660 +f 1971/3465/5882 2045/3573/5881 2044/3094/5350 +f 4285/4222/4924 4284/4297/4924 4282/3711/4924 +f 3088/3180/5444 3089/4241/5444 3094/3209/5476 +f 2224/4298/6968 2225/3484/5774 2221/2495/4792 +f 3342/2308/4625 3345/2309/4350 3344/3405/5685 +f 2439/3251/5518 2440/4238/6841 2427/4225/6796 +f 2132/3291/6969 2131/2709/4978 2589/2711/4980 +f 1967/2240/5955 2052/2109/4438 2067/3552/5856 +f 3847/3103/6422 3834/2380/6879 3845/3104/6970 +f 2507/3743/6088 2503/3574/5883 2515/3582/5893 +f 4066/2073/6942 4063/4244/6857 4140/3321/5590 +f 3546/3538/5838 3468/3697/6844 3462/3912/6301 +f 3181/2858/5115 3169/2857/5114 3168/3602/5908 +f 2709/3784/6135 2708/3999/6442 2819/4299/6971 +f 3440/3579/5890 3442/3096/5352 3441/3899/6281 +f 3027/2406/4718 2892/3975/6400 2893/2673/4942 +f 4172/3087/4924 4181/2879/4924 4182/3088/4924 +f 2156/4300/6972 2154/4301/6973 2489/4275/6912 +f 3284/3900/6282 3297/3930/6328 3300/3717/6056 +f 3943/3203/5470 4029/3205/5472 4031/2081/4417 +f 3786/3182/6974 3798/2792/5053 3785/2907/5161 +f 2030/3994/6435 2017/3273/6436 2016/2493/5931 +f 2012/3962/6383 1985/3727/6383 1986/2267/6383 +f 3264/2135/4351 3256/3618/4351 3258/4229/4351 +f 2775/4302/6975 2772/2575/4860 2773/3235/5502 +f 1992/2640/5361 1995/2972/5344 1994/3891/6269 +f 3074/4255/6866 2902/2049/4390 3013/4223/6792 +f 2144/3266/5535 2182/3520/5813 2487/2590/4871 +f 2874/3316/5584 2877/2342/4654 2875/4126/6622 +f 2333/2285/4602 2332/4007/6451 2523/3420/5702 +f 4229/4303/6976 4235/4062/6523 4254/4061/6522 +f 2037/2644/6870 2036/2355/4668 2067/3552/5856 +f 3960/2251/6977 3958/2253/6978 3959/3733/6978 +f 2328/3983/6415 2242/3250/5517 2216/4304/6979 +f 2200/3662/5983 2270/3804/6163 2278/2530/5340 +f 2317/4305/6980 2571/2390/4702 2570/2632/4911 +f 2524/3655/5974 2160/3658/5977 2158/3534/6910 +f 2668/2804/5064 2829/2441/4745 2850/2805/5065 +f 3411/3297/6981 3410/4086/6982 3397/4111/6983 +f 4157/4097/6582 4159/3690/6021 4158/2442/4746 +f 2356/2529/4822 2572/3616/5926 2316/3617/5927 +f 3423/2283/4600 3440/3579/5890 3437/2281/4598 +f 3518/2170/4388 3498/4287/4388 3495/3337/4388 +f 3862/3188/5454 3860/4203/6984 3859/2315/4632 +f 3861/4247/6854 3860/4203/6984 3862/3188/5454 +f 3854/2032/5552 3856/3588/5896 3855/2030/6786 +f 2739/3859/6222 2683/4092/6573 2843/4090/6570 +f 4211/3456/5745 4210/2119/5744 4212/3886/6939 +f 3832/1993/4343 3900/1992/4342 3901/3746/6093 +f 2938/2409/511 2937/4293/26 2978/1979/26 +f 3030/3082/5337 3069/3848/6211 3070/3543/5843 +f 2447/4195/6744 2249/3302/5568 2446/3301/5567 +f 2756/3597/5901 2763/3686/6013 2796/4041/6492 +f 4214/2491/4790 4213/2352/6938 4215/2322/4638 +f 4347/1995/4345 4375/1994/4344 4348/4216/6985 +f 2860/3709/6046 2859/3968/6392 2857/3972/6396 +f 2849/2871/5127 2905/4306/6986 2727/3625/5940 +f 3702/3763/5358 3703/3864/6229 3701/3838/5358 +f 4073/3568/5872 4098/3528/6706 4096/4227/6987 +f 3536/2460/4762 3571/2462/4764 3535/2145/6714 +f 2598/4068/6988 2107/2985/6989 2106/3793/6990 +f 4291/4250/4329 4289/1976/4329 4290/2809/6774 +f 4353/3861/4422 4352/1996/4422 4316/3967/4422 +f 2740/3002/5252 2738/2730/4999 2770/2573/4858 +f 4354/2205/4529 4366/2603/6991 4367/2206/4530 +f 3688/2596/4877 3653/2151/4876 3589/3323/6507 +f 4045/3691/6022 3942/3098/6592 4044/3724/6067 +f 4243/2991/6992 4226/4085/6562 4242/2992/6993 +f 2727/3625/5940 2904/3110/5367 2908/3991/6429 +f 3497/4295/6994 3500/2045/4966 3499/2287/4968 +f 3947/2252/5000 3949/3703/5000 3946/3510/5000 +f 2629/3041/6401 2630/4204/6758 2631/3977/6402 +f 2431/3151/5412 2432/2411/4720 2112/3160/6995 +f 3270/2893/4351 3267/2180/6749 3236/4307/6749 +f 2835/4263/6883 2757/3726/6069 2755/2701/4970 +f 4123/3882/6996 4124/4272/6899 4109/3148/6901 +f 2427/4225/6796 2412/3242/5509 2439/3251/5518 +f 3389/2453/6997 3408/3095/5351 3391/4202/6756 +f 2935/4027/512 2934/4308/26 2979/4200/26 +f 3465/3578/5889 3553/3504/5793 3556/2812/5071 +f 3566/2348/4660 3529/2718/4987 3569/2717/4986 +f 3562/2114/4443 3524/2851/5107 3525/2918/5172 +f 4226/4085/4517 4225/3462/5503 4217/2321/4517 +f 2566/3735/6076 2325/3933/6332 2567/3314/5582 +f 2526/3767/6115 2523/3420/5702 2342/3239/5506 +f 2054/3445/5734 1971/3465/5882 2044/3094/5350 +f 4004/2890/6998 4044/3724/6067 4003/2226/6066 +f 3060/3137/5398 3062/3136/5397 3071/4106/6593 +f 4229/4303/6976 4254/4061/6522 4255/2598/4879 +f 3928/3494/4688 3925/2499/4688 3927/3345/4688 +f 4323/3288/4422 4357/2940/4422 4321/3349/4422 +f 2299/2895/5147 2284/2736/5004 2286/2358/4671 +f 2518/4047/6999 2575/4267/6891 2514/4268/6893 +f 3108/3883/6835 3100/1966/4319 3109/2389/4701 +f 3596/4294/7000 3595/2738/5006 3605/2737/5005 +f 3888/3411/4554 3853/3285/4554 3884/4096/5778 +f 2517/3584/6646 2516/3583/6892 2580/3253/6647 +f 2288/2735/6459 2296/2961/5208 2192/4280/6923 +f 4280/2964/5211 4260/2966/5213 4279/2850/5106 +f 3199/3464/5753 3175/4242/6848 3099/3179/7001 +f 4294/1977/4329 4289/1976/4329 4291/4250/4329 +f 2548/2328/4642 2547/3527/5825 2492/4278/6916 +f 3691/3308/5576 3655/2601/4882 3667/3668/5990 +f 4006/4309/7002 3996/4266/7003 4007/3872/6242 +f 2549/2925/5177 2533/2312/4629 2550/2326/4640 +f 3391/4202/4755 3381/2451/4755 3389/2453/4755 +f 2046/3572/5880 2047/2612/6503 2019/2613/7004 +f 2583/3748/26 2379/4310/26 2373/4311/26 +f 3194/4240/6846 3195/3327/5596 3196/4172/6700 +f 3787/3199/5466 3717/3626/5941 3786/3182/6974 +f 3177/3211/5478 3161/3379/5655 3198/3328/5597 +f 2491/3387/5665 2490/3386/5664 2488/4312/7005 +f 3225/3016/6598 3237/2398/6600 3224/3642/5958 +f 3695/2188/6349 3696/2538/6349 3580/2537/6349 +f 3838/2232/4785 3863/3189/7006 3839/2231/6262 +f 4191/3270/5539 4183/3712/6049 4222/3413/5697 +f 2034/2760/5025 2035/2541/4832 2022/2776/6248 +f 3355/4279/4755 3352/2656/4755 3354/2044/4386 +f 3712/3472/5761 3702/3763/5358 3708/3627/5358 +f 3304/4157/6671 3308/3643/5959 3306/3644/5960 +f 4017/2817/5076 3987/2733/7007 4000/3471/5760 +f 3466/2209/7008 3576/2213/7008 3575/2605/7009 +f 2324/3237/5504 2325/3933/6332 2245/3412/5696 +f 4168/2647/6837 4170/2646/4923 4271/4258/6874 +f 2323/3652/5971 2319/4313/7010 2247/3653/5972 +f 3390/3907/6295 3404/2162/4491 3388/3448/5738 +f 2519/3865/6230 2180/2501/7011 2179/3133/6231 +f 4113/2468/4367 4111/2176/4367 4080/2365/4367 +f 3263/2033/4351 3269/3079/4351 3251/3070/4351 +f 3879/3842/4554 3844/2395/5778 3876/3840/4554 +f 3664/3898/6280 3663/3410/5693 3638/2199/6804 +f 4121/2816/5075 4106/4296/6961 4107/2835/5886 +f 3321/3507/5796 3323/4314/7012 3322/3831/6195 +f 2057/3417/5699 2055/3919/6308 2056/3418/5700 +f 3281/2828/5087 3280/3832/6196 3292/2829/5088 +f 2567/3314/5582 2565/3238/5505 2555/3139/5401 +f 3706/3839/5358 3714/3112/5358 3705/4315/5358 +f 3290/2625/4906 3307/2627/4908 3309/4316/7013 +f 3311/3920/6309 3314/4317/7014 3313/3887/6266 +f 2141/3376/7015 2140/2408/7015 2139/2407/7015 +f 3132/2359/4672 3133/3157/4672 3131/2360/4673 +f 3123/3171/5994 3125/2216/7016 3126/3672/5995 +f 4104/2058/4396 4103/4063/7017 4074/2059/4397 +f 4237/2853/4517 4238/2189/4517 4205/3674/4517 +f 2564/3140/5402 2326/3050/5305 2329/2341/4653 +f 2232/2334/4648 2234/4318/7018 2233/2294/4611 +f 1964/3740/4316 1965/3739/4316 1963/3488/4316 +f 4292/2604/4885 4366/2603/4884 4391/3902/6288 +f 3581/2104/7019 3683/2303/4620 3578/2102/4433 +f 4177/3086/6710 4281/3043/5296 4280/2964/5211 +f 3272/4281/4351 3273/2003/4351 3242/2159/4351 +f 3475/2288/4605 3499/2287/4604 3501/2697/7020 +f 4129/2014/4360 4160/4288/6943 4140/3321/5590 +f 2356/2529/4822 2318/2528/4821 2572/3616/5926 +f 4006/4309/7021 4045/3691/6022 4005/3439/6640 +f 4080/2365/4678 4077/2065/5250 4079/2064/4678 +f 3724/3129/5388 3726/3751/4336 3723/3130/4336 +f 4306/2086/4422 4304/2088/4422 4309/2519/4422 +f 3194/4240/6846 3196/4172/6700 3159/2822/5081 +f 3829/2307/4624 3904/2629/4910 3905/2305/4622 +f 2119/3607/7022 2121/2410/7023 2718/2660/4932 +f 3635/2806/5671 3648/2304/4621 3633/2999/5248 +f 4281/3043/5296 4177/3086/6710 4182/3088/5661 +f 3642/4230/6805 3662/3442/6478 3641/4032/6477 +f 4250/2852/5108 4251/4177/7024 4238/2189/5109 +f 2416/3173/5434 2418/3249/5516 2417/4226/6797 +f 3269/3079/7025 3263/2033/4377 3278/2116/4698 +f 3099/3179/5444 3089/4241/5444 3088/3180/5444 +f 3322/3831/6195 3324/3986/6419 3292/2829/5088 +f 2089/2968/6730 2703/3995/6437 2832/4081/6554 +f 2321/2705/4974 2569/3730/6074 2322/3731/6075 +f 4152/3032/5284 4122/2815/5074 4150/2368/4681 +f 2266/3851/6214 2250/2923/5175 2249/3302/5568 +f 3603/2739/5007 3595/2738/5006 3602/3890/7026 +f 3975/3259/6733 3951/4044/6500 3974/4128/7027 +f 3996/4266/7003 3986/3873/6243 4007/3872/6242 +f 3758/2163/4492 3728/3938/6341 3727/2909/6822 +f 3548/4065/6528 3570/2166/4495 3569/2717/4986 +f 4087/2023/7028 4088/2369/4682 4090/2021/4684 +f 3342/2308/4625 3430/3296/5562 3431/2018/4364 +f 2952/4208/6762 2949/4224/6793 2948/4083/6763 +f 3875/4057/4554 3870/1999/4554 3878/3187/5778 +f 3519/3974/4388 3484/2903/4388 3520/3734/4388 +f 3097/2425/4965 3096/2424/6160 3184/2153/4481 +f 3778/2905/5159 3806/2245/4565 3777/3720/6059 +f 3510/2046/5834 3529/2718/5836 3528/2296/5720 +f 3613/2562/6676 3615/2434/6894 3598/3879/6675 +f 3367/2856/7029 3368/4319/7029 3370/2884/6390 +f 3218/3843/6205 3215/3630/6119 3207/3629/6119 +f 4309/2519/4812 4334/2617/4898 4332/2517/4810 +f 3485/2488/6836 3487/2490/6927 3471/2556/4844 +f 3929/2651/4688 3925/2499/4688 3928/3494/4688 +f 3778/2905/5159 3807/3246/5513 3806/2245/4565 +f 2000/3750/4585 2002/3334/4585 2021/2643/4584 +f 3268/3078/5333 3281/2828/6924 3272/4281/6926 +f 4060/3414/5698 4162/3416/5698 4055/3744/7030 +f 3257/2841/5097 3229/2234/4556 3259/3226/5492 +f 3139/2300/6258 3137/3904/6928 3136/2484/6928 +f 3238/2930/5182 3236/4307/5268 3235/3017/5268 +f 2412/3242/5509 2427/4225/6796 2428/3243/5510 +f 2579/2553/5493 2578/4320/7031 2452/3227/5494 +f 3561/2115/4444 3562/2114/4443 3456/3917/6306 +f 2420/3519/5812 2450/2412/4721 2432/2411/4720 +f 3560/3918/6307 3542/4040/6491 3543/4133/6632 +f 2805/4000/6443 2806/2505/4802 2712/2899/5151 +f 4118/2876/4367 4117/2875/4367 4085/3011/4367 +f 3514/2543/4388 3480/2764/5028 3478/2384/4388 +f 4104/2058/6914 4076/2837/5251 4105/2836/6525 +f 2409/3396/5677 2389/3955/6368 2398/2896/5148 +f 3736/2067/6888 3737/4321/7032 3739/2435/6889 +f 2806/2505/4802 2807/3620/5934 2813/3881/6255 +f 2466/3025/5278 2410/3395/5676 2408/3394/5675 +f 3589/3323/4434 3585/2173/4434 3588/3863/6228 +f 2628/3569/5876 2150/3282/5875 2627/3281/6391 +f 3775/4134/6633 3761/4142/6643 3760/3760/6111 +f 2490/3386/5664 2524/3655/5974 2158/3534/6910 +f 3147/3381/5657 3141/3354/5627 3160/3355/5629 +f 4238/2189/5109 4251/4177/7024 4236/2190/7033 +f 3974/4128/7027 3951/4044/6500 3972/4045/6501 +f 2815/3023/5274 3000/4218/6779 2816/3868/6237 +f 3223/3641/4351 3222/3225/4351 3225/3016/4351 +f 4227/3127/4517 4217/2321/4517 4220/3940/4517 +f 3254/2235/4557 3252/3069/7034 3228/2233/4555 +f 3985/2731/7035 3955/3427/5710 3984/4322/7036 +f 2738/2730/4999 2748/2729/4998 2769/3072/5327 +f 4086/4274/7037 4088/2369/4682 4087/2023/7028 +f 3565/2297/4614 3452/2681/4948 3564/3905/6292 +f 3707/2247/4567 3805/3770/6117 3806/2245/4565 +f 2992/2975/5222 2998/4206/6788 2977/2973/5220 +f 3947/2252/4572 3956/3429/5800 3958/2253/4573 +f 2633/3330/7038 2155/3785/6345 2926/3535/5832 +f 2795/3601/5905 2758/3598/5902 2756/3597/5901 +f 3960/2251/6977 3961/4276/7039 3962/3909/6297 +f 4193/2583/6704 4192/2084/6050 4183/3712/6049 +f 3421/2772/5035 3422/2807/5066 3335/2773/5036 +f 3720/1987/4405 3736/2067/4404 3721/1985/5448 +f 3138/1964/4317 3136/2484/4783 3107/1965/4318 +f 2141/3376/7040 2994/1981/7041 2995/3753/6103 +f 2962/2782/6275 2967/3460/6712 2972/3896/6276 +f 3996/4266/5000 3973/4014/5000 3986/3873/5000 +f 1992/2640/5361 1991/3107/5363 1990/2547/6932 +f 1974/3466/5755 1975/2239/4561 1976/2506/4316 +f 3430/3296/5562 3429/2869/5125 3425/3716/6055 +f 2177/4153/7042 2175/3521/7043 2960/4323/7044 +f 3559/2531/4824 3459/3758/6109 3558/2532/4825 +f 4122/2815/5074 4149/2366/4679 4150/2368/4681 +f 4033/3915/6304 4032/3008/5260 4034/3913/6302 +f 3352/2656/4755 3350/4029/4755 3351/2854/4755 +f 3162/3380/5656 3161/3379/5655 3177/3211/5478 +f 3265/2034/4378 3275/2219/4542 3276/2035/4379 +f 2450/2412/4721 2469/4214/6773 2476/4176/6707 +f 4073/3568/5872 4072/2429/4735 4070/2431/4367 +f 2486/2277/4594 2497/2026/4370 2484/4324/7045 +f 3991/2280/5000 3980/2479/5000 3992/2278/5000 +f 2311/3124/5382 2313/2749/5017 2531/3679/6004 +f 1966/2535/4828 1961/2534/4827 1962/2820/6472 +f 4259/2965/5212 4280/2964/5211 4281/3043/5296 +f 3582/2548/4434 3580/2537/4434 3590/3639/4434 +f 3360/2723/4992 3359/3969/6393 3358/4185/7046 +f 2940/4105/26 2977/2973/26 2937/4293/26 +f 3227/3654/5973 3247/3699/7047 3245/2684/4952 +f 2036/2355/4668 2035/2541/4832 2048/2353/4666 +f 2448/4198/6747 2251/2747/5015 2396/3551/5854 +f 3215/3630/7048 3220/3550/7049 3330/2041/7048 +f 2578/4320/7031 2577/3352/5624 2455/3353/5626 +f 3161/3379/5655 3160/3355/6333 3178/4325/7050 +f 3772/3181/4336 3737/4321/4336 3771/3957/4336 +f 1987/2330/5731 1988/2268/5730 1986/2267/6331 +f 4282/3711/4924 4283/4006/4924 4287/2569/4924 +f 2512/3450/6235 2584/3867/6234 2588/4082/6555 +f 3771/3957/4336 3737/4321/4336 3734/2753/4336 +f 4227/3127/4517 4226/4085/4517 4217/2321/4517 +f 2367/2552/26 2363/4326/26 2578/4320/26 +f 2810/2138/4466 2809/2140/4468 2808/2504/4801 +f 4391/3902/6288 4299/4016/6935 4292/2604/4885 +f 3864/2487/5455 3867/2111/4440 3865/4261/6881 +f 3086/3053/4731 3087/4137/4731 3085/2678/4731 +f 3344/3405/5685 3430/3296/5562 3342/2308/4625 +f 2360/3834/6198 2384/3836/6200 2392/4327/7051 +f 3229/2234/4351 3228/2233/4555 3227/3654/5973 +f 2069/2565/4316 2073/4328/5756 2072/2508/4316 +f 3747/2549/5387 3749/2131/6702 3724/3129/5388 +f 3247/3699/7047 3227/3654/5973 3248/3193/6381 +f 3346/3404/6918 3444/4329/7052 3445/3877/6251 +f 2790/3027/5279 2791/2877/5133 2792/2423/4730 +f 4110/3147/7053 4106/4296/6961 4122/2815/5074 +f 2260/4196/7054 2261/3207/7055 2262/3206/7055 +f 3212/3506/5795 3219/3718/6057 3323/4314/7012 +f 2494/3666/5987 2492/4278/6916 2151/4330/7056 +f 2307/3987/6420 2301/3502/5791 2306/2572/4857 +f 4392/3661/5981 4302/2201/4525 4368/3287/5555 +f 3089/4241/6847 3099/3179/7001 3175/4242/6848 +f 4198/4331/4517 4200/3026/4517 4235/4062/4517 +f 3438/2017/4363 3437/2281/4598 3440/3579/5890 +f 2869/3797/6150 2868/4120/6613 3037/2525/4818 +f 3228/2233/4555 3252/3069/7034 3250/3071/6380 +f 2468/2799/5059 2474/4332/7057 2451/3292/5558 +f 3752/2130/4457 3751/2467/4457 3749/2131/4458 +f 2497/2026/4370 2499/2025/4369 2534/3248/5515 +f 2731/2751/5019 2768/4213/6770 2767/3647/5966 +f 2325/3933/6332 2246/2703/4972 2245/3412/5696 +f 3562/2114/4443 3525/2918/5172 3563/2917/5171 +f 3176/3210/5477 3089/4241/6847 3163/2758/5023 +f 3601/3044/5297 3629/2635/5554 3602/3890/7026 +f 3577/2595/4532 3572/2337/4532 3576/2213/4532 +f 3542/4040/6491 3559/2531/4824 3541/2533/4826 +f 3215/3630/7048 3330/2041/7048 3331/3631/7048 +f 2412/3242/5509 2438/3252/5519 2439/3251/5518 +f 4325/3452/5849 4328/3549/5851 4326/3289/6636 +f 1983/2156/4484 2008/2155/4483 2006/2865/5120 +f 3409/4333/7058 3443/2900/5152 3408/3095/5351 +f 1984/3224/6579 1977/3728/6071 1985/3727/6070 +f 3602/3890/7026 3629/2635/5554 3631/2634/7059 +f 3449/4334/7060 3337/2001/7061 3345/2309/7060 +f 3348/2657/7062 3361/2722/7063 3349/2655/5601 +f 3969/2271/4587 3967/2270/4586 3966/3942/6348 +f 3202/4194/4731 3200/2680/4731 3204/3855/4731 +f 3358/4185/7046 3359/3969/6393 3357/4335/7064 +f 1990/2547/4839 1978/2331/4645 1979/2639/4916 +f 2560/3077/5332 2558/4037/6487 2557/4039/6489 +f 2708/3999/6442 2707/2503/4800 2903/3375/5651 +f 2820/3432/5717 2709/3784/6135 2819/4299/6971 +f 3608/2200/6286 3609/2687/4956 3607/4336/6286 +f 2525/3660/5980 2174/4161/6941 2162/3656/5975 +f 2002/3334/4585 2005/2186/4584 2020/2557/4585 +f 4269/4075/6548 4168/2647/6837 4270/3723/6064 +f 3545/3537/5837 3534/2146/4474 3535/2145/6714 +f 2869/3797/6150 2867/4123/6617 2868/4120/6613 +f 3145/2757/4406 3126/3672/4406 3129/3146/4406 +f 2449/3310/5578 2448/4198/6747 2421/4048/6506 +f 1993/3106/4585 1994/3891/4585 2025/2944/4585 +f 2588/4082/6555 2386/2450/4754 2387/3165/7065 +f 3112/2317/6929 3109/2389/6343 3111/2318/6929 +f 2117/3344/7066 2118/3343/7066 2126/4337/7067 +f 2096/3692/6023 2099/2077/6025 2097/2712/7068 +f 2797/3144/5406 2798/3143/5405 2780/2970/5217 +f 2355/4338/7069 2354/4339/7070 2353/3849/6212 +f 2276/3798/6154 2196/3801/6157 2195/3799/6155 +f 3399/3347/5620 3421/2772/5619 3420/3577/5887 +f 3931/3976/5355 3941/3757/5355 3938/2415/5355 +f 3908/3841/7071 3913/4340/7072 3907/4341/7073 +f 3641/4032/6477 3660/3219/5485 3643/3649/5968 +f 4160/4288/6943 4129/2014/4360 4128/2566/4852 +f 2855/3971/6395 2858/3997/6440 2857/3972/6396 +f 2350/2259/4579 2351/2258/4578 2352/4139/6638 +f 2260/4196/6745 2251/2747/5015 2264/4342/7074 +f 4156/3196/5463 4155/4215/6775 4061/2771/5034 +f 2400/2798/5058 2402/4343/7075 2468/2799/5059 +f 2576/4246/6853 2518/4047/6999 2519/3865/6230 +f 2751/2702/4971 2758/3598/5902 2752/4077/6550 +f 4269/4075/6548 4268/2029/4373 4168/2647/6837 +f 3754/2699/4768 3756/4245/6852 3755/3294/5560 +f 2101/2299/4617 2099/2077/4413 2471/2079/4415 +f 4244/3061/6563 4245/2849/5105 4225/3462/6561 +f 3467/2208/7076 3552/2461/4763 3465/3578/5889 +f 4346/3829/6361 4351/3497/4422 4341/3539/4422 +f 2994/1981/7041 2996/1980/6104 2995/3753/6103 +f 3103/2796/4406 3102/3046/4406 3101/2388/4406 +f 2384/3836/7077 2295/2962/6510 2389/3955/6368 +f 2690/3980/6409 2786/4251/6861 2800/2636/4914 +f 2976/2974/26 2977/2973/26 2940/4105/26 +f 3429/2869/5125 3430/3296/5562 3427/4178/6709 +f 2155/3785/6911 2156/4300/6972 2489/4275/6912 +f 3270/2893/4351 3236/4307/6749 3238/2930/4351 +f 2893/2673/4942 2894/2404/4716 3027/2406/4718 +f 4397/2663/4329 4396/4344/4329 4395/2979/4329 +f 2491/3387/5665 2493/4277/6915 2545/3698/6031 +f 4175/2567/4853 4181/2879/4854 4286/2568/4854 +f 3469/2939/7078 3507/2382/7079 3477/3762/7080 +f 3463/2349/4661 3567/2167/4496 3462/3912/6301 +f 3443/2900/5152 3441/3899/6281 3442/3096/5352 +f 3692/4264/6886 3584/3322/7081 3690/3434/5719 +f 4065/2071/4407 4059/2770/4409 4058/2072/4408 +f 3517/2524/4388 3498/4287/4388 3518/2170/4388 +f 2008/2155/7082 2009/3275/7082 2007/2185/4515 +f 3531/2394/4706 3548/4065/6528 3530/3536/5835 +f 2822/4345/7083 2823/2050/4391 2902/2049/4390 +f 2890/2957/5204 2889/3081/5336 2824/3525/5819 +f 2365/4346/26 2364/2777/26 2587/2448/26 +f 4336/2638/6499 4335/2616/6498 4337/3613/5920 +f 3457/2207/4807 3575/2605/4807 3574/2512/4807 +f 3310/4285/6933 3309/4316/7013 3209/3939/7084 +f 2030/3994/6435 2016/2493/5931 2029/3619/5933 +f 3777/3720/6059 3806/2245/4565 3805/3770/6117 +f 3216/2919/5173 3319/2217/4539 3315/4347/7085 +f 4173/3307/5575 4180/2891/5144 4169/2892/4924 +f 2591/3713/6053 2593/3453/6052 2117/3344/6832 +f 2903/3375/5651 2906/2075/4411 2819/4299/6971 +f 3951/4044/5000 3952/3704/5000 3950/2242/5001 +f 3725/4110/6603 3751/2467/6701 3753/2466/6601 +f 2214/3004/5254 2213/4189/6731 2308/4348/7086 +f 3133/3157/4672 3134/2485/7087 3135/3158/7087 +f 2419/3120/5378 2416/3173/5434 2442/3175/5436 +f 3960/2251/6977 3959/3733/6978 3961/4276/7039 +f 4166/3415/6311 4064/2579/6312 4165/2581/6312 +f 2996/1980/7088 2997/4205/6759 2991/4207/6761 +f 2671/4138/6635 2670/4349/7089 2895/2454/4756 +f 3291/2833/5092 3294/4286/6934 3293/3928/6326 +f 2031/3929/6327 2062/4173/6703 2063/4150/6660 +f 2494/3666/5987 2496/4350/7090 2549/2925/5177 +f 3465/3578/5889 3556/2812/5071 3464/2546/4838 +f 3120/3172/5432 3118/3701/6040 3103/2796/6039 +f 4105/2836/4367 4110/3147/4367 4102/2743/4367 +f 3513/3168/4388 3503/2047/4388 3510/2046/4388 +f 3090/4253/6864 3088/3180/5444 3094/3209/5476 +f 3692/4264/6886 3593/3706/6041 3584/3322/7081 +f 4227/3127/5385 4224/3229/5497 4240/3125/5383 +f 2708/3999/6442 2903/3375/5651 2819/4299/6971 +f 2805/4000/6922 2710/4002/6689 2946/3772/6120 +f 2909/3990/6428 2904/3110/5367 2818/3111/5368 +f 4084/3010/5262 4086/4274/7091 4087/2023/5263 +f 2540/3675/5999 2539/3677/6001 2529/2642/4919 +f 2646/4351/7092 3015/2994/5243 3014/4352/7093 +f 3113/2319/4635 3115/3047/5965 3116/2263/5964 +f 3971/3524/5817 3972/4045/7094 3970/2244/5818 +f 3769/4069/7095 3770/2223/4546 3780/2222/4545 +f 3167/4074/6547 3166/2193/4519 3182/2696/4964 +f 3796/3903/6289 3794/3871/6240 3795/2794/5055 +f 3536/2460/7096 3535/2145/4473 3522/4055/6811 +f 4163/4135/5263 4059/2770/5263 4054/2769/6634 +f 4271/4258/6874 4273/3935/6338 4272/3222/5489 +f 1963/3488/4316 1962/2820/6472 1964/3740/4316 +f 3969/2271/5000 3999/3089/5000 3971/3524/5000 +f 2315/2996/5245 2572/3616/5926 2573/2677/4946 +f 3023/4233/6827 2901/3313/5581 2822/4345/7083 +f 3894/2371/4685 3893/2373/5452 3877/2414/4723 +f 3603/2739/5007 3602/3890/7026 3631/2634/7059 +f 4366/2603/4884 4365/3901/6287 4391/3902/6288 +f 2467/4210/6766 2474/4332/7057 2402/4343/7075 +f 4305/2087/5198 4306/2086/5691 4322/2950/5196 +f 3735/2066/6366 3737/4321/7032 3736/2067/6888 +f 2427/4225/6796 2416/3173/5434 2417/4226/6797 +f 4273/3935/6338 4170/2646/4923 4171/3936/6339 +f 3968/2243/4563 3949/3703/6264 3967/2270/6263 +f 4032/3008/5260 4031/2081/4417 4014/2080/4416 +f 3496/3335/5604 3498/4287/7097 3497/4295/6994 +f 4311/3951/6361 4310/3419/4422 4309/2519/4422 +f 3740/2436/4741 3742/3283/5713 3741/3511/5804 +f 3239/2157/6599 3225/3016/6598 3241/2158/4513 +f 4205/3674/6677 4202/2191/5366 4203/2831/7098 +f 3598/3879/6675 3597/3340/5611 3611/3341/5613 +f 3205/3856/7099 3085/2678/7099 3092/3542/7099 +f 3701/3838/7100 3813/3212/6889 3811/3764/7100 +f 3304/4157/6671 3306/3644/5960 3288/2179/6672 +f 3207/3629/6471 3326/2039/6471 3206/3015/6471 +f 3449/4334/7101 3339/2002/7101 3337/2001/7102 +f 2079/2741/6008 2078/2740/7103 2077/3223/6009 +f 2903/3375/6122 2706/3374/7104 2946/3772/6120 +f 3746/3092/5348 3770/2223/4337 3748/2550/4336 +f 1969/1961/4314 2066/2354/4667 2065/2653/4928 +f 3435/2301/4618 3336/2016/4362 3334/3512/5805 +f 2691/3372/5648 2784/3371/5647 2782/3612/5919 +f 3149/2631/5924 3148/3710/6047 3171/3599/6813 +f 4199/3108/5364 4202/2191/5366 4200/3026/5364 +f 2323/3652/5971 2569/3730/6074 2568/4232/6826 +f 2470/4353/7105 2429/2078/4414 2430/4354/7106 +f 4142/4033/6481 4143/3075/5330 4141/3278/5546 +f 3512/3167/4387 3505/2614/4387 3513/3168/4388 +f 3225/3016/6598 3226/2182/4511 3241/2158/4513 +f 3973/4014/6626 3974/4128/6625 3972/4045/7094 +f 3586/3409/5692 3587/3769/6785 3594/2768/5032 +f 3674/2576/4861 3658/2446/4750 3675/2445/4749 +f 3985/2731/7035 3984/4322/7036 3982/4231/6807 +f 3937/4355/7107 3940/2324/5354 3943/3203/5470 +f 2658/3221/5487 2657/3122/5380 2848/3123/5381 +f 3291/2833/5092 3290/2625/4906 3294/4286/6934 +f 2077/3223/5490 2078/2740/6257 2383/3360/5634 +f 3379/2452/5594 3381/2451/5595 3380/2042/5595 +f 2272/2481/5982 2199/3663/5984 2273/2482/6162 +f 4017/2817/5076 3993/3732/7108 3988/4356/7109 +f 3881/2707/4554 3857/2314/4554 3874/3431/4554 +f 3786/3182/6974 3717/3626/5941 3798/2792/5053 +f 2804/4243/6851 2686/2953/5200 2802/4054/6513 +f 3267/2180/4509 3288/2179/4508 3289/2626/5307 +f 4173/3307/5575 4268/2029/4373 4267/3953/6363 +f 3358/4185/7046 3356/2237/4559 3387/2236/4558 +f 3539/2960/5207 3519/3974/6398 3540/2621/4902 +f 3316/4248/6856 3314/4317/7014 3315/4347/7085 +f 4342/4121/7110 4340/3541/5842 4343/4357/7111 +f 3763/3721/4336 3756/4245/4336 3754/2699/4336 +f 4266/3954/6364 4267/3953/6363 4262/2597/4878 +f 3044/2527/4820 3034/3707/6044 3004/4221/6790 +f 4297/4249/7112 4300/4358/7113 4397/2663/7112 +f 3123/3171/5994 3124/3284/5996 3122/3463/6036 +f 4174/4159/5364 4167/2648/7114 4282/3711/5364 +f 3627/2470/4770 3628/3443/4770 3630/2633/4912 +f 3661/3382/5658 3677/4070/6543 3668/3383/5659 +f 4289/1976/7115 4297/4249/7115 4398/4359/7115 +f 4193/2583/6704 4183/3712/6049 4184/3422/5708 +f 3145/2757/4406 3146/2756/4406 3126/3672/4406 +f 4026/3204/5471 3945/2260/4580 4024/2262/4582 +f 2564/3140/5402 2562/2340/4652 2556/3141/5403 +f 3931/3976/5355 3932/2325/5354 3933/3012/5355 +f 3876/3840/6520 3889/2053/6519 3909/2052/6202 +f 3273/2003/6284 3272/4281/6926 3283/3931/6909 +f 4005/3439/5725 3996/4266/7003 4006/4309/7002 +f 3453/2338/4532 3461/2350/4662 3458/2336/5703 +f 4102/2743/5011 4101/2742/5010 4103/4063/6526 +f 4199/3108/7116 4198/4331/7117 4197/3425/7117 +f 3999/3089/5345 4009/3646/5962 3986/3873/6243 +f 3078/2725/4994 3009/2727/4996 3010/4360/7118 +f 4126/3362/5637 4125/4098/6583 4157/4097/6582 +f 4015/3009/5728 3994/3441/5727 4016/4184/7119 +f 4369/3201/6291 4368/3287/5555 4377/2203/4527 +f 2679/2955/5202 2678/4103/6589 2853/2956/5203 +f 3348/2657/4808 3352/2656/4755 3347/3007/4755 +f 3221/3824/6187 3219/3718/6057 3220/3550/4383 +f 3278/2116/4698 3279/3080/7120 3269/3079/7025 +f 4329/2981/6544 4331/3358/5632 4330/3357/5631 +f 4304/2088/5543 4305/2087/5198 4317/4036/7121 +f 3880/4066/6532 3907/4341/7122 3906/2402/7123 +f 4023/2261/4581 4021/3944/6351 4022/4283/6930 +f 3141/3354/4406 3147/3381/4406 3131/2360/4406 +f 3449/4334/4350 3446/3162/4350 3448/4236/4626 +f 3163/2758/5023 3162/3380/5656 3176/3210/5477 +f 3244/2623/4351 3246/2622/4351 3268/3078/4351 +f 2905/4306/6986 2849/2871/5127 2848/3123/5381 +f 3446/3162/4350 3451/2097/4350 3447/3163/4350 +f 3041/3795/6148 3047/2692/4960 3039/4025/6469 +f 3997/3440/5000 3964/3910/5000 3961/4276/5000 +f 3381/2451/5595 3383/4018/6314 3382/2043/6314 +f 3101/2388/4406 3107/1965/4406 3103/2796/4406 +f 3576/2213/4532 3572/2337/4532 3575/2605/4532 +f 3915/2051/4392 3913/4340/7072 3908/3841/7071 +f 2222/4361/7124 2224/4298/6968 2221/2495/4792 +f 3207/3629/5944 3331/3631/5944 3327/2040/5944 +f 2019/2613/4585 2018/2269/4585 1988/2268/4585 +f 2484/4324/7045 2497/2026/4370 2535/2311/4628 +f 2495/2926/5178 2485/2310/4627 2533/2312/4629 +f 2318/2528/4821 2270/3804/6681 2271/2483/4782 +f 2493/4277/6915 2491/3387/5665 2151/4330/7056 +f 3130/1990/4340 3128/2316/4633 3105/1988/4338 +f 3456/3917/6306 3559/2531/4824 3560/3918/6307 +f 3642/4230/5462 3610/2688/5462 3608/2200/4524 +f 3394/3368/4808 3362/2724/4755 3360/2723/4755 +f 4316/3967/6484 4314/2122/6725 4313/3277/6724 +f 3197/2823/5082 3178/4325/7050 3179/2821/5080 +f 2959/4362/7125 2958/2783/7125 3020/4021/7125 +f 2085/2844/5440 2094/2914/5437 2394/2558/4846 +f 2462/3390/6604 2464/2449/4753 2587/2448/4752 +f 3019/2726/4995 3021/4028/6470 3009/2727/4996 +f 2473/2986/5235 2108/3794/7126 2107/2985/5233 +f 3230/4147/7127 3222/3225/5491 3231/4042/6494 +f 3579/2103/4434 3582/2548/4434 3581/2104/4434 +f 2437/3604/5911 2436/2840/5096 2238/2293/4610 +f 2706/3374/7104 2705/3683/6921 2946/3772/6120 +f 2715/3135/5396 2130/2802/7128 2132/3291/7129 +f 2849/2871/5127 2907/2074/4410 2661/2076/4412 +f 1998/2379/5342 1995/2972/5344 1997/2255/5342 +f 3552/2461/4763 3554/3505/5794 3553/3504/5793 +f 2783/3496/5785 2784/3371/5647 2769/3072/5327 +f 3775/4134/6633 3803/3262/5528 3791/4140/6955 +f 3402/2885/4755 3370/2884/4755 3368/4319/4755 +f 2804/4243/6851 2820/3432/5717 2686/2953/5200 +f 4042/3563/5866 4002/2224/4954 4043/3725/6068 +f 2479/2571/7130 2512/3450/6235 2588/4082/6555 +f 3255/3065/4351 3256/3618/4351 3264/2135/4351 +f 2615/3958/6376 2145/2721/7131 2614/3959/6377 +f 2027/2377/4585 2025/2944/4585 1996/2378/4585 +f 2622/3964/6387 2620/3696/6389 2621/3695/7132 +f 3019/2726/4995 3022/4363/7133 2822/4345/7083 +f 4347/1995/4422 4348/4216/4422 4344/2123/4422 +f 4228/3596/6860 4256/2027/6871 4257/4211/6936 +f 2433/3517/5810 2421/4048/6506 2448/4198/6747 +f 4264/3305/5571 4251/4177/6708 4182/3088/5661 +f 2800/2636/4914 2801/3373/5649 2690/3980/6409 +f 2271/2483/4782 2265/4008/7134 2266/3851/6214 +f 4372/2941/7135 4371/3714/6054 4378/3003/5253 +f 4003/2226/6066 4043/3725/6068 4002/2224/4954 +f 3251/3070/4351 3269/3079/4351 3249/3194/6749 +f 3907/4341/7073 3913/4340/7072 3912/2306/4623 +f 3678/3216/5482 3663/3410/5693 3679/3217/5483 +f 2872/4124/6618 2871/4024/6468 2874/3316/5584 +f 4289/1976/7115 4398/4359/7115 4394/2662/7115 +f 3599/3766/6895 3620/3566/6843 3600/3468/5757 +f 3081/3454/5742 2718/2660/4932 2817/2990/5239 +f 4039/4060/6521 4041/3562/5865 4040/3013/5266 +f 3016/4187/6722 2645/4160/7136 2170/2947/5193 +f 4063/4244/6857 4132/2882/6480 4131/2881/6945 +f 1984/3224/6579 2012/3962/6580 2010/2060/4485 +f 2511/3366/6236 2510/3192/6098 2583/3748/6097 +f 2025/2944/4585 2023/2943/4585 1993/3106/4585 +f 2452/3227/7137 2475/4209/6765 2477/2825/5084 +f 3386/2238/5258 3355/4279/6919 3384/3490/6920 +f 3474/2286/4603 3493/3336/5689 3496/3335/6957 +f 2970/3557/5862 2956/3556/5861 2955/4118/6611 +f 2808/2504/4801 2807/3620/5934 2806/2505/4802 +f 2488/4312/7005 2489/4275/6912 2153/3514/7138 +f 3704/3474/5763 3801/3473/5762 3791/4140/6955 +f 3446/3162/5420 3333/2230/5420 3332/3570/5420 +f 3114/2630/4406 3116/2263/4406 3148/3710/4406 +f 1966/2535/4828 1973/1962/4315 2063/4150/6660 +f 2014/2492/5932 2028/4046/6508 2029/3619/5933 +f 3318/4235/6834 3316/4248/6856 3315/4347/7085 +f 3626/2469/4769 3628/3443/4770 3627/2470/4770 +f 3300/3717/6056 3301/3719/6058 3284/3900/6282 +f 3699/2187/6313 3592/3705/6313 3587/3769/6313 +f 4296/1978/6169 4373/3862/6274 4372/2941/7135 +f 3365/2855/6838 3366/2515/6838 3368/4319/7029 +f 1963/3488/4316 1965/3739/4316 1971/3465/5754 +f 2121/2410/4719 2451/3292/5558 2130/2802/7139 +f 3337/2001/4350 3341/2000/4350 3338/3814/4350 +f 2043/2945/5191 2042/3669/5991 2051/3895/6273 +f 2800/2636/4914 2688/2143/4471 2774/3530/5828 +f 3369/3966/6407 3351/2854/5111 3367/2856/5113 +f 3722/3183/5447 3738/2437/5449 3740/2436/6819 +f 2356/2529/4822 2357/4079/6552 2278/2530/4823 +f 3468/3697/4531 3457/2207/4531 3462/3912/4532 +f 2685/1969/4322 2684/2592/4873 2737/1967/4320 +f 3333/2230/5878 3334/3512/5878 3332/3570/5878 +f 3765/2755/4337 3732/2754/4336 3764/4141/4336 +f 2885/3480/5770 3031/3479/5769 3036/2859/5116 +f 3450/2098/4350 3446/3162/4350 3449/4334/4350 +f 3532/3064/5320 3546/3538/5838 3547/2393/4705 +f 2743/4043/6495 2742/3754/6105 2694/3989/6425 +f 3462/3912/6301 3570/2166/4495 3547/2393/4705 +f 4067/2057/4395 4068/2063/4400 4077/2065/4402 +f 3709/3645/5358 3706/3839/5358 3710/2246/5358 +f 4202/2191/5366 4201/3109/5365 4203/2831/7098 +f 2432/2411/4720 2118/3343/7140 2116/3356/7141 +f 2751/2702/4971 2755/2701/4970 2758/3598/5902 +f 4085/3011/5264 4082/2364/4677 4083/3664/5985 +f 2297/2894/5146 2398/2896/5148 2284/2736/5004 +f 2268/2924/6138 2202/3790/6142 2204/3787/6139 +f 4341/3539/5840 4339/3498/5921 4338/3540/5841 +f 3618/2433/4738 3619/3916/6305 3621/3565/5869 +f 2044/3094/5350 2045/3573/7142 2023/2943/5189 +f 2728/2988/5237 2723/3093/5349 2727/3625/5940 +f 2436/2840/5096 2231/2332/4646 2233/2294/4611 +f 3188/3688/6019 3172/3689/6020 3187/3837/6201 +f 2560/3077/5332 2331/1974/4327 2333/2285/4602 +f 4298/2810/5069 4389/3215/5481 4386/2811/5070 +f 3266/3051/5306 3290/2625/4906 3291/2833/5092 +f 3470/2554/4842 3469/2939/7078 3479/3761/7143 +f 2290/3827/7144 2291/3820/6737 2284/2736/5004 +f 1967/2240/5955 1975/2239/4561 2052/2109/4438 +f 2872/4124/6618 2867/4123/6617 2870/3796/6149 +f 3064/3228/5496 3004/4221/6790 3073/3433/5718 +f 2284/2736/5004 2285/3633/6823 2286/2358/4671 +f 2138/3370/5646 2453/3290/5556 2451/3292/5558 +f 3732/2754/7145 3731/3885/7145 3729/2910/6821 +f 3859/2315/4632 3860/4203/6984 3858/2313/4630 +f 2041/3670/6042 2026/2667/4938 2040/2110/4937 +f 3464/2546/4838 3558/2532/4825 3459/3758/6109 +f 4357/2940/5186 4359/3202/5469 4370/3200/6516 +f 2222/4361/7124 2221/2495/4792 2223/4364/7146 +f 2795/3601/5905 2789/2690/4958 2758/3598/5902 +f 3768/4144/7147 3779/2904/5158 3762/2698/5157 +f 4287/2569/5745 4169/2892/5745 4175/2567/5745 +f 2980/4199/26 2981/3737/26 2935/4027/512 +f 2164/4109/6597 2883/4131/6629 2882/4130/6628 +f 3701/3838/7100 3706/3839/6889 3813/3212/6889 +f 2851/2618/4899 2675/4100/6585 2674/2619/4900 +f 3543/4133/6632 3561/2115/4444 3560/3918/6307 +f 3227/3654/5973 3228/2233/4555 3250/3071/6380 +f 3293/3928/6326 3310/4285/6933 3312/3921/6310 +f 2617/3169/6379 2616/3960/6378 2619/2229/4552 +f 3840/2178/4506 3869/1997/5373 3841/4237/6839 +f 4232/2606/4886 4225/3462/6561 4245/2849/5105 +f 3000/4218/6779 2992/2975/6772 2993/4122/7148 +f 3243/2183/4904 3244/2623/4904 3242/2159/4487 +f 4294/1977/6030 4382/2762/5027 4381/2520/4813 +f 2993/4122/6614 2976/2974/5221 2975/3559/6615 +f 3164/2838/5094 3163/2758/5023 3175/4242/6848 +f 2360/3834/6198 2392/4327/7051 2361/3922/6315 +f 3599/3766/6895 3615/2434/6894 3618/2433/6906 +f 3808/3245/5512 3710/2246/4566 3807/3246/5513 +f 2969/3558/6080 2980/4199/6753 2968/4197/6752 +f 3030/3082/5337 2888/3481/5771 2854/3083/5338 +f 3167/4074/6547 3168/3602/5908 3153/3531/5907 +f 2309/2641/4918 2304/3503/5792 2214/3004/5254 +f 3878/3187/5778 3867/2111/5778 3877/2414/4554 +f 2551/2327/4641 2572/3616/5926 2552/2392/4704 +f 4224/3229/4517 4223/2083/4517 4194/2085/4517 +f 2924/3580/5891 3052/4170/6698 3053/3948/6355 +f 2112/3160/6995 2110/3852/7149 2473/2986/5235 +f 3777/3720/6059 3804/3771/6118 3793/3264/5530 +f 3728/3938/4337 3761/4142/4336 3730/4180/4337 +f 3788/3197/6859 3771/3957/6370 3789/3786/6372 +f 2524/3655/5974 2542/3388/5666 2559/4003/6446 +f 3835/2381/6421 3852/3286/6496 3836/2031/4375 +f 3641/4032/6477 3661/3382/5658 3660/3219/5485 +f 3818/2376/4690 3817/3941/6347 3822/3234/4688 +f 3956/3429/5800 3947/2252/4572 3946/3510/5801 +f 3234/3018/4351 3266/3051/4351 3232/4148/4351 +f 3823/2649/4925 3929/2651/4925 3928/3494/4925 +f 2866/3978/6404 2865/4119/6612 2864/4116/6609 +f 4289/1976/5851 4394/2662/5851 4393/2661/5851 +f 3873/2397/4709 3842/2396/4708 3872/4365/7150 +f 3104/2795/5433 3120/3172/5432 3103/2796/6039 +f 2275/3438/5724 2276/3798/7151 2271/2483/4782 +f 2700/3269/5538 2777/3293/5559 2776/2037/4381 +f 3713/2862/5119 3814/2864/5119 3705/4315/7152 +f 4159/3690/6021 4157/4097/6582 4065/2071/4407 +f 3512/3167/5426 3525/2918/6037 3509/2544/4836 +f 2023/2943/5189 2045/3573/7142 2024/4282/7153 +f 3324/3986/6419 3323/4314/7012 3299/4163/6687 +f 2259/3776/6125 2258/3777/6126 2206/3774/6123 +f 1974/3466/5755 2054/3445/5734 2053/3741/6086 +f 2997/4205/6787 2978/1979/4330 2977/2973/5220 +f 3337/2001/4350 3346/3404/4350 3345/2309/4350 +f 2650/4093/6575 2685/1969/4322 2844/4366/7154 +f 3486/2902/4388 3521/2586/4388 3488/2489/4388 +f 2583/3748/26 2574/3747/26 2379/4310/26 +f 2102/2010/6412 2103/2011/7155 2602/2427/6413 +f 3199/3464/5753 3099/3179/7001 3182/2696/4964 +f 4092/2089/4367 4115/2013/5277 4119/2012/4367 +f 4329/2981/5228 4327/3548/7156 4307/2980/5227 +f 3395/4257/6869 3377/3339/4808 3374/3029/4755 +f 3971/3524/5817 3973/4014/6626 3972/4045/7094 +f 3934/3854/7157 4036/4367/7158 4037/2819/5078 +f 4094/3485/6944 4073/3568/5872 4096/4227/6987 +f 3582/2548/5573 3682/3306/5572 3581/2104/7019 +f 2820/3432/5717 2804/4243/6851 2810/2138/4466 +f 3336/2016/4362 3439/2015/4361 3341/2000/5153 +f 3733/3134/6367 3731/3885/7145 3732/2754/7145 +f 4318/3348/6483 4317/4036/6485 4319/3058/7159 +f 3961/4276/7039 3964/3910/6298 3962/3909/6297 +f 3971/3524/5817 3968/2243/4588 3969/2271/4587 +f 3266/3051/5306 3267/2180/4509 3289/2626/5307 +f 3566/2348/4660 3569/2717/4986 3568/2168/4497 +f 2166/3257/5521 2168/2588/4869 2169/2587/4868 +f 3190/3020/5271 3191/3817/6178 3192/3052/5308 +f 2523/3420/5702 2340/3364/5639 2342/3239/5506 +f 3022/4363/7133 3023/4233/6827 2822/4345/7083 +f 2331/1974/4327 2330/3076/5331 2358/1975/4328 +f 2112/3160/6735 2596/3324/5591 2597/3455/5743 +f 2335/2284/4601 2332/4007/6451 2333/2285/4602 +f 3592/3705/6718 3698/2438/6718 3583/2174/6718 +f 4263/3304/5570 4265/3303/5569 4253/3926/6324 +f 2999/3752/6102 2815/3023/5274 2589/2711/5276 +f 3310/4285/6933 3311/3920/6309 3312/3921/6310 +f 3907/4341/7073 3912/2306/4623 3906/2402/4714 +f 2585/2094/4427 2463/2093/4426 2462/3390/6604 +f 4340/3541/7160 4311/3951/6644 4343/4357/7161 +f 2443/3121/5379 2245/3412/5696 2246/2703/4972 +f 1994/3891/6269 1993/3106/5362 1992/2640/5361 +f 3086/3053/5309 3192/3052/5308 3191/3817/6178 +f 3187/3837/6201 3087/4137/6946 3188/3688/6019 +f 4048/3593/7162 3931/3976/7162 3938/2415/7163 +f 4182/3088/5661 4248/2766/7164 4247/2765/7165 +f 4048/3593/7162 3938/2415/7163 4050/2417/7163 +f 4285/4222/7166 4172/3087/7166 4174/4159/7166 +f 3443/2900/5152 3439/2015/4361 3441/3899/6281 +f 2212/2750/5018 2286/2358/4671 2279/4080/6553 +f 3593/3706/6041 3670/2577/4862 3671/4368/7167 +f 3978/2478/5000 3989/2225/5001 3980/2479/5000 +f 3320/2118/4447 3317/2220/4543 3318/4235/6834 +f 2218/2982/5229 2353/3849/6212 2358/1975/4328 +f 3001/4284/6931 3063/3640/5954 3007/3333/5603 +f 2999/3752/6102 2996/1980/7088 2991/4207/6761 +f 2461/3482/5772 2579/2553/5493 2458/2824/5495 +f 2957/3892/6270 2959/4362/7168 3075/2610/4890 +f 4397/2663/7169 4293/4015/7169 4396/4344/7170 +f 4040/3013/5266 4018/2818/5077 4039/4060/6521 +f 3704/3474/5358 3702/3763/5358 3712/3472/5761 +f 2909/3990/6428 2821/4369/7171 2907/2074/4410 +f 3031/3479/5769 2888/3481/5771 3030/3082/5337 +f 4207/2846/5102 4206/2211/5102 4208/2120/5103 +f 1978/2331/4645 1987/2330/4644 1977/3728/6071 +f 3184/2153/4481 3181/2858/5115 3183/2695/4963 +f 3876/3840/4554 3873/2397/4554 3875/4057/4554 +f 3633/2999/4524 3632/3184/4524 3635/2806/4524 +f 2554/3315/5583 2566/3735/6076 2567/3314/5582 +f 2383/3360/5634 2394/2558/4846 2436/2840/5096 +f 3718/2911/5165 3729/2910/5164 3719/1986/5394 +f 3497/4295/6994 3498/4287/7097 3500/2045/4966 +f 2954/4117/6610 2953/4165/7172 2970/3557/5862 +f 3162/3380/5656 3163/2758/5023 3145/2757/5022 +f 3762/2698/5157 3778/2905/5159 3763/3721/6060 +f 3093/3406/5686 3083/3054/6864 3084/4023/4731 +f 4178/4370/6680 4176/2779/6679 4174/4159/6680 +f 4208/2120/5103 4210/2119/5744 4209/2845/5101 +f 3801/3473/5762 3712/3472/5761 3800/4186/6720 +f 2279/4080/6553 2278/2530/4823 2357/4079/6552 +f 2213/4189/6731 2530/3681/6006 2529/2642/4919 +f 4178/4370/7173 4279/2850/5106 4278/2780/5041 +f 3044/2527/4820 3003/4220/6789 3008/3231/5499 +f 3031/3479/5769 3070/3543/5843 3071/4106/6593 +f 2076/3177/7174 2074/3176/7174 2075/3682/7174 +f 2946/3772/26 2983/4058/26 2944/4059/26 +f 2155/3785/6136 2634/3329/5598 2635/3981/6410 +f 4302/2201/4329 4292/2604/4329 4293/4015/4329 +f 2409/3396/5677 2382/3477/5767 2408/3394/5675 +f 3107/1965/4406 3106/1989/4339 3105/1988/4338 +f 2947/3773/6121 2949/4224/6829 2950/3858/6829 +f 2759/3700/6034 2702/3385/5663 2761/2038/4382 +f 2423/3606/5913 2446/3301/5567 2449/3310/5578 +f 2588/4082/26 2584/3867/26 2374/4174/26 +f 3260/3145/6514 3259/3226/6515 3230/4147/6650 +f 2477/2825/5084 2458/2824/5083 2452/3227/7137 +f 3827/1984/4690 3825/2652/4690 3822/3234/4688 +f 3054/3949/6356 3053/3948/6355 3051/2958/5205 +f 3842/2396/4708 3844/2395/4707 3843/3545/5846 +f 3319/2217/4539 3216/2919/5173 3217/2218/4540 +f 2123/3608/7175 2590/3493/6947 2591/3713/6053 +f 2181/2913/5167 2177/4153/7042 2961/2912/5166 +f 2177/4153/7042 2960/4323/7044 3020/4021/6464 +f 3361/2722/7063 3348/2657/7062 3359/3969/7176 +f 2723/3093/5349 2728/2988/5237 2817/2990/5239 +f 2408/3394/5675 2407/2401/4713 2466/3025/5278 +f 3639/2599/4524 3619/3916/4524 3644/4104/4524 +f 2382/3477/5767 2398/2896/5148 2397/4010/6455 +f 3432/2808/5067 3404/2162/4491 3434/2161/4490 +f 4161/4136/4409 4162/3416/4409 4164/2580/4409 +f 2395/2713/4982 2097/2712/4981 2095/3178/5443 +f 3605/2737/6285 3608/2200/6286 3607/4336/6286 +f 2650/4093/6575 2844/4366/7154 2733/2560/4848 +f 3390/3907/4755 3385/3491/4755 3383/4018/4755 +f 2499/2025/4369 2502/2387/4696 2534/3248/5515 +f 3509/2544/4388 3508/2383/4388 3512/3167/4387 +f 3108/3883/6260 3110/2070/6344 3139/2300/6258 +f 3201/2679/4731 3205/3856/4731 3204/3855/4731 +f 3989/2225/5001 3978/2478/5000 3995/2889/5000 +f 4341/3539/4422 4342/4121/4422 4346/3829/6361 +f 4014/2080/7177 3997/3440/5726 4015/3009/5728 +f 3709/3645/5961 3808/3245/5512 3809/3952/6362 +f 4190/3461/4517 4189/2351/4517 4186/2832/4517 +f 4323/3288/6537 4322/2950/7178 4324/3408/6637 +f 3945/2260/4580 3944/3590/5354 3935/3060/5354 +f 4261/2028/4372 4267/3953/6363 4268/2029/4373 +f 2561/4179/6713 2328/3983/6415 2330/3076/5331 +f 2268/2924/5176 2269/3788/6902 2253/2922/5174 +f 2499/2025/4369 2498/2024/4368 2500/2654/4929 +f 3666/2998/6913 3680/3897/6279 3665/3132/6278 +f 4019/4252/6862 4022/4283/6930 4021/3944/6351 +f 3737/4321/4336 3772/3181/4336 3739/2435/4336 +f 2726/2345/4657 2765/2498/4795 2731/2751/5019 +f 2142/4371/7179 2144/3266/7179 2175/3521/7179 +f 3014/4352/7093 3015/2994/5243 3012/2949/5195 +f 3540/2621/4902 3557/2545/4837 3550/2814/5073 +f 2341/3365/5640 2343/4372/7180 2342/3239/5506 +f 2321/2705/4974 2566/3735/6076 2569/3730/6074 +f 3693/3667/5989 3593/3706/6041 3692/4264/6886 +f 3735/2066/6366 3734/2753/6365 3737/4321/7032 +f 2503/3574/5883 2483/3513/5806 2506/2459/4761 +f 4359/3202/4422 4357/2940/4422 4323/3288/4422 +f 2087/2842/5098 2083/2274/7181 2084/3945/7182 +f 4357/2940/5186 4371/3714/6863 4372/2941/5187 +f 2739/3859/6222 2738/2730/4999 2740/3002/5252 +f 3507/2382/4691 3478/2384/4693 3477/3762/4693 +f 2688/2143/4471 2687/4132/6631 2768/4213/6770 +f 2755/2701/4970 2757/3726/6069 2756/3597/5901 +f 2353/3849/6212 2354/4339/7070 2358/1975/4328 +f 2305/3005/5255 2214/3004/5254 2388/3166/5424 +f 4138/3576/5885 4137/2177/6673 4145/3635/5948 +f 2725/2752/5020 2724/4373/7183 2726/2345/4657 +f 3476/2938/6061 3507/2382/7079 3469/2939/7078 +f 4167/2648/4924 4174/4159/6680 4171/3936/6339 +f 2339/4072/6545 2341/3365/5640 2340/3364/5639 +f 3609/2687/5612 3596/4294/7000 3607/4336/7184 +f 3216/2919/5173 3208/4374/7185 3206/3015/4383 +f 4306/2086/5691 4307/2980/5227 4325/3452/5740 +f 3913/4340/7072 3915/2051/4392 3914/2291/4608 +f 2176/2591/4872 2177/4153/6907 2520/3993/6434 +f 2266/3851/6214 2317/4305/6980 2318/2528/4821 +f 2178/2933/6375 2612/4154/6667 2181/2913/6373 +f 2021/2643/4584 2026/2667/4584 2000/3750/4585 +f 3939/3014/5354 3931/3976/5355 3933/3012/5355 +f 4366/2603/6991 4355/3694/6027 4365/3901/6574 +f 2915/3515/5808 2633/3330/7038 2926/3535/5832 +f 3851/4375/4554 3886/2789/5778 3884/4096/5778 +f 3219/3718/6057 3300/3717/6056 3299/4163/6687 +f 2235/4376/7186 2236/4377/7187 2233/2294/4611 +f 3928/3494/5783 3927/3345/5783 3825/2652/5783 +f 3999/3089/5000 3966/3942/5000 3998/3522/5000 +f 4059/2770/7188 4163/4135/7188 4164/2580/7188 +f 3530/3536/5835 3548/4065/6528 3549/2719/4988 +f 3966/3942/6348 3967/2270/4586 3965/3822/7189 +f 2466/3025/5278 2411/3398/5679 2410/3395/5676 +f 3810/3113/5370 3781/3555/5860 3782/3554/6241 +f 3601/3044/5297 3599/3766/4524 3600/3468/5757 +f 3346/3404/6918 3426/3876/6250 3344/3405/5685 +f 4235/4062/6523 4236/2190/7033 4253/3926/6524 +f 4338/3540/6645 4337/3613/7190 4310/3419/5701 +f 2968/4197/6746 2965/2609/4889 3076/2611/4891 +f 2315/2996/7191 2573/2677/7191 2528/2676/7191 +f 3571/2462/4764 3468/3697/6844 3545/3537/5837 +f 2520/3993/6434 2478/2275/4592 2176/2591/4872 +f 4186/2832/5091 4203/2831/5090 4201/3109/6153 +f 3274/2137/4465 3312/3921/6310 3313/3887/6266 +f 3948/3811/6185 3960/2251/4571 3962/3909/6814 +f 2021/2643/4920 2036/2355/4668 2037/2644/4921 +f 3539/2960/5207 3521/2586/6729 3519/3974/6398 +f 2858/3997/6440 3035/3039/5292 3033/3998/6441 +f 3091/3943/6350 3187/3837/6201 3186/2791/5052 +f 2855/3971/6395 2887/2860/5117 3035/3039/5292 +f 4235/4062/4517 4229/4303/4517 4198/4331/4517 +f 3267/2180/6749 3266/3051/4351 3234/3018/4351 +f 2827/4030/6475 2855/3971/6395 2856/3973/6397 +f 2135/3378/7192 2134/3377/7193 2140/2408/7194 +f 2275/3438/6158 2274/3437/7195 2197/3802/6159 +f 3921/2372/4686 3892/3911/7196 3893/2373/4687 +f 3338/3814/6175 3413/3813/6174 3444/4329/7052 +f 2724/4373/7183 2725/2752/5020 2729/4013/6458 +f 2972/3896/26 2979/4200/26 2934/4308/26 +f 2574/3747/26 2378/3255/26 2379/4310/26 +f 3420/3577/7197 3343/2020/4366 3419/2019/4365 +f 2698/3648/5967 2076/3177/6431 2695/3338/5607 +f 2287/3632/6824 2281/3816/7198 2286/2358/4671 +f 2884/3738/6083 2882/4130/6628 3015/2994/5243 +f 2960/4323/7044 2175/3521/7043 3009/2727/4996 +f 2148/3040/7199 2151/4330/7056 2488/4312/7005 +f 2289/3426/5709 2290/3827/7144 2284/2736/5004 +f 3959/3733/6978 3958/2253/6978 3956/3429/5712 +f 4151/3033/5285 4061/2771/5034 4154/3031/5283 +f 3521/2586/4388 3486/2902/4388 3519/3974/4388 +f 3010/4360/7118 3009/2727/4996 2175/3521/7043 +f 2175/3521/7043 2144/3266/5535 3010/4360/7118 +f 3303/3844/6206 3305/4145/6648 3304/4157/6671 +f 2294/3819/7200 2285/3633/6823 2284/2736/5004 +f 2821/4369/7171 2909/3990/6428 2818/3111/5368 +f 3063/3640/5954 3005/4254/6865 3006/3036/5289 +f 3677/4070/6543 3594/2768/5032 3676/2510/4805 +f 2956/3556/5861 3076/2611/4891 3077/2775/5038 +f 3397/4111/6983 3395/4257/7201 3412/3298/7202 +f 4177/3086/4924 4178/4370/6680 4172/3087/4924 +f 2994/1981/4332 2141/3376/7203 2139/2407/6780 +f 2137/2710/7204 2136/4259/7205 2135/3378/7192 +f 3749/2131/4458 3748/2550/4841 3750/2132/4459 +f 2579/2553/26 2581/3483/512 2368/2551/26 +f 2518/4047/6504 2514/4268/7206 2515/3582/5893 +f 2953/4165/7172 2954/4117/6610 2952/4208/6762 +f 3371/3028/6408 3373/3030/5821 3352/2656/6406 +f 3491/2105/4435 3494/2107/4436 3493/3336/5605 +f 2548/2328/4642 2549/2925/5177 2550/2326/4640 +f 2560/3077/5332 2561/4179/6713 2330/3076/5331 +f 4184/3422/4517 4183/3712/4517 4190/3461/4517 +f 3913/4340/7072 3914/2291/4608 3821/2540/4831 +f 3202/4194/7207 3088/3180/7207 3090/4253/7207 +f 3863/3189/7006 3838/2232/4785 3861/4247/6937 +f 4128/2566/4852 4116/4191/6875 4127/2444/4748 +f 3308/3643/5959 3305/4145/6648 3210/4146/6649 +f 3157/2248/6685 3083/3054/5310 3194/4240/6846 +f 4071/2430/5533 4072/2429/4735 4091/3591/6771 +f 2896/1971/4324 3024/1970/4323 3026/2455/4757 +f 3039/4025/6469 3047/2692/4960 3046/3035/5288 +f 1999/3749/6099 1998/2379/5342 1997/2255/5342 +f 3649/2302/4619 3636/2133/4460 3650/2100/6342 +f 2726/2345/4657 2656/2347/4659 2655/4152/6663 +f 2771/2574/4859 2784/3371/5647 2801/3373/5649 +f 2651/4378/7208 2650/4093/6575 2845/4094/6576 +f 2240/4004/6447 2216/4304/6979 2438/3252/5519 +f 2567/3314/5582 2325/3933/6332 2324/3237/5504 +f 3045/3037/5290 3006/3036/5289 3005/4254/6865 +f 2753/4076/6549 2754/3756/6107 2751/2702/4971 +f 2424/3149/5410 2431/3151/5412 2426/3400/5681 +f 4022/4283/6930 4025/3258/5522 4024/2262/4582 +f 3520/3734/6490 3543/4133/6632 3542/4040/6491 +f 3444/4329/7052 3413/3813/6174 3414/2197/7209 +f 3282/3810/6170 3325/2827/5086 3298/3932/6330 +f 2306/2572/4857 2309/2641/4918 2538/2570/4855 +f 3333/2230/5878 3335/2773/5878 3334/3512/5878 +f 2586/3866/26 2179/3133/26 2376/4379/26 +f 3639/2599/4524 3621/3565/4524 3619/3916/4524 +f 2559/4003/6446 2523/3420/5702 2525/3660/5980 +f 3710/2246/5358 3706/3839/5358 3707/2247/4567 +f 3078/2725/4994 3022/4363/7133 3019/2726/4995 +f 2545/3698/6031 2544/3684/6011 2491/3387/5665 +f 3410/4086/6564 3443/2900/5152 3409/4333/7058 +f 3596/4294/7000 3609/2687/5612 3597/3340/5611 +f 3001/4284/6931 3052/4170/6698 2924/3580/5891 +f 2228/2494/4791 2229/3894/6272 2230/2333/4647 +f 3504/3722/6486 3503/2047/7210 3505/2614/4895 +f 4340/3541/7160 4338/3540/6645 4311/3951/6644 +f 2374/4174/26 2584/3867/26 2373/4311/26 +f 3900/1992/4342 3831/1991/4341 3899/3403/7211 +f 2259/3776/6125 2205/3775/6124 2264/4342/7212 +f 2296/2961/5208 2193/2963/5210 2192/4280/6923 +f 3872/4365/7213 3833/4192/6741 3841/4237/6839 +f 2217/3850/6213 2218/2982/5229 2239/2983/5230 +f 3949/3703/6264 3968/2243/4563 3950/2242/4562 +f 3232/4148/6652 3260/3145/6514 3230/4147/6650 +f 4125/4098/6900 4126/3362/5637 4108/3361/5636 +f 3208/4374/7185 3209/3939/6119 3206/3015/4383 +f 3200/2680/4731 3201/2679/4731 3204/3855/4731 +f 3404/2162/4491 3432/2808/5067 3403/2883/5138 +f 3953/3702/7214 3979/2480/7215 3982/4231/7216 +f 4144/3074/5329 4145/3635/5948 4137/2177/6673 +f 3041/3795/6148 3039/4025/6469 2870/3796/6149 +f 3879/3842/6204 3907/4341/7122 3880/4066/6532 +f 2414/3603/5910 2412/3242/5509 2413/3244/5511 +f 3402/2885/4755 3368/4319/4755 3400/2936/4755 +f 2064/2759/5024 1973/1962/4315 2065/2653/4928 +f 3641/4032/4524 3612/2686/4524 3610/2688/5462 +f 3552/2461/4763 3467/2208/7076 3468/3697/6844 +f 3887/3402/4554 3856/3588/5778 3888/3411/4554 +f 2922/3500/5789 2923/3138/5399 2921/3499/5788 +f 2430/4354/7106 2431/3151/5412 2112/3160/6995 +f 2966/2781/5042 2958/2783/5044 2965/2609/4889 +f 4256/2027/4371 4255/2598/4879 4261/2028/4372 +f 4236/2190/7033 4252/3927/7217 4253/3926/6524 +f 3118/3701/6427 3121/3875/6449 3119/3532/7218 +f 2095/3178/6531 2097/2712/7219 2096/3692/6529 +f 3174/3021/7220 3140/2069/5798 3144/2068/5923 +f 3427/4178/6709 3430/3296/5562 3344/3405/5685 +f 4299/4016/6935 4390/4260/6878 4389/3215/5481 +f 3687/2624/4905 3684/2976/5223 3685/2099/4430 +f 2298/2734/5002 2296/2961/6511 2288/2735/5003 +f 3884/4096/5778 3853/3285/4554 3851/4375/4554 +f 3235/3017/5956 3233/3019/6493 3223/3641/5957 +f 3174/3021/7220 3154/4273/7221 3140/2069/5798 +f 3155/3509/5799 3156/3673/5997 3142/3508/5797 +f 3398/2514/4755 3364/2513/4808 3399/3347/4755 +f 2047/2612/6503 2046/3572/5880 1965/3739/6084 +f 2004/2184/5121 2003/4067/7222 1982/2866/5122 +f 4239/3230/6065 4258/4053/7223 4269/4075/6548 +f 3125/2216/4538 3123/3171/5431 3104/2795/5433 +f 3328/2672/4383 3326/2039/4383 3330/2041/4383 +f 3271/2004/4351 3270/2893/4351 3238/2930/4351 +f 2522/2276/4593 2521/4056/6517 2500/2654/4929 +f 4109/3148/4367 4108/3361/4367 4100/2744/4367 +f 3664/3898/6280 3680/3897/6279 3679/3217/5483 +f 3850/3808/4554 3886/2789/5778 3851/4375/4554 +f 3875/4057/6518 3891/3318/5586 3890/3320/5588 +f 2186/4078/6551 2293/3424/7224 2292/3423/6183 +f 2497/2026/4370 2486/2277/4594 2522/2276/4593 +f 4373/3862/6274 4296/1978/6169 4379/2522/4815 +f 3253/3102/4351 3255/3065/4351 3265/2034/4351 +f 3377/3339/5609 3375/2666/5608 3374/3029/5281 +f 4017/2817/5076 4037/2819/5078 4036/4367/7158 +f 4290/2809/5068 4384/2714/4983 4383/2761/5026 +f 4000/3471/5760 3990/4005/6450 4001/2279/4596 +f 2140/2408/7194 2137/2710/7204 2135/3378/7192 +f 2170/2947/7225 2645/4160/6682 2644/4380/7226 +f 2924/3580/5891 2926/3535/5832 3001/4284/6931 +f 2130/2802/7139 2451/3292/5558 2132/3291/5557 +f 2277/3800/7227 2265/4008/7134 2271/2483/4782 +f 2016/2493/4585 2017/3273/4585 2011/2062/4585 +f 2101/2299/7228 2102/2010/7229 2100/4381/7230 +f 4246/2607/4887 4231/2767/6467 4234/3236/7231 +f 2845/4094/6576 2652/4155/7232 2651/4378/7208 +f 2061/2536/4829 2060/2928/5180 1961/2534/4827 +f 3990/4005/5001 3983/2732/5001 3981/3451/5001 +f 3948/3811/6185 3965/3822/6184 3949/3703/6264 +f 3839/2231/6262 3863/3189/7006 3865/4261/7233 +f 3806/2245/4565 3807/3246/5513 3710/2246/4566 +f 2410/3395/5676 2411/3398/7234 2404/3397/5868 +f 4245/2849/5105 4279/2850/5106 4260/2966/5213 +f 2485/2310/4627 2484/4324/7045 2535/2311/4628 +f 2395/2713/4982 2077/3223/5490 2383/3360/5634 +f 2821/4369/7171 2819/4299/6971 2907/2074/4410 +f 3098/2426/7235 3203/4193/7236 3204/3855/7235 +f 2660/4382/7237 2849/2871/5127 2664/4383/7238 +f 2906/2075/4411 2665/2440/4744 2661/2076/4412 +f 3080/2774/5037 3019/2726/4995 2822/4345/7083 +f 3454/2594/4875 3573/3547/4875 3577/2595/4875 +f 2901/3313/5581 2900/2516/4809 2899/2476/4775 +f 2488/4312/7005 2490/3386/5664 2489/4275/6912 +f 2127/4113/6606 2124/4034/7239 2123/3608/7240 +f 3113/2319/4635 3116/2263/5964 3114/2630/6534 +f 2451/3292/5558 2476/4176/6707 2468/2799/5059 +f 2259/3776/7241 2264/4342/7074 2251/2747/5015 +f 3224/3642/5958 3237/2398/6600 3235/3017/5956 +f 3530/3536/5835 3511/2523/4816 3531/2394/4706 +f 3183/2695/4963 3097/2425/4965 3184/2153/4481 +f 4176/2779/5040 4178/4370/7173 4278/2780/5041 +f 3413/3813/6949 3395/4257/7201 3396/3045/6950 +f 4229/4303/4517 4196/2582/4517 4198/4331/4517 +f 2905/4306/6986 2729/4013/6458 2727/3625/5940 +f 3675/2445/4749 3673/2637/4915 3674/2576/4861 +f 4109/3148/6901 4110/3147/7242 4123/3882/6996 +f 3166/2193/4519 3167/4074/6547 3152/2194/4520 +f 2718/2660/4932 2716/4384/7243 2715/3135/5396 +f 2181/2913/6908 2519/3865/7244 2520/3993/6434 +f 2401/3526/5820 2399/2797/5057 2468/2799/5059 +f 3985/2731/7035 3982/4231/6807 3983/2732/6917 +f 4090/2021/4684 4091/3591/5899 4092/2089/5898 +f 3587/3769/6785 3592/3705/4434 3594/2768/5032 +f 3360/2723/4755 3392/3449/4755 3394/3368/4808 +f 2010/2060/4398 2012/3962/4399 2013/2061/4399 +f 2636/4385/7245 2641/3984/6416 2637/3678/6094 +f 2854/3083/5338 2680/4108/6595 2681/3299/5565 +f 2099/2077/7246 2100/4381/7230 2098/3693/7246 +f 3348/2657/7062 3357/4335/7247 3359/3969/7176 +f 2430/4354/7106 2429/2078/4414 2381/4219/6784 +f 3817/3941/6347 3917/2292/4609 3918/3319/5587 +f 2029/3619/5933 2057/3417/5699 2059/2929/5181 +f 3008/3231/5499 3003/4220/6789 3002/3232/5500 +f 3492/2106/4388 3490/2847/4388 3522/4055/4388 +f 2715/3135/5396 2817/2990/5239 2718/2660/4932 +f 2005/2186/4516 2002/3334/6539 2003/4067/6541 +f 3716/3114/5371 3796/3903/6289 3715/3908/6296 +f 4350/2419/4422 4336/2638/4422 4339/3498/4422 +f 4027/3553/5857 4025/3258/5522 4028/3638/5952 +f 2387/3165/7065 2302/3594/7248 2588/4082/6555 +f 3083/3054/6864 3086/3053/4731 3084/4023/4731 +f 2842/4089/6569 2749/4088/6568 2747/2728/4997 +f 3594/2768/5032 3677/4070/6543 3586/3409/5692 +f 3713/2862/5942 3715/3908/6296 3717/3626/5941 +f 2460/3857/7249 2459/2826/5085 2463/2093/5670 +f 2428/3243/5510 2417/4226/6797 2430/4354/7106 +f 3760/3760/6111 3776/3759/6110 3775/4134/6633 +f 2519/3865/7244 2518/4047/7250 2520/3993/6434 +f 3347/3007/4755 3352/2656/4755 3355/4279/4755 +f 2492/4278/6916 2493/4277/6915 2151/4330/7056 +f 2234/4318/7018 2235/4376/7186 2233/2294/4611 +f 4206/2211/4534 4187/2210/4533 4188/2121/4450 +f 2170/2947/5193 3012/2949/5195 3005/4254/6865 +f 3094/3209/5476 3177/3211/5478 3198/3328/5597 +f 2423/3606/5913 2421/4048/6506 2422/3150/5411 +f 2126/4337/7251 2118/3343/7140 2432/2411/4720 +f 4030/2082/4418 4031/2081/4417 4029/3205/5472 +f 2062/4173/6703 2061/2536/4829 1966/2535/4828 +f 4185/3421/6152 4186/2832/5091 4201/3109/6153 +f 3101/2388/4406 3100/1966/5056 3107/1965/4406 +f 3847/3103/5359 3846/3105/5360 3848/3889/5359 +f 2090/2888/5141 2093/3260/5525 2091/2887/5140 +f 3099/3179/7001 3097/2425/4965 3182/2696/4964 +f 4272/3222/5489 4273/3935/6338 4274/3067/5322 +f 3202/4194/7207 3203/4193/7207 3088/3180/7207 +f 2687/4132/6631 2767/3647/5966 2768/4213/6770 +f 2383/3360/5634 2415/4271/6898 2395/2713/4982 +f 4222/3413/6855 4192/2084/4420 4223/2083/4419 +f 2145/2721/7131 2143/3267/7252 2614/3959/6377 +f 3711/3853/6217 3799/3198/5465 3800/4186/6720 +f 2008/2155/7082 2007/2185/4515 2006/2865/4515 +f 2473/2986/5235 2470/4353/7105 2430/4354/7106 +f 3718/2911/5165 3758/2163/6316 3727/2909/5163 +f 3856/3588/5896 3857/2314/4631 3855/2030/6786 +f 3878/3187/5453 3893/2373/5452 3892/3911/6300 +f 3397/4111/4755 3377/3339/4808 3395/4257/6869 +f 2318/2528/4821 2317/4305/6980 2570/2632/4911 +f 2014/2492/5932 2018/2269/4893 2047/2612/4892 +f 2782/3612/5919 2743/4043/6495 2694/3989/6425 +f 3165/2839/5095 3166/2193/4519 3151/2192/4518 +f 3707/2247/4567 3701/3838/5358 3703/3864/6229 +f 2153/3514/6403 2631/3977/6402 2632/3331/5600 +f 3703/3864/6229 3805/3770/6117 3707/2247/4567 +f 2657/3122/5380 2656/2347/4659 2830/2346/4658 +f 3916/2403/4715 3918/3319/5587 3917/2292/4609 +f 3028/3393/5674 3029/3100/5357 2891/4011/6456 +f 3840/2178/4554 3834/2380/4554 3836/2031/4554 +f 3921/2372/4686 3920/3457/5746 3892/3911/7196 +f 2421/4048/6506 2423/3606/5913 2449/3310/5578 +f 4273/3935/6338 4276/3066/5321 4274/3067/5322 +f 2638/3614/7253 2639/3154/5415 2159/3153/5414 +f 4382/2762/5027 4291/4250/6858 4290/2809/5068 +f 3324/3986/6419 3322/3831/6195 3323/4314/7012 +f 3206/3015/6535 3326/2039/6535 3328/2672/6535 +f 2415/4271/6898 2414/3603/5910 2381/4219/6784 +f 3501/2697/4967 3503/2047/7210 3502/3765/7254 +f 4164/2580/4409 4163/4135/4409 4161/4136/4409 +f 3990/4005/5001 3981/3451/5001 3991/2280/5000 +f 4159/3690/6021 4065/2071/4407 4160/4288/6943 +f 3527/2298/4615 3564/3905/6292 3526/2916/5170 +f 2127/4113/6606 2128/4112/6605 2124/4034/7239 +f 3901/3746/6750 3884/4096/6581 3902/3055/5311 +f 2902/2049/4390 2910/2048/4389 3013/4223/6792 +f 2362/4175/26 2365/4346/26 2587/2448/26 +f 3343/2020/4626 3333/2230/5878 3340/2096/4626 +f 2551/2327/4641 2552/2392/4704 2548/2328/4642 +f 3488/2489/4388 3523/2585/4388 3490/2847/4388 +f 2867/4123/6617 2865/4119/6612 2868/4120/6613 +f 2491/3387/5665 2543/3685/6012 2542/3388/5666 +f 3118/3701/6427 3120/3172/6035 3121/3875/6449 +f 2686/2953/5200 2818/3111/5368 2730/2954/5201 +f 3365/2855/5112 3350/4029/6473 3349/2655/5601 +f 2019/2613/7004 2024/4282/7153 2046/3572/5880 +f 3017/3807/6166 3016/4187/6722 3005/4254/6865 +f 4025/3258/5522 4010/3091/5347 4011/3090/5951 +f 2259/3776/7241 2251/2747/5015 2258/3777/6337 +f 3963/3823/6299 3966/3942/6348 3965/3822/7189 +f 3399/3347/4755 3362/2724/4755 3393/3346/4808 +f 3168/3602/5908 3169/2857/5114 3150/2265/5909 +f 2405/3845/6208 2464/2449/6207 2462/3390/7255 +f 2119/3607/5914 2124/4034/7256 2123/3608/5915 +f 3978/2478/5000 3976/4127/5000 3995/2889/5000 +f 4116/4191/4367 4114/4143/5277 4092/2089/4367 +f 3406/4020/6463 3390/3907/6295 3391/4202/6756 +f 4119/2012/4358 4131/2881/5136 4120/2022/5135 +f 3733/3134/6367 3732/2754/7145 3734/2753/6365 +f 2521/4056/6517 2501/4149/6658 2500/2654/4929 +f 3624/3195/7257 3622/3567/7258 3621/3565/5869 +f 2380/3605/5912 2438/3252/5519 2412/3242/5509 +f 2136/4259/7259 2141/3376/7040 2995/3753/6103 +f 1977/3728/4585 1984/3224/4585 1980/2256/4585 +f 3567/2167/4496 3463/2349/4661 3566/2348/4660 +f 2946/3772/26 2945/4239/26 2930/3585/26 +f 2406/2399/4711 2459/2826/5085 2465/2400/4712 +f 2047/2612/6503 1965/3739/6084 2055/3919/6308 +f 3724/3129/5388 3751/2467/6701 3725/4110/6603 +f 3670/2577/4862 3672/2509/4804 3671/4368/7167 +f 1972/3467/7260 2072/2508/7260 2073/4328/7260 +f 3711/3853/6217 3800/4186/6720 3712/3472/5761 +f 3759/2165/4336 3756/4245/4336 3763/3721/4336 +f 3554/3505/5794 3537/3621/5935 3555/3116/5374 +f 3784/2908/5162 3773/2056/6654 3774/2906/5160 +f 3208/4374/7185 3216/2919/5173 3315/4347/7085 +f 2112/3160/6995 2473/2986/5235 2430/4354/7106 +f 3769/4069/4336 3748/2550/4336 3770/2223/4337 +f 3481/3736/7261 3470/2554/4842 3479/3761/7143 +f 2252/3311/5579 2269/3788/6902 2254/3783/7262 +f 3882/2413/4722 3895/2946/5192 3894/2371/4685 +f 2899/2476/4775 2912/2475/4774 2911/3312/5580 +f 4390/4260/6878 4364/3213/5479 4389/3215/5481 +f 4008/3874/6294 4047/2127/4454 4007/3872/7263 +f 4321/3349/6538 4318/3348/6483 4319/3058/7159 +f 3048/3436/5722 3065/3446/5735 3079/3435/5721 +f 4196/2582/4865 4195/2584/4867 4197/3425/7117 +f 4320/2951/6536 4322/2950/7178 4323/3288/6537 +f 3349/2655/5601 3361/2722/7063 3363/3332/5602 +f 3723/3130/4336 3719/1986/4336 3721/1985/4336 +f 3258/4229/6802 3256/3618/5929 3257/2841/5928 +f 2577/3352/5624 2139/2407/7264 2457/3119/6798 +f 2382/3477/5767 2462/3390/5669 2406/2399/4711 +f 4314/2122/6725 4344/2123/7265 4312/4188/6723 +f 3775/4134/6633 3791/4140/6641 3761/4142/6643 +f 2078/2740/7266 2604/3992/7267 2605/3946/6353 +f 2991/4207/6761 2992/2975/6772 3000/4218/6779 +f 3316/4248/6856 3318/4235/6834 3317/2220/4543 +f 3568/2168/4497 3569/2717/4986 3570/2166/4495 +f 3945/2260/4580 3935/3060/5354 3936/2128/4455 +f 2646/4351/7092 2168/2588/6082 3015/2994/5243 +f 4072/2429/4735 4093/3487/7268 4091/3591/6771 +f 2153/3514/5807 2633/3330/7038 2915/3515/5808 +f 3301/3719/6058 3296/2290/4607 3284/3900/6282 +f 3043/4181/6715 3055/2693/4961 3047/2692/4960 +f 2623/3279/6385 2624/3963/6384 2622/3964/6387 +f 2143/3267/5536 2916/3170/5430 3011/3268/5537 +f 3215/3630/6119 3218/3843/6205 3214/3034/5286 +f 2323/3652/5971 2568/4232/6826 2319/4313/7010 +f 2064/2759/5024 2063/4150/6660 1973/1962/4315 +f 3040/3317/5585 3045/3037/5290 3042/2343/4655 +f 3044/2527/4820 3008/3231/5499 3043/4181/6715 +f 3294/4286/6934 3290/2625/4906 3309/4316/7013 +f 3780/2222/4545 3768/4144/7269 3769/4069/7095 +f 3134/2485/7087 3137/3904/6928 3135/3158/7087 +f 4030/2082/4418 4026/3204/5471 4027/3553/5857 +f 2748/2729/4998 2747/2728/4997 2749/4088/6568 +f 4121/2816/5075 4138/3576/5885 4146/3636/5949 +f 2214/3004/5254 2215/3006/5256 2213/4189/6731 +f 2916/3170/5430 2145/2721/5864 2615/3958/7270 +f 3833/4192/6741 3872/4365/7213 3842/2396/6739 +f 3934/3854/6218 3932/2325/5354 3937/4355/7107 +f 3161/3379/5655 3178/4325/7050 3198/3328/5597 +f 4288/4168/6774 4295/4167/6825 4298/2810/6825 +f 2550/2326/4640 2536/2675/4944 2573/2677/4946 +f 3381/2451/5595 3382/2043/6314 3380/2042/5595 +f 3743/3185/5450 3722/3183/5447 3741/3511/6820 +f 3670/2577/4862 3593/3706/6041 3693/3667/5989 +f 2294/3819/6180 2293/3424/7224 2186/4078/6551 +f 2117/3344/7066 2126/4337/7067 2125/4114/6607 +f 3537/3621/6810 3523/2585/6728 3538/3622/5936 +f 3041/3795/6148 3043/4181/6715 3047/2692/4960 +f 2182/3520/5813 2176/2591/4872 2487/2590/4871 +f 2327/3937/6340 2561/4179/6713 2563/2339/4651 +f 2776/2037/4381 2796/4041/6492 2763/3686/6013 +f 4077/2065/5250 4076/2837/5251 4075/3391/6948 +f 3874/3431/5716 3887/3402/5683 3898/3401/5682 +f 2760/2463/4765 2761/2038/4382 2763/3686/6013 +f 3795/2794/5055 3785/2907/5161 3798/2792/5053 +f 3824/1983/4334 3923/3142/5404 3924/3988/6424 +f 4141/3278/5546 4134/2874/5545 4133/3478/6479 +f 3200/2680/7271 3090/4253/7271 3084/4023/7271 +f 2515/3582/5893 2517/3584/5895 2508/3190/5457 +f 3764/4141/7272 3790/4386/7273 3765/2755/6371 +f 3904/2629/4910 3911/2628/4909 3903/2788/6727 +f 3492/2106/4388 3516/2144/4388 3494/2107/4388 +f 2316/3617/5927 2314/2997/5246 2357/4079/6552 +f 3814/2864/7274 3706/3839/7274 3705/4315/7274 +f 3352/2656/6406 3373/3030/5821 3353/2665/4934 +f 2604/3992/7267 2603/3947/6354 2605/3946/6353 +f 2750/1968/4321 2733/2560/4848 2844/4366/7154 +f 4128/2566/4852 4159/3690/6021 4160/4288/6943 +f 3895/2946/6655 3883/3950/6657 3896/2706/4975 +f 4115/2013/4359 4114/4143/7275 4128/2566/4852 +f 3572/2337/4532 3577/2595/4532 3573/3547/4531 +f 3356/2237/5259 3357/4335/7247 3347/3007/5257 +f 3129/3146/5409 3126/3672/5995 3127/2215/5407 +f 2959/4362/7168 2957/3892/6270 2958/2783/5044 +f 3388/3448/4755 3385/3491/4755 3390/3907/4755 +f 3098/2426/7235 3088/3180/7236 3203/4193/7236 +f 2043/2945/5191 2051/3895/6273 2050/3444/5733 +f 2746/2473/4772 2841/4087/6567 2840/3610/5917 +f 3690/3434/5719 3691/3308/5576 3692/4264/6886 +f 2812/2786/5047 2813/3881/6255 2807/3620/5934 +f 3513/3168/4388 3505/2614/4387 3503/2047/4388 +f 3460/2214/4532 3466/2209/4532 3464/2546/4838 +f 3278/2116/4445 3217/2218/4540 3279/3080/5335 +f 2079/2741/7276 2075/3682/7277 2076/3177/7278 +f 4342/4121/4422 4345/3830/4422 4346/3829/6361 +f 2877/2342/4654 2876/3924/6320 2875/4126/6622 +f 4161/4136/4683 4054/2769/7279 4055/3744/4683 +f 2809/2140/4468 2993/4122/7148 2988/2784/5045 +f 2816/3868/6237 2811/2139/4467 2803/3869/6238 +f 4345/3830/6194 4348/4216/6985 4360/2716/4985 +f 2328/3983/6415 2216/4304/6979 2358/1975/4328 +f 3419/2019/4365 3424/3295/5561 3418/2937/5185 +f 3084/4023/4731 3090/4253/6864 3093/3406/5686 +f 3935/3060/6803 3944/3590/6803 4052/3592/6803 +f 2576/4246/26 2375/4289/26 2372/4269/26 +f 2484/4324/7045 2485/2310/4627 2486/2277/4594 +f 3222/3225/5491 3230/4147/7127 3259/3226/5492 +f 2250/2923/5175 2266/3851/6214 2268/2924/5176 +f 2150/3282/5988 2494/3666/5987 2151/4330/7056 +f 3633/2999/5248 3648/2304/4621 3647/3000/5249 +f 2042/3669/5991 2043/2945/5191 2025/2944/5190 +f 2495/2926/5178 2496/4350/7090 2487/2590/4871 +f 2660/4382/7237 2659/3220/5486 2849/2871/5127 +f 3082/2685/4953 2600/2683/6621 2107/2985/7280 +f 3209/3939/7084 3208/4374/7185 3311/3920/6309 +f 3666/2998/6913 3647/3000/5574 3582/2548/5573 +f 2542/3388/5666 2558/4037/6487 2559/4003/6446 +f 2143/3267/7252 2142/4371/7281 2614/3959/6377 +f 2221/2495/4792 2220/4387/7282 2223/4364/7146 +f 2106/3793/7283 2105/2335/4649 2107/2985/7284 +f 2160/3658/6095 2638/3614/7253 2159/3153/5414 +f 4367/2206/4530 4366/2603/4884 4376/2602/4883 +f 2786/4251/6861 2787/2669/4940 2791/2877/5133 +f 2507/3743/6088 2508/3190/5457 2480/3676/6000 +f 3025/2405/4717 3026/2455/4757 3079/3435/5721 +f 2475/4209/6765 2454/3117/5375 2451/3292/5558 +f 3816/4217/6776 3713/2862/6777 3708/3627/6776 +f 3286/2147/4475 3295/2149/4477 3302/2289/4606 +f 3608/2200/6286 3610/2688/4956 3609/2687/4956 +f 2083/2274/4591 2603/3947/6432 2699/2272/4589 +f 2307/3987/7285 2479/2571/7130 2588/4082/6555 +f 4189/2351/4517 4188/2121/4517 4186/2832/4517 +f 4281/3043/5296 4182/3088/5661 4247/2765/7165 +f 4161/4136/4683 4055/3744/4683 4162/3416/4683 +f 4380/2521/4814 4381/2520/4813 4383/2761/5026 +f 3452/2681/4948 3565/2297/4614 3461/2350/4662 +f 2995/3753/6103 2999/3752/6102 2136/4259/7259 +f 4140/3321/5590 4063/4244/6857 4131/2881/6945 +f 3688/2596/4877 3589/3323/6507 3588/3863/6228 +f 4041/3562/5865 4042/3563/5866 3941/3757/6108 +f 3809/3952/6362 3714/3112/5369 3709/3645/5961 +f 2200/3662/5983 2278/2530/5340 2201/3084/5339 +f 2555/3139/5401 2546/3533/5829 2554/3315/5583 +f 4228/3596/4517 4224/3229/4517 4194/2085/4517 +f 2951/4201/6755 2985/4166/6692 2953/4165/6691 +f 3031/3479/5769 3071/4106/6593 3036/2859/5116 +f 3934/3854/7157 4035/3914/6303 4036/4367/7158 +f 2951/4201/6764 2953/4165/7172 2952/4208/6762 +f 3643/3649/4524 3612/2686/4524 3641/4032/4524 +f 2265/4008/7134 2267/3791/7286 2266/3851/6214 +f 3941/3757/5355 3931/3976/5355 3939/3014/5354 +f 3678/3216/5482 3681/3218/5484 3590/3639/5953 +f 4117/2875/4367 4113/2468/4367 4082/2364/4367 +f 4366/2603/6991 4354/2205/4529 4355/3694/6027 +f 2897/2477/4776 2896/1971/4324 2850/2805/5065 +f 2890/2957/5204 3029/3100/5357 3032/3099/5356 +f 2243/3049/5304 2440/4238/6841 2439/3251/5518 +f 2488/4312/7005 2151/4330/7056 2491/3387/5665 +f 3585/2173/4434 3589/3323/4434 3583/2174/4434 +f 2518/4047/6999 2576/4246/6853 2575/4267/6891 +f 2391/4019/6461 2435/3956/6369 2434/3518/5811 +f 2447/4195/6744 2247/3653/5972 2249/3302/5568 +f 4234/3236/4517 4231/2767/5503 4207/2846/5503 +f 2240/4004/6447 2438/3252/5519 2380/3605/5912 +f 2793/2878/5134 2788/2668/4939 2789/2690/4958 +f 2425/2091/4424 2423/3606/5913 2424/3149/5410 +f 2990/4164/6688 2983/4058/6782 2946/3772/6120 +f 4255/2598/4879 4254/4061/6522 4262/2597/4878 +f 2009/3275/4585 2011/2062/4585 2017/3273/4585 +f 3490/2847/5104 3492/2106/4435 3491/2105/4435 +f 3581/2104/7019 3682/3306/5572 3683/2303/4620 +f 3459/3758/6109 3460/2214/4532 3464/2546/4838 +f 2545/3698/6031 2493/4277/6915 2546/3533/5829 +f 2273/2482/4781 2274/3437/5723 2271/2483/4782 +f 3995/2889/5142 3996/4266/7003 4005/3439/5725 +f 2615/3958/7270 2617/3169/5428 2916/3170/5430 +f 2407/2401/4713 2465/2400/4712 2466/3025/5278 +f 2085/2844/5100 2083/2274/7181 2087/2842/5098 +f 4264/3305/5571 4179/2880/6778 4266/3954/6364 +f 2969/3558/5863 3076/2611/4891 2956/3556/5861 +f 3852/3286/5553 3851/4375/7287 3853/3285/5551 +f 4142/4033/6481 4062/3073/5328 4143/3075/5330 +f 2971/2934/26 2972/3896/26 2933/2969/26 +f 3988/4356/5000 3957/3428/5000 3985/2731/5000 +f 2784/3371/5647 2771/2574/4859 2769/3072/5327 +f 2045/3573/7142 2046/3572/5880 2024/4282/7153 +f 2132/3291/6873 2129/2801/5061 2131/2709/7288 +f 2927/3516/5809 2915/3515/5808 2926/3535/5832 +f 3298/3932/6330 3299/4163/6687 3297/3930/6328 +f 2350/2259/4579 2168/2588/6247 2526/3767/6115 +f 3244/2623/4351 3272/4281/4351 3242/2159/4351 +f 3849/3809/6423 3852/3286/6496 3835/2381/6421 +f 2174/4161/6683 2643/4091/6571 2173/4162/6684 +f 3449/4334/7101 3448/4236/7101 3339/2002/7101 +f 2470/4353/7105 2472/4388/7289 2471/2079/4415 +f 2696/2428/4734 2097/2712/6073 2099/2077/4732 +f 3831/1991/4690 3823/2649/4688 3824/1983/4688 +f 2605/3946/6353 2079/2741/7290 2078/2740/7266 +f 2366/4290/26 2369/4389/26 2582/2095/512 +f 2432/2411/4720 2121/2410/4719 2119/3607/7291 +f 3814/2864/7274 3813/3212/7274 3706/3839/7274 +f 2388/3166/5424 2387/3165/5423 2386/2450/6748 +f 4106/4296/4367 4110/3147/4367 4105/2836/4367 +f 4290/2809/5068 4386/2811/5070 4361/3057/5313 +f 4230/3595/6872 4229/4303/6976 4255/2598/4879 +f 2044/3094/5350 2043/2945/5191 2050/3444/5733 +f 4303/3276/5542 4312/4188/7292 4343/4357/7161 +f 2566/3735/6076 2320/2704/4973 2325/3933/6332 +f 3728/3938/6341 3730/4180/6821 3729/2910/6821 +f 4218/3637/5950 4219/3272/6695 4220/3940/6346 +f 2720/3024/5275 2715/3135/5396 2132/3291/7129 +f 4015/3009/5261 4034/3913/6302 4032/3008/5260 +f 4152/3032/5284 4150/2368/4681 4151/3033/5285 +f 2154/4301/6973 2153/3514/7138 2489/4275/6912 +f 2858/3997/6440 2855/3971/6395 3035/3039/5292 +f 3589/3323/6507 3690/3434/5719 3584/3322/7081 +f 4317/4036/7121 4315/4035/6653 4304/2088/5543 +f 4250/2852/5108 4237/2853/5110 4249/3384/5839 +f 4010/3091/5347 4019/4252/6862 4009/3646/5962 +f 3035/3039/5292 3073/3433/5718 3033/3998/6441 +f 3096/2424/6160 3185/2154/4482 3184/2153/4481 +f 3173/3615/5925 3174/3021/7220 3144/2068/5923 +f 2241/3495/5784 2437/3604/5911 2239/2983/5230 +f 3397/4111/6983 3410/4086/6982 3389/2453/6997 +f 1982/2866/5122 2003/4067/7222 2001/3650/5969 +f 2442/3175/5436 2244/3048/5303 2245/3412/5696 +f 1964/3740/6085 1961/2534/4827 2060/2928/5180 +f 2128/4112/6605 2125/4114/6607 2126/4337/7067 +f 3001/4284/6931 2161/3657/7293 2642/3805/6164 +f 2094/2914/5527 2607/2886/5139 2608/4265/6887 +f 4229/4303/4517 4230/3595/4517 4196/2582/4517 +f 3472/3687/6015 3487/2490/6927 3489/2848/6014 +f 3946/3510/5000 3949/3703/5000 3954/4071/5000 +f 4139/2443/4747 4158/2442/4746 4159/3690/6021 +f 3650/2100/4431 3685/2099/4430 3649/2302/4619 +f 3943/3203/5470 4032/3008/5260 4033/3915/6304 +f 2249/3302/5568 2247/3653/5972 2266/3851/6214 +f 4296/1978/6169 4294/1977/6030 4379/2522/4815 +f 3018/3806/6165 2174/4161/6721 3017/3807/6166 +f 2625/3115/6386 2147/2227/4550 2624/3963/6384 +f 3721/1985/5448 3736/2067/4404 3738/2437/5449 +f 4037/2819/5078 3933/3012/5265 3934/3854/7157 +f 4279/2850/5106 4178/4370/7173 4177/3086/6710 +f 2709/3784/6135 2810/2138/4466 2808/2504/4801 +f 3095/2790/4731 3092/3542/4731 3091/3943/4731 +f 3483/2555/4843 3470/2554/4842 3481/3736/7261 +f 4171/3936/6339 4176/2779/5040 4276/3066/5321 +f 2054/3445/5734 1974/3466/5755 1971/3465/5882 +f 2979/4200/26 2980/4199/26 2935/4027/512 +f 4070/2431/5737 4086/4274/6904 4084/3010/6812 +f 2304/3503/5792 2303/3164/5422 2214/3004/5254 +f 3406/4020/6463 3391/4202/6756 3407/3097/5353 +f 4174/4159/5364 4282/3711/5364 4284/4297/7294 +f 3607/4336/7184 3596/4294/7000 3605/2737/5005 +f 4053/2323/4639 3932/2325/4639 4049/4390/4639 +f 2052/2109/4438 2039/2108/4437 2038/2645/5855 +f 3826/2984/5231 3930/4391/5231 3929/2651/5232 +f 3937/4355/7107 4033/3915/6304 4035/3914/6303 +f 2377/4392/26 2575/4267/26 2372/4269/26 +f 3904/2629/7295 3903/2788/5049 3885/2787/5048 +f 2106/3793/6705 2107/2985/7296 2600/2683/4950 +f 2897/2477/4776 2898/1972/4325 2896/1971/4324 +f 2460/3857/7249 2461/3482/6664 2459/2826/5085 +f 2521/4056/6517 2518/4047/6504 2503/3574/5883 +f 3653/2151/4479 3640/2150/4478 3654/3309/7297 +f 2009/3275/7082 2010/2060/4398 2011/2062/4398 +f 3939/3014/5267 4040/3013/5266 4041/3562/5865 +f 2402/4343/7075 2400/2798/5058 2403/3564/5867 +f 3456/3917/6306 3562/2114/4443 3455/4393/7298 +f 3512/3167/4387 3508/2383/4388 3505/2614/4387 +f 3059/2126/4453 3067/2125/4452 3066/3392/5673 +f 3189/3022/5273 3087/4137/6946 3191/3817/6178 +f 1975/2239/4561 1974/3466/5755 2053/3741/6086 +f 3648/2304/4621 3683/2303/4620 3682/3306/5572 +f 2961/2912/5166 2177/4153/7042 3020/4021/6464 +f 3885/2787/5048 3905/2305/6533 3904/2629/7295 +f 2400/2798/5058 2399/2797/5057 2403/3564/5867 +f 3260/3145/4351 3232/4148/4351 3266/3051/4351 +f 4305/2087/5198 4319/3058/5314 4317/4036/7121 +f 2077/3223/6009 2076/3177/7174 2075/3682/6007 +f 3247/3699/6033 3248/3193/5460 3249/3194/5461 +f 4228/3596/6860 4230/3595/6872 4256/2027/6871 +f 3479/3761/7143 3469/2939/7078 3477/3762/7080 +f 2251/2747/5015 2263/3430/6462 2396/3551/5854 +f 3617/2432/4524 3616/2563/4524 3645/4012/4524 +f 3323/4314/7012 3321/3507/5796 3212/3506/5795 +f 2298/2734/5002 2389/3955/6368 2295/2962/6510 +f 2503/3574/5883 2507/3743/6088 2483/3513/5806 +f 3817/3941/6347 3818/2376/4690 3820/2375/4689 +f 2261/3207/5474 2264/4342/7212 2211/3208/5475 +f 2637/3678/6003 2161/3657/7293 2926/3535/5832 +f 3642/4230/5462 3608/2200/4524 3638/2199/4524 +f 2773/3235/5502 2774/3530/5828 2775/4302/6975 +f 4109/3148/6901 4125/4098/6900 4108/3361/5636 +f 2565/3238/5505 2567/3314/5582 2324/3237/5504 +f 3320/2118/4447 3319/2217/4539 3278/2116/4445 +f 2922/3500/5789 2925/3878/6252 3054/3949/6356 +f 2423/3606/5913 2425/2091/4424 2447/4195/6744 +f 2496/4350/7090 2495/2926/5178 2549/2925/5177 +f 2389/3955/6368 2391/4019/6461 2392/4327/7299 +f 2392/4327/7299 2384/3836/7077 2389/3955/6368 +f 4036/4367/7158 4034/3913/6302 4017/2817/5076 +f 2630/4204/6758 2148/3040/5874 2628/3569/5876 +f 2254/3783/7262 2255/3781/7300 2251/2747/5015 +f 2197/3802/6159 2273/2482/6162 2198/3803/6161 +f 2057/3417/5699 2058/2927/5179 2059/2929/5181 +f 2584/3867/26 2583/3748/26 2373/4311/26 +f 3704/3474/5763 3803/3262/5528 3703/3864/6229 +f 3761/4142/4336 3728/3938/4337 3760/3760/4336 +f 2719/2659/4931 2590/3493/5782 2718/2660/4932 +f 2418/3249/5516 2419/3120/5378 2425/2091/4424 +f 4014/2080/7177 4013/3628/6885 3997/3440/5726 +f 2950/3858/6221 2906/2075/4411 2903/3375/5651 +f 3356/2237/4559 3358/4185/7046 3357/4335/7064 +f 4360/2716/4985 4375/1994/4344 4384/2714/4983 +f 4240/3125/5852 4270/3723/6064 4272/3222/5489 +f 2432/2411/4720 2431/3151/5412 2422/3150/5411 +f 2319/4313/7010 2568/4232/6826 2571/2390/4702 +f 2854/3083/5338 2888/3481/5771 2826/4107/6594 +f 2775/4302/6975 2734/4234/6833 2735/2561/4849 +f 4395/2979/6693 4288/4168/6694 4393/2661/7301 +f 2385/3846/6209 2305/3005/5255 2388/3166/5424 +f 3583/2174/4434 3593/3706/6041 3592/3705/4434 +f 4384/2714/4983 4290/2809/5068 4385/2715/4984 +f 3243/2183/4904 3242/2159/4487 3241/2158/4487 +f 4389/3215/5481 4298/2810/5069 4299/4016/6935 +f 2664/4383/7238 2849/2871/5127 2663/2870/5126 +f 2835/4263/6883 2755/2701/4970 2836/2700/4969 +f 2179/3133/6742 2180/2501/7302 2963/2500/6566 +f 2720/3024/5275 2803/3869/6238 2721/4038/6488 +f 2716/4384/7243 2130/2802/7128 2715/3135/5396 +f 2263/3430/6462 2390/3745/7303 2391/4019/6461 +f 2124/4034/6482 2119/3607/7022 2718/2660/4932 +f 3716/3114/5371 3705/4315/5358 3714/3112/5358 +f 3537/3621/6810 3536/2460/7096 3522/4055/6811 +f 2687/4132/6631 2688/2143/4471 2798/3143/5405 +f 2563/2339/4651 2561/4179/6713 2557/4039/6489 +f 2799/2142/4470 2798/3143/5405 2688/2143/4471 +f 2053/3741/6086 2050/3444/5733 2051/3895/6273 +f 3785/2907/5161 3795/2794/5055 3784/2908/5162 +f 2513/3191/5458 2508/3190/5457 2517/3584/5895 +f 3875/4057/4554 3873/2397/4554 3870/1999/4554 +f 3613/2562/4850 3614/4064/4850 3616/2563/4851 +f 2926/3535/5832 2638/3614/5922 2160/3658/6002 +f 3011/3268/5537 2917/3063/5319 2913/3280/5548 +f 3622/3567/7258 3624/3195/7257 3623/3469/6956 +f 2612/4154/7304 2142/4371/7304 2175/3521/7304 +f 4172/3087/7305 4286/2568/7305 4181/2879/7305 +f 4049/4390/5354 4052/3592/5354 4053/2323/5354 +f 3716/3114/5371 3715/3908/6296 3713/2862/5942 +f 3945/2260/4580 4021/3944/6351 4023/2261/4581 +f 3885/2787/4554 3848/3889/4554 3880/4066/4554 +f 2900/2516/4809 2901/3313/5581 3024/1970/4323 +f 3083/3054/5310 3093/3406/5686 3194/4240/6846 +f 3719/1986/4336 3723/3130/4336 3718/2911/4336 +f 3909/2052/4393 3915/2051/4392 3908/3841/7071 +f 3272/4281/6926 3282/3810/6925 3283/3931/6909 +f 3673/2637/4915 3672/2509/4804 3670/2577/4862 +f 2435/3956/6369 2403/3564/5867 2399/2797/5057 +f 2955/4118/6611 3074/4255/6866 2954/4117/6610 +f 2402/4343/7075 2403/3564/5867 2404/3397/5868 +f 2358/1975/4328 2330/3076/5331 2328/3983/6415 +f 2474/4332/7057 2475/4209/6765 2451/3292/5558 +f 3418/2937/5185 3425/3716/6055 3417/2935/5183 +f 2787/2669/4940 2786/4251/6861 2690/3980/6409 +f 2321/2705/4974 2322/3731/6075 2248/3651/5970 +f 3679/3217/5483 3663/3410/5693 3664/3898/6280 +f 3317/2220/4543 3320/2118/4447 3276/2035/4541 +f 3309/4316/7013 3310/4285/6933 3294/4286/6934 +f 4297/4249/7112 4397/2663/7112 4398/4359/7112 +f 2986/3587/26 2947/3773/26 2930/3585/26 +f 2639/3154/5415 2158/3534/6411 2157/3152/5413 +f 4232/2606/5503 4233/2608/4517 4211/3456/5503 +f 2106/3793/7283 2104/2009/4355 2105/2335/4649 +f 2750/1968/4321 2737/1967/4320 2735/2561/4849 +f 2621/3695/7132 2623/3279/6385 2622/3964/6387 +f 3092/3542/4731 3085/2678/4731 3091/3943/4731 +f 4357/2940/4422 4356/2942/4422 4321/3349/4422 +f 3614/4064/4524 3646/3265/4524 3616/2563/4524 +f 3426/3876/6250 3428/2867/5123 3427/4178/6709 +f 2786/4251/6861 2785/2141/4469 2800/2636/4914 +f 1965/3739/6084 2046/3572/5880 1971/3465/5882 +f 3633/2999/5248 3666/2998/5247 3637/3131/5392 +f 2332/4007/6451 2335/2284/4601 2336/4394/7306 +f 2487/2590/4871 2494/3666/5987 2147/2227/7307 +f 2141/3376/7308 2137/2710/7309 2140/2408/7308 +f 2174/4161/6721 2645/4160/7136 3016/4187/6722 +f 3878/3187/5453 3891/3318/5586 3875/4057/6518 +f 2030/3994/6435 2059/2929/5181 2062/4173/6703 +f 1970/1963/4316 1968/2241/4316 1969/1961/4314 +f 3017/3807/6166 3063/3640/5954 3001/4284/6931 +f 2528/2676/4945 2532/4158/6674 2312/2748/5016 +f 3306/3644/5960 3289/2626/4907 3288/2179/6672 +f 3347/3007/5257 3357/4335/7247 3348/2657/7062 +f 3392/3449/4755 3358/4185/4755 3388/3448/4755 +f 2239/2983/5230 2238/2293/4610 2237/2295/4612 +f 3119/3532/7218 3117/2264/5963 3118/3701/6427 +f 4065/2071/4407 4157/4097/6582 4156/3196/5463 +f 2646/4351/7310 2647/4291/6951 2649/2589/4870 +f 4062/3073/5328 4057/3575/5884 4144/3074/5329 +f 2528/2676/4945 2536/2675/4944 2537/3247/5514 +f 3833/4192/4554 3840/2178/4554 3841/4237/5778 +f 2105/2335/5234 2103/2011/4616 2472/4388/7289 +f 2121/2410/7023 2130/2802/7128 2716/4384/7243 +f 3549/2719/4988 3529/2718/4987 3530/3536/5835 +f 2962/2782/5043 2966/2781/5042 2967/3460/5749 +f 2101/2299/7228 2103/2011/7311 2102/2010/7229 +f 4369/3201/5468 4358/2204/4528 4368/3287/5555 +f 2882/4130/6628 2884/3738/6083 2164/4109/6597 +f 4125/4098/6583 4124/4272/7312 4153/4171/6699 +f 3768/4144/4336 3752/2130/4336 3750/2132/4336 +f 2846/3888/6267 2654/4095/6578 2653/4395/7313 +f 3062/3136/5397 3072/3489/5779 3071/4106/6593 +f 3925/2499/4688 3930/4391/4688 3926/3546/4688 +f 3648/2304/4621 3635/2806/5671 3649/2302/4619 +f 2655/4152/6663 2654/4095/6578 2847/2497/4794 +f 3414/2197/7209 3445/3877/6251 3444/4329/7052 +f 2469/4214/6773 2468/2799/5059 2476/4176/6707 +f 3820/2375/4689 3917/2292/4609 3817/3941/6347 +f 2455/3353/5626 2452/3227/5494 2578/4320/7031 +f 4356/2942/4422 4353/3861/4422 4318/3348/4422 +f 3210/4146/6649 3209/3939/7084 3308/3643/5959 +f 2076/3177/6431 2074/3176/6719 2695/3338/5607 +f 3681/3218/5484 3680/3897/6279 3666/2998/6913 +f 4292/2604/4885 4302/2201/4525 4376/2602/4883 +f 4180/2891/5144 4173/3307/5575 4267/3953/6363 +f 2560/3077/5332 2523/3420/5702 2559/4003/6446 +f 4354/2205/4422 4328/3549/4422 4330/3357/6361 +f 4274/3067/5322 4242/2992/5241 4241/3126/5488 +f 3249/3194/6749 3269/3079/4351 3246/2622/4351 +f 2467/4210/6766 2475/4209/6765 2474/4332/7057 +f 3776/3759/6110 3763/3721/6060 3777/3720/6059 +f 3171/3599/6813 3172/3689/6020 3149/2631/5924 +f 3988/4356/5000 3985/2731/5000 3987/2733/5000 +f 4397/2663/7169 4300/4358/7169 4293/4015/7169 +f 3371/3028/5280 3370/2884/6390 3372/2931/5280 +f 3849/3809/6168 3851/4375/7287 3852/3286/5553 +f 2577/3352/512 2578/4320/26 2363/4326/26 +f 3365/2855/6838 3368/4319/7029 3367/2856/7029 +f 3658/2446/4750 3645/4012/6457 3646/3265/5531 +f 3504/3722/6486 3502/3765/7254 3503/2047/7210 +f 2083/2274/7314 2611/2273/7315 2610/3934/6334 +f 2811/2139/4467 2810/2138/4466 2804/4243/6851 +f 3900/1992/5694 3899/3403/5684 3887/3402/5683 +f 2128/4112/7316 2126/4337/7251 2119/3607/7291 +f 2112/3160/6995 2432/2411/4720 2114/3161/7317 +f 2967/3460/5749 2966/2781/5042 2965/2609/4889 +f 3350/4029/4755 3352/2656/4755 3349/2655/4755 +f 3398/2514/5888 3419/2019/4365 3418/2937/5185 +f 2793/2878/5134 2794/3671/5993 2792/2423/4730 +f 2809/2140/4468 2816/3868/6237 2993/4122/7148 +f 3148/3710/4406 3149/2631/4406 3114/2630/4406 +f 2026/2667/4938 2021/2643/4920 2038/2645/4922 +f 2558/4037/6487 2542/3388/5666 2543/3685/6012 +f 2116/3356/5630 2113/3159/5417 2114/3161/5419 +f 3052/4170/6698 3007/3333/5603 3049/2959/5206 +f 3880/4066/4554 3848/3889/4554 3846/3105/4554 +f 2849/2871/5127 2659/3220/5486 2848/3123/5381 +f 3784/2908/5162 3794/3871/6240 3783/3870/6239 +f 3074/4255/6866 2952/4208/6762 2954/4117/6610 +f 2606/3729/6358 2075/3682/6357 2096/3692/6794 +f 3211/4182/4383 3220/3550/4383 3219/3718/6057 +f 3051/2958/5205 3055/2693/4961 3008/3231/5499 +f 2139/2407/7264 2141/3376/7318 2457/3119/6798 +f 4023/2261/4581 4022/4283/6930 4024/2262/4582 +f 3993/3732/5000 3957/3428/5000 3988/4356/5000 +f 2414/3603/5910 2413/3244/5511 2381/4219/6784 +f 2317/4305/6980 2266/3851/6214 2319/4313/7010 +f 1963/3488/7319 1972/3467/7319 2073/4328/7319 +f 3183/2695/4963 3168/3602/5908 3167/4074/6547 +f 3346/3404/4350 3337/2001/4350 3338/3814/4350 +f 3540/2621/4902 3550/2814/5073 3539/2960/5207 +f 2514/4268/7206 2516/3583/5894 2515/3582/5893 +f 4005/3439/6640 4044/3724/6067 4004/2890/6998 +f 4395/2979/7320 4396/4344/7320 4293/4015/7320 +f 2573/2677/4946 2572/3616/5926 2551/2327/4641 +f 4185/3421/6152 4199/3108/6151 4197/3425/5706 +f 3389/2453/6997 3410/4086/6982 3409/4333/7321 +f 3926/3546/5847 3930/4391/5847 3826/2984/5847 +f 3058/4022/6465 3048/3436/5722 2919/3042/5295 +f 4116/4191/4367 4092/2089/4367 4095/3486/4367 +f 3758/2163/6316 3718/2911/5165 3726/3751/6317 +f 4312/4188/7292 4303/3276/5542 4313/3277/5544 +f 4266/3954/6364 4254/4061/6522 4264/3305/5571 +f 3951/4044/6500 3975/3259/6733 3952/3704/6732 +f 3283/3931/6329 3282/3810/6170 3298/3932/6330 +f 2236/4377/7187 2237/2295/4612 2233/2294/4611 +f 3482/2763/6077 3484/2903/5156 3483/2555/5155 +f 3057/3501/5790 3056/3233/5501 3002/3232/5500 +f 2283/2357/4670 2279/4080/6553 2286/2358/4671 +f 2644/4380/7226 2645/4160/6682 2173/4162/6684 +f 2467/4210/6766 2402/4343/7075 2404/3397/5868 +f 2826/4107/6594 2888/3481/5771 2827/4030/6475 +f 3028/3393/5674 3027/2406/4718 3066/3392/5673 +f 3498/4287/4388 3517/2524/4388 3511/2523/4388 +f 2302/3594/5900 2303/3164/5422 2301/3502/5791 +f 3534/2146/4474 3545/3537/5837 3533/2169/4498 +f 3919/3458/5747 3891/3318/5586 3920/3457/5746 +f 3764/4141/7322 3791/4140/6955 3790/4386/7323 +f 4245/2849/5105 4246/2607/4887 4232/2606/4886 +f 3682/3306/5572 3647/3000/5574 3648/2304/4621 +f 2388/3166/5424 2386/2450/6748 2385/3846/6209 +f 3977/2921/6734 3979/2480/7215 3953/3702/7214 +f 3591/2511/4806 3671/4368/7167 3672/2509/4804 +f 3590/3639/4434 3587/3769/6785 3586/3409/5692 +f 2024/4282/4584 2019/2613/4585 1991/3107/4585 +f 2871/4024/6468 3039/4025/6469 2874/3316/5584 +f 3641/4032/4524 3610/2688/5462 3642/4230/5462 +f 2270/3804/6681 2318/2528/4821 2278/2530/4823 +f 4342/4121/7110 4341/3539/5840 4340/3541/5842 +f 3462/3912/6301 3547/2393/4705 3546/3538/5838 +f 2574/3747/26 2580/3253/26 2378/3255/26 +f 2115/3342/5614 2116/3356/5630 2118/3343/5615 +f 3097/2425/4731 3099/3179/5444 3098/2426/4731 +f 3851/4375/7287 3849/3809/6168 3850/3808/6167 +f 2877/2342/4654 3040/3317/5585 3042/2343/4655 +f 4307/2980/5227 4327/3548/7156 4325/3452/5740 +f 3822/3234/6290 3921/2372/4686 3827/1984/4335 +f 3856/3588/5778 3853/3285/4554 3888/3411/4554 +f 2247/3653/5972 2319/4313/7010 2266/3851/6214 +f 2828/3363/5638 2672/4396/7324 2671/4138/6635 +f 4108/3361/4367 4097/4228/5277 4100/2744/4367 +f 3314/4317/7014 3208/4374/7185 3315/4347/7085 +f 3846/3105/5845 3843/3545/5846 3844/2395/4707 +f 4296/1978/6169 4372/2941/7135 4378/3003/5253 +f 2795/3601/5905 2796/4041/6492 2794/3671/5993 +f 2830/2346/4658 2726/2345/4657 2848/3123/5381 +f 3866/2112/4507 3839/2231/6262 3865/4261/7233 +f 3917/2292/4609 3820/2375/4689 3914/2291/4608 +f 3451/2097/4553 3333/2230/4553 3447/3163/4553 +f 2309/2641/4918 2308/4348/7086 2529/2642/4919 +f 3787/3199/6268 3772/3181/5445 3771/3957/6370 +f 2736/2901/5154 2846/3888/6267 2733/2560/4848 +f 4080/2365/4678 4078/3001/5250 4077/2065/5250 +f 2670/4349/7089 2850/2805/5065 2895/2454/4756 +f 4196/2582/4865 4197/3425/7117 4198/4331/7117 +f 2179/3133/7325 2178/2933/6375 2180/2501/6966 +f 2474/4332/7057 2468/2799/5059 2402/4343/7075 +f 3211/4182/4383 3217/2218/4383 3213/2920/4383 +f 3677/4070/6543 3669/2620/4901 3668/3383/5659 +f 3068/3847/6210 3032/3099/5356 3067/2125/4452 +f 3302/2289/4606 3301/3719/6058 3221/3824/6187 +f 4304/2088/4422 4303/3276/4422 4309/2519/4422 +f 2184/3634/5947 2281/3816/6177 2287/3632/5945 +f 4346/3829/6193 4360/2716/4985 4361/3057/5313 +f 3009/2727/4996 3021/4028/6470 3020/4021/6464 +f 3407/3097/5353 3423/2283/4600 3406/4020/6463 +f 4297/4249/4329 4301/2202/4329 4300/4358/7326 +f 2022/2776/6248 2035/2541/4832 2020/2557/4845 +f 2733/2560/4848 2846/3888/6267 2845/4094/6576 +f 2118/3343/5786 2595/3326/5593 2594/3325/5592 +f 2147/2227/7307 2146/2720/4989 2487/2590/4871 +f 3057/3501/5790 2922/3500/5789 3054/3949/6356 +f 4152/3032/5284 4153/4171/6699 4123/3882/6256 +f 2735/2561/4849 2772/2575/4860 2775/4302/6975 +f 4199/3108/7116 4200/3026/7116 4198/4331/7117 +f 3253/3102/5325 3252/3069/5325 3254/2235/5930 +f 2698/3648/5967 2695/3338/5607 2797/3144/5406 +f 3498/4287/7097 3496/3335/5604 3495/3337/5606 +f 3316/4248/6856 3313/3887/6266 3314/4317/7014 +f 2383/3360/5634 2436/2840/5096 2415/4271/6898 +f 2482/3970/6394 2505/2386/4695 2483/3513/5806 +f 3010/4360/7118 2144/3266/5535 3011/3268/5537 +f 3588/3863/6228 3579/2103/4434 3578/2102/4433 +f 3034/3707/6044 3038/2526/4819 2863/3979/6405 +f 3280/3832/6196 3281/2828/6924 3268/3078/5333 +f 4302/2201/4525 4377/2203/4527 4368/3287/5555 +f 2326/3050/5305 2564/3140/5402 2565/3238/5505 +f 3205/3856/7099 3201/2679/7099 3085/2678/7099 +f 3341/2000/4350 3339/2002/4350 3336/2016/4350 +f 2627/3281/6391 2620/3696/6389 2626/3965/6388 +f 3000/4218/6779 2993/4122/7148 2816/3868/6237 +f 3427/4178/6709 3344/3405/5685 3426/3876/6250 +f 2358/1975/4328 2354/4339/7070 2355/4338/7069 +f 2108/3794/6147 2110/3852/7327 2109/4256/6867 +f 3058/4022/6465 2920/3581/5892 3059/2126/4453 +f 3024/1970/4323 3023/4233/6827 3079/3435/5721 +f 3653/2151/4876 3654/3309/5577 3589/3323/6507 +f 2829/2441/4745 2912/2475/4774 2897/2477/4776 +f 4246/2607/4887 4260/2966/5213 4259/2965/5212 +f 2725/2752/5020 2731/2751/5019 2767/3647/5966 +f 2415/4271/6898 2436/2840/5096 2437/3604/5911 +f 2611/2273/7315 2609/2915/6335 2610/3934/6334 +f 3957/3428/5711 3955/3427/5710 3985/2731/7035 +f 2105/2335/5234 2472/4388/7289 2473/2986/5235 +f 2389/3955/6368 2435/3956/6369 2391/4019/6461 +f 3058/4022/6465 3059/2126/4453 3066/3392/5673 +f 3943/3203/5470 4033/3915/6304 3937/4355/7107 +f 4388/3884/6261 4387/3056/5312 4386/2811/5070 +f 2775/4302/6975 2768/4213/6770 2732/4017/6460 +f 3267/2180/6749 3234/3018/4351 3236/4307/6749 +f 3455/4393/7298 3564/3905/6292 3452/2681/4948 +f 3631/2634/7328 3632/3184/7328 3604/4190/7328 +f 2637/3678/6094 2159/3153/5414 2636/4385/7245 +f 2969/3558/6080 2981/3737/6079 2980/4199/6753 +f 3986/3873/5000 3971/3524/5000 3999/3089/5000 +f 3159/2822/5081 3158/2249/6845 3194/4240/6846 +f 3873/2397/4709 3871/2691/4959 3870/1999/4349 +f 2144/3266/5535 2487/2590/4871 2143/3267/5536 +f 2728/2988/5237 2725/2752/5020 2766/2989/5238 +f 4034/3913/6302 4036/4367/7158 4035/3914/6303 +f 2981/3737/26 2984/4051/26 2928/4050/26 +f 2990/4164/6769 2710/4002/6445 2711/4001/6444 +f 4029/3205/5472 4026/3204/5471 4030/2082/4418 +f 2072/2508/4316 2071/2507/4316 2070/2987/4316 +f 3646/3265/4524 3614/4064/4524 3643/3649/4524 +f 4048/3593/5354 4052/3592/5354 4049/4390/5354 +f 3922/1982/4333 3923/3142/5404 3824/1983/4334 +f 3932/2325/5354 3940/2324/5354 3937/4355/7107 +f 2882/4130/6628 2880/2995/5244 3015/2994/5243 +f 2267/3791/6143 2265/4008/6453 2203/3792/6144 +f 3165/2839/5752 3164/2838/5094 3175/4242/6848 +f 2314/2997/5246 2316/3617/5927 2315/2996/5245 +f 1984/3224/4585 1983/2156/4484 1982/2866/5122 +f 3732/2754/4336 3730/4180/4337 3764/4141/4336 +f 4246/2607/4887 4234/3236/7231 4233/2608/4888 +f 3443/2900/5152 3442/3096/5352 3408/3095/5351 +f 2975/3559/26 2976/2974/26 2939/3715/26 +f 4030/2082/4418 4012/3523/6448 4013/3628/5943 +f 2343/4372/7180 2344/3240/5507 2342/3239/5506 +f 2290/3827/6191 2188/3828/6192 2189/3833/6197 +f 2748/2729/4998 2783/3496/5785 2769/3072/5327 +f 4251/4177/7024 4252/3927/7217 4236/2190/7033 +f 3743/3185/5803 3746/3092/7329 3745/3186/7329 +f 4020/3906/6293 4021/3944/6351 4008/3874/6294 +f 3324/3986/6419 3299/4163/6687 3325/2827/5086 +f 3994/3441/5000 3961/4276/5000 3959/3733/5000 +f 4344/2123/7265 4343/4357/7111 4312/4188/6723 +f 4252/3927/6325 4251/4177/6708 4264/3305/5571 +f 2808/2504/4801 2809/2140/4468 2807/3620/5934 +f 3087/4137/6946 3189/3022/5273 3188/3688/6019 +f 3020/4021/6464 2960/4323/7044 3009/2727/4996 +f 4062/3073/4408 4064/2579/6233 4060/3414/6726 +f 4007/3872/7263 4046/2129/4456 4006/4309/7021 +f 3310/4285/6933 3209/3939/7084 3311/3920/6309 +f 3890/3320/5588 3916/2403/4715 3889/2053/4394 +f 3066/3392/5673 3065/3446/5735 3058/4022/6465 +f 2849/2871/5127 2908/3991/6429 2907/2074/4410 +f 3027/2406/4718 3065/3446/5735 3066/3392/5673 +f 3112/2317/4406 3144/2068/4406 3110/2070/4406 +f 4311/3951/6644 4303/3276/5542 4343/4357/7161 +f 2281/3816/7198 2282/2356/4669 2286/2358/4671 +f 3695/2188/6101 3585/2173/6101 3697/2172/6101 +f 2078/2740/6430 2698/3648/5967 2697/3447/5736 +f 4310/3419/5701 4337/3613/7190 4335/2616/4897 +f 2723/3093/5349 2730/2954/5201 2727/3625/5940 +f 2446/3301/5567 2423/3606/5913 2447/4195/6744 +f 3268/3078/5333 3279/3080/5335 3280/3832/6196 +f 3998/3522/5000 3964/3910/5000 3997/3440/5000 +f 2599/2682/4949 2103/2011/4951 2102/2010/7330 +f 4254/4061/6522 4253/3926/6324 4265/3303/5569 +f 2503/3574/5883 2501/4149/6658 2521/4056/6517 +f 2707/2503/4800 2705/3683/6010 2706/3374/5650 +f 2216/4304/6979 2240/4004/6447 2358/1975/4328 +f 4052/3592/5354 4050/2417/5354 4051/2416/5354 +f 4059/2770/7188 4164/2580/7188 4058/2072/7188 +f 4349/2418/4422 4355/3694/4422 4336/2638/4422 +f 3544/2113/4834 3509/2544/4836 3524/2851/6038 +f 2322/3731/6075 2323/3652/5971 2248/3651/5970 +f 2530/3681/6006 2541/3680/6005 2540/3675/5999 +f 3760/3760/4336 3728/3938/4337 3759/2165/4336 +f 3134/2485/7087 3136/2484/6928 3137/3904/6928 +f 3454/2594/4532 3455/4393/4532 3453/2338/4532 +f 2983/4058/26 2982/3350/6896 2943/4052/26 +f 4112/2175/4367 4107/2835/4367 4076/2837/4367 +f 2481/3742/6087 2507/3743/6088 2480/3676/6000 +f 2153/3514/7138 2152/4397/7331 2488/4312/7005 +f 4103/4063/7017 4101/2742/6512 4074/2059/4397 +f 2327/3937/6340 2329/2341/4653 2243/3049/5304 +f 1963/3488/7319 2073/4328/7319 2069/2565/7332 +f 2431/3151/5412 2430/4354/7106 2417/4226/6797 +f 2764/3755/6106 2839/3611/5918 2838/4183/6716 +f 2532/4158/6674 2528/2676/4945 2537/3247/5514 +f 2907/2074/4410 2908/3991/6429 2909/3990/6428 +f 3466/2209/7008 3575/2605/7009 3457/2207/7009 +f 4355/3694/4422 4354/2205/4422 4333/3359/4422 +f 4006/4309/7021 4046/2129/4456 4045/3691/6022 +f 2078/2740/7333 2079/2741/7276 2076/3177/7278 +f 2094/2914/5527 2092/3261/5526 2086/2843/7334 +f 2276/3798/7151 2277/3800/7227 2271/2483/4782 +f 2451/3292/5558 2454/3117/5375 2136/4259/6960 +f 3338/3814/6175 3444/4329/7052 3346/3404/6918 +f 3261/2834/7335 3266/3051/5306 3291/2833/5092 +f 2243/3049/5304 2244/3048/5303 2441/3174/5435 +f 2465/2400/4712 2459/2826/5085 2477/2825/5084 +f 2015/3274/5764 2017/3273/6436 2031/3929/6327 +f 3415/2196/6249 3445/3877/6251 3414/2197/7209 +f 3367/2856/7029 3370/2884/6390 3369/3966/6390 +f 3984/4322/7336 3946/3510/5801 3954/4071/7337 +f 3662/3442/6478 3642/4230/6805 3663/3410/5693 +f 3386/2238/5258 3347/3007/5257 3355/4279/6919 +f 3832/1993/4690 3830/2650/4690 3831/1991/4690 +f 3156/3673/6686 3155/3509/6253 3193/3399/5680 +f 3877/2414/4554 3867/2111/5778 3864/2487/4554 +f 3789/3786/6372 3765/2755/6371 3790/4386/7273 +f 3725/4110/6603 3726/3751/4336 3724/3129/5388 +f 3834/2380/6879 3843/3545/6740 3845/3104/6970 +f 3872/4365/7150 3871/2691/4959 3873/2397/4709 +f 3512/3167/5426 3527/2298/5425 3526/2916/6849 +f 4166/3415/4409 4165/2581/4408 4164/2580/4409 +f 2233/2294/4611 2231/2332/4646 2232/2334/4648 +f 2434/3518/5811 2399/2797/5057 2420/3519/5812 +f 3343/2020/4366 3420/3577/7197 3421/2772/5035 +f 3747/2549/4840 3746/3092/7329 3748/2550/4841 +f 2492/4278/6916 2494/3666/5987 2548/2328/4642 +f 2913/3280/5548 2148/3040/5293 2918/3589/5897 +f 2476/4176/6707 2451/3292/5558 2121/2410/4719 +f 3880/4066/4554 3846/3105/4554 3879/3842/4554 +f 3299/4163/6687 3298/3932/6330 3325/2827/5086 +f 4017/2817/5076 3988/4356/7109 3987/2733/7007 +f 2061/2536/4829 2062/4173/6703 2059/2929/5181 +f 2183/3815/6176 2194/3812/6171 2282/2356/6173 +f 3857/2314/4554 3856/3588/5778 3874/3431/4554 +f 2798/3143/5405 2112/3160/6216 2687/4132/6631 +f 4227/3127/5385 4241/3126/5384 4242/2992/6993 +f 4278/2780/5041 4244/3061/5316 4277/2778/5039 +f 3580/2537/4434 3587/3769/6785 3590/3639/4434 +f 3479/3761/6112 3480/2764/6112 3482/2763/6077 +f 3140/2069/5798 3154/4273/7221 3155/3509/5799 +f 2848/3123/5381 2724/4373/7183 2905/4306/6986 +f 3714/3112/5358 3706/3839/5358 3709/3645/5358 +f 2326/3050/5305 2324/3237/5504 2244/3048/5303 +f 2734/4234/6833 2732/4017/6460 2736/2901/5154 +f 2170/2947/7225 2644/4380/7226 2171/4292/6952 +f 3959/3733/6978 3956/3429/5712 3957/3428/5711 +f 4248/2766/7164 4182/3088/5661 4249/3384/5660 +f 3643/3649/4524 3614/4064/4524 3612/2686/4524 +f 2868/4120/6613 2866/3978/6404 3038/2526/4819 +f 4172/3087/4924 4178/4370/6680 4174/4159/6680 +f 2473/2986/5235 2472/4388/7289 2470/4353/7105 +f 4223/2083/4419 4220/3940/6346 4219/3272/6695 +f 2119/3607/7291 2124/4034/7338 2128/4112/7316 +f 2741/2593/4874 2684/2592/4873 2683/4092/6573 +f 3977/2921/6734 3953/3702/7214 3952/3704/6732 +f 2361/3922/6315 2392/4327/7051 2390/3745/6090 +f 2817/2990/7339 2766/2989/5238 2687/4132/6631 +f 4258/4053/7223 4257/4211/6767 4268/2029/4373 +f 2952/4208/6762 3074/4255/6866 2949/4224/6793 +f 3538/3622/5936 3521/2586/6729 3539/2960/5207 +f 4226/4085/6562 4243/2991/6992 4244/3061/6563 +f 2134/3377/7193 2141/3376/7340 2140/2408/7194 +f 3147/3381/4406 3145/2757/4406 3129/3146/4406 +f 2074/3176/6719 2606/3729/6072 2696/2428/4734 +f 3626/2469/4769 3623/3469/6956 3624/3195/7257 +f 4287/2569/4924 4286/2568/4924 4282/3711/4924 +f 2862/3708/6045 2861/4115/6608 2859/3968/6392 +f 2350/2259/4579 2342/3239/5506 2345/3241/5508 +f 2132/3291/7129 2589/2711/5276 2720/3024/5275 +f 3791/4140/6955 3801/3473/5762 3790/4386/7323 +f 3362/2724/4993 3364/2513/5391 3363/3332/5391 +f 2575/4267/26 2377/4392/26 2371/3254/26 +f 2168/2588/4869 2646/4351/7310 2649/2589/4870 +f 2665/2440/4744 2906/2075/4411 2912/2475/4774 +f 2319/4313/7010 2571/2390/4702 2317/4305/6980 +f 3702/3763/5804 3701/3838/7341 3811/3764/5804 +f 4107/2835/4367 4106/4296/4367 4105/2836/4367 +f 2462/3390/7255 2382/3477/5767 2405/3845/6208 +f 2370/4270/512 2577/3352/512 2363/4326/26 +f 2754/3756/6107 2837/4084/6560 2751/2702/4971 +f 2161/3657/7293 3001/4284/6931 2926/3535/5832 +f 2293/3424/5705 2294/3819/7200 2284/2736/5004 +f 2443/3121/5379 2419/3120/5378 2442/3175/5436 +f 4010/3091/5347 4022/4283/6930 4019/4252/6862 +f 1972/3467/7260 1976/2506/7260 2072/2508/7260 +f 3034/3707/6044 2860/3709/6046 3033/3998/6441 +f 4219/3272/5541 4218/3637/6474 4190/3461/5750 +f 3451/2097/4350 3446/3162/4350 3450/2098/4350 +f 3341/2000/5153 3412/3298/5564 3338/3814/6175 +f 3026/2455/4757 3025/2405/4717 2895/2454/4756 +f 4128/2566/4852 4114/4143/7275 4116/4191/6875 +f 4353/3861/6226 4356/2942/5188 4373/3862/6227 +f 3318/4235/6834 3315/4347/7085 3319/2217/4539 +f 3023/4233/6827 3022/4363/7133 3078/2725/4994 +f 2828/3363/5638 2673/4099/6584 2672/4396/7324 +f 4285/4222/7166 4174/4159/7166 4284/4297/7166 +f 2988/2784/6616 2974/3351/5623 2987/2785/5622 +f 2818/3111/5368 2820/3432/5717 2821/4369/7171 +f 3953/3702/7214 3982/4231/7216 3954/4071/7337 +f 2238/2293/4610 2239/2983/5230 2437/3604/5911 +f 4037/2819/5078 4018/2818/5077 3933/3012/5265 +f 2301/3502/7342 2307/3987/7285 2588/4082/6555 +f 2254/3783/7262 2251/2747/5015 2252/3311/5579 +f 3774/2906/4336 3739/2435/4336 3772/3181/4336 +f 3247/3699/6033 3249/3194/5461 3246/2622/4903 +f 3316/4248/6856 3317/2220/4543 3275/2219/4542 +f 2501/4149/6658 2503/3574/5883 2504/2385/4694 +f 2580/3253/26 2575/4267/26 2371/3254/26 +f 2801/3373/5649 2773/3235/5502 2771/2574/4859 +f 3268/3078/4351 3272/4281/4351 3244/2623/4351 +f 3079/3435/5721 3065/3446/5735 3025/2405/4717 +f 3990/4005/6450 4000/3471/5760 3987/2733/7007 +f 4226/4085/6562 4227/3127/5385 4242/2992/6993 +f 3897/2708/4977 3924/3988/6424 3896/2706/4975 +f 3972/4045/6501 3950/2242/4562 3970/2244/4564 +f 4375/1994/4344 4374/3068/5323 4380/2521/4814 +f 2589/2711/5276 2136/4259/7259 2999/3752/6102 +f 2212/2750/5018 2357/4079/6552 2314/2997/5246 +f 2340/3364/5639 2332/4007/6451 2339/4072/6545 +f 3863/3189/5456 3864/2487/5455 3865/4261/6881 +f 3449/4334/7060 3345/2309/7060 3450/2098/7060 +f 4062/3073/4408 4063/4244/6233 4064/2579/6233 +f 2179/3133/26 2178/2933/26 2376/4379/26 +f 3080/2774/5037 3076/2611/4891 3021/4028/6470 +f 2042/3669/5991 2052/2109/4438 2053/3741/6086 +f 3209/3939/6119 3210/4146/6649 3207/3629/6119 +f 4328/3549/4422 4358/2204/4422 4326/3289/4422 +f 3068/3847/6210 3061/2124/4451 3069/3848/6211 +f 3995/2889/5000 3976/4127/5000 3996/4266/5000 +f 2785/2141/4469 2786/4251/6861 2790/3027/5279 +f 4309/2519/4422 4308/2518/7343 4307/2980/4422 +f 3605/2737/6285 3604/4190/6953 3606/2198/6285 +f 2083/2274/7344 2082/2456/4758 2084/3945/6505 +f 2924/3580/5891 2925/3878/6252 2921/3499/5788 +f 4172/3087/7305 4285/4222/7305 4286/2568/7305 +f 2327/3937/6340 2328/3983/6415 2561/4179/6713 +f 4356/2942/5188 4372/2941/5187 4373/3862/6227 +f 2440/4238/6841 2441/3174/5435 2416/3173/5434 +f 4094/3485/5775 4097/4228/6800 4095/3486/5776 +f 2261/3207/7055 2260/4196/7054 2264/4342/7054 +f 2452/3227/7137 2455/3353/5652 2454/3117/5375 +f 2724/4373/7183 2848/3123/5381 2726/2345/4657 +f 2368/2551/26 2581/3483/512 2369/4389/26 +f 2574/3747/6096 2510/3192/6098 2513/3191/6884 +f 2366/4290/26 2585/2094/26 2364/2777/26 +f 4144/3074/5329 4135/2978/6017 4143/3075/5330 +f 2745/2472/4771 2748/2729/4998 2749/4088/6568 +f 1961/2534/4827 1964/3740/4316 1962/2820/6472 +f 2670/4349/7089 2669/2803/5063 2850/2805/5065 +f 2531/3679/6004 2313/2749/5017 2312/2748/5016 +f 4153/4171/6699 4154/3031/5283 4155/4215/6775 +f 2333/2285/4602 2331/1974/4327 2334/1973/4326 +f 2086/2843/7334 2094/2914/5527 2608/4265/6887 +f 4181/2879/4924 4179/2880/4924 4182/3088/4924 +f 2775/4302/6975 2774/3530/5828 2688/2143/4471 +f 4094/3485/5775 4096/4227/6799 4097/4228/6800 +f 3859/2315/4554 3857/2314/4554 3881/2707/4554 +f 3465/3578/5889 3466/2209/4532 3467/2208/4531 +f 2569/3730/6074 2566/3735/6076 2554/3315/5583 +f 3742/3283/4336 3739/2435/4336 3774/2906/4336 +f 3409/4333/7321 3408/3095/5351 3389/2453/6997 +f 3621/3565/5869 3622/3567/7258 3620/3566/5870 +f 2248/3651/5970 2246/2703/4972 2321/2705/4974 +f 3859/2315/4554 3883/3950/4554 3862/3188/4554 +f 2009/3275/7082 2008/2155/7082 2010/2060/4398 +f 2257/2746/6128 2256/2745/6130 2208/3779/6129 +f 2880/2995/5244 2878/3923/6319 2879/2344/4656 +f 4057/3575/5884 4148/3156/5416 4147/2367/4680 +f 3501/2697/4967 3500/2045/4966 3503/2047/7210 +f 2923/3138/5399 3060/3137/5398 2921/3499/5788 +f 4230/3595/4517 4194/2085/4517 4196/2582/4517 +f 3637/3131/4524 3606/2198/4524 3604/4190/4524 +f 3969/2271/5000 3966/3942/5000 3999/3089/5000 +f 3235/3017/5268 3236/4307/5268 3234/3018/5269 +f 2242/3250/5517 2438/3252/5519 2216/4304/6979 +f 4059/2770/4409 4065/2071/4407 4061/2771/5034 +f 3899/3403/7211 3831/1991/4341 3898/3401/6876 +f 2205/3775/6124 2211/3208/5475 2264/4342/7212 +f 2802/4054/6513 2686/2953/5200 2721/4038/6488 +f 2430/4354/7106 2413/3244/5511 2428/3243/5510 +f 3464/2546/4838 3556/2812/5071 3557/2545/4837 +f 3001/4284/6931 3007/3333/5603 3052/4170/6698 +f 2141/3376/7308 2136/4259/7345 2137/2710/7309 +f 3155/3509/6253 3154/4273/6903 3190/3020/5271 +f 4149/2366/4679 4146/3636/5949 4147/2367/4680 +f 3061/2124/4451 3068/3847/6210 3067/2125/4452 +f 2197/3802/6159 2274/3437/7195 2273/2482/6162 +f 3937/4355/7107 4035/3914/6303 3934/3854/7157 +f 2829/2441/4745 2897/2477/4776 2850/2805/5065 +f 3033/3998/6441 3073/3433/5718 3004/4221/6790 +f 3034/3707/6044 3033/3998/6441 3004/4221/6790 +f 4394/2662/4329 4398/4359/4329 4397/2663/4329 +f 3200/2680/7271 3202/4194/7346 3090/4253/7271 +f 4395/2979/7320 4293/4015/7320 4295/4167/7320 +f 3251/3070/4351 3253/3102/4351 3263/2033/4351 +f 3906/2402/7123 3905/2305/6533 3880/4066/6532 +f 3487/2490/4789 3490/2847/5104 3489/2848/5104 +f 2202/3790/6142 2268/2924/6138 2267/3791/6143 +f 3593/3706/6041 3671/4368/7167 3591/2511/4806 +f 2777/3293/5559 2794/3671/5993 2796/4041/6492 +f 2697/3447/5736 2778/2971/5218 2700/3269/5538 +f 2145/2721/4990 2143/3267/5536 2487/2590/4871 +f 2283/2357/4670 2280/3085/7347 2279/4080/6553 +f 2613/2502/4799 2181/2913/5167 2963/2500/4797 +f 4145/3635/5948 4057/3575/5884 4147/2367/4680 +f 2924/3580/5891 2919/3042/5295 2927/3516/5809 +f 2481/3742/6087 2540/3675/5999 2482/3970/6394 +f 2986/3587/6556 2951/4201/6755 2948/4083/6557 +f 4124/4272/7312 4123/3882/6256 4153/4171/6699 +f 2420/3519/5812 2399/2797/5057 2401/3526/5820 +f 2853/2956/5203 2852/2674/4943 2892/3975/6400 +f 2832/4081/6554 2703/3995/6437 2759/3700/6034 +f 3178/4325/7050 3197/2823/5082 3198/3328/5597 +f 2219/3389/5668 2220/4387/7282 2221/2495/4792 +f 3175/4242/6848 3199/3464/5753 3165/2839/5752 +f 4351/3497/6743 4361/3057/5313 4350/2419/4726 +f 2781/2422/4729 2790/3027/5279 2792/2423/4730 +f 4318/3348/6483 4316/3967/6484 4315/4035/6484 +f 2823/2050/4391 2822/4345/7083 2901/3313/5581 +f 3993/3732/7348 4016/4184/7119 3994/3441/5727 +f 2863/3979/6405 2862/3708/6045 3034/3707/6044 +f 2418/3249/5516 2431/3151/5412 2417/4226/6797 +f 2528/2676/4945 2312/2748/5016 2314/2997/5246 +f 2916/3170/5430 2914/3062/5317 3011/3268/5537 +f 4107/2835/5886 4138/3576/5885 4121/2816/5075 +f 3802/3263/5529 3775/4134/6633 3776/3759/6110 +f 4287/2569/5745 4283/4006/7349 4169/2892/5745 +f 3013/4223/6792 2949/4224/6793 3074/4255/6866 +f 3571/2462/4764 3552/2461/4763 3468/3697/6844 +f 3563/2917/5171 3455/4393/7298 3562/2114/4443 +f 3416/2868/6738 3401/2195/4521 3402/2885/6452 +f 3746/3092/7329 3743/3185/5803 3744/2055/5833 +f 4046/2129/4456 4007/3872/7263 4047/2127/4454 +f 3142/3508/4406 3143/2250/4406 3135/3158/5056 +f 3631/2634/7328 3604/4190/7328 3603/2739/7328 +f 3924/3988/6424 3897/2708/4977 3824/1983/4334 +f 3309/4316/7013 3308/3643/5959 3209/3939/7084 +f 3796/3903/6289 3795/2794/5055 3797/2793/5054 +f 3074/4255/6866 3077/2775/5038 3080/2774/5037 +f 2119/3607/7291 2126/4337/7251 2432/2411/4720 +f 2152/4397/7331 2148/3040/7199 2488/4312/7005 +f 2385/3846/6209 2397/4010/6455 2305/3005/5255 +f 2742/3754/6105 2754/3756/6107 2753/4076/6549 +f 2357/4079/6552 2356/2529/4822 2316/3617/5927 +f 3010/4360/7118 3011/3268/5537 3078/2725/4994 +f 3391/4202/4755 3383/4018/4755 3381/2451/4755 +f 2084/3945/7350 2083/2274/7314 2610/3934/6334 +f 3061/2124/4451 3060/3137/5398 3069/3848/6211 +f 2477/2825/5084 2467/4210/6766 2466/3025/5278 +f 3036/2859/5116 3071/4106/6593 3072/3489/5779 +f 3422/2807/5644 3394/3368/5643 3392/3449/5739 +f 3974/4128/6625 3976/4127/6624 3975/3259/5524 +f 2099/2077/6321 2601/3925/6323 2602/2427/6413 +f 2279/4080/6553 2280/3085/7347 2278/2530/4823 +f 2552/2392/4704 2553/2391/4703 2547/3527/5825 +f 3790/4386/7323 3801/3473/5762 3789/3786/6137 +f 2300/4009/6454 2299/2895/5147 2215/3006/5256 +f 2038/2645/4922 2039/2108/4936 2026/2667/4938 +f 2110/3852/6223 2109/4256/7351 2111/3860/6224 +f 2512/3450/5641 2479/2571/4856 2509/3367/5642 +f 3411/3297/6981 3397/4111/6983 3412/3298/7202 +f 3479/3761/6112 3482/2763/6077 3481/3736/6078 +f 2450/2412/4721 2401/3526/5820 2469/4214/6773 +f 2553/2391/4703 2554/3315/5583 2546/3533/5829 +f 2974/3351/26 2975/3559/26 2942/3561/26 +f 2895/2454/4756 2894/2404/4716 2828/3363/5638 +f 2548/2328/4642 2494/3666/5987 2549/2925/5177 +f 3726/3751/6317 3755/3294/6602 3757/2164/6318 +f 1999/3749/6850 1997/2255/4575 1981/2254/4574 +f 3126/3672/5995 3125/2216/7016 3127/2215/5407 +f 3889/2053/6519 3875/4057/6518 3890/3320/5588 +f 2147/2227/7307 2494/3666/5987 2149/3665/5986 +f 3030/3082/5337 3032/3099/5356 3068/3847/6210 +f 2798/3143/5405 3082/2685/4953 2112/3160/6216 +f 2107/2985/7280 2598/4068/6542 3082/2685/4953 +f 4094/3485/6944 4093/3487/7268 4072/2429/4735 +f 3262/2136/4351 3264/2135/4351 3258/4229/4351 +f 2124/4034/7352 2590/3493/6947 2123/3608/7175 +f 4319/3058/7159 4320/2951/6536 4321/3349/6538 +f 4263/3304/5570 4252/3927/6325 4264/3305/5571 +f 3419/2019/4365 3431/2018/4364 3424/3295/5561 +f 2535/2311/4628 2534/3248/5515 2536/2675/4944 +f 2985/4166/26 2986/3587/26 2929/3586/26 +f 3400/2936/4755 3368/4319/4755 3366/2515/4755 +f 2215/3006/5256 2305/3005/5255 2300/4009/6454 +f 2139/2407/26 2577/3352/512 2370/4270/512 +f 2805/4000/6443 2712/2899/5151 2711/4001/6444 +f 3162/3380/5656 3177/3211/5478 3176/3210/5477 +f 2443/3121/5379 2442/3175/5436 2245/3412/5696 +f 4300/4358/7326 4302/2201/4329 4293/4015/4329 +f 2403/3564/5867 2435/3956/6369 2409/3396/5677 +f 3167/4074/6547 3153/3531/5907 3152/2194/4520 +f 2448/4198/6747 2396/3551/5854 2433/3517/5810 +f 3745/3186/7329 3746/3092/7329 3747/2549/4840 +f 2803/3869/6238 2804/4243/6851 2802/4054/6513 +f 3803/3262/5528 3805/3770/6117 3703/3864/6229 +f 3412/3298/7202 3395/4257/7201 3413/3813/6949 +f 3452/2681/4948 3453/2338/4532 3455/4393/4532 +f 2099/2077/7246 2101/2299/7228 2100/4381/7230 +f 2144/3266/5535 2175/3521/5814 2182/3520/5813 +f 3833/4192/6741 3843/3545/6740 3834/2380/6879 +f 2891/4011/6456 2853/2956/5203 2892/3975/6400 +f 2286/2358/4671 2215/3006/5256 2299/2895/5147 +f 3187/3837/6201 3091/3943/6350 3087/4137/6946 +f 2746/2473/4772 2745/2472/4771 2749/4088/6568 +f 2712/2899/5151 2814/3880/6254 2714/2897/5149 +f 2112/3160/6216 2597/3455/5823 3081/3454/5742 +f 2721/4038/6488 2715/3135/5396 2720/3024/5275 +f 2648/2948/5194 3014/4352/7093 3012/2949/5195 +f 3358/4185/4755 3392/3449/4755 3360/2723/4755 +f 3578/2102/4433 3684/2976/5223 3588/3863/6228 +f 2429/2078/4414 2099/2077/4413 2395/2713/4982 +f 2819/4299/6971 2821/4369/7171 2820/3432/5717 +f 3354/2044/4386 3382/2043/4385 3355/4279/6919 +f 3722/3183/5447 3743/3185/5450 3723/3130/5389 +f 2066/2354/4667 2067/3552/5856 2036/2355/4668 +f 2581/3483/512 2582/2095/512 2369/4389/26 +f 2762/3038/5291 2834/4262/6882 2833/2464/4766 +f 3042/2343/4655 3045/3037/5290 3012/2949/5195 +f 3779/2904/5158 3768/4144/7147 3780/2222/4545 +f 3231/4042/6651 3234/3018/6830 3232/4148/6652 +f 4111/2176/4367 4112/2175/4367 4078/3001/4367 +f 3501/2697/7020 3502/3765/6114 3475/2288/4605 +f 4017/2817/5076 4034/3913/6302 4016/4184/6717 +f 4048/3593/5817 4049/4390/5817 3932/2325/5817 +f 3416/2868/6738 3402/2885/6452 3417/2935/5183 +f 2768/4213/6770 2775/4302/6975 2688/2143/4471 +f 3760/3760/4336 3759/2165/4336 3763/3721/4336 +f 2911/3312/5580 2910/2048/4389 2823/2050/4391 +f 2384/3836/6200 2359/3835/6199 2193/2963/5210 +f 2334/1973/4326 2358/1975/4328 2355/4338/7069 +f 4361/3057/5313 4360/2716/4985 4385/2715/4984 +f 4236/2190/4517 4235/4062/4517 4200/3026/4517 +f 2703/3995/6437 2704/3996/6439 2702/3385/5663 +f 2432/2411/4720 2116/3356/7141 2114/3161/7317 +f 3036/2859/5116 2886/2861/5118 2885/3480/5770 +f 2237/2295/4612 2217/3850/6213 2239/2983/5230 +f 2138/3370/6868 2136/4259/6868 2137/2710/6816 +f 3886/2789/5778 3850/3808/4554 3885/2787/4554 +f 2444/2090/4423 2445/2092/4425 2248/3651/5970 +f 3308/3643/5959 3304/4157/6671 3305/4145/6648 +f 2496/4350/7090 2494/3666/5987 2487/2590/4871 +f 4352/1996/7353 4353/3861/6226 4374/3068/6225 +f 2578/4320/26 2579/2553/26 2367/2552/26 +f 3563/2917/5171 3564/3905/6292 3455/4393/7298 +f 4269/4075/6548 4258/4053/7223 4268/2029/4373 +f 2947/3773/6121 2948/4083/6557 2949/4224/6829 +f 4203/2831/7098 4204/2212/6678 4205/3674/6677 +f 2435/3956/6369 2399/2797/5057 2434/3518/5811 +f 3907/4341/7122 3879/3842/6204 3908/3841/6203 +f 2213/4189/6731 2529/2642/4919 2308/4348/7086 +f 3401/2195/4521 3414/2197/4523 3396/3045/6950 +f 4231/2767/5503 4237/2853/4517 4205/3674/4517 +f 2624/3963/6384 2147/2227/4550 2619/2229/4552 +f 3048/3436/5722 3011/3268/5537 2913/3280/5548 +f 4156/3196/5463 4125/4098/6583 4155/4215/6775 +f 2760/2463/4765 2763/3686/6013 2762/3038/5291 +f 3494/2107/4388 3515/2171/4388 3495/3337/4388 +f 4182/3088/5661 4179/2880/7354 4264/3305/5571 +f 2294/3819/6180 2186/4078/6551 2185/3818/6179 +f 3047/2692/4960 3050/2694/4962 3046/3035/5288 +f 4136/2977/5224 4111/2176/4503 4113/2468/5225 +f 4301/2202/4329 4302/2201/4329 4300/4358/7326 +f 3552/2461/4763 3553/3504/5793 3465/3578/5889 +f 2308/4348/7086 2309/2641/4918 2214/3004/5254 +f 3901/3746/6093 3910/2361/4674 3832/1993/4343 +f 3499/2287/4604 3474/2286/4603 3497/4295/6958 +f 4041/3562/5865 3941/3757/6108 3939/3014/5267 +f 2920/3581/5892 2921/3499/5788 3059/2126/4453 +f 2131/2709/6817 2132/3291/7355 2133/3369/6818 +f 3777/3720/6059 3793/3264/5530 3776/3759/6110 +f 2255/3781/7300 2256/2745/5013 2251/2747/5015 +f 2016/2493/4585 2011/2062/4585 2013/2061/4585 +f 3049/2959/5206 3051/2958/5205 3053/3948/6355 +f 2815/3023/5274 2803/3869/6238 2720/3024/5275 +f 2699/2272/4589 2700/3269/5538 2611/2273/4590 +f 2158/3534/6411 2640/3982/6414 2157/3152/5413 +f 3883/3950/6657 3881/2707/4976 3896/2706/4975 +f 3506/2615/6063 3507/2382/7079 3476/2938/6061 +f 4090/2021/4684 4089/2370/4683 4091/3591/5899 +f 2524/3655/5974 2525/3660/5980 2162/3656/5975 +f 2485/2310/4627 2495/2926/5178 2486/2277/4594 +f 4343/4357/7111 4344/2123/7265 4342/4121/7110 +f 2413/3244/5511 2430/4354/7106 2381/4219/6784 +f 3821/2540/4831 3912/2306/4623 3913/4340/7072 +f 2490/3386/5664 2158/3534/6910 2489/4275/6912 +f 3174/3021/5272 3173/3615/5925 3189/3022/5273 +f 2375/4289/26 2586/3866/26 2376/4379/26 +f 2735/2561/4849 2734/4234/6833 2733/2560/4848 +f 3176/3210/5477 3094/3209/5476 3089/4241/6847 +f 3351/2854/5111 3369/3966/6407 3352/2656/6406 +f 3984/4322/7336 3954/4071/7337 3982/4231/7216 +f 4128/2566/4852 4127/2444/4748 4139/2443/4747 +f 2440/4238/6841 2416/3173/5434 2427/4225/6796 +f 2822/4345/7083 3074/4255/6866 3080/2774/5037 +f 3274/2137/4465 3291/2833/5092 3293/3928/6326 +f 2493/4277/6915 2547/3527/5825 2546/3533/5829 +f 2886/2861/5118 2827/4030/6475 2885/3480/5770 +f 3848/3889/4554 3885/2787/4554 3850/3808/4554 +f 2652/4155/6668 2846/3888/6267 2653/4395/7313 +f 3930/4391/4688 3925/2499/4688 3929/2651/4688 +f 2332/4007/6451 2337/4398/7356 2338/4073/6546 +f 3043/4181/6715 3008/3231/5499 3055/2693/4961 +f 2689/2670/4941 2691/3372/5648 2694/3989/6425 +f 3544/2113/4442 3561/2115/4444 3543/4133/6632 +f 2265/4008/6453 2277/3800/6156 2195/3799/6155 +f 2475/4209/6765 2452/3227/7137 2454/3117/5375 +f 2472/4388/7289 2103/2011/4616 2471/2079/4415 +f 2088/2967/5214 2090/2888/7357 2091/2887/5215 +f 2990/4164/6769 2711/4001/6444 2713/2898/5150 +f 2214/3004/5254 2303/3164/5422 2388/3166/5424 +f 3186/2791/5052 3171/3599/5903 3185/2154/4482 +f 2410/3395/5676 2403/3564/5867 2409/3396/5677 +f 2332/4007/6451 2336/4394/7306 2337/4398/7356 +f 2034/2760/5025 2033/3476/6967 2064/2759/5024 +f 4355/3694/4422 4333/3359/4422 4336/2638/4422 +f 3884/4096/6581 3901/3746/6750 3888/3411/5695 +f 3160/3355/6333 3179/2821/5080 3178/4325/7050 +f 2181/2913/6908 2180/2501/7358 2519/3865/7244 +f 2729/4013/6458 2905/4306/6986 2724/4373/7183 +f 2531/3679/6004 2530/3681/6006 2311/3124/5382 +f 2907/2074/4410 2819/4299/6971 2906/2075/4411 +f 2964/3459/6711 2979/4200/6754 2972/3896/6276 +f 3716/3114/5371 3713/2862/5942 3705/4315/5358 +f 3459/3758/6109 3559/2531/4824 3456/3917/6306 +f 3314/4317/7014 3311/3920/6309 3208/4374/7185 +f 3074/4255/6866 2822/4345/7359 2902/2049/4390 +f 2457/3119/5377 2135/3378/6959 2454/3117/5375 +f 2030/3994/6435 2029/3619/5933 2059/2929/5181 +f 3662/3442/5729 3677/4070/6543 3661/3382/5658 +f 2766/2989/5238 2767/3647/5966 2687/4132/6631 +f 4123/3882/6256 4110/3147/7053 4122/2815/5074 +f 2874/3316/5584 3039/4025/6469 3040/3317/5585 +f 2648/2948/6965 2170/2947/7225 2171/4292/6952 +f 2920/3581/5892 2924/3580/5891 2921/3499/5788 +f 2725/2752/5020 2728/2988/5237 2729/4013/6458 +f 2136/4259/6960 2138/3370/5646 2451/3292/5558 +f 2853/2956/5203 2891/4011/6456 2890/2957/5204 +f 2415/4271/6898 2437/3604/5911 2414/3603/5910 +f 2033/3476/6967 2032/3475/6659 2063/4150/6660 +f 3133/3157/4672 3132/2359/4672 3134/2485/7087 +f 2779/2421/4728 2792/2423/4730 2794/3671/5993 +f 2502/2387/4696 2501/4149/6658 2504/2385/4694 +f 3027/2406/4718 3028/3393/5674 2892/3975/6400 +f 4042/3563/5866 4001/2279/4596 4002/2224/4954 +f 2247/3653/5972 2447/4195/6744 2444/2090/4423 +f 3911/2628/4909 3910/2361/4674 3903/2788/6727 +f 2888/3481/5771 2885/3480/5770 2827/4030/6475 +f 2309/2641/4918 2306/2572/4857 2304/3503/5792 +f 2518/4047/7250 2521/4056/6517 2520/3993/6434 +f 2984/4051/26 2985/4166/26 2931/4049/26 +f 2110/3852/7149 2108/3794/7126 2473/2986/5235 +f 3946/3510/5801 3984/4322/7336 3955/3427/5802 +f 3309/4316/7013 3307/2627/4908 3308/3643/5959 +f 2732/4017/6460 2734/4234/6833 2775/4302/6975 +f 2976/2974/5221 2993/4122/6614 2992/2975/5222 +f 3436/2282/4599 3405/2160/4489 3406/4020/6463 +f 2534/3248/5515 2537/3247/5514 2536/2675/4944 +f 2609/2915/6335 2094/2914/7360 2086/2843/6336 +f 4063/4244/6857 4062/3073/5328 4142/4033/6481 +f 3644/4104/4524 3617/2432/4524 3645/4012/4524 +f 3632/3184/4524 3633/2999/4524 3604/4190/4524 +f 3032/3099/5356 3030/3082/5337 2889/3081/5336 +f 4290/2809/6774 4288/4168/6774 4298/2810/6825 +f 2716/4384/7243 2718/2660/4932 2121/2410/7023 +f 2092/3261/5526 2093/3260/5525 2090/2888/5141 +f 2531/3679/6004 2537/3247/5514 2541/3680/6005 +f 3892/3911/7196 3920/3457/5746 3891/3318/5586 +f 2557/4039/6489 2543/3685/6012 2544/3684/6011 +f 3020/4021/6464 3075/2610/4890 2959/4362/7168 +f 2390/3745/7303 2392/4327/7299 2391/4019/6461 +f 2109/4256/7361 2110/3852/7362 2598/4068/6988 +f 2602/2427/4733 2103/2011/6620 3082/2685/4953 +f 3436/2282/4599 3434/2161/4490 3405/2160/4489 +f 2901/3313/5581 3023/4233/6827 3024/1970/4323 +f 2571/2390/4702 2568/4232/6826 2553/2391/4703 +f 2914/3062/5317 2917/3063/5319 3011/3268/5537 +f 3872/4365/7213 3841/4237/6839 3871/2691/6840 +f 3732/2754/7145 3729/2910/6821 3730/4180/6821 +f 2698/3648/5967 2780/2970/5217 2778/2971/5218 +f 2165/4156/6670 2164/4109/7363 2166/3257/5521 +f 2470/4353/7105 2471/2079/4415 2429/2078/4414 +f 2226/2496/4793 2227/3893/6271 2228/2494/4791 +f 3455/4393/4532 3454/2594/4532 3456/3917/4532 +f 3173/3615/5925 3188/3688/6019 3189/3022/5273 +f 2173/4162/6684 2643/4091/6571 2163/3985/6418 +f 2449/3310/5578 2252/3311/5579 2251/2747/5015 +f 2281/3816/6177 2183/3815/6176 2282/2356/6173 +f 2950/3858/6221 3013/4223/6792 2910/2048/4389 +f 3222/3225/5491 3223/3641/5957 3231/4042/6494 +f 2844/4366/7154 2685/1969/4322 2750/1968/4321 +f 2934/4308/26 2933/2969/26 2972/3896/26 +f 2302/3594/7248 2301/3502/7342 2588/4082/6555 +f 3029/3100/5357 3066/3392/5673 3067/2125/4452 +f 4375/1994/4344 4360/2716/4985 4348/4216/6985 +f 3219/3718/6057 3299/4163/6687 3323/4314/7012 +f 2106/3793/6990 2109/4256/7361 2598/4068/6988 +f 2268/2924/5176 2266/3851/6214 2267/3791/7286 +f 2633/3330/5599 2153/3514/6403 2632/3331/5600 +f 3780/2222/4545 3766/2221/4544 3781/3555/5860 diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 877b3270ce..11518d1b2f 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -56,7 +56,7 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); - AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base); + AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, "examples/Cassie/urdf/cassie_v2_shells.urdf"); if (FLAGS_floating_base) { // Ground direction Eigen::Vector3d ground_normal(sin(FLAGS_ground_incline), 0, From d00c46d7486d421c3b751787aaacc8cc04fe8c34 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 15 Sep 2022 15:25:32 -0400 Subject: [PATCH 314/758] using new meshes for visualization --- examples/Cassie/urdf/cassie_v2_shells.urdf | 909 + .../urdf/meshes/agility/achilles-rod.obj | 6460 + .../Cassie/urdf/meshes/agility/foot-crank.obj | 2288 + examples/Cassie/urdf/meshes/agility/foot.obj | 4048 + .../urdf/meshes/agility/heel-spring.obj | 3246 + .../Cassie/urdf/meshes/agility/hip-pitch.obj | 18176 +++ .../Cassie/urdf/meshes/agility/hip-roll.obj | 9385 ++ .../Cassie/urdf/meshes/agility/hip-yaw.obj | 4782 + .../urdf/meshes/agility/knee-spring.obj | 5643 + examples/Cassie/urdf/meshes/agility/knee.obj | 4543 + .../Cassie/urdf/meshes/agility/pelvis.obj | 98360 ++++++++-------- .../urdf/meshes/agility/plantar-rod.obj | 5035 + examples/Cassie/urdf/meshes/agility/shin.obj | 22185 ++++ .../Cassie/urdf/meshes/agility/tarsus.obj | 24843 ++++ examples/Cassie/visualizer.cc | 2 +- 15 files changed, 162912 insertions(+), 46993 deletions(-) create mode 100644 examples/Cassie/urdf/cassie_v2_shells.urdf create mode 100644 examples/Cassie/urdf/meshes/agility/achilles-rod.obj create mode 100644 examples/Cassie/urdf/meshes/agility/foot-crank.obj create mode 100644 examples/Cassie/urdf/meshes/agility/foot.obj create mode 100644 examples/Cassie/urdf/meshes/agility/heel-spring.obj create mode 100644 examples/Cassie/urdf/meshes/agility/hip-pitch.obj create mode 100644 examples/Cassie/urdf/meshes/agility/hip-roll.obj create mode 100644 examples/Cassie/urdf/meshes/agility/hip-yaw.obj create mode 100644 examples/Cassie/urdf/meshes/agility/knee-spring.obj create mode 100644 examples/Cassie/urdf/meshes/agility/knee.obj create mode 100644 examples/Cassie/urdf/meshes/agility/plantar-rod.obj create mode 100644 examples/Cassie/urdf/meshes/agility/shin.obj create mode 100644 examples/Cassie/urdf/meshes/agility/tarsus.obj diff --git a/examples/Cassie/urdf/cassie_v2_shells.urdf b/examples/Cassie/urdf/cassie_v2_shells.urdf new file mode 100644 index 0000000000..e92e03e89e --- /dev/null +++ b/examples/Cassie/urdf/cassie_v2_shells.urdf @@ -0,0 +1,909 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/Cassie/urdf/meshes/agility/achilles-rod.obj b/examples/Cassie/urdf/meshes/agility/achilles-rod.obj new file mode 100644 index 0000000000..bb9e5c8bcd --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/achilles-rod.obj @@ -0,0 +1,6460 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o achilles-rod +v 0.493264 0.000612 -0.005533 +v 0.495129 -0.001861 -0.007164 +v 0.493521 -0.001920 -0.005476 +v 0.494809 -0.003573 0.006126 +v 0.494500 -0.001991 0.006460 +v 0.493541 -0.001375 0.005639 +v 0.493349 0.002201 0.005103 +v 0.494816 0.003570 0.006131 +v 0.493210 0.003571 0.004174 +v 0.495032 0.002169 -0.006987 +v 0.494782 0.000144 -0.007076 +v 0.492357 -0.003566 0.003275 +v 0.493635 -0.003568 0.004674 +v 0.492735 -0.002468 0.004474 +v 0.489734 -0.003109 0.001830 +v 0.489910 -0.003568 0.000803 +v 0.491197 -0.003559 0.002174 +v 0.490964 -0.003570 -0.001946 +v 0.491383 -0.003026 -0.003089 +v 0.492900 -0.003566 -0.003858 +v 0.487927 0.003095 -0.001014 +v 0.486881 0.002895 -0.001396 +v 0.487444 0.003192 0.000359 +v 0.488422 0.003302 -0.000157 +v 0.489053 0.002956 -0.001766 +v 0.489455 -0.000296 0.003519 +v 0.487924 0.001241 0.002976 +v 0.487653 0.000187 0.003202 +v 0.489065 -0.001235 -0.003186 +v 0.487567 -0.001818 -0.002640 +v 0.489091 -0.000453 -0.003381 +v 0.487289 -0.000743 -0.003123 +v 0.489741 0.003572 -0.000571 +v 0.489883 0.003569 0.000763 +v 0.488465 0.003162 0.000969 +v 0.487888 -0.003192 0.000456 +v 0.489721 -0.003570 -0.000588 +v 0.487884 -0.003164 -0.000600 +v 0.490500 0.003567 -0.001485 +v 0.489687 0.003032 0.001906 +v 0.491120 0.003566 0.002083 +v 0.491032 -0.000071 0.004110 +v 0.489971 0.000760 0.003597 +v 0.487964 -0.002829 0.001550 +v 0.487889 -0.002818 -0.001557 +v 0.489928 -0.002959 -0.002177 +v 0.490300 0.002877 -0.002508 +v 0.488430 -0.001166 0.003120 +v 0.487123 -0.001107 0.003005 +v 0.491882 0.003566 -0.002809 +v 0.488256 0.002327 -0.002309 +v 0.488001 -0.002252 0.002315 +v 0.489698 0.000263 -0.003565 +v 0.487691 0.000771 -0.003128 +v 0.487272 0.001931 -0.002546 +v 0.492250 -0.000876 0.004697 +v 0.491144 -0.001727 0.003762 +v 0.490818 -0.002672 0.003037 +v 0.492829 0.003568 -0.003767 +v 0.490865 0.001896 -0.003577 +v 0.489633 0.001656 -0.003189 +v 0.489714 -0.001877 0.003093 +v 0.492696 0.000204 -0.005080 +v 0.492234 0.001876 -0.004404 +v 0.491265 0.000268 -0.004231 +v 0.493494 0.002468 -0.005130 +v 0.488465 0.001399 -0.002996 +v 0.493807 0.003566 -0.004873 +v 0.492458 -0.001545 -0.004691 +v 0.491601 -0.001890 -0.004004 +v 0.490853 -0.001248 -0.003793 +v 0.490260 -0.002012 -0.003194 +v 0.489078 -0.002139 -0.002671 +v 0.494807 0.003570 -0.006127 +v 0.492521 0.002389 0.004309 +v 0.492034 0.003557 0.002978 +v 0.489939 0.002174 0.002965 +v 0.487896 0.002770 0.001644 +v 0.491062 0.001662 0.003763 +v 0.492460 0.000577 0.004903 +v 0.493577 0.000637 0.005790 +v 0.487916 0.002096 0.002450 +v 0.494687 -0.003575 -0.005947 +v 0.487267 -0.002383 -0.002116 +v 0.510674 -0.000683 0.000948 +v 0.510693 -0.000370 -0.000840 +v 0.510729 0.000360 0.000168 +v 0.494718 -0.000854 0.006961 +v 0.502831 -0.002459 -0.009076 +v 0.504209 -0.003568 -0.008361 +v 0.501754 -0.003571 -0.008830 +v 0.510074 -0.002342 -0.002675 +v 0.509959 -0.003571 -0.001201 +v 0.509580 -0.003571 -0.002850 +v 0.510002 -0.003571 0.000908 +v 0.510328 -0.002762 -0.000280 +v 0.510323 -0.002579 0.001008 +v 0.509497 0.003572 -0.003093 +v 0.509943 0.003572 -0.001325 +v 0.510309 0.002571 -0.001352 +v 0.500774 0.003571 -0.008839 +v 0.500668 0.002450 -0.009214 +v 0.498989 0.003569 -0.008568 +v 0.495126 0.000374 0.007391 +v 0.495930 0.003571 -0.007101 +v 0.495170 0.002115 0.007120 +v 0.495989 0.003570 0.007152 +v 0.495646 -0.002096 0.007511 +v 0.496026 -0.003570 0.007181 +v 0.495475 -0.003565 -0.006775 +v 0.497124 0.003564 -0.007875 +v 0.497310 0.001760 -0.008572 +v 0.497504 0.002439 0.008486 +v 0.497689 0.003572 0.008119 +v 0.499754 0.003573 0.008752 +v 0.496804 -0.002586 0.008110 +v 0.497889 -0.003573 0.008211 +v 0.498170 -0.002152 0.008805 +v 0.500309 -0.003570 0.008828 +v 0.497030 -0.003570 -0.007803 +v 0.496998 -0.002030 -0.008335 +v 0.499544 -0.003572 -0.008727 +v 0.499070 -0.002058 -0.009098 +v 0.496421 0.001314 0.008172 +v 0.500052 0.002167 0.009256 +v 0.501998 0.003566 0.008836 +v 0.501775 0.000938 0.009503 +v 0.503437 0.003566 0.008578 +v 0.503448 0.000908 0.009241 +v 0.497734 0.000361 0.008899 +v 0.499434 0.001213 0.009305 +v 0.500642 -0.000373 0.009533 +v 0.496794 -0.000821 0.008435 +v 0.499315 -0.001143 0.009308 +v 0.501585 -0.001558 0.009436 +v 0.503392 -0.001587 0.009173 +v 0.502463 -0.003571 0.008764 +v 0.504005 -0.003558 0.008415 +v 0.504650 0.000574 0.008904 +v 0.504390 0.003553 0.008291 +v 0.505542 -0.003572 0.007711 +v 0.505208 -0.001965 0.008423 +v 0.506146 -0.000269 0.008169 +v 0.506133 0.001715 0.008019 +v 0.505973 0.003573 0.007452 +v 0.506427 -0.002083 0.007772 +v 0.497411 -0.000650 -0.008758 +v 0.495719 0.000536 -0.007815 +v 0.498486 0.000254 -0.009177 +v 0.499277 0.001523 -0.009237 +v 0.500642 0.000373 -0.009533 +v 0.504347 -0.000598 -0.009016 +v 0.502530 -0.000309 -0.009465 +v 0.502999 0.001563 -0.009264 +v 0.506142 -0.000265 -0.008168 +v 0.506021 0.001053 -0.008179 +v 0.505091 0.002114 -0.008485 +v 0.502676 0.003569 -0.008754 +v 0.506610 0.003562 -0.007040 +v 0.504867 0.003572 -0.008052 +v 0.506899 -0.003565 0.006797 +v 0.507762 0.001743 -0.006717 +v 0.507550 0.000080 -0.007139 +v 0.507330 -0.000250 0.007343 +v 0.507105 0.003563 0.006612 +v 0.507596 0.003573 -0.006123 +v 0.507982 -0.001508 0.006525 +v 0.508022 0.001934 0.006413 +v 0.508285 -0.003568 0.005327 +v 0.508499 -0.000114 0.006176 +v 0.508616 0.003569 0.004868 +v 0.508722 0.003571 -0.004658 +v 0.508819 0.002108 -0.005407 +v 0.508785 -0.000258 -0.005811 +v 0.509147 -0.001503 0.005062 +v 0.509061 0.001829 0.005134 +v 0.509678 0.000717 -0.004376 +v 0.509044 -0.003569 0.004102 +v 0.509364 -0.000247 0.004933 +v 0.509786 0.002018 -0.003722 +v 0.509782 -0.001486 0.003945 +v 0.509897 0.000942 0.003859 +v 0.509965 0.002140 0.003096 +v 0.509641 0.003568 0.002724 +v 0.508905 -0.003574 -0.004345 +v 0.509316 -0.002235 -0.004558 +v 0.507780 -0.003567 -0.005953 +v 0.509688 -0.003565 0.002556 +v 0.504412 -0.002417 -0.008656 +v 0.505692 -0.002074 -0.008187 +v 0.506590 -0.003565 -0.007045 +v 0.507152 -0.001625 -0.007265 +v 0.508150 -0.001947 -0.006280 +v 0.501204 -0.001628 -0.009422 +v 0.509936 -0.001019 -0.003757 +v 0.510372 -0.001850 0.001968 +v 0.510264 -0.000628 0.002917 +v 0.510437 0.001827 0.001601 +v 0.510040 0.003570 0.000617 +v 0.510426 0.000735 -0.002380 +v 0.510442 -0.001944 -0.001309 +v 0.510482 -0.000828 -0.002037 +v 0.510576 0.000380 0.001743 +v 0.510583 0.001657 0.000539 +v 0.510625 -0.001488 0.000085 +v 0.510636 0.001209 -0.000790 +v 0.507090 -0.003572 0.003098 +v 0.507884 -0.003572 -0.000073 +v 0.502770 -0.003572 -0.006498 +v 0.495023 -0.003572 -0.002411 +v 0.494530 -0.003572 0.000441 +v 0.495749 -0.003572 0.003868 +v 0.505486 -0.003572 0.005061 +v 0.505648 -0.003572 -0.004949 +v 0.500175 -0.003572 -0.006535 +v 0.498266 -0.003572 0.005973 +v 0.507158 -0.003572 -0.002913 +v 0.496141 -0.003572 -0.004286 +v 0.503610 -0.003572 0.006178 +v 0.501096 -0.003572 0.006654 +v 0.498124 -0.003572 -0.005902 +v 0.507252 0.003572 -0.002769 +v 0.507676 0.003572 0.001533 +v 0.507787 0.003572 -0.000611 +v 0.495599 0.003572 -0.003549 +v 0.497605 0.003572 -0.005636 +v 0.506402 0.003572 0.004149 +v 0.494749 0.003572 -0.001539 +v 0.500730 0.003572 -0.006638 +v 0.503266 0.003572 -0.006301 +v 0.505491 0.003572 -0.005085 +v 0.504437 0.003572 0.005788 +v 0.501679 0.003572 0.006667 +v 0.495881 0.003572 0.004048 +v 0.498455 0.003572 0.006062 +v 0.494624 0.003572 0.001017 +v 0.507706 -0.000168 -0.000760 +v 0.507731 0.000546 0.000092 +v 0.507736 -0.000204 0.000400 +v 0.505695 -0.004761 -0.000566 +v 0.506361 -0.004019 0.000511 +v 0.505553 -0.004760 0.001122 +v 0.499135 -0.003817 0.004945 +v 0.498693 -0.004761 0.003752 +v 0.500393 -0.004762 0.004456 +v 0.506042 0.004269 0.001151 +v 0.505735 0.004753 -0.000095 +v 0.505520 0.004762 0.001234 +v 0.494809 0.000083 0.001482 +v 0.494664 -0.000201 0.000415 +v 0.494844 -0.001024 0.001176 +v 0.494725 -0.000999 -0.000194 +v 0.494889 -0.001318 -0.001153 +v 0.495106 -0.002419 -0.000318 +v 0.494694 0.000751 -0.000172 +v 0.494722 0.000830 0.000531 +v 0.494798 0.001373 -0.000509 +v 0.495069 -0.001126 0.002095 +v 0.494688 -0.000034 -0.000763 +v 0.495070 0.002098 -0.001055 +v 0.495138 0.002403 0.000773 +v 0.495577 0.003380 -0.000276 +v 0.495274 0.000750 0.002747 +v 0.495428 -0.000944 0.002997 +v 0.495500 0.000347 0.003238 +v 0.495461 0.002762 -0.001601 +v 0.495928 -0.001132 0.003773 +v 0.496012 0.000987 0.003919 +v 0.495731 -0.003563 0.000788 +v 0.495667 -0.003433 -0.000818 +v 0.495040 -0.000767 -0.002111 +v 0.494951 0.000726 -0.001874 +v 0.495259 0.000318 -0.002768 +v 0.494835 -0.001524 0.000408 +v 0.495790 -0.001060 -0.003571 +v 0.495874 0.000270 -0.003835 +v 0.496235 0.003626 -0.002350 +v 0.496048 0.004009 -0.000607 +v 0.496837 0.004758 -0.001196 +v 0.495235 -0.002365 0.001413 +v 0.496665 -0.004757 -0.000285 +v 0.496731 -0.004757 0.000711 +v 0.495461 0.002998 0.000999 +v 0.496056 0.003883 0.001276 +v 0.496731 0.004759 0.000741 +v 0.495502 0.002399 0.002268 +v 0.495728 0.002914 0.002205 +v 0.497061 -0.004745 0.001886 +v 0.496032 -0.003828 -0.001426 +v 0.497187 -0.004746 -0.002145 +v 0.497483 0.004758 -0.002585 +v 0.496354 0.003944 0.001925 +v 0.494969 0.001637 0.001280 +v 0.497200 0.004751 0.002123 +v 0.496045 0.003288 0.002316 +v 0.496126 -0.003784 0.001751 +v 0.495224 -0.002197 -0.001721 +v 0.496354 -0.003845 -0.002116 +v 0.496465 0.003808 0.002411 +v 0.495015 0.001171 0.001825 +v 0.496045 0.003045 0.002627 +v 0.496750 0.003685 0.003155 +v 0.495776 -0.002581 0.002671 +v 0.496465 -0.003778 0.002459 +v 0.495762 -0.003223 0.001672 +v 0.495432 -0.002601 -0.001647 +v 0.495674 -0.002823 -0.001926 +v 0.497177 -0.002032 -0.004736 +v 0.496602 -0.001047 -0.004582 +v 0.497716 -0.001432 -0.005373 +v 0.495947 0.002686 0.002821 +v 0.497466 0.004754 0.002602 +v 0.495590 0.001936 0.002748 +v 0.495590 0.002225 0.002517 +v 0.495872 0.002060 0.003167 +v 0.496144 0.002822 0.003037 +v 0.497455 -0.004754 0.002585 +v 0.497160 -0.003963 -0.003319 +v 0.497866 -0.004759 -0.003032 +v 0.496329 -0.003433 -0.002728 +v 0.496021 -0.002874 -0.002877 +v 0.496565 -0.002670 -0.003817 +v 0.497177 -0.002374 -0.004574 +v 0.497566 -0.002444 -0.004856 +v 0.496692 0.003838 -0.002772 +v 0.496465 -0.003553 0.002773 +v 0.496808 -0.003819 -0.002981 +v 0.495286 -0.001778 -0.002234 +v 0.495590 -0.001692 -0.002903 +v 0.496144 -0.002045 -0.003609 +v 0.496808 -0.002388 -0.004215 +v 0.498382 -0.003172 -0.005019 +v 0.497131 0.004150 -0.003061 +v 0.497358 -0.003524 -0.004025 +v 0.497910 -0.003777 0.004269 +v 0.496929 -0.003788 0.003186 +v 0.498653 -0.004349 -0.004169 +v 0.498728 -0.004760 -0.003766 +v 0.498333 0.004755 -0.003519 +v 0.496808 0.003668 -0.003164 +v 0.495432 -0.001925 -0.002405 +v 0.495590 -0.002068 -0.002650 +v 0.496465 -0.002773 -0.003553 +v 0.497051 -0.003661 0.003485 +v 0.496465 -0.003302 0.003069 +v 0.499946 -0.004762 -0.004319 +v 0.498356 0.004752 0.003549 +v 0.496808 -0.003341 -0.003509 +v 0.499828 -0.003663 -0.005286 +v 0.496398 -0.002705 0.003512 +v 0.500270 0.004760 -0.004441 +v 0.498777 0.003811 -0.004749 +v 0.497704 0.003288 -0.004524 +v 0.496639 0.002670 -0.003907 +v 0.496354 0.003065 -0.003141 +v 0.496144 0.002860 -0.003004 +v 0.495676 0.002411 -0.002533 +v 0.498662 0.003761 0.004731 +v 0.497784 0.003975 0.003996 +v 0.497177 0.003598 0.003689 +v 0.496808 0.003509 0.003341 +v 0.501185 -0.004758 -0.004526 +v 0.495592 0.001591 -0.003037 +v 0.501163 -0.000607 0.006544 +v 0.499865 0.000727 0.006394 +v 0.499601 -0.000996 0.006298 +v 0.498869 0.000744 0.006089 +v 0.498573 -0.000513 0.006007 +v 0.497698 -0.000950 0.005479 +v 0.497271 0.000226 0.005251 +v 0.496611 -0.000393 0.004685 +v 0.501287 -0.001884 0.006296 +v 0.502795 -0.002023 0.006037 +v 0.502485 -0.000478 0.006419 +v 0.498048 -0.002108 0.005350 +v 0.496884 -0.002096 0.004498 +v 0.498511 -0.002554 0.005436 +v 0.499950 -0.002477 0.005942 +v 0.501677 -0.003021 0.005809 +v 0.500546 -0.003705 0.005384 +v 0.497566 -0.003130 0.004445 +v 0.497304 -0.003024 0.004294 +v 0.495735 -0.002228 0.002892 +v 0.502161 -0.003801 0.005266 +v 0.497051 -0.003301 0.003827 +v 0.502263 -0.004759 0.004405 +v 0.502498 -0.003855 -0.005155 +v 0.503088 -0.004762 -0.004118 +v 0.501452 -0.003774 -0.005356 +v 0.501067 -0.003032 -0.005827 +v 0.502811 -0.002638 -0.005804 +v 0.500008 -0.001952 -0.006160 +v 0.498929 -0.002075 -0.005806 +v 0.501471 -0.001793 -0.006310 +v 0.501710 -0.000878 -0.006496 +v 0.499516 -0.000720 -0.006319 +v 0.498110 0.000041 -0.005793 +v 0.497252 -0.000118 -0.005214 +v 0.500724 0.000297 -0.006544 +v 0.502366 -0.000025 -0.006462 +v 0.499759 0.001182 -0.006293 +v 0.498314 0.001085 -0.005811 +v 0.496951 0.000855 -0.004911 +v 0.502197 0.001230 -0.006366 +v 0.500832 0.001626 -0.006345 +v 0.496181 0.001268 -0.003992 +v 0.501885 0.002184 -0.006147 +v 0.499044 0.002388 -0.005733 +v 0.502799 0.002553 -0.005822 +v 0.497299 0.002443 -0.004702 +v 0.500089 0.002759 -0.005850 +v 0.498228 0.002705 -0.005175 +v 0.501479 0.003065 -0.005799 +v 0.496249 0.001730 -0.003903 +v 0.501540 0.003789 -0.005375 +v 0.499762 0.003901 -0.005069 +v 0.497746 0.002937 -0.004709 +v 0.495947 0.002544 -0.002949 +v 0.495288 0.001826 -0.002117 +v 0.502140 0.004762 -0.004421 +v 0.503262 0.003839 -0.004903 +v 0.503658 -0.003773 0.004780 +v 0.503340 -0.002911 0.005437 +v 0.503214 -0.001272 -0.006099 +v 0.503907 -0.001514 0.005798 +v 0.503377 -0.000118 0.006181 +v 0.503678 0.004745 -0.003817 +v 0.503474 0.001229 -0.006034 +v 0.503453 -0.000225 -0.006154 +v 0.503567 -0.003731 -0.004880 +v 0.503764 -0.004758 0.003731 +v 0.504108 0.002590 -0.005279 +v 0.504046 -0.001929 -0.005579 +v 0.504629 -0.002968 0.004784 +v 0.504467 -0.000894 0.005630 +v 0.504474 0.003693 -0.004295 +v 0.504693 0.001554 -0.005332 +v 0.504368 0.000485 -0.005728 +v 0.504579 -0.000636 -0.005593 +v 0.504551 -0.003143 -0.004724 +v 0.504929 -0.003708 -0.003922 +v 0.504447 -0.004751 -0.003183 +v 0.504626 -0.004750 0.002969 +v 0.504921 -0.003521 0.004147 +v 0.504655 0.004750 -0.002962 +v 0.504423 -0.001917 -0.005356 +v 0.504563 -0.002273 -0.005127 +v 0.504698 -0.002664 -0.004838 +v 0.505236 -0.002453 0.004530 +v 0.504959 0.003937 -0.003559 +v 0.505415 0.002113 -0.004559 +v 0.505376 -0.001183 -0.004921 +v 0.505060 -0.002094 -0.004817 +v 0.505044 0.004755 0.002416 +v 0.503877 0.004756 0.003671 +v 0.505453 0.004185 0.002792 +v 0.504834 0.003937 0.003749 +v 0.504719 0.003481 0.004321 +v 0.503304 0.003646 0.005071 +v 0.502221 0.004758 0.004423 +v 0.501474 0.003641 0.005472 +v 0.500063 0.004760 0.004397 +v 0.499785 0.004189 0.004852 +v 0.497051 0.003301 0.003827 +v 0.496692 0.003135 0.003548 +v 0.496354 0.002742 0.003426 +v 0.500203 0.003370 0.005548 +v 0.497246 0.002522 0.004606 +v 0.496575 0.002844 0.003645 +v 0.496808 0.002790 0.003961 +v 0.496144 0.002388 0.003391 +v 0.498505 0.002741 0.005332 +v 0.497566 0.002909 0.004593 +v 0.496465 0.002411 0.003808 +v 0.495762 0.001788 0.003157 +v 0.502750 0.002645 0.005811 +v 0.496929 0.002491 0.004277 +v 0.496462 0.001484 0.004296 +v 0.504316 0.002117 0.005383 +v 0.501195 0.002125 0.006212 +v 0.499943 0.001972 0.006127 +v 0.497817 0.001334 0.005477 +v 0.498677 0.002180 0.005678 +v 0.503237 0.001139 0.006130 +v 0.502085 0.001132 0.006407 +v 0.504263 0.000962 0.005725 +v 0.505213 0.001793 0.004901 +v 0.501008 0.000771 0.006509 +v 0.505144 0.000359 0.005230 +v 0.505223 0.003415 -0.003860 +v 0.505223 0.003121 -0.004101 +v 0.505487 0.000324 -0.004948 +v 0.505096 -0.003804 0.003621 +v 0.505096 -0.003231 0.004140 +v 0.505457 -0.001311 0.004833 +v 0.505349 0.003661 -0.003485 +v 0.505462 -0.002319 -0.004356 +v 0.505784 -0.002464 -0.003956 +v 0.505349 -0.003110 -0.003985 +v 0.506020 -0.003750 -0.002486 +v 0.505173 -0.004757 -0.002145 +v 0.505349 -0.003827 0.003301 +v 0.505471 -0.003094 0.003864 +v 0.505471 0.002598 0.004213 +v 0.505349 0.003110 0.003985 +v 0.505239 0.004750 -0.002079 +v 0.505592 0.003819 -0.002981 +v 0.505709 0.003509 -0.003180 +v 0.505592 0.003341 -0.003509 +v 0.505709 0.002957 -0.003697 +v 0.506169 0.001398 -0.004069 +v 0.505142 -0.004756 0.002226 +v 0.505592 -0.003819 0.002981 +v 0.505709 -0.003509 0.003180 +v 0.505592 -0.003341 0.003509 +v 0.505923 -0.000057 0.004550 +v 0.505592 0.002790 0.003961 +v 0.505592 0.003164 0.003669 +v 0.505709 0.003389 0.003305 +v 0.505595 0.004749 -0.001162 +v 0.505936 0.004026 -0.002026 +v 0.505943 0.003479 -0.002743 +v 0.505825 0.003188 -0.003348 +v 0.505825 0.002662 -0.003780 +v 0.506101 -0.001043 -0.004262 +v 0.505936 -0.002901 -0.003450 +v 0.505936 -0.003975 0.002218 +v 0.505936 -0.003553 0.002773 +v 0.505825 -0.003188 0.003349 +v 0.506087 -0.002831 0.003395 +v 0.505936 -0.002595 0.003685 +v 0.505936 -0.002222 0.003922 +v 0.505936 -0.001827 0.004121 +v 0.506317 -0.000930 0.004002 +v 0.506080 0.001315 0.004204 +v 0.505825 0.002662 0.003780 +v 0.505825 0.003020 0.003501 +v 0.505936 0.003413 0.002944 +v 0.506151 0.002284 0.003607 +v 0.506151 0.002627 0.003366 +v 0.506151 0.002944 0.003092 +v 0.506046 0.003845 0.002116 +v 0.506046 0.003288 -0.002907 +v 0.506165 0.002838 -0.003059 +v 0.506151 0.002458 -0.003491 +v 0.506494 0.000525 -0.003834 +v 0.506577 -0.003407 0.001603 +v 0.506046 -0.003180 0.003028 +v 0.506355 0.003106 0.002553 +v 0.506256 0.003391 0.002388 +v 0.506256 0.003632 0.001999 +v 0.506714 0.003361 -0.001133 +v 0.506271 0.003540 -0.002266 +v 0.506256 0.003141 -0.002709 +v 0.506671 -0.001907 -0.003122 +v 0.506256 -0.002219 -0.003504 +v 0.506256 -0.002591 -0.003237 +v 0.506268 -0.003632 -0.002084 +v 0.506773 -0.003485 -0.000278 +v 0.506256 -0.003419 0.002345 +v 0.506355 -0.003045 0.002627 +v 0.506256 -0.002822 0.003037 +v 0.506654 0.001054 0.003502 +v 0.506454 0.002433 0.003039 +v 0.506454 0.002821 0.002686 +v 0.506561 0.003357 0.001869 +v 0.506454 0.003498 0.001708 +v 0.506733 0.003529 0.000365 +v 0.506546 0.003077 -0.002167 +v 0.506454 0.002916 -0.002579 +v 0.506454 0.002433 -0.003039 +v 0.506454 0.002084 -0.003291 +v 0.506820 -0.000822 -0.003315 +v 0.506454 -0.002786 -0.002719 +v 0.506546 -0.002595 0.002726 +v 0.506454 -0.002357 0.003098 +v 0.506454 -0.001793 0.003456 +v 0.507002 0.001471 0.002716 +v 0.506638 0.002471 0.002660 +v 0.506638 0.002835 0.002269 +v 0.506638 0.002751 -0.002373 +v 0.506638 0.002471 -0.002660 +v 0.506638 0.002054 -0.002994 +v 0.506546 -0.003044 -0.002258 +v 0.507033 -0.002869 -0.000974 +v 0.506638 -0.002235 0.002864 +v 0.506638 -0.001828 0.003137 +v 0.506901 -0.001316 0.002978 +v 0.506810 0.002432 0.002315 +v 0.506810 0.002837 0.001796 +v 0.507092 0.002739 0.000948 +v 0.506810 0.002674 -0.002034 +v 0.506810 0.002315 -0.002432 +v 0.507015 0.001911 -0.002337 +v 0.507158 0.000539 -0.002710 +v 0.507142 -0.002048 -0.001947 +v 0.507027 -0.002655 0.001503 +v 0.506810 -0.002066 0.002647 +v 0.506904 -0.000001 0.003224 +v 0.507118 0.001678 0.002237 +v 0.507302 0.002083 0.001257 +v 0.506968 0.002427 -0.001894 +v 0.506968 0.002097 -0.002257 +v 0.507324 -0.001583 0.001788 +v 0.507329 -0.000181 0.002341 +v 0.507402 0.002110 -0.000452 +v 0.507133 0.002502 -0.000938 +v 0.507399 -0.000764 -0.002027 +v 0.507387 0.001518 -0.001503 +v 0.507466 -0.001915 0.000396 +v 0.507560 0.000683 0.001453 +v 0.507488 0.000473 -0.001794 +v 0.507576 -0.001337 -0.000826 +v 0.507575 -0.000401 0.001473 +v 0.507633 0.001198 0.000385 +v 0.507649 0.000795 -0.000872 +v 0.507638 -0.000935 0.000766 +v 0.507682 -0.000912 -0.000167 +v 0.504605 -0.004762 0.000889 +v 0.503717 -0.004762 0.002479 +v 0.500191 -0.004762 -0.003407 +v 0.503379 -0.004762 -0.002770 +v 0.502071 -0.004762 -0.003399 +v 0.497795 -0.004762 0.000941 +v 0.497751 -0.004762 -0.000664 +v 0.498883 -0.004762 0.002673 +v 0.502349 -0.004762 0.003319 +v 0.498419 -0.004762 -0.002188 +v 0.504595 -0.004762 -0.001088 +v 0.500697 -0.004762 0.003502 +v 0.504714 0.004762 0.000611 +v 0.502988 0.004762 -0.003095 +v 0.504406 0.004762 -0.001463 +v 0.503740 0.004762 0.002425 +v 0.500349 0.004762 -0.003470 +v 0.498193 0.004762 -0.001932 +v 0.502510 0.004762 0.003271 +v 0.498515 0.004762 0.002330 +v 0.500527 0.004762 0.003491 +v 0.497680 0.004762 0.000341 +v 0.501665 -0.004443 -0.003192 +v 0.500669 0.004442 -0.003146 +v 0.499957 -0.004446 -0.002952 +v 0.499392 0.004445 -0.002643 +v 0.498909 -0.004446 -0.002218 +v 0.498300 0.004444 -0.001388 +v 0.498271 -0.004444 -0.001268 +v 0.498017 -0.004444 -0.000160 +v 0.498008 0.004447 0.000178 +v 0.498173 -0.004442 0.001025 +v 0.498286 0.004446 0.001288 +v 0.498927 -0.004446 0.002241 +v 0.499158 0.004440 0.002483 +v 0.500270 -0.004446 0.003086 +v 0.500685 0.004444 0.003160 +v 0.502162 -0.004444 0.003068 +v 0.502038 0.004445 0.003079 +v 0.503423 0.004445 0.002330 +v 0.503556 -0.004441 0.002166 +v 0.504303 -0.004443 0.000768 +v 0.504283 0.004442 0.000826 +v 0.504338 0.004444 -0.000701 +v 0.504332 -0.004445 -0.000668 +v 0.503801 -0.004445 -0.001843 +v 0.503688 0.004446 -0.001994 +v 0.503072 -0.004447 -0.002579 +v 0.502843 0.004445 -0.002738 +v 0.501850 0.004445 -0.003117 +v 0.013985 0.003203 -0.000048 +v 0.013952 0.002860 -0.001418 +v 0.013374 0.003129 -0.000819 +v 0.010710 0.003571 -0.001502 +v 0.011614 0.003571 0.000195 +v 0.012088 0.003275 -0.001055 +v 0.012812 -0.003263 0.000598 +v 0.013585 -0.003111 -0.000812 +v 0.013951 -0.003190 0.000126 +v 0.011476 -0.000891 0.003465 +v 0.013570 -0.001164 0.002985 +v 0.013364 -0.000001 0.003243 +v 0.012748 0.003286 0.000543 +v 0.013920 0.002969 0.001169 +v 0.011504 -0.003564 -0.000469 +v 0.014277 0.000279 0.003192 +v 0.013063 0.000739 -0.003167 +v 0.013662 0.001724 -0.002702 +v 0.014312 0.000234 -0.003206 +v 0.011313 -0.003570 0.000763 +v 0.012117 -0.003200 0.001226 +v 0.011584 0.000264 0.003545 +v 0.012140 0.003084 0.001509 +v 0.012112 -0.002921 -0.001762 +v 0.010647 -0.003569 -0.001541 +v 0.012121 -0.002812 0.001919 +v 0.009957 -0.003568 0.002205 +v 0.010465 0.003564 0.001752 +v 0.012094 0.002844 -0.001868 +v 0.013865 -0.002340 -0.002205 +v 0.009834 -0.000003 0.004288 +v 0.010948 0.000930 0.003657 +v 0.010945 0.002904 0.002414 +v 0.012339 0.002504 0.002290 +v 0.013576 0.002317 0.002227 +v 0.011495 0.000807 -0.003507 +v 0.013061 -0.000221 -0.003245 +v 0.009369 -0.003569 -0.002752 +v 0.011251 -0.002584 -0.002595 +v 0.009846 0.002950 -0.003053 +v 0.009112 0.003571 -0.003002 +v 0.009316 0.000527 -0.004533 +v 0.010283 0.000791 -0.003982 +v 0.010902 -0.000395 -0.003743 +v 0.009471 -0.001169 -0.004319 +v 0.010374 -0.002338 -0.003265 +v 0.012731 -0.002167 -0.002492 +v 0.009277 0.001908 0.004151 +v 0.012130 0.001454 0.003104 +v 0.013561 0.001410 0.002886 +v 0.010459 0.002275 0.003246 +v 0.008947 -0.002524 -0.004067 +v 0.008195 0.003568 0.003932 +v 0.007823 -0.001315 -0.005485 +v 0.013300 -0.001248 -0.002971 +v 0.007458 -0.003565 -0.004807 +v 0.011278 -0.001521 -0.003336 +v 0.009469 -0.002749 0.003506 +v 0.007978 -0.003570 0.004182 +v 0.007932 0.003569 -0.004239 +v 0.007864 -0.001979 0.005243 +v 0.006353 -0.003565 0.006181 +v 0.006382 0.003569 0.006142 +v 0.007801 0.001957 0.005323 +v 0.005982 0.003570 -0.006574 +v 0.007686 0.002485 -0.005200 +v 0.006451 -0.000399 -0.007015 +v 0.007935 0.000670 -0.005497 +v 0.009789 0.001821 -0.003885 +v 0.010859 0.002137 -0.003167 +v 0.012147 0.002153 -0.002682 +v 0.006546 -0.003571 -0.005945 +v 0.006352 -0.002276 -0.006763 +v 0.013920 -0.002964 0.001181 +v 0.010964 -0.002253 0.003047 +v 0.009520 -0.001680 0.004093 +v 0.012159 -0.001930 0.002847 +v 0.007652 -0.000003 0.005800 +v 0.006262 -0.001392 0.007088 +v 0.013656 -0.002237 0.002310 +v 0.008687 -0.000777 0.004896 +v 0.008743 0.000444 0.004900 +v 0.006553 0.001561 0.006763 +v 0.008596 0.001973 -0.004623 +v 0.006297 0.001240 -0.007087 +v 0.006483 0.002741 -0.006431 +v 0.013969 0.002334 -0.002168 +v -0.009459 0.001033 0.000707 +v -0.009471 0.001159 -0.000209 +v -0.009520 -0.000610 -0.000284 +v -0.009467 -0.000409 0.001143 +v 0.006233 0.000245 0.007232 +v -0.001931 0.002589 -0.008985 +v -0.002360 0.003570 -0.008530 +v -0.000007 0.003572 -0.008864 +v -0.008936 0.002292 -0.002463 +v -0.008797 0.003571 -0.000940 +v -0.008379 0.003570 -0.002857 +v -0.009137 0.002660 -0.000671 +v -0.009134 0.002643 0.000741 +v -0.008748 0.003571 0.001321 +v -0.000007 -0.003572 0.008864 +v -0.001930 -0.002589 0.008985 +v -0.002360 -0.003570 0.008530 +v -0.004392 -0.003560 -0.007718 +v -0.005818 -0.003572 -0.006666 +v -0.005778 -0.002286 -0.007255 +v 0.005225 -0.003564 -0.007160 +v 0.004120 -0.002229 -0.008323 +v 0.003008 -0.003563 -0.008355 +v 0.005481 -0.003567 0.006954 +v 0.004338 -0.002288 0.008205 +v 0.004172 -0.003571 0.007802 +v 0.002658 -0.003562 0.008460 +v 0.001567 -0.002584 0.009052 +v 0.005226 0.003564 0.007160 +v 0.004118 0.002224 0.008323 +v 0.003008 0.003564 0.008355 +v 0.004539 0.001688 -0.008255 +v 0.004059 0.003568 -0.007872 +v 0.002658 0.003562 -0.008459 +v 0.001567 0.002583 -0.009052 +v -0.000346 -0.001686 0.009408 +v 0.004467 -0.000733 0.008428 +v 0.002056 -0.001443 0.009223 +v -0.001689 0.000090 0.009419 +v 0.002455 -0.000086 0.009222 +v 0.000531 -0.000312 0.009524 +v 0.005219 0.001277 0.007900 +v 0.003260 0.001179 0.008907 +v 0.001463 0.001537 0.009316 +v -0.000013 0.001623 0.009422 +v -0.002209 0.001487 0.009192 +v 0.000882 0.003571 0.008824 +v -0.001843 0.003573 0.008679 +v -0.003120 0.002506 0.008667 +v -0.003229 -0.000960 0.008945 +v -0.003308 -0.003562 0.008247 +v -0.004338 0.003571 0.007712 +v -0.004222 0.001183 0.008481 +v -0.005217 0.002329 0.007666 +v -0.004774 -0.000607 0.008245 +v -0.004769 -0.002080 0.008005 +v -0.005636 0.000186 0.007717 +v -0.005276 -0.003569 0.007114 +v 0.002117 0.000869 -0.009289 +v 0.002677 -0.000896 -0.009127 +v 0.001463 -0.001537 -0.009316 +v -0.000089 -0.000312 -0.009538 +v -0.001330 0.000930 -0.009419 +v -0.002254 -0.001005 -0.009232 +v -0.003295 0.000903 -0.008935 +v -0.004201 -0.000915 -0.008535 +v -0.000089 -0.001863 -0.009368 +v 0.005362 -0.001009 -0.007850 +v 0.004039 -0.000210 -0.008659 +v -0.002556 -0.002339 -0.008925 +v -0.005349 -0.000506 -0.007888 +v 0.000882 -0.003571 -0.008824 +v -0.001843 -0.003573 -0.008679 +v -0.005818 0.003572 0.006666 +v -0.006107 -0.001895 0.007098 +v -0.006817 -0.001487 -0.006538 +v -0.005675 0.000659 -0.007662 +v -0.006777 0.002575 0.006204 +v -0.006558 0.001136 0.006839 +v -0.006648 -0.003571 0.005852 +v -0.007144 -0.003570 -0.005235 +v -0.007495 -0.000042 -0.005947 +v -0.007186 0.003571 0.005161 +v -0.007234 -0.000265 0.006226 +v -0.007169 -0.001776 0.006050 +v -0.007720 0.001661 0.005401 +v -0.007954 -0.002009 -0.004885 +v -0.008084 -0.002167 0.004606 +v -0.007629 -0.003570 0.004488 +v -0.007982 -0.003565 -0.003830 +v -0.007982 0.003566 0.003830 +v -0.008279 -0.000330 0.004741 +v -0.008452 -0.000521 -0.004406 +v -0.008588 0.001569 0.003899 +v -0.008447 -0.003567 0.002692 +v -0.007652 0.003571 -0.004444 +v -0.008338 0.001792 -0.004328 +v -0.006532 0.003569 -0.005977 +v -0.007540 0.002231 -0.005440 +v -0.008499 -0.003566 -0.002511 +v -0.008678 -0.002007 -0.003403 +v -0.008499 0.003566 0.002511 +v -0.008727 -0.001535 0.003562 +v -0.005276 0.003569 -0.007114 +v -0.006331 0.002082 -0.006837 +v -0.003308 0.003562 -0.008248 +v -0.004772 0.002083 -0.008004 +v 0.000200 0.001640 -0.009421 +v -0.008993 0.000695 -0.003165 +v -0.009051 0.000402 0.003029 +v -0.009065 -0.000791 -0.002886 +v -0.009251 0.001489 0.001873 +v -0.009111 -0.001380 0.002474 +v -0.009246 -0.002022 0.001302 +v -0.008849 -0.003569 0.000548 +v -0.008748 -0.003571 -0.001321 +v -0.009190 -0.002072 -0.001585 +v -0.009305 0.001694 -0.001255 +v -0.009310 -0.002085 -0.000108 +v -0.009422 0.000031 -0.001564 +v -0.006425 0.003572 0.001735 +v -0.005289 0.003572 0.004001 +v -0.006550 0.003572 -0.001173 +v -0.000471 0.003572 -0.006638 +v 0.006654 0.003572 0.000079 +v 0.005984 0.003572 0.002911 +v -0.003396 0.003572 0.005723 +v -0.001001 0.003572 0.006556 +v -0.003259 0.003572 -0.005802 +v 0.005300 0.003572 -0.004025 +v 0.004169 0.003572 0.005187 +v -0.005423 0.003572 -0.003857 +v 0.002752 0.003572 -0.006092 +v 0.006294 0.003572 -0.002036 +v 0.001557 0.003572 0.006470 +v -0.006052 -0.003572 -0.002768 +v -0.006654 -0.003572 0.000079 +v -0.005984 -0.003572 0.002911 +v 0.003822 -0.003572 -0.005399 +v 0.005423 -0.003572 -0.003857 +v 0.006550 -0.003572 -0.001173 +v 0.001911 -0.003572 -0.006374 +v -0.004018 -0.003572 -0.005343 +v -0.000992 -0.003572 -0.006580 +v -0.003900 -0.003572 0.005429 +v -0.000836 -0.003572 0.006602 +v 0.006425 -0.003572 0.001735 +v 0.002412 -0.003572 0.006234 +v 0.005070 -0.003572 0.004311 +v -0.006514 -0.000532 -0.000438 +v -0.006522 -0.000511 0.000319 +v -0.006531 0.000610 0.000020 +v -0.003635 0.004763 0.002657 +v -0.004339 0.004755 0.001291 +v -0.004559 0.003957 0.002578 +v -0.005088 -0.004132 0.000428 +v -0.004512 -0.004762 -0.000368 +v -0.004285 -0.004762 0.001385 +v -0.004826 -0.004250 -0.001316 +v -0.004008 -0.004758 -0.002069 +v -0.001483 -0.003977 -0.005014 +v -0.000012 -0.004761 -0.004520 +v -0.002213 -0.004752 -0.004000 +v 0.006534 0.000396 0.000267 +v 0.006520 0.000107 -0.000631 +v 0.006473 0.000933 -0.000333 +v 0.006334 0.001692 0.000269 +v 0.006350 0.001224 -0.001068 +v 0.006058 0.002379 -0.000765 +v 0.005986 0.000243 0.002667 +v 0.006419 0.000394 0.001303 +v 0.006221 0.001164 0.001726 +v 0.006355 -0.001447 -0.000725 +v 0.006452 -0.000932 0.000719 +v 0.006191 -0.002125 0.000509 +v 0.006495 -0.000679 -0.000458 +v 0.006530 -0.000362 0.000314 +v 0.006016 -0.002576 -0.000344 +v 0.005932 0.002808 0.000208 +v 0.005263 -0.000367 0.003907 +v 0.005371 0.000615 0.003707 +v 0.006084 0.000877 -0.002280 +v 0.006381 -0.000060 -0.001532 +v 0.005947 -0.000406 -0.002749 +v 0.005482 -0.003453 -0.001063 +v 0.005508 -0.003576 -0.000046 +v 0.005542 0.000854 -0.003395 +v 0.005560 -0.000103 -0.003476 +v 0.004683 0.001171 -0.004445 +v 0.004725 -0.000161 -0.004553 +v 0.004762 -0.004076 -0.001944 +v 0.004431 -0.004758 -0.000868 +v 0.005489 0.003332 -0.001361 +v 0.005110 0.004064 -0.000620 +v 0.005478 0.003599 0.000454 +v 0.004505 0.004761 0.000452 +v 0.004257 0.004757 -0.001559 +v 0.005975 -0.002227 -0.001518 +v 0.004493 -0.004761 0.000510 +v 0.005570 -0.003212 0.001269 +v 0.006174 -0.001660 0.001429 +v 0.005047 -0.003961 0.001425 +v 0.005753 -0.002394 0.002050 +v 0.003871 0.004761 0.002319 +v 0.004850 0.004137 0.001557 +v 0.005849 0.002590 0.001504 +v 0.003911 -0.004761 -0.002262 +v 0.005087 -0.003291 0.002524 +v 0.003992 -0.004760 0.002098 +v 0.006203 -0.000771 0.001983 +v 0.005263 0.002114 -0.003304 +v 0.005397 -0.002316 0.002912 +v 0.004043 -0.004059 0.003202 +v 0.004931 0.003573 0.002445 +v 0.004527 0.003986 -0.002593 +v 0.005385 0.002993 -0.002251 +v 0.003499 0.004761 -0.002836 +v 0.006010 0.002037 -0.001642 +v 0.005780 0.001683 -0.002601 +v 0.005411 -0.002867 -0.002363 +v 0.005803 -0.001061 0.002865 +v 0.004100 0.004022 0.003125 +v 0.004529 0.002549 -0.004005 +v 0.003971 0.001738 -0.004929 +v 0.004358 -0.003834 -0.003074 +v 0.002679 0.004763 0.003637 +v 0.003521 0.003866 0.003972 +v 0.002793 -0.004757 -0.003569 +v 0.003390 0.002734 -0.004919 +v 0.004834 0.002840 0.003436 +v 0.003548 0.003873 -0.003930 +v 0.002557 0.004760 -0.003719 +v 0.004626 0.003299 -0.003272 +v 0.006091 -0.001414 -0.001996 +v 0.002931 -0.004023 0.004280 +v 0.002881 -0.004761 0.003495 +v 0.002539 0.003980 -0.004555 +v 0.002193 0.003084 -0.005366 +v 0.005723 0.002223 0.002298 +v 0.001318 0.004032 -0.005010 +v 0.003840 -0.003500 -0.004015 +v 0.004416 -0.003257 0.003590 +v 0.001588 0.004761 -0.004206 +v 0.001415 0.004749 0.004310 +v 0.002476 0.004086 0.004473 +v 0.000012 0.004761 -0.004520 +v 0.001432 -0.004761 -0.004268 +v 0.002429 -0.003792 -0.004772 +v 0.004902 -0.002455 -0.003623 +v 0.001440 -0.004760 0.004265 +v 0.004132 0.000279 -0.005080 +v -0.001124 0.001107 0.006383 +v -0.002061 -0.000758 0.006200 +v -0.000425 -0.000294 0.006553 +v 0.000491 0.000697 0.006501 +v 0.001148 -0.000650 0.006436 +v 0.002271 0.000736 0.006129 +v 0.002538 -0.000545 0.006029 +v 0.003775 0.000261 0.005360 +v 0.004621 0.000141 0.004662 +v 0.000297 0.002055 0.006237 +v 0.001629 0.001659 0.006129 +v 0.003837 0.001472 0.005125 +v 0.004807 0.001824 0.004084 +v -0.001025 0.002632 0.005922 +v -0.002063 0.001715 0.006004 +v 0.002547 0.002193 0.005636 +v 0.003764 0.002567 0.004729 +v 0.005678 0.001431 0.002955 +v 0.001126 0.003334 0.005560 +v 0.002455 0.003157 0.005219 +v -0.000057 0.003667 0.005447 +v -0.001526 0.003859 0.005086 +v 0.000028 0.004761 0.004521 +v -0.001440 0.004760 0.004265 +v -0.001393 0.003914 -0.005076 +v -0.001432 0.004761 -0.004268 +v 0.000000 0.003704 -0.005425 +v -0.001302 0.002542 -0.005916 +v 0.000837 0.002472 -0.006029 +v -0.000284 0.001946 -0.006278 +v 0.002023 0.001918 -0.005938 +v 0.002817 0.001365 -0.005769 +v -0.001616 0.000861 -0.006303 +v 0.000824 0.001022 -0.006429 +v 0.001847 0.000702 -0.006248 +v -0.000026 -0.000013 -0.006574 +v 0.003148 0.000426 -0.005741 +v -0.000962 -0.000161 -0.006486 +v 0.001282 -0.000399 -0.006419 +v 0.002465 -0.000533 -0.006061 +v 0.003736 -0.000742 -0.005336 +v -0.001184 -0.001489 -0.006294 +v -0.001954 -0.000617 -0.006234 +v 0.000296 -0.001639 -0.006350 +v 0.005061 -0.001187 -0.004003 +v 0.001888 -0.001895 -0.006000 +v 0.003017 -0.001618 -0.005596 +v 0.004057 -0.001600 -0.004896 +v 0.001028 -0.002630 -0.005922 +v -0.000392 -0.002948 -0.005857 +v 0.005471 -0.001728 -0.003182 +v -0.001720 -0.002867 -0.005640 +v 0.002404 -0.002893 -0.005386 +v 0.003668 -0.002813 -0.004660 +v 0.000047 -0.003743 -0.005396 +v 0.001393 -0.003914 -0.005076 +v -0.002405 0.002891 0.005385 +v -0.002397 0.002923 -0.005373 +v -0.002730 0.000157 0.005973 +v -0.002556 -0.002016 -0.005705 +v -0.002539 0.001731 -0.005806 +v -0.002433 0.003796 -0.004773 +v -0.002587 0.004762 0.003690 +v -0.002691 0.003748 0.004669 +v -0.002793 0.004756 -0.003569 +v -0.002884 -0.003162 -0.004968 +v -0.003067 -0.000020 -0.005816 +v -0.003494 0.001410 0.005386 +v -0.003649 0.004174 0.003511 +v -0.002498 -0.004760 -0.003753 +v -0.003748 -0.003777 -0.003850 +v -0.003534 -0.001352 -0.005349 +v -0.003808 0.001249 -0.005200 +v -0.003532 0.003320 -0.004420 +v -0.003770 0.003047 0.004440 +v -0.003370 -0.004761 -0.002980 +v -0.003787 -0.002548 -0.004727 +v -0.003822 0.000308 -0.005322 +v -0.003775 0.002169 -0.004903 +v -0.003594 -0.000660 0.005465 +v -0.004066 0.003891 -0.003374 +v -0.003944 0.004762 -0.002211 +v -0.003559 -0.004761 0.002770 +v -0.002595 -0.004762 0.003690 +v -0.003787 -0.003836 0.003748 +v -0.001415 -0.004749 0.004310 +v -0.002775 -0.003833 0.004548 +v 0.001468 -0.003883 0.005091 +v -0.000028 -0.004761 0.004521 +v -0.004042 -0.002722 0.004407 +v -0.001704 -0.003500 0.005295 +v -0.000330 -0.003598 0.005488 +v 0.003820 -0.002838 0.004514 +v 0.002372 -0.003081 0.005299 +v 0.004974 -0.001977 0.003812 +v 0.000411 -0.002780 0.005951 +v -0.003250 -0.002264 0.005246 +v -0.001780 -0.002366 0.005868 +v 0.003516 -0.002139 0.005114 +v -0.001315 -0.001804 0.006178 +v 0.001991 -0.001868 0.005967 +v 0.004550 -0.001324 0.004530 +v 0.000508 -0.001710 0.006324 +v 0.003384 -0.001165 0.005518 +v -0.004307 -0.001190 0.004815 +v -0.004587 -0.003820 -0.002737 +v -0.004435 -0.001024 -0.004734 +v -0.004818 0.002617 -0.003628 +v -0.004571 0.002761 0.003831 +v -0.004518 0.001491 0.004509 +v -0.004576 0.000192 0.004709 +v -0.004450 -0.004131 0.002482 +v -0.004712 -0.002519 -0.003813 +v -0.004827 0.000544 -0.004413 +v -0.004658 0.001871 -0.004213 +v -0.004645 0.003795 -0.002657 +v -0.004894 -0.002608 0.003511 +v -0.004431 0.004741 -0.001063 +v -0.004981 -0.003256 0.002758 +v -0.005235 -0.001196 0.003770 +v -0.005395 -0.003401 0.001570 +v -0.005047 -0.001057 -0.004070 +v -0.005227 0.003410 -0.002029 +v -0.005470 -0.000135 0.003628 +v -0.005325 -0.002893 -0.002520 +v -0.005489 0.001394 -0.003319 +v -0.005444 0.003649 -0.000393 +v -0.004517 0.004756 0.000226 +v -0.005584 0.003376 0.000752 +v -0.005436 0.003312 0.001606 +v -0.005345 0.002626 0.002758 +v -0.005227 0.001423 0.003711 +v -0.005565 -0.003385 -0.000839 +v -0.005656 -0.001802 -0.002794 +v -0.005510 -0.000395 -0.003555 +v -0.005716 -0.002001 0.002550 +v -0.005821 0.002161 -0.002135 +v -0.005810 -0.002948 0.000728 +v -0.005880 -0.002418 -0.001592 +v -0.005842 0.002772 -0.001105 +v -0.005882 0.002103 0.001987 +v -0.005796 0.001026 0.002900 +v -0.006103 -0.000721 0.002318 +v -0.005964 -0.000238 -0.002729 +v -0.006021 0.000802 -0.002466 +v -0.006141 -0.001807 0.001408 +v -0.006001 -0.002597 -0.000415 +v -0.006093 -0.001326 -0.002027 +v -0.006192 0.002168 -0.000137 +v -0.006214 0.001864 0.000988 +v -0.006114 0.001109 0.002078 +v -0.006298 -0.001807 0.000395 +v -0.006278 0.000311 0.001868 +v -0.006302 -0.001668 -0.000683 +v -0.006328 0.000534 -0.001641 +v -0.006328 0.001403 -0.000996 +v -0.006369 -0.000780 -0.001351 +v -0.006421 -0.000695 0.001119 +v -0.006463 0.000624 0.000923 +v -0.006505 0.000388 -0.000677 +v 0.003522 0.004762 -0.000336 +v -0.001157 0.004762 0.003344 +v -0.002508 0.004762 0.002454 +v -0.003373 0.004762 0.001050 +v -0.003360 0.004762 -0.001252 +v -0.001905 0.004762 -0.002964 +v 0.003274 0.004762 0.001262 +v 0.002198 0.004762 0.002794 +v 0.000500 0.004762 0.003476 +v 0.000000 0.004762 -0.003560 +v 0.001905 0.004762 -0.002964 +v 0.002955 0.004762 -0.001899 +v -0.002542 -0.004762 -0.002424 +v -0.001157 -0.004762 -0.003344 +v -0.003455 -0.004762 -0.000838 +v -0.003343 -0.004762 0.001102 +v -0.002198 -0.004762 0.002794 +v 0.001395 -0.004761 -0.003304 +v 0.003360 -0.004762 -0.001252 +v 0.003291 -0.004762 0.001388 +v -0.000335 -0.004762 0.003508 +v 0.001629 -0.004762 0.003160 +v 0.000877 0.004446 -0.003075 +v 0.001209 -0.004442 -0.002988 +v 0.001964 0.004444 -0.002510 +v 0.002576 -0.004445 -0.001904 +v 0.002667 0.004446 -0.001746 +v 0.003155 0.004444 -0.000547 +v 0.003053 -0.004445 -0.000891 +v 0.003190 -0.004445 0.000400 +v 0.003083 0.004442 0.000826 +v 0.002399 -0.004445 0.002147 +v 0.002526 0.004446 0.001945 +v 0.001607 0.004444 0.002764 +v 0.000815 -0.004445 0.003111 +v 0.000094 0.004445 0.003215 +v -0.000847 -0.004445 0.003089 +v -0.001300 0.004446 0.002910 +v -0.002272 -0.004445 0.002273 +v -0.002257 0.004442 0.002256 +v -0.002983 0.004446 0.001137 +v -0.003110 -0.004443 0.000742 +v -0.003195 0.004446 -0.000365 +v -0.003116 -0.004443 -0.000767 +v -0.002537 0.004446 -0.001965 +v -0.002359 -0.004444 -0.002166 +v -0.001337 0.004444 -0.002904 +v -0.000906 -0.004445 -0.003090 +v -0.000304 0.004444 -0.003168 +v 0.019999 0.004801 0.001159 +v 0.020000 0.003387 -0.003494 +v 0.020000 0.002933 0.003974 +v 0.020000 0.001159 -0.004801 +v 0.020000 0.000108 0.004895 +v 0.020000 -0.001776 -0.004563 +v 0.020000 -0.002731 0.004115 +v 0.020000 -0.004115 -0.002731 +v 0.020000 -0.004563 0.001776 +v 0.020000 0.004563 -0.001776 +v 0.020000 -0.004854 -0.000349 +v 0.022046 -0.001916 -0.002766 +v 0.022046 -0.001992 0.002774 +v 0.022046 -0.003301 0.000858 +v 0.022046 0.003250 -0.000866 +v 0.022046 0.003301 0.000858 +v 0.022046 0.002605 -0.002152 +v 0.022046 0.001992 0.002774 +v 0.022046 0.001423 -0.003048 +v 0.022046 -0.000000 0.003386 +v 0.022046 -0.000286 -0.003396 +v 0.022046 -0.003107 -0.001416 +v 0.480001 0.004908 0.000553 +v 0.480000 0.003404 0.003579 +v 0.480000 0.004294 -0.002354 +v 0.480001 -0.004527 0.001975 +v 0.480000 0.000553 -0.004908 +v 0.480000 0.002852 -0.003942 +v 0.480001 0.000307 0.004929 +v 0.480000 -0.002541 0.004186 +v 0.480000 -0.004802 -0.000956 +v 0.480000 -0.003681 -0.003229 +v 0.480000 -0.001988 -0.004442 +v 0.476574 -0.002759 -0.001920 +v 0.476574 -0.003333 -0.000589 +v 0.476574 -0.003248 0.000867 +v 0.476574 -0.001744 -0.002909 +v 0.476574 -0.002595 0.002174 +v 0.476574 0.002787 -0.001961 +v 0.476574 0.001441 0.003088 +v 0.476574 0.003081 0.001473 +v 0.476574 0.001423 -0.003048 +v 0.476574 -0.000848 0.003308 +v 0.476574 0.000000 -0.003381 +v 0.476574 0.003350 -0.000306 +v 0.028491 0.006314 -0.001117 +v 0.471509 0.006412 0.000004 +v 0.471509 0.005555 -0.003203 +v 0.028502 0.005220 -0.003658 +v 0.471498 0.003657 -0.005219 +v 0.028502 0.003654 -0.005222 +v 0.471498 0.001652 -0.006156 +v 0.028502 0.001647 -0.006157 +v 0.471498 -0.000553 -0.006349 +v 0.028491 -0.001117 -0.006314 +v 0.471498 -0.002691 -0.005777 +v 0.028502 -0.003658 -0.005220 +v 0.471498 -0.004505 -0.004509 +v 0.028502 -0.005222 -0.003654 +v 0.471509 -0.006024 -0.002197 +v 0.028491 -0.006315 -0.001110 +v 0.471498 -0.006349 0.000553 +v 0.028502 -0.006156 0.001652 +v 0.471498 -0.005777 0.002692 +v 0.028502 -0.005220 0.003657 +v 0.471498 -0.004508 0.004505 +v 0.028502 -0.003654 0.005222 +v 0.471498 -0.002696 0.005775 +v 0.028491 -0.001110 0.006315 +v 0.471498 -0.000558 0.006349 +v 0.471498 0.001647 0.006157 +v 0.028502 0.001652 0.006156 +v 0.471498 0.003654 0.005222 +v 0.028502 0.003658 0.005220 +v 0.471509 0.005551 0.003209 +v 0.028502 0.005222 0.003654 +v 0.028502 0.006157 0.001647 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vn -0.6721 0.0731 -0.7368 +vn -0.6284 -0.1880 -0.7548 +vn -0.6836 -0.2336 -0.6915 +vn -0.4448 -0.7885 0.4248 +vn -0.6946 -0.2329 0.6807 +vn -0.6816 -0.1818 0.7087 +vn -0.6700 0.2833 0.6862 +vn -0.4392 0.7925 0.4231 +vn -0.3861 0.8445 0.3712 +vn -0.6352 0.2261 -0.7385 +vn -0.6718 -0.0007 -0.7408 +vn -0.3037 -0.8830 0.3579 +vn -0.4089 -0.8281 0.3835 +vn -0.5913 -0.3867 0.7077 +vn -0.2762 -0.8119 0.5144 +vn -0.1456 -0.9783 0.1473 +vn -0.2392 -0.9291 0.2821 +vn -0.2159 -0.9441 -0.2490 +vn -0.4725 -0.6162 -0.6301 +vn -0.3414 -0.8577 -0.3845 +vn -0.0995 0.9507 -0.2936 +vn -0.0171 0.9070 -0.4209 +vn -0.0566 0.9940 0.0939 +vn -0.1677 0.9837 -0.0647 +vn -0.2439 0.8295 -0.5024 +vn -0.2690 -0.0895 0.9590 +vn -0.0994 0.3628 0.9266 +vn -0.0618 0.0520 0.9967 +vn -0.2121 -0.3212 -0.9229 +vn -0.0519 -0.5697 -0.8202 +vn -0.2166 -0.1472 -0.9651 +vn -0.0306 -0.2207 -0.9749 +vn -0.1697 0.9786 -0.1165 +vn -0.1563 0.9763 0.1494 +vn -0.1843 0.9419 0.2809 +vn -0.1005 -0.9841 0.1467 +vn -0.1499 -0.9796 -0.1340 +vn -0.0997 -0.9772 -0.1873 +vn -0.1835 0.9574 -0.2231 +vn -0.2711 0.8121 0.5168 +vn -0.2289 0.9351 0.2705 +vn -0.4315 -0.0173 0.9019 +vn -0.3099 0.2168 0.9257 +vn -0.1048 -0.8774 0.4681 +vn -0.0934 -0.8595 -0.5025 +vn -0.3213 -0.7697 -0.5516 +vn -0.3662 0.6872 -0.6274 +vn -0.1713 -0.3474 0.9219 +vn -0.0218 -0.3439 0.9387 +vn -0.2727 0.9071 -0.3207 +vn -0.1258 0.7125 -0.6903 +vn -0.1078 -0.6766 0.7284 +vn -0.2849 0.0822 -0.9550 +vn -0.0856 0.2242 -0.9708 +vn -0.0461 0.6081 -0.7925 +vn -0.5528 -0.1589 0.8180 +vn -0.4320 -0.3598 0.8270 +vn -0.4340 -0.6147 0.6587 +vn -0.3405 0.8709 -0.3543 +vn -0.4264 0.4174 -0.8025 +vn -0.2888 0.4394 -0.8506 +vn -0.2938 -0.5052 0.8114 +vn -0.5817 0.0074 -0.8133 +vn -0.5420 0.3108 -0.7808 +vn -0.4629 0.0449 -0.8853 +vn -0.6553 0.2925 -0.6965 +vn -0.1668 0.4274 -0.8886 +vn -0.4092 0.8344 -0.3693 +vn -0.5736 -0.2486 -0.7805 +vn -0.4846 -0.3487 -0.8023 +vn -0.3991 -0.2256 -0.8887 +vn -0.3704 -0.4853 -0.7920 +vn -0.2254 -0.6119 -0.7581 +vn -0.4410 0.7933 -0.4198 +vn -0.5693 0.3977 0.7196 +vn -0.2870 0.8862 0.3637 +vn -0.3044 0.5650 0.7669 +vn -0.1015 0.8604 0.4994 +vn -0.4295 0.3616 0.8275 +vn -0.5658 0.1142 0.8166 +vn -0.6735 0.1002 0.7323 +vn -0.1029 0.6541 0.7494 +vn -0.4374 -0.8044 -0.4020 +vn 0.0511 -0.7296 -0.6819 +vn 0.9925 -0.0709 0.0996 +vn 0.9952 -0.0391 -0.0895 +vn 0.9992 0.0350 0.0211 +vn -0.6747 -0.0910 0.7324 +vn 0.1711 -0.2532 -0.9521 +vn 0.2110 -0.7857 -0.5815 +vn 0.0329 -0.7893 -0.6131 +vn 0.9287 -0.2475 -0.2762 +vn 0.5983 -0.7968 -0.0845 +vn 0.5730 -0.7956 -0.1966 +vn 0.5983 -0.7989 0.0619 +vn 0.9536 -0.2994 -0.0319 +vn 0.9560 -0.2727 0.1077 +vn 0.5749 0.7908 -0.2100 +vn 0.5899 0.8026 -0.0889 +vn 0.9530 0.2667 -0.1440 +vn -0.0294 0.7953 -0.6056 +vn -0.0458 0.2469 -0.9679 +vn -0.1570 0.7854 -0.5987 +vn -0.6345 0.0397 0.7719 +vn -0.3566 0.7917 -0.4960 +vn -0.6377 0.2202 0.7381 +vn -0.3521 0.7902 0.5017 +vn -0.5919 -0.2097 0.7782 +vn -0.3556 -0.7999 0.4833 +vn -0.4007 -0.7827 -0.4762 +vn -0.2931 0.7790 -0.5543 +vn -0.4128 0.1908 -0.8906 +vn -0.3779 0.2509 0.8912 +vn -0.2375 0.8000 0.5509 +vn -0.1073 0.7873 0.6072 +vn -0.4537 -0.2757 0.8474 +vn -0.2121 -0.7978 0.5644 +vn -0.3026 -0.2230 0.9267 +vn -0.0664 -0.7756 0.6278 +vn -0.2854 -0.7863 -0.5480 +vn -0.4454 -0.2205 -0.8677 +vn -0.1209 -0.7795 -0.6146 +vn -0.2242 -0.2101 -0.9516 +vn -0.5009 0.1384 0.8544 +vn -0.1200 0.2248 0.9670 +vn 0.0623 0.7709 0.6339 +vn 0.0735 0.1071 0.9915 +vn 0.1503 0.7736 0.6155 +vn 0.2231 0.1114 0.9684 +vn -0.3494 0.0420 0.9360 +vn -0.2282 0.1479 0.9623 +vn -0.0609 -0.0278 0.9978 +vn -0.4626 -0.0778 0.8831 +vn -0.1997 -0.1240 0.9720 +vn 0.0446 -0.1653 0.9852 +vn 0.2345 -0.1543 0.9598 +vn 0.0814 -0.7840 0.6155 +vn 0.1998 -0.7792 0.5940 +vn 0.3613 0.0612 0.9304 +vn 0.2361 0.7659 0.5981 +vn 0.2855 -0.7990 0.5293 +vn 0.3967 -0.1944 0.8971 +vn 0.5010 -0.0260 0.8651 +vn 0.5149 0.1855 0.8369 +vn 0.3277 0.7911 0.5165 +vn 0.5484 -0.2172 0.8075 +vn -0.4138 -0.0699 -0.9077 +vn -0.5589 0.0483 -0.8278 +vn -0.2724 0.0154 -0.9621 +vn -0.1994 0.1757 -0.9640 +vn -0.0560 0.0352 -0.9978 +vn 0.3276 -0.0518 -0.9434 +vn 0.1402 -0.0306 -0.9897 +vn 0.1883 0.1651 -0.9681 +vn 0.5155 -0.0334 -0.8562 +vn 0.5087 0.1201 -0.8525 +vn 0.4008 0.2176 -0.8899 +vn 0.1086 0.7765 -0.6207 +vn 0.3788 0.7714 -0.5113 +vn 0.2486 0.7908 -0.5593 +vn 0.4126 -0.7826 0.4662 +vn 0.6772 0.1802 -0.7134 +vn 0.6650 0.0108 -0.7467 +vn 0.6437 -0.0117 0.7652 +vn 0.4178 0.7803 0.4655 +vn 0.4424 0.7913 -0.4221 +vn 0.7148 -0.1842 0.6746 +vn 0.7040 0.2019 0.6809 +vn 0.4984 -0.7776 0.3832 +vn 0.7654 -0.0058 0.6435 +vn 0.5226 0.7824 0.3387 +vn 0.5153 0.7962 -0.3169 +vn 0.7920 0.2167 -0.5708 +vn 0.7951 -0.0239 -0.6060 +vn 0.8196 -0.1801 0.5439 +vn 0.8250 0.1937 0.5309 +vn 0.8859 0.0600 -0.4600 +vn 0.5507 -0.7846 0.2849 +vn 0.8580 -0.0154 0.5133 +vn 0.9000 0.2204 -0.3761 +vn 0.8975 -0.1670 0.4082 +vn 0.9130 0.0954 0.3967 +vn 0.9160 0.2262 0.3312 +vn 0.5910 0.7827 0.1951 +vn 0.5234 -0.7978 -0.2992 +vn 0.8441 -0.2321 -0.4834 +vn 0.4617 -0.7832 -0.4165 +vn 0.5955 -0.7810 0.1883 +vn 0.3273 -0.2351 -0.9152 +vn 0.4767 -0.2204 -0.8510 +vn 0.3778 -0.7801 -0.4987 +vn 0.6203 -0.1751 -0.7646 +vn 0.7232 -0.2054 -0.6594 +vn -0.0112 -0.1740 -0.9847 +vn 0.9136 -0.0949 -0.3953 +vn 0.9569 -0.1965 0.2139 +vn 0.9504 -0.0522 0.3067 +vn 0.9633 0.1984 0.1809 +vn 0.6187 0.7843 0.0446 +vn 0.9646 0.0780 -0.2519 +vn 0.9691 -0.2058 -0.1361 +vn 0.9724 -0.0832 -0.2180 +vn 0.9796 0.0440 0.1962 +vn 0.9817 0.1840 0.0482 +vn 0.9879 -0.1553 0.0053 +vn 0.9881 0.1269 -0.0873 +vn -0.5847 -0.7552 -0.2962 +vn -0.6451 -0.7640 0.0042 +vn -0.1649 -0.7633 0.6247 +vn 0.6227 -0.7477 0.2306 +vn 0.6397 -0.7665 -0.0564 +vn 0.5226 -0.7699 -0.3663 +vn -0.4331 -0.7447 -0.5077 +vn -0.4292 -0.7595 0.4888 +vn 0.1002 -0.7432 0.6615 +vn 0.2916 -0.7611 -0.5794 +vn -0.5942 -0.7523 0.2847 +vn 0.5065 -0.7461 0.4322 +vn -0.2342 -0.7476 -0.6214 +vn 0.0184 -0.7550 -0.6555 +vn 0.3041 -0.7545 0.5816 +vn -0.5890 0.7569 0.2830 +vn -0.6399 0.7508 -0.1639 +vn -0.6692 0.7399 0.0692 +vn 0.5556 0.7470 0.3652 +vn 0.3396 0.7642 0.5483 +vn -0.5165 0.7539 -0.4059 +vn 0.6496 0.7456 0.1491 +vn 0.0571 0.7576 0.6503 +vn -0.2112 0.7499 0.6269 +vn -0.4270 0.7552 0.4973 +vn -0.3202 0.7495 -0.5795 +vn -0.0383 0.7633 -0.6449 +vn 0.5067 0.7693 -0.3892 +vn 0.2672 0.7622 -0.5896 +vn 0.6406 0.7599 -0.1104 +vn 0.9920 -0.0278 -0.1227 +vn 0.9966 0.0805 0.0162 +vn 0.9976 -0.0249 0.0642 +vn 0.4499 -0.8908 -0.0632 +vn 0.7812 -0.6175 0.0917 +vn 0.4198 -0.9018 0.1021 +vn -0.3059 -0.5823 0.7532 +vn -0.2408 -0.8999 0.3635 +vn -0.0753 -0.8930 0.4437 +vn 0.7406 0.6482 0.1772 +vn 0.4554 0.8901 -0.0142 +vn 0.3983 0.9095 0.1187 +vn -0.9723 0.0122 0.2335 +vn -0.9973 -0.0342 0.0651 +vn -0.9726 -0.1565 0.1717 +vn -0.9874 -0.1536 -0.0377 +vn -0.9677 -0.1896 -0.1661 +vn -0.9278 -0.3713 -0.0367 +vn -0.9946 0.0998 -0.0298 +vn -0.9866 0.1359 0.0900 +vn -0.9736 0.2158 -0.0744 +vn -0.9329 -0.1680 0.3184 +vn -0.9914 -0.0074 -0.1304 +vn -0.9354 0.3203 -0.1500 +vn -0.9274 0.3618 0.0946 +vn -0.8593 0.5101 -0.0376 +vn -0.9029 0.1140 0.4145 +vn -0.8828 -0.1398 0.4485 +vn -0.8610 0.0384 0.5071 +vn -0.8685 0.4314 -0.2442 +vn -0.7956 -0.1701 0.5815 +vn -0.7904 0.1382 0.5968 +vn -0.8316 -0.5458 0.1028 +vn -0.8487 -0.5195 -0.0986 +vn -0.9401 -0.1049 -0.3243 +vn -0.9548 0.1097 -0.2763 +vn -0.9043 0.0373 -0.4253 +vn -0.9685 -0.2397 0.0673 +vn -0.8270 -0.1630 -0.5381 +vn -0.8023 0.0394 -0.5956 +vn -0.7549 0.5582 -0.3443 +vn -0.7778 0.6216 -0.0931 +vn -0.4317 0.8943 -0.1176 +vn -0.9104 -0.3584 0.2068 +vn -0.4545 -0.8901 -0.0321 +vn -0.4438 -0.8924 0.0816 +vn -0.8699 0.4705 0.1479 +vn -0.7797 0.5987 0.1834 +vn -0.4427 0.8944 0.0643 +vn -0.8703 0.3471 0.3494 +vn -0.8194 0.4614 0.3401 +vn -0.4167 -0.8921 0.1747 +vn -0.7807 -0.5852 -0.2194 +vn -0.4068 -0.8902 -0.2049 +vn -0.3644 0.9007 -0.2364 +vn -0.7454 0.5946 0.3012 +vn -0.9533 0.2416 0.1812 +vn -0.3997 0.8983 0.1827 +vn -0.7627 0.5409 0.3547 +vn -0.7634 -0.5917 0.2590 +vn -0.8780 -0.3707 -0.3030 +vn -0.7094 -0.5912 -0.3836 +vn -0.7264 0.5916 0.3498 +vn -0.9445 0.1685 0.2819 +vn -0.7723 0.4759 0.4207 +vn -0.6685 0.5606 0.4887 +vn -0.8279 -0.3969 0.3962 +vn -0.7171 -0.5811 0.3848 +vn -0.8393 -0.4745 0.2653 +vn -0.8311 -0.4601 -0.3123 +vn -0.8399 -0.4372 -0.3215 +vn -0.6329 -0.2991 -0.7142 +vn -0.6989 -0.1518 -0.6990 +vn -0.5176 -0.2132 -0.8286 +vn -0.7964 0.4012 0.4525 +vn -0.3691 0.8916 0.2625 +vn -0.8548 0.2873 0.4323 +vn -0.8088 0.3153 0.4964 +vn -0.8057 0.3190 0.4990 +vn -0.7729 0.4289 0.4676 +vn -0.3685 -0.8907 0.2662 +vn -0.6121 -0.6173 -0.4942 +vn -0.3145 -0.9028 -0.2933 +vn -0.8635 -0.5039 -0.0220 +vn -0.7930 -0.4383 -0.4232 +vn -0.7062 -0.4087 -0.5782 +vn -0.6167 -0.3714 -0.6941 +vn -0.5417 -0.3970 -0.7409 +vn -0.6779 0.6062 -0.4159 +vn -0.7252 -0.5489 0.4157 +vn -0.6845 -0.5830 -0.4377 +vn -0.8967 -0.2601 -0.3582 +vn -0.8502 -0.2475 -0.4647 +vn -0.7594 -0.2669 -0.5933 +vn -0.6685 -0.3367 -0.6631 +vn -0.4242 -0.4838 -0.7655 +vn -0.6238 0.6247 -0.4698 +vn -0.5702 -0.5373 -0.6214 +vn -0.4999 -0.5807 0.6426 +vn -0.6471 -0.5898 0.4831 +vn -0.3903 -0.6495 -0.6525 +vn -0.2429 -0.9015 -0.3582 +vn -0.2761 0.8906 -0.3614 +vn -0.6730 0.5296 -0.5163 +vn -0.8337 -0.4474 -0.3237 +vn -0.8537 -0.3299 -0.4029 +vn -0.6495 -0.5719 -0.5010 +vn -0.6287 -0.5757 0.5227 +vn -0.7135 -0.4983 0.4927 +vn -0.1254 -0.8996 -0.4183 +vn -0.2759 0.8936 0.3541 +vn -0.6903 -0.5019 -0.5212 +vn -0.2121 -0.5587 -0.8018 +vn -0.7281 -0.4092 0.5500 +vn -0.0963 0.8919 -0.4419 +vn -0.3607 0.5908 -0.7217 +vn -0.5174 0.4786 -0.7094 +vn -0.6985 0.3998 -0.5934 +vn -0.6682 0.5422 -0.5094 +vn -0.7786 0.4317 -0.4554 +vn -0.8586 0.3598 -0.3650 +vn -0.3750 0.5769 0.7257 +vn -0.5395 0.6126 0.5777 +vn -0.6058 0.5577 0.5674 +vn -0.6090 0.4911 0.6229 +vn -0.0001 -0.8930 -0.4501 +vn -0.8531 0.2414 -0.4625 +vn -0.0102 -0.0848 0.9963 +vn -0.2002 0.1016 0.9745 +vn -0.2384 -0.1579 0.9583 +vn -0.3615 0.1070 0.9262 +vn -0.3956 -0.0769 0.9152 +vn -0.5355 -0.1530 0.8306 +vn -0.5964 0.0501 0.8011 +vn -0.7056 -0.0552 0.7065 +vn 0.0098 -0.2856 0.9583 +vn 0.2384 -0.3103 0.9202 +vn 0.1916 -0.0746 0.9786 +vn -0.4925 -0.3045 0.8153 +vn -0.6554 -0.3175 0.6854 +vn -0.3980 -0.3846 0.8329 +vn -0.1910 -0.3764 0.9066 +vn 0.0752 -0.4554 0.8871 +vn -0.0933 -0.5644 0.8202 +vn -0.5491 -0.4409 0.7100 +vn -0.6027 -0.4429 0.6638 +vn -0.7957 0.3619 -0.4857 +vn 0.1466 -0.5810 0.8006 +vn -0.6510 -0.4910 0.5788 +vn 0.1003 -0.8923 0.4402 +vn 0.1824 -0.5943 -0.7833 +vn 0.1867 -0.8954 -0.4042 +vn 0.0383 -0.5790 -0.8145 +vn -0.0189 -0.4582 -0.8886 +vn 0.2422 -0.3939 -0.8867 +vn -0.1662 -0.2974 -0.9402 +vn -0.3561 -0.3156 -0.8795 +vn 0.0444 -0.2724 -0.9612 +vn 0.0690 -0.1413 -0.9876 +vn -0.2572 -0.0999 -0.9612 +vn -0.4604 -0.0080 -0.8877 +vn -0.6140 -0.0166 -0.7891 +vn -0.0704 0.0351 -0.9969 +vn 0.1791 0.0037 -0.9838 +vn -0.2314 0.1699 -0.9579 +vn -0.4393 0.1650 -0.8830 +vn -0.6515 0.1343 -0.7467 +vn 0.1512 0.1800 -0.9720 +vn -0.0539 0.2518 -0.9663 +vn -0.7484 0.1956 -0.6337 +vn 0.1032 0.3303 -0.9382 +vn -0.3283 0.3665 -0.8706 +vn 0.2552 0.3971 -0.8816 +vn -0.6002 0.3572 -0.7157 +vn -0.1610 0.4261 -0.8902 +vn -0.4480 0.4117 -0.7936 +vn 0.0373 0.4549 -0.8897 +vn -0.6991 0.2625 -0.6651 +vn 0.0524 0.5840 -0.8100 +vn -0.2168 0.5883 -0.7791 +vn -0.5080 0.4323 -0.7450 +vn -0.8010 0.3849 -0.4585 +vn -0.9020 0.2837 -0.3253 +vn 0.0923 0.8960 -0.4344 +vn 0.3115 0.5786 -0.7538 +vn 0.3559 -0.5818 0.7314 +vn 0.3186 -0.4411 0.8390 +vn 0.2968 -0.2005 -0.9336 +vn 0.4121 -0.2450 0.8776 +vn 0.3371 -0.0155 0.9413 +vn 0.2484 0.8882 -0.3865 +vn 0.3403 0.1948 -0.9199 +vn 0.3415 -0.0352 -0.9392 +vn 0.3657 -0.5678 -0.7375 +vn 0.2481 -0.8944 0.3723 +vn 0.4428 0.4046 -0.8001 +vn 0.4251 -0.2967 -0.8551 +vn 0.5139 -0.4203 0.7479 +vn 0.5085 -0.1301 0.8512 +vn 0.5049 0.5571 -0.6594 +vn 0.5384 0.2355 -0.8091 +vn 0.4865 0.0750 -0.8704 +vn 0.5137 -0.1054 -0.8515 +vn 0.5081 -0.4652 -0.7249 +vn 0.5718 -0.5808 -0.5794 +vn 0.3264 -0.8874 -0.3255 +vn 0.3367 -0.8930 0.2986 +vn 0.5701 -0.5394 0.6196 +vn 0.3437 0.8878 -0.3059 +vn 0.5206 -0.2468 -0.8173 +vn 0.4986 -0.3679 -0.7849 +vn 0.5568 -0.3545 -0.7512 +vn 0.6209 -0.3479 0.7025 +vn 0.5467 0.6096 -0.5741 +vn 0.6316 0.3265 -0.7032 +vn 0.6287 -0.1869 -0.7548 +vn 0.6052 -0.3215 -0.7283 +vn 0.3662 0.9017 0.2297 +vn 0.2649 0.8906 0.3698 +vn 0.6461 0.6313 0.4290 +vn 0.5671 0.6039 0.5601 +vn 0.5295 0.5279 0.6641 +vn 0.3221 0.5562 0.7661 +vn 0.0966 0.8903 0.4451 +vn 0.0410 0.5608 0.8270 +vn -0.1037 0.8926 0.4388 +vn -0.2103 0.6294 0.7481 +vn -0.6067 0.5123 0.6078 +vn -0.6824 0.4765 0.5543 +vn -0.7419 0.4218 0.5212 +vn -0.1589 0.5082 0.8464 +vn -0.5998 0.3771 0.7057 +vn -0.7079 0.4364 0.5554 +vn -0.6688 0.4263 0.6090 +vn -0.7818 0.3466 0.5183 +vn -0.4019 0.4380 0.8042 +vn -0.5203 0.4785 0.7073 +vn -0.7274 0.3525 0.5888 +vn -0.8241 0.2635 0.5013 +vn 0.2328 0.3928 0.8897 +vn -0.6875 0.3578 0.6319 +vn -0.7096 0.2272 0.6670 +vn 0.4575 0.3392 0.8220 +vn 0.0015 0.3312 0.9436 +vn -0.1922 0.3085 0.9316 +vn -0.5255 0.1941 0.8284 +vn -0.3603 0.3382 0.8694 +vn 0.3051 0.1788 0.9354 +vn 0.1416 0.1686 0.9755 +vn 0.4646 0.1336 0.8754 +vn 0.6114 0.2755 0.7418 +vn -0.0267 0.1124 0.9933 +vn 0.5992 0.0475 0.7992 +vn 0.5116 0.5595 -0.6521 +vn 0.5884 0.4712 -0.6571 +vn 0.6577 0.0540 -0.7513 +vn 0.5828 -0.6218 0.5231 +vn 0.6433 -0.4012 0.6521 +vn 0.6299 -0.2095 0.7479 +vn 0.6121 0.5911 -0.5253 +vn -0.1334 -0.9508 -0.2795 +vn 0.6911 -0.3812 -0.6141 +vn 0.7915 -0.5398 -0.2865 +vn 0.7148 -0.5791 -0.3921 +vn 0.3877 -0.8993 -0.2021 +vn 0.6255 -0.6019 0.4964 +vn 0.6563 -0.4460 0.6086 +vn 0.6480 0.3845 0.6574 +vn 0.6281 0.4825 0.6104 +vn 0.4014 0.8911 -0.2119 +vn 0.6776 0.5884 -0.4412 +vn 0.6928 0.5578 -0.4571 +vn 0.6663 0.5095 -0.5445 +vn 0.6965 0.4448 -0.5630 +vn 0.7573 0.2099 -0.6185 +vn 0.3848 -0.8971 0.2173 +vn 0.6698 -0.6066 0.4282 +vn 0.6883 -0.5397 0.4847 +vn 0.6632 -0.5253 0.5332 +vn 0.7277 -0.0023 0.6859 +vn 0.6703 0.4241 0.6089 +vn 0.6551 0.5069 0.5602 +vn 0.6736 0.5264 0.5189 +vn 0.4464 0.8881 -0.1097 +vn 0.6985 0.6309 -0.3378 +vn 0.6935 0.6029 -0.3945 +vn 0.7423 0.4415 -0.5040 +vn 0.7008 0.4015 -0.5896 +vn 0.7413 -0.1556 -0.6529 +vn 0.4545 -0.6260 -0.6337 +vn 0.7090 -0.6160 0.3433 +vn 0.7194 -0.5511 0.4228 +vn 0.6930 -0.5433 0.4738 +vn 0.7433 -0.4305 0.5120 +vn 0.6459 -0.4058 0.6467 +vn 0.7290 -0.3238 0.6030 +vn 0.7267 -0.2893 0.6230 +vn 0.7846 -0.1322 0.6058 +vn 0.7405 0.1957 0.6429 +vn 0.7099 0.3882 0.5877 +vn 0.7119 0.4605 0.5303 +vn 0.7313 0.5152 0.4470 +vn 0.7625 0.3278 0.5579 +vn 0.7582 0.4001 0.5149 +vn 0.7570 0.4536 0.4703 +vn 0.7387 0.5885 0.3285 +vn 0.7434 0.5305 -0.4074 +vn 0.7534 0.4372 -0.4912 +vn 0.7523 0.4005 -0.5231 +vn 0.8077 0.0723 -0.5851 +vn 0.8163 -0.5294 0.2310 +vn 0.7427 -0.5095 0.4345 +vn 0.7778 0.4749 0.4117 +vn 0.7447 0.5380 0.3950 +vn 0.7395 0.6011 0.3030 +vn 0.8409 0.5177 -0.1575 +vn 0.7389 0.5631 -0.3701 +vn 0.7500 0.4574 -0.4779 +vn 0.8302 -0.2901 -0.4761 +vn 0.7451 -0.2581 -0.6150 +vn 0.7615 -0.4127 -0.4998 +vn 0.7811 -0.5642 -0.2673 +vn 0.8462 -0.5314 -0.0387 +vn 0.7817 -0.5050 0.3659 +vn 0.7983 -0.4622 0.3860 +vn 0.8014 -0.4370 0.4083 +vn 0.8302 0.1479 0.5375 +vn 0.8049 0.3531 0.4769 +vn 0.7997 0.4331 0.4158 +vn 0.7918 0.5471 0.2714 +vn 0.7316 0.6558 0.1863 +vn 0.8386 0.5437 0.0344 +vn 0.8403 0.4471 -0.3067 +vn 0.7939 0.4313 -0.4286 +vn 0.7813 0.4104 -0.4703 +vn 0.8060 0.2955 -0.5128 +vn 0.8598 -0.1113 -0.4984 +vn 0.8018 -0.4228 -0.4223 +vn 0.8251 -0.4036 0.3953 +vn 0.8116 -0.3518 0.4663 +vn 0.7754 -0.2800 0.5659 +vn 0.8845 0.2174 0.4127 +vn 0.8350 0.3673 0.4097 +vn 0.8388 0.4101 0.3581 +vn 0.8326 0.4195 -0.3617 +vn 0.8292 0.3783 -0.4114 +vn 0.8507 0.2549 -0.4597 +vn 0.8215 -0.4512 -0.3487 +vn 0.8907 -0.4309 -0.1447 +vn 0.8334 -0.3413 0.4347 +vn 0.8278 -0.2930 0.4784 +vn 0.8707 -0.1907 0.4533 +vn 0.8662 0.3637 0.3427 +vn 0.8787 0.3842 0.2834 +vn 0.9008 0.4146 0.1289 +vn 0.8600 0.4176 -0.2932 +vn 0.8554 0.3602 -0.3722 +vn 0.8931 0.2723 -0.3581 +vn 0.9014 0.0961 -0.4222 +vn 0.9044 -0.3081 -0.2950 +vn 0.8859 -0.4091 0.2185 +vn 0.8640 -0.3224 0.3868 +vn 0.8600 0.0041 0.5102 +vn 0.9148 0.2584 0.3105 +vn 0.9334 0.3037 0.1913 +vn 0.9091 0.3402 -0.2403 +vn 0.8702 0.3623 -0.3338 +vn 0.9325 -0.2358 0.2737 +vn 0.9318 -0.0203 0.3624 +vn 0.9404 0.3318 -0.0740 +vn 0.9043 0.3803 -0.1939 +vn 0.9438 -0.1132 -0.3105 +vn 0.9385 0.2526 -0.2353 +vn 0.9500 -0.3079 0.0528 +vn 0.9680 0.1096 0.2258 +vn 0.9591 0.0733 -0.2733 +vn 0.9687 -0.2128 -0.1279 +vn 0.9735 -0.0596 0.2209 +vn 0.9791 0.1943 0.0603 +vn 0.9830 0.1293 -0.1302 +vn 0.9817 -0.1494 0.1182 +vn 0.9905 -0.1367 -0.0175 +vn -0.3143 -0.9459 -0.0801 +vn -0.2189 -0.9498 -0.2237 +vn 0.0788 -0.9551 0.2855 +vn -0.1990 -0.9461 0.2554 +vn -0.1012 -0.9430 0.3171 +vn 0.3029 -0.9491 -0.0865 +vn 0.3234 -0.9441 0.0643 +vn 0.1936 -0.9524 -0.2356 +vn -0.1208 -0.9386 -0.3231 +vn 0.2403 -0.9496 0.2013 +vn -0.2818 -0.9550 0.0926 +vn 0.0294 -0.9533 -0.3005 +vn -0.2831 0.9576 -0.0543 +vn -0.1395 0.9565 0.2563 +vn -0.2786 0.9511 0.1332 +vn -0.2583 0.9420 -0.2143 +vn 0.0727 0.9562 0.2835 +vn 0.2359 0.9586 0.1593 +vn -0.1200 0.9493 -0.2906 +vn 0.2249 0.9558 -0.1894 +vn 0.0645 0.9527 -0.2971 +vn 0.3169 0.9482 -0.0243 +vn -0.1131 -0.3583 0.9267 +vn 0.1306 0.4231 0.8966 +vn 0.3833 -0.3821 0.8409 +vn 0.5598 0.2478 0.7907 +vn 0.6347 -0.3802 0.6727 +vn 0.8560 0.3750 0.3559 +vn 0.8550 -0.3647 0.3688 +vn 0.9252 -0.3780 0.0321 +vn 0.9130 0.4078 -0.0081 +vn 0.8549 -0.3931 -0.3385 +vn 0.8619 0.3261 -0.3884 +vn 0.6762 -0.3964 -0.6210 +vn 0.5608 0.3371 -0.7562 +vn 0.2863 -0.3606 -0.8877 +vn 0.1443 0.4269 -0.8927 +vn -0.2629 -0.4006 -0.8777 +vn -0.2218 0.3795 -0.8982 +vn -0.6426 0.3951 -0.6565 +vn -0.6822 -0.4109 -0.6048 +vn -0.8878 -0.4043 -0.2197 +vn -0.8665 0.4041 -0.2931 +vn -0.9258 0.3292 0.1858 +vn -0.9093 -0.3911 0.1420 +vn -0.7721 -0.3319 0.5419 +vn -0.7378 0.3273 0.5904 +vn -0.5023 -0.4061 0.7634 +vn -0.4682 0.4420 0.7651 +vn -0.1698 0.2545 0.9521 +vn 0.0359 0.9989 -0.0287 +vn 0.0518 0.9057 -0.4207 +vn 0.1180 0.9662 -0.2291 +vn 0.1860 0.9533 -0.2378 +vn 0.1736 0.9843 0.0315 +vn 0.2357 0.9308 -0.2794 +vn 0.1616 -0.9705 0.1788 +vn 0.0775 -0.9598 -0.2699 +vn 0.0239 -0.9989 0.0393 +vn 0.2919 -0.2482 0.9237 +vn 0.0922 -0.3523 0.9313 +vn 0.1345 0.0012 0.9909 +vn 0.1506 0.9741 0.1687 +vn 0.0367 0.9261 0.3756 +vn 0.1530 -0.9825 -0.1066 +vn -0.0009 0.0774 0.9970 +vn 0.1344 0.2579 -0.9568 +vn 0.0557 0.5106 -0.8580 +vn 0.0074 0.0861 -0.9963 +vn 0.1556 -0.9769 0.1462 +vn 0.2296 -0.8705 0.4354 +vn 0.2867 0.0699 0.9555 +vn 0.3373 0.8461 0.4128 +vn 0.2157 -0.8423 -0.4939 +vn 0.2033 -0.9503 -0.2359 +vn 0.2245 -0.8073 0.5458 +vn 0.2273 -0.9256 0.3026 +vn 0.1991 0.9399 0.2774 +vn 0.2313 0.8025 -0.5500 +vn 0.0394 -0.7364 -0.6754 +vn 0.4516 0.0056 0.8922 +vn 0.3528 0.2544 0.9004 +vn 0.2294 0.7478 0.6231 +vn 0.2260 0.7234 0.6524 +vn 0.0682 0.7227 0.6878 +vn 0.2851 0.2322 -0.9299 +vn 0.1481 -0.0881 -0.9850 +vn 0.2630 -0.9070 -0.3289 +vn 0.3227 -0.6738 -0.6647 +vn 0.4656 0.6111 -0.6401 +vn 0.2860 0.9157 -0.2822 +vn 0.5184 0.0950 -0.8498 +vn 0.4241 0.1947 -0.8844 +vn 0.3564 -0.0848 -0.9305 +vn 0.5006 -0.2214 -0.8369 +vn 0.4085 -0.5267 -0.7455 +vn 0.1626 -0.6370 -0.7535 +vn 0.5139 0.3301 0.7918 +vn 0.2290 0.4118 0.8820 +vn 0.0658 0.4247 0.9029 +vn 0.4049 0.5372 0.7399 +vn 0.5620 -0.4316 -0.7056 +vn 0.3391 0.8628 0.3750 +vn 0.6616 -0.1797 -0.7280 +vn 0.1088 -0.3814 -0.9180 +vn 0.4070 -0.8275 -0.3867 +vn 0.3137 -0.3977 -0.8622 +vn 0.5080 -0.5347 0.6753 +vn 0.3621 -0.8538 0.3740 +vn 0.3676 0.8515 -0.3739 +vn 0.6556 -0.2652 0.7070 +vn 0.4395 -0.7855 0.4356 +vn 0.4358 0.7880 0.4350 +vn 0.6709 0.2575 0.6954 +vn 0.4110 0.7789 -0.4738 +vn 0.6832 0.3083 -0.6619 +vn 0.6679 -0.0421 -0.7430 +vn 0.6553 0.0919 -0.7498 +vn 0.4701 0.3822 -0.7956 +vn 0.3629 0.4980 -0.7876 +vn 0.2217 0.6150 -0.7567 +vn 0.4492 -0.7954 -0.4068 +vn 0.6567 -0.2386 -0.7154 +vn 0.0501 -0.9203 0.3881 +vn 0.3575 -0.5571 0.7495 +vn 0.4957 -0.3200 0.8074 +vn 0.2022 -0.5591 0.8041 +vn 0.6795 -0.0029 0.7336 +vn 0.6454 -0.1560 0.7478 +vn 0.0739 -0.6996 0.7107 +vn 0.5725 -0.1267 0.8100 +vn 0.5782 0.0978 0.8100 +vn 0.6729 0.1791 0.7177 +vn 0.5811 0.3185 -0.7489 +vn 0.6421 0.1355 -0.7546 +vn 0.6833 0.2605 -0.6821 +vn 0.0261 0.7343 -0.6784 +vn -0.9918 0.1034 0.0758 +vn -0.9927 0.1185 -0.0236 +vn -0.9974 -0.0665 -0.0286 +vn -0.9915 -0.0408 0.1235 +vn 0.6453 0.0186 0.7637 +vn -0.1967 0.2656 -0.9438 +vn -0.1430 0.8018 -0.5803 +vn -0.0047 0.7845 -0.6201 +vn -0.9348 0.2421 -0.2597 +vn -0.6007 0.7968 -0.0660 +vn -0.5788 0.7904 -0.2007 +vn -0.9572 0.2821 -0.0653 +vn -0.9564 0.2819 0.0760 +vn -0.6057 0.7906 0.0900 +vn -0.0015 -0.7852 0.6192 +vn -0.1999 -0.2576 0.9454 +vn -0.1398 -0.8017 0.5812 +vn -0.3074 -0.7726 -0.5555 +vn -0.4108 -0.7918 -0.4521 +vn -0.5969 -0.2351 -0.7671 +vn 0.3618 -0.7817 -0.5080 +vn 0.4304 -0.2363 -0.8712 +vn 0.2088 -0.7754 -0.5959 +vn 0.3816 -0.7844 0.4890 +vn 0.4515 -0.2356 0.8606 +vn 0.2876 -0.7985 0.5288 +vn 0.1879 -0.7801 0.5968 +vn 0.1564 -0.2829 0.9463 +vn 0.3673 0.7791 0.5080 +vn 0.4350 0.2422 0.8673 +vn 0.2083 0.7767 0.5945 +vn 0.4707 0.1775 -0.8642 +vn 0.2897 0.7833 -0.5500 +vn 0.1896 0.7741 -0.6041 +vn 0.1782 0.2776 -0.9440 +vn -0.0403 -0.1762 0.9835 +vn 0.4638 -0.0714 0.8830 +vn 0.2252 -0.1533 0.9622 +vn -0.1748 -0.0032 0.9846 +vn 0.2598 -0.0110 0.9656 +vn 0.0559 -0.0269 0.9981 +vn 0.5443 0.1364 0.8277 +vn 0.3416 0.1254 0.9314 +vn 0.1634 0.1673 0.9723 +vn -0.0136 0.1789 0.9838 +vn -0.2305 0.1557 0.9605 +vn 0.0593 0.7796 0.6235 +vn -0.1175 0.7809 0.6135 +vn -0.3400 0.2756 0.8992 +vn -0.3339 -0.1017 0.9371 +vn -0.2446 -0.7725 0.5860 +vn -0.2900 0.7924 0.5366 +vn -0.4338 0.1172 0.8933 +vn -0.5465 0.2397 0.8024 +vn -0.4946 -0.0648 0.8667 +vn -0.4901 -0.2223 0.8428 +vn -0.5968 0.0174 0.8022 +vn -0.3641 -0.7890 0.4949 +vn 0.2278 0.0953 -0.9690 +vn 0.2803 -0.1050 -0.9542 +vn 0.1597 -0.1640 -0.9734 +vn -0.0042 -0.0310 -0.9995 +vn -0.1449 0.0932 -0.9850 +vn -0.2260 -0.0936 -0.9696 +vn -0.3513 0.0979 -0.9311 +vn -0.4396 -0.1007 -0.8925 +vn -0.0246 -0.2064 -0.9782 +vn 0.5614 -0.1015 -0.8213 +vn 0.4269 -0.0117 -0.9042 +vn -0.2743 -0.2481 -0.9291 +vn -0.5636 -0.0573 -0.8240 +vn 0.0622 -0.7805 -0.6220 +vn -0.1164 -0.7839 -0.6099 +vn -0.4005 0.7943 0.4569 +vn -0.6401 -0.1928 0.7437 +vn -0.7134 -0.1571 -0.6829 +vn -0.5971 0.0646 -0.7996 +vn -0.7041 0.2731 0.6555 +vn -0.6863 0.1203 0.7173 +vn -0.4640 -0.7863 0.4079 +vn -0.4944 -0.7847 -0.3739 +vn -0.7804 0.0065 -0.6252 +vn -0.4989 0.7919 0.3521 +vn -0.7561 -0.0268 0.6539 +vn -0.7553 -0.1893 0.6275 +vn -0.8097 0.1714 0.5612 +vn -0.8295 -0.2116 -0.5168 +vn -0.8428 -0.2309 0.4862 +vn -0.5282 -0.7908 0.3094 +vn -0.5529 -0.7890 -0.2679 +vn -0.5562 0.7853 0.2720 +vn -0.8656 -0.0314 0.4998 +vn -0.8828 -0.0477 -0.4673 +vn -0.8973 0.1742 0.4056 +vn -0.5950 -0.7809 0.1904 +vn -0.5287 0.7935 -0.3012 +vn -0.8737 0.1819 -0.4511 +vn -0.4503 0.7922 -0.4119 +vn -0.7841 0.2241 -0.5788 +vn -0.5906 -0.7866 -0.1802 +vn -0.9089 -0.2157 -0.3570 +vn -0.5988 0.7803 0.1807 +vn -0.9141 -0.1647 0.3707 +vn -0.3637 0.7883 -0.4963 +vn -0.6674 0.2076 -0.7151 +vn -0.2434 0.7738 -0.5848 +vn -0.4918 0.2158 -0.8435 +vn 0.0198 0.1714 -0.9850 +vn -0.9404 0.0760 -0.3313 +vn -0.9483 0.0317 0.3159 +vn -0.9497 -0.0897 -0.3001 +vn -0.9646 0.1662 0.2047 +vn -0.9547 -0.1459 0.2594 +vn -0.9660 -0.2167 0.1410 +vn -0.6161 -0.7868 0.0366 +vn -0.6052 -0.7926 -0.0738 +vn -0.9622 -0.2163 -0.1653 +vn -0.9747 0.1717 -0.1429 +vn -0.9737 -0.2270 -0.0186 +vn -0.9864 0.0028 -0.1642 +vn 0.6381 0.7520 -0.1656 +vn 0.5286 0.7467 -0.4037 +vn 0.6462 0.7543 0.1157 +vn 0.0411 0.7580 0.6509 +vn -0.6596 0.7514 -0.0184 +vn -0.5898 0.7548 -0.2872 +vn 0.3327 0.7532 -0.5674 +vn 0.1013 0.7498 -0.6539 +vn 0.3154 0.7573 0.5719 +vn -0.5135 0.7546 0.4085 +vn -0.4101 0.7560 -0.5102 +vn 0.5348 0.7547 0.3800 +vn -0.2664 0.7659 0.5852 +vn -0.6393 0.7393 0.2114 +vn -0.1555 0.7538 -0.6384 +vn 0.5919 -0.7577 0.2749 +vn 0.6562 -0.7546 -0.0075 +vn 0.5848 -0.7569 -0.2919 +vn -0.3924 -0.7407 0.5454 +vn -0.5425 -0.7536 0.3713 +vn -0.6438 -0.7565 0.1154 +vn -0.1754 -0.7527 0.6346 +vn 0.3895 -0.7648 0.5132 +vn 0.1023 -0.7578 0.6444 +vn 0.3773 -0.7629 -0.5250 +vn 0.0828 -0.7606 -0.6440 +vn -0.6341 -0.7542 -0.1707 +vn -0.2321 -0.7659 -0.5996 +vn -0.4936 -0.7574 -0.4274 +vn -0.9940 -0.0874 -0.0659 +vn -0.9956 -0.0808 0.0481 +vn -0.9945 0.1041 0.0072 +vn -0.3466 0.9059 0.2432 +vn -0.4369 0.8900 0.1306 +vn -0.6997 0.5985 0.3901 +vn -0.7744 -0.6292 0.0662 +vn -0.4405 -0.8971 -0.0345 +vn -0.4176 -0.8989 0.1330 +vn -0.7374 -0.6430 -0.2069 +vn -0.3857 -0.9008 -0.1995 +vn -0.2226 -0.6116 -0.7592 +vn -0.0081 -0.8962 -0.4437 +vn -0.2230 -0.8791 -0.4213 +vn 0.9963 0.0693 0.0501 +vn 0.9950 0.0187 -0.0984 +vn 0.9878 0.1475 -0.0500 +vn 0.9657 0.2546 0.0502 +vn 0.9679 0.1875 -0.1673 +vn 0.9238 0.3650 -0.1155 +vn 0.9127 0.0354 0.4072 +vn 0.9786 0.0564 0.1977 +vn 0.9474 0.1860 0.2605 +vn 0.9697 -0.2186 -0.1091 +vn 0.9835 -0.1434 0.1101 +vn 0.9408 -0.3297 0.0791 +vn 0.9912 -0.1107 -0.0730 +vn 0.9974 -0.0529 0.0492 +vn 0.9179 -0.3929 -0.0557 +vn 0.9039 0.4270 0.0232 +vn 0.8061 -0.0675 0.5879 +vn 0.8171 0.1019 0.5675 +vn 0.9300 0.1262 -0.3451 +vn 0.9714 -0.0139 -0.2372 +vn 0.9065 -0.0631 -0.4175 +vn 0.8305 -0.5313 -0.1674 +vn 0.8326 -0.5539 0.0014 +vn 0.8401 0.1282 -0.5270 +vn 0.8415 -0.0130 -0.5401 +vn 0.7250 0.1742 -0.6664 +vn 0.7259 -0.0267 -0.6873 +vn 0.7312 -0.6178 -0.2894 +vn 0.4385 -0.8951 -0.0802 +vn 0.8331 0.5153 -0.2010 +vn 0.7744 0.6248 -0.0996 +vn 0.8306 0.5523 0.0707 +vn 0.4410 0.8965 0.0421 +vn 0.4269 0.8920 -0.1488 +vn 0.9088 -0.3481 -0.2299 +vn 0.4423 -0.8958 0.0446 +vn 0.8596 -0.4767 0.1841 +vn 0.9386 -0.2567 0.2303 +vn 0.7597 -0.6120 0.2199 +vn 0.8830 -0.3568 0.3051 +vn 0.3761 0.8977 0.2296 +vn 0.7367 0.6337 0.2359 +vn 0.8884 0.3995 0.2262 +vn 0.3718 -0.9007 -0.2246 +vn 0.7666 -0.5134 0.3857 +vn 0.3936 -0.8960 0.2057 +vn 0.9467 -0.1183 0.2998 +vn 0.7997 0.3208 -0.5075 +vn 0.8228 -0.3487 0.4488 +vn 0.6153 -0.6250 0.4804 +vn 0.7547 0.5424 0.3691 +vn 0.6889 0.6117 -0.3890 +vn 0.8193 0.4551 -0.3488 +vn 0.3376 0.9007 -0.2734 +vn 0.9151 0.3132 -0.2540 +vn 0.8816 0.2607 -0.3935 +vn 0.8234 -0.4373 -0.3617 +vn 0.8820 -0.1667 0.4408 +vn 0.6186 0.6235 0.4781 +vn 0.6832 0.3909 -0.6168 +vn 0.5987 0.2586 -0.7581 +vn 0.6606 -0.5852 -0.4703 +vn 0.2661 0.8995 0.3464 +vn 0.5422 0.5858 0.6024 +vn 0.2837 -0.8903 -0.3562 +vn 0.5136 0.4184 -0.7491 +vn 0.7334 0.4340 0.5232 +vn 0.5484 0.5866 -0.5960 +vn 0.2492 0.9017 -0.3534 +vn 0.7016 0.5039 -0.5039 +vn 0.9278 -0.2123 -0.3069 +vn 0.4459 -0.6077 0.6571 +vn 0.2804 -0.8977 0.3397 +vn 0.3889 0.6039 -0.6958 +vn 0.3292 0.4638 -0.8225 +vn 0.8663 0.3432 0.3629 +vn 0.1923 0.6101 -0.7686 +vn 0.5766 -0.5433 -0.6103 +vn 0.6700 -0.4944 0.5537 +vn 0.1445 0.9060 -0.3979 +vn 0.1388 0.8864 0.4416 +vn 0.3631 0.6184 0.6970 +vn -0.0005 0.8963 -0.4434 +vn 0.1393 -0.9021 -0.4084 +vn 0.3805 -0.5878 -0.7140 +vn 0.7369 -0.3803 -0.5589 +vn 0.1416 -0.9007 0.4108 +vn 0.6210 0.0536 -0.7820 +vn -0.1670 0.1567 0.9734 +vn -0.3115 -0.1156 0.9432 +vn -0.0722 -0.0502 0.9961 +vn 0.0819 0.1073 0.9908 +vn 0.1779 -0.0888 0.9800 +vn 0.3483 0.1096 0.9310 +vn 0.3834 -0.0791 0.9202 +vn 0.5660 0.0354 0.8237 +vn 0.6990 0.0235 0.7147 +vn 0.0445 0.3151 0.9480 +vn 0.2355 0.2617 0.9360 +vn 0.5791 0.2170 0.7859 +vn 0.7333 0.2675 0.6251 +vn -0.1499 0.4059 0.9016 +vn -0.3230 0.2567 0.9109 +vn 0.3890 0.3237 0.8625 +vn 0.5713 0.4018 0.7157 +vn 0.8629 0.2217 0.4541 +vn 0.1748 0.5111 0.8416 +vn 0.3706 0.4910 0.7884 +vn -0.0130 0.5622 0.8269 +vn -0.2197 0.5925 0.7751 +vn 0.0060 0.8918 0.4524 +vn -0.1369 0.9001 0.4137 +vn -0.1971 0.5962 -0.7782 +vn -0.1365 0.9020 -0.4095 +vn -0.0026 0.5564 -0.8309 +vn -0.1912 0.3913 -0.9002 +vn 0.1299 0.3878 -0.9125 +vn -0.0493 0.2894 -0.9559 +vn 0.3058 0.2990 -0.9039 +vn 0.4371 0.2175 -0.8727 +vn -0.2419 0.1354 -0.9608 +vn 0.1222 0.1577 -0.9799 +vn 0.2835 0.1046 -0.9532 +vn -0.0048 0.0009 -1.0000 +vn 0.4843 0.0644 -0.8725 +vn -0.1447 -0.0197 -0.9893 +vn 0.1915 -0.0705 -0.9790 +vn 0.3739 -0.0815 -0.9239 +vn 0.5696 -0.1086 -0.8147 +vn -0.1727 -0.2349 -0.9566 +vn -0.3146 -0.0930 -0.9447 +vn 0.0456 -0.2420 -0.9692 +vn 0.7674 -0.1792 -0.6156 +vn 0.2801 -0.2772 -0.9191 +vn 0.4632 -0.2519 -0.8497 +vn 0.6267 -0.2502 -0.7380 +vn 0.1530 -0.4102 -0.8991 +vn -0.0663 -0.4395 -0.8958 +vn 0.8433 -0.2548 -0.4731 +vn -0.2583 -0.4373 -0.8614 +vn 0.3675 -0.4390 -0.8199 +vn 0.5578 -0.4191 -0.7164 +vn 0.0116 -0.5769 -0.8168 +vn 0.2010 -0.5954 -0.7779 +vn -0.3737 0.4303 0.8217 +vn -0.3711 0.4408 -0.8173 +vn -0.4141 0.0393 0.9094 +vn -0.3898 -0.2967 -0.8718 +vn -0.3902 0.2540 -0.8850 +vn -0.3764 0.5902 -0.7141 +vn -0.2456 0.8999 0.3604 +vn -0.4101 0.5817 0.7024 +vn -0.2798 0.8908 -0.3582 +vn -0.4313 -0.4973 -0.7528 +vn -0.4590 -0.0067 -0.8884 +vn -0.5332 0.2163 0.8179 +vn -0.5572 0.6294 0.5416 +vn -0.2633 -0.9118 -0.3152 +vn -0.5659 -0.5770 -0.5889 +vn -0.5336 -0.1966 -0.8226 +vn -0.5765 0.1913 -0.7944 +vn -0.5416 0.5071 -0.6704 +vn -0.5675 0.4556 0.6858 +vn -0.3240 -0.9016 -0.2865 +vn -0.5797 -0.3828 -0.7193 +vn -0.5927 0.0309 -0.8049 +vn -0.5704 0.3441 -0.7458 +vn -0.5379 -0.0961 0.8375 +vn -0.6070 0.5974 -0.5241 +vn -0.3829 0.8979 -0.2170 +vn -0.3406 -0.9016 0.2668 +vn -0.2510 -0.9001 0.3560 +vn -0.5801 -0.5842 0.5676 +vn -0.1398 -0.8892 0.4356 +vn -0.4213 -0.5767 0.6999 +vn 0.2127 -0.5926 0.7769 +vn 0.0009 -0.8929 0.4503 +vn -0.6189 -0.4113 0.6692 +vn -0.2604 -0.5351 0.8037 +vn -0.0544 -0.5514 0.8325 +vn 0.5830 -0.4397 0.6832 +vn 0.3588 -0.4629 0.8106 +vn 0.7549 -0.3012 0.5826 +vn 0.0630 -0.4252 0.9029 +vn -0.4815 -0.3437 0.8062 +vn -0.2759 -0.3678 0.8880 +vn 0.5324 -0.3296 0.7797 +vn -0.1722 -0.2746 0.9460 +vn 0.3019 -0.2928 0.9073 +vn 0.6859 -0.1974 0.7005 +vn 0.0664 -0.2563 0.9643 +vn 0.5196 -0.1727 0.8368 +vn -0.6669 -0.1919 0.7200 +vn -0.6996 -0.5803 -0.4169 +vn -0.6668 -0.1525 -0.7295 +vn -0.7339 0.4056 -0.5449 +vn -0.6990 0.4227 0.5769 +vn -0.6801 0.2321 0.6954 +vn -0.6944 0.0330 0.7188 +vn -0.6792 -0.6321 0.3729 +vn -0.7203 -0.3824 -0.5787 +vn -0.7376 0.0812 -0.6703 +vn -0.7070 0.2759 -0.6511 +vn -0.7133 0.5774 -0.3973 +vn -0.7421 -0.3891 0.5457 +vn -0.4571 0.8823 -0.1120 +vn -0.7584 -0.4974 0.4212 +vn -0.7941 -0.1907 0.5771 +vn -0.8201 -0.5175 0.2443 +vn -0.7686 -0.1713 -0.6163 +vn -0.7959 0.5226 -0.3057 +vn -0.8353 -0.0173 0.5496 +vn -0.8088 -0.4490 -0.3797 +vn -0.8362 0.2065 -0.5080 +vn -0.8250 0.5614 -0.0643 +vn -0.4489 0.8933 0.0239 +vn -0.8487 0.5175 0.1095 +vn -0.8224 0.5112 0.2497 +vn -0.8119 0.4007 0.4246 +vn -0.7962 0.2155 0.5654 +vn -0.8426 -0.5225 -0.1306 +vn -0.8574 -0.2716 -0.4372 +vn -0.8403 -0.0487 -0.5399 +vn -0.8691 -0.3073 0.3876 +vn -0.8842 0.3274 -0.3333 +vn -0.8873 -0.4484 0.1080 +vn -0.8963 -0.3705 -0.2437 +vn -0.8908 0.4231 -0.1659 +vn -0.8958 0.3245 0.3036 +vn -0.8834 0.1508 0.4437 +vn -0.9250 -0.1065 0.3648 +vn -0.9101 -0.0359 -0.4129 +vn -0.9149 0.1307 -0.3820 +vn -0.9325 -0.2851 0.2216 +vn -0.9148 -0.3997 -0.0587 +vn -0.9290 -0.2020 -0.3100 +vn -0.9430 0.3324 -0.0153 +vn -0.9463 0.2881 0.1464 +vn -0.9343 0.1760 0.3099 +vn -0.9603 -0.2724 0.0596 +vn -0.9550 0.0415 0.2937 +vn -0.9618 -0.2515 -0.1085 +vn -0.9640 0.0799 -0.2535 +vn -0.9624 0.2214 -0.1571 +vn -0.9712 -0.1113 -0.2108 +vn -0.9790 -0.1062 0.1740 +vn -0.9848 0.0988 0.1426 +vn -0.9923 0.0519 -0.1124 +vn -0.3174 0.9480 0.0246 +vn 0.1003 0.9503 -0.2947 +vn 0.2445 0.9415 -0.2319 +vn 0.2986 0.9504 -0.0871 +vn 0.2477 0.9641 0.0961 +vn 0.1746 0.9495 0.2606 +vn -0.3109 0.9417 -0.1290 +vn -0.1903 0.9526 -0.2375 +vn -0.0580 0.9445 -0.3234 +vn -0.0014 0.9532 0.3023 +vn -0.1727 0.9452 0.2772 +vn -0.2841 0.9416 0.1806 +vn 0.2420 -0.9417 0.2337 +vn 0.1010 -0.9497 0.2963 +vn 0.3007 -0.9510 0.0716 +vn 0.2986 -0.9478 -0.1115 +vn 0.1776 -0.9543 -0.2402 +vn -0.1095 -0.9580 0.2649 +vn -0.2684 -0.9583 0.0983 +vn -0.2460 -0.9636 -0.1047 +vn 0.0175 -0.9505 -0.3102 +vn -0.1372 -0.9588 -0.2488 +vn -0.2628 0.3412 0.9025 +vn -0.3037 -0.4384 0.8459 +vn -0.5768 0.3921 0.7167 +vn -0.7412 -0.2445 0.6252 +vn -0.7715 0.4058 0.4900 +vn -0.8988 0.4005 0.1780 +vn -0.8699 -0.4396 0.2236 +vn -0.9572 -0.2689 -0.1068 +vn -0.8953 0.3847 -0.2245 +vn -0.7113 -0.2851 -0.6424 +vn -0.7506 0.3551 -0.5573 +vn -0.4279 0.3839 -0.8182 +vn -0.2230 -0.3474 -0.9108 +vn -0.0173 0.3733 -0.9275 +vn 0.2674 -0.3576 -0.8948 +vn 0.3933 0.3996 -0.8280 +vn 0.6826 -0.3842 -0.6217 +vn 0.6559 0.3931 -0.6444 +vn 0.8468 0.4036 -0.3465 +vn 0.8984 -0.3894 -0.2031 +vn 0.9429 0.3231 0.0813 +vn 0.8782 -0.4229 0.2233 +vn 0.7437 0.3163 0.5889 +vn 0.6764 -0.4004 0.6182 +vn 0.3806 0.3610 0.8514 +vn 0.2076 -0.3954 0.8948 +vn 0.1009 0.4157 0.9039 +vn -0.7139 0.6783 0.1739 +vn -0.7292 0.4671 -0.5000 +vn -0.7136 0.4228 0.5585 +vn -0.7161 0.1573 -0.6800 +vn -0.7199 0.0169 0.6939 +vn -0.7199 -0.2532 -0.6463 +vn -0.7149 -0.3877 0.5819 +vn -0.7163 -0.5755 -0.3946 +vn -0.7221 -0.6382 0.2669 +vn -0.7234 0.6499 -0.2331 +vn -0.7286 -0.6827 -0.0546 +vn 0.6547 -0.4322 -0.6201 +vn 0.6368 -0.4576 0.6205 +vn 0.6355 -0.7466 0.1966 +vn 0.6571 0.7307 -0.1853 +vn 0.6402 0.7375 0.2150 +vn 0.6546 0.5816 -0.4830 +vn 0.6360 0.4560 0.6225 +vn 0.6558 0.3112 -0.6878 +vn 0.6425 0.0020 0.7663 +vn 0.6452 -0.0628 -0.7615 +vn 0.6398 -0.7063 -0.3031 +vn 0.7126 0.6965 0.0843 +vn 0.7118 0.4822 0.5108 +vn 0.7193 0.6176 -0.3181 +vn 0.7151 -0.6403 0.2805 +vn 0.7159 0.0787 -0.6937 +vn 0.7255 0.3971 -0.5621 +vn 0.7123 0.0501 0.7001 +vn 0.7180 -0.3598 0.5959 +vn 0.7215 -0.6808 -0.1265 +vn 0.7237 -0.5222 -0.4512 +vn 0.7271 -0.2711 -0.6307 +vn -0.6622 -0.6168 -0.4255 +vn -0.6557 -0.7436 -0.1312 +vn -0.6619 -0.7243 0.1931 +vn -0.6513 -0.3773 -0.6584 +vn -0.6501 -0.5668 0.5061 +vn -0.6457 0.6247 -0.4390 +vn -0.6386 0.3254 0.6974 +vn -0.6410 0.6844 0.3474 +vn -0.6583 0.3286 -0.6773 +vn -0.6381 -0.1842 0.7476 +vn -0.6535 -0.0128 -0.7568 +vn -0.6546 0.7529 -0.0680 +vn -0.0828 0.9815 -0.1728 +vn 0.0830 0.9966 -0.0017 +vn 0.0861 0.8701 -0.4853 +vn -0.0819 0.8240 -0.5606 +vn 0.0888 0.5819 -0.8084 +vn -0.0843 0.5710 -0.8166 +vn 0.0857 0.2626 -0.9611 +vn -0.0826 0.2441 -0.9662 +vn 0.0833 -0.0889 -0.9925 +vn -0.0829 -0.1728 -0.9815 +vn 0.0849 -0.4213 -0.9029 +vn -0.0833 -0.5610 -0.8236 +vn 0.0854 -0.7129 -0.6961 +vn -0.0827 -0.8245 -0.5598 +vn 0.0830 -0.9361 -0.3418 +vn -0.0841 -0.9815 -0.1722 +vn 0.0825 -0.9940 0.0723 +vn -0.0830 -0.9664 0.2434 +vn 0.0829 -0.9030 0.4215 +vn -0.0843 -0.8156 0.5725 +vn 0.0843 -0.7054 0.7038 +vn -0.0827 -0.5599 0.8244 +vn 0.0860 -0.4182 0.9043 +vn -0.0828 -0.1733 0.9814 +vn 0.0862 -0.0917 0.9920 +vn 0.0867 0.2618 0.9612 +vn -0.0832 0.2452 0.9659 +vn 0.0854 0.5792 0.8107 +vn -0.0828 0.5714 0.8165 +vn 0.0810 0.8702 0.4859 +vn -0.0849 0.8169 0.5705 +vn -0.0827 0.9662 0.2441 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/5 6/6/6 +f 7/7/7 8/8/8 9/9/9 +f 10/10/10 11/11/11 1/1/1 +f 12/12/12 13/13/13 14/14/14 +f 15/15/15 16/16/16 17/17/17 +f 18/18/18 19/19/19 20/20/20 +f 21/21/21 22/22/22 23/23/23 +f 24/24/24 21/21/21 23/23/23 +f 25/25/25 21/21/21 24/24/24 +f 26/26/26 27/27/27 28/28/28 +f 29/29/29 30/30/30 31/31/31 +f 31/31/31 30/30/30 32/32/32 +f 33/33/33 25/25/25 24/24/24 +f 33/33/33 24/24/24 34/34/34 +f 34/34/34 24/24/24 35/35/35 +f 16/16/16 36/36/36 37/37/37 +f 37/37/37 36/36/36 38/38/38 +f 39/39/39 25/25/25 33/33/33 +f 24/24/24 23/23/23 35/35/35 +f 34/34/34 40/40/40 41/41/41 +f 42/42/42 43/43/43 26/26/26 +f 16/16/16 15/15/15 44/44/44 +f 16/16/16 44/44/44 36/36/36 +f 38/38/38 45/45/45 37/37/37 +f 37/37/37 46/46/46 18/18/18 +f 39/39/39 47/47/47 25/25/25 +f 34/34/34 35/35/35 40/40/40 +f 48/48/48 26/26/26 28/28/28 +f 48/48/48 28/28/28 49/49/49 +f 50/50/50 47/47/47 39/39/39 +f 25/25/25 51/51/51 21/21/21 +f 21/21/21 51/51/51 22/22/22 +f 15/15/15 52/52/52 44/44/44 +f 37/37/37 45/45/45 46/46/46 +f 18/18/18 46/46/46 19/19/19 +f 53/53/53 31/31/31 54/54/54 +f 54/54/54 31/31/31 32/32/32 +f 51/51/51 55/55/55 22/22/22 +f 56/56/56 42/42/42 57/57/57 +f 57/57/57 42/42/42 26/26/26 +f 12/12/12 58/58/58 17/17/17 +f 50/50/50 59/59/59 60/60/60 +f 47/47/47 61/61/61 25/25/25 +f 25/25/25 61/61/61 51/51/51 +f 14/14/14 56/56/56 57/57/57 +f 57/57/57 26/26/26 62/62/62 +f 62/62/62 26/26/26 48/48/48 +f 17/17/17 62/62/62 15/15/15 +f 15/15/15 62/62/62 52/52/52 +f 1/1/1 63/63/63 64/64/64 +f 64/64/64 63/63/63 65/65/65 +f 50/50/50 60/60/60 47/47/47 +f 47/47/47 60/60/60 61/61/61 +f 58/58/58 62/62/62 17/17/17 +f 66/66/66 1/1/1 64/64/64 +f 60/60/60 65/65/65 53/53/53 +f 60/60/60 53/53/53 61/61/61 +f 61/61/61 53/53/53 67/67/67 +f 67/67/67 53/53/53 54/54/54 +f 12/12/12 14/14/14 57/57/57 +f 12/12/12 57/57/57 58/58/58 +f 58/58/58 57/57/57 62/62/62 +f 62/62/62 48/48/48 52/52/52 +f 52/52/52 48/48/48 49/49/49 +f 59/59/59 68/68/68 64/64/64 +f 59/59/59 64/64/64 60/60/60 +f 61/61/61 67/67/67 51/51/51 +f 51/51/51 67/67/67 55/55/55 +f 63/63/63 69/69/69 65/65/65 +f 65/65/65 69/69/69 70/70/70 +f 65/65/65 70/70/70 71/71/71 +f 29/29/29 72/72/72 73/73/73 +f 31/31/31 71/71/71 72/72/72 +f 31/31/31 72/72/72 29/29/29 +f 29/29/29 73/73/73 30/30/30 +f 53/53/53 65/65/65 71/71/71 +f 53/53/53 71/71/71 31/31/31 +f 60/60/60 64/64/64 65/65/65 +f 1/1/1 66/66/66 10/10/10 +f 54/54/54 55/55/55 67/67/67 +f 64/64/64 68/68/68 66/66/66 +f 66/66/66 74/74/74 10/10/10 +f 66/66/66 68/68/68 74/74/74 +f 7/7/7 9/9/9 75/75/75 +f 75/75/75 9/9/9 76/76/76 +f 77/77/77 76/76/76 41/41/41 +f 77/77/77 41/41/41 40/40/40 +f 78/78/78 40/40/40 35/35/35 +f 78/78/78 35/35/35 23/23/23 +f 79/79/79 75/75/75 76/76/76 +f 79/79/79 76/76/76 77/77/77 +f 80/80/80 81/81/81 7/7/7 +f 80/80/80 7/7/7 75/75/75 +f 77/77/77 40/40/40 82/82/82 +f 82/82/82 40/40/40 78/78/78 +f 80/80/80 75/75/75 79/79/79 +f 81/81/81 80/80/80 6/6/6 +f 42/42/42 80/80/80 79/79/79 +f 43/43/43 79/79/79 77/77/77 +f 56/56/56 6/6/6 80/80/80 +f 43/43/43 42/42/42 79/79/79 +f 43/43/43 77/77/77 27/27/27 +f 27/27/27 77/77/77 82/82/82 +f 56/56/56 80/80/80 42/42/42 +f 14/14/14 6/6/6 56/56/56 +f 13/13/13 4/4/4 6/6/6 +f 13/13/13 6/6/6 14/14/14 +f 26/26/26 43/43/43 27/27/27 +f 3/3/3 83/83/83 20/20/20 +f 70/70/70 20/20/20 19/19/19 +f 69/69/69 3/3/3 20/20/20 +f 69/69/69 20/20/20 70/70/70 +f 70/70/70 19/19/19 72/72/72 +f 72/72/72 19/19/19 46/46/46 +f 73/73/73 46/46/46 45/45/45 +f 72/72/72 46/46/46 73/73/73 +f 63/63/63 1/1/1 3/3/3 +f 63/63/63 3/3/3 69/69/69 +f 71/71/71 70/70/70 72/72/72 +f 30/30/30 73/73/73 45/45/45 +f 30/30/30 45/45/45 84/84/84 +f 85/85/85 86/86/86 87/87/87 +f 6/6/6 5/5/5 88/88/88 +f 89/89/89 90/90/90 91/91/91 +f 92/92/92 93/93/93 94/94/94 +f 95/95/95 93/93/93 96/96/96 +f 95/95/95 96/96/96 97/97/97 +f 98/98/98 99/99/99 100/100/100 +f 101/101/101 102/102/102 103/103/103 +f 81/81/81 104/104/104 7/7/7 +f 10/10/10 74/74/74 105/105/105 +f 8/8/8 7/7/7 106/106/106 +f 107/107/107 8/8/8 106/106/106 +f 108/108/108 4/4/4 109/109/109 +f 83/83/83 3/3/3 2/2/2 +f 83/83/83 2/2/2 110/110/110 +f 10/10/10 105/105/105 111/111/111 +f 112/112/112 111/111/111 103/103/103 +f 107/107/107 106/106/106 113/113/113 +f 107/107/107 113/113/113 114/114/114 +f 114/114/114 113/113/113 115/115/115 +f 108/108/108 5/5/5 4/4/4 +f 116/116/116 108/108/108 109/109/109 +f 116/116/116 109/109/109 117/117/117 +f 116/116/116 117/117/117 118/118/118 +f 118/118/118 117/117/117 119/119/119 +f 110/110/110 2/2/2 120/120/120 +f 120/120/120 2/2/2 121/121/121 +f 120/120/120 121/121/121 122/122/122 +f 122/122/122 121/121/121 123/123/123 +f 113/113/113 106/106/106 124/124/124 +f 115/115/115 113/113/113 125/125/125 +f 115/115/115 125/125/125 126/126/126 +f 106/106/106 7/7/7 104/104/104 +f 126/126/126 125/125/125 127/127/127 +f 126/126/126 127/127/127 128/128/128 +f 128/128/128 127/127/127 129/129/129 +f 124/124/124 130/130/130 113/113/113 +f 113/113/113 130/130/130 125/125/125 +f 125/125/125 130/130/130 131/131/131 +f 125/125/125 131/131/131 127/127/127 +f 106/106/106 104/104/104 124/124/124 +f 131/131/131 132/132/132 127/127/127 +f 104/104/104 81/81/81 88/88/88 +f 124/124/124 104/104/104 133/133/133 +f 124/124/124 133/133/133 130/130/130 +f 131/131/131 130/130/130 134/134/134 +f 131/131/131 134/134/134 132/132/132 +f 127/127/127 132/132/132 135/135/135 +f 127/127/127 135/135/135 129/129/129 +f 129/129/129 135/135/135 136/136/136 +f 81/81/81 6/6/6 88/88/88 +f 104/104/104 88/88/88 108/108/108 +f 104/104/104 108/108/108 133/133/133 +f 130/130/130 133/133/133 118/118/118 +f 130/130/130 118/118/118 134/134/134 +f 132/132/132 134/134/134 135/135/135 +f 133/133/133 108/108/108 116/116/116 +f 133/133/133 116/116/116 118/118/118 +f 134/134/134 119/119/119 135/135/135 +f 88/88/88 5/5/5 108/108/108 +f 134/134/134 118/118/118 119/119/119 +f 135/135/135 119/119/119 137/137/137 +f 135/135/135 137/137/137 136/136/136 +f 137/137/137 138/138/138 136/136/136 +f 136/136/136 139/139/139 129/129/129 +f 129/129/129 139/139/139 140/140/140 +f 129/129/129 140/140/140 128/128/128 +f 138/138/138 141/141/141 142/142/142 +f 138/138/138 142/142/142 136/136/136 +f 136/136/136 142/142/142 139/139/139 +f 142/142/142 143/143/143 139/139/139 +f 139/139/139 143/143/143 144/144/144 +f 139/139/139 144/144/144 140/140/140 +f 140/140/140 144/144/144 145/145/145 +f 141/141/141 146/146/146 142/142/142 +f 142/142/142 146/146/146 143/143/143 +f 147/147/147 148/148/148 112/112/112 +f 147/147/147 112/112/112 149/149/149 +f 149/149/149 150/150/150 151/151/151 +f 152/152/152 153/153/153 154/154/154 +f 155/155/155 152/152/152 156/156/156 +f 153/153/153 151/151/151 154/154/154 +f 152/152/152 154/154/154 157/157/157 +f 152/152/152 157/157/157 156/156/156 +f 149/149/149 112/112/112 150/150/150 +f 151/151/151 150/150/150 102/102/102 +f 151/151/151 102/102/102 154/154/154 +f 11/11/11 10/10/10 148/148/148 +f 148/148/148 10/10/10 112/112/112 +f 154/154/154 102/102/102 158/158/158 +f 156/156/156 157/157/157 159/159/159 +f 112/112/112 10/10/10 111/111/111 +f 150/150/150 112/112/112 103/103/103 +f 150/150/150 103/103/103 102/102/102 +f 102/102/102 101/101/101 158/158/158 +f 154/154/154 158/158/158 157/157/157 +f 157/157/157 158/158/158 160/160/160 +f 157/157/157 160/160/160 159/159/159 +f 141/141/141 161/161/161 146/146/146 +f 159/159/159 162/162/162 156/156/156 +f 156/156/156 162/162/162 163/163/163 +f 156/156/156 163/163/163 155/155/155 +f 146/146/146 164/164/164 143/143/143 +f 143/143/143 164/164/164 144/144/144 +f 144/144/144 165/165/165 145/145/145 +f 166/166/166 162/162/162 159/159/159 +f 161/161/161 167/167/167 146/146/146 +f 146/146/146 167/167/167 164/164/164 +f 164/164/164 168/168/168 144/144/144 +f 144/144/144 168/168/168 165/165/165 +f 161/161/161 169/169/169 167/167/167 +f 164/164/164 167/167/167 170/170/170 +f 164/164/164 170/170/170 168/168/168 +f 165/165/165 168/168/168 171/171/171 +f 172/172/172 173/173/173 166/166/166 +f 166/166/166 173/173/173 162/162/162 +f 162/162/162 174/174/174 163/163/163 +f 162/162/162 173/173/173 174/174/174 +f 169/169/169 175/175/175 167/167/167 +f 167/167/167 175/175/175 170/170/170 +f 170/170/170 176/176/176 168/168/168 +f 168/168/168 176/176/176 171/171/171 +f 173/173/173 177/177/177 174/174/174 +f 178/178/178 175/175/175 169/169/169 +f 170/170/170 175/175/175 179/179/179 +f 170/170/170 179/179/179 176/176/176 +f 172/172/172 98/98/98 180/180/180 +f 172/172/172 180/180/180 173/173/173 +f 173/173/173 180/180/180 177/177/177 +f 178/178/178 181/181/181 175/175/175 +f 179/179/179 182/182/182 176/176/176 +f 176/176/176 182/182/182 183/183/183 +f 176/176/176 183/183/183 171/171/171 +f 171/171/171 183/183/183 184/184/184 +f 94/94/94 185/185/185 186/186/186 +f 185/185/185 187/187/187 186/186/186 +f 178/178/178 188/188/188 181/181/181 +f 175/175/175 181/181/181 179/179/179 +f 179/179/179 181/181/181 182/182/182 +f 92/92/92 94/94/94 186/186/186 +f 90/90/90 89/89/89 189/189/189 +f 90/90/90 189/189/189 190/190/190 +f 90/90/90 190/190/190 191/191/191 +f 187/187/187 191/191/191 192/192/192 +f 187/187/187 192/192/192 193/193/193 +f 187/187/187 193/193/193 186/186/186 +f 122/122/122 194/194/194 91/91/91 +f 91/91/91 194/194/194 89/89/89 +f 191/191/191 190/190/190 192/192/192 +f 186/186/186 193/193/193 174/174/174 +f 121/121/121 147/147/147 123/123/123 +f 122/122/122 123/123/123 194/194/194 +f 189/189/189 89/89/89 152/152/152 +f 186/186/186 174/174/174 195/195/195 +f 194/194/194 153/153/153 89/89/89 +f 89/89/89 153/153/153 152/152/152 +f 189/189/189 152/152/152 190/190/190 +f 190/190/190 155/155/155 192/192/192 +f 193/193/193 192/192/192 163/163/163 +f 193/193/193 163/163/163 174/174/174 +f 2/2/2 1/1/1 11/11/11 +f 2/2/2 11/11/11 148/148/148 +f 2/2/2 148/148/148 121/121/121 +f 121/121/121 148/148/148 147/147/147 +f 123/123/123 147/147/147 149/149/149 +f 123/123/123 149/149/149 151/151/151 +f 123/123/123 151/151/151 194/194/194 +f 190/190/190 152/152/152 155/155/155 +f 192/192/192 155/155/155 163/163/163 +f 195/195/195 174/174/174 177/177/177 +f 194/194/194 151/151/151 153/153/153 +f 188/188/188 196/196/196 181/181/181 +f 181/181/181 197/197/197 182/182/182 +f 98/98/98 100/100/100 180/180/180 +f 195/195/195 92/92/92 186/186/186 +f 95/95/95 97/97/97 188/188/188 +f 188/188/188 97/97/97 196/196/196 +f 181/181/181 196/196/196 197/197/197 +f 184/184/184 183/183/183 198/198/198 +f 184/184/184 198/198/198 199/199/199 +f 199/199/199 100/100/100 99/99/99 +f 180/180/180 100/100/100 200/200/200 +f 180/180/180 200/200/200 177/177/177 +f 177/177/177 200/200/200 195/195/195 +f 92/92/92 201/201/201 93/93/93 +f 93/93/93 201/201/201 96/96/96 +f 195/195/195 200/200/200 202/202/202 +f 195/195/195 202/202/202 92/92/92 +f 92/92/92 202/202/202 201/201/201 +f 197/197/197 203/203/203 182/182/182 +f 182/182/182 203/203/203 183/183/183 +f 183/183/183 203/203/203 198/198/198 +f 199/199/199 198/198/198 204/204/204 +f 199/199/199 204/204/204 100/100/100 +f 201/201/201 205/205/205 96/96/96 +f 96/96/96 205/205/205 97/97/97 +f 97/97/97 205/205/205 196/196/196 +f 196/196/196 85/85/85 197/197/197 +f 197/197/197 85/85/85 203/203/203 +f 100/100/100 204/204/204 206/206/206 +f 100/100/100 206/206/206 200/200/200 +f 200/200/200 86/86/86 202/202/202 +f 202/202/202 86/86/86 201/201/201 +f 201/201/201 86/86/86 205/205/205 +f 196/196/196 205/205/205 85/85/85 +f 198/198/198 203/203/203 204/204/204 +f 200/200/200 206/206/206 86/86/86 +f 205/205/205 86/86/86 85/85/85 +f 85/85/85 87/87/87 203/203/203 +f 203/203/203 87/87/87 204/204/204 +f 204/204/204 87/87/87 206/206/206 +f 206/206/206 87/87/87 86/86/86 +f 207/207/207 188/188/188 178/178/178 +f 207/207/207 178/178/178 169/169/169 +f 208/208/208 93/93/93 95/95/95 +f 209/209/209 91/91/91 90/90/90 +f 18/18/18 210/210/210 211/211/211 +f 37/37/37 18/18/18 211/211/211 +f 17/17/17 16/16/16 211/211/211 +f 12/12/12 17/17/17 211/211/211 +f 13/13/13 12/12/12 212/212/212 +f 207/207/207 169/169/169 213/213/213 +f 213/213/213 169/169/169 161/161/161 +f 95/95/95 188/188/188 208/208/208 +f 208/208/208 188/188/188 207/207/207 +f 208/208/208 94/94/94 93/93/93 +f 90/90/90 214/214/214 209/209/209 +f 215/215/215 122/122/122 209/209/209 +f 210/210/210 18/18/18 20/20/20 +f 211/211/211 16/16/16 37/37/37 +f 212/212/212 12/12/12 211/211/211 +f 117/117/117 109/109/109 216/216/216 +f 217/217/217 94/94/94 208/208/208 +f 185/185/185 94/94/94 217/217/217 +f 214/214/214 187/187/187 217/217/217 +f 217/217/217 187/187/187 185/185/185 +f 187/187/187 214/214/214 191/191/191 +f 214/214/214 90/90/90 191/191/191 +f 122/122/122 91/91/91 209/209/209 +f 20/20/20 83/83/83 210/210/210 +f 210/210/210 83/83/83 218/218/218 +f 212/212/212 4/4/4 13/13/13 +f 216/216/216 109/109/109 212/212/212 +f 212/212/212 109/109/109 4/4/4 +f 219/219/219 141/141/141 138/138/138 +f 141/141/141 213/213/213 161/161/161 +f 220/220/220 119/119/119 216/216/216 +f 216/216/216 119/119/119 117/117/117 +f 220/220/220 137/137/137 119/119/119 +f 219/219/219 138/138/138 137/137/137 +f 219/219/219 137/137/137 220/220/220 +f 213/213/213 141/141/141 219/219/219 +f 221/221/221 120/120/120 122/122/122 +f 221/221/221 122/122/122 215/215/215 +f 110/110/110 221/221/221 218/218/218 +f 110/110/110 218/218/218 83/83/83 +f 110/110/110 120/120/120 221/221/221 +f 98/98/98 222/222/222 99/99/99 +f 223/223/223 199/199/199 224/224/224 +f 223/223/223 184/184/184 199/199/199 +f 68/68/68 59/59/59 225/225/225 +f 74/74/74 225/225/225 226/226/226 +f 226/226/226 105/105/105 74/74/74 +f 224/224/224 99/99/99 222/222/222 +f 224/224/224 199/199/199 99/99/99 +f 227/227/227 171/171/171 223/223/223 +f 223/223/223 171/171/171 184/184/184 +f 228/228/228 59/59/59 50/50/50 +f 111/111/111 105/105/105 226/226/226 +f 229/229/229 103/103/103 226/226/226 +f 230/230/230 160/160/160 158/158/158 +f 225/225/225 59/59/59 228/228/228 +f 225/225/225 74/74/74 68/68/68 +f 226/226/226 103/103/103 111/111/111 +f 103/103/103 229/229/229 101/101/101 +f 158/158/158 101/101/101 229/229/229 +f 159/159/159 160/160/160 231/231/231 +f 231/231/231 160/160/160 230/230/230 +f 222/222/222 98/98/98 172/172/172 +f 165/165/165 171/171/171 227/227/227 +f 128/128/128 232/232/232 233/233/233 +f 228/228/228 50/50/50 39/39/39 +f 230/230/230 158/158/158 229/229/229 +f 159/159/159 231/231/231 166/166/166 +f 234/234/234 9/9/9 8/8/8 +f 222/222/222 172/172/172 231/231/231 +f 128/128/128 140/140/140 232/232/232 +f 233/233/233 126/126/126 128/128/128 +f 235/235/235 107/107/107 114/114/114 +f 234/234/234 107/107/107 235/235/235 +f 234/234/234 8/8/8 107/107/107 +f 236/236/236 76/76/76 234/234/234 +f 234/234/234 76/76/76 9/9/9 +f 236/236/236 33/33/33 34/34/34 +f 228/228/228 39/39/39 236/236/236 +f 172/172/172 166/166/166 231/231/231 +f 232/232/232 145/145/145 165/165/165 +f 232/232/232 165/165/165 227/227/227 +f 236/236/236 39/39/39 33/33/33 +f 140/140/140 145/145/145 232/232/232 +f 233/233/233 115/115/115 126/126/126 +f 236/236/236 41/41/41 76/76/76 +f 236/236/236 34/34/34 41/41/41 +f 114/114/114 115/115/115 235/235/235 +f 235/235/235 115/115/115 233/233/233 +f 229/229/229 209/209/209 230/230/230 +f 230/230/230 209/209/209 231/231/231 +f 231/231/231 209/209/209 214/214/214 +f 231/231/231 214/214/214 222/222/222 +f 222/222/222 214/214/214 217/217/217 +f 222/222/222 217/217/217 208/208/208 +f 222/222/222 208/208/208 224/224/224 +f 224/224/224 208/208/208 223/223/223 +f 223/223/223 208/208/208 207/207/207 +f 223/223/223 207/207/207 227/227/227 +f 227/227/227 207/207/207 213/213/213 +f 227/227/227 213/213/213 232/232/232 +f 232/232/232 213/213/213 219/219/219 +f 232/232/232 219/219/219 233/233/233 +f 233/233/233 219/219/219 220/220/220 +f 233/233/233 220/220/220 235/235/235 +f 235/235/235 220/220/220 216/216/216 +f 235/235/235 216/216/216 234/234/234 +f 234/234/234 216/216/216 212/212/212 +f 234/234/234 212/212/212 236/236/236 +f 236/236/236 212/212/212 211/211/211 +f 236/236/236 211/211/211 228/228/228 +f 228/228/228 211/211/211 210/210/210 +f 228/228/228 210/210/210 225/225/225 +f 225/225/225 210/210/210 218/218/218 +f 225/225/225 218/218/218 226/226/226 +f 226/226/226 218/218/218 221/221/221 +f 226/226/226 221/221/221 229/229/229 +f 229/229/229 221/221/221 215/215/215 +f 229/229/229 215/215/215 209/209/209 +f 237/237/237 238/238/238 239/239/239 +f 240/240/240 241/241/241 242/242/242 +f 243/243/243 244/244/244 245/245/245 +f 246/246/246 247/247/247 248/248/248 +f 249/249/249 250/250/250 251/251/251 +f 252/252/252 253/253/253 254/254/254 +f 255/255/255 256/256/256 257/257/257 +f 249/249/249 251/251/251 258/258/258 +f 250/250/250 259/259/259 252/252/252 +f 260/260/260 257/257/257 261/261/261 +f 260/260/260 261/261/261 262/262/262 +f 249/249/249 258/258/258 263/263/263 +f 263/263/263 258/258/258 264/264/264 +f 263/263/263 264/264/264 265/265/265 +f 260/260/260 262/262/262 266/266/266 +f 265/265/265 267/267/267 268/268/268 +f 269/269/269 254/254/254 270/270/270 +f 271/271/271 259/259/259 272/272/272 +f 271/271/271 272/272/272 273/273/273 +f 274/274/274 252/252/252 254/254/254 +f 275/275/275 273/273/273 276/276/276 +f 277/277/277 278/278/278 279/279/279 +f 254/254/254 280/280/280 274/274/274 +f 281/281/281 282/282/282 269/269/269 +f 269/269/269 270/270/270 281/281/281 +f 271/271/271 273/273/273 275/275/275 +f 266/266/266 262/262/262 278/278/278 +f 261/261/261 283/283/283 262/262/262 +f 262/262/262 284/284/284 278/278/278 +f 278/278/278 285/285/285 279/279/279 +f 283/283/283 284/284/284 262/262/262 +f 278/278/278 284/284/284 285/285/285 +f 283/283/283 286/286/286 287/287/287 +f 283/283/283 287/287/287 284/284/284 +f 286/286/286 283/283/283 261/261/261 +f 282/282/282 288/288/288 269/269/269 +f 254/254/254 269/269/269 280/280/280 +f 289/289/289 281/281/281 270/270/270 +f 290/290/290 281/281/281 289/289/289 +f 277/277/277 266/266/266 278/278/278 +f 277/277/277 279/279/279 291/291/291 +f 284/284/284 292/292/292 285/285/285 +f 256/256/256 249/249/249 293/293/293 +f 261/261/261 293/293/293 286/286/286 +f 294/294/294 285/285/285 292/292/292 +f 295/295/295 284/284/284 287/287/287 +f 296/296/296 269/269/269 288/288/288 +f 297/297/297 270/270/270 254/254/254 +f 290/290/290 289/289/289 298/298/298 +f 284/284/284 295/295/295 299/299/299 +f 284/284/284 299/299/299 292/292/292 +f 292/292/292 299/299/299 294/294/294 +f 249/249/249 300/300/300 293/293/293 +f 287/287/287 286/286/286 301/301/301 +f 287/287/287 301/301/301 295/295/295 +f 302/302/302 299/299/299 295/295/295 +f 302/302/302 295/295/295 301/301/301 +f 286/286/286 293/293/293 300/300/300 +f 249/249/249 256/256/256 250/250/250 +f 250/250/250 252/252/252 274/274/274 +f 303/303/303 296/296/296 304/304/304 +f 304/304/304 296/296/296 288/288/288 +f 269/269/269 296/296/296 305/305/305 +f 269/269/269 305/305/305 280/280/280 +f 274/274/274 280/280/280 251/251/251 +f 306/306/306 289/289/289 270/270/270 +f 306/306/306 270/270/270 297/297/297 +f 307/307/307 289/289/289 306/306/306 +f 297/297/297 254/254/254 253/253/253 +f 308/308/308 309/309/309 310/310/310 +f 286/286/286 311/311/311 301/301/301 +f 299/299/299 302/302/302 312/312/312 +f 299/299/299 312/312/312 294/294/294 +f 286/286/286 313/313/313 314/314/314 +f 314/314/314 313/313/313 315/315/315 +f 314/314/314 315/315/315 286/286/286 +f 286/286/286 315/315/315 311/311/311 +f 311/311/311 316/316/316 301/301/301 +f 301/301/301 316/316/316 302/302/302 +f 261/261/261 257/257/257 293/293/293 +f 293/293/293 257/257/257 256/256/256 +f 256/256/256 255/255/255 250/250/250 +f 288/288/288 317/317/317 304/304/304 +f 305/305/305 296/296/296 303/303/303 +f 305/305/305 303/303/303 280/280/280 +f 318/318/318 319/319/319 290/290/290 +f 320/320/320 290/290/290 321/321/321 +f 321/321/321 290/290/290 298/298/298 +f 321/321/321 298/298/298 289/289/289 +f 321/321/321 289/289/289 307/307/307 +f 253/253/253 259/259/259 271/271/271 +f 322/322/322 275/275/275 309/309/309 +f 323/323/323 309/309/309 308/308/308 +f 324/324/324 308/308/308 310/310/310 +f 277/277/277 291/291/291 325/325/325 +f 304/304/304 317/317/317 326/326/326 +f 304/304/304 326/326/326 303/303/303 +f 274/274/274 251/251/251 250/250/250 +f 327/327/327 290/290/290 320/320/320 +f 328/328/328 271/271/271 329/329/329 +f 329/329/329 271/271/271 275/275/275 +f 330/330/330 275/275/275 322/322/322 +f 331/331/331 322/322/322 309/309/309 +f 331/331/331 309/309/309 323/323/323 +f 323/323/323 308/308/308 324/324/324 +f 332/332/332 324/324/324 310/310/310 +f 291/291/291 333/333/333 325/325/325 +f 334/334/334 331/331/331 323/323/323 +f 334/334/334 323/323/323 332/332/332 +f 332/332/332 323/323/323 324/324/324 +f 317/317/317 244/244/244 335/335/335 +f 317/317/317 336/336/336 326/326/326 +f 337/337/337 338/338/338 319/319/319 +f 334/334/334 319/319/319 318/318/318 +f 318/318/318 290/290/290 327/327/327 +f 328/328/328 307/307/307 306/306/306 +f 328/328/328 306/306/306 297/297/297 +f 328/328/328 297/297/297 253/253/253 +f 321/321/321 329/329/329 275/275/275 +f 321/321/321 275/275/275 330/330/330 +f 321/321/321 330/330/330 322/322/322 +f 322/322/322 331/331/331 334/334/334 +f 291/291/291 339/339/339 333/333/333 +f 325/325/325 333/333/333 340/340/340 +f 325/325/325 340/340/340 277/277/277 +f 341/341/341 328/328/328 342/342/342 +f 342/342/342 328/328/328 329/329/329 +f 342/342/342 329/329/329 321/321/321 +f 343/343/343 321/321/321 322/322/322 +f 317/317/317 335/335/335 336/336/336 +f 336/336/336 335/335/335 344/344/344 +f 326/326/326 336/336/336 345/345/345 +f 326/326/326 345/345/345 303/303/303 +f 280/280/280 258/258/258 251/251/251 +f 346/346/346 338/338/338 337/337/337 +f 334/334/334 337/337/337 319/319/319 +f 318/318/318 327/327/327 321/321/321 +f 321/321/321 327/327/327 320/320/320 +f 321/321/321 307/307/307 328/328/328 +f 252/252/252 259/259/259 253/253/253 +f 253/253/253 271/271/271 328/328/328 +f 334/334/334 343/343/343 322/322/322 +f 347/347/347 312/312/312 302/302/302 +f 321/321/321 341/341/341 342/342/342 +f 321/321/321 343/343/343 348/348/348 +f 348/348/348 343/343/343 334/334/334 +f 337/337/337 334/334/334 332/332/332 +f 337/337/337 332/332/332 349/349/349 +f 328/328/328 341/341/341 321/321/321 +f 318/318/318 348/348/348 334/334/334 +f 346/346/346 337/337/337 349/349/349 +f 244/244/244 243/243/243 335/335/335 +f 336/336/336 344/344/344 350/350/350 +f 336/336/336 350/350/350 345/345/345 +f 345/345/345 350/350/350 303/303/303 +f 280/280/280 303/303/303 258/258/258 +f 348/348/348 318/318/318 321/321/321 +f 309/309/309 275/275/275 276/276/276 +f 339/339/339 351/351/351 352/352/352 +f 339/339/339 353/353/353 333/333/333 +f 340/340/340 333/333/333 354/354/354 +f 340/340/340 354/354/354 277/277/277 +f 277/277/277 354/354/354 355/355/355 +f 277/277/277 355/355/355 356/356/356 +f 266/266/266 277/277/277 357/357/357 +f 257/257/257 260/260/260 272/272/272 +f 358/358/358 347/347/347 359/359/359 +f 360/360/360 347/347/347 302/302/302 +f 360/360/360 302/302/302 361/361/361 +f 362/362/362 346/346/346 349/349/349 +f 363/363/363 276/276/276 273/273/273 +f 272/272/272 259/259/259 257/257/257 +f 364/364/364 365/365/365 366/366/366 +f 366/366/366 367/367/367 368/368/368 +f 369/369/369 370/370/370 371/371/371 +f 372/372/372 364/364/364 366/366/366 +f 373/373/373 374/374/374 372/372/372 +f 372/372/372 374/374/374 364/364/364 +f 375/375/375 368/368/368 369/369/369 +f 376/376/376 369/369/369 371/371/371 +f 377/377/377 366/366/366 368/368/368 +f 377/377/377 368/368/368 375/375/375 +f 378/378/378 372/372/372 366/366/366 +f 377/377/377 378/378/378 366/366/366 +f 376/376/376 371/371/371 267/267/267 +f 375/375/375 369/369/369 376/376/376 +f 379/379/379 373/373/373 372/372/372 +f 379/379/379 372/372/372 378/378/378 +f 380/380/380 379/379/379 378/378/378 +f 243/243/243 378/378/378 377/377/377 +f 350/350/350 376/376/376 267/267/267 +f 380/380/380 378/378/378 243/243/243 +f 303/303/303 267/267/267 264/264/264 +f 243/243/243 377/377/377 335/335/335 +f 381/381/381 377/377/377 375/375/375 +f 381/381/381 375/375/375 382/382/382 +f 382/382/382 375/375/375 376/376/376 +f 303/303/303 350/350/350 383/383/383 +f 383/383/383 350/350/350 267/267/267 +f 383/383/383 267/267/267 303/303/303 +f 303/303/303 264/264/264 258/258/258 +f 384/384/384 379/379/379 380/380/380 +f 335/335/335 377/377/377 381/381/381 +f 335/335/335 381/381/381 382/382/382 +f 335/335/335 382/382/382 385/385/385 +f 385/385/385 382/382/382 376/376/376 +f 385/385/385 376/376/376 350/350/350 +f 380/380/380 243/243/243 245/245/245 +f 380/380/380 245/245/245 384/384/384 +f 384/384/384 245/245/245 386/386/386 +f 344/344/344 335/335/335 385/385/385 +f 344/344/344 385/385/385 350/350/350 +f 371/371/371 268/268/268 267/267/267 +f 267/267/267 265/265/265 264/264/264 +f 387/387/387 388/388/388 362/362/362 +f 389/389/389 387/387/387 362/362/362 +f 389/389/389 362/362/362 349/349/349 +f 390/390/390 389/389/389 349/349/349 +f 391/391/391 387/387/387 390/390/390 +f 390/390/390 387/387/387 389/389/389 +f 392/392/392 390/390/390 349/349/349 +f 393/393/393 349/349/349 332/332/332 +f 393/393/393 392/392/392 349/349/349 +f 394/394/394 391/391/391 390/390/390 +f 394/394/394 390/390/390 392/392/392 +f 395/395/395 391/391/391 394/394/394 +f 396/396/396 392/392/392 393/393/393 +f 396/396/396 393/393/393 310/310/310 +f 395/395/395 394/394/394 396/396/396 +f 396/396/396 394/394/394 392/392/392 +f 397/397/397 396/396/396 310/310/310 +f 398/398/398 310/310/310 309/309/309 +f 399/399/399 395/395/395 396/396/396 +f 398/398/398 397/397/397 310/310/310 +f 399/399/399 400/400/400 395/395/395 +f 401/401/401 399/399/399 396/396/396 +f 402/402/402 396/396/396 397/397/397 +f 403/403/403 398/398/398 309/309/309 +f 403/403/403 309/309/309 276/276/276 +f 401/401/401 396/396/396 402/402/402 +f 403/403/403 397/397/397 398/398/398 +f 404/404/404 400/400/400 399/399/399 +f 405/405/405 399/399/399 401/401/401 +f 406/406/406 403/403/403 276/276/276 +f 405/405/405 404/404/404 399/399/399 +f 402/402/402 397/397/397 403/403/403 +f 407/407/407 404/404/404 405/405/405 +f 408/408/408 401/401/401 402/402/402 +f 409/409/409 404/404/404 407/407/407 +f 410/410/410 402/402/402 403/403/403 +f 411/411/411 405/405/405 401/401/401 +f 411/411/411 401/401/401 408/408/408 +f 412/412/412 408/408/408 402/402/402 +f 354/354/354 403/403/403 406/406/406 +f 363/363/363 406/406/406 276/276/276 +f 413/413/413 407/407/407 405/405/405 +f 413/413/413 405/405/405 411/411/411 +f 412/412/412 402/402/402 410/410/410 +f 410/410/410 403/403/403 354/354/354 +f 414/414/414 354/354/354 406/406/406 +f 413/413/413 409/409/409 407/407/407 +f 354/354/354 414/414/414 363/363/363 +f 363/363/363 414/414/414 406/406/406 +f 363/363/363 273/273/273 272/272/272 +f 415/415/415 409/409/409 413/413/413 +f 415/415/415 413/413/413 411/411/411 +f 416/416/416 411/411/411 408/408/408 +f 352/352/352 408/408/408 412/412/412 +f 415/415/415 411/411/411 416/416/416 +f 352/352/352 416/416/416 408/408/408 +f 417/417/417 412/412/412 410/410/410 +f 352/352/352 412/412/412 417/417/417 +f 418/418/418 354/354/354 363/363/363 +f 419/419/419 363/363/363 272/272/272 +f 363/363/363 357/357/357 418/418/418 +f 354/354/354 418/418/418 356/356/356 +f 354/354/354 356/356/356 355/355/355 +f 410/410/410 354/354/354 417/417/417 +f 417/417/417 354/354/354 353/353/353 +f 417/417/417 353/353/353 352/352/352 +f 415/415/415 416/416/416 351/351/351 +f 415/415/415 351/351/351 420/420/420 +f 420/420/420 421/421/421 415/415/415 +f 351/351/351 416/416/416 352/352/352 +f 339/339/339 352/352/352 353/353/353 +f 333/333/333 353/353/353 354/354/354 +f 277/277/277 356/356/356 418/418/418 +f 277/277/277 418/418/418 357/357/357 +f 266/266/266 357/357/357 363/363/363 +f 266/266/266 363/363/363 419/419/419 +f 266/266/266 419/419/419 260/260/260 +f 260/260/260 419/419/419 272/272/272 +f 255/255/255 257/257/257 259/259/259 +f 255/255/255 259/259/259 250/250/250 +f 393/393/393 332/332/332 310/310/310 +f 386/386/386 422/422/422 384/384/384 +f 384/384/384 423/423/423 379/379/379 +f 379/379/379 423/423/423 373/373/373 +f 415/415/415 421/421/421 409/409/409 +f 400/400/400 424/424/424 395/395/395 +f 395/395/395 424/424/424 391/391/391 +f 384/384/384 422/422/422 423/423/423 +f 373/373/373 425/425/425 374/374/374 +f 374/374/374 425/425/425 426/426/426 +f 420/420/420 427/427/427 421/421/421 +f 409/409/409 428/428/428 404/404/404 +f 404/404/404 428/428/428 400/400/400 +f 400/400/400 428/428/428 429/429/429 +f 400/400/400 429/429/429 424/424/424 +f 391/391/391 430/430/430 387/387/387 +f 387/387/387 430/430/430 388/388/388 +f 386/386/386 431/431/431 422/422/422 +f 409/409/409 421/421/421 432/432/432 +f 409/409/409 432/432/432 428/428/428 +f 424/424/424 433/433/433 391/391/391 +f 373/373/373 423/423/423 425/425/425 +f 391/391/391 433/433/433 430/430/430 +f 422/422/422 434/434/434 423/423/423 +f 423/423/423 434/434/434 425/425/425 +f 425/425/425 435/435/435 426/426/426 +f 427/427/427 436/436/436 421/421/421 +f 432/432/432 437/437/437 428/428/428 +f 428/428/428 438/438/438 429/429/429 +f 429/429/429 438/438/438 439/439/439 +f 429/429/429 439/439/439 424/424/424 +f 424/424/424 439/439/439 433/433/433 +f 433/433/433 440/440/440 430/430/430 +f 421/421/421 436/436/436 432/432/432 +f 428/428/428 437/437/437 438/438/438 +f 430/430/430 440/440/440 441/441/441 +f 430/430/430 441/441/441 388/388/388 +f 388/388/388 441/441/441 442/442/442 +f 431/431/431 443/443/443 444/444/444 +f 431/431/431 444/444/444 422/422/422 +f 422/422/422 444/444/444 434/434/434 +f 445/445/445 436/436/436 427/427/427 +f 446/446/446 447/447/447 433/433/433 +f 433/433/433 447/447/447 448/448/448 +f 433/433/433 448/448/448 440/440/440 +f 434/434/434 449/449/449 425/425/425 +f 425/425/425 449/449/449 435/435/435 +f 436/436/436 445/445/445 450/450/450 +f 436/436/436 451/451/451 432/432/432 +f 439/439/439 452/452/452 433/433/433 +f 433/433/433 452/452/452 446/446/446 +f 446/446/446 452/452/452 453/453/453 +f 446/446/446 453/453/453 447/447/447 +f 447/447/447 453/453/453 448/448/448 +f 454/454/454 455/455/455 456/456/456 +f 456/456/456 455/455/455 457/457/457 +f 458/458/458 457/457/457 455/455/455 +f 459/459/459 455/455/455 460/460/460 +f 461/461/461 460/460/460 462/462/462 +f 358/358/358 463/463/463 462/462/462 +f 358/358/358 462/462/462 347/347/347 +f 359/359/359 347/347/347 360/360/360 +f 464/464/464 360/360/360 465/465/465 +f 465/465/465 360/360/360 361/361/361 +f 465/465/465 361/361/361 302/302/302 +f 465/465/465 302/302/302 466/466/466 +f 466/466/466 302/302/302 316/316/316 +f 458/458/458 455/455/455 459/459/459 +f 461/461/461 462/462/462 467/467/467 +f 467/467/467 462/462/462 463/463/463 +f 468/468/468 359/359/359 360/360/360 +f 468/468/468 360/360/360 464/464/464 +f 469/469/469 465/465/465 466/466/466 +f 459/459/459 460/460/460 461/461/461 +f 468/468/468 464/464/464 470/470/470 +f 470/470/470 464/464/464 465/465/465 +f 470/470/470 465/465/465 469/469/469 +f 471/471/471 466/466/466 316/316/316 +f 471/471/471 316/316/316 315/315/315 +f 467/467/467 463/463/463 358/358/358 +f 472/472/472 358/358/358 359/359/359 +f 472/472/472 359/359/359 473/473/473 +f 473/473/473 359/359/359 468/468/468 +f 474/474/474 470/470/470 469/469/469 +f 474/474/474 469/469/469 466/466/466 +f 474/474/474 466/466/466 471/471/471 +f 475/475/475 315/315/315 313/313/313 +f 476/476/476 459/459/459 461/461/461 +f 472/472/472 467/467/467 358/358/358 +f 477/477/477 468/468/468 470/470/470 +f 477/477/477 470/470/470 474/474/474 +f 478/478/478 474/474/474 471/471/471 +f 478/478/478 471/471/471 315/315/315 +f 263/263/263 475/475/475 313/313/313 +f 479/479/479 458/458/458 459/459/459 +f 468/468/468 472/472/472 473/473/473 +f 468/468/468 477/477/477 478/478/478 +f 478/478/478 477/477/477 474/474/474 +f 479/479/479 459/459/459 476/476/476 +f 480/480/480 461/461/461 467/467/467 +f 268/268/268 478/478/478 315/315/315 +f 268/268/268 315/315/315 475/475/475 +f 480/480/480 476/476/476 461/461/461 +f 480/480/480 467/467/467 481/481/481 +f 481/481/481 467/467/467 472/472/472 +f 482/482/482 472/472/472 468/468/468 +f 268/268/268 475/475/475 265/265/265 +f 265/265/265 475/475/475 263/263/263 +f 481/481/481 472/472/472 483/483/483 +f 482/482/482 483/483/483 472/472/472 +f 484/484/484 479/479/479 476/476/476 +f 485/485/485 476/476/476 480/480/480 +f 486/486/486 479/479/479 484/484/484 +f 484/484/484 476/476/476 485/485/485 +f 365/365/365 481/481/481 367/367/367 +f 367/367/367 481/481/481 483/483/483 +f 367/367/367 483/483/483 482/482/482 +f 482/482/482 468/468/468 478/478/478 +f 486/486/486 487/487/487 479/479/479 +f 488/488/488 480/480/480 481/481/481 +f 488/488/488 481/481/481 365/365/365 +f 370/370/370 482/482/482 478/478/478 +f 488/488/488 485/485/485 480/480/480 +f 368/368/368 367/367/367 482/482/482 +f 371/371/371 370/370/370 478/478/478 +f 371/371/371 478/478/478 268/268/268 +f 482/482/482 370/370/370 368/368/368 +f 485/485/485 374/374/374 484/484/484 +f 484/484/484 374/374/374 426/426/426 +f 484/484/484 426/426/426 486/486/486 +f 435/435/435 489/489/489 486/486/486 +f 435/435/435 486/486/486 426/426/426 +f 374/374/374 485/485/485 364/364/364 +f 364/364/364 485/485/485 488/488/488 +f 364/364/364 488/488/488 365/365/365 +f 366/366/366 365/365/365 367/367/367 +f 369/369/369 368/368/368 370/370/370 +f 450/450/450 490/490/490 491/491/491 +f 450/450/450 491/491/491 436/436/436 +f 436/436/436 491/491/491 451/451/451 +f 432/432/432 451/451/451 437/437/437 +f 437/437/437 492/492/492 438/438/438 +f 438/438/438 492/492/492 439/439/439 +f 448/448/448 453/453/453 440/440/440 +f 443/443/443 493/493/493 444/444/444 +f 444/444/444 494/494/494 434/434/434 +f 449/449/449 495/495/495 435/435/435 +f 435/435/435 495/495/495 489/489/489 +f 486/486/486 489/489/489 487/487/487 +f 479/479/479 487/487/487 458/458/458 +f 457/457/457 458/458/458 456/456/456 +f 445/445/445 496/496/496 450/450/450 +f 450/450/450 496/496/496 490/490/490 +f 437/437/437 451/451/451 492/492/492 +f 492/492/492 452/452/452 439/439/439 +f 453/453/453 452/452/452 497/497/497 +f 453/453/453 497/497/497 498/498/498 +f 453/453/453 498/498/498 440/440/440 +f 440/440/440 498/498/498 499/499/499 +f 440/440/440 499/499/499 441/441/441 +f 442/442/442 441/441/441 500/500/500 +f 442/442/442 500/500/500 501/501/501 +f 443/443/443 502/502/502 493/493/493 +f 493/493/493 502/502/502 444/444/444 +f 444/444/444 503/503/503 494/494/494 +f 494/494/494 503/503/503 434/434/434 +f 487/487/487 504/504/504 458/458/458 +f 458/458/458 504/504/504 505/505/505 +f 445/445/445 506/506/506 507/507/507 +f 445/445/445 507/507/507 508/508/508 +f 445/445/445 508/508/508 496/496/496 +f 496/496/496 508/508/508 509/509/509 +f 496/496/496 509/509/509 490/490/490 +f 490/490/490 509/509/509 510/510/510 +f 490/490/490 510/510/510 491/491/491 +f 491/491/491 510/510/510 451/451/451 +f 451/451/451 511/511/511 492/492/492 +f 499/499/499 498/498/498 441/441/441 +f 512/512/512 513/513/513 443/443/443 +f 443/443/443 513/513/513 502/502/502 +f 502/502/502 513/513/513 514/514/514 +f 502/502/502 514/514/514 515/515/515 +f 502/502/502 515/515/515 444/444/444 +f 444/444/444 515/515/515 503/503/503 +f 434/434/434 503/503/503 449/449/449 +f 495/495/495 516/516/516 489/489/489 +f 504/504/504 517/517/517 505/505/505 +f 505/505/505 517/517/517 518/518/518 +f 505/505/505 518/518/518 458/458/458 +f 458/458/458 518/518/518 519/519/519 +f 458/458/458 519/519/519 456/456/456 +f 506/506/506 520/520/520 521/521/521 +f 506/506/506 522/522/522 507/507/507 +f 507/507/507 522/522/522 508/508/508 +f 508/508/508 523/523/523 509/509/509 +f 509/509/509 523/523/523 510/510/510 +f 510/510/510 524/524/524 451/451/451 +f 452/452/452 492/492/492 525/525/525 +f 452/452/452 525/525/525 497/497/497 +f 497/497/497 525/525/525 498/498/498 +f 498/498/498 526/526/526 500/500/500 +f 498/498/498 500/500/500 441/441/441 +f 501/501/501 500/500/500 240/240/240 +f 242/242/242 527/527/527 512/512/512 +f 512/512/512 527/527/527 528/528/528 +f 512/512/512 528/528/528 513/513/513 +f 513/513/513 528/528/528 514/514/514 +f 514/514/514 529/529/529 515/515/515 +f 515/515/515 529/529/529 530/530/530 +f 515/515/515 530/530/530 503/503/503 +f 503/503/503 530/530/530 531/531/531 +f 503/503/503 531/531/531 449/449/449 +f 449/449/449 531/531/531 532/532/532 +f 449/449/449 532/532/532 495/495/495 +f 495/495/495 532/532/532 533/533/533 +f 495/495/495 533/533/533 534/534/534 +f 495/495/495 534/534/534 516/516/516 +f 489/489/489 516/516/516 535/535/535 +f 489/489/489 535/535/535 487/487/487 +f 487/487/487 535/535/535 504/504/504 +f 504/504/504 535/535/535 536/536/536 +f 504/504/504 536/536/536 517/517/517 +f 517/517/517 536/536/536 537/537/537 +f 517/517/517 537/537/537 518/518/518 +f 518/518/518 537/537/537 519/519/519 +f 519/519/519 538/538/538 456/456/456 +f 454/454/454 456/456/456 246/246/246 +f 454/454/454 246/246/246 248/248/248 +f 316/316/316 311/311/311 315/315/315 +f 313/313/313 286/286/286 263/263/263 +f 263/263/263 286/286/286 300/300/300 +f 263/263/263 300/300/300 249/249/249 +f 535/535/535 539/539/539 536/536/536 +f 536/536/536 539/539/539 540/540/540 +f 536/536/536 540/540/540 537/537/537 +f 537/537/537 540/540/540 541/541/541 +f 537/537/537 541/541/541 519/519/519 +f 519/519/519 541/541/541 538/538/538 +f 456/456/456 542/542/542 246/246/246 +f 521/521/521 522/522/522 506/506/506 +f 522/522/522 543/543/543 508/508/508 +f 508/508/508 543/543/543 523/523/523 +f 523/523/523 543/543/543 544/544/544 +f 523/523/523 544/544/544 510/510/510 +f 510/510/510 544/544/544 545/545/545 +f 510/510/510 545/545/545 524/524/524 +f 524/524/524 545/545/545 511/511/511 +f 524/524/524 511/511/511 451/451/451 +f 511/511/511 546/546/546 492/492/492 +f 492/492/492 546/546/546 525/525/525 +f 242/242/242 241/241/241 547/547/547 +f 242/242/242 547/547/547 527/527/527 +f 528/528/528 548/548/548 514/514/514 +f 514/514/514 548/548/548 529/529/529 +f 529/529/529 548/548/548 530/530/530 +f 541/541/541 549/549/549 538/538/538 +f 538/538/538 549/549/549 550/550/550 +f 538/538/538 550/550/550 456/456/456 +f 456/456/456 550/550/550 551/551/551 +f 456/456/456 551/551/551 542/542/542 +f 542/542/542 551/551/551 246/246/246 +f 520/520/520 552/552/552 553/553/553 +f 520/520/520 553/553/553 521/521/521 +f 521/521/521 553/553/553 522/522/522 +f 522/522/522 553/553/553 554/554/554 +f 522/522/522 554/554/554 543/543/543 +f 543/543/543 554/554/554 544/544/544 +f 525/525/525 555/555/555 498/498/498 +f 498/498/498 555/555/555 556/556/556 +f 498/498/498 556/556/556 557/557/557 +f 498/498/498 557/557/557 526/526/526 +f 526/526/526 557/557/557 500/500/500 +f 500/500/500 558/558/558 240/240/240 +f 240/240/240 558/558/558 559/559/559 +f 240/240/240 559/559/559 241/241/241 +f 527/527/527 547/547/547 560/560/560 +f 527/527/527 560/560/560 528/528/528 +f 528/528/528 560/560/560 561/561/561 +f 528/528/528 561/561/561 548/548/548 +f 548/548/548 561/561/561 562/562/562 +f 548/548/548 562/562/562 530/530/530 +f 531/531/531 530/530/530 532/532/532 +f 532/532/532 530/530/530 534/534/534 +f 532/532/532 534/534/534 533/533/533 +f 516/516/516 563/563/563 535/535/535 +f 535/535/535 563/563/563 539/539/539 +f 539/539/539 563/563/563 564/564/564 +f 539/539/539 564/564/564 540/540/540 +f 540/540/540 564/564/564 541/541/541 +f 541/541/541 564/564/564 565/565/565 +f 541/541/541 565/565/565 549/549/549 +f 550/550/550 549/549/549 566/566/566 +f 550/550/550 566/566/566 551/551/551 +f 551/551/551 566/566/566 567/567/567 +f 551/551/551 567/567/567 246/246/246 +f 246/246/246 567/567/567 568/568/568 +f 246/246/246 568/568/568 247/247/247 +f 247/247/247 568/568/568 552/552/552 +f 247/247/247 552/552/552 520/520/520 +f 553/553/553 552/552/552 569/569/569 +f 553/553/553 569/569/569 570/570/570 +f 553/553/553 570/570/570 554/554/554 +f 554/554/554 570/570/570 544/544/544 +f 544/544/544 570/570/570 571/571/571 +f 544/544/544 571/571/571 545/545/545 +f 545/545/545 571/571/571 572/572/572 +f 545/545/545 572/572/572 511/511/511 +f 525/525/525 546/546/546 573/573/573 +f 556/556/556 555/555/555 557/557/557 +f 557/557/557 555/555/555 574/574/574 +f 557/557/557 574/574/574 500/500/500 +f 500/500/500 574/574/574 558/558/558 +f 560/560/560 547/547/547 561/561/561 +f 561/561/561 575/575/575 562/562/562 +f 562/562/562 575/575/575 576/576/576 +f 562/562/562 576/576/576 530/530/530 +f 530/530/530 576/576/576 577/577/577 +f 530/530/530 577/577/577 534/534/534 +f 516/516/516 534/534/534 563/563/563 +f 563/563/563 578/578/578 564/564/564 +f 564/564/564 578/578/578 579/579/579 +f 564/564/564 579/579/579 565/565/565 +f 565/565/565 579/579/579 580/580/580 +f 565/565/565 580/580/580 549/549/549 +f 549/549/549 580/580/580 566/566/566 +f 567/567/567 566/566/566 568/568/568 +f 569/569/569 581/581/581 570/570/570 +f 570/570/570 581/581/581 582/582/582 +f 570/570/570 582/582/582 571/571/571 +f 571/571/571 582/582/582 583/583/583 +f 571/571/571 583/583/583 572/572/572 +f 572/572/572 583/583/583 511/511/511 +f 525/525/525 573/573/573 555/555/555 +f 555/555/555 584/584/584 574/574/574 +f 574/574/574 584/584/584 558/558/558 +f 558/558/558 585/585/585 559/559/559 +f 561/561/561 547/547/547 575/575/575 +f 575/575/575 586/586/586 576/576/576 +f 576/576/576 586/586/586 587/587/587 +f 576/576/576 587/587/587 577/577/577 +f 577/577/577 587/587/587 588/588/588 +f 577/577/577 588/588/588 534/534/534 +f 579/579/579 578/578/578 589/589/589 +f 579/579/579 589/589/589 580/580/580 +f 580/580/580 589/589/589 590/590/590 +f 580/580/580 590/590/590 566/566/566 +f 566/566/566 590/590/590 591/591/591 +f 566/566/566 591/591/591 568/568/568 +f 552/552/552 592/592/592 569/569/569 +f 569/569/569 592/592/592 581/581/581 +f 581/581/581 592/592/592 593/593/593 +f 581/581/581 593/593/593 582/582/582 +f 582/582/582 593/593/593 594/594/594 +f 582/582/582 594/594/594 583/583/583 +f 583/583/583 594/594/594 511/511/511 +f 511/511/511 594/594/594 595/595/595 +f 511/511/511 595/595/595 546/546/546 +f 584/584/584 555/555/555 596/596/596 +f 584/584/584 596/596/596 585/585/585 +f 584/584/584 585/585/585 558/558/558 +f 547/547/547 597/597/597 575/575/575 +f 575/575/575 597/597/597 598/598/598 +f 575/575/575 598/598/598 586/586/586 +f 586/586/586 598/598/598 587/587/587 +f 587/587/587 598/598/598 588/588/588 +f 534/534/534 588/588/588 599/599/599 +f 534/534/534 599/599/599 563/563/563 +f 578/578/578 600/600/600 589/589/589 +f 589/589/589 600/600/600 601/601/601 +f 589/589/589 601/601/601 590/590/590 +f 590/590/590 601/601/601 591/591/591 +f 552/552/552 602/602/602 592/592/592 +f 592/592/592 602/602/602 593/593/593 +f 593/593/593 602/602/602 603/603/603 +f 593/593/593 603/603/603 594/594/594 +f 546/546/546 595/595/595 573/573/573 +f 241/241/241 559/559/559 597/597/597 +f 241/241/241 597/597/597 547/547/547 +f 597/597/597 604/604/604 598/598/598 +f 598/598/598 604/604/604 588/588/588 +f 599/599/599 605/605/605 578/578/578 +f 599/599/599 578/578/578 563/563/563 +f 568/568/568 591/591/591 606/606/606 +f 568/568/568 606/606/606 552/552/552 +f 552/552/552 606/606/606 607/607/607 +f 552/552/552 607/607/607 602/602/602 +f 602/602/602 607/607/607 594/594/594 +f 602/602/602 594/594/594 603/603/603 +f 573/573/573 608/608/608 596/596/596 +f 573/573/573 596/596/596 555/555/555 +f 588/588/588 605/605/605 599/599/599 +f 607/607/607 606/606/606 609/609/609 +f 607/607/607 609/609/609 594/594/594 +f 594/594/594 609/609/609 595/595/595 +f 595/595/595 608/608/608 573/573/573 +f 559/559/559 585/585/585 610/610/610 +f 559/559/559 610/610/610 597/597/597 +f 588/588/588 604/604/604 605/605/605 +f 605/605/605 611/611/611 578/578/578 +f 578/578/578 611/611/611 600/600/600 +f 600/600/600 611/611/611 601/601/601 +f 591/591/591 601/601/601 606/606/606 +f 609/609/609 612/612/612 595/595/595 +f 596/596/596 613/613/613 585/585/585 +f 610/610/610 604/604/604 597/597/597 +f 595/595/595 612/612/612 608/608/608 +f 596/596/596 608/608/608 613/613/613 +f 585/585/585 613/613/613 610/610/610 +f 604/604/604 614/614/614 605/605/605 +f 605/605/605 614/614/614 611/611/611 +f 601/601/601 611/611/611 615/615/615 +f 601/601/601 615/615/615 606/606/606 +f 606/606/606 616/616/616 609/609/609 +f 609/609/609 616/616/616 612/612/612 +f 610/610/610 617/617/617 604/604/604 +f 604/604/604 617/617/617 614/614/614 +f 606/606/606 615/615/615 616/616/616 +f 612/612/612 616/616/616 237/237/237 +f 612/612/612 237/237/237 608/608/608 +f 608/608/608 237/237/237 613/613/613 +f 613/613/613 618/618/618 610/610/610 +f 614/614/614 239/239/239 611/611/611 +f 611/611/611 238/238/238 615/615/615 +f 610/610/610 618/618/618 617/617/617 +f 614/614/614 617/617/617 239/239/239 +f 611/611/611 239/239/239 238/238/238 +f 615/615/615 238/238/238 616/616/616 +f 616/616/616 238/238/238 237/237/237 +f 613/613/613 237/237/237 618/618/618 +f 617/617/617 618/618/618 239/239/239 +f 237/237/237 239/239/239 618/618/618 +f 512/512/512 619/619/619 242/242/242 +f 242/242/242 619/619/619 240/240/240 +f 443/443/443 620/620/620 512/512/512 +f 619/619/619 512/512/512 620/620/620 +f 362/362/362 621/621/621 346/346/346 +f 431/431/431 620/620/620 443/443/443 +f 388/388/388 622/622/622 623/623/623 +f 624/624/624 282/282/282 281/281/281 +f 624/624/624 281/281/281 625/625/625 +f 624/624/624 288/288/288 282/282/282 +f 626/626/626 317/317/317 288/288/288 +f 626/626/626 288/288/288 624/624/624 +f 386/386/386 627/627/627 431/431/431 +f 620/620/620 431/431/431 627/627/627 +f 625/625/625 290/290/290 628/628/628 +f 625/625/625 281/281/281 290/290/290 +f 629/629/629 240/240/240 619/619/619 +f 629/629/629 501/501/501 240/240/240 +f 501/501/501 629/629/629 442/442/442 +f 442/442/442 629/629/629 622/622/622 +f 622/622/622 388/388/388 442/442/442 +f 623/623/623 362/362/362 388/388/388 +f 621/621/621 362/362/362 623/623/623 +f 628/628/628 338/338/338 621/621/621 +f 628/628/628 290/290/290 319/319/319 +f 627/627/627 386/386/386 630/630/630 +f 621/621/621 338/338/338 346/346/346 +f 628/628/628 319/319/319 338/338/338 +f 244/244/244 626/626/626 245/245/245 +f 245/245/245 626/626/626 630/630/630 +f 630/630/630 386/386/386 245/245/245 +f 626/626/626 244/244/244 317/317/317 +f 247/247/247 520/520/520 631/631/631 +f 445/445/445 427/427/427 632/632/632 +f 633/633/633 520/520/520 506/506/506 +f 631/631/631 520/520/520 633/633/633 +f 634/634/634 454/454/454 631/631/631 +f 633/633/633 506/506/506 632/632/632 +f 632/632/632 506/506/506 445/445/445 +f 631/631/631 454/454/454 248/248/248 +f 420/420/420 635/635/635 632/632/632 +f 632/632/632 427/427/427 420/420/420 +f 631/631/631 248/248/248 247/247/247 +f 636/636/636 339/339/339 291/291/291 +f 634/634/634 455/455/455 454/454/454 +f 339/339/339 636/636/636 635/635/635 +f 455/455/455 634/634/634 637/637/637 +f 312/312/312 638/638/638 294/294/294 +f 339/339/339 635/635/635 351/351/351 +f 420/420/420 351/351/351 635/635/635 +f 460/460/460 455/455/455 637/637/637 +f 460/460/460 637/637/637 639/639/639 +f 460/460/460 639/639/639 462/462/462 +f 285/285/285 294/294/294 640/640/640 +f 640/640/640 294/294/294 638/638/638 +f 639/639/639 347/347/347 462/462/462 +f 638/638/638 347/347/347 639/639/639 +f 636/636/636 291/291/291 279/279/279 +f 638/638/638 312/312/312 347/347/347 +f 279/279/279 640/640/640 636/636/636 +f 640/640/640 279/279/279 285/285/285 +f 641/641/641 642/642/642 643/643/643 +f 643/643/643 642/642/642 644/644/644 +f 643/643/643 644/644/644 645/645/645 +f 645/645/645 644/644/644 646/646/646 +f 645/645/645 646/646/646 647/647/647 +f 647/647/647 646/646/646 648/648/648 +f 648/648/648 646/646/646 649/649/649 +f 648/648/648 649/649/649 650/650/650 +f 650/650/650 649/649/649 651/651/651 +f 650/650/650 651/651/651 652/652/652 +f 652/652/652 651/651/651 653/653/653 +f 652/652/652 653/653/653 654/654/654 +f 654/654/654 653/653/653 655/655/655 +f 654/654/654 655/655/655 656/656/656 +f 656/656/656 655/655/655 657/657/657 +f 656/656/656 657/657/657 658/658/658 +f 656/656/656 658/658/658 659/659/659 +f 659/659/659 658/658/658 660/660/660 +f 660/660/660 658/658/658 661/661/661 +f 660/660/660 661/661/661 662/662/662 +f 660/660/660 662/662/662 663/663/663 +f 663/663/663 662/662/662 664/664/664 +f 664/664/664 662/662/662 665/665/665 +f 664/664/664 665/665/665 666/666/666 +f 666/666/666 665/665/665 667/667/667 +f 666/666/666 667/667/667 641/641/641 +f 641/641/641 667/667/667 668/668/668 +f 641/641/641 668/668/668 642/642/642 +f 639/639/639 655/655/655 653/653/653 +f 639/639/639 653/653/653 638/638/638 +f 638/638/638 653/653/653 651/651/651 +f 638/638/638 651/651/651 640/640/640 +f 651/651/651 649/649/649 640/640/640 +f 640/640/640 649/649/649 646/646/646 +f 640/640/640 646/646/646 636/636/636 +f 636/636/636 646/646/646 644/644/644 +f 636/636/636 644/644/644 635/635/635 +f 635/635/635 644/644/644 642/642/642 +f 642/642/642 668/668/668 635/635/635 +f 635/635/635 668/668/668 632/632/632 +f 668/668/668 667/667/667 632/632/632 +f 667/667/667 665/665/665 632/632/632 +f 632/632/632 665/665/665 633/633/633 +f 633/633/633 665/665/665 662/662/662 +f 633/633/633 662/662/662 631/631/631 +f 631/631/631 662/662/662 661/661/661 +f 631/631/631 661/661/661 658/658/658 +f 631/631/631 658/658/658 634/634/634 +f 634/634/634 658/658/658 637/637/637 +f 637/637/637 658/658/658 657/657/657 +f 637/637/637 657/657/657 639/639/639 +f 639/639/639 657/657/657 655/655/655 +f 641/641/641 643/643/643 621/621/621 +f 621/621/621 643/643/643 628/628/628 +f 643/643/643 645/645/645 628/628/628 +f 628/628/628 645/645/645 647/647/647 +f 628/628/628 647/647/647 625/625/625 +f 625/625/625 647/647/647 648/648/648 +f 625/625/625 648/648/648 624/624/624 +f 648/648/648 650/650/650 624/624/624 +f 624/624/624 650/650/650 626/626/626 +f 650/650/650 652/652/652 626/626/626 +f 652/652/652 654/654/654 626/626/626 +f 626/626/626 654/654/654 630/630/630 +f 630/630/630 654/654/654 656/656/656 +f 630/630/630 656/656/656 627/627/627 +f 627/627/627 656/656/656 620/620/620 +f 620/620/620 656/656/656 659/659/659 +f 620/620/620 659/659/659 619/619/619 +f 659/659/659 660/660/660 619/619/619 +f 619/619/619 660/660/660 629/629/629 +f 629/629/629 660/660/660 663/663/663 +f 629/629/629 663/663/663 664/664/664 +f 629/629/629 664/664/664 622/622/622 +f 664/664/664 666/666/666 622/622/622 +f 622/622/622 666/666/666 641/641/641 +f 622/622/622 641/641/641 623/623/623 +f 623/623/623 641/641/641 621/621/621 +f 669/669/669 670/670/670 671/671/671 +f 672/672/672 673/673/673 674/674/674 +f 675/675/675 676/676/676 677/677/677 +f 678/678/678 679/679/679 680/680/680 +f 681/681/681 682/682/682 669/669/669 +f 681/681/681 669/669/669 671/671/671 +f 683/683/683 676/676/676 675/675/675 +f 680/680/680 679/679/679 684/684/684 +f 674/674/674 681/681/681 671/671/671 +f 685/685/685 686/686/686 687/687/687 +f 683/683/683 675/675/675 688/688/688 +f 688/688/688 675/675/675 689/689/689 +f 690/690/690 678/678/678 680/680/680 +f 673/673/673 691/691/691 681/681/681 +f 673/673/673 681/681/681 674/674/674 +f 683/683/683 692/692/692 676/676/676 +f 693/693/693 692/692/692 683/683/683 +f 688/688/688 689/689/689 694/694/694 +f 688/688/688 694/694/694 695/695/695 +f 696/696/696 691/691/691 673/673/673 +f 672/672/672 674/674/674 697/697/697 +f 692/692/692 698/698/698 676/676/676 +f 699/699/699 690/690/690 700/700/700 +f 696/696/696 701/701/701 691/691/691 +f 702/702/702 703/703/703 682/682/682 +f 691/691/691 702/702/702 681/681/681 +f 681/681/681 702/702/702 682/682/682 +f 704/704/704 685/685/685 705/705/705 +f 705/705/705 685/685/685 687/687/687 +f 706/706/706 707/707/707 693/693/693 +f 693/693/693 707/707/707 692/692/692 +f 672/672/672 697/697/697 708/708/708 +f 672/672/672 708/708/708 709/709/709 +f 710/710/710 711/711/711 712/712/712 +f 711/711/711 704/704/704 712/712/712 +f 712/712/712 704/704/704 705/705/705 +f 713/713/713 710/710/710 712/712/712 +f 706/706/706 714/714/714 707/707/707 +f 707/707/707 715/715/715 692/692/692 +f 692/692/692 715/715/715 698/698/698 +f 716/716/716 699/699/699 700/700/700 +f 700/700/700 690/690/690 717/717/717 +f 690/690/690 680/680/680 718/718/718 +f 718/718/718 680/680/680 684/684/684 +f 696/696/696 719/719/719 701/701/701 +f 701/701/701 702/702/702 691/691/691 +f 706/706/706 720/720/720 714/714/714 +f 717/717/717 690/690/690 718/718/718 +f 721/721/721 719/719/719 696/696/696 +f 722/722/722 710/710/710 713/713/713 +f 723/723/723 705/705/705 687/687/687 +f 724/724/724 720/720/720 706/706/706 +f 707/707/707 725/725/725 715/715/715 +f 726/726/726 727/727/727 695/695/695 +f 716/716/716 700/700/700 719/719/719 +f 719/719/719 700/700/700 717/717/717 +f 701/701/701 719/719/719 702/702/702 +f 709/709/709 708/708/708 728/728/728 +f 713/713/713 712/712/712 725/725/725 +f 725/725/725 712/712/712 705/705/705 +f 725/725/725 705/705/705 723/723/723 +f 721/721/721 716/716/716 719/719/719 +f 702/702/702 717/717/717 718/718/718 +f 702/702/702 718/718/718 703/703/703 +f 714/714/714 725/725/725 707/707/707 +f 725/725/725 723/723/723 715/715/715 +f 715/715/715 723/723/723 698/698/698 +f 729/729/729 730/730/730 727/727/727 +f 731/731/731 732/732/732 721/721/721 +f 721/721/721 732/732/732 716/716/716 +f 719/719/719 717/717/717 702/702/702 +f 733/733/733 728/728/728 734/734/734 +f 722/722/722 735/735/735 736/736/736 +f 711/711/711 737/737/737 738/738/738 +f 722/722/722 736/736/736 710/710/710 +f 711/711/711 710/710/710 737/737/737 +f 704/704/704 711/711/711 738/738/738 +f 704/704/704 738/738/738 739/739/739 +f 685/685/685 704/704/704 739/739/739 +f 685/685/685 739/739/739 686/686/686 +f 713/713/713 720/720/720 722/722/722 +f 725/725/725 714/714/714 713/713/713 +f 720/720/720 724/724/724 722/722/722 +f 722/722/722 724/724/724 740/740/740 +f 722/722/722 740/740/740 741/741/741 +f 714/714/714 720/720/720 713/713/713 +f 742/742/742 675/675/675 677/677/677 +f 729/729/729 727/727/727 726/726/726 +f 743/743/743 726/726/726 695/695/695 +f 743/743/743 695/695/695 694/694/694 +f 694/694/694 689/689/689 675/675/675 +f 694/694/694 675/675/675 742/742/742 +f 744/744/744 729/729/729 726/726/726 +f 745/745/745 743/743/743 694/694/694 +f 746/746/746 747/747/747 729/729/729 +f 748/748/748 694/694/694 742/742/742 +f 746/746/746 729/729/729 749/749/749 +f 749/749/749 729/729/729 744/744/744 +f 744/744/744 726/726/726 743/743/743 +f 745/745/745 694/694/694 748/748/748 +f 743/743/743 678/678/678 744/744/744 +f 744/744/744 699/699/699 749/749/749 +f 749/749/749 750/750/750 746/746/746 +f 732/732/732 751/751/751 746/746/746 +f 699/699/699 744/744/744 678/678/678 +f 678/678/678 743/743/743 745/745/745 +f 732/732/732 746/746/746 750/750/750 +f 750/750/750 749/749/749 699/699/699 +f 679/679/679 745/745/745 748/748/748 +f 716/716/716 732/732/732 750/750/750 +f 690/690/690 699/699/699 678/678/678 +f 678/678/678 745/745/745 679/679/679 +f 716/716/716 750/750/750 699/699/699 +f 734/734/734 728/728/728 752/752/752 +f 752/752/752 728/728/728 708/708/708 +f 753/753/753 754/754/754 734/734/734 +f 697/697/697 674/674/674 671/671/671 +f 736/736/736 753/753/753 734/734/734 +f 736/736/736 734/734/734 752/752/752 +f 752/752/752 708/708/708 737/737/737 +f 738/738/738 708/708/708 697/697/697 +f 738/738/738 697/697/697 739/739/739 +f 697/697/697 671/671/671 670/670/670 +f 737/737/737 708/708/708 738/738/738 +f 710/710/710 752/752/752 737/737/737 +f 735/735/735 753/753/753 736/736/736 +f 736/736/736 752/752/752 710/710/710 +f 686/686/686 739/739/739 697/697/697 +f 686/686/686 697/697/697 755/755/755 +f 755/755/755 697/697/697 670/670/670 +f 756/756/756 757/757/757 758/758/758 +f 759/759/759 756/756/756 758/758/758 +f 747/747/747 746/746/746 760/760/760 +f 761/761/761 762/762/762 763/763/763 +f 764/764/764 765/765/765 766/766/766 +f 765/765/765 767/767/767 768/768/768 +f 765/765/765 768/768/768 769/769/769 +f 770/770/770 771/771/771 772/772/772 +f 773/773/773 774/774/774 775/775/775 +f 741/741/741 740/740/740 776/776/776 +f 734/734/734 754/754/754 733/733/733 +f 751/751/751 732/732/732 731/731/731 +f 777/777/777 776/776/776 778/778/778 +f 730/730/730 747/747/747 779/779/779 +f 779/779/779 780/780/780 781/781/781 +f 781/781/781 780/780/780 782/782/782 +f 782/782/782 783/783/783 770/770/770 +f 751/751/751 731/731/731 784/784/784 +f 785/785/785 784/784/784 786/786/786 +f 754/754/754 753/753/753 733/733/733 +f 733/733/733 787/787/787 788/788/788 +f 789/789/789 790/790/790 763/763/763 +f 729/729/729 747/747/747 730/730/730 +f 779/779/779 747/747/747 780/780/780 +f 770/770/770 783/783/783 791/791/791 +f 770/770/770 791/791/791 771/771/771 +f 780/780/780 747/747/747 792/792/792 +f 782/782/782 780/780/780 793/793/793 +f 782/782/782 793/793/793 783/783/783 +f 783/783/783 793/793/793 791/791/791 +f 780/780/780 792/792/792 793/793/793 +f 771/771/771 791/791/791 794/794/794 +f 793/793/793 792/792/792 795/795/795 +f 793/793/793 796/796/796 791/791/791 +f 747/747/747 760/760/760 792/792/792 +f 793/793/793 795/795/795 796/796/796 +f 791/791/791 796/796/796 794/794/794 +f 792/792/792 760/760/760 797/797/797 +f 792/792/792 797/797/797 798/798/798 +f 792/792/792 798/798/798 795/795/795 +f 795/795/795 799/799/799 796/796/796 +f 796/796/796 799/799/799 800/800/800 +f 796/796/796 800/800/800 794/794/794 +f 746/746/746 751/751/751 760/760/760 +f 795/795/795 798/798/798 799/799/799 +f 760/760/760 751/751/751 797/797/797 +f 797/797/797 785/785/785 798/798/798 +f 794/794/794 800/800/800 801/801/801 +f 798/798/798 785/785/785 786/786/786 +f 798/798/798 786/786/786 799/799/799 +f 797/797/797 751/751/751 784/784/784 +f 797/797/797 784/784/784 785/785/785 +f 799/799/799 786/786/786 802/802/802 +f 799/799/799 802/802/802 800/800/800 +f 800/800/800 802/802/802 803/803/803 +f 800/800/800 803/803/803 801/801/801 +f 803/803/803 804/804/804 801/801/801 +f 794/794/794 805/805/805 771/771/771 +f 801/801/801 805/805/805 794/794/794 +f 805/805/805 806/806/806 771/771/771 +f 771/771/771 806/806/806 772/772/772 +f 803/803/803 807/807/807 804/804/804 +f 804/804/804 808/808/808 801/801/801 +f 801/801/801 808/808/808 805/805/805 +f 807/807/807 809/809/809 804/804/804 +f 804/804/804 809/809/809 808/808/808 +f 808/808/808 810/810/810 805/805/805 +f 805/805/805 810/810/810 811/811/811 +f 805/805/805 811/811/811 806/806/806 +f 808/808/808 812/812/812 810/810/810 +f 811/811/811 813/813/813 806/806/806 +f 814/814/814 815/815/815 816/816/816 +f 814/814/814 816/816/816 817/817/817 +f 818/818/818 817/817/817 819/819/819 +f 818/818/818 819/819/819 820/820/820 +f 820/820/820 819/819/819 821/821/821 +f 817/817/817 816/816/816 822/822/822 +f 817/817/817 822/822/822 819/819/819 +f 735/735/735 722/722/722 741/741/741 +f 735/735/735 741/741/741 823/823/823 +f 823/823/823 777/777/777 824/824/824 +f 824/824/824 777/777/777 815/815/815 +f 819/819/819 822/822/822 825/825/825 +f 819/819/819 825/825/825 821/821/821 +f 826/826/826 821/821/821 775/775/775 +f 815/815/815 777/777/777 778/778/778 +f 815/815/815 778/778/778 816/816/816 +f 821/821/821 825/825/825 773/773/773 +f 821/821/821 773/773/773 775/775/775 +f 823/823/823 741/741/741 776/776/776 +f 823/823/823 776/776/776 777/777/777 +f 816/816/816 778/778/778 827/827/827 +f 816/816/816 827/827/827 822/822/822 +f 822/822/822 827/827/827 828/828/828 +f 822/822/822 828/828/828 825/825/825 +f 825/825/825 828/828/828 773/773/773 +f 807/807/807 829/829/829 809/809/809 +f 808/808/808 809/809/809 812/812/812 +f 810/810/810 812/812/812 830/830/830 +f 810/810/810 830/830/830 811/811/811 +f 811/811/811 830/830/830 813/813/813 +f 775/775/775 831/831/831 826/826/826 +f 826/826/826 831/831/831 832/832/832 +f 829/829/829 833/833/833 809/809/809 +f 809/809/809 833/833/833 834/834/834 +f 809/809/809 834/834/834 812/812/812 +f 830/830/830 835/835/835 813/813/813 +f 774/774/774 836/836/836 831/831/831 +f 774/774/774 831/831/831 775/775/775 +f 831/831/831 837/837/837 832/832/832 +f 829/829/829 838/838/838 833/833/833 +f 834/834/834 839/839/839 812/812/812 +f 812/812/812 839/839/839 830/830/830 +f 830/830/830 839/839/839 840/840/840 +f 830/830/830 840/840/840 835/835/835 +f 833/833/833 841/841/841 834/834/834 +f 834/834/834 841/841/841 839/839/839 +f 836/836/836 842/842/842 831/831/831 +f 831/831/831 842/842/842 837/837/837 +f 838/838/838 841/841/841 833/833/833 +f 840/840/840 843/843/843 835/835/835 +f 835/835/835 843/843/843 844/844/844 +f 836/836/836 845/845/845 842/842/842 +f 838/838/838 846/846/846 841/841/841 +f 839/839/839 841/841/841 847/847/847 +f 839/839/839 847/847/847 840/840/840 +f 840/840/840 847/847/847 843/843/843 +f 842/842/842 848/848/848 837/837/837 +f 846/846/846 849/849/849 841/841/841 +f 841/841/841 849/849/849 847/847/847 +f 844/844/844 843/843/843 850/850/850 +f 766/766/766 851/851/851 852/852/852 +f 851/851/851 853/853/853 854/854/854 +f 851/851/851 854/854/854 852/852/852 +f 845/845/845 855/855/855 856/856/856 +f 845/845/845 856/856/856 842/842/842 +f 842/842/842 856/856/856 848/848/848 +f 846/846/846 857/857/857 849/849/849 +f 847/847/847 858/858/858 843/843/843 +f 843/843/843 858/858/858 850/850/850 +f 859/859/859 860/860/860 853/853/853 +f 762/762/762 761/761/761 861/861/861 +f 861/861/861 862/862/862 859/859/859 +f 853/853/853 860/860/860 854/854/854 +f 733/733/733 753/753/753 787/787/787 +f 788/788/788 787/787/787 789/789/789 +f 763/763/763 790/790/790 863/863/863 +f 763/763/763 863/863/863 761/761/761 +f 859/859/859 862/862/862 860/860/860 +f 789/789/789 787/787/787 814/814/814 +f 789/789/789 814/814/814 790/790/790 +f 863/863/863 818/818/818 761/761/761 +f 761/761/761 820/820/820 861/861/861 +f 861/861/861 820/820/820 862/862/862 +f 860/860/860 862/862/862 832/832/832 +f 790/790/790 814/814/814 863/863/863 +f 761/761/761 818/818/818 820/820/820 +f 862/862/862 820/820/820 832/832/832 +f 860/860/860 832/832/832 837/837/837 +f 860/860/860 837/837/837 854/854/854 +f 854/854/854 837/837/837 852/852/852 +f 787/787/787 824/824/824 814/814/814 +f 852/852/852 837/837/837 848/848/848 +f 852/852/852 848/848/848 864/864/864 +f 753/753/753 735/735/735 823/823/823 +f 753/753/753 823/823/823 787/787/787 +f 787/787/787 823/823/823 824/824/824 +f 814/814/814 824/824/824 815/815/815 +f 863/863/863 814/814/814 817/817/817 +f 863/863/863 817/817/817 818/818/818 +f 820/820/820 821/821/821 832/832/832 +f 832/832/832 821/821/821 826/826/826 +f 849/849/849 865/865/865 847/847/847 +f 847/847/847 865/865/865 858/858/858 +f 856/856/856 866/866/866 848/848/848 +f 848/848/848 866/866/866 864/864/864 +f 852/852/852 864/864/864 764/764/764 +f 852/852/852 764/764/764 766/766/766 +f 769/769/769 768/768/768 867/867/867 +f 769/769/769 867/867/867 857/857/857 +f 857/857/857 867/867/867 849/849/849 +f 849/849/849 867/867/867 865/865/865 +f 858/858/858 865/865/865 868/868/868 +f 858/858/858 868/868/868 850/850/850 +f 850/850/850 868/868/868 869/869/869 +f 850/850/850 869/869/869 870/870/870 +f 871/871/871 870/870/870 872/872/872 +f 871/871/871 872/872/872 855/855/855 +f 855/855/855 872/872/872 856/856/856 +f 856/856/856 872/872/872 866/866/866 +f 765/765/765 764/764/764 767/767/767 +f 764/764/764 864/864/864 873/873/873 +f 764/764/764 873/873/873 767/767/767 +f 870/870/870 869/869/869 874/874/874 +f 870/870/870 874/874/874 872/872/872 +f 864/864/864 875/875/875 873/873/873 +f 767/767/767 873/873/873 757/757/757 +f 767/767/767 757/757/757 768/768/768 +f 768/768/768 757/757/757 756/756/756 +f 768/768/768 756/756/756 867/867/867 +f 865/865/865 867/867/867 759/759/759 +f 865/865/865 759/759/759 868/868/868 +f 868/868/868 759/759/759 869/869/869 +f 872/872/872 875/875/875 866/866/866 +f 866/866/866 875/875/875 864/864/864 +f 875/875/875 757/757/757 873/873/873 +f 867/867/867 756/756/756 759/759/759 +f 869/869/869 759/759/759 874/874/874 +f 874/874/874 759/759/759 758/758/758 +f 874/874/874 758/758/758 872/872/872 +f 872/872/872 758/758/758 875/875/875 +f 875/875/875 758/758/758 757/757/757 +f 846/846/846 876/876/876 857/857/857 +f 876/876/876 846/846/846 877/877/877 +f 877/877/877 846/846/846 838/838/838 +f 878/878/878 765/765/765 769/769/769 +f 878/878/878 769/769/769 876/876/876 +f 769/769/769 857/857/857 876/876/876 +f 878/878/878 766/766/766 765/765/765 +f 879/879/879 763/763/763 762/762/762 +f 880/880/880 696/696/696 673/673/673 +f 881/881/881 721/721/721 696/696/696 +f 881/881/881 696/696/696 880/880/880 +f 882/882/882 803/803/803 883/883/883 +f 877/877/877 838/838/838 829/829/829 +f 829/829/829 882/882/882 877/877/877 +f 861/861/861 884/884/884 762/762/762 +f 879/879/879 762/762/762 884/884/884 +f 733/733/733 885/885/885 728/728/728 +f 731/731/731 881/881/881 886/886/886 +f 786/786/786 784/784/784 886/886/886 +f 851/851/851 766/766/766 887/887/887 +f 887/887/887 766/766/766 878/878/878 +f 887/887/887 853/853/853 851/851/851 +f 853/853/853 887/887/887 859/859/859 +f 859/859/859 887/887/887 884/884/884 +f 884/884/884 861/861/861 859/859/859 +f 888/888/888 789/789/789 763/763/763 +f 888/888/888 763/763/763 879/879/879 +f 889/889/889 709/709/709 885/885/885 +f 885/885/885 709/709/709 728/728/728 +f 880/880/880 672/672/672 889/889/889 +f 889/889/889 672/672/672 709/709/709 +f 673/673/673 672/672/672 880/880/880 +f 881/881/881 731/731/731 721/721/721 +f 886/886/886 784/784/784 731/731/731 +f 890/890/890 786/786/786 886/886/886 +f 802/802/802 890/890/890 883/883/883 +f 882/882/882 807/807/807 803/803/803 +f 807/807/807 882/882/882 829/829/829 +f 890/890/890 802/802/802 786/786/786 +f 883/883/883 803/803/803 802/802/802 +f 888/888/888 788/788/788 789/789/789 +f 733/733/733 888/888/888 885/885/885 +f 733/733/733 788/788/788 888/888/888 +f 855/855/855 891/891/891 871/871/871 +f 892/892/892 870/870/870 871/871/871 +f 892/892/892 850/850/850 870/870/870 +f 893/893/893 850/850/850 892/892/892 +f 894/894/894 776/776/776 895/895/895 +f 895/895/895 776/776/776 740/740/740 +f 892/892/892 871/871/871 891/891/891 +f 893/893/893 844/844/844 850/850/850 +f 895/895/895 724/724/724 896/896/896 +f 896/896/896 724/724/724 706/706/706 +f 778/778/778 776/776/776 894/894/894 +f 897/897/897 827/827/827 778/778/778 +f 898/898/898 828/828/828 899/899/899 +f 891/891/891 845/845/845 836/836/836 +f 895/895/895 740/740/740 724/724/724 +f 897/897/897 778/778/778 894/894/894 +f 828/828/828 827/827/827 899/899/899 +f 899/899/899 827/827/827 897/897/897 +f 898/898/898 773/773/773 828/828/828 +f 900/900/900 835/835/835 893/893/893 +f 893/893/893 835/835/835 844/844/844 +f 772/772/772 900/900/900 901/901/901 +f 688/688/688 902/902/902 896/896/896 +f 896/896/896 706/706/706 693/693/693 +f 782/782/782 770/770/770 903/903/903 +f 904/904/904 727/727/727 730/730/730 +f 902/902/902 727/727/727 904/904/904 +f 896/896/896 683/683/683 688/688/688 +f 898/898/898 774/774/774 773/773/773 +f 891/891/891 836/836/836 898/898/898 +f 891/891/891 855/855/855 845/845/845 +f 772/772/772 806/806/806 900/900/900 +f 901/901/901 770/770/770 772/772/772 +f 903/903/903 779/779/779 781/781/781 +f 904/904/904 779/779/779 903/903/903 +f 904/904/904 730/730/730 779/779/779 +f 902/902/902 695/695/695 727/727/727 +f 898/898/898 836/836/836 774/774/774 +f 900/900/900 813/813/813 835/835/835 +f 781/781/781 782/782/782 903/903/903 +f 896/896/896 693/693/693 683/683/683 +f 900/900/900 806/806/806 813/813/813 +f 903/903/903 770/770/770 901/901/901 +f 902/902/902 688/688/688 695/695/695 +f 899/899/899 879/879/879 884/884/884 +f 899/899/899 884/884/884 898/898/898 +f 898/898/898 884/884/884 887/887/887 +f 898/898/898 887/887/887 891/891/891 +f 891/891/891 887/887/887 878/878/878 +f 891/891/891 878/878/878 892/892/892 +f 892/892/892 878/878/878 876/876/876 +f 892/892/892 876/876/876 893/893/893 +f 893/893/893 876/876/876 877/877/877 +f 893/893/893 877/877/877 900/900/900 +f 900/900/900 877/877/877 882/882/882 +f 900/900/900 882/882/882 901/901/901 +f 901/901/901 882/882/882 883/883/883 +f 901/901/901 883/883/883 890/890/890 +f 901/901/901 890/890/890 903/903/903 +f 903/903/903 890/890/890 886/886/886 +f 903/903/903 886/886/886 904/904/904 +f 904/904/904 886/886/886 881/881/881 +f 904/904/904 881/881/881 902/902/902 +f 902/902/902 881/881/881 880/880/880 +f 902/902/902 880/880/880 896/896/896 +f 896/896/896 880/880/880 889/889/889 +f 896/896/896 889/889/889 895/895/895 +f 895/895/895 889/889/889 885/885/885 +f 895/895/895 885/885/885 894/894/894 +f 894/894/894 885/885/885 888/888/888 +f 894/894/894 888/888/888 897/897/897 +f 897/897/897 888/888/888 879/879/879 +f 897/897/897 879/879/879 899/899/899 +f 905/905/905 906/906/906 907/907/907 +f 908/908/908 909/909/909 910/910/910 +f 911/911/911 912/912/912 913/913/913 +f 912/912/912 914/914/914 915/915/915 +f 916/916/916 917/917/917 918/918/918 +f 919/919/919 920/920/920 921/921/921 +f 922/922/922 923/923/923 924/924/924 +f 925/925/925 926/926/926 927/927/927 +f 922/922/922 921/921/921 923/923/923 +f 928/928/928 929/929/929 930/930/930 +f 931/931/931 932/932/932 929/929/929 +f 931/931/931 929/929/929 928/928/928 +f 928/928/928 930/930/930 933/933/933 +f 932/932/932 919/919/919 926/926/926 +f 922/922/922 924/924/924 934/934/934 +f 935/935/935 925/925/925 936/936/936 +f 937/937/937 938/938/938 939/939/939 +f 940/940/940 933/933/933 941/941/941 +f 919/919/919 921/921/921 922/922/922 +f 937/937/937 939/939/939 942/942/942 +f 942/942/942 939/939/939 943/943/943 +f 942/942/942 943/943/943 944/944/944 +f 944/944/944 943/943/943 945/945/945 +f 946/946/946 940/940/940 947/947/947 +f 947/947/947 940/940/940 941/941/941 +f 941/941/941 933/933/933 930/930/930 +f 924/924/924 948/948/948 934/934/934 +f 934/934/934 948/948/948 949/949/949 +f 934/934/934 949/949/949 950/950/950 +f 950/950/950 949/949/949 951/951/951 +f 952/952/952 951/951/951 949/949/949 +f 953/953/953 928/928/928 933/933/933 +f 953/953/953 933/933/933 940/940/940 +f 941/941/941 954/954/954 947/947/947 +f 930/930/930 955/955/955 941/941/941 +f 929/929/929 956/956/956 930/930/930 +f 941/941/941 955/955/955 957/957/957 +f 941/941/941 957/957/957 954/954/954 +f 930/930/930 956/956/956 958/958/958 +f 930/930/930 958/958/958 955/955/955 +f 951/951/951 959/959/959 960/960/960 +f 950/950/950 960/960/960 961/961/961 +f 960/960/960 950/950/950 951/951/951 +f 952/952/952 949/949/949 948/948/948 +f 947/947/947 962/962/962 946/946/946 +f 955/955/955 958/958/958 963/963/963 +f 955/955/955 963/963/963 957/957/957 +f 957/957/957 964/964/964 954/954/954 +f 965/965/965 956/956/956 929/929/929 +f 950/950/950 961/961/961 934/934/934 +f 934/934/934 961/961/961 922/922/922 +f 966/966/966 942/942/942 944/944/944 +f 956/956/956 965/965/965 958/958/958 +f 958/958/958 967/967/967 963/963/963 +f 968/968/968 964/964/964 957/957/957 +f 968/968/968 957/957/957 963/963/963 +f 960/960/960 959/959/959 969/969/969 +f 960/960/960 969/969/969 961/961/961 +f 970/970/970 952/952/952 948/948/948 +f 970/970/970 948/948/948 971/971/971 +f 970/970/970 972/972/972 952/952/952 +f 973/973/973 948/948/948 924/924/924 +f 973/973/973 924/924/924 923/923/923 +f 974/974/974 937/937/937 942/942/942 +f 953/953/953 940/940/940 975/975/975 +f 940/940/940 946/946/946 975/975/975 +f 965/965/965 976/976/976 958/958/958 +f 932/932/932 926/926/926 929/929/929 +f 958/958/958 976/976/976 967/967/967 +f 959/959/959 977/977/977 969/969/969 +f 922/922/922 926/926/926 919/919/919 +f 966/966/966 974/974/974 942/942/942 +f 978/978/978 966/966/966 944/944/944 +f 978/978/978 944/944/944 979/979/979 +f 962/962/962 980/980/980 946/946/946 +f 946/946/946 980/980/980 975/975/975 +f 932/932/932 931/931/931 920/920/920 +f 932/932/932 920/920/920 919/919/919 +f 959/959/959 981/981/981 982/982/982 +f 959/959/959 982/982/982 977/977/977 +f 922/922/922 927/927/927 926/926/926 +f 971/971/971 948/948/948 973/973/973 +f 923/923/923 920/920/920 938/938/938 +f 923/923/923 938/938/938 937/937/937 +f 962/962/962 983/983/983 980/980/980 +f 978/978/978 979/979/979 984/984/984 +f 969/969/969 977/977/977 985/985/985 +f 961/961/961 927/927/927 922/922/922 +f 986/986/986 987/987/987 972/972/972 +f 986/986/986 972/972/972 970/970/970 +f 988/988/988 970/970/970 971/971/971 +f 953/953/953 989/989/989 928/928/928 +f 990/990/990 991/991/991 968/968/968 +f 992/992/992 984/984/984 993/993/993 +f 961/961/961 969/969/969 994/994/994 +f 961/961/961 994/994/994 927/927/927 +f 988/988/988 986/986/986 970/970/970 +f 973/973/973 923/923/923 937/937/937 +f 973/973/973 937/937/937 974/974/974 +f 988/988/988 966/966/966 978/978/978 +f 986/986/986 978/978/978 984/984/984 +f 986/986/986 984/984/984 992/992/992 +f 992/992/992 993/993/993 995/995/995 +f 980/980/980 983/983/983 996/996/996 +f 997/997/997 968/968/968 963/963/963 +f 988/988/988 978/978/978 986/986/986 +f 971/971/971 974/974/974 966/966/966 +f 998/998/998 992/992/992 995/995/995 +f 981/981/981 999/999/999 1000/1000/1000 +f 981/981/981 1000/1000/1000 982/982/982 +f 977/977/977 982/982/982 985/985/985 +f 969/969/969 985/985/985 994/994/994 +f 992/992/992 998/998/998 987/987/987 +f 992/992/992 987/987/987 986/986/986 +f 966/966/966 988/988/988 971/971/971 +f 974/974/974 971/971/971 973/973/973 +f 920/920/920 923/923/923 921/921/921 +f 1001/1001/1001 998/998/998 995/995/995 +f 989/989/989 939/939/939 938/938/938 +f 938/938/938 920/920/920 931/931/931 +f 983/983/983 1002/1002/1002 1003/1003/1003 +f 975/975/975 980/980/980 1004/1004/1004 +f 953/953/953 975/975/975 989/989/989 +f 990/990/990 1005/1005/1005 991/991/991 +f 1006/1006/1006 944/944/944 945/945/945 +f 1007/1007/1007 1008/1008/1008 1009/1009/1009 +f 1010/1010/1010 1009/1009/1009 1011/1011/1011 +f 1012/1012/1012 1013/1013/1013 1014/1014/1014 +f 1012/1012/1012 1010/1010/1010 1011/1011/1011 +f 1007/1007/1007 1009/1009/1009 1010/1010/1010 +f 936/936/936 1015/1015/1015 935/935/935 +f 1016/1016/1016 1007/1007/1007 1010/1010/1010 +f 1016/1016/1016 1010/1010/1010 1017/1017/1017 +f 1017/1017/1017 1010/1010/1010 1012/1012/1012 +f 1018/1018/1018 1012/1012/1012 1014/1014/1014 +f 1018/1018/1018 1014/1014/1014 1015/1015/1015 +f 1018/1018/1018 1015/1015/1015 1019/1019/1019 +f 1019/1019/1019 1015/1015/1015 936/936/936 +f 1020/1020/1020 1021/1021/1021 1007/1007/1007 +f 1022/1022/1022 1017/1017/1017 1012/1012/1012 +f 1022/1022/1022 1012/1012/1012 1018/1018/1018 +f 1020/1020/1020 1007/1007/1007 1016/1016/1016 +f 1023/1023/1023 1022/1022/1022 1018/1018/1018 +f 1019/1019/1019 936/936/936 1024/1024/1024 +f 1025/1025/1025 1016/1016/1016 1017/1017/1017 +f 1025/1025/1025 1017/1017/1017 1022/1022/1022 +f 1024/1024/1024 925/925/925 927/927/927 +f 1026/1026/1026 1025/1025/1025 1022/1022/1022 +f 1026/1026/1026 1022/1022/1022 1023/1023/1023 +f 1023/1023/1023 1018/1018/1018 1019/1019/1019 +f 1027/1027/1027 1020/1020/1020 1016/1016/1016 +f 1027/1027/1027 1016/1016/1016 1025/1025/1025 +f 985/985/985 1019/1019/1019 1024/1024/1024 +f 1028/1028/1028 1020/1020/1020 1027/1027/1027 +f 982/982/982 1026/1026/1026 1023/1023/1023 +f 985/985/985 1023/1023/1023 1019/1019/1019 +f 994/994/994 1024/1024/1024 927/927/927 +f 999/999/999 1025/1025/1025 1026/1026/1026 +f 999/999/999 1026/1026/1026 1000/1000/1000 +f 982/982/982 1023/1023/1023 985/985/985 +f 994/994/994 985/985/985 1024/1024/1024 +f 1026/1026/1026 982/982/982 1000/1000/1000 +f 1025/1025/1025 999/999/999 1029/1029/1029 +f 1025/1025/1025 1029/1029/1029 1027/1027/1027 +f 1027/1027/1027 1029/1029/1029 1028/1028/1028 +f 1030/1030/1030 1028/1028/1028 1029/1029/1029 +f 936/936/936 925/925/925 1024/1024/1024 +f 1031/1031/1031 1032/1032/1032 1001/1001/1001 +f 1033/1033/1033 1031/1031/1031 1001/1001/1001 +f 1033/1033/1033 1001/1001/1001 995/995/995 +f 1034/1034/1034 1031/1031/1031 1033/1033/1033 +f 1035/1035/1035 1033/1033/1033 995/995/995 +f 1035/1035/1035 995/995/995 993/993/993 +f 1036/1036/1036 1034/1034/1034 1033/1033/1033 +f 1036/1036/1036 1033/1033/1033 1035/1035/1035 +f 1037/1037/1037 1035/1035/1035 993/993/993 +f 1037/1037/1037 993/993/993 984/984/984 +f 1038/1038/1038 1037/1037/1037 984/984/984 +f 1039/1039/1039 1034/1034/1034 1036/1036/1036 +f 1040/1040/1040 1036/1036/1036 1035/1035/1035 +f 1040/1040/1040 1035/1035/1035 1037/1037/1037 +f 1041/1041/1041 1040/1040/1040 1037/1037/1037 +f 1042/1042/1042 1036/1036/1036 1040/1040/1040 +f 1041/1041/1041 1037/1037/1037 1038/1038/1038 +f 1043/1043/1043 1038/1038/1038 979/979/979 +f 1043/1043/1043 979/979/979 1006/1006/1006 +f 1042/1042/1042 1039/1039/1039 1036/1036/1036 +f 1041/1041/1041 1038/1038/1038 1043/1043/1043 +f 1044/1044/1044 1039/1039/1039 1042/1042/1042 +f 1045/1045/1045 1040/1040/1040 1041/1041/1041 +f 1042/1042/1042 1040/1040/1040 1045/1045/1045 +f 1045/1045/1045 1041/1041/1041 1046/1046/1046 +f 1046/1046/1046 1041/1041/1041 1043/1043/1043 +f 1046/1046/1046 1043/1043/1043 1047/1047/1047 +f 1047/1047/1047 1043/1043/1043 1006/1006/1006 +f 1047/1047/1047 1006/1006/1006 945/945/945 +f 1048/1048/1048 1049/1049/1049 1044/1044/1044 +f 1048/1048/1048 1044/1044/1044 1042/1042/1042 +f 1050/1050/1050 1042/1042/1042 1045/1045/1045 +f 1051/1051/1051 945/945/945 943/943/943 +f 1050/1050/1050 1048/1048/1048 1042/1042/1042 +f 1050/1050/1050 1045/1045/1045 1052/1052/1052 +f 1052/1052/1052 1045/1045/1045 1046/1046/1046 +f 1053/1053/1053 1046/1046/1046 1047/1047/1047 +f 1054/1054/1054 1047/1047/1047 945/945/945 +f 1052/1052/1052 1046/1046/1046 1053/1053/1053 +f 1054/1054/1054 945/945/945 1051/1051/1051 +f 939/939/939 1051/1051/1051 943/943/943 +f 1055/1055/1055 1050/1050/1050 1052/1052/1052 +f 1054/1054/1054 1053/1053/1053 1047/1047/1047 +f 1056/1056/1056 1048/1048/1048 1050/1050/1050 +f 1057/1057/1057 1051/1051/1051 939/939/939 +f 1058/1058/1058 1048/1048/1048 1056/1056/1056 +f 1056/1056/1056 1050/1050/1050 1055/1055/1055 +f 1059/1059/1059 1052/1052/1052 1053/1053/1053 +f 1057/1057/1057 939/939/939 989/989/989 +f 1059/1059/1059 1055/1055/1055 1052/1052/1052 +f 1059/1059/1059 1053/1053/1053 1060/1060/1060 +f 1060/1060/1060 1053/1053/1053 1054/1054/1054 +f 1060/1060/1060 1054/1054/1054 1004/1004/1004 +f 1004/1004/1004 1054/1054/1054 1051/1051/1051 +f 1061/1061/1061 1056/1056/1056 1055/1055/1055 +f 1057/1057/1057 1004/1004/1004 1051/1051/1051 +f 916/916/916 1058/1058/1058 1056/1056/1056 +f 1062/1062/1062 1055/1055/1055 1059/1059/1059 +f 1062/1062/1062 1061/1061/1061 1055/1055/1055 +f 1062/1062/1062 1059/1059/1059 1003/1003/1003 +f 1003/1003/1003 1059/1059/1059 1060/1060/1060 +f 1061/1061/1061 916/916/916 1056/1056/1056 +f 996/996/996 1060/1060/1060 1004/1004/1004 +f 928/928/928 989/989/989 938/938/938 +f 996/996/996 1003/1003/1003 1060/1060/1060 +f 975/975/975 1004/1004/1004 1057/1057/1057 +f 975/975/975 1057/1057/1057 989/989/989 +f 928/928/928 938/938/938 931/931/931 +f 1061/1061/1061 1062/1062/1062 917/917/917 +f 1061/1061/1061 917/917/917 916/916/916 +f 1002/1002/1002 917/917/917 1062/1062/1062 +f 1002/1002/1002 1062/1062/1062 1003/1003/1003 +f 983/983/983 1003/1003/1003 996/996/996 +f 980/980/980 996/996/996 1004/1004/1004 +f 1038/1038/1038 984/984/984 979/979/979 +f 979/979/979 944/944/944 1006/1006/1006 +f 1028/1028/1028 1063/1063/1063 1020/1020/1020 +f 1034/1034/1034 1064/1064/1064 1031/1031/1031 +f 1020/1020/1020 1063/1063/1063 1021/1021/1021 +f 1007/1007/1007 1065/1065/1065 1008/1008/1008 +f 1058/1058/1058 1066/1066/1066 1048/1048/1048 +f 1044/1044/1044 1049/1049/1049 1039/1039/1039 +f 1039/1039/1039 1067/1067/1067 1034/1034/1034 +f 1064/1064/1064 1068/1068/1068 1031/1031/1031 +f 1030/1030/1030 1069/1069/1069 1070/1070/1070 +f 1030/1030/1030 1070/1070/1070 1028/1028/1028 +f 1007/1007/1007 1021/1021/1021 1065/1065/1065 +f 1034/1034/1034 1067/1067/1067 1064/1064/1064 +f 1031/1031/1031 1068/1068/1068 1032/1032/1032 +f 1032/1032/1032 1068/1068/1068 1071/1071/1071 +f 1028/1028/1028 1070/1070/1070 1063/1063/1063 +f 918/918/918 1072/1072/1072 916/916/916 +f 916/916/916 1072/1072/1072 1058/1058/1058 +f 1058/1058/1058 1072/1072/1072 1066/1066/1066 +f 1048/1048/1048 1066/1066/1066 1049/1049/1049 +f 1049/1049/1049 1073/1073/1073 1039/1039/1039 +f 1039/1039/1039 1073/1073/1073 1067/1067/1067 +f 1021/1021/1021 1063/1063/1063 1074/1074/1074 +f 1066/1066/1066 1073/1073/1073 1049/1049/1049 +f 1069/1069/1069 1075/1075/1075 1070/1070/1070 +f 1021/1021/1021 1074/1074/1074 1065/1065/1065 +f 1076/1076/1076 1077/1077/1077 918/918/918 +f 918/918/918 1077/1077/1077 1072/1072/1072 +f 1066/1066/1066 1078/1078/1078 1073/1073/1073 +f 1073/1073/1073 1079/1079/1079 1067/1067/1067 +f 1064/1064/1064 1080/1080/1080 1068/1068/1068 +f 1068/1068/1068 1080/1080/1080 1071/1071/1071 +f 908/908/908 1075/1075/1075 1069/1069/1069 +f 1075/1075/1075 1081/1081/1081 1070/1070/1070 +f 1070/1070/1070 1081/1081/1081 1063/1063/1063 +f 1063/1063/1063 1081/1081/1081 1074/1074/1074 +f 1076/1076/1076 1082/1082/1082 1077/1077/1077 +f 1077/1077/1077 1083/1083/1083 1072/1072/1072 +f 1072/1072/1072 1083/1083/1083 1066/1066/1066 +f 1066/1066/1066 1083/1083/1083 1078/1078/1078 +f 1073/1073/1073 1084/1084/1084 1079/1079/1079 +f 1067/1067/1067 1079/1079/1079 1085/1085/1085 +f 1067/1067/1067 1085/1085/1085 1064/1064/1064 +f 1064/1064/1064 1085/1085/1085 1080/1080/1080 +f 1074/1074/1074 1086/1086/1086 1065/1065/1065 +f 1080/1080/1080 1087/1087/1087 1071/1071/1071 +f 1071/1071/1071 1087/1087/1087 1088/1088/1088 +f 1089/1089/1089 1090/1090/1090 1091/1091/1091 +f 1090/1090/1090 1092/1092/1092 1093/1093/1093 +f 1090/1090/1090 1093/1093/1093 1091/1091/1091 +f 1094/1094/1094 1095/1095/1095 1005/1005/1005 +f 1094/1094/1094 1005/1005/1005 990/990/990 +f 990/990/990 968/968/968 997/997/997 +f 1096/1096/1096 1091/1091/1091 1093/1093/1093 +f 1097/1097/1097 1092/1092/1092 1098/1098/1098 +f 1098/1098/1098 1092/1092/1092 1095/1095/1095 +f 1098/1098/1098 1095/1095/1095 1094/1094/1094 +f 1099/1099/1099 990/990/990 997/997/997 +f 1097/1097/1097 1093/1093/1093 1092/1092/1092 +f 1100/1100/1100 990/990/990 1099/1099/1099 +f 1101/1101/1101 997/997/997 967/967/967 +f 1102/1102/1102 1098/1098/1098 1094/1094/1094 +f 1100/1100/1100 1094/1094/1094 990/990/990 +f 1101/1101/1101 1099/1099/1099 997/997/997 +f 1103/1103/1103 1096/1096/1096 1093/1093/1093 +f 1103/1103/1103 1093/1093/1093 1097/1097/1097 +f 1104/1104/1104 1097/1097/1097 1098/1098/1098 +f 1102/1102/1102 1094/1094/1094 1100/1100/1100 +f 1105/1105/1105 1100/1100/1100 1099/1099/1099 +f 1101/1101/1101 967/967/967 976/976/976 +f 1104/1104/1104 1103/1103/1103 1097/1097/1097 +f 1106/1106/1106 1104/1104/1104 1098/1098/1098 +f 1106/1106/1106 1098/1098/1098 1102/1102/1102 +f 1107/1107/1107 1102/1102/1102 1100/1100/1100 +f 1107/1107/1107 1100/1100/1100 1105/1105/1105 +f 1105/1105/1105 1099/1099/1099 1108/1108/1108 +f 1108/1108/1108 1099/1099/1099 1101/1101/1101 +f 1109/1109/1109 1102/1102/1102 1107/1107/1107 +f 1110/1110/1110 1107/1107/1107 1105/1105/1105 +f 935/935/935 1101/1101/1101 976/976/976 +f 1111/1111/1111 1103/1103/1103 1086/1086/1086 +f 1086/1086/1086 1103/1103/1103 1008/1008/1008 +f 1008/1008/1008 1103/1103/1103 1104/1104/1104 +f 1008/1008/1008 1104/1104/1104 1106/1106/1106 +f 1109/1109/1109 1106/1106/1106 1102/1102/1102 +f 1011/1011/1011 1109/1109/1109 1107/1107/1107 +f 1110/1110/1110 1105/1105/1105 1108/1108/1108 +f 935/935/935 1108/1108/1108 1101/1101/1101 +f 1009/1009/1009 1106/1106/1106 1109/1109/1109 +f 1013/1013/1013 1107/1107/1107 1110/1110/1110 +f 926/926/926 965/965/965 929/929/929 +f 1008/1008/1008 1106/1106/1106 1009/1009/1009 +f 1011/1011/1011 1107/1107/1107 1013/1013/1013 +f 1110/1110/1110 1108/1108/1108 1015/1015/1015 +f 1015/1015/1015 1108/1108/1108 935/935/935 +f 1065/1065/1065 1086/1086/1086 1008/1008/1008 +f 1009/1009/1009 1109/1109/1109 1011/1011/1011 +f 935/935/935 976/976/976 925/925/925 +f 925/925/925 976/976/976 965/965/965 +f 965/965/965 926/926/926 925/925/925 +f 1110/1110/1110 1015/1015/1015 1014/1014/1014 +f 1110/1110/1110 1014/1014/1014 1013/1013/1013 +f 1012/1012/1012 1011/1011/1011 1013/1013/1013 +f 1082/1082/1082 915/915/915 1112/1112/1112 +f 1082/1082/1082 1112/1112/1112 1077/1077/1077 +f 1078/1078/1078 1113/1113/1113 1073/1073/1073 +f 1073/1073/1073 1113/1113/1113 1084/1084/1084 +f 1083/1083/1083 1113/1113/1113 1078/1078/1078 +f 1085/1085/1085 1114/1114/1114 1080/1080/1080 +f 1080/1080/1080 1114/1114/1114 1087/1087/1087 +f 908/908/908 910/910/910 1075/1075/1075 +f 1075/1075/1075 1115/1115/1115 1081/1081/1081 +f 1081/1081/1081 1116/1116/1116 1074/1074/1074 +f 1074/1074/1074 1116/1116/1116 1117/1117/1117 +f 1074/1074/1074 1117/1117/1117 1086/1086/1086 +f 1086/1086/1086 1117/1117/1117 1111/1111/1111 +f 1103/1103/1103 1111/1111/1111 1096/1096/1096 +f 1091/1091/1091 1118/1118/1118 1089/1089/1089 +f 1089/1089/1089 1118/1118/1118 913/913/913 +f 1077/1077/1077 1119/1119/1119 1083/1083/1083 +f 1083/1083/1083 1119/1119/1119 1113/1113/1113 +f 1084/1084/1084 1113/1113/1113 1120/1120/1120 +f 1084/1084/1084 1120/1120/1120 1079/1079/1079 +f 1079/1079/1079 1121/1121/1121 1085/1085/1085 +f 1085/1085/1085 1121/1121/1121 1114/1114/1114 +f 1087/1087/1087 1122/1122/1122 1088/1088/1088 +f 1075/1075/1075 910/910/910 1115/1115/1115 +f 1081/1081/1081 1115/1115/1115 1116/1116/1116 +f 1096/1096/1096 1123/1123/1123 1091/1091/1091 +f 915/915/915 914/914/914 1112/1112/1112 +f 1077/1077/1077 1112/1112/1112 1119/1119/1119 +f 1079/1079/1079 1120/1120/1120 1121/1121/1121 +f 1087/1087/1087 1114/1114/1114 1122/1122/1122 +f 1122/1122/1122 1124/1124/1124 1088/1088/1088 +f 1091/1091/1091 1123/1123/1123 1125/1125/1125 +f 1091/1091/1091 1125/1125/1125 1118/1118/1118 +f 991/991/991 964/964/964 968/968/968 +f 997/997/997 963/963/963 967/967/967 +f 1111/1111/1111 1126/1126/1126 1096/1096/1096 +f 1096/1096/1096 1126/1126/1126 1123/1123/1123 +f 1118/1118/1118 1127/1127/1127 913/913/913 +f 913/913/913 1127/1127/1127 911/911/911 +f 912/912/912 911/911/911 914/914/914 +f 1119/1119/1119 1128/1128/1128 1113/1113/1113 +f 1113/1113/1113 1128/1128/1128 1120/1120/1120 +f 1122/1122/1122 1129/1129/1129 1124/1124/1124 +f 1117/1117/1117 1130/1130/1130 1126/1126/1126 +f 1117/1117/1117 1126/1126/1126 1111/1111/1111 +f 1125/1125/1125 1127/1127/1127 1118/1118/1118 +f 1112/1112/1112 1131/1131/1131 1119/1119/1119 +f 1120/1120/1120 1132/1132/1132 1121/1121/1121 +f 1121/1121/1121 1132/1132/1132 1114/1114/1114 +f 1122/1122/1122 1114/1114/1114 1129/1129/1129 +f 1124/1124/1124 1133/1133/1133 1134/1134/1134 +f 1134/1134/1134 1135/1135/1135 909/909/909 +f 909/909/909 1135/1135/1135 1136/1136/1136 +f 909/909/909 1136/1136/1136 910/910/910 +f 910/910/910 1136/1136/1136 1137/1137/1137 +f 910/910/910 1137/1137/1137 1115/1115/1115 +f 1115/1115/1115 1137/1137/1137 1138/1138/1138 +f 1115/1115/1115 1138/1138/1138 1116/1116/1116 +f 1116/1116/1116 1138/1138/1138 1117/1117/1117 +f 1117/1117/1117 1138/1138/1138 1130/1130/1130 +f 911/911/911 1139/1139/1139 914/914/914 +f 914/914/914 1139/1139/1139 1131/1131/1131 +f 914/914/914 1131/1131/1131 1112/1112/1112 +f 1119/1119/1119 1131/1131/1131 1140/1140/1140 +f 1119/1119/1119 1140/1140/1140 1128/1128/1128 +f 1128/1128/1128 1141/1141/1141 1120/1120/1120 +f 1124/1124/1124 1129/1129/1129 1133/1133/1133 +f 1134/1134/1134 1133/1133/1133 1135/1135/1135 +f 1126/1126/1126 1142/1142/1142 1123/1123/1123 +f 1123/1123/1123 1142/1142/1142 1125/1125/1125 +f 1125/1125/1125 1142/1142/1142 1127/1127/1127 +f 1128/1128/1128 1140/1140/1140 1141/1141/1141 +f 1120/1120/1120 1141/1141/1141 1132/1132/1132 +f 1114/1114/1114 1132/1132/1132 1143/1143/1143 +f 1114/1114/1114 1143/1143/1143 1129/1129/1129 +f 1127/1127/1127 1144/1144/1144 911/911/911 +f 911/911/911 1144/1144/1144 1139/1139/1139 +f 1139/1139/1139 1145/1145/1145 1131/1131/1131 +f 1129/1129/1129 1143/1143/1143 1146/1146/1146 +f 1129/1129/1129 1146/1146/1146 1133/1133/1133 +f 1136/1136/1136 1147/1147/1147 1137/1137/1137 +f 1137/1137/1137 1148/1148/1148 1138/1138/1138 +f 1138/1138/1138 1148/1148/1148 1130/1130/1130 +f 1130/1130/1130 1149/1149/1149 1126/1126/1126 +f 1126/1126/1126 1149/1149/1149 1142/1142/1142 +f 1131/1131/1131 1145/1145/1145 1140/1140/1140 +f 1140/1140/1140 1150/1150/1150 1141/1141/1141 +f 1141/1141/1141 1150/1150/1150 1132/1132/1132 +f 1132/1132/1132 1150/1150/1150 1151/1151/1151 +f 1137/1137/1137 1147/1147/1147 1148/1148/1148 +f 1142/1142/1142 1152/1152/1152 1127/1127/1127 +f 1127/1127/1127 1152/1152/1152 1144/1144/1144 +f 1144/1144/1144 1153/1153/1153 1139/1139/1139 +f 1139/1139/1139 1153/1153/1153 1145/1145/1145 +f 1140/1140/1140 1154/1154/1154 1150/1150/1150 +f 1132/1132/1132 1151/1151/1151 1143/1143/1143 +f 1133/1133/1133 1146/1146/1146 1155/1155/1155 +f 1133/1133/1133 1155/1155/1155 1135/1135/1135 +f 1135/1135/1135 1156/1156/1156 1136/1136/1136 +f 1136/1136/1136 1156/1156/1156 1147/1147/1147 +f 1148/1148/1148 1147/1147/1147 1157/1157/1157 +f 1148/1148/1148 1149/1149/1149 1130/1130/1130 +f 1142/1142/1142 1149/1149/1149 1152/1152/1152 +f 1144/1144/1144 1152/1152/1152 1158/1158/1158 +f 1144/1144/1144 1158/1158/1158 1153/1153/1153 +f 1145/1145/1145 1154/1154/1154 1140/1140/1140 +f 1135/1135/1135 1155/1155/1155 1156/1156/1156 +f 1148/1148/1148 1157/1157/1157 1159/1159/1159 +f 1148/1148/1148 1159/1159/1159 1149/1149/1149 +f 1153/1153/1153 1158/1158/1158 1160/1160/1160 +f 1153/1153/1153 1160/1160/1160 1145/1145/1145 +f 1145/1145/1145 1160/1160/1160 1154/1154/1154 +f 1151/1151/1151 1161/1161/1161 1143/1143/1143 +f 1143/1143/1143 1161/1161/1161 1162/1162/1162 +f 1143/1143/1143 1162/1162/1162 1146/1146/1146 +f 1146/1146/1146 1162/1162/1162 1155/1155/1155 +f 1147/1147/1147 1156/1156/1156 1157/1157/1157 +f 1160/1160/1160 1163/1163/1163 1154/1154/1154 +f 1154/1154/1154 1163/1163/1163 1150/1150/1150 +f 1150/1150/1150 1163/1163/1163 1161/1161/1161 +f 1150/1150/1150 1161/1161/1161 1151/1151/1151 +f 1159/1159/1159 1164/1164/1164 1149/1149/1149 +f 1149/1149/1149 1164/1164/1164 1152/1152/1152 +f 1152/1152/1152 1164/1164/1164 1158/1158/1158 +f 1156/1156/1156 1165/1165/1165 1157/1157/1157 +f 1157/1157/1157 1165/1165/1165 1159/1159/1159 +f 1162/1162/1162 907/907/907 1155/1155/1155 +f 1155/1155/1155 907/907/907 1156/1156/1156 +f 1156/1156/1156 907/907/907 1165/1165/1165 +f 1159/1159/1159 1165/1165/1165 1164/1164/1164 +f 1164/1164/1164 906/906/906 1158/1158/1158 +f 1158/1158/1158 906/906/906 905/905/905 +f 1158/1158/1158 905/905/905 1160/1160/1160 +f 1160/1160/1160 905/905/905 1163/1163/1163 +f 1163/1163/1163 905/905/905 1166/1166/1166 +f 1163/1163/1163 1166/1166/1166 1161/1161/1161 +f 1161/1161/1161 1166/1166/1166 1162/1162/1162 +f 1162/1162/1162 1166/1166/1166 907/907/907 +f 1165/1165/1165 906/906/906 1164/1164/1164 +f 1166/1166/1166 905/905/905 907/907/907 +f 1165/1165/1165 907/907/907 906/906/906 +f 951/951/951 952/952/952 1167/1167/1167 +f 1029/1029/1029 1168/1168/1168 1030/1030/1030 +f 1169/1169/1169 1069/1069/1069 1168/1168/1168 +f 1169/1169/1169 908/908/908 1069/1069/1069 +f 909/909/909 1170/1170/1170 1134/1134/1134 +f 1168/1168/1168 1069/1069/1069 1030/1030/1030 +f 908/908/908 1169/1169/1169 1170/1170/1170 +f 1088/1088/1088 1171/1171/1171 1071/1071/1071 +f 1071/1071/1071 1171/1171/1171 1172/1172/1172 +f 1071/1071/1071 1172/1172/1172 1032/1032/1032 +f 1173/1173/1173 951/951/951 1167/1167/1167 +f 959/959/959 1173/1173/1173 1174/1174/1174 +f 999/999/999 981/981/981 1174/1174/1174 +f 999/999/999 1174/1174/1174 1175/1175/1175 +f 1175/1175/1175 1168/1168/1168 1029/1029/1029 +f 909/909/909 908/908/908 1170/1170/1170 +f 1171/1171/1171 1088/1088/1088 1124/1124/1124 +f 1032/1032/1032 1172/1172/1172 1176/1176/1176 +f 1176/1176/1176 1001/1001/1001 1032/1032/1032 +f 998/998/998 1176/1176/1176 1177/1177/1177 +f 1177/1177/1177 987/987/987 998/998/998 +f 1173/1173/1173 959/959/959 951/951/951 +f 1174/1174/1174 981/981/981 959/959/959 +f 1176/1176/1176 998/998/998 1001/1001/1001 +f 972/972/972 987/987/987 1177/1177/1177 +f 1167/1167/1167 952/952/952 1178/1178/1178 +f 1175/1175/1175 1029/1029/1029 999/999/999 +f 1171/1171/1171 1124/1124/1124 1134/1134/1134 +f 1171/1171/1171 1134/1134/1134 1170/1170/1170 +f 972/972/972 1177/1177/1177 1178/1178/1178 +f 952/952/952 972/972/972 1178/1178/1178 +f 1179/1179/1179 1076/1076/1076 1180/1180/1180 +f 915/915/915 1179/1179/1179 1181/1181/1181 +f 1181/1181/1181 912/912/912 915/915/915 +f 1089/1089/1089 913/913/913 1182/1182/1182 +f 1183/1183/1183 1089/1089/1089 1182/1182/1182 +f 1179/1179/1179 1082/1082/1082 1076/1076/1076 +f 1179/1179/1179 915/915/915 1082/1082/1082 +f 1180/1180/1180 1076/1076/1076 918/918/918 +f 912/912/912 1181/1181/1181 1182/1182/1182 +f 1182/1182/1182 913/913/913 912/912/912 +f 1180/1180/1180 917/917/917 1184/1184/1184 +f 962/962/962 1185/1185/1185 983/983/983 +f 983/983/983 1185/1185/1185 1184/1184/1184 +f 1180/1180/1180 918/918/918 917/917/917 +f 1183/1183/1183 1090/1090/1090 1089/1089/1089 +f 991/991/991 1186/1186/1186 964/964/964 +f 983/983/983 1184/1184/1184 1002/1002/1002 +f 1092/1092/1092 1090/1090/1090 1183/1183/1183 +f 1092/1092/1092 1183/1183/1183 1187/1187/1187 +f 991/991/991 1188/1188/1188 1186/1186/1186 +f 947/947/947 1185/1185/1185 962/962/962 +f 1002/1002/1002 1184/1184/1184 917/917/917 +f 954/954/954 964/964/964 1186/1186/1186 +f 1187/1187/1187 1095/1095/1095 1092/1092/1092 +f 1095/1095/1095 1187/1187/1187 1188/1188/1188 +f 1188/1188/1188 1005/1005/1005 1095/1095/1095 +f 1188/1188/1188 991/991/991 1005/1005/1005 +f 1185/1185/1185 947/947/947 954/954/954 +f 1185/1185/1185 954/954/954 1186/1186/1186 +f 1189/1189/1189 1190/1190/1190 1191/1191/1191 +f 1191/1191/1191 1190/1190/1190 1192/1192/1192 +f 1191/1191/1191 1192/1192/1192 1193/1193/1193 +f 1193/1193/1193 1192/1192/1192 1194/1194/1194 +f 1194/1194/1194 1192/1192/1192 1195/1195/1195 +f 1194/1194/1194 1195/1195/1195 1196/1196/1196 +f 1194/1194/1194 1196/1196/1196 1197/1197/1197 +f 1197/1197/1197 1196/1196/1196 1198/1198/1198 +f 1197/1197/1197 1198/1198/1198 1199/1199/1199 +f 1199/1199/1199 1198/1198/1198 1200/1200/1200 +f 1200/1200/1200 1198/1198/1198 1201/1201/1201 +f 1200/1200/1200 1201/1201/1201 1202/1202/1202 +f 1202/1202/1202 1201/1201/1201 1203/1203/1203 +f 1202/1202/1202 1203/1203/1203 1204/1204/1204 +f 1204/1204/1204 1203/1203/1203 1205/1205/1205 +f 1204/1204/1204 1205/1205/1205 1206/1206/1206 +f 1206/1206/1206 1205/1205/1205 1207/1207/1207 +f 1207/1207/1207 1205/1205/1205 1208/1208/1208 +f 1207/1207/1207 1208/1208/1208 1209/1209/1209 +f 1209/1209/1209 1208/1208/1208 1210/1210/1210 +f 1209/1209/1209 1210/1210/1210 1211/1211/1211 +f 1211/1211/1211 1210/1210/1210 1212/1212/1212 +f 1211/1211/1211 1212/1212/1212 1213/1213/1213 +f 1213/1213/1213 1212/1212/1212 1214/1214/1214 +f 1213/1213/1213 1214/1214/1214 1215/1215/1215 +f 1215/1215/1215 1214/1214/1214 1189/1189/1189 +f 1189/1189/1189 1214/1214/1214 1190/1190/1190 +f 1187/1187/1187 1201/1201/1201 1188/1188/1188 +f 1201/1201/1201 1198/1198/1198 1188/1188/1188 +f 1188/1188/1188 1198/1198/1198 1186/1186/1186 +f 1186/1186/1186 1198/1198/1198 1196/1196/1196 +f 1186/1186/1186 1196/1196/1196 1185/1185/1185 +f 1185/1185/1185 1196/1196/1196 1195/1195/1195 +f 1195/1195/1195 1192/1192/1192 1185/1185/1185 +f 1185/1185/1185 1192/1192/1192 1184/1184/1184 +f 1192/1192/1192 1190/1190/1190 1184/1184/1184 +f 1184/1184/1184 1190/1190/1190 1214/1214/1214 +f 1184/1184/1184 1214/1214/1214 1180/1180/1180 +f 1180/1180/1180 1214/1214/1214 1212/1212/1212 +f 1180/1180/1180 1212/1212/1212 1179/1179/1179 +f 1179/1179/1179 1212/1212/1212 1181/1181/1181 +f 1181/1181/1181 1212/1212/1212 1210/1210/1210 +f 1210/1210/1210 1208/1208/1208 1181/1181/1181 +f 1181/1181/1181 1208/1208/1208 1182/1182/1182 +f 1182/1182/1182 1208/1208/1208 1205/1205/1205 +f 1182/1182/1182 1205/1205/1205 1183/1183/1183 +f 1205/1205/1205 1203/1203/1203 1183/1183/1183 +f 1183/1183/1183 1203/1203/1203 1187/1187/1187 +f 1187/1187/1187 1203/1203/1203 1201/1201/1201 +f 1176/1176/1176 1189/1189/1189 1177/1177/1177 +f 1177/1177/1177 1189/1189/1189 1191/1191/1191 +f 1177/1177/1177 1191/1191/1191 1178/1178/1178 +f 1191/1191/1191 1193/1193/1193 1178/1178/1178 +f 1178/1178/1178 1193/1193/1193 1194/1194/1194 +f 1178/1178/1178 1194/1194/1194 1167/1167/1167 +f 1167/1167/1167 1194/1194/1194 1197/1197/1197 +f 1167/1167/1167 1197/1197/1197 1173/1173/1173 +f 1173/1173/1173 1197/1197/1197 1199/1199/1199 +f 1173/1173/1173 1199/1199/1199 1174/1174/1174 +f 1174/1174/1174 1199/1199/1199 1200/1200/1200 +f 1174/1174/1174 1200/1200/1200 1175/1175/1175 +f 1200/1200/1200 1202/1202/1202 1175/1175/1175 +f 1175/1175/1175 1202/1202/1202 1168/1168/1168 +f 1202/1202/1202 1204/1204/1204 1168/1168/1168 +f 1168/1168/1168 1204/1204/1204 1206/1206/1206 +f 1168/1168/1168 1206/1206/1206 1169/1169/1169 +f 1169/1169/1169 1206/1206/1206 1170/1170/1170 +f 1170/1170/1170 1206/1206/1206 1207/1207/1207 +f 1207/1207/1207 1209/1209/1209 1170/1170/1170 +f 1170/1170/1170 1209/1209/1209 1171/1171/1171 +f 1209/1209/1209 1211/1211/1211 1171/1171/1171 +f 1171/1171/1171 1211/1211/1211 1172/1172/1172 +f 1172/1172/1172 1211/1211/1211 1213/1213/1213 +f 1172/1172/1172 1213/1213/1213 1176/1176/1176 +f 1213/1213/1213 1215/1215/1215 1176/1176/1176 +f 1176/1176/1176 1215/1215/1215 1189/1189/1189 +f 1216/1216/1216 1217/1217/1217 1218/1218/1218 +f 1218/1218/1218 1217/1217/1217 1219/1219/1219 +f 1218/1218/1218 1219/1219/1219 1220/1220/1220 +f 1220/1220/1220 1219/1219/1219 1221/1221/1221 +f 1220/1220/1220 1221/1221/1221 1222/1222/1222 +f 1222/1222/1222 1223/1223/1223 1224/1224/1224 +f 1222/1222/1222 1221/1221/1221 1223/1223/1223 +f 1217/1217/1217 1216/1216/1216 1225/1225/1225 +f 1224/1224/1224 1223/1223/1223 1226/1226/1226 +f 1227/1227/1227 1228/1228/1228 1229/1229/1229 +f 1230/1230/1230 1231/1231/1231 1232/1232/1232 +f 1232/1232/1232 1231/1231/1231 1233/1233/1233 +f 1232/1232/1232 1233/1233/1233 1234/1234/1234 +f 1234/1234/1234 1235/1235/1235 1236/1236/1236 +f 1234/1234/1234 1233/1233/1233 1235/1235/1235 +f 1236/1236/1236 1235/1235/1235 1228/1228/1228 +f 1236/1236/1236 1228/1228/1228 1227/1227/1227 +f 1237/1237/1237 1227/1227/1227 1229/1229/1229 +f 1238/1238/1238 1239/1239/1239 1240/1240/1240 +f 1240/1240/1240 1239/1239/1239 1241/1241/1241 +f 1240/1240/1240 1242/1242/1242 1243/1243/1243 +f 1244/1244/1244 1245/1245/1245 1239/1239/1239 +f 1240/1240/1240 1241/1241/1241 1246/1246/1246 +f 1239/1239/1239 1245/1245/1245 1241/1241/1241 +f 1242/1242/1242 1240/1240/1240 1247/1247/1247 +f 1248/1248/1248 1242/1242/1242 1247/1247/1247 +f 1247/1247/1247 1240/1240/1240 1246/1246/1246 +f 1249/1249/1249 1250/1250/1250 1251/1251/1251 +f 1252/1252/1252 1249/1249/1249 1253/1253/1253 +f 1254/1254/1254 1255/1255/1255 1256/1256/1256 +f 1255/1255/1255 1257/1257/1257 1258/1258/1258 +f 1257/1257/1257 1259/1259/1259 1258/1258/1258 +f 1259/1259/1259 1252/1252/1252 1258/1258/1258 +f 1252/1252/1252 1253/1253/1253 1258/1258/1258 +f 1254/1254/1254 1257/1257/1257 1255/1255/1255 +f 1249/1249/1249 1251/1251/1251 1253/1253/1253 +f 1260/1260/1260 1254/1254/1254 1256/1256/1256 +f 1261/1261/1261 1262/1262/1262 1263/1263/1263 +f 1261/1261/1261 1263/1263/1263 1264/1264/1264 +f 1264/1264/1264 1263/1263/1263 1265/1265/1265 +f 1264/1264/1264 1265/1265/1265 1266/1266/1266 +f 1266/1266/1266 1265/1265/1265 1267/1267/1267 +f 1266/1266/1266 1267/1267/1267 1268/1268/1268 +f 1268/1268/1268 1267/1267/1267 1269/1269/1269 +f 1268/1268/1268 1269/1269/1269 1270/1270/1270 +f 1270/1270/1270 1269/1269/1269 1271/1271/1271 +f 1270/1270/1270 1271/1271/1271 1272/1272/1272 +f 1272/1272/1272 1271/1271/1271 1273/1273/1273 +f 1272/1272/1272 1273/1273/1273 1274/1274/1274 +f 1274/1274/1274 1273/1273/1273 1275/1275/1275 +f 1274/1274/1274 1275/1275/1275 1276/1276/1276 +f 1276/1276/1276 1275/1275/1275 1277/1277/1277 +f 1276/1276/1276 1277/1277/1277 1278/1278/1278 +f 1278/1278/1278 1277/1277/1277 1279/1279/1279 +f 1278/1278/1278 1279/1279/1279 1280/1280/1280 +f 1280/1280/1280 1279/1279/1279 1281/1281/1281 +f 1280/1280/1280 1281/1281/1281 1282/1282/1282 +f 1282/1282/1282 1281/1281/1281 1283/1283/1283 +f 1282/1282/1282 1283/1283/1283 1284/1284/1284 +f 1284/1284/1284 1283/1283/1283 1285/1285/1285 +f 1284/1284/1284 1285/1285/1285 1286/1286/1286 +f 1284/1284/1284 1286/1286/1286 1287/1287/1287 +f 1287/1287/1287 1286/1286/1286 1288/1288/1288 +f 1287/1287/1287 1288/1288/1288 1289/1289/1289 +f 1289/1289/1289 1288/1288/1288 1290/1290/1290 +f 1289/1289/1289 1290/1290/1290 1291/1291/1291 +f 1291/1291/1291 1290/1290/1290 1292/1292/1292 +f 1292/1292/1292 1290/1290/1290 1262/1262/1262 +f 1292/1292/1292 1262/1262/1262 1261/1261/1261 +f 1260/1260/1260 1256/1256/1256 23/23/23 +f 28/28/28 1255/1255/1255 1258/1258/1258 +f 1254/1254/1254 1260/1260/1260 22/22/22 +f 23/23/23 1256/1256/1256 78/78/78 +f 78/78/78 1256/1256/1256 82/82/82 +f 1254/1254/1254 22/22/22 55/55/55 +f 82/82/82 1256/1256/1256 1255/1255/1255 +f 1254/1254/1254 55/55/55 1257/1257/1257 +f 82/82/82 1255/1255/1255 27/27/27 +f 1257/1257/1257 55/55/55 54/54/54 +f 1257/1257/1257 54/54/54 1259/1259/1259 +f 27/27/27 1255/1255/1255 28/28/28 +f 1259/1259/1259 54/54/54 32/32/32 +f 28/28/28 1258/1258/1258 49/49/49 +f 1259/1259/1259 32/32/32 1252/1252/1252 +f 52/52/52 49/49/49 1258/1258/1258 +f 1252/1252/1252 32/32/32 30/30/30 +f 1251/1251/1251 36/36/36 44/44/44 +f 1260/1260/1260 23/23/23 22/22/22 +f 1252/1252/1252 84/84/84 1249/1249/1249 +f 45/45/45 1249/1249/1249 84/84/84 +f 30/30/30 84/84/84 1252/1252/1252 +f 52/52/52 1258/1258/1258 1253/1253/1253 +f 44/44/44 52/52/52 1253/1253/1253 +f 1253/1253/1253 1251/1251/1251 44/44/44 +f 38/38/38 1250/1250/1250 45/45/45 +f 1251/1251/1251 1250/1250/1250 36/36/36 +f 1250/1250/1250 1249/1249/1249 45/45/45 +f 1250/1250/1250 38/38/38 36/36/36 +f 686/686/686 1234/1234/1234 687/687/687 +f 1233/1233/1233 718/718/718 684/684/684 +f 687/687/687 1234/1234/1234 1236/1236/1236 +f 1233/1233/1233 684/684/684 1235/1235/1235 +f 1231/1231/1231 1230/1230/1230 669/669/669 +f 1235/1235/1235 684/684/684 679/679/679 +f 687/687/687 1236/1236/1236 723/723/723 +f 686/686/686 1232/1232/1232 1234/1234/1234 +f 698/698/698 1227/1227/1227 1237/1237/1237 +f 1235/1235/1235 679/679/679 1228/1228/1228 +f 723/723/723 1227/1227/1227 698/698/698 +f 1228/1228/1228 679/679/679 748/748/748 +f 1237/1237/1237 677/677/677 676/676/676 +f 676/676/676 698/698/698 1237/1237/1237 +f 1228/1228/1228 748/748/748 1229/1229/1229 +f 748/748/748 742/742/742 1229/1229/1229 +f 1237/1237/1237 1229/1229/1229 677/677/677 +f 1231/1231/1231 669/669/669 682/682/682 +f 1276/1276/1276 1226/1226/1226 1223/1223/1223 +f 1276/1276/1276 1223/1223/1223 1274/1274/1274 +f 1274/1274/1274 1223/1223/1223 1272/1272/1272 +f 1272/1272/1272 1223/1223/1223 1221/1221/1221 +f 1272/1272/1272 1221/1221/1221 1270/1270/1270 +f 1270/1270/1270 1221/1221/1221 1219/1219/1219 +f 1270/1270/1270 1219/1219/1219 1268/1268/1268 +f 1268/1268/1268 1219/1219/1219 1266/1266/1266 +f 1266/1266/1266 1219/1219/1219 1217/1217/1217 +f 1266/1266/1266 1217/1217/1217 1264/1264/1264 +f 1264/1264/1264 1217/1217/1217 1225/1225/1225 +f 1264/1264/1264 1225/1225/1225 1261/1261/1261 +f 1261/1261/1261 1225/1225/1225 1216/1216/1216 +f 1261/1261/1261 1216/1216/1216 1292/1292/1292 +f 1292/1292/1292 1216/1216/1216 1291/1291/1291 +f 1291/1291/1291 1216/1216/1216 1218/1218/1218 +f 1291/1291/1291 1218/1218/1218 1289/1289/1289 +f 1289/1289/1289 1218/1218/1218 1287/1287/1287 +f 1287/1287/1287 1218/1218/1218 1220/1220/1220 +f 1287/1287/1287 1220/1220/1220 1284/1284/1284 +f 1284/1284/1284 1220/1220/1220 1222/1222/1222 +f 1284/1284/1284 1222/1222/1222 1282/1282/1282 +f 1282/1282/1282 1222/1222/1222 1280/1280/1280 +f 1280/1280/1280 1222/1222/1222 1224/1224/1224 +f 1280/1280/1280 1224/1224/1224 1278/1278/1278 +f 1278/1278/1278 1224/1224/1224 1226/1226/1226 +f 1278/1278/1278 1226/1226/1226 1276/1276/1276 +f 1262/1262/1262 1238/1238/1238 1240/1240/1240 +f 1262/1262/1262 1240/1240/1240 1263/1263/1263 +f 1263/1263/1263 1240/1240/1240 1243/1243/1243 +f 1263/1263/1263 1243/1243/1243 1265/1265/1265 +f 1265/1265/1265 1243/1243/1243 1242/1242/1242 +f 1265/1265/1265 1242/1242/1242 1267/1267/1267 +f 1267/1267/1267 1242/1242/1242 1269/1269/1269 +f 1269/1269/1269 1242/1242/1242 1248/1248/1248 +f 1269/1269/1269 1248/1248/1248 1271/1271/1271 +f 1271/1271/1271 1248/1248/1248 1247/1247/1247 +f 1271/1271/1271 1247/1247/1247 1273/1273/1273 +f 1273/1273/1273 1247/1247/1247 1275/1275/1275 +f 1275/1275/1275 1247/1247/1247 1246/1246/1246 +f 1275/1275/1275 1246/1246/1246 1277/1277/1277 +f 1277/1277/1277 1246/1246/1246 1241/1241/1241 +f 1277/1277/1277 1241/1241/1241 1279/1279/1279 +f 1279/1279/1279 1241/1241/1241 1281/1281/1281 +f 1281/1281/1281 1241/1241/1241 1245/1245/1245 +f 1281/1281/1281 1245/1245/1245 1283/1283/1283 +f 1283/1283/1283 1245/1245/1245 1244/1244/1244 +f 1283/1283/1283 1244/1244/1244 1285/1285/1285 +f 1285/1285/1285 1244/1244/1244 1286/1286/1286 +f 1286/1286/1286 1244/1244/1244 1239/1239/1239 +f 1286/1286/1286 1239/1239/1239 1288/1288/1288 +f 1288/1288/1288 1239/1239/1239 1290/1290/1290 +f 1290/1290/1290 1239/1239/1239 1238/1238/1238 +f 1290/1290/1290 1238/1238/1238 1262/1262/1262 +f 677/677/677 1229/1229/1229 742/742/742 +f 1230/1230/1230 1232/1232/1232 670/670/670 +f 669/669/669 1230/1230/1230 670/670/670 +f 1231/1231/1231 682/682/682 703/703/703 +f 670/670/670 1232/1232/1232 755/755/755 +f 723/723/723 1236/1236/1236 1227/1227/1227 +f 1231/1231/1231 703/703/703 1233/1233/1233 +f 1233/1233/1233 703/703/703 718/718/718 +f 755/755/755 1232/1232/1232 686/686/686 diff --git a/examples/Cassie/urdf/meshes/agility/foot-crank.obj b/examples/Cassie/urdf/meshes/agility/foot-crank.obj new file mode 100644 index 0000000000..1f58845f18 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/foot-crank.obj @@ -0,0 +1,2288 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o foot-crank +v 0.010112 0.006500 -0.012100 +v 0.013631 0.006500 -0.010024 +v 0.015140 0.006500 -0.014033 +v 0.011655 0.006500 -0.015195 +v 0.045881 0.009829 0.004350 +v 0.058340 0.009674 0.003165 +v 0.058320 0.009776 -0.002873 +v 0.010199 0.009850 -0.012440 +v 0.011151 0.009850 -0.014928 +v 0.007261 0.009862 -0.017347 +v 0.014829 0.009853 -0.014520 +v 0.017547 0.009850 -0.007428 +v 0.014904 0.009850 -0.011291 +v 0.011854 0.009850 -0.010143 +v 0.007184 0.009819 0.018008 +v 0.014211 0.009850 0.015182 +v 0.010320 0.009850 0.013934 +v 0.014583 0.009850 0.010591 +v 0.018888 0.009850 0.007083 +v 0.014979 0.009850 0.005865 +v -0.014673 0.009850 -0.004259 +v 0.016142 0.009850 0.002145 +v 0.024922 0.009841 -0.002128 +v 0.019642 0.009850 0.003271 +v 0.023921 0.009850 0.008141 +v 0.014698 0.009850 -0.004818 +v 0.016975 0.009850 -0.001961 +v 0.023760 0.009728 -0.008461 +v 0.020101 0.009850 -0.004259 +v -0.012382 0.009695 -0.015353 +v -0.005558 0.009850 -0.014676 +v -0.006936 0.009509 -0.019030 +v -0.002146 0.009850 -0.016551 +v -0.010239 0.009850 -0.013483 +v 0.004741 0.009850 -0.014532 +v 0.002113 0.009960 -0.018665 +v -0.003226 0.009649 -0.019677 +v 0.025909 0.009713 -0.010863 +v 0.045679 0.009820 -0.004959 +v 0.025482 0.009812 0.010659 +v 0.010970 0.009850 0.010748 +v -0.010040 0.009850 0.012887 +v -0.011691 0.009850 0.010335 +v 0.002539 0.009850 0.015386 +v 0.006452 0.009850 0.015493 +v -0.007319 0.009934 0.017050 +v -0.003503 0.009850 0.014710 +v -0.017273 0.009901 0.007318 +v -0.014710 0.009905 0.010934 +v -0.012712 0.009585 0.015460 +v -0.002333 0.009877 0.018559 +v 0.002815 0.009809 0.019199 +v -0.017103 0.009926 -0.007334 +v -0.011892 0.009850 -0.009935 +v -0.015242 0.009763 -0.012038 +v 0.058395 -0.002886 0.001583 +v 0.060941 -0.003150 -0.001941 +v 0.059731 -0.003150 0.004084 +v 0.054124 -0.002906 0.003515 +v 0.053668 -0.003072 0.006377 +v 0.056665 -0.002911 -0.003360 +v 0.056736 -0.003188 -0.005845 +v 0.052146 -0.002946 -0.002382 +v 0.051788 -0.003124 -0.005201 +v 0.051412 -0.002875 0.000623 +v 0.048546 -0.003174 -0.000656 +v 0.042186 0.003939 0.010004 +v 0.008658 0.004352 0.019841 +v 0.016932 0.004350 0.013583 +v 0.021852 0.004350 0.001363 +v 0.036187 0.004177 0.001313 +v 0.018555 0.004350 -0.011265 +v 0.010044 0.004349 -0.019303 +v 0.039204 0.004232 -0.010872 +v 0.000796 0.008033 0.021628 +v 0.002963 0.000853 0.021900 +v 0.016317 0.000850 0.014316 +v 0.022128 0.000850 0.000586 +v 0.015864 0.000850 -0.015091 +v 0.002194 0.000851 -0.021767 +v 0.001657 0.007707 -0.021533 +v -0.009686 0.007857 0.019190 +v -0.014615 0.000850 0.016616 +v -0.014810 0.008777 0.015014 +v -0.019442 0.008196 0.009242 +v -0.021430 0.000850 0.003368 +v -0.021306 0.008222 0.001557 +v -0.019698 0.000850 -0.009627 +v -0.020572 0.008560 -0.005243 +v -0.017562 0.008172 -0.012271 +v -0.011650 0.007907 -0.018061 +v -0.010489 0.000850 -0.018978 +v -0.005737 0.007387 -0.020753 +v -0.017214 0.006500 0.007322 +v -0.019810 0.009057 0.005769 +v -0.019754 0.006500 0.005747 +v -0.019279 0.006500 0.002756 +v -0.019195 0.009787 0.002801 +v -0.014887 0.006500 0.005402 +v -0.014767 0.009850 0.005046 +v -0.015780 0.006500 0.002497 +v -0.016318 0.009850 0.002187 +v -0.013463 0.006500 0.015444 +v -0.015341 0.006500 0.012070 +v -0.009875 0.006500 0.012794 +v -0.012654 0.006500 0.010081 +v -0.002294 0.006500 0.018954 +v -0.005419 0.009001 0.020027 +v -0.006206 0.006500 0.019580 +v -0.007009 0.006500 0.015800 +v -0.003271 0.006500 0.015131 +v 0.006858 0.006500 0.018950 +v 0.004746 0.009058 0.020067 +v 0.003524 0.006500 0.019839 +v 0.002078 0.006500 0.017360 +v 0.006723 0.006500 0.015732 +v 0.003590 0.006500 0.014915 +v 0.011423 0.006500 0.010316 +v 0.010314 0.006500 0.014031 +v 0.014712 0.006500 0.014883 +v 0.014622 0.006500 0.010935 +v 0.018500 0.006500 0.007218 +v 0.019801 0.006500 0.003355 +v 0.015865 0.006500 0.002300 +v 0.015058 0.006500 0.005918 +v 0.016200 0.006500 -0.002233 +v 0.019548 0.006500 -0.003052 +v 0.018698 0.006500 -0.007254 +v 0.014806 0.006500 -0.005429 +v 0.002071 0.006500 -0.018026 +v 0.004514 0.006500 -0.020072 +v 0.005706 0.009038 -0.019846 +v 0.007253 0.006500 -0.018068 +v 0.004573 0.006500 -0.014413 +v -0.003886 0.006500 -0.020080 +v -0.007214 0.006500 -0.018211 +v -0.002078 0.006500 -0.017360 +v -0.004745 0.006500 -0.014413 +v -0.015369 0.006500 -0.012196 +v -0.014067 0.009230 -0.015061 +v -0.013412 0.006500 -0.015446 +v -0.010228 0.006500 -0.013622 +v -0.011829 0.006500 -0.010018 +v -0.019887 0.009471 -0.003604 +v -0.018124 0.006500 -0.002161 +v -0.020155 0.006500 -0.005107 +v -0.016022 0.006500 -0.007228 +v -0.017245 0.009872 -0.002028 +v -0.015225 0.006500 -0.003052 +v 0.057162 0.007571 0.005588 +v 0.048665 0.000661 0.007974 +v 0.046786 0.001933 -0.008632 +v 0.058501 0.007656 -0.005057 +v 0.060812 0.008242 -0.001021 +v 0.060024 0.007766 0.003425 +v 0.042021 0.002240 0.001512 +v 0.046524 -0.000719 -0.000820 +v 0.026055 0.007407 0.008351 +v 0.044269 0.007535 0.003459 +v 0.026593 0.007565 -0.000062 +v 0.025716 0.007448 -0.008216 +v 0.044273 0.007624 -0.004157 +v 0.044259 0.008502 0.005160 +v 0.045361 0.008609 -0.002678 +v 0.026228 0.008408 0.010209 +v 0.024386 0.008625 0.008167 +v 0.026370 0.007950 -0.009665 +v 0.005195 0.009005 0.019447 +v 0.006975 0.008933 0.017818 +v 0.005627 0.009018 0.015476 +v 0.003079 0.008919 0.015641 +v 0.002739 0.008997 0.018524 +v 0.006172 0.006409 0.017382 +v 0.006284 0.006520 0.015982 +v 0.006512 0.006543 0.018959 +v 0.004060 0.006413 0.018754 +v 0.002789 0.006543 0.018939 +v 0.003434 0.006426 0.016660 +v 0.003300 0.006551 0.015423 +v 0.004621 0.007500 0.018277 +v 0.004800 0.007500 0.016203 +v -0.015115 0.008922 0.012549 +v -0.013498 0.008936 0.014879 +v -0.013884 0.008786 0.013051 +v -0.010949 0.009009 0.014077 +v -0.013095 0.009002 0.010642 +v -0.010983 0.008922 0.011149 +v -0.012961 0.006377 0.014273 +v -0.011131 0.006528 0.014564 +v -0.014872 0.006526 0.013878 +v -0.013926 0.006424 0.011928 +v -0.014107 0.006497 0.011059 +v -0.011185 0.006556 0.010853 +v -0.011345 0.006424 0.012325 +v -0.011937 0.007500 0.012316 +v -0.006149 0.008933 0.019313 +v -0.003156 0.008911 0.019109 +v -0.006634 0.009023 0.016520 +v -0.002418 0.008963 0.017174 +v -0.003394 0.006422 0.018115 +v -0.003020 0.006532 0.019295 +v -0.005385 0.006426 0.018611 +v -0.006568 0.006536 0.018695 +v -0.005924 0.006422 0.016658 +v -0.006213 0.006568 0.015523 +v -0.003932 0.006426 0.016162 +v -0.003051 0.006548 0.015725 +v -0.004011 0.008994 0.015286 +v -0.003607 0.007500 0.016862 +v -0.005711 0.007500 0.017912 +v -0.015318 0.008932 0.005779 +v -0.015680 0.008923 0.003142 +v -0.016224 0.008735 0.004957 +v -0.017827 0.009002 0.002575 +v -0.019436 0.008934 0.003721 +v -0.019207 0.009010 0.005673 +v -0.017772 0.008936 0.006910 +v -0.015985 0.006408 0.005128 +v -0.017999 0.006560 0.006886 +v -0.018577 0.006385 0.005666 +v -0.019733 0.006568 0.004674 +v -0.017451 0.006407 0.003148 +v -0.018310 0.006542 0.002609 +v -0.016034 0.006570 0.002785 +v -0.015229 0.006551 0.005680 +v -0.018277 0.007500 0.004621 +v 0.012584 0.008937 0.015118 +v 0.015115 0.008922 0.012907 +v 0.012226 0.009000 0.013791 +v 0.013940 0.008972 0.010924 +v 0.010555 0.008934 0.013327 +v 0.011432 0.008990 0.010858 +v 0.013919 0.006385 0.011721 +v 0.014957 0.006571 0.012120 +v 0.013601 0.006528 0.014999 +v 0.012792 0.006407 0.014239 +v 0.010256 0.006513 0.012869 +v 0.011326 0.006408 0.012258 +v 0.012765 0.006566 0.010381 +v 0.013442 0.007500 0.011773 +v 0.012249 0.007500 0.013480 +v 0.019569 0.008922 0.005643 +v 0.018758 0.009017 0.003081 +v 0.017729 0.009019 0.006683 +v 0.015380 0.009021 0.004240 +v 0.015537 0.008915 0.006056 +v 0.016777 0.008942 0.002423 +v 0.018115 0.006422 0.003394 +v 0.019401 0.006544 0.003449 +v 0.018664 0.006427 0.005195 +v 0.018537 0.006526 0.006802 +v 0.017221 0.006424 0.006072 +v 0.014988 0.006544 0.005253 +v 0.015941 0.006407 0.004264 +v 0.016779 0.006571 0.002430 +v 0.018035 0.007500 0.003678 +v 0.016738 0.007500 0.005639 +v 0.015318 0.008932 -0.005779 +v 0.016031 0.009003 -0.002945 +v 0.016224 0.008735 -0.004957 +v 0.018812 0.008939 -0.002736 +v 0.019342 0.009012 -0.005390 +v 0.017924 0.008925 -0.006913 +v 0.016725 0.006413 -0.005996 +v 0.016124 0.006547 -0.006596 +v 0.019275 0.006554 -0.006186 +v 0.018769 0.006424 -0.005062 +v 0.018772 0.006563 -0.002716 +v 0.017790 0.006424 -0.003276 +v 0.015301 0.006528 -0.003405 +v 0.016136 0.006430 -0.004046 +v 0.018277 0.007500 -0.004621 +v 0.014243 0.009000 -0.010990 +v 0.014638 0.008929 -0.014044 +v 0.012778 0.009017 -0.014798 +v 0.010646 0.008919 -0.013828 +v 0.011117 0.008994 -0.011233 +v 0.011196 0.006377 -0.012419 +v 0.010501 0.006560 -0.013340 +v 0.012349 0.006563 -0.014972 +v 0.013582 0.006392 -0.014012 +v 0.014665 0.006547 -0.013990 +v 0.013580 0.006424 -0.011567 +v 0.014602 0.006570 -0.011376 +v 0.011707 0.006551 -0.010570 +v 0.013518 0.007500 -0.013140 +v 0.011632 0.007500 -0.012258 +v 0.002902 0.009010 -0.016096 +v 0.005119 0.008923 -0.015150 +v 0.006720 0.008980 -0.016668 +v 0.003276 0.006424 -0.016984 +v 0.003051 0.006517 -0.019323 +v 0.004256 0.006424 -0.018769 +v 0.006596 0.006547 -0.018649 +v 0.006041 0.006424 -0.017790 +v 0.006273 0.006544 -0.015626 +v 0.005062 0.006424 -0.016004 +v 0.003122 0.006566 -0.015613 +v 0.006289 0.008997 -0.018889 +v 0.003103 0.008982 -0.019145 +v 0.003607 0.007500 -0.016862 +v 0.005711 0.007500 -0.017912 +v -0.005671 0.008999 -0.019404 +v -0.006870 0.008945 -0.016572 +v -0.004485 0.008996 -0.015203 +v -0.002956 0.008998 -0.018704 +v -0.002492 0.008923 -0.016667 +v -0.005924 0.006422 -0.018115 +v -0.006640 0.006499 -0.016990 +v -0.005967 0.006536 -0.019296 +v -0.003859 0.006424 -0.018584 +v -0.002771 0.006554 -0.018914 +v -0.003579 0.006413 -0.016356 +v -0.002926 0.006563 -0.015911 +v -0.005271 0.006560 -0.015160 +v -0.004621 0.007500 -0.018277 +v -0.004800 0.007500 -0.016203 +v -0.010589 0.008999 -0.013104 +v -0.012584 0.008937 -0.015118 +v -0.014867 0.009008 -0.013178 +v -0.013828 0.008919 -0.010646 +v -0.011545 0.009010 -0.010977 +v -0.013919 0.006385 -0.011721 +v -0.013668 0.006548 -0.010532 +v -0.014971 0.006548 -0.013289 +v -0.012792 0.006407 -0.014239 +v -0.012507 0.006551 -0.015105 +v -0.011326 0.006408 -0.012258 +v -0.010334 0.006546 -0.012114 +v -0.013709 0.007500 -0.013377 +v -0.011747 0.007500 -0.012079 +v -0.019474 0.008989 -0.005331 +v -0.018391 0.008955 -0.002484 +v -0.016290 0.009007 -0.002784 +v -0.015303 0.009005 -0.005116 +v -0.017243 0.008939 -0.007048 +v -0.018769 0.006424 -0.004256 +v -0.019168 0.006497 -0.003353 +v -0.019260 0.006570 -0.006011 +v -0.017451 0.006407 -0.006170 +v -0.016774 0.006560 -0.006886 +v -0.015985 0.006408 -0.004189 +v -0.015040 0.006557 -0.004645 +v -0.016779 0.006571 -0.002430 +v -0.016213 0.007500 -0.004587 +v -0.018560 0.007500 -0.004730 +v 0.059855 -0.015745 0.000714 +v 0.056740 -0.015760 -0.000579 +v 0.057468 -0.015697 -0.004239 +v 0.051237 -0.015757 0.002934 +v 0.055407 -0.015749 0.001924 +v 0.055933 -0.015763 0.004819 +v 0.055444 -0.015801 -0.001806 +v 0.053155 -0.015743 -0.004352 +v 0.053620 -0.015815 -0.001255 +v 0.050382 -0.015747 -0.001445 +v 0.053260 -0.015761 0.000585 +v 0.050731 -0.012675 0.002687 +v 0.056517 -0.012675 0.004901 +v 0.060040 -0.012675 -0.000192 +v 0.056136 -0.012675 -0.005003 +v 0.050826 -0.012675 -0.002695 +v 0.057466 -0.012675 0.002558 +v 0.057462 -0.012675 -0.002375 +v 0.052534 -0.012675 -0.002558 +v 0.052539 -0.012675 0.002375 +v 0.052136 0.003073 0.001708 +v 0.055533 0.003118 0.003061 +v 0.057850 0.003065 0.001528 +v 0.057772 0.003060 -0.001413 +v 0.055501 0.003048 -0.003197 +v 0.052574 0.003103 -0.001978 +v 0.054255 -0.014263 -0.001752 +v 0.055745 -0.014263 0.001752 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn -0.0000 1.0000 0.0000 +vn 0.0133 0.9994 0.0323 +vn 0.0163 0.9995 0.0269 +vn 0.1023 0.9457 -0.3084 +vn 0.0003 1.0000 0.0007 +vn -0.0000 1.0000 0.0050 +vn 0.0585 0.9776 -0.2023 +vn 0.0029 1.0000 -0.0047 +vn 0.0106 0.9999 -0.0055 +vn -0.0008 1.0000 0.0006 +vn 0.0001 1.0000 -0.0000 +vn 0.0953 0.9421 0.3215 +vn 0.0134 0.9991 0.0410 +vn -0.0087 1.0000 0.0009 +vn 0.0034 0.9999 0.0095 +vn 0.0003 1.0000 -0.0002 +vn 0.0042 1.0000 -0.0068 +vn 0.0005 1.0000 -0.0008 +vn 0.0032 1.0000 0.0039 +vn 0.0006 1.0000 0.0003 +vn 0.0135 0.9999 -0.0064 +vn 0.0084 0.9999 -0.0087 +vn -0.0158 0.9975 -0.0689 +vn -0.0048 0.9997 -0.0219 +vn -0.0154 0.9972 -0.0732 +vn -0.0172 0.9998 -0.0096 +vn -0.0080 0.9995 -0.0314 +vn -0.0017 1.0000 0.0055 +vn -0.0206 0.9997 0.0104 +vn -0.0492 0.9977 -0.0472 +vn -0.1517 0.8571 0.4923 +vn 0.0113 0.9999 -0.0022 +vn 0.0113 0.9999 0.0039 +vn 0.0054 0.9999 -0.0117 +vn -0.0079 0.9996 -0.0281 +vn -0.0001 1.0000 0.0004 +vn -0.0211 0.9998 0.0044 +vn 0.0023 1.0000 0.0088 +vn 0.0028 1.0000 0.0012 +vn 0.0047 1.0000 0.0045 +vn -0.0995 0.9747 0.2003 +vn 0.0013 1.0000 -0.0058 +vn -0.2691 0.9495 0.1612 +vn -0.1872 0.9735 0.1316 +vn -0.2987 0.8284 0.4738 +vn -0.0227 0.9670 0.2539 +vn 0.0112 0.9126 0.4087 +vn 0.0010 1.0000 -0.0077 +vn -0.0009 0.9997 -0.0241 +vn -0.0034 0.9993 -0.0360 +vn -0.0652 -0.9975 -0.0275 +vn -0.0860 -0.9958 0.0326 +vn -0.0701 -0.9956 -0.0629 +vn 0.0028 -0.9990 -0.0451 +vn 0.0114 -0.9979 -0.0639 +vn -0.0338 -0.9972 0.0664 +vn -0.0334 -0.9934 0.1098 +vn 0.0476 -0.9979 0.0447 +vn 0.0383 -0.9969 0.0683 +vn 0.0763 -0.9968 -0.0246 +vn 0.1017 -0.9948 0.0089 +vn -0.2313 -0.9667 0.1093 +vn -0.0200 -0.9995 -0.0261 +vn -0.0192 -0.9996 -0.0206 +vn -0.0122 -0.9999 -0.0056 +vn -0.1251 -0.9921 0.0029 +vn -0.0058 -1.0000 0.0046 +vn -0.0058 -1.0000 0.0063 +vn -0.1416 -0.9889 -0.0454 +vn 0.3765 -0.0186 0.9262 +vn 0.2747 0.1182 0.9542 +vn 0.3395 0.0010 0.9406 +vn 0.5827 -0.0077 0.8126 +vn 0.6021 0.0609 0.7961 +vn 0.9195 -0.0705 0.3866 +vn 0.9180 -0.0799 0.3885 +vn 0.9262 -0.0226 0.3764 +vn 0.9276 -0.0098 0.3735 +vn 0.9592 0.1312 -0.2504 +vn 0.9605 0.0627 -0.2711 +vn 0.9045 -0.2489 -0.3462 +vn 0.8874 -0.2947 -0.3546 +vn 0.6634 0.2578 -0.7025 +vn 0.3374 -0.0959 -0.9364 +vn 0.4139 -0.3319 -0.8477 +vn 0.0944 -0.0426 -0.9946 +vn 0.0981 0.0697 -0.9927 +vn -0.2495 -0.0770 0.9653 +vn -0.2262 -0.0171 0.9739 +vn -0.3784 -0.0252 0.9253 +vn -0.6497 -0.0117 0.7601 +vn -0.7111 0.1224 0.6923 +vn -0.9037 0.0244 0.4276 +vn -0.9883 -0.0242 0.1506 +vn -0.9105 0.4111 0.0436 +vn -0.8985 0.0097 -0.4388 +vn -0.9761 0.0218 -0.2164 +vn -0.7879 0.0422 -0.6143 +vn -0.5292 0.3367 -0.7789 +vn -0.5002 -0.0301 -0.8654 +vn -0.2371 0.2434 -0.9405 +vn 0.5192 0.0080 -0.8546 +vn 0.5227 0.0129 -0.8524 +vn 0.5228 0.0131 -0.8524 +vn 0.5269 0.0189 -0.8497 +vn 0.9841 -0.0047 0.1774 +vn 0.9874 0.0203 0.1568 +vn 0.9839 -0.0063 0.1788 +vn 0.9802 -0.0277 0.1963 +vn -0.6364 -0.0119 -0.7713 +vn -0.6553 -0.0347 -0.7545 +vn -0.6541 -0.0331 -0.7557 +vn -0.6713 -0.0545 -0.7392 +vn -0.9538 0.0653 0.2932 +vn -0.9191 -0.0215 0.3935 +vn -0.9231 -0.0133 0.3844 +vn -0.8749 -0.0966 0.4746 +vn 0.0734 0.1036 0.9919 +vn 0.1394 0.0448 0.9892 +vn 0.1360 0.0479 0.9896 +vn 0.2091 -0.0187 0.9777 +vn 0.2261 -0.0500 -0.9728 +vn 0.8041 0.3912 -0.4476 +vn 0.9811 -0.1914 -0.0289 +vn -0.5876 0.1472 -0.7956 +vn -0.6337 0.0820 -0.7692 +vn -0.6494 0.0580 -0.7582 +vn -0.6928 -0.0141 -0.7210 +vn -0.7683 0.0518 0.6380 +vn -0.8383 -0.0563 0.5423 +vn -0.7674 0.0530 0.6390 +vn -0.6912 0.1450 0.7080 +vn 0.1907 -0.1286 0.9732 +vn 0.5877 0.1560 0.7939 +vn -0.4010 -0.1110 -0.9093 +vn -0.3060 0.0260 -0.9517 +vn -0.2675 0.0778 -0.9604 +vn -0.1541 0.2206 -0.9631 +vn 0.8103 -0.1539 -0.5654 +vn 0.9146 -0.0016 -0.4045 +vn 0.9325 0.0376 -0.3592 +vn 0.9653 0.1618 -0.2051 +vn -0.9624 -0.0033 0.2715 +vn -0.9566 0.0229 0.2906 +vn -0.9636 -0.0091 0.2673 +vn -0.9682 -0.0360 0.2474 +vn 0.1746 0.1347 0.9754 +vn 0.5013 -0.2557 0.8267 +vn -0.6069 -0.1613 -0.7782 +vn -0.2522 0.2048 -0.9458 +vn 0.3762 -0.0976 -0.9214 +vn 0.8605 0.0873 -0.5019 +vn -0.9931 0.1094 0.0417 +vn -0.9855 0.0215 0.1683 +vn -0.9890 0.0398 0.1423 +vn -0.9587 -0.0577 0.2783 +vn -0.2520 0.0486 0.9665 +vn -0.1374 -0.0533 0.9891 +vn -0.1322 -0.0578 0.9895 +vn -0.0270 -0.1475 0.9887 +vn 0.8351 0.1894 0.5164 +vn 0.9813 -0.1780 -0.0729 +vn -0.0690 -0.0168 0.9975 +vn -0.0712 -0.0147 0.9974 +vn 0.0431 -0.1220 0.9916 +vn 0.9541 0.0923 0.2848 +vn 0.9677 0.0522 0.2467 +vn 0.9686 0.0492 0.2438 +vn 0.9798 0.0040 0.1999 +vn 0.2553 0.0350 -0.9662 +vn 0.3053 -0.0281 -0.9518 +vn 0.2373 0.0571 -0.9698 +vn 0.1889 0.1153 -0.9752 +vn -0.9953 -0.0885 -0.0391 +vn -0.9869 -0.1404 -0.0800 +vn -0.9973 -0.0691 -0.0240 +vn -0.9997 -0.0093 0.0228 +vn -0.1891 0.0981 0.9771 +vn -0.9433 0.0965 -0.3177 +vn -0.9638 0.0319 -0.2647 +vn -0.9678 0.0158 -0.2513 +vn -0.9797 -0.0514 -0.1938 +vn -0.2838 0.0361 0.9582 +vn -0.3062 0.0093 0.9519 +vn -0.2795 0.0412 0.9593 +vn -0.2583 0.0660 0.9638 +vn 0.9648 -0.0237 0.2621 +vn 0.9524 -0.0650 0.2978 +vn 0.9666 -0.0164 0.2556 +vn 0.9757 0.0265 0.2176 +vn 0.3533 -0.0065 -0.9355 +vn 0.3269 -0.0377 -0.9443 +vn 0.3217 -0.0439 -0.9458 +vn 0.2967 -0.0727 -0.9522 +vn -0.2355 0.1327 -0.9628 +vn -0.4234 -0.0303 -0.9055 +vn -0.4329 -0.0392 -0.9006 +vn -0.5816 -0.1891 -0.7912 +vn -0.9545 0.2271 0.1931 +vn -0.7580 -0.2287 0.6109 +vn 0.4169 0.1894 0.8890 +vn 0.5377 0.0618 0.8409 +vn 0.5667 0.0277 0.8235 +vn 0.6713 -0.1120 0.7327 +vn 0.9118 0.1019 -0.3977 +vn 0.8576 -0.0123 -0.5142 +vn 0.8537 -0.0188 -0.5204 +vn 0.7755 -0.1292 -0.6180 +vn 0.8906 0.0986 0.4440 +vn 0.9138 0.0561 0.4022 +vn 0.9110 0.0618 0.4078 +vn 0.9339 0.0120 0.3573 +vn 0.6523 0.0997 -0.7514 +vn 0.8087 -0.0801 -0.5827 +vn 0.6615 0.0909 -0.7444 +vn 0.4942 0.2324 -0.8377 +vn -0.3440 -0.2150 -0.9140 +vn -0.9136 0.2171 -0.3439 +vn -0.9791 0.0829 -0.1855 +vn -0.9819 0.0737 -0.1745 +vn -0.9958 -0.0890 0.0230 +vn -0.3145 0.1078 0.9431 +vn -0.2198 0.0117 0.9755 +vn -0.2086 0.0006 0.9780 +vn -0.1097 -0.0954 0.9894 +vn 0.6364 0.1326 0.7599 +vn 0.2577 -0.2051 0.9442 +vn -0.7272 0.0369 0.6854 +vn -0.7208 0.0452 0.6916 +vn -0.5784 0.2013 0.7905 +vn -0.8256 -0.1164 0.5521 +vn 0.8167 -0.1144 -0.5656 +vn 0.8276 -0.0920 -0.5537 +vn 0.8322 -0.0822 -0.5484 +vn 0.8415 -0.0613 -0.5367 +vn -0.7728 0.0671 -0.6311 +vn -0.7450 0.0137 -0.6669 +vn -0.7798 0.0819 -0.6206 +vn -0.7998 0.1277 -0.5865 +vn 0.3182 -0.0083 0.9480 +vn 0.3560 0.0350 0.9338 +vn 0.4809 0.1886 0.8563 +vn 0.1755 -0.1611 0.9712 +vn -0.8951 0.0017 0.4458 +vn -0.8964 -0.0007 0.4432 +vn -0.8284 0.1032 0.5506 +vn 0.9177 -0.0360 -0.3957 +vn 0.9440 -0.1650 -0.2858 +vn 0.8916 0.0357 -0.4515 +vn 0.8278 0.1586 -0.5381 +vn -0.6089 -0.0334 -0.7925 +vn -0.4735 -0.1826 -0.8617 +vn -0.6327 -0.0033 -0.7744 +vn -0.7336 0.1454 -0.6639 +vn -0.9386 -0.0989 0.3306 +vn 0.8991 0.0296 0.4368 +vn 0.8909 0.0490 0.4515 +vn 0.9275 -0.0540 0.3700 +vn 0.8492 0.1316 0.5114 +vn 0.1944 -0.0911 0.9767 +vn -0.5722 0.0575 0.8181 +vn -0.5758 0.0538 0.8158 +vn -0.4926 0.1338 0.8599 +vn 0.5279 0.0251 -0.8490 +vn 0.5312 0.0203 -0.8470 +vn 0.5269 0.0264 -0.8495 +vn 0.5238 0.0309 -0.8513 +vn -0.9139 -0.0071 -0.4060 +vn -0.9106 0.0026 -0.4133 +vn -0.9098 0.0048 -0.4149 +vn -0.9064 0.0145 -0.4223 +vn -0.6557 -0.0334 0.7542 +vn 0.7407 0.0780 -0.6673 +vn 0.6910 0.0602 -0.7203 +vn 0.8331 0.1880 -0.5203 +vn 0.8804 0.1485 -0.4505 +vn 0.4562 0.1649 0.8745 +vn 0.4543 0.1587 0.8766 +vn 0.4514 0.1495 0.8797 +vn 0.4582 0.1715 0.8722 +vn 0.5210 -0.1024 -0.8474 +vn -0.2919 0.1135 -0.9497 +vn -0.5027 -0.0389 -0.8636 +vn -0.4773 -0.0192 -0.8785 +vn -0.6474 -0.1617 -0.7448 +vn -0.9574 0.2236 0.1827 +vn -0.7674 -0.2235 0.6009 +vn 0.2768 0.0299 0.9605 +vn 0.3881 0.3300 0.8605 +vn 0.2880 -0.0236 0.9573 +vn 0.3204 -0.0350 0.9466 +vn 0.2851 0.0151 -0.9584 +vn 0.2791 0.0551 -0.9587 +vn 0.5141 0.2917 -0.8066 +vn 0.5024 -0.0190 -0.8644 +vn 0.7324 -0.0307 -0.6801 +vn 0.8635 0.0503 -0.5018 +vn 0.9815 -0.0115 0.1911 +vn 0.9847 -0.0029 0.1742 +vn 0.9834 -0.0064 0.1811 +vn 0.9803 -0.0144 0.1969 +vn 0.4058 -0.0309 0.9134 +vn 0.5715 0.2570 0.7793 +vn -0.1083 -0.6293 -0.7696 +vn -0.4430 -0.8759 -0.1912 +vn -0.3918 -0.9181 0.0594 +vn -0.6235 -0.7129 -0.3209 +vn -0.6203 -0.7376 0.2668 +vn -0.4795 -0.8340 0.2730 +vn -0.6082 -0.7193 -0.3359 +vn -0.6619 -0.5771 -0.4785 +vn -0.6639 -0.6799 0.3113 +vn -0.4806 -0.7989 0.3616 +vn -0.0020 0.9998 0.0186 +vn -0.0062 0.9999 0.0081 +vn 0.0018 1.0000 -0.0003 +vn -0.0391 0.9874 0.1535 +vn -0.0149 0.9996 0.0250 +vn -0.7957 0.5853 -0.1557 +vn -0.7720 0.6199 -0.1402 +vn -0.6918 0.6260 -0.3599 +vn -0.8705 0.4746 0.1306 +vn -0.8440 0.5342 0.0483 +vn -0.7508 0.6496 0.1197 +vn -0.2695 0.1380 -0.9531 +vn -0.2883 -0.2169 -0.9327 +vn -0.2882 -0.2063 -0.9351 +vn -0.2668 0.1627 -0.9499 +vn -0.1335 0.8776 -0.4604 +vn -0.1374 0.8618 -0.4883 +vn -0.1337 0.8766 -0.4622 +vn -0.1377 0.8607 -0.4901 +vn 0.8133 0.2981 -0.4997 +vn 0.7077 0.4643 -0.5324 +vn 0.7935 0.5737 -0.2031 +vn 0.6271 0.5952 -0.5024 +vn 0.5924 0.7833 -0.1886 +vn -0.0739 0.9522 0.2965 +vn -0.2464 0.4998 0.8304 +vn -0.2543 0.4729 0.8436 +vn -0.2472 0.4969 0.8319 +vn -0.2547 0.4714 0.8443 +vn 0.8162 0.5762 -0.0416 +vn 0.9304 0.3551 0.0904 +vn 0.7583 0.6343 -0.1504 +vn 0.7807 0.6095 -0.1378 +vn 0.7696 0.6366 0.0496 +vn 0.6274 0.5432 0.5579 +vn 0.6307 0.5668 0.5301 +vn 0.6310 0.5696 0.5267 +vn 0.6336 0.5965 0.4926 +vn 0.3694 0.6031 0.7070 +vn 0.5173 0.8557 0.0127 +vn 0.6573 0.7416 0.1344 +vn 0.5757 0.8154 0.0610 +vn 0.7212 0.6636 0.1989 +vn 0.6895 0.5475 -0.4743 +vn 0.2418 0.4974 -0.8331 +vn 0.1443 0.8604 0.4888 +vn 0.2844 0.2937 0.9126 +vn 0.2742 0.3706 0.8874 +vn -0.6137 0.7879 0.0502 +vn -0.8169 0.5474 0.1816 +vn -0.0319 0.8553 0.5172 +vn -0.0883 0.5930 -0.8004 +vn -0.2835 0.5482 -0.7869 +vn -0.5806 0.4723 -0.6632 +vn -0.2265 0.1397 0.9639 +vn 0.0128 0.7440 -0.6680 +vn -0.5091 0.7918 -0.3375 +vn -0.5152 0.8126 -0.2725 +vn -0.5203 0.8018 -0.2940 +vn -0.0012 0.7865 -0.6176 +vn 0.0353 0.7832 -0.6208 +vn -0.3922 0.6711 0.6291 +vn -0.3239 0.7305 0.6012 +vn -0.0092 0.8108 0.5852 +vn 0.0348 0.7928 0.6085 +vn -0.4827 0.8385 -0.2530 +vn -0.4943 0.8326 -0.2498 +vn -0.7541 0.6549 -0.0488 +vn -0.7305 0.6820 -0.0358 +vn -0.4439 0.8577 0.2597 +vn -0.4407 0.8581 0.2636 +vn -0.3098 0.8088 -0.4998 +vn -0.1296 0.9910 -0.0349 +vn -0.0569 0.9984 -0.0054 +vn -0.0485 0.9988 -0.0111 +vn -0.3962 0.8819 0.2556 +vn -0.2483 0.8282 0.5024 +vn -0.0059 1.0000 0.0037 +vn 0.0020 1.0000 -0.0088 +vn 0.0482 0.9988 0.0085 +vn -0.0409 0.9987 -0.0318 +vn 0.3619 -0.9322 0.0012 +vn 0.4855 -0.8737 -0.0304 +vn 0.0899 -0.9913 0.0958 +vn 0.0064 -0.8774 0.4797 +vn -0.0030 -0.8278 0.5610 +vn -0.0984 -0.9949 0.0232 +vn -0.1278 -0.9917 0.0147 +vn -0.2213 -0.9733 -0.0606 +vn -0.0566 -0.9939 -0.0943 +vn 0.0087 -0.9948 -0.1015 +vn -0.1429 -0.0641 0.9877 +vn -0.1871 -0.0198 0.9821 +vn -0.0053 -0.1971 0.9804 +vn 0.6643 0.2133 0.7164 +vn 0.9721 -0.2230 -0.0727 +vn 0.8616 0.1271 -0.4913 +vn 0.0746 -0.0490 -0.9960 +vn 0.1806 -0.1494 -0.9721 +vn 0.0562 -0.0316 -0.9979 +vn -0.0677 0.0852 -0.9941 +vn -0.9890 -0.0640 -0.1330 +vn -0.9865 -0.0789 -0.1436 +vn -0.9901 -0.0571 -0.1282 +vn -0.9925 -0.0398 -0.1160 +vn -0.3483 0.1494 0.9254 +vn -0.9026 0.4195 -0.0968 +vn -0.8963 0.4350 -0.0862 +vn -0.8997 0.4267 -0.0919 +vn -0.8905 0.4484 -0.0769 +vn 0.3009 0.5111 -0.8051 +vn 0.7245 -0.0662 0.6861 +vn 0.6259 0.7780 0.0540 +vn 0.0956 0.9948 0.0350 +vn -0.0067 0.9967 -0.0804 +vn 0.0814 0.9961 -0.0328 +vn -0.0509 0.9962 -0.0710 +vn 0.0647 0.9918 0.1101 +vn 0.0451 0.9985 -0.0302 +vn -0.1733 0.2805 0.9441 +vn -0.0804 -0.9967 0.0131 +vn -0.0946 -0.9955 0.0062 +vn -0.1644 -0.9860 -0.0282 +vn -0.1927 -0.9803 -0.0422 +vn 0.0139 -0.9960 -0.0878 +vn 0.4621 -0.8868 -0.0030 +vn 0.5545 -0.8321 -0.0143 +vn 0.1098 -0.9933 0.0356 +vn 0.0760 -0.9963 0.0390 +vn -0.8009 0.2263 0.5544 +vn -0.1723 -0.2924 0.9406 +vn 0.2918 0.1636 0.9424 +vn 0.9968 -0.0789 -0.0129 +vn 0.9970 -0.0761 -0.0151 +vn 0.9967 -0.0804 -0.0118 +vn 0.9964 -0.0839 -0.0091 +vn 0.2358 0.1008 -0.9666 +vn 0.0710 -0.0305 -0.9970 +vn 0.0725 -0.0294 -0.9969 +vn -0.0669 -0.1375 -0.9882 +vn -0.6813 0.1562 -0.7151 +vn -0.9386 -0.2351 -0.2523 +vn -0.8463 -0.0631 0.5289 +vn 0.1918 0.6895 -0.6984 +vn 0.5990 0.7560 0.2640 +vn 0.0094 0.9995 0.0306 +vn 0.0095 0.9995 0.0305 +vn 0.1903 -0.9815 0.0232 +vn 0.0758 -0.9930 0.0904 +vn -0.0616 -0.9707 0.2321 +vn -0.1143 -0.9910 0.0699 +vn -0.1894 -0.9800 -0.0615 +vn -0.0882 -0.9887 -0.1211 +vn 0.0475 -0.9867 -0.1557 +vn 0.1026 -0.9894 -0.1030 +vn -0.0786 -0.1098 0.9908 +vn -0.1629 -0.2195 0.9619 +vn -0.0336 -0.0513 0.9981 +vn 0.0684 0.0816 0.9943 +vn 0.9305 0.0811 0.3571 +vn 0.9819 -0.1065 0.1566 +vn 0.9827 -0.1207 0.1406 +vn 0.9687 -0.2482 -0.0095 +vn 0.7530 0.1820 -0.6323 +vn 0.0620 -0.1527 -0.9863 +vn -0.4057 0.2833 -0.8690 +vn -0.9998 -0.0171 0.0108 +vn -0.9860 -0.1238 -0.1116 +vn -0.9991 0.0104 0.0422 +vn -0.9767 0.1260 0.1737 +vn -0.6857 0.4324 0.5856 +vn 0.1098 -0.6335 -0.7659 +vn -0.3906 0.4844 -0.7828 +vn 0.2976 0.7298 0.6155 +vn 0.3000 0.7332 0.6102 +vn 0.2995 0.7326 0.6113 +vn 0.3021 0.7364 0.6054 +vn -0.0757 0.9938 -0.0813 +vn -0.0462 0.9949 0.0892 +vn -0.0833 0.9931 -0.0828 +vn -0.0644 0.9974 -0.0313 +vn 0.0213 0.9986 -0.0474 +vn 0.0190 0.9991 0.0377 +vn 0.0087 0.9944 0.1056 +vn 0.1414 -0.9895 0.0301 +vn -0.0212 -0.9868 0.1606 +vn -0.2299 -0.9559 0.1829 +vn -0.1471 -0.9890 -0.0144 +vn 0.0003 -0.9857 -0.1687 +vn -0.0794 -0.9894 -0.1212 +vn 0.1044 -0.9883 -0.1109 +vn 0.1354 -0.9883 0.0706 +vn -0.9800 0.1667 0.1085 +vn -0.7263 -0.0179 0.6872 +vn -0.7845 -0.0825 0.6147 +vn -0.7338 -0.0257 0.6789 +vn -0.6503 0.0545 0.7577 +vn 0.4071 -0.0367 0.9127 +vn 0.3986 -0.0473 0.9159 +vn 0.4094 -0.0337 0.9118 +vn 0.4184 -0.0221 0.9080 +vn 0.9898 0.0427 -0.1360 +vn 0.9800 -0.0252 -0.1976 +vn 0.9763 -0.0414 -0.2122 +vn 0.9581 -0.1036 -0.2671 +vn 0.2575 0.1070 -0.9603 +vn 0.1617 0.0341 -0.9862 +vn 0.1725 0.0422 -0.9841 +vn 0.0774 -0.0290 -0.9966 +vn -0.5799 0.1027 -0.8082 +vn -0.7311 -0.0272 -0.6818 +vn -0.7094 -0.0063 -0.7048 +vn -0.8178 -0.1237 -0.5620 +vn -0.1590 0.4965 -0.8533 +vn 0.8800 0.2694 0.3913 +vn -0.5160 0.7407 0.4303 +vn 0.0056 0.9989 0.0459 +vn 0.0315 0.9994 0.0148 +vn -0.0145 0.9992 0.0375 +vn 0.0294 0.9995 0.0078 +vn -0.0452 0.9988 0.0206 +vn -0.0416 0.9991 0.0079 +vn 0.1915 -0.9619 -0.1953 +vn 0.1852 -0.9824 -0.0240 +vn 0.1143 -0.9920 0.0544 +vn 0.0989 -0.9937 0.0529 +vn -0.2385 -0.8970 0.3722 +vn -0.2618 -0.8703 0.4172 +vn -0.1179 -0.9930 0.0084 +vn -0.1582 -0.9773 -0.1409 +vn -0.0072 -0.9876 -0.1569 +vn 0.6404 0.2342 0.7315 +vn 0.8878 -0.1986 0.4152 +vn 0.8562 0.1113 -0.5045 +vn 0.7461 -0.0155 -0.6657 +vn 0.7504 -0.0114 -0.6609 +vn 0.6167 -0.1258 -0.7770 +vn 0.0272 0.2074 -0.9779 +vn -0.6813 -0.2385 -0.6921 +vn -0.9288 0.1764 -0.3259 +vn -0.6605 -0.0600 0.7484 +vn -0.5965 -0.1573 0.7870 +vn -0.5716 -0.1913 0.7979 +vn -0.5180 -0.2589 0.8153 +vn 0.4637 0.8246 0.3241 +vn -0.0191 0.5044 0.8633 +vn -0.8542 0.0930 -0.5116 +vn -0.8377 0.0144 -0.5459 +vn -0.8472 0.0557 -0.5284 +vn -0.8185 -0.0530 -0.5720 +vn 0.9629 0.0689 -0.2609 +vn 0.0624 0.9979 0.0173 +vn -0.0655 0.9958 0.0638 +vn -0.0186 0.9982 -0.0577 +vn 0.0723 -0.9803 -0.1840 +vn 0.1215 -0.9901 -0.0696 +vn 0.2468 -0.9670 0.0640 +vn 0.0851 -0.9941 0.0680 +vn 0.0414 -0.9970 0.0647 +vn -0.2462 -0.7946 0.5549 +vn -0.0769 -0.9950 0.0638 +vn -0.1316 -0.9912 0.0105 +vn -0.2565 -0.9551 -0.1483 +vn -0.0463 -0.9880 -0.1473 +vn 0.9286 -0.2850 0.2377 +vn 0.9361 0.2004 -0.2889 +vn 0.3406 -0.0255 -0.9399 +vn 0.3615 -0.0446 -0.9313 +vn 0.3410 -0.0258 -0.9397 +vn 0.3153 -0.0025 -0.9490 +vn -0.8240 -0.0513 -0.5643 +vn -0.8444 -0.0023 -0.5357 +vn -0.8207 -0.0585 -0.5684 +vn -0.7895 -0.1211 -0.6017 +vn -0.9764 0.1937 0.0957 +vn -0.3503 -0.1512 0.9244 +vn -0.3918 -0.2125 0.8952 +vn -0.3378 -0.1332 0.9318 +vn -0.2729 -0.0426 0.9611 +vn 0.4901 0.1994 0.8485 +vn 0.3173 0.2125 0.9242 +vn 0.5205 0.7814 0.3443 +vn -0.7502 0.5562 -0.3575 +vn -0.9075 0.3304 -0.2594 +vn -0.8391 0.4463 -0.3110 +vn -0.6128 0.6784 -0.4053 +vn 0.7208 0.0061 -0.6931 +vn 0.0824 0.9948 0.0601 +vn 0.4588 0.8855 -0.0739 +vn 0.2383 0.9696 0.0549 +vn 0.0206 0.9993 0.0316 +vn -0.0237 0.9989 0.0393 +vn -0.0158 0.9990 -0.0424 +vn -0.0504 -0.9875 -0.1494 +vn -0.0907 -0.9874 -0.1297 +vn 0.1066 -0.9905 -0.0874 +vn 0.2342 -0.9722 0.0065 +vn 0.0978 -0.9879 0.1203 +vn 0.0005 -0.9752 0.2212 +vn -0.0948 -0.9938 0.0585 +vn -0.0996 -0.9948 0.0223 +vn 0.9856 -0.0443 0.1629 +vn 0.9840 -0.0543 0.1696 +vn 0.9772 -0.0890 0.1927 +vn 0.7116 0.1988 -0.6739 +vn 0.1262 -0.2244 -0.9663 +vn -0.3923 0.1766 -0.9027 +vn -0.9410 -0.2344 -0.2441 +vn -0.9439 0.2354 0.2316 +vn -0.1481 -0.0738 0.9862 +vn -0.1920 -0.1243 0.9735 +vn -0.1295 -0.0526 0.9902 +vn -0.0747 0.0097 0.9972 +vn 0.9895 -0.0155 0.1435 +vn 0.0912 0.3997 0.9121 +vn -0.5940 0.0093 -0.8044 +vn 0.5220 0.8506 -0.0632 +vn 0.0538 0.9984 -0.0163 +vn -0.0545 0.9983 -0.0190 +vn -0.0883 -0.9898 -0.1120 +vn -0.1030 -0.9876 -0.1185 +vn -0.0420 -0.9895 -0.1381 +vn 0.0942 -0.9784 -0.1840 +vn 0.1422 -0.9879 -0.0616 +vn 0.0879 -0.9835 0.1579 +vn 0.1263 -0.9888 0.0800 +vn -0.0010 -0.9922 0.1245 +vn -0.0154 -0.9951 0.0979 +vn -0.5095 -0.8321 0.2191 +vn 0.3831 -0.0083 -0.9237 +vn 0.3902 -0.0164 -0.9206 +vn 0.3838 -0.0091 -0.9234 +vn 0.3757 0.0000 -0.9267 +vn -0.4154 0.1364 -0.8993 +vn -0.5487 0.0093 -0.8360 +vn -0.5452 0.0129 -0.8382 +vn -0.6576 -0.1137 -0.7448 +vn -0.9798 0.0964 0.1751 +vn -0.9586 -0.0039 0.2847 +vn -0.9525 -0.0219 0.3038 +vn -0.9112 -0.1125 0.3963 +vn -0.0756 0.2441 0.9668 +vn 0.0724 0.0953 0.9928 +vn 0.1183 0.0476 0.9918 +vn 0.2672 -0.1126 0.9570 +vn 0.9940 0.0817 0.0730 +vn 0.9895 0.1426 0.0226 +vn 0.9941 0.0693 0.0832 +vn 0.9917 0.0141 0.1279 +vn 0.6694 0.6722 0.3162 +vn 0.3826 -0.4294 0.8181 +vn -0.9316 -0.0630 0.3581 +vn 0.0621 0.5791 -0.8129 +vn -0.1000 0.7381 -0.6672 +vn -0.0730 0.7149 -0.6954 +vn -0.2346 0.8326 -0.5017 +vn 0.0160 0.9984 0.0544 +vn -0.0615 -0.9975 -0.0337 +vn -0.0368 -0.9955 -0.0871 +vn 0.0244 -0.9796 -0.1993 +vn 0.1160 -0.9896 -0.0848 +vn 0.1648 -0.9862 -0.0172 +vn 0.0901 -0.9913 0.0960 +vn 0.0138 -0.9782 0.2073 +vn -0.0466 -0.9906 0.1284 +vn -0.0532 -0.9939 0.0970 +vn -0.5663 -0.8239 0.0217 +vn 0.1468 -0.0186 -0.9890 +vn 0.1869 -0.0726 -0.9797 +vn 0.1250 0.0104 -0.9921 +vn 0.0796 0.0701 -0.9944 +vn -0.9975 0.0258 -0.0660 +vn -0.9993 -0.0227 -0.0286 +vn -0.9989 -0.0446 -0.0117 +vn -0.9961 -0.0857 0.0202 +vn -0.3834 0.1457 0.9120 +vn 0.0027 -0.1949 0.9808 +vn 0.6730 0.1831 0.7167 +vn 0.9992 -0.0277 -0.0285 +vn 0.9851 -0.1358 0.1051 +vn 0.9992 -0.0236 -0.0335 +vn 0.9765 0.1039 -0.1887 +vn 0.9154 0.3986 0.0567 +vn -0.0688 0.5637 0.8231 +vn 0.2443 0.8371 0.4895 +vn -0.8755 0.4511 0.1733 +vn -0.1328 0.3984 -0.9076 +vn -0.2437 0.6112 -0.7530 +vn -0.1903 0.5103 -0.8387 +vn -0.3070 0.7263 -0.6151 +vn -0.0260 0.9996 0.0081 +vn 0.0545 0.9982 0.0244 +vn -0.1613 -0.9829 -0.0890 +vn -0.2373 -0.9677 -0.0848 +vn -0.0548 -0.9920 -0.1141 +vn 0.0581 -0.9863 -0.1547 +vn 0.1101 -0.9910 -0.0765 +vn 0.1108 -0.9889 0.0994 +vn 0.1488 -0.9824 0.1128 +vn -0.0227 -0.9957 0.0902 +vn -0.0413 -0.9971 0.0641 +vn 0.1733 0.0082 -0.9848 +vn 0.1898 0.0284 -0.9814 +vn 0.1188 -0.0577 -0.9912 +vn -0.9411 0.0406 -0.3357 +vn -0.9553 0.1027 -0.2772 +vn -0.9389 0.0331 -0.3426 +vn -0.9206 -0.0199 -0.3901 +vn -0.7855 -0.1753 0.5935 +vn -0.4930 0.1741 0.8524 +vn 0.4582 0.0351 0.8882 +vn 0.3041 -0.0814 0.9492 +vn 0.4523 0.0305 0.8913 +vn 0.5891 0.1462 0.7947 +vn 0.9963 -0.0515 -0.0694 +vn 0.9850 -0.1647 0.0513 +vn 0.9962 -0.0479 -0.0731 +vn 0.9716 0.0923 -0.2179 +vn 0.2484 0.1016 -0.9633 +vn 0.8710 0.4255 -0.2456 +vn 0.9625 -0.2582 0.0831 +vn -0.2183 0.4841 0.8473 +vn -0.8325 0.4182 -0.3634 +vn -0.7663 0.6109 -0.1991 +vn -0.8024 0.5300 -0.2742 +vn -0.6759 0.7347 -0.0583 +vn 0.0027 0.9994 -0.0334 +vn -0.0328 0.9983 0.0485 +vn -0.2458 -0.9587 0.1434 +vn -0.0386 -0.9869 0.1569 +vn -0.1308 -0.9905 -0.0433 +vn -0.0158 -0.9888 -0.1484 +vn 0.0306 -0.9876 -0.1541 +vn 0.1219 -0.9907 0.0602 +vn 0.1336 -0.9906 0.0291 +vn -0.6164 0.0131 -0.7873 +vn -0.5931 -0.0235 -0.8048 +vn -0.6238 0.0252 -0.7812 +vn -0.6452 0.0616 -0.7615 +vn -0.9135 -0.0076 0.4069 +vn -0.9039 0.0189 0.4272 +vn -0.9158 -0.0147 0.4014 +vn -0.9248 -0.0442 0.3779 +vn 0.1410 0.0570 0.9884 +vn 0.2940 -0.0814 0.9523 +vn 0.3165 -0.1025 0.9430 +vn 0.4198 -0.2020 0.8849 +vn 0.8833 0.2515 0.3957 +vn 0.7713 -0.0891 -0.6302 +vn 0.7996 -0.1514 -0.5812 +vn 0.7559 -0.0592 -0.6521 +vn 0.7100 0.0191 -0.7039 +vn 0.4870 0.4710 -0.7355 +vn 0.4867 0.4714 -0.7355 +vn 0.4869 0.4712 -0.7355 +vn 0.4865 0.4716 -0.7354 +vn -0.0174 -0.1439 0.9894 +vn -0.3908 0.7059 0.5908 +vn -0.8395 0.3891 -0.3793 +vn -0.0218 0.9996 0.0202 +vn -0.0022 0.9995 -0.0319 +vn -0.1882 -0.9817 -0.0290 +vn -0.2216 -0.9749 -0.0191 +vn -0.1140 -0.9897 -0.0872 +vn -0.0266 -0.9812 -0.1909 +vn 0.0618 -0.9869 -0.1493 +vn 0.1586 -0.9841 0.0806 +vn 0.1489 -0.9887 -0.0145 +vn 0.0298 -0.9940 0.1056 +vn -0.0041 -0.9959 0.0904 +vn -0.9807 0.0327 0.1929 +vn -0.9948 -0.0969 0.0318 +vn -0.9758 0.0494 0.2131 +vn -0.9209 0.1666 0.3523 +vn -0.3463 -0.2135 0.9135 +vn 0.1376 0.1153 0.9837 +vn 0.8552 0.0441 0.5164 +vn 0.7845 -0.0679 0.6164 +vn 0.8607 0.0547 0.5061 +vn 0.9073 0.1713 0.3839 +vn 0.7532 0.0227 -0.6574 +vn 0.7904 -0.0328 -0.6117 +vn 0.7458 0.0329 -0.6653 +vn 0.7012 0.0901 -0.7072 +vn -0.4694 0.0132 -0.8829 +vn -0.3297 -0.1287 -0.9353 +vn -0.4877 0.0333 -0.8724 +vn -0.5990 0.1672 -0.7831 +vn -0.8491 0.3870 -0.3597 +vn 0.0390 0.7675 -0.6398 +vn 0.6230 0.0679 -0.7793 +vn -0.0494 0.3577 0.9325 +vn -0.0538 0.3496 0.9353 +vn -0.0511 0.3546 0.9336 +vn -0.0571 0.3433 0.9375 +vn 0.0049 -1.0000 -0.0051 +vn 0.0145 -0.9999 -0.0059 +vn 0.0184 -0.9996 -0.0216 +vn -0.0005 -1.0000 -0.0009 +vn 0.0010 -1.0000 -0.0015 +vn 0.0002 -1.0000 -0.0049 +vn 0.0198 -0.9996 -0.0212 +vn -0.0036 -0.9997 -0.0256 +vn -0.0138 -0.9999 -0.0059 +vn -0.0149 -0.9999 -0.0022 +vn -0.0061 -1.0000 0.0078 +vn -0.3669 0.0239 0.9299 +vn -0.3725 0.0132 0.9280 +vn -0.3615 0.0343 0.9317 +vn -0.3571 0.0427 0.9331 +vn 0.7546 -0.0694 0.6525 +vn 0.7148 -0.1533 0.6823 +vn 0.7954 0.0400 0.6048 +vn 0.8167 0.1175 0.5649 +vn 0.8639 -0.0668 -0.4992 +vn 0.8855 -0.1798 -0.4285 +vn 0.8142 0.0776 -0.5754 +vn 0.7638 0.1800 -0.6198 +vn 0.0280 -0.2334 -0.9720 +vn -0.3914 0.1892 -0.9005 +vn -0.7125 -0.1737 -0.6799 +vn -0.9905 0.1361 -0.0175 +vn -0.9977 0.0440 0.0516 +vn -0.9931 -0.0372 0.1115 +vn -0.9713 -0.1443 0.1893 +vn -0.3702 0.0299 0.9285 +vn -0.0851 -0.0271 0.9960 +vn -0.3117 0.0178 0.9500 +vn -0.0371 -0.0363 0.9987 +vn 0.5520 0.0410 0.8328 +vn 0.9996 -0.0193 -0.0216 +vn 0.9997 -0.0244 -0.0008 +vn 0.9997 -0.0237 -0.0039 +vn 0.9995 -0.0181 -0.0265 +vn 0.6172 0.0359 -0.7860 +vn -0.3117 0.0202 -0.9500 +vn 0.0371 -0.0476 -0.9982 +vn -0.0160 -0.0376 -0.9992 +vn -0.3837 0.0349 -0.9228 +vn -0.9930 0.0069 -0.1179 +vn -0.9996 -0.0207 -0.0168 +vn -0.9954 0.0007 -0.0955 +vn -0.9997 -0.0255 0.0010 +vn 0.0014 1.0000 -0.0012 +vn 0.0003 0.9994 -0.0341 +vn 0.0044 1.0000 -0.0073 +vn 0.0053 1.0000 -0.0009 +vn 0.0090 0.9999 -0.0064 +vn 0.0104 0.9997 -0.0200 +vn 0.5829 -0.7738 -0.2479 +vn -0.5831 -0.7736 0.2479 +vn -0.6051 -0.6796 0.4146 +vn -0.6023 -0.7021 0.3799 +vn 0.5178 -0.2137 -0.8284 +vn 0.9284 -0.3187 0.1910 +vn 0.2828 0.1856 0.9410 +vn -0.5943 -0.4820 0.6438 +vn -0.8731 0.1447 -0.4656 +s 1 +f 1/1/1 2/2/1 3/3/1 +f 1/1/1 3/3/1 4/4/1 +f 5/5/2 6/6/3 7/7/4 +f 8/8/5 9/9/6 10/10/7 +f 10/10/7 9/9/6 11/11/8 +f 12/12/9 13/13/10 14/14/11 +f 15/15/12 16/16/13 17/17/14 +f 18/18/1 19/19/1 20/20/1 +f 21/21/15 20/20/1 22/22/16 +f 23/23/17 24/24/18 25/25/19 +f 25/25/19 24/24/18 19/19/1 +f 21/21/15 26/26/1 14/14/11 +f 21/21/15 27/27/20 26/26/1 +f 14/14/11 26/26/1 12/12/9 +f 28/28/21 12/12/9 29/29/22 +f 28/28/21 29/29/22 23/23/17 +f 29/29/22 27/27/20 23/23/17 +f 30/30/23 31/31/24 32/32/25 +f 8/8/5 33/33/26 31/31/24 +f 8/8/5 31/31/24 34/34/27 +f 10/10/7 35/35/28 8/8/5 +f 35/35/28 33/33/26 8/8/5 +f 34/34/27 31/31/24 30/30/23 +f 33/33/26 35/35/28 36/36/29 +f 36/36/29 37/37/30 33/33/26 +f 11/11/31 38/38/31 39/39/31 +f 11/11/32 13/13/10 12/12/9 +f 11/11/32 12/12/9 28/28/21 +f 11/11/32 28/28/21 38/38/33 +f 7/7/4 39/39/34 5/5/2 +f 5/5/2 40/40/35 16/16/13 +f 18/18/1 16/16/13 19/19/1 +f 19/19/1 16/16/13 25/25/19 +f 25/25/19 16/16/13 40/40/35 +f 17/17/14 41/41/36 15/15/12 +f 42/42/37 41/41/36 43/43/38 +f 41/41/36 44/44/39 45/45/40 +f 41/41/36 45/45/40 15/15/12 +f 42/42/37 46/46/41 47/47/42 +f 48/48/43 49/49/44 43/43/38 +f 42/42/37 47/47/42 41/41/36 +f 47/47/42 44/44/39 41/41/36 +f 46/46/41 42/42/37 50/50/45 +f 44/44/39 47/47/42 51/51/46 +f 44/44/39 51/51/46 52/52/47 +f 43/43/38 41/41/36 48/48/43 +f 14/14/11 53/53/48 21/21/15 +f 34/34/27 54/54/49 14/14/11 +f 14/14/11 54/54/49 53/53/48 +f 53/53/48 54/54/49 55/55/50 +f 21/21/15 18/18/1 20/20/1 +f 8/8/5 34/34/27 14/14/11 +f 27/27/20 21/21/15 22/22/16 +f 27/27/20 22/22/16 23/23/17 +f 23/23/17 22/22/16 24/24/18 +f 56/56/51 57/57/52 58/58/53 +f 56/56/51 58/58/53 59/59/54 +f 59/59/54 58/58/53 60/60/55 +f 61/61/56 62/62/57 57/57/52 +f 61/61/56 57/57/52 56/56/51 +f 63/63/58 64/64/59 61/61/56 +f 61/61/56 64/64/59 62/62/57 +f 65/65/60 66/66/61 63/63/58 +f 63/63/58 66/66/61 64/64/59 +f 65/65/60 60/60/55 66/66/61 +f 59/59/54 60/60/55 65/65/60 +f 67/67/62 68/68/63 69/69/64 +f 67/67/62 70/70/65 71/71/66 +f 67/67/62 69/69/64 70/70/65 +f 72/72/67 73/73/68 74/74/69 +f 72/72/67 74/74/69 70/70/65 +f 70/70/65 74/74/69 71/71/66 +f 68/68/70 75/75/71 76/76/72 +f 68/68/70 76/76/72 77/77/73 +f 68/68/70 77/77/73 69/69/74 +f 69/69/75 77/77/76 78/78/77 +f 69/69/75 78/78/77 70/70/78 +f 70/70/79 78/78/80 72/72/81 +f 72/72/81 78/78/80 79/79/82 +f 72/72/83 79/79/83 73/73/83 +f 73/73/84 79/79/85 80/80/86 +f 80/80/86 81/81/87 73/73/84 +f 76/76/88 75/75/89 82/82/90 +f 76/76/88 82/82/90 83/83/91 +f 84/84/92 83/83/91 82/82/90 +f 85/85/93 83/83/91 84/84/92 +f 83/83/91 85/85/93 86/86/94 +f 87/87/95 86/86/94 85/85/93 +f 88/88/96 89/89/97 90/90/98 +f 88/88/96 90/90/98 91/91/99 +f 88/88/96 91/91/99 92/92/100 +f 93/93/101 92/92/100 91/91/99 +f 92/92/100 93/93/101 80/80/86 +f 80/80/86 93/93/101 81/81/87 +f 48/48/102 94/94/103 95/95/104 +f 95/95/104 94/94/103 96/96/105 +f 95/95/106 96/96/107 97/97/108 +f 95/95/106 97/97/108 98/98/109 +f 94/94/110 48/48/111 99/99/112 +f 99/99/112 48/48/111 100/100/113 +f 99/99/114 100/100/115 101/101/116 +f 101/101/116 100/100/115 102/102/117 +f 101/101/118 102/102/119 97/97/120 +f 97/97/120 102/102/119 98/98/121 +f 103/103/122 84/84/122 50/50/122 +f 84/84/123 103/103/123 104/104/123 +f 84/84/124 104/104/124 49/49/124 +f 103/103/125 50/50/126 105/105/127 +f 105/105/127 50/50/126 42/42/128 +f 105/105/129 42/42/130 43/43/131 +f 105/105/129 43/43/131 106/106/132 +f 106/106/133 43/43/133 49/49/133 +f 106/106/134 49/49/134 104/104/134 +f 51/51/135 107/107/136 108/108/137 +f 109/109/138 108/108/137 107/107/136 +f 108/108/139 109/109/140 46/46/141 +f 46/46/141 109/109/140 110/110/142 +f 107/107/143 51/51/144 47/47/145 +f 107/107/143 47/47/145 111/111/146 +f 111/111/147 47/47/147 110/110/147 +f 110/110/148 47/47/148 46/46/148 +f 15/15/149 112/112/149 113/113/149 +f 113/113/150 112/112/150 114/114/150 +f 114/114/151 52/52/151 113/113/151 +f 115/115/152 52/52/152 114/114/152 +f 112/112/153 15/15/154 116/116/155 +f 116/116/155 15/15/154 45/45/156 +f 116/116/157 45/45/158 117/117/159 +f 117/117/159 45/45/158 44/44/160 +f 117/117/161 44/44/161 115/115/161 +f 115/115/162 44/44/162 52/52/162 +f 118/118/163 18/18/164 41/41/165 +f 118/118/166 41/41/167 119/119/168 +f 119/119/168 41/41/167 17/17/169 +f 119/119/170 17/17/171 16/16/172 +f 119/119/170 16/16/172 120/120/173 +f 120/120/174 16/16/175 18/18/176 +f 120/120/174 18/18/176 121/121/177 +f 121/121/178 18/18/164 118/118/163 +f 122/122/179 19/19/180 123/123/181 +f 123/123/181 19/19/180 24/24/182 +f 123/123/183 24/24/184 22/22/185 +f 123/123/183 22/22/185 124/124/186 +f 124/124/187 22/22/188 20/20/189 +f 124/124/187 20/20/189 125/125/190 +f 125/125/191 20/20/192 122/122/193 +f 122/122/193 20/20/192 19/19/194 +f 126/126/195 27/27/196 127/127/197 +f 127/127/197 27/27/196 29/29/198 +f 127/127/199 29/29/199 128/128/199 +f 128/128/200 29/29/200 12/12/200 +f 128/128/201 12/12/202 129/129/203 +f 129/129/203 12/12/202 26/26/204 +f 129/129/205 26/26/206 126/126/207 +f 126/126/207 26/26/206 27/27/208 +f 4/4/209 9/9/210 1/1/211 +f 9/9/210 8/8/212 1/1/211 +f 1/1/213 8/8/214 14/14/215 +f 1/1/213 14/14/215 2/2/216 +f 2/2/217 14/14/217 13/13/217 +f 2/2/218 13/13/219 3/3/220 +f 13/13/219 11/11/221 3/3/220 +f 3/3/222 11/11/223 4/4/224 +f 4/4/224 11/11/223 9/9/225 +f 36/36/226 130/130/226 131/131/226 +f 36/36/227 131/131/227 132/132/227 +f 133/133/228 132/132/229 131/131/230 +f 133/133/228 10/10/231 132/132/229 +f 130/130/232 36/36/233 134/134/234 +f 134/134/234 36/36/233 35/35/235 +f 134/134/236 35/35/237 10/10/238 +f 134/134/236 10/10/238 133/133/239 +f 135/135/240 32/32/241 136/136/242 +f 37/37/243 32/32/241 135/135/240 +f 137/137/244 37/37/245 135/135/246 +f 136/136/247 32/32/248 31/31/249 +f 136/136/247 31/31/249 138/138/250 +f 138/138/251 31/31/252 33/33/253 +f 138/138/251 33/33/253 137/137/254 +f 137/137/244 33/33/255 37/37/245 +f 139/139/256 140/140/257 55/55/258 +f 141/141/259 140/140/257 139/139/256 +f 141/141/260 30/30/260 140/140/260 +f 142/142/261 30/30/262 141/141/263 +f 139/139/264 55/55/265 54/54/266 +f 139/139/264 54/54/266 143/143/267 +f 143/143/268 54/54/269 142/142/270 +f 142/142/270 54/54/269 34/34/271 +f 142/142/261 34/34/272 30/30/262 +f 134/134/1 133/133/1 130/130/1 +f 144/144/273 145/145/274 146/146/275 +f 144/144/273 146/146/275 89/89/276 +f 147/147/277 89/89/278 146/146/279 +f 147/147/277 53/53/280 89/89/278 +f 145/145/274 144/144/273 148/148/281 +f 145/145/282 148/148/283 149/149/284 +f 149/149/284 148/148/283 21/21/285 +f 149/149/286 21/21/286 147/147/286 +f 147/147/287 21/21/287 53/53/287 +f 67/67/288 150/150/289 75/75/71 +f 67/67/288 75/75/71 68/68/70 +f 150/150/289 67/67/288 151/151/290 +f 60/60/291 150/150/289 151/151/290 +f 152/152/292 74/74/293 153/153/294 +f 73/73/84 81/81/87 74/74/293 +f 74/74/293 81/81/87 153/153/294 +f 152/152/292 153/153/294 62/62/295 +f 62/62/295 153/153/294 57/57/296 +f 57/57/296 153/153/294 154/154/297 +f 57/57/298 154/154/299 155/155/300 +f 57/57/298 155/155/300 58/58/301 +f 58/58/302 155/155/303 150/150/289 +f 58/58/302 150/150/289 60/60/291 +f 152/152/304 62/62/304 64/64/304 +f 74/74/69 152/152/305 156/156/306 +f 74/74/69 156/156/306 71/71/66 +f 71/71/66 156/156/306 67/67/62 +f 152/152/305 157/157/307 156/156/306 +f 156/156/306 157/157/308 151/151/309 +f 156/156/306 151/151/309 67/67/62 +f 152/152/305 64/64/310 157/157/307 +f 64/64/310 66/66/311 157/157/307 +f 157/157/308 66/66/312 151/151/309 +f 151/151/309 66/66/312 60/60/313 +f 158/158/314 159/159/315 160/160/316 +f 160/160/316 159/159/315 161/161/317 +f 161/161/317 159/159/315 162/162/318 +f 5/5/319 159/159/320 163/163/321 +f 5/5/319 39/39/322 164/164/323 +f 5/5/319 164/164/323 159/159/320 +f 164/164/323 162/162/324 159/159/320 +f 40/40/325 5/5/326 163/163/327 +f 165/165/328 40/40/325 163/163/327 +f 165/165/329 163/163/330 158/158/331 +f 158/158/331 163/163/330 159/159/332 +f 39/39/322 162/162/324 164/164/323 +f 25/25/333 40/40/334 166/166/335 +f 40/40/334 165/165/336 166/166/335 +f 166/166/335 165/165/336 158/158/337 +f 161/161/317 162/162/318 167/167/338 +f 167/167/339 162/162/340 38/38/341 +f 38/38/341 162/162/340 39/39/342 +f 23/23/343 25/25/344 166/166/335 +f 28/28/345 23/23/343 161/161/346 +f 23/23/343 160/160/347 161/161/346 +f 23/23/343 166/166/335 160/160/347 +f 166/166/335 158/158/337 160/160/347 +f 38/38/348 28/28/349 167/167/350 +f 28/28/349 161/161/351 167/167/350 +f 104/104/1 103/103/1 105/105/1 +f 107/107/1 111/111/1 110/110/1 +f 110/110/1 109/109/1 107/107/1 +f 114/114/1 112/112/1 115/115/1 +f 115/115/1 112/112/1 116/116/1 +f 117/117/1 115/115/1 116/116/1 +f 120/120/1 118/118/1 119/119/1 +f 120/120/1 121/121/1 118/118/1 +f 125/125/1 122/122/1 123/123/1 +f 123/123/1 124/124/1 125/125/1 +f 129/129/1 127/127/1 128/128/1 +f 126/126/1 127/127/1 129/129/1 +f 56/56/51 65/65/60 61/61/56 +f 61/61/56 65/65/60 63/63/58 +f 59/59/54 65/65/60 56/56/51 +f 150/150/289 155/155/303 6/6/352 +f 7/7/353 6/6/354 154/154/355 +f 154/154/355 6/6/354 155/155/356 +f 154/154/357 153/153/357 7/7/357 +f 10/10/7 11/11/8 7/7/4 +f 11/11/8 39/39/34 7/7/4 +f 7/7/4 132/132/358 10/10/7 +f 132/132/358 7/7/4 153/153/294 +f 132/132/358 153/153/294 81/81/87 +f 6/6/3 15/15/12 113/113/359 +f 6/6/3 5/5/2 16/16/13 +f 6/6/3 16/16/13 15/15/12 +f 113/113/360 75/75/361 6/6/352 +f 6/6/352 75/75/361 150/150/289 +f 87/87/95 89/89/97 86/86/94 +f 88/88/96 86/86/94 89/89/97 +f 98/98/362 87/87/95 95/95/363 +f 52/52/47 51/51/46 108/108/364 +f 37/37/365 93/93/101 32/32/366 +f 91/91/99 90/90/98 140/140/367 +f 87/87/95 85/85/93 95/95/363 +f 82/82/90 75/75/89 108/108/368 +f 81/81/369 93/93/101 37/37/365 +f 93/93/101 91/91/99 32/32/366 +f 32/32/366 91/91/99 140/140/367 +f 140/140/370 90/90/371 55/55/372 +f 132/132/373 81/81/369 36/36/374 +f 84/84/375 82/82/376 50/50/45 +f 52/52/47 75/75/377 113/113/378 +f 90/90/371 89/89/379 53/53/380 +f 89/89/381 87/87/95 144/144/382 +f 144/144/382 87/87/95 98/98/362 +f 95/95/383 85/85/384 48/48/43 +f 81/81/369 37/37/365 36/36/374 +f 32/32/366 140/140/367 30/30/385 +f 55/55/372 90/90/371 53/53/380 +f 144/144/386 98/98/387 148/148/388 +f 48/48/43 85/85/384 84/84/389 +f 48/48/43 84/84/389 49/49/44 +f 82/82/376 108/108/390 50/50/45 +f 50/50/45 108/108/390 46/46/41 +f 108/108/364 75/75/377 52/52/47 +f 130/130/1 133/133/1 131/131/1 +f 138/138/1 137/137/1 136/136/1 +f 136/136/1 137/137/1 135/135/1 +f 143/143/1 142/142/1 139/139/1 +f 141/141/1 139/139/1 142/142/1 +f 146/146/1 149/149/1 147/147/1 +f 145/145/1 149/149/1 146/146/1 +f 96/96/1 94/94/1 99/99/1 +f 96/96/1 99/99/1 97/97/1 +f 99/99/1 101/101/1 97/97/1 +f 104/104/1 105/105/1 106/106/1 +f 21/21/15 102/102/391 100/100/392 +f 41/41/36 100/100/392 48/48/43 +f 18/18/1 21/21/15 41/41/36 +f 102/102/391 148/148/388 98/98/387 +f 148/148/388 102/102/391 21/21/15 +f 41/41/36 21/21/15 100/100/392 +f 168/168/393 169/169/393 170/170/393 +f 170/170/394 171/171/394 172/172/394 +f 173/173/395 174/174/396 175/175/397 +f 173/173/395 175/175/397 176/176/398 +f 176/176/398 175/175/397 177/177/399 +f 176/176/400 177/177/401 178/178/402 +f 178/178/402 177/177/401 179/179/403 +f 178/178/402 179/179/403 174/174/404 +f 168/168/405 177/177/406 175/175/407 +f 168/168/408 175/175/408 169/169/408 +f 169/169/409 175/175/409 174/174/409 +f 169/169/410 174/174/410 170/170/410 +f 170/170/411 174/174/412 179/179/413 +f 170/170/411 179/179/413 171/171/414 +f 171/171/415 179/179/416 177/177/417 +f 171/171/415 177/177/417 172/172/418 +f 172/172/419 177/177/406 168/168/405 +f 168/168/420 170/170/421 180/180/422 +f 180/180/422 170/170/421 181/181/423 +f 172/172/424 168/168/424 180/180/424 +f 170/170/425 172/172/425 181/181/425 +f 181/181/426 172/172/426 180/180/426 +f 182/182/427 183/183/428 184/184/429 +f 184/184/429 183/183/428 185/185/430 +f 184/184/429 186/186/431 182/182/427 +f 185/185/432 187/187/432 186/186/432 +f 188/188/433 189/189/433 190/190/433 +f 188/188/434 190/190/435 191/191/436 +f 191/191/436 190/190/435 192/192/437 +f 192/192/438 193/193/438 194/194/438 +f 194/194/439 193/193/440 189/189/441 +f 194/194/439 189/189/441 188/188/442 +f 182/182/443 190/190/443 183/183/443 +f 183/183/444 190/190/444 189/189/444 +f 183/183/445 189/189/445 185/185/445 +f 185/185/446 189/189/447 193/193/448 +f 185/185/446 193/193/448 187/187/449 +f 187/187/450 193/193/451 186/186/452 +f 186/186/452 193/193/451 192/192/453 +f 186/186/454 192/192/454 182/182/454 +f 182/182/455 192/192/455 190/190/455 +f 185/185/456 186/186/456 195/195/456 +f 184/184/457 185/185/457 195/195/457 +f 186/186/458 184/184/458 195/195/458 +f 196/196/459 197/197/460 198/198/460 +f 198/198/460 197/197/460 199/199/460 +f 200/200/461 201/201/462 202/202/463 +f 202/202/463 201/201/462 203/203/464 +f 202/202/463 203/203/464 204/204/465 +f 204/204/465 203/203/464 205/205/466 +f 204/204/465 205/205/466 206/206/467 +f 206/206/467 205/205/466 207/207/468 +f 206/206/467 207/207/468 200/200/461 +f 200/200/461 207/207/468 201/201/462 +f 196/196/469 203/203/470 201/201/471 +f 196/196/469 201/201/471 197/197/472 +f 197/197/473 201/201/474 199/199/475 +f 199/199/475 201/201/474 207/207/476 +f 199/199/477 207/207/477 208/208/477 +f 208/208/478 207/207/478 205/205/478 +f 208/208/479 205/205/479 198/198/479 +f 198/198/480 205/205/481 203/203/482 +f 198/198/480 203/203/482 196/196/483 +f 199/199/484 208/208/484 209/209/484 +f 198/198/485 199/199/485 210/210/485 +f 210/210/486 199/199/486 209/209/486 +f 208/208/487 198/198/488 209/209/489 +f 209/209/489 198/198/488 210/210/490 +f 211/211/491 212/212/492 213/213/493 +f 214/214/494 215/215/494 216/216/494 +f 216/216/495 217/217/496 211/211/491 +f 216/216/495 211/211/491 213/213/493 +f 213/213/493 212/212/492 214/214/497 +f 218/218/498 219/219/499 220/220/500 +f 220/220/500 219/219/499 221/221/501 +f 220/220/500 221/221/501 222/222/502 +f 222/222/502 221/221/501 223/223/503 +f 222/222/502 223/223/503 224/224/504 +f 222/222/502 224/224/504 218/218/498 +f 218/218/498 224/224/504 225/225/505 +f 218/218/498 225/225/505 219/219/499 +f 215/215/506 221/221/506 216/216/506 +f 216/216/507 221/221/508 219/219/509 +f 216/216/507 219/219/509 217/217/510 +f 217/217/511 219/219/512 225/225/513 +f 217/217/511 225/225/513 211/211/514 +f 211/211/515 225/225/516 212/212/517 +f 212/212/517 225/225/516 224/224/518 +f 212/212/519 224/224/520 214/214/521 +f 214/214/521 224/224/520 223/223/522 +f 214/214/523 223/223/524 215/215/525 +f 215/215/525 223/223/524 221/221/526 +f 216/216/527 213/213/527 226/226/527 +f 214/214/528 216/216/528 226/226/528 +f 213/213/529 214/214/529 226/226/529 +f 227/227/530 228/228/531 229/229/532 +f 229/229/532 228/228/531 230/230/533 +f 229/229/532 231/231/534 227/227/530 +f 229/229/532 232/232/535 231/231/534 +f 233/233/536 234/234/537 235/235/538 +f 233/233/536 235/235/538 236/236/539 +f 236/236/540 235/235/541 237/237/542 +f 236/236/540 237/237/542 238/238/543 +f 238/238/543 237/237/542 239/239/544 +f 238/238/543 239/239/544 233/233/536 +f 233/233/536 239/239/544 234/234/537 +f 227/227/545 235/235/545 228/228/545 +f 228/228/546 235/235/546 234/234/546 +f 228/228/547 234/234/548 230/230/549 +f 230/230/549 234/234/548 239/239/550 +f 230/230/551 239/239/551 232/232/551 +f 232/232/552 239/239/552 237/237/552 +f 232/232/553 237/237/553 231/231/553 +f 231/231/554 237/237/555 227/227/556 +f 227/227/556 237/237/555 235/235/557 +f 240/240/558 232/232/558 241/241/558 +f 230/230/559 232/232/559 240/240/559 +f 229/229/560 230/230/561 241/241/562 +f 241/241/562 230/230/561 240/240/563 +f 232/232/564 229/229/564 241/241/564 +f 242/242/565 243/243/565 244/244/565 +f 245/245/566 246/246/566 244/244/566 +f 243/243/567 247/247/567 245/245/567 +f 248/248/568 249/249/569 250/250/570 +f 250/250/570 249/249/569 251/251/571 +f 250/250/570 251/251/571 252/252/572 +f 252/252/573 251/251/573 253/253/573 +f 252/252/574 253/253/575 254/254/576 +f 254/254/576 253/253/575 255/255/577 +f 254/254/576 255/255/577 248/248/568 +f 248/248/568 255/255/577 249/249/569 +f 242/242/578 251/251/578 249/249/578 +f 242/242/579 249/249/579 243/243/579 +f 243/243/580 249/249/581 255/255/582 +f 243/243/580 255/255/582 247/247/583 +f 247/247/584 255/255/585 253/253/586 +f 247/247/584 253/253/586 245/245/587 +f 245/245/588 253/253/588 246/246/588 +f 246/246/589 253/253/590 251/251/591 +f 246/246/589 251/251/591 244/244/592 +f 244/244/593 251/251/593 242/242/593 +f 243/243/594 245/245/594 256/256/594 +f 256/256/595 245/245/595 257/257/595 +f 244/244/596 243/243/597 256/256/598 +f 257/257/599 244/244/596 256/256/598 +f 245/245/600 244/244/600 257/257/600 +f 258/258/601 259/259/602 260/260/603 +f 259/259/604 261/261/604 262/262/604 +f 262/262/605 263/263/606 258/258/601 +f 262/262/605 258/258/601 260/260/603 +f 264/264/607 265/265/608 266/266/609 +f 264/264/607 266/266/609 267/267/610 +f 267/267/610 266/266/609 268/268/611 +f 267/267/610 268/268/611 269/269/612 +f 269/269/612 268/268/611 270/270/613 +f 269/269/612 270/270/613 271/271/614 +f 271/271/614 270/270/613 264/264/607 +f 264/264/607 270/270/613 265/265/608 +f 261/261/615 266/266/616 262/262/617 +f 262/262/618 266/266/618 263/263/618 +f 263/263/619 266/266/619 265/265/619 +f 263/263/620 265/265/620 258/258/620 +f 258/258/621 265/265/621 270/270/621 +f 258/258/622 270/270/622 259/259/622 +f 259/259/623 270/270/624 268/268/625 +f 259/259/623 268/268/625 261/261/626 +f 261/261/615 268/268/627 266/266/616 +f 262/262/628 260/260/628 272/272/628 +f 259/259/629 262/262/629 272/272/629 +f 260/260/603 259/259/602 272/272/630 +f 273/273/631 274/274/631 275/275/631 +f 275/275/632 276/276/632 277/277/632 +f 278/278/633 279/279/634 280/280/635 +f 278/278/633 280/280/635 281/281/636 +f 281/281/636 280/280/635 282/282/637 +f 281/281/636 282/282/637 283/283/638 +f 283/283/638 282/282/637 284/284/639 +f 283/283/638 284/284/639 285/285/640 +f 283/283/638 285/285/640 278/278/641 +f 278/278/642 285/285/642 279/279/642 +f 274/274/643 282/282/644 280/280/645 +f 274/274/643 280/280/645 275/275/646 +f 275/275/647 280/280/648 276/276/649 +f 276/276/649 280/280/648 279/279/650 +f 276/276/651 279/279/652 277/277/653 +f 277/277/653 279/279/652 285/285/654 +f 277/277/655 285/285/656 273/273/657 +f 273/273/657 285/285/656 284/284/658 +f 273/273/659 284/284/660 282/282/661 +f 273/273/659 282/282/661 274/274/662 +f 275/275/663 277/277/663 286/286/663 +f 286/286/664 277/277/664 287/287/664 +f 273/273/665 275/275/665 286/286/665 +f 277/277/666 273/273/667 287/287/668 +f 287/287/668 273/273/667 286/286/669 +f 288/288/670 289/289/670 290/290/670 +f 291/291/671 292/292/672 293/293/673 +f 293/293/673 292/292/672 294/294/674 +f 293/293/673 294/294/674 295/295/675 +f 295/295/675 294/294/674 296/296/676 +f 295/295/675 296/296/676 297/297/677 +f 297/297/677 296/296/676 298/298/678 +f 297/297/677 298/298/678 291/291/679 +f 291/291/680 298/298/680 292/292/680 +f 299/299/681 294/294/682 292/292/683 +f 299/299/681 292/292/683 300/300/684 +f 300/300/685 292/292/686 288/288/687 +f 288/288/687 292/292/686 298/298/688 +f 288/288/689 298/298/689 289/289/689 +f 289/289/690 298/298/690 296/296/690 +f 289/289/691 296/296/691 290/290/691 +f 290/290/692 296/296/693 294/294/694 +f 290/290/692 294/294/694 299/299/695 +f 300/300/696 288/288/696 301/301/696 +f 299/299/697 300/300/697 302/302/697 +f 302/302/698 300/300/698 301/301/698 +f 290/290/699 299/299/699 302/302/699 +f 288/288/700 290/290/701 301/301/702 +f 301/301/702 290/290/701 302/302/703 +f 303/303/704 304/304/704 305/305/704 +f 306/306/705 305/305/705 307/307/705 +f 308/308/706 309/309/707 310/310/708 +f 308/308/706 310/310/708 311/311/709 +f 311/311/709 310/310/708 312/312/710 +f 311/311/709 312/312/710 313/313/711 +f 313/313/711 312/312/710 314/314/712 +f 313/313/711 314/314/712 315/315/713 +f 313/313/711 315/315/713 309/309/714 +f 303/303/715 312/312/716 310/310/717 +f 303/303/718 310/310/719 309/309/720 +f 303/303/718 309/309/720 304/304/721 +f 304/304/722 309/309/722 315/315/722 +f 304/304/723 315/315/723 305/305/723 +f 305/305/724 315/315/725 314/314/726 +f 305/305/724 314/314/726 307/307/727 +f 307/307/728 314/314/729 312/312/730 +f 307/307/728 312/312/730 306/306/731 +f 306/306/732 312/312/716 303/303/715 +f 303/303/733 305/305/733 316/316/733 +f 316/316/734 305/305/734 317/317/734 +f 306/306/735 303/303/735 316/316/735 +f 305/305/736 306/306/737 317/317/738 +f 317/317/738 306/306/737 316/316/739 +f 318/318/740 319/319/740 320/320/740 +f 320/320/741 321/321/741 322/322/741 +f 323/323/742 324/324/743 325/325/744 +f 323/323/742 325/325/744 326/326/745 +f 326/326/745 325/325/744 327/327/746 +f 326/326/745 327/327/746 328/328/747 +f 328/328/747 327/327/746 329/329/748 +f 328/328/747 329/329/748 324/324/743 +f 328/328/747 324/324/743 323/323/742 +f 319/319/749 327/327/750 325/325/751 +f 319/319/749 325/325/751 320/320/752 +f 320/320/753 325/325/754 324/324/755 +f 320/320/753 324/324/755 321/321/756 +f 321/321/757 324/324/758 322/322/759 +f 322/322/759 324/324/758 329/329/760 +f 322/322/761 329/329/761 318/318/761 +f 318/318/762 329/329/763 327/327/764 +f 318/318/762 327/327/764 319/319/765 +f 320/320/766 322/322/767 330/330/768 +f 330/330/768 322/322/767 331/331/769 +f 318/318/770 320/320/770 330/330/770 +f 331/331/771 318/318/771 330/330/771 +f 322/322/772 318/318/772 331/331/772 +f 332/332/773 333/333/773 334/334/773 +f 335/335/774 336/336/774 332/332/774 +f 337/337/775 338/338/776 339/339/777 +f 337/337/775 339/339/777 340/340/778 +f 340/340/778 339/339/777 341/341/779 +f 340/340/778 341/341/779 342/342/780 +f 342/342/780 341/341/779 343/343/781 +f 342/342/780 343/343/781 344/344/782 +f 342/342/780 344/344/782 338/338/783 +f 332/332/784 339/339/785 338/338/786 +f 332/332/784 338/338/786 333/333/787 +f 333/333/788 338/338/788 344/344/788 +f 333/333/789 344/344/789 334/334/789 +f 334/334/790 344/344/791 343/343/792 +f 334/334/790 343/343/792 335/335/793 +f 335/335/794 343/343/795 341/341/796 +f 335/335/794 341/341/796 336/336/797 +f 336/336/798 341/341/799 339/339/800 +f 336/336/798 339/339/800 332/332/801 +f 334/334/802 335/335/802 345/345/802 +f 346/346/803 334/334/803 345/345/803 +f 332/332/804 334/334/804 346/346/804 +f 335/335/805 332/332/806 345/345/807 +f 345/345/807 332/332/806 346/346/808 +f 347/347/809 348/348/810 349/349/811 +f 350/350/812 351/351/813 352/352/814 +f 352/352/814 351/351/813 347/347/809 +f 347/347/809 351/351/813 348/348/810 +f 348/348/810 353/353/815 349/349/811 +f 349/349/811 353/353/815 354/354/816 +f 353/353/815 355/355/817 354/354/816 +f 354/354/816 355/355/817 356/356/818 +f 355/355/817 357/357/819 356/356/818 +f 356/356/818 357/357/819 350/350/812 +f 350/350/812 357/357/819 351/351/813 +f 358/358/820 350/350/821 352/352/822 +f 358/358/820 352/352/822 359/359/823 +f 359/359/824 352/352/825 347/347/826 +f 359/359/824 347/347/826 360/360/827 +f 360/360/828 347/347/829 349/349/830 +f 360/360/828 349/349/830 361/361/831 +f 361/361/832 349/349/832 354/354/832 +f 361/361/833 354/354/833 362/362/833 +f 362/362/834 354/354/834 356/356/834 +f 362/362/835 356/356/836 358/358/837 +f 358/358/837 356/356/836 350/350/838 +f 363/363/1 359/359/1 360/360/1 +f 363/363/1 360/360/1 364/364/1 +f 364/364/1 360/360/1 361/361/1 +f 364/364/1 361/361/1 365/365/1 +f 365/365/1 361/361/1 362/362/1 +f 365/365/1 362/362/1 358/358/1 +f 365/365/1 358/358/1 366/366/1 +f 366/366/1 358/358/1 359/359/1 +f 366/366/1 359/359/1 363/363/1 +f 367/367/839 366/366/840 368/368/841 +f 368/368/841 366/366/840 363/363/842 +f 368/368/843 363/363/843 369/369/843 +f 369/369/844 363/363/845 364/364/846 +f 369/369/844 364/364/846 370/370/847 +f 370/370/848 364/364/848 371/371/848 +f 371/371/849 364/364/850 365/365/851 +f 371/371/849 365/365/851 372/372/852 +f 372/372/853 365/365/854 367/367/855 +f 367/367/855 365/365/854 366/366/856 +f 367/367/857 368/368/858 369/369/859 +f 367/367/857 369/369/859 372/372/860 +f 369/369/859 370/370/861 372/372/860 +f 372/372/860 370/370/861 371/371/862 +f 357/357/863 373/373/863 374/374/863 +f 374/374/864 373/373/865 348/348/866 +f 374/374/867 351/351/867 357/357/867 +f 357/357/868 355/355/868 373/373/868 +f 355/355/869 353/353/869 373/373/869 +f 373/373/865 353/353/870 348/348/866 +f 348/348/871 351/351/871 374/374/871 diff --git a/examples/Cassie/urdf/meshes/agility/foot.obj b/examples/Cassie/urdf/meshes/agility/foot.obj new file mode 100644 index 0000000000..88dc821034 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/foot.obj @@ -0,0 +1,4048 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o foot +v 0.076973 -0.009653 0.006310 +v 0.056887 -0.010000 0.001162 +v 0.055851 -0.010000 -0.002144 +v 0.053448 -0.009982 -0.009669 +v 0.053841 -0.010000 -0.006651 +v 0.053221 -0.009913 0.004400 +v 0.046939 -0.010004 0.002206 +v 0.052755 -0.010000 -0.000261 +v 0.054399 -0.010000 0.002019 +v 0.072184 -0.009754 0.010842 +v 0.048795 -0.010000 0.000387 +v 0.049932 -0.009999 -0.003414 +v 0.036423 -0.007706 0.004716 +v 0.037835 0.003321 0.004721 +v 0.036219 0.007583 0.004754 +v 0.044717 -0.007794 0.005000 +v 0.052229 0.003001 0.006258 +v 0.056765 -0.007796 0.007503 +v 0.072604 -0.007892 0.012781 +v 0.078209 0.003132 0.014036 +v 0.077885 -0.002818 0.014118 +v 0.029832 -0.008017 0.005400 +v 0.029983 0.007876 0.005398 +v 0.049823 0.010108 -0.010290 +v 0.052811 0.004962 -0.011050 +v 0.057414 0.009316 -0.011194 +v 0.057757 0.005145 -0.010877 +v 0.061343 0.005393 -0.009298 +v 0.062714 0.009116 -0.008229 +v 0.063626 0.004424 -0.006933 +v 0.065854 0.009379 -0.003650 +v 0.065810 0.004542 -0.002583 +v 0.066174 0.005278 0.001567 +v 0.066158 0.010021 0.001513 +v 0.047711 0.004849 -0.008544 +v 0.058084 0.003820 -0.010108 +v 0.051717 0.003836 -0.009980 +v 0.064419 0.003175 0.002173 +v 0.049887 0.003071 -0.007810 +v 0.057756 0.003055 -0.008840 +v 0.063843 0.003073 -0.003134 +v -0.008802 0.010000 -0.010016 +v -0.008599 0.009994 -0.006675 +v -0.003234 0.010000 -0.012625 +v -0.010973 0.009897 0.001490 +v -0.011774 0.010004 -0.011091 +v 0.009669 0.010000 -0.008745 +v 0.007873 0.009999 -0.007220 +v 0.012775 0.010000 -0.003311 +v 0.010680 0.009997 -0.001419 +v 0.008976 0.010005 0.006046 +v 0.014873 0.010004 0.006018 +v 0.012749 0.010000 0.003457 +v -0.001396 0.009997 -0.010683 +v 0.001812 0.010000 -0.013469 +v -0.037755 0.009871 -0.073892 +v -0.037733 0.010000 -0.078233 +v -0.052346 0.009825 -0.096591 +v -0.026572 0.010040 -0.056860 +v -0.050279 0.009664 -0.100339 +v -0.036464 0.010000 -0.081600 +v -0.033233 0.010000 -0.081758 +v 0.044941 0.010007 -0.014985 +v 0.045273 0.010000 -0.011932 +v 0.033700 0.010001 0.001774 +v 0.037698 0.009771 0.003116 +v 0.002700 0.009918 -0.010104 +v 0.008695 0.010007 -0.037001 +v -0.024841 0.010006 -0.074799 +v 0.005551 0.010000 -0.012434 +v 0.010955 0.010000 -0.031986 +v 0.013788 0.010014 -0.033107 +v 0.075688 -0.008095 0.012227 +v 0.080764 -0.006420 0.009146 +v 0.077500 -0.005919 0.013344 +v 0.082661 -0.004623 0.008631 +v 0.079492 -0.002976 0.013446 +v 0.084229 -0.003981 0.007234 +v 0.086223 -0.002592 0.005676 +v 0.079914 0.000937 0.013625 +v 0.086460 0.001999 0.005617 +v 0.084813 0.003877 0.006623 +v 0.079137 0.005287 0.012437 +v 0.082502 0.004673 0.008819 +v 0.080284 0.006973 0.008855 +v 0.077570 0.009420 0.006748 +v 0.074364 0.009911 0.008343 +v 0.057282 -0.004000 0.000335 +v 0.055313 -0.004000 -0.002116 +v 0.052897 -0.004000 -0.000698 +v 0.054302 -0.004000 0.002103 +v 0.009053 -0.009998 0.005872 +v 0.015565 -0.010002 0.006029 +v 0.003959 -0.009911 0.010178 +v 0.012841 -0.010000 0.004175 +v 0.005580 -0.010000 -0.012390 +v 0.010482 -0.009888 -0.001259 +v 0.007277 -0.009997 -0.007945 +v 0.012775 -0.010000 -0.003311 +v -0.009595 -0.010007 -0.004768 +v -0.011572 -0.010004 -0.010731 +v -0.006695 -0.009822 -0.007823 +v -0.008384 -0.010000 -0.010162 +v 0.009669 -0.010000 -0.008745 +v -0.003785 -0.010000 -0.012533 +v -0.002958 -0.009729 -0.009894 +v 0.001892 -0.010000 -0.013522 +v 0.001706 -0.009881 -0.010173 +v -0.025283 -0.010001 -0.054127 +v -0.015693 -0.010016 -0.028788 +v -0.032603 -0.009883 -0.064449 +v -0.050935 -0.009996 -0.096707 +v -0.037925 -0.010000 -0.079069 +v 0.008669 -0.010007 -0.037047 +v 0.013895 -0.010015 -0.033103 +v 0.010928 -0.010000 -0.031960 +v -0.034616 -0.010000 -0.082256 +v -0.024864 -0.010007 -0.074829 +v -0.024880 0.009451 -0.079249 +v 0.063035 0.008898 -0.009576 +v 0.064431 0.008925 -0.008204 +v 0.065596 0.009005 -0.006631 +v 0.066501 0.009137 -0.004896 +v 0.067124 0.009317 -0.003041 +v 0.067653 0.009435 -0.001721 +v 0.051724 0.009451 -0.014971 +v 0.054457 0.009436 -0.012785 +v 0.061442 0.008925 -0.010712 +v 0.059691 0.009005 -0.011587 +v 0.057825 0.009137 -0.012177 +v 0.055890 0.009317 -0.012468 +v -0.024880 -0.009451 -0.079249 +v -0.050375 -0.009451 -0.100642 +v 0.051724 -0.009451 -0.014971 +v 0.048880 -0.009985 -0.013541 +v -0.053854 0.008750 -0.096312 +v -0.056238 0.006762 -0.097906 +v -0.043950 0.008471 -0.081064 +v -0.022746 0.000273 -0.037725 +v -0.019818 0.008144 -0.031827 +v -0.026109 0.008155 -0.047371 +v -0.034799 -0.008264 -0.064849 +v -0.023935 -0.008209 -0.042521 +v -0.017822 -0.007733 -0.025635 +v -0.047616 0.001127 -0.083186 +v -0.058707 -0.001606 -0.099146 +v -0.056626 -0.006174 -0.097986 +v -0.058198 0.003430 -0.098791 +v -0.031531 0.002513 -0.056065 +v -0.041421 -0.002445 -0.073641 +v -0.035073 0.008142 -0.065261 +v -0.043994 -0.008647 -0.081340 +v -0.054464 -0.008394 -0.096846 +v -0.017240 0.008334 -0.023868 +v 0.001939 -0.008370 0.012667 +v 0.000879 0.008281 0.012886 +v -0.012316 0.008265 0.003658 +v -0.012432 -0.007776 0.003653 +v -0.010716 -0.008268 0.007138 +v -0.010696 0.008268 0.007169 +v -0.007368 -0.008393 0.010537 +v -0.007779 0.008268 0.010261 +v -0.002906 -0.008188 0.012636 +v -0.004015 0.008268 0.012234 +v 0.049065 0.009451 -0.016900 +v 0.046162 0.009451 -0.018438 +v 0.028200 0.010016 -0.023777 +v 0.032046 0.009452 -0.025490 +v 0.015477 0.009445 -0.036420 +v -0.010086 0.010007 -0.054946 +v 0.001322 0.009450 -0.048410 +v -0.011348 0.009447 -0.062008 +v -0.020500 0.009451 -0.074374 +v -0.022518 0.009451 -0.076966 +v 0.049065 -0.009451 -0.016900 +v 0.046162 -0.009451 -0.018438 +v -0.010014 -0.010011 -0.054866 +v -0.020500 -0.009451 -0.074374 +v -0.019430 -0.009210 -0.072529 +v -0.002498 -0.009450 -0.052089 +v 0.014495 -0.009443 -0.037124 +v 0.030518 -0.010019 -0.022415 +v 0.031639 -0.009453 -0.025697 +v -0.022518 -0.009451 -0.076966 +v -0.012132 0.003454 -0.011873 +v -0.015349 0.010006 -0.028083 +v -0.014492 0.003297 -0.024830 +v -0.033159 0.003700 -0.081687 +v -0.025042 0.002730 -0.074690 +v -0.019150 0.002780 -0.066248 +v -0.008003 0.003128 -0.052833 +v 0.008020 0.003371 -0.037812 +v 0.002348 0.002978 -0.014414 +v 0.008668 0.003594 -0.036138 +v 0.000714 0.003201 -0.013191 +v -0.004038 0.003263 -0.012562 +v -0.008634 0.003264 -0.010124 +v -0.018301 0.003292 -0.037006 +v -0.020888 0.002401 -0.044533 +v -0.037423 0.003259 -0.077686 +v -0.029864 0.002923 -0.063884 +v 0.000684 0.001240 -0.014916 +v -0.009067 0.001075 -0.050413 +v -0.009604 0.001075 -0.012409 +v 0.006710 0.001167 -0.036222 +v -0.015257 0.001062 -0.036265 +v -0.026472 0.001146 -0.073457 +v -0.034894 0.000977 -0.079580 +v 0.028378 0.003340 0.002712 +v 0.015746 0.002849 0.005859 +v 0.012767 0.003539 0.002889 +v 0.013202 0.002796 -0.001399 +v 0.011837 0.002778 -0.005883 +v 0.009318 0.003279 -0.009223 +v 0.006487 0.002787 -0.011597 +v 0.010682 0.003010 -0.031219 +v 0.005717 0.003248 -0.014166 +v 0.014319 0.003124 -0.032837 +v 0.027103 0.002717 -0.024254 +v 0.043984 0.003520 -0.015612 +v 0.033960 0.003094 0.001475 +v 0.045249 0.003346 -0.011992 +v 0.033132 0.003179 0.001876 +v 0.032738 0.001068 -0.000578 +v 0.014549 0.001083 -0.005207 +v 0.014679 0.001197 0.003339 +v 0.013159 0.001081 -0.030816 +v 0.007834 0.001114 -0.013067 +v 0.027889 0.001062 -0.021064 +v 0.010510 0.001224 -0.010339 +v 0.043105 0.001065 -0.013187 +v -0.014544 -0.003393 -0.025001 +v -0.012088 -0.003383 -0.011755 +v -0.008565 -0.003420 -0.010137 +v -0.008076 -0.002554 -0.010746 +v -0.003516 -0.002747 -0.012792 +v 0.001231 -0.003458 -0.013280 +v 0.002384 -0.002907 -0.014557 +v 0.008652 -0.003751 -0.035903 +v 0.008176 -0.003455 -0.037703 +v -0.000145 -0.002762 -0.044897 +v -0.010134 -0.002477 -0.055029 +v -0.019096 -0.002734 -0.066151 +v -0.024932 -0.003174 -0.074745 +v -0.033244 -0.002844 -0.081586 +v -0.030363 -0.002838 -0.064936 +v -0.037591 -0.003545 -0.077982 +v -0.025331 -0.003395 -0.054090 +v -0.018290 -0.003377 -0.036952 +v 0.006255 -0.001082 -0.036107 +v 0.000743 -0.001171 -0.015283 +v -0.013755 -0.001054 -0.055805 +v -0.009830 -0.001070 -0.012498 +v -0.026135 -0.001278 -0.073734 +v -0.028003 -0.001090 -0.064933 +v -0.035696 -0.001125 -0.078692 +v -0.013760 -0.001083 -0.031531 +v 0.037229 -0.003104 -0.018796 +v 0.048872 -0.003334 -0.013450 +v 0.024127 -0.003294 -0.026259 +v 0.014001 -0.003323 -0.032995 +v 0.010613 -0.003240 -0.031196 +v 0.005625 -0.003274 -0.013756 +v 0.006160 -0.003236 -0.011766 +v 0.009310 -0.002790 -0.009371 +v 0.012128 -0.002821 -0.005317 +v 0.013177 -0.002860 -0.000729 +v 0.012750 -0.003745 0.002710 +v 0.015901 -0.003268 0.005939 +v 0.033818 -0.010033 0.001749 +v 0.030983 -0.003355 0.002140 +v 0.036861 -0.003014 0.001574 +v 0.046570 -0.003334 0.002172 +v 0.047566 -0.001057 -0.011406 +v 0.051438 -0.001040 -0.007819 +v 0.048291 -0.001059 -0.005296 +v 0.028762 -0.001215 -0.021317 +v 0.011592 -0.001096 -0.010055 +v 0.007822 -0.001113 -0.013074 +v 0.012736 -0.001110 -0.030755 +v 0.015206 -0.001086 -0.002782 +v 0.036726 -0.001150 -0.000362 +v 0.015194 -0.001077 0.003528 +v 0.046710 -0.001124 -0.000164 +v -0.058572 0.001692 -0.101225 +v -0.051155 0.000297 -0.110348 +v -0.058115 -0.003521 -0.100902 +v -0.051645 -0.003788 -0.108453 +v -0.053632 -0.004631 -0.105490 +v -0.057515 -0.005257 -0.100171 +v -0.053011 -0.007527 -0.102818 +v -0.055001 -0.008102 -0.099121 +v -0.052539 -0.009716 -0.096504 +v -0.051722 0.003819 -0.108328 +v -0.053517 0.004528 -0.105688 +v -0.057237 0.005483 -0.100292 +v -0.053469 0.006782 -0.103394 +v -0.055268 0.007878 -0.099271 +v 0.053054 -0.003169 -0.009950 +v 0.053002 -0.003637 -0.005862 +v 0.053852 -0.003528 -0.007453 +v 0.053706 -0.003025 -0.008766 +v 0.050226 -0.003453 -0.003891 +v 0.048897 -0.003387 -0.000196 +v 0.008356 -0.002573 -0.036155 +v 0.007638 -0.001691 -0.036752 +v 0.000411 -0.002046 -0.013831 +v -0.009333 -0.001557 -0.011191 +v -0.010562 -0.003268 -0.010405 +v -0.011379 -0.001904 -0.012335 +v -0.035692 -0.003129 -0.081774 +v -0.037525 -0.003252 -0.079754 +v -0.034169 -0.001287 -0.080250 +v -0.013647 -0.001874 -0.024933 +v -0.036038 -0.001561 -0.080052 +v -0.036893 -0.002213 -0.077947 +v -0.018257 -0.001904 -0.039313 +v 0.011691 -0.003429 -0.032485 +v 0.014333 -0.001782 -0.031872 +v 0.048554 -0.001971 -0.012785 +v 0.052611 -0.001484 -0.008360 +v 0.011754 -0.001841 -0.031470 +v 0.052656 -0.002121 -0.006440 +v 0.006670 -0.001637 -0.012807 +v 0.049257 -0.001892 -0.003946 +v 0.048146 -0.001970 -0.000519 +v 0.047997 -0.002875 0.001272 +v 0.046154 -0.001713 0.001136 +v 0.014061 -0.003469 0.005374 +v 0.013013 -0.002757 0.003579 +v 0.013965 -0.001729 0.003874 +v 0.030387 -0.001704 0.001228 +v 0.015862 -0.001790 0.004988 +v 0.005687 0.003472 -0.012809 +v 0.006520 0.001821 -0.013497 +v 0.012967 0.002836 0.003726 +v 0.014138 0.002962 0.005285 +v 0.012010 0.003120 -0.032661 +v 0.011876 0.001709 -0.031344 +v 0.015912 0.001288 0.004263 +v 0.013759 0.001786 -0.032035 +v 0.033282 0.001623 0.000582 +v 0.045127 0.003383 -0.014356 +v 0.043848 0.001864 -0.014719 +v 0.034592 0.001785 -0.019110 +v 0.044440 0.001753 -0.012594 +v -0.033541 0.002272 -0.081343 +v -0.037677 0.003513 -0.078960 +v -0.036762 0.002848 -0.080897 +v -0.035641 0.003494 -0.081839 +v -0.036680 0.001635 -0.078903 +v 0.007364 0.002060 -0.037488 +v -0.008366 0.001618 -0.051603 +v -0.013871 0.001848 -0.026150 +v 0.008243 0.002425 -0.036174 +v -0.011401 0.001781 -0.012583 +v -0.010830 0.002815 -0.010606 +v -0.008569 0.002018 -0.010859 +v -0.004396 0.001933 -0.013337 +v 0.051809 0.003000 -0.001062 +v 0.057873 0.003000 0.001559 +v 0.055094 0.003000 0.003361 +v 0.052399 0.003000 0.001920 +v 0.054347 0.003000 -0.003203 +v 0.057745 0.003000 -0.002040 +v 0.056062 -0.004000 0.003191 +v 0.058361 -0.004000 0.000094 +v 0.055702 -0.004000 -0.003412 +v 0.051723 -0.004000 -0.000978 +v 0.052833 -0.004000 0.002448 +v 0.061442 0.008925 -0.010712 +v 0.054016 0.007888 -0.023865 +v 0.059691 0.009005 -0.011587 +v 0.063035 0.008898 -0.009576 +v 0.046162 0.009451 -0.018438 +v 0.025493 0.009439 -0.029209 +v 0.049065 0.009451 -0.016900 +v 0.051724 0.009451 -0.014971 +v 0.066501 0.009137 -0.004896 +v 0.077814 0.009301 0.006912 +v 0.084156 0.007927 0.001609 +v 0.067124 0.009317 -0.003041 +v 0.067634 0.009428 -0.001761 +v 0.057825 0.009137 -0.012177 +v 0.055890 0.009317 -0.012468 +v 0.054450 0.009439 -0.012801 +v 0.065596 0.009005 -0.006631 +v 0.064431 0.008925 -0.008204 +v 0.038538 -0.009226 0.003706 +v 0.029709 -0.009683 0.004000 +v 0.053696 -0.008934 0.005968 +v -0.001052 -0.009910 0.010984 +v -0.005290 -0.009908 0.009615 +v -0.009375 -0.009910 0.005966 +v -0.011570 -0.009326 0.003160 +v -0.010854 -0.009914 0.000462 +v -0.017026 -0.009310 -0.026474 +v -0.023928 -0.009416 -0.044785 +v -0.030611 0.009514 -0.059236 +v -0.016889 0.009723 -0.028644 +v -0.007926 0.009917 0.007782 +v -0.001465 0.009908 0.011018 +v 0.003931 0.009933 0.010200 +v 0.029534 0.009672 0.004073 +v 0.002698 -0.008914 0.009832 +v 0.008328 -0.008984 0.005827 +v 0.009481 -0.008991 -0.003433 +v 0.005889 -0.008983 -0.008290 +v -0.009455 -0.009008 -0.003512 +v -0.009992 -0.008892 0.001574 +v -0.008029 -0.008914 0.005998 +v -0.004351 -0.008901 0.009175 +v -0.009979 0.008916 0.001146 +v -0.009641 0.009039 -0.003090 +v 0.003724 0.008905 0.009386 +v 0.007867 0.009006 0.006319 +v -0.007238 0.009007 -0.006949 +v -0.003574 0.009007 -0.009441 +v 0.004924 0.009007 -0.008812 +v 0.009177 0.009000 -0.004406 +v 0.009968 0.009007 0.001597 +v -0.000885 0.008921 0.009995 +v -0.005036 0.008886 0.008719 +v -0.008570 0.008919 0.005329 +v 0.084316 -0.007840 0.001304 +v 0.053863 -0.007660 -0.024699 +v 0.086881 -0.005033 0.000152 +v 0.055708 -0.003830 -0.026481 +v 0.055897 0.000712 -0.026951 +v 0.088481 -0.000226 0.000235 +v 0.055273 0.005476 -0.025966 +v 0.087642 0.004468 0.000730 +v 0.085302 0.006798 0.000405 +v -0.046675 0.007893 -0.108377 +v -0.016024 0.007891 -0.082480 +v -0.015333 0.007089 -0.083518 +v -0.046363 0.006476 -0.110259 +v -0.014564 0.004476 -0.085131 +v -0.046576 0.004073 -0.112070 +v -0.046187 -0.000480 -0.112820 +v -0.013871 -0.000708 -0.085617 +v -0.014594 -0.005242 -0.084663 +v -0.046301 -0.004077 -0.111908 +v -0.046145 -0.007319 -0.109282 +v -0.015438 -0.007049 -0.083628 +v -0.016245 -0.007901 -0.082639 +v -0.047417 -0.007954 -0.108140 +v -0.020500 -0.009451 -0.074374 +v -0.022518 -0.009451 -0.076966 +v -0.000801 -0.007881 -0.062591 +v -0.003474 -0.005564 -0.069340 +v -0.002477 -0.000114 -0.070149 +v -0.005533 0.005434 -0.072157 +v 0.003362 0.005429 -0.061768 +v -0.002981 0.007873 -0.064976 +v 0.012501 -0.006494 -0.051550 +v 0.011113 -0.003603 -0.054977 +v 0.013885 0.000819 -0.052936 +v 0.034519 -0.007899 -0.033569 +v 0.014186 -0.007883 -0.048095 +v 0.034318 -0.005641 -0.036466 +v 0.023563 -0.003506 -0.044848 +v 0.030165 0.000828 -0.040728 +v 0.026094 0.005412 -0.042066 +v 0.014269 0.007862 -0.048078 +v 0.031145 0.007862 -0.035834 +v 0.039974 -0.003652 -0.034290 +v 0.038005 0.006389 -0.033717 +v 0.041767 0.002648 -0.033726 +v 0.013186 0.005430 -0.052253 +v 0.088833 -0.001352 0.001475 +v 0.088455 -0.002287 0.002996 +v 0.087145 -0.005550 0.002197 +v 0.085493 0.007019 0.002673 +v 0.088405 0.002381 0.003214 +v 0.088629 0.002251 0.001630 +v 0.084958 -0.007358 0.002677 +v -0.048392 -0.004621 -0.111591 +v -0.047477 0.000596 -0.113017 +v -0.048992 -0.001154 -0.112518 +v -0.049108 0.002051 -0.112238 +v -0.048470 0.005411 -0.110890 +v -0.048385 -0.006852 -0.109301 +v -0.047906 0.007567 -0.108607 +v 0.009332 -0.010000 0.004200 +v 0.011880 -0.010000 0.003136 +v 0.009378 -0.010000 -0.004442 +v 0.010703 -0.010000 -0.006036 +v 0.001672 -0.010000 -0.010241 +v 0.004084 -0.010000 -0.011506 +v 0.004705 -0.010000 0.008964 +v 0.001884 -0.010000 0.012063 +v 0.007830 -0.010000 0.009210 +v -0.008241 -0.010000 0.005913 +v -0.010780 -0.010000 0.006083 +v -0.002270 -0.010000 0.010034 +v -0.004682 -0.010000 0.011145 +v -0.007479 -0.010000 -0.007194 +v -0.008326 -0.010000 -0.008765 +v -0.011804 -0.010000 -0.003120 +v -0.010141 -0.010000 0.000185 +v -0.003176 -0.010000 -0.011720 +v -0.012177 -0.012000 -0.000882 +v -0.008656 -0.012000 -0.008721 +v -0.001468 -0.012000 -0.012054 +v 0.006329 -0.012000 -0.010532 +v 0.011880 -0.012000 -0.003136 +v 0.011545 -0.012000 0.003438 +v 0.008163 -0.012000 0.009184 +v 0.000802 -0.012000 0.012116 +v -0.005029 -0.012000 0.010993 +v -0.010151 -0.012000 0.006784 +v -0.001392 -0.012000 0.008254 +v -0.007005 -0.012000 0.004149 +v -0.008071 -0.012000 -0.000540 +v 0.006569 -0.012000 0.005188 +v 0.007825 -0.012000 -0.002717 +v -0.001345 -0.012000 -0.007976 +v 0.003427 -0.012000 -0.007386 +v -0.006087 -0.012000 -0.005505 +v -0.009845 0.010000 -0.003279 +v -0.011880 0.010000 0.003136 +v -0.011545 0.010000 -0.003438 +v -0.008163 0.010000 -0.009184 +v -0.004549 0.010000 -0.009066 +v -0.001406 0.010000 0.010045 +v -0.006329 0.010000 0.010532 +v -0.008291 0.010000 0.006240 +v 0.008241 0.010000 0.005913 +v 0.008656 0.010000 0.008721 +v 0.003982 0.010000 0.009270 +v 0.001468 0.010000 0.012054 +v 0.006446 0.010000 -0.007917 +v 0.010151 0.010000 -0.006784 +v 0.010234 0.010000 -0.001044 +v 0.012177 0.010000 0.000882 +v -0.000802 0.010000 -0.012116 +v 0.000782 0.010000 -0.010058 +v 0.005029 0.010000 -0.010993 +v 0.011804 0.012000 0.003120 +v 0.011580 0.012000 -0.003471 +v 0.007153 0.012000 -0.010101 +v -0.001884 0.012000 -0.012063 +v -0.007830 0.012000 -0.009210 +v -0.011880 0.012000 -0.003136 +v -0.010703 0.012000 0.006036 +v -0.004084 0.012000 0.011506 +v 0.003176 0.012000 0.011720 +v 0.008326 0.012000 0.008765 +v 0.006669 0.012000 0.004578 +v 0.008209 0.012000 -0.001104 +v 0.001392 0.012000 0.008254 +v -0.005257 0.012000 0.006218 +v -0.008265 0.012000 0.000553 +v -0.000810 0.012000 -0.008048 +v -0.005705 0.012000 -0.005899 +v 0.004416 0.012000 -0.006918 +v 0.053019 -0.004926 0.000021 +v 0.052950 -0.005225 0.000997 +v 0.054221 -0.005130 0.001919 +v 0.053273 -0.005266 -0.001445 +v 0.056145 -0.004970 -0.001596 +v 0.054882 -0.005382 -0.002492 +v 0.057068 -0.005470 -0.001328 +v 0.057479 -0.005483 0.000279 +v 0.054060 -0.009123 -0.002376 +v 0.054176 -0.009600 -0.001763 +v 0.052591 -0.009096 -0.000605 +v 0.055748 -0.009701 -0.001750 +v 0.053442 -0.009555 0.001335 +v 0.055204 -0.009441 0.002139 +v 0.053901 -0.009386 0.001609 +v 0.056927 -0.009730 0.000396 +v 0.056913 -0.009342 0.001201 +v 0.056985 -0.009233 -0.001409 +v 0.050332 0.015653 0.000133 +v 0.053327 0.015686 -0.000862 +v 0.051533 0.015548 -0.003416 +v 0.054936 0.015614 -0.001836 +v 0.054880 0.015575 -0.004671 +v 0.058372 0.015552 -0.003512 +v 0.056555 0.015666 -0.001021 +v 0.059744 0.015624 0.000342 +v 0.056677 0.015651 0.000804 +v 0.057859 0.015576 0.003788 +v 0.054995 0.015594 0.001851 +v 0.054831 0.015617 0.004662 +v 0.053356 0.015656 0.000909 +v 0.051581 0.015494 0.003496 +v 0.055271 0.012525 0.004826 +v 0.052040 0.012525 0.003876 +v 0.050077 0.012525 0.000266 +v 0.051396 0.012525 -0.003221 +v 0.055525 0.012525 -0.005035 +v 0.059951 0.012525 -0.001057 +v 0.058366 0.012525 0.003530 +v 0.055507 0.012525 -0.003447 +v 0.058361 0.012525 -0.000094 +v 0.055702 0.012525 0.003412 +v 0.052213 0.012525 0.001709 +v 0.051961 0.012525 -0.001317 +v 0.055970 -0.003256 0.003075 +v 0.052764 -0.003261 0.002212 +v 0.051813 -0.003151 -0.000911 +v 0.053706 -0.003294 -0.002788 +v 0.056868 -0.003268 -0.002638 +v 0.058182 -0.003198 0.000334 +v 0.054684 -0.003492 -0.002008 +v 0.053286 -0.003481 -0.001079 +v 0.052998 -0.003494 0.000318 +v 0.053899 -0.003481 0.001707 +v 0.056229 -0.003500 0.001585 +v 0.056989 -0.003482 0.000425 +v 0.056622 -0.003466 -0.001235 +v 0.055943 -0.003744 -0.001671 +v 0.055322 -0.003675 0.001906 +v 0.056254 -0.005141 0.001523 +v 0.055050 -0.005222 0.001980 +v 0.056993 -0.004995 -0.000252 +v 0.053065 -0.009545 -0.000500 +v 0.053021 -0.008663 -0.000127 +v 0.054318 -0.008828 -0.001843 +v 0.054256 -0.006422 -0.001760 +v 0.055503 -0.006497 -0.001853 +v 0.054618 -0.006852 -0.002451 +v 0.056929 -0.005894 0.000168 +v 0.056120 -0.006009 0.001571 +v 0.057459 -0.006305 0.000649 +v 0.057336 -0.008710 0.001158 +v 0.056994 -0.008582 -0.001565 +v 0.056988 -0.008274 0.000128 +v 0.053023 -0.008338 -0.001588 +v 0.052642 -0.008237 0.001000 +v 0.053151 -0.007910 -0.000532 +v 0.055108 -0.008066 0.002584 +v 0.057276 -0.007928 0.001093 +v 0.056828 -0.007507 0.000768 +v 0.057246 -0.007809 -0.001038 +v 0.054275 -0.007643 -0.002363 +v 0.052811 -0.007547 -0.001228 +v 0.054280 -0.007241 -0.001848 +v 0.052765 -0.007436 0.001298 +v 0.053079 -0.007107 -0.000312 +v 0.055166 -0.007267 0.002508 +v 0.056831 -0.007170 0.001681 +v 0.056576 -0.006752 0.001116 +v 0.052896 -0.006775 -0.001382 +v 0.052469 -0.005928 -0.000378 +v 0.053704 -0.005774 0.002239 +v 0.053459 -0.005411 0.001156 +v 0.056031 -0.008932 -0.001627 +v 0.056927 -0.009051 -0.000293 +v 0.056519 -0.009125 0.001162 +v 0.055351 -0.009221 0.001896 +v 0.053835 -0.005589 -0.001518 +v 0.053837 -0.005998 -0.002196 +v 0.055330 -0.005697 -0.001915 +v 0.055686 -0.006103 -0.002389 +v 0.056546 -0.005799 -0.001109 +v 0.057025 -0.006200 -0.001408 +v 0.054283 -0.006499 0.002365 +v 0.056012 -0.006427 0.002264 +v 0.054733 -0.006089 0.001895 +v 0.053483 -0.006194 0.001191 +v 0.052677 -0.006638 0.001048 +v 0.056851 -0.006614 -0.000703 +v 0.056265 -0.006929 -0.002145 +v 0.054962 -0.006876 0.001967 +v 0.053483 -0.006999 0.001178 +v 0.056036 -0.007727 -0.002249 +v 0.056417 -0.007376 -0.001394 +v 0.053503 -0.007776 0.001310 +v 0.054288 -0.008012 -0.001846 +v 0.055691 -0.008417 0.001838 +v 0.052971 -0.008966 0.001517 +v 0.056411 -0.005575 0.002100 +v 0.053095 -0.005503 -0.000283 +v 0.053120 -0.006324 -0.000594 +v 0.057523 -0.007059 -0.000317 +v 0.055357 -0.007643 0.001898 +v 0.055007 -0.008456 -0.002503 +v 0.056078 -0.008137 -0.001604 +v 0.054939 -0.008860 0.002515 +v 0.053917 -0.008533 0.001606 +v 0.056588 0.014113 0.000917 +v 0.053413 0.014113 0.000917 +v 0.056588 0.014113 -0.000917 +v 0.053413 0.014113 -0.000917 +v -0.006303 -0.009439 -0.055889 +v 0.013834 -0.009452 -0.037575 +v -0.024880 -0.009451 -0.079249 +v 0.051724 -0.009451 -0.014971 +v 0.049065 -0.009451 -0.016900 +v 0.046162 -0.009451 -0.018438 +v -0.051001 -0.009274 -0.101176 +v 0.077649 -0.009333 0.006775 +v -0.054864 -0.004292 -0.104409 +v -0.055392 0.001869 -0.104852 +v -0.053531 0.006837 -0.103291 +v -0.050804 0.009329 -0.101009 +v 0.081685 0.004301 0.010169 +v 0.082209 -0.001878 0.010609 +v 0.080350 -0.006862 0.009048 +v 0.032189 -0.009452 -0.025375 +v -0.024880 0.009451 -0.079249 +v -0.022518 0.009451 -0.076966 +v -0.020500 0.009451 -0.074374 +v -0.011242 0.009452 -0.061817 +v 0.003958 0.009452 -0.045860 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vn 0.2403 -0.9557 0.1698 +vn 0.0108 -0.9999 0.0112 +vn 0.0128 -0.9999 -0.0053 +vn 0.0874 -0.9905 -0.1063 +vn 0.0129 -0.9999 -0.0058 +vn -0.0526 -0.9575 0.2835 +vn 0.0021 -0.9995 0.0311 +vn -0.0012 -1.0000 0.0068 +vn -0.0059 -0.9994 0.0336 +vn 0.0065 -0.9105 0.4134 +vn -0.0003 -1.0000 -0.0019 +vn -0.0001 -1.0000 -0.0001 +vn 0.0602 -0.2412 0.9686 +vn -0.0212 -0.0103 0.9997 +vn 0.0873 -0.0012 0.9962 +vn -0.1134 -0.0058 0.9935 +vn -0.2115 -0.0035 0.9774 +vn -0.2829 -0.2174 0.9342 +vn -0.1412 -0.4045 0.9036 +vn 0.2243 0.1703 0.9595 +vn 0.0716 -0.1015 0.9923 +vn 0.1668 -0.3443 0.9239 +vn 0.1784 -0.0007 0.9840 +vn 0.4660 -0.0134 0.8847 +vn 0.1563 0.3197 0.9346 +vn -0.1879 -0.0097 0.9821 +vn -0.2172 0.2568 0.9417 +vn -0.5355 0.2559 0.8048 +vn -0.6893 -0.0138 0.7244 +vn -0.8124 0.0513 0.5809 +vn -0.9496 0.0337 0.3117 +vn -0.9646 0.0647 0.2558 +vn -0.9974 0.0118 0.0705 +vn -0.9982 -0.0027 0.0591 +vn 0.6064 0.3760 0.7007 +vn -0.2248 0.6800 0.6979 +vn -0.4002 0.8274 0.3941 +vn 0.2210 0.7175 0.6605 +vn -0.7733 0.6325 -0.0444 +vn -0.6530 0.7488 0.1136 +vn -0.7227 0.6910 -0.0128 +vn 0.2261 0.9216 0.3157 +vn -0.1062 0.9489 0.2973 +vn -0.3571 0.9239 0.1377 +vn -0.0022 1.0000 0.0049 +vn -0.0203 0.9998 0.0030 +vn 0.0003 1.0000 0.0014 +vn -0.0360 0.9993 0.0106 +vn -0.0416 0.9991 0.0111 +vn -0.0061 1.0000 -0.0001 +vn -0.0052 1.0000 -0.0054 +vn -0.0009 1.0000 0.0004 +vn -0.0009 1.0000 0.0001 +vn 0.0003 0.9999 0.0110 +vn 0.0069 0.9995 0.0311 +vn 0.0002 1.0000 -0.0012 +vn 0.0039 1.0000 0.0055 +vn 0.0307 0.9994 0.0133 +vn -0.2813 0.9477 0.1508 +vn -0.0399 0.9990 0.0212 +vn -0.3299 0.9426 0.0512 +vn -0.1683 0.9830 0.0734 +vn -0.2108 0.9562 -0.2030 +vn -0.0033 0.9999 -0.0114 +vn 0.0458 0.9971 -0.0601 +vn 0.0683 0.9920 -0.1059 +vn -0.0220 0.9997 -0.0049 +vn 0.0436 0.9971 -0.0630 +vn 0.0169 0.9921 0.1246 +vn 0.0318 0.9966 0.0762 +vn 0.0011 0.9999 0.0103 +vn 0.0648 0.9954 -0.0706 +vn 0.1243 0.9859 -0.1123 +vn -0.0282 0.9996 0.0007 +vn -0.0040 1.0000 0.0025 +vn 0.0648 0.9935 -0.0933 +vn 0.2934 -0.7473 0.5962 +vn 0.5863 -0.6451 0.4901 +vn 0.3437 -0.4773 0.8087 +vn 0.6814 -0.4337 0.5896 +vn 0.5785 -0.2503 0.7763 +vn 0.7129 -0.3598 0.6019 +vn 0.7651 -0.1210 0.6325 +vn 0.5673 0.0727 0.8203 +vn 0.7641 0.0981 0.6376 +vn 0.7191 0.3009 0.6263 +vn 0.6082 0.5097 0.6085 +vn 0.6806 0.4829 0.5509 +vn 0.4712 0.7303 0.4946 +vn 0.3571 0.7997 0.4827 +vn 0.3613 0.7988 0.4810 +vn -0.9491 0.1035 0.2974 +vn -0.8490 -0.0157 0.5281 +vn -0.9136 0.0512 0.4034 +vn -0.7775 -0.0726 0.6246 +vn 0.5153 0.0475 0.8557 +vn 0.5057 0.0413 0.8617 +vn 0.5103 0.0443 0.8589 +vn 0.5190 0.0499 0.8533 +vn 0.8384 -0.0014 -0.5450 +vn 0.8926 -0.0537 -0.4477 +vn 0.8726 -0.0329 -0.4874 +vn 0.8109 0.0213 -0.5847 +vn -0.3257 0.0080 -0.9455 +vn -0.4626 -0.0606 -0.8845 +vn -0.3871 -0.0222 -0.9218 +vn -0.5084 -0.0846 -0.8569 +vn -0.0030 -1.0000 0.0075 +vn 0.0075 -0.9992 0.0401 +vn 0.1232 -0.8322 0.5406 +vn -0.0082 -0.9999 -0.0066 +vn -0.0281 -0.9996 -0.0012 +vn -0.0334 -0.9994 0.0029 +vn 0.1194 -0.9918 -0.0449 +vn -0.0375 -0.9992 0.0126 +vn -0.0087 -1.0000 0.0024 +vn -0.0264 -0.9996 0.0127 +vn 0.0368 -0.9987 0.0348 +vn 0.0019 -0.9972 0.0745 +vn -0.0173 -0.9997 0.0168 +vn 0.0349 -0.9959 0.0840 +vn 0.0351 -0.9963 0.0786 +vn 0.0980 -0.9941 0.0474 +vn -0.0191 -0.9996 0.0192 +vn -0.0339 -0.9993 0.0126 +vn -0.0328 -0.9994 0.0118 +vn -0.0531 -0.9982 0.0269 +vn -0.0775 -0.9963 -0.0369 +vn -0.0158 -0.9998 0.0111 +vn 0.0675 -0.9950 -0.0741 +vn 0.0641 -0.9934 -0.0954 +vn -0.0054 -1.0000 0.0029 +vn -0.0025 -1.0000 0.0025 +vn 0.1223 -0.9861 -0.1126 +vn 0.1134 0.9858 -0.1239 +vn 0.1115 0.9848 -0.1328 +vn 0.1115 0.9848 -0.1329 +vn 0.1116 0.9848 -0.1330 +vn 0.1117 0.9848 -0.1331 +vn 0.1110 0.9850 -0.1323 +vn 0.1118 0.9848 -0.1332 +vn 0.1118 0.9848 -0.1329 +vn 0.1087 0.9857 -0.1288 +vn 0.0821 0.9910 -0.1057 +vn 0.0922 0.9906 -0.1013 +vn 0.1084 0.9860 -0.1268 +vn 0.1115 0.9848 -0.1330 +vn 0.1115 0.9848 -0.1331 +vn 0.1116 0.9848 -0.1332 +vn 0.1116 0.9848 -0.1331 +vn 0.1083 0.9862 -0.1249 +vn 0.1024 0.9887 -0.1096 +vn 0.0995 0.9896 -0.1037 +vn 0.1086 -0.9863 -0.1245 +vn -0.2277 -0.9491 -0.2176 +vn 0.1113 -0.9838 -0.1406 +vn 0.1004 -0.9843 -0.1453 +vn -0.6534 0.6998 0.2886 +vn -0.7998 0.5267 0.2880 +vn -0.7320 0.5068 0.4554 +vn -0.9239 0.0031 0.3826 +vn -0.9402 0.1076 0.3232 +vn -0.8919 0.1444 0.4286 +vn -0.8512 -0.2505 0.4613 +vn -0.8607 -0.3543 0.3655 +vn -0.9255 -0.2801 0.2551 +vn -0.8359 0.0939 0.5408 +vn -0.9667 -0.1179 0.2272 +vn -0.8266 -0.4620 0.3215 +vn -0.9268 0.2591 0.2718 +vn -0.8765 0.1737 0.4490 +vn -0.8477 -0.1751 0.5007 +vn -0.7972 0.4005 0.4518 +vn -0.7833 -0.3426 0.5187 +vn -0.6830 -0.6780 0.2717 +vn -0.9659 0.0257 0.2575 +vn 0.1291 -0.0057 0.9916 +vn 0.0627 0.0069 0.9980 +vn -0.9528 0.0056 0.3035 +vn -0.9475 0.0068 0.3197 +vn -0.8116 0.0024 0.5842 +vn -0.8273 -0.0026 0.5617 +vn -0.5775 0.0016 0.8164 +vn -0.6034 -0.0069 0.7974 +vn -0.2270 -0.0034 0.9739 +vn -0.3102 0.0023 0.9507 +vn 0.0619 0.9925 -0.1057 +vn 0.0748 0.9891 -0.1265 +vn 0.0826 0.9871 -0.1375 +vn 0.0792 0.9861 -0.1463 +vn 0.0893 0.9886 -0.1212 +vn 0.1103 0.9888 -0.1006 +vn 0.1424 0.9759 -0.1653 +vn 0.1321 0.9860 -0.1017 +vn 0.1360 0.9855 -0.1018 +vn 0.1279 0.9851 -0.1151 +vn 0.0901 -0.9843 -0.1515 +vn 0.0760 -0.9858 -0.1497 +vn 0.1361 -0.9855 -0.1015 +vn 0.1363 -0.9853 -0.1028 +vn 0.1125 -0.9881 -0.1048 +vn 0.1236 -0.9829 -0.1363 +vn 0.1129 -0.9877 -0.1082 +vn 0.0914 -0.9882 -0.1227 +vn 0.0803 -0.9866 -0.1419 +vn 0.0833 -0.9864 -0.1419 +vn 0.1283 -0.9850 -0.1154 +vn 0.9782 -0.0289 -0.2058 +vn 0.9114 0.2969 -0.2849 +vn 0.9619 0.0097 -0.2733 +vn 0.9361 0.2823 -0.2098 +vn -0.6330 0.1622 0.7570 +vn -0.7352 0.0396 0.6767 +vn -0.6473 0.0116 0.7621 +vn -0.7318 0.0388 0.6804 +vn -0.8005 0.0497 0.5973 +vn -0.7446 -0.0032 0.6676 +vn -0.7171 -0.0031 0.6969 +vn -0.7971 0.2398 0.5542 +vn -0.7400 -0.0069 0.6725 +vn -0.9592 -0.0355 -0.2806 +vn -0.9593 -0.0340 -0.2802 +vn -0.9001 0.3461 -0.2647 +vn -0.9518 0.1399 -0.2729 +vn -0.2316 0.0099 -0.9728 +vn -0.3598 0.0200 -0.9328 +vn -0.2967 0.2865 -0.9110 +vn -0.2877 0.0254 -0.9574 +vn -0.4429 0.0255 -0.8962 +vn -0.2968 0.3168 -0.9008 +vn 0.9261 0.1552 -0.3438 +vn 0.9071 0.0256 -0.4201 +vn 0.9275 0.1285 -0.3511 +vn 0.8963 0.3040 -0.3227 +vn 0.8958 0.0159 -0.4442 +vn 0.8902 0.0288 -0.4547 +vn -0.0125 0.9999 -0.0012 +vn -0.0051 1.0000 -0.0001 +vn -0.0139 0.9999 -0.0002 +vn -0.0022 1.0000 -0.0040 +vn -0.0024 1.0000 -0.0001 +vn -0.2933 0.9186 0.2650 +vn -0.2414 0.9195 0.3101 +vn -0.5099 0.0120 -0.8601 +vn -0.2210 0.2343 -0.9467 +vn -0.2348 0.0064 -0.9720 +vn -0.2241 0.3218 -0.9199 +vn 0.9920 0.1222 -0.0310 +vn 0.9117 0.4040 -0.0745 +vn 0.9466 0.0196 -0.3218 +vn 0.9661 0.0468 -0.2540 +vn 0.8909 0.0095 -0.4541 +vn 0.7690 0.0317 -0.6385 +vn 0.7258 0.0027 -0.6879 +vn 0.7275 0.0148 -0.6859 +vn 0.6862 0.0152 -0.7273 +vn 0.7489 -0.0169 0.6625 +vn 0.9692 -0.0306 0.2445 +vn 0.8383 0.3188 0.4423 +vn 0.9517 0.2687 0.1484 +vn -0.5434 -0.0090 0.8394 +vn -0.5468 0.0006 0.8373 +vn -0.5013 0.0111 0.8652 +vn -0.5127 0.0210 0.8583 +vn -0.5669 0.2266 0.7920 +vn -0.5113 -0.0076 0.8594 +vn -0.7659 0.0063 -0.6430 +vn -0.6232 0.0116 -0.7820 +vn -0.7664 0.0086 -0.6423 +vn -0.3048 0.0111 -0.9524 +vn -0.1369 0.9699 -0.2014 +vn 0.0080 1.0000 0.0002 +vn -0.0016 0.9992 -0.0404 +vn 0.0845 0.9543 0.2867 +vn 0.1895 0.9808 0.0463 +vn -0.1313 0.9605 0.2455 +vn 0.0026 0.9999 -0.0109 +vn -0.2802 0.9582 0.0574 +vn 0.9580 -0.0258 -0.2857 +vn 0.9360 -0.2615 -0.2357 +vn 0.9807 0.0210 -0.1945 +vn 0.9821 0.0484 -0.1821 +vn -0.4806 -0.0488 -0.8756 +vn -0.7665 -0.0186 -0.6420 +vn -0.5361 -0.0276 -0.8437 +vn -0.3007 -0.0206 -0.9535 +vn -0.2572 -0.0689 -0.9639 +vn -0.2723 -0.3056 -0.9124 +vn -0.1721 0.0191 -0.9849 +vn -0.7959 -0.3829 -0.4690 +vn -0.9918 -0.1180 -0.0483 +vn -0.9381 0.0181 -0.3460 +vn -0.9598 0.0480 -0.2765 +vn -0.6525 0.0267 0.7573 +vn -0.6876 -0.0330 0.7253 +vn -0.6672 -0.0046 0.7449 +vn -0.7463 -0.0179 0.6653 +vn -0.7469 0.0025 0.6649 +vn -0.8023 -0.0527 0.5946 +vn -0.7392 -0.0156 0.6733 +vn -0.7282 -0.0167 0.6852 +vn -0.6053 0.0416 0.7949 +vn -0.6154 0.0233 0.7879 +vn 0.8021 -0.4371 -0.4069 +vn 0.9151 -0.0097 -0.4031 +vn 0.8794 0.0107 -0.4760 +vn 0.9452 -0.2111 -0.2491 +vn 0.9103 -0.0459 -0.4114 +vn 0.9086 -0.2669 -0.3212 +vn -0.2513 -0.9654 0.0701 +vn -0.3726 -0.9058 -0.2018 +vn 0.0149 -0.9999 -0.0014 +vn 0.2955 -0.9348 -0.1970 +vn -0.0225 -0.9996 0.0169 +vn -0.0312 -0.9994 0.0147 +vn 0.0345 -0.9917 0.1238 +vn 0.1933 -0.9794 -0.0590 +vn -0.4141 -0.3115 0.8553 +vn -0.4922 -0.0054 0.8705 +vn -0.5378 -0.0164 0.8429 +vn -0.5160 -0.2419 0.8217 +vn -0.5194 -0.3081 0.7971 +vn -0.5439 -0.1849 0.8185 +vn -0.5496 -0.0139 0.8353 +vn 0.8568 -0.2856 0.4293 +vn 0.9632 0.0406 0.2656 +vn 0.7422 0.0244 0.6698 +vn 0.9636 0.0470 0.2633 +vn 0.6031 0.0218 -0.7973 +vn 0.7305 -0.0051 -0.6829 +vn 0.6459 -0.0145 -0.7633 +vn 0.7716 -0.0370 -0.6350 +vn 0.9095 -0.0081 -0.4156 +vn 0.9652 -0.0413 -0.2582 +vn 0.8974 -0.4396 -0.0383 +vn 0.9949 -0.0966 -0.0277 +vn 0.8945 0.0005 -0.4471 +vn -0.2283 -0.0016 -0.9736 +vn 0.0339 -0.2864 -0.9575 +vn -0.0965 -0.0196 -0.9951 +vn -0.1613 -0.2758 -0.9476 +vn -0.0077 -0.4007 -0.9162 +vn -0.0654 -0.3584 -0.9313 +vn 0.0348 -0.0032 -0.9994 +vn -0.1372 -0.9665 0.2170 +vn -0.1357 -0.9792 0.1511 +vn 0.0033 -1.0000 -0.0038 +vn -0.2068 -0.9093 0.3612 +vn 0.2221 -0.9564 -0.1895 +vn 0.2623 -0.9600 -0.0981 +vn 0.1681 -0.9390 0.3001 +vn 0.2840 -0.9573 -0.0544 +vn -0.0126 -0.9343 -0.3561 +vn 0.2724 -0.9622 0.0019 +vn -0.2566 -0.9246 -0.2816 +vn -0.9267 0.1448 -0.3467 +vn -0.7645 0.0081 -0.6446 +vn -0.8871 -0.2948 -0.3553 +vn -0.7429 -0.2305 -0.6284 +vn -0.6791 -0.4647 -0.5683 +vn -0.8296 -0.5279 -0.1819 +vn -0.5217 -0.7440 -0.4174 +vn -0.5722 -0.7998 -0.1817 +vn -0.4029 -0.9116 0.0811 +vn -0.7323 0.2693 -0.6255 +vn -0.7066 0.4104 -0.5765 +vn -0.8058 0.5315 -0.2614 +vn -0.5562 0.6789 -0.4793 +vn -0.5954 0.7814 -0.1869 +vn -0.8746 0.0048 0.4848 +vn -0.7181 -0.3197 0.6181 +vn -0.6708 -0.0192 -0.7414 +vn -0.7218 -0.1937 -0.6645 +vn -0.8672 -0.3654 -0.3384 +vn -0.9916 0.0195 0.1277 +vn -0.9931 0.0160 0.1162 +vn -0.9514 -0.0067 0.3079 +vn -0.5910 -0.2180 -0.7767 +vn -0.6376 -0.0275 -0.7699 +vn -0.9526 -0.0011 -0.3042 +vn -0.8928 -0.2407 -0.3807 +vn -0.9407 0.0176 -0.3387 +vn -0.8594 -0.0029 -0.5113 +vn -0.9676 -0.0480 0.2480 +vn -0.8437 -0.3273 0.4254 +vn -0.8885 -0.4588 0.0077 +vn -0.4867 -0.8732 0.0249 +vn -0.7308 -0.0487 -0.6808 +vn -0.7029 -0.4917 0.5141 +vn -0.3537 -0.5632 -0.7468 +vn -0.5824 -0.6982 0.4163 +vn -0.5595 -0.6469 0.5181 +vn -0.5673 -0.6378 0.5210 +vn -0.5844 -0.5159 0.6263 +vn -0.4193 -0.8303 0.3671 +vn -0.4129 -0.8173 0.4020 +vn -0.5389 -0.6634 0.5191 +vn -0.2973 -0.8383 -0.4570 +vn -0.2315 -0.6247 -0.7457 +vn 0.0365 -0.7903 -0.6116 +vn -0.0608 -0.7933 -0.6058 +vn 0.0174 -0.8581 -0.5131 +vn -0.1800 -0.6626 -0.7270 +vn -0.2594 -0.9331 -0.2490 +vn -0.2029 -0.6328 -0.7472 +vn 0.6639 -0.0635 -0.7451 +vn 0.6446 -0.3001 -0.7031 +vn 0.3928 -0.2937 -0.8715 +vn 0.1676 0.0124 -0.9858 +vn 0.0713 -0.2593 -0.9632 +vn 0.1757 0.0086 -0.9844 +vn 0.6339 -0.6939 -0.3415 +vn -0.0670 -0.0803 0.9945 +vn 0.6925 0.0580 0.7190 +vn 0.7225 0.0370 0.6904 +vn 0.7044 0.0498 0.7080 +vn 0.7396 0.0244 0.6726 +vn 0.9980 -0.0563 0.0279 +vn 0.9206 -0.3889 0.0347 +vn -0.2438 -0.7034 0.6677 +vn -0.0868 -0.8794 0.4681 +vn 0.7191 -0.6766 -0.1585 +vn 0.8642 -0.4770 -0.1599 +vn 0.1771 -0.8532 0.4906 +vn 0.0899 -0.6779 0.7296 +vn 0.6538 -0.7494 -0.1045 +vn 0.7556 -0.6299 -0.1795 +vn 0.7527 -0.6580 0.0212 +vn 0.6632 -0.4820 0.5726 +vn 0.5710 -0.7745 -0.2722 +vn 0.8016 -0.5090 -0.3136 +vn 0.5434 -0.8077 -0.2286 +vn 0.3288 0.0214 0.9442 +vn 0.2161 -0.0193 0.9762 +vn 0.4807 -0.2480 0.8411 +vn -0.4953 -0.4502 0.7430 +vn -0.0205 -0.8283 0.5598 +vn -0.3909 -0.6940 0.6046 +vn -0.4500 -0.7833 0.4289 +vn 0.4868 -0.6958 0.5281 +vn 0.1641 -0.5756 0.8011 +vn -0.6699 -0.7092 -0.2196 +vn -0.6247 -0.6357 -0.4534 +vn -0.3718 -0.8610 -0.3471 +vn -0.6720 -0.5940 0.4423 +vn -0.8124 -0.5640 -0.1479 +vn 0.9643 -0.0589 -0.2581 +vn 0.9102 -0.4118 -0.0449 +vn 0.9421 -0.2247 -0.2490 +vn 0.6428 -0.7384 -0.2040 +vn -0.5645 -0.3766 -0.7345 +vn -0.6683 -0.6812 -0.2990 +vn -0.8142 -0.5098 -0.2780 +vn -0.5631 -0.7845 -0.2596 +vn -0.3844 -0.8785 -0.2838 +vn -0.6764 0.0039 -0.7365 +vn -0.5255 -0.0334 -0.8502 +vn -0.6506 -0.3906 -0.6513 +vn -0.1414 -0.7459 -0.6509 +vn 0.5182 0.0336 -0.8546 +vn 0.5725 -0.2491 -0.7812 +vn 0.8761 -0.4045 -0.2624 +vn 0.4515 -0.7494 -0.4842 +vn 0.5461 -0.5724 -0.6117 +vn 0.6245 -0.7800 0.0411 +vn 0.6103 -0.7380 -0.2879 +vn -0.1447 -0.5830 -0.7995 +vn 0.0612 -0.7248 -0.6862 +vn 0.4766 -0.6191 -0.6241 +vn 0.1037 -0.8702 -0.4817 +vn 0.8459 0.0481 -0.5312 +vn 0.9502 0.2994 -0.0863 +vn 0.4784 0.7646 -0.4319 +vn 0.6868 0.7247 -0.0560 +vn 0.5996 0.6767 -0.4274 +vn 0.5434 0.6696 -0.5064 +vn 0.8535 0.4082 -0.3241 +vn 0.5914 0.7434 -0.3124 +vn 0.5650 0.6221 -0.5420 +vn 0.5782 0.7411 -0.3412 +vn 0.6048 0.7651 -0.2212 +vn 0.3394 0.0623 -0.9386 +vn 0.7752 -0.0041 -0.6317 +vn 0.8002 -0.0211 -0.5993 +vn 0.4088 0.2969 0.8630 +vn 0.3115 -0.0189 0.9501 +vn 0.0732 0.2495 0.9656 +vn 0.4753 0.7596 0.4439 +vn 0.4113 0.6726 -0.6151 +vn 0.3144 0.7274 -0.6100 +vn 0.3864 0.7341 -0.5584 +vn -0.1076 0.7292 0.6758 +vn -0.3320 0.7666 -0.5497 +vn -0.0836 0.9206 -0.3815 +vn -0.8959 0.2527 0.3654 +vn -0.9954 -0.0031 0.0955 +vn -0.9800 0.1887 0.0626 +vn -0.9941 0.0026 0.1081 +vn -0.5123 0.6958 0.5034 +vn -0.2974 0.7685 0.5665 +vn -0.4371 0.5899 0.6790 +vn -0.3246 0.7942 0.5136 +vn -0.1880 0.6172 -0.7640 +vn -0.6811 0.7181 -0.1428 +vn -0.4646 0.6039 -0.6477 +vn -0.6526 0.5344 -0.5371 +vn -0.5920 0.3346 0.7332 +vn -0.3248 0.8510 0.4126 +vn -0.4808 0.7661 0.4266 +vn 0.9722 0.2031 0.1161 +vn 0.9353 -0.0314 0.3525 +vn 0.9040 -0.0145 0.4273 +vn 0.8457 0.1559 0.5104 +vn 0.6253 0.0505 0.7787 +vn 0.0488 -0.0305 0.9983 +vn -0.0435 0.0697 0.9966 +vn 0.0232 -0.0210 0.9995 +vn -0.0708 0.1165 0.9907 +vn -0.0805 0.2534 0.9640 +vn 0.2962 0.7191 0.6286 +vn 0.2188 0.6877 0.6922 +vn 0.2178 0.6645 0.7149 +vn 0.3210 0.7385 0.5930 +vn 0.8366 0.5419 -0.0801 +vn 0.4536 0.7697 0.4493 +vn -0.9260 0.1735 0.3353 +vn -0.2815 0.9181 0.2790 +vn -0.5596 0.8215 0.1095 +vn -0.5989 0.6643 0.4472 +vn -0.5807 0.6853 0.4394 +vn -0.6037 0.5857 0.5409 +vn -0.5856 0.5892 0.5566 +vn -0.2639 0.9269 0.2669 +vn -0.6377 0.5728 0.5150 +vn 0.7064 0.6021 -0.3722 +vn 0.8150 0.5358 -0.2208 +vn 0.5820 0.8011 -0.1396 +vn 0.4221 0.8963 -0.1355 +vn 0.5066 0.8363 -0.2096 +vn 0.6314 0.7190 -0.2904 +vn 0.3100 0.9263 -0.2142 +vn 0.2698 0.9413 -0.2031 +vn 0.1919 0.8978 -0.3964 +vn -0.8300 0.5563 0.0402 +vn 0.6170 0.7346 -0.2824 +vn 0.3156 -0.0112 -0.9488 +vn 0.2103 0.0209 -0.9774 +vn 0.4565 0.0256 -0.8894 +vn 0.4024 -0.0089 -0.9154 +vn 0.7081 0.0454 -0.7047 +vn -0.5925 0.0629 -0.8031 +vn -0.6745 0.7105 -0.2003 +vn 0.3900 0.6773 -0.6239 +vn -0.1379 0.7005 -0.7002 +vn -0.4243 0.6017 -0.6767 +vn -0.2537 0.6253 -0.7380 +vn -0.2524 0.6271 -0.7369 +vn -0.2477 0.4819 -0.8405 +vn -0.2176 0.8916 -0.3971 +vn -0.2237 0.3929 -0.8920 +vn -0.0142 0.9999 0.0008 +vn 0.0053 1.0000 -0.0001 +vn -0.0094 0.9999 0.0145 +vn 0.0187 0.9998 0.0024 +vn 0.0230 0.9997 0.0009 +vn -0.0248 0.9995 -0.0209 +vn -0.0151 0.9997 -0.0166 +vn 0.0157 0.9999 -0.0015 +vn 0.0028 1.0000 0.0094 +vn -0.0127 0.9999 0.0021 +vn -0.0000 1.0000 -0.0000 +vn -0.3225 -0.0906 0.9422 +vn -0.7916 0.1134 0.6004 +vn -0.9964 -0.0769 0.0354 +vn -0.6303 -0.0179 -0.7761 +vn -0.8011 0.0686 -0.5946 +vn -0.7419 0.0358 -0.6696 +vn -0.5432 -0.0548 -0.8378 +vn 0.4074 -0.0125 -0.9132 +vn 0.2239 0.0546 -0.9731 +vn 0.2890 0.0315 -0.9568 +vn 0.4712 -0.0369 -0.8812 +vn 0.9736 0.0004 -0.2282 +vn 0.9507 0.0357 -0.3080 +vn 0.9601 0.0227 -0.2788 +vn 0.9809 -0.0144 -0.1941 +vn 0.6450 0.0009 0.7642 +vn 0.5570 0.0546 0.8287 +vn 0.6018 0.0281 0.7981 +vn 0.5203 0.0753 0.8506 +vn -0.5106 0.6090 0.6069 +vn -0.4973 0.6448 0.5804 +vn -0.4987 0.6413 0.5831 +vn -0.5125 0.6037 0.6107 +vn -0.6420 0.0137 0.7666 +vn -0.6397 0.0066 0.7686 +vn -0.6404 0.0088 0.7680 +vn -0.6425 0.0152 0.7662 +vn 0.7528 -0.0268 0.6578 +vn 0.7631 0.1504 0.6285 +vn 0.4741 0.7622 0.4408 +vn 0.7539 0.2813 0.5937 +vn 0.1196 0.9822 -0.1450 +vn 0.2625 0.8783 -0.3996 +vn 0.1160 0.9829 -0.1430 +vn 0.1224 0.9816 -0.1463 +vn 0.0842 0.9833 -0.1613 +vn 0.0971 0.9833 -0.1537 +vn 0.0949 0.9836 -0.1533 +vn 0.1131 0.9831 -0.1436 +vn 0.1187 0.9838 -0.1345 +vn 0.2924 0.9453 0.1445 +vn 0.3900 0.9154 -0.0998 +vn 0.1308 0.9816 -0.1389 +vn 0.1284 0.9823 -0.1364 +vn 0.1140 0.9833 -0.1422 +vn 0.1141 0.9833 -0.1421 +vn 0.1167 0.9829 -0.1424 +vn 0.1182 0.9834 -0.1375 +vn 0.1199 0.9827 -0.1410 +vn -0.0100 -0.5486 0.8360 +vn 0.1047 -0.8443 0.5256 +vn -0.0483 -0.8763 0.4793 +vn 0.0450 -0.9601 0.2762 +vn -0.1300 -0.3177 0.9392 +vn -0.1599 -0.7122 0.6835 +vn 0.0817 -0.7803 0.6201 +vn -0.1674 -0.7704 0.6152 +vn -0.0682 -0.7585 0.6481 +vn -0.3539 -0.7813 0.5141 +vn -0.2825 -0.7508 0.5970 +vn -0.5839 -0.7090 0.3954 +vn -0.5195 -0.7738 0.3624 +vn -0.8155 -0.5282 0.2366 +vn -0.6416 -0.7444 0.1848 +vn -0.3920 -0.9170 0.0738 +vn -0.3174 -0.9423 0.1062 +vn -0.3520 -0.9324 0.0817 +vn -0.8083 -0.5370 0.2415 +vn -0.5470 -0.7753 0.3158 +vn -0.5993 -0.7404 0.3045 +vn -0.6007 -0.7289 0.3284 +vn -0.6558 -0.6900 0.3062 +vn -0.4440 0.8660 0.2301 +vn -0.8008 0.4810 0.3569 +vn -0.2047 0.9763 0.0706 +vn -0.1931 0.9800 0.0471 +vn -0.6422 0.7424 0.1910 +vn -0.6592 0.7071 0.2558 +vn -0.7269 0.6719 0.1420 +vn -0.6350 0.7533 0.1712 +vn -0.5938 0.7747 0.2173 +vn -0.5387 0.7786 0.3218 +vn -0.4559 0.7686 0.4487 +vn -0.3594 0.7670 0.5315 +vn -0.2255 0.7774 0.5872 +vn -0.0984 0.7599 0.6426 +vn 0.0574 0.7636 0.6431 +vn 0.1319 0.8086 0.5734 +vn 0.1167 0.8342 0.5390 +vn 0.1541 0.6112 0.7763 +vn 0.0900 0.5572 0.8255 +vn 0.0931 0.5652 0.8197 +vn -0.1998 -0.6119 -0.7653 +vn -0.5663 -0.4790 -0.6707 +vn -0.3574 -0.6500 -0.6706 +vn -0.5821 -0.4464 -0.6796 +vn -0.7980 -0.5786 -0.1688 +vn -0.9156 -0.0568 0.3981 +vn -0.8942 -0.0020 0.4477 +vn -0.9013 0.0398 0.4314 +vn -0.5983 -0.6688 0.4414 +vn -0.3678 -0.1940 0.9095 +vn -0.5181 -0.0774 0.8518 +vn -0.4138 -0.0219 0.9101 +vn 0.6548 -0.6254 0.4244 +vn 0.5502 -0.6826 0.4810 +vn 0.8113 -0.5139 0.2786 +vn 0.7785 -0.6273 0.0214 +vn 0.8039 -0.5758 -0.1488 +vn 0.5871 -0.7220 -0.3661 +vn 0.5327 -0.7048 -0.4686 +vn 0.3149 -0.6623 -0.6799 +vn 0.4072 -0.6570 -0.6345 +vn 0.0550 -0.7798 -0.6236 +vn 0.6908 0.7206 -0.0589 +vn 0.7137 0.6961 0.0772 +vn 0.7017 0.7025 -0.1188 +vn -0.3795 0.3424 -0.8595 +vn -0.6514 0.6183 -0.4398 +vn -0.7144 0.2756 -0.6432 +vn 0.9602 0.0008 0.2792 +vn 0.5935 0.7179 0.3638 +vn 0.6566 0.2978 0.6930 +vn 0.5862 0.6430 0.4929 +vn 0.4087 0.0161 0.9125 +vn 0.4860 0.0266 0.8735 +vn -0.0622 0.8307 0.5532 +vn -0.4937 0.0275 0.8692 +vn -0.5497 0.0221 0.8351 +vn -0.4870 0.0476 0.8721 +vn -0.5030 0.7143 0.4867 +vn -0.8990 0.0516 0.4349 +vn -0.6646 0.7421 0.0867 +vn -0.9747 0.0233 -0.2222 +vn -0.6781 0.6703 -0.3015 +vn 0.0963 0.7073 -0.7003 +vn -0.3111 0.6277 -0.7136 +vn 0.0211 0.7254 -0.6880 +vn 0.3866 0.4542 -0.8026 +vn 0.7940 0.4784 -0.3751 +vn 0.8066 0.4423 -0.3921 +vn 0.4246 0.7940 -0.4350 +vn 0.4097 0.4060 -0.8169 +vn 0.4277 -0.8788 -0.2117 +vn 0.4451 -0.5524 -0.7048 +vn 0.7206 -0.4758 -0.5043 +vn 0.5126 -0.3281 -0.7935 +vn 0.5411 0.0581 -0.8390 +vn 0.8299 -0.0048 -0.5580 +vn 0.4802 0.4855 -0.7305 +vn 0.6653 0.2841 -0.6904 +vn 0.5874 0.6928 -0.4184 +vn 0.1034 0.9025 -0.4181 +vn 0.3021 0.9178 -0.2578 +vn 0.5308 0.6979 -0.4808 +vn 0.5216 0.5795 -0.6262 +vn 0.6771 0.3515 -0.6465 +vn 0.2259 0.3963 -0.8899 +vn 0.5743 0.0329 -0.8180 +vn 0.7287 -0.0474 -0.6832 +vn 0.6613 -0.4230 -0.6195 +vn 0.6055 -0.3315 -0.7235 +vn 0.4245 -0.7470 -0.5117 +vn 0.5133 -0.7174 -0.4709 +vn 0.2966 -0.9181 -0.2630 +vn 0.1682 -0.9645 -0.2036 +vn 0.1437 -0.9834 -0.1105 +vn 0.1341 -0.9836 -0.1205 +vn 0.4732 -0.7571 -0.4505 +vn 0.6818 -0.4731 -0.5580 +vn 0.7680 -0.0086 -0.6404 +vn 0.7021 0.4724 -0.5329 +vn 0.6264 0.4811 -0.6134 +vn 0.5217 0.7246 -0.4504 +vn 0.5277 -0.6105 -0.5906 +vn 0.6761 -0.2826 -0.6804 +vn 0.6562 0.0756 -0.7508 +vn 0.2159 -0.9003 -0.3780 +vn 0.2501 -0.9134 -0.3212 +vn 0.4271 -0.6064 -0.6707 +vn 0.5720 -0.2222 -0.7896 +vn 0.5357 0.0761 -0.8410 +vn 0.5072 0.4809 -0.7152 +vn 0.4485 0.7116 -0.5407 +vn 0.3526 0.7310 -0.5842 +vn 0.4759 -0.2411 -0.8458 +vn 0.3995 0.5794 -0.7104 +vn 0.4603 0.1845 -0.8684 +vn 0.5908 0.4689 -0.6566 +vn 0.9791 -0.1602 -0.1256 +vn 0.8935 -0.2483 0.3741 +vn 0.7905 -0.5812 -0.1933 +vn 0.6534 0.7197 0.2348 +vn 0.8822 0.2535 0.3969 +vn 0.8193 0.5626 0.1107 +vn 0.9662 0.2291 -0.1180 +vn 0.5585 -0.7919 0.2472 +vn -0.1058 -0.7234 -0.6823 +vn -0.0408 -0.4982 -0.8661 +vn -0.0189 -0.4204 -0.9071 +vn -0.0457 0.0696 -0.9965 +vn -0.4744 -0.1594 -0.8658 +vn -0.5280 0.2389 -0.8150 +vn -0.4187 0.5626 -0.7129 +vn -0.3398 -0.8071 -0.4828 +vn -0.4059 -0.7153 -0.5688 +vn -0.1263 0.7066 -0.6963 +vn -0.3143 0.8147 -0.4873 +vn -0.0466 -0.2404 -0.9696 +vn -0.8765 -0.2771 -0.3937 +vn -0.8813 -0.2274 -0.4141 +vn -0.7129 0.0315 -0.7006 +vn -0.6774 0.0957 -0.7293 +vn -0.4255 -0.1675 -0.8893 +vn -0.4119 -0.2034 -0.8883 +vn 0.0543 0.1209 -0.9912 +vn 0.0289 0.1886 -0.9816 +vn 0.1649 -0.1928 -0.9673 +vn 0.1853 -0.2543 -0.9492 +vn 0.6032 0.3216 -0.7299 +vn 0.7427 -0.3707 -0.5576 +vn 0.9212 0.3707 -0.1182 +vn 0.9862 -0.1576 0.0503 +vn 0.9527 -0.0970 0.2879 +vn 0.9431 -0.1106 0.3135 +vn 0.8331 0.0979 0.5444 +vn 0.8249 0.1302 0.5500 +vn 0.4202 0.0133 0.9073 +vn 0.4318 0.0602 0.9000 +vn 0.3751 -0.1411 0.9162 +vn 0.3645 -0.1729 0.9150 +vn -0.1466 0.0769 0.9862 +vn -0.1378 0.1006 0.9853 +vn -0.3951 0.0160 0.9185 +vn -0.4535 0.0126 0.8912 +vn -0.6343 0.0667 0.7702 +vn -0.6333 0.0709 0.7707 +vn -0.9453 -0.2097 0.2498 +vn -0.9495 0.2953 0.1057 +vn 0.0000 -1.0000 0.0000 +vn 0.9752 0.2190 -0.0331 +vn 0.9340 -0.2581 -0.2469 +vn 0.7908 0.3097 -0.5280 +vn 0.6030 -0.3131 -0.7338 +vn 0.1928 0.2009 -0.9605 +vn 0.1841 0.2304 -0.9555 +vn 0.2071 0.1503 -0.9667 +vn 0.2101 0.1393 -0.9677 +vn -0.3751 -0.1411 -0.9162 +vn -0.3645 -0.1729 -0.9150 +vn -0.4202 0.0133 -0.9073 +vn -0.4318 0.0602 -0.9000 +vn -0.8249 0.1302 -0.5500 +vn -0.8331 0.0979 -0.5444 +vn -0.9527 -0.0970 -0.2879 +vn -0.9431 -0.1106 -0.3135 +vn -0.9862 -0.1576 -0.0503 +vn -0.9210 0.3711 0.1183 +vn -0.7427 -0.3707 0.5576 +vn -0.6032 0.3216 0.7299 +vn -0.1649 -0.1928 0.9673 +vn -0.1853 -0.2543 0.9492 +vn -0.0543 0.1209 0.9912 +vn -0.0289 0.1886 0.9816 +vn 0.4255 -0.1675 0.8893 +vn 0.4119 -0.2034 0.8883 +vn 0.7129 0.0315 0.7006 +vn 0.6774 0.0961 0.7293 +vn 0.8813 -0.2274 0.4141 +vn 0.8765 -0.2771 0.3937 +vn -0.2934 -0.0351 -0.9553 +vn -0.4729 0.0147 -0.8810 +vn -0.1829 0.0009 -0.9831 +vn 0.5587 -0.0371 -0.8286 +vn 0.3539 0.0243 -0.9350 +vn 0.6499 0.0229 -0.7596 +vn 0.8962 -0.0395 -0.4419 +vn 0.9939 0.0279 -0.1068 +vn 0.9227 -0.0263 0.3847 +vn 0.8268 0.0166 0.5622 +vn 0.4553 -0.0132 0.8902 +vn 0.3892 0.0014 0.9212 +vn 0.1500 -0.0091 0.9886 +vn 0.1424 -0.0067 0.9898 +vn -0.5486 -0.0066 0.8361 +vn -0.4836 0.0204 0.8751 +vn -0.5027 0.0126 0.8644 +vn -0.9998 -0.0176 -0.0008 +vn -0.9812 0.0332 0.1902 +vn -0.9579 0.0359 -0.2849 +vn -0.6975 -0.0359 -0.7157 +vn -0.2004 -0.0084 0.9797 +vn -0.1349 0.0035 0.9909 +vn -0.2116 -0.0103 0.9773 +vn 0.4104 -0.0044 0.9119 +vn 0.4539 0.0054 0.8910 +vn 0.4020 -0.0062 0.9156 +vn 0.9293 -0.0088 0.3691 +vn 0.9287 -0.0093 0.3707 +vn 0.9295 -0.0087 0.3688 +vn 0.6386 -0.0255 -0.7691 +vn 0.8370 0.0196 -0.5468 +vn 0.8978 -0.0188 -0.4401 +vn 0.2926 -0.0339 -0.9556 +vn 0.5437 0.0164 -0.8391 +vn -0.5715 -0.0185 -0.8204 +vn -0.3958 0.0319 -0.9178 +vn -0.5298 -0.0059 -0.8481 +vn -0.9706 0.0032 -0.2409 +vn -0.9846 0.0219 -0.1732 +vn -0.9652 -0.0026 -0.2616 +vn -0.8213 -0.0168 0.5703 +vn -0.7487 0.0097 0.6628 +vn -0.8373 -0.0233 0.5462 +vn -0.2621 0.9278 0.2657 +vn -0.9857 0.0201 -0.1671 +vn -0.9884 -0.0799 -0.1294 +vn -0.9839 -0.0897 -0.1545 +vn -0.1129 0.9537 -0.2788 +vn 0.4448 0.3898 -0.8063 +vn 0.4995 0.8578 -0.1206 +vn -0.5499 -0.7067 -0.4452 +vn -0.5508 -0.7048 -0.4471 +vn -0.5540 -0.6972 -0.4549 +vn -0.0459 -0.7929 -0.6077 +vn -0.3605 -0.3930 0.8459 +vn 0.2803 -0.8631 0.4200 +vn 0.9994 -0.0206 0.0266 +vn 0.9985 0.0456 0.0294 +vn 0.9995 0.0125 0.0280 +vn 0.3987 -0.8875 -0.2311 +vn 0.3069 -0.1250 -0.9435 +vn 0.3144 0.0226 -0.9490 +vn 0.3153 0.0657 -0.9467 +vn -0.0158 0.9998 0.0105 +vn -0.0055 0.9995 -0.0298 +vn -0.0124 0.9993 -0.0343 +vn 0.0001 0.9995 -0.0328 +vn -0.0010 0.9999 -0.0137 +vn 0.0133 0.9995 -0.0279 +vn 0.0079 0.9996 -0.0279 +vn 0.0161 0.9999 0.0001 +vn 0.0025 0.9998 0.0193 +vn 0.0049 0.9999 0.0127 +vn 0.0186 0.9998 0.0038 +vn -0.0037 1.0000 0.0053 +vn -0.0106 0.9996 0.0266 +vn -0.0342 0.9987 0.0387 +vn -0.3123 0.0371 0.9493 +vn -0.3378 0.0019 0.9412 +vn -0.3087 0.0419 0.9502 +vn -0.2812 0.0789 0.9564 +vn -0.8761 -0.0745 0.4764 +vn -0.9043 -0.0063 0.4268 +vn -0.9126 0.0181 0.4083 +vn -0.9321 0.0909 0.3505 +vn -0.9409 0.0444 -0.3357 +vn -0.9448 0.0631 -0.3214 +vn -0.9398 0.0392 -0.3395 +vn -0.9351 0.0196 -0.3537 +vn -0.4019 -0.0408 -0.9148 +vn -0.3832 -0.0113 -0.9236 +vn -0.3748 0.0015 -0.9271 +vn -0.3511 0.0374 -0.9356 +vn 0.3111 0.1772 -0.9337 +vn 0.6478 -0.2466 -0.7208 +vn 0.9196 0.2110 -0.3313 +vn 0.9418 -0.0840 0.3254 +vn 0.9232 -0.0155 0.3840 +vn 0.9087 0.0245 0.4166 +vn 0.8719 0.1044 0.4784 +vn 0.3864 -0.0141 0.9222 +vn 0.3351 0.0361 0.9415 +vn 0.3319 0.0391 0.9425 +vn 0.2770 0.0903 0.9566 +vn -0.2598 -0.0250 0.9653 +vn -0.4160 0.0083 0.9093 +vn -0.2874 -0.0193 0.9576 +vn -0.4386 0.0133 0.8986 +vn -0.9566 -0.0241 0.2904 +vn -0.9939 0.0070 0.1099 +vn -0.9636 -0.0200 0.2666 +vn -0.9965 0.0116 0.0830 +vn -0.6743 0.0396 -0.7374 +vn -0.5148 -0.0173 -0.8571 +vn -0.5375 -0.0098 -0.8432 +vn -0.7013 0.0502 -0.7111 +vn 0.0477 -0.0470 -0.9978 +vn 0.8941 -0.0124 -0.4476 +vn 0.7611 0.0324 -0.6478 +vn 0.7845 0.0256 -0.6196 +vn 0.9146 -0.0214 -0.4039 +vn 0.7814 0.0011 0.6240 +vn 0.7967 0.0074 0.6043 +vn 0.7942 0.0063 0.6077 +vn 0.7782 -0.0002 0.6280 +vn -0.0974 -0.9792 -0.1782 +vn -0.0078 -0.9788 -0.2048 +vn -0.2020 -0.9749 -0.0933 +vn -0.2220 -0.9745 -0.0327 +vn -0.2151 -0.9761 0.0311 +vn -0.8333 0.5268 -0.1675 +vn -0.1448 -0.9841 0.1032 +vn -0.0846 -0.9774 0.1939 +vn -0.1140 -0.9790 0.1690 +vn 0.0638 -0.9802 0.1872 +vn 0.2305 -0.9531 0.1960 +vn 0.2466 -0.9668 0.0675 +vn 0.2333 -0.9721 0.0246 +vn 0.1153 -0.9837 -0.1376 +vn 0.2323 -0.9679 -0.0959 +vn 0.3159 0.4971 -0.8081 +vn 0.0358 0.8320 0.5535 +vn 0.3497 -0.0223 0.9366 +vn 0.1393 0.0175 0.9901 +vn 0.1117 0.0451 0.9927 +vn 0.3393 -0.0299 0.9402 +vn 0.8857 -0.1036 0.4526 +vn 0.8857 -0.1031 0.4527 +vn 0.9232 -0.0005 0.3843 +vn 0.8145 -0.2348 0.5305 +vn 0.9718 0.0985 -0.2144 +vn 0.6015 -0.3236 -0.7304 +vn 0.8418 0.1063 -0.5292 +vn 0.8251 0.2293 -0.5164 +vn 0.8404 0.1226 -0.5280 +vn 0.0925 -0.1815 -0.9790 +vn 0.0608 -0.2118 -0.9754 +vn 0.2552 -0.0174 -0.9667 +vn -0.0210 -0.2876 -0.9575 +vn -0.5446 0.1722 -0.8208 +vn -0.9809 0.0356 -0.1913 +vn -0.9790 0.0270 -0.2022 +vn -0.8455 -0.0976 0.5250 +vn -0.8407 -0.1077 0.5307 +vn -0.8388 -0.1114 0.5330 +vn -0.8316 -0.1251 0.5411 +vn -0.1075 0.0841 0.9906 +vn -0.0601 0.1157 0.9915 +vn -0.0549 -0.9980 0.0314 +vn -0.0173 -0.9978 0.0643 +vn -0.0014 -0.9989 0.0462 +vn -0.1153 -0.9921 0.0501 +vn -0.0569 -0.9984 0.0024 +vn -0.0640 -0.9979 -0.0128 +vn -0.4095 0.8379 -0.3608 +vn -0.1068 0.8907 -0.4418 +vn -0.1671 0.8878 -0.4289 +vn -0.2513 0.7839 -0.5677 +vn 0.1923 0.8109 -0.5527 +vn -0.0566 0.8027 -0.5937 +vn 0.3987 0.8663 0.3009 +vn 0.3601 0.7911 0.4944 +vn 0.4227 0.8381 0.3448 +vn 0.8685 0.4882 -0.0859 +vn -0.7986 0.5853 -0.1404 +vn -0.5400 0.8417 0.0003 +vn -0.7499 0.6523 -0.1099 +vn 0.3622 0.7373 0.5702 +vn 0.3279 0.7698 0.5477 +vn 0.3344 0.7638 0.5521 +vn 0.6731 0.7389 0.0320 +vn 0.5095 0.8601 -0.0259 +vn 0.6351 0.7722 0.0177 +vn -0.1138 0.7837 -0.6106 +vn -0.3383 0.8628 -0.3756 +vn -0.1799 0.8153 -0.5503 +vn -0.8136 0.5801 -0.0399 +vn -0.5799 0.8130 0.0530 +vn -0.7685 0.6396 -0.0190 +vn 0.2102 0.8281 0.5197 +vn 0.3680 0.8190 0.4402 +vn 0.4666 0.8107 0.3535 +vn -0.3391 0.8277 -0.4472 +vn -0.5884 0.7983 -0.1284 +vn -0.7962 0.4959 0.3467 +vn -0.7753 0.5469 0.3160 +vn 0.3076 0.3267 -0.8937 +vn 0.9924 0.1185 0.0322 +vn 0.4309 0.8296 0.3551 +vn 0.3927 0.7962 0.4603 +vn 0.3691 0.5770 0.7286 +vn 0.3719 0.5639 0.7374 +vn -0.2053 0.7831 0.5871 +vn -0.3839 0.7969 -0.4665 +vn -0.2230 0.8193 -0.5282 +vn 0.1193 0.8140 -0.5685 +vn 0.2275 0.8140 -0.5345 +vn 0.6888 0.7085 -0.1537 +vn 0.6539 0.7462 -0.1248 +vn 0.5051 0.8132 -0.2891 +vn 0.5130 0.8151 -0.2692 +vn -0.2364 0.8099 0.5368 +vn 0.1903 0.8094 0.5556 +vn -0.0983 0.8152 0.5707 +vn -0.4738 0.8027 0.3622 +vn -0.5459 0.8232 0.1556 +vn 0.6039 0.6912 -0.3970 +vn 0.3554 0.8207 -0.4474 +vn -0.3667 0.6823 0.6324 +vn -0.3662 0.6900 0.6243 +vn -0.3631 0.7265 0.5835 +vn -0.3606 0.7462 0.5596 +vn 0.2307 0.8431 -0.4857 +vn 0.4751 0.8791 -0.0370 +vn -0.5052 0.4471 0.7382 +vn -0.4796 0.8770 0.0279 +vn -0.3112 0.6867 -0.6569 +vn -0.3059 0.8559 -0.4169 +vn -0.2979 0.8967 -0.3273 +vn 0.2835 0.9136 0.2914 +vn -0.7577 0.6455 0.0962 +vn -0.4862 0.8618 0.1445 +vn -0.6966 0.7090 0.1097 +vn 0.8192 0.2583 -0.5121 +vn 0.4748 0.8200 0.3197 +vn 0.5107 0.7968 0.3229 +vn 0.5954 0.7334 0.3282 +vn 0.6584 0.6766 0.3298 +vn 0.1601 0.8095 0.5649 +vn 0.0189 0.3865 0.9221 +vn -0.2932 0.8844 0.3632 +vn -0.5438 0.8295 -0.1273 +vn -0.7567 0.6488 -0.0802 +vn -0.8049 0.5840 -0.1055 +vn -0.3322 0.8562 -0.3956 +vn 0.6553 0.6370 -0.4060 +vn 0.4899 0.8606 0.1393 +vn 0.5188 0.8392 0.1629 +vn 0.2107 0.8278 0.5200 +vn -0.5091 0.8573 0.0759 +vn -0.3239 0.8865 -0.3306 +vn 0.4351 0.7482 -0.5009 +vn 0.5601 0.6483 -0.5157 +vn 0.3806 0.7188 0.5819 +vn -0.2075 0.8643 0.4582 +vn -0.3056 0.5993 -0.7399 +vn 0.1235 0.8797 -0.4593 +vn 0.3049 0.7235 -0.6194 +vn 0.1693 0.8478 -0.5025 +vn 0.3520 0.6677 -0.6560 +vn 0.4366 0.8854 -0.1599 +vn 0.4062 0.4889 0.7720 +vn -0.1173 0.8851 0.4503 +vn -0.3130 0.7255 0.6129 +vn -0.1677 0.8525 0.4951 +vn -0.3656 0.6658 0.6504 +vn -0.4231 0.8932 0.1521 +vn -0.4264 0.8270 -0.3664 +vn 0.1173 0.8438 -0.5238 +vn 0.3267 0.9353 -0.1356 +vn 0.4618 0.8698 0.1737 +vn -0.3884 0.9176 0.0845 +vn 0.3832 -0.7884 0.4813 +vn 0.0847 -0.5945 0.7996 +vn 0.0993 -0.6302 0.7701 +vn 0.4165 -0.8391 -0.3500 +vn 0.5759 -0.8167 0.0372 +vn 0.3663 -0.8363 -0.4081 +vn -0.4353 -0.7478 -0.5013 +vn -0.5008 -0.7907 -0.3521 +vn -0.2125 -0.8841 -0.4163 +vn -0.9868 0.0940 -0.1321 +vn -0.4311 -0.6174 0.6580 +vn -0.3983 -0.6573 0.6398 +vn -0.1605 -0.8637 0.4778 +vn -0.1302 -0.8814 0.4540 +vn -0.3814 -0.9114 0.1547 +vn -0.5068 -0.8262 -0.2461 +vn -0.1646 -0.9139 -0.3711 +vn 0.3769 -0.6581 -0.6519 +vn 0.3263 -0.7220 -0.6102 +vn -0.7064 -0.6138 0.3525 +vn -0.7352 -0.5613 0.3800 +vn -0.5213 -0.8305 0.1962 +vn -0.3628 -0.5344 0.7634 +vn -0.2779 -0.8351 0.4747 +vn -0.3217 -0.7216 0.6130 +vn -0.4266 -0.8864 0.1799 +vn -0.4298 -0.6289 -0.6479 +vn -0.4276 -0.7087 -0.5611 +vn -0.3935 -0.8694 -0.2987 +vn 0.6417 -0.5952 -0.4836 +vn 0.1583 -0.8392 0.5203 +vn 0.4297 -0.8312 0.3528 +vn 0.0555 -0.8228 0.5656 +vn -0.2810 -0.6788 0.6785 +vn -0.6145 -0.7864 -0.0629 +vn -0.4163 -0.8977 0.1447 +vn -0.4801 -0.8685 0.1237 +vn -0.5118 -0.8269 -0.2329 +vn -0.2478 -0.8158 -0.5225 +vn -0.1966 -0.8001 -0.5667 +vn 0.3768 -0.9021 0.2105 +vn 0.4858 -0.5819 0.6522 +vn -0.3246 -0.9158 0.2364 +vn -0.3811 -0.9024 -0.2013 +vn 0.2611 -0.7758 -0.5744 +vn 0.0083 -0.8745 -0.4850 +vn 0.0643 -0.8434 -0.5334 +vn 0.3335 -0.8428 -0.4224 +vn 0.3424 -0.8873 -0.3091 +vn 0.4464 -0.8574 0.2562 +vn 0.4205 -0.8250 0.3775 +vn 0.4517 -0.8884 0.0815 +vn 0.2744 -0.7472 0.6053 +vn 0.0613 -0.7906 0.6092 +vn -0.2744 -0.6612 0.6983 +vn -0.3391 -0.5912 0.7317 +vn -0.4184 -0.8781 0.2321 +vn -0.4700 -0.8541 0.2228 +vn -0.6375 -0.7480 0.1846 +vn -0.5555 -0.6937 -0.4585 +vn 0.5969 -0.8002 0.0574 +vn 0.3948 -0.8086 0.4362 +vn -0.1459 -0.9073 0.3944 +vn -0.4734 -0.8663 0.1592 +vn -0.5328 -0.7303 -0.4276 +vn -0.2696 -0.7976 -0.5396 +vn -0.5651 -0.6605 -0.4944 +vn -0.3341 -0.8183 -0.4676 +vn 0.1236 -0.8162 -0.5644 +vn 0.1101 -0.8250 -0.5543 +vn 0.2604 -0.8593 -0.4403 +vn 0.2825 -0.8462 -0.4518 +vn 0.5112 -0.8588 -0.0336 +vn 0.6915 -0.7067 -0.1495 +vn 0.7470 -0.6371 -0.1901 +vn 0.4519 -0.8921 0.0006 +vn 0.5842 -0.6591 0.4736 +vn 0.2911 -0.8280 0.4793 +vn 0.5169 -0.7231 0.4583 +vn 0.1311 -0.7418 0.6577 +vn 0.0712 -0.6607 0.7473 +vn -0.2532 -0.8801 0.4017 +vn -0.8142 -0.5791 -0.0407 +vn -0.3761 -0.9011 -0.2156 +vn 0.0560 -0.8531 -0.5188 +vn 0.0560 -0.8530 -0.5189 +vn 0.0564 -0.8530 -0.5188 +vn 0.0566 -0.8526 -0.5194 +vn 0.3874 -0.9128 -0.1291 +vn 0.6416 -0.7201 0.2642 +vn 0.7529 -0.6180 0.2262 +vn -0.3079 -0.6435 0.7008 +vn 0.1605 -0.8241 -0.5433 +vn 0.2931 -0.8244 -0.4842 +vn 0.3960 -0.8610 -0.3192 +vn 0.3791 -0.8853 -0.2692 +vn 0.8238 -0.5653 -0.0432 +vn 0.0034 -0.9042 0.4272 +vn -0.4666 -0.4298 0.7730 +vn -0.8679 -0.4847 -0.1089 +vn -0.3657 -0.5934 -0.7171 +vn 0.8674 -0.4799 -0.1315 +vn -0.6969 -0.6974 0.1674 +vn -0.0000 0.5332 -0.8460 +vn 0.0000 0.5222 0.8528 +vn 0.4986 0.0139 -0.8667 +vn -0.5274 -0.0319 -0.8490 +vn -0.9983 0.0578 0.0000 +vn -0.9993 0.0245 0.0297 +vn -0.9992 0.0164 0.0370 +vn -0.9977 -0.0165 0.0664 +vn -0.4505 0.0504 0.8914 +vn 0.5178 -0.0016 0.8555 +vn 0.9990 0.0447 -0.0069 +vn 0.9993 0.0369 0.0000 +vn 0.9989 0.0468 -0.0084 +vn 0.9984 0.0545 -0.0152 +vn 0.1335 -0.9836 -0.1216 +vn 0.1099 -0.9833 -0.1448 +vn 0.1348 -0.9838 -0.1181 +vn 0.1207 -0.9825 -0.1418 +vn 0.1068 -0.9813 -0.1601 +vn 0.1248 -0.9803 -0.1530 +vn 0.1016 -0.9814 -0.1629 +vn 0.0888 -0.9816 -0.1690 +vn 0.1098 -0.9850 -0.1328 +vn 0.2565 -0.9636 0.0750 +vn -0.7169 -0.4268 -0.5512 +vn -0.5632 -0.7248 -0.3969 +vn -0.6896 -0.4008 -0.6031 +vn -0.7713 0.1726 -0.6126 +vn -0.5900 0.6541 -0.4733 +vn -0.1224 0.9635 -0.2381 +vn 0.6632 0.4292 0.6131 +vn 0.7382 -0.1799 0.6501 +vn 0.5751 -0.6503 0.4964 +vn 0.6692 -0.4842 0.5637 +vn 0.9384 0.0031 0.3457 +vn 0.9497 -0.0006 0.3131 +vn 0.9931 -0.0035 -0.1175 +vn 0.9882 0.0084 -0.1527 +vn 0.0908 -0.9829 -0.1605 +vn 0.1215 0.9825 -0.1414 +vn 0.1339 0.9836 -0.1206 +vn 0.1450 0.9834 -0.1092 +vn 0.8419 0.0000 -0.5397 +vn 0.1393 0.9828 -0.1214 +vn 0.1431 0.9828 -0.1171 +vn -0.9877 -0.0166 0.1552 +vn -0.9018 -0.0109 0.4321 +vn 0.2779 -0.0074 0.9606 +vn 0.0999 -0.0181 0.9948 +vn 0.6747 -0.0046 0.7381 +vn 0.4023 0.0088 -0.9155 +vn 0.5126 -0.0023 -0.8587 +vn 0.0843 -0.0100 -0.9964 +vn -0.2653 0.0180 -0.9640 +vn -0.8180 0.0133 -0.5751 +vn -0.9246 -0.0052 -0.3808 +vn -0.5680 -0.0149 0.8229 +vn -0.9491 -0.0075 0.3148 +vn -0.1227 0.0057 0.9924 +vn 0.4621 0.0072 0.8868 +vn 0.9286 -0.0094 0.3711 +vn 0.9750 0.0180 -0.2216 +vn -0.3591 0.0417 -0.9324 +vn -0.9873 0.0263 -0.1569 +vn -0.7278 0.0166 0.6856 +vn 0.7992 0.0017 -0.6010 +vn 0.1246 0.9830 -0.1348 +vn 0.1186 0.9825 -0.1437 +vn 0.0935 0.9836 -0.1544 +vn -0.9560 0.0183 -0.2929 +vn 0.0595 -0.0065 0.9982 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 1/1/1 3/3/3 4/4/4 +f 4/4/4 3/3/3 5/5/5 +f 6/6/6 7/7/7 8/8/8 +f 6/6/6 9/9/9 2/2/2 +f 9/9/9 6/6/6 8/8/8 +f 1/1/1 10/10/10 2/2/2 +f 2/2/2 10/10/10 6/6/6 +f 11/11/11 12/12/12 8/8/8 +f 8/8/8 12/12/12 3/3/3 +f 3/3/3 12/12/12 5/5/5 +f 8/8/8 7/7/7 11/11/11 +f 13/13/13 14/14/14 15/15/15 +f 13/13/13 16/16/16 14/14/14 +f 14/14/14 16/16/16 17/17/17 +f 18/18/18 17/17/17 16/16/16 +f 17/17/17 18/18/18 19/19/19 +f 17/17/17 19/19/19 20/20/20 +f 19/19/19 21/21/21 20/20/20 +f 13/13/13 15/15/15 22/22/22 +f 22/22/22 15/15/15 23/23/23 +f 24/24/24 25/25/25 26/26/26 +f 25/25/25 27/27/27 26/26/26 +f 27/27/27 28/28/28 26/26/26 +f 26/26/26 28/28/28 29/29/29 +f 28/28/28 30/30/30 29/29/29 +f 29/29/29 30/30/30 31/31/31 +f 30/30/30 32/32/32 31/31/31 +f 32/32/32 33/33/33 31/31/31 +f 31/31/31 33/33/33 34/34/34 +f 24/24/24 35/35/35 25/25/25 +f 28/28/28 27/27/27 36/36/36 +f 28/28/28 36/36/36 30/30/37 +f 35/35/35 37/37/38 25/25/25 +f 25/25/25 37/37/38 36/36/36 +f 25/25/25 36/36/36 27/27/27 +f 33/33/39 32/32/40 38/38/41 +f 35/35/35 39/39/42 37/37/38 +f 36/36/36 37/37/38 40/40/43 +f 30/30/37 41/41/44 32/32/40 +f 32/32/40 41/41/44 38/38/41 +f 37/37/38 39/39/42 40/40/43 +f 36/36/36 40/40/43 30/30/37 +f 30/30/37 40/40/43 41/41/44 +f 42/42/45 43/43/46 44/44/47 +f 43/43/46 42/42/45 45/45/48 +f 45/45/48 42/42/45 46/46/49 +f 47/47/50 48/48/51 49/49/52 +f 49/49/52 48/48/51 50/50/53 +f 51/51/54 52/52/55 53/53/56 +f 44/44/47 43/43/46 54/54/57 +f 44/44/47 54/54/57 55/55/58 +f 51/51/54 53/53/56 50/50/53 +f 50/50/53 53/53/56 49/49/52 +f 56/56/59 57/57/60 58/58/61 +f 56/56/59 59/59/62 57/57/60 +f 60/60/63 61/61/64 62/62/65 +f 57/57/60 61/61/64 58/58/61 +f 63/63/66 64/64/67 24/24/68 +f 65/65/69 66/66/70 24/24/68 +f 58/58/61 61/61/64 60/60/63 +f 67/67/71 68/68/72 55/55/58 +f 55/55/58 54/54/57 67/67/71 +f 24/24/68 64/64/67 65/65/69 +f 60/60/63 62/62/65 69/69/73 +f 47/47/50 67/67/71 48/48/51 +f 47/47/50 70/70/74 67/67/71 +f 68/68/72 71/71/75 72/72/76 +f 67/67/71 70/70/74 71/71/75 +f 67/67/71 71/71/75 68/68/72 +f 10/10/10 1/1/1 73/73/77 +f 73/73/77 1/1/1 74/74/78 +f 73/73/77 74/74/78 75/75/79 +f 74/74/78 76/76/80 75/75/79 +f 75/75/79 76/76/80 77/77/81 +f 77/77/81 76/76/80 78/78/82 +f 78/78/82 79/79/83 77/77/81 +f 77/77/81 79/79/83 80/80/84 +f 81/81/85 80/80/84 79/79/83 +f 80/80/84 81/81/85 82/82/86 +f 80/80/84 82/82/86 83/83/87 +f 83/83/87 82/82/86 84/84/88 +f 83/83/87 84/84/88 85/85/89 +f 83/83/87 85/85/89 86/86/90 +f 83/83/87 86/86/90 87/87/91 +f 2/2/92 88/88/93 3/3/94 +f 3/3/94 88/88/93 89/89/95 +f 3/3/96 89/89/97 90/90/98 +f 3/3/96 90/90/98 8/8/99 +f 8/8/100 90/90/101 91/91/102 +f 8/8/100 91/91/102 9/9/103 +f 9/9/104 91/91/105 2/2/106 +f 2/2/106 91/91/105 88/88/107 +f 92/92/108 93/93/109 94/94/110 +f 95/95/111 93/93/109 92/92/108 +f 96/96/112 97/97/113 98/98/114 +f 97/97/113 99/99/115 95/95/111 +f 97/97/113 95/95/111 92/92/108 +f 100/100/116 101/101/117 102/102/118 +f 102/102/118 101/101/117 103/103/119 +f 97/97/113 96/96/112 104/104/120 +f 97/97/113 104/104/120 99/99/115 +f 102/102/118 103/103/119 105/105/121 +f 102/102/118 105/105/121 106/106/122 +f 106/106/122 105/105/121 107/107/123 +f 106/106/122 107/107/123 108/108/124 +f 109/109/125 110/110/126 111/111/127 +f 112/112/128 113/113/129 111/111/127 +f 111/111/127 113/113/129 109/109/125 +f 114/114/130 115/115/131 116/116/132 +f 114/114/130 116/116/132 108/108/124 +f 116/116/132 96/96/112 108/108/124 +f 108/108/124 96/96/112 98/98/114 +f 112/112/128 117/117/133 113/113/129 +f 108/108/124 107/107/123 114/114/130 +f 118/118/134 117/117/133 112/112/128 +f 69/69/73 119/119/135 60/60/63 +f 120/120/136 29/29/137 121/121/138 +f 121/121/138 29/29/137 122/122/139 +f 122/122/139 29/29/137 31/31/140 +f 122/122/139 31/31/140 123/123/141 +f 123/123/141 31/31/140 124/124/142 +f 124/124/142 31/31/140 125/125/143 +f 126/126/144 24/24/68 127/127/145 +f 127/127/145 24/24/68 26/26/146 +f 29/29/137 120/120/136 26/26/146 +f 26/26/146 120/120/136 128/128/147 +f 26/26/146 128/128/147 129/129/148 +f 26/26/146 129/129/148 130/130/149 +f 26/26/146 130/130/149 131/131/150 +f 26/26/146 131/131/150 127/127/145 +f 125/125/143 31/31/140 34/34/151 +f 125/125/143 34/34/151 86/86/152 +f 86/86/152 34/34/151 87/87/153 +f 132/132/154 118/118/134 133/133/155 +f 133/133/155 118/118/134 112/112/128 +f 4/4/4 134/134/156 1/1/1 +f 134/134/156 4/4/4 135/135/157 +f 136/136/158 137/137/159 138/138/160 +f 139/139/161 140/140/162 141/141/163 +f 142/142/164 143/143/165 139/139/161 +f 139/139/161 143/143/165 144/144/166 +f 145/145/167 146/146/168 147/147/169 +f 145/145/167 148/148/170 146/146/168 +f 137/137/159 148/148/170 145/145/167 +f 149/149/171 145/145/167 150/150/172 +f 139/139/161 141/141/163 149/149/171 +f 149/149/171 141/141/163 151/151/173 +f 152/152/174 142/142/164 150/150/172 +f 153/153/175 152/152/174 147/147/169 +f 147/147/169 152/152/174 150/150/172 +f 147/147/169 150/150/172 145/145/167 +f 138/138/160 137/137/159 145/145/167 +f 138/138/160 145/145/167 151/151/173 +f 151/151/173 145/145/167 149/149/171 +f 150/150/172 142/142/164 139/139/161 +f 150/150/172 139/139/161 149/149/171 +f 139/139/161 144/144/166 154/154/176 +f 139/139/161 154/154/176 140/140/162 +f 22/22/22 23/23/23 155/155/177 +f 155/155/177 23/23/23 156/156/178 +f 157/157/179 158/158/180 159/159/181 +f 157/157/179 159/159/181 160/160/182 +f 160/160/182 159/159/181 161/161/183 +f 160/160/182 161/161/183 162/162/184 +f 162/162/184 161/161/183 163/163/185 +f 162/162/184 163/163/185 164/164/186 +f 164/164/186 163/163/185 156/156/178 +f 156/156/178 163/163/185 155/155/177 +f 157/157/179 154/154/176 144/144/166 +f 157/157/179 144/144/166 158/158/180 +f 24/24/68 126/126/144 165/165/187 +f 24/24/68 165/165/187 166/166/188 +f 24/24/68 166/166/188 63/63/66 +f 167/167/189 63/63/66 166/166/188 +f 166/166/188 168/168/190 167/167/189 +f 167/167/189 168/168/190 72/72/76 +f 168/168/190 169/169/191 72/72/76 +f 72/72/76 169/169/191 68/68/72 +f 68/68/72 169/169/191 170/170/192 +f 170/170/192 169/169/191 171/171/193 +f 170/170/192 171/171/193 172/172/194 +f 173/173/195 69/69/73 172/172/194 +f 172/172/194 69/69/73 170/170/192 +f 69/69/73 173/173/195 174/174/196 +f 69/69/73 174/174/196 119/119/135 +f 134/134/156 135/135/157 175/175/197 +f 175/175/197 135/135/157 176/176/198 +f 177/177/199 118/118/134 178/178/200 +f 179/179/201 180/180/202 177/177/203 +f 177/177/203 180/180/202 181/181/204 +f 177/177/203 181/181/204 114/114/130 +f 114/114/130 181/181/204 115/115/131 +f 115/115/131 181/181/204 182/182/205 +f 182/182/205 181/181/204 183/183/206 +f 176/176/198 135/135/157 183/183/206 +f 183/183/206 135/135/157 182/182/205 +f 118/118/134 132/132/154 184/184/207 +f 118/118/134 184/184/207 178/178/200 +f 46/46/208 185/185/209 186/186/210 +f 186/186/210 185/185/209 187/187/211 +f 188/188/212 189/189/213 62/62/214 +f 62/62/214 189/189/213 69/69/215 +f 189/189/213 190/190/216 69/69/215 +f 69/69/215 190/190/216 170/170/217 +f 191/191/218 170/170/217 190/190/216 +f 192/192/219 68/68/220 170/170/217 +f 192/192/219 170/170/217 191/191/218 +f 55/55/221 68/68/222 193/193/223 +f 193/193/223 68/68/222 194/194/224 +f 55/55/225 195/195/226 196/196/227 +f 55/55/225 196/196/227 44/44/228 +f 44/44/228 196/196/227 42/42/229 +f 42/42/229 196/196/227 197/197/230 +f 198/198/231 59/59/232 186/186/210 +f 186/186/210 187/187/211 198/198/231 +f 198/198/231 199/199/233 59/59/232 +f 200/200/234 57/57/235 201/201/236 +f 201/201/236 57/57/235 59/59/232 +f 201/201/236 59/59/232 199/199/233 +f 202/202/237 203/203/238 204/204/239 +f 202/202/237 205/205/240 203/203/238 +f 203/203/238 206/206/241 204/204/239 +f 207/207/242 208/208/243 203/203/238 +f 203/203/238 208/208/243 206/206/241 +f 65/65/244 209/209/245 52/52/246 +f 52/52/246 209/209/245 210/210/247 +f 211/211/248 212/212/249 53/53/250 +f 53/53/250 212/212/249 49/49/251 +f 49/49/251 212/212/249 213/213/252 +f 49/49/251 213/213/252 47/47/253 +f 213/213/252 214/214/254 47/47/253 +f 215/215/255 70/70/256 214/214/254 +f 214/214/254 70/70/256 47/47/253 +f 71/71/257 70/70/258 216/216/259 +f 216/216/259 70/70/258 217/217/260 +f 72/72/261 218/218/262 167/167/263 +f 167/167/263 218/218/262 219/219/264 +f 220/220/265 63/63/266 167/167/263 +f 220/220/265 167/167/263 219/219/264 +f 65/65/244 64/64/267 221/221/268 +f 221/221/268 64/64/267 222/222/269 +f 209/209/245 65/65/244 223/223/270 +f 224/224/271 225/225/272 226/226/273 +f 227/227/274 228/228/275 229/229/276 +f 229/229/276 228/228/275 230/230/277 +f 229/229/276 230/230/277 225/225/272 +f 229/229/276 225/225/272 231/231/278 +f 231/231/278 225/225/272 224/224/271 +f 110/110/279 232/232/280 101/101/281 +f 101/101/281 232/232/280 233/233/282 +f 103/103/283 234/234/284 235/235/285 +f 103/103/283 235/235/285 105/105/286 +f 105/105/286 235/235/285 236/236/287 +f 105/105/286 236/236/287 237/237/288 +f 105/105/286 237/237/288 107/107/289 +f 238/238/290 239/239/291 107/107/292 +f 107/107/292 239/239/291 114/114/293 +f 240/240/294 241/241/295 114/114/296 +f 114/114/296 241/241/295 177/177/297 +f 242/242/298 177/177/297 241/241/295 +f 177/177/297 242/242/298 243/243/299 +f 244/244/300 118/118/301 243/243/299 +f 243/243/299 118/118/301 177/177/297 +f 117/117/302 118/118/301 245/245/303 +f 245/245/303 118/118/301 244/244/300 +f 246/246/304 109/109/305 113/113/306 +f 246/246/304 113/113/306 247/247/307 +f 109/109/305 246/246/304 248/248/308 +f 109/109/305 248/248/308 249/249/309 +f 249/249/309 110/110/279 109/109/305 +f 232/232/280 110/110/279 249/249/309 +f 250/250/310 251/251/311 252/252/312 +f 252/252/312 251/251/311 253/253/313 +f 254/254/314 255/255/315 256/256/316 +f 253/253/313 257/257/317 252/252/312 +f 252/252/312 257/257/317 254/254/314 +f 254/254/314 257/257/317 255/255/315 +f 258/258/318 182/182/319 135/135/320 +f 258/258/318 135/135/320 259/259/321 +f 182/182/319 258/258/318 260/260/322 +f 261/261/323 115/115/324 260/260/322 +f 260/260/322 115/115/324 182/182/319 +f 262/262/325 263/263/326 116/116/327 +f 116/116/327 263/263/326 96/96/328 +f 264/264/329 265/265/330 96/96/331 +f 96/96/331 265/265/330 104/104/332 +f 104/104/332 265/265/330 266/266/333 +f 104/104/332 266/266/333 99/99/334 +f 266/266/333 267/267/335 99/99/334 +f 268/268/336 95/95/337 267/267/335 +f 267/267/335 95/95/337 99/99/334 +f 93/93/338 269/269/339 270/270/340 +f 270/270/340 269/269/339 271/271/341 +f 270/270/340 271/271/341 272/272/342 +f 270/270/340 272/272/342 273/273/343 +f 270/270/340 273/273/343 7/7/344 +f 274/274/345 275/275/346 276/276/347 +f 276/276/347 277/277/348 274/274/345 +f 276/276/347 278/278/349 279/279/350 +f 276/276/347 279/279/350 280/280/351 +f 276/276/347 280/280/351 277/277/348 +f 281/281/352 278/278/349 276/276/347 +f 282/282/353 283/283/354 281/281/352 +f 276/276/347 284/284/355 282/282/353 +f 276/276/347 282/282/353 281/281/352 +f 285/285/356 286/286/357 287/287/358 +f 287/287/358 286/286/357 288/288/359 +f 287/287/358 288/288/359 289/289/360 +f 289/289/360 290/290/361 287/287/358 +f 289/289/360 291/291/362 290/290/361 +f 290/290/361 291/291/362 292/292/363 +f 133/133/155 293/293/364 291/291/362 +f 291/291/362 293/293/364 292/292/363 +f 133/133/155 112/112/128 293/293/364 +f 285/285/356 294/294/365 286/286/357 +f 285/285/356 295/295/366 294/294/365 +f 296/296/367 297/297/368 295/295/366 +f 296/296/367 295/295/366 285/285/356 +f 298/298/369 60/60/63 297/297/368 +f 298/298/369 297/297/368 296/296/367 +f 58/58/61 60/60/63 298/298/369 +f 4/4/370 299/299/371 135/135/320 +f 135/135/320 299/299/371 259/259/321 +f 5/5/372 300/300/373 301/301/374 +f 5/5/375 301/301/376 302/302/377 +f 5/5/375 302/302/377 4/4/370 +f 4/4/370 302/302/377 299/299/371 +f 300/300/373 5/5/372 303/303/378 +f 303/303/378 5/5/372 12/12/379 +f 12/12/380 304/304/381 303/303/382 +f 304/304/381 12/12/380 11/11/383 +f 114/114/384 239/239/291 240/240/385 +f 239/239/291 238/238/290 305/305/386 +f 305/305/386 238/238/290 306/306/387 +f 251/251/311 250/250/310 306/306/387 +f 251/251/311 306/306/387 238/238/290 +f 107/107/292 237/237/388 238/238/290 +f 305/305/386 240/240/385 239/239/291 +f 305/305/386 306/306/389 240/240/385 +f 238/238/290 237/237/288 307/307/390 +f 238/238/290 307/307/390 251/251/311 +f 243/243/391 254/254/392 244/244/393 +f 240/240/385 306/306/389 241/241/394 +f 252/252/395 254/254/392 243/243/391 +f 242/242/396 252/252/395 243/243/391 +f 250/250/310 252/252/395 242/242/396 +f 241/241/397 306/306/387 250/250/310 +f 242/242/396 241/241/397 250/250/310 +f 236/236/287 307/307/390 237/237/288 +f 236/236/398 235/235/399 308/308/400 +f 251/251/401 307/307/402 236/236/403 +f 236/236/398 308/308/400 253/253/404 +f 236/236/403 253/253/405 251/251/401 +f 101/101/406 233/233/407 309/309/408 +f 101/101/409 309/309/408 234/234/410 +f 101/101/409 234/234/410 103/103/411 +f 308/308/400 235/235/399 234/234/410 +f 308/308/400 234/234/410 309/309/408 +f 253/253/313 308/308/400 310/310/412 +f 310/310/412 308/308/400 309/309/408 +f 310/310/412 309/309/408 233/233/407 +f 117/117/413 245/245/413 311/311/413 +f 117/117/414 311/311/415 113/113/416 +f 311/311/415 312/312/417 113/113/416 +f 113/113/418 312/312/419 247/247/307 +f 245/245/420 244/244/393 254/254/392 +f 245/245/420 254/254/392 313/313/421 +f 313/313/421 254/254/314 256/256/316 +f 314/314/422 310/310/412 232/232/280 +f 232/232/280 310/310/412 233/233/423 +f 310/310/412 314/314/422 257/257/317 +f 310/310/412 257/257/317 253/253/313 +f 313/313/421 256/256/316 315/315/424 +f 245/245/420 313/313/421 311/311/425 +f 313/313/421 315/315/424 311/311/425 +f 256/256/426 316/316/427 312/312/419 +f 256/256/426 312/312/419 315/315/428 +f 315/315/429 312/312/429 311/311/429 +f 316/316/427 247/247/307 312/312/419 +f 246/246/304 247/247/307 316/316/427 +f 255/255/430 316/316/427 256/256/426 +f 317/317/431 249/249/309 248/248/308 +f 317/317/431 248/248/308 246/246/304 +f 255/255/430 246/246/304 316/316/427 +f 246/246/304 255/255/430 317/317/432 +f 317/317/432 257/257/317 314/314/422 +f 255/255/430 257/257/317 317/317/432 +f 249/249/309 317/317/431 314/314/422 +f 249/249/309 314/314/422 232/232/280 +f 115/115/433 261/261/434 318/318/435 +f 115/115/433 318/318/435 116/116/327 +f 116/116/327 318/318/435 262/262/325 +f 261/261/323 260/260/322 319/319/436 +f 319/319/436 260/260/322 277/277/348 +f 319/319/437 277/277/348 280/280/351 +f 260/260/322 258/258/318 277/277/348 +f 258/258/318 259/259/321 320/320/438 +f 258/258/318 320/320/438 277/277/348 +f 277/277/348 320/320/438 274/274/345 +f 320/320/438 321/321/439 274/274/345 +f 274/274/345 321/321/439 275/275/346 +f 320/320/438 299/299/371 321/321/439 +f 259/259/321 299/299/371 320/320/438 +f 280/280/351 322/322/440 319/319/437 +f 262/262/325 318/318/435 322/322/440 +f 322/322/440 318/318/435 261/261/441 +f 322/322/440 261/261/441 319/319/437 +f 321/321/442 323/323/443 275/275/444 +f 321/321/439 299/299/371 302/302/445 +f 321/321/442 302/302/446 323/323/443 +f 300/300/373 323/323/443 301/301/374 +f 301/301/374 323/323/443 302/302/446 +f 96/96/447 263/263/448 264/264/449 +f 324/324/450 263/263/448 262/262/325 +f 262/262/325 322/322/440 324/324/450 +f 324/324/450 322/322/440 280/280/351 +f 324/324/450 280/280/351 279/279/350 +f 323/323/443 300/300/373 303/303/378 +f 303/303/378 325/325/451 323/323/443 +f 304/304/381 326/326/452 303/303/453 +f 303/303/453 326/326/452 325/325/454 +f 326/326/452 284/284/355 325/325/454 +f 325/325/454 276/276/455 323/323/443 +f 323/323/443 276/276/455 275/275/444 +f 325/325/454 284/284/355 276/276/455 +f 7/7/456 273/273/457 327/327/458 +f 7/7/456 327/327/458 11/11/383 +f 11/11/383 327/327/458 304/304/381 +f 263/263/448 324/324/450 264/264/449 +f 304/304/381 327/327/458 326/326/452 +f 326/326/452 327/327/458 284/284/355 +f 327/327/458 273/273/343 328/328/459 +f 327/327/458 328/328/459 284/284/355 +f 93/93/460 95/95/337 329/329/461 +f 95/95/337 268/268/336 330/330/462 +f 95/95/337 330/330/462 329/329/461 +f 93/93/460 329/329/461 269/269/339 +f 267/267/335 330/330/462 268/268/336 +f 265/265/463 264/264/464 324/324/450 +f 281/281/352 331/331/465 330/330/462 +f 265/265/463 324/324/450 278/278/349 +f 278/278/349 324/324/450 279/279/350 +f 281/281/352 283/283/354 331/331/465 +f 330/330/462 267/267/335 281/281/352 +f 267/267/335 266/266/466 281/281/352 +f 266/266/466 278/278/349 281/281/352 +f 266/266/466 265/265/463 278/278/349 +f 272/272/342 282/282/353 328/328/459 +f 272/272/342 328/328/459 273/273/343 +f 332/332/467 282/282/353 272/272/342 +f 282/282/353 284/284/355 328/328/459 +f 269/269/339 329/329/461 333/333/468 +f 333/333/468 329/329/461 331/331/469 +f 333/333/468 331/331/469 283/283/470 +f 329/329/461 330/330/462 331/331/469 +f 283/283/470 282/282/353 332/332/467 +f 272/272/342 271/271/341 332/332/467 +f 271/271/341 269/269/339 332/332/467 +f 332/332/467 269/269/339 333/333/468 +f 283/283/470 332/332/467 333/333/468 +f 215/215/255 334/334/471 70/70/256 +f 217/217/260 70/70/258 334/334/472 +f 228/228/473 335/335/474 215/215/475 +f 215/215/475 335/335/474 334/334/472 +f 335/335/474 217/217/260 334/334/472 +f 228/228/473 215/215/475 230/230/476 +f 336/336/477 226/226/478 212/212/249 +f 212/212/249 211/211/248 336/336/477 +f 214/214/479 213/213/480 230/230/476 +f 214/214/479 230/230/476 215/215/475 +f 212/212/249 226/226/478 225/225/481 +f 212/212/249 225/225/481 213/213/480 +f 213/213/480 225/225/481 230/230/476 +f 210/210/482 337/337/482 52/52/482 +f 52/52/483 337/337/484 336/336/477 +f 52/52/483 336/336/477 53/53/250 +f 53/53/250 336/336/477 211/211/248 +f 71/71/257 216/216/259 338/338/485 +f 71/71/257 338/338/485 72/72/486 +f 72/72/486 338/338/485 218/218/487 +f 217/217/260 335/335/474 216/216/259 +f 335/335/474 339/339/488 216/216/259 +f 228/228/275 227/227/274 335/335/474 +f 335/335/474 227/227/274 339/339/488 +f 340/340/489 226/226/478 210/210/490 +f 210/210/490 226/226/478 337/337/491 +f 226/226/478 336/336/477 337/337/491 +f 341/341/492 218/218/487 338/338/485 +f 339/339/488 341/341/492 338/338/485 +f 339/339/488 338/338/485 216/216/259 +f 227/227/274 341/341/492 339/339/488 +f 210/210/247 209/209/245 342/342/493 +f 210/210/247 342/342/493 340/340/494 +f 224/224/271 340/340/494 342/342/493 +f 224/224/271 226/226/273 340/340/494 +f 220/220/265 343/343/495 63/63/266 +f 63/63/496 343/343/495 222/222/497 +f 63/63/496 222/222/497 64/64/498 +f 344/344/499 220/220/265 345/345/500 +f 218/218/501 341/341/492 219/219/502 +f 229/229/276 344/344/499 345/345/500 +f 341/341/492 229/229/276 219/219/502 +f 229/229/276 231/231/278 344/344/499 +f 220/220/265 219/219/502 345/345/500 +f 345/345/500 219/219/502 229/229/276 +f 341/341/492 227/227/274 229/229/276 +f 209/209/245 223/223/503 342/342/493 +f 65/65/244 221/221/268 223/223/270 +f 220/220/265 344/344/499 343/343/495 +f 343/343/495 344/344/499 346/346/504 +f 344/344/499 231/231/278 346/346/504 +f 343/343/495 346/346/504 222/222/497 +f 221/221/505 342/342/493 223/223/503 +f 221/221/505 222/222/506 346/346/504 +f 221/221/505 346/346/504 342/342/493 +f 342/342/493 346/346/504 224/224/271 +f 231/231/278 224/224/271 346/346/504 +f 189/189/213 188/188/212 347/347/507 +f 347/347/508 207/207/242 189/189/509 +f 207/207/242 347/347/508 208/208/243 +f 57/57/235 200/200/234 348/348/510 +f 57/57/511 348/348/510 61/61/512 +f 61/61/512 348/348/510 349/349/513 +f 61/61/512 349/349/513 350/350/514 +f 61/61/515 350/350/516 62/62/517 +f 350/350/516 188/188/518 62/62/517 +f 347/347/519 188/188/518 350/350/516 +f 349/349/520 347/347/521 350/350/522 +f 347/347/521 349/349/520 208/208/523 +f 348/348/510 200/200/234 351/351/524 +f 348/348/510 351/351/524 349/349/513 +f 351/351/525 208/208/523 349/349/520 +f 192/192/219 194/194/526 68/68/220 +f 203/203/527 205/205/528 352/352/529 +f 190/190/530 189/189/509 207/207/242 +f 192/192/219 191/191/531 353/353/532 +f 192/192/219 353/353/532 352/352/529 +f 352/352/529 353/353/533 203/203/527 +f 191/191/531 190/190/534 353/353/532 +f 353/353/533 190/190/530 203/203/527 +f 190/190/530 207/207/242 203/203/527 +f 200/200/234 201/201/535 351/351/524 +f 187/187/211 354/354/536 198/198/231 +f 198/198/231 354/354/536 199/199/233 +f 354/354/537 206/206/538 199/199/539 +f 201/201/540 199/199/539 206/206/538 +f 201/201/540 206/206/538 208/208/541 +f 201/201/540 208/208/541 351/351/542 +f 354/354/537 204/204/543 206/206/538 +f 192/192/219 352/352/529 355/355/544 +f 355/355/544 352/352/529 205/205/528 +f 194/194/526 192/192/219 355/355/544 +f 356/356/545 187/187/211 185/185/209 +f 187/187/211 356/356/545 354/354/536 +f 354/354/537 356/356/545 204/204/543 +f 42/42/546 197/197/547 357/357/548 +f 42/42/546 357/357/548 46/46/549 +f 46/46/549 357/357/548 185/185/550 +f 193/193/551 195/195/226 55/55/225 +f 193/193/223 194/194/224 355/355/544 +f 193/193/223 355/355/544 202/202/552 +f 202/202/552 355/355/544 205/205/528 +f 356/356/545 357/357/553 204/204/543 +f 357/357/553 197/197/230 358/358/554 +f 356/356/545 185/185/209 357/357/553 +f 357/357/553 358/358/554 204/204/543 +f 193/193/555 202/202/556 195/195/557 +f 358/358/554 196/196/227 359/359/558 +f 196/196/227 195/195/557 359/359/558 +f 359/359/558 195/195/557 202/202/556 +f 196/196/227 358/358/554 197/197/230 +f 358/358/554 359/359/559 204/204/543 +f 202/202/556 204/204/560 359/359/558 +f 38/38/561 17/17/562 20/20/563 +f 360/360/564 39/39/42 14/14/565 +f 361/361/566 362/362/567 38/38/561 +f 38/38/561 362/362/567 17/17/562 +f 17/17/562 362/362/567 363/363/568 +f 17/17/562 363/363/568 14/14/565 +f 14/14/565 363/363/568 360/360/564 +f 39/39/42 360/360/564 364/364/569 +f 39/39/42 364/364/569 40/40/43 +f 40/40/43 364/364/569 365/365/570 +f 40/40/43 365/365/570 41/41/44 +f 41/41/44 365/365/570 38/38/561 +f 38/38/561 365/365/570 361/361/566 +f 91/91/571 366/366/571 88/88/571 +f 88/88/571 366/366/571 367/367/571 +f 88/88/571 367/367/571 368/368/571 +f 88/88/571 368/368/571 89/89/571 +f 89/89/571 368/368/571 90/90/571 +f 90/90/571 368/368/571 369/369/571 +f 90/90/571 369/369/571 91/91/571 +f 91/91/571 369/369/571 370/370/571 +f 91/91/571 370/370/571 366/366/571 +f 364/364/572 368/368/572 365/365/572 +f 365/365/573 368/368/573 367/367/573 +f 365/365/574 367/367/574 361/361/574 +f 361/361/575 367/367/576 366/366/577 +f 361/361/575 366/366/577 362/362/578 +f 362/362/579 366/366/580 370/370/581 +f 362/362/579 370/370/581 363/363/582 +f 363/363/583 370/370/584 369/369/585 +f 363/363/583 369/369/585 360/360/586 +f 360/360/587 369/369/588 364/364/589 +f 364/364/589 369/369/588 368/368/590 +f 38/38/591 20/20/592 83/83/593 +f 38/38/591 83/83/593 33/33/594 +f 87/87/595 34/34/596 33/33/597 +f 33/33/597 83/83/598 87/87/595 +f 35/35/35 24/24/24 66/66/599 +f 35/35/35 66/66/599 15/15/600 +f 14/14/601 39/39/42 35/35/35 +f 14/14/602 35/35/35 15/15/600 +f 371/371/603 372/372/604 373/373/605 +f 374/374/606 372/372/604 371/371/603 +f 375/375/607 372/372/604 376/376/608 +f 372/372/604 375/375/607 377/377/609 +f 378/378/610 372/372/604 377/377/609 +f 379/379/611 380/380/612 381/381/613 +f 380/380/612 382/382/614 383/383/615 +f 372/372/604 384/384/616 373/373/605 +f 372/372/604 385/385/617 384/384/616 +f 378/378/610 386/386/618 372/372/604 +f 381/381/613 387/387/619 379/379/611 +f 388/388/620 387/387/619 381/381/613 +f 83/83/87 20/20/20 80/80/84 +f 77/77/81 21/21/21 75/75/79 +f 73/73/77 19/19/19 10/10/10 +f 80/80/84 21/21/21 77/77/81 +f 75/75/79 19/19/19 73/73/77 +f 75/75/79 21/21/21 19/19/19 +f 20/20/20 21/21/21 80/80/84 +f 13/13/13 22/22/22 389/389/621 +f 389/389/621 22/22/22 390/390/622 +f 389/389/623 390/390/622 270/270/624 +f 16/16/625 13/13/13 389/389/621 +f 16/16/625 389/389/621 391/391/626 +f 391/391/626 389/389/623 6/6/6 +f 6/6/6 389/389/623 270/270/624 +f 6/6/6 270/270/624 7/7/7 +f 18/18/18 16/16/625 391/391/626 +f 19/19/19 18/18/18 391/391/626 +f 19/19/19 391/391/626 10/10/10 +f 10/10/10 391/391/626 6/6/6 +f 94/94/110 270/270/624 390/390/622 +f 94/94/110 93/93/109 270/270/624 +f 22/22/22 155/155/627 390/390/622 +f 390/390/622 155/155/627 94/94/110 +f 155/155/627 163/163/628 392/392/629 +f 155/155/627 392/392/629 94/94/110 +f 163/163/628 161/161/630 392/392/629 +f 161/161/630 393/393/631 392/392/629 +f 161/161/630 159/159/632 394/394/633 +f 161/161/630 394/394/633 393/393/631 +f 158/158/634 395/395/635 159/159/632 +f 159/159/632 395/395/635 394/394/633 +f 394/394/633 395/395/635 396/396/636 +f 101/101/117 100/100/116 396/396/636 +f 110/110/637 396/396/636 395/395/635 +f 110/110/637 395/395/635 397/397/638 +f 110/110/637 101/101/117 396/396/636 +f 397/397/639 395/395/635 158/158/634 +f 397/397/639 158/158/634 144/144/166 +f 152/152/174 153/153/175 293/293/364 +f 152/152/640 111/111/641 142/142/642 +f 143/143/165 398/398/643 397/397/639 +f 143/143/165 397/397/639 144/144/166 +f 397/397/638 398/398/643 110/110/637 +f 110/110/637 398/398/643 111/111/641 +f 398/398/643 142/142/642 111/111/641 +f 111/111/641 152/152/640 112/112/128 +f 112/112/128 152/152/640 293/293/364 +f 398/398/643 143/143/165 142/142/642 +f 285/285/356 287/287/358 146/146/168 +f 146/146/168 290/290/361 147/147/169 +f 287/287/358 290/290/361 146/146/168 +f 290/290/361 292/292/363 147/147/169 +f 153/153/175 292/292/363 293/293/364 +f 147/147/169 292/292/363 153/153/175 +f 137/137/159 136/136/158 298/298/369 +f 298/298/369 136/136/158 58/58/61 +f 298/298/369 296/296/367 137/137/159 +f 137/137/159 296/296/367 148/148/170 +f 296/296/367 285/285/356 148/148/170 +f 146/146/168 148/148/170 285/285/356 +f 138/138/160 58/58/61 136/136/158 +f 138/138/160 151/151/173 399/399/644 +f 399/399/644 151/151/173 141/141/645 +f 399/399/644 400/400/646 186/186/647 +f 56/56/59 399/399/644 59/59/62 +f 59/59/62 399/399/644 186/186/647 +f 58/58/61 138/138/160 56/56/59 +f 56/56/59 138/138/160 399/399/644 +f 399/399/644 141/141/645 400/400/648 +f 400/400/648 141/141/645 140/140/649 +f 400/400/648 140/140/649 154/154/650 +f 45/45/48 46/46/49 186/186/647 +f 45/45/48 186/186/647 400/400/646 +f 45/45/651 400/400/648 157/157/652 +f 157/157/652 400/400/648 154/154/650 +f 157/157/652 160/160/653 45/45/651 +f 45/45/651 160/160/653 401/401/654 +f 160/160/653 162/162/655 401/401/654 +f 162/162/655 164/164/656 401/401/654 +f 164/164/656 402/402/657 401/401/654 +f 164/164/656 156/156/658 402/402/657 +f 156/156/658 403/403/659 402/402/657 +f 52/52/55 51/51/54 403/403/659 +f 403/403/659 404/404/660 65/65/69 +f 65/65/69 52/52/55 403/403/659 +f 404/404/660 403/403/659 156/156/658 +f 404/404/660 156/156/658 23/23/661 +f 65/65/69 404/404/660 66/66/70 +f 66/66/662 404/404/660 15/15/663 +f 15/15/663 404/404/660 23/23/661 +f 405/405/664 406/406/665 94/94/666 +f 94/94/666 406/406/665 92/92/667 +f 92/92/668 406/406/668 97/97/668 +f 97/97/669 407/407/670 98/98/671 +f 98/98/672 407/407/672 408/408/672 +f 98/98/673 408/408/674 108/108/675 +f 100/100/676 102/102/677 409/409/678 +f 396/396/679 100/100/676 409/409/678 +f 409/409/678 410/410/680 396/396/679 +f 396/396/679 410/410/680 394/394/681 +f 394/394/681 410/410/680 411/411/682 +f 394/394/681 411/411/682 412/412/683 +f 394/394/681 412/412/683 393/393/684 +f 393/393/684 412/412/683 392/392/685 +f 392/392/685 412/412/683 405/405/664 +f 392/392/685 405/405/664 94/94/666 +f 413/413/686 414/414/687 45/45/688 +f 415/415/689 51/51/690 416/416/691 +f 43/43/692 45/45/692 414/414/692 +f 414/414/693 417/417/694 43/43/695 +f 417/417/694 418/418/696 43/43/695 +f 43/43/695 418/418/696 54/54/697 +f 418/418/698 67/67/698 54/54/698 +f 67/67/699 419/419/700 48/48/701 +f 419/419/702 420/420/702 48/48/702 +f 48/48/703 420/420/703 50/50/703 +f 420/420/704 421/421/704 50/50/704 +f 50/50/705 421/421/705 51/51/705 +f 421/421/706 416/416/691 51/51/690 +f 402/402/707 403/403/708 415/415/689 +f 402/402/707 415/415/689 422/422/709 +f 402/402/707 422/422/709 423/423/710 +f 413/413/686 45/45/688 424/424/711 +f 424/424/711 45/45/688 401/401/712 +f 424/424/713 401/401/713 423/423/713 +f 423/423/710 401/401/714 402/402/707 +f 415/415/689 403/403/708 51/51/690 +f 425/425/715 426/426/716 427/427/717 +f 427/427/717 426/426/716 428/428/718 +f 429/429/719 430/430/720 428/428/718 +f 428/428/718 430/430/720 427/427/717 +f 431/431/721 432/432/722 429/429/719 +f 429/429/719 432/432/722 430/430/720 +f 433/433/723 432/432/722 431/431/721 +f 372/372/604 433/433/723 431/431/721 +f 372/372/604 381/381/613 433/433/723 +f 434/434/724 435/435/725 436/436/726 +f 434/434/724 436/436/726 437/437/727 +f 437/437/727 436/436/726 438/438/728 +f 438/438/728 439/439/729 437/437/727 +f 438/438/728 440/440/730 439/439/729 +f 438/438/728 441/441/731 440/440/730 +f 442/442/732 443/443/733 441/441/731 +f 441/441/731 443/443/733 440/440/730 +f 442/442/732 444/444/734 443/443/733 +f 445/445/735 444/444/734 442/442/732 +f 446/446/736 444/444/734 445/445/735 +f 444/444/734 446/446/736 447/447/737 +f 446/446/736 448/448/738 449/449/739 +f 450/450/740 446/446/736 451/451/741 +f 452/452/742 453/453/743 454/454/744 +f 454/454/744 453/453/743 455/455/745 +f 450/450/740 451/451/741 456/456/746 +f 456/456/746 451/451/741 457/457/747 +f 457/457/747 451/451/741 452/452/742 +f 457/457/747 452/452/742 458/458/748 +f 458/458/748 452/452/742 454/454/744 +f 459/459/749 460/460/750 456/456/746 +f 459/459/749 456/456/746 461/461/751 +f 461/461/751 456/456/746 462/462/752 +f 462/462/752 458/458/748 463/463/753 +f 463/463/753 458/458/748 464/464/754 +f 464/464/754 465/465/755 466/466/756 +f 461/461/751 462/462/752 467/467/757 +f 467/467/757 462/462/752 463/463/753 +f 468/468/758 464/464/754 466/466/756 +f 467/467/757 463/463/753 469/469/759 +f 469/469/759 463/463/753 464/464/754 +f 469/469/759 464/464/754 468/468/758 +f 435/435/725 455/455/745 453/453/743 +f 435/435/725 453/453/743 436/436/726 +f 436/436/726 453/453/743 438/438/728 +f 438/438/728 453/453/743 452/452/742 +f 438/438/728 452/452/742 441/441/731 +f 441/441/731 452/452/742 451/451/741 +f 441/441/731 451/451/741 442/442/732 +f 442/442/732 451/451/741 445/445/735 +f 445/445/735 451/451/741 446/446/736 +f 460/460/750 450/450/740 456/456/746 +f 458/458/748 454/454/744 470/470/760 +f 470/470/760 454/454/744 455/455/745 +f 470/470/760 455/455/745 465/465/755 +f 465/465/755 464/464/754 470/470/760 +f 470/470/760 464/464/754 458/458/748 +f 458/458/748 462/462/752 457/457/747 +f 457/457/747 462/462/752 456/456/746 +f 468/468/758 466/466/756 372/372/604 +f 459/459/749 461/461/751 426/426/716 +f 426/426/716 461/461/751 467/467/757 +f 426/426/716 467/467/757 428/428/718 +f 428/428/718 467/467/757 469/469/759 +f 428/428/718 469/469/759 429/429/719 +f 429/429/719 469/469/759 431/431/721 +f 431/431/721 469/469/759 468/468/758 +f 431/431/721 468/468/758 372/372/604 +f 471/471/761 472/472/762 473/473/763 +f 474/474/764 475/475/765 432/432/766 +f 432/432/766 475/475/765 476/476/767 +f 471/471/761 475/475/765 472/472/762 +f 477/477/768 425/425/715 473/473/763 +f 471/471/761 476/476/767 475/475/765 +f 381/381/613 474/474/764 433/433/723 +f 433/433/723 474/474/764 432/432/766 +f 430/430/720 476/476/767 471/471/761 +f 471/471/761 473/473/763 427/427/717 +f 425/425/715 427/427/717 473/473/763 +f 471/471/761 427/427/717 430/430/720 +f 476/476/767 430/430/720 432/432/722 +f 444/444/769 478/478/770 443/443/771 +f 440/440/730 479/479/772 439/439/729 +f 479/479/772 480/480/773 481/481/774 +f 439/439/729 481/481/774 482/482/775 +f 447/447/776 483/483/777 444/444/769 +f 444/444/769 483/483/777 478/478/770 +f 479/479/772 481/481/774 439/439/729 +f 439/439/729 482/482/775 437/437/778 +f 437/437/778 482/482/775 484/484/779 +f 484/484/779 434/434/724 437/437/778 +f 479/479/772 440/440/780 480/480/773 +f 480/480/773 440/440/780 443/443/771 +f 480/480/773 443/443/771 478/478/770 +f 485/485/571 486/486/571 487/487/571 +f 487/487/571 486/486/571 488/488/571 +f 487/487/571 488/488/571 489/489/571 +f 489/489/571 488/488/571 490/490/571 +f 491/491/571 492/492/571 493/493/571 +f 491/491/571 493/493/571 485/485/571 +f 485/485/571 493/493/571 486/486/571 +f 494/494/571 495/495/571 496/496/571 +f 496/496/571 495/495/571 497/497/571 +f 496/496/571 497/497/571 492/492/571 +f 496/496/571 492/492/571 491/491/571 +f 498/498/571 499/499/571 500/500/571 +f 498/498/571 500/500/571 501/501/571 +f 501/501/571 500/500/571 495/495/571 +f 501/501/571 495/495/571 494/494/571 +f 489/489/571 490/490/571 502/502/571 +f 489/489/571 502/502/571 498/498/571 +f 498/498/571 502/502/571 499/499/571 +f 503/503/781 500/500/782 504/504/783 +f 504/504/783 500/500/782 499/499/784 +f 504/504/783 499/499/784 502/502/785 +f 504/504/783 502/502/785 505/505/786 +f 505/505/787 502/502/788 490/490/789 +f 505/505/787 490/490/789 506/506/790 +f 506/506/791 490/490/791 488/488/791 +f 506/506/792 488/488/792 507/507/792 +f 507/507/793 488/488/793 486/486/793 +f 507/507/794 486/486/795 508/508/796 +f 508/508/796 486/486/795 509/509/797 +f 509/509/797 486/486/795 493/493/798 +f 509/509/799 493/493/800 492/492/801 +f 509/509/799 492/492/801 510/510/802 +f 510/510/803 492/492/804 497/497/805 +f 510/510/803 497/497/805 511/511/806 +f 511/511/806 497/497/805 495/495/807 +f 511/511/806 495/495/807 512/512/808 +f 512/512/809 495/495/809 503/503/809 +f 503/503/810 495/495/810 500/500/810 +f 513/513/811 510/510/811 511/511/811 +f 514/514/811 512/512/811 503/503/811 +f 514/514/811 503/503/811 515/515/811 +f 513/513/811 511/511/811 512/512/811 +f 513/513/811 512/512/811 514/514/811 +f 516/516/811 509/509/811 513/513/811 +f 513/513/811 509/509/811 510/510/811 +f 516/516/811 508/508/811 509/509/811 +f 517/517/811 507/507/811 516/516/811 +f 516/516/811 507/507/811 508/508/811 +f 518/518/811 505/505/811 519/519/811 +f 519/519/811 505/505/811 506/506/811 +f 519/519/811 506/506/811 517/517/811 +f 517/517/811 506/506/811 507/507/811 +f 520/520/811 504/504/811 518/518/811 +f 518/518/811 504/504/811 505/505/811 +f 515/515/811 503/503/811 520/520/811 +f 520/520/811 503/503/811 504/504/811 +f 521/521/811 522/522/811 523/523/811 +f 521/521/811 523/523/811 524/524/811 +f 521/521/811 524/524/811 525/525/811 +f 526/526/811 527/527/811 528/528/811 +f 528/528/811 527/527/811 522/522/811 +f 528/528/811 522/522/811 521/521/811 +f 529/529/811 530/530/811 531/531/811 +f 531/531/811 530/530/811 532/532/811 +f 531/531/811 532/532/811 526/526/811 +f 526/526/811 532/532/811 527/527/811 +f 533/533/811 534/534/811 535/535/811 +f 535/535/811 534/534/811 536/536/811 +f 535/535/811 536/536/811 529/529/811 +f 529/529/811 536/536/811 530/530/811 +f 525/525/811 524/524/811 537/537/811 +f 525/525/811 537/537/811 538/538/811 +f 538/538/811 537/537/811 539/539/811 +f 538/538/811 539/539/811 533/533/811 +f 533/533/811 539/539/811 534/534/811 +f 540/540/812 536/536/812 541/541/812 +f 541/541/813 536/536/813 534/534/813 +f 541/541/814 534/534/814 542/542/814 +f 542/542/815 534/534/815 539/539/815 +f 542/542/816 539/539/817 537/537/818 +f 542/542/816 537/537/818 543/543/819 +f 543/543/820 537/537/821 524/524/822 +f 543/543/820 524/524/822 544/544/823 +f 544/544/824 524/524/825 545/545/826 +f 545/545/826 524/524/825 523/523/827 +f 545/545/826 523/523/827 522/522/828 +f 545/545/829 522/522/829 546/546/829 +f 546/546/830 522/522/830 527/527/830 +f 546/546/831 527/527/831 547/547/831 +f 547/547/832 527/527/833 532/532/834 +f 547/547/832 532/532/834 548/548/835 +f 548/548/836 532/532/837 530/530/838 +f 548/548/836 530/530/838 549/549/839 +f 549/549/839 530/530/838 540/540/840 +f 540/540/840 530/530/838 536/536/841 +f 550/550/571 540/540/571 551/551/571 +f 551/551/571 540/540/571 541/541/571 +f 552/552/571 548/548/571 549/549/571 +f 552/552/571 549/549/571 550/550/571 +f 550/550/571 549/549/571 540/540/571 +f 553/553/571 547/547/571 552/552/571 +f 552/552/571 547/547/571 548/548/571 +f 554/554/571 546/546/571 553/553/571 +f 553/553/571 546/546/571 547/547/571 +f 554/554/571 545/545/571 546/546/571 +f 555/555/571 543/543/571 556/556/571 +f 543/543/571 544/544/571 556/556/571 +f 556/556/571 544/544/571 545/545/571 +f 556/556/571 545/545/571 554/554/571 +f 557/557/571 542/542/571 555/555/571 +f 555/555/571 542/542/571 543/543/571 +f 551/551/571 541/541/571 542/542/571 +f 551/551/571 542/542/571 557/557/571 +f 489/489/842 525/525/843 538/538/844 +f 489/489/845 538/538/846 533/533/847 +f 487/487/848 533/533/847 535/535/849 +f 485/485/850 535/535/849 529/529/851 +f 491/491/852 529/529/851 531/531/853 +f 496/496/854 531/531/853 526/526/855 +f 496/496/856 526/526/857 528/528/858 +f 501/501/859 528/528/860 521/521/861 +f 498/498/862 521/521/861 525/525/843 +f 555/555/863 519/519/864 557/557/865 +f 556/556/866 518/518/867 555/555/868 +f 554/554/869 520/520/870 556/556/871 +f 553/553/872 514/514/873 554/554/874 +f 552/552/875 513/513/876 553/553/872 +f 550/550/877 516/516/878 552/552/879 +f 551/551/880 516/516/881 550/550/882 +f 557/557/883 517/517/884 551/551/885 +f 558/558/886 559/559/886 560/560/886 +f 561/561/887 559/559/888 558/558/889 +f 562/562/890 563/563/890 561/561/890 +f 563/563/891 562/562/891 564/564/891 +f 562/562/892 565/565/892 564/564/892 +f 566/566/893 567/567/894 568/568/895 +f 567/567/896 566/566/896 569/569/896 +f 570/570/897 571/571/897 572/572/897 +f 573/573/898 574/574/898 571/571/898 +f 573/573/899 575/575/900 574/574/901 +f 569/569/902 575/575/902 573/573/902 +f 569/569/903 566/566/904 575/575/905 +f 576/576/906 577/577/907 578/578/908 +f 578/578/908 577/577/907 579/579/909 +f 578/578/908 579/579/909 580/580/910 +f 580/580/910 579/579/909 581/581/911 +f 581/581/911 579/579/909 582/582/912 +f 581/581/911 582/582/912 583/583/913 +f 582/582/912 584/584/914 583/583/913 +f 583/583/913 584/584/914 585/585/915 +f 585/585/915 584/584/914 586/586/916 +f 585/585/915 586/586/916 587/587/917 +f 587/587/917 586/586/916 588/588/918 +f 587/587/917 588/588/918 589/589/919 +f 589/589/919 588/588/918 576/576/906 +f 576/576/906 588/588/918 577/577/907 +f 590/590/920 587/587/921 589/589/922 +f 590/590/920 589/589/922 591/591/923 +f 591/591/924 589/589/925 592/592/926 +f 592/592/926 589/589/925 576/576/927 +f 592/592/928 576/576/929 578/578/930 +f 592/592/928 578/578/930 593/593/931 +f 593/593/932 578/578/933 594/594/934 +f 594/594/934 578/578/933 580/580/935 +f 594/594/936 580/580/936 581/581/936 +f 594/594/937 581/581/937 595/595/937 +f 595/595/938 581/581/938 583/583/938 +f 595/595/939 583/583/940 596/596/941 +f 596/596/941 583/583/940 585/585/942 +f 596/596/943 585/585/944 590/590/945 +f 590/590/945 585/585/944 587/587/946 +f 597/597/811 595/595/811 598/598/811 +f 598/598/811 595/595/811 596/596/811 +f 598/598/811 596/596/811 599/599/811 +f 599/599/811 596/596/811 590/590/811 +f 599/599/811 590/590/811 591/591/811 +f 599/599/811 591/591/811 600/600/811 +f 601/601/811 593/593/811 597/597/811 +f 597/597/811 593/593/811 594/594/811 +f 597/597/811 594/594/811 595/595/811 +f 600/600/811 591/591/811 592/592/811 +f 600/600/811 592/592/811 601/601/811 +f 601/601/811 592/592/811 593/593/811 +f 602/602/947 599/599/948 603/603/949 +f 603/603/949 599/599/948 600/600/950 +f 603/603/951 600/600/952 604/604/953 +f 604/604/953 600/600/952 601/601/954 +f 604/604/955 601/601/956 597/597/957 +f 604/604/955 597/597/957 605/605/958 +f 605/605/959 597/597/959 606/606/959 +f 606/606/960 597/597/961 598/598/962 +f 606/606/960 598/598/962 607/607/963 +f 607/607/964 598/598/965 599/599/966 +f 607/607/964 599/599/966 602/602/967 +f 605/605/968 608/608/969 609/609/970 +f 605/605/968 609/609/970 604/604/971 +f 604/604/971 609/609/970 603/603/972 +f 603/603/973 609/609/973 610/610/973 +f 610/610/974 611/611/975 603/603/976 +f 603/603/976 611/611/975 602/602/977 +f 602/602/977 611/611/975 612/612/978 +f 602/602/977 612/612/978 613/613/979 +f 602/602/977 613/613/979 607/607/980 +f 607/607/980 613/613/979 606/606/981 +f 613/613/979 614/614/982 606/606/981 +f 606/606/981 614/614/982 608/608/969 +f 606/606/981 608/608/969 605/605/968 +f 615/615/983 608/608/983 614/614/983 +f 616/616/984 612/612/984 611/611/984 +f 617/617/985 616/616/986 618/618/987 +f 617/617/985 612/612/988 616/616/986 +f 619/619/989 612/612/990 617/617/991 +f 619/619/989 613/613/992 612/612/990 +f 613/613/993 619/619/993 614/614/993 +f 614/614/994 619/619/994 615/615/994 +f 615/615/995 619/619/996 562/562/997 +f 562/562/998 608/608/999 615/615/1000 +f 561/561/1001 608/608/999 562/562/998 +f 561/561/1002 609/609/1002 608/608/1002 +f 609/609/1003 561/561/887 558/558/889 +f 609/609/1003 558/558/889 610/610/1004 +f 560/560/1005 611/611/1006 558/558/1007 +f 558/558/1007 611/611/1006 610/610/1008 +f 618/618/987 616/616/986 611/611/1009 +f 618/618/987 611/611/1009 560/560/1010 +f 569/569/1011 571/571/1012 570/570/1013 +f 569/569/1011 573/573/1014 571/571/1012 +f 620/620/1015 567/567/1016 569/569/1011 +f 569/569/1011 570/570/1013 620/620/1015 +f 621/621/1017 622/622/1018 566/566/1019 +f 623/623/1020 624/624/1021 625/625/1022 +f 626/626/1023 627/627/1024 628/628/1025 +f 629/629/1026 630/630/1026 631/631/1026 +f 632/632/1027 633/633/1028 634/634/1029 +f 635/635/1030 636/636/1031 637/637/1032 +f 636/636/1033 638/638/1034 637/637/1035 +f 639/639/1036 640/640/1037 641/641/1038 +f 640/640/1039 642/642/1040 643/643/1041 +f 644/644/1042 645/645/1043 646/646/1044 +f 625/625/1022 647/647/1045 623/623/1020 +f 648/648/1046 649/649/1047 650/650/1048 +f 575/575/905 566/566/904 651/651/1049 +f 652/652/1050 574/574/901 575/575/900 +f 574/574/1051 653/653/1052 654/654/1053 +f 654/654/1053 571/571/1054 574/574/1051 +f 572/572/1055 571/571/1055 654/654/1055 +f 655/655/1056 656/656/1057 648/648/1046 +f 657/657/1058 658/658/1059 656/656/1057 +f 626/626/1060 628/628/1061 659/659/1062 +f 659/659/1062 628/628/1061 660/660/1063 +f 661/661/1064 662/662/1065 663/663/1066 +f 664/664/1067 665/665/1068 661/661/1064 +f 666/666/1069 667/667/1070 624/624/1021 +f 644/644/1071 668/668/1072 642/642/1073 +f 642/642/1073 668/668/1072 669/669/1074 +f 670/670/1075 639/639/1036 641/641/1038 +f 637/637/1035 638/638/1034 671/671/1076 +f 672/672/1077 633/633/1077 635/635/1077 +f 634/634/1029 633/633/1028 672/672/1078 +f 673/673/1079 632/632/1080 634/634/1081 +f 629/629/1082 631/631/1082 674/674/1082 +f 568/568/1083 675/675/1084 621/621/1085 +f 565/565/1086 562/562/997 619/619/996 +f 565/565/1087 619/619/1088 676/676/1089 +f 676/676/1089 619/619/1088 617/617/1090 +f 676/676/1091 617/617/1091 618/618/1091 +f 676/676/1092 618/618/1092 649/649/1092 +f 649/649/1093 618/618/1093 650/650/1093 +f 650/650/1048 677/677/1094 648/648/1046 +f 648/648/1046 677/677/1094 655/655/1056 +f 656/656/1057 655/655/1056 657/657/1058 +f 658/658/1059 657/657/1058 659/659/1062 +f 658/658/1059 659/659/1062 660/660/1063 +f 628/628/1025 627/627/1024 662/662/1065 +f 662/662/1065 627/627/1024 663/663/1066 +f 661/661/1064 663/663/1066 664/664/1067 +f 665/665/1068 664/664/1067 678/678/1095 +f 665/665/1068 678/678/1095 647/647/1096 +f 678/678/1097 623/623/1020 647/647/1045 +f 625/625/1022 624/624/1021 667/667/1070 +f 666/666/1069 679/679/1098 667/667/1070 +f 666/666/1099 646/646/1044 679/679/1100 +f 679/679/1100 646/646/1044 645/645/1043 +f 646/646/1044 668/668/1101 644/644/1042 +f 642/642/1040 669/669/1102 643/643/1041 +f 640/640/1037 643/643/1103 641/641/1038 +f 641/641/1038 671/671/1104 670/670/1075 +f 670/670/1075 671/671/1104 638/638/1105 +f 637/637/1032 680/680/1106 635/635/1030 +f 680/680/1107 672/672/1107 635/635/1107 +f 632/632/1080 673/673/1079 681/681/1108 +f 673/673/1109 682/682/1110 681/681/1111 +f 681/681/1111 682/682/1110 630/630/1112 +f 682/682/1113 631/631/1113 630/630/1113 +f 629/629/1114 674/674/1114 683/683/1114 +f 674/674/1115 684/684/1116 683/683/1117 +f 683/683/1117 684/684/1116 675/675/1118 +f 684/684/1119 621/621/1085 675/675/1084 +f 621/621/1017 566/566/1019 568/568/1120 +f 622/622/1018 651/651/1121 566/566/1019 +f 651/651/1122 652/652/1122 575/575/1122 +f 652/652/1123 653/653/1052 574/574/1051 +f 572/572/1124 620/620/1124 570/570/1124 +f 676/676/1125 649/649/1126 663/663/1127 +f 564/564/1128 626/626/1129 659/659/1130 +f 655/655/1131 561/561/1132 563/563/1133 +f 559/559/888 561/561/887 677/677/1134 +f 559/559/1135 650/650/1136 560/560/1137 +f 560/560/1137 650/650/1136 618/618/1138 +f 559/559/1139 677/677/1139 650/650/1139 +f 655/655/1131 677/677/1140 561/561/1132 +f 657/657/1141 655/655/1131 563/563/1133 +f 659/659/1130 657/657/1142 563/563/1143 +f 659/659/1130 563/563/1143 564/564/1128 +f 664/664/1144 649/649/1145 648/648/1146 +f 669/669/1147 668/668/1148 665/665/1149 +f 669/669/1150 665/665/1150 643/643/1150 +f 625/625/1151 641/641/1152 647/647/1153 +f 671/671/1154 667/667/1154 679/679/1154 +f 680/680/1155 645/645/1156 644/644/1157 +f 680/680/1155 644/644/1157 672/672/1158 +f 634/634/1159 672/672/1160 642/642/1161 +f 640/640/1162 634/634/1159 642/642/1161 +f 634/634/1159 640/640/1162 673/673/1163 +f 673/673/1163 640/640/1162 639/639/1164 +f 631/631/1165 636/636/1165 674/674/1165 +f 674/674/1166 636/636/1166 635/635/1166 +f 621/621/1167 684/684/1167 633/633/1167 +f 632/632/1168 622/622/1168 621/621/1168 +f 651/651/1169 622/622/1170 681/681/1171 +f 651/651/1169 630/630/1172 652/652/1173 +f 629/629/1174 653/653/1175 652/652/1176 +f 654/654/1177 683/683/1178 572/572/1179 +f 675/675/1180 572/572/1179 683/683/1178 +f 572/572/1181 675/675/1182 620/620/1183 +f 568/568/895 567/567/894 620/620/1184 +f 565/565/1185 626/626/1129 564/564/1128 +f 676/676/1125 627/627/1186 565/565/1185 +f 565/565/1185 627/627/1186 626/626/1129 +f 627/627/1186 676/676/1125 663/663/1127 +f 663/663/1187 649/649/1187 664/664/1187 +f 664/664/1144 648/648/1146 678/678/1188 +f 648/648/1189 623/623/1190 678/678/1191 +f 648/648/1189 656/656/1192 623/623/1190 +f 623/623/1190 656/656/1192 624/624/1193 +f 656/656/1192 658/658/1194 624/624/1193 +f 660/660/1195 666/666/1196 658/658/1194 +f 658/658/1194 666/666/1196 624/624/1193 +f 628/628/1197 666/666/1198 660/660/1199 +f 666/666/1198 628/628/1197 646/646/1200 +f 628/628/1201 662/662/1202 646/646/1203 +f 646/646/1203 662/662/1202 668/668/1204 +f 661/661/1205 668/668/1204 662/662/1202 +f 661/661/1206 665/665/1149 668/668/1148 +f 665/665/1207 647/647/1207 643/643/1207 +f 643/643/1208 647/647/1153 641/641/1152 +f 667/667/1209 671/671/1210 625/625/1211 +f 625/625/1211 671/671/1210 641/641/1212 +f 671/671/1213 679/679/1213 637/637/1213 +f 637/637/1214 679/679/1215 645/645/1156 +f 637/637/1214 645/645/1156 680/680/1155 +f 644/644/1157 642/642/1216 672/672/1158 +f 670/670/1217 673/673/1163 639/639/1164 +f 673/673/1163 670/670/1217 682/682/1218 +f 670/670/1217 638/638/1219 682/682/1218 +f 682/682/1218 638/638/1219 631/631/1220 +f 636/636/1221 631/631/1221 638/638/1221 +f 674/674/1222 635/635/1222 684/684/1222 +f 635/635/1223 633/633/1223 684/684/1223 +f 632/632/1224 621/621/1224 633/633/1224 +f 632/632/1225 681/681/1225 622/622/1225 +f 630/630/1172 651/651/1169 681/681/1171 +f 630/630/1226 629/629/1226 652/652/1226 +f 653/653/1175 629/629/1174 654/654/1177 +f 629/629/1174 683/683/1178 654/654/1177 +f 620/620/1183 675/675/1182 568/568/1227 +f 586/586/1228 685/685/1228 686/686/1228 +f 686/686/571 685/685/571 687/687/571 +f 686/686/571 687/687/571 688/688/571 +f 688/688/1229 687/687/1229 579/579/1229 +f 588/588/1230 586/586/1230 686/686/1230 +f 586/586/1231 584/584/1231 685/685/1231 +f 685/685/1232 584/584/1233 687/687/1234 +f 687/687/1234 584/584/1233 582/582/1235 +f 687/687/1236 582/582/1236 579/579/1236 +f 579/579/1237 577/577/1237 688/688/1237 +f 588/588/1238 686/686/1239 688/688/1240 +f 688/688/1240 577/577/1241 588/588/1238 +f 689/689/1242 460/460/750 690/690/1243 +f 689/689/1242 450/450/1244 460/460/750 +f 691/691/1245 446/446/736 449/449/739 +f 689/689/1242 446/446/736 450/450/1244 +f 448/448/738 446/446/736 689/689/1242 +f 426/426/1246 692/692/1247 693/693/1248 +f 694/694/1249 426/426/1246 693/693/1248 +f 695/695/1250 446/446/736 691/691/1245 +f 447/447/737 446/446/736 695/695/1250 +f 696/696/1251 426/426/1246 425/425/715 +f 696/696/1251 692/692/1247 426/426/1246 +f 697/697/1252 483/483/777 695/695/1253 +f 483/483/777 697/697/1252 478/478/1254 +f 478/478/1254 697/697/1252 480/480/773 +f 698/698/1255 480/480/773 697/697/1252 +f 698/698/1255 481/481/774 480/480/773 +f 699/699/1256 482/482/775 698/698/1255 +f 698/698/1255 482/482/775 481/481/774 +f 699/699/1256 484/484/779 482/482/775 +f 699/699/1256 700/700/1257 484/484/779 +f 701/701/1258 474/474/764 380/380/612 +f 701/701/1258 475/475/765 474/474/764 +f 702/702/1259 475/475/765 701/701/1258 +f 702/702/1259 472/472/762 475/475/765 +f 703/703/1260 473/473/1261 702/702/1259 +f 702/702/1259 473/473/1261 472/472/762 +f 703/703/1260 477/477/768 473/473/1261 +f 703/703/1260 696/696/1251 477/477/768 +f 425/425/715 477/477/768 696/696/1251 +f 381/381/613 380/380/612 474/474/764 +f 434/434/724 484/484/779 700/700/1257 +f 447/447/776 695/695/1253 483/483/777 +f 409/409/1262 417/417/694 414/414/1263 +f 413/413/1264 410/410/1265 414/414/1263 +f 459/459/749 694/694/1249 704/704/1266 +f 426/426/1246 694/694/1249 459/459/749 +f 690/690/1243 459/459/749 704/704/1266 +f 690/690/1243 460/460/750 459/459/749 +f 435/435/725 705/705/1267 706/706/1268 +f 707/707/1269 435/435/725 706/706/1268 +f 424/424/1270 410/410/1265 413/413/1264 +f 455/455/1271 707/707/1269 708/708/1272 +f 407/407/670 421/421/1273 420/420/1274 +f 408/408/674 420/420/1274 419/419/700 +f 108/108/675 419/419/700 67/67/699 +f 106/106/1275 67/67/1276 418/418/696 +f 102/102/1277 418/418/696 417/417/694 +f 412/412/1278 424/424/1270 423/423/1279 +f 422/422/1280 412/412/1278 423/423/1279 +f 405/405/1281 422/422/1280 415/415/689 +f 406/406/1282 415/415/689 416/416/691 +f 406/406/1282 416/416/691 421/421/1283 +f 435/435/725 707/707/1269 455/455/1271 +f 487/487/848 489/489/845 533/533/847 +f 485/485/850 487/487/848 535/535/849 +f 529/529/851 491/491/852 485/485/850 +f 496/496/854 491/491/852 531/531/853 +f 494/494/1284 496/496/856 528/528/858 +f 501/501/859 494/494/1285 528/528/860 +f 498/498/862 501/501/859 521/521/861 +f 489/489/842 498/498/862 525/525/843 +f 555/555/863 518/518/1286 519/519/864 +f 556/556/866 520/520/1287 518/518/867 +f 554/554/869 515/515/1288 520/520/870 +f 554/554/874 514/514/873 515/515/1289 +f 553/553/872 513/513/876 514/514/873 +f 552/552/879 516/516/878 513/513/1290 +f 551/551/880 517/517/1291 516/516/881 +f 557/557/883 519/519/1292 517/517/884 +f 409/409/1262 102/102/1277 417/417/694 +f 411/411/1293 410/410/1265 424/424/1270 +f 414/414/1263 410/410/1265 409/409/1262 +f 709/709/1294 455/455/1271 708/708/1272 +f 709/709/1294 465/465/1295 455/455/1271 +f 376/376/608 465/465/1295 709/709/1294 +f 376/376/608 466/466/1296 465/465/1295 +f 700/700/1257 435/435/725 434/434/724 +f 700/700/1257 705/705/1267 435/435/725 +f 97/97/1297 406/406/1282 421/421/1283 +f 407/407/670 97/97/669 421/421/1273 +f 408/408/674 407/407/670 420/420/1274 +f 108/108/675 408/408/674 419/419/700 +f 106/106/1275 108/108/1298 67/67/1276 +f 102/102/1277 106/106/1275 418/418/696 +f 412/412/1278 411/411/1293 424/424/1270 +f 405/405/1281 412/412/1278 422/422/1280 +f 406/406/1282 405/405/1281 415/415/689 +f 374/374/606 381/381/613 372/372/604 +f 388/388/620 381/381/613 374/374/606 +f 376/376/608 372/372/604 466/466/1296 +f 379/379/611 382/382/614 380/380/612 +f 385/385/617 372/372/604 386/386/618 diff --git a/examples/Cassie/urdf/meshes/agility/heel-spring.obj b/examples/Cassie/urdf/meshes/agility/heel-spring.obj new file mode 100644 index 0000000000..7fe1a97321 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/heel-spring.obj @@ -0,0 +1,3246 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o heel-spring +v 0.124673 -0.024882 -0.010098 +v 0.124657 -0.024899 -0.007598 +v 0.112896 -0.024910 -0.010098 +v 0.112875 -0.024891 -0.007598 +v 0.112886 0.024904 -0.007598 +v 0.112869 0.024885 -0.010098 +v 0.124647 0.024922 -0.010098 +v 0.124667 0.024900 -0.007598 +v 0.119162 -0.006220 -0.013398 +v 0.119425 -0.005466 -0.013396 +v 0.120908 -0.006304 -0.013393 +v 0.116995 -0.007020 -0.013398 +v 0.116516 -0.006415 -0.013393 +v 0.117837 -0.005567 -0.013385 +v 0.120546 -0.009973 -0.013398 +v 0.121622 -0.009686 -0.013395 +v 0.120139 -0.011245 -0.013391 +v 0.120937 -0.007697 -0.013398 +v 0.121769 -0.007774 -0.013395 +v 0.115805 -0.007591 -0.013376 +v 0.116490 -0.010572 -0.013389 +v 0.115763 -0.008986 -0.013397 +v 0.116604 -0.009296 -0.013398 +v 0.118101 -0.011543 -0.013396 +v 0.118380 -0.010773 -0.013398 +v 0.121396 -0.009874 0.005817 +v 0.121759 -0.008307 0.005818 +v 0.121147 -0.006782 0.005885 +v 0.120151 -0.011174 0.005818 +v 0.117893 -0.011378 0.005818 +v 0.116455 -0.010348 0.005817 +v 0.115764 -0.008685 0.005818 +v 0.116307 -0.006824 0.005817 +v 0.117548 -0.005782 0.005817 +v 0.118998 -0.005532 0.005805 +v 0.120194 -0.005901 0.005829 +v 0.120077 -0.005691 -0.010098 +v 0.121698 -0.007564 -0.010098 +v 0.121391 -0.010190 -0.010098 +v 0.119614 -0.011399 -0.010098 +v 0.117789 -0.011407 -0.010098 +v 0.116240 -0.010173 -0.010098 +v 0.115706 -0.007913 -0.010098 +v 0.117436 -0.005705 -0.010098 +v 0.114123 -0.011016 -0.010098 +v 0.115721 -0.012838 -0.010098 +v 0.113447 -0.008452 -0.010098 +v 0.122656 -0.012166 -0.010098 +v 0.121256 -0.003764 -0.010098 +v 0.118032 -0.003224 -0.010098 +v 0.123291 -0.005752 -0.010098 +v 0.114155 -0.005917 -0.010098 +v 0.123974 -0.007629 -0.010098 +v 0.120394 -0.013516 -0.010098 +v 0.115596 -0.004268 -0.010098 +v 0.123936 -0.009625 -0.010098 +v 0.118219 -0.013770 -0.010098 +v 0.122240 -0.004572 -0.010945 +v 0.120703 -0.003607 -0.010806 +v 0.119028 -0.003223 -0.010811 +v 0.117131 -0.003486 -0.010767 +v 0.115479 -0.004364 -0.010797 +v 0.114041 -0.006140 -0.010770 +v 0.113564 -0.007737 -0.010767 +v 0.113585 -0.009430 -0.010787 +v 0.114111 -0.010954 -0.010803 +v 0.115177 -0.012330 -0.010835 +v 0.116638 -0.013323 -0.010829 +v 0.118632 -0.013777 -0.010778 +v 0.120827 -0.013360 -0.010794 +v 0.122480 -0.012163 -0.011001 +v 0.123284 -0.011222 -0.010771 +v 0.124013 -0.009204 -0.010834 +v 0.123804 -0.006937 -0.010796 +v 0.123019 -0.005371 -0.010772 +v 0.113925 -0.008770 -0.011591 +v 0.116384 -0.011688 -0.012697 +v 0.116722 -0.012632 -0.011989 +v 0.118342 -0.012294 -0.012816 +v 0.118893 -0.013345 -0.011624 +v 0.119699 -0.012437 -0.012603 +v 0.120641 -0.012686 -0.011968 +v 0.121460 -0.011469 -0.012660 +v 0.122309 -0.009946 -0.012824 +v 0.123174 -0.010161 -0.011866 +v 0.123117 -0.008151 -0.012298 +v 0.122799 -0.006803 -0.012290 +v 0.122200 -0.006098 -0.012447 +v 0.121330 -0.004996 -0.012308 +v 0.120113 -0.004509 -0.012478 +v 0.118749 -0.004218 -0.012399 +v 0.117270 -0.004236 -0.012100 +v 0.116392 -0.005437 -0.012755 +v 0.115464 -0.005029 -0.011727 +v 0.114984 -0.006284 -0.012260 +v 0.114169 -0.007326 -0.011729 +v 0.114715 -0.008228 -0.012583 +v 0.114869 -0.009838 -0.012556 +v 0.114849 -0.011126 -0.011799 +v 0.119162 -0.006220 -0.011098 +v 0.120937 -0.007697 -0.011098 +v 0.116995 -0.007020 -0.011098 +v 0.116604 -0.009296 -0.011098 +v 0.118380 -0.010773 -0.011098 +v 0.120546 -0.009973 -0.011098 +v 0.120974 0.007812 -0.013398 +v 0.121705 0.007535 -0.013387 +v 0.120495 0.005977 -0.013392 +v 0.119274 0.006250 -0.013398 +v 0.119225 0.005444 -0.013384 +v 0.117527 0.005720 -0.013393 +v 0.115670 0.008789 -0.013396 +v 0.116535 0.010641 -0.013384 +v 0.116567 0.009195 -0.013398 +v 0.118268 0.010757 -0.013398 +v 0.116210 0.006764 -0.013391 +v 0.117070 0.006941 -0.013398 +v 0.120558 0.011049 -0.013371 +v 0.120471 0.010066 -0.013398 +v 0.119590 0.011492 -0.013379 +v 0.121724 0.009493 -0.013399 +v 0.118177 0.011505 -0.013393 +v 0.115856 0.009114 0.005817 +v 0.115984 0.007463 0.005828 +v 0.121469 0.009596 0.005893 +v 0.116503 0.010413 0.005817 +v 0.117718 0.011286 0.005828 +v 0.119479 0.011417 0.005808 +v 0.120989 0.010490 0.005817 +v 0.121135 0.006702 0.005805 +v 0.121750 0.008211 0.005818 +v 0.120175 0.005898 0.005829 +v 0.118391 0.005515 0.005818 +v 0.116779 0.006296 0.005805 +v 0.115700 0.008560 -0.010098 +v 0.116316 0.010266 -0.010098 +v 0.117747 0.011400 -0.010098 +v 0.119561 0.011421 -0.010098 +v 0.121124 0.010478 -0.010098 +v 0.121780 0.008786 -0.010098 +v 0.121376 0.006835 -0.010098 +v 0.119784 0.005656 -0.010098 +v 0.117962 0.005540 -0.010098 +v 0.116343 0.006681 -0.010098 +v 0.113850 0.006468 -0.010098 +v 0.123990 0.007658 -0.010098 +v 0.123919 0.009651 -0.010098 +v 0.122848 0.005049 -0.010098 +v 0.120993 0.013364 -0.010098 +v 0.117746 0.013728 -0.010098 +v 0.115462 0.004379 -0.010098 +v 0.117416 0.003393 -0.010098 +v 0.113516 0.009093 -0.010098 +v 0.120066 0.003340 -0.010098 +v 0.114206 0.011171 -0.010098 +v 0.115530 0.012665 -0.010098 +v 0.123135 0.011488 -0.010098 +v 0.113932 0.006418 -0.010769 +v 0.114957 0.004848 -0.010787 +v 0.116254 0.003898 -0.010842 +v 0.117759 0.003330 -0.010798 +v 0.120107 0.003379 -0.010797 +v 0.122233 0.004514 -0.010789 +v 0.123442 0.006064 -0.010785 +v 0.124003 0.007764 -0.010786 +v 0.123849 0.009930 -0.010764 +v 0.123219 0.011301 -0.010810 +v 0.121936 0.012753 -0.010756 +v 0.119677 0.013708 -0.010780 +v 0.117878 0.013689 -0.010787 +v 0.116449 0.013228 -0.010822 +v 0.114985 0.012175 -0.010780 +v 0.113949 0.010611 -0.010873 +v 0.113485 0.008427 -0.010790 +v 0.120841 0.012618 -0.012006 +v 0.122815 0.009228 -0.012556 +v 0.122038 0.010761 -0.012694 +v 0.122993 0.010312 -0.011992 +v 0.122157 0.011833 -0.011718 +v 0.119186 0.012588 -0.012548 +v 0.118577 0.013184 -0.011859 +v 0.117307 0.012136 -0.012751 +v 0.116867 0.012823 -0.011765 +v 0.115640 0.011843 -0.012013 +v 0.115322 0.010756 -0.012539 +v 0.114307 0.009277 -0.012103 +v 0.114591 0.008261 -0.012458 +v 0.114384 0.006975 -0.011946 +v 0.115284 0.005964 -0.012330 +v 0.115927 0.005189 -0.012304 +v 0.117142 0.004403 -0.012214 +v 0.118162 0.004805 -0.012876 +v 0.118637 0.003891 -0.011952 +v 0.119962 0.004288 -0.012256 +v 0.121409 0.004879 -0.012154 +v 0.121607 0.005951 -0.012827 +v 0.122763 0.006417 -0.012131 +v 0.123008 0.008033 -0.012382 +v 0.123684 0.008488 -0.011490 +v 0.117070 0.006941 -0.011098 +v 0.116567 0.009195 -0.011098 +v 0.119274 0.006250 -0.011098 +v 0.120974 0.007812 -0.011098 +v 0.120471 0.010066 -0.011098 +v 0.118268 0.010757 -0.011098 +v 0.120648 0.017061 -0.013394 +v 0.120947 0.018729 -0.013398 +v 0.121692 0.018694 -0.013397 +v 0.115751 0.019929 -0.013394 +v 0.116300 0.021334 -0.013392 +v 0.116595 0.020278 -0.013398 +v 0.119188 0.017232 -0.013398 +v 0.119176 0.016468 -0.013393 +v 0.117554 0.016713 -0.013395 +v 0.118354 0.021775 -0.013398 +v 0.117473 0.022291 -0.013389 +v 0.118888 0.022574 -0.013392 +v 0.117012 0.018006 -0.013398 +v 0.116150 0.017907 -0.013398 +v 0.120529 0.021001 -0.013398 +v 0.120497 0.022032 -0.013395 +v 0.121725 0.020590 -0.013370 +v 0.121594 0.020400 0.005230 +v 0.115947 0.020390 0.005179 +v 0.115896 0.018601 0.005169 +v 0.116681 0.021634 0.005158 +v 0.118437 0.022498 0.005169 +v 0.120472 0.021967 0.005168 +v 0.120617 0.017181 0.005172 +v 0.121582 0.018460 0.005159 +v 0.119148 0.016535 0.005179 +v 0.117208 0.016950 0.005168 +v 0.115776 0.019005 -0.010098 +v 0.116137 0.021128 -0.010098 +v 0.118185 0.022519 -0.010098 +v 0.120299 0.022146 -0.010098 +v 0.121516 0.020798 -0.010098 +v 0.121788 0.019169 -0.010098 +v 0.120750 0.017092 -0.010098 +v 0.118349 0.016480 -0.010098 +v 0.116581 0.017377 -0.010098 +v 0.113831 0.017462 -0.010098 +v 0.123954 0.018460 -0.010098 +v 0.123959 0.020456 -0.010098 +v 0.122715 0.015897 -0.010098 +v 0.118783 0.024791 -0.010098 +v 0.115464 0.015394 -0.010098 +v 0.117224 0.014448 -0.010098 +v 0.113543 0.020292 -0.010098 +v 0.119869 0.014294 -0.010098 +v 0.114310 0.022342 -0.010098 +v 0.121341 0.024166 -0.010098 +v 0.116216 0.024176 -0.010098 +v 0.123245 0.022321 -0.010098 +v 0.113896 0.017464 -0.010792 +v 0.115006 0.015815 -0.010776 +v 0.116245 0.014892 -0.010799 +v 0.117947 0.014283 -0.010783 +v 0.120001 0.014374 -0.010839 +v 0.121907 0.015272 -0.010805 +v 0.123281 0.016728 -0.010798 +v 0.124009 0.018904 -0.010767 +v 0.123918 0.020635 -0.010792 +v 0.123343 0.022091 -0.010827 +v 0.122213 0.023512 -0.010766 +v 0.120231 0.024563 -0.010878 +v 0.118037 0.024741 -0.010772 +v 0.116128 0.024049 -0.010835 +v 0.114799 0.022970 -0.010841 +v 0.114061 0.021799 -0.010933 +v 0.113495 0.019743 -0.010755 +v 0.123277 0.017469 -0.011466 +v 0.122646 0.019662 -0.012769 +v 0.123240 0.021056 -0.011827 +v 0.121868 0.022031 -0.012652 +v 0.122014 0.023228 -0.011510 +v 0.120803 0.022953 -0.012666 +v 0.119919 0.023658 -0.012327 +v 0.118422 0.023895 -0.012247 +v 0.117187 0.023634 -0.012223 +v 0.115953 0.022784 -0.012320 +v 0.114954 0.021388 -0.012391 +v 0.115008 0.020314 -0.012789 +v 0.113967 0.020250 -0.011578 +v 0.115040 0.018966 -0.012859 +v 0.114075 0.018897 -0.011771 +v 0.114702 0.017803 -0.012223 +v 0.115044 0.016684 -0.011883 +v 0.116207 0.016664 -0.012814 +v 0.116099 0.015492 -0.011631 +v 0.117238 0.015289 -0.012141 +v 0.118339 0.015344 -0.012500 +v 0.119941 0.015253 -0.012237 +v 0.121013 0.015690 -0.012221 +v 0.122112 0.016695 -0.012268 +v 0.122333 0.017855 -0.012741 +v 0.123395 0.019156 -0.011921 +v 0.117012 0.018006 -0.011098 +v 0.116595 0.020278 -0.011098 +v 0.119188 0.017232 -0.011098 +v 0.120947 0.018729 -0.011098 +v 0.120529 0.021001 -0.011098 +v 0.118354 0.021775 -0.011098 +v 0.121845 -0.019120 -0.013385 +v 0.121524 -0.020970 -0.013378 +v 0.120952 -0.020255 -0.013398 +v 0.116589 -0.018738 -0.013398 +v 0.115746 -0.018905 -0.013395 +v 0.116882 -0.017096 -0.013395 +v 0.118659 -0.016439 -0.013397 +v 0.118337 -0.017228 -0.013398 +v 0.117023 -0.021007 -0.013398 +v 0.116631 -0.021710 -0.013388 +v 0.115874 -0.020504 -0.013390 +v 0.119205 -0.021765 -0.013398 +v 0.118211 -0.022573 -0.013390 +v 0.120340 -0.022107 -0.013394 +v 0.120207 -0.016750 -0.013373 +v 0.121257 -0.017672 -0.013390 +v 0.120518 -0.017986 -0.013398 +v 0.121169 -0.021206 0.004521 +v 0.118646 -0.022467 0.004476 +v 0.120059 -0.022176 0.004444 +v 0.116802 -0.021786 0.004437 +v 0.115859 -0.020133 0.004460 +v 0.115961 -0.018519 0.004467 +v 0.117162 -0.016945 0.004449 +v 0.118866 -0.016538 0.004468 +v 0.120454 -0.017015 0.004448 +v 0.121532 -0.018388 0.004467 +v 0.121713 -0.019863 0.004456 +v 0.120853 -0.021728 -0.010098 +v 0.119043 -0.022537 -0.010098 +v 0.116818 -0.021897 -0.010098 +v 0.115780 -0.020017 -0.010098 +v 0.116060 -0.018051 -0.010098 +v 0.117682 -0.016645 -0.010098 +v 0.119495 -0.016548 -0.010098 +v 0.120932 -0.017364 -0.010098 +v 0.121890 -0.019478 -0.010098 +v 0.123341 -0.022155 -0.010098 +v 0.117046 -0.014498 -0.010098 +v 0.115323 -0.015504 -0.010098 +v 0.119884 -0.014269 -0.010098 +v 0.113437 -0.019840 -0.010098 +v 0.114316 -0.022321 -0.010098 +v 0.124093 -0.019631 -0.010098 +v 0.121344 -0.024181 -0.010098 +v 0.122211 -0.015498 -0.010098 +v 0.118131 -0.024782 -0.010098 +v 0.123461 -0.017057 -0.010098 +v 0.115676 -0.023784 -0.010098 +v 0.114075 -0.017065 -0.010098 +v 0.122348 -0.023386 -0.010802 +v 0.123539 -0.021743 -0.010778 +v 0.123956 -0.020000 -0.011025 +v 0.123994 -0.018790 -0.010791 +v 0.123368 -0.016891 -0.010775 +v 0.122555 -0.015866 -0.010861 +v 0.121004 -0.014713 -0.010821 +v 0.119230 -0.014270 -0.010854 +v 0.117683 -0.014332 -0.010788 +v 0.115736 -0.015176 -0.010838 +v 0.114319 -0.016670 -0.010760 +v 0.113572 -0.018557 -0.010771 +v 0.113617 -0.020666 -0.010775 +v 0.114485 -0.022480 -0.010971 +v 0.115006 -0.023181 -0.010784 +v 0.116243 -0.024114 -0.010768 +v 0.118167 -0.024759 -0.010791 +v 0.120501 -0.024490 -0.010760 +v 0.115029 -0.016741 -0.011909 +v 0.116122 -0.015946 -0.012196 +v 0.115802 -0.017256 -0.012903 +v 0.114513 -0.017959 -0.012102 +v 0.114281 -0.019310 -0.012135 +v 0.114524 -0.020804 -0.012213 +v 0.115323 -0.021735 -0.012532 +v 0.116123 -0.023525 -0.011674 +v 0.116170 -0.022712 -0.012505 +v 0.117321 -0.023549 -0.012322 +v 0.118305 -0.024163 -0.011856 +v 0.118854 -0.023341 -0.012797 +v 0.119646 -0.024208 -0.011674 +v 0.120261 -0.023138 -0.012715 +v 0.121208 -0.023602 -0.011731 +v 0.121617 -0.022371 -0.012609 +v 0.122607 -0.022316 -0.011716 +v 0.122750 -0.021260 -0.012279 +v 0.122800 -0.019900 -0.012599 +v 0.123236 -0.018487 -0.012004 +v 0.122746 -0.017573 -0.012224 +v 0.121504 -0.016319 -0.012472 +v 0.121291 -0.015463 -0.011745 +v 0.119841 -0.015459 -0.012503 +v 0.118533 -0.015034 -0.012159 +v 0.117386 -0.015577 -0.012523 +v 0.120952 -0.020255 -0.011098 +v 0.119205 -0.021765 -0.011098 +v 0.120518 -0.017986 -0.011098 +v 0.118337 -0.017228 -0.011098 +v 0.116589 -0.018738 -0.011098 +v 0.117023 -0.021007 -0.011098 +v 0.119629 -0.013568 0.015979 +v 0.117687 -0.013744 0.015910 +v 0.116157 -0.015145 0.015432 +v 0.121761 -0.015469 0.015234 +v 0.118121 -0.015759 0.015006 +v 0.114615 -0.016492 0.014359 +v 0.120262 -0.016017 0.014802 +v 0.123099 -0.016634 0.014182 +v 0.122386 -0.017072 0.013584 +v 0.115535 -0.016823 0.013949 +v 0.124771 -0.024894 0.002054 +v 0.118220 -0.022957 0.004919 +v 0.112771 -0.024877 0.002080 +v 0.121049 -0.022553 0.005512 +v 0.115489 -0.022103 0.006172 +v 0.122669 -0.021665 0.006814 +v 0.112977 -0.018161 0.011954 +v 0.114236 -0.020971 0.007832 +v 0.124611 -0.018291 0.011763 +v 0.123733 -0.020179 0.008995 +v 0.113729 -0.019597 0.009848 +v 0.114075 -0.018279 0.011782 +v 0.123628 -0.018606 0.011302 +v 0.124771 -0.024997 0.000002 +v 0.112771 -0.024997 0.000002 +v 0.112771 -0.004759 0.000002 +v 0.112858 -0.004759 0.011327 +v 0.116228 -0.011744 0.014338 +v 0.118297 -0.011744 0.015038 +v 0.120826 -0.011745 0.014614 +v 0.122513 -0.011744 0.013350 +v 0.114618 -0.011744 0.012880 +v 0.123619 -0.011745 0.011463 +v 0.123618 -0.011744 0.008461 +v 0.119431 -0.011744 0.004992 +v 0.117362 -0.011744 0.005183 +v 0.121884 -0.011744 0.006009 +v 0.115609 -0.011744 0.006072 +v 0.123810 -0.004759 0.013388 +v 0.124722 -0.004759 0.010931 +v 0.121330 -0.004759 0.015517 +v 0.118203 -0.004759 0.016027 +v 0.115893 -0.004759 0.015296 +v 0.114132 -0.004759 0.013880 +v 0.120337 0.014193 0.015823 +v 0.114996 0.016165 0.014748 +v 0.117684 0.013754 0.015961 +v 0.122129 0.015800 0.015004 +v 0.123298 0.016804 0.013959 +v 0.112771 0.024904 0.002035 +v 0.119250 0.022058 0.006248 +v 0.124771 0.024887 0.002066 +v 0.118825 0.016920 0.013785 +v 0.112930 0.018299 0.011763 +v 0.117414 0.021636 0.006867 +v 0.117146 0.017574 0.012826 +v 0.120885 0.018013 0.012182 +v 0.121206 0.020450 0.008607 +v 0.116443 0.020529 0.008492 +v 0.116312 0.018816 0.011003 +v 0.124631 0.018367 0.011662 +v 0.112926 0.004766 0.011685 +v 0.112771 0.004766 0.000002 +v 0.112771 0.025003 0.000002 +v 0.124771 0.025003 0.000002 +v 0.124771 0.004766 0.000002 +v 0.124771 -0.004759 0.000002 +v 0.114368 0.004766 0.014113 +v 0.116218 0.004766 0.015477 +v 0.118312 0.004766 0.016002 +v 0.120968 0.004766 0.015676 +v 0.123581 0.004766 0.013704 +v 0.124704 0.004766 0.011118 +v 0.116960 0.018485 0.008917 +v 0.117431 0.010994 0.008345 +v 0.116729 0.010910 0.009415 +v 0.117324 0.018906 0.010571 +v 0.118012 0.018900 0.011336 +v 0.117443 0.018942 0.009181 +v 0.120313 -0.016473 0.011036 +v 0.120349 -0.016524 0.014292 +v 0.118655 -0.016483 0.011854 +v 0.120438 -0.016425 0.009798 +v 0.123341 -0.016442 0.008940 +v 0.122731 -0.016522 0.012103 +v 0.120369 -0.016502 0.009036 +v 0.120659 -0.016522 0.005908 +v 0.122657 -0.016522 0.007766 +v 0.117257 -0.016418 0.014436 +v 0.114433 -0.016524 0.008562 +v 0.117192 -0.016524 0.005713 +v 0.117133 -0.016503 0.009107 +v 0.118727 -0.016502 0.008137 +v 0.117117 -0.016463 0.010821 +v 0.114836 -0.016523 0.012261 +v 0.119338 -0.011759 0.005155 +v 0.119178 -0.016192 0.005171 +v 0.116566 -0.016190 0.005740 +v 0.115984 -0.011759 0.006035 +v 0.114935 -0.016190 0.007118 +v 0.114349 -0.011759 0.008139 +v 0.114063 -0.016190 0.009069 +v 0.113987 -0.011759 0.010792 +v 0.114125 -0.016190 0.011203 +v 0.115268 -0.016190 0.013315 +v 0.115344 -0.011759 0.013393 +v 0.117937 -0.011759 0.014778 +v 0.119713 -0.016191 0.014730 +v 0.120840 -0.011759 0.014357 +v 0.122294 -0.016192 0.013332 +v 0.122668 -0.011759 0.012803 +v 0.123545 -0.016191 0.010675 +v 0.123497 -0.011759 0.010835 +v 0.123390 -0.011759 0.008702 +v 0.122101 -0.016192 0.006479 +v 0.122198 -0.011759 0.006611 +v 0.119554 -0.011759 0.006888 +v 0.117611 -0.011759 0.006985 +v 0.120734 -0.011759 0.012644 +v 0.122027 -0.011759 0.010143 +v 0.121226 -0.011759 0.007898 +v 0.116445 -0.011759 0.012286 +v 0.118419 -0.011759 0.013194 +v 0.115539 -0.011759 0.010085 +v 0.116099 -0.011759 0.008221 +v 0.118051 0.010377 0.006974 +v 0.116616 0.010135 0.007622 +v 0.115493 0.010141 0.009730 +v 0.116249 0.010135 0.011990 +v 0.117852 0.010136 0.013101 +v 0.119799 0.010134 0.013044 +v 0.121230 0.010134 0.012067 +v 0.122029 0.010138 0.010050 +v 0.121166 0.010136 0.007832 +v 0.119495 0.010403 0.007030 +v 0.118237 0.010519 0.007958 +v 0.119616 0.010497 0.007978 +v 0.121499 0.010469 0.008817 +v 0.120879 0.010503 0.009306 +v 0.115906 0.010469 0.009199 +v 0.117204 0.010514 0.008591 +v 0.121078 0.010469 0.011880 +v 0.120555 0.010500 0.011342 +v 0.119562 0.010504 0.011972 +v 0.118767 0.010466 0.012895 +v 0.118490 0.010509 0.012133 +v 0.116619 0.010468 0.012010 +v 0.116883 0.010491 0.011227 +v 0.116625 0.010498 0.009616 +v 0.118480 0.010980 0.007908 +v 0.117382 0.010804 0.011639 +v 0.118058 0.010977 0.011969 +v 0.119041 0.010958 0.012079 +v 0.119972 0.010969 0.011736 +v 0.120610 0.010886 0.011063 +v 0.120932 0.010862 0.009932 +v 0.120516 0.010950 0.008775 +v 0.119614 0.010898 0.008018 +v 0.116728 0.010894 0.010584 +v 0.119437 0.018553 0.007955 +v 0.120838 0.018507 0.009579 +v 0.120477 0.018487 0.011307 +v 0.118910 0.018491 0.012092 +v 0.117727 0.018490 0.011794 +v 0.116794 0.018476 0.010749 +v 0.118294 0.018587 0.007886 +v 0.120291 0.018933 0.009727 +v 0.118007 -0.016259 0.008610 +v 0.119594 -0.016258 0.008645 +v 0.118811 -0.014140 0.008169 +v 0.120378 -0.014140 0.009121 +v 0.117204 -0.014140 0.009051 +v 0.120338 -0.014140 0.010953 +v 0.117163 -0.014140 0.010883 +v 0.118730 -0.014140 0.011835 +v 0.000001 -0.024997 -0.007598 +v 0.000001 0.025003 -0.007598 +v 0.124771 0.025003 -0.007598 +v 0.124771 -0.024997 -0.007598 +v 0.000001 -0.024997 0.000002 +v 0.124771 -0.024997 0.000002 +v 0.120450 0.021505 0.003789 +v 0.116222 0.019867 0.003789 +v 0.117006 0.021304 0.003789 +v 0.118299 0.022013 0.003789 +v 0.118290 0.016949 0.003789 +v 0.114247 -0.011744 0.007792 +v 0.113704 -0.011744 0.010275 +v 0.116687 0.018044 0.003789 +v 0.121324 0.019476 0.003789 +v 0.120578 0.017676 0.003789 +v 0.124771 0.025003 0.000002 +v 0.000001 0.025003 0.000002 +v 0.118848 0.018908 0.011552 +v 0.120031 0.018915 0.010964 +v 0.119181 0.018978 0.008445 +v 0.118463 0.018938 0.008391 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn 0.0024 -1.0000 -0.0068 +vn 0.0020 -1.0000 -0.0049 +vn -0.0003 -1.0000 0.0057 +vn -0.0007 -1.0000 0.0076 +vn -1.0000 0.0002 0.0068 +vn -1.0000 0.0002 0.0063 +vn -1.0000 -0.0005 -0.0079 +vn -1.0000 -0.0005 -0.0084 +vn -0.0031 1.0000 -0.0076 +vn -0.0027 1.0000 -0.0054 +vn -0.0001 1.0000 0.0066 +vn 0.0003 1.0000 0.0088 +vn 1.0000 -0.0002 0.0059 +vn 1.0000 0.0005 -0.0080 +vn 1.0000 0.0005 -0.0075 +vn 1.0000 -0.0002 0.0064 +vn -0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.0020 0.0051 -1.0000 +vn -0.0017 0.0033 -1.0000 +vn 0.0032 0.0033 -1.0000 +vn -0.0104 0.0037 -0.9999 +vn -0.0071 0.0027 -1.0000 +vn -0.0040 0.0097 -0.9999 +vn 0.0037 -0.0050 -1.0000 +vn 0.0033 -0.0017 -1.0000 +vn 0.0028 -0.0060 -1.0000 +vn 0.0036 0.0020 -1.0000 +vn 0.0036 0.0011 -1.0000 +vn -0.0149 0.0037 -0.9999 +vn -0.0050 -0.0056 -1.0000 +vn 0.0020 0.0086 -1.0000 +vn -0.0050 -0.0012 -1.0000 +vn -0.0014 -0.0021 -1.0000 +vn -0.0008 -0.0036 -1.0000 +vn 0.0274 -0.0198 0.9994 +vn 0.0682 -0.0164 0.9975 +vn 0.0048 0.0051 1.0000 +vn 0.0060 -0.0166 0.9998 +vn -0.0043 -0.0116 0.9999 +vn -0.0091 -0.0072 0.9999 +vn -0.0120 -0.0013 0.9999 +vn -0.0141 0.0080 0.9999 +vn -0.0122 0.0242 0.9996 +vn -0.0020 0.0604 0.9982 +vn -0.0007 0.0627 0.9980 +vn 0.4145 0.9100 -0.0081 +vn 0.8220 0.5694 0.0087 +vn 0.9554 0.2951 -0.0075 +vn 0.9969 0.0777 0.0086 +vn 0.9923 -0.1232 -0.0084 +vn 0.9742 -0.2257 0.0042 +vn 0.5747 -0.8183 -0.0058 +vn 0.7222 -0.6916 0.0135 +vn 0.4329 -0.9014 0.0122 +vn 0.2936 -0.9559 -0.0023 +vn 0.0838 -0.9964 0.0104 +vn 0.0044 -1.0000 0.0018 +vn -0.6203 -0.7844 0.0002 +vn -0.5823 -0.8130 0.0053 +vn -0.7823 -0.6229 0.0068 +vn -0.8433 -0.5375 -0.0036 +vn -0.9983 -0.0577 0.0125 +vn -0.9770 0.2131 -0.0099 +vn -0.8359 0.5487 0.0118 +vn -0.7788 0.6271 -0.0112 +vn -0.6430 0.7658 0.0082 +vn -0.0150 0.9998 -0.0094 +vn -0.1699 0.9855 0.0060 +vn 0.0636 0.9980 0.0075 +vn 0.5045 0.8634 0.0077 +vn 0.6424 0.7170 -0.2706 +vn 0.3239 0.9032 -0.2816 +vn 0.4703 0.8807 -0.0566 +vn 0.0790 0.9758 -0.2037 +vn -0.1325 0.9905 -0.0365 +vn -0.3242 0.9221 -0.2111 +vn -0.5938 0.8045 0.0167 +vn -0.6099 0.7542 -0.2432 +vn -0.8648 0.5020 -0.0063 +vn -0.8757 0.4253 -0.2286 +vn -0.9990 0.0118 -0.0437 +vn -0.9633 0.1811 -0.1982 +vn -0.9552 -0.2081 -0.2103 +vn -0.8761 -0.4820 0.0141 +vn -0.8585 -0.4395 -0.2642 +vn -0.6759 -0.6916 -0.2547 +vn -0.5752 -0.8177 -0.0243 +vn -0.3697 -0.9040 -0.2146 +vn -0.1281 -0.9916 -0.0149 +vn -0.0114 -0.9723 -0.2336 +vn 0.2854 -0.9584 -0.0099 +vn 0.3941 -0.8907 -0.2267 +vn 0.7126 -0.6997 -0.0507 +vn 0.6428 -0.6711 -0.3694 +vn 0.8597 -0.4760 -0.1853 +vn 0.9681 -0.2505 0.0022 +vn 0.9609 -0.1086 -0.2546 +vn 0.9887 0.1412 -0.0504 +vn 0.9267 0.2848 -0.2452 +vn 0.8528 0.5222 -0.0013 +vn 0.7705 0.5925 -0.2351 +vn -0.8446 -0.0575 -0.5324 +vn -0.4689 -0.3971 -0.7889 +vn -0.1308 -0.5971 -0.7914 +vn -0.4329 -0.5510 -0.7134 +vn -0.3485 -0.7240 -0.5953 +vn -0.0796 -0.6839 -0.7252 +vn 0.0175 -0.8425 -0.5385 +vn 0.1640 -0.6817 -0.7130 +vn 0.2669 -0.5352 -0.8015 +vn 0.3387 -0.7317 -0.5915 +vn 0.4791 -0.5185 -0.7082 +vn 0.5517 -0.2196 -0.8046 +vn 0.6272 -0.2472 -0.7386 +vn 0.7609 -0.2994 -0.5756 +vn 0.7613 0.0444 -0.6469 +vn 0.6039 0.1361 -0.7854 +vn 0.7049 0.3092 -0.6384 +vn 0.5998 0.4371 -0.6703 +vn 0.4338 0.4436 -0.7843 +vn 0.4464 0.6240 -0.6413 +vn 0.2519 0.7046 -0.6634 +vn 0.1365 0.5972 -0.7904 +vn -0.0135 0.7548 -0.6558 +vn -0.2652 0.7465 -0.6102 +vn -0.1896 0.5968 -0.7797 +vn -0.4115 0.5425 -0.7324 +vn -0.4595 0.4137 -0.7860 +vn -0.5776 0.6052 -0.5478 +vn -0.6597 0.3760 -0.6507 +vn -0.6048 0.1925 -0.7728 +vn -0.8039 0.2084 -0.5571 +vn -0.7060 0.0567 -0.7059 +vn -0.5928 -0.1072 -0.7982 +vn -0.6812 -0.2457 -0.6896 +vn -0.6736 -0.4616 -0.5773 +vn -0.6396 -0.7687 0.0000 +vn 0.3463 -0.9381 -0.0000 +vn 0.9856 -0.1693 0.0000 +vn 0.6394 0.7689 0.0000 +vn -0.3465 0.9381 0.0000 +vn -0.9856 0.1693 0.0000 +vn 0.0094 -0.0052 -0.9999 +vn 0.0126 -0.0064 -0.9999 +vn 0.0046 -0.0077 -1.0000 +vn 0.0018 -0.0126 -0.9999 +vn 0.0018 -0.0175 -0.9998 +vn -0.0019 -0.0073 -1.0000 +vn -0.0042 0.0018 -1.0000 +vn -0.0083 0.0089 -0.9999 +vn -0.0055 0.0063 -1.0000 +vn -0.0006 0.0090 -1.0000 +vn -0.0071 -0.0052 -1.0000 +vn -0.0053 -0.0050 -1.0000 +vn 0.0176 0.0259 -0.9995 +vn 0.0089 0.0188 -0.9998 +vn 0.0093 0.0169 -0.9998 +vn 0.0038 0.0041 -1.0000 +vn 0.0016 0.0069 -1.0000 +vn -0.0141 0.0062 0.9999 +vn -0.0085 -0.0085 0.9999 +vn 0.0157 0.0105 0.9998 +vn -0.0141 0.0071 0.9999 +vn -0.0100 0.0162 0.9998 +vn 0.0119 0.0596 0.9981 +vn 0.0683 0.1209 0.9903 +vn 0.0577 -0.0370 0.9977 +vn 0.0743 -0.0389 0.9965 +vn 0.0092 -0.0205 0.9997 +vn -0.0096 -0.0111 0.9999 +vn -0.0070 -0.0167 0.9998 +vn -1.0000 0.0093 -0.0037 +vn -0.9434 -0.3316 0.0104 +vn -0.9812 0.1925 0.0094 +vn -0.8113 0.5846 -0.0011 +vn -0.7609 0.6488 0.0056 +vn -0.6189 0.7855 0.0003 +vn -0.5835 0.8121 0.0048 +vn -0.0160 0.9999 0.0007 +vn -0.0741 0.9972 0.0070 +vn -0.0696 0.9976 0.0065 +vn -0.0116 0.9999 0.0002 +vn 0.5166 0.8562 0.0029 +vn 0.5227 0.8525 0.0037 +vn 0.5171 0.8559 0.0029 +vn 0.5232 0.8522 0.0038 +vn 0.9306 0.3661 0.0001 +vn 0.8808 0.4735 0.0071 +vn 0.9407 0.3392 0.0078 +vn 0.9964 0.0844 -0.0026 +vn 0.9961 -0.0872 0.0097 +vn 0.8420 -0.5394 -0.0035 +vn 0.8059 -0.5920 0.0073 +vn 0.4398 -0.8981 0.0064 +vn 0.3436 -0.9391 -0.0025 +vn -0.1180 -0.9930 0.0101 +vn -0.2715 -0.9624 -0.0033 +vn -0.6542 -0.7563 0.0094 +vn -0.7998 -0.6002 -0.0045 +vn -0.8779 -0.3893 -0.2789 +vn -0.7270 -0.6506 -0.2197 +vn -0.9265 -0.3750 -0.0308 +vn -0.6203 -0.7843 0.0031 +vn -0.4570 -0.8531 -0.2517 +vn -0.2543 -0.9671 0.0035 +vn -0.1525 -0.9584 -0.2411 +vn 0.2442 -0.9697 -0.0074 +vn 0.2537 -0.9301 -0.2656 +vn 0.6039 -0.7684 -0.2118 +vn 0.5139 -0.8365 0.1903 +vn 0.8758 -0.4388 -0.2008 +vn 0.8149 -0.5649 -0.1300 +vn 0.9853 -0.1695 0.0232 +vn 0.9579 -0.1349 -0.2534 +vn 0.9818 0.1896 -0.0108 +vn 0.9365 0.2617 -0.2334 +vn 0.8165 0.5773 -0.0049 +vn 0.8161 0.5128 -0.2665 +vn 0.6002 0.7808 -0.1734 +vn 0.6398 0.7305 0.2386 +vn 0.1626 0.9720 -0.1697 +vn 0.3763 0.8830 -0.2807 +vn -0.1835 0.9830 -0.0098 +vn 0.1071 0.9554 0.2752 +vn -0.1494 0.9475 -0.2828 +vn -0.4365 0.8723 -0.2205 +vn -0.6011 0.7991 -0.0068 +vn -0.7064 0.6687 -0.2322 +vn -0.8602 0.5093 -0.0264 +vn -0.8860 0.3748 -0.2732 +vn -0.9902 0.1352 -0.0340 +vn -0.9746 -0.0366 -0.2210 +vn 0.3524 0.7183 -0.5999 +vn 0.7057 0.1158 -0.6990 +vn 0.5557 0.4154 -0.7201 +vn 0.7458 0.3185 -0.5851 +vn 0.5824 0.1798 -0.7928 +vn 0.5963 0.5755 -0.5597 +vn 0.3800 0.5250 -0.7616 +vn 0.1691 0.6185 -0.7674 +vn 0.0822 0.7151 -0.6941 +vn -0.0330 0.8190 -0.5728 +vn -0.1156 0.5927 -0.7971 +vn -0.2593 0.6329 -0.7296 +vn -0.3276 0.7580 -0.5640 +vn -0.5484 0.5830 -0.5994 +vn -0.4447 0.4230 -0.7895 +vn -0.6135 0.3811 -0.6916 +vn -0.6236 0.0451 -0.7804 +vn -0.7791 0.1443 -0.6100 +vn -0.7237 -0.0881 -0.6844 +vn -0.7598 -0.2606 -0.5957 +vn -0.5323 -0.3305 -0.7794 +vn -0.6310 -0.4249 -0.6490 +vn -0.4839 -0.5849 -0.6509 +vn -0.2661 -0.5462 -0.7942 +vn -0.2870 -0.7198 -0.6321 +vn -0.0929 -0.6490 -0.7551 +vn -0.0191 -0.8110 -0.5848 +vn 0.1018 -0.6224 -0.7760 +vn 0.2113 -0.7291 -0.6510 +vn 0.4590 -0.6430 -0.6131 +vn 0.3365 -0.5118 -0.7905 +vn 0.4941 -0.4345 -0.7530 +vn 0.7028 -0.3638 -0.6113 +vn 0.5859 -0.1848 -0.7890 +vn 0.7368 -0.1033 -0.6682 +vn 0.8634 0.0042 -0.5046 +vn 0.9760 0.2178 0.0000 +vn 0.2992 0.9542 0.0000 +vn -0.6766 0.7364 0.0000 +vn -0.9760 -0.2178 0.0000 +vn -0.2993 -0.9542 0.0000 +vn 0.6764 -0.7366 0.0000 +vn 0.0021 -0.0035 -1.0000 +vn 0.0049 0.0032 -1.0000 +vn 0.0017 0.0074 -1.0000 +vn -0.0055 0.0019 -1.0000 +vn -0.0047 0.0052 -1.0000 +vn -0.0048 0.0031 -1.0000 +vn 0.0011 -0.0052 -1.0000 +vn 0.0010 -0.0066 -1.0000 +vn -0.0005 -0.0033 -1.0000 +vn -0.0027 0.0080 -1.0000 +vn -0.0047 0.0094 -0.9999 +vn -0.0009 0.0081 -1.0000 +vn -0.0001 -0.0015 -1.0000 +vn -0.0007 -0.0006 -1.0000 +vn 0.0180 0.0037 -0.9998 +vn 0.0071 0.0039 -1.0000 +vn 0.0213 0.0059 -0.9998 +vn 0.0049 0.0013 1.0000 +vn -0.0090 0.0055 0.9999 +vn -0.0087 -0.0063 0.9999 +vn -0.0098 0.0192 0.9998 +vn -0.0084 0.0164 0.9998 +vn 0.0133 0.0490 0.9987 +vn 0.0210 -0.0244 0.9995 +vn 0.0623 -0.0369 0.9974 +vn -0.0023 -0.0118 0.9999 +vn -0.0081 -0.0077 0.9999 +vn -0.9895 -0.1447 -0.0041 +vn -0.9495 -0.3135 0.0117 +vn -0.9614 0.2748 0.0109 +vn -0.8417 0.5398 -0.0056 +vn -0.6791 0.7340 0.0107 +vn -0.5525 0.8335 -0.0061 +vn -0.4415 0.8972 0.0085 +vn 0.1738 0.9848 -0.0015 +vn 0.2456 0.9693 0.0076 +vn 0.1806 0.9836 -0.0006 +vn 0.2525 0.9676 0.0085 +vn 0.7422 0.6701 -0.0006 +vn 0.8080 0.5891 0.0101 +vn 0.9005 0.4350 -0.0002 +vn 0.9527 0.3038 0.0122 +vn 0.9893 -0.1459 -0.0042 +vn 0.9478 -0.3187 0.0114 +vn 0.6278 -0.7784 -0.0086 +vn 0.6193 -0.7851 0.0100 +vn 0.1035 -0.9946 0.0111 +vn -0.1107 -0.9938 -0.0074 +vn -0.5264 -0.8501 0.0146 +vn -0.7111 -0.7031 -0.0049 +vn -0.8886 -0.3631 -0.2801 +vn -0.7191 -0.6645 -0.2034 +vn -0.9278 -0.3707 -0.0412 +vn -0.6287 -0.7776 0.0109 +vn -0.4571 -0.8605 -0.2250 +vn -0.2979 -0.9545 -0.0112 +vn -0.1214 -0.9682 -0.2188 +vn 0.2111 -0.9774 -0.0128 +vn 0.2335 -0.9279 -0.2906 +vn 0.5521 -0.8088 -0.2024 +vn 0.6701 -0.7328 -0.1181 +vn 0.8443 -0.4993 -0.1948 +vn 0.9720 -0.2336 -0.0251 +vn 0.8809 -0.4258 0.2067 +vn 0.9677 -0.1015 -0.2306 +vn 0.9845 0.1751 0.0054 +vn 0.9488 0.2062 -0.2391 +vn 0.8411 0.5408 -0.0106 +vn 0.8374 0.4742 -0.2718 +vn 0.6484 0.7436 -0.1631 +vn 0.4763 0.8755 -0.0811 +vn 0.2584 0.9329 -0.2510 +vn 0.0269 0.9993 -0.0255 +vn -0.1515 0.9661 -0.2091 +vn -0.4718 0.8810 -0.0348 +vn -0.4795 0.8243 -0.3011 +vn -0.7151 0.6544 -0.2456 +vn -0.8465 0.5324 0.0074 +vn -0.8674 0.4008 -0.2948 +vn -0.9848 0.1714 -0.0278 +vn -0.9823 0.0098 -0.1870 +vn 0.7972 -0.3317 -0.5044 +vn 0.6750 0.0279 -0.7373 +vn 0.5848 0.2199 -0.7808 +vn 0.7650 0.2757 -0.5820 +vn 0.5597 0.4322 -0.7070 +vn 0.5566 0.6442 -0.5246 +vn 0.3290 0.4917 -0.8062 +vn 0.3487 0.6133 -0.7087 +vn 0.2031 0.7320 -0.6503 +vn 0.0277 0.6267 -0.7787 +vn -0.0474 0.7675 -0.6393 +vn -0.2826 0.7188 -0.6352 +vn -0.2661 0.5747 -0.7739 +vn -0.5035 0.5663 -0.6526 +vn -0.4986 0.3775 -0.7803 +vn -0.6654 0.3510 -0.6589 +vn -0.6695 0.1362 -0.7302 +vn -0.8327 0.1392 -0.5360 +vn -0.5687 0.0731 -0.8193 +vn -0.6494 -0.0917 -0.7549 +vn -0.8270 -0.1017 -0.5530 +vn -0.5168 -0.3059 -0.7996 +vn -0.7031 -0.2975 -0.6458 +vn -0.6475 -0.4971 -0.5776 +vn -0.4451 -0.5002 -0.7428 +vn -0.4737 -0.6911 -0.5459 +vn -0.2392 -0.5563 -0.7958 +vn -0.2747 -0.7328 -0.6225 +vn -0.0613 -0.7305 -0.6801 +vn 0.0908 -0.6102 -0.7870 +vn 0.1884 -0.7448 -0.6402 +vn 0.3973 -0.6627 -0.6349 +vn 0.3771 -0.4922 -0.7846 +vn 0.5792 -0.5042 -0.6405 +vn 0.6185 -0.2807 -0.7339 +vn 0.5563 -0.1564 -0.8161 +vn 0.8101 -0.0617 -0.5831 +vn 0.9836 0.1805 0.0000 +vn 0.3351 0.9422 0.0000 +vn -0.6481 0.7615 0.0000 +vn -0.9835 -0.1809 0.0000 +vn -0.3353 -0.9421 0.0000 +vn 0.6481 -0.7615 0.0000 +vn 0.0140 -0.0000 -0.9999 +vn 0.0235 -0.0092 -0.9997 +vn 0.0188 -0.0057 -0.9998 +vn -0.0039 0.0005 -1.0000 +vn -0.0033 -0.0014 -1.0000 +vn -0.0022 0.0022 -1.0000 +vn 0.0035 0.0061 -1.0000 +vn -0.0011 0.0017 -1.0000 +vn -0.0077 -0.0071 -0.9999 +vn -0.0084 -0.0095 -0.9999 +vn -0.0075 -0.0033 -1.0000 +vn 0.0002 -0.0078 -1.0000 +vn -0.0027 -0.0082 -1.0000 +vn 0.0060 -0.0057 -1.0000 +vn 0.0163 0.0243 -0.9996 +vn 0.0069 0.0092 -0.9999 +vn 0.0085 0.0115 -0.9999 +vn 0.0102 -0.0087 0.9999 +vn -0.0126 -0.0104 0.9999 +vn 0.0505 -0.1363 0.9894 +vn -0.0169 -0.0178 0.9997 +vn -0.0135 -0.0101 0.9999 +vn -0.0073 0.0060 1.0000 +vn -0.0071 0.0102 0.9999 +vn -0.0026 0.0101 0.9999 +vn 0.0162 0.0202 0.9997 +vn 0.0155 0.0172 0.9997 +vn 0.1052 0.0055 0.9944 +vn 0.7033 -0.7109 -0.0050 +vn 0.4458 -0.8951 0.0111 +vn 0.0691 -0.9976 -0.0041 +vn -0.0765 -0.9970 0.0083 +vn -0.2825 -0.9593 -0.0021 +vn -0.3466 -0.9380 0.0068 +vn -0.8749 -0.4844 0.0011 +vn -0.8686 -0.4955 0.0028 +vn -0.8692 -0.4944 0.0026 +vn -0.8754 -0.4834 0.0009 +vn -0.9908 0.1356 -0.0016 +vn -0.9980 0.0631 0.0059 +vn -0.9378 0.3470 0.0100 +vn -0.8789 0.4770 -0.0044 +vn -0.5445 0.8387 0.0126 +vn -0.3730 0.9278 -0.0051 +vn 0.0286 0.9995 0.0116 +vn 0.2289 0.9734 -0.0034 +vn 0.5635 0.8261 0.0113 +vn 0.7377 0.6751 -0.0062 +vn 0.9230 0.3847 0.0125 +vn 1.0000 -0.0044 -0.0062 +vn 0.9903 -0.1384 0.0084 +vn 0.8169 -0.5767 0.0067 +vn 0.6757 -0.7116 -0.1926 +vn 0.8572 -0.5149 -0.0022 +vn 0.6951 -0.6852 0.2176 +vn 0.8931 -0.3884 -0.2270 +vn 0.9986 -0.0440 -0.0289 +vn 0.9290 -0.1254 -0.3482 +vn 0.9610 0.1814 -0.2087 +vn 0.8972 0.4415 0.0117 +vn 0.8424 0.4785 -0.2478 +vn 0.6412 0.7671 -0.0214 +vn 0.7001 0.6591 -0.2748 +vn 0.4179 0.8821 -0.2174 +vn 0.2043 0.9769 -0.0632 +vn 0.0677 0.9567 -0.2832 +vn -0.1906 0.9570 -0.2187 +vn -0.3331 0.9425 -0.0264 +vn -0.5424 0.7994 -0.2583 +vn -0.6734 0.7391 -0.0162 +vn -0.8146 0.5320 -0.2311 +vn -0.9008 0.4341 -0.0129 +vn -0.9649 0.1885 -0.1828 +vn -0.9494 0.2183 0.2257 +vn -0.9450 -0.2429 -0.2189 +vn -0.9853 -0.1034 -0.1359 +vn -0.8613 -0.5078 -0.0174 +vn -0.7860 -0.5189 -0.3360 +vn -0.6909 -0.6888 -0.2198 +vn -0.5777 -0.8162 -0.0022 +vn -0.4246 -0.8815 -0.2067 +vn -0.1112 -0.9938 0.0033 +vn -0.1096 -0.9594 -0.2600 +vn 0.2784 -0.9448 -0.1726 +vn 0.1794 -0.9590 0.2192 +vn 0.4942 -0.8358 -0.2391 +vn -0.6550 0.4939 -0.5718 +vn -0.4559 0.6284 -0.6304 +vn -0.5160 0.3773 -0.7690 +vn -0.6131 0.1105 -0.7822 +vn -0.3540 0.4701 -0.8085 +vn -0.7418 0.2688 -0.6144 +vn -0.7784 0.0195 -0.6275 +vn -0.7317 -0.2255 -0.6433 +vn -0.6142 -0.2150 -0.7593 +vn -0.5954 -0.3702 -0.7130 +vn -0.4352 -0.4476 -0.7812 +vn -0.4584 -0.7058 -0.5401 +vn -0.4571 -0.5565 -0.6939 +vn -0.2585 -0.7131 -0.6517 +vn -0.1164 -0.6013 -0.7905 +vn -0.0986 -0.8139 -0.5726 +vn 0.0337 -0.6676 -0.7438 +vn 0.1539 -0.8288 -0.5380 +vn 0.2488 -0.6361 -0.7304 +vn 0.2893 -0.5110 -0.8094 +vn 0.4284 -0.7178 -0.5489 +vn 0.4975 -0.5036 -0.7063 +vn 0.5496 -0.2875 -0.7844 +vn 0.6727 -0.5018 -0.5437 +vn 0.7038 -0.2989 -0.6444 +vn 0.7085 -0.0682 -0.7024 +vn 0.6244 0.0850 -0.7764 +vn 0.7816 0.1669 -0.6011 +vn 0.6828 0.3485 -0.6421 +vn 0.5194 0.3618 -0.7742 +vn 0.4892 0.5451 -0.6809 +vn 0.4405 0.7063 -0.5541 +vn 0.2826 0.5509 -0.7853 +vn 0.1901 0.7088 -0.6793 +vn -0.0338 0.6072 -0.7938 +vn -0.0406 0.7826 -0.6211 +vn -0.2486 0.6852 -0.6847 +vn -0.6539 0.7566 0.0000 +vn -0.9822 -0.1879 0.0000 +vn -0.3283 -0.9446 0.0000 +vn 0.6537 -0.7567 0.0000 +vn 0.9822 0.1879 0.0000 +vn 0.3282 0.9446 0.0000 +vn 0.1144 -0.1366 0.9840 +vn -0.1263 -0.1294 0.9835 +vn -0.2710 -0.2905 0.9177 +vn 0.3055 -0.3181 0.8975 +vn -0.0044 -0.5995 0.8004 +vn -0.0120 -0.7580 0.6521 +vn 0.0012 -0.6444 0.7647 +vn -0.0001 -0.7778 0.6286 +vn -0.0070 -0.8049 0.5934 +vn 0.0070 -0.7748 0.6322 +vn 0.0013 -0.8276 0.5612 +vn -0.0002 -0.8280 0.5607 +vn -0.0013 -0.8276 0.5613 +vn 0.0011 -0.8275 0.5614 +vn -0.0018 -0.8272 0.5619 +vn 0.0024 -0.8271 0.5621 +vn -0.0049 -0.8258 0.5639 +vn -0.0035 -0.8269 0.5624 +vn 0.0048 -0.8268 0.5625 +vn 0.0042 -0.8268 0.5625 +vn -0.0022 -0.8266 0.5628 +vn -0.0012 -0.8280 0.5607 +vn 0.0018 -0.8274 0.5616 +vn 0.0000 -0.9987 0.0501 +vn -0.0001 -0.9987 0.0510 +vn -0.0012 -0.9984 0.0568 +vn -0.0013 -0.9983 0.0577 +vn -1.0000 0.0007 0.0072 +vn -1.0000 -0.0000 0.0000 +vn -1.0000 -0.0014 0.0070 +vn -0.9777 -0.0074 0.2099 +vn -0.9734 0.0055 0.2292 +vn 0.1571 0.0132 -0.9875 +vn 0.6804 0.0181 -0.7326 +vn 0.4982 -0.0143 -0.8670 +vn 0.0841 -0.0094 -0.9964 +vn -0.3942 -0.0145 -0.9189 +vn -0.7499 -0.0112 -0.6615 +vn -0.7670 0.0095 -0.6416 +vn 0.9492 0.0127 -0.3143 +vn 0.8348 -0.0210 -0.5501 +vn -0.9641 -0.0049 -0.2656 +vn -0.9532 -0.0138 0.3019 +vn -0.9590 0.0086 0.2832 +vn -0.3233 0.0142 -0.9462 +vn -0.1511 -0.0125 0.9884 +vn 0.2862 -0.0007 0.9582 +vn 0.0986 0.0095 0.9951 +vn -0.3906 0.0128 0.9205 +vn -0.7394 0.0107 0.6731 +vn -0.6230 -0.0140 0.7821 +vn 0.6287 0.0046 0.7776 +vn 0.8202 0.0111 0.5720 +vn 0.9823 -0.0044 0.1872 +vn 0.9851 0.0025 0.1722 +vn 0.7784 -0.0075 0.6277 +vn 0.4243 0.0139 0.9054 +vn -0.0773 0.0111 0.9969 +vn -0.4719 0.0050 0.8816 +vn -0.7527 -0.0079 0.6583 +vn -0.7773 0.0081 0.6291 +vn 0.1588 0.1955 0.9678 +vn -0.0113 0.7253 0.6884 +vn -0.1411 0.1609 0.9768 +vn 0.0060 0.6503 0.7596 +vn 0.0027 0.7974 0.6034 +vn -0.0013 0.8279 0.5609 +vn 0.0004 0.8278 0.5611 +vn 0.0008 0.8277 0.5611 +vn -0.0039 0.8033 0.5955 +vn -0.0035 0.8224 0.5689 +vn -0.0019 0.8275 0.5615 +vn 0.0001 0.8263 0.5633 +vn -0.0002 0.8265 0.5630 +vn 0.0015 0.8269 0.5623 +vn -0.0018 0.8270 0.5621 +vn 0.0003 0.8263 0.5633 +vn 0.0005 0.8267 0.5627 +vn -0.9628 -0.0013 0.2703 +vn -0.9797 0.0027 0.2006 +vn -0.9999 -0.0005 0.0132 +vn -1.0000 -0.0006 0.0063 +vn 0.0000 0.9988 0.0486 +vn 0.0001 0.9988 0.0495 +vn 0.0011 0.9985 0.0553 +vn 0.0013 0.9984 0.0561 +vn -0.7434 -0.0059 0.6688 +vn -0.7164 0.0124 0.6976 +vn -0.4264 -0.0099 0.9045 +vn -0.0536 0.0008 0.9986 +vn 0.3670 -0.0021 0.9302 +vn 0.5996 0.0018 0.8003 +vn 0.7864 -0.0112 0.6176 +vn 0.8056 0.0064 0.5925 +vn 0.9844 0.0024 0.1758 +vn 0.9795 -0.0028 0.2013 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn -0.8722 0.0232 -0.4885 +vn -0.6270 -0.0304 -0.7784 +vn -0.9497 0.0490 -0.3094 +vn -0.0183 0.9995 0.0243 +vn -0.0074 0.9999 0.0156 +vn -0.3697 0.9135 -0.1696 +vn -0.0099 -0.9997 -0.0236 +vn 0.0210 -0.9991 0.0357 +vn -0.0051 -1.0000 -0.0010 +vn -0.0009 -0.9999 0.0168 +vn 0.0676 -0.9973 0.0276 +vn 0.0978 -0.9940 0.0487 +vn 0.0088 -0.9989 0.0456 +vn 0.0016 -0.9979 -0.0649 +vn 0.0098 -0.9994 0.0335 +vn -0.0069 -0.9997 0.0214 +vn -0.1936 -0.9804 -0.0359 +vn -0.0985 -0.9822 -0.1597 +vn 0.0116 -0.9999 0.0070 +vn 0.0006 -1.0000 0.0071 +vn 0.0249 -0.9997 -0.0022 +vn -0.0788 -0.9967 0.0177 +vn -0.2396 0.0217 -0.9706 +vn -0.2128 -0.0254 -0.9768 +vn -0.4011 -0.0507 -0.9146 +vn -0.5497 0.0248 -0.8350 +vn -0.8082 -0.0426 -0.5873 +vn -0.9216 0.0276 -0.3873 +vn -0.9722 -0.0681 -0.2240 +vn -0.9836 0.0148 0.1795 +vn -0.9567 -0.0325 0.2894 +vn -0.8809 -0.0442 0.4713 +vn -0.8866 0.0071 0.4625 +vn -0.4771 0.0009 0.8789 +vn -0.4916 -0.0069 0.8708 +vn -0.3242 -0.0273 0.9456 +vn -0.1844 0.0105 0.9828 +vn 0.2180 -0.0585 0.9742 +vn 0.4152 0.0245 0.9094 +vn 0.7349 -0.0612 0.6754 +vn 0.8143 0.0103 0.5804 +vn 0.9858 -0.0362 0.1637 +vn 0.9839 0.0042 0.1786 +vn 0.9583 -0.0046 -0.2857 +vn 0.9543 -0.0434 -0.2956 +vn 0.8830 -0.0544 -0.4662 +vn 0.8687 -0.0043 -0.4952 +vn 0.4536 0.0166 -0.8910 +vn 0.4243 -0.0275 -0.9051 +vn 0.4359 0.0029 -0.9000 +vn 0.4081 -0.0393 -0.9121 +vn -0.1786 0.0071 -0.9839 +vn -0.3574 -0.0027 -0.9340 +vn -0.6865 0.0273 -0.7267 +vn -0.8316 -0.0062 -0.5554 +vn -0.8834 0.0835 -0.4612 +vn -0.9577 -0.0067 -0.2877 +vn -0.9468 -0.0036 0.3217 +vn -0.9247 0.0042 0.3806 +vn -0.9265 0.0036 0.3763 +vn -0.9483 -0.0042 0.3172 +vn -0.5591 0.1926 0.8065 +vn -0.4267 -0.0062 0.9044 +vn -0.2711 0.4136 0.8691 +vn -0.0991 -0.0075 0.9951 +vn 0.2824 0.0564 0.9576 +vn 0.6158 -0.0083 0.7879 +vn 0.7826 0.0050 0.6225 +vn 0.8911 -0.0074 0.4537 +vn 0.9297 0.0015 0.3683 +vn 0.9324 0.0199 -0.3610 +vn 0.9418 -0.0015 -0.3360 +vn 0.9412 -0.0013 -0.3379 +vn 0.9317 0.0244 -0.3625 +vn 0.4380 0.0065 -0.8989 +vn 0.5171 -0.0012 -0.8560 +vn 0.2438 0.0000 -0.9698 +vn 0.2326 0.0069 -0.9726 +vn -0.0833 0.9826 -0.1662 +vn -0.0438 0.9910 -0.1266 +vn 0.0588 0.9871 -0.1487 +vn 0.0426 0.9944 -0.0970 +vn 0.1667 0.9827 -0.0802 +vn 0.0476 0.9988 -0.0082 +vn -0.2142 0.9767 -0.0119 +vn -0.0849 0.9901 -0.1116 +vn 0.4277 0.8443 0.3228 +vn 0.0387 0.9991 0.0200 +vn 0.0238 0.9981 0.0574 +vn -0.0009 0.9761 0.2172 +vn -0.0119 0.9984 0.0556 +vn -0.3728 0.8527 0.3660 +vn -0.0401 0.9991 0.0157 +vn -0.0431 0.9991 0.0048 +vn -0.1125 -0.0340 -0.9931 +vn -0.4174 0.0316 -0.9082 +vn -0.5126 -0.1870 -0.8380 +vn -0.8426 0.0929 -0.5304 +vn -0.5765 -0.1589 0.8015 +vn -0.1407 0.0719 0.9874 +vn -0.3144 0.0063 0.9493 +vn 0.1307 0.0312 0.9909 +vn 0.3507 0.0654 0.9342 +vn 0.5398 0.0389 0.8409 +vn 0.6699 0.2435 0.7014 +vn 0.8921 0.0851 0.4438 +vn 0.9681 -0.0639 0.2424 +vn 0.9562 -0.2114 0.2027 +vn 0.7885 -0.0974 -0.6073 +vn 0.6659 -0.2059 -0.7171 +vn 0.7163 0.0154 -0.6976 +vn 0.0601 0.0243 -0.9979 +vn 0.0674 -0.0876 -0.9939 +vn -0.8704 -0.0203 -0.4920 +vn -0.9840 0.1749 0.0332 +vn -0.9958 -0.0397 0.0828 +vn -0.9795 -0.1273 0.1563 +vn 0.9377 0.1133 -0.3285 +vn 0.8817 0.3732 -0.2886 +vn -0.7159 0.5009 0.4865 +vn 0.9110 -0.3863 0.1444 +vn 0.7226 0.0721 -0.6875 +vn 0.0160 0.0993 -0.9949 +vn -0.4575 -0.3479 0.8184 +vn 0.7185 0.0270 -0.6950 +vn 0.7462 0.0241 -0.6653 +vn 0.7928 0.0214 0.6090 +vn 0.9786 0.0215 0.2047 +vn 0.1056 0.0159 0.9943 +vn -0.5147 0.0162 0.8572 +vn -0.9964 0.0229 -0.0813 +vn -0.7574 0.0177 0.6527 +vn -0.8501 -0.0041 0.5266 +vn -0.2826 0.0066 -0.9592 +vn -0.0026 0.9997 0.0225 +vn 0.0601 -0.0068 -0.9982 +vn -0.6588 0.7187 0.2223 +vn -0.5237 0.8406 0.1381 +vn -0.8331 0.3289 -0.4447 +vn -0.2978 0.8979 -0.3243 +vn 0.3288 0.8553 -0.4003 +vn 0.9228 0.1396 -0.3592 +vn 0.4270 0.9023 0.0587 +vn 0.7870 0.5317 0.3128 +vn 0.6273 0.5767 0.5233 +vn 0.2338 0.8354 0.4974 +vn 0.0262 0.4760 0.8790 +vn -0.2029 -0.3051 -0.9304 +vn -0.4239 -0.7540 -0.5018 +vn -0.3384 -0.8796 -0.3344 +vn -0.8500 -0.3649 -0.3799 +vn -0.6554 -0.7550 0.0190 +vn -0.5010 -0.8640 0.0508 +vn -0.8260 -0.3433 0.4470 +vn -0.3255 -0.8551 0.4036 +vn 0.0010 -0.7954 0.6061 +vn 0.4623 -0.2399 0.8537 +vn 0.3232 -0.8789 0.3509 +vn 0.8436 -0.3616 0.3970 +vn 0.4790 -0.8750 0.0703 +vn 0.8114 -0.3765 -0.4471 +vn 0.3440 -0.8631 -0.3699 +vn 0.4001 -0.2012 -0.8941 +vn 0.0259 -0.8919 -0.4514 +vn 0.5375 -0.0465 0.8420 +vn 0.5132 -0.0566 0.8564 +vn 0.4972 -0.0141 0.8675 +vn -0.4614 -0.0456 0.8860 +vn -0.4856 -0.0553 0.8724 +vn -0.5027 -0.0133 0.8643 +vn 0.9995 -0.0204 0.0224 +vn 0.9995 -0.0259 0.0152 +vn 0.9996 -0.0242 0.0174 +vn 0.9995 -0.0298 0.0100 +vn 0.4845 0.0015 0.8748 +vn 0.4964 -0.0077 0.8680 +vn -0.5158 0.0018 0.8567 +vn -0.5041 -0.0075 0.8636 +vn -1.0000 -0.0049 -0.0019 +vn -0.9987 -0.0202 -0.0465 +vn -0.9997 -0.0260 0.0008 +vn -0.9949 0.0071 -0.1002 +vn -0.9959 0.0005 0.0901 +vn -0.4808 -0.0260 -0.8765 +vn -0.4588 -0.0070 -0.8885 +vn -0.4646 -0.0120 -0.8854 +vn -0.4425 0.0069 -0.8968 +vn 0.5191 -0.0235 -0.8544 +vn 0.5415 -0.0036 -0.8407 +vn 0.5357 -0.0088 -0.8444 +vn 0.5576 0.0111 -0.8300 +vn 1.0000 -0.0037 0.0085 +vn 1.0000 0.0007 0.0064 +vn 1.0000 0.0000 0.0000 +vn 1.0000 0.0023 0.0086 +vn 1.0000 -0.0006 0.0056 +vn -0.5646 -0.8203 -0.0910 +vn -0.2343 -0.9712 -0.0438 +vn -0.3716 -0.9280 0.0274 +vn 0.9921 -0.1238 0.0214 +vn 0.7088 -0.7051 0.0232 +vn 0.9663 -0.2563 -0.0237 +vn 0.5842 -0.8112 -0.0277 +vn 0.1569 -0.9867 0.0430 +vn 0.5076 0.8614 -0.0146 +vn 0.3714 0.9283 -0.0172 +vn 0.5425 0.8400 0.0106 +vn 0.9932 0.0030 0.1163 +vn 0.8693 0.0011 0.4943 +vn 0.9029 -0.0049 0.4297 +vn 0.9983 -0.0131 -0.0567 +vn 0.5747 0.0028 0.8184 +vn -0.9821 0.0031 -0.1883 +vn 0.8174 0.5758 0.0181 +vn 0.9018 0.4320 -0.0139 +vn -0.9169 -0.3950 0.0574 +vn -0.9995 0.0054 0.0308 +vn -0.9997 -0.0018 -0.0241 +vn -0.9236 0.3828 0.0184 +vn -0.9827 0.1843 -0.0193 +vn -0.4396 0.8981 -0.0092 +vn -0.4793 0.8775 -0.0177 +vn -0.3296 0.9440 0.0136 +vn -0.3028 0.9529 0.0190 +vn -0.0007 -1.0000 -0.0017 +vn -0.0001 -1.0000 0.0001 +vn 0.0002 -1.0000 0.0005 +vn -0.0001 -1.0000 -0.0001 +vn -0.0002 -1.0000 -0.0001 +vn -0.3201 0.7918 0.5202 +vn -0.5807 0.7919 0.1891 +vn -0.5795 0.7927 0.1895 +vn 0.0609 0.7952 0.6033 +vn -0.3141 0.7961 0.5172 +vn -0.1689 0.8258 -0.5381 +vn -0.5726 0.7728 -0.2737 +vn 0.0654 0.7919 0.6072 +vn 0.2876 0.7667 0.5740 +vn 0.4932 0.7709 -0.4030 +vn 0.4968 0.7681 -0.4041 +vn 0.4984 0.7667 -0.4046 +vn -0.1157 0.9222 -0.3690 +vn 0.0312 0.7828 -0.6215 +vn 0.6304 0.7630 0.1426 +vn 0.6284 0.7650 0.1408 +vn 0.6274 0.7660 0.1399 +vn -0.0086 0.9999 0.0069 +vn 0.0015 0.9999 0.0149 +vn -0.0136 0.9998 0.0168 +vn 0.2905 0.7642 0.5759 +vn 0.4921 0.7718 -0.4027 +vn 0.0069 0.7572 -0.6531 +vn 0.6320 0.7615 0.1439 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 5/5/5 6/6/6 4/4/7 +f 4/4/7 6/6/6 3/3/8 +f 6/6/9 5/5/10 7/7/11 +f 7/7/11 5/5/10 8/8/12 +f 1/1/13 7/7/14 8/8/15 +f 2/2/16 1/1/13 8/8/15 +f 5/5/17 2/2/17 8/8/17 +f 5/5/17 4/4/17 2/2/17 +f 6/6/18 7/7/18 1/1/18 +f 3/3/18 6/6/18 1/1/18 +f 9/9/19 10/10/20 11/11/21 +f 12/12/22 13/13/23 14/14/24 +f 14/14/24 10/10/20 9/9/19 +f 15/15/25 16/16/26 17/17/27 +f 18/18/28 19/19/29 15/15/25 +f 15/15/25 19/19/29 16/16/26 +f 9/9/19 11/11/21 18/18/28 +f 18/18/28 11/11/21 19/19/29 +f 20/20/30 13/13/23 12/12/22 +f 21/21/31 22/22/32 23/23/33 +f 24/24/34 25/25/35 17/17/27 +f 12/12/22 14/14/24 9/9/19 +f 23/23/33 22/22/32 20/20/30 +f 23/23/33 20/20/30 12/12/22 +f 24/24/34 21/21/31 25/25/35 +f 25/25/35 21/21/31 23/23/33 +f 15/15/25 17/17/27 25/25/35 +f 26/26/36 27/27/37 28/28/38 +f 28/28/38 29/29/39 26/26/36 +f 28/28/38 30/30/40 29/29/39 +f 31/31/41 30/30/40 28/28/38 +f 28/28/38 32/32/42 31/31/41 +f 28/28/38 33/33/43 32/32/42 +f 28/28/38 34/34/44 33/33/43 +f 35/35/45 34/34/44 28/28/38 +f 36/36/46 35/35/45 28/28/38 +f 37/37/47 28/28/48 38/38/49 +f 38/38/49 28/28/48 27/27/50 +f 38/38/49 27/27/50 39/39/51 +f 39/39/51 27/27/50 26/26/52 +f 39/39/53 26/26/54 29/29/55 +f 39/39/53 29/29/55 40/40/56 +f 40/40/56 29/29/55 30/30/57 +f 40/40/56 30/30/57 41/41/58 +f 41/41/59 30/30/60 31/31/61 +f 41/41/59 31/31/61 42/42/62 +f 42/42/62 31/31/61 32/32/63 +f 42/42/62 32/32/63 43/43/64 +f 43/43/64 32/32/63 33/33/65 +f 43/43/64 33/33/65 44/44/66 +f 44/44/66 33/33/65 34/34/67 +f 44/44/68 34/34/69 35/35/70 +f 44/44/68 35/35/70 37/37/47 +f 37/37/47 35/35/70 36/36/71 +f 37/37/47 36/36/71 28/28/48 +f 42/42/17 45/45/17 46/46/17 +f 42/42/17 46/46/17 41/41/17 +f 43/43/17 47/47/17 45/45/17 +f 43/43/17 45/45/17 42/42/17 +f 40/40/17 48/48/17 39/39/17 +f 37/37/17 49/49/17 50/50/17 +f 37/37/17 50/50/17 44/44/17 +f 38/38/17 51/51/17 37/37/17 +f 37/37/17 51/51/17 49/49/17 +f 43/43/17 52/52/17 47/47/17 +f 44/44/17 52/52/17 43/43/17 +f 38/38/17 53/53/17 51/51/17 +f 40/40/17 54/54/17 48/48/17 +f 50/50/17 55/55/17 44/44/17 +f 44/44/17 55/55/17 52/52/17 +f 39/39/17 56/56/17 38/38/17 +f 38/38/17 56/56/17 53/53/17 +f 39/39/17 48/48/17 56/56/17 +f 41/41/17 57/57/17 40/40/17 +f 40/40/17 57/57/17 54/54/17 +f 41/41/17 46/46/17 57/57/17 +f 58/58/72 59/59/73 49/49/74 +f 59/59/73 60/60/75 49/49/74 +f 60/60/75 50/50/76 49/49/74 +f 60/60/75 61/61/77 50/50/76 +f 61/61/77 55/55/78 50/50/76 +f 61/61/77 62/62/79 55/55/78 +f 55/55/78 62/62/79 52/52/80 +f 63/63/81 52/52/80 62/62/79 +f 63/63/81 47/47/82 52/52/80 +f 63/63/81 64/64/83 47/47/82 +f 64/64/83 65/65/84 47/47/82 +f 65/65/84 45/45/85 47/47/82 +f 65/65/84 66/66/86 45/45/85 +f 67/67/87 46/46/88 45/45/85 +f 67/67/87 45/45/85 66/66/86 +f 67/67/87 68/68/89 46/46/88 +f 46/46/88 68/68/89 57/57/90 +f 68/68/89 69/69/91 57/57/90 +f 57/57/90 69/69/91 54/54/92 +f 70/70/93 54/54/92 69/69/91 +f 54/54/92 70/70/93 48/48/94 +f 70/70/93 71/71/95 48/48/94 +f 71/71/95 72/72/96 48/48/94 +f 72/72/96 56/56/97 48/48/94 +f 72/72/96 73/73/98 56/56/97 +f 73/73/98 53/53/99 56/56/97 +f 74/74/100 53/53/99 73/73/98 +f 53/53/99 74/74/100 51/51/101 +f 74/74/100 75/75/102 51/51/101 +f 51/51/101 75/75/102 49/49/74 +f 49/49/74 75/75/102 58/58/72 +f 65/65/84 64/64/83 76/76/103 +f 21/21/104 24/24/105 77/77/106 +f 67/67/87 78/78/107 68/68/89 +f 79/79/108 78/78/107 77/77/106 +f 79/79/108 77/77/106 24/24/105 +f 78/78/107 79/79/108 80/80/109 +f 78/78/107 80/80/109 68/68/89 +f 68/68/89 80/80/109 69/69/91 +f 81/81/110 80/80/109 79/79/108 +f 81/81/110 79/79/108 24/24/105 +f 70/70/93 69/69/91 80/80/109 +f 24/24/105 17/17/111 81/81/110 +f 81/81/110 82/82/112 80/80/109 +f 80/80/109 82/82/112 70/70/93 +f 83/83/113 82/82/112 81/81/110 +f 83/83/113 81/81/110 17/17/111 +f 71/71/95 70/70/93 82/82/112 +f 82/82/112 83/83/113 71/71/95 +f 16/16/114 83/83/113 17/17/111 +f 84/84/115 83/83/113 16/16/114 +f 85/85/116 72/72/96 71/71/95 +f 85/85/116 71/71/95 83/83/113 +f 85/85/116 83/83/113 84/84/115 +f 73/73/98 72/72/96 85/85/116 +f 84/84/115 86/86/117 85/85/116 +f 86/86/117 84/84/115 16/16/114 +f 86/86/117 73/73/98 85/85/116 +f 86/86/117 16/16/114 19/19/118 +f 74/74/100 73/73/98 86/86/117 +f 87/87/119 86/86/117 19/19/118 +f 86/86/117 87/87/119 74/74/100 +f 87/87/119 19/19/118 88/88/120 +f 74/74/100 87/87/119 75/75/102 +f 88/88/120 19/19/118 11/11/121 +f 58/58/72 75/75/102 87/87/119 +f 58/58/72 87/87/119 88/88/120 +f 89/89/122 88/88/120 11/11/121 +f 89/89/122 58/58/72 88/88/120 +f 90/90/123 89/89/122 11/11/121 +f 10/10/124 90/90/123 11/11/121 +f 89/89/122 90/90/123 58/58/72 +f 58/58/72 90/90/123 59/59/73 +f 60/60/75 59/59/73 90/90/123 +f 91/91/125 60/60/75 90/90/123 +f 91/91/125 90/90/123 10/10/124 +f 61/61/77 60/60/75 92/92/126 +f 92/92/126 60/60/75 91/91/125 +f 14/14/127 91/91/125 10/10/124 +f 14/14/127 92/92/126 91/91/125 +f 62/62/79 61/61/77 92/92/126 +f 93/93/128 92/92/126 14/14/127 +f 14/14/127 13/13/129 93/93/128 +f 92/92/126 93/93/128 94/94/130 +f 92/92/126 94/94/130 62/62/79 +f 95/95/131 94/94/130 93/93/128 +f 63/63/81 62/62/79 94/94/130 +f 95/95/131 93/93/128 13/13/129 +f 63/63/81 94/94/130 95/95/131 +f 20/20/132 95/95/131 13/13/129 +f 96/96/133 63/63/81 95/95/131 +f 64/64/83 63/63/81 96/96/133 +f 97/97/134 96/96/133 95/95/131 +f 97/97/134 95/95/131 20/20/132 +f 76/76/103 64/64/83 96/96/133 +f 76/76/103 96/96/133 97/97/134 +f 20/20/132 22/22/135 97/97/134 +f 98/98/136 97/97/134 22/22/135 +f 98/98/136 76/76/103 97/97/134 +f 98/98/136 65/65/84 76/76/103 +f 66/66/86 65/65/84 98/98/136 +f 98/98/136 99/99/137 66/66/86 +f 21/21/104 98/98/136 22/22/135 +f 77/77/106 99/99/137 98/98/136 +f 77/77/106 98/98/136 21/21/104 +f 67/67/87 66/66/86 99/99/137 +f 99/99/137 77/77/106 78/78/107 +f 99/99/137 78/78/107 67/67/87 +f 9/9/138 18/18/138 100/100/138 +f 100/100/138 18/18/138 101/101/138 +f 12/12/139 9/9/139 102/102/139 +f 102/102/139 9/9/139 100/100/139 +f 23/23/140 12/12/140 103/103/140 +f 103/103/140 12/12/140 102/102/140 +f 25/25/141 23/23/141 104/104/141 +f 104/104/141 23/23/141 103/103/141 +f 15/15/142 25/25/142 105/105/142 +f 105/105/142 25/25/142 104/104/142 +f 18/18/143 15/15/143 101/101/143 +f 101/101/143 15/15/143 105/105/143 +f 105/105/18 104/104/18 101/101/18 +f 101/101/18 104/104/18 103/103/18 +f 101/101/18 103/103/18 100/100/18 +f 100/100/18 103/103/18 102/102/18 +f 106/106/144 107/107/145 108/108/146 +f 109/109/147 110/110/148 111/111/149 +f 112/112/150 113/113/151 114/114/152 +f 114/114/152 113/113/151 115/115/153 +f 116/116/154 112/112/150 117/117/155 +f 117/117/155 112/112/150 114/114/152 +f 117/117/155 111/111/149 116/116/154 +f 109/109/147 108/108/146 110/110/148 +f 118/118/156 119/119/157 120/120/158 +f 119/119/157 118/118/156 121/121/159 +f 115/115/153 113/113/151 122/122/160 +f 109/109/147 111/111/149 117/117/155 +f 106/106/144 108/108/146 109/109/147 +f 119/119/157 121/121/159 106/106/144 +f 106/106/144 121/121/159 107/107/145 +f 122/122/160 120/120/158 115/115/153 +f 115/115/153 120/120/158 119/119/157 +f 123/123/161 124/124/162 125/125/163 +f 125/125/163 126/126/164 123/123/161 +f 127/127/165 126/126/164 125/125/163 +f 128/128/166 127/127/165 125/125/163 +f 125/125/163 129/129/167 128/128/166 +f 130/130/168 131/131/169 125/125/163 +f 132/132/170 130/130/168 125/125/163 +f 125/125/163 133/133/171 132/132/170 +f 134/134/172 133/133/171 125/125/163 +f 124/124/162 134/134/172 125/125/163 +f 135/135/173 124/124/174 123/123/175 +f 135/135/173 123/123/175 136/136/176 +f 136/136/176 123/123/175 126/126/177 +f 136/136/176 126/126/177 137/137/178 +f 137/137/178 126/126/177 127/127/179 +f 137/137/180 127/127/181 128/128/182 +f 137/137/180 128/128/182 138/138/183 +f 138/138/184 128/128/185 139/139/186 +f 139/139/186 128/128/185 129/129/187 +f 139/139/188 129/129/189 125/125/190 +f 139/139/188 125/125/190 140/140/191 +f 140/140/191 125/125/190 131/131/192 +f 140/140/191 131/131/192 141/141/193 +f 141/141/193 131/131/192 130/130/194 +f 141/141/193 130/130/194 132/132/195 +f 141/141/193 132/132/195 142/142/196 +f 142/142/196 132/132/195 133/133/197 +f 142/142/196 133/133/197 143/143/198 +f 143/143/198 133/133/197 134/134/199 +f 143/143/198 134/134/199 144/144/200 +f 144/144/200 134/134/199 124/124/174 +f 144/144/200 124/124/174 135/135/173 +f 135/135/17 145/145/17 144/144/17 +f 140/140/17 146/146/17 147/147/17 +f 140/140/17 147/147/17 139/139/17 +f 141/141/17 148/148/17 146/146/17 +f 141/141/17 146/146/17 140/140/17 +f 138/138/17 149/149/17 150/150/17 +f 138/138/17 150/150/17 137/137/17 +f 143/143/17 151/151/17 152/152/17 +f 144/144/17 145/145/17 151/151/17 +f 144/144/17 151/151/17 143/143/17 +f 135/135/17 153/153/17 145/145/17 +f 142/142/17 148/148/17 141/141/17 +f 142/142/17 154/154/17 148/148/17 +f 136/136/17 155/155/17 135/135/17 +f 135/135/17 155/155/17 153/153/17 +f 139/139/17 149/149/17 138/138/17 +f 143/143/17 152/152/17 154/154/17 +f 143/143/17 154/154/17 142/142/17 +f 137/137/17 156/156/17 136/136/17 +f 136/136/17 156/156/17 155/155/17 +f 137/137/17 150/150/17 156/156/17 +f 139/139/17 157/157/17 149/149/17 +f 139/139/17 147/147/17 157/157/17 +f 158/158/201 159/159/202 145/145/203 +f 145/145/203 159/159/202 151/151/204 +f 159/159/202 160/160/205 151/151/204 +f 151/151/204 160/160/205 152/152/206 +f 161/161/207 152/152/206 160/160/205 +f 161/161/207 154/154/208 152/152/206 +f 161/161/207 162/162/209 154/154/208 +f 162/162/209 163/163/210 154/154/208 +f 154/154/208 163/163/210 148/148/211 +f 163/163/210 164/164/212 148/148/213 +f 164/164/212 146/146/214 148/148/213 +f 164/164/212 165/165/215 146/146/214 +f 165/165/215 147/147/216 146/146/214 +f 165/165/215 166/166/217 147/147/216 +f 147/147/216 166/166/217 157/157/218 +f 167/167/219 157/157/218 166/166/217 +f 167/167/219 168/168/220 157/157/218 +f 168/168/220 149/149/221 157/157/218 +f 169/169/222 149/149/223 168/168/220 +f 169/169/222 150/150/224 149/149/225 +f 170/170/226 150/150/224 169/169/222 +f 171/171/227 150/150/224 170/170/226 +f 171/171/227 156/156/228 150/150/224 +f 172/172/229 156/156/228 171/171/227 +f 156/156/228 172/172/229 155/155/230 +f 155/155/230 172/172/229 173/173/231 +f 155/155/230 173/173/231 153/153/232 +f 173/173/231 174/174/233 153/153/232 +f 153/153/232 174/174/233 145/145/203 +f 145/145/203 174/174/233 158/158/201 +f 169/169/222 168/168/220 175/175/234 +f 176/176/235 177/177/236 178/178/237 +f 177/177/236 176/176/235 121/121/238 +f 167/167/219 166/166/217 178/178/237 +f 179/179/239 167/167/219 178/178/237 +f 179/179/239 178/178/237 177/177/236 +f 177/177/236 121/121/238 118/118/240 +f 167/167/219 179/179/239 168/168/220 +f 175/175/234 179/179/239 177/177/236 +f 175/175/234 177/177/236 118/118/240 +f 179/179/239 175/175/234 168/168/220 +f 118/118/240 120/120/241 175/175/234 +f 180/180/242 175/175/234 120/120/241 +f 181/181/243 169/169/222 175/175/234 +f 181/181/243 175/175/234 180/180/242 +f 120/120/241 122/122/244 180/180/242 +f 170/170/226 169/169/222 181/181/243 +f 182/182/245 181/181/243 180/180/242 +f 180/180/242 122/122/244 182/182/245 +f 171/171/227 170/170/226 183/183/246 +f 183/183/246 170/170/226 181/181/243 +f 183/183/246 181/181/243 182/182/245 +f 184/184/247 183/183/246 182/182/245 +f 113/113/248 182/182/245 122/122/244 +f 183/183/246 184/184/247 171/171/227 +f 172/172/229 171/171/227 184/184/247 +f 184/184/247 182/182/245 113/113/248 +f 113/113/248 185/185/249 184/184/247 +f 173/173/231 172/172/229 184/184/247 +f 184/184/247 185/185/249 173/173/231 +f 112/112/250 185/185/249 113/113/248 +f 186/186/251 173/173/231 185/185/249 +f 186/186/251 185/185/249 112/112/250 +f 174/174/233 173/173/231 186/186/251 +f 187/187/252 186/186/251 112/112/250 +f 188/188/253 174/174/233 186/186/251 +f 188/188/253 186/186/251 187/187/252 +f 187/187/252 112/112/250 188/188/253 +f 174/174/233 188/188/253 158/158/201 +f 116/116/254 188/188/253 112/112/250 +f 188/188/253 116/116/254 189/189/255 +f 159/159/202 158/158/201 188/188/253 +f 188/188/253 189/189/255 159/159/202 +f 190/190/256 159/159/202 189/189/255 +f 190/190/256 189/189/255 116/116/254 +f 160/160/205 159/159/202 190/190/256 +f 111/111/257 190/190/256 116/116/254 +f 190/190/256 191/191/258 160/160/205 +f 191/191/258 190/190/256 111/111/257 +f 161/161/207 160/160/205 191/191/258 +f 111/111/257 192/192/259 191/191/258 +f 193/193/260 161/161/207 191/191/258 +f 193/193/260 191/191/258 192/192/259 +f 111/111/257 110/110/261 192/192/259 +f 162/162/209 161/161/207 193/193/260 +f 193/193/260 192/192/259 110/110/261 +f 162/162/209 193/193/260 194/194/262 +f 194/194/262 193/193/260 110/110/261 +f 195/195/263 162/162/209 194/194/262 +f 108/108/264 194/194/262 110/110/261 +f 194/194/262 108/108/264 195/195/263 +f 163/163/210 162/162/209 195/195/263 +f 196/196/265 195/195/263 108/108/264 +f 195/195/263 197/197/266 163/163/210 +f 164/164/212 163/163/210 197/197/266 +f 197/197/266 195/195/263 196/196/265 +f 107/107/267 196/196/265 108/108/264 +f 197/197/266 196/196/265 107/107/267 +f 165/165/215 164/164/212 197/197/266 +f 197/197/266 107/107/267 198/198/268 +f 199/199/269 165/165/215 197/197/266 +f 199/199/269 197/197/266 198/198/268 +f 121/121/238 198/198/268 107/107/267 +f 176/176/235 199/199/269 198/198/268 +f 176/176/235 198/198/268 121/121/238 +f 166/166/217 165/165/215 199/199/269 +f 178/178/237 166/166/217 199/199/269 +f 178/178/237 199/199/269 176/176/235 +f 117/117/270 114/114/270 200/200/270 +f 200/200/270 114/114/270 201/201/270 +f 109/109/271 117/117/271 202/202/271 +f 202/202/271 117/117/271 200/200/271 +f 106/106/272 109/109/272 203/203/272 +f 203/203/272 109/109/272 202/202/272 +f 119/119/273 106/106/273 204/204/273 +f 204/204/273 106/106/273 203/203/273 +f 115/115/274 119/119/274 205/205/274 +f 205/205/274 119/119/274 204/204/274 +f 114/114/275 115/115/275 201/201/275 +f 201/201/275 115/115/275 205/205/275 +f 205/205/18 204/204/18 201/201/18 +f 201/201/18 204/204/18 203/203/18 +f 201/201/18 203/203/18 200/200/18 +f 200/200/18 203/203/18 202/202/18 +f 206/206/276 207/207/277 208/208/278 +f 209/209/279 210/210/280 211/211/281 +f 212/212/282 213/213/283 214/214/284 +f 211/211/281 210/210/280 215/215/285 +f 215/215/285 210/210/280 216/216/286 +f 215/215/285 216/216/286 217/217/287 +f 218/218/288 219/219/289 211/211/281 +f 211/211/281 219/219/289 209/209/279 +f 218/218/288 214/214/284 219/219/289 +f 212/212/282 206/206/276 213/213/283 +f 220/220/290 221/221/291 222/222/292 +f 212/212/282 214/214/284 218/218/288 +f 207/207/277 206/206/276 212/212/282 +f 220/220/290 222/222/292 207/207/277 +f 207/207/277 222/222/292 208/208/278 +f 215/215/285 217/217/287 221/221/291 +f 215/215/285 221/221/291 220/220/290 +f 223/223/293 224/224/294 225/225/295 +f 226/226/296 224/224/294 223/223/293 +f 223/223/293 227/227/297 226/226/296 +f 223/223/293 228/228/298 227/227/297 +f 223/223/293 229/229/299 230/230/300 +f 223/223/293 231/231/301 229/229/299 +f 232/232/302 231/231/301 223/223/293 +f 225/225/295 232/232/302 223/223/293 +f 233/233/303 225/225/304 224/224/305 +f 233/233/303 224/224/305 234/234/306 +f 234/234/306 224/224/305 226/226/307 +f 234/234/306 226/226/307 235/235/308 +f 235/235/308 226/226/307 227/227/309 +f 235/235/310 227/227/311 236/236/312 +f 236/236/312 227/227/311 228/228/313 +f 236/236/314 228/228/315 237/237/316 +f 237/237/316 228/228/315 223/223/317 +f 237/237/316 223/223/317 238/238/318 +f 238/238/318 223/223/317 230/230/319 +f 238/238/318 230/230/319 239/239/320 +f 239/239/320 230/230/319 229/229/321 +f 239/239/320 229/229/321 231/231/322 +f 239/239/320 231/231/322 240/240/323 +f 240/240/323 231/231/322 232/232/324 +f 240/240/323 232/232/324 241/241/325 +f 241/241/325 232/232/324 225/225/304 +f 241/241/325 225/225/304 233/233/303 +f 233/233/17 242/242/17 241/241/17 +f 238/238/17 243/243/17 244/244/17 +f 238/238/17 244/244/17 237/237/17 +f 239/239/17 245/245/17 243/243/17 +f 239/239/17 243/243/17 238/238/17 +f 236/236/17 246/246/17 235/235/17 +f 241/241/17 247/247/17 248/248/17 +f 241/241/17 248/248/17 240/240/17 +f 241/241/17 242/242/17 247/247/17 +f 233/233/17 249/249/17 242/242/17 +f 234/234/17 249/249/17 233/233/17 +f 240/240/17 250/250/17 239/239/17 +f 239/239/17 250/250/17 245/245/17 +f 234/234/17 251/251/17 249/249/17 +f 236/236/17 252/252/17 246/246/17 +f 240/240/17 248/248/17 250/250/17 +f 235/235/17 253/253/17 234/234/17 +f 234/234/17 253/253/17 251/251/17 +f 235/235/17 246/246/17 253/253/17 +f 237/237/17 254/254/17 236/236/17 +f 236/236/17 254/254/17 252/252/17 +f 237/237/17 244/244/17 254/254/17 +f 255/255/326 256/256/327 242/242/328 +f 256/256/327 247/247/329 242/242/328 +f 256/256/327 257/257/330 247/247/329 +f 247/247/329 257/257/330 248/248/331 +f 258/258/332 248/248/331 257/257/330 +f 258/258/332 250/250/333 248/248/331 +f 258/258/332 259/259/334 250/250/333 +f 259/259/334 260/260/335 250/250/333 +f 250/250/333 260/260/335 245/245/336 +f 260/260/335 261/261/337 245/245/336 +f 261/261/337 243/243/338 245/245/339 +f 261/261/337 262/262/340 243/243/338 +f 262/262/340 244/244/341 243/243/338 +f 262/262/340 263/263/342 244/244/341 +f 244/244/341 263/263/342 254/254/343 +f 264/264/344 254/254/343 263/263/342 +f 264/264/344 265/265/345 254/254/343 +f 265/265/345 252/252/346 254/254/343 +f 266/266/347 252/252/346 265/265/345 +f 252/252/346 266/266/347 246/246/348 +f 266/266/347 267/267/349 246/246/348 +f 246/246/348 267/267/349 253/253/350 +f 253/253/350 267/267/349 268/268/351 +f 268/268/351 269/269/352 253/253/350 +f 253/253/350 269/269/352 251/251/353 +f 269/269/352 270/270/354 251/251/353 +f 251/251/353 270/270/354 249/249/355 +f 270/270/354 271/271/356 249/249/355 +f 249/249/355 271/271/356 242/242/328 +f 242/242/328 271/271/356 255/255/326 +f 262/262/340 261/261/337 272/272/357 +f 273/273/358 222/222/359 274/274/360 +f 264/264/344 263/263/342 274/274/360 +f 222/222/359 275/275/361 274/274/360 +f 265/265/345 264/264/344 276/276/362 +f 276/276/362 264/264/344 274/274/360 +f 276/276/362 274/274/360 275/275/361 +f 222/222/359 221/221/363 275/275/361 +f 277/277/364 276/276/362 275/275/361 +f 275/275/361 221/221/363 277/277/364 +f 266/266/347 265/265/345 276/276/362 +f 277/277/364 278/278/365 276/276/362 +f 276/276/362 278/278/365 266/266/347 +f 221/221/363 217/217/366 277/277/364 +f 277/277/364 217/217/366 278/278/365 +f 279/279/367 266/266/347 278/278/365 +f 279/279/367 278/278/365 217/217/366 +f 266/266/347 279/279/367 267/267/349 +f 280/280/368 267/267/349 279/279/367 +f 216/216/369 279/279/367 217/217/366 +f 280/280/368 279/279/367 216/216/369 +f 280/280/368 268/268/351 267/267/349 +f 280/280/368 281/281/370 268/268/351 +f 281/281/370 280/280/368 216/216/369 +f 269/269/352 268/268/351 281/281/370 +f 210/210/371 281/281/370 216/216/369 +f 282/282/372 281/281/370 210/210/371 +f 281/281/370 282/282/372 270/270/354 +f 281/281/370 270/270/354 269/269/352 +f 210/210/371 283/283/373 282/282/372 +f 284/284/374 270/270/354 282/282/372 +f 209/209/375 283/283/373 210/210/371 +f 271/271/356 270/270/354 284/284/374 +f 282/282/372 283/283/373 284/284/374 +f 283/283/373 209/209/375 285/285/376 +f 283/283/373 285/285/376 284/284/374 +f 284/284/374 285/285/376 286/286/377 +f 286/286/377 271/271/356 284/284/374 +f 209/209/375 219/219/378 285/285/376 +f 271/271/356 286/286/377 255/255/326 +f 285/285/376 287/287/379 286/286/377 +f 287/287/379 255/255/326 286/286/377 +f 285/285/376 219/219/378 287/287/379 +f 288/288/380 255/255/326 287/287/379 +f 287/287/379 219/219/378 289/289/381 +f 287/287/379 289/289/381 288/288/380 +f 256/256/327 255/255/326 288/288/380 +f 288/288/380 290/290/382 256/256/327 +f 290/290/382 288/288/380 289/289/381 +f 257/257/330 256/256/327 290/290/382 +f 214/214/383 289/289/381 219/219/378 +f 291/291/384 290/290/382 289/289/381 +f 214/214/383 291/291/384 289/289/381 +f 291/291/384 257/257/330 290/290/382 +f 291/291/384 214/214/383 292/292/385 +f 257/257/330 291/291/384 258/258/332 +f 214/214/383 213/213/386 292/292/385 +f 291/291/384 292/292/385 258/258/332 +f 258/258/332 292/292/385 259/259/334 +f 259/259/334 292/292/385 293/293/387 +f 293/293/387 292/292/385 213/213/386 +f 294/294/388 259/259/334 293/293/387 +f 206/206/389 293/293/387 213/213/386 +f 260/260/335 259/259/334 294/294/388 +f 294/294/388 293/293/387 206/206/389 +f 295/295/390 260/260/335 294/294/388 +f 261/261/337 260/260/335 295/295/390 +f 295/295/390 294/294/388 206/206/389 +f 272/272/357 261/261/337 295/295/390 +f 296/296/391 295/295/390 206/206/389 +f 272/272/357 295/295/390 296/296/391 +f 206/206/389 208/208/392 296/296/391 +f 297/297/393 272/272/357 296/296/391 +f 297/297/393 262/262/340 272/272/357 +f 273/273/358 297/297/393 296/296/391 +f 296/296/391 208/208/392 273/273/358 +f 222/222/359 273/273/358 208/208/392 +f 263/263/342 262/262/340 297/297/393 +f 297/297/393 273/273/358 274/274/360 +f 297/297/393 274/274/360 263/263/342 +f 218/218/394 211/211/394 298/298/394 +f 298/298/394 211/211/394 299/299/394 +f 212/212/395 218/218/395 300/300/395 +f 300/300/395 218/218/395 298/298/395 +f 207/207/396 212/212/396 301/301/396 +f 301/301/396 212/212/396 300/300/396 +f 220/220/397 207/207/397 302/302/397 +f 302/302/397 207/207/397 301/301/397 +f 215/215/398 220/220/398 303/303/398 +f 303/303/398 220/220/398 302/302/398 +f 211/211/399 215/215/399 299/299/399 +f 299/299/399 215/215/399 303/303/399 +f 303/303/18 302/302/18 299/299/18 +f 299/299/18 302/302/18 301/301/18 +f 299/299/18 301/301/18 298/298/18 +f 298/298/18 301/301/18 300/300/18 +f 304/304/400 305/305/401 306/306/402 +f 307/307/403 308/308/404 309/309/405 +f 309/309/405 310/310/406 311/311/407 +f 312/312/408 313/313/409 314/314/410 +f 315/315/411 316/316/412 312/312/408 +f 306/306/402 305/305/401 317/317/413 +f 306/306/402 317/317/413 315/315/411 +f 315/315/411 317/317/413 316/316/412 +f 318/318/414 319/319/415 320/320/416 +f 312/312/408 316/316/412 313/313/409 +f 319/319/415 304/304/400 320/320/416 +f 320/320/416 304/304/400 306/306/402 +f 311/311/407 310/310/406 320/320/416 +f 320/320/416 310/310/406 318/318/414 +f 307/307/403 309/309/405 311/311/407 +f 312/312/408 314/314/410 307/307/403 +f 307/307/403 314/314/410 308/308/404 +f 321/321/417 322/322/418 323/323/419 +f 324/324/420 322/322/418 321/321/417 +f 321/321/417 325/325/421 324/324/420 +f 321/321/417 326/326/422 325/325/421 +f 321/321/417 327/327/423 326/326/422 +f 321/321/417 328/328/424 327/327/423 +f 329/329/425 328/328/424 321/321/417 +f 321/321/417 330/330/426 329/329/425 +f 321/321/417 331/331/427 330/330/426 +f 332/332/428 323/323/429 333/333/430 +f 333/333/430 323/323/429 322/322/431 +f 333/333/430 322/322/431 334/334/432 +f 334/334/432 322/322/431 324/324/433 +f 334/334/434 324/324/435 325/325/436 +f 334/334/434 325/325/436 335/335/437 +f 335/335/438 325/325/439 326/326/440 +f 335/335/438 326/326/440 336/336/441 +f 336/336/441 326/326/440 327/327/442 +f 336/336/441 327/327/442 337/337/443 +f 337/337/443 327/327/442 328/328/444 +f 337/337/443 328/328/444 338/338/445 +f 338/338/445 328/328/444 329/329/446 +f 338/338/445 329/329/446 339/339/447 +f 339/339/447 329/329/446 330/330/448 +f 339/339/447 330/330/448 340/340/449 +f 340/340/449 330/330/448 331/331/450 +f 340/340/449 331/331/450 321/321/451 +f 340/340/449 321/321/451 332/332/428 +f 332/332/428 321/321/451 323/323/429 +f 332/332/17 341/341/17 340/340/17 +f 337/337/17 342/342/17 343/343/17 +f 337/337/17 343/343/17 336/336/17 +f 338/338/17 344/344/17 337/337/17 +f 337/337/17 344/344/17 342/342/17 +f 335/335/17 345/345/17 346/346/17 +f 335/335/17 346/346/17 334/334/17 +f 340/340/17 341/341/17 347/347/17 +f 332/332/17 348/348/17 341/341/17 +f 333/333/17 348/348/17 332/332/17 +f 339/339/17 344/344/17 338/338/17 +f 339/339/17 349/349/17 344/344/17 +f 333/333/17 350/350/17 348/348/17 +f 347/347/17 351/351/17 340/340/17 +f 340/340/17 351/351/17 339/339/17 +f 339/339/17 351/351/17 349/349/17 +f 334/334/17 352/352/17 350/350/17 +f 334/334/17 350/350/17 333/333/17 +f 334/334/17 346/346/17 352/352/17 +f 336/336/17 353/353/17 345/345/17 +f 336/336/17 345/345/17 335/335/17 +f 336/336/17 343/343/17 353/353/17 +f 354/354/452 341/341/453 348/348/454 +f 355/355/455 341/341/453 354/354/452 +f 355/355/455 347/347/456 341/341/453 +f 355/355/455 356/356/457 347/347/456 +f 356/356/457 357/357/458 347/347/456 +f 357/357/458 351/351/459 347/347/456 +f 357/357/458 358/358/460 351/351/459 +f 351/351/459 358/358/460 349/349/461 +f 359/359/462 349/349/461 358/358/460 +f 360/360/463 349/349/461 359/359/462 +f 349/349/461 360/360/463 344/344/464 +f 360/360/463 361/361/465 344/344/464 +f 362/362/466 344/344/464 361/361/465 +f 362/362/466 342/342/467 344/344/464 +f 363/363/468 342/342/467 362/362/466 +f 363/363/468 343/343/469 342/342/467 +f 363/363/468 364/364/470 343/343/469 +f 343/343/469 364/364/470 353/353/471 +f 364/364/470 365/365/472 353/353/471 +f 365/365/472 345/345/473 353/353/471 +f 366/366/474 345/345/475 365/365/472 +f 366/366/474 346/346/476 345/345/475 +f 366/366/474 367/367/477 346/346/476 +f 367/367/477 368/368/478 346/346/476 +f 346/346/476 368/368/478 352/352/479 +f 369/369/480 352/352/479 368/368/478 +f 369/369/480 350/350/481 352/352/479 +f 369/369/480 370/370/482 350/350/481 +f 370/370/482 371/371/483 350/350/481 +f 350/350/481 371/371/483 348/348/484 +f 371/371/483 354/354/452 348/348/485 +f 372/372/486 373/373/487 374/374/488 +f 363/363/468 373/373/487 372/372/486 +f 364/364/470 363/363/468 372/372/486 +f 308/308/489 374/374/488 309/309/490 +f 372/372/486 374/374/488 375/375/491 +f 375/375/491 364/364/470 372/372/486 +f 365/365/472 364/364/470 375/375/491 +f 374/374/488 308/308/489 375/375/491 +f 365/365/472 375/375/491 376/376/492 +f 375/375/491 308/308/489 376/376/492 +f 366/366/474 365/365/472 376/376/492 +f 376/376/492 308/308/489 377/377/493 +f 377/377/493 366/366/474 376/376/492 +f 314/314/494 377/377/493 308/308/489 +f 367/367/477 366/366/474 377/377/493 +f 377/377/493 378/378/495 367/367/477 +f 378/378/495 377/377/493 313/313/496 +f 313/313/496 377/377/493 314/314/494 +f 379/379/497 367/367/477 380/380/498 +f 380/380/498 367/367/477 378/378/495 +f 379/379/497 368/368/478 367/367/477 +f 380/380/498 378/378/495 313/313/496 +f 369/369/480 368/368/478 379/379/497 +f 379/379/497 380/380/498 381/381/499 +f 313/313/496 316/316/500 380/380/498 +f 380/380/498 316/316/500 381/381/499 +f 370/370/482 369/369/480 379/379/497 +f 379/379/497 381/381/499 382/382/501 +f 379/379/497 382/382/501 370/370/482 +f 383/383/502 381/381/499 316/316/500 +f 382/382/501 381/381/499 383/383/502 +f 384/384/503 370/370/482 382/382/501 +f 371/371/483 370/370/482 384/384/503 +f 384/384/503 382/382/501 383/383/502 +f 385/385/504 384/384/503 383/383/502 +f 385/385/504 383/383/502 316/316/500 +f 385/385/504 316/316/500 317/317/505 +f 384/384/503 385/385/504 386/386/506 +f 384/384/503 386/386/506 371/371/483 +f 371/371/483 386/386/506 354/354/452 +f 387/387/507 386/386/506 385/385/504 +f 387/387/507 385/385/504 317/317/505 +f 317/317/505 305/305/508 387/387/507 +f 386/386/506 387/387/507 388/388/509 +f 386/386/506 388/388/509 354/354/452 +f 387/387/507 305/305/508 389/389/510 +f 387/387/507 389/389/510 388/388/509 +f 355/355/455 354/354/452 388/388/509 +f 388/388/509 389/389/510 355/355/455 +f 356/356/457 355/355/455 389/389/510 +f 305/305/508 390/390/511 389/389/510 +f 389/389/510 390/390/511 356/356/457 +f 304/304/512 390/390/511 305/305/508 +f 391/391/513 356/356/457 390/390/511 +f 391/391/513 390/390/511 304/304/512 +f 391/391/513 357/357/458 356/356/457 +f 392/392/514 391/391/513 304/304/512 +f 358/358/460 357/357/458 391/391/513 +f 391/391/513 392/392/514 358/358/460 +f 319/319/515 392/392/514 304/304/512 +f 359/359/462 358/358/460 392/392/514 +f 359/359/462 392/392/514 393/393/516 +f 393/393/516 392/392/514 319/319/515 +f 394/394/517 359/359/462 393/393/516 +f 360/360/463 359/359/462 394/394/517 +f 318/318/518 393/393/516 319/319/515 +f 395/395/519 394/394/517 393/393/516 +f 395/395/519 393/393/516 318/318/518 +f 394/394/517 395/395/519 360/360/463 +f 310/310/520 395/395/519 318/318/518 +f 360/360/463 395/395/519 361/361/465 +f 361/361/465 395/395/519 396/396/521 +f 396/396/521 395/395/519 310/310/520 +f 361/361/465 396/396/521 362/362/466 +f 397/397/522 396/396/521 310/310/520 +f 397/397/522 362/362/466 396/396/521 +f 310/310/520 309/309/490 397/397/522 +f 362/362/466 397/397/522 363/363/468 +f 373/373/487 363/363/468 397/397/522 +f 309/309/490 373/373/487 397/397/522 +f 374/374/488 373/373/487 309/309/490 +f 306/306/523 315/315/523 398/398/523 +f 398/398/523 315/315/523 399/399/523 +f 320/320/524 306/306/524 400/400/524 +f 400/400/524 306/306/524 398/398/524 +f 311/311/525 320/320/525 401/401/525 +f 401/401/525 320/320/525 400/400/525 +f 307/307/526 311/311/526 402/402/526 +f 402/402/526 311/311/526 401/401/526 +f 312/312/527 307/307/527 403/403/527 +f 403/403/527 307/307/527 402/402/527 +f 315/315/528 312/312/528 399/399/528 +f 399/399/528 312/312/528 403/403/528 +f 403/403/18 402/402/18 399/399/18 +f 399/399/18 402/402/18 401/401/18 +f 399/399/18 401/401/18 398/398/18 +f 398/398/18 401/401/18 400/400/18 +f 404/404/529 405/405/530 406/406/531 +f 406/406/531 407/407/532 404/404/529 +f 408/408/533 406/406/531 409/409/534 +f 406/406/531 408/408/533 407/407/532 +f 407/407/532 408/408/533 410/410/535 +f 410/410/535 411/411/536 407/407/532 +f 410/410/535 412/412/537 411/411/536 +f 409/409/534 413/413/538 408/408/533 +f 414/414/539 415/415/540 416/416/541 +f 414/414/539 417/417/542 415/415/540 +f 416/416/541 415/415/540 418/418/543 +f 414/414/539 419/419/544 417/417/542 +f 413/413/538 409/409/534 420/420/545 +f 418/418/543 421/421/546 416/416/541 +f 411/411/536 412/412/537 422/422/547 +f 414/414/539 423/423/548 419/419/544 +f 416/416/541 421/421/546 420/420/545 +f 420/420/545 421/421/546 424/424/549 +f 423/423/548 414/414/539 422/422/547 +f 413/413/538 420/420/545 425/425/550 +f 425/425/550 420/420/545 424/424/549 +f 422/422/547 412/412/537 426/426/551 +f 422/422/547 426/426/551 423/423/548 +f 427/427/552 414/414/553 428/428/554 +f 428/428/554 414/414/553 416/416/555 +f 429/429/556 428/428/557 416/416/558 +f 420/420/559 430/430/560 416/416/558 +f 416/416/558 430/430/560 429/429/556 +f 408/408/561 413/413/562 431/431/563 +f 431/431/563 432/432/564 408/408/561 +f 433/433/565 434/434/566 412/412/567 +f 413/413/562 425/425/568 435/435/569 +f 436/436/570 437/437/571 423/423/572 +f 435/435/569 431/431/563 413/413/562 +f 410/410/573 408/408/561 432/432/564 +f 438/438/574 439/439/575 415/415/576 +f 434/434/566 436/436/570 412/412/567 +f 417/417/577 419/419/578 440/440/579 +f 412/412/567 410/410/573 433/433/565 +f 439/439/575 441/441/580 415/415/576 +f 442/442/581 422/422/582 443/443/583 +f 442/442/581 411/411/584 422/422/582 +f 407/407/532 411/411/584 444/444/585 +f 444/444/585 411/411/584 442/442/581 +f 404/404/529 407/407/532 444/444/585 +f 445/445/586 404/404/529 444/444/585 +f 405/405/530 404/404/529 445/445/586 +f 406/406/531 405/405/530 445/445/586 +f 446/446/587 406/406/531 445/445/586 +f 409/409/588 406/406/531 446/446/587 +f 447/447/589 409/409/588 446/446/587 +f 409/409/588 447/447/589 420/420/559 +f 420/420/559 447/447/589 430/430/560 +f 448/448/590 449/449/591 450/450/592 +f 451/451/593 449/449/591 448/448/590 +f 449/449/591 451/451/593 452/452/594 +f 453/453/595 454/454/596 455/455/597 +f 452/452/594 456/456/598 449/449/591 +f 456/456/598 457/457/599 449/449/591 +f 453/453/595 458/458/600 454/454/596 +f 459/459/601 457/457/599 456/456/598 +f 452/452/594 460/460/602 456/456/598 +f 455/455/597 454/454/596 461/461/603 +f 453/453/595 462/462/604 458/458/600 +f 459/459/601 463/463/605 457/457/599 +f 455/455/597 461/461/603 464/464/606 +f 460/460/602 452/452/594 464/464/606 +f 457/457/599 462/462/604 453/453/595 +f 460/460/602 464/464/606 461/461/603 +f 457/457/599 463/463/605 462/462/604 +f 465/465/607 457/457/608 466/466/609 +f 466/466/609 457/457/608 453/453/610 +f 466/466/609 453/453/610 467/467/557 +f 467/467/611 453/453/612 468/468/613 +f 468/468/613 453/453/612 455/455/614 +f 468/468/18 469/469/18 466/466/18 +f 470/470/18 427/427/18 428/428/18 +f 467/467/18 468/468/18 466/466/18 +f 429/429/18 470/470/18 428/428/18 +f 465/465/607 471/471/615 457/457/608 +f 471/471/615 449/449/616 457/457/608 +f 472/472/617 449/449/616 471/471/615 +f 450/450/592 449/449/616 472/472/617 +f 473/473/618 450/450/592 472/472/617 +f 448/448/590 450/450/592 474/474/619 +f 474/474/619 450/450/592 473/473/618 +f 451/451/620 448/448/590 474/474/619 +f 475/475/621 451/451/620 474/474/619 +f 452/452/622 451/451/620 475/475/621 +f 452/452/622 475/475/621 464/464/623 +f 464/464/623 475/475/621 476/476/624 +f 442/442/625 443/443/625 446/446/625 +f 445/445/625 444/444/625 442/442/625 +f 445/445/625 442/442/625 446/446/625 +f 443/443/625 447/447/625 446/446/625 +f 443/443/625 430/430/625 447/447/625 +f 443/443/625 470/470/625 430/430/625 +f 476/476/626 465/465/626 466/466/626 +f 470/470/625 429/429/625 430/430/625 +f 475/475/626 474/474/626 473/473/626 +f 475/475/626 473/473/626 476/476/626 +f 473/473/626 472/472/626 476/476/626 +f 472/472/626 471/471/626 476/476/626 +f 471/471/626 465/465/626 476/476/626 +f 469/469/626 476/476/626 466/466/626 +f 477/477/627 478/478/628 479/479/629 +f 480/480/630 481/481/631 482/482/632 +f 483/483/633 484/484/634 485/485/635 +f 486/486/636 487/487/637 483/483/633 +f 483/483/633 487/487/637 488/488/638 +f 489/489/639 490/490/640 491/491/641 +f 485/485/635 484/484/634 492/492/642 +f 489/489/639 491/491/641 487/487/637 +f 489/489/639 487/487/637 486/486/636 +f 493/493/643 494/494/644 495/495/645 +f 495/495/645 494/494/644 496/496/646 +f 497/497/647 498/498/648 495/495/645 +f 495/495/645 498/498/648 493/493/643 +f 485/485/635 492/492/642 498/498/648 +f 485/485/635 498/498/648 497/497/647 +f 483/483/633 488/488/638 484/484/634 +f 496/496/646 490/490/640 489/489/639 +f 496/496/646 494/494/644 490/490/640 +f 499/499/649 500/500/650 501/501/651 +f 499/499/649 501/501/651 502/502/652 +f 502/502/652 501/501/651 503/503/653 +f 502/502/652 503/503/653 504/504/654 +f 504/504/654 503/503/653 505/505/655 +f 504/504/654 505/505/655 506/506/656 +f 506/506/656 505/505/655 507/507/657 +f 506/506/656 507/507/657 508/508/658 +f 506/506/656 508/508/658 509/509/659 +f 509/509/660 508/508/661 492/492/662 +f 509/509/660 492/492/662 510/510/663 +f 510/510/663 492/492/662 511/511/664 +f 510/510/663 511/511/664 512/512/665 +f 512/512/665 511/511/664 513/513/666 +f 512/512/665 513/513/666 514/514/667 +f 514/514/667 513/513/666 515/515/668 +f 514/514/667 515/515/668 516/516/669 +f 516/516/669 515/515/668 517/517/670 +f 517/517/670 515/515/668 487/487/671 +f 517/517/670 487/487/671 518/518/672 +f 517/517/670 518/518/672 519/519/673 +f 519/519/674 518/518/675 499/499/676 +f 499/499/676 518/518/675 500/500/677 +f 520/520/625 499/499/625 521/521/625 +f 522/522/625 514/514/625 523/523/625 +f 523/523/625 514/514/625 516/516/625 +f 524/524/625 519/519/625 520/520/625 +f 520/520/625 519/519/625 499/499/625 +f 525/525/625 510/510/625 526/526/625 +f 526/526/625 510/510/625 522/522/625 +f 523/523/625 516/516/625 517/517/625 +f 523/523/625 517/517/625 524/524/625 +f 524/524/625 517/517/625 519/519/625 +f 525/525/625 509/509/625 510/510/625 +f 510/510/625 512/512/625 522/522/625 +f 522/522/625 512/512/625 514/514/625 +f 527/527/625 506/506/625 525/525/625 +f 525/525/625 506/506/625 509/509/625 +f 528/528/625 502/502/625 504/504/625 +f 528/528/625 504/504/625 527/527/625 +f 527/527/625 504/504/625 506/506/625 +f 521/521/625 499/499/625 502/502/625 +f 521/521/625 502/502/625 528/528/625 +f 529/529/678 521/521/679 530/530/680 +f 530/530/680 521/521/679 528/528/681 +f 530/530/680 528/528/681 531/531/682 +f 531/531/682 528/528/681 527/527/683 +f 531/531/684 527/527/685 525/525/686 +f 531/531/684 525/525/686 532/532/687 +f 532/532/688 525/525/689 533/533/690 +f 533/533/690 525/525/689 526/526/691 +f 533/533/690 526/526/691 534/534/692 +f 534/534/692 526/526/691 522/522/693 +f 534/534/692 522/522/693 535/535/694 +f 535/535/694 522/522/693 523/523/695 +f 535/535/694 523/523/695 536/536/696 +f 536/536/697 523/523/698 524/524/699 +f 536/536/697 524/524/699 537/537/700 +f 537/537/701 524/524/702 520/520/703 +f 537/537/701 520/520/703 538/538/704 +f 538/538/704 520/520/703 529/529/678 +f 529/529/678 520/520/703 521/521/679 +f 529/529/705 539/539/706 538/538/707 +f 538/538/707 539/539/706 540/540/708 +f 538/538/707 540/540/708 541/541/709 +f 541/541/709 540/540/708 542/542/710 +f 543/543/711 544/544/712 529/529/705 +f 529/529/705 544/544/712 539/539/706 +f 545/545/713 546/546/714 547/547/715 +f 545/545/713 547/547/715 548/548/716 +f 548/548/716 549/549/717 550/550/718 +f 550/550/718 549/549/717 551/551/719 +f 548/548/716 547/547/715 549/549/717 +f 541/541/709 542/542/710 545/545/713 +f 545/545/713 542/542/710 546/546/714 +f 550/550/718 551/551/719 543/543/711 +f 543/543/711 551/551/719 552/552/720 +f 543/543/711 552/552/720 544/544/712 +f 553/553/721 539/539/722 478/478/628 +f 478/478/628 539/539/722 544/544/723 +f 478/478/628 544/544/724 479/479/629 +f 554/554/725 549/549/726 555/555/727 +f 555/555/727 549/549/726 556/556/728 +f 556/556/728 547/547/729 557/557/730 +f 557/557/730 547/547/729 546/546/731 +f 557/557/730 546/546/731 558/558/732 +f 558/558/732 546/546/733 559/559/734 +f 560/560/735 542/542/736 561/561/737 +f 553/553/721 561/561/738 539/539/739 +f 479/479/629 544/544/724 552/552/740 +f 479/479/629 552/552/741 562/562/742 +f 562/562/742 552/552/741 551/551/743 +f 556/556/728 549/549/726 547/547/729 +f 560/560/735 559/559/744 542/542/745 +f 562/562/746 551/551/746 554/554/746 +f 546/546/733 542/542/747 559/559/734 +f 561/561/737 542/542/736 540/540/748 +f 561/561/738 540/540/749 539/539/739 +f 554/554/725 551/551/750 549/549/726 +f 561/561/737 563/563/751 564/564/752 560/560/735 +f 565/565/753 559/559/734 564/564/754 +f 564/564/752 559/559/744 560/560/735 +f 565/565/753 558/558/732 559/559/734 +f 565/565/753 557/557/730 558/558/732 +f 566/566/755 555/555/727 556/556/728 +f 566/566/755 557/557/730 565/565/753 +f 566/566/755 556/556/728 557/557/730 +f 567/567/756 555/555/727 566/566/755 +f 568/568/757 479/479/629 562/562/742 +f 568/568/758 562/562/759 554/554/725 +f 569/569/760 553/553/721 478/478/628 +f 567/567/756 554/554/725 555/555/727 +f 477/477/627 479/479/629 568/568/757 +f 570/570/761 482/482/632 481/481/631 +f 563/563/762 561/561/738 569/569/760 +f 569/569/760 561/561/738 553/553/721 +f 568/568/758 554/554/725 567/567/756 +f 533/533/690 548/548/716 550/550/718 +f 533/533/690 550/550/718 532/532/688 +f 532/532/763 550/550/718 531/531/764 +f 531/531/764 550/550/718 543/543/711 +f 531/531/682 543/543/765 530/530/680 +f 530/530/766 543/543/711 529/529/705 +f 537/537/767 538/538/707 541/541/709 +f 537/537/700 541/541/768 536/536/697 +f 536/536/769 541/541/709 545/545/713 +f 536/536/770 545/545/713 535/535/771 +f 535/535/771 545/545/713 534/534/772 +f 534/534/772 545/545/713 548/548/716 +f 534/534/692 548/548/773 533/533/690 +f 500/500/650 494/494/774 501/501/651 +f 501/501/775 494/494/644 503/503/776 +f 503/503/776 494/494/644 493/493/643 +f 503/503/653 493/493/777 505/505/655 +f 505/505/778 493/493/643 507/507/779 +f 507/507/779 493/493/643 498/498/648 +f 507/507/657 498/498/780 508/508/658 +f 508/508/781 498/498/781 492/492/781 +f 492/492/782 484/484/782 511/511/782 +f 511/511/664 484/484/783 513/513/666 +f 513/513/784 484/484/634 488/488/638 +f 513/513/666 488/488/785 515/515/668 +f 515/515/786 488/488/638 487/487/637 +f 487/487/671 491/491/787 518/518/672 +f 518/518/788 491/491/788 490/490/788 +f 518/518/675 490/490/789 500/500/677 +f 500/500/790 490/490/640 494/494/644 +f 496/496/791 571/571/792 495/495/793 +f 489/489/794 572/572/795 496/496/796 +f 573/573/626 574/574/626 575/575/626 +f 575/575/626 574/574/626 576/576/626 +f 575/575/626 576/576/626 577/577/626 +f 577/577/626 576/576/626 578/578/626 +f 577/577/797 497/497/798 575/575/799 +f 575/575/799 497/497/798 495/495/800 +f 495/495/793 571/571/792 575/575/801 +f 575/575/801 571/571/792 573/573/802 +f 573/573/802 571/571/792 496/496/791 +f 496/496/796 572/572/795 573/573/803 +f 573/573/803 572/572/795 574/574/804 +f 574/574/804 572/572/795 489/489/794 +f 486/486/805 576/576/806 574/574/807 +f 486/486/805 483/483/808 576/576/806 +f 574/574/807 489/489/809 486/486/805 +f 576/576/810 483/483/811 578/578/812 +f 578/578/812 483/483/811 485/485/813 +f 578/578/814 485/485/815 577/577/816 +f 485/485/815 497/497/817 577/577/816 +f 579/579/18 580/580/18 581/581/18 +f 581/581/18 582/582/18 579/579/18 +f 583/583/626 579/579/626 582/582/626 +f 582/582/626 584/584/626 583/583/626 +f 470/470/818 414/414/819 427/427/820 +f 470/470/818 422/422/582 414/414/819 +f 470/470/818 443/443/583 422/422/582 +f 469/469/821 468/468/820 455/455/822 +f 464/464/623 469/469/821 455/455/822 +f 464/464/623 476/476/624 469/469/821 +f 461/461/823 454/454/824 585/585/825 +f 586/586/826 587/587/827 462/462/828 +f 454/454/824 458/458/829 588/588/830 +f 459/459/831 456/456/832 589/589/833 +f 587/587/827 588/588/830 458/458/829 +f 424/424/834 421/421/835 590/590/836 +f 590/590/836 591/591/837 424/424/834 +f 418/418/838 415/415/576 441/441/580 +f 441/441/580 590/590/836 418/418/838 +f 419/419/578 423/423/572 437/437/571 +f 426/426/839 412/412/567 436/436/570 +f 425/425/568 424/424/834 591/591/837 +f 423/423/572 426/426/839 436/436/570 +f 421/421/835 418/418/838 590/590/836 +f 591/591/837 435/435/569 425/425/568 +f 415/415/576 417/417/577 438/438/574 +f 432/432/564 433/433/565 410/410/573 +f 437/437/571 440/440/579 419/419/578 +f 440/440/579 438/438/574 417/417/577 +f 588/588/830 585/585/825 454/454/824 +f 592/592/840 586/586/826 463/463/841 +f 585/585/842 593/593/843 461/461/844 +f 458/458/829 462/462/828 587/587/827 +f 463/463/841 459/459/831 592/592/840 +f 593/593/843 594/594/845 460/460/846 +f 462/462/828 463/463/841 586/586/826 +f 460/460/846 461/461/844 593/593/843 +f 589/589/833 592/592/840 459/459/831 +f 456/456/847 460/460/848 594/594/849 +f 594/594/849 589/589/850 456/456/847 +f 594/594/17 592/592/17 589/589/17 +f 594/594/17 593/593/17 592/592/17 +f 587/587/17 586/586/17 585/585/17 +f 593/593/17 585/585/17 586/586/17 +f 585/585/17 588/588/17 587/587/17 +f 593/593/17 586/586/17 592/592/17 +f 438/438/626 590/590/626 439/439/626 +f 591/591/626 438/438/626 440/440/626 +f 433/433/851 432/432/852 434/434/853 +f 435/435/626 440/440/626 437/437/854 +f 590/590/626 441/441/626 439/439/626 +f 435/435/626 591/591/626 440/440/626 +f 431/431/626 437/437/854 436/436/855 +f 591/591/626 590/590/626 438/438/626 +f 432/432/852 431/431/626 436/436/855 +f 432/432/852 436/436/855 434/434/853 +f 437/437/854 431/431/626 435/435/626 +f 584/584/820 582/582/820 581/581/820 +f 584/584/820 581/581/820 595/595/820 +f 580/580/625 596/596/625 595/595/625 +f 595/595/625 581/581/625 580/580/625 +f 596/596/17 583/583/17 584/584/17 +f 584/584/17 595/595/17 596/596/17 +f 583/583/557 596/596/557 579/579/557 +f 596/596/557 580/580/557 579/579/557 +f 567/567/856 480/480/857 568/568/858 +f 567/567/856 597/597/859 481/481/860 +f 482/482/632 569/569/861 477/477/862 +f 477/477/862 480/480/857 482/482/632 +f 566/566/863 598/598/864 597/597/859 +f 570/570/865 563/563/866 599/599/867 +f 600/600/868 563/563/869 569/569/861 +f 564/564/870 598/598/871 565/565/872 +f 569/569/760 478/478/628 477/477/627 +f 481/481/631 597/597/873 570/570/761 +f 597/597/873 598/598/874 570/570/761 +f 570/570/761 599/599/875 482/482/632 +f 599/599/875 600/600/868 482/482/632 +f 567/567/856 481/481/860 480/480/857 +f 567/567/856 566/566/863 597/597/859 +f 482/482/632 600/600/868 569/569/861 +f 477/477/862 568/568/858 480/480/857 +f 566/566/863 565/565/876 598/598/864 +f 570/570/865 564/564/877 563/563/866 +f 600/600/868 599/599/878 563/563/869 +f 564/564/870 570/570/879 598/598/871 diff --git a/examples/Cassie/urdf/meshes/agility/hip-pitch.obj b/examples/Cassie/urdf/meshes/agility/hip-pitch.obj new file mode 100644 index 0000000000..b3fd9672bf --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/hip-pitch.obj @@ -0,0 +1,18176 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o hip-pitch +v 0.082607 -0.059250 0.062126 +v 0.081991 -0.064250 0.062463 +v 0.046863 -0.059250 0.062499 +v 0.046805 -0.064250 0.062414 +v 0.064382 -0.064250 0.018673 +v 0.056584 -0.064250 0.018172 +v 0.063337 -0.064250 0.026502 +v 0.062765 -0.064250 0.032530 +v 0.045193 -0.064250 0.038703 +v 0.046774 -0.064250 0.045680 +v 0.041802 -0.059250 -0.051531 +v 0.046947 -0.059250 -0.045597 +v 0.040599 -0.064250 -0.054106 +v 0.046914 -0.064250 -0.045560 +v 0.081788 -0.064250 -0.062496 +v 0.081998 -0.059250 -0.062451 +v 0.046857 -0.064250 -0.062490 +v 0.046882 -0.059250 -0.062516 +v -0.056495 -0.059250 -0.034365 +v -0.045679 -0.059250 -0.038139 +v -0.041276 -0.059250 -0.051917 +v 0.044782 -0.059250 -0.039770 +v 0.075262 -0.059250 -0.039797 +v 0.096815 -0.059250 -0.054827 +v 0.073058 -0.059250 -0.045870 +v 0.025752 -0.059250 -0.053852 +v 0.172680 -0.059250 -0.040533 +v 0.150609 -0.059250 -0.058941 +v 0.159381 -0.059250 -0.045418 +v 0.035000 -0.059250 0.066000 +v 0.084049 -0.059250 -0.056096 +v 0.129198 -0.059250 -0.058966 +v 0.129243 -0.059250 -0.065556 +v -0.026873 -0.059250 -0.052757 +v -0.004663 -0.059250 -0.059349 +v -0.013329 -0.059250 -0.065383 +v 0.010933 -0.059250 0.058559 +v -0.013447 -0.059250 0.065213 +v 0.041714 -0.059250 -0.056764 +v 0.134600 -0.059250 0.064941 +v 0.101953 -0.058450 0.056350 +v 0.056798 -0.064250 -0.017929 +v 0.063418 -0.064250 -0.018174 +v 0.075153 -0.064250 -0.039545 +v 0.044814 -0.064250 -0.039800 +v 0.073053 -0.064250 -0.045610 +v 0.084231 -0.064250 -0.056350 +v 0.084137 -0.064250 0.056674 +v 0.080864 -0.064250 0.045526 +v 0.069991 -0.064250 0.032510 +v 0.079840 -0.064250 0.051890 +v 0.040637 -0.064250 0.054030 +v 0.073103 -0.049250 -0.045658 +v 0.073040 -0.047250 -0.045878 +v 0.086013 -0.049250 -0.056835 +v 0.096392 -0.047250 -0.062364 +v 0.111651 -0.049250 -0.066159 +v 0.133476 -0.047250 -0.065631 +v 0.141888 -0.049250 -0.062714 +v 0.161411 -0.048393 -0.051682 +v 0.175132 -0.047250 -0.037512 +v 0.177774 -0.049250 -0.032776 +v 0.185104 -0.047250 -0.012118 +v 0.185394 -0.049250 -0.010437 +v 0.185424 -0.047250 0.011482 +v 0.185480 -0.049250 0.009887 +v 0.177937 -0.049250 0.032488 +v 0.173683 -0.047250 0.039558 +v 0.160141 -0.049250 0.052923 +v 0.150240 -0.047250 0.059141 +v 0.135665 -0.049250 0.064550 +v 0.117354 -0.047250 0.066948 +v 0.108581 -0.049250 0.065435 +v 0.090288 -0.048250 0.059031 +v 0.079801 -0.047250 0.051764 +v 0.079825 -0.049250 0.051707 +v 0.073052 -0.045250 -0.045624 +v 0.073040 -0.043250 -0.045878 +v 0.091980 -0.045250 -0.060511 +v 0.096392 -0.043250 -0.062364 +v 0.118318 -0.045250 -0.066201 +v 0.126710 -0.043250 -0.066084 +v 0.141888 -0.045250 -0.062714 +v 0.155563 -0.043250 -0.056409 +v 0.167783 -0.045250 -0.046513 +v 0.176793 -0.043250 -0.034448 +v 0.185576 -0.045250 -0.013740 +v 0.185825 -0.043250 -0.008899 +v 0.184526 -0.043250 0.014891 +v 0.181455 -0.045250 0.026690 +v 0.175393 -0.043250 0.036656 +v 0.159745 -0.044393 0.053115 +v 0.137541 -0.043250 0.064066 +v 0.135664 -0.045250 0.064550 +v 0.103754 -0.043250 0.065001 +v 0.105123 -0.045250 0.065002 +v 0.079864 -0.045250 0.052091 +v 0.079801 -0.043250 0.051764 +v 0.073052 -0.041250 -0.045624 +v 0.073040 -0.039250 -0.045878 +v 0.086013 -0.041250 -0.056835 +v 0.096392 -0.039250 -0.062364 +v 0.111651 -0.041250 -0.066159 +v 0.133476 -0.039250 -0.065631 +v 0.141887 -0.041250 -0.062714 +v 0.161681 -0.040191 -0.051471 +v 0.176793 -0.039250 -0.034448 +v 0.181395 -0.041250 -0.026827 +v 0.185825 -0.039250 -0.008899 +v 0.186077 -0.041250 -0.000528 +v 0.184338 -0.040250 0.015723 +v 0.175394 -0.039250 0.036656 +v 0.174300 -0.041250 0.038257 +v 0.158057 -0.040250 0.054205 +v 0.137541 -0.039250 0.064066 +v 0.139782 -0.041250 0.061274 +v 0.129277 -0.041250 0.065425 +v 0.103754 -0.039250 0.065001 +v 0.105123 -0.041250 0.065002 +v 0.079864 -0.041250 0.052091 +v 0.079801 -0.039250 0.051764 +v 0.073052 -0.037250 -0.045624 +v 0.073299 -0.034750 -0.045942 +v 0.085339 -0.036000 -0.056301 +v 0.108244 -0.037250 -0.065961 +v 0.109609 -0.034750 -0.065869 +v 0.140048 -0.034750 -0.063326 +v 0.141888 -0.037250 -0.062714 +v 0.161008 -0.034750 -0.051997 +v 0.167782 -0.037250 -0.046513 +v 0.176793 -0.034750 -0.034448 +v 0.185576 -0.037250 -0.013740 +v 0.185825 -0.034750 -0.008900 +v 0.184526 -0.034750 0.014891 +v 0.184121 -0.037250 0.016549 +v 0.175394 -0.034750 0.036655 +v 0.176082 -0.037250 0.035217 +v 0.160141 -0.037250 0.052923 +v 0.153417 -0.034750 0.057706 +v 0.139782 -0.037250 0.061274 +v 0.127367 -0.034750 0.065811 +v 0.129277 -0.037250 0.065425 +v 0.105123 -0.037250 0.065002 +v 0.100499 -0.034750 0.063768 +v 0.079864 -0.037250 0.052091 +v 0.079801 -0.034750 0.051764 +v 0.073052 -0.053250 -0.045624 +v 0.073040 -0.051250 -0.045878 +v 0.086013 -0.053250 -0.056835 +v 0.096392 -0.051250 -0.062364 +v 0.111651 -0.053250 -0.066159 +v 0.126710 -0.051250 -0.066084 +v 0.141887 -0.053250 -0.062714 +v 0.155563 -0.051250 -0.056409 +v 0.162334 -0.053250 -0.050922 +v 0.176793 -0.051250 -0.034448 +v 0.181395 -0.053250 -0.026827 +v 0.185825 -0.051250 -0.008900 +v 0.184333 -0.053250 0.000017 +v 0.184338 -0.052250 0.015723 +v 0.175394 -0.051250 0.036655 +v 0.174300 -0.053250 0.038257 +v 0.158058 -0.052250 0.054205 +v 0.137541 -0.051250 0.064066 +v 0.135664 -0.053250 0.064550 +v 0.103754 -0.051250 0.065001 +v 0.105123 -0.053250 0.065002 +v 0.079864 -0.053250 0.052091 +v 0.079801 -0.051250 0.051764 +v 0.073052 -0.057250 -0.045624 +v 0.073040 -0.055250 -0.045878 +v 0.086013 -0.057250 -0.056835 +v 0.096392 -0.055250 -0.062364 +v 0.111651 -0.057250 -0.066159 +v 0.133476 -0.055250 -0.065631 +v 0.148531 -0.057250 -0.060622 +v 0.168931 -0.055250 -0.045769 +v 0.174109 -0.057250 -0.038527 +v 0.185525 -0.055250 -0.012372 +v 0.184993 -0.057250 -0.013711 +v 0.185061 -0.057250 0.013387 +v 0.184526 -0.055250 0.014891 +v 0.175394 -0.055250 0.036656 +v 0.176082 -0.057250 0.035216 +v 0.159746 -0.056393 0.053115 +v 0.134342 -0.055250 0.065123 +v 0.139989 -0.057250 0.061198 +v 0.129277 -0.057250 0.065425 +v 0.105123 -0.057250 0.065002 +v 0.100499 -0.055250 0.063768 +v 0.079864 -0.057250 0.052091 +v 0.079801 -0.055250 0.051764 +v 0.067738 -0.028904 -0.027824 +v 0.078625 -0.028874 -0.042186 +v 0.074718 -0.034751 -0.037907 +v 0.086538 -0.034750 -0.049101 +v 0.096429 -0.028902 -0.054463 +v 0.110189 -0.034750 -0.058604 +v 0.118273 -0.028931 -0.059137 +v 0.137666 -0.034750 -0.056623 +v 0.137166 -0.028883 -0.056588 +v 0.156959 -0.028895 -0.046426 +v 0.167597 -0.034750 -0.036513 +v 0.174587 -0.028874 -0.023887 +v 0.180160 -0.034750 -0.001831 +v 0.179105 -0.028887 0.007606 +v 0.179471 -0.034750 0.001041 +v 0.171174 -0.034750 0.030197 +v 0.166766 -0.028878 0.036927 +v 0.156364 -0.034750 0.046740 +v 0.143957 -0.028926 0.054309 +v 0.137869 -0.034750 0.056479 +v 0.125298 -0.028871 0.058746 +v 0.107782 -0.034750 0.058412 +v 0.106300 -0.028909 0.057746 +v 0.083273 -0.028889 0.046621 +v 0.080802 -0.034750 0.044707 +v 0.061878 -0.034750 -0.012963 +v 0.061864 -0.028906 -0.012806 +v 0.062625 -0.034750 -0.017285 +v 0.070066 -0.028895 0.032411 +v 0.047011 -0.049250 0.046598 +v 0.046961 -0.047250 0.046484 +v 0.022856 -0.048210 0.062155 +v 0.000829 -0.047250 0.066406 +v -0.001081 -0.049250 0.066403 +v -0.028524 -0.047250 0.060253 +v -0.030347 -0.049250 0.059356 +v -0.049728 -0.047250 0.043723 +v -0.055316 -0.049250 0.037204 +v -0.061950 -0.047250 0.023932 +v -0.065785 -0.049250 0.009100 +v -0.066368 -0.047250 -0.002406 +v -0.064689 -0.049250 -0.014136 +v -0.060055 -0.047250 -0.028354 +v -0.055873 -0.049250 -0.035898 +v -0.041661 -0.047250 -0.052042 +v -0.037215 -0.049250 -0.055005 +v -0.019508 -0.047250 -0.061412 +v -0.019312 -0.049250 -0.063192 +v 0.005592 -0.047250 -0.066738 +v 0.000829 -0.049250 -0.066406 +v 0.029117 -0.048488 -0.059727 +v 0.047017 -0.049250 -0.046371 +v 0.046897 -0.047250 -0.045658 +v 0.046948 -0.045250 0.045623 +v 0.046914 -0.043250 0.045575 +v 0.035170 -0.044481 0.056108 +v 0.023640 -0.043250 0.061852 +v 0.005592 -0.045250 0.066738 +v 0.000829 -0.043250 0.066406 +v -0.028524 -0.043250 0.060253 +v -0.030347 -0.045250 0.059356 +v -0.054157 -0.043250 0.038872 +v -0.055316 -0.045250 0.037204 +v -0.065496 -0.043250 0.010987 +v -0.065785 -0.045250 0.009100 +v -0.064529 -0.043250 -0.015700 +v -0.064689 -0.045250 -0.014136 +v -0.054157 -0.045250 -0.038872 +v -0.053127 -0.043250 -0.039849 +v -0.030347 -0.043250 -0.059356 +v -0.028524 -0.045250 -0.060253 +v -0.001081 -0.043250 -0.066403 +v 0.000829 -0.045250 -0.066406 +v 0.022856 -0.044290 -0.062155 +v 0.047008 -0.043250 -0.046636 +v 0.047017 -0.045250 -0.046371 +v 0.046948 -0.041250 0.045623 +v 0.046961 -0.039250 0.046484 +v 0.028295 -0.041250 0.060361 +v 0.023640 -0.039250 0.061852 +v 0.000829 -0.039250 0.066406 +v -0.001081 -0.041250 0.066403 +v -0.022298 -0.039250 0.062348 +v -0.019834 -0.041250 0.061211 +v -0.036135 -0.040500 0.055422 +v -0.051960 -0.039250 0.041360 +v -0.053127 -0.041250 0.039849 +v -0.062930 -0.039250 0.020600 +v -0.065499 -0.041250 0.012407 +v -0.066352 -0.039250 -0.009086 +v -0.064051 -0.041250 -0.017549 +v -0.053127 -0.039250 -0.039849 +v -0.053891 -0.041250 -0.038474 +v -0.037215 -0.041250 -0.055005 +v -0.030347 -0.039250 -0.059356 +v -0.019766 -0.041250 -0.061231 +v -0.001081 -0.039250 -0.066403 +v 0.000829 -0.041250 -0.066406 +v 0.022062 -0.039250 -0.062432 +v 0.029070 -0.040694 -0.059852 +v 0.047017 -0.041250 -0.046371 +v 0.046948 -0.039250 -0.045623 +v 0.046948 -0.037250 0.045623 +v 0.046859 -0.034750 0.045938 +v 0.034164 -0.037250 0.056722 +v 0.020908 -0.034750 0.063624 +v 0.005592 -0.037250 0.066738 +v -0.006212 -0.034750 0.065784 +v -0.022298 -0.034750 0.062348 +v -0.030347 -0.037250 0.059356 +v -0.037323 -0.034750 0.054526 +v -0.051960 -0.034750 0.041361 +v -0.053128 -0.037250 0.039849 +v -0.062930 -0.034750 0.020600 +v -0.065499 -0.037250 0.012407 +v -0.066352 -0.034750 -0.009086 +v -0.064051 -0.037250 -0.017549 +v -0.053127 -0.034750 -0.039849 +v -0.053891 -0.037250 -0.038474 +v -0.031652 -0.037250 -0.059020 +v -0.030347 -0.034750 -0.059356 +v 0.005591 -0.034750 -0.066738 +v -0.006212 -0.037250 -0.065784 +v 0.020908 -0.037250 -0.063624 +v 0.034164 -0.034750 -0.056721 +v 0.046960 -0.037250 -0.045874 +v 0.046948 -0.034750 -0.045623 +v 0.045188 -0.034751 0.038112 +v 0.044783 -0.045250 0.039777 +v 0.044806 -0.048000 0.039739 +v 0.044968 -0.052375 0.039539 +v 0.044739 -0.043250 0.039804 +v 0.044783 -0.041250 0.039777 +v 0.044739 -0.039250 0.039804 +v 0.044783 -0.037250 0.039777 +v 0.046914 -0.059250 0.045560 +v 0.044803 -0.059250 0.040524 +v 0.044777 -0.057250 0.039749 +v 0.046961 -0.055250 0.046484 +v 0.046948 -0.057250 0.045623 +v 0.044739 -0.055250 0.039804 +v 0.045529 -0.051250 0.041523 +v 0.046897 -0.053250 0.045658 +v 0.047017 -0.053250 -0.046371 +v 0.047011 -0.051250 -0.046598 +v 0.044948 -0.054250 -0.039548 +v 0.044972 -0.050393 -0.039800 +v 0.047017 -0.057250 -0.046371 +v 0.046897 -0.055250 -0.045658 +v 0.044948 -0.057250 -0.039541 +v 0.045209 -0.034750 -0.038107 +v 0.044831 -0.038500 -0.039688 +v 0.044831 -0.042500 -0.039688 +v 0.044601 -0.034750 -0.039444 +v 0.044954 -0.045865 -0.039593 +v -0.059167 -0.034750 -0.000569 +v -0.059188 -0.037250 -0.000353 +v -0.060861 -0.034750 0.002150 +v -0.062892 -0.037250 0.002257 +v -0.063783 -0.034750 0.000906 +v -0.062454 -0.037250 -0.002209 +v -0.062162 -0.034750 -0.002219 +v -0.016709 -0.034750 -0.057349 +v -0.016745 -0.037250 -0.057423 +v -0.019129 -0.037250 -0.056206 +v -0.020924 -0.034750 -0.056625 +v -0.021407 -0.037250 -0.058349 +v -0.019075 -0.034750 -0.060945 +v -0.018726 -0.037250 -0.060880 +v -0.016594 -0.034750 0.058858 +v -0.016831 -0.037250 0.056977 +v -0.019075 -0.037250 0.060945 +v -0.021407 -0.034750 0.059697 +v -0.021287 -0.037250 0.057584 +v -0.018261 -0.034750 0.056203 +v 0.045717 -0.051250 0.048159 +v 0.034164 -0.053250 0.056722 +v 0.023640 -0.051250 0.061852 +v 0.005592 -0.053250 0.066738 +v 0.000829 -0.051250 0.066406 +v -0.028524 -0.051250 0.060253 +v -0.019508 -0.053250 0.061412 +v -0.035804 -0.053250 0.055701 +v -0.049728 -0.051250 0.043723 +v -0.055316 -0.053250 0.037204 +v -0.061950 -0.051250 0.023931 +v -0.065785 -0.053250 0.009100 +v -0.066368 -0.051250 -0.002406 +v -0.064170 -0.052662 -0.016568 +v -0.054157 -0.053250 -0.038872 +v -0.053127 -0.051250 -0.039849 +v -0.035099 -0.052298 -0.056158 +v -0.020441 -0.051250 -0.062836 +v -0.005844 -0.053250 -0.066716 +v -0.001081 -0.051250 -0.066403 +v 0.022856 -0.052290 -0.062155 +v -0.059289 -0.051250 0.001334 +v -0.059740 -0.053250 -0.002044 +v -0.060379 -0.053250 0.002076 +v -0.063509 -0.051250 0.001237 +v -0.064031 -0.053250 0.000371 +v -0.062219 -0.051250 -0.002402 +v -0.017460 -0.051250 -0.056446 +v -0.016995 -0.053250 -0.059813 +v -0.017540 -0.053250 -0.056707 +v -0.020288 -0.053250 -0.056523 +v -0.021224 -0.051250 -0.057828 +v -0.020840 -0.053250 -0.060122 +v -0.018853 -0.051250 -0.061093 +v -0.016664 -0.051250 0.057180 +v -0.017074 -0.053250 0.059926 +v -0.019146 -0.051250 0.060892 +v -0.021306 -0.051250 0.057496 +v -0.021287 -0.053250 0.057584 +v -0.017886 -0.053250 0.056554 +v 0.028295 -0.057250 0.060361 +v 0.023640 -0.055250 0.061852 +v 0.000829 -0.055250 0.066406 +v -0.001081 -0.057250 0.066403 +v -0.028524 -0.055250 0.060253 +v -0.030347 -0.057250 0.059356 +v -0.054157 -0.055250 0.038873 +v -0.055316 -0.057250 0.037204 +v -0.065496 -0.055250 0.010987 +v -0.065785 -0.057250 0.009100 +v -0.064529 -0.055250 -0.015701 +v -0.064689 -0.057250 -0.014136 +v -0.055873 -0.057250 -0.035898 +v -0.053127 -0.055250 -0.039849 +v -0.036817 -0.056380 -0.055174 +v -0.014409 -0.055250 -0.064830 +v -0.005844 -0.057250 -0.066716 +v 0.012292 -0.055250 -0.065264 +v 0.023640 -0.057250 -0.061852 +v 0.034164 -0.055250 -0.056722 +v -0.007812 -0.066007 0.065615 +v -0.029707 -0.066151 0.059183 +v -0.042516 -0.059250 0.051165 +v -0.052679 -0.065996 0.040758 +v -0.062251 -0.059250 0.023846 +v -0.064088 -0.066045 0.016056 +v -0.066251 -0.059250 -0.007786 +v -0.065867 -0.066117 -0.008073 +v -0.059082 -0.066011 -0.029606 +v -0.047941 -0.066016 -0.045530 +v -0.029222 -0.066108 -0.059487 +v -0.007269 -0.066062 -0.065622 +v -0.059118 -0.055250 0.000394 +v -0.059096 -0.057250 -0.000137 +v -0.060372 -0.057250 0.002251 +v -0.063481 -0.055250 0.001763 +v -0.063955 -0.057250 -0.000071 +v -0.061778 -0.055250 -0.002390 +v -0.061437 -0.057250 -0.002276 +v -0.016674 -0.055250 -0.059660 +v -0.017242 -0.057250 -0.060471 +v -0.018402 -0.057250 -0.056237 +v -0.018926 -0.055250 -0.056127 +v -0.021459 -0.057250 -0.058561 +v -0.021433 -0.055250 -0.059295 +v -0.016646 -0.055250 0.058423 +v -0.017940 -0.057250 0.060959 +v -0.020263 -0.055250 0.060824 +v -0.021287 -0.057250 0.057584 +v -0.019655 -0.055250 0.056019 +v -0.017786 -0.057250 0.056478 +v 0.040569 -0.059250 0.054052 +v 0.063097 -0.034750 0.017818 +v 0.056447 -0.034750 0.018322 +v 0.056096 -0.034750 -0.018891 +v 0.133876 -0.066074 0.064978 +v 0.131170 -0.066166 -0.065243 +v 0.051444 -0.028924 -0.029782 +v 0.035887 -0.028898 -0.047015 +v 0.026200 -0.034750 -0.053113 +v 0.012728 -0.028891 -0.058231 +v 0.004677 -0.034750 -0.059242 +v -0.016099 -0.028889 -0.057118 +v -0.034254 -0.028845 -0.048046 +v -0.039937 -0.034750 -0.043732 +v -0.047598 -0.028933 -0.035472 +v -0.053478 -0.034750 -0.025915 +v -0.056043 -0.028863 -0.018385 +v -0.059347 -0.028901 0.000660 +v -0.056569 -0.034750 0.018204 +v -0.054672 -0.028908 0.022581 +v -0.041557 -0.034750 0.042843 +v -0.042436 -0.028873 0.041471 +v -0.023924 -0.028898 0.054092 +v -0.002051 -0.028909 0.059320 +v 0.015604 -0.034750 0.057341 +v 0.016906 -0.028880 0.056517 +v 0.034443 -0.028901 0.048335 +v 0.035784 -0.034750 0.047190 +v 0.051384 -0.028876 0.029636 +v 0.057852 -0.028895 -0.013152 +v 0.057860 -0.034750 -0.013252 +v 0.058311 -0.034750 0.012769 +v 0.057724 -0.028895 0.013306 +v 0.062283 -0.034750 0.013460 +v 0.061790 -0.028900 0.012741 +v -0.035949 -0.057250 0.047133 +v -0.036928 -0.057250 -0.046874 +v 0.030451 -0.057250 -0.050769 +v 0.009174 -0.057250 -0.058789 +v -0.004378 -0.057250 0.059358 +v -0.055804 -0.057250 -0.021085 +v 0.024971 -0.057250 0.054168 +v -0.050571 -0.057250 0.031188 +v -0.057696 -0.059250 -0.013656 +v -0.057016 -0.059250 0.018214 +v -0.037157 -0.059250 0.046616 +v -0.014856 -0.059250 0.057303 +v -0.056059 -0.053250 0.019684 +v 0.025069 -0.053250 0.054147 +v 0.031835 -0.053250 -0.049766 +v 0.011051 -0.053250 -0.058636 +v -0.000739 -0.054309 0.059221 +v -0.046307 -0.053250 -0.037629 +v -0.057300 -0.053250 -0.014948 +v -0.042755 -0.053250 0.041256 +v 0.023303 -0.055250 0.054930 +v 0.025069 -0.055250 -0.054147 +v 0.000060 -0.055250 -0.059217 +v -0.055135 -0.055250 -0.022814 +v -0.038083 -0.055250 -0.045605 +v -0.034466 -0.055250 0.048397 +v -0.053268 -0.055250 0.026886 +v -0.020991 -0.045250 0.056881 +v -0.019075 -0.045250 0.060945 +v -0.017079 -0.045250 -0.060014 +v -0.020935 -0.045250 -0.059926 +v -0.063719 -0.045250 -0.000662 +v -0.061791 -0.045250 0.002490 +v -0.020288 -0.045250 -0.056523 +v -0.056059 -0.045250 0.019684 +v -0.059165 -0.045250 -0.000127 +v -0.016824 -0.045250 0.056965 +v -0.060733 -0.045250 -0.002290 +v 0.026157 -0.045250 -0.053347 +v -0.017540 -0.045250 -0.056707 +v 0.006438 -0.046650 -0.059159 +v 0.005501 -0.046309 0.059193 +v -0.046307 -0.045250 -0.037629 +v 0.025069 -0.045250 0.054147 +v -0.043387 -0.046250 0.040605 +v -0.016746 -0.047250 0.057455 +v -0.018934 -0.047250 0.060945 +v -0.017074 -0.047250 -0.059926 +v 0.028981 -0.047250 0.051641 +v 0.031188 -0.047250 -0.050297 +v -0.018114 -0.047250 -0.056250 +v -0.021335 -0.047250 0.057717 +v -0.063345 -0.047250 0.001956 +v -0.061177 -0.047250 -0.002530 +v -0.056634 -0.047250 0.017963 +v -0.059205 -0.047250 0.000496 +v -0.021167 -0.047250 -0.057444 +v -0.046933 -0.047250 -0.036433 +v -0.019655 -0.047250 0.056217 +v -0.034746 -0.038380 0.048094 +v 0.026157 -0.037250 -0.053347 +v 0.002444 -0.038393 -0.059203 +v 0.005502 -0.038309 0.059193 +v -0.039458 -0.037250 -0.044420 +v -0.054017 -0.038197 -0.024766 +v 0.025069 -0.037250 0.054147 +v -0.052369 -0.037250 0.028597 +v -0.017798 -0.039250 0.060892 +v -0.016827 -0.039250 -0.059833 +v -0.021306 -0.039250 -0.059483 +v -0.021306 -0.039250 0.057496 +v -0.017648 -0.039250 0.056611 +v 0.028980 -0.039250 0.051641 +v -0.018928 -0.039250 -0.056045 +v 0.025069 -0.039250 -0.054147 +v -0.063651 -0.039250 0.001079 +v -0.062693 -0.039250 -0.001940 +v -0.059313 -0.039250 -0.001146 +v -0.060662 -0.039250 0.002117 +v -0.053268 -0.039250 0.026886 +v -0.035687 -0.039250 -0.047820 +v -0.017159 -0.043250 0.056534 +v -0.018934 -0.043250 0.060945 +v -0.021339 -0.043250 0.058147 +v -0.021310 -0.041250 0.057801 +v -0.061429 -0.041250 -0.002455 +v -0.063776 -0.041250 -0.000063 +v -0.021346 -0.041250 -0.057934 +v -0.016603 -0.041250 0.059209 +v -0.061571 -0.041250 0.002455 +v -0.018546 -0.041250 0.056253 +v -0.040610 -0.041250 0.043717 +v -0.056059 -0.041250 0.019684 +v -0.059190 -0.041250 0.000059 +v -0.054931 -0.041250 -0.024082 +v -0.034465 -0.041250 -0.048397 +v -0.018250 -0.041250 -0.056241 +v -0.016605 -0.041250 -0.059036 +v 0.023303 -0.041250 -0.054930 +v -0.000739 -0.042309 0.059221 +v 0.025069 -0.041250 0.054147 +v -0.019075 -0.043250 -0.060945 +v -0.016709 -0.043250 -0.057338 +v 0.023303 -0.043250 0.054930 +v 0.006621 -0.043250 -0.059300 +v 0.030363 -0.043250 -0.050841 +v -0.063955 -0.043250 0.000071 +v -0.054931 -0.043250 0.024082 +v -0.059171 -0.043250 -0.000253 +v -0.061024 -0.043250 0.002311 +v -0.061363 -0.043250 -0.002312 +v -0.055135 -0.043250 -0.022814 +v -0.020974 -0.043250 -0.056713 +v -0.034466 -0.043250 0.048397 +v -0.038083 -0.043250 -0.045605 +v -0.016674 -0.049250 0.059660 +v -0.021306 -0.049250 0.059483 +v -0.019290 -0.049250 0.056135 +v 0.030410 -0.049250 -0.050761 +v 0.026313 -0.051250 -0.053669 +v -0.063783 -0.049250 -0.000906 +v -0.021339 -0.049250 -0.058147 +v -0.019348 -0.049250 -0.060824 +v -0.061778 -0.049250 0.002390 +v -0.056059 -0.049250 0.019684 +v -0.059242 -0.049250 0.000480 +v -0.016500 -0.049250 -0.057778 +v -0.060459 -0.049250 -0.002176 +v 0.030363 -0.049250 0.050841 +v 0.005501 -0.050191 -0.059193 +v 0.006621 -0.049250 0.059300 +v -0.046307 -0.049250 -0.037629 +v -0.019685 -0.049250 -0.056303 +v -0.042755 -0.049250 0.041257 +v -0.034466 -0.051250 0.048396 +v 0.011051 -0.051250 0.058636 +v -0.055135 -0.051250 -0.022814 +v -0.038083 -0.051250 -0.045605 +v -0.051500 -0.051250 0.029629 +v 0.075169 -0.046033 -0.039688 +v 0.075169 -0.042033 -0.039688 +v 0.075177 -0.039250 -0.040549 +v 0.075218 -0.037250 -0.039770 +v 0.075169 -0.056467 -0.039688 +v 0.075218 -0.053250 -0.039770 +v 0.075047 -0.050250 -0.039546 +v 0.179294 -0.037250 -0.001159 +v 0.183830 -0.034750 -0.001170 +v 0.183067 -0.037250 -0.001763 +v 0.182334 -0.037250 0.002517 +v 0.181567 -0.034750 0.002358 +v 0.136707 -0.037250 -0.057388 +v 0.138257 -0.034750 -0.060988 +v 0.139075 -0.037250 -0.060945 +v 0.141346 -0.034750 -0.057934 +v 0.140895 -0.037250 -0.056565 +v 0.137169 -0.034750 0.060122 +v 0.136843 -0.037250 0.059656 +v 0.138245 -0.037250 0.056359 +v 0.141629 -0.034750 0.058874 +v 0.141346 -0.037250 0.057934 +v 0.179313 -0.051250 0.001146 +v 0.179433 -0.053250 0.001027 +v 0.181143 -0.053250 -0.002430 +v 0.181222 -0.051250 -0.002390 +v 0.183894 -0.051250 0.001033 +v 0.181833 -0.053250 0.002253 +v 0.136995 -0.051250 -0.059813 +v 0.137169 -0.053250 -0.060122 +v 0.141469 -0.051250 -0.059469 +v 0.141014 -0.053250 -0.059813 +v 0.138954 -0.053250 -0.055900 +v 0.138420 -0.051250 -0.056358 +v 0.137169 -0.051250 0.060122 +v 0.137618 -0.053250 0.056516 +v 0.138811 -0.051250 0.056140 +v 0.141346 -0.053250 0.057934 +v 0.141166 -0.051250 0.059656 +v 0.138257 -0.053250 0.060988 +v 0.157425 -0.065975 -0.055124 +v 0.176581 -0.066088 -0.034209 +v 0.183820 -0.059250 -0.017406 +v 0.185363 -0.066112 -0.011155 +v 0.185906 -0.059250 0.009250 +v 0.184769 -0.065903 0.013998 +v 0.176510 -0.059250 0.034429 +v 0.174745 -0.066115 0.037408 +v 0.162165 -0.059250 0.051334 +v 0.157314 -0.066050 0.054513 +v 0.179279 -0.055250 0.001383 +v 0.179441 -0.057250 0.000902 +v 0.179909 -0.057250 -0.001683 +v 0.181857 -0.055250 -0.002430 +v 0.183067 -0.057250 -0.001763 +v 0.183709 -0.055250 0.000954 +v 0.182533 -0.057250 0.002394 +v 0.137304 -0.055250 -0.060401 +v 0.136627 -0.057250 -0.059434 +v 0.141399 -0.057250 -0.059523 +v 0.141562 -0.055250 -0.058564 +v 0.138922 -0.057250 -0.056120 +v 0.138089 -0.055250 -0.056315 +v 0.136692 -0.055250 0.057598 +v 0.137290 -0.057250 0.056793 +v 0.140587 -0.055250 0.056209 +v 0.140678 -0.057250 0.056574 +v 0.141495 -0.055250 0.058199 +v 0.138661 -0.055250 0.060824 +v 0.137321 -0.057250 0.060081 +v 0.083829 -0.059250 0.056021 +v 0.079819 -0.059250 0.051830 +v 0.065425 -0.028887 0.023316 +v 0.124873 -0.057250 0.059176 +v 0.116615 -0.057250 -0.059314 +v 0.177197 -0.057250 -0.016860 +v 0.080879 -0.057250 0.044901 +v 0.092957 -0.057250 -0.052927 +v 0.174602 -0.058139 0.022796 +v 0.160672 -0.057250 -0.043673 +v 0.163916 -0.057250 0.039991 +v 0.080778 -0.059250 0.044703 +v 0.124925 -0.059250 0.059293 +v 0.145304 -0.059250 0.053423 +v 0.162715 -0.059250 0.041288 +v 0.178883 -0.059250 0.007202 +v 0.176550 -0.059250 -0.018121 +v 0.120739 -0.054450 -0.059221 +v 0.177847 -0.053250 -0.013558 +v 0.108949 -0.053250 0.058636 +v 0.080880 -0.053250 0.044907 +v 0.094931 -0.053250 -0.054147 +v 0.169438 -0.054393 0.033311 +v 0.153535 -0.054083 -0.048646 +v 0.159457 -0.053250 0.044420 +v 0.166934 -0.053250 -0.036433 +v 0.172031 -0.055250 -0.029835 +v 0.096697 -0.055250 -0.054930 +v 0.113588 -0.055250 0.058869 +v 0.177847 -0.055250 0.013558 +v 0.092226 -0.055250 0.052523 +v 0.080728 -0.055250 0.044544 +v 0.138257 -0.045250 0.060988 +v 0.141290 -0.045250 0.057711 +v 0.141014 -0.045250 -0.059813 +v 0.137169 -0.045250 -0.060122 +v 0.138954 -0.045250 -0.055900 +v 0.116245 -0.046150 -0.059213 +v 0.137651 -0.045250 0.056444 +v 0.112105 -0.045250 0.059456 +v 0.080880 -0.045250 0.044907 +v 0.183359 -0.045250 0.001381 +v 0.092226 -0.045250 -0.052523 +v 0.182444 -0.045250 -0.002378 +v 0.181031 -0.045250 0.002291 +v 0.168024 -0.045250 0.034982 +v 0.158083 -0.045250 -0.045605 +v 0.179464 -0.045250 -0.000812 +v 0.172578 -0.046050 -0.027252 +v 0.140592 -0.047250 -0.060497 +v 0.139889 -0.047250 -0.056168 +v 0.141174 -0.047250 0.057401 +v 0.137940 -0.047250 0.060959 +v 0.183359 -0.047250 -0.001381 +v 0.136404 -0.047250 -0.057982 +v 0.182444 -0.047250 0.002378 +v 0.179831 -0.047250 -0.001855 +v 0.162004 -0.047250 -0.042379 +v 0.093843 -0.047250 -0.053347 +v 0.179275 -0.047250 0.000402 +v 0.171005 -0.047250 0.031558 +v 0.113379 -0.047250 0.059300 +v 0.137935 -0.047250 0.056365 +v 0.080958 -0.047250 0.045270 +v 0.119940 -0.037250 -0.059217 +v 0.108949 -0.037250 0.058636 +v 0.080879 -0.037250 0.044916 +v 0.094931 -0.037250 -0.054147 +v 0.177777 -0.037250 0.014906 +v 0.153536 -0.038083 -0.048645 +v 0.162004 -0.037250 0.042379 +v 0.176041 -0.038450 -0.018721 +v 0.167492 -0.038250 -0.035717 +v 0.141469 -0.039250 -0.059469 +v 0.136995 -0.039250 -0.059813 +v 0.141014 -0.039250 0.059813 +v 0.138954 -0.039250 0.056015 +v 0.137169 -0.039250 0.060122 +v 0.181433 -0.039250 -0.002358 +v 0.183858 -0.039250 -0.000067 +v 0.180406 -0.039250 0.002372 +v 0.138240 -0.039250 -0.056285 +v 0.107057 -0.039250 0.058248 +v 0.172049 -0.039250 0.028240 +v 0.158083 -0.039250 0.045605 +v 0.179177 -0.039250 0.000018 +v 0.108949 -0.039250 -0.058636 +v 0.080777 -0.039250 0.044686 +v 0.137169 -0.043250 0.060122 +v 0.138954 -0.043250 0.056015 +v 0.141014 -0.043250 0.059813 +v 0.141174 -0.041250 -0.057401 +v 0.139075 -0.041250 -0.060945 +v 0.136915 -0.041250 -0.056893 +v 0.117551 -0.042513 -0.059316 +v 0.136995 -0.041250 0.059813 +v 0.141346 -0.041250 0.057934 +v 0.138033 -0.041250 0.056400 +v 0.115178 -0.041250 0.059021 +v 0.093843 -0.041250 0.053347 +v 0.080807 -0.041250 0.044618 +v 0.183830 -0.041250 0.001170 +v 0.180323 -0.041250 -0.002364 +v 0.092226 -0.041250 -0.052523 +v 0.179650 -0.041250 0.001517 +v 0.172578 -0.042450 0.027252 +v 0.162004 -0.041250 0.042379 +v 0.169000 -0.041250 -0.034049 +v 0.141290 -0.043250 -0.057711 +v 0.137798 -0.043250 -0.060892 +v 0.180781 -0.043250 -0.002402 +v 0.183858 -0.043250 -0.000067 +v 0.181359 -0.043250 0.002402 +v 0.172031 -0.043250 -0.029835 +v 0.096697 -0.043250 -0.054930 +v 0.107057 -0.043250 0.058248 +v 0.158082 -0.043250 0.045605 +v 0.179633 -0.043250 0.001643 +v 0.138089 -0.043250 -0.056315 +v 0.080800 -0.043250 0.044991 +v 0.079604 -0.043250 0.043083 +v 0.137079 -0.049250 0.060014 +v 0.137649 -0.049250 0.056592 +v 0.140543 -0.049250 0.056529 +v 0.140595 -0.049250 0.060173 +v 0.112105 -0.049250 0.059456 +v 0.140243 -0.049250 -0.056209 +v 0.139317 -0.049250 -0.061160 +v 0.136935 -0.049250 -0.057337 +v 0.114702 -0.050173 -0.058984 +v 0.080880 -0.049250 0.044907 +v 0.092226 -0.049250 -0.052523 +v 0.179294 -0.049250 -0.001398 +v 0.182079 -0.049250 0.002439 +v 0.174017 -0.050107 0.024766 +v 0.183576 -0.049250 -0.001121 +v 0.161006 -0.050173 0.042735 +v 0.174017 -0.050361 -0.024766 +v 0.161007 -0.050250 -0.042734 +v 0.096697 -0.051250 -0.054930 +v 0.107057 -0.051250 0.058248 +v 0.080777 -0.051250 0.044686 +v 0.064445 -0.028816 0.032641 +v 0.061854 -0.028793 0.029098 +v 0.068099 -0.028750 0.028947 +v 0.067681 -0.026048 0.030538 +v 0.064837 -0.026060 0.031721 +v 0.062884 -0.026056 0.029827 +v 0.064149 -0.028706 0.026662 +v 0.064058 -0.026067 0.027270 +v 0.066651 -0.026115 0.027095 +v 0.008971 -0.090721 -0.018593 +v 0.007398 -0.090656 -0.022301 +v 0.009565 -0.090664 -0.020561 +v 0.006823 -0.090725 -0.017861 +v 0.005111 -0.090632 -0.019097 +v 0.005497 -0.090723 -0.021312 +v 0.006109 -0.080305 -0.019960 +v 0.007471 -0.080469 -0.018720 +v 0.008394 -0.080330 -0.020310 +v 0.005798 -0.088079 -0.019384 +v 0.008729 -0.088122 -0.019583 +v 0.006480 -0.088227 -0.021697 +v 0.006731 -0.080721 -0.021311 +v 0.007794 -0.088317 -0.017703 +v 0.009577 -0.088271 -0.021075 +v 0.004888 -0.088306 -0.019369 +v 0.007250 -0.089250 -0.020000 +v -0.018703 -0.090722 0.005414 +v -0.020872 -0.090640 0.005776 +v -0.022161 -0.090716 0.003827 +v -0.021035 -0.090646 0.001508 +v -0.017760 -0.090742 0.002614 +v -0.021123 -0.080286 0.003531 +v -0.019732 -0.080403 0.004890 +v -0.018851 -0.080414 0.003200 +v -0.021355 -0.088130 0.003038 +v -0.020061 -0.088250 0.005481 +v -0.018638 -0.088135 0.004178 +v -0.018872 -0.088227 0.002267 +v -0.020481 -0.080721 0.002319 +v -0.017662 -0.088310 0.004367 +v -0.022329 -0.088306 0.003953 +v -0.020739 -0.088328 0.001428 +v -0.019962 -0.089250 0.003631 +v -0.054435 -0.070714 -0.022881 +v -0.057137 -0.070648 -0.022997 +v -0.057949 -0.070694 -0.025633 +v -0.055502 -0.070716 -0.027039 +v -0.053533 -0.070656 -0.025523 +v -0.054688 -0.060363 -0.025566 +v -0.057111 -0.060393 -0.024820 +v -0.055072 -0.060404 -0.023824 +v -0.057570 -0.068265 -0.025697 +v -0.055348 -0.068115 -0.023334 +v -0.054214 -0.068241 -0.025730 +v -0.056423 -0.068151 -0.026046 +v -0.054163 -0.068291 -0.022854 +v -0.055833 -0.068320 -0.027144 +v -0.057585 -0.068333 -0.023393 +v -0.055726 -0.069250 -0.024811 +v -0.031630 -0.070731 -0.049474 +v -0.034343 -0.070648 -0.049153 +v -0.035459 -0.070722 -0.051151 +v -0.031454 -0.070700 -0.052742 +v -0.034307 -0.070633 -0.053204 +v -0.032868 -0.060341 -0.050014 +v -0.032221 -0.060396 -0.052042 +v -0.034539 -0.060412 -0.051231 +v -0.033345 -0.068067 -0.052700 +v -0.034254 -0.068144 -0.050085 +v -0.031977 -0.068154 -0.050437 +v -0.030895 -0.068308 -0.051369 +v -0.033436 -0.068289 -0.053626 +v -0.032513 -0.068320 -0.048879 +v -0.035565 -0.068314 -0.050464 +v -0.033223 -0.069250 -0.051159 +v 0.002407 -0.070722 -0.060894 +v -0.000070 -0.070648 -0.058644 +v -0.001842 -0.070674 -0.059911 +v -0.001973 -0.070711 -0.062014 +v 0.000091 -0.070686 -0.063349 +v 0.001214 -0.060364 -0.060491 +v -0.000121 -0.060341 -0.062168 +v -0.001353 -0.060452 -0.060658 +v -0.001142 -0.068155 -0.061789 +v -0.000937 -0.068154 -0.059896 +v -0.000100 -0.068198 -0.058955 +v 0.001023 -0.068130 -0.062081 +v 0.000318 -0.068319 -0.063339 +v -0.002457 -0.068309 -0.061287 +v 0.002411 -0.068258 -0.060128 +v 0.000746 -0.069250 -0.061489 +v 0.009107 -0.090726 -0.053887 +v 0.007356 -0.090656 -0.052661 +v 0.004887 -0.090711 -0.054617 +v 0.006097 -0.080377 -0.055428 +v 0.007159 -0.080448 -0.053728 +v 0.008349 -0.080367 -0.055776 +v 0.006670 -0.088135 -0.053619 +v 0.008717 -0.088139 -0.055076 +v 0.006503 -0.088122 -0.056321 +v 0.007768 -0.088308 -0.052696 +v 0.009587 -0.088283 -0.056051 +v 0.006224 -0.088307 -0.057048 +v 0.004889 -0.088325 -0.054373 +v 0.009138 -0.090677 -0.056422 +v 0.006404 -0.090720 -0.057069 +v 0.007250 -0.089250 -0.055000 +v -0.052377 -0.090713 0.013465 +v -0.050612 -0.090687 0.014916 +v -0.051289 -0.090687 0.017174 +v -0.052364 -0.080342 0.016836 +v -0.052095 -0.080370 0.014656 +v -0.054093 -0.080512 0.015101 +v -0.053968 -0.088160 0.016445 +v -0.052025 -0.088156 0.016795 +v -0.051915 -0.088115 0.014463 +v -0.053885 -0.088151 0.014669 +v -0.055207 -0.088314 0.016251 +v -0.052307 -0.088317 0.017898 +v -0.050466 -0.088303 0.014841 +v -0.053652 -0.088302 0.013406 +v -0.055030 -0.090713 0.014537 +v -0.053659 -0.090720 0.017795 +v -0.052851 -0.089250 0.015601 +v -0.062440 -0.070726 0.009755 +v -0.060739 -0.070698 0.007102 +v -0.057880 -0.070700 0.009471 +v -0.059787 -0.060406 0.010822 +v -0.059387 -0.060379 0.008690 +v -0.061409 -0.060372 0.009028 +v -0.061747 -0.068117 0.009298 +v -0.059838 -0.068114 0.010960 +v -0.059200 -0.068134 0.008463 +v -0.062036 -0.068294 0.007746 +v -0.061854 -0.068321 0.011207 +v -0.059125 -0.068308 0.011619 +v -0.058079 -0.068306 0.008416 +v -0.060462 -0.070719 0.011955 +v -0.060249 -0.069250 0.009543 +v 0.041279 -0.073220 -0.064267 +v 0.044267 -0.073148 -0.063134 +v 0.044367 -0.073220 -0.059820 +v 0.040978 -0.073220 -0.058980 +v 0.039133 -0.073167 -0.061312 +v 0.042915 -0.060350 -0.060321 +v 0.041744 -0.060332 -0.062938 +v 0.040623 -0.060405 -0.060808 +v 0.042818 -0.070150 -0.063026 +v 0.040210 -0.070092 -0.061492 +v 0.043071 -0.070106 -0.060015 +v 0.043232 -0.060711 -0.062594 +v 0.043184 -0.070312 -0.064256 +v 0.039453 -0.070299 -0.062823 +v 0.039871 -0.070329 -0.059622 +v 0.042974 -0.070319 -0.058804 +v 0.044761 -0.070325 -0.061114 +v 0.043443 -0.071250 -0.061128 +v 0.040945 -0.071250 -0.061859 +v -0.031121 -0.073214 0.055972 +v -0.033644 -0.073195 0.053743 +v -0.032055 -0.073179 0.050829 +v -0.030146 -0.060270 0.051861 +v -0.032267 -0.060499 0.053241 +v -0.030023 -0.060422 0.054778 +v -0.032499 -0.070105 0.052829 +v -0.031006 -0.070164 0.054868 +v -0.029206 -0.070157 0.053927 +v -0.029883 -0.070161 0.051825 +v -0.029180 -0.070305 0.050954 +v -0.032012 -0.070321 0.050719 +v -0.031089 -0.070284 0.056317 +v -0.027895 -0.070336 0.053527 +v -0.033561 -0.070323 0.053191 +v -0.027888 -0.073231 0.054038 +v -0.029561 -0.073231 0.050823 +v -0.029307 -0.071250 0.053633 +v -0.031805 -0.071250 0.052901 +v 0.041552 -0.073221 0.064249 +v 0.039071 -0.073152 0.061685 +v 0.041045 -0.073225 0.058932 +v 0.043663 -0.073162 0.059267 +v 0.044768 -0.073217 0.062341 +v 0.042478 -0.060418 0.062849 +v 0.043536 -0.060521 0.061048 +v 0.041485 -0.060339 0.060158 +v 0.040577 -0.060465 0.062131 +v 0.041396 -0.070156 0.059908 +v 0.040380 -0.070129 0.062113 +v 0.042540 -0.070163 0.063066 +v 0.043668 -0.070142 0.061003 +v 0.041161 -0.070306 0.064276 +v 0.044858 -0.070301 0.062416 +v 0.039180 -0.070285 0.060190 +v 0.043243 -0.070323 0.058948 +v 0.043055 -0.071250 0.061859 +v 0.040557 -0.071250 0.061128 +v 0.069197 -0.090673 0.061053 +v 0.068449 -0.090726 0.057826 +v 0.071907 -0.090712 0.060690 +v 0.071345 -0.090645 0.056851 +v 0.072691 -0.090692 0.058763 +v 0.069710 -0.080324 0.058093 +v 0.071075 -0.080337 0.060027 +v 0.071429 -0.080438 0.058242 +v 0.069518 -0.088161 0.060028 +v 0.071625 -0.088253 0.060430 +v 0.069359 -0.080717 0.059880 +v 0.071657 -0.088146 0.058230 +v 0.069512 -0.088142 0.057883 +v 0.072600 -0.088292 0.057938 +v 0.068178 -0.088347 0.058406 +v 0.069243 -0.088283 0.061010 +v 0.070156 -0.088325 0.056736 +v 0.070464 -0.089250 0.059011 +v 0.077815 -0.070722 0.060450 +v 0.080053 -0.070657 0.058631 +v 0.082022 -0.070694 0.060094 +v 0.081646 -0.070706 0.062747 +v 0.078563 -0.070656 0.062812 +v 0.080336 -0.062356 0.062159 +v 0.081066 -0.062439 0.060276 +v 0.078680 -0.062438 0.060631 +v 0.079273 -0.068159 0.059783 +v 0.079248 -0.068091 0.062375 +v 0.081472 -0.068135 0.060651 +v 0.081638 -0.068318 0.062673 +v 0.081892 -0.068313 0.059458 +v 0.078431 -0.068305 0.059196 +v 0.078285 -0.068297 0.062777 +v 0.080000 -0.069250 0.061000 +v 0.105770 -0.090715 0.022647 +v 0.102870 -0.090687 0.020809 +v 0.104064 -0.090696 0.018515 +v 0.105820 -0.090719 0.018251 +v 0.107614 -0.090661 0.020019 +v 0.105544 -0.080305 0.021618 +v 0.105940 -0.080481 0.019139 +v 0.104090 -0.080346 0.020437 +v 0.103744 -0.088233 0.019437 +v 0.104790 -0.088139 0.021762 +v 0.107113 -0.088211 0.019690 +v 0.106116 -0.088157 0.019249 +v 0.103311 -0.088319 0.021657 +v 0.105369 -0.088325 0.018009 +v 0.106695 -0.088290 0.022419 +v 0.105258 -0.089250 0.020367 +v 0.141566 -0.090722 0.002296 +v 0.139651 -0.090640 0.003112 +v 0.137645 -0.090749 0.000954 +v 0.139467 -0.090652 -0.001445 +v 0.142096 -0.090712 -0.000291 +v 0.140643 -0.080346 0.001854 +v 0.139558 -0.080329 -0.000295 +v 0.138921 -0.080453 0.001363 +v 0.138770 -0.088113 0.001756 +v 0.141335 -0.088141 0.001357 +v 0.141069 -0.080726 -0.000076 +v 0.140073 -0.088122 -0.000710 +v 0.139230 -0.088325 0.003034 +v 0.142017 -0.088327 0.002030 +v 0.137703 -0.088278 -0.000198 +v 0.141435 -0.088301 -0.001142 +v 0.140000 -0.089250 0.000803 +v 0.119044 -0.070734 0.059048 +v 0.121275 -0.070655 0.059018 +v 0.122129 -0.070687 0.062098 +v 0.121119 -0.060381 0.060450 +v 0.118828 -0.060501 0.060307 +v 0.120009 -0.060320 0.062258 +v 0.120162 -0.068098 0.059439 +v 0.118761 -0.068134 0.061872 +v 0.121185 -0.068152 0.061847 +v 0.117560 -0.068295 0.060827 +v 0.119823 -0.068330 0.058694 +v 0.120525 -0.068278 0.063449 +v 0.122245 -0.068323 0.060187 +v 0.117676 -0.070696 0.061160 +v 0.119440 -0.070711 0.063159 +v 0.120000 -0.069250 0.061000 +v 0.159769 -0.070679 0.048017 +v 0.158709 -0.070669 0.050090 +v 0.155864 -0.070700 0.049664 +v 0.155664 -0.070671 0.046666 +v 0.158329 -0.070710 0.045935 +v 0.156237 -0.060445 0.048086 +v 0.158213 -0.060390 0.049179 +v 0.158142 -0.060354 0.046970 +v 0.156401 -0.068144 0.047203 +v 0.156795 -0.068153 0.049281 +v 0.158586 -0.068243 0.049559 +v 0.158495 -0.068150 0.046963 +v 0.159733 -0.068303 0.046835 +v 0.155730 -0.068250 0.046393 +v 0.156174 -0.068322 0.050015 +v 0.157555 -0.069250 0.048069 +v 0.178645 -0.070719 0.012599 +v 0.181604 -0.070694 0.014046 +v 0.179395 -0.070714 0.017121 +v 0.178929 -0.060496 0.013472 +v 0.178348 -0.060322 0.015767 +v 0.180392 -0.060359 0.014821 +v 0.178483 -0.068235 0.013084 +v 0.178255 -0.068238 0.016500 +v 0.179524 -0.068153 0.016165 +v 0.180521 -0.068142 0.014080 +v 0.181222 -0.068301 0.013453 +v 0.180613 -0.068316 0.016640 +v 0.176831 -0.068326 0.014628 +v 0.176837 -0.070711 0.014828 +v 0.179188 -0.069250 0.014757 +v 0.151990 -0.073232 -0.055849 +v 0.153533 -0.073149 -0.052812 +v 0.151768 -0.073186 -0.050674 +v 0.149297 -0.060347 -0.053310 +v 0.151471 -0.060401 -0.051758 +v 0.151266 -0.060425 -0.054773 +v 0.149264 -0.070117 -0.054292 +v 0.150297 -0.070151 -0.051612 +v 0.152551 -0.070092 -0.053663 +v 0.151382 -0.070321 -0.056027 +v 0.153586 -0.070319 -0.053679 +v 0.147773 -0.070284 -0.054031 +v 0.151112 -0.070284 -0.050207 +v 0.148246 -0.073196 -0.054682 +v 0.148882 -0.073219 -0.051206 +v 0.150966 -0.071250 -0.052167 +v 0.150351 -0.071250 -0.054696 +v 0.173909 -0.090722 0.002673 +v 0.172668 -0.090637 0.001148 +v 0.174523 -0.090730 -0.001532 +v 0.177197 -0.090661 0.000063 +v 0.176325 -0.090724 0.002684 +v 0.173755 -0.080363 0.001103 +v 0.175651 -0.080433 0.001849 +v 0.175648 -0.080369 -0.000368 +v 0.173656 -0.088140 0.001215 +v 0.175562 -0.088143 0.002172 +v 0.176252 -0.088158 0.000164 +v 0.174278 -0.088135 -0.000439 +v 0.176755 -0.088311 0.002344 +v 0.173684 -0.088320 0.002828 +v 0.172908 -0.088317 -0.000290 +v 0.176481 -0.088282 -0.001254 +v 0.175000 -0.089250 0.000803 +v 0.060211 -0.028750 -0.031385 +v 0.059856 -0.032750 -0.031195 +v 0.056296 -0.028750 -0.033051 +v 0.070396 -0.032792 -0.033484 +v 0.078065 -0.032587 -0.041977 +v 0.071451 -0.028750 -0.034335 +v 0.089082 -0.028750 -0.050733 +v 0.095180 -0.032494 -0.054176 +v 0.115773 -0.028750 -0.059509 +v 0.114896 -0.032544 -0.058992 +v 0.127229 -0.032735 -0.059098 +v 0.143455 -0.028750 -0.054587 +v 0.147325 -0.032712 -0.053241 +v 0.161507 -0.028750 -0.042240 +v 0.161962 -0.032816 -0.042759 +v 0.174161 -0.028750 -0.024422 +v 0.174505 -0.032823 -0.024880 +v 0.179246 -0.032720 -0.008978 +v 0.179505 -0.028761 0.002770 +v 0.176138 -0.032666 0.020839 +v 0.171894 -0.028754 0.028890 +v 0.162857 -0.032568 0.041071 +v 0.155443 -0.028753 0.047661 +v 0.149195 -0.032720 0.051862 +v 0.132731 -0.028753 0.058017 +v 0.132934 -0.032613 0.058155 +v 0.107768 -0.028752 0.058126 +v 0.107815 -0.032727 0.058604 +v 0.084963 -0.028752 0.047967 +v 0.083240 -0.032495 0.046984 +v 0.071409 -0.028750 0.034253 +v 0.071466 -0.032723 0.034339 +v 0.062144 -0.028572 -0.029650 +v 0.064502 -0.026000 -0.026080 +v 0.063261 -0.028713 -0.026533 +v 0.067477 -0.028681 -0.026904 +v 0.068571 -0.028546 -0.029630 +v 0.068251 -0.026000 -0.030811 +v 0.065600 -0.028570 -0.032705 +v 0.063143 -0.026000 -0.031457 +v 0.056206 -0.028750 0.033152 +v 0.059788 -0.032750 0.031194 +v 0.060201 -0.028750 0.031414 +v 0.008144 -0.026798 -0.059821 +v 0.008774 -0.032750 -0.060194 +v -0.008056 -0.032755 -0.059115 +v -0.012057 -0.028088 -0.059968 +v -0.012154 -0.028029 0.059936 +v -0.006293 -0.032629 0.059306 +v 0.008290 -0.032750 0.060349 +v 0.008426 -0.026738 0.059667 +v -0.025391 -0.028029 -0.055641 +v -0.028267 -0.032730 -0.052679 +v -0.037511 -0.032793 -0.046598 +v -0.039506 -0.027935 -0.046030 +v -0.049168 -0.032829 -0.034728 +v -0.054160 -0.027946 -0.028093 +v -0.054617 -0.032717 -0.024163 +v -0.058998 -0.032745 -0.009986 +v -0.060741 -0.028081 -0.007080 +v -0.060746 -0.028024 0.006975 +v -0.058595 -0.032768 0.011316 +v -0.054603 -0.032844 0.024733 +v -0.055276 -0.026849 0.023609 +v -0.043988 -0.028094 0.042384 +v -0.041945 -0.032773 0.043399 +v -0.028306 -0.032736 0.052689 +v -0.025361 -0.028061 0.055692 +v 0.058360 -0.028750 0.014890 +v 0.057071 -0.032685 0.016308 +v 0.050041 -0.028750 0.032027 +v 0.050946 -0.032628 0.031117 +v 0.032393 -0.028750 0.049802 +v 0.037342 -0.032587 0.046058 +v 0.019862 -0.032525 0.056120 +v 0.008986 -0.028750 0.058724 +v -0.016019 -0.028750 0.057204 +v -0.038175 -0.028750 0.045511 +v -0.036548 -0.032564 0.046774 +v -0.055035 -0.028750 0.022993 +v -0.059196 -0.028751 -0.006224 +v -0.050511 -0.028750 -0.031255 +v -0.033134 -0.028750 -0.049303 +v -0.009864 -0.028750 -0.058581 +v 0.007669 -0.032545 -0.059044 +v 0.015161 -0.028750 -0.057441 +v 0.028283 -0.032512 -0.052158 +v 0.037192 -0.028752 -0.046289 +v 0.047683 -0.032648 -0.036139 +v 0.050899 -0.028752 -0.030255 +v 0.058113 -0.028750 -0.015040 +v 0.057577 -0.032743 -0.015600 +v -0.065341 -0.032750 0.000054 +v -0.065314 -0.027898 -0.000013 +v -0.020328 -0.032750 -0.062122 +v -0.020195 -0.027922 -0.062131 +v -0.020283 -0.032750 0.062156 +v -0.020186 -0.027908 0.062118 +v 0.066086 -0.032750 0.034822 +v 0.070834 -0.032750 0.043497 +v 0.111710 -0.032750 -0.060349 +v 0.049496 -0.032750 0.042422 +v 0.165610 -0.032750 0.040918 +v 0.060564 -0.032750 0.027379 +v 0.078957 -0.032750 -0.051212 +v 0.070732 -0.032750 -0.044962 +v 0.064833 -0.032480 0.021382 +v 0.061842 -0.032829 0.015285 +v 0.044324 -0.028122 0.050497 +v 0.045078 -0.032750 0.050409 +v 0.079389 -0.028064 0.051284 +v 0.081212 -0.032750 0.051607 +v 0.111870 -0.026694 0.059773 +v 0.070732 -0.028750 0.044962 +v 0.068437 -0.032750 0.046137 +v 0.050906 -0.028750 0.046005 +v 0.050574 -0.032750 0.045882 +v 0.049369 -0.028750 0.042718 +v 0.111577 -0.026702 -0.059650 +v 0.078716 -0.026457 -0.050287 +v 0.045070 -0.028130 -0.050412 +v 0.042671 -0.032750 -0.050744 +v 0.049661 -0.032750 -0.042155 +v 0.049230 -0.028750 -0.043097 +v 0.050188 -0.032750 -0.045724 +v 0.051316 -0.028750 -0.046117 +v 0.068437 -0.028750 -0.046137 +v 0.132154 -0.028029 -0.059936 +v 0.132026 -0.032750 0.060175 +v 0.132057 -0.028088 0.059968 +v 0.180746 -0.028024 -0.006976 +v 0.174326 -0.026985 -0.026311 +v 0.160478 -0.026375 -0.044315 +v 0.145361 -0.028060 -0.055692 +v 0.145391 -0.028029 0.055641 +v 0.166192 -0.028023 0.040262 +v 0.176836 -0.026666 0.018892 +v 0.180654 -0.032750 0.007175 +v 0.180741 -0.028080 0.007080 +v 0.185314 -0.027898 0.000013 +v 0.185341 -0.032750 -0.000054 +v 0.064427 -0.032830 -0.022458 +v 0.063217 -0.032519 -0.016467 +v 0.060572 -0.032750 -0.027336 +v 0.140283 -0.032750 -0.062156 +v 0.140186 -0.027908 -0.062118 +v 0.140328 -0.032750 0.062122 +v 0.140194 -0.027922 0.062131 +v 0.066032 -0.028750 0.034939 +v 0.066007 -0.032750 -0.035541 +v 0.070834 -0.028750 -0.043497 +v 0.066085 -0.028750 -0.034822 +v 0.062184 -0.028578 0.030081 +v 0.062619 -0.026000 0.028262 +v 0.063951 -0.026000 0.032001 +v 0.065358 -0.028572 0.032603 +v 0.067651 -0.026000 0.031192 +v 0.068622 -0.028669 0.030029 +v 0.067139 -0.026000 0.026699 +v 0.067515 -0.028538 0.026936 +v 0.063257 -0.028718 0.026543 +v 0.060656 -0.028750 0.027216 +v 0.064070 -0.028750 0.017966 +v 0.060647 -0.028750 -0.027258 +v 0.063986 -0.028750 -0.017662 +v -0.061094 -0.025985 0.000258 +v -0.041569 -0.025998 0.041749 +v -0.018692 -0.025984 0.058208 +v -0.019534 -0.026161 0.060225 +v -0.063327 -0.026159 0.000007 +v -0.019095 -0.025984 -0.058078 +v -0.047028 -0.025993 -0.036393 +v 0.038358 -0.026000 0.049653 +v 0.074417 -0.026001 0.048312 +v -0.019554 -0.026161 -0.060218 +v 0.139095 -0.025984 0.058077 +v 0.139606 -0.026137 0.060246 +v 0.047194 -0.026001 -0.048060 +v 0.162837 -0.025998 0.040447 +v 0.181355 -0.025973 0.000756 +v 0.138236 -0.025980 -0.058447 +v 0.183339 -0.026164 0.000001 +v 0.139532 -0.026166 -0.060236 +v 0.047040 0.027001 0.001808 +v 0.046559 0.032830 0.003160 +v 0.045657 0.025499 0.009752 +v 0.046905 0.027001 -0.001883 +v 0.045181 0.025508 -0.012831 +v 0.046541 0.032569 -0.003060 +v 0.045355 0.030366 -0.012372 +v 0.040821 0.026997 -0.025453 +v 0.036311 0.027000 -0.030885 +v 0.036370 0.025500 -0.030979 +v 0.036382 0.025499 0.030983 +v 0.042508 0.027032 0.019404 +v 0.036370 0.027000 0.030979 +v 0.045575 0.030234 0.009859 +v 0.083629 0.025499 -0.030918 +v 0.077638 0.027009 -0.019717 +v 0.083664 0.027000 -0.030868 +v 0.074343 0.025498 -0.009752 +v 0.074818 0.030061 -0.012768 +v 0.073413 0.033047 -0.003369 +v 0.072960 0.027001 -0.001808 +v 0.073095 0.027001 0.001883 +v 0.074666 0.025503 0.012636 +v 0.073356 0.032729 0.002751 +v 0.074363 0.030874 0.011077 +v 0.078243 0.027042 0.021804 +v 0.083689 0.027000 0.030885 +v 0.083664 0.025500 0.030868 +v 0.117211 0.036880 -0.017588 +v 0.087470 0.036885 -0.002833 +v 0.090924 0.036899 0.000113 +v 0.136687 0.036927 0.007161 +v 0.136852 0.036850 -0.007189 +v 0.089457 0.036969 0.002499 +v 0.127004 0.036844 0.017140 +v 0.061172 0.037087 0.002414 +v 0.085435 0.036915 0.001333 +v 0.127349 0.036833 -0.016837 +v 0.116487 0.036813 0.017511 +v 0.009850 0.037295 0.001553 +v 0.046627 0.036799 -0.003570 +v 0.005177 0.037260 -0.008983 +v 0.034019 0.036866 0.006385 +v -0.011855 0.037051 0.006081 +v -0.017832 0.036877 -0.000578 +v -0.008315 0.036931 0.016090 +v -0.008769 0.037127 -0.006726 +v -0.007083 0.036901 -0.016871 +v -0.001029 0.037131 -0.010997 +v 0.003559 0.036821 -0.017512 +v 0.005904 0.037370 0.007811 +v 0.002937 0.036836 0.017711 +v 0.077249 0.025498 0.033727 +v 0.076994 0.026462 0.033767 +v 0.046136 0.026288 0.033384 +v 0.109814 0.025500 0.045989 +v 0.109982 0.026494 0.045965 +v 0.032503 0.025500 0.036841 +v 0.011504 0.026484 0.045294 +v 0.012727 0.025501 0.045037 +v -0.003380 0.026349 0.046545 +v -0.043804 0.026264 0.016708 +v -0.046207 0.026502 0.005341 +v -0.046561 0.026191 -0.005586 +v -0.032864 0.031464 -0.001306 +v -0.037014 0.029513 -0.003078 +v -0.032549 0.029000 0.000000 +v -0.034733 0.030738 0.002950 +v -0.037025 0.029394 0.003102 +v 0.022891 0.032353 0.023226 +v 0.027922 0.031724 0.023306 +v 0.027343 0.029568 0.028237 +v 0.023965 0.030438 0.028448 +v -0.039229 0.029098 -0.000134 +v -0.022232 0.031161 0.025331 +v -0.024678 0.029585 0.028540 +v -0.027638 0.026303 0.037655 +v -0.036751 0.026323 0.028881 +v -0.028243 0.029092 0.027251 +v -0.024694 0.031307 0.022349 +v -0.016758 0.036548 0.009125 +v -0.028130 0.029477 0.023670 +v 0.000674 0.031483 0.032822 +v 0.003172 0.029725 0.036913 +v -0.000545 0.029101 0.039262 +v -0.003156 0.030623 0.035038 +v -0.016938 0.026153 0.043583 +v -0.022627 0.028997 0.027183 +v -0.023627 0.029000 0.022798 +v 0.023060 0.029000 0.027516 +v 0.022788 0.029000 0.023631 +v 0.028064 0.028995 0.023046 +v -0.003297 0.029000 0.036000 +v -0.000009 0.028999 0.032710 +v 0.003064 0.028999 0.035331 +v 0.063564 0.026470 0.028838 +v 0.059976 0.026998 0.024604 +v 0.048142 0.034500 0.004366 +v 0.071895 0.034518 0.004174 +v 0.046551 0.031439 0.012649 +v 0.041339 0.027025 0.026117 +v 0.077977 0.027039 0.026405 +v 0.087496 0.025500 -0.036841 +v 0.108496 0.026484 -0.045294 +v 0.107273 0.025501 -0.045037 +v 0.072327 0.026276 -0.033087 +v 0.025328 0.025500 -0.039623 +v 0.009629 0.026392 -0.046085 +v 0.043852 0.026271 -0.033733 +v 0.026517 0.029542 -0.028685 +v 0.028248 0.030379 -0.027091 +v 0.027888 0.031654 -0.023524 +v 0.024325 0.032461 -0.022386 +v 0.022312 0.031408 -0.026233 +v -0.025279 0.029381 -0.028800 +v -0.022231 0.031162 -0.025331 +v -0.030117 0.026299 -0.035891 +v -0.028860 0.029256 -0.025421 +v -0.025069 0.031244 -0.022197 +v -0.040860 0.026366 -0.022791 +v -0.016647 0.036542 -0.009317 +v 0.002933 0.029379 -0.037758 +v 0.000959 0.031482 -0.032826 +v -0.002162 0.029196 -0.038608 +v -0.007087 0.026388 -0.046093 +v -0.003065 0.030677 -0.034893 +v -0.018810 0.026002 -0.042797 +v -0.022457 0.029000 -0.024392 +v -0.025449 0.029000 -0.022281 +v -0.023860 0.029000 -0.028340 +v 0.028001 0.028999 -0.022999 +v 0.022592 0.029000 -0.023834 +v 0.023338 0.029000 -0.027743 +v 0.001992 0.029000 -0.033622 +v -0.001666 0.029000 -0.033182 +v 0.061532 0.026561 -0.028677 +v 0.059995 0.026998 -0.024604 +v 0.048027 0.034502 -0.004170 +v 0.045470 0.029920 -0.017474 +v 0.078659 0.027029 -0.026042 +v 0.123362 0.026330 -0.046553 +v 0.161870 0.025984 0.020763 +v 0.155403 0.026471 0.030457 +v 0.152330 0.025500 0.033692 +v 0.141891 0.026383 0.041480 +v 0.127087 0.026388 0.046093 +v 0.154697 0.029000 -0.002967 +v 0.152864 0.031464 0.001306 +v 0.153088 0.029000 0.001920 +v 0.154733 0.030738 -0.002950 +v 0.158603 0.029204 -0.001883 +v 0.158424 0.029297 0.002341 +v 0.094983 0.030272 0.028540 +v 0.091752 0.030379 0.027091 +v 0.092112 0.031654 0.023524 +v 0.095675 0.032461 0.022386 +v 0.083113 0.036610 0.006611 +v 0.097688 0.031408 0.026233 +v 0.145627 0.029341 0.028633 +v 0.142704 0.030612 0.026903 +v 0.144054 0.031512 0.022252 +v 0.148798 0.029240 0.025754 +v 0.118500 0.029191 0.038911 +v 0.117076 0.030769 0.034653 +v 0.120103 0.031456 0.032894 +v 0.122582 0.029251 0.037990 +v 0.123065 0.030677 0.034893 +v 0.166063 0.026440 0.007656 +v 0.143619 0.029000 0.022805 +v 0.142699 0.029000 0.027381 +v 0.147319 0.028999 0.022937 +v 0.091436 0.029000 0.026333 +v 0.093196 0.029000 0.022505 +v 0.097408 0.029000 0.023834 +v 0.095650 0.029000 0.028678 +v 0.116600 0.028998 0.035028 +v 0.121666 0.029000 0.033182 +v 0.097109 0.032353 -0.023226 +v 0.086003 0.036551 -0.007548 +v 0.092078 0.031724 -0.023306 +v 0.092062 0.030307 -0.027406 +v 0.096035 0.030438 -0.028448 +v 0.166568 0.026236 -0.003351 +v 0.142232 0.031161 -0.025331 +v 0.144902 0.029489 -0.028630 +v 0.147627 0.026324 -0.037654 +v 0.156751 0.026323 -0.028881 +v 0.145639 0.031129 -0.022038 +v 0.148598 0.029139 -0.026566 +v 0.119932 0.031468 -0.032865 +v 0.116748 0.030461 -0.035461 +v 0.116712 0.029290 -0.037172 +v 0.120887 0.029137 -0.039110 +v 0.123156 0.030623 -0.035038 +v 0.136973 0.026196 -0.043561 +v 0.163179 0.026320 -0.018039 +v 0.142627 0.028997 -0.027183 +v 0.147255 0.029000 -0.022900 +v 0.143627 0.029000 -0.022798 +v 0.093227 0.029000 -0.028493 +v 0.091557 0.028998 -0.024005 +v 0.097923 0.029000 -0.026103 +v 0.095346 0.029000 -0.022423 +v 0.123297 0.029000 -0.036000 +v 0.120009 0.028999 -0.032710 +v 0.071298 0.034653 -0.003938 +v 0.071313 0.033056 0.001545 +v 0.048198 0.033325 0.001665 +v 0.048397 0.032995 -0.001518 +v 0.071830 0.032823 -0.001518 +v -0.006788 0.040275 0.002935 +v -0.007839 0.038068 0.004711 +v -0.001065 0.037948 0.009115 +v 0.002480 0.040266 0.007046 +v 0.007253 0.040239 -0.000461 +v 0.007940 0.038016 -0.003788 +v 0.002020 0.040025 -0.007046 +v -0.005494 0.039983 -0.004725 +v 0.000853 0.052779 0.001589 +v 0.004720 0.052829 0.000929 +v 0.001820 0.052860 0.000096 +v -0.000882 0.052768 -0.001569 +v -0.000966 0.052836 -0.004814 +v -0.004547 0.052836 -0.001469 +v -0.001833 0.052856 -0.000042 +v 0.000982 0.052812 -0.001558 +v 0.003566 0.052805 -0.003171 +v -0.000956 0.052818 0.001549 +v -0.003987 0.052784 0.002791 +v 0.001139 0.052805 0.004827 +v 0.001347 0.049762 0.004860 +v -0.002741 0.049763 0.003040 +v -0.005022 0.049762 -0.000464 +v -0.001886 0.049763 -0.004568 +v 0.002963 0.049762 -0.004015 +v 0.004932 0.049763 0.000757 +v 0.003507 0.049762 -0.000977 +v 0.000899 0.049762 0.003234 +v -0.001933 0.049762 -0.003010 +v 0.002124 0.034039 0.002589 +v -0.000638 0.033959 0.003115 +v -0.003204 0.033957 0.000391 +v -0.000809 0.033968 -0.003267 +v 0.002910 0.034037 -0.001410 +v -0.000509 0.032011 0.038575 +v 0.002389 0.031926 0.037696 +v 0.001708 0.031960 0.033648 +v -0.001492 0.032005 0.033815 +v -0.002854 0.031920 0.036510 +v -0.001389 0.021070 0.036008 +v 0.000075 0.021230 0.034378 +v 0.001406 0.021138 0.035748 +v -0.000026 0.021217 0.037630 +v -0.000592 0.028880 0.034314 +v 0.001670 0.028905 0.035818 +v 0.000806 0.028912 0.037437 +v -0.001383 0.028899 0.037018 +v 0.002722 0.029054 0.035196 +v 0.001146 0.029052 0.038760 +v -0.001070 0.029011 0.033101 +v -0.002569 0.029060 0.037270 +v -0.001449 0.030000 0.036349 +v 0.001061 0.030000 0.035658 +v 0.027685 0.031994 0.023934 +v 0.024032 0.032014 0.028029 +v 0.028163 0.031925 0.026577 +v 0.024729 0.031988 0.022831 +v 0.022799 0.031921 0.024660 +v 0.025470 0.021096 0.026843 +v 0.023860 0.021284 0.025791 +v 0.025245 0.021086 0.024074 +v 0.027093 0.021252 0.025391 +v 0.024641 0.028886 0.023868 +v 0.026794 0.028915 0.024556 +v 0.026603 0.028888 0.026793 +v 0.024074 0.028908 0.026423 +v 0.027033 0.029066 0.023156 +v 0.028259 0.029047 0.026398 +v 0.024494 0.029043 0.028221 +v 0.022691 0.029069 0.025536 +v 0.024016 0.029069 0.022981 +v 0.026569 0.030000 0.025400 +v 0.023966 0.030000 0.025418 +v 0.022852 0.032005 -0.025454 +v 0.023816 0.031917 -0.023100 +v 0.026757 0.032004 -0.023162 +v 0.028256 0.031922 -0.025144 +v 0.026682 0.031932 -0.028083 +v 0.024119 0.031993 -0.027789 +v 0.024929 0.021096 -0.026805 +v 0.026906 0.021022 -0.025628 +v 0.024063 0.021136 -0.025084 +v 0.023829 0.028909 -0.024884 +v 0.022908 0.028958 -0.025781 +v 0.027044 0.028854 -0.026348 +v 0.025931 0.021416 -0.023778 +v 0.025827 0.028911 -0.023837 +v 0.024636 0.029063 -0.022650 +v 0.028300 0.029038 -0.024637 +v 0.025493 0.029025 -0.028545 +v 0.025400 0.030000 -0.026569 +v 0.025418 0.030000 -0.023966 +v -0.002771 0.031974 -0.035183 +v 0.000184 0.031931 -0.033188 +v 0.002421 0.031987 -0.034770 +v 0.001390 0.021060 -0.036177 +v -0.000075 0.021230 -0.034378 +v -0.001406 0.021138 -0.035748 +v 0.000036 0.021222 -0.037647 +v -0.001140 0.028905 -0.034736 +v -0.001164 0.028890 -0.037306 +v 0.000999 0.028938 -0.037777 +v 0.001258 0.028901 -0.034848 +v 0.000198 0.029063 -0.033083 +v 0.002925 0.029054 -0.036011 +v -0.001821 0.029057 -0.038327 +v -0.002574 0.029059 -0.034929 +v 0.001645 0.031983 -0.038407 +v -0.001555 0.031996 -0.038127 +v 0.001449 0.030000 -0.036349 +v -0.001061 0.030000 -0.035658 +v -0.024209 0.031989 -0.027928 +v -0.026839 0.031921 -0.027818 +v -0.028322 0.031966 -0.025511 +v -0.025102 0.021084 -0.024076 +v -0.026077 0.021199 -0.026834 +v -0.023927 0.021262 -0.025884 +v -0.026846 0.021236 -0.024878 +v -0.024347 0.028917 -0.024244 +v -0.026711 0.028893 -0.024227 +v -0.026555 0.028911 -0.026690 +v -0.024126 0.028888 -0.026623 +v -0.024725 0.029055 -0.022713 +v -0.022516 0.029047 -0.025778 +v -0.025296 0.029062 -0.028289 +v -0.027871 0.029056 -0.026855 +v -0.027844 0.029076 -0.023874 +v -0.026146 0.031986 -0.022768 +v -0.022699 0.031965 -0.024526 +v -0.024678 0.030000 -0.026727 +v -0.025964 0.030000 -0.024464 +v -0.037119 0.032009 -0.002710 +v -0.038313 0.031986 0.002005 +v -0.034749 0.031992 0.002344 +v -0.034500 0.021144 -0.000281 +v -0.036353 0.021106 0.001515 +v -0.037133 0.021117 -0.001165 +v -0.034173 0.028844 0.000343 +v -0.037544 0.028821 0.000972 +v -0.036375 0.028904 -0.001661 +v -0.033650 0.029069 -0.001636 +v -0.033636 0.029064 0.001523 +v -0.036769 0.029038 0.002795 +v -0.038778 0.029064 0.000253 +v -0.037214 0.029062 -0.002660 +v -0.033228 0.031992 -0.000679 +v -0.034593 0.030000 -0.000426 +v -0.037407 0.030000 0.000426 +v -0.023265 0.031994 0.023969 +v -0.025541 0.031923 0.022639 +v -0.028342 0.032003 0.025038 +v -0.026048 0.031988 0.028115 +v -0.022930 0.031932 0.026883 +v -0.026636 0.021058 0.026482 +v -0.025288 0.021202 0.023790 +v -0.024185 0.021209 0.026245 +v -0.023670 0.028850 0.024915 +v -0.025975 0.028872 0.027154 +v -0.026830 0.028891 0.024338 +v -0.023526 0.029055 0.027537 +v -0.027586 0.029034 0.027602 +v -0.023334 0.029011 0.023209 +v -0.027589 0.029072 0.023586 +v -0.026392 0.030000 0.026061 +v -0.024147 0.030000 0.024744 +v 0.121549 0.031989 0.038177 +v 0.122815 0.031932 0.035300 +v 0.121055 0.031959 0.033516 +v 0.119439 0.021096 0.034622 +v 0.121564 0.021161 0.035704 +v 0.119170 0.021113 0.037405 +v 0.120386 0.028887 0.037744 +v 0.118275 0.028900 0.035940 +v 0.117857 0.028971 0.034675 +v 0.121517 0.028898 0.035150 +v 0.122625 0.029055 0.037080 +v 0.117528 0.029051 0.037451 +v 0.120250 0.029075 0.038777 +v 0.121434 0.029052 0.033378 +v 0.117835 0.032008 0.034096 +v 0.118264 0.031961 0.038347 +v 0.119874 0.030000 0.034536 +v 0.120126 0.030000 0.037464 +v 0.095252 0.032001 0.022870 +v 0.092291 0.031947 0.023579 +v 0.092511 0.031989 0.027313 +v 0.096231 0.031954 0.027893 +v 0.097083 0.031994 0.024736 +v 0.094493 0.021085 0.023899 +v 0.095948 0.021172 0.026240 +v 0.093135 0.021098 0.026095 +v 0.094308 0.028903 0.027186 +v 0.092989 0.028862 0.024516 +v 0.096284 0.028853 0.024859 +v 0.092361 0.029066 0.027191 +v 0.095552 0.029052 0.028202 +v 0.097364 0.029069 0.024959 +v 0.092142 0.029047 0.023731 +v 0.095392 0.029060 0.022823 +v 0.094043 0.030000 0.024074 +v 0.095045 0.030000 0.026838 +v 0.095084 0.031946 -0.024114 +v 0.097389 0.031929 -0.025833 +v 0.095337 0.031955 -0.027996 +v 0.092697 0.031933 -0.027583 +v 0.091871 0.031989 -0.025168 +v 0.094780 0.031971 -0.022404 +v 0.095878 0.021089 -0.024912 +v 0.093674 0.021178 -0.024131 +v 0.094939 0.021090 -0.026866 +v 0.093177 0.028854 -0.024257 +v 0.094793 0.028839 -0.027271 +v 0.093317 0.021489 -0.026526 +v 0.096020 0.028910 -0.024643 +v 0.097246 0.029069 -0.024865 +v 0.095343 0.029069 -0.022706 +v 0.092623 0.029062 -0.027659 +v 0.096364 0.029052 -0.027671 +v 0.092112 0.029052 -0.023938 +v 0.094544 0.030000 -0.025456 +v 0.122620 0.031995 -0.036763 +v 0.119892 0.031948 -0.038930 +v 0.117261 0.031986 -0.036318 +v 0.119432 0.031952 -0.033059 +v 0.121849 0.032004 -0.034196 +v 0.121293 0.021104 -0.035241 +v 0.119168 0.021222 -0.034735 +v 0.118663 0.021124 -0.036451 +v 0.120354 0.021274 -0.037580 +v 0.119569 0.028917 -0.037600 +v 0.121769 0.028883 -0.036314 +v 0.120234 0.028896 -0.034360 +v 0.118309 0.028880 -0.035660 +v 0.118300 0.029066 -0.033790 +v 0.117203 0.029059 -0.036620 +v 0.120514 0.029031 -0.038949 +v 0.122757 0.029075 -0.036242 +v 0.121490 0.029057 -0.033518 +v 0.120126 0.030000 -0.034536 +v 0.119874 0.030000 -0.037464 +v 0.143131 0.032000 -0.026706 +v 0.143483 0.031971 -0.023076 +v 0.147518 0.031994 -0.023701 +v 0.147890 0.031995 -0.026555 +v 0.145738 0.031937 -0.028314 +v 0.144090 0.021197 -0.026270 +v 0.146846 0.021111 -0.026159 +v 0.145471 0.021115 -0.023876 +v 0.144868 0.028837 -0.027122 +v 0.147121 0.028912 -0.025643 +v 0.145739 0.028903 -0.023766 +v 0.143899 0.028895 -0.024942 +v 0.148146 0.029063 -0.024557 +v 0.146422 0.029024 -0.028357 +v 0.144657 0.029034 -0.022539 +v 0.142694 0.029060 -0.026214 +v 0.145281 0.030000 -0.024355 +v 0.145801 0.030000 -0.026906 +v 0.154352 0.032008 -0.002419 +v 0.153910 0.031939 0.002143 +v 0.158126 0.031990 0.001942 +v 0.155202 0.021059 0.001231 +v 0.156702 0.021093 -0.001360 +v 0.157112 0.021161 0.000953 +v 0.156916 0.028912 -0.001343 +v 0.157507 0.028897 0.000862 +v 0.155219 0.028908 0.001464 +v 0.154515 0.028888 -0.001027 +v 0.154469 0.021482 -0.000621 +v 0.152941 0.028979 -0.000082 +v 0.158844 0.029066 -0.000530 +v 0.156632 0.029066 0.002920 +v 0.156265 0.029053 -0.002826 +v 0.158127 0.031993 -0.001680 +v 0.154536 0.030000 0.000126 +v 0.157464 0.030000 -0.000126 +v 0.145724 0.031995 0.022678 +v 0.142661 0.031932 0.024680 +v 0.143797 0.031992 0.027557 +v 0.147100 0.031937 0.027883 +v 0.148108 0.031986 0.024978 +v 0.145087 0.021135 0.023897 +v 0.146905 0.021114 0.025615 +v 0.144208 0.021083 0.026151 +v 0.147142 0.028905 0.025298 +v 0.145988 0.021469 0.027005 +v 0.145454 0.028897 0.027197 +v 0.143800 0.028913 0.025436 +v 0.145279 0.028902 0.023744 +v 0.142600 0.029060 0.025219 +v 0.145535 0.029040 0.022466 +v 0.146978 0.029062 0.027851 +v 0.144070 0.029066 0.027876 +v 0.148244 0.029064 0.025087 +v 0.145029 0.030000 0.024028 +v 0.145855 0.030000 0.026497 +v 0.001489 -0.068250 -0.058434 +v 0.002242 -0.074831 -0.059217 +v -0.002003 -0.074667 -0.059123 +v -0.002971 -0.068250 -0.061812 +v -0.002085 -0.072067 -0.062618 +v 0.000975 -0.071029 -0.063501 +v 0.001703 -0.068250 -0.063148 +v 0.001421 -0.076294 -0.055453 +v 0.005204 -0.075469 -0.060945 +v 0.006662 -0.070763 -0.064167 +v 0.003598 -0.078455 -0.055313 +v 0.000260 -0.075688 -0.028942 +v 0.003599 -0.078757 -0.021820 +v -0.054423 -0.076166 0.009377 +v -0.017243 -0.075731 -0.005441 +v -0.053919 -0.077436 0.011390 +v -0.009026 -0.078590 -0.004304 +v -0.055712 -0.078300 0.012993 +v -0.059185 -0.073999 0.014171 +v -0.057497 -0.075225 0.009440 +v -0.061867 -0.070095 0.018710 +v -0.059837 -0.073480 0.012272 +v -0.006514 -0.069594 -0.064414 +v 0.009066 -0.066566 -0.065980 +v -0.053981 -0.076063 -0.014781 +v -0.053097 -0.075076 -0.025916 +v -0.035626 -0.076147 -0.042331 +v -0.019252 -0.073008 -0.059071 +v -0.012325 -0.076012 -0.054920 +v -0.030348 -0.074138 -0.052013 +v -0.033236 -0.074856 -0.048444 +v -0.053471 -0.075069 -0.023194 +v -0.060717 -0.073686 -0.005406 +v -0.041806 -0.073382 -0.044885 +v -0.035950 -0.072141 -0.051271 +v -0.060341 -0.073779 0.006642 +v -0.056788 -0.073576 -0.022417 +v -0.050790 -0.070517 -0.039449 +v -0.056686 -0.071831 -0.027336 +v -0.064070 -0.070035 -0.008365 +v -0.034922 -0.070807 -0.053554 +v -0.062951 -0.070854 0.009988 +v -0.058618 -0.070934 -0.025336 +v -0.065510 -0.066269 0.010120 +v -0.021380 -0.066299 -0.062708 +v -0.040839 -0.066259 -0.052357 +v -0.057483 -0.066254 -0.033108 +v -0.065568 -0.066249 -0.009918 +v -0.002311 -0.090025 0.065724 +v -0.013593 -0.089326 0.064482 +v -0.011428 -0.092022 0.062946 +v -0.027790 -0.088880 0.059996 +v -0.029461 -0.091954 0.056521 +v -0.044161 -0.088920 0.049089 +v -0.033843 -0.091132 0.054956 +v -0.056775 -0.088803 0.034021 +v -0.045389 -0.091787 0.044946 +v -0.062307 -0.088941 0.020904 +v -0.059825 -0.091668 0.021406 +v -0.055337 -0.091824 0.031245 +v -0.032177 -0.093062 0.049727 +v 0.172227 -0.094335 0.000668 +v 0.142624 -0.099522 0.001288 +v 0.141394 -0.100160 -0.001408 +v 0.139006 -0.098601 0.003454 +v 0.175181 -0.090885 0.003845 +v 0.128607 -0.098590 0.004205 +v 0.128461 -0.101599 0.001563 +v 0.137825 -0.100656 -0.000919 +v 0.041925 -0.091193 0.064926 +v 0.064938 -0.089735 0.065573 +v 0.038182 -0.093304 0.061590 +v 0.045331 -0.092902 0.062498 +v 0.063824 -0.091972 0.064198 +v 0.119964 -0.102761 0.005122 +v 0.122074 -0.099709 0.006836 +v 0.092321 -0.097828 0.039791 +v 0.105059 -0.102296 0.023261 +v 0.088369 -0.099978 0.041384 +v 0.073046 -0.090842 0.061180 +v 0.073213 -0.094363 0.058498 +v 0.107868 -0.102711 0.019396 +v 0.095113 -0.102223 0.031317 +v 0.102972 -0.103557 0.018494 +v 0.070579 -0.092576 0.061663 +v 0.067810 -0.094171 0.059682 +v 0.008688 -0.088988 -0.065751 +v 0.009711 -0.086250 -0.065964 +v 0.010172 -0.086250 -0.066000 +v 0.009261 -0.086250 -0.065858 +v 0.008833 -0.086250 -0.065685 +v 0.008436 -0.086250 -0.065447 +v 0.008081 -0.086250 -0.065152 +v 0.007775 -0.086250 -0.064805 +v -0.062099 -0.086250 0.019873 +v -0.061880 -0.086250 0.019471 +v -0.062253 -0.086250 0.020304 +v -0.062341 -0.086250 0.020753 +v -0.062359 -0.086250 0.021210 +v -0.062308 -0.086250 0.021664 +v -0.062188 -0.086250 0.022106 +v -0.060222 -0.089661 0.017684 +v -0.060612 -0.086250 0.017726 +v 0.004783 -0.086250 -0.059116 +v 0.003978 -0.091244 -0.056651 +v 0.005574 -0.086250 -0.061116 +v 0.003866 -0.086250 -0.054919 +v 0.003750 -0.086250 -0.052771 +v 0.004211 -0.086250 -0.057042 +v 0.006575 -0.086250 -0.063020 +v 0.122990 -0.102474 -0.008793 +v 0.102669 -0.102455 -0.029108 +v 0.146751 -0.098724 -0.018030 +v 0.085388 -0.105924 -0.003550 +v -0.018881 -0.099117 0.026703 +v -0.050219 -0.094293 0.016886 +v 0.059751 -0.099144 -0.046865 +v 0.056573 -0.105136 -0.021697 +v 0.147847 -0.093346 -0.051444 +v 0.151154 -0.093368 -0.049831 +v 0.123421 -0.097099 -0.047062 +v 0.168323 -0.091802 -0.042077 +v 0.179255 -0.091805 -0.023112 +v 0.007500 -0.102336 -0.022796 +v 0.007289 -0.099911 -0.037273 +v 0.027624 -0.105135 -0.010254 +v 0.058372 -0.101477 0.039189 +v 0.056222 -0.106156 0.013236 +v 0.174969 -0.093809 -0.001866 +v 0.183368 -0.091882 -0.002674 +v 0.125328 -0.091796 -0.064056 +v 0.139191 -0.091826 -0.061072 +v 0.045493 -0.093006 -0.062440 +v 0.006828 -0.096124 -0.052258 +v 0.009979 -0.095380 -0.054942 +v -0.000643 -0.102815 -0.003099 +v 0.007003 -0.102737 -0.017336 +v -0.000076 -0.102726 0.012861 +v 0.008707 -0.100331 0.037045 +v -0.027327 -0.093182 0.052386 +v -0.054460 -0.093288 0.017690 +v 0.043029 -0.094790 0.057937 +v 0.069740 -0.095456 0.056336 +v -0.034149 -0.097682 0.008335 +v 0.009803 -0.102883 -0.019262 +v 0.009234 -0.091767 -0.064020 +v 0.007733 -0.094300 -0.057603 +v 0.038402 -0.093605 -0.060751 +v 0.042786 -0.094699 -0.058098 +v 0.148804 -0.092009 -0.056386 +v 0.154435 -0.091459 -0.054314 +v 0.177886 -0.092878 0.001107 +v -0.019648 -0.100216 0.006306 +v -0.022677 -0.099599 0.004094 +v -0.017215 -0.100677 0.003135 +v 0.010750 -0.086250 -0.066000 +v 0.122783 -0.088719 -0.065955 +v 0.131373 -0.066250 -0.065433 +v 0.010750 -0.066250 -0.066000 +v -0.055711 -0.066250 0.036165 +v -0.036231 -0.066250 0.055716 +v -0.011721 -0.066250 0.065343 +v 0.183730 -0.066250 -0.018630 +v 0.184869 -0.089500 -0.011053 +v 0.182660 -0.088681 -0.020911 +v 0.175836 -0.088938 -0.035145 +v 0.173343 -0.066250 -0.039220 +v 0.165297 -0.089606 -0.047798 +v 0.156239 -0.066250 -0.055711 +v 0.150956 -0.088947 -0.058342 +v 0.135936 -0.088971 -0.064082 +v 0.061346 -0.066260 0.066000 +v -0.062467 -0.066464 0.021196 +v -0.004457 -0.074748 -0.004953 +v -0.009738 -0.074750 -0.034314 +v -0.009114 -0.076250 -0.033965 +v -0.021897 -0.076250 -0.030060 +v -0.021291 -0.074750 -0.030008 +v -0.025925 -0.074750 -0.020830 +v -0.025810 -0.076250 -0.015160 +v -0.023576 -0.074750 -0.010820 +v 0.003848 -0.099692 -0.016755 +v 0.002195 -0.100272 -0.011698 +v 0.004368 -0.100581 -0.019809 +v 0.004119 -0.074748 -0.017765 +v -0.002645 -0.100210 -0.006269 +v 0.061341 -0.086250 0.066000 +v 0.137857 -0.076250 0.032348 +v 0.145518 -0.075700 0.023527 +v 0.138550 -0.076147 0.052950 +v 0.175211 -0.076169 0.006855 +v 0.144917 -0.075400 0.013390 +v 0.139693 -0.075959 0.006893 +v 0.166341 -0.076125 0.030850 +v 0.082014 -0.076284 0.054924 +v 0.116741 -0.077162 0.014039 +v 0.116128 -0.075249 0.022497 +v 0.125433 -0.076250 0.033440 +v 0.118355 -0.074749 0.010957 +v 0.126141 -0.074750 0.033694 +v 0.140529 -0.074750 0.030951 +v 0.128314 -0.074749 0.004124 +v 0.133100 -0.079159 0.004408 +v 0.080855 -0.070822 0.063803 +v 0.069355 -0.070486 0.064103 +v 0.077247 -0.073704 0.060599 +v 0.116932 -0.073470 0.061245 +v 0.121973 -0.071583 0.063250 +v 0.062738 -0.066375 0.066005 +v 0.131534 -0.066265 0.065414 +v 0.082325 -0.074321 0.059721 +v 0.121000 -0.075032 0.058404 +v 0.079262 -0.075006 0.058368 +v 0.152706 -0.070763 0.055054 +v 0.159300 -0.070866 0.050044 +v 0.164419 -0.066526 0.049183 +v 0.178769 -0.073438 0.017660 +v 0.181904 -0.071125 0.014157 +v 0.180429 -0.069757 0.023017 +v 0.178496 -0.074322 0.012171 +v 0.176483 -0.075241 0.014551 +v 0.184207 -0.070718 0.001194 +v 0.185929 -0.066651 -0.000959 +v 0.184833 -0.066255 0.013468 +v 0.176111 -0.066257 0.035601 +v 0.171824 -0.070339 0.038024 +v 0.148982 -0.066329 0.059603 +v 0.136191 -0.071272 0.061449 +v 0.159971 -0.073068 0.046898 +v 0.170145 -0.073614 0.035364 +v 0.155762 -0.073069 0.050193 +v 0.139567 -0.074380 0.056814 +v 0.181249 -0.073395 0.004070 +v 0.155899 -0.075162 0.045706 +v 0.178681 -0.076464 0.003853 +v 0.173999 -0.077975 0.004687 +v 0.081917 -0.078626 0.051837 +v 0.073446 -0.074596 0.061288 +v 0.122380 -0.068250 0.059619 +v 0.120476 -0.068250 0.063895 +v 0.117573 -0.068250 0.059168 +v 0.155123 -0.068250 0.049710 +v 0.160558 -0.068250 0.048759 +v 0.156623 -0.068250 0.045485 +v 0.181406 -0.068250 0.013203 +v 0.180451 -0.068250 0.017423 +v 0.178223 -0.068250 0.012300 +v 0.176488 -0.068250 0.015179 +v 0.077262 -0.068250 0.059894 +v 0.079542 -0.068250 0.063606 +v 0.082543 -0.068250 0.061997 +v 0.081322 -0.068250 0.058707 +v 0.185963 -0.086250 -0.002195 +v 0.185941 -0.086250 -0.001716 +v 0.185842 -0.086250 -0.001246 +v 0.185670 -0.086250 -0.000799 +v 0.185429 -0.086250 -0.000384 +v 0.185124 -0.086250 -0.000013 +v 0.184765 -0.086250 0.000305 +v 0.061591 -0.086250 0.065990 +v 0.180297 -0.086250 0.002831 +v 0.182612 -0.086250 0.001712 +v 0.177858 -0.086250 0.003644 +v 0.175334 -0.086250 0.004137 +v 0.172768 -0.086250 0.004303 +v 0.131000 -0.086250 0.004303 +v 0.120372 -0.086250 0.008824 +v 0.122058 -0.086250 0.007322 +v 0.123954 -0.086250 0.006095 +v 0.126014 -0.086250 0.005171 +v 0.128192 -0.086250 0.004572 +v 0.130435 -0.086250 0.004313 +v 0.120039 -0.086250 0.009183 +v 0.074785 -0.086250 0.059442 +v 0.072990 -0.086250 0.061200 +v 0.070989 -0.086250 0.062719 +v 0.068813 -0.086250 0.063975 +v 0.064076 -0.086250 0.065623 +v 0.066496 -0.086250 0.064948 +v 0.185945 -0.086250 -0.002697 +v 0.185945 -0.066250 -0.002697 +v 0.061936 -0.086250 0.052394 +v 0.158285 -0.086250 -0.001649 +v 0.151777 -0.086250 0.002696 +v 0.109062 -0.086250 0.003609 +v 0.158208 -0.066250 -0.001495 +v 0.058683 -0.066253 0.052568 +v 0.109255 -0.066250 0.003522 +v 0.152261 -0.066250 0.002571 +v 0.066974 -0.066250 0.049338 +v -0.036171 -0.068250 -0.050390 +v -0.031757 -0.068250 -0.053792 +v -0.031462 -0.068250 -0.049052 +v -0.053555 -0.068250 -0.022743 +v -0.058688 -0.068250 -0.024897 +v -0.054753 -0.068250 -0.027373 +v -0.057299 -0.068250 0.009994 +v -0.062793 -0.068250 0.011140 +v -0.060700 -0.068250 0.006836 +v -0.061991 -0.086250 0.022652 +v -0.061991 -0.066250 0.022652 +v -0.001919 -0.086250 -0.007429 +v -0.000390 -0.086250 -0.008806 +v 0.011069 -0.086250 -0.008360 +v 0.003750 -0.086250 -0.019053 +v 0.003714 -0.086250 -0.018024 +v -0.005955 -0.086250 -0.005192 +v -0.005475 -0.086250 -0.005377 +v -0.003625 -0.086250 -0.006279 +v 0.000933 -0.086250 -0.010383 +v 0.002023 -0.086250 -0.012128 +v 0.002860 -0.086250 -0.014008 +v 0.003428 -0.086250 -0.015986 +v -0.051928 -0.086250 0.011541 +v -0.053912 -0.086250 0.012387 +v -0.055794 -0.086250 0.013442 +v -0.057552 -0.086250 0.014693 +v -0.059164 -0.086250 0.016127 +v -0.034648 -0.086250 0.009852 +v 0.017080 -0.086250 -0.053387 +v 0.012836 -0.086250 -0.047389 +v -0.040720 -0.086250 0.016308 +v 0.016246 -0.066250 -0.053132 +v -0.040625 -0.066250 0.016718 +v 0.010892 -0.066250 -0.008120 +v -0.036475 -0.066250 0.010861 +v 0.012514 -0.066250 -0.045333 +v 0.185740 -0.088920 -0.000985 +v 0.181925 -0.088939 0.002055 +v -0.055421 -0.089709 0.013033 +v -0.052033 -0.092654 0.013095 +v -0.055367 -0.091858 0.014532 +v -0.020413 -0.098202 0.000922 +v 0.041754 -0.091174 -0.064986 +v 0.004583 -0.092695 -0.055740 +v 0.150243 -0.070250 -0.049452 +v 0.147499 -0.070250 -0.054870 +v 0.154200 -0.070250 -0.053418 +v 0.151824 -0.070250 -0.056516 +v -0.029778 -0.070250 0.056737 +v -0.034504 -0.070250 0.053095 +v -0.027356 -0.070250 0.052708 +v -0.030080 -0.070250 0.049863 +v 0.045524 -0.070250 -0.061255 +v 0.041597 -0.070250 -0.057897 +v 0.038479 -0.070250 -0.062680 +v 0.043155 -0.070250 -0.064732 +v 0.041434 -0.070250 0.065024 +v 0.038522 -0.070250 0.061516 +v 0.045525 -0.070250 0.061985 +v 0.042081 -0.070250 0.057782 +v 0.106911 -0.088250 0.017938 +v 0.102233 -0.088250 0.020649 +v 0.106843 -0.088250 0.022695 +v 0.139733 -0.088250 -0.001976 +v 0.137349 -0.088250 0.000877 +v 0.140397 -0.088250 0.003695 +v 0.142601 -0.088250 0.000295 +v 0.176747 -0.088250 -0.001676 +v 0.175761 -0.088250 0.003621 +v 0.172238 -0.088250 0.000491 +v 0.067814 -0.088250 0.060254 +v 0.072204 -0.088250 0.061139 +v 0.072579 -0.088250 0.057282 +v 0.069359 -0.088250 0.056638 +v 0.008216 -0.088250 -0.017138 +v 0.004524 -0.088250 -0.019939 +v 0.008514 -0.088250 -0.022715 +v -0.019199 -0.088250 0.006351 +v -0.022745 -0.088250 0.003828 +v -0.017365 -0.088250 0.003056 +v -0.020015 -0.088250 0.000904 +v -0.050373 -0.088250 0.014670 +v -0.054977 -0.088250 0.017331 +v -0.054098 -0.088250 0.012987 +v -0.051340 -0.088250 0.017827 +v 0.008545 -0.088250 -0.057450 +v 0.009295 -0.088250 -0.052871 +v 0.004194 -0.088250 -0.054953 +v 0.063411 -0.086250 0.052393 +v 0.018312 -0.086250 -0.053261 +v -0.034647 -0.086250 0.010631 +v 0.012535 -0.086250 -0.008337 +v 0.014302 -0.086250 -0.047366 +v -0.039173 -0.086250 0.016659 +v 0.159750 -0.086250 -0.001625 +v 0.153242 -0.086250 0.002719 +v 0.110527 -0.086250 0.003632 +v 0.017902 -0.066250 -0.053242 +v 0.159673 -0.066250 -0.001472 +v -0.039250 -0.066250 0.016445 +v 0.060126 -0.066248 0.052587 +v 0.013980 -0.066250 -0.045310 +v 0.012357 -0.066250 -0.008097 +v 0.153726 -0.066250 0.002594 +v 0.068439 -0.066250 0.049361 +v 0.110720 -0.066250 0.003545 +v -0.033517 -0.066250 0.010062 +v -0.060606 -0.065730 0.004181 +v -0.065400 -0.065742 0.001951 +v -0.062715 -0.065575 0.000880 +v -0.060130 -0.065634 0.000612 +v -0.057055 -0.065742 -0.000047 +v -0.061655 -0.065675 -0.001492 +v -0.060307 -0.065774 -0.004041 +v -0.064471 -0.065751 -0.003020 +v -0.062407 -0.025972 -0.001838 +v -0.062582 -0.025858 0.001800 +v -0.059354 -0.026072 -0.000108 +v -0.063882 -0.063545 0.000405 +v -0.060123 -0.063539 -0.001946 +v -0.060277 -0.063562 0.001828 +v -0.014778 -0.065747 -0.059253 +v -0.016376 -0.065776 -0.055258 +v -0.017537 -0.065575 -0.058181 +v -0.020006 -0.065684 -0.057373 +v -0.023507 -0.065726 -0.058743 +v -0.019471 -0.065622 -0.059916 +v -0.019964 -0.065735 -0.054380 +v -0.018758 -0.065746 -0.062845 +v -0.020751 -0.025936 -0.057694 +v -0.018502 -0.026129 -0.056456 +v -0.017250 -0.025981 -0.059684 +v -0.020333 -0.026044 -0.059932 +v -0.017667 -0.063562 -0.056743 +v -0.021290 -0.063539 -0.057812 +v -0.017852 -0.063545 -0.060613 +v -0.018354 -0.065730 0.054264 +v -0.015212 -0.065756 0.056831 +v -0.017934 -0.065575 0.057522 +v -0.018702 -0.065675 0.059901 +v -0.015551 -0.065768 0.061102 +v -0.019964 -0.065735 0.062600 +v -0.022597 -0.065771 0.056185 +v -0.020378 -0.065634 0.058047 +v -0.022797 -0.065756 0.060149 +v -0.020862 -0.025922 0.058576 +v -0.017079 -0.026000 0.058008 +v -0.019315 -0.026101 0.056426 +v -0.019229 -0.026058 0.060664 +v -0.021323 -0.063523 0.057669 +v -0.016783 -0.063551 0.057652 +v -0.018768 -0.063563 0.060639 +v 0.140079 -0.065618 0.059454 +v 0.141102 -0.065756 0.054540 +v 0.143017 -0.065725 0.060139 +v 0.139410 -0.065756 0.062610 +v 0.135585 -0.065747 0.061089 +v 0.137930 -0.065634 0.057526 +v 0.135475 -0.065752 0.056040 +v 0.137357 -0.025970 0.057054 +v 0.138172 -0.025991 0.060294 +v 0.141117 -0.025886 0.058391 +v 0.137040 -0.063555 0.059743 +v 0.137739 -0.063565 0.056852 +v 0.140562 -0.063558 0.056818 +v 0.140459 -0.063563 0.060089 +v 0.181869 -0.065545 -0.001425 +v 0.185745 -0.065735 0.001276 +v 0.181177 -0.065675 0.001236 +v 0.177936 -0.065751 0.002289 +v 0.178296 -0.065739 -0.003065 +v 0.181586 -0.065754 0.004183 +v 0.183636 -0.065751 -0.003658 +v 0.180233 -0.026122 -0.001753 +v 0.180046 -0.025995 0.001294 +v 0.182700 -0.025970 0.001616 +v 0.183055 -0.026007 -0.001184 +v 0.180511 -0.063563 0.001922 +v 0.179726 -0.063551 -0.001578 +v 0.183959 -0.063523 0.000064 +v 0.137999 -0.065622 -0.059603 +v 0.135151 -0.065749 -0.059998 +v 0.137928 -0.065756 -0.062588 +v 0.143234 -0.065751 -0.058247 +v 0.140420 -0.065752 -0.054434 +v 0.140471 -0.065587 -0.058805 +v 0.138544 -0.065675 -0.057062 +v 0.135585 -0.065747 -0.055891 +v 0.141630 -0.065749 -0.061689 +v 0.140954 -0.025920 -0.059132 +v 0.136996 -0.025947 -0.058447 +v 0.139257 -0.026052 -0.056517 +v 0.140295 -0.063561 -0.056658 +v 0.137562 -0.063569 -0.056981 +v 0.137211 -0.063549 -0.059925 +v 0.138352 -0.026349 -0.060536 +v 0.140690 -0.063562 -0.059903 +v -0.042808 0.026348 -0.017732 +v -0.016044 0.026348 -0.043108 +v -0.019137 -0.027731 -0.041827 +v -0.042235 -0.027731 -0.017494 +v 0.019137 0.026348 -0.041827 +v 0.008829 -0.027731 -0.044389 +v 0.031320 -0.027731 -0.033686 +v 0.043108 0.026348 -0.016044 +v 0.045966 -0.027731 -0.001673 +v 0.044389 0.026348 0.008829 +v 0.031320 0.026348 0.033686 +v 0.033686 -0.027731 0.031320 +v 0.008829 0.026348 0.044389 +v 0.001673 -0.027731 0.045966 +v -0.019137 0.026348 0.041827 +v -0.031320 -0.027731 0.033686 +v -0.042235 0.026348 0.017494 +v -0.044389 -0.027731 0.008829 +v 0.075611 0.026348 -0.008829 +v 0.088680 0.026348 -0.033686 +v 0.077765 -0.027731 -0.017494 +v 0.100863 -0.027731 -0.041827 +v 0.121674 0.026348 -0.045966 +v 0.136045 -0.027731 -0.043108 +v 0.145144 0.026348 -0.037631 +v 0.163108 0.026348 -0.016045 +v 0.161827 -0.027731 -0.019137 +v 0.164389 0.026348 0.008829 +v 0.163108 -0.027731 0.016044 +v 0.151320 0.026348 0.033686 +v 0.139137 -0.027731 0.041827 +v 0.118327 0.026348 0.045966 +v 0.111171 -0.027731 0.044389 +v 0.094856 0.026348 0.037631 +v 0.088680 -0.027731 0.033686 +v 0.077765 0.026348 0.017494 +v 0.075611 -0.027731 0.008829 +v 0.145509 -0.097494 0.063490 +v 0.120459 -0.097134 0.068046 +v 0.124388 -0.097184 0.067418 +v 0.104887 -0.097134 0.069884 +v 0.096885 -0.097134 0.070469 +v 0.080609 -0.097134 0.071658 +v 0.072304 -0.097111 0.071965 +v 0.069074 -0.096663 0.072079 +v 0.066356 -0.095775 0.072200 +v 0.064003 -0.094478 0.072335 +v 0.060116 -0.088857 0.072797 +v 0.060815 -0.090946 0.072635 +v 0.062179 -0.092898 0.072475 +v 0.056485 -0.069124 0.074058 +v 0.056484 -0.069126 0.074093 +v 0.051572 -0.065082 0.074227 +v 0.051572 -0.065083 0.074248 +v -0.032244 -0.065083 0.064805 +v -0.040827 -0.065091 0.062012 +v -0.048641 -0.065094 0.057404 +v -0.055279 -0.065093 0.051195 +v -0.062745 -0.065083 0.038467 +v -0.060396 -0.065088 0.043711 +v -0.063557 -0.065083 0.036180 +v -0.064826 -0.068785 0.031509 +v -0.064834 -0.068786 0.031511 +v -0.064784 -0.092177 0.025544 +v -0.064730 -0.093532 0.024779 +v -0.064685 -0.094660 0.024141 +v -0.064372 -0.096779 0.022208 +v -0.064256 -0.097353 0.021352 +v -0.064059 -0.098326 0.019900 +v -0.064030 -0.099902 0.013892 +v -0.063902 -0.099368 0.017149 +v -0.065100 -0.099929 0.002424 +v -0.065033 -0.099933 -0.002799 +v -0.065016 -0.099934 -0.004068 +v -0.062671 -0.099991 -0.020942 +v -0.057991 -0.100071 -0.035731 +v -0.052221 -0.100095 -0.045787 +v -0.055220 -0.100094 -0.041299 +v -0.048728 -0.100077 -0.049868 +v -0.040561 -0.099994 -0.056499 +v -0.044830 -0.100043 -0.053448 +v -0.031431 -0.099861 -0.060741 +v -0.036050 -0.099932 -0.058940 +v -0.023523 -0.099709 -0.063032 +v 0.006317 -0.097685 -0.068866 +v 0.003637 -0.098836 -0.068370 +v 0.000771 -0.099353 -0.067857 +v 0.008237 -0.096493 -0.069195 +v 0.009872 -0.094931 -0.069512 +v 0.011751 -0.090861 -0.070048 +v 0.011083 -0.093041 -0.069801 +v 0.015328 -0.069183 -0.071858 +v 0.015481 -0.069103 -0.070309 +v 0.015325 -0.069185 -0.071887 +v 0.020205 -0.065082 -0.072556 +v 0.067722 -0.065083 -0.074261 +v 0.152244 -0.065083 -0.064805 +v 0.160827 -0.065091 -0.062012 +v 0.168641 -0.065094 -0.057404 +v 0.175279 -0.065093 -0.051195 +v 0.182745 -0.065083 -0.038467 +v 0.180396 -0.065088 -0.043711 +v 0.188977 -0.065083 -0.011634 +v 0.187788 -0.065083 -0.019949 +v 0.188018 -0.088857 -0.002896 +v 0.189156 -0.069081 -0.006726 +v 0.189164 -0.069081 -0.006727 +v 0.187882 -0.090802 -0.002246 +v 0.187718 -0.093111 -0.000597 +v 0.186821 -0.096597 0.003993 +v 0.187356 -0.095127 0.001527 +v 0.186557 -0.097043 0.005342 +v 0.186357 -0.097381 0.006362 +v 0.185956 -0.097701 0.009315 +v 0.182239 -0.097770 0.028558 +v 0.160682 -0.097736 0.058138 +v 0.178454 -0.097830 0.038885 +v 0.175840 -0.097842 0.043646 +v 0.172757 -0.097838 0.047926 +v 0.169116 -0.097818 0.051866 +v 0.165098 -0.097784 0.055261 +v 0.156032 -0.097676 0.060397 +v 0.178360 -0.104484 -0.011156 +v 0.077166 -0.117738 -0.043103 +v 0.115291 -0.112196 -0.050148 +v 0.121479 -0.111859 -0.048487 +v 0.142353 -0.112717 -0.030512 +v 0.146838 -0.109847 -0.038587 +v 0.142839 -0.115204 -0.021214 +v 0.147181 -0.111993 -0.028523 +v 0.144213 -0.114905 -0.020776 +v 0.177798 -0.104545 -0.013419 +v 0.177952 -0.104501 -0.013215 +v 0.124204 -0.108964 0.057666 +v 0.125690 -0.110774 0.050488 +v 0.137916 -0.107425 0.055530 +v 0.066719 -0.111712 0.062187 +v 0.123881 -0.111714 0.047775 +v 0.115006 -0.112211 0.050219 +v 0.172896 -0.103691 0.034190 +v 0.171547 -0.103544 0.037379 +v 0.163430 -0.103811 0.047389 +v 0.155144 -0.104798 0.051995 +v -0.059439 -0.104467 0.004070 +v 0.002277 -0.115505 0.037832 +v 0.004709 -0.112196 0.050148 +v 0.000429 -0.119291 0.026603 +v -0.003439 -0.114972 0.036489 +v -0.001479 -0.111859 0.048487 +v -0.030948 -0.105468 -0.053150 +v -0.004204 -0.108964 -0.057666 +v -0.005690 -0.110774 -0.050488 +v 0.053281 -0.111712 -0.062187 +v -0.003881 -0.111714 -0.047775 +v 0.004994 -0.112211 -0.050219 +v -0.056682 -0.104307 -0.020676 +v -0.054868 -0.104018 -0.028022 +v -0.048292 -0.103511 -0.042522 +v -0.043430 -0.103811 -0.047389 +v -0.038292 -0.104367 -0.050653 +v 0.154385 -0.108249 -0.038164 +v 0.171241 -0.103526 -0.037980 +v 0.175182 -0.104069 -0.026902 +v 0.153740 -0.105545 -0.050488 +v 0.103301 -0.110550 -0.060151 +v 0.131035 -0.108255 -0.056651 +v 0.157459 -0.104475 -0.051051 +v 0.154270 -0.104929 -0.052292 +v 0.162731 -0.103875 -0.047925 +v -0.056919 -0.104343 0.019507 +v -0.051241 -0.103526 0.037980 +v 0.016699 -0.110550 0.060151 +v -0.011035 -0.108255 0.056651 +v -0.034270 -0.104929 0.052292 +v -0.042731 -0.103875 0.047925 +v -0.047345 -0.103546 0.043662 +v -0.024547 -0.114832 -0.020668 +v -0.024225 -0.114945 -0.020671 +v -0.042899 -0.110650 -0.010950 +v -0.043088 -0.111147 -0.005806 +v -0.059472 -0.104511 -0.002800 +v -0.024560 -0.116041 -0.015932 +v -0.005892 -0.119905 -0.020671 +v -0.022057 -0.115367 -0.021448 +v 0.011730 -0.120764 -0.028274 +v 0.006159 -0.120077 -0.027514 +v 0.125892 -0.119905 -0.020671 +v 0.179472 -0.104511 0.002800 +v 0.179439 -0.104467 0.004070 +v 0.175759 -0.105923 0.006554 +v 0.069416 -0.124986 0.027668 +v -0.024987 -0.117433 0.004619 +v -0.025024 -0.117555 -0.000586 +v -0.024965 -0.117361 -0.005806 +v 0.144987 -0.117433 0.004619 +v 0.144965 -0.117361 -0.005806 +v -0.006213 -0.121267 0.014643 +v -0.006488 -0.122438 0.004619 +v 0.126213 -0.121267 0.014643 +v 0.126488 -0.122438 0.004619 +v 0.126471 -0.122364 -0.005806 +v 0.126155 -0.121020 -0.015932 +v 0.012668 -0.124004 0.019311 +v 0.012498 -0.125024 0.014643 +v 0.012300 -0.126210 0.004619 +v 0.012312 -0.126136 -0.005806 +v 0.012539 -0.124774 -0.015932 +v 0.107502 -0.125024 0.014643 +v 0.107700 -0.126210 0.004619 +v 0.107688 -0.126136 -0.005806 +v 0.031518 -0.126509 0.019311 +v 0.031645 -0.125233 0.023668 +v 0.050458 -0.128797 0.014643 +v 0.050418 -0.130000 0.004619 +v 0.050421 -0.129924 -0.005806 +v 0.050466 -0.128545 -0.015932 +v 0.050551 -0.125986 -0.025097 +v 0.069466 -0.126483 0.023668 +v 0.069508 -0.127764 0.019311 +v 0.069582 -0.130000 0.004619 +v 0.069579 -0.129924 -0.005806 +v 0.069562 -0.129393 -0.010950 +v 0.069534 -0.128545 -0.015932 +v 0.088482 -0.126509 0.019311 +v 0.088584 -0.127538 0.014643 +v 0.088703 -0.128735 0.004619 +v 0.088696 -0.128660 -0.005806 +v 0.088643 -0.128131 -0.010950 +v 0.088559 -0.127286 -0.015932 +v -0.050678 -0.071331 0.055258 +v -0.057698 -0.071243 0.047429 +v -0.062534 -0.070983 0.038095 +v -0.056817 -0.091591 0.045973 +v -0.056856 -0.091590 0.045921 +v -0.059315 -0.091589 0.041783 +v -0.060892 -0.091637 0.038357 +v -0.047453 -0.091978 0.055777 +v -0.051134 -0.091778 0.052673 +v -0.053906 -0.091664 0.049770 +v -0.043401 -0.092247 0.058447 +v -0.030771 -0.093352 0.063188 +v -0.035499 -0.092896 0.061960 +v -0.040020 -0.092506 0.060196 +v 0.066755 -0.099534 0.071874 +v 0.053369 -0.065417 0.074261 +v 0.054813 -0.066273 0.074234 +v 0.055892 -0.067557 0.074175 +v 0.016517 -0.098361 0.069917 +v 0.112678 -0.097760 0.068980 +v 0.104872 -0.098233 0.069727 +v 0.097585 -0.098676 0.070425 +v -0.064705 -0.067272 0.032235 +v -0.064474 -0.066174 0.033193 +v -0.064431 -0.066088 0.033343 +v -0.064068 -0.065363 0.034606 +v -0.064736 -0.067422 0.032104 +v 0.060000 -0.099562 -0.071923 +v 0.016938 -0.066312 -0.072204 +v 0.018360 -0.065438 -0.072384 +v 0.019994 -0.065088 -0.072551 +v 0.015887 -0.067609 -0.072031 +v 0.150771 -0.093352 -0.063188 +v 0.103483 -0.098361 -0.069917 +v 0.053245 -0.099534 -0.071874 +v 0.170678 -0.071331 -0.055258 +v 0.176817 -0.091591 -0.045973 +v 0.176856 -0.091590 -0.045921 +v 0.182534 -0.070983 -0.038095 +v 0.179315 -0.091589 -0.041783 +v 0.180892 -0.091637 -0.038357 +v 0.167453 -0.091978 -0.055777 +v 0.171134 -0.091778 -0.052673 +v 0.177698 -0.071243 -0.047429 +v 0.173906 -0.091664 -0.049770 +v 0.163401 -0.092247 -0.058447 +v 0.155499 -0.092896 -0.061960 +v 0.160020 -0.092506 -0.060196 +v 0.187134 -0.092540 -0.011778 +v 0.189202 -0.066174 -0.008518 +v 0.189214 -0.067422 -0.007398 +v 0.189123 -0.065363 -0.009986 +v 0.189195 -0.066099 -0.008654 +v 0.185795 -0.092331 -0.020805 +v 0.183992 -0.092055 -0.028691 +v 0.163415 -0.108928 0.019883 +v 0.155558 -0.110552 0.024488 +v 0.125706 -0.114743 0.035903 +v 0.117440 -0.115530 0.037894 +v 0.053204 -0.117915 -0.043493 +v 0.020616 -0.116833 -0.041035 +v 0.138369 -0.104794 0.060363 +v 0.138384 -0.100519 0.063858 +v 0.066777 -0.104779 0.070355 +v 0.066764 -0.109052 0.066956 +v 0.097663 -0.108209 0.065465 +v 0.097723 -0.103931 0.068886 +v 0.151312 -0.098481 0.061371 +v -0.031360 -0.098591 0.061523 +v 0.016349 -0.103620 0.068371 +v 0.016413 -0.107899 0.064942 +v 0.175926 -0.100406 0.039398 +v 0.172056 -0.100393 0.045521 +v 0.166297 -0.100721 0.051349 +v 0.160199 -0.101309 0.055307 +v 0.156453 -0.101762 0.056966 +v 0.153605 -0.102149 0.057902 +v 0.177113 -0.100976 0.035483 +v -0.035765 -0.098060 0.060303 +v -0.060205 -0.096733 0.036291 +v -0.057161 -0.100931 0.035496 +v -0.059520 -0.096674 0.038062 +v -0.055201 -0.100772 0.039937 +v -0.058020 -0.096603 0.041265 +v -0.055699 -0.096591 0.045137 +v -0.052929 -0.096664 0.048744 +v -0.050638 -0.100813 0.046611 +v -0.046899 -0.097010 0.054396 +v -0.041880 -0.101489 0.053907 +v -0.045248 -0.101168 0.051652 +v -0.043122 -0.097316 0.056927 +v -0.035334 -0.102280 0.056912 +v 0.179147 -0.101302 0.029082 +v -0.062598 -0.097108 0.028555 +v -0.061307 -0.101580 0.020252 +v 0.183754 -0.101250 0.006295 +v 0.183863 -0.101190 0.004081 +v 0.186407 -0.097580 0.004019 +v -0.062580 -0.102514 0.004093 +v 0.183575 -0.101690 0.002814 +v 0.186407 -0.097580 -0.004019 +v 0.183540 -0.101648 -0.004089 +v -0.062614 -0.102557 -0.002816 +v 0.185774 -0.097536 -0.011762 +v 0.182367 -0.101736 -0.013719 +v 0.180205 -0.096733 -0.036291 +v 0.181307 -0.101580 -0.020252 +v 0.184409 -0.097382 -0.020706 +v 0.182598 -0.097108 -0.028555 +v 0.177161 -0.100931 -0.035496 +v -0.058138 -0.102156 -0.028843 +v -0.059994 -0.102444 -0.021281 +v -0.056668 -0.101378 -0.035353 +v 0.155765 -0.098060 -0.060303 +v 0.179520 -0.096674 -0.038062 +v 0.175201 -0.100772 -0.039937 +v 0.178020 -0.096604 -0.041265 +v 0.175699 -0.096591 -0.045137 +v 0.172929 -0.096664 -0.048744 +v 0.170638 -0.100813 -0.046611 +v 0.166899 -0.097010 -0.054396 +v 0.161880 -0.101489 -0.053907 +v 0.165248 -0.101168 -0.051652 +v 0.163122 -0.097316 -0.056926 +v 0.155334 -0.102280 -0.056912 +v 0.151360 -0.098591 -0.061523 +v -0.033482 -0.102971 -0.056913 +v -0.051348 -0.101216 -0.044952 +v -0.045768 -0.101542 -0.050591 +v -0.043308 -0.101762 -0.052394 +v -0.039863 -0.102129 -0.054414 +v -0.031423 -0.102849 -0.057996 +v 0.103651 -0.103620 -0.068371 +v 0.103587 -0.107899 -0.064942 +v 0.007104 -0.103023 -0.067419 +v -0.004658 -0.102042 -0.065946 +v 0.053236 -0.109052 -0.066956 +v 0.053223 -0.104779 -0.070355 +v -0.004603 -0.106323 -0.062482 +v 0.015522 -0.068895 -0.070325 +v 0.015584 -0.068741 -0.070340 +v 0.189160 -0.067065 -0.007724 +v 0.053792 -0.065600 0.074219 +v 0.055551 -0.067047 0.074159 +v 0.018020 -0.065670 -0.072282 +v 0.016232 -0.067079 -0.072058 +v -0.064793 -0.067990 0.031799 +v -0.064574 -0.066913 0.032537 +v 0.144829 -0.097503 0.062983 +v 0.119984 -0.097146 0.067502 +v 0.123881 -0.097195 0.066879 +v 0.104540 -0.097146 0.069325 +v 0.096604 -0.097146 0.069905 +v 0.080461 -0.097146 0.071085 +v 0.072224 -0.097123 0.071388 +v 0.069021 -0.096679 0.071502 +v 0.066325 -0.095798 0.071622 +v 0.063992 -0.094512 0.071755 +v 0.060136 -0.088937 0.072214 +v 0.060829 -0.091009 0.072053 +v 0.062182 -0.092944 0.071895 +v 0.056535 -0.069366 0.073464 +v 0.056534 -0.069368 0.073499 +v 0.051662 -0.065357 0.073633 +v 0.051662 -0.065358 0.073653 +v -0.031467 -0.065358 0.064288 +v -0.039979 -0.065365 0.061518 +v -0.047729 -0.065369 0.056947 +v -0.054313 -0.065368 0.050789 +v -0.061718 -0.065358 0.038166 +v -0.059388 -0.065363 0.043366 +v -0.062523 -0.065358 0.035897 +v -0.063782 -0.069030 0.031264 +v -0.063790 -0.069030 0.031266 +v -0.063740 -0.092230 0.025349 +v -0.063686 -0.093573 0.024589 +v -0.063641 -0.094692 0.023957 +v -0.063332 -0.096794 0.022040 +v -0.063216 -0.097363 0.021191 +v -0.063021 -0.098328 0.019751 +v -0.062993 -0.099892 0.013792 +v -0.062865 -0.099362 0.017022 +v -0.064054 -0.099918 0.002418 +v -0.063987 -0.099922 -0.002763 +v -0.063970 -0.099923 -0.004021 +v -0.061645 -0.099980 -0.020756 +v -0.057002 -0.100059 -0.035424 +v -0.051280 -0.100082 -0.045398 +v -0.054255 -0.100082 -0.040947 +v -0.047815 -0.100065 -0.049446 +v -0.039715 -0.099982 -0.056022 +v -0.043949 -0.100031 -0.052996 +v -0.030660 -0.099851 -0.060229 +v -0.035242 -0.099921 -0.058443 +v -0.022817 -0.099700 -0.062502 +v 0.006778 -0.097693 -0.068288 +v 0.004120 -0.098834 -0.067796 +v 0.001277 -0.099346 -0.067287 +v 0.008683 -0.096510 -0.068614 +v 0.010304 -0.094961 -0.068928 +v 0.012168 -0.090924 -0.069460 +v 0.011505 -0.093086 -0.069215 +v 0.015715 -0.069424 -0.071256 +v 0.015712 -0.069426 -0.071284 +v 0.020553 -0.065357 -0.071947 +v 0.067679 -0.065358 -0.073638 +v 0.151509 -0.065358 -0.064260 +v 0.160022 -0.065365 -0.061490 +v 0.167771 -0.065369 -0.056920 +v 0.174355 -0.065368 -0.050762 +v 0.181760 -0.065358 -0.038139 +v 0.179430 -0.065363 -0.043339 +v 0.187941 -0.065358 -0.011525 +v 0.186761 -0.065358 -0.019772 +v 0.186989 -0.088937 -0.002859 +v 0.188119 -0.069323 -0.006658 +v 0.188127 -0.069323 -0.006658 +v 0.186855 -0.090866 -0.002214 +v 0.186692 -0.093156 -0.000578 +v 0.185803 -0.096613 0.003974 +v 0.186333 -0.095156 0.001528 +v 0.185540 -0.097056 0.005312 +v 0.185342 -0.097391 0.006323 +v 0.184945 -0.097709 0.009252 +v 0.181258 -0.097777 0.028337 +v 0.159878 -0.097743 0.057675 +v 0.177504 -0.097837 0.038580 +v 0.174912 -0.097848 0.043301 +v 0.171854 -0.097845 0.047547 +v 0.168243 -0.097825 0.051454 +v 0.164257 -0.097791 0.054822 +v 0.155265 -0.097684 0.059916 +v 0.177410 -0.104436 -0.011051 +v 0.077046 -0.117581 -0.042736 +v 0.114859 -0.112085 -0.049723 +v 0.120996 -0.111750 -0.048076 +v 0.141699 -0.112601 -0.030249 +v 0.146147 -0.109755 -0.038257 +v 0.142181 -0.115068 -0.021027 +v 0.146487 -0.111884 -0.028276 +v 0.143544 -0.114772 -0.020592 +v 0.176853 -0.104496 -0.013295 +v 0.177006 -0.104452 -0.013093 +v 0.123698 -0.108879 0.057207 +v 0.125173 -0.110674 0.050088 +v 0.137299 -0.107353 0.055089 +v 0.066685 -0.111604 0.061691 +v 0.123378 -0.111607 0.047397 +v 0.114576 -0.112099 0.049820 +v 0.171992 -0.103650 0.033923 +v 0.170654 -0.103503 0.037087 +v 0.162604 -0.103768 0.047014 +v 0.154385 -0.104747 0.051582 +v -0.058439 -0.104419 0.004050 +v 0.002771 -0.115367 0.037536 +v 0.005184 -0.112085 0.049750 +v 0.000938 -0.119121 0.026399 +v -0.002898 -0.114838 0.036204 +v -0.000954 -0.111750 0.048103 +v -0.030181 -0.105412 -0.052700 +v -0.003656 -0.108879 -0.057180 +v -0.005131 -0.110674 -0.050061 +v 0.053358 -0.111604 -0.061664 +v -0.003336 -0.111607 -0.047370 +v 0.005466 -0.112099 -0.049793 +v -0.055705 -0.104260 -0.020493 +v -0.053905 -0.103974 -0.027779 +v -0.047383 -0.103471 -0.042160 +v -0.042561 -0.103768 -0.046987 +v -0.037465 -0.104319 -0.050224 +v 0.153632 -0.108170 -0.037838 +v 0.170350 -0.103486 -0.037655 +v 0.174259 -0.104024 -0.026668 +v 0.152993 -0.105488 -0.050061 +v 0.102967 -0.110452 -0.059644 +v 0.130474 -0.108176 -0.056173 +v 0.156681 -0.104426 -0.050619 +v 0.153519 -0.104877 -0.051850 +v 0.161910 -0.103831 -0.047519 +v -0.055939 -0.104296 0.019361 +v -0.050308 -0.103486 0.037682 +v 0.017075 -0.110452 0.059671 +v -0.010432 -0.108176 0.056200 +v -0.033476 -0.104877 0.051877 +v -0.041868 -0.103831 0.047546 +v -0.046444 -0.103505 0.043317 +v -0.023833 -0.114699 -0.020485 +v -0.023513 -0.114811 -0.020488 +v -0.042034 -0.110552 -0.010847 +v -0.042222 -0.111044 -0.005744 +v -0.058471 -0.104462 -0.002764 +v -0.023846 -0.115898 -0.015788 +v -0.005331 -0.119731 -0.020488 +v -0.021364 -0.115230 -0.021259 +v 0.012147 -0.120583 -0.028029 +v 0.006621 -0.119901 -0.027275 +v 0.125373 -0.119731 -0.020488 +v 0.178513 -0.104462 0.002791 +v 0.178481 -0.104419 0.004050 +v 0.174831 -0.105863 0.006514 +v 0.069360 -0.124770 0.027455 +v -0.024269 -0.117278 0.004595 +v -0.024306 -0.117399 -0.000568 +v -0.024247 -0.117207 -0.005744 +v 0.144311 -0.117278 0.004595 +v 0.144289 -0.117207 -0.005744 +v -0.005649 -0.121081 0.014537 +v -0.005922 -0.122242 0.004595 +v 0.125691 -0.121081 0.014537 +v 0.125964 -0.122242 0.004595 +v 0.125947 -0.122169 -0.005744 +v 0.125634 -0.120837 -0.015788 +v 0.013077 -0.123796 0.019166 +v 0.012908 -0.124807 0.014537 +v 0.012712 -0.125984 0.004595 +v 0.012724 -0.125910 -0.005744 +v 0.012949 -0.124560 -0.015788 +v 0.107134 -0.124807 0.014537 +v 0.107330 -0.125984 0.004595 +v 0.107318 -0.125910 -0.005744 +v 0.031772 -0.126280 0.019166 +v 0.031898 -0.125015 0.023487 +v 0.050557 -0.128550 0.014537 +v 0.050518 -0.129742 0.004595 +v 0.050520 -0.129668 -0.005744 +v 0.050566 -0.128299 -0.015788 +v 0.050649 -0.125762 -0.024877 +v 0.069409 -0.126254 0.023487 +v 0.069451 -0.127525 0.019166 +v 0.069524 -0.129742 0.004595 +v 0.069522 -0.129668 -0.005744 +v 0.069504 -0.129141 -0.010847 +v 0.069477 -0.128299 -0.015788 +v 0.088270 -0.126280 0.019166 +v 0.088371 -0.127300 0.014537 +v 0.088489 -0.128488 0.004595 +v 0.088482 -0.128413 -0.005744 +v 0.088430 -0.127889 -0.010847 +v 0.088346 -0.127051 -0.015788 +v -0.049750 -0.071555 0.054819 +v -0.056712 -0.071467 0.047054 +v -0.061508 -0.071209 0.037796 +v -0.055838 -0.091649 0.045609 +v -0.055877 -0.091648 0.045558 +v -0.058316 -0.091646 0.041454 +v -0.059880 -0.091694 0.038056 +v -0.046551 -0.092032 0.055333 +v -0.050202 -0.091834 0.052255 +v -0.052951 -0.091720 0.049376 +v -0.042532 -0.092299 0.057982 +v -0.030006 -0.093395 0.062684 +v -0.034695 -0.092942 0.061465 +v -0.039179 -0.092556 0.059716 +v 0.066720 -0.099527 0.071299 +v 0.053444 -0.065688 0.073665 +v 0.054876 -0.066538 0.073639 +v 0.055947 -0.067812 0.073581 +v 0.016894 -0.098363 0.069358 +v 0.112267 -0.097767 0.068428 +v 0.104525 -0.098236 0.069169 +v 0.097298 -0.098675 0.069861 +v -0.063661 -0.067529 0.031985 +v -0.063432 -0.066439 0.032935 +v -0.063390 -0.066354 0.033083 +v -0.063030 -0.065636 0.034336 +v -0.063693 -0.067678 0.031855 +v 0.060021 -0.099554 -0.071319 +v 0.017312 -0.066576 -0.071598 +v 0.018723 -0.065710 -0.071777 +v 0.020343 -0.065362 -0.071943 +v 0.016270 -0.067863 -0.071427 +v 0.150048 -0.093395 -0.062656 +v 0.103148 -0.098363 -0.069331 +v 0.053322 -0.099527 -0.071271 +v 0.169792 -0.071555 -0.054792 +v 0.175880 -0.091649 -0.045582 +v 0.175919 -0.091648 -0.045531 +v 0.181550 -0.071209 -0.037769 +v 0.178358 -0.091646 -0.041427 +v 0.179922 -0.091694 -0.038029 +v 0.166594 -0.092032 -0.055306 +v 0.170244 -0.091834 -0.052227 +v 0.176755 -0.071467 -0.047027 +v 0.172993 -0.091720 -0.049348 +v 0.162575 -0.092299 -0.057955 +v 0.154737 -0.092942 -0.061438 +v 0.159221 -0.092556 -0.059689 +v 0.186113 -0.092589 -0.011668 +v 0.188164 -0.066439 -0.008435 +v 0.188176 -0.067678 -0.007323 +v 0.188085 -0.065636 -0.009890 +v 0.188157 -0.066365 -0.008569 +v 0.184785 -0.092382 -0.020621 +v 0.182997 -0.092109 -0.028442 +v 0.162588 -0.108843 0.019734 +v 0.154795 -0.110454 0.024301 +v 0.125189 -0.114611 0.035623 +v 0.116990 -0.115391 0.037597 +v 0.053281 -0.117757 -0.043123 +v 0.020960 -0.116684 -0.040685 +v 0.137747 -0.104743 0.059882 +v 0.137763 -0.100503 0.063348 +v 0.066743 -0.104728 0.069792 +v 0.066730 -0.108966 0.066421 +v 0.097375 -0.108130 0.064942 +v 0.097435 -0.103887 0.068335 +v 0.150585 -0.098482 0.060881 +v -0.030590 -0.098591 0.061032 +v 0.016728 -0.103579 0.067824 +v 0.016792 -0.107823 0.064424 +v 0.174997 -0.100391 0.039089 +v 0.171158 -0.100378 0.045161 +v 0.165447 -0.100704 0.050942 +v 0.159399 -0.101287 0.054867 +v 0.155684 -0.101736 0.056512 +v 0.152858 -0.102120 0.057441 +v 0.176174 -0.100956 0.035205 +v -0.034959 -0.098065 0.059822 +v -0.059199 -0.096749 0.036007 +v -0.056179 -0.100912 0.035219 +v -0.058519 -0.096689 0.037764 +v -0.054235 -0.100754 0.039624 +v -0.057032 -0.096620 0.040941 +v -0.054730 -0.096607 0.044781 +v -0.051982 -0.096680 0.048358 +v -0.049710 -0.100795 0.046243 +v -0.046001 -0.097023 0.053963 +v -0.041024 -0.101465 0.053479 +v -0.044364 -0.101147 0.051242 +v -0.042256 -0.097326 0.056473 +v -0.034531 -0.102250 0.056459 +v 0.178192 -0.101280 0.028858 +v -0.061572 -0.097121 0.028335 +v -0.060291 -0.101555 0.020100 +v 0.182761 -0.101228 0.006257 +v 0.182869 -0.101169 0.004061 +v 0.185392 -0.097588 0.004000 +v -0.061554 -0.102482 0.004073 +v 0.182583 -0.101665 0.002804 +v 0.185392 -0.097588 -0.003973 +v 0.182549 -0.101623 -0.004042 +v -0.061588 -0.102524 -0.002780 +v 0.184764 -0.097544 -0.011652 +v 0.181385 -0.101710 -0.013593 +v 0.179241 -0.096749 -0.035980 +v 0.180333 -0.101555 -0.020072 +v 0.183410 -0.097392 -0.020522 +v 0.181614 -0.097121 -0.028308 +v 0.176221 -0.100912 -0.035192 +v -0.057148 -0.102127 -0.028593 +v -0.058989 -0.102412 -0.021093 +v -0.055691 -0.101355 -0.035050 +v 0.155001 -0.098065 -0.059795 +v 0.178561 -0.096689 -0.037737 +v 0.174277 -0.100754 -0.039596 +v 0.177074 -0.096620 -0.040914 +v 0.174772 -0.096607 -0.044754 +v 0.172024 -0.096680 -0.048331 +v 0.169752 -0.100795 -0.046215 +v 0.166043 -0.097023 -0.053936 +v 0.161066 -0.101465 -0.053452 +v 0.164406 -0.101147 -0.051215 +v 0.162298 -0.097326 -0.056446 +v 0.154573 -0.102250 -0.056432 +v 0.150633 -0.098591 -0.061005 +v -0.032695 -0.102935 -0.056433 +v -0.050414 -0.101194 -0.044570 +v -0.044880 -0.101517 -0.050163 +v -0.042440 -0.101736 -0.051950 +v -0.039024 -0.102100 -0.053955 +v -0.030652 -0.102814 -0.057506 +v 0.103314 -0.103579 -0.067797 +v 0.103250 -0.107823 -0.064396 +v 0.007559 -0.102986 -0.066853 +v -0.004106 -0.102014 -0.065392 +v 0.053312 -0.108966 -0.066393 +v 0.053300 -0.104728 -0.069765 +v -0.004052 -0.106259 -0.061956 +v 0.188122 -0.067323 -0.007647 +v 0.053864 -0.065870 0.073625 +v 0.055609 -0.067306 0.073564 +v 0.018385 -0.065939 -0.071676 +v 0.016612 -0.067338 -0.071454 +v -0.063749 -0.068241 0.031552 +v -0.063531 -0.067172 0.032284 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.749923 0.250016 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vn -0.0104 -0.0660 -0.9978 +vn -0.0094 -0.0591 -0.9982 +vn 0.0003 0.0096 -1.0000 +vn 0.0014 0.0170 -0.9999 +vn -0.0000 1.0000 0.0000 +vn 0.7466 0.1537 -0.6473 +vn 0.7906 0.0366 -0.6113 +vn 0.7734 0.0868 -0.6280 +vn 0.8042 -0.0097 -0.5943 +vn 0.0002 -0.0090 1.0000 +vn -0.0000 -0.0077 1.0000 +vn -0.0017 0.0039 1.0000 +vn -0.0019 0.0052 1.0000 +vn -0.0111 0.9999 0.0068 +vn 0.0040 1.0000 0.0012 +vn -0.0130 0.9964 0.0841 +vn -0.6510 -0.1032 -0.7520 +vn -0.4648 0.5920 -0.6584 +vn -0.2637 -0.6361 -0.7252 +vn -0.0556 0.7736 -0.6313 +vn -0.0380 0.9965 -0.0745 +vn 0.0355 0.9962 -0.0793 +vn 0.0811 -0.6974 -0.7121 +vn 0.3870 0.5649 -0.7288 +vn 0.6351 -0.5178 -0.5732 +vn 0.8799 0.3279 -0.3439 +vn 0.8747 0.3421 -0.3435 +vn 0.9697 -0.0454 -0.2401 +vn 0.9934 0.0565 -0.1003 +vn 0.9648 -0.1450 0.2194 +vn 0.9951 -0.0431 0.0890 +vn 0.9253 -0.2204 0.3088 +vn 0.7916 0.5135 0.3311 +vn 0.6127 -0.5830 0.5336 +vn 0.5036 0.6188 0.6029 +vn 0.3541 -0.5646 0.7455 +vn 0.1676 0.6880 0.7061 +vn 0.0243 -0.6687 0.7431 +vn -0.2583 0.5140 0.8180 +vn -0.5713 -0.0302 0.8202 +vn -0.6149 -0.1033 -0.7818 +vn -0.5127 0.4581 -0.7262 +vn -0.1933 -0.4026 -0.8947 +vn -0.1058 0.4946 -0.8627 +vn 0.1279 -0.4861 -0.8645 +vn 0.2464 0.6318 -0.7349 +vn 0.3838 -0.6903 -0.6134 +vn 0.5202 0.6902 -0.5029 +vn 0.5968 -0.7340 -0.3240 +vn 0.7762 0.5676 -0.2744 +vn 0.9341 -0.3520 0.0588 +vn 0.9674 -0.2478 0.0528 +vn 0.7368 -0.6720 0.0740 +vn 0.7287 -0.6808 0.0743 +vn 0.6971 0.6546 0.2924 +vn 0.5462 -0.6925 0.4712 +vn 0.4268 -0.1864 0.8849 +vn 0.0267 0.2061 0.9782 +vn 0.0270 0.2111 0.9771 +vn 0.0156 0.0239 0.9996 +vn 0.0148 0.0111 0.9998 +vn -0.4347 -0.2966 0.8503 +vn -0.4376 -0.2826 0.8536 +vn -0.4796 0.1078 0.8708 +vn -0.4798 0.1268 0.8682 +vn -0.6510 -0.0995 -0.7526 +vn -0.2637 -0.6361 -0.7251 +vn 0.3872 0.5576 -0.7343 +vn 0.6323 -0.5650 -0.5301 +vn 0.7010 0.6687 -0.2478 +vn 0.8407 -0.5205 -0.1497 +vn 0.9074 0.4141 0.0716 +vn 0.9018 -0.1777 0.3938 +vn 0.8711 -0.0899 0.4829 +vn 0.7668 0.0894 0.6357 +vn 0.6950 0.1776 0.6967 +vn 0.3076 -0.6392 0.7048 +vn 0.2825 -0.6579 0.6981 +vn 0.3002 -0.6449 0.7029 +vn 0.2750 -0.6634 0.6959 +vn 0.0241 0.4919 0.8703 +vn -0.0175 -0.0110 0.9998 +vn -0.6538 -0.0316 -0.7560 +vn -0.3670 0.2335 -0.9004 +vn 0.0842 -0.0208 -0.9962 +vn 0.0833 -0.0088 -0.9965 +vn 0.2108 -0.0789 -0.9743 +vn 0.3655 0.0413 -0.9299 +vn 0.4712 0.1334 -0.8719 +vn 0.4886 -0.3891 -0.7809 +vn 0.6521 0.4803 -0.5866 +vn 0.6647 -0.6542 -0.3609 +vn 0.8256 0.4829 -0.2919 +vn 0.9808 -0.1879 0.0524 +vn 0.9782 -0.2005 0.0534 +vn 0.9860 -0.0585 0.1560 +vn 0.9580 0.0305 0.2850 +vn 0.8074 -0.1084 0.5799 +vn 0.8715 -0.0418 0.4886 +vn 0.7314 -0.1775 0.6585 +vn 0.6239 0.4319 0.6513 +vn 0.3037 -0.5997 0.7404 +vn 0.3041 -0.5792 0.7563 +vn 0.2963 -0.2533 0.9209 +vn 0.0906 -0.0840 0.9923 +vn 0.2583 0.0484 0.9648 +vn -0.0695 0.3121 0.9475 +vn -0.0715 0.3320 0.9406 +vn -0.4222 -0.3732 0.8261 +vn -0.4273 -0.3557 0.8312 +vn -0.4976 0.0683 0.8647 +vn -0.4992 0.1000 0.8607 +vn -0.0881 0.6903 -0.7181 +vn 0.0877 -0.6318 -0.7701 +vn 0.2464 0.6318 -0.7350 +vn 0.4122 -0.5650 -0.7147 +vn 0.6359 0.4667 -0.6147 +vn 0.6844 -0.4883 -0.5414 +vn 0.6281 -0.7751 -0.0687 +vn 0.6483 -0.7589 -0.0617 +vn 0.8436 -0.5366 0.0208 +vn 0.8638 -0.5029 0.0317 +vn 0.9018 -0.1778 0.3938 +vn 0.8711 -0.0897 0.4829 +vn 0.7667 0.0897 0.6356 +vn 0.6950 0.1779 0.6967 +vn 0.4193 -0.1775 0.8903 +vn 0.0267 0.2058 0.9782 +vn -0.4346 -0.2971 0.8502 +vn -0.4376 -0.2829 0.8535 +vn 0.0880 -0.8055 -0.5861 +vn 0.2719 0.8310 -0.4853 +vn 0.4513 -0.7234 -0.5225 +vn 0.7311 0.5775 -0.3633 +vn 0.9155 0.0253 -0.4015 +vn 0.9788 -0.1657 -0.1205 +vn 0.9566 -0.0640 -0.2844 +vn 0.9795 0.1459 0.1391 +vn 0.9564 0.0377 0.2896 +vn 0.7913 -0.1557 0.5913 +vn 0.8819 -0.0352 0.4702 +vn 0.7131 -0.2308 0.6619 +vn 0.3366 -0.5498 0.7644 +vn 0.2938 -0.6119 0.7344 +vn 0.3311 -0.5582 0.7608 +vn 0.2881 -0.6195 0.7302 +vn -0.0172 0.1917 0.9813 +vn -0.0209 0.2472 0.9687 +vn -0.0350 0.4576 0.8885 +vn -0.0354 0.4641 0.8850 +vn -0.4066 -0.4493 0.7955 +vn -0.4978 0.1246 0.8583 +vn -0.8677 0.0331 -0.4959 +vn -0.6993 0.0144 -0.7147 +vn -0.8160 0.0329 -0.5772 +vn -0.5578 0.0928 -0.8248 +vn -0.3830 -0.1006 -0.9183 +vn -0.1738 0.0688 -0.9824 +vn 0.0209 -0.0924 -0.9955 +vn 0.3114 -0.0249 -0.9499 +vn 0.2913 0.0309 -0.9561 +vn 0.5173 -0.3280 -0.7905 +vn 0.5192 -0.3650 -0.7728 +vn 0.7343 0.3613 -0.5747 +vn 0.8769 -0.3606 -0.3177 +vn 0.9170 0.3765 -0.1314 +vn 0.9432 -0.2434 0.2263 +vn 0.9415 -0.1920 0.2768 +vn 0.9469 -0.2196 0.2350 +vn 0.9086 0.1947 0.3695 +vn 0.8947 0.2402 0.3765 +vn 0.7299 -0.2010 0.6534 +vn 0.7184 -0.1309 0.6832 +vn 0.6022 0.1445 0.7852 +vn 0.4308 -0.0407 0.9015 +vn 0.2660 0.0039 0.9640 +vn 0.0746 -0.1575 0.9847 +vn -0.2059 0.0131 0.9785 +vn -0.2811 0.0380 0.9589 +vn -0.4492 -0.0903 0.8889 +vn -0.4506 -0.0997 0.8871 +vn -0.7461 0.4689 -0.4727 +vn -0.9854 0.0022 -0.1703 +vn -0.9539 0.0942 -0.2850 +vn -0.9310 0.0548 -0.3608 +vn -0.8807 -0.0215 -0.4731 +vn -0.8711 -0.0146 -0.4909 +vn -0.7325 0.0035 0.6808 +vn 0.5423 0.0618 0.8379 +vn 0.1794 -0.1732 0.9684 +vn -0.2028 0.1780 0.9629 +vn -0.2014 0.1904 0.9608 +vn -0.2282 -0.2052 0.9517 +vn -0.2285 -0.2173 0.9490 +vn -0.6022 0.2021 0.7723 +vn -0.5732 -0.5039 0.6462 +vn -0.7086 0.5535 0.4376 +vn -0.7347 -0.6208 0.2737 +vn -0.8215 0.5533 0.1378 +vn -0.8707 -0.4901 -0.0411 +vn -0.8437 0.4960 -0.2053 +vn -0.8217 -0.4626 -0.3329 +vn -0.6586 0.5519 -0.5114 +vn -0.6255 -0.4856 -0.6108 +vn -0.3480 0.4544 -0.8200 +vn -0.3486 0.4461 -0.8243 +vn -0.2601 0.6223 -0.7383 +vn -0.2300 0.6244 -0.7465 +vn -0.1587 0.3216 -0.9335 +vn -0.1542 0.2071 -0.9661 +vn 0.1988 -0.6019 -0.7734 +vn 0.5779 0.3046 -0.7571 +vn 0.6657 0.0289 0.7457 +vn 0.2582 -0.6981 0.6678 +vn 0.1659 0.5321 0.8303 +vn -0.1951 -0.3013 0.9334 +vn -0.1951 -0.3101 0.9305 +vn -0.1949 -0.2496 0.9485 +vn -0.1949 -0.2479 0.9490 +vn -0.6254 0.2205 0.7485 +vn -0.6229 0.2329 0.7468 +vn -0.6467 -0.2203 0.7302 +vn -0.6454 -0.2327 0.7275 +vn -0.9070 0.2052 0.3678 +vn -0.9042 0.2173 0.3677 +vn -0.9218 -0.1780 0.3444 +vn -0.9200 -0.1904 0.3427 +vn -0.9846 0.1712 -0.0361 +vn -0.9838 0.1758 -0.0356 +vn -0.9470 -0.1353 -0.2913 +vn -0.9881 -0.0375 -0.1491 +vn -0.8314 0.1487 -0.5355 +vn -0.7413 0.0545 -0.6690 +vn -0.6240 -0.2276 -0.7475 +vn -0.6229 -0.2329 -0.7468 +vn -0.2282 0.2052 -0.9517 +vn -0.2285 0.2178 -0.9489 +vn -0.2028 -0.1782 -0.9629 +vn -0.2014 -0.1909 -0.9607 +vn 0.1794 0.1732 -0.9684 +vn 0.5407 -0.1081 -0.8342 +vn 0.5868 -0.3230 0.7425 +vn 0.4596 0.5498 0.6975 +vn 0.1905 -0.2521 0.9488 +vn 0.1888 -0.2655 0.9454 +vn 0.1037 -0.1025 0.9893 +vn -0.0726 0.0678 0.9951 +vn -0.1706 0.1610 0.9721 +vn -0.2006 -0.6592 0.7247 +vn -0.2484 -0.6916 0.6782 +vn -0.2202 -0.6728 0.7063 +vn -0.2665 -0.7031 0.6593 +vn -0.6623 -0.1655 0.7307 +vn -0.7347 -0.0797 0.6737 +vn -0.8358 0.0770 0.5436 +vn -0.8726 0.1608 0.4611 +vn -0.8112 -0.4562 0.3657 +vn -0.7731 0.6280 0.0891 +vn -0.7260 -0.6868 -0.0351 +vn -0.7888 0.5117 -0.3405 +vn -0.7830 0.5231 -0.3365 +vn -0.7677 -0.1247 -0.6285 +vn -0.8523 -0.0333 -0.5220 +vn -0.6877 -0.2142 -0.6937 +vn -0.5624 0.5025 -0.6567 +vn -0.2504 -0.6669 -0.7018 +vn -0.2499 -0.6456 -0.7216 +vn -0.2267 -0.3379 -0.9135 +vn -0.2368 -0.2294 -0.9441 +vn -0.2375 -0.2249 -0.9450 +vn 0.1669 0.1609 -0.9728 +vn 0.2045 -0.5054 -0.8383 +vn 0.5783 0.3032 -0.7574 +vn 0.6539 -0.0716 0.7532 +vn 0.4603 0.5761 0.6755 +vn 0.2519 -0.6486 0.7183 +vn 0.0635 0.6023 0.7957 +vn -0.1782 -0.4989 0.8482 +vn -0.1781 -0.5227 0.8337 +vn -0.1782 -0.4667 0.8663 +vn -0.1782 -0.4645 0.8675 +vn -0.4250 0.3913 0.8163 +vn -0.6269 -0.3262 0.7076 +vn -0.6144 -0.3947 0.6831 +vn -0.7288 -0.0793 0.6801 +vn -0.8281 0.0262 0.5599 +vn -0.8493 -0.3604 0.3857 +vn -0.8435 -0.3794 0.3802 +vn -0.8346 0.5424 0.0962 +vn -0.7968 -0.6030 -0.0385 +vn -0.8297 0.4279 -0.3585 +vn -0.8245 0.4410 -0.3545 +vn -0.7597 -0.0945 -0.6433 +vn -0.8400 -0.0408 -0.5410 +vn -0.6367 0.2132 -0.7410 +vn -0.6328 0.2310 -0.7390 +vn -0.2011 -0.0266 -0.9792 +vn -0.1963 0.6451 -0.7384 +vn 0.0634 -0.6027 -0.7955 +vn 0.2519 0.6483 -0.7185 +vn 0.4602 -0.5759 -0.6757 +vn 0.6535 0.0787 -0.7528 +vn 0.8671 0.0249 0.4976 +vn 0.9639 0.0051 0.2664 +vn 0.9625 0.0056 0.2712 +vn 0.8054 0.0568 -0.5900 +vn 0.9357 0.0074 -0.3527 +vn 0.9361 0.0110 -0.3516 +vn 0.9372 0.0222 -0.3480 +vn 0.9375 0.0253 -0.3472 +vn 0.9459 0.0145 0.3243 +vn 0.9846 -0.0167 0.1740 +vn 0.9570 0.0133 0.2896 +vn 0.9390 0.0459 -0.3407 +vn 0.9412 0.1123 -0.3187 +vn 0.9410 0.1286 -0.3130 +vn 0.9496 -0.0172 -0.3130 +vn 0.9350 0.0769 -0.3463 +vn 0.9934 -0.1137 0.0144 +vn 0.9217 -0.0351 -0.3864 +vn 0.9494 0.0557 -0.3090 +vn 0.9950 0.0625 -0.0775 +vn 0.9807 0.1334 -0.1426 +vn 0.9594 0.0149 0.2818 +vn 0.9412 0.1126 -0.3186 +vn 0.9391 0.0473 -0.3402 +vn 0.9376 0.0273 -0.3465 +vn 0.7759 -0.0065 0.6308 +vn 0.6268 0.0216 0.7789 +vn 0.9546 0.0437 -0.2947 +vn 0.8691 -0.0199 0.4943 +vn 0.9523 0.0069 -0.3050 +vn 0.9549 0.0360 0.2948 +vn 0.9560 0.0288 0.2920 +vn 0.9987 0.0037 0.0502 +vn 0.9983 -0.0018 0.0583 +vn 0.9560 -0.0459 0.2896 +vn 0.9555 -0.0356 0.2928 +vn 0.9611 -0.0214 0.2754 +vn 0.8721 -0.1277 -0.4724 +vn 0.9395 -0.0037 0.3425 +vn 0.9386 -0.0004 0.3450 +vn 0.9383 0.0006 0.3458 +vn 0.9374 0.0039 0.3483 +vn 0.9414 -0.0590 0.3322 +vn 0.9335 -0.0969 0.3452 +vn 0.9482 -0.0171 0.3172 +vn 0.9504 0.0000 0.3109 +vn 0.9410 0.0230 -0.3378 +vn 0.9670 0.0098 -0.2544 +vn 0.9101 -0.0212 -0.4139 +vn 0.9412 0.0204 0.3374 +vn 0.9427 0.0362 0.3318 +vn 0.9376 -0.0093 0.3476 +vn 0.9344 -0.0311 0.3549 +vn 0.9547 0.0433 0.2945 +vn 0.9547 0.0432 0.2945 +vn 0.9561 -0.0459 0.2896 +vn 0.9548 -0.0344 0.2953 +vn 0.9527 -0.0178 0.3035 +vn 0.9516 -0.0103 0.3072 +vn 0.9554 0.0175 -0.2949 +vn 0.7127 0.0212 -0.7011 +vn 0.6081 0.0263 -0.7934 +vn 0.7717 0.0088 -0.6359 +vn 0.9620 -0.0285 0.2714 +vn -0.8481 -0.0385 -0.5284 +vn -0.5286 0.3973 -0.7502 +vn 0.3688 -0.3367 -0.8664 +vn 0.9217 0.3773 0.0904 +vn 0.8831 -0.1013 0.4581 +vn -0.4817 0.0598 0.8743 +vn -0.4861 0.0676 0.8713 +vn -0.4885 0.0718 0.8696 +vn -0.4925 0.0790 0.8667 +vn -0.1953 -0.0055 -0.9807 +vn -0.2888 -0.2728 -0.9177 +vn -0.3765 -0.1383 -0.9160 +vn -0.3318 0.0687 -0.9409 +vn 0.6429 0.3469 -0.6829 +vn 0.8388 -0.4093 0.3591 +vn 0.6820 0.1140 0.7224 +vn -0.8311 -0.1018 0.5468 +vn -0.8444 -0.0689 0.5312 +vn -0.8558 -0.0381 0.5159 +vn -0.8676 -0.0022 0.4972 +vn -0.7929 0.4126 -0.4484 +vn -0.1439 -0.5461 -0.8252 +vn 0.7457 0.4506 -0.4908 +vn 0.6563 -0.4682 0.5916 +vn 0.1260 0.3585 0.9250 +vn -0.8068 -0.3048 0.5061 +vn 0.5729 -0.4870 0.6593 +vn 0.4532 0.5105 0.7307 +vn 0.2736 -0.5622 0.7804 +vn 0.1657 0.5324 0.8301 +vn -0.1950 -0.3153 0.9287 +vn -0.2383 -0.6618 0.7108 +vn -0.2005 -0.3806 0.9027 +vn -0.2405 -0.6865 0.6862 +vn -0.5621 0.4050 0.7211 +vn -0.6289 -0.4053 0.6635 +vn -0.7347 -0.6207 0.2737 +vn -0.7973 -0.6001 -0.0639 +vn -0.8372 0.1781 -0.5172 +vn -0.8792 0.2567 -0.4015 +vn -0.7539 0.0691 -0.6533 +vn -0.6713 -0.0163 -0.7410 +vn -0.0795 -0.9854 -0.1507 +vn -0.2775 -0.6467 -0.7105 +vn 0.0057 -1.0000 -0.0067 +vn -0.1564 0.5052 -0.8487 +vn 0.1602 -0.2314 -0.9596 +vn 0.5419 -0.0935 -0.8352 +vn 0.8476 0.5301 -0.0240 +vn -0.8903 0.4340 -0.1381 +vn 0.0215 -0.3580 -0.9335 +vn 0.4072 0.2714 -0.8721 +vn 0.8778 -0.3642 0.3112 +vn 0.3898 0.6071 0.6925 +vn -0.5952 -0.6542 0.4668 +vn -0.9831 0.0618 -0.1725 +vn -0.0662 0.1317 -0.9891 +vn -0.1086 -0.0819 -0.9907 +vn -0.2742 -0.2985 -0.9142 +vn 0.3142 -0.4113 -0.8557 +vn 0.9288 0.3420 -0.1423 +vn 0.7183 -0.4604 0.5216 +vn -0.0698 0.4909 0.8684 +vn -0.7825 -0.5768 0.2346 +vn -0.7151 -0.5099 -0.4781 +vn -0.5169 -0.1266 -0.8466 +vn 0.8099 -0.2805 -0.5151 +vn 0.8475 -0.2005 -0.4915 +vn 0.8868 -0.0902 -0.4533 +vn 0.9068 -0.0099 -0.4214 +vn 0.2175 -0.0860 0.9723 +vn 0.2896 0.0445 0.9561 +vn 0.1230 -0.2428 0.9622 +vn 0.0640 -0.3335 0.9406 +vn -0.8623 0.4619 0.2076 +vn 0.1887 -0.2655 0.9454 +vn 0.1975 -0.1927 0.9612 +vn 0.1978 -0.1903 0.9616 +vn -0.2028 0.1785 0.9628 +vn -0.2014 0.1906 0.9608 +vn -0.6254 0.2204 0.7485 +vn -0.6229 0.2328 0.7468 +vn -0.6467 -0.2202 0.7302 +vn -0.9069 0.2056 0.3678 +vn -0.9042 0.2172 0.3677 +vn -0.9218 -0.1784 0.3442 +vn -0.9199 -0.1907 0.3427 +vn -0.9515 -0.1363 -0.2759 +vn -0.9890 -0.0336 -0.1440 +vn -0.9053 -0.2145 -0.3667 +vn -0.8401 0.3699 -0.3967 +vn -0.6401 -0.4076 -0.6512 +vn -0.3013 -0.5683 -0.7657 +vn -0.0122 0.6578 -0.7531 +vn 0.1296 -0.6049 -0.7857 +vn 0.3286 0.4291 -0.8414 +vn 0.4382 -0.6085 -0.6616 +vn 0.6268 0.2948 -0.7213 +vn -0.0903 -0.0235 0.9956 +vn -0.2267 -0.0634 0.9719 +vn -0.4073 0.1768 0.8960 +vn -0.4232 0.2320 0.8758 +vn -0.6069 -0.2498 0.7545 +vn -0.7726 0.3026 0.5581 +vn -0.8834 -0.2295 0.4085 +vn -0.9285 -0.1423 0.3430 +vn -0.9816 0.0267 0.1890 +vn -0.9938 -0.0198 -0.1095 +vn -0.9914 -0.0504 -0.1211 +vn -0.9116 0.0429 -0.4087 +vn -0.8518 0.0002 -0.5239 +vn -0.7358 0.0351 -0.6762 +vn -0.6103 -0.0496 -0.7906 +vn -0.4363 0.1183 -0.8920 +vn -0.2165 -0.0858 -0.9725 +vn -0.0712 -0.0283 -0.9971 +vn -0.8763 0.1144 -0.4681 +vn -0.2455 -0.5725 -0.7823 +vn 0.4579 0.5394 -0.7066 +vn 0.8050 -0.4931 0.3300 +vn 0.6510 0.1534 0.7434 +vn -0.6882 -0.1160 0.7162 +vn -0.6728 -0.0727 0.7363 +vn -0.7003 -0.1541 0.6970 +vn -0.7101 -0.1880 0.6785 +vn -0.9012 0.3561 -0.2469 +vn -0.8282 -0.1880 -0.5279 +vn 0.6625 0.0688 -0.7459 +vn 0.5932 0.1983 -0.7803 +vn 0.7325 -0.1101 -0.6718 +vn 0.7629 -0.2315 -0.6037 +vn 0.3919 0.3125 0.8653 +vn 0.0704 -0.3919 0.9173 +vn -0.4534 -0.5727 -0.6830 +vn 0.5606 0.6137 -0.5560 +vn 0.8084 -0.5796 0.1023 +vn 0.2694 0.4475 0.8528 +vn -0.5787 -0.3746 0.7244 +vn -0.8558 0.5164 -0.0294 +vn 0.8011 -0.0081 0.5985 +vn 0.8044 0.0036 0.5940 +vn 0.8024 -0.0035 0.5968 +vn 0.8057 0.0084 0.5922 +vn -0.0641 0.0261 0.9976 +vn 0.0530 0.0003 0.9986 +vn -0.0444 0.0218 0.9988 +vn 0.0756 -0.0047 0.9971 +vn 0.0018 0.0215 -0.9998 +vn 0.2388 -0.0260 -0.9707 +vn 0.2014 -0.0184 -0.9793 +vn -0.0370 0.0291 -0.9989 +vn 0.2002 -0.0179 0.9796 +vn 0.2300 -0.0065 0.9732 +vn 0.0035 -0.0765 0.9971 +vn 0.1229 -0.0107 -0.9924 +vn 0.1816 -0.0156 -0.9832 +vn 0.7222 0.2320 -0.6516 +vn 0.7081 0.1666 -0.6862 +vn 0.5969 -0.0365 -0.8015 +vn 0.4398 0.1059 -0.8918 +vn 0.2970 -0.1419 -0.9443 +vn 0.2680 -0.2059 -0.9412 +vn -0.0376 0.2199 -0.9748 +vn -0.0432 0.2014 -0.9786 +vn -0.2017 0.1351 -0.9701 +vn -0.5777 0.0186 -0.8161 +vn -0.6782 0.0375 -0.7340 +vn -0.7958 -0.0828 -0.5998 +vn -0.9034 0.0542 -0.4253 +vn -0.9632 -0.0641 -0.2609 +vn -0.9984 -0.0381 -0.0424 +vn -0.9999 -0.0088 0.0104 +vn -0.9539 0.0608 0.2938 +vn -0.8985 -0.0265 0.4383 +vn -0.6882 0.0314 0.7248 +vn -0.7376 0.0469 0.6736 +vn -0.4399 -0.0712 0.8952 +vn -0.3083 0.0444 0.9502 +vn -0.2306 0.1250 0.9650 +vn -0.3689 0.9002 0.2316 +vn 0.0581 -0.1585 0.9857 +vn 0.0462 -0.1925 0.9802 +vn 0.2584 0.0358 0.9654 +vn 0.3088 0.0647 0.9489 +vn 0.5601 -0.0055 0.8284 +vn 0.6010 -0.0186 0.7990 +vn 0.8596 0.0434 0.5091 +vn 0.8838 0.0060 -0.4679 +vn 0.9331 0.0074 -0.3596 +vn 0.9367 0.0467 -0.3471 +vn 0.9344 0.1174 -0.3363 +vn 0.9460 0.0657 0.3175 +vn 0.9368 0.0861 0.3390 +vn 0.9261 0.0543 0.3733 +vn 0.8831 -0.0221 0.4687 +vn 0.8866 -0.0206 -0.4620 +vn 0.8631 -0.0188 -0.5047 +vn -0.0000 1.0000 -0.0001 +vn 0.0772 0.0232 -0.9967 +vn 0.0860 0.0171 -0.9962 +vn 0.0805 0.0209 -0.9965 +vn 0.0717 0.0270 -0.9971 +vn -0.1704 0.1060 0.9796 +vn 0.0215 -0.0080 0.9997 +vn -0.0541 0.0369 0.9979 +vn 0.1368 -0.0770 0.9876 +vn -0.0000 -1.0000 -0.0000 +vn -0.0047 -0.9999 -0.0089 +vn -0.0592 -0.9921 -0.1109 +vn -0.0848 -0.9878 -0.1308 +vn -0.0065 -0.9999 -0.0098 +vn 0.6008 -0.1541 -0.7844 +vn 0.5980 -0.2148 -0.7722 +vn 0.3006 0.5231 -0.7975 +vn 0.1286 -0.6906 -0.7117 +vn -0.0679 0.6756 -0.7341 +vn -0.2582 -0.4201 -0.8700 +vn -0.4247 0.3367 -0.8404 +vn -0.4879 -0.6066 -0.6277 +vn -0.5847 0.6892 -0.4280 +vn -0.7053 -0.6187 -0.3462 +vn -0.1653 -0.9823 -0.0883 +vn -0.7640 -0.6450 0.0163 +vn -0.9301 0.3369 -0.1462 +vn -0.6795 0.6967 0.2301 +vn -0.5578 -0.7326 0.3900 +vn -0.7115 0.2611 0.6524 +vn -0.6394 0.1841 0.7465 +vn -0.5505 0.1189 0.8263 +vn -0.3856 -0.1813 0.9047 +vn -0.2551 0.0250 0.9666 +vn -0.2091 0.0952 0.9733 +vn -0.0385 -0.6108 0.7908 +vn 0.1269 0.6848 0.7176 +vn 0.2783 -0.8059 0.5226 +vn 0.5604 0.3059 0.7696 +vn 0.0119 -0.9999 0.0060 +vn -0.1215 -0.9657 -0.2296 +vn -0.0832 -0.9964 -0.0161 +vn -0.0942 -0.9952 -0.0251 +vn -0.0083 -1.0000 -0.0017 +vn -0.0300 -0.9993 0.0205 +vn 0.0257 -0.9945 0.1011 +vn -0.0600 -0.9980 -0.0219 +vn -0.0151 -0.9998 -0.0135 +vn 0.0375 -0.9936 -0.1070 +vn -0.0327 -0.9990 -0.0298 +vn 0.0026 -1.0000 0.0003 +vn -0.0491 -0.9908 -0.1262 +vn -0.0406 -0.9937 -0.1044 +vn 0.0262 -0.9946 -0.1009 +vn 0.0285 -0.9914 -0.1274 +vn 0.0304 -0.9903 -0.1359 +vn 0.0219 -0.9997 -0.0136 +vn -0.0089 -0.9567 -0.2910 +vn -0.0212 -0.9889 0.1470 +vn -0.0640 -0.9978 0.0154 +vn -0.0105 0.9999 -0.0134 +vn -0.0637 0.9945 -0.0834 +vn -0.0628 0.9949 0.0786 +vn 0.0156 0.9999 -0.0008 +vn 0.0224 0.9997 -0.0011 +vn 0.0388 0.9992 -0.0019 +vn -0.0731 0.5073 0.8587 +vn 0.0559 0.9880 -0.1439 +vn 0.0463 0.9918 -0.1190 +vn 0.0042 0.9999 -0.0107 +vn -0.1256 0.9712 -0.2027 +vn -0.0096 0.9998 -0.0157 +vn 0.5784 -0.2724 -0.7689 +vn 0.3236 0.5661 -0.7582 +vn 0.1546 -0.6281 -0.7626 +vn -0.0562 0.5507 -0.8328 +vn -0.1582 -0.1723 -0.9723 +vn -0.2255 -0.2992 -0.9271 +vn -0.4304 -0.4479 -0.7836 +vn -0.4564 0.6298 -0.6285 +vn -0.5942 -0.6703 -0.4445 +vn -0.7229 0.5955 -0.3504 +vn -0.9125 -0.3777 -0.1574 +vn -0.9147 -0.3724 -0.1570 +vn -0.9745 -0.2054 0.0908 +vn -0.9132 -0.3969 -0.0926 +vn -0.8501 -0.4927 0.1859 +vn -0.8424 -0.5057 0.1860 +vn -0.6965 0.5748 0.4295 +vn -0.5964 -0.6105 0.5213 +vn -0.3954 0.6562 0.6427 +vn -0.2353 -0.0512 0.9706 +vn -0.4514 0.1649 0.8770 +vn -0.3838 0.0937 0.9186 +vn -0.1599 -0.1204 0.9798 +vn 0.1797 0.2169 0.9595 +vn 0.5683 -0.1755 0.8039 +vn 0.5665 -0.1859 0.8028 +vn -0.0068 -0.9999 0.0119 +vn 0.0104 -0.9999 0.0059 +vn 0.0129 -0.9923 0.1235 +vn -0.0121 -0.9999 0.0005 +vn 0.0268 -0.9968 0.0751 +vn 0.0272 -0.9978 0.0603 +vn -0.0096 -0.9997 0.0221 +vn 0.0596 -0.9901 -0.1270 +vn 0.0294 -0.9957 -0.0878 +vn 0.0274 -0.9963 -0.0820 +vn 0.0242 -0.9997 0.0034 +vn -0.1035 -0.2049 -0.9733 +vn -0.1158 -0.3664 -0.9232 +vn -0.1157 -0.3617 -0.9251 +vn 0.0168 -0.9902 0.1388 +vn -0.0754 -0.9967 0.0291 +vn 0.1139 -0.9822 -0.1497 +vn 0.0944 -0.9852 -0.1428 +vn 0.0555 -0.9940 0.0942 +vn 0.0519 -0.9912 0.1215 +vn -0.1435 -0.9650 0.2195 +vn 0.0093 -0.9997 0.0239 +vn 0.0055 0.9999 -0.0109 +vn 0.0285 0.9980 -0.0560 +vn 0.0315 0.9976 -0.0619 +vn -0.0120 0.9999 -0.0085 +vn 0.0227 0.9966 -0.0790 +vn -0.0291 0.9944 -0.1013 +vn 0.0363 0.9950 0.0934 +vn -0.0193 0.9975 -0.0674 +vn -0.2565 0.1765 0.9503 +vn -0.0884 0.5188 0.8503 +vn -0.0884 0.5106 0.8553 +vn 0.0535 0.9875 -0.1483 +vn 0.0602 0.9771 -0.2039 +vn 0.0564 0.9800 -0.1910 +vn 0.0337 0.9957 -0.0859 +vn -0.0253 0.9997 -0.0071 +vn 0.0843 0.9867 0.1392 +vn 0.0739 0.9883 0.1333 +vn 0.0677 0.9882 -0.1377 +vn -0.0106 0.9999 0.0028 +vn -0.0901 0.9934 0.0710 +vn -0.0991 0.9884 0.1154 +vn -0.0104 0.9996 0.0249 +vn 0.5749 0.2661 -0.7738 +vn 0.2739 -0.5325 -0.8009 +vn -0.0896 -0.1973 -0.9762 +vn -0.0661 -0.1421 -0.9876 +vn 0.3520 0.2598 -0.8992 +vn 0.3641 -0.0236 -0.9310 +vn 0.3643 0.0322 -0.9307 +vn -0.4970 0.5336 -0.6844 +vn -0.6108 -0.2571 -0.7489 +vn -0.9201 0.0672 -0.3860 +vn -0.9204 0.0568 -0.3867 +vn -0.8992 0.2373 -0.3675 +vn -0.8980 0.2433 -0.3666 +vn -0.7844 0.0151 0.6200 +vn -0.8373 -0.0340 0.5457 +vn -0.9253 0.0494 0.3759 +vn -0.8746 0.1108 0.4720 +vn -0.9663 0.0588 0.2506 +vn -0.9034 -0.0993 0.4172 +vn -0.8438 -0.1894 0.5021 +vn -0.4761 -0.5467 0.6888 +vn -0.0191 -0.3265 0.9450 +vn -0.2149 0.2250 0.9504 +vn -0.3919 -0.0134 0.9199 +vn 0.2369 -0.5446 0.8045 +vn 0.5964 0.1355 0.7912 +vn 0.5961 0.1877 0.7807 +vn 0.5899 0.0034 0.8075 +vn 0.5890 -0.0062 0.8081 +vn -0.0141 -0.9999 0.0099 +vn 0.0078 -0.9933 0.1153 +vn 0.0135 -0.9950 0.0993 +vn -0.0004 -0.9929 0.1188 +vn -0.2523 -0.8517 0.4593 +vn -0.0447 -0.9975 -0.0550 +vn 0.0186 -0.9996 -0.0214 +vn 0.0548 -0.9868 -0.1526 +vn 0.0635 -0.9822 -0.1766 +vn -0.1045 -0.7660 -0.6343 +vn -0.1049 -0.7573 -0.6446 +vn -0.0475 -0.9989 -0.0032 +vn -0.0044 -0.9999 -0.0106 +vn -0.2343 -0.9700 -0.0648 +vn 0.0551 -0.9981 -0.0281 +vn 0.0431 -0.9988 -0.0220 +vn -0.0197 -0.9992 0.0346 +vn 0.0082 -0.9999 0.0127 +vn -0.0131 -0.9999 -0.0009 +vn -0.0596 -0.9982 -0.0040 +vn -0.2649 -0.8389 0.4755 +vn -0.0375 0.9993 -0.0077 +vn -0.0174 0.9997 -0.0177 +vn 0.0924 0.9945 -0.0484 +vn -0.1568 0.9445 0.2889 +vn -0.0284 0.9984 0.0482 +vn 0.0166 0.9975 0.0686 +vn 0.0108 0.9999 0.0056 +vn -0.3230 -0.0345 0.9458 +vn -0.1179 0.3519 0.9286 +vn -0.1179 0.3392 0.9333 +vn -0.0208 0.9369 -0.3489 +vn -0.0436 0.9988 -0.0242 +vn 0.0481 0.9985 0.0252 +vn 0.0380 0.9991 0.0199 +vn 0.1064 0.9884 -0.1083 +vn 0.1478 0.9785 -0.1440 +vn 0.0429 0.9930 -0.1102 +vn 0.0482 0.9911 -0.1238 +vn -0.0090 1.0000 0.0008 +vn -0.1084 0.9765 0.1864 +vn -0.0560 0.9977 0.0373 +vn -0.0288 0.9976 -0.0630 +vn -0.5669 0.8188 -0.0906 +vn -0.0327 0.9969 -0.0715 +vn -0.0043 0.9999 -0.0094 +vn 0.5904 0.0016 -0.8071 +vn 0.3444 0.1811 -0.9212 +vn 0.4845 0.0847 -0.8707 +vn 0.2200 0.2567 -0.9411 +vn -0.3754 -0.2032 -0.9043 +vn -0.4376 -0.1158 -0.8917 +vn -0.4441 0.4648 -0.7660 +vn -0.7206 -0.4171 -0.5539 +vn -0.9670 0.1439 -0.2104 +vn -0.9955 0.0814 -0.0484 +vn -0.9974 0.0473 0.0540 +vn -0.9481 0.2269 0.2227 +vn -0.9462 0.2346 0.2229 +vn -0.7293 -0.2250 0.6462 +vn -0.2319 -0.0826 0.9692 +vn -0.4451 0.0180 0.8953 +vn 0.2369 -0.5447 0.8045 +vn 0.5927 0.1361 0.7938 +vn 0.5918 0.1704 0.7879 +vn 0.5896 0.0064 0.8077 +vn 0.5890 -0.0025 0.8081 +vn -0.9029 -0.2295 -0.3633 +vn -0.9032 -0.1588 -0.3987 +vn -0.8868 -0.0163 -0.4619 +vn -0.8688 0.0612 -0.4914 +vn 0.7573 -0.0534 -0.6509 +vn 0.8318 0.3929 -0.3921 +vn 0.3186 -0.4665 0.8252 +vn -0.0194 0.2075 0.9780 +vn -0.0690 -0.9907 0.1174 +vn -0.0306 -0.9993 0.0205 +vn -0.0543 -0.9982 0.0235 +vn 0.0023 -1.0000 -0.0002 +vn 0.0120 -0.9995 0.0283 +vn 0.0225 -0.9970 -0.0747 +vn 0.0193 -0.9949 -0.0990 +vn 0.0546 -0.9870 -0.1513 +vn 0.0594 -0.9845 -0.1647 +vn -0.0240 -0.3487 0.9369 +vn -0.0666 -0.9968 0.0438 +vn -0.0059 -0.9999 0.0104 +vn 0.0161 -0.9998 -0.0084 +vn 0.0372 -0.9991 -0.0193 +vn 0.0193 -0.9998 -0.0100 +vn 0.0297 0.9982 0.0512 +vn 0.0066 0.9999 0.0114 +vn 0.0332 0.9978 0.0572 +vn 0.0679 0.9974 0.0250 +vn 0.0151 0.9992 0.0381 +vn 0.0680 0.9977 -0.0033 +vn -0.1120 -0.4998 0.8589 +vn 0.0857 0.9828 0.1638 +vn 0.0378 0.9908 -0.1301 +vn -0.0481 0.8190 -0.5718 +vn -0.0354 0.8574 -0.5134 +vn 0.0302 0.9934 -0.1103 +vn 0.0256 0.9945 -0.1013 +vn 0.0251 0.9947 -0.0995 +vn 0.5411 0.4176 -0.7300 +vn 0.2696 -0.5954 -0.7568 +vn 0.0618 0.7971 -0.6007 +vn -0.0641 -0.6439 -0.7624 +vn -0.8190 -0.3111 -0.4821 +vn -0.8040 -0.3600 -0.4732 +vn -0.8311 -0.2891 -0.4751 +vn -0.2100 0.4859 -0.8484 +vn -0.1332 0.3958 -0.9086 +vn -0.2924 0.5780 -0.7619 +vn -0.3391 0.6273 -0.7010 +vn -0.5354 -0.1827 -0.8246 +vn -0.6884 0.4364 -0.5794 +vn -0.7673 -0.2857 -0.5741 +vn -0.9844 -0.0088 -0.1759 +vn -0.9843 -0.0116 -0.1761 +vn -0.9998 -0.0074 -0.0182 +vn -0.9997 -0.0166 0.0155 +vn -0.9721 -0.1735 0.1579 +vn -0.9663 -0.2060 0.1542 +vn -0.6844 0.5814 0.4399 +vn -0.5848 -0.6448 0.4922 +vn -0.4388 0.4592 0.7724 +vn -0.3456 -0.1087 0.9320 +vn -0.4196 -0.1656 0.8925 +vn -0.2465 -0.0349 0.9685 +vn -0.1629 0.0256 0.9863 +vn 0.5676 -0.1795 0.8035 +vn 0.5884 -0.0117 0.8085 +vn -0.7213 -0.5246 -0.4522 +vn 0.0315 0.5652 -0.8243 +vn 0.7132 -0.4581 -0.5305 +vn 0.7566 0.3258 0.5670 +vn 0.7758 0.4241 0.4672 +vn 0.7380 0.2632 0.6213 +vn 0.6633 0.0906 0.7429 +vn -0.3895 -0.1083 0.9146 +vn -0.6800 0.5319 0.5047 +vn 0.5972 -0.0606 -0.7998 +vn 0.0020 -1.0000 0.0003 +vn 0.0288 -0.9974 -0.0666 +vn 0.0034 -1.0000 0.0067 +vn 0.0162 -0.9993 0.0326 +vn 0.0183 -0.9992 0.0367 +vn 0.0378 -0.9932 0.1101 +vn 0.0225 -0.9966 0.0793 +vn -0.0423 -0.9852 -0.1660 +vn -0.0300 -0.9926 -0.1178 +vn 0.0401 -0.9944 -0.0981 +vn 0.0382 -0.9888 -0.1444 +vn 0.0419 -0.9865 -0.1585 +vn -0.0458 0.3405 -0.9391 +vn 0.0102 -0.9605 0.2780 +vn 0.0695 -0.9931 -0.0944 +vn 0.0548 -0.9942 -0.0924 +vn -0.0262 0.9996 -0.0041 +vn 0.0292 0.9984 0.0480 +vn 0.0079 0.9999 0.0130 +vn 0.0336 0.9979 0.0552 +vn 0.0589 0.9880 -0.1430 +vn 0.0388 0.9928 -0.1135 +vn 0.0400 0.9923 -0.1171 +vn -0.1269 0.2898 -0.9486 +vn 0.0807 0.9848 -0.1536 +vn 0.0920 0.9832 -0.1579 +vn 0.0000 0.9988 -0.0499 +vn -0.0185 0.9993 -0.0315 +vn -0.0925 0.9843 -0.1505 +vn -0.0360 0.9992 -0.0179 +vn -0.2278 0.9715 -0.0655 +vn -0.0272 0.9995 -0.0185 +vn 0.2308 0.6189 -0.7508 +vn -0.1845 -0.4819 -0.8566 +vn -0.0770 -0.5268 -0.8465 +vn -0.2984 -0.4410 -0.8464 +vn -0.4148 -0.4031 -0.8157 +vn -0.4236 -0.4137 -0.8059 +vn -0.4261 0.6704 -0.6075 +vn -0.5519 0.8042 -0.2203 +vn -0.7420 -0.6581 -0.1276 +vn -0.8715 -0.0640 0.4862 +vn -0.9649 0.1220 0.2326 +vn -0.9292 0.1091 0.3530 +vn -0.9823 0.0926 0.1628 +vn -0.7245 -0.6598 0.1994 +vn -0.7072 0.5565 0.4361 +vn -0.6152 -0.5565 0.5584 +vn -0.4191 0.6224 0.6610 +vn -0.4397 -0.1117 0.8912 +vn -0.1141 0.3383 0.9341 +vn -0.0479 -0.4087 0.9114 +vn 0.3083 0.3955 0.8652 +vn 0.3469 -0.6256 0.6988 +vn -0.1618 0.8774 -0.4517 +vn 0.6101 -0.0136 0.7922 +vn -0.8349 -0.2688 -0.4804 +vn -0.8486 -0.2416 -0.4707 +vn 0.4655 0.2416 -0.8514 +vn 0.7480 -0.4157 -0.5174 +vn 0.8597 0.3019 0.4120 +vn 0.0605 -0.6301 0.7742 +vn -0.5515 0.2553 0.7942 +vn -0.9295 0.3453 -0.1296 +vn -0.1406 -0.2443 -0.9595 +vn -0.0987 -0.1724 -0.9801 +vn 0.9359 0.3041 -0.1779 +vn 0.7685 -0.5390 0.3448 +vn 0.0205 0.4387 0.8984 +vn -0.7236 -0.5012 0.4746 +vn -0.8365 -0.4942 -0.2367 +vn -0.3961 0.3338 -0.8554 +vn 0.3524 -0.2529 -0.9010 +vn 0.7338 0.1683 -0.6582 +vn 0.9020 -0.2101 0.3771 +vn 0.8914 -0.0913 0.4439 +vn 0.8496 0.0745 0.5221 +vn 0.7805 0.2327 0.5802 +vn -0.5100 0.2048 0.8354 +vn -0.5781 0.3203 0.7505 +vn -0.6124 0.3868 0.6894 +vn -0.6470 0.4640 0.6050 +vn -0.8883 -0.2759 -0.3672 +vn -0.6951 0.1992 -0.6908 +vn 0.3138 -0.2946 -0.9026 +vn 0.7146 0.3127 -0.6258 +vn 0.9284 -0.2263 0.2946 +vn 0.6890 0.2610 0.6761 +vn -0.2127 -0.3675 0.9054 +vn -0.7038 0.3344 0.6268 +vn -0.8099 -0.0393 -0.5853 +vn -0.7745 0.0490 -0.6307 +vn -0.7345 0.1294 -0.6662 +vn -0.6913 0.2027 -0.6936 +vn 0.5810 -0.2908 -0.7602 +vn 0.8189 0.2802 -0.5009 +vn 0.6649 -0.1866 0.7232 +vn 0.6141 -0.0752 0.7856 +vn 0.5485 0.0428 0.8350 +vn 0.4726 0.1584 0.8669 +vn -0.6703 -0.2033 0.7137 +vn -0.7602 -0.0646 0.6464 +vn -0.6015 0.0175 -0.7987 +vn -0.3015 -0.4218 -0.8551 +vn 0.7465 0.4863 -0.4541 +vn 0.6963 -0.6340 0.3365 +vn 0.3427 0.2813 0.8964 +vn -0.4889 0.3719 -0.7891 +vn 0.5371 -0.6353 -0.5549 +vn 0.9160 -0.0618 -0.3964 +vn 0.4010 -0.0159 0.9159 +vn 0.4844 0.1309 0.8650 +vn 0.3139 -0.1500 0.9375 +vn 0.2265 -0.2692 0.9361 +vn -0.8053 0.2668 0.5294 +vn -0.8691 -0.4937 -0.0305 +vn -0.9420 0.0241 0.3348 +vn -0.9397 0.0376 0.3401 +vn -0.9446 0.0072 0.3281 +vn -0.9456 0.0000 0.3252 +vn -0.9966 0.0217 -0.0789 +vn -0.9424 0.0151 -0.3342 +vn -0.9732 0.1345 -0.1865 +vn -0.9354 0.0598 0.3486 +vn -0.9523 0.0205 0.3044 +vn -0.9293 0.1351 0.3438 +vn -0.9508 -0.2368 0.1997 +vn -0.9361 -0.3105 0.1653 +vn -0.7537 0.2519 -0.6070 +vn -0.9398 0.0187 0.3411 +vn -0.9418 0.0264 0.3352 +vn -0.9425 0.0293 0.3329 +vn -0.9443 0.0371 0.3270 +vn -0.7744 -0.0078 -0.6326 +vn -0.8506 -0.0079 -0.5258 +vn -0.6096 0.0107 -0.7927 +vn -0.9428 0.0364 0.3314 +vn 0.4770 0.0151 0.8788 +vn -0.8341 -0.0064 -0.5516 +vn -0.9888 -0.0065 -0.1491 +vn -0.9461 -0.0560 0.3190 +vn -0.9468 -0.0773 0.3123 +vn -0.9413 0.0059 0.3376 +vn -0.9373 0.0380 0.3466 +vn -0.9505 0.0379 0.3085 +vn -0.9497 0.0317 0.3116 +vn -0.9476 0.0168 0.3189 +vn -0.9460 0.0059 0.3242 +vn 0.9378 -0.2644 0.2250 +vn -0.1684 0.3096 0.9358 +vn 0.1521 -0.2718 0.9502 +vn -0.9329 0.3226 -0.1598 +vn -0.8079 -0.2808 -0.5182 +vn 0.5289 0.1087 -0.8417 +vn 0.6333 0.3054 -0.7111 +vn 0.6518 0.3489 -0.6733 +vn 0.6875 0.4517 -0.5686 +vn 0.9131 -0.3885 0.1235 +vn 0.8012 0.2713 0.5334 +vn -0.6870 -0.2128 0.6948 +vn -0.8642 0.3525 0.3591 +vn -0.3054 -0.4144 -0.8573 +vn 0.1881 0.2207 -0.9570 +vn 0.9693 -0.1611 0.1859 +vn 0.9622 -0.0565 0.2663 +vn 0.9492 0.0100 0.3144 +vn 0.9137 0.1192 0.3884 +vn -0.5336 -0.1205 0.8371 +vn -0.5029 -0.1716 0.8472 +vn -0.4782 -0.2104 0.8527 +vn -0.4356 -0.2732 0.8577 +vn -0.8761 0.2534 -0.4102 +vn -0.2181 -0.5872 -0.7795 +vn 0.4799 0.0999 -0.8716 +vn 0.8914 0.0055 0.4533 +vn 0.8960 0.0279 0.4432 +vn 0.8846 -0.0229 0.4657 +vn 0.8791 -0.0442 0.4746 +vn -0.7880 0.0184 0.6154 +vn -0.5363 -0.4729 0.6991 +vn -0.6493 0.2268 -0.7260 +vn -0.0213 -0.5046 -0.8631 +vn 0.4535 0.0800 -0.8877 +vn -0.0757 -0.1587 0.9844 +vn -0.0766 -0.1568 0.9847 +vn -0.0780 -0.1538 0.9850 +vn -0.0792 -0.1515 0.9853 +vn -0.8518 0.2709 -0.4484 +vn -0.6739 -0.3312 -0.6605 +vn 0.9129 0.1580 -0.3765 +vn 0.9127 0.1515 -0.3796 +vn 0.9124 0.1437 -0.3833 +vn 0.9121 0.1389 -0.3856 +vn 0.8335 -0.4326 0.3437 +vn -0.3315 0.3616 0.8714 +vn -0.7268 -0.4845 0.4868 +vn -0.6163 0.4812 -0.6234 +vn -0.1039 -0.4422 -0.8909 +vn 0.8935 0.4304 -0.1277 +vn -0.6811 0.0124 -0.7321 +vn -0.6836 0.0021 -0.7298 +vn -0.6903 -0.0271 -0.7230 +vn -0.6924 -0.0368 -0.7206 +vn 0.4219 -0.0561 -0.9049 +vn 0.5896 0.0838 -0.8033 +vn 0.7715 -0.0865 -0.6303 +vn 0.8734 0.0110 -0.4870 +vn 0.9555 -0.0182 -0.2946 +vn 0.9885 0.0516 -0.1421 +vn 0.9923 -0.0482 0.1138 +vn 0.9659 0.0013 0.2588 +vn 0.8751 0.0019 0.4839 +vn 0.8203 0.0038 0.5718 +vn 0.6412 -0.0626 0.7648 +vn 0.5166 0.0166 0.8560 +vn 0.9833 0.0368 0.1780 +vn 0.7111 -0.5130 0.4808 +vn 0.0241 0.3290 0.9440 +vn -0.8225 -0.3475 0.4502 +vn -0.8902 0.4411 -0.1143 +vn -0.0804 -0.5508 -0.8307 +vn 0.4214 0.2442 -0.8734 +vn 0.0168 0.4306 0.9024 +vn -0.3668 -0.3778 0.8502 +vn -0.7636 0.3287 -0.5558 +vn -0.5194 -0.2946 -0.8021 +vn 0.7902 0.2758 -0.5473 +vn 0.9042 -0.3901 -0.1737 +vn 0.3236 -0.2685 0.9073 +vn 0.0632 0.1824 0.9812 +vn -0.9092 0.0343 0.4149 +vn -0.8762 0.4640 -0.1306 +vn -0.5857 -0.5071 -0.6323 +vn 0.3848 0.0836 -0.9192 +vn 0.7983 -0.3539 -0.4873 +vn 0.9570 0.2898 -0.0090 +vn -0.9337 0.0917 -0.3461 +vn -0.9591 0.0149 -0.2828 +vn -0.9649 -0.0093 -0.2623 +vn -0.9769 -0.0857 -0.1955 +vn -0.7433 0.0414 0.6677 +vn -0.7348 0.0262 0.6778 +vn -0.7322 0.0216 0.6808 +vn -0.7225 0.0053 0.6913 +vn -0.9429 -0.0151 0.3327 +vn -0.9505 -0.0502 0.3068 +vn -0.9390 0.0003 0.3439 +vn -0.9287 0.0357 0.3691 +vn -0.9491 0.0952 0.3004 +vn -0.9096 -0.0276 0.4146 +vn -0.9397 0.0132 0.3417 +vn -0.9584 0.0381 0.2829 +vn -0.9449 -0.0397 0.3249 +vn -0.0106 0.9998 -0.0146 +vn -0.0090 0.9993 -0.0376 +vn 0.0000 1.0000 0.0001 +vn -0.0534 0.9907 -0.1250 +vn -0.0845 0.9840 -0.1568 +vn -0.0447 -0.9893 0.1390 +vn 0.0044 -0.9999 0.0148 +vn -0.0018 -0.9925 0.1226 +vn 0.0461 -0.9989 0.0069 +vn 0.0474 -0.9986 0.0221 +vn 0.0624 -0.9932 0.0981 +vn 0.0494 -0.9969 0.0605 +vn -0.0579 -0.9981 0.0189 +vn -0.0528 -0.9986 -0.0075 +vn 0.0035 -0.9999 0.0096 +vn 0.0346 -0.9949 0.0943 +vn 0.0177 -0.9992 -0.0367 +vn 0.0138 -0.9999 -0.0105 +vn 0.1748 -0.9836 0.0449 +vn 0.0425 -0.9924 0.1158 +vn 0.0049 -0.9999 0.0124 +vn -0.6677 -0.0068 0.7444 +vn -0.6803 -0.0037 0.7329 +vn -0.4792 -0.0625 0.8755 +vn -0.1250 0.0547 0.9906 +vn 0.0279 0.0591 0.9979 +vn 0.0322 0.0592 0.9977 +vn 0.1881 0.0622 0.9802 +vn 0.1533 -0.6459 0.7479 +vn 0.0371 -0.8182 0.5738 +vn 0.2228 -0.5086 0.8317 +vn 0.2466 -0.4544 0.8560 +vn 0.5727 0.0622 0.8174 +vn 0.5715 0.0300 0.8200 +vn 0.6574 0.0867 0.7485 +vn 0.7819 -0.0676 0.6198 +vn 0.8348 -0.1595 0.5270 +vn 0.8816 0.4218 0.2120 +vn 0.9627 -0.2555 -0.0887 +vn 0.9586 -0.2702 -0.0896 +vn 0.8657 -0.4902 -0.1014 +vn 0.8236 -0.5576 -0.1041 +vn 0.8456 0.0522 -0.5312 +vn 0.8449 0.0617 -0.5314 +vn 0.8482 -0.0793 -0.5236 +vn 0.8477 -0.0914 -0.5225 +vn 0.4552 0.4002 -0.7954 +vn 0.3366 -0.5695 -0.7499 +vn 0.1151 0.5840 -0.8035 +vn -0.0910 -0.6964 -0.7119 +vn -0.2408 0.3828 -0.8919 +vn -0.5478 -0.2942 -0.7831 +vn -0.5441 -0.3084 -0.7803 +vn 0.0418 -0.9983 0.0407 +vn 0.0116 -0.9999 0.0100 +vn 0.0295 -0.9993 -0.0249 +vn -0.0350 -0.9943 -0.1007 +vn 0.0292 -0.9810 -0.1920 +vn 0.0712 -0.9970 -0.0301 +vn 0.0924 -0.9843 0.1501 +vn 0.1186 -0.9883 0.0954 +vn 0.1759 -0.9836 0.0403 +vn 0.0445 -0.9984 0.0344 +vn 0.0567 -0.9964 0.0634 +vn -0.0056 -0.9999 0.0084 +vn -0.0077 -0.9999 -0.0107 +vn 0.0240 -0.9997 0.0033 +vn 0.1560 -0.9826 0.1009 +vn 0.1959 0.9380 -0.2861 +vn 0.1593 -0.9685 0.1916 +vn -0.1362 -0.9692 0.2050 +vn -0.1599 -0.9573 0.2407 +vn 0.0293 0.9985 -0.0454 +vn -0.0090 0.9993 -0.0362 +vn 0.0725 0.9966 -0.0384 +vn 0.0108 0.9999 0.0112 +vn 0.0600 0.9960 0.0660 +vn 0.1078 0.9801 0.1668 +vn 0.0926 0.9934 0.0682 +vn 0.0239 0.9997 -0.0093 +vn 0.1032 0.9735 -0.2042 +vn -0.0426 0.9969 -0.0658 +vn 0.0125 0.9999 -0.0024 +vn -0.0086 0.9999 0.0127 +vn 0.0567 0.9873 0.1481 +vn 0.0654 0.9831 0.1708 +vn 0.2663 0.9592 0.0946 +vn 0.1162 0.9900 0.0795 +vn 0.0476 0.9988 -0.0091 +vn -0.0041 0.9935 -0.1138 +vn -0.0188 0.9998 -0.0118 +vn 0.0063 0.9999 0.0112 +vn -0.6916 -0.0363 0.7213 +vn -0.6915 -0.0490 0.7207 +vn -0.5670 -0.1052 0.8170 +vn -0.3220 0.6803 0.6584 +vn -0.2496 -0.4811 0.8403 +vn 0.0559 0.2785 0.9588 +vn 0.0534 0.2368 0.9701 +vn 0.1533 0.4091 0.8995 +vn 0.2547 0.4164 0.8728 +vn 0.3985 0.4708 0.7871 +vn 0.4182 0.5049 0.7551 +vn 0.3335 -0.8592 0.3880 +vn 0.5503 0.8109 0.1991 +vn 0.9967 -0.0794 -0.0147 +vn 0.9916 -0.0556 0.1166 +vn 0.9971 -0.0733 0.0224 +vn 0.9896 -0.0954 -0.1076 +vn 0.6915 -0.7043 -0.1606 +vn 0.6777 0.6605 -0.3233 +vn 0.5933 -0.5187 -0.6156 +vn 0.4451 -0.0070 -0.8954 +vn 0.2694 0.0826 -0.9595 +vn 0.3518 0.0416 -0.9352 +vn 0.1696 0.1290 -0.9770 +vn -0.1785 0.2180 -0.9595 +vn -0.5636 -0.1704 -0.8083 +vn -0.5616 -0.1797 -0.8076 +vn -0.5881 -0.0213 -0.8085 +vn -0.5892 -0.0116 -0.8079 +vn 0.0576 -0.9970 0.0518 +vn 0.0094 -0.9999 0.0078 +vn -0.0028 -0.9996 -0.0294 +vn 0.0055 -0.7708 -0.6370 +vn 0.0422 -0.9990 -0.0178 +vn 0.0674 -0.9941 0.0852 +vn 0.0060 -1.0000 0.0078 +vn -0.0228 -0.9997 0.0007 +vn -0.0371 -0.9993 0.0011 +vn -0.0176 -0.9998 -0.0095 +vn -0.0347 -0.9947 -0.0965 +vn -0.0011 -0.9999 -0.0114 +vn -0.0417 -0.9924 -0.1160 +vn 0.9575 -0.1527 -0.2447 +vn 0.9245 0.2881 -0.2495 +vn 0.9590 -0.1418 -0.2454 +vn -0.0038 -0.9992 -0.0406 +vn 0.0829 0.9920 -0.0952 +vn 0.0848 0.9848 -0.1513 +vn 0.0546 0.9984 -0.0168 +vn 0.0758 0.9931 -0.0894 +vn 0.0251 0.9996 -0.0096 +vn -0.0134 0.9999 0.0070 +vn 0.0228 0.9997 -0.0030 +vn 0.0068 0.9998 -0.0183 +vn -0.0208 0.9996 -0.0187 +vn -0.0529 0.9877 -0.1473 +vn -0.0618 0.9831 -0.1720 +vn 0.2322 0.9711 -0.0558 +vn -0.0293 0.9993 0.0238 +vn -0.0143 0.9851 -0.1713 +vn -0.0273 0.9962 0.0832 +vn 0.0301 0.9982 0.0522 +vn 0.0846 0.9963 0.0151 +vn -0.7099 0.0686 0.7010 +vn -0.6622 0.0732 0.7458 +vn -0.3800 -0.2965 0.8762 +vn -0.3776 -0.3092 0.8728 +vn 0.2363 0.4217 -0.8754 +vn 0.0816 0.6669 -0.7406 +vn 0.3725 0.4045 -0.8352 +vn 0.4524 0.2417 -0.8584 +vn 0.4488 0.3212 -0.8339 +vn 0.5022 -0.3146 -0.8055 +vn 0.6869 0.5073 -0.5204 +vn 0.9211 0.2994 -0.2489 +vn 0.9673 -0.0873 0.2383 +vn 0.9695 0.0535 0.2393 +vn 0.9690 -0.0639 0.2387 +vn 0.8404 -0.3370 -0.4244 +vn 0.6531 -0.7372 0.1734 +vn 0.7426 0.6010 0.2955 +vn 0.6183 -0.3022 0.7256 +vn 0.6135 -0.3210 0.7216 +vn 0.6462 -0.1593 0.7464 +vn 0.6470 -0.1533 0.7469 +vn -0.3088 -0.1927 0.9314 +vn -0.3286 0.0341 0.9438 +vn -0.1435 0.0602 0.9878 +vn -0.1476 -0.1017 0.9838 +vn 0.1186 -0.0034 0.9929 +vn 0.1187 -0.0018 0.9929 +vn -0.2574 0.1828 -0.9488 +vn -0.3529 0.0981 -0.9305 +vn -0.5142 -0.0633 -0.8553 +vn -0.5900 -0.1502 -0.7933 +vn 0.0078 -0.9998 -0.0208 +vn 0.0782 -0.9922 -0.0969 +vn -0.0128 -0.9998 -0.0145 +vn -0.0767 -0.9914 -0.1061 +vn -0.0856 -0.9787 -0.1869 +vn -0.0147 -0.9992 -0.0377 +vn 0.0901 -0.9708 -0.2224 +vn 0.6949 0.6971 -0.1764 +vn 0.1311 -0.9875 -0.0879 +vn 0.1503 -0.9848 -0.0872 +vn 0.0071 0.9999 -0.0092 +vn 0.0887 0.9892 -0.1171 +vn 0.1035 0.9839 -0.1457 +vn 0.1219 0.9899 -0.0725 +vn 0.0571 0.9981 0.0235 +vn 0.0129 0.9999 0.0105 +vn 0.0629 0.9925 0.1048 +vn 0.0529 0.9986 0.0100 +vn 0.0229 0.9996 0.0155 +vn 0.0145 0.9999 0.0032 +vn 0.0265 0.9995 0.0145 +vn 0.1523 0.9873 0.0445 +vn 0.1588 0.9869 0.0289 +vn 0.0625 0.9967 0.0512 +vn 0.2969 0.8597 -0.4157 +vn -0.0505 0.9974 -0.0512 +vn 0.1197 0.9879 -0.0986 +vn 0.2248 0.9738 -0.0350 +vn 0.0382 0.9986 0.0362 +vn -0.4568 -0.0656 0.8871 +vn -0.4572 -0.0786 0.8859 +vn -0.4284 0.2255 0.8750 +vn -0.4269 0.2344 0.8734 +vn 0.0679 -0.2481 0.9663 +vn 0.0676 -0.2513 0.9656 +vn 0.3308 -0.0473 0.9425 +vn 0.2376 -0.0715 0.9687 +vn 0.4727 0.3576 0.8054 +vn 0.4715 0.3682 0.8013 +vn 0.6923 -0.4591 0.5568 +vn 0.6654 0.6413 0.3820 +vn 0.7884 -0.5599 0.2547 +vn 0.2117 0.9711 -0.1105 +vn 0.9955 -0.0034 0.0942 +vn 0.9984 -0.0561 0.0045 +vn 0.9911 -0.1059 -0.0809 +vn 0.9730 -0.1567 -0.1695 +vn 0.3898 -0.6136 -0.6867 +vn 0.2079 -0.4551 -0.8658 +vn 0.3441 -0.5621 -0.7520 +vn 0.1219 -0.4061 -0.9057 +vn 0.0661 -0.5828 -0.8099 +vn 0.0646 -0.5892 -0.8054 +vn -0.1546 0.6281 -0.7626 +vn -0.2837 -0.7994 -0.5297 +vn -0.5601 0.3106 -0.7680 +vn 0.8163 -0.4557 0.3548 +vn -0.3035 0.3847 0.8717 +vn -0.7462 -0.5282 0.4052 +vn -0.6258 0.5224 -0.5792 +vn -0.0724 -0.4292 -0.9003 +vn 0.8931 0.4339 -0.1191 +vn 0.0215 -0.9998 0.0029 +vn 0.0414 -0.9991 -0.0103 +vn 0.0798 -0.9919 -0.0989 +vn 0.0078 -0.9999 -0.0102 +vn -0.0312 -0.9921 -0.1217 +vn 0.0116 -0.9994 -0.0316 +vn 0.0394 -0.9760 -0.2141 +vn 0.0666 -0.9973 0.0312 +vn 0.0379 -0.9990 0.0255 +vn 0.0925 -0.9843 0.1505 +vn 0.0833 -0.9928 0.0861 +vn 0.1276 -0.9914 0.0283 +vn 0.0219 -0.9987 0.0462 +vn 0.0144 -0.9997 0.0191 +vn -0.0116 -0.9997 -0.0213 +vn -0.0339 -0.9950 -0.0941 +vn 0.0627 -0.9965 0.0560 +vn 0.2741 -0.9597 0.0617 +vn 0.0062 -0.9998 0.0185 +vn 0.0131 0.9999 -0.0069 +vn 0.0606 0.9978 0.0262 +vn 0.0136 0.9998 0.0111 +vn 0.0725 0.9897 0.1236 +vn 0.0559 0.9984 0.0098 +vn 0.0624 0.9959 0.0662 +vn 0.0208 0.9969 -0.0758 +vn -0.0185 0.9998 -0.0117 +vn -0.0567 0.9873 -0.1481 +vn -0.0654 0.9831 -0.1708 +vn 0.1552 0.9872 0.0375 +vn 0.0046 1.0000 0.0088 +vn 0.0210 0.9998 0.0025 +vn 0.0362 0.9993 -0.0023 +vn -0.0070 0.9951 -0.0983 +vn -0.0199 0.9997 -0.0123 +vn -0.7333 0.0638 0.6770 +vn -0.7680 0.0015 0.6404 +vn -0.7620 0.0670 0.6441 +vn -0.5497 0.1550 0.8209 +vn -0.3536 -0.6200 0.7004 +vn -0.2135 0.5567 0.8028 +vn 0.0598 -0.5453 0.8361 +vn 0.0580 -0.5561 0.8291 +vn 0.3535 -0.0309 0.9349 +vn 0.2486 -0.0620 0.9666 +vn 0.4695 0.3634 0.8047 +vn 0.4684 0.3732 0.8008 +vn 0.6868 -0.5075 0.5203 +vn 0.9641 0.0085 0.2653 +vn 0.9736 0.0061 0.2282 +vn 0.9749 0.0873 0.2046 +vn 0.9635 0.2089 0.1671 +vn 0.7569 -0.6274 -0.1828 +vn 0.7649 0.5833 -0.2733 +vn 0.5904 -0.4771 -0.6511 +vn 0.6352 0.1541 -0.7568 +vn -0.3970 0.1181 -0.9102 +vn -0.3997 -0.0225 -0.9164 +vn -0.3912 -0.2074 -0.8966 +vn -0.1116 -0.3358 -0.9353 +vn -0.0124 -0.2843 -0.9586 +vn 0.0494 -0.2504 -0.9669 +vn 0.1345 -0.2014 -0.9702 +vn -0.1903 0.5518 -0.8120 +vn -0.5577 -0.3305 -0.7614 +vn 0.9187 -0.3950 -0.0010 +vn 0.9436 -0.3284 0.0418 +vn 0.9691 -0.2234 0.1050 +vn 0.9791 -0.1215 0.1631 +vn 0.0216 0.1097 0.9937 +vn 0.0628 -0.0871 0.9942 +vn 0.0217 -0.0725 0.9971 +vn -0.2902 -0.3036 0.9075 +vn -0.9553 0.2954 0.0136 +vn -0.6011 -0.5832 -0.5464 +vn 0.0412 0.4123 -0.9101 +vn -0.0159 -0.9999 0.0045 +vn 0.0183 -0.9998 0.0046 +vn 0.0587 -0.9945 -0.0863 +vn 0.0347 -0.9994 -0.0084 +vn 0.0612 -0.9933 -0.0980 +vn -0.0188 -0.9951 -0.0967 +vn 0.0067 -0.9998 -0.0192 +vn 0.0018 -0.9917 -0.1283 +vn -0.0288 -0.9994 -0.0170 +vn -0.0092 -0.9992 0.0383 +vn -0.0111 -0.9997 -0.0220 +vn -0.0424 -0.9921 -0.1182 +vn 0.0353 -0.9990 -0.0256 +vn 0.0214 -0.9997 -0.0096 +vn 0.1403 -0.9895 0.0337 +vn -0.0485 -0.9828 0.1782 +vn 0.1050 -0.9933 0.0485 +vn -0.0521 -0.9880 -0.1451 +vn 0.0925 -0.9937 0.0633 +vn 0.0250 -0.9997 -0.0012 +vn 0.2144 -0.9761 -0.0348 +vn 0.1284 -0.9898 -0.0611 +vn 0.4859 -0.3978 -0.7782 +vn 0.4859 -0.3976 -0.7783 +vn 0.4420 -0.2373 -0.8651 +vn 0.1100 -0.9902 -0.0858 +vn 0.4672 -0.5036 0.7267 +vn 0.4675 -0.5027 0.7271 +vn 0.4563 -0.5329 0.7126 +vn 0.0335 0.9967 -0.0738 +vn 0.0571 0.9981 0.0211 +vn 0.0129 0.9999 0.0106 +vn 0.0632 0.9924 0.1051 +vn 0.0635 0.9975 0.0316 +vn 0.1273 0.9627 0.2389 +vn 0.0145 0.9999 0.0028 +vn 0.0283 0.9995 0.0103 +vn 0.1718 0.9845 0.0340 +vn 0.2466 0.9674 0.0584 +vn 0.1087 0.9927 -0.0522 +vn 0.4192 0.5341 -0.7342 +vn 0.0963 0.9933 -0.0636 +vn 0.1770 0.9835 -0.0364 +vn -0.0271 0.9996 -0.0091 +vn -0.0463 0.9916 -0.1209 +vn -0.0533 0.9888 -0.1393 +vn 0.1428 0.9871 0.0729 +vn 0.0259 0.9997 0.0029 +vn 0.3335 0.9413 0.0519 +vn 0.1091 0.9906 0.0826 +vn 0.0460 0.9986 0.0249 +vn 0.0285 0.9990 -0.0343 +vn -0.0133 0.9896 -0.1429 +vn -0.0328 0.9992 -0.0208 +vn 0.2870 0.7921 0.5388 +vn -0.6191 -0.0856 0.7806 +vn -0.6625 -0.0351 0.7483 +vn -0.4573 -0.0744 0.8862 +vn -0.3749 0.4603 0.8047 +vn 0.0543 -0.5992 0.7987 +vn 0.0525 -0.6103 0.7904 +vn 0.0603 -0.2049 0.9769 +vn 0.4561 -0.5335 0.7123 +vn 0.9443 0.2621 0.1990 +vn 0.9474 -0.2481 -0.2021 +vn 0.3037 -0.3179 -0.8982 +vn 0.2165 -0.2935 -0.9311 +vn 0.0841 -0.3870 -0.9182 +vn -0.2177 0.5128 -0.8304 +vn -0.5573 -0.3276 -0.7630 +vn 0.7394 0.5459 0.3941 +vn -0.0645 -0.5415 0.8382 +vn -0.7201 0.5472 0.4265 +vn -0.5932 -0.5350 -0.6016 +vn -0.1107 0.3555 -0.9281 +vn 0.8354 -0.4638 -0.2948 +vn -0.0741 0.3785 0.9226 +vn -0.5558 -0.5646 0.6102 +vn -0.7548 0.5218 -0.3974 +vn -0.3758 -0.3413 -0.8616 +vn 0.9206 0.3860 -0.0585 +vn 0.8432 -0.4024 -0.3565 +vn 0.7891 0.3681 0.4917 +vn 0.4390 -0.5225 0.7309 +vn -0.8556 0.4924 0.1600 +vn -0.9729 -0.1690 -0.1580 +vn 0.9267 0.3396 0.1607 +vn 0.6723 -0.3750 0.6383 +vn -0.6422 0.3544 0.6797 +vn -0.6450 0.3756 0.6655 +vn -0.6469 0.3945 0.6526 +vn -0.6484 0.4070 0.6434 +vn -0.5167 -0.4451 -0.7313 +vn -0.0753 0.4155 -0.9065 +vn 0.8782 -0.1360 -0.4585 +vn 0.8881 -0.3844 0.2520 +vn 0.4323 0.3693 0.8226 +vn -0.5422 -0.4422 0.7145 +vn -0.8978 0.3825 0.2183 +vn -0.6655 -0.3216 -0.6736 +vn -0.3618 0.1107 -0.9256 +vn 0.4025 -0.0152 -0.9153 +vn 0.8054 0.4312 -0.4067 +vn 0.9510 -0.2018 0.2343 +vn -0.1288 0.2536 0.9587 +vn -0.1067 0.2086 0.9722 +vn -0.0823 0.1589 0.9839 +vn -0.0641 0.1218 0.9905 +vn -0.9627 -0.1349 -0.2343 +vn -0.9581 -0.0481 -0.2825 +vn -0.9372 0.0679 -0.3420 +vn -0.9107 0.1545 -0.3830 +vn 0.5252 -0.1215 -0.8423 +vn 0.7132 0.4727 -0.5176 +vn 0.9081 -0.1400 0.3947 +vn 0.9097 -0.2018 0.3630 +vn 0.9049 -0.2837 0.3173 +vn 0.8930 -0.3589 0.2716 +vn -0.3946 0.3454 0.8515 +vn -0.7558 -0.5106 0.4099 +vn -0.8790 0.2408 -0.4116 +vn -0.0663 -0.5616 -0.8247 +vn 0.4622 0.0957 -0.8816 +vn 0.0408 -0.0051 0.9992 +vn 0.0067 0.0020 1.0000 +vn 0.0360 -0.0041 0.9993 +vn 0.0028 0.0028 1.0000 +vn -0.8778 0.0087 -0.4789 +vn -0.9901 0.0466 -0.1322 +vn -0.9903 0.0055 -0.1390 +vn -0.8742 -0.0010 -0.4855 +vn -0.9949 -0.0347 -0.0944 +vn -0.7814 0.1075 0.6148 +vn -0.8065 0.0364 0.5901 +vn -0.7961 0.1617 0.5832 +vn 0.6831 -0.2892 0.6706 +vn 0.3714 0.2460 0.8953 +vn -0.7499 0.2201 0.6239 +vn -0.6944 0.0706 0.7161 +vn -0.6693 0.4159 -0.6157 +vn -0.7923 0.2733 -0.5455 +vn -0.8037 0.2572 -0.5365 +vn -0.9068 0.0647 -0.4166 +vn -0.0618 0.2224 -0.9730 +vn 0.4720 -0.3184 -0.8221 +vn 0.9108 0.3048 -0.2784 +vn -0.0023 1.0000 0.0045 +vn 0.0001 0.9999 -0.0120 +vn 0.0048 1.0000 -0.0054 +vn 0.0188 0.9998 0.0043 +vn 0.0069 0.9999 -0.0126 +vn -0.7546 0.0258 0.6556 +vn -0.7387 -0.0246 0.6735 +vn -0.9892 -0.0432 -0.1399 +vn -0.9892 -0.0427 -0.1400 +vn -0.9892 -0.0424 -0.1402 +vn -0.9892 -0.0422 -0.1403 +vn -0.9253 0.0035 0.3792 +vn -0.8958 0.0012 -0.4445 +vn -0.8104 0.0073 -0.5859 +vn -0.9897 -0.0175 -0.1419 +vn -0.9909 -0.0448 -0.1269 +vn -0.9908 -0.0511 -0.1251 +vn -0.9887 -0.0534 -0.1399 +vn -0.9887 -0.0507 -0.1408 +vn -0.9888 -0.0372 -0.1447 +vn -0.9887 -0.0334 -0.1458 +vn -0.9821 0.0701 -0.1750 +vn -0.9838 0.0545 -0.1707 +vn -0.9875 0.0070 -0.1574 +vn -0.9881 -0.0070 -0.1534 +vn -0.9887 -0.0535 -0.1399 +vn -0.9887 -0.0556 -0.1393 +vn -0.9885 -0.0640 -0.1369 +vn -0.9885 -0.0664 -0.1361 +vn -0.9872 -0.0974 -0.1265 +vn -0.9876 -0.0902 -0.1288 +vn -0.9886 -0.0610 -0.1375 +vn -0.9888 -0.0536 -0.1396 +vn -0.9873 -0.0061 -0.1589 +vn -0.9888 -0.0199 -0.1481 +vn -0.9894 -0.0263 -0.1431 +vn -0.9903 -0.0390 -0.1333 +vn -0.7642 0.0919 0.6384 +vn -0.1576 0.9810 -0.1133 +vn -0.0836 0.9928 -0.0857 +vn -0.0022 0.9985 -0.0549 +vn 0.7646 0.0507 0.6425 +vn 0.7820 0.0998 0.6153 +vn 0.7937 0.1375 0.5926 +vn 0.9740 -0.2259 -0.0164 +vn 0.7439 -0.0002 0.6683 +vn 0.8054 0.0136 -0.5925 +vn 0.8044 0.0099 -0.5940 +vn 0.8029 0.0044 -0.5961 +vn 0.8019 0.0009 -0.5975 +vn 0.0179 -0.9995 -0.0250 +vn 0.0198 -0.9995 -0.0257 +vn 0.0157 -0.9996 -0.0242 +vn -0.0744 -0.9968 0.0280 +vn 0.0214 -0.9994 -0.0266 +vn -0.0070 0.9929 -0.1188 +vn 0.0269 0.9944 0.1025 +vn -0.0018 0.9965 -0.0831 +vn -0.6656 0.0816 0.7419 +vn 0.0659 -0.1011 0.9927 +vn 0.8586 0.0841 0.5058 +vn 0.5593 0.0100 -0.8289 +vn 0.6853 -0.0384 -0.7272 +vn 0.6600 -0.0281 -0.7507 +vn 0.5108 0.0271 -0.8593 +vn -0.9176 0.0123 -0.3974 +vn -0.9574 0.0467 -0.2849 +vn -0.9521 0.0414 -0.3029 +vn -0.9077 0.0052 -0.4195 +vn -0.1599 0.9330 0.3224 +vn -0.0091 0.9885 0.1508 +vn 0.0223 0.9932 0.1141 +vn 0.8538 0.2531 0.4549 +vn 0.9029 0.1769 0.3918 +vn 0.8430 0.2950 0.4498 +vn 0.0306 0.9962 -0.0821 +vn -0.2170 0.8971 0.3849 +vn -0.2417 0.9612 -0.1326 +vn -0.5347 0.0957 0.8396 +vn -0.5835 0.0389 0.8112 +vn -0.5291 0.1019 0.8424 +vn -0.4916 0.1421 0.8591 +vn 0.3171 -0.1888 0.9294 +vn 0.8995 0.1803 0.3980 +vn 0.9553 0.0575 0.2900 +vn 0.6168 -0.1683 -0.7689 +vn 0.1917 0.3045 -0.9330 +vn -0.4623 0.0455 -0.8856 +vn -0.8063 0.2337 -0.5434 +vn -0.9796 -0.1133 -0.1661 +vn -0.6160 0.0321 0.7871 +vn 0.7320 -0.6203 -0.2816 +vn -0.1972 -0.7882 -0.5829 +vn -0.0370 0.9501 -0.3096 +vn -0.0282 -0.9980 0.0572 +vn -0.0164 -0.9992 -0.0376 +vn 0.0320 0.9863 -0.1619 +vn 0.0598 0.9979 0.0247 +vn 0.0373 0.9911 -0.1275 +vn -0.7403 0.0651 0.6691 +vn -0.8838 -0.0033 0.4679 +vn -0.8595 0.0105 0.5110 +vn -0.6928 0.0830 0.7163 +vn 0.8596 0.0751 0.5054 +vn 0.6739 0.0274 0.7383 +vn 0.7093 0.0355 0.7040 +vn 0.8838 0.0827 0.4606 +vn 0.9924 0.0119 -0.1221 +vn 0.4576 0.1042 -0.8830 +vn -0.2981 -0.0573 -0.9528 +vn -0.8738 0.0562 -0.4830 +vn 0.1659 0.9845 0.0567 +vn 0.1895 0.9793 -0.0707 +vn 0.1588 0.9832 0.0905 +vn 0.1293 0.9653 0.2267 +vn -0.2505 0.9574 -0.1438 +vn -0.1472 0.9886 0.0329 +vn -0.0886 0.9915 0.0954 +vn 0.0010 0.9926 -0.1217 +vn -0.0517 0.9886 -0.1412 +vn -0.8294 -0.0867 0.5519 +vn -0.5409 0.2814 0.7926 +vn 0.3110 0.1454 0.9392 +vn 0.1662 0.0647 0.9840 +vn 0.2912 0.1343 0.9472 +vn 0.4165 0.2048 0.8858 +vn 0.9145 -0.2599 0.3100 +vn 0.8309 0.3030 -0.4668 +vn 0.4069 0.0541 -0.9119 +vn 0.3581 -0.0168 -0.9335 +vn 0.3544 -0.0220 -0.9349 +vn 0.3172 -0.0731 -0.9455 +vn -0.8425 0.0892 -0.5313 +vn -0.8697 0.0337 -0.4925 +vn -0.8753 0.0208 -0.4832 +vn -0.8984 -0.0398 -0.4374 +vn -0.6113 -0.7656 -0.2004 +vn 0.2551 -0.2581 0.9318 +vn 0.3335 -0.5978 -0.7290 +vn 0.0041 0.9419 -0.3359 +vn -0.0255 -0.9994 0.0253 +vn 0.0375 -0.9993 -0.0091 +vn -0.0055 0.9997 0.0223 +vn -0.7270 -0.0340 0.6858 +vn -0.6828 -0.0153 0.7305 +vn -0.5139 0.0475 0.8565 +vn -0.4374 0.0726 0.8963 +vn 0.9764 -0.0213 0.2147 +vn 0.9171 0.0363 0.3971 +vn 0.9656 -0.0074 0.2600 +vn 0.9039 0.0455 0.4254 +vn 0.1427 0.0292 -0.9893 +vn -0.1130 0.0851 -0.9899 +vn -0.2221 0.1092 -0.9689 +vn -0.2945 0.1237 -0.9476 +vn -0.3000 0.1229 -0.9460 +vn 0.1411 0.9899 0.0147 +vn 0.0581 0.9909 -0.1216 +vn 0.0066 0.9888 -0.1490 +vn -0.0909 0.9757 -0.1992 +vn -0.1675 0.9568 -0.2376 +vn -0.0954 0.8356 0.5410 +vn -0.0977 0.9948 0.0287 +vn -0.9880 0.1544 -0.0022 +vn -0.9885 0.0091 0.1510 +vn -0.9872 0.0008 0.1595 +vn -0.9465 -0.1332 0.2940 +vn -0.1558 0.1372 0.9782 +vn -0.1128 0.0822 0.9902 +vn -0.0950 0.0596 0.9937 +vn -0.0433 -0.0059 0.9990 +vn 0.9415 -0.1089 0.3189 +vn 0.9846 0.1039 0.1404 +vn 0.9829 0.0694 0.1705 +vn 0.9627 0.2704 -0.0124 +vn 0.6304 0.0803 -0.7721 +vn 0.6052 0.1029 -0.7894 +vn 0.6283 0.0822 -0.7737 +vn 0.6551 0.0575 -0.7533 +vn -0.4961 -0.1063 -0.8617 +vn -0.5676 -0.0172 -0.8231 +vn -0.5643 -0.0223 -0.8253 +vn -0.6366 0.0791 -0.7672 +vn -0.8572 -0.4656 0.2202 +vn 0.3059 -0.7809 0.5446 +vn 0.5504 -0.4455 -0.7061 +vn -0.0245 -0.9984 0.0507 +vn -0.0151 -0.9986 -0.0514 +vn -0.0184 0.9993 -0.0333 +vn -0.9407 -0.0834 -0.3290 +vn -0.5886 0.0973 0.8025 +vn 0.1525 -0.0361 0.9876 +vn 0.9494 0.0920 0.3004 +vn 0.8516 -0.0804 -0.5179 +vn -0.3286 0.1284 -0.9357 +vn 0.2059 0.9567 -0.2057 +vn 0.1659 0.9859 -0.0202 +vn 0.2273 0.9418 -0.2478 +vn 0.1964 0.9729 0.1218 +vn -0.1936 0.8914 0.4099 +vn 0.0431 0.9857 0.1630 +vn -0.2483 0.8407 0.4813 +vn -0.2713 0.9484 -0.1643 +vn -0.2998 0.9340 -0.1945 +vn -0.1532 0.9873 -0.0431 +vn -0.1246 0.9921 -0.0141 +vn -0.8128 0.2038 -0.5457 +vn -0.8350 0.1666 -0.5244 +vn -0.8424 0.1533 -0.5165 +vn -0.8696 0.0997 -0.4836 +vn -0.8566 -0.1761 0.4850 +vn -0.4459 0.2494 0.8596 +vn 0.1091 -0.2003 0.9736 +vn 0.8260 0.1698 0.5375 +vn 0.9659 -0.2542 0.0496 +vn 0.6417 0.2635 -0.7203 +vn 0.1504 -0.2290 -0.9617 +vn -0.6558 -0.7537 -0.0425 +vn 0.3245 -0.4885 0.8100 +vn 0.3411 -0.5223 -0.7816 +vn -0.0049 -0.9996 0.0279 +vn 0.0016 -0.9999 -0.0162 +vn -0.0370 0.9984 0.0432 +vn -0.7754 0.0709 -0.6275 +vn -0.9933 -0.0430 0.1071 +vn -0.0679 0.0946 0.9932 +vn -0.6108 0.5501 0.5695 +vn -0.6796 0.2196 0.7000 +vn -0.7177 0.2480 0.6506 +vn 0.9378 -0.0916 0.3349 +vn 0.7786 0.1074 -0.6183 +vn -0.1333 -0.0306 -0.9906 +vn -0.0293 0.9908 -0.1324 +vn -0.0558 0.9860 -0.1569 +vn -0.1679 0.9661 -0.1963 +vn -0.1376 0.9889 -0.0570 +vn 0.0409 0.9985 0.0364 +vn 0.7200 0.5025 -0.4786 +vn 0.8214 0.1868 -0.5389 +vn 0.7759 0.0632 -0.6276 +vn -0.6876 0.2453 0.6833 +vn -0.1119 0.9936 0.0116 +vn -0.5933 0.0603 -0.8027 +vn -0.5729 0.0924 -0.8144 +vn -0.5670 0.1013 -0.8175 +vn -0.5388 0.1427 -0.8303 +vn -0.9743 -0.2157 0.0648 +vn -0.6468 0.1676 0.7440 +vn -0.5799 0.0956 0.8091 +vn 0.4226 0.1192 0.8985 +vn 0.5438 -0.0441 0.8381 +vn 0.5728 -0.0886 0.8149 +vn 0.6511 -0.2260 0.7246 +vn 0.7975 0.0857 -0.5972 +vn 0.7253 -0.0667 -0.6852 +vn -0.1944 -0.5482 -0.8135 +vn -0.2459 0.1117 0.9628 +vn 0.4754 -0.8797 -0.0141 +vn -0.0108 -0.9991 0.0417 +vn 0.0018 0.9992 0.0406 +vn -0.8962 0.0369 0.4422 +vn -0.9895 -0.0407 0.1388 +vn -0.8451 0.0613 0.5311 +vn 0.8184 0.0657 0.5709 +vn 0.5797 -0.0253 0.8145 +vn 0.6413 -0.0046 0.7673 +vn 0.8599 0.0860 0.5031 +vn 0.4891 -0.0552 -0.8705 +vn -0.1523 0.1053 -0.9827 +vn -0.9964 -0.0593 0.0613 +vn 0.0727 0.9924 0.0995 +vn 0.1037 0.9883 0.1119 +vn 0.2481 0.9635 0.1000 +vn 0.1268 0.9899 -0.0631 +vn -0.0945 0.9817 -0.1651 +vn -0.0973 0.9729 -0.2097 +vn -0.3013 0.8059 0.5096 +vn -0.1380 0.9904 -0.0115 +vn -0.1105 0.9938 0.0116 +vn -0.5740 -0.0060 0.8189 +vn -0.6179 -0.0795 0.7822 +vn -0.5505 0.0301 0.8343 +vn -0.5012 0.1008 0.8594 +vn 0.5690 -0.0877 0.8177 +vn 0.8519 0.2434 0.4637 +vn 0.9826 -0.1856 0.0084 +vn 0.2274 0.1073 -0.9679 +vn 0.2627 0.0592 -0.9631 +vn 0.2536 0.0716 -0.9647 +vn 0.2839 0.0295 -0.9584 +vn -0.8709 -0.0125 -0.4914 +vn -0.8490 -0.0588 -0.5251 +vn -0.8766 0.0010 -0.4812 +vn -0.8939 0.0463 -0.4458 +vn -0.6137 -0.7892 -0.0228 +vn -0.1319 -0.7818 0.6094 +vn 0.5343 -0.7768 0.3334 +vn 0.1489 -0.4691 -0.8705 +vn 0.0121 -0.9999 0.0034 +vn -0.0758 0.9969 -0.0222 +vn -0.7094 0.1107 0.6961 +vn -0.1772 -0.0129 0.9841 +vn 0.9979 0.0430 0.0478 +vn 0.9974 0.0390 0.0608 +vn 0.9938 0.0244 0.1083 +vn 0.9923 0.0200 0.1222 +vn -0.2017 0.0448 -0.9784 +vn -0.1041 0.0223 -0.9943 +vn -0.1235 0.0268 -0.9920 +vn -0.2208 0.0492 -0.9741 +vn -0.9986 -0.0245 -0.0468 +vn -0.1349 0.9746 0.1788 +vn -0.1599 0.9861 0.0458 +vn 0.0337 0.9835 0.1777 +vn 0.2169 0.9604 0.1752 +vn -0.2119 0.9680 -0.1348 +vn 0.1511 0.9874 0.0462 +vn 0.1227 0.9922 0.0232 +vn -0.0955 0.9861 -0.1360 +vn -0.0312 0.9917 -0.1249 +vn 0.2466 0.8001 -0.5469 +vn -0.8717 -0.3259 0.3661 +vn -0.4800 0.2338 0.8456 +vn 0.2516 -0.1823 0.9505 +vn 0.8380 0.2055 0.5056 +vn 0.8973 0.1085 0.4278 +vn 0.9108 0.0817 0.4047 +vn 0.9567 -0.0496 0.2868 +vn 0.5222 0.0712 -0.8499 +vn 0.6343 -0.0631 -0.7705 +vn 0.5026 0.0922 -0.8596 +vn 0.4031 0.1913 -0.8949 +vn -0.3658 -0.2156 -0.9054 +vn -0.8461 0.2672 -0.4613 +vn -0.7745 -0.5887 0.2313 +vn 0.2361 -0.7765 0.5842 +vn 0.6232 -0.7363 -0.2638 +vn -0.1426 -0.7972 -0.5866 +vn 0.0053 -1.0000 -0.0072 +vn 0.0058 0.9999 0.0137 +vn -0.7401 0.0557 0.6702 +vn -0.6736 0.0252 0.7387 +vn -0.7245 0.0486 0.6875 +vn -0.6565 0.0178 0.7541 +vn 0.9689 -0.0020 0.2476 +vn 0.9716 0.0016 0.2365 +vn 0.9802 0.0142 0.1974 +vn 0.9827 0.0183 0.1843 +vn -0.1647 0.0249 -0.9860 +vn -0.2876 -0.0121 -0.9577 +vn -0.1957 0.0157 -0.9805 +vn -0.3116 -0.0195 -0.9500 +vn -0.6723 0.7391 0.0412 +vn -0.0891 0.9909 0.1006 +vn -0.0836 0.9864 0.1418 +vn 0.0402 0.9809 0.1902 +vn 0.1142 0.9797 0.1648 +vn -0.0289 0.9938 -0.1076 +vn 0.1003 0.8098 -0.5780 +vn 0.1653 0.9854 0.0399 +vn 0.1529 0.9878 0.0311 +vn -0.7255 -0.2175 0.6530 +vn -0.1467 0.2155 0.9654 +vn 0.6678 -0.2739 0.6921 +vn 0.9292 0.2105 0.3038 +vn 0.6133 -0.2753 -0.7404 +vn 0.1583 0.3346 -0.9290 +vn -0.8031 -0.2945 -0.5180 +vn -0.9771 0.2061 0.0530 +vn 0.0618 0.0515 0.9968 +vn 0.4767 -0.7689 -0.4262 +vn -0.4662 -0.7367 -0.4899 +vn 0.0327 -0.9992 -0.0227 +vn -0.0268 -0.9996 -0.0015 +vn 0.0867 0.9957 -0.0319 +vn 0.1257 0.9908 -0.0494 +vn -0.0281 0.9994 0.0195 +vn -0.5072 -0.0478 -0.8605 +vn -0.8837 0.0703 -0.4627 +vn -0.2590 0.0136 0.9658 +vn -0.4585 -0.0431 0.8877 +vn -0.4224 -0.0326 0.9058 +vn -0.2081 0.0273 0.9777 +vn 0.9907 0.0199 0.1347 +vn 0.9983 -0.0308 -0.0498 +vn 0.9953 0.0095 0.0966 +vn 0.9958 -0.0398 -0.0828 +vn 0.2334 0.0342 -0.9718 +vn 0.0518 0.9931 -0.1052 +vn 0.0446 0.9924 -0.1144 +vn -0.1903 0.9816 0.0183 +vn -0.1161 0.9893 -0.0884 +vn -0.0881 0.9901 0.1095 +vn 0.0293 0.9864 0.1618 +vn 0.0968 0.9857 0.1376 +vn 0.1455 0.9894 0.0033 +vn -0.3481 0.2315 -0.9084 +vn -0.7923 -0.2132 -0.5717 +vn -0.9757 0.1769 0.1291 +vn -0.7757 -0.1616 0.6100 +vn -0.2535 0.1162 0.9603 +vn 0.2347 -0.2190 0.9471 +vn 0.7805 0.1635 0.6034 +vn 0.9882 -0.1493 -0.0331 +vn 0.8822 0.1620 -0.4421 +vn 0.3501 -0.2259 -0.9090 +vn -0.1918 -0.6033 -0.7741 +vn -0.0122 -0.7299 -0.6834 +vn -0.0152 -0.7282 -0.6852 +vn 0.1634 -0.8133 -0.5584 +vn -0.6300 -0.6416 0.4375 +vn -0.2507 0.4511 0.8565 +vn 0.9934 0.0993 0.0566 +vn 0.2699 0.9561 -0.1142 +vn -0.0018 -1.0000 -0.0065 +vn -0.0718 0.9959 0.0549 +vn -0.5152 0.0390 -0.8562 +vn -0.3898 0.0026 -0.9209 +vn -0.5484 0.0490 -0.8348 +vn -0.5645 -0.0218 0.8252 +vn -0.7683 0.0683 0.6365 +vn -0.6102 -0.0034 0.7923 +vn -0.8026 0.0864 0.5902 +vn 0.4631 -0.0385 0.8855 +vn 0.9955 0.0868 -0.0375 +vn 0.9649 0.0374 -0.2601 +vn 0.9940 0.0785 -0.0764 +vn 0.9515 0.0264 -0.3065 +vn -0.3584 -0.0061 -0.9335 +vn 0.0589 0.9931 -0.1011 +vn 0.0764 0.9917 -0.1031 +vn -0.0534 0.9907 -0.1252 +vn -0.1678 0.9848 -0.0456 +vn -0.0178 0.9966 0.0810 +vn -0.0098 0.9945 0.1044 +vn 0.1553 0.9820 0.1071 +vn 0.1428 0.9897 0.0137 +vn -0.1954 0.9806 0.0174 +vn -0.8638 -0.0381 -0.5024 +vn -0.8777 -0.0055 -0.4791 +vn -0.8623 -0.0414 -0.5047 +vn -0.8448 -0.0773 -0.5294 +vn -0.7773 0.1408 0.6131 +vn -0.7375 0.0519 0.6734 +vn -0.7207 0.0204 0.6930 +vn -0.6603 -0.0807 0.7467 +vn 0.5101 -0.1057 0.8536 +vn 0.6047 0.0418 0.7953 +vn 0.5769 -0.0051 0.8168 +vn 0.6532 0.1331 0.7454 +vn 0.8916 -0.0766 -0.4462 +vn 0.8873 -0.0857 -0.4531 +vn 0.8868 -0.0865 -0.4541 +vn 0.8831 -0.0940 -0.4597 +vn 0.0828 0.0341 -0.9960 +vn 0.0392 -0.0027 -0.9992 +vn 0.0441 0.0014 -0.9990 +vn -0.0032 -0.0384 -0.9993 +vn -0.4527 -0.4782 -0.7526 +vn 0.1629 -0.8143 -0.5572 +vn -0.7802 -0.4759 0.4060 +vn -0.1075 -0.7750 0.6227 +vn -0.0852 -0.7655 0.6378 +vn -0.1691 -0.7982 0.5782 +vn -0.0136 -0.7310 0.6822 +vn 0.9820 0.0638 -0.1779 +vn -0.0312 -0.9995 0.0037 +vn 0.0274 -0.9992 -0.0276 +vn 0.0255 0.9995 0.0199 +vn 0.0901 0.9959 -0.0040 +vn 0.0253 0.9995 0.0200 +vn -0.0415 0.9981 0.0446 +vn -0.9087 0.0189 -0.4170 +vn -0.9082 0.0192 -0.4181 +vn -0.9086 0.0189 -0.4172 +vn -0.9080 0.0193 -0.4186 +vn -0.3612 0.0168 0.9324 +vn -0.4036 0.0065 0.9149 +vn -0.3970 0.0081 0.9178 +vn -0.3537 0.0186 0.9352 +vn 0.8625 0.0167 0.5057 +vn 0.8753 0.0108 0.4834 +vn 0.8648 0.0157 0.5020 +vn 0.8773 0.0098 0.4798 +vn 0.4341 0.0102 -0.9008 +vn 0.4290 0.0116 -0.9032 +vn 0.4049 0.0182 -0.9142 +vn 0.3995 0.0197 -0.9165 +vn 0.0829 0.9795 0.1838 +vn 0.0040 0.9925 0.1218 +vn 0.1203 0.9918 0.0433 +vn 0.1930 0.9774 -0.0868 +vn -0.0241 0.9957 0.0898 +vn -0.0646 0.9692 -0.2375 +vn -0.0687 0.9940 -0.0849 +vn -0.0633 0.9971 -0.0414 +vn 0.0614 0.9892 -0.1330 +vn -0.5083 0.8239 0.2507 +vn -0.7878 -0.2610 -0.5579 +vn -0.8699 0.2537 0.4230 +vn -0.8349 0.1253 0.5359 +vn -0.8061 0.0557 0.5891 +vn -0.7162 -0.1025 0.6903 +vn 0.4485 0.0519 0.8923 +vn 0.4732 0.0171 0.8808 +vn 0.4848 0.0001 0.8746 +vn 0.5099 -0.0378 0.8594 +vn 0.9257 0.0289 -0.3772 +vn 0.9407 -0.0203 -0.3385 +vn 0.9207 0.0424 -0.3879 +vn 0.9030 0.0865 -0.4208 +vn 0.1282 -0.0919 -0.9875 +vn -0.2833 0.2197 -0.9335 +vn -0.4264 -0.5477 -0.7198 +vn -0.6249 -0.3771 0.6836 +vn -0.1855 -0.7508 0.6340 +vn 0.9390 0.3319 -0.0898 +vn 0.1650 -0.8093 -0.5637 +vn -0.0118 -0.9997 0.0192 +vn 0.0159 -0.9992 -0.0358 +vn -0.0760 0.9953 0.0603 +vn -0.0866 0.9939 0.0678 +vn 0.0698 0.9967 -0.0426 +vn -0.1862 0.0158 0.9824 +vn -0.1727 0.0199 0.9848 +vn -0.1093 0.0396 0.9932 +vn -0.0949 0.0440 0.9945 +vn 0.9974 0.0702 0.0179 +vn 0.9970 0.0645 0.0427 +vn 0.9861 0.0362 0.1622 +vn 0.9808 0.0287 0.1929 +vn 0.0999 0.0215 -0.9948 +vn 0.1597 0.0063 -0.9871 +vn 0.1496 0.0089 -0.9887 +vn 0.0883 0.0245 -0.9958 +vn -0.9820 0.0299 -0.1863 +vn -0.9996 -0.0134 -0.0266 +vn -0.9873 0.0219 -0.1571 +vn -0.9998 -0.0213 0.0026 +vn 0.1688 0.9843 0.0507 +vn 0.1326 0.9888 -0.0679 +vn 0.1136 0.9893 -0.0920 +vn -0.1626 0.9709 -0.1760 +vn -0.1620 0.9864 -0.0275 +vn -0.0709 0.9935 0.0890 +vn -0.2350 0.9705 0.0540 +vn 0.0189 0.9916 0.1279 +vn -0.0186 0.9828 -0.1837 +vn -0.9603 -0.1643 0.2253 +vn -0.9483 -0.0608 0.3116 +vn -0.9534 -0.0900 0.2880 +vn -0.9255 0.0246 0.3779 +vn 0.2363 0.0132 0.9716 +vn 0.1852 0.0666 0.9804 +vn 0.1811 0.0708 0.9809 +vn 0.1335 0.1193 0.9838 +vn 0.9185 0.1519 0.3651 +vn 0.9160 0.1446 0.3742 +vn 0.9183 0.1514 0.3657 +vn 0.9204 0.1578 0.3576 +vn 0.8045 -0.1656 -0.5704 +vn 0.4324 0.1778 -0.8840 +vn -0.3073 -0.2036 -0.9296 +vn -0.4955 -0.0416 -0.8676 +vn -0.4685 -0.0669 -0.8809 +vn -0.6417 0.1123 -0.7586 +vn -0.5468 -0.8048 -0.2308 +vn -0.1897 -0.4441 0.8756 +vn 0.6189 -0.2459 -0.7460 +vn -0.2263 0.9597 0.1663 +vn 0.0039 -0.9995 -0.0310 +vn -0.0155 -0.9993 0.0328 +vn -0.0065 0.9989 -0.0466 +vn -0.1459 0.1302 -0.9807 +vn -0.9948 -0.1021 -0.0069 +vn -0.6741 0.1551 0.7222 +vn 0.6091 -0.0860 0.7884 +vn 0.9299 0.0898 0.3566 +vn 0.3673 -0.0350 -0.9295 +vn 0.2848 0.9586 -0.0032 +vn 0.1221 0.9848 0.1231 +vn 0.1227 0.9850 -0.1217 +vn -0.0509 0.9866 -0.1550 +vn 0.0363 0.9137 0.4048 +vn -0.1034 0.9883 -0.1119 +vn 0.0208 0.8687 0.4949 +vn -0.2057 0.9785 -0.0133 +vn -0.2138 0.9768 -0.0110 +vn 0.0731 0.2803 -0.9571 +vn -0.6085 -0.2377 -0.7571 +vn -0.9730 0.2271 -0.0402 +vn -0.9904 0.1002 0.0956 +vn -0.9889 0.0621 0.1350 +vn -0.9470 -0.1071 0.3029 +vn 0.0255 0.0232 0.9994 +vn 0.0214 0.0173 0.9996 +vn 0.0273 0.0257 0.9993 +vn 0.0312 0.0311 0.9990 +vn 0.9969 0.0058 0.0788 +vn 0.9937 0.0409 0.1041 +vn 0.9925 0.0507 0.1111 +vn 0.9859 0.0913 0.1401 +vn 0.5845 -0.1794 -0.7913 +vn 0.4710 -0.4067 -0.7828 +vn -0.6050 -0.7912 -0.0893 +vn 0.0783 -0.4486 0.8903 +vn -0.0088 -1.0000 -0.0010 +vn 0.0311 -0.9995 0.0013 +vn 0.0261 0.9975 -0.0663 +vn -0.6937 0.0597 0.7178 +vn -0.9117 -0.0121 0.4107 +vn -0.8832 0.0004 0.4690 +vn -0.6300 0.0748 0.7730 +vn 0.6639 -0.0502 0.7461 +vn 0.9767 0.1585 0.1448 +vn 0.4048 -0.0038 -0.9144 +vn 0.1735 -0.0100 -0.9848 +vn 0.0767 -0.0125 -0.9970 +vn -0.0788 -0.0161 -0.9968 +vn -0.5633 0.1282 -0.8162 +vn -0.1218 0.9924 0.0147 +vn 0.0920 0.9780 -0.1874 +vn -0.0097 0.9917 -0.1282 +vn -0.0405 0.9931 -0.1097 +vn 0.1497 0.9639 -0.2204 +vn 0.0656 0.9971 0.0389 +vn -0.1386 0.7986 0.5856 +vn -0.4162 -0.0520 0.9078 +vn -0.5261 -0.1982 0.8270 +vn -0.3493 0.0285 0.9366 +vn -0.2178 0.1734 0.9605 +vn 0.7950 -0.2508 0.5524 +vn 0.9638 0.2178 0.1539 +vn 0.6917 0.0450 -0.7208 +vn 0.6958 0.0523 -0.7163 +vn 0.6958 0.0523 -0.7164 +vn 0.6993 0.0600 -0.7123 +vn -0.1491 -0.1269 -0.9806 +vn -0.6413 0.1945 -0.7423 +vn -0.8012 0.1157 -0.5872 +vn -0.8487 0.1748 -0.4992 +vn -0.9309 0.1437 -0.3359 +vn -0.9543 0.2410 -0.1768 +vn -0.9388 -0.3442 -0.0104 +vn 0.0769 -0.8093 0.5823 +vn 0.8913 -0.2631 -0.3692 +vn -0.0152 -0.9978 0.0646 +vn -0.0038 -0.9991 -0.0433 +vn 0.0855 0.9957 -0.0353 +vn 0.1132 0.9924 -0.0487 +vn -0.0749 0.9961 0.0457 +vn -0.2769 0.0547 0.9593 +vn 0.0925 -0.0349 0.9951 +vn -0.1922 0.0340 0.9808 +vn 0.1530 -0.0493 0.9870 +vn 0.9768 0.0741 0.2008 +vn 0.8511 -0.0700 -0.5203 +vn 0.1593 0.0630 -0.9852 +vn -0.9235 -0.0075 -0.3835 +vn -0.8837 -0.0335 -0.4668 +vn -0.8918 -0.0287 -0.4516 +vn -0.9334 -0.0000 -0.3590 +vn 0.0344 0.9879 0.1515 +vn 0.0423 0.9860 0.1613 +vn 0.1808 0.9821 0.0530 +vn 0.1584 0.9812 0.1107 +vn -0.7491 0.5550 0.3617 +vn -0.8753 0.2452 0.4169 +vn -0.8204 0.0861 0.5653 +vn -0.0749 0.9963 -0.0432 +vn -0.2173 0.4435 -0.8695 +vn -0.2297 0.3291 -0.9159 +vn -0.2302 0.3233 -0.9179 +vn 0.1432 0.9880 -0.0571 +vn 0.1116 0.9920 -0.0590 +vn -0.8424 0.0959 0.5302 +vn -0.7253 -0.1090 0.6797 +vn 0.3375 0.0929 0.9367 +vn 0.3619 0.0648 0.9300 +vn 0.3635 0.0630 0.9295 +vn 0.3929 0.0281 0.9192 +vn 0.9671 -0.1602 0.1975 +vn 0.9635 0.2023 -0.1751 +vn 0.3889 -0.2100 -0.8970 +vn -0.2312 0.3123 -0.9214 +vn -0.7644 -0.2576 -0.5910 +vn -0.6112 -0.7810 -0.1286 +vn 0.2581 -0.3133 0.9139 +vn 0.2797 -0.5206 -0.8067 +vn 0.2694 0.9544 -0.1285 +vn 0.0348 -0.9992 -0.0201 +vn -0.0483 0.9968 -0.0633 +vn 0.0548 0.1229 -0.9909 +vn -0.8621 -0.0945 -0.4978 +vn -0.8547 0.1115 0.5070 +vn 0.0099 -0.0509 0.9987 +vn 0.8494 0.1004 0.5181 +vn 0.9181 -0.0626 -0.3914 +vn 0.0533 0.9676 -0.2469 +vn -0.1144 0.9907 -0.0738 +vn -0.0973 0.9944 -0.0413 +vn -0.0445 0.9594 -0.2785 +vn -0.6604 0.0845 0.7461 +vn -0.7014 0.1239 0.7019 +vn -0.6503 0.1965 0.7338 +vn 0.1352 0.9875 -0.0810 +vn 0.1171 0.9927 -0.0275 +vn 0.0082 0.9966 0.0821 +vn 0.5951 0.7442 0.3035 +vn 0.8232 0.3720 0.4289 +vn 0.8264 0.3625 0.4308 +vn -0.0082 -0.1431 -0.9897 +vn -0.6805 0.1139 -0.7238 +vn -0.7567 0.0163 -0.6536 +vn -0.7700 -0.0031 -0.6381 +vn -0.8347 -0.1150 -0.5386 +vn -0.7485 0.0560 0.6608 +vn -0.6868 0.1522 0.7108 +vn 0.3559 -0.2655 0.8960 +vn 0.8416 0.3139 0.4394 +vn 0.9308 -0.2562 -0.2606 +vn 0.5132 0.2044 -0.8336 +vn -0.2240 -0.7792 -0.5854 +vn -0.6282 -0.4395 0.6420 +vn 0.5127 -0.7857 0.3462 +vn 0.4604 -0.7862 -0.4122 +vn 0.0094 -0.9999 0.0097 +vn -0.0171 -0.9998 -0.0088 +vn -0.0378 0.9991 0.0170 +vn -0.4465 0.0731 -0.8918 +vn -0.1837 0.0117 -0.9829 +vn -0.5066 0.0876 -0.8577 +vn -0.9817 -0.0422 0.1859 +vn -0.4837 0.0998 0.8695 +vn -0.2085 0.0509 0.9767 +vn -0.4400 0.0921 0.8933 +vn -0.1516 0.0406 0.9876 +vn 0.9985 0.0454 -0.0318 +vn 0.9984 0.0458 -0.0334 +vn 0.9984 0.0457 -0.0330 +vn 0.9985 0.0453 -0.0317 +vn -0.1139 -0.0043 -0.9935 +vn 0.1261 0.9915 0.0312 +vn 0.1168 0.9914 -0.0592 +vn 0.0819 0.9577 -0.2758 +vn -0.0906 0.9929 -0.0777 +vn -0.1198 0.9923 -0.0306 +vn -0.1044 0.9849 0.1382 +vn -0.1114 0.9849 0.1325 +vn 0.0125 0.9721 0.2343 +vn -0.9971 0.0352 0.0668 +vn -0.9913 0.0826 0.1025 +vn -0.9935 0.0676 0.0914 +vn -0.9862 0.1104 0.1231 +vn -0.1456 -0.1259 0.9813 +vn 0.0173 0.0511 0.9985 +vn -0.0003 0.0316 0.9995 +vn 0.1743 0.2190 0.9600 +vn 0.8945 0.1735 0.4121 +vn 0.8815 0.1432 0.4500 +vn 0.8949 0.1746 0.4107 +vn 0.9044 0.2010 0.3764 +vn 0.7960 -0.2602 -0.5465 +vn 0.1088 0.2919 -0.9503 +vn -0.2645 -0.1009 -0.9591 +vn -0.3358 -0.4919 -0.8032 +vn -0.5004 -0.7884 0.3578 +vn 0.7832 -0.3429 0.5187 +vn 0.0086 -1.0000 -0.0003 +vn -0.0192 0.9966 -0.0804 +vn -0.9658 0.0682 -0.2500 +vn -0.9947 0.0173 -0.1011 +vn -0.9780 0.0519 -0.2023 +vn -0.9978 0.0056 -0.0666 +vn 0.4022 0.1066 0.9093 +vn 0.2489 0.0864 0.9647 +vn 0.2766 0.0902 0.9568 +vn 0.4191 0.1088 0.9014 +vn 0.9019 -0.0261 0.4311 +vn 0.6715 0.0813 -0.7365 +vn 0.4771 0.0295 -0.8784 +vn 0.6359 0.0713 -0.7685 +vn 0.4383 0.0198 -0.8986 +vn 0.1637 0.9854 -0.0473 +vn 0.1464 0.9855 -0.0855 +vn 0.0496 0.9801 -0.1923 +vn 0.0557 0.9767 0.2074 +vn 0.0140 0.9552 0.2956 +vn 0.1190 0.9865 0.1123 +vn -0.0578 0.9983 -0.0030 +vn -0.7961 0.0486 0.6033 +vn -0.7328 -0.0391 0.6793 +vn -0.7225 -0.0519 0.6894 +vn -0.6628 -0.1197 0.7392 +vn -0.0505 0.2210 0.9740 +vn 0.7795 -0.2837 0.5584 +vn 0.9623 0.1994 0.1852 +vn 0.4353 -0.1505 -0.8876 +vn 0.2808 0.0394 -0.9590 +vn 0.3189 -0.0052 -0.9478 +vn 0.1356 0.1984 -0.9707 +vn -0.7358 0.0123 -0.6771 +vn -0.7746 0.0725 -0.6283 +vn -0.7335 0.0089 -0.6797 +vn -0.6796 -0.0630 -0.7309 +vn -0.9789 0.1239 0.1623 +vn 0.4921 -0.7724 0.4014 +vn 0.4465 -0.7427 -0.4990 +vn 0.0332 -0.9994 0.0101 +vn 0.0321 0.9994 -0.0101 +vn -0.5923 0.0826 -0.8015 +vn -0.9327 -0.0329 0.3591 +vn -0.5777 0.0817 0.8121 +vn 0.6724 -0.0699 0.7369 +vn 0.9900 0.1237 -0.0683 +vn 0.1879 -0.0874 -0.9783 +vn 0.1643 0.9859 -0.0326 +vn 0.0267 0.9898 -0.1396 +vn -0.1126 0.9818 -0.1526 +vn 0.2139 0.9767 -0.0174 +vn -0.1322 0.9909 -0.0243 +vn -0.1646 0.9701 0.1785 +vn 0.0177 0.9933 0.1142 +vn -0.9648 -0.1959 0.1752 +vn -0.7113 0.3290 0.6211 +vn -0.1757 -0.1947 0.9650 +vn 0.7686 0.0714 0.6357 +vn 0.7922 0.1266 0.5970 +vn 0.7886 0.1177 0.6035 +vn 0.8047 0.1601 0.5718 +vn 0.8828 -0.1527 -0.4443 +vn 0.8139 -0.0133 -0.5808 +vn 0.8261 -0.0336 -0.5625 +vn 0.7247 0.1098 -0.6803 +vn -0.3754 -0.0240 -0.9266 +vn -0.2965 -0.1199 -0.9475 +vn -0.4126 0.0240 -0.9106 +vn -0.4798 0.1165 -0.8696 +vn 0.1562 -0.5621 -0.8122 +vn -0.8177 -0.5701 0.0795 +vn -0.9135 -0.4053 -0.0356 +vn -0.8678 -0.4963 0.0258 +vn -0.7077 -0.6853 0.1721 +vn 0.2815 -0.2979 0.9122 +vn 0.6505 -0.7492 -0.1245 +vn 0.6591 -0.7385 -0.1421 +vn 0.6589 -0.7390 -0.1408 +vn 0.6690 -0.7251 -0.1630 +vn -0.0599 -0.9982 -0.0069 +vn 0.0335 -0.9994 -0.0129 +vn 0.0256 0.9993 0.0288 +vn -0.4486 0.0186 0.8935 +vn -0.4351 0.0226 0.9001 +vn -0.3793 0.0389 0.9245 +vn -0.3644 0.0432 0.9302 +vn 0.9999 -0.0116 -0.0017 +vn 0.9603 0.0769 0.2682 +vn 0.9984 0.0073 0.0560 +vn 0.9417 0.0951 0.3229 +vn 0.2914 -0.0427 -0.9556 +vn -0.6093 0.1147 -0.7846 +vn -0.9358 0.0069 -0.3524 +vn 0.0661 0.9610 0.2686 +vn 0.1458 0.9831 0.1112 +vn 0.2460 0.9687 -0.0326 +vn -0.2915 0.9531 0.0817 +vn -0.0976 0.9837 0.1508 +vn -0.1367 0.9894 -0.0484 +vn -0.1869 0.9821 -0.0226 +vn -0.1691 0.7831 -0.5984 +vn 0.1030 0.9922 -0.0704 +vn 0.0364 0.9960 -0.0812 +vn -0.9413 0.2427 0.2345 +vn -0.7738 -0.1127 0.6234 +vn 0.0759 0.0236 0.9968 +vn -0.0044 -0.0646 0.9979 +vn 0.0883 0.0374 0.9954 +vn 0.1544 0.1108 0.9818 +vn 0.9424 -0.1242 0.3106 +vn 0.9653 0.2512 -0.0713 +vn 0.4940 -0.3026 -0.8151 +vn -0.2509 0.3050 -0.9187 +vn -0.7992 -0.2547 -0.5444 +vn -0.8745 -0.3085 0.3742 +vn 0.8675 -0.4809 0.1276 +vn 0.0022 -0.7864 -0.6178 +vn 0.3904 -0.0782 -0.9173 +vn 0.7418 -0.0529 0.6685 +vn 0.6658 -0.2095 0.7161 +vn 0.7279 -0.0971 0.6788 +vn 0.5844 0.1442 0.7985 +vn 0.5690 0.1913 0.7998 +vn 0.2934 -0.3428 0.8924 +vn 0.2913 -0.3161 0.9029 +vn 0.1241 0.0798 0.9890 +vn 0.1410 0.1016 0.9848 +vn 0.0106 0.1326 0.9911 +vn -0.1624 -0.3728 0.9136 +vn -0.1736 -0.3396 0.9244 +vn -0.3453 -0.0613 0.9365 +vn -0.4902 -0.1800 0.8528 +vn -0.6978 -0.1738 0.6949 +vn -0.6988 -0.1652 0.6960 +vn -0.8948 -0.1551 0.4186 +vn -0.8901 -0.1245 0.4385 +vn -0.8868 -0.4243 0.1829 +vn -0.8751 -0.4525 0.1718 +vn -0.9313 0.3509 -0.0977 +vn -0.8702 -0.4225 -0.2535 +vn -0.8152 0.2191 -0.5362 +vn -0.7156 -0.3074 -0.6272 +vn -0.7120 -0.2509 -0.6558 +vn -0.6079 0.0204 -0.7938 +vn -0.4354 -0.2142 -0.8744 +vn -0.1844 -0.0631 -0.9808 +vn -0.1914 -0.0494 -0.9803 +vn 0.2038 -0.1104 -0.9728 +vn 0.1945 -0.1078 -0.9750 +vn 0.5323 -0.0308 -0.8460 +vn 0.6209 -0.0695 -0.7808 +vn 0.7289 -0.0233 -0.6842 +vn 0.7319 -0.0042 -0.6814 +vn 0.8615 -0.4413 -0.2511 +vn 0.8682 -0.4118 -0.2768 +vn 0.8780 -0.3462 -0.3305 +vn -0.0874 0.2028 -0.9753 +vn -0.2425 -0.9638 -0.1108 +vn -0.7224 -0.5211 -0.4546 +vn -0.4577 -0.8476 -0.2685 +vn -0.7310 -0.3606 -0.5793 +vn -0.7015 0.2254 0.6760 +vn -0.1075 -0.5156 0.8501 +vn 0.6394 0.2600 0.7235 +vn 0.8500 -0.4811 -0.2148 +vn 0.3973 -0.0912 0.9132 +vn 0.1011 0.0446 -0.9939 +vn 0.1137 0.0741 -0.9907 +vn 0.0724 -0.0902 -0.9933 +vn 0.1905 -0.0161 -0.9815 +vn 0.1551 0.0516 0.9866 +vn -0.0138 -0.1532 0.9881 +vn 0.1215 0.0817 0.9892 +vn 0.1329 0.1084 0.9852 +vn -0.7163 -0.0082 -0.6977 +vn -0.6091 -0.1212 -0.7838 +vn -0.6135 -0.1677 -0.7717 +vn -0.6651 -0.1377 -0.7340 +vn -0.7905 -0.0205 -0.6121 +vn -0.8775 -0.1687 -0.4490 +vn -0.9225 -0.1890 -0.3367 +vn -0.9209 -0.1124 -0.3732 +vn -0.8800 -0.0337 -0.4737 +vn -0.8852 0.0153 0.4650 +vn -0.9333 -0.1106 0.3416 +vn -0.9005 -0.0476 0.4323 +vn -0.9144 -0.0269 0.4039 +vn -0.7380 -0.1622 0.6550 +vn -0.6642 -0.1303 0.7361 +vn -0.6302 -0.0897 0.7712 +vn -0.7218 -0.0015 0.6921 +vn -0.8912 0.1360 -0.4326 +vn -0.8973 0.1073 -0.4282 +vn -0.8075 -0.0325 -0.5889 +vn -0.8510 -0.0905 -0.5173 +vn -0.7150 -0.2145 -0.6654 +vn -0.7091 -0.2854 -0.6448 +vn -0.4884 0.1991 -0.8496 +vn -0.3328 -0.3565 -0.8730 +vn -0.1160 0.3155 -0.9418 +vn 0.0566 -0.3623 -0.9303 +vn 0.2814 0.1969 -0.9392 +vn 0.4277 -0.4004 -0.8104 +vn 0.4480 -0.3624 -0.8173 +vn 0.6009 -0.1765 -0.7796 +vn 0.5650 -0.0320 -0.8245 +vn 0.7071 -0.3101 -0.6355 +vn 0.9170 -0.1295 -0.3772 +vn 0.8817 -0.1027 -0.4605 +vn 0.9259 -0.3514 -0.1386 +vn 0.9965 -0.0604 0.0572 +vn 0.9659 -0.1506 0.2107 +vn 0.8896 -0.3173 0.3286 +vn 0.8420 -0.2073 0.4981 +vn 0.7447 -0.2707 0.6100 +vn 0.5496 -0.1525 0.8214 +vn 0.6607 -0.2392 0.7116 +vn 0.3909 -0.2448 0.8873 +vn 0.1959 -0.0787 0.9775 +vn 0.1101 -0.0824 0.9905 +vn -0.0398 -0.3000 0.9531 +vn -0.0432 -0.3152 0.9480 +vn -0.3094 0.2200 0.9251 +vn -0.4299 -0.3069 0.8491 +vn -0.6086 0.2877 0.7395 +vn -0.7166 -0.3336 0.6126 +vn -0.7653 -0.2596 0.5891 +vn -0.8834 0.0223 0.4681 +vn -0.8993 0.0645 0.4326 +vn -0.8992 0.0599 0.4334 +vn -0.8454 -0.0027 -0.5341 +vn -0.8440 0.0039 -0.5364 +vn -0.8369 0.0122 0.5473 +vn -0.8434 0.0349 0.5361 +vn 0.2380 -0.0084 -0.9712 +vn 0.2424 0.0033 -0.9702 +vn -0.7753 0.0342 -0.6306 +vn -0.7806 0.0203 -0.6247 +vn -0.7733 0.0352 0.6330 +vn -0.7789 0.0205 0.6268 +vn 0.2414 0.0403 0.9696 +vn 0.2622 0.0023 0.9650 +vn 0.0048 -1.0000 -0.0026 +vn 0.0107 -0.9999 -0.0022 +vn 0.0120 -0.9999 -0.0046 +vn 0.0223 -0.9990 -0.0384 +vn 0.0184 -0.9936 0.1113 +vn -0.0069 -0.9861 0.1658 +vn 0.0411 -0.9890 0.1420 +vn -0.0121 -0.9999 -0.0104 +vn -0.0137 -0.9999 -0.0059 +vn -0.0149 -0.9999 -0.0066 +vn -0.0705 -0.9937 -0.0869 +vn -0.0681 -0.9969 -0.0399 +vn -0.0690 -0.9962 -0.0532 +vn -0.0338 -0.9979 -0.0544 +vn 0.0152 -0.9997 0.0196 +vn 0.0190 -0.9998 0.0111 +vn 0.0078 -1.0000 0.0028 +vn 0.0247 -0.9995 0.0200 +vn 0.0086 -0.9998 0.0186 +vn -0.0327 -0.9994 -0.0096 +vn 0.1360 0.0075 0.9907 +vn 0.1053 0.0018 0.9944 +vn -0.1184 0.0188 0.9928 +vn -0.1695 0.0029 0.9855 +vn -0.1186 -0.0950 0.9884 +vn -0.1966 -0.0575 0.9788 +vn -0.0508 -0.2545 -0.9657 +vn -0.0440 -0.2248 -0.9734 +vn 0.0052 -0.0102 -0.9999 +vn 0.0143 0.0295 -0.9995 +vn 0.8134 -0.0172 0.5814 +vn 0.7978 0.0536 0.6006 +vn 0.7225 0.2666 0.6380 +vn 0.7002 0.3128 0.6418 +vn 0.9041 -0.0620 -0.4228 +vn 0.9340 -0.0012 -0.3572 +vn 0.9308 -0.0087 -0.3655 +vn 0.9535 0.0525 -0.2968 +vn -0.1415 0.1256 -0.9820 +vn -0.1310 0.0849 -0.9877 +vn -0.1334 0.1377 -0.9815 +vn -0.1414 0.1358 -0.9806 +vn 0.0784 0.0352 -0.9963 +vn 0.1578 -0.0025 -0.9875 +vn 0.7196 0.2661 -0.6414 +vn 0.6941 0.3182 -0.6457 +vn 0.8027 0.0247 -0.5959 +vn 0.8170 -0.0473 -0.5747 +vn 0.9796 0.1396 0.1446 +vn 0.8103 -0.1735 0.5597 +vn 0.0012 0.0975 0.9952 +vn -0.0052 0.1261 0.9920 +vn -0.0320 0.2458 0.9688 +vn -0.0358 0.2627 0.9642 +vn -0.0818 0.2617 -0.9617 +vn 0.0036 -0.1790 -0.9839 +vn -0.1336 0.0180 0.9909 +vn -0.1312 0.0445 0.9904 +vn 0.8811 -0.0628 -0.4687 +vn 0.9144 -0.1284 -0.3839 +vn 0.8995 -0.0885 -0.4278 +vn 0.8771 -0.0735 -0.4747 +vn 0.7193 -0.0168 -0.6945 +vn 0.6770 -0.0322 -0.7353 +vn 0.6646 -0.0949 -0.7411 +vn 0.7310 -0.0465 -0.6808 +vn 0.7210 0.0202 0.6926 +vn 0.5993 -0.1479 0.7868 +vn 0.7400 -0.0140 0.6725 +vn 0.7793 -0.0014 0.6266 +vn 0.9177 0.0158 0.3970 +vn 0.9312 0.0345 0.3630 +vn 0.9024 -0.0074 0.4309 +vn 0.9136 0.2022 0.3528 +vn 0.8369 0.0122 -0.5472 +vn 0.8333 0.0006 -0.5528 +vn 0.8391 -0.0028 0.5440 +vn 0.8392 -0.0034 0.5438 +vn -0.0192 -0.9998 -0.0002 +vn -0.0070 -1.0000 -0.0012 +vn -0.0159 -0.9999 -0.0005 +vn -0.0009 -1.0000 -0.0011 +vn 0.0138 -0.9987 -0.0490 +vn 0.0184 -0.9992 -0.0367 +vn -0.0025 -1.0000 -0.0016 +vn 0.0094 -0.9998 0.0195 +vn 0.0006 -0.9999 0.0133 +vn 0.0491 -0.9969 0.0617 +vn -0.0098 -1.0000 -0.0012 +vn -0.0131 -0.9999 0.0089 +vn -0.0098 -0.9999 0.0035 +vn -0.2509 0.0230 -0.9677 +vn -0.2622 0.0023 -0.9650 +vn 0.7808 0.0153 -0.6245 +vn 0.7789 0.0205 -0.6268 +vn 0.7722 0.0421 0.6339 +vn 0.7806 0.0205 0.6247 +vn -0.2283 -0.0082 0.9736 +vn -0.2377 0.0086 0.9713 +vn -0.0722 -0.9974 -0.0068 +vn 0.0040 -1.0000 -0.0035 +vn -0.0047 -1.0000 0.0034 +vn -0.0128 -0.9998 0.0140 +vn -0.0001 -1.0000 0.0044 +vn -0.0245 -0.9966 0.0789 +vn -0.0278 -0.9888 0.1469 +vn -0.0060 -0.9854 0.1704 +vn -0.0714 -0.9920 -0.1043 +vn -0.0137 -0.9833 0.1814 +vn 0.0123 -0.9823 0.1869 +vn -0.0008 -1.0000 0.0015 +vn -0.8769 -0.0259 0.4800 +vn -0.8903 -0.1448 0.4318 +vn -0.8826 -0.0630 0.4658 +vn -0.8913 -0.1758 0.4179 +vn -0.7219 0.2217 -0.6555 +vn -0.8786 0.1838 -0.4407 +vn -0.8746 0.1224 -0.4691 +vn -0.8779 0.1662 -0.4491 +vn -0.8725 0.1029 -0.4776 +vn -0.7219 -0.2217 0.6555 +vn 0.8759 -0.3680 -0.3120 +vn 0.6144 0.1550 -0.7736 +vn -0.2019 -0.3266 -0.9234 +vn -0.6128 0.1176 -0.7815 +vn -0.9419 -0.2795 0.1863 +vn -0.9190 -0.3800 0.1047 +vn -0.9437 -0.2381 0.2295 +vn -0.9219 0.1893 0.3379 +vn -0.0949 0.0786 0.9924 +vn 0.2898 -0.4621 0.8382 +vn 0.9566 0.0421 0.2884 +vn 0.9296 -0.0317 0.3672 +vn 0.9475 -0.0088 0.3195 +vn 0.9862 -0.0643 0.1524 +vn 0.9738 -0.1114 0.1981 +vn -0.1044 -0.0025 -0.9945 +vn -0.0893 -0.0228 -0.9957 +vn -0.1116 0.0071 -0.9937 +vn -0.1265 0.0273 -0.9916 +vn 0.9565 0.2777 0.0896 +vn 0.1683 -0.7714 0.6137 +vn 0.8146 0.0049 0.5801 +vn 0.9787 -0.0955 -0.1816 +vn 0.9881 -0.0556 -0.1431 +vn 0.9882 -0.0553 -0.1428 +vn 0.9943 -0.0166 -0.1050 +vn 0.9951 -0.0085 0.0988 +vn 0.9945 0.1049 0.0022 +vn 0.9769 0.1985 -0.0790 +vn 0.9701 -0.1336 0.2029 +vn 0.7264 -0.3685 -0.5801 +vn 0.2671 0.0138 -0.9636 +vn -0.2324 0.0732 0.9699 +vn -0.0880 0.2272 0.9699 +vn -0.2802 0.0189 0.9598 +vn -0.4206 -0.1526 0.8943 +vn 0.2534 -0.0231 0.9671 +vn 0.3213 0.0778 0.9438 +vn 0.3993 0.2021 0.8943 +vn 0.1562 -0.1577 0.9751 +vn 0.8832 -0.2054 -0.4215 +vn -0.2097 -0.2700 -0.9398 +vn 0.4518 0.3044 -0.8386 +vn -0.7846 0.5808 0.2170 +vn -0.5473 0.7464 0.3786 +vn -0.5068 0.7258 0.4652 +vn -0.4774 0.7079 0.5205 +vn -0.4355 0.6667 0.6049 +vn -0.4358 0.6662 0.6052 +vn -0.5700 0.6923 0.4426 +vn -0.2851 0.9579 -0.0350 +vn -0.6039 0.6853 0.4071 +vn -0.1067 0.9499 0.2939 +vn 0.2007 0.6845 0.7008 +vn 0.2479 0.9506 0.1869 +vn -0.5996 0.6898 -0.4059 +vn -0.0437 0.9601 -0.2763 +vn -0.0267 0.5939 0.8041 +vn -0.4148 0.6921 -0.5907 +vn -0.4509 0.5917 -0.6682 +vn -0.3392 0.8315 -0.4399 +vn -0.3338 0.8391 -0.4296 +vn -0.7670 0.1383 -0.6265 +vn -0.0449 0.9988 -0.0187 +vn -0.4488 0.8772 -0.1704 +vn -0.1042 0.9942 -0.0250 +vn -0.7220 0.6553 -0.2219 +vn 0.1684 0.7348 0.6571 +vn 0.1863 0.7676 0.6133 +vn 0.0551 0.5169 0.8543 +vn -0.0435 0.7762 0.6290 +vn -0.1913 0.6267 0.7555 +vn -0.2293 0.5767 0.7841 +vn -0.5700 0.6908 -0.4449 +vn -0.3129 0.9497 -0.0114 +vn 0.0339 0.6029 0.7971 +vn -0.2015 0.6791 0.7059 +vn -0.2526 0.9592 0.1272 +vn 0.1998 0.6866 -0.6990 +vn 0.2509 0.9588 -0.1331 +vn -0.0328 0.6049 -0.7956 +vn 0.5827 0.6730 0.4555 +vn 0.3071 0.9517 -0.0052 +vn 0.1434 0.6661 -0.7320 +vn 0.0319 0.7268 -0.6861 +vn -0.0352 0.7565 -0.6530 +vn 0.2147 0.6197 -0.7549 +vn 0.4463 0.6610 0.6032 +vn 0.4480 0.6571 0.6062 +vn 0.4921 0.7789 0.3888 +vn 0.2707 0.9151 0.2990 +vn 0.1866 0.9782 0.0909 +vn 0.8645 0.4457 0.2324 +vn 0.0232 0.5416 -0.8403 +vn 0.4749 0.7898 0.3881 +vn 0.4398 0.8131 0.3815 +vn 0.6013 0.6877 0.4068 +vn 0.2132 0.9205 0.3274 +vn -0.2289 0.8229 -0.5200 +vn -0.2237 0.7954 -0.5633 +vn -0.2010 0.6831 -0.7021 +vn -0.2459 0.9295 -0.2748 +vn 0.6040 0.6851 -0.4071 +vn -0.0044 0.9666 -0.2561 +vn 0.5700 0.6922 -0.4426 +vn 0.2503 0.9648 0.0814 +vn 0.7638 0.6064 -0.2210 +vn 0.4346 0.6051 -0.6671 +vn 0.9831 0.0397 0.1787 +vn 0.9850 0.0313 0.1696 +vn 0.9715 0.0180 0.2365 +vn 0.6677 -0.7440 -0.0244 +vn 0.6952 -0.7185 -0.0182 +vn 0.7055 -0.7086 -0.0158 +vn 0.7080 -0.7060 -0.0152 +vn 0.9867 0.0308 -0.1596 +vn 0.9709 -0.0035 -0.2394 +vn 0.9886 0.0170 -0.1499 +vn 0.9791 -0.0159 -0.2029 +vn 0.9451 -0.0030 -0.3268 +vn 0.1086 -0.9940 -0.0163 +vn 0.2306 -0.9539 -0.1921 +vn 0.0412 -0.9985 -0.0347 +vn 0.8978 0.0626 -0.4359 +vn 0.8834 0.0086 0.4685 +vn 0.7725 -0.5380 0.3375 +vn 0.9511 0.0100 0.3088 +vn 0.9766 0.0121 0.2149 +vn -0.8792 0.0358 -0.4751 +vn -0.9739 -0.0575 -0.2197 +vn -0.9513 -0.2142 -0.2215 +vn -0.8372 -0.4852 -0.2523 +vn -0.7668 -0.5467 -0.3364 +vn -0.9858 0.0194 -0.1666 +vn -0.9839 0.0281 -0.1766 +vn -0.6682 -0.7436 0.0244 +vn -0.7083 -0.7057 0.0152 +vn -0.7236 -0.6901 0.0115 +vn -0.7273 -0.6863 0.0106 +vn -0.9888 0.0227 0.1476 +vn -0.9635 0.0291 0.2662 +vn -0.9903 0.0104 0.1388 +vn -0.9813 0.0006 0.1927 +vn -0.9333 0.0506 0.3556 +vn -0.5946 -0.7223 0.3532 +vn -0.8967 0.0103 0.4425 +vn -0.0262 0.9823 -0.1853 +vn -0.0071 0.9995 -0.0323 +vn 0.0025 0.9999 -0.0118 +vn 0.1818 0.9804 0.0757 +vn 0.1835 0.9799 -0.0780 +vn -0.0056 0.9999 0.0089 +vn 0.0771 0.9796 0.1855 +vn -0.0002 0.9911 0.1333 +vn 0.0041 0.9995 -0.0322 +vn 0.0833 0.9799 -0.1814 +vn -0.0344 0.9810 0.1909 +vn 0.0142 0.9999 -0.0033 +vn 0.0205 0.9830 -0.1827 +vn 0.0107 0.9991 -0.0419 +vn 0.0412 0.9799 0.1954 +vn -0.0940 0.9950 0.0328 +vn -0.1996 0.9799 -0.0075 +vn -0.0938 0.9780 0.1865 +vn -0.2769 0.9586 -0.0668 +vn -0.0831 0.9778 -0.1925 +vn -0.0042 0.9992 -0.0399 +vn 0.0350 0.9774 -0.2086 +vn 0.0107 0.9992 0.0393 +vn 0.0284 0.9762 0.2149 +vn -0.2086 -0.0942 0.9735 +vn -0.1552 -0.0825 0.9844 +vn -0.0121 -0.0451 0.9989 +vn -0.2030 0.0579 0.9775 +vn -0.1651 0.0493 0.9850 +vn 0.3727 0.2286 0.8993 +vn 0.1469 -0.0751 0.9863 +vn 0.3205 0.1544 0.9346 +vn 0.1896 -0.8034 0.5644 +vn 0.0841 -0.1527 0.9847 +vn -0.0174 -0.9998 0.0068 +vn -0.2659 -0.9633 0.0360 +vn -0.0170 -0.9999 -0.0023 +vn -0.5030 0.3537 0.7886 +vn -0.8410 -0.3334 -0.4262 +vn -0.4032 0.6105 -0.6817 +vn -0.4087 0.6213 -0.6686 +vn -0.3654 0.5369 -0.7604 +vn 0.1193 0.9383 0.3245 +vn 0.0936 0.9345 0.3436 +vn 0.0461 0.9445 0.3252 +vn 0.1068 0.9333 0.3428 +vn 0.0788 0.9425 0.3246 +vn 0.1871 0.9160 0.3549 +vn -0.3522 0.5117 -0.7836 +vn -0.3353 0.9419 0.0192 +vn -0.1131 0.9935 -0.0139 +vn -0.2153 0.9765 0.0040 +vn -0.3416 0.9379 -0.0602 +vn -0.3283 0.9322 -0.1525 +vn -0.3393 0.9406 0.0115 +vn -0.1913 0.9358 0.2962 +vn -0.2244 0.9357 0.2721 +vn -0.2026 0.9365 0.2863 +vn -0.2707 0.9394 0.2105 +vn -0.1813 0.9702 0.1606 +vn -0.3547 0.9222 0.1538 +vn -0.2125 0.9706 0.1128 +vn -0.1296 0.9703 0.2045 +vn 0.0344 0.9414 0.3355 +vn 0.0030 0.9859 0.1672 +vn -0.0258 0.9608 0.2760 +vn -0.0380 0.9361 0.3498 +vn -0.0844 0.9371 0.3386 +vn -0.1235 0.9364 0.3284 +vn 0.2212 -0.0492 0.9740 +vn -0.3315 0.9396 0.0855 +vn -0.3206 0.9384 0.1293 +vn -0.5768 -0.4678 -0.6697 +vn 0.2110 0.2799 0.9366 +vn -0.7559 -0.2303 0.6128 +vn -0.9148 0.3457 0.2089 +vn 0.0771 0.5076 -0.8581 +vn 0.8822 -0.3536 -0.3111 +vn 0.9342 -0.2622 -0.2417 +vn 0.9796 -0.1379 -0.1463 +vn 0.9968 -0.0389 -0.0702 +vn 0.0244 -0.0159 0.9996 +vn 0.0681 0.0516 0.9963 +vn 0.1096 0.1159 0.9872 +vn -0.0279 -0.0962 0.9950 +vn -0.9903 -0.0388 -0.1333 +vn 0.7046 -0.4061 -0.5819 +vn 0.6661 0.3366 0.6656 +vn 0.5227 -0.1813 0.8330 +vn -0.6423 0.1427 0.7531 +vn -0.8182 -0.4993 0.2850 +vn -0.0786 -0.0033 -0.9969 +vn 0.1009 0.0093 -0.9949 +vn -0.0045 -0.9739 -0.2269 +vn -0.0018 -0.9380 -0.3466 +vn 0.0133 -0.9408 -0.3386 +vn -0.0105 -0.9412 -0.3378 +vn -0.0040 -0.9980 -0.0635 +vn 0.0166 -0.9994 -0.0298 +vn 0.0179 -0.9955 -0.0930 +vn -0.0060 -1.0000 -0.0010 +vn 0.0048 -1.0000 -0.0002 +vn -0.0046 -0.9997 -0.0224 +vn 0.0048 -0.9928 -0.1196 +vn -0.3727 0.2286 -0.8993 +vn -0.1476 -0.0742 -0.9863 +vn -0.3205 0.1544 -0.9346 +vn -0.1729 -0.8324 -0.5266 +vn 0.2508 -0.6672 -0.7014 +vn 0.1121 0.9288 -0.3533 +vn 0.0694 0.9131 -0.4018 +vn 0.0589 0.9431 -0.3272 +vn 0.1038 0.9365 -0.3349 +vn 0.1137 0.9342 -0.3381 +vn 0.1479 0.9317 -0.3318 +vn 0.0663 0.9432 -0.3257 +vn -0.0498 0.9413 -0.3338 +vn -0.2633 0.9553 0.1342 +vn -0.2287 0.9396 -0.2546 +vn -0.1922 0.9370 -0.2917 +vn -0.2192 0.9368 -0.2728 +vn -0.2721 0.9322 -0.2387 +vn -0.2605 0.9399 -0.2206 +vn -0.3079 0.9372 -0.1636 +vn -0.2089 0.9707 -0.1189 +vn -0.0014 0.9703 -0.2420 +vn 0.0607 0.9388 -0.3391 +vn 0.0068 0.9637 -0.2667 +vn -0.0623 0.9367 -0.3445 +vn -0.0383 0.9399 -0.3392 +vn -0.1471 0.9338 -0.3260 +vn -0.7278 -0.2078 -0.6536 +vn -0.6922 -0.1077 -0.7136 +vn -0.6372 0.0121 -0.7706 +vn -0.5718 0.1272 -0.8105 +vn 0.6713 -0.0856 -0.7362 +vn -0.3874 -0.6364 0.6670 +vn -0.9155 0.2370 0.3250 +vn -0.9951 -0.0581 -0.0797 +vn -0.3384 -0.1964 -0.9203 +vn 0.1446 0.3194 -0.9365 +vn 0.8799 -0.2800 -0.3838 +vn 0.9405 0.2885 0.1796 +vn 0.3224 -0.4005 0.8577 +vn -0.5855 0.7782 0.2271 +vn -0.2827 0.9451 0.1640 +vn -0.1965 0.9750 0.1036 +vn -0.9214 -0.3072 -0.2378 +vn -0.1153 0.2595 -0.9588 +vn 0.4810 -0.3965 -0.7819 +vn 0.7916 0.6090 -0.0504 +vn 0.0991 -0.0354 0.9944 +vn -0.0882 -0.0658 0.9939 +vn 0.0021 -0.9733 0.2295 +vn -0.0091 -0.9404 0.3400 +vn 0.2030 -0.9505 0.2350 +vn 0.0123 -0.9997 0.0187 +vn 0.0097 -0.9969 0.0785 +vn 0.0043 -0.9954 0.0962 +vn -0.0105 -0.9999 -0.0049 +vn -0.0850 -0.1517 -0.9848 +vn 0.6818 -0.5498 0.4825 +vn 0.5413 0.5111 0.6676 +vn -0.0072 0.0248 0.9997 +vn 0.9256 0.0350 0.3769 +vn 0.9358 0.1244 0.3297 +vn 0.9373 0.1621 0.3086 +vn 0.9139 -0.0232 0.4054 +vn -0.2668 -0.0039 0.9638 +vn 0.0894 -0.2332 -0.9683 +vn -0.1176 0.9440 0.3084 +vn -0.1057 0.9418 0.3190 +vn -0.0634 0.9438 0.3243 +vn -0.1030 0.9387 0.3291 +vn -0.1150 0.9366 0.3310 +vn -0.0385 0.9777 0.2065 +vn -0.1247 0.9406 0.3158 +vn -0.0623 0.9424 0.3286 +vn 0.2512 0.9679 0.0072 +vn 0.3371 0.9406 0.0414 +vn 0.1417 0.9776 0.1556 +vn 0.2130 0.9382 0.2729 +vn 0.1621 0.9371 0.3091 +vn 0.2472 0.9430 0.2229 +vn 0.2263 0.9379 0.2628 +vn 0.1007 0.9914 0.0831 +vn -0.4368 0.3590 0.8248 +vn 0.0277 0.9576 0.2868 +vn -0.0270 0.9413 0.3364 +vn 0.0020 0.9432 0.3321 +vn -0.0579 0.9608 0.2710 +vn 0.0479 0.9394 0.3395 +vn 0.0268 0.9385 0.3443 +vn 0.3398 0.9381 0.0664 +vn 0.3092 0.9354 0.1714 +vn 0.3238 0.9339 0.1518 +vn 0.9727 -0.1251 0.1957 +vn 0.9727 -0.0782 0.2187 +vn 0.9653 0.0119 0.2609 +vn -0.0347 0.2206 0.9747 +vn -0.6128 -0.6923 0.3810 +vn 0.4049 -0.2614 -0.8762 +vn 0.9525 0.0838 0.2927 +vn 0.9727 -0.2314 0.0155 +vn 0.8890 0.2062 0.4088 +vn 0.3407 -0.2125 0.9159 +vn -0.2920 0.2410 0.9255 +vn -0.8799 -0.2800 0.3838 +vn -0.8575 0.4097 -0.3112 +vn -0.5159 -0.3548 -0.7797 +vn 0.4266 0.1877 -0.8847 +vn 0.4510 0.3131 -0.8358 +vn 0.4095 0.1171 -0.9047 +vn 0.4562 0.3461 -0.8198 +vn 0.4230 0.1700 0.8901 +vn 0.3596 0.2644 0.8949 +vn 0.4928 0.0519 0.8686 +vn 0.3252 0.3117 0.8928 +vn -0.5866 -0.2844 0.7583 +vn -0.8218 0.5554 0.1276 +vn 0.8581 -0.3166 -0.4043 +vn -0.1181 0.9376 -0.3269 +vn -0.0450 0.9796 -0.1960 +vn -0.1038 0.9392 -0.3274 +vn -0.1040 0.9446 -0.3114 +vn -0.0646 0.9440 -0.3235 +vn -0.1174 0.9435 -0.3099 +vn 0.3481 0.9367 -0.0378 +vn 0.3433 0.9352 -0.0868 +vn 0.2421 0.9701 0.0139 +vn 0.1871 0.9363 -0.2973 +vn 0.2230 0.9372 -0.2683 +vn 0.2029 0.9373 -0.2834 +vn 0.2748 0.9369 -0.2159 +vn 0.2641 0.9415 -0.2095 +vn 0.2482 0.9330 -0.2608 +vn 0.0035 0.9430 -0.3328 +vn 0.2300 0.8774 -0.4210 +vn 0.1881 0.9090 -0.3720 +vn 0.0234 0.9403 -0.3396 +vn -0.0371 0.9625 -0.2689 +vn 0.0837 0.9361 -0.3416 +vn 0.1233 0.9365 -0.3284 +vn 0.3229 0.9379 -0.1267 +vn 0.5412 -0.4875 0.6851 +vn -0.8129 -0.4890 -0.3163 +vn -0.0259 0.3580 -0.9334 +vn 0.6440 -0.3695 -0.6699 +vn 0.9148 0.3457 -0.2089 +vn 0.8228 0.4786 0.3064 +vn 0.2364 -0.4880 0.8402 +vn -0.3443 0.6511 0.6764 +vn -0.8009 -0.4899 0.3444 +vn -0.7860 0.2815 -0.5504 +vn 0.0474 -0.2561 -0.9655 +vn 0.3802 0.1609 -0.9108 +vn 0.9768 -0.2034 0.0666 +vn -0.7356 -0.3915 0.5528 +vn -0.6524 0.2282 -0.7227 +vn -0.6661 0.3366 -0.6656 +vn -0.6071 0.0388 -0.7936 +vn -0.5700 -0.0692 -0.8187 +vn 0.6371 -0.0285 -0.7703 +vn 0.6489 0.6214 -0.4390 +vn 0.0129 -0.9399 0.3411 +vn 0.0042 0.0508 0.9987 +vn 0.0059 0.0575 0.9983 +vn -0.0017 0.0278 0.9996 +vn -0.0029 0.0231 0.9997 +vn 0.0029 0.0601 -0.9982 +vn 0.0026 0.0588 -0.9983 +vn 0.0008 0.0516 -0.9987 +vn 0.0004 0.0498 -0.9988 +vn -0.3455 0.7268 0.5936 +vn -0.2689 0.9231 0.2747 +vn -0.2472 0.8260 0.5065 +vn -0.2312 0.8204 0.5230 +vn 0.5623 0.7497 0.3489 +vn 0.5642 0.7462 0.3534 +vn 0.5657 0.7433 0.3570 +vn 0.6903 0.6593 -0.2980 +vn 0.8000 0.5621 -0.2100 +vn 0.5803 0.7331 -0.3549 +vn 0.2013 0.8176 -0.5394 +vn 0.2000 0.4643 0.8628 +vn 0.5603 0.7534 0.3443 +vn 0.3693 0.7780 -0.5083 +vn -0.2627 0.7941 -0.5481 +vn -0.0848 0.8065 -0.5851 +vn -0.3145 0.7596 -0.5693 +vn -0.6044 0.7856 -0.1321 +vn -0.6887 0.7190 -0.0931 +vn -0.8493 0.5280 0.0021 +vn -0.8910 0.4526 0.0352 +vn -0.0156 -0.9424 0.3342 +vn 0.7954 -0.4941 -0.3511 +vn -0.5179 -0.1050 0.8489 +vn -0.7482 -0.1130 -0.6538 +vn 0.6504 -0.1162 -0.7507 +vn 0.6877 -0.1097 0.7176 +vn -0.7065 -0.7076 -0.0105 +vn -0.8039 -0.5942 -0.0262 +vn -0.8942 -0.4377 0.0942 +vn -0.6472 -0.7614 -0.0379 +vn -0.7896 -0.6123 -0.0409 +vn -0.4212 -0.7498 0.5102 +vn -0.1606 -0.8471 0.5066 +vn -0.1557 -0.8506 0.5022 +vn -0.0075 -0.9138 0.4061 +vn -0.0086 -0.9172 0.3984 +vn 0.5448 -0.7648 0.3440 +vn 0.8291 -0.5402 0.1438 +vn 0.8226 -0.5533 0.1314 +vn 0.7836 -0.6212 0.0115 +vn 0.7790 -0.6165 -0.1147 +vn 0.8006 -0.5980 -0.0370 +vn 0.7652 -0.6302 -0.1318 +vn 0.7359 -0.6732 0.0727 +vn 0.7991 -0.5997 0.0421 +vn 0.8028 -0.5950 0.0385 +vn 0.5489 -0.6916 -0.4696 +vn -0.1872 -0.8070 -0.5602 +vn -0.0064 -0.8698 -0.4934 +vn -0.0048 -0.8640 -0.5035 +vn -0.1441 -0.8043 -0.5765 +vn -0.4477 -0.7578 -0.4746 +vn -0.6232 -0.7674 0.1506 +vn -0.8847 -0.4395 -0.1556 +vn -0.9198 -0.3447 -0.1874 +vn -0.0181 0.9986 -0.0487 +vn -0.0205 0.9988 -0.0440 +vn -0.0517 0.9976 -0.0465 +vn -0.0291 0.9991 -0.0303 +vn 0.0032 0.9962 -0.0867 +vn -0.0508 0.9985 -0.0204 +vn -0.0478 0.9987 -0.0157 +vn -0.0333 0.9951 0.0930 +vn -0.0220 0.9969 0.0757 +vn -0.0490 0.9667 0.2513 +vn -0.0154 0.9997 0.0166 +vn 0.0011 0.9993 0.0383 +vn 0.0373 0.9986 0.0376 +vn 0.0393 0.9989 0.0263 +vn -0.0004 1.0000 -0.0003 +vn -0.0003 1.0000 0.0001 +vn -0.0002 1.0000 0.0004 +vn -0.0690 0.9953 0.0680 +vn 0.0002 1.0000 0.0000 +vn 0.0043 0.9994 0.0357 +vn -0.0213 0.9981 0.0570 +vn 0.0325 0.9984 0.0461 +vn 0.0382 0.9992 0.0106 +vn 0.0610 0.9970 0.0473 +vn 0.0969 0.9922 0.0789 +vn 0.1826 0.9562 0.2288 +vn 0.0143 0.9997 0.0189 +vn 0.0110 0.9236 -0.3832 +vn 0.0499 0.9940 -0.0974 +vn 0.1010 0.9946 -0.0224 +vn -0.0290 0.9604 -0.2770 +vn -0.0606 0.9975 -0.0356 +vn 0.0001 1.0000 -0.0002 +vn -0.1330 0.9911 0.0093 +vn -0.0609 0.9962 -0.0627 +vn -0.0653 0.9962 -0.0583 +vn -0.0114 0.9937 -0.1113 +vn -0.0017 -0.9913 -0.1319 +vn -0.0115 -0.9999 0.0040 +vn 0.0003 -0.9934 -0.1148 +vn -0.0157 -0.9998 -0.0102 +vn -0.0318 -0.9772 0.2101 +vn -0.0233 -0.9994 0.0274 +vn 0.0497 -0.9858 0.1606 +vn 0.0054 -0.9998 0.0179 +vn 0.0524 -0.9822 0.1806 +vn -0.0132 -0.9999 0.0069 +vn 0.0234 -0.9995 0.0226 +vn 0.0079 -1.0000 -0.0043 +vn -0.0493 -0.9975 -0.0506 +vn -0.0206 -0.9997 -0.0152 +vn -0.0029 -0.9993 0.0364 +vn 0.0156 -0.9998 0.0105 +vn 0.0441 -0.9937 0.1035 +vn -0.0208 -0.9936 -0.1113 +vn -0.0017 -0.9999 -0.0111 +vn -0.0289 -0.9969 -0.0729 +vn -0.0139 -0.9999 -0.0093 +vn 0.0127 -0.9999 0.0022 +vn -0.0116 -0.9999 0.0111 +vn -0.0081 -1.0000 -0.0013 +vn 0.0128 -0.9998 -0.0150 +vn 0.0070 -1.0000 -0.0020 +vn 0.0171 -0.9998 -0.0059 +vn 0.1909 -0.9812 0.0269 +vn -0.0087 -1.0000 0.0010 +vn 0.0091 -1.0000 0.0010 +vn 0.0086 -0.9999 -0.0068 +vn 0.0117 -0.9999 -0.0055 +vn -0.0029 -1.0000 -0.0095 +vn -0.0095 -0.9999 -0.0091 +vn 0.0270 -0.9987 -0.0434 +vn 0.0528 -0.9927 -0.1087 +vn -0.0120 -0.9999 0.0011 +vn 0.0251 -0.9993 -0.0259 +vn 0.0250 -0.9992 -0.0326 +vn 0.0325 -0.9809 -0.1917 +vn 0.0020 1.0000 -0.0023 +vn -0.0050 0.9998 -0.0193 +vn -0.0037 0.9997 -0.0260 +vn -0.0086 0.9994 -0.0341 +vn -0.0125 0.9997 -0.0225 +vn -0.0029 1.0000 0.0012 +vn -0.0023 1.0000 0.0011 +vn -0.0170 0.9999 0.0029 +vn 0.0052 1.0000 0.0024 +vn 0.0037 0.9999 0.0153 +vn 0.0039 1.0000 0.0020 +vn -0.0125 0.9999 0.0032 +vn 0.0017 1.0000 -0.0016 +vn 0.0123 0.9999 0.0015 +vn -0.0087 0.9999 0.0148 +vn -0.0031 1.0000 -0.0025 +vn -0.4067 -0.0179 0.9134 +vn -0.3922 -0.0396 0.9190 +vn -0.3803 -0.0572 0.9231 +vn -0.3678 -0.0753 0.9268 +vn -0.8025 -0.2877 0.5227 +vn -0.9726 0.1928 0.1302 +vn -0.7923 -0.0755 -0.6054 +vn -0.7590 -0.0006 -0.6511 +vn -0.7231 0.0671 -0.6875 +vn -0.6755 0.1443 -0.7231 +vn 0.1126 -0.1127 -0.9872 +vn 0.1956 -0.0049 -0.9807 +vn 0.2598 0.0820 -0.9622 +vn 0.3358 0.1894 -0.9227 +vn 0.9217 -0.0772 -0.3803 +vn 0.9384 -0.0237 -0.3447 +vn 0.9488 0.0190 -0.3153 +vn 0.9593 0.0815 -0.2705 +vn 0.7418 0.0284 0.6701 +vn 0.7363 0.0130 0.6765 +vn 0.7469 0.0436 0.6635 +vn 0.7517 0.0585 0.6569 +vn -0.0000 -1.0000 0.0001 +vn -0.0001 -1.0000 0.0000 +vn 0.0001 -1.0000 -0.0001 +vn -0.0001 -1.0000 -0.0001 +vn 0.0001 -1.0000 0.0001 +vn 0.0001 -1.0000 0.0002 +vn 0.1877 -0.0257 0.9819 +vn -0.0274 -0.0049 0.9996 +vn 0.1553 -0.0225 0.9876 +vn -0.0532 -0.0023 0.9986 +vn -0.7247 -0.0932 0.6827 +vn -0.8853 -0.0287 -0.4641 +vn -0.9899 0.0512 -0.1322 +vn -0.9782 0.0346 -0.2049 +vn -0.8355 -0.0506 -0.5472 +vn 0.4255 0.0149 -0.9048 +vn 0.3498 0.0401 -0.9360 +vn 0.3662 0.0348 -0.9299 +vn 0.4466 0.0077 -0.8947 +vn 0.9803 -0.0425 0.1927 +vn 0.8783 0.0309 0.4770 +vn 0.9657 -0.0264 0.2582 +vn 0.8493 0.0446 0.5260 +vn 0.0145 -0.9999 0.0047 +vn 0.0173 -0.9998 -0.0014 +vn 0.0151 -0.9999 0.0069 +vn 0.0247 -0.9994 -0.0225 +vn 0.0172 -0.9998 -0.0044 +vn 0.0303 0.9995 0.0033 +vn -0.0457 0.9989 0.0081 +vn 0.0244 -0.9997 0.0004 +vn 0.0165 -0.9964 -0.0830 +vn 0.0232 -0.9997 -0.0119 +vn 0.0304 -0.9974 0.0646 +vn 0.5529 0.0412 -0.8322 +vn 0.5806 0.0320 -0.8136 +vn 0.6857 -0.0059 -0.7279 +vn 0.7165 -0.0181 -0.6973 +vn 0.7947 -0.0325 0.6061 +vn 0.8650 -0.0738 0.4964 +vn 0.8089 -0.0402 0.5866 +vn 0.8790 -0.0833 0.4695 +vn -0.1879 0.0445 0.9812 +vn -0.7593 -0.0827 0.6455 +vn -0.8014 -0.0475 -0.5962 +vn -0.9591 0.0368 -0.2805 +vn -0.9356 0.0190 -0.3527 +vn -0.7387 -0.0700 -0.6704 +vn -0.0375 -0.9952 -0.0903 +vn 0.1194 -0.9922 -0.0357 +vn 0.1519 -0.9882 0.0190 +vn 0.0779 -0.9931 0.0879 +vn 0.0439 -0.9934 0.1061 +vn -0.1066 -0.9897 0.0954 +vn -0.0366 -0.9952 -0.0910 +vn -0.1230 -0.9909 0.0543 +vn -0.0473 0.2253 -0.9731 +vn -0.8921 -0.0181 -0.4514 +vn -0.9139 -0.0994 -0.3935 +vn -0.9180 -0.1198 -0.3781 +vn -0.9263 -0.1802 -0.3309 +vn -0.6580 0.1315 0.7414 +vn -0.5283 -0.0066 0.8490 +vn -0.5033 -0.0306 0.8636 +vn -0.3684 -0.1487 0.9177 +vn 0.2890 0.2199 0.9317 +vn 0.8882 -0.2388 0.3926 +vn 0.9555 0.2489 -0.1586 +vn 0.4662 -0.2837 -0.8380 +vn -0.1707 0.7659 -0.6199 +vn 0.9536 -0.2281 -0.1966 +vn 0.1087 0.7442 0.6590 +vn 0.1043 0.7418 0.6625 +vn 0.1679 0.7745 0.6099 +vn 0.0467 0.7074 0.7053 +vn -0.9060 -0.1178 -0.4065 +vn 0.0289 0.9994 0.0209 +vn -0.0451 0.9989 -0.0111 +vn -0.0158 -0.9999 0.0049 +vn -0.1251 -0.9921 0.0140 +vn -0.0091 -0.9999 0.0044 +vn 0.0922 -0.9957 -0.0039 +vn 0.5788 0.0233 -0.8151 +vn 0.3583 -0.0706 -0.9309 +vn 0.5338 0.0028 -0.8456 +vn 0.3042 -0.0914 -0.9482 +vn 0.9952 0.0482 0.0856 +vn 0.6688 -0.0925 0.7376 +vn -0.4769 -0.0380 0.8782 +vn -0.1445 0.0274 0.9891 +vn -0.2088 0.0155 0.9778 +vn -0.5506 -0.0536 0.8331 +vn -0.9752 0.0453 -0.2168 +vn -0.9559 0.0241 -0.2929 +vn -0.8322 -0.0541 -0.5518 +vn -0.7804 -0.0768 -0.6206 +vn 0.1235 -0.9898 -0.0706 +vn 0.0761 -0.9907 -0.1124 +vn 0.1229 -0.9919 0.0333 +vn -0.0617 -0.9900 -0.1270 +vn 0.1242 -0.9673 0.2209 +vn -0.0386 -0.9928 0.1134 +vn -0.1256 -0.9893 0.0742 +vn -0.1343 -0.9909 -0.0017 +vn -0.0858 -0.9861 -0.1424 +vn -0.6844 0.1303 -0.7174 +vn -0.8071 0.0032 -0.5904 +vn -0.7958 0.0168 -0.6054 +vn -0.8826 -0.1072 -0.4577 +vn -0.9312 0.1388 0.3370 +vn -0.8974 0.0364 0.4398 +vn -0.8882 0.0156 0.4593 +vn -0.8270 -0.0928 0.5545 +vn 0.3943 0.0581 0.9171 +vn 0.4323 0.1249 0.8930 +vn 0.3714 0.0188 0.9283 +vn 0.3303 -0.0476 0.9427 +vn 0.9833 0.0438 -0.1767 +vn 0.9615 -0.0399 -0.2717 +vn 0.9605 -0.0427 -0.2748 +vn 0.9291 -0.1134 -0.3520 +vn 0.3446 0.1686 -0.9235 +vn 0.2081 0.0554 -0.9765 +vn 0.2057 0.0535 -0.9771 +vn 0.0577 -0.0653 -0.9962 +vn -0.7445 -0.0713 -0.6638 +vn -0.0042 0.7919 -0.6107 +vn 0.9706 -0.2020 0.1308 +vn -0.1254 0.7392 0.6618 +vn -0.1352 0.7344 0.6651 +vn 0.0042 0.7923 0.6101 +vn -0.2630 0.6627 0.7012 +vn -0.0285 0.9984 0.0490 +vn 0.0292 0.9995 -0.0151 +vn 0.0346 0.9993 -0.0151 +vn 0.0251 0.9996 -0.0150 +vn 0.0221 0.9996 -0.0150 +vn -0.0394 -0.9992 0.0034 +vn -0.0172 -0.9929 0.1181 +vn -0.0206 -0.9947 0.1006 +vn -0.8935 -0.0154 -0.4489 +vn -0.6801 -0.2639 0.6839 +vn -0.1329 0.0943 -0.9866 +vn 0.5072 -0.0878 -0.8574 +vn 0.8865 0.0269 0.4619 +vn 0.8976 0.0179 0.4405 +vn 0.8895 0.0246 0.4564 +vn 0.8999 0.0159 0.4358 +vn -0.4642 0.0005 0.8858 +vn -0.4845 -0.0068 0.8748 +vn -0.5512 -0.0316 0.8337 +vn -0.5687 -0.0383 0.8216 +vn 0.0744 -0.9816 0.1760 +vn -0.0245 -0.9922 0.1218 +vn -0.1519 -0.9807 0.1227 +vn -0.1817 -0.9743 0.1329 +vn 0.0778 -0.9935 0.0829 +vn 0.0693 -0.9960 0.0562 +vn -0.0326 -0.9980 -0.0547 +vn 0.8067 -0.1179 -0.5791 +vn 0.7913 -0.2275 -0.5676 +vn 0.8401 -0.1459 -0.5224 +vn -0.8925 -0.1200 0.4348 +vn -0.8929 -0.1193 0.4341 +vn -0.8601 -0.1714 0.4804 +vn 0.0161 0.1602 0.9869 +vn 0.4674 -0.1866 0.8641 +vn 0.7944 0.1169 0.5960 +vn 0.8793 -0.0694 -0.4712 +vn 0.8249 -0.1778 -0.5366 +vn -0.1072 0.1982 -0.9743 +vn -0.8018 -0.0726 -0.5932 +vn -0.7189 -0.1606 -0.6763 +vn -0.8017 -0.0726 -0.5933 +vn -0.8783 0.0350 -0.4768 +vn -0.9246 -0.0574 0.3765 +vn -0.8416 -0.2469 0.4804 +vn -0.8325 0.5540 0.0058 +vn 0.5062 0.0078 -0.8624 +vn 0.6508 0.7447 0.1481 +vn 0.6577 0.7279 0.1940 +vn 0.6172 0.7868 -0.0043 +vn 0.6691 0.6503 0.3597 +vn 0.0010 -0.9779 0.2093 +vn -0.0048 0.9996 0.0286 +vn -0.0290 -0.9996 -0.0071 +vn -0.0153 -0.9965 0.0817 +vn -0.0260 -0.9996 0.0123 +vn -0.0395 -0.9965 -0.0738 +vn -0.7134 -0.0665 0.6976 +vn -0.9994 0.0330 0.0091 +vn -0.7906 -0.0968 -0.6046 +vn -0.2130 0.0101 -0.9770 +vn 0.7257 -0.1021 -0.6804 +vn 0.9957 0.0316 -0.0876 +vn 0.7675 -0.0945 0.6340 +vn 0.0467 0.0530 0.9975 +vn 0.1628 -0.9749 0.1518 +vn 0.0106 -0.9914 0.1308 +vn -0.0977 -0.9879 0.1203 +vn 0.1034 -0.9945 0.0174 +vn -0.0992 -0.9902 -0.0987 +vn -0.0115 -0.9879 -0.1550 +vn -0.1026 -0.9912 -0.0842 +vn -0.1268 -0.9909 0.0449 +vn 0.0779 -0.9968 -0.0195 +vn 0.5765 0.0324 0.8164 +vn 0.6594 -0.0701 0.7486 +vn 0.6692 -0.0827 0.7385 +vn 0.7220 -0.1607 0.6730 +vn 0.9473 0.2484 -0.2024 +vn 0.6573 -0.2839 -0.6982 +vn 0.0433 -0.0785 -0.9960 +vn 0.1765 -0.2352 -0.9558 +vn 0.0446 -0.0800 -0.9958 +vn -0.0866 0.0754 -0.9934 +vn -0.9190 0.1090 -0.3788 +vn -0.9525 0.0175 -0.3041 +vn -0.9567 0.0021 -0.2910 +vn -0.9728 -0.0845 -0.2155 +vn -0.5566 0.0315 0.8302 +vn -0.5540 0.0350 0.8318 +vn -0.5568 0.0309 0.8300 +vn -0.5591 0.0276 0.8287 +vn 0.0634 0.7156 0.6956 +vn 0.1120 0.7496 0.6523 +vn 0.1151 0.7517 0.6494 +vn 0.1651 0.7829 0.5999 +vn -0.9334 0.2986 0.1988 +vn -0.1977 0.6673 -0.7181 +vn 0.0751 0.2943 -0.9528 +vn 0.7535 0.5768 0.3155 +vn -0.0274 0.9989 -0.0371 +vn -0.0077 -0.9992 -0.0390 +vn -0.0078 -0.9992 -0.0386 +vn 0.0564 -0.9965 -0.0615 +vn -0.0809 -0.9966 -0.0130 +vn -0.3469 -0.0534 0.9364 +vn 0.0070 0.0208 0.9998 +vn -0.0582 0.0073 0.9983 +vn -0.4218 -0.0694 0.9040 +vn -0.9500 -0.0372 -0.3099 +vn -0.9977 0.0230 -0.0634 +vn -0.9934 0.0106 -0.1146 +vn -0.9298 -0.0508 -0.3646 +vn 0.3366 -0.0596 -0.9397 +vn 0.0278 0.0204 -0.9994 +vn 0.0984 0.0023 -0.9951 +vn 0.4048 -0.0777 -0.9111 +vn 0.8821 -0.0519 0.4683 +vn 0.9952 0.0349 0.0917 +vn 0.9851 0.0174 0.1711 +vn 0.8396 -0.0694 0.5388 +vn 0.1163 -0.9879 0.1024 +vn 0.0304 -0.9920 0.1223 +vn -0.0983 -0.9885 0.1151 +vn 0.1247 -0.9922 -0.0067 +vn 0.1490 -0.9758 -0.1598 +vn -0.0790 -0.9920 -0.0983 +vn 0.0055 -0.9911 -0.1330 +vn -0.1117 -0.9922 -0.0555 +vn -0.1341 -0.9876 0.0814 +vn 0.4432 0.2311 0.8661 +vn 0.7952 -0.1963 0.5737 +vn 0.8912 0.2249 -0.3940 +vn 0.6617 -0.1553 -0.7335 +vn -0.0450 0.1387 -0.9893 +vn -0.4829 -0.1177 -0.8677 +vn -0.8341 0.1194 -0.5385 +vn -0.9874 -0.1577 0.0100 +vn -0.7656 0.2165 0.6058 +vn -0.3458 -0.1503 0.9262 +vn 0.4685 0.3731 0.8008 +vn 0.5285 0.7941 0.3001 +vn -0.4990 0.8363 0.2274 +vn -0.8658 -0.0924 -0.4918 +vn -0.3657 0.5848 -0.7241 +vn 0.6683 0.5175 -0.5343 +vn -0.0021 1.0000 0.0043 +vn 0.0129 -0.9999 -0.0079 +vn 0.6942 -0.0874 0.7144 +vn 0.1819 0.0970 0.9785 +vn -0.9525 -0.1276 0.2767 +vn -0.9129 0.0632 -0.4033 +vn 0.3178 -0.0910 -0.9438 +vn 0.6057 0.0049 -0.7957 +vn 0.4038 -0.0647 -0.9126 +vn 0.6732 0.0313 -0.7388 +vn 0.2099 -0.9774 0.0261 +vn 0.1109 -0.9888 -0.0996 +vn 0.1436 -0.9826 0.1178 +vn -0.1858 -0.9748 0.1233 +vn -0.0191 -0.9901 0.1393 +vn -0.1860 -0.9825 -0.0135 +vn -0.0563 -0.9911 -0.1203 +vn -0.0031 -0.9905 -0.1377 +vn 0.9899 -0.1414 -0.0046 +vn 0.4524 0.2178 -0.8648 +vn 0.3908 0.1281 -0.9115 +vn 0.3566 0.0804 -0.9308 +vn 0.2760 -0.0255 -0.9608 +vn -0.9187 0.1500 -0.3653 +vn -0.8809 0.0204 -0.4729 +vn -0.9257 0.1958 -0.3237 +vn -0.9287 0.2877 -0.2340 +vn -0.7633 -0.2389 0.6003 +vn -0.0929 0.2120 0.9728 +vn 0.3745 -0.1156 0.9200 +vn 0.8736 0.2088 0.4395 +vn -0.4239 0.3941 0.8155 +vn 0.1643 0.8237 0.5428 +vn -0.7811 0.4853 -0.3930 +vn -0.1760 0.7945 -0.5812 +vn 0.7076 -0.6227 -0.3339 +vn -0.0070 0.9991 -0.0411 +vn 0.0252 0.9995 0.0184 +vn 0.0589 -0.9980 -0.0235 +vn 0.9044 -0.1316 -0.4059 +vn 0.6950 0.0776 0.7148 +vn 0.1015 -0.0938 0.9904 +vn -0.9553 0.0558 0.2904 +vn -0.8816 -0.1448 -0.4492 +vn 0.1799 0.1058 -0.9780 +vn 0.0627 -0.9953 0.0744 +vn 0.0568 -0.9922 0.1108 +vn -0.0113 -0.9760 0.2174 +vn -0.0961 -0.9922 0.0794 +vn 0.5641 -0.8250 0.0334 +vn -0.1140 -0.9893 -0.0914 +vn -0.1245 -0.9859 -0.1116 +vn -0.0023 -0.9936 -0.1128 +vn 0.0042 -0.9957 -0.0928 +vn 0.4891 0.2047 -0.8479 +vn -0.0890 -0.2558 -0.9626 +vn -0.6331 0.2066 -0.7460 +vn -0.9687 -0.2481 -0.0016 +vn -0.7646 0.2987 0.5711 +vn 0.1672 -0.0503 0.9846 +vn 0.0167 -0.1795 0.9836 +vn 0.2078 -0.0140 0.9781 +vn 0.3663 0.1335 0.9209 +vn 0.9929 -0.1176 -0.0157 +vn 0.9802 -0.1927 0.0454 +vn 0.9948 -0.0958 -0.0333 +vn 0.9935 0.0061 -0.1141 +vn 0.7246 0.4309 -0.5378 +vn 0.1984 0.2776 0.9400 +vn 0.3699 0.6822 0.6306 +vn -0.6746 0.5837 -0.4520 +vn -0.5029 -0.1107 -0.8572 +vn 0.0245 0.9997 -0.0090 +vn 0.0262 -0.9996 0.0086 +vn -0.6479 0.0683 0.7587 +vn -0.9868 -0.1312 -0.0946 +vn -0.9569 -0.1811 0.2270 +vn -0.9889 -0.1386 -0.0528 +vn -0.9354 -0.1899 0.2984 +vn 0.1293 0.0326 -0.9911 +vn 0.1910 0.0156 -0.9815 +vn 0.3728 -0.0366 -0.9272 +vn 0.4544 -0.0609 -0.8887 +vn 0.9161 0.0342 0.3996 +vn 0.5763 -0.1254 0.8076 +vn 0.1770 -0.9817 -0.0704 +vn 0.1188 -0.9918 0.0468 +vn 0.0361 -0.9890 0.1437 +vn -0.0881 -0.9932 0.0758 +vn -0.1423 -0.9894 0.0285 +vn 0.0079 -0.9836 0.1801 +vn 0.0478 -0.9949 -0.0890 +vn -0.1859 -0.9825 0.0063 +vn -0.0087 -0.9962 -0.0862 +vn 0.5785 -0.0909 0.8106 +vn 0.9011 0.1836 0.3929 +vn 0.9231 -0.2446 -0.2968 +vn 0.7072 0.1252 -0.6958 +vn -0.1769 0.0236 -0.9839 +vn -0.2542 -0.0753 -0.9642 +vn -0.2698 -0.0957 -0.9581 +vn -0.3318 -0.1790 -0.9262 +vn -0.9950 0.0998 -0.0031 +vn -0.9928 -0.0292 -0.1166 +vn -0.9927 0.1196 0.0146 +vn -0.9715 0.2148 0.1004 +vn -0.4310 -0.1640 0.8873 +vn 0.0493 0.1803 0.9824 +vn 0.1700 0.3725 0.9123 +vn -0.8244 0.5598 0.0838 +vn -0.8313 0.5504 0.0775 +vn -0.8281 0.5548 0.0804 +vn -0.8372 0.5422 0.0721 +vn -0.0512 0.3689 -0.9280 +vn 0.7072 0.7042 -0.0636 +vn 0.7086 0.7029 -0.0623 +vn 0.7082 0.7032 -0.0627 +vn 0.7097 0.7018 -0.0615 +vn -0.0206 0.9997 -0.0100 +vn 0.0070 0.9999 0.0143 +vn 0.0249 -0.9995 0.0219 +vn -0.8948 0.0728 0.4405 +vn -0.8445 -0.1219 -0.5215 +vn 0.1033 0.0985 -0.9898 +vn 0.8442 -0.1304 -0.5199 +vn 0.7605 0.0825 0.6440 +vn -0.0476 -0.1313 0.9902 +vn -0.0385 -0.9880 0.1498 +vn -0.1059 -0.9911 0.0811 +vn -0.1177 -0.9912 -0.0607 +vn 0.0510 -0.9922 0.1141 +vn 0.1496 -0.9871 -0.0564 +vn 0.1974 -0.9802 -0.0146 +vn -0.1270 -0.9873 -0.0956 +vn 0.0329 -0.9907 -0.1323 +vn -0.2345 0.0511 0.9708 +vn -0.2160 0.0711 0.9738 +vn -0.1513 0.1396 0.9786 +vn 0.9186 -0.0391 0.3932 +vn 0.8633 -0.1507 0.4816 +vn 0.9293 -0.0104 0.3691 +vn 0.9590 0.1120 0.2602 +vn 0.7139 0.0152 -0.7000 +vn 0.7247 0.0317 -0.6883 +vn 0.7239 0.0304 -0.6892 +vn 0.7339 0.0458 -0.6777 +vn -0.2524 -0.0162 -0.9675 +vn -0.2691 0.0026 -0.9631 +vn -0.2503 -0.0186 -0.9680 +vn -0.2320 -0.0390 -0.9719 +vn -0.9968 0.0543 0.0581 +vn -0.9968 0.0518 0.0601 +vn -0.9968 0.0514 0.0609 +vn -0.9968 0.0485 0.0628 +vn -0.3020 -0.0243 0.9530 +vn -0.5644 0.7371 0.3717 +vn -0.5419 0.6488 0.5342 +vn -0.5660 0.7474 0.3478 +vn -0.5677 0.7971 0.2058 +vn -0.4529 -0.3849 -0.8042 +vn 0.8350 -0.1949 0.5146 +vn 0.5790 0.7878 -0.2099 +vn 0.0056 0.9999 -0.0109 +vn 0.0074 1.0000 -0.0000 +vn 0.0096 0.9999 0.0029 +vn -0.0126 0.9995 -0.0275 +vn 0.0103 0.9999 -0.0128 +vn 0.0168 0.9998 -0.0112 +vn -0.0346 -0.9993 0.0161 +vn -0.1304 -0.9911 -0.0284 +vn -0.1498 -0.9880 -0.0375 +vn -0.8738 0.1275 -0.4693 +vn -0.2178 -0.0550 -0.9744 +vn 0.9012 -0.0057 -0.4334 +vn 0.9053 -0.0026 -0.4248 +vn 0.9023 -0.0048 -0.4312 +vn 0.9061 -0.0019 -0.4230 +vn 0.3324 -0.0384 0.9424 +vn 0.1723 0.0130 0.9850 +vn 0.2906 -0.0248 0.9565 +vn 0.1340 0.0249 0.9907 +vn -0.9884 -0.0617 0.1390 +vn 0.1154 -0.9913 0.0640 +vn 0.1322 -0.9910 0.0205 +vn 0.0384 -0.9912 0.1264 +vn -0.1103 -0.9876 0.1116 +vn -0.1019 -0.9902 -0.0954 +vn 0.0089 -0.9629 -0.2698 +vn 0.1082 -0.9891 -0.1000 +vn -0.1586 -0.9839 0.0825 +vn -0.9454 0.0330 -0.3241 +vn -0.9730 -0.0606 -0.2225 +vn -0.9738 -0.0647 -0.2179 +vn -0.9813 -0.1375 -0.1349 +vn -0.6679 0.2402 0.7045 +vn -0.3507 -0.1640 0.9220 +vn 0.7687 0.1205 0.6282 +vn 0.7478 0.0763 0.6595 +vn 0.7730 0.1303 0.6209 +vn 0.7862 0.1625 0.5962 +vn 0.9438 -0.1473 -0.2958 +vn 0.7151 0.1773 -0.6762 +vn -0.0682 -0.0521 -0.9963 +vn -0.0035 -0.1125 -0.9936 +vn -0.0751 -0.0457 -0.9961 +vn -0.1547 0.0301 -0.9875 +vn 0.2773 0.4921 -0.8252 +vn 0.5108 0.5968 0.6188 +vn -0.9501 0.3059 -0.0612 +vn -0.2547 -0.9631 -0.0868 +vn -0.0032 0.9998 -0.0177 +vn -0.0126 0.9997 0.0189 +vn -0.0014 -0.9999 -0.0134 +vn -0.0387 -0.9969 0.0684 +vn -0.0006 -0.9999 -0.0152 +vn 0.0316 -0.9959 -0.0850 +vn 0.5046 0.0496 -0.8619 +vn 0.9198 -0.1083 -0.3771 +vn 0.7860 0.0370 0.6172 +vn 0.2268 -0.0789 0.9707 +vn -0.5595 0.0373 0.8280 +vn -0.9556 -0.0727 0.2854 +vn -0.6111 -0.0455 -0.7902 +vn -0.8389 0.0172 -0.5440 +vn -0.8020 0.0052 -0.5973 +vn -0.5507 -0.0587 -0.8326 +vn -0.1572 -0.9866 0.0427 +vn -0.0860 -0.9890 0.1207 +vn -0.1379 -0.9895 -0.0433 +vn 0.1593 -0.9865 -0.0382 +vn 0.0180 -0.9945 -0.1034 +vn 0.1912 -0.9815 -0.0129 +vn 0.0046 -0.9890 0.1481 +vn 0.0721 -0.9911 0.1117 +vn -0.0765 -0.9888 -0.1280 +vn -0.6286 -0.0360 -0.7769 +vn -0.5721 -0.1167 -0.8119 +vn -0.6519 0.0004 -0.7583 +vn -0.7012 0.0869 -0.7076 +vn -0.8855 0.0810 0.4575 +vn -0.9324 -0.0191 0.3610 +vn -0.8751 0.0988 0.4738 +vn -0.8174 0.1822 0.5464 +vn -0.0833 -0.2134 0.9734 +vn 0.4178 0.1554 0.8952 +vn 0.9340 0.0418 0.3547 +vn 0.9067 -0.0134 0.4216 +vn 0.9322 0.0374 0.3601 +vn 0.9534 0.0958 0.2860 +vn 0.7078 0.0178 -0.7061 +vn 0.7683 -0.0773 -0.6354 +vn 0.6910 0.0411 -0.7216 +vn 0.6148 0.1361 -0.7769 +vn 0.4117 -0.2032 -0.8884 +vn 0.5901 0.8057 -0.0508 +vn 0.0756 -0.4222 0.9034 +vn -0.7215 0.6569 -0.2191 +vn -0.6651 0.7425 -0.0796 +vn -0.6577 0.7506 -0.0641 +vn -0.5955 0.8017 0.0513 +vn -0.0044 1.0000 0.0084 +vn 0.0022 0.9994 -0.0356 +vn -0.0305 -0.9994 -0.0166 +vn 0.5476 0.0360 -0.8360 +vn 0.8548 -0.0642 0.5149 +vn 0.8158 -0.0419 0.5768 +vn 0.8462 -0.0590 0.5296 +vn 0.8051 -0.0363 0.5921 +vn -0.5385 0.0066 0.8426 +vn -0.6183 -0.0173 0.7858 +vn -0.8211 -0.0887 0.5638 +vn -0.8627 -0.1066 0.4944 +vn -0.9125 0.0476 -0.4063 +vn 0.0364 -0.1144 -0.9928 +vn 0.1766 -0.9830 -0.0504 +vn 0.1268 -0.9908 0.0464 +vn 0.0769 -0.9847 0.1565 +vn 0.0727 -0.9955 -0.0601 +vn 0.0973 -0.9931 -0.0662 +vn -0.2020 -0.9753 0.0898 +vn -0.0330 -0.9929 0.1143 +vn -0.1445 -0.9895 0.0085 +vn -0.1116 -0.9935 -0.0232 +vn -0.2892 -0.8228 -0.4893 +vn -0.5237 -0.1105 -0.8447 +vn -0.5109 -0.0908 -0.8548 +vn -0.5076 -0.0857 -0.8573 +vn -0.4976 -0.0707 -0.8645 +vn -0.9820 0.1622 0.0962 +vn -0.8530 -0.2580 0.4538 +vn 0.1475 0.2346 0.9608 +vn 0.4964 -0.1437 0.8561 +vn 0.9768 0.1721 0.1274 +vn 0.8936 -0.1969 -0.4034 +vn 0.6224 0.1575 -0.7667 +vn 0.5309 -0.3412 -0.7757 +vn -0.0315 -0.1411 0.9895 +vn 0.6009 0.7899 0.1225 +vn -0.6492 0.7560 -0.0844 +vn -0.6598 0.7437 -0.1081 +vn -0.6611 0.7421 -0.1110 +vn -0.6720 0.7278 -0.1370 +vn -0.0114 0.9998 0.0140 +vn -0.0808 -0.9949 -0.0598 +vn -0.0838 -0.9946 -0.0616 +vn 0.0561 -0.9982 0.0194 +vn 0.9655 -0.0259 -0.2590 +vn 0.9694 -0.0307 -0.2435 +vn 0.9809 -0.0474 -0.1888 +vn 0.9836 -0.0523 -0.1728 +vn 0.1438 0.0043 0.9896 +vn 0.2372 -0.0240 0.9712 +vn 0.1653 -0.0022 0.9862 +vn 0.2542 -0.0292 0.9667 +vn -0.9365 0.0188 0.3501 +vn -0.9623 -0.0060 0.2720 +vn -0.9575 -0.0009 0.2883 +vn -0.9274 0.0262 0.3731 +vn -0.3212 -0.0498 -0.9457 +vn -0.1664 -0.0046 -0.9861 +vn -0.2823 -0.0382 -0.9586 +vn -0.1305 0.0057 -0.9914 +vn -0.1767 -0.9508 0.2546 +vn -0.0861 -0.9963 0.0041 +vn -0.1628 -0.9653 -0.2040 +vn 0.2317 -0.9622 0.1435 +vn 0.1348 -0.9906 -0.0247 +vn 0.0341 -0.9906 0.1323 +vn 0.0178 -0.9919 -0.1260 +vn 0.0927 -0.9892 -0.1140 +vn 0.6597 -0.1293 -0.7403 +vn 0.1869 0.2518 -0.9496 +vn -0.6054 -0.2899 -0.7412 +vn -0.9265 0.3666 -0.0842 +vn -0.5844 -0.3566 0.7289 +vn 0.0419 0.2976 0.9538 +vn 0.8168 -0.2422 0.5237 +vn 0.9712 0.2381 0.0005 +vn 0.6001 -0.6063 -0.5218 +vn -0.1455 0.6380 0.7562 +vn -0.0392 0.7248 0.6878 +vn -0.0585 0.7103 0.7015 +vn 0.0534 0.7859 0.6161 +vn -0.9490 0.3154 0.0002 +vn -0.0590 0.7287 -0.6822 +vn -0.2134 -0.9675 -0.1360 +vn -0.0272 0.9996 -0.0101 +vn 0.0142 0.9997 0.0219 +vn 0.0075 -0.9998 -0.0201 +vn 0.0365 -0.9916 0.1240 +vn 0.0322 -0.9940 0.1043 +vn 0.8344 -0.0030 0.5512 +vn 0.7605 0.0309 0.6486 +vn 0.8198 0.0042 0.5726 +vn 0.7466 0.0366 0.6642 +vn -0.4224 -0.0538 0.9048 +vn -0.6881 0.0128 0.7255 +vn -0.4915 -0.0381 0.8701 +vn -0.7286 0.0245 0.6845 +vn -0.9279 -0.0816 -0.3637 +vn -0.7935 -0.0109 -0.6085 +vn -0.9057 -0.0671 -0.4185 +vn -0.7529 0.0056 -0.6581 +vn 0.6403 -0.0309 -0.7675 +vn 0.6495 -0.0348 -0.7596 +vn 0.6772 -0.0467 -0.7343 +vn 0.6857 -0.0504 -0.7262 +vn -0.1154 -0.9933 0.0014 +vn -0.1243 -0.9922 -0.0132 +vn -0.0369 -0.9931 -0.1114 +vn 0.0050 -0.9936 -0.1126 +vn 0.1254 -0.9920 -0.0167 +vn 0.0770 -0.9915 0.1046 +vn -0.0019 -0.9884 0.1520 +vn -0.0766 -0.9909 0.1110 +vn 0.1385 -0.9901 -0.0227 +vn 0.9274 0.0053 0.3740 +vn 0.9286 0.0086 0.3711 +vn 0.9430 0.0561 0.3281 +vn 0.6949 0.0063 -0.7191 +vn 0.6953 0.0056 -0.7187 +vn 0.6948 0.0065 -0.7192 +vn 0.6943 0.0072 -0.7196 +vn -0.5460 0.0946 -0.8324 +vn -0.6086 0.0027 -0.7935 +vn -0.6315 -0.0352 -0.7745 +vn -0.6795 -0.1214 -0.7236 +vn -0.9271 0.0881 0.3642 +vn -0.9051 0.0315 0.4239 +vn -0.9037 0.0282 0.4273 +vn -0.8747 -0.0286 0.4838 +vn -0.0964 0.0990 0.9904 +vn -0.0486 0.0489 0.9976 +vn -0.0442 0.0442 0.9980 +vn 0.0086 -0.0115 0.9999 +vn 0.9083 -0.0432 0.4160 +vn 0.9275 -0.0749 0.3663 +vn 0.6227 0.7542 -0.2083 +vn -0.4143 0.8008 0.4325 +vn -0.8329 0.4784 0.2784 +vn -0.5121 -0.0736 -0.8558 +vn 0.0684 -0.9549 0.2890 +vn -0.0297 0.9995 0.0080 +vn -0.0388 0.9992 0.0016 +vn 0.0085 0.9995 -0.0292 +vn 0.0304 0.9993 -0.0199 +vn 0.1278 0.9903 0.0539 +vn 0.0622 0.9955 0.0710 +vn 0.0067 0.9999 0.0134 +vn 0.0343 0.9977 -0.0588 +vn -0.0005 -1.0000 0.0010 +vn -0.0001 -1.0000 0.0019 +vn -0.0067 -1.0000 -0.0025 +vn -0.0006 -1.0000 -0.0017 +vn 0.0002 -1.0000 -0.0032 +vn 0.0019 -1.0000 0.0046 +vn -0.0000 -1.0000 -0.0001 +vn 0.0000 -1.0000 -0.0002 +vn -0.0006 -1.0000 0.0006 +vn 0.0305 -0.9994 -0.0163 +vn 0.0060 -0.9993 -0.0377 +vn 0.0066 -0.9990 0.0433 +vn 0.0008 -0.9997 0.0229 +vn -0.0006 -1.0000 -0.0000 +vn 0.0227 -0.9970 0.0738 +vn 0.0323 -0.9993 0.0167 +vn -0.8769 0.3508 0.3286 +vn 0.0648 -0.9979 0.0041 +vn 0.0541 -0.9977 -0.0404 +vn 0.0043 -1.0000 -0.0085 +vn 0.0358 -0.9982 -0.0486 +vn 0.0296 -0.9980 -0.0557 +vn -0.0007 -1.0000 -0.0001 +vn 0.0370 -0.9967 -0.0724 +vn 0.0135 -0.9999 -0.0005 +vn 0.0072 -1.0000 -0.0048 +vn 0.0132 -0.9999 -0.0001 +vn -0.0008 -1.0000 -0.0002 +vn 0.0002 -1.0000 0.0000 +vn 0.0603 -0.9980 -0.0187 +vn 0.0415 -0.9991 0.0077 +vn 0.0458 -0.9983 0.0355 +vn 0.0244 -0.9986 0.0469 +vn -0.0008 -1.0000 -0.0009 +vn -0.0004 1.0000 0.0010 +vn -0.0010 0.9999 -0.0111 +vn 0.0001 1.0000 -0.0023 +vn 0.0001 1.0000 -0.0008 +vn 0.0007 1.0000 -0.0012 +vn 0.0006 1.0000 0.0059 +vn 0.0000 1.0000 0.0016 +vn -0.0002 1.0000 0.0008 +vn -0.0002 1.0000 0.0001 +vn 0.0002 1.0000 -0.0010 +vn 0.0002 1.0000 -0.0003 +vn -0.0002 1.0000 0.0007 +vn -0.0002 1.0000 0.0000 +vn 0.0010 1.0000 -0.0005 +vn 0.0009 1.0000 -0.0001 +vn -0.0000 1.0000 0.0010 +vn 0.0004 1.0000 -0.0004 +vn 0.0002 1.0000 0.0002 +vn 0.0005 1.0000 -0.0004 +vn -0.0000 1.0000 -0.0005 +vn 0.0001 1.0000 -0.0004 +vn -0.0002 1.0000 -0.0009 +vn -0.0003 1.0000 -0.0003 +vn 0.0347 0.9986 -0.0408 +vn 0.0154 0.9993 0.0331 +vn 0.5562 0.7813 -0.2831 +vn 0.0003 1.0000 0.0010 +vn 0.0001 1.0000 0.0008 +vn -0.0001 1.0000 -0.0051 +vn 0.0052 0.9999 0.0096 +vn 0.0003 1.0000 -0.0007 +vn -0.0006 1.0000 0.0030 +vn -0.0024 1.0000 0.0067 +vn -0.0008 1.0000 0.0053 +vn 0.0326 0.9986 0.0423 +vn 0.0004 1.0000 0.0042 +vn -0.1630 0.9836 0.0770 +vn 0.0015 1.0000 0.0008 +vn 0.0008 1.0000 -0.0000 +vn -0.0006 1.0000 -0.0062 +vn -0.0015 1.0000 -0.0050 +vn 0.0044 1.0000 -0.0081 +vn 0.0077 0.9999 -0.0103 +vn 0.0041 0.9998 -0.0205 +vn -0.0067 1.0000 -0.0042 +vn 0.0001 1.0000 0.0000 +vn 0.0130 0.9999 -0.0043 +vn 0.0093 1.0000 -0.0007 +vn -0.0001 1.0000 0.0044 +vn -0.0138 0.9999 -0.0004 +vn 0.0133 0.9999 -0.0027 +vn 0.1382 0.9877 -0.0728 +vn -0.0304 0.9967 0.0757 +vn 0.0301 0.9986 -0.0426 +vn -0.0285 0.9988 -0.0392 +vn -0.0132 -0.9998 -0.0134 +vn -0.0055 -1.0000 -0.0012 +vn -0.0104 -0.9998 -0.0143 +vn 0.3487 -0.7870 -0.5090 +vn -0.0473 -0.9833 -0.1756 +vn -0.0053 -0.9977 -0.0677 +vn 0.0071 -0.9999 -0.0075 +vn -0.0116 -0.9998 -0.0129 +vn -0.0083 -0.9998 -0.0191 +vn 0.0044 -0.9987 -0.0509 +vn -0.0077 -1.0000 -0.0039 +vn 0.0033 -0.9978 -0.0662 +vn 0.0079 -0.9979 -0.0641 +vn -0.0037 -0.9980 -0.0634 +vn 0.0002 -1.0000 0.0006 +vn 0.0008 -1.0000 0.0002 +vn 0.0012 -1.0000 -0.0009 +vn 0.0000 -1.0000 0.0010 +vn 0.0025 -1.0000 0.0011 +vn -0.0132 -0.9999 0.0081 +vn -0.0076 -1.0000 0.0038 +vn 0.0000 -1.0000 -0.0012 +vn -0.0027 -1.0000 -0.0007 +vn 0.0071 -1.0000 -0.0015 +vn 0.0017 -1.0000 -0.0002 +vn -0.0118 -0.9999 -0.0086 +vn -0.0055 -1.0000 0.0065 +vn -0.0098 -0.9999 -0.0065 +vn 0.0042 -1.0000 -0.0037 +vn 0.0145 -0.9997 -0.0186 +vn 0.0027 -1.0000 0.0004 +vn -0.0175 0.1162 -0.9931 +vn 0.5867 -0.2361 -0.7746 +vn 0.9719 0.1991 0.1253 +vn 0.3142 -0.1258 0.9410 +vn 0.2891 -0.1629 0.9433 +vn 0.2944 -0.1551 0.9430 +vn 0.2696 -0.1908 0.9439 +vn -0.8891 0.1789 0.4214 +vn -0.9931 -0.1083 -0.0451 +vn -0.3507 -0.9023 -0.2507 +vn -0.2720 -0.8742 -0.4021 +vn -0.5013 -0.7355 -0.4558 +vn -0.5266 -0.3631 -0.7686 +vn -0.6726 -0.6976 -0.2469 +vn -0.6709 -0.7415 -0.0069 +vn -0.6689 -0.7433 -0.0067 +vn -0.3902 -0.8196 -0.4194 +vn -0.2088 -0.8169 -0.5377 +vn -0.3429 -0.7720 -0.5352 +vn -0.2113 -0.8116 -0.5446 +vn -0.2491 -0.7084 -0.6604 +vn -0.1954 -0.9803 0.0277 +vn -0.6948 -0.7128 0.0961 +vn -0.3452 -0.9369 0.0558 +vn -0.6270 -0.7201 -0.2973 +vn -0.5751 -0.2511 -0.7786 +vn -0.8620 -0.4666 0.1981 +vn -0.7599 -0.6418 0.1030 +vn -0.6318 -0.7752 0.0051 +vn -0.1126 -0.3662 -0.9237 +vn -0.0343 -0.3141 -0.9488 +vn -0.0267 -0.5231 -0.8518 +vn -0.0435 -0.7098 -0.7031 +vn -0.0416 -0.7534 -0.6563 +vn -0.2419 -0.9685 -0.0598 +vn -0.3149 -0.9252 -0.2118 +vn -0.1449 -0.9761 -0.1619 +vn -0.2203 -0.7449 -0.6297 +vn -0.0699 -0.9633 -0.2592 +vn -0.0435 -0.9732 -0.2257 +vn -0.1472 -0.9436 -0.2966 +vn -0.8385 -0.5329 -0.1138 +vn -0.5724 -0.8190 -0.0397 +vn -0.0594 -0.8788 -0.4735 +vn -0.4369 -0.7768 -0.4536 +vn -0.4574 -0.6952 -0.5545 +vn -0.6060 -0.7954 0.0115 +vn -0.5811 -0.7984 -0.1577 +vn -0.4323 -0.8921 -0.1316 +vn -0.0557 -0.6951 -0.7168 +vn -0.6513 -0.5457 -0.5273 +vn -0.6432 -0.6619 -0.3849 +vn -0.8234 -0.5582 -0.1023 +vn -0.4509 -0.5059 -0.7354 +vn -0.3180 -0.7213 -0.6153 +vn -0.8186 -0.5682 0.0839 +vn -0.8285 -0.4659 -0.3108 +vn -0.8831 -0.4586 0.0996 +vn -0.3002 -0.5083 -0.8071 +vn -0.5525 -0.4890 -0.6750 +vn -0.7799 -0.4433 -0.4418 +vn -0.9011 -0.4039 -0.1578 +vn -0.1065 0.0340 -0.9937 +vn -0.0351 -0.4383 0.8982 +vn -0.2123 -0.6069 0.7659 +vn -0.1228 -0.8154 0.5658 +vn -0.3845 -0.3216 0.8653 +vn -0.3300 -0.6228 0.7094 +vn -0.6341 -0.3156 0.7059 +vn -0.4443 -0.5852 0.6784 +vn -0.7991 -0.3441 0.4930 +vn -0.4342 -0.8099 0.3943 +vn -0.9625 -0.2707 0.0162 +vn -0.7274 -0.6099 0.3144 +vn -0.6689 -0.6499 0.3608 +vn -0.1581 -0.9647 0.2108 +vn 0.1772 -0.9261 0.3330 +vn 0.1660 -0.8986 0.4061 +vn 0.1622 -0.9867 0.0122 +vn 0.1098 -0.5893 0.8004 +vn 0.1775 -0.3074 0.9349 +vn 0.2284 -0.3547 0.9067 +vn 0.1867 -0.9132 0.3623 +vn 0.1516 -0.9814 0.1178 +vn -0.0009 -0.5971 0.8022 +vn 0.2195 -0.2836 0.9335 +vn -0.0132 -0.8919 0.4521 +vn 0.0001 -0.8780 0.4787 +vn 0.0685 -0.7350 0.6745 +vn 0.4897 -0.6591 0.5708 +vn 0.5509 -0.3806 0.7427 +vn 0.6759 -0.3147 0.6664 +vn 0.5077 -0.7018 0.4997 +vn 0.3138 -0.8126 0.4912 +vn 0.5886 -0.2415 0.7715 +vn 0.5556 -0.4870 0.6739 +vn 0.5690 -0.6642 0.4848 +vn 0.1729 -0.9442 0.2805 +vn 0.1046 -0.9943 0.0203 +vn 0.1461 -0.9811 0.1272 +vn 0.0900 -0.9903 0.1056 +vn 0.3647 -0.5439 0.7558 +vn 0.0376 -0.9021 0.4298 +vn -0.4610 -0.2886 -0.8392 +vn -0.1358 -0.0263 -0.9904 +vn -0.0276 -0.0752 -0.9968 +vn -0.2937 0.0241 -0.9556 +vn -0.4441 0.0453 -0.8948 +vn -0.5835 0.0364 -0.8113 +vn -0.7072 -0.0021 -0.7070 +vn -0.8013 -0.0616 -0.5951 +vn -0.9014 -0.0924 -0.4231 +vn -0.8441 -0.1147 -0.5238 +vn -0.9603 -0.0424 -0.2756 +vn -0.9927 -0.0192 -0.1188 +vn -0.9988 -0.0240 0.0416 +vn -0.9781 -0.0568 0.2004 +vn -0.9327 -0.1279 0.3372 +vn -0.7295 -0.4331 -0.5293 +vn -0.7754 -0.0809 -0.6262 +vn -0.9153 -0.0905 -0.3924 +vn -0.9155 -0.2815 -0.2874 +vn -0.8572 -0.3722 -0.3560 +vn -0.9953 0.0106 -0.0960 +vn -0.9993 -0.0335 -0.0156 +vn -0.9759 0.0286 -0.2163 +vn -0.8586 -0.1863 -0.4776 +vn 0.1098 -0.9927 -0.0492 +vn 0.0627 -0.9839 -0.1672 +vn 0.1559 -0.9838 -0.0881 +vn 0.0465 -0.9987 -0.0199 +vn -0.1924 -0.9751 0.1103 +vn -0.1388 -0.9829 0.1206 +vn -0.2348 -0.9719 -0.0148 +vn 0.0002 -0.9553 -0.2956 +vn -0.0074 -0.9904 -0.1382 +vn 0.1047 -0.9658 -0.2374 +vn 0.1518 -0.9700 -0.1898 +vn 0.0772 -0.9708 -0.2272 +vn 0.4624 -0.8043 -0.3733 +vn 0.5099 -0.8341 -0.2106 +vn -0.0558 -0.9873 -0.1487 +vn -0.0362 -0.9764 -0.2130 +vn -0.0555 -0.9971 -0.0514 +vn -0.0011 -0.9676 0.2523 +vn -0.0102 -0.9967 0.0805 +vn 0.2052 -0.9786 -0.0157 +vn 0.5211 -0.8527 -0.0364 +vn 0.0724 -0.7632 -0.6420 +vn 0.0891 -0.9614 -0.2603 +vn 0.0009 -0.8735 -0.4869 +vn -0.0264 -0.9650 -0.2608 +vn -0.0196 -0.9433 -0.3315 +vn -0.0977 -0.9952 -0.0052 +vn -0.0954 -0.9937 -0.0587 +vn -0.0971 -0.9930 0.0667 +vn -0.0625 -0.9776 0.2009 +vn -0.0893 -0.9665 0.2408 +vn -0.1042 -0.9711 0.2148 +vn -0.4571 -0.8782 -0.1410 +vn -0.3128 -0.9486 -0.0485 +vn -0.0094 -0.9388 0.3444 +vn 0.0509 -0.9492 0.3106 +vn 0.0882 -0.9551 0.2829 +vn -0.2855 -0.9106 -0.2990 +vn -0.0814 -0.9929 -0.0871 +vn -0.0157 -0.7710 -0.6367 +vn -0.0096 -0.9293 -0.3691 +vn -0.0084 -0.9071 -0.4209 +vn -0.0103 -0.9344 -0.3562 +vn 0.0995 -0.9652 -0.2419 +vn 0.4101 -0.6847 -0.6025 +vn 0.2301 -0.9700 0.0780 +vn -0.1564 -0.9859 0.0598 +vn -0.1765 -0.9838 -0.0327 +vn -0.1343 -0.9906 0.0279 +vn 0.0001 -0.0121 -0.9999 +vn 0.0492 -0.2549 -0.9657 +vn 0.1869 0.0117 -0.9823 +vn 0.0009 0.0027 -1.0000 +vn -0.8257 0.0068 0.5640 +vn -0.5483 0.0174 0.8361 +vn -0.1836 0.0105 0.9829 +vn -0.2098 -0.0195 0.9776 +vn 0.9557 0.0033 -0.2945 +vn 0.9867 -0.0218 -0.1613 +vn 0.9426 -0.0110 -0.3336 +vn 0.7938 -0.3664 -0.4854 +vn 0.8057 0.0100 -0.5923 +vn 0.6278 -0.3798 -0.6794 +vn 0.5400 0.0085 -0.8416 +vn 0.4312 -0.3182 -0.8443 +vn 0.2406 -0.3019 -0.9225 +vn -0.0054 0.0028 1.0000 +vn -0.9151 -0.3195 0.2458 +vn -0.4712 -0.0756 -0.8788 +vn -0.1576 -0.0748 -0.9847 +vn 0.0547 -0.2292 -0.9718 +vn -0.4727 0.0084 0.8812 +vn 0.2826 0.2963 0.9123 +vn 0.3412 -0.1229 0.9319 +vn 0.2763 0.3253 0.9043 +vn 0.3441 -0.1707 0.9233 +vn 0.8355 -0.3522 0.4218 +vn 0.6723 0.7189 0.1766 +vn 0.7643 -0.6194 -0.1794 +vn 0.5365 0.6733 -0.5088 +vn -0.9139 -0.3691 -0.1687 +vn -0.7173 -0.6769 -0.1650 +vn -0.7013 -0.5979 -0.3881 +vn -0.8434 -0.5356 -0.0420 +vn -0.4072 -0.7938 -0.4517 +vn -0.9163 -0.2198 0.3348 +vn -0.9871 -0.0711 0.1435 +vn -0.9845 -0.0916 -0.1498 +vn -0.3688 -0.8187 -0.4402 +vn 0.0053 -0.9999 0.0107 +vn -0.0037 -1.0000 -0.0058 +vn 0.0244 -0.9992 0.0319 +vn 0.0063 -0.0716 0.9974 +vn 0.0144 -0.9999 0.0042 +vn 0.0465 -0.9986 0.0249 +vn 0.0458 -0.9989 0.0035 +vn -0.0071 -1.0000 -0.0015 +vn 0.0797 -0.9735 0.2145 +vn 0.2504 -0.9674 0.0374 +vn -0.0225 -0.9994 0.0262 +vn -0.1141 -0.9778 0.1759 +vn 0.1848 -0.9760 0.1154 +vn 0.2019 -0.8786 0.4328 +vn 0.2766 -0.9266 0.2548 +vn 0.1420 -0.9828 0.1180 +vn -0.0089 -0.9998 -0.0182 +vn 0.9018 -0.4029 0.1565 +vn 0.7296 -0.2357 -0.6420 +vn -0.0857 0.2055 -0.9749 +vn -0.1619 -0.5025 -0.8493 +vn -0.6074 0.6265 -0.4885 +vn 0.2133 -0.0743 0.9742 +vn -0.1044 -0.0736 0.9918 +vn -0.2523 -0.2131 0.9439 +vn -0.0062 -0.7592 0.6509 +vn 0.1962 -0.2668 0.9436 +vn 0.1757 -0.7162 0.6754 +vn -0.0028 -0.8038 0.5949 +vn 0.0425 -0.5902 0.8061 +vn 0.0878 -0.0763 0.9932 +vn 0.1417 -0.4891 0.8606 +vn -0.0025 -0.8475 0.5309 +vn 0.0246 -0.9351 0.3536 +vn 0.0094 -0.9250 0.3799 +vn 0.4085 -0.5900 0.6965 +vn 0.5397 -0.5562 0.6320 +vn 0.5788 -0.5291 0.6205 +vn 0.5802 -0.7803 0.2335 +vn 0.7270 -0.6500 0.2214 +vn 0.8146 -0.4768 0.3301 +vn 0.5202 -0.8509 0.0728 +vn 0.3203 -0.9412 0.1074 +vn 0.9832 -0.0595 0.1728 +vn 0.9325 -0.3522 0.0805 +vn 0.8446 -0.5047 0.1788 +vn 0.9144 -0.3932 0.0963 +vn 0.7554 -0.4725 0.4539 +vn 0.6593 -0.5548 0.5074 +vn 0.3632 -0.4820 0.7974 +vn 0.1998 -0.6256 0.7541 +vn 0.4826 -0.7380 0.4716 +vn 0.4947 -0.8002 0.3391 +vn 0.3350 -0.7866 0.5187 +vn 0.1885 -0.8282 0.5277 +vn 0.6920 -0.7100 0.1303 +vn 0.7302 -0.6715 0.1261 +vn 0.6604 -0.7406 0.1238 +vn 0.2022 -0.9451 0.2568 +vn 0.7487 -0.6393 0.1752 +vn 0.5013 -0.5856 0.6370 +vn 0.2550 -0.7630 0.5940 +vn 0.1249 -0.7911 0.5988 +vn 0.5415 -0.5009 0.6752 +vn 0.0124 -0.6345 0.7728 +vn 0.0129 -0.6298 0.7767 +vn 0.4912 -0.7011 0.5169 +vn -0.7858 -0.3817 -0.4866 +vn 0.4709 -0.2514 0.8456 +vn -0.8671 -0.3147 -0.3861 +vn -0.9801 0.1882 0.0629 +vn -0.0922 -0.1574 0.9832 +vn 0.6145 0.2254 0.7560 +vn 0.8133 -0.2986 -0.4994 +vn 0.2565 0.2934 -0.9209 +vn -0.1711 -0.1207 -0.9778 +vn 0.2982 -0.5325 -0.7921 +vn -0.8961 0.2506 -0.3662 +vn -0.5017 -0.0965 0.8597 +vn -0.4485 -0.0500 0.8924 +vn -0.6251 -0.2141 0.7506 +vn -0.3103 0.0628 0.9486 +vn 0.9793 -0.0072 0.2022 +vn 0.9881 0.0228 0.1522 +vn 0.9387 -0.0877 0.3333 +vn 0.9913 0.1285 -0.0297 +vn -0.9479 -0.2354 -0.2145 +vn -0.6022 0.1555 0.7830 +vn -0.4172 0.0457 0.9077 +vn -0.4344 0.0554 0.8990 +vn -0.2728 -0.0327 0.9615 +vn 0.7595 0.0203 0.6502 +vn 0.8325 -0.0291 0.5532 +vn 0.7949 -0.0025 0.6068 +vn 0.8556 -0.0469 0.5156 +vn 0.6172 -0.1017 -0.7802 +vn 0.6975 -0.0356 -0.7157 +vn 0.7891 0.0544 -0.6118 +vn 0.4832 -0.1956 -0.8534 +vn -0.7960 0.2325 -0.5588 +vn 0.7627 0.0808 0.6417 +vn 0.7017 -0.0932 -0.7063 +vn 0.7925 0.3673 -0.4868 +vn -0.4515 -0.2950 -0.8421 +vn -0.8466 0.2132 -0.4876 +vn -0.9332 -0.0963 0.3463 +vn -0.4180 0.0821 0.9047 +vn 0.2781 -0.1325 0.9514 +vn -0.0129 -0.9999 -0.0031 +vn -0.0206 -0.9989 -0.0426 +vn -0.0376 -0.9993 -0.0029 +vn -0.0134 -0.9952 0.0973 +vn 0.0073 -0.9992 0.0380 +vn 1.0000 0.0015 0.0034 +vn 0.9856 -0.0006 0.1694 +vn 0.9922 -0.0042 0.1244 +vn 0.9593 -0.0084 0.2824 +vn 0.9013 -0.0084 0.4331 +vn 0.8206 -0.0054 0.5714 +vn 0.7103 -0.0068 0.7039 +vn 0.7233 -0.0109 0.6904 +vn 0.6082 -0.0236 0.7934 +vn 0.0395 -0.0031 0.9992 +vn -0.0036 0.0000 1.0000 +vn 0.0918 -0.0061 0.9958 +vn 0.3857 -0.0295 0.9222 +vn 0.3557 -0.0271 0.9342 +vn 0.4883 -0.0210 0.8724 +vn 0.2505 -0.0407 0.9673 +vn 0.0999 -0.0407 0.9942 +vn 0.1350 -0.0440 0.9899 +vn 0.0293 -0.0507 0.9983 +vn 0.0090 -0.0194 0.9998 +vn 0.7121 -0.0360 0.7011 +vn 0.7327 -0.0092 0.6805 +vn 0.7989 -0.0235 0.6010 +vn 0.5957 -0.0524 0.8015 +vn 0.4940 -0.0384 0.8686 +vn 0.3480 0.0157 0.9373 +vn 0.1912 0.0362 0.9809 +vn 0.0490 0.0098 0.9987 +vn 0.7322 -0.0947 0.6744 +vn 0.7218 -0.0282 0.6915 +vn 0.7368 -0.0150 0.6759 +vn 0.6524 -0.0312 0.7572 +vn 0.5453 -0.0121 0.8381 +vn 0.4287 0.0377 0.9027 +vn 0.2115 -0.0032 0.9774 +vn 0.3415 0.0133 0.9398 +vn 0.9994 0.0039 -0.0344 +vn 1.0000 0.0000 0.0092 +vn -0.0400 0.0030 -0.9992 +vn -0.0379 0.0000 -0.9993 +vn -0.0411 0.0045 -0.9991 +vn -0.0433 0.0075 -0.9990 +vn -0.9938 -0.1005 0.0470 +vn -0.9809 0.0002 0.1945 +vn -0.9926 -0.0614 0.1050 +vn -0.9862 -0.1600 -0.0431 +vn -0.0219 -0.0053 -0.9997 +vn -0.0214 -0.0041 -0.9998 +vn -0.0216 -0.0046 -0.9998 +vn -0.0221 -0.0057 -0.9997 +vn -0.3625 -0.0509 -0.9306 +vn -0.5876 0.0165 -0.8090 +vn -0.6400 0.0440 -0.7671 +vn -0.5573 0.0073 -0.8303 +vn -0.5552 0.0082 -0.8316 +vn -0.5622 0.0051 -0.8270 +vn -0.5644 0.0042 -0.8255 +vn -0.7317 0.0181 -0.6814 +vn -0.7349 0.0041 -0.6782 +vn 0.0073 0.9999 0.0069 +vn 0.0824 0.9965 -0.0158 +vn 0.0334 0.9994 -0.0020 +vn 0.0001 1.0000 0.0002 +vn 0.0001 1.0000 0.0053 +vn 0.0013 1.0000 0.0013 +vn 0.0032 1.0000 0.0007 +vn 0.0060 0.9999 -0.0104 +vn 0.0124 0.9947 0.1019 +vn 0.0003 1.0000 0.0014 +vn 0.0074 1.0000 0.0018 +vn 0.0053 1.0000 0.0045 +vn 0.0097 0.9743 0.2249 +vn -0.0079 1.0000 0.0059 +vn 0.7896 0.1778 -0.5873 +vn 0.2698 -0.1598 -0.9496 +vn -0.7830 0.1548 -0.6024 +vn -0.9747 -0.2149 0.0607 +vn -0.1354 0.2567 0.9569 +vn 0.5044 -0.5634 0.6544 +vn 0.9191 -0.0367 0.3924 +vn 0.8809 0.0987 -0.4629 +vn 0.3715 -0.2797 -0.8853 +vn -0.2010 0.0622 -0.9776 +vn -0.9779 -0.1384 0.1566 +vn -0.9976 -0.0693 0.0052 +vn -0.9907 -0.0032 -0.1361 +vn -0.9526 -0.1785 0.2465 +vn -0.2490 0.1441 0.9577 +vn 0.5771 -0.2142 0.7881 +vn 0.5130 -0.2685 0.8153 +vn 0.5895 -0.2030 0.7819 +vn 0.6932 -0.0987 0.7139 +vn 0.0108 -0.9993 -0.0348 +vn 0.0841 -0.9581 -0.2738 +vn 0.0142 -0.9988 -0.0461 +vn -0.0045 -0.9990 0.0446 +vn -0.0154 -0.9999 0.0073 +vn -0.0417 -0.9985 -0.0352 +vn -0.0192 -0.9992 0.0360 +vn -0.0382 -0.9940 -0.1025 +vn 0.7016 0.2523 -0.6665 +vn -0.1941 -0.3111 -0.9304 +vn -0.7460 0.0737 -0.6618 +vn -0.6917 -0.0559 0.7200 +vn -0.6989 -0.0481 0.7136 +vn -0.7100 -0.0357 0.7033 +vn -0.6788 -0.0697 0.7310 +vn 0.8985 0.0430 0.4369 +vn 0.5519 -0.3652 0.7497 +vn -0.9534 0.0003 0.3018 +vn -0.9413 0.0022 0.3375 +vn -0.9852 -0.0004 0.1717 +vn -0.9505 -0.0000 0.3107 +vn -0.0117 0.0003 -0.9999 +vn -0.0379 -0.0016 -0.9993 +vn -0.1734 -0.0013 -0.9849 +vn -0.9994 -0.0280 -0.0214 +vn -0.9977 0.0124 -0.0661 +vn -0.3521 -0.0327 -0.9354 +vn -0.3692 0.0304 -0.9288 +vn -0.5037 0.0628 -0.8616 +vn -0.6257 0.0297 -0.7795 +vn -0.7328 -0.0314 -0.6797 +vn -0.8181 -0.1177 -0.5629 +vn -0.8631 -0.0975 -0.4956 +vn -0.9345 -0.0140 -0.3556 +vn -0.9763 0.0254 -0.2150 +vn -0.3629 -0.0045 -0.9318 +vn -0.5637 -0.0068 -0.8259 +vn -0.4339 -0.0296 -0.9005 +vn -0.5358 -0.0421 -0.8433 +vn -0.6312 -0.0197 -0.7754 +vn -0.7160 0.0361 -0.6972 +vn -0.7614 0.0007 -0.6483 +vn -0.9312 -0.0041 -0.3645 +vn -0.8462 -0.0244 -0.5323 +vn -0.6746 -0.0142 -0.7380 +vn -0.7965 -0.0181 -0.6043 +vn -0.9078 -0.0311 -0.4182 +vn -0.8547 -0.0088 -0.5190 +vn -0.9081 -0.0245 -0.4179 +vn -0.9491 -0.0195 -0.3143 +vn -0.9874 -0.0183 -0.1572 +vn -0.9749 -0.0276 -0.2211 +vn -0.9936 -0.0395 -0.1057 +vn -0.9994 -0.0266 -0.0216 +vn -0.9137 -0.0162 -0.4060 +vn -0.9653 -0.0027 -0.2611 +vn -0.9929 -0.0007 -0.1193 +vn -0.9993 -0.0054 0.0363 +vn -0.9820 -0.0034 0.1889 +vn -0.1519 -0.0058 -0.9884 +vn -0.3032 -0.0089 -0.9529 +vn -0.4522 0.0004 -0.8919 +vn -0.5728 0.0021 -0.8197 +vn -0.6927 -0.0176 -0.7210 +vn 0.9096 0.0264 -0.4146 +vn 0.9188 0.0433 -0.3924 +vn 0.9041 0.0169 -0.4270 +vn 0.8938 0.0000 -0.4485 +vn 0.2773 -0.0098 0.9607 +vn 0.2858 -0.0000 0.9583 +vn 0.2761 -0.0112 0.9611 +vn 0.2675 -0.0210 0.9633 +vn 0.0000 0.0000 -1.0000 +vn 0.5514 0.0089 0.8342 +vn 0.3701 -0.0079 0.9290 +vn 0.3705 -0.0091 0.9288 +vn 0.6189 -0.0081 0.7854 +vn 0.9472 0.0124 0.3204 +vn 0.8160 0.0267 0.5774 +vn 0.8851 -0.0174 0.4651 +vn 0.9731 -0.0085 0.2303 +vn 0.7486 0.0216 0.6627 +vn 0.8158 -0.0157 0.5781 +vn 0.9990 0.0093 0.0441 +vn 0.9990 0.0083 0.0435 +vn -0.0001 1.0000 -0.0001 +vn -0.0023 1.0000 -0.0066 +vn 0.0000 1.0000 -0.0008 +vn -0.0026 1.0000 0.0075 +vn -0.0026 1.0000 -0.0005 +vn -0.0003 1.0000 -0.0000 +vn -0.1830 0.9800 0.0781 +vn -0.0639 0.9978 0.0176 +vn -0.0312 0.9995 -0.0071 +vn -0.0001 1.0000 0.0002 +vn -0.0206 0.9984 -0.0528 +vn -0.0371 0.9904 -0.1335 +vn 0.0017 1.0000 -0.0061 +vn 0.4548 -0.6872 0.5665 +vn 0.4757 -0.3430 0.8100 +vn 0.4802 -0.6715 0.5644 +vn 0.4173 -0.5935 0.6882 +vn -0.6805 -0.6728 -0.2902 +vn -0.5268 -0.2421 -0.8148 +vn -0.3957 -0.6411 -0.6576 +vn -0.5343 -0.6173 -0.5775 +vn -0.7033 -0.0873 -0.7055 +vn -0.9013 -0.2408 0.3601 +vn -0.9069 0.0000 0.4214 +vn 0.3179 -0.6589 -0.6817 +vn 0.6353 -0.7628 -0.1206 +vn 0.7892 -0.6132 -0.0329 +vn 0.7379 -0.6251 -0.2545 +vn 0.2784 -0.5466 -0.7898 +vn -0.3813 -0.4611 -0.8013 +vn -0.3360 -0.7498 -0.5700 +vn -0.5697 -0.0222 -0.8216 +vn -0.2921 -0.8193 -0.4933 +vn -0.2923 -0.8191 -0.4936 +vn -0.0006 -0.5425 -0.8400 +vn -0.5743 -0.8087 -0.1271 +vn -0.7166 -0.6820 -0.1460 +vn -0.7521 -0.6428 -0.1453 +vn -0.7992 -0.5489 -0.2450 +vn -0.5951 -0.6902 -0.4116 +vn -0.7173 -0.5034 -0.4817 +vn -0.7930 -0.0345 0.6082 +vn -0.3495 0.0541 0.9354 +vn 0.3553 -0.0437 0.9337 +vn 0.9785 0.0446 0.2016 +vn 0.8908 -0.0535 -0.4512 +vn 0.4383 0.0320 -0.8982 +vn -0.7247 0.0147 -0.6889 +vn -0.7904 -0.0159 -0.6123 +vn -0.8023 -0.0218 -0.5965 +vn -0.7080 0.0220 -0.7059 +vn 0.5756 -0.0424 -0.8166 +vn 0.3833 0.0042 -0.9236 +vn 0.6096 -0.0512 -0.7910 +vn 0.3387 0.0143 -0.9408 +vn -0.8570 0.0062 -0.5152 +vn -0.8848 -0.0062 -0.4658 +vn -0.8614 0.0043 -0.5079 +vn -0.8896 -0.0084 -0.4566 +vn -0.6911 -0.0034 0.7228 +vn -0.5084 0.0336 0.8604 +vn -0.7223 -0.0106 0.6915 +vn -0.4796 0.0389 0.8766 +vn 0.5889 -0.0589 0.8061 +vn 0.9571 0.0556 0.2844 +vn -0.6001 0.0189 0.7997 +vn -0.8261 -0.0282 0.5628 +vn -0.7988 -0.0215 0.6012 +vn -0.5536 0.0270 0.8324 +vn 0.4639 -0.0250 0.8855 +vn 0.7341 0.0402 0.6778 +vn 0.4016 -0.0380 0.9150 +vn 0.7689 0.0501 0.6374 +vn 0.8041 -0.0375 -0.5933 +vn 0.5710 0.0222 -0.8206 +vn 0.8368 -0.0478 -0.5455 +vn 0.5234 0.0325 -0.8515 +vn -0.6802 -0.0185 -0.7328 +vn -0.8259 0.0197 -0.5635 +vn -0.6497 -0.0253 -0.7598 +vn -0.8532 0.0283 -0.5209 +vn 0.7555 -0.0090 -0.6551 +vn 0.6789 0.0136 -0.7341 +vn 0.7694 -0.0134 -0.6387 +vn 0.6592 0.0190 -0.7517 +vn -0.5963 -0.0131 -0.8027 +vn -0.5861 -0.0105 -0.8102 +vn -0.5948 -0.0127 -0.8038 +vn -0.5837 -0.0099 -0.8119 +vn -0.8774 0.0101 0.4797 +vn -0.8955 0.0177 0.4446 +vn -0.7915 -0.0202 0.6108 +vn -0.7732 -0.0259 0.6336 +vn 0.7063 -0.0025 0.7079 +vn 0.6223 0.0240 0.7824 +vn 0.6072 0.0285 0.7941 +vn 0.7238 -0.0085 0.6899 +vn -0.1948 0.0856 0.9771 +vn 0.4990 -0.0971 0.8611 +vn 0.9009 0.1029 -0.4216 +vn 0.4041 -0.0880 -0.9105 +vn -0.8025 0.0781 -0.5916 +vn -0.9976 -0.0675 -0.0143 +vn 0.7658 -0.0633 0.6399 +vn 0.9524 0.0792 -0.2944 +vn 0.6770 -0.0739 -0.7323 +vn -0.7775 -0.0194 -0.6286 +vn -0.5925 0.0546 -0.8038 +vn -0.4954 0.0867 -0.8643 +vn -0.8381 -0.0496 -0.5433 +vn -0.9123 0.0341 0.4081 +vn -0.6746 -0.0371 0.7373 +vn -0.8693 0.0175 0.4940 +vn -0.6200 -0.0491 0.7830 +vn 0.1266 0.0649 0.9898 +vn 0.3480 -0.0817 -0.9339 +vn 0.4186 -0.0281 -0.9077 +vn 0.5491 0.0800 -0.8319 +vn 0.1940 -0.1895 -0.9625 +vn -0.7033 0.1809 -0.6875 +vn -0.9879 -0.1216 -0.0961 +vn -0.5496 0.1078 0.8284 +vn -0.3174 0.0006 0.9483 +vn -0.4454 0.0582 0.8934 +vn -0.1959 -0.0514 0.9793 +vn 0.8848 -0.0167 0.4657 +vn 0.9191 0.0321 0.3927 +vn 0.9022 0.0067 0.4312 +vn 0.8569 -0.0498 0.5131 +vn -0.6764 0.0867 -0.7314 +vn -0.9273 -0.3320 -0.1726 +vn -0.7299 0.2113 0.6500 +vn 0.5267 -0.0992 0.8443 +vn 0.5807 -0.0590 0.8120 +vn 0.4271 -0.1670 0.8887 +vn 0.6765 0.0202 0.7362 +vn 0.7350 -0.1015 -0.6705 +vn 0.8234 -0.2255 -0.5207 +vn 0.7182 -0.0817 -0.6911 +vn 0.6640 -0.0229 -0.7474 +vn -0.5637 0.0585 -0.8239 +vn -0.9936 -0.1000 -0.0531 +vn -0.8322 0.0568 0.5515 +vn 0.5711 0.0014 0.8209 +vn 0.6549 -0.0424 0.7545 +vn 0.5949 -0.0106 0.8037 +vn 0.6736 -0.0527 0.7372 +vn 0.6539 -0.0404 -0.7555 +vn 0.6043 -0.0160 -0.7966 +vn 0.6161 -0.0217 -0.7874 +vn 0.6636 -0.0454 -0.7467 +vn -0.5564 0.0238 0.8306 +vn -0.5768 0.0166 0.8167 +vn -0.6164 0.0025 0.7874 +vn -0.6304 -0.0027 0.7763 +vn 0.7505 -0.0171 0.6607 +vn 0.7953 0.0094 0.6062 +vn 0.7307 -0.0280 0.6822 +vn 0.8099 0.0186 0.5863 +vn 0.5812 -0.0163 -0.8136 +vn 0.5856 -0.0183 -0.8104 +vn 0.5797 -0.0156 -0.8147 +vn 0.5871 -0.0190 -0.8093 +vn -0.7907 0.0320 -0.6113 +vn -0.8590 -0.0047 -0.5120 +vn -0.8091 0.0228 -0.5872 +vn -0.8737 -0.0136 -0.4863 +vn 0.4304 0.2235 0.8745 +vn 0.9486 -0.2515 0.1920 +vn 0.9672 0.0825 -0.2402 +vn -0.0567 0.0622 -0.9964 +vn 0.1346 -0.0565 -0.9893 +vn 0.0119 0.0198 -0.9997 +vn -0.1565 0.1236 -0.9799 +vn -0.9480 -0.1306 -0.2904 +vn -0.8637 0.1540 0.4799 +vn -0.4059 -0.1683 0.8983 +vn -0.6611 0.1500 -0.7351 +vn -0.9771 -0.1402 0.1600 +vn -0.7446 0.0832 0.6623 +vn 0.4814 -0.0998 0.8708 +vn 0.4958 -0.0884 0.8639 +vn 0.4846 -0.0973 0.8693 +vn 0.4615 -0.1154 0.8796 +vn 0.8924 0.1532 -0.4244 +vn 0.3712 -0.1871 -0.9095 +vn -0.3605 -0.0338 -0.9322 +vn -0.6406 -0.0264 -0.7674 +vn -0.5394 0.0409 -0.8411 +vn -0.4275 0.0177 -0.9038 +vn -0.9998 -0.0120 -0.0182 +vn -0.8028 -0.0104 -0.5961 +vn -0.8832 -0.0252 -0.4684 +vn -0.8634 -0.0075 -0.5044 +vn -0.9405 -0.0175 -0.3393 +vn -0.9774 -0.0185 -0.2107 +vn -0.9963 -0.0179 -0.0840 +vn -0.7267 -0.0074 -0.6869 +vn -0.6185 -0.0331 -0.7851 +vn -0.3934 -0.0210 -0.9191 +vn -0.4975 -0.0355 -0.8668 +vn -0.3489 -0.0104 -0.9371 +vn 0.9908 0.0028 -0.1355 +vn 0.9936 -0.0686 -0.0898 +vn 0.9172 -0.1168 0.3809 +vn 0.0684 -0.0534 0.9962 +vn 0.1983 0.0350 0.9795 +vn 0.7262 -0.0125 0.6874 +vn 0.6531 0.0047 0.7573 +vn 0.5191 -0.0673 0.8521 +vn 0.4717 -0.1242 0.8730 +vn 0.3454 0.0139 0.9383 +vn 0.1291 -0.0666 0.9894 +vn 0.0224 -0.0868 0.9960 +vn 0.2609 -0.0986 0.9603 +vn 0.3536 -0.0554 0.9338 +vn 0.5019 -0.0179 0.8647 +vn 0.6163 -0.1137 0.7793 +vn 0.7029 -0.0945 0.7050 +vn 0.8136 -0.0356 0.5804 +vn 0.9000 -0.0067 0.4358 +vn 0.9606 -0.0095 0.2779 +vn 0.9963 -0.0862 -0.0065 +vn 0.9927 -0.0440 0.1124 +vn 0.7379 -0.0066 0.6748 +vn 0.0132 -0.0135 0.9998 +vn 0.7034 -0.0160 0.7106 +vn 0.4655 -0.0082 0.8850 +vn 0.0625 -0.0180 0.9979 +vn 0.6071 -0.0278 0.7942 +vn 0.1923 -0.0227 0.9811 +vn 0.3483 -0.0002 0.9374 +vn 0.0001 1.0000 0.0009 +vn -0.9491 -0.0078 -0.3148 +vn -0.8825 0.0208 -0.4698 +vn -0.8267 -0.0164 -0.5624 +vn -0.7996 -0.0095 -0.6004 +vn -0.7572 0.0156 -0.6531 +vn -0.6065 -0.0018 -0.7951 +vn -0.9990 -0.0093 -0.0441 +vn -0.9717 0.0092 -0.2362 +vn -0.3718 0.0046 -0.9283 +vn -0.3730 0.0078 -0.9278 +vn 0.5572 -0.0073 0.8303 +vn 0.5622 -0.0051 0.8270 +vn 0.5552 -0.0082 0.8317 +vn 0.7317 -0.0182 0.6814 +vn 0.5870 -0.0169 0.8094 +vn 0.6395 -0.0444 0.7675 +vn 0.0219 0.0053 0.9997 +vn 0.0216 0.0046 0.9998 +vn 0.0214 0.0041 0.9998 +vn 0.0432 -0.0031 0.9991 +vn 0.0442 -0.0044 0.9990 +vn 0.0409 -0.0000 0.9992 +vn 0.0466 -0.0075 0.9989 +vn 0.9761 0.1589 0.1485 +vn 0.9981 0.0613 0.0010 +vn 0.9931 0.1005 0.0600 +vn 0.9959 -0.0002 -0.0906 +vn -0.8598 -0.0181 0.5104 +vn -0.8673 -0.0074 0.4977 +vn -0.8649 -0.0108 0.5018 +vn -0.2633 0.0000 -0.9647 +vn -0.2582 -0.0063 -0.9661 +vn -0.2592 -0.0051 -0.9658 +vn -0.8723 -0.0000 0.4890 +vn -0.2540 -0.0113 -0.9671 +vn 0.0001 1.0000 -0.0001 +vn -0.5637 0.0083 -0.8260 +vn -0.9990 -0.0084 -0.0436 +vn 0.5644 -0.0041 0.8255 +vn 0.7349 -0.0041 0.6782 +vn 0.3613 0.0503 0.9311 +vn 0.0221 0.0057 0.9997 +vn -0.0123 -0.9990 -0.0433 +vn 0.0530 -0.9983 -0.0228 +vn 0.0188 -0.9998 -0.0097 +vn -0.0300 -0.9995 0.0015 +vn -0.0312 -0.9995 0.0080 +vn -0.0090 -0.9993 0.0371 +vn -0.0114 -0.9994 0.0328 +vn 0.0235 -0.9992 0.0339 +vn 0.0494 0.9984 -0.0289 +vn -0.9981 0.0362 -0.0491 +vn -0.5300 -0.0298 -0.8475 +vn 0.4936 0.0325 -0.8691 +vn 0.9989 -0.0225 0.0406 +vn 0.5101 0.0318 0.8595 +vn -0.3672 -0.0218 0.9299 +vn -0.8615 0.4813 -0.1619 +vn -0.2522 0.7762 -0.5779 +vn -0.3010 0.8244 -0.4792 +vn -0.2343 0.7568 -0.6102 +vn -0.1708 0.6813 -0.7118 +vn 0.6832 0.4687 -0.5600 +vn 0.5714 0.8202 0.0283 +vn 0.6629 0.5021 0.5553 +vn -0.2750 0.7093 0.6490 +vn -0.2482 0.7295 0.6374 +vn -0.2896 0.6978 0.6551 +vn -0.3102 0.6811 0.6633 +vn -0.0578 -0.9983 0.0113 +vn -0.0263 -0.9988 -0.0422 +vn -0.0189 -0.9997 -0.0171 +vn 0.0168 -0.9995 -0.0256 +vn 0.0252 -0.9997 0.0002 +vn 0.0198 -0.9995 0.0242 +vn -0.0042 -0.9998 -0.0170 +vn -0.0033 -0.9989 0.0471 +vn 0.0194 0.9997 0.0116 +vn 0.0498 0.9966 0.0650 +vn 0.0190 0.9998 0.0109 +vn -0.0163 0.9986 -0.0512 +vn 0.9996 -0.0130 -0.0241 +vn 0.9414 0.0159 0.3369 +vn 0.9319 0.0180 0.3623 +vn -0.2831 -0.0137 0.9590 +vn -0.4710 0.0031 0.8822 +vn -0.2924 -0.0129 0.9562 +vn -0.4820 0.0042 0.8762 +vn -0.9828 0.0147 -0.1843 +vn -0.6314 -0.0277 -0.7749 +vn 0.0797 0.0234 -0.9965 +vn 0.9987 -0.0148 -0.0478 +vn 0.6596 0.7432 0.1123 +vn 0.6766 0.7205 0.1516 +vn 0.7260 0.6212 0.2949 +vn 0.1929 0.6217 0.7592 +vn 0.0079 0.7322 0.6810 +vn -0.0021 0.7371 0.6758 +vn -0.1649 0.8006 0.5760 +vn -0.6889 0.4598 0.5604 +vn -0.4524 0.7064 -0.5444 +vn -0.4527 0.6961 -0.5572 +vn -0.4520 0.7133 -0.5356 +vn -0.4519 0.7201 -0.5266 +vn 0.6048 0.4305 -0.6700 +vn 0.5893 0.8075 -0.0246 +vn -0.0005 -0.9989 0.0464 +vn -0.0616 -0.9979 0.0186 +vn -0.0158 -0.9998 0.0096 +vn 0.0007 -0.9994 -0.0337 +vn -0.0331 -0.9991 -0.0278 +vn 0.0050 -0.9998 -0.0196 +vn 0.0409 -0.9988 0.0253 +vn 0.0304 -0.9995 0.0005 +vn 0.0319 -0.9994 -0.0133 +vn 0.0194 0.9998 -0.0080 +vn 0.0180 0.9997 -0.0174 +vn 0.0091 0.9970 -0.0765 +vn 0.0272 0.9987 0.0438 +vn -0.0039 -0.0330 -0.9994 +vn 0.5772 0.0123 -0.8165 +vn 0.8298 0.0093 0.5580 +vn 0.7775 0.0003 0.6288 +vn 0.7808 0.0007 0.6248 +vn 0.8328 0.0099 0.5535 +vn -0.7581 -0.0098 0.6520 +vn -0.7860 -0.0055 0.6182 +vn -0.7595 -0.0095 0.6504 +vn -0.7879 -0.0052 0.6158 +vn -0.8105 0.0241 -0.5852 +vn -0.3214 0.6418 -0.6963 +vn -0.1793 0.7468 -0.6404 +vn -0.1234 0.7802 -0.6133 +vn 0.0032 0.8404 -0.5420 +vn 0.5114 0.5952 -0.6199 +vn 0.8241 0.5625 0.0668 +vn 0.6969 0.6903 0.1947 +vn 0.6574 0.7185 0.2270 +vn 0.4994 0.7990 0.3351 +vn 0.2701 0.5593 0.7837 +vn -0.4716 0.7487 0.4658 +vn -0.5287 0.7105 0.4644 +vn -0.4629 0.7541 0.4659 +vn -0.4081 0.7857 0.4649 +vn -0.8560 0.5149 -0.0451 +vn -0.0129 -0.9998 -0.0124 +vn -0.0146 -0.9994 0.0325 +vn -0.0338 -0.9994 -0.0113 +vn 0.0002 -0.9990 -0.0436 +vn 0.0272 -0.9994 -0.0205 +vn 0.0175 -0.9997 0.0185 +vn 0.0330 -0.9991 0.0248 +vn -0.0271 0.9995 0.0133 +vn -0.9778 -0.0067 -0.2095 +vn -0.9749 0.0240 0.2212 +vn -0.9720 -0.0086 -0.2350 +vn -0.0121 0.0053 -0.9999 +vn 0.3187 0.0331 -0.9473 +vn 0.0110 0.0072 -0.9999 +vn 0.3342 0.0344 -0.9419 +vn 0.9994 -0.0160 0.0314 +vn 0.5418 0.0284 0.8400 +vn -0.1007 -0.0116 0.9948 +vn -0.9694 0.0256 0.2440 +vn -0.7446 0.6629 -0.0786 +vn -0.7747 0.6306 -0.0467 +vn -0.6552 0.7381 -0.1610 +vn -0.2181 0.5300 -0.8195 +vn -0.1541 0.5954 -0.7885 +vn -0.1110 0.6357 -0.7639 +vn -0.0102 0.7184 -0.6956 +vn 0.8210 0.4956 -0.2835 +vn 0.7809 0.5955 -0.1887 +vn 0.7374 0.6664 -0.1103 +vn 0.6451 0.7638 0.0215 +vn 0.4634 0.5640 0.6835 +vn -0.1636 0.7126 0.6823 +vn -0.0630 0.7658 0.6400 +vn -0.1886 0.6975 0.6914 +vn -0.2851 0.6318 0.7208 +vn -0.8280 0.5604 0.0175 +vn 0.0016 -0.9998 0.0180 +vn -0.0317 -0.9994 -0.0155 +vn 0.0115 -0.9996 -0.0273 +vn 0.0196 -0.9997 -0.0119 +vn 0.0330 -0.9992 0.0206 +vn -0.0004 -0.9996 -0.0267 +vn -0.0382 -0.9974 0.0618 +vn -0.0213 0.9993 -0.0295 +vn -0.0043 0.9991 -0.0419 +vn -0.0201 0.9993 -0.0304 +vn -0.0371 0.9992 -0.0179 +vn -0.9758 -0.0083 0.2183 +vn -0.9989 0.0119 -0.0443 +vn -0.9788 -0.0073 0.2048 +vn -0.9980 0.0132 -0.0618 +vn 0.3617 -0.0093 -0.9323 +vn 0.2110 -0.0264 -0.9771 +vn 0.3538 -0.0102 -0.9353 +vn 0.1987 -0.0278 -0.9797 +vn 0.9917 0.0281 0.1254 +vn 0.4745 -0.0205 0.8800 +vn -0.1206 0.0151 0.9926 +vn -0.7169 0.6943 0.0632 +vn -0.6288 0.7642 0.1437 +vn -0.7620 0.6474 0.0156 +vn -0.8187 0.5716 -0.0538 +vn -0.0871 0.5983 -0.7965 +vn 0.0268 0.7115 -0.7022 +vn 0.0938 0.7669 -0.6348 +vn 0.1947 0.8341 -0.5162 +vn 0.8133 0.4654 -0.3492 +vn 0.4215 0.6732 0.6075 +vn 0.3806 0.7034 0.6003 +vn 0.3552 0.7209 0.5951 +vn 0.3058 0.7523 0.5836 +vn -0.3787 0.5682 0.7306 +vn 0.0223 -0.9996 0.0154 +vn 0.0425 -0.9990 0.0150 +vn 0.0113 -0.9988 0.0469 +vn -0.0575 -0.9983 -0.0073 +vn -0.0094 -0.9993 -0.0371 +vn -0.0222 -0.9998 0.0017 +vn 0.0138 -0.9994 -0.0315 +vn 0.0237 -0.9995 -0.0214 +vn -0.0306 -0.9986 0.0438 +vn -0.0189 0.9974 -0.0698 +vn -0.0206 0.9966 -0.0797 +vn 0.0022 0.9987 0.0518 +vn -0.1177 -0.0070 0.9930 +vn -0.6486 0.0199 0.7609 +vn -0.9929 -0.0103 0.1183 +vn -0.8372 0.0167 -0.5467 +vn 0.0063 -0.0166 -0.9998 +vn 0.4506 0.0131 -0.8926 +vn 0.0298 -0.0151 -0.9994 +vn 0.4729 0.0147 -0.8810 +vn 0.9926 -0.0094 0.1208 +vn 0.8514 0.0195 0.5241 +vn 0.9896 -0.0079 0.1437 +vn 0.8382 0.0211 0.5450 +vn -0.1586 0.6547 0.7391 +vn -0.0850 0.7074 0.7017 +vn -0.1805 0.6375 0.7490 +vn -0.2313 0.5951 0.7696 +vn -0.7221 0.6868 0.0831 +vn -0.7149 0.6934 0.0897 +vn -0.7234 0.6856 0.0820 +vn -0.7291 0.6801 0.0767 +vn -0.5680 0.5521 -0.6105 +vn 0.0832 0.7280 -0.6805 +vn 0.0069 0.7708 -0.6370 +vn 0.0965 0.7198 -0.6874 +vn 0.1747 0.6668 -0.7245 +vn 0.7307 0.5919 -0.3402 +vn 0.6950 0.7064 -0.1340 +vn 0.7209 0.6900 0.0643 +vn 0.6721 0.6639 0.3280 +vn 0.6749 0.5443 0.4982 +vn -0.0441 0.9753 -0.2163 +vn -0.7014 0.0105 -0.7127 +vn -0.6879 0.0222 -0.7255 +vn -0.7114 0.0017 -0.7028 +vn -0.7252 -0.0107 -0.6884 +vn -0.0020 0.0228 -0.9997 +vn 0.4096 0.0408 -0.9113 +vn 0.1681 -0.0164 -0.9856 +vn -0.0912 -0.0184 -0.9957 +vn 0.7076 -0.0292 -0.7060 +vn 0.9230 0.0292 -0.3836 +vn 0.9987 -0.0408 -0.0297 +vn 0.9749 0.0164 0.2219 +vn 0.8850 0.0184 0.4653 +vn 0.9229 -0.0228 0.3844 +vn 0.4246 -0.0273 0.9050 +vn 0.4295 -0.0305 0.9025 +vn 0.4198 -0.0241 0.9073 +vn 0.4159 -0.0216 0.9091 +vn -0.0912 0.0411 0.9950 +vn -0.4300 0.0298 0.9023 +vn -0.2749 -0.0323 0.9609 +vn -0.6661 -0.0318 0.7452 +vn -0.9275 0.0358 0.3722 +vn -0.9817 -0.0148 0.1901 +vn -0.9997 0.0233 -0.0120 +vn -0.9966 -0.0109 -0.0816 +vn -0.9804 0.0251 -0.1954 +vn -0.6660 0.0318 -0.7452 +vn -0.9163 -0.0305 -0.3993 +vn -0.4109 -0.0387 -0.9108 +vn -0.0011 0.0292 -0.9996 +vn 0.3548 -0.0408 -0.9341 +vn 0.5781 0.0164 -0.8158 +vn 0.7685 0.0184 -0.6396 +vn 0.7083 -0.0228 -0.7055 +vn 0.9986 -0.0273 -0.0459 +vn 0.9982 -0.0305 -0.0514 +vn 0.9989 -0.0241 -0.0406 +vn 0.9991 -0.0216 -0.0364 +vn 0.8844 0.0411 0.4650 +vn 0.6658 0.0311 0.7455 +vn 0.7826 -0.0322 0.6217 +vn 0.4339 -0.0310 0.9004 +vn 0.2749 0.0323 0.9609 +vn 0.0912 -0.0411 0.9950 +vn -0.3616 -0.0134 0.9322 +vn -0.3345 -0.0305 0.9419 +vn -0.4035 0.0134 0.9149 +vn -0.4295 0.0305 0.9025 +vn -0.7618 0.0398 0.6466 +vn -0.9249 0.0221 0.3794 +vn -0.8550 -0.0174 0.5184 +vn -0.9804 -0.0251 0.1954 +vn 0.4564 -0.7363 -0.4996 +vn 0.5715 -0.4462 -0.6887 +vn 0.6765 -0.4441 -0.5875 +vn -0.2068 -0.1699 0.9635 +vn -0.1095 -0.4602 0.8810 +vn -0.1035 -0.1620 0.9813 +vn 0.0909 -0.8035 0.5883 +vn 0.0044 -0.7611 0.6486 +vn 0.0123 -0.9070 0.4210 +vn 0.5974 -0.7322 0.3271 +vn 0.5298 -0.7456 0.4043 +vn 0.3744 -0.8975 0.2330 +vn -0.2366 -0.9146 0.3281 +vn -0.2852 -0.7494 0.5976 +vn -0.3857 -0.7441 0.5455 +vn 0.8249 0.4226 0.3755 +vn 0.6151 -0.7453 0.2574 +vn 0.4199 0.5300 0.7367 +vn 0.0030 -0.1933 0.9811 +vn 0.3012 0.6088 0.7340 +vn -0.0212 -0.9331 -0.3589 +vn -0.0337 -0.9415 -0.3354 +vn -0.0779 -0.9337 -0.3495 +vn 0.9169 -0.1625 -0.3645 +vn 0.9507 -0.1625 -0.2642 +vn 0.8465 -0.4328 -0.3101 +vn -0.4812 -0.8017 -0.3545 +vn -0.7453 0.3490 -0.5681 +vn -0.6904 0.3383 -0.6394 +vn 0.1031 -0.9850 -0.1381 +vn 0.0320 -0.9903 -0.1354 +vn 0.0395 -0.9658 -0.2562 +vn 0.0258 -0.9342 0.3559 +vn 0.0231 -0.9468 0.3210 +vn 0.1004 -0.9542 0.2817 +vn -0.5796 -0.7901 -0.1993 +vn -0.5380 -0.8050 -0.2500 +vn -0.3826 -0.9087 -0.1670 +vn 0.2449 -0.9111 0.3314 +vn 0.2616 -0.7336 0.6272 +vn 0.1921 -0.9181 0.3467 +vn 0.1137 -0.9470 -0.3005 +vn 0.1514 -0.9487 -0.2776 +vn 0.0994 -0.9619 -0.2547 +vn -0.0503 -0.9778 -0.2034 +vn -0.2129 -0.9116 -0.3516 +vn -0.1321 -0.9158 -0.3792 +vn -0.1554 -0.9565 -0.2469 +vn 0.6729 -0.7323 -0.1044 +vn 0.6539 -0.7401 -0.1573 +vn 0.8815 -0.4360 -0.1814 +vn 0.3883 -0.7411 -0.5477 +vn 0.4712 -0.4488 -0.7593 +vn 0.3933 -0.9023 0.1766 +vn 0.2619 -0.9462 0.1900 +vn 0.3189 -0.9384 0.1329 +vn -0.8875 0.1370 -0.4400 +vn -0.9193 -0.1612 0.3590 +vn -0.9235 -0.0742 0.3764 +vn 0.0945 -0.4640 0.8808 +vn 0.1877 -0.4758 0.8593 +vn 0.1967 -0.7563 0.6239 +vn 0.1055 -0.9452 0.3091 +vn 0.1367 -0.9552 0.2624 +vn 0.1300 -0.9031 0.4092 +vn 0.6576 0.1079 0.7456 +vn 0.0466 0.8224 0.5670 +vn 0.2846 -0.7488 -0.5985 +vn 0.2310 -0.9055 -0.3559 +vn 0.1714 -0.8824 -0.4382 +vn 0.4487 0.4427 0.7763 +vn 0.3454 0.4521 0.8224 +vn 0.3209 -0.7313 0.6019 +vn -0.0195 -0.9122 -0.4092 +vn -0.0979 -0.9428 -0.3187 +vn 0.1643 -0.9821 -0.0917 +vn -0.0816 -0.9445 0.3183 +vn -0.3524 -0.9034 -0.2443 +vn 0.3175 -0.9006 0.2969 +vn 0.2229 -0.4797 -0.8486 +vn 0.3433 -0.4512 -0.8238 +vn 0.0274 -0.9799 0.1975 +vn -0.0381 -0.9789 0.2005 +vn -0.0494 -0.9972 0.0560 +vn 0.0329 -0.9965 0.0771 +vn 0.9690 -0.1629 -0.1856 +vn 0.6431 0.7560 -0.1220 +vn 0.7307 0.1788 0.6589 +vn 0.3168 -0.1692 -0.9333 +vn -0.4712 -0.4488 0.7593 +vn 0.6192 -0.7643 0.1801 +vn 0.8788 0.4168 0.2324 +vn 0.2171 -0.9576 -0.1897 +vn 0.2001 -0.9433 -0.2650 +vn 0.2976 -0.9332 -0.2016 +vn 0.9057 -0.4213 -0.0476 +vn 0.9806 -0.1607 -0.1120 +vn 0.7869 0.3256 0.5241 +vn -0.6424 -0.0723 0.7629 +vn -0.6795 -0.1816 0.7108 +vn -0.5941 -0.1718 0.7858 +vn 0.1896 -0.9436 0.2714 +vn 0.2261 -0.9525 0.2040 +vn 0.6240 -0.7378 -0.2575 +vn 0.5909 -0.7336 -0.3356 +vn 0.8223 -0.4378 -0.3635 +vn -0.2824 -0.9416 -0.1832 +vn -0.3009 -0.9037 -0.3046 +vn -0.2587 -0.9403 -0.2211 +vn -0.1191 0.9676 -0.2228 +vn -0.0359 -0.1739 -0.9841 +vn -0.8750 0.1571 -0.4579 +vn -0.1490 -0.9489 -0.2781 +vn -0.9904 0.0867 -0.1076 +vn -0.8451 0.1823 -0.5026 +vn 0.7497 -0.1716 -0.6392 +vn 0.7932 -0.1580 -0.5881 +vn 0.5442 0.4284 0.7213 +vn 0.3776 -0.7371 0.5604 +vn -0.2109 -0.9561 -0.2032 +vn -0.8534 -0.4499 0.2634 +vn -0.8481 -0.4309 0.3085 +vn 0.3040 -0.9491 -0.0820 +vn 0.3615 -0.9270 -0.1001 +vn 0.4456 -0.8934 -0.0574 +vn -0.9229 0.3752 -0.0860 +vn -0.9158 0.3542 -0.1896 +vn -0.5840 -0.8006 -0.1344 +vn 0.6914 -0.7212 -0.0423 +vn 0.8947 -0.4327 -0.1104 +vn -0.3433 -0.4512 0.8238 +vn -0.3168 -0.1692 0.9333 +vn -0.4247 -0.1724 0.8887 +vn 0.0415 0.6357 0.7708 +vn 0.0839 -0.1404 0.9865 +vn 0.1626 -0.9638 0.2113 +vn 0.1599 -0.9428 0.2925 +vn -0.3001 -0.9283 -0.2195 +vn -0.3375 -0.9335 -0.1211 +vn 0.0131 0.8043 -0.5941 +vn 0.0252 -0.2006 -0.9794 +vn -0.1717 -0.8792 0.4444 +vn 0.7749 0.2332 0.5875 +vn -0.1528 -0.9748 0.1627 +vn -0.2278 -0.9543 0.1933 +vn -0.2284 -0.9729 0.0355 +vn 0.0988 -0.9936 -0.0550 +vn 0.1641 -0.9848 0.0560 +vn 0.0988 -0.9935 0.0560 +vn 0.5828 0.7482 -0.3171 +vn 0.6153 0.7562 -0.2228 +vn 0.9319 -0.0652 -0.3568 +vn -0.4460 -0.8940 0.0436 +vn -0.4253 -0.8968 0.1218 +vn -0.6436 -0.7472 0.1661 +vn 0.5009 -0.1570 -0.8512 +vn 0.5941 -0.1718 -0.7858 +vn -0.1509 -0.9666 -0.2072 +vn -0.0512 -0.9962 -0.0698 +vn 0.8809 0.4060 0.2433 +vn 0.8870 0.4174 0.1976 +vn 0.7098 -0.6993 0.0844 +vn 0.1113 -0.4611 -0.8803 +vn 0.1018 -0.7589 -0.6432 +vn -0.0174 -0.7623 -0.6470 +vn -0.1682 -0.9398 -0.2975 +vn -0.4931 0.3644 -0.7899 +vn -0.3815 -0.7957 -0.4704 +vn -0.5883 0.3612 -0.7235 +vn 0.1285 -0.1671 0.9775 +vn 0.0986 -0.2051 0.9738 +vn 0.5187 -0.7416 -0.4255 +vn 0.3684 -0.9039 -0.2175 +vn -0.5715 -0.4462 0.6887 +vn -0.4564 -0.7363 0.4996 +vn 0.7422 -0.4436 -0.5022 +vn -0.2705 -0.9095 -0.3156 +vn -0.5439 0.5863 -0.6004 +vn -0.6847 0.4851 -0.5439 +vn 0.8704 -0.4896 0.0513 +vn 0.7017 -0.7121 0.0236 +vn -0.2034 -0.9291 0.3089 +vn -0.1580 -0.9397 0.3032 +vn 0.4983 0.7485 -0.4376 +vn 0.8225 -0.0723 -0.5641 +vn -0.0898 -0.9087 0.4077 +vn 0.4374 -0.8950 -0.0877 +vn -0.1224 -0.9404 -0.3174 +vn 0.4854 -0.8714 0.0704 +vn -0.1520 -0.7685 -0.6215 +vn -0.1760 -0.4742 -0.8627 +vn -0.0937 -0.5125 -0.8536 +vn 0.3149 -0.9027 -0.2933 +vn 0.2752 -0.9041 -0.3270 +vn 0.4580 -0.8889 -0.0001 +vn -0.4150 -0.9032 -0.1094 +vn -0.4502 -0.8924 -0.0298 +vn -0.0217 -0.4655 -0.8848 +vn -0.8219 0.3066 -0.4800 +vn -0.3398 -0.7918 -0.5075 +vn -0.2709 -0.7924 -0.5465 +vn -0.8223 -0.4378 0.3635 +vn -0.8716 -0.1589 0.4638 +vn -0.1805 -0.9405 0.2879 +vn -0.3797 -0.9000 0.2143 +vn -0.3012 -0.9497 0.0854 +vn 0.8716 -0.1589 -0.4638 +vn 0.3794 -0.9232 0.0610 +vn -0.2968 -0.9549 -0.0052 +vn 0.4010 -0.9044 -0.1461 +vn -0.7919 -0.4372 0.4264 +vn -0.7422 -0.4436 0.5022 +vn -0.8157 -0.1376 0.5618 +vn -0.4232 -0.7951 -0.4344 +vn -0.1583 -0.9845 -0.0759 +vn -0.1479 -0.9874 0.0560 +vn -0.6319 -0.7734 0.0499 +vn -0.6330 -0.7731 -0.0403 +vn -0.2690 0.7616 0.5896 +vn -0.4082 0.3747 -0.8324 +vn -0.3035 0.3977 -0.8658 +vn -0.6550 0.7523 -0.0704 +vn -0.7289 0.6278 -0.2731 +vn 0.7564 0.1173 0.6435 +vn 0.1784 0.6492 0.7394 +vn -0.1567 -0.9474 0.2790 +vn 0.0559 0.7148 0.6971 +vn -0.2229 -0.4797 0.8486 +vn 0.2068 -0.1699 -0.9635 +vn 0.8569 -0.4504 -0.2505 +vn 0.4247 -0.1724 -0.8887 +vn 0.0749 0.6552 0.7517 +vn -0.8616 0.3558 -0.3621 +vn 0.2700 0.7612 -0.5897 +vn 0.6424 -0.0723 -0.7629 +vn -0.3101 -0.9068 -0.2856 +vn -0.5417 0.4945 -0.6797 +vn 0.6073 0.2307 0.7602 +vn 0.8282 -0.5593 0.0345 +vn 0.2461 -0.5034 0.8283 +vn 0.0458 -0.9369 -0.3465 +vn -0.6189 -0.7446 0.2502 +vn 0.2225 -0.9409 -0.2553 +vn 0.2602 -0.9416 -0.2135 +vn -0.1268 0.7859 0.6052 +vn 0.1056 -0.1602 -0.9814 +vn -0.0921 -0.9760 0.1975 +vn -0.6765 -0.4441 0.5875 +vn -0.7931 -0.1580 0.5882 +vn 0.2286 -0.9709 -0.0712 +vn -0.6515 0.7490 -0.1206 +vn -0.9208 0.3808 -0.0851 +vn -0.7889 0.5983 -0.1400 +vn 0.6795 -0.1816 -0.7108 +vn -0.2769 -0.9569 -0.0878 +vn 0.0047 -0.4594 0.8882 +vn -0.8922 0.2045 -0.4027 +vn -0.2663 0.9409 -0.2092 +vn 0.1339 0.5730 0.8085 +vn -0.1018 -0.7589 0.6432 +vn 0.6399 0.4207 0.6431 +vn 0.4572 -0.7382 0.4960 +vn -0.9002 0.2168 -0.3777 +vn -0.9011 0.2590 -0.3479 +vn -0.3381 -0.9027 0.2662 +vn -0.3860 0.7878 0.4800 +vn 0.7675 0.4172 0.4868 +vn 0.6948 0.4177 0.5856 +vn 0.6618 0.6186 0.4236 +vn 0.6456 0.7635 -0.0188 +vn 0.6363 0.7436 0.2051 +vn 0.2161 0.9441 0.2489 +vn 0.7039 0.1734 0.6888 +vn -0.3014 0.8456 -0.4406 +vn -0.0553 0.6371 -0.7688 +vn 0.2460 -0.9499 -0.1928 +vn 0.2096 -0.9472 -0.2426 +vn -0.1331 -0.9461 0.2951 +vn -0.5909 -0.7336 0.3356 +vn -0.8076 0.3142 -0.4991 +vn 0.2288 -0.9719 0.0560 +vn -0.1296 -0.9531 0.2736 +vn 0.0853 -0.9182 -0.3868 +vn -0.5996 0.7628 0.2422 +vn -0.6072 0.7832 0.1339 +vn 0.8158 -0.1377 -0.5617 +vn -0.5247 -0.7340 0.4312 +vn 0.8912 0.3971 0.2193 +vn 0.7227 0.5967 0.3488 +vn 0.6241 0.7548 0.2019 +vn 0.3719 0.7452 -0.5535 +vn 0.2688 -0.9400 -0.2099 +vn -0.2962 -0.9120 0.2836 +vn -0.5009 -0.1570 0.8512 +vn -0.4990 0.7472 0.4389 +vn -0.3718 0.7447 0.5543 +vn -0.9179 0.3966 -0.0122 +vn -0.8225 -0.0723 0.5641 +vn -0.5844 0.7464 0.3184 +vn -0.8641 0.2147 -0.4552 +vn 0.1392 0.5670 0.8119 +vn 0.1219 -0.9571 0.2629 +vn 0.2426 0.4049 0.8816 +vn 0.0666 0.6589 0.7493 +vn 0.7919 -0.4372 -0.4264 +vn 0.5204 0.3991 0.7549 +vn -0.7497 -0.1716 0.6392 +vn -0.2593 0.4178 -0.8708 +vn -0.2380 -0.7596 -0.6052 +vn 0.0330 -0.9979 -0.0550 +vn -0.9436 0.3301 0.0264 +vn 0.1739 0.8483 0.5001 +vn -0.1314 0.6235 0.7707 +vn -0.8922 0.1972 -0.4063 +vn 0.1949 -0.9541 -0.2274 +vn 0.1284 0.7840 -0.6074 +vn 0.3015 -0.9507 0.0724 +vn 0.0937 -0.9814 0.1674 +vn -0.6543 -0.3948 0.6450 +vn -0.3583 -0.9335 -0.0131 +vn 0.8082 0.3564 0.4688 +vn -0.4350 0.5965 -0.6745 +vn 0.2288 0.5333 0.8144 +vn -0.9239 0.3812 0.0317 +vn -0.1835 0.5537 -0.8123 +vn -0.2882 0.5892 -0.7548 +vn 0.8283 0.4326 0.3560 +vn 0.4287 0.8593 0.2790 +vn 0.8296 0.4244 0.3629 +vn -0.9377 0.3260 -0.1200 +vn -0.9407 0.2553 -0.2234 +vn -0.6140 0.7108 -0.3431 +vn -0.3398 0.6773 -0.6526 +vn 0.8348 -0.3574 -0.4187 +vn -0.0942 -0.0575 -0.9939 +vn 0.6456 0.6484 0.4036 +vn -0.7932 0.4312 -0.4300 +vn -0.1218 0.4788 -0.8695 +vn -0.1428 0.6675 -0.7308 +vn 0.9987 -0.0214 -0.0454 +vn 0.6723 0.7003 0.2399 +vn -0.4564 0.7363 0.4996 +vn -0.6765 0.4441 0.5875 +vn -0.5715 0.4462 0.6887 +vn 0.2068 0.1699 -0.9635 +vn 0.1035 0.1620 -0.9813 +vn 0.1095 0.4602 -0.8810 +vn -0.0909 0.8035 -0.5883 +vn -0.0123 0.9070 -0.4210 +vn -0.0044 0.7611 -0.6486 +vn -0.5974 0.7322 -0.3271 +vn -0.3744 0.8975 -0.2330 +vn -0.5298 0.7456 -0.4043 +vn 0.2366 0.9146 -0.3281 +vn 0.3857 0.7441 -0.5455 +vn 0.2852 0.7494 -0.5976 +vn -0.3866 0.9062 -0.1713 +vn -0.6151 0.7453 -0.2574 +vn 0.3607 0.5881 -0.7239 +vn 0.2449 0.6472 -0.7219 +vn -0.0030 0.1933 -0.9811 +vn 0.0212 0.9331 0.3589 +vn 0.0779 0.9337 0.3495 +vn 0.0337 0.9415 0.3354 +vn -0.9169 0.1625 0.3645 +vn -0.8465 0.4328 0.3101 +vn -0.9507 0.1625 0.2642 +vn 0.4812 0.8017 0.3545 +vn 0.2450 0.9409 0.2337 +vn 0.2765 0.9371 0.2130 +vn -0.1031 0.9850 0.1381 +vn -0.0395 0.9658 0.2562 +vn -0.0320 0.9903 0.1354 +vn -0.0258 0.9342 -0.3559 +vn -0.1004 0.9542 -0.2817 +vn -0.0231 0.9468 -0.3210 +vn 0.5796 0.7901 0.1993 +vn 0.3826 0.9087 0.1670 +vn 0.5380 0.8050 0.2500 +vn -0.2449 0.9111 -0.3314 +vn -0.1921 0.9181 -0.3467 +vn -0.2616 0.7336 -0.6272 +vn -0.1137 0.9470 0.3005 +vn -0.0994 0.9619 0.2547 +vn -0.1514 0.9487 0.2776 +vn 0.0503 0.9778 0.2034 +vn 0.2129 0.9116 0.3516 +vn 0.1554 0.9565 0.2469 +vn 0.1321 0.9158 0.3792 +vn -0.6729 0.7323 0.1044 +vn -0.8815 0.4360 0.1814 +vn -0.6539 0.7401 0.1573 +vn -0.3883 0.7411 0.5477 +vn -0.4712 0.4488 0.7593 +vn -0.3933 0.9023 -0.1766 +vn -0.3189 0.9384 -0.1329 +vn -0.2619 0.9462 -0.1900 +vn 0.5343 0.3404 -0.7738 +vn 0.9235 0.0742 -0.3764 +vn 0.9193 0.1612 -0.3590 +vn -0.0945 0.4640 -0.8808 +vn -0.1877 0.4758 -0.8593 +vn -0.1967 0.7563 -0.6239 +vn -0.1055 0.9452 -0.3091 +vn -0.1300 0.9031 -0.4092 +vn -0.1367 0.9552 -0.2624 +vn 0.6784 0.2329 -0.6968 +vn 0.1007 0.5930 -0.7988 +vn -0.2846 0.7488 0.5985 +vn -0.1714 0.8824 0.4382 +vn -0.2310 0.9055 0.3559 +vn -0.2118 0.8962 -0.3899 +vn -0.3209 0.7313 -0.6019 +vn -0.1607 0.8905 -0.4256 +vn 0.0979 0.9428 0.3187 +vn 0.0195 0.9122 0.4092 +vn -0.1643 0.9821 0.0917 +vn 0.0816 0.9445 -0.3183 +vn 0.3524 0.9034 0.2443 +vn -0.3175 0.9006 -0.2969 +vn -0.2229 0.4797 0.8486 +vn -0.3433 0.4512 0.8238 +vn -0.0274 0.9799 -0.1975 +vn 0.0381 0.9789 -0.2005 +vn -0.0329 0.9965 -0.0771 +vn 0.0494 0.9972 -0.0560 +vn -0.9690 0.1629 0.1856 +vn -0.6348 0.2319 0.7370 +vn -0.7474 0.6479 0.1470 +vn -0.3168 0.1692 0.9333 +vn 0.4712 0.4488 -0.7593 +vn -0.4028 0.9097 -0.1015 +vn -0.6192 0.7643 -0.1801 +vn -0.2171 0.9576 0.1897 +vn -0.2976 0.9332 0.2016 +vn -0.2001 0.9433 0.2650 +vn -0.9057 0.4213 0.0476 +vn -0.6539 0.5547 0.5145 +vn -0.9806 0.1607 0.1120 +vn 0.6424 0.0723 -0.7629 +vn 0.5941 0.1718 -0.7858 +vn 0.6795 0.1816 -0.7108 +vn -0.1896 0.9436 -0.2714 +vn -0.2261 0.9525 -0.2040 +vn -0.6240 0.7378 0.2575 +vn -0.8223 0.4378 0.3635 +vn -0.5909 0.7336 0.3356 +vn 0.2824 0.9416 0.1832 +vn 0.2587 0.9403 0.2211 +vn 0.3009 0.9037 0.3045 +vn 0.2093 -0.9605 0.1835 +vn -0.3926 0.1828 0.9014 +vn 0.0359 0.1739 0.9841 +vn 0.1490 0.9489 0.2780 +vn 0.6818 0.2206 -0.6975 +vn 0.5040 0.2375 -0.8304 +vn -0.7931 0.1580 0.5882 +vn -0.7497 0.1716 0.6392 +vn -0.2515 0.9031 -0.3480 +vn -0.3776 0.7371 -0.5604 +vn 0.2109 0.9561 0.2032 +vn 0.8534 0.4499 -0.2634 +vn 0.8481 0.4309 -0.3085 +vn -0.3040 0.9491 0.0820 +vn -0.4456 0.8934 0.0574 +vn -0.3614 0.9270 0.1000 +vn 0.3719 0.9277 0.0326 +vn 0.5840 0.8006 0.1344 +vn 0.3457 0.9360 0.0667 +vn -0.8947 0.4327 0.1104 +vn -0.6914 0.7212 0.0423 +vn 0.3433 0.4512 -0.8238 +vn 0.4247 0.1724 -0.8887 +vn 0.3168 0.1692 -0.9333 +vn -0.0325 0.7712 -0.6358 +vn -0.0839 0.1404 -0.9865 +vn -0.1599 0.9428 -0.2925 +vn -0.1626 0.9638 -0.2113 +vn 0.3001 0.9283 0.2194 +vn 0.3375 0.9335 0.1211 +vn -0.0253 0.5797 0.8144 +vn -0.0252 0.2006 0.9794 +vn 0.1717 0.8792 -0.4444 +vn -0.7037 0.3696 0.6068 +vn 0.1528 0.9748 -0.1627 +vn 0.2284 0.9729 -0.0355 +vn 0.2278 0.9543 -0.1933 +vn -0.0988 0.9936 0.0550 +vn -0.0988 0.9935 -0.0560 +vn -0.1641 0.9848 -0.0560 +vn -0.6635 0.6533 0.3647 +vn -0.9319 0.0652 0.3568 +vn -0.7181 0.6463 0.2582 +vn 0.4460 0.8940 -0.0436 +vn 0.6436 0.7472 -0.1661 +vn 0.4253 0.8968 -0.1218 +vn -0.5941 0.1718 0.7859 +vn -0.5009 0.1570 0.8512 +vn 0.1509 0.9666 0.2072 +vn 0.0512 0.9962 0.0698 +vn -0.5031 0.8587 0.0981 +vn -0.7098 0.6993 -0.0844 +vn -0.4492 0.8926 -0.0378 +vn -0.1113 0.4611 0.8803 +vn 0.0174 0.7623 0.6470 +vn -0.1018 0.7589 0.6432 +vn 0.1682 0.9398 0.2975 +vn 0.1831 0.9312 0.3151 +vn 0.2212 0.9324 0.2856 +vn 0.3815 0.7957 0.4704 +vn -0.1285 0.1672 -0.9775 +vn -0.0986 0.2051 -0.9738 +vn -0.5187 0.7416 0.4255 +vn -0.3684 0.9039 0.2175 +vn 0.4564 0.7363 -0.4996 +vn 0.5715 0.4462 -0.6887 +vn -0.7422 0.4436 0.5022 +vn 0.2705 0.9095 0.3156 +vn -0.3018 0.3932 0.8685 +vn -0.2465 0.5002 0.8301 +vn -0.7017 0.7121 -0.0236 +vn -0.8704 0.4896 -0.0513 +vn 0.2034 0.9291 -0.3089 +vn 0.1580 0.9397 -0.3032 +vn -0.5733 0.6495 0.4995 +vn -0.8225 0.0723 0.5641 +vn 0.0898 0.9087 -0.4077 +vn -0.4374 0.8950 0.0877 +vn 0.1224 0.9404 0.3174 +vn -0.4854 0.8714 -0.0704 +vn 0.1520 0.7685 0.6215 +vn 0.0937 0.5125 0.8536 +vn 0.1760 0.4742 0.8627 +vn -0.2752 0.9041 0.3270 +vn -0.3149 0.9027 0.2933 +vn -0.4580 0.8889 0.0001 +vn 0.4150 0.9032 0.1094 +vn 0.4502 0.8924 0.0298 +vn 0.0217 0.4655 0.8848 +vn 0.2662 0.9517 0.1532 +vn 0.3398 0.7918 0.5075 +vn 0.2709 0.7924 0.5465 +vn 0.8716 0.1589 -0.4638 +vn 0.8223 0.4378 -0.3635 +vn 0.1805 0.9405 -0.2879 +vn 0.3797 0.9000 -0.2143 +vn 0.3012 0.9497 -0.0854 +vn -0.8716 0.1589 0.4638 +vn -0.3794 0.9232 -0.0610 +vn 0.2968 0.9549 0.0052 +vn -0.4010 0.9044 0.1461 +vn 0.7919 0.4372 -0.4264 +vn 0.8157 0.1377 -0.5618 +vn 0.7422 0.4436 -0.5022 +vn 0.4232 0.7951 0.4344 +vn 0.1583 0.9845 0.0759 +vn 0.1479 0.9874 -0.0560 +vn 0.6319 0.7734 -0.0499 +vn 0.6330 0.7731 0.0403 +vn 0.3188 0.6265 -0.7113 +vn 0.1522 0.9271 0.3425 +vn 0.1150 0.9168 0.3823 +vn 0.6371 0.6387 -0.4315 +vn 0.5855 0.5484 -0.5971 +vn -0.6833 0.2293 0.6932 +vn 0.1310 0.6872 -0.7146 +vn 0.1567 0.9474 -0.2790 +vn -0.0570 0.6994 -0.7125 +vn 0.2229 0.4797 -0.8486 +vn -0.2068 0.1699 0.9635 +vn -0.8569 0.4504 0.2505 +vn -0.4247 0.1724 0.8887 +vn 0.0244 0.7221 -0.6914 +vn 0.3289 0.9349 0.1332 +vn -0.6424 0.0723 0.7629 +vn -0.3189 0.6284 0.7095 +vn 0.3101 0.9068 0.2856 +vn 0.5417 -0.4945 0.6797 +vn 0.5923 0.3682 -0.7167 +vn -0.8283 0.5593 -0.0345 +vn -0.2461 0.5034 -0.8283 +vn -0.0458 0.9369 0.3465 +vn 0.6189 0.7446 -0.2502 +vn -0.2225 0.9409 0.2553 +vn -0.2602 0.9416 0.2136 +vn 0.1647 0.5879 -0.7920 +vn -0.1056 0.1602 0.9814 +vn 0.0921 0.9760 -0.1975 +vn 0.7931 0.1580 -0.5882 +vn 0.6765 0.4441 -0.5875 +vn -0.2286 0.9709 0.0712 +vn 0.6514 -0.7490 0.1206 +vn -0.1507 0.2210 0.9636 +vn 0.9085 -0.4097 0.0827 +vn -0.6795 0.1816 0.7108 +vn 0.2769 0.9569 0.0878 +vn -0.0047 0.4594 -0.8882 +vn -0.4144 0.1796 0.8922 +vn 0.2663 -0.9409 0.2092 +vn -0.0849 0.8224 -0.5626 +vn 0.1018 0.7589 -0.6432 +vn -0.2929 0.9070 -0.3027 +vn -0.4572 0.7382 -0.4960 +vn 0.4793 0.7162 -0.5072 +vn 0.4025 0.7967 -0.4507 +vn 0.3381 0.9027 -0.2662 +vn 0.7075 -0.0385 0.7057 +vn -0.3533 0.9085 -0.2231 +vn -0.3182 0.9084 -0.2713 +vn -0.6868 0.5551 0.4692 +vn -0.7036 0.6505 0.2859 +vn -0.7232 0.6749 0.1467 +vn -0.2287 -0.9407 -0.2507 +vn 0.7027 0.2185 -0.6771 +vn 0.3016 -0.8452 0.4412 +vn 0.2131 -0.7672 -0.6050 +vn -0.2460 0.9499 0.1928 +vn -0.2096 0.9472 0.2426 +vn 0.1331 0.9461 -0.2951 +vn 0.5909 0.7336 -0.3356 +vn -0.3469 0.2760 0.8964 +vn -0.2288 0.9719 -0.0560 +vn 0.1296 0.9531 -0.2736 +vn -0.0853 0.9182 0.3868 +vn 0.6986 0.6527 -0.2932 +vn 0.7112 0.6423 -0.2858 +vn -0.8157 0.1377 0.5618 +vn 0.5247 0.7340 -0.4312 +vn -0.8894 -0.4022 -0.2170 +vn -0.6240 -0.7549 -0.2019 +vn 0.4144 0.2544 -0.8738 +vn -0.4361 0.6509 0.6214 +vn -0.2688 0.9400 0.2099 +vn 0.2962 0.9120 -0.2836 +vn 0.5009 0.1570 -0.8512 +vn 0.5722 0.6508 -0.4991 +vn 0.4356 0.6509 -0.6217 +vn 0.3966 0.9180 0.0043 +vn 0.8225 0.0723 -0.5641 +vn 0.6617 0.6554 -0.3641 +vn 0.5014 0.4455 -0.7417 +vn -0.0799 0.8239 -0.5610 +vn -0.1219 0.9571 -0.2629 +vn -0.2422 -0.4066 -0.8809 +vn -0.0585 0.7521 -0.6565 +vn -0.7919 0.4372 0.4264 +vn 0.4869 0.5040 -0.7133 +vn 0.7497 0.1716 -0.6392 +vn 0.1014 0.9093 0.4036 +vn 0.2380 0.7596 0.6052 +vn -0.0330 0.9979 0.0550 +vn 0.3766 0.9212 -0.0976 +vn -0.1740 -0.8484 -0.4999 +vn 0.6005 -0.6465 0.4705 +vn 0.5060 0.5440 -0.6693 +vn -0.1949 0.9541 0.2274 +vn -0.1648 0.5931 0.7881 +vn -0.3015 0.9507 -0.0724 +vn -0.0937 0.9814 -0.1674 +vn -0.9522 0.0507 -0.3013 +vn 0.3583 0.9335 0.0131 +vn -0.6161 0.6928 0.3747 +vn -0.1874 0.6238 0.7588 +vn -0.1256 0.8458 -0.5185 +vn 0.3806 0.9246 -0.0147 +vn -0.0970 0.7004 0.7071 +vn 0.0242 0.7864 0.6173 +vn -0.5072 0.8483 0.1521 +vn 0.1760 0.3651 -0.9142 +vn -0.5872 0.7748 0.2342 +vn 0.4100 0.8845 -0.2228 +vn 0.4029 0.8288 -0.3883 +vn 0.4626 0.8150 -0.3489 +vn -0.3166 0.8445 0.4319 +vn 0.8175 0.0714 0.5715 +vn 0.0430 0.8882 -0.4575 +vn 0.5352 0.4152 -0.7357 +vn 0.0761 0.6462 -0.7593 +vn -0.0524 0.4762 -0.8778 +vn -0.5878 -0.2584 0.7666 +vn -0.3850 0.8172 0.4290 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 5/5/5 6/6/5 7/7/5 +f 8/8/5 9/9/5 10/10/5 +f 11/11/6 12/12/7 13/13/8 +f 13/13/8 12/12/7 14/14/9 +f 15/15/10 16/16/11 17/17/12 +f 17/17/12 16/16/11 18/18/13 +f 19/19/5 20/20/5 21/21/5 +f 12/12/5 11/11/5 22/22/5 +f 23/23/5 24/24/5 25/25/5 +f 11/11/5 26/26/5 22/22/5 +f 27/27/5 28/28/5 29/29/5 +f 1/1/14 3/3/5 30/30/5 +f 25/25/5 24/24/5 31/31/5 +f 32/32/5 28/28/5 33/33/5 +f 34/34/5 35/35/5 36/36/5 +f 30/30/5 37/37/5 38/38/5 +f 16/16/5 31/31/5 24/24/5 +f 18/18/5 36/36/5 39/39/5 +f 21/21/5 34/34/5 36/36/5 +f 1/1/14 40/40/15 41/41/16 +f 36/36/5 35/35/5 26/26/5 +f 33/33/5 16/16/5 24/24/5 +f 42/42/5 43/43/5 44/44/5 +f 42/42/5 44/44/5 45/45/5 +f 44/44/5 46/46/5 45/45/5 +f 45/45/5 46/46/5 14/14/5 +f 18/18/5 16/16/5 36/36/5 +f 47/47/5 17/17/5 46/46/5 +f 14/14/5 17/17/5 13/13/5 +f 46/46/5 17/17/5 14/14/5 +f 15/15/5 17/17/5 47/47/5 +f 6/6/5 9/9/5 7/7/5 +f 4/4/5 2/2/5 48/48/5 +f 49/49/5 50/50/5 51/51/5 +f 4/4/5 48/48/5 51/51/5 +f 51/51/5 10/10/5 4/4/5 +f 4/4/5 10/10/5 52/52/5 +f 51/51/5 50/50/5 10/10/5 +f 8/8/5 10/10/5 50/50/5 +f 53/53/17 54/54/17 55/55/17 +f 55/55/18 54/54/18 56/56/18 +f 55/55/19 56/56/19 57/57/19 +f 57/57/20 56/56/21 58/58/22 +f 57/57/23 58/58/23 59/59/23 +f 59/59/24 58/58/24 60/60/24 +f 60/60/25 61/61/25 62/62/25 +f 62/62/26 61/61/27 63/63/28 +f 62/62/26 63/63/28 64/64/29 +f 64/64/29 63/63/28 65/65/30 +f 64/64/29 65/65/30 66/66/31 +f 66/66/31 65/65/30 67/67/32 +f 67/67/33 65/65/33 68/68/33 +f 67/67/34 68/68/34 69/69/34 +f 69/69/35 68/68/35 70/70/35 +f 69/69/36 70/70/36 71/71/36 +f 71/71/37 70/70/37 72/72/37 +f 71/71/38 72/72/38 73/73/38 +f 73/73/39 72/72/39 74/74/39 +f 74/74/40 75/75/40 76/76/40 +f 77/77/41 78/78/41 79/79/41 +f 79/79/42 78/78/42 80/80/42 +f 79/79/43 80/80/43 81/81/43 +f 81/81/44 80/80/44 82/82/44 +f 81/81/45 82/82/45 83/83/45 +f 83/83/46 82/82/46 84/84/46 +f 83/83/47 84/84/47 85/85/47 +f 85/85/48 84/84/48 86/86/48 +f 85/85/49 86/86/49 87/87/49 +f 87/87/50 86/86/50 88/88/50 +f 87/87/51 88/88/52 89/89/53 +f 87/87/51 89/89/53 90/90/54 +f 90/90/55 89/89/55 91/91/55 +f 90/90/56 91/91/56 92/92/56 +f 92/92/57 93/93/57 94/94/57 +f 94/94/58 93/93/59 95/95/60 +f 94/94/58 95/95/60 96/96/61 +f 96/96/62 95/95/63 97/97/64 +f 97/97/64 95/95/63 98/98/65 +f 99/99/66 100/100/66 101/101/66 +f 101/101/18 100/100/18 102/102/18 +f 101/101/67 102/102/67 103/103/67 +f 103/103/20 102/102/20 104/104/20 +f 103/103/23 104/104/23 105/105/23 +f 105/105/68 104/104/68 106/106/68 +f 106/106/69 107/107/69 108/108/69 +f 108/108/70 107/107/70 109/109/70 +f 108/108/71 109/109/71 110/110/71 +f 110/110/72 109/109/72 111/111/72 +f 111/111/73 112/112/74 113/113/75 +f 113/113/75 112/112/74 114/114/76 +f 114/114/77 115/115/78 116/116/79 +f 116/116/79 115/115/78 117/117/80 +f 117/117/81 115/115/81 118/118/81 +f 117/117/82 118/118/82 119/119/82 +f 119/119/62 118/118/63 120/120/64 +f 120/120/64 118/118/63 121/121/65 +f 122/122/83 123/123/83 124/124/83 +f 125/125/84 124/124/84 126/126/84 +f 125/125/85 126/126/86 127/127/87 +f 125/125/85 127/127/87 128/128/88 +f 128/128/88 127/127/87 129/129/89 +f 128/128/90 129/129/90 130/130/90 +f 130/130/91 129/129/91 131/131/91 +f 130/130/92 131/131/92 132/132/92 +f 132/132/93 131/131/93 133/133/93 +f 132/132/94 133/133/95 134/134/96 +f 132/132/94 134/134/96 135/135/97 +f 135/135/97 134/134/96 136/136/98 +f 135/135/97 136/136/98 137/137/99 +f 137/137/99 136/136/98 138/138/100 +f 138/138/101 136/136/101 139/139/101 +f 138/138/102 139/139/103 140/140/104 +f 140/140/104 139/139/103 141/141/105 +f 140/140/104 141/141/105 142/142/106 +f 142/142/106 141/141/105 143/143/107 +f 143/143/107 141/141/105 144/144/108 +f 143/143/109 144/144/110 145/145/111 +f 145/145/111 144/144/110 146/146/112 +f 147/147/66 148/148/66 149/149/66 +f 149/149/18 148/148/18 150/150/18 +f 149/149/67 150/150/67 151/151/67 +f 151/151/113 150/150/113 152/152/113 +f 151/151/114 152/152/114 153/153/114 +f 153/153/115 152/152/115 154/154/115 +f 153/153/116 154/154/116 155/155/116 +f 155/155/117 154/154/117 156/156/117 +f 155/155/118 156/156/118 157/157/118 +f 157/157/70 156/156/70 158/158/70 +f 157/157/119 158/158/120 159/159/121 +f 159/159/121 158/158/120 160/160/122 +f 160/160/123 161/161/124 162/162/125 +f 162/162/125 161/161/124 163/163/126 +f 163/163/127 164/164/127 165/165/127 +f 165/165/128 164/164/59 166/166/60 +f 165/165/128 166/166/60 167/167/61 +f 167/167/129 166/166/130 168/168/64 +f 168/168/64 166/166/130 169/169/65 +f 170/170/66 171/171/66 172/172/66 +f 172/172/18 171/171/18 173/173/18 +f 172/172/67 173/173/67 174/174/67 +f 174/174/20 173/173/20 175/175/20 +f 174/174/131 175/175/131 176/176/131 +f 176/176/132 175/175/132 177/177/132 +f 176/176/133 177/177/133 178/178/133 +f 178/178/134 177/177/134 179/179/134 +f 178/178/135 179/179/136 180/180/137 +f 180/180/137 179/179/136 181/181/138 +f 181/181/138 179/179/136 182/182/139 +f 181/181/138 182/182/139 183/183/140 +f 181/181/138 183/183/140 184/184/141 +f 184/184/141 183/183/140 185/185/142 +f 185/185/143 186/186/144 187/187/145 +f 187/187/145 186/186/144 188/188/146 +f 188/188/147 186/186/148 189/189/149 +f 189/189/149 186/186/148 190/190/150 +f 189/189/151 190/190/151 191/191/151 +f 191/191/152 190/190/152 192/192/152 +f 193/193/153 194/194/154 195/195/155 +f 195/195/155 194/194/154 196/196/156 +f 196/196/156 194/194/154 197/197/157 +f 196/196/156 197/197/157 198/198/158 +f 198/198/158 197/197/157 199/199/159 +f 198/198/158 199/199/159 200/200/160 +f 200/200/160 199/199/159 201/201/161 +f 200/200/160 201/201/161 202/202/162 +f 200/200/160 202/202/162 203/203/163 +f 203/203/164 202/202/164 204/204/164 +f 203/203/165 204/204/165 205/205/165 +f 205/205/166 204/204/166 206/206/166 +f 205/205/167 206/206/168 207/207/169 +f 207/207/169 206/206/168 208/208/170 +f 208/208/170 206/206/168 209/209/171 +f 208/208/172 209/209/173 210/210/174 +f 210/210/174 209/209/173 211/211/175 +f 210/210/174 211/211/175 212/212/176 +f 212/212/176 211/211/175 213/213/177 +f 212/212/176 213/213/177 214/214/178 +f 214/214/178 213/213/177 215/215/179 +f 214/214/178 215/215/179 216/216/180 +f 214/214/178 216/216/180 217/217/181 +f 217/217/182 216/216/182 50/50/182 +f 218/218/183 219/219/184 220/220/185 +f 220/220/185 219/219/184 193/193/153 +f 220/220/185 193/193/153 43/43/186 +f 43/43/186 193/193/153 44/44/187 +f 44/44/187 193/193/153 195/195/155 +f 50/50/188 216/216/188 221/221/188 +f 222/222/189 223/223/189 224/224/189 +f 224/224/190 225/225/190 226/226/190 +f 226/226/191 225/225/192 227/227/193 +f 226/226/191 227/227/193 228/228/194 +f 228/228/195 227/227/195 229/229/195 +f 228/228/196 229/229/196 230/230/196 +f 230/230/197 229/229/197 231/231/197 +f 230/230/198 231/231/198 232/232/198 +f 232/232/199 231/231/199 233/233/199 +f 232/232/200 233/233/200 234/234/200 +f 234/234/201 233/233/201 235/235/201 +f 234/234/202 235/235/202 236/236/202 +f 236/236/203 235/235/203 237/237/203 +f 236/236/204 237/237/204 238/238/204 +f 238/238/205 237/237/206 239/239/207 +f 238/238/205 239/239/207 240/240/208 +f 240/240/208 239/239/207 241/241/209 +f 240/240/208 241/241/209 242/242/210 +f 242/242/211 241/241/211 243/243/211 +f 244/244/212 243/243/212 245/245/212 +f 246/246/213 247/247/213 248/248/213 +f 248/248/214 249/249/214 250/250/214 +f 250/250/215 249/249/215 251/251/215 +f 250/250/216 251/251/217 252/252/218 +f 250/250/216 252/252/218 253/253/219 +f 253/253/220 252/252/221 254/254/222 +f 253/253/220 254/254/222 255/255/223 +f 255/255/224 254/254/225 256/256/226 +f 255/255/224 256/256/226 257/257/227 +f 257/257/228 256/256/229 258/258/230 +f 257/257/228 258/258/230 259/259/231 +f 259/259/231 258/258/230 260/260/232 +f 260/260/232 258/258/230 261/261/233 +f 260/260/232 261/261/233 262/262/234 +f 260/260/232 262/262/234 263/263/235 +f 263/263/236 262/262/237 264/264/238 +f 263/263/236 264/264/238 265/265/239 +f 265/265/240 264/264/240 266/266/240 +f 266/266/241 267/267/241 268/268/241 +f 269/269/242 270/270/242 271/271/242 +f 271/271/243 270/270/243 272/272/243 +f 271/271/244 272/272/245 273/273/246 +f 271/271/244 273/273/246 274/274/247 +f 274/274/247 273/273/246 275/275/248 +f 274/274/249 275/275/250 276/276/251 +f 276/276/251 275/275/250 277/277/252 +f 277/277/253 278/278/254 279/279/255 +f 279/279/255 278/278/254 280/280/256 +f 279/279/257 280/280/257 281/281/257 +f 281/281/258 280/280/258 282/282/258 +f 281/281/259 282/282/259 283/283/259 +f 283/283/260 282/282/261 284/284/262 +f 283/283/260 284/284/262 285/285/263 +f 285/285/263 284/284/262 286/286/264 +f 286/286/265 284/284/265 287/287/265 +f 286/286/266 287/287/267 288/288/268 +f 288/288/268 287/287/267 289/289/269 +f 288/288/268 289/289/269 290/290/270 +f 290/290/271 289/289/271 291/291/271 +f 290/290/272 291/291/272 292/292/272 +f 293/293/273 292/292/273 294/294/273 +f 295/295/274 296/296/274 297/297/274 +f 297/297/275 296/296/275 298/298/275 +f 297/297/276 298/298/276 299/299/276 +f 299/299/277 298/298/277 300/300/277 +f 299/299/278 300/300/279 301/301/280 +f 299/299/278 301/301/280 302/302/281 +f 302/302/282 301/301/282 303/303/282 +f 302/302/283 303/303/284 304/304/285 +f 302/302/283 304/304/285 305/305/286 +f 305/305/286 304/304/285 306/306/287 +f 305/305/286 306/306/287 307/307/288 +f 307/307/289 306/306/289 308/308/289 +f 307/307/290 308/308/290 309/309/290 +f 309/309/291 308/308/292 310/310/293 +f 309/309/291 310/310/293 311/311/294 +f 311/311/294 310/310/293 312/312/295 +f 312/312/295 310/310/293 313/313/296 +f 312/312/297 313/313/297 314/314/297 +f 312/312/298 314/314/298 315/315/298 +f 315/315/299 314/314/299 316/316/299 +f 316/316/300 314/314/300 317/317/300 +f 316/316/301 317/317/301 318/318/301 +f 318/318/302 317/317/302 319/319/302 +f 320/320/303 321/321/304 322/322/305 +f 322/322/306 323/323/306 9/9/306 +f 247/247/307 246/246/308 324/324/309 +f 324/324/309 246/246/308 321/321/310 +f 324/324/311 321/321/304 320/320/303 +f 324/324/311 320/320/303 325/325/312 +f 325/325/312 320/320/303 326/326/313 +f 325/325/310 326/326/314 269/269/315 +f 269/269/315 326/326/314 270/270/316 +f 296/296/317 295/295/318 327/327/319 +f 296/296/317 327/327/319 320/320/303 +f 320/320/303 327/327/319 326/326/313 +f 328/328/320 10/10/321 329/329/322 +f 329/329/322 10/10/321 9/9/323 +f 329/329/322 9/9/323 330/330/324 +f 331/331/316 332/332/325 333/333/326 +f 333/333/326 332/332/325 330/330/327 +f 333/333/328 330/330/324 9/9/323 +f 333/333/328 9/9/323 323/323/329 +f 323/323/330 334/334/330 335/335/330 +f 9/9/331 320/320/303 322/322/305 +f 222/222/332 322/322/332 223/223/332 +f 336/336/333 337/337/334 338/338/335 +f 338/338/335 337/337/334 339/339/336 +f 340/340/337 341/341/338 342/342/339 +f 342/342/339 341/341/338 338/338/335 +f 342/342/339 338/338/335 343/343/340 +f 343/343/340 338/338/335 339/339/336 +f 14/14/341 12/12/342 45/45/343 +f 45/45/343 12/12/342 22/22/344 +f 293/293/345 294/294/346 344/344/347 +f 293/293/345 344/344/347 345/345/348 +f 345/345/349 344/344/350 343/343/340 +f 343/343/340 344/344/350 346/346/351 +f 346/346/352 344/344/353 318/318/354 +f 346/346/352 318/318/354 319/319/355 +f 268/268/356 267/267/356 345/345/357 +f 268/268/356 345/345/357 347/347/357 +f 244/244/358 245/245/359 339/339/360 +f 339/339/360 245/245/359 347/347/361 +f 339/339/336 347/347/362 343/343/340 +f 343/343/340 347/347/362 345/345/349 +f 22/22/363 342/342/364 45/45/365 +f 45/45/366 342/342/339 343/343/340 +f 348/348/367 349/349/367 350/350/367 +f 350/350/368 349/349/368 351/351/368 +f 350/350/369 351/351/369 352/352/369 +f 352/352/370 351/351/370 353/353/370 +f 352/352/371 353/353/371 354/354/371 +f 354/354/372 353/353/373 348/348/374 +f 348/348/374 353/353/373 349/349/375 +f 355/355/376 356/356/377 357/357/378 +f 355/355/376 357/357/378 358/358/379 +f 358/358/380 357/357/380 359/359/380 +f 358/358/381 359/359/381 360/360/381 +f 360/360/382 359/359/382 361/361/382 +f 360/360/383 361/361/384 355/355/385 +f 355/355/385 361/361/384 356/356/386 +f 362/362/387 363/363/387 364/364/387 +f 362/362/388 364/364/388 365/365/388 +f 365/365/389 364/364/389 366/366/389 +f 365/365/390 366/366/390 367/367/390 +f 367/367/391 366/366/391 363/363/391 +f 367/367/392 363/363/392 362/362/392 +f 335/335/393 368/368/393 369/369/393 +f 369/369/394 368/368/394 370/370/394 +f 369/369/395 370/370/395 371/371/395 +f 371/371/396 370/370/396 372/372/396 +f 371/371/397 372/372/217 373/373/398 +f 371/371/397 373/373/398 374/374/399 +f 374/374/399 373/373/398 375/375/400 +f 375/375/401 373/373/401 376/376/401 +f 375/375/402 376/376/402 377/377/402 +f 377/377/197 376/376/197 378/378/197 +f 377/377/403 378/378/403 379/379/403 +f 379/379/199 378/378/199 380/380/199 +f 379/379/404 380/380/404 381/381/404 +f 382/382/405 381/381/406 383/383/407 +f 382/382/405 383/383/407 384/384/408 +f 384/384/409 385/385/410 386/386/411 +f 386/386/412 385/385/412 387/387/412 +f 386/386/413 387/387/413 388/388/413 +f 388/388/414 337/337/414 336/336/414 +f 335/335/415 334/334/415 368/368/415 +f 389/389/416 390/390/416 391/391/416 +f 389/389/417 391/391/417 392/392/417 +f 392/392/418 391/391/418 393/393/418 +f 392/392/419 393/393/419 394/394/419 +f 394/394/420 393/393/420 390/390/420 +f 394/394/421 390/390/421 389/389/421 +f 395/395/422 396/396/422 397/397/422 +f 395/395/423 397/397/424 398/398/425 +f 395/395/426 398/398/426 399/399/426 +f 399/399/427 398/398/427 400/400/427 +f 399/399/428 400/400/428 401/401/428 +f 401/401/429 400/400/429 396/396/429 +f 401/401/430 396/396/430 395/395/430 +f 402/402/431 403/403/431 404/404/431 +f 404/404/432 403/403/432 374/374/432 +f 404/404/433 374/374/434 405/405/435 +f 405/405/435 374/374/434 406/406/436 +f 405/405/437 406/406/438 407/407/439 +f 405/405/437 407/407/439 402/402/440 +f 402/402/441 407/407/441 403/403/441 +f 332/332/242 331/331/242 408/408/242 +f 408/408/243 331/331/243 409/409/243 +f 408/408/244 409/409/442 410/410/443 +f 408/408/244 410/410/443 411/411/444 +f 411/411/445 410/410/446 412/412/193 +f 411/411/445 412/412/193 413/413/194 +f 413/413/447 412/412/448 414/414/449 +f 413/413/447 414/414/449 415/415/223 +f 415/415/450 414/414/451 416/416/452 +f 415/415/450 416/416/452 417/417/453 +f 417/417/228 416/416/229 418/418/454 +f 417/417/228 418/418/454 419/419/455 +f 419/419/455 418/418/454 420/420/456 +f 420/420/457 418/418/457 421/421/457 +f 420/420/458 421/421/458 422/422/458 +f 422/422/459 423/423/459 424/424/459 +f 424/424/460 423/423/460 425/425/460 +f 424/424/461 425/425/461 426/426/461 +f 426/426/462 425/425/462 427/427/462 +f 426/426/463 427/427/463 340/340/463 +f 340/340/464 427/427/464 341/341/464 +f 428/428/465 38/38/466 429/429/467 +f 429/429/467 38/38/466 430/430/468 +f 429/429/469 430/430/469 431/431/469 +f 431/431/470 430/430/470 432/432/470 +f 431/431/471 432/432/472 433/433/473 +f 433/433/473 432/432/472 434/434/474 +f 433/433/473 434/434/474 435/435/475 +f 435/435/475 434/434/474 436/436/476 +f 436/436/476 434/434/474 19/19/477 +f 436/436/476 19/19/477 437/437/478 +f 437/437/478 19/19/477 21/21/479 +f 437/437/478 21/21/479 438/438/480 +f 438/438/480 21/21/479 36/36/481 +f 438/438/480 36/36/481 439/439/482 +f 440/440/483 441/441/483 442/442/483 +f 440/440/484 442/442/484 443/443/484 +f 443/443/485 442/442/485 444/444/485 +f 443/443/486 444/444/486 445/445/486 +f 445/445/487 444/444/487 446/446/487 +f 445/445/488 446/446/489 441/441/490 +f 445/445/488 441/441/490 440/440/491 +f 447/447/492 448/448/492 449/449/492 +f 447/447/493 449/449/493 450/450/493 +f 450/450/494 449/449/495 451/451/496 +f 450/450/494 451/451/496 452/452/497 +f 452/452/498 451/451/498 448/448/498 +f 452/452/499 448/448/499 447/447/499 +f 453/453/500 454/454/500 455/455/500 +f 455/455/501 454/454/501 456/456/501 +f 455/455/502 456/456/502 457/457/502 +f 457/457/503 456/456/503 458/458/503 +f 457/457/504 458/458/504 453/453/504 +f 453/453/505 458/458/505 454/454/505 +f 328/328/506 459/459/507 10/10/508 +f 10/10/508 459/459/507 52/52/509 +f 5/5/510 460/460/511 6/6/512 +f 6/6/512 460/460/511 461/461/513 +f 42/42/514 462/462/515 220/220/516 +f 42/42/514 220/220/516 43/43/517 +f 463/463/518 40/40/519 30/30/520 +f 463/463/518 30/30/520 428/428/465 +f 428/428/465 30/30/520 38/38/466 +f 33/33/521 464/464/522 36/36/481 +f 36/36/481 464/464/522 439/439/482 +f 465/465/523 346/346/524 466/466/525 +f 466/466/525 346/346/524 467/467/526 +f 466/466/525 467/467/526 468/468/527 +f 468/468/527 467/467/526 469/469/528 +f 468/468/529 469/469/530 470/470/531 +f 470/470/531 469/469/530 355/355/376 +f 470/470/531 355/355/376 358/358/379 +f 470/470/531 358/358/379 471/471/532 +f 471/471/532 358/358/379 472/472/533 +f 471/471/532 472/472/533 473/473/534 +f 473/473/534 472/472/533 474/474/535 +f 473/473/534 474/474/535 475/475/536 +f 475/475/536 474/474/535 348/348/537 +f 475/475/536 348/348/537 476/476/538 +f 476/476/538 348/348/537 477/477/539 +f 476/476/538 477/477/539 478/478/540 +f 478/478/540 477/477/539 479/479/541 +f 478/478/540 479/479/541 480/480/542 +f 480/480/542 479/479/541 481/481/543 +f 481/481/543 479/479/541 367/367/544 +f 481/481/543 367/367/544 482/482/545 +f 482/482/546 367/367/546 362/362/546 +f 482/482/547 362/362/548 483/483/549 +f 482/482/547 483/483/549 484/484/550 +f 484/484/550 483/483/549 485/485/551 +f 485/485/551 483/483/549 486/486/552 +f 485/485/551 486/486/552 320/320/303 +f 485/485/551 320/320/303 487/487/553 +f 465/465/554 343/343/340 346/346/351 +f 488/488/555 489/489/556 465/465/554 +f 465/465/554 489/489/556 462/462/557 +f 490/490/558 491/491/559 461/461/560 +f 461/461/560 491/491/559 487/487/553 +f 461/461/560 487/487/553 6/6/561 +f 6/6/561 487/487/553 9/9/331 +f 9/9/331 487/487/553 320/320/303 +f 462/462/557 42/42/562 465/465/554 +f 465/465/554 42/42/562 45/45/563 +f 465/465/554 45/45/563 343/343/340 +f 7/7/5 9/9/5 8/8/5 +f 301/301/5 362/362/5 365/365/5 +f 298/298/5 362/362/5 300/300/5 +f 300/300/5 362/362/5 301/301/5 +f 486/486/5 483/483/5 298/298/5 +f 313/313/5 360/360/5 314/314/5 +f 486/486/5 296/296/564 320/320/564 +f 298/298/5 483/483/5 362/362/5 +f 477/477/5 348/348/5 350/350/5 +f 486/486/5 298/298/5 296/296/564 +f 308/308/5 352/352/5 354/354/5 +f 314/314/5 360/360/5 355/355/5 +f 314/314/5 355/355/5 469/469/5 +f 306/306/5 350/350/5 352/352/5 +f 306/306/5 352/352/5 308/308/5 +f 301/301/5 365/365/5 303/303/5 +f 303/303/5 365/365/5 304/304/5 +f 313/313/5 358/358/5 360/360/5 +f 314/314/5 469/469/5 467/467/5 +f 314/314/5 467/467/5 317/317/5 +f 317/317/5 467/467/5 319/319/5 +f 358/358/5 313/313/5 310/310/5 +f 350/350/5 306/306/5 304/304/5 +f 308/308/5 354/354/5 310/310/5 +f 479/479/5 477/477/5 304/304/5 +f 350/350/5 304/304/5 477/477/5 +f 354/354/5 348/348/5 474/474/5 +f 354/354/5 474/474/5 310/310/5 +f 310/310/5 474/474/5 472/472/5 +f 358/358/5 310/310/5 472/472/5 +f 467/467/5 346/346/5 319/319/5 +f 365/365/5 367/367/5 479/479/5 +f 365/365/5 479/479/5 304/304/5 +f 220/220/5 489/489/5 218/218/5 +f 462/462/5 489/489/5 220/220/5 +f 489/489/565 488/488/566 219/219/567 +f 489/489/565 219/219/567 218/218/568 +f 460/460/5 492/492/5 490/490/5 +f 460/460/5 490/490/5 461/461/5 +f 492/492/569 493/493/570 490/490/571 +f 490/490/571 493/493/570 491/491/572 +f 413/413/573 456/456/573 454/454/573 +f 424/424/574 448/448/573 451/451/575 +f 419/419/573 444/444/573 417/417/573 +f 451/451/575 422/422/576 424/424/574 +f 413/413/573 454/454/573 411/411/573 +f 458/458/573 456/456/573 494/494/573 +f 451/451/575 449/449/573 495/495/573 +f 448/448/573 424/424/574 426/426/573 +f 411/411/573 454/454/573 408/408/573 +f 419/419/573 446/446/573 444/444/573 +f 417/417/573 444/444/573 442/442/573 +f 446/446/573 419/419/573 420/420/577 +f 422/422/576 451/451/575 420/420/577 +f 496/496/573 340/340/573 342/342/573 +f 449/449/573 448/448/573 426/426/573 +f 449/449/573 426/426/573 497/497/573 +f 408/408/573 454/454/573 498/498/573 +f 498/498/573 454/454/573 458/458/573 +f 417/417/573 442/442/573 415/415/573 +f 420/420/577 495/495/573 499/499/573 +f 456/456/573 413/413/573 415/415/573 +f 495/495/573 420/420/577 451/451/575 +f 497/497/573 426/426/573 496/496/573 +f 446/446/573 420/420/577 499/499/573 +f 446/446/573 499/499/573 441/441/573 +f 426/426/573 340/340/573 496/496/573 +f 408/408/573 498/498/573 500/500/573 +f 415/415/573 442/442/573 501/501/573 +f 415/415/573 501/501/573 494/494/573 +f 494/494/573 456/456/573 415/415/573 +f 330/330/573 332/332/573 500/500/573 +f 500/500/573 332/332/573 408/408/573 +f 22/22/363 26/26/578 342/342/364 +f 342/342/364 26/26/578 496/496/579 +f 496/496/580 26/26/580 497/497/580 +f 497/497/581 26/26/581 35/35/581 +f 497/497/582 35/35/582 449/449/582 +f 34/34/583 449/449/583 35/35/583 +f 449/449/584 34/34/584 495/495/584 +f 34/34/585 20/20/585 495/495/585 +f 495/495/586 20/20/586 499/499/586 +f 499/499/587 20/20/587 502/502/587 +f 503/503/588 442/442/588 441/441/588 +f 503/503/589 441/441/589 502/502/589 +f 502/502/590 441/441/590 499/499/590 +f 442/442/591 503/503/591 501/501/591 +f 501/501/592 503/503/592 504/504/592 +f 501/501/593 504/504/594 494/494/595 +f 494/494/595 504/504/594 458/458/596 +f 458/458/596 504/504/594 505/505/597 +f 458/458/596 505/505/597 498/498/598 +f 498/498/599 505/505/599 37/37/599 +f 498/498/600 37/37/600 500/500/600 +f 500/500/601 37/37/601 329/329/601 +f 329/329/602 330/330/602 500/500/602 +f 375/375/573 406/406/573 374/374/573 +f 396/396/603 400/400/604 386/386/411 +f 381/381/605 393/393/606 379/379/607 +f 400/400/604 384/384/409 386/386/411 +f 374/374/573 403/403/608 371/371/609 +f 384/384/409 400/400/604 398/398/610 +f 384/384/409 398/398/610 382/382/611 +f 506/506/573 391/391/573 390/390/573 +f 396/396/603 386/386/411 388/388/612 +f 381/381/605 390/390/613 393/393/606 +f 390/390/613 381/381/605 382/382/611 +f 507/507/614 323/323/615 335/335/616 +f 508/508/617 336/336/618 338/338/619 +f 397/397/620 396/396/603 388/388/612 +f 397/397/620 388/388/612 509/509/621 +f 371/371/609 403/403/608 510/510/622 +f 510/510/622 403/403/608 407/407/623 +f 379/379/607 393/393/606 391/391/573 +f 379/379/607 391/391/573 377/377/573 +f 406/406/573 375/375/573 377/377/573 +f 511/511/573 382/382/611 398/398/610 +f 382/382/611 511/511/573 512/512/573 +f 509/509/621 388/388/612 508/508/617 +f 390/390/613 382/382/611 512/512/573 +f 388/388/612 336/336/618 508/508/617 +f 371/371/609 510/510/622 507/507/614 +f 371/371/609 507/507/614 369/369/573 +f 391/391/573 506/506/573 377/377/573 +f 506/506/573 513/513/573 377/377/573 +f 407/407/573 406/406/573 377/377/573 +f 407/407/573 377/377/573 513/513/573 +f 507/507/614 335/335/616 369/369/573 +f 453/453/5 410/410/5 409/409/5 +f 410/410/5 453/453/5 455/455/5 +f 410/410/5 455/455/5 412/412/5 +f 423/423/624 452/452/625 447/447/5 +f 453/453/626 510/510/626 457/457/626 +f 423/423/624 447/447/5 425/425/5 +f 333/333/5 514/514/627 331/331/5 +f 409/409/628 514/514/627 510/510/629 +f 510/510/630 453/453/630 409/409/630 +f 338/338/631 341/341/632 515/515/633 +f 425/425/5 447/447/5 516/516/5 +f 516/516/5 447/447/5 450/450/5 +f 514/514/627 409/409/628 331/331/5 +f 425/425/5 516/516/5 515/515/633 +f 425/425/5 515/515/633 427/427/5 +f 416/416/5 443/443/5 418/418/5 +f 418/418/5 443/443/5 445/445/5 +f 445/445/5 440/440/5 517/517/5 +f 422/422/634 452/452/625 423/423/624 +f 412/412/5 455/455/5 457/457/5 +f 412/412/5 457/457/5 414/414/5 +f 450/450/5 452/452/625 518/518/5 +f 418/418/5 445/445/5 421/421/635 +f 515/515/633 341/341/632 427/427/5 +f 452/452/625 422/422/634 421/421/635 +f 445/445/5 517/517/5 421/421/635 +f 519/519/5 520/520/5 414/414/5 +f 440/440/5 443/443/5 520/520/5 +f 520/520/5 443/443/5 414/414/5 +f 443/443/5 416/416/5 414/414/5 +f 421/421/635 517/517/5 518/518/5 +f 457/457/5 519/519/5 414/414/5 +f 518/518/5 452/452/625 421/421/635 +f 338/338/636 515/515/636 508/508/636 +f 508/508/637 515/515/637 509/509/637 +f 509/509/638 515/515/638 516/516/638 +f 509/509/639 516/516/639 397/397/639 +f 397/397/424 516/516/640 450/450/641 +f 397/397/424 450/450/641 398/398/425 +f 398/398/425 450/450/641 518/518/642 +f 398/398/643 518/518/643 511/511/643 +f 511/511/644 518/518/644 517/517/644 +f 511/511/645 517/517/645 512/512/645 +f 512/512/646 517/517/647 440/440/648 +f 512/512/646 440/440/648 390/390/649 +f 390/390/649 440/440/648 506/506/650 +f 506/506/650 440/440/648 520/520/651 +f 506/506/652 520/520/652 513/513/652 +f 513/513/653 520/520/653 519/519/653 +f 513/513/654 519/519/654 407/407/654 +f 407/407/655 519/519/656 457/457/657 +f 407/407/655 457/457/657 510/510/658 +f 510/510/659 514/514/659 507/507/659 +f 507/507/660 514/514/661 333/333/328 +f 507/507/660 333/333/328 323/323/329 +f 253/253/573 521/521/662 522/522/573 +f 263/263/573 523/523/663 524/524/573 +f 259/259/573 525/525/573 257/257/573 +f 253/253/573 522/522/573 250/250/664 +f 257/257/573 525/525/573 526/526/573 +f 263/263/573 524/524/573 527/527/573 +f 263/263/573 527/527/573 260/260/573 +f 528/528/665 526/526/573 529/529/573 +f 523/523/663 265/265/666 266/266/667 +f 265/265/666 523/523/663 263/263/573 +f 250/250/664 522/522/573 530/530/668 +f 259/259/573 531/531/573 525/525/573 +f 531/531/573 259/259/573 260/260/573 +f 532/532/669 268/268/670 347/347/671 +f 533/533/672 523/523/663 266/266/667 +f 533/533/673 266/266/674 534/534/675 +f 250/250/664 530/530/668 535/535/676 +f 257/257/573 526/526/573 255/255/677 +f 521/521/662 253/253/573 255/255/677 +f 536/536/573 260/260/573 527/527/573 +f 260/260/573 536/536/573 531/531/573 +f 534/534/678 266/266/679 532/532/669 +f 266/266/679 268/268/670 532/532/669 +f 250/250/664 535/535/676 537/537/680 +f 250/250/664 537/537/680 248/248/681 +f 526/526/573 528/528/665 255/255/677 +f 528/528/665 538/538/682 255/255/677 +f 521/521/662 255/255/677 538/538/682 +f 321/321/573 246/246/683 537/537/680 +f 537/537/680 246/246/683 248/248/681 +f 539/539/684 225/225/685 224/224/686 +f 539/539/684 540/540/5 225/225/685 +f 225/225/685 540/540/5 227/227/5 +f 239/239/5 541/541/687 241/241/688 +f 322/322/689 542/542/690 223/223/691 +f 539/539/692 224/224/693 535/535/694 +f 543/543/695 347/347/696 245/245/697 +f 241/241/688 541/541/687 534/534/698 +f 534/534/698 541/541/687 544/544/699 +f 535/535/700 224/224/701 542/542/690 +f 542/542/690 224/224/701 223/223/691 +f 241/241/688 534/534/698 243/243/702 +f 243/243/702 534/534/698 543/543/695 +f 545/545/5 227/227/5 540/540/5 +f 233/233/5 546/546/5 547/547/5 +f 548/548/703 549/549/5 546/546/5 +f 237/237/5 550/550/5 239/239/5 +f 227/227/5 545/545/5 229/229/704 +f 233/233/5 547/547/5 235/235/5 +f 543/543/695 245/245/697 243/243/702 +f 550/550/5 237/237/5 235/235/5 +f 231/231/5 546/546/5 233/233/5 +f 235/235/5 547/547/5 551/551/5 +f 548/548/703 546/546/5 229/229/704 +f 546/546/5 231/231/5 229/229/704 +f 538/538/705 548/548/703 229/229/704 +f 545/545/5 552/552/706 229/229/704 +f 229/229/704 552/552/706 538/538/705 +f 550/550/5 235/235/5 551/551/5 +f 347/347/707 543/543/707 532/532/707 +f 532/532/708 543/543/708 534/534/708 +f 533/533/673 534/534/675 544/544/709 +f 533/533/673 544/544/709 527/527/710 +f 527/527/711 544/544/712 550/550/713 +f 527/527/714 550/550/714 536/536/714 +f 536/536/715 550/550/715 551/551/715 +f 536/536/716 551/551/717 547/547/718 +f 536/536/716 547/547/718 531/531/719 +f 531/531/720 547/547/721 549/549/722 +f 531/531/720 549/549/722 529/529/723 +f 529/529/723 549/549/722 548/548/724 +f 529/529/723 548/548/724 528/528/725 +f 528/528/725 548/548/724 538/538/726 +f 538/538/727 552/552/727 521/521/727 +f 521/521/728 552/552/728 530/530/728 +f 530/530/729 552/552/730 539/539/692 +f 530/530/729 539/539/692 535/535/694 +f 537/537/731 535/535/731 542/542/731 +f 537/537/732 542/542/733 322/322/734 +f 537/537/732 322/322/734 321/321/735 +f 302/302/573 366/366/573 364/364/573 +f 309/309/573 353/353/736 307/307/573 +f 307/307/573 353/353/736 351/351/573 +f 359/359/573 312/312/573 361/361/573 +f 302/302/573 364/364/573 299/299/737 +f 363/363/738 366/366/739 553/553/740 +f 356/356/573 315/315/573 316/316/573 +f 356/356/573 361/361/573 315/315/573 +f 315/315/573 361/361/573 312/312/573 +f 299/299/737 364/364/573 363/363/668 +f 353/353/736 309/309/573 311/311/741 +f 312/312/573 359/359/573 311/311/741 +f 554/554/742 318/318/743 344/344/744 +f 356/356/377 316/316/745 555/555/746 +f 299/299/737 363/363/668 556/556/676 +f 307/307/573 351/351/573 305/305/747 +f 311/311/741 557/557/748 558/558/749 +f 366/366/573 302/302/573 305/305/573 +f 557/557/748 311/311/741 359/359/573 +f 557/557/748 359/359/573 357/357/573 +f 555/555/750 316/316/751 554/554/742 +f 353/353/736 311/311/741 558/558/749 +f 353/353/736 558/558/749 349/349/752 +f 554/554/742 316/316/751 318/318/743 +f 299/299/737 556/556/676 559/559/753 +f 299/299/737 559/559/753 297/297/573 +f 351/351/573 349/349/573 560/560/754 +f 351/351/573 560/560/754 305/305/747 +f 305/305/747 560/560/754 553/553/755 +f 553/553/740 366/366/739 305/305/756 +f 327/327/573 295/295/573 559/559/753 +f 559/559/753 295/295/573 297/297/573 +f 561/561/5 273/273/5 272/272/5 +f 273/273/5 561/561/5 275/275/757 +f 287/287/5 562/562/758 289/289/5 +f 287/287/5 563/563/5 562/562/758 +f 289/289/5 562/562/758 291/291/759 +f 553/553/760 564/564/761 565/565/762 +f 326/326/5 566/566/763 270/270/5 +f 565/565/5 561/561/5 272/272/5 +f 565/565/764 272/272/765 556/556/766 +f 291/291/759 562/562/758 555/555/767 +f 555/555/767 562/562/758 567/567/768 +f 556/556/769 272/272/770 566/566/763 +f 566/566/763 272/272/770 270/270/5 +f 291/291/759 555/555/767 568/568/771 +f 291/291/759 568/568/771 292/292/772 +f 568/568/771 344/344/773 294/294/774 +f 564/564/761 275/275/757 561/561/5 +f 282/282/5 569/569/5 570/570/5 +f 571/571/5 572/572/5 573/573/775 +f 275/275/757 564/564/761 277/277/776 +f 277/277/776 564/564/761 278/278/777 +f 282/282/5 570/570/5 284/284/5 +f 284/284/5 570/570/5 571/571/5 +f 568/568/771 294/294/774 292/292/772 +f 563/563/5 287/287/5 284/284/778 +f 280/280/5 572/572/5 569/569/5 +f 280/280/5 569/569/5 282/282/5 +f 571/571/779 558/558/779 284/284/779 +f 553/553/760 573/573/775 278/278/777 +f 573/573/775 572/572/5 278/278/777 +f 572/572/5 280/280/5 278/278/777 +f 284/284/778 558/558/780 574/574/781 +f 564/564/761 553/553/760 278/278/777 +f 567/567/5 563/563/5 574/574/781 +f 574/574/781 563/563/5 284/284/778 +f 344/344/782 568/568/783 554/554/784 +f 554/554/784 568/568/783 555/555/785 +f 356/356/377 555/555/746 567/567/786 +f 356/356/377 567/567/786 357/357/378 +f 357/357/378 567/567/786 574/574/787 +f 357/357/788 574/574/788 557/557/788 +f 557/557/789 574/574/789 558/558/789 +f 558/558/790 571/571/791 349/349/792 +f 349/349/792 571/571/791 573/573/793 +f 349/349/792 573/573/793 560/560/794 +f 560/560/795 573/573/795 553/553/795 +f 363/363/796 553/553/797 565/565/764 +f 363/363/796 565/565/764 556/556/766 +f 559/559/798 556/556/798 566/566/798 +f 559/559/799 566/566/800 326/326/801 +f 559/559/799 326/326/801 327/327/802 +f 575/575/803 530/530/804 576/576/805 +f 576/576/805 530/530/804 522/522/806 +f 576/576/807 522/522/807 577/577/807 +f 577/577/808 522/522/808 521/521/808 +f 577/577/809 521/521/809 575/575/809 +f 575/575/810 521/521/810 530/530/810 +f 277/277/811 578/578/812 276/276/813 +f 283/283/573 579/579/573 580/580/573 +f 283/283/573 580/580/573 281/281/573 +f 581/581/573 286/286/573 288/288/573 +f 276/276/573 582/582/573 274/274/573 +f 281/281/573 580/580/573 583/583/573 +f 584/584/573 578/578/812 585/585/573 +f 586/586/573 583/583/573 587/587/573 +f 588/588/573 587/587/573 579/579/573 +f 589/589/573 581/581/573 590/590/573 +f 591/591/814 290/290/815 292/292/816 +f 290/290/815 591/591/814 288/288/573 +f 274/274/573 582/582/573 271/271/573 +f 592/592/817 591/591/814 292/292/816 +f 579/579/573 283/283/573 285/285/573 +f 286/286/573 581/581/573 285/285/573 +f 592/592/817 293/293/818 345/345/819 +f 271/271/820 582/582/820 593/593/820 +f 593/593/821 582/582/821 584/584/821 +f 281/281/573 583/583/573 279/279/822 +f 285/285/573 589/589/573 588/588/573 +f 578/578/812 277/277/811 279/279/822 +f 589/589/573 285/285/573 581/581/573 +f 579/579/573 285/285/573 588/588/573 +f 292/292/816 293/293/818 592/592/817 +f 271/271/823 593/593/824 594/594/825 +f 583/583/573 586/586/573 279/279/822 +f 586/586/573 585/585/573 279/279/822 +f 585/585/573 578/578/812 279/279/822 +f 325/325/573 269/269/573 594/594/825 +f 594/594/825 269/269/573 271/271/823 +f 575/575/5 251/251/5 249/249/5 +f 575/575/5 576/576/5 251/251/5 +f 251/251/5 576/576/5 252/252/5 +f 262/262/5 595/595/5 264/264/826 +f 264/264/826 595/595/5 596/596/827 +f 264/264/826 596/596/827 266/266/828 +f 324/324/5 597/597/829 247/247/830 +f 249/249/831 597/597/829 593/593/629 +f 593/593/832 575/575/832 249/249/832 +f 247/247/830 597/597/829 248/248/833 +f 266/266/834 596/596/835 598/598/836 +f 597/597/829 249/249/831 248/248/833 +f 266/266/834 598/598/836 599/599/837 +f 266/266/834 599/599/837 267/267/838 +f 599/599/837 345/345/839 267/267/838 +f 577/577/5 252/252/5 576/576/5 +f 256/256/5 600/600/5 258/258/5 +f 601/601/5 602/602/5 603/603/5 +f 604/604/5 602/602/5 605/605/5 +f 262/262/5 606/606/5 595/595/5 +f 252/252/5 577/577/5 254/254/5 +f 607/607/5 577/577/5 575/575/5 +f 258/258/5 600/600/5 604/604/5 +f 258/258/5 604/604/5 261/261/5 +f 606/606/5 262/262/5 261/261/5 +f 256/256/5 603/603/5 600/600/5 +f 604/604/5 605/605/5 261/261/5 +f 607/607/5 601/601/5 254/254/5 +f 601/601/5 603/603/5 254/254/5 +f 603/603/5 256/256/5 254/254/5 +f 261/261/5 605/605/5 608/608/5 +f 577/577/5 607/607/5 254/254/5 +f 608/608/5 606/606/5 261/261/5 +f 345/345/840 599/599/840 592/592/840 +f 592/592/841 599/599/841 598/598/841 +f 592/592/842 598/598/842 591/591/842 +f 591/591/843 598/598/843 596/596/843 +f 591/591/844 596/596/845 590/590/846 +f 590/590/847 596/596/848 606/606/849 +f 590/590/847 606/606/849 589/589/850 +f 589/589/851 606/606/851 608/608/851 +f 589/589/852 608/608/852 588/588/852 +f 588/588/853 608/608/853 605/605/853 +f 588/588/854 605/605/855 602/602/856 +f 588/588/854 602/602/856 587/587/857 +f 587/587/857 602/602/856 601/601/858 +f 587/587/857 601/601/858 586/586/859 +f 586/586/860 601/601/860 585/585/860 +f 585/585/861 601/601/861 607/607/861 +f 585/585/862 607/607/862 584/584/862 +f 584/584/863 607/607/864 575/575/865 +f 584/584/863 575/575/865 593/593/866 +f 593/593/659 597/597/659 594/594/659 +f 594/594/867 597/597/661 324/324/868 +f 594/594/867 324/324/868 325/325/802 +f 539/539/869 609/609/869 540/540/869 +f 540/540/870 609/609/870 610/610/870 +f 540/540/871 610/610/871 545/545/871 +f 545/545/872 610/610/873 611/611/874 +f 545/545/872 611/611/874 552/552/875 +f 552/552/730 611/611/876 539/539/692 +f 539/539/877 611/611/877 609/609/877 +f 612/612/878 339/339/878 613/613/878 +f 228/228/573 610/610/573 609/609/879 +f 234/234/573 614/614/573 232/232/573 +f 615/615/573 238/238/573 240/240/573 +f 615/615/573 240/240/573 616/616/573 +f 228/228/573 609/609/879 226/226/880 +f 232/232/573 614/614/573 617/617/573 +f 618/618/573 617/617/573 619/619/573 +f 620/620/881 242/242/882 243/243/883 +f 242/242/882 620/620/881 240/240/573 +f 240/240/573 620/620/881 616/616/573 +f 226/226/880 609/609/879 224/224/884 +f 234/234/573 621/621/573 614/614/573 +f 621/621/573 234/234/573 236/236/573 +f 622/622/885 322/322/886 222/222/887 +f 238/238/573 615/615/573 236/236/573 +f 612/612/888 244/244/889 339/339/890 +f 620/620/891 243/243/891 623/623/891 +f 224/224/884 609/609/879 624/624/892 +f 624/624/892 609/609/879 611/611/573 +f 232/232/573 617/617/573 230/230/573 +f 610/610/573 228/228/573 230/230/573 +f 625/625/573 236/236/573 626/626/573 +f 626/626/573 236/236/573 615/615/573 +f 236/236/573 625/625/573 621/621/573 +f 623/623/893 243/243/894 612/612/888 +f 243/243/894 244/244/889 612/612/888 +f 224/224/884 624/624/892 622/622/885 +f 224/224/884 622/622/885 222/222/887 +f 617/617/573 618/618/573 230/230/573 +f 618/618/573 627/627/573 230/230/573 +f 611/611/573 610/610/573 230/230/573 +f 611/611/573 230/230/573 627/627/573 +f 402/402/5 372/372/5 370/370/5 +f 372/372/5 402/402/5 404/404/5 +f 372/372/5 404/404/5 373/373/5 +f 385/385/895 401/401/5 387/387/896 +f 387/387/896 401/401/5 395/395/897 +f 387/387/896 395/395/897 388/388/898 +f 628/628/5 405/405/5 402/402/5 +f 402/402/5 370/370/5 629/629/5 +f 613/613/899 339/339/900 337/337/901 +f 388/388/902 395/395/902 623/623/902 +f 629/629/5 370/370/5 334/334/5 +f 334/334/5 370/370/5 368/368/5 +f 388/388/903 623/623/904 613/613/899 +f 388/388/903 613/613/899 337/337/901 +f 405/405/5 373/373/5 404/404/5 +f 380/380/905 392/392/5 394/394/906 +f 394/394/906 389/389/5 630/630/5 +f 384/384/907 399/399/908 385/385/895 +f 385/385/895 399/399/908 401/401/5 +f 373/373/5 405/405/5 376/376/5 +f 380/380/905 394/394/906 381/381/909 +f 381/381/909 394/394/906 383/383/910 +f 631/631/5 395/395/5 399/399/908 +f 399/399/908 384/384/907 383/383/910 +f 378/378/5 389/389/5 392/392/5 +f 378/378/5 392/392/5 380/380/905 +f 394/394/906 630/630/5 383/383/910 +f 628/628/5 632/632/5 376/376/5 +f 389/389/5 378/378/5 376/376/5 +f 383/383/910 630/630/5 631/631/5 +f 376/376/5 632/632/5 389/389/5 +f 405/405/5 628/628/5 376/376/5 +f 631/631/5 399/399/908 383/383/910 +f 612/612/911 613/613/911 623/623/911 +f 620/620/912 623/623/913 395/395/914 +f 620/620/912 395/395/914 626/626/915 +f 626/626/915 395/395/914 631/631/916 +f 626/626/917 631/631/917 625/625/917 +f 625/625/644 631/631/644 630/630/644 +f 625/625/918 630/630/918 621/621/918 +f 621/621/919 630/630/919 389/389/919 +f 621/621/920 389/389/921 619/619/922 +f 619/619/922 389/389/921 618/618/923 +f 618/618/924 389/389/924 632/632/924 +f 618/618/925 632/632/925 627/627/925 +f 627/627/926 632/632/926 628/628/926 +f 627/627/927 628/628/927 611/611/927 +f 611/611/928 628/628/928 402/402/928 +f 611/611/929 402/402/929 624/624/929 +f 624/624/930 402/402/930 629/629/930 +f 624/624/931 629/629/931 622/622/931 +f 622/622/932 629/629/932 334/334/932 +f 622/622/933 334/334/933 323/323/933 +f 622/622/934 323/323/934 322/322/934 +f 562/562/935 591/591/844 590/590/846 +f 562/562/935 590/590/846 567/567/936 +f 567/567/937 590/590/937 581/581/937 +f 567/567/938 581/581/938 563/563/938 +f 563/563/939 581/581/939 288/288/939 +f 563/563/940 288/288/940 562/562/940 +f 562/562/941 288/288/941 591/591/941 +f 596/596/942 523/523/942 533/533/942 +f 596/596/943 533/533/673 606/606/944 +f 606/606/944 533/533/673 527/527/710 +f 606/606/945 527/527/945 524/524/945 +f 606/606/946 524/524/946 595/595/946 +f 595/595/947 524/524/947 523/523/947 +f 595/595/948 523/523/948 596/596/948 +f 541/541/949 620/620/949 544/544/949 +f 544/544/950 620/620/950 626/626/950 +f 544/544/712 626/626/951 550/550/713 +f 550/550/952 626/626/952 615/615/952 +f 550/550/953 615/615/954 239/239/955 +f 239/239/955 615/615/954 616/616/956 +f 239/239/957 616/616/958 541/541/959 +f 541/541/959 616/616/958 620/620/960 +f 571/571/961 587/587/961 572/572/961 +f 572/572/962 587/587/962 583/583/962 +f 572/572/963 583/583/963 569/569/963 +f 569/569/964 583/583/964 580/580/964 +f 569/569/965 580/580/965 570/570/965 +f 570/570/966 580/580/966 579/579/966 +f 570/570/967 579/579/967 571/571/967 +f 571/571/968 579/579/968 587/587/968 +f 602/602/969 529/529/970 603/603/971 +f 603/603/971 529/529/970 526/526/972 +f 603/603/973 526/526/973 600/600/973 +f 600/600/974 526/526/974 525/525/974 +f 600/600/975 525/525/976 604/604/977 +f 604/604/977 525/525/976 531/531/978 +f 604/604/979 531/531/720 602/602/980 +f 602/602/980 531/531/720 529/529/723 +f 549/549/981 619/619/981 617/617/981 +f 549/549/982 617/617/982 546/546/982 +f 546/546/983 617/617/983 614/614/983 +f 546/546/984 614/614/984 547/547/984 +f 547/547/985 614/614/985 621/621/985 +f 547/547/721 621/621/920 549/549/722 +f 549/549/722 621/621/920 619/619/922 +f 561/561/986 582/582/986 276/276/986 +f 561/561/987 276/276/987 564/564/987 +f 564/564/988 276/276/988 578/578/988 +f 564/564/989 578/578/990 584/584/991 +f 564/564/989 584/584/991 565/565/992 +f 565/565/993 584/584/993 582/582/993 +f 565/565/994 582/582/994 561/561/994 +f 78/78/995 77/77/996 633/633/997 +f 78/78/995 633/633/997 634/634/998 +f 634/634/999 633/633/1000 195/195/155 +f 634/634/999 195/195/155 635/635/1001 +f 634/634/999 635/635/1001 100/100/1002 +f 634/634/999 100/100/1002 99/99/996 +f 123/123/1003 122/122/1004 636/636/1005 +f 123/123/1003 636/636/1005 195/195/1006 +f 195/195/155 636/636/1007 635/635/1001 +f 25/25/1008 46/46/1009 23/23/1010 +f 23/23/1010 46/46/1009 44/44/1011 +f 23/23/1012 44/44/1013 637/637/1014 +f 171/171/1015 170/170/1015 637/637/1015 +f 637/637/1016 44/44/1016 638/638/1016 +f 638/638/1017 44/44/187 639/639/1018 +f 638/638/1019 639/639/1020 148/148/1021 +f 638/638/1019 148/148/1021 147/147/1022 +f 44/44/187 195/195/155 639/639/1018 +f 639/639/1018 195/195/155 633/633/1000 +f 639/639/1023 633/633/1024 53/53/1025 +f 53/53/1025 633/633/1024 54/54/1026 +f 207/207/169 640/640/1027 205/205/167 +f 205/205/1028 640/640/1028 641/641/1028 +f 641/641/1029 640/640/1029 642/642/1029 +f 641/641/1030 642/642/1030 643/643/1030 +f 641/641/1031 643/643/1031 644/644/1031 +f 644/644/1032 643/643/1033 207/207/1034 +f 207/207/1034 643/643/1033 640/640/1035 +f 200/200/1036 645/645/1036 646/646/1036 +f 646/646/1037 645/645/1037 647/647/1037 +f 646/646/1038 647/647/1038 648/648/1038 +f 648/648/1039 647/647/1039 649/649/1039 +f 648/648/1040 649/649/1040 200/200/1040 +f 200/200/1041 649/649/1041 645/645/1041 +f 650/650/1042 651/651/1043 212/212/1044 +f 212/212/1044 651/651/1043 652/652/1045 +f 212/212/1046 652/652/1047 653/653/1048 +f 653/653/1048 652/652/1047 654/654/1049 +f 653/653/1050 654/654/1050 140/140/1050 +f 653/653/1051 140/140/1051 650/650/1051 +f 650/650/1052 140/140/1052 651/651/1052 +f 655/655/1053 656/656/1054 657/657/1055 +f 655/655/1053 657/657/1055 658/658/1056 +f 658/658/1057 657/657/1057 659/659/1057 +f 659/659/1058 657/657/1058 159/159/1058 +f 659/659/1059 159/159/1059 660/660/1059 +f 659/659/1060 660/660/1060 655/655/1060 +f 655/655/1061 660/660/1061 656/656/1061 +f 661/661/1062 662/662/1063 663/663/1064 +f 663/663/1064 662/662/1063 664/664/1065 +f 663/663/1066 664/664/1066 665/665/1066 +f 663/663/1067 665/665/1067 666/666/1067 +f 666/666/1068 665/665/1069 661/661/1070 +f 661/661/1070 665/665/1069 662/662/1071 +f 667/667/1072 668/668/1072 669/669/1072 +f 669/669/1073 668/668/1073 670/670/1073 +f 669/669/1074 670/670/1074 671/671/1074 +f 671/671/1075 670/670/1075 672/672/1075 +f 671/671/1076 672/672/1076 667/667/1076 +f 667/667/1077 672/672/1077 668/668/1077 +f 31/31/1078 47/47/1079 25/25/1080 +f 25/25/1080 47/47/1079 46/46/1081 +f 33/33/521 28/28/1082 464/464/522 +f 464/464/522 28/28/1082 673/673/1083 +f 28/28/1082 27/27/1084 673/673/1083 +f 673/673/1083 27/27/1084 674/674/1085 +f 674/674/1085 27/27/1084 675/675/1086 +f 674/674/1085 675/675/1086 676/676/1087 +f 676/676/1087 675/675/1086 677/677/1088 +f 676/676/1087 677/677/1088 678/678/1089 +f 678/678/1089 677/677/1088 679/679/1090 +f 678/678/1089 679/679/1090 680/680/1091 +f 680/680/1091 679/679/1090 681/681/1092 +f 681/681/1092 682/682/1093 680/680/1091 +f 682/682/1093 681/681/1092 40/40/519 +f 682/682/1093 40/40/519 463/463/518 +f 683/683/1094 684/684/1094 685/685/1094 +f 683/683/1095 685/685/1095 686/686/1095 +f 686/686/1096 685/685/1096 687/687/1096 +f 686/686/1097 687/687/1097 688/688/1097 +f 688/688/1098 687/687/1098 689/689/1098 +f 688/688/1099 689/689/1099 683/683/1099 +f 683/683/1100 689/689/1100 684/684/1100 +f 690/690/1101 691/691/1101 692/692/1101 +f 690/690/1102 692/692/1102 693/693/1102 +f 693/693/1103 692/692/1103 694/694/1103 +f 693/693/1104 694/694/1104 695/695/1104 +f 695/695/1105 694/694/1105 691/691/1105 +f 695/695/1106 691/691/1106 690/690/1106 +f 696/696/1107 697/697/1107 698/698/1107 +f 698/698/1108 697/697/1108 699/699/1108 +f 698/698/1109 699/699/1109 700/700/1109 +f 700/700/1110 699/699/1110 187/187/1110 +f 700/700/1111 187/187/1111 701/701/1111 +f 701/701/1112 187/187/1112 702/702/1112 +f 701/701/1113 702/702/1113 696/696/1113 +f 696/696/1114 702/702/1114 697/697/1114 +f 2/2/1115 1/1/1116 48/48/1117 +f 48/48/1117 1/1/1116 703/703/1118 +f 48/48/1119 703/703/1120 51/51/1121 +f 51/51/1121 703/703/1120 704/704/1122 +f 47/47/1123 31/31/1124 16/16/1125 +f 47/47/1123 16/16/1125 15/15/1126 +f 460/460/1127 5/5/1128 705/705/1129 +f 460/460/1127 705/705/1129 492/492/1130 +f 492/492/1130 705/705/1129 493/493/1131 +f 127/127/5 648/648/5 129/129/5 +f 129/129/5 648/648/5 131/131/5 +f 646/646/5 648/648/5 127/127/5 +f 653/653/5 139/139/5 136/136/5 +f 653/653/5 650/650/5 139/139/5 +f 139/139/5 650/650/5 141/141/5 +f 646/646/5 126/126/1132 200/200/5 +f 126/126/1132 646/646/5 127/127/5 +f 653/653/5 210/210/5 212/212/5 +f 133/133/5 641/641/5 134/134/5 +f 134/134/5 641/641/5 644/644/5 +f 131/131/5 205/205/5 641/641/5 +f 131/131/5 641/641/5 133/133/5 +f 123/123/1133 195/195/1134 196/196/1135 +f 134/134/5 644/644/5 136/136/5 +f 141/141/5 650/650/5 144/144/5 +f 144/144/5 650/650/5 212/212/5 +f 144/144/5 212/212/5 214/214/5 +f 208/208/5 136/136/5 207/207/5 +f 207/207/5 136/136/5 644/644/5 +f 203/203/5 131/131/5 200/200/5 +f 200/200/5 131/131/5 648/648/5 +f 131/131/5 203/203/5 205/205/5 +f 136/136/5 208/208/5 210/210/5 +f 210/210/5 653/653/5 136/136/5 +f 200/200/5 126/126/1132 198/198/5 +f 198/198/5 126/126/1132 196/196/1135 +f 196/196/1135 126/126/1132 124/124/1136 +f 144/144/5 214/214/5 146/146/5 +f 196/196/1135 124/124/1136 123/123/1133 +f 214/214/5 217/217/5 146/146/5 +f 176/176/573 692/692/573 691/691/573 +f 692/692/573 176/176/573 178/178/573 +f 176/176/573 691/691/573 174/174/573 +f 188/188/573 702/702/573 187/187/573 +f 41/41/1137 706/706/1138 189/189/1139 +f 702/702/573 188/188/573 189/189/1139 +f 174/174/573 691/691/573 707/707/573 +f 707/707/573 691/691/573 694/694/573 +f 187/187/1140 699/699/1141 185/185/1142 +f 185/185/1142 699/699/1141 184/184/1143 +f 708/708/573 685/685/573 684/684/573 +f 697/697/573 702/702/573 706/706/1138 +f 706/706/1138 702/702/573 189/189/1139 +f 41/41/1137 191/191/1144 709/709/1145 +f 174/174/573 707/707/573 710/710/1146 +f 174/174/573 710/710/1146 172/172/573 +f 172/172/573 710/710/1146 170/170/1147 +f 684/684/1148 689/689/1149 711/711/1150 +f 181/181/573 689/689/1149 180/180/573 +f 180/180/573 689/689/1149 687/687/573 +f 41/41/1137 189/189/1139 191/191/1144 +f 689/689/1149 181/181/573 184/184/1143 +f 711/711/1150 689/689/1149 184/184/1143 +f 692/692/573 178/178/573 712/712/573 +f 692/692/573 712/712/573 694/694/573 +f 710/710/1146 637/637/1151 170/170/1147 +f 184/184/1143 713/713/1152 711/711/1150 +f 180/180/573 687/687/573 178/178/573 +f 178/178/573 687/687/573 685/685/573 +f 178/178/573 685/685/573 708/708/573 +f 178/178/573 708/708/573 712/712/573 +f 713/713/1152 184/184/1143 699/699/1141 +f 709/709/1153 714/714/1154 41/41/1155 +f 41/41/1156 715/715/1157 706/706/1158 +f 706/706/1158 715/715/1157 697/697/1159 +f 716/716/1160 699/699/1161 697/697/1162 +f 716/716/1160 697/697/1162 715/715/1163 +f 699/699/1164 716/716/1165 717/717/1166 +f 699/699/1164 717/717/1166 713/713/1167 +f 713/713/1167 717/717/1166 711/711/1168 +f 711/711/1169 718/718/1169 684/684/1169 +f 719/719/1170 708/708/1171 718/718/1172 +f 718/718/1172 708/708/1171 684/684/1173 +f 708/708/1174 719/719/1175 29/29/1176 +f 708/708/1174 29/29/1176 712/712/1177 +f 29/29/1178 694/694/1178 712/712/1178 +f 694/694/1179 29/29/1179 32/32/1179 +f 694/694/1180 32/32/1180 707/707/1180 +f 707/707/1181 32/32/1181 24/24/1181 +f 707/707/1182 24/24/1182 710/710/1182 +f 710/710/1183 24/24/1184 23/23/1012 +f 710/710/1183 23/23/1012 637/637/1014 +f 672/672/573 670/670/1185 165/165/1186 +f 153/153/573 155/155/573 664/664/573 +f 664/664/573 662/662/1187 153/153/573 +f 664/664/573 155/155/573 665/665/573 +f 665/665/573 155/155/573 157/157/573 +f 153/153/573 662/662/1187 151/151/1188 +f 672/672/573 165/165/1186 167/167/573 +f 151/151/1188 662/662/1187 720/720/1189 +f 720/720/1189 662/662/1187 665/665/1190 +f 165/165/1186 670/670/1185 163/163/1191 +f 163/163/1191 670/670/1185 162/162/1192 +f 657/657/573 656/656/573 721/721/573 +f 668/668/573 672/672/573 167/167/573 +f 668/668/573 167/167/573 722/722/573 +f 722/722/573 168/168/573 723/723/573 +f 160/160/1193 660/660/1194 159/159/1195 +f 159/159/573 657/657/573 157/157/1196 +f 151/151/1188 720/720/1189 724/724/1197 +f 151/151/1188 724/724/1197 149/149/573 +f 149/149/573 724/724/1197 147/147/573 +f 722/722/573 167/167/573 168/168/573 +f 660/660/1194 160/160/1193 162/162/1192 +f 656/656/1198 660/660/1194 162/162/1192 +f 656/656/1198 162/162/1192 725/725/1199 +f 665/665/1200 157/157/1200 726/726/1200 +f 724/724/1197 638/638/573 147/147/573 +f 162/162/1192 727/727/1201 725/725/1199 +f 157/157/1196 728/728/1202 726/726/1203 +f 157/157/1196 657/657/573 721/721/573 +f 721/721/573 728/728/1202 157/157/1196 +f 727/727/1201 162/162/1192 670/670/1185 +f 727/727/1201 670/670/1185 668/668/573 +f 175/175/1204 693/693/1205 177/177/1206 +f 186/186/1207 700/700/1208 701/701/5 +f 686/686/5 688/688/5 179/179/5 +f 700/700/1208 186/186/1207 185/185/1209 +f 700/700/1208 185/185/1209 183/183/1210 +f 175/175/1204 690/690/1211 693/693/1205 +f 186/186/1207 701/701/5 696/696/5 +f 186/186/1207 696/696/5 190/190/5 +f 179/179/5 688/688/5 182/182/5 +f 177/177/1206 686/686/5 179/179/5 +f 726/726/1212 177/177/1206 693/693/1205 +f 726/726/1212 693/693/1205 695/695/1213 +f 726/726/1212 729/729/1214 177/177/1206 +f 730/730/1215 171/171/1216 637/637/1217 +f 696/696/5 731/731/5 190/190/5 +f 182/182/5 688/688/5 683/683/5 +f 182/182/5 683/683/5 183/183/1210 +f 683/683/5 732/732/1218 183/183/1210 +f 183/183/1210 732/732/1218 725/725/1219 +f 686/686/5 177/177/1206 729/729/1214 +f 686/686/5 729/729/1214 683/683/5 +f 695/695/1220 690/690/1211 720/720/1221 +f 720/720/1221 690/690/1211 175/175/1204 +f 720/720/1221 175/175/1204 173/173/1222 +f 720/720/1221 173/173/1222 730/730/1215 +f 730/730/1215 173/173/1222 171/171/1216 +f 698/698/1223 700/700/1208 183/183/1210 +f 698/698/1223 183/183/1210 725/725/1219 +f 190/190/5 731/731/5 733/733/5 +f 190/190/5 733/733/5 192/192/5 +f 733/733/5 734/734/5 192/192/5 +f 723/723/1224 734/734/1225 733/733/1226 +f 723/723/1227 733/733/1227 722/722/1227 +f 722/722/1228 733/733/1228 731/731/1228 +f 722/722/1229 731/731/1230 696/696/1231 +f 722/722/1229 696/696/1231 668/668/1232 +f 668/668/1232 696/696/1231 698/698/1233 +f 668/668/1232 698/698/1233 727/727/1234 +f 727/727/1201 698/698/1235 725/725/1199 +f 725/725/1219 732/732/1218 656/656/1236 +f 656/656/1237 732/732/1238 683/683/1239 +f 656/656/1237 683/683/1239 721/721/1240 +f 721/721/1241 683/683/1241 729/729/1241 +f 721/721/1242 729/729/1242 728/728/1242 +f 728/728/1243 729/729/1243 726/726/1243 +f 726/726/1244 695/695/1245 665/665/1246 +f 665/665/1246 695/695/1245 720/720/1247 +f 720/720/1248 730/730/1248 724/724/1248 +f 724/724/1249 730/730/1250 637/637/1251 +f 724/724/1249 637/637/1251 638/638/1252 +f 735/735/573 736/736/1253 94/94/1254 +f 83/83/573 85/85/1255 737/737/573 +f 737/737/573 738/738/573 83/83/573 +f 737/737/573 85/85/1255 739/739/573 +f 83/83/573 738/738/573 81/81/573 +f 81/81/573 738/738/573 79/79/573 +f 735/735/573 94/94/1254 96/96/573 +f 79/79/1256 738/738/1256 740/740/1256 +f 740/740/1257 738/738/1257 739/739/1257 +f 94/94/1254 736/736/1253 92/92/1258 +f 92/92/1258 736/736/1253 90/90/1259 +f 741/741/573 735/735/573 742/742/573 +f 742/742/573 735/735/573 96/96/573 +f 742/742/573 97/97/573 743/743/573 +f 90/90/1259 744/744/573 87/87/573 +f 79/79/1260 740/740/1261 745/745/1262 +f 79/79/1260 745/745/1262 77/77/1263 +f 87/87/573 744/744/573 746/746/573 +f 742/742/573 96/96/573 97/97/573 +f 744/744/573 90/90/1259 747/747/573 +f 747/747/573 90/90/1259 748/748/573 +f 739/739/573 85/85/1255 749/749/1264 +f 745/745/1262 633/633/1265 77/77/1263 +f 736/736/1253 748/748/573 90/90/1259 +f 85/85/1266 750/750/1267 751/751/1268 +f 87/87/573 746/746/573 85/85/573 +f 85/85/573 746/746/573 750/750/573 +f 85/85/1255 751/751/1269 749/749/1264 +f 58/58/22 752/752/1270 60/60/1271 +f 60/60/1271 752/752/1270 753/753/1272 +f 60/60/1271 753/753/1272 61/61/1273 +f 754/754/5 755/755/5 70/70/5 +f 63/63/5 756/756/5 65/65/5 +f 754/754/5 70/70/5 68/68/5 +f 58/58/22 757/757/1274 752/752/1270 +f 70/70/5 755/755/5 72/72/1275 +f 65/65/5 756/756/5 758/758/5 +f 61/61/1273 759/759/1276 63/63/5 +f 63/63/5 759/759/1276 756/756/5 +f 760/760/1277 61/61/1273 753/753/1272 +f 761/761/1278 54/54/1279 633/633/1280 +f 65/65/5 758/758/5 68/68/5 +f 758/758/5 762/762/5 763/763/5 +f 758/758/5 763/763/5 68/68/5 +f 760/760/1277 751/751/1281 61/61/1273 +f 61/61/1273 751/751/1281 759/759/1276 +f 72/72/1275 755/755/5 764/764/1282 +f 764/764/1282 755/755/5 765/765/5 +f 757/757/1274 58/58/22 740/740/1283 +f 740/740/1283 58/58/22 56/56/21 +f 740/740/1283 56/56/21 761/761/1278 +f 761/761/1278 56/56/21 54/54/1279 +f 754/754/5 68/68/5 763/763/5 +f 72/72/1275 764/764/1282 74/74/1284 +f 74/74/1284 764/764/1282 766/766/1285 +f 74/74/1284 766/766/1285 75/75/1286 +f 743/743/1287 766/766/1288 742/742/1289 +f 742/742/1289 766/766/1288 764/764/1290 +f 757/757/1291 740/740/1292 739/739/1293 +f 757/757/1291 739/739/1293 753/753/1294 +f 753/753/1294 739/739/1293 749/749/1295 +f 753/753/1296 749/749/1296 760/760/1296 +f 760/760/1297 749/749/1297 751/751/1297 +f 751/751/1268 750/750/1267 759/759/1298 +f 759/759/1299 750/750/1300 762/762/1301 +f 762/762/1302 750/750/1302 747/747/1302 +f 762/762/1303 747/747/1303 763/763/1303 +f 763/763/1304 747/747/1304 748/748/1304 +f 763/763/1305 748/748/1306 736/736/1307 +f 763/763/1305 736/736/1307 754/754/1308 +f 754/754/1309 736/736/1310 741/741/1311 +f 754/754/1309 741/741/1311 765/765/1312 +f 765/765/1312 741/741/1311 742/742/1313 +f 765/765/1312 742/742/1313 764/764/1314 +f 740/740/1315 761/761/1316 745/745/1317 +f 745/745/1317 761/761/1316 633/633/1318 +f 128/128/573 649/649/1319 647/647/573 +f 128/128/573 130/130/1320 649/649/1319 +f 128/128/573 647/647/573 125/125/1321 +f 125/125/1321 647/647/573 645/645/573 +f 142/142/573 651/651/573 140/140/573 +f 651/651/573 142/142/573 143/143/573 +f 125/125/1321 645/645/573 767/767/573 +f 140/140/573 654/654/573 138/138/573 +f 138/138/573 654/654/573 137/137/573 +f 652/652/573 651/651/573 143/143/573 +f 652/652/573 143/143/573 768/768/573 +f 768/768/573 145/145/573 769/769/573 +f 135/135/573 643/643/573 132/132/573 +f 125/125/1321 767/767/573 770/770/1322 +f 125/125/1321 770/770/1322 124/124/1323 +f 124/124/1323 770/770/1322 122/122/1324 +f 640/640/573 643/643/573 771/771/573 +f 132/132/573 643/643/573 642/642/573 +f 768/768/573 143/143/573 145/145/573 +f 643/643/573 135/135/573 137/137/573 +f 771/771/573 643/643/573 137/137/573 +f 649/649/1319 130/130/1320 772/772/1325 +f 770/770/1322 636/636/573 122/122/1324 +f 137/137/573 773/773/573 771/771/573 +f 640/640/1326 774/774/1326 130/130/1326 +f 130/130/1320 775/775/1327 772/772/1325 +f 132/132/573 642/642/573 640/640/573 +f 132/132/573 640/640/573 130/130/573 +f 774/774/1328 775/775/1327 130/130/1320 +f 773/773/573 137/137/573 654/654/573 +f 773/773/573 654/654/573 652/652/573 +f 104/104/1329 776/776/1330 106/106/1331 +f 106/106/1331 776/776/1330 107/107/1332 +f 776/776/1330 104/104/1329 777/777/5 +f 778/778/1333 115/115/1334 114/114/1335 +f 778/778/1333 114/114/1335 779/779/1336 +f 779/779/1336 114/114/1335 112/112/1337 +f 778/778/1333 780/780/5 115/115/1334 +f 115/115/1334 780/780/5 118/118/5 +f 109/109/1338 781/781/1339 782/782/1340 +f 109/109/1338 782/782/1340 111/111/1341 +f 111/111/1341 782/782/1340 783/783/1342 +f 107/107/1332 781/781/1339 109/109/1338 +f 772/772/1343 107/107/1332 776/776/1330 +f 772/772/1344 776/776/1344 784/784/1344 +f 772/772/1343 775/775/1345 107/107/1332 +f 779/779/5 785/785/5 118/118/5 +f 111/111/1341 783/783/1342 112/112/1337 +f 112/112/1337 786/786/5 787/787/5 +f 112/112/1337 783/783/1342 786/786/5 +f 107/107/1332 775/775/1345 774/774/1346 +f 118/118/5 780/780/5 779/779/5 +f 781/781/1339 107/107/1332 774/774/1346 +f 781/781/1339 774/774/1346 788/788/1347 +f 784/784/5 777/777/5 104/104/1329 +f 784/784/5 104/104/1329 789/789/5 +f 789/789/5 104/104/1329 102/102/5 +f 789/789/5 102/102/5 635/635/5 +f 635/635/5 102/102/5 100/100/5 +f 787/787/5 779/779/1336 112/112/1337 +f 118/118/5 785/785/5 121/121/5 +f 785/785/5 790/790/5 121/121/5 +f 769/769/1348 790/790/1349 785/785/1350 +f 769/769/1348 785/785/1350 768/768/1351 +f 768/768/1352 785/785/1353 779/779/1354 +f 768/768/1352 779/779/1354 652/652/1355 +f 652/652/1355 779/779/1354 787/787/1356 +f 652/652/1355 787/787/1356 773/773/1357 +f 773/773/1358 787/787/1358 786/786/1358 +f 773/773/1359 786/786/1359 771/771/1359 +f 771/771/1360 786/786/1360 783/783/1360 +f 771/771/1361 783/783/1361 788/788/1361 +f 771/771/1362 788/788/1363 640/640/1364 +f 640/640/1364 788/788/1363 774/774/1365 +f 772/772/1366 784/784/1367 649/649/1368 +f 649/649/1368 784/784/1367 645/645/1369 +f 645/645/1369 784/784/1367 767/767/1370 +f 767/767/1370 784/784/1367 789/789/1371 +f 767/767/1372 789/789/1372 770/770/1372 +f 770/770/1373 789/789/1373 635/635/1373 +f 770/770/1374 635/635/1001 636/636/1007 +f 791/791/1375 741/741/1375 792/792/1375 +f 792/792/1376 741/741/1311 736/736/1310 +f 792/792/1377 736/736/1377 793/793/1377 +f 793/793/1378 736/736/1378 735/735/1378 +f 793/793/1379 735/735/1379 791/791/1379 +f 791/791/1380 735/735/1380 741/741/1380 +f 105/105/1381 794/794/1382 795/795/573 +f 105/105/1381 106/106/1383 794/794/1382 +f 794/794/1382 106/106/1383 108/108/1384 +f 105/105/1381 795/795/573 103/103/1385 +f 103/103/1385 795/795/573 796/796/1386 +f 796/796/1386 797/797/1387 103/103/1385 +f 117/117/573 798/798/573 116/116/573 +f 798/798/573 117/117/573 119/119/573 +f 116/116/1388 799/799/1389 114/114/1390 +f 114/114/1390 799/799/1389 113/113/1391 +f 800/800/573 798/798/573 119/119/573 +f 800/800/573 119/119/573 801/801/573 +f 802/802/573 120/120/573 803/803/573 +f 801/801/573 119/119/573 802/802/573 +f 111/111/1392 804/804/1393 110/110/1394 +f 110/110/1394 804/804/1393 805/805/573 +f 110/110/1394 805/805/573 108/108/1384 +f 103/103/1385 797/797/1387 806/806/1395 +f 103/103/1385 806/806/1395 101/101/573 +f 101/101/573 806/806/1395 99/99/1396 +f 802/802/573 119/119/573 120/120/573 +f 804/804/1393 111/111/1392 807/807/1397 +f 807/807/1397 111/111/1392 113/113/1391 +f 807/807/1397 113/113/1391 808/808/1398 +f 806/806/1395 634/634/1265 99/99/1396 +f 113/113/1391 809/809/1399 808/808/1398 +f 108/108/1384 805/805/573 810/810/573 +f 108/108/1384 810/810/573 794/794/1382 +f 809/809/1399 113/113/1391 799/799/1389 +f 809/809/1399 799/799/1389 800/800/573 +f 84/84/5 811/811/5 86/86/5 +f 812/812/1400 811/811/5 84/84/5 +f 793/793/1401 93/93/1402 92/92/1403 +f 793/793/1401 92/92/1403 792/792/1404 +f 792/792/1404 92/92/1403 91/91/1405 +f 82/82/1406 812/812/1400 84/84/5 +f 793/793/1401 791/791/5 93/93/1402 +f 93/93/1402 791/791/5 95/95/5 +f 88/88/5 813/813/5 814/814/5 +f 88/88/5 814/814/5 89/89/5 +f 89/89/5 814/814/5 815/815/5 +f 86/86/5 813/813/5 88/88/5 +f 811/811/5 816/816/5 86/86/5 +f 817/817/1407 78/78/1408 634/634/1409 +f 792/792/5 818/818/5 95/95/5 +f 89/89/5 815/815/5 91/91/1405 +f 91/91/1405 808/808/1410 819/819/1411 +f 815/815/5 820/820/1412 91/91/1405 +f 91/91/1405 820/820/1412 808/808/1410 +f 95/95/5 791/791/5 792/792/5 +f 813/813/5 86/86/5 816/816/5 +f 813/813/5 816/816/5 820/820/5 +f 821/821/1413 812/812/1400 797/797/1414 +f 797/797/1414 812/812/1400 82/82/1406 +f 797/797/1414 82/82/1406 80/80/1415 +f 797/797/1414 80/80/1415 817/817/1407 +f 817/817/1407 80/80/1415 78/78/1408 +f 819/819/1411 792/792/1404 91/91/1405 +f 95/95/5 818/818/5 98/98/5 +f 818/818/5 822/822/5 98/98/5 +f 803/803/1416 823/823/1417 822/822/1418 +f 803/803/1416 822/822/1418 802/802/1419 +f 802/802/1420 822/822/1420 818/818/1420 +f 802/802/1421 818/818/1421 801/801/1421 +f 801/801/1422 818/818/1423 792/792/1424 +f 801/801/1422 792/792/1424 800/800/1425 +f 800/800/1425 792/792/1424 819/819/1426 +f 800/800/1425 819/819/1426 809/809/1427 +f 809/809/1428 819/819/1428 808/808/1428 +f 808/808/1429 820/820/1430 807/807/1431 +f 807/807/1431 820/820/1430 805/805/1432 +f 805/805/1433 820/820/1433 816/816/1433 +f 805/805/1434 816/816/1434 810/810/1434 +f 810/810/1435 816/816/1435 811/811/1435 +f 810/810/1436 811/811/1436 794/794/1436 +f 794/794/1437 811/811/1438 821/821/1439 +f 794/794/1440 821/821/1441 796/796/1442 +f 796/796/1442 821/821/1441 797/797/1443 +f 797/797/1444 817/817/1444 806/806/1444 +f 806/806/1445 817/817/1445 634/634/1445 +f 755/755/1446 824/824/1447 765/765/1448 +f 765/765/1448 824/824/1447 825/825/1449 +f 765/765/1450 825/825/1451 826/826/1452 +f 765/765/1312 826/826/1453 754/754/1309 +f 754/754/1454 826/826/1454 827/827/1454 +f 754/754/1455 827/827/1455 755/755/1455 +f 755/755/1456 827/827/1456 824/824/1456 +f 71/71/573 824/824/573 827/827/573 +f 824/824/573 828/828/1457 825/825/573 +f 59/59/1458 60/60/1459 829/829/1460 +f 829/829/1460 60/60/1459 62/62/1461 +f 59/59/1458 829/829/1460 830/830/573 +f 59/59/1458 830/830/573 57/57/1462 +f 57/57/1462 830/830/573 831/831/1463 +f 831/831/1463 832/832/1464 57/57/1462 +f 824/824/573 71/71/573 73/73/1465 +f 71/71/573 827/827/573 69/69/573 +f 69/69/573 827/827/573 826/826/573 +f 69/69/573 826/826/573 67/67/573 +f 828/828/1457 824/824/573 73/73/1465 +f 828/828/1457 76/76/1466 833/833/573 +f 57/57/1462 832/832/1464 834/834/1467 +f 57/57/1462 834/834/1467 55/55/573 +f 55/55/573 834/834/1467 53/53/1468 +f 835/835/1469 836/836/1470 837/837/1471 +f 836/836/1470 838/838/573 66/66/573 +f 66/66/573 838/838/573 64/64/573 +f 73/73/1465 74/74/1472 828/828/1457 +f 828/828/1457 74/74/1472 76/76/1466 +f 836/836/1470 66/66/573 67/67/1473 +f 837/837/1471 836/836/1470 67/67/1473 +f 639/639/1474 53/53/1468 834/834/1467 +f 67/67/1473 839/839/1475 837/837/1471 +f 835/835/1476 840/840/1477 62/62/1478 +f 62/62/1479 841/841/1480 829/829/1481 +f 64/64/573 838/838/573 835/835/1476 +f 64/64/573 835/835/1476 62/62/1478 +f 62/62/1478 840/840/1477 841/841/1482 +f 839/839/1483 67/67/1484 826/826/1485 +f 154/154/5 663/663/5 156/156/5 +f 663/663/5 152/152/1486 661/661/5 +f 671/671/1487 164/164/1488 163/163/1489 +f 671/671/1487 163/163/1489 669/669/1490 +f 669/669/1490 163/163/1489 161/161/1491 +f 152/152/1486 663/663/5 154/154/5 +f 671/671/1487 667/667/5 164/164/1488 +f 164/164/1488 667/667/5 166/166/5 +f 158/158/1492 658/658/1493 659/659/1494 +f 158/158/1492 659/659/1494 160/160/1495 +f 156/156/1496 658/658/1493 158/158/1492 +f 841/841/1497 156/156/1497 666/666/1497 +f 666/666/5 156/156/5 663/663/5 +f 156/156/1496 841/841/1498 840/840/1499 +f 842/842/1500 148/148/1501 639/639/1502 +f 669/669/5 843/843/5 166/166/5 +f 160/160/1495 659/659/1494 161/161/1503 +f 161/161/1503 659/659/1494 655/655/1504 +f 161/161/1503 837/837/1505 839/839/1506 +f 655/655/1504 837/837/1505 161/161/1503 +f 166/166/5 667/667/5 669/669/5 +f 658/658/1493 156/156/1496 840/840/1499 +f 658/658/1493 840/840/1499 655/655/1507 +f 666/666/1508 661/661/5 152/152/1486 +f 666/666/1508 152/152/1486 832/832/1509 +f 832/832/1509 152/152/1486 150/150/1510 +f 832/832/1509 150/150/1510 842/842/1500 +f 842/842/1500 150/150/1510 148/148/1501 +f 669/669/1490 161/161/1491 839/839/1511 +f 166/166/5 843/843/5 169/169/5 +f 843/843/5 844/844/5 169/169/5 +f 833/833/1512 844/844/1513 843/843/1514 +f 833/833/1515 843/843/1515 828/828/1515 +f 828/828/1516 843/843/1517 669/669/1518 +f 828/828/1516 669/669/1518 825/825/1451 +f 825/825/1451 669/669/1518 826/826/1452 +f 826/826/1485 669/669/1519 839/839/1483 +f 837/837/1520 655/655/1520 835/835/1520 +f 835/835/1521 655/655/1521 840/840/1521 +f 841/841/1480 666/666/1522 829/829/1481 +f 829/829/1481 666/666/1522 831/831/1523 +f 831/831/1523 666/666/1522 832/832/1524 +f 832/832/1525 842/842/1525 834/834/1525 +f 834/834/1526 842/842/1526 639/639/1526 +f 777/777/1527 796/796/1527 795/795/1527 +f 777/777/1528 795/795/1528 776/776/1528 +f 776/776/1529 795/795/1529 794/794/1529 +f 776/776/1530 794/794/1530 784/784/1530 +f 784/784/1531 794/794/1531 796/796/1531 +f 784/784/1532 796/796/1532 777/777/1532 +f 812/812/1533 738/738/1533 737/737/1533 +f 812/812/1534 737/737/1534 811/811/1534 +f 811/811/1535 737/737/1535 739/739/1535 +f 811/811/1438 739/739/1536 821/821/1439 +f 821/821/1537 739/739/1537 812/812/1537 +f 812/812/1538 739/739/1538 738/738/1538 +f 757/757/1539 831/831/1539 830/830/1539 +f 757/757/1540 830/830/1540 752/752/1540 +f 752/752/1541 830/830/1541 829/829/1541 +f 752/752/1542 829/829/1542 753/753/1542 +f 753/753/1294 829/829/1481 757/757/1291 +f 757/757/1291 829/829/1481 831/831/1523 +f 788/788/1543 807/807/1431 805/805/1432 +f 788/788/1544 805/805/1544 781/781/1544 +f 781/781/1545 805/805/1546 782/782/1547 +f 782/782/1547 805/805/1546 804/804/1548 +f 782/782/1549 804/804/1549 783/783/1549 +f 783/783/1550 804/804/1550 807/807/1550 +f 783/783/1551 807/807/1551 788/788/1551 +f 820/820/1552 750/750/1552 813/813/1552 +f 813/813/1553 750/750/1553 746/746/1553 +f 813/813/1554 746/746/1554 814/814/1554 +f 814/814/1555 746/746/1555 744/744/1555 +f 814/814/1556 744/744/1556 815/815/1556 +f 815/815/1557 744/744/1557 747/747/1557 +f 815/815/1558 747/747/1558 820/820/1558 +f 820/820/1559 747/747/1559 750/750/1559 +f 762/762/1301 835/835/1560 759/759/1299 +f 759/759/1561 835/835/1562 756/756/1563 +f 756/756/1563 835/835/1562 838/838/1564 +f 756/756/1565 838/838/1566 758/758/1567 +f 758/758/1567 838/838/1566 836/836/1568 +f 758/758/1569 836/836/1569 762/762/1569 +f 762/762/1570 836/836/1570 835/835/1570 +f 780/780/1571 798/798/1572 779/779/1573 +f 779/779/1573 798/798/1572 800/800/1574 +f 779/779/1575 800/800/1575 799/799/1575 +f 779/779/1576 799/799/1576 778/778/1576 +f 778/778/1577 799/799/1577 116/116/1577 +f 778/778/1578 116/116/1578 780/780/1578 +f 780/780/1579 116/116/1579 798/798/1579 +f 845/845/1580 8/8/1581 221/221/1582 +f 221/221/1582 8/8/1581 50/50/1583 +f 705/705/1584 5/5/1585 7/7/1586 +f 705/705/1584 7/7/1586 846/846/1587 +f 846/846/1587 7/7/1586 8/8/1588 +f 846/846/1589 8/8/1590 845/845/1591 +f 847/847/1592 848/848/1592 845/845/1592 +f 845/845/1593 848/848/1593 849/849/1593 +f 845/845/1591 849/849/1594 846/846/1589 +f 846/846/1589 849/849/1594 850/850/1595 +f 846/846/1596 850/850/1597 851/851/1598 +f 851/851/1598 850/850/1597 852/852/1599 +f 851/851/1600 852/852/1600 853/853/1600 +f 851/851/1601 853/853/1601 847/847/1601 +f 847/847/1602 853/853/1602 848/848/1602 +f 849/849/1603 848/848/1604 850/850/1605 +f 852/852/1606 850/850/1605 853/853/1607 +f 850/850/1605 848/848/1604 853/853/1607 +f 50/50/1608 844/844/1513 833/833/1512 +f 803/803/1416 217/217/1609 823/823/1417 +f 823/823/1417 217/217/1609 50/50/1608 +f 145/145/1610 146/146/1611 769/769/1612 +f 769/769/1612 146/146/1611 217/217/1613 +f 769/769/1614 217/217/1614 790/790/1614 +f 790/790/1615 217/217/1616 803/803/1617 +f 790/790/1615 803/803/1617 121/121/1618 +f 121/121/1618 803/803/1617 120/120/1619 +f 97/97/1620 98/98/1621 743/743/1622 +f 743/743/1622 98/98/1621 822/822/1623 +f 743/743/1287 822/822/1418 823/823/1417 +f 743/743/1287 823/823/1417 50/50/1608 +f 743/743/1287 50/50/1608 766/766/1288 +f 766/766/1288 50/50/1608 833/833/1512 +f 766/766/1624 833/833/1625 75/75/1626 +f 75/75/1626 833/833/1625 76/76/1627 +f 168/168/1628 169/169/1629 723/723/1630 +f 723/723/1630 169/169/1629 844/844/1631 +f 723/723/1224 844/844/1513 50/50/1608 +f 723/723/1224 50/50/1608 734/734/1225 +f 734/734/1225 50/50/1608 709/709/1153 +f 734/734/1632 709/709/1633 192/192/1634 +f 192/192/1634 709/709/1633 191/191/1635 +f 51/51/1636 704/704/1637 49/49/1638 +f 49/49/1638 704/704/1637 714/714/1639 +f 49/49/1640 714/714/1154 50/50/1608 +f 50/50/1608 714/714/1154 709/709/1153 +f 846/846/1641 851/851/1642 705/705/1643 +f 17/17/1644 39/39/1645 13/13/1646 +f 13/13/1647 39/39/1647 11/11/1647 +f 17/17/1644 18/18/1648 39/39/1645 +f 52/52/1649 459/459/1650 4/4/1651 +f 4/4/1651 459/459/1650 3/3/1652 +f 854/854/1653 855/855/1654 856/856/1655 +f 857/857/1656 858/858/1656 859/859/1656 +f 859/859/1657 855/855/1654 854/854/1653 +f 860/860/1658 861/861/1659 862/862/1660 +f 860/860/1661 863/863/1661 861/861/1661 +f 861/861/1662 863/863/1662 864/864/1662 +f 861/861/1663 864/864/1663 862/862/1663 +f 862/862/1664 864/864/1665 865/865/1666 +f 862/862/1664 865/865/1666 866/866/1667 +f 866/866/1668 865/865/1669 863/863/1670 +f 866/866/1668 863/863/1670 860/860/1671 +f 863/863/1672 867/867/1673 864/864/1674 +f 867/867/1675 868/868/1676 864/864/1677 +f 864/864/1678 868/868/1678 865/865/1678 +f 863/863/1672 869/869/1679 867/867/1673 +f 863/863/1680 865/865/1680 869/869/1680 +f 869/869/1681 858/858/1682 857/857/1683 +f 869/869/1681 857/857/1683 867/867/1684 +f 857/857/1685 854/854/1685 867/867/1685 +f 867/867/1675 854/854/1686 868/868/1676 +f 868/868/1676 854/854/1686 856/856/1687 +f 856/856/1688 855/855/1688 868/868/1688 +f 868/868/1689 855/855/1689 865/865/1689 +f 865/865/1690 855/855/1690 859/859/1690 +f 865/865/1691 859/859/1691 869/869/1691 +f 869/869/1692 859/859/1692 858/858/1692 +f 859/859/1693 854/854/1693 870/870/1693 +f 857/857/1694 859/859/1694 870/870/1694 +f 854/854/1695 857/857/1695 870/870/1695 +f 866/866/1696 860/860/1658 862/862/1660 +f 871/871/1697 872/872/1697 873/873/1697 +f 873/873/1698 874/874/1698 875/875/1698 +f 876/876/1699 877/877/1700 878/878/1701 +f 876/876/1702 879/879/1703 880/880/1704 +f 876/876/1702 880/880/1704 877/877/1705 +f 877/877/1706 880/880/1707 881/881/1708 +f 877/877/1706 881/881/1708 878/878/1709 +f 881/881/1710 882/882/1710 878/878/1710 +f 878/878/1711 882/882/1711 883/883/1711 +f 883/883/1712 882/882/1712 879/879/1712 +f 883/883/1713 879/879/1713 876/876/1713 +f 884/884/1714 882/882/1715 881/881/1716 +f 881/881/1716 880/880/1717 884/884/1714 +f 879/879/1718 885/885/1719 880/880/1720 +f 882/882/1721 886/886/1722 879/879/1718 +f 879/879/1718 886/886/1722 885/885/1719 +f 873/873/1723 872/872/1723 885/885/1723 +f 885/885/1724 872/872/1724 880/880/1724 +f 880/880/1725 872/872/1726 871/871/1727 +f 880/880/1725 871/871/1727 884/884/1728 +f 871/871/1729 875/875/1729 884/884/1729 +f 884/884/1730 875/875/1730 882/882/1730 +f 882/882/1731 875/875/1732 886/886/1733 +f 875/875/1732 874/874/1734 886/886/1733 +f 886/886/1735 874/874/1736 885/885/1737 +f 885/885/1737 874/874/1736 873/873/1738 +f 875/875/1739 871/871/1739 887/887/1739 +f 873/873/1740 875/875/1740 887/887/1740 +f 871/871/1741 873/873/1741 887/887/1741 +f 883/883/1742 876/876/1699 878/878/1701 +f 888/888/1743 889/889/1743 890/890/1743 +f 891/891/1744 892/892/1744 888/888/1744 +f 893/893/1745 894/894/1745 895/895/1745 +f 896/896/1746 897/897/1747 894/894/1748 +f 894/894/1748 897/897/1747 895/895/1749 +f 895/895/1750 897/897/1751 893/893/1752 +f 897/897/1751 898/898/1753 893/893/1752 +f 898/898/1754 899/899/1755 893/893/1756 +f 893/893/1756 899/899/1755 894/894/1757 +f 894/894/1757 899/899/1755 896/896/1758 +f 897/897/1759 900/900/1759 898/898/1759 +f 898/898/1760 901/901/1761 899/899/1762 +f 899/899/1762 901/901/1761 896/896/1763 +f 897/897/1764 902/902/1764 900/900/1764 +f 896/896/1765 902/902/1765 897/897/1765 +f 896/896/1766 890/890/1767 902/902/1768 +f 890/890/1767 889/889/1769 902/902/1768 +f 902/902/1770 889/889/1771 900/900/1772 +f 889/889/1771 888/888/1773 900/900/1772 +f 888/888/1774 892/892/1775 900/900/1776 +f 900/900/1776 892/892/1775 898/898/1777 +f 898/898/1778 892/892/1779 891/891/1780 +f 898/898/1778 891/891/1780 901/901/1781 +f 891/891/1782 890/890/1783 901/901/1784 +f 901/901/1784 890/890/1783 896/896/1785 +f 891/891/1786 888/888/1786 903/903/1786 +f 890/890/1787 891/891/1787 903/903/1787 +f 888/888/1788 890/890/1788 903/903/1788 +f 904/904/1789 905/905/1789 906/906/1789 +f 907/907/1790 906/906/1790 908/908/1790 +f 909/909/1791 910/910/1791 911/911/1791 +f 911/911/1792 912/912/1792 913/913/1792 +f 911/911/1793 913/913/1793 909/909/1793 +f 909/909/1794 913/913/1794 914/914/1794 +f 909/909/1795 914/914/1795 910/910/1795 +f 910/910/1796 914/914/1796 912/912/1796 +f 910/910/1797 912/912/1797 911/911/1797 +f 912/912/1798 915/915/1799 916/916/1800 +f 914/914/1801 915/915/1799 912/912/1798 +f 913/913/1802 917/917/1803 914/914/1801 +f 913/913/1802 918/918/1804 917/917/1803 +f 912/912/1805 916/916/1806 918/918/1807 +f 912/912/1805 918/918/1807 913/913/1808 +f 914/914/1801 917/917/1803 915/915/1799 +f 916/916/1809 908/908/1810 918/918/1811 +f 908/908/1810 906/906/1812 918/918/1811 +f 918/918/1813 906/906/1813 905/905/1813 +f 918/918/1814 905/905/1814 917/917/1814 +f 917/917/1815 905/905/1815 904/904/1815 +f 917/917/1816 904/904/1816 915/915/1816 +f 904/904/1817 907/907/1817 915/915/1817 +f 915/915/1818 907/907/1818 916/916/1818 +f 916/916/1819 907/907/1819 908/908/1819 +f 907/907/1820 904/904/1820 919/919/1820 +f 906/906/1821 907/907/1821 919/919/1821 +f 904/904/1822 906/906/1822 919/919/1822 +f 920/920/1823 921/921/1823 922/922/1823 +f 923/923/1824 924/924/1824 920/920/1824 +f 925/925/1825 926/926/1825 927/927/1825 +f 926/926/1826 928/928/1826 927/927/1826 +f 927/927/1827 928/928/1827 929/929/1827 +f 927/927/1828 929/929/1828 925/925/1828 +f 929/929/1829 930/930/1830 925/925/1831 +f 925/925/1832 930/930/1832 931/931/1832 +f 925/925/1833 931/931/1833 926/926/1833 +f 926/926/1834 931/931/1834 928/928/1834 +f 931/931/1835 932/932/1836 928/928/1837 +f 928/928/1837 932/932/1836 933/933/1838 +f 930/930/1839 934/934/1839 931/931/1839 +f 931/931/1840 934/934/1841 932/932/1842 +f 929/929/1829 933/933/1843 930/930/1830 +f 928/928/1837 933/933/1838 929/929/1844 +f 932/932/1845 924/924/1846 933/933/1847 +f 933/933/1847 924/924/1846 923/923/1848 +f 933/933/1849 923/923/1849 922/922/1849 +f 933/933/1843 922/922/1850 930/930/1830 +f 930/930/1830 922/922/1850 921/921/1851 +f 930/930/1852 921/921/1853 934/934/1854 +f 921/921/1853 920/920/1855 934/934/1854 +f 934/934/1841 920/920/1856 932/932/1842 +f 920/920/1856 924/924/1857 932/932/1842 +f 920/920/1858 922/922/1858 935/935/1858 +f 923/923/1859 920/920/1859 935/935/1859 +f 922/922/1860 923/923/1860 935/935/1860 +f 936/936/1861 937/937/1861 938/938/1861 +f 939/939/1862 940/940/1862 941/941/1862 +f 939/939/1863 942/942/1864 940/940/1865 +f 940/940/1866 942/942/1867 943/943/1868 +f 940/940/1866 943/943/1868 941/941/1869 +f 941/941/1870 943/943/1870 944/944/1870 +f 941/941/1871 944/944/1871 939/939/1871 +f 939/939/1863 944/944/1872 942/942/1864 +f 942/942/1873 945/945/1874 943/943/1875 +f 943/943/1875 945/945/1874 946/946/1876 +f 943/943/1875 946/946/1876 944/944/1877 +f 944/944/1877 946/946/1876 947/947/1878 +f 942/942/1879 948/948/1879 945/945/1879 +f 944/944/1877 948/948/1880 942/942/1881 +f 944/944/1877 947/947/1878 948/948/1880 +f 948/948/1882 938/938/1883 937/937/1884 +f 948/948/1882 937/937/1884 945/945/1885 +f 945/945/1886 937/937/1886 936/936/1886 +f 945/945/1887 936/936/1887 946/946/1887 +f 946/946/1888 936/936/1888 949/949/1888 +f 949/949/1889 950/950/1890 946/946/1891 +f 946/946/1891 950/950/1890 947/947/1892 +f 947/947/1893 950/950/1894 938/938/1895 +f 947/947/1893 938/938/1895 948/948/1896 +f 949/949/1897 936/936/1897 951/951/1897 +f 950/950/1898 949/949/1898 951/951/1898 +f 938/938/1899 950/950/1899 951/951/1899 +f 936/936/1900 938/938/1900 951/951/1900 +f 952/952/1901 953/953/1901 954/954/1901 +f 955/955/1902 956/956/1902 957/957/1902 +f 957/957/1903 958/958/1903 955/955/1903 +f 958/958/1904 959/959/1904 955/955/1904 +f 959/959/1905 960/960/1906 955/955/1907 +f 955/955/1907 960/960/1906 956/956/1908 +f 956/956/1909 960/960/1910 961/961/1911 +f 956/956/1909 961/961/1911 957/957/1912 +f 957/957/1913 961/961/1913 958/958/1913 +f 958/958/1914 962/962/1915 963/963/1916 +f 958/958/1914 963/963/1916 959/959/1917 +f 961/961/1918 962/962/1915 958/958/1914 +f 959/959/1917 964/964/1919 960/960/1920 +f 959/959/1917 963/963/1916 964/964/1919 +f 961/961/1918 965/965/1921 962/962/1915 +f 960/960/1922 965/965/1921 961/961/1918 +f 960/960/1923 964/964/1923 965/965/1923 +f 966/966/1924 967/967/1924 962/962/1924 +f 962/962/1925 967/967/1925 963/963/1925 +f 963/963/1926 967/967/1926 954/954/1926 +f 963/963/1927 954/954/1928 964/964/1929 +f 964/964/1929 954/954/1928 953/953/1930 +f 964/964/1931 953/953/1932 952/952/1933 +f 964/964/1931 952/952/1933 965/965/1934 +f 965/965/1935 952/952/1935 966/966/1935 +f 965/965/1936 966/966/1936 962/962/1936 +f 952/952/1937 954/954/1937 968/968/1937 +f 966/966/1938 952/952/1938 968/968/1938 +f 967/967/1939 966/966/1939 968/968/1939 +f 954/954/1940 967/967/1940 968/968/1940 +f 969/969/1941 970/970/1941 971/971/1941 +f 972/972/1942 973/973/1942 974/974/1942 +f 974/974/1943 975/975/1944 972/972/1945 +f 975/975/1944 976/976/1946 972/972/1945 +f 976/976/1947 977/977/1948 972/972/1949 +f 972/972/1949 977/977/1948 973/973/1950 +f 973/973/1951 977/977/1952 974/974/1953 +f 977/977/1952 975/975/1954 974/974/1953 +f 975/975/1955 978/978/1955 979/979/1955 +f 975/975/1956 979/979/1957 976/976/1958 +f 976/976/1958 979/979/1957 980/980/1959 +f 977/977/1960 978/978/1960 975/975/1960 +f 977/977/1961 981/981/1961 978/978/1961 +f 980/980/1959 981/981/1962 976/976/1958 +f 976/976/1958 981/981/1962 977/977/1963 +f 969/969/1964 982/982/1964 979/979/1964 +f 979/979/1965 982/982/1965 980/980/1965 +f 982/982/1966 971/971/1966 980/980/1966 +f 980/980/1967 971/971/1967 981/981/1967 +f 981/981/1968 971/971/1968 970/970/1968 +f 981/981/1969 970/970/1969 978/978/1969 +f 970/970/1970 969/969/1970 978/978/1970 +f 978/978/1971 969/969/1971 979/979/1971 +f 969/969/1972 971/971/1972 983/983/1972 +f 982/982/1973 969/969/1973 983/983/1973 +f 971/971/1974 982/982/1974 983/983/1974 +f 984/984/1975 985/985/1975 986/986/1975 +f 987/987/1976 988/988/1976 984/984/1976 +f 989/989/1977 990/990/1978 991/991/1979 +f 992/992/1980 993/993/1980 990/990/1980 +f 990/990/1981 993/993/1981 991/991/1981 +f 991/991/1982 993/993/1983 994/994/1984 +f 991/991/1982 994/994/1984 989/989/1985 +f 989/989/1986 994/994/1987 995/995/1988 +f 995/995/1988 994/994/1987 992/992/1989 +f 995/995/1990 992/992/1990 990/990/1990 +f 992/992/1991 996/996/1992 993/993/1993 +f 993/993/1993 996/996/1992 997/997/1994 +f 993/993/1993 998/998/1995 999/999/1996 +f 993/993/1993 999/999/1996 994/994/1997 +f 994/994/1997 1000/1000/1998 992/992/1991 +f 992/992/1991 1000/1000/1998 996/996/1992 +f 994/994/1997 999/999/1996 1000/1000/1998 +f 993/993/1993 997/997/1994 998/998/1995 +f 984/984/1999 997/997/1999 996/996/1999 +f 997/997/2000 984/984/2000 988/988/2000 +f 997/997/2001 988/988/2001 998/998/2001 +f 998/998/2002 988/988/2002 987/987/2002 +f 998/998/2003 987/987/2003 999/999/2003 +f 999/999/2004 987/987/2004 986/986/2004 +f 999/999/2005 986/986/2005 1000/1000/2005 +f 1000/1000/2006 986/986/2006 985/985/2006 +f 1000/1000/2007 985/985/2007 996/996/2007 +f 996/996/2008 985/985/2008 984/984/2008 +f 986/986/2009 987/987/2010 1001/1001/2011 +f 1001/1001/2011 987/987/2010 1002/1002/2012 +f 984/984/2013 986/986/2013 1002/1002/2013 +f 1002/1002/2014 986/986/2014 1001/1001/2014 +f 987/987/2015 984/984/2015 1002/1002/2015 +f 995/995/2016 990/990/1978 989/989/1977 +f 1003/1003/2017 1004/1004/2017 1005/1005/2017 +f 1006/1006/2018 1007/1007/2018 1008/1008/2018 +f 1006/1006/2019 1009/1009/2020 1007/1007/2021 +f 1007/1007/2022 1009/1009/2023 1008/1008/2024 +f 1008/1008/2024 1009/1009/2023 1010/1010/2025 +f 1008/1008/2026 1010/1010/2026 1011/1011/2026 +f 1008/1008/2027 1011/1011/2028 1006/1006/2029 +f 1006/1006/2029 1011/1011/2028 1012/1012/2030 +f 1006/1006/2019 1012/1012/2031 1009/1009/2020 +f 1012/1012/2032 1013/1013/2033 1014/1014/2034 +f 1012/1012/2032 1014/1014/2034 1009/1009/2035 +f 1010/1010/2036 1015/1015/2037 1011/1011/2038 +f 1011/1011/2038 1015/1015/2037 1016/1016/2039 +f 1009/1009/2035 1015/1015/2037 1010/1010/2036 +f 1009/1009/2035 1017/1017/2040 1015/1015/2037 +f 1014/1014/2034 1017/1017/2040 1009/1009/2035 +f 1011/1011/2038 1016/1016/2039 1012/1012/2032 +f 1012/1012/2032 1016/1016/2039 1013/1013/2033 +f 1014/1014/2041 1005/1005/2042 1004/1004/2043 +f 1014/1014/2041 1004/1004/2043 1017/1017/2044 +f 1017/1017/2045 1004/1004/2046 1015/1015/2047 +f 1015/1015/2047 1004/1004/2046 1003/1003/2048 +f 1003/1003/2049 1018/1018/2050 1015/1015/2051 +f 1015/1015/2051 1018/1018/2050 1016/1016/2052 +f 1016/1016/2053 1018/1018/2054 1013/1013/2055 +f 1013/1013/2055 1018/1018/2054 1019/1019/2056 +f 1013/1013/2057 1019/1019/2058 1014/1014/2059 +f 1019/1019/2058 1005/1005/2060 1014/1014/2059 +f 1018/1018/2061 1003/1003/2061 1020/1020/2061 +f 1020/1020/2062 1003/1003/2062 1021/1021/2062 +f 1019/1019/2063 1018/1018/2063 1020/1020/2063 +f 1021/1021/2064 1019/1019/2065 1020/1020/2066 +f 1005/1005/2067 1019/1019/2065 1021/1021/2064 +f 1003/1003/2068 1005/1005/2068 1021/1021/2068 +f 1022/1022/2069 1023/1023/2069 1024/1024/2069 +f 1024/1024/2070 1025/1025/2070 1026/1026/2070 +f 1027/1027/2071 1028/1028/2072 1029/1029/2073 +f 1029/1029/2073 1030/1030/2074 1027/1027/2071 +f 1029/1029/2075 1031/1031/2076 1030/1030/2077 +f 1031/1031/2076 1032/1032/2078 1030/1030/2077 +f 1030/1030/2079 1032/1032/2080 1033/1033/2081 +f 1030/1030/2079 1033/1033/2081 1027/1027/2082 +f 1027/1027/2083 1033/1033/2084 1028/1028/2085 +f 1033/1033/2084 1034/1034/2086 1028/1028/2085 +f 1034/1034/2087 1031/1031/2088 1028/1028/2089 +f 1028/1028/2089 1031/1031/2088 1029/1029/2090 +f 1033/1033/2091 1035/1035/2092 1036/1036/2093 +f 1033/1033/2091 1036/1036/2093 1034/1034/2094 +f 1032/1032/2095 1035/1035/2092 1033/1033/2091 +f 1031/1031/2096 1037/1037/2097 1032/1032/2098 +f 1034/1034/2094 1038/1038/2099 1031/1031/2096 +f 1031/1031/2096 1038/1038/2099 1037/1037/2097 +f 1037/1037/2100 1035/1035/2100 1032/1032/2100 +f 1034/1034/2094 1036/1036/2093 1038/1038/2099 +f 1037/1037/2101 1024/1024/2101 1023/1023/2101 +f 1037/1037/2102 1023/1023/2103 1035/1035/2104 +f 1035/1035/2104 1023/1023/2103 1022/1022/2105 +f 1035/1035/2106 1022/1022/2107 1036/1036/2108 +f 1036/1036/2108 1022/1022/2107 1026/1026/2109 +f 1036/1036/2110 1026/1026/2111 1025/1025/2112 +f 1036/1036/2110 1025/1025/2112 1038/1038/2113 +f 1025/1025/2114 1024/1024/2114 1038/1038/2114 +f 1038/1038/2115 1024/1024/2115 1037/1037/2115 +f 1026/1026/2116 1022/1022/2116 1039/1039/2116 +f 1024/1024/2117 1026/1026/2117 1039/1039/2117 +f 1040/1040/2118 1024/1024/2118 1039/1039/2118 +f 1022/1022/2119 1024/1024/2119 1040/1040/2119 +f 1039/1039/2120 1022/1022/2120 1040/1040/2120 +f 1041/1041/2121 1042/1042/2121 1043/1043/2121 +f 1042/1042/2122 1044/1044/2122 1045/1045/2122 +f 1046/1046/2123 1047/1047/2124 1048/1048/2125 +f 1049/1049/2126 1050/1050/2127 1051/1051/2128 +f 1051/1051/2128 1050/1050/2127 1047/1047/2129 +f 1050/1050/2130 1052/1052/2131 1047/1047/2132 +f 1047/1047/2132 1052/1052/2131 1048/1048/2133 +f 1048/1048/2134 1052/1052/2135 1053/1053/2136 +f 1048/1048/2134 1053/1053/2136 1046/1046/2137 +f 1046/1046/2138 1053/1053/2139 1051/1051/2140 +f 1051/1051/2140 1053/1053/2139 1049/1049/2141 +f 1050/1050/2142 1054/1054/2143 1052/1052/2144 +f 1053/1053/2145 1055/1055/2146 1056/1056/2147 +f 1053/1053/2145 1056/1056/2147 1049/1049/2148 +f 1049/1049/2148 1056/1056/2147 1050/1050/2149 +f 1053/1053/2145 1057/1057/2150 1055/1055/2146 +f 1052/1052/2144 1054/1054/2143 1057/1057/2150 +f 1052/1052/2144 1057/1057/2150 1053/1053/2145 +f 1042/1042/2151 1041/1041/2152 1055/1055/2153 +f 1055/1055/2153 1041/1041/2152 1056/1056/2154 +f 1056/1056/2155 1041/1041/2156 1050/1050/2157 +f 1050/1050/2157 1041/1041/2156 1043/1043/2158 +f 1050/1050/2159 1043/1043/2160 1045/1045/2161 +f 1050/1050/2159 1045/1045/2161 1054/1054/2162 +f 1054/1054/2163 1045/1045/2163 1044/1044/2163 +f 1054/1054/2164 1044/1044/2164 1057/1057/2164 +f 1044/1044/2165 1042/1042/2166 1057/1057/2167 +f 1057/1057/2167 1042/1042/2166 1055/1055/2168 +f 1045/1045/2169 1043/1043/2169 1058/1058/2169 +f 1042/1042/2170 1045/1045/2170 1058/1058/2170 +f 1043/1043/2171 1042/1042/2171 1058/1058/2171 +f 1051/1051/2172 1047/1047/2124 1046/1046/2123 +f 1059/1059/2173 1060/1060/2173 1061/1061/2173 +f 1062/1062/2174 1063/1063/2174 1059/1059/2174 +f 1064/1064/2175 1065/1065/2175 1066/1066/2175 +f 1065/1065/2176 1067/1067/2176 1066/1066/2176 +f 1067/1067/2177 1068/1068/2177 1066/1066/2177 +f 1066/1066/2178 1068/1068/2178 1064/1064/2178 +f 1068/1068/2179 1069/1069/2179 1064/1064/2179 +f 1064/1064/2180 1069/1069/2180 1065/1065/2180 +f 1065/1065/2181 1069/1069/2181 1067/1067/2181 +f 1069/1069/2182 1070/1070/2183 1071/1071/2184 +f 1069/1069/2182 1071/1071/2184 1067/1067/2185 +f 1068/1068/2186 1070/1070/2183 1069/1069/2182 +f 1071/1071/2184 1072/1072/2187 1067/1067/2185 +f 1068/1068/2186 1073/1073/2188 1070/1070/2183 +f 1067/1067/2185 1072/1072/2187 1068/1068/2189 +f 1068/1068/2189 1072/1072/2187 1073/1073/2190 +f 1071/1071/2191 1060/1060/2191 1072/1072/2191 +f 1072/1072/2192 1060/1060/2192 1059/1059/2192 +f 1072/1072/2193 1059/1059/2194 1073/1073/2195 +f 1059/1059/2194 1063/1063/2196 1073/1073/2195 +f 1073/1073/2197 1063/1063/2198 1062/1062/2199 +f 1073/1073/2197 1062/1062/2199 1070/1070/2200 +f 1070/1070/2201 1062/1062/2202 1071/1071/2203 +f 1062/1062/2202 1061/1061/2204 1071/1071/2203 +f 1071/1071/2205 1061/1061/2205 1060/1060/2205 +f 1062/1062/2206 1059/1059/2206 1074/1074/2206 +f 1061/1061/2207 1062/1062/2207 1074/1074/2207 +f 1059/1059/2208 1061/1061/2208 1074/1074/2208 +f 1075/1075/2209 1076/1076/2209 1077/1077/2209 +f 1078/1078/2210 1079/1079/2210 1075/1075/2210 +f 1080/1080/2211 1081/1081/2211 1082/1082/2211 +f 1082/1082/2212 1083/1083/2213 1084/1084/2214 +f 1082/1082/2212 1084/1084/2214 1080/1080/2215 +f 1080/1080/2216 1084/1084/2216 1085/1085/2216 +f 1080/1080/2217 1085/1085/2217 1081/1081/2217 +f 1085/1085/2218 1086/1086/2219 1081/1081/2220 +f 1081/1081/2220 1086/1086/2219 1083/1083/2221 +f 1081/1081/2222 1083/1083/2222 1082/1082/2222 +f 1083/1083/2223 1087/1087/2223 1084/1084/2223 +f 1086/1086/2224 1088/1088/2225 1083/1083/2226 +f 1086/1086/2224 1085/1085/2227 1088/1088/2225 +f 1084/1084/2228 1089/1089/2228 1085/1085/2228 +f 1084/1084/2229 1087/1087/2229 1089/1089/2229 +f 1087/1087/2230 1076/1076/2231 1075/1075/2232 +f 1087/1087/2230 1075/1075/2232 1089/1089/2233 +f 1089/1089/2234 1075/1075/2234 1079/1079/2234 +f 1089/1089/2235 1079/1079/2235 1085/1085/2235 +f 1085/1085/2236 1079/1079/2237 1088/1088/2238 +f 1079/1079/2237 1078/1078/2239 1088/1088/2238 +f 1078/1078/2240 1077/1077/2240 1088/1088/2240 +f 1088/1088/2241 1077/1077/2242 1083/1083/2243 +f 1077/1077/2242 1076/1076/2244 1083/1083/2243 +f 1083/1083/2243 1076/1076/2244 1087/1087/2245 +f 1078/1078/2246 1075/1075/2246 1090/1090/2246 +f 1077/1077/2247 1078/1078/2247 1090/1090/2247 +f 1075/1075/2248 1077/1077/2248 1090/1090/2248 +f 1091/1091/2249 1092/1092/2249 1093/1093/2249 +f 1093/1093/2250 1094/1094/2250 1095/1095/2250 +f 1096/1096/2251 1097/1097/2252 1098/1098/2253 +f 1098/1098/2254 1099/1099/2255 1096/1096/2256 +f 1096/1096/2256 1099/1099/2255 1100/1100/2257 +f 1096/1096/2258 1100/1100/2258 1101/1101/2258 +f 1101/1101/2259 1100/1100/2259 1102/1102/2259 +f 1101/1101/2260 1102/1102/2260 1097/1097/2260 +f 1097/1097/2261 1102/1102/2262 1099/1099/2263 +f 1097/1097/2261 1099/1099/2263 1098/1098/2264 +f 1099/1099/2265 1103/1103/2266 1100/1100/2267 +f 1100/1100/2267 1103/1103/2266 1104/1104/2268 +f 1099/1099/2269 1105/1105/2270 1103/1103/2271 +f 1102/1102/2272 1105/1105/2272 1099/1099/2272 +f 1102/1102/2273 1106/1106/2274 1105/1105/2275 +f 1100/1100/2267 1104/1104/2268 1106/1106/2276 +f 1100/1100/2267 1106/1106/2276 1102/1102/2277 +f 1105/1105/2270 1093/1093/2278 1103/1103/2271 +f 1093/1093/2278 1092/1092/2279 1103/1103/2271 +f 1103/1103/2280 1092/1092/2281 1104/1104/2282 +f 1104/1104/2282 1092/1092/2281 1091/1091/2283 +f 1104/1104/2284 1091/1091/2284 1095/1095/2284 +f 1104/1104/2285 1095/1095/2285 1106/1106/2285 +f 1106/1106/2286 1095/1095/2286 1094/1094/2286 +f 1106/1106/2274 1094/1094/2287 1105/1105/2275 +f 1094/1094/2288 1093/1093/2288 1105/1105/2288 +f 1095/1095/2289 1091/1091/2289 1107/1107/2289 +f 1093/1093/2290 1095/1095/2290 1107/1107/2290 +f 1091/1091/2291 1093/1093/2291 1107/1107/2291 +f 1101/1101/2292 1097/1097/2252 1096/1096/2251 +f 1108/1108/2293 1109/1109/2293 1110/1110/2293 +f 1111/1111/2294 1112/1112/2294 1113/1113/2294 +f 1111/1111/2295 1114/1114/2295 1112/1112/2295 +f 1114/1114/2296 1115/1115/2296 1112/1112/2296 +f 1112/1112/2297 1115/1115/2297 1113/1113/2297 +f 1115/1115/2298 1116/1116/2298 1113/1113/2298 +f 1113/1113/2299 1116/1116/2299 1111/1111/2299 +f 1116/1116/2300 1114/1114/2300 1111/1111/2300 +f 1114/1114/2301 1117/1117/2302 1115/1115/2303 +f 1114/1114/2301 1118/1118/2304 1117/1117/2302 +f 1115/1115/2305 1117/1117/2306 1119/1119/2307 +f 1114/1114/2301 1120/1120/2308 1118/1118/2304 +f 1116/1116/2309 1120/1120/2308 1114/1114/2301 +f 1115/1115/2310 1119/1119/2310 1116/1116/2310 +f 1116/1116/2311 1119/1119/2312 1120/1120/2313 +f 1109/1109/2314 1108/1108/2314 1118/1118/2314 +f 1118/1118/2315 1108/1108/2316 1117/1117/2317 +f 1108/1108/2316 1121/1121/2318 1117/1117/2317 +f 1117/1117/2306 1121/1121/2319 1122/1122/2320 +f 1117/1117/2306 1122/1122/2320 1119/1119/2307 +f 1122/1122/2321 1110/1110/2321 1119/1119/2321 +f 1119/1119/2312 1110/1110/2322 1120/1120/2313 +f 1120/1120/2323 1110/1110/2323 1109/1109/2323 +f 1120/1120/2324 1109/1109/2324 1118/1118/2324 +f 1110/1110/2325 1122/1122/2325 1123/1123/2325 +f 1108/1108/2326 1110/1110/2326 1123/1123/2326 +f 1121/1121/2327 1108/1108/2327 1123/1123/2327 +f 1122/1122/2328 1121/1121/2328 1123/1123/2328 +f 1124/1124/2329 1125/1125/2329 1126/1126/2329 +f 1126/1126/2330 1127/1127/2330 1128/1128/2330 +f 1129/1129/2331 1130/1130/2331 1131/1131/2331 +f 1131/1131/2332 1132/1132/2333 1129/1129/2334 +f 1132/1132/2335 1133/1133/2335 1129/1129/2335 +f 1129/1129/2336 1133/1133/2337 1130/1130/2338 +f 1130/1130/2338 1133/1133/2337 1134/1134/2339 +f 1130/1130/2340 1134/1134/2341 1135/1135/2342 +f 1130/1130/2340 1135/1135/2342 1131/1131/2343 +f 1131/1131/2332 1135/1135/2344 1132/1132/2333 +f 1134/1134/2345 1136/1136/2346 1135/1135/2347 +f 1135/1135/2347 1136/1136/2346 1137/1137/2348 +f 1135/1135/2347 1137/1137/2348 1132/1132/2349 +f 1132/1132/2349 1137/1137/2348 1133/1133/2350 +f 1133/1133/2350 1137/1137/2348 1138/1138/2351 +f 1133/1133/2350 1138/1138/2351 1134/1134/2352 +f 1127/1127/2353 1126/1126/2354 1137/1137/2355 +f 1137/1137/2355 1126/1126/2354 1138/1138/2356 +f 1126/1126/2357 1125/1125/2358 1138/1138/2359 +f 1138/1138/2359 1125/1125/2358 1134/1134/2360 +f 1134/1134/2361 1125/1125/2362 1124/1124/2363 +f 1134/1134/2361 1124/1124/2363 1136/1136/2364 +f 1136/1136/2365 1124/1124/2365 1128/1128/2365 +f 1136/1136/2366 1128/1128/2366 1137/1137/2366 +f 1137/1137/2367 1128/1128/2367 1127/1127/2367 +f 1124/1124/2368 1126/1126/2368 1139/1139/2368 +f 1128/1128/2369 1124/1124/2369 1139/1139/2369 +f 1126/1126/2370 1128/1128/2370 1139/1139/2370 +f 1140/1140/2371 1141/1141/2371 1142/1142/2371 +f 1143/1143/2372 1144/1144/2372 1145/1145/2372 +f 1143/1143/2373 1146/1146/2374 1144/1144/2375 +f 1146/1146/2374 1147/1147/2376 1144/1144/2375 +f 1144/1144/2377 1147/1147/2378 1148/1148/2379 +f 1144/1144/2377 1148/1148/2379 1145/1145/2380 +f 1148/1148/2381 1149/1149/2381 1145/1145/2381 +f 1145/1145/2382 1149/1149/2383 1143/1143/2384 +f 1149/1149/2383 1146/1146/2385 1143/1143/2384 +f 1149/1149/2386 1150/1150/2387 1146/1146/2388 +f 1148/1148/2389 1147/1147/2390 1151/1151/2391 +f 1146/1146/2392 1152/1152/2392 1147/1147/2392 +f 1148/1148/2389 1151/1151/2391 1149/1149/2386 +f 1149/1149/2386 1151/1151/2391 1150/1150/2387 +f 1152/1152/2393 1153/1153/2394 1147/1147/2395 +f 1153/1153/2394 1142/1142/2396 1147/1147/2395 +f 1147/1147/2397 1142/1142/2397 1151/1151/2397 +f 1151/1151/2398 1142/1142/2398 1141/1141/2398 +f 1151/1151/2399 1141/1141/2399 1150/1150/2399 +f 1141/1141/2400 1140/1140/2401 1150/1150/2402 +f 1150/1150/2402 1140/1140/2401 1146/1146/2403 +f 1146/1146/2404 1140/1140/2405 1153/1153/2406 +f 1146/1146/2404 1153/1153/2406 1152/1152/2407 +f 1140/1140/2408 1142/1142/2408 1154/1154/2408 +f 1153/1153/2409 1140/1140/2409 1154/1154/2409 +f 1142/1142/2410 1153/1153/2410 1154/1154/2410 +f 1155/1155/2411 1156/1156/2411 1157/1157/2411 +f 1158/1158/2412 1159/1159/2412 1160/1160/2412 +f 1160/1160/2413 1161/1161/2413 1158/1158/2413 +f 1161/1161/2414 1162/1162/2414 1158/1158/2414 +f 1158/1158/2415 1162/1162/2415 1159/1159/2415 +f 1159/1159/2416 1162/1162/2416 1163/1163/2416 +f 1159/1159/2417 1163/1163/2417 1160/1160/2417 +f 1160/1160/2418 1163/1163/2418 1161/1161/2418 +f 1163/1163/2419 1164/1164/2420 1161/1161/2421 +f 1163/1163/2419 1165/1165/2422 1164/1164/2420 +f 1161/1161/2421 1164/1164/2420 1166/1166/2423 +f 1161/1161/2421 1166/1166/2423 1162/1162/2424 +f 1163/1163/2419 1167/1167/2425 1165/1165/2422 +f 1162/1162/2424 1166/1166/2423 1167/1167/2425 +f 1162/1162/2424 1167/1167/2425 1163/1163/2419 +f 1166/1166/2426 1168/1168/2426 1169/1169/2426 +f 1166/1166/2427 1169/1169/2427 1167/1167/2427 +f 1169/1169/2428 1157/1157/2428 1167/1167/2428 +f 1157/1157/2429 1156/1156/2430 1167/1167/2431 +f 1167/1167/2431 1156/1156/2430 1165/1165/2432 +f 1156/1156/2433 1155/1155/2434 1165/1165/2435 +f 1165/1165/2435 1155/1155/2434 1164/1164/2436 +f 1164/1164/2437 1155/1155/2438 1168/1168/2439 +f 1164/1164/2437 1168/1168/2439 1166/1166/2440 +f 1157/1157/2441 1169/1169/2441 1170/1170/2441 +f 1155/1155/2442 1157/1157/2443 1170/1170/2444 +f 1171/1171/2445 1155/1155/2442 1170/1170/2444 +f 1168/1168/2446 1155/1155/2446 1171/1171/2446 +f 1169/1169/2447 1168/1168/2448 1170/1170/2449 +f 1170/1170/2449 1168/1168/2448 1171/1171/2450 +f 1172/1172/2451 1173/1173/2451 1174/1174/2451 +f 1174/1174/2452 1175/1175/2452 1176/1176/2452 +f 1177/1177/2453 1178/1178/2453 1179/1179/2453 +f 1180/1180/2454 1181/1181/2455 1177/1177/2456 +f 1177/1177/2456 1181/1181/2455 1178/1178/2457 +f 1178/1178/2458 1181/1181/2459 1179/1179/2460 +f 1181/1181/2459 1182/1182/2461 1179/1179/2460 +f 1179/1179/2462 1182/1182/2462 1183/1183/2462 +f 1179/1179/2463 1183/1183/2463 1177/1177/2463 +f 1177/1177/2464 1183/1183/2464 1180/1180/2464 +f 1181/1181/2465 1184/1184/2466 1182/1182/2467 +f 1180/1180/2468 1185/1185/2469 1181/1181/2465 +f 1183/1183/2470 1186/1186/2471 1180/1180/2468 +f 1180/1180/2468 1186/1186/2471 1185/1185/2469 +f 1181/1181/2465 1185/1185/2469 1184/1184/2466 +f 1183/1183/2472 1187/1187/2472 1186/1186/2472 +f 1182/1182/2467 1187/1187/2473 1183/1183/2474 +f 1184/1184/2466 1187/1187/2473 1182/1182/2467 +f 1185/1185/2475 1186/1186/2475 1173/1173/2475 +f 1173/1173/2476 1172/1172/2476 1185/1185/2476 +f 1185/1185/2477 1172/1172/2478 1176/1176/2479 +f 1185/1185/2477 1176/1176/2479 1184/1184/2480 +f 1184/1184/2481 1176/1176/2481 1175/1175/2481 +f 1184/1184/2482 1175/1175/2482 1187/1187/2482 +f 1187/1187/2483 1175/1175/2483 1174/1174/2483 +f 1187/1187/2484 1174/1174/2484 1186/1186/2484 +f 1186/1186/2485 1174/1174/2485 1173/1173/2485 +f 1174/1174/2486 1176/1176/2486 1188/1188/2486 +f 1172/1172/2487 1174/1174/2487 1188/1188/2487 +f 1176/1176/2488 1172/1172/2488 1188/1188/2488 +f 1189/1189/2489 1190/1190/2489 1191/1191/2489 +f 1192/1192/2490 1193/1193/2491 1194/1194/2492 +f 1194/1194/2492 1193/1193/2491 1195/1195/2493 +f 1193/1193/2491 1196/1196/2494 1195/1195/2493 +f 1195/1195/2495 1196/1196/2496 1197/1197/2497 +f 1196/1196/2496 1198/1198/2498 1197/1197/2497 +f 1198/1198/2498 1199/1199/2499 1197/1197/2497 +f 1197/1197/2500 1199/1199/2501 1200/1200/2502 +f 1199/1199/2501 1201/1201/2503 1200/1200/2502 +f 1200/1200/2502 1201/1201/2503 1202/1202/2504 +f 1201/1201/2503 1203/1203/2505 1202/1202/2504 +f 1202/1202/2504 1203/1203/2505 1204/1204/2506 +f 1203/1203/2505 1205/1205/2507 1204/1204/2506 +f 1205/1205/2507 1206/1206/2508 1204/1204/2506 +f 1204/1204/2506 1206/1206/2508 1207/1207/2509 +f 1206/1206/2510 1208/1208/2510 1207/1207/2510 +f 1207/1207/2511 1208/1208/2511 1209/1209/2511 +f 1208/1208/2512 1210/1210/2512 1209/1209/2512 +f 1209/1209/2513 1210/1210/2514 1211/1211/2515 +f 1210/1210/2514 1212/1212/2516 1211/1211/2515 +f 1211/1211/2515 1212/1212/2516 1213/1213/2517 +f 1212/1212/2516 1214/1214/2518 1213/1213/2517 +f 1213/1213/2517 1214/1214/2518 1215/1215/2519 +f 1214/1214/2518 1216/1216/2520 1215/1215/2519 +f 1215/1215/2519 1216/1216/2520 1217/1217/2521 +f 1216/1216/2520 1218/1218/2522 1217/1217/2521 +f 1217/1217/2521 1218/1218/2522 1219/1219/2523 +f 1219/1219/2523 1218/1218/2522 1220/1220/2524 +f 1221/1221/2525 1222/1222/2526 1223/1223/2527 +f 1223/1223/2528 1222/1222/2528 1224/1224/2528 +f 1224/1224/2529 1222/1222/2530 1225/1225/2531 +f 1225/1225/2531 1222/1222/2530 1226/1226/2532 +f 1225/1225/2533 1226/1226/2533 1227/1227/2533 +f 1227/1227/2534 1226/1226/2534 1228/1228/2534 +f 1227/1227/2535 1228/1228/2535 1221/1221/2535 +f 1221/1221/2525 1228/1228/2536 1222/1222/2526 +f 1229/1229/2537 1230/1230/2537 1231/1231/2537 +f 1232/1232/2538 1233/1233/2539 1234/1234/2540 +f 1232/1232/2538 1234/1234/2540 1235/1235/2541 +f 1236/1236/2542 1237/1237/2543 1238/1238/2544 +f 1236/1236/2542 1238/1238/2544 1239/1239/2545 +f 1240/1240/2546 1241/1241/2547 1242/1242/2548 +f 1240/1240/2546 1242/1242/2548 1243/1243/2549 +f 1242/1242/2548 1244/1244/2550 1243/1243/2549 +f 1243/1243/2549 1244/1244/2550 1245/1245/2551 +f 1245/1245/2551 1244/1244/2550 1246/1246/2552 +f 1245/1245/2551 1246/1246/2552 1247/1247/2553 +f 1245/1245/2551 1247/1247/2553 1248/1248/2554 +f 1249/1249/2555 1250/1250/2556 1251/1251/2557 +f 1249/1249/2555 1251/1251/2557 1252/1252/2558 +f 1252/1252/2558 1251/1251/2557 1253/1253/2559 +f 1253/1253/2559 1251/1251/2557 1254/1254/2560 +f 1253/1253/2559 1254/1254/2560 1255/1255/2561 +f 1253/1253/2559 1255/1255/2561 1256/1256/2562 +f 1257/1257/2563 1258/1258/2564 1259/1259/2565 +f 1258/1258/2564 1260/1260/2566 1259/1259/2565 +f 1259/1259/2565 1260/1260/2566 1261/1261/2567 +f 1260/1260/2566 1262/1262/2568 1261/1261/2567 +f 1262/1262/2569 1263/1263/2569 1261/1261/2569 +f 1261/1261/2570 1263/1263/2570 1264/1264/2570 +f 1263/1263/2571 1237/1237/2571 1264/1264/2571 +f 1264/1264/2572 1237/1237/2572 1265/1265/2572 +f 1237/1237/2573 1255/1255/2573 1265/1265/2573 +f 1265/1265/2574 1255/1255/2575 1266/1266/2576 +f 1255/1255/2575 1267/1267/2577 1266/1266/2576 +f 1267/1267/2577 1254/1254/2578 1266/1266/2576 +f 1266/1266/2576 1254/1254/2578 1268/1268/2579 +f 1254/1254/2578 1251/1251/2580 1268/1268/2579 +f 1250/1250/2581 1269/1269/2582 1268/1268/2579 +f 1250/1250/2581 1268/1268/2579 1251/1251/2580 +f 1269/1269/2582 1250/1250/2581 1247/1247/2583 +f 1269/1269/2582 1247/1247/2583 1246/1246/2584 +f 1269/1269/2582 1246/1246/2584 1270/1270/2585 +f 1270/1270/2585 1246/1246/2584 1244/1244/2586 +f 1270/1270/2585 1244/1244/2586 1271/1271/2587 +f 1271/1271/2587 1244/1244/2586 1242/1242/2588 +f 1271/1271/2587 1242/1242/2588 1241/1241/2589 +f 1271/1271/2587 1241/1241/2589 1272/1272/2590 +f 1272/1272/2590 1241/1241/2589 1234/1234/2591 +f 1272/1272/2590 1234/1234/2591 1273/1273/2592 +f 1272/1272/2590 1273/1273/2592 1274/1274/2593 +f 1274/1274/2594 1273/1273/2594 1275/1275/2594 +f 1274/1274/2595 1275/1275/2595 1276/1276/2595 +f 1276/1276/2596 1275/1275/2596 1277/1277/2596 +f 1276/1276/2597 1277/1277/2598 1278/1278/2599 +f 1278/1278/2599 1277/1277/2598 1279/1279/2600 +f 1279/1279/2600 1277/1277/2598 1280/1280/2601 +f 1281/1281/2602 1282/1282/2603 1247/1247/2553 +f 1247/1247/2553 1282/1282/2603 1248/1248/2554 +f 1282/1282/2604 1281/1281/2605 1249/1249/2555 +f 1249/1249/2555 1281/1281/2605 1250/1250/2556 +f 1283/1283/2606 1284/1284/2607 1234/1234/2540 +f 1234/1234/2540 1284/1284/2607 1235/1235/2541 +f 1241/1241/2547 1240/1240/2546 1283/1283/2608 +f 1283/1283/2608 1240/1240/2546 1284/1284/2609 +f 1285/1285/2610 1286/1286/2611 1256/1256/2562 +f 1256/1256/2562 1255/1255/2561 1285/1285/2610 +f 1237/1237/2543 1236/1236/2542 1285/1285/2612 +f 1285/1285/2612 1236/1236/2542 1286/1286/2613 +f 1287/1287/2614 1220/1220/2615 1288/1288/2616 +f 1220/1220/2615 1218/1218/2617 1288/1288/2616 +f 1289/1289/2618 1198/1198/2619 1196/1196/2620 +f 1260/1260/2621 1230/1230/2622 1290/1290/2623 +f 1210/1210/2624 1208/1208/2625 1291/1291/2626 +f 1292/1292/2627 1230/1230/2622 1260/1260/2621 +f 1293/1293/2628 1193/1193/2629 1294/1294/2630 +f 1260/1260/2621 1295/1295/2631 1292/1292/2627 +f 1260/1260/2621 1296/1296/2632 1295/1295/2631 +f 1260/1260/2621 1258/1258/2633 1296/1296/2632 +f 1239/1239/2545 1238/1238/2544 1297/1297/2634 +f 1297/1297/2634 1238/1238/2544 1298/1298/2635 +f 1297/1297/2634 1298/1298/2635 1299/1299/2636 +f 1299/1299/2636 1298/1298/2635 1300/1300/2637 +f 1299/1299/2636 1300/1300/2637 1301/1301/2638 +f 1301/1301/2638 1300/1300/2637 1216/1216/2639 +f 1302/1302/2640 1303/1303/2641 1304/1304/2642 +f 1304/1304/2642 1303/1303/2641 1305/1305/2643 +f 1306/1306/2644 1290/1290/2645 1229/1229/2646 +f 1229/1229/2646 1290/1290/2645 1230/1230/2647 +f 1304/1304/2648 1305/1305/2649 1306/1306/2650 +f 1306/1306/2650 1305/1305/2649 1290/1290/2651 +f 1307/1307/2652 1289/1289/2653 1308/1308/2654 +f 1308/1308/2654 1289/1289/2653 1293/1293/2655 +f 1308/1308/2654 1293/1293/2655 1309/1309/2656 +f 1309/1309/2656 1293/1293/2655 1310/1310/2657 +f 1309/1309/2656 1310/1310/2657 1232/1232/2538 +f 1232/1232/2538 1310/1310/2657 1233/1233/2539 +f 1191/1191/2658 1190/1190/2659 1311/1311/2660 +f 1191/1191/2658 1311/1311/2660 1312/1312/2661 +f 1312/1312/2662 1311/1311/2662 1313/1313/2662 +f 1312/1312/2663 1313/1313/2663 1314/1314/2663 +f 1314/1314/2664 1313/1313/2665 1315/1315/2666 +f 1315/1315/2666 1313/1313/2665 1294/1294/2667 +f 1316/1316/2668 1199/1199/2669 1289/1289/2653 +f 1316/1316/2668 1289/1289/2653 1307/1307/2652 +f 1216/1216/2639 1317/1317/2670 1301/1301/2638 +f 1301/1301/2638 1317/1317/2670 1318/1318/2671 +f 1319/1319/2672 1206/1206/2673 1205/1205/2674 +f 1319/1319/2672 1205/1205/2674 1320/1320/2675 +f 1320/1320/2675 1205/1205/2674 1203/1203/2676 +f 1320/1320/2675 1203/1203/2676 1321/1321/2677 +f 1321/1321/2677 1203/1203/2676 1201/1201/2678 +f 1321/1321/2677 1201/1201/2678 1322/1322/2679 +f 1323/1323/2680 1212/1212/2681 1291/1291/2682 +f 1323/1323/2680 1291/1291/2682 1324/1324/2683 +f 1324/1324/2683 1291/1291/2682 1208/1208/2684 +f 1324/1324/2683 1208/1208/2684 1325/1325/2685 +f 1325/1325/2685 1208/1208/2684 1326/1326/2686 +f 1325/1325/2685 1326/1326/2686 1327/1327/2687 +f 1328/1328/2688 1329/1329/2689 1319/1319/2672 +f 1319/1319/2672 1329/1329/2689 1206/1206/2673 +f 1329/1329/2690 1328/1328/2691 1326/1326/2686 +f 1326/1326/2686 1328/1328/2691 1327/1327/2687 +f 1208/1208/2692 1206/1206/2693 1326/1326/2694 +f 1250/1250/2695 1281/1281/2695 1247/1247/2695 +f 1216/1216/2696 1300/1300/2697 1218/1218/2617 +f 1206/1206/2693 1329/1329/2698 1326/1326/2694 +f 1280/1280/2699 1330/1330/2700 1331/1331/2701 +f 1280/1280/2699 1332/1332/2702 1330/1330/2700 +f 1280/1280/2699 1277/1277/2703 1332/1332/2702 +f 1277/1277/2703 1190/1190/2704 1332/1332/2702 +f 1199/1199/2669 1316/1316/2668 1333/1333/2705 +f 1333/1333/2705 1316/1316/2668 1334/1334/2706 +f 1333/1333/2707 1334/1334/2708 1322/1322/2679 +f 1322/1322/2679 1201/1201/2678 1333/1333/2707 +f 1212/1212/2681 1323/1323/2680 1335/1335/2709 +f 1335/1335/2709 1323/1323/2680 1336/1336/2710 +f 1335/1335/2711 1336/1336/2712 1317/1317/2670 +f 1317/1317/2670 1336/1336/2712 1318/1318/2671 +f 1190/1190/2704 1277/1277/2703 1311/1311/2713 +f 1193/1193/2629 1192/1192/2714 1294/1294/2630 +f 1277/1277/2703 1313/1313/2715 1311/1311/2713 +f 1277/1277/2703 1310/1310/2716 1313/1313/2715 +f 1313/1313/2715 1310/1310/2716 1294/1294/2630 +f 1201/1201/2717 1199/1199/2717 1333/1333/2717 +f 1310/1310/2716 1293/1293/2628 1294/1294/2630 +f 1293/1293/2628 1196/1196/2620 1193/1193/2629 +f 1275/1275/2718 1233/1233/2719 1310/1310/2716 +f 1275/1275/2718 1273/1273/2720 1233/1233/2719 +f 1291/1291/2626 1212/1212/2721 1210/1210/2624 +f 1199/1199/2722 1198/1198/2619 1289/1289/2618 +f 1273/1273/2720 1234/1234/2723 1233/1233/2719 +f 1234/1234/2724 1241/1241/2724 1283/1283/2724 +f 1287/1287/2725 1288/1288/2726 1337/1337/2727 +f 1337/1337/2727 1288/1288/2726 1302/1302/2728 +f 1302/1302/2729 1288/1288/2729 1303/1303/2729 +f 1294/1294/2730 1338/1338/2731 1339/1339/2732 +f 1339/1339/2732 1338/1338/2731 1340/1340/2733 +f 1315/1315/2734 1294/1294/2734 1339/1339/2734 +f 1341/1341/2735 1342/1342/2735 1343/1343/2735 +f 1341/1341/2736 1343/1343/2736 1344/1344/2736 +f 1343/1343/2737 1345/1345/2737 1344/1344/2737 +f 1344/1344/2738 1345/1345/2738 1346/1346/2738 +f 1346/1346/2739 1345/1345/2740 1347/1347/2741 +f 1346/1346/2739 1347/1347/2741 1348/1348/2742 +f 1348/1348/2743 1347/1347/2743 1349/1349/2743 +f 1349/1349/2744 1347/1347/2744 1342/1342/2744 +f 1349/1349/2745 1342/1342/2745 1341/1341/2745 +f 1292/1292/2746 1350/1350/2747 1231/1231/2748 +f 1292/1292/2746 1231/1231/2748 1230/1230/2749 +f 1219/1219/2750 1220/1220/2751 1287/1287/2752 +f 1219/1219/2750 1287/1287/2752 1337/1337/2753 +f 1295/1295/2754 1351/1351/2754 1349/1349/2754 +f 1295/1295/2755 1349/1349/2755 1350/1350/2755 +f 1295/1295/2756 1350/1350/2747 1292/1292/2746 +f 1190/1190/2757 1189/1189/2758 1332/1332/2759 +f 1332/1332/2759 1189/1189/2758 1352/1352/2760 +f 1353/1353/2761 1330/1330/2762 1223/1223/2763 +f 1353/1353/2761 1331/1331/2764 1330/1330/2762 +f 1223/1223/2765 1330/1330/2765 1332/1332/2765 +f 1223/1223/2766 1332/1332/2766 1352/1352/2766 +f 1192/1192/2767 1194/1194/2768 1340/1340/2769 +f 1192/1192/2767 1340/1340/2769 1338/1338/2770 +f 1279/1279/2771 1331/1331/2772 1353/1353/2773 +f 1279/1279/2771 1280/1280/2774 1331/1331/2772 +f 1351/1351/2775 1295/1295/2775 1296/1296/2775 +f 1257/1257/2776 1296/1296/2776 1258/1258/2776 +f 1351/1351/2777 1296/1296/2777 1257/1257/2777 +f 1354/1354/2778 1249/1249/2778 1252/1252/2778 +f 1252/1252/2779 1253/1253/2780 1355/1355/2781 +f 1355/1355/2781 1253/1253/2780 1256/1256/2782 +f 1355/1355/2781 1256/1256/2782 1356/1356/2783 +f 1286/1286/2784 1357/1357/2784 1256/1256/2784 +f 1256/1256/2785 1357/1357/2785 1356/1356/2785 +f 1249/1249/2786 1358/1358/2786 1282/1282/2786 +f 1249/1249/2787 1354/1354/2787 1358/1358/2787 +f 1236/1236/2788 1357/1357/2788 1286/1286/2788 +f 1236/1236/2789 1356/1356/2789 1357/1357/2789 +f 1358/1358/2790 1248/1248/2790 1282/1282/2790 +f 1248/1248/2791 1358/1358/2791 1354/1354/2791 +f 1356/1356/2792 1236/1236/2792 1239/1239/2792 +f 1359/1359/2793 1240/1240/2794 1243/1243/2795 +f 1359/1359/2793 1243/1243/2795 1360/1360/2796 +f 1360/1360/2797 1243/1243/2549 1245/1245/2551 +f 1360/1360/2798 1245/1245/2799 1354/1354/2800 +f 1354/1354/2800 1245/1245/2799 1248/1248/2801 +f 1361/1361/2802 1239/1239/2803 1297/1297/2804 +f 1297/1297/2804 1362/1362/2805 1361/1361/2802 +f 1299/1299/2806 1362/1362/2805 1297/1297/2804 +f 1299/1299/2806 1301/1301/2807 1362/1362/2805 +f 1240/1240/2808 1363/1363/2808 1284/1284/2808 +f 1240/1240/2809 1359/1359/2809 1363/1363/2809 +f 1301/1301/2810 1318/1318/2810 1364/1364/2810 +f 1336/1336/2811 1365/1365/2811 1318/1318/2811 +f 1318/1318/2812 1365/1365/2812 1364/1364/2812 +f 1284/1284/2813 1363/1363/2813 1235/1235/2813 +f 1235/1235/2814 1363/1363/2814 1359/1359/2814 +f 1232/1232/2815 1235/1235/2815 1359/1359/2815 +f 1323/1323/2816 1365/1365/2816 1336/1336/2816 +f 1323/1323/2817 1364/1364/2817 1365/1365/2817 +f 1309/1309/2818 1366/1366/2819 1308/1308/2820 +f 1309/1309/2818 1232/1232/2821 1366/1366/2819 +f 1364/1364/2822 1323/1323/2823 1324/1324/2824 +f 1364/1364/2822 1324/1324/2824 1367/1367/2825 +f 1367/1367/2825 1324/1324/2824 1325/1325/2826 +f 1325/1325/2685 1327/1327/2687 1368/1368/2827 +f 1369/1369/2828 1316/1316/2668 1307/1307/2652 +f 1370/1370/2829 1327/1327/2830 1328/1328/2831 +f 1327/1327/2830 1370/1370/2829 1368/1368/2832 +f 1316/1316/2833 1371/1371/2834 1334/1334/2835 +f 1316/1316/2833 1369/1369/2836 1371/1371/2834 +f 1319/1319/2837 1370/1370/2837 1328/1328/2837 +f 1319/1319/2838 1368/1368/2838 1370/1370/2838 +f 1334/1334/2839 1371/1371/2839 1322/1322/2839 +f 1322/1322/2840 1371/1371/2840 1369/1369/2840 +f 1368/1368/2841 1319/1319/2841 1320/1320/2841 +f 1321/1321/2842 1322/1322/2842 1369/1369/2842 +f 1372/1372/2843 1373/1373/2844 1374/1374/2845 +f 1372/1372/2846 1374/1374/2847 1375/1375/2848 +f 1375/1375/2848 1374/1374/2847 1376/1376/2849 +f 1375/1375/2850 1376/1376/2851 1377/1377/2852 +f 1377/1377/2852 1376/1376/2851 1378/1378/2853 +f 1376/1376/2851 1379/1379/2854 1378/1378/2853 +f 1379/1379/2855 1376/1376/2856 1380/1380/2857 +f 1380/1380/2858 1376/1376/2858 1381/1381/2858 +f 1382/1382/2859 1383/1383/2859 1384/1384/2859 +f 1374/1374/2860 1383/1383/2860 1382/1382/2860 +f 1383/1383/2861 1374/1374/2845 1385/1385/2862 +f 1373/1373/2844 1385/1385/2862 1374/1374/2845 +f 1386/1386/2863 1387/1387/2863 1388/1388/2863 +f 1389/1389/2864 1390/1390/2865 1387/1387/2866 +f 1389/1389/2864 1387/1387/2866 1386/1386/2867 +f 1391/1391/2868 1390/1390/2865 1389/1389/2864 +f 1392/1392/2869 1391/1391/2868 1389/1389/2864 +f 1392/1392/2870 1389/1389/2871 1393/1393/2872 +f 1393/1393/2872 1389/1389/2871 1394/1394/2873 +f 1393/1393/2874 1394/1394/2875 1395/1395/2876 +f 1395/1395/2876 1394/1394/2875 1396/1396/2877 +f 1394/1394/2875 1397/1397/2878 1396/1396/2877 +f 1397/1397/2879 1394/1394/2879 1398/1398/2879 +f 1398/1398/2880 1394/1394/2880 1399/1399/2880 +f 1400/1400/2881 1401/1401/2882 1402/1402/2883 +f 1403/1403/2884 1404/1404/2885 1402/1402/2883 +f 1402/1402/2883 1405/1405/2886 1406/1406/2887 +f 1401/1401/2882 1407/1407/2888 1408/1408/2889 +f 1402/1402/2883 1406/1406/2887 1403/1403/2884 +f 1402/1402/2883 1404/1404/2885 1409/1409/2890 +f 1409/1409/2890 1400/1400/2881 1402/1402/2883 +f 1406/1406/2887 1405/1405/2886 1410/1410/2891 +f 1411/1411/2892 1412/1412/2893 1413/1413/2894 +f 1414/1414/2895 1407/1407/2888 1411/1411/2892 +f 1415/1415/2896 1416/1416/2897 1417/1417/2898 +f 1418/1418/2899 1419/1419/2900 1415/1415/2896 +f 1420/1420/2901 1421/1421/2902 1419/1419/2900 +f 1413/1413/2894 1412/1412/2893 1421/1421/2902 +f 1413/1413/2894 1421/1421/2902 1420/1420/2901 +f 1407/1407/2888 1412/1412/2893 1411/1411/2892 +f 1405/1405/2886 1408/1408/2889 1407/1407/2888 +f 1422/1422/2903 1423/1423/2904 1414/1414/2895 +f 1417/1417/2898 1422/1422/2903 1415/1415/2896 +f 1420/1420/2901 1419/1419/2900 1418/1418/2899 +f 1422/1422/2903 1414/1414/2895 1411/1411/2892 +f 1417/1417/2898 1423/1423/2904 1422/1422/2903 +f 1424/1424/2905 1425/1425/2906 1426/1426/2907 +f 1427/1427/2908 1428/1428/2909 1424/1424/2905 +f 1424/1424/2905 1428/1428/2909 1425/1425/2906 +f 1429/1429/2910 1430/1430/2911 1431/1431/2912 +f 1429/1429/2913 1426/1426/2913 1430/1430/2913 +f 1431/1431/2912 1430/1430/2911 1432/1432/2914 +f 1433/1433/2915 1434/1434/2916 1435/1435/2917 +f 1436/1436/2918 1437/1437/2918 1438/1438/2918 +f 1438/1438/2919 1439/1439/2919 1436/1436/2919 +f 1439/1439/2920 1438/1438/2921 1440/1440/2922 +f 1441/1441/2923 1442/1442/2924 1414/1414/2895 +f 1423/1423/2904 1441/1441/2923 1414/1414/2895 +f 1426/1426/2925 1442/1442/2924 1443/1443/2926 +f 1426/1426/2925 1443/1443/2926 1430/1430/2927 +f 1444/1444/2928 1430/1430/2927 1443/1443/2926 +f 1444/1444/2928 1441/1441/2923 1423/1423/2904 +f 1407/1407/2888 1414/1414/2895 1426/1426/2925 +f 1414/1414/2895 1442/1442/2924 1426/1426/2925 +f 1430/1430/2927 1444/1444/2928 1423/1423/2904 +f 1434/1434/2929 1439/1439/2920 1440/1440/2922 +f 1434/1434/2930 1440/1440/2931 1445/1445/2932 +f 1434/1434/2930 1445/1445/2932 1435/1435/2933 +f 1416/1416/2897 1436/1436/2934 1439/1439/2935 +f 1417/1417/2898 1446/1446/2936 1447/1447/2937 +f 1417/1417/2898 1447/1447/2937 1448/1448/2938 +f 1448/1448/2938 1447/1447/2937 1449/1449/2939 +f 1449/1449/2939 1447/1447/2937 1450/1450/2940 +f 1451/1451/2941 1446/1446/2936 1417/1417/2898 +f 1452/1452/2942 1451/1451/2941 1417/1417/2898 +f 1449/1449/2939 1450/1450/2940 1453/1453/2943 +f 1452/1452/2942 1453/1453/2943 1451/1451/2941 +f 1423/1423/2904 1454/1454/2944 1455/1455/2945 +f 1423/1423/2904 1455/1455/2945 1430/1430/2927 +f 1430/1430/2927 1455/1455/2945 1456/1456/2946 +f 1456/1456/2946 1432/1432/2947 1430/1430/2927 +f 1456/1456/2946 1457/1457/2948 1432/1432/2947 +f 1417/1417/2898 1457/1457/2948 1454/1454/2944 +f 1417/1417/2898 1454/1454/2944 1423/1423/2904 +f 1458/1458/2949 1417/1417/2898 1448/1448/2938 +f 1432/1432/2947 1457/1457/2948 1417/1417/2898 +f 1432/1432/2947 1417/1417/2898 1458/1458/2949 +f 1416/1416/2950 1439/1439/2950 1434/1434/2950 +f 1416/1416/2897 1434/1434/2951 1452/1452/2942 +f 1452/1452/2942 1434/1434/2951 1433/1433/2952 +f 1449/1449/2939 1453/1453/2943 1452/1452/2942 +f 1449/1449/2939 1452/1452/2942 1433/1433/2952 +f 1416/1416/2897 1452/1452/2942 1417/1417/2898 +f 1446/1446/2953 1459/1459/2953 1447/1447/2953 +f 1451/1451/2954 1453/1453/2954 1460/1460/2954 +f 1460/1460/2955 1446/1446/2955 1451/1451/2955 +f 1459/1459/2956 1446/1446/2956 1460/1460/2956 +f 1461/1461/2957 1444/1444/2957 1443/1443/2957 +f 1444/1444/2958 1461/1461/2959 1441/1441/2960 +f 1441/1441/2960 1461/1461/2959 1462/1462/2961 +f 1463/1463/2962 1441/1441/2963 1462/1462/2964 +f 1441/1441/2963 1463/1463/2962 1442/1442/2965 +f 1463/1463/2966 1443/1443/2966 1442/1442/2966 +f 1464/1464/2967 1457/1457/2967 1456/1456/2967 +f 1457/1457/2968 1464/1464/2968 1465/1465/2968 +f 1465/1465/2969 1454/1454/2969 1457/1457/2969 +f 1454/1454/2970 1465/1465/2970 1466/1466/2970 +f 1454/1454/2971 1466/1466/2971 1455/1455/2971 +f 1382/1382/2972 1384/1384/2972 1467/1467/2972 +f 1467/1467/2973 1398/1398/2973 1399/1399/2973 +f 1468/1468/2974 1469/1469/2975 1470/1470/2976 +f 1469/1469/2975 1468/1468/2974 1471/1471/2977 +f 1468/1468/2974 1472/1472/2978 1471/1471/2977 +f 1398/1398/2979 1473/1473/2980 1397/1397/2981 +f 1383/1383/2982 1472/1472/2978 1384/1384/2983 +f 1467/1467/2984 1473/1473/2980 1398/1398/2979 +f 1467/1467/2984 1468/1468/2974 1473/1473/2980 +f 1384/1384/2983 1472/1472/2978 1468/1468/2974 +f 1384/1384/2983 1468/1468/2974 1467/1467/2984 +f 1474/1474/2985 1475/1475/2986 1476/1476/2987 +f 1474/1474/2988 1477/1477/2988 1475/1475/2988 +f 1478/1478/2989 1479/1479/2989 1480/1480/2989 +f 1481/1481/2990 1482/1482/2991 1480/1480/2992 +f 1483/1483/2993 1484/1484/2994 1412/1412/2893 +f 1412/1412/2893 1484/1484/2994 1421/1421/2902 +f 1484/1484/2994 1485/1485/2995 1421/1421/2902 +f 1479/1479/2996 1485/1485/2995 1481/1481/2990 +f 1479/1479/2996 1481/1481/2990 1480/1480/2992 +f 1479/1479/2996 1421/1421/2902 1485/1485/2995 +f 1482/1482/2991 1483/1483/2993 1480/1480/2992 +f 1480/1480/2992 1483/1483/2993 1412/1412/2893 +f 1480/1480/2992 1412/1412/2893 1477/1477/2997 +f 1435/1435/2933 1445/1445/2932 1437/1437/2998 +f 1437/1437/2998 1436/1436/2934 1416/1416/2897 +f 1486/1486/2999 1487/1487/3000 1419/1419/2900 +f 1488/1488/3001 1489/1489/3002 1486/1486/2999 +f 1490/1490/3003 1489/1489/3002 1491/1491/3004 +f 1491/1491/3004 1489/1489/3002 1488/1488/3001 +f 1487/1487/3000 1490/1490/3003 1419/1419/2900 +f 1419/1419/2900 1490/1490/3003 1492/1492/3005 +f 1421/1421/2902 1493/1493/3006 1494/1494/3007 +f 1494/1494/3007 1419/1419/2900 1421/1421/2902 +f 1495/1495/3008 1493/1493/3006 1479/1479/2996 +f 1496/1496/3009 1497/1497/3010 1495/1495/3008 +f 1496/1496/3009 1495/1495/3008 1479/1479/2996 +f 1419/1419/2900 1494/1494/3007 1497/1497/3010 +f 1419/1419/2900 1497/1497/3010 1496/1496/3009 +f 1479/1479/2996 1493/1493/3006 1421/1421/2902 +f 1416/1416/2897 1435/1435/2933 1437/1437/2998 +f 1492/1492/3005 1490/1490/3003 1491/1491/3004 +f 1492/1492/3005 1491/1491/3004 1435/1435/2933 +f 1492/1492/3005 1435/1435/2933 1416/1416/2897 +f 1496/1496/3009 1498/1498/3011 1419/1419/2900 +f 1419/1419/2900 1498/1498/3011 1488/1488/3001 +f 1419/1419/2900 1488/1488/3001 1486/1486/2999 +f 1416/1416/2897 1415/1415/2896 1419/1419/2900 +f 1419/1419/2900 1492/1492/3005 1416/1416/2897 +f 1487/1487/3012 1499/1499/3013 1490/1490/3014 +f 1500/1500/3015 1490/1490/3014 1499/1499/3013 +f 1489/1489/3016 1490/1490/3016 1500/1500/3016 +f 1486/1486/3017 1501/1501/3017 1487/1487/3017 +f 1499/1499/3018 1487/1487/3018 1501/1501/3018 +f 1502/1502/3019 1483/1483/3019 1482/1482/3019 +f 1502/1502/3020 1484/1484/3020 1483/1483/3020 +f 1503/1503/3021 1484/1484/3021 1502/1502/3021 +f 1503/1503/3022 1485/1485/3022 1484/1484/3022 +f 1485/1485/3023 1503/1503/3023 1504/1504/3023 +f 1504/1504/3024 1481/1481/3024 1485/1485/3024 +f 1482/1482/3025 1481/1481/3026 1502/1502/3027 +f 1493/1493/3028 1505/1505/3028 1494/1494/3028 +f 1494/1494/3029 1505/1505/3029 1506/1506/3029 +f 1506/1506/3030 1497/1497/3030 1494/1494/3030 +f 1497/1497/3031 1506/1506/3031 1495/1495/3031 +f 1386/1386/3032 1388/1388/3032 1507/1507/3032 +f 1381/1381/3033 1507/1507/3033 1380/1380/3033 +f 1508/1508/3034 1509/1509/3035 1510/1510/3036 +f 1508/1508/3034 1510/1510/3036 1379/1379/2855 +f 1388/1388/3037 1511/1511/3038 1507/1507/3039 +f 1387/1387/3040 1511/1511/3038 1388/1388/3037 +f 1379/1379/2855 1380/1380/2857 1507/1507/3039 +f 1379/1379/2855 1507/1507/3039 1508/1508/3034 +f 1507/1507/3039 1511/1511/3038 1508/1508/3034 +f 1476/1476/2987 1475/1475/2986 1512/1512/3041 +f 1513/1513/3042 1514/1514/3042 1515/1515/3042 +f 1515/1515/3043 1514/1514/3043 1516/1516/3043 +f 1427/1427/2908 1517/1517/3044 1428/1428/2909 +f 1518/1518/3045 1519/1519/3046 1520/1520/3047 +f 1518/1518/3045 1521/1521/3048 1519/1519/3046 +f 1522/1522/3049 1521/1521/3049 1518/1518/3049 +f 1520/1520/3050 1519/1519/3050 1523/1523/3050 +f 1524/1524/3051 1525/1525/3052 1425/1425/3053 +f 1526/1526/3054 1527/1527/3055 1528/1528/3056 +f 1528/1528/3056 1527/1527/3055 1410/1410/2891 +f 1527/1527/3055 1529/1529/3057 1410/1410/2891 +f 1428/1428/3058 1529/1529/3057 1524/1524/3051 +f 1428/1428/3058 1524/1524/3051 1425/1425/3053 +f 1407/1407/2888 1426/1426/2925 1425/1425/3053 +f 1428/1428/3058 1410/1410/2891 1529/1529/3057 +f 1525/1525/3052 1526/1526/3054 1425/1425/3053 +f 1425/1425/3053 1526/1526/3054 1528/1528/3056 +f 1425/1425/3053 1528/1528/3056 1407/1407/2888 +f 1410/1410/2891 1405/1405/2886 1528/1528/3056 +f 1528/1528/3056 1405/1405/2886 1407/1407/2888 +f 1523/1523/3059 1519/1519/3060 1403/1403/2884 +f 1530/1530/3061 1531/1531/3062 1516/1516/3063 +f 1406/1406/2887 1531/1531/3062 1532/1532/3064 +f 1514/1514/3065 1533/1533/3066 1530/1530/3061 +f 1514/1514/3065 1530/1530/3061 1516/1516/3063 +f 1532/1532/3067 1533/1533/3067 1514/1514/3067 +f 1406/1406/2887 1532/1532/3064 1403/1403/2884 +f 1534/1534/3068 1535/1535/3069 1428/1428/3058 +f 1536/1536/3070 1406/1406/2887 1410/1410/2891 +f 1536/1536/3070 1410/1410/2891 1535/1535/3069 +f 1428/1428/3058 1537/1537/3071 1534/1534/3068 +f 1517/1517/3072 1538/1538/3073 1537/1537/3071 +f 1517/1517/3072 1537/1537/3071 1428/1428/3058 +f 1406/1406/2887 1536/1536/3070 1538/1538/3073 +f 1406/1406/2887 1538/1538/3073 1517/1517/3072 +f 1428/1428/3058 1535/1535/3069 1410/1410/2891 +f 1403/1403/2884 1539/1539/3074 1523/1523/3059 +f 1403/1403/2884 1532/1532/3064 1514/1514/3075 +f 1514/1514/3075 1513/1513/3076 1403/1403/2884 +f 1403/1403/2884 1513/1513/3076 1539/1539/3074 +f 1517/1517/3072 1516/1516/3063 1406/1406/2887 +f 1406/1406/2887 1516/1516/3063 1531/1531/3062 +f 1540/1540/3077 1532/1532/3078 1541/1541/3079 +f 1542/1542/3080 1532/1532/3080 1540/1540/3080 +f 1542/1542/3081 1533/1533/3081 1532/1532/3081 +f 1530/1530/3082 1541/1541/3082 1531/1531/3082 +f 1532/1532/3078 1531/1531/3083 1541/1541/3079 +f 1543/1543/3084 1526/1526/3084 1525/1525/3084 +f 1544/1544/3085 1526/1526/3085 1543/1543/3085 +f 1544/1544/3086 1527/1527/3086 1526/1526/3086 +f 1545/1545/3087 1527/1527/3087 1544/1544/3087 +f 1545/1545/3088 1529/1529/3088 1527/1527/3088 +f 1529/1529/3089 1545/1545/3089 1546/1546/3089 +f 1546/1546/3090 1524/1524/3090 1529/1529/3090 +f 1546/1546/3091 1525/1525/3092 1524/1524/3093 +f 1525/1525/3092 1546/1546/3091 1543/1543/3094 +f 1547/1547/3095 1536/1536/3096 1535/1535/3097 +f 1536/1536/3096 1547/1547/3095 1548/1548/3098 +f 1548/1548/3099 1538/1538/3099 1536/1536/3099 +f 1538/1538/3100 1548/1548/3100 1537/1537/3100 +f 1547/1547/3101 1535/1535/3101 1534/1534/3101 +f 1468/1468/2974 1470/1470/2976 1473/1473/2980 +f 1400/1400/2881 1549/1549/3102 1550/1550/3103 +f 1549/1549/3102 1551/1551/3104 1550/1550/3103 +f 1550/1550/3103 1551/1551/3104 1477/1477/2997 +f 1477/1477/2997 1551/1551/3104 1552/1552/3105 +f 1477/1477/2997 1552/1552/3105 1475/1475/3106 +f 1553/1553/3107 1475/1475/3106 1552/1552/3105 +f 1553/1553/3107 1549/1549/3102 1400/1400/2881 +f 1412/1412/2893 1550/1550/3103 1477/1477/2997 +f 1475/1475/3106 1553/1553/3107 1400/1400/2881 +f 1401/1401/2882 1400/1400/2881 1550/1550/3103 +f 1401/1401/2882 1550/1550/3103 1407/1407/2888 +f 1407/1407/2888 1550/1550/3103 1412/1412/2893 +f 1554/1554/3108 1521/1521/3109 1522/1522/3110 +f 1554/1554/3108 1522/1522/3110 1523/1523/3059 +f 1554/1554/3108 1523/1523/3059 1539/1539/3074 +f 1403/1403/2884 1519/1519/3060 1404/1404/2885 +f 1404/1404/2885 1519/1519/3060 1521/1521/3109 +f 1409/1409/2890 1555/1555/3111 1556/1556/3112 +f 1409/1409/2890 1556/1556/3112 1557/1557/3113 +f 1557/1557/3113 1556/1556/3112 1558/1558/3114 +f 1559/1559/3115 1555/1555/3111 1409/1409/2890 +f 1404/1404/2885 1559/1559/3115 1409/1409/2890 +f 1558/1558/3114 1560/1560/3116 1559/1559/3115 +f 1558/1558/3114 1556/1556/3112 1560/1560/3116 +f 1561/1561/3117 1562/1562/3118 1400/1400/2881 +f 1400/1400/2881 1562/1562/3118 1475/1475/3106 +f 1562/1562/3118 1563/1563/3119 1475/1475/3106 +f 1563/1563/3119 1512/1512/3120 1475/1475/3106 +f 1564/1564/3121 1565/1565/3122 1512/1512/3120 +f 1409/1409/2890 1565/1565/3122 1561/1561/3117 +f 1409/1409/2890 1561/1561/3117 1400/1400/2881 +f 1563/1563/3119 1564/1564/3121 1512/1512/3120 +f 1566/1566/3123 1409/1409/2890 1557/1557/3113 +f 1512/1512/3120 1565/1565/3122 1409/1409/2890 +f 1512/1512/3120 1409/1409/2890 1566/1566/3123 +f 1404/1404/2885 1521/1521/3109 1554/1554/3108 +f 1404/1404/2885 1554/1554/3108 1567/1567/3124 +f 1558/1558/3114 1559/1559/3115 1404/1404/2885 +f 1558/1558/3114 1404/1404/2885 1567/1567/3124 +f 1555/1555/3125 1568/1568/3125 1556/1556/3125 +f 1569/1569/3126 1559/1559/3126 1560/1560/3126 +f 1559/1559/3127 1569/1569/3127 1570/1570/3127 +f 1570/1570/3128 1555/1555/3128 1559/1559/3128 +f 1568/1568/3129 1555/1555/3129 1570/1570/3129 +f 1571/1571/3130 1552/1552/3130 1572/1572/3130 +f 1571/1571/3131 1553/1553/3131 1552/1552/3131 +f 1573/1573/3132 1553/1553/3132 1571/1571/3132 +f 1553/1553/3133 1573/1573/3133 1549/1549/3133 +f 1549/1549/3134 1573/1573/3134 1574/1574/3134 +f 1549/1549/3135 1574/1574/3135 1551/1551/3135 +f 1551/1551/3136 1574/1574/3136 1572/1572/3136 +f 1572/1572/3137 1552/1552/3137 1551/1551/3137 +f 1575/1575/3138 1565/1565/3138 1564/1564/3138 +f 1565/1565/3139 1575/1575/3140 1576/1576/3141 +f 1576/1576/3141 1561/1561/3142 1565/1565/3139 +f 1562/1562/3143 1561/1561/3143 1576/1576/3143 +f 1562/1562/3118 1576/1576/3144 1563/1563/3119 +f 1508/1508/3034 1577/1577/3145 1509/1509/3035 +f 1508/1508/3034 1511/1511/3038 1577/1577/3145 +f 1393/1393/3146 1578/1578/3147 1579/1579/3148 +f 1393/1393/3146 1579/1579/3148 1372/1372/3149 +f 1375/1375/3150 1580/1580/3151 1392/1392/3152 +f 1392/1392/3152 1580/1580/3151 1581/1581/3153 +f 1372/1372/573 1375/1375/573 1393/1393/573 +f 1393/1393/573 1375/1375/573 1392/1392/573 +f 1582/1582/3154 1583/1583/3155 1584/1584/3156 +f 1582/1582/3154 1584/1584/3156 1585/1585/3157 +f 1585/1585/3158 1411/1411/3159 1586/1586/3160 +f 1586/1586/3161 1411/1411/3162 1587/1587/3163 +f 1586/1586/3161 1587/1587/3163 1588/1588/3164 +f 1585/1585/3165 1584/1584/3165 1422/1422/3165 +f 1585/1585/3158 1422/1422/3166 1411/1411/3159 +f 1588/1588/3164 1587/1587/3163 1413/1413/3167 +f 1589/1589/3168 1588/1588/3164 1420/1420/3169 +f 1588/1588/3164 1413/1413/3167 1420/1420/3169 +f 1589/1589/3168 1420/1420/3169 1418/1418/3170 +f 1589/1589/3171 1418/1418/3172 1582/1582/3173 +f 1582/1582/3173 1418/1418/3172 1583/1583/3174 +f 1584/1584/3156 1583/1583/3155 1415/1415/2896 +f 1584/1584/3175 1415/1415/3175 1422/1422/3175 +f 1587/1587/3176 1411/1411/3176 1413/1413/3176 +f 1418/1418/2899 1415/1415/2896 1583/1583/3155 +f 1402/1402/2883 1401/1401/2882 1408/1408/2889 +f 1408/1408/2889 1405/1405/2886 1402/1402/2883 +f 1393/1393/3177 1395/1395/3177 1578/1578/3177 +f 1391/1391/3178 1392/1392/3178 1581/1581/3178 +f 1375/1375/3179 1377/1377/3179 1580/1580/3179 +f 1373/1373/3180 1372/1372/3180 1579/1579/3180 +f 1473/1473/3181 1470/1470/3182 1396/1396/3183 +f 1396/1396/3183 1397/1397/3184 1473/1473/3181 +f 1396/1396/3183 1470/1470/3182 1395/1395/3185 +f 1395/1395/3186 1470/1470/3187 1578/1578/3188 +f 1469/1469/3189 1578/1578/3188 1470/1470/3187 +f 1579/1579/3190 1578/1578/3188 1469/1469/3189 +f 1373/1373/3191 1579/1579/3191 1469/1469/3191 +f 1472/1472/3192 1383/1383/3193 1471/1471/3194 +f 1469/1469/3195 1385/1385/3196 1373/1373/3197 +f 1385/1385/3196 1469/1469/3195 1471/1471/3194 +f 1471/1471/3194 1383/1383/3193 1385/1385/3196 +f 1378/1378/3198 1379/1379/2855 1510/1510/3036 +f 1378/1378/3198 1510/1510/3036 1509/1509/3199 +f 1378/1378/3198 1509/1509/3199 1377/1377/3200 +f 1509/1509/3201 1580/1580/3201 1377/1377/3201 +f 1581/1581/3202 1580/1580/3203 1509/1509/3204 +f 1509/1509/3204 1577/1577/3205 1581/1581/3202 +f 1577/1577/3205 1391/1391/3206 1581/1581/3202 +f 1391/1391/3207 1577/1577/3207 1390/1390/3207 +f 1511/1511/3208 1387/1387/2866 1390/1390/2865 +f 1511/1511/3208 1390/1390/2865 1577/1577/3209 +f 1543/1543/5 1546/1546/5 1545/1545/5 +f 1544/1544/5 1543/1543/5 1545/1545/5 +f 1537/1537/3071 1548/1548/3210 1547/1547/3211 +f 1547/1547/3211 1534/1534/3068 1537/1537/3071 +f 1530/1530/3061 1533/1533/3066 1541/1541/3212 +f 1533/1533/3066 1540/1540/3213 1541/1541/3212 +f 1533/1533/3066 1542/1542/3214 1540/1540/3213 +f 1520/1520/3215 1523/1523/3059 1522/1522/3110 +f 1518/1518/3216 1520/1520/3215 1522/1522/3110 +f 1568/1568/3217 1560/1560/3218 1556/1556/3219 +f 1570/1570/3220 1569/1569/3221 1560/1560/3218 +f 1570/1570/3220 1560/1560/3218 1568/1568/3217 +f 1563/1563/3119 1576/1576/3222 1575/1575/3223 +f 1563/1563/3119 1575/1575/3223 1564/1564/3121 +f 1574/1574/3224 1573/1573/3225 1572/1572/3225 +f 1572/1572/3225 1573/1573/3225 1571/1571/3226 +f 1502/1502/3027 1504/1504/3227 1503/1503/3228 +f 1502/1502/3027 1481/1481/3026 1504/1504/3227 +f 1506/1506/3229 1505/1505/3230 1495/1495/3008 +f 1505/1505/3230 1493/1493/3006 1495/1495/3008 +f 1500/1500/3231 1499/1499/3232 1489/1489/3233 +f 1499/1499/3232 1501/1501/3234 1489/1489/3233 +f 1489/1489/3233 1501/1501/3234 1486/1486/3235 +f 1445/1445/2932 1440/1440/2931 1438/1438/3236 +f 1445/1445/2932 1438/1438/3236 1437/1437/2998 +f 1447/1447/3237 1459/1459/3238 1450/1450/2940 +f 1450/1450/2940 1459/1459/3238 1453/1453/2943 +f 1459/1459/3238 1460/1460/3239 1453/1453/2943 +f 1455/1455/2945 1466/1466/3240 1464/1464/3241 +f 1456/1456/2946 1455/1455/2945 1464/1464/3241 +f 1466/1466/3240 1465/1465/3242 1464/1464/3241 +f 1461/1461/3243 1443/1443/3244 1462/1462/3245 +f 1443/1443/3244 1463/1463/3246 1462/1462/3245 +f 1479/1479/3247 1498/1498/3248 1496/1496/3249 +f 1431/1431/3250 1432/1432/3251 1458/1458/3252 +f 1517/1517/3253 1427/1427/3254 1516/1516/3255 +f 1431/1431/3250 1458/1458/3252 1448/1448/3256 +f 1448/1448/3256 1382/1382/3257 1431/1431/3250 +f 1516/1516/3255 1427/1427/3254 1515/1515/3258 +f 1477/1477/3259 1386/1386/3260 1507/1507/3261 +f 1429/1429/3262 1431/1431/3250 1382/1382/3257 +f 1382/1382/3257 1426/1426/3263 1429/1429/3262 +f 1426/1426/3263 1382/1382/3257 1467/1467/3264 +f 1399/1399/3265 1424/1424/3266 1467/1467/3264 +f 1427/1427/3254 1424/1424/3266 1399/1399/3265 +f 1424/1424/3266 1426/1426/3263 1467/1467/3264 +f 1474/1474/3267 1476/1476/3268 1386/1386/3260 +f 1399/1399/3265 1515/1515/3258 1427/1427/3254 +f 1382/1382/3257 1448/1448/3256 1449/1449/3269 +f 1382/1382/3257 1433/1433/2915 1374/1374/3270 +f 1433/1433/2915 1382/1382/3257 1449/1449/3269 +f 1513/1513/3271 1394/1394/3272 1554/1554/3273 +f 1374/1374/3270 1433/1433/2915 1435/1435/2917 +f 1539/1539/3274 1513/1513/3271 1554/1554/3273 +f 1435/1435/2917 1376/1376/3275 1374/1374/3270 +f 1554/1554/3273 1394/1394/3272 1389/1389/3276 +f 1389/1389/3276 1567/1567/3277 1554/1554/3273 +f 1399/1399/3265 1394/1394/3272 1513/1513/3271 +f 1386/1386/3260 1558/1558/3278 1389/1389/3276 +f 1478/1478/3279 1498/1498/3248 1479/1479/3247 +f 1376/1376/3275 1491/1491/3280 1381/1381/3281 +f 1558/1558/3278 1567/1567/3277 1389/1389/3276 +f 1376/1376/3275 1435/1435/2917 1491/1491/3280 +f 1381/1381/3281 1480/1480/3282 1507/1507/3261 +f 1480/1480/3282 1477/1477/3259 1507/1507/3261 +f 1515/1515/3258 1399/1399/3265 1513/1513/3271 +f 1478/1478/3279 1381/1381/3281 1488/1488/3283 +f 1386/1386/3260 1477/1477/3259 1474/1474/3267 +f 1558/1558/3278 1386/1386/3260 1476/1476/3268 +f 1480/1480/3282 1381/1381/3281 1478/1478/3279 +f 1488/1488/3283 1381/1381/3281 1491/1491/3280 +f 1558/1558/3278 1476/1476/3268 1557/1557/3284 +f 1498/1498/3248 1478/1478/3279 1488/1488/3283 +f 1476/1476/3268 1566/1566/3285 1557/1557/3284 +f 1476/1476/3268 1512/1512/3286 1566/1566/3285 +f 1585/1585/3287 1586/1586/3288 1582/1582/3289 +f 1589/1589/3290 1582/1582/3289 1586/1586/3288 +f 1589/1589/3290 1586/1586/3288 1588/1588/3291 +f 1590/1590/3292 1591/1591/3293 1592/1592/3294 +f 1593/1593/3295 1594/1594/3296 1595/1595/3297 +f 1593/1593/3295 1595/1595/3297 1596/1596/1211 +f 1597/1597/3298 1598/1598/3299 1594/1594/3296 +f 1599/1599/3300 1600/1600/3301 1601/1601/3302 +f 1596/1596/1211 1600/1600/3301 1599/1599/3300 +f 1599/1599/3300 1601/1601/3302 1590/1590/3292 +f 1590/1590/3292 1601/1601/3302 1591/1591/3293 +f 1596/1596/1211 1595/1595/3297 1600/1600/3301 +f 1597/1597/3298 1594/1594/3296 1593/1593/3295 +f 1592/1592/3294 1591/1591/3293 1597/1597/3298 +f 1597/1597/3298 1591/1591/3293 1598/1598/3299 +f 1602/1602/3303 1601/1601/3304 1603/1603/3305 +f 1603/1603/3305 1601/1601/3304 1600/1600/3306 +f 1603/1603/3307 1600/1600/3307 1604/1604/3307 +f 1604/1604/3308 1600/1600/3308 1595/1595/3308 +f 1604/1604/3309 1595/1595/3310 1605/1605/3311 +f 1605/1605/3311 1595/1595/3310 1594/1594/3312 +f 1605/1605/3313 1594/1594/3314 1606/1606/3315 +f 1606/1606/3315 1594/1594/3314 1598/1598/3316 +f 1606/1606/3317 1598/1598/3318 1607/1607/3319 +f 1607/1607/3319 1598/1598/3318 1591/1591/3320 +f 1607/1607/3321 1591/1591/3322 1601/1601/3323 +f 1607/1607/3321 1601/1601/3323 1602/1602/3324 +f 1608/1608/573 1602/1602/3325 1609/1609/3326 +f 1608/1608/573 1607/1607/3326 1602/1602/3325 +f 1608/1608/573 1606/1606/3327 1607/1607/3326 +f 1603/1603/3328 1604/1604/3329 1610/1610/3329 +f 1610/1610/3329 1605/1605/3330 1606/1606/3327 +f 1610/1610/3329 1606/1606/3327 1608/1608/573 +f 1610/1610/3329 1604/1604/3329 1605/1605/3330 +f 1609/1609/3326 1602/1602/3325 1603/1603/573 +f 1611/1611/3331 1609/1609/3332 1612/1612/3333 +f 1612/1612/3333 1609/1609/3332 1603/1603/3334 +f 1612/1612/3335 1603/1603/3335 1613/1613/3335 +f 1613/1613/3336 1603/1603/3337 1610/1610/3338 +f 1613/1613/3336 1610/1610/3338 1614/1614/3339 +f 1614/1614/3340 1610/1610/3341 1608/1608/3342 +f 1614/1614/3340 1608/1608/3342 1615/1615/3343 +f 1615/1615/3344 1608/1608/3345 1611/1611/3346 +f 1611/1611/3346 1608/1608/3345 1609/1609/3347 +f 1615/1615/3348 1613/1613/3349 1614/1614/3350 +f 1612/1612/3351 1613/1613/3349 1611/1611/3352 +f 1615/1615/3348 1611/1611/3352 1613/1613/3349 +f 1596/1596/1211 1599/1599/3300 1593/1593/3295 +f 1593/1593/3295 1599/1599/3300 1590/1590/3292 +f 1593/1593/3295 1590/1590/3292 1597/1597/3298 +f 1597/1597/3298 1590/1590/3292 1592/1592/3294 +f 1616/1616/3353 1617/1617/3353 1618/1618/3353 +f 1619/1619/3354 1620/1620/3354 1616/1616/3354 +f 1621/1621/3355 1622/1622/3356 1623/1623/3357 +f 1623/1623/3357 1624/1624/3358 1621/1621/3355 +f 1625/1625/3359 1626/1626/3360 1622/1622/3361 +f 1622/1622/3361 1626/1626/3360 1623/1623/3362 +f 1623/1623/3363 1626/1626/3364 1624/1624/3365 +f 1624/1624/3365 1626/1626/3364 1627/1627/3366 +f 1624/1624/3367 1627/1627/3367 1628/1628/3367 +f 1624/1624/3368 1628/1628/3368 1621/1621/3368 +f 1621/1621/3369 1628/1628/3370 1625/1625/3371 +f 1621/1621/3369 1625/1625/3371 1622/1622/3372 +f 1625/1625/3373 1629/1629/3374 1626/1626/3375 +f 1627/1627/3376 1630/1630/3377 1628/1628/3378 +f 1626/1626/3375 1629/1629/3374 1627/1627/3376 +f 1627/1627/3376 1629/1629/3374 1630/1630/3377 +f 1625/1625/3373 1631/1631/3379 1629/1629/3374 +f 1628/1628/3378 1630/1630/3377 1632/1632/3380 +f 1628/1628/3378 1632/1632/3380 1631/1631/3379 +f 1628/1628/3378 1631/1631/3379 1625/1625/3373 +f 1618/1618/3381 1631/1631/3381 1619/1619/3381 +f 1619/1619/3382 1631/1631/3383 1620/1620/3384 +f 1620/1620/3384 1631/1631/3383 1632/1632/3385 +f 1620/1620/3386 1632/1632/3387 1616/1616/3388 +f 1616/1616/3388 1632/1632/3387 1630/1630/3389 +f 1616/1616/3390 1630/1630/3390 1617/1617/3390 +f 1617/1617/3391 1630/1630/3391 1629/1629/3391 +f 1617/1617/3392 1629/1629/3392 1618/1618/3392 +f 1618/1618/3393 1629/1629/3393 1631/1631/3393 +f 1633/1633/3394 1616/1616/3394 1634/1634/3394 +f 1619/1619/3395 1616/1616/3395 1633/1633/3395 +f 1634/1634/3396 1619/1619/3397 1633/1633/3398 +f 1618/1618/3399 1619/1619/3397 1634/1634/3396 +f 1616/1616/3400 1618/1618/3400 1634/1634/3400 +f 1635/1635/3401 1636/1636/3401 1637/1637/3401 +f 1638/1638/3402 1639/1639/3402 1636/1636/3402 +f 1640/1640/3403 1641/1641/3404 1642/1642/3405 +f 1643/1643/3406 1640/1640/3403 1642/1642/3405 +f 1642/1642/3407 1644/1644/3408 1643/1643/3409 +f 1644/1644/3408 1645/1645/3410 1643/1643/3409 +f 1643/1643/3411 1645/1645/3411 1646/1646/3411 +f 1643/1643/3412 1646/1646/3412 1640/1640/3412 +f 1640/1640/3413 1646/1646/3414 1647/1647/3415 +f 1640/1640/3413 1647/1647/3415 1641/1641/3416 +f 1647/1647/3417 1644/1644/3418 1641/1641/3419 +f 1641/1641/3419 1644/1644/3418 1642/1642/3420 +f 1645/1645/3421 1648/1648/3422 1649/1649/3423 +f 1644/1644/3424 1648/1648/3422 1645/1645/3421 +f 1646/1646/3425 1650/1650/3426 1647/1647/3427 +f 1647/1647/3427 1650/1650/3426 1651/1651/3428 +f 1645/1645/3421 1649/1649/3423 1646/1646/3425 +f 1644/1644/3424 1652/1652/3429 1648/1648/3422 +f 1647/1647/3427 1651/1651/3428 1644/1644/3424 +f 1646/1646/3425 1649/1649/3423 1650/1650/3426 +f 1644/1644/3424 1651/1651/3428 1652/1652/3429 +f 1638/1638/3430 1652/1652/3431 1639/1639/3432 +f 1639/1639/3432 1652/1652/3431 1651/1651/3433 +f 1639/1639/3434 1651/1651/3435 1636/1636/3436 +f 1636/1636/3436 1651/1651/3435 1650/1650/3437 +f 1636/1636/3438 1650/1650/3439 1649/1649/3440 +f 1636/1636/3438 1649/1649/3440 1637/1637/3441 +f 1637/1637/3442 1649/1649/3443 1635/1635/3444 +f 1635/1635/3444 1649/1649/3443 1648/1648/3445 +f 1635/1635/3446 1648/1648/3447 1638/1638/3448 +f 1638/1638/3448 1648/1648/3447 1652/1652/3449 +f 1636/1636/3450 1635/1635/3450 1653/1653/3450 +f 1654/1654/3451 1636/1636/3451 1653/1653/3451 +f 1638/1638/3452 1636/1636/3452 1654/1654/3452 +f 1653/1653/3453 1638/1638/3454 1654/1654/3455 +f 1635/1635/3456 1638/1638/3454 1653/1653/3453 +f 1655/1655/3457 1656/1656/3457 1657/1657/3457 +f 1657/1657/3458 1658/1658/3459 1659/1659/3460 +f 1657/1657/3458 1659/1659/3460 1660/1660/3461 +f 1661/1661/3462 1662/1662/3463 1663/1663/3464 +f 1663/1663/3465 1664/1664/3465 1661/1661/3465 +f 1664/1664/3466 1665/1665/3466 1661/1661/3466 +f 1661/1661/3467 1665/1665/3467 1666/1666/3467 +f 1661/1661/3468 1666/1666/3468 1662/1662/3468 +f 1662/1662/3469 1666/1666/3470 1667/1667/3471 +f 1667/1667/3471 1666/1666/3470 1668/1668/3472 +f 1668/1668/3473 1664/1664/3474 1667/1667/3475 +f 1667/1667/3475 1664/1664/3474 1663/1663/3476 +f 1668/1668/3477 1669/1669/3478 1664/1664/3479 +f 1664/1664/3479 1669/1669/3478 1665/1665/3480 +f 1668/1668/3477 1670/1670/3481 1669/1669/3478 +f 1666/1666/3482 1670/1670/3481 1668/1668/3477 +f 1665/1665/3483 1671/1671/3483 1666/1666/3483 +f 1666/1666/3484 1671/1671/3485 1670/1670/3486 +f 1656/1656/3487 1665/1665/3488 1669/1669/3489 +f 1656/1656/3490 1669/1669/3490 1657/1657/3490 +f 1657/1657/3491 1669/1669/3491 1670/1670/3491 +f 1657/1657/3492 1670/1670/3492 1658/1658/3492 +f 1658/1658/3493 1670/1670/3486 1659/1659/3494 +f 1659/1659/3494 1670/1670/3486 1671/1671/3485 +f 1659/1659/3495 1671/1671/3495 1660/1660/3495 +f 1660/1660/3496 1671/1671/3497 1665/1665/3498 +f 1660/1660/3496 1665/1665/3498 1655/1655/3499 +f 1655/1655/3500 1665/1665/3488 1656/1656/3487 +f 1657/1657/3501 1660/1660/3501 1672/1672/3501 +f 1673/1673/3502 1657/1657/3502 1672/1672/3502 +f 1655/1655/3503 1657/1657/3503 1673/1673/3503 +f 1672/1672/3504 1655/1655/3505 1673/1673/3506 +f 1660/1660/3507 1655/1655/3505 1672/1672/3504 +f 1667/1667/3508 1663/1663/3464 1662/1662/3463 +f 1674/1674/3509 1675/1675/3509 1676/1676/3509 +f 1677/1677/3510 1678/1678/3511 1679/1679/3512 +f 1679/1679/3512 1680/1680/3513 1677/1677/3510 +f 1678/1678/3514 1681/1681/3514 1679/1679/3514 +f 1679/1679/3515 1681/1681/3515 1682/1682/3515 +f 1679/1679/3516 1682/1682/3516 1680/1680/3516 +f 1680/1680/3517 1682/1682/3517 1683/1683/3517 +f 1680/1680/3518 1683/1683/3518 1677/1677/3518 +f 1683/1683/3519 1684/1684/3519 1677/1677/3519 +f 1677/1677/3520 1684/1684/3520 1678/1678/3520 +f 1678/1678/3521 1684/1684/3521 1681/1681/3521 +f 1684/1684/3522 1685/1685/3523 1681/1681/3524 +f 1684/1684/3522 1686/1686/3525 1685/1685/3523 +f 1687/1687/3526 1683/1683/3527 1682/1682/3528 +f 1681/1681/3524 1688/1688/3529 1682/1682/3528 +f 1682/1682/3528 1688/1688/3529 1687/1687/3526 +f 1683/1683/3530 1686/1686/3525 1684/1684/3522 +f 1681/1681/3524 1685/1685/3523 1688/1688/3529 +f 1675/1675/3531 1685/1685/3532 1676/1676/3533 +f 1676/1676/3533 1685/1685/3532 1686/1686/3534 +f 1676/1676/3535 1686/1686/3535 1689/1689/3535 +f 1689/1689/3536 1686/1686/3536 1683/1683/3536 +f 1689/1689/3537 1683/1683/3538 1687/1687/3539 +f 1689/1689/3537 1687/1687/3539 1690/1690/3540 +f 1690/1690/3541 1687/1687/3542 1674/1674/3543 +f 1674/1674/3543 1687/1687/3542 1688/1688/3544 +f 1674/1674/3545 1688/1688/3546 1685/1685/3547 +f 1674/1674/3545 1685/1685/3547 1675/1675/3548 +f 1689/1689/3549 1690/1690/3550 1691/1691/3551 +f 1691/1691/3551 1690/1690/3550 1692/1692/3552 +f 1676/1676/3553 1689/1689/3553 1691/1691/3553 +f 1692/1692/3554 1676/1676/3554 1691/1691/3554 +f 1674/1674/3555 1676/1676/3555 1692/1692/3555 +f 1690/1690/3556 1674/1674/3556 1692/1692/3556 +f 1693/1693/3557 1694/1694/3557 1695/1695/3557 +f 1696/1696/3558 1697/1697/3559 1698/1698/3560 +f 1696/1696/3558 1699/1699/3561 1697/1697/3559 +f 1696/1696/3562 1700/1700/3563 1701/1701/3564 +f 1696/1696/3562 1701/1701/3564 1699/1699/3565 +f 1699/1699/3566 1701/1701/3567 1702/1702/3568 +f 1699/1699/3566 1702/1702/3568 1697/1697/3569 +f 1697/1697/3570 1702/1702/3571 1703/1703/3572 +f 1697/1697/3570 1703/1703/3572 1698/1698/3573 +f 1698/1698/3574 1703/1703/3575 1700/1700/3576 +f 1698/1698/3574 1700/1700/3576 1696/1696/3577 +f 1700/1700/3578 1704/1704/3579 1701/1701/3580 +f 1700/1700/3578 1705/1705/3581 1704/1704/3579 +f 1703/1703/3582 1705/1705/3581 1700/1700/3578 +f 1702/1702/3583 1706/1706/3584 1703/1703/3582 +f 1703/1703/3582 1706/1706/3584 1705/1705/3581 +f 1702/1702/3583 1707/1707/3585 1706/1706/3584 +f 1701/1701/3580 1704/1704/3579 1708/1708/3586 +f 1701/1701/3580 1708/1708/3586 1707/1707/3585 +f 1701/1701/3580 1707/1707/3585 1702/1702/3583 +f 1709/1709/3587 1704/1704/3587 1710/1710/3587 +f 1710/1710/3588 1704/1704/3588 1705/1705/3588 +f 1710/1710/3589 1705/1705/3589 1693/1693/3589 +f 1693/1693/3590 1705/1705/3590 1706/1706/3590 +f 1693/1693/3591 1706/1706/3591 1694/1694/3591 +f 1694/1694/3592 1706/1706/3592 1707/1707/3592 +f 1694/1694/3593 1707/1707/3593 1695/1695/3593 +f 1695/1695/3594 1707/1707/3594 1708/1708/3594 +f 1695/1695/3595 1708/1708/3595 1709/1709/3595 +f 1709/1709/3596 1708/1708/3596 1704/1704/3596 +f 1693/1693/3597 1695/1695/3597 1711/1711/3597 +f 1711/1711/3598 1695/1695/3598 1712/1712/3598 +f 1710/1710/3599 1693/1693/3599 1712/1712/3599 +f 1712/1712/3600 1693/1693/3600 1711/1711/3600 +f 1709/1709/3601 1710/1710/3601 1712/1712/3601 +f 1695/1695/3602 1709/1709/3602 1712/1712/3602 +f 1713/1713/3603 1714/1714/3603 1715/1715/3603 +f 1716/1716/3604 1717/1717/3604 1718/1718/3604 +f 1716/1716/3605 1719/1719/3605 1717/1717/3605 +f 1719/1719/3606 1720/1720/3606 1717/1717/3606 +f 1717/1717/3607 1720/1720/3607 1718/1718/3607 +f 1718/1718/3608 1720/1720/3608 1721/1721/3608 +f 1718/1718/3609 1721/1721/3610 1716/1716/3611 +f 1716/1716/3611 1721/1721/3610 1719/1719/3612 +f 1719/1719/3613 1722/1722/3614 1723/1723/3615 +f 1720/1720/3616 1724/1724/3617 1725/1725/3618 +f 1723/1723/3615 1724/1724/3617 1719/1719/3613 +f 1719/1719/3613 1724/1724/3617 1720/1720/3616 +f 1725/1725/3618 1726/1726/3619 1720/1720/3616 +f 1720/1720/3616 1726/1726/3619 1721/1721/3620 +f 1721/1721/3620 1726/1726/3619 1722/1722/3614 +f 1721/1721/3620 1722/1722/3614 1719/1719/3613 +f 1727/1727/3621 1723/1723/3621 1722/1722/3621 +f 1727/1727/3622 1722/1722/3623 1713/1713/3624 +f 1713/1713/3624 1722/1722/3623 1726/1726/3625 +f 1713/1713/3626 1726/1726/3627 1725/1725/3628 +f 1713/1713/3626 1725/1725/3628 1714/1714/3629 +f 1714/1714/3630 1725/1725/3630 1724/1724/3630 +f 1714/1714/3631 1724/1724/3631 1715/1715/3631 +f 1715/1715/3632 1724/1724/3632 1723/1723/3632 +f 1715/1715/3633 1723/1723/3633 1727/1727/3633 +f 1727/1727/3634 1713/1713/3634 1728/1728/3634 +f 1728/1728/3635 1713/1713/3635 1729/1729/3635 +f 1715/1715/3636 1727/1727/3636 1728/1728/3636 +f 1729/1729/3637 1715/1715/3637 1728/1728/3637 +f 1713/1713/3638 1715/1715/3638 1729/1729/3638 +f 1730/1730/3639 1731/1731/3639 1732/1732/3639 +f 1733/1733/3640 1734/1734/3640 1730/1730/3640 +f 1735/1735/3641 1736/1736/3641 1737/1737/3641 +f 1736/1736/3642 1738/1738/3642 1737/1737/3642 +f 1737/1737/3643 1738/1738/3643 1739/1739/3643 +f 1737/1737/3644 1739/1739/3644 1735/1735/3644 +f 1735/1735/3645 1739/1739/3645 1740/1740/3645 +f 1735/1735/3646 1740/1740/3646 1736/1736/3646 +f 1736/1736/3647 1740/1740/3647 1738/1738/3647 +f 1738/1738/3648 1741/1741/3649 1739/1739/3650 +f 1739/1739/3650 1741/1741/3649 1742/1742/3651 +f 1738/1738/3652 1743/1743/3652 1741/1741/3652 +f 1740/1740/3653 1744/1744/3654 1743/1743/3655 +f 1740/1740/3653 1742/1742/3651 1744/1744/3654 +f 1739/1739/3650 1742/1742/3651 1740/1740/3653 +f 1740/1740/3653 1743/1743/3655 1738/1738/3656 +f 1730/1730/3657 1743/1743/3657 1731/1731/3657 +f 1731/1731/3658 1743/1743/3658 1744/1744/3658 +f 1731/1731/3659 1744/1744/3659 1732/1732/3659 +f 1732/1732/3660 1744/1744/3660 1742/1742/3660 +f 1732/1732/3661 1742/1742/3661 1733/1733/3661 +f 1733/1733/3662 1742/1742/3663 1741/1741/3664 +f 1733/1733/3662 1741/1741/3664 1734/1734/3665 +f 1734/1734/3666 1741/1741/3667 1743/1743/3668 +f 1734/1734/3666 1743/1743/3668 1730/1730/3669 +f 1732/1732/3670 1733/1733/3670 1745/1745/3670 +f 1730/1730/3671 1732/1732/3671 1746/1746/3671 +f 1746/1746/3672 1732/1732/3672 1745/1745/3672 +f 1733/1733/3673 1730/1730/3673 1745/1745/3673 +f 1745/1745/3674 1730/1730/3674 1746/1746/3674 +f 1747/1747/3675 1748/1748/3675 1749/1749/3675 +f 1750/1750/3676 1751/1751/3676 1752/1752/3676 +f 1752/1752/3677 1753/1753/3677 1754/1754/3677 +f 1752/1752/3678 1754/1754/3679 1750/1750/3680 +f 1750/1750/3680 1754/1754/3679 1755/1755/3681 +f 1755/1755/3682 1756/1756/3683 1750/1750/3684 +f 1750/1750/3684 1756/1756/3683 1751/1751/3685 +f 1756/1756/3686 1753/1753/3686 1751/1751/3686 +f 1751/1751/3687 1753/1753/3687 1752/1752/3687 +f 1756/1756/3688 1757/1757/3689 1753/1753/3690 +f 1753/1753/3690 1758/1758/3691 1754/1754/3692 +f 1753/1753/3690 1759/1759/3693 1758/1758/3691 +f 1756/1756/3688 1760/1760/3694 1757/1757/3689 +f 1754/1754/3692 1758/1758/3691 1755/1755/3695 +f 1753/1753/3690 1757/1757/3689 1759/1759/3693 +f 1755/1755/3696 1760/1760/3694 1756/1756/3688 +f 1747/1747/3697 1759/1759/3697 1757/1757/3697 +f 1747/1747/3698 1757/1757/3698 1748/1748/3698 +f 1748/1748/3699 1757/1757/3699 1760/1760/3699 +f 1748/1748/3700 1760/1760/3700 1749/1749/3700 +f 1749/1749/3701 1760/1760/3702 1761/1761/3703 +f 1761/1761/3703 1760/1760/3702 1755/1755/3704 +f 1761/1761/3705 1755/1755/3706 1758/1758/3707 +f 1761/1761/3705 1758/1758/3707 1762/1762/3708 +f 1762/1762/3709 1758/1758/3709 1759/1759/3709 +f 1762/1762/3710 1759/1759/3710 1747/1747/3710 +f 1749/1749/3711 1761/1761/3711 1763/1763/3711 +f 1747/1747/3712 1749/1749/3713 1764/1764/3714 +f 1764/1764/3714 1749/1749/3713 1763/1763/3715 +f 1762/1762/3716 1747/1747/3716 1764/1764/3716 +f 1761/1761/3717 1762/1762/3718 1763/1763/3719 +f 1763/1763/3719 1762/1762/3718 1764/1764/3720 +f 1765/1765/3721 1766/1766/3721 1767/1767/3721 +f 1767/1767/3722 1768/1768/3722 1769/1769/3722 +f 1770/1770/3723 1771/1771/3723 1772/1772/3723 +f 1772/1772/3724 1773/1773/3724 1774/1774/3724 +f 1772/1772/3725 1774/1774/3725 1770/1770/3725 +f 1770/1770/3726 1774/1774/3726 1775/1775/3726 +f 1770/1770/3727 1775/1775/3727 1771/1771/3727 +f 1771/1771/3728 1775/1775/3728 1773/1773/3728 +f 1771/1771/3729 1773/1773/3729 1772/1772/3729 +f 1773/1773/3730 1776/1776/3731 1774/1774/3732 +f 1773/1773/3730 1777/1777/3733 1776/1776/3731 +f 1775/1775/3734 1777/1777/3733 1773/1773/3730 +f 1775/1775/3734 1778/1778/3735 1777/1777/3733 +f 1774/1774/3732 1776/1776/3731 1779/1779/3736 +f 1775/1775/3734 1780/1780/3737 1778/1778/3735 +f 1774/1774/3732 1780/1780/3737 1775/1775/3734 +f 1774/1774/3732 1779/1779/3736 1780/1780/3737 +f 1767/1767/3738 1777/1777/3739 1768/1768/3740 +f 1768/1768/3741 1777/1777/3742 1778/1778/3743 +f 1768/1768/3741 1778/1778/3743 1769/1769/3744 +f 1769/1769/3745 1778/1778/3746 1765/1765/3747 +f 1765/1765/3747 1778/1778/3746 1780/1780/3748 +f 1765/1765/3749 1780/1780/3750 1779/1779/3751 +f 1765/1765/3749 1779/1779/3751 1766/1766/3752 +f 1766/1766/3753 1779/1779/3754 1767/1767/3755 +f 1767/1767/3755 1779/1779/3754 1776/1776/3756 +f 1767/1767/3738 1776/1776/3757 1777/1777/3739 +f 1769/1769/3758 1765/1765/3759 1781/1781/3760 +f 1782/1782/3761 1769/1769/3758 1781/1781/3760 +f 1767/1767/3762 1769/1769/3762 1782/1782/3762 +f 1765/1765/3763 1767/1767/3763 1781/1781/3763 +f 1781/1781/3764 1767/1767/3764 1782/1782/3764 +f 1783/1783/3765 1784/1784/3766 1785/1785/3767 +f 1785/1785/3768 1786/1786/3768 1787/1787/3768 +f 1783/1783/3765 1788/1788/3769 1784/1784/3766 +f 1783/1783/3765 1787/1787/3770 1788/1788/3769 +f 1789/1789/3771 1790/1790/3772 1791/1791/3773 +f 1792/1792/3774 1793/1793/3774 1794/1794/3774 +f 1794/1794/3775 1793/1793/3775 1791/1791/3775 +f 1791/1791/3776 1793/1793/3777 1789/1789/3778 +f 1789/1789/3778 1793/1793/3777 1795/1795/3779 +f 1789/1789/3780 1795/1795/3781 1790/1790/3782 +f 1790/1790/3782 1795/1795/3781 1792/1792/3783 +f 1790/1790/3784 1792/1792/3784 1794/1794/3784 +f 1795/1795/3785 1796/1796/3786 1797/1797/3787 +f 1792/1792/3788 1798/1798/3789 1793/1793/3790 +f 1795/1795/3785 1797/1797/3787 1792/1792/3788 +f 1793/1793/3790 1799/1799/3791 1795/1795/3785 +f 1795/1795/3785 1799/1799/3791 1796/1796/3786 +f 1792/1792/3788 1800/1800/3792 1798/1798/3789 +f 1792/1792/3788 1797/1797/3787 1800/1800/3792 +f 1793/1793/3790 1798/1798/3789 1799/1799/3791 +f 1786/1786/3793 1798/1798/3794 1787/1787/3795 +f 1787/1787/3795 1798/1798/3794 1800/1800/3796 +f 1787/1787/3797 1800/1800/3797 1788/1788/3797 +f 1788/1788/3798 1800/1800/3798 1797/1797/3798 +f 1788/1788/3799 1797/1797/3800 1796/1796/3801 +f 1788/1788/3799 1796/1796/3801 1784/1784/3802 +f 1784/1784/3803 1796/1796/3803 1799/1799/3803 +f 1784/1784/3804 1799/1799/3804 1785/1785/3804 +f 1785/1785/3805 1799/1799/3806 1798/1798/3807 +f 1785/1785/3805 1798/1798/3807 1786/1786/3808 +f 1787/1787/3809 1783/1783/3809 1801/1801/3809 +f 1785/1785/3810 1787/1787/3810 1801/1801/3810 +f 1783/1783/3811 1785/1785/3811 1801/1801/3811 +f 1794/1794/3812 1791/1791/3773 1790/1790/3772 +f 1802/1802/3813 1803/1803/3813 1804/1804/3813 +f 1804/1804/3814 1805/1805/3814 1806/1806/3814 +f 1807/1807/3815 1808/1808/3816 1809/1809/3817 +f 1809/1809/3817 1810/1810/3818 1807/1807/3815 +f 1810/1810/3819 1811/1811/3819 1812/1812/3819 +f 1810/1810/3820 1812/1812/3820 1807/1807/3820 +f 1812/1812/3821 1813/1813/3821 1807/1807/3821 +f 1807/1807/3822 1813/1813/3822 1808/1808/3822 +f 1808/1808/3823 1813/1813/3823 1814/1814/3823 +f 1808/1808/3824 1814/1814/3824 1809/1809/3824 +f 1809/1809/3825 1814/1814/3826 1811/1811/3827 +f 1809/1809/3825 1811/1811/3827 1810/1810/3828 +f 1814/1814/3829 1815/1815/3830 1816/1816/3831 +f 1812/1812/3832 1817/1817/3833 1818/1818/3834 +f 1813/1813/3835 1819/1819/3836 1815/1815/3830 +f 1813/1813/3835 1815/1815/3830 1814/1814/3829 +f 1818/1818/3834 1819/1819/3836 1812/1812/3832 +f 1812/1812/3832 1819/1819/3836 1813/1813/3835 +f 1814/1814/3829 1816/1816/3831 1811/1811/3837 +f 1811/1811/3837 1817/1817/3833 1812/1812/3832 +f 1816/1816/3831 1817/1817/3833 1811/1811/3837 +f 1803/1803/3838 1817/1817/3839 1816/1816/3840 +f 1803/1803/3838 1816/1816/3840 1804/1804/3841 +f 1804/1804/3842 1816/1816/3843 1815/1815/3844 +f 1804/1804/3842 1815/1815/3844 1805/1805/3845 +f 1805/1805/3846 1815/1815/3846 1819/1819/3846 +f 1805/1805/3847 1819/1819/3847 1806/1806/3847 +f 1806/1806/3848 1819/1819/3849 1818/1818/3850 +f 1806/1806/3848 1818/1818/3850 1802/1802/3851 +f 1802/1802/3852 1818/1818/3853 1817/1817/3854 +f 1802/1802/3852 1817/1817/3854 1803/1803/3855 +f 1804/1804/3856 1806/1806/3856 1820/1820/3856 +f 1821/1821/3857 1804/1804/3857 1820/1820/3857 +f 1802/1802/3858 1804/1804/3858 1821/1821/3858 +f 1806/1806/3859 1802/1802/3860 1820/1820/3861 +f 1820/1820/3861 1802/1802/3860 1821/1821/3862 +f 1822/1822/3863 1823/1823/3863 1824/1824/3863 +f 1825/1825/3864 1826/1826/3864 1822/1822/3864 +f 1827/1827/3865 1828/1828/3865 1829/1829/3865 +f 1828/1828/3866 1830/1830/3866 1831/1831/3866 +f 1828/1828/3867 1831/1831/3868 1829/1829/3869 +f 1829/1829/3869 1831/1831/3868 1832/1832/3870 +f 1832/1832/3871 1833/1833/3872 1829/1829/3873 +f 1829/1829/3873 1833/1833/3872 1827/1827/3874 +f 1833/1833/3875 1830/1830/3875 1827/1827/3875 +f 1827/1827/3876 1830/1830/3876 1828/1828/3876 +f 1831/1831/3877 1834/1834/3878 1832/1832/3879 +f 1830/1830/3880 1835/1835/3881 1831/1831/3877 +f 1831/1831/3877 1835/1835/3881 1834/1834/3878 +f 1833/1833/3882 1836/1836/3883 1837/1837/3884 +f 1833/1833/3882 1837/1837/3884 1830/1830/3885 +f 1830/1830/3886 1837/1837/3886 1835/1835/3886 +f 1832/1832/3879 1836/1836/3883 1833/1833/3882 +f 1832/1832/3879 1834/1834/3878 1836/1836/3883 +f 1826/1826/3887 1835/1835/3888 1822/1822/3889 +f 1822/1822/3889 1835/1835/3888 1837/1837/3890 +f 1822/1822/3891 1837/1837/3891 1823/1823/3891 +f 1823/1823/3892 1837/1837/3892 1836/1836/3892 +f 1823/1823/3893 1836/1836/3893 1824/1824/3893 +f 1824/1824/3894 1836/1836/3894 1834/1834/3894 +f 1824/1824/3895 1834/1834/3895 1825/1825/3895 +f 1825/1825/3896 1834/1834/3896 1835/1835/3896 +f 1825/1825/3897 1835/1835/3897 1826/1826/3897 +f 1822/1822/3898 1824/1824/3898 1838/1838/3898 +f 1825/1825/3899 1822/1822/3899 1839/1839/3899 +f 1839/1839/3900 1822/1822/3900 1838/1838/3900 +f 1824/1824/3901 1825/1825/3902 1838/1838/3903 +f 1838/1838/3903 1825/1825/3902 1839/1839/3904 +f 1840/1840/3905 1841/1841/3905 1842/1842/3905 +f 1843/1843/3906 1844/1844/3907 1845/1845/3908 +f 1846/1846/3909 1847/1847/3910 1844/1844/3911 +f 1844/1844/3911 1847/1847/3910 1845/1845/3912 +f 1845/1845/3913 1847/1847/3914 1843/1843/3915 +f 1843/1843/3915 1847/1847/3914 1848/1848/3916 +f 1843/1843/3917 1848/1848/3918 1849/1849/3919 +f 1843/1843/3917 1849/1849/3919 1850/1850/3920 +f 1850/1850/3921 1849/1849/3922 1844/1844/3923 +f 1849/1849/3922 1846/1846/3924 1844/1844/3923 +f 1848/1848/3925 1851/1851/3926 1849/1849/3927 +f 1847/1847/3928 1852/1852/3929 1853/1853/3930 +f 1854/1854/3931 1852/1852/3929 1846/1846/3932 +f 1846/1846/3932 1852/1852/3929 1847/1847/3928 +f 1849/1849/3927 1854/1854/3931 1846/1846/3932 +f 1849/1849/3927 1851/1851/3926 1854/1854/3931 +f 1847/1847/3928 1853/1853/3930 1848/1848/3925 +f 1848/1848/3925 1853/1853/3930 1851/1851/3926 +f 1855/1855/3933 1852/1852/3933 1854/1854/3933 +f 1855/1855/3934 1854/1854/3934 1840/1840/3934 +f 1840/1840/3935 1854/1854/3935 1851/1851/3935 +f 1840/1840/3936 1851/1851/3936 1841/1841/3936 +f 1841/1841/3937 1851/1851/3937 1853/1853/3937 +f 1841/1841/3938 1853/1853/3938 1842/1842/3938 +f 1842/1842/3939 1853/1853/3939 1852/1852/3939 +f 1842/1842/3940 1852/1852/3940 1855/1855/3940 +f 1840/1840/3941 1842/1842/3941 1856/1856/3941 +f 1855/1855/3942 1840/1840/3943 1857/1857/3944 +f 1857/1857/3944 1840/1840/3943 1856/1856/3945 +f 1842/1842/3946 1855/1855/3946 1857/1857/3946 +f 1856/1856/3947 1842/1842/3947 1857/1857/3947 +f 1850/1850/3948 1844/1844/3907 1843/1843/3906 +f 1858/1858/3949 1859/1859/3949 1860/1860/3949 +f 1860/1860/3950 1861/1861/3950 1862/1862/3950 +f 1863/1863/3951 1864/1864/3952 1865/1865/3953 +f 1864/1864/3954 1866/1866/3955 1867/1867/3956 +f 1866/1866/3955 1868/1868/3957 1867/1867/3956 +f 1867/1867/3958 1868/1868/3959 1865/1865/3960 +f 1865/1865/3960 1868/1868/3959 1869/1869/3961 +f 1865/1865/3962 1869/1869/3963 1863/1863/3964 +f 1869/1869/3963 1870/1870/3965 1863/1863/3964 +f 1870/1870/3966 1866/1866/3967 1863/1863/3968 +f 1863/1863/3968 1866/1866/3967 1864/1864/3969 +f 1869/1869/3970 1871/1871/3971 1870/1870/3972 +f 1870/1870/3972 1871/1871/3971 1872/1872/3973 +f 1866/1866/3974 1873/1873/3975 1868/1868/3976 +f 1868/1868/3976 1874/1874/3977 1869/1869/3970 +f 1869/1869/3970 1874/1874/3977 1871/1871/3971 +f 1873/1873/3975 1874/1874/3977 1868/1868/3976 +f 1866/1866/3974 1875/1875/3978 1873/1873/3975 +f 1870/1870/3972 1872/1872/3973 1866/1866/3974 +f 1866/1866/3974 1872/1872/3973 1875/1875/3978 +f 1861/1861/3979 1875/1875/3980 1862/1862/3981 +f 1862/1862/3982 1875/1875/3983 1872/1872/3984 +f 1862/1862/3982 1872/1872/3984 1858/1858/3985 +f 1858/1858/3986 1872/1872/3987 1859/1859/3988 +f 1859/1859/3988 1872/1872/3987 1871/1871/3989 +f 1859/1859/3990 1871/1871/3991 1860/1860/3992 +f 1860/1860/3992 1871/1871/3991 1874/1874/3993 +f 1860/1860/3994 1874/1874/3995 1861/1861/3996 +f 1861/1861/3996 1874/1874/3995 1873/1873/3997 +f 1861/1861/3979 1873/1873/3998 1875/1875/3980 +f 1858/1858/3999 1860/1860/3999 1876/1876/3999 +f 1876/1876/4000 1860/1860/4000 1877/1877/4000 +f 1862/1862/4001 1858/1858/4001 1877/1877/4001 +f 1877/1877/4002 1858/1858/4002 1876/1876/4002 +f 1860/1860/4003 1862/1862/4003 1877/1877/4003 +f 1867/1867/4004 1865/1865/3953 1864/1864/3952 +f 505/505/5 504/504/5 38/38/5 +f 27/27/5 29/29/5 719/719/5 +f 434/434/5 502/502/5 19/19/5 +f 719/719/5 675/675/5 27/27/5 +f 41/41/16 714/714/4005 703/703/4006 +f 719/719/5 718/718/4007 675/675/5 +f 503/503/5 502/502/5 434/434/5 +f 26/26/5 11/11/5 39/39/5 +f 434/434/5 432/432/5 503/503/5 +f 718/718/4007 677/677/4008 675/675/5 +f 711/711/4009 677/677/4008 718/718/4007 +f 677/677/4008 711/711/4009 679/679/4010 +f 502/502/5 20/20/5 19/19/5 +f 28/28/5 32/32/5 29/29/5 +f 711/711/4009 717/717/4011 679/679/4010 +f 432/432/5 430/430/5 503/503/5 +f 681/681/5 679/679/4010 717/717/4011 +f 716/716/5 681/681/5 717/717/4011 +f 459/459/5 328/328/5 329/329/5 +f 34/34/5 21/21/5 20/20/5 +f 329/329/5 30/30/5 459/459/5 +f 33/33/5 24/24/5 32/32/5 +f 704/704/5 703/703/4006 714/714/4005 +f 26/26/5 39/39/5 36/36/5 +f 37/37/5 30/30/5 329/329/5 +f 504/504/5 430/430/5 38/38/5 +f 715/715/4012 40/40/15 716/716/5 +f 681/681/5 716/716/5 40/40/15 +f 430/430/5 504/504/5 503/503/5 +f 30/30/5 3/3/5 459/459/5 +f 40/40/15 715/715/4012 41/41/16 +f 703/703/4006 1/1/14 41/41/16 +f 38/38/5 37/37/5 505/505/5 +f 40/40/15 1/1/14 30/30/5 +f 16/16/5 33/33/5 36/36/5 +f 1200/1200/4013 1224/1224/2529 1197/1197/4014 +f 1346/1346/4015 1213/1213/4016 1215/1215/4017 +f 1197/1197/4014 1224/1224/2529 1195/1195/4018 +f 1276/1276/573 1272/1272/4019 1274/1274/4020 +f 1271/1271/573 1272/1272/4019 1276/1276/573 +f 1202/1202/4021 1224/1224/2529 1200/1200/4013 +f 1229/1229/573 1231/1231/4022 1337/1337/4023 +f 1314/1314/573 1315/1315/573 1312/1312/573 +f 1276/1276/573 1278/1278/3325 1270/1270/573 +f 1315/1315/573 1339/1339/573 1340/1340/4024 +f 1195/1195/4018 1224/1224/2529 1194/1194/4025 +f 1271/1271/573 1276/1276/573 1270/1270/573 +f 1312/1312/573 1315/1315/573 1191/1191/573 +f 1204/1204/4026 1224/1224/2529 1202/1202/4021 +f 1191/1191/573 1315/1315/573 1340/1340/4024 +f 1302/1302/573 1304/1304/573 1337/1337/4023 +f 1340/1340/4024 1194/1194/4025 1227/1227/4027 +f 1189/1189/4028 1340/1340/4024 1227/1227/4027 +f 1346/1346/2739 1348/1348/2742 1351/1351/4029 +f 1221/1221/4030 1189/1189/4028 1227/1227/4027 +f 1352/1352/4031 1189/1189/4028 1221/1221/4030 +f 1346/1346/4015 1217/1217/4032 1219/1219/4033 +f 1223/1223/4034 1352/1352/4031 1221/1221/4030 +f 1224/1224/2529 1204/1204/4026 1207/1207/4035 +f 1219/1219/4033 1344/1344/4036 1346/1346/4015 +f 1270/1270/573 1278/1278/3325 1279/1279/573 +f 1270/1270/573 1257/1257/573 1268/1268/573 +f 1224/1224/2529 1353/1353/4037 1223/1223/4038 +f 1346/1346/4015 1224/1224/2529 1207/1207/4035 +f 1353/1353/4037 1257/1257/573 1279/1279/573 +f 1351/1351/4039 1257/1257/573 1353/1353/4037 +f 1209/1209/4040 1346/1346/4015 1207/1207/4035 +f 1269/1269/4041 1270/1270/573 1268/1268/573 +f 1337/1337/4023 1231/1231/4022 1341/1341/4042 +f 1268/1268/573 1257/1257/573 1259/1259/573 +f 1270/1270/573 1279/1279/573 1257/1257/573 +f 1349/1349/4043 1351/1351/4043 1348/1348/4043 +f 1225/1225/2531 1227/1227/4027 1194/1194/4025 +f 1350/1350/4044 1349/1349/4045 1341/1341/4042 +f 1346/1346/4015 1209/1209/4040 1211/1211/4046 +f 1231/1231/4022 1350/1350/4044 1341/1341/4042 +f 1224/1224/2529 1225/1225/2531 1194/1194/4025 +f 1337/1337/4023 1341/1341/4042 1344/1344/4036 +f 1219/1219/4033 1337/1337/4023 1344/1344/4036 +f 1224/1224/2529 1346/1346/4015 1351/1351/4039 +f 1189/1189/4028 1191/1191/573 1340/1340/4024 +f 1229/1229/573 1337/1337/4023 1304/1304/573 +f 1261/1261/573 1265/1265/573 1266/1266/573 +f 1266/1266/573 1268/1268/573 1261/1261/573 +f 1353/1353/4037 1224/1224/2529 1351/1351/4039 +f 1346/1346/4015 1211/1211/4046 1213/1213/4016 +f 1304/1304/573 1306/1306/573 1229/1229/573 +f 1268/1268/573 1259/1259/573 1261/1261/573 +f 1264/1264/573 1265/1265/573 1261/1261/573 +f 1346/1346/4015 1215/1215/4017 1217/1217/4032 +f 201/201/4047 199/199/4048 197/197/4049 +f 201/201/4047 197/197/4049 202/202/4050 +f 468/468/4051 471/471/4052 466/466/4053 +f 194/194/4054 204/204/4055 202/202/4050 +f 466/466/4053 471/471/4052 473/473/4056 +f 465/465/4056 466/466/4053 473/473/4056 +f 473/473/4056 475/475/4057 465/465/4056 +f 204/204/4055 194/194/4054 193/193/4058 +f 193/193/4058 206/206/4059 204/204/4055 +f 488/488/4060 465/465/4056 475/475/4057 +f 219/219/4061 206/206/4059 193/193/4058 +f 194/194/4054 202/202/4050 197/197/4049 +f 488/488/4060 476/476/4062 491/491/4063 +f 209/209/4064 206/206/4059 493/493/4065 +f 491/491/4063 493/493/4065 488/488/4060 +f 219/219/4061 493/493/4065 206/206/4059 +f 705/705/4066 209/209/4064 493/493/4065 +f 491/491/4063 476/476/4062 487/487/4067 +f 480/480/4068 487/487/4067 478/478/4069 +f 705/705/1643 851/851/1642 847/847/4070 +f 476/476/4062 488/488/4060 475/475/4057 +f 847/847/4071 845/845/4071 221/221/4071 +f 219/219/4061 488/488/4060 493/493/4065 +f 847/847/4072 221/221/4072 705/705/4072 +f 209/209/4064 705/705/4066 221/221/4058 +f 209/209/4064 221/221/4058 216/216/3225 +f 485/485/4073 487/487/4067 480/480/4068 +f 476/476/4062 478/478/4069 487/487/4067 +f 216/216/3225 213/213/4074 209/209/4064 +f 471/471/4052 468/468/4051 470/470/4075 +f 213/213/4074 211/211/4076 209/209/4064 +f 484/484/4077 485/485/4073 480/480/4068 +f 484/484/4077 480/480/4068 481/481/4078 +f 213/213/4074 216/216/3225 215/215/4079 +f 481/481/4078 482/482/4080 484/484/4077 +f 1359/1359/4081 1360/1360/2798 1232/1232/4082 +f 1354/1354/2800 1252/1252/4083 1355/1355/4084 +f 1321/1321/4085 1301/1301/4086 1367/1367/2825 +f 1232/1232/4082 1360/1360/2798 1239/1239/4087 +f 1228/1228/4088 1226/1226/4089 1308/1308/4090 +f 1366/1366/4091 1228/1228/4088 1308/1308/4090 +f 1345/1345/4092 1343/1343/5 1362/1362/4093 +f 1226/1226/4089 1222/1222/5 1347/1347/4094 +f 1307/1307/4095 1301/1301/4086 1321/1321/4085 +f 1343/1343/5 1361/1361/4096 1362/1362/4093 +f 1239/1239/4087 1361/1361/4096 1232/1232/4082 +f 1361/1361/4096 1343/1343/5 1342/1342/5 +f 1307/1307/4095 1308/1308/4090 1226/1226/4089 +f 1228/1228/4088 1366/1366/4091 1222/1222/5 +f 1226/1226/4089 1301/1301/4086 1307/1307/4095 +f 1360/1360/2798 1354/1354/2800 1355/1355/4084 +f 1222/1222/5 1366/1366/4091 1342/1342/5 +f 1368/1368/4097 1321/1321/4085 1367/1367/2825 +f 1222/1222/5 1342/1342/5 1347/1347/4094 +f 1301/1301/4086 1226/1226/4089 1347/1347/4094 +f 1320/1320/4098 1321/1321/4085 1368/1368/4097 +f 1321/1321/4085 1369/1369/4099 1307/1307/4095 +f 1361/1361/4096 1366/1366/4091 1232/1232/4082 +f 1361/1361/4096 1342/1342/5 1366/1366/4091 +f 1345/1345/4092 1362/1362/4093 1347/1347/4094 +f 1362/1362/4093 1301/1301/4086 1347/1347/4094 +f 1360/1360/2798 1355/1355/4084 1239/1239/4087 +f 1325/1325/2826 1368/1368/4097 1367/1367/2825 +f 1355/1355/4084 1356/1356/4100 1239/1239/4087 +f 1364/1364/4101 1367/1367/2825 1301/1301/4086 +f 1262/1262/4102 1260/1260/2621 1290/1290/2623 +f 1305/1305/4103 1298/1298/4104 1262/1262/4102 +f 1300/1300/2697 1288/1288/2616 1218/1218/2617 +f 1262/1262/4102 1290/1290/2623 1305/1305/4103 +f 1298/1298/4104 1305/1305/4103 1303/1303/573 +f 1277/1277/2703 1275/1275/2718 1310/1310/2716 +f 1255/1255/4105 1254/1254/4105 1267/1267/4105 +f 1300/1300/2697 1298/1298/4104 1303/1303/573 +f 1263/1263/4106 1262/1262/4102 1298/1298/4104 +f 1263/1263/4106 1298/1298/4104 1238/1238/4107 +f 1196/1196/2620 1293/1293/2628 1289/1289/2618 +f 1237/1237/4108 1285/1285/4108 1255/1255/4108 +f 1212/1212/4109 1335/1335/4110 1214/1214/4111 +f 1192/1192/2714 1338/1338/4112 1294/1294/2630 +f 1216/1216/4113 1214/1214/4111 1317/1317/4114 +f 1238/1238/4107 1237/1237/4115 1263/1263/4106 +f 1300/1300/2697 1303/1303/573 1288/1288/2616 +f 1317/1317/4114 1214/1214/4111 1335/1335/4110 +f 463/463/4116 439/439/4117 464/464/4118 +f 464/464/4118 682/682/4119 463/463/4116 +f 429/429/4120 431/431/4121 433/433/4122 +f 438/438/4123 429/429/4120 435/435/4124 +f 429/429/4120 433/433/4122 435/435/4124 +f 464/464/4118 678/678/4125 680/680/4126 +f 436/436/4127 438/438/4123 435/435/4124 +f 464/464/4118 676/676/4128 678/678/4125 +f 437/437/4129 438/438/4123 436/436/4127 +f 429/429/4120 438/438/4123 439/439/4117 +f 464/464/4118 674/674/4130 676/676/4128 +f 464/464/4118 680/680/4126 682/682/4119 +f 464/464/4118 673/673/4131 674/674/4130 +f 428/428/4132 429/429/4120 439/439/4117 +f 463/463/4116 428/428/4132 439/439/4117 +f 1878/1878/4133 1879/1879/4133 1880/1880/4133 +f 1878/1878/4134 1880/1880/4134 1881/1881/4134 +f 1882/1882/4135 1881/1881/4135 1880/1880/4135 +f 1882/1882/4136 1883/1883/4137 1881/1881/4138 +f 1881/1881/4138 1883/1883/4137 1884/1884/4139 +f 1884/1884/4140 1883/1883/4140 1879/1879/4140 +f 1884/1884/4141 1879/1879/4141 1878/1878/4141 +f 1878/1878/573 1881/1881/573 1884/1884/573 +f 1885/1885/4142 1879/1879/4143 1886/1886/4144 +f 1879/1879/4145 1887/1887/4145 1886/1886/4145 +f 1886/1886/4144 1888/1888/4146 1885/1885/4142 +f 1888/1888/4146 1889/1889/4147 1885/1885/4142 +f 1888/1888/4146 1890/1890/4148 1889/1889/4147 +f 1891/1891/4149 1892/1892/4150 1893/1893/4151 +f 1892/1892/4150 1894/1894/4152 1893/1893/4151 +f 1894/1894/4152 1895/1895/4153 1893/1893/4151 +f 1891/1891/4154 1896/1896/4155 1897/1897/4156 +f 1891/1891/4149 1893/1893/4151 1896/1896/4157 +f 1893/1893/4158 1895/1895/4158 1896/1896/4158 +f 1898/1898/4159 1896/1896/4155 1895/1895/4160 +f 1899/1899/4161 1897/1897/4156 1896/1896/4155 +f 1900/1900/4162 1901/1901/4163 1887/1887/4164 +f 1900/1900/4162 1887/1887/4164 1883/1883/4165 +f 1887/1887/4164 1879/1879/4166 1883/1883/4165 +f 1897/1897/4156 1902/1902/4167 1891/1891/4154 +f 1903/1903/4168 1904/1904/4169 1902/1902/4167 +f 1904/1904/4169 1905/1905/4170 1906/1906/4171 +f 1904/1904/4169 1907/1907/4172 1905/1905/4170 +f 1904/1904/4169 1908/1908/4173 1907/1907/4172 +f 1902/1902/4174 1909/1909/4174 1903/1903/4174 +f 1897/1897/4156 1910/1910/4175 1902/1902/4167 +f 1879/1879/4143 1906/1906/4171 1880/1880/4176 +f 1911/1911/4177 1904/1904/4169 1903/1903/4168 +f 1911/1911/4177 1908/1908/4173 1904/1904/4169 +f 1880/1880/4176 1906/1906/4171 1905/1905/4170 +f 1912/1912/4178 1908/1908/4173 1911/1911/4177 +f 1910/1910/4175 1897/1897/4156 1913/1913/4179 +f 1914/1914/4180 1902/1902/4167 1910/1910/4175 +f 1914/1914/4180 1909/1909/4181 1902/1902/4167 +f 1882/1882/4182 1880/1880/4176 1905/1905/4170 +f 1915/1915/4183 1903/1903/4168 1916/1916/4184 +f 1911/1911/4177 1903/1903/4168 1915/1915/4183 +f 1882/1882/4182 1905/1905/4170 1900/1900/4162 +f 1917/1917/4185 1914/1914/4180 1910/1910/4175 +f 1918/1918/4186 1905/1905/4170 1907/1907/4187 +f 1918/1918/4186 1912/1912/4178 1911/1911/4177 +f 1917/1917/4185 1913/1913/4179 1919/1919/4188 +f 1917/1917/4185 1910/1910/4175 1913/1913/4179 +f 1920/1920/4189 1914/1914/4180 1917/1917/4185 +f 1918/1918/4186 1911/1911/4177 1915/1915/4183 +f 1898/1898/4159 1919/1919/4188 1896/1896/4155 +f 1898/1898/4159 1921/1921/4190 1919/1919/4188 +f 1918/1918/4186 1922/1922/4191 1905/1905/4170 +f 1915/1915/4183 1923/1923/4192 1918/1918/4186 +f 1916/1916/4184 1920/1920/4189 1915/1915/4183 +f 1919/1919/4188 1921/1921/4190 1917/1917/4185 +f 1905/1905/4170 1922/1922/4191 1900/1900/4162 +f 1920/1920/4189 1924/1924/4193 1915/1915/4183 +f 1925/1925/4194 1917/1917/4185 1921/1921/4190 +f 1925/1925/4194 1920/1920/4189 1917/1917/4185 +f 1924/1924/4193 1920/1920/4189 1925/1925/4194 +f 1923/1923/4192 1915/1915/4183 1924/1924/4193 +f 1922/1922/4191 1918/1918/4186 1923/1923/4192 +f 1901/1901/4163 1900/1900/4162 1922/1922/4195 +f 1926/1926/4196 1927/1927/4197 1928/1928/4198 +f 1928/1928/4198 1927/1927/4197 1929/1929/4199 +f 1930/1930/4200 1928/1928/4198 1929/1929/4199 +f 1931/1931/4201 1932/1932/4202 1929/1929/4199 +f 1929/1929/4199 1932/1932/4202 1930/1930/4200 +f 1933/1933/4203 1934/1934/4204 1931/1931/4201 +f 1935/1935/4205 1936/1936/4206 1933/1933/4203 +f 1937/1937/4207 1933/1933/4203 1936/1936/4206 +f 1934/1934/4204 1933/1933/4203 1937/1937/4207 +f 1932/1932/4202 1931/1931/4201 1934/1934/4204 +f 1938/1938/4208 1932/1932/4202 1934/1934/4204 +f 1939/1939/4209 1940/1940/4210 1941/1941/4211 +f 1939/1939/4209 1942/1942/4212 1940/1940/4210 +f 1943/1943/4213 1944/1944/4214 1942/1942/4212 +f 1939/1939/4209 1943/1943/4213 1942/1942/4212 +f 1945/1945/4215 1946/1946/4216 1942/1942/4212 +f 1945/1945/4215 1942/1942/4212 1944/1944/4214 +f 1926/1926/4196 1947/1947/4217 1948/1948/4218 +f 1928/1928/4198 1949/1949/4219 1926/1926/4196 +f 1926/1926/4196 1949/1949/4219 1947/1947/4217 +f 1947/1947/4217 1950/1950/4220 1951/1951/4221 +f 1951/1951/4221 1948/1948/4218 1947/1947/4217 +f 1952/1952/4222 1945/1945/4215 1953/1953/4223 +f 1953/1953/4223 1945/1945/4215 1944/1944/4214 +f 1954/1954/4224 1955/1955/4225 1953/1953/4223 +f 1956/1956/4226 1957/1957/4227 1958/1958/4228 +f 1956/1956/4226 1954/1954/4224 1957/1957/4227 +f 1955/1955/4225 1954/1954/4224 1956/1956/4226 +f 1959/1959/4229 1953/1953/4223 1955/1955/4225 +f 1955/1955/4225 1956/1956/4226 1960/1960/4230 +f 1953/1953/4223 1959/1959/4229 1952/1952/4222 +f 1952/1952/4231 1959/1959/4232 1961/1961/4233 +f 1957/1957/4227 1948/1948/4218 1962/1962/4234 +f 1962/1962/4234 1951/1951/4221 1963/1963/4235 +f 1962/1962/4234 1948/1948/4218 1951/1951/4221 +f 1957/1957/4227 1962/1962/4234 1958/1958/4228 +f 1964/1964/4236 1965/1965/4237 1966/1966/4238 +f 1964/1964/4236 1967/1967/4239 1965/1965/4237 +f 1964/1964/4236 1968/1968/4240 1967/1967/4239 +f 1964/1964/4236 1969/1969/4241 1968/1968/4240 +f 1964/1964/4236 1970/1970/4242 1969/1969/4241 +f 1964/1964/4236 1971/1971/4243 1970/1970/4242 +f 1935/1935/4205 1972/1972/4244 1973/1973/4245 +f 1935/1935/4205 1974/1974/4246 1972/1972/4244 +f 1935/1935/4205 1975/1975/4247 1974/1974/4246 +f 1935/1935/4205 1976/1976/4248 1975/1975/4247 +f 1935/1935/4205 1977/1977/4249 1976/1976/4248 +f 1935/1935/4205 1978/1978/4250 1977/1977/4249 +f 1973/1973/4245 1979/1979/4251 1935/1935/4205 +f 1973/1973/4245 1980/1980/4252 1979/1979/4251 +f 1981/1981/4253 1964/1964/4236 1982/1982/4254 +f 1981/1981/4253 1983/1983/4255 1964/1964/4236 +f 1984/1984/4256 1982/1982/4254 1985/1985/4257 +f 1981/1981/4253 1982/1982/4254 1986/1986/4258 +f 1964/1964/4236 1983/1983/4255 1987/1987/4259 +f 1988/1988/4260 1989/1989/4261 1990/1990/4262 +f 1988/1988/4260 1991/1991/4263 1989/1989/4261 +f 1937/1937/4264 1992/1992/4265 1934/1934/4204 +f 1937/1937/4264 1993/1993/4266 1992/1992/4265 +f 1994/1994/4267 1989/1989/4261 1995/1995/4268 +f 1996/1996/4269 1997/1997/4270 1998/1998/4271 +f 1999/1999/4272 1990/1990/4262 1997/1997/4270 +f 2000/2000/4273 1990/1990/4262 1999/1999/4272 +f 1995/1995/4268 1989/1989/4261 1991/1991/4263 +f 1995/1995/4268 2001/2001/4274 2002/2002/4275 +f 2003/2003/4276 2001/2001/4274 1995/1995/4268 +f 2004/2004/4277 2005/2005/4278 1960/1960/4230 +f 2005/2005/4278 1961/1961/4233 1960/1960/4230 +f 2005/2005/4278 1991/1991/4263 1961/1961/4233 +f 1941/1941/4211 1988/1988/4260 1990/1990/4262 +f 1998/1998/4271 1990/1990/4262 1989/1989/4261 +f 1939/1939/4209 1990/1990/4262 2006/2006/4279 +f 1939/1939/4209 1941/1941/4211 1990/1990/4262 +f 2006/2006/4279 2000/2000/4273 2007/2007/4280 +f 1990/1990/4262 2000/2000/4273 2006/2006/4279 +f 1997/1997/4270 1990/1990/4262 1998/1998/4271 +f 1994/1994/4267 2008/2008/4281 1998/1998/4271 +f 1989/1989/4261 1994/1994/4267 1998/1998/4271 +f 1996/1996/4269 1998/1998/4271 2009/2009/4282 +f 2008/2008/4281 1994/1994/4267 2010/2010/4283 +f 1994/1994/4267 2011/2011/4284 2012/2012/4285 +f 2003/2003/4276 2013/2013/4286 2014/2014/4287 +f 2015/2015/4288 2013/2013/4286 2003/2003/4276 +f 2016/2016/4289 2005/2005/4278 2004/2004/4277 +f 2005/2005/4278 1995/1995/4268 1991/1991/4263 +f 2005/2005/4278 2003/2003/4276 1995/1995/4268 +f 2011/2011/4284 1995/1995/4268 2002/2002/4275 +f 1994/1994/4267 1995/1995/4268 2011/2011/4284 +f 1956/1956/4226 2004/2004/4277 1960/1960/4230 +f 1928/1928/4198 2016/2016/4289 2004/2004/4277 +f 1930/1930/4290 2016/2016/4289 1928/1928/4198 +f 2017/2017/4291 2016/2016/4289 1930/1930/4290 +f 2017/2017/4291 1992/1992/4265 2016/2016/4289 +f 1938/1938/4208 1992/1992/4265 2017/2017/4291 +f 1934/1934/4204 1992/1992/4265 1938/1938/4208 +f 1936/1936/4292 2018/2018/4293 1937/1937/4264 +f 2019/2019/4294 1949/1949/4219 1928/1928/4198 +f 2004/2004/4277 2019/2019/4294 1928/1928/4198 +f 1956/1956/4226 1958/1958/4295 2004/2004/4277 +f 2004/2004/4277 2020/2020/4296 2019/2019/4294 +f 2004/2004/4277 1958/1958/4295 2020/2020/4296 +f 2021/2021/4297 1992/1992/4265 1993/1993/4266 +f 2015/2015/4288 1992/1992/4265 2021/2021/4297 +f 2005/2005/4278 2016/2016/4289 2015/2015/4288 +f 2016/2016/4289 1992/1992/4265 2015/2015/4288 +f 2005/2005/4278 2015/2015/4288 2003/2003/4276 +f 1988/1988/4260 1952/1952/4231 1991/1991/4263 +f 1988/1988/4260 1945/1945/4215 1952/1952/4231 +f 1961/1961/4233 1991/1991/4263 1952/1952/4231 +f 2003/2003/4276 2022/2022/4298 2001/2001/4274 +f 2014/2014/4287 2022/2022/4298 2003/2003/4276 +f 2023/2023/4299 2012/2012/4285 2024/2024/4300 +f 2023/2023/4299 2025/2025/4301 2012/2012/4285 +f 1994/1994/4267 2026/2026/4302 2010/2010/4283 +f 2012/2012/4285 2026/2026/4302 1994/1994/4267 +f 2025/2025/4301 2026/2026/4302 2012/2012/4285 +f 2008/2008/4281 2009/2009/4282 1998/1998/4271 +f 2009/2009/4282 2027/2027/4303 1996/1996/4269 +f 1999/1999/4272 1997/1997/4270 2028/2028/4304 +f 2029/2029/4305 2006/2006/4279 2007/2007/4280 +f 1946/1946/4216 1945/1945/4215 1988/1988/4260 +f 1941/1941/4211 1946/1946/4216 1988/1988/4260 +f 1961/1961/4233 1955/1955/4225 1960/1960/4230 +f 2019/2019/4294 1963/1963/4235 1951/1951/4221 +f 2020/2020/4296 1963/1963/4235 2019/2019/4294 +f 1951/1951/4221 1950/1950/4220 2019/2019/4294 +f 2018/2018/4293 1993/1993/4266 1937/1937/4264 +f 2021/2021/4297 2030/2030/4306 2015/2015/4288 +f 2031/2031/4307 2030/2030/4306 2021/2021/4297 +f 2015/2015/4288 2030/2030/4306 2032/2032/4308 +f 2032/2032/4308 2013/2013/4286 2015/2015/4288 +f 1966/1966/4238 2033/2033/4309 2034/2034/4310 +f 2034/2034/4310 1964/1964/4236 1966/1966/4238 +f 2035/2035/4311 2034/2034/4310 2036/2036/4312 +f 1978/1978/4250 1935/1935/4205 1933/1933/4203 +f 2037/2037/4313 1931/1931/4201 2038/2038/4314 +f 1933/1933/4203 1931/1931/4201 2037/2037/4313 +f 2038/2038/4314 1931/1931/4201 1929/1929/4199 +f 2038/2038/4314 1929/1929/4199 2039/2039/4315 +f 2039/2039/4315 1929/1929/4199 1927/1927/4316 +f 1927/1927/4316 1926/1926/4196 2039/2039/4315 +f 2040/2040/4317 2041/2041/4318 2042/2042/4319 +f 2040/2040/4317 2043/2043/4320 2044/2044/4321 +f 2040/2040/4317 2042/2042/4319 2043/2043/4320 +f 2045/2045/4322 2044/2044/4321 2043/2043/4320 +f 2044/2044/4321 2045/2045/4322 2046/2046/4323 +f 2046/2046/4323 2045/2045/4322 2047/2047/4324 +f 2035/2035/4311 2047/2047/4324 2048/2048/4325 +f 2046/2046/4323 2047/2047/4324 2035/2035/4311 +f 2048/2048/4325 2034/2034/4310 2035/2035/4311 +f 2039/2039/4315 1926/1926/4196 2049/2049/4326 +f 1900/1900/4162 1883/1883/4165 1882/1882/4182 +f 1906/1906/4171 1879/1879/4143 1885/1885/4142 +f 1919/1919/4188 1899/1899/4161 1896/1896/4155 +f 1898/1898/4159 2050/2050/4327 1921/1921/4190 +f 2051/2051/4328 1894/1894/4329 1892/1892/4330 +f 2052/2052/4331 2053/2053/4331 1889/1889/4331 +f 2052/2052/4332 2054/2054/4333 2053/2053/4334 +f 2055/2055/4335 2054/2054/4333 2052/2052/4332 +f 2056/2056/4336 2054/2054/4336 2055/2055/4336 +f 2056/2056/4337 2057/2057/4337 2054/2054/4337 +f 2058/2058/4338 2057/2057/4338 2056/2056/4338 +f 2058/2058/4339 1892/1892/4339 2057/2057/4339 +f 2059/2059/4340 2014/2014/4341 2060/2060/4342 +f 2059/2059/4340 2061/2061/4343 2014/2014/4341 +f 2060/2060/4342 2014/2014/4341 2013/2013/4344 +f 1889/1889/4345 1890/1890/4346 2062/2062/4347 +f 2013/2013/4344 2063/2063/4348 2060/2060/4342 +f 2057/2057/4349 1891/1891/4154 1902/1902/4167 +f 2054/2054/4350 1902/1902/4167 1904/1904/4169 +f 2057/2057/4349 1902/1902/4167 2054/2054/4350 +f 2057/2057/4349 1892/1892/4351 1891/1891/4154 +f 1971/1971/4243 1964/1964/4236 1987/1987/4259 +f 1948/1948/4218 2064/2064/4352 1926/1926/4196 +f 2049/2049/4326 1926/1926/4196 2064/2064/4352 +f 2054/2054/4350 1906/1906/4171 2053/2053/4353 +f 1904/1904/4169 1906/1906/4171 2054/2054/4350 +f 1885/1885/4142 2053/2053/4353 1906/1906/4171 +f 1885/1885/4142 1889/1889/4354 2053/2053/4353 +f 2065/2065/4355 2066/2066/4356 2067/2067/4357 +f 2068/2068/4358 2069/2069/4359 2070/2070/4360 +f 2067/2067/4357 2066/2066/4356 2071/2071/4361 +f 2071/2071/4361 2066/2066/4356 2069/2069/4359 +f 2072/2072/4362 2073/2073/4363 2074/2074/4364 +f 2069/2069/4359 2068/2068/4358 2071/2071/4361 +f 2074/2074/4364 2075/2075/4365 2072/2072/4362 +f 2072/2072/4362 2075/2075/4365 2067/2067/4357 +f 2065/2065/4355 2067/2067/4357 2075/2075/4365 +f 2074/2074/4366 2073/2073/4366 2076/2076/4366 +f 2075/2075/4367 2074/2074/4367 2077/2077/4367 +f 2075/2075/4368 2077/2077/4368 2065/2065/4368 +f 2065/2065/4369 2077/2077/4369 2078/2078/4369 +f 2065/2065/4370 2078/2078/4370 2066/2066/4370 +f 2079/2079/4371 2080/2080/4372 2070/2070/4373 +f 2081/2081/4374 2082/2082/4375 2083/2083/4376 +f 2081/2081/4374 2084/2084/4377 2085/2085/4378 +f 2086/2086/4379 2082/2082/4375 2085/2085/4378 +f 2082/2082/4375 2081/2081/4374 2085/2085/4378 +f 2086/2086/4379 2085/2085/4378 2087/2087/4380 +f 2088/2088/4381 2084/2084/4377 2081/2081/4374 +f 2089/2089/4382 2084/2084/4377 2090/2090/4383 +f 2084/2084/4377 2088/2088/4381 2090/2090/4383 +f 2089/2089/4382 2090/2090/4383 2067/2067/4357 +f 2067/2067/4357 2090/2090/4383 2072/2072/4362 +f 2091/2091/4384 2092/2092/4385 2093/2093/4386 +f 2094/2094/4387 2095/2095/4388 2096/2096/4389 +f 2068/2068/4358 2097/2097/4390 2098/2098/4391 +f 2096/2096/4392 2095/2095/4392 2099/2099/4392 +f 2100/2100/4393 2101/2101/4394 2099/2099/4395 +f 2102/2102/4396 2096/2096/4389 2101/2101/4394 +f 2099/2099/4395 2101/2101/4394 2096/2096/4389 +f 2096/2096/4389 2102/2102/4396 2103/2103/4397 +f 2103/2103/4397 2102/2102/4396 2093/2093/4386 +f 2091/2091/4384 2093/2093/4386 2104/2104/4398 +f 2104/2104/4398 2087/2087/4380 2105/2105/4399 +f 2091/2091/4384 2104/2104/4398 2105/2105/4399 +f 2105/2105/4399 2087/2087/4380 2085/2085/4378 +f 2092/2092/4385 2106/2106/4400 2093/2093/4386 +f 2093/2093/4386 2106/2106/4400 2103/2103/4397 +f 2103/2103/4397 2107/2107/4401 2096/2096/4389 +f 2091/2091/4384 2108/2108/4402 2092/2092/4385 +f 2106/2106/4400 2107/2107/4401 2103/2103/4397 +f 2107/2107/4401 2094/2094/4387 2096/2096/4389 +f 2085/2085/4378 2109/2109/4403 2105/2105/4399 +f 2105/2105/4399 2109/2109/4403 2091/2091/4384 +f 2091/2091/4384 2109/2109/4403 2108/2108/4402 +f 2085/2085/4378 2089/2089/4382 2109/2109/4403 +f 2110/2110/4404 2099/2099/4405 2095/2095/4406 +f 2110/2110/4404 2095/2095/4406 2097/2097/4390 +f 2110/2110/4404 2097/2097/4390 2068/2068/4358 +f 2106/2106/4400 2111/2111/4407 2107/2107/4401 +f 2107/2107/4401 2071/2071/4361 2094/2094/4387 +f 2109/2109/4403 2111/2111/4407 2108/2108/4402 +f 2089/2089/4382 2067/2067/4357 2109/2109/4403 +f 2109/2109/4403 2067/2067/4357 2111/2111/4407 +f 2111/2111/4407 2071/2071/4361 2107/2107/4401 +f 2071/2071/4361 2098/2098/4391 2094/2094/4387 +f 2071/2071/4361 2111/2111/4407 2067/2067/4357 +f 2071/2071/4361 2068/2068/4358 2098/2098/4391 +f 2112/2112/4408 2099/2099/4405 2110/2110/4404 +f 2112/2112/4409 2068/2068/4410 2113/2113/4411 +f 2068/2068/4410 2112/2112/4409 2110/2110/4412 +f 2113/2113/4411 2070/2070/4413 2080/2080/4414 +f 2068/2068/4410 2070/2070/4413 2113/2113/4411 +f 2114/2114/4415 2073/2073/4363 2072/2072/4362 +f 2090/2090/4416 2083/2083/4416 2072/2072/4416 +f 2072/2072/4362 2083/2083/4376 2115/2115/4417 +f 2114/2114/4415 2072/2072/4362 2115/2115/4417 +f 2082/2082/4375 2115/2115/4417 2083/2083/4376 +f 2116/2116/4418 2085/2085/4418 2117/2117/4418 +f 2116/2116/4419 2089/2089/4419 2085/2085/4419 +f 2118/2118/4420 2089/2089/4420 2116/2116/4420 +f 2118/2118/4421 2084/2084/4421 2089/2089/4421 +f 2084/2084/4422 2118/2118/4422 2117/2117/4422 +f 2117/2117/4423 2085/2085/4423 2084/2084/4423 +f 2108/2108/4424 2119/2119/4424 2120/2120/4424 +f 2108/2108/4425 2120/2120/4425 2092/2092/4425 +f 2120/2120/4426 2106/2106/4426 2092/2092/4426 +f 2121/2121/4427 2106/2106/4428 2120/2120/4429 +f 2121/2121/4427 2111/2111/4430 2106/2106/4428 +f 2119/2119/4431 2111/2111/4432 2121/2121/4433 +f 2119/2119/4431 2108/2108/4434 2111/2111/4432 +f 2122/2122/4435 2095/2095/4435 2123/2123/4435 +f 2095/2095/4436 2122/2122/4437 2097/2097/4438 +f 2097/2097/4438 2122/2122/4437 2124/2124/4439 +f 2097/2097/4440 2124/2124/4441 2098/2098/4442 +f 2098/2098/4442 2124/2124/4441 2125/2125/4443 +f 2125/2125/4444 2094/2094/4445 2098/2098/4446 +f 2123/2123/4447 2094/2094/4445 2125/2125/4444 +f 2123/2123/4448 2095/2095/4448 2094/2094/4448 +f 2126/2126/4449 2083/2083/4449 2090/2090/4449 +f 2083/2083/4450 2126/2126/4450 2081/2081/4450 +f 2081/2081/4451 2126/2126/4451 2127/2127/4451 +f 2128/2128/4452 2081/2081/4452 2127/2127/4452 +f 2128/2128/4453 2088/2088/4453 2081/2081/4453 +f 2129/2129/4454 2088/2088/4454 2128/2128/4454 +f 2129/2129/4455 2090/2090/4455 2088/2088/4455 +f 2126/2126/4456 2090/2090/4456 2129/2129/4456 +f 2118/2118/573 2116/2116/573 2117/2117/573 +f 2074/2074/4457 2069/2069/4359 2066/2066/4356 +f 2069/2069/4359 2076/2076/4458 2079/2079/4459 +f 2074/2074/4457 2078/2078/4460 2077/2077/4461 +f 2066/2066/4356 2078/2078/4460 2074/2074/4457 +f 2074/2074/4457 2076/2076/4458 2069/2069/4359 +f 2079/2079/4459 2070/2070/4360 2069/2069/4359 +f 2120/2120/573 2119/2119/573 2121/2121/573 +f 2122/2122/573 2123/2123/573 2125/2125/573 +f 2125/2125/573 2124/2124/573 2122/2122/573 +f 2127/2127/573 2126/2126/573 2128/2128/573 +f 2128/2128/573 2126/2126/573 2129/2129/573 +f 2130/2130/4462 2100/2100/4463 2131/2131/4464 +f 2131/2131/4464 2100/2100/4463 2132/2132/4465 +f 2100/2100/4463 2133/2133/4466 2132/2132/4465 +f 2133/2133/4466 2100/2100/4463 2134/2134/4467 +f 2099/2099/4468 2134/2134/4467 2100/2100/4463 +f 2099/2099/4468 2135/2135/4469 2134/2134/4467 +f 2099/2099/4468 2136/2136/4470 2135/2135/4469 +f 2064/2064/4471 2086/2086/4379 2049/2049/4472 +f 2064/2064/4471 2137/2137/4473 2086/2086/4379 +f 2138/2138/4474 2099/2099/4468 2112/2112/4475 +f 2139/2139/4476 2099/2099/4468 2138/2138/4474 +f 2136/2136/4470 2099/2099/4468 2139/2139/4476 +f 2138/2138/4474 2112/2112/4475 2140/2140/4477 +f 2140/2140/4477 2113/2113/4478 2141/2141/4479 +f 2140/2140/4477 2112/2112/4475 2113/2113/4478 +f 2113/2113/4478 2142/2142/4480 2141/2141/4479 +f 2113/2113/4478 2143/2143/4481 2142/2142/4480 +f 2080/2080/4372 2143/2143/4481 2113/2113/4478 +f 2144/2144/4482 2076/2076/4483 2073/2073/4484 +f 2145/2145/4485 2076/2076/4483 2144/2144/4482 +f 2145/2145/4485 2079/2079/4371 2076/2076/4483 +f 2146/2146/4486 2079/2079/4371 2145/2145/4485 +f 2147/2147/4487 2079/2079/4371 2146/2146/4486 +f 2148/2148/4488 2079/2079/4371 2147/2147/4487 +f 2149/2149/4489 2079/2079/4371 2148/2148/4488 +f 2149/2149/4489 2080/2080/4372 2079/2079/4371 +f 2143/2143/4481 2080/2080/4372 2149/2149/4489 +f 2073/2073/4484 2150/2150/4490 2144/2144/4482 +f 2151/2151/4491 2073/2073/4484 2114/2114/4492 +f 2150/2150/4490 2073/2073/4484 2151/2151/4491 +f 2151/2151/4491 2114/2114/4492 2115/2115/4417 +f 2152/2152/4493 2115/2115/4417 2153/2153/4494 +f 2151/2151/4491 2115/2115/4417 2152/2152/4493 +f 2153/2153/4494 2115/2115/4417 2154/2154/4495 +f 2155/2155/4496 2082/2082/4375 2086/2086/4379 +f 2156/2156/4497 2082/2082/4375 2155/2155/4496 +f 2156/2156/4497 2115/2115/4417 2082/2082/4375 +f 2154/2154/4495 2115/2115/4417 2156/2156/4497 +f 2155/2155/4496 2086/2086/4379 2137/2137/4473 +f 2100/2100/4463 2157/2157/4498 2158/2158/4499 +f 2130/2130/4462 2157/2157/4498 2100/2100/4463 +f 2156/2156/573 2155/2155/573 2159/2159/573 +f 2133/2133/573 2134/2134/573 2160/2160/573 +f 2132/2132/573 2133/2133/573 2160/2160/573 +f 2131/2131/573 2132/2132/573 2160/2160/573 +f 2136/2136/573 2139/2139/573 2161/2161/573 +f 2161/2161/573 2160/2160/573 2136/2136/573 +f 2147/2147/573 2146/2146/573 2162/2162/573 +f 2140/2140/573 2141/2141/573 2161/2161/573 +f 2152/2152/573 2153/2153/573 2159/2159/573 +f 2137/2137/573 2064/2064/573 2159/2159/573 +f 2158/2158/4500 2157/2157/4501 2160/2160/4502 +f 2160/2160/4502 2163/2163/4503 2158/2158/4500 +f 2130/2130/573 2131/2131/573 2160/2160/573 +f 2155/2155/573 2137/2137/573 2159/2159/573 +f 2143/2143/573 2149/2149/573 2162/2162/573 +f 2064/2064/4504 2049/2049/4505 2164/2164/4506 +f 2164/2164/4506 2159/2159/4507 2064/2064/4504 +f 2139/2139/573 2138/2138/573 2161/2161/573 +f 2151/2151/573 2152/2152/573 2159/2159/573 +f 2150/2150/573 2151/2151/573 2159/2159/573 +f 2159/2159/573 2162/2162/573 2150/2150/573 +f 2144/2144/573 2150/2150/573 2162/2162/573 +f 2141/2141/573 2142/2142/573 2161/2161/573 +f 2154/2154/573 2156/2156/573 2159/2159/573 +f 2157/2157/573 2130/2130/573 2160/2160/573 +f 2135/2135/573 2136/2136/573 2160/2160/573 +f 2146/2146/573 2145/2145/573 2162/2162/573 +f 2153/2153/573 2154/2154/573 2159/2159/573 +f 2149/2149/573 2148/2148/573 2162/2162/573 +f 2148/2148/573 2147/2147/573 2162/2162/573 +f 2145/2145/573 2144/2144/573 2162/2162/573 +f 2142/2142/573 2143/2143/573 2162/2162/573 +f 2162/2162/573 2161/2161/573 2142/2142/573 +f 2134/2134/573 2135/2135/573 2160/2160/573 +f 2138/2138/573 2140/2140/573 2161/2161/573 +f 2161/2161/4508 2162/2162/4509 2165/2165/4510 +f 2165/2165/4510 2166/2166/4511 2161/2161/4508 +f 2164/2164/4512 2167/2167/4513 2159/2159/4514 +f 2160/2160/4515 2161/2161/4516 2166/2166/4517 +f 2166/2166/4517 2163/2163/4518 2160/2160/4515 +f 2162/2162/4519 2159/2159/4514 2167/2167/4513 +f 2167/2167/4513 2165/2165/4520 2162/2162/4519 +f 2164/2164/4521 2049/2049/4522 2086/2086/4523 +f 2165/2165/4524 2167/2167/4525 2087/2087/4526 +f 2086/2086/4523 2087/2087/4526 2167/2167/4525 +f 2163/2163/4527 2101/2101/4528 2100/2100/4529 +f 2166/2166/4530 2165/2165/4524 2087/2087/4526 +f 2166/2166/4530 2087/2087/4526 2104/2104/4531 +f 2104/2104/4531 2093/2093/4532 2166/2166/4530 +f 2100/2100/4529 2158/2158/4533 2163/2163/4527 +f 2102/2102/4534 2101/2101/4528 2166/2166/4530 +f 2101/2101/4528 2163/2163/4527 2166/2166/4530 +f 2166/2166/4530 2093/2093/4532 2102/2102/4534 +f 2167/2167/4525 2164/2164/4521 2086/2086/4523 +f 2168/2168/573 2169/2169/573 2170/2170/573 +f 2168/2168/4535 1908/1908/4535 1912/1912/4535 +f 2170/2170/4536 1908/1908/4536 2168/2168/4536 +f 1908/1908/4537 2170/2170/4537 1907/1907/4537 +f 2169/2169/4538 1907/1907/4538 2170/2170/4538 +f 2169/2169/4539 1918/1918/4539 1907/1907/4539 +f 1918/1918/4540 2169/2169/4540 2168/2168/4540 +f 1918/1918/4541 2168/2168/4541 1912/1912/4541 +f 2171/2171/573 2172/2172/573 2173/2173/573 +f 2172/2172/4542 1914/1914/4542 1920/1920/4542 +f 2171/2171/4543 1914/1914/4543 2172/2172/4543 +f 2171/2171/4544 1909/1909/4544 1914/1914/4544 +f 2171/2171/4545 1903/1903/4546 1909/1909/4547 +f 1903/1903/4546 2171/2171/4545 2173/2173/4548 +f 2173/2173/4549 1916/1916/4549 1903/1903/4549 +f 1916/1916/4550 2173/2173/4551 2172/2172/4552 +f 2172/2172/4552 1920/1920/4553 1916/1916/4550 +f 2051/2051/4554 1892/1892/4555 2058/2058/4556 +f 2051/2051/4554 2058/2058/4556 2062/2062/4557 +f 2056/2056/4558 2055/2055/4559 1889/1889/4560 +f 2062/2062/4557 2058/2058/4556 2056/2056/4558 +f 2062/2062/4557 2056/2056/4558 1889/1889/4560 +f 2055/2055/4559 2052/2052/4561 1889/1889/4560 +f 2174/2174/573 2175/2175/573 2176/2176/573 +f 1919/1919/4562 2175/2175/4562 1899/1899/4562 +f 1899/1899/4563 2175/2175/4563 2174/2174/4563 +f 1899/1899/4564 2174/2174/4564 1897/1897/4564 +f 2174/2174/4565 1913/1913/4566 1897/1897/4567 +f 1913/1913/4566 2174/2174/4565 2176/2176/4568 +f 1913/1913/4569 2176/2176/4569 2175/2175/4569 +f 1913/1913/4570 2175/2175/4570 1919/1919/4570 +f 1978/1978/4571 2177/2177/4572 2050/2050/4573 +f 2050/2050/4573 2177/2177/4572 2178/2178/4574 +f 2179/2179/573 2180/2180/573 2181/2181/573 +f 2036/2036/4575 1966/1966/4576 1901/1901/4577 +f 1890/1890/4346 2182/2182/4578 2183/2183/4579 +f 2184/2184/4580 1894/1894/4329 2185/2185/4581 +f 2185/2185/4581 1894/1894/4329 2051/2051/4328 +f 2185/2185/4581 2051/2051/4328 2186/2186/4582 +f 2186/2186/4582 2051/2051/4328 2179/2179/4583 +f 2179/2179/4583 2051/2051/4328 2180/2180/4584 +f 2180/2180/4584 2051/2051/4328 2187/2187/4585 +f 2187/2187/4585 2051/2051/4328 2188/2188/4586 +f 2188/2188/4586 2051/2051/4328 2062/2062/4347 +f 2188/2188/4586 2062/2062/4347 2189/2189/4587 +f 2189/2189/4587 2062/2062/4347 2190/2190/4588 +f 2190/2190/4588 2062/2062/4347 2183/2183/4579 +f 2183/2183/4579 2062/2062/4347 1890/1890/4346 +f 1894/1894/4329 2184/2184/4580 2191/2191/4589 +f 1894/1894/4329 2191/2191/4589 1895/1895/4590 +f 1895/1895/4590 2191/2191/4589 2192/2192/4591 +f 2193/2193/4592 1895/1895/4590 2192/2192/4591 +f 2194/2194/4593 1895/1895/4590 2193/2193/4592 +f 2195/2195/4594 1895/1895/4590 2194/2194/4593 +f 1980/1980/4595 1898/1898/4596 1895/1895/4590 +f 1980/1980/4595 1895/1895/4590 2195/2195/4594 +f 1973/1973/4597 1898/1898/4596 1980/1980/4595 +f 1887/1887/4598 1971/1971/4599 1886/1886/4600 +f 1987/1987/4601 1886/1886/4600 1971/1971/4599 +f 1983/1983/4602 1886/1886/4600 1987/1987/4601 +f 1981/1981/4603 1888/1888/4604 1886/1886/4600 +f 1981/1981/4603 1886/1886/4600 1983/1983/4602 +f 1986/1986/4605 1888/1888/4604 1981/1981/4603 +f 1888/1888/4604 1984/1984/4606 1985/1985/4607 +f 1984/1984/4606 1888/1888/4604 1986/1986/4605 +f 2182/2182/4578 1890/1890/4346 1985/1985/4607 +f 1985/1985/4607 1890/1890/4346 1888/1888/4604 +f 1898/1898/4596 1973/1973/4597 1972/1972/4608 +f 1898/1898/4596 1972/1972/4608 1974/1974/4609 +f 2050/2050/4573 1898/1898/4596 1975/1975/4610 +f 1975/1975/4610 1898/1898/4596 1974/1974/4609 +f 2050/2050/4573 1975/1975/4610 1976/1976/4611 +f 1977/1977/4612 2050/2050/4573 1976/1976/4611 +f 1978/1978/4571 2050/2050/4573 1977/1977/4612 +f 1965/1965/4613 1901/1901/4577 1966/1966/4576 +f 1967/1967/4614 1901/1901/4577 1965/1965/4613 +f 1887/1887/4598 1968/1968/4615 1969/1969/4616 +f 1968/1968/4615 1887/1887/4598 1901/1901/4577 +f 1968/1968/4615 1901/1901/4577 1967/1967/4614 +f 1970/1970/4617 1971/1971/4599 1887/1887/4598 +f 1970/1970/4617 1887/1887/4598 1969/1969/4616 +f 2192/2192/573 2191/2191/573 2196/2196/573 +f 1987/1987/573 1971/1971/573 2197/2197/573 +f 2197/2197/573 2198/2198/573 1987/1987/573 +f 1971/1971/573 1970/1970/573 2197/2197/573 +f 2190/2190/573 2183/2183/573 2181/2181/573 +f 1984/1984/573 1986/1986/573 2198/2198/573 +f 1985/1985/573 1984/1984/573 2198/2198/573 +f 1973/1973/573 1980/1980/573 2199/2199/573 +f 2182/2182/573 1985/1985/573 2198/2198/573 +f 2198/2198/573 2181/2181/573 2182/2182/573 +f 1980/1980/573 2195/2195/573 2199/2199/573 +f 1972/1972/573 1973/1973/573 2199/2199/573 +f 2180/2180/573 2187/2187/573 2181/2181/573 +f 1970/1970/573 1969/1969/573 2197/2197/573 +f 2183/2183/573 2182/2182/573 2181/2181/573 +f 1976/1976/573 1975/1975/573 2199/2199/573 +f 1975/1975/573 1974/1974/573 2199/2199/573 +f 1977/1977/573 1976/1976/573 2199/2199/573 +f 1974/1974/573 1972/1972/573 2199/2199/573 +f 1978/1978/573 1977/1977/573 2199/2199/573 +f 2194/2194/573 2193/2193/573 2196/2196/573 +f 2186/2186/573 2179/2179/573 2181/2181/573 +f 2193/2193/573 2192/2192/573 2196/2196/573 +f 2197/2197/573 1966/1966/573 2033/2033/573 +f 2185/2185/573 2186/2186/573 2181/2181/573 +f 2195/2195/573 2194/2194/573 2196/2196/573 +f 2196/2196/573 2199/2199/573 2195/2195/573 +f 2036/2036/4618 2200/2200/4619 2197/2197/4620 +f 2197/2197/4620 2033/2033/4621 2036/2036/4618 +f 1967/1967/573 1965/1965/573 2197/2197/573 +f 1986/1986/573 1981/1981/573 2198/2198/573 +f 1968/1968/573 1967/1967/573 2197/2197/573 +f 2191/2191/573 2184/2184/573 2181/2181/573 +f 2181/2181/573 2196/2196/573 2191/2191/573 +f 1983/1983/573 1987/1987/573 2198/2198/573 +f 2187/2187/573 2188/2188/573 2181/2181/573 +f 1965/1965/573 1966/1966/573 2197/2197/573 +f 2188/2188/573 2189/2189/573 2181/2181/573 +f 1981/1981/573 1983/1983/573 2198/2198/573 +f 2189/2189/573 2190/2190/573 2181/2181/573 +f 1969/1969/573 1968/1968/573 2197/2197/573 +f 2184/2184/573 2185/2185/573 2181/2181/573 +f 2178/2178/4622 2177/2177/4623 2199/2199/4624 +f 2199/2199/4624 2201/2201/4625 2178/2178/4622 +f 2177/2177/573 1978/1978/573 2199/2199/573 +f 1966/1966/4576 2036/2036/4575 2033/2033/4626 +f 2196/2196/4627 2181/2181/4628 2202/2202/4629 +f 2202/2202/4629 2203/2203/4630 2196/2196/4627 +f 2198/2198/4631 2197/2197/4632 2200/2200/4633 +f 2200/2200/4633 2204/2204/4634 2198/2198/4631 +f 2199/2199/4635 2196/2196/4627 2203/2203/4630 +f 2203/2203/4630 2201/2201/4636 2199/2199/4635 +f 2181/2181/4637 2198/2198/4631 2204/2204/4634 +f 2204/2204/4634 2202/2202/4638 2181/2181/4637 +f 2202/2202/4639 2204/2204/4640 1923/1923/4641 +f 1921/1921/4642 2201/2201/4643 2203/2203/4644 +f 2036/2036/4645 1901/1901/4646 2200/2200/4647 +f 1925/1925/4648 1921/1921/4642 2203/2203/4644 +f 2202/2202/4639 1923/1923/4641 2203/2203/4644 +f 1925/1925/4648 2203/2203/4644 1924/1924/3242 +f 1923/1923/4641 1924/1924/3242 2203/2203/4644 +f 2201/2201/4643 2050/2050/4649 2178/2178/4650 +f 1922/1922/4651 2204/2204/4640 1901/1901/4646 +f 1922/1922/4651 1923/1923/4641 2204/2204/4640 +f 2200/2200/4647 1901/1901/4646 2204/2204/4640 +f 1921/1921/4642 2050/2050/4649 2201/2201/4643 +f 2205/2205/4652 2206/2206/4653 2007/2007/4654 +f 2029/2029/4655 2007/2007/4654 2206/2206/4653 +f 2206/2206/4653 1943/1943/4213 2029/2029/4655 +f 1936/1936/4292 1935/1935/4656 1979/1979/4251 +f 2207/2207/4657 2208/2208/4658 2209/2209/4659 +f 1979/1979/4251 2195/2195/4660 2207/2207/4657 +f 1933/1933/4203 2037/2037/4313 2177/2177/4661 +f 2209/2209/4659 1936/1936/4292 1979/1979/4251 +f 2209/2209/4659 2018/2018/4293 1936/1936/4292 +f 2177/2177/4661 2037/2037/4313 2178/2178/4662 +f 1979/1979/4251 2207/2207/4657 2209/2209/4659 +f 2028/2028/4304 2027/2027/4663 2047/2047/4324 +f 1999/1999/4272 2028/2028/4304 2045/2045/4322 +f 2000/2000/4273 2041/2041/4664 2007/2007/4280 +f 1999/1999/4272 2043/2043/4320 2000/2000/4273 +f 2205/2205/4665 2007/2007/4280 2041/2041/4664 +f 2041/2041/4664 2000/2000/4273 2042/2042/4666 +f 2042/2042/4666 2000/2000/4273 2043/2043/4320 +f 2043/2043/4320 1999/1999/4272 2045/2045/4322 +f 2045/2045/4322 2028/2028/4304 2047/2047/4324 +f 2027/2027/4663 2009/2009/4667 2047/2047/4324 +f 2047/2047/4324 2009/2009/4667 2048/2048/4325 +f 2008/2008/4281 2048/2048/4325 2009/2009/4667 +f 2034/2034/4310 2048/2048/4325 2008/2008/4281 +f 1993/1993/4266 2208/2208/4658 2021/2021/4297 +f 2021/2021/4297 2208/2208/4658 2210/2210/4668 +f 2210/2210/4668 2208/2208/4658 2207/2207/4657 +f 2031/2031/4669 2021/2021/4297 2210/2210/4668 +f 2210/2210/4668 2207/2207/4657 2063/2063/4670 +f 2013/2013/4344 2032/2032/4671 2063/2063/4348 +f 2063/2063/4348 2032/2032/4671 2210/2210/4672 +f 2025/2025/4301 2023/2023/4299 2211/2211/4673 +f 2023/2023/4299 1964/1964/4236 2211/2211/4673 +f 1964/1964/4236 2034/2034/4310 2211/2211/4673 +f 2211/2211/4673 2008/2008/4281 2010/2010/4283 +f 2008/2008/4281 2211/2211/4673 2034/2034/4310 +f 2001/2001/4674 2061/2061/4343 2002/2002/4675 +f 2061/2061/4343 2011/2011/4676 2002/2002/4675 +f 2061/2061/4343 2059/2059/4340 1982/1982/4254 +f 2061/2061/4343 1982/1982/4254 2212/2212/4677 +f 2011/2011/4676 2061/2061/4343 2212/2212/4677 +f 2024/2024/4678 2212/2212/4677 2023/2023/4679 +f 1982/1982/4254 1964/1964/4236 2023/2023/4679 +f 2212/2212/4677 1982/1982/4254 2023/2023/4679 +f 2213/2213/573 2214/2214/573 2215/2215/573 +f 2214/2214/573 2216/2216/573 2215/2215/573 +f 2216/2216/4680 2028/2028/4680 2215/2215/4680 +f 2027/2027/4681 2028/2028/4681 2216/2216/4681 +f 2027/2027/4682 2216/2216/4682 2214/2214/4682 +f 2027/2027/4683 2214/2214/4683 1996/1996/4683 +f 2213/2213/4684 1996/1996/4684 2214/2214/4684 +f 2213/2213/4685 1997/1997/4685 1996/1996/4685 +f 2213/2213/4686 2028/2028/4687 1997/1997/4688 +f 2215/2215/4689 2028/2028/4687 2213/2213/4686 +f 2217/2217/573 2218/2218/573 2219/2219/573 +f 2220/2220/573 2219/2219/573 2218/2218/573 +f 2217/2217/4690 1932/1932/4691 2218/2218/4692 +f 1932/1932/4691 2217/2217/4690 1930/1930/4693 +f 2219/2219/4694 2017/2017/4695 2217/2217/4696 +f 2217/2217/4696 2017/2017/4695 1930/1930/4697 +f 2220/2220/4698 2017/2017/4699 2219/2219/4700 +f 2017/2017/4699 2220/2220/4698 1938/1938/4701 +f 2218/2218/4702 1938/1938/4702 2220/2220/4702 +f 2218/2218/4703 1932/1932/4703 1938/1938/4703 +f 2221/2221/573 2222/2222/573 2223/2223/573 +f 2221/2221/573 2223/2223/573 2224/2224/573 +f 2010/2010/4704 2221/2221/4705 2224/2224/4706 +f 2224/2224/4706 2211/2211/4707 2010/2010/4704 +f 2223/2223/4708 2211/2211/4709 2224/2224/4710 +f 2211/2211/4709 2223/2223/4708 2025/2025/4711 +f 2222/2222/4712 2025/2025/4713 2223/2223/4714 +f 2222/2222/4712 2026/2026/4715 2025/2025/4713 +f 2221/2221/4716 2026/2026/4717 2222/2222/4718 +f 2221/2221/4716 2010/2010/4719 2026/2026/4717 +f 2225/2225/4720 1949/1949/4721 2226/2226/4722 +f 2225/2225/4720 1947/1947/4723 1949/1949/4721 +f 2227/2227/4724 1950/1950/4725 2225/2225/4726 +f 2225/2225/4726 1950/1950/4725 1947/1947/4727 +f 2019/2019/4728 1950/1950/4729 2227/2227/4730 +f 2228/2228/4731 2019/2019/4728 2227/2227/4730 +f 2228/2228/4732 1949/1949/4733 2019/2019/4734 +f 2226/2226/4735 1949/1949/4733 2228/2228/4732 +f 2229/2229/4736 1961/1961/4736 1959/1959/4736 +f 1961/1961/4737 2229/2229/4737 2230/2230/4737 +f 2230/2230/4738 1955/1955/4738 1961/1961/4738 +f 2231/2231/4739 1955/1955/4739 2230/2230/4739 +f 1959/1959/4740 1955/1955/4740 2231/2231/4740 +f 2229/2229/4741 1959/1959/4741 2231/2231/4741 +f 1946/1946/4742 2232/2232/4742 2233/2233/4742 +f 2233/2233/4743 1942/1942/4743 1946/1946/4743 +f 2234/2234/4744 1942/1942/4744 2233/2233/4744 +f 2234/2234/4745 1940/1940/4746 1942/1942/4747 +f 2235/2235/4748 1940/1940/4746 2234/2234/4745 +f 1940/1940/4749 2235/2235/4750 1941/1941/4751 +f 1941/1941/4751 2235/2235/4750 2232/2232/4752 +f 2232/2232/4753 1946/1946/4753 1941/1941/4753 +f 2236/2236/573 2237/2237/573 2238/2238/573 +f 2235/2235/573 2233/2233/573 2232/2232/573 +f 2234/2234/573 2233/2233/573 2235/2235/573 +f 2239/2239/4754 1962/1962/4755 1963/1963/4756 +f 2240/2240/4757 1962/1962/4755 2239/2239/4754 +f 2240/2240/4758 1958/1958/4758 1962/1962/4758 +f 2241/2241/4759 1958/1958/4759 2240/2240/4759 +f 1958/1958/4760 2241/2241/4761 2020/2020/4762 +f 2242/2242/4763 2020/2020/4762 2241/2241/4761 +f 2020/2020/4764 2242/2242/4765 2239/2239/4766 +f 2020/2020/4764 2239/2239/4766 1963/1963/4767 +f 2230/2230/573 2229/2229/573 2231/2231/573 +f 2241/2241/573 2239/2239/573 2242/2242/573 +f 2240/2240/573 2239/2239/573 2241/2241/573 +f 2227/2227/573 2225/2225/573 2226/2226/573 +f 2227/2227/573 2226/2226/573 2228/2228/573 +f 2237/2237/4768 2029/2029/4768 1943/1943/4768 +f 2029/2029/4769 2237/2237/4769 2236/2236/4769 +f 2236/2236/4770 2006/2006/4770 2029/2029/4770 +f 2238/2238/4771 2006/2006/4772 2236/2236/4773 +f 2238/2238/4771 1939/1939/4774 2006/2006/4772 +f 2237/2237/4775 1943/1943/4776 1939/1939/4777 +f 2237/2237/4775 1939/1939/4777 2238/2238/4778 +f 2243/2243/573 2244/2244/573 2245/2245/573 +f 2014/2014/4779 2243/2243/4779 2022/2022/4779 +f 2245/2245/4780 2022/2022/4780 2243/2243/4780 +f 2245/2245/4781 2001/2001/4781 2022/2022/4781 +f 2244/2244/4782 2061/2061/4783 2245/2245/4784 +f 2245/2245/4784 2061/2061/4783 2001/2001/4785 +f 2061/2061/4786 2244/2244/4787 2243/2243/4788 +f 2243/2243/4788 2014/2014/4789 2061/2061/4786 +f 2246/2246/573 2247/2247/573 2248/2248/573 +f 2248/2248/573 2247/2247/573 2249/2249/573 +f 2210/2210/4790 2032/2032/4791 2249/2249/4792 +f 2249/2249/4792 2032/2032/4791 2248/2248/4793 +f 2247/2247/4794 2210/2210/4795 2249/2249/4796 +f 2210/2210/4795 2247/2247/4794 2031/2031/4797 +f 2246/2246/4798 2031/2031/4799 2247/2247/4800 +f 2246/2246/4798 2030/2030/4801 2031/2031/4799 +f 2030/2030/4802 2246/2246/4803 2032/2032/4804 +f 2248/2248/4805 2032/2032/4804 2246/2246/4803 +f 2250/2250/573 2251/2251/573 2252/2252/573 +f 2253/2253/573 2251/2251/573 2250/2250/573 +f 2252/2252/4806 2209/2209/4806 2208/2208/4806 +f 2251/2251/4807 2209/2209/4807 2252/2252/4807 +f 2251/2251/4808 2018/2018/4808 2209/2209/4808 +f 2018/2018/4809 2251/2251/4810 2253/2253/4811 +f 2018/2018/4809 2253/2253/4811 1993/1993/4812 +f 1993/1993/4813 2253/2253/4813 2250/2250/4813 +f 2250/2250/4814 2208/2208/4814 1993/1993/4814 +f 2252/2252/4815 2208/2208/4815 2250/2250/4815 +f 2254/2254/573 2255/2255/573 2256/2256/573 +f 2011/2011/4816 2255/2255/4816 2012/2012/4816 +f 2254/2254/4817 2012/2012/4817 2255/2255/4817 +f 2254/2254/4818 2024/2024/4818 2012/2012/4818 +f 2024/2024/4819 2254/2254/4820 2256/2256/4821 +f 2256/2256/4821 2212/2212/4822 2024/2024/4819 +f 2256/2256/4823 2011/2011/4823 2212/2212/4823 +f 2255/2255/4824 2011/2011/4824 2256/2256/4824 +f 2063/2063/4670 2207/2207/4657 2191/2191/4825 +f 2207/2207/4657 2195/2195/4660 2194/2194/4826 +f 2194/2194/4826 2193/2193/4827 2207/2207/4657 +f 2177/2177/4661 1978/1978/4250 1933/1933/4203 +f 2207/2207/4657 2192/2192/4828 2191/2191/4825 +f 2182/2182/4829 1985/1985/4257 1982/1982/4254 +f 2187/2187/4830 2188/2188/4831 2060/2060/4832 +f 2059/2059/4340 2060/2060/4832 2189/2189/4833 +f 2189/2189/4833 2190/2190/4834 2059/2059/4340 +f 2187/2187/4830 2060/2060/4832 2063/2063/4670 +f 2190/2190/4834 2183/2183/4835 2059/2059/4340 +f 2183/2183/4835 2182/2182/4829 2059/2059/4340 +f 2180/2180/4836 2187/2187/4830 2063/2063/4670 +f 2063/2063/4670 2179/2179/4837 2180/2180/4836 +f 2063/2063/4670 2185/2185/4838 2186/2186/4839 +f 2063/2063/4670 2184/2184/4840 2185/2185/4838 +f 2063/2063/4670 2186/2186/4839 2179/2179/4837 +f 1979/1979/4251 1980/1980/4252 2195/2195/4660 +f 2193/2193/4827 2192/2192/4828 2207/2207/4657 +f 2040/2040/4317 2158/2158/4841 2041/2041/4318 +f 2158/2158/4841 2157/2157/4842 2041/2041/4318 +f 1984/1984/4256 1986/1986/4258 1982/1982/4254 +f 2041/2041/4318 2157/2157/4842 2205/2205/4843 +f 2036/2036/4312 2034/2034/4310 2033/2033/4309 +f 2189/2189/4833 2060/2060/4832 2188/2188/4831 +f 2184/2184/4840 2063/2063/4670 2191/2191/4825 +f 1982/1982/4254 2059/2059/4340 2182/2182/4829 +f 2137/2137/4844 1948/1948/4218 2155/2155/4845 +f 1957/1957/4227 2151/2151/4846 2152/2152/4847 +f 1957/1957/4227 2152/2152/4847 2153/2153/4848 +f 1957/1957/4227 2153/2153/4848 1948/1948/4218 +f 1948/1948/4218 2153/2153/4848 2154/2154/4849 +f 1948/1948/4218 2154/2154/4849 2156/2156/4850 +f 2137/2137/4844 2064/2064/4352 1948/1948/4218 +f 2156/2156/4850 2155/2155/4845 1948/1948/4218 +f 2141/2141/4851 2142/2142/4852 1943/1943/4213 +f 2140/2140/4853 2141/2141/4851 1943/1943/4213 +f 2138/2138/4854 2140/2140/4853 2206/2206/4653 +f 2139/2139/4855 2138/2138/4854 2206/2206/4653 +f 2140/2140/4853 1943/1943/4213 2206/2206/4653 +f 2136/2136/4856 2139/2139/4855 2206/2206/4653 +f 2135/2135/4857 2136/2136/4856 2205/2205/4843 +f 2134/2134/4858 2135/2135/4857 2205/2205/4843 +f 2133/2133/4859 2134/2134/4858 2205/2205/4843 +f 2136/2136/4856 2206/2206/4653 2205/2205/4843 +f 2132/2132/4860 2133/2133/4859 2205/2205/4843 +f 2205/2205/4843 2157/2157/4842 2130/2130/4861 +f 2131/2131/4862 2132/2132/4860 2205/2205/4843 +f 2205/2205/4843 2130/2130/4861 2131/2131/4862 +f 2150/2150/4863 2151/2151/4846 1954/1954/4224 +f 1954/1954/4224 1953/1953/4223 2150/2150/4863 +f 1957/1957/4227 1954/1954/4224 2151/2151/4846 +f 2142/2142/4852 2143/2143/4864 1943/1943/4213 +f 1944/1944/4214 1943/1943/4213 2143/2143/4864 +f 2144/2144/4865 2150/2150/4863 1953/1953/4223 +f 1953/1953/4223 1944/1944/4214 2146/2146/4866 +f 1944/1944/4214 2143/2143/4864 2149/2149/4867 +f 2145/2145/4868 2144/2144/4865 1953/1953/4223 +f 2146/2146/4866 2145/2145/4868 1953/1953/4223 +f 1944/1944/4214 2149/2149/4867 2148/2148/4869 +f 2146/2146/4866 1944/1944/4214 2147/2147/4870 +f 1944/1944/4214 2148/2148/4869 2147/2147/4870 +f 2152/2152/5 2257/2257/5 2153/2153/5 +f 1970/1970/5 2258/2258/5 1969/1969/5 +f 2153/2153/5 2257/2257/5 2154/2154/5 +f 2184/2184/5 2259/2259/5 2260/2260/5 +f 2183/2183/5 2260/2260/5 2182/2182/5 +f 2182/2182/5 2261/2261/5 1985/1985/5 +f 1983/1983/5 2261/2261/5 1987/1987/5 +f 1985/1985/5 2261/2261/5 1984/1984/5 +f 1980/1980/5 2262/2262/5 2259/2259/5 +f 1981/1981/5 2261/2261/5 1983/1983/5 +f 2155/2155/5 2257/2257/5 2137/2137/5 +f 1978/1978/5 2262/2262/5 1977/1977/5 +f 2157/2157/5 2263/2263/5 2130/2130/5 +f 2139/2139/5 2263/2263/5 2264/2264/5 +f 1987/1987/5 2258/2258/5 1971/1971/5 +f 1984/1984/5 2261/2261/5 1986/1986/5 +f 2190/2190/5 2260/2260/5 2183/2183/5 +f 2143/2143/5 2264/2264/5 2265/2265/5 +f 1971/1971/5 2258/2258/5 1970/1970/5 +f 1986/1986/5 2261/2261/5 1981/1981/5 +f 2177/2177/5 2262/2262/5 1978/1978/5 +f 2151/2151/5 2265/2265/5 2257/2257/5 +f 2156/2156/5 2257/2257/5 2155/2155/5 +f 2154/2154/5 2257/2257/5 2156/2156/5 +f 2151/2151/5 2257/2257/5 2152/2152/5 +f 2036/2036/5 2266/2266/5 2035/2035/5 +f 2267/2267/5 2158/2158/5 2040/2040/5 +f 2044/2044/5 2046/2046/5 2267/2267/5 +f 2266/2266/5 2267/2267/5 2035/2035/5 +f 2046/2046/5 2035/2035/5 2267/2267/5 +f 2267/2267/5 2040/2040/5 2044/2044/5 +f 2037/2037/5 2038/2038/5 2268/2268/5 +f 2049/2049/4871 2269/2269/4524 2039/2039/1134 +f 2268/2268/5 2178/2178/5 2037/2037/5 +f 2269/2269/4524 2268/2268/5 2039/2039/1134 +f 2039/2039/1134 2268/2268/5 2038/2038/5 +f 2261/2261/4872 2266/2266/4873 2258/2258/4874 +f 2262/2262/4875 2268/2268/4876 2259/2259/4877 +f 2260/2260/4878 2270/2270/4879 2261/2261/4872 +f 2259/2259/4877 2271/2271/4880 2260/2260/4881 +f 2263/2263/4882 2272/2272/4883 2264/2264/4884 +f 2265/2265/4885 2273/2273/4886 2257/2257/4887 +f 2264/2264/4888 2274/2274/4889 2265/2265/4890 +f 2158/2158/4891 2263/2263/4892 2157/2157/4893 +f 2158/2158/4891 2267/2267/4894 2263/2263/4892 +f 2257/2257/4895 2269/2269/4896 2064/2064/4897 +f 2269/2269/4896 2049/2049/4898 2064/2064/4897 +f 2258/2258/4899 2266/2266/4900 2033/2033/4901 +f 2178/2178/4902 2268/2268/4903 2177/2177/4904 +f 2266/2266/4900 2036/2036/4905 2033/2033/4901 +f 2269/2269/4524 2271/2271/5 2268/2268/5 +f 2268/2268/4903 2262/2262/4906 2177/2177/4904 +f 2271/2271/5 2275/2275/5 2268/2268/5 +f 2273/2273/4907 2274/2274/5 2271/2271/5 +f 2274/2274/5 2266/2266/5 2271/2271/5 +f 2266/2266/5 2270/2270/5 2271/2271/5 +f 2271/2271/5 2269/2269/4524 2273/2273/4907 +f 2274/2274/5 2267/2267/5 2266/2266/5 +f 2274/2274/5 2272/2272/5 2267/2267/5 +f 1974/1974/5 1975/1975/5 2262/2262/5 +f 1967/1967/5 1968/1968/5 2258/2258/5 +f 1972/1972/5 1974/1974/5 2262/2262/5 +f 1976/1976/5 1977/1977/5 2262/2262/5 +f 2134/2134/5 2133/2133/5 2263/2263/5 +f 2133/2133/5 2132/2132/5 2263/2263/5 +f 2185/2185/5 2184/2184/5 2260/2260/5 +f 2184/2184/5 2191/2191/5 2259/2259/5 +f 2179/2179/5 2186/2186/5 2260/2260/5 +f 2182/2182/5 2260/2260/5 2261/2261/5 +f 1966/1966/5 1965/1965/5 2258/2258/5 +f 2180/2180/5 2179/2179/5 2260/2260/5 +f 2187/2187/5 2180/2180/5 2260/2260/5 +f 2195/2195/5 1980/1980/5 2259/2259/5 +f 2064/2064/5 2137/2137/5 2257/2257/5 +f 1980/1980/5 1973/1973/5 2262/2262/5 +f 2193/2193/5 2194/2194/5 2259/2259/5 +f 2033/2033/5 1966/1966/5 2258/2258/5 +f 2261/2261/4872 2270/2270/4879 2266/2266/4873 +f 2192/2192/5 2193/2193/5 2259/2259/5 +f 2131/2131/5 2130/2130/5 2263/2263/5 +f 2132/2132/5 2131/2131/5 2263/2263/5 +f 2194/2194/5 2195/2195/5 2259/2259/5 +f 2139/2139/5 2136/2136/5 2263/2263/5 +f 2188/2188/5 2187/2187/5 2260/2260/5 +f 1987/1987/5 2261/2261/5 2258/2258/5 +f 2136/2136/5 2135/2135/5 2263/2263/5 +f 2138/2138/5 2139/2139/5 2264/2264/5 +f 2142/2142/5 2141/2141/5 2264/2264/5 +f 2189/2189/5 2188/2188/5 2260/2260/5 +f 2186/2186/5 2185/2185/5 2260/2260/5 +f 2143/2143/5 2142/2142/5 2264/2264/5 +f 2190/2190/5 2189/2189/5 2260/2260/5 +f 2141/2141/5 2140/2140/5 2264/2264/5 +f 2148/2148/5 2149/2149/5 2265/2265/5 +f 2149/2149/5 2143/2143/5 2265/2265/5 +f 2147/2147/5 2148/2148/5 2265/2265/5 +f 2146/2146/5 2147/2147/5 2265/2265/5 +f 2145/2145/5 2146/2146/5 2265/2265/5 +f 2144/2144/5 2145/2145/5 2265/2265/5 +f 2140/2140/5 2138/2138/5 2264/2264/5 +f 2191/2191/5 2192/2192/5 2259/2259/5 +f 2150/2150/5 2144/2144/5 2265/2265/5 +f 2151/2151/5 2150/2150/5 2265/2265/5 +f 2135/2135/5 2134/2134/5 2263/2263/5 +f 1973/1973/5 1972/1972/5 2262/2262/5 +f 1965/1965/5 1967/1967/5 2258/2258/5 +f 1975/1975/5 1976/1976/5 2262/2262/5 +f 1968/1968/5 1969/1969/5 2258/2258/5 +f 2259/2259/4877 2268/2268/4876 2275/2275/4908 +f 2260/2260/4878 2271/2271/4909 2270/2270/4879 +f 2259/2259/4877 2275/2275/4908 2271/2271/4880 +f 2263/2263/4882 2267/2267/4910 2272/2272/4883 +f 2265/2265/4885 2274/2274/4911 2273/2273/4886 +f 2257/2257/4887 2273/2273/4886 2269/2269/4912 +f 2264/2264/4888 2272/2272/4913 2274/2274/4889 +f 2276/2276/4914 2277/2277/4915 2278/2278/4916 +f 2279/2279/4917 2276/2276/4914 2278/2278/4916 +f 2276/2276/4914 2279/2279/4917 2280/2280/4918 +f 2281/2281/4919 2282/2282/4920 2280/2280/4918 +f 2281/2281/4919 2280/2280/4918 2279/2279/4917 +f 2277/2277/4915 2283/2283/4921 2278/2278/4916 +f 2278/2278/4916 2283/2283/4921 2281/2281/4919 +f 2281/2281/4919 2283/2283/4921 2282/2282/4920 +f 2284/2284/4922 2285/2285/4922 2286/2286/4922 +f 2287/2287/4923 2285/2285/4923 2284/2284/4923 +f 2287/2287/4924 2284/2284/4924 2288/2288/4924 +f 2288/2288/4925 2284/2284/4925 2286/2286/4925 +f 2288/2288/4926 2286/2286/4926 2289/2289/4926 +f 2289/2289/4927 2286/2286/4927 2285/2285/4927 +f 2289/2289/4928 2285/2285/4928 2287/2287/4928 +f 2277/2277/4929 2287/2287/4929 2283/2283/4929 +f 2283/2283/4930 2287/2287/4931 2288/2288/4932 +f 2283/2283/4930 2288/2288/4932 2282/2282/4933 +f 2282/2282/4934 2288/2288/4934 2280/2280/4934 +f 2280/2280/4935 2288/2288/4935 2289/2289/4935 +f 2280/2280/4936 2289/2289/4936 2276/2276/4936 +f 2276/2276/4937 2289/2289/4938 2287/2287/4939 +f 2276/2276/4937 2287/2287/4939 2277/2277/4940 +f 2279/2279/4917 2278/2278/4916 2281/2281/4919 +f 2290/2290/4941 2291/2291/4942 2292/2292/4943 +f 2293/2293/4944 2294/2294/4945 2295/2295/4946 +f 2292/2292/4943 2291/2291/4942 2293/2293/4944 +f 2293/2293/4944 2291/2291/4942 2296/2296/4947 +f 2293/2293/4944 2296/2296/4947 2294/2294/4945 +f 2295/2295/4946 2297/2297/4948 2292/2292/4943 +f 2292/2292/4943 2297/2297/4948 2290/2290/4941 +f 2294/2294/4945 2297/2297/4948 2295/2295/4946 +f 2298/2298/4949 2299/2299/4950 2300/2300/4951 +f 2298/2298/4949 2300/2300/4951 2301/2301/4952 +f 2302/2302/4953 2300/2300/4954 2299/2299/4955 +f 2302/2302/4956 2299/2299/4957 2303/2303/4958 +f 2303/2303/4958 2299/2299/4957 2298/2298/4959 +f 2303/2303/4960 2298/2298/4960 2301/2301/4960 +f 2303/2303/4961 2301/2301/4961 2304/2304/4961 +f 2304/2304/4962 2301/2301/4962 2300/2300/4962 +f 2304/2304/4963 2300/2300/4954 2302/2302/4953 +f 2290/2290/4964 2302/2302/4965 2291/2291/4966 +f 2291/2291/4967 2302/2302/4968 2296/2296/4969 +f 2296/2296/4969 2302/2302/4968 2303/2303/4970 +f 2296/2296/4971 2303/2303/4971 2294/2294/4971 +f 2294/2294/4972 2303/2303/4973 2304/2304/4974 +f 2294/2294/4972 2304/2304/4974 2297/2297/4975 +f 2297/2297/4976 2304/2304/4976 2290/2290/4976 +f 2290/2290/4964 2304/2304/4977 2302/2302/4965 +f 2295/2295/4946 2292/2292/4943 2293/2293/4944 +f 2305/2305/4978 2306/2306/4979 2307/2307/4980 +f 2308/2308/4981 2309/2309/4982 2310/2310/4983 +f 2311/2311/4984 2305/2305/4978 2312/2312/4985 +f 2308/2308/4981 2310/2310/4983 2313/2313/4986 +f 2307/2307/4980 2309/2309/4982 2308/2308/4981 +f 2307/2307/4980 2306/2306/4979 2309/2309/4982 +f 2312/2312/4985 2305/2305/4978 2307/2307/4980 +f 2308/2308/4981 2313/2313/4986 2312/2312/4985 +f 2312/2312/4985 2313/2313/4986 2311/2311/4984 +f 2314/2314/4987 2315/2315/4988 2316/2316/4989 +f 2317/2317/4990 2315/2315/4988 2314/2314/4987 +f 2318/2318/4991 2316/2316/4991 2319/2319/4991 +f 2319/2319/4992 2316/2316/4992 2315/2315/4992 +f 2319/2319/4993 2315/2315/4994 2317/2317/4995 +f 2319/2319/4993 2317/2317/4995 2320/2320/4996 +f 2320/2320/4997 2317/2317/4998 2318/2318/4999 +f 2318/2318/4999 2317/2317/4998 2314/2314/5000 +f 2318/2318/5001 2314/2314/5001 2316/2316/5001 +f 2311/2311/5002 2318/2318/5003 2305/2305/5004 +f 2305/2305/5004 2318/2318/5003 2319/2319/5005 +f 2305/2305/5006 2319/2319/5006 2306/2306/5006 +f 2306/2306/5007 2319/2319/5008 2309/2309/5009 +f 2309/2309/5009 2319/2319/5008 2320/2320/5010 +f 2309/2309/5011 2320/2320/5011 2310/2310/5011 +f 2310/2310/5012 2320/2320/5013 2318/2318/5014 +f 2310/2310/5012 2318/2318/5014 2313/2313/5015 +f 2313/2313/5016 2318/2318/5016 2311/2311/5016 +f 2312/2312/4985 2307/2307/4980 2308/2308/4981 +f 2321/2321/5017 2322/2322/5018 2323/2323/5019 +f 2321/2321/5017 2324/2324/5020 2325/2325/5021 +f 2321/2321/5017 2323/2323/5019 2324/2324/5020 +f 2326/2326/5022 2322/2322/5018 2321/2321/5017 +f 2325/2325/5021 2327/2327/5023 2326/2326/5022 +f 2321/2321/5017 2325/2325/5021 2326/2326/5022 +f 2326/2326/5022 2327/2327/5023 2322/2322/5018 +f 2328/2328/5024 2329/2329/5024 2330/2330/5024 +f 2331/2331/5025 2328/2328/5026 2332/2332/5027 +f 2332/2332/5028 2328/2328/5029 2333/2333/5030 +f 2333/2333/5030 2328/2328/5029 2330/2330/5031 +f 2333/2333/5032 2330/2330/5032 2334/2334/5032 +f 2334/2334/5033 2330/2330/5033 2329/2329/5033 +f 2334/2334/5034 2329/2329/5034 2331/2331/5034 +f 2331/2331/5025 2329/2329/5035 2328/2328/5026 +f 2327/2327/5036 2331/2331/5037 2332/2332/5038 +f 2327/2327/5039 2332/2332/5040 2322/2322/5041 +f 2322/2322/5041 2332/2332/5040 2333/2333/5042 +f 2322/2322/5043 2333/2333/5044 2323/2323/5045 +f 2323/2323/5045 2333/2333/5044 2334/2334/5046 +f 2323/2323/5047 2334/2334/5047 2324/2324/5047 +f 2324/2324/5048 2334/2334/5049 2331/2331/5050 +f 2324/2324/5048 2331/2331/5050 2325/2325/5051 +f 2325/2325/5052 2331/2331/5037 2327/2327/5036 +f 2335/2335/5053 2336/2336/5054 2337/2337/5055 +f 2337/2337/5055 2338/2338/5056 2339/2339/5057 +f 2337/2337/5055 2336/2336/5054 2340/2340/5058 +f 2341/2341/5059 2335/2335/5053 2339/2339/5057 +f 2337/2337/5055 2340/2340/5058 2338/2338/5056 +f 2335/2335/5053 2341/2341/5059 2336/2336/5054 +f 2337/2337/5055 2339/2339/5057 2335/2335/5053 +f 2342/2342/5060 2343/2343/5061 2344/2344/5062 +f 2344/2344/5062 2345/2345/5063 2342/2342/5060 +f 2346/2346/5064 2343/2343/5065 2347/2347/5066 +f 2347/2347/5066 2343/2343/5065 2342/2342/5067 +f 2347/2347/5068 2342/2342/5069 2348/2348/5070 +f 2348/2348/5070 2342/2342/5069 2345/2345/5071 +f 2348/2348/5072 2345/2345/5072 2344/2344/5072 +f 2348/2348/5073 2344/2344/5073 2346/2346/5073 +f 2346/2346/5074 2344/2344/5074 2343/2343/5074 +f 2338/2338/5075 2346/2346/5076 2347/2347/5077 +f 2338/2338/5075 2347/2347/5077 2339/2339/5078 +f 2339/2339/5079 2347/2347/5080 2341/2341/5081 +f 2341/2341/5081 2347/2347/5080 2348/2348/5082 +f 2341/2341/5083 2348/2348/5083 2336/2336/5083 +f 2336/2336/5084 2348/2348/5085 2340/2340/5086 +f 2340/2340/5086 2348/2348/5085 2346/2346/5087 +f 2340/2340/5088 2346/2346/5088 2338/2338/5088 +f 2349/2349/5089 2350/2350/5090 2351/2351/5091 +f 2352/2352/5092 2353/2353/5093 2354/2354/5094 +f 2354/2354/5094 2353/2353/5093 2355/2355/5095 +f 2355/2355/5095 2356/2356/5096 2349/2349/5089 +f 2349/2349/5089 2356/2356/5096 2350/2350/5090 +f 2357/2357/5097 2352/2352/5092 2354/2354/5094 +f 2355/2355/5095 2353/2353/5093 2356/2356/5096 +f 2349/2349/5089 2351/2351/5091 2354/2354/5094 +f 2354/2354/5094 2351/2351/5091 2357/2357/5097 +f 2358/2358/5098 2359/2359/5099 2360/2360/5100 +f 2361/2361/5101 2360/2360/5101 2362/2362/5101 +f 2362/2362/5102 2360/2360/5102 2359/2359/5102 +f 2362/2362/5103 2359/2359/5103 2363/2363/5103 +f 2363/2363/5104 2359/2359/5104 2364/2364/5104 +f 2363/2363/5105 2364/2364/5106 2365/2365/5107 +f 2365/2365/5107 2364/2364/5106 2358/2358/5108 +f 2365/2365/5109 2358/2358/5110 2361/2361/5111 +f 2361/2361/5111 2358/2358/5110 2360/2360/5112 +f 2353/2353/5113 2361/2361/5114 2362/2362/5115 +f 2353/2353/5113 2362/2362/5115 2356/2356/5116 +f 2356/2356/5117 2362/2362/5118 2363/2363/5119 +f 2356/2356/5117 2363/2363/5119 2350/2350/5120 +f 2350/2350/5121 2363/2363/5121 2351/2351/5121 +f 2351/2351/5122 2363/2363/5123 2365/2365/5124 +f 2351/2351/5122 2365/2365/5124 2357/2357/5125 +f 2357/2357/5126 2365/2365/5127 2352/2352/5128 +f 2352/2352/5128 2365/2365/5127 2361/2361/5129 +f 2352/2352/5128 2361/2361/5129 2353/2353/5130 +f 2354/2354/5094 2355/2355/5095 2349/2349/5089 +f 2364/2364/5131 2359/2359/5099 2358/2358/5098 +f 2366/2366/5132 2367/2367/5133 2368/2368/5134 +f 2368/2368/5134 2369/2369/5135 2366/2366/5132 +f 2367/2367/5136 2370/2370/5137 2371/2371/5138 +f 2371/2371/5138 2368/2368/5139 2367/2367/5136 +f 2372/2372/5140 2371/2371/5138 2370/2370/5137 +f 2370/2370/5137 2373/2373/5141 2372/2372/5140 +f 2374/2374/5142 2372/2372/5140 2373/2373/5141 +f 2373/2373/5141 2375/2375/5143 2374/2374/5142 +f 2375/2375/5143 2376/2376/5144 2377/2377/5145 +f 2377/2377/5145 2374/2374/5142 2375/2375/5143 +f 2376/2376/5146 2378/2378/5147 2379/2379/5148 +f 2379/2379/5148 2377/2377/5149 2376/2376/5146 +f 2378/2378/5150 2380/2380/5151 2379/2379/5152 +f 2381/2381/5153 2379/2379/5152 2380/2380/5151 +f 2380/2380/5151 2382/2382/5154 2381/2381/5153 +f 2383/2383/5155 2381/2381/5153 2382/2382/5154 +f 2376/2376/5 2375/2375/5 2373/2373/5 +f 2366/2366/5 2382/2382/5 2380/2380/5 +f 2380/2380/5 2378/2378/5 2376/2376/5 +f 2376/2376/5 2373/2373/5 2370/2370/5 +f 2370/2370/5 2367/2367/5 2366/2366/5 +f 2366/2366/5 2380/2380/5 2376/2376/5 +f 2376/2376/5 2370/2370/5 2366/2366/5 +f 2368/2368/573 2371/2371/573 2372/2372/573 +f 2383/2383/573 2369/2369/573 2368/2368/573 +f 2368/2368/573 2372/2372/573 2374/2374/573 +f 2374/2374/573 2377/2377/573 2379/2379/573 +f 2379/2379/573 2381/2381/573 2383/2383/573 +f 2383/2383/573 2368/2368/573 2374/2374/573 +f 2374/2374/573 2379/2379/573 2383/2383/573 +f 2383/2383/5155 2382/2382/5154 2366/2366/5156 +f 2366/2366/5156 2369/2369/5157 2383/2383/5155 +f 2384/2384/5158 2385/2385/5159 2386/2386/5160 +f 2387/2387/5161 2386/2386/5160 2385/2385/5159 +f 2385/2385/5159 2388/2388/5162 2387/2387/5161 +f 2389/2389/5163 2387/2387/5161 2388/2388/5162 +f 2388/2388/5162 2390/2390/5164 2389/2389/5163 +f 2390/2390/5164 2391/2391/5165 2392/2392/5166 +f 2392/2392/5166 2389/2389/5163 2390/2390/5164 +f 2391/2391/5167 2393/2393/5168 2394/2394/5169 +f 2394/2394/5169 2392/2392/5170 2391/2391/5167 +f 2393/2393/5171 2395/2395/5172 2394/2394/5173 +f 2396/2396/5174 2394/2394/5173 2395/2395/5172 +f 2395/2395/5172 2397/2397/5175 2396/2396/5174 +f 2398/2398/5176 2396/2396/5174 2397/2397/5175 +f 2397/2397/5177 2399/2399/5178 2400/2400/5179 +f 2400/2400/5179 2398/2398/5180 2397/2397/5177 +f 2399/2399/5181 2401/2401/5182 2400/2400/5183 +f 2402/2402/5184 2400/2400/5183 2401/2401/5182 +f 2385/2385/5 2384/2384/5 2401/2401/5 +f 2395/2395/5 2393/2393/5 2391/2391/5 +f 2385/2385/5 2401/2401/5 2399/2399/5 +f 2399/2399/5 2397/2397/5 2395/2395/5 +f 2395/2395/5 2391/2391/5 2390/2390/5 +f 2390/2390/5 2388/2388/5 2385/2385/5 +f 2385/2385/5 2399/2399/5 2395/2395/5 +f 2395/2395/5 2390/2390/5 2385/2385/5 +f 2396/2396/573 2398/2398/573 2400/2400/573 +f 2402/2402/573 2386/2386/573 2387/2387/573 +f 2387/2387/573 2389/2389/573 2392/2392/573 +f 2392/2392/573 2394/2394/573 2396/2396/573 +f 2396/2396/573 2400/2400/573 2402/2402/573 +f 2402/2402/573 2387/2387/573 2392/2392/573 +f 2392/2392/573 2396/2396/573 2402/2402/573 +f 2402/2402/5184 2401/2401/5182 2384/2384/5158 +f 2384/2384/5158 2386/2386/5160 2402/2402/5184 +f 2717/2403/5185 2715/2404/5186 2713/2405/5187 +f 2606/2406/5188 2664/2407/5189 2613/2408/5190 +f 2660/2409/5191 2659/2410/5192 2502/2411/5193 +f 2666/2412/5194 2667/2413/5195 2506/2414/5196 +f 2539/2415/5197 2686/2416/5198 2683/2417/5199 +f 2482/2418/5200 2666/2412/5194 2672/2419/5201 +f 2412/2420/5202 2609/2421/5203 2411/2422/5204 +f 2654/2423/5205 2582/2424/5206 2655/2425/5207 +f 2635/2426/5208 2649/2427/5209 2700/2428/5210 +f 2722/2429/5211 2442/2430/5212 2444/2431/5213 +f 2593/2432/5214 2587/2433/5215 2588/2434/5216 +f 2556/2435/5217 2583/2436/5218 2589/2437/5219 +f 2705/2438/5220 2707/2439/5221 2522/2440/5222 +f 2508/2441/5223 2671/2442/5224 2501/2443/5225 +f 2490/2444/5226 2491/2445/5227 2594/2446/5228 +f 2581/2447/5229 2582/2424/5206 2588/2434/5216 +f 2515/2448/5230 2516/2449/5231 2517/2450/5232 +f 2699/2451/5233 2701/2452/5234 2702/2453/5235 +f 2716/2454/5236 2718/2455/5237 2715/2404/5186 +f 2505/2456/5238 2651/2457/5239 2650/2458/5240 +f 2429/2459/5241 2601/2460/5242 2597/2461/5243 +f 2661/2462/5244 2660/2409/5191 2657/2463/5245 +f 2671/2442/5224 2656/2464/5246 2501/2443/5225 +f 2504/2465/5247 2500/2466/5248 2499/2467/5249 +f 2413/2468/5250 2419/2469/5251 2613/2408/5190 +f 2719/2470/5252 2533/2471/5253 2531/2472/5254 +f 2481/2473/5255 2487/2474/5256 2670/2475/5257 +f 2516/2449/5231 2518/2476/5258 2520/2477/5259 +f 2575/2478/5260 2593/2432/5214 2594/2446/5228 +f 2577/2479/5261 2583/2436/5218 2556/2435/5217 +f 2522/2440/5222 2707/2439/5221 2523/2480/5262 +f 2507/2481/5263 2508/2441/5223 2651/2457/5239 +f 2720/2482/5264 2708/2483/5265 2719/2470/5252 +f 2583/2436/5218 2584/2484/5266 2589/2437/5219 +f 2578/2485/5267 2579/2486/5268 2585/2487/5269 +f 2648/2488/5270 2469/2489/5271 2472/2490/5272 +f 2641/2491/5273 2708/2483/5265 2720/2482/5264 +f 2686/2416/5198 2685/2492/5274 2683/2417/5199 +f 2672/2419/5201 2687/2493/5275 2480/2494/5276 +f 2567/2495/5277 2552/2496/5278 2496/2497/5279 +f 2695/2498/5280 2643/2499/5281 2474/2500/5282 +f 2595/2501/5283 2603/2502/5284 2602/2503/5285 +f 2652/2504/5286 2564/2505/5287 2651/2457/5239 +f 2704/2506/5288 2710/2507/5289 2709/2508/5290 +f 2547/2509/5291 2543/2510/5292 2549/2511/5293 +f 2625/2512/5294 2629/2513/5295 2455/2514/5296 +f 2517/2450/5232 2519/2515/5297 2515/2448/5230 +f 2741/2516/5298 2428/2517/5299 2597/2461/5243 +f 2713/2405/5187 2639/2518/5300 2631/2519/5301 +f 2486/2520/5302 2481/2473/5255 2669/2521/5303 +f 2548/2522/5304 2547/2509/5291 2549/2511/5293 +f 2688/2523/5305 2674/2524/5306 2601/2460/5242 +f 2561/2525/5307 2497/2526/5308 2488/2527/5309 +f 2439/2528/5310 2440/2529/5311 2706/2530/5312 +f 2695/2498/5280 2696/2531/5313 2698/2532/5314 +f 2673/2533/5315 2607/2534/5316 2608/2535/5317 +f 2408/2536/5318 2609/2421/5203 2616/2537/5319 +f 2594/2446/5228 2491/2445/5227 2552/2496/5278 +f 2589/2437/5219 2573/2538/5320 2653/2539/5321 +f 2542/2540/5322 2547/2509/5291 2544/2541/5323 +f 2461/2542/5324 2622/2543/5325 2629/2513/5295 +f 2686/2416/5198 2539/2415/5197 2538/2544/5326 +f 2473/2545/5327 2474/2500/5282 2643/2499/5281 +f 2569/2546/5328 2562/2547/5329 2563/2548/5330 +f 2592/2549/5331 2574/2550/5332 2591/2551/5333 +f 2467/2552/5334 2466/2553/5335 2633/2554/5336 +f 2509/2555/5337 2535/2556/5338 2689/2557/5339 +f 2718/2455/5237 2640/2558/5340 2636/2559/5341 +f 2572/2560/5342 2581/2447/5229 2580/2561/5343 +f 2478/2562/5344 2479/2563/5345 2690/2564/5346 +f 2727/2565/5347 2728/2566/5348 2731/2567/5349 +f 2519/2515/5297 2551/2568/5350 2548/2522/5304 +f 2445/2569/5351 2724/2570/5352 2446/2571/5353 +f 2614/2572/5354 2615/2573/5355 2661/2462/5244 +f 2714/2574/5356 2710/2507/5289 2527/2575/5357 +f 2683/2417/5199 2682/2576/5358 2684/2577/5359 +f 2714/2574/5356 2713/2405/5187 2712/2578/5360 +f 2525/2579/5361 2549/2511/5293 2542/2540/5322 +f 2629/2513/5295 2453/2580/5362 2454/2581/5363 +f 2695/2498/5280 2692/2582/5364 2694/2583/5365 +f 2512/2584/5366 2577/2479/5261 2510/2585/5367 +f 2465/2586/5368 2467/2552/5334 2638/2587/5369 +f 2502/2411/5193 2537/2588/5370 2577/2479/5261 +f 2701/2452/5234 2699/2451/5233 2498/2589/5371 +f 2572/2560/5342 2551/2568/5350 2550/2590/5372 +f 2694/2583/5365 2690/2564/5346 2554/2591/5373 +f 2733/2592/5374 2730/2593/5375 2729/2594/5376 +f 2716/2454/5236 2534/2595/5377 2532/2596/5378 +f 2554/2591/5373 2553/2597/5379 2694/2583/5365 +f 2521/2598/5380 2546/2599/5381 2706/2530/5312 +f 2727/2565/5347 2731/2567/5349 2732/2600/5382 +f 2443/2601/5383 2442/2430/5212 2722/2429/5211 +f 2725/2602/5384 2721/2603/5385 2525/2579/5361 +f 2601/2460/5242 2676/2604/5386 2600/2605/5387 +f 2510/2585/5367 2513/2606/5388 2512/2584/5366 +f 2536/2607/5389 2535/2556/5338 2557/2608/5390 +f 2550/2590/5372 2519/2515/5297 2520/2477/5259 +f 2542/2540/5322 2543/2510/5292 2547/2509/5291 +f 2553/2597/5379 2488/2527/5309 2696/2531/5313 +f 2635/2426/5208 2709/2508/5290 2634/2609/5391 +f 2488/2527/5309 2553/2597/5379 2555/2610/5392 +f 2563/2548/5330 2557/2608/5390 2558/2611/5393 +f 2528/2612/5394 2498/2589/5371 2497/2526/5308 +f 2678/2613/5395 2679/2614/5396 2599/2615/5397 +f 2446/2571/5353 2724/2570/5352 2723/2616/5398 +f 2571/2617/5399 2570/2618/5400 2563/2548/5330 +f 2728/2566/5348 2719/2470/5252 2531/2472/5254 +f 2693/2619/5401 2697/2620/5402 2546/2599/5381 +f 2608/2535/5317 2421/2621/5403 2595/2501/5283 +f 2448/2622/5404 2447/2623/5405 2721/2603/5385 +f 2620/2624/5406 2619/2625/5407 2597/2461/5243 +f 2472/2490/5272 2470/2626/5408 2643/2499/5281 +f 2615/2573/5355 2616/2537/5319 2661/2462/5244 +f 2527/2575/5357 2710/2507/5289 2704/2506/5288 +f 2609/2421/5203 2410/2627/5409 2411/2422/5204 +f 2487/2474/5256 2671/2442/5224 2670/2475/5257 +f 2507/2481/5263 2506/2414/5196 2667/2413/5195 +f 2650/2458/5240 2555/2610/5392 2505/2456/5238 +f 2568/2628/5410 2577/2479/5261 2512/2584/5366 +f 2555/2610/5392 2561/2525/5307 2488/2527/5309 +f 2407/2629/5411 2616/2537/5319 2615/2573/5355 +f 2732/2600/5382 2729/2594/5376 2629/2513/5295 +f 2575/2478/5260 2592/2549/5331 2593/2432/5214 +f 2663/2630/5412 2673/2533/5315 2686/2416/5198 +f 2627/2631/5413 2720/2482/5264 2727/2565/5347 +f 2727/2565/5347 2720/2482/5264 2728/2566/5348 +f 2548/2522/5304 2525/2579/5361 2515/2448/5230 +f 2702/2453/5235 2703/2632/5414 2649/2427/5209 +f 2708/2483/5265 2641/2491/5273 2642/2633/5415 +f 2609/2421/5203 2409/2634/5416 2410/2627/5409 +f 2633/2554/5336 2638/2587/5369 2467/2552/5334 +f 2441/2635/5417 2707/2439/5221 2705/2438/5220 +f 2674/2524/5306 2676/2604/5386 2601/2460/5242 +f 2642/2633/5415 2463/2636/5418 2630/2637/5419 +f 2524/2638/5420 2723/2616/5398 2724/2570/5352 +f 2729/2594/5376 2732/2600/5382 2731/2567/5349 +f 2617/2639/5421 2741/2516/5298 2597/2461/5243 +f 2556/2435/5217 2589/2437/5219 2504/2465/5247 +f 2687/2493/5275 2690/2564/5346 2479/2563/5345 +f 2587/2433/5215 2593/2432/5214 2592/2549/5331 +f 2414/2640/5422 2413/2468/5250 2613/2408/5190 +f 2573/2538/5320 2652/2504/5286 2653/2539/5321 +f 2691/2641/5423 2694/2583/5365 2692/2582/5364 +f 2652/2504/5286 2573/2538/5320 2564/2505/5287 +f 2671/2442/5224 2487/2474/5256 2662/2642/5424 +f 2480/2494/5276 2482/2418/5200 2672/2419/5201 +f 2686/2416/5198 2673/2533/5315 2685/2492/5274 +f 2582/2424/5206 2489/2643/5425 2588/2434/5216 +f 2682/2576/5358 2602/2503/5285 2603/2502/5284 +f 2674/2524/5306 2675/2644/5426 2676/2604/5386 +f 2492/2645/5427 2494/2646/5428 2552/2496/5278 +f 2420/2647/5429 2421/2621/5403 2607/2534/5316 +f 2550/2590/5372 2582/2424/5206 2572/2560/5342 +f 2643/2499/5281 2698/2532/5314 2648/2488/5270 +f 2499/2467/5249 2502/2411/5193 2504/2465/5247 +f 2583/2436/5218 2577/2479/5261 2578/2485/5267 +f 2719/2470/5252 2716/2454/5236 2532/2596/5378 +f 2627/2631/5413 2727/2565/5347 2628/2648/5430 +f 2576/2649/5431 2568/2628/5410 2569/2546/5328 +f 2679/2614/5396 2680/2650/5432 2598/2651/5433 +f 2574/2550/5332 2575/2478/5260 2566/2652/5434 +f 2580/2561/5343 2581/2447/5229 2587/2433/5215 +f 2506/2414/5196 2505/2456/5238 2672/2419/5201 +f 2535/2556/5338 2536/2607/5389 2675/2644/5426 +f 2623/2653/5435 2626/2654/5436 2740/2655/5437 +f 2630/2637/5419 2637/2656/5438 2636/2559/5341 +f 2558/2611/5393 2559/2657/5439 2563/2548/5330 +f 2658/2658/5440 2661/2462/5244 2616/2537/5319 +f 2459/2659/5441 2626/2654/5436 2624/2660/5442 +f 2607/2534/5316 2673/2533/5315 2663/2630/5412 +f 2700/2428/5210 2709/2508/5290 2635/2426/5208 +f 2656/2464/5246 2660/2409/5191 2499/2467/5249 +f 2661/2462/5244 2657/2463/5245 2404/2661/5443 +f 2625/2512/5294 2461/2542/5324 2629/2513/5295 +f 2557/2608/5390 2563/2548/5330 2562/2547/5329 +f 2607/2534/5316 2606/2406/5188 2420/2647/5429 +f 2665/2662/5444 2502/2411/5193 2659/2410/5192 +f 2485/2663/5445 2668/2664/5446 2667/2413/5195 +f 2704/2506/5288 2701/2452/5234 2528/2612/5394 +f 2674/2524/5306 2688/2523/5305 2675/2644/5426 +f 2654/2423/5205 2489/2643/5425 2582/2424/5206 +f 2697/2620/5402 2439/2528/5310 2706/2530/5312 +f 2552/2496/5278 2494/2646/5428 2496/2497/5279 +f 2638/2587/5369 2631/2519/5301 2639/2518/5300 +f 2432/2665/5447 2433/2666/5448 2688/2523/5305 +f 2445/2569/5351 2725/2602/5384 2724/2570/5352 +f 2541/2667/5449 2562/2547/5329 2513/2606/5388 +f 2739/2668/5450 2624/2660/5442 2623/2653/5435 +f 2483/2669/5451 2484/2670/5452 2667/2413/5195 +f 2732/2600/5382 2629/2513/5295 2622/2543/5325 +f 2541/2667/5449 2536/2607/5389 2557/2608/5390 +f 2647/2671/5453 2468/2672/5454 2646/2673/5455 +f 2505/2456/5238 2506/2414/5196 2651/2457/5239 +f 2731/2567/5349 2733/2592/5374 2729/2594/5376 +f 2727/2565/5347 2732/2600/5382 2622/2543/5325 +f 2680/2650/5432 2682/2576/5358 2603/2502/5284 +f 2610/2674/5456 2419/2469/5251 2417/2675/5457 +f 2618/2676/5458 2742/2677/5459 2617/2639/5421 +f 2526/2678/5460 2529/2679/5461 2532/2596/5378 +f 2522/2440/5222 2523/2480/5262 2542/2540/5322 +f 2684/2577/5359 2682/2576/5358 2680/2650/5432 +f 2537/2588/5370 2538/2544/5326 2511/2680/5462 +f 2675/2644/5426 2677/2681/5463 2676/2604/5386 +f 2629/2513/5295 2454/2581/5363 2456/2682/5464 +f 2565/2683/5465 2574/2550/5332 2566/2652/5434 +f 2703/2632/5414 2701/2452/5234 2704/2506/5288 +f 2642/2633/5415 2640/2558/5340 2718/2455/5237 +f 2514/2684/5466 2538/2544/5326 2513/2606/5388 +f 2664/2407/5189 2663/2630/5412 2665/2662/5444 +f 2712/2578/5360 2713/2405/5187 2631/2519/5301 +f 2556/2435/5217 2502/2411/5193 2577/2479/5261 +f 2530/2685/5467 2531/2472/5254 2490/2444/5226 +f 2597/2461/5243 2424/2686/5468 2426/2687/5469 +f 2628/2648/5430 2727/2565/5347 2622/2543/5325 +f 2700/2428/5210 2704/2506/5288 2709/2508/5290 +f 2613/2408/5190 2658/2658/5440 2609/2421/5203 +f 2404/2661/5443 2614/2572/5354 2661/2462/5244 +f 2594/2446/5228 2567/2495/5277 2575/2478/5260 +f 2672/2419/5201 2666/2412/5194 2506/2414/5196 +f 2444/2431/5213 2446/2571/5353 2723/2616/5398 +f 2632/2688/5470 2712/2578/5360 2631/2519/5301 +f 2684/2577/5359 2680/2650/5432 2681/2689/5471 +f 2678/2613/5395 2677/2681/5463 2679/2614/5396 +f 2612/2690/5472 2738/2691/5473 2611/2692/5474 +f 2428/2517/5299 2429/2459/5241 2597/2461/5243 +f 2536/2607/5389 2677/2681/5463 2675/2644/5426 +f 2465/2586/5368 2630/2637/5419 2464/2693/5475 +f 2496/2497/5279 2495/2694/5476 2497/2526/5308 +f 2565/2683/5465 2564/2505/5287 2573/2538/5320 +f 2557/2608/5390 2509/2555/5337 2558/2611/5393 +f 2541/2667/5449 2540/2695/5477 2681/2689/5471 +f 2629/2513/5295 2456/2682/5464 2455/2514/5296 +f 2606/2406/5188 2613/2408/5190 2420/2647/5429 +f 2499/2467/5249 2501/2443/5225 2656/2464/5246 +f 2676/2604/5386 2678/2613/5395 2600/2605/5387 +f 2608/2535/5317 2605/2696/5478 2685/2492/5274 +f 2423/2697/5479 2595/2501/5283 2422/2698/5480 +f 2626/2654/5436 2623/2653/5435 2624/2660/5442 +f 2521/2598/5380 2522/2440/5222 2544/2541/5323 +f 2667/2413/5195 2668/2664/5446 2507/2481/5263 +f 2438/2699/5481 2439/2528/5310 2697/2620/5402 +f 2659/2410/5192 2661/2462/5244 2658/2658/5440 +f 2596/2700/5482 2423/2697/5479 2425/2701/5483 +f 2707/2439/5221 2722/2429/5211 2523/2480/5262 +f 2597/2461/5243 2599/2615/5397 2598/2651/5433 +f 2599/2615/5397 2597/2461/5243 2600/2605/5387 +f 2597/2461/5243 2601/2460/5242 2600/2605/5387 +f 2669/2521/5303 2508/2441/5223 2507/2481/5263 +f 2648/2488/5270 2649/2427/5209 2469/2489/5271 +f 2705/2438/5220 2522/2440/5222 2521/2598/5380 +f 2507/2481/5263 2668/2664/5446 2669/2521/5303 +f 2541/2667/5449 2557/2608/5390 2562/2547/5329 +f 2683/2417/5199 2684/2577/5359 2540/2695/5477 +f 2633/2554/5336 2631/2519/5301 2638/2587/5369 +f 2429/2459/5241 2430/2702/5484 2601/2460/5242 +f 2657/2463/5245 2405/2703/5485 2404/2661/5443 +f 2500/2466/5248 2504/2465/5247 2503/2704/5486 +f 2690/2564/5346 2687/2493/5275 2554/2591/5373 +f 2534/2595/5377 2527/2575/5357 2526/2678/5460 +f 2579/2486/5268 2570/2618/5400 2580/2561/5343 +f 2728/2566/5348 2720/2482/5264 2719/2470/5252 +f 2517/2450/5232 2520/2477/5259 2519/2515/5297 +f 2645/2705/5487 2472/2490/5272 2647/2671/5453 +f 2404/2661/5443 2406/2706/5488 2614/2572/5354 +f 2612/2690/5472 2611/2692/5474 2610/2674/5456 +f 2711/2707/5489 2710/2507/5289 2712/2578/5360 +f 2613/2408/5190 2609/2421/5203 2415/2708/5490 +f 2492/2645/5427 2552/2496/5278 2491/2445/5227 +f 2599/2615/5397 2600/2605/5387 2678/2613/5395 +f 2597/2461/5243 2426/2687/5469 2620/2624/5406 +f 2596/2700/5482 2598/2651/5433 2604/2709/5491 +f 2695/2498/5280 2698/2532/5314 2643/2499/5281 +f 2559/2657/5439 2571/2617/5399 2563/2548/5330 +f 2723/2616/5398 2524/2638/5420 2523/2480/5262 +f 2563/2548/5330 2570/2618/5400 2569/2546/5328 +f 2570/2618/5400 2571/2617/5399 2580/2561/5343 +f 2528/2612/5394 2527/2575/5357 2704/2506/5288 +f 2449/2710/5492 2730/2593/5375 2733/2592/5374 +f 2726/2711/5493 2449/2710/5492 2733/2592/5374 +f 2655/2425/5207 2550/2590/5372 2520/2477/5259 +f 2728/2566/5348 2530/2685/5467 2518/2476/5258 +f 2559/2657/5439 2544/2541/5323 2547/2509/5291 +f 2519/2515/5297 2550/2590/5372 2551/2568/5350 +f 2591/2551/5333 2585/2487/5269 2586/2712/5494 +f 2595/2501/5283 2423/2697/5479 2596/2700/5482 +f 2549/2511/5293 2543/2510/5292 2542/2540/5322 +f 2631/2519/5301 2633/2554/5336 2632/2688/5470 +f 2632/2688/5470 2633/2554/5336 2634/2609/5391 +f 2633/2554/5336 2635/2426/5208 2634/2609/5391 +f 2424/2686/5468 2597/2461/5243 2425/2701/5483 +f 2693/2619/5401 2689/2557/5339 2435/2713/5495 +f 2604/2709/5491 2595/2501/5283 2596/2700/5482 +f 2644/2714/5496 2736/2715/5497 2645/2705/5487 +f 2532/2596/5378 2534/2595/5377 2526/2678/5460 +f 2421/2621/5403 2608/2535/5317 2607/2534/5316 +f 2511/2680/5462 2538/2544/5326 2514/2684/5466 +f 2497/2526/5308 2498/2589/5371 2488/2527/5309 +f 2533/2471/5253 2532/2596/5378 2529/2679/5461 +f 2430/2702/5484 2431/2716/5498 2688/2523/5305 +f 2601/2460/5242 2430/2702/5484 2688/2523/5305 +f 2492/2645/5427 2493/2717/5499 2495/2694/5476 +f 2687/2493/5275 2505/2456/5238 2554/2591/5373 +f 2425/2701/5483 2597/2461/5243 2596/2700/5482 +f 2499/2467/5249 2660/2409/5191 2502/2411/5193 +f 2669/2521/5303 2670/2475/5257 2508/2441/5223 +f 2461/2542/5324 2462/2718/5500 2628/2648/5430 +f 2518/2476/5258 2654/2423/5205 2655/2425/5207 +f 2567/2495/5277 2566/2652/5434 2575/2478/5260 +f 2527/2575/5357 2528/2612/5394 2526/2678/5460 +f 2733/2592/5374 2518/2476/5258 2516/2449/5231 +f 2666/2412/5194 2482/2418/5200 2483/2669/5451 +f 2639/2518/5300 2637/2656/5438 2630/2637/5419 +f 2697/2620/5402 2706/2530/5312 2546/2599/5381 +f 2665/2662/5444 2663/2630/5412 2686/2416/5198 +f 2650/2458/5240 2564/2505/5287 2560/2719/5501 +f 2502/2411/5193 2556/2435/5217 2504/2465/5247 +f 2447/2623/5405 2726/2711/5493 2721/2603/5385 +f 2406/2706/5488 2615/2573/5355 2614/2572/5354 +f 2606/2406/5188 2663/2630/5412 2664/2407/5189 +f 2580/2561/5343 2585/2487/5269 2579/2486/5268 +f 2589/2437/5219 2590/2720/5502 2573/2538/5320 +f 2649/2427/5209 2635/2426/5208 2633/2554/5336 +f 2413/2468/5250 2417/2675/5457 2419/2469/5251 +f 2529/2679/5461 2493/2717/5499 2531/2472/5254 +f 2677/2681/5463 2678/2613/5395 2676/2604/5386 +f 2733/2592/5374 2731/2567/5349 2518/2476/5258 +f 2613/2408/5190 2664/2407/5189 2658/2658/5440 +f 2665/2662/5444 2686/2416/5198 2538/2544/5326 +f 2713/2405/5187 2715/2404/5186 2637/2656/5438 +f 2724/2570/5352 2725/2602/5384 2525/2579/5361 +f 2625/2512/5294 2739/2668/5450 2460/2721/5503 +f 2497/2526/5308 2561/2525/5307 2496/2497/5279 +f 2586/2712/5494 2580/2561/5343 2587/2433/5215 +f 2528/2612/5394 2701/2452/5234 2498/2589/5371 +f 2572/2560/5342 2547/2509/5291 2548/2522/5304 +f 2527/2575/5357 2534/2595/5377 2714/2574/5356 +f 2651/2457/5239 2506/2414/5196 2507/2481/5263 +f 2578/2485/5267 2590/2720/5502 2584/2484/5266 +f 2683/2417/5199 2685/2492/5274 2682/2576/5358 +f 2490/2444/5226 2531/2472/5254 2491/2445/5227 +f 2560/2719/5501 2565/2683/5465 2566/2652/5434 +f 2718/2455/5237 2636/2559/5341 2715/2404/5186 +f 2540/2695/5477 2684/2577/5359 2681/2689/5471 +f 2681/2689/5471 2677/2681/5463 2536/2607/5389 +f 2705/2438/5220 2706/2530/5312 2440/2529/5311 +f 2545/2722/5504 2559/2657/5439 2558/2611/5393 +f 2592/2549/5331 2575/2478/5260 2574/2550/5332 +f 2546/2599/5381 2521/2598/5380 2544/2541/5323 +f 2571/2617/5399 2559/2657/5439 2547/2509/5291 +f 2704/2506/5288 2700/2428/5210 2703/2632/5414 +f 2619/2625/5407 2618/2676/5458 2617/2639/5421 +f 2531/2472/5254 2530/2685/5467 2728/2566/5348 +f 2624/2660/5442 2625/2512/5294 2459/2659/5441 +f 2710/2507/5289 2714/2574/5356 2712/2578/5360 +f 2688/2523/5305 2431/2716/5498 2432/2665/5447 +f 2591/2551/5333 2574/2550/5332 2573/2538/5320 +f 2590/2720/5502 2589/2437/5219 2584/2484/5266 +f 2630/2637/5419 2465/2586/5368 2638/2587/5369 +f 2688/2523/5305 2689/2557/5339 2675/2644/5426 +f 2719/2470/5252 2708/2483/5265 2718/2455/5237 +f 2585/2487/5269 2590/2720/5502 2578/2485/5267 +f 2723/2616/5398 2722/2429/5211 2444/2431/5213 +f 2406/2706/5488 2407/2629/5411 2615/2573/5355 +f 2692/2582/5364 2695/2498/5280 2476/2723/5505 +f 2447/2623/5405 2449/2710/5492 2726/2711/5493 +f 2625/2512/5294 2624/2660/5442 2739/2668/5450 +f 2647/2671/5453 2644/2714/5496 2645/2705/5487 +f 2450/2724/5506 2629/2513/5295 2729/2594/5376 +f 2630/2637/5419 2636/2559/5341 2640/2558/5340 +f 2711/2707/5489 2712/2578/5360 2632/2688/5470 +f 2523/2480/5262 2524/2638/5420 2542/2540/5322 +f 2662/2642/5424 2403/2725/5507 2657/2463/5245 +f 2496/2497/5279 2494/2646/5428 2495/2694/5476 +f 2685/2492/5274 2605/2696/5478 2602/2503/5285 +f 2493/2717/5499 2492/2645/5427 2491/2445/5227 +f 2548/2522/5304 2515/2448/5230 2519/2515/5297 +f 2437/2726/5508 2438/2699/5481 2697/2620/5402 +f 2520/2477/5259 2517/2450/5232 2516/2449/5231 +f 2539/2415/5197 2540/2695/5477 2513/2606/5388 +f 2613/2408/5190 2415/2708/5490 2414/2640/5422 +f 2696/2531/5313 2694/2583/5365 2553/2597/5379 +f 2664/2407/5189 2665/2662/5444 2659/2410/5192 +f 2544/2541/5323 2522/2440/5222 2542/2540/5322 +f 2649/2427/5209 2633/2554/5336 2469/2489/5271 +f 2513/2606/5388 2510/2585/5367 2514/2684/5466 +f 2698/2532/5314 2702/2453/5235 2648/2488/5270 +f 2687/2493/5275 2479/2563/5345 2480/2494/5276 +f 2619/2625/5407 2617/2639/5421 2597/2461/5243 +f 2591/2551/5333 2586/2712/5494 2592/2549/5331 +f 2604/2709/5491 2680/2650/5432 2603/2502/5284 +f 2529/2679/5461 2526/2678/5460 2493/2717/5499 +f 2721/2603/5385 2515/2448/5230 2525/2579/5361 +f 2516/2449/5231 2515/2448/5230 2726/2711/5493 +f 2640/2558/5340 2642/2633/5415 2630/2637/5419 +f 2525/2579/5361 2548/2522/5304 2549/2511/5293 +f 2566/2652/5434 2561/2525/5307 2560/2719/5501 +f 2510/2585/5367 2577/2479/5261 2511/2680/5462 +f 2693/2619/5401 2509/2555/5337 2689/2557/5339 +f 2683/2417/5199 2540/2695/5477 2539/2415/5197 +f 2729/2594/5376 2452/2727/5509 2451/2728/5510 +f 2599/2615/5397 2679/2614/5396 2598/2651/5433 +f 2655/2425/5207 2582/2424/5206 2550/2590/5372 +f 2665/2662/5444 2537/2588/5370 2502/2411/5193 +f 2568/2628/5410 2576/2649/5431 2577/2479/5261 +f 2687/2493/5275 2672/2419/5201 2505/2456/5238 +f 2500/2466/5248 2503/2704/5486 2652/2504/5286 +f 2562/2547/5329 2568/2628/5410 2512/2584/5366 +f 2485/2663/5445 2486/2520/5302 2668/2664/5446 +f 2608/2535/5317 2685/2492/5274 2673/2533/5315 +f 2493/2717/5499 2526/2678/5460 2495/2694/5476 +f 2560/2719/5501 2555/2610/5392 2650/2458/5240 +f 2567/2495/5277 2594/2446/5228 2552/2496/5278 +f 2501/2443/5225 2499/2467/5249 2500/2466/5248 +f 2562/2547/5329 2512/2584/5366 2513/2606/5388 +f 2709/2508/5290 2711/2707/5489 2634/2609/5391 +f 2690/2564/5346 2694/2583/5365 2691/2641/5423 +f 2642/2633/5415 2718/2455/5237 2708/2483/5265 +f 2407/2629/5411 2408/2536/5318 2616/2537/5319 +f 2658/2658/5440 2664/2407/5189 2659/2410/5192 +f 2616/2537/5319 2609/2421/5203 2658/2658/5440 +f 2716/2454/5236 2715/2404/5186 2717/2403/5185 +f 2528/2612/5394 2497/2526/5308 2495/2694/5476 +f 2592/2549/5331 2586/2712/5494 2587/2433/5215 +f 2641/2491/5273 2720/2482/5264 2627/2631/5413 +f 2577/2479/5261 2576/2649/5431 2578/2485/5267 +f 2656/2464/5246 2671/2442/5224 2662/2642/5424 +f 2524/2638/5420 2525/2579/5361 2542/2540/5322 +f 2580/2561/5343 2586/2712/5494 2585/2487/5269 +f 2582/2424/5206 2581/2447/5229 2572/2560/5342 +f 2562/2547/5329 2569/2546/5328 2568/2628/5410 +f 2509/2555/5337 2546/2599/5381 2558/2611/5393 +f 2703/2632/5414 2702/2453/5235 2701/2452/5234 +f 2656/2464/5246 2662/2642/5424 2657/2463/5245 +f 2504/2465/5247 2589/2437/5219 2653/2539/5321 +f 2462/2718/5500 2627/2631/5413 2628/2648/5430 +f 2538/2544/5326 2537/2588/5370 2665/2662/5444 +f 2581/2447/5229 2588/2434/5216 2587/2433/5215 +f 2483/2669/5451 2667/2413/5195 2666/2412/5194 +f 2546/2599/5381 2545/2722/5504 2558/2611/5393 +f 2546/2599/5381 2509/2555/5337 2693/2619/5401 +f 2540/2695/5477 2541/2667/5449 2513/2606/5388 +f 2691/2641/5423 2692/2582/5364 2477/2729/5511 +f 2503/2704/5486 2653/2539/5321 2652/2504/5286 +f 2417/2675/5457 2612/2690/5472 2610/2674/5456 +f 2702/2453/5235 2698/2532/5314 2699/2451/5233 +f 2726/2711/5493 2733/2592/5374 2516/2449/5231 +f 2533/2471/5253 2719/2470/5252 2532/2596/5378 +f 2546/2599/5381 2544/2541/5323 2545/2722/5504 +f 2469/2489/5271 2468/2672/5454 2472/2490/5272 +f 2572/2560/5342 2580/2561/5343 2571/2617/5399 +f 2681/2689/5471 2536/2607/5389 2541/2667/5449 +f 2515/2448/5230 2721/2603/5385 2726/2711/5493 +f 2579/2486/5268 2578/2485/5267 2569/2546/5328 +f 2610/2674/5456 2611/2692/5474 2737/2730/5512 +f 2594/2446/5228 2588/2434/5216 2489/2643/5425 +f 2707/2439/5221 2441/2635/5417 2443/2601/5383 +f 2496/2497/5279 2561/2525/5307 2567/2495/5277 +f 2559/2657/5439 2545/2722/5504 2544/2541/5323 +f 2670/2475/5257 2669/2521/5303 2481/2473/5255 +f 2629/2513/5295 2450/2724/5506 2453/2580/5362 +f 2699/2451/5233 2488/2527/5309 2498/2589/5371 +f 2535/2556/5338 2509/2555/5337 2557/2608/5390 +f 2632/2688/5470 2634/2609/5391 2711/2707/5489 +f 2639/2518/5300 2713/2405/5187 2637/2656/5438 +f 2462/2718/5500 2463/2636/5418 2641/2491/5273 +f 2530/2685/5467 2490/2444/5226 2489/2643/5425 +f 2421/2621/5403 2422/2698/5480 2595/2501/5283 +f 2405/2703/5485 2657/2463/5245 2403/2725/5507 +f 2455/2514/5296 2459/2659/5441 2625/2512/5294 +f 2531/2472/5254 2533/2471/5253 2529/2679/5461 +f 2551/2568/5350 2572/2560/5342 2548/2522/5304 +f 2538/2544/5326 2539/2415/5197 2513/2606/5388 +f 2647/2671/5453 2472/2490/5272 2468/2672/5454 +f 2489/2643/5425 2654/2423/5205 2518/2476/5258 +f 2564/2505/5287 2565/2683/5465 2560/2719/5501 +f 2470/2626/5408 2473/2545/5327 2643/2499/5281 +f 2435/2713/5495 2437/2726/5508 2693/2619/5401 +f 2706/2530/5312 2705/2438/5220 2521/2598/5380 +f 2605/2696/5478 2608/2535/5317 2595/2501/5283 +f 2561/2525/5307 2566/2652/5434 2567/2495/5277 +f 2555/2610/5392 2554/2591/5373 2505/2456/5238 +f 2595/2501/5283 2602/2503/5285 2605/2696/5478 +f 2607/2534/5316 2663/2630/5412 2606/2406/5188 +f 2408/2536/5318 2409/2634/5416 2609/2421/5203 +f 2696/2531/5313 2699/2451/5233 2698/2532/5314 +f 2639/2518/5300 2630/2637/5419 2638/2587/5369 +f 2570/2618/5400 2579/2486/5268 2569/2546/5328 +f 2716/2454/5236 2717/2403/5185 2534/2595/5377 +f 2508/2441/5223 2501/2443/5225 2651/2457/5239 +f 2569/2546/5328 2578/2485/5267 2576/2649/5431 +f 2633/2554/5336 2466/2553/5335 2469/2489/5271 +f 2685/2492/5274 2602/2503/5285 2682/2576/5358 +f 2643/2499/5281 2648/2488/5270 2472/2490/5272 +f 2501/2443/5225 2500/2466/5248 2652/2504/5286 +f 2604/2709/5491 2603/2502/5284 2595/2501/5283 +f 2622/2543/5325 2461/2542/5324 2628/2648/5430 +f 2719/2470/5252 2718/2455/5237 2716/2454/5236 +f 2475/2731/5513 2477/2729/5511 2692/2582/5364 +f 2451/2728/5510 2450/2724/5506 2729/2594/5376 +f 2528/2612/5394 2495/2694/5476 2526/2678/5460 +f 2547/2509/5291 2572/2560/5342 2571/2617/5399 +f 2653/2539/5321 2503/2704/5486 2504/2465/5247 +f 2574/2550/5332 2565/2683/5465 2573/2538/5320 +f 2518/2476/5258 2655/2425/5207 2520/2477/5259 +f 2537/2588/5370 2511/2680/5462 2577/2479/5261 +f 2488/2527/5309 2699/2451/5233 2696/2531/5313 +f 2722/2429/5211 2707/2439/5221 2443/2601/5383 +f 2492/2645/5427 2495/2694/5476 2494/2646/5428 +f 2721/2603/5385 2725/2602/5384 2448/2622/5404 +f 2651/2457/5239 2501/2443/5225 2652/2504/5286 +f 2588/2434/5216 2594/2446/5228 2593/2432/5214 +f 2691/2641/5423 2477/2729/5511 2478/2562/5344 +f 2487/2474/5256 2403/2725/5507 2662/2642/5424 +f 2490/2444/5226 2594/2446/5228 2489/2643/5425 +f 2723/2616/5398 2523/2480/5262 2722/2429/5211 +f 2420/2647/5429 2613/2408/5190 2419/2469/5251 +f 2668/2664/5446 2486/2520/5302 2669/2521/5303 +f 2725/2602/5384 2445/2569/5351 2448/2622/5404 +f 2485/2663/5445 2667/2413/5195 2484/2670/5452 +f 2597/2461/5243 2598/2651/5433 2596/2700/5482 +f 2694/2583/5365 2696/2531/5313 2695/2498/5280 +f 2463/2636/5418 2464/2693/5475 2630/2637/5419 +f 2670/2475/5257 2671/2442/5224 2508/2441/5223 +f 2690/2564/5346 2691/2641/5423 2478/2562/5344 +f 2688/2523/5305 2433/2666/5448 2689/2557/5339 +f 2525/2579/5361 2524/2638/5420 2724/2570/5352 +f 2463/2636/5418 2642/2633/5415 2641/2491/5273 +f 2715/2404/5186 2636/2559/5341 2637/2656/5438 +f 2680/2650/5432 2604/2709/5491 2598/2651/5433 +f 2452/2727/5509 2729/2594/5376 2730/2593/5375 +f 2677/2681/5463 2681/2689/5471 2679/2614/5396 +f 2689/2557/5339 2436/2732/5514 2435/2713/5495 +f 2641/2491/5273 2627/2631/5413 2462/2718/5500 +f 2476/2723/5505 2475/2731/5513 2692/2582/5364 +f 2649/2427/5209 2703/2632/5414 2700/2428/5210 +f 2584/2484/5266 2583/2436/5218 2578/2485/5267 +f 2659/2410/5192 2660/2409/5191 2661/2462/5244 +f 2440/2529/5311 2441/2635/5417 2705/2438/5220 +f 2491/2445/5227 2531/2472/5254 2493/2717/5499 +f 2564/2505/5287 2650/2458/5240 2651/2457/5239 +f 2710/2507/5289 2711/2707/5489 2709/2508/5290 +f 2675/2644/5426 2689/2557/5339 2535/2556/5338 +f 2693/2619/5401 2437/2726/5508 2697/2620/5402 +f 2474/2500/5282 2476/2723/5505 2695/2498/5280 +f 2717/2403/5185 2713/2405/5187 2714/2574/5356 +f 2609/2421/5203 2412/2420/5202 2415/2708/5490 +f 2434/2733/5515 2436/2732/5514 2689/2557/5339 +f 2511/2680/5462 2514/2684/5466 2510/2585/5367 +f 2585/2487/5269 2591/2551/5333 2590/2720/5502 +f 2660/2409/5191 2656/2464/5246 2657/2463/5245 +f 2681/2689/5471 2680/2650/5432 2679/2614/5396 +f 2452/2727/5509 2730/2593/5375 2449/2710/5492 +f 2728/2566/5348 2518/2476/5258 2731/2567/5349 +f 2645/2705/5487 2736/2715/5497 2471/2734/5516 +f 2736/2715/5497 2644/2714/5496 2647/2671/5453 +f 2518/2476/5258 2530/2685/5467 2489/2643/5425 +f 2738/2691/5473 2612/2690/5472 2416/2735/5517 +f 2611/2692/5474 2738/2691/5473 2737/2730/5512 +f 2573/2538/5320 2590/2720/5502 2591/2551/5333 +f 2418/2736/5518 2610/2674/5456 2737/2730/5512 +f 2555/2610/5392 2560/2719/5501 2561/2525/5307 +f 2553/2597/5379 2554/2591/5373 2555/2610/5392 +f 2433/2666/5448 2434/2733/5515 2689/2557/5339 +f 2734/2737/5519 2735/2738/5519 2458/2739/5519 +f 2740/2655/5437 2626/2654/5436 2457/2740/5520 +f 2623/2653/5435 2740/2655/5437 2739/2668/5450 +f 2621/2741/5521 2741/2516/5522 2617/2639/5523 +f 2617/2639/5421 2742/2677/5459 2741/2516/5524 +f 2649/2427/5209 2648/2488/5270 2702/2453/5235 +f 2534/2595/5377 2717/2403/5185 2714/2574/5356 +f 2741/2516/5524 2742/2677/5459 2427/2742/5525 +f 2742/2677/5459 2618/2676/5458 2619/2625/5407 +f 3056/2743/5526 3052/2744/5527 3054/2745/5528 +f 2945/2746/5529 2952/2747/5530 3003/2748/5531 +f 2999/2749/5532 2841/2750/5533 2998/2751/5534 +f 3005/2752/5535 2845/2753/5536 3006/2754/5537 +f 2878/2755/5538 3022/2756/5539 3025/2757/5540 +f 2821/2758/5541 3011/2759/5542 3005/2752/5535 +f 2752/2760/5543 2751/2761/5544 2948/2762/5545 +f 2993/2763/5546 2994/2764/5547 2921/2765/5548 +f 2974/2766/5549 3039/2767/5550 2988/2768/5551 +f 3061/2769/5552 2784/2770/5553 2782/2771/5554 +f 2932/2772/5555 2927/2773/5556 2926/2774/5557 +f 2895/2775/5558 2928/2776/5559 2922/2777/5560 +f 3044/2778/5561 2861/2779/5562 3046/2780/5563 +f 2847/2781/5564 2840/2782/5565 3010/2783/5566 +f 2829/2784/5567 2933/2785/5568 2830/2786/5569 +f 2920/2787/5570 2927/2773/5556 2921/2765/5548 +f 2854/2788/5571 2856/2789/5572 2855/2790/5573 +f 3038/2791/5574 3041/2792/5575 3040/2793/5576 +f 3055/2794/5577 3054/2745/5528 3057/2795/5578 +f 2844/2796/5579 2989/2797/5580 2990/2798/5581 +f 2769/2799/5582 2936/2800/5583 2940/2801/5584 +f 3000/2802/5585 2996/2803/5586 2999/2749/5532 +f 3010/2783/5566 2840/2782/5565 2995/2804/5587 +f 2843/2805/5588 2838/2806/5589 2839/2807/5590 +f 2753/2808/5591 2952/2747/5530 2759/2809/5592 +f 3058/2810/5593 2870/2811/5594 2872/2812/5595 +f 2820/2813/5596 3009/2814/5597 2826/2815/5598 +f 2855/2790/5573 2859/2816/5599 2857/2817/5600 +f 2914/2818/5601 2933/2785/5568 2932/2772/5555 +f 2916/2819/5602 2895/2775/5558 2922/2777/5560 +f 2861/2779/5562 2862/2820/5603 3046/2780/5563 +f 2846/2821/5604 2990/2798/5581 2847/2781/5564 +f 3059/2822/5605 3058/2810/5593 3047/2823/5606 +f 2922/2777/5560 2928/2776/5559 2923/2824/5607 +f 2917/2825/5608 2924/2826/5609 2918/2827/5610 +f 2987/2828/5611 2811/2829/5612 2808/2830/5613 +f 2980/2831/5614 3059/2822/5605 3047/2823/5606 +f 3025/2757/5540 3022/2756/5539 3024/2832/5615 +f 3011/2759/5542 2819/2833/5616 3026/2834/5617 +f 2906/2835/5618 2835/2836/5619 2891/2837/5620 +f 3034/2838/5621 2813/2839/5622 2982/2840/5623 +f 2934/2841/5624 2941/2842/5625 2942/2843/5626 +f 2991/2844/5627 2990/2798/5581 2903/2845/5628 +f 3043/2846/5629 3048/2847/5630 3049/2848/5631 +f 2886/2849/5632 2888/2850/5633 2882/2851/5634 +f 2964/2852/5635 2795/2853/5636 2968/2854/5637 +f 2856/2789/5572 2854/2788/5571 2858/2855/5638 +f 3078/2856/5639 2936/2800/5583 2768/2857/5640 +f 3052/2744/5527 2970/2858/5641 2978/2859/5642 +f 2825/2860/5643 3008/2861/5644 2820/2813/5596 +f 2887/2862/5645 2888/2850/5633 2886/2849/5632 +f 3027/2863/5646 2940/2801/5584 3013/2864/5647 +f 2900/2865/5648 2827/2866/5649 2836/2867/5650 +f 2779/2868/5651 3045/2869/5652 2780/2870/5653 +f 3034/2838/5621 3037/2871/5654 3035/2872/5655 +f 3012/2873/5656 2947/2874/5657 2946/2875/5658 +f 2748/2876/5659 2955/2877/5660 2948/2762/5545 +f 2933/2785/5568 2891/2837/5620 2830/2786/5569 +f 2928/2776/5559 2992/2878/5661 2912/2879/5662 +f 2881/2880/5663 2883/2881/5664 2886/2849/5632 +f 2800/2882/5665 2968/2854/5637 2961/2883/5666 +f 3025/2757/5540 2877/2884/5667 2878/2755/5538 +f 2812/2885/5668 2982/2840/5623 2813/2839/5622 +f 2908/2886/5669 2902/2887/5670 2901/2888/5671 +f 2931/2889/5672 2930/2890/5673 2913/2891/5674 +f 2806/2892/5675 2972/2893/5676 2805/2894/5677 +f 2848/2895/5678 3028/2896/5679 2874/2897/5680 +f 3057/2795/5578 2975/2898/5681 2979/2899/5682 +f 2911/2900/5683 2919/2901/5684 2920/2787/5570 +f 2817/2902/5685 3029/2903/5686 2818/2904/5687 +f 3066/2905/5688 3070/2906/5689 3067/2907/5690 +f 2858/2855/5638 2887/2862/5645 2890/2908/5691 +f 2785/2909/5692 2786/2910/5693 3063/2911/5694 +f 2953/2912/5695 3000/2802/5585 2954/2913/5696 +f 3053/2914/5697 2866/2915/5698 3049/2848/5631 +f 3022/2756/5539 3023/2916/5699 3021/2917/5700 +f 3053/2914/5697 3051/2918/5701 3052/2744/5527 +f 2864/2919/5702 2881/2880/5663 2888/2850/5633 +f 2968/2854/5637 2794/2920/5703 2793/2921/5704 +f 3034/2838/5621 3033/2922/5705 3031/2923/5706 +f 2851/2924/5707 2849/2925/5708 2916/2819/5602 +f 2804/2926/5709 2977/2927/5710 2806/2892/5675 +f 2841/2750/5533 2916/2819/5602 2876/2928/5711 +f 3040/2793/5576 2837/2929/5712 3038/2791/5574 +f 2911/2900/5683 2889/2930/5713 2890/2908/5691 +f 3033/2922/5705 2893/2931/5714 3029/2903/5686 +f 3072/2932/5715 3068/2933/5716 3069/2934/5717 +f 3055/2794/5577 2871/2935/5718 2873/2936/5719 +f 2893/2931/5714 3033/2922/5705 2892/2937/5720 +f 2860/2938/5721 3045/2869/5652 2885/2939/5722 +f 3066/2905/5688 3071/2940/5723 3070/2906/5689 +f 2783/2941/5724 3061/2769/5552 2782/2771/5554 +f 3064/2942/5725 2864/2919/5702 3060/2943/5726 +f 2940/2801/5584 2939/2944/5727 3015/2945/5728 +f 2849/2925/5708 2851/2924/5707 2852/2946/5729 +f 2875/2947/5730 2896/2948/5731 2874/2897/5680 +f 2889/2930/5713 2859/2816/5599 2858/2855/5638 +f 2881/2880/5663 2886/2849/5632 2882/2851/5634 +f 2892/2937/5720 3035/2872/5655 2827/2866/5649 +f 2974/2766/5549 2973/2949/5732 3048/2847/5630 +f 2827/2866/5649 2894/2950/5733 2892/2937/5720 +f 2902/2887/5670 2897/2951/5734 2896/2948/5731 +f 2867/2952/5735 2836/2867/5650 2837/2929/5712 +f 3017/2953/5736 2938/2954/5737 3018/2955/5738 +f 2786/2910/5693 3062/2956/5739 3063/2911/5694 +f 2910/2957/5740 2902/2887/5670 2909/2958/5741 +f 3067/2907/5690 2870/2811/5594 3058/2810/5593 +f 3032/2959/5742 2885/2939/5722 3036/2960/5743 +f 2947/2874/5657 2934/2841/5624 2761/2961/5744 +f 2788/2962/5745 3060/2943/5726 2787/2963/5746 +f 2959/2964/5747 2936/2800/5583 2958/2965/5748 +f 2811/2829/5612 2982/2840/5623 2809/2966/5749 +f 2954/2913/5696 3000/2802/5585 2955/2877/5660 +f 2866/2915/5698 3043/2846/5629 3049/2848/5631 +f 2948/2762/5545 2751/2761/5544 2750/2967/5750 +f 2826/2815/5598 3009/2814/5597 3010/2783/5566 +f 2846/2821/5604 3006/2754/5537 2845/2753/5536 +f 2989/2797/5580 2844/2796/5579 2894/2950/5733 +f 2907/2968/5751 2851/2924/5707 2916/2819/5602 +f 2894/2950/5733 2827/2866/5649 2900/2865/5648 +f 2747/2969/5752 2954/2913/5696 2955/2877/5660 +f 3071/2940/5723 2968/2854/5637 3068/2933/5716 +f 2914/2818/5601 2932/2772/5555 2931/2889/5672 +f 3002/2970/5753 3025/2757/5540 3012/2873/5656 +f 2966/2971/5754 3066/2905/5688 3059/2822/5605 +f 3066/2905/5688 3067/2907/5690 3059/2822/5605 +f 2887/2862/5645 2854/2788/5571 2864/2919/5702 +f 3041/2792/5575 2988/2768/5551 3042/2972/5755 +f 3047/2823/5606 2981/2973/5756 2980/2831/5614 +f 2948/2762/5545 2750/2967/5750 2749/2974/5757 +f 2972/2893/5676 2806/2892/5675 2977/2927/5710 +f 2781/2975/5758 3044/2778/5561 3046/2780/5563 +f 3013/2864/5647 2940/2801/5584 3015/2945/5728 +f 2981/2973/5756 2969/2976/5759 2802/2977/5760 +f 2863/2978/5761 3063/2911/5694 3062/2956/5739 +f 3068/2933/5716 3070/2906/5689 3071/2940/5723 +f 2956/2979/5762 2936/2800/5583 3078/2856/5639 +f 2895/2775/5558 2843/2805/5588 2928/2776/5559 +f 3026/2834/5617 2818/2904/5687 3029/2903/5686 +f 2926/2774/5557 2931/2889/5672 2932/2772/5555 +f 2754/2980/5763 2952/2747/5530 2753/2808/5591 +f 2912/2879/5662 2992/2878/5661 2991/2844/5627 +f 3030/2981/5764 3031/2923/5706 3033/2922/5705 +f 2991/2844/5627 2903/2845/5628 2912/2879/5662 +f 3010/2783/5566 3001/2982/5765 2826/2815/5598 +f 2819/2833/5616 3011/2759/5542 2821/2758/5541 +f 3025/2757/5540 3024/2832/5615 3012/2873/5656 +f 2921/2765/5548 2927/2773/5556 2828/2983/5766 +f 3021/2917/5700 2942/2843/5626 2941/2842/5625 +f 3013/2864/5647 3015/2945/5728 3014/2984/5767 +f 2831/2985/5768 2891/2837/5620 2833/2986/5769 +f 2760/2987/5770 2946/2875/5658 2761/2961/5744 +f 2889/2930/5713 2911/2900/5683 2921/2765/5548 +f 2982/2840/5623 2987/2828/5611 3037/2871/5654 +f 2838/2806/5589 2843/2805/5588 2841/2750/5533 +f 2922/2777/5560 2917/2825/5608 2916/2819/5602 +f 3058/2810/5593 2871/2935/5718 3055/2794/5577 +f 2966/2971/5754 2967/2988/5771 3066/2905/5688 +f 2915/2989/5772 2908/2886/5669 2907/2968/5751 +f 3018/2955/5738 2937/2990/5773 3019/2991/5774 +f 2913/2891/5674 2905/2992/5775 2914/2818/5601 +f 2919/2901/5684 2926/2774/5557 2920/2787/5570 +f 2845/2753/5536 3011/2759/5542 2844/2796/5579 +f 2874/2897/5680 3014/2984/5767 2875/2947/5730 +f 2962/2993/5776 3077/2994/5777 2965/2995/5778 +f 2969/2976/5759 2975/2898/5681 2976/2996/5779 +f 2897/2951/5734 2902/2887/5670 2898/2997/5780 +f 2997/2998/5781 2955/2877/5660 3000/2802/5585 +f 2798/2999/5782 2963/3000/5783 2965/2995/5778 +f 2946/2875/5658 3002/2970/5753 3012/2873/5656 +f 3039/2767/5550 2974/2766/5549 3048/2847/5630 +f 2995/2804/5587 2838/2806/5589 2999/2749/5532 +f 3000/2802/5585 2744/3001/5784 2996/2803/5586 +f 2964/2852/5635 2968/2854/5637 2800/2882/5665 +f 2896/2948/5731 2901/2888/5671 2902/2887/5670 +f 2946/2875/5658 2760/2987/5770 2945/2746/5529 +f 3004/3002/5785 2998/2751/5534 2841/2750/5533 +f 2824/3003/5786 3006/2754/5537 3007/3004/5787 +f 3043/2846/5629 2867/2952/5735 3040/2793/5576 +f 3013/2864/5647 3014/2984/5767 3027/2863/5646 +f 2993/2763/5546 2921/2765/5548 2828/2983/5766 +f 3036/2960/5743 3045/2869/5652 2779/2868/5651 +f 2891/2837/5620 2835/2836/5619 2833/2986/5769 +f 2977/2927/5710 2978/2859/5642 2970/2858/5641 +f 2772/3005/5788 3027/2863/5646 2773/3006/5789 +f 2785/2909/5692 3063/2911/5694 3064/2942/5725 +f 2880/3007/5790 2852/2946/5729 2901/2888/5671 +f 3076/3008/5791 2962/2993/5776 2963/3000/5783 +f 2822/3009/5792 3006/2754/5537 2823/3010/5793 +f 3071/2940/5723 2961/2883/5666 2968/2854/5637 +f 2880/3007/5790 2896/2948/5731 2875/2947/5730 +f 2986/3011/5794 2985/3012/5795 2807/3013/5796 +f 2844/2796/5579 2990/2798/5581 2845/2753/5536 +f 3070/2906/5689 3068/2933/5716 3072/2932/5715 +f 3066/2905/5688 2961/2883/5666 3071/2940/5723 +f 3019/2991/5774 2942/2843/5626 3021/2917/5700 +f 2949/3014/5797 2757/3015/5798 2759/2809/5592 +f 2957/3016/5799 2956/2979/5762 3079/3017/5800 +f 2865/3018/5801 2871/2935/5718 2868/3019/5802 +f 2861/2779/5562 2881/2880/5663 2862/2820/5603 +f 3023/2916/5699 3019/2991/5774 3021/2917/5700 +f 2876/2928/5711 2850/3020/5803 2877/2884/5667 +f 3014/2984/5767 3015/2945/5728 3016/3021/5804 +f 2968/2854/5637 2796/3022/5805 2794/2920/5703 +f 2904/3023/5806 2905/2992/5775 2913/2891/5674 +f 3042/2972/5755 3043/2846/5629 3040/2793/5576 +f 2981/2973/5756 3057/2795/5578 2979/2899/5682 +f 2853/3024/5807 2852/2946/5729 2877/2884/5667 +f 3003/2748/5531 3004/3002/5785 3002/2970/5753 +f 3051/2918/5701 2970/2858/5641 3052/2744/5527 +f 2895/2775/5558 2916/2819/5602 2841/2750/5533 +f 2869/3025/5808 2829/2784/5567 2870/2811/5594 +f 2936/2800/5583 2766/3026/5809 2764/3027/5810 +f 2967/2988/5771 2961/2883/5666 3066/2905/5688 +f 3039/2767/5550 3048/2847/5630 3043/2846/5629 +f 2952/2747/5530 2948/2762/5545 2997/2998/5781 +f 2744/3001/5784 3000/2802/5585 2953/2912/5695 +f 2933/2785/5568 2914/2818/5601 2906/2835/5618 +f 3011/2759/5542 2845/2753/5536 3005/2752/5535 +f 2784/2770/5553 3062/2956/5739 2786/2910/5693 +f 2971/3028/5811 2970/2858/5641 3051/2918/5701 +f 3023/2916/5699 3020/3029/5812 3019/2991/5774 +f 3017/2953/5736 3018/2955/5738 3016/3021/5804 +f 2951/3030/5813 2950/3031/5814 3075/3032/5815 +f 2768/2857/5640 2936/2800/5583 2769/2799/5582 +f 2875/2947/5730 3014/2984/5767 3016/3021/5804 +f 2804/2926/5709 2803/3033/5816 2969/2976/5759 +f 2835/2836/5619 2836/2867/5650 2834/3034/5817 +f 2904/3023/5806 2912/2879/5662 2903/2845/5628 +f 2896/2948/5731 2897/2951/5734 2848/2895/5678 +f 2880/3007/5790 3020/3029/5812 2879/3035/5818 +f 2968/2854/5637 2795/2853/5636 2796/3022/5805 +f 2945/2746/5529 2760/2987/5770 2952/2747/5530 +f 2838/2806/5589 2995/2804/5587 2840/2782/5565 +f 3015/2945/5728 2939/2944/5727 3017/2953/5736 +f 2947/2874/5657 3024/2832/5615 2944/3036/5819 +f 2763/3037/5820 2762/3038/5821 2934/2841/5624 +f 2965/2995/5778 2963/3000/5783 2962/2993/5776 +f 2860/2938/5721 2883/2881/5664 2861/2779/5562 +f 3006/2754/5537 2846/2821/5604 3007/3004/5787 +f 2778/3039/5822 3036/2960/5743 2779/2868/5651 +f 2998/2751/5534 2997/2998/5781 3000/2802/5585 +f 2935/3040/5823 2765/3041/5824 2763/3037/5820 +f 3046/2780/5563 2862/2820/5603 3061/2769/5552 +f 2936/2800/5583 2937/2990/5773 2938/2954/5737 +f 2938/2954/5737 2939/2944/5727 2936/2800/5583 +f 2936/2800/5583 2939/2944/5727 2940/2801/5584 +f 3008/2861/5644 2846/2821/5604 2847/2781/5564 +f 2987/2828/5611 2808/2830/5613 2988/2768/5551 +f 3044/2778/5561 2860/2938/5721 2861/2779/5562 +f 2846/2821/5604 3008/2861/5644 3007/3004/5787 +f 2880/3007/5790 2901/2888/5671 2896/2948/5731 +f 3022/2756/5539 2879/3035/5818 3023/2916/5699 +f 2972/2893/5676 2977/2927/5710 2970/2858/5641 +f 2769/2799/5582 2940/2801/5584 2770/3042/5825 +f 2996/2803/5586 2744/3001/5784 2745/3043/5826 +f 2839/2807/5590 2842/3044/5827 2843/2805/5588 +f 3029/2903/5686 2893/2931/5714 3026/2834/5617 +f 2873/2936/5719 2865/3018/5801 2866/2915/5698 +f 2918/2827/5610 2919/2901/5684 2909/2958/5741 +f 3067/2907/5690 3058/2810/5593 3059/2822/5605 +f 2856/2789/5572 2858/2855/5638 2859/2816/5599 +f 2984/3045/5828 2986/3011/5794 2811/2829/5612 +f 2744/3001/5784 2953/2912/5695 2746/3046/5829 +f 2951/3030/5813 2949/3014/5797 2950/3031/5814 +f 3050/3047/5830 3051/2918/5701 3049/2848/5631 +f 2952/2747/5530 2755/3048/5831 2948/2762/5545 +f 2831/2985/5768 2830/2786/5569 2891/2837/5620 +f 2938/2954/5737 3017/2953/5736 2939/2944/5727 +f 2936/2800/5583 2959/2964/5747 2766/3026/5809 +f 2935/3040/5823 2943/3049/5832 2937/2990/5773 +f 3034/2838/5621 2982/2840/5623 3037/2871/5654 +f 2898/2997/5780 2902/2887/5670 2910/2957/5740 +f 3062/2956/5739 2862/2820/5603 2863/2978/5761 +f 2902/2887/5670 2908/2886/5669 2909/2958/5741 +f 2909/2958/5741 2919/2901/5684 2910/2957/5740 +f 2867/2952/5735 3043/2846/5629 2866/2915/5698 +f 2789/3050/5833 3072/2932/5715 3069/2934/5717 +f 3065/3051/5834 3072/2932/5715 2789/3050/5833 +f 2994/2764/5547 2859/2816/5599 2889/2930/5713 +f 3067/2907/5690 2857/2817/5600 2869/3025/5808 +f 2898/2997/5780 2886/2849/5632 2883/2881/5664 +f 2858/2855/5638 2890/2908/5691 2889/2930/5713 +f 2930/2890/5673 2925/3052/5835 2924/2826/5609 +f 2934/2841/5624 2935/3040/5823 2763/3037/5820 +f 2888/2850/5633 2881/2880/5663 2882/2851/5634 +f 2970/2858/5641 2971/3028/5811 2972/2893/5676 +f 2971/3028/5811 2973/2949/5732 2972/2893/5676 +f 2972/2893/5676 2973/2949/5732 2974/2766/5549 +f 2764/3027/5810 2765/3041/5824 2936/2800/5583 +f 3032/2959/5742 2775/3053/5836 3028/2896/5679 +f 2943/3049/5832 2935/3040/5823 2934/2841/5624 +f 2983/3054/5837 2984/3045/5828 3073/3055/5838 +f 2871/2935/5718 2865/3018/5801 2873/2936/5719 +f 2761/2961/5744 2946/2875/5658 2947/2874/5657 +f 2850/3020/5803 2853/3024/5807 2877/2884/5667 +f 2836/2867/5650 2827/2866/5649 2837/2929/5712 +f 2872/2812/5595 2868/3019/5802 2871/2935/5718 +f 2770/3042/5825 3027/2863/5646 2771/3056/5839 +f 2940/2801/5584 3027/2863/5646 2770/3042/5825 +f 2831/2985/5768 2834/3034/5817 2832/3057/5840 +f 3026/2834/5617 2893/2931/5714 2844/2796/5579 +f 2765/3041/5824 2935/3040/5823 2936/2800/5583 +f 2838/2806/5589 2841/2750/5533 2999/2749/5532 +f 3008/2861/5644 2847/2781/5564 3009/2814/5597 +f 2800/2882/5665 2967/2988/5771 2801/3058/5841 +f 2857/2817/5600 2994/2764/5547 2993/2763/5546 +f 2906/2835/5618 2914/2818/5601 2905/2992/5775 +f 2866/2915/5698 2865/3018/5801 2867/2952/5735 +f 3072/2932/5715 2855/2790/5573 2857/2817/5600 +f 3005/2752/5535 2822/3009/5792 2821/2758/5541 +f 2978/2859/5642 2969/2976/5759 2976/2996/5779 +f 3036/2960/5743 2885/2939/5722 3045/2869/5652 +f 3004/3002/5785 3025/2757/5540 3002/2970/5753 +f 2989/2797/5580 2899/3059/5842 2903/2845/5628 +f 2841/2750/5533 2843/2805/5588 2895/2775/5558 +f 2787/2963/5746 3060/2943/5726 3065/3051/5834 +f 2746/3046/5829 2953/2912/5695 2954/2913/5696 +f 2945/2746/5529 3003/2748/5531 3002/2970/5753 +f 2919/2901/5684 2918/2827/5610 2924/2826/5609 +f 2928/2776/5559 2912/2879/5662 2929/3060/5843 +f 2988/2768/5551 2972/2893/5676 2974/2766/5549 +f 2753/2808/5591 2759/2809/5592 2757/3015/5798 +f 2868/3019/5802 2870/2811/5594 2832/3057/5840 +f 3016/3021/5804 3015/2945/5728 3017/2953/5736 +f 3072/2932/5715 2857/2817/5600 3070/2906/5689 +f 2952/2747/5530 2997/2998/5781 3003/2748/5531 +f 3004/3002/5785 2877/2884/5667 3025/2757/5540 +f 3052/2744/5527 2976/2996/5779 3054/2745/5528 +f 3063/2911/5694 2864/2919/5702 3064/2942/5725 +f 2964/2852/5635 2799/3061/5844 3076/3008/5791 +f 2836/2867/5650 2835/2836/5619 2900/2865/5648 +f 2925/3052/5835 2926/2774/5557 2919/2901/5684 +f 2867/2952/5735 2837/2929/5712 3040/2793/5576 +f 2911/2900/5683 2887/2862/5645 2886/2849/5632 +f 2866/2915/5698 3053/2914/5697 2873/2936/5719 +f 2990/2798/5581 2846/2821/5604 2845/2753/5536 +f 2917/2825/5608 2923/2824/5607 2929/3060/5843 +f 3022/2756/5539 3021/2917/5700 3024/2832/5615 +f 2829/2784/5567 2830/2786/5569 2870/2811/5594 +f 2899/3059/5842 2905/2992/5775 2904/3023/5806 +f 3057/2795/5578 3054/2745/5528 2975/2898/5681 +f 2879/3035/5818 3020/3029/5812 3023/2916/5699 +f 3020/3029/5812 2875/2947/5730 3016/3021/5804 +f 3044/2778/5561 2780/2870/5653 3045/2869/5652 +f 2884/3062/5845 2897/2951/5734 2898/2997/5780 +f 2931/2889/5672 2913/2891/5674 2914/2818/5601 +f 2885/2939/5722 2883/2881/5664 2860/2938/5721 +f 2910/2957/5740 2886/2849/5632 2898/2997/5780 +f 3043/2846/5629 3042/2972/5755 3039/2767/5550 +f 2958/2965/5748 2956/2979/5762 2957/3016/5799 +f 2870/2811/5594 3067/2907/5690 2869/3025/5808 +f 2963/3000/5783 2798/2999/5782 2964/2852/5635 +f 3049/2848/5631 3051/2918/5701 3053/2914/5697 +f 3027/2863/5646 2772/3005/5788 2771/3056/5839 +f 2930/2890/5673 2912/2879/5662 2913/2891/5674 +f 2929/3060/5843 2923/2824/5607 2928/2776/5559 +f 2969/2976/5759 2977/2927/5710 2804/2926/5709 +f 3027/2863/5646 3014/2984/5767 3028/2896/5679 +f 3058/2810/5593 3057/2795/5578 3047/2823/5606 +f 2924/2826/5609 2917/2825/5608 2929/3060/5843 +f 3062/2956/5739 2784/2770/5553 3061/2769/5552 +f 2746/3046/5829 2954/2913/5696 2747/2969/5752 +f 3031/2923/5706 2815/3063/5846 3034/2838/5621 +f 2787/2963/5746 3065/3051/5834 2789/3050/5833 +f 2964/2852/5635 3076/3008/5791 2963/3000/5783 +f 2986/3011/5794 2984/3045/5828 2983/3054/5837 +f 2790/3064/5847 3068/2933/5716 2968/2854/5637 +f 2969/2976/5759 2979/2899/5682 2975/2898/5681 +f 3050/3047/5830 2971/3028/5811 3051/2918/5701 +f 2862/2820/5603 2881/2880/5663 2863/2978/5761 +f 3001/2982/5765 2996/2803/5586 2743/3065/5848 +f 2835/2836/5619 2834/3034/5817 2833/2986/5769 +f 3024/2832/5615 2941/2842/5625 2944/3036/5819 +f 2832/3057/5840 2830/2786/5569 2831/2985/5768 +f 2887/2862/5645 2858/2855/5638 2854/2788/5571 +f 2777/3066/5849 3036/2960/5743 2778/3039/5822 +f 2859/2816/5599 2855/2790/5573 2856/2789/5572 +f 2878/2755/5538 2852/2946/5729 2879/3035/5818 +f 2952/2747/5530 2754/2980/5763 2755/3048/5831 +f 3035/2872/5655 2892/2937/5720 3033/2922/5705 +f 3003/2748/5531 2998/2751/5534 3004/3002/5785 +f 2883/2881/5664 2881/2880/5663 2861/2779/5562 +f 2988/2768/5551 2808/2830/5613 2972/2893/5676 +f 2852/2946/5729 2853/3024/5807 2849/2925/5708 +f 3037/2871/5654 2987/2828/5611 3041/2792/5575 +f 3026/2834/5617 2819/2833/5616 2818/2904/5687 +f 2958/2965/5748 2936/2800/5583 2956/2979/5762 +f 2930/2890/5673 2931/2889/5672 2925/3052/5835 +f 2943/3049/5832 2942/2843/5626 3019/2991/5774 +f 2868/3019/5802 2832/3057/5840 2865/3018/5801 +f 3060/2943/5726 2864/2919/5702 2854/2788/5571 +f 2855/2790/5573 3065/3051/5834 2854/2788/5571 +f 2979/2899/5682 2969/2976/5759 2981/2973/5756 +f 2864/2919/5702 2888/2850/5633 2887/2862/5645 +f 2905/2992/5775 2899/3059/5842 2900/2865/5648 +f 2849/2925/5708 2850/3020/5803 2916/2819/5602 +f 3032/2959/5742 3028/2896/5679 2848/2895/5678 +f 3022/2756/5539 2878/2755/5538 2879/3035/5818 +f 3068/2933/5716 2791/3067/5850 2792/3068/5851 +f 2938/2954/5737 2937/2990/5773 3018/2955/5738 +f 2994/2764/5547 2889/2930/5713 2921/2765/5548 +f 3004/3002/5785 2841/2750/5533 2876/2928/5711 +f 2907/2968/5751 2916/2819/5602 2915/2989/5772 +f 3026/2834/5617 2844/2796/5579 3011/2759/5542 +f 2839/2807/5590 2991/2844/5627 2842/3044/5827 +f 2901/2888/5671 2851/2924/5707 2907/2968/5751 +f 2824/3003/5786 3007/3004/5787 2825/2860/5643 +f 2947/2874/5657 3012/2873/5656 3024/2832/5615 +f 2832/3057/5840 2834/3034/5817 2865/3018/5801 +f 2899/3059/5842 2989/2797/5580 2894/2950/5733 +f 2906/2835/5618 2891/2837/5620 2933/2785/5568 +f 2840/2782/5565 2839/2807/5590 2838/2806/5589 +f 2901/2888/5671 2852/2946/5729 2851/2924/5707 +f 3048/2847/5630 2973/2949/5732 3050/3047/5830 +f 3029/2903/5686 3030/2981/5764 3033/2922/5705 +f 2981/2973/5756 3047/2823/5606 3057/2795/5578 +f 2747/2969/5752 2955/2877/5660 2748/2876/5659 +f 2997/2998/5781 2998/2751/5534 3003/2748/5531 +f 2955/2877/5660 2997/2998/5781 2948/2762/5545 +f 3055/2794/5577 3056/2743/5526 3054/2745/5528 +f 2867/2952/5735 2834/3034/5817 2836/2867/5650 +f 2931/2889/5672 2926/2774/5557 2925/3052/5835 +f 2980/2831/5614 2966/2971/5754 3059/2822/5605 +f 2916/2819/5602 2917/2825/5608 2915/2989/5772 +f 2995/2804/5587 3001/2982/5765 3010/2783/5566 +f 2863/2978/5761 2881/2880/5663 2864/2919/5702 +f 2919/2901/5684 2924/2826/5609 2925/3052/5835 +f 2921/2765/5548 2911/2900/5683 2920/2787/5570 +f 2901/2888/5671 2907/2968/5751 2908/2886/5669 +f 2848/2895/5678 2897/2951/5734 2885/2939/5722 +f 3042/2972/5755 3040/2793/5576 3041/2792/5575 +f 2995/2804/5587 2996/2803/5586 3001/2982/5765 +f 2843/2805/5588 2992/2878/5661 2928/2776/5559 +f 2801/3058/5841 2967/2988/5771 2966/2971/5754 +f 2877/2884/5667 3004/3002/5785 2876/2928/5711 +f 2920/2787/5570 2926/2774/5557 2927/2773/5556 +f 2822/3009/5792 3005/2752/5535 3006/2754/5537 +f 2885/2939/5722 2897/2951/5734 2884/3062/5845 +f 2885/2939/5722 3032/2959/5742 2848/2895/5678 +f 2879/3035/5818 2852/2946/5729 2880/3007/5790 +f 3030/2981/5764 2816/3069/5852 3031/2923/5706 +f 2842/3044/5827 2991/2844/5627 2992/2878/5661 +f 2757/3015/5798 2949/3014/5797 2951/3030/5813 +f 3041/2792/5575 3038/2791/5574 3037/2871/5654 +f 3065/3051/5834 2855/2790/5573 3072/2932/5715 +f 2872/2812/5595 2871/2935/5718 3058/2810/5593 +f 2885/2939/5722 2884/3062/5845 2883/2881/5664 +f 2808/2830/5613 2811/2829/5612 2807/3013/5796 +f 2911/2900/5683 2910/2957/5740 2919/2901/5684 +f 3020/3029/5812 2880/3007/5790 2875/2947/5730 +f 2854/2788/5571 3065/3051/5834 3060/2943/5726 +f 2918/2827/5610 2908/2886/5669 2917/2825/5608 +f 2949/3014/5797 3074/3070/5853 2950/3031/5814 +f 2933/2785/5568 2828/2983/5766 2927/2773/5556 +f 3046/2780/5563 2783/2941/5724 2781/2975/5758 +f 2835/2836/5619 2906/2835/5618 2900/2865/5648 +f 2898/2997/5780 2883/2881/5664 2884/3062/5845 +f 3009/2814/5597 2820/2813/5596 3008/2861/5644 +f 2968/2854/5637 2793/2921/5704 2790/3064/5847 +f 3038/2791/5574 2837/2929/5712 2827/2866/5649 +f 2874/2897/5680 2896/2948/5731 2848/2895/5678 +f 2971/3028/5811 3050/3047/5830 2973/2949/5732 +f 2978/2859/5642 2976/2996/5779 3052/2744/5527 +f 2801/3058/5841 2980/2831/5614 2802/2977/5760 +f 2869/3025/5808 2828/2983/5766 2829/2784/5567 +f 2761/2961/5744 2934/2841/5624 2762/3038/5821 +f 2745/3043/5826 2743/3065/5848 2996/2803/5586 +f 2795/2853/5636 2964/2852/5635 2798/2999/5782 +f 2870/2811/5594 2868/3019/5802 2872/2812/5595 +f 2890/2908/5691 2887/2862/5645 2911/2900/5683 +f 2877/2884/5667 2852/2946/5729 2878/2755/5538 +f 2986/3011/5794 2807/3013/5796 2811/2829/5612 +f 2828/2983/5766 2857/2817/5600 2993/2763/5546 +f 2903/2845/5628 2899/3059/5842 2904/3023/5806 +f 2809/2966/5749 2982/2840/5623 2812/2885/5668 +f 2775/3053/5836 3032/2959/5742 2777/3066/5849 +f 3045/2869/5652 2860/2938/5721 3044/2778/5561 +f 2944/3036/5819 2934/2841/5624 2947/2874/5657 +f 2900/2865/5648 2906/2835/5618 2905/2992/5775 +f 2894/2950/5733 2844/2796/5579 2893/2931/5714 +f 2934/2841/5624 2944/3036/5819 2941/2842/5625 +f 2946/2875/5658 2945/2746/5529 3002/2970/5753 +f 2748/2876/5659 2948/2762/5545 2749/2974/5757 +f 3035/2872/5655 3037/2871/5654 3038/2791/5574 +f 2978/2859/5642 2977/2927/5710 2969/2976/5759 +f 2909/2958/5741 2908/2886/5669 2918/2827/5610 +f 3055/2794/5577 2873/2936/5719 3056/2743/5526 +f 2847/2781/5564 2990/2798/5581 2840/2782/5565 +f 2908/2886/5669 2915/2989/5772 2917/2825/5608 +f 2972/2893/5676 2808/2830/5613 2805/2894/5677 +f 3024/2832/5615 3021/2917/5700 2941/2842/5625 +f 2982/2840/5623 2811/2829/5612 2987/2828/5611 +f 2840/2782/5565 2991/2844/5627 2839/2807/5590 +f 2943/3049/5832 2934/2841/5624 2942/2843/5626 +f 2961/2883/5666 2967/2988/5771 2800/2882/5665 +f 3058/2810/5593 3055/2794/5577 3057/2795/5578 +f 2814/3071/5854 3031/2923/5706 2816/3069/5852 +f 2791/3067/5850 3068/2933/5716 2790/3064/5847 +f 2867/2952/5735 2865/3018/5801 2834/3034/5817 +f 2886/2849/5632 2910/2957/5740 2911/2900/5683 +f 2992/2878/5661 2843/2805/5588 2842/3044/5827 +f 2913/2891/5674 2912/2879/5662 2904/3023/5806 +f 2857/2817/5600 2859/2816/5599 2994/2764/5547 +f 2876/2928/5711 2916/2819/5602 2850/3020/5803 +f 2827/2866/5649 3035/2872/5655 3038/2791/5574 +f 3061/2769/5552 2783/2941/5724 3046/2780/5563 +f 2831/2985/5768 2833/2986/5769 2834/3034/5817 +f 3060/2943/5726 2788/2962/5745 3064/2942/5725 +f 2990/2798/5581 2991/2844/5627 2840/2782/5565 +f 2927/2773/5556 2932/2772/5555 2933/2785/5568 +f 3030/2981/5764 2817/2902/5685 2816/3069/5852 +f 2826/2815/5598 3001/2982/5765 2743/3065/5848 +f 2829/2784/5567 2828/2983/5766 2933/2785/5568 +f 3062/2956/5739 3061/2769/5552 2862/2820/5603 +f 2760/2987/5770 2759/2809/5592 2952/2747/5530 +f 3007/3004/5787 3008/2861/5644 2825/2860/5643 +f 3064/2942/5725 2788/2962/5745 2785/2909/5692 +f 2824/3003/5786 2823/3010/5793 3006/2754/5537 +f 2936/2800/5583 2935/3040/5823 2937/2990/5773 +f 3033/2922/5705 3034/2838/5621 3035/2872/5655 +f 2802/2977/5760 2969/2976/5759 2803/3033/5816 +f 3009/2814/5597 2847/2781/5564 3010/2783/5566 +f 3029/2903/5686 2817/2902/5685 3030/2981/5764 +f 3027/2863/5646 3028/2896/5679 2773/3006/5789 +f 2864/2919/5702 3063/2911/5694 2863/2978/5761 +f 2802/2977/5760 2980/2831/5614 2981/2973/5756 +f 3054/2745/5528 2976/2996/5779 2975/2898/5681 +f 3019/2991/5774 2937/2990/5773 2943/3049/5832 +f 2792/3068/5851 3069/2934/5717 3068/2933/5716 +f 3016/3021/5804 3018/2955/5738 3020/3029/5812 +f 3028/2896/5679 2775/3053/5836 2776/3072/5855 +f 2980/2831/5614 2801/3058/5841 2966/2971/5754 +f 2815/3063/5846 3031/2923/5706 2814/3071/5854 +f 2988/2768/5551 3039/2767/5550 3042/2972/5755 +f 2923/2824/5607 2917/2825/5608 2922/2777/5560 +f 2998/2751/5534 3000/2802/5585 2999/2749/5532 +f 2780/2870/5653 3044/2778/5561 2781/2975/5758 +f 2830/2786/5569 2832/3057/5840 2870/2811/5594 +f 2903/2845/5628 2990/2798/5581 2989/2797/5580 +f 3049/2848/5631 3048/2847/5630 3050/3047/5830 +f 3014/2984/5767 2874/2897/5680 3028/2896/5679 +f 3032/2959/5742 3036/2960/5743 2777/3066/5849 +f 2813/2839/5622 3034/2838/5621 2815/3063/5846 +f 3056/2743/5526 3053/2914/5697 3052/2744/5527 +f 2948/2762/5545 2755/3048/5831 2752/2760/5543 +f 2774/3073/5856 3028/2896/5679 2776/3072/5855 +f 2850/3020/5803 2849/2925/5708 2853/3024/5807 +f 2924/2826/5609 2929/3060/5843 2930/2890/5673 +f 2999/2749/5532 2996/2803/5586 2995/2804/5587 +f 3020/3029/5812 3018/2955/5738 3019/2991/5774 +f 2792/3068/5851 2789/3050/5833 3069/2934/5717 +f 3067/2907/5690 3070/2906/5689 2857/2817/5600 +f 2984/3045/5828 2810/3074/5857 3073/3055/5838 +f 3073/3055/5838 2986/3011/5794 2983/3054/5837 +f 2857/2817/5600 2828/2983/5766 2869/3025/5808 +f 3075/3032/5815 2756/3075/5858 2951/3030/5813 +f 2950/3031/5814 3074/3070/5853 3075/3032/5815 +f 2912/2879/5662 2930/2890/5673 2929/3060/5843 +f 2758/3076/5859 3074/3070/5853 2949/3014/5797 +f 2894/2950/5733 2900/2865/5648 2899/3059/5842 +f 2892/2937/5720 2894/2950/5733 2893/2931/5714 +f 2773/3006/5789 3028/2896/5679 2774/3073/5856 +f 3077/2994/5777 2797/3077/5860 2965/2995/5778 +f 2962/2993/5776 3076/3008/5791 3077/2994/5777 +f 2960/3078/5861 2956/2979/5862 3078/2856/5863 +f 2956/2979/5762 3078/2856/5864 3079/3017/5800 +f 2988/2768/5551 3041/2792/5575 2987/2828/5611 +f 2873/2936/5719 3053/2914/5697 3056/2743/5526 +f 3078/2856/5864 2767/3079/5865 3079/3017/5800 +f 3079/3017/5800 2958/2965/5748 2957/3016/5799 +f 2485/2663/5445 2824/3003/5786 2825/2860/5643 2486/2520/5302 +f 2742/2677/5459 3079/3017/5800 2767/3079/5865 2427/2742/5525 +f 2740/2655/5437 3077/2994/5777 3076/3008/5791 2739/2668/5450 +f 2415/2708/5490 2755/3048/5831 2754/2980/5763 2414/2640/5422 +f 2434/2733/5515 2774/3073/5856 2776/3072/5855 2436/2732/5514 +f 2626/2654/5436 2965/2995/5778 2797/3077/5860 2457/2740/5520 +f 2427/2742/5525 2767/3079/5865 3078/2856/5864 2741/2516/5524 +f 2469/2489/5271 2808/2830/5613 2807/3013/5796 2468/2672/5454 +f 2407/2629/5411 2747/2969/5752 2748/2876/5659 2408/2536/5318 +f 2464/2693/5475 2803/3033/5816 2804/2926/5709 2465/2586/5368 +f 2455/2514/5296 2795/2853/5636 2798/2999/5782 2459/2659/5441 +f 2451/2728/5510 2791/3067/5850 2790/3064/5847 2450/2724/5506 +f 2436/2732/5514 2776/3072/5855 2775/3053/5836 2435/2713/5495 +f 2741/2516/5522 2621/2741/5521 2960/3078/5861 3078/2856/5863 +f 2470/2626/5408 2809/2966/5749 2812/2885/5668 2473/2545/5327 +f 2418/2736/5518 2758/3076/5859 2949/3014/5797 2610/2674/5456 +f 2472/2490/5272 2811/2829/5612 2809/2966/5749 2470/2626/5408 +f 2439/2528/5310 2779/2868/5651 2780/2870/5653 2440/2529/5311 +f 2431/2716/5498 2771/3056/5839 2772/3005/5788 2432/2665/5447 +f 2441/2635/5417 2781/2975/5758 2783/2941/5724 2443/2601/5383 +f 2421/2621/5403 2761/2961/5744 2762/3038/5821 2422/2698/5480 +f 2403/2725/5507 2743/3065/5848 2745/3043/5826 2405/2703/5485 +f 2416/2735/5517 2756/3075/5858 3075/3032/5815 2738/2691/5473 +f 2429/2459/5241 2769/2799/5582 2770/3042/5825 2430/2702/5484 +f 2459/2659/5441 2798/2999/5782 2965/2995/5778 2626/2654/5436 +f 2406/2706/5488 2746/3046/5829 2747/2969/5752 2407/2629/5411 +f 2409/2634/5416 2749/2974/5757 2750/2967/5750 2410/2627/5409 +f 2625/2512/5294 2964/2852/5635 2800/2882/5665 2461/2542/5324 +f 2467/2552/5334 2806/2892/5675 2805/2894/5677 2466/2553/5335 +f 2739/2668/5450 3076/3008/5791 2799/3061/5844 2460/2721/5503 +f 2612/2690/5472 2951/3030/5813 2756/3075/5858 2416/2735/5517 +f 2466/2553/5335 2805/2894/5677 2808/2830/5613 2469/2489/5271 +f 2619/2625/5407 2958/2965/5748 3079/3017/5800 2742/2677/5459 +f 2476/2723/5505 2815/3063/5846 2814/3071/5854 2475/2731/5513 +f 2741/2516/5298 3078/2856/5639 2768/2857/5640 2428/2517/5299 +f 2474/2500/5282 2813/2839/5622 2815/3063/5846 2476/2723/5505 +f 2738/2691/5473 3075/3032/5815 3074/3070/5853 2737/2730/5512 +f 2450/2724/5506 2790/3064/5847 2793/2921/5704 2453/2580/5362 +f 2477/2729/5511 2816/3069/5852 2817/2902/5685 2478/2562/5344 +f 2424/2686/5468 2764/3027/5810 2766/3026/5809 2426/2687/5469 +f 2483/2669/5451 2822/3009/5792 2823/3010/5793 2484/2670/5452 +f 2438/2699/5481 2778/3039/5822 2779/2868/5651 2439/2528/5310 +f 2426/2687/5469 2766/3026/5809 2959/2964/5747 2620/2624/5406 +f 2443/2601/5383 2783/2941/5724 2782/2771/5554 2442/2430/5212 +f 2620/2624/5406 2959/2964/5747 2958/2965/5748 2619/2625/5407 +f 2435/2713/5495 2775/3053/5836 2777/3066/5849 2437/2726/5508 +f 2465/2586/5368 2804/2926/5709 2806/2892/5675 2467/2552/5334 +f 2461/2542/5324 2800/2882/5665 2801/3058/5841 2462/2718/5500 +f 2460/2721/5503 2799/3061/5844 2964/2852/5635 2625/2512/5294 +f 2475/2731/5513 2814/3071/5854 2816/3069/5852 2477/2729/5511 +f 2417/2675/5457 2757/3015/5798 2951/3030/5813 2612/2690/5472 +f 2437/2726/5508 2777/3066/5849 2778/3039/5822 2438/2699/5481 +f 2420/2647/5429 2760/2987/5770 2761/2961/5744 2421/2621/5403 +f 2448/2622/5404 2788/2962/5745 2787/2963/5746 2447/2623/5405 +f 2411/2422/5204 2751/2761/5544 2752/2760/5543 2412/2420/5202 +f 2456/2682/5464 2796/3022/5805 2795/2853/5636 2455/2514/5296 +f 2457/2740/5520 2797/3077/5860 3077/2994/5777 2740/2655/5437 +f 2610/2674/5456 2949/3014/5797 2759/2809/5592 2419/2469/5251 +f 2484/2670/5452 2823/3010/5793 2824/3003/5786 2485/2663/5445 +f 2478/2562/5344 2817/2902/5685 2818/2904/5687 2479/2563/5345 +f 2487/2474/5256 2826/2815/5598 2743/3065/5848 2403/2725/5507 +f 2482/2418/5200 2821/2758/5541 2822/3009/5792 2483/2669/5451 +f 2480/2494/5276 2819/2833/5616 2821/2758/5541 2482/2418/5200 +f 2468/2672/5454 2807/3013/5796 2985/3012/5795 2646/2673/5455 +f 2447/2623/5405 2787/2963/5746 2789/3050/5833 2449/2710/5492 +f 2647/2671/5453 2986/3011/5794 3073/3055/5838 2736/2715/5497 +f 2423/2697/5479 2763/3037/5820 2765/3041/5824 2425/2701/5483 +f 2432/2665/5447 2772/3005/5788 2773/3006/5789 2433/2666/5448 +f 2404/2661/5443 2744/3001/5784 2746/3046/5829 2406/2706/5488 +f 2471/2734/5516 2810/3074/5857 2984/3045/5828 2645/2705/5487 +f 2444/2431/5213 2784/2770/5553 2786/2910/5693 2446/2571/5353 +f 2440/2529/5311 2780/2870/5653 2781/2975/5758 2441/2635/5417 +f 2413/2468/5250 2753/2808/5591 2757/3015/5798 2417/2675/5457 +f 2646/2673/5455 2985/3012/5795 2986/3011/5794 2647/2671/5453 +f 2449/2710/5492 2789/3050/5833 2792/3068/5851 2452/2727/5509 +f 2414/2640/5422 2754/2980/5763 2753/2808/5591 2413/2468/5250 +f 2408/2536/5318 2748/2876/5659 2749/2974/5757 2409/2634/5416 +f 2621/2741/5521 2617/2639/5523 2956/2979/5862 2960/3078/5861 +f 2445/2569/5351 2785/2909/5692 2788/2962/5745 2448/2622/5404 +f 2479/2563/5345 2818/2904/5687 2819/2833/5616 2480/2494/5276 +f 2422/2698/5480 2762/3038/5821 2763/3037/5820 2423/2697/5479 +f 2433/2666/5448 2773/3006/5789 2774/3073/5856 2434/2733/5515 +f 2473/2545/5327 2812/2885/5668 2813/2839/5622 2474/2500/5282 +f 2453/2580/5362 2793/2921/5704 2794/2920/5703 2454/2581/5363 +f 2486/2520/5302 2825/2860/5643 2820/2813/5596 2481/2473/5255 +f 2425/2701/5483 2765/3041/5824 2764/3027/5810 2424/2686/5468 +f 2454/2581/5363 2794/2920/5703 2796/3022/5805 2456/2682/5464 +f 2410/2627/5409 2750/2967/5750 2751/2761/5544 2411/2422/5204 +f 2463/2636/5418 2802/2977/5760 2803/3033/5816 2464/2693/5475 +f 2419/2469/5251 2759/2809/5592 2760/2987/5770 2420/2647/5429 +f 2645/2705/5487 2984/3045/5828 2811/2829/5612 2472/2490/5272 +f 2737/2730/5512 3074/3070/5853 2758/3076/5859 2418/2736/5518 +f 2430/2702/5484 2770/3042/5825 2771/3056/5839 2431/2716/5498 +f 2452/2727/5509 2792/3068/5851 2791/3067/5850 2451/2728/5510 +f 2405/2703/5485 2745/3043/5826 2744/3001/5784 2404/2661/5443 +f 2428/2517/5299 2768/2857/5640 2769/2799/5582 2429/2459/5241 +f 2446/2571/5353 2786/2910/5693 2785/2909/5692 2445/2569/5351 +f 2736/2715/5497 3073/3055/5838 2810/3074/5857 2471/2734/5516 +f 2412/2420/5202 2752/2760/5543 2755/3048/5831 2415/2708/5490 +f 2442/2430/5212 2782/2771/5554 2784/2770/5553 2444/2431/5213 +f 2481/2473/5255 2820/2813/5596 2826/2815/5598 2487/2474/5256 +f 2462/2718/5500 2801/3058/5841 2802/2977/5760 2463/2636/5418 diff --git a/examples/Cassie/urdf/meshes/agility/hip-roll.obj b/examples/Cassie/urdf/meshes/agility/hip-roll.obj new file mode 100644 index 0000000000..bc12f3761e --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/hip-roll.obj @@ -0,0 +1,9385 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o hip-roll +v -0.054937 -0.105193 0.030586 +v -0.054830 -0.106841 0.033716 +v -0.054900 -0.104405 0.034586 +v -0.054849 -0.103392 0.036990 +v -0.054900 -0.101478 0.033572 +v -0.054825 -0.099811 0.034305 +v -0.054848 -0.101219 0.030060 +v -0.020979 -0.105103 0.032460 +v -0.021035 -0.102271 0.034909 +v -0.021029 -0.104448 0.034682 +v -0.021011 -0.102451 0.031443 +v -0.050811 -0.105058 0.031831 +v -0.050824 -0.104591 0.034994 +v -0.050801 -0.101259 0.034494 +v -0.021367 -0.101063 0.033002 +v -0.050828 -0.102053 0.031394 +v -0.050961 -0.104414 0.036613 +v -0.050957 -0.106847 0.033600 +v -0.050965 -0.105511 0.030581 +v -0.050957 -0.102342 0.029714 +v -0.050957 -0.099621 0.032868 +v -0.050963 -0.101171 0.036103 +v -0.051900 -0.104010 0.034845 +v -0.051900 -0.101451 0.033100 +v -0.051900 -0.104242 0.031756 +v -0.054946 -0.100509 -0.034940 +v -0.054837 -0.103402 -0.036927 +v -0.054938 -0.106254 -0.034548 +v -0.054837 -0.105956 -0.030732 +v -0.054935 -0.102414 -0.030031 +v -0.054825 -0.099811 -0.032163 +v -0.021054 -0.101145 -0.032945 +v -0.021087 -0.103308 -0.031290 +v -0.021008 -0.105273 -0.033033 +v -0.020985 -0.102985 -0.035198 +v -0.050830 -0.103690 -0.035340 +v -0.050801 -0.105557 -0.032930 +v -0.050824 -0.102758 -0.031064 +v -0.050801 -0.101000 -0.033937 +v -0.050957 -0.106755 -0.034126 +v -0.050963 -0.104191 -0.036636 +v -0.050957 -0.100701 -0.035837 +v -0.050951 -0.100013 -0.031433 +v -0.050942 -0.104773 -0.029809 +v -0.051900 -0.104310 -0.034632 +v -0.051900 -0.102158 -0.031836 +v -0.059700 -0.070852 -0.059778 +v -0.059619 -0.068050 -0.058881 +v -0.059698 -0.067471 -0.061819 +v -0.059671 -0.071851 -0.058734 +v -0.059633 -0.069868 -0.063879 +v -0.059697 -0.072344 -0.062299 +v -0.044806 -0.070921 -0.059838 +v -0.044816 -0.070979 -0.062021 +v -0.044779 -0.068632 -0.060523 +v -0.056605 -0.068597 -0.059898 +v -0.045175 -0.069234 -0.062447 +v -0.056626 -0.069231 -0.062534 +v -0.056634 -0.071217 -0.062091 +v -0.056623 -0.071385 -0.059949 +v -0.056756 -0.072216 -0.059227 +v -0.056759 -0.072529 -0.062210 +v -0.056731 -0.067222 -0.060235 +v -0.056761 -0.069575 -0.058260 +v -0.056764 -0.069217 -0.063897 +v -0.057700 -0.069497 -0.062403 +v -0.057700 -0.070295 -0.059925 +v -0.049700 -0.038615 0.034665 +v -0.050900 -0.039591 0.033437 +v -0.050900 -0.034724 0.036236 +v -0.049700 -0.035210 0.035121 +v -0.050900 -0.034606 0.034459 +v -0.049700 -0.034775 0.032043 +v -0.050900 -0.036228 0.030771 +v -0.049700 -0.037691 0.030969 +v -0.050580 -0.039037 0.032933 +v -0.050300 -0.040278 0.033232 +v -0.050900 -0.039683 0.031045 +v -0.049700 -0.038622 0.029733 +v -0.050900 -0.035872 0.029595 +v -0.049700 -0.033449 0.031490 +v -0.050900 -0.033167 0.032647 +v -0.049700 -0.034503 0.036321 +v -0.050900 -0.039004 0.036152 +v -0.049700 -0.039789 0.035412 +v -0.049700 -0.104119 0.031119 +v -0.050900 -0.105073 0.031695 +v -0.049700 -0.105552 0.034125 +v -0.050900 -0.104746 0.034993 +v -0.049700 -0.101375 0.035052 +v -0.050900 -0.101222 0.034817 +v -0.049700 -0.102255 0.031115 +v -0.050900 -0.102151 0.031185 +v -0.049700 -0.101961 0.029817 +v -0.050900 -0.103064 0.029613 +v -0.050900 -0.100071 0.031419 +v -0.049700 -0.099523 0.033309 +v -0.050900 -0.100333 0.035667 +v -0.049700 -0.101703 0.036544 +v -0.050900 -0.105941 0.036128 +v -0.049700 -0.105240 0.036280 +v -0.049700 -0.106866 0.031770 +v -0.050900 -0.106152 0.030996 +v -0.050300 -0.103556 0.029715 +v -0.054900 -0.035010 -0.032896 +v -0.054830 -0.034078 -0.030781 +v -0.054849 -0.033787 -0.035527 +v -0.054944 -0.037847 -0.036327 +v -0.054900 -0.037937 -0.031882 +v -0.054825 -0.037837 -0.029811 +v -0.054848 -0.040523 -0.033392 +v -0.021066 -0.037849 -0.034986 +v -0.021131 -0.034932 -0.034135 +v -0.020969 -0.035514 -0.031847 +v -0.021096 -0.038217 -0.031711 +v -0.050801 -0.034426 -0.033130 +v -0.050824 -0.036858 -0.035454 +v -0.050827 -0.038855 -0.033809 +v -0.050806 -0.037623 -0.031063 +v -0.050961 -0.037434 -0.036751 +v -0.050929 -0.033193 -0.034592 +v -0.050957 -0.035187 -0.029964 +v -0.050951 -0.039560 -0.030823 +v -0.050963 -0.039987 -0.034688 +v -0.051900 -0.037773 -0.034712 +v -0.051900 -0.037542 -0.031623 +v -0.051900 -0.034983 -0.033368 +v -0.049700 -0.035691 -0.031197 +v -0.050900 -0.036444 -0.030249 +v -0.050900 -0.034514 -0.032373 +v -0.049700 -0.034630 -0.034574 +v -0.050900 -0.035284 -0.034957 +v -0.050900 -0.038558 -0.035063 +v -0.049700 -0.038515 -0.034944 +v -0.049700 -0.038125 -0.031308 +v -0.050900 -0.038030 -0.031268 +v -0.049700 -0.037793 -0.029749 +v -0.050900 -0.037458 -0.029623 +v -0.050900 -0.040257 -0.032280 +v -0.049700 -0.040465 -0.032933 +v -0.050900 -0.039353 -0.035895 +v -0.049700 -0.038767 -0.036249 +v -0.050900 -0.034790 -0.036464 +v -0.049700 -0.034501 -0.036319 +v -0.050900 -0.033279 -0.031759 +v -0.049700 -0.033289 -0.032230 +v -0.049700 -0.035971 -0.029654 +v -0.049700 -0.100441 -0.033405 +v -0.050900 -0.101115 -0.034202 +v -0.049700 -0.102894 -0.035503 +v -0.050900 -0.103579 -0.035502 +v -0.049700 -0.105225 -0.034478 +v -0.050900 -0.105625 -0.033544 +v -0.049700 -0.104980 -0.031664 +v -0.050900 -0.103742 -0.030911 +v -0.049700 -0.101540 -0.031536 +v -0.050900 -0.101111 -0.032340 +v -0.049700 -0.099988 -0.031489 +v -0.050900 -0.099623 -0.032542 +v -0.050900 -0.102995 -0.029494 +v -0.049700 -0.104056 -0.029615 +v -0.050900 -0.106975 -0.032426 +v -0.049700 -0.106970 -0.032943 +v -0.050900 -0.104559 -0.036739 +v -0.049700 -0.105068 -0.036354 +v -0.049700 -0.101161 -0.036356 +v -0.050900 -0.100152 -0.035255 +v -0.059675 -0.110136 0.008622 +v -0.059616 -0.108081 0.005763 +v -0.059676 -0.110101 0.003454 +v -0.059682 -0.113652 0.006218 +v -0.059601 -0.112700 0.008177 +v -0.059598 -0.112916 0.003904 +v -0.048784 -0.111392 0.004633 +v -0.048895 -0.109822 0.007000 +v -0.048944 -0.112437 0.006786 +v -0.048876 -0.109846 0.005161 +v -0.056591 -0.109425 0.005254 +v -0.056595 -0.110642 0.007706 +v -0.056607 -0.112654 0.006267 +v -0.056613 -0.111623 0.004471 +v -0.056770 -0.111927 0.008816 +v -0.056753 -0.109839 0.003354 +v -0.056767 -0.108171 0.006887 +v -0.056735 -0.113755 0.004787 +v -0.057700 -0.111556 0.006966 +v -0.057700 -0.110162 0.004768 +v -0.030200 -0.080032 -0.042923 +v -0.030200 -0.086925 -0.043915 +v -0.030200 -0.100164 -0.032641 +v -0.030200 -0.100521 -0.034930 +v -0.028000 -0.100526 -0.034943 +v -0.028000 -0.086658 -0.043911 +v -0.028001 -0.100056 -0.033059 +v -0.028000 -0.079730 -0.042927 +v -0.032200 -0.080032 -0.042923 +v -0.031717 -0.085532 -0.043786 +v -0.031700 -0.093419 -0.040315 +v -0.032200 -0.100164 -0.032641 +v -0.032200 -0.100521 -0.034930 +v -0.031200 -0.100526 -0.034943 +v -0.031200 -0.100090 -0.032984 +v -0.031200 -0.077443 -0.043510 +v -0.034200 -0.080032 -0.042923 +v -0.033717 -0.085532 -0.043786 +v -0.033700 -0.093419 -0.040315 +v -0.034200 -0.100164 -0.032641 +v -0.034200 -0.100521 -0.034930 +v -0.033200 -0.100526 -0.034943 +v -0.033200 -0.100090 -0.032984 +v -0.033200 -0.077443 -0.043510 +v -0.036200 -0.080032 -0.042923 +v -0.035717 -0.085532 -0.043786 +v -0.035700 -0.093419 -0.040315 +v -0.036200 -0.100164 -0.032641 +v -0.036200 -0.100521 -0.034930 +v -0.035200 -0.100526 -0.034943 +v -0.035200 -0.100090 -0.032984 +v -0.035200 -0.077443 -0.043510 +v -0.038200 -0.080032 -0.042923 +v -0.037717 -0.085532 -0.043786 +v -0.037700 -0.093419 -0.040315 +v -0.038200 -0.100164 -0.032641 +v -0.038200 -0.100521 -0.034930 +v -0.037200 -0.100526 -0.034943 +v -0.037200 -0.100090 -0.032984 +v -0.037200 -0.077443 -0.043510 +v -0.040200 -0.080032 -0.042923 +v -0.039717 -0.085532 -0.043786 +v -0.039700 -0.093420 -0.040315 +v -0.040200 -0.100164 -0.032641 +v -0.040200 -0.100521 -0.034930 +v -0.039200 -0.100526 -0.034943 +v -0.039200 -0.100090 -0.032984 +v -0.039200 -0.077443 -0.043510 +v -0.042571 -0.084509 -0.041689 +v -0.042201 -0.078516 -0.043079 +v -0.041717 -0.085532 -0.043786 +v -0.041700 -0.093420 -0.040315 +v -0.042199 -0.100165 -0.032609 +v -0.042200 -0.100521 -0.034930 +v -0.041200 -0.100526 -0.034943 +v -0.041200 -0.100090 -0.032984 +v -0.041200 -0.077443 -0.043510 +v -0.030477 -0.063259 -0.043571 +v -0.030200 -0.073031 -0.046356 +v -0.030200 -0.067053 -0.046431 +v -0.030685 -0.108989 0.021100 +v -0.030200 -0.104931 0.030521 +v -0.030200 -0.101435 0.030488 +v -0.030200 -0.110920 0.022452 +v -0.030200 -0.116474 0.005788 +v -0.030700 -0.113909 0.004860 +v -0.030200 -0.104949 -0.030520 +v -0.030200 -0.113965 -0.016718 +v -0.030644 -0.112660 -0.012063 +v -0.030200 -0.102092 -0.030319 +v -0.028001 -0.062988 -0.043540 +v -0.028000 -0.072884 -0.046425 +v -0.028000 -0.066944 -0.046362 +v -0.027999 -0.110471 -0.018624 +v -0.028000 -0.104931 -0.030521 +v -0.028001 -0.102205 -0.030204 +v -0.027999 -0.108894 0.021251 +v -0.028000 -0.113965 0.016718 +v -0.027998 -0.114224 0.002886 +v -0.028000 -0.101773 0.030440 +v -0.028000 -0.104949 0.030520 +v -0.028000 -0.116474 -0.005788 +v -0.028000 -0.110920 -0.022452 +v -0.032477 -0.063259 -0.043571 +v -0.031717 -0.072969 -0.046405 +v -0.031719 -0.067018 -0.046408 +v -0.032658 -0.111373 0.015723 +v -0.032200 -0.104931 0.030521 +v -0.032200 -0.101505 0.030487 +v -0.032200 -0.110920 0.022452 +v -0.032200 -0.116474 0.005788 +v -0.032700 -0.114265 -0.002442 +v -0.032200 -0.104949 -0.030520 +v -0.032200 -0.113965 -0.016718 +v -0.032700 -0.108989 -0.021100 +v -0.032686 -0.102010 -0.030291 +v -0.031200 -0.113965 0.016718 +v -0.031200 -0.101771 0.030440 +v -0.031200 -0.104949 0.030520 +v -0.031200 -0.116474 -0.005788 +v -0.031200 -0.110920 -0.022452 +v -0.031200 -0.102512 -0.030126 +v -0.031200 -0.104931 -0.030521 +v -0.034477 -0.063259 -0.043571 +v -0.033717 -0.072969 -0.046405 +v -0.033719 -0.067018 -0.046408 +v -0.034685 -0.108989 0.021100 +v -0.034200 -0.104931 0.030521 +v -0.034200 -0.101435 0.030488 +v -0.034200 -0.110920 0.022452 +v -0.034200 -0.116474 0.005788 +v -0.034575 -0.113749 0.005770 +v -0.034200 -0.104949 -0.030520 +v -0.034200 -0.113965 -0.016718 +v -0.034700 -0.108989 -0.021100 +v -0.034825 -0.113749 -0.005770 +v -0.034686 -0.102010 -0.030291 +v -0.033200 -0.104931 -0.030521 +v -0.033200 -0.113965 0.016718 +v -0.033200 -0.102092 0.030319 +v -0.033200 -0.104949 0.030520 +v -0.033200 -0.116474 -0.005788 +v -0.033200 -0.110920 -0.022452 +v -0.036477 -0.063259 -0.043571 +v -0.035717 -0.072969 -0.046405 +v -0.035719 -0.067018 -0.046408 +v -0.036593 -0.110155 0.018832 +v -0.036200 -0.104931 0.030521 +v -0.036200 -0.101435 0.030488 +v -0.035729 -0.111228 0.021896 +v -0.035700 -0.115476 0.010025 +v -0.036700 -0.114132 0.002435 +v -0.035700 -0.116565 -0.005072 +v -0.036200 -0.104949 -0.030520 +v -0.035671 -0.111228 -0.021896 +v -0.036664 -0.111950 -0.014402 +v -0.036200 -0.102092 -0.030319 +v -0.035200 -0.104931 -0.030521 +v -0.035200 -0.101771 0.030440 +v -0.035200 -0.104949 0.030520 +v -0.038200 -0.063356 -0.043616 +v -0.037717 -0.072969 -0.046405 +v -0.037719 -0.067018 -0.046408 +v -0.038200 -0.110920 0.022452 +v -0.038200 -0.104931 0.030521 +v -0.038200 -0.102512 0.030126 +v -0.038200 -0.111972 0.013763 +v -0.038200 -0.116474 0.005788 +v -0.038700 -0.114220 0.002440 +v -0.038200 -0.104949 -0.030520 +v -0.038200 -0.113965 -0.016718 +v -0.038200 -0.111575 -0.014919 +v -0.038200 -0.102092 -0.030319 +v -0.037200 -0.104931 -0.030521 +v -0.037200 -0.102237 -0.030195 +v -0.037200 -0.113965 0.016718 +v -0.037200 -0.102092 0.030319 +v -0.037200 -0.104949 0.030520 +v -0.037200 -0.116474 -0.005788 +v -0.037200 -0.110920 -0.022452 +v -0.039923 -0.063259 -0.043571 +v -0.039717 -0.072969 -0.046405 +v -0.039719 -0.067018 -0.046408 +v -0.040200 -0.109309 0.020483 +v -0.040200 -0.104931 0.030521 +v -0.040200 -0.101435 0.030488 +v -0.040200 -0.110920 0.022452 +v -0.040200 -0.116474 0.005788 +v -0.040200 -0.114291 0.001748 +v -0.040200 -0.104949 -0.030520 +v -0.040200 -0.113965 -0.016718 +v -0.040700 -0.112535 -0.012404 +v -0.040200 -0.102092 -0.030319 +v -0.039200 -0.112346 -0.013756 +v -0.039200 -0.104931 -0.030521 +v -0.039200 -0.102237 -0.030195 +v -0.039200 -0.108648 0.021705 +v -0.039200 -0.113965 0.016718 +v -0.039200 -0.101771 0.030440 +v -0.039200 -0.104949 0.030520 +v -0.039200 -0.116474 -0.005788 +v -0.039200 -0.110920 -0.022452 +v -0.042200 -0.063861 -0.043800 +v -0.041717 -0.072969 -0.046405 +v -0.041719 -0.067018 -0.046408 +v -0.042200 -0.107895 0.022656 +v -0.042200 -0.104931 0.030521 +v -0.042200 -0.101440 0.030504 +v -0.042200 -0.110920 0.022452 +v -0.042200 -0.113830 0.006610 +v -0.042200 -0.116474 0.005788 +v -0.042200 -0.104949 -0.030520 +v -0.042200 -0.113965 -0.016718 +v -0.042575 -0.112732 -0.011707 +v -0.042200 -0.102247 -0.030259 +v -0.041200 -0.063091 -0.043491 +v -0.041200 -0.102092 0.030319 +v -0.041200 -0.104949 0.030520 +v -0.041200 -0.113279 0.010457 +v -0.041200 -0.113965 0.016718 +v -0.041200 -0.116474 -0.005788 +v -0.041200 -0.110920 -0.022452 +v -0.041200 -0.102512 -0.030126 +v -0.041200 -0.104931 -0.030521 +v -0.043316 -0.114328 -0.014293 +v -0.049718 -0.113759 -0.015604 +v -0.043389 -0.107168 -0.029276 +v -0.049785 -0.107387 -0.027486 +v -0.043365 -0.102038 -0.038878 +v -0.049775 -0.100882 -0.039984 +v -0.043309 -0.089651 -0.061669 +v -0.049700 -0.088789 -0.062784 +v -0.030200 -0.039498 0.034940 +v -0.030200 -0.039376 0.031542 +v -0.030200 -0.050608 0.039858 +v -0.030546 -0.087466 0.040719 +v -0.030200 -0.091329 0.041516 +v -0.030200 -0.074353 0.046630 +v -0.030700 -0.068778 0.044315 +v -0.030200 -0.051854 0.043395 +v -0.030200 -0.100488 0.034971 +v -0.028000 -0.039474 0.034945 +v -0.028000 -0.049798 0.039450 +v -0.028001 -0.039748 0.032104 +v -0.028000 -0.053282 0.043965 +v -0.027241 -0.064999 0.044128 +v -0.028000 -0.075788 0.046474 +v -0.027998 -0.083512 0.042210 +v -0.028000 -0.092452 0.040920 +v -0.028000 -0.100166 0.032591 +v -0.028000 -0.100521 0.034931 +v -0.031679 -0.039488 0.034945 +v -0.032200 -0.038708 0.030596 +v -0.032200 -0.050608 0.039858 +v -0.032546 -0.087466 0.040719 +v -0.031671 -0.091896 0.041228 +v -0.031700 -0.075072 0.046565 +v -0.032700 -0.068778 0.044315 +v -0.031700 -0.059975 0.045476 +v -0.031700 -0.048104 0.041228 +v -0.032200 -0.100488 0.034971 +v -0.031200 -0.049369 0.039231 +v -0.031200 -0.039750 0.032122 +v -0.031200 -0.100164 0.032641 +v -0.031200 -0.100521 0.034931 +v -0.034200 -0.039498 0.034940 +v -0.034200 -0.039376 0.031542 +v -0.034200 -0.050608 0.039858 +v -0.034546 -0.087466 0.040719 +v -0.033671 -0.091896 0.041228 +v -0.033700 -0.075072 0.046565 +v -0.034700 -0.068778 0.044315 +v -0.033700 -0.059975 0.045476 +v -0.033700 -0.048104 0.041228 +v -0.034200 -0.100488 0.034971 +v -0.033200 -0.039474 0.034945 +v -0.033200 -0.049369 0.039231 +v -0.033200 -0.039750 0.032122 +v -0.033200 -0.100164 0.032641 +v -0.033200 -0.100521 0.034931 +v -0.036200 -0.039498 0.034940 +v -0.036200 -0.038708 0.030596 +v -0.036200 -0.050608 0.039858 +v -0.036546 -0.087466 0.040719 +v -0.035671 -0.091896 0.041228 +v -0.035700 -0.075072 0.046565 +v -0.036700 -0.068778 0.044315 +v -0.035700 -0.059975 0.045476 +v -0.035700 -0.048104 0.041228 +v -0.036200 -0.100488 0.034971 +v -0.035200 -0.039474 0.034945 +v -0.035200 -0.049369 0.039231 +v -0.035200 -0.039750 0.032122 +v -0.035200 -0.100164 0.032641 +v -0.035200 -0.100521 0.034931 +v -0.038200 -0.039498 0.034940 +v -0.038200 -0.038708 0.030596 +v -0.038200 -0.050608 0.039858 +v -0.038546 -0.087466 0.040719 +v -0.037671 -0.091896 0.041228 +v -0.037700 -0.075072 0.046565 +v -0.038700 -0.068778 0.044315 +v -0.037700 -0.059975 0.045476 +v -0.037700 -0.048104 0.041228 +v -0.038839 -0.100199 0.032514 +v -0.038200 -0.100488 0.034971 +v -0.037200 -0.039474 0.034945 +v -0.037200 -0.049369 0.039231 +v -0.037200 -0.039750 0.032122 +v -0.037200 -0.100164 0.032641 +v -0.037200 -0.100521 0.034931 +v -0.040200 -0.039498 0.034940 +v -0.040200 -0.039236 0.031307 +v -0.040200 -0.050608 0.039858 +v -0.040546 -0.087466 0.040719 +v -0.039671 -0.091896 0.041228 +v -0.039700 -0.075072 0.046565 +v -0.040700 -0.068778 0.044315 +v -0.039700 -0.059975 0.045476 +v -0.039700 -0.048104 0.041228 +v -0.040200 -0.100488 0.034971 +v -0.039200 -0.039474 0.034945 +v -0.039200 -0.049369 0.039231 +v -0.039200 -0.039750 0.032122 +v -0.039200 -0.100521 0.034931 +v -0.041679 -0.039488 0.034945 +v -0.042200 -0.039376 0.031540 +v -0.042200 -0.050652 0.039845 +v -0.042200 -0.100503 0.034197 +v -0.041671 -0.091896 0.041228 +v -0.042200 -0.077886 0.043603 +v -0.041700 -0.075072 0.046565 +v -0.042867 -0.067481 0.044059 +v -0.041700 -0.059975 0.045476 +v -0.041700 -0.048104 0.041228 +v -0.041200 -0.049369 0.039231 +v -0.041200 -0.039750 0.032122 +v -0.041200 -0.100164 0.032641 +v -0.041200 -0.100521 0.034931 +v -0.049711 -0.116611 0.000189 +v -0.043358 -0.116421 0.004490 +v -0.049708 -0.113467 0.016356 +v -0.043322 -0.112458 0.018656 +v -0.049745 -0.107267 0.027492 +v -0.043391 -0.107085 0.028611 +v -0.043199 -0.101390 0.031522 +v -0.043200 -0.113172 0.011240 +v -0.043200 -0.083147 0.042264 +v -0.043200 -0.054545 0.041476 +v -0.043197 -0.038644 0.031475 +v -0.042200 -0.026031 0.005587 +v -0.043200 -0.027222 0.012096 +v -0.042200 -0.031448 0.021558 +v -0.043200 -0.026266 -0.006774 +v -0.042199 -0.037511 -0.030172 +v -0.043200 -0.031448 -0.021558 +v -0.042200 -0.027856 -0.013734 +v -0.042199 -0.039885 -0.032635 +v -0.043200 -0.041841 -0.034139 +v -0.042507 -0.057966 -0.042722 +v -0.043201 -0.068436 -0.044218 +v -0.043200 -0.093110 -0.037661 +v -0.043201 -0.106291 -0.025550 +v -0.040845 -0.037586 0.030186 +v -0.041200 -0.028476 0.016067 +v -0.040200 -0.028307 0.015047 +v -0.040700 -0.025937 -0.004877 +v -0.040800 -0.030148 -0.018807 +v -0.040200 -0.037510 -0.030173 +v -0.041200 -0.037610 -0.030213 +v -0.041200 -0.039814 -0.032289 +v -0.040200 -0.039839 -0.032448 +v -0.041200 -0.057513 -0.042810 +v -0.040200 -0.058226 -0.042740 +v -0.039200 -0.037675 0.030198 +v -0.038640 -0.031147 0.021026 +v -0.039200 -0.037610 -0.030213 +v -0.038575 -0.029702 -0.018266 +v -0.038200 -0.039412 -0.031796 +v -0.039200 -0.039814 -0.032289 +v -0.039200 -0.057513 -0.042810 +v -0.038200 -0.058226 -0.042740 +v -0.037200 -0.037675 0.030198 +v -0.036640 -0.031147 0.021026 +v -0.036700 -0.031147 -0.021026 +v -0.036200 -0.039412 -0.031796 +v -0.037200 -0.037671 -0.030227 +v -0.037200 -0.039814 -0.032289 +v -0.037200 -0.057513 -0.042810 +v -0.036200 -0.058226 -0.042740 +v -0.035200 -0.037675 0.030198 +v -0.034640 -0.031147 0.021026 +v -0.034700 -0.031147 -0.021026 +v -0.034200 -0.039412 -0.031796 +v -0.035200 -0.037671 -0.030227 +v -0.035200 -0.039814 -0.032289 +v -0.035200 -0.057513 -0.042810 +v -0.034200 -0.058226 -0.042740 +v -0.033200 -0.037675 0.030198 +v -0.032640 -0.031147 0.021026 +v -0.032867 -0.031034 -0.020808 +v -0.032200 -0.037510 -0.030173 +v -0.033200 -0.037671 -0.030227 +v -0.033200 -0.039814 -0.032289 +v -0.032200 -0.039839 -0.032448 +v -0.033200 -0.057513 -0.042810 +v -0.032200 -0.058226 -0.042740 +v -0.031200 -0.037675 0.030198 +v -0.030200 -0.031448 0.021558 +v -0.031200 -0.028476 0.016067 +v -0.030200 -0.026026 0.005566 +v -0.031200 -0.025935 -0.003043 +v -0.030200 -0.028476 -0.016067 +v -0.031200 -0.030216 -0.019543 +v -0.030200 -0.039412 -0.031796 +v -0.031200 -0.039524 -0.031535 +v -0.031200 -0.057513 -0.042810 +v -0.030200 -0.058226 -0.042740 +v -0.028000 -0.026002 0.005322 +v -0.028000 -0.031238 0.021180 +v -0.026816 -0.029166 0.017256 +v -0.026904 -0.103550 -0.028963 +v -0.049757 -0.097512 0.037175 +v -0.043381 -0.098460 0.037115 +v -0.043350 -0.087445 0.043120 +v -0.049689 -0.086187 0.043567 +v -0.043327 -0.071712 0.046597 +v -0.049680 -0.072713 0.046420 +v -0.049706 -0.055268 0.044189 +v -0.043279 -0.054180 0.043761 +v -0.043377 -0.041486 0.037090 +v -0.049760 -0.042455 0.037175 +v -0.043329 -0.055827 -0.065142 +v -0.043322 -0.085064 -0.065038 +v -0.049705 -0.055046 -0.065063 +v -0.049700 -0.083677 -0.065215 +v -0.043445 -0.104193 0.037090 +v -0.049602 -0.104321 0.036977 +v -0.049493 -0.106979 0.034803 +v -0.043371 -0.106930 0.034847 +v -0.043384 -0.106864 -0.035109 +v -0.049554 -0.106812 -0.035166 +v -0.026789 -0.074071 0.044098 +v -0.026803 -0.091118 -0.039118 +v -0.026761 -0.026080 0.005817 +v -0.026784 -0.026368 -0.007656 +v -0.028000 -0.036962 -0.030059 +v -0.028000 -0.027334 -0.011406 +v -0.026801 -0.030054 -0.018923 +v -0.026880 -0.035860 0.028243 +v -0.026816 -0.076266 -0.043811 +v -0.028000 -0.037683 0.030199 +v -0.028000 -0.039795 -0.032191 +v -0.026902 -0.034949 -0.026997 +v -0.026846 -0.043028 -0.035160 +v -0.026884 -0.102659 0.030147 +v -0.026763 -0.114180 0.004255 +v -0.026779 -0.113439 -0.008382 +v -0.026801 -0.053396 0.041013 +v -0.026854 -0.043977 0.035762 +v -0.028000 -0.047793 -0.038183 +v -0.026755 -0.087616 0.040764 +v -0.026780 -0.059049 -0.043180 +v -0.026811 -0.109405 -0.020161 +v -0.026785 -0.110488 0.017966 +v -0.049904 -0.100783 -0.030040 +v -0.030200 -0.039590 -0.035393 +v -0.030200 -0.054345 -0.043826 +v -0.028000 -0.053075 -0.043915 +v -0.028000 -0.039479 -0.034930 +v -0.032200 -0.039519 -0.035383 +v -0.031756 -0.054412 -0.043821 +v -0.031200 -0.039589 -0.035694 +v -0.033662 -0.045919 -0.039883 +v -0.033756 -0.054412 -0.043821 +v -0.033781 -0.039530 -0.034954 +v -0.035662 -0.045919 -0.039883 +v -0.035756 -0.054412 -0.043821 +v -0.035781 -0.039530 -0.034954 +v -0.037662 -0.045919 -0.039883 +v -0.037756 -0.054412 -0.043821 +v -0.037781 -0.039530 -0.034954 +v -0.040200 -0.039519 -0.035383 +v -0.039756 -0.054412 -0.043821 +v -0.039200 -0.039589 -0.035694 +v -0.042200 -0.039519 -0.035383 +v -0.041756 -0.054412 -0.043821 +v -0.041200 -0.039589 -0.035694 +v -0.030200 -0.035133 0.030380 +v -0.030200 -0.035130 -0.030401 +v -0.030200 -0.026035 0.016718 +v -0.030200 -0.023526 -0.005788 +v -0.030200 -0.029080 -0.022452 +v -0.028000 -0.035069 0.030521 +v -0.028000 -0.028484 -0.021329 +v -0.028000 -0.023370 -0.004353 +v -0.028000 -0.026605 0.018146 +v -0.028000 -0.035055 -0.030526 +v -0.032200 -0.035055 0.030526 +v -0.032200 -0.026035 0.016718 +v -0.032700 -0.027000 0.009637 +v -0.032700 -0.025937 -0.004877 +v -0.032200 -0.023526 -0.005788 +v -0.032200 -0.029080 -0.022452 +v -0.032200 -0.035069 -0.030521 +v -0.031200 -0.035069 0.030521 +v -0.031200 -0.035029 -0.030488 +v -0.031200 -0.026035 -0.016718 +v -0.031200 -0.023526 0.005788 +v -0.031200 -0.029080 0.022452 +v -0.034200 -0.035133 0.030380 +v -0.034200 -0.035130 -0.030401 +v -0.033671 -0.028772 0.021896 +v -0.034700 -0.027000 0.009636 +v -0.033700 -0.024524 0.010025 +v -0.034700 -0.025937 -0.004877 +v -0.033700 -0.023435 -0.005072 +v -0.033729 -0.028772 -0.021895 +v -0.033200 -0.035069 0.030521 +v -0.033200 -0.035055 -0.030526 +v -0.036200 -0.035130 -0.030401 +v -0.036200 -0.035055 0.030526 +v -0.035671 -0.028772 0.021896 +v -0.036700 -0.027000 0.009637 +v -0.035700 -0.024524 0.010025 +v -0.036700 -0.025937 -0.004877 +v -0.035700 -0.023435 -0.005072 +v -0.035729 -0.028772 -0.021896 +v -0.035200 -0.035069 0.030521 +v -0.035200 -0.035055 -0.030526 +v -0.038200 -0.035130 -0.030401 +v -0.038200 -0.035055 0.030526 +v -0.037671 -0.028772 0.021896 +v -0.038600 -0.026635 0.008171 +v -0.037700 -0.024524 0.010025 +v -0.037700 -0.023435 -0.005072 +v -0.038867 -0.026104 -0.005542 +v -0.037729 -0.028772 -0.021896 +v -0.037200 -0.035069 0.030521 +v -0.037200 -0.035055 -0.030526 +v -0.040200 -0.035055 0.030526 +v -0.040200 -0.026035 0.016718 +v -0.040200 -0.023526 -0.005788 +v -0.040200 -0.029080 -0.022452 +v -0.040200 -0.035069 -0.030521 +v -0.039200 -0.035069 0.030521 +v -0.039200 -0.035055 -0.030526 +v -0.039200 -0.026035 -0.016718 +v -0.039200 -0.023526 0.005788 +v -0.039200 -0.029080 0.022452 +v -0.042200 -0.035133 0.030380 +v -0.042200 -0.026035 0.016718 +v -0.042200 -0.023526 -0.005788 +v -0.042200 -0.029080 -0.022452 +v -0.042200 -0.035069 -0.030521 +v -0.041200 -0.035069 0.030521 +v -0.041200 -0.035055 -0.030526 +v -0.041200 -0.026035 -0.016718 +v -0.041200 -0.023526 0.005788 +v -0.041200 -0.029080 0.022452 +v -0.049687 -0.026135 -0.015124 +v -0.043384 -0.024653 -0.011788 +v -0.049192 -0.032667 -0.029280 +v -0.043401 -0.032839 -0.029323 +v -0.049779 -0.039136 -0.039985 +v -0.043335 -0.038036 -0.038875 +v -0.049706 -0.050690 -0.062097 +v -0.043359 -0.051170 -0.062789 +v -0.049779 -0.032738 0.027448 +v -0.043408 -0.032837 0.028457 +v -0.043363 -0.026827 0.017290 +v -0.049659 -0.027762 0.019156 +v -0.049698 -0.024539 0.009020 +v -0.043322 -0.023927 0.005287 +v -0.049687 -0.023641 -0.003281 +v -0.043436 -0.033084 0.035162 +v -0.049562 -0.033011 0.033817 +v -0.049554 -0.034872 0.036866 +v -0.043282 -0.035450 0.036926 +v -0.043396 -0.033163 -0.035177 +v -0.049554 -0.033152 -0.035099 +v -0.049902 -0.099192 -0.032580 +v -0.049811 -0.032588 -0.027506 +v -0.081684 -0.097345 0.013028 +v -0.075900 -0.106239 0.026385 +v -0.077598 -0.098548 0.029880 +v -0.076964 -0.110692 0.009089 +v -0.075622 -0.114118 0.006876 +v -0.075442 -0.111594 0.017986 +v -0.079273 -0.105536 -0.004879 +v -0.077915 -0.109060 0.003697 +v -0.078312 -0.107989 0.006552 +v -0.076519 -0.112359 0.003209 +v -0.075029 -0.115381 -0.001796 +v -0.075028 -0.112000 -0.016445 +v -0.069096 -0.093980 -0.050187 +v -0.068173 -0.079046 -0.056391 +v -0.062112 -0.087948 -0.062371 +v -0.062831 -0.070084 -0.064310 +v -0.060627 -0.085268 -0.064719 +v -0.065078 -0.073158 -0.061100 +v -0.065212 -0.066843 -0.060916 +v -0.061400 -0.057619 -0.064703 +v -0.068439 -0.060413 -0.055756 +v -0.062173 -0.052155 -0.062354 +v -0.079961 -0.051847 -0.028160 +v -0.075192 -0.033709 -0.025965 +v -0.075941 -0.038800 -0.028647 +v -0.075739 -0.042904 -0.033643 +v -0.078472 -0.032927 -0.007827 +v -0.078067 -0.031263 0.003717 +v -0.075148 -0.024797 -0.002777 +v -0.075756 -0.026087 0.004522 +v -0.075556 -0.027460 0.015092 +v -0.076130 -0.027352 0.008615 +v -0.077890 -0.031332 0.008103 +v -0.075988 -0.044381 0.037219 +v -0.076888 -0.042742 0.033434 +v -0.080180 -0.049831 0.029029 +v -0.076115 -0.065230 0.045250 +v -0.076194 -0.053443 0.041953 +v -0.079431 -0.064700 0.037447 +v -0.076252 -0.079081 0.044314 +v -0.080332 -0.085800 0.031786 +v -0.076004 -0.091130 0.040176 +v -0.076186 -0.096685 0.035861 +v -0.067444 -0.070062 -0.057832 +v -0.067488 -0.046889 -0.052910 +v -0.073726 -0.052407 -0.044315 +v -0.076638 -0.080071 -0.040535 +v -0.076766 -0.066855 -0.041504 +v -0.072046 -0.041325 -0.041452 +v -0.072262 -0.098729 -0.040938 +v -0.079424 -0.087391 -0.030577 +v -0.075996 -0.097208 -0.032831 +v -0.083775 -0.074851 -0.019855 +v -0.077299 -0.039662 0.028799 +v -0.083738 -0.068531 0.023423 +v -0.076300 -0.101668 -0.027750 +v -0.080538 -0.097227 -0.016968 +v -0.082480 -0.049978 -0.016492 +v -0.074566 -0.107199 -0.026239 +v -0.074854 -0.028396 -0.017834 +v -0.084163 -0.088491 -0.003389 +v -0.086030 -0.069694 -0.002006 +v -0.084074 -0.052271 0.010181 +v -0.083043 -0.046851 -0.004958 +v -0.080804 -0.039780 0.011976 +v -0.084297 -0.082884 0.014147 +v -0.075856 -0.034054 0.026788 +v -0.072580 -0.108303 -0.026478 +v -0.073280 -0.112395 -0.018808 +v -0.060710 -0.089424 -0.062251 +v -0.070044 -0.100105 -0.042233 +v -0.072966 -0.115059 -0.011507 +v -0.073058 -0.116517 -0.000588 +v -0.073356 -0.115396 0.010042 +v -0.073360 -0.112586 0.018583 +v -0.073625 -0.108771 0.025554 +v -0.073879 -0.096504 0.038058 +v -0.074103 -0.089171 0.042388 +v -0.074153 -0.079370 0.045519 +v -0.074225 -0.070692 0.046470 +v -0.074012 -0.057919 0.045046 +v -0.074130 -0.044199 0.038730 +v -0.059879 -0.082062 -0.065473 +v -0.059694 -0.055838 -0.065335 +v -0.056700 -0.111123 0.009362 +v -0.056700 -0.107926 0.006000 +v -0.056700 -0.114053 0.005946 +v -0.056700 -0.110971 0.002656 +v -0.056700 -0.032074 0.006000 +v -0.056700 -0.029790 0.009026 +v -0.056700 -0.025761 0.006495 +v -0.056700 -0.029350 0.002762 +v -0.056700 -0.073061 -0.060919 +v -0.056700 -0.070451 -0.057872 +v -0.056700 -0.070796 -0.064015 +v -0.056700 -0.066614 -0.061350 +v -0.074812 -0.101669 0.029708 +v -0.049931 -0.100332 0.030342 +v -0.075085 -0.099838 0.031291 +v -0.074583 -0.099519 -0.031576 +v -0.073234 -0.099241 -0.033423 +v -0.074317 -0.101601 -0.029635 +v -0.074087 -0.105519 0.028467 +v -0.074325 -0.098782 0.034857 +v -0.071477 -0.100436 -0.037869 +v -0.073204 -0.104719 -0.028868 +v -0.076418 -0.099981 0.030023 +v -0.073452 -0.025908 -0.014774 +v -0.073199 -0.031298 -0.025733 +v -0.060955 -0.050357 -0.062003 +v -0.069872 -0.039994 -0.042411 +v -0.074245 -0.031979 0.026351 +v -0.073355 -0.027008 0.017893 +v -0.073300 -0.023943 0.006468 +v -0.072943 -0.023676 -0.003920 +v -0.049932 -0.039667 0.030344 +v -0.074999 -0.038347 0.029678 +v -0.075277 -0.040235 0.031354 +v -0.049960 -0.039618 -0.030315 +v -0.074478 -0.040480 -0.031775 +v -0.073922 -0.038814 -0.029889 +v -0.049847 -0.040835 -0.032910 +v -0.073359 -0.040738 -0.034271 +v -0.073924 -0.035306 0.028863 +v -0.074551 -0.041256 0.034863 +v -0.071257 -0.039433 -0.038143 +v -0.073701 -0.034353 -0.028304 +v -0.043129 -0.058174 -0.045261 +v -0.043129 -0.056026 -0.044960 +v -0.043129 -0.058104 -0.046297 +v -0.043129 -0.059054 -0.042872 +v -0.043129 -0.063920 -0.046613 +v -0.043129 -0.063216 -0.043941 +v -0.043129 -0.062091 -0.045394 +v -0.043129 -0.057159 -0.043738 +v -0.043129 -0.059591 -0.042903 +v -0.043129 -0.061426 -0.043949 +v -0.043129 -0.060297 -0.045583 +v -0.043129 -0.052443 -0.050807 +v -0.042629 -0.055427 -0.043691 +v -0.043129 -0.067450 -0.051172 +v -0.043129 -0.063131 -0.047739 +v -0.043129 -0.050986 -0.050018 +v -0.043129 -0.050927 -0.058289 +v -0.043129 -0.053039 -0.057693 +v -0.043129 -0.066278 -0.053885 +v -0.043129 -0.061037 -0.060582 +v -0.043129 -0.058362 -0.062829 +v -0.043129 -0.066361 -0.059362 +v -0.042129 -0.054519 -0.046266 +v -0.042129 -0.056612 -0.045531 +v -0.042129 -0.062544 -0.044881 +v -0.042129 -0.061252 -0.043785 +v -0.042129 -0.063090 -0.043735 +v -0.042129 -0.056404 -0.046959 +v -0.042129 -0.058293 -0.045125 +v -0.042129 -0.059977 -0.046346 +v -0.042129 -0.060634 -0.045679 +v -0.042129 -0.057572 -0.043579 +v -0.042129 -0.049953 -0.052844 +v -0.042129 -0.052129 -0.051302 +v -0.042129 -0.052920 -0.056957 +v -0.042129 -0.052971 -0.060528 +v -0.042129 -0.057759 -0.060682 +v -0.042129 -0.061394 -0.062755 +v -0.042129 -0.064864 -0.057702 +v -0.042129 -0.067351 -0.050525 +v -0.042129 -0.065637 -0.050846 +v -0.042129 -0.067103 -0.057402 +v -0.047521 -0.056304 -0.046007 +v -0.046565 -0.058150 -0.045579 +v -0.046935 -0.054693 -0.046595 +v -0.047392 -0.066581 -0.056127 +v -0.046903 -0.067115 -0.052729 +v -0.047541 -0.066820 -0.053036 +v -0.046581 -0.053317 -0.058881 +v -0.046749 -0.052134 -0.055405 +v -0.046648 -0.054160 -0.058957 +v -0.047266 -0.064634 -0.059269 +v -0.046536 -0.063697 -0.059620 +v -0.046542 -0.066226 -0.056507 +v -0.047545 -0.059020 -0.045724 +v -0.047484 -0.061523 -0.045975 +v -0.047309 -0.052258 -0.049115 +v -0.046563 -0.051618 -0.050608 +v -0.046961 -0.062762 -0.046303 +v -0.046999 -0.065743 -0.055318 +v -0.047119 -0.064732 -0.057499 +v -0.046535 -0.065973 -0.050005 +v -0.046941 -0.065815 -0.051758 +v -0.046716 -0.064056 -0.048476 +v -0.047367 -0.062399 -0.047213 +v -0.047165 -0.059589 -0.046553 +v -0.047257 -0.057516 -0.060371 +v -0.047536 -0.059125 -0.061375 +v -0.047399 -0.061920 -0.060086 +v -0.047573 -0.064004 -0.059461 +v -0.047532 -0.065920 -0.050707 +v -0.046988 -0.052359 -0.051184 +v -0.047392 -0.052027 -0.055303 +v -0.047350 -0.065433 -0.048643 +v -0.047537 -0.051376 -0.055754 +v -0.046748 -0.057148 -0.046580 +v -0.047345 -0.056311 -0.046899 +v -0.046571 -0.056742 -0.061117 +v -0.046529 -0.064151 -0.047986 +v -0.047435 -0.054555 -0.059112 +v -0.047350 -0.054474 -0.060132 +v -0.046879 -0.057909 -0.061496 +v -0.047551 -0.052669 -0.049623 +v -0.047361 -0.051002 -0.052789 +v -0.046640 -0.051096 -0.054853 +v -0.046857 -0.061728 -0.061131 +v -0.046866 -0.054177 -0.048401 +v -0.047135 -0.051733 -0.057128 +v -0.046845 -0.058755 -0.060552 +v -0.046807 -0.062876 -0.059471 +v -0.059685 -0.030454 0.008228 +v -0.059618 -0.027797 0.008593 +v -0.059679 -0.026323 0.006132 +v -0.059611 -0.027313 0.003734 +v -0.059687 -0.029832 0.003503 +v -0.059616 -0.031872 0.005427 +v -0.048771 -0.029357 0.004610 +v -0.048867 -0.027419 0.005868 +v -0.048808 -0.030384 0.006502 +v -0.056620 -0.027588 0.006807 +v -0.049183 -0.029113 0.007605 +v -0.056573 -0.029984 0.007517 +v -0.056602 -0.030121 0.004736 +v -0.056597 -0.027803 0.004790 +v -0.056767 -0.027887 0.008664 +v -0.056761 -0.028557 0.003027 +v -0.056773 -0.026181 0.005921 +v -0.056753 -0.031838 0.005454 +v -0.056774 -0.030726 0.008161 +v -0.057700 -0.027594 0.005505 +v -0.057700 -0.030020 0.006449 +v -0.054951 -0.037105 0.036422 +v -0.054830 -0.034078 0.035687 +v -0.054944 -0.033673 0.032153 +v -0.054948 -0.038878 0.030734 +v -0.054848 -0.040350 0.034370 +v -0.054825 -0.035695 0.029811 +v -0.020993 -0.038354 0.031997 +v -0.021092 -0.034997 0.034307 +v -0.021136 -0.037916 0.034921 +v -0.021025 -0.035653 0.031637 +v -0.050790 -0.038400 0.034922 +v -0.050824 -0.035006 0.034591 +v -0.050829 -0.035006 0.031951 +v -0.050809 -0.037906 0.031234 +v -0.050957 -0.033271 0.032247 +v -0.050963 -0.034236 0.035702 +v -0.050961 -0.037341 0.036767 +v -0.050961 -0.040113 0.034502 +v -0.050951 -0.039177 0.030440 +v -0.050965 -0.035607 0.029936 +v -0.051900 -0.035288 0.032227 +v -0.051900 -0.038377 0.032458 +v -0.051900 -0.036632 0.035017 +v -0.043129 -0.079718 -0.045190 +v -0.043129 -0.080601 -0.046510 +v -0.042641 -0.080382 -0.042895 +v -0.043129 -0.085481 -0.046266 +v -0.042629 -0.084573 -0.043691 +v -0.043129 -0.083519 -0.044398 +v -0.043129 -0.078084 -0.044074 +v -0.043129 -0.081891 -0.044090 +v -0.042688 -0.080929 -0.046512 +v -0.043129 -0.082728 -0.045781 +v -0.043129 -0.080870 -0.042887 +v -0.043129 -0.079017 -0.046152 +v -0.043129 -0.076063 -0.046684 +v -0.042629 -0.076770 -0.043956 +v -0.043129 -0.072649 -0.050525 +v -0.043129 -0.089186 -0.050647 +v -0.043129 -0.086806 -0.048962 +v -0.043129 -0.074275 -0.051258 +v -0.043129 -0.074645 -0.056524 +v -0.042646 -0.072554 -0.056382 +v -0.043129 -0.076122 -0.061324 +v -0.043129 -0.078882 -0.060327 +v -0.043129 -0.083351 -0.062610 +v -0.042550 -0.084554 -0.059594 +v -0.043129 -0.089458 -0.057066 +v -0.043129 -0.087534 -0.056249 +v -0.042129 -0.078652 -0.043878 +v -0.042129 -0.077477 -0.044822 +v -0.042129 -0.079332 -0.046545 +v -0.042129 -0.079480 -0.045630 +v -0.042129 -0.081939 -0.045504 +v -0.042129 -0.086313 -0.048620 +v -0.042129 -0.083855 -0.044708 +v -0.042129 -0.082457 -0.043588 +v -0.042129 -0.073033 -0.049843 +v -0.042129 -0.073995 -0.051773 +v -0.042129 -0.076945 -0.059758 +v -0.042129 -0.075462 -0.060921 +v -0.042129 -0.082102 -0.062724 +v -0.042129 -0.088103 -0.059364 +v -0.042129 -0.089721 -0.051273 +v -0.042129 -0.087948 -0.054907 +v -0.046603 -0.076047 -0.047285 +v -0.046687 -0.076192 -0.048161 +v -0.046531 -0.073607 -0.052194 +v -0.047471 -0.073507 -0.051022 +v -0.047589 -0.075835 -0.047705 +v -0.046793 -0.074116 -0.049339 +v -0.047576 -0.086804 -0.048485 +v -0.047231 -0.085499 -0.046704 +v -0.047578 -0.080982 -0.045819 +v -0.046487 -0.074383 -0.057292 +v -0.047257 -0.074411 -0.056021 +v -0.047332 -0.076836 -0.059306 +v -0.047599 -0.076508 -0.059730 +v -0.047576 -0.083126 -0.061021 +v -0.047117 -0.080382 -0.061598 +v -0.046481 -0.081542 -0.061137 +v -0.046707 -0.084589 -0.060673 +v -0.046536 -0.088094 -0.056724 +v -0.046767 -0.085697 -0.058888 +v -0.047049 -0.087764 -0.055170 +v -0.046538 -0.080353 -0.045965 +v -0.046645 -0.076717 -0.060278 +v -0.046814 -0.079116 -0.060312 +v -0.047633 -0.088161 -0.051200 +v -0.047098 -0.087721 -0.049027 +v -0.047325 -0.076499 -0.047953 +v -0.046698 -0.076115 -0.058752 +v -0.046626 -0.088475 -0.050781 +v -0.047179 -0.085542 -0.048092 +v -0.046539 -0.084793 -0.046655 +v -0.046953 -0.073861 -0.057443 +v -0.046817 -0.072943 -0.052740 +v -0.047529 -0.073956 -0.056948 +v -0.047575 -0.078754 -0.060572 +v -0.046870 -0.087789 -0.051539 +v -0.046984 -0.082249 -0.045475 +v -0.047140 -0.078358 -0.045813 +v -0.047533 -0.088381 -0.056326 +v -0.047269 -0.089054 -0.053219 +v -0.047078 -0.080884 -0.046491 +v -0.047455 -0.078974 -0.046625 +v -0.047338 -0.086261 -0.058371 +v -0.047073 -0.074051 -0.052272 +v -0.047581 -0.073227 -0.053518 +v -0.047135 -0.082529 -0.060329 +v -0.047329 -0.087118 -0.058812 +v -0.046569 -0.088817 -0.053949 +v -0.046718 -0.084388 -0.047181 +v 0.010328 -0.042294 0.034111 +v 0.012488 -0.041852 0.032290 +v 0.009890 -0.040615 0.033527 +v 0.010399 -0.039105 0.037300 +v 0.010378 -0.038031 0.036111 +v 0.014086 -0.037189 0.036953 +v 0.013494 -0.038331 0.038074 +v 0.016134 -0.039708 0.036697 +v 0.016329 -0.039265 0.034877 +v 0.014771 -0.042792 0.033613 +v 0.014634 -0.041690 0.032452 +v 0.013798 -0.044256 0.032149 +v 0.012706 -0.043068 0.031074 +v 0.017364 -0.041809 0.032333 +v 0.017436 -0.042384 0.034021 +v 0.017758 -0.039189 0.037216 +v 0.017147 -0.037376 0.036766 +v 0.012386 -0.036914 0.039491 +v 0.011496 -0.035910 0.038232 +v 0.007987 -0.039819 0.036586 +v 0.007854 -0.039300 0.034843 +v 0.009178 -0.043083 0.033322 +v 0.010505 -0.042735 0.031407 +v 0.012249 -0.044165 0.032240 +v 0.009959 -0.041929 0.042816 +v 0.008006 -0.044382 0.040372 +v 0.011257 -0.043208 0.041682 +v 0.013599 -0.041325 0.043423 +v 0.011778 -0.046840 0.038050 +v 0.009414 -0.047560 0.037201 +v 0.014356 -0.048314 0.036441 +v 0.015965 -0.044706 0.040185 +v 0.017979 -0.045960 0.038803 +v 0.016841 -0.042468 0.042277 +v 0.015941 -0.027552 0.020886 +v 0.012293 -0.028626 0.019649 +v 0.009901 -0.026902 0.021369 +v 0.014618 -0.024886 0.023459 +v 0.011855 -0.024759 0.023648 +v 0.010016 -0.041785 0.034485 +v 0.014323 -0.042723 0.033583 +v 0.016198 -0.040667 0.035640 +v 0.014177 -0.038442 0.037853 +v 0.010811 -0.039019 0.037293 +v 0.008631 -0.042520 0.033990 +v 0.008162 -0.039472 0.037031 +v 0.012137 -0.044316 0.032186 +v 0.016788 -0.038255 0.038248 +v 0.011992 -0.037152 0.039353 +v 0.015973 -0.043578 0.032928 +v 0.017991 -0.041460 0.035047 +v 0.012532 -0.043464 0.034355 +v 0.015783 -0.040628 0.037191 +v 0.010685 -0.040055 0.037764 +v -0.015981 -0.044912 0.039978 +v -0.017646 -0.046229 0.038526 +v -0.014291 -0.048430 0.036333 +v -0.010261 -0.047800 0.036940 +v -0.011518 -0.046747 0.038144 +v -0.008135 -0.045938 0.038807 +v -0.008553 -0.043147 0.041601 +v -0.012730 -0.041128 0.043648 +v -0.011502 -0.043096 0.041794 +v -0.017636 -0.043254 0.041501 +v -0.011704 -0.024617 0.023611 +v -0.015700 -0.027331 0.020951 +v -0.015530 -0.025509 0.022955 +v -0.013452 -0.028918 0.019621 +v -0.010168 -0.027477 0.020857 +v -0.011522 -0.042603 0.033709 +v -0.009673 -0.040057 0.036213 +v -0.013168 -0.038368 0.037940 +v -0.015676 -0.039442 0.036869 +v -0.015491 -0.042261 0.034009 +v -0.007852 -0.040874 0.035629 +v -0.009931 -0.043565 0.032945 +v -0.018070 -0.041104 0.035402 +v -0.016421 -0.038000 0.038503 +v -0.014910 -0.044201 0.032287 +v -0.010735 -0.037342 0.039148 +v -0.015108 -0.039892 0.037927 +v -0.010121 -0.040837 0.036982 +v -0.013771 -0.043418 0.034401 +v 0.015783 -0.044164 -0.040726 +v 0.014940 -0.041492 -0.043268 +v 0.018185 -0.044436 -0.040327 +v 0.010685 -0.043591 -0.041299 +v 0.010615 -0.041677 -0.043065 +v 0.012532 -0.047000 -0.037891 +v 0.016133 -0.047696 -0.037054 +v 0.012521 -0.048386 -0.036355 +v 0.009262 -0.047285 -0.037465 +v 0.007925 -0.044202 -0.040553 +v 0.012805 -0.028780 -0.019501 +v 0.015456 -0.025254 -0.023022 +v 0.010229 -0.027105 -0.021103 +v 0.011125 -0.024949 -0.023442 +v 0.016159 -0.041528 -0.034742 +v 0.015678 -0.028020 -0.020791 +v 0.012609 -0.042845 -0.033466 +v 0.010170 -0.041681 -0.034627 +v 0.010188 -0.039611 -0.036701 +v 0.013733 -0.038249 -0.038022 +v 0.016722 -0.043371 -0.033119 +v 0.017690 -0.039109 -0.037388 +v 0.009648 -0.037958 -0.038545 +v 0.007927 -0.041574 -0.034922 +v 0.013846 -0.037207 -0.039303 +v 0.011423 -0.044154 -0.032353 +v 0.011778 -0.043305 -0.034514 +v 0.011257 -0.039673 -0.038146 +v 0.015965 -0.041170 -0.036649 +v -0.015879 -0.045464 -0.039426 +v -0.014989 -0.048215 -0.036540 +v -0.017612 -0.046219 -0.038536 +v -0.010892 -0.046408 -0.038482 +v -0.010658 -0.048015 -0.036733 +v -0.008266 -0.043448 -0.041311 +v -0.008375 -0.046246 -0.038485 +v -0.017844 -0.043657 -0.041083 +v -0.015118 -0.041618 -0.043137 +v -0.012229 -0.042882 -0.042008 +v -0.011516 -0.041413 -0.043329 +v -0.010594 -0.025244 -0.023010 +v -0.013946 -0.024713 -0.023704 +v -0.015869 -0.026113 -0.022263 +v -0.012565 -0.028836 -0.019631 +v -0.010322 -0.027372 -0.020876 +v -0.015311 -0.028002 -0.020450 +v -0.015679 -0.039109 -0.037161 +v -0.010956 -0.038790 -0.037504 +v -0.010095 -0.041728 -0.034570 +v -0.014623 -0.042734 -0.033536 +v -0.012977 -0.037122 -0.039385 +v -0.017688 -0.038994 -0.037495 +v -0.009348 -0.038261 -0.038249 +v -0.011889 -0.044324 -0.032172 +v -0.016976 -0.043044 -0.033462 +v -0.007876 -0.041408 -0.035089 +v -0.010707 -0.040142 -0.037677 +v -0.011518 -0.043211 -0.034608 +v -0.014482 -0.039554 -0.038265 +v -0.015293 -0.042623 -0.035196 +v -0.013522 -0.037154 -0.036988 +v -0.014896 -0.038726 -0.037678 +v -0.011004 -0.038600 -0.037805 +v -0.009674 -0.038766 -0.035377 +v -0.009893 -0.041820 -0.034585 +v -0.011322 -0.041718 -0.032424 +v -0.014720 -0.042954 -0.033451 +v -0.016223 -0.040760 -0.033382 +v -0.016026 -0.039580 -0.036825 +v -0.015243 -0.037789 -0.036353 +v -0.016687 -0.037054 -0.037089 +v -0.016271 -0.038009 -0.038396 +v -0.018360 -0.041211 -0.035194 +v -0.018038 -0.039800 -0.034342 +v -0.015870 -0.042612 -0.031531 +v -0.013570 -0.044331 -0.032074 +v -0.011367 -0.042924 -0.031218 +v -0.009360 -0.043151 -0.033253 +v -0.008074 -0.040725 -0.033417 +v -0.007855 -0.040134 -0.036270 +v -0.009854 -0.036480 -0.037662 +v -0.010753 -0.037452 -0.038953 +v -0.015326 -0.037455 -0.038950 +v -0.015801 -0.036508 -0.037634 +v 0.010769 -0.041402 -0.032740 +v 0.011422 -0.042836 -0.033569 +v 0.009732 -0.039783 -0.036622 +v 0.010377 -0.037747 -0.036395 +v 0.012783 -0.038310 -0.038095 +v 0.015833 -0.037974 -0.036168 +v 0.015777 -0.039264 -0.037141 +v 0.015370 -0.042555 -0.033850 +v 0.014771 -0.041660 -0.032482 +v 0.012706 -0.043721 -0.031741 +v 0.015978 -0.042522 -0.031620 +v 0.017151 -0.043068 -0.033337 +v 0.018170 -0.038557 -0.035585 +v 0.017334 -0.038642 -0.037763 +v 0.013710 -0.035960 -0.038182 +v 0.011496 -0.037041 -0.039364 +v 0.008603 -0.037451 -0.036691 +v 0.008070 -0.039900 -0.036505 +v 0.008786 -0.041700 -0.032442 +v 0.008875 -0.042865 -0.033540 +v 0.012240 -0.043603 -0.031671 +v -0.012961 -0.038215 0.038190 +v -0.013710 -0.037160 0.036982 +v -0.009857 -0.038591 0.035551 +v -0.009356 -0.041160 0.035245 +v -0.010347 -0.041029 0.033113 +v -0.013674 -0.043075 0.033330 +v -0.014263 -0.041890 0.032252 +v -0.016203 -0.041375 0.035030 +v -0.016290 -0.038816 0.035326 +v -0.015479 -0.039017 0.037388 +v -0.017321 -0.038708 0.037696 +v -0.016874 -0.037106 0.037036 +v -0.017528 -0.041492 0.032650 +v -0.017239 -0.042865 0.033540 +v -0.010903 -0.043073 0.031069 +v -0.012091 -0.044265 0.032139 +v -0.008345 -0.042180 0.034225 +v -0.007855 -0.039003 0.035139 +v -0.008566 -0.038812 0.037593 +v -0.010753 -0.036321 0.037822 +v -0.011891 -0.037211 0.039194 +v -0.015326 -0.036323 0.037819 +v -0.015801 -0.037639 0.038765 +v -0.021000 -0.106771 0.028745 +v -0.027000 -0.106482 0.029439 +v -0.021000 -0.112863 0.018445 +v -0.027000 -0.116524 0.008160 +v -0.021000 -0.116778 0.001757 +v -0.027000 -0.113938 -0.016148 +v -0.021000 -0.113437 -0.017450 +v -0.027000 -0.106424 -0.029507 +v -0.021000 -0.106470 -0.029442 +v -0.021074 -0.048371 0.041318 +v -0.027000 -0.055524 0.044453 +v -0.021000 -0.070080 0.046751 +v -0.027000 -0.073482 0.046625 +v -0.021000 -0.085787 0.043892 +v -0.027000 -0.088990 0.042604 +v -0.021000 -0.099423 0.036481 +v -0.027000 -0.099502 0.036424 +v -0.027000 -0.043919 0.038707 +v -0.016811 -0.038499 0.020936 +v 0.016818 -0.038496 0.020905 +v -0.016994 -0.034596 0.013084 +v 0.017000 -0.034573 0.013025 +v -0.016971 -0.032446 0.002856 +v 0.016972 -0.032448 0.002871 +v -0.016951 -0.033060 -0.007687 +v 0.016958 -0.033064 -0.007707 +v -0.016975 -0.038236 -0.020394 +v 0.016962 -0.035931 -0.015934 +v 0.016760 -0.038502 -0.020886 +v 0.020884 -0.077248 0.037017 +v -0.018565 -0.076248 0.037285 +v -0.018188 -0.087289 0.033561 +v 0.020758 -0.093232 0.029699 +v -0.018202 -0.094118 0.028900 +v -0.018018 -0.100453 0.022240 +v 0.020773 -0.104926 0.014629 +v -0.018125 -0.104762 0.014371 +v -0.018960 -0.107459 0.005824 +v 0.020916 -0.107433 -0.002195 +v -0.017937 -0.107380 -0.004347 +v -0.018273 -0.105358 -0.013027 +v 0.020928 -0.103859 -0.016621 +v -0.017986 -0.100511 -0.022140 +v 0.020722 -0.093218 -0.029732 +v -0.019173 -0.095630 -0.027966 +v -0.018438 -0.088511 -0.032878 +v -0.018584 -0.077599 -0.037137 +v 0.020888 -0.076966 -0.037102 +v -0.021115 -0.030672 -0.026570 +v -0.026999 -0.030696 -0.026633 +v -0.027000 -0.024144 -0.010168 +v -0.021000 -0.024541 -0.011088 +v -0.021000 -0.023857 0.007760 +v -0.027000 -0.024541 0.011088 +v -0.021111 -0.030689 0.026605 +v -0.027000 -0.030731 0.026539 +v -0.021000 -0.098739 -0.036772 +v -0.027000 -0.099423 -0.036481 +v -0.021000 -0.082491 -0.045468 +v -0.027000 -0.085787 -0.043892 +v -0.027000 -0.070104 -0.046729 +v -0.021000 -0.061047 -0.045903 +v -0.027000 -0.053843 -0.043781 +v -0.020683 -0.046981 -0.040428 +v -0.027000 -0.043855 -0.038680 +v -0.020790 -0.035473 0.022960 +v -0.020897 -0.031269 0.015391 +v -0.020893 -0.028446 0.002826 +v -0.020890 -0.029457 -0.009464 +v -0.020825 -0.035351 -0.023093 +v -0.018626 -0.042773 -0.038646 +v -0.027000 -0.035373 -0.038822 +v -0.016181 -0.050244 -0.038203 +v -0.009616 -0.049765 -0.038293 +v 0.020774 -0.035554 -0.038754 +v 0.018661 -0.043273 -0.038539 +v 0.015620 -0.036052 -0.038428 +v 0.012163 -0.035569 -0.038759 +v 0.008755 -0.048972 -0.038323 +v 0.015539 -0.050702 -0.038258 +v -0.013839 -0.035599 -0.038787 +v 0.007629 -0.041031 -0.038624 +v -0.007368 -0.040523 -0.038641 +v 0.020793 -0.028682 0.031712 +v 0.020807 -0.035559 0.038750 +v 0.020783 -0.028671 -0.031731 +v -0.027000 -0.028530 -0.031770 +v 0.020353 -0.035979 0.023570 +v 0.020684 -0.031152 0.013620 +v 0.020405 -0.035997 -0.023580 +v 0.020521 -0.029009 0.004346 +v 0.020721 -0.029990 -0.010454 +v 0.016243 -0.043027 -0.031115 +v 0.018601 -0.038953 -0.035189 +v 0.009235 -0.042703 -0.031439 +v 0.007576 -0.038051 -0.036090 +v -0.018236 -0.041224 -0.032917 +v -0.017536 -0.036907 -0.037233 +v -0.014450 -0.043372 -0.030771 +v -0.009380 -0.042756 -0.031386 +v -0.007784 -0.037286 -0.036851 +v -0.019694 -0.029179 -0.030718 +v -0.019751 -0.035880 -0.023948 +v -0.016688 -0.038305 -0.021438 +v -0.018536 -0.043320 0.038676 +v -0.027000 -0.035387 0.038822 +v -0.015620 -0.036052 0.038428 +v 0.010461 -0.050702 0.038258 +v -0.014170 -0.050952 0.038248 +v -0.009757 -0.049857 0.038290 +v 0.017245 -0.048972 0.038323 +v -0.007339 -0.043682 0.038523 +v -0.009470 -0.037384 0.038761 +v 0.010453 -0.035967 0.038435 +v 0.013838 -0.035583 0.038772 +v -0.012708 -0.035578 0.038732 +v 0.018371 -0.041031 0.038624 +v 0.007339 -0.043273 0.038539 +v -0.017875 -0.047527 0.038430 +v 0.020986 -0.036603 0.023575 +v 0.020984 -0.036600 -0.023630 +v -0.018837 -0.040406 0.033737 +v -0.013000 -0.043666 0.030476 +v -0.008376 -0.041796 0.032346 +v -0.019760 -0.035886 0.023936 +v -0.019671 -0.029176 0.030725 +v 0.016765 -0.042703 0.031439 +v 0.018424 -0.038052 0.036090 +v -0.027000 -0.028523 0.031792 +v 0.009757 -0.043027 0.031115 +v 0.007399 -0.038953 0.035189 +v -0.007576 -0.038052 0.036090 +v -0.027000 -0.104608 0.036703 +v -0.021000 -0.103762 0.036789 +v -0.027000 -0.106789 0.033762 +v -0.021000 -0.106685 0.034591 +v -0.020743 -0.097684 0.028538 +v -0.020820 -0.079753 0.039090 +v -0.020808 -0.091421 -0.033925 +v -0.021000 -0.104591 -0.036685 +v -0.027000 -0.106778 -0.033705 +v -0.021000 -0.106789 -0.033762 +v -0.027000 -0.104668 -0.036715 +v -0.020863 -0.108333 0.013338 +v -0.020953 -0.110144 -0.009676 +v -0.020737 -0.102232 -0.023012 +v -0.020795 -0.077944 -0.039287 +v -0.020202 -0.089892 0.033599 +v -0.020210 -0.105622 0.016490 +v -0.020094 -0.108691 -0.004823 +v -0.020129 -0.105403 -0.016192 +v 0.007333 -0.033478 -0.008646 +v -0.006295 -0.033848 -0.010484 +v 0.005056 -0.034292 -0.011741 +v 0.008645 -0.032447 0.003007 +v 0.008464 -0.032623 -0.003994 +v 0.015732 -0.032564 0.002171 +v 0.016745 -0.032336 -0.001228 +v 0.005463 -0.033131 0.007718 +v -0.005228 -0.034262 0.011582 +v -0.006595 -0.032986 0.006868 +v -0.008503 -0.032469 -0.002808 +v -0.015669 -0.032296 0.000055 +v -0.016534 -0.035222 0.014058 +v -0.005594 -0.037565 0.019028 +v -0.016927 -0.037681 0.019670 +v 0.005654 -0.035119 0.013835 +v 0.016810 -0.035383 0.014690 +v 0.016915 -0.037813 0.019995 +v 0.005602 -0.037575 0.019031 +v 0.015701 -0.035574 -0.014848 +v 0.016900 -0.037795 -0.019917 +v 0.005592 -0.037572 -0.019045 +v -0.016950 -0.037670 -0.019670 +v -0.005530 -0.037866 -0.019999 +v -0.016693 -0.034992 -0.013720 +v 0.001702 -0.037208 0.022443 +v -0.016988 -0.037289 0.022469 +v -0.002023 -0.037262 0.022323 +v 0.016974 -0.036810 0.023142 +v -0.020670 -0.034008 -0.020733 +v -0.020568 -0.029942 -0.009411 +v -0.020624 -0.028897 0.005399 +v -0.017342 -0.031858 0.000080 +v -0.020671 -0.034009 0.020733 +v -0.017018 -0.037250 -0.022521 +v 0.001317 -0.037149 -0.022620 +v 0.016985 -0.036837 -0.023110 +v 0.020593 -0.029173 0.005761 +v 0.020684 -0.033921 0.020816 +v 0.020495 -0.029767 -0.008363 +v 0.018038 -0.034256 -0.014263 +v 0.020621 -0.034083 -0.020708 +v 0.017356 -0.029373 0.030277 +v 0.016736 -0.022963 0.030746 +v 0.001686 -0.027361 0.030682 +v 0.021339 -0.027878 0.020974 +v 0.021273 -0.023341 0.027841 +v 0.021361 -0.023096 -0.027747 +v 0.021342 -0.027873 -0.020917 +v 0.020981 -0.025226 -0.015078 +v 0.021000 -0.022820 0.004411 +v 0.028520 -0.022353 -0.020650 +v 0.032421 -0.023832 -0.010006 +v 0.034300 -0.022338 -0.007948 +v 0.034759 -0.022779 0.001682 +v 0.033206 -0.022346 0.011384 +v 0.030468 -0.024601 0.012509 +v 0.028168 -0.022325 0.020992 +v 0.006160 -0.022340 0.034655 +v 0.004288 -0.026086 0.031146 +v -0.006786 -0.022377 0.034466 +v -0.010575 -0.025169 0.030751 +v -0.016792 -0.022783 0.030743 +v 0.009089 -0.020337 0.034053 +v 0.020929 -0.020338 0.028315 +v -0.007542 -0.020337 0.034558 +v -0.017387 -0.029305 0.030283 +v -0.018965 -0.020336 0.029516 +v -0.027129 -0.020337 0.022535 +v -0.021290 -0.023367 0.027828 +v -0.030318 -0.022346 0.018182 +v -0.034522 -0.020337 0.007649 +v -0.034918 -0.022698 0.002390 +v -0.034206 -0.020337 -0.008411 +v -0.034196 -0.023043 -0.005752 +v -0.029762 -0.022332 -0.019072 +v -0.028075 -0.020337 -0.021271 +v -0.019907 -0.020337 -0.028856 +v -0.021297 -0.023292 -0.027798 +v -0.017303 -0.029376 -0.030332 +v -0.011169 -0.020337 -0.033387 +v -0.016789 -0.022964 -0.030719 +v -0.008757 -0.022324 -0.034004 +v 0.005206 -0.020338 -0.035022 +v 0.005023 -0.022334 -0.034986 +v 0.017776 -0.020338 -0.030198 +v 0.016603 -0.023068 -0.030778 +v 0.017407 -0.029241 -0.030306 +v 0.026004 -0.020337 -0.023808 +v 0.034078 -0.020339 -0.009428 +v 0.034596 -0.020338 0.006625 +v 0.030240 -0.020338 0.017816 +v -0.021304 -0.027886 -0.020972 +v -0.021358 -0.027864 0.020901 +v -0.020980 -0.025203 0.015025 +v -0.021000 -0.022818 -0.004428 +v -0.030365 -0.024635 0.012622 +v -0.027401 -0.025739 -0.015925 +v -0.001806 -0.028148 -0.030532 +v 0.000596 -0.026787 -0.031008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vn -0.9993 -0.0344 0.0160 +vn -0.9991 -0.0363 0.0213 +vn -0.9993 -0.0259 0.0276 +vn -0.9996 0.0006 0.0267 +vn -0.9995 0.0325 0.0063 +vn -0.9992 0.0390 0.0128 +vn -0.9995 0.0272 -0.0128 +vn -0.9997 0.0206 -0.0133 +vn 0.9999 0.0096 0.0118 +vn 0.9963 0.0853 0.0071 +vn 0.9998 0.0008 0.0220 +vn 0.9949 0.1006 0.0017 +vn -0.0046 -0.9893 0.1460 +vn 0.0067 -0.9619 0.2734 +vn -0.0040 -0.9882 0.1529 +vn 0.0076 -0.9591 0.2829 +vn -0.0078 0.1368 0.9906 +vn 0.0109 -0.1037 0.9946 +vn 0.0096 -0.0862 0.9962 +vn -0.0087 0.1485 0.9889 +vn 0.0213 0.8464 0.5321 +vn -0.0190 0.9686 -0.2479 +vn 0.0093 0.7664 -0.6423 +vn -0.0177 0.9633 -0.2679 +vn 0.0111 0.7481 -0.6635 +vn -0.0003 -0.1439 -0.9896 +vn 0.0179 -0.3447 -0.9385 +vn 0.0009 -0.1570 -0.9876 +vn 0.0191 -0.3578 -0.9336 +vn 0.9922 0.1056 0.0658 +vn 0.9956 -0.0259 0.0901 +vn 0.9948 -0.0664 0.0770 +vn 0.9958 -0.0904 0.0126 +vn 0.9943 -0.0853 -0.0638 +vn 0.9928 -0.0719 -0.0959 +vn 0.9960 0.0203 -0.0874 +vn 0.9950 0.0644 -0.0770 +vn 0.9953 0.0954 -0.0171 +vn 0.9937 0.0551 0.0974 +vn -0.0468 -0.7340 0.6775 +vn 0.0176 -0.7779 0.6282 +vn -0.0542 -0.7286 0.6828 +vn -0.1101 -0.6846 0.7206 +vn 0.1354 0.1540 0.9788 +vn -0.1587 0.5930 0.7894 +vn 0.1155 0.8957 0.4294 +vn -0.1612 0.9370 -0.3099 +vn -0.0106 0.8753 -0.4835 +vn 0.0019 0.8680 -0.4966 +vn 0.1584 0.7476 -0.6450 +vn -0.1243 -0.1275 -0.9840 +vn -0.0728 -0.1974 -0.9776 +vn -0.0797 -0.1881 -0.9789 +vn -0.0223 -0.2638 -0.9643 +vn -0.0416 -0.8980 -0.4379 +vn -0.0735 -0.9121 -0.4034 +vn -0.0467 -0.9004 -0.4325 +vn -0.0156 -0.8850 -0.4654 +vn 0.1237 -0.3248 -0.9376 +vn -0.0014 -0.4509 -0.8926 +vn 0.0015 -0.4477 -0.8942 +vn -0.1240 -0.5590 -0.8198 +vn -0.2276 0.9558 -0.1862 +vn -0.1765 0.9756 -0.1309 +vn -0.1845 0.9729 -0.1395 +vn -0.1239 0.9895 -0.0743 +vn 0.1271 -0.6222 0.7725 +vn -0.0344 -0.5380 0.8423 +vn 0.0058 -0.5609 0.8279 +vn -0.2067 -0.4245 0.8815 +vn -1.0000 0.0000 0.0000 +vn 0.9668 0.2553 -0.0066 +vn -0.9988 -0.0047 -0.0480 +vn -0.9990 -0.0334 0.0290 +vn -0.9975 0.0645 0.0273 +vn 0.9996 0.0106 0.0270 +vn 0.9994 0.0107 0.0335 +vn 0.9996 0.0109 0.0274 +vn 0.9997 0.0107 0.0219 +vn 0.0064 -0.7842 -0.6205 +vn 0.0197 -0.6873 -0.7261 +vn 0.0188 -0.6944 -0.7193 +vn 0.0054 -0.7905 -0.6125 +vn -0.0032 -0.5611 0.8277 +vn 0.0089 -0.6634 0.7483 +vn 0.0080 -0.6562 0.7546 +vn -0.0039 -0.5547 0.8320 +vn -0.0115 0.8418 0.5396 +vn 0.0173 0.6078 0.7939 +vn 0.0152 0.6277 0.7783 +vn -0.0132 0.8530 0.5218 +vn -0.0048 0.4838 -0.8752 +vn 0.0248 0.7747 -0.6319 +vn 0.0229 0.7583 -0.6516 +vn -0.0067 0.4625 -0.8866 +vn 0.9880 -0.1481 0.0437 +vn 0.9946 -0.0982 -0.0347 +vn 0.9959 -0.0190 -0.0881 +vn 0.9954 -0.0277 -0.0915 +vn 0.9948 0.0645 -0.0782 +vn 0.9874 0.1543 -0.0346 +vn 0.9956 0.0799 0.0487 +vn 0.9891 0.0453 0.1400 +vn 0.9962 -0.0352 0.0795 +vn -0.0405 -0.6678 -0.7433 +vn -0.0885 -0.6969 -0.7117 +vn -0.0454 -0.6709 -0.7402 +vn 0.0008 -0.6406 -0.7679 +vn -0.1326 -0.9879 0.0809 +vn 0.0255 -0.9662 0.2566 +vn 0.0350 -0.9631 0.2667 +vn 0.1746 -0.8951 0.4103 +vn -0.1689 -0.1960 0.9659 +vn 0.0241 0.4740 0.8802 +vn 0.1370 0.3201 0.9374 +vn 0.0291 0.4676 0.8835 +vn -0.1115 0.6325 0.7665 +vn 0.0389 0.9798 -0.1964 +vn 0.0804 0.9848 -0.1540 +vn 0.0445 0.9806 -0.1907 +vn -0.0081 0.9699 -0.2434 +vn -0.1570 0.5551 -0.8168 +vn -0.0083 0.3844 -0.9231 +vn -0.0329 0.4143 -0.9095 +vn 0.1178 0.2214 -0.9680 +vn -0.4512 0.6801 -0.5779 +vn -0.4238 0.7042 -0.5697 +vn -0.4334 0.6959 -0.5727 +vn -0.3951 0.7278 -0.5605 +vn -0.0160 0.0680 0.9976 +vn -0.7243 -0.5464 0.4205 +vn -0.1351 -0.9238 -0.3582 +vn -0.9996 0.0027 0.0276 +vn -0.9993 0.0187 0.0329 +vn -0.9993 0.0191 0.0306 +vn -0.9997 -0.0030 0.0249 +vn -0.9994 0.0033 -0.0353 +vn -0.9998 -0.0187 0.0099 +vn 0.9999 -0.0129 -0.0045 +vn 0.9918 0.0573 -0.1142 +vn 0.9919 0.0566 -0.1136 +vn 0.0003 0.9705 -0.2410 +vn -0.0128 0.9550 -0.2962 +vn -0.0109 0.9576 -0.2881 +vn 0.0020 0.9722 -0.2342 +vn 0.0100 -0.2190 -0.9757 +vn 0.0073 -0.2362 -0.9717 +vn 0.0075 -0.2338 -0.9722 +vn 0.0102 -0.2177 -0.9760 +vn 0.0206 -0.9968 -0.0778 +vn 0.0369 -0.9992 0.0145 +vn 0.0227 -0.9976 -0.0659 +vn 0.0390 -0.9989 0.0264 +vn -0.0087 -0.0182 0.9998 +vn 0.0431 0.2436 0.9689 +vn -0.0011 0.0203 0.9998 +vn 0.0514 0.2858 0.9569 +vn 0.9944 -0.0841 0.0639 +vn 0.9927 -0.0939 0.0757 +vn 0.9937 -0.1001 -0.0505 +vn 0.9919 -0.0788 -0.0999 +vn 0.9919 0.0876 0.0917 +vn 0.9941 0.1076 0.0156 +vn 0.9938 0.0074 0.1112 +vn 0.9936 0.0257 -0.1101 +vn 0.9923 0.0828 -0.0921 +vn -0.1846 0.9634 0.1946 +vn 0.0468 0.7963 -0.6030 +vn 0.1799 0.8631 -0.4719 +vn 0.0103 0.7727 -0.6347 +vn -0.1504 0.6420 -0.7518 +vn 0.0522 -0.4896 -0.8704 +vn 0.0965 -0.4519 -0.8868 +vn 0.0438 -0.4964 -0.8670 +vn -0.0083 -0.5378 -0.8431 +vn -0.0827 -0.9893 0.1204 +vn -0.0656 -0.9924 0.1042 +vn -0.0851 -0.9888 0.1227 +vn -0.1002 -0.9855 0.1370 +vn -0.0456 -0.1475 0.9880 +vn 0.1150 -0.3414 0.9329 +vn -0.0573 -0.1328 0.9895 +vn -0.1914 0.0405 0.9807 +vn 0.1730 0.6319 0.7555 +vn -0.8017 0.5690 0.1832 +vn 0.1881 -0.0959 0.9775 +vn -0.7257 -0.6549 -0.2109 +vn 0.0808 -0.5151 -0.8533 +vn -0.2673 0.8292 -0.4909 +vn 0.9605 0.1387 -0.2411 +vn 0.4339 0.4492 -0.7810 +vn -0.6549 0.1005 -0.7490 +vn -0.4063 -0.9090 -0.0928 +vn -0.4221 -0.9045 -0.0601 +vn -0.4023 -0.9099 -0.1011 +vn -0.3882 -0.9125 -0.1290 +vn 0.5632 -0.7564 0.3327 +vn -0.4997 -0.2994 0.8128 +vn 0.5603 0.5445 0.6241 +vn 0.3870 -0.8574 -0.3394 +vn -0.5775 -0.2903 -0.7630 +vn 0.6458 0.2455 -0.7229 +vn -0.4206 0.6789 -0.6017 +vn 0.3990 0.8959 0.1955 +vn -0.1934 0.9001 0.3905 +vn -0.0671 -0.0196 0.9976 +vn 0.4450 -0.1518 0.8826 +vn -0.4535 -0.8712 0.1881 +vn 0.7926 -0.3273 -0.5144 +vn 1.0000 0.0000 0.0000 +vn 0.9878 -0.1245 0.0938 +vn 0.9771 -0.1698 0.1279 +vn 0.9171 0.2759 0.2878 +vn 0.9317 -0.2902 0.2186 +vn -0.9618 -0.1642 0.2192 +vn -0.9772 -0.0850 0.1947 +vn -0.9868 -0.0365 0.1577 +vn -0.9998 0.0015 0.0192 +vn -0.4146 0.7920 0.4481 +vn -0.4377 0.7992 0.4119 +vn -0.4551 0.8038 0.3832 +vn 0.5126 0.8544 -0.0847 +vn -0.4893 0.1889 -0.8514 +vn 0.1854 -0.0490 -0.9814 +vn -0.1649 -0.9626 0.2152 +vn -0.1482 -0.9640 0.2209 +vn -0.0718 -0.9333 0.3519 +vn -0.0589 -0.9266 0.3713 +vn 0.6826 -0.7128 -0.1614 +vn -0.0457 -0.8637 0.5020 +vn -0.3128 0.4907 -0.8132 +vn 0.4663 0.7253 -0.5064 +vn -0.4835 0.8737 0.0539 +vn 0.4740 0.7302 0.4921 +vn -0.4883 0.0528 0.8711 +vn -0.5360 0.0692 0.8414 +vn -0.2247 -0.0320 0.9739 +vn -0.0825 -0.0742 0.9938 +vn 0.4519 -0.8392 0.3026 +vn -0.5275 -0.8488 0.0349 +vn 0.2602 -0.4750 -0.8406 +vn -0.3919 0.7838 0.4818 +vn 0.9493 -0.0725 -0.3060 +vn 0.9962 -0.0201 -0.0848 +vn 0.8997 -0.1007 -0.4248 +vn -0.9950 0.0544 -0.0839 +vn -0.9923 0.0671 -0.1036 +vn -0.9721 0.1275 -0.1969 +vn -0.9993 0.0349 0.0110 +vn -0.9994 0.0215 0.0254 +vn -0.9995 0.0322 -0.0044 +vn -0.9997 0.0249 -0.0078 +vn -0.9993 -0.0202 0.0304 +vn -0.9993 -0.0074 0.0365 +vn -0.9994 -0.0294 0.0156 +vn -0.9996 -0.0256 0.0094 +vn 0.9996 -0.0066 -0.0260 +vn 0.9974 0.0399 -0.0605 +vn 0.9996 -0.0056 -0.0267 +vn 0.9989 -0.0467 0.0039 +vn -0.0127 0.6909 -0.7229 +vn 0.0220 0.3112 -0.9501 +vn -0.0104 0.6691 -0.7431 +vn 0.0244 0.2805 -0.9595 +vn -0.0090 -0.6358 -0.7718 +vn 0.0292 -0.9934 -0.1110 +vn -0.0093 -0.9123 0.4094 +vn 0.0229 0.0495 0.9985 +vn -0.0163 0.5429 0.8396 +vn 0.0248 0.9693 0.2448 +vn 0.9949 0.0081 -0.1001 +vn 0.9952 -0.0211 -0.0954 +vn 0.9964 0.0770 -0.0362 +vn 0.9893 0.1378 0.0475 +vn 0.9954 0.0435 0.0852 +vn 0.9893 -0.0349 0.1416 +vn 0.9953 -0.0774 0.0580 +vn 0.9954 -0.0932 -0.0212 +vn 0.9953 -0.0871 -0.0427 +vn 0.0232 0.3403 -0.9400 +vn 0.1426 0.4482 -0.8825 +vn 0.0065 0.3239 -0.9461 +vn -0.1238 0.1946 -0.9730 +vn -0.0763 -0.6918 -0.7180 +vn -0.0176 -0.6284 -0.7777 +vn -0.0677 -0.6830 -0.7273 +vn -0.1209 -0.7355 -0.6666 +vn 0.1710 -0.9794 0.1077 +vn -0.1948 -0.7841 0.5893 +vn 0.1683 -0.1898 0.9673 +vn -0.1316 0.2475 0.9599 +vn 0.0312 0.9661 0.2562 +vn 0.1763 0.9037 0.3901 +vn -0.0133 0.9769 0.2131 +vn -0.1638 0.9846 0.0610 +vn -0.0350 0.9992 0.0202 +vn -0.0802 0.9964 -0.0273 +vn -0.0706 0.9974 -0.0171 +vn -0.1238 0.9895 -0.0743 +vn 0.1065 -0.7670 0.6328 +vn -0.4235 -0.3932 0.8162 +vn -0.0013 -0.4510 -0.8925 +vn -0.0667 -0.7384 -0.6710 +vn -0.5402 -0.8028 -0.2522 +vn 0.3959 -0.8800 0.2622 +vn -0.2357 -0.0489 0.9706 +vn -0.2880 -0.0312 0.9571 +vn -0.1341 -0.0820 0.9876 +vn -0.0952 -0.0943 0.9910 +vn -0.0250 0.9940 -0.1066 +vn -0.0039 0.9936 -0.1132 +vn 0.0944 0.9743 -0.2044 +vn 0.0688 0.9691 -0.2368 +vn 0.2436 0.9486 -0.2020 +vn 0.1691 0.9517 -0.2563 +vn -0.0562 -0.7019 0.7100 +vn -0.1153 -0.6839 0.7204 +vn 0.1605 -0.7442 0.6484 +vn 0.2118 -0.7486 0.6283 +vn -0.2875 -0.9292 -0.2324 +vn 0.2875 -0.8525 -0.4365 +vn -0.1773 -0.1063 -0.9784 +vn -0.2267 -0.1205 -0.9665 +vn 0.0659 -0.0339 -0.9973 +vn 0.1235 -0.0161 -0.9922 +vn -0.1770 0.9380 -0.2979 +vn -0.1889 0.9350 -0.3003 +vn -0.1210 0.9504 -0.2865 +vn -0.1027 0.9537 -0.2826 +vn 0.2775 0.6655 0.6929 +vn -0.5252 0.3664 0.7680 +vn 0.4301 -0.8883 -0.1612 +vn -0.1383 -0.6437 0.7526 +vn -0.0496 -0.6111 0.7900 +vn 0.1618 -0.5091 0.8454 +vn 0.2577 -0.4511 0.8544 +vn -0.2232 0.3924 0.8923 +vn 0.3150 0.6562 0.6857 +vn -0.3711 0.9251 -0.0805 +vn 0.4280 0.7351 -0.5258 +vn -0.5073 0.0320 -0.8612 +vn 0.4969 -0.2665 -0.8259 +vn 0.3858 -0.4403 -0.8107 +vn 0.4828 -0.2320 -0.8444 +vn 0.6633 0.0227 -0.7480 +vn 0.6004 -0.0432 -0.7985 +vn -0.4081 0.6122 0.6773 +vn 0.4190 0.3799 0.8247 +vn -0.4052 -0.5422 0.7361 +vn 0.2758 -0.7232 0.6332 +vn -0.2036 -0.8543 -0.4782 +vn -0.2029 -0.8544 -0.4784 +vn -0.2074 -0.8542 -0.4769 +vn -0.2090 -0.8541 -0.4763 +vn 0.3057 -0.0006 -0.9521 +vn -0.5152 0.2735 -0.8122 +vn 0.5141 0.8333 -0.2033 +vn -0.6532 0.5587 0.5110 +vn -0.9996 0.0289 0.0004 +vn -0.9974 -0.0390 0.0601 +vn -0.9983 -0.0353 -0.0474 +vn 0.9991 0.0072 0.0421 +vn 0.9978 -0.0238 0.0626 +vn 0.9984 0.0560 0.0099 +vn 0.0543 0.9984 -0.0125 +vn -0.0390 0.9234 0.3818 +vn 0.0326 0.9960 0.0827 +vn -0.0546 0.8944 0.4438 +vn 0.0998 -0.0830 0.9915 +vn -0.0386 -0.5811 0.8129 +vn 0.0393 -0.8948 -0.4447 +vn 0.0582 -0.8657 -0.4972 +vn 0.0538 -0.8727 -0.4852 +vn 0.0358 -0.9000 -0.4344 +vn 0.0069 0.3258 -0.9454 +vn 0.0096 0.3355 -0.9420 +vn 0.0091 0.3342 -0.9425 +vn 0.0062 0.3235 -0.9462 +vn 0.9675 0.0993 0.2324 +vn 0.9895 -0.0489 0.1361 +vn 0.9727 -0.2132 0.0922 +vn 0.9734 0.2088 -0.0940 +vn 0.9911 0.0513 -0.1232 +vn 0.9904 0.1294 0.0486 +vn 0.9795 -0.0657 -0.1902 +vn 0.9935 -0.1053 -0.0444 +vn 0.0478 0.8331 -0.5511 +vn 0.0772 0.8468 -0.5262 +vn 0.1931 0.8876 -0.4183 +vn -0.1994 0.7976 0.5692 +vn 0.2169 0.4458 0.8684 +vn -0.1716 -0.1733 0.9698 +vn 0.1471 -0.8920 0.4274 +vn 0.1599 -0.8955 0.4154 +vn 0.1592 -0.8953 0.4160 +vn 0.1670 -0.8973 0.4086 +vn -0.1803 -0.9354 -0.3041 +vn 0.1859 -0.3369 -0.9230 +vn 0.1053 -0.2688 -0.9574 +vn 0.0854 -0.2513 -0.9641 +vn -0.0199 -0.1582 -0.9872 +vn -0.0897 0.7508 -0.6545 +vn -0.2748 0.5431 -0.7934 +vn -0.4511 0.5487 0.7039 +vn -0.6225 0.5744 0.5316 +vn -0.5657 0.5692 0.5967 +vn -0.7387 0.5693 0.3609 +vn -0.5867 -0.8098 -0.0054 +vn 0.3134 -0.8019 -0.5086 +vn 1.0000 0.0003 0.0005 +vn 1.0000 0.0000 0.0001 +vn 1.0000 0.0002 0.0004 +vn -0.9894 -0.0624 -0.1308 +vn -0.9878 -0.0645 -0.1417 +vn -0.9924 -0.0518 -0.1118 +vn -0.9988 0.0258 -0.0424 +vn -0.9980 0.0628 -0.0098 +vn 0.9981 0.0601 -0.0134 +vn 0.9925 -0.0475 -0.1122 +vn 0.9987 0.0264 -0.0441 +vn 0.9902 -0.0565 -0.1274 +vn 0.9887 -0.0585 -0.1378 +vn -0.9878 -0.0645 -0.1418 +vn -0.9421 -0.0799 -0.3257 +vn -0.9304 -0.0273 -0.3656 +vn -0.9374 -0.0964 -0.3347 +vn -0.9786 -0.1110 -0.1730 +vn -0.9985 0.0121 -0.0540 +vn -0.9980 0.0632 -0.0093 +vn 0.0614 -0.5427 -0.8377 +vn 0.0673 -0.5418 -0.8378 +vn 0.0001 -0.5506 -0.8347 +vn -0.0062 -0.5513 -0.8343 +vn -0.0134 -0.6035 -0.7972 +vn -0.0129 -0.6036 -0.7972 +vn -0.0131 -0.6036 -0.7972 +vn -0.0134 -0.6036 -0.7972 +vn -0.9976 -0.0089 -0.0680 +vn -0.9990 -0.0161 -0.0428 +vn -0.9992 -0.0179 -0.0365 +vn -0.9955 -0.0012 -0.0948 +vn -0.9820 -0.1684 0.0856 +vn -0.9981 -0.0170 0.0587 +vn -0.9987 0.0005 0.0512 +vn -0.9792 -0.1789 0.0957 +vn -0.9825 -0.1849 0.0228 +vn -0.9819 -0.1889 0.0105 +vn -0.9996 -0.0075 -0.0272 +vn -0.9908 -0.1214 -0.0598 +vn -0.9762 -0.2149 -0.0302 +vn -0.9997 0.0016 -0.0234 +vn 1.0000 0.0000 0.0002 +vn 1.0000 0.0001 0.0001 +vn 1.0000 -0.0000 0.0004 +vn 1.0000 -0.0005 -0.0002 +vn 1.0000 0.0003 0.0001 +vn 1.0000 0.0004 0.0001 +vn 1.0000 -0.0004 0.0003 +vn 1.0000 -0.0004 0.0002 +vn 1.0000 -0.0013 0.0001 +vn 1.0000 -0.0005 -0.0001 +vn 1.0000 -0.0003 -0.0002 +vn -0.9748 -0.0112 -0.2230 +vn -0.9812 -0.0208 -0.1918 +vn -0.9827 -0.0233 -0.1836 +vn -0.9663 -0.0005 -0.2576 +vn -0.9746 -0.2113 0.0740 +vn -0.9993 -0.0102 0.0354 +vn -0.9995 0.0003 0.0308 +vn -0.9841 -0.1551 0.0865 +vn -0.9792 -0.2010 0.0279 +vn -0.9472 -0.3189 -0.0325 +vn -0.9798 -0.1596 -0.1205 +vn -0.9832 -0.1757 -0.0506 +vn -0.9699 -0.2070 -0.1284 +vn -0.9812 -0.1531 -0.1177 +vn 0.9658 -0.0237 -0.2582 +vn 0.9844 0.0000 -0.1757 +vn 0.9441 -0.0438 -0.3266 +vn 0.9373 -0.0493 -0.3451 +vn 0.9709 -0.2023 0.1282 +vn 0.9817 -0.1825 0.0538 +vn 0.9508 -0.3079 0.0342 +vn 0.9985 0.0014 0.0540 +vn 0.9979 -0.0186 0.0625 +vn 0.9746 -0.2232 -0.0194 +vn 0.9610 -0.2627 -0.0859 +vn 0.9909 -0.1125 -0.0735 +vn 0.9998 -0.0151 -0.0165 +vn -0.9823 -0.1667 0.0849 +vn -0.9902 -0.1395 0.0097 +vn -0.9906 -0.1362 0.0122 +vn -0.9858 -0.1554 -0.0640 +vn -0.9689 -0.2097 -0.1315 +vn -0.9878 -0.1464 -0.0535 +vn -0.2437 -0.9698 0.0053 +vn -0.9905 -0.1364 -0.0152 +vn 0.9784 -0.1847 -0.0924 +vn 0.9790 -0.1631 -0.1222 +vn 0.9791 -0.1627 -0.1220 +vn 0.9830 -0.1719 0.0647 +vn 0.9764 -0.2046 0.0689 +vn 0.9721 -0.2344 0.0114 +vn 0.9994 0.0025 0.0355 +vn 0.9991 -0.0113 0.0415 +vn 0.9793 -0.2005 -0.0275 +vn 0.9779 -0.1842 -0.0986 +vn -0.9377 -0.3234 0.1269 +vn -0.9985 -0.0296 0.0468 +vn -0.9994 0.0003 0.0335 +vn -0.9371 -0.3129 0.1547 +vn -0.9478 -0.3097 0.0756 +vn -0.9064 -0.4214 0.0295 +vn -0.9494 -0.3116 -0.0391 +vn -0.9987 -0.0298 -0.0417 +vn -0.9384 -0.3092 -0.1541 +vn -0.8839 -0.4448 -0.1443 +vn -0.9996 0.0020 -0.0279 +vn 0.9312 -0.3323 -0.1498 +vn 0.9746 -0.1820 -0.1301 +vn 0.9261 -0.3434 0.1565 +vn 0.9170 -0.3657 0.1593 +vn 0.8484 -0.5292 0.0114 +vn 0.9314 -0.3509 0.0964 +vn 0.9467 -0.3185 -0.0483 +vn 0.9967 -0.0386 0.0711 +vn 0.9525 -0.3038 -0.0221 +vn 0.9256 -0.3479 -0.1490 +vn -0.9871 -0.0031 -0.1601 +vn -0.9884 -0.0056 -0.1519 +vn -0.9887 -0.0062 -0.1498 +vn -0.9855 -0.0003 -0.1697 +vn -0.9999 -0.0110 0.0062 +vn -0.9862 -0.1609 0.0400 +vn -0.9765 -0.2154 -0.0067 +vn -0.9993 -0.0345 -0.0133 +vn -0.9998 0.0113 -0.0151 +vn 0.9604 -0.2638 -0.0895 +vn 0.9993 -0.0084 -0.0369 +vn 0.9995 0.0038 -0.0316 +vn 0.9696 -0.2118 0.1224 +vn 0.9742 -0.2175 0.0599 +vn 0.9534 -0.3003 0.0306 +vn 0.9987 0.0035 0.0503 +vn 0.9981 -0.0159 0.0589 +vn 0.9761 -0.2160 -0.0240 +vn 0.9823 -0.1627 -0.0925 +vn -0.9958 0.0055 -0.0912 +vn -0.9940 0.0107 -0.1089 +vn -0.9935 0.0120 -0.1134 +vn -0.9974 -0.0003 -0.0715 +vn -0.9676 -0.2521 -0.0167 +vn -0.9995 -0.0086 -0.0312 +vn -0.9882 -0.1391 -0.0644 +vn -0.9620 -0.2723 -0.0213 +vn -0.9996 0.0019 -0.0268 +vn 0.9955 0.0239 -0.0922 +vn 0.9989 0.0454 -0.0151 +vn 0.9987 0.0509 0.0043 +vn 1.0000 -0.0078 -0.0040 +vn 1.0000 -0.0051 0.0054 +vn 0.9968 -0.0721 0.0347 +vn 0.9539 -0.2987 0.0304 +vn 0.9929 -0.1157 -0.0278 +vn -0.9854 -0.0036 -0.1701 +vn -0.9872 -0.0068 -0.1591 +vn -0.9877 -0.0076 -0.1564 +vn -0.9835 -0.0004 -0.1809 +vn -1.0000 -0.0057 0.0000 +vn -0.9997 -0.0059 -0.0224 +vn -0.9940 -0.0991 -0.0467 +vn -0.9681 -0.2504 -0.0089 +vn -0.9998 0.0019 -0.0192 +vn 0.9845 0.0002 -0.1755 +vn 0.9844 0.0000 -0.1759 +vn 1.0000 -0.0059 0.0012 +vn 0.9911 -0.1332 -0.0014 +vn 0.9705 -0.2296 -0.0734 +vn 0.9918 -0.1076 -0.0691 +vn 0.9998 -0.0138 -0.0151 +vn -0.0311 -0.8075 -0.5891 +vn 0.0063 -0.8030 -0.5960 +vn -0.2379 -0.8106 -0.5351 +vn -0.2576 -0.8089 -0.5284 +vn 0.4393 -0.8523 -0.2841 +vn -0.5036 -0.8586 -0.0957 +vn 0.5036 -0.8586 0.0957 +vn -0.4393 -0.8523 0.2841 +vn 0.2374 -0.8107 0.5351 +vn 0.2573 -0.8090 0.5285 +vn 0.0311 -0.8075 0.5891 +vn -0.0063 -0.8030 0.5960 +vn 0.0139 -0.8029 -0.5959 +vn -0.5054 -0.7224 -0.4719 +vn 0.7324 -0.6459 -0.2153 +vn -0.7886 -0.6111 -0.0681 +vn 0.7886 -0.6111 0.0681 +vn -0.7324 -0.6459 0.2153 +vn 0.5055 -0.7224 0.4719 +vn -0.0139 -0.8029 0.5959 +vn -0.5052 -0.7225 -0.4720 +vn 0.5056 -0.7223 0.4719 +vn 0.0140 -0.8079 -0.5891 +vn -0.0140 -0.8079 0.5891 +vn 0.0143 -0.8031 -0.5957 +vn 0.7326 -0.6457 -0.2152 +vn 0.5055 -0.7223 0.4719 +vn -0.5056 -0.7223 -0.4719 +vn 0.5054 -0.7224 0.4719 +vn -0.5055 -0.7224 -0.4719 +vn 0.5057 -0.7223 0.4718 +vn 0.0172 0.0054 -0.9998 +vn 0.0305 0.0107 -0.9995 +vn -0.0038 -0.2210 -0.9753 +vn -0.0143 -0.2419 -0.9702 +vn -0.0053 -0.9597 -0.2809 +vn -0.0080 -0.9435 -0.3313 +vn -0.0174 -0.9739 -0.2264 +vn -0.0244 -0.8376 -0.5457 +vn -0.0257 -0.7462 -0.6653 +vn -0.0144 -0.9220 -0.3869 +vn 0.0020 -0.7759 -0.6308 +vn -0.0008 -0.6925 -0.7215 +vn -1.0000 0.0084 0.0030 +vn -0.9877 -0.0526 0.1475 +vn -0.9917 -0.0661 0.1104 +vn -0.9879 -0.0270 0.1526 +vn -0.9626 0.0314 0.2690 +vn -0.9995 0.0236 0.0186 +vn -0.9996 -0.0293 0.0062 +vn -0.9994 -0.0327 0.0140 +vn 0.9999 0.0116 0.0089 +vn 1.0000 -0.0001 -0.0003 +vn 0.9974 0.0568 0.0438 +vn 0.9966 0.0653 0.0504 +vn 0.8573 0.0511 0.5123 +vn 0.8315 0.0615 0.5521 +vn 0.9934 -0.0420 0.1068 +vn 0.9999 -0.0060 0.0113 +vn 1.0000 -0.0003 0.0003 +vn 1.0000 -0.0001 0.0001 +vn 1.0000 -0.0002 0.0002 +vn -0.0055 -0.5940 0.8044 +vn 0.0057 -0.5960 0.8030 +vn -0.0132 -0.4985 0.8668 +vn 0.0289 -0.4079 0.9126 +vn -0.0275 -0.1651 0.9859 +vn 0.0493 -0.0161 0.9987 +vn -0.1476 0.1393 0.9792 +vn -0.1619 0.1404 0.9768 +vn 0.1271 0.5437 0.8296 +vn 0.1368 0.5418 0.8293 +vn 0.0061 0.5631 0.8264 +vn -0.0076 0.5647 0.8252 +vn -0.9845 0.1073 0.1385 +vn -0.9848 0.1067 0.1371 +vn -0.9770 0.0887 0.1938 +vn -0.9254 -0.1241 0.3581 +vn -0.9387 -0.1499 0.3103 +vn -0.9534 -0.0524 0.2972 +vn -0.9043 0.0256 0.4262 +vn -0.9669 0.0774 0.2432 +vn -0.9800 0.1023 0.1707 +vn -0.9995 -0.0295 0.0067 +vn -0.9986 -0.0412 0.0332 +vn 0.9808 0.1157 0.1572 +vn 0.9780 0.0948 0.1857 +vn 0.9811 0.1151 0.1558 +vn 0.9782 0.0973 0.1833 +vn 0.9681 0.0777 0.2381 +vn 0.9031 0.0275 0.4285 +vn 0.9445 -0.0452 0.3253 +vn 0.8804 -0.1679 0.4436 +vn 0.9402 -0.1875 0.2845 +vn 0.8533 -0.2912 0.4326 +vn 0.9988 0.0490 0.0076 +vn 0.0129 -0.5891 0.8079 +vn -0.9998 0.0085 0.0193 +vn -0.9774 0.0753 0.1977 +vn -0.9255 -0.1240 0.3578 +vn -0.9389 -0.1498 0.3100 +vn -0.9757 0.0841 0.2024 +vn -0.9986 -0.0410 0.0329 +vn 0.9997 0.0089 0.0206 +vn 0.9800 0.0725 0.1853 +vn 0.9776 0.0776 0.1956 +vn 0.8802 -0.1680 0.4439 +vn 0.8108 -0.3492 0.4697 +vn -0.0175 0.5892 0.8078 +vn -0.9998 0.0080 0.0181 +vn -0.9777 0.0748 0.1964 +vn 0.0129 -0.5892 0.8079 +vn -0.0182 0.5892 0.8078 +vn -0.9188 -0.1298 0.3729 +vn -0.9633 -0.1295 0.2353 +vn -0.9614 -0.1321 0.2413 +vn 0.6430 -0.5151 0.5667 +vn -0.0177 0.5892 0.8078 +vn -0.9998 0.0084 0.0190 +vn -0.9775 0.0751 0.1973 +vn 0.8812 -0.1605 0.4447 +vn 0.9303 -0.1882 0.3148 +vn 0.9812 -0.0839 0.1736 +vn 0.9888 -0.0491 0.1411 +vn -0.9816 0.1132 0.1535 +vn -0.9816 0.1134 0.1539 +vn -0.9765 0.0899 0.1961 +vn -0.9865 -0.0629 0.1512 +vn -0.9858 -0.0636 0.1557 +vn -0.9703 -0.0748 0.2299 +vn -0.9628 -0.0623 0.2630 +vn -0.8920 0.0337 0.4508 +vn -0.9559 0.0935 0.2785 +vn -0.9805 0.1010 0.1684 +vn 0.8193 -0.3433 0.4593 +vn -0.5096 -0.5253 0.6814 +vn 0.0194 -0.9998 -0.0101 +vn -0.0122 -0.9939 0.1098 +vn 0.0073 -0.9386 0.3449 +vn -0.0057 -0.9148 0.4040 +vn -0.0045 -0.8434 0.5373 +vn -0.0179 -0.9716 0.2358 +vn 0.4632 -0.8590 0.2180 +vn 0.1981 -0.9501 0.2411 +vn 0.3484 -0.9086 0.2304 +vn 0.5199 -0.6597 0.5426 +vn -0.7607 -0.5612 0.3261 +vn -0.8804 -0.2406 0.4086 +vn 0.6169 -0.3022 0.7267 +vn -0.6364 -0.0744 0.7678 +vn 0.6040 0.1710 0.7784 +vn -0.5693 0.4378 0.6959 +vn 0.4360 0.6500 0.6224 +vn 0.3570 0.5540 0.7521 +vn 0.4007 0.6074 0.6859 +vn 0.6936 0.6822 0.2314 +vn -0.7589 0.5610 0.3307 +vn 0.4709 0.6908 0.5487 +vn -0.6521 0.7572 0.0384 +vn 0.6542 0.6522 -0.3830 +vn -0.6255 0.7363 -0.2581 +vn 0.6808 0.7293 -0.0689 +vn -0.1854 0.6991 -0.6906 +vn -0.4883 0.6482 -0.5842 +vn -0.4196 0.6804 -0.6008 +vn -0.6294 0.5991 -0.4949 +vn 0.3509 0.4516 -0.8203 +vn -0.0781 0.0074 -0.9969 +vn -0.2075 0.1519 -0.9664 +vn -0.3162 0.1547 -0.9360 +vn -0.5878 -0.1482 -0.7953 +vn 0.5402 -0.0414 -0.8405 +vn 0.7101 -0.3405 -0.6162 +vn -0.1079 -0.7487 -0.6540 +vn -0.0958 -0.7450 -0.6602 +vn -0.1850 -0.7355 -0.6518 +vn -0.7247 -0.4662 -0.5074 +vn 0.7032 -0.6668 0.2466 +vn -0.6490 -0.7601 -0.0322 +vn 0.9456 -0.3173 -0.0712 +vn 0.9482 -0.2801 -0.1500 +vn 0.8028 -0.5259 -0.2810 +vn 0.3767 -0.7225 0.5798 +vn 0.4369 -0.6778 0.5914 +vn -0.2898 0.2355 0.9276 +vn 0.2397 0.5833 0.7761 +vn 0.2366 0.5839 0.7766 +vn 0.0806 0.6340 0.7691 +vn 0.1926 0.6157 0.7641 +vn 0.0425 0.6072 0.7934 +vn 0.3737 0.7836 0.4962 +vn -0.0461 0.9918 0.1191 +vn -0.0613 0.8363 -0.5449 +vn -0.0253 0.7488 -0.6623 +vn -0.0074 0.7455 -0.6665 +vn 0.0086 0.6413 -0.7672 +vn -0.0430 0.6298 -0.7755 +vn 0.1554 0.1305 -0.9792 +vn 0.0627 0.2066 -0.9764 +vn 0.0650 0.1000 -0.9929 +vn -0.0297 0.0778 -0.9965 +vn 0.4080 -0.0407 -0.9121 +vn 0.4222 -0.0419 -0.9056 +vn -0.4879 -0.3679 -0.7916 +vn 0.1085 -0.6436 -0.7576 +vn 0.2628 -0.4389 -0.8593 +vn 0.0753 -0.6936 -0.7164 +vn 0.1304 -0.8049 -0.5788 +vn 0.1213 -0.7957 -0.5934 +vn 0.3808 -0.7266 0.5719 +vn -0.8252 -0.4921 0.2772 +vn 0.7833 -0.6007 0.1598 +vn -0.8475 -0.5296 -0.0358 +vn 0.2590 -0.8376 -0.4810 +vn -0.0900 -0.7568 0.6474 +vn -0.3089 -0.7360 0.6024 +vn -0.1974 -0.7387 0.6445 +vn 0.2665 0.5914 0.7610 +vn 0.2572 0.5935 0.7626 +vn 0.4345 0.6291 0.6446 +vn 0.4966 0.5302 0.6872 +vn 0.4726 0.6756 0.5659 +vn 0.5041 0.6888 0.5210 +vn 0.3126 0.7256 -0.6130 +vn 0.4959 0.7120 -0.4972 +vn 0.1878 0.6392 -0.7458 +vn 0.1464 0.6072 -0.7810 +vn 0.2095 0.3155 -0.9255 +vn 0.0542 0.2143 -0.9753 +vn -0.0099 0.2295 -0.9733 +vn 0.4135 -0.0362 -0.9098 +vn 0.4316 -0.0374 -0.9013 +vn 0.1155 -0.6622 -0.7404 +vn 0.0610 -0.7049 -0.7067 +vn 0.0285 -0.8110 -0.5844 +vn 0.0067 -0.8010 -0.5986 +vn -0.3617 -0.7325 0.5767 +vn 0.7391 -0.5831 0.3371 +vn -0.7817 -0.6043 0.1545 +vn 0.5201 -0.8465 -0.1140 +vn 0.0467 -0.8506 -0.5238 +vn 0.0476 -0.8506 -0.5237 +vn 0.2799 -0.7335 0.6194 +vn 0.4425 -0.6829 0.5813 +vn 0.4963 0.5304 0.6873 +vn 0.4219 0.7286 -0.5395 +vn 0.1715 0.6427 -0.7467 +vn 0.3296 0.7344 -0.5932 +vn 0.1106 0.6013 -0.7913 +vn 0.2067 0.3277 -0.9219 +vn 0.0707 0.2294 -0.9708 +vn 0.0020 0.3599 -0.9330 +vn 0.4528 -0.0270 -0.8912 +vn 0.2626 -0.4389 -0.8593 +vn 0.0282 -0.8103 -0.5853 +vn 0.0338 -0.8049 -0.5925 +vn 0.3958 -0.7417 0.5415 +vn 0.0586 -0.8495 -0.5244 +vn 0.2279 -0.7643 0.6032 +vn 0.2322 -0.7751 0.5876 +vn 0.0923 -0.7954 0.5990 +vn 0.0000 -0.8076 0.5897 +vn 0.7186 -0.3993 0.5694 +vn 0.2276 0.5794 0.7826 +vn 0.2272 0.5795 0.7827 +vn 0.2377 0.6516 0.7203 +vn 0.2158 0.6079 0.7641 +vn 0.4399 0.7016 0.5606 +vn 0.4815 0.6999 0.5275 +vn 0.1711 0.6427 -0.7468 +vn 0.3297 0.7344 -0.5932 +vn 0.1103 0.6016 -0.7912 +vn 0.2070 0.3280 -0.9217 +vn 0.0001 0.3637 -0.9315 +vn -0.4882 -0.3679 -0.7914 +vn 0.1175 -0.6669 -0.7358 +vn 0.0567 -0.7095 -0.7024 +vn 0.0260 -0.8069 -0.5902 +vn 0.3549 -0.7603 0.5441 +vn 0.4088 -0.7068 0.5773 +vn -0.0999 0.8150 -0.5707 +vn -0.0308 0.7573 -0.6523 +vn -0.0844 0.7440 -0.6628 +vn -0.0996 0.6319 -0.7686 +vn 0.0103 0.6233 -0.7819 +vn 0.1986 0.3217 -0.9258 +vn 0.0686 0.2264 -0.9716 +vn 0.1169 -0.6695 -0.7336 +vn -0.0756 -0.7867 -0.6127 +vn 0.3710 -0.7773 0.5081 +vn 0.0295 -0.8073 0.5894 +vn 0.1055 -0.7944 0.5981 +vn 0.2337 0.6512 0.7221 +vn 0.2155 0.6080 0.7642 +vn 0.4067 0.7015 0.5852 +vn 0.4441 0.7017 0.5571 +vn -0.4508 0.7481 0.4870 +vn 0.7246 0.6526 0.2213 +vn -0.7223 0.6855 0.0912 +vn 0.7271 0.6821 -0.0773 +vn -0.6300 0.7517 -0.1950 +vn 0.4857 0.7177 -0.4990 +vn -0.2412 0.7666 -0.5951 +vn -0.2604 0.6398 -0.7231 +vn -0.2586 0.6553 -0.7097 +vn -0.2702 0.5113 -0.8158 +vn 0.2069 0.3257 -0.9226 +vn 0.3865 0.4637 -0.7972 +vn -0.0229 0.1493 -0.9885 +vn -0.0113 0.3814 -0.9243 +vn 0.1087 -0.6497 -0.7524 +vn 0.1089 -0.6898 -0.7158 +vn 0.1125 -0.8076 -0.5788 +vn 0.1341 -0.7951 -0.5914 +vn 0.2597 -0.8385 -0.4791 +vn 0.0085 0.9958 0.0912 +vn -0.5286 0.8061 0.2662 +vn -0.5136 0.8154 0.2671 +vn -0.2037 -0.7840 -0.5864 +vn -0.3072 -0.7735 -0.5544 +vn 0.3192 -0.8786 -0.3552 +vn -0.0106 -0.5334 0.8458 +vn -0.0247 -0.2279 0.9734 +vn -0.0135 -0.3733 0.9276 +vn 0.0059 -0.3461 0.9382 +vn -0.0111 -0.0211 0.9997 +vn -0.0012 -0.0492 0.9988 +vn 0.0063 0.3034 0.9528 +vn 0.0063 0.3337 0.9426 +vn -0.0226 0.2406 0.9704 +vn -0.0091 0.5359 0.8442 +vn 0.0139 0.2120 -0.9772 +vn 0.0117 -0.3043 -0.9525 +vn 0.0030 0.2945 -0.9557 +vn 0.0037 -0.2033 -0.9791 +vn -0.0007 -0.6336 0.7736 +vn -0.0010 -0.6331 0.7740 +vn -0.0009 -0.6334 0.7738 +vn -0.0005 -0.6339 0.7734 +vn 0.0954 -0.9835 -0.1535 +vn 0.5799 -0.7897 0.2003 +vn -0.3577 -0.7185 0.5965 +vn 0.2247 0.0685 0.9720 +vn 0.1641 0.0513 0.9851 +vn 0.0421 0.0165 0.9990 +vn 0.0011 0.0049 1.0000 +vn -0.0378 -0.9898 -0.1376 +vn 0.5023 -0.8460 0.1787 +vn -0.2250 -0.7573 0.6131 +vn 0.0571 0.0253 0.9980 +vn 0.0441 0.0216 0.9988 +vn 0.0110 0.0122 0.9999 +vn 0.0009 0.0092 1.0000 +vn -0.0387 -0.9873 -0.1539 +vn -0.0133 -0.9896 -0.1433 +vn 0.0138 -0.9912 -0.1319 +vn 0.0308 -0.9917 -0.1247 +vn -0.2160 0.0687 0.9740 +vn -0.1730 0.0876 0.9810 +vn -0.0521 0.1385 0.9890 +vn 0.0039 0.1612 0.9869 +vn 0.6240 -0.7645 0.1615 +vn -0.2362 -0.7848 0.5730 +vn -0.3694 -0.7149 0.5936 +vn 0.2109 0.0688 0.9751 +vn 0.1536 0.0526 0.9867 +vn 0.0393 0.0203 0.9990 +vn 0.6393 -0.7499 0.1701 +vn -0.1839 -0.7939 0.5796 +vn 0.0546 0.0253 0.9982 +vn 0.0430 0.0220 0.9988 +vn 0.0107 0.0127 0.9999 +vn 0.0008 0.0096 1.0000 +vn -0.0176 -0.9885 -0.1500 +vn 0.1677 -0.9856 0.0216 +vn 0.2337 -0.9686 0.0850 +vn 0.3444 -0.9186 0.1940 +vn -0.2148 -0.7824 0.5845 +vn -0.1094 -0.7963 0.5949 +vn -0.3313 -0.7537 0.5675 +vn 0.0260 0.0252 0.9993 +vn 0.0158 0.0190 0.9997 +vn 0.0095 0.0151 0.9998 +vn 0.0005 0.0091 1.0000 +vn -0.0039 0.1612 -0.9869 +vn 0.0362 0.1445 -0.9888 +vn 0.1222 0.1093 -0.9865 +vn 0.1559 0.0950 -0.9832 +vn 0.1530 -0.9646 0.2147 +vn 0.1027 -0.9755 0.1948 +vn 0.0376 -0.9849 0.1689 +vn -0.0030 -0.9884 0.1516 +vn -0.0032 0.1201 -0.9928 +vn 0.0278 0.1088 -0.9937 +vn 0.1045 0.0802 -0.9913 +vn 0.1321 0.0698 -0.9888 +vn 0.1446 -0.9658 0.2150 +vn 0.0976 -0.9757 0.1961 +vn 0.0362 -0.9846 0.1710 +vn -0.0027 -0.9880 0.1546 +vn 0.1043 0.0803 -0.9913 +vn 0.1322 0.0698 -0.9888 +vn -0.0024 0.0789 -0.9969 +vn 0.0028 0.0762 -0.9971 +vn 0.0108 0.0721 -0.9973 +vn 0.0146 0.0702 -0.9974 +vn 0.1447 -0.9658 0.2150 +vn 0.0978 -0.9757 0.1959 +vn 0.0360 -0.9847 0.1705 +vn -0.0029 -0.9881 0.1541 +vn -0.0015 0.0785 -0.9969 +vn -0.0005 0.0779 -0.9970 +vn 0.0000 0.0777 -0.9970 +vn 0.1449 -0.9658 0.2150 +vn -0.0028 -0.9880 0.1544 +vn 0.0436 0.1420 -0.9889 +vn 0.1133 0.1131 -0.9871 +vn 0.1429 0.1005 -0.9846 +vn -0.0014 0.1155 -0.9933 +vn 0.0232 0.0960 -0.9951 +vn 0.0320 0.0890 -0.9955 +vn 0.0557 0.0701 -0.9960 +vn -0.0840 -0.7812 -0.6186 +vn 0.0930 -0.9661 0.2409 +vn 0.0421 -0.9800 0.1943 +vn 0.0446 -0.9795 0.1967 +vn -0.0013 -0.9880 0.1546 +vn -0.4471 0.0590 -0.8925 +vn 0.1951 -0.5168 -0.8336 +vn -0.6274 0.0666 -0.7758 +vn 0.5919 -0.3886 -0.7061 +vn 0.5917 -0.3887 -0.7063 +vn -0.6277 0.0666 -0.7756 +vn -0.0157 0.1406 -0.9899 +vn -0.0165 0.1410 -0.9899 +vn -0.0201 0.1420 -0.9897 +vn -0.0214 0.1424 -0.9896 +vn 0.0607 -0.4542 -0.8888 +vn 0.0497 -0.4517 -0.8908 +vn -0.0177 -0.0295 0.9994 +vn -0.0050 -0.0175 0.9998 +vn 0.0149 -0.9994 0.0318 +vn 0.0078 -0.9997 0.0248 +vn 0.0021 -0.6155 -0.7881 +vn 0.0114 -0.6230 -0.7821 +vn 0.0043 -0.9979 -0.0648 +vn -0.0077 -0.9972 -0.0749 +vn -0.7414 -0.0391 0.6699 +vn -0.7908 -0.2673 -0.5507 +vn 0.0006 0.9879 0.1551 +vn 0.0718 0.9972 -0.0213 +vn -0.6519 0.6738 -0.3478 +vn 0.2281 0.8309 0.5076 +vn -0.5384 -0.0309 -0.8421 +vn 0.0776 0.6913 0.7184 +vn 0.0942 0.6762 0.7307 +vn -0.2355 0.7744 0.5872 +vn -0.2951 0.7774 0.5555 +vn 0.1818 0.6995 -0.6911 +vn -0.4229 -0.7163 0.5550 +vn -0.4252 -0.7179 0.5512 +vn -0.4502 -0.8614 0.2352 +vn 0.0088 -0.9997 0.0242 +vn -0.1888 -0.9625 0.1949 +vn -0.6903 -0.7128 -0.1243 +vn -0.3950 0.2521 0.8834 +vn 0.3115 0.4640 0.8292 +vn 0.1660 0.6705 0.7231 +vn -0.3552 0.5605 -0.7482 +vn 0.4408 -0.5201 0.7316 +vn -0.6219 0.2604 -0.7385 +vn 0.4367 0.4041 -0.8037 +vn 0.1749 0.0357 -0.9839 +vn 0.1675 -0.2969 -0.9401 +vn 0.6481 -0.4849 -0.5872 +vn 0.1035 -0.8528 -0.5119 +vn 0.3935 -0.8694 -0.2988 +vn 0.0996 -0.9933 -0.0582 +vn -0.4932 -0.8402 0.2255 +vn 0.3432 -0.7888 0.5098 +vn -0.3707 0.5480 0.7498 +vn 0.2009 0.9309 -0.3049 +vn 0.3248 -0.2253 0.9186 +vn -0.4800 0.8745 -0.0696 +vn -0.5417 -0.4203 0.7279 +vn -0.1250 0.8491 -0.5133 +vn 0.7481 0.3989 -0.5303 +vn -0.9991 -0.0371 -0.0202 +vn -0.9990 -0.0307 -0.0321 +vn -0.9990 -0.0344 -0.0277 +vn -0.9999 0.0048 -0.0122 +vn -0.9885 0.0553 -0.1406 +vn -0.9833 0.0665 -0.1692 +vn 0.9785 0.0761 -0.1918 +vn 0.9999 0.0058 -0.0147 +vn 0.9662 0.0951 -0.2396 +vn -0.9882 0.0803 -0.1304 +vn -0.9894 0.0733 -0.1257 +vn -0.9883 0.0742 -0.1335 +vn -0.9874 0.0755 -0.1392 +vn -0.9873 0.0851 -0.1342 +vn 0.9771 0.0879 -0.1939 +vn 0.9884 0.0788 -0.1298 +vn 0.9761 0.1364 -0.1691 +vn 0.9675 0.0974 -0.2332 +vn 0.9669 0.1669 -0.1930 +vn -0.9873 0.0849 -0.1340 +vn -0.9873 0.0755 -0.1396 +vn 0.9773 0.0782 -0.1969 +vn 0.9999 0.0061 -0.0153 +vn -0.9999 0.0157 0.0024 +vn -0.9996 0.0234 -0.0170 +vn -0.9692 0.1048 -0.2229 +vn -0.9571 0.1208 -0.2635 +vn 0.1094 0.5437 -0.8321 +vn 0.1462 0.5454 -0.8253 +vn -0.2766 0.4807 -0.8321 +vn -0.3061 0.4724 -0.8265 +vn -0.2313 0.4743 -0.8494 +vn -0.2310 0.4744 -0.8495 +vn 1.0000 -0.0003 0.0000 +vn 1.0000 0.0003 -0.0001 +vn -0.9809 0.1633 0.1055 +vn -0.9989 0.0009 0.0466 +vn -0.9984 0.0174 0.0534 +vn -0.9829 0.1745 0.0583 +vn -0.9558 0.2928 0.0276 +vn -0.9793 0.2025 -0.0078 +vn -0.9701 0.2414 -0.0259 +vn -0.9677 0.2172 -0.1281 +vn -0.9625 0.2324 -0.1398 +vn -0.9986 0.0359 -0.0392 +vn -0.9985 0.0146 0.0532 +vn -0.9967 0.0458 0.0664 +vn -0.9420 0.3025 0.1457 +vn -0.9412 0.3076 -0.1397 +vn -0.9960 0.0501 -0.0744 +vn -0.9979 0.0201 -0.0618 +vn -0.9329 0.3274 0.1501 +vn -0.9291 0.3613 0.0795 +vn -0.9286 0.3632 0.0764 +vn -0.9289 0.3675 -0.0464 +vn -0.9293 0.3669 -0.0424 +vn -0.9334 0.3297 -0.1418 +vn 0.9967 0.0350 0.0732 +vn 0.9984 -0.0069 0.0560 +vn 0.9346 0.3216 0.1522 +vn 0.9521 0.2799 -0.1229 +vn 0.9995 -0.0037 -0.0327 +vn 0.9984 0.0312 -0.0471 +vn 0.9447 0.3010 -0.1300 +vn 0.9297 0.3654 -0.0456 +vn 0.9289 0.3678 -0.0426 +vn 0.9286 0.3631 0.0772 +vn 0.9286 0.3636 0.0740 +vn 0.9257 0.3450 0.1552 +vn -0.9411 0.3078 -0.1399 +vn -0.9428 0.3013 0.1427 +vn -0.9974 0.0373 0.0615 +vn -0.9329 0.3281 0.1481 +vn -0.9335 0.3293 -0.1418 +vn 0.9349 0.3242 -0.1445 +vn 0.9987 -0.0057 -0.0502 +vn 0.9971 0.0361 -0.0673 +vn 0.9261 0.3472 -0.1479 +vn 0.9289 0.3676 -0.0461 +vn 0.9286 0.3630 0.0771 +vn -0.9332 0.3384 -0.1214 +vn -0.9983 0.0359 -0.0469 +vn -0.9993 0.0118 -0.0361 +vn -0.9431 0.3028 0.1376 +vn -0.9345 0.3266 0.1418 +vn -0.9341 0.3524 0.0574 +vn -0.9412 0.3274 0.0837 +vn -0.9151 0.4017 -0.0357 +vn -0.9099 0.4095 -0.0664 +vn -0.9444 0.2952 -0.1445 +vn 0.9348 0.3245 -0.1447 +vn -0.9998 -0.0006 0.0175 +vn -0.9672 0.2328 0.1015 +vn -0.9724 0.2139 0.0933 +vn -0.9993 0.0343 0.0122 +vn -0.9811 0.1932 -0.0072 +vn -0.9701 0.2414 -0.0260 +vn -0.9720 0.2156 -0.0937 +vn -0.9766 0.1790 -0.1191 +vn -0.9992 0.0266 -0.0290 +vn 0.9978 0.0150 0.0651 +vn 0.9780 0.1861 0.0946 +vn 0.9728 0.2031 -0.1118 +vn 0.9988 -0.0059 -0.0483 +vn 0.9983 0.0139 -0.0570 +vn 0.9748 0.2160 -0.0564 +vn 0.9716 0.2350 -0.0263 +vn 0.9706 0.2401 0.0153 +vn 0.9691 0.2377 0.0662 +vn 0.9670 0.2287 0.1125 +vn -1.0000 -0.0001 0.0000 +vn -1.0000 -0.0003 0.0002 +vn -1.0000 -0.0004 0.0003 +vn 0.9915 0.1183 0.0540 +vn 0.9895 0.1316 0.0600 +vn 0.9999 0.0114 0.0054 +vn 0.9885 0.1297 -0.0784 +vn 0.9995 -0.0040 -0.0324 +vn 0.9992 0.0094 -0.0381 +vn 0.9857 0.1597 -0.0541 +vn 0.9436 0.3292 -0.0353 +vn 0.9943 0.1041 0.0226 +vn -0.0680 0.8241 0.5623 +vn -0.0601 0.8239 0.5635 +vn -0.1371 0.8240 0.5497 +vn -0.1427 0.8238 0.5486 +vn 0.1476 0.9792 0.1393 +vn 0.1619 0.9768 0.1404 +vn -0.0493 0.9987 -0.0161 +vn 0.0276 0.9859 -0.1651 +vn -0.0290 0.9126 -0.4079 +vn 0.0093 0.8664 -0.4992 +vn -0.0422 0.7976 -0.6017 +vn -0.0614 0.7942 -0.6045 +vn 0.0139 0.8029 0.5959 +vn -0.5057 0.7222 0.4718 +vn 0.7324 0.6459 0.2153 +vn -0.7886 0.6111 0.0681 +vn 0.7886 0.6111 -0.0681 +vn -0.7324 0.6459 -0.2153 +vn 0.5057 0.7223 -0.4718 +vn -0.0125 0.8029 -0.5959 +vn -0.1344 0.7969 0.5890 +vn -0.1338 0.7972 -0.5886 +vn 0.0136 0.8080 0.5891 +vn -0.1337 0.7973 -0.5886 +vn -0.1334 0.7973 -0.5886 +vn 0.0137 0.8029 0.5959 +vn 0.5057 0.7222 -0.4718 +vn -0.0137 0.8030 -0.5959 +vn -0.1644 0.7939 0.5854 +vn -0.1342 0.7957 0.5906 +vn -0.5287 0.7055 0.4719 +vn -0.5413 0.6998 0.4660 +vn -0.0158 0.9390 -0.3436 +vn -0.0307 0.9686 -0.2468 +vn -0.0299 0.9841 -0.1750 +vn 0.0194 0.9684 -0.2488 +vn -0.0139 0.9235 -0.3833 +vn -0.0048 0.7415 -0.6710 +vn -0.0025 0.7492 -0.6623 +vn 0.0090 0.6989 -0.7152 +vn -0.0063 0.8400 0.5426 +vn -0.0231 0.9703 0.2408 +vn -0.0153 0.9291 0.3696 +vn 0.0007 0.9054 0.4245 +vn 0.0029 0.9811 0.1932 +vn 0.0107 0.9946 0.1033 +vn 0.0172 0.9980 -0.0616 +vn 0.0032 0.8876 0.4606 +vn -0.0447 0.9657 0.2559 +vn -0.0629 0.7929 0.6061 +vn 0.0476 0.5990 0.7993 +vn -0.1287 -0.1487 0.9805 +vn 0.5246 0.2246 0.8212 +vn -0.1680 0.6724 0.7208 +vn 0.3629 0.9315 -0.0249 +vn 0.0029 -0.1229 0.9924 +vn -0.0027 -0.1252 0.9921 +vn -0.0104 -0.1279 0.9917 +vn -0.0142 -0.1296 0.9915 +vn -0.0566 0.6021 0.7964 +vn -0.2412 0.6599 0.7116 +vn 0.3510 0.9355 0.0409 +vn 0.4134 0.9082 0.0655 +vn 0.0797 0.9950 -0.0607 +vn -0.0237 0.9950 -0.0972 +vn 0.0901 -0.0895 0.9919 +vn 0.3018 -0.0041 0.9534 +vn 0.3537 0.0179 0.9352 +vn -0.3798 0.6290 0.6784 +vn 0.6011 0.7863 0.1430 +vn -0.0234 0.9950 -0.0973 +vn 0.0905 -0.0896 0.9919 +vn 0.3016 -0.0039 0.9534 +vn 0.3535 0.0182 0.9352 +vn -0.1313 -0.1219 0.9838 +vn 0.6463 0.2016 0.7360 +vn -0.1686 0.6702 0.7228 +vn 0.2769 0.9608 0.0126 +vn 0.3328 0.9424 0.0338 +vn 0.0578 0.9960 -0.0686 +vn 0.6842 0.7277 0.0486 +vn -0.0599 -0.1220 0.9907 +vn 0.3597 0.2465 0.8999 +vn -0.0729 0.6763 0.7330 +vn 0.0973 0.9952 -0.0123 +vn 0.1579 0.9868 0.0354 +vn 0.0605 0.9974 -0.0404 +vn -0.0106 0.9953 -0.0960 +vn 0.0900 0.9938 0.0657 +vn 0.0557 0.9955 0.0769 +vn -0.0643 0.9912 0.1153 +vn -0.1151 0.9847 0.1310 +vn -0.0527 -0.1214 -0.9912 +vn -0.0413 -0.1261 -0.9912 +vn -0.0152 -0.1366 -0.9905 +vn -0.0025 -0.1413 -0.9900 +vn 0.0680 0.9950 0.0729 +vn -0.0130 0.9950 0.0991 +vn -0.0414 0.9933 0.1080 +vn -0.0519 -0.1211 -0.9913 +vn -0.0406 -0.1260 -0.9912 +vn -0.0150 -0.1363 -0.9906 +vn -0.0026 -0.1411 -0.9900 +vn 0.3796 0.9250 0.0158 +vn -0.0766 0.6913 -0.7185 +vn 0.6897 0.2243 -0.6885 +vn -0.1152 -0.1127 -0.9869 +vn -0.0763 0.6913 -0.7185 +vn -0.1149 -0.1128 -0.9870 +vn -0.1151 -0.1126 -0.9869 +vn -0.1151 -0.1126 -0.9870 +vn 0.0650 0.9978 -0.0156 +vn 0.0001 1.0000 0.0013 +vn -0.2560 0.9643 0.0678 +vn -0.3807 0.9193 0.1001 +vn 0.3974 0.6412 -0.6565 +vn -0.6562 0.1712 -0.7349 +vn 0.0383 -0.1410 -0.9893 +vn -0.0740 0.9907 0.1143 +vn 0.0307 0.9986 0.0425 +vn 0.0818 0.9966 0.0076 +vn 0.1628 0.9855 -0.0488 +vn -0.0387 0.6009 -0.7984 +vn 0.3756 0.2872 -0.8812 +vn -0.0470 -0.2376 -0.9702 +vn -0.2248 0.6000 -0.7678 +vn 0.0409 -0.3031 -0.9521 +vn 0.1367 -0.2848 -0.9488 +vn -0.0133 0.6052 -0.7960 +vn 0.0000 0.6024 -0.7982 +vn 0.1370 -0.2848 -0.9487 +vn -0.0032 0.5807 -0.8141 +vn -0.0190 0.5863 -0.8099 +vn -0.0847 0.3483 -0.9335 +vn -0.4068 -0.0345 -0.9129 +vn 0.1158 -0.2677 -0.9565 +vn 0.0003 0.0341 0.9994 +vn -0.0071 0.0273 0.9996 +vn 0.0102 0.6204 -0.7842 +vn -0.0087 0.6326 -0.7744 +vn 0.0011 0.9985 -0.0553 +vn 0.0085 0.9975 -0.0704 +vn -0.9991 -0.0399 -0.0169 +vn -0.9990 -0.0432 -0.0073 +vn -0.7637 0.5755 -0.2923 +vn -0.0929 0.9927 -0.0769 +vn -0.9577 -0.2658 0.1099 +vn -0.7455 -0.4984 0.4425 +vn -0.8750 -0.3650 0.3179 +vn -0.9140 -0.3895 0.1140 +vn -0.7108 -0.6970 0.0941 +vn -0.7355 -0.6267 0.2574 +vn -0.9377 -0.3416 -0.0630 +vn -0.9294 -0.3690 -0.0044 +vn -0.9396 -0.3381 0.0536 +vn -0.9070 -0.4210 -0.0099 +vn -0.7170 -0.6948 -0.0559 +vn -0.7716 -0.5935 -0.2290 +vn -0.7186 -0.4324 -0.5447 +vn -0.8352 -0.0901 -0.5426 +vn -0.6434 -0.3583 -0.6765 +vn -0.4734 -0.0222 -0.8805 +vn -0.7446 -0.0982 -0.6602 +vn -0.7820 -0.0830 -0.6177 +vn -0.8021 0.0621 -0.5939 +vn -0.6023 0.1012 -0.7919 +vn -0.7837 0.0705 -0.6171 +vn -0.8402 0.0924 -0.5344 +vn -0.6264 0.3365 -0.7032 +vn -0.9445 0.1647 -0.2841 +vn -0.8050 0.4479 -0.3891 +vn -0.8435 0.3101 -0.4387 +vn -0.8471 0.4098 -0.3383 +vn -0.9299 0.3552 -0.0956 +vn -0.9387 0.3448 -0.0024 +vn -0.7256 0.6865 -0.0475 +vn -0.9129 0.4082 -0.0039 +vn -0.7443 0.6347 0.2078 +vn -0.8761 0.4745 0.0854 +vn -0.9291 0.3622 0.0752 +vn -0.7460 0.4341 0.5051 +vn -0.8093 0.4635 0.3607 +vn -0.9494 0.1898 0.2501 +vn -0.6809 0.0777 0.7283 +vn -0.7269 0.2729 0.6302 +vn -0.9409 0.0467 0.3355 +vn -0.7570 -0.1335 0.6396 +vn -0.9484 -0.1472 0.2807 +vn -0.7213 -0.3378 0.6047 +vn -0.7376 -0.4895 0.4650 +vn -0.8673 0.0036 -0.4978 +vn -0.6736 0.4712 -0.5694 +vn -0.8864 0.1709 -0.4302 +vn -0.9110 -0.1011 -0.3998 +vn -0.9164 0.0314 -0.3990 +vn -0.7621 0.5179 -0.3885 +vn -0.7822 -0.5017 -0.3694 +vn -0.9378 -0.1705 -0.3025 +vn -0.9159 -0.2421 -0.3201 +vn -0.9779 -0.0381 -0.2055 +vn -0.9354 0.2889 0.2040 +vn -0.9799 0.0171 0.1988 +vn -0.9252 -0.2905 -0.2440 +vn -0.9492 -0.2611 -0.1757 +vn -0.9671 0.1881 -0.1712 +vn -0.6871 -0.5350 -0.4916 +vn -0.7586 0.5889 -0.2789 +vn -0.9827 -0.1785 -0.0483 +vn -0.9995 0.0103 -0.0294 +vn -0.9837 0.1595 0.0834 +vn -0.9736 0.2220 -0.0527 +vn -0.9495 0.2959 0.1042 +vn -0.9864 -0.1167 0.1160 +vn -0.7562 0.4543 0.4709 +vn -0.2087 -0.7390 -0.6405 +vn -0.3241 -0.8575 -0.3997 +vn 0.0240 -0.8841 -0.4667 +vn -0.0094 -0.9682 -0.2500 +vn -0.3285 -0.9183 -0.2210 +vn -0.2557 -0.9667 -0.0045 +vn -0.3245 -0.9251 0.1973 +vn -0.2413 -0.8900 0.3868 +vn -0.2844 -0.7716 0.5691 +vn -0.2581 -0.6413 0.7226 +vn -0.2851 -0.3823 0.8789 +vn -0.2604 -0.2022 0.9441 +vn -0.3034 -0.0136 0.9528 +vn -0.2926 0.2535 0.9220 +vn -0.2816 0.5876 0.7586 +vn -0.2588 -0.0873 -0.9620 +vn -0.2254 0.2514 -0.9413 +vn -0.0582 -0.3981 -0.9155 +vn -0.3325 -0.5525 -0.7644 +vn 0.0053 0.7595 -0.6505 +vn 0.0200 0.7399 -0.6724 +vn 0.0111 0.7519 -0.6592 +vn 0.0241 0.7344 -0.6783 +vn 0.0208 0.7467 0.6648 +vn -0.0221 0.8069 0.5903 +vn 0.0001 0.7769 0.6296 +vn 0.0479 0.7043 0.7083 +vn -0.0381 -0.6087 0.7925 +vn 0.0025 -0.6515 0.7586 +vn -0.1024 -0.5346 0.8389 +vn 0.0551 -0.7025 0.7095 +vn -0.0271 -0.6714 -0.7406 +vn -0.0221 -0.6795 -0.7334 +vn -0.0250 -0.6747 -0.7376 +vn -0.0187 -0.6849 -0.7284 +vn -0.0320 0.7294 0.6833 +vn 0.0101 0.8813 0.4724 +vn -0.0258 0.7556 0.6545 +vn 0.0180 0.9032 0.4289 +vn 0.0368 -0.1310 0.9907 +vn 0.0064 -0.9193 0.3935 +vn -0.0335 -0.7390 0.6729 +vn -0.0297 -0.7610 0.6481 +vn 0.0117 -0.9356 0.3530 +vn -0.0066 -0.6924 -0.7215 +vn -0.0155 -0.7246 -0.6890 +vn -0.0143 -0.7205 -0.6933 +vn -0.0048 -0.6856 -0.7279 +vn 0.0229 0.5488 -0.8357 +vn -0.0270 0.7340 -0.6787 +vn 0.0160 0.5770 -0.8166 +vn -0.0346 0.7586 -0.6507 +vn -0.0738 -0.4255 0.9019 +vn 0.0084 -0.3900 0.9208 +vn 0.0158 -0.6526 0.7575 +vn -0.0084 -0.9866 -0.1632 +vn -0.3430 -0.7376 -0.5817 +vn 0.0057 -1.0000 0.0006 +vn 0.0015 -0.6293 -0.7771 +vn -0.3382 -0.5398 -0.7709 +vn -0.2678 -0.5087 0.8182 +vn -0.2598 -0.8502 0.4578 +vn 0.0099 -0.9282 0.3721 +vn -0.1334 -0.9422 0.3074 +vn -0.0069 -0.9904 0.1378 +vn -0.2824 -0.4204 -0.8623 +vn -0.5981 -0.5491 0.5837 +vn -0.5147 -0.6034 0.6091 +vn -0.5964 -0.4787 -0.6444 +vn -0.5473 -0.6298 -0.5512 +vn -0.5767 -0.6330 -0.5165 +vn -0.6724 -0.7157 -0.1889 +vn -0.6243 -0.6405 -0.4472 +vn -0.6456 -0.7579 -0.0935 +vn -0.5951 -0.8034 -0.0191 +vn 0.0080 0.9446 -0.3281 +vn 0.0005 0.6717 -0.7408 +vn -0.0027 0.7915 -0.6112 +vn -0.2385 0.6809 -0.6924 +vn -0.3129 0.8663 -0.3894 +vn -0.3504 0.7249 0.5931 +vn -0.2825 0.8820 0.3771 +vn -0.3663 0.9218 0.1270 +vn -0.2419 0.9657 -0.0947 +vn 0.0465 -0.9556 -0.2911 +vn -0.0488 -0.5313 -0.8458 +vn 0.0351 0.1122 -0.9931 +vn -0.0318 0.7978 -0.6021 +vn 0.0364 0.9992 0.0143 +vn -0.0397 0.7646 0.6432 +vn 0.0600 -0.1795 0.9819 +vn -0.0593 -0.7196 0.6918 +vn 0.0112 0.3940 0.9190 +vn 0.0032 0.4977 0.8673 +vn 0.0150 0.6626 0.7489 +vn -0.0030 0.3971 -0.9178 +vn -0.3882 0.7219 -0.5729 +vn -0.1185 0.6539 -0.7472 +vn 0.0282 0.9055 -0.4234 +vn -0.0246 0.9906 -0.1349 +vn 0.0244 0.9148 -0.4032 +vn -0.0280 0.9929 -0.1152 +vn -0.2378 0.4406 0.8656 +vn -0.0120 0.9003 0.4350 +vn 0.0077 0.9295 0.3687 +vn -0.0103 0.9596 0.2813 +vn -0.0165 0.9889 0.1475 +vn 0.0040 0.9699 0.2436 +vn -0.0142 0.9498 0.3124 +vn -0.0063 0.4812 -0.8766 +vn -0.6283 0.6580 0.4151 +vn -0.5304 0.6879 0.4955 +vn -0.5229 0.5601 0.6426 +vn -0.5425 0.4770 0.6915 +vn -0.4139 0.9017 0.1249 +vn -0.8486 0.5224 0.0839 +vn -0.7129 0.6727 -0.1979 +vn -0.6654 0.6135 -0.4253 +vn -0.6583 0.4420 -0.6093 +vn -0.4962 0.3124 -0.8101 +vn -0.3825 0.7275 -0.5696 +vn -0.6876 0.6946 -0.2114 +vn -0.6875 0.6927 -0.2179 +vn -0.8948 0.3992 0.1999 +vn -0.8809 0.4543 0.1327 +vn -0.8671 0.2385 0.4373 +vn -0.8360 0.2279 0.4991 +vn 0.9981 0.0202 0.0575 +vn 0.9738 0.1594 0.1620 +vn 0.9951 0.0637 0.0759 +vn 0.9607 -0.2507 -0.1195 +vn 0.9814 -0.1732 -0.0825 +vn 0.9920 0.1127 0.0561 +vn 0.9662 0.2312 0.1137 +vn 0.9009 0.3885 0.1934 +vn -0.6256 0.4724 -0.6208 +vn -0.6323 0.4719 -0.6145 +vn -0.6533 0.4695 -0.5940 +vn -0.6574 0.4689 -0.5898 +vn 0.6315 0.6901 -0.3534 +vn -0.6990 0.7106 0.0801 +vn 0.7781 0.4946 0.3871 +vn -0.7617 0.2506 0.5975 +vn 0.7702 -0.2167 0.5998 +vn -0.4551 -0.5431 0.7057 +vn 0.0719 -0.9890 0.1296 +vn 0.0154 -0.9902 0.1386 +vn 0.3114 -0.9464 0.0860 +vn 0.3350 -0.9387 0.0812 +vn -0.1881 -0.6120 -0.7682 +vn 0.5832 -0.5689 -0.5799 +vn 0.5985 -0.5709 -0.5620 +vn 0.5948 -0.5703 -0.5666 +vn 0.5788 -0.5680 -0.5851 +vn 0.7782 -0.6052 -0.1679 +vn -0.5542 -0.7545 0.3516 +vn 0.4194 0.1446 0.8962 +vn -0.8132 0.5801 0.0466 +vn -0.1447 0.7009 0.6984 +vn 0.6065 0.6531 0.4534 +vn -0.7116 0.7026 0.0050 +vn 0.7350 0.6311 -0.2479 +vn -0.6460 0.3978 -0.6515 +vn 0.6461 0.1951 -0.7379 +vn -0.7511 -0.2625 -0.6057 +vn 0.6780 -0.5028 -0.5362 +vn -0.5571 -0.8299 -0.0299 +vn 0.1804 -0.9750 -0.1296 +vn -0.3029 -0.7535 0.5835 +vn -0.2825 -0.7558 0.5907 +vn -0.0921 -0.7602 0.6432 +vn -0.0753 -0.7591 0.6466 +vn 0.0695 -0.9647 0.2541 +vn 0.8933 -0.4058 -0.1934 +vn -0.1612 -0.2717 0.9488 +vn 0.6798 0.0199 0.7332 +vn -0.4499 0.8636 -0.2275 +vn 0.8829 0.4204 0.2093 +vn -0.6331 -0.5676 -0.5263 +vn -0.5209 -0.6909 -0.5013 +vn -0.4102 -0.7832 -0.4674 +vn -0.2883 -0.8592 -0.4227 +vn 0.3269 0.8334 -0.4456 +vn 0.4043 0.8290 -0.3864 +vn 0.2526 0.8303 -0.4968 +vn 0.1718 0.8198 -0.5463 +vn -0.1037 0.2335 0.9668 +vn 0.4352 -0.1248 0.8917 +vn -0.3309 -0.8972 -0.2926 +vn 0.2300 -0.8007 -0.5532 +vn -0.0895 0.9048 -0.4163 +vn 0.5647 0.5339 -0.6294 +vn -0.1710 0.3009 0.9382 +vn -0.2862 0.3694 0.8841 +vn -0.0063 0.1961 0.9806 +vn 0.1299 0.1037 0.9861 +vn 0.0780 0.2636 0.9615 +vn -0.1267 0.0711 0.9894 +vn 0.1428 0.2931 0.9454 +vn -0.3822 -0.9197 -0.0895 +vn -0.4728 -0.8686 0.1487 +vn -0.4522 -0.8899 0.0590 +vn 0.9916 -0.0917 0.0914 +vn 0.9860 -0.1547 0.0623 +vn 0.9877 -0.0902 0.1277 +vn 0.4919 -0.6513 -0.5778 +vn 0.3911 -0.5745 -0.7190 +vn 0.2242 -0.8772 -0.4245 +vn -0.1067 -0.0454 0.9933 +vn 0.1778 -0.1624 0.9706 +vn 0.5346 0.6460 0.5448 +vn 0.2045 -0.1689 0.9642 +vn -0.0235 0.9064 0.4218 +vn -0.2518 0.8855 0.3905 +vn -0.1262 0.9031 0.4105 +vn 0.9459 0.2521 -0.2043 +vn 0.9488 0.2467 -0.1974 +vn 0.8926 0.3718 -0.2550 +vn -0.9765 0.0417 -0.2113 +vn -0.9360 -0.0172 -0.3515 +vn -0.8790 0.0946 -0.4673 +vn -0.9787 0.0445 0.2006 +vn -0.9750 0.0519 0.2161 +vn -0.8100 0.2209 0.5432 +vn -0.9402 0.1675 0.2966 +vn 0.4879 0.8722 -0.0344 +vn 0.8276 0.5307 0.1826 +vn 0.5010 0.8648 -0.0327 +vn -0.8429 0.3983 -0.3616 +vn -0.9964 -0.0160 -0.0829 +vn -0.1734 -0.9829 -0.0622 +vn -0.9873 -0.1111 0.1133 +vn -0.8846 -0.4304 0.1797 +vn -0.9767 -0.1712 0.1292 +vn -0.9834 -0.1608 0.0837 +vn -0.9865 -0.1383 0.0882 +vn -0.9836 -0.1546 0.0931 +vn -0.9876 -0.1455 -0.0589 +vn -0.8691 -0.4130 -0.2721 +vn -0.9839 -0.1631 -0.0726 +vn 0.3850 -0.0759 -0.9198 +vn 0.9849 -0.0929 0.1462 +vn -0.3410 0.2381 -0.9094 +vn -0.9770 0.0377 -0.2097 +vn 0.2703 -0.8067 0.5256 +vn -0.0656 -0.8676 0.4929 +vn -0.0148 -0.8649 0.5017 +vn 0.2966 -0.7972 0.5258 +vn -0.5750 0.2326 -0.7844 +vn -0.3920 0.2926 -0.8722 +vn -0.5250 0.2509 -0.8132 +vn 0.0287 -0.9232 0.3832 +vn 0.9286 -0.1634 -0.3333 +vn 0.9291 -0.1624 -0.3324 +vn 0.9249 -0.1706 -0.3398 +vn -0.9358 0.3050 0.1766 +vn -0.9222 0.3085 0.2333 +vn -0.9805 0.1920 0.0422 +vn 0.2452 -0.9186 -0.3098 +vn 0.9617 0.1670 0.2173 +vn -0.9463 0.1628 0.2794 +vn 0.8676 0.4314 -0.2475 +vn 0.4146 0.9041 0.1037 +vn 0.9944 -0.1054 0.0012 +vn -0.4639 -0.4247 -0.7775 +vn -0.7062 -0.2608 -0.6582 +vn -0.4215 -0.4465 -0.7893 +vn -0.1364 0.9904 0.0223 +vn -0.6584 -0.4395 0.6111 +vn 0.4730 0.4826 -0.7371 +vn -0.9577 0.2698 -0.1003 +vn -0.2800 -0.5097 -0.8135 +vn -0.0780 0.9714 -0.2241 +vn -0.1923 0.9750 -0.1116 +vn -0.1597 0.9765 -0.1445 +vn -0.0384 0.9644 -0.2616 +vn 0.7177 0.6142 -0.3281 +vn -0.8011 -0.4938 -0.3382 +vn 0.8375 0.4989 -0.2229 +vn -0.7756 0.4097 0.4802 +vn -0.1577 0.9337 0.3214 +vn -0.9965 0.0451 -0.0699 +vn -0.9952 0.0580 -0.0783 +vn 0.9563 -0.0540 -0.2872 +vn 0.8400 -0.0466 -0.5406 +vn 0.8951 -0.0500 -0.4431 +vn -0.5258 -0.5188 -0.6741 +vn -0.8157 0.4552 -0.3569 +vn 0.9849 -0.0930 0.1463 +vn -0.6099 -0.3408 0.7155 +vn 0.3233 -0.5424 -0.7754 +vn 0.9431 -0.3323 0.0119 +vn 0.3520 0.6509 -0.6726 +vn 0.9167 -0.3752 -0.1372 +vn 0.8933 -0.4396 -0.0936 +vn 0.8773 0.2898 0.3825 +vn 0.9027 0.2331 0.3617 +vn 0.7497 0.5232 0.4053 +vn -0.6936 -0.6167 -0.3724 +vn 0.9600 -0.0543 -0.2747 +vn 0.4632 -0.6212 0.6321 +vn 0.5170 -0.6291 0.5805 +vn 0.4776 -0.6236 0.6189 +vn 0.9272 -0.1346 0.3496 +vn -0.9775 0.0826 -0.1940 +vn -0.9808 0.0165 -0.1944 +vn -0.2809 -0.6780 -0.6793 +vn -0.0490 -0.3802 0.9236 +vn -0.4208 -0.2863 0.8608 +vn -0.4535 -0.2748 0.8478 +vn 0.5004 0.0398 0.8649 +vn 0.0143 -0.3904 0.9206 +vn -0.7203 -0.2486 -0.6476 +vn -0.6740 0.6693 -0.3126 +vn 0.7751 0.6305 0.0423 +vn 0.9237 -0.1729 -0.3419 +vn -0.0169 0.7392 -0.6733 +vn 0.4126 0.1937 0.8901 +vn -0.9831 0.1798 0.0357 +vn 0.9110 -0.3259 -0.2529 +vn 0.3577 0.6514 0.6691 +vn -0.2623 0.8833 0.3885 +vn 0.5298 -0.6305 0.5673 +vn 0.5175 0.3213 -0.7931 +vn -0.0339 -0.9779 -0.2063 +vn -0.1698 0.1723 0.9703 +vn 0.8850 0.3485 -0.3088 +vn -0.7044 0.4552 0.5446 +vn -0.9951 0.0607 -0.0781 +vn -0.0075 -0.0951 -0.9954 +vn -0.1670 0.3440 -0.9240 +vn 0.3041 -0.9334 -0.1906 +vn -0.9991 0.0201 0.0368 +vn -0.9985 0.0342 -0.0419 +vn -0.9992 -0.0392 -0.0047 +vn 0.9990 0.0272 0.0343 +vn 0.9908 0.0469 0.1270 +vn 0.9881 0.0507 0.1454 +vn 0.0694 0.7075 0.7033 +vn -0.0232 0.3725 0.9278 +vn 0.0497 0.6427 0.7645 +vn -0.0448 0.2830 0.9581 +vn 0.0667 -0.6427 0.7632 +vn -0.0449 -0.9978 0.0496 +vn 0.0779 -0.8768 -0.4744 +vn -0.0184 0.0233 -0.9996 +vn 0.0891 0.5454 -0.8334 +vn -0.0345 0.9937 -0.1063 +vn 0.9893 0.1253 0.0746 +vn 0.9914 0.0560 0.1182 +vn 0.9871 -0.0835 0.1367 +vn 0.9796 0.1533 -0.1302 +vn 0.9910 0.0186 -0.1328 +vn 0.9896 0.1435 -0.0035 +vn 0.9920 -0.1240 -0.0245 +vn 0.9766 -0.1333 -0.1688 +vn 0.9792 -0.1307 0.1550 +vn -0.0292 -0.1352 0.9904 +vn -0.0112 -0.1550 0.9878 +vn -0.0104 -0.1560 0.9877 +vn 0.0064 -0.1745 0.9846 +vn -0.0351 -0.9082 0.4172 +vn -0.0729 -0.8905 0.4490 +vn -0.0327 -0.9092 0.4151 +vn 0.0074 -0.9250 0.3800 +vn 0.0146 -0.5946 -0.8039 +vn 0.0800 -0.6288 -0.7734 +vn 0.0915 -0.6345 -0.7675 +vn 0.1759 -0.6722 -0.7192 +vn -0.2002 0.0955 -0.9751 +vn 0.1774 0.7610 -0.6240 +vn 0.0686 0.8469 -0.5274 +vn 0.0625 0.8509 -0.5215 +vn -0.0729 0.9212 -0.3821 +vn -0.0035 0.8492 0.5280 +vn 0.0044 0.8533 0.5213 +vn 0.0055 0.8536 0.5209 +vn 0.0143 0.8580 0.5135 +vn -0.1302 -0.5943 0.7936 +vn -0.8030 0.2161 0.5554 +vn -0.5739 -0.3699 -0.7306 +vn -0.5223 -0.3464 -0.7792 +vn -0.5448 -0.3567 -0.7589 +vn -0.4670 -0.3207 -0.8241 +vn -0.0993 0.9865 0.1299 +vn 0.9668 0.0718 0.2454 +vn -0.9981 0.0491 0.0378 +vn -0.9992 -0.0394 0.0118 +vn -0.9976 0.0191 -0.0667 +vn 0.9993 0.0045 0.0363 +vn 0.9988 -0.0050 0.0497 +vn 0.9997 0.0148 0.0212 +vn 0.0087 0.1045 0.9945 +vn -0.0033 0.2059 0.9786 +vn -0.0024 0.1980 0.9802 +vn 0.0095 0.0972 0.9952 +vn -0.0003 1.0000 0.0000 +vn 0.0176 0.9741 -0.2253 +vn 0.0008 0.9999 -0.0136 +vn 0.0186 0.9711 -0.2381 +vn -0.0050 0.2400 -0.9708 +vn 0.0217 -0.1091 -0.9938 +vn -0.0034 0.2195 -0.9756 +vn 0.0234 -0.1318 -0.9910 +vn -0.0115 -0.9911 -0.1327 +vn 0.0140 -0.9918 0.1267 +vn -0.0098 -0.9933 -0.1153 +vn 0.0161 -0.9887 0.1489 +vn 0.9957 0.0696 -0.0605 +vn 0.9959 0.0877 -0.0221 +vn 0.9955 0.0754 0.0576 +vn 0.9946 0.0719 0.0746 +vn 0.9949 -0.0059 0.1010 +vn 0.9915 -0.0901 0.0939 +vn 0.9942 -0.1049 0.0230 +vn 0.9954 -0.0689 -0.0662 +vn 0.9955 -0.0448 -0.0836 +vn 0.9952 0.0326 -0.0918 +vn -0.0697 0.2380 0.9688 +vn -0.0248 0.2875 0.9575 +vn -0.0351 0.2762 0.9605 +vn 0.0096 0.3244 0.9459 +vn -0.0371 0.9814 0.1886 +vn 0.0383 0.9624 0.2689 +vn -0.0284 0.9797 0.1982 +vn -0.1023 0.9879 0.1168 +vn -0.0606 0.7540 -0.6541 +vn -0.0223 0.7261 -0.6872 +vn -0.0311 0.7328 -0.6798 +vn 0.0065 0.7033 -0.7109 +vn -0.0324 -0.2125 -0.9766 +vn 0.0352 -0.1396 -0.9896 +vn -0.0220 -0.2013 -0.9793 +vn -0.0909 -0.2741 -0.9574 +vn -0.0964 -0.9235 -0.3712 +vn -0.0152 -0.9539 -0.2998 +vn -0.0129 -0.9546 -0.2977 +vn 0.0669 -0.9723 -0.2239 +vn -0.0503 -0.5817 0.8118 +vn 0.0123 -0.6327 0.7743 +vn -0.0456 -0.5857 0.8092 +vn -0.1043 -0.5335 0.8393 +vn -0.1608 -0.2595 0.9523 +vn -0.3397 -0.1005 0.9351 +vn -0.2934 -0.1439 0.9451 +vn -0.4993 0.0646 0.8640 +vn -0.1655 -0.7685 -0.6181 +vn -0.2972 -0.8041 -0.5149 +vn -0.2585 -0.7959 -0.5475 +vn -0.4235 -0.8162 -0.3932 +vn 0.0114 0.9546 -0.2976 +vn -0.1779 0.8889 -0.4221 +vn -0.1100 0.9187 -0.3794 +vn -0.3613 0.7704 -0.5253 +vn -0.9842 -0.1345 0.1152 +vn -0.9941 -0.0903 0.0604 +vn -0.9752 -0.1476 0.1647 +vn -0.9986 -0.0370 0.0388 +vn -0.9237 -0.2355 0.3021 +vn -0.9643 -0.1523 0.2168 +vn -0.9777 -0.1186 0.1736 +vn -0.9943 0.0869 -0.0625 +vn -0.9747 0.1710 -0.1438 +vn -0.9872 0.1185 -0.1072 +vn -0.9994 0.0254 0.0231 +vn -0.8732 0.1946 0.4468 +vn -0.9988 0.0395 0.0306 +vn -0.8815 0.3029 0.3623 +vn -0.6980 0.2040 0.6864 +vn -0.9994 0.0327 -0.0109 +vn -0.9999 0.0102 -0.0131 +vn -0.9813 0.1833 -0.0581 +vn -0.9705 0.2292 -0.0742 +vn -0.9994 0.0324 -0.0100 +vn -0.9996 -0.0122 0.0239 +vn -0.9864 0.0018 0.1646 +vn -0.9670 0.1440 0.2101 +vn -0.9986 0.0520 -0.0139 +vn -0.9979 0.0253 -0.0596 +vn 0.8746 0.4202 0.2419 +vn 0.6692 0.2074 0.7135 +vn 0.7359 0.2220 0.6396 +vn 0.8881 0.4300 0.1621 +vn 0.7690 -0.6349 -0.0748 +vn 0.6632 -0.7388 -0.1195 +vn 0.7701 -0.6336 -0.0742 +vn 0.9683 -0.2259 0.1068 +vn 0.9293 0.2142 -0.3007 +vn 0.9716 0.1373 -0.1927 +vn 0.9997 0.0138 -0.0194 +vn 0.7867 0.5959 0.1612 +vn 0.8341 0.5380 0.1217 +vn 0.8499 0.5159 0.1071 +vn 0.9002 -0.4069 0.1553 +vn 0.9026 -0.3987 0.1622 +vn 0.9277 -0.2334 0.2913 +vn 0.9995 0.0297 -0.0148 +vn 0.9938 0.1008 -0.0470 +vn 0.9884 0.1456 -0.0419 +vn 0.9991 0.0323 0.0265 +vn 0.9983 0.0363 0.0463 +vn 0.9942 -0.0160 0.1066 +vn 0.9847 0.0875 0.1507 +vn 0.9931 0.1086 0.0437 +vn 0.9998 0.0194 -0.0007 +vn 0.1302 0.3732 -0.9186 +vn -0.3642 0.9013 -0.2344 +vn 0.4785 0.8737 -0.0873 +vn -0.4471 0.7049 0.5506 +vn -0.5639 0.0490 0.8244 +vn 0.6565 -0.5038 0.5613 +vn -0.7197 -0.6512 0.2406 +vn 0.3005 -0.9514 0.0669 +vn -0.1438 -0.7251 -0.6734 +vn -0.1868 -0.7159 -0.6728 +vn -0.4230 -0.6370 -0.6444 +vn -0.4481 -0.6256 -0.6386 +vn -0.2995 0.2108 -0.9305 +vn 0.7827 -0.6187 -0.0682 +vn 0.8165 0.5774 0.0000 +vn -0.1719 0.7376 0.6530 +vn -0.1726 0.7376 0.6528 +vn -0.1644 0.7374 0.6551 +vn -0.1634 0.7374 0.6554 +vn 0.3326 0.9421 0.0427 +vn -0.3022 0.7866 -0.5384 +vn 0.2111 0.2561 -0.9433 +vn -0.3138 0.1663 -0.9348 +vn 0.4548 -0.4351 -0.7771 +vn -0.6202 -0.5272 -0.5808 +vn 0.6598 -0.7368 -0.1473 +vn -0.4529 -0.8907 0.0377 +vn -0.0036 -0.7636 0.6457 +vn 0.0269 -0.7603 0.6491 +vn 0.1621 -0.7368 0.6563 +vn 0.1718 -0.7346 0.6564 +vn 0.8389 -0.5435 0.0287 +vn 0.4090 -0.1405 0.9016 +vn 0.8608 0.4997 0.0966 +vn -0.1991 -0.6136 -0.7641 +vn 0.4346 0.5081 -0.7436 +vn -0.3739 0.8385 -0.3963 +vn 0.0666 0.8064 0.5876 +vn -0.5493 -0.3126 0.7750 +vn 0.6523 -0.6914 0.3105 +vn -0.3839 -0.8913 -0.2413 +vn 0.5135 0.1595 -0.8431 +vn -0.0318 0.6249 -0.7800 +vn 0.4064 0.7930 0.4538 +vn -0.4876 0.3350 0.8063 +vn 0.5045 -0.7738 0.3830 +vn 0.9979 -0.0215 -0.0618 +vn 0.9907 -0.1129 -0.0763 +vn 0.8975 0.4297 0.0991 +vn -0.5408 0.6974 0.4702 +vn -0.2156 0.6707 0.7097 +vn -0.4886 0.7093 0.5082 +vn -0.9522 -0.1274 0.2775 +vn -0.9414 -0.1329 0.3100 +vn -0.8292 -0.1680 0.5330 +vn 0.2767 -0.9497 0.1469 +vn 0.6158 -0.7846 -0.0720 +vn 0.3022 -0.9428 0.1406 +vn -0.8951 -0.2719 0.3534 +vn -0.9314 -0.3460 0.1133 +vn -0.9024 -0.2545 0.3476 +vn 0.1474 -0.1736 -0.9737 +vn 0.2450 -0.2385 -0.9397 +vn 0.2202 -0.2222 -0.9498 +vn 0.1247 -0.1584 -0.9795 +vn 0.9229 0.3032 0.2374 +vn 0.9577 0.2281 0.1754 +vn 0.9216 0.3053 0.2397 +vn 0.9956 -0.0135 -0.0932 +vn 0.8421 -0.0668 0.5351 +vn 0.9902 -0.0893 0.1074 +vn 0.8777 -0.0684 0.4744 +vn -0.6042 -0.6147 0.5071 +vn -0.4403 -0.8462 0.3002 +vn -0.6800 -0.6473 0.3445 +vn -0.0686 -0.4684 -0.8809 +vn -0.0629 -0.4676 -0.8817 +vn -0.0615 -0.4674 -0.8819 +vn 0.8195 -0.4681 0.3306 +vn 0.5431 0.6208 -0.5654 +vn 0.7556 0.5925 -0.2794 +vn 0.9103 0.4140 -0.0026 +vn 0.7634 0.5709 -0.3020 +vn -0.9567 -0.2428 0.1606 +vn -0.4999 0.3430 -0.7953 +vn -0.3818 0.4536 -0.8053 +vn -0.5155 0.3484 -0.7829 +vn 0.9987 -0.0508 0.0021 +vn 0.9970 -0.0760 -0.0137 +vn -0.5240 0.8392 -0.1454 +vn -0.5244 0.8240 -0.2147 +vn -0.8420 0.4254 -0.3317 +vn -0.8699 0.3738 -0.3217 +vn 0.5272 0.0944 0.8445 +vn 0.5723 0.1105 0.8126 +vn 0.7621 0.1822 0.6213 +vn -0.3434 0.5466 -0.7638 +vn -0.5720 0.6117 -0.5466 +vn -0.5341 0.6235 -0.5710 +vn -0.9277 -0.3734 -0.0021 +vn 0.6085 -0.5951 0.5249 +vn 0.7654 -0.4601 0.4500 +vn 0.5852 -0.6110 0.5331 +vn -0.7937 -0.0791 -0.6031 +vn -0.7945 -0.0745 -0.6027 +vn -0.7726 -0.1951 -0.6041 +vn 0.7855 -0.4520 0.4227 +vn 0.6820 -0.5496 0.4825 +vn -0.4195 0.8065 0.4166 +vn 0.8670 -0.0767 0.4923 +vn -0.9005 -0.4264 0.0851 +vn -0.9021 -0.4233 0.0837 +vn 0.7380 0.1425 -0.6596 +vn 0.6280 0.1226 -0.7685 +vn 0.5977 0.1686 -0.7838 +vn 0.6559 0.0768 -0.7509 +vn -0.0722 -0.4688 -0.8804 +vn -0.4502 0.8849 0.1191 +vn -0.3792 0.9246 0.0352 +vn -0.2545 0.9609 -0.1092 +vn -0.8644 0.0598 0.4993 +vn -0.8997 0.1243 0.4185 +vn -0.9981 0.0372 0.0494 +vn -0.8949 -0.2068 -0.3955 +vn -0.8812 -0.1869 -0.4341 +vn -0.9040 -0.2216 -0.3655 +vn -0.4412 -0.3847 0.8108 +vn -0.2846 -0.4404 0.8515 +vn -0.4626 -0.4089 0.7867 +vn -0.4556 -0.4524 -0.7667 +vn 0.9586 0.2519 0.1329 +vn 0.3764 -0.7495 0.5447 +vn -0.8876 -0.1700 0.4281 +vn -0.7982 0.6014 0.0340 +vn 0.7859 0.1919 0.5878 +vn 0.2271 -0.8239 -0.5193 +vn -0.9242 0.3566 0.1368 +vn -0.4452 -0.3425 0.8273 +vn 0.6417 0.1842 0.7445 +vn 0.6904 0.1260 0.7124 +vn 0.4639 0.3552 0.8116 +vn 0.3309 -0.9436 0.0114 +vn 0.1347 -0.9390 -0.3164 +vn 0.1931 -0.9707 -0.1433 +vn 0.4150 -0.9037 0.1050 +vn 0.9430 -0.0149 -0.3324 +vn 0.9249 -0.0753 -0.3727 +vn 0.9440 -0.0110 -0.3297 +vn 0.0784 -0.8914 -0.4464 +vn 0.1184 -0.9221 -0.3683 +vn 0.3464 0.4215 0.8381 +vn -0.3982 -0.8633 0.3100 +vn -0.3923 -0.8735 0.2882 +vn 0.8584 -0.3453 0.3794 +vn 0.9558 0.0449 -0.2906 +vn -0.9997 0.0024 -0.0237 +vn -0.8039 0.0346 -0.5938 +vn -0.9530 0.1219 0.2773 +vn -0.9509 0.1020 0.2921 +vn -0.9464 0.0683 0.3158 +vn 0.6385 -0.7646 -0.0874 +vn -0.5514 -0.6184 0.5599 +vn -0.9127 -0.2373 -0.3327 +vn 0.6371 -0.7396 -0.2169 +vn -0.9894 0.1328 0.0583 +vn -0.2966 0.9342 -0.1983 +vn 0.5648 0.2149 -0.7968 +vn 0.0410 0.9447 0.3254 +vn -0.2549 -0.4382 0.8620 +vn 0.9826 0.1797 0.0461 +vn 0.9853 0.1620 0.0539 +vn 0.9593 0.2805 -0.0335 +vn -0.3955 0.0639 0.9162 +vn -0.1898 0.6221 0.7596 +vn -0.8812 0.0485 -0.4703 +vn 0.6724 -0.5389 -0.5074 +vn 0.3018 -0.3572 0.8839 +vn -0.4285 -0.8242 -0.3704 +vn -0.3268 0.9234 -0.2014 +vn 0.7287 0.5204 -0.4452 +vn 0.4637 0.4274 -0.7761 +vn -0.9549 0.1589 0.2507 +vn -0.8182 -0.0586 0.5719 +vn -0.3896 0.3833 -0.8374 +vn 0.4991 0.8663 -0.0187 +vn -0.7538 -0.1816 0.6315 +vn 0.3434 0.4216 0.8392 +vn 0.9588 0.2782 -0.0573 +vn 0.9637 0.2547 -0.0797 +vn -0.2199 0.5599 0.7988 +vn 0.5979 0.2350 0.7663 +vn 0.6347 0.0690 0.7696 +vn 0.5421 0.3987 0.7397 +vn 0.9625 0.1808 -0.2022 +vn 0.9750 0.1271 -0.1824 +vn 0.9917 -0.0158 -0.1275 +vn 0.9911 -0.0892 -0.0984 +vn 0.3120 -0.7139 -0.6268 +vn 0.3055 -0.7039 -0.6412 +vn 0.3232 -0.7308 -0.6012 +vn 0.3313 -0.7428 -0.5818 +vn -0.5789 -0.3983 -0.7115 +vn -0.7667 -0.6001 -0.2282 +vn -0.9148 0.4040 0.0003 +vn -0.9217 0.3811 0.0728 +vn -0.8498 0.3726 0.3729 +vn -0.8087 0.3763 0.4521 +vn -0.7627 -0.1272 0.6341 +vn -0.7102 0.4668 0.5269 +vn 0.3429 -0.4372 -0.8314 +vn 0.5516 -0.7821 -0.2899 +vn 0.9974 -0.0432 -0.0573 +vn 0.9939 0.0415 -0.1025 +vn 0.9553 0.2215 -0.1959 +vn 0.9401 0.2630 -0.2170 +vn 0.4892 0.3614 0.7938 +vn 0.4892 0.3613 0.7938 +vn 0.3301 0.8378 0.4348 +vn -0.6543 0.2943 0.6966 +vn -0.7704 0.5925 0.2352 +vn -0.9465 -0.3218 -0.0236 +vn -0.8163 -0.0546 -0.5751 +vn -0.4328 -0.7856 -0.4423 +vn 0.6519 -0.0839 0.7536 +vn 0.4153 -0.0233 -0.9094 +vn 0.0000 -0.7071 0.7071 +vn 0.0000 0.7071 -0.7071 +vn -0.0001 0.7071 -0.7071 +vn -0.0003 0.7071 -0.7071 +vn -0.0283 -0.6791 0.7335 +vn -0.0333 -0.7048 0.7086 +vn -0.0185 -0.6879 0.7256 +vn 0.0071 -0.6828 0.7306 +vn -0.0117 -0.7283 0.6852 +vn -0.0270 -0.7240 0.6893 +vn 0.0117 -0.7291 0.6843 +vn 0.0339 -0.7025 0.7108 +vn 0.0326 -0.7160 0.6973 +vn 0.0253 -0.6879 0.7253 +vn 0.0195 0.7066 -0.7074 +vn 0.0223 0.7214 -0.6921 +vn 0.0118 0.7163 -0.6977 +vn 0.0083 0.7103 -0.7039 +vn -0.0127 0.7339 -0.6792 +vn -0.3381 -0.6777 -0.6530 +vn -0.7128 -0.4668 -0.5234 +vn -0.6654 -0.5048 -0.5499 +vn -0.2892 -0.6937 -0.6597 +vn 0.4096 -0.6108 -0.6776 +vn 0.8400 -0.3982 -0.3685 +vn 0.8555 0.3673 0.3649 +vn 0.9414 0.2600 0.2147 +vn 0.9322 0.2750 0.2354 +vn 0.8407 0.3811 0.3846 +vn -0.2057 0.6878 0.6961 +vn 0.0801 0.7244 0.6847 +vn 0.0472 0.7233 0.6890 +vn -0.2323 0.6813 0.6942 +vn -0.9713 0.1592 0.1767 +vn -0.8471 0.3985 0.3516 +vn -0.8701 0.3670 0.3290 +vn -0.9801 0.1269 0.1525 +vn -0.0724 0.6759 -0.7334 +vn -0.0890 0.6663 -0.7403 +vn -0.0676 0.7242 -0.6863 +vn 0.0290 0.6596 -0.7511 +vn -0.0120 0.6567 -0.7541 +vn 0.0292 0.7614 -0.6477 +vn 0.0564 0.7392 -0.6712 +vn 0.0719 0.7063 -0.7043 +vn -0.0518 0.7447 -0.6653 +vn -0.0167 0.7566 -0.6537 +vn 0.0479 0.6641 -0.7461 +vn 0.0699 0.6939 -0.7167 +vn -0.9930 -0.0432 -0.1099 +vn -0.9821 -0.1316 -0.1346 +vn -0.9742 -0.1725 -0.1457 +vn -0.8688 0.2971 0.3961 +vn -0.6029 0.5437 0.5839 +vn -0.7413 0.5033 0.4440 +vn -0.5213 0.6351 0.5700 +vn -0.2284 0.6333 0.7395 +vn 0.3087 0.7224 0.6188 +vn 0.3878 0.6680 0.6352 +vn 0.3585 0.6891 0.6297 +vn 0.4466 0.6213 0.6438 +vn 0.9701 0.1629 0.1798 +vn 0.9743 0.1619 0.1565 +vn 0.9710 0.1627 0.1750 +vn 0.9662 0.1637 0.1992 +vn 0.8284 -0.3602 -0.4289 +vn 0.7342 -0.5039 -0.4550 +vn 0.5897 -0.5519 -0.5896 +vn 0.2707 -0.7257 -0.6325 +vn -0.1725 -0.6701 -0.7220 +vn -0.3642 -0.6792 -0.6371 +vn -0.5847 -0.4986 -0.6400 +vn -0.9524 -0.2547 -0.1676 +vn -0.5803 0.6567 0.4816 +vn -0.6881 0.5119 0.5142 +vn -0.6856 0.5159 0.5136 +vn -0.7709 0.3543 0.5294 +vn 0.9872 0.1583 -0.0167 +vn 0.9725 0.1636 0.1659 +vn 0.9733 0.1636 0.1612 +vn 0.9266 0.1635 0.3385 +vn -0.4071 -0.5523 -0.7275 +vn -0.2845 -0.6790 -0.6768 +vn -0.2878 -0.6760 -0.6784 +vn -0.1558 -0.7805 -0.6054 +vn -0.0322 -0.7057 0.7077 +vn -0.0357 -0.7195 0.6935 +vn -0.0092 -0.7284 0.6850 +vn 0.0296 -0.7369 0.6754 +vn 0.0185 -0.7269 0.6865 +vn 0.0326 -0.7115 0.7020 +vn 0.0335 -0.6983 0.7150 +vn -0.0021 -0.6864 0.7272 +vn 0.0189 -0.6884 0.7251 +vn -0.0291 -0.6931 0.7202 +vn -0.0162 0.6985 -0.7154 +vn 0.0050 0.6962 -0.7178 +vn -0.0581 0.7411 -0.6689 +vn 0.0107 0.6777 -0.7352 +vn -0.0272 0.6858 -0.7273 +vn 0.8879 -0.3415 -0.3084 +vn 0.9314 0.2958 0.2123 +vn 0.5685 0.5638 0.5991 +vn -0.4897 0.6220 0.6110 +vn -0.2765 0.7073 0.6506 +vn -0.2993 0.7003 0.6481 +vn -0.5175 0.6074 0.6028 +vn -0.9989 -0.0272 -0.0378 +vn -0.9987 0.0259 0.0428 +vn -0.9993 -0.0218 -0.0295 +vn -0.9980 0.0335 0.0542 +vn -0.6733 -0.4921 -0.5519 +vn -0.1138 -0.7204 -0.6842 +vn 0.4983 -0.5868 -0.6382 +vn 0.0916 0.7256 -0.6820 +vn 0.0848 0.6975 -0.7115 +vn 0.0460 0.6646 -0.7457 +vn 0.0322 0.6600 -0.7506 +vn -0.0780 0.6604 -0.7468 +vn -0.0771 0.7022 -0.7078 +vn -0.0641 0.7284 -0.6822 +vn -0.0481 0.7444 -0.6660 +vn -0.0211 0.6553 -0.7551 +vn -0.0099 0.7631 -0.6462 +vn 0.0288 0.7501 -0.6607 +vn 0.1930 -0.6713 -0.7156 +vn 0.2120 -0.6793 -0.7026 +vn 0.1979 -0.6734 -0.7123 +vn 0.1807 -0.6660 -0.7238 +vn -0.7600 -0.4417 -0.4768 +vn -0.6785 -0.5573 -0.4787 +vn -0.7444 -0.4663 -0.4780 +vn -0.8091 -0.3532 -0.4696 +vn -0.9973 -0.0500 0.0533 +vn -0.9894 0.0995 0.1055 +vn -0.9742 0.1821 0.1335 +vn -0.9316 0.3170 0.1780 +vn -0.5207 0.5108 0.6841 +vn -0.3587 0.6609 0.6592 +vn -0.3393 0.6758 0.6543 +vn -0.1586 0.7890 0.5935 +vn 0.5632 0.4922 0.6638 +vn 0.8654 0.3279 0.3789 +vn 0.7561 0.4746 0.4506 +vn 0.9297 0.2946 0.2213 +vn 0.9919 0.0232 0.1252 +vn 0.8753 -0.2912 -0.3861 +vn 0.8201 -0.3971 -0.4120 +vn 0.8470 -0.3492 -0.4009 +vn 0.7782 -0.4620 -0.4254 +vn 0.4793 -0.4021 -0.7801 +vn -0.2494 -0.8471 -0.4693 +vn -0.9636 0.1910 -0.1869 +vn -0.6814 0.2929 0.6707 +vn 0.4844 0.7779 0.4003 +vn 0.9307 -0.0125 0.3655 +vn 0.0294 -0.6980 -0.7155 +vn 0.0099 -0.6847 -0.7288 +vn 0.0375 -0.7059 -0.7073 +vn -0.0270 -0.6913 -0.7221 +vn -0.0181 -0.6784 -0.7345 +vn -0.0057 -0.7301 -0.6833 +vn 0.0223 -0.7251 -0.6883 +vn -0.0040 -0.7424 -0.6699 +vn -0.0273 -0.7211 -0.6922 +vn -0.0348 -0.7049 -0.7084 +vn 0.0652 0.6801 0.7302 +vn 0.0561 0.6933 0.7184 +vn 0.0023 0.7166 0.6975 +vn -0.0135 0.7378 0.6749 +vn 0.9060 0.2725 -0.3240 +vn 0.9915 0.1014 -0.0813 +vn 0.9979 0.0606 -0.0242 +vn 0.4580 -0.6297 0.6275 +vn 0.4501 -0.6337 0.6291 +vn 0.4513 -0.6331 0.6289 +vn 0.4586 -0.6294 0.6273 +vn -0.5589 -0.5803 0.5923 +vn -0.6585 -0.5121 0.5515 +vn -0.5714 -0.5726 0.5879 +vn -0.6681 -0.5046 0.5468 +vn -1.0000 0.0065 -0.0026 +vn -0.9682 0.1963 -0.1548 +vn -0.9994 0.0277 -0.0196 +vn -0.9617 0.2152 -0.1700 +vn -0.4716 0.6078 -0.6388 +vn 0.1162 0.7440 -0.6579 +vn 0.8852 0.2964 -0.3585 +vn 0.1016 0.6854 0.7210 +vn 0.0494 0.6641 0.7460 +vn 0.0645 0.7274 0.6831 +vn 0.0204 0.7614 0.6480 +vn -0.0708 0.7278 0.6821 +vn -0.0478 0.7435 0.6670 +vn -0.0688 0.6945 0.7162 +vn -0.0599 0.6761 0.7344 +vn 0.0160 0.7753 0.6314 +vn -0.0022 0.6532 0.7572 +vn -0.0234 0.6550 0.7552 +vn 0.6780 0.5140 -0.5254 +vn 0.7837 0.3543 -0.5101 +vn 0.7059 0.4772 -0.5235 +vn 0.5729 0.6307 -0.5235 +vn -0.0634 0.6690 -0.7405 +vn -0.1360 0.6936 -0.7074 +vn -0.1749 0.7049 -0.6874 +vn -0.2459 0.7220 -0.6467 +vn -0.8979 0.3383 -0.2817 +vn -0.7957 0.3730 -0.4772 +vn -0.8765 0.3486 -0.3319 +vn -0.9415 0.3055 -0.1423 +vn -0.8341 -0.3751 0.4045 +vn -0.9508 -0.2807 0.1314 +vn -0.7478 -0.4944 0.4430 +vn -0.6321 -0.5125 0.5811 +vn -0.4318 -0.6764 0.5968 +vn 0.2018 -0.6448 0.7372 +vn 0.2342 -0.6580 0.7157 +vn 0.2242 -0.6540 0.7225 +vn 0.2624 -0.6687 0.6957 +vn 0.9616 -0.1649 0.2195 +vn 0.9114 -0.3378 0.2349 +vn 0.9583 -0.1807 0.2212 +vn 0.9792 -0.0203 0.2018 +vn 0.9266 0.3386 -0.1635 +vn 0.9733 0.1613 -0.1636 +vn 0.9725 0.1659 -0.1636 +vn 0.9872 -0.0167 -0.1583 +vn -0.7708 0.5294 -0.3544 +vn -0.6856 0.5136 -0.5159 +vn -0.6881 0.5143 -0.5119 +vn -0.5804 0.4817 -0.6566 +vn -0.1558 -0.6054 0.7805 +vn -0.2877 -0.6783 0.6761 +vn -0.2844 -0.6767 0.6791 +vn -0.4070 -0.7275 0.5524 +vn 0.0000 -0.7071 -0.7071 +vn 0.1752 0.6266 0.7594 +vn -0.0314 -0.7115 -0.7020 +vn -0.0108 -0.7284 -0.6851 +vn -0.0427 -0.7193 -0.6934 +vn 0.0253 -0.7235 -0.6898 +vn 0.0189 -0.7350 -0.6778 +vn 0.0314 -0.6988 -0.7146 +vn 0.0454 -0.7178 -0.6947 +vn -0.0342 -0.6954 -0.7178 +vn -0.0175 -0.6860 -0.7274 +vn 0.0085 -0.6840 -0.7295 +vn 0.0159 -0.6728 -0.7396 +vn -0.0269 0.7035 0.7102 +vn -0.0246 0.7332 0.6796 +vn -0.0150 0.7026 0.7114 +vn -0.0218 0.6913 0.7222 +vn -0.0651 0.7024 0.7088 +vn -0.0096 0.6891 0.7246 +vn -0.0990 0.6859 -0.7209 +vn 0.2016 0.7072 -0.6777 +vn -0.0610 0.6921 -0.7192 +vn 0.2492 0.7044 -0.6646 +vn 0.9791 0.1358 -0.1514 +vn 0.9945 0.0788 -0.0695 +vn 0.9813 0.1295 -0.1422 +vn 0.9959 0.0701 -0.0570 +vn 0.3382 -0.6841 0.6463 +vn 0.6482 -0.5202 0.5561 +vn 0.6059 -0.5500 0.5748 +vn 0.3033 -0.6960 0.6508 +vn -0.3912 -0.6213 0.6789 +vn -0.9790 -0.1595 0.1270 +vn -0.9779 -0.1626 0.1316 +vn -0.9781 -0.1620 0.1307 +vn -0.9792 -0.1590 0.1262 +vn -0.7215 0.5172 -0.4604 +vn -0.0587 0.7412 0.6687 +vn -0.0009 0.7571 0.6533 +vn -0.0706 0.7249 0.6853 +vn 0.0452 0.7456 0.6649 +vn 0.0641 0.7431 0.6661 +vn -0.0443 0.6435 0.7642 +vn 0.0186 0.6559 0.7546 +vn 0.0658 0.6723 0.7373 +vn -0.0659 0.6757 0.7342 +vn 0.0704 0.6983 0.7123 +vn -0.4318 0.6231 -0.6522 +vn -0.7263 0.4343 -0.5328 +vn -0.5855 0.5996 -0.5456 +vn -0.9927 -0.0274 0.1174 +vn -0.9973 -0.0206 0.0701 +vn -0.9941 -0.0257 0.1058 +vn -0.9892 -0.0311 0.1434 +vn -0.7304 -0.5341 0.4258 +vn -0.3724 -0.6763 0.6355 +vn -0.4863 -0.5773 0.6559 +vn -0.1839 -0.6655 0.7234 +vn 0.0639 -0.7673 0.6381 +vn 0.7146 -0.4368 0.5464 +vn 0.7256 -0.4377 0.5310 +vn 0.7218 -0.4374 0.5363 +vn 0.7358 -0.4383 0.5163 +vn 0.9811 0.1569 -0.1129 +vn 0.9964 -0.0765 -0.0374 +vn 0.9936 0.0732 -0.0863 +vn 0.9453 0.2879 -0.1536 +vn 0.6596 0.4793 -0.5789 +vn 0.3154 0.6409 -0.6998 +vn 0.5077 0.6181 -0.6002 +vn -0.0375 0.7475 -0.6632 +vn -0.9402 -0.0160 0.3402 +vn -0.9777 0.0550 -0.2029 +vn -0.2126 -0.7903 0.5747 +vn 0.6816 -0.2928 0.6706 +vn 0.9719 -0.2342 0.0226 +vn 0.2566 0.7654 -0.5902 +vn 0.2382 0.7791 -0.5799 +vn 0.2347 0.7816 -0.5779 +vn 0.2122 0.7974 -0.5649 +vn -0.0969 -0.3282 0.9396 +vn -0.1576 -0.2785 0.9474 +vn 0.0434 -0.4331 0.9003 +vn -0.4439 -0.8772 0.1831 +vn -0.8563 0.1863 0.4818 +vn -0.8331 -0.0821 -0.5470 +vn -0.2723 0.9357 -0.2241 +vn 0.2229 0.1828 -0.9575 +vn 0.8060 0.5442 0.2329 +vn 0.9209 -0.3820 -0.0782 +vn 0.9142 -0.3427 -0.2161 +vn 0.9089 -0.3305 -0.2544 +vn 0.5629 0.7422 -0.3637 +vn 0.8707 -0.2729 -0.4092 +vn -0.9092 0.1992 -0.3657 +vn -0.8950 0.1728 -0.4111 +vn -0.9352 0.2741 -0.2242 +vn -0.9389 0.3075 -0.1544 +vn -0.8421 -0.1244 0.5248 +vn -0.5830 -0.8077 0.0874 +vn -0.0915 -0.4091 0.9079 +vn 0.3547 -0.8241 0.4417 +vn 0.6611 -0.3041 0.6859 +vn 0.8823 -0.4697 -0.0296 +vn 0.8351 0.5225 0.1723 +vn 0.7473 0.1635 -0.6440 +vn -0.0024 0.8023 -0.5969 +vn -0.0009 0.7992 -0.6011 +vn -0.0057 0.8088 -0.5880 +vn -0.0066 0.8105 -0.5856 +vn -0.3075 -0.1441 0.9406 +vn -0.9245 -0.3760 -0.0631 +vn -0.0001 0.7070 0.7072 +vn 0.0000 0.7072 0.7071 +vn -0.0001 0.7069 0.7073 +vn -0.0004 0.7072 0.7070 +vn -0.0002 0.7072 0.7070 +vn -0.0001 0.7071 0.7071 +vn 0.0000 0.7071 0.7071 +vn -0.0005 0.7070 0.7072 +vn 0.0001 -0.7071 -0.7071 +vn 0.0004 -0.7073 -0.7069 +vn 0.0003 -0.7071 -0.7071 +vn -0.0002 -0.7074 -0.7068 +vn -0.0001 -0.7073 -0.7069 +vn 0.8831 0.4588 -0.0980 +vn 0.8750 0.4685 -0.1219 +vn 0.8963 0.4400 -0.0557 +vn 0.9053 -0.2477 -0.3451 +vn 0.5175 -0.2550 0.8168 +vn -0.0506 -0.9671 0.2492 +vn -0.4067 -0.5388 0.7377 +vn -0.9923 0.0412 -0.1171 +vn -0.9959 0.0779 -0.0452 +vn -0.9516 -0.0567 -0.3021 +vn -0.9319 -0.0844 -0.3528 +vn -0.6665 0.4557 -0.5900 +vn 0.2896 -0.8371 0.4641 +vn 0.8349 0.0826 0.5441 +vn 0.8761 -0.3585 -0.3223 +vn 0.5939 0.7622 -0.2577 +vn 0.3287 0.3044 -0.8940 +vn -0.3317 0.9178 -0.2182 +vn -0.6828 0.0936 -0.7246 +vn -0.9379 0.2242 0.2646 +vn -0.9560 0.1660 0.2420 +vn -0.9872 -0.0759 0.1403 +vn -0.9809 -0.1678 0.0985 +vn -0.4803 -0.6207 0.6197 +vn 0.8555 0.4885 -0.1716 +vn 0.0619 0.4692 0.8809 +vn 0.0331 0.5880 0.8082 +vn 0.0216 0.6315 0.7751 +vn -0.0944 0.6347 0.7669 +vn -0.1059 0.6251 0.7734 +vn -0.2204 0.5180 0.8265 +vn -0.0781 -0.8274 -0.5561 +vn -0.0409 -0.7739 -0.6320 +vn -0.0298 -0.7566 -0.6532 +vn 0.0039 -0.8581 -0.5134 +vn 0.0063 -0.9262 -0.3770 +vn 0.0015 -0.7710 -0.6368 +vn -0.3725 -0.8010 -0.4686 +vn -0.3568 -0.8019 -0.4791 +vn -0.4483 -0.7921 -0.4142 +vn -0.6499 -0.0363 -0.7592 +vn -0.8897 -0.2207 0.3997 +vn -0.4899 0.8261 0.2785 +vn -0.2934 0.5594 0.7752 +vn 0.6730 0.6521 0.3491 +vn 0.8158 -0.0390 0.5770 +vn 0.9305 0.0731 -0.3589 +vn 0.9053 0.2674 -0.3300 +vn 0.8835 0.3480 -0.3136 +vn 0.2085 0.3226 0.9233 +vn 0.8017 0.5368 -0.2630 +vn -0.9814 0.1824 -0.0604 +vn -0.9684 0.2332 -0.0889 +vn -0.9938 -0.0748 0.0821 +vn -0.9845 -0.1334 0.1140 +vn -0.3206 -0.5427 -0.7763 +vn -0.3164 -0.5623 -0.7640 +vn -0.3369 -0.4521 -0.8259 +vn -0.3423 -0.4154 -0.8428 +vn 0.5709 -0.7850 -0.2406 +vn 0.7660 0.0658 -0.6395 +vn 0.9308 -0.2262 0.2873 +vn 0.7485 0.6418 0.1669 +vn 0.5492 0.4155 0.7251 +vn -0.0315 0.8019 0.5966 +vn -0.0007 0.8392 0.5438 +vn -0.1178 0.6738 0.7295 +vn -0.1519 0.6129 0.7754 +vn -0.2705 -0.8019 -0.5327 +vn -0.5645 -0.3380 -0.7531 +vn -0.0002 -0.7071 0.7072 +vn -0.0001 -0.7071 0.7071 +vn 0.0000 -0.7073 0.7069 +vn -0.0003 -0.7070 0.7072 +vn -0.0004 -0.7071 0.7072 +vn -0.0001 -0.7072 0.7071 +vn 0.0001 -0.7073 0.7069 +vn -0.0001 -0.7070 0.7072 +vn -0.0002 -0.7070 0.7072 +vn 0.0001 0.7072 -0.7070 +vn 0.0000 0.7072 -0.7071 +vn 0.0001 0.7073 -0.7069 +vn 0.0002 0.7073 -0.7070 +vn -0.0125 -0.9568 0.2904 +vn -0.0254 -0.9761 0.2158 +vn -0.0894 -0.9094 0.4062 +vn 0.0531 -0.9819 0.1816 +vn -0.0478 -0.9984 -0.0315 +vn -0.0092 -0.9520 -0.3060 +vn 0.0044 -0.9328 -0.3604 +vn -0.0096 -0.8664 -0.4992 +vn -0.0012 -0.8647 -0.5023 +vn 0.0013 0.4199 0.9076 +vn 0.1207 0.2698 0.9553 +vn 0.0064 0.0345 0.9994 +vn 0.0016 -0.0893 0.9960 +vn -0.0049 -0.3192 0.9477 +vn 0.0095 -0.4088 0.9126 +vn 0.0182 -0.4983 0.8668 +vn -0.0015 -0.5068 0.8621 +vn -0.0228 0.2399 0.9705 +vn 0.0003 0.8955 0.4451 +vn 0.0002 0.8952 0.4456 +vn -0.0000 0.9448 0.3275 +vn 0.0000 0.9450 0.3272 +vn -0.0001 0.9972 0.0745 +vn 0.0000 0.9972 0.0742 +vn -0.0000 0.9754 -0.2206 +vn -0.0079 0.9794 -0.2017 +vn 0.0014 0.9706 -0.2409 +vn -0.0115 0.9212 -0.3890 +vn 0.0004 0.8911 -0.4539 +vn 0.0149 -0.2281 0.9735 +vn 0.0019 -0.1786 0.9839 +vn 0.0012 -0.4439 0.8961 +vn 0.0245 -0.6200 0.7842 +vn -0.0008 -0.6489 0.7609 +vn 0.0025 -0.8057 0.5924 +vn 0.0253 -0.9193 0.3927 +vn -0.0065 -0.9210 0.3896 +vn 0.0014 -0.9891 0.1474 +vn 0.0205 -0.9984 -0.0527 +vn 0.0053 -0.9928 -0.1199 +vn 0.0021 -0.9384 -0.3456 +vn 0.0168 -0.8962 -0.4432 +vn 0.0067 -0.8215 -0.5702 +vn 0.0215 -0.6113 -0.7911 +vn 0.0081 -0.6749 -0.7379 +vn 0.0049 -0.4686 -0.8834 +vn 0.0046 -0.2062 -0.9785 +vn 0.0119 -0.2251 -0.9743 +vn 0.0012 0.9293 -0.3694 +vn 0.0002 0.9291 -0.3697 +vn 0.0184 0.9830 -0.1827 +vn 0.0304 0.9746 -0.2220 +vn -0.0242 0.9921 0.1234 +vn 0.0094 0.9711 0.2385 +vn 0.0096 0.9309 0.3652 +vn -0.0108 0.9282 0.3719 +vn -0.0161 -0.2682 -0.9632 +vn -0.0041 -0.2175 -0.9761 +vn -0.0520 -0.2572 -0.9650 +vn -0.0318 -0.3834 -0.9230 +vn 0.0638 -0.0057 -0.9979 +vn -0.0251 0.1832 -0.9828 +vn 0.0246 0.3437 -0.9388 +vn -0.0094 0.4187 -0.9081 +vn -0.0147 0.2349 -0.9719 +vn 0.9987 0.0474 0.0166 +vn 0.9984 0.0546 0.0162 +vn 0.9993 0.0334 0.0152 +vn 0.9997 0.0220 0.0051 +vn 0.9997 0.0224 0.0006 +vn 0.9997 0.0245 -0.0056 +vn 0.9998 0.0214 -0.0029 +vn 0.9990 0.0395 -0.0210 +vn 0.9987 0.0436 -0.0247 +vn -0.0130 0.1161 -0.9932 +vn 0.0044 -0.0194 -0.9998 +vn 0.0257 -0.0412 -0.9988 +vn -0.0025 -0.0399 -0.9992 +vn -0.0428 -0.0161 -0.9990 +vn 0.0217 -0.0351 -0.9991 +vn -0.0621 -0.0108 -0.9980 +vn 0.0014 -0.5417 -0.8406 +vn -0.0062 -0.6366 -0.7712 +vn -0.0078 -0.3631 -0.9317 +vn -0.0003 -0.0417 -0.9991 +vn 0.0048 -0.0430 -0.9991 +vn 0.0013 -0.0618 -0.9981 +vn 0.0005 -0.0312 -0.9995 +vn 0.0001 -0.0329 -0.9995 +vn 1.0000 -0.0008 0.0015 +vn 0.9999 0.0031 0.0112 +vn 1.0000 0.0019 -0.0002 +vn 0.0037 0.7142 -0.6999 +vn 0.0028 0.7172 -0.6968 +vn 0.0036 0.7146 -0.6995 +vn 0.0027 0.7177 -0.6964 +vn -0.6921 0.6582 0.2963 +vn -0.6840 0.6896 0.2380 +vn -0.6870 0.6610 0.3018 +vn -0.6712 0.6742 -0.3081 +vn -0.6841 0.6585 -0.3138 +vn -0.6727 0.6806 -0.2902 +vn -0.6853 0.6848 0.2476 +vn -0.6997 0.7111 0.0693 +vn -0.7035 0.7096 0.0383 +vn -0.6837 0.7070 -0.1807 +vn -0.6845 0.7184 -0.1240 +vn 0.6483 0.7517 -0.1212 +vn 0.7041 0.6928 0.1556 +vn 0.7058 0.6913 -0.1546 +vn 0.7074 0.7051 0.0492 +vn 0.7126 0.6992 0.0574 +vn 0.7068 0.6842 -0.1795 +vn 0.7014 0.6739 0.2321 +vn 0.7102 0.6561 0.2554 +vn 0.6885 0.6496 0.3223 +vn 0.6710 0.6700 0.3174 +vn -0.8835 0.3600 -0.2997 +vn -0.9047 0.2978 -0.3045 +vn -0.9013 0.3089 -0.3038 +vn -0.9239 0.2263 -0.3084 +vn -0.8244 -0.3540 0.4417 +vn 0.9689 0.1455 -0.2001 +vn 0.9727 0.1425 -0.1831 +vn 0.9737 0.1416 -0.1786 +vn 0.9815 0.1340 -0.1370 +vn 0.6215 -0.5010 0.6022 +vn 0.0652 0.6766 -0.7334 +vn 0.1384 0.7034 -0.6972 +vn 0.1116 0.6942 -0.7111 +vn 0.1898 0.7193 -0.6683 +vn 0.9999 -0.0120 0.0103 +vn 1.0000 -0.0007 0.0012 +vn 0.9999 -0.0127 0.0106 +vn 0.9966 0.0307 -0.0760 +vn 0.9875 0.1220 -0.1002 +vn 0.9838 -0.1783 -0.0188 +vn 0.9428 0.2999 -0.1453 +vn 0.6238 0.4961 -0.6040 +vn -0.0950 0.7160 -0.6916 +vn -0.1688 0.7430 -0.6477 +vn -0.1295 0.7293 -0.6719 +vn -0.0609 0.7016 -0.7099 +vn -0.9546 0.2248 -0.1955 +vn -0.9624 0.1644 -0.2163 +vn -0.9657 0.1172 -0.2317 +vn -0.9650 0.0205 -0.2613 +vn -0.3859 -0.4839 0.7854 +vn 0.4558 -0.2876 0.8423 +vn -0.0002 0.7366 0.6764 +vn -0.0177 0.7440 0.6679 +vn 0.0036 0.7428 0.6695 +vn 0.0019 0.8466 0.5322 +vn 0.0234 0.9153 0.4020 +vn 0.0144 0.9287 0.3706 +vn -0.0074 0.9417 0.3364 +vn 0.8350 0.3606 0.4156 +vn 0.7950 0.4085 0.4485 +vn 0.6193 0.7081 0.3392 +vn 0.5497 0.8287 0.1050 +vn 0.0069 0.9979 -0.0641 +vn 0.0045 0.1750 0.9846 +vn 0.0189 0.0018 0.9998 +vn 0.0357 0.0198 0.9992 +vn 0.0022 -0.0422 0.9991 +vn 0.0062 -0.0391 0.9992 +vn -0.0000 -0.0379 0.9993 +vn 0.0252 -0.0430 0.9988 +vn -0.0000 -0.0378 0.9993 +vn 0.0723 -0.9373 0.3410 +vn 0.0405 -0.8608 0.5073 +vn 0.0183 -0.7265 0.6869 +vn 0.0127 -0.5626 0.8266 +vn -0.0002 -0.4374 0.8993 +vn -0.0016 -0.5173 0.8558 +vn 0.0134 -0.0294 0.9995 +vn 0.0362 -0.0391 0.9986 +vn -0.0008 0.7882 0.6155 +vn -0.0015 0.0134 0.9999 +vn 0.0032 -0.0245 0.9997 +vn 0.0158 0.0075 0.9998 +vn 0.0049 -0.0237 0.9997 +vn 0.0066 -0.0190 0.9998 +vn 0.0821 -0.0417 0.9958 +vn 0.0090 -0.6179 0.7862 +vn 0.9999 -0.0064 -0.0119 +vn 1.0000 -0.0014 -0.0024 +vn 1.0000 -0.0038 0.0042 +vn 1.0000 0.0051 0.0062 +vn 0.9998 -0.0139 -0.0142 +vn 0.0058 -0.7188 -0.6952 +vn -0.0241 -0.7111 -0.7027 +vn -0.0073 -0.7147 -0.6994 +vn 0.0502 -0.7206 -0.6916 +vn -0.0137 0.7107 0.7034 +vn -0.0087 0.7116 0.7026 +vn -0.0041 -0.7602 -0.6496 +vn -0.0006 -0.7176 -0.6964 +vn -0.0010 -0.7209 -0.6930 +vn -0.0210 -0.7256 0.6878 +vn 0.0017 -0.7184 0.6956 +vn 0.0100 -0.7130 0.7011 +vn 0.0002 -0.7069 -0.7073 +vn 0.0000 -0.7069 -0.7073 +vn -0.0169 0.7216 -0.6921 +vn -0.0836 0.7093 -0.6999 +vn 0.0010 0.8483 -0.5295 +vn 1.0000 0.0071 -0.0064 +vn 0.0101 -0.7169 0.6971 +vn 0.0273 -0.7117 0.7019 +vn 0.0035 0.7152 0.6989 +vn 0.0036 0.7155 0.6986 +vn 0.0036 0.7153 0.6988 +vn 0.8835 0.3600 0.2997 +vn 0.9047 0.2978 0.3045 +vn 0.9013 0.3089 0.3038 +vn 0.9239 0.2263 0.3084 +vn 0.8215 -0.3565 -0.4450 +vn -0.9689 0.1455 0.2001 +vn -0.9727 0.1425 0.1831 +vn -0.9737 0.1416 0.1786 +vn -0.9815 0.1340 0.1370 +vn -0.6218 -0.5010 -0.6020 +vn -0.0652 0.6766 0.7334 +vn -0.1384 0.7034 0.6972 +vn -0.1116 0.6942 0.7111 +vn -0.1898 0.7193 0.6683 +vn 0.0021 0.7426 -0.6698 +vn -0.0283 0.7452 -0.6663 +vn -0.0015 0.7381 -0.6747 +vn -0.0003 -0.7070 -0.7072 +vn 0.9877 0.1534 0.0303 +vn 0.8903 -0.3664 -0.2704 +vn -0.9645 0.1594 0.2106 +vn -0.9034 0.3440 0.2562 +vn -0.9414 0.2442 0.2326 +vn -0.9839 0.0348 0.1753 +vn -0.8175 -0.2571 -0.5154 +vn -0.4820 -0.8672 -0.1251 +vn -0.4210 0.6178 0.6642 +vn -0.2742 0.6951 0.6645 +vn -0.4955 0.5689 0.6564 +vn -0.1875 0.7305 0.6566 +vn 0.6174 0.4893 0.6159 +vn 0.5763 0.5386 0.6147 +vn 0.5965 0.5150 0.6156 +vn 0.5524 0.5650 0.6128 +vn 0.9999 0.0037 -0.0133 +vn 0.9995 0.0293 0.0081 +vn 1.0000 0.0026 -0.0038 +vn -0.0082 -0.7194 0.6946 +vn -0.0378 -0.7175 0.6956 +vn 0.0209 -0.7092 0.7047 +vn 0.0232 0.9158 -0.4009 +vn -0.0028 0.9390 -0.3438 +vn 0.0159 0.9279 -0.3726 +vn 0.7920 0.4290 -0.4344 +vn 0.7213 0.4555 -0.5218 +vn 0.7837 0.4326 -0.4457 +vn 0.7007 0.4616 -0.5441 +vn 0.5247 0.8265 -0.2040 +vn -0.0220 0.0545 0.9983 +vn -0.0155 0.0636 0.9979 +vn -0.0172 0.0607 0.9980 +vn -0.0101 0.0705 0.9975 +vn -0.0682 -0.8014 0.5943 +vn 0.0254 -0.6757 0.7367 +vn -0.0205 -0.7414 0.6708 +vn 0.0731 -0.5994 0.7971 +vn -0.0171 -0.9997 -0.0195 +vn 0.0271 -0.9971 -0.0708 +vn 0.9996 -0.0111 0.0271 +vn 0.9996 -0.0189 0.0195 +vn 0.9996 -0.0096 0.0270 +vn 0.9997 -0.0050 0.0259 +vn 0.9998 0.0048 0.0175 +vn 0.9999 0.0071 0.0146 +vn 0.9998 -0.0156 0.0118 +vn 0.9996 -0.0127 -0.0265 +vn 0.9997 -0.0144 -0.0179 +vn 0.9984 -0.0044 -0.0561 +vn 0.9996 -0.0269 0.0067 +vn -0.0010 -0.9965 0.0840 +vn -0.0056 -0.9970 0.0777 +vn -0.0040 -0.9968 0.0799 +vn -0.0084 -0.9972 0.0736 +vn 0.0001 -0.8121 -0.5835 +vn 0.0133 -0.7992 -0.6010 +vn 0.0065 -0.8061 -0.5917 +vn -0.0070 -0.8188 -0.5740 +vn -0.0234 0.0123 -0.9997 +vn 0.0044 0.0446 -0.9990 +vn 0.9998 -0.0201 0.0090 +vn 0.9999 -0.0136 -0.0015 +vn 0.9998 -0.0214 0.0063 +vn 0.9999 -0.0134 -0.0007 +vn 0.9998 -0.0218 -0.0025 +vn 0.9996 -0.0263 -0.0139 +vn 0.9992 -0.0372 -0.0128 +vn 0.9996 -0.0079 -0.0283 +vn 0.9995 -0.0050 -0.0309 +vn 0.9990 -0.0052 -0.0444 +vn 0.9991 -0.0047 -0.0429 +vn -0.9921 0.0144 0.1245 +vn -0.9992 0.0129 -0.0383 +vn -0.9972 -0.0253 -0.0710 +vn -0.9941 0.0421 -0.0995 +vn -0.9978 -0.0168 -0.0643 +vn -0.9966 -0.0056 -0.0826 +vn -0.9956 0.0158 0.0926 +vn -0.9974 0.0219 0.0683 +vn -0.9946 0.0496 0.0913 +vn -0.9985 -0.0185 -0.0513 +vn -0.9944 0.0365 -0.0997 +vn -0.9992 0.0238 -0.0327 +vn -0.9996 0.0232 -0.0175 +vn -0.9999 0.0068 -0.0157 +vn -0.9997 0.0212 -0.0079 +vn -0.9999 -0.0146 -0.0037 +vn -0.9998 -0.0180 -0.0094 +vn -0.9998 -0.0105 -0.0163 +vn -0.9992 -0.0145 -0.0368 +vn -0.9991 0.0370 -0.0191 +vn -0.9995 -0.0300 -0.0114 +vn -0.9998 -0.0106 0.0152 +vn -0.9994 -0.0124 0.0335 +vn -0.9998 -0.0178 0.0102 +vn -0.9988 -0.0156 0.0474 +vn -0.9970 -0.0334 0.0692 +vn -0.9887 0.1359 -0.0641 +vn -0.9966 0.0807 -0.0171 +vn -0.9965 -0.0777 -0.0320 +vn -0.9964 -0.0812 -0.0228 +vn -0.9947 0.1030 0.0015 +vn -0.9914 -0.1307 -0.0059 +vn -0.9975 0.0004 0.0700 +vn -0.9967 -0.0783 0.0193 +vn -0.9884 0.1509 0.0179 +vn -0.9963 -0.0856 0.0099 +vn -0.9971 0.0719 0.0266 +vn -0.9963 0.0755 0.0419 +vn -0.9969 -0.0728 0.0311 +vn -0.9996 -0.0279 0.0104 +vn -0.9993 0.0339 0.0143 +vn -0.9996 0.0228 0.0164 +vn -0.9999 -0.0124 0.0038 +vn -0.9998 0.0187 0.0075 +vn -0.9999 0.0048 0.0117 +vn -0.9993 0.0245 0.0293 +vn -0.9922 -0.0252 0.1221 +vn 0.6979 -0.1521 -0.6999 +vn 0.6901 -0.0303 -0.7230 +vn 0.6897 -0.0305 -0.7235 +vn 0.7010 -0.1466 -0.6979 +vn 0.0489 -0.0432 -0.9979 +vn 0.5698 -0.3818 0.7277 +vn 0.5722 -0.4387 0.6929 +vn 0.6034 -0.4891 0.6299 +vn 0.5432 -0.8145 0.2039 +vn 0.5815 -0.7712 0.2592 +vn 0.5733 -0.7095 0.4098 +vn 0.5300 -0.8446 -0.0757 +vn 0.5392 -0.8412 0.0399 +vn 0.7004 -0.7129 -0.0337 +vn 0.4959 -0.8251 -0.2708 +vn 0.6785 -0.6561 -0.3304 +vn 0.5727 -0.6536 -0.4948 +vn 0.5800 -0.6551 -0.4842 +vn 0.6165 -0.5509 -0.5626 +vn 0.6849 -0.3228 -0.6532 +vn 0.7116 -0.3925 -0.5827 +vn 0.6156 -0.5527 0.5617 +vn 0.4879 -0.7142 0.5019 +vn 0.7030 -0.0841 0.7062 +vn 0.7262 -0.1655 0.6672 +vn 0.8903 -0.4198 0.1766 +vn 0.6049 -0.7952 0.0413 +vn -0.5802 -0.4149 0.7008 +vn 0.5499 -0.6861 0.4763 +vn 0.9378 -0.3366 -0.0849 +vn 0.7477 -0.0287 0.6634 +vn 0.7444 -0.0295 0.6671 +vn 0.1021 -0.0421 0.9939 +vn 0.6314 0.5620 0.5344 +vn 0.5844 0.5883 -0.5589 +vn 0.6686 0.6700 -0.3227 +vn 0.9946 0.1040 0.0065 +vn 0.6575 0.6691 0.3465 +vn -0.0090 -0.9819 0.1892 +vn 0.0269 -0.9658 0.2581 +vn -0.0352 -0.9534 0.2995 +vn 0.0792 -0.9957 -0.0480 +vn 0.1795 -0.9791 0.0952 +vn -0.1735 -0.9756 -0.1346 +vn -0.0337 -0.9986 0.0406 +vn 0.0049 -0.9854 -0.1700 +vn 0.0243 -0.9526 -0.3033 +vn 0.0030 -0.9883 -0.1524 +vn -0.0116 -0.9972 0.0745 +vn -0.1088 -0.9941 -0.0024 +vn 0.0066 -0.9449 -0.3273 +vn 0.2252 -0.8949 -0.3853 +vn -0.0134 -0.9155 -0.4021 +vn -0.0352 -0.9425 -0.3324 +vn -0.0202 -0.9407 -0.3387 +vn 0.0112 -0.9984 -0.0548 +vn -0.1635 -0.9582 -0.2348 +vn 0.1763 -0.9203 0.3494 +vn 0.3571 -0.9315 0.0698 +vn -0.1419 -0.9672 0.2107 +vn -0.0038 -0.9118 0.4106 +vn 0.1339 -0.9076 0.3980 +vn 0.0023 -0.9482 0.3176 +vn 0.0003 -0.9311 0.3646 +vn 0.0069 -0.8924 0.4511 +vn 0.0042 -0.9676 0.2525 +vn 0.0030 -0.8440 0.5364 +vn 0.0180 -0.9901 0.1391 +vn 0.0042 -0.9956 0.0935 +vn -0.6836 -0.6891 0.2405 +vn -0.8750 -0.4750 -0.0930 +vn -0.7143 -0.6870 0.1331 +vn -0.7010 -0.6984 0.1444 +vn -0.7108 -0.6965 -0.0978 +vn -0.6791 -0.7337 0.0213 +vn -0.7134 -0.6863 -0.1417 +vn -0.8754 -0.4746 0.0917 +vn -0.6657 -0.7042 -0.2468 +vn -0.0110 -0.8878 -0.4601 +vn 0.0017 -0.9696 -0.2447 +vn -0.0212 -0.9892 -0.1452 +vn -0.0008 -0.9112 -0.4120 +vn 0.0060 -0.8475 -0.5308 +vn 0.6827 -0.6922 -0.2342 +vn 0.7130 -0.6921 -0.1121 +vn 0.6849 -0.6760 -0.2718 +vn 0.6609 -0.7500 0.0279 +vn 0.7157 -0.6813 0.1537 +vn 0.5860 -0.7685 0.2569 +vn 0.8731 -0.4771 -0.1001 +vn 0.5313 -0.2421 0.8118 +vn 0.3646 0.0239 0.9309 +vn 0.0009 -0.1764 0.9843 +vn 0.8979 -0.3631 0.2487 +vn 0.9941 -0.1052 0.0260 +vn 0.7266 -0.1141 0.6775 +vn 0.8899 -0.2870 -0.3545 +vn 0.9947 -0.1016 -0.0166 +vn 0.9951 -0.0974 0.0140 +vn 0.9983 -0.0296 0.0497 +vn 0.9969 -0.0757 -0.0230 +vn 0.9977 -0.0666 -0.0126 +vn 0.8276 -0.2779 -0.4876 +vn 0.5633 -0.7122 -0.4190 +vn 0.5462 -0.6871 -0.4791 +vn 0.7461 -0.5922 -0.3044 +vn 0.9190 -0.3634 -0.1529 +vn 0.6641 -0.7447 -0.0658 +vn 0.6630 -0.7356 0.1390 +vn 0.8973 -0.3136 0.3107 +vn 0.6587 -0.6885 0.3036 +vn 0.7660 -0.2718 0.5826 +vn 0.5719 -0.7047 0.4199 +vn 0.5592 -0.6892 0.4607 +vn 0.1364 -0.6922 0.7087 +vn 0.2096 -0.6915 0.6913 +vn 0.2007 -0.7141 0.6706 +vn -0.1256 -0.6870 0.7157 +vn 0.0324 -0.6657 0.7455 +vn -0.2064 -0.6694 0.7136 +vn -0.2457 -0.6378 0.7300 +vn 0.3437 -0.1636 0.9247 +vn 0.6086 0.0130 0.7933 +vn 0.3288 -0.2037 0.9222 +vn 0.0269 0.2311 0.9726 +vn 0.0294 0.2480 0.9683 +vn -0.2180 -0.0879 0.9720 +vn -0.1467 -0.0984 0.9843 +vn -0.2059 -0.0661 0.9763 +vn -0.3633 0.0098 0.9316 +vn -0.5376 0.0330 0.8425 +vn -0.7148 -0.2149 0.6655 +vn -0.6401 -0.1372 0.7560 +vn -0.6520 -0.6532 0.3850 +vn -0.8142 0.4166 0.4044 +vn -0.8614 -0.4360 0.2606 +vn -0.8374 -0.4836 0.2547 +vn -0.9395 -0.2329 -0.2514 +vn -0.9833 0.1801 -0.0255 +vn -0.9782 0.2069 -0.0192 +vn -0.9641 -0.2114 -0.1610 +vn -0.6350 -0.6870 -0.3532 +vn -0.8672 0.2776 -0.4134 +vn -0.5764 0.0261 -0.8168 +vn -0.6290 0.0038 -0.7774 +vn -0.7152 -0.1191 -0.6887 +vn -0.7182 -0.1433 -0.6809 +vn -0.5405 -0.0183 -0.8412 +vn -0.3234 -0.0516 -0.9449 +vn -0.4813 0.0227 -0.8763 +vn -0.1620 0.0977 -0.9819 +vn 0.1484 -0.0156 -0.9888 +vn 0.1294 -0.0297 -0.9912 +vn 0.4867 0.0279 -0.8731 +vn 0.3180 -0.0668 -0.9457 +vn 0.2029 -0.0575 -0.9775 +vn 0.6022 0.0284 -0.7978 +vn 0.6907 -0.1535 -0.7066 +vn 0.7002 -0.1998 -0.6854 +vn 0.9469 -0.0894 -0.3089 +vn 0.8302 0.3060 -0.4661 +vn 0.9747 -0.1527 0.1630 +vn 0.9974 0.0726 -0.0051 +vn 0.8699 -0.0732 0.4877 +vn 0.0288 -0.9959 -0.0859 +vn 0.0245 -0.9700 -0.2419 +vn 0.0709 -0.9536 -0.2927 +vn -0.0005 -0.9998 -0.0175 +vn 0.0308 -0.9877 0.1535 +vn -0.0197 -0.9518 0.3060 +vn -0.0701 -0.9102 0.4083 +vn -0.0000 1.0000 -0.0000 +vn 0.0001 1.0000 0.0000 +vn -0.0001 1.0000 0.0000 +vn 0.0002 1.0000 -0.0000 +vn -0.0001 1.0000 -0.0001 +vn 0.7158 -0.6294 -0.3025 +vn 0.7035 -0.6104 0.3639 +vn 0.6795 -0.7026 0.2112 +vn -0.0156 -0.0869 0.9961 +vn -0.9945 -0.1028 -0.0187 +vn -0.8882 -0.2880 -0.3580 +vn -0.8875 -0.2902 0.3578 +vn -0.9938 -0.1108 -0.0096 +vn -0.9973 -0.0643 -0.0359 +vn -0.9977 -0.0670 -0.0087 +vn -0.9974 -0.0710 0.0105 +vn -0.9957 -0.0859 0.0345 +vn -0.5567 -0.6889 -0.4642 +vn -0.5599 -0.7023 -0.4397 +vn -0.5648 -0.7096 0.4213 +vn -0.7269 -0.6328 0.2667 +vn -0.6173 -0.7202 -0.3166 +vn -0.0396 -0.9953 0.0887 +vn -0.0613 -0.9587 0.2777 +vn -0.0924 -0.9516 0.2932 +vn 0.0039 -0.9915 0.1299 +vn -0.0281 -0.9974 -0.0666 +vn 0.0082 -0.9542 -0.2990 +vn -0.0014 -0.9744 -0.2248 +vn 0.0497 -0.9110 -0.4094 +vn -0.0039 -0.6937 0.7203 +vn -0.0012 -0.6995 0.7146 +vn -0.7093 -0.6390 0.2976 +vn -0.7924 -0.3933 0.4662 +vn -0.2284 -0.6850 -0.6918 +vn -0.1697 -0.6600 -0.7318 +vn 0.0104 -0.3051 -0.9523 +vn 0.0811 -0.5776 -0.8122 +vn 0.1089 -0.7203 -0.6851 +vn -0.0077 -0.0657 -0.9978 +vn -0.0024 -0.7012 -0.7130 +vn 0.0032 -0.6878 -0.7259 +vn 0.7027 -0.6136 -0.3602 +vn 0.7995 -0.3843 -0.4616 +vn -0.0082 -0.0596 -0.9982 +vn -0.7113 -0.6351 -0.3012 +vn -0.7934 -0.3907 -0.4668 +vn 0.9993 -0.0244 0.0274 +vn 0.9987 -0.0235 0.0448 +vn 0.9992 -0.0085 0.0401 +vn 0.9995 -0.0051 -0.0296 +vn 0.9997 0.0011 -0.0228 +vn 1.0000 0.0046 -0.0034 +vn 0.9993 -0.0284 -0.0243 +vn 0.9998 0.0094 -0.0198 +vn 0.9994 0.0334 -0.0104 +vn 0.9991 -0.0061 -0.0417 +vn 0.9992 -0.0288 -0.0262 +vn 0.9993 -0.0354 -0.0123 +vn 0.9905 -0.0243 0.1354 +vn 0.9985 -0.0252 0.0496 +vn 0.9969 -0.0216 0.0751 +vn 0.9994 0.0332 -0.0041 +vn 0.9991 0.0158 0.0394 +vn 0.9991 0.0276 0.0313 +vn 0.9995 0.0265 0.0182 +vn 0.9996 -0.0246 -0.0172 +vn 0.9998 -0.0167 -0.0129 +vn 0.9997 0.0221 -0.0041 +vn 0.9967 0.0804 -0.0089 +vn 0.9963 0.0770 -0.0383 +vn 0.9979 0.0611 -0.0190 +vn 0.9990 0.0383 -0.0241 +vn 0.9879 -0.1544 -0.0135 +vn 0.9631 -0.2449 -0.1117 +vn 0.9934 -0.1127 0.0225 +vn 0.9952 -0.0946 0.0254 +vn 0.9989 0.0474 0.0033 +vn 0.9969 0.0757 0.0228 +vn 0.9984 0.0492 0.0276 +vn 0.9990 -0.0395 0.0212 +vn 0.9986 0.0476 0.0230 +vn 0.9989 0.0466 -0.0060 +vn 0.9996 -0.0185 0.0209 +vn 0.9997 0.0244 0.0013 +vn 0.9988 0.0284 0.0404 +vn 0.9987 -0.0457 0.0236 +vn 0.9789 0.0218 0.2033 +vn -0.9985 -0.0416 0.0361 +vn -0.9985 -0.0485 0.0256 +vn -0.9988 -0.0370 0.0321 +vn -0.9988 -0.0413 0.0249 +vn -0.9991 -0.0238 0.0353 +vn -0.9988 0.0341 0.0346 +vn -0.9987 0.0393 0.0311 +vn -0.9987 0.0369 0.0356 +vn -0.9989 0.0354 0.0318 +vn -0.9989 0.0286 0.0368 +vn -0.9991 0.0292 -0.0311 +vn -0.9991 0.0346 -0.0243 +vn -0.9993 0.0380 -0.0005 +vn -0.9985 0.0282 -0.0466 +vn -0.9987 0.0357 -0.0365 +vn -0.2530 -0.9674 -0.0057 +vn -0.0338 -0.9396 0.3406 +vn -0.0886 -0.9520 -0.2931 +vn 0.1183 -0.9467 -0.2997 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 4/4/4 5/5/5 +f 5/5/5 4/4/4 6/6/6 +f 3/3/3 2/2/2 4/4/4 +f 5/5/5 7/7/7 1/1/8 +f 5/5/5 6/6/6 7/7/7 +f 8/8/9 9/9/10 10/10/11 +f 8/8/9 11/11/12 9/9/10 +f 12/12/13 8/8/14 13/13/15 +f 13/13/15 8/8/14 10/10/16 +f 13/13/17 10/10/18 9/9/19 +f 13/13/17 9/9/19 14/14/20 +f 14/14/21 9/9/21 15/15/21 +f 14/14/22 15/15/23 16/16/24 +f 16/16/24 15/15/23 11/11/25 +f 16/16/26 11/11/27 12/12/28 +f 12/12/28 11/11/27 8/8/29 +f 14/14/30 17/17/31 13/13/32 +f 13/13/32 17/17/31 18/18/33 +f 13/13/32 18/18/33 12/12/34 +f 12/12/34 18/18/33 19/19/35 +f 12/12/34 19/19/35 20/20/36 +f 12/12/34 20/20/36 16/16/37 +f 16/16/37 20/20/36 21/21/38 +f 16/16/37 21/21/38 14/14/30 +f 14/14/30 21/21/38 22/22/39 +f 14/14/30 22/22/39 17/17/31 +f 2/2/40 18/18/41 17/17/42 +f 2/2/40 17/17/42 4/4/43 +f 4/4/44 17/17/44 22/22/44 +f 4/4/45 22/22/45 6/6/45 +f 6/6/46 22/22/46 21/21/46 +f 6/6/47 21/21/48 7/7/49 +f 7/7/49 21/21/48 20/20/50 +f 7/7/51 20/20/52 1/1/53 +f 1/1/53 20/20/52 19/19/54 +f 1/1/55 19/19/56 18/18/57 +f 1/1/55 18/18/57 2/2/58 +f 3/3/59 5/5/60 23/23/61 +f 23/23/61 5/5/60 24/24/62 +f 1/1/63 3/3/64 25/25/65 +f 25/25/65 3/3/64 23/23/66 +f 5/5/67 1/1/68 24/24/69 +f 24/24/69 1/1/68 25/25/70 +f 24/24/71 25/25/71 23/23/71 +f 15/15/72 9/9/10 11/11/12 +f 26/26/73 27/27/73 28/28/73 +f 28/28/74 29/29/74 30/30/74 +f 30/30/75 31/31/75 26/26/75 +f 32/32/76 33/33/77 34/34/78 +f 35/35/79 32/32/76 34/34/78 +f 36/36/80 35/35/81 34/34/82 +f 36/36/80 34/34/82 37/37/83 +f 37/37/84 34/34/85 33/33/86 +f 37/37/84 33/33/86 38/38/87 +f 38/38/88 33/33/89 32/32/90 +f 38/38/88 32/32/90 39/39/91 +f 39/39/92 32/32/93 35/35/94 +f 39/39/92 35/35/94 36/36/95 +f 37/37/96 40/40/97 36/36/98 +f 36/36/98 40/40/97 41/41/99 +f 36/36/98 41/41/99 42/42/100 +f 36/36/98 42/42/100 39/39/101 +f 39/39/101 42/42/100 43/43/102 +f 39/39/101 43/43/102 38/38/103 +f 38/38/103 43/43/102 44/44/104 +f 38/38/103 44/44/104 37/37/96 +f 37/37/96 44/44/104 40/40/97 +f 27/27/105 41/41/106 40/40/107 +f 27/27/105 40/40/107 28/28/108 +f 28/28/109 40/40/110 29/29/111 +f 29/29/111 40/40/110 44/44/112 +f 29/29/113 44/44/113 30/30/113 +f 30/30/114 44/44/115 43/43/116 +f 30/30/114 43/43/116 31/31/117 +f 31/31/118 43/43/119 42/42/120 +f 31/31/118 42/42/120 26/26/121 +f 26/26/122 42/42/123 27/27/124 +f 27/27/124 42/42/123 41/41/125 +f 28/28/126 30/30/127 45/45/128 +f 45/45/128 30/30/127 46/46/129 +f 26/26/130 28/28/130 45/45/130 +f 46/46/131 26/26/131 45/45/131 +f 30/30/132 26/26/132 46/46/132 +f 47/47/133 48/48/134 49/49/135 +f 47/47/133 50/50/136 48/48/134 +f 49/49/137 51/51/137 52/52/137 +f 52/52/138 50/50/136 47/47/133 +f 53/53/139 54/54/140 55/55/141 +f 56/56/142 55/55/143 57/57/144 +f 56/56/142 57/57/144 58/58/145 +f 58/58/146 57/57/147 54/54/148 +f 58/58/146 54/54/148 59/59/149 +f 59/59/150 54/54/151 60/60/152 +f 60/60/152 54/54/151 53/53/153 +f 60/60/154 53/53/155 56/56/156 +f 56/56/156 53/53/155 55/55/157 +f 60/60/158 61/61/159 62/62/160 +f 60/60/158 62/62/160 59/59/161 +f 56/56/162 63/63/163 64/64/164 +f 59/59/161 62/62/160 65/65/165 +f 59/59/161 65/65/165 58/58/166 +f 56/56/162 64/64/164 60/60/158 +f 60/60/158 64/64/164 61/61/159 +f 58/58/166 63/63/163 56/56/162 +f 58/58/166 65/65/165 63/63/163 +f 48/48/167 63/63/167 49/49/167 +f 49/49/168 63/63/169 65/65/170 +f 49/49/168 65/65/170 51/51/171 +f 51/51/172 65/65/173 62/62/174 +f 51/51/172 62/62/174 52/52/175 +f 52/52/176 62/62/177 61/61/178 +f 52/52/176 61/61/178 50/50/179 +f 50/50/180 61/61/181 64/64/182 +f 50/50/180 64/64/182 48/48/183 +f 48/48/184 64/64/184 63/63/184 +f 66/66/185 52/52/185 67/67/185 +f 49/49/186 52/52/186 66/66/186 +f 67/67/187 49/49/187 66/66/187 +f 47/47/188 49/49/188 67/67/188 +f 52/52/189 47/47/189 67/67/189 +f 57/57/190 55/55/141 54/54/140 +f 68/68/191 69/69/191 70/70/191 +f 68/68/192 70/70/192 71/71/192 +f 71/71/193 70/70/194 72/72/195 +f 71/71/193 72/72/195 73/73/196 +f 73/73/197 72/72/197 74/74/197 +f 73/73/198 74/74/198 75/75/198 +f 75/75/199 74/74/199 76/76/199 +f 77/77/200 78/78/200 79/79/200 +f 79/79/201 78/78/201 80/80/201 +f 79/79/202 80/80/202 81/81/202 +f 81/81/203 80/80/203 82/82/203 +f 81/81/204 82/82/204 83/83/204 +f 83/83/205 82/82/205 70/70/205 +f 83/83/206 70/70/206 84/84/206 +f 83/83/207 84/84/207 85/85/207 +f 85/85/208 84/84/208 69/69/208 +f 68/68/209 85/85/209 69/69/209 +f 73/73/210 81/81/210 71/71/210 +f 71/71/210 81/81/210 83/83/210 +f 75/75/211 79/79/212 73/73/210 +f 73/73/210 79/79/212 81/81/210 +f 76/76/213 77/77/213 79/79/213 +f 76/76/214 79/79/212 75/75/211 +f 71/71/210 83/83/210 68/68/210 +f 68/68/210 83/83/210 85/85/210 +f 77/77/215 76/76/216 78/78/217 +f 74/74/218 82/82/71 80/80/71 +f 72/72/71 70/70/71 82/82/71 +f 72/72/71 82/82/71 74/74/218 +f 74/74/218 80/80/71 78/78/217 +f 74/74/218 78/78/217 76/76/216 +f 69/69/71 84/84/71 70/70/71 +f 86/86/219 87/87/220 88/88/221 +f 88/88/222 87/87/222 89/89/222 +f 88/88/223 89/89/223 90/90/223 +f 90/90/224 89/89/224 91/91/224 +f 90/90/225 91/91/226 92/92/227 +f 92/92/227 91/91/226 93/93/228 +f 94/94/229 92/92/229 95/95/229 +f 95/95/230 92/92/227 93/93/228 +f 94/94/231 95/95/231 96/96/231 +f 94/94/232 96/96/232 97/97/232 +f 97/97/233 96/96/233 98/98/233 +f 97/97/234 98/98/234 99/99/234 +f 99/99/235 98/98/236 100/100/237 +f 99/99/235 100/100/237 101/101/238 +f 101/101/239 100/100/239 102/102/239 +f 102/102/240 100/100/240 103/103/240 +f 102/102/241 103/103/241 104/104/241 +f 86/86/219 104/104/242 87/87/220 +f 90/90/210 99/99/210 101/101/210 +f 90/90/210 101/101/210 88/88/210 +f 90/90/210 97/97/210 99/99/210 +f 86/86/243 102/102/244 104/104/245 +f 88/88/210 102/102/244 86/86/243 +f 92/92/210 97/97/210 90/90/210 +f 92/92/210 94/94/210 97/97/210 +f 88/88/210 101/101/210 102/102/244 +f 89/89/71 100/100/71 91/91/71 +f 91/91/71 98/98/71 96/96/71 +f 91/91/71 100/100/71 98/98/71 +f 93/93/71 96/96/71 95/95/71 +f 91/91/71 96/96/71 93/93/71 +f 87/87/246 100/100/71 89/89/71 +f 87/87/246 103/103/247 100/100/71 +f 87/87/246 104/104/248 103/103/247 +f 105/105/249 106/106/250 107/107/251 +f 105/105/249 107/107/251 108/108/252 +f 109/109/253 110/110/254 106/106/250 +f 109/109/253 106/106/250 105/105/249 +f 109/109/253 111/111/255 110/110/254 +f 108/108/256 111/111/255 109/109/253 +f 112/112/257 113/113/258 114/114/259 +f 114/114/259 115/115/260 112/112/257 +f 116/116/261 113/113/262 117/117/263 +f 117/117/263 113/113/262 112/112/264 +f 117/117/265 112/112/265 118/118/265 +f 118/118/266 112/112/266 115/115/266 +f 118/118/267 115/115/267 119/119/267 +f 119/119/268 115/115/268 114/114/268 +f 119/119/269 114/114/269 116/116/269 +f 116/116/270 114/114/270 113/113/270 +f 117/117/271 120/120/272 121/121/273 +f 117/117/271 121/121/273 116/116/274 +f 116/116/274 121/121/273 122/122/275 +f 116/116/274 122/122/275 119/119/276 +f 119/119/276 122/122/275 123/123/277 +f 119/119/276 123/123/277 118/118/278 +f 118/118/278 123/123/277 124/124/279 +f 118/118/278 124/124/279 117/117/271 +f 117/117/271 124/124/279 120/120/272 +f 107/107/280 121/121/281 120/120/282 +f 107/107/280 120/120/282 108/108/283 +f 108/108/284 120/120/285 124/124/286 +f 108/108/284 124/124/286 111/111/287 +f 111/111/288 124/124/288 123/123/288 +f 111/111/289 123/123/289 110/110/289 +f 110/110/290 123/123/290 122/122/290 +f 110/110/291 122/122/291 106/106/291 +f 106/106/292 122/122/293 121/121/294 +f 106/106/292 121/121/294 107/107/295 +f 108/108/296 109/109/297 125/125/298 +f 125/125/298 109/109/297 126/126/299 +f 105/105/300 108/108/300 127/127/300 +f 127/127/301 108/108/301 125/125/301 +f 109/109/59 105/105/302 126/126/61 +f 126/126/61 105/105/302 127/127/62 +f 126/126/71 127/127/71 125/125/71 +f 128/128/303 129/129/303 130/130/303 +f 128/128/304 130/130/304 131/131/304 +f 131/131/305 130/130/305 132/132/305 +f 131/131/306 132/132/307 133/133/308 +f 131/131/306 133/133/308 134/134/309 +f 134/134/310 133/133/311 135/135/312 +f 135/135/312 133/133/311 136/136/313 +f 137/137/314 135/135/312 138/138/315 +f 138/138/315 135/135/312 136/136/313 +f 137/137/316 138/138/317 139/139/318 +f 137/137/316 139/139/318 140/140/319 +f 140/140/320 139/139/320 141/141/320 +f 140/140/321 141/141/321 142/142/321 +f 142/142/322 141/141/323 143/143/324 +f 142/142/322 143/143/324 144/144/325 +f 144/144/326 143/143/327 145/145/328 +f 144/144/326 145/145/328 146/146/329 +f 146/146/330 145/145/330 147/147/330 +f 147/147/331 145/145/331 129/129/331 +f 128/128/332 147/147/332 129/129/332 +f 134/134/210 144/144/210 131/131/210 +f 134/134/210 142/142/210 144/144/210 +f 134/134/210 140/140/210 142/142/210 +f 131/131/210 146/146/210 128/128/210 +f 128/128/210 146/146/210 147/147/210 +f 135/135/210 140/140/210 134/134/210 +f 135/135/210 137/137/210 140/140/210 +f 131/131/210 144/144/210 146/146/210 +f 132/132/71 143/143/71 133/133/71 +f 133/133/71 139/139/71 136/136/71 +f 133/133/71 141/141/71 139/139/71 +f 133/133/71 143/143/71 141/141/71 +f 136/136/71 139/139/71 138/138/71 +f 130/130/71 145/145/71 143/143/71 +f 130/130/71 143/143/71 132/132/71 +f 130/130/71 129/129/71 145/145/71 +f 148/148/333 149/149/334 150/150/335 +f 150/150/335 149/149/334 151/151/336 +f 150/150/337 151/151/337 152/152/337 +f 152/152/338 151/151/338 153/153/338 +f 152/152/339 153/153/339 154/154/339 +f 154/154/340 153/153/340 155/155/340 +f 154/154/341 155/155/341 156/156/341 +f 156/156/342 155/155/343 157/157/344 +f 158/158/345 156/156/342 159/159/346 +f 159/159/346 156/156/342 157/157/344 +f 158/158/347 159/159/347 160/160/347 +f 158/158/348 160/160/348 161/161/348 +f 161/161/349 160/160/349 162/162/349 +f 161/161/350 162/162/350 163/163/350 +f 163/163/351 162/162/352 164/164/353 +f 163/163/351 164/164/353 165/165/354 +f 165/165/355 164/164/355 166/166/355 +f 166/166/356 164/164/356 167/167/356 +f 166/166/357 167/167/357 148/148/357 +f 149/149/358 148/148/358 167/167/358 +f 152/152/210 163/163/210 165/165/210 +f 154/154/210 163/163/210 152/152/210 +f 154/154/210 161/161/210 163/163/210 +f 156/156/210 161/161/210 154/154/210 +f 150/150/210 166/166/210 148/148/210 +f 156/156/210 158/158/210 161/161/210 +f 150/150/210 165/165/210 166/166/210 +f 152/152/210 165/165/210 150/150/210 +f 153/153/71 162/162/71 155/155/71 +f 155/155/71 162/162/71 160/160/71 +f 151/151/71 164/164/71 153/153/71 +f 153/153/71 164/164/71 162/162/71 +f 155/155/71 160/160/71 157/157/71 +f 157/157/71 160/160/71 159/159/71 +f 149/149/71 167/167/71 151/151/71 +f 151/151/71 167/167/71 164/164/71 +f 168/168/359 169/169/359 170/170/359 +f 171/171/360 172/172/360 168/168/360 +f 170/170/361 173/173/361 171/171/361 +f 174/174/362 175/175/362 176/176/363 +f 174/174/362 177/177/364 175/175/362 +f 177/177/365 178/178/366 175/175/367 +f 175/175/367 178/178/366 179/179/368 +f 175/175/369 179/179/369 176/176/369 +f 179/179/370 180/180/370 176/176/370 +f 176/176/371 180/180/372 181/181/373 +f 176/176/371 181/181/373 174/174/374 +f 174/174/375 181/181/376 178/178/377 +f 174/174/375 178/178/377 177/177/378 +f 179/179/379 182/182/380 180/180/381 +f 178/178/382 183/183/383 184/184/384 +f 181/181/385 185/185/386 183/183/383 +f 181/181/385 183/183/383 178/178/382 +f 180/180/381 182/182/380 185/185/386 +f 180/180/381 185/185/386 181/181/385 +f 179/179/379 184/184/384 182/182/380 +f 178/178/382 184/184/384 179/179/379 +f 183/183/387 169/169/388 184/184/389 +f 184/184/390 169/169/390 168/168/390 +f 184/184/391 168/168/391 182/182/391 +f 182/182/392 168/168/392 172/172/392 +f 172/172/393 171/171/394 182/182/395 +f 182/182/395 171/171/394 185/185/396 +f 171/171/397 173/173/397 185/185/397 +f 185/185/398 173/173/399 183/183/400 +f 183/183/400 173/173/399 170/170/401 +f 183/183/387 170/170/402 169/169/388 +f 171/171/403 168/168/403 186/186/403 +f 170/170/404 171/171/405 187/187/406 +f 187/187/406 171/171/405 186/186/407 +f 168/168/408 170/170/408 186/186/408 +f 186/186/409 170/170/409 187/187/409 +f 188/188/71 189/189/71 190/190/71 +f 190/190/71 189/189/71 191/191/71 +f 192/192/410 193/193/411 194/194/412 +f 194/194/412 193/193/411 195/195/411 +f 196/196/413 197/197/414 198/198/415 +f 196/196/413 198/198/415 199/199/416 +f 199/199/416 198/198/415 200/200/417 +f 201/201/418 198/198/419 202/202/420 +f 202/202/420 198/198/419 203/203/421 +f 198/198/419 197/197/422 203/203/421 +f 204/204/413 205/205/414 206/206/415 +f 204/204/413 206/206/415 207/207/416 +f 207/207/416 206/206/415 208/208/417 +f 209/209/418 206/206/419 210/210/420 +f 210/210/420 206/206/419 211/211/421 +f 206/206/419 205/205/422 211/211/421 +f 212/212/413 213/213/414 214/214/415 +f 212/212/413 214/214/415 215/215/416 +f 215/215/416 214/214/415 216/216/417 +f 217/217/418 214/214/419 218/218/420 +f 218/218/420 214/214/419 219/219/421 +f 214/214/419 213/213/422 219/219/421 +f 220/220/413 221/221/414 222/222/415 +f 220/220/413 222/222/415 223/223/416 +f 223/223/416 222/222/415 224/224/417 +f 225/225/418 222/222/419 226/226/420 +f 226/226/420 222/222/419 227/227/421 +f 222/222/419 221/221/422 227/227/421 +f 228/228/413 229/229/423 230/230/415 +f 228/228/413 230/230/415 231/231/416 +f 231/231/416 230/230/415 232/232/417 +f 233/233/418 230/230/419 234/234/420 +f 234/234/420 230/230/419 235/235/421 +f 230/230/419 229/229/422 235/235/421 +f 236/236/424 237/237/425 238/238/426 +f 236/236/424 238/238/426 239/239/427 +f 236/236/424 239/239/427 240/240/428 +f 240/240/428 239/239/427 241/241/429 +f 242/242/418 239/239/419 243/243/420 +f 243/243/420 239/239/419 244/244/421 +f 239/239/419 238/238/422 244/244/421 +f 189/189/430 193/193/431 192/192/432 +f 189/189/430 192/192/432 191/191/433 +f 198/198/434 201/201/434 200/200/434 +f 206/206/435 209/209/435 208/208/435 +f 214/214/436 217/217/436 216/216/436 +f 222/222/435 225/225/435 224/224/435 +f 230/230/437 233/233/437 232/232/437 +f 239/239/436 242/242/436 241/241/436 +f 245/245/438 246/246/439 188/188/440 +f 247/247/441 246/246/439 245/245/438 +f 248/248/442 249/249/443 250/250/444 +f 251/251/445 249/249/443 248/248/442 +f 251/251/445 248/248/442 252/252/446 +f 252/252/446 248/248/442 253/253/447 +f 254/254/448 255/255/449 256/256/450 +f 256/256/450 255/255/449 253/253/447 +f 253/253/447 255/255/449 252/252/446 +f 257/257/451 254/254/448 256/256/450 +f 258/258/452 195/195/453 259/259/453 +f 258/258/452 259/259/453 260/260/454 +f 261/261/455 262/262/456 263/263/457 +f 264/264/458 265/265/459 266/266/460 +f 264/264/458 267/267/411 268/268/411 +f 264/264/458 268/268/411 265/265/459 +f 265/265/459 269/269/461 266/266/460 +f 266/266/460 269/269/461 261/261/455 +f 261/261/455 269/269/461 270/270/462 +f 261/261/455 270/270/462 262/262/456 +f 271/271/463 272/272/464 196/196/465 +f 273/273/466 272/272/464 271/271/463 +f 274/274/467 275/275/468 276/276/469 +f 277/277/470 275/275/468 274/274/467 +f 277/277/470 274/274/467 278/278/471 +f 278/278/471 274/274/467 279/279/472 +f 280/280/473 281/281/474 282/282/475 +f 282/282/475 281/281/474 279/279/472 +f 279/279/472 281/281/474 278/278/471 +f 282/282/475 283/283/476 280/280/473 +f 203/203/477 272/272/478 273/273/479 +f 203/203/477 273/273/479 245/245/480 +f 248/248/481 284/284/482 253/253/483 +f 248/248/481 285/285/484 286/286/485 +f 248/248/481 286/286/485 284/284/482 +f 284/284/482 287/287/486 253/253/483 +f 253/253/483 287/287/486 256/256/487 +f 256/256/487 287/287/486 288/288/488 +f 256/256/487 288/288/488 289/289/489 +f 289/289/489 288/288/488 290/290/210 +f 291/291/463 292/292/464 204/204/465 +f 293/293/466 292/292/464 291/291/463 +f 294/294/490 295/295/443 296/296/444 +f 297/297/445 295/295/443 294/294/490 +f 297/297/445 294/294/490 298/298/491 +f 298/298/491 294/294/490 299/299/492 +f 300/300/473 301/301/493 302/302/494 +f 302/302/494 301/301/493 303/303/495 +f 303/303/496 301/301/496 299/299/496 +f 299/299/492 301/301/497 298/298/491 +f 302/302/494 304/304/476 300/300/473 +f 211/211/477 292/292/478 293/293/479 +f 211/211/477 293/293/479 271/271/480 +f 282/282/498 305/305/499 283/283/500 +f 274/274/501 306/306/502 279/279/503 +f 307/307/504 308/308/505 274/274/501 +f 274/274/501 308/308/505 306/306/502 +f 306/306/502 309/309/506 279/279/503 +f 279/279/503 309/309/506 282/282/498 +f 282/282/498 309/309/506 310/310/507 +f 282/282/498 310/310/507 305/305/499 +f 311/311/463 312/312/464 212/212/465 +f 313/313/466 312/312/464 311/311/463 +f 314/314/508 315/315/509 316/316/510 +f 317/317/511 315/315/509 314/314/508 +f 317/317/511 314/314/508 318/318/512 +f 318/318/512 314/314/508 319/319/513 +f 318/318/512 319/319/513 320/320/514 +f 321/321/515 322/322/516 323/323/517 +f 323/323/517 322/322/516 320/320/514 +f 323/323/517 320/320/514 319/319/513 +f 324/324/518 321/321/515 323/323/517 +f 219/219/477 312/312/478 313/313/479 +f 219/219/477 313/313/479 291/291/480 +f 302/302/519 325/325/520 304/304/500 +f 294/294/521 317/317/522 299/299/523 +f 299/299/523 317/317/522 318/318/524 +f 299/299/523 318/318/524 303/303/525 +f 294/294/521 326/326/484 327/327/526 +f 294/294/521 327/327/526 317/317/522 +f 318/318/524 320/320/527 303/303/525 +f 303/303/525 320/320/527 302/302/519 +f 302/302/519 320/320/527 322/322/528 +f 302/302/519 322/322/528 325/325/520 +f 328/328/529 329/329/530 220/220/531 +f 330/330/532 329/329/530 328/328/529 +f 331/331/71 332/332/71 333/333/71 +f 331/331/71 333/333/71 334/334/533 +f 331/331/71 334/334/533 335/335/534 +f 335/335/534 334/334/533 336/336/535 +f 337/337/71 338/338/536 339/339/537 +f 339/339/537 338/338/536 336/336/535 +f 336/336/535 338/338/536 335/335/534 +f 340/340/71 337/337/71 339/339/537 +f 227/227/477 329/329/478 330/330/479 +f 227/227/477 330/330/479 311/311/480 +f 323/323/538 341/341/539 342/342/540 +f 314/314/541 343/343/542 319/319/543 +f 344/344/544 345/345/545 314/314/541 +f 314/314/541 345/345/545 343/343/542 +f 343/343/542 346/346/546 319/319/543 +f 319/319/543 346/346/546 323/323/538 +f 323/323/538 346/346/546 347/347/547 +f 323/323/538 347/347/547 341/341/539 +f 348/348/548 349/349/549 228/228/550 +f 350/350/551 349/349/549 348/348/548 +f 351/351/71 352/352/71 353/353/71 +f 354/354/71 352/352/71 351/351/71 +f 354/354/71 351/351/71 355/355/71 +f 355/355/71 351/351/71 356/356/552 +f 357/357/553 358/358/554 359/359/555 +f 359/359/555 358/358/554 356/356/552 +f 356/356/552 358/358/554 355/355/71 +f 360/360/556 357/357/553 359/359/555 +f 235/235/557 349/349/478 350/350/558 +f 235/235/557 350/350/558 348/348/559 +f 361/361/560 362/362/210 363/363/210 +f 364/364/561 365/365/562 336/336/563 +f 364/364/561 366/366/210 367/367/210 +f 364/364/561 367/367/210 365/365/562 +f 365/365/562 368/368/564 336/336/563 +f 336/336/563 368/368/564 361/361/560 +f 361/361/560 368/368/564 369/369/210 +f 361/361/560 369/369/210 362/362/210 +f 370/370/565 371/371/566 237/237/567 +f 372/372/568 371/371/566 370/370/565 +f 373/373/71 374/374/71 375/375/71 +f 376/376/71 374/374/71 373/373/71 +f 376/376/71 373/373/71 377/377/569 +f 376/376/71 377/377/569 378/378/71 +f 379/379/570 380/380/571 381/381/572 +f 381/381/572 380/380/571 377/377/569 +f 377/377/569 380/380/571 378/378/71 +f 382/382/573 379/379/570 381/381/572 +f 244/244/574 371/371/575 372/372/574 +f 244/244/574 372/372/574 383/383/574 +f 384/384/210 385/385/210 386/386/576 +f 386/386/576 385/385/210 387/387/210 +f 387/387/210 388/388/577 386/386/576 +f 386/386/576 388/388/577 359/359/578 +f 359/359/578 388/388/577 389/389/579 +f 359/359/578 389/389/579 390/390/580 +f 390/390/580 389/389/579 391/391/210 +f 254/254/581 262/262/582 270/270/583 +f 254/254/581 270/270/583 255/255/584 +f 255/255/585 270/270/585 269/269/585 +f 255/255/586 269/269/586 252/252/586 +f 252/252/587 269/269/587 265/265/587 +f 252/252/588 265/265/588 251/251/588 +f 251/251/589 265/265/590 268/268/591 +f 251/251/589 268/268/591 249/249/592 +f 280/280/593 290/290/593 288/288/593 +f 280/280/594 288/288/594 281/281/594 +f 281/281/595 288/288/488 287/287/486 +f 281/281/474 287/287/596 278/278/471 +f 278/278/597 287/287/486 284/284/482 +f 278/278/471 284/284/598 277/277/470 +f 277/277/599 284/284/599 286/286/599 +f 277/277/600 286/286/600 275/275/600 +f 300/300/593 305/305/593 310/310/593 +f 300/300/601 310/310/601 301/301/601 +f 301/301/595 310/310/595 309/309/595 +f 301/301/596 309/309/596 298/298/596 +f 298/298/597 309/309/506 306/306/502 +f 298/298/598 306/306/598 297/297/598 +f 297/297/602 306/306/602 308/308/602 +f 297/297/600 308/308/600 295/295/600 +f 321/321/603 325/325/603 322/322/603 +f 317/317/604 327/327/604 315/315/604 +f 337/337/605 341/341/605 347/347/605 +f 337/337/594 347/347/594 338/338/594 +f 338/338/606 347/347/547 346/346/546 +f 338/338/536 346/346/596 335/335/534 +f 335/335/597 346/346/546 343/343/542 +f 335/335/598 343/343/598 331/331/598 +f 331/331/607 343/343/607 345/345/607 +f 331/331/600 345/345/600 332/332/600 +f 357/357/593 362/362/593 369/369/593 +f 357/357/608 369/369/608 358/358/608 +f 358/358/595 369/369/595 368/368/595 +f 358/358/596 368/368/596 355/355/596 +f 355/355/597 368/368/564 365/365/562 +f 355/355/598 365/365/598 354/354/598 +f 354/354/609 365/365/609 367/367/609 +f 354/354/600 367/367/600 352/352/600 +f 379/379/593 391/391/593 389/389/593 +f 379/379/610 389/389/610 380/380/610 +f 380/380/595 389/389/579 388/388/577 +f 380/380/596 388/388/596 378/378/596 +f 378/378/597 388/388/597 387/387/597 +f 378/378/598 387/387/598 376/376/598 +f 376/376/611 387/387/611 385/385/611 +f 376/376/600 385/385/600 374/374/600 +f 247/247/612 260/260/613 259/259/614 +f 247/247/612 259/259/614 246/246/615 +f 392/392/616 393/393/617 394/394/618 +f 394/394/618 393/393/617 395/395/619 +f 396/396/620 397/397/621 398/398/622 +f 398/398/622 397/397/621 399/399/623 +f 400/400/71 401/401/71 402/402/624 +f 403/403/625 404/404/626 405/405/627 +f 403/403/625 405/405/627 406/406/628 +f 406/406/628 405/405/627 407/407/629 +f 406/406/628 407/407/629 402/402/624 +f 402/402/624 407/407/629 400/400/71 +f 250/250/630 408/408/631 403/403/625 +f 403/403/625 408/408/631 404/404/626 +f 409/409/210 410/410/632 411/411/633 +f 410/410/632 412/412/634 413/413/635 +f 413/413/636 412/412/637 414/414/638 +f 413/413/636 414/414/638 415/415/639 +f 415/415/639 414/414/638 416/416/640 +f 415/415/639 416/416/640 417/417/641 +f 417/417/641 416/416/640 418/418/642 +f 410/410/632 409/409/210 412/412/634 +f 408/408/643 418/418/644 416/416/645 +f 408/408/643 416/416/645 404/404/646 +f 404/404/646 416/416/645 414/414/647 +f 404/404/646 414/414/647 405/405/648 +f 405/405/648 414/414/647 412/412/649 +f 405/405/648 412/412/649 407/407/650 +f 407/407/651 412/412/652 409/409/653 +f 407/407/651 409/409/653 400/400/654 +f 419/419/655 420/420/656 421/421/657 +f 422/422/658 423/423/659 424/424/660 +f 422/422/658 424/424/660 425/425/661 +f 425/425/661 424/424/660 426/426/662 +f 425/425/661 426/426/662 421/421/657 +f 421/421/657 426/426/662 427/427/663 +f 421/421/657 427/427/663 419/419/655 +f 276/276/664 428/428/665 422/422/658 +f 422/422/658 428/428/665 423/423/659 +f 419/419/666 429/429/667 430/430/668 +f 429/429/667 427/427/669 426/426/670 +f 429/429/667 426/426/670 406/406/671 +f 406/406/671 426/426/670 424/424/672 +f 406/406/671 424/424/672 403/403/673 +f 403/403/673 424/424/672 423/423/674 +f 403/403/673 423/423/674 431/431/675 +f 431/431/675 423/423/674 432/432/676 +f 429/429/667 419/419/666 427/427/669 +f 428/428/677 432/432/677 423/423/677 +f 433/433/678 434/434/71 435/435/679 +f 436/436/680 437/437/681 438/438/660 +f 436/436/680 438/438/660 439/439/661 +f 439/439/661 438/438/660 440/440/662 +f 439/439/661 440/440/662 435/435/679 +f 435/435/679 440/440/662 441/441/682 +f 435/435/679 441/441/682 433/433/678 +f 296/296/630 442/442/683 436/436/680 +f 436/436/680 442/442/683 437/437/681 +f 443/443/684 444/444/685 445/445/210 +f 444/444/685 441/441/686 440/440/670 +f 444/444/685 440/440/670 425/425/671 +f 425/425/671 440/440/670 438/438/672 +f 425/425/671 438/438/672 422/422/687 +f 422/422/687 438/438/672 437/437/674 +f 422/422/687 437/437/674 446/446/688 +f 446/446/688 437/437/674 447/447/676 +f 444/444/685 443/443/684 441/441/686 +f 442/442/677 447/447/677 437/437/677 +f 441/441/689 443/443/689 433/433/689 +f 448/448/690 449/449/71 450/450/691 +f 451/451/680 452/452/659 453/453/660 +f 451/451/680 453/453/660 454/454/661 +f 454/454/661 453/453/660 455/455/662 +f 454/454/661 455/455/662 450/450/691 +f 450/450/691 455/455/662 456/456/682 +f 450/450/691 456/456/682 448/448/690 +f 316/316/630 457/457/683 451/451/680 +f 451/451/680 457/457/683 452/452/659 +f 458/458/684 459/459/685 460/460/210 +f 459/459/685 456/456/686 455/455/670 +f 459/459/685 455/455/670 439/439/671 +f 439/439/671 455/455/670 453/453/672 +f 439/439/671 453/453/672 436/436/673 +f 436/436/673 453/453/672 452/452/674 +f 436/436/673 452/452/674 461/461/675 +f 461/461/675 452/452/674 462/462/676 +f 459/459/685 458/458/684 456/456/686 +f 457/457/692 462/462/692 452/452/692 +f 456/456/693 458/458/693 448/448/693 +f 463/463/690 464/464/71 465/465/691 +f 466/466/694 467/467/681 468/468/660 +f 466/466/694 468/468/660 469/469/661 +f 469/469/661 468/468/660 470/470/662 +f 469/469/661 470/470/662 465/465/691 +f 465/465/691 470/470/662 471/471/682 +f 465/465/691 471/471/682 463/463/690 +f 472/472/695 473/473/696 466/466/694 +f 466/466/694 473/473/696 467/467/681 +f 474/474/684 475/475/685 476/476/210 +f 475/475/685 471/471/686 470/470/670 +f 475/475/685 470/470/670 454/454/671 +f 454/454/671 470/470/670 468/468/672 +f 454/454/671 468/468/672 451/451/673 +f 451/451/673 468/468/672 467/467/674 +f 451/451/673 467/467/674 477/477/697 +f 477/477/697 467/467/674 478/478/676 +f 475/475/685 474/474/684 471/471/686 +f 473/473/677 478/478/677 467/467/677 +f 471/471/698 474/474/698 463/463/698 +f 479/479/699 480/480/71 481/481/700 +f 482/482/680 483/483/681 484/484/660 +f 482/482/680 484/484/660 485/485/661 +f 485/485/661 484/484/660 486/486/662 +f 485/485/661 486/486/662 481/481/700 +f 481/481/700 486/486/662 487/487/682 +f 481/481/700 487/487/682 479/479/699 +f 353/353/630 488/488/683 482/482/680 +f 482/482/680 488/488/683 483/483/681 +f 489/489/684 490/490/685 491/491/210 +f 490/490/685 487/487/686 486/486/670 +f 490/490/685 486/486/670 469/469/671 +f 469/469/671 486/486/670 484/484/672 +f 469/469/671 484/484/672 466/466/701 +f 466/466/701 484/484/672 483/483/702 +f 466/466/701 483/483/702 472/472/703 +f 472/472/703 483/483/702 492/492/704 +f 490/490/685 489/489/684 487/487/686 +f 488/488/692 492/492/692 483/483/692 +f 487/487/698 489/489/698 479/479/698 +f 493/493/705 494/494/706 495/495/707 +f 496/496/708 497/497/709 498/498/710 +f 498/498/710 497/497/709 499/499/711 +f 498/498/710 499/499/711 500/500/712 +f 500/500/712 499/499/711 501/501/713 +f 500/500/712 501/501/713 495/495/707 +f 495/495/707 501/501/713 502/502/714 +f 495/495/707 502/502/714 493/493/705 +f 493/493/666 503/503/667 504/504/668 +f 503/503/667 502/502/669 501/501/670 +f 503/503/667 501/501/670 485/485/671 +f 485/485/671 501/501/670 499/499/672 +f 485/485/671 499/499/672 482/482/673 +f 482/482/673 499/499/672 497/497/674 +f 482/482/673 497/497/674 505/505/715 +f 505/505/715 497/497/674 506/506/676 +f 503/503/667 493/493/666 502/502/669 +f 496/496/716 506/506/716 497/497/716 +f 393/393/617 392/392/616 507/507/717 +f 507/507/717 392/392/616 508/508/718 +f 507/507/717 508/508/718 509/509/719 +f 509/509/719 508/508/718 510/510/720 +f 509/509/719 510/510/720 511/511/721 +f 511/511/721 510/510/720 512/512/722 +f 496/496/723 513/513/724 375/375/725 +f 375/375/726 513/513/726 373/373/726 +f 373/373/727 513/513/727 514/514/727 +f 496/496/728 515/515/728 513/513/728 +f 498/498/729 515/515/729 496/496/729 +f 498/498/730 500/500/730 515/515/730 +f 495/495/731 516/516/731 500/500/731 +f 516/516/732 495/495/732 517/517/732 +f 517/517/733 495/495/734 494/494/735 +f 518/518/736 519/519/736 520/520/736 +f 520/520/737 519/519/737 517/517/737 +f 520/520/738 517/517/733 494/494/735 +f 518/518/739 521/521/739 519/519/739 +f 522/522/740 523/523/740 524/524/740 +f 524/524/741 523/523/741 521/521/741 +f 524/524/742 521/521/742 518/518/742 +f 525/525/743 526/526/744 522/522/745 +f 522/522/745 526/526/744 523/523/746 +f 526/526/747 525/525/747 527/527/747 +f 527/527/748 370/370/749 528/528/750 +f 237/237/751 236/236/751 528/528/751 +f 237/237/752 528/528/752 370/370/752 +f 529/529/753 236/236/753 240/240/753 +f 382/382/754 530/530/755 240/240/756 +f 240/240/757 530/530/757 529/529/757 +f 373/373/758 514/514/758 377/377/758 +f 377/377/759 514/514/759 381/381/759 +f 381/381/760 530/530/761 382/382/762 +f 505/505/715 384/384/763 353/353/764 +f 505/505/715 353/353/764 482/482/673 +f 485/485/765 481/481/765 503/503/765 +f 503/503/766 481/481/767 480/480/768 +f 503/503/766 480/480/768 504/504/769 +f 504/504/769 480/480/768 531/531/770 +f 532/532/771 531/531/771 533/533/771 +f 532/532/772 533/533/772 534/534/772 +f 535/535/773 536/536/774 537/537/775 +f 537/537/775 536/536/774 538/538/776 +f 538/538/776 536/536/774 539/539/777 +f 538/538/776 539/539/777 540/540/778 +f 540/540/778 539/539/777 541/541/779 +f 540/540/778 541/541/779 383/383/780 +f 383/383/780 541/541/779 348/348/781 +f 383/383/780 348/348/781 244/244/782 +f 244/244/782 348/348/781 228/228/783 +f 244/244/784 228/228/784 243/243/784 +f 243/243/785 228/228/786 231/231/787 +f 243/243/785 231/231/787 390/390/788 +f 390/390/788 231/231/787 360/360/789 +f 353/353/764 384/384/763 351/351/790 +f 351/351/791 384/384/791 386/386/791 +f 351/351/792 386/386/792 356/356/792 +f 356/356/552 386/386/793 359/359/555 +f 359/359/794 390/390/788 360/360/789 +f 472/472/795 366/366/796 333/333/797 +f 469/469/765 465/465/765 490/490/765 +f 490/490/798 465/465/799 464/464/800 +f 490/490/798 464/464/800 491/491/801 +f 491/491/801 464/464/800 542/542/802 +f 542/542/802 464/464/800 543/543/803 +f 544/544/804 545/545/805 546/546/806 +f 544/544/804 546/546/806 547/547/807 +f 547/547/807 546/546/806 548/548/808 +f 548/548/808 546/546/806 549/549/809 +f 548/548/808 549/549/809 348/348/781 +f 348/348/781 549/549/809 328/328/810 +f 348/348/781 328/328/810 235/235/811 +f 235/235/811 328/328/810 220/220/812 +f 235/235/784 220/220/784 234/234/784 +f 234/234/813 220/220/786 223/223/814 +f 234/234/813 223/223/814 363/363/815 +f 363/363/815 223/223/814 340/340/816 +f 333/333/797 366/366/796 364/364/817 +f 333/333/818 364/364/818 334/334/818 +f 334/334/819 364/364/819 336/336/819 +f 336/336/820 361/361/820 339/339/820 +f 339/339/821 361/361/822 340/340/816 +f 340/340/816 361/361/822 363/363/815 +f 477/477/697 344/344/823 316/316/824 +f 477/477/697 316/316/824 451/451/673 +f 454/454/765 450/450/765 475/475/765 +f 475/475/798 450/450/799 449/449/800 +f 475/475/798 449/449/800 476/476/825 +f 476/476/825 449/449/800 550/550/802 +f 550/550/802 449/449/800 551/551/803 +f 552/552/826 553/553/827 554/554/828 +f 554/554/828 553/553/827 555/555/829 +f 555/555/829 553/553/827 556/556/830 +f 556/556/830 553/553/827 557/557/831 +f 556/556/830 557/557/831 311/311/832 +f 227/227/833 311/311/833 212/212/833 +f 227/227/784 212/212/784 226/226/784 +f 226/226/813 212/212/834 215/215/814 +f 226/226/813 215/215/814 342/342/835 +f 342/342/835 215/215/814 324/324/836 +f 316/316/824 344/344/823 314/314/837 +f 324/324/836 323/323/838 342/342/835 +f 294/294/839 296/296/840 326/326/841 +f 326/326/841 296/296/840 461/461/842 +f 461/461/675 296/296/843 436/436/673 +f 439/439/765 435/435/765 459/459/765 +f 459/459/844 435/435/845 434/434/846 +f 459/459/844 434/434/846 460/460/847 +f 460/460/847 434/434/846 558/558/848 +f 558/558/848 434/434/846 559/559/849 +f 560/560/826 561/561/850 562/562/851 +f 562/562/851 561/561/850 563/563/852 +f 563/563/852 561/561/850 564/564/853 +f 564/564/853 561/561/850 565/565/831 +f 564/564/853 565/565/831 291/291/854 +f 219/219/833 291/291/833 204/204/833 +f 219/219/855 204/204/855 218/218/855 +f 218/218/856 204/204/834 207/207/857 +f 218/218/856 207/207/857 304/304/858 +f 446/446/688 307/307/859 276/276/860 +f 446/446/688 276/276/860 422/422/687 +f 425/425/765 421/421/765 444/444/765 +f 444/444/798 421/421/799 420/420/800 +f 444/444/798 420/420/800 445/445/825 +f 445/445/825 420/420/800 566/566/802 +f 566/566/802 420/420/800 567/567/803 +f 568/568/861 569/569/862 570/570/863 +f 570/570/863 569/569/862 571/571/864 +f 571/571/864 569/569/862 572/572/865 +f 571/571/864 572/572/865 573/573/866 +f 573/573/866 572/572/865 574/574/867 +f 573/573/866 574/574/867 271/271/854 +f 211/211/833 271/271/833 196/196/833 +f 211/211/855 196/196/855 210/210/855 +f 210/210/868 196/196/834 199/199/857 +f 210/210/868 199/199/857 283/283/869 +f 276/276/860 307/307/859 274/274/870 +f 431/431/871 285/285/872 250/250/840 +f 431/431/675 250/250/843 403/403/673 +f 406/406/765 402/402/765 429/429/765 +f 429/429/844 402/402/845 401/401/873 +f 429/429/844 401/401/873 430/430/874 +f 430/430/874 401/401/873 575/575/875 +f 575/575/875 401/401/873 576/576/876 +f 575/575/877 576/576/877 577/577/877 +f 577/577/878 576/576/878 578/578/878 +f 577/577/879 578/578/879 579/579/879 +f 579/579/880 578/578/880 580/580/880 +f 579/579/881 580/580/881 581/581/881 +f 581/581/882 580/580/882 582/582/882 +f 581/581/883 582/582/884 583/583/885 +f 583/583/885 582/582/884 584/584/886 +f 584/584/887 582/582/888 585/585/889 +f 584/584/887 585/585/889 245/245/890 +f 203/203/833 245/245/833 188/188/833 +f 203/203/855 188/188/855 202/202/855 +f 202/202/891 188/188/786 190/190/892 +f 202/202/891 190/190/892 289/289/893 +f 289/289/893 190/190/892 257/257/894 +f 250/250/840 285/285/872 248/248/839 +f 256/256/895 289/289/893 257/257/894 +f 586/586/896 587/587/897 588/588/898 +f 263/263/899 589/589/900 261/261/901 +f 590/590/902 591/591/903 592/592/904 +f 590/590/902 592/592/904 593/593/905 +f 593/593/905 592/592/904 594/594/906 +f 593/593/905 594/594/906 595/595/907 +f 595/595/907 594/594/906 596/596/908 +f 596/596/908 594/594/906 597/597/909 +f 596/596/908 597/597/909 598/598/910 +f 596/596/908 598/598/910 599/599/911 +f 600/600/912 601/601/913 602/602/914 +f 602/602/914 601/601/913 603/603/915 +f 604/604/916 605/605/917 606/606/918 +f 604/604/916 606/606/918 607/607/919 +f 506/506/920 496/496/920 505/505/920 +f 505/505/921 496/496/723 375/375/725 +f 505/505/922 375/375/922 384/384/922 +f 384/384/923 375/375/924 385/385/925 +f 385/385/925 375/375/924 374/374/926 +f 492/492/927 488/488/927 472/472/927 +f 472/472/928 488/488/928 353/353/928 +f 472/472/795 353/353/929 366/366/796 +f 366/366/930 353/353/931 367/367/932 +f 367/367/932 353/353/931 352/352/933 +f 478/478/934 473/473/935 477/477/936 +f 477/477/936 473/473/935 472/472/937 +f 477/477/697 472/472/795 344/344/823 +f 344/344/823 472/472/795 333/333/797 +f 344/344/938 333/333/939 345/345/940 +f 345/345/940 333/333/939 332/332/941 +f 462/462/934 457/457/934 461/461/934 +f 461/461/942 457/457/942 316/316/942 +f 461/461/842 316/316/943 326/326/841 +f 326/326/930 316/316/931 327/327/932 +f 327/327/932 316/316/931 315/315/933 +f 447/447/934 442/442/934 446/446/934 +f 446/446/942 442/442/942 296/296/942 +f 446/446/944 296/296/944 307/307/944 +f 307/307/945 296/296/946 308/308/947 +f 308/308/947 296/296/946 295/295/933 +f 432/432/934 428/428/934 431/431/934 +f 431/431/948 428/428/948 276/276/948 +f 431/431/871 276/276/949 285/285/872 +f 285/285/950 276/276/951 286/286/952 +f 286/286/952 276/276/951 275/275/953 +f 418/418/954 408/408/955 417/417/956 +f 417/417/956 408/408/955 250/250/957 +f 417/417/958 250/250/959 267/267/960 +f 267/267/961 250/250/962 268/268/963 +f 268/268/963 250/250/962 249/249/964 +f 391/391/965 379/379/966 390/390/967 +f 390/390/967 379/379/966 382/382/968 +f 390/390/788 382/382/754 243/243/785 +f 243/243/785 382/382/754 240/240/756 +f 243/243/969 240/240/970 242/242/971 +f 242/242/971 240/240/970 241/241/972 +f 362/362/973 357/357/974 363/363/975 +f 363/363/975 357/357/974 360/360/976 +f 363/363/815 360/360/789 234/234/813 +f 234/234/813 360/360/789 231/231/787 +f 234/234/977 231/231/978 233/233/979 +f 233/233/979 231/231/978 232/232/980 +f 341/341/973 337/337/974 342/342/981 +f 342/342/981 337/337/974 340/340/982 +f 342/342/835 340/340/816 226/226/813 +f 226/226/813 340/340/816 223/223/814 +f 226/226/977 223/223/978 225/225/979 +f 225/225/979 223/223/978 224/224/980 +f 325/325/983 321/321/984 304/304/985 +f 304/304/985 321/321/984 324/324/986 +f 304/304/858 324/324/836 218/218/856 +f 218/218/856 324/324/836 215/215/814 +f 218/218/987 215/215/988 217/217/989 +f 217/217/989 215/215/988 216/216/990 +f 305/305/983 300/300/991 283/283/992 +f 283/283/992 300/300/991 304/304/993 +f 283/283/869 304/304/858 210/210/868 +f 210/210/868 304/304/858 207/207/857 +f 210/210/994 207/207/978 209/209/989 +f 209/209/989 207/207/978 208/208/995 +f 290/290/965 280/280/996 289/289/997 +f 289/289/997 280/280/996 283/283/998 +f 289/289/893 283/283/869 202/202/891 +f 202/202/891 283/283/869 199/199/857 +f 202/202/977 199/199/988 201/201/989 +f 201/201/989 199/199/988 200/200/995 +f 262/262/999 254/254/1000 263/263/1001 +f 263/263/1001 254/254/1000 257/257/1002 +f 263/263/899 257/257/894 194/194/1003 +f 194/194/1003 257/257/894 190/190/892 +f 194/194/1004 190/190/1005 192/192/1006 +f 192/192/1006 190/190/1005 191/191/1007 +f 244/244/1008 238/238/1008 237/237/1008 +f 244/244/1009 237/237/1009 371/371/1009 +f 235/235/1010 229/229/1010 228/228/1010 +f 235/235/1011 228/228/1011 349/349/1011 +f 227/227/1010 221/221/1010 220/220/1010 +f 227/227/1012 220/220/1012 329/329/1012 +f 219/219/1013 213/213/1013 212/212/1013 +f 219/219/1012 212/212/1012 312/312/1012 +f 211/211/1013 205/205/1013 204/204/1013 +f 211/211/1012 204/204/1012 292/292/1012 +f 203/203/1013 197/197/1013 196/196/1013 +f 203/203/1012 196/196/1012 272/272/1012 +f 193/193/1014 189/189/1015 195/195/1016 +f 195/195/1016 189/189/1015 188/188/1017 +f 195/195/1018 188/188/1019 259/259/614 +f 259/259/614 188/188/1019 246/246/615 +f 605/605/1020 604/604/1021 590/590/902 +f 590/590/902 604/604/1021 591/591/903 +f 511/511/721 512/512/722 606/606/1022 +f 606/606/1022 512/512/722 607/607/1023 +f 608/608/1024 609/609/1025 396/396/620 +f 396/396/620 609/609/1025 397/397/621 +f 394/394/618 395/395/619 608/608/1026 +f 608/608/1026 395/395/619 609/609/1027 +f 398/398/622 399/399/623 601/601/913 +f 601/601/913 399/399/623 603/603/915 +f 413/413/1028 415/415/1028 610/610/1028 +f 194/194/1029 195/195/1029 611/611/1029 +f 586/586/896 612/612/1030 613/613/1031 +f 614/614/1032 615/615/1032 616/616/1032 +f 587/587/1033 617/617/1033 588/588/1033 +f 195/195/1034 258/258/1034 618/618/1034 +f 619/619/1035 411/411/1036 617/617/1037 +f 587/587/1038 619/619/1035 617/617/1037 +f 620/620/1039 621/621/1039 622/622/1039 +f 267/267/960 264/264/1040 623/623/1041 +f 264/264/1042 266/266/1043 624/624/1044 +f 266/266/1045 261/261/1045 625/625/1045 +f 410/410/1046 413/413/1046 626/626/1046 +f 410/410/1047 626/626/1047 627/627/1047 +f 263/263/899 194/194/1003 589/589/900 +f 627/627/1048 617/617/1037 411/411/1036 +f 628/628/1049 620/620/1049 622/622/1049 +f 623/623/1050 629/629/1050 417/417/1050 +f 258/258/1051 628/628/1051 630/630/1051 +f 628/628/1052 622/622/1052 630/630/1052 +f 618/618/1053 258/258/1053 630/630/1053 +f 611/611/1054 195/195/1054 618/618/1054 +f 589/589/1055 194/194/1055 611/611/1055 +f 631/631/1056 261/261/901 589/589/900 +f 625/625/1057 261/261/901 631/631/1056 +f 624/624/1044 266/266/1043 625/625/1058 +f 632/632/1059 264/264/1042 624/624/1044 +f 623/623/1060 264/264/1060 632/632/1060 +f 411/411/1061 410/410/1061 627/627/1061 +f 615/615/1062 613/613/1062 616/616/1062 +f 610/610/1063 415/415/1063 629/629/1063 +f 267/267/960 623/623/1041 417/417/958 +f 615/615/1064 586/586/1064 613/613/1064 +f 586/586/896 588/588/898 612/612/1030 +f 415/415/1065 417/417/1065 629/629/1065 +f 614/614/1066 616/616/1066 621/621/1066 +f 621/621/1067 620/620/1067 614/614/1067 +f 609/609/1068 395/395/1069 633/633/1070 +f 582/582/71 634/634/71 585/585/71 +f 585/585/71 634/634/71 635/635/71 +f 628/628/210 258/258/641 636/636/641 +f 636/636/641 637/637/210 628/628/210 +f 628/628/210 637/637/210 620/620/210 +f 572/572/71 638/638/1071 574/574/1072 +f 574/574/1072 638/638/1071 639/639/1073 +f 584/584/1074 640/640/1075 583/583/210 +f 584/584/1074 639/639/1076 640/640/1075 +f 561/561/1077 641/641/1078 565/565/1079 +f 565/565/1079 641/641/1078 642/642/1080 +f 561/561/1077 643/643/1081 641/641/1078 +f 573/573/1082 641/641/1083 571/571/1084 +f 573/573/1082 642/642/1085 641/641/1083 +f 641/641/1083 643/643/1086 571/571/1084 +f 553/553/1077 644/644/1078 557/557/1079 +f 557/557/1079 644/644/1078 645/645/1080 +f 553/553/1077 646/646/1087 644/644/1078 +f 564/564/1082 644/644/1083 563/563/1084 +f 564/564/1082 645/645/1085 644/644/1083 +f 644/644/1083 646/646/1086 563/563/1084 +f 546/546/1077 647/647/1078 549/549/1079 +f 549/549/1079 647/647/1078 648/648/1088 +f 546/546/1077 649/649/1081 647/647/1078 +f 556/556/1082 647/647/1083 555/555/1084 +f 556/556/1082 648/648/1085 647/647/1083 +f 647/647/1083 649/649/1086 555/555/1084 +f 539/539/71 650/650/1071 541/541/1072 +f 541/541/1072 650/650/1071 651/651/1073 +f 548/548/1089 652/652/1090 547/547/210 +f 548/548/1089 651/651/1076 652/652/1090 +f 525/525/1091 653/653/1092 527/527/1093 +f 527/527/1093 653/653/1092 654/654/1094 +f 540/540/1089 655/655/1090 538/538/210 +f 540/540/1089 654/654/1076 655/655/1090 +f 634/634/1095 637/637/1096 636/636/1097 +f 634/634/1095 636/636/1097 635/635/1098 +f 638/638/1099 640/640/1099 639/639/1099 +f 650/650/1100 652/652/1100 651/651/1100 +f 653/653/1100 655/655/1100 654/654/1100 +f 401/401/71 656/656/71 576/576/71 +f 580/580/71 657/657/71 582/582/71 +f 656/656/71 658/658/71 576/576/71 +f 576/576/71 658/658/71 578/578/71 +f 578/578/71 658/658/71 659/659/71 +f 578/578/71 659/659/71 580/580/71 +f 580/580/71 659/659/71 660/660/71 +f 580/580/71 660/660/71 657/657/71 +f 661/661/210 619/619/462 587/587/210 +f 614/614/210 662/662/210 615/615/210 +f 615/615/210 662/662/210 663/663/1101 +f 615/615/210 663/663/1101 586/586/210 +f 586/586/210 663/663/1101 664/664/210 +f 586/586/210 664/664/210 587/587/210 +f 587/587/210 664/664/210 661/661/210 +f 614/614/210 665/665/1102 662/662/210 +f 567/567/1103 420/420/1104 666/666/1105 +f 666/666/1105 667/667/1106 567/567/1103 +f 567/567/1103 667/667/1106 668/668/1107 +f 668/668/1107 667/667/1106 669/669/1108 +f 669/669/1108 667/667/1106 670/670/1109 +f 669/669/1108 670/670/1109 568/568/1110 +f 568/568/1110 670/670/1109 671/671/1111 +f 568/568/1110 671/671/1111 569/569/1112 +f 569/569/1112 671/671/1111 672/672/71 +f 673/673/210 575/575/210 577/577/210 +f 583/583/210 674/674/210 581/581/210 +f 581/581/210 675/675/210 579/579/210 +f 579/579/210 675/675/210 676/676/210 +f 579/579/210 676/676/210 577/577/210 +f 577/577/210 676/676/210 677/677/210 +f 577/577/210 677/677/210 673/673/210 +f 581/581/210 674/674/210 675/675/210 +f 434/434/1113 678/678/1114 559/559/1115 +f 560/560/1116 679/679/1117 561/561/1118 +f 678/678/1114 680/680/1119 559/559/1115 +f 559/559/1115 680/680/1119 681/681/1120 +f 681/681/1120 680/680/1119 682/682/1121 +f 681/681/1120 682/682/1121 683/683/1122 +f 683/683/1122 682/682/1121 684/684/1123 +f 683/683/1122 684/684/1123 560/560/1116 +f 560/560/1116 684/684/1123 685/685/1124 +f 560/560/1116 685/685/1124 679/679/1117 +f 686/686/1125 566/566/1126 567/567/1127 +f 568/568/1128 570/570/1129 687/687/1130 +f 568/568/1128 685/685/1131 669/669/1132 +f 669/669/1132 685/685/1131 684/684/1133 +f 669/669/1132 684/684/1133 668/668/1134 +f 668/668/1134 684/684/1133 682/682/1135 +f 668/668/1134 682/682/1135 567/567/1127 +f 567/567/1127 682/682/1135 680/680/1136 +f 567/567/1127 680/680/1136 686/686/1125 +f 568/568/1128 687/687/1130 685/685/1131 +f 552/552/1137 688/688/1117 553/553/1118 +f 551/551/1138 449/449/1104 689/689/1139 +f 689/689/1139 690/690/1140 551/551/1138 +f 551/551/1138 690/690/1140 691/691/1120 +f 691/691/1120 690/690/1140 692/692/1121 +f 691/691/1120 692/692/1121 693/693/1122 +f 693/693/1122 692/692/1121 694/694/1123 +f 693/693/1122 694/694/1123 552/552/1137 +f 552/552/1137 694/694/1123 695/695/1141 +f 552/552/1137 695/695/1141 688/688/1117 +f 696/696/1125 558/558/1126 559/559/1127 +f 560/560/1142 562/562/1143 697/697/1144 +f 560/560/1142 695/695/1145 683/683/1146 +f 683/683/1146 695/695/1145 694/694/1133 +f 683/683/1146 694/694/1133 681/681/1147 +f 681/681/1147 694/694/1133 692/692/1135 +f 681/681/1147 692/692/1135 559/559/1127 +f 559/559/1127 692/692/1135 690/690/1136 +f 559/559/1127 690/690/1136 696/696/1125 +f 560/560/1142 697/697/1144 695/695/1145 +f 545/545/1148 698/698/1149 546/546/1150 +f 543/543/1151 464/464/1104 699/699/1139 +f 699/699/1139 700/700/1152 543/543/1151 +f 543/543/1151 700/700/1152 701/701/1153 +f 701/701/1153 700/700/1152 702/702/1154 +f 701/701/1153 702/702/1154 703/703/1155 +f 701/701/1153 703/703/1155 704/704/1156 +f 704/704/1156 703/703/1155 545/545/1148 +f 545/545/1148 703/703/1155 705/705/1157 +f 545/545/1148 705/705/1157 698/698/1149 +f 706/706/1125 550/550/1126 551/551/1127 +f 552/552/1158 554/554/1143 707/707/1144 +f 552/552/1158 705/705/1145 693/693/1146 +f 693/693/1146 705/705/1145 703/703/1133 +f 693/693/1146 703/703/1133 691/691/1134 +f 691/691/1134 703/703/1133 702/702/1135 +f 691/691/1134 702/702/1135 551/551/1127 +f 551/551/1127 702/702/1135 700/700/1136 +f 551/551/1127 700/700/1136 706/706/1125 +f 552/552/1158 707/707/1144 705/705/1145 +f 533/533/1159 531/531/1160 708/708/1161 +f 708/708/1161 709/709/1162 533/533/1159 +f 533/533/1159 709/709/1162 534/534/1163 +f 534/534/1163 709/709/1162 710/710/1164 +f 534/534/1163 710/710/1164 535/535/1165 +f 535/535/1165 710/710/1164 711/711/1166 +f 535/535/1165 711/711/1166 536/536/1167 +f 536/536/1167 711/711/1166 712/712/71 +f 713/713/1168 542/542/1126 543/543/1169 +f 545/545/1170 544/544/1171 714/714/1172 +f 545/545/1170 715/715/1173 704/704/1174 +f 704/704/1174 715/715/1173 716/716/1175 +f 704/704/1174 716/716/1175 701/701/1176 +f 701/701/1176 716/716/1175 543/543/1169 +f 543/543/1169 716/716/1175 717/717/1177 +f 543/543/1169 717/717/1177 713/713/1168 +f 545/545/1170 714/714/1172 715/715/1173 +f 494/494/71 718/718/71 520/520/71 +f 718/718/71 719/719/71 520/520/71 +f 520/520/71 719/719/71 518/518/71 +f 518/518/71 719/719/71 720/720/71 +f 518/518/71 720/720/71 524/524/71 +f 524/524/71 720/720/71 721/721/1178 +f 524/524/71 721/721/1178 522/522/1179 +f 522/522/1179 721/721/1178 722/722/1180 +f 723/723/1181 531/531/1182 532/532/1183 +f 535/535/1184 537/537/1185 724/724/1186 +f 535/535/1184 725/725/1187 534/534/1188 +f 534/534/1188 725/725/1187 726/726/1189 +f 534/534/1188 726/726/1189 532/532/1183 +f 532/532/1183 726/726/1189 727/727/210 +f 532/532/1183 727/727/210 723/723/1181 +f 535/535/1184 724/724/1186 725/725/1187 +f 656/656/1190 661/661/1191 664/664/1192 +f 656/656/1190 664/664/1192 658/658/1193 +f 658/658/1194 664/664/1195 663/663/1196 +f 658/658/1194 663/663/1196 659/659/1197 +f 659/659/1197 663/663/1196 662/662/1198 +f 659/659/1197 662/662/1198 660/660/1199 +f 660/660/1199 662/662/1198 665/665/1200 +f 660/660/1199 665/665/1200 657/657/1201 +f 666/666/1202 673/673/1202 677/677/1202 +f 666/666/1203 677/677/1203 667/667/1203 +f 667/667/1204 677/677/1204 676/676/1204 +f 667/667/1106 676/676/1205 670/670/1109 +f 670/670/1206 676/676/1206 675/675/1206 +f 670/670/1109 675/675/1207 671/671/1111 +f 671/671/1208 675/675/1208 674/674/1208 +f 671/671/1209 674/674/1209 672/672/1209 +f 678/678/1210 686/686/1210 680/680/1210 +f 685/685/1211 687/687/1211 679/679/1211 +f 689/689/1212 696/696/1212 690/690/1212 +f 695/695/1213 697/697/1213 688/688/1213 +f 699/699/1212 706/706/1212 700/700/1212 +f 705/705/1214 707/707/1214 698/698/1214 +f 708/708/1215 713/713/1215 717/717/1215 +f 708/708/1203 717/717/1203 709/709/1203 +f 709/709/1204 717/717/1177 716/716/1175 +f 709/709/1162 716/716/1205 710/710/1164 +f 710/710/1206 716/716/1175 715/715/1173 +f 710/710/1164 715/715/1207 711/711/1166 +f 711/711/1216 715/715/1216 714/714/1216 +f 711/711/1217 714/714/1217 712/712/1217 +f 718/718/1218 723/723/1219 727/727/1220 +f 718/718/1218 727/727/1220 719/719/1221 +f 719/719/1204 727/727/1204 726/726/1204 +f 719/719/1205 726/726/1205 720/720/1205 +f 720/720/1206 726/726/1189 725/725/1187 +f 720/720/1207 725/725/1207 721/721/1207 +f 721/721/1216 725/725/1216 724/724/1216 +f 721/721/1217 724/724/1217 722/722/1217 +f 728/728/1222 729/729/1223 730/730/1224 +f 730/730/1224 729/729/1223 731/731/1225 +f 732/732/1226 733/733/1227 734/734/1228 +f 734/734/1228 733/733/1227 735/735/1229 +f 736/736/1230 737/737/1231 738/738/1232 +f 736/736/1230 738/738/1232 739/739/1233 +f 739/739/1233 738/738/1232 740/740/1234 +f 740/740/1234 738/738/1232 741/741/1235 +f 740/740/1234 741/741/1235 742/742/1236 +f 742/742/1236 741/741/1235 729/729/1223 +f 742/742/1236 729/729/1223 728/728/1222 +f 743/743/1237 744/744/1238 745/745/1239 +f 743/743/1237 745/745/1239 746/746/1240 +f 723/723/1241 718/718/1241 531/531/1241 +f 531/531/1242 718/718/1242 494/494/1242 +f 531/531/770 494/494/1243 504/504/769 +f 504/504/1244 494/494/1244 493/493/1244 +f 713/713/1245 708/708/1246 542/542/1247 +f 542/542/1247 708/708/1246 531/531/1248 +f 542/542/1249 531/531/770 480/480/768 +f 542/542/1249 480/480/768 491/491/1250 +f 491/491/1251 480/480/1252 479/479/1253 +f 491/491/1251 479/479/1253 489/489/1254 +f 706/706/1245 699/699/1255 550/550/1256 +f 550/550/1256 699/699/1255 464/464/1257 +f 550/550/1258 464/464/1258 476/476/1258 +f 476/476/1259 464/464/1259 463/463/1259 +f 476/476/1260 463/463/1260 474/474/1260 +f 696/696/1245 689/689/1261 558/558/1262 +f 558/558/1262 689/689/1261 449/449/1263 +f 558/558/1258 449/449/1258 460/460/1258 +f 460/460/1259 449/449/1259 448/448/1259 +f 460/460/1260 448/448/1260 458/458/1260 +f 686/686/1264 678/678/1264 566/566/1264 +f 566/566/1265 678/678/1265 434/434/1265 +f 566/566/1266 434/434/1266 445/445/1266 +f 445/445/1267 434/434/1268 433/433/1269 +f 445/445/1267 433/433/1269 443/443/1254 +f 673/673/1245 666/666/1255 575/575/1262 +f 575/575/1262 666/666/1255 420/420/1257 +f 575/575/1258 420/420/1258 430/430/1258 +f 430/430/1270 420/420/1270 419/419/1270 +f 661/661/1271 656/656/1271 619/619/1271 +f 619/619/1272 656/656/1272 401/401/1272 +f 619/619/1035 401/401/1273 411/411/1036 +f 411/411/1274 401/401/1275 400/400/1276 +f 411/411/1274 400/400/1276 409/409/1277 +f 655/655/1278 653/653/1279 538/538/1280 +f 538/538/1280 653/653/1279 525/525/1281 +f 538/538/776 525/525/743 537/537/775 +f 537/537/775 525/525/743 522/522/745 +f 537/537/1282 522/522/1283 724/724/1284 +f 724/724/1284 522/522/1283 722/722/1285 +f 652/652/1278 650/650/1286 547/547/1287 +f 547/547/1287 650/650/1286 539/539/1288 +f 547/547/807 539/539/777 544/544/804 +f 544/544/804 539/539/777 536/536/774 +f 544/544/1289 536/536/1290 714/714/1291 +f 714/714/1291 536/536/1290 712/712/1292 +f 555/555/1293 649/649/1293 546/546/1293 +f 555/555/829 546/546/1294 554/554/828 +f 554/554/1295 546/546/1295 698/698/1295 +f 554/554/1296 698/698/1296 707/707/1296 +f 563/563/1293 646/646/1293 553/553/1293 +f 563/563/852 553/553/1297 562/562/851 +f 562/562/1295 553/553/1295 688/688/1295 +f 562/562/1298 688/688/1298 697/697/1298 +f 571/571/1293 643/643/1293 561/561/1293 +f 571/571/864 561/561/1297 570/570/863 +f 570/570/1295 561/561/1295 679/679/1295 +f 570/570/1299 679/679/1300 687/687/1300 +f 640/640/1301 638/638/1302 583/583/1303 +f 583/583/1303 638/638/1302 572/572/1304 +f 583/583/1305 572/572/865 569/569/862 +f 583/583/1306 569/569/1306 674/674/1306 +f 674/674/1307 569/569/1307 672/672/1307 +f 637/637/1308 634/634/1309 620/620/1310 +f 620/620/1310 634/634/1309 582/582/1311 +f 620/620/1312 582/582/1312 614/614/1312 +f 614/614/1313 582/582/1313 657/657/1313 +f 614/614/1314 657/657/1314 665/665/1314 +f 383/383/1315 372/372/1315 370/370/1315 +f 383/383/780 370/370/749 540/540/778 +f 540/540/778 370/370/749 527/527/748 +f 540/540/778 527/527/748 654/654/1316 +f 548/548/808 348/348/781 541/541/779 +f 548/548/1317 541/541/1317 651/651/1317 +f 311/311/832 330/330/1318 328/328/810 +f 311/311/832 328/328/810 556/556/830 +f 556/556/830 328/328/810 549/549/809 +f 556/556/1317 549/549/1317 648/648/1317 +f 291/291/854 313/313/1319 311/311/832 +f 291/291/854 311/311/832 564/564/853 +f 564/564/853 311/311/832 557/557/831 +f 564/564/1320 557/557/1320 645/645/1320 +f 271/271/854 293/293/1319 291/291/854 +f 271/271/854 291/291/854 573/573/866 +f 573/573/866 291/291/854 565/565/831 +f 573/573/1320 565/565/1320 642/642/1320 +f 245/245/890 273/273/1319 271/271/854 +f 245/245/890 271/271/854 584/584/887 +f 584/584/887 271/271/854 574/574/867 +f 584/584/1320 574/574/1320 639/639/1320 +f 260/260/1321 247/247/1322 258/258/1323 +f 258/258/1323 247/247/1322 245/245/890 +f 258/258/1323 245/245/890 585/585/889 +f 258/258/1323 585/585/889 636/636/1324 +f 636/636/1325 585/585/1325 635/635/1325 +f 599/599/911 598/598/910 745/745/1326 +f 745/745/1326 598/598/910 746/746/1327 +f 744/744/1238 743/743/1237 736/736/1230 +f 736/736/1230 743/743/1237 737/737/1231 +f 733/733/1227 732/732/1226 747/747/1328 +f 747/747/1328 732/732/1226 748/748/1329 +f 747/747/1330 748/748/1331 731/731/1225 +f 731/731/1225 748/748/1331 730/730/1224 +f 600/600/912 602/602/914 735/735/1229 +f 735/735/1229 602/602/914 734/734/1228 +f 633/633/1070 749/749/1332 609/609/1068 +f 609/609/1068 749/749/1332 397/397/1333 +f 730/730/1334 750/750/1334 728/728/1334 +f 730/730/1224 748/748/1331 750/750/1335 +f 751/751/1336 752/752/1337 753/753/1338 +f 754/754/1339 755/755/1340 756/756/1341 +f 751/751/1336 754/754/1339 756/756/1341 +f 757/757/1342 758/758/1343 759/759/1344 +f 757/757/1342 760/760/1345 758/758/1343 +f 761/761/1346 760/760/1345 757/757/1342 +f 762/762/1347 761/761/1346 757/757/1342 +f 763/763/1348 764/764/1349 765/765/1350 +f 764/764/1349 766/766/1351 767/767/1352 +f 764/764/1349 767/767/1352 765/765/1350 +f 766/766/1351 764/764/1349 768/768/1353 +f 769/769/1354 770/770/1355 766/766/1356 +f 771/771/1357 770/770/1355 769/769/1354 +f 772/772/1358 770/770/1355 771/771/1357 +f 773/773/1359 774/774/1360 775/775/1361 +f 773/773/1359 775/775/1361 776/776/1362 +f 777/777/1363 778/778/1364 779/779/1365 +f 778/778/1364 780/780/1366 779/779/1365 +f 781/781/1367 782/782/1368 783/783/1369 +f 784/784/1370 785/785/1371 786/786/1372 +f 787/787/1373 788/788/1374 789/789/1375 +f 787/787/1373 789/789/1375 790/790/1376 +f 791/791/1377 792/792/1378 790/790/1376 +f 791/791/1377 793/793/1379 792/792/1378 +f 769/769/1354 794/794/1380 771/771/1357 +f 764/764/1349 794/794/1380 768/768/1353 +f 772/772/1358 771/771/1357 795/795/1381 +f 791/791/1377 790/790/1376 789/789/1375 +f 786/786/1372 789/789/1375 788/788/1374 +f 786/786/1372 788/788/1374 784/784/1370 +f 794/794/1380 764/764/1349 771/771/1357 +f 771/771/1357 796/796/1382 795/795/1381 +f 763/763/1348 797/797/1383 764/764/1349 +f 764/764/1349 797/797/1383 798/798/1384 +f 764/764/1349 798/798/1384 771/771/1357 +f 771/771/1357 798/798/1384 796/796/1382 +f 795/795/1381 796/796/1382 799/799/1385 +f 800/800/1386 801/801/1387 763/763/1348 +f 763/763/1348 801/801/1387 797/797/1383 +f 799/799/1385 796/796/1382 776/776/1362 +f 800/800/1386 802/802/1388 801/801/1387 +f 798/798/1384 773/773/1359 796/796/1382 +f 796/796/1382 773/773/1359 776/776/1362 +f 797/797/1383 801/801/1387 803/803/1389 +f 797/797/1383 803/803/1389 798/798/1384 +f 798/798/1384 803/803/1389 773/773/1359 +f 751/751/1336 753/753/1338 791/791/1377 +f 786/786/1372 785/785/1371 804/804/1390 +f 791/791/1377 753/753/1338 793/793/1379 +f 805/805/1391 791/791/1377 789/789/1375 +f 805/805/1391 789/789/1375 786/786/1372 +f 802/802/1388 806/806/1392 807/807/1393 +f 802/802/1388 807/807/1393 801/801/1387 +f 773/773/1359 803/803/1389 808/808/1394 +f 773/773/1359 808/808/1394 774/774/1360 +f 809/809/1395 762/762/1347 807/807/1393 +f 809/809/1395 807/807/1393 806/806/1392 +f 801/801/1387 807/807/1393 803/803/1389 +f 774/774/1360 808/808/1394 777/777/1363 +f 774/774/1360 777/777/1363 810/810/1396 +f 757/757/1342 759/759/1344 751/751/1336 +f 757/757/1342 751/751/1336 811/811/1397 +f 812/812/1398 813/813/1399 814/814/1400 +f 814/814/1400 813/813/1399 815/815/1401 +f 814/814/1400 815/815/1401 777/777/1363 +f 777/777/1363 815/815/1401 778/778/1364 +f 811/811/1397 751/751/1336 816/816/1402 +f 811/811/1397 816/816/1402 812/812/1398 +f 778/778/1364 815/815/1401 783/783/1369 +f 759/759/1344 754/754/1339 751/751/1336 +f 812/812/1398 816/816/1402 805/805/1391 +f 812/812/1398 805/805/1391 813/813/1399 +f 815/815/1401 781/781/1367 783/783/1369 +f 751/751/1336 756/756/1341 752/752/1337 +f 751/751/1336 791/791/1377 816/816/1402 +f 816/816/1402 791/791/1377 805/805/1391 +f 813/813/1399 805/805/1391 786/786/1372 +f 813/813/1399 786/786/1372 815/815/1401 +f 815/815/1401 786/786/1372 804/804/1390 +f 815/815/1401 804/804/1390 781/781/1367 +f 781/781/1367 804/804/1390 817/817/1403 +f 807/807/1393 762/762/1347 757/757/1342 +f 803/803/1389 812/812/1398 808/808/1394 +f 810/810/1396 777/777/1363 779/779/1365 +f 807/807/1393 757/757/1342 811/811/1397 +f 807/807/1393 811/811/1397 803/803/1389 +f 803/803/1389 811/811/1397 812/812/1398 +f 808/808/1394 812/812/1398 814/814/1400 +f 808/808/1394 814/814/1400 777/777/1363 +f 818/818/1404 395/395/619 819/819/1405 +f 819/819/1405 395/395/619 393/393/617 +f 820/820/1406 399/399/623 397/397/621 +f 820/820/1406 397/397/621 821/821/1407 +f 393/393/617 822/822/1408 819/819/1405 +f 507/507/717 822/822/1408 393/393/617 +f 822/822/1408 507/507/717 823/823/1409 +f 823/823/1409 507/507/717 824/824/1410 +f 509/509/719 824/824/1410 507/507/717 +f 824/824/1410 509/509/719 825/825/1411 +f 825/825/1411 509/509/719 826/826/1412 +f 826/826/1412 509/509/719 511/511/721 +f 827/827/1413 590/590/902 828/828/1414 +f 828/828/1414 590/590/902 593/593/905 +f 593/593/905 829/829/1415 828/828/1414 +f 595/595/907 829/829/1415 593/593/905 +f 829/829/1415 595/595/907 830/830/1416 +f 831/831/1417 830/830/1416 595/595/907 +f 831/831/1417 595/595/907 596/596/908 +f 831/831/1417 596/596/908 832/832/1418 +f 599/599/911 832/832/1418 596/596/908 +f 833/833/1419 834/834/1420 602/602/914 +f 833/833/1419 602/602/914 603/603/915 +f 833/833/1419 603/603/915 767/767/1421 +f 399/399/623 767/767/1421 603/603/915 +f 399/399/623 820/820/1422 767/767/1421 +f 835/835/71 836/836/71 837/837/71 +f 837/837/71 836/836/71 838/838/71 +f 839/839/71 840/840/71 841/841/71 +f 839/839/71 841/841/71 842/842/71 +f 843/843/1423 768/768/1424 844/844/1425 +f 844/844/1425 768/768/1424 794/794/1426 +f 768/768/1427 843/843/1428 845/845/1429 +f 768/768/1427 845/845/1429 766/766/1430 +f 846/846/1431 766/766/1432 845/845/1433 +f 846/846/1431 769/769/1434 766/766/1432 +f 844/844/1435 794/794/1436 846/846/1437 +f 846/846/1437 794/794/1436 769/769/1438 +f 838/838/1439 760/760/1440 837/837/1441 +f 837/837/1441 760/760/1440 755/755/1442 +f 760/760/1443 838/838/1443 758/758/1443 +f 758/758/1444 838/838/1445 836/836/1446 +f 758/758/1444 836/836/1446 759/759/1447 +f 759/759/1448 836/836/1449 835/835/1450 +f 759/759/1448 835/835/1450 754/754/1451 +f 754/754/1452 835/835/1453 755/755/1454 +f 837/837/1455 755/755/1454 835/835/1453 +f 847/847/1456 848/848/1457 849/849/1458 +f 749/749/1459 850/850/1460 851/851/1461 +f 633/633/1462 852/852/1463 850/850/1460 +f 633/633/1462 850/850/1460 749/749/1459 +f 511/511/721 853/853/1464 826/826/1412 +f 853/853/1464 511/511/721 848/848/1457 +f 853/853/1464 848/848/1457 847/847/1456 +f 590/590/902 854/854/1465 848/848/1466 +f 848/848/1466 854/854/1465 849/849/1467 +f 590/590/902 827/827/1413 854/854/1465 +f 397/397/621 855/855/1468 821/821/1407 +f 855/855/1468 397/397/621 851/851/1461 +f 851/851/1461 397/397/621 749/749/1459 +f 395/395/619 856/856/1469 633/633/1462 +f 633/633/1462 856/856/1469 852/852/1463 +f 395/395/619 818/818/1404 856/856/1469 +f 832/832/1418 788/788/1374 831/831/1417 +f 831/831/1417 788/788/1374 787/787/1373 +f 787/787/1373 790/790/1376 830/830/1416 +f 830/830/1416 790/790/1376 829/829/1415 +f 828/828/1414 790/790/1376 792/792/1378 +f 831/831/1417 787/787/1373 830/830/1416 +f 788/788/1374 832/832/1418 784/784/1370 +f 828/828/1414 792/792/1378 827/827/1413 +f 828/828/1414 829/829/1415 790/790/1376 +f 793/793/1379 854/854/1465 827/827/1413 +f 793/793/1379 827/827/1413 792/792/1378 +f 793/793/1379 857/857/1470 854/854/1465 +f 854/854/1465 857/857/1470 849/849/1467 +f 753/753/1338 857/857/1470 793/793/1379 +f 847/847/1471 849/849/1471 857/857/1471 +f 857/857/1470 753/753/1338 752/752/1337 +f 853/853/1464 847/847/1456 857/857/1470 +f 853/853/1464 857/857/1470 752/752/1337 +f 853/853/1464 752/752/1337 826/826/1412 +f 755/755/1340 760/760/1345 761/761/1346 +f 819/819/1405 822/822/1408 762/762/1347 +f 761/761/1346 822/822/1408 823/823/1409 +f 761/761/1346 823/823/1409 824/824/1410 +f 755/755/1340 824/824/1410 756/756/1341 +f 826/826/1412 756/756/1341 825/825/1411 +f 825/825/1411 756/756/1341 824/824/1410 +f 756/756/1341 826/826/1412 752/752/1337 +f 755/755/1340 761/761/1346 824/824/1410 +f 761/761/1346 762/762/1347 822/822/1408 +f 818/818/1404 819/819/1405 809/809/1395 +f 819/819/1405 762/762/1347 809/809/1395 +f 809/809/1395 806/806/1472 852/852/1463 +f 852/852/1463 856/856/1469 809/809/1395 +f 818/818/1404 809/809/1395 856/856/1469 +f 802/802/1473 852/852/1463 806/806/1472 +f 850/850/1460 852/852/1463 802/802/1473 +f 851/851/1474 850/850/1460 802/802/1473 +f 855/855/1475 800/800/1386 821/821/1476 +f 802/802/1477 800/800/1386 855/855/1475 +f 802/802/1477 855/855/1475 851/851/1478 +f 765/765/1350 820/820/1422 763/763/1348 +f 821/821/1476 763/763/1348 820/820/1422 +f 821/821/1476 800/800/1386 763/763/1348 +f 767/767/1421 820/820/1422 765/765/1350 +f 770/770/1355 834/834/1420 766/766/1351 +f 833/833/1419 766/766/1351 834/834/1420 +f 766/766/1351 833/833/1419 767/767/1352 +f 858/858/1479 750/750/1480 859/859/1481 +f 734/734/1228 860/860/1482 732/732/1226 +f 860/860/1482 861/861/1483 732/732/1226 +f 862/862/1484 736/736/1230 863/863/1485 +f 863/863/1485 736/736/1230 739/739/1233 +f 740/740/1234 864/864/1486 863/863/1485 +f 740/740/1234 863/863/1485 739/739/1233 +f 742/742/1236 864/864/1486 740/740/1234 +f 865/865/1487 864/864/1486 742/742/1236 +f 858/858/1479 865/865/1487 742/742/1236 +f 858/858/1479 742/742/1236 728/728/1222 +f 858/858/1479 728/728/1222 750/750/1480 +f 860/860/1482 734/734/1228 602/602/914 +f 602/602/914 834/834/1420 860/860/1482 +f 780/780/1488 841/841/1488 782/782/1488 +f 782/782/1489 841/841/1489 840/840/1489 +f 782/782/1490 840/840/1490 783/783/1490 +f 783/783/1491 840/840/1491 839/839/1491 +f 783/783/1492 839/839/1492 778/778/1492 +f 778/778/1493 839/839/1493 842/842/1493 +f 778/778/1494 842/842/1494 780/780/1494 +f 780/780/1495 842/842/1495 841/841/1495 +f 866/866/1496 867/867/1497 868/868/1498 +f 869/869/1499 870/870/1500 871/871/1501 +f 872/872/1502 873/873/1503 869/869/1504 +f 869/869/1504 873/873/1503 870/870/1505 +f 736/736/1230 874/874/1506 866/866/1496 +f 866/866/1496 874/874/1506 867/867/1497 +f 862/862/1484 874/874/1506 736/736/1230 +f 599/599/911 875/875/1507 832/832/1418 +f 875/875/1507 599/599/911 866/866/1508 +f 875/875/1507 866/866/1508 868/868/1509 +f 732/732/1226 876/876/1510 872/872/1511 +f 872/872/1511 876/876/1510 873/873/1512 +f 861/861/1483 876/876/1510 732/732/1226 +f 859/859/1481 750/750/1480 877/877/1513 +f 877/877/1513 750/750/1480 871/871/1501 +f 871/871/1501 750/750/1480 869/869/1499 +f 875/875/1514 868/868/1515 785/785/1371 +f 832/832/1418 875/875/1514 784/784/1370 +f 784/784/1370 875/875/1514 785/785/1371 +f 804/804/1516 785/785/1371 868/868/1515 +f 868/868/1515 867/867/1517 804/804/1516 +f 817/817/1403 804/804/1516 867/867/1517 +f 862/862/1484 817/817/1403 874/874/1506 +f 867/867/1517 874/874/1506 817/817/1403 +f 779/779/1365 780/780/1518 781/781/1367 +f 781/781/1367 780/780/1519 782/782/1368 +f 858/858/1520 779/779/1365 865/865/1487 +f 865/865/1487 779/779/1365 864/864/1486 +f 864/864/1486 781/781/1367 863/863/1485 +f 863/863/1485 781/781/1367 862/862/1484 +f 817/817/1403 862/862/1484 781/781/1367 +f 781/781/1367 864/864/1486 779/779/1365 +f 779/779/1365 858/858/1520 810/810/1396 +f 774/774/1360 810/810/1396 859/859/1521 +f 858/858/1520 859/859/1521 810/810/1396 +f 775/775/1361 774/774/1360 877/877/1522 +f 775/775/1361 877/877/1522 871/871/1523 +f 859/859/1521 877/877/1522 774/774/1360 +f 776/776/1362 775/775/1524 870/870/1500 +f 870/870/1500 775/775/1524 871/871/1501 +f 870/870/1500 873/873/1525 776/776/1362 +f 876/876/1526 861/861/1483 799/799/1385 +f 873/873/1525 876/876/1526 776/776/1362 +f 776/776/1362 876/876/1526 799/799/1385 +f 860/860/1482 772/772/1358 795/795/1381 +f 795/795/1381 799/799/1385 861/861/1483 +f 861/861/1483 860/860/1482 795/795/1381 +f 860/860/1482 834/834/1420 772/772/1358 +f 772/772/1358 834/834/1420 770/770/1355 +f 846/846/71 843/843/71 844/844/71 +f 846/846/71 845/845/71 843/843/71 +f 878/878/71 879/879/71 880/880/71 +f 878/878/71 880/880/71 881/881/71 +f 882/882/71 883/883/71 884/884/71 +f 881/881/71 885/885/71 878/878/71 +f 883/883/71 886/886/71 887/887/71 +f 886/886/71 888/888/71 887/887/71 +f 880/880/71 879/879/71 889/889/71 +f 884/884/71 883/883/71 887/887/71 +f 890/890/1527 879/879/1528 885/885/1529 +f 890/890/1527 885/885/1529 881/881/1530 +f 891/891/71 882/882/71 884/884/71 +f 884/884/71 888/888/71 892/892/71 +f 889/889/71 879/879/71 893/893/71 +f 889/889/71 893/893/71 894/894/71 +f 889/889/71 894/894/71 895/895/71 +f 892/892/71 891/891/71 884/884/71 +f 892/892/71 896/896/71 891/891/71 +f 897/897/71 898/898/71 899/899/71 +f 895/895/71 894/894/71 898/898/71 +f 895/895/71 898/898/71 897/897/71 +f 897/897/71 899/899/71 896/896/71 +f 891/891/71 896/896/71 899/899/71 +f 900/900/1531 890/890/1532 901/901/1533 +f 902/902/1534 903/903/210 904/904/1535 +f 905/905/210 901/901/1533 906/906/210 +f 907/907/1536 908/908/210 902/902/210 +f 901/901/1533 890/890/1532 909/909/1537 +f 908/908/210 907/907/1536 903/903/1538 +f 901/901/1533 910/910/210 900/900/1531 +f 901/901/1533 905/905/210 911/911/210 +f 901/901/1533 911/911/210 910/910/210 +f 910/910/210 911/911/210 912/912/210 +f 910/910/210 912/912/210 913/913/210 +f 913/913/210 912/912/210 914/914/210 +f 913/913/210 914/914/210 915/915/210 +f 915/915/210 914/914/210 916/916/210 +f 902/902/210 917/917/210 918/918/210 +f 902/902/210 918/918/210 907/907/1536 +f 915/915/210 916/916/210 919/919/210 +f 919/919/210 916/916/210 917/917/210 +f 917/917/210 916/916/210 918/918/210 +f 888/888/1539 907/907/1540 892/892/1541 +f 892/892/1541 907/907/1540 918/918/1542 +f 892/892/1543 918/918/1543 896/896/1543 +f 896/896/1544 918/918/1544 916/916/1544 +f 896/896/1545 916/916/1545 897/897/1545 +f 897/897/1546 916/916/1546 914/914/1546 +f 897/897/1547 914/914/1547 895/895/1547 +f 895/895/1548 914/914/1548 912/912/1548 +f 895/895/1549 912/912/1550 911/911/1551 +f 895/895/1549 911/911/1551 889/889/1552 +f 889/889/1553 911/911/1553 880/880/1553 +f 880/880/1554 911/911/1555 905/905/1556 +f 880/880/1554 905/905/1556 906/906/1557 +f 881/881/1558 880/880/1558 909/909/1558 +f 909/909/1559 880/880/1559 906/906/1559 +f 881/881/1560 909/909/1560 890/890/1560 +f 879/879/1528 890/890/1527 900/900/1561 +f 879/879/1562 900/900/1562 893/893/1562 +f 893/893/1563 900/900/1563 910/910/1563 +f 893/893/1564 910/910/1564 894/894/1564 +f 894/894/1565 910/910/1565 913/913/1565 +f 894/894/1566 913/913/1566 898/898/1566 +f 898/898/1567 913/913/1567 915/915/1567 +f 898/898/1568 915/915/1568 899/899/1568 +f 899/899/1569 915/915/1569 919/919/1569 +f 899/899/1570 919/919/1570 917/917/1570 +f 899/899/1571 917/917/1571 891/891/1571 +f 891/891/1572 917/917/1573 882/882/1574 +f 882/882/1574 917/917/1573 902/902/1575 +f 883/883/1576 882/882/1576 904/904/1576 +f 904/904/1535 882/882/1577 902/902/1534 +f 883/883/1578 904/904/1578 886/886/1578 +f 886/886/1579 904/904/1579 903/903/1579 +f 888/888/1580 886/886/1580 907/907/1580 +f 907/907/1536 886/886/1581 903/903/1538 +f 879/879/1582 901/901/1583 885/885/1584 +f 885/885/1584 901/901/1583 909/909/1585 +f 885/885/1586 909/909/1587 906/906/1588 +f 885/885/1586 906/906/1588 878/878/1589 +f 878/878/1590 906/906/1590 901/901/1590 +f 878/878/1591 901/901/1591 879/879/1591 +f 888/888/1592 908/908/1592 903/903/1592 +f 888/888/1593 903/903/1593 887/887/1593 +f 887/887/1594 903/903/1594 884/884/1594 +f 884/884/1595 903/903/1595 902/902/1595 +f 884/884/1596 902/902/1597 908/908/1598 +f 884/884/1596 908/908/1598 888/888/1599 +f 920/920/1600 921/921/1601 922/922/1602 +f 923/923/1603 924/924/1604 925/925/1605 +f 926/926/1606 927/927/1607 928/928/1608 +f 929/929/1609 930/930/1610 931/931/1611 +f 932/932/1612 933/933/1613 921/921/1601 +f 934/934/1614 922/922/1614 935/935/1614 +f 933/933/1613 936/936/1615 921/921/1601 +f 937/937/1616 938/938/1617 925/925/1618 +f 939/939/1619 940/940/1620 941/941/1621 +f 942/942/1622 932/932/1623 943/943/1624 +f 944/944/1625 945/945/1626 946/946/1627 +f 946/946/1627 945/945/1626 947/947/1628 +f 939/939/1629 931/931/1630 940/940/1631 +f 948/948/1632 933/933/1632 942/942/1632 +f 942/942/1622 933/933/1633 932/932/1623 +f 932/932/1612 921/921/1601 920/920/1600 +f 949/949/1634 950/950/1634 927/927/1634 +f 933/933/1635 948/948/1636 951/951/1637 +f 949/949/1638 952/952/1639 950/950/1640 +f 925/925/1641 947/947/1642 923/923/1643 +f 953/953/1644 943/943/1644 954/954/1644 +f 955/955/1645 926/926/1606 928/928/1608 +f 956/956/1646 942/942/1646 943/943/1646 +f 954/954/1647 943/943/1624 932/932/1623 +f 928/928/1648 927/927/1649 950/950/1650 +f 928/928/1648 950/950/1650 957/957/1651 +f 945/945/1652 958/958/1653 959/959/1654 +f 925/925/1605 924/924/1604 951/951/1637 +f 951/951/1655 924/924/1655 939/939/1655 +f 921/921/1656 943/943/1657 953/953/1658 +f 960/960/1659 934/934/1660 961/961/1661 +f 923/923/1662 929/929/1609 931/931/1611 +f 922/922/1663 921/921/1663 935/935/1663 +f 938/938/1664 946/946/1627 947/947/1628 +f 956/956/1665 939/939/1619 941/941/1621 +f 961/961/1666 935/935/1666 962/962/1666 +f 962/962/1667 927/927/1607 926/926/1606 +f 947/947/1668 963/963/1669 929/929/1670 +f 940/940/1671 937/937/1671 948/948/1671 +f 933/933/1672 951/951/1672 936/936/1672 +f 958/958/1673 926/926/1673 955/955/1673 +f 937/937/1674 925/925/1674 948/948/1674 +f 948/948/1636 925/925/1605 951/951/1637 +f 964/964/1675 953/953/1675 954/954/1675 +f 952/952/1676 961/961/1677 962/962/1678 +f 952/952/1676 962/962/1678 965/965/1679 +f 965/965/1680 962/962/1680 926/926/1680 +f 947/947/1642 929/929/1681 923/923/1643 +f 956/956/1665 941/941/1621 942/942/1682 +f 960/960/1659 920/920/1683 934/934/1660 +f 961/961/1684 934/934/1684 935/935/1684 +f 957/957/1685 952/952/1639 958/958/1686 +f 963/963/1687 959/959/1688 955/955/1689 +f 935/935/1690 921/921/1690 964/964/1690 +f 952/952/1691 965/965/1691 958/958/1691 +f 955/955/1645 928/928/1608 966/966/1692 +f 944/944/1693 957/957/1693 945/945/1693 +f 929/929/1609 963/963/1694 930/930/1610 +f 924/924/1695 931/931/1695 939/939/1695 +f 941/941/1696 948/948/1696 942/942/1696 +f 935/935/1697 949/949/1698 927/927/1607 +f 930/930/1699 967/967/1700 938/938/1701 +f 964/964/1702 960/960/1702 949/949/1702 +f 963/963/1687 955/955/1689 930/930/1703 +f 936/936/1704 951/951/1705 956/956/1706 +f 936/936/1707 956/956/1707 921/921/1707 +f 964/964/1708 954/954/1647 920/920/1709 +f 964/964/1710 920/920/1710 960/960/1710 +f 928/928/1711 944/944/1712 966/966/1713 +f 966/966/1714 944/944/1714 946/946/1714 +f 928/928/1711 957/957/1715 944/944/1712 +f 947/947/1668 945/945/1716 963/963/1669 +f 940/940/1717 948/948/1717 941/941/1717 +f 931/931/1630 937/937/1718 940/940/1631 +f 921/921/1656 953/953/1658 964/964/1719 +f 958/958/1720 965/965/1720 926/926/1720 +f 955/955/1721 966/966/1721 930/930/1721 +f 952/952/1722 960/960/1659 961/961/1661 +f 950/950/1640 952/952/1639 957/957/1685 +f 935/935/1697 964/964/1723 949/949/1698 +f 967/967/1724 946/946/1724 938/938/1724 +f 938/938/1617 947/947/1725 925/925/1618 +f 951/951/1705 939/939/1726 956/956/1706 +f 921/921/1727 956/956/1727 943/943/1727 +f 949/949/1728 960/960/1728 952/952/1728 +f 930/930/1729 966/966/1729 946/946/1729 +f 930/930/1730 946/946/1730 967/967/1730 +f 954/954/1647 932/932/1623 920/920/1709 +f 920/920/1683 922/922/1731 934/934/1660 +f 962/962/1667 935/935/1697 927/927/1607 +f 957/957/1685 958/958/1686 945/945/1732 +f 945/945/1733 959/959/1733 963/963/1733 +f 931/931/1630 930/930/1699 938/938/1701 +f 931/931/1630 938/938/1701 937/937/1718 +f 958/958/1653 955/955/1734 959/959/1654 +f 923/923/1662 931/931/1611 924/924/1735 +f 968/968/1736 969/969/1736 970/970/1736 +f 971/971/1737 972/972/1737 970/970/1737 +f 972/972/1738 973/973/1738 968/968/1738 +f 974/974/1739 975/975/1740 976/976/1741 +f 975/975/1742 977/977/1743 978/978/1744 +f 977/977/1743 979/979/1745 978/978/1744 +f 978/978/1746 979/979/1746 976/976/1746 +f 979/979/1747 980/980/1747 976/976/1747 +f 976/976/1748 980/980/1748 974/974/1748 +f 980/980/1749 981/981/1749 974/974/1749 +f 974/974/1750 981/981/1750 975/975/1750 +f 975/975/1751 981/981/1751 977/977/1751 +f 977/977/1752 982/982/1753 979/979/1754 +f 981/981/1755 983/983/1756 984/984/1757 +f 981/981/1755 984/984/1757 977/977/1752 +f 985/985/1758 983/983/1756 980/980/1759 +f 980/980/1759 983/983/1756 981/981/1755 +f 979/979/1754 985/985/1758 980/980/1759 +f 977/977/1752 984/984/1757 982/982/1753 +f 979/979/1754 986/986/1760 985/985/1758 +f 979/979/1754 982/982/1753 986/986/1760 +f 969/969/1761 968/968/1762 982/982/1763 +f 982/982/1763 968/968/1762 986/986/1764 +f 986/986/1765 968/968/1766 973/973/1767 +f 986/986/1765 973/973/1767 985/985/1768 +f 985/985/1769 973/973/1770 983/983/1771 +f 983/983/1771 973/973/1770 972/972/1772 +f 972/972/1773 971/971/1773 983/983/1773 +f 983/983/1774 971/971/1775 984/984/1776 +f 971/971/1775 970/970/1777 984/984/1776 +f 984/984/1778 970/970/1779 982/982/1780 +f 970/970/1779 969/969/1781 982/982/1780 +f 970/970/1782 972/972/1782 987/987/1782 +f 987/987/1783 972/972/1783 988/988/1783 +f 968/968/1784 970/970/1785 988/988/1786 +f 988/988/1786 970/970/1785 987/987/1787 +f 972/972/1788 968/968/1788 988/988/1788 +f 978/978/1789 976/976/1741 975/975/1740 +f 989/989/1790 990/990/1790 991/991/1790 +f 992/992/1791 993/993/1791 989/989/1791 +f 991/991/1792 994/994/1792 992/992/1792 +f 995/995/1793 996/996/1793 997/997/1794 +f 995/995/1793 998/998/1795 996/996/1793 +f 999/999/1796 997/997/1797 996/996/1798 +f 999/999/1796 996/996/1798 1000/1000/1799 +f 1000/1000/1800 996/996/1801 1001/1001/1802 +f 1001/1001/1802 996/996/1801 998/998/1803 +f 1001/1001/1804 998/998/1805 1002/1002/1806 +f 1002/1002/1806 998/998/1805 995/995/1807 +f 1002/1002/1808 995/995/1809 999/999/1810 +f 999/999/1810 995/995/1809 997/997/1811 +f 1001/1001/1812 1003/1003/1813 1000/1000/1814 +f 1000/1000/1814 1003/1003/1813 1004/1004/1815 +f 1000/1000/1814 1004/1004/1815 1005/1005/1816 +f 1000/1000/1814 1005/1005/1816 999/999/1817 +f 999/999/1817 1005/1005/1816 1006/1006/1818 +f 999/999/1817 1006/1006/1818 1007/1007/1819 +f 999/999/1817 1007/1007/1819 1002/1002/1820 +f 1002/1002/1820 1007/1007/1819 1008/1008/1821 +f 1002/1002/1820 1008/1008/1821 1001/1001/1812 +f 1001/1001/1812 1008/1008/1821 1003/1003/1813 +f 989/989/1822 1005/1005/1823 990/990/1824 +f 990/990/1824 1005/1005/1823 1004/1004/1825 +f 990/990/1826 1004/1004/1827 1003/1003/1828 +f 990/990/1826 1003/1003/1828 991/991/1829 +f 991/991/1830 1003/1003/1831 994/994/1832 +f 994/994/1832 1003/1003/1831 1008/1008/1833 +f 994/994/1834 1008/1008/1835 1007/1007/1836 +f 994/994/1834 1007/1007/1836 992/992/1837 +f 992/992/1838 1007/1007/1839 993/993/1840 +f 993/993/1840 1007/1007/1839 1006/1006/1841 +f 993/993/1842 1006/1006/1843 1005/1005/1844 +f 993/993/1842 1005/1005/1844 989/989/1845 +f 991/991/1846 992/992/1847 1009/1009/1848 +f 1009/1009/1848 992/992/1847 1010/1010/1849 +f 989/989/1850 991/991/1851 1011/1011/1852 +f 1011/1011/1852 991/991/1851 1009/1009/1853 +f 992/992/1854 989/989/1855 1010/1010/1856 +f 1010/1010/1856 989/989/1855 1011/1011/1857 +f 1010/1010/71 1011/1011/71 1009/1009/71 +f 1012/1012/1858 1013/1013/1859 1014/1014/1860 +f 1015/1015/1861 1016/1016/1862 1017/1017/1863 +f 1018/1018/1864 1012/1012/1858 1014/1014/1860 +f 1019/1019/1865 1020/1020/1866 1021/1021/1867 +f 1016/1016/1862 1022/1022/1868 1017/1017/1863 +f 1013/1013/1859 1012/1012/1858 1023/1023/71 +f 1022/1022/1868 1019/1019/1865 1017/1017/1863 +f 1020/1020/1866 1019/1019/1865 1022/1022/1868 +f 1023/1023/71 1018/1018/1869 1024/1024/1870 +f 1024/1024/1870 1018/1018/1869 1025/1025/1871 +f 1015/1015/1861 1017/1017/1863 1021/1021/1867 +f 1025/1025/1871 1018/1018/1869 1014/1014/1872 +f 1023/1023/71 1024/1024/1870 1026/1026/1873 +f 1027/1027/71 1015/1015/1861 1021/1021/1867 +f 1021/1021/1867 1020/1020/1866 1028/1028/1874 +f 1029/1029/71 1023/1023/71 1026/1026/1873 +f 1029/1029/71 1026/1026/1873 1030/1030/1875 +f 1030/1030/1875 1026/1026/1873 1031/1031/1876 +f 1030/1030/1875 1031/1031/1876 1032/1032/1877 +f 1030/1030/1875 1032/1032/1877 1033/1033/1878 +f 1028/1028/1874 1027/1027/71 1021/1021/1867 +f 1033/1033/1878 1034/1034/1879 1035/1035/1880 +f 1033/1033/1878 1032/1032/1877 1034/1034/1879 +f 1035/1035/1880 1034/1034/1879 1036/1036/1881 +f 1035/1035/1880 1036/1036/1881 1037/1037/1882 +f 1027/1027/71 1028/1028/1874 1036/1036/1881 +f 1036/1036/1881 1028/1028/1874 1037/1037/1882 +f 1025/1025/1883 1014/1014/1884 1038/1038/1885 +f 1025/1025/1883 1038/1038/1885 1039/1039/1886 +f 1040/1040/1887 1041/1041/1888 1014/1014/1889 +f 1014/1014/1890 1041/1041/1890 1038/1038/1890 +f 1020/1020/1891 1042/1042/1892 1043/1043/1893 +f 1043/1043/1893 1042/1042/1892 1044/1044/210 +f 1042/1042/1894 1020/1020/1895 1045/1045/1896 +f 1016/1016/1897 1044/1044/1898 1045/1045/1899 +f 1041/1041/210 1040/1040/210 1039/1039/210 +f 1046/1046/1900 1047/1047/1901 1031/1031/1902 +f 1039/1039/210 1040/1040/210 1047/1047/1901 +f 1039/1039/210 1047/1047/1901 1046/1046/1900 +f 1031/1031/1902 1047/1047/1901 1048/1048/1903 +f 1031/1031/1902 1048/1048/1903 1049/1049/1904 +f 1049/1049/1904 1048/1048/1903 1050/1050/1905 +f 1050/1050/1905 1048/1048/1903 1035/1035/1906 +f 1050/1050/1905 1035/1035/1906 1051/1051/1907 +f 1044/1044/210 1052/1052/210 1043/1043/1893 +f 1051/1051/1907 1035/1035/1906 1053/1053/1908 +f 1051/1051/1907 1053/1053/1908 1052/1052/210 +f 1052/1052/210 1053/1053/1908 1043/1043/1893 +f 1028/1028/1909 1020/1020/1909 1043/1043/1909 +f 1028/1028/1910 1043/1043/1910 1053/1053/1910 +f 1028/1028/1911 1053/1053/1911 1037/1037/1911 +f 1037/1037/1912 1053/1053/1912 1035/1035/1912 +f 1033/1033/1913 1035/1035/1913 1048/1048/1913 +f 1033/1033/1914 1048/1048/1914 1030/1030/1914 +f 1030/1030/1915 1048/1048/1915 1047/1047/1915 +f 1030/1030/1916 1047/1047/1916 1029/1029/1916 +f 1029/1029/1917 1047/1047/1918 1023/1023/1919 +f 1023/1023/1919 1047/1047/1918 1040/1040/1920 +f 1023/1023/1921 1040/1040/1921 1013/1013/1921 +f 1014/1014/1889 1013/1013/1922 1040/1040/1887 +f 1024/1024/1923 1025/1025/1883 1039/1039/1886 +f 1024/1024/1924 1039/1039/1925 1046/1046/1926 +f 1024/1024/1924 1046/1046/1926 1026/1026/1927 +f 1026/1026/1928 1046/1046/1928 1031/1031/1928 +f 1031/1031/1929 1049/1049/1929 1032/1032/1929 +f 1032/1032/1930 1049/1049/1930 1050/1050/1930 +f 1032/1032/1931 1050/1050/1931 1034/1034/1931 +f 1034/1034/1932 1050/1050/1932 1051/1051/1932 +f 1034/1034/1933 1051/1051/1933 1036/1036/1933 +f 1036/1036/1934 1051/1051/1934 1052/1052/1934 +f 1036/1036/1935 1052/1052/1935 1027/1027/1935 +f 1027/1027/1936 1052/1052/1937 1015/1015/1938 +f 1015/1015/1938 1052/1052/1937 1044/1044/1939 +f 1016/1016/1897 1015/1015/1940 1044/1044/1898 +f 1016/1016/1941 1045/1045/1941 1022/1022/1941 +f 1020/1020/1895 1022/1022/1942 1045/1045/1896 +f 1018/1018/1943 1039/1039/1943 1038/1038/1943 +f 1018/1018/1944 1038/1038/1944 1012/1012/1944 +f 1012/1012/1945 1038/1038/1945 1041/1041/1945 +f 1012/1012/1946 1041/1041/1946 1023/1023/1946 +f 1023/1023/1947 1041/1041/1947 1039/1039/1947 +f 1023/1023/1948 1039/1039/1948 1018/1018/1948 +f 1019/1019/1949 1042/1042/1949 1045/1045/1949 +f 1019/1019/1950 1045/1045/1950 1017/1017/1950 +f 1017/1017/1951 1045/1045/1951 1044/1044/1951 +f 1017/1017/1952 1044/1044/1952 1021/1021/1952 +f 1021/1021/1953 1044/1044/1953 1042/1042/1953 +f 1021/1021/1954 1042/1042/1954 1019/1019/1954 +f 1054/1054/1955 1055/1055/1956 1056/1056/1957 +f 1057/1057/1958 1058/1058/1959 1059/1059/1960 +f 1060/1060/1961 1061/1061/1962 1062/1062/1963 +f 1063/1063/1964 1056/1056/1965 1064/1064/1966 +f 1065/1065/1967 1064/1064/1968 1066/1066/1969 +f 1067/1067/1970 1068/1068/1971 1069/1069/1972 +f 1067/1067/1970 1069/1069/1972 1070/1070/1973 +f 1071/1071/1974 1072/1072/1975 1073/1073/1976 +f 1054/1054/1955 1074/1074/1977 1055/1055/1956 +f 1069/1069/1978 1075/1075/1979 1076/1076/1980 +f 1060/1060/1981 1077/1077/1982 1078/1078/1983 +f 1074/1074/1984 1079/1079/1985 1055/1055/1986 +f 1075/1075/1979 1080/1080/1987 1076/1076/1980 +f 1081/1081/1988 1082/1082/1988 1083/1083/1988 +f 1084/1084/1989 1085/1085/1990 1063/1063/1991 +f 1064/1064/1968 1086/1086/1992 1066/1066/1969 +f 1087/1087/1993 1075/1075/1994 1068/1068/1995 +f 1070/1070/1996 1069/1069/1997 1072/1072/1975 +f 1088/1088/1998 1077/1077/1999 1060/1060/2000 +f 1088/1088/1998 1060/1060/2000 1082/1082/2001 +f 1089/1089/2002 1074/1074/2003 1090/1090/2004 +f 1066/1066/2005 1086/1086/2006 1084/1084/2007 +f 1066/1066/2005 1084/1084/2007 1075/1075/1994 +f 1091/1091/2008 1092/1092/2008 1077/1077/2008 +f 1061/1061/2009 1081/1081/2010 1083/1083/2011 +f 1093/1093/2012 1062/1062/2013 1094/1094/2014 +f 1063/1063/2015 1064/1064/2016 1080/1080/1987 +f 1073/1073/2017 1072/1072/2017 1095/1095/2017 +f 1089/1089/2018 1083/1083/2018 1074/1074/2018 +f 1096/1096/2019 1097/1097/2020 1064/1064/1968 +f 1064/1064/1968 1097/1097/2020 1086/1086/1992 +f 1068/1068/2021 1075/1075/2021 1069/1069/2021 +f 1074/1074/2022 1093/1093/2023 1094/1094/2024 +f 1074/1074/1984 1094/1094/2025 1079/1079/1985 +f 1057/1057/2026 1085/1085/2027 1097/1097/2028 +f 1098/1098/2029 1067/1067/2030 1095/1095/2031 +f 1079/1079/2032 1094/1094/2033 1058/1058/2034 +f 1076/1076/2035 1065/1065/2036 1087/1087/2037 +f 1067/1067/2038 1070/1070/2038 1099/1099/2038 +f 1085/1085/1990 1059/1059/2039 1056/1056/1957 +f 1080/1080/1987 1064/1064/2016 1065/1065/2040 +f 1065/1065/1967 1066/1066/1969 1087/1087/2041 +f 1088/1088/1998 1073/1073/2042 1077/1077/1999 +f 1090/1090/2004 1074/1074/2003 1054/1054/2043 +f 1055/1055/2044 1079/1079/2044 1056/1056/2044 +f 1077/1077/1999 1073/1073/2042 1091/1091/2045 +f 1069/1069/2046 1076/1076/2035 1087/1087/2037 +f 1069/1069/2047 1087/1087/2048 1098/1098/2049 +f 1092/1092/2050 1091/1091/2051 1100/1100/2052 +f 1092/1092/2050 1100/1100/2052 1081/1081/2053 +f 1083/1083/2054 1082/1082/2055 1101/1101/2056 +f 1091/1091/2051 1099/1099/2057 1071/1071/2058 +f 1059/1059/2039 1054/1054/1955 1056/1056/1957 +f 1069/1069/2047 1098/1098/2049 1072/1072/2059 +f 1073/1073/2042 1095/1095/2031 1091/1091/2045 +f 1077/1077/1982 1092/1092/2060 1081/1081/2061 +f 1078/1078/2062 1081/1081/2010 1061/1061/2009 +f 1083/1083/2054 1101/1101/2056 1074/1074/2063 +f 1095/1095/2031 1099/1099/2064 1091/1091/2045 +f 1101/1101/2065 1062/1062/2013 1093/1093/2012 +f 1094/1094/2066 1090/1090/2067 1058/1058/2068 +f 1056/1056/1965 1096/1096/2069 1064/1064/1966 +f 1060/1060/1981 1078/1078/1983 1061/1061/2070 +f 1056/1056/2071 1079/1079/2032 1058/1058/2034 +f 1056/1056/1965 1058/1058/2072 1096/1096/2069 +f 1097/1097/2073 1058/1058/2073 1057/1057/2073 +f 1097/1097/2028 1085/1085/2027 1084/1084/2074 +f 1095/1095/2031 1067/1067/2030 1099/1099/2064 +f 1074/1074/2022 1101/1101/2075 1093/1093/2023 +f 1057/1057/2076 1059/1059/2076 1085/1085/2076 +f 1080/1080/2077 1065/1065/2036 1076/1076/2035 +f 1100/1100/2078 1071/1071/2079 1088/1088/2080 +f 1062/1062/2081 1089/1089/2081 1090/1090/2081 +f 1058/1058/1959 1054/1054/2082 1059/1059/1960 +f 1087/1087/2083 1068/1068/2083 1067/1067/2083 +f 1099/1099/2084 1070/1070/2084 1071/1071/2084 +f 1089/1089/2085 1061/1061/2085 1083/1083/2085 +f 1096/1096/2086 1058/1058/2086 1097/1097/2086 +f 1086/1086/2087 1097/1097/2028 1084/1084/2074 +f 1075/1075/2088 1084/1084/1989 1063/1063/1991 +f 1101/1101/2089 1082/1082/2089 1062/1062/2089 +f 1094/1094/2066 1062/1062/2090 1090/1090/2067 +f 1098/1098/2029 1087/1087/2091 1067/1067/2030 +f 1082/1082/2092 1060/1060/2092 1062/1062/2092 +f 1087/1087/1993 1066/1066/2005 1075/1075/1994 +f 1070/1070/1996 1072/1072/1975 1071/1071/1974 +f 1071/1071/2093 1073/1073/2093 1088/1088/2093 +f 1062/1062/1963 1061/1061/1962 1089/1089/2094 +f 1077/1077/1982 1081/1081/2061 1078/1078/1983 +f 1072/1072/2059 1098/1098/2049 1095/1095/2095 +f 1085/1085/1990 1056/1056/1957 1063/1063/1991 +f 1081/1081/2096 1100/1100/2078 1088/1088/2080 +f 1081/1081/2096 1088/1088/2080 1082/1082/2097 +f 1058/1058/1959 1090/1090/2098 1054/1054/2082 +f 1075/1075/1979 1063/1063/2015 1080/1080/1987 +f 1091/1091/2051 1071/1071/2058 1100/1100/2052 +f 1102/1102/2099 1103/1103/2100 1104/1104/2101 +f 1102/1102/2102 1104/1104/2103 1105/1105/2104 +f 1105/1105/2104 1104/1104/2103 1106/1106/2105 +f 1105/1105/2106 1106/1106/2107 1107/1107/2108 +f 1105/1105/2106 1107/1107/2108 1108/1108/2109 +f 1108/1108/2110 1107/1107/2110 1109/1109/2110 +f 1109/1109/2111 1107/1107/2111 1110/1110/2111 +f 1109/1109/2112 1110/1110/2113 1111/1111/2114 +f 1111/1111/2114 1110/1110/2113 1112/1112/2115 +f 1113/1113/2116 1111/1111/2116 1114/1114/2116 +f 1114/1114/2117 1111/1111/2114 1112/1112/2115 +f 1113/1113/2118 1114/1114/2118 1115/1115/2118 +f 1113/1113/2119 1115/1115/2119 1116/1116/2119 +f 1116/1116/2120 1115/1115/2121 1117/1117/2122 +f 1117/1117/2122 1115/1115/2121 1118/1118/2123 +f 1117/1117/2124 1118/1118/2125 1119/1119/2124 +f 1119/1119/2126 1118/1118/2126 1120/1120/2126 +f 1119/1119/2127 1120/1120/2127 1121/1121/2127 +f 1121/1121/2128 1120/1120/2128 1122/1122/2128 +f 1121/1121/2129 1122/1122/2129 1123/1123/2129 +f 1123/1123/2130 1122/1122/2130 1124/1124/2130 +f 1123/1123/2131 1124/1124/2131 1125/1125/2131 +f 1102/1102/2099 1125/1125/2132 1103/1103/2100 +f 1103/1103/2133 1125/1125/2133 1124/1124/2133 +f 1125/1125/2134 1102/1102/2134 1123/1123/2134 +f 1111/1111/2134 1116/1116/2134 1109/1109/2134 +f 1109/1109/2134 1116/1116/2134 1117/1117/2134 +f 1111/1111/2134 1113/1113/2134 1116/1116/2134 +f 1105/1105/2134 1119/1119/2134 1121/1121/2134 +f 1109/1109/2134 1117/1117/2134 1108/1108/2134 +f 1108/1108/2134 1117/1117/2134 1119/1119/2134 +f 1102/1102/2134 1121/1121/2134 1123/1123/2134 +f 1105/1105/2134 1121/1121/2134 1102/1102/2134 +f 1108/1108/2134 1119/1119/2134 1105/1105/2134 +f 1114/1114/2135 1112/1112/2135 1115/1115/2135 +f 1110/1110/2135 1115/1115/2135 1112/1112/2135 +f 1110/1110/2135 1118/1118/2135 1115/1115/2135 +f 1107/1107/2135 1118/1118/2135 1110/1110/2135 +f 1107/1107/2135 1120/1120/2136 1118/1118/2135 +f 1106/1106/2135 1120/1120/2136 1107/1107/2135 +f 1106/1106/2135 1122/1122/2137 1120/1120/2136 +f 1103/1103/2135 1124/1124/2136 1104/1104/2135 +f 1104/1104/2135 1122/1122/2137 1106/1106/2135 +f 1104/1104/2135 1124/1124/2136 1122/1122/2137 +f 1126/1126/2138 1127/1127/2139 1128/1128/2140 +f 1128/1128/2140 1129/1129/2141 1126/1126/2138 +f 1128/1128/2140 1127/1127/2139 1130/1130/2142 +f 1127/1127/2139 1131/1131/2143 1130/1130/2142 +f 1130/1130/2142 1132/1132/2144 1133/1133/2145 +f 1133/1133/2145 1132/1132/2144 1134/1134/2146 +f 1130/1130/2142 1131/1131/2143 1132/1132/2144 +f 1133/1133/2145 1135/1135/2147 1129/1129/2141 +f 1133/1133/2145 1129/1129/2141 1128/1128/2140 +f 1133/1133/2145 1134/1134/2146 1135/1135/2147 +f 1136/1136/2148 1137/1137/2149 1138/1138/2150 +f 1138/1138/2150 1139/1139/2151 1136/1136/2148 +f 1138/1138/2150 1140/1140/2152 1139/1139/2151 +f 1141/1141/2153 1138/1138/2154 1137/1137/2155 +f 1141/1141/2153 1137/1137/2155 1142/1142/2156 +f 1142/1142/2157 1137/1137/2157 1136/1136/2157 +f 1142/1142/2158 1136/1136/2158 1143/1143/2158 +f 1143/1143/2159 1136/1136/2160 1139/1139/2161 +f 1143/1143/2159 1139/1139/2161 1144/1144/2162 +f 1144/1144/2163 1139/1139/2164 1140/1140/2165 +f 1144/1144/2163 1140/1140/2165 1145/1145/2166 +f 1145/1145/2167 1140/1140/2168 1138/1138/2169 +f 1145/1145/2167 1138/1138/2169 1141/1141/2170 +f 1141/1141/2171 1146/1146/2172 1147/1147/2173 +f 1142/1142/2174 1148/1148/2175 1141/1141/2171 +f 1141/1141/2171 1148/1148/2175 1146/1146/2172 +f 1144/1144/2176 1149/1149/2177 1143/1143/2178 +f 1145/1145/2179 1150/1150/2180 1144/1144/2176 +f 1144/1144/2176 1150/1150/2180 1149/1149/2177 +f 1141/1141/2171 1147/1147/2173 1145/1145/2179 +f 1145/1145/2179 1147/1147/2173 1150/1150/2180 +f 1142/1142/2174 1151/1151/2181 1148/1148/2175 +f 1143/1143/2178 1149/1149/2177 1152/1152/2182 +f 1143/1143/2178 1152/1152/2182 1142/1142/2174 +f 1142/1142/2174 1152/1152/2182 1151/1151/2181 +f 1147/1147/2183 1146/1146/2184 1127/1127/2185 +f 1127/1127/2186 1126/1126/2187 1147/1147/2188 +f 1147/1147/2188 1126/1126/2187 1150/1150/2189 +f 1150/1150/2189 1126/1126/2187 1129/1129/2190 +f 1150/1150/2191 1129/1129/2192 1149/1149/2193 +f 1149/1149/2193 1129/1129/2192 1135/1135/2194 +f 1149/1149/2195 1135/1135/2196 1134/1134/2197 +f 1149/1149/2195 1134/1134/2197 1152/1152/2198 +f 1152/1152/2199 1134/1134/2200 1151/1151/2201 +f 1151/1151/2201 1134/1134/2200 1132/1132/2202 +f 1151/1151/2201 1132/1132/2202 1148/1148/2203 +f 1132/1132/2202 1131/1131/2204 1148/1148/2203 +f 1148/1148/2203 1131/1131/2204 1146/1146/2205 +f 1146/1146/2184 1131/1131/2206 1127/1127/2185 +f 1130/1130/2207 1133/1133/2208 1153/1153/2209 +f 1153/1153/2209 1133/1133/2208 1154/1154/2210 +f 1128/1128/2211 1130/1130/2212 1155/1155/2213 +f 1155/1155/2213 1130/1130/2212 1153/1153/2214 +f 1133/1133/2215 1128/1128/2216 1154/1154/2217 +f 1154/1154/2217 1128/1128/2216 1155/1155/2218 +f 1155/1155/2134 1153/1153/2134 1154/1154/2134 +f 1156/1156/2219 1157/1157/2220 1158/1158/2221 +f 1158/1158/2221 1159/1159/2222 1160/1160/2223 +f 1160/1160/2223 1159/1159/2222 1161/1161/2224 +f 1162/1162/2225 1163/1163/2226 1164/1164/2227 +f 1160/1160/2223 1161/1161/2224 1162/1162/2225 +f 1160/1160/2223 1162/1162/2225 1164/1164/2227 +f 1156/1156/2219 1165/1165/2228 1157/1157/2220 +f 1164/1164/2227 1163/1163/2226 1165/1165/2228 +f 1164/1164/2227 1165/1165/2228 1156/1156/2219 +f 1156/1156/2219 1158/1158/2221 1160/1160/2223 +f 1166/1166/2229 1167/1167/2230 1168/1168/2231 +f 1166/1166/2229 1169/1169/2232 1167/1167/2230 +f 1166/1166/2229 1170/1170/2233 1169/1169/2232 +f 1171/1171/2234 1170/1170/2234 1172/1172/2234 +f 1172/1172/2235 1170/1170/2235 1166/1166/2235 +f 1172/1172/2236 1166/1166/2236 1173/1173/2236 +f 1173/1173/2237 1166/1166/2238 1168/1168/2239 +f 1173/1173/2237 1168/1168/2239 1174/1174/2240 +f 1174/1174/2241 1168/1168/2242 1175/1175/2243 +f 1175/1175/2243 1168/1168/2242 1167/1167/2244 +f 1175/1175/2245 1167/1167/2245 1169/1169/2245 +f 1175/1175/2246 1169/1169/2246 1171/1171/2246 +f 1171/1171/2247 1169/1169/2247 1170/1170/2247 +f 1172/1172/2248 1176/1176/2249 1177/1177/2250 +f 1172/1172/2248 1177/1177/2250 1171/1171/2251 +f 1175/1175/2252 1178/1178/2253 1174/1174/2254 +f 1174/1174/2254 1178/1178/2253 1179/1179/2255 +f 1175/1175/2252 1180/1180/2256 1178/1178/2253 +f 1171/1171/2251 1177/1177/2250 1180/1180/2256 +f 1171/1171/2251 1180/1180/2256 1175/1175/2252 +f 1173/1173/2257 1181/1181/2258 1172/1172/2248 +f 1172/1172/2248 1181/1181/2258 1176/1176/2249 +f 1174/1174/2254 1179/1179/2255 1173/1173/2257 +f 1173/1173/2257 1179/1179/2255 1181/1181/2258 +f 1177/1177/2259 1159/1159/2260 1158/1158/2261 +f 1177/1177/2259 1158/1158/2261 1180/1180/2262 +f 1180/1180/2263 1158/1158/2264 1157/1157/2265 +f 1180/1180/2263 1157/1157/2265 1178/1178/2266 +f 1157/1157/2267 1165/1165/2268 1178/1178/2269 +f 1178/1178/2269 1165/1165/2268 1179/1179/2270 +f 1165/1165/2271 1163/1163/2272 1179/1179/2273 +f 1179/1179/2273 1163/1163/2272 1181/1181/2274 +f 1163/1163/2275 1162/1162/2276 1181/1181/2277 +f 1181/1181/2277 1162/1162/2276 1176/1176/2278 +f 1162/1162/2276 1161/1161/2279 1176/1176/2278 +f 1176/1176/2280 1161/1161/2281 1177/1177/2282 +f 1161/1161/2281 1159/1159/2283 1177/1177/2282 +f 1164/1164/2284 1156/1156/2284 1182/1182/2284 +f 1183/1183/2285 1164/1164/2285 1182/1182/2285 +f 1160/1160/2286 1164/1164/2286 1183/1183/2286 +f 1184/1184/2287 1160/1160/2287 1183/1183/2287 +f 1156/1156/2288 1160/1160/2288 1184/1184/2288 +f 1182/1182/2289 1156/1156/2289 1184/1184/2289 +f 1184/1184/2134 1183/1183/2134 1182/1182/2134 +f 1185/1185/2290 1186/1186/2291 1187/1187/2292 +f 1188/1188/2293 1189/1189/2294 1186/1186/2291 +f 1190/1190/2295 1191/1191/2296 1192/1192/2297 +f 1185/1185/2290 1187/1187/2292 1191/1191/2296 +f 1190/1190/2295 1192/1192/2297 1193/1193/2298 +f 1185/1185/2290 1191/1191/2296 1190/1190/2295 +f 1188/1188/2293 1194/1194/2299 1189/1189/2294 +f 1190/1190/2295 1193/1193/2298 1194/1194/2299 +f 1190/1190/2295 1194/1194/2299 1188/1188/2293 +f 1188/1188/2293 1186/1186/2291 1185/1185/2290 +f 1195/1195/2300 1196/1196/2301 1197/1197/2302 +f 1197/1197/2302 1196/1196/2301 1198/1198/2303 +f 1199/1199/2304 1196/1196/2305 1200/1200/2306 +f 1199/1199/2307 1200/1200/2308 1195/1195/2309 +f 1199/1199/2307 1195/1195/2309 1201/1201/2310 +f 1201/1201/2311 1195/1195/2312 1202/1202/2313 +f 1202/1202/2313 1195/1195/2312 1197/1197/2314 +f 1202/1202/2315 1197/1197/2316 1203/1203/2317 +f 1203/1203/2317 1197/1197/2316 1198/1198/2318 +f 1203/1203/2319 1198/1198/2319 1204/1204/2319 +f 1204/1204/2320 1198/1198/2320 1196/1196/2320 +f 1204/1204/2321 1196/1196/2305 1199/1199/2304 +f 1199/1199/2322 1205/1205/2323 1206/1206/2324 +f 1199/1199/2322 1206/1206/2324 1204/1204/2325 +f 1203/1203/2326 1207/1207/2327 1208/1208/2328 +f 1203/1203/2326 1208/1208/2328 1202/1202/2329 +f 1204/1204/2325 1209/1209/2330 1207/1207/2327 +f 1204/1204/2325 1207/1207/2327 1203/1203/2326 +f 1204/1204/2325 1206/1206/2324 1209/1209/2330 +f 1201/1201/2331 1210/1210/2332 1205/1205/2323 +f 1201/1201/2331 1205/1205/2323 1199/1199/2322 +f 1202/1202/2329 1208/1208/2328 1210/1210/2332 +f 1202/1202/2329 1210/1210/2332 1201/1201/2331 +f 1206/1206/2333 1187/1187/2334 1186/1186/2335 +f 1206/1206/2333 1186/1186/2335 1209/1209/2336 +f 1186/1186/2337 1189/1189/2338 1209/1209/2339 +f 1209/1209/2339 1189/1189/2338 1207/1207/2340 +f 1207/1207/2341 1189/1189/2342 1194/1194/2343 +f 1207/1207/2341 1194/1194/2343 1208/1208/2344 +f 1208/1208/2345 1194/1194/2346 1193/1193/2347 +f 1208/1208/2345 1193/1193/2347 1210/1210/2348 +f 1193/1193/2347 1192/1192/2349 1210/1210/2348 +f 1210/1210/2350 1192/1192/2351 1205/1205/2352 +f 1205/1205/2352 1192/1192/2351 1191/1191/2353 +f 1205/1205/2354 1191/1191/2355 1187/1187/2356 +f 1205/1205/2354 1187/1187/2356 1206/1206/2357 +f 1190/1190/2358 1188/1188/2359 1211/1211/2360 +f 1211/1211/2360 1188/1188/2359 1212/1212/2361 +f 1185/1185/2362 1190/1190/2363 1213/1213/2364 +f 1213/1213/2364 1190/1190/2363 1211/1211/2365 +f 1188/1188/2366 1185/1185/2367 1212/1212/2368 +f 1212/1212/2368 1185/1185/2367 1213/1213/2369 +f 1212/1212/2370 1213/1213/2370 1211/1211/2370 +f 1200/1200/2371 1196/1196/2301 1195/1195/2300 +f 1214/1214/2372 1215/1215/2373 1216/1216/2374 +f 1217/1217/2375 1218/1218/2376 1215/1215/2373 +f 1219/1219/2377 1220/1220/2378 1217/1217/2375 +f 1214/1214/2372 1221/1221/2379 1222/1222/2380 +f 1214/1214/2372 1222/1222/2380 1223/1223/2381 +f 1223/1223/2381 1222/1222/2380 1224/1224/2382 +f 1223/1223/2381 1219/1219/2377 1217/1217/2375 +f 1223/1223/2381 1224/1224/2382 1219/1219/2377 +f 1217/1217/2375 1215/1215/2373 1214/1214/2372 +f 1220/1220/2378 1218/1218/2376 1217/1217/2375 +f 1214/1214/2372 1216/1216/2374 1221/1221/2379 +f 1225/1225/2383 1226/1226/2384 1227/1227/2385 +f 1228/1228/2386 1229/1229/2387 1225/1225/2383 +f 1225/1225/2383 1230/1230/2388 1228/1228/2386 +f 1227/1227/2385 1230/1230/2388 1225/1225/2383 +f 1231/1231/2389 1226/1226/2390 1232/1232/2391 +f 1232/1232/2391 1226/1226/2390 1225/1225/2392 +f 1232/1232/2393 1225/1225/2394 1233/1233/2395 +f 1233/1233/2395 1225/1225/2394 1229/1229/2396 +f 1233/1233/2397 1229/1229/2398 1228/1228/2399 +f 1233/1233/2397 1228/1228/2399 1234/1234/2400 +f 1234/1234/2401 1228/1228/2401 1230/1230/2401 +f 1234/1234/2402 1230/1230/2403 1227/1227/2404 +f 1234/1234/2402 1227/1227/2404 1231/1231/2405 +f 1231/1231/2406 1227/1227/2406 1226/1226/2406 +f 1231/1231/2407 1235/1235/2408 1236/1236/2409 +f 1232/1232/2410 1237/1237/2411 1235/1235/2408 +f 1232/1232/2410 1235/1235/2408 1231/1231/2407 +f 1234/1234/2412 1238/1238/2413 1233/1233/2414 +f 1234/1234/2412 1239/1239/2415 1238/1238/2413 +f 1231/1231/2407 1236/1236/2409 1234/1234/2412 +f 1234/1234/2412 1236/1236/2409 1239/1239/2415 +f 1233/1233/2414 1240/1240/2416 1232/1232/2410 +f 1232/1232/2410 1240/1240/2416 1237/1237/2411 +f 1233/1233/2414 1238/1238/2413 1240/1240/2416 +f 1222/1222/2417 1221/1221/2418 1236/1236/2419 +f 1236/1236/2420 1221/1221/2421 1216/1216/2422 +f 1236/1236/2420 1216/1216/2422 1239/1239/2423 +f 1216/1216/2424 1215/1215/2425 1239/1239/2426 +f 1239/1239/2426 1215/1215/2425 1238/1238/2427 +f 1215/1215/2425 1218/1218/2428 1238/1238/2427 +f 1238/1238/2429 1218/1218/2430 1240/1240/2431 +f 1218/1218/2430 1220/1220/2432 1240/1240/2431 +f 1240/1240/2433 1220/1220/2434 1219/1219/2435 +f 1240/1240/2433 1219/1219/2435 1237/1237/2436 +f 1219/1219/2437 1224/1224/2438 1237/1237/2439 +f 1237/1237/2439 1224/1224/2438 1235/1235/2440 +f 1235/1235/2440 1224/1224/2438 1222/1222/2417 +f 1235/1235/2440 1222/1222/2417 1236/1236/2419 +f 1223/1223/2441 1217/1217/2441 1241/1241/2441 +f 1241/1241/2442 1217/1217/2442 1242/1242/2442 +f 1243/1243/2443 1223/1223/2443 1241/1241/2443 +f 1214/1214/2444 1223/1223/2444 1243/1243/2444 +f 1244/1244/2445 1214/1214/2445 1243/1243/2445 +f 1217/1217/2446 1214/1214/2447 1242/1242/2448 +f 1242/1242/2448 1214/1214/2447 1244/1244/2449 +f 1244/1244/2370 1243/1243/2370 1241/1241/2370 +f 1244/1244/2370 1241/1241/2370 1242/1242/2370 +f 1245/1245/2450 1246/1246/2451 1247/1247/2452 +f 1245/1245/2453 1247/1247/2453 1248/1248/2453 +f 1248/1248/2454 1247/1247/2454 1249/1249/2454 +f 1248/1248/2455 1249/1249/2455 1250/1250/2455 +f 1250/1250/2456 1249/1249/2456 1251/1251/2456 +f 1250/1250/2457 1251/1251/2457 1252/1252/2457 +f 1252/1252/2458 1251/1251/2458 1253/1253/2458 +f 1252/1252/2459 1253/1253/2460 1254/1254/2461 +f 1255/1255/2462 1254/1254/2462 1256/1256/2462 +f 1256/1256/2463 1254/1254/2461 1253/1253/2460 +f 1255/1255/2464 1256/1256/2465 1257/1257/2466 +f 1255/1255/2464 1257/1257/2466 1258/1258/2467 +f 1258/1258/2468 1257/1257/2468 1259/1259/2468 +f 1259/1259/2469 1257/1257/2469 1260/1260/2469 +f 1259/1259/2470 1260/1260/2470 1261/1261/2470 +f 1261/1261/2471 1260/1260/2471 1262/1262/2471 +f 1261/1261/2472 1262/1262/2472 1263/1263/2472 +f 1263/1263/2473 1262/1262/2473 1264/1264/2473 +f 1263/1263/2474 1264/1264/2474 1265/1265/2474 +f 1265/1265/2475 1264/1264/2475 1266/1266/2475 +f 1265/1265/2476 1266/1266/2477 1267/1267/2478 +f 1265/1265/2476 1267/1267/2478 1268/1268/2479 +f 1245/1245/2450 1268/1268/2480 1246/1246/2451 +f 1246/1246/2481 1268/1268/2481 1267/1267/2481 +f 1252/1252/2482 1258/1258/2483 1259/1259/2484 +f 1254/1254/2485 1255/1255/2486 1252/1252/2482 +f 1252/1252/2482 1255/1255/2486 1258/1258/2483 +f 1250/1250/2487 1259/1259/2484 1261/1261/2487 +f 1252/1252/2482 1259/1259/2484 1250/1250/2487 +f 1245/1245/2488 1265/1265/2482 1268/1268/2488 +f 1248/1248/2489 1265/1265/2482 1245/1245/2488 +f 1263/1263/2486 1265/1265/2482 1248/1248/2489 +f 1250/1250/2487 1263/1263/2486 1248/1248/2489 +f 1250/1250/2487 1261/1261/2487 1263/1263/2486 +f 1256/1256/2370 1253/1253/2370 1257/1257/2370 +f 1251/1251/2370 1257/1257/2370 1253/1253/2370 +f 1251/1251/2370 1260/1260/2490 1257/1257/2370 +f 1249/1249/2370 1260/1260/2490 1251/1251/2370 +f 1249/1249/2370 1262/1262/2491 1260/1260/2490 +f 1249/1249/2370 1264/1264/2492 1262/1262/2491 +f 1247/1247/2490 1264/1264/2492 1249/1249/2370 +f 1246/1246/2493 1267/1267/2494 1247/1247/2490 +f 1247/1247/2490 1266/1266/2490 1264/1264/2492 +f 1267/1267/2494 1266/1266/2490 1247/1247/2490 +f 1269/1269/2495 1270/1270/2496 1271/1271/2497 +f 1269/1269/2498 1271/1271/2498 1272/1272/2498 +f 1272/1272/2499 1271/1271/2499 1273/1273/2499 +f 1272/1272/2500 1273/1273/2500 1274/1274/2500 +f 1274/1274/2501 1273/1273/2501 1275/1275/2501 +f 1274/1274/2502 1275/1275/2503 1276/1276/2504 +f 1274/1274/2502 1276/1276/2504 1277/1277/2505 +f 1278/1278/2506 1277/1277/2506 1276/1276/2506 +f 1279/1279/2507 1278/1278/2507 1280/1280/2507 +f 1279/1279/2508 1280/1280/2508 1281/1281/2508 +f 1281/1281/2509 1280/1280/2509 1282/1282/2509 +f 1281/1281/2510 1282/1282/2510 1283/1283/2510 +f 1283/1283/2511 1282/1282/2511 1284/1284/2511 +f 1283/1283/2512 1284/1284/2512 1285/1285/2512 +f 1285/1285/2513 1284/1284/2513 1286/1286/2513 +f 1285/1285/2514 1286/1286/2515 1287/1287/2516 +f 1287/1287/2516 1286/1286/2515 1288/1288/2517 +f 1287/1287/2518 1288/1288/2518 1289/1289/2518 +f 1269/1269/2495 1289/1289/2519 1270/1270/2496 +f 1289/1289/2520 1269/1269/2521 1287/1287/2522 +f 1277/1277/2523 1281/1281/2488 1274/1274/2488 +f 1277/1277/2523 1279/1279/2524 1281/1281/2488 +f 1278/1278/2525 1279/1279/2524 1277/1277/2523 +f 1274/1274/2488 1281/1281/2488 1283/1283/2488 +f 1272/1272/2488 1287/1287/2522 1269/1269/2521 +f 1272/1272/2488 1285/1285/2488 1287/1287/2522 +f 1272/1272/2488 1283/1283/2488 1285/1285/2488 +f 1274/1274/2488 1283/1283/2488 1272/1272/2488 +f 1278/1278/2526 1276/1276/2527 1280/1280/2528 +f 1275/1275/2370 1282/1282/2370 1276/1276/2527 +f 1276/1276/2527 1282/1282/2370 1280/1280/2528 +f 1273/1273/2370 1284/1284/2370 1275/1275/2370 +f 1275/1275/2370 1284/1284/2370 1282/1282/2370 +f 1271/1271/2370 1284/1284/2370 1273/1273/2370 +f 1271/1271/2370 1286/1286/2370 1284/1284/2370 +f 1270/1270/2529 1289/1289/2530 1288/1288/2531 +f 1270/1270/2529 1288/1288/2531 1271/1271/2370 +f 1271/1271/2370 1288/1288/2531 1286/1286/2370 +f 1290/1290/2532 1291/1291/2533 1292/1292/2534 +f 1290/1290/2535 1292/1292/2535 1293/1293/2535 +f 1293/1293/2536 1292/1292/2536 1294/1294/2536 +f 1293/1293/2537 1294/1294/2537 1295/1295/2537 +f 1295/1295/2538 1294/1294/2538 1296/1296/2538 +f 1295/1295/2539 1296/1296/2539 1297/1297/2539 +f 1297/1297/2540 1296/1296/2540 1298/1298/2540 +f 1297/1297/2541 1298/1298/2542 1299/1299/2543 +f 1300/1300/2544 1299/1299/2544 1301/1301/2544 +f 1301/1301/2545 1299/1299/2543 1298/1298/2542 +f 1300/1300/2546 1301/1301/2547 1302/1302/2548 +f 1300/1300/2546 1302/1302/2548 1303/1303/2549 +f 1303/1303/2550 1302/1302/2551 1304/1304/2552 +f 1303/1303/2550 1304/1304/2552 1305/1305/2553 +f 1305/1305/2554 1304/1304/2554 1306/1306/2554 +f 1306/1306/2555 1304/1304/2555 1307/1307/2555 +f 1306/1306/2556 1307/1307/2556 1308/1308/2556 +f 1308/1308/2557 1307/1307/2557 1309/1309/2557 +f 1308/1308/2558 1309/1309/2558 1310/1310/2558 +f 1310/1310/2559 1309/1309/2560 1311/1311/2561 +f 1310/1310/2559 1311/1311/2561 1312/1312/2562 +f 1290/1290/2532 1312/1312/2563 1291/1291/2533 +f 1291/1291/2564 1312/1312/2564 1311/1311/2564 +f 1297/1297/2565 1303/1303/2566 1295/1295/2567 +f 1297/1297/2565 1300/1300/2568 1303/1303/2566 +f 1299/1299/2569 1300/1300/2568 1297/1297/2565 +f 1293/1293/2134 1306/1306/2570 1308/1308/2134 +f 1295/1295/2567 1303/1303/2566 1305/1305/2571 +f 1290/1290/2572 1310/1310/2566 1312/1312/2573 +f 1290/1290/2572 1308/1308/2134 1310/1310/2566 +f 1293/1293/2134 1308/1308/2134 1290/1290/2572 +f 1295/1295/2567 1305/1305/2571 1293/1293/2134 +f 1293/1293/2134 1305/1305/2571 1306/1306/2570 +f 1296/1296/2135 1302/1302/2135 1298/1298/2135 +f 1298/1298/2135 1302/1302/2135 1301/1301/2135 +f 1296/1296/2135 1304/1304/2135 1302/1302/2135 +f 1294/1294/2135 1304/1304/2135 1296/1296/2135 +f 1292/1292/2574 1307/1307/2575 1294/1294/2135 +f 1294/1294/2135 1307/1307/2575 1304/1304/2135 +f 1292/1292/2574 1309/1309/2576 1307/1307/2575 +f 1311/1311/2577 1309/1309/2576 1291/1291/2576 +f 1291/1291/2576 1309/1309/2576 1292/1292/2574 +f 1313/1313/2578 1314/1314/2579 1315/1315/2580 +f 1315/1315/2580 1314/1314/2579 1316/1316/2581 +f 1315/1315/2580 1316/1316/2581 1317/1317/2582 +f 1317/1317/2582 1316/1316/2581 1318/1318/2583 +f 1317/1317/2582 1318/1318/2583 1319/1319/2584 +f 1319/1319/2584 1318/1318/2583 1320/1320/2585 +f 1319/1319/2584 1320/1320/2585 1321/1321/2586 +f 1322/1322/2587 1323/1323/2588 1324/1324/2589 +f 1324/1324/2589 1323/1323/2588 1325/1325/2590 +f 1324/1324/2589 1325/1325/2590 1326/1326/2591 +f 1326/1326/2591 1325/1325/2590 1327/1327/2592 +f 1326/1326/2591 1327/1327/2592 1328/1328/2593 +f 1328/1328/2593 1327/1327/2592 1329/1329/2594 +f 1323/1323/2588 1322/1322/2587 1330/1330/2595 +f 1331/1331/2596 1332/1332/2597 1333/1333/2598 +f 1333/1333/2598 1332/1332/2597 1334/1334/2599 +f 1333/1333/2598 1334/1334/2599 1335/1335/2600 +f 1335/1335/2600 1334/1334/2599 1336/1336/2601 +f 1335/1335/2600 1336/1336/2601 1337/1337/2602 +f 1337/1337/2602 1336/1336/2601 1338/1338/2603 +f 1337/1337/2602 1338/1338/2603 1339/1339/2604 +f 1339/1339/2604 1338/1338/2603 1340/1340/2605 +f 1339/1339/2604 1340/1340/2605 1341/1341/2606 +f 1342/1342/2607 1343/1343/2608 1344/1344/2609 +f 1344/1344/2609 1345/1345/2610 1342/1342/2607 +f 1346/1346/2611 1345/1345/2610 1344/1344/2609 +f 1345/1345/2610 1346/1346/2611 1347/1347/2612 +f 1345/1345/2610 1347/1347/2612 1348/1348/2613 +f 1348/1348/2613 1347/1347/2612 1349/1349/2614 +f 1350/1350/2615 1348/1348/2613 1349/1349/2614 +f 1350/1350/2615 1351/1351/2616 1348/1348/2613 +f 1351/1351/2616 1350/1350/2615 1352/1352/2617 +f 1351/1351/2616 1352/1352/2617 1353/1353/2618 +f 1351/1351/2616 1353/1353/2618 1354/1354/2619 +f 1353/1353/2618 1355/1355/2620 1354/1354/2619 +f 1355/1355/2620 1356/1356/2621 1354/1354/2619 +f 1356/1356/2621 1355/1355/2620 1357/1357/2622 +f 1358/1358/2623 1356/1356/2621 1357/1357/2622 +f 1359/1359/2624 1360/1360/2625 1358/1358/2623 +f 1358/1358/2623 1360/1360/2625 1356/1356/2621 +f 1361/1361/2626 1362/1362/2627 1363/1363/2628 +f 1361/1361/2626 1363/1363/2628 1364/1364/2629 +f 1364/1364/2629 1363/1363/2628 1365/1365/2630 +f 1365/1365/2630 1363/1363/2628 1366/1366/2631 +f 1365/1365/2630 1366/1366/2631 1367/1367/2632 +f 1367/1367/2632 1366/1366/2631 1368/1368/2633 +f 1369/1369/2634 1370/1370/2635 1371/1371/2636 +f 1371/1371/2636 1370/1370/2635 1372/1372/2637 +f 1371/1371/2636 1372/1372/2637 1373/1373/2638 +f 1371/1371/2636 1373/1373/2638 1374/1374/2639 +f 1375/1375/2640 1374/1374/2639 1373/1373/2638 +f 1375/1375/2640 1376/1376/2641 1374/1374/2639 +f 1377/1377/2642 1376/1376/2641 1375/1375/2640 +f 1367/1367/2643 1378/1378/2644 1379/1379/2645 +f 1367/1367/2643 1379/1379/2645 1365/1365/2646 +f 1365/1365/2646 1379/1379/2645 1380/1380/2647 +f 1365/1365/2646 1380/1380/2647 1364/1364/2648 +f 1364/1364/2648 1380/1380/2647 1381/1381/2649 +f 1382/1382/2650 1361/1361/2651 1364/1364/2648 +f 1382/1382/2650 1364/1364/2648 1381/1381/2649 +f 1383/1383/2652 1377/1377/2642 1384/1384/2653 +f 1385/1385/2654 1386/1386/2655 1359/1359/2624 +f 1359/1359/2624 1386/1386/2655 1360/1360/2625 +f 1387/1387/2656 1388/1388/2657 1389/1389/2658 +f 1387/1387/2659 1389/1389/2660 1390/1390/2661 +f 1390/1390/2661 1384/1384/2653 1387/1387/2659 +f 1360/1360/2625 1391/1391/2662 1392/1392/2663 +f 1393/1393/2664 1384/1384/2653 1390/1390/2661 +f 1394/1394/2665 1395/1395/2666 1393/1393/2664 +f 1392/1392/2663 1388/1388/2657 1360/1360/2625 +f 1360/1360/2625 1388/1388/2657 1387/1387/2656 +f 1384/1384/2653 1393/1393/2664 1383/1383/2652 +f 1393/1393/2664 1390/1390/2661 1394/1394/2665 +f 1391/1391/2662 1386/1386/2655 1395/1395/2666 +f 1386/1386/2655 1391/1391/2662 1360/1360/2625 +f 1395/1395/2666 1394/1394/2665 1391/1391/2662 +f 1342/1342/2667 1396/1396/2668 1397/1397/2669 +f 1387/1387/2670 1384/1384/2671 1398/1398/2672 +f 1398/1398/2672 1384/1384/2671 1399/1399/2673 +f 1400/1400/2674 1401/1401/2675 1332/1332/2676 +f 1402/1402/2677 1341/1341/2678 1340/1340/2679 +f 1401/1401/2675 1334/1334/2680 1332/1332/2676 +f 1403/1403/2681 1336/1336/2682 1334/1334/2680 +f 1403/1403/2681 1334/1334/2680 1401/1401/2675 +f 1404/1404/2683 1338/1338/2684 1403/1403/2681 +f 1403/1403/2681 1338/1338/2684 1336/1336/2682 +f 1402/1402/2677 1340/1340/2679 1404/1404/2683 +f 1404/1404/2683 1340/1340/2679 1338/1338/2684 +f 1339/1339/2685 1382/1382/2686 1337/1337/2687 +f 1380/1380/2688 1335/1335/2689 1337/1337/2687 +f 1380/1380/2688 1337/1337/2687 1381/1381/2690 +f 1381/1381/2690 1337/1337/2687 1382/1382/2686 +f 1335/1335/2689 1380/1380/2688 1333/1333/2691 +f 1333/1333/2691 1380/1380/2688 1379/1379/2692 +f 1333/1333/2691 1379/1379/2692 1378/1378/2693 +f 1333/1333/2691 1378/1378/2693 1331/1331/2694 +f 1392/1392/2695 1405/1405/2696 1388/1388/2697 +f 1388/1388/2697 1405/1405/2696 1406/1406/2698 +f 1388/1388/2699 1406/1406/2699 1389/1389/2699 +f 1407/1407/2700 1391/1391/2701 1408/1408/2702 +f 1408/1408/2702 1391/1391/2701 1394/1394/2703 +f 1408/1408/2704 1394/1394/2704 1390/1390/2704 +f 1405/1405/2705 1392/1392/2706 1407/1407/2707 +f 1407/1407/2707 1392/1392/2706 1391/1391/2708 +f 1348/1348/2709 1351/1351/2710 1345/1345/2711 +f 1345/1345/2711 1351/1351/2710 1342/1342/2667 +f 1409/1409/2712 1383/1383/2713 1410/1410/2714 +f 1383/1383/2713 1409/1409/2712 1385/1385/2715 +f 1385/1385/2716 1409/1409/2716 1411/1411/2716 +f 1385/1385/2717 1411/1411/2718 1412/1412/2719 +f 1385/1385/2717 1412/1412/2719 1386/1386/2720 +f 1386/1386/2721 1412/1412/2722 1395/1395/2723 +f 1395/1395/2723 1412/1412/2722 1413/1413/2724 +f 1413/1413/2725 1393/1393/2725 1395/1395/2725 +f 1410/1410/2726 1383/1383/2726 1393/1393/2726 +f 1341/1341/2727 1402/1402/2728 1398/1398/2729 +f 1414/1414/2730 1398/1398/2729 1399/1399/2731 +f 1362/1362/2732 1414/1414/2730 1399/1399/2731 +f 1362/1362/2732 1361/1361/2733 1414/1414/2730 +f 1361/1361/2734 1382/1382/2686 1414/1414/2735 +f 1382/1382/2686 1415/1415/2736 1414/1414/2735 +f 1416/1416/2737 1415/1415/2736 1382/1382/2686 +f 1416/1416/2737 1382/1382/2686 1339/1339/2685 +f 1339/1339/2604 1341/1341/2606 1416/1416/2738 +f 1330/1330/2595 1417/1417/2739 1418/1418/2740 +f 1418/1418/2740 1417/1417/2739 1419/1419/2741 +f 1342/1342/2607 1420/1420/2742 1343/1343/2608 +f 1421/1421/2743 1343/1343/2608 1422/1422/2744 +f 1342/1342/2607 1423/1423/2745 1420/1420/2742 +f 1422/1422/2744 1420/1420/2742 1424/1424/2746 +f 1425/1425/2747 1426/1426/2748 1427/1427/2749 +f 1428/1428/2750 1397/1397/2751 1418/1418/2752 +f 1397/1397/2753 1429/1429/2754 1423/1423/2745 +f 1397/1397/2753 1423/1423/2745 1342/1342/2607 +f 1427/1427/2755 1397/1397/2755 1428/1428/2755 +f 1427/1427/2756 1428/1428/2756 1425/1425/2756 +f 1397/1397/2753 1427/1427/2757 1429/1429/2754 +f 1426/1426/2758 1425/1425/2759 1430/1430/2760 +f 1430/1430/2760 1425/1425/2759 1424/1424/2746 +f 1420/1420/2742 1422/1422/2744 1343/1343/2608 +f 1421/1421/2743 1431/1431/2761 1343/1343/2608 +f 1418/1418/2752 1419/1419/2762 1428/1428/2750 +f 1420/1420/2742 1430/1430/2760 1424/1424/2746 +f 1396/1396/2668 1342/1342/2667 1432/1432/2763 +f 1360/1360/2764 1433/1433/2765 1404/1404/2766 +f 1351/1351/2710 1356/1356/2767 1360/1360/2764 +f 1405/1405/2768 1390/1390/2661 1389/1389/2660 +f 1408/1408/2769 1390/1390/2661 1407/1407/2770 +f 1406/1406/2771 1405/1405/2768 1389/1389/2660 +f 1414/1414/2730 1415/1415/2772 1416/1416/2773 +f 1393/1393/2774 1413/1413/2775 1410/1410/2776 +f 1398/1398/2729 1414/1414/2730 1341/1341/2727 +f 1419/1419/2762 1434/1434/2777 1435/1435/2778 +f 1428/1428/2750 1435/1435/2778 1436/1436/2779 +f 1412/1412/2780 1411/1411/2781 1410/1410/2776 +f 1416/1416/2773 1341/1341/2727 1414/1414/2730 +f 1331/1331/2782 1437/1437/2783 1438/1438/2784 +f 1432/1432/2763 1342/1342/2667 1401/1401/2785 +f 1428/1428/2750 1419/1419/2762 1435/1435/2778 +f 1410/1410/2776 1413/1413/2775 1412/1412/2780 +f 1439/1439/2786 1440/1440/2787 1427/1427/2749 +f 1426/1426/2748 1439/1439/2786 1427/1427/2749 +f 1396/1396/2788 1441/1441/2789 1397/1397/2790 +f 1397/1397/2790 1441/1441/2789 1418/1418/2789 +f 1420/1420/2791 1442/1442/2792 1430/1430/2793 +f 1430/1430/2793 1442/1442/2792 1443/1443/2794 +f 1430/1430/2795 1443/1443/2795 1426/1426/2795 +f 1439/1439/2796 1423/1423/2797 1440/1440/2798 +f 1440/1440/2798 1423/1423/2797 1429/1429/2799 +f 1440/1440/2800 1429/1429/2800 1427/1427/2800 +f 1442/1442/2801 1420/1420/2802 1439/1439/2803 +f 1439/1439/2803 1420/1420/2802 1423/1423/2804 +f 1396/1396/2805 1400/1400/2806 1332/1332/2807 +f 1411/1411/2781 1409/1409/2808 1410/1410/2776 +f 1434/1434/2809 1417/1417/2809 1431/1431/2809 +f 1417/1417/2810 1434/1434/2810 1419/1419/2810 +f 1436/1436/2811 1422/1422/2812 1424/1424/2813 +f 1436/1436/2811 1424/1424/2813 1444/1444/2814 +f 1444/1444/2815 1424/1424/2815 1425/1425/2815 +f 1444/1444/2816 1425/1425/2816 1428/1428/2816 +f 1435/1435/2817 1422/1422/2818 1436/1436/2819 +f 1435/1435/2817 1421/1421/2820 1422/1422/2818 +f 1434/1434/2821 1431/1431/2822 1435/1435/2823 +f 1435/1435/2823 1431/1431/2822 1421/1421/2824 +f 1401/1401/2785 1342/1342/2667 1404/1404/2766 +f 1360/1360/2764 1342/1342/2667 1351/1351/2710 +f 1342/1342/2667 1360/1360/2764 1404/1404/2766 +f 1360/1360/2764 1398/1398/2825 1433/1433/2765 +f 1351/1351/2710 1354/1354/2826 1356/1356/2767 +f 1390/1390/2661 1405/1405/2768 1407/1407/2770 +f 1360/1360/2764 1387/1387/2827 1398/1398/2825 +f 1396/1396/2805 1332/1332/2807 1438/1438/2784 +f 1332/1332/2807 1331/1331/2782 1438/1438/2784 +f 1426/1426/2748 1442/1442/2828 1439/1439/2786 +f 1442/1442/2828 1426/1426/2748 1443/1443/2829 +f 1428/1428/2750 1436/1436/2779 1444/1444/2830 +f 1438/1438/2784 1441/1441/2831 1396/1396/2805 +f 1367/1367/2832 1368/1368/2833 1438/1438/2784 +f 1441/1441/2831 1438/1438/2784 1368/1368/2833 +f 1438/1438/2834 1437/1437/2835 1367/1367/2836 +f 1437/1437/2835 1378/1378/2837 1367/1367/2836 +f 1437/1437/2838 1331/1331/2838 1378/1378/2838 +f 1445/1445/2839 1446/1446/2840 1329/1329/2841 +f 1329/1329/2841 1446/1446/2840 1328/1328/2842 +f 1447/1447/2843 1448/1448/2844 1445/1445/2845 +f 1445/1445/2845 1448/1448/2844 1446/1446/2846 +f 1314/1314/2579 1313/1313/2578 1448/1448/2847 +f 1314/1314/2579 1448/1448/2847 1447/1447/2848 +f 1328/1328/2849 1449/1449/2850 1326/1326/2851 +f 1326/1326/2851 1450/1450/2852 1324/1324/2853 +f 1450/1450/2852 1322/1322/2854 1324/1324/2853 +f 1449/1449/2850 1450/1450/2852 1326/1326/2851 +f 1328/1328/2849 1446/1446/210 1448/1448/2855 +f 1451/1451/2856 1452/1452/2857 1369/1369/2858 +f 1313/1313/2859 1449/1449/2850 1448/1448/2855 +f 1453/1453/2860 1454/1454/2861 1320/1320/2862 +f 1320/1320/2862 1454/1454/2861 1321/1321/2863 +f 1455/1455/2864 1452/1452/2865 1454/1454/2866 +f 1455/1455/2864 1454/1454/2866 1453/1453/2867 +f 1370/1370/2635 1369/1369/2634 1452/1452/2868 +f 1370/1370/2635 1452/1452/2868 1455/1455/2869 +f 1315/1315/2870 1317/1317/2871 1456/1456/2872 +f 1317/1317/2871 1457/1457/2873 1456/1456/2872 +f 1317/1317/2871 1319/1319/2874 1457/1457/2873 +f 1458/1458/2875 1319/1319/2874 1321/1321/2876 +f 1319/1319/2874 1458/1458/2875 1457/1457/2873 +f 1313/1313/2859 1315/1315/2870 1456/1456/2872 +f 1456/1456/2872 1449/1449/2850 1313/1313/2859 +f 1321/1321/2876 1452/1452/2857 1458/1458/2875 +f 1454/1454/210 1452/1452/2857 1321/1321/2876 +f 1452/1452/2857 1451/1451/2856 1458/1458/2875 +f 1451/1451/2856 1369/1369/2858 1371/1371/2877 +f 1328/1328/2849 1448/1448/2855 1449/1449/2850 +f 1371/1371/2877 1459/1459/2878 1451/1451/2856 +f 1376/1376/2879 1459/1459/2878 1374/1374/2880 +f 413/413/2881 1323/1323/2882 626/626/2883 +f 1327/1327/2884 1325/1325/2885 610/610/2886 +f 618/618/2887 1372/1372/2888 611/611/2889 +f 413/413/2881 610/610/2886 1325/1325/2885 +f 626/626/2883 1323/1323/2882 1330/1330/2890 +f 629/629/2891 1329/1329/2892 1327/1327/2884 +f 629/629/2891 623/623/2893 1329/1329/2892 +f 1329/1329/2892 623/623/2893 1445/1445/2894 +f 623/623/2893 1447/1447/2895 1445/1445/2894 +f 1441/1441/2896 617/617/2897 1418/1418/2898 +f 617/617/2897 627/627/2899 1418/1418/2898 +f 1314/1314/2900 1447/1447/2895 623/623/2893 +f 1374/1374/2880 1459/1459/2878 1371/1371/2877 +f 617/617/2897 1441/1441/2896 1368/1368/2901 +f 1384/1384/2902 622/622/2903 621/621/2904 +f 622/622/2903 1377/1377/2905 1375/1375/2906 +f 1314/1314/2900 623/623/2893 632/632/2907 +f 1314/1314/2900 632/632/2907 1316/1316/2908 +f 588/588/2909 1368/1368/2901 1366/1366/2910 +f 1316/1316/2908 632/632/2907 624/624/2911 +f 588/588/2909 1366/1366/2910 612/612/2912 +f 1373/1373/2913 1372/1372/2888 618/618/2887 +f 612/612/2912 1366/1366/2910 1363/1363/2914 +f 1316/1316/2908 624/624/2911 625/625/2915 +f 612/612/2912 1363/1363/2914 613/613/2916 +f 1316/1316/2908 625/625/2915 1318/1318/2917 +f 1318/1318/2917 625/625/2915 631/631/2918 +f 613/613/2916 1363/1363/2914 616/616/2919 +f 616/616/2919 1363/1363/2914 1362/1362/2920 +f 1320/1320/2921 631/631/2918 589/589/2922 +f 616/616/2919 1362/1362/2920 621/621/2904 +f 1318/1318/2917 631/631/2918 1320/1320/2921 +f 621/621/2904 1362/1362/2920 1399/1399/2923 +f 1320/1320/2921 589/589/2922 1453/1453/2924 +f 1399/1399/2923 1384/1384/2902 621/621/2904 +f 1453/1453/2924 589/589/2922 1455/1455/2925 +f 627/627/2899 626/626/2883 1330/1330/2890 +f 589/589/2922 1370/1370/2926 1455/1455/2925 +f 627/627/2899 1330/1330/2890 1418/1418/2898 +f 1325/1325/2885 1323/1323/2882 413/413/2881 +f 1377/1377/2905 622/622/2903 1384/1384/2902 +f 589/589/2922 611/611/2889 1370/1370/2926 +f 630/630/2927 622/622/2903 1375/1375/2906 +f 1370/1370/2926 611/611/2889 1372/1372/2888 +f 1327/1327/2884 610/610/2886 629/629/2891 +f 588/588/2909 617/617/2897 1368/1368/2901 +f 1375/1375/2906 1373/1373/2913 630/630/2927 +f 1373/1373/2913 618/618/2887 630/630/2927 +f 1359/1359/2928 1376/1376/2929 1383/1383/2930 +f 1376/1376/2929 1359/1359/2928 1459/1459/2931 +f 1383/1383/2932 1385/1385/2654 1359/1359/2624 +f 1344/1344/2933 1460/1460/2934 1346/1346/2935 +f 1350/1350/2936 1349/1349/2937 1461/1461/2938 +f 1352/1352/2939 1350/1350/2940 1462/1462/2941 +f 1353/1353/2942 1463/1463/2943 1355/1355/2944 +f 1355/1355/2944 1458/1458/2945 1357/1357/2946 +f 1359/1359/2928 1358/1358/2947 1451/1451/2948 +f 1346/1346/2935 1449/1449/2949 1347/1347/2950 +f 1347/1347/2950 1449/1449/2949 1461/1461/2938 +f 1347/1347/2950 1461/1461/2938 1349/1349/2937 +f 1352/1352/2939 1462/1462/2941 1353/1353/2942 +f 1355/1355/2944 1463/1463/2943 1458/1458/2945 +f 1359/1359/2928 1451/1451/2948 1459/1459/2931 +f 1343/1343/2951 1450/1450/2952 1344/1344/2933 +f 1344/1344/2933 1450/1450/2952 1460/1460/2934 +f 1346/1346/2935 1460/1460/2934 1449/1449/2949 +f 1353/1353/2942 1462/1462/2941 1463/1463/2943 +f 1358/1358/2947 1357/1357/2946 1451/1451/2948 +f 1461/1461/2953 1456/1456/2953 1350/1350/2953 +f 1350/1350/2940 1456/1456/2954 1462/1462/2941 +f 1357/1357/2946 1458/1458/2945 1451/1451/2948 +f 1460/1460/2955 1450/1450/2955 1449/1449/2955 +f 1449/1449/2949 1456/1456/2956 1461/1461/2938 +f 1462/1462/2941 1456/1456/2954 1457/1457/2957 +f 1462/1462/2941 1457/1457/2957 1463/1463/2943 +f 1463/1463/2943 1457/1457/2957 1458/1458/2945 +f 1343/1343/2951 1417/1417/2958 1322/1322/2959 +f 1343/1343/2608 1431/1431/2761 1417/1417/2960 +f 1343/1343/2951 1322/1322/2959 1450/1450/2952 +f 1417/1417/2739 1330/1330/2595 1322/1322/2587 +f 1377/1377/2642 1383/1383/2652 1376/1376/2641 +f 1433/1433/2961 1398/1398/2961 1402/1402/2961 +f 1400/1400/2962 1396/1396/2962 1432/1432/2962 +f 1433/1433/2963 1402/1402/2963 1404/1404/2963 +f 1404/1404/2766 1403/1403/2964 1401/1401/2785 +f 1400/1400/2965 1432/1432/2965 1401/1401/2965 +f 1464/1464/2966 1465/1465/2967 1466/1466/2968 +f 1467/1467/2969 1468/1468/2970 1469/1469/2971 +f 1469/1469/2971 1468/1468/2970 1470/1470/2972 +f 1471/1471/2973 1472/1472/2974 1473/1473/2975 +f 1474/1474/2976 1473/1473/2975 1475/1475/2977 +f 1465/1465/2967 1464/1464/2966 1474/1474/2976 +f 1473/1473/2975 1472/1472/2974 1476/1476/2978 +f 1476/1476/2978 1472/1472/2974 1477/1477/2979 +f 1476/1476/2978 1477/1477/2979 1478/1478/2980 +f 1471/1471/2973 1479/1479/2981 1472/1472/2974 +f 1479/1479/2981 1471/1471/2973 1480/1480/2982 +f 1481/1481/2983 1482/1482/2984 1480/1480/2982 +f 1480/1480/2982 1482/1482/2984 1479/1479/2981 +f 1464/1464/2966 1466/1466/2968 1483/1483/2985 +f 1483/1483/2985 1466/1466/2968 1484/1484/2986 +f 1484/1484/2986 1466/1466/2968 1485/1485/2987 +f 1486/1486/2988 1487/1487/2989 1488/1488/2990 +f 1488/1488/2990 1487/1487/2989 1465/1465/2967 +f 1481/1481/2983 1489/1489/2991 1482/1482/2984 +f 1490/1490/2992 1491/1491/2993 1489/1489/2991 +f 1492/1492/2994 1489/1489/2991 1481/1481/2983 +f 1478/1478/2995 1477/1477/2996 1490/1490/2992 +f 1490/1490/2992 1477/1477/2996 1491/1491/2993 +f 1489/1489/2991 1492/1492/2994 1490/1490/2992 +f 1488/1488/2997 1493/1493/2998 1486/1486/2999 +f 1493/1493/2998 1488/1488/2997 1494/1494/3000 +f 1495/1495/3001 1494/1494/3000 1496/1496/3002 +f 1478/1478/3003 1497/1497/3004 1476/1476/3005 +f 1476/1476/3005 1497/1497/3004 1495/1495/3001 +f 1498/1498/3006 1487/1487/3007 1486/1486/3008 +f 1499/1499/3009 1487/1487/3007 1498/1498/3006 +f 1484/1484/2986 1499/1499/3009 1500/1500/3010 +f 1484/1484/2986 1485/1485/2987 1499/1499/3009 +f 1499/1499/3009 1498/1498/3006 1500/1500/3010 +f 1480/1480/3011 1501/1501/3012 1502/1502/3013 +f 1501/1501/3012 1470/1470/3014 1503/1503/3015 +f 1504/1504/3016 1505/1505/3017 1503/1503/3015 +f 1484/1484/2986 1504/1504/3016 1483/1483/2985 +f 1506/1506/3018 1507/1507/3019 1508/1508/3020 +f 1502/1502/3021 1509/1509/3022 1510/1510/3023 +f 1511/1511/3024 1512/1512/3025 1505/1505/3017 +f 1505/1505/3017 1512/1512/3025 1503/1503/3026 +f 1503/1503/3026 1512/1512/3025 1513/1513/3027 +f 1503/1503/3026 1513/1513/3027 1501/1501/3028 +f 1501/1501/3028 1513/1513/3027 1514/1514/3029 +f 1501/1501/3028 1514/1514/3029 1509/1509/3022 +f 1501/1501/3028 1509/1509/3022 1502/1502/3021 +f 1515/1515/3030 1512/1512/3031 1511/1511/3032 +f 1515/1515/3030 1516/1516/3033 1512/1512/3031 +f 1517/1517/3034 1516/1516/3033 1515/1515/3030 +f 1516/1516/3033 1517/1517/3034 1518/1518/3035 +f 1518/1518/3036 1519/1519/3037 1520/1520/3038 +f 1520/1520/3038 1519/1519/3037 1521/1521/3039 +f 1520/1520/3038 1521/1521/3039 1509/1509/3040 +f 1521/1521/3039 1510/1510/3041 1509/1509/3040 +f 1522/1522/3042 1523/1523/3043 1507/1507/3044 +f 1524/1524/3045 1508/1508/3046 1522/1522/3042 +f 1522/1522/3042 1508/1508/3046 1523/1523/3043 +f 1524/1524/3045 1525/1525/3047 1508/1508/3046 +f 1525/1525/3047 1524/1524/3045 1526/1526/3048 +f 1527/1527/3049 1507/1507/3019 1528/1528/3050 +f 1507/1507/3019 1527/1527/3049 1522/1522/3051 +f 1522/1522/3052 1527/1527/3053 1529/1529/3054 +f 1529/1529/3054 1524/1524/3055 1522/1522/3052 +f 1530/1530/3056 1526/1526/3057 1531/1531/3058 +f 1526/1526/3057 1529/1529/3054 1531/1531/3058 +f 1529/1529/3054 1526/1526/3057 1524/1524/3055 +f 1532/1532/3059 1533/1533/3060 1531/1531/3058 +f 1531/1531/3058 1533/1533/3060 1530/1530/3056 +f 1532/1532/3059 1534/1534/3061 1533/1533/3060 +f 1535/1535/3062 1534/1534/3062 1532/1532/3062 +f 1535/1535/3063 1536/1536/3064 1534/1534/3061 +f 1537/1537/3065 1536/1536/3066 1535/1535/3067 +f 1537/1537/3065 1538/1538/3068 1536/1536/3066 +f 1537/1537/3065 1539/1539/3069 1538/1538/3068 +f 1540/1540/3070 1539/1539/3070 1537/1537/3070 +f 1541/1541/3071 1542/1542/3072 1540/1540/3073 +f 1540/1540/3073 1542/1542/3072 1539/1539/3074 +f 1543/1543/3075 1542/1542/3072 1541/1541/3071 +f 1544/1544/3076 1545/1545/3077 1541/1541/3071 +f 1541/1541/3071 1545/1545/3077 1543/1543/3075 +f 1544/1544/3076 1546/1546/3078 1545/1545/3077 +f 1546/1546/3078 1544/1544/3076 1547/1547/3079 +f 1546/1546/3078 1547/1547/3079 1548/1548/3080 +f 1549/1549/3081 1550/1550/3082 1547/1547/3079 +f 1547/1547/3079 1550/1550/3082 1548/1548/3080 +f 1549/1549/3081 1551/1551/3083 1550/1550/3082 +f 1549/1549/3081 1511/1511/3084 1551/1551/3083 +f 1552/1552/3085 1515/1515/3086 1511/1511/3084 +f 1552/1552/3085 1511/1511/3084 1549/1549/3081 +f 1517/1517/3034 1515/1515/3030 1553/1553/3087 +f 1553/1553/3087 1515/1515/3030 1552/1552/3088 +f 1553/1553/3087 1554/1554/3089 1518/1518/3090 +f 1518/1518/3090 1517/1517/3034 1553/1553/3087 +f 1519/1519/3037 1518/1518/3090 1554/1554/3089 +f 1554/1554/3089 1555/1555/3091 1519/1519/3037 +f 1555/1555/3091 1521/1521/3039 1519/1519/3037 +f 1528/1528/3050 1521/1521/3039 1555/1555/3091 +f 1528/1528/3050 1510/1510/3023 1521/1521/3039 +f 1510/1510/3023 1528/1528/3050 1506/1506/3018 +f 1506/1506/3018 1528/1528/3050 1507/1507/3019 +f 1514/1514/3092 1520/1520/3093 1509/1509/3094 +f 1514/1514/3092 1518/1518/3095 1520/1520/3093 +f 1514/1514/3092 1516/1516/3096 1518/1518/3095 +f 1513/1513/3097 1516/1516/3096 1514/1514/3092 +f 1512/1512/3098 1516/1516/3096 1513/1513/3097 +f 1508/1508/3046 1507/1507/3044 1523/1523/3043 +f 1506/1506/3018 1508/1508/3020 1530/1530/3056 +f 1549/1549/3099 1528/1528/3100 1552/1552/3101 +f 1555/1555/3099 1552/1552/3101 1528/1528/3100 +f 1555/1555/3099 1553/1553/3102 1552/1552/3101 +f 1553/1553/3102 1555/1555/3099 1554/1554/3103 +f 1480/1480/3011 1502/1502/3013 1481/1481/3104 +f 1502/1502/3021 1492/1492/3105 1481/1481/3106 +f 1502/1502/3021 1510/1510/3023 1506/1506/3018 +f 1502/1502/3021 1506/1506/3018 1492/1492/3105 +f 1532/1532/3101 1537/1537/3099 1535/1535/3099 +f 1540/1540/3099 1537/1537/3099 1532/1532/3101 +f 1540/1540/3099 1532/1532/3101 1541/1541/3099 +f 1541/1541/3099 1532/1532/3101 1531/1531/3099 +f 1531/1531/3099 1544/1544/3099 1541/1541/3099 +f 1544/1544/3099 1531/1531/3099 1529/1529/3099 +f 1544/1544/3099 1529/1529/3099 1547/1547/3099 +f 1547/1547/3099 1529/1529/3099 1527/1527/3099 +f 1527/1527/3099 1549/1549/3099 1547/1547/3099 +f 1549/1549/3099 1527/1527/3099 1528/1528/3100 +f 1508/1508/3020 1525/1525/3107 1530/1530/3056 +f 1530/1530/3056 1525/1525/3107 1526/1526/3057 +f 1493/1493/2998 1556/1556/3108 1542/1542/3109 +f 1533/1533/3110 1557/1557/3111 1497/1497/3004 +f 1497/1497/3004 1557/1557/3111 1558/1558/3112 +f 1497/1497/3004 1558/1558/3112 1495/1495/3113 +f 1495/1495/3113 1558/1558/3112 1559/1559/3114 +f 1495/1495/3113 1559/1559/3114 1494/1494/3115 +f 1494/1494/3115 1559/1559/3114 1556/1556/3108 +f 1494/1494/3115 1556/1556/3108 1493/1493/2998 +f 1539/1539/3069 1542/1542/3116 1556/1556/3117 +f 1557/1557/3118 1533/1533/3060 1534/1534/3061 +f 1557/1557/3118 1534/1534/3061 1560/1560/3119 +f 1536/1536/3064 1560/1560/3119 1534/1534/3061 +f 1539/1539/3069 1561/1561/3120 1538/1538/3068 +f 1539/1539/3069 1556/1556/3117 1561/1561/3120 +f 1559/1559/3121 1561/1561/3122 1556/1556/3123 +f 1559/1559/3121 1538/1538/3124 1561/1561/3122 +f 1559/1559/3121 1536/1536/3125 1538/1538/3124 +f 1558/1558/3126 1536/1536/3125 1559/1559/3121 +f 1558/1558/3126 1560/1560/3127 1536/1536/3125 +f 1557/1557/3128 1560/1560/3127 1558/1558/3126 +f 1490/1490/2992 1492/1492/2994 1506/1506/3129 +f 1490/1490/2992 1506/1506/3129 1530/1530/3130 +f 1497/1497/3004 1478/1478/3003 1490/1490/3131 +f 1497/1497/3004 1490/1490/3131 1530/1530/3132 +f 1533/1533/3110 1497/1497/3004 1530/1530/3132 +f 1545/1545/3133 1546/1546/3134 1562/1562/3135 +f 1546/1546/3134 1563/1563/3136 1562/1562/3135 +f 1548/1548/3137 1563/1563/3136 1546/1546/3134 +f 1548/1548/3137 1550/1550/3082 1563/1563/3136 +f 1563/1563/3136 1550/1550/3082 1562/1562/3135 +f 1543/1543/3138 1562/1562/3135 1551/1551/3083 +f 1500/1500/3010 1498/1498/3006 1543/1543/3139 +f 1551/1551/3140 1500/1500/3010 1543/1543/3139 +f 1562/1562/3135 1550/1550/3082 1551/1551/3083 +f 1505/1505/3017 1504/1504/3016 1484/1484/2986 +f 1505/1505/3017 1484/1484/2986 1500/1500/3141 +f 1505/1505/3017 1500/1500/3141 1551/1551/3142 +f 1505/1505/3017 1551/1551/3142 1511/1511/3024 +f 1562/1562/3135 1543/1543/3138 1545/1545/3143 +f 1486/1486/2999 1493/1493/2998 1498/1498/3144 +f 1543/1543/3145 1493/1493/2998 1542/1542/3109 +f 1498/1498/3144 1493/1493/2998 1543/1543/3145 +f 513/513/3146 591/591/3147 604/604/3148 +f 528/528/3149 601/601/3150 600/600/3151 +f 601/601/3150 528/528/3149 236/236/3152 +f 528/528/3149 600/600/3151 735/735/3153 +f 733/733/3154 527/527/3155 735/735/3153 +f 398/398/3156 236/236/3152 529/529/3157 +f 398/398/3156 601/601/3150 236/236/3152 +f 594/594/3158 592/592/3159 515/515/3160 +f 526/526/3161 527/527/3155 733/733/3154 +f 598/598/3162 516/516/3163 517/517/3164 +f 529/529/3157 608/608/3165 396/396/3166 +f 733/733/3154 747/747/3167 526/526/3161 +f 529/529/3157 530/530/761 608/608/3165 +f 521/521/3168 523/523/3169 729/729/3170 +f 731/731/3171 526/526/3161 747/747/3167 +f 530/530/761 394/394/3172 608/608/3165 +f 731/731/3171 523/523/3169 526/526/3161 +f 729/729/3170 523/523/3169 731/731/3171 +f 530/530/761 392/392/3173 394/394/3172 +f 381/381/760 392/392/3173 530/530/761 +f 381/381/760 508/508/3174 392/392/3173 +f 514/514/3175 508/508/3174 381/381/760 +f 741/741/3176 521/521/3168 729/729/3170 +f 741/741/3176 519/519/3177 521/521/3168 +f 738/738/3178 519/519/3177 741/741/3176 +f 514/514/3175 510/510/3179 508/508/3174 +f 513/513/3146 510/510/3179 514/514/3175 +f 738/738/3178 737/737/3180 519/519/3177 +f 737/737/3180 517/517/3164 519/519/3177 +f 737/737/3180 743/743/3181 517/517/3164 +f 527/527/3155 528/528/3149 735/735/3153 +f 529/529/3157 396/396/3166 398/398/3156 +f 607/607/3182 513/513/3146 604/604/3148 +f 746/746/3183 517/517/3164 743/743/3181 +f 598/598/3162 517/517/3164 746/746/3183 +f 513/513/3146 515/515/3160 592/592/3159 +f 516/516/3163 598/598/3162 597/597/3184 +f 591/591/3147 513/513/3146 592/592/3159 +f 512/512/3185 510/510/3179 513/513/3146 +f 500/500/3186 594/594/3158 515/515/3160 +f 500/500/3186 597/597/3184 594/594/3158 +f 597/597/3184 500/500/3186 516/516/3163 +f 607/607/3182 512/512/3185 513/513/3146 +f 511/511/3187 606/606/3188 848/848/3189 +f 606/606/3188 605/605/3190 848/848/3189 +f 848/848/3189 605/605/3190 590/590/3191 +f 866/866/3192 744/744/3193 736/736/3194 +f 745/745/3195 744/744/3193 866/866/3192 +f 745/745/3195 866/866/3192 599/599/3196 +f 872/872/3197 748/748/3198 732/732/3199 +f 748/748/3198 872/872/3197 869/869/3200 +f 750/750/3201 748/748/3198 869/869/3200 +f 1465/1465/2967 1474/1474/2976 1475/1475/2977 +f 1496/1496/3202 1488/1488/2990 1475/1475/2977 +f 1488/1488/2997 1496/1496/3002 1494/1494/3000 +f 1475/1475/2977 1488/1488/2990 1465/1465/2967 +f 1476/1476/2978 1475/1475/2977 1473/1473/2975 +f 1496/1496/3002 1476/1476/3005 1495/1495/3001 +f 1476/1476/2978 1496/1496/3202 1475/1475/2977 +f 1471/1471/2973 1464/1464/2966 1468/1468/2970 +f 1464/1464/2966 1471/1471/2973 1473/1473/2975 +f 1474/1474/2976 1464/1464/2966 1473/1473/2975 +f 1471/1471/2973 1468/1468/2970 1467/1467/2969 +f 1499/1499/3203 1466/1466/2968 1465/1465/2967 +f 1465/1465/2967 1487/1487/2989 1499/1499/3203 +f 1485/1485/2987 1466/1466/2968 1499/1499/3203 +f 1479/1479/2981 1482/1482/2984 1489/1489/3204 +f 1489/1489/3204 1472/1472/2974 1479/1479/2981 +f 1489/1489/3204 1491/1491/3205 1472/1472/2974 +f 1477/1477/2979 1472/1472/2974 1491/1491/3205 +f 1470/1470/3014 1504/1504/3016 1503/1503/3015 +f 1468/1468/2970 1464/1464/2966 1470/1470/2972 +f 1470/1470/3014 1483/1483/2985 1504/1504/3016 +f 1483/1483/2985 1470/1470/2972 1464/1464/2966 +f 1471/1471/2973 1467/1467/2969 1469/1469/2971 +f 1469/1469/2971 1480/1480/2982 1471/1471/2973 +f 1469/1469/2971 1470/1470/2972 1480/1480/2982 +f 1501/1501/3012 1480/1480/3011 1470/1470/3014 diff --git a/examples/Cassie/urdf/meshes/agility/hip-yaw.obj b/examples/Cassie/urdf/meshes/agility/hip-yaw.obj new file mode 100644 index 0000000000..d1f54f21c7 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/hip-yaw.obj @@ -0,0 +1,4782 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o hip-yaw +v 0.009840 -0.037390 -0.008288 +v 0.008183 -0.037125 0.001224 +v 0.004829 -0.036659 -0.007895 +v 0.004415 -0.036610 0.007760 +v 0.010947 -0.037598 0.008391 +v -0.000082 -0.036465 0.008233 +v 0.001837 -0.036526 0.014639 +v -0.000074 -0.036534 0.019923 +v 0.008661 -0.037147 0.020085 +v -0.005368 -0.036756 0.019961 +v -0.001959 -0.036516 0.012938 +v -0.007581 -0.037018 0.003753 +v -0.007974 -0.037028 -0.007445 +v -0.006595 -0.036891 -0.005051 +v -0.010276 -0.037461 0.008161 +v 0.000474 -0.036455 -0.008319 +v -0.002184 -0.036546 -0.014127 +v 0.000001 -0.036534 -0.019925 +v -0.005039 -0.036722 -0.019953 +v 0.005858 -0.036807 -0.019959 +v 0.001923 -0.036532 -0.014363 +v 0.013900 -0.038314 0.019905 +v 0.013469 -0.038156 0.005431 +v 0.011557 -0.037759 -0.003599 +v 0.014265 -0.038432 -0.005559 +v 0.014230 -0.038420 -0.012609 +v 0.011706 -0.037766 -0.019978 +v 0.014330 -0.038483 -0.019952 +v -0.013955 -0.038350 -0.012087 +v -0.014192 -0.038401 -0.005547 +v -0.013869 -0.038303 -0.019930 +v -0.010085 -0.037432 0.001124 +v -0.014263 -0.038431 0.005558 +v -0.014340 -0.038494 0.019920 +v -0.018863 -0.039901 -0.020074 +v -0.019385 -0.040047 -0.005436 +v -0.019308 -0.040033 0.005457 +v -0.020073 -0.040081 0.020847 +v 0.018991 -0.039939 0.020096 +v 0.019844 -0.040151 0.005390 +v 0.019303 -0.040027 -0.005449 +v 0.018772 -0.039875 -0.020053 +v -0.020460 -0.040048 -0.021081 +v -0.022043 -0.039560 0.002517 +v -0.022501 -0.039364 0.021033 +v -0.022580 -0.039294 -0.001194 +v -0.023030 -0.038945 -0.021001 +v -0.011575 -0.036956 -0.021702 +v -0.002341 -0.035767 -0.021721 +v 0.010548 -0.036724 -0.021669 +v 0.020521 -0.040074 -0.021074 +v -0.010635 -0.037551 -0.019983 +v 0.021876 -0.039628 -0.002806 +v 0.022508 -0.039376 0.020997 +v 0.022537 -0.039274 0.000440 +v 0.023110 -0.038867 -0.020995 +v 0.020173 -0.039929 0.021157 +v 0.002083 -0.035773 0.021713 +v 0.011016 -0.036895 0.021707 +v -0.016475 -0.038254 0.021845 +v -0.011450 -0.037713 0.019961 +v -0.007386 -0.036286 0.021664 +v -0.030550 -0.027836 0.002076 +v -0.030547 -0.026737 -0.009064 +v -0.030493 -0.029920 -0.017182 +v -0.030456 -0.030481 0.017254 +v -0.030782 -0.022719 0.016726 +v -0.030566 -0.025418 0.012580 +v -0.030586 -0.023414 -0.017021 +v 0.001586 -0.031101 0.024998 +v -0.005236 -0.023153 0.025000 +v -0.021083 -0.035499 0.024949 +v -0.015518 -0.024765 0.024993 +v -0.020985 -0.026371 0.025045 +v -0.024559 -0.031789 0.024997 +v -0.024402 -0.023859 0.025093 +v 0.005474 -0.023165 0.025000 +v 0.015725 -0.024826 0.024993 +v 0.021039 -0.035298 0.025000 +v 0.020508 -0.026212 0.025103 +v 0.024558 -0.031796 0.024993 +v 0.024429 -0.024050 0.025065 +v 0.023450 -0.022490 0.026000 +v 0.018160 -0.022345 0.029968 +v 0.018264 -0.025531 0.026115 +v 0.011722 -0.022328 0.033023 +v 0.012555 -0.024147 0.030851 +v 0.004960 -0.022335 0.034689 +v 0.002316 -0.022945 0.034508 +v -0.004010 -0.022333 0.034885 +v -0.012419 -0.022326 0.032766 +v -0.007474 -0.023397 0.033152 +v -0.018707 -0.022332 0.029627 +v -0.018778 -0.025673 0.025714 +v -0.013819 -0.024413 0.029951 +v -0.023520 -0.022538 0.025933 +v -0.031213 -0.024120 0.011689 +v -0.033702 -0.022335 0.009580 +v -0.031160 -0.025646 0.006360 +v -0.034913 -0.022335 0.002936 +v -0.031098 -0.026348 0.000754 +v -0.034834 -0.022350 -0.003450 +v -0.031138 -0.026034 -0.004030 +v -0.033759 -0.022344 -0.009361 +v -0.031170 -0.024803 -0.009800 +v -0.031428 -0.022409 -0.015447 +v -0.028325 -0.033892 0.020671 +v -0.029710 -0.020337 0.018525 +v -0.032828 -0.020337 0.012281 +v -0.034644 -0.020337 0.005265 +v -0.034977 -0.020338 -0.002097 +v -0.033378 -0.020338 -0.010901 +v -0.030460 -0.020338 -0.017239 +v -0.027601 -0.020336 -0.021722 +v -0.029842 -0.032053 -0.018332 +v -0.023444 -0.022479 -0.026025 +v -0.024429 -0.024050 -0.025065 +v -0.024603 -0.031760 -0.024986 +v -0.028004 -0.033992 -0.021005 +v -0.022168 -0.020338 -0.027122 +v -0.016211 -0.020338 -0.031066 +v -0.015942 -0.022339 -0.031198 +v -0.009546 -0.020338 -0.033717 +v -0.009420 -0.022341 -0.033743 +v -0.000585 -0.020338 -0.035113 +v -0.000798 -0.022338 -0.035095 +v 0.011294 -0.020338 -0.033328 +v 0.008152 -0.022337 -0.034071 +v 0.016523 -0.022339 -0.030998 +v 0.020991 -0.020337 -0.028078 +v 0.027768 -0.020334 -0.021721 +v 0.024385 -0.023767 -0.025110 +v 0.023488 -0.022507 -0.025968 +v 0.029704 -0.032231 -0.018527 +v 0.028000 -0.033999 -0.021001 +v 0.024565 -0.031786 -0.024995 +v 0.032196 -0.020338 -0.013821 +v 0.031715 -0.022345 -0.014854 +v 0.030890 -0.022795 -0.016458 +v 0.030532 -0.023955 -0.017109 +v 0.030485 -0.030118 -0.017197 +v 0.034226 -0.020338 -0.007442 +v 0.034338 -0.022331 -0.006989 +v 0.035071 -0.020338 -0.000000 +v 0.035065 -0.022329 0.000001 +v 0.033860 -0.020337 0.009283 +v 0.034043 -0.022325 0.008568 +v 0.030687 -0.020339 0.016852 +v 0.031249 -0.022500 0.015786 +v 0.030571 -0.023554 0.017045 +v 0.029900 -0.031989 0.018225 +v 0.030497 -0.029812 0.017175 +v 0.028006 -0.033993 0.021001 +v 0.026282 -0.020337 0.023239 +v 0.020916 -0.020337 0.028129 +v 0.012789 -0.020337 0.032704 +v 0.002327 -0.020337 0.035041 +v -0.006517 -0.020337 0.034432 +v -0.016726 -0.020337 0.030998 +v -0.024708 -0.020338 0.024804 +v 0.020263 -0.036640 0.024406 +v 0.009795 -0.034039 0.024285 +v -0.000336 -0.033155 0.024283 +v -0.010152 -0.034083 0.024295 +v -0.019905 -0.036676 0.024334 +v 0.010996 -0.032333 -0.024999 +v 0.005239 -0.023153 -0.025000 +v 0.015539 -0.024771 -0.024993 +v 0.020901 -0.035679 -0.024910 +v 0.020339 -0.026157 -0.025133 +v -0.006489 -0.031700 -0.024999 +v -0.005445 -0.023174 -0.025000 +v -0.015659 -0.024807 -0.024993 +v -0.021032 -0.035303 -0.025000 +v -0.020496 -0.026208 -0.025105 +v -0.011619 -0.023944 -0.031479 +v -0.018261 -0.025531 -0.026117 +v -0.000916 -0.022950 -0.034489 +v 0.009196 -0.023583 -0.032598 +v 0.018192 -0.025498 -0.026225 +v -0.020252 -0.036642 -0.024411 +v -0.013522 -0.034801 -0.024293 +v -0.004887 -0.033383 -0.024290 +v 0.006598 -0.033460 -0.024279 +v 0.019841 -0.036695 -0.024320 +v 0.030565 -0.027231 -0.005942 +v 0.030550 -0.027844 0.001937 +v 0.030552 -0.025588 0.012373 +v 0.031076 -0.025147 -0.009106 +v 0.031102 -0.026358 -0.001324 +v 0.031141 -0.026011 0.004175 +v 0.031185 -0.024926 0.009246 +v 0.046227 -0.104876 -0.025000 +v -0.000559 -0.138526 -0.025000 +v 0.048610 -0.092476 -0.025000 +v 0.047452 -0.079601 -0.025000 +v 0.042075 -0.114247 -0.025000 +v 0.028415 -0.129380 -0.025000 +v 0.036048 -0.122538 -0.025000 +v 0.038675 -0.048955 -0.024740 +v 0.023141 -0.037704 -0.025031 +v 0.019516 -0.134467 -0.025000 +v 0.000361 -0.032811 -0.025006 +v 0.014182 -0.034664 -0.024761 +v 0.009748 -0.137573 -0.025000 +v -0.039865 -0.053105 -0.024973 +v -0.047346 -0.079207 -0.025000 +v -0.010637 -0.137382 -0.025000 +v -0.014269 -0.034683 -0.024750 +v -0.036651 -0.121858 -0.025000 +v -0.020346 -0.134094 -0.025000 +v -0.022671 -0.037463 -0.024780 +v -0.029148 -0.128841 -0.025000 +v -0.024455 -0.037222 -0.024975 +v -0.046497 -0.104008 -0.025000 +v -0.048658 -0.091186 -0.025000 +v -0.042522 -0.113455 -0.025000 +v 0.010637 -0.137382 0.025000 +v 0.020346 -0.134094 0.025000 +v -0.009748 -0.137573 0.025000 +v 0.047347 -0.079206 0.025000 +v 0.036651 -0.121858 0.025000 +v 0.048658 -0.091186 0.025000 +v 0.042521 -0.113455 0.025000 +v 0.046498 -0.104007 0.025000 +v 0.029148 -0.128841 0.025000 +v 0.038869 -0.049629 0.024857 +v 0.022671 -0.037463 0.024780 +v 0.014275 -0.034677 0.024776 +v -0.047452 -0.079600 0.025000 +v -0.048610 -0.092476 0.025000 +v -0.042075 -0.114247 0.025000 +v 0.023747 -0.037357 0.024962 +v 0.007011 -0.033358 0.024762 +v -0.000922 -0.032874 0.024820 +v -0.036048 -0.122538 0.025000 +v -0.028416 -0.129380 0.025000 +v 0.000515 -0.138540 0.025000 +v -0.014181 -0.034656 0.024786 +v -0.019517 -0.134467 0.025000 +v -0.022876 -0.037560 0.024777 +v -0.038877 -0.049660 0.024859 +v -0.023372 -0.037440 0.024932 +v -0.046227 -0.104876 0.025000 +v -0.030843 -0.031157 -0.017813 +v -0.027808 -0.034192 -0.015078 +v -0.027568 -0.034432 -0.017839 +v -0.028091 -0.033909 -0.023311 +v -0.023202 -0.038798 -0.016094 +v -0.024230 -0.037770 -0.013378 +v -0.022633 -0.039321 0.021568 +v -0.030821 -0.031179 0.017768 +v -0.026355 -0.035645 -0.012784 +v -0.026044 -0.035956 -0.019169 +v -0.022335 -0.039550 -0.021468 +v -0.024487 -0.037513 -0.018896 +v -0.028303 -0.033697 0.023077 +v -0.027342 -0.034658 0.018184 +v -0.023928 -0.038072 0.018246 +v -0.023269 -0.038731 0.015913 +v -0.025105 -0.036839 0.024865 +v -0.025536 -0.036464 0.019293 +v -0.027902 -0.034098 0.015514 +v -0.024458 -0.037542 0.013019 +v -0.026816 -0.035184 0.013191 +v -0.034564 -0.034633 0.016358 +v -0.035891 -0.039256 0.014321 +v -0.035750 -0.038765 0.016946 +v -0.041882 -0.060125 0.017694 +v -0.042024 -0.060620 0.015105 +v -0.035652 -0.038424 0.021262 +v -0.042024 -0.060620 -0.016895 +v -0.041134 -0.057519 -0.019993 +v -0.035750 -0.038765 -0.015054 +v -0.034693 -0.035083 -0.018104 +v -0.035891 -0.039256 -0.017680 +v -0.036649 -0.041897 -0.019968 +v -0.041882 -0.060125 -0.014305 +v -0.041127 -0.057493 0.019965 +v -0.038972 -0.049988 0.021661 +v -0.037130 -0.043573 -0.023619 +v -0.036692 -0.042048 0.020069 +v -0.038801 -0.049393 -0.021661 +v -0.041126 -0.057493 -0.012034 +v -0.041134 -0.057519 0.012007 +v -0.036649 -0.041897 0.012031 +v -0.036693 -0.042048 -0.011931 +v -0.038801 -0.049393 0.010339 +v -0.038972 -0.049988 -0.010339 +v -0.021800 -0.039735 0.021635 +v -0.020282 -0.039867 0.021533 +v -0.020424 -0.039891 -0.021555 +v 0.034693 -0.035083 0.018104 +v 0.034564 -0.034634 -0.016358 +v 0.030843 -0.031157 0.017813 +v 0.030821 -0.031179 -0.017768 +v 0.041882 -0.060125 -0.017694 +v 0.042024 -0.060620 -0.015105 +v 0.041882 -0.060125 0.014306 +v 0.042024 -0.060620 0.016895 +v 0.035891 -0.039256 -0.014320 +v 0.035750 -0.038765 -0.016946 +v 0.035652 -0.038423 -0.021262 +v 0.041126 -0.057493 -0.019966 +v 0.038972 -0.049988 -0.021661 +v 0.041134 -0.057519 0.019993 +v 0.035750 -0.038765 0.015054 +v 0.035891 -0.039256 0.017680 +v 0.036649 -0.041897 0.019969 +v 0.036692 -0.042048 -0.020069 +v 0.036389 -0.040989 0.022444 +v 0.041126 -0.057493 0.012035 +v 0.041134 -0.057519 -0.012007 +v 0.036649 -0.041897 -0.012032 +v 0.036692 -0.042049 0.011931 +v 0.038801 -0.049393 0.021661 +v 0.038801 -0.049393 -0.010339 +v 0.038972 -0.049988 0.010339 +v 0.023806 -0.038194 0.018250 +v 0.023358 -0.038642 0.015235 +v 0.022373 -0.039529 0.021505 +v 0.022583 -0.039349 -0.021560 +v 0.024230 -0.037770 -0.018622 +v 0.025091 -0.036850 -0.024867 +v 0.023294 -0.038706 -0.016486 +v 0.025741 -0.036259 -0.019252 +v 0.028303 -0.033697 -0.023077 +v 0.027494 -0.034506 -0.017989 +v 0.025077 -0.036856 0.024867 +v 0.026480 -0.035520 -0.012849 +v 0.027838 -0.034162 -0.015235 +v 0.027808 -0.034192 0.015078 +v 0.026355 -0.035645 0.012784 +v 0.023975 -0.038025 -0.013576 +v 0.027568 -0.034432 0.017839 +v 0.028091 -0.033909 0.023311 +v 0.024230 -0.037770 0.013378 +v 0.025856 -0.036144 0.019238 +v 0.019599 -0.040119 0.020584 +v 0.020548 -0.040143 -0.020822 +v 0.019294 -0.040043 -0.020585 +v 0.021010 -0.040066 0.020888 +v 0.021798 -0.039736 -0.021634 +v 0.015389 -0.038669 0.020976 +v 0.013546 -0.038120 -0.020964 +v 0.010187 -0.037355 0.020976 +v 0.005759 -0.036686 0.020931 +v 0.005767 -0.036676 -0.020989 +v -0.000280 -0.036424 0.020929 +v 0.000280 -0.036424 -0.020929 +v -0.005767 -0.036676 0.020989 +v -0.005759 -0.036687 -0.020931 +v -0.013545 -0.038120 0.020964 +v -0.010188 -0.037355 -0.020976 +v -0.015392 -0.038669 -0.020978 +v -0.019315 -0.040045 0.020610 +v -0.019599 -0.040119 -0.020584 +v 0.034531 -0.037369 0.015894 +v 0.026714 -0.045185 0.017501 +v 0.028283 -0.043617 0.020574 +v 0.030147 -0.041752 0.021490 +v 0.032131 -0.039768 0.021134 +v 0.033763 -0.038136 0.019137 +v 0.033184 -0.038715 0.011742 +v 0.028296 -0.043604 0.011376 +v 0.030634 -0.041265 0.010448 +v 0.026856 -0.045043 0.014100 +v 0.032848 -0.039052 0.015797 +v 0.032402 -0.039498 0.017935 +v 0.030689 -0.041210 0.019332 +v 0.028578 -0.043322 0.017839 +v 0.028338 -0.043562 0.015078 +v 0.029609 -0.042290 0.012937 +v 0.031954 -0.039946 0.013319 +v 0.034483 -0.037417 -0.015595 +v 0.026609 -0.045290 -0.016997 +v 0.027033 -0.044866 -0.013594 +v 0.028283 -0.043617 -0.011426 +v 0.030794 -0.041105 -0.010410 +v 0.033395 -0.038505 -0.012071 +v 0.034086 -0.037814 -0.018333 +v 0.028296 -0.043604 -0.020624 +v 0.030634 -0.041265 -0.021552 +v 0.032872 -0.039028 -0.020530 +v 0.032893 -0.039007 -0.015618 +v 0.031304 -0.040595 -0.012784 +v 0.028670 -0.043230 -0.013895 +v 0.028338 -0.043562 -0.016922 +v 0.029437 -0.042463 -0.018896 +v 0.031803 -0.040096 -0.018887 +v -0.021010 -0.040066 -0.020888 +v -0.020548 -0.040143 0.020822 +v -0.028440 -0.043460 0.014388 +v -0.028484 -0.043415 0.017451 +v -0.029809 -0.042090 0.019125 +v -0.031573 -0.040326 0.018918 +v -0.032757 -0.039142 0.017044 +v -0.032611 -0.039288 0.014549 +v -0.030898 -0.041002 0.012647 +v -0.031138 -0.040761 0.010399 +v -0.028283 -0.043617 0.011426 +v -0.026613 -0.045286 0.014885 +v -0.027314 -0.044585 0.019247 +v -0.029957 -0.041942 0.021601 +v -0.032872 -0.039028 0.020530 +v -0.034086 -0.037814 0.018333 +v -0.034483 -0.037417 0.015595 +v -0.033588 -0.038312 0.012463 +v -0.028248 -0.043652 -0.016203 +v -0.028925 -0.042975 -0.013576 +v -0.030806 -0.041094 -0.012762 +v -0.032656 -0.039244 -0.014388 +v -0.032534 -0.039366 -0.017722 +v -0.031088 -0.040811 -0.019168 +v -0.029142 -0.042758 -0.018681 +v -0.026856 -0.045043 -0.014100 +v -0.028296 -0.043604 -0.011376 +v -0.030634 -0.041265 -0.010448 +v -0.033184 -0.038715 -0.011742 +v -0.034531 -0.037369 -0.015894 +v -0.033588 -0.038312 -0.019537 +v -0.031477 -0.040423 -0.021445 +v -0.028553 -0.043346 -0.020885 +v -0.026714 -0.045185 -0.017501 +v 0.020424 -0.039891 0.021555 +v -0.007898 -0.033557 0.024481 +v -0.005268 -0.033226 -0.024499 +v 0.004021 -0.033036 -0.024696 +v 0.023117 -0.037487 -0.024864 +v 0.020262 -0.039881 -0.021509 +v -0.030752 -0.041147 -0.012750 +v -0.032130 -0.042032 -0.012647 +v -0.031815 -0.040084 -0.013228 +v -0.033990 -0.040172 -0.015124 +v -0.032951 -0.038949 -0.015614 +v -0.033589 -0.040573 -0.017938 +v -0.032124 -0.039776 -0.018467 +v -0.031829 -0.042334 -0.019377 +v -0.030191 -0.041709 -0.019346 +v -0.029844 -0.044319 -0.018121 +v -0.028273 -0.043626 -0.017161 +v -0.029369 -0.044793 -0.015119 +v -0.028762 -0.043137 -0.013747 +v -0.030587 -0.043575 -0.013082 +v -0.030532 -0.041368 -0.012696 +v -0.031676 -0.042487 -0.012738 +v -0.030523 -0.041377 -0.010998 +v -0.031671 -0.042492 -0.011008 +v -0.029844 -0.044318 -0.011699 +v -0.028618 -0.043282 -0.011783 +v -0.028434 -0.045729 -0.013958 +v -0.027346 -0.044553 -0.013878 +v -0.027029 -0.044871 -0.016865 +v -0.028171 -0.045991 -0.016451 +v -0.028742 -0.045420 -0.018825 +v -0.028281 -0.043619 -0.019903 +v -0.030577 -0.043585 -0.020804 +v -0.031000 -0.040900 -0.021078 +v -0.033061 -0.041101 -0.020657 +v -0.033426 -0.038473 -0.018989 +v -0.034669 -0.039494 -0.018670 +v -0.035209 -0.038953 -0.016277 +v -0.034109 -0.037791 -0.015086 +v -0.034792 -0.039371 -0.013579 +v -0.032641 -0.039259 -0.011941 +v -0.033546 -0.040616 -0.011776 +v -0.032013 -0.042150 -0.011020 +v -0.030864 -0.041036 -0.011028 +v -0.034154 -0.048494 -0.017443 +v -0.033516 -0.048989 -0.019777 +v -0.032467 -0.050045 -0.017441 +v -0.035922 -0.046726 -0.018887 +v -0.036736 -0.045751 -0.020840 +v -0.035128 -0.047368 -0.020885 +v -0.039344 -0.043154 -0.016728 +v -0.038507 -0.044005 -0.019362 +v -0.037690 -0.044958 -0.017443 +v -0.037688 -0.044809 -0.011733 +v -0.039078 -0.043428 -0.013861 +v -0.037690 -0.044958 -0.014557 +v -0.034154 -0.048494 -0.014557 +v -0.032389 -0.050098 -0.014912 +v -0.034471 -0.048042 -0.011396 +v -0.036153 -0.046342 -0.011030 +v -0.035922 -0.046726 -0.013113 +v -0.033102 -0.049394 -0.012863 +v -0.015703 -0.030172 -0.016532 +v -0.017959 -0.027918 -0.013526 +v -0.016437 -0.029435 -0.013909 +v -0.019268 -0.026600 -0.015028 +v -0.018659 -0.027202 -0.018151 +v -0.016817 -0.029060 -0.018333 +v -0.029436 -0.044633 -0.015425 +v -0.015682 -0.030887 -0.016302 +v -0.016597 -0.029972 -0.013456 +v -0.030532 -0.043537 -0.013251 +v -0.018614 -0.027962 -0.013089 +v -0.032011 -0.042057 -0.012949 +v -0.033043 -0.041032 -0.013623 +v -0.019838 -0.026742 -0.014685 +v -0.033835 -0.040234 -0.015478 +v -0.019944 -0.026632 -0.017029 +v -0.033331 -0.040738 -0.018051 +v -0.018651 -0.027924 -0.018891 +v -0.031613 -0.042456 -0.019159 +v -0.016812 -0.029764 -0.018688 +v -0.029909 -0.044160 -0.018010 +v -0.028456 -0.045809 -0.014229 +v -0.028198 -0.046072 -0.016366 +v -0.031603 -0.042666 -0.010991 +v -0.029447 -0.044820 -0.012118 +v -0.033365 -0.040903 -0.020492 +v -0.034942 -0.039328 -0.018128 +v -0.031345 -0.042919 -0.020950 +v -0.028673 -0.045592 -0.018427 +v -0.029671 -0.044599 -0.020077 +v -0.034558 -0.039709 -0.012913 +v -0.033102 -0.041163 -0.011436 +v -0.035242 -0.039022 -0.015636 +v -0.034154 -0.041423 -0.014557 +v -0.034154 -0.041423 -0.017443 +v -0.032386 -0.043190 -0.013113 +v -0.030618 -0.044958 -0.014557 +v -0.030618 -0.044958 -0.017443 +v -0.032386 -0.043190 -0.018887 +v 0.037690 -0.044958 -0.017443 +v 0.038486 -0.044019 -0.019340 +v 0.039210 -0.043272 -0.017434 +v 0.035922 -0.046726 -0.018887 +v 0.035286 -0.047210 -0.020957 +v 0.037064 -0.045443 -0.020681 +v 0.034154 -0.048494 -0.017443 +v 0.032619 -0.049877 -0.018017 +v 0.033586 -0.048912 -0.019842 +v 0.034237 -0.048276 -0.011552 +v 0.032738 -0.049752 -0.013536 +v 0.034154 -0.048494 -0.014557 +v 0.039354 -0.043159 -0.015272 +v 0.037690 -0.044958 -0.014557 +v 0.038686 -0.043810 -0.013039 +v 0.036149 -0.046348 -0.010999 +v 0.035922 -0.046726 -0.013113 +v 0.037679 -0.044819 -0.011755 +v 0.032339 -0.050177 -0.016000 +v 0.015705 -0.030172 -0.015702 +v 0.017243 -0.028608 -0.013307 +v 0.019303 -0.026565 -0.015167 +v 0.018800 -0.027072 -0.017891 +v 0.016679 -0.029182 -0.018396 +v 0.033829 -0.040240 -0.015425 +v 0.020041 -0.026538 -0.015760 +v 0.019428 -0.027151 -0.013858 +v 0.032733 -0.041336 -0.013251 +v 0.017906 -0.028670 -0.012913 +v 0.030851 -0.043218 -0.013041 +v 0.016373 -0.030206 -0.013822 +v 0.029624 -0.044442 -0.014695 +v 0.015678 -0.030890 -0.016243 +v 0.029540 -0.044529 -0.017106 +v 0.016777 -0.029799 -0.018660 +v 0.030361 -0.043717 -0.018499 +v 0.031652 -0.042417 -0.019159 +v 0.018245 -0.028337 -0.018987 +v 0.019545 -0.027030 -0.018006 +v 0.033356 -0.040713 -0.018010 +v 0.034673 -0.039600 -0.013251 +v 0.035264 -0.039000 -0.015634 +v 0.033128 -0.041139 -0.011351 +v 0.029488 -0.044777 -0.019811 +v 0.028396 -0.045871 -0.017804 +v 0.032367 -0.041898 -0.020876 +v 0.030836 -0.043433 -0.020849 +v 0.034924 -0.039348 -0.018115 +v 0.033795 -0.040475 -0.020077 +v 0.029253 -0.045014 -0.012364 +v 0.031091 -0.043174 -0.011103 +v 0.028293 -0.045972 -0.014917 +v 0.030618 -0.044958 -0.014557 +v 0.030618 -0.044958 -0.017443 +v 0.032386 -0.043190 -0.013113 +v 0.034154 -0.041423 -0.014557 +v 0.034154 -0.041423 -0.017443 +v 0.032386 -0.043190 -0.018887 +v 0.031903 -0.042259 -0.012726 +v 0.030882 -0.041018 -0.012649 +v 0.033422 -0.040741 -0.013728 +v 0.032593 -0.039307 -0.014361 +v 0.034023 -0.040139 -0.016257 +v 0.032807 -0.039092 -0.017012 +v 0.033155 -0.041008 -0.018623 +v 0.031680 -0.040220 -0.018887 +v 0.031178 -0.042985 -0.019276 +v 0.030104 -0.041795 -0.019265 +v 0.028442 -0.043457 -0.017608 +v 0.029750 -0.044412 -0.017858 +v 0.029339 -0.044823 -0.015467 +v 0.028306 -0.043594 -0.015153 +v 0.029077 -0.042822 -0.013406 +v 0.030374 -0.043788 -0.013235 +v 0.030527 -0.041373 -0.012710 +v 0.031676 -0.042486 -0.012730 +v 0.031654 -0.042508 -0.010998 +v 0.030517 -0.041383 -0.010966 +v 0.029749 -0.044413 -0.011783 +v 0.028110 -0.043790 -0.012266 +v 0.028159 -0.046004 -0.014814 +v 0.026983 -0.044916 -0.015680 +v 0.028536 -0.045626 -0.018291 +v 0.027452 -0.044448 -0.018375 +v 0.028932 -0.042967 -0.020540 +v 0.030015 -0.044147 -0.020469 +v 0.032663 -0.041499 -0.020888 +v 0.031589 -0.040311 -0.020831 +v 0.033330 -0.038569 -0.019085 +v 0.034865 -0.039297 -0.018351 +v 0.034080 -0.037820 -0.016535 +v 0.035173 -0.038989 -0.015370 +v 0.033660 -0.038239 -0.013579 +v 0.034229 -0.039933 -0.012368 +v 0.032270 -0.039629 -0.011633 +v 0.031995 -0.042167 -0.011028 +v 0.030858 -0.041041 -0.011050 +v -0.037838 -0.044669 0.020119 +v -0.039066 -0.043423 0.018137 +v -0.037690 -0.044958 0.017443 +v -0.034154 -0.048494 0.017443 +v -0.032686 -0.049810 0.018218 +v -0.033857 -0.048648 0.020150 +v -0.034083 -0.048424 0.011687 +v -0.033053 -0.049430 0.012957 +v -0.034154 -0.048494 0.014557 +v -0.032302 -0.050204 0.015390 +v -0.039331 -0.043181 0.014905 +v -0.037690 -0.044958 0.014557 +v -0.038296 -0.044190 0.012399 +v -0.035922 -0.046726 0.013113 +v -0.035721 -0.046784 0.010999 +v -0.037167 -0.045344 0.011399 +v -0.035922 -0.046726 0.018887 +v -0.035981 -0.046525 0.021037 +v -0.018959 -0.026916 0.014400 +v -0.019299 -0.026573 0.016742 +v -0.015769 -0.030107 0.015257 +v -0.017259 -0.028609 0.013388 +v -0.018112 -0.027763 0.018439 +v -0.016293 -0.029575 0.017974 +v -0.033835 -0.040234 0.016522 +v -0.019853 -0.026726 0.014733 +v -0.033331 -0.040738 0.013949 +v -0.018817 -0.027762 0.013242 +v -0.031613 -0.042456 0.012841 +v -0.017158 -0.029418 0.013089 +v -0.029909 -0.044160 0.013990 +v -0.016042 -0.030540 0.014466 +v -0.015732 -0.030843 0.016508 +v -0.029443 -0.044631 0.015997 +v -0.029934 -0.044135 0.018051 +v -0.016500 -0.030082 0.018306 +v -0.017866 -0.028710 0.019087 +v -0.031652 -0.042417 0.019159 +v -0.019253 -0.027328 0.018335 +v -0.033039 -0.041029 0.018374 +v -0.019969 -0.026610 0.016816 +v -0.035188 -0.039076 0.014911 +v -0.035043 -0.039226 0.017791 +v -0.032377 -0.041893 0.011071 +v -0.034193 -0.040077 0.012392 +v -0.029091 -0.045173 0.019344 +v -0.028226 -0.046043 0.016730 +v -0.032877 -0.041392 0.020744 +v -0.030836 -0.043433 0.020849 +v -0.034164 -0.040101 0.019570 +v -0.030099 -0.044169 0.011508 +v -0.028522 -0.045742 0.013873 +v -0.030618 -0.044958 0.014557 +v -0.030618 -0.044958 0.017443 +v -0.032386 -0.043190 0.013113 +v -0.034154 -0.041423 0.014557 +v -0.034154 -0.041423 0.017443 +v -0.032386 -0.043190 0.018887 +v 0.030752 -0.041147 0.012750 +v 0.031883 -0.042279 0.012743 +v 0.032074 -0.039826 0.013435 +v 0.033522 -0.040640 0.013786 +v 0.032918 -0.038982 0.016046 +v 0.033939 -0.040224 0.017012 +v 0.031916 -0.039983 0.018776 +v 0.032556 -0.041607 0.019114 +v 0.029758 -0.042142 0.019161 +v 0.030388 -0.043774 0.018849 +v 0.028391 -0.043509 0.017322 +v 0.029344 -0.044818 0.016387 +v 0.028472 -0.043428 0.014246 +v 0.030052 -0.044110 0.013470 +v 0.030495 -0.041405 0.012655 +v 0.031676 -0.042487 0.012738 +v 0.030543 -0.041356 0.011030 +v 0.031671 -0.042492 0.011008 +v 0.028930 -0.042969 0.011528 +v 0.029682 -0.044480 0.011813 +v 0.027411 -0.044488 0.013643 +v 0.028109 -0.046053 0.015158 +v 0.027021 -0.044879 0.016348 +v 0.028926 -0.045236 0.019267 +v 0.027675 -0.044224 0.018955 +v 0.029388 -0.042511 0.020748 +v 0.031110 -0.043053 0.020958 +v 0.031157 -0.040742 0.020906 +v 0.033723 -0.040439 0.020224 +v 0.032790 -0.039110 0.019896 +v 0.034138 -0.037761 0.016639 +v 0.035206 -0.038956 0.016793 +v 0.034792 -0.039371 0.013579 +v 0.033405 -0.038494 0.013016 +v 0.033546 -0.040616 0.011777 +v 0.031032 -0.040867 0.010919 +v 0.032013 -0.042150 0.011020 +v 0.034012 -0.048501 0.020270 +v 0.032903 -0.049579 0.018747 +v 0.034154 -0.048494 0.017443 +v 0.032355 -0.050158 0.016728 +v 0.035922 -0.046726 0.018887 +v 0.036814 -0.045682 0.020798 +v 0.035454 -0.047028 0.020948 +v 0.037690 -0.044958 0.017443 +v 0.039127 -0.043355 0.017778 +v 0.038309 -0.044204 0.019601 +v 0.037690 -0.044958 0.014557 +v 0.037635 -0.044870 0.011619 +v 0.039006 -0.043490 0.013782 +v 0.034154 -0.048494 0.014557 +v 0.032685 -0.049814 0.013637 +v 0.035638 -0.046857 0.011019 +v 0.035922 -0.046726 0.013113 +v 0.034169 -0.048337 0.011618 +v 0.039376 -0.043131 0.015888 +v 0.016521 -0.029356 0.018176 +v 0.017805 -0.028063 0.013388 +v 0.015697 -0.030154 0.015142 +v 0.019148 -0.026729 0.014867 +v 0.019470 -0.026621 0.017226 +v 0.018203 -0.027673 0.018392 +v 0.029436 -0.044633 0.015425 +v 0.015734 -0.030845 0.015760 +v 0.016467 -0.030108 0.013653 +v 0.030532 -0.043537 0.013251 +v 0.018058 -0.028522 0.012955 +v 0.032414 -0.041655 0.013041 +v 0.019402 -0.027177 0.013822 +v 0.033638 -0.040428 0.014695 +v 0.020038 -0.026542 0.015708 +v 0.033725 -0.040344 0.017106 +v 0.018817 -0.027762 0.018758 +v 0.032378 -0.041691 0.018977 +v 0.017158 -0.029418 0.018911 +v 0.030499 -0.043570 0.018722 +v 0.016042 -0.030540 0.017534 +v 0.029675 -0.044403 0.017344 +v 0.028796 -0.045477 0.013251 +v 0.028160 -0.046107 0.016000 +v 0.030110 -0.044154 0.011544 +v 0.034000 -0.040270 0.019853 +v 0.035218 -0.039050 0.017098 +v 0.030112 -0.044157 0.020458 +v 0.032117 -0.042147 0.020981 +v 0.028793 -0.045471 0.018748 +v 0.034000 -0.040270 0.012147 +v 0.032120 -0.042149 0.011018 +v 0.035019 -0.039245 0.014221 +v 0.034154 -0.041423 0.014557 +v 0.034154 -0.041423 0.017443 +v 0.032386 -0.043190 0.013113 +v 0.030618 -0.044958 0.014557 +v 0.030618 -0.044958 0.017443 +v 0.032386 -0.043190 0.018887 +v -0.031903 -0.042259 0.012726 +v -0.030752 -0.041147 0.012743 +v -0.032019 -0.039881 0.013407 +v -0.033184 -0.040979 0.013476 +v -0.034069 -0.040093 0.015832 +v -0.032962 -0.038937 0.016186 +v -0.032935 -0.041228 0.018923 +v -0.031814 -0.040085 0.018801 +v -0.030104 -0.041795 0.019265 +v -0.030471 -0.043691 0.018921 +v -0.028442 -0.043457 0.017608 +v -0.029357 -0.044805 0.016516 +v -0.028306 -0.043594 0.015153 +v -0.029743 -0.044420 0.014115 +v -0.029077 -0.042822 0.013406 +v -0.031553 -0.042610 0.012620 +v -0.030527 -0.041373 0.012710 +v -0.031654 -0.042508 0.010998 +v -0.030539 -0.041360 0.011008 +v -0.028231 -0.043668 0.012068 +v -0.030079 -0.044083 0.011562 +v -0.028400 -0.045762 0.013834 +v -0.026931 -0.044968 0.016194 +v -0.028464 -0.045698 0.018350 +v -0.028449 -0.043451 0.020169 +v -0.031033 -0.043129 0.021036 +v -0.031056 -0.040843 0.020972 +v -0.033630 -0.040532 0.020197 +v -0.033119 -0.038781 0.019506 +v -0.034799 -0.039363 0.018312 +v -0.034080 -0.037820 0.016535 +v -0.035230 -0.038932 0.015867 +v -0.033419 -0.038481 0.012884 +v -0.034537 -0.039626 0.013016 +v -0.032164 -0.041998 0.010919 +v -0.030939 -0.040961 0.010990 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn -0.1801 -0.9833 0.0261 +vn -0.1010 -0.9949 0.0018 +vn -0.0804 -0.9967 -0.0108 +vn -0.0747 -0.9970 0.0197 +vn -0.1796 -0.9837 -0.0126 +vn 0.0045 -0.9980 0.0629 +vn -0.0669 -0.9977 -0.0096 +vn 0.0026 -0.9832 0.1825 +vn -0.1552 -0.9588 0.2380 +vn 0.0944 -0.9776 0.1880 +vn 0.0688 -0.9976 -0.0032 +vn 0.0907 -0.9959 0.0035 +vn 0.1471 -0.9889 0.0207 +vn 0.0577 -0.9983 -0.0111 +vn 0.1814 -0.9833 -0.0152 +vn -0.0048 -0.9968 -0.0800 +vn 0.0750 -0.9972 0.0013 +vn -0.0157 -0.9839 -0.1782 +vn 0.1082 -0.9756 -0.1910 +vn -0.1034 -0.9818 -0.1594 +vn -0.0717 -0.9974 0.0065 +vn -0.2580 -0.9542 0.1514 +vn -0.2261 -0.9736 -0.0301 +vn -0.2017 -0.9793 0.0165 +vn -0.2351 -0.9700 0.0619 +vn -0.3375 -0.9413 0.0045 +vn -0.2074 -0.9530 -0.2209 +vn -0.2874 -0.9459 -0.1506 +vn 0.1234 -0.9923 0.0057 +vn 0.2245 -0.9733 0.0471 +vn 0.2596 -0.9489 -0.1793 +vn 0.1885 -0.9821 -0.0015 +vn 0.2346 -0.9709 -0.0490 +vn 0.2497 -0.9471 0.2015 +vn 0.2353 -0.9612 -0.1441 +vn 0.0975 -0.9851 0.1420 +vn 0.1248 -0.9796 -0.1577 +vn 0.0020 -0.9372 0.3487 +vn -0.1980 -0.9704 0.1384 +vn -0.0417 -0.9931 -0.1100 +vn -0.1341 -0.9777 0.1614 +vn -0.2373 -0.9622 -0.1335 +vn -0.0930 -0.9163 -0.3895 +vn -0.3855 -0.9227 -0.0028 +vn -0.5022 -0.8647 -0.0016 +vn -0.5410 -0.8410 0.0014 +vn -0.5636 -0.8261 -0.0003 +vn 0.1700 -0.8116 -0.5589 +vn 0.0261 -0.8277 -0.5605 +vn -0.1640 -0.8168 -0.5531 +vn 0.1091 -0.9151 -0.3881 +vn 0.1854 -0.9446 -0.2709 +vn 0.4767 -0.8789 -0.0139 +vn 0.4838 -0.8752 0.0011 +vn 0.4614 -0.8872 -0.0044 +vn 0.5751 -0.8181 -0.0006 +vn 0.0289 -0.9129 0.4071 +vn -0.0426 -0.8162 0.5762 +vn -0.1709 -0.8144 0.5546 +vn 0.2278 -0.7819 0.5803 +vn 0.2196 -0.9466 0.2361 +vn 0.1126 -0.8243 0.5549 +vn -0.9843 -0.1765 0.0105 +vn -0.9848 -0.1693 -0.0378 +vn -0.9682 -0.0981 -0.2302 +vn -0.9415 -0.3369 0.0012 +vn -0.9616 -0.2622 0.0811 +vn -0.9814 -0.1822 0.0601 +vn -0.9287 -0.0768 -0.3627 +vn -0.0004 -0.0006 1.0000 +vn -0.0010 -0.0017 1.0000 +vn 0.0033 -0.0073 1.0000 +vn 0.0034 -0.0058 1.0000 +vn -0.0631 -0.1283 0.9897 +vn 0.0032 -0.0109 0.9999 +vn -0.1716 -0.2516 0.9525 +vn 0.0004 -0.0004 1.0000 +vn -0.0071 -0.0032 1.0000 +vn -0.0002 -0.0064 1.0000 +vn 0.0933 -0.1634 0.9821 +vn 0.0131 -0.0102 0.9999 +vn 0.1411 -0.2389 0.9607 +vn 0.3047 -0.5104 0.8041 +vn 0.3600 -0.7057 0.6102 +vn 0.3546 -0.6349 0.6864 +vn 0.2071 -0.7121 0.6708 +vn 0.2763 -0.6961 0.6626 +vn 0.1445 -0.7994 0.5832 +vn 0.1490 -0.7661 0.6252 +vn -0.0940 0.0499 0.9943 +vn 0.0203 -0.3641 0.9311 +vn 0.1690 0.0241 0.9853 +vn -0.2425 -0.7072 0.6641 +vn -0.1795 -0.6595 0.7299 +vn -0.0619 -0.7907 0.6091 +vn -0.0436 -0.8102 0.5845 +vn -0.3702 -0.6954 0.6159 +vn -0.3902 -0.6967 0.6019 +vn -0.3071 -0.6974 0.6476 +vn -0.4252 -0.6845 0.5922 +vn -0.8191 -0.5431 0.1847 +vn -0.6963 -0.6934 0.1852 +vn -0.8168 -0.5659 0.1121 +vn -0.7176 -0.6938 0.0604 +vn -0.8502 -0.5265 0.0065 +vn -0.7159 -0.6947 -0.0698 +vn -0.8220 -0.5655 -0.0666 +vn -0.6974 -0.6923 -0.1855 +vn -0.8431 -0.5180 -0.1446 +vn -0.8478 -0.4935 -0.1940 +vn -0.8509 -0.0033 0.5254 +vn -0.7952 0.0045 0.6063 +vn -0.8367 0.0254 0.5470 +vn -0.9319 -0.0390 0.3607 +vn -0.8800 0.0168 0.4747 +vn -0.9633 0.0248 0.2672 +vn -0.9871 -0.0190 0.1591 +vn -0.9972 0.0286 0.0686 +vn -0.9983 -0.0102 -0.0574 +vn -0.9917 0.0152 -0.1274 +vn -0.9487 -0.0342 -0.3143 +vn -0.9729 0.0074 -0.2312 +vn -0.8699 0.0163 -0.4930 +vn -0.9018 0.0242 -0.4316 +vn -0.7851 0.0086 -0.6194 +vn -0.8368 0.0016 -0.5476 +vn -0.6787 0.0141 -0.7343 +vn -0.7177 0.0137 -0.6962 +vn -0.7499 -0.0078 -0.6615 +vn -0.7924 -0.0086 -0.6100 +vn -0.6070 -0.0383 -0.7938 +vn -0.4698 -0.0069 -0.8828 +vn -0.4533 -0.0077 -0.8913 +vn -0.2682 -0.0041 -0.9634 +vn -0.2590 -0.0018 -0.9659 +vn -0.0088 0.0033 -1.0000 +vn -0.0295 -0.0062 -0.9995 +vn 0.3239 -0.0889 -0.9419 +vn 0.1718 -0.3438 -0.9232 +vn 0.4394 -0.3236 -0.8380 +vn 0.5911 -0.0423 -0.8055 +vn 0.7889 0.0154 -0.6144 +vn 0.7031 0.0091 -0.7110 +vn 0.6751 0.0304 -0.7371 +vn 0.8397 -0.0091 -0.5429 +vn 0.7913 -0.0188 -0.6112 +vn 0.7427 -0.0163 -0.6694 +vn 0.9268 -0.0243 -0.3747 +vn 0.9003 0.0165 -0.4351 +vn 0.9255 -0.1001 -0.3654 +vn 0.9420 -0.0545 -0.3312 +vn 0.8597 0.0026 -0.5107 +vn 0.9748 0.0041 -0.2229 +vn 0.9807 0.0035 -0.1955 +vn 1.0000 0.0034 0.0075 +vn 1.0000 -0.0027 0.0076 +vn 0.9614 -0.0005 0.2751 +vn 0.9754 0.0067 0.2205 +vn 0.8721 0.0212 0.4889 +vn 0.9056 0.0185 0.4237 +vn 0.9375 -0.0759 0.3395 +vn 0.8298 0.0092 0.5581 +vn 0.9709 -0.0915 0.2211 +vn 0.7933 0.0004 0.6089 +vn 0.7589 0.0146 0.6511 +vn 0.6710 0.0219 0.7411 +vn 0.5947 -0.0232 0.8036 +vn 0.6965 0.0053 0.7176 +vn 0.7470 -0.0106 0.6647 +vn 0.5036 0.0657 0.8614 +vn 0.3710 -0.0185 0.9284 +vn 0.3047 -0.0107 0.9524 +vn 0.0538 -0.0647 0.9965 +vn -0.2152 -0.0147 0.9765 +vn -0.4678 -0.0762 0.8806 +vn -0.3272 0.0856 0.9411 +vn -0.5765 0.0110 0.8170 +vn -0.7127 0.0295 0.7009 +vn -0.6475 0.0397 0.7611 +vn -0.7526 0.0013 0.6585 +vn -0.6670 0.0030 0.7451 +vn -0.2265 -0.9740 -0.0015 +vn -0.2788 -0.9600 0.0274 +vn -0.2718 -0.9623 0.0105 +vn 0.2224 -0.9749 -0.0007 +vn 0.2775 -0.9596 0.0462 +vn 0.2818 -0.9570 0.0695 +vn 0.1744 -0.9846 0.0082 +vn 0.0778 -0.9969 0.0074 +vn 0.0993 -0.9951 -0.0025 +vn -0.0286 -0.9996 -0.0024 +vn -0.0827 -0.9965 0.0083 +vn -0.1598 -0.9871 0.0036 +vn -0.2438 -0.3690 0.8969 +vn -0.1762 -0.3313 0.9269 +vn -0.8079 -0.5893 0.0040 +vn -0.7446 -0.6675 -0.0025 +vn 0.0800 -0.5736 0.8152 +vn -0.1118 -0.5985 0.7933 +vn 0.0138 -0.5282 0.8490 +vn 0.1307 -0.6761 0.7251 +vn -0.0033 -0.5944 0.8041 +vn -0.3389 -0.6175 0.7098 +vn -0.3073 -0.5353 0.7868 +vn -0.5157 -0.5030 0.6935 +vn -0.5196 -0.5025 0.6910 +vn -0.0139 -0.3416 0.9397 +vn -0.1002 -0.3702 0.9235 +vn -0.0320 -0.1536 -0.9876 +vn 0.0002 0.0000 -1.0000 +vn -0.0073 -0.0082 -0.9999 +vn 0.1849 -0.3774 -0.9074 +vn 0.0985 -0.1784 -0.9790 +vn 0.0048 -0.0209 -0.9998 +vn 0.1574 -0.2571 -0.9535 +vn 0.0200 -0.1709 -0.9851 +vn -0.0003 -0.0001 -1.0000 +vn 0.0071 -0.0032 -1.0000 +vn 0.0428 -0.1450 -0.9885 +vn -0.0938 -0.1657 -0.9817 +vn -0.0148 -0.0105 -0.9998 +vn -0.1429 -0.2426 -0.9596 +vn -0.1471 -0.7320 -0.6652 +vn -0.2592 -0.6822 -0.6837 +vn -0.3316 -0.7061 -0.6256 +vn -0.3560 -0.6238 -0.6958 +vn -0.2999 -0.5044 -0.8097 +vn -0.0034 -0.7053 -0.7089 +vn -0.0227 -0.7066 -0.7072 +vn 0.2186 -0.6820 -0.6979 +vn 0.3530 -0.6453 -0.6774 +vn 0.3152 -0.5146 -0.7974 +vn 0.2273 -0.9738 0.0033 +vn 0.2787 -0.9600 -0.0268 +vn 0.2716 -0.9624 -0.0088 +vn -0.2228 -0.9747 0.0191 +vn -0.2672 -0.9636 -0.0070 +vn -0.2783 -0.9599 -0.0330 +vn -0.1223 -0.9925 0.0042 +vn -0.0757 -0.9971 -0.0085 +vn 0.0121 -0.9999 0.0055 +vn 0.0795 -0.9968 -0.0075 +vn 0.1470 -0.9891 -0.0029 +vn -0.0750 -0.5727 -0.8163 +vn 0.1394 -0.5713 -0.8088 +vn 0.0394 -0.5450 -0.8375 +vn -0.0474 -0.5714 -0.8193 +vn -0.0197 -0.5986 -0.8008 +vn -0.4111 -0.5768 -0.7059 +vn -0.4719 -0.5216 -0.7108 +vn -0.4992 -0.5013 -0.7067 +vn -0.4987 -0.5013 -0.7071 +vn 0.9851 -0.1695 -0.0277 +vn 0.9846 -0.1746 0.0093 +vn 0.9787 -0.2052 -0.0034 +vn 0.9855 -0.1593 0.0591 +vn 0.7095 -0.6906 -0.1404 +vn 0.8312 -0.5352 -0.1508 +vn 0.7490 -0.6246 -0.2212 +vn 0.8388 -0.5436 -0.0298 +vn 0.7216 -0.6923 0.0042 +vn 0.8388 -0.5393 0.0750 +vn 0.6996 -0.6946 0.1675 +vn 0.8153 -0.5597 0.1486 +vn 0.8659 -0.4717 0.1664 +vn 0.8135 -0.5816 -0.0049 +vn 0.7934 -0.6087 0.0033 +vn 0.3680 -0.6018 0.7088 +vn 0.4735 -0.5220 0.7094 +vn 0.4988 -0.5053 0.7041 +vn 0.4996 -0.5006 0.7070 +vn 0.4150 -0.5766 -0.7037 +vn 0.5055 -0.5001 -0.7031 +vn 0.5064 -0.4918 -0.7083 +vn -0.0000 1.0000 -0.0000 +vn -0.0000 1.0000 -0.0002 +vn 0.0001 1.0000 -0.0007 +vn -0.0000 1.0000 -0.0003 +vn -0.0000 1.0000 0.0003 +vn -0.0000 1.0000 0.0002 +vn 0.0000 1.0000 -0.0001 +vn 0.0000 1.0000 0.0001 +vn -0.7053 -0.7083 0.0288 +vn 0.7054 -0.7085 0.0205 +vn 0.6991 -0.7140 -0.0385 +vn 0.0000 0.0000 -1.0000 +vn 0.0025 0.0013 -1.0000 +vn 0.1018 0.0857 -0.9911 +vn 0.0096 0.2624 -0.9649 +vn 0.0012 0.0340 -0.9994 +vn 0.0497 0.2362 -0.9704 +vn -0.0318 0.0325 -0.9990 +vn 0.0000 0.0005 -1.0000 +vn -0.0208 0.0410 -0.9989 +vn 0.0227 -0.0127 -0.9997 +vn -0.0329 0.0392 -0.9987 +vn 0.0000 0.0000 1.0000 +vn 0.0001 0.0020 1.0000 +vn 0.0617 0.0624 0.9961 +vn -0.0287 -0.0319 0.9991 +vn -0.0008 0.0047 1.0000 +vn -0.0002 0.0020 1.0000 +vn -0.0866 -0.1151 0.9896 +vn 0.0060 0.0105 0.9999 +vn 0.0011 0.0067 1.0000 +vn -0.0033 0.0076 1.0000 +vn 0.0508 -0.0604 0.9969 +vn -0.0714 0.0694 0.9950 +vn 0.1458 -0.1908 0.9707 +vn 0.7071 0.7071 0.0000 +vn 0.6933 0.7205 0.0134 +vn 0.6703 0.7421 0.0024 +vn 0.7062 0.7080 -0.0005 +vn 0.5522 0.8257 -0.1151 +vn 0.7003 0.7135 0.0190 +vn 0.6952 0.7180 0.0337 +vn 0.4423 0.8715 0.2119 +vn 0.7002 0.7136 0.0207 +vn 0.7051 0.7091 -0.0029 +vn 0.7017 0.7125 -0.0053 +vn 0.6770 0.7360 0.0013 +vn 0.6103 0.7799 -0.1387 +vn 0.7050 0.7092 -0.0047 +vn -0.8337 0.5422 0.1048 +vn -0.9612 0.2759 0.0000 +vn -0.8845 0.4567 -0.0958 +vn -0.9187 0.3941 -0.0250 +vn -0.9829 0.1840 0.0015 +vn -0.9812 0.1932 -0.0007 +vn -0.9185 0.3947 -0.0242 +vn -0.9613 0.2756 -0.0006 +vn -0.9612 0.2760 0.0000 +vn -0.8853 0.4649 -0.0028 +vn -0.8848 0.4561 -0.0956 +vn -0.9612 0.2759 0.0004 +vn -0.9613 0.2754 0.0010 +vn -0.9612 0.2758 -0.0005 +vn -0.9612 0.2760 0.0002 +vn -0.9612 0.2759 -0.0001 +vn -0.9611 0.2762 0.0000 +vn -0.9612 0.2759 -0.0003 +vn -0.6572 0.6973 0.2862 +vn -0.7106 0.7036 -0.0058 +vn 0.2314 0.8463 -0.4798 +vn 0.2576 0.9209 -0.2926 +vn -0.1214 0.8492 -0.5139 +vn -0.0702 0.8686 0.4905 +vn -0.0548 0.7788 0.6248 +vn 0.0864 0.8322 0.5477 +vn 0.8868 0.4621 0.0027 +vn 0.8337 0.5422 -0.1047 +vn 0.7106 0.7036 0.0058 +vn 0.6573 0.6972 -0.2861 +vn 0.9614 0.2752 -0.0006 +vn 0.9614 0.2752 -0.0001 +vn 0.9830 0.1839 -0.0015 +vn 0.9812 0.1930 0.0007 +vn 0.8848 0.4561 0.0957 +vn 0.9185 0.3947 0.0242 +vn 0.9612 0.2759 -0.0000 +vn 0.9612 0.2758 0.0001 +vn 0.9613 0.2754 -0.0010 +vn 0.9612 0.2759 -0.0001 +vn 0.9612 0.2758 -0.0003 +vn 0.9613 0.2756 0.0005 +vn 0.9612 0.2759 -0.0002 +vn 0.9612 0.2758 -0.0002 +vn 0.9612 0.2760 -0.0000 +vn 0.9612 0.2758 0.0000 +vn -0.0106 -0.9999 -0.0018 +vn -0.1995 -0.9799 0.0015 +vn -0.2180 -0.9759 -0.0016 +vn -0.4019 -0.9157 0.0015 +vn -0.4190 -0.9080 -0.0015 +vn -0.5852 -0.8109 0.0015 +vn -0.6002 -0.7998 -0.0015 +vn -0.7423 -0.6700 0.0015 +vn -0.7547 -0.6560 -0.0015 +vn -0.8664 -0.4993 0.0015 +vn -0.8756 -0.4830 -0.0015 +vn -0.9543 -0.2989 0.0017 +vn -0.9602 -0.2793 -0.0021 +vn -0.9987 -0.0505 0.0022 +vn -0.9996 -0.0282 -0.0019 +vn 0.0100 -0.9999 0.0015 +vn 0.1988 -0.9800 -0.0018 +vn 0.2185 -0.9758 0.0015 +vn 0.4019 -0.9157 -0.0015 +vn 0.4190 -0.9080 0.0015 +vn 0.5851 -0.8109 -0.0015 +vn 0.6002 -0.7998 0.0015 +vn 0.7423 -0.6701 -0.0015 +vn 0.7548 -0.6560 0.0015 +vn 0.8664 -0.4993 -0.0015 +vn 0.8756 -0.4830 0.0015 +vn 0.9543 -0.2989 -0.0017 +vn 0.9602 -0.2794 0.0021 +vn 0.9987 -0.0505 -0.0022 +vn 0.9996 -0.0283 0.0019 +vn -0.6937 0.7202 -0.0073 +vn -0.6718 0.7407 0.0008 +vn -0.4354 0.8747 -0.2130 +vn -0.5497 0.8275 0.1145 +vn -0.7010 0.7132 0.0075 +vn -0.6051 0.7827 0.1458 +vn -0.6784 0.7347 0.0011 +vn -0.7053 0.7089 0.0046 +vn -0.7049 0.7093 0.0030 +vn -0.7071 0.7071 0.0000 +vn -0.7004 0.7137 -0.0084 +vn -0.7044 0.7098 -0.0011 +vn -0.7040 0.7102 -0.0034 +vn -0.7050 0.7092 -0.0048 +vn 0.1710 0.9697 -0.1744 +vn -0.0737 0.9856 0.1524 +vn 0.2185 0.9578 0.1865 +vn -0.1784 0.9709 -0.1594 +vn -0.2564 0.9205 0.2950 +vn 0.2707 0.8911 -0.3642 +vn 0.2316 0.8998 0.3697 +vn 0.1951 0.9808 -0.0023 +vn 0.0987 0.9951 -0.0025 +vn 0.1145 0.9934 0.0004 +vn -0.0017 1.0000 -0.0002 +vn 0.0016 1.0000 0.0002 +vn -0.1145 0.9934 -0.0004 +vn -0.0986 0.9951 0.0025 +vn -0.2323 0.9003 -0.3680 +vn -0.1952 0.9808 0.0023 +vn -0.2707 0.8906 0.3654 +vn -0.2176 0.9567 -0.1936 +vn -0.1711 0.9697 0.1743 +vn -0.7733 -0.6294 -0.0762 +vn -0.6651 -0.6610 -0.3476 +vn -0.7040 -0.6849 -0.1876 +vn 0.5882 0.5721 -0.5716 +vn 0.6196 0.6297 -0.4686 +vn 0.6224 0.6353 -0.4571 +vn 0.5831 0.5635 -0.5852 +vn 0.2399 0.2608 -0.9351 +vn 0.2302 0.2417 -0.9427 +vn 0.1503 0.1724 -0.9735 +vn 0.0854 0.0745 -0.9936 +vn -0.2700 -0.2977 -0.9157 +vn -0.4402 -0.4018 -0.8030 +vn -0.5535 -0.6127 -0.5641 +vn -0.5999 -0.6581 0.4549 +vn -0.5807 -0.6852 0.4396 +vn -0.5479 -0.7272 0.4135 +vn 0.2127 0.2003 0.9564 +vn 0.2589 0.2830 0.9235 +vn 0.2530 0.2723 0.9284 +vn 0.2015 0.1806 0.9627 +vn -0.2382 -0.2394 0.9412 +vn -0.2662 -0.2525 0.9303 +vn -0.2540 -0.2468 0.9352 +vn -0.3068 -0.2711 0.9124 +vn -0.6207 -0.6264 0.4715 +vn 0.6700 0.6590 0.3417 +vn 0.6049 0.6081 0.5141 +vn 0.5741 0.5587 0.5986 +vn 0.7099 0.7018 0.0589 +vn -0.6799 -0.7231 -0.1220 +vn -0.6904 -0.6803 -0.2461 +vn -0.6837 -0.7134 -0.1537 +vn -0.6912 -0.6649 -0.2829 +vn -0.3537 -0.3536 -0.8659 +vn -0.3532 -0.3534 -0.8662 +vn -0.3534 -0.3535 -0.8661 +vn -0.3539 -0.3537 -0.8658 +vn 0.2424 0.2137 -0.9463 +vn 0.2783 0.3090 -0.9094 +vn 0.2563 0.2500 -0.9337 +vn 0.2903 0.3417 -0.8938 +vn 0.7082 0.6755 -0.2056 +vn 0.6994 0.7001 -0.1441 +vn 0.7057 0.6838 -0.1857 +vn 0.6956 0.7079 -0.1223 +vn 0.5944 0.5839 0.5529 +vn 0.5374 0.5649 0.6261 +vn 0.5783 0.5789 0.5749 +vn 0.5230 0.5596 0.6429 +vn 0.1687 0.1052 0.9800 +vn -0.0499 -0.0014 0.9988 +vn 0.0903 0.0671 0.9937 +vn -0.1238 -0.0378 0.9916 +vn -0.4932 -0.5591 0.6665 +vn -0.6156 -0.5998 0.5111 +vn -0.5331 -0.5742 0.6214 +vn -0.6512 -0.6081 0.4540 +vn 0.7072 -0.7071 0.0002 +vn 0.7073 -0.7070 0.0003 +vn 0.7071 -0.7071 0.0001 +vn 0.7072 -0.7070 0.0000 +vn 0.7072 -0.7071 0.0000 +vn 0.7070 -0.7072 0.0000 +vn 0.7069 -0.7073 -0.0000 +vn 0.7069 -0.7073 -0.0002 +vn 0.7070 -0.7072 -0.0001 +vn 0.7071 -0.7071 0.0000 +vn 0.7072 -0.7070 0.0003 +vn 0.7071 -0.7071 -0.0001 +vn 0.7072 -0.7070 -0.0002 +vn -0.7005 -0.6806 0.2149 +vn -0.6514 -0.6653 -0.3648 +vn -0.6757 -0.7295 -0.1061 +vn 0.6950 0.7083 -0.1233 +vn 0.7015 0.6836 0.2017 +vn 0.6505 0.6351 -0.4164 +vn 0.6184 0.6303 -0.4693 +vn 0.5559 0.5403 -0.6318 +vn 0.2102 0.2028 -0.9564 +vn 0.2355 0.2521 -0.9386 +vn 0.2020 0.1869 -0.9614 +vn -0.2916 -0.2898 -0.9116 +vn -0.2921 -0.2900 -0.9114 +vn -0.2918 -0.2899 -0.9115 +vn -0.2904 -0.2893 -0.9121 +vn -0.6035 -0.6583 -0.4500 +vn -0.6255 -0.6057 -0.4919 +vn -0.6192 -0.6527 0.4367 +vn 0.2124 0.1999 0.9565 +vn 0.2589 0.2829 0.9236 +vn 0.2529 0.2722 0.9284 +vn -0.2162 -0.2185 0.9516 +vn -0.2698 -0.2462 0.9309 +vn -0.3910 -0.4070 0.8255 +vn -0.4229 -0.3799 0.8227 +vn 0.6133 0.6065 0.5059 +vn 0.6006 0.5809 0.5494 +vn 0.6822 0.6911 0.2386 +vn -0.5633 -0.5382 -0.6269 +vn -0.5639 -0.5425 -0.6227 +vn -0.5635 -0.5400 -0.6252 +vn -0.5640 -0.5441 -0.6211 +vn 0.1522 0.1321 -0.9795 +vn 0.1728 0.1954 -0.9654 +vn 0.1617 0.1611 -0.9736 +vn 0.1815 0.2224 -0.9579 +vn 0.6953 0.6465 -0.3140 +vn 0.6849 0.7020 -0.1953 +vn 0.6931 0.6670 -0.2733 +vn 0.6785 0.7185 -0.1532 +vn 0.6127 0.5892 0.5267 +vn 0.5592 0.5726 0.5995 +vn 0.5986 0.5851 0.5470 +vn 0.5438 0.5672 0.6185 +vn 0.2161 0.1837 0.9589 +vn 0.0104 0.0635 0.9979 +vn -0.0383 -0.0772 0.9963 +vn -0.0948 -0.0552 0.9940 +vn -0.2813 -0.3597 0.8897 +vn -0.6823 -0.6875 0.2485 +vn -0.6824 -0.5944 0.4255 +vn -0.6854 -0.6281 0.3684 +vn -0.6745 -0.7175 0.1739 +vn 0.7069 -0.7073 -0.0001 +vn 0.7072 -0.7071 -0.0001 +vn 0.7069 -0.7073 0.0002 +vn 0.1772 0.9710 0.1604 +vn 0.0733 0.9853 -0.1546 +vn -0.6854 0.6680 -0.2897 +vn -0.6714 0.7408 -0.0205 +vn -0.6160 0.6649 -0.4224 +vn -0.5327 0.4932 -0.6877 +vn -0.2057 0.2450 -0.9474 +vn -0.0302 -0.0138 -0.9994 +vn 0.3351 -0.2938 -0.8952 +vn 0.5035 -0.5530 -0.6638 +vn 0.6912 -0.6493 -0.3171 +vn 0.6749 -0.7226 0.1497 +vn 0.6478 -0.5985 0.4713 +vn 0.5465 -0.5681 0.6153 +vn 0.4694 -0.4028 0.7858 +vn -0.0120 -0.0847 0.9963 +vn -0.2540 0.3769 0.8907 +vn -0.6598 0.5599 0.5011 +vn -0.7071 -0.7071 -0.0001 +vn -0.7071 -0.7071 -0.0003 +vn -0.7070 -0.7072 0.0001 +vn -0.7071 -0.7071 0.0000 +vn -0.7070 -0.7072 -0.0002 +vn -0.7069 -0.7073 -0.0002 +vn -0.7069 -0.7073 -0.0001 +vn -0.7069 -0.7073 0.0000 +vn -0.7070 -0.7072 0.0002 +vn 0.7005 -0.6805 -0.2148 +vn 0.6634 -0.6588 0.3547 +vn 0.6805 -0.7263 0.0969 +vn -0.5986 0.5807 0.5518 +vn -0.6222 0.6289 0.4661 +vn -0.6246 0.6343 0.4555 +vn -0.5947 0.5733 0.5637 +vn -0.2399 0.2608 0.9351 +vn -0.1994 0.1819 0.9629 +vn -0.2332 0.2477 0.9404 +vn -0.1882 0.1603 0.9690 +vn 0.3268 -0.2964 0.8974 +vn 0.3316 -0.3498 0.8762 +vn 0.3293 -0.3224 0.8875 +vn 0.3344 -0.3890 0.8584 +vn 0.6173 -0.6585 0.4305 +vn 0.6363 -0.6015 0.4831 +vn 0.6193 -0.6524 -0.4368 +vn -0.5873 0.5664 -0.5781 +vn -0.5551 0.5677 -0.6079 +vn -0.3688 0.3552 -0.8590 +vn -0.2587 0.2830 -0.9236 +vn 0.1643 -0.1913 -0.9677 +vn 0.2332 -0.2273 -0.9455 +vn 0.3717 -0.3983 -0.8386 +vn 0.4229 -0.3799 -0.8227 +vn -0.7009 0.6811 -0.2120 +vn -0.6476 0.6211 -0.4414 +vn -0.6475 0.6808 -0.3423 +vn -0.6485 0.6614 -0.3768 +vn -0.6458 0.6004 -0.4717 +vn -0.1245 0.1496 -0.9809 +vn -0.2021 0.1750 -0.9636 +vn -0.1506 0.1582 -0.9759 +vn -0.2298 0.1838 -0.9557 +vn 0.4732 -0.5081 -0.7196 +vn 0.4083 -0.3374 -0.8482 +vn 0.4333 -0.3982 -0.8085 +vn 0.4904 -0.5616 -0.6664 +vn 0.7244 -0.6785 0.1219 +vn 0.7098 -0.7010 0.0690 +vn 0.7192 -0.6873 0.1020 +vn 0.7045 -0.7078 0.0517 +vn 0.3759 -0.3832 0.8437 +vn 0.4166 -0.4000 0.8163 +vn 0.4053 -0.3954 0.8243 +vn 0.3640 -0.3783 0.8511 +vn -0.0852 0.0888 0.9924 +vn -0.1043 0.1274 0.9863 +vn -0.0909 0.1003 0.9908 +vn -0.1091 0.1372 0.9845 +vn -0.6165 0.5694 0.5438 +vn -0.6217 0.6189 0.4800 +vn -0.6187 0.5865 0.5228 +vn -0.6226 0.6370 0.4545 +vn -0.7070 -0.7072 -0.0000 +vn -0.7072 -0.7070 0.0002 +vn -0.7072 -0.7070 0.0003 +vn -0.7071 -0.7071 0.0001 +vn -0.7070 -0.7072 -0.0001 +vn -0.7072 -0.7071 0.0002 +vn -0.7071 -0.7071 0.0002 +vn 0.7733 -0.6294 0.0762 +vn 0.6523 -0.6700 0.3544 +vn 0.6952 -0.6904 0.2001 +vn -0.5800 0.5582 0.5933 +vn -0.6186 0.6278 0.4725 +vn -0.6224 0.6353 0.4571 +vn -0.5736 0.5475 0.6093 +vn -0.2229 0.2570 0.9404 +vn -0.1391 0.1096 0.9842 +vn -0.2096 0.2333 0.9496 +vn -0.1176 0.0721 0.9904 +vn 0.3399 -0.2990 0.8917 +vn 0.3501 -0.3634 0.8633 +vn 0.4165 -0.3942 0.8193 +vn 0.5137 -0.5726 0.6389 +vn 0.5998 -0.6583 -0.4548 +vn 0.5807 -0.6853 -0.4395 +vn 0.5479 -0.7272 -0.4135 +vn -0.2127 0.2003 -0.9564 +vn -0.2589 0.2829 -0.9236 +vn -0.2529 0.2722 -0.9284 +vn -0.2015 0.1806 -0.9627 +vn 0.2382 -0.2394 -0.9412 +vn 0.2661 -0.2524 -0.9303 +vn 0.2540 -0.2468 -0.9352 +vn 0.3065 -0.2709 -0.9125 +vn 0.6206 -0.6266 -0.4714 +vn -0.6701 0.6590 -0.3417 +vn -0.6049 0.6080 -0.5141 +vn -0.5741 0.5587 -0.5986 +vn -0.7099 0.7018 -0.0589 +vn -0.0612 0.7904 -0.6095 +vn 0.1001 0.7599 -0.6422 +vn 0.0705 0.8690 -0.4898 +vn 0.1877 0.7129 -0.6757 +vn 0.1432 0.7246 -0.6741 +vn 0.0884 0.7405 -0.6662 +vn 0.0730 0.7393 -0.6694 +vn -0.0038 0.7398 -0.6729 +vn -0.0009 0.7383 -0.6745 +vn -0.1097 0.7075 -0.6982 +vn -0.0817 0.7226 -0.6864 +vn -0.1861 0.7069 -0.6824 +vn -0.1063 0.7792 0.6177 +vn -0.1891 0.7106 0.6777 +vn -0.1450 0.7207 0.6779 +vn -0.0556 0.7255 0.6860 +vn -0.0685 0.7267 0.6836 +vn 0.0522 0.7364 0.6745 +vn -0.0111 0.7489 0.6626 +vn 0.0933 0.7292 0.6779 +vn 0.1781 0.7150 0.6760 +vn -0.0880 0.8173 0.5695 +vn 0.1239 0.8497 0.5126 +vn -0.1124 0.7967 -0.5938 +vn -0.0034 0.7911 0.6116 +vn 0.1035 0.6754 -0.7302 +vn 0.0063 0.6103 -0.7921 +vn -0.2455 0.8518 -0.4628 +vn -0.3484 0.8498 -0.3955 +vn -0.1902 0.5852 -0.7883 +vn 0.1431 0.1504 -0.9782 +vn 0.4171 0.4542 -0.7872 +vn 0.5240 0.4921 -0.6951 +vn 0.4190 0.4373 0.7958 +vn 0.5620 0.5901 0.5796 +vn 0.5610 0.5930 0.5776 +vn 0.4406 0.4191 0.7939 +vn 0.1314 0.1411 0.9812 +vn -0.5690 0.5697 -0.5930 +vn -0.5610 0.5930 -0.5776 +vn -0.5682 0.5721 -0.5914 +vn -0.5735 0.5556 -0.6019 +vn -0.2026 0.1996 -0.9587 +vn -0.2191 0.2351 -0.9469 +vn -0.1258 0.1346 0.9829 +vn -0.4182 0.4531 0.7873 +vn -0.5223 0.4876 0.6996 +vn 0.1232 -0.3019 -0.9453 +vn 0.6082 -0.4119 -0.6786 +vn 0.6311 -0.3136 -0.7094 +vn 0.5592 -0.5552 -0.6157 +vn 0.5107 -0.6563 -0.5554 +vn 0.7168 -0.6484 0.2563 +vn 0.7847 -0.5882 0.1956 +vn 0.6239 -0.7106 0.3253 +vn 0.5438 -0.7506 0.3752 +vn 0.3418 -0.2800 0.8971 +vn 0.4476 -0.2535 0.8576 +vn 0.2187 -0.3046 0.9270 +vn 0.1053 -0.3225 0.9407 +vn -0.3038 0.3714 0.8774 +vn -0.1697 0.4001 0.9006 +vn -0.4823 0.3188 0.8159 +vn -0.5873 0.2786 0.7599 +vn -0.4998 0.8398 0.2117 +vn -0.8600 0.4731 -0.1910 +vn -0.3910 0.6679 -0.6332 +vn -0.3730 0.1689 -0.9123 +vn -0.2881 0.1723 -0.9420 +vn -0.2575 0.1727 -0.9507 +vn -0.1348 0.1742 -0.9754 +vn -0.6965 0.7175 0.0075 +vn -0.6981 0.7160 0.0057 +vn -0.6980 0.7161 0.0059 +vn -0.6991 0.7150 0.0042 +vn 0.1899 -0.1859 0.9640 +vn 0.1758 -0.1897 0.9660 +vn 0.2035 -0.1823 0.9620 +vn 0.2168 -0.1787 0.9597 +vn 0.5174 -0.5464 0.6585 +vn 0.5099 -0.5498 0.6616 +vn 0.5262 -0.5425 0.6549 +vn 0.5344 -0.5387 0.6513 +vn 0.7208 -0.6770 0.1486 +vn 0.7203 -0.6776 0.1482 +vn 0.7073 -0.6868 -0.1676 +vn 0.6896 -0.7223 -0.0520 +vn 0.6026 -0.5708 -0.5578 +vn 0.4630 -0.5395 -0.7033 +vn 0.2992 -0.5453 -0.7830 +vn 0.3646 -0.0375 -0.9304 +vn -0.1864 -0.1288 -0.9740 +vn -0.2195 0.5008 -0.8373 +vn -0.2956 0.4823 -0.8246 +vn -0.4358 0.4383 -0.7861 +vn -0.5244 0.4031 -0.7500 +vn -0.6219 0.7315 -0.2794 +vn -0.6501 0.6964 -0.3041 +vn -0.5914 0.7656 -0.2533 +vn -0.5723 0.7850 -0.2373 +vn -0.7002 0.6275 0.3406 +vn -0.8084 0.5499 0.2101 +vn -0.5801 0.6387 0.5055 +vn -0.4052 0.4377 0.8026 +vn -0.3690 0.3508 0.8607 +vn -0.2261 0.2507 0.9413 +vn -0.2344 0.2485 0.9398 +vn 0.5429 -0.8350 0.0891 +vn 0.6233 -0.7820 -0.0063 +vn 0.6196 -0.7849 -0.0017 +vn 0.6924 -0.7144 -0.1016 +vn 0.7070 0.7072 0.0004 +vn 0.7069 0.7073 0.0002 +vn 0.7071 0.7071 0.0002 +vn 0.7072 0.7070 0.0001 +vn 0.7073 0.7069 -0.0002 +vn 0.7074 0.7068 -0.0002 +vn 0.7071 0.7071 0.0003 +vn 0.7071 0.7071 0.0001 +vn 0.7073 0.7069 0.0001 +vn 0.7073 0.7069 0.0002 +vn 0.7072 0.7071 -0.0002 +vn 0.7071 0.7071 -0.0001 +vn 0.7072 0.7071 0.0000 +vn -0.7072 -0.7070 -0.0001 +vn -0.7074 -0.7068 -0.0002 +vn -0.7069 -0.7074 -0.0002 +vn -0.7072 -0.7071 -0.0003 +vn -0.7072 -0.7071 -0.0002 +vn -0.7069 -0.7073 0.0003 +vn -0.7072 -0.7070 -0.0002 +vn -0.7068 -0.7074 -0.0002 +vn -0.6818 -0.7313 -0.0204 +vn -0.6869 -0.7259 -0.0358 +vn -0.6755 -0.7373 -0.0097 +vn -0.7069 -0.7059 -0.0446 +vn -0.7158 -0.6965 -0.0494 +vn -0.6995 -0.7130 -0.0489 +vn -0.7390 -0.6737 -0.0049 +vn -0.7288 -0.6840 -0.0316 +vn -0.7322 -0.6808 -0.0197 +vn -0.7232 -0.6894 0.0404 +vn -0.7362 -0.6765 0.0189 +vn -0.7323 -0.6806 0.0212 +vn -0.6789 -0.7340 0.0207 +vn -0.6713 -0.7411 0.0113 +vn -0.6937 -0.7191 0.0405 +vn -0.7111 -0.7013 0.0501 +vn -0.7078 -0.7052 0.0420 +vn -0.6772 -0.7352 0.0299 +vn 0.7081 0.7061 -0.0002 +vn 0.7076 0.7066 0.0013 +vn 0.7059 0.7083 -0.0014 +vn 0.6355 0.7717 -0.0248 +vn 0.6213 0.7829 -0.0310 +vn 0.7099 0.7043 -0.0040 +vn 0.5817 -0.5853 0.5649 +vn 0.6566 -0.6306 0.4138 +vn 0.6503 -0.6271 0.4288 +vn 0.5723 -0.5792 0.5805 +vn 0.1075 -0.0926 0.9899 +vn 0.0966 -0.0842 0.9918 +vn 0.0974 -0.0848 0.9916 +vn 0.1086 -0.0934 0.9897 +vn -0.3002 0.2944 0.9073 +vn -0.4626 0.4802 0.7452 +vn -0.4744 0.4683 0.7454 +vn -0.6274 0.6484 0.4312 +vn -0.7059 0.6946 0.1389 +vn -0.6227 0.6830 -0.3817 +vn -0.5455 0.5301 -0.6492 +vn -0.2465 0.3335 -0.9100 +vn -0.0017 -0.0137 -0.9999 +vn 0.0877 -0.0655 -0.9940 +vn 0.2964 -0.3122 -0.9026 +vn 0.6727 -0.6851 -0.2794 +vn 0.6020 -0.5739 -0.5552 +vn 0.6110 -0.5865 -0.5317 +vn 0.6763 -0.6927 -0.2505 +vn 0.7530 0.6579 0.0128 +vn 0.7532 0.6572 0.0291 +vn 0.7563 0.6542 -0.0077 +vn 0.7429 0.6680 -0.0434 +vn 0.7305 0.6801 0.0622 +vn 0.7088 0.7014 0.0753 +vn 0.7383 0.6722 0.0552 +vn 0.6669 0.7438 -0.0456 +vn 0.6811 0.7293 -0.0650 +vn 0.6577 0.7526 -0.0311 +vn 0.6565 0.7543 0.0102 +vn 0.7063 0.7045 -0.0691 +vn 0.7119 0.6983 -0.0743 +vn 0.7517 0.6587 -0.0340 +vn 0.7336 0.6768 -0.0609 +vn 0.6736 0.7372 0.0524 +vn 0.6649 0.7456 0.0437 +vn 0.6838 0.7265 0.0681 +vn 0.6972 0.7135 0.0691 +vn 0.6524 0.7579 0.0042 +vn 0.7167 -0.6936 -0.0726 +vn 0.6596 -0.6895 -0.2994 +vn 0.6257 -0.6059 -0.4914 +vn 0.4578 -0.4811 -0.7476 +vn 0.4132 -0.3950 -0.8205 +vn 0.1432 -0.1586 -0.9769 +vn 0.0849 -0.0570 -0.9948 +vn -0.2013 0.1747 -0.9638 +vn -0.3083 0.3473 -0.8856 +vn -0.5444 0.5104 -0.6656 +vn -0.6150 0.6536 -0.4412 +vn -0.7169 0.6822 -0.1440 +vn -0.6877 0.7212 0.0834 +vn -0.6580 0.6244 0.4209 +vn -0.5480 0.5782 0.6045 +vn -0.3905 0.3637 0.8457 +vn -0.2709 0.2944 0.9165 +vn -0.0695 0.0486 0.9964 +vn 0.0615 -0.0315 0.9976 +vn 0.2619 -0.2860 0.9217 +vn 0.4583 -0.4253 0.7804 +vn 0.5367 -0.5621 0.6292 +vn 0.6700 -0.6438 0.3695 +vn 0.6796 -0.7022 0.2122 +vn 0.3536 -0.3536 -0.8660 +vn 0.3536 -0.3537 -0.8659 +vn 0.3536 -0.3535 -0.8661 +vn -0.3536 0.3536 -0.8660 +vn -0.3536 0.3536 0.8660 +vn 0.3536 -0.3537 0.8660 +vn 0.3536 -0.3537 0.8659 +vn 0.3537 -0.3537 0.8659 +vn 0.3535 -0.3535 0.8661 +vn 0.9640 0.0875 0.2511 +vn 0.9649 0.1060 0.2405 +vn 0.9530 -0.0038 0.3030 +vn 0.9499 -0.0200 0.3118 +vn 0.5706 0.4028 0.7157 +vn 0.5868 0.4128 0.6966 +vn 0.5125 0.3663 0.7766 +vn 0.5012 0.3591 0.7873 +vn 0.2454 0.8303 0.5004 +vn 0.2714 0.8282 0.4902 +vn 0.1510 0.8322 0.5336 +vn 0.1199 0.8310 0.5433 +vn -0.2096 0.9762 0.0555 +vn 0.3126 0.9422 -0.1207 +vn -0.2820 0.6853 -0.6715 +vn 0.5426 0.5755 -0.6119 +vn 0.5490 0.6012 -0.5806 +vn 0.4976 0.4346 -0.7507 +vn 0.4833 0.3969 -0.7803 +vn 0.8895 0.1645 -0.4264 +vn 0.8844 0.2151 -0.4142 +vn 0.8802 -0.0797 -0.4678 +vn 0.8722 -0.1264 -0.4726 +vn 0.7331 -0.6798 -0.0213 +vn 0.7318 -0.6809 -0.0300 +vn 0.7427 -0.6695 -0.0165 +vn 0.7055 -0.7074 -0.0426 +vn 0.6989 -0.7136 -0.0479 +vn 0.7175 -0.6952 -0.0420 +vn 0.6811 -0.7318 -0.0229 +vn 0.6740 -0.7384 -0.0233 +vn 0.6858 -0.7268 -0.0370 +vn 0.6914 -0.7215 0.0393 +vn 0.6746 -0.7377 0.0266 +vn 0.6804 -0.7325 0.0218 +vn 0.7382 -0.6745 0.0041 +vn 0.7315 -0.6815 0.0225 +vn 0.7340 -0.6784 0.0314 +vn 0.7105 -0.7020 0.0492 +vn 0.7077 -0.7053 0.0423 +vn 0.7232 -0.6895 0.0400 +vn 0.6753 -0.7376 0.0005 +vn -0.7607 0.6451 0.0723 +vn -0.6438 0.7128 0.2782 +vn -0.6419 0.7568 0.1236 +vn -0.7071 0.7071 0.0009 +vn -0.7059 0.7083 0.0051 +vn 0.5858 0.5762 0.5700 +vn 0.5405 0.7342 0.4108 +vn 0.5691 0.7039 0.4249 +vn 0.5814 0.5701 0.5805 +vn 0.0795 0.0665 0.9946 +vn 0.2734 0.2956 0.9154 +vn -0.1163 0.0145 0.9931 +vn -0.2310 -0.2441 0.9418 +vn -0.5625 -0.4376 0.7015 +vn -0.6366 -0.6487 0.4171 +vn -0.7683 -0.5346 0.3520 +vn -0.6989 -0.7135 0.0501 +vn -0.5531 -0.5456 -0.6296 +vn -0.6072 -0.5830 -0.5398 +vn -0.6041 -0.5810 -0.5455 +vn -0.5476 -0.5417 -0.6378 +vn -0.2369 -0.2420 -0.9409 +vn -0.1267 -0.1103 -0.9858 +vn -0.2293 -0.2330 -0.9450 +vn -0.1191 -0.1013 -0.9877 +vn 0.3050 0.3075 -0.9013 +vn 0.3348 0.3296 -0.8828 +vn 0.3320 0.3275 -0.8846 +vn 0.3028 0.3059 -0.9026 +vn 0.6845 0.6833 -0.2541 +vn 0.6720 0.6784 -0.2970 +vn 0.6734 0.6789 -0.2926 +vn 0.6855 0.6836 -0.2505 +vn -0.6572 0.7537 0.0117 +vn -0.6616 0.7486 0.0424 +vn -0.6541 0.7564 0.0029 +vn -0.6666 0.7442 -0.0437 +vn -0.6810 0.7298 0.0605 +vn -0.6858 0.7246 0.0674 +vn -0.7335 0.6774 -0.0566 +vn -0.7377 0.6728 -0.0552 +vn -0.7521 0.6586 -0.0235 +vn -0.7541 0.6562 -0.0258 +vn -0.7039 0.7070 -0.0689 +vn -0.6938 0.7165 -0.0724 +vn -0.7196 0.6908 -0.0703 +vn -0.6572 0.7532 -0.0290 +vn -0.6756 0.7348 -0.0600 +vn -0.7212 0.6895 0.0664 +vn -0.7414 0.6689 0.0533 +vn -0.7128 0.6976 0.0728 +vn -0.7569 0.6533 0.0147 +vn -0.7505 0.6603 0.0286 +vn 0.7040 0.6925 0.1576 +vn 0.6853 0.6698 -0.2860 +vn 0.6956 0.7145 0.0751 +vn 0.6268 0.6550 -0.4221 +vn 0.5345 0.5113 -0.6730 +vn 0.4038 0.4293 -0.8079 +vn 0.2526 0.2267 -0.9406 +vn 0.1177 0.1379 -0.9834 +vn -0.1039 -0.1239 -0.9868 +vn -0.1877 -0.1753 -0.9665 +vn -0.4448 -0.4518 -0.7733 +vn -0.4642 -0.4543 -0.7603 +vn -0.6707 -0.6531 -0.3517 +vn -0.6372 -0.6500 -0.4142 +vn -0.6971 -0.7168 0.0138 +vn -0.7096 -0.6713 0.2140 +vn -0.5984 -0.6303 0.4947 +vn -0.5079 -0.4713 0.7210 +vn -0.3046 -0.3405 0.8895 +vn -0.1484 -0.1100 0.9828 +vn 0.0612 0.0336 0.9976 +vn 0.2677 0.2943 0.9174 +vn 0.3728 0.3674 0.8521 +vn 0.5700 0.5770 0.5850 +vn 0.5778 0.5919 0.5620 +vn 0.3536 0.3536 -0.8660 +vn -0.3536 -0.3537 -0.8660 +vn -0.3536 -0.3537 -0.8659 +vn -0.3537 -0.3537 -0.8659 +vn -0.3535 -0.3535 -0.8661 +vn -0.3536 -0.3536 0.8660 +vn -0.3536 -0.3537 0.8659 +vn -0.3537 -0.3537 0.8659 +vn -0.3537 -0.3538 0.8659 +vn 0.3536 0.3536 0.8660 +vn 0.2683 0.8882 0.3729 +vn -0.4211 0.7963 0.4342 +vn -0.3113 0.7070 0.6351 +vn -0.5108 0.0010 0.8597 +vn -0.8722 0.3726 0.3169 +vn -0.9226 -0.2094 0.3240 +vn -0.9395 0.2023 -0.2763 +vn -0.9395 0.2277 -0.2561 +vn -0.9233 0.0638 -0.3787 +vn -0.9146 0.0274 -0.4035 +vn -0.4687 0.2832 -0.8367 +vn -0.4951 0.6828 -0.5373 +vn -0.5498 0.6718 -0.4964 +vn -0.2535 0.6946 -0.6733 +vn -0.1488 0.6840 -0.7141 +vn -0.0985 0.9807 -0.1690 +vn -0.0813 0.9825 -0.1678 +vn -0.1517 0.9732 -0.1726 +vn -0.1741 0.9693 -0.1738 +vn -0.3576 -0.2382 -0.9030 +vn -0.3339 -0.3492 -0.8756 +vn -0.3110 -0.4367 -0.8442 +vn -0.2850 -0.5205 -0.8049 +vn -0.7543 -0.5754 -0.3160 +vn -0.7117 -0.6570 -0.2485 +vn -0.6665 -0.7220 -0.1859 +vn -0.6072 -0.7865 -0.1128 +vn -0.7265 -0.5147 0.4553 +vn -0.6384 -0.5598 0.5282 +vn -0.5583 -0.5910 0.5822 +vn -0.4473 -0.6218 0.6429 +vn -0.2244 -0.0958 0.9698 +vn -0.1913 -0.1028 0.9761 +vn -0.1611 -0.1089 0.9809 +vn -0.1195 -0.1170 0.9859 +vn 0.4324 0.3813 0.8171 +vn 0.4322 0.3821 0.8169 +vn 0.4329 0.3801 0.8174 +vn 0.4331 0.3791 0.8177 +vn 0.6021 0.7632 0.2347 +vn 0.6699 0.7205 0.1790 +vn 0.7166 0.6841 0.1362 +vn 0.7729 0.6297 0.0780 +vn 0.5642 0.6269 -0.5373 +vn 0.5779 0.6210 -0.5295 +vn 0.5563 0.6304 -0.5413 +vn 0.5451 0.6351 -0.5473 +vn 0.2293 0.1929 -0.9541 +vn 0.2652 0.1887 -0.9455 +vn 0.2156 0.1944 -0.9569 +vn 0.1755 0.1985 -0.9643 +vn 0.7036 0.7104 0.0182 +vn 0.6993 0.7147 0.0132 +vn 0.6999 0.7142 0.0133 +vn 0.6958 0.7182 0.0081 +vn -0.1831 -0.2124 0.9599 +vn -0.2345 -0.1972 0.9519 +vn -0.2982 -0.1770 0.9380 +vn -0.3360 -0.1649 0.9273 +vn -0.4330 -0.6845 0.5865 +vn -0.5233 -0.6482 0.5532 +vn -0.6934 -0.5504 0.4650 +vn -0.7635 -0.4947 0.4152 +vn -0.6093 -0.7785 -0.1507 +vn -0.6365 -0.7513 -0.1743 +vn -0.6759 -0.7064 -0.2101 +vn -0.7061 -0.6667 -0.2387 +vn -0.5057 -0.5120 -0.6944 +vn -0.5036 -0.5130 -0.6952 +vn -0.5081 -0.5109 -0.6934 +vn -0.5101 -0.5099 -0.6927 +vn -0.0508 -0.1064 -0.9930 +vn -0.0588 -0.0863 -0.9945 +vn -0.0743 -0.0473 -0.9961 +vn -0.0823 -0.0270 -0.9962 +vn 0.4499 0.3917 -0.8026 +vn 0.4090 0.4089 -0.8158 +vn 0.5067 0.3652 -0.7810 +vn 0.5340 0.3519 -0.7688 +vn 0.6349 0.7107 -0.3030 +vn 0.5383 0.7525 -0.3794 +vn 0.7014 0.7061 -0.0977 +vn 0.7163 0.6827 0.1442 +vn 0.6294 0.6327 0.4511 +vn 0.4905 0.4996 0.7140 +vn 0.3378 0.3161 0.8865 +vn 0.2654 0.1963 0.9439 +vn 0.1879 0.2084 0.9598 +vn -0.7680 -0.6359 0.0766 +vn -0.7373 -0.6749 0.0279 +vn -0.7385 -0.6736 0.0296 +vn -0.7033 -0.7106 -0.0208 +vn 0.7071 -0.7071 0.0002 +vn 0.7072 -0.7070 0.0001 +vn 0.7073 -0.7069 -0.0001 +vn 0.7070 -0.7072 0.0001 +vn 0.7073 -0.7070 -0.0000 +vn 0.7070 -0.7072 -0.0002 +vn 0.7072 -0.7070 -0.0001 +vn 0.7072 -0.7070 -0.0004 +vn -0.7070 0.7072 0.0002 +vn -0.7069 0.7073 0.0000 +vn -0.7073 0.7069 0.0002 +vn -0.7070 0.7072 0.0001 +vn -0.7071 0.7071 -0.0001 +vn -0.7072 0.7070 -0.0001 +vn -0.7074 0.7068 -0.0002 +vn -0.7070 0.7072 -0.0001 +vn -0.7072 0.7070 -0.0000 +vn -0.7072 0.7070 -0.0004 +vn -0.7073 0.7070 -0.0003 +vn -0.7071 0.7071 0.0001 +vn -0.7072 0.7070 -0.0002 +vn -0.7073 0.7069 -0.0003 +vn -0.7250 -0.6877 0.0370 +vn -0.7398 -0.6725 0.0206 +vn -0.7336 -0.6793 0.0213 +vn -0.6800 -0.7329 0.0211 +vn -0.6737 -0.7387 0.0217 +vn -0.6883 -0.7244 0.0377 +vn -0.6887 -0.7241 -0.0383 +vn -0.6740 -0.7380 -0.0321 +vn -0.6796 -0.7332 -0.0226 +vn -0.6741 -0.7386 -0.0061 +vn -0.7378 -0.6750 -0.0091 +vn -0.7322 -0.6807 -0.0228 +vn -0.7329 -0.6793 -0.0359 +vn -0.7063 -0.7068 -0.0405 +vn -0.7040 -0.7086 -0.0475 +vn -0.7203 -0.6925 -0.0400 +vn -0.7063 -0.7067 0.0414 +vn -0.7073 -0.7054 0.0465 +vn 0.7072 0.7070 0.0004 +vn 0.7075 0.7067 -0.0002 +vn 0.7067 0.7075 0.0002 +vn 0.7067 0.7075 0.0036 +vn 0.7070 0.7072 -0.0004 +vn 0.7052 0.7090 -0.0032 +vn -0.6886 0.6790 -0.2545 +vn -0.6351 0.6523 -0.4137 +vn -0.5444 0.5318 -0.6488 +vn -0.2318 0.3157 -0.9201 +vn -0.0014 -0.0130 -0.9999 +vn 0.2523 -0.1064 -0.9618 +vn 0.3094 -0.3223 -0.8947 +vn 0.4730 -0.4552 -0.7543 +vn 0.6801 -0.6661 -0.3063 +vn 0.7841 -0.5854 -0.2059 +vn 0.7580 -0.6166 -0.2129 +vn 0.6791 -0.6637 -0.3135 +vn 0.6654 -0.6736 0.3217 +vn 0.6192 -0.6033 0.5025 +vn 0.6631 -0.6694 0.3350 +vn 0.6148 -0.5971 0.5153 +vn 0.2927 -0.2902 0.9111 +vn 0.2621 -0.2674 0.9273 +vn 0.2648 -0.2693 0.9259 +vn 0.2949 -0.2919 0.9099 +vn -0.2596 0.2640 0.9289 +vn -0.2506 0.2569 0.9334 +vn -0.2511 0.2573 0.9332 +vn -0.2605 0.2648 0.9285 +vn -0.6035 0.6033 0.5214 +vn -0.5855 0.5907 0.5552 +vn -0.5869 0.5917 0.5527 +vn -0.6046 0.6041 0.5192 +vn -0.6978 0.7119 -0.0785 +vn 0.6684 0.7423 -0.0466 +vn 0.6550 0.7555 -0.0165 +vn 0.6563 0.7544 0.0110 +vn 0.6557 0.7545 0.0272 +vn 0.7053 0.7054 -0.0711 +vn 0.6942 0.7160 -0.0732 +vn 0.6693 0.7409 -0.0560 +vn 0.7425 0.6683 0.0459 +vn 0.7440 0.6663 0.0498 +vn 0.7564 0.6540 0.0110 +vn 0.7548 0.6560 -0.0001 +vn 0.7061 0.7045 0.0715 +vn 0.6886 0.7216 0.0715 +vn 0.7194 0.6910 0.0712 +vn 0.6730 0.7377 0.0532 +vn 0.6682 0.7421 0.0528 +vn 0.7432 0.6675 -0.0459 +vn 0.7286 0.6818 -0.0661 +vn 0.7530 0.6573 -0.0307 +vn -0.6622 0.6728 0.3300 +vn -0.7021 0.7084 0.0722 +vn -0.7099 0.6973 0.0991 +vn -0.6562 0.6374 0.4038 +vn -0.4818 0.5011 0.7189 +vn -0.4120 0.3819 0.8273 +vn -0.2008 0.2317 0.9518 +vn -0.0369 0.0005 0.9993 +vn 0.1991 -0.1613 0.9666 +vn 0.3693 -0.4036 0.8371 +vn 0.5459 -0.5082 0.6661 +vn 0.6206 -0.6521 0.4355 +vn 0.7188 -0.6790 0.1492 +vn 0.6876 -0.7172 -0.1134 +vn 0.6563 -0.6140 -0.4385 +vn 0.5605 -0.5720 -0.5989 +vn 0.3424 -0.3057 -0.8884 +vn 0.3383 -0.3534 -0.8721 +vn 0.0261 -0.0434 -0.9987 +vn -0.1043 0.1407 -0.9845 +vn -0.2684 0.2574 -0.9283 +vn -0.4862 0.5022 -0.7152 +vn -0.5089 0.5065 -0.6961 +vn -0.6137 0.6139 -0.4964 +vn -0.6135 0.6200 -0.4891 +vn 0.3537 -0.3537 -0.8659 +vn 0.3537 -0.3538 -0.8659 +vn -0.0340 0.9832 0.1795 +vn 0.0356 0.9805 0.1931 +vn 0.1274 0.9857 -0.1102 +vn 0.1632 0.9793 -0.1195 +vn -0.0508 0.8031 -0.5937 +vn 0.0795 0.8093 -0.5820 +vn 0.3664 0.7719 -0.5196 +vn 0.4511 0.7459 -0.4900 +vn 0.2808 0.3634 -0.8883 +vn 0.8467 0.2765 -0.4546 +vn 0.8470 0.2741 -0.4555 +vn 0.8457 0.2845 -0.4514 +vn 0.8452 0.2890 -0.4496 +vn 0.9473 -0.2632 -0.1829 +vn 0.9593 0.2219 0.1746 +vn 0.9538 0.2706 0.1310 +vn 0.8315 0.1473 0.5356 +vn 0.7894 0.0754 0.6092 +vn 0.6668 0.4903 0.5613 +vn 0.6641 0.5323 0.5249 +vn 0.1502 0.5846 0.7973 +vn 0.1938 0.6791 0.7080 +vn 0.2312 0.8403 0.4903 +vn -0.2401 -0.2463 0.9390 +vn -0.2879 -0.2392 0.9273 +vn -0.3107 -0.2358 0.9208 +vn -0.3491 -0.2291 0.9086 +vn -0.5204 -0.7489 0.4103 +vn -0.6314 -0.6960 0.3419 +vn -0.7505 -0.6123 0.2486 +vn -0.8232 -0.5398 0.1760 +vn -0.4836 -0.7494 -0.4523 +vn -0.5412 -0.6515 -0.5316 +vn -0.5965 -0.5177 -0.6133 +vn -0.6314 -0.3885 -0.6711 +vn 0.0213 -0.1961 -0.9803 +vn 0.0002 -0.0868 -0.9962 +vn -0.0278 0.0592 -0.9979 +vn -0.0486 0.1690 -0.9844 +vn 0.5954 0.3665 -0.7150 +vn 0.5675 0.4979 -0.6558 +vn 0.5307 0.6103 -0.5881 +vn 0.4827 0.7138 -0.5074 +vn 0.8202 0.5709 0.0366 +vn 0.7401 0.6603 0.1272 +vn 0.6168 0.7508 0.2363 +vn 0.5029 0.8041 0.3172 +vn 0.4940 0.1756 0.8515 +vn 0.4060 0.2020 0.8912 +vn 0.2972 0.2305 0.9266 +vn 0.1701 0.2586 0.9509 +vn 0.7094 0.7036 0.0422 +vn 0.6921 0.7216 0.0179 +vn 0.6931 0.7206 0.0196 +vn 0.6757 0.7372 -0.0041 +vn -0.1608 -0.1408 -0.9769 +vn -0.1525 -0.1828 -0.9713 +vn -0.1454 -0.2155 -0.9656 +vn -0.1384 -0.2496 -0.9584 +vn -0.5694 -0.4170 -0.7084 +vn -0.5357 -0.5177 -0.6671 +vn -0.4745 -0.6518 -0.5916 +vn -0.4344 -0.7192 -0.5423 +vn -0.8105 -0.5518 -0.1966 +vn -0.5762 -0.7671 0.2822 +vn -0.5563 -0.7869 0.2671 +vn -0.6132 -0.7260 0.3114 +vn -0.6417 -0.6902 0.3344 +vn -0.4849 -0.3527 0.8003 +vn -0.4140 -0.3796 0.8273 +vn -0.2471 -0.2684 0.9311 +vn -0.0702 -0.1416 0.9874 +vn 0.1562 0.0925 0.9834 +vn 0.2223 0.2425 0.9443 +vn 0.1990 0.3639 0.9099 +vn 0.6430 0.5760 0.5047 +vn 0.6319 0.5839 0.5096 +vn 0.6122 0.5979 0.5175 +vn 0.6017 0.6049 0.5216 +vn 0.7042 0.6791 -0.2070 +vn 0.7449 0.6427 -0.1789 +vn 0.6310 0.7339 -0.2513 +vn 0.5909 0.7591 -0.2731 +vn 0.4494 0.4725 -0.7581 +vn 0.5636 0.4441 -0.6965 +vn 0.3309 0.4266 -0.8417 +vn 0.2816 0.2974 -0.9123 +vn 0.3046 0.1590 -0.9391 +vn -0.6918 -0.6904 -0.2117 +vn -0.7438 -0.6500 -0.1561 +vn -0.7370 -0.6557 -0.1638 +vn -0.7863 -0.6090 -0.1046 +vn -0.7069 0.7074 0.0001 +vn -0.7072 0.7070 0.0003 +vn -0.7072 0.7071 -0.0001 +vn -0.7069 0.7073 0.0003 +vn -0.7070 0.7072 -0.0000 +vn -0.7070 0.7072 -0.0002 +vn -0.7070 0.7072 0.0004 +vn -0.7070 0.7072 0.0003 +vn -0.7073 0.7069 -0.0000 +vn -0.7074 0.7069 -0.0001 +vn -0.7069 0.7073 -0.0003 +vn -0.7070 0.7072 -0.0004 +vn 0.7071 -0.7072 -0.0001 +vn 0.7072 -0.7070 0.0002 +vn 0.7074 -0.7068 0.0000 +vn 0.7073 -0.7069 0.0000 +vn 0.7070 -0.7072 0.0004 +vn 0.7071 -0.7072 0.0000 +vn 0.6895 -0.7232 0.0393 +vn 0.6734 -0.7387 0.0306 +vn 0.6804 -0.7325 0.0217 +vn 0.6749 -0.7378 0.0075 +vn 0.7068 -0.7060 0.0444 +vn 0.7142 -0.6983 0.0481 +vn 0.7029 -0.7091 0.0554 +vn 0.7331 -0.6798 0.0205 +vn 0.7424 -0.6696 0.0196 +vn 0.7286 -0.6842 0.0319 +vn 0.7326 -0.6803 -0.0215 +vn 0.7225 -0.6902 -0.0397 +vn 0.7380 -0.6744 -0.0237 +vn 0.6807 -0.7322 -0.0214 +vn 0.6760 -0.7365 -0.0227 +vn 0.7050 -0.7074 -0.0510 +vn 0.7065 -0.7065 -0.0429 +vn 0.6909 -0.7219 -0.0400 +vn 0.7390 -0.6737 0.0009 +vn -0.6951 0.7189 -0.0026 +vn -0.7447 0.5873 -0.3169 +vn -0.7465 0.6552 -0.1161 +vn -0.6911 0.7223 0.0248 +vn -0.6755 0.7370 0.0250 +vn -0.6952 0.7095 -0.1152 +vn -0.5768 -0.5846 -0.5705 +vn -0.6902 -0.5737 -0.4410 +vn -0.6667 -0.5927 -0.4520 +vn -0.5709 -0.5806 -0.5805 +vn -0.0629 -0.0719 -0.9954 +vn -0.2191 -0.2009 -0.9548 +vn 0.0346 0.0539 -0.9979 +vn 0.2427 0.2316 -0.9420 +vn 0.4863 0.5056 -0.7127 +vn 0.6482 0.6375 -0.4164 +vn 0.6954 0.7166 -0.0543 +vn 0.6610 0.6555 0.3653 +vn 0.6119 0.6314 0.4764 +vn 0.5333 0.5471 0.6452 +vn 0.4966 0.4947 0.7132 +vn -0.0550 -0.0629 0.9965 +vn 0.0387 0.0534 0.9978 +vn 0.0301 0.0427 0.9986 +vn -0.0627 -0.0724 0.9954 +vn -0.5347 -0.5335 0.6554 +vn -0.5704 -0.3466 0.7447 +vn -0.6403 -0.5416 0.5447 +vn -0.6406 -0.6402 0.4240 +vn -0.6915 -0.6838 0.2332 +vn -0.6969 -0.6967 0.1700 +vn -0.7539 0.6568 -0.0151 +vn -0.7493 0.6609 -0.0409 +vn -0.7572 0.6532 0.0008 +vn -0.7503 0.6605 0.0282 +vn -0.7293 0.6815 -0.0601 +vn -0.7286 0.6818 -0.0663 +vn -0.6888 0.7220 0.0650 +vn -0.6704 0.7399 0.0562 +vn -0.6588 0.7519 0.0262 +vn -0.6540 0.7563 0.0158 +vn -0.7294 0.6813 0.0617 +vn -0.7284 0.6818 0.0682 +vn -0.7009 0.7096 0.0728 +vn -0.7485 0.6620 0.0389 +vn -0.6884 0.7222 -0.0667 +vn -0.6712 0.7390 -0.0577 +vn -0.7005 0.7099 -0.0737 +vn -0.6598 0.7509 -0.0286 +vn -0.6553 0.7549 -0.0252 +vn -0.7188 -0.6952 0.0025 +vn -0.6919 -0.7116 0.1223 +vn -0.6033 -0.5837 0.5434 +vn -0.5895 -0.5899 0.5518 +vn -0.3673 -0.3746 0.8514 +vn -0.3302 -0.3067 0.8927 +vn -0.0790 -0.0936 0.9925 +vn 0.0613 0.0941 0.9937 +vn 0.2174 0.2013 0.9551 +vn 0.4487 0.4721 0.7588 +vn 0.4890 0.4941 0.7188 +vn 0.6742 0.7009 0.2330 +vn 0.6538 0.6538 0.3808 +vn 0.7154 0.6977 -0.0375 +vn 0.6489 0.6764 -0.3485 +vn 0.6366 0.6162 -0.4637 +vn 0.4349 0.4639 -0.7718 +vn 0.3675 0.3407 -0.8654 +vn 0.0587 0.0911 -0.9941 +vn -0.0206 -0.0394 -0.9990 +vn -0.3264 -0.3186 -0.8899 +vn -0.3530 -0.3578 -0.8645 +vn -0.6169 -0.6317 -0.4695 +vn -0.5952 -0.5829 -0.5531 +vn -0.3536 -0.3535 0.8661 +vn -0.7986 -0.4248 -0.4264 +vn -0.7773 0.4519 -0.4377 +vn -0.6302 0.3206 -0.7071 +vn -0.1467 0.6355 -0.7580 +vn -0.1932 0.6899 -0.6977 +vn -0.2250 0.8498 -0.4767 +vn -0.0335 0.9446 -0.3266 +vn -0.1224 0.9884 -0.0903 +vn -0.1881 0.9820 -0.0193 +vn -0.1952 0.8244 0.5313 +vn -0.3556 0.6367 0.6842 +vn -0.2917 0.6912 0.6612 +vn -0.5837 0.5317 0.6137 +vn -0.6136 0.5388 0.5772 +vn -0.7568 -0.0473 0.6519 +vn -0.9504 0.2549 0.1782 +vn -0.9420 0.2822 0.1816 +vn -0.9727 0.1615 0.1665 +vn -0.9841 0.0855 0.1559 +vn 0.2595 -0.2542 0.9317 +vn 0.2345 -0.2570 0.9375 +vn 0.2663 -0.2533 0.9300 +vn 0.2911 -0.2503 0.9234 +vn 0.6202 -0.6285 0.4693 +vn 0.6073 -0.6502 0.4566 +vn 0.5936 -0.6718 0.4431 +vn 0.5820 -0.6891 0.4318 +vn 0.7081 -0.5380 -0.4573 +vn 0.6754 -0.5622 -0.4773 +vn 0.6204 -0.5984 -0.5070 +vn 0.5776 -0.6231 -0.5273 +vn 0.1076 -0.0613 -0.9923 +vn 0.0814 -0.1844 -0.9795 +vn 0.1313 0.0584 -0.9896 +vn 0.1479 0.1488 -0.9777 +vn -0.5461 0.2507 -0.7993 +vn -0.4305 0.7263 -0.5358 +vn -0.7303 0.6818 0.0426 +vn -0.7948 0.6019 -0.0776 +vn -0.7036 0.6688 0.2402 +vn -0.6550 0.6452 0.3933 +vn -0.6764 0.5154 0.5262 +vn -0.2295 0.4731 0.8506 +vn -0.2502 0.3800 0.8905 +vn -0.2659 0.2962 0.9174 +vn -0.2852 0.1679 0.9437 +vn -0.7149 0.6936 0.0881 +vn -0.7447 0.6657 0.0474 +vn -0.7434 0.6670 0.0496 +vn -0.7700 0.6379 0.0103 +vn 0.2407 -0.1709 -0.9554 +vn 0.2260 -0.2108 -0.9511 +vn 0.2546 -0.1325 -0.9579 +vn 0.2771 -0.0665 -0.9585 +vn 0.3336 -0.6234 -0.7072 +vn 0.8340 -0.3935 -0.3868 +vn 0.4516 -0.8920 0.0190 +vn 0.8116 -0.3709 0.4515 +vn 0.1791 -0.6197 0.7641 +vn 0.3210 0.0299 0.9466 +vn -0.2852 0.0240 0.9582 +vn -0.2711 0.1321 0.9534 +vn -0.3680 0.3535 0.8600 +vn -0.4935 0.5315 0.6884 +vn -0.6233 0.6402 0.4490 +vn -0.6777 0.6685 0.3063 +vn -0.7434 0.6240 0.2410 +vn -0.6218 0.7365 -0.2662 +vn -0.5960 0.7643 -0.2463 +vn -0.6659 0.6826 -0.3011 +vn -0.6951 0.6412 -0.3251 +vn -0.4274 0.3199 -0.8456 +vn -0.3925 0.3379 -0.8554 +vn -0.3162 0.3741 -0.8718 +vn -0.2796 0.3903 -0.8772 +vn 0.6823 -0.7032 -0.2001 +vn 0.6624 -0.7289 -0.1727 +vn 0.6653 -0.7253 -0.1766 +vn 0.6440 -0.7505 -0.1483 +vn -0.7072 -0.7070 0.0000 +vn -0.7071 -0.7072 -0.0000 +vn -0.7070 -0.7072 -0.0004 +vn -0.7073 -0.7069 0.0004 +vn -0.7073 -0.7070 0.0000 +vn -0.7072 -0.7071 0.0001 +vn 0.7070 0.7072 0.0002 +vn 0.7070 0.7072 0.0001 +vn 0.7069 0.7073 0.0001 +vn 0.7070 0.7072 -0.0000 +vn 0.7073 0.7070 0.0003 +vn 0.7072 0.7070 0.0002 +vn 0.7069 0.7074 0.0000 +vn 0.7068 0.7074 0.0000 +vn 0.7070 0.7072 -0.0001 +vn 0.7069 0.7073 -0.0002 +vn 0.7071 0.7072 -0.0001 +vn -0.2000 -0.9794 -0.0285 +vn -0.2224 -0.9542 0.2002 +vn 0.2023 -0.9663 -0.1589 +vn 0.1897 -0.9806 0.0499 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 2/2/2 5/5/5 +f 6/6/6 4/4/4 7/7/7 +f 6/6/6 7/7/7 8/8/8 +f 8/8/8 7/7/7 9/9/9 +f 8/8/8 10/10/10 11/11/11 +f 8/8/8 11/11/11 6/6/6 +f 6/6/6 11/11/11 12/12/12 +f 13/13/13 14/14/14 12/12/12 +f 12/12/12 11/11/11 15/15/15 +f 13/13/13 12/12/12 15/15/15 +f 14/14/14 13/13/13 16/16/16 +f 16/16/16 13/13/13 17/17/17 +f 16/16/16 17/17/17 18/18/18 +f 18/18/18 17/17/17 19/19/19 +f 18/18/18 20/20/20 21/21/21 +f 21/21/21 16/16/16 18/18/18 +f 16/16/16 21/21/21 3/3/3 +f 22/22/22 5/5/5 23/23/23 +f 1/1/1 24/24/24 23/23/23 +f 5/5/5 2/2/2 1/1/1 +f 5/5/5 1/1/1 23/23/23 +f 25/25/25 24/24/24 1/1/1 +f 25/25/25 1/1/1 26/26/26 +f 26/26/26 27/27/27 28/28/28 +f 29/29/29 30/30/30 31/31/31 +f 30/30/30 29/29/29 13/13/13 +f 15/15/15 32/32/32 13/13/13 +f 13/13/13 32/32/32 30/30/30 +f 33/33/33 32/32/32 15/15/15 +f 15/15/15 34/34/34 33/33/33 +f 31/31/31 30/30/30 35/35/35 +f 35/35/35 30/30/30 36/36/36 +f 33/33/33 34/34/34 37/37/37 +f 37/37/37 34/34/34 38/38/38 +f 22/22/22 23/23/23 39/39/39 +f 39/39/39 23/23/23 40/40/40 +f 25/25/25 26/26/26 28/28/28 +f 25/25/25 28/28/28 41/41/41 +f 41/41/41 28/28/28 42/42/42 +f 43/43/43 35/35/35 36/36/36 +f 37/37/37 38/38/38 44/44/44 +f 44/44/44 38/38/38 45/45/45 +f 45/45/45 46/46/46 44/44/44 +f 43/43/43 46/46/46 47/47/47 +f 43/43/43 36/36/36 46/46/46 +f 46/46/46 45/45/45 47/47/47 +f 19/19/19 48/48/48 49/49/49 +f 27/27/27 20/20/20 50/50/50 +f 51/51/51 42/42/42 50/50/50 +f 50/50/50 42/42/42 28/28/28 +f 50/50/50 28/28/28 27/27/27 +f 50/50/50 20/20/20 49/49/49 +f 49/49/49 20/20/20 18/18/18 +f 49/49/49 18/18/18 19/19/19 +f 48/48/48 52/52/52 31/31/31 +f 48/48/48 31/31/31 43/43/43 +f 43/43/43 31/31/31 35/35/35 +f 41/41/41 42/42/42 51/51/51 +f 41/41/41 51/51/51 53/53/53 +f 54/54/54 55/55/55 56/56/56 +f 56/56/56 55/55/55 51/51/51 +f 51/51/51 55/55/55 53/53/53 +f 40/40/40 55/55/55 54/54/54 +f 39/39/39 40/40/40 57/57/57 +f 57/57/57 40/40/40 54/54/54 +f 58/58/58 9/9/9 59/59/59 +f 60/60/60 38/38/38 34/34/34 +f 60/60/60 34/34/34 61/61/61 +f 60/60/60 61/61/61 62/62/62 +f 62/62/62 10/10/10 58/58/58 +f 58/58/58 10/10/10 8/8/8 +f 58/58/58 8/8/8 9/9/9 +f 59/59/59 9/9/9 22/22/22 +f 59/59/59 22/22/22 57/57/57 +f 57/57/57 22/22/22 39/39/39 +f 63/63/63 64/64/64 65/65/65 +f 66/66/66 63/63/63 65/65/65 +f 67/67/67 68/68/68 66/66/66 +f 66/66/66 68/68/68 63/63/63 +f 65/65/65 64/64/64 69/69/69 +f 70/70/70 71/71/71 72/72/72 +f 72/72/72 71/71/71 73/73/73 +f 72/72/72 73/73/73 74/74/74 +f 72/72/72 74/74/74 75/75/75 +f 75/75/75 74/74/74 76/76/76 +f 71/71/71 70/70/70 77/77/77 +f 77/77/77 70/70/70 78/78/78 +f 78/78/78 70/70/70 79/79/79 +f 78/78/78 79/79/79 80/80/80 +f 80/80/80 79/79/79 81/81/81 +f 80/80/80 81/81/81 82/82/82 +f 83/83/83 84/84/84 85/85/85 +f 86/86/86 87/87/87 84/84/84 +f 84/84/84 87/87/87 85/85/85 +f 88/88/88 89/89/89 86/86/86 +f 86/86/86 89/89/89 87/87/87 +f 90/90/90 89/89/91 88/88/92 +f 91/91/93 92/92/94 90/90/95 +f 90/90/95 92/92/94 89/89/96 +f 93/93/97 94/94/98 95/95/99 +f 93/93/97 95/95/99 91/91/93 +f 91/91/93 95/95/99 92/92/94 +f 93/93/97 96/96/100 94/94/98 +f 97/97/101 67/67/67 98/98/102 +f 98/98/102 99/99/103 97/97/101 +f 100/100/104 99/99/103 98/98/102 +f 100/100/104 101/101/105 99/99/103 +f 102/102/106 101/101/105 100/100/104 +f 102/102/106 103/103/107 101/101/105 +f 104/104/108 103/103/107 102/102/106 +f 104/104/108 105/105/109 103/103/107 +f 105/105/109 104/104/108 106/106/110 +f 66/66/111 107/107/112 108/108/113 +f 109/109/114 67/67/115 108/108/113 +f 67/67/115 109/109/114 98/98/116 +f 98/98/116 109/109/114 110/110/117 +f 98/98/116 110/110/117 100/100/118 +f 100/100/118 110/110/117 111/111/119 +f 111/111/119 102/102/120 100/100/118 +f 112/112/121 104/104/122 111/111/119 +f 111/111/119 104/104/122 102/102/120 +f 113/113/123 69/69/69 106/106/124 +f 106/106/124 112/112/121 113/113/123 +f 112/112/121 106/106/124 104/104/122 +f 114/114/125 115/115/126 65/65/65 +f 114/114/125 65/65/65 113/113/123 +f 113/113/123 65/65/65 69/69/69 +f 114/114/125 116/116/127 117/117/128 +f 114/114/125 117/117/128 118/118/129 +f 119/119/130 115/115/126 114/114/125 +f 119/119/130 114/114/125 118/118/129 +f 120/120/131 116/116/127 114/114/125 +f 121/121/132 122/122/133 120/120/131 +f 120/120/131 122/122/133 116/116/127 +f 123/123/134 124/124/135 121/121/132 +f 121/121/132 124/124/135 122/122/133 +f 125/125/136 126/126/137 123/123/134 +f 123/123/134 126/126/137 124/124/135 +f 125/125/136 127/127/138 128/128/139 +f 128/128/139 126/126/137 125/125/136 +f 129/129/140 128/128/139 127/127/138 +f 130/130/141 129/129/140 127/127/138 +f 131/131/142 132/132/143 133/133/144 +f 131/131/142 133/133/144 130/130/141 +f 130/130/141 133/133/144 129/129/140 +f 134/134/145 135/135/146 131/131/142 +f 136/136/147 132/132/143 131/131/142 +f 136/136/147 131/131/142 135/135/146 +f 137/137/148 138/138/149 131/131/142 +f 131/131/142 138/138/149 139/139/150 +f 139/139/150 140/140/151 131/131/142 +f 131/131/142 140/140/151 141/141/152 +f 141/141/152 134/134/145 131/131/142 +f 142/142/153 143/143/154 137/137/148 +f 143/143/154 138/138/149 137/137/148 +f 143/143/154 142/142/153 144/144/155 +f 143/143/154 144/144/155 145/145/156 +f 146/146/157 147/147/158 144/144/155 +f 144/144/155 147/147/158 145/145/156 +f 148/148/159 149/149/160 146/146/157 +f 146/146/157 149/149/160 147/147/158 +f 150/150/161 148/148/159 151/151/162 +f 150/150/161 151/151/162 152/152/163 +f 148/148/159 150/150/161 149/149/160 +f 153/153/164 151/151/162 154/154/165 +f 154/154/165 151/151/162 148/148/159 +f 83/83/166 154/154/165 155/155/167 +f 83/83/166 82/82/168 154/154/165 +f 154/154/165 82/82/168 81/81/169 +f 154/154/165 81/81/169 153/153/164 +f 155/155/167 84/84/170 83/83/166 +f 156/156/171 84/84/170 155/155/167 +f 156/156/171 86/86/172 84/84/170 +f 157/157/173 88/88/92 156/156/171 +f 156/156/171 88/88/92 86/86/172 +f 157/157/173 90/90/90 88/88/92 +f 158/158/174 90/90/90 157/157/173 +f 159/159/175 91/91/176 158/158/174 +f 158/158/174 91/91/176 90/90/90 +f 159/159/175 93/93/177 91/91/176 +f 160/160/178 96/96/179 159/159/175 +f 159/159/175 96/96/179 93/93/177 +f 75/75/180 76/76/181 160/160/178 +f 160/160/178 76/76/181 96/96/179 +f 108/108/113 107/107/112 160/160/178 +f 160/160/178 107/107/112 75/75/180 +f 78/78/182 80/80/183 85/85/184 +f 73/73/185 94/94/186 74/74/187 +f 73/73/185 95/95/188 94/94/186 +f 71/71/189 92/92/190 95/95/188 +f 71/71/189 95/95/188 73/73/185 +f 89/89/191 92/92/190 71/71/189 +f 77/77/192 89/89/191 71/71/189 +f 77/77/192 87/87/193 89/89/191 +f 78/78/182 87/87/193 77/77/192 +f 78/78/182 85/85/184 87/87/193 +f 76/76/76 74/74/74 96/96/194 +f 74/74/74 94/94/195 96/96/194 +f 69/69/69 64/64/64 106/106/110 +f 68/68/68 67/67/67 97/97/101 +f 63/63/63 68/68/68 99/99/103 +f 64/64/64 63/63/63 103/103/107 +f 64/64/64 103/103/107 105/105/109 +f 68/68/68 97/97/101 99/99/103 +f 63/63/63 99/99/103 101/101/105 +f 63/63/63 101/101/105 103/103/107 +f 64/64/64 105/105/109 106/106/110 +f 65/65/65 115/115/196 66/66/66 +f 66/66/66 115/115/196 107/107/197 +f 57/57/57 161/161/198 59/59/59 +f 59/59/59 161/161/198 162/162/199 +f 59/59/59 162/162/199 58/58/58 +f 58/58/58 162/162/199 163/163/200 +f 58/58/58 163/163/200 62/62/62 +f 62/62/62 163/163/200 164/164/201 +f 62/62/62 164/164/201 60/60/60 +f 60/60/60 164/164/201 165/165/202 +f 60/60/60 165/165/202 38/38/38 +f 38/38/38 165/165/202 45/45/203 +f 45/45/203 165/165/202 72/72/204 +f 107/107/205 45/45/203 75/75/206 +f 75/75/206 45/45/203 72/72/204 +f 165/165/202 164/164/201 72/72/204 +f 72/72/204 164/164/201 70/70/207 +f 164/164/201 163/163/200 70/70/207 +f 163/163/200 162/162/199 70/70/207 +f 70/70/207 162/162/199 79/79/208 +f 162/162/199 161/161/198 79/79/208 +f 166/166/209 167/167/210 168/168/211 +f 166/166/209 168/168/211 169/169/212 +f 169/169/212 168/168/211 170/170/213 +f 169/169/212 170/170/213 136/136/214 +f 136/136/214 170/170/213 132/132/215 +f 167/167/210 166/166/209 171/171/216 +f 167/167/210 171/171/216 172/172/217 +f 172/172/217 171/171/216 173/173/218 +f 173/173/218 171/171/216 174/174/219 +f 173/173/218 174/174/219 175/175/220 +f 175/175/220 174/174/219 118/118/221 +f 175/175/220 118/118/221 117/117/222 +f 124/124/223 176/176/224 122/122/225 +f 122/122/225 176/176/224 177/177/226 +f 122/122/225 177/177/226 116/116/227 +f 126/126/228 178/178/229 124/124/223 +f 124/124/223 178/178/229 176/176/224 +f 178/178/229 126/126/228 179/179/230 +f 179/179/230 126/126/228 128/128/139 +f 179/179/230 128/128/139 129/129/140 +f 179/179/230 129/129/140 180/180/231 +f 180/180/231 129/129/140 133/133/232 +f 173/173/233 175/175/234 177/177/235 +f 168/168/236 180/180/237 170/170/238 +f 179/179/239 180/180/237 168/168/236 +f 167/167/240 179/179/239 168/168/236 +f 178/178/241 179/179/239 167/167/240 +f 178/178/241 167/167/240 172/172/242 +f 172/172/242 176/176/243 178/178/241 +f 173/173/233 177/177/235 176/176/243 +f 173/173/233 176/176/243 172/172/242 +f 175/175/220 117/117/222 116/116/227 +f 116/116/227 177/177/226 175/175/220 +f 43/43/43 181/181/244 48/48/48 +f 48/48/48 181/181/244 182/182/245 +f 48/48/48 182/182/245 183/183/246 +f 48/48/48 183/183/246 49/49/49 +f 49/49/49 183/183/246 184/184/247 +f 49/49/49 184/184/247 50/50/50 +f 50/50/50 184/184/247 185/185/248 +f 50/50/50 185/185/248 51/51/51 +f 181/181/244 43/43/43 47/47/249 +f 174/174/250 181/181/244 47/47/249 +f 118/118/251 174/174/250 47/47/249 +f 118/118/251 47/47/249 119/119/252 +f 169/169/212 185/185/248 166/166/209 +f 185/185/248 184/184/247 166/166/209 +f 166/166/209 184/184/247 171/171/216 +f 184/184/247 183/183/246 171/171/216 +f 183/183/246 182/182/245 171/171/216 +f 171/171/216 182/182/245 174/174/219 +f 174/174/219 182/182/245 181/181/244 +f 186/186/253 187/187/254 141/141/255 +f 141/141/255 187/187/254 152/152/163 +f 141/141/255 140/140/151 186/186/253 +f 187/187/254 188/188/256 152/152/163 +f 152/152/163 188/188/256 150/150/161 +f 143/143/257 189/189/258 138/138/259 +f 190/190/260 189/189/258 143/143/257 +f 145/145/261 190/190/260 143/143/257 +f 190/190/260 145/145/261 191/191/262 +f 191/191/262 145/145/261 147/147/263 +f 147/147/263 192/192/264 191/191/262 +f 147/147/263 149/149/265 192/192/264 +f 80/80/80 82/82/82 83/83/83 +f 83/83/83 85/85/85 80/80/80 +f 189/189/258 139/139/150 138/138/259 +f 149/149/265 150/150/161 192/192/264 +f 192/192/264 150/150/161 188/188/256 +f 192/192/264 188/188/256 187/187/254 +f 192/192/264 187/187/254 191/191/262 +f 191/191/262 187/187/254 190/190/260 +f 190/190/260 187/187/254 186/186/253 +f 190/190/260 186/186/253 189/189/258 +f 189/189/258 186/186/253 140/140/151 +f 189/189/258 140/140/151 139/139/150 +f 151/151/266 141/141/255 152/152/163 +f 151/151/266 134/134/267 141/141/255 +f 161/161/198 57/57/57 54/54/268 +f 161/161/198 54/54/268 79/79/269 +f 79/79/269 54/54/268 153/153/270 +f 79/79/269 153/153/270 81/81/271 +f 133/133/232 132/132/215 170/170/213 +f 133/133/232 170/170/213 180/180/231 +f 169/169/212 56/56/272 51/51/51 +f 51/51/51 185/185/248 169/169/212 +f 56/56/272 169/169/212 135/135/273 +f 135/135/273 169/169/212 136/136/274 +f 155/155/275 158/158/275 156/156/275 +f 127/127/276 121/121/275 130/130/277 +f 130/130/277 121/121/275 120/120/278 +f 120/120/278 131/131/279 130/130/277 +f 131/131/279 114/114/280 113/113/280 +f 131/131/279 113/113/280 137/137/280 +f 137/137/280 113/113/280 112/112/275 +f 120/120/278 114/114/280 131/131/279 +f 142/142/275 137/137/280 112/112/275 +f 123/123/275 127/127/276 125/125/275 +f 142/142/275 112/112/275 144/144/281 +f 111/111/275 146/146/275 144/144/281 +f 146/146/275 109/109/275 108/108/275 +f 110/110/275 109/109/275 111/111/275 +f 127/127/276 123/123/275 121/121/275 +f 146/146/275 108/108/275 148/148/282 +f 109/109/275 146/146/275 111/111/275 +f 148/148/282 108/108/275 154/154/276 +f 154/154/276 108/108/275 160/160/282 +f 154/154/276 160/160/282 155/155/275 +f 155/155/275 160/160/282 159/159/281 +f 159/159/281 158/158/275 155/155/275 +f 112/112/275 111/111/275 144/144/281 +f 157/157/275 156/156/275 158/158/275 +f 47/47/47 115/115/196 119/119/283 +f 47/47/47 45/45/45 115/115/196 +f 45/45/45 107/107/197 115/115/196 +f 135/135/284 134/134/267 56/56/56 +f 56/56/56 134/134/267 54/54/54 +f 54/54/54 134/134/267 151/151/266 +f 151/151/266 153/153/285 54/54/54 +f 193/193/286 194/194/286 195/195/286 +f 194/194/286 196/196/287 195/195/286 +f 197/197/286 194/194/286 193/193/286 +f 198/198/286 194/194/286 199/199/286 +f 200/200/288 196/196/287 201/201/289 +f 202/202/286 194/194/286 198/198/286 +f 203/203/290 204/204/291 201/201/289 +f 205/205/286 194/194/286 202/202/286 +f 196/196/287 206/206/292 201/201/289 +f 194/194/286 207/207/293 196/196/287 +f 206/206/292 203/203/290 201/201/289 +f 208/208/286 207/207/293 194/194/286 +f 209/209/294 203/203/290 206/206/292 +f 196/196/287 207/207/293 206/206/292 +f 210/210/286 208/208/286 211/211/286 +f 206/206/292 212/212/295 209/209/294 +f 213/213/286 210/210/286 211/211/286 +f 206/206/292 214/214/296 212/212/295 +f 215/215/286 216/216/286 210/210/286 +f 210/210/286 207/207/293 208/208/286 +f 217/217/286 215/215/286 210/210/286 +f 199/199/286 194/194/286 197/197/286 +f 216/216/286 207/207/293 210/210/286 +f 218/218/297 219/219/297 220/220/297 +f 221/221/298 222/222/297 223/223/297 +f 222/222/297 224/224/297 225/225/297 +f 222/222/297 221/221/298 226/226/297 +f 221/221/298 219/219/297 226/226/297 +f 227/227/299 228/228/300 229/229/301 +f 230/230/302 231/231/297 232/232/297 +f 221/221/298 227/227/299 229/229/301 +f 227/227/299 233/233/303 228/228/300 +f 221/221/298 234/234/304 235/235/305 +f 232/232/297 236/236/297 237/237/297 +f 230/230/302 221/221/298 235/235/305 +f 222/222/297 225/225/297 223/223/297 +f 238/238/297 218/218/297 220/220/297 +f 239/239/306 230/230/302 235/235/305 +f 240/240/297 219/219/297 221/221/298 +f 219/219/297 240/240/297 220/220/297 +f 241/241/307 242/242/308 239/239/306 +f 230/230/302 240/240/297 221/221/298 +f 243/243/309 242/242/308 241/241/307 +f 242/242/308 230/230/302 239/239/306 +f 221/221/298 229/229/301 234/234/304 +f 230/230/302 237/237/297 240/240/297 +f 230/230/302 232/232/297 237/237/297 +f 244/244/297 232/232/297 231/231/297 +f 245/245/310 246/246/310 247/247/310 +f 245/245/310 247/247/310 248/248/311 +f 249/249/312 250/250/313 251/251/314 +f 252/252/310 253/253/310 245/245/310 +f 245/245/310 253/253/310 246/246/310 +f 248/248/311 247/247/310 254/254/315 +f 248/248/311 254/254/315 214/214/316 +f 214/214/316 254/254/315 255/255/317 +f 254/254/315 256/256/318 255/255/317 +f 255/255/317 256/256/318 249/249/312 +f 257/257/319 258/258/310 252/252/310 +f 259/259/320 251/251/314 260/260/321 +f 251/251/314 259/259/320 261/261/322 +f 259/259/320 262/262/323 261/261/322 +f 261/261/322 262/262/323 257/257/319 +f 257/257/319 262/262/323 258/258/310 +f 258/258/310 263/263/310 252/252/310 +f 255/255/317 249/249/312 251/251/314 +f 264/264/310 260/260/321 253/253/310 +f 253/253/310 260/260/321 250/250/313 +f 250/250/313 260/260/321 251/251/314 +f 252/252/310 263/263/310 253/253/310 +f 253/253/310 263/263/310 265/265/310 +f 253/253/310 265/265/310 264/264/310 +f 266/266/324 267/267/325 268/268/325 +f 269/269/326 270/270/327 230/230/328 +f 230/230/328 270/270/327 207/207/329 +f 266/266/324 268/268/325 271/271/325 +f 207/207/329 272/272/330 273/273/331 +f 274/274/332 275/275/333 276/276/325 +f 276/276/325 275/275/333 277/277/325 +f 207/207/329 278/278/334 272/272/330 +f 242/242/335 279/279/336 230/230/328 +f 273/273/331 206/206/337 207/207/329 +f 230/230/328 279/279/336 269/269/326 +f 207/207/329 270/270/327 278/278/334 +f 242/242/335 280/280/338 279/279/336 +f 277/277/325 275/275/333 281/281/339 +f 271/271/325 268/268/325 282/282/340 +f 271/271/325 282/282/340 242/242/335 +f 242/242/335 282/282/340 280/280/338 +f 206/206/337 273/273/331 283/283/341 +f 277/277/325 281/281/339 283/283/341 +f 283/283/341 281/281/339 206/206/337 +f 275/275/333 274/274/332 266/266/324 +f 266/266/324 274/274/332 267/267/325 +f 270/270/327 284/284/332 278/278/334 +f 284/284/332 270/270/327 285/285/325 +f 274/274/332 286/286/325 267/267/325 +f 274/274/332 287/287/332 286/286/325 +f 286/286/325 287/287/332 288/288/325 +f 287/287/332 289/289/325 288/288/325 +f 288/288/325 289/289/325 285/285/325 +f 285/285/325 289/289/325 284/284/332 +f 252/252/342 245/245/343 266/266/324 +f 266/266/324 245/245/343 275/275/333 +f 243/243/344 290/290/345 261/261/322 +f 251/251/314 261/261/322 290/290/345 +f 290/290/345 243/243/344 291/291/346 +f 292/292/347 212/212/348 214/214/349 +f 292/292/347 214/214/349 255/255/317 +f 293/293/350 294/294/351 295/295/352 +f 295/295/352 294/294/351 296/296/353 +f 297/297/354 298/298/355 196/196/356 +f 196/196/356 298/298/355 221/221/357 +f 299/299/358 300/300/359 221/221/357 +f 301/301/360 294/294/351 293/293/350 +f 294/294/351 301/301/360 302/302/360 +f 294/294/351 302/302/360 303/303/361 +f 196/196/356 304/304/362 297/297/354 +f 221/221/357 298/298/355 299/299/358 +f 305/305/363 304/304/362 200/200/364 +f 200/200/364 304/304/362 196/196/356 +f 221/221/357 300/300/359 306/306/365 +f 307/307/360 293/293/350 308/308/360 +f 308/308/360 293/293/350 309/309/366 +f 306/306/365 227/227/360 221/221/357 +f 303/303/361 302/302/360 310/310/361 +f 303/303/361 310/310/361 200/200/364 +f 200/200/364 310/310/361 305/305/363 +f 309/309/366 293/293/350 311/311/367 +f 298/298/355 312/312/368 299/299/358 +f 312/312/368 298/298/355 313/313/360 +f 293/293/350 314/314/360 301/301/360 +f 314/314/360 307/307/360 315/315/369 +f 307/307/360 314/314/360 293/293/350 +f 227/227/360 306/306/365 316/316/363 +f 309/309/366 311/311/367 227/227/360 +f 309/309/366 227/227/360 316/316/363 +f 312/312/368 313/313/360 317/317/360 +f 312/312/368 317/317/360 318/318/360 +f 318/318/360 317/317/360 315/315/369 +f 315/315/369 317/317/360 314/314/360 +f 194/194/370 220/220/371 208/208/372 +f 208/208/372 220/220/371 240/240/373 +f 208/208/372 240/240/373 211/211/374 +f 211/211/374 240/240/373 237/237/375 +f 211/211/374 237/237/375 213/213/376 +f 213/213/376 237/237/375 236/236/377 +f 213/213/376 236/236/377 210/210/378 +f 210/210/378 236/236/377 232/232/379 +f 210/210/378 232/232/379 217/217/380 +f 217/217/380 232/232/379 244/244/381 +f 217/217/380 244/244/381 215/215/382 +f 215/215/382 244/244/381 231/231/383 +f 215/215/382 231/231/383 216/216/384 +f 216/216/384 231/231/383 230/230/328 +f 216/216/384 230/230/328 207/207/329 +f 194/194/370 238/238/385 220/220/371 +f 238/238/385 194/194/370 205/205/386 +f 238/238/385 205/205/386 218/218/387 +f 218/218/387 205/205/386 202/202/388 +f 218/218/387 202/202/388 219/219/389 +f 219/219/389 202/202/388 198/198/390 +f 219/219/389 198/198/390 226/226/391 +f 226/226/391 198/198/390 199/199/392 +f 226/226/391 199/199/392 222/222/393 +f 222/222/393 199/199/392 197/197/394 +f 222/222/393 197/197/394 224/224/395 +f 224/224/395 197/197/394 193/193/396 +f 224/224/395 193/193/396 225/225/397 +f 225/225/397 193/193/396 195/195/398 +f 225/225/397 195/195/398 223/223/399 +f 223/223/399 195/195/398 196/196/356 +f 223/223/399 196/196/356 221/221/357 +f 319/319/400 320/320/401 321/321/402 +f 322/322/403 323/323/404 324/324/405 +f 322/322/403 325/325/406 323/323/404 +f 324/324/405 323/323/404 326/326/407 +f 324/324/405 326/326/407 327/327/408 +f 327/327/408 326/326/407 328/328/409 +f 329/329/410 319/319/400 321/321/402 +f 330/330/409 295/295/409 331/331/409 +f 331/331/409 295/295/409 296/296/409 +f 332/332/409 295/295/409 333/333/409 +f 333/333/409 295/295/409 330/330/409 +f 327/327/408 328/328/409 296/296/409 +f 296/296/409 328/328/409 331/331/409 +f 320/320/401 330/330/409 334/334/411 +f 320/320/401 334/334/411 321/321/402 +f 295/295/409 332/332/409 335/335/409 +f 295/295/409 335/335/409 336/336/412 +f 330/330/409 320/320/401 337/337/409 +f 330/330/409 337/337/409 333/333/409 +f 334/334/411 325/325/406 321/321/402 +f 321/321/402 325/325/406 322/322/403 +f 336/336/412 335/335/409 338/338/413 +f 336/336/412 338/338/413 329/329/410 +f 329/329/410 338/338/413 319/319/400 +f 339/339/414 340/340/415 341/341/416 +f 340/340/415 339/339/414 342/342/417 +f 340/340/415 342/342/417 343/343/418 +f 343/343/418 342/342/417 321/321/402 +f 343/343/418 321/321/402 322/322/403 +f 339/339/414 341/341/416 344/344/419 +f 344/344/419 341/341/416 345/345/420 +f 344/344/419 345/345/420 346/346/421 +f 346/346/421 345/345/420 347/347/422 +f 347/347/422 345/345/420 348/348/423 +f 347/347/422 348/348/423 349/349/424 +f 349/349/424 348/348/423 350/350/425 +f 349/349/424 350/350/425 351/351/426 +f 351/351/426 350/350/425 352/352/427 +f 351/351/426 352/352/427 353/353/428 +f 353/353/428 352/352/427 354/354/429 +f 353/353/428 354/354/429 355/355/430 +f 353/353/428 355/355/430 356/356/431 +f 356/356/431 355/355/430 357/357/432 +f 307/307/433 308/308/434 358/358/435 +f 359/359/436 306/306/437 300/300/438 +f 359/359/436 360/360/439 306/306/437 +f 306/306/440 360/360/441 316/316/442 +f 316/316/442 360/360/441 361/361/443 +f 316/316/442 361/361/443 362/362/444 +f 316/316/442 362/362/444 309/309/445 +f 309/309/445 362/362/444 363/363/446 +f 358/358/435 308/308/434 363/363/446 +f 363/363/446 308/308/434 309/309/445 +f 364/364/447 307/307/448 358/358/449 +f 365/365/450 312/312/451 318/318/452 +f 365/365/450 318/318/452 366/366/453 +f 366/366/454 318/318/455 364/364/456 +f 364/364/456 318/318/455 315/315/457 +f 364/364/447 315/315/458 307/307/448 +f 367/367/459 312/312/460 365/365/461 +f 367/367/459 299/299/358 312/312/460 +f 359/359/462 300/300/359 367/367/459 +f 367/367/459 300/300/359 299/299/358 +f 332/332/463 368/368/464 335/335/465 +f 335/335/465 368/368/464 369/369/466 +f 335/335/467 369/369/468 370/370/469 +f 335/335/467 370/370/469 338/338/470 +f 338/338/471 370/370/472 319/319/473 +f 319/319/473 370/370/472 371/371/474 +f 319/319/475 371/371/476 320/320/477 +f 320/320/477 371/371/476 372/372/478 +f 320/320/479 372/372/480 337/337/481 +f 337/337/481 372/372/480 373/373/482 +f 337/337/483 373/373/484 333/333/485 +f 333/333/485 373/373/484 374/374/486 +f 333/333/487 374/374/488 332/332/489 +f 332/332/489 374/374/488 368/368/490 +f 369/369/491 363/363/492 362/362/493 +f 369/369/491 362/362/493 370/370/493 +f 370/370/493 362/362/493 361/361/494 +f 370/370/493 361/361/494 360/360/495 +f 370/370/493 360/360/495 371/371/496 +f 371/371/496 360/360/495 359/359/497 +f 371/371/496 359/359/497 372/372/498 +f 372/372/498 359/359/497 367/367/499 +f 372/372/498 367/367/499 373/373/500 +f 373/373/500 367/367/499 365/365/501 +f 373/373/500 365/365/501 366/366/502 +f 373/373/500 366/366/502 374/374/503 +f 374/374/503 366/366/502 364/364/503 +f 374/374/503 364/364/503 368/368/502 +f 368/368/502 364/364/503 358/358/500 +f 368/368/502 358/358/500 369/369/491 +f 369/369/491 358/358/500 363/363/492 +f 302/302/504 301/301/505 375/375/506 +f 298/298/507 376/376/508 377/377/509 +f 377/377/509 313/313/510 298/298/507 +f 377/377/509 378/378/511 313/313/510 +f 313/313/440 378/378/512 317/317/513 +f 317/317/513 378/378/512 379/379/514 +f 317/317/515 379/379/516 380/380/517 +f 317/317/515 380/380/517 314/314/518 +f 375/375/506 301/301/505 380/380/519 +f 380/380/519 301/301/505 314/314/520 +f 381/381/521 302/302/504 375/375/506 +f 382/382/522 304/304/523 305/305/524 +f 382/382/522 305/305/524 383/383/453 +f 383/383/525 305/305/526 384/384/527 +f 384/384/527 305/305/526 310/310/528 +f 384/384/527 310/310/528 381/381/521 +f 381/381/521 310/310/528 302/302/504 +f 376/376/508 304/304/529 382/382/530 +f 376/376/508 297/297/531 304/304/529 +f 376/376/508 298/298/507 297/297/531 +f 331/331/532 385/385/533 330/330/534 +f 330/330/534 385/385/533 386/386/535 +f 330/330/536 386/386/537 334/334/538 +f 334/334/538 386/386/537 387/387/539 +f 334/334/540 387/387/541 325/325/542 +f 325/325/542 387/387/541 388/388/543 +f 325/325/544 388/388/545 323/323/546 +f 323/323/546 388/388/545 389/389/547 +f 323/323/548 389/389/549 326/326/550 +f 326/326/550 389/389/549 390/390/551 +f 326/326/550 390/390/551 328/328/552 +f 328/328/553 390/390/554 385/385/555 +f 328/328/553 385/385/555 331/331/556 +f 388/388/557 376/376/497 389/389/502 +f 389/389/502 376/376/497 382/382/500 +f 389/389/502 382/382/500 383/383/558 +f 389/389/502 383/383/558 390/390/496 +f 390/390/496 383/383/558 384/384/559 +f 390/390/496 384/384/559 381/381/496 +f 390/390/496 381/381/496 385/385/496 +f 385/385/496 381/381/496 375/375/500 +f 385/385/496 375/375/500 380/380/496 +f 385/385/496 380/380/496 386/386/496 +f 386/386/496 380/380/496 379/379/500 +f 386/386/496 379/379/500 387/387/496 +f 387/387/496 379/379/500 378/378/500 +f 387/387/496 378/378/500 377/377/497 +f 387/387/496 377/377/497 376/376/497 +f 387/387/496 376/376/497 388/388/557 +f 255/255/317 251/251/314 290/290/345 +f 290/290/345 391/391/560 255/255/317 +f 391/391/560 290/290/345 392/392/561 +f 391/391/560 392/392/561 357/357/432 +f 357/357/432 392/392/561 356/356/431 +f 260/260/562 393/393/563 394/394/564 +f 260/260/562 394/394/564 259/259/565 +f 259/259/565 394/394/564 395/395/566 +f 259/259/565 395/395/566 262/262/567 +f 262/262/567 395/395/566 396/396/568 +f 262/262/567 396/396/568 258/258/569 +f 258/258/569 396/396/568 397/397/570 +f 258/258/569 397/397/570 263/263/571 +f 263/263/571 397/397/570 398/398/572 +f 263/263/571 398/398/572 265/265/573 +f 265/265/573 398/398/572 399/399/574 +f 265/265/575 399/399/575 264/264/575 +f 264/264/576 399/399/576 393/393/576 +f 264/264/577 393/393/577 260/260/577 +f 399/399/578 400/400/579 401/401/578 +f 399/399/578 401/401/578 393/393/580 +f 393/393/580 401/401/578 402/402/580 +f 393/393/580 402/402/580 394/394/581 +f 394/394/581 402/402/580 403/403/581 +f 394/394/581 403/403/581 395/395/581 +f 395/395/581 403/403/581 404/404/581 +f 395/395/581 404/404/581 396/396/582 +f 396/396/582 404/404/581 405/405/583 +f 396/396/582 405/405/583 397/397/584 +f 397/397/584 405/405/583 406/406/584 +f 397/397/584 406/406/584 407/407/585 +f 397/397/584 407/407/585 398/398/586 +f 398/398/586 407/407/585 408/408/580 +f 398/398/586 408/408/580 399/399/578 +f 399/399/578 408/408/580 400/400/579 +f 268/268/587 267/267/588 407/407/589 +f 402/402/590 285/285/591 270/270/592 +f 402/402/590 401/401/593 285/285/591 +f 285/285/594 401/401/595 288/288/596 +f 288/288/596 401/401/595 400/400/597 +f 288/288/598 400/400/599 286/286/600 +f 286/286/600 400/400/599 408/408/601 +f 407/407/589 267/267/588 408/408/602 +f 408/408/602 267/267/588 286/286/603 +f 406/406/604 268/268/587 407/407/589 +f 403/403/605 279/279/606 404/404/607 +f 404/404/607 279/279/606 280/280/608 +f 404/404/609 280/280/610 405/405/611 +f 405/405/611 280/280/610 282/282/612 +f 405/405/611 282/282/612 406/406/604 +f 406/406/604 282/282/612 268/268/587 +f 403/403/605 269/269/326 279/279/606 +f 402/402/613 269/269/326 403/403/605 +f 402/402/613 270/270/327 269/269/326 +f 249/249/614 409/409/615 410/410/616 +f 249/249/614 410/410/616 250/250/617 +f 250/250/618 410/410/619 253/253/620 +f 253/253/620 410/410/619 411/411/621 +f 253/253/622 411/411/623 412/412/624 +f 253/253/622 412/412/624 246/246/625 +f 246/246/626 412/412/627 247/247/628 +f 247/247/628 412/412/627 413/413/629 +f 247/247/630 413/413/631 414/414/632 +f 247/247/630 414/414/632 254/254/633 +f 254/254/634 414/414/635 256/256/636 +f 256/256/636 414/414/635 415/415/637 +f 256/256/638 415/415/639 249/249/640 +f 249/249/640 415/415/639 409/409/641 +f 410/410/642 416/416/585 417/417/581 +f 410/410/642 417/417/581 411/411/643 +f 411/411/643 417/417/581 418/418/644 +f 411/411/643 418/418/644 419/419/644 +f 411/411/643 419/419/644 412/412/643 +f 412/412/643 419/419/644 420/420/645 +f 412/412/643 420/420/645 413/413/646 +f 413/413/646 420/420/645 421/421/642 +f 413/413/646 421/421/642 414/414/647 +f 414/414/647 421/421/642 422/422/648 +f 414/414/647 422/422/648 415/415/646 +f 415/415/646 422/422/648 423/423/583 +f 415/415/646 423/423/583 424/424/584 +f 415/415/646 424/424/584 409/409/585 +f 409/409/585 424/424/584 416/416/585 +f 409/409/585 416/416/585 410/410/642 +f 274/274/649 276/276/650 420/420/651 +f 424/424/652 273/273/653 272/272/654 +f 424/424/652 423/423/655 273/273/653 +f 273/273/656 423/423/657 283/283/658 +f 283/283/658 423/423/657 422/422/659 +f 283/283/660 422/422/661 277/277/662 +f 277/277/662 422/422/661 421/421/663 +f 420/420/651 276/276/650 421/421/663 +f 421/421/663 276/276/650 277/277/662 +f 419/419/664 274/274/665 420/420/666 +f 417/417/667 284/284/668 289/289/669 +f 417/417/667 289/289/669 418/418/670 +f 418/418/671 289/289/672 419/419/673 +f 419/419/673 289/289/672 287/287/674 +f 419/419/664 287/287/675 274/274/665 +f 416/416/676 284/284/677 417/417/678 +f 416/416/676 278/278/334 284/284/677 +f 424/424/679 272/272/330 416/416/676 +f 416/416/676 272/272/330 278/278/334 +f 241/241/680 291/291/346 243/243/344 +f 228/228/681 425/425/682 229/229/683 +f 229/229/683 425/425/682 344/344/419 +f 344/344/419 346/346/684 229/229/683 +f 229/229/683 346/346/684 234/234/685 +f 234/234/685 346/346/684 347/347/686 +f 234/234/685 347/347/686 235/235/687 +f 235/235/687 347/347/686 349/349/688 +f 235/235/687 349/349/688 426/426/689 +f 426/426/689 351/351/690 239/239/691 +f 239/239/691 351/351/690 353/353/428 +f 239/239/691 353/353/428 241/241/680 +f 241/241/680 353/353/428 291/291/346 +f 426/426/692 239/239/692 235/235/692 +f 212/212/348 292/292/347 209/209/693 +f 209/209/693 292/292/347 355/355/430 +f 355/355/430 354/354/694 209/209/693 +f 209/209/693 354/354/694 427/427/695 +f 427/427/695 354/354/694 352/352/696 +f 427/427/695 352/352/696 428/428/697 +f 428/428/697 352/352/696 350/350/698 +f 428/428/697 348/348/699 204/204/700 +f 204/204/700 348/348/699 345/345/420 +f 204/204/700 345/345/420 429/429/701 +f 429/429/701 345/345/420 430/430/702 +f 209/209/703 427/427/703 203/203/703 +f 203/203/704 427/427/695 428/428/697 +f 203/203/290 428/428/705 204/204/291 +f 429/429/706 201/201/289 204/204/291 +f 290/290/345 291/291/346 392/392/561 +f 392/392/561 291/291/346 356/356/431 +f 353/353/428 356/356/431 291/291/346 +f 349/349/688 351/351/690 426/426/689 +f 344/344/419 425/425/682 339/339/414 +f 339/339/414 425/425/682 342/342/417 +f 342/342/417 425/425/682 321/321/402 +f 425/425/682 228/228/681 233/233/707 +f 425/425/682 233/233/707 321/321/402 +f 321/321/402 233/233/707 329/329/708 +f 357/357/432 292/292/347 391/391/560 +f 391/391/560 292/292/347 255/255/317 +f 355/355/430 292/292/347 357/357/432 +f 341/341/416 430/430/702 345/345/420 +f 350/350/698 348/348/699 428/428/697 +f 343/343/418 430/430/702 340/340/415 +f 341/341/416 340/340/415 430/430/702 +f 343/343/418 324/324/405 429/429/701 +f 322/322/403 324/324/405 343/343/418 +f 343/343/418 429/429/701 430/430/702 +f 201/201/289 429/429/706 324/324/709 +f 201/201/289 324/324/710 200/200/288 +f 324/324/710 327/327/711 200/200/288 +f 327/327/711 303/303/712 200/200/288 +f 327/327/711 296/296/353 303/303/712 +f 296/296/353 294/294/351 303/303/712 +f 336/336/713 293/293/714 295/295/715 +f 336/336/713 311/311/716 293/293/714 +f 336/336/713 227/227/299 311/311/716 +f 329/329/717 227/227/299 336/336/713 +f 233/233/303 227/227/299 329/329/717 +f 275/275/718 245/245/719 248/248/720 +f 275/275/718 248/248/720 281/281/721 +f 281/281/722 248/248/723 214/214/296 +f 281/281/722 214/214/296 206/206/292 +f 242/242/308 243/243/309 261/261/724 +f 261/261/724 257/257/725 242/242/308 +f 257/257/725 271/271/726 242/242/308 +f 257/257/725 252/252/342 271/271/726 +f 252/252/342 266/266/324 271/271/726 +f 431/431/727 432/432/727 433/433/727 +f 433/433/728 432/432/729 434/434/730 +f 433/433/728 434/434/730 435/435/731 +f 435/435/732 434/434/733 436/436/734 +f 435/435/732 436/436/734 437/437/735 +f 437/437/736 436/436/737 438/438/738 +f 437/437/736 438/438/738 439/439/739 +f 439/439/740 438/438/741 440/440/742 +f 439/439/740 440/440/742 441/441/743 +f 441/441/744 440/440/744 442/442/744 +f 441/441/745 442/442/745 443/443/745 +f 443/443/746 442/442/746 444/444/746 +f 443/443/747 444/444/748 445/445/749 +f 445/445/749 444/444/748 446/446/750 +f 447/447/751 445/445/752 448/448/753 +f 448/448/753 445/445/752 446/446/754 +f 447/447/755 448/448/756 449/449/757 +f 447/447/755 449/449/757 450/450/758 +f 450/450/759 449/449/760 451/451/761 +f 450/450/759 451/451/761 452/452/762 +f 452/452/763 451/451/764 453/453/765 +f 453/453/765 451/451/764 454/454/766 +f 453/453/765 454/454/766 455/455/767 +f 453/453/765 455/455/767 456/456/768 +f 456/456/768 455/455/767 457/457/769 +f 456/456/770 457/457/770 458/458/770 +f 458/458/771 457/457/771 459/459/771 +f 458/458/772 459/459/773 460/460/774 +f 460/460/774 459/459/773 461/461/775 +f 460/460/776 461/461/777 462/462/778 +f 460/460/776 462/462/778 463/463/779 +f 463/463/780 462/462/781 464/464/782 +f 463/463/780 464/464/782 465/465/783 +f 465/465/783 464/464/782 466/466/784 +f 465/465/783 466/466/784 467/467/785 +f 465/465/783 467/467/785 468/468/786 +f 431/431/787 468/468/788 432/432/789 +f 432/432/789 468/468/788 467/467/790 +f 468/468/791 431/431/791 433/433/792 +f 468/468/791 433/433/792 465/465/310 +f 443/443/793 452/452/794 441/441/795 +f 441/441/795 452/452/794 453/453/796 +f 443/443/793 450/450/797 452/452/794 +f 445/445/798 447/447/310 450/450/797 +f 445/445/798 450/450/797 443/443/793 +f 437/437/799 460/460/800 435/435/798 +f 441/441/795 456/456/801 439/439/802 +f 441/441/795 453/453/796 456/456/801 +f 435/435/798 465/465/310 433/433/792 +f 435/435/798 463/463/798 465/465/310 +f 435/435/798 460/460/800 463/463/798 +f 439/439/802 458/458/803 437/437/799 +f 437/437/799 458/458/803 460/460/800 +f 439/439/802 456/456/801 458/458/803 +f 448/448/584 446/446/642 444/444/646 +f 448/448/584 444/444/646 449/449/578 +f 440/440/581 454/454/642 442/442/804 +f 442/442/804 454/454/642 451/451/805 +f 442/442/804 451/451/805 449/449/578 +f 442/442/804 449/449/578 444/444/646 +f 440/440/581 455/455/806 454/454/642 +f 438/438/807 457/457/578 440/440/581 +f 440/440/581 457/457/578 455/455/806 +f 438/438/807 459/459/808 457/457/578 +f 436/436/580 459/459/808 438/438/807 +f 436/436/580 461/461/809 459/459/808 +f 432/432/810 467/467/578 466/466/578 +f 432/432/810 466/466/578 434/434/646 +f 434/434/646 462/462/642 436/436/580 +f 436/436/580 462/462/642 461/461/809 +f 466/466/578 464/464/811 434/434/646 +f 434/434/646 464/464/811 462/462/642 +f 469/469/812 470/470/813 471/471/814 +f 472/472/815 473/473/816 474/474/817 +f 475/475/818 476/476/819 477/477/820 +f 478/478/821 479/479/822 480/480/823 +f 469/469/812 471/471/814 481/481/824 +f 471/471/814 482/482/825 481/481/824 +f 483/483/826 484/484/827 485/485/828 +f 482/482/825 486/486/829 481/481/824 +f 485/485/828 484/484/827 478/478/821 +f 485/485/828 478/478/821 480/480/823 +f 486/486/829 483/483/826 481/481/824 +f 481/481/824 483/483/826 485/485/828 +f 477/477/820 476/476/819 472/472/815 +f 472/472/815 476/476/819 473/473/816 +f 480/480/823 479/479/822 475/475/818 +f 480/480/823 475/475/818 477/477/820 +f 472/472/815 474/474/817 470/470/813 +f 472/472/815 470/470/813 469/469/812 +f 487/487/830 488/488/831 489/489/832 +f 487/487/830 490/490/833 488/488/831 +f 491/491/834 490/490/833 487/487/830 +f 487/487/830 492/492/835 491/491/834 +f 493/493/836 494/494/837 495/495/838 +f 493/493/836 495/495/838 496/496/839 +f 496/496/840 495/495/841 497/497/842 +f 496/496/840 497/497/842 498/498/843 +f 498/498/844 497/497/845 499/499/846 +f 499/499/846 497/497/845 500/500/847 +f 499/499/846 500/500/847 501/501/848 +f 501/501/848 500/500/847 502/502/849 +f 501/501/848 502/502/849 503/503/850 +f 503/503/850 502/502/849 504/504/851 +f 503/503/850 504/504/851 505/505/852 +f 505/505/852 504/504/851 506/506/853 +f 505/505/852 506/506/853 507/507/854 +f 507/507/855 506/506/856 494/494/857 +f 507/507/855 494/494/857 493/493/858 +f 493/493/859 508/508/860 509/509/861 +f 493/493/859 509/509/861 507/507/862 +f 496/496/863 510/510/864 511/511/865 +f 496/496/863 511/511/865 493/493/859 +f 493/493/859 511/511/865 508/508/860 +f 503/503/866 512/512/867 513/513/868 +f 503/503/866 513/513/868 501/501/869 +f 505/505/870 514/514/871 512/512/867 +f 505/505/870 512/512/867 503/503/866 +f 507/507/862 509/509/861 515/515/872 +f 507/507/862 515/515/872 516/516/873 +f 507/507/862 516/516/873 505/505/870 +f 505/505/870 516/516/873 514/514/871 +f 499/499/874 517/517/875 518/518/876 +f 499/499/874 518/518/876 498/498/877 +f 498/498/877 518/518/876 510/510/864 +f 498/498/877 510/510/864 496/496/863 +f 501/501/869 513/513/868 519/519/878 +f 501/501/869 519/519/878 517/517/875 +f 501/501/869 517/517/875 499/499/874 +f 509/509/879 471/471/880 515/515/881 +f 471/471/880 470/470/882 515/515/881 +f 515/515/881 470/470/882 516/516/883 +f 470/470/882 474/474/884 516/516/883 +f 516/516/883 474/474/884 514/514/885 +f 474/474/884 473/473/886 514/514/885 +f 514/514/885 473/473/886 512/512/887 +f 512/512/887 473/473/886 476/476/888 +f 512/512/887 476/476/888 513/513/889 +f 476/476/888 475/475/890 513/513/889 +f 513/513/889 475/475/890 519/519/891 +f 519/519/891 475/475/890 479/479/892 +f 519/519/891 479/479/892 517/517/893 +f 479/479/892 478/478/894 517/517/893 +f 517/517/893 478/478/894 518/518/895 +f 518/518/895 478/478/894 484/484/896 +f 518/518/895 484/484/896 510/510/897 +f 510/510/897 484/484/896 483/483/898 +f 510/510/897 483/483/898 511/511/899 +f 483/483/898 486/486/900 511/511/899 +f 511/511/899 486/486/900 508/508/901 +f 486/486/900 482/482/902 508/508/901 +f 508/508/901 482/482/902 509/509/879 +f 509/509/879 482/482/902 471/471/880 +f 480/480/496 477/477/496 520/520/496 +f 520/520/496 477/477/496 521/521/496 +f 485/485/903 480/480/904 522/522/904 +f 522/522/904 480/480/904 520/520/905 +f 481/481/906 485/485/906 523/523/906 +f 523/523/906 485/485/906 522/522/906 +f 469/469/409 481/481/409 524/524/409 +f 524/524/409 481/481/409 523/523/409 +f 472/472/907 469/469/907 525/525/907 +f 525/525/907 469/469/907 524/524/907 +f 477/477/908 472/472/909 521/521/910 +f 521/521/910 472/472/909 525/525/911 +f 524/524/581 523/523/581 525/525/642 +f 525/525/642 523/523/581 522/522/642 +f 525/525/642 522/522/642 521/521/585 +f 521/521/585 522/522/642 520/520/585 +f 494/494/912 487/487/913 489/489/914 +f 494/494/912 489/489/914 495/495/915 +f 495/495/916 489/489/917 488/488/918 +f 495/495/916 488/488/918 497/497/919 +f 497/497/920 488/488/921 490/490/922 +f 497/497/920 490/490/922 500/500/923 +f 500/500/924 490/490/924 502/502/924 +f 502/502/925 490/490/833 491/491/834 +f 502/502/849 491/491/926 504/504/851 +f 504/504/927 491/491/928 492/492/929 +f 504/504/927 492/492/929 506/506/930 +f 506/506/931 492/492/932 487/487/933 +f 506/506/931 487/487/933 494/494/934 +f 526/526/935 527/527/936 528/528/937 +f 529/529/938 530/530/939 531/531/940 +f 532/532/941 533/533/942 534/534/943 +f 535/535/944 536/536/945 537/537/946 +f 526/526/935 528/528/937 538/538/947 +f 526/526/935 538/538/947 539/539/948 +f 538/538/947 540/540/949 539/539/948 +f 541/541/950 535/535/944 542/542/951 +f 542/542/951 535/535/944 537/537/946 +f 540/540/949 543/543/952 539/539/948 +f 539/539/948 543/543/952 542/542/951 +f 542/542/951 543/543/952 541/541/950 +f 532/532/941 534/534/943 529/529/938 +f 529/529/938 534/534/943 530/530/939 +f 536/536/945 544/544/953 537/537/946 +f 537/537/946 544/544/953 532/532/941 +f 532/532/941 544/544/953 533/533/942 +f 529/529/938 531/531/940 526/526/935 +f 526/526/935 531/531/940 527/527/936 +f 545/545/954 546/546/955 547/547/956 +f 548/548/957 549/549/958 545/545/954 +f 547/547/956 548/548/957 545/545/954 +f 550/550/959 551/551/960 552/552/961 +f 550/550/959 552/552/961 553/553/962 +f 553/553/963 552/552/964 554/554/965 +f 553/553/963 554/554/965 555/555/966 +f 555/555/966 554/554/965 556/556/967 +f 555/555/966 556/556/967 557/557/968 +f 557/557/968 556/556/967 558/558/969 +f 557/557/968 558/558/969 559/559/970 +f 559/559/971 558/558/972 560/560/973 +f 559/559/971 560/560/973 561/561/974 +f 561/561/975 560/560/976 562/562/977 +f 562/562/977 560/560/976 563/563/978 +f 562/562/979 563/563/980 564/564/981 +f 562/562/979 564/564/981 565/565/982 +f 565/565/983 564/564/984 551/551/985 +f 565/565/983 551/551/985 550/550/986 +f 550/550/987 566/566/988 567/567/989 +f 550/550/987 567/567/989 565/565/990 +f 553/553/991 568/568/992 566/566/988 +f 553/553/991 566/566/988 550/550/987 +f 561/561/993 569/569/994 559/559/995 +f 559/559/995 569/569/994 570/570/996 +f 562/562/997 571/571/998 572/572/999 +f 562/562/997 572/572/999 561/561/993 +f 561/561/993 572/572/999 569/569/994 +f 567/567/989 573/573/1000 565/565/990 +f 565/565/990 573/573/1000 574/574/1001 +f 565/565/990 574/574/1001 562/562/997 +f 562/562/997 574/574/1001 571/571/998 +f 555/555/1002 575/575/1003 576/576/1004 +f 555/555/1002 576/576/1004 553/553/991 +f 553/553/991 576/576/1004 568/568/992 +f 559/559/995 570/570/996 577/577/1005 +f 559/559/995 577/577/1005 557/557/1006 +f 557/557/1006 577/577/1005 575/575/1003 +f 557/557/1006 575/575/1003 555/555/1002 +f 538/538/1007 528/528/1008 567/567/1009 +f 567/567/1009 528/528/1008 573/573/1010 +f 573/573/1010 528/528/1008 527/527/1011 +f 573/573/1010 527/527/1011 574/574/1012 +f 527/527/1011 531/531/1013 574/574/1012 +f 574/574/1012 531/531/1013 571/571/1014 +f 531/531/1013 530/530/1015 571/571/1014 +f 571/571/1014 530/530/1015 572/572/1016 +f 530/530/1015 534/534/1017 572/572/1016 +f 572/572/1016 534/534/1017 569/569/1018 +f 569/569/1018 534/534/1017 570/570/1019 +f 570/570/1019 534/534/1017 533/533/1020 +f 570/570/1019 533/533/1020 544/544/1021 +f 570/570/1019 544/544/1021 577/577/1022 +f 544/544/1021 536/536/1023 577/577/1022 +f 577/577/1022 536/536/1023 575/575/1024 +f 575/575/1024 536/536/1023 535/535/1025 +f 575/575/1024 535/535/1025 576/576/1026 +f 535/535/1025 541/541/1027 576/576/1026 +f 576/576/1026 541/541/1027 568/568/1028 +f 541/541/1027 543/543/1029 568/568/1028 +f 568/568/1028 543/543/1029 540/540/1030 +f 568/568/1028 540/540/1030 566/566/1031 +f 566/566/1031 540/540/1030 538/538/1007 +f 566/566/1031 538/538/1007 567/567/1009 +f 537/537/310 532/532/310 578/578/310 +f 578/578/310 532/532/310 579/579/310 +f 542/542/1032 537/537/1032 580/580/1032 +f 580/580/1032 537/537/1032 578/578/1032 +f 539/539/1033 542/542/1034 581/581/1035 +f 581/581/1035 542/542/1034 580/580/1036 +f 526/526/642 539/539/642 582/582/642 +f 582/582/642 539/539/642 581/581/642 +f 529/529/1037 526/526/1038 583/583/1039 +f 583/583/1039 526/526/1038 582/582/1040 +f 532/532/1041 529/529/1041 579/579/1041 +f 579/579/1041 529/529/1041 583/583/1041 +f 582/582/497 581/581/497 583/583/496 +f 583/583/496 581/581/497 580/580/496 +f 583/583/496 580/580/496 579/579/500 +f 579/579/500 580/580/496 578/578/500 +f 551/551/960 547/547/1042 552/552/961 +f 552/552/1043 547/547/956 546/546/955 +f 552/552/1043 546/546/955 554/554/1044 +f 554/554/965 546/546/1045 556/556/967 +f 556/556/1046 546/546/955 545/545/954 +f 556/556/967 545/545/1047 558/558/969 +f 558/558/1048 545/545/1049 549/549/1050 +f 558/558/1048 549/549/1050 560/560/1051 +f 560/560/1052 549/549/1052 563/563/1052 +f 563/563/1053 549/549/1054 548/548/1055 +f 563/563/1053 548/548/1055 564/564/1056 +f 564/564/1057 548/548/1058 547/547/1059 +f 564/564/1057 547/547/1059 551/551/1060 +f 584/584/1061 585/585/1062 586/586/1063 +f 586/586/1063 585/585/1062 587/587/1064 +f 586/586/1065 587/587/1066 588/588/1067 +f 588/588/1067 587/587/1066 589/589/1068 +f 588/588/1069 589/589/1070 590/590/1071 +f 590/590/1071 589/589/1070 591/591/1072 +f 590/590/1073 591/591/1074 592/592/1075 +f 592/592/1075 591/591/1074 593/593/1076 +f 592/592/1077 593/593/1078 594/594/1079 +f 592/592/1077 594/594/1079 595/595/1080 +f 595/595/1081 594/594/1082 596/596/1083 +f 596/596/1083 594/594/1082 597/597/1084 +f 596/596/1085 597/597/1086 598/598/1087 +f 596/596/1085 598/598/1087 599/599/1088 +f 599/599/1089 598/598/1090 600/600/1091 +f 599/599/1089 600/600/1091 601/601/1092 +f 602/602/1093 601/601/1094 603/603/1095 +f 603/603/1095 601/601/1094 600/600/1096 +f 602/602/1097 603/603/1098 604/604/1099 +f 604/604/1099 603/603/1098 605/605/1100 +f 604/604/1101 605/605/1102 606/606/1103 +f 606/606/1103 605/605/1102 607/607/1104 +f 606/606/1105 607/607/1106 608/608/1107 +f 608/608/1107 607/607/1106 609/609/1108 +f 608/608/1109 609/609/1110 610/610/1111 +f 608/608/1109 610/610/1111 611/611/1112 +f 611/611/1113 610/610/1114 612/612/1115 +f 612/612/1115 610/610/1114 613/613/1116 +f 612/612/1117 613/613/1118 614/614/1119 +f 612/612/1117 614/614/1119 615/615/1120 +f 615/615/1121 614/614/1122 616/616/1123 +f 615/615/1121 616/616/1123 617/617/1124 +f 617/617/1124 616/616/1123 618/618/1125 +f 617/617/1124 618/618/1125 619/619/1126 +f 619/619/1126 618/618/1125 620/620/1127 +f 619/619/1126 620/620/1127 621/621/1128 +f 621/621/1128 620/620/1127 622/622/1129 +f 584/584/1130 621/621/1131 585/585/1132 +f 585/585/1132 621/621/1131 622/622/1133 +f 601/601/500 602/602/500 599/599/494 +f 621/621/500 584/584/1134 619/619/501 +f 619/619/501 584/584/1134 586/586/501 +f 599/599/494 604/604/1135 606/606/1136 +f 599/599/494 606/606/1136 596/596/1137 +f 599/599/494 602/602/500 604/604/1135 +f 590/590/500 615/615/1138 588/588/494 +f 595/595/496 611/611/1139 592/592/500 +f 596/596/1137 606/606/1136 608/608/495 +f 596/596/1137 608/608/495 595/595/496 +f 595/595/496 608/608/495 611/611/1139 +f 588/588/494 617/617/1140 586/586/501 +f 586/586/501 617/617/1140 619/619/501 +f 588/588/494 615/615/1138 617/617/1140 +f 592/592/500 612/612/1141 590/590/500 +f 590/590/500 612/612/1141 615/615/1138 +f 592/592/500 611/611/1139 612/612/1141 +f 603/603/1142 600/600/1143 598/598/1144 +f 597/597/1145 607/607/1145 605/605/1146 +f 597/597/1145 605/605/1146 598/598/1144 +f 594/594/1147 607/607/1145 597/597/1145 +f 598/598/1144 605/605/1146 603/603/1142 +f 594/594/1147 610/610/1146 609/609/1148 +f 594/594/1147 609/609/1148 607/607/1145 +f 593/593/1149 610/610/1146 594/594/1147 +f 591/591/1150 613/613/1146 593/593/1149 +f 593/593/1149 613/613/1146 610/610/1146 +f 591/591/1150 614/614/1150 613/613/1146 +f 589/589/1145 616/616/1145 614/614/1150 +f 589/589/1145 614/614/1150 591/591/1150 +f 622/622/1151 620/620/1152 585/585/1153 +f 585/585/1153 620/620/1152 587/587/1154 +f 587/587/1154 616/616/1145 589/589/1145 +f 620/620/1152 618/618/1155 587/587/1154 +f 587/587/1154 618/618/1155 616/616/1145 +f 623/623/1156 624/624/1157 625/625/1158 +f 626/626/1159 627/627/1160 628/628/1161 +f 629/629/1162 630/630/1163 631/631/1164 +f 631/631/1164 630/630/1163 632/632/1165 +f 625/625/1158 624/624/1157 633/633/1166 +f 625/625/1158 633/633/1166 634/634/1167 +f 634/634/1167 633/633/1166 635/635/1168 +f 636/636/1169 637/637/1170 629/629/1162 +f 636/636/1169 629/629/1162 631/631/1164 +f 634/634/1167 635/635/1168 638/638/1171 +f 634/634/1167 638/638/1171 636/636/1169 +f 636/636/1169 638/638/1171 637/637/1170 +f 626/626/1159 628/628/1161 639/639/1172 +f 639/639/1172 628/628/1161 640/640/1173 +f 631/631/1164 632/632/1165 626/626/1159 +f 626/626/1159 632/632/1165 627/627/1160 +f 639/639/1172 640/640/1173 623/623/1156 +f 639/639/1172 623/623/1156 625/625/1158 +f 641/641/1174 642/642/1175 643/643/1176 +f 643/643/1176 644/644/1177 641/641/1174 +f 643/643/1176 645/645/1178 646/646/1179 +f 642/642/1175 645/645/1178 643/643/1176 +f 647/647/1180 648/648/1181 649/649/1182 +f 649/649/1182 648/648/1181 650/650/1183 +f 649/649/1182 650/650/1183 651/651/1184 +f 651/651/1184 650/650/1183 652/652/1185 +f 651/651/1184 652/652/1185 653/653/1186 +f 653/653/1186 652/652/1185 654/654/1187 +f 653/653/1188 654/654/1189 655/655/1190 +f 653/653/1188 655/655/1190 656/656/1191 +f 656/656/1192 655/655/1193 657/657/1194 +f 657/657/1194 655/655/1193 658/658/1195 +f 657/657/1196 658/658/1197 659/659/1198 +f 657/657/1196 659/659/1198 660/660/1199 +f 660/660/1200 659/659/1201 661/661/1202 +f 660/660/1200 661/661/1202 662/662/1203 +f 662/662/1204 661/661/1205 663/663/1206 +f 662/662/1204 663/663/1206 647/647/1207 +f 647/647/1180 663/663/1208 648/648/1181 +f 649/649/1209 664/664/1210 647/647/1211 +f 647/647/1211 664/664/1210 665/665/1212 +f 651/651/1213 666/666/1214 649/649/1209 +f 649/649/1209 666/666/1214 667/667/1215 +f 649/649/1209 667/667/1215 664/664/1210 +f 657/657/1216 668/668/1217 669/669/1218 +f 657/657/1216 669/669/1218 656/656/1219 +f 660/660/1220 670/670/1221 671/671/1222 +f 660/660/1220 671/671/1222 657/657/1216 +f 657/657/1216 671/671/1222 668/668/1217 +f 647/647/1211 665/665/1212 662/662/1223 +f 662/662/1223 665/665/1212 672/672/1224 +f 662/662/1223 672/672/1224 670/670/1221 +f 662/662/1223 670/670/1221 660/660/1220 +f 653/653/1225 673/673/1226 651/651/1213 +f 651/651/1213 673/673/1226 666/666/1214 +f 656/656/1219 669/669/1218 674/674/1227 +f 656/656/1219 674/674/1227 653/653/1225 +f 653/653/1225 674/674/1227 673/673/1226 +f 665/665/1228 664/664/1229 633/633/1230 +f 633/633/1230 624/624/1231 665/665/1228 +f 665/665/1228 624/624/1231 672/672/1232 +f 672/672/1232 624/624/1231 623/623/1233 +f 672/672/1232 623/623/1233 670/670/1234 +f 670/670/1234 623/623/1233 640/640/1235 +f 670/670/1234 640/640/1235 671/671/1236 +f 640/640/1235 628/628/1237 671/671/1236 +f 671/671/1236 628/628/1237 668/668/1238 +f 628/628/1237 627/627/1239 668/668/1238 +f 668/668/1238 627/627/1239 669/669/1240 +f 627/627/1239 632/632/1241 669/669/1240 +f 669/669/1240 632/632/1241 674/674/1242 +f 632/632/1241 630/630/1243 674/674/1242 +f 674/674/1242 630/630/1243 673/673/1244 +f 673/673/1244 630/630/1243 629/629/1245 +f 673/673/1244 629/629/1245 637/637/1246 +f 673/673/1244 637/637/1246 666/666/1247 +f 637/637/1246 638/638/1248 666/666/1247 +f 666/666/1247 638/638/1248 667/667/1249 +f 638/638/1248 635/635/1250 667/667/1249 +f 667/667/1249 635/635/1250 633/633/1251 +f 667/667/1249 633/633/1251 664/664/1252 +f 631/631/409 626/626/409 675/675/409 +f 675/675/409 626/626/409 676/676/409 +f 636/636/907 631/631/907 677/677/907 +f 677/677/907 631/631/907 675/675/907 +f 634/634/908 636/636/909 678/678/910 +f 678/678/910 636/636/909 677/677/911 +f 625/625/496 634/634/496 679/679/496 +f 679/679/496 634/634/496 678/678/496 +f 639/639/903 625/625/904 680/680/1253 +f 680/680/1253 625/625/904 679/679/1254 +f 626/626/906 639/639/906 676/676/906 +f 676/676/906 639/639/906 680/680/906 +f 679/679/585 678/678/585 680/680/642 +f 680/680/642 678/678/585 677/677/642 +f 680/680/642 677/677/642 676/676/581 +f 676/676/581 677/677/642 675/675/581 +f 663/663/1255 642/642/1256 648/648/1257 +f 648/648/1257 642/642/1256 641/641/1258 +f 648/648/1259 641/641/1260 650/650/1261 +f 650/650/1261 641/641/1260 644/644/1262 +f 650/650/1183 644/644/1263 652/652/1185 +f 652/652/1264 644/644/1265 643/643/1266 +f 652/652/1264 643/643/1266 654/654/1267 +f 654/654/1189 643/643/1268 655/655/1190 +f 655/655/1269 643/643/1270 646/646/1271 +f 655/655/1269 646/646/1271 658/658/1272 +f 658/658/1272 646/646/1271 659/659/1273 +f 659/659/1273 646/646/1271 645/645/1274 +f 659/659/1275 645/645/1276 661/661/1277 +f 661/661/1277 645/645/1276 642/642/1256 +f 661/661/1277 642/642/1256 663/663/1255 +f 681/681/1278 682/682/1279 683/683/1280 +f 683/683/1280 682/682/1279 684/684/1281 +f 683/683/1282 684/684/1283 685/685/1284 +f 685/685/1284 684/684/1283 686/686/1285 +f 685/685/1286 686/686/1287 687/687/1288 +f 687/687/1288 686/686/1287 688/688/1289 +f 687/687/1290 688/688/1291 689/689/1292 +f 689/689/1292 688/688/1291 690/690/1293 +f 689/689/1294 690/690/1295 691/691/1296 +f 691/691/1296 690/690/1295 692/692/1297 +f 691/691/1298 692/692/1299 693/693/1300 +f 693/693/1300 692/692/1299 694/694/1301 +f 693/693/1302 694/694/1303 695/695/1304 +f 695/695/1304 694/694/1303 696/696/1305 +f 697/697/1306 695/695/1307 698/698/1308 +f 698/698/1308 695/695/1307 696/696/1309 +f 697/697/1310 698/698/1311 699/699/1312 +f 699/699/1312 698/698/1311 700/700/1313 +f 699/699/1314 700/700/1315 701/701/1316 +f 701/701/1316 700/700/1315 702/702/1317 +f 701/701/1318 702/702/1318 703/703/1318 +f 703/703/1319 702/702/1320 704/704/1321 +f 703/703/1319 704/704/1321 705/705/1322 +f 705/705/1323 704/704/1324 706/706/1325 +f 706/706/1325 704/704/1324 707/707/1326 +f 706/706/1325 707/707/1326 708/708/1327 +f 708/708/1327 707/707/1326 709/709/1328 +f 708/708/1327 709/709/1328 710/710/1329 +f 710/710/1330 709/709/1331 711/711/1332 +f 711/711/1332 709/709/1331 712/712/1333 +f 711/711/1334 712/712/1335 713/713/1336 +f 711/711/1334 713/713/1336 714/714/1337 +f 714/714/1338 713/713/1339 715/715/1340 +f 714/714/1338 715/715/1340 716/716/1341 +f 716/716/1341 715/715/1340 717/717/1342 +f 681/681/1343 716/716/1344 682/682/1345 +f 682/682/1345 716/716/1344 717/717/1346 +f 716/716/1142 681/681/1347 683/683/1348 +f 693/693/1349 701/701/1350 703/703/1351 +f 693/693/1349 703/703/1351 691/691/1352 +f 697/697/1353 699/699/1354 695/695/1353 +f 695/695/1353 699/699/1354 693/693/1349 +f 693/693/1349 699/699/1354 701/701/1350 +f 687/687/1145 710/710/1350 711/711/1355 +f 687/687/1145 711/711/1355 685/685/1356 +f 691/691/1352 705/705/1357 689/689/409 +f 689/689/409 705/705/1357 706/706/1358 +f 691/691/1352 703/703/1351 705/705/1357 +f 683/683/1348 714/714/1144 716/716/1142 +f 685/685/1356 711/711/1355 714/714/1144 +f 685/685/1356 714/714/1144 683/683/1348 +f 687/687/1145 708/708/1146 710/710/1350 +f 689/689/409 706/706/1358 708/708/1146 +f 689/689/409 708/708/1146 687/687/1145 +f 698/698/497 696/696/497 694/694/496 +f 698/698/497 694/694/496 700/700/496 +f 692/692/500 702/702/500 694/694/496 +f 702/702/500 700/700/496 694/694/496 +f 690/690/1139 704/704/502 692/692/500 +f 692/692/500 704/704/502 702/702/500 +f 690/690/1139 707/707/1359 704/704/502 +f 688/688/1360 709/709/1359 707/707/1359 +f 688/688/1360 707/707/1359 690/690/1139 +f 686/686/1361 712/712/1362 709/709/1359 +f 686/686/1361 709/709/1359 688/688/1360 +f 682/682/1363 717/717/1134 684/684/1137 +f 684/684/1137 717/717/1134 715/715/494 +f 684/684/1137 712/712/1362 686/686/1361 +f 715/715/494 713/713/1364 684/684/1137 +f 684/684/1137 713/713/1364 712/712/1362 +f 718/718/1365 719/719/1366 720/720/1367 +f 720/720/1367 719/719/1366 721/721/1368 +f 722/722/1369 723/723/1370 724/724/1371 +f 725/725/1372 726/726/1373 727/727/1374 +f 728/728/1375 729/729/1376 730/730/1377 +f 720/720/1367 721/721/1368 731/731/1378 +f 731/731/1378 721/721/1368 732/732/1379 +f 733/733/1380 729/729/1376 734/734/1381 +f 734/734/1381 729/729/1376 728/728/1375 +f 732/732/1379 735/735/1382 731/731/1378 +f 731/731/1378 735/735/1382 734/734/1381 +f 734/734/1381 735/735/1382 733/733/1380 +f 725/725/1372 727/727/1374 722/722/1369 +f 722/722/1369 727/727/1374 723/723/1370 +f 730/730/1377 736/736/1383 728/728/1375 +f 728/728/1375 736/736/1383 725/725/1372 +f 725/725/1372 736/736/1383 726/726/1373 +f 724/724/1371 718/718/1365 722/722/1369 +f 722/722/1369 718/718/1365 720/720/1367 +f 737/737/1384 738/738/1385 739/739/1386 +f 740/740/1387 738/738/1385 737/737/1384 +f 737/737/1384 741/741/1388 740/740/1387 +f 742/742/1389 741/741/1388 737/737/1384 +f 743/743/1390 744/744/1391 745/745/1392 +f 743/743/1390 745/745/1392 746/746/1393 +f 746/746/1394 745/745/1395 747/747/1396 +f 746/746/1394 747/747/1396 748/748/1397 +f 748/748/1397 747/747/1396 749/749/1398 +f 748/748/1397 749/749/1398 750/750/1399 +f 750/750/1399 749/749/1398 751/751/1400 +f 750/750/1399 751/751/1400 752/752/1401 +f 752/752/1401 751/751/1400 741/741/1402 +f 752/752/1401 741/741/1402 753/753/1403 +f 752/752/1401 753/753/1403 754/754/1404 +f 754/754/1405 753/753/1406 755/755/1407 +f 754/754/1405 755/755/1407 756/756/1408 +f 756/756/1409 755/755/1410 757/757/1411 +f 756/756/1409 757/757/1411 758/758/1412 +f 758/758/1412 757/757/1411 744/744/1413 +f 758/758/1412 744/744/1413 743/743/1414 +f 743/743/1415 759/759/1416 760/760/1417 +f 743/743/1415 760/760/1417 758/758/1418 +f 746/746/1419 761/761/1420 759/759/1416 +f 746/746/1419 759/759/1416 743/743/1415 +f 754/754/1421 762/762/1422 752/752/1423 +f 752/752/1423 762/762/1422 763/763/1424 +f 756/756/1425 764/764/1426 765/765/1427 +f 756/756/1425 765/765/1427 754/754/1421 +f 754/754/1421 765/765/1427 762/762/1422 +f 758/758/1418 760/760/1417 766/766/1428 +f 758/758/1418 766/766/1428 756/756/1425 +f 756/756/1425 766/766/1428 764/764/1426 +f 748/748/1429 767/767/1430 768/768/1431 +f 748/748/1429 768/768/1431 746/746/1419 +f 746/746/1419 768/768/1431 761/761/1420 +f 752/752/1423 763/763/1424 750/750/1432 +f 750/750/1432 763/763/1424 769/769/1433 +f 750/750/1432 769/769/1433 767/767/1430 +f 750/750/1432 767/767/1430 748/748/1429 +f 760/760/1434 721/721/1435 766/766/1436 +f 721/721/1435 719/719/1437 766/766/1436 +f 766/766/1436 719/719/1437 718/718/1438 +f 766/766/1436 718/718/1438 764/764/1439 +f 718/718/1438 724/724/1440 764/764/1439 +f 764/764/1439 724/724/1440 765/765/1441 +f 765/765/1441 724/724/1440 723/723/1442 +f 765/765/1441 723/723/1442 762/762/1443 +f 762/762/1443 723/723/1442 727/727/1444 +f 762/762/1443 727/727/1444 763/763/1445 +f 727/727/1444 726/726/1446 763/763/1445 +f 763/763/1445 726/726/1446 736/736/1447 +f 763/763/1445 736/736/1447 769/769/1448 +f 769/769/1448 736/736/1447 730/730/1449 +f 769/769/1448 730/730/1449 767/767/1450 +f 767/767/1450 730/730/1449 729/729/1451 +f 767/767/1450 729/729/1451 768/768/1452 +f 768/768/1452 729/729/1451 733/733/1453 +f 768/768/1452 733/733/1453 761/761/1454 +f 761/761/1454 733/733/1453 735/735/1455 +f 761/761/1454 735/735/1455 732/732/1456 +f 761/761/1454 732/732/1456 759/759/1457 +f 759/759/1457 732/732/1456 760/760/1434 +f 760/760/1434 732/732/1456 721/721/1435 +f 728/728/642 725/725/642 770/770/642 +f 770/770/642 725/725/642 771/771/642 +f 734/734/1037 728/728/1038 772/772/1039 +f 772/772/1039 728/728/1038 770/770/1458 +f 731/731/1041 734/734/1041 773/773/1041 +f 773/773/1041 734/734/1041 772/772/1041 +f 720/720/310 731/731/310 774/774/310 +f 774/774/310 731/731/310 773/773/310 +f 722/722/1032 720/720/1032 775/775/1032 +f 775/775/1032 720/720/1032 774/774/1032 +f 725/725/1033 722/722/1034 771/771/1035 +f 771/771/1035 722/722/1034 775/775/1036 +f 774/774/500 773/773/500 775/775/496 +f 775/775/496 773/773/500 772/772/496 +f 775/775/496 772/772/496 771/771/497 +f 771/771/497 772/772/496 770/770/497 +f 744/744/1391 739/739/1459 745/745/1392 +f 745/745/1460 739/739/1386 738/738/1385 +f 745/745/1460 738/738/1385 747/747/1461 +f 747/747/1462 738/738/1463 749/749/1464 +f 749/749/1464 738/738/1463 740/740/1465 +f 749/749/1464 740/740/1465 751/751/1466 +f 751/751/1466 740/740/1465 741/741/1467 +f 741/741/1468 742/742/1469 753/753/1470 +f 753/753/1470 742/742/1469 755/755/1471 +f 755/755/1471 742/742/1469 737/737/1472 +f 755/755/1410 737/737/1473 757/757/1411 +f 757/757/1474 737/737/1475 739/739/1476 +f 757/757/1474 739/739/1476 744/744/1477 +f 776/776/1478 777/777/1479 778/778/1480 +f 776/776/1478 778/778/1480 779/779/1481 +f 779/779/1482 778/778/1483 780/780/1484 +f 780/780/1484 778/778/1483 781/781/1485 +f 780/780/1486 781/781/1487 782/782/1488 +f 782/782/1488 781/781/1487 783/783/1489 +f 782/782/1490 783/783/1491 784/784/1492 +f 782/782/1490 784/784/1492 785/785/1493 +f 785/785/1494 784/784/1494 786/786/1494 +f 785/785/1495 786/786/1495 787/787/1495 +f 787/787/1496 786/786/1497 788/788/1498 +f 787/787/1496 788/788/1498 789/789/1499 +f 789/789/1499 788/788/1498 790/790/1500 +f 789/789/1501 790/790/1502 791/791/1503 +f 791/791/1503 790/790/1502 792/792/1504 +f 793/793/1505 791/791/1506 794/794/1507 +f 794/794/1507 791/791/1506 792/792/1508 +f 793/793/1509 794/794/1510 795/795/1511 +f 793/793/1509 795/795/1511 796/796/1512 +f 796/796/1513 795/795/1513 797/797/1513 +f 797/797/1514 795/795/1514 798/798/1514 +f 797/797/1515 798/798/1515 799/799/1515 +f 799/799/1516 798/798/1516 800/800/1516 +f 799/799/1517 800/800/1517 801/801/1517 +f 801/801/1518 800/800/1518 802/802/1518 +f 801/801/1519 802/802/1520 803/803/1521 +f 803/803/1521 802/802/1520 804/804/1522 +f 803/803/1521 804/804/1522 805/805/1523 +f 805/805/1523 804/804/1522 806/806/1524 +f 805/805/1523 806/806/1524 807/807/1525 +f 807/807/1526 806/806/1527 808/808/1528 +f 807/807/1526 808/808/1528 809/809/1529 +f 809/809/1530 808/808/1531 810/810/1532 +f 810/810/1532 808/808/1531 811/811/1533 +f 776/776/1534 810/810/1535 777/777/1536 +f 777/777/1536 810/810/1535 811/811/1537 +f 810/810/584 776/776/1538 779/779/1539 +f 789/789/584 797/797/584 787/787/1539 +f 787/787/1539 797/797/584 799/799/581 +f 791/791/1540 793/793/581 796/796/578 +f 791/791/1540 796/796/578 789/789/584 +f 789/789/584 796/796/578 797/797/584 +f 782/782/643 803/803/1541 805/805/1542 +f 782/782/643 805/805/1542 780/780/1543 +f 785/785/581 799/799/581 801/801/580 +f 787/787/1539 799/799/581 785/785/581 +f 779/779/1539 809/809/645 810/810/584 +f 780/780/1543 807/807/645 809/809/645 +f 780/780/1543 809/809/645 779/779/1539 +f 780/780/1543 805/805/1542 807/807/645 +f 782/782/643 801/801/580 803/803/1541 +f 785/785/581 801/801/580 782/782/643 +f 794/794/310 792/792/1544 795/795/1545 +f 795/795/1545 792/792/1544 790/790/310 +f 788/788/1546 798/798/1547 795/795/1545 +f 788/788/1546 795/795/1545 790/790/310 +f 786/786/794 798/798/1547 788/788/1546 +f 786/786/794 800/800/1548 798/798/1547 +f 784/784/1549 800/800/1548 786/786/794 +f 783/783/1546 802/802/798 784/784/1549 +f 784/784/1549 802/802/798 800/800/1548 +f 783/783/1546 804/804/792 802/802/798 +f 781/781/1550 806/806/1551 804/804/792 +f 781/781/1550 804/804/792 783/783/1546 +f 777/777/1552 811/811/1553 778/778/1554 +f 778/778/1554 811/811/1553 808/808/1554 +f 778/778/1554 808/808/1554 781/781/1550 +f 781/781/1550 808/808/1554 806/806/1551 +f 108/108/113 67/67/115 66/66/111 +f 5/5/5 22/22/22 7/7/7 +f 7/7/7 22/22/22 9/9/9 +f 4/4/4 5/5/5 7/7/7 +f 55/55/1555 40/40/40 23/23/23 +f 55/55/1555 23/23/23 24/24/24 +f 55/55/1555 24/24/24 25/25/25 +f 53/53/1556 55/55/1555 25/25/25 +f 25/25/25 41/41/41 53/53/1556 +f 1/1/1 3/3/3 21/21/21 +f 21/21/21 27/27/27 26/26/26 +f 21/21/21 26/26/26 1/1/1 +f 20/20/20 27/27/27 21/21/21 +f 4/4/4 6/6/6 12/12/12 +f 2/2/2 12/12/12 14/14/14 +f 3/3/3 2/2/2 14/14/14 +f 16/16/16 3/3/3 14/14/14 +f 12/12/12 2/2/2 4/4/4 +f 29/29/29 17/17/17 13/13/13 +f 52/52/52 48/48/48 19/19/19 +f 31/31/31 17/17/17 29/29/29 +f 17/17/17 31/31/31 52/52/52 +f 52/52/52 19/19/19 17/17/17 +f 10/10/10 62/62/62 61/61/61 +f 10/10/10 61/61/61 11/11/11 +f 34/34/34 11/11/11 61/61/61 +f 11/11/11 34/34/34 15/15/15 +f 33/33/33 37/37/37 44/44/1557 +f 32/32/32 46/46/1558 30/30/30 +f 46/46/1558 32/32/32 33/33/33 +f 44/44/1557 46/46/1558 33/33/33 +f 36/36/36 30/30/30 46/46/1558 diff --git a/examples/Cassie/urdf/meshes/agility/knee-spring.obj b/examples/Cassie/urdf/meshes/agility/knee-spring.obj new file mode 100644 index 0000000000..c5704d9a2a --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/knee-spring.obj @@ -0,0 +1,5643 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o knee-spring +v -0.000003 0.025000 0.000004 +v -0.000003 -0.025000 0.000004 +v 0.137997 -0.025000 0.000004 +v 0.137997 0.025000 0.000004 +v -0.000003 -0.025000 -0.008496 +v -0.000003 0.025000 -0.008496 +v 0.137997 0.025000 -0.008496 +v 0.137997 -0.025000 -0.008496 +v 0.129997 -0.018345 -0.014296 +v 0.128969 -0.018944 -0.014291 +v 0.129917 -0.017252 -0.014291 +v 0.129997 -0.020655 -0.014296 +v 0.129421 -0.021147 -0.014297 +v 0.133133 -0.022397 -0.014287 +v 0.131192 -0.022481 -0.014289 +v 0.131997 -0.021809 -0.014296 +v 0.131240 -0.016438 -0.014261 +v 0.131997 -0.017191 -0.014296 +v 0.133021 -0.016611 -0.014295 +v 0.133997 -0.020655 -0.014296 +v 0.134600 -0.021162 -0.014293 +v 0.133997 -0.018345 -0.014296 +v 0.134579 -0.017816 -0.014291 +v 0.135078 -0.019581 -0.014281 +v 0.129555 -0.021172 0.004983 +v 0.129565 -0.017787 0.004919 +v 0.129010 -0.019382 0.004919 +v 0.130461 -0.016978 0.004919 +v 0.131643 -0.016547 0.004919 +v 0.133166 -0.016765 0.004919 +v 0.134482 -0.017840 0.004919 +v 0.134984 -0.019618 0.004919 +v 0.134429 -0.021213 0.004919 +v 0.133104 -0.022276 0.004919 +v 0.131108 -0.022375 0.004912 +v 0.128987 -0.019136 -0.010996 +v 0.129660 -0.017544 -0.010996 +v 0.131256 -0.016544 -0.010996 +v 0.132979 -0.016631 -0.010996 +v 0.134506 -0.017740 -0.010996 +v 0.135036 -0.020034 -0.010996 +v 0.133757 -0.022009 -0.010996 +v 0.131299 -0.022529 -0.010996 +v 0.129318 -0.020988 -0.010996 +v 0.126969 -0.017876 -0.010996 +v 0.126731 -0.019924 -0.010996 +v 0.135758 -0.023260 -0.010996 +v 0.137227 -0.020540 -0.010996 +v 0.128868 -0.023793 -0.010996 +v 0.127294 -0.021907 -0.010996 +v 0.133621 -0.024528 -0.010996 +v 0.131387 -0.024761 -0.010996 +v 0.128496 -0.015444 -0.010996 +v 0.137024 -0.017876 -0.010996 +v 0.131387 -0.014239 -0.010996 +v 0.133621 -0.014472 -0.010996 +v 0.135757 -0.015740 -0.010996 +v 0.126804 -0.020439 -0.011659 +v 0.127339 -0.021941 -0.011699 +v 0.128659 -0.023624 -0.011672 +v 0.130038 -0.024354 -0.011801 +v 0.131483 -0.024732 -0.011696 +v 0.133001 -0.024673 -0.011691 +v 0.134287 -0.024184 -0.011823 +v 0.135273 -0.023629 -0.011707 +v 0.136398 -0.022401 -0.011673 +v 0.137200 -0.020406 -0.011685 +v 0.137173 -0.018507 -0.011687 +v 0.136480 -0.016750 -0.011767 +v 0.134958 -0.015128 -0.011697 +v 0.132590 -0.014227 -0.011685 +v 0.130255 -0.014533 -0.011755 +v 0.128610 -0.015476 -0.011686 +v 0.127626 -0.016552 -0.011666 +v 0.126798 -0.018620 -0.011724 +v 0.136399 -0.019725 -0.013129 +v 0.136494 -0.018349 -0.012800 +v 0.135639 -0.018173 -0.013670 +v 0.135448 -0.016700 -0.013069 +v 0.134068 -0.016415 -0.013779 +v 0.134573 -0.015720 -0.012896 +v 0.133319 -0.014899 -0.012604 +v 0.132675 -0.015470 -0.013458 +v 0.131368 -0.014946 -0.012894 +v 0.129600 -0.015518 -0.012820 +v 0.129210 -0.016644 -0.013557 +v 0.128047 -0.016764 -0.012620 +v 0.128375 -0.017807 -0.013567 +v 0.127547 -0.018498 -0.012936 +v 0.128218 -0.020001 -0.013732 +v 0.127492 -0.020594 -0.012847 +v 0.128705 -0.021430 -0.013676 +v 0.128147 -0.022265 -0.012667 +v 0.129883 -0.022476 -0.013871 +v 0.129254 -0.022982 -0.013072 +v 0.131135 -0.023876 -0.013097 +v 0.131782 -0.023447 -0.013601 +v 0.133201 -0.023736 -0.013139 +v 0.134541 -0.023095 -0.013075 +v 0.135412 -0.022254 -0.013167 +v 0.135686 -0.020955 -0.013580 +v 0.136469 -0.021333 -0.012528 +v 0.129997 -0.020655 -0.011996 +v 0.129997 -0.018345 -0.011996 +v 0.131997 -0.021809 -0.011996 +v 0.133997 -0.020655 -0.011996 +v 0.133997 -0.018345 -0.011996 +v 0.131997 -0.017191 -0.011996 +v 0.135201 -0.030040 0.009184 +v 0.135944 -0.030324 0.008132 +v 0.136767 -0.030025 0.007502 +v 0.134904 -0.030375 0.009104 +v 0.136626 -0.030260 0.007015 +v 0.137305 -0.030025 0.005323 +v 0.137014 -0.030317 0.005537 +v 0.136969 -0.030280 0.004189 +v 0.137134 -0.030026 0.003498 +v 0.136534 -0.030321 0.002802 +v 0.134557 -0.030024 0.000320 +v 0.135737 -0.030311 0.001637 +v 0.134743 -0.030277 0.000772 +v 0.132135 -0.030307 -0.000040 +v 0.132299 -0.030031 -0.000336 +v 0.133686 -0.030282 0.000249 +v 0.132028 -0.029000 0.000906 +v 0.133804 -0.029000 -0.002335 +v 0.129796 -0.029000 -0.002293 +v 0.129012 -0.029000 0.002163 +v 0.126791 -0.029000 -0.000436 +v 0.127995 -0.029000 0.004537 +v 0.124449 -0.029000 0.004604 +v 0.128315 -0.029000 0.006756 +v 0.125243 -0.029000 0.001646 +v 0.134600 -0.029000 0.001891 +v 0.136561 -0.029000 -0.001001 +v 0.138868 -0.030000 0.001853 +v 0.138584 -0.029000 0.001297 +v 0.139499 -0.029000 0.004221 +v 0.139538 -0.030000 0.004841 +v 0.137040 -0.030000 -0.000605 +v 0.134184 -0.030000 -0.002251 +v 0.130290 0.019097 0.010848 +v 0.127374 0.015073 0.008917 +v 0.136155 0.016205 0.009407 +v 0.133547 0.019116 0.010863 +v 0.129018 -0.017987 0.010268 +v 0.134213 -0.018675 0.010626 +v 0.136636 -0.015032 0.008898 +v 0.126178 -0.006365 0.006487 +v 0.137915 -0.002342 0.006008 +v 0.126066 0.001029 0.005931 +v 0.137860 0.005372 0.006312 +v 0.134256 -0.030000 0.012186 +v 0.132307 -0.029000 0.012540 +v 0.131447 -0.030000 0.012543 +v 0.135504 -0.029000 0.011720 +v 0.137141 -0.030000 0.010595 +v 0.138002 -0.029000 0.009568 +v 0.139068 -0.030000 0.007628 +v 0.139260 -0.029000 0.007037 +v 0.125997 -0.029000 0.000004 +v 0.137997 0.029000 0.000004 +v 0.137997 -0.029000 0.000004 +v 0.125997 0.029000 0.000004 +v 0.137686 -0.008852 0.006957 +v 0.126867 -0.013334 0.008234 +v 0.137402 0.011398 0.007642 +v 0.131623 -0.019430 0.011039 +v 0.126317 0.008971 0.006981 +v 0.132311 0.029000 0.011068 +v 0.135720 0.029000 0.009835 +v 0.126811 0.029000 0.008273 +v 0.126016 0.029000 0.005591 +v 0.126025 -0.029000 0.005651 +v 0.137892 -0.029000 0.006299 +v 0.137968 0.029000 0.005651 +v 0.129604 -0.029000 0.010536 +v 0.137554 0.029000 0.007343 +v 0.129483 0.029000 0.010487 +v 0.126440 -0.029000 0.007342 +v 0.127691 -0.029000 0.009220 +v 0.132454 -0.029000 0.011062 +v 0.136150 -0.029000 0.009534 +v 0.135939 -0.030032 0.001453 +v 0.136511 -0.033500 0.007221 +v 0.137053 -0.033504 0.004980 +v 0.124586 -0.030000 0.006582 +v 0.124742 -0.030000 0.002817 +v 0.126693 -0.030000 -0.000408 +v 0.130182 -0.030000 -0.002374 +v 0.128607 -0.029000 0.011830 +v 0.128075 -0.030000 0.011487 +v 0.125242 -0.029000 0.008533 +v 0.125864 -0.030000 0.009372 +v 0.135366 -0.033505 0.001233 +v 0.132955 -0.033497 0.000035 +v 0.136575 -0.033500 0.002949 +v 0.132378 -0.034000 0.009045 +v 0.134557 -0.034001 0.009067 +v 0.131201 -0.034001 0.009762 +v 0.134744 -0.034000 0.008017 +v 0.129860 -0.034000 0.008476 +v 0.127997 -0.034002 0.007743 +v 0.128067 -0.034000 0.006165 +v 0.127260 -0.034001 0.004212 +v 0.136309 -0.034000 0.006999 +v 0.136024 -0.034000 0.005541 +v 0.129530 -0.034000 0.001782 +v 0.130794 -0.034000 0.000421 +v 0.131444 -0.034000 0.001013 +v 0.128723 -0.034000 0.001517 +v 0.128210 -0.034000 0.003589 +v 0.136752 -0.034001 0.004330 +v 0.135793 -0.034000 0.003516 +v 0.134919 -0.033502 0.009156 +v 0.133921 -0.030254 0.009678 +v 0.132499 -0.030257 0.010038 +v 0.132195 -0.033504 0.010057 +v 0.130947 -0.030366 0.009919 +v 0.129580 -0.033498 0.009450 +v 0.129697 -0.030301 0.009484 +v 0.128335 -0.030316 0.008476 +v 0.127879 -0.033503 0.007889 +v 0.127429 -0.030311 0.007131 +v 0.127106 -0.033502 0.006170 +v 0.127002 -0.030333 0.005694 +v 0.127044 -0.030033 0.006878 +v 0.126720 -0.030036 0.005334 +v 0.134413 -0.029000 0.008265 +v 0.131966 -0.029000 0.009081 +v 0.135973 -0.029000 0.005995 +v 0.135772 -0.029000 0.003595 +v 0.129829 -0.029000 0.008400 +v 0.135356 -0.034000 0.001599 +v 0.133837 -0.034000 0.001343 +v 0.132961 -0.034000 0.000337 +v 0.130185 -0.030029 0.010044 +v 0.132913 -0.030018 0.010318 +v 0.128177 -0.030037 0.008677 +v 0.127464 -0.030021 0.002141 +v 0.126860 -0.030048 0.003930 +v 0.129231 -0.030019 0.000372 +v 0.127073 -0.033506 0.003859 +v 0.127036 -0.030343 0.004201 +v 0.127394 -0.030291 0.002958 +v 0.128138 -0.030271 0.001737 +v 0.128229 -0.033501 0.001653 +v 0.129461 -0.030271 0.000627 +v 0.130280 -0.033504 0.000248 +v 0.130856 -0.030263 0.000092 +v 0.126120 0.024918 -0.010996 +v 0.126100 0.024897 -0.008496 +v 0.137882 0.024900 -0.008496 +v 0.137899 0.024881 -0.010996 +v 0.137893 -0.024894 -0.008496 +v 0.137872 -0.024914 -0.010996 +v 0.126111 -0.024903 -0.008496 +v 0.126094 -0.024886 -0.010996 +v 0.128831 -0.008560 -0.014259 +v 0.129554 -0.006568 -0.014293 +v 0.129997 -0.007345 -0.014296 +v 0.135025 -0.009104 -0.014280 +v 0.134281 -0.010558 -0.014299 +v 0.133997 -0.009655 -0.014296 +v 0.131997 -0.010809 -0.014296 +v 0.131742 -0.011586 -0.014298 +v 0.129934 -0.010767 -0.014287 +v 0.129997 -0.009655 -0.014296 +v 0.129047 -0.009311 -0.014295 +v 0.131333 -0.005533 -0.014296 +v 0.132997 -0.005625 -0.014292 +v 0.131997 -0.006191 -0.014296 +v 0.134429 -0.006626 -0.014292 +v 0.135070 -0.007797 -0.014247 +v 0.133997 -0.007345 -0.014296 +v 0.130066 -0.010714 0.004990 +v 0.129549 -0.006750 0.004911 +v 0.129021 -0.008521 0.004922 +v 0.131337 -0.005567 0.004920 +v 0.133167 -0.005765 0.004919 +v 0.134145 -0.006472 0.004919 +v 0.134812 -0.007540 0.004919 +v 0.134931 -0.008911 0.004919 +v 0.134429 -0.010213 0.004919 +v 0.133074 -0.011286 0.004929 +v 0.131399 -0.011415 0.004922 +v 0.129362 -0.009904 0.004902 +v 0.128987 -0.008136 -0.010996 +v 0.129660 -0.006544 -0.010996 +v 0.131256 -0.005544 -0.010996 +v 0.133444 -0.005775 -0.010996 +v 0.134859 -0.007454 -0.010996 +v 0.134953 -0.009177 -0.010996 +v 0.133659 -0.011157 -0.010996 +v 0.131160 -0.011430 -0.010996 +v 0.129382 -0.010137 -0.010996 +v 0.126969 -0.006876 -0.010996 +v 0.126766 -0.009540 -0.010996 +v 0.136700 -0.010906 -0.010996 +v 0.135421 -0.012524 -0.010996 +v 0.128496 -0.012556 -0.010996 +v 0.137315 -0.008500 -0.010996 +v 0.133621 -0.013528 -0.010996 +v 0.131387 -0.013761 -0.010996 +v 0.128496 -0.004444 -0.010996 +v 0.136700 -0.006094 -0.010996 +v 0.131387 -0.003239 -0.010996 +v 0.133621 -0.003472 -0.010996 +v 0.135422 -0.004477 -0.010996 +v 0.126758 -0.008930 -0.011736 +v 0.127269 -0.010887 -0.011723 +v 0.128463 -0.012395 -0.011738 +v 0.129836 -0.013283 -0.011799 +v 0.131511 -0.013735 -0.011696 +v 0.133523 -0.013582 -0.011692 +v 0.135720 -0.012248 -0.011695 +v 0.136709 -0.010807 -0.011771 +v 0.137279 -0.008884 -0.011664 +v 0.137023 -0.006961 -0.011716 +v 0.136372 -0.005638 -0.011865 +v 0.135375 -0.004496 -0.011763 +v 0.133962 -0.003581 -0.011666 +v 0.131766 -0.003223 -0.011675 +v 0.129817 -0.003746 -0.011852 +v 0.128410 -0.004621 -0.011654 +v 0.127626 -0.005608 -0.011783 +v 0.126859 -0.007350 -0.011701 +v 0.136173 -0.009547 -0.013244 +v 0.136246 -0.007431 -0.013153 +v 0.136796 -0.008978 -0.012575 +v 0.135332 -0.006038 -0.013398 +v 0.134508 -0.004542 -0.012771 +v 0.134142 -0.005356 -0.013732 +v 0.133349 -0.004217 -0.013055 +v 0.132124 -0.004781 -0.013802 +v 0.131356 -0.003943 -0.012888 +v 0.130376 -0.004847 -0.013557 +v 0.129057 -0.005654 -0.013474 +v 0.128778 -0.005125 -0.012746 +v 0.127777 -0.006853 -0.012983 +v 0.127573 -0.008025 -0.013057 +v 0.127589 -0.009284 -0.013006 +v 0.128569 -0.010148 -0.013745 +v 0.128070 -0.011014 -0.012826 +v 0.129443 -0.011872 -0.013303 +v 0.130915 -0.012071 -0.013804 +v 0.130643 -0.012884 -0.012865 +v 0.132112 -0.012913 -0.013119 +v 0.133321 -0.012080 -0.013722 +v 0.133413 -0.012906 -0.012803 +v 0.134665 -0.012457 -0.012614 +v 0.134418 -0.011554 -0.013650 +v 0.135512 -0.010860 -0.013338 +v 0.129997 -0.009655 -0.011996 +v 0.129997 -0.007345 -0.011996 +v 0.131997 -0.010809 -0.011996 +v 0.133997 -0.009655 -0.011996 +v 0.133997 -0.007345 -0.011996 +v 0.131997 -0.006191 -0.011996 +v 0.132640 -0.024499 0.007202 +v 0.134122 -0.024499 0.005999 +v 0.130812 -0.024497 0.007020 +v 0.129706 -0.024498 0.005301 +v 0.130438 -0.024494 0.003230 +v 0.132943 -0.024494 0.002840 +v 0.134144 -0.024500 0.004257 +v 0.131754 -0.025251 0.008040 +v 0.130245 -0.025248 0.007468 +v 0.131362 -0.034500 0.008044 +v 0.129371 -0.034500 0.006581 +v 0.129135 -0.025249 0.006092 +v 0.128974 -0.034500 0.004770 +v 0.129195 -0.025251 0.003692 +v 0.129645 -0.034500 0.003042 +v 0.130645 -0.025248 0.002300 +v 0.131526 -0.034500 0.001977 +v 0.132382 -0.025249 0.001966 +v 0.133641 -0.034500 0.002419 +v 0.134472 -0.025251 0.003147 +v 0.134732 -0.034500 0.003724 +v 0.135032 -0.034500 0.005403 +v 0.135018 -0.025247 0.005083 +v 0.134532 -0.025253 0.006710 +v 0.133910 -0.034500 0.007422 +v 0.133265 -0.025250 0.007744 +v 0.129757 -0.034500 0.011535 +v 0.133933 -0.034500 0.011632 +v 0.127222 -0.034500 0.009872 +v 0.125328 -0.034500 0.003215 +v 0.125517 -0.034500 0.007388 +v 0.132392 -0.034500 -0.001890 +v 0.138321 -0.034500 0.007670 +v 0.136711 -0.034500 0.009948 +v 0.136295 -0.034500 -0.000400 +v 0.138438 -0.034500 0.002636 +v 0.128991 -0.034500 -0.001147 +v 0.126957 -0.034500 0.000393 +v 0.138814 -0.034500 0.005171 +v 0.134151 -0.035325 -0.001533 +v 0.132091 -0.035329 -0.000176 +v 0.130207 -0.035325 -0.001665 +v 0.137857 -0.035325 0.008657 +v 0.137154 -0.035328 0.005289 +v 0.138859 -0.035325 0.005078 +v 0.136494 -0.035326 0.002404 +v 0.138365 -0.035325 0.002564 +v 0.137063 -0.035325 0.000375 +v 0.134640 -0.035327 0.000585 +v 0.130074 -0.035325 0.011592 +v 0.129861 -0.035329 0.009679 +v 0.131178 -0.035343 0.010092 +v 0.132629 -0.035325 0.011794 +v 0.129107 -0.035327 0.000741 +v 0.126899 -0.035325 0.009661 +v 0.135088 -0.035325 0.011131 +v 0.133143 -0.035328 0.010011 +v 0.134867 -0.035325 0.009268 +v 0.136511 -0.035327 0.007487 +v 0.125263 -0.035325 0.006328 +v 0.127821 -0.035336 0.008064 +v 0.127208 -0.035325 0.000112 +v 0.125460 -0.035325 0.002850 +v 0.127501 -0.035327 0.002464 +v 0.126861 -0.035326 0.005297 +v 0.132827 -0.037794 0.007959 +v 0.131997 -0.037794 0.007323 +v 0.133164 -0.037800 0.007026 +v 0.130460 -0.037791 0.007669 +v 0.130829 -0.037800 0.007026 +v 0.134985 -0.037786 0.005836 +v 0.134077 -0.037776 0.003926 +v 0.134875 -0.037790 0.003825 +v 0.131498 -0.037778 0.008057 +v 0.134081 -0.037789 0.007264 +v 0.134017 -0.037792 0.006154 +v 0.132110 -0.037778 0.002660 +v 0.133551 -0.037797 0.002350 +v 0.130829 -0.037800 0.002982 +v 0.130531 -0.037798 0.002313 +v 0.129977 -0.037792 0.003854 +v 0.131893 -0.037797 0.001971 +v 0.129342 -0.037797 0.003536 +v 0.129917 -0.037775 0.006075 +v 0.128934 -0.037799 0.005018 +v 0.129245 -0.037788 0.006450 +v 0.128183 -0.037123 0.004144 +v 0.129426 -0.037328 0.002377 +v 0.132753 -0.037238 0.001317 +v 0.134918 -0.037012 0.002246 +v 0.135664 -0.037289 0.004407 +v 0.135481 -0.036974 0.007058 +v 0.133391 -0.036891 0.008919 +v 0.130769 -0.037179 0.001376 +v 0.133684 -0.036687 0.001021 +v 0.132049 -0.036710 0.009296 +v 0.130586 -0.036833 0.008938 +v 0.129144 -0.036582 0.008377 +v 0.127748 -0.036733 0.005415 +v 0.128210 -0.036738 0.003021 +v 0.131882 -0.036676 0.000677 +v 0.136336 -0.036613 0.005420 +v 0.135216 -0.036402 0.008216 +v 0.127881 -0.036479 0.006809 +v 0.135837 -0.036278 0.002468 +v 0.136300 -0.036511 0.003835 +v 0.130108 -0.036361 0.000843 +v 0.134770 -0.036265 0.001292 +v 0.134053 -0.036255 0.009148 +v 0.128760 -0.036313 0.001757 +v 0.136397 -0.036102 0.006702 +v 0.127327 -0.036015 0.004059 +v 0.133997 -0.037473 0.005153 +v 0.132960 -0.037457 0.006757 +v 0.131034 -0.037457 0.006757 +v 0.129997 -0.037473 0.004855 +v 0.130942 -0.037468 0.003304 +v 0.133088 -0.037466 0.003325 +v 0.133997 -0.035490 0.006159 +v 0.131997 -0.035490 0.007313 +v 0.133997 -0.035490 0.003849 +v 0.129997 -0.035490 0.006159 +v 0.131997 -0.035490 0.002695 +v 0.129997 -0.035490 0.003849 +v 0.124558 0.030000 0.003662 +v 0.124536 0.029000 0.006111 +v 0.124742 0.030000 0.007191 +v 0.125365 0.029000 0.008569 +v 0.126388 0.030000 0.010047 +v 0.126954 0.029000 0.010613 +v 0.129058 0.030000 0.011988 +v 0.129809 0.029000 0.012259 +v 0.132307 0.030000 0.012540 +v 0.133104 0.029000 0.012465 +v 0.134835 0.030000 0.011978 +v 0.136192 0.029000 0.011313 +v 0.137226 0.030000 0.010462 +v 0.138451 0.029000 0.008907 +v 0.138839 0.030000 0.008145 +v 0.139486 0.029000 0.006026 +v 0.139612 0.030000 0.004687 +v 0.139260 0.029000 0.002970 +v 0.138452 0.030000 0.001101 +v 0.138002 0.029000 0.000439 +v 0.136379 0.030000 -0.001155 +v 0.135704 0.029000 -0.001583 +v 0.133570 0.030000 -0.002373 +v 0.132074 0.029000 -0.002594 +v 0.129796 0.030000 -0.002293 +v 0.127778 0.029000 -0.001343 +v 0.126094 0.030000 0.000220 +v 0.124853 0.029000 0.002349 +v 0.132828 0.029000 0.001048 +v 0.134950 0.029000 0.002193 +v 0.130935 0.029000 0.001117 +v 0.129272 0.029000 0.002018 +v 0.135762 0.029000 0.006406 +v 0.134732 0.029000 0.008003 +v 0.136028 0.029000 0.004536 +v 0.132891 0.029000 0.008933 +v 0.130996 0.029000 0.008921 +v 0.128234 0.029000 0.006481 +v 0.128026 0.029000 0.004079 +v 0.129331 0.029000 0.008025 +v 0.128059 0.034000 0.005920 +v 0.129369 0.034000 0.008148 +v 0.131965 0.034000 0.009063 +v 0.134271 0.034000 0.008366 +v 0.135515 0.034000 0.006946 +v 0.136088 0.034000 0.004771 +v 0.135084 0.034000 0.002394 +v 0.133392 0.034000 0.001210 +v 0.130986 0.034000 0.001054 +v 0.129213 0.034000 0.002106 +v 0.128158 0.034000 0.003686 +v 0.130484 0.034001 0.000424 +v 0.128184 0.034000 0.002169 +v 0.133730 0.034000 0.000546 +v 0.127322 0.034000 0.004155 +v 0.127680 0.034002 0.007209 +v 0.136650 0.034000 0.006033 +v 0.136314 0.034002 0.002799 +v 0.130599 0.034001 0.009621 +v 0.135687 0.034000 0.007976 +v 0.133839 0.034000 0.009418 +v 0.127139 0.033507 0.003664 +v 0.126962 0.030298 0.005101 +v 0.127102 0.033510 0.006333 +v 0.127079 0.030274 0.003892 +v 0.127512 0.030374 0.002743 +v 0.127994 0.033501 0.001978 +v 0.128438 0.030278 0.001411 +v 0.129912 0.033499 0.000350 +v 0.129770 0.030293 0.000480 +v 0.130892 0.030281 0.000088 +v 0.132088 0.030242 -0.000048 +v 0.132966 0.033504 0.000041 +v 0.133396 0.030354 0.000178 +v 0.134472 0.030251 0.000607 +v 0.135686 0.033498 0.001483 +v 0.135567 0.030265 0.001425 +v 0.136628 0.030365 0.002984 +v 0.136996 0.033508 0.004255 +v 0.137043 0.030261 0.004854 +v 0.136946 0.030263 0.005965 +v 0.136836 0.033500 0.006334 +v 0.136446 0.030262 0.007436 +v 0.135673 0.033508 0.008532 +v 0.135325 0.030286 0.008790 +v 0.134133 0.030280 0.009578 +v 0.133157 0.033501 0.009912 +v 0.132842 0.030316 0.009962 +v 0.131027 0.033497 0.009940 +v 0.131510 0.030266 0.010027 +v 0.130391 0.030328 0.009773 +v 0.128742 0.033501 0.008901 +v 0.129126 0.030268 0.009152 +v 0.128080 0.030261 0.008188 +v 0.127232 0.030321 0.006695 +v 0.128567 0.030049 0.001026 +v 0.129970 0.030030 0.000084 +v 0.127279 0.030042 0.002616 +v 0.126664 0.030017 0.004434 +v 0.132027 0.030026 -0.000341 +v 0.134330 0.030023 0.000180 +v 0.135989 0.030019 0.001400 +v 0.136971 0.030045 0.003294 +v 0.137399 0.030017 0.005489 +v 0.126930 0.030031 0.006693 +v 0.133461 0.030045 0.010079 +v 0.131502 0.030034 0.010276 +v 0.130064 0.030037 0.009916 +v 0.136781 0.030028 0.007318 +v 0.135626 0.030040 0.008845 +v 0.128397 0.030046 0.008843 +v 0.133556 0.024494 0.003230 +v 0.134285 0.024497 0.005421 +v 0.132724 0.024498 0.007277 +v 0.131409 0.024498 0.002770 +v 0.129890 0.024497 0.004018 +v 0.130092 0.024492 0.006433 +v 0.132703 0.025248 0.007984 +v 0.134328 0.025247 0.006949 +v 0.132941 0.034500 0.007963 +v 0.134686 0.034500 0.006436 +v 0.134974 0.025253 0.005547 +v 0.135016 0.034500 0.004926 +v 0.134864 0.025247 0.004006 +v 0.134538 0.034500 0.003294 +v 0.133713 0.025249 0.002468 +v 0.132777 0.034500 0.002042 +v 0.131997 0.025253 0.001978 +v 0.131079 0.034500 0.002127 +v 0.130501 0.025247 0.002362 +v 0.129531 0.034500 0.003153 +v 0.129403 0.025253 0.003446 +v 0.128941 0.025247 0.005171 +v 0.128969 0.034500 0.005084 +v 0.129398 0.034500 0.006565 +v 0.129665 0.025247 0.006949 +v 0.130635 0.034500 0.007729 +v 0.130929 0.025253 0.007836 +v 0.132629 0.034500 0.011905 +v 0.128132 0.034500 0.010756 +v 0.136270 0.034500 0.010374 +v 0.138838 0.034500 0.005546 +v 0.138030 0.034500 0.008209 +v 0.132071 0.034500 -0.001858 +v 0.125673 0.034500 0.007670 +v 0.136917 0.034500 0.000191 +v 0.138457 0.034500 0.002783 +v 0.129122 0.034500 -0.001209 +v 0.134560 0.034500 -0.001315 +v 0.126400 0.034500 0.000960 +v 0.125156 0.034500 0.004462 +v 0.128951 0.035325 -0.001221 +v 0.132508 0.035326 -0.000121 +v 0.132164 0.035325 -0.001813 +v 0.125134 0.035325 0.005078 +v 0.126885 0.035326 0.005437 +v 0.127059 0.035330 0.003494 +v 0.126245 0.035325 0.008869 +v 0.127660 0.035327 0.007803 +v 0.125961 0.035325 0.001697 +v 0.128358 0.035335 0.001318 +v 0.130417 0.035328 0.000120 +v 0.134576 0.035325 0.011346 +v 0.132512 0.035328 0.010117 +v 0.132067 0.035325 0.011835 +v 0.135106 0.035325 -0.001162 +v 0.134278 0.035328 0.000414 +v 0.137681 0.035325 0.001189 +v 0.136452 0.035329 0.002468 +v 0.138880 0.035325 0.004457 +v 0.137063 0.035357 0.004007 +v 0.136711 0.035325 0.009948 +v 0.135080 0.035326 0.009169 +v 0.138210 0.035325 0.007878 +v 0.136662 0.035330 0.007148 +v 0.129331 0.035325 0.011328 +v 0.129993 0.035326 0.009775 +v 0.135561 0.035329 0.001290 +v 0.137069 0.035327 0.005799 +v 0.130895 0.037788 0.007890 +v 0.132001 0.037790 0.007325 +v 0.130829 0.037800 0.007026 +v 0.132879 0.037801 0.007968 +v 0.133164 0.037800 0.007026 +v 0.132594 0.037803 0.001951 +v 0.130829 0.037800 0.002982 +v 0.131997 0.037790 0.002683 +v 0.129423 0.037794 0.006669 +v 0.129987 0.037787 0.006167 +v 0.133165 0.037800 0.002982 +v 0.134857 0.037801 0.003830 +v 0.134007 0.037792 0.003846 +v 0.129662 0.037800 0.005004 +v 0.128920 0.037802 0.004621 +v 0.129989 0.037792 0.003842 +v 0.130181 0.037800 0.002548 +v 0.134332 0.037800 0.005004 +v 0.134005 0.037794 0.006163 +v 0.134999 0.037794 0.005740 +v 0.134339 0.037772 0.007043 +v 0.129622 0.037359 0.007749 +v 0.130743 0.037095 0.008780 +v 0.134136 0.037150 0.008236 +v 0.134068 0.037333 0.001992 +v 0.130709 0.036973 0.001136 +v 0.128979 0.037136 0.002509 +v 0.128185 0.037218 0.004889 +v 0.128302 0.037053 0.006441 +v 0.132503 0.037256 0.001266 +v 0.127819 0.036621 0.003695 +v 0.132698 0.036973 0.009016 +v 0.135533 0.037132 0.006678 +v 0.136254 0.036759 0.005163 +v 0.135208 0.037197 0.002992 +v 0.128425 0.036563 0.007612 +v 0.135979 0.036674 0.003291 +v 0.129349 0.036335 0.001273 +v 0.135190 0.036350 0.001770 +v 0.133557 0.036469 0.000779 +v 0.131843 0.036303 0.000413 +v 0.127442 0.036298 0.005785 +v 0.129219 0.036109 0.008823 +v 0.134981 0.036325 0.008490 +v 0.131056 0.036077 0.009669 +v 0.133826 0.036140 0.009318 +v 0.135995 0.036355 0.007235 +v 0.129997 0.037466 0.004898 +v 0.131126 0.037473 0.006810 +v 0.133126 0.037473 0.006662 +v 0.133997 0.037466 0.005110 +v 0.133089 0.037466 0.003325 +v 0.130997 0.037473 0.003272 +v 0.129997 0.035490 0.006159 +v 0.131997 0.035490 0.007313 +v 0.129997 0.035490 0.003849 +v 0.133997 0.035490 0.006159 +v 0.131997 0.035490 0.002695 +v 0.133997 0.035490 0.003849 +v 0.133949 0.021881 -0.014286 +v 0.134955 0.020225 -0.014296 +v 0.133997 0.020655 -0.014296 +v 0.131997 0.021809 -0.014296 +v 0.132035 0.022573 -0.014291 +v 0.129997 0.020655 -0.014296 +v 0.129058 0.020310 -0.014292 +v 0.130228 0.022005 -0.014297 +v 0.132899 0.016561 -0.014287 +v 0.131997 0.017191 -0.014296 +v 0.133997 0.018345 -0.014296 +v 0.134749 0.018075 -0.014296 +v 0.131726 0.016449 -0.014288 +v 0.129895 0.017248 -0.014295 +v 0.129997 0.018345 -0.014296 +v 0.129059 0.018710 -0.014294 +v 0.129615 0.021263 0.004989 +v 0.134784 0.018489 0.004923 +v 0.134954 0.019710 0.004923 +v 0.134027 0.017318 0.004909 +v 0.132651 0.016592 0.004909 +v 0.131151 0.016651 0.004930 +v 0.129699 0.017589 0.004919 +v 0.129082 0.019002 0.004930 +v 0.132097 0.022463 0.004923 +v 0.130903 0.022248 0.004930 +v 0.133445 0.022105 0.004909 +v 0.134561 0.021001 0.004929 +v 0.134927 0.020399 -0.010996 +v 0.134902 0.018675 -0.010996 +v 0.134010 0.017189 -0.010996 +v 0.132425 0.016510 -0.010996 +v 0.130397 0.016835 -0.010996 +v 0.128989 0.018913 -0.010996 +v 0.129100 0.020220 0.004902 +v 0.129247 0.020777 -0.010996 +v 0.130509 0.022179 -0.010996 +v 0.133170 0.022406 -0.010996 +v 0.137025 0.017876 -0.010996 +v 0.137263 0.019923 -0.010996 +v 0.128867 0.023793 -0.010996 +v 0.127084 0.021535 -0.010996 +v 0.136700 0.021907 -0.010996 +v 0.126731 0.019076 -0.010996 +v 0.135422 0.023523 -0.010996 +v 0.133621 0.024528 -0.010996 +v 0.136020 0.016076 -0.010996 +v 0.127294 0.017093 -0.010996 +v 0.131387 0.024761 -0.010996 +v 0.134404 0.014797 -0.010996 +v 0.131812 0.014167 -0.010996 +v 0.128868 0.015207 -0.010996 +v 0.137186 0.020380 -0.011729 +v 0.136693 0.021883 -0.011670 +v 0.135800 0.023148 -0.011694 +v 0.134767 0.023958 -0.011725 +v 0.133458 0.024545 -0.011724 +v 0.131497 0.024781 -0.011686 +v 0.128950 0.023815 -0.011696 +v 0.127498 0.022251 -0.011687 +v 0.126875 0.020741 -0.011676 +v 0.126754 0.018792 -0.011725 +v 0.127728 0.016408 -0.011704 +v 0.129212 0.015037 -0.011752 +v 0.130626 0.014427 -0.011742 +v 0.132829 0.014276 -0.011714 +v 0.135104 0.015226 -0.011676 +v 0.136473 0.016726 -0.011713 +v 0.137171 0.018496 -0.011677 +v 0.128191 0.018912 -0.013707 +v 0.127343 0.018714 -0.012690 +v 0.127490 0.019869 -0.012956 +v 0.128533 0.017802 -0.013677 +v 0.128030 0.016828 -0.012655 +v 0.129404 0.016532 -0.013591 +v 0.129755 0.015522 -0.012908 +v 0.130796 0.015795 -0.013662 +v 0.131449 0.014791 -0.012654 +v 0.132438 0.015380 -0.013403 +v 0.133723 0.015053 -0.012607 +v 0.134272 0.015930 -0.013342 +v 0.134753 0.017272 -0.013976 +v 0.135550 0.016498 -0.012777 +v 0.136300 0.017789 -0.012833 +v 0.135612 0.018864 -0.013847 +v 0.136561 0.019543 -0.012940 +v 0.135829 0.020275 -0.013627 +v 0.136292 0.021443 -0.012705 +v 0.135231 0.021444 -0.013746 +v 0.135147 0.022543 -0.013165 +v 0.134377 0.023450 -0.012854 +v 0.133224 0.022962 -0.013830 +v 0.132858 0.023880 -0.013044 +v 0.131467 0.023870 -0.013139 +v 0.130235 0.024009 -0.012485 +v 0.130412 0.023068 -0.013634 +v 0.129284 0.023058 -0.013044 +v 0.129147 0.021647 -0.013915 +v 0.128313 0.022343 -0.012783 +v 0.127932 0.020946 -0.013250 +v 0.133997 0.020655 -0.011996 +v 0.133997 0.018345 -0.011996 +v 0.131997 0.021809 -0.011996 +v 0.129997 0.020655 -0.011996 +v 0.129997 0.018345 -0.011996 +v 0.131997 0.017191 -0.011996 +v 0.133941 0.010841 -0.014296 +v 0.134860 0.009601 -0.014285 +v 0.133997 0.009655 -0.014296 +v 0.133997 0.007345 -0.014296 +v 0.135051 0.008024 -0.014289 +v 0.134342 0.006411 -0.014270 +v 0.131997 0.010809 -0.014296 +v 0.132626 0.011479 -0.014293 +v 0.131350 0.011515 -0.014286 +v 0.132548 0.005520 -0.014296 +v 0.130694 0.005728 -0.014293 +v 0.131997 0.006191 -0.014296 +v 0.129997 0.009655 -0.014296 +v 0.129470 0.010358 -0.014276 +v 0.129997 0.007345 -0.014296 +v 0.129402 0.006845 -0.014294 +v 0.128915 0.008356 -0.014284 +v 0.133935 0.010713 0.004986 +v 0.134874 0.007760 0.004907 +v 0.134880 0.009307 0.004910 +v 0.134341 0.006696 0.004930 +v 0.133106 0.005720 0.004911 +v 0.131108 0.005630 0.004939 +v 0.129614 0.006709 0.004909 +v 0.129123 0.007819 0.004919 +v 0.129087 0.009101 0.004929 +v 0.129658 0.010323 0.004923 +v 0.130741 0.011203 0.004909 +v 0.132426 0.011458 0.004919 +v 0.134857 0.009716 -0.010996 +v 0.134902 0.007675 -0.010996 +v 0.133898 0.006070 -0.010996 +v 0.131788 0.005460 -0.010996 +v 0.129528 0.006570 -0.010996 +v 0.129031 0.009348 -0.010996 +v 0.130379 0.011082 -0.010996 +v 0.132695 0.011529 -0.010996 +v 0.137025 0.006876 -0.010996 +v 0.137263 0.008923 -0.010996 +v 0.127973 0.011924 -0.010996 +v 0.126969 0.010124 -0.010996 +v 0.136431 0.011463 -0.010996 +v 0.134403 0.013203 -0.010996 +v 0.126731 0.008076 -0.010996 +v 0.129962 0.013413 -0.010996 +v 0.135758 0.004740 -0.010996 +v 0.127293 0.006094 -0.010996 +v 0.133621 0.003472 -0.010996 +v 0.132421 0.013766 -0.010996 +v 0.131387 0.003239 -0.010996 +v 0.128868 0.004207 -0.010996 +v 0.137267 0.008744 -0.011698 +v 0.136751 0.010862 -0.011682 +v 0.135070 0.012783 -0.011669 +v 0.133750 0.013453 -0.011714 +v 0.132156 0.013777 -0.011685 +v 0.130612 0.013566 -0.011709 +v 0.129027 0.012862 -0.011685 +v 0.127655 0.011502 -0.011654 +v 0.126812 0.009512 -0.011659 +v 0.126809 0.007540 -0.011697 +v 0.127399 0.006021 -0.011822 +v 0.128387 0.004643 -0.011657 +v 0.129740 0.003772 -0.011757 +v 0.130985 0.003327 -0.011673 +v 0.132720 0.003274 -0.011715 +v 0.135409 0.004423 -0.011657 +v 0.136859 0.006435 -0.011748 +v 0.127752 0.007295 -0.013130 +v 0.127474 0.008601 -0.012976 +v 0.128602 0.006078 -0.013365 +v 0.128674 0.005085 -0.012618 +v 0.129688 0.004855 -0.013236 +v 0.130890 0.004685 -0.013570 +v 0.131286 0.003892 -0.012782 +v 0.132238 0.004745 -0.013773 +v 0.132829 0.003992 -0.012862 +v 0.133699 0.004925 -0.013600 +v 0.134265 0.004180 -0.012459 +v 0.135267 0.005394 -0.012991 +v 0.135889 0.006535 -0.013160 +v 0.136349 0.007480 -0.013081 +v 0.136569 0.008796 -0.012860 +v 0.135790 0.009712 -0.013586 +v 0.136342 0.010229 -0.012763 +v 0.134873 0.010939 -0.013770 +v 0.135546 0.011629 -0.012682 +v 0.134294 0.012167 -0.013238 +v 0.132590 0.012285 -0.013726 +v 0.133205 0.012913 -0.012887 +v 0.131612 0.013225 -0.012672 +v 0.130348 0.012635 -0.013093 +v 0.129884 0.011844 -0.013593 +v 0.128523 0.011725 -0.012687 +v 0.127818 0.010465 -0.012861 +v 0.127877 0.009372 -0.013353 +v 0.133997 0.009655 -0.011996 +v 0.133997 0.007345 -0.011996 +v 0.131997 0.010809 -0.011996 +v 0.129997 0.009655 -0.011996 +v 0.129997 0.007345 -0.011996 +v 0.131997 0.006191 -0.011996 +v 0.128242 -0.034000 0.003369 +v 0.124650 -0.034000 0.002993 +v 0.128085 -0.034000 0.006079 +v 0.132287 -0.034000 0.000939 +v 0.130523 -0.034000 -0.002469 +v 0.129979 -0.034000 0.001502 +v 0.126839 -0.034000 -0.000543 +v 0.134494 -0.034000 0.001827 +v 0.136842 -0.034000 -0.000758 +v 0.134439 -0.034000 -0.002147 +v 0.135646 -0.034000 0.003298 +v 0.138864 -0.034000 0.001761 +v 0.125375 -0.034000 0.008643 +v 0.129125 -0.034000 0.007828 +v 0.127152 -0.034000 0.010766 +v 0.132560 -0.034000 0.008993 +v 0.133471 -0.034000 0.012477 +v 0.134887 -0.034000 0.007937 +v 0.137338 -0.034000 0.010403 +v 0.138945 -0.034000 0.007873 +v 0.130701 -0.034000 0.008832 +v 0.129555 -0.034000 0.012155 +v 0.139543 -0.034000 0.005396 +v 0.124579 -0.034000 0.006222 +v 0.128025 -0.034500 0.004092 +v 0.128182 -0.034500 0.006297 +v 0.129394 -0.034500 0.008139 +v 0.131434 -0.034500 0.008993 +v 0.133459 -0.034500 0.008789 +v 0.135098 -0.034500 0.007575 +v 0.136031 -0.034500 0.005577 +v 0.135341 -0.034500 0.002602 +v 0.132905 -0.034500 0.001050 +v 0.130701 -0.034500 0.001176 +v 0.129124 -0.034500 0.002180 +v 0.139261 -0.034500 0.007149 +v 0.137229 -0.034500 0.010508 +v 0.132533 -0.034500 -0.002518 +v 0.134995 -0.034500 -0.001901 +v 0.139343 -0.034500 0.002993 +v 0.137310 -0.034500 -0.000370 +v 0.129780 -0.034500 -0.002204 +v 0.126582 -0.034500 -0.000353 +v 0.134214 -0.034500 0.012212 +v 0.124614 -0.034500 0.003311 +v 0.131461 -0.034500 0.012526 +v 0.128998 -0.034500 0.011909 +v 0.126863 -0.034500 0.010528 +v 0.124788 -0.034500 0.007463 +v 0.136044 0.034000 0.004714 +v 0.139191 0.034000 0.002789 +v 0.139534 0.034000 0.005543 +v 0.135363 0.034000 0.002791 +v 0.138058 0.034000 0.000518 +v 0.131537 0.034000 0.001002 +v 0.132773 0.034000 -0.002550 +v 0.133726 0.034000 0.001314 +v 0.136028 0.034000 -0.001369 +v 0.129481 0.034000 0.001799 +v 0.129561 0.034000 -0.002119 +v 0.127326 0.034000 -0.000916 +v 0.128025 0.034000 0.004091 +v 0.125375 0.034000 0.001365 +v 0.129690 0.034000 0.008322 +v 0.126163 0.034000 0.009901 +v 0.128278 0.034000 0.006625 +v 0.134096 0.034000 0.008520 +v 0.138413 0.034000 0.009066 +v 0.136097 0.034000 0.011318 +v 0.135646 0.034000 0.006710 +v 0.131601 0.034000 0.009026 +v 0.129846 0.034000 0.012287 +v 0.133541 0.034000 0.012401 +v 0.124535 0.034000 0.004010 +v 0.124615 0.034000 0.006547 +v 0.135986 0.034500 0.004265 +v 0.135716 0.034500 0.006625 +v 0.134032 0.034500 0.008534 +v 0.131363 0.034500 0.009029 +v 0.129106 0.034500 0.007850 +v 0.128112 0.034500 0.006069 +v 0.128117 0.034500 0.003693 +v 0.130103 0.034500 0.001373 +v 0.132627 0.034500 0.001012 +v 0.134776 0.034500 0.002024 +v 0.130523 0.034500 -0.002469 +v 0.125374 0.034500 0.008643 +v 0.126839 0.034500 -0.000543 +v 0.124495 0.034500 0.005772 +v 0.124829 0.034500 0.002557 +v 0.134887 0.034500 -0.002019 +v 0.127682 0.034500 0.011229 +v 0.130911 0.034500 0.012482 +v 0.137513 0.034500 -0.000119 +v 0.139016 0.034500 0.002206 +v 0.133906 0.034500 0.012299 +v 0.139542 0.034500 0.005862 +v 0.136213 0.034500 0.011241 +v 0.138206 0.034500 0.009310 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.0054 0.0031 -1.0000 +vn -0.0048 0.0013 -1.0000 +vn -0.0038 0.0119 -0.9999 +vn -0.0005 -0.0005 -1.0000 +vn -0.3090 -0.1923 -0.9314 +vn 0.0030 -0.0080 -1.0000 +vn -0.0991 -0.3610 -0.9273 +vn 0.0006 -0.0098 -1.0000 +vn -0.0071 0.0396 -0.9992 +vn -0.0080 0.0223 -0.9997 +vn -0.0027 0.0082 -1.0000 +vn 0.0065 -0.0010 -1.0000 +vn 0.0044 -0.0007 -1.0000 +vn 0.0083 0.0003 -1.0000 +vn 0.0075 0.0005 -1.0000 +vn 0.0124 0.0005 -0.9999 +vn -0.0031 -0.0029 1.0000 +vn -0.0218 0.0190 0.9996 +vn -0.0540 0.0191 0.9984 +vn -0.0090 0.0174 0.9998 +vn -0.0005 0.0141 0.9999 +vn 0.0050 0.0104 0.9999 +vn 0.0090 0.0059 0.9999 +vn 0.0117 0.0002 0.9999 +vn 0.0131 -0.0076 0.9999 +vn 0.0111 -0.0223 0.9997 +vn -0.0009 -0.0606 0.9982 +vn -0.9937 0.1119 -0.0002 +vn -0.9998 0.0177 0.0087 +vn -0.8335 0.5525 0.0069 +vn -0.7618 0.6478 -0.0013 +vn -0.5162 0.8564 0.0076 +vn -0.2512 0.9679 -0.0020 +vn -0.1030 0.9947 0.0075 +vn 0.3331 0.9429 -0.0003 +vn 0.4021 0.9156 0.0062 +vn 0.5907 0.8069 0.0003 +vn 0.6326 0.7744 0.0058 +vn 0.9735 0.2286 -0.0023 +vn 0.9624 0.2717 0.0032 +vn 0.9636 0.2674 0.0026 +vn 0.9743 0.2251 -0.0027 +vn 0.8478 -0.5302 -0.0069 +vn 0.9444 -0.3286 0.0117 +vn 0.8170 -0.5765 0.0116 +vn 0.5664 -0.8241 -0.0080 +vn 0.3545 -0.9350 0.0110 +vn 0.1947 -0.9808 -0.0065 +vn 0.0495 -0.9987 0.0103 +vn -0.6139 -0.7894 0.0000 +vn -0.6124 -0.7906 0.0003 +vn -0.6125 -0.7904 0.0003 +vn -0.6140 -0.7893 0.0000 +vn -0.9828 -0.1845 -0.0004 +vn -0.9567 -0.2909 0.0108 +vn -0.9979 -0.0647 -0.0082 +vn -0.9574 -0.1790 -0.2266 +vn -0.8822 -0.4709 -0.0041 +vn -0.8492 -0.4622 -0.2553 +vn -0.6337 -0.7350 -0.2411 +vn -0.5778 -0.8160 0.0195 +vn -0.3602 -0.8981 -0.2521 +vn -0.1281 -0.9918 -0.0027 +vn -0.0794 -0.9567 -0.2799 +vn 0.1570 -0.9578 -0.2410 +vn 0.3255 -0.9455 -0.0059 +vn 0.4261 -0.8569 -0.2902 +vn 0.5861 -0.7721 -0.2456 +vn 0.7132 -0.7008 -0.0149 +vn 0.8358 -0.5201 -0.1757 +vn 0.9774 -0.2103 -0.0231 +vn 0.9491 -0.1531 -0.2752 +vn 0.9640 0.1557 -0.2157 +vn 0.9485 0.3167 -0.0100 +vn 0.8243 0.5056 -0.2548 +vn 0.7127 0.6969 -0.0806 +vn 0.5366 0.8152 -0.2181 +vn 0.3318 0.9407 -0.0713 +vn 0.1077 0.9722 -0.2080 +vn -0.1357 0.9892 -0.0547 +vn -0.3323 0.9218 -0.1996 +vn -0.6421 0.7652 -0.0460 +vn -0.5984 0.7405 -0.3058 +vn -0.8353 0.5248 -0.1637 +vn -0.9407 0.3362 -0.0446 +vn -0.9556 0.1574 -0.2489 +vn 0.7710 -0.0361 -0.6358 +vn 0.7831 0.2240 -0.5801 +vn 0.6436 0.2359 -0.7281 +vn 0.6147 -0.0122 -0.7887 +vn 0.4983 0.3419 -0.7967 +vn 0.6177 0.4804 -0.6227 +vn 0.3649 0.5415 -0.7574 +vn 0.4476 0.6620 -0.6012 +vn 0.2019 0.5697 -0.7966 +vn 0.2449 0.8042 -0.5416 +vn 0.1190 0.6983 -0.7059 +vn -0.1141 0.7892 -0.6035 +vn -0.1644 0.6318 -0.7575 +vn -0.4083 0.6901 -0.5976 +vn -0.4692 0.5111 -0.7202 +vn -0.4114 0.4448 -0.7955 +vn -0.6939 0.4731 -0.5428 +vn -0.6207 0.2868 -0.7297 +vn -0.5843 0.1043 -0.8048 +vn -0.7843 0.1614 -0.5990 +vn -0.6507 -0.0836 -0.7547 +vn -0.7881 -0.1861 -0.5867 +vn -0.5907 -0.3487 -0.7276 +vn -0.6724 -0.4800 -0.5635 +vn -0.3667 -0.5140 -0.7754 +vn -0.4731 -0.6174 -0.6285 +vn -0.1575 -0.7691 -0.6194 +vn -0.0111 -0.6796 -0.7335 +vn 0.2483 -0.5780 -0.7774 +vn 0.2074 -0.7436 -0.6356 +vn 0.4354 -0.6272 -0.6458 +vn 0.5815 -0.4927 -0.6474 +vn 0.5032 -0.3549 -0.7879 +vn 0.6473 -0.2410 -0.7232 +vn 0.7900 -0.3197 -0.5232 +vn 1.0000 0.0000 0.0000 +vn 0.4998 0.8662 0.0000 +vn 0.5002 0.8659 0.0000 +vn -0.4998 0.8662 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4998 -0.8662 0.0000 +vn 0.4998 -0.8662 0.0000 +vn 0.5032 -0.5801 0.6406 +vn 0.6147 -0.5694 0.5458 +vn 0.5612 -0.7802 0.2761 +vn 0.4489 -0.5645 0.6927 +vn 0.6261 -0.7554 0.1935 +vn 0.7110 -0.7027 0.0248 +vn 0.7529 -0.6450 0.1309 +vn 0.7469 -0.6617 -0.0655 +vn 0.6347 -0.7520 -0.1776 +vn 0.7224 -0.5648 -0.3990 +vn 0.3196 -0.7407 -0.5909 +vn 0.5243 -0.7002 -0.4846 +vn 0.4262 -0.7035 -0.5687 +vn -0.0068 -0.7302 -0.6832 +vn 0.0472 -0.7153 -0.6972 +vn 0.2317 -0.6176 -0.7516 +vn 0.0000 1.0000 -0.0000 +vn 0.9203 0.0121 -0.3911 +vn 0.8572 -0.0111 -0.5149 +vn 0.9912 -0.0114 -0.1319 +vn 1.0000 0.0052 -0.0031 +vn 0.6842 0.0073 -0.7293 +vn 0.5812 -0.0163 -0.8136 +vn 0.2938 0.0050 -0.9559 +vn 0.1869 0.0021 -0.9824 +vn -0.2272 -0.1729 0.9584 +vn 0.0053 -0.3539 0.9353 +vn -0.0035 -0.3830 0.9237 +vn 0.1910 -0.1801 0.9649 +vn 0.0042 0.4213 0.9069 +vn 0.2696 0.1918 0.9437 +vn -0.0064 0.3534 0.9355 +vn 0.0099 0.1577 0.9874 +vn -0.0080 0.0547 0.9985 +vn 0.0089 -0.0275 0.9996 +vn -0.0078 -0.1281 0.9917 +vn 0.2806 0.0347 0.9592 +vn 0.0581 0.0064 0.9983 +vn -0.1139 0.0545 0.9920 +vn 0.4632 -0.0626 0.8841 +vn 0.6714 0.0750 0.7372 +vn 0.8136 -0.0497 0.5793 +vn 0.9281 -0.0026 0.3723 +vn 0.9686 -0.0071 0.2486 +vn -0.0056 0.2180 0.9759 +vn 0.0061 0.3125 0.9499 +vn -0.0057 -0.2763 0.9610 +vn -0.0499 0.1879 0.9809 +vn 0.0090 -0.2150 0.9766 +vn -1.0000 0.0000 0.0034 +vn -1.0000 -0.0001 0.0049 +vn -0.9895 0.0009 0.1447 +vn -0.9925 -0.0012 0.1218 +vn 0.9999 0.0000 0.0167 +vn 1.0000 -0.0012 0.0059 +vn 0.9999 -0.0001 0.0160 +vn 1.0000 -0.0013 0.0051 +vn -0.5692 0.0093 0.8222 +vn -0.3834 -0.0101 0.9235 +vn 0.9715 0.0022 0.2370 +vn 0.9835 0.0001 0.1810 +vn 0.9854 0.0003 0.1702 +vn 0.9066 0.0046 0.4219 +vn 0.9297 -0.0018 0.3683 +vn 0.6023 0.0128 0.7982 +vn 0.7591 -0.0004 0.6509 +vn 0.0708 0.0174 0.9973 +vn -0.4353 0.0126 0.9002 +vn -0.8108 -0.0104 0.5852 +vn -0.8359 0.0054 0.5488 +vn -0.9906 0.0157 0.1358 +vn -0.9787 -0.0002 0.2051 +vn -0.9886 0.0003 0.1504 +vn -0.9163 -0.0053 0.4005 +vn -0.8965 0.0042 0.4430 +vn -0.7126 -0.0081 0.7015 +vn 0.1006 -0.0173 0.9948 +vn 0.6746 -0.0137 0.7381 +vn 0.8495 -0.0055 0.5276 +vn 0.8837 -0.0062 0.4680 +vn 0.9624 0.0007 0.2716 +vn 0.9692 0.0019 0.2463 +vn 0.4972 0.0090 0.8676 +vn 0.0043 -0.9999 -0.0119 +vn 0.0056 -0.9999 -0.0110 +vn 0.0004 -0.9999 -0.0123 +vn 0.0117 -0.9999 -0.0001 +vn 0.0117 -0.9999 -0.0025 +vn 0.0120 -0.9999 -0.0049 +vn 0.0082 -0.9999 -0.0104 +vn 0.0091 -0.9999 -0.0092 +vn 0.8603 -0.2602 0.4383 +vn 0.9923 -0.0044 0.1238 +vn 0.9228 -0.0083 0.3852 +vn 0.9568 -0.2890 0.0320 +vn 0.7795 -0.0040 0.6265 +vn -0.9761 -0.2137 -0.0404 +vn -0.9866 -0.1404 -0.0832 +vn -0.9585 0.0382 -0.2826 +vn -0.6899 0.0042 -0.7239 +vn -0.6671 0.0449 -0.7436 +vn -0.4935 -0.0975 -0.8642 +vn -0.4876 -0.1176 -0.8651 +vn -0.8776 -0.0713 -0.4741 +vn -0.2798 -0.1150 0.9532 +vn -0.6928 0.1317 0.7090 +vn -0.6942 0.1263 0.7086 +vn -0.6852 0.1586 0.7108 +vn -0.2946 -0.1657 0.9412 +vn -0.6809 0.1732 0.7116 +vn -0.8886 -0.2112 0.4071 +vn -0.9200 -0.1225 0.3722 +vn -0.9570 0.1714 0.2340 +vn -0.9494 0.2489 0.1916 +vn -0.0047 0.0561 -0.9984 +vn -0.0107 0.0771 -0.9970 +vn 0.3366 -0.0143 -0.9415 +vn 0.6175 -0.2632 -0.7412 +vn 0.1832 -0.2623 -0.9474 +vn 0.5378 -0.0166 -0.8429 +vn 0.7552 -0.0048 -0.6555 +vn 0.8969 -0.0118 -0.4421 +vn 0.8563 -0.3256 -0.4009 +vn 0.9848 0.0008 -0.1739 +vn -0.0003 -1.0000 -0.0018 +vn -0.0004 -1.0000 -0.0008 +vn 0.0003 -1.0000 -0.0014 +vn -0.0005 -1.0000 -0.0009 +vn 0.0019 -1.0000 -0.0026 +vn 0.0019 -1.0000 -0.0013 +vn 0.0027 -1.0000 -0.0008 +vn 0.0010 -1.0000 0.0001 +vn -0.0002 -1.0000 -0.0001 +vn -0.0009 -1.0000 0.0002 +vn 0.0003 -1.0000 0.0003 +vn 0.0000 -1.0000 0.0000 +vn 0.0005 -1.0000 0.0004 +vn 0.0011 -1.0000 0.0002 +vn -0.0012 -1.0000 0.0002 +vn -0.0011 -1.0000 0.0002 +vn 0.5641 -0.2626 0.7829 +vn 0.5961 0.0162 0.8028 +vn 0.3460 -0.0443 0.9372 +vn 0.0523 -0.4377 0.8976 +vn 0.0794 -0.3221 0.9434 +vn -0.1495 -0.2584 0.9544 +vn -0.4626 -0.0579 0.8847 +vn -0.4656 0.0076 0.8849 +vn -0.7215 0.0029 0.6924 +vn -0.7945 -0.1837 0.5788 +vn -0.9048 0.0054 0.4258 +vn -0.9108 -0.3614 0.1993 +vn -0.9919 -0.0045 0.1267 +vn -0.7792 -0.6157 0.1174 +vn -0.6892 -0.6767 0.2591 +vn -0.7222 -0.6917 -0.0049 +vn -0.0003 -1.0000 0.0003 +vn -0.0003 -1.0000 0.0005 +vn -0.9958 -0.0092 0.0910 +vn -0.9190 0.0059 0.3941 +vn -0.9933 -0.0204 0.1133 +vn -0.9424 -0.0092 0.3342 +vn -0.6278 -0.0194 0.7782 +vn -0.4667 0.0253 0.8841 +vn 0.0192 -0.0281 0.9994 +vn 0.1413 0.0047 0.9900 +vn 0.3770 -0.0261 0.9259 +vn 0.3845 -0.0305 0.9226 +vn 0.8947 -0.0162 0.4464 +vn 0.9419 0.0250 0.3350 +vn 0.8069 0.0387 0.5894 +vn 0.9914 -0.0239 0.1290 +vn 0.9546 0.0252 -0.2967 +vn 0.8991 -0.0115 -0.4375 +vn 0.5346 0.0199 -0.8449 +vn 0.5394 -0.0095 -0.8420 +vn 0.2791 -0.0014 -0.9603 +vn 0.2203 0.0252 -0.9751 +vn -0.3410 -0.0078 -0.9400 +vn -0.3744 0.0077 -0.9272 +vn -0.3163 -0.0192 -0.9485 +vn -0.3984 0.0191 -0.9170 +vn -0.8459 -0.0077 -0.5332 +vn -0.8695 0.0140 -0.4938 +vn -0.8239 -0.0265 -0.5662 +vn -0.8878 0.0326 -0.4590 +vn 0.0116 -0.9999 0.0106 +vn 0.0119 -0.9999 0.0051 +vn 0.0109 -0.9999 0.0040 +vn 0.0003 -0.9999 0.0108 +vn -0.0025 -0.9999 0.0125 +vn -0.0001 -0.9999 0.0105 +vn -0.0070 -0.9999 0.0132 +vn -0.0134 -0.9999 0.0089 +vn -0.0141 -0.9999 0.0060 +vn -0.0108 -0.9999 0.0106 +vn -0.0160 -0.9999 0.0044 +vn 0.0090 -0.9999 0.0111 +vn -0.0131 -0.9999 0.0064 +vn 0.0112 -0.9999 0.0011 +vn 0.0017 -0.9999 0.0120 +vn -0.0156 -0.9999 -0.0073 +vn -0.0090 -0.9999 -0.0097 +vn -0.0164 -0.9998 -0.0071 +vn -0.0061 -1.0000 -0.0070 +vn -0.0053 -1.0000 -0.0081 +vn -0.0038 -0.9999 -0.0108 +vn -0.9318 -0.2583 -0.2552 +vn -0.9897 0.0043 -0.1434 +vn -0.9040 -0.0293 -0.4266 +vn -0.7690 -0.0202 -0.6389 +vn -0.7444 -0.2742 -0.6088 +vn -0.5123 -0.0024 -0.8588 +vn -0.3308 -0.2883 -0.8986 +vn -0.2192 -0.0080 -0.9757 +vn 0.0225 -0.0107 -0.9997 +vn -0.2025 -0.3932 -0.8969 +vn -0.2109 -0.3616 -0.9082 +vn -0.2930 -0.7993 -0.5247 +vn -0.3303 -0.7906 -0.5156 +vn -0.2181 -0.7857 -0.5789 +vn -0.5418 -0.6629 -0.5167 +vn -0.5424 -0.7663 -0.3442 +vn -0.7132 -0.6466 -0.2707 +vn -0.7602 -0.6263 -0.1728 +vn -0.8175 -0.5694 -0.0866 +vn -0.5363 -0.6603 0.5258 +vn -0.6879 -0.6185 0.3798 +vn -0.5407 -0.6711 0.5072 +vn -0.4206 -0.6204 0.6619 +vn -0.2478 -0.7082 0.6611 +vn 0.3608 -0.5358 0.7633 +vn 0.1071 -0.7951 0.5969 +vn 0.5358 -0.6879 -0.4896 +vn -0.5917 -0.4444 -0.6726 +vn -0.8684 -0.4820 -0.1167 +vn -0.1628 -0.4833 -0.8602 +vn 0.1990 -0.5082 -0.8379 +vn 0.6188 -0.5045 -0.6021 +vn 0.8997 -0.3607 -0.2458 +vn 0.7854 -0.5043 0.3590 +vn 0.7651 -0.6312 0.1270 +vn 0.6344 -0.5556 0.5375 +vn 0.2763 -0.4143 0.8672 +vn 0.1443 -0.7024 0.6970 +vn -0.2245 -0.1252 0.9664 +vn -0.3424 -0.7662 0.5438 +vn -0.7677 -0.3410 0.5426 +vn -0.6569 -0.7414 0.1370 +vn 0.0002 1.0000 0.0063 +vn -0.0003 1.0000 0.0087 +vn 0.0027 1.0000 -0.0055 +vn 0.0031 1.0000 -0.0076 +vn 1.0000 -0.0005 -0.0079 +vn 1.0000 -0.0005 -0.0084 +vn 1.0000 0.0002 0.0063 +vn 1.0000 0.0002 0.0068 +vn 0.0003 -1.0000 0.0060 +vn 0.0008 -1.0000 0.0080 +vn -0.0020 -1.0000 -0.0048 +vn -0.0024 -1.0000 -0.0068 +vn -1.0000 0.0005 -0.0080 +vn -1.0000 -0.0002 0.0063 +vn -1.0000 0.0005 -0.0075 +vn -1.0000 -0.0002 0.0068 +vn -0.0560 0.0234 -0.9982 +vn -0.0089 -0.0019 -1.0000 +vn -0.0154 -0.0006 -0.9999 +vn 0.0233 0.0062 -0.9997 +vn 0.2681 -0.2442 -0.9319 +vn 0.0084 0.0039 -1.0000 +vn -0.0027 0.0024 -1.0000 +vn -0.0153 -0.3721 -0.9281 +vn -0.0042 -0.0057 -1.0000 +vn -0.0031 -0.0053 -1.0000 +vn -0.0174 0.0057 -0.9998 +vn 0.0023 0.0034 -1.0000 +vn 0.0012 0.0020 -1.0000 +vn 0.0166 -0.0039 -0.9999 +vn 0.0506 0.0126 -0.9986 +vn 0.0245 -0.0009 -0.9997 +vn -0.0187 -0.0109 0.9998 +vn -0.0194 0.0174 0.9997 +vn -0.0449 0.0096 0.9989 +vn -0.0037 0.0145 0.9999 +vn 0.0049 0.0113 0.9999 +vn 0.0088 0.0083 0.9999 +vn 0.0120 0.0044 0.9999 +vn 0.0150 -0.0012 0.9999 +vn 0.0172 -0.0080 0.9998 +vn 0.0162 -0.0213 0.9996 +vn 0.0028 -0.0917 0.9958 +vn -0.1942 -0.0621 0.9790 +vn -0.9947 0.1027 -0.0017 +vn -0.9997 0.0226 0.0056 +vn -0.9561 0.2929 0.0083 +vn -0.9209 0.3898 -0.0014 +vn -0.5327 0.8463 0.0042 +vn -0.5518 0.8339 0.0069 +vn -0.5502 0.8350 0.0067 +vn -0.5309 0.8474 0.0039 +vn 0.1050 0.9945 0.0009 +vn 0.1073 0.9942 0.0012 +vn 0.4669 0.8843 -0.0021 +vn 0.3561 0.9344 0.0056 +vn 0.7315 0.6818 0.0071 +vn 0.9303 0.3667 -0.0023 +vn 0.9487 0.3163 0.0045 +vn 0.9903 -0.1390 0.0054 +vn 0.9664 -0.2569 -0.0036 +vn 0.8068 -0.5908 0.0113 +vn 0.8251 -0.5649 -0.0064 +vn 0.6208 -0.7838 0.0165 +vn 0.1064 -0.9943 -0.0010 +vn 0.0768 -0.9970 -0.0053 +vn 0.0803 -0.9968 -0.0048 +vn 0.1089 -0.9940 -0.0007 +vn -0.5812 -0.8138 -0.0033 +vn -0.4654 -0.8851 0.0078 +vn -0.6189 -0.7855 0.0078 +vn -0.8430 -0.5379 -0.0031 +vn -0.8861 -0.4634 0.0058 +vn -0.9630 -0.0533 -0.2641 +vn -0.8795 -0.4497 -0.1559 +vn -0.9836 -0.1462 -0.1056 +vn -0.6518 -0.7578 -0.0312 +vn -0.8257 -0.4737 0.3063 +vn -0.6413 -0.6958 -0.3236 +vn -0.3955 -0.8903 -0.2257 +vn -0.1261 -0.9920 -0.0067 +vn -0.0727 -0.9599 -0.2709 +vn 0.2753 -0.9323 -0.2346 +vn 0.3207 -0.9468 0.0287 +vn 0.6134 -0.7890 -0.0355 +vn 0.6874 -0.6833 -0.2462 +vn 0.8950 -0.4457 -0.0155 +vn 0.8634 -0.4118 -0.2914 +vn 0.9701 -0.0933 -0.2239 +vn 0.9997 0.0186 -0.0183 +vn 0.9359 0.2643 -0.2330 +vn 0.8889 0.4578 -0.0153 +vn 0.7859 0.5329 -0.3136 +vn 0.6547 0.7555 -0.0243 +vn 0.6260 0.7249 -0.2875 +vn 0.3570 0.9073 -0.2223 +vn 0.2716 0.9624 0.0031 +vn -0.0140 0.9704 -0.2411 +vn -0.1524 0.9883 -0.0067 +vn -0.3942 0.8820 -0.2583 +vn -0.6404 0.7674 -0.0313 +vn -0.6508 0.7029 -0.2869 +vn -0.8204 0.5190 -0.2399 +vn -0.9458 0.3248 -0.0084 +vn -0.9544 0.1918 -0.2289 +vn 0.7200 -0.1787 -0.6706 +vn 0.6423 0.1374 -0.7540 +vn 0.7423 0.1840 -0.6442 +vn 0.8344 -0.0721 -0.5465 +vn 0.5992 0.4305 -0.6750 +vn 0.4839 0.3730 -0.7916 +vn 0.4646 0.6760 -0.5721 +vn 0.3717 0.5428 -0.7531 +vn 0.2096 0.7561 -0.6200 +vn 0.1934 0.5563 -0.8082 +vn 0.0223 0.6500 -0.7596 +vn -0.1089 0.7979 -0.5929 +vn -0.1443 0.5651 -0.8123 +vn -0.3008 0.6386 -0.7083 +vn -0.4920 0.3696 -0.7882 +vn -0.5178 0.5066 -0.6894 +vn -0.5432 0.6029 -0.5843 +vn -0.7222 0.2969 -0.6247 +vn -0.6533 0.0214 -0.7568 +vn -0.7689 0.0777 -0.6346 +vn -0.7740 -0.1449 -0.6164 +vn -0.5751 -0.1938 -0.7948 +vn -0.5926 -0.3028 -0.7464 +vn -0.6712 -0.4413 -0.5957 +vn -0.4136 -0.4529 -0.7898 +vn -0.4552 -0.5880 -0.6686 +vn -0.2061 -0.6211 -0.7561 +vn -0.2423 -0.7703 -0.5898 +vn 0.0195 -0.7776 -0.6285 +vn 0.2214 -0.6043 -0.7653 +vn 0.2486 -0.7703 -0.5872 +vn 0.4742 -0.6968 -0.5381 +vn 0.4181 -0.5446 -0.7271 +vn 0.6236 -0.4135 -0.6634 +vn 0.6284 -0.1276 -0.7673 +vn 0.0012 1.0000 0.0017 +vn 0.0012 1.0000 0.0007 +vn 0.0005 1.0000 -0.0005 +vn 0.0001 1.0000 0.0009 +vn 0.0000 1.0000 0.0017 +vn 0.0011 1.0000 0.0012 +vn 0.0053 1.0000 -0.0004 +vn -0.3544 0.0154 0.9350 +vn -0.5874 0.0117 0.8092 +vn -0.5684 -0.0174 0.8225 +vn -0.8396 -0.0165 0.5429 +vn -0.9461 0.0160 0.3235 +vn -0.9971 -0.0142 -0.0752 +vn -0.9143 0.0177 -0.4047 +vn -0.7556 -0.0167 -0.6549 +vn -0.4592 0.0148 -0.8882 +vn -0.1551 -0.0173 -0.9878 +vn 0.1588 0.0183 -0.9871 +vn 0.5147 -0.0165 -0.8572 +vn 0.7926 0.0084 -0.6097 +vn 0.9109 -0.0001 -0.4127 +vn 0.9819 0.0133 -0.1892 +vn 0.9623 -0.0080 -0.2717 +vn 0.8856 -0.0177 0.4641 +vn 0.9581 0.0113 0.2862 +vn 0.8330 0.0120 0.5532 +vn 0.6052 -0.0188 0.7958 +vn 0.4181 0.0033 0.9084 +vn 0.2323 -0.0163 0.9725 +vn 0.1922 -0.0077 0.9813 +vn -0.0957 0.7828 -0.6148 +vn -0.1029 0.7765 -0.6217 +vn -0.4365 0.7278 -0.5289 +vn -0.2692 0.7179 -0.6420 +vn -0.6341 0.7252 -0.2684 +vn -0.6910 0.7195 0.0698 +vn -0.6476 0.7181 0.2549 +vn -0.3580 0.7282 0.5845 +vn -0.4447 0.6821 0.5805 +vn -0.0558 0.7183 0.6935 +vn 0.2056 0.7367 0.6442 +vn 0.3224 0.7147 0.6207 +vn 0.6219 0.7230 0.3007 +vn 0.5668 0.7070 0.4229 +vn 0.7106 0.7036 0.0037 +vn 0.6490 0.7303 -0.2131 +vn 0.5583 0.7129 -0.4244 +vn 0.4396 0.6270 -0.6431 +vn 0.4144 0.5403 -0.7324 +vn 0.0008 -1.0000 -0.0016 +vn 0.0000 -1.0000 -0.0020 +vn -0.0007 -1.0000 -0.0016 +vn 0.0007 -1.0000 0.0008 +vn 0.0016 -1.0000 -0.0002 +vn 0.0015 -1.0000 -0.0002 +vn 0.0008 -1.0000 -0.0004 +vn 0.0006 -1.0000 -0.0002 +vn 0.0009 -1.0000 -0.0008 +vn 0.0009 -1.0000 -0.0009 +vn -0.0041 -1.0000 0.0060 +vn -0.0048 -1.0000 0.0034 +vn -0.0025 -1.0000 0.0066 +vn 0.0027 -1.0000 0.0052 +vn -0.0008 -1.0000 -0.0011 +vn -0.0033 -1.0000 0.0042 +vn 0.0007 -1.0000 0.0005 +vn 0.0034 -1.0000 0.0020 +vn 0.0006 -1.0000 0.0002 +vn 0.0006 -1.0000 0.0010 +vn -0.0026 -1.0000 -0.0006 +vn -0.0038 -1.0000 0.0033 +vn -0.0008 -1.0000 -0.0009 +vn -0.0009 -1.0000 -0.0002 +vn -0.0010 -1.0000 -0.0005 +vn -0.0013 -1.0000 -0.0010 +vn -0.9762 -0.0240 -0.2157 +vn -0.9785 0.2033 0.0335 +vn -0.9694 0.2416 0.0438 +vn -0.8666 -0.2250 0.4453 +vn -0.8622 -0.2786 0.4231 +vn -0.7423 0.0567 0.6676 +vn -0.6591 0.0658 0.7492 +vn -0.3557 -0.0447 0.9335 +vn -0.2548 -0.0319 0.9665 +vn -0.0288 0.2068 0.9780 +vn -0.0226 0.2269 0.9736 +vn 0.3201 -0.1223 0.9394 +vn 0.2541 -0.2166 0.9426 +vn 0.4917 0.0691 0.8680 +vn 0.6688 -0.1150 0.7345 +vn 0.7837 0.1427 0.6045 +vn 0.7958 0.2247 0.5623 +vn 0.9490 -0.1846 0.2557 +vn 0.9407 -0.2140 0.2634 +vn 0.9998 0.0139 0.0143 +vn 0.9981 0.0504 0.0361 +vn 0.9372 -0.0136 -0.3484 +vn 0.9284 -0.0500 -0.3682 +vn 0.8085 0.1844 -0.5589 +vn 0.7981 0.2137 -0.5633 +vn 0.5284 -0.2656 -0.8064 +vn 0.3360 0.3355 -0.8801 +vn 0.0315 -0.3394 -0.9401 +vn -0.2045 0.2868 -0.9359 +vn -0.5164 -0.1655 -0.8402 +vn -0.4988 -0.2062 -0.8419 +vn -0.6920 -0.0057 -0.7219 +vn -0.7691 -0.0004 -0.6392 +vn -0.9363 -0.0110 -0.3511 +vn -0.0019 -1.0000 0.0094 +vn -0.0047 -0.9999 0.0147 +vn 0.0068 -1.0000 0.0066 +vn -0.0039 -0.9999 0.0135 +vn -0.0029 -1.0000 0.0068 +vn 0.0015 -1.0000 -0.0030 +vn -0.0127 -0.9999 0.0106 +vn -0.0164 -0.9998 0.0090 +vn -0.0015 -0.9998 0.0220 +vn 0.0098 -0.9999 0.0044 +vn 0.0069 -1.0000 -0.0007 +vn -0.0011 -0.9998 0.0218 +vn -0.0100 -0.9998 0.0191 +vn 0.0028 -1.0000 -0.0046 +vn 0.0049 -1.0000 0.0022 +vn 0.0068 -1.0000 0.0039 +vn 0.0017 -0.9996 0.0275 +vn 0.0066 -1.0000 0.0032 +vn 0.0117 -0.9999 -0.0109 +vn 0.0154 -0.9999 0.0058 +vn 0.0097 -0.9999 -0.0068 +vn -0.6257 -0.7799 0.0138 +vn -0.6812 -0.7165 -0.1501 +vn -0.5268 -0.7996 -0.2883 +vn -0.4585 -0.7502 -0.4764 +vn -0.2921 -0.7945 -0.5324 +vn -0.0195 -0.7936 -0.6081 +vn 0.1284 -0.7465 -0.6529 +vn 0.3185 -0.7879 -0.5270 +vn 0.5230 -0.7091 -0.4728 +vn 0.5759 -0.7762 -0.2568 +vn 0.6553 -0.7495 -0.0934 +vn 0.6128 -0.7722 0.1677 +vn 0.6242 -0.6935 0.3599 +vn 0.4351 -0.7623 0.4791 +vn 0.2503 -0.6785 0.6906 +vn 0.1708 -0.7741 0.6096 +vn -0.2202 -0.7285 -0.6487 +vn 0.2896 -0.6209 -0.7284 +vn 0.0062 -0.6345 0.7729 +vn -0.0903 -0.7619 0.6414 +vn -0.2542 -0.6565 0.7101 +vn -0.3491 -0.7627 0.5445 +vn -0.5126 -0.6143 0.5999 +vn -0.5796 -0.7506 0.3172 +vn -0.7604 -0.6444 0.0806 +vn -0.6775 -0.6424 -0.3582 +vn -0.0233 -0.6250 -0.7803 +vn 0.7714 -0.6312 0.0812 +vn 0.5776 -0.5817 0.5727 +vn -0.7432 -0.5863 0.3223 +vn 0.6724 -0.5868 -0.4510 +vn 0.7822 -0.5846 -0.2153 +vn -0.3272 -0.5496 -0.7687 +vn 0.5189 -0.5463 -0.6575 +vn 0.3718 -0.5502 0.7477 +vn -0.5832 -0.5617 -0.5868 +vn 0.7908 -0.5354 0.2967 +vn -0.1247 -0.5268 0.8408 +vn -0.7080 -0.4837 0.5145 +vn -0.8680 -0.4632 -0.1792 +vn -0.3807 -0.5089 0.7721 +vn 0.0143 -0.4932 -0.8698 +vn 0.4386 -0.4613 -0.7713 +vn 0.7645 -0.4779 -0.4326 +vn 0.8758 -0.4818 0.0290 +vn 0.7638 -0.4741 0.4381 +vn 0.1817 -0.4983 0.8478 +vn -0.8864 -0.4585 0.0646 +vn -0.7712 -0.4707 -0.4286 +vn -0.4850 -0.4546 -0.7470 +vn 0.5088 -0.4564 0.7299 +vn -0.9973 -0.0707 -0.0186 +vn -0.9972 -0.0546 -0.0519 +vn -0.9993 -0.0360 0.0085 +vn -0.3443 -0.6983 -0.6275 +vn -0.5086 -0.6985 -0.5034 +vn -0.3638 -0.6998 -0.6147 +vn -0.1851 -0.6731 -0.7160 +vn 0.3460 -0.6986 -0.6263 +vn 0.1850 -0.6732 -0.7159 +vn 0.3623 -0.6998 -0.6157 +vn 0.5069 -0.6991 -0.5043 +vn 0.9973 -0.0712 0.0188 +vn 0.9971 -0.0549 0.0522 +vn 0.9993 -0.0360 -0.0085 +vn 0.3711 -0.7085 0.6003 +vn 0.5225 -0.6783 0.5166 +vn 0.3424 -0.7116 0.6135 +vn 0.1818 -0.7158 0.6742 +vn -0.5310 -0.0457 0.8461 +vn -0.5509 -0.0490 0.8331 +vn -0.5211 -0.0077 0.8535 +vn -1.0000 -0.0023 0.0053 +vn -0.9997 -0.0131 -0.0200 +vn -0.4988 -0.0008 -0.8667 +vn -0.5007 -0.0022 -0.8656 +vn -0.5021 -0.0011 -0.8648 +vn -0.4961 -0.0024 -0.8683 +vn -0.5057 -0.0037 -0.8627 +vn 0.5020 -0.0011 -0.8649 +vn 0.5084 0.0032 -0.8611 +vn 0.5066 0.0050 -0.8622 +vn 0.5057 -0.0037 -0.8627 +vn 0.5183 0.0133 -0.8551 +vn 0.9997 -0.0132 0.0200 +vn 1.0000 -0.0026 -0.0051 +vn 0.4987 -0.0008 0.8667 +vn 0.4933 0.0027 0.8699 +vn 0.4943 0.0040 0.8693 +vn 0.4958 -0.0024 0.8684 +vn 0.4850 0.0106 0.8745 +vn -0.5186 -0.0138 0.8549 +vn -0.5054 0.0037 0.8629 +vn -0.9896 -0.1296 -0.0620 +vn -0.9943 0.0373 0.0996 +vn -0.9558 -0.0227 0.2932 +vn -0.8724 0.0518 0.4860 +vn -0.7525 0.0054 0.6586 +vn -0.6413 0.0284 0.7668 +vn -0.4202 -0.0273 0.9070 +vn -0.2545 0.0274 0.9667 +vn 0.0053 -0.0279 0.9996 +vn 0.1600 -0.0051 0.9871 +vn 0.3644 -0.0487 0.9300 +vn 0.5458 0.0369 0.8371 +vn 0.7070 -0.0578 0.7049 +vn 0.8486 0.0119 0.5290 +vn 0.9208 -0.0078 0.3899 +vn 0.9832 0.0501 0.1755 +vn 0.9960 -0.0720 -0.0530 +vn 0.9539 0.0786 -0.2896 +vn 0.8677 0.0005 -0.4971 +vn 0.7796 0.0200 -0.6259 +vn 0.6021 -0.0207 -0.7982 +vn 0.4622 0.0110 -0.8867 +vn 0.2319 -0.0630 -0.9707 +vn 0.0430 0.1539 -0.9872 +vn -0.0205 0.2450 -0.9693 +vn -0.2641 -0.3286 -0.9068 +vn -0.5305 0.3282 -0.7816 +vn -0.7400 -0.3298 -0.5862 +vn -0.8826 0.2568 -0.3938 +vn -0.9802 -0.1802 -0.0826 +vn 0.9735 0.0159 0.2283 +vn 0.9707 -0.0182 -0.2394 +vn 0.9365 0.0109 -0.3504 +vn 0.6382 -0.0230 -0.7695 +vn 0.6643 0.0133 -0.7474 +vn 0.2506 0.0129 -0.9680 +vn 0.0199 -0.0271 -0.9994 +vn -0.2301 0.0176 -0.9730 +vn -0.5432 -0.0194 -0.8394 +vn -0.6705 0.0158 -0.7417 +vn -0.8830 -0.0167 -0.4691 +vn -0.9368 0.0127 -0.3496 +vn -0.9733 -0.0115 -0.2292 +vn -0.9899 0.0185 -0.1408 +vn -0.9084 -0.0087 0.4180 +vn -0.9174 0.0036 0.3980 +vn -0.9124 -0.0033 0.4092 +vn -0.9212 0.0090 0.3891 +vn -0.4997 0.0146 0.8661 +vn -0.5732 -0.0176 0.8192 +vn -0.3340 -0.0152 0.9425 +vn -0.2228 0.0131 0.9748 +vn 0.2379 -0.0115 0.9712 +vn 0.2652 0.0094 0.9642 +vn 0.6875 0.0083 0.7262 +vn 0.6901 -0.0046 0.7237 +vn 0.9479 -0.0085 0.3184 +vn 0.0004 1.0000 0.0012 +vn 0.0004 1.0000 0.0011 +vn 0.0001 1.0000 0.0005 +vn 0.0000 1.0000 0.0001 +vn -0.0002 1.0000 0.0005 +vn -0.0002 1.0000 0.0006 +vn 0.0002 1.0000 -0.0001 +vn 0.0018 1.0000 -0.0008 +vn 0.0019 1.0000 -0.0012 +vn -0.0015 1.0000 0.0007 +vn -0.0002 1.0000 0.0001 +vn -0.0019 1.0000 0.0009 +vn -0.0019 1.0000 0.0013 +vn 0.0024 1.0000 -0.0025 +vn 0.0005 1.0000 -0.0012 +vn -0.0002 1.0000 -0.0004 +vn -0.0003 1.0000 -0.0001 +vn 0.0001 1.0000 -0.0013 +vn -0.0002 1.0000 -0.0007 +vn -0.9264 0.2772 -0.2550 +vn -0.9997 0.0086 0.0241 +vn -0.9220 0.3149 0.2254 +vn -0.9759 0.0027 -0.2181 +vn -0.8863 -0.0036 -0.4630 +vn -0.7597 0.2508 -0.5999 +vn -0.7042 0.0026 -0.7100 +vn -0.4105 0.2841 -0.8665 +vn -0.4601 -0.0156 -0.8878 +vn -0.1995 0.0190 -0.9797 +vn 0.0065 0.0223 -0.9997 +vn 0.1537 0.3195 -0.9350 +vn 0.2820 -0.0032 -0.9594 +vn 0.4873 0.0191 -0.8730 +vn 0.7287 0.0466 -0.6832 +vn 0.7174 -0.0140 -0.6966 +vn 0.9168 0.0018 -0.3993 +vn 0.9282 0.3437 -0.1429 +vn 0.9989 0.0063 -0.0454 +vn 0.9807 0.0134 0.1951 +vn 0.9243 0.2545 0.2843 +vn 0.8772 -0.0015 0.4802 +vn 0.6775 0.3041 0.6698 +vn 0.5907 0.3569 0.7237 +vn 0.4861 0.1047 0.8676 +vn 0.2823 0.0589 0.9575 +vn 0.1600 -0.0003 0.9871 +vn -0.2454 0.0672 0.9671 +vn -0.0806 0.0066 0.9967 +vn -0.3407 0.0107 0.9401 +vn -0.6506 0.0472 0.7579 +vn -0.5564 -0.0016 0.8309 +vn -0.7908 0.0118 0.6120 +vn -0.9370 0.0015 0.3494 +vn -0.0145 0.9998 -0.0128 +vn -0.0116 0.9996 -0.0246 +vn -0.0052 0.9999 -0.0156 +vn -0.0036 0.9999 -0.0125 +vn -0.0163 0.9999 -0.0041 +vn -0.0122 0.9999 0.0004 +vn -0.0111 0.9999 0.0035 +vn 0.0009 0.9999 -0.0120 +vn 0.0061 1.0000 -0.0078 +vn 0.0051 0.9999 -0.0089 +vn 0.0066 0.9999 -0.0098 +vn 0.0111 0.9999 -0.0097 +vn 0.0026 0.9999 -0.0111 +vn 0.0135 0.9999 -0.0053 +vn 0.0130 0.9999 0.0021 +vn 0.0109 0.9999 0.0045 +vn -0.0122 0.9999 0.0023 +vn -0.0152 0.9999 0.0016 +vn 0.0124 0.9999 0.0110 +vn 0.0045 0.9998 0.0172 +vn 0.0079 0.9998 0.0180 +vn -0.0007 0.9998 0.0176 +vn -0.0030 0.9999 0.0164 +vn -0.0057 0.9999 0.0161 +vn -0.0032 0.9999 0.0158 +vn 0.0109 0.9999 0.0038 +vn 0.0138 0.9999 0.0035 +vn 0.0144 0.9998 0.0104 +vn -0.0134 0.9998 0.0119 +vn -0.0147 0.9998 0.0112 +vn -0.1565 0.6470 -0.7463 +vn -0.0045 0.7694 -0.6388 +vn -0.2600 0.7226 -0.6405 +vn 0.0016 0.8048 -0.5936 +vn -0.3907 0.6636 -0.6380 +vn 0.0995 0.6016 0.7926 +vn 0.1852 0.7144 0.6748 +vn 0.2083 0.7479 0.6302 +vn -0.0729 0.7183 0.6919 +vn 0.6586 0.7479 -0.0827 +vn 0.6059 0.7756 0.1770 +vn 0.5709 0.8194 0.0509 +vn 0.7607 0.6162 -0.2039 +vn 0.4674 0.7751 -0.4251 +vn 0.7666 0.5379 -0.3507 +vn 0.3043 0.7590 -0.5756 +vn 0.3616 0.7669 -0.5303 +vn 0.1939 0.5935 -0.7811 +vn -0.6014 0.5823 -0.5470 +vn -0.6945 0.6227 -0.3604 +vn -0.6952 0.6235 -0.3577 +vn -0.6507 0.7558 -0.0739 +vn -0.6968 0.6882 -0.2019 +vn 0.4851 0.4017 0.7767 +vn 0.4938 0.7012 0.5143 +vn 0.6101 0.6946 0.3813 +vn 0.6122 0.7423 0.2726 +vn 0.4177 0.7676 -0.4861 +vn -0.4351 0.7019 -0.5640 +vn -0.7441 0.6653 0.0605 +vn -0.6899 0.6867 0.2290 +vn -0.6674 0.6936 0.2712 +vn -0.7030 0.5076 0.4982 +vn -0.4790 0.7176 0.5055 +vn -0.4520 0.5677 0.6881 +vn -0.2960 0.6608 0.6898 +vn -0.2142 0.6137 0.7599 +vn -0.0823 0.7204 0.6886 +vn 0.8575 0.4817 0.1807 +vn 0.7163 0.5127 0.4733 +vn 0.4639 0.6568 0.5945 +vn 0.4701 0.2056 0.8584 +vn 0.0431 0.6577 0.7521 +vn 0.0465 0.6692 0.7416 +vn 0.0200 0.5771 0.8164 +vn 0.0105 0.5422 0.8402 +vn -0.4036 0.2206 0.8879 +vn -0.3969 0.7820 0.4806 +vn -0.8423 0.0311 0.5382 +vn -0.7163 0.6928 0.0835 +vn -0.8767 0.4708 -0.0988 +vn -0.6849 0.4993 -0.5307 +vn -0.4707 0.6277 -0.6200 +vn -0.0851 0.3057 -0.9483 +vn 0.0274 0.6919 -0.7215 +vn 0.4615 0.1747 -0.8698 +vn 0.4306 0.7552 -0.4943 +vn 0.9042 -0.0108 -0.4270 +vn 0.6796 0.7302 -0.0705 +vn -0.0013 -1.0000 0.0007 +vn 0.0007 -1.0000 0.0011 +vn -0.0007 -1.0000 0.0002 +vn 0.0013 -1.0000 -0.0008 +vn 0.0031 -1.0000 -0.0026 +vn 0.5372 -0.0119 0.8434 +vn 0.7533 -0.0099 0.6576 +vn 0.6436 0.0126 0.7652 +vn 0.8620 0.0124 0.5068 +vn 0.9839 -0.0098 0.1785 +vn 0.9994 0.0103 -0.0342 +vn 0.9378 -0.0126 -0.3470 +vn 0.8161 0.0151 -0.5777 +vn 0.5672 -0.0151 -0.8235 +vn 0.2771 0.0148 -0.9607 +vn 0.0109 -0.0118 -0.9999 +vn -0.3116 0.0115 -0.9501 +vn -0.4916 -0.0097 -0.8708 +vn -0.5690 0.0107 -0.8223 +vn -0.7023 -0.0128 -0.7118 +vn -0.9660 0.0052 -0.2584 +vn -0.9652 0.0045 -0.2615 +vn -0.9609 0.0009 -0.2769 +vn -0.9602 0.0003 -0.2794 +vn -0.9605 0.0055 0.2782 +vn -0.9302 -0.0093 0.3670 +vn -0.8539 0.0071 0.5203 +vn -0.7818 -0.0091 0.6235 +vn -0.4145 0.0088 0.9100 +vn -0.3367 -0.0018 0.9416 +vn -0.0988 0.0078 0.9951 +vn -0.0831 0.0044 0.9965 +vn -0.1587 -0.7433 -0.6499 +vn 0.0393 -0.7253 -0.6874 +vn 0.4515 -0.7328 -0.5091 +vn 0.3776 -0.6958 -0.6110 +vn 0.6354 -0.7393 -0.2227 +vn 0.6480 -0.7520 0.1205 +vn 0.7217 -0.6796 0.1316 +vn 0.5083 -0.7462 0.4299 +vn 0.2014 -0.7445 0.6365 +vn 0.1527 -0.6754 0.7215 +vn -0.2100 -0.7682 0.6047 +vn -0.5339 -0.7433 0.4031 +vn -0.5786 -0.6569 0.4833 +vn -0.6651 -0.7457 0.0402 +vn -0.6125 -0.7398 -0.2784 +vn -0.6147 -0.6883 -0.3852 +vn -0.3625 -0.7220 -0.5892 +vn -0.0005 1.0000 -0.0033 +vn 0.0000 1.0000 -0.0012 +vn -0.0000 1.0000 -0.0006 +vn -0.0014 1.0000 0.0006 +vn -0.0009 1.0000 0.0009 +vn -0.0030 1.0000 -0.0000 +vn -0.0011 1.0000 0.0007 +vn -0.0010 1.0000 0.0006 +vn -0.0041 1.0000 -0.0016 +vn -0.0034 1.0000 -0.0036 +vn 0.0009 1.0000 -0.0032 +vn 0.0007 1.0000 0.0010 +vn -0.0000 1.0000 0.0014 +vn -0.0003 1.0000 0.0014 +vn 0.0004 1.0000 -0.0016 +vn -0.0001 1.0000 -0.0019 +vn 0.0020 1.0000 -0.0013 +vn 0.0054 1.0000 -0.0051 +vn 0.0096 1.0000 0.0008 +vn 0.0207 0.9997 -0.0111 +vn 0.0006 1.0000 0.0013 +vn 0.0003 1.0000 0.0010 +vn 0.0024 1.0000 0.0007 +vn 0.0026 1.0000 0.0004 +vn -0.0003 1.0000 0.0009 +vn -0.0004 1.0000 0.0008 +vn 0.0015 1.0000 -0.0017 +vn 0.0052 1.0000 0.0044 +vn 0.9658 0.1615 0.2029 +vn 0.9615 0.2001 0.1883 +vn 0.9190 -0.0063 0.3943 +vn 0.8716 -0.0137 0.4901 +vn 0.7194 -0.0039 0.6946 +vn 0.6040 0.0156 0.7968 +vn 0.4027 -0.2192 0.8887 +vn 0.3723 -0.2780 0.8855 +vn 0.0508 0.0984 0.9939 +vn 0.1871 0.2089 0.9599 +vn -0.0668 0.0394 0.9970 +vn -0.2319 -0.2742 0.9333 +vn -0.2363 -0.2978 0.9249 +vn -0.5857 0.3416 0.7350 +vn -0.7349 -0.3419 0.5857 +vn -0.9436 0.2036 0.2610 +vn -0.9297 0.2483 0.2721 +vn -0.9985 -0.0165 0.0530 +vn -0.9911 0.0319 -0.1293 +vn -0.9345 -0.1577 -0.3191 +vn -0.9236 -0.1984 -0.3281 +vn -0.6740 0.2189 -0.7056 +vn -0.6747 0.2586 -0.6913 +vn -0.4563 -0.0628 -0.8876 +vn -0.4045 -0.0971 -0.9094 +vn 0.0006 0.0440 -0.9990 +vn 0.0320 0.0512 -0.9982 +vn 0.4582 -0.0719 -0.8859 +vn 0.3184 -0.0340 -0.9473 +vn 0.6430 0.1983 -0.7398 +vn 0.6509 0.2598 -0.7134 +vn 0.8464 -0.1755 -0.5029 +vn 0.8704 -0.1091 -0.4802 +vn 0.9361 0.0962 -0.3382 +vn 0.9738 -0.1466 -0.1738 +vn 0.9653 -0.2249 -0.1331 +vn -0.0014 1.0000 0.0093 +vn -0.0048 1.0000 -0.0031 +vn -0.0025 0.9999 0.0098 +vn 0.0005 1.0000 -0.0022 +vn 0.0141 0.9999 0.0057 +vn 0.0717 0.9254 -0.3722 +vn -0.0010 1.0000 0.0052 +vn 0.0083 0.9996 0.0257 +vn 0.0042 1.0000 -0.0025 +vn 0.0055 1.0000 -0.0050 +vn -0.0058 1.0000 0.0076 +vn 0.3585 0.9223 -0.1444 +vn -0.0107 0.9999 0.0110 +vn 0.0001 1.0000 0.0052 +vn 0.0064 1.0000 0.0016 +vn 0.0104 0.9999 0.0055 +vn 0.0002 1.0000 0.0045 +vn 0.0016 1.0000 0.0026 +vn 0.0120 0.9998 0.0160 +vn 0.0054 0.9999 0.0094 +vn 0.0190 0.9997 0.0156 +vn -0.5154 0.7980 0.3124 +vn -0.4290 0.7559 0.4945 +vn -0.1922 0.8069 0.5586 +vn -0.2178 0.7022 0.6779 +vn 0.1562 0.7886 0.5947 +vn 0.3919 0.7190 0.5739 +vn 0.4733 0.7727 0.4230 +vn 0.3709 0.7749 -0.5117 +vn -0.2292 0.6954 -0.6810 +vn -0.3419 0.8065 -0.4824 +vn -0.5499 0.7125 -0.4358 +vn -0.5907 0.8020 -0.0885 +vn -0.6911 0.7227 -0.0068 +vn -0.6557 0.7118 0.2518 +vn 0.0797 0.7289 -0.6800 +vn -0.7491 0.6132 -0.2508 +vn 0.1105 0.6785 0.7262 +vn 0.6335 0.7110 0.3052 +vn 0.6131 0.7816 0.1148 +vn 0.7617 0.6474 0.0254 +vn 0.5520 0.7348 -0.3942 +vn -0.6414 0.6111 0.4638 +vn 0.7175 0.6285 -0.3004 +vn -0.4644 0.5726 -0.6756 +vn 0.5652 0.5847 -0.5819 +vn 0.2920 0.5916 -0.7515 +vn -0.0393 0.5625 -0.8258 +vn -0.8231 0.5495 0.1434 +vn -0.5201 0.4960 0.6953 +vn 0.5487 0.5796 0.6024 +vn -0.1504 0.5091 0.8475 +vn 0.3158 0.5129 0.7982 +vn 0.7195 0.5624 0.4075 +vn -0.6212 0.5139 -0.5916 +vn 0.8344 0.5281 -0.1579 +vn 0.5859 0.5127 -0.6275 +vn -0.2729 0.4916 -0.8269 +vn -0.8140 0.5199 -0.2592 +vn -0.8755 0.4790 0.0634 +vn -0.7448 0.4696 0.4741 +vn 0.0963 0.4783 0.8729 +vn 0.5306 0.4648 0.7088 +vn 0.7910 0.4828 0.3758 +vn 0.8401 0.5250 0.1365 +vn 0.7440 0.5101 -0.4317 +vn 0.3990 0.4989 -0.7693 +vn 0.0861 0.4796 -0.8732 +vn -0.3555 0.4689 0.8086 +vn 0.7110 0.7022 0.0379 +vn 0.7221 0.6627 0.1985 +vn 0.7022 0.7117 -0.0200 +vn 0.6653 0.7249 -0.1786 +vn 0.4734 0.7422 -0.4743 +vn 0.3703 0.7218 -0.5847 +vn 0.3093 0.7035 -0.6398 +vn 0.1918 0.6562 -0.7298 +vn -0.1726 0.7424 -0.6473 +vn -0.3218 0.7216 -0.6129 +vn -0.4007 0.7028 -0.5877 +vn -0.5394 0.6546 -0.5297 +vn -0.7109 0.7023 -0.0380 +vn -0.7223 0.6619 -0.2005 +vn -0.7020 0.7118 0.0208 +vn -0.6646 0.7249 0.1814 +vn -0.3881 0.7021 0.5970 +vn -0.5334 0.6622 0.5263 +vn -0.3332 0.7117 0.6185 +vn -0.1769 0.7248 0.6659 +vn 0.1820 0.7034 0.6871 +vn 0.3498 0.7161 0.6040 +vn 0.3495 0.7161 0.6042 +vn 0.5049 0.7036 0.5000 +vn 1.0000 0.0028 -0.0001 +vn 1.0000 0.0016 0.0025 +vn 1.0000 0.0011 -0.0020 +vn 1.0000 0.0036 -0.0068 +vn 1.0000 0.0041 0.0065 +vn 0.4976 0.0020 -0.8674 +vn 0.4999 0.0031 -0.8661 +vn 0.5017 0.0010 -0.8650 +vn 0.4931 0.0051 -0.8700 +vn 0.5057 0.0033 -0.8627 +vn -0.5023 0.0021 -0.8647 +vn -0.5001 0.0031 -0.8660 +vn -0.4982 0.0011 -0.8671 +vn -0.5070 0.0053 -0.8619 +vn -0.4937 0.0036 -0.8696 +vn -1.0000 0.0011 0.0020 +vn -1.0000 0.0028 0.0001 +vn -1.0000 0.0016 -0.0025 +vn -1.0000 0.0036 0.0068 +vn -1.0000 0.0045 -0.0073 +vn -0.4981 0.0010 0.8671 +vn -0.4998 0.0028 0.8661 +vn -0.5020 0.0017 0.8649 +vn -0.4938 0.0037 0.8696 +vn -0.5058 0.0045 0.8626 +vn 0.5023 0.0014 0.8647 +vn 0.4998 0.0032 0.8661 +vn 0.4976 0.0015 0.8674 +vn 0.5064 0.0045 0.8623 +vn 0.4933 0.0044 0.8699 +vn 0.0046 0.0080 -1.0000 +vn 0.3412 0.0839 -0.9362 +vn 0.0028 0.0058 -1.0000 +vn 0.0029 0.0056 -1.0000 +vn 0.0031 0.0070 -1.0000 +vn -0.0027 -0.0002 -1.0000 +vn -0.3568 0.0949 -0.9294 +vn -0.2110 0.3017 -0.9298 +vn 0.1232 -0.3565 -0.9261 +vn 0.0015 -0.0089 -1.0000 +vn 0.0002 -0.0029 -1.0000 +vn 0.3384 -0.1650 -0.9264 +vn 0.0005 -0.0106 -0.9999 +vn -0.0010 -0.0023 -1.0000 +vn -0.0018 -0.0005 -1.0000 +vn -0.0026 0.0000 -1.0000 +vn -0.0169 0.0049 0.9998 +vn 0.0081 -0.0087 0.9999 +vn 0.0120 -0.0014 0.9999 +vn 0.0056 -0.0140 0.9999 +vn 0.0089 -0.0111 0.9999 +vn 0.0049 -0.0112 0.9999 +vn -0.0207 -0.0193 0.9996 +vn -0.0427 -0.0160 0.9990 +vn 0.0139 0.0263 0.9996 +vn -0.0058 0.0668 0.9977 +vn 0.0142 0.0302 0.9994 +vn 0.0124 0.0078 0.9999 +vn 0.9392 0.3435 -0.0048 +vn 0.9970 0.0771 0.0082 +vn 0.9615 -0.2748 -0.0008 +vn 0.9372 -0.3486 0.0046 +vn 0.6574 -0.7535 0.0001 +vn 0.6763 -0.7366 0.0051 +vn 0.2198 -0.9755 0.0061 +vn 0.1236 -0.9923 -0.0022 +vn -0.2991 -0.9542 0.0107 +vn -0.5356 -0.8444 -0.0065 +vn -0.7637 -0.6455 0.0112 +vn -0.9743 -0.2253 -0.0067 +vn -0.9803 -0.1976 0.0068 +vn -0.9714 0.2373 0.0063 +vn -0.9066 0.4219 -0.0037 +vn -0.7714 0.6363 0.0091 +vn -0.4470 0.8945 -0.0059 +vn -0.4031 0.9151 0.0060 +vn 0.0353 0.9994 0.0063 +vn 0.3745 0.9272 -0.0084 +vn 0.5004 0.8658 0.0077 +vn 0.8548 0.5189 0.0057 +vn 0.9975 0.0667 -0.0227 +vn 0.9518 0.1714 -0.2545 +vn 0.8914 0.4532 0.0038 +vn 0.8620 0.4413 -0.2493 +vn 0.7165 0.6530 -0.2454 +vn 0.6426 0.7662 0.0068 +vn 0.5004 0.8313 -0.2419 +vn 0.2996 0.9540 -0.0106 +vn 0.2457 0.9306 -0.2713 +vn -0.0967 0.9668 -0.2365 +vn -0.1546 0.9880 0.0040 +vn -0.5791 0.8150 -0.0182 +vn -0.5417 0.8021 -0.2515 +vn -0.8158 0.5384 -0.2112 +vn -0.9218 0.3871 -0.0198 +vn -0.9524 0.2048 -0.2257 +vn -0.9982 -0.0567 0.0181 +vn -0.9572 -0.1493 -0.2480 +vn -0.8989 -0.4301 -0.0839 +vn -0.7884 -0.5775 -0.2117 +vn -0.5944 -0.8038 -0.0255 +vn -0.5039 -0.8183 -0.2765 +vn -0.2720 -0.9408 -0.2023 +vn -0.0539 -0.9955 -0.0780 +vn 0.1755 -0.9597 -0.2196 +vn 0.4231 -0.9040 -0.0605 +vn 0.5745 -0.7865 -0.2267 +vn 0.7559 -0.6534 -0.0399 +vn 0.8289 -0.5073 -0.2358 +vn 0.9463 -0.3221 -0.0288 +vn 0.9574 -0.1725 -0.2317 +vn -0.6697 -0.0940 -0.7366 +vn -0.8041 -0.1703 -0.5696 +vn -0.7933 0.0714 -0.6046 +vn -0.5481 -0.1484 -0.8231 +vn -0.6191 -0.3049 -0.7237 +vn -0.6941 -0.4579 -0.5555 +vn -0.4020 -0.4387 -0.8037 +vn -0.4647 -0.5253 -0.7128 +vn -0.4006 -0.6962 -0.5957 +vn -0.2074 -0.6454 -0.7352 +vn -0.0942 -0.8257 -0.5562 +vn -0.0639 -0.5981 -0.7989 +vn 0.0832 -0.7230 -0.6858 +vn 0.3032 -0.7886 -0.5349 +vn 0.3923 -0.6226 -0.6770 +vn 0.4709 -0.3971 -0.7877 +vn 0.6215 -0.5313 -0.5757 +vn 0.7496 -0.2958 -0.5921 +vn 0.6275 -0.1147 -0.7701 +vn 0.8026 0.0057 -0.5965 +vn 0.6739 0.1430 -0.7248 +vn 0.7498 0.3409 -0.5671 +vn 0.5614 0.3345 -0.7569 +vn 0.3790 0.4675 -0.7986 +vn 0.5503 0.5326 -0.6431 +vn 0.4076 0.6912 -0.5967 +vn 0.2211 0.6003 -0.7686 +vn 0.1488 0.7709 -0.6193 +vn 0.0001 0.6059 -0.7955 +vn -0.0858 0.7584 -0.6462 +vn -0.3144 0.8081 -0.4981 +vn -0.2663 0.6222 -0.7361 +vn -0.4754 0.6178 -0.6263 +vn -0.4972 0.3726 -0.7836 +vn -0.6505 0.4986 -0.5729 +vn -0.7099 0.2536 -0.6571 +vn -0.2168 0.0256 0.9759 +vn 0.0028 0.0009 -1.0000 +vn 0.0129 0.0029 -0.9999 +vn 0.0089 0.0012 -1.0000 +vn 0.0145 -0.0164 -0.9998 +vn 0.0107 -0.0039 -0.9999 +vn 0.0146 -0.0170 -0.9997 +vn -0.0050 0.0073 -1.0000 +vn -0.0017 0.0056 -1.0000 +vn -0.0078 0.0070 -0.9999 +vn 0.0067 0.0055 -1.0000 +vn -0.0015 -0.0020 -1.0000 +vn 0.0026 -0.0012 -1.0000 +vn -0.0167 0.0126 -0.9998 +vn -0.0158 0.0141 -0.9998 +vn -0.0052 0.0004 -1.0000 +vn -0.0043 0.0004 -1.0000 +vn -0.0124 0.0026 -0.9999 +vn 0.0061 0.0055 1.0000 +vn 0.0610 -0.0073 0.9981 +vn 0.0769 -0.0022 0.9970 +vn 0.0087 -0.0129 0.9999 +vn 0.0090 -0.0165 0.9998 +vn -0.0048 -0.0065 1.0000 +vn -0.0132 -0.0050 0.9999 +vn -0.0076 -0.0105 0.9999 +vn -0.0111 -0.0019 0.9999 +vn -0.0164 0.0180 0.9997 +vn -0.0178 0.0400 0.9990 +vn -0.0149 0.0584 0.9982 +vn 0.9998 0.0201 0.0013 +vn 0.9728 -0.2315 0.0014 +vn 0.9645 -0.2639 -0.0004 +vn 0.7771 -0.6293 0.0086 +vn 0.6036 -0.7972 -0.0047 +vn 0.3489 -0.9371 0.0128 +vn -0.0868 -0.9962 -0.0080 +vn -0.2871 -0.9578 0.0110 +vn -0.4519 -0.8920 -0.0078 +vn -0.5856 -0.8105 0.0102 +vn -0.9822 -0.1878 -0.0103 +vn -0.9145 -0.4045 0.0085 +vn -0.9760 -0.2178 0.0049 +vn -0.9705 0.2410 -0.0088 +vn -0.9795 0.2013 0.0066 +vn -0.7888 0.6146 0.0088 +vn -0.5221 0.8529 -0.0047 +vn -0.4027 0.9153 0.0051 +vn -0.1868 0.9824 -0.0028 +vn -0.1496 0.9887 0.0019 +vn 0.6304 0.7763 -0.0093 +vn 0.4422 0.8968 0.0115 +vn 0.6578 0.7531 0.0113 +vn 0.6564 0.7544 -0.0092 +vn 0.8302 0.5573 0.0131 +vn 1.0000 -0.0033 -0.0015 +vn 0.9670 0.0325 -0.2527 +vn 0.8858 0.4127 -0.2123 +vn 0.9952 0.0978 0.0069 +vn 0.9368 0.3070 0.1678 +vn 0.5945 0.7770 -0.2070 +vn 0.7275 0.6660 -0.1649 +vn 0.4584 0.8887 0.0064 +vn 0.3143 0.9163 -0.2483 +vn 0.0801 0.9967 0.0127 +vn 0.0151 0.9730 -0.2304 +vn -0.3768 0.9252 -0.0445 +vn -0.2361 0.9430 -0.2348 +vn -0.5583 0.8014 -0.2147 +vn -0.7461 0.6657 -0.0079 +vn -0.8161 0.5357 -0.2168 +vn -0.9417 0.3343 -0.0385 +vn -0.9572 0.1792 -0.2273 +vn -0.9979 -0.0625 -0.0175 +vn -0.9534 -0.1838 -0.2394 +vn -0.8868 -0.4615 -0.0250 +vn -0.8323 -0.4577 -0.3125 +vn -0.6874 -0.6955 -0.2092 +vn -0.5718 -0.8201 -0.0208 +vn -0.3984 -0.8861 -0.2368 +vn -0.2177 -0.9505 -0.2215 +vn -0.1205 -0.9927 -0.0039 +vn 0.1433 -0.9630 -0.2284 +vn 0.3460 -0.9305 -0.1207 +vn 0.6090 -0.7622 -0.2193 +vn 0.7365 -0.6759 -0.0267 +vn 0.8842 -0.3958 -0.2481 +vn 0.9598 -0.2795 -0.0263 +vn -0.7327 -0.2169 -0.6451 +vn -0.7979 0.0123 -0.6026 +vn -0.6220 -0.0262 -0.7826 +vn -0.5255 -0.3438 -0.7783 +vn -0.5929 -0.4217 -0.6860 +vn -0.5867 -0.5962 -0.5480 +vn -0.4017 -0.6360 -0.6589 +vn -0.2657 -0.5379 -0.8000 +vn -0.1908 -0.6658 -0.7213 +vn -0.1283 -0.8083 -0.5746 +vn 0.0323 -0.6558 -0.7543 +vn 0.1070 -0.5505 -0.8279 +vn 0.1449 -0.7925 -0.5924 +vn 0.3041 -0.6154 -0.7272 +vn 0.3900 -0.7819 -0.4863 +vn 0.4768 -0.4123 -0.7763 +vn 0.5780 -0.5394 -0.6123 +vn 0.6611 -0.3501 -0.6635 +vn 0.6346 -0.1062 -0.7655 +vn 0.7543 -0.1616 -0.6363 +vn 0.7964 0.0522 -0.6025 +vn 0.6630 0.1991 -0.7216 +vn 0.5515 0.2039 -0.8089 +vn 0.7608 0.3017 -0.5746 +vn 0.5145 0.4220 -0.7465 +vn 0.6333 0.5512 -0.5431 +vn 0.3563 0.4745 -0.8049 +vn 0.3944 0.6447 -0.6549 +vn 0.0960 0.6632 -0.7423 +vn 0.1602 0.5731 -0.8037 +vn 0.2118 0.7836 -0.5840 +vn -0.0629 0.8156 -0.5752 +vn -0.1446 0.6056 -0.7825 +vn -0.2832 0.7247 -0.6282 +vn -0.3816 0.5624 -0.7336 +vn -0.5103 0.3687 -0.7770 +vn -0.5940 0.5647 -0.5729 +vn -0.7296 0.3456 -0.5901 +vn -0.7049 0.1581 -0.6914 +vn 0.9577 -0.2844 0.0427 +vn 0.9937 0.0977 -0.0546 +vn 0.9846 0.1604 -0.0701 +vn 0.8328 -0.0778 -0.5481 +vn 0.8392 -0.0378 -0.5425 +vn 0.8505 0.0943 -0.5175 +vn 0.8507 0.1441 -0.5055 +vn 0.5088 -0.1574 -0.8464 +vn 0.5230 -0.2293 -0.8209 +vn 0.3985 0.1984 -0.8954 +vn 0.3729 0.2598 -0.8907 +vn 0.0547 -0.1232 -0.9909 +vn 0.0846 -0.1904 -0.9780 +vn -0.0691 0.1557 -0.9854 +vn -0.0978 0.2202 -0.9705 +vn -0.3873 -0.3479 -0.8538 +vn -0.5647 0.3141 -0.7631 +vn -0.9035 -0.0761 -0.4219 +vn -0.9033 -0.0692 -0.4233 +vn -0.9027 -0.0472 -0.4276 +vn -0.9026 -0.0435 -0.4283 +vn -0.9741 0.0015 0.2260 +vn -0.9748 0.0383 0.2199 +vn -0.9498 0.2581 0.1768 +vn -0.9248 0.3472 0.1558 +vn -0.7367 -0.3538 0.5763 +vn -0.4994 0.3690 0.7839 +vn -0.3614 -0.2477 0.8989 +vn 0.0548 0.2796 0.9585 +vn 0.2274 -0.2799 0.9327 +vn 0.5240 0.2196 0.8229 +vn 0.6954 -0.3123 0.6472 +vn 0.8198 0.3255 0.4712 +vn 0.9424 -0.3300 0.0546 +vn -0.9034 -0.4282 -0.0201 +vn -0.8887 0.3532 0.2922 +vn -0.7861 -0.2982 0.5414 +vn -0.7812 -0.3315 0.5289 +vn -0.7108 0.0390 0.7023 +vn -0.6126 -0.0036 0.7904 +vn -0.4493 0.0411 0.8925 +vn -0.3056 -0.1240 0.9440 +vn -0.2380 -0.2023 0.9500 +vn -0.0752 0.3932 0.9164 +vn 0.1067 -0.3372 0.9354 +vn 0.4755 0.2250 0.8504 +vn 0.4750 0.2602 0.8407 +vn 0.4718 0.0943 0.8767 +vn 0.4710 0.0824 0.8783 +vn 0.8515 -0.0885 0.5169 +vn 0.8531 -0.0768 0.5160 +vn 0.8295 -0.2009 0.5211 +vn 0.8201 -0.2365 0.5211 +vn 0.9375 0.2644 0.2263 +vn 0.8961 -0.4434 0.0177 +vn 0.8828 0.4398 -0.1650 +vn 0.7790 -0.4141 -0.4709 +vn 0.7576 0.2372 -0.6081 +vn 0.7226 0.1539 -0.6740 +vn 0.6036 -0.0289 -0.7968 +vn 0.4501 0.0378 -0.8922 +vn 0.3058 -0.1244 -0.9439 +vn 0.2380 -0.2026 -0.9499 +vn 0.0754 0.3928 -0.9165 +vn -0.1067 -0.3372 -0.9354 +vn -0.4831 0.2062 -0.8509 +vn -0.4817 0.2747 -0.8322 +vn -0.4668 -0.0559 -0.8826 +vn -0.4611 -0.0981 -0.8819 +vn -0.8273 0.2306 -0.5122 +vn -0.8345 0.2032 -0.5121 +vn -0.8608 -0.2029 -0.4667 +vn -0.8571 -0.2311 -0.4604 +vn -0.9943 0.0981 0.0417 +vn -0.9710 -0.2118 -0.1111 +vn -0.9766 -0.1778 -0.1210 +vn -0.9155 0.0266 -0.4014 +vn -0.8830 0.0441 -0.4673 +vn -0.7493 -0.0686 -0.6587 +vn -0.7478 -0.0767 -0.6595 +vn -0.1824 0.0042 -0.9832 +vn -0.1845 -0.0076 -0.9828 +vn -0.1956 -0.0736 -0.9779 +vn -0.1979 -0.0881 -0.9763 +vn 0.3599 0.1061 -0.9269 +vn 0.3406 0.1682 -0.9250 +vn 0.4375 -0.2374 -0.8673 +vn 0.4438 -0.2841 -0.8499 +vn 0.7375 0.2821 -0.6136 +vn 0.8467 -0.2444 -0.4726 +vn 0.9807 0.1749 -0.0874 +vn 0.9718 0.2148 -0.0970 +vn 0.9908 -0.1352 -0.0090 +vn 0.9839 -0.1789 0.0022 +vn 0.8147 0.2624 0.5172 +vn 0.7073 -0.3649 0.6054 +vn 0.3417 0.3255 0.8816 +vn 0.1345 -0.3121 0.9405 +vn -0.1356 0.2766 0.9514 +vn -0.3969 -0.3633 0.8429 +vn -0.6317 0.3329 0.7001 +vn -0.8419 -0.2906 0.4546 +vn -0.8631 -0.2376 0.4456 +vn -0.9283 0.1237 0.3505 +vn -0.9259 0.1881 0.3276 +vn 0.9996 -0.0259 0.0143 +vn 0.9811 -0.0960 0.1680 +vn 0.8696 0.1029 0.4828 +vn 0.7878 0.0258 0.6154 +vn 0.5890 -0.0128 0.8080 +vn 0.5391 -0.0052 0.8422 +vn 0.2980 -0.0125 0.9545 +vn 0.1554 0.0533 0.9864 +vn -0.0231 -0.2769 0.9606 +vn -0.0292 -0.3079 0.9510 +vn -0.3351 0.3770 0.8635 +vn -0.4709 -0.5000 0.7268 +vn -0.6678 0.4458 0.5960 +vn -0.8492 -0.3539 0.3919 +vn -0.9607 0.1401 0.2396 +vn -0.9331 0.2184 0.2857 +vn -0.9951 -0.0721 0.0679 +vn -0.9694 0.2297 -0.0872 +vn -0.9567 0.2737 -0.0994 +vn -0.9081 -0.3038 -0.2884 +vn -0.7839 0.3566 -0.5083 +vn -0.7365 -0.2465 -0.6300 +vn -0.4535 0.2105 -0.8660 +vn -0.4534 0.2060 -0.8672 +vn -0.4544 0.2603 -0.8519 +vn -0.4544 0.2837 -0.8444 +vn -0.1220 -0.4003 -0.9082 +vn 0.0870 0.5296 -0.8438 +vn 0.3119 -0.4048 -0.8596 +vn 0.5792 0.2329 -0.7812 +vn 0.5638 0.2736 -0.7793 +vn 0.7024 -0.0798 -0.7072 +vn 0.8153 0.1152 -0.5675 +vn 0.9174 -0.0856 -0.3886 +vn 0.9736 0.0887 -0.2105 +s 1 +f 1/1/1 2/2/1 3/3/1 +f 3/3/1 4/4/1 1/1/1 +f 5/5/2 6/6/2 7/7/2 +f 7/7/2 8/8/2 5/5/2 +f 9/9/3 10/10/4 11/11/5 +f 12/12/6 13/13/7 10/10/4 +f 14/14/8 15/15/9 16/16/10 +f 16/16/10 15/15/9 12/12/6 +f 15/15/9 13/13/7 12/12/6 +f 17/17/11 18/18/12 11/11/5 +f 11/11/5 18/18/12 9/9/3 +f 18/18/12 17/17/11 19/19/13 +f 12/12/6 10/10/4 9/9/3 +f 20/20/14 21/21/15 14/14/8 +f 20/20/14 14/14/8 16/16/10 +f 22/22/16 23/23/17 24/24/18 +f 24/24/18 21/21/15 20/20/14 +f 19/19/13 22/22/16 18/18/12 +f 22/22/16 19/19/13 23/23/17 +f 22/22/16 24/24/18 20/20/14 +f 25/25/19 26/26/20 27/27/21 +f 25/25/19 28/28/22 26/26/20 +f 25/25/19 29/29/23 28/28/22 +f 30/30/24 29/29/23 25/25/19 +f 25/25/19 31/31/25 30/30/24 +f 25/25/19 32/32/26 31/31/25 +f 25/25/19 33/33/27 32/32/26 +f 25/25/19 34/34/28 33/33/27 +f 25/25/19 35/35/29 34/34/28 +f 36/36/30 27/27/31 26/26/32 +f 36/36/30 26/26/32 37/37/33 +f 37/37/33 26/26/32 28/28/34 +f 37/37/33 28/28/34 38/38/35 +f 38/38/35 28/28/34 29/29/36 +f 38/38/35 29/29/36 39/39/37 +f 39/39/37 29/29/36 30/30/38 +f 39/39/37 30/30/38 40/40/39 +f 40/40/39 30/30/38 31/31/40 +f 40/40/41 31/31/42 32/32/43 +f 40/40/41 32/32/43 41/41/44 +f 41/41/45 32/32/46 33/33/47 +f 41/41/45 33/33/47 42/42/48 +f 42/42/48 33/33/47 34/34/49 +f 42/42/48 34/34/49 43/43/50 +f 43/43/50 34/34/49 35/35/51 +f 43/43/52 35/35/53 25/25/54 +f 43/43/52 25/25/54 44/44/55 +f 44/44/56 25/25/57 27/27/31 +f 44/44/56 27/27/31 36/36/30 +f 36/36/1 45/45/1 46/46/1 +f 42/42/1 47/47/1 41/41/1 +f 41/41/1 47/47/1 48/48/1 +f 44/44/1 49/49/1 43/43/1 +f 36/36/1 46/46/1 44/44/1 +f 44/44/1 46/46/1 50/50/1 +f 42/42/1 51/51/1 47/47/1 +f 44/44/1 50/50/1 49/49/1 +f 43/43/1 49/49/1 52/52/1 +f 37/37/1 53/53/1 45/45/1 +f 37/37/1 45/45/1 36/36/1 +f 41/41/1 48/48/1 54/54/1 +f 41/41/1 54/54/1 40/40/1 +f 43/43/1 51/51/1 42/42/1 +f 38/38/1 53/53/1 37/37/1 +f 38/38/1 55/55/1 53/53/1 +f 43/43/1 52/52/1 51/51/1 +f 39/39/1 56/56/1 55/55/1 +f 39/39/1 55/55/1 38/38/1 +f 40/40/1 54/54/1 57/57/1 +f 40/40/1 57/57/1 39/39/1 +f 39/39/1 57/57/1 56/56/1 +f 46/46/58 58/58/59 50/50/60 +f 58/58/59 59/59/61 50/50/60 +f 59/59/61 60/60/62 50/50/60 +f 50/50/60 60/60/62 49/49/63 +f 60/60/62 61/61/64 49/49/63 +f 49/49/63 61/61/64 52/52/65 +f 61/61/64 62/62/66 52/52/65 +f 52/52/65 62/62/66 63/63/67 +f 63/63/67 51/51/68 52/52/65 +f 63/63/67 64/64/69 51/51/68 +f 65/65/70 47/47/71 51/51/68 +f 65/65/70 51/51/68 64/64/69 +f 47/47/71 65/65/70 66/66/72 +f 47/47/71 66/66/72 48/48/73 +f 66/66/72 67/67/74 48/48/73 +f 48/48/73 67/67/74 68/68/75 +f 68/68/75 54/54/76 48/48/73 +f 68/68/75 69/69/77 54/54/76 +f 69/69/77 57/57/78 54/54/76 +f 69/69/77 70/70/79 57/57/78 +f 57/57/78 70/70/79 56/56/80 +f 56/56/80 70/70/79 71/71/81 +f 56/56/80 71/71/81 55/55/82 +f 71/71/81 72/72/83 55/55/82 +f 55/55/82 72/72/83 53/53/84 +f 72/72/83 73/73/85 53/53/84 +f 53/53/84 73/73/85 74/74/86 +f 53/53/84 74/74/86 45/45/87 +f 74/74/86 75/75/88 45/45/87 +f 45/45/87 75/75/88 46/46/58 +f 46/46/58 75/75/88 58/58/59 +f 67/67/74 76/76/89 68/68/75 +f 77/77/90 68/68/75 76/76/89 +f 78/78/91 76/76/89 24/24/92 +f 24/24/92 23/23/93 78/78/91 +f 76/76/89 78/78/91 77/77/90 +f 77/77/90 69/69/77 68/68/75 +f 77/77/90 78/78/91 69/69/77 +f 79/79/94 69/69/77 78/78/91 +f 78/78/91 23/23/93 79/79/94 +f 23/23/93 80/80/95 79/79/94 +f 69/69/77 79/79/94 70/70/79 +f 79/79/94 81/81/96 70/70/79 +f 81/81/96 79/79/94 80/80/95 +f 19/19/97 80/80/95 23/23/93 +f 82/82/98 70/70/79 81/81/96 +f 80/80/95 19/19/97 83/83/99 +f 80/80/95 83/83/99 81/81/96 +f 81/81/96 83/83/99 82/82/98 +f 82/82/98 71/71/81 70/70/79 +f 71/71/81 82/82/98 84/84/100 +f 84/84/100 82/82/98 83/83/99 +f 17/17/101 83/83/99 19/19/97 +f 83/83/99 17/17/101 84/84/100 +f 72/72/83 71/71/81 84/84/100 +f 84/84/100 17/17/101 85/85/102 +f 84/84/100 85/85/102 72/72/83 +f 73/73/85 72/72/83 85/85/102 +f 86/86/103 85/85/102 17/17/101 +f 86/86/103 17/17/101 11/11/104 +f 87/87/105 85/85/102 86/86/103 +f 85/85/102 87/87/105 73/73/85 +f 73/73/85 87/87/105 74/74/86 +f 88/88/106 87/87/105 86/86/103 +f 11/11/104 88/88/106 86/86/103 +f 10/10/107 88/88/106 11/11/104 +f 74/74/86 87/87/105 75/75/88 +f 87/87/105 88/88/106 89/89/108 +f 87/87/105 89/89/108 75/75/88 +f 89/89/108 88/88/106 10/10/107 +f 90/90/109 89/89/108 10/10/107 +f 89/89/108 91/91/110 75/75/88 +f 89/89/108 90/90/109 91/91/110 +f 75/75/88 91/91/110 58/58/59 +f 10/10/107 13/13/7 90/90/109 +f 59/59/61 58/58/59 91/91/110 +f 90/90/109 13/13/7 92/92/111 +f 90/90/109 92/92/111 91/91/110 +f 93/93/112 59/59/61 91/91/110 +f 93/93/112 91/91/110 92/92/111 +f 60/60/62 59/59/61 93/93/112 +f 94/94/113 92/92/111 13/13/7 +f 95/95/114 93/93/112 92/92/111 +f 95/95/114 92/92/111 94/94/113 +f 93/93/112 95/95/114 60/60/62 +f 15/15/9 94/94/113 13/13/7 +f 61/61/64 60/60/62 95/95/114 +f 61/61/64 95/95/114 96/96/115 +f 96/96/115 95/95/114 94/94/113 +f 97/97/116 96/96/115 15/15/9 +f 15/15/9 96/96/115 94/94/113 +f 61/61/64 96/96/115 62/62/66 +f 15/15/9 14/14/117 97/97/116 +f 96/96/115 97/97/116 98/98/118 +f 62/62/66 96/96/115 63/63/67 +f 98/98/118 63/63/67 96/96/115 +f 97/97/116 14/14/117 98/98/118 +f 64/64/69 63/63/67 98/98/118 +f 99/99/119 64/64/69 98/98/118 +f 99/99/119 98/98/118 14/14/117 +f 64/64/69 99/99/119 65/65/70 +f 100/100/120 99/99/119 14/14/117 +f 100/100/120 14/14/117 21/21/121 +f 99/99/119 100/100/120 65/65/70 +f 66/66/72 65/65/70 100/100/120 +f 100/100/120 21/21/121 101/101/122 +f 102/102/123 66/66/72 100/100/120 +f 102/102/123 100/100/120 101/101/122 +f 66/66/72 102/102/123 67/67/74 +f 67/67/74 102/102/123 76/76/89 +f 76/76/89 102/102/123 101/101/122 +f 24/24/92 101/101/122 21/21/121 +f 76/76/89 101/101/122 24/24/92 +f 12/12/124 9/9/124 103/103/124 +f 103/103/124 9/9/124 104/104/124 +f 16/16/125 12/12/125 105/105/125 +f 105/105/125 12/12/125 103/103/126 +f 20/20/127 16/16/127 106/106/127 +f 106/106/127 16/16/127 105/105/127 +f 22/22/128 20/20/128 107/107/128 +f 107/107/128 20/20/128 106/106/128 +f 18/18/129 22/22/129 108/108/129 +f 108/108/129 22/22/129 107/107/129 +f 9/9/130 18/18/130 104/104/130 +f 104/104/130 18/18/130 108/108/130 +f 108/108/2 107/107/2 104/104/2 +f 104/104/2 107/107/2 106/106/2 +f 104/104/2 106/106/2 103/103/2 +f 103/103/2 106/106/2 105/105/2 +f 109/109/131 110/110/132 111/111/133 +f 112/112/134 110/110/132 109/109/131 +f 113/113/135 111/111/133 110/110/132 +f 114/114/136 113/113/135 115/115/137 +f 115/115/137 116/116/138 117/117/139 +f 118/118/140 117/117/139 116/116/138 +f 119/119/141 120/120/142 121/121/143 +f 122/122/144 123/123/145 124/124/146 +f 125/125/147 126/126/147 127/127/147 +f 128/128/147 127/127/147 129/129/147 +f 130/130/147 131/131/147 132/132/147 +f 128/128/147 129/129/147 133/133/147 +f 134/134/147 126/126/147 125/125/147 +f 134/134/147 135/135/147 126/126/147 +f 125/125/147 127/127/147 128/128/147 +f 136/136/148 137/137/149 138/138/150 +f 136/136/148 138/138/150 139/139/151 +f 140/140/152 137/137/149 136/136/148 +f 140/140/152 135/135/153 137/137/149 +f 141/141/154 135/135/153 140/140/152 +f 141/141/154 126/126/155 135/135/153 +f 142/142/156 143/143/157 144/144/158 +f 142/142/156 144/144/158 145/145/159 +f 146/146/160 147/147/161 148/148/162 +f 149/149/163 150/150/164 151/151/165 +f 151/151/165 150/150/164 152/152/166 +f 153/153/167 154/154/168 155/155/169 +f 153/153/167 156/156/170 154/154/168 +f 157/157/171 158/158/172 156/156/170 +f 159/159/173 160/160/174 158/158/172 +f 159/159/173 158/158/172 157/157/171 +f 139/139/151 160/160/174 159/159/173 +f 161/161/2 162/162/2 163/163/2 +f 139/139/151 138/138/150 160/160/174 +f 161/161/2 164/164/2 162/162/2 +f 165/165/175 150/150/164 149/149/163 +f 149/149/163 166/166/176 165/165/175 +f 143/143/157 167/167/177 144/144/158 +f 148/148/162 166/166/176 146/146/160 +f 146/146/160 168/168/178 147/147/161 +f 148/148/162 165/165/175 166/166/176 +f 167/167/177 143/143/157 169/169/179 +f 169/169/179 151/151/165 152/152/166 +f 167/167/177 169/169/179 152/152/166 +f 170/170/147 171/171/147 172/172/147 +f 164/164/180 161/161/181 173/173/182 +f 161/161/181 174/174/183 173/173/182 +f 163/163/184 162/162/185 175/175/186 +f 175/175/186 162/162/185 176/176/187 +f 168/168/178 146/146/188 177/177/189 +f 176/176/190 152/152/191 150/150/192 +f 178/178/193 152/152/191 176/176/190 +f 178/178/193 167/167/194 152/152/191 +f 171/171/195 144/144/196 178/178/193 +f 178/178/193 144/144/196 167/167/194 +f 171/171/195 145/145/159 144/144/196 +f 170/170/197 145/145/159 171/171/195 +f 142/142/156 145/145/159 170/170/197 +f 179/179/198 142/142/156 170/170/197 +f 142/142/156 179/179/198 143/143/199 +f 143/143/199 179/179/198 172/172/200 +f 172/172/200 169/169/201 143/143/199 +f 174/174/183 149/149/202 151/151/203 +f 173/173/182 151/151/203 172/172/200 +f 172/172/200 151/151/203 169/169/201 +f 180/180/204 149/149/202 174/174/183 +f 180/180/204 166/166/205 149/149/202 +f 181/181/206 166/166/205 180/180/204 +f 177/177/189 146/146/188 181/181/206 +f 181/181/206 146/146/188 166/166/205 +f 182/182/207 168/168/178 177/177/189 +f 182/182/207 147/147/161 168/168/178 +f 147/147/161 182/182/207 183/183/208 +f 147/147/161 183/183/208 148/148/209 +f 175/175/210 165/165/211 183/183/208 +f 183/183/208 165/165/211 148/148/209 +f 175/175/210 150/150/212 165/165/211 +f 151/151/203 173/173/182 174/174/183 +f 150/150/213 175/175/213 176/176/213 +f 141/141/214 119/119/215 123/123/216 +f 139/139/217 117/117/218 136/136/219 +f 140/140/220 119/119/215 141/141/214 +f 136/136/219 184/184/221 140/140/220 +f 136/136/219 117/117/218 184/184/221 +f 140/140/220 184/184/221 119/119/215 +f 185/185/222 115/115/223 113/113/224 +f 186/186/225 115/115/223 185/185/222 +f 110/110/226 185/185/222 113/113/224 +f 187/187/227 131/131/228 188/188/229 +f 189/189/230 129/129/231 127/127/232 +f 189/189/230 127/127/232 190/190/233 +f 188/188/229 131/131/228 133/133/234 +f 157/157/171 156/156/170 153/153/167 +f 155/155/169 154/154/168 191/191/235 +f 192/192/236 191/191/237 193/193/238 +f 155/155/169 191/191/235 192/192/239 +f 192/192/236 193/193/238 194/194/240 +f 194/194/241 193/193/242 187/187/243 +f 188/188/229 133/133/234 189/189/230 +f 187/187/243 193/193/242 131/131/244 +f 190/190/245 127/127/246 126/126/155 +f 190/190/245 126/126/155 141/141/154 +f 189/189/230 133/133/234 129/129/231 +f 124/124/247 195/195/248 196/196/249 +f 121/121/250 195/195/248 124/124/247 +f 195/195/248 121/121/250 120/120/251 +f 195/195/248 120/120/251 118/118/252 +f 195/195/248 118/118/252 197/197/253 +f 197/197/253 118/118/252 116/116/254 +f 197/197/253 116/116/254 186/186/225 +f 115/115/223 186/186/225 116/116/254 +f 198/198/255 199/199/256 200/200/257 +f 201/201/258 199/199/256 198/198/255 +f 202/202/259 200/200/257 203/203/260 +f 198/198/255 200/200/257 202/202/259 +f 204/204/261 203/203/260 205/205/262 +f 202/202/259 203/203/260 204/204/261 +f 201/201/258 206/206/263 199/199/256 +f 207/207/264 206/206/263 201/201/258 +f 208/208/265 209/209/266 210/210/266 +f 208/208/265 211/211/267 209/209/266 +f 212/212/268 211/211/267 208/208/265 +f 212/212/268 205/205/262 211/211/267 +f 204/204/261 205/205/262 212/212/268 +f 207/207/264 213/213/269 206/206/263 +f 214/214/270 213/213/269 207/207/264 +f 185/185/222 110/110/226 215/215/271 +f 112/112/272 215/215/271 110/110/226 +f 216/216/273 215/215/271 112/112/272 +f 215/215/271 217/217/274 218/218/275 +f 215/215/271 216/216/273 217/217/274 +f 218/218/275 217/217/274 219/219/276 +f 219/219/276 220/220/277 218/218/275 +f 220/220/277 219/219/276 221/221/278 +f 220/220/277 221/221/278 222/222/279 +f 222/222/279 223/223/280 220/220/277 +f 223/223/280 222/222/279 224/224/281 +f 224/224/281 225/225/282 223/223/280 +f 225/225/282 224/224/281 226/226/283 +f 182/182/266 177/177/266 183/183/266 +f 181/181/266 175/175/266 183/183/266 +f 172/172/147 179/179/147 170/170/147 +f 164/164/147 173/173/147 176/176/147 +f 183/183/266 177/177/266 181/181/266 +f 181/181/266 180/180/266 174/174/266 +f 174/174/266 161/161/266 175/175/266 +f 171/171/147 178/178/147 173/173/147 +f 173/173/147 172/172/147 171/171/147 +f 161/161/266 163/163/266 175/175/266 +f 178/178/147 176/176/147 173/173/147 +f 176/176/147 162/162/147 164/164/147 +f 174/174/266 175/175/266 181/181/266 +f 226/226/284 227/227/285 228/228/286 +f 131/131/147 193/193/147 132/132/147 +f 229/229/147 156/156/147 158/158/147 +f 230/230/147 156/156/147 229/229/147 +f 231/231/147 138/138/147 232/232/147 +f 233/233/147 191/191/147 230/230/147 +f 134/134/147 137/137/147 135/135/147 +f 231/231/147 158/158/147 160/160/147 +f 130/130/147 133/133/147 131/131/147 +f 230/230/147 191/191/147 154/154/147 +f 233/233/147 193/193/147 191/191/147 +f 132/132/147 193/193/147 233/233/147 +f 231/231/147 160/160/147 138/138/147 +f 230/230/147 154/154/147 156/156/147 +f 232/232/147 137/137/147 134/134/147 +f 229/229/147 158/158/147 231/231/147 +f 128/128/147 133/133/147 130/130/147 +f 234/234/287 213/213/269 214/214/270 +f 235/235/288 236/236/266 234/234/287 +f 210/210/266 236/236/266 235/235/288 +f 210/210/266 209/209/266 236/236/266 +f 235/235/288 234/234/287 214/214/270 +f 231/231/289 214/214/290 207/207/291 +f 232/232/292 214/214/290 231/231/289 +f 134/134/293 214/214/290 232/232/292 +f 134/134/293 235/235/294 214/214/290 +f 125/125/295 235/235/294 134/134/293 +f 125/125/295 210/210/296 235/235/294 +f 125/125/295 208/208/297 210/210/296 +f 128/128/298 208/208/297 125/125/295 +f 128/128/299 212/212/300 208/208/301 +f 130/130/302 212/212/300 128/128/299 +f 130/130/302 204/204/303 212/212/300 +f 132/132/304 204/204/303 130/130/302 +f 132/132/304 202/202/305 204/204/303 +f 233/233/306 202/202/305 132/132/304 +f 230/230/307 202/202/305 233/233/306 +f 230/230/307 198/198/308 202/202/305 +f 229/229/309 198/198/310 230/230/311 +f 229/229/309 201/201/312 198/198/310 +f 231/231/313 201/201/314 229/229/315 +f 231/231/313 207/207/316 201/201/314 +f 232/232/147 138/138/147 137/137/147 +f 157/157/317 111/111/318 159/159/319 +f 155/155/320 237/237/321 238/238/322 +f 192/192/323 237/237/321 155/155/320 +f 194/194/324 227/227/325 239/239/326 +f 187/187/327 227/227/325 194/194/324 +f 157/157/317 109/109/328 111/111/318 +f 192/192/323 239/239/326 237/237/321 +f 194/194/324 239/239/326 192/192/323 +f 187/187/327 228/228/329 227/227/325 +f 159/159/319 114/114/330 139/139/217 +f 159/159/319 111/111/318 114/114/330 +f 155/155/320 238/238/322 153/153/331 +f 139/139/217 114/114/330 117/117/218 +f 153/153/331 109/109/328 157/157/317 +f 153/153/331 238/238/322 109/109/328 +f 188/188/332 240/240/333 241/241/334 +f 189/189/335 240/240/333 188/188/332 +f 242/242/336 240/240/333 189/189/335 +f 190/190/337 123/123/216 242/242/336 +f 190/190/337 242/242/336 189/189/335 +f 187/187/327 241/241/334 228/228/329 +f 188/188/332 241/241/334 187/187/327 +f 141/141/214 123/123/216 190/190/337 +f 226/226/283 243/243/338 225/225/282 +f 244/244/339 243/243/338 226/226/283 +f 243/243/338 244/244/339 245/245/340 +f 246/246/341 243/243/338 245/245/340 +f 246/246/341 247/247/342 243/243/338 +f 248/248/343 247/247/342 246/246/341 +f 247/247/342 248/248/343 249/249/344 +f 249/249/344 248/248/343 250/250/345 +f 122/122/346 249/249/344 250/250/345 +f 122/122/346 196/196/249 249/249/344 +f 124/124/247 196/196/249 122/122/346 +f 250/250/347 123/123/145 122/122/144 +f 123/123/145 250/250/347 242/242/348 +f 248/248/349 242/242/350 250/250/351 +f 246/246/352 242/242/350 248/248/349 +f 242/242/350 246/246/352 240/240/353 +f 240/240/353 246/246/352 245/245/354 +f 226/226/284 228/228/286 241/241/355 +f 226/226/284 241/241/355 244/244/356 +f 239/239/357 224/224/358 222/222/359 +f 221/221/360 237/237/361 239/239/357 +f 216/216/362 238/238/363 217/217/274 +f 112/112/134 109/109/131 216/216/362 +f 114/114/136 111/111/133 113/113/135 +f 117/117/139 114/114/136 115/115/137 +f 184/184/364 117/117/139 118/118/140 +f 120/120/142 184/184/364 118/118/140 +f 119/119/141 184/184/364 120/120/142 +f 124/124/146 119/119/141 121/121/143 +f 124/124/146 123/123/145 119/119/141 +f 241/241/355 240/240/353 245/245/354 +f 245/245/354 244/244/356 241/241/355 +f 217/217/274 238/238/363 237/237/361 +f 247/247/342 211/211/365 205/205/366 +f 249/249/344 211/211/365 247/247/342 +f 247/247/342 205/205/366 243/243/338 +f 249/249/344 209/209/367 211/211/365 +f 237/237/361 219/219/276 217/217/274 +f 238/238/363 216/216/362 109/109/131 +f 196/196/249 209/209/367 249/249/344 +f 196/196/249 236/236/368 209/209/367 +f 195/195/248 236/236/368 196/196/249 +f 195/195/248 234/234/369 236/236/368 +f 197/197/253 234/234/369 195/195/248 +f 197/197/253 213/213/370 234/234/369 +f 186/186/225 213/213/370 197/197/253 +f 186/186/225 206/206/371 213/213/372 +f 185/185/222 206/206/371 186/186/225 +f 215/215/271 206/206/371 185/185/222 +f 215/215/271 199/199/373 206/206/371 +f 218/218/275 199/199/374 215/215/271 +f 226/226/284 224/224/358 227/227/285 +f 224/224/358 239/239/357 227/227/285 +f 221/221/360 239/239/357 222/222/359 +f 219/219/276 237/237/361 221/221/360 +f 218/218/275 200/200/375 199/199/374 +f 220/220/277 200/200/376 218/218/275 +f 220/220/377 203/203/377 200/200/377 +f 223/223/280 203/203/378 220/220/277 +f 225/225/282 203/203/378 223/223/280 +f 225/225/282 205/205/366 203/203/379 +f 243/243/338 205/205/366 225/225/282 +f 251/251/380 252/252/381 253/253/382 +f 251/251/380 253/253/382 254/254/383 +f 255/255/384 256/256/385 254/254/386 +f 255/255/384 254/254/386 253/253/387 +f 256/256/388 255/255/389 257/257/390 +f 256/256/388 257/257/390 258/258/391 +f 251/251/392 258/258/393 252/252/394 +f 252/252/394 258/258/393 257/257/395 +f 253/253/1 252/252/1 255/255/1 +f 255/255/1 252/252/1 257/257/1 +f 251/251/2 254/254/2 258/258/2 +f 258/258/2 254/254/2 256/256/2 +f 259/259/396 260/260/397 261/261/398 +f 262/262/399 263/263/400 264/264/401 +f 265/265/402 266/266/403 267/267/404 +f 265/265/402 267/267/404 268/268/405 +f 268/268/405 267/267/404 269/269/406 +f 263/263/400 266/266/403 265/265/402 +f 270/270/2 271/271/407 272/272/408 +f 260/260/397 272/272/408 261/261/398 +f 268/268/405 269/269/406 261/261/398 +f 261/261/398 269/269/406 259/259/396 +f 260/260/397 270/270/2 272/272/408 +f 264/264/401 263/263/400 265/265/402 +f 273/273/409 274/274/410 275/275/411 +f 273/273/409 275/275/411 271/271/407 +f 271/271/407 275/275/411 272/272/408 +f 275/275/411 274/274/410 262/262/399 +f 275/275/411 262/262/399 264/264/401 +f 276/276/412 277/277/413 278/278/414 +f 276/276/412 279/279/415 277/277/413 +f 280/280/416 279/279/415 276/276/412 +f 276/276/412 281/281/417 280/280/416 +f 276/276/412 282/282/418 281/281/417 +f 276/276/412 283/283/419 282/282/418 +f 276/276/412 284/284/420 283/283/419 +f 276/276/412 285/285/421 284/284/420 +f 276/276/412 286/286/422 285/285/421 +f 278/278/414 287/287/423 276/276/412 +f 288/288/424 278/278/425 277/277/426 +f 288/288/424 277/277/426 289/289/427 +f 289/289/428 277/277/429 279/279/430 +f 289/289/428 279/279/430 290/290/431 +f 290/290/432 279/279/433 291/291/434 +f 291/291/434 279/279/433 280/280/435 +f 291/291/434 280/280/435 281/281/436 +f 291/291/434 281/281/436 292/292/437 +f 292/292/437 281/281/436 282/282/438 +f 292/292/437 282/282/438 283/283/439 +f 292/292/437 283/283/439 293/293/440 +f 293/293/440 283/283/439 284/284/441 +f 293/293/440 284/284/441 294/294/442 +f 294/294/442 284/284/441 285/285/443 +f 294/294/444 285/285/445 286/286/446 +f 294/294/444 286/286/446 295/295/447 +f 295/295/448 286/286/449 276/276/450 +f 295/295/448 276/276/450 296/296/451 +f 296/296/451 276/276/450 287/287/452 +f 296/296/451 287/287/452 278/278/425 +f 296/296/451 278/278/425 288/288/424 +f 288/288/1 297/297/1 298/298/1 +f 294/294/1 299/299/1 293/293/1 +f 294/294/1 300/300/1 299/299/1 +f 296/296/1 301/301/1 295/295/1 +f 288/288/1 298/298/1 296/296/1 +f 299/299/1 302/302/1 293/293/1 +f 293/293/1 302/302/1 292/292/1 +f 294/294/1 303/303/1 300/300/1 +f 296/296/1 298/298/1 301/301/1 +f 295/295/1 301/301/1 304/304/1 +f 289/289/1 305/305/1 297/297/1 +f 289/289/1 297/297/1 288/288/1 +f 292/292/1 302/302/1 306/306/1 +f 290/290/1 305/305/1 289/289/1 +f 290/290/1 307/307/1 305/305/1 +f 295/295/1 304/304/1 294/294/1 +f 294/294/1 304/304/1 303/303/1 +f 291/291/1 308/308/1 307/307/1 +f 291/291/1 307/307/1 290/290/1 +f 292/292/1 306/306/1 291/291/1 +f 306/306/1 309/309/1 291/291/1 +f 291/291/1 309/309/1 308/308/1 +f 310/310/453 311/311/454 298/298/455 +f 311/311/454 301/301/456 298/298/457 +f 301/301/456 311/311/454 312/312/458 +f 312/312/458 313/313/459 301/301/456 +f 301/301/456 313/313/459 304/304/460 +f 313/313/459 314/314/461 304/304/460 +f 304/304/460 314/314/461 315/315/462 +f 315/315/462 303/303/463 304/304/460 +f 315/315/462 300/300/464 303/303/463 +f 315/315/462 316/316/465 300/300/464 +f 316/316/465 299/299/466 300/300/464 +f 299/299/466 316/316/465 317/317/467 +f 318/318/468 302/302/469 299/299/466 +f 318/318/468 299/299/466 317/317/467 +f 318/318/468 319/319/470 302/302/469 +f 302/302/469 319/319/470 306/306/471 +f 306/306/471 319/319/470 320/320/472 +f 306/306/471 320/320/472 309/309/473 +f 320/320/472 321/321/474 309/309/473 +f 321/321/474 322/322/475 309/309/473 +f 309/309/473 322/322/475 308/308/476 +f 322/322/475 323/323/477 308/308/476 +f 308/308/476 323/323/477 307/307/478 +f 323/323/477 324/324/479 307/307/478 +f 307/307/478 324/324/479 305/305/480 +f 324/324/479 325/325/481 305/305/480 +f 325/325/481 326/326/482 305/305/480 +f 305/305/480 326/326/482 297/297/483 +f 326/326/482 327/327/484 297/297/483 +f 297/297/483 327/327/484 298/298/455 +f 298/298/455 327/327/484 310/310/453 +f 328/328/485 274/274/486 329/329/487 +f 328/328/485 329/329/487 330/330/488 +f 319/319/470 318/318/468 330/330/488 +f 319/319/470 330/330/488 329/329/487 +f 274/274/486 331/331/489 329/329/487 +f 329/329/487 320/320/472 319/319/470 +f 320/320/472 329/329/487 331/331/489 +f 331/331/489 274/274/486 273/273/490 +f 332/332/491 320/320/472 331/331/489 +f 273/273/490 333/333/492 331/331/489 +f 320/320/472 332/332/491 321/321/474 +f 332/332/491 331/331/489 333/333/492 +f 321/321/474 332/332/491 322/322/475 +f 332/332/491 333/333/492 334/334/493 +f 271/271/494 333/333/492 273/273/490 +f 271/271/494 334/334/493 333/333/492 +f 332/332/491 334/334/493 322/322/475 +f 335/335/495 334/334/493 271/271/494 +f 323/323/477 322/322/475 334/334/493 +f 323/323/477 334/334/493 336/336/496 +f 336/336/496 334/334/493 335/335/495 +f 270/270/497 335/335/495 271/271/494 +f 335/335/495 270/270/497 337/337/498 +f 335/335/495 337/337/498 336/336/496 +f 324/324/479 323/323/477 336/336/496 +f 336/336/496 337/337/498 324/324/479 +f 260/260/499 337/337/498 270/270/497 +f 338/338/500 337/337/498 260/260/499 +f 337/337/498 338/338/500 324/324/479 +f 324/324/479 338/338/500 339/339/501 +f 325/325/481 324/324/479 339/339/501 +f 339/339/501 326/326/482 325/325/481 +f 326/326/482 339/339/501 338/338/500 +f 338/338/500 340/340/502 326/326/482 +f 260/260/499 340/340/502 338/338/500 +f 326/326/482 340/340/502 327/327/484 +f 259/259/503 340/340/502 260/260/499 +f 327/327/484 340/340/502 341/341/504 +f 340/340/502 259/259/503 341/341/504 +f 310/310/453 327/327/484 341/341/504 +f 341/341/504 259/259/503 342/342/505 +f 342/342/505 310/310/453 341/341/504 +f 259/259/503 269/269/506 343/343/507 +f 259/259/503 343/343/507 342/342/505 +f 311/311/454 310/310/453 342/342/505 +f 344/344/508 311/311/454 342/342/505 +f 344/344/508 342/342/505 343/343/507 +f 312/312/458 311/311/454 344/344/508 +f 267/267/509 343/343/507 269/269/506 +f 345/345/510 344/344/508 267/267/509 +f 267/267/509 344/344/508 343/343/507 +f 344/344/508 345/345/510 312/312/458 +f 313/313/459 312/312/458 345/345/510 +f 267/267/509 346/346/511 345/345/510 +f 347/347/512 313/313/459 345/345/510 +f 266/266/403 346/346/511 267/267/509 +f 345/345/510 346/346/511 347/347/512 +f 347/347/512 346/346/511 348/348/513 +f 313/313/459 347/347/512 314/314/461 +f 348/348/513 314/314/461 347/347/512 +f 346/346/511 266/266/403 348/348/513 +f 314/314/461 348/348/513 315/315/462 +f 349/349/514 348/348/513 266/266/403 +f 348/348/513 350/350/515 315/315/462 +f 350/350/515 348/348/513 349/349/514 +f 266/266/403 263/263/400 349/349/514 +f 350/350/515 351/351/516 315/315/462 +f 351/351/516 350/350/515 349/349/514 +f 351/351/516 349/349/514 352/352/517 +f 352/352/517 349/349/514 263/263/400 +f 315/315/462 351/351/516 316/316/465 +f 353/353/518 351/351/516 352/352/517 +f 351/351/516 353/353/518 316/316/465 +f 353/353/518 352/352/517 263/263/400 +f 353/353/518 317/317/467 316/316/465 +f 317/317/467 353/353/518 328/328/485 +f 353/353/518 263/263/400 262/262/519 +f 317/317/467 328/328/485 330/330/488 +f 318/318/468 317/317/467 330/330/488 +f 328/328/485 353/353/518 262/262/519 +f 262/262/519 274/274/486 328/328/485 +f 268/268/124 261/261/124 354/354/124 +f 354/354/124 261/261/124 355/355/124 +f 265/265/125 268/268/125 356/356/125 +f 356/356/125 268/268/125 354/354/126 +f 264/264/127 265/265/127 357/357/127 +f 357/357/127 265/265/127 356/356/127 +f 275/275/128 264/264/128 358/358/128 +f 358/358/128 264/264/128 357/357/128 +f 272/272/129 275/275/129 359/359/129 +f 359/359/129 275/275/129 358/358/129 +f 261/261/130 272/272/130 355/355/130 +f 355/355/130 272/272/130 359/359/130 +f 359/359/2 358/358/2 355/355/2 +f 355/355/2 358/358/2 357/357/2 +f 355/355/2 357/357/2 354/354/2 +f 354/354/2 357/357/2 356/356/2 +f 360/360/520 361/361/521 362/362/522 +f 361/361/521 363/363/523 362/362/522 +f 364/364/524 363/363/523 361/361/521 +f 361/361/521 365/365/525 364/364/524 +f 361/361/521 366/366/526 365/365/525 +f 367/367/527 368/368/528 369/369/529 +f 369/369/529 368/368/528 370/370/530 +f 370/370/530 368/368/528 371/371/531 +f 370/370/530 371/371/531 372/372/532 +f 372/372/532 371/371/531 373/373/533 +f 372/372/532 373/373/533 374/374/534 +f 373/373/533 375/375/535 374/374/534 +f 374/374/534 375/375/535 376/376/536 +f 376/376/536 375/375/535 377/377/537 +f 376/376/536 377/377/537 378/378/538 +f 378/378/538 377/377/537 379/379/539 +f 378/378/538 379/379/539 380/380/540 +f 380/380/540 379/379/539 381/381/541 +f 379/379/539 382/382/542 381/381/541 +f 381/381/543 382/382/544 383/383/545 +f 381/381/543 383/383/545 384/384/546 +f 383/383/545 385/385/547 384/384/546 +f 384/384/546 385/385/547 369/369/548 +f 385/385/547 367/367/549 369/369/548 +f 365/365/550 377/377/551 364/364/552 +f 364/364/552 377/377/551 375/375/553 +f 375/375/553 373/373/554 364/364/552 +f 364/364/552 373/373/554 363/363/555 +f 363/363/555 373/373/554 371/371/556 +f 363/363/555 371/371/556 362/362/557 +f 362/362/557 371/371/556 368/368/558 +f 368/368/558 367/367/559 362/362/557 +f 362/362/557 367/367/559 360/360/560 +f 367/367/559 385/385/561 360/360/560 +f 360/360/560 385/385/561 361/361/562 +f 385/385/561 383/383/563 361/361/562 +f 361/361/562 383/383/563 382/382/564 +f 361/361/562 382/382/564 366/366/565 +f 382/382/564 379/379/566 366/366/565 +f 366/366/565 379/379/566 365/365/567 +f 365/365/567 379/379/566 377/377/568 +f 369/369/147 386/386/147 387/387/147 +f 369/369/147 387/387/147 384/384/147 +f 370/370/147 388/388/147 369/369/147 +f 369/369/147 388/388/147 386/386/147 +f 372/372/147 389/389/147 390/390/147 +f 372/372/147 390/390/147 370/370/147 +f 378/378/147 391/391/147 376/376/147 +f 384/384/147 392/392/147 381/381/147 +f 384/384/147 393/393/147 392/392/147 +f 387/387/147 393/393/147 384/384/147 +f 370/370/147 390/390/147 388/388/147 +f 378/378/147 394/394/147 391/391/147 +f 380/380/147 395/395/147 394/394/147 +f 380/380/147 394/394/147 378/378/147 +f 374/374/147 396/396/147 397/397/147 +f 374/374/147 389/389/147 372/372/147 +f 374/374/147 397/397/147 389/389/147 +f 376/376/147 396/396/147 374/374/147 +f 376/376/147 391/391/147 396/396/147 +f 381/381/147 395/395/147 380/380/147 +f 381/381/147 392/392/147 398/398/147 +f 381/381/147 398/398/147 395/395/147 +f 399/399/569 400/400/570 401/401/571 +f 402/402/572 403/403/573 404/404/574 +f 404/404/574 403/403/573 405/405/575 +f 404/404/574 405/405/575 406/406/576 +f 406/406/576 405/405/575 407/407/577 +f 407/407/577 408/408/578 399/399/569 +f 399/399/569 408/408/578 400/400/570 +f 409/409/579 410/410/580 411/411/581 +f 409/409/579 411/411/581 412/412/582 +f 407/407/577 405/405/575 408/408/578 +f 401/401/571 400/400/570 413/413/583 +f 414/414/584 410/410/580 409/409/579 +f 415/415/585 416/416/586 417/417/587 +f 402/402/572 418/418/588 403/403/573 +f 419/419/589 420/420/590 414/414/584 +f 414/414/584 420/420/590 410/410/580 +f 415/415/585 417/417/587 402/402/572 +f 402/402/572 417/417/587 418/418/588 +f 401/401/571 413/413/583 421/421/591 +f 422/422/592 423/423/593 424/424/594 +f 422/422/592 424/424/594 419/419/589 +f 419/419/589 424/424/594 420/420/590 +f 421/421/591 413/413/583 423/423/593 +f 421/421/591 423/423/593 422/422/592 +f 412/412/582 411/411/581 416/416/586 +f 412/412/582 416/416/586 415/415/585 +f 389/389/595 419/419/596 390/390/597 +f 390/390/598 419/419/599 414/414/600 +f 390/390/598 414/414/600 388/388/601 +f 388/388/601 414/414/600 386/386/602 +f 386/386/602 414/414/600 409/409/603 +f 386/386/602 409/409/603 412/412/604 +f 386/386/602 412/412/604 387/387/605 +f 387/387/606 412/412/607 415/415/608 +f 387/387/606 415/415/608 393/393/609 +f 393/393/609 415/415/608 402/402/610 +f 393/393/609 402/402/610 392/392/611 +f 392/392/612 402/402/613 404/404/614 +f 392/392/612 404/404/614 398/398/615 +f 398/398/615 404/404/614 395/395/616 +f 395/395/616 404/404/614 406/406/617 +f 395/395/616 406/406/617 407/407/618 +f 395/395/616 407/407/618 394/394/619 +f 394/394/620 407/407/620 399/399/620 +f 394/394/621 399/399/621 391/391/621 +f 391/391/622 399/399/622 401/401/622 +f 391/391/623 401/401/623 396/396/623 +f 396/396/624 401/401/625 421/421/626 +f 396/396/624 421/421/626 397/397/627 +f 397/397/627 421/421/626 422/422/628 +f 397/397/627 422/422/628 389/389/595 +f 389/389/595 422/422/628 419/419/596 +f 425/425/629 426/426/630 427/427/631 +f 426/426/630 428/428/632 429/429/633 +f 430/430/634 431/431/635 432/432/636 +f 426/426/630 433/433/637 428/428/632 +f 427/427/631 434/434/638 425/425/629 +f 435/435/639 434/434/638 427/427/631 +f 431/431/635 436/436/640 437/437/641 +f 436/436/640 438/438/642 439/439/643 +f 439/439/643 438/438/642 440/440/644 +f 425/425/629 433/433/637 426/426/630 +f 431/431/635 430/430/634 435/435/639 +f 439/439/643 441/441/645 436/436/640 +f 440/440/644 442/442/646 439/439/643 +f 443/443/647 444/444/648 440/440/644 +f 436/436/640 441/441/645 437/437/641 +f 435/435/639 430/430/634 434/434/638 +f 431/431/635 437/437/641 432/432/636 +f 440/440/644 444/444/648 442/442/646 +f 429/429/633 445/445/649 443/443/647 +f 429/429/633 428/428/632 445/445/649 +f 443/443/647 445/445/649 444/444/648 +f 444/444/650 446/446/651 442/442/652 +f 442/442/652 447/447/653 439/439/654 +f 441/441/655 448/448/656 437/437/657 +f 437/437/657 449/449/658 432/432/659 +f 432/432/659 450/450/660 430/430/661 +f 430/430/661 451/451/662 434/434/663 +f 434/434/663 452/452/664 425/425/665 +f 439/439/654 453/453/666 441/441/655 +f 437/437/657 448/448/656 454/454/667 +f 425/425/665 455/455/668 433/433/669 +f 433/433/669 456/456/670 428/428/671 +f 428/428/671 457/457/672 445/445/673 +f 445/445/673 458/458/674 444/444/650 +f 444/444/650 458/458/674 446/446/651 +f 442/442/652 446/446/651 459/459/675 +f 442/442/652 459/459/675 447/447/653 +f 439/439/654 447/447/653 453/453/666 +f 453/453/666 460/460/676 441/441/655 +f 441/441/655 460/460/676 448/448/656 +f 454/454/667 449/449/658 437/437/657 +f 450/450/660 461/461/677 430/430/661 +f 451/451/662 462/462/678 434/434/663 +f 434/434/663 462/462/678 452/452/664 +f 425/425/665 452/452/664 455/455/668 +f 428/428/671 456/456/670 457/457/672 +f 445/445/673 457/457/672 463/463/679 +f 445/445/673 463/463/679 458/458/674 +f 449/449/658 464/464/680 432/432/659 +f 432/432/659 464/464/680 465/465/681 +f 432/432/659 465/465/681 450/450/660 +f 450/450/660 465/465/681 461/461/677 +f 430/430/661 461/461/677 451/451/662 +f 455/455/668 456/456/670 433/433/669 +f 447/447/653 466/466/682 453/453/666 +f 454/454/667 467/467/683 449/449/658 +f 462/462/678 468/468/684 452/452/664 +f 447/447/653 459/459/675 469/469/685 +f 447/447/653 469/469/685 466/466/682 +f 448/448/656 460/460/676 454/454/667 +f 461/461/677 470/470/686 451/451/662 +f 453/453/666 466/466/682 460/460/676 +f 451/451/662 470/470/686 462/462/678 +f 455/455/668 411/411/687 456/456/670 +f 457/457/672 420/420/688 463/463/679 +f 458/458/674 471/471/689 446/446/651 +f 446/446/651 471/471/689 459/459/675 +f 449/449/658 467/467/683 464/464/680 +f 456/456/670 411/411/687 410/410/690 +f 456/456/670 410/410/690 457/457/672 +f 460/460/676 400/400/691 454/454/667 +f 454/454/667 408/408/692 467/467/683 +f 464/464/680 405/405/693 465/465/681 +f 465/465/681 403/403/694 461/461/677 +f 461/461/677 403/403/694 470/470/686 +f 470/470/686 403/403/694 418/418/695 +f 468/468/684 416/416/696 452/452/664 +f 452/452/664 416/416/696 455/455/668 +f 455/455/668 416/416/696 411/411/687 +f 463/463/679 424/424/697 458/458/674 +f 458/458/674 424/424/697 471/471/689 +f 471/471/689 423/423/698 459/459/675 +f 459/459/675 423/423/698 469/469/685 +f 469/469/685 423/423/698 413/413/699 +f 469/469/685 413/413/699 466/466/682 +f 466/466/682 400/400/691 460/460/676 +f 400/400/691 408/408/692 454/454/667 +f 408/408/692 405/405/693 467/467/683 +f 467/467/683 405/405/693 464/464/680 +f 465/465/681 405/405/693 403/403/694 +f 470/470/686 418/418/695 462/462/678 +f 462/462/678 417/417/700 468/468/684 +f 468/468/684 417/417/700 416/416/696 +f 471/471/689 424/424/697 423/423/698 +f 466/466/682 413/413/699 400/400/691 +f 418/418/695 417/417/700 462/462/678 +f 457/457/672 410/410/690 420/420/688 +f 463/463/679 420/420/688 424/424/697 +f 472/472/701 431/431/702 435/435/703 +f 473/473/704 435/435/705 427/427/706 +f 473/473/704 427/427/706 426/426/707 +f 474/474/708 426/426/709 429/429/710 +f 474/474/708 429/429/710 443/443/711 +f 475/475/712 443/443/713 440/440/714 +f 476/476/715 440/440/716 438/438/717 +f 476/476/715 438/438/717 436/436/718 +f 477/477/719 436/436/720 431/431/721 +f 478/478/266 479/479/266 480/480/266 +f 480/480/266 479/479/266 481/481/266 +f 480/480/266 481/481/266 482/482/266 +f 482/482/266 481/481/266 483/483/266 +f 472/472/701 478/478/722 480/480/723 +f 431/431/702 472/472/701 480/480/723 +f 478/478/722 472/472/701 435/435/703 +f 478/478/724 473/473/725 479/479/726 +f 478/478/724 435/435/727 473/473/725 +f 479/479/726 473/473/725 426/426/728 +f 479/479/729 474/474/730 481/481/731 +f 426/426/732 474/474/730 479/479/729 +f 481/481/731 474/474/730 443/443/733 +f 481/481/734 475/475/712 483/483/735 +f 443/443/713 475/475/712 481/481/734 +f 483/483/735 475/475/712 440/440/714 +f 483/483/736 476/476/737 482/482/738 +f 483/483/736 440/440/739 476/476/737 +f 476/476/737 436/436/740 482/482/738 +f 482/482/741 477/477/719 480/480/742 +f 482/482/741 436/436/720 477/477/719 +f 480/480/742 477/477/719 431/431/721 +f 484/484/743 485/485/744 486/486/745 +f 486/486/745 485/485/744 487/487/746 +f 486/486/745 487/487/746 488/488/747 +f 488/488/747 487/487/746 489/489/748 +f 488/488/747 489/489/748 490/490/749 +f 490/490/749 489/489/748 491/491/750 +f 490/490/749 491/491/750 492/492/751 +f 492/492/751 491/491/750 493/493/752 +f 492/492/751 493/493/752 494/494/753 +f 494/494/753 493/493/752 495/495/754 +f 494/494/753 495/495/754 496/496/755 +f 496/496/755 495/495/754 497/497/756 +f 496/496/755 497/497/756 498/498/757 +f 498/498/757 497/497/756 499/499/758 +f 498/498/757 499/499/758 500/500/759 +f 500/500/759 499/499/758 501/501/760 +f 500/500/759 501/501/760 502/502/761 +f 502/502/761 501/501/760 503/503/762 +f 502/502/761 503/503/762 504/504/763 +f 504/504/763 503/503/762 505/505/764 +f 504/504/763 505/505/764 506/506/765 +f 506/506/765 505/505/764 507/507/766 +f 506/506/765 507/507/766 508/508/767 +f 508/508/768 507/507/768 509/509/768 +f 508/508/769 509/509/769 510/510/769 +f 510/510/770 509/509/770 511/511/770 +f 510/510/771 511/511/771 484/484/771 +f 484/484/743 511/511/772 485/485/744 +f 512/512/266 505/505/266 513/513/266 +f 514/514/266 509/509/266 507/507/266 +f 515/515/266 509/509/266 514/514/266 +f 513/513/266 505/505/266 503/503/266 +f 512/512/266 507/507/266 505/505/266 +f 514/514/266 507/507/266 512/512/266 +f 516/516/266 497/497/266 517/517/266 +f 501/501/266 499/499/266 518/518/266 +f 518/518/266 499/499/266 516/516/266 +f 513/513/266 503/503/266 501/501/266 +f 513/513/266 501/501/266 518/518/266 +f 519/519/266 493/493/266 520/520/266 +f 516/516/266 499/499/266 497/497/266 +f 521/521/266 485/485/266 522/522/266 +f 521/521/266 487/487/266 485/485/266 +f 523/523/266 489/489/266 521/521/266 +f 519/519/266 495/495/266 493/493/266 +f 517/517/266 497/497/266 495/495/266 +f 522/522/266 511/511/266 515/515/266 +f 515/515/266 511/511/266 509/509/266 +f 489/489/266 487/487/266 521/521/266 +f 520/520/266 491/491/266 523/523/266 +f 523/523/266 491/491/266 489/489/266 +f 520/520/266 493/493/266 491/491/266 +f 517/517/266 495/495/266 519/519/266 +f 485/485/266 511/511/266 522/522/266 +f 522/522/773 524/524/774 521/521/775 +f 521/521/775 524/524/774 525/525/776 +f 521/521/775 525/525/776 523/523/777 +f 523/523/777 525/525/776 520/520/778 +f 520/520/778 525/525/776 526/526/779 +f 520/520/778 526/526/779 519/519/780 +f 519/519/780 526/526/779 527/527/781 +f 519/519/780 527/527/781 517/517/782 +f 517/517/782 527/527/781 528/528/783 +f 517/517/782 528/528/783 516/516/784 +f 516/516/784 528/528/783 529/529/785 +f 516/516/784 529/529/785 518/518/786 +f 518/518/787 529/529/788 513/513/789 +f 513/513/789 529/529/788 530/530/790 +f 513/513/791 530/530/792 531/531/793 +f 513/513/791 531/531/793 512/512/794 +f 512/512/794 531/531/793 532/532/795 +f 512/512/794 532/532/795 514/514/796 +f 514/514/796 532/532/795 515/515/797 +f 515/515/797 532/532/795 533/533/798 +f 515/515/797 533/533/798 534/534/799 +f 515/515/797 534/534/799 522/522/773 +f 522/522/773 534/534/799 524/524/774 +f 532/532/800 535/535/801 533/533/802 +f 533/533/802 535/535/801 536/536/803 +f 533/533/802 536/536/803 534/534/147 +f 531/531/804 537/537/805 532/532/800 +f 532/532/800 537/537/805 535/535/801 +f 534/534/147 536/536/803 538/538/806 +f 534/534/147 538/538/806 524/524/807 +f 524/524/807 538/538/806 539/539/808 +f 529/529/809 540/540/810 541/541/811 +f 529/529/809 541/541/811 530/530/812 +f 530/530/812 541/541/811 537/537/805 +f 530/530/812 537/537/805 531/531/804 +f 524/524/807 539/539/808 525/525/813 +f 525/525/813 539/539/808 542/542/814 +f 527/527/815 543/543/147 528/528/816 +f 528/528/816 543/543/147 540/540/810 +f 528/528/816 540/540/810 529/529/809 +f 526/526/817 544/544/818 527/527/815 +f 527/527/815 544/544/818 543/543/147 +f 525/525/813 542/542/814 526/526/817 +f 526/526/817 542/542/814 544/544/818 +f 545/545/819 546/546/820 547/547/821 +f 546/546/820 545/545/819 548/548/822 +f 545/545/819 549/549/823 548/548/822 +f 549/549/823 545/545/819 550/550/824 +f 550/550/824 551/551/825 549/549/823 +f 551/551/825 550/550/824 552/552/826 +f 552/552/826 553/553/827 551/551/825 +f 552/552/826 554/554/828 553/553/827 +f 554/554/828 552/552/826 555/555/829 +f 556/556/830 555/555/829 552/552/826 +f 555/555/829 556/556/830 557/557/831 +f 557/557/831 556/556/830 558/558/832 +f 558/558/832 556/556/830 559/559/833 +f 559/559/833 560/560/834 558/558/832 +f 559/559/833 561/561/835 560/560/834 +f 562/562/836 561/561/835 559/559/833 +f 563/563/837 561/561/835 562/562/836 +f 563/563/837 562/562/836 564/564/838 +f 564/564/838 562/562/836 565/565/839 +f 565/565/839 566/566/840 564/564/838 +f 566/566/840 565/565/839 567/567/841 +f 566/566/840 567/567/841 568/568/842 +f 567/567/841 569/569/843 568/568/842 +f 569/569/843 567/567/841 570/570/844 +f 570/570/844 571/571/845 569/569/843 +f 572/572/846 573/573/847 570/570/844 +f 570/570/844 573/573/847 571/571/845 +f 573/573/847 572/572/846 574/574/848 +f 574/574/848 572/572/846 575/575/849 +f 574/574/848 575/575/849 576/576/850 +f 576/576/850 575/575/849 577/577/851 +f 577/577/851 575/575/849 547/547/821 +f 577/577/851 547/547/821 578/578/852 +f 547/547/821 546/546/820 578/578/852 +f 510/510/853 579/579/854 580/580/855 +f 510/510/853 580/580/855 508/508/856 +f 510/510/853 581/581/857 579/579/854 +f 484/484/858 582/582/859 581/581/857 +f 484/484/858 581/581/857 510/510/853 +f 508/508/856 580/580/855 583/583/860 +f 504/504/861 584/584/862 585/585/863 +f 504/504/861 585/585/863 502/502/864 +f 506/506/865 584/584/862 504/504/861 +f 508/508/856 583/583/860 506/506/865 +f 506/506/865 583/583/860 584/584/862 +f 502/502/864 585/585/863 586/586/866 +f 502/502/864 586/586/866 500/500/867 +f 500/500/867 586/586/866 587/587/868 +f 486/486/869 588/588/870 582/582/859 +f 486/486/869 582/582/859 484/484/858 +f 496/496/871 589/589/872 494/494/873 +f 492/492/874 590/590/875 490/490/876 +f 490/490/876 590/590/875 591/591/877 +f 500/500/867 587/587/868 498/498/878 +f 498/498/878 587/587/868 592/592/879 +f 496/496/871 593/593/880 589/589/872 +f 591/591/877 594/594/881 490/490/876 +f 490/490/876 594/594/881 488/488/882 +f 498/498/878 592/592/879 496/496/871 +f 496/496/871 592/592/879 593/593/880 +f 494/494/873 589/589/872 492/492/874 +f 492/492/874 589/589/872 590/590/875 +f 488/488/882 594/594/881 588/588/870 +f 488/488/882 588/588/870 486/486/869 +f 554/554/883 583/583/884 580/580/885 +f 555/555/886 583/583/884 554/554/883 +f 554/554/883 580/580/885 553/553/887 +f 571/571/888 589/589/889 569/569/890 +f 590/590/891 589/589/889 571/571/888 +f 563/563/892 564/564/893 587/587/894 +f 586/586/895 585/585/896 561/561/897 +f 585/585/896 584/584/898 558/558/899 +f 558/558/899 584/584/898 557/557/900 +f 551/551/901 581/581/902 549/549/903 +f 581/581/902 582/582/904 548/548/905 +f 589/589/906 593/593/907 568/568/842 +f 568/568/842 593/593/907 566/566/908 +f 593/593/907 592/592/909 566/566/908 +f 561/561/897 563/563/892 587/587/894 +f 586/586/895 561/561/897 587/587/894 +f 560/560/910 561/561/897 585/585/896 +f 558/558/899 560/560/910 585/585/896 +f 584/584/898 583/583/884 557/557/900 +f 557/557/900 583/583/884 555/555/886 +f 553/553/887 580/580/885 551/551/901 +f 551/551/901 580/580/885 579/579/911 +f 579/579/911 581/581/902 551/551/901 +f 549/549/903 581/581/902 548/548/905 +f 546/546/912 548/548/905 582/582/904 +f 582/582/904 588/588/913 546/546/912 +f 546/546/912 588/588/913 578/578/914 +f 577/577/915 578/578/914 588/588/913 +f 588/588/913 594/594/916 577/577/915 +f 577/577/915 594/594/916 576/576/917 +f 576/576/917 591/591/918 574/574/919 +f 591/591/918 576/576/917 594/594/916 +f 573/573/920 574/574/919 591/591/918 +f 573/573/920 591/591/918 590/590/891 +f 573/573/920 590/590/891 571/571/888 +f 569/569/843 589/589/906 568/568/842 +f 564/564/893 566/566/908 587/587/894 +f 587/587/894 566/566/908 592/592/909 +f 562/562/836 540/540/921 565/565/839 +f 565/565/839 540/540/921 567/567/841 +f 567/567/841 540/540/921 543/543/922 +f 567/567/841 543/543/922 544/544/923 +f 567/567/841 544/544/924 570/570/844 +f 570/570/925 544/544/926 542/542/927 +f 570/570/925 542/542/927 572/572/928 +f 572/572/846 542/542/929 575/575/849 +f 575/575/930 542/542/930 539/539/930 +f 575/575/849 539/539/931 547/547/821 +f 547/547/821 539/539/932 538/538/933 +f 547/547/821 538/538/933 545/545/819 +f 545/545/819 538/538/933 536/536/934 +f 545/545/819 536/536/934 550/550/824 +f 550/550/824 536/536/934 552/552/826 +f 552/552/826 536/536/934 535/535/935 +f 552/552/826 535/535/936 556/556/830 +f 556/556/830 535/535/936 537/537/937 +f 556/556/830 537/537/938 559/559/833 +f 559/559/939 537/537/939 541/541/939 +f 559/559/833 541/541/940 562/562/836 +f 562/562/836 541/541/941 540/540/921 +f 595/595/942 596/596/943 597/597/576 +f 597/597/576 598/598/944 595/595/942 +f 597/597/576 599/599/945 598/598/944 +f 597/597/576 600/600/946 599/599/945 +f 601/601/947 602/602/948 603/603/949 +f 603/603/949 602/602/948 604/604/950 +f 604/604/950 602/602/948 605/605/951 +f 604/604/950 605/605/951 606/606/952 +f 605/605/951 607/607/953 606/606/952 +f 606/606/952 607/607/953 608/608/954 +f 608/608/954 607/607/953 609/609/955 +f 608/608/954 609/609/955 610/610/956 +f 610/610/956 609/609/955 611/611/957 +f 610/610/956 611/611/957 612/612/958 +f 611/611/957 613/613/959 612/612/958 +f 612/612/958 613/613/959 614/614/960 +f 614/614/960 613/613/959 615/615/961 +f 615/615/962 616/616/963 614/614/964 +f 614/614/964 616/616/963 617/617/965 +f 617/617/966 616/616/967 618/618/968 +f 616/616/967 619/619/969 618/618/968 +f 618/618/968 619/619/969 620/620/970 +f 620/620/970 619/619/969 621/621/971 +f 620/620/970 621/621/971 603/603/972 +f 621/621/971 601/601/973 603/603/972 +f 598/598/974 611/611/975 595/595/976 +f 595/595/976 611/611/975 609/609/977 +f 595/595/976 609/609/977 607/607/978 +f 595/595/976 607/607/978 596/596/979 +f 607/607/978 605/605/980 596/596/979 +f 596/596/979 605/605/980 602/602/981 +f 596/596/979 602/602/981 597/597/982 +f 602/602/981 601/601/983 597/597/982 +f 601/601/983 621/621/984 597/597/982 +f 597/597/982 621/621/984 600/600/985 +f 600/600/985 621/621/984 619/619/986 +f 619/619/986 616/616/987 600/600/985 +f 600/600/985 616/616/987 599/599/988 +f 616/616/987 615/615/989 599/599/988 +f 599/599/988 615/615/989 613/613/990 +f 599/599/988 613/613/990 598/598/974 +f 613/613/990 611/611/975 598/598/974 +f 603/603/266 622/622/266 620/620/266 +f 620/620/266 622/622/266 623/623/266 +f 603/603/266 624/624/266 622/622/266 +f 604/604/266 624/624/266 603/603/266 +f 604/604/266 625/625/266 626/626/266 +f 606/606/266 625/625/266 604/604/266 +f 612/612/266 627/627/266 610/610/266 +f 618/618/266 623/623/266 628/628/266 +f 620/620/266 623/623/266 618/618/266 +f 604/604/266 626/626/266 624/624/266 +f 608/608/266 629/629/266 630/630/266 +f 612/612/266 631/631/266 627/627/266 +f 610/610/266 629/629/266 608/608/266 +f 608/608/266 630/630/266 606/606/266 +f 606/606/266 630/630/266 625/625/266 +f 610/610/266 632/632/266 629/629/266 +f 610/610/266 627/627/266 632/632/266 +f 614/614/266 631/631/266 612/612/266 +f 614/614/266 633/633/266 631/631/266 +f 617/617/266 634/634/266 614/614/266 +f 614/614/266 634/634/266 633/633/266 +f 618/618/266 628/628/266 617/617/266 +f 617/617/266 628/628/266 634/634/266 +f 635/635/991 636/636/992 637/637/993 +f 638/638/994 639/639/995 640/640/996 +f 641/641/997 642/642/998 639/639/995 +f 641/641/997 639/639/995 638/638/994 +f 638/638/994 640/640/996 643/643/999 +f 635/635/991 644/644/1000 645/645/1001 +f 635/635/991 645/645/1001 636/636/992 +f 646/646/1002 647/647/1003 648/648/1004 +f 643/643/999 640/640/996 644/644/1000 +f 643/643/999 644/644/1000 635/635/991 +f 637/637/993 636/636/992 649/649/1005 +f 649/649/1005 636/636/992 650/650/1006 +f 651/651/1007 652/652/1008 653/653/1009 +f 653/653/1009 652/652/1008 654/654/1010 +f 655/655/1011 656/656/1012 646/646/1002 +f 646/646/1002 656/656/1012 647/647/1003 +f 657/657/1013 658/658/1014 655/655/1011 +f 658/658/1014 656/656/1012 655/655/1011 +f 659/659/1015 660/660/1016 641/641/997 +f 641/641/997 660/660/1016 642/642/998 +f 649/649/1005 650/650/1006 661/661/1017 +f 653/653/1009 662/662/1018 657/657/1013 +f 657/657/1013 662/662/1018 658/658/1014 +f 649/649/1005 661/661/1017 651/651/1007 +f 651/651/1007 661/661/1017 652/652/1008 +f 648/648/1004 647/647/1003 660/660/1016 +f 648/648/1004 660/660/1016 659/659/1015 +f 654/654/1010 662/662/1018 653/653/1009 +f 625/625/1019 653/653/1020 657/657/1021 +f 625/625/1019 657/657/1021 626/626/1022 +f 626/626/1022 657/657/1021 655/655/1023 +f 626/626/1022 655/655/1023 624/624/1024 +f 624/624/1024 655/655/1023 646/646/1025 +f 624/624/1024 646/646/1025 622/622/1026 +f 622/622/1027 646/646/1028 648/648/1029 +f 622/622/1027 648/648/1029 659/659/1030 +f 622/622/1027 659/659/1030 623/623/1031 +f 623/623/1032 659/659/1032 641/641/1032 +f 623/623/1033 641/641/1033 628/628/1033 +f 628/628/1034 641/641/1035 638/638/1036 +f 628/628/1034 638/638/1036 634/634/1037 +f 634/634/1037 638/638/1036 643/643/1038 +f 634/634/1037 643/643/1038 633/633/1039 +f 633/633/1040 643/643/1041 635/635/1042 +f 633/633/1040 635/635/1042 631/631/1043 +f 631/631/1043 635/635/1042 627/627/1044 +f 627/627/1044 635/635/1042 637/637/1045 +f 627/627/1044 637/637/1045 649/649/1046 +f 627/627/1044 649/649/1046 632/632/1047 +f 632/632/1047 649/649/1046 629/629/1048 +f 629/629/1048 649/649/1046 651/651/1049 +f 629/629/1050 651/651/1051 630/630/1052 +f 630/630/1052 651/651/1051 653/653/1053 +f 630/630/1052 653/653/1053 625/625/1054 +f 663/663/1055 664/664/1056 665/665/1057 +f 664/664/1056 666/666/1058 667/667/1059 +f 668/668/1060 669/669/1061 670/670/1062 +f 665/665/1057 671/671/1063 663/663/1055 +f 672/672/1064 671/671/1063 665/665/1057 +f 670/670/1062 673/673/1065 668/668/1060 +f 674/674/1066 673/673/1065 675/675/1067 +f 663/663/1055 666/666/1058 664/664/1056 +f 672/672/1064 676/676/1068 677/677/1069 +f 678/678/1070 677/677/1069 676/676/1068 +f 669/669/1061 679/679/1071 678/678/1070 +f 668/668/1060 679/679/1071 669/669/1061 +f 673/673/1065 674/674/1066 668/668/1060 +f 680/680/1072 674/674/1066 675/675/1067 +f 681/681/1073 682/682/1074 680/680/1072 +f 672/672/1064 677/677/1069 671/671/1063 +f 680/680/1072 682/682/1074 674/674/1066 +f 678/678/1070 679/679/1071 677/677/1069 +f 681/681/1073 683/683/1075 682/682/1074 +f 667/667/1059 683/683/1075 681/681/1073 +f 667/667/1059 666/666/1058 683/683/1075 +f 671/671/1076 684/684/1077 663/663/1078 +f 663/663/1078 685/685/1079 666/666/1080 +f 666/666/1080 686/686/1081 683/683/1082 +f 674/674/1066 687/687/1083 668/668/1060 +f 668/668/1060 688/688/1084 679/679/1085 +f 679/679/1085 689/689/1086 677/677/1087 +f 677/677/1087 690/690/1088 691/691/1089 +f 677/677/1087 691/691/1089 671/671/1076 +f 668/668/1060 692/692/1090 688/688/1084 +f 679/679/1085 688/688/1084 689/689/1086 +f 677/677/1087 689/689/1086 693/693/1091 +f 677/677/1087 693/693/1091 690/690/1088 +f 666/666/1080 685/685/1079 694/694/1092 +f 666/666/1080 694/694/1092 686/686/1081 +f 683/683/1082 695/695/1093 682/682/1094 +f 682/682/1094 696/696/1095 674/674/1066 +f 674/674/1066 697/697/1096 687/687/1083 +f 668/668/1060 687/687/1083 692/692/1090 +f 671/671/1076 691/691/1089 698/698/1097 +f 671/671/1076 698/698/1097 684/684/1077 +f 684/684/1077 685/685/1079 663/663/1078 +f 682/682/1094 695/695/1093 696/696/1095 +f 696/696/1095 699/699/1098 674/674/1066 +f 674/674/1066 699/699/1098 697/697/1096 +f 688/688/1084 700/700/1099 689/689/1086 +f 683/683/1082 686/686/1081 695/695/1093 +f 697/697/1096 701/701/1100 687/687/1083 +f 692/692/1090 687/687/1083 702/702/1101 +f 692/692/1090 702/702/1101 703/703/1102 +f 692/692/1090 703/703/1102 688/688/1084 +f 690/690/1088 693/693/1091 704/704/1103 +f 690/690/1088 704/704/1103 691/691/1089 +f 698/698/1097 705/705/1104 684/684/1077 +f 684/684/1077 705/705/1104 685/685/1079 +f 686/686/1081 706/706/1105 695/695/1093 +f 697/697/1096 699/699/1098 701/701/1100 +f 687/687/1083 701/701/1100 702/702/1101 +f 685/685/1079 707/707/1106 694/694/1092 +f 694/694/1092 708/708/1107 686/686/1081 +f 686/686/1081 708/708/1107 706/706/1105 +f 706/706/1105 709/709/1108 695/695/1093 +f 695/695/1093 709/709/1108 696/696/1095 +f 689/689/1086 700/700/1099 644/644/1109 +f 691/691/1089 704/704/1103 698/698/1097 +f 696/696/1095 654/654/1110 699/699/1098 +f 689/689/1086 644/644/1109 693/693/1091 +f 685/685/1079 705/705/1104 707/707/1106 +f 701/701/1100 661/661/1111 702/702/1101 +f 703/703/1102 645/645/1112 688/688/1084 +f 688/688/1084 645/645/1112 700/700/1099 +f 644/644/1109 640/640/1113 693/693/1091 +f 693/693/1091 640/640/1113 704/704/1103 +f 704/704/1103 640/640/1113 639/639/1114 +f 704/704/1103 642/642/1115 698/698/1097 +f 698/698/1097 642/642/1115 705/705/1104 +f 707/707/1106 647/647/1116 694/694/1092 +f 694/694/1092 647/647/1116 708/708/1107 +f 708/708/1107 656/656/1117 706/706/1105 +f 706/706/1105 656/656/1117 709/709/1108 +f 709/709/1108 658/658/1118 662/662/1119 +f 709/709/1108 662/662/1119 696/696/1095 +f 696/696/1095 662/662/1119 654/654/1110 +f 654/654/1110 652/652/1120 699/699/1098 +f 699/699/1098 652/652/1120 701/701/1100 +f 701/701/1100 652/652/1120 661/661/1111 +f 702/702/1101 661/661/1111 650/650/1121 +f 703/703/1102 636/636/1122 645/645/1112 +f 645/645/1112 644/644/1109 700/700/1099 +f 705/705/1104 660/660/1123 707/707/1106 +f 702/702/1101 650/650/1121 636/636/1122 +f 702/702/1101 636/636/1122 703/703/1102 +f 704/704/1103 639/639/1114 642/642/1115 +f 705/705/1104 642/642/1115 660/660/1123 +f 707/707/1106 660/660/1123 647/647/1116 +f 647/647/1116 656/656/1117 708/708/1107 +f 656/656/1117 658/658/1118 709/709/1108 +f 710/710/1124 678/678/1125 676/676/1126 +f 710/710/1124 676/676/1126 672/672/1127 +f 672/672/1128 665/665/1129 711/711/1130 +f 711/711/1130 665/665/1129 664/664/1131 +f 664/664/1132 667/667/1133 712/712/1134 +f 712/712/1134 667/667/1133 681/681/1135 +f 713/713/1136 681/681/1137 680/680/1138 +f 713/713/1136 680/680/1138 675/675/1139 +f 714/714/1140 675/675/1141 673/673/1142 +f 714/714/1140 673/673/1142 670/670/1143 +f 670/670/1144 669/669/1145 715/715/1146 +f 715/715/1146 669/669/1145 678/678/1147 +f 716/716/147 717/717/147 718/718/147 +f 718/718/147 717/717/147 719/719/147 +f 718/718/147 719/719/147 720/720/147 +f 720/720/147 719/719/147 721/721/147 +f 710/710/1148 716/716/1149 718/718/1150 +f 678/678/1151 710/710/1148 718/718/1150 +f 710/710/1148 672/672/1152 716/716/1149 +f 716/716/1153 711/711/1154 717/717/1155 +f 672/672/1156 711/711/1154 716/716/1153 +f 717/717/1155 711/711/1154 664/664/1157 +f 717/717/1158 712/712/1159 719/719/1160 +f 664/664/1161 712/712/1159 717/717/1158 +f 719/719/1160 712/712/1159 681/681/1162 +f 719/719/1163 713/713/1164 721/721/1165 +f 681/681/1166 713/713/1164 719/719/1163 +f 713/713/1164 675/675/1167 721/721/1165 +f 721/721/1168 714/714/1169 720/720/1170 +f 675/675/1171 714/714/1169 721/721/1168 +f 714/714/1169 670/670/1172 720/720/1170 +f 720/720/1173 715/715/1174 718/718/1175 +f 720/720/1173 670/670/1176 715/715/1174 +f 715/715/1174 678/678/1177 718/718/1175 +f 722/722/1178 723/723/1179 724/724/1180 +f 725/725/1181 726/726/1182 722/722/1178 +f 725/725/1181 722/722/1178 724/724/1180 +f 727/727/1183 728/728/1184 729/729/1185 +f 730/730/1186 731/731/1187 732/732/1188 +f 730/730/1186 732/732/1188 733/733/1189 +f 731/731/1187 730/730/1186 734/734/1190 +f 724/724/1180 723/723/1179 732/732/1188 +f 732/732/1188 723/723/1179 733/733/1189 +f 725/725/1181 729/729/1185 726/726/1182 +f 727/727/1183 729/729/1185 725/725/1181 +f 735/735/1191 736/736/1192 731/731/1187 +f 731/731/1187 734/734/1190 735/735/1191 +f 736/736/1192 735/735/1191 737/737/1193 +f 736/736/1192 737/737/1193 727/727/1183 +f 727/727/1183 737/737/1193 728/728/1184 +f 738/738/1194 739/739/1195 740/740/1196 +f 738/738/1194 741/741/1197 739/739/1195 +f 742/742/1198 741/741/1197 738/738/1194 +f 738/738/1194 743/743/1199 742/742/1198 +f 738/738/1194 744/744/1200 743/743/1199 +f 738/738/1194 745/745/1201 744/744/1200 +f 738/738/1194 746/746/1202 747/747/1203 +f 738/738/1194 748/748/1204 746/746/1202 +f 749/749/1205 748/748/1204 738/738/1194 +f 740/740/1196 749/749/1205 738/738/1194 +f 750/750/1206 740/740/1207 751/751/1208 +f 751/751/1208 740/740/1207 739/739/1209 +f 751/751/1208 739/739/1209 752/752/1210 +f 752/752/1210 739/739/1209 741/741/1211 +f 752/752/1210 741/741/1211 742/742/1212 +f 752/752/1210 742/742/1212 753/753/1213 +f 753/753/1213 742/742/1212 743/743/1214 +f 753/753/1213 743/743/1214 754/754/1215 +f 754/754/1215 743/743/1214 744/744/1216 +f 754/754/1215 744/744/1216 755/755/1217 +f 755/755/1217 744/744/1216 745/745/1218 +f 755/755/1217 745/745/1218 756/756/1219 +f 755/755/1217 756/756/1219 757/757/1220 +f 757/757/1220 756/756/1219 738/738/1221 +f 757/757/1220 738/738/1221 758/758/1222 +f 758/758/1222 738/738/1221 747/747/1223 +f 758/758/1222 747/747/1223 746/746/1224 +f 758/758/1222 746/746/1224 759/759/1225 +f 759/759/1225 746/746/1224 748/748/1226 +f 759/759/1225 748/748/1226 749/749/1227 +f 759/759/1225 749/749/1227 750/750/1206 +f 750/750/1206 749/749/1227 740/740/1207 +f 751/751/1 760/760/1 761/761/1 +f 751/751/1 761/761/1 750/750/1 +f 758/758/1 762/762/1 757/757/1 +f 757/757/1 762/762/1 763/763/1 +f 750/750/1 761/761/1 764/764/1 +f 757/757/1 763/763/1 755/755/1 +f 755/755/1 763/763/1 765/765/1 +f 750/750/1 764/764/1 759/759/1 +f 759/759/1 764/764/1 766/766/1 +f 759/759/1 766/766/1 767/767/1 +f 752/752/1 768/768/1 760/760/1 +f 752/752/1 760/760/1 751/751/1 +f 755/755/1 765/765/1 769/769/1 +f 759/759/1 770/770/1 758/758/1 +f 758/758/1 770/770/1 762/762/1 +f 752/752/1 771/771/1 768/768/1 +f 753/753/1 772/772/1 771/771/1 +f 753/753/1 771/771/1 752/752/1 +f 759/759/1 767/767/1 770/770/1 +f 754/754/1 772/772/1 753/753/1 +f 755/755/1 769/769/1 754/754/1 +f 754/754/1 773/773/1 772/772/1 +f 769/769/1 773/773/1 754/754/1 +f 761/761/1228 774/774/1229 764/764/1230 +f 764/764/1230 774/774/1229 775/775/1231 +f 775/775/1231 776/776/1232 764/764/1230 +f 764/764/1230 776/776/1232 766/766/1233 +f 776/776/1232 777/777/1234 766/766/1233 +f 766/766/1233 777/777/1234 767/767/1235 +f 777/777/1234 778/778/1236 767/767/1235 +f 778/778/1236 779/779/1237 767/767/1235 +f 767/767/1235 779/779/1237 770/770/1238 +f 770/770/1238 779/779/1237 762/762/1239 +f 779/779/1237 780/780/1240 762/762/1239 +f 762/762/1239 780/780/1240 781/781/1241 +f 781/781/1241 763/763/1242 762/762/1239 +f 781/781/1241 782/782/1243 763/763/1242 +f 763/763/1242 782/782/1243 765/765/1244 +f 765/765/1244 782/782/1243 783/783/1245 +f 765/765/1244 783/783/1245 769/769/1246 +f 769/769/1246 783/783/1245 784/784/1247 +f 769/769/1246 784/784/1247 773/773/1248 +f 773/773/1248 784/784/1247 785/785/1249 +f 773/773/1248 785/785/1249 786/786/1250 +f 773/773/1248 786/786/1250 772/772/1251 +f 786/786/1250 787/787/1252 772/772/1251 +f 772/772/1251 787/787/1252 771/771/1253 +f 771/771/1253 787/787/1252 788/788/1254 +f 771/771/1253 788/788/1254 768/768/1255 +f 789/789/1256 768/768/1255 788/788/1254 +f 768/768/1255 789/789/1256 760/760/1257 +f 760/760/1257 789/789/1256 790/790/1258 +f 760/760/1257 790/790/1258 761/761/1228 +f 761/761/1228 790/790/1258 774/774/1229 +f 791/791/1259 792/792/1260 793/793/1261 +f 737/737/1262 794/794/1263 791/791/1259 +f 791/791/1259 795/795/1264 792/792/1260 +f 792/792/1260 795/795/1264 783/783/1245 +f 791/791/1259 794/794/1263 795/795/1264 +f 783/783/1245 795/795/1264 784/784/1247 +f 735/735/1265 794/794/1263 737/737/1262 +f 796/796/1266 794/794/1263 735/735/1265 +f 796/796/1266 795/795/1264 794/794/1263 +f 784/784/1247 795/795/1264 785/785/1249 +f 797/797/1267 785/785/1249 795/795/1264 +f 797/797/1267 795/795/1264 796/796/1266 +f 796/796/1266 735/735/1265 798/798/1268 +f 797/797/1267 796/796/1266 798/798/1268 +f 785/785/1249 797/797/1267 786/786/1250 +f 799/799/1269 786/786/1250 797/797/1267 +f 799/799/1269 797/797/1267 798/798/1268 +f 734/734/1270 798/798/1268 735/735/1265 +f 787/787/1252 786/786/1250 799/799/1269 +f 800/800/1271 799/799/1269 798/798/1268 +f 800/800/1271 798/798/1268 734/734/1270 +f 787/787/1252 799/799/1269 800/800/1271 +f 730/730/1186 800/800/1271 734/734/1270 +f 787/787/1252 800/800/1271 801/801/1272 +f 802/802/1273 801/801/1272 800/800/1271 +f 802/802/1273 800/800/1271 730/730/1186 +f 787/787/1252 801/801/1272 788/788/1254 +f 802/802/1273 788/788/1254 801/801/1272 +f 803/803/1274 802/802/1273 730/730/1186 +f 733/733/1189 803/803/1274 730/730/1186 +f 804/804/1275 788/788/1254 802/802/1273 +f 802/802/1273 803/803/1274 804/804/1275 +f 788/788/1254 804/804/1275 789/789/1256 +f 805/805/1276 789/789/1256 804/804/1275 +f 805/805/1276 804/804/1275 803/803/1274 +f 803/803/1274 733/733/1189 806/806/1277 +f 803/803/1274 806/806/1277 805/805/1276 +f 789/789/1256 805/805/1276 790/790/1258 +f 807/807/1278 805/805/1276 806/806/1277 +f 805/805/1276 807/807/1278 790/790/1258 +f 723/723/1179 806/806/1277 733/733/1189 +f 790/790/1258 807/807/1278 774/774/1229 +f 806/806/1277 808/808/1279 807/807/1278 +f 808/808/1279 806/806/1277 723/723/1179 +f 809/809/1280 774/774/1229 807/807/1278 +f 809/809/1280 807/807/1278 808/808/1279 +f 723/723/1179 810/810/1281 808/808/1279 +f 808/808/1279 810/810/1281 809/809/1280 +f 774/774/1229 809/809/1280 775/775/1231 +f 723/723/1179 722/722/1282 810/810/1281 +f 810/810/1281 811/811/1283 809/809/1280 +f 809/809/1280 811/811/1283 776/776/1232 +f 809/809/1280 776/776/1232 775/775/1231 +f 810/810/1281 722/722/1282 811/811/1283 +f 811/811/1283 812/812/1284 776/776/1232 +f 777/777/1234 776/776/1232 812/812/1284 +f 813/813/1285 812/812/1284 811/811/1283 +f 813/813/1285 811/811/1283 722/722/1282 +f 812/812/1284 813/813/1285 814/814/1286 +f 777/777/1234 812/812/1284 778/778/1236 +f 722/722/1282 726/726/1287 813/813/1285 +f 812/812/1284 814/814/1286 778/778/1236 +f 779/779/1237 778/778/1236 814/814/1286 +f 814/814/1286 813/813/1285 726/726/1287 +f 726/726/1287 815/815/1288 814/814/1286 +f 814/814/1286 815/815/1288 779/779/1237 +f 816/816/1289 779/779/1237 815/815/1288 +f 817/817/1290 815/815/1288 726/726/1287 +f 817/817/1290 726/726/1287 729/729/1185 +f 816/816/1289 815/815/1288 817/817/1290 +f 779/779/1237 816/816/1289 780/780/1240 +f 818/818/1291 780/780/1240 816/816/1289 +f 818/818/1291 816/816/1289 817/817/1290 +f 817/817/1290 729/729/1185 818/818/1291 +f 819/819/1292 818/818/1291 729/729/1185 +f 818/818/1291 820/820/1293 780/780/1240 +f 781/781/1241 780/780/1240 820/820/1293 +f 820/820/1293 818/818/1291 819/819/1292 +f 819/819/1292 821/821/1294 820/820/1293 +f 821/821/1294 781/781/1241 820/820/1293 +f 728/728/1184 819/819/1292 729/729/1185 +f 819/819/1292 728/728/1184 821/821/1294 +f 781/781/1241 821/821/1294 782/782/1243 +f 821/821/1294 793/793/1261 782/782/1243 +f 783/783/1245 782/782/1243 793/793/1261 +f 791/791/1259 821/821/1294 728/728/1184 +f 793/793/1261 821/821/1294 791/791/1259 +f 728/728/1184 737/737/1262 791/791/1259 +f 793/793/1261 792/792/1260 783/783/1245 +f 724/724/128 732/732/128 822/822/128 +f 822/822/128 732/732/128 823/823/128 +f 725/725/129 724/724/129 824/824/129 +f 824/824/129 724/724/129 822/822/129 +f 727/727/130 725/725/130 825/825/130 +f 825/825/130 725/725/130 824/824/130 +f 736/736/124 727/727/124 826/826/124 +f 826/826/124 727/727/124 825/825/124 +f 731/731/125 736/736/125 827/827/125 +f 827/827/125 736/736/125 826/826/126 +f 732/732/127 731/731/127 823/823/127 +f 823/823/127 731/731/127 827/827/127 +f 827/827/2 826/826/2 823/823/2 +f 823/823/2 826/826/2 825/825/2 +f 823/823/2 825/825/2 822/822/2 +f 822/822/2 825/825/2 824/824/2 +f 756/756/1295 745/745/1201 738/738/1194 +f 828/828/1296 829/829/1297 830/830/1298 +f 831/831/1299 832/832/1300 833/833/1301 +f 830/830/1298 829/829/1297 832/832/1300 +f 834/834/1302 835/835/1303 828/828/1296 +f 834/834/1302 828/828/1296 830/830/1298 +f 834/834/1302 836/836/1304 835/835/1303 +f 837/837/1305 838/838/1306 839/839/1307 +f 833/833/1301 839/839/1307 831/831/1299 +f 830/830/1298 832/832/1300 831/831/1299 +f 833/833/1301 837/837/1305 839/839/1307 +f 840/840/1308 841/841/1309 834/834/1302 +f 834/834/1302 841/841/1309 836/836/1304 +f 842/842/1310 843/843/1311 844/844/1312 +f 840/840/1308 844/844/1312 841/841/1309 +f 838/838/1306 842/842/1310 839/839/1307 +f 842/842/1310 838/838/1306 843/843/1311 +f 842/842/1310 844/844/1312 840/840/1308 +f 845/845/1313 846/846/1314 847/847/1315 +f 845/845/1313 848/848/1316 846/846/1314 +f 845/845/1313 849/849/1317 848/848/1316 +f 850/850/1318 849/849/1317 845/845/1313 +f 851/851/1319 850/850/1318 845/845/1313 +f 845/845/1313 852/852/1320 851/851/1319 +f 845/845/1313 853/853/1321 852/852/1320 +f 845/845/1313 854/854/1322 853/853/1321 +f 845/845/1313 855/855/1323 854/854/1322 +f 856/856/1324 855/855/1323 845/845/1313 +f 857/857/1325 846/846/1326 858/858/1327 +f 858/858/1327 846/846/1326 848/848/1328 +f 858/858/1327 848/848/1328 859/859/1329 +f 859/859/1329 848/848/1328 849/849/1330 +f 859/859/1329 849/849/1330 860/860/1331 +f 860/860/1331 849/849/1330 850/850/1332 +f 860/860/1331 850/850/1332 861/861/1333 +f 861/861/1333 850/850/1332 851/851/1334 +f 861/861/1335 851/851/1336 852/852/1337 +f 861/861/1335 852/852/1337 862/862/1338 +f 862/862/1338 852/852/1337 853/853/1339 +f 862/862/1338 853/853/1339 854/854/1340 +f 862/862/1338 854/854/1340 863/863/1341 +f 863/863/1341 854/854/1340 855/855/1342 +f 863/863/1341 855/855/1342 864/864/1343 +f 864/864/1343 855/855/1342 856/856/1344 +f 864/864/1345 856/856/1346 845/845/1347 +f 864/864/1345 845/845/1347 857/857/1348 +f 857/857/1348 845/845/1347 847/847/1349 +f 857/857/1325 847/847/1350 846/846/1326 +f 858/858/1 865/865/1 866/866/1 +f 858/858/1 866/866/1 857/857/1 +f 863/863/1 867/867/1 862/862/1 +f 862/862/1 867/867/1 868/868/1 +f 857/857/1 869/869/1 864/864/1 +f 864/864/1 869/869/1 870/870/1 +f 857/857/1 866/866/1 869/869/1 +f 862/862/1 868/868/1 871/871/1 +f 863/863/1 872/872/1 867/867/1 +f 859/859/1 873/873/1 865/865/1 +f 859/859/1 865/865/1 858/858/1 +f 862/862/1 871/871/1 861/861/1 +f 861/861/1 871/871/1 874/874/1 +f 864/864/1 872/872/1 863/863/1 +f 859/859/1 875/875/1 873/873/1 +f 860/860/1 875/875/1 859/859/1 +f 870/870/1 876/876/1 864/864/1 +f 864/864/1 876/876/1 872/872/1 +f 860/860/1 877/877/1 875/875/1 +f 861/861/1 878/878/1 860/860/1 +f 860/860/1 878/878/1 877/877/1 +f 874/874/1 878/878/1 861/861/1 +f 879/879/1351 880/880/1352 866/866/1353 +f 866/866/1353 880/880/1352 869/869/1354 +f 880/880/1352 881/881/1355 869/869/1356 +f 881/881/1355 870/870/1357 869/869/1356 +f 870/870/1357 881/881/1355 882/882/1358 +f 882/882/1358 876/876/1359 870/870/1357 +f 882/882/1358 883/883/1360 876/876/1359 +f 883/883/1360 872/872/1361 876/876/1359 +f 883/883/1360 884/884/1362 872/872/1361 +f 884/884/1362 885/885/1363 872/872/1361 +f 872/872/1361 885/885/1363 867/867/1364 +f 885/885/1363 886/886/1365 867/867/1364 +f 867/867/1364 886/886/1365 868/868/1366 +f 886/886/1365 887/887/1367 868/868/1366 +f 868/868/1366 887/887/1367 871/871/1368 +f 871/871/1368 887/887/1367 888/888/1369 +f 871/871/1368 888/888/1369 874/874/1370 +f 874/874/1370 888/888/1369 889/889/1371 +f 889/889/1371 890/890/1372 874/874/1370 +f 874/874/1370 890/890/1372 878/878/1373 +f 890/890/1372 891/891/1374 878/878/1373 +f 878/878/1373 891/891/1374 892/892/1375 +f 878/878/1373 892/892/1375 877/877/1376 +f 892/892/1375 893/893/1377 877/877/1376 +f 893/893/1377 875/875/1378 877/877/1376 +f 893/893/1377 894/894/1379 875/875/1378 +f 894/894/1379 873/873/1380 875/875/1378 +f 894/894/1379 895/895/1381 873/873/1380 +f 873/873/1380 895/895/1381 865/865/1382 +f 895/895/1381 879/879/1351 865/865/1382 +f 865/865/1382 879/879/1351 866/866/1353 +f 896/896/1383 888/888/1369 897/897/1384 +f 896/896/1383 897/897/1384 844/844/1385 +f 843/843/1386 896/896/1383 844/844/1385 +f 896/896/1383 889/889/1371 888/888/1369 +f 898/898/1387 889/889/1371 896/896/1383 +f 898/898/1387 896/896/1383 843/843/1386 +f 890/890/1372 889/889/1371 899/899/1388 +f 899/899/1388 889/889/1371 898/898/1387 +f 898/898/1387 843/843/1386 900/900/1389 +f 898/898/1387 900/900/1389 899/899/1388 +f 838/838/1390 900/900/1389 843/843/1386 +f 899/899/1388 900/900/1389 891/891/1374 +f 899/899/1388 891/891/1374 890/890/1372 +f 901/901/1391 900/900/1389 838/838/1390 +f 900/900/1389 901/901/1391 902/902/1392 +f 900/900/1389 902/902/1392 891/891/1374 +f 892/892/1375 891/891/1374 902/902/1392 +f 901/901/1391 838/838/1390 903/903/1393 +f 893/893/1377 892/892/1375 902/902/1392 +f 903/903/1393 902/902/1392 901/901/1391 +f 837/837/1394 903/903/1393 838/838/1390 +f 902/902/1392 903/903/1393 904/904/1395 +f 904/904/1395 893/893/1377 902/902/1392 +f 905/905/1396 903/903/1393 837/837/1394 +f 906/906/1397 893/893/1377 904/904/1395 +f 906/906/1397 904/904/1395 905/905/1396 +f 905/905/1396 904/904/1395 903/903/1393 +f 893/893/1377 906/906/1397 894/894/1379 +f 833/833/1398 905/905/1396 837/837/1394 +f 894/894/1379 906/906/1397 907/907/1399 +f 907/907/1399 906/906/1397 905/905/1396 +f 833/833/1398 907/907/1399 905/905/1396 +f 895/895/1381 894/894/1379 907/907/1399 +f 833/833/1398 908/908/1400 907/907/1399 +f 907/907/1399 908/908/1400 895/895/1381 +f 833/833/1398 832/832/1401 909/909/1402 +f 833/833/1398 909/909/1402 908/908/1400 +f 908/908/1400 909/909/1402 895/895/1381 +f 879/879/1351 895/895/1381 909/909/1402 +f 909/909/1402 910/910/1403 879/879/1351 +f 909/909/1402 832/832/1401 911/911/1404 +f 909/909/1402 911/911/1404 910/910/1403 +f 829/829/1405 911/911/1404 832/832/1401 +f 910/910/1403 911/911/1404 912/912/1406 +f 910/910/1403 912/912/1406 879/879/1351 +f 879/879/1351 912/912/1406 880/880/1352 +f 913/913/1407 911/911/1404 829/829/1405 +f 914/914/1408 912/912/1406 911/911/1404 +f 829/829/1405 828/828/1409 913/913/1407 +f 911/911/1404 913/913/1407 914/914/1408 +f 912/912/1406 914/914/1408 880/880/1352 +f 880/880/1352 914/914/1408 881/881/1355 +f 915/915/1410 914/914/1408 913/913/1407 +f 915/915/1410 913/913/1407 828/828/1409 +f 915/915/1410 881/881/1355 914/914/1408 +f 882/882/1358 881/881/1355 915/915/1410 +f 916/916/1411 915/915/1410 828/828/1409 +f 828/828/1409 835/835/1412 916/916/1411 +f 915/915/1410 917/917/1413 882/882/1358 +f 915/915/1410 916/916/1411 917/917/1413 +f 882/882/1358 917/917/1413 883/883/1360 +f 918/918/1414 883/883/1360 917/917/1413 +f 918/918/1414 917/917/1413 916/916/1411 +f 835/835/1412 836/836/1415 916/916/1411 +f 884/884/1362 883/883/1360 918/918/1414 +f 919/919/1416 918/918/1414 916/916/1411 +f 919/919/1416 916/916/1411 836/836/1415 +f 919/919/1416 884/884/1362 918/918/1414 +f 919/919/1416 836/836/1415 920/920/1417 +f 884/884/1362 919/919/1416 885/885/1363 +f 920/920/1417 836/836/1415 841/841/1418 +f 919/919/1416 920/920/1417 921/921/1419 +f 919/919/1416 921/921/1419 885/885/1363 +f 920/920/1417 841/841/1418 921/921/1419 +f 885/885/1363 921/921/1419 886/886/1365 +f 922/922/1420 921/921/1419 841/841/1418 +f 921/921/1419 922/922/1420 886/886/1365 +f 886/886/1365 922/922/1420 887/887/1367 +f 841/841/1418 923/923/1421 922/922/1420 +f 887/887/1367 922/922/1420 923/923/1421 +f 844/844/1385 923/923/1421 841/841/1418 +f 897/897/1384 887/887/1367 923/923/1421 +f 923/923/1421 844/844/1385 897/897/1384 +f 897/897/1384 888/888/1369 887/887/1367 +f 830/830/128 831/831/128 924/924/128 +f 924/924/128 831/831/128 925/925/128 +f 834/834/129 830/830/129 926/926/129 +f 926/926/129 830/830/129 924/924/129 +f 840/840/130 834/834/130 927/927/130 +f 927/927/130 834/834/130 926/926/130 +f 842/842/124 840/840/124 928/928/124 +f 928/928/124 840/840/124 927/927/124 +f 839/839/125 842/842/125 929/929/125 +f 929/929/125 842/842/125 928/928/126 +f 831/831/127 839/839/127 925/925/127 +f 925/925/127 839/839/127 929/929/127 +f 929/929/2 928/928/2 925/925/2 +f 925/925/2 928/928/2 927/927/2 +f 925/925/2 927/927/2 924/924/2 +f 924/924/2 927/927/2 926/926/2 +f 930/930/147 931/931/147 932/932/147 +f 933/933/147 934/934/147 935/935/147 +f 935/935/147 934/934/147 936/936/147 +f 937/937/147 938/938/147 939/939/147 +f 937/937/147 939/939/147 933/933/147 +f 935/935/147 936/936/147 930/930/147 +f 930/930/147 936/936/147 931/931/147 +f 933/933/147 939/939/147 934/934/147 +f 940/940/147 941/941/147 937/937/147 +f 941/941/147 938/938/147 937/937/147 +f 932/932/147 942/942/147 943/943/147 +f 943/943/147 942/942/147 944/944/147 +f 945/945/147 946/946/147 947/947/147 +f 947/947/147 946/946/147 948/948/147 +f 947/947/147 948/948/147 949/949/147 +f 947/947/147 949/949/147 207/207/147 +f 943/943/147 944/944/147 950/950/147 +f 950/950/147 944/944/147 951/951/147 +f 207/207/147 952/952/147 941/941/147 +f 207/207/147 941/941/147 940/940/147 +f 950/950/147 951/951/147 946/946/147 +f 950/950/147 946/946/147 945/945/147 +f 931/931/147 953/953/147 932/932/147 +f 932/932/147 953/953/147 942/942/147 +f 207/207/147 949/949/147 952/952/147 +f 954/954/1422 932/932/1423 955/955/1424 +f 955/955/1425 932/932/1426 956/956/1427 +f 956/956/1427 932/932/1426 943/943/1428 +f 956/956/1429 943/943/1430 950/950/1431 +f 956/956/1429 950/950/1431 957/957/1432 +f 957/957/1433 950/950/1434 945/945/1435 +f 957/957/1433 945/945/1435 958/958/1436 +f 958/958/1437 945/945/1437 947/947/1437 +f 958/958/1438 947/947/1438 959/959/1438 +f 959/959/1439 947/947/1440 960/960/1441 +f 960/960/1441 947/947/1440 207/207/1442 +f 960/960/1443 207/207/1444 961/961/1445 +f 961/961/1445 207/207/1444 940/940/1446 +f 961/961/1447 940/940/1447 937/937/1447 +f 961/961/1448 937/937/1448 962/962/1448 +f 962/962/1449 937/937/1449 933/933/1449 +f 962/962/1450 933/933/1450 963/963/1450 +f 963/963/1451 933/933/1451 935/935/1451 +f 963/963/1452 935/935/1452 964/964/1452 +f 964/964/1453 935/935/1453 930/930/1453 +f 964/964/1454 930/930/1454 954/954/1454 +f 954/954/1422 930/930/1455 932/932/1423 +f 960/960/266 965/965/266 959/959/266 +f 959/959/266 965/965/266 966/966/266 +f 967/967/266 968/968/266 962/962/266 +f 962/962/266 968/968/266 961/961/266 +f 960/960/266 969/969/266 965/965/266 +f 961/961/266 970/970/266 969/969/266 +f 961/961/266 968/968/266 970/970/266 +f 963/963/266 971/971/266 967/967/266 +f 963/963/266 967/967/266 962/962/266 +f 964/964/266 972/972/266 963/963/266 +f 963/963/266 972/972/266 971/971/266 +f 958/958/266 966/966/266 973/973/266 +f 959/959/266 966/966/266 958/958/266 +f 954/954/266 972/972/266 964/964/266 +f 961/961/266 969/969/266 960/960/266 +f 954/954/266 974/974/266 972/972/266 +f 975/975/266 976/976/266 957/957/266 +f 957/957/266 976/976/266 956/956/266 +f 956/956/266 976/976/266 977/977/266 +f 958/958/266 973/973/266 975/975/266 +f 958/958/266 975/975/266 957/957/266 +f 955/955/266 978/978/266 954/954/266 +f 954/954/266 978/978/266 974/974/266 +f 977/977/266 978/978/266 956/956/266 +f 956/956/266 978/978/266 955/955/266 +f 931/931/1456 978/978/1456 953/953/1456 +f 953/953/1457 978/978/1457 942/942/1457 +f 942/942/1458 978/978/1459 977/977/1460 +f 942/942/1458 977/977/1460 944/944/1461 +f 944/944/1461 977/977/1460 976/976/1462 +f 944/944/1461 976/976/1462 951/951/1463 +f 951/951/1463 976/976/1462 975/975/1464 +f 951/951/1465 975/975/1465 946/946/1465 +f 946/946/1466 975/975/1466 973/973/1466 +f 946/946/1467 973/973/1468 966/966/1469 +f 946/946/1467 966/966/1469 948/948/1470 +f 948/948/1471 966/966/1472 965/965/1473 +f 948/948/1471 965/965/1473 949/949/1474 +f 949/949/1475 965/965/1475 952/952/1475 +f 952/952/1476 965/965/1476 969/969/1476 +f 952/952/1477 969/969/1477 941/941/1477 +f 941/941/1478 969/969/1478 970/970/1478 +f 941/941/1479 970/970/1480 938/938/1481 +f 938/938/1481 970/970/1480 968/968/1482 +f 938/938/1481 968/968/1482 939/939/1483 +f 939/939/1483 968/968/1482 967/967/1484 +f 939/939/1485 967/967/1485 934/934/1485 +f 934/934/1486 967/967/1486 971/971/1486 +f 934/934/1487 971/971/1488 972/972/1489 +f 934/934/1487 972/972/1489 936/936/1490 +f 936/936/1491 972/972/1492 931/931/1493 +f 931/931/1493 972/972/1492 974/974/1494 +f 931/931/1495 974/974/1495 978/978/1495 +f 979/979/266 980/980/266 981/981/266 +f 982/982/266 983/983/266 980/980/266 +f 982/982/266 980/980/266 979/979/266 +f 984/984/266 985/985/266 986/986/266 +f 986/986/266 985/985/266 987/987/266 +f 988/988/266 989/989/266 984/984/266 +f 988/988/266 990/990/266 989/989/266 +f 986/986/266 987/987/266 983/983/266 +f 986/986/266 983/983/266 982/982/266 +f 989/989/266 985/985/266 984/984/266 +f 991/991/266 992/992/266 988/988/266 +f 993/993/266 994/994/266 995/995/266 +f 996/996/266 997/997/266 998/998/266 +f 992/992/266 990/990/266 988/988/266 +f 999/999/266 997/997/266 996/996/266 +f 1000/1000/266 1001/1001/266 993/993/266 +f 993/993/266 1001/1001/266 994/994/266 +f 996/996/266 1002/1002/266 1000/1000/266 +f 996/996/266 998/998/266 1002/1002/266 +f 991/991/266 1003/1003/266 992/992/266 +f 1000/1000/266 1002/1002/266 1001/1001/266 +f 979/979/266 981/981/266 999/999/266 +f 999/999/266 981/981/266 997/997/266 +f 995/995/266 1004/1004/266 991/991/266 +f 991/991/266 1004/1004/266 1003/1003/266 +f 994/994/266 1004/1004/266 995/995/266 +f 1005/1005/1496 979/979/1497 1006/1006/1498 +f 1006/1006/1498 979/979/1497 999/999/1499 +f 1006/1006/1498 999/999/1499 996/996/1500 +f 1006/1006/1498 996/996/1500 1007/1007/1501 +f 1007/1007/1502 996/996/1503 1008/1008/1504 +f 1008/1008/1504 996/996/1503 1000/1000/1505 +f 1008/1008/1506 1000/1000/1507 993/993/1508 +f 1008/1008/1506 993/993/1508 1009/1009/1509 +f 1009/1009/1510 993/993/1510 995/995/1510 +f 1009/1009/1511 995/995/1511 1010/1010/1511 +f 1010/1010/1512 995/995/1513 991/991/1514 +f 1010/1010/1512 991/991/1514 1011/1011/1515 +f 1011/1011/1516 991/991/1516 988/988/1516 +f 1011/1011/1517 988/988/1517 1012/1012/1517 +f 1012/1012/1518 988/988/1518 984/984/1518 +f 1012/1012/1519 984/984/1519 1013/1013/1519 +f 1013/1013/1520 984/984/1520 986/986/1520 +f 1013/1013/1521 986/986/1521 1014/1014/1521 +f 1014/1014/1522 986/986/1522 982/982/1522 +f 1014/1014/1523 982/982/1524 1005/1005/1525 +f 1005/1005/1525 982/982/1524 979/979/1526 +f 1013/1013/147 1015/1015/147 1012/1012/147 +f 1010/1010/147 1016/1016/147 1009/1009/147 +f 1012/1012/147 1017/1017/147 1011/1011/147 +f 1010/1010/147 1018/1018/147 1016/1016/147 +f 1011/1011/147 1019/1019/147 1018/1018/147 +f 1011/1011/147 1018/1018/147 1010/1010/147 +f 1011/1011/147 1017/1017/147 1019/1019/147 +f 1015/1015/147 1017/1017/147 1012/1012/147 +f 1013/1013/147 1020/1020/147 1015/1015/147 +f 1014/1014/147 1020/1020/147 1013/1013/147 +f 1009/1009/147 1021/1021/147 1008/1008/147 +f 1008/1008/147 1021/1021/147 1022/1022/147 +f 1016/1016/147 1021/1021/147 1009/1009/147 +f 1014/1014/147 1023/1023/147 1020/1020/147 +f 1014/1014/147 1024/1024/147 1023/1023/147 +f 1005/1005/147 1024/1024/147 1014/1014/147 +f 1008/1008/147 1025/1025/147 1007/1007/147 +f 1005/1005/147 1026/1026/147 1024/1024/147 +f 1007/1007/147 1027/1027/147 1028/1028/147 +f 1007/1007/147 1028/1028/147 1006/1006/147 +f 1007/1007/147 1025/1025/147 1027/1027/147 +f 1008/1008/147 1022/1022/147 1025/1025/147 +f 1006/1006/147 1026/1026/147 1005/1005/147 +f 1006/1006/147 1028/1028/147 1026/1026/147 +f 981/981/1527 1026/1026/1528 997/997/1529 +f 997/997/1529 1026/1026/1528 1028/1028/1530 +f 997/997/1529 1028/1028/1530 1027/1027/1531 +f 997/997/1529 1027/1027/1531 998/998/1532 +f 998/998/1532 1027/1027/1531 1025/1025/1533 +f 998/998/1532 1025/1025/1533 1002/1002/1534 +f 1002/1002/1534 1025/1025/1533 1022/1022/1535 +f 1002/1002/1534 1022/1022/1535 1001/1001/1536 +f 1001/1001/1537 1022/1022/1537 1021/1021/1537 +f 1001/1001/1538 1021/1021/1538 994/994/1538 +f 994/994/1539 1021/1021/1539 1016/1016/1539 +f 994/994/1540 1016/1016/1540 1004/1004/1540 +f 1004/1004/1541 1016/1016/1542 1018/1018/1543 +f 1004/1004/1541 1018/1018/1543 1003/1003/1544 +f 1003/1003/1544 1018/1018/1543 1019/1019/1545 +f 1003/1003/1546 1019/1019/1546 992/992/1546 +f 992/992/1547 1019/1019/1547 1017/1017/1547 +f 992/992/1548 1017/1017/1548 990/990/1548 +f 990/990/1549 1017/1017/1550 1015/1015/1551 +f 990/990/1549 1015/1015/1551 989/989/1552 +f 989/989/1553 1015/1015/1553 985/985/1553 +f 985/985/1554 1015/1015/1554 1020/1020/1554 +f 985/985/1555 1020/1020/1555 987/987/1555 +f 987/987/1556 1020/1020/1557 1023/1023/1558 +f 987/987/1556 1023/1023/1558 983/983/1559 +f 983/983/1559 1023/1023/1558 1024/1024/1560 +f 983/983/1559 1024/1024/1560 980/980/1561 +f 980/980/1561 1024/1024/1560 1026/1026/1528 +f 980/980/1561 1026/1026/1528 981/981/1527 +f 8/8/124 4/4/124 3/3/124 +f 7/7/124 4/4/124 8/8/124 +f 6/6/147 1/1/147 4/4/147 +f 4/4/147 7/7/147 6/6/147 +f 2/2/266 5/5/266 8/8/266 +f 8/8/266 3/3/266 2/2/266 +f 6/6/128 5/5/128 2/2/128 +f 6/6/128 2/2/128 1/1/128 diff --git a/examples/Cassie/urdf/meshes/agility/knee.obj b/examples/Cassie/urdf/meshes/agility/knee.obj new file mode 100644 index 0000000000..98830d3f73 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/knee.obj @@ -0,0 +1,4543 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o knee +v 0.060677 -0.025000 -0.090906 +v 0.010677 0.025000 -0.090906 +v 0.060677 0.025000 -0.090906 +v 0.010677 -0.025000 -0.090906 +v 0.010677 0.025000 -0.082406 +v 0.010677 -0.025000 -0.082406 +v 0.060677 -0.025000 -0.082406 +v 0.060677 0.025000 -0.082406 +v 0.060677 0.008450 -0.090906 +v 0.057872 -0.017056 -0.090899 +v 0.061715 -0.025000 -0.090924 +v 0.061801 0.025000 -0.090920 +v 0.065745 -0.025000 -0.092613 +v 0.065811 0.025000 -0.092708 +v 0.011677 0.000000 -0.095906 +v 0.014772 -0.010734 -0.095893 +v 0.011095 -0.015271 -0.095339 +v 0.026759 -0.008299 -0.095906 +v 0.020151 -0.022425 -0.095900 +v 0.023150 -0.017480 -0.095898 +v 0.026489 -0.023813 -0.095906 +v 0.011885 -0.023765 -0.095912 +v 0.011396 -0.020055 -0.095666 +v 0.014711 -0.023137 -0.095901 +v 0.020854 -0.012110 -0.095901 +v 0.026821 0.008335 -0.095906 +v 0.017782 0.010664 -0.095901 +v 0.022475 0.014105 -0.095898 +v 0.022368 0.019997 -0.095901 +v 0.026489 0.024000 -0.095906 +v 0.018268 0.023195 -0.095903 +v 0.011898 0.023779 -0.095912 +v 0.014094 0.022784 -0.095905 +v 0.011663 0.012774 -0.095885 +v 0.011134 0.019120 -0.095408 +v 0.050940 0.022180 -0.095903 +v 0.048204 0.017480 -0.095898 +v 0.047927 0.024000 -0.095906 +v 0.047516 0.008946 -0.095906 +v 0.049754 0.013067 -0.095905 +v 0.060580 0.019679 -0.095899 +v 0.055996 0.023296 -0.095901 +v 0.064585 0.024025 -0.095881 +v 0.057704 -0.000853 -0.095959 +v 0.059692 0.012700 -0.095897 +v 0.053358 0.010704 -0.095901 +v 0.049505 0.007317 -0.095906 +v 0.049448 -0.007443 -0.095906 +v 0.050940 -0.011820 -0.095903 +v 0.047446 -0.008954 -0.095906 +v 0.048276 -0.016229 -0.095900 +v 0.045177 -0.023813 -0.095906 +v 0.049495 -0.020651 -0.095905 +v 0.059598 -0.013076 -0.095906 +v 0.055996 -0.010704 -0.095901 +v 0.064610 -0.024027 -0.095880 +v 0.058674 -0.022035 -0.095902 +v 0.061116 -0.017107 -0.095901 +v 0.053477 -0.023407 -0.095940 +v 0.036782 -0.023336 -0.095901 +v 0.031838 -0.022100 -0.095903 +v 0.041263 -0.020187 -0.095901 +v 0.029180 -0.017371 -0.095897 +v 0.031667 -0.011970 -0.095901 +v 0.036186 -0.010685 -0.095905 +v 0.041253 -0.013427 -0.095883 +v 0.054198 0.003257 -0.095906 +v 0.051451 -0.000191 -0.095906 +v 0.054583 -0.003291 -0.095906 +v 0.057222 0.001689 -0.095906 +v 0.017162 -0.001003 -0.095906 +v 0.019289 -0.002924 -0.095906 +v 0.022798 -0.002704 -0.095906 +v 0.024213 -0.000342 -0.095906 +v 0.018304 0.002604 -0.095906 +v 0.023091 0.002614 -0.095906 +v 0.030374 0.020436 -0.095905 +v 0.029310 0.015368 -0.095890 +v 0.041573 0.014415 -0.095901 +v 0.041369 0.019997 -0.095901 +v 0.037992 0.022872 -0.095905 +v 0.033834 0.023157 -0.095901 +v 0.033711 0.010864 -0.095900 +v 0.038260 0.011217 -0.095904 +v 0.011057 -0.024564 -0.095027 +v 0.011032 -0.024523 -0.090906 +v 0.010677 0.000000 -0.090906 +v 0.010692 0.023373 -0.094915 +v 0.011108 0.024568 -0.090906 +v 0.011654 0.024857 -0.094928 +v 0.025177 0.025000 -0.090906 +v 0.045177 0.025000 -0.090906 +v 0.065765 0.025002 -0.094897 +v 0.025177 -0.025000 -0.090906 +v 0.065778 -0.025006 -0.094883 +v 0.045177 -0.025000 -0.090906 +v 0.057786 0.000358 -0.090906 +v 0.056150 0.002715 -0.090906 +v 0.052749 0.002594 -0.090906 +v 0.051723 -0.001169 -0.090906 +v 0.054489 -0.003124 -0.090906 +v 0.056890 -0.002106 -0.090906 +v 0.018007 0.002493 -0.090906 +v 0.017378 -0.001400 -0.090906 +v 0.020796 -0.003277 -0.090906 +v 0.022550 0.002783 -0.090906 +v 0.024434 -0.000479 -0.090906 +v 0.013495 0.016866 -0.092761 +v 0.014439 0.019275 -0.092744 +v 0.013379 0.017000 -0.090906 +v 0.015102 0.019782 -0.090906 +v 0.017116 0.020174 -0.092751 +v 0.018049 0.019930 -0.090906 +v 0.019047 0.019036 -0.092757 +v 0.019974 0.017000 -0.090906 +v 0.019919 0.016224 -0.092732 +v 0.018251 0.014218 -0.090906 +v 0.017323 0.013877 -0.092752 +v 0.015305 0.014070 -0.090906 +v 0.014671 0.014521 -0.092745 +v 0.051379 0.017000 -0.090906 +v 0.051463 0.016120 -0.092727 +v 0.052976 0.019793 -0.092743 +v 0.053102 0.019782 -0.090906 +v 0.056346 0.019834 -0.090906 +v 0.056410 0.019744 -0.092750 +v 0.057873 0.017045 -0.092753 +v 0.057871 0.015851 -0.090905 +v 0.056802 0.014638 -0.092754 +v 0.053814 0.013771 -0.090906 +v 0.054238 0.013826 -0.092751 +v 0.032379 0.017000 -0.090906 +v 0.032480 0.016953 -0.092753 +v 0.033610 0.019429 -0.092753 +v 0.034102 0.019782 -0.090906 +v 0.036512 0.020120 -0.092743 +v 0.037049 0.019930 -0.090906 +v 0.038908 0.017634 -0.092748 +v 0.038974 0.017000 -0.090906 +v 0.037546 0.014367 -0.092743 +v 0.037251 0.014218 -0.090906 +v 0.034115 0.014108 -0.092748 +v 0.034305 0.014070 -0.090906 +v 0.051531 -0.016430 -0.090906 +v 0.051437 -0.016217 -0.092726 +v 0.053102 -0.014218 -0.090906 +v 0.054031 -0.013877 -0.092752 +v 0.056346 -0.014166 -0.090906 +v 0.057299 -0.014978 -0.092737 +v 0.057493 -0.018496 -0.092752 +v 0.055801 -0.020206 -0.090906 +v 0.055674 -0.019983 -0.092757 +v 0.053023 -0.019811 -0.092743 +v 0.052223 -0.019043 -0.090906 +v 0.032379 -0.017000 -0.090906 +v 0.032768 -0.015780 -0.092753 +v 0.034102 -0.014218 -0.090906 +v 0.034670 -0.013915 -0.092750 +v 0.037049 -0.014070 -0.090906 +v 0.037810 -0.014600 -0.092751 +v 0.038823 -0.016430 -0.090906 +v 0.038854 -0.017907 -0.092736 +v 0.038130 -0.019045 -0.090906 +v 0.035725 -0.020282 -0.092737 +v 0.034814 -0.020229 -0.090906 +v 0.032809 -0.018448 -0.092751 +v 0.013531 -0.016430 -0.090906 +v 0.014119 -0.014943 -0.092744 +v 0.015102 -0.014218 -0.090906 +v 0.017512 -0.013880 -0.092743 +v 0.018049 -0.014070 -0.090906 +v 0.019545 -0.015652 -0.092764 +v 0.019974 -0.017000 -0.090906 +v 0.019571 -0.018378 -0.092742 +v 0.017540 -0.020229 -0.090906 +v 0.017323 -0.020123 -0.092752 +v 0.014042 -0.019001 -0.092725 +v 0.014223 -0.019043 -0.090906 +v 0.026860 -0.008404 -0.092906 +v 0.047565 -0.008924 -0.092906 +v 0.026349 0.007317 -0.092906 +v 0.028299 0.008924 -0.092906 +v 0.048992 0.008415 -0.092906 +v 0.049505 -0.007317 -0.092906 +v 0.053505 0.002805 -0.078790 +v 0.052667 0.002394 -0.093997 +v 0.051673 0.000951 -0.078779 +v 0.051602 -0.000204 -0.093984 +v 0.052127 -0.001668 -0.078795 +v 0.052700 -0.002092 -0.095028 +v 0.053945 -0.003011 -0.078800 +v 0.054965 -0.003116 -0.093985 +v 0.056817 -0.002255 -0.078781 +v 0.057321 -0.001581 -0.093989 +v 0.057735 0.000084 -0.078766 +v 0.057645 0.000765 -0.093967 +v 0.056923 0.002077 -0.078801 +v 0.056473 0.002182 -0.095132 +v 0.055104 0.002842 -0.095051 +v 0.055282 0.002980 -0.078800 +v 0.054401 -0.002770 -0.095153 +v 0.051933 -0.000091 -0.095166 +v 0.053178 0.002331 -0.095206 +v 0.057433 0.000041 -0.095162 +v 0.056608 -0.001930 -0.095140 +v 0.055917 -0.000827 -0.095754 +v 0.053378 0.000383 -0.095779 +v 0.054087 -0.001282 -0.095750 +v 0.055220 0.001164 -0.095771 +v 0.054727 0.000135 -0.095934 +v 0.054708 -0.000750 -0.077923 +v 0.054834 0.000418 -0.077901 +v 0.053135 0.000657 -0.078102 +v 0.053292 -0.001197 -0.078149 +v 0.054306 0.001956 -0.078238 +v 0.055865 0.001274 -0.078135 +v 0.056069 -0.000511 -0.078074 +v 0.055192 -0.002121 -0.078327 +v 0.022346 0.002859 -0.078803 +v 0.021656 0.002806 -0.095052 +v 0.020294 0.002906 -0.093959 +v 0.020444 0.002935 -0.078783 +v 0.018834 0.001974 -0.078787 +v 0.018587 0.001670 -0.093984 +v 0.018112 -0.000374 -0.078799 +v 0.018323 -0.000366 -0.095078 +v 0.019550 -0.002674 -0.093985 +v 0.019085 -0.002202 -0.078807 +v 0.020691 -0.003000 -0.078768 +v 0.022356 -0.002846 -0.093989 +v 0.023148 -0.002417 -0.078782 +v 0.024016 -0.001156 -0.093967 +v 0.024263 0.000625 -0.078794 +v 0.023966 0.000530 -0.095070 +v 0.023135 0.002103 -0.095032 +v 0.018847 -0.001433 -0.095128 +v 0.020757 -0.002759 -0.095181 +v 0.019342 0.002075 -0.095176 +v 0.023388 -0.001637 -0.095160 +v 0.022035 -0.001510 -0.095642 +v 0.022198 0.001232 -0.095700 +v 0.019713 -0.000262 -0.095741 +v 0.022414 -0.000149 -0.095788 +v 0.021091 0.000824 -0.095898 +v 0.020877 -0.000788 -0.095866 +v 0.019471 0.000645 -0.078183 +v 0.020843 0.001680 -0.078120 +v 0.021356 0.000027 -0.077867 +v 0.022399 0.000997 -0.078079 +v 0.022984 -0.000978 -0.078260 +v 0.021395 -0.001491 -0.078079 +v 0.019649 -0.001066 -0.078168 +v 0.056828 -0.018029 -0.095976 +v 0.059332 -0.020952 -0.095836 +v 0.057178 -0.022586 -0.095832 +v 0.060666 -0.015802 -0.095886 +v 0.060422 -0.019201 -0.095894 +v 0.052526 -0.015971 -0.095976 +v 0.048897 -0.018907 -0.095903 +v 0.048596 -0.016091 -0.095862 +v 0.053414 -0.018933 -0.095976 +v 0.054040 -0.023063 -0.095889 +v 0.050900 -0.021891 -0.095818 +v 0.055940 -0.015067 -0.095976 +v 0.056347 -0.011061 -0.095893 +v 0.059231 -0.012925 -0.095813 +v 0.052121 -0.011401 -0.095817 +v 0.049742 -0.013420 -0.095870 +v 0.054367 -0.014408 -0.077975 +v 0.053792 -0.019762 -0.078127 +v 0.056378 -0.019500 -0.078199 +v 0.051934 -0.016752 -0.077952 +v 0.057209 -0.015616 -0.078066 +v 0.056921 -0.019312 -0.092674 +v 0.053510 -0.019899 -0.092668 +v 0.051630 -0.017827 -0.078463 +v 0.051457 -0.017104 -0.092674 +v 0.052379 -0.014943 -0.078472 +v 0.053569 -0.014026 -0.092669 +v 0.054994 -0.013885 -0.078467 +v 0.056349 -0.014430 -0.092675 +v 0.057649 -0.016164 -0.092667 +v 0.057761 -0.016991 -0.078472 +v 0.053414 -0.018933 -0.093676 +v 0.052870 -0.015444 -0.093676 +v 0.056483 -0.018556 -0.093676 +v 0.055940 -0.015067 -0.093676 +v 0.015851 0.020500 0.045928 +v -0.010881 0.020500 0.047432 +v 0.003533 0.020500 0.048536 +v -0.024336 0.020500 0.042142 +v 0.027256 0.020500 0.040316 +v -0.035642 0.020500 0.033134 +v -0.048542 0.020500 -0.003455 +v 0.048734 0.020500 -0.002218 +v 0.046578 0.020500 -0.015619 +v 0.010048 0.020500 -0.047619 +v -0.015015 0.020500 -0.046385 +v 0.026578 0.020500 -0.040987 +v 0.037650 0.020500 0.030820 +v -0.043803 0.020500 0.021201 +v -0.047724 0.020500 0.009110 +v 0.051420 0.020500 -0.000351 +v 0.054530 0.020500 -0.000824 +v 0.063605 0.020500 -0.009666 +v 0.060295 0.020500 -0.009396 +v 0.059960 0.020500 -0.012847 +v 0.061805 0.020500 -0.015319 +v -0.044350 0.020500 -0.020508 +v -0.018503 0.020500 -0.051288 +v 0.000257 0.020500 -0.077138 +v -0.001478 0.020500 -0.079729 +v 0.050856 0.020500 -0.018105 +v 0.042425 0.020500 -0.027224 +v 0.029543 0.020500 -0.041371 +v 0.037053 0.020500 -0.034270 +v 0.031243 0.020500 -0.044046 +v 0.033782 0.020500 -0.042938 +v -0.017703 0.020500 -0.048080 +v -0.004271 0.020500 -0.048479 +v 0.031419 0.020500 -0.052280 +v 0.034609 0.020500 -0.055044 +v 0.036103 0.020500 -0.064193 +v 0.038883 0.020500 -0.063489 +v 0.044233 0.020500 -0.068907 +v 0.043303 0.020500 -0.071624 +v 0.043252 0.020500 -0.075184 +v 0.058666 0.020500 -0.077457 +v 0.040816 0.020500 -0.077311 +v 0.045161 -0.029500 -0.025263 +v 0.050622 -0.029500 -0.018152 +v 0.046571 -0.029500 -0.015425 +v -0.001174 -0.029500 0.048874 +v -0.018760 -0.029500 0.044903 +v 0.014991 -0.029500 0.046216 +v -0.031123 -0.029500 0.037411 +v 0.026397 -0.029500 0.040883 +v 0.036905 -0.029500 0.031694 +v -0.039622 -0.029500 0.028120 +v -0.045629 -0.029500 0.016919 +v -0.048756 -0.029500 0.000926 +v 0.053975 -0.029500 -0.000356 +v 0.048959 -0.029500 -0.001704 +v 0.058955 -0.029500 -0.007527 +v 0.063722 -0.029500 -0.009922 +v -0.045746 -0.029500 -0.016892 +v 0.057617 -0.029500 -0.014281 +v 0.023852 -0.029500 -0.042653 +v 0.061570 -0.029500 -0.015488 +v -0.035393 -0.029500 -0.033744 +v -0.020961 -0.029500 -0.043889 +v 0.007196 -0.029500 -0.048114 +v -0.007484 -0.029500 -0.048097 +v -0.001436 0.025000 -0.079751 +v -0.000548 0.025000 -0.077600 +v 0.007677 0.025000 -0.092406 +v 0.010677 0.025000 -0.082406 +v 0.010677 0.025000 -0.092406 +v 0.064119 0.025000 -0.080625 +v 0.064178 0.025000 -0.082037 +v 0.058628 0.025000 -0.077445 +v 0.064206 0.012000 -0.080698 +v 0.041576 0.012000 -0.066986 +v 0.051572 -0.002000 -0.017912 +v 0.057597 -0.002000 -0.014267 +v 0.046560 -0.002000 -0.014700 +v 0.058974 -0.002000 -0.007523 +v 0.049011 -0.002000 -0.001595 +v 0.053987 -0.002000 -0.000406 +v 0.048586 -0.002000 -0.017536 +v 0.000750 -0.002091 -0.055743 +v 0.007594 -0.002177 -0.067262 +v 0.011546 -0.002071 -0.067369 +v -0.007312 -0.002218 -0.062432 +v 0.000060 -0.002191 -0.072041 +v 0.000688 -0.002179 -0.051468 +v 0.013918 -0.002089 -0.049772 +v 0.040225 -0.002029 -0.073920 +v 0.016850 -0.002269 -0.075077 +v 0.031021 -0.002180 -0.059752 +v 0.027313 -0.002055 -0.043914 +v 0.036075 -0.002162 -0.068360 +v 0.000587 -0.025000 -0.077159 +v 0.001241 -0.013744 -0.077263 +v -0.000164 -0.013299 -0.076349 +v -0.018794 -0.025000 -0.050518 +v -0.001423 -0.012348 -0.074299 +v -0.018409 -0.013529 -0.051321 +v -0.009841 -0.012244 -0.062753 +v -0.009316 -0.004411 -0.063648 +v -0.001880 -0.004880 -0.073883 +v 0.018075 -0.004706 -0.045257 +v 0.026567 -0.004796 -0.040942 +v 0.026416 -0.025000 -0.040836 +v 0.009353 -0.004943 -0.047766 +v 0.000527 -0.013289 -0.048633 +v 0.000894 -0.004894 -0.048649 +v -0.006398 -0.012759 -0.048341 +v -0.014752 -0.013343 -0.046484 +v -0.015387 -0.025000 -0.046338 +v -0.033988 -0.025000 -0.035224 +v -0.017538 -0.013525 -0.047937 +v 0.083966 -0.012000 -0.051527 +v 0.084399 0.012000 -0.049339 +v 0.083350 -0.012000 -0.040165 +v 0.082434 0.012000 -0.038131 +v 0.073813 0.012000 -0.079141 +v 0.074166 -0.012000 -0.078654 +v 0.063614 -0.012000 -0.009381 +v 0.063732 0.012000 -0.009824 +v 0.063839 -0.012000 -0.082245 +v 0.064066 0.012000 -0.082082 +v 0.063440 -0.025000 -0.082288 +v 0.010677 -0.025000 -0.092406 +v 0.010677 -0.025000 -0.082406 +v 0.007677 -0.025000 -0.092406 +v 0.034920 -0.025000 -0.038467 +v 0.040992 -0.025000 -0.028739 +v 0.030824 -0.025000 -0.042302 +v 0.043434 -0.025000 -0.075033 +v 0.040664 -0.025000 -0.077316 +v 0.044468 -0.025000 -0.069065 +v 0.043050 -0.025000 -0.071292 +v 0.064489 -0.025000 -0.081190 +v 0.037629 -0.025000 -0.061970 +v 0.037020 -0.025000 -0.065300 +v 0.033689 -0.025000 -0.050493 +v 0.031592 -0.025000 -0.053705 +v 0.043340 0.012000 -0.026494 +v 0.036640 0.012000 -0.034754 +v 0.033613 0.012000 -0.045084 +v 0.034836 0.012000 -0.055779 +v 0.061570 0.012000 -0.015488 +v 0.045826 0.012000 -0.056965 +v 0.043071 0.012000 -0.048802 +v 0.054025 0.012000 -0.064003 +v 0.064757 0.012000 -0.064589 +v 0.073275 0.012000 -0.059924 +v 0.078202 0.012000 -0.050307 +v 0.077031 0.012000 -0.040738 +v 0.044505 0.012000 -0.040307 +v 0.070266 0.012000 -0.032314 +v 0.059824 0.012000 -0.029765 +v 0.050593 0.012000 -0.032786 +v 0.044401 -0.012000 -0.069050 +v 0.037202 -0.012000 -0.061271 +v 0.033613 -0.012000 -0.049727 +v 0.035609 -0.012000 -0.036378 +v 0.043478 -0.012000 -0.026448 +v 0.061805 -0.012000 -0.015319 +v 0.064340 -0.012000 -0.080897 +v 0.071276 -0.012000 -0.061442 +v 0.064456 -0.012000 -0.064662 +v 0.076240 -0.012000 -0.055763 +v 0.055842 -0.012000 -0.064397 +v 0.076124 -0.012000 -0.039111 +v 0.078408 -0.012000 -0.046312 +v 0.047549 -0.012000 -0.059374 +v 0.049898 -0.012000 -0.033133 +v 0.043843 -0.012000 -0.042051 +v 0.060133 -0.012000 -0.029749 +v 0.070556 -0.012000 -0.032497 +v 0.043312 -0.012000 -0.050652 +v 0.043116 -0.027300 -0.045231 +v 0.045915 -0.027300 -0.037853 +v 0.051247 -0.027300 -0.032474 +v 0.061226 -0.027300 -0.029585 +v 0.071008 -0.027300 -0.033083 +v 0.075593 -0.027300 -0.038170 +v 0.078103 -0.027300 -0.044542 +v 0.077198 -0.027300 -0.053806 +v 0.071341 -0.027300 -0.061527 +v 0.061910 -0.027300 -0.065122 +v 0.050828 -0.027300 -0.062269 +v 0.044353 -0.027300 -0.054145 +v 0.077802 0.027300 -0.051814 +v 0.072801 0.027300 -0.060384 +v 0.061985 0.027300 -0.065238 +v 0.050593 0.027300 -0.062026 +v 0.043537 0.027300 -0.052499 +v 0.043692 0.027300 -0.042853 +v 0.047777 0.027300 -0.035199 +v 0.056142 0.027300 -0.030337 +v 0.066942 0.027300 -0.030659 +v 0.075269 0.027300 -0.037456 +v 0.077986 0.027300 -0.044338 +v 0.020543 0.004236 -0.044243 +v 0.026461 0.004720 -0.041007 +v 0.011919 0.004991 -0.047182 +v 0.002931 0.004915 -0.048530 +v -0.004116 0.004873 -0.048451 +v -0.014300 0.004794 -0.046623 +v 0.042667 0.004436 -0.071159 +v 0.038728 0.004859 -0.067357 +v 0.035457 0.004529 -0.063036 +v 0.033099 0.004929 -0.058307 +v 0.031148 0.004925 -0.050511 +v 0.031083 0.004741 -0.043832 +v 0.029399 0.005016 -0.041394 +v -0.016248 0.004826 -0.046898 +v -0.018139 0.004632 -0.049164 +v -0.018191 0.005404 -0.051884 +v -0.000146 0.004415 -0.076245 +v 0.001222 0.004854 -0.077192 +v 0.040913 0.005049 -0.077188 +v 0.042683 0.004792 -0.075781 +v 0.043543 0.004943 -0.073072 +v 0.036753 0.002122 -0.069209 +v 0.040313 0.002073 -0.074277 +v 0.001985 0.002062 -0.074192 +v 0.029505 0.002071 -0.057970 +v -0.005306 0.002094 -0.051335 +v 0.013626 0.002130 -0.049608 +v -0.015080 0.002088 -0.049436 +v 0.027609 0.002097 -0.043619 +v 0.048694 0.002000 -0.002515 +v 0.046525 0.002000 -0.014395 +v 0.048445 0.002000 -0.017512 +v 0.051656 0.002000 -0.017878 +v 0.059834 0.002000 -0.012947 +v 0.060388 0.002000 -0.009666 +v 0.054986 0.002000 -0.001244 +v 0.051523 0.002000 -0.000180 +v 0.031069 -0.004932 -0.043668 +v 0.031644 -0.005225 -0.053272 +v 0.033420 -0.004435 -0.059320 +v 0.035887 -0.004809 -0.063737 +v 0.038853 -0.004826 -0.067504 +v 0.042817 -0.004702 -0.071242 +v 0.043498 -0.005153 -0.072791 +v 0.043317 -0.005334 -0.074810 +v 0.042136 -0.004793 -0.076366 +v 0.040440 -0.004411 -0.077133 +v 0.016208 -0.013366 -0.077300 +v 0.016715 -0.004546 -0.077194 +v 0.029434 -0.005237 -0.041468 +v -0.009515 -0.004840 -0.061531 +v -0.008535 -0.004880 -0.059778 +v -0.008611 -0.010546 -0.059733 +v -0.002001 -0.010500 -0.054564 +v -0.001861 -0.004985 -0.053995 +v -0.002089 -0.010608 -0.051525 +v -0.002036 -0.005091 -0.051836 +v -0.001036 -0.005053 -0.049691 +v -0.001037 -0.011600 -0.049724 +v -0.002340 -0.004903 -0.055124 +v -0.015621 -0.010580 -0.050289 +v 0.009962 -0.005204 -0.070158 +v 0.009044 -0.010500 -0.069610 +v 0.014915 -0.005367 -0.076695 +v 0.013801 -0.010921 -0.075529 +v 0.001576 -0.010640 -0.074357 +v 0.001326 -0.005047 -0.074406 +v 0.008385 -0.005325 -0.069690 +v 0.041692 0.002800 -0.074814 +v 0.041272 0.002433 -0.072465 +v 0.042863 0.003589 -0.073859 +v 0.040221 0.003404 -0.076454 +v 0.030824 0.003307 -0.054179 +v 0.037913 0.003165 -0.068043 +v 0.033284 0.002754 -0.062255 +v 0.029437 0.002459 -0.053146 +v 0.029389 0.002634 -0.043581 +v 0.001365 0.002801 -0.075741 +v 0.026980 0.003094 -0.041997 +v 0.011109 0.003353 -0.048266 +v 0.001752 0.002763 -0.050039 +v -0.006646 0.003168 -0.049325 +v -0.015335 0.002977 -0.047792 +v -0.017611 0.003631 -0.051574 +v -0.016555 0.002490 -0.050463 +v 0.040959 -0.002710 -0.075451 +v 0.041580 -0.002596 -0.072325 +v 0.042516 -0.003189 -0.073826 +v 0.015315 -0.003347 -0.075813 +v 0.030721 -0.003718 -0.051862 +v 0.030327 -0.003455 -0.043718 +v 0.035642 -0.003165 -0.065220 +v 0.029373 -0.002470 -0.051856 +v 0.028540 -0.002207 -0.043904 +v 0.010122 -0.003156 -0.068895 +v 0.026708 -0.002885 -0.042302 +v 0.028495 -0.003589 -0.041781 +v 0.007752 -0.003986 -0.069433 +v 0.017406 -0.002791 -0.046967 +v 0.000826 -0.003134 -0.049798 +v 0.007811 -0.003076 -0.049193 +v 0.001423 -0.003359 -0.073387 +v -0.000905 -0.003220 -0.054979 +v -0.001107 -0.003340 -0.051476 +v -0.001059 -0.003273 -0.073288 +v -0.008051 -0.003014 -0.061063 +v 0.001255 -0.011474 -0.076048 +v -0.017259 -0.011861 -0.051742 +v -0.015278 -0.011542 -0.047679 +v -0.017355 -0.011840 -0.049530 +v -0.014984 -0.010802 -0.048883 +v 0.022550 0.018696 -0.095821 +v 0.022508 0.015039 -0.095882 +v 0.018828 0.015971 -0.095976 +v 0.011805 0.013126 -0.095870 +v 0.010565 0.017116 -0.095828 +v 0.014526 0.018029 -0.095976 +v 0.015414 0.015067 -0.095976 +v 0.015623 0.010960 -0.095882 +v 0.011348 0.019940 -0.095903 +v 0.019713 0.011588 -0.095816 +v 0.017002 0.023092 -0.095835 +v 0.017940 0.018933 -0.095976 +v 0.020499 0.021898 -0.095900 +v 0.013368 0.022202 -0.095833 +v 0.014613 0.018950 -0.078033 +v 0.016366 0.014128 -0.078111 +v 0.018845 0.015472 -0.077969 +v 0.013741 0.016823 -0.078155 +v 0.019404 0.018025 -0.078131 +v 0.016363 0.019853 -0.078126 +v 0.019735 0.016286 -0.092671 +v 0.019137 0.015021 -0.078463 +v 0.017535 0.013971 -0.092668 +v 0.014502 0.014742 -0.092674 +v 0.014620 0.014702 -0.078472 +v 0.013621 0.017095 -0.092672 +v 0.014633 0.019376 -0.092674 +v 0.017333 0.020022 -0.092673 +v 0.018211 0.019676 -0.078472 +v 0.019165 0.018777 -0.092672 +v 0.015414 0.015067 -0.093676 +v 0.014870 0.018556 -0.093676 +v 0.018483 0.015444 -0.093676 +v 0.017940 0.018933 -0.093676 +v 0.056828 0.015971 -0.095976 +v 0.060666 0.018198 -0.095886 +v 0.060351 0.014577 -0.095848 +v 0.049583 0.020374 -0.095884 +v 0.051653 0.022278 -0.095872 +v 0.052526 0.018029 -0.095976 +v 0.053414 0.015067 -0.095976 +v 0.052353 0.011357 -0.095895 +v 0.050218 0.012820 -0.095869 +v 0.048814 0.015296 -0.095794 +v 0.048678 0.018044 -0.095860 +v 0.055940 0.018933 -0.095976 +v 0.054625 0.023145 -0.095848 +v 0.058764 0.021656 -0.095842 +v 0.057615 0.011616 -0.095893 +v 0.055278 0.010932 -0.095802 +v 0.055564 0.014278 -0.078133 +v 0.057279 0.016626 -0.077971 +v 0.053620 0.014360 -0.078032 +v 0.052639 0.019109 -0.078163 +v 0.051842 0.017296 -0.078084 +v 0.055970 0.019316 -0.077969 +v 0.057067 0.014845 -0.092661 +v 0.057287 0.015316 -0.078470 +v 0.054120 0.013982 -0.092674 +v 0.051731 0.015748 -0.092669 +v 0.051951 0.015601 -0.078473 +v 0.052470 0.019270 -0.092672 +v 0.054830 0.020103 -0.078470 +v 0.055333 0.020022 -0.092673 +v 0.057486 0.018443 -0.078463 +v 0.057529 0.018304 -0.092674 +v 0.053414 0.015067 -0.093676 +v 0.052870 0.018556 -0.093676 +v 0.056483 0.015444 -0.093676 +v 0.055940 0.018933 -0.093676 +v 0.041466 0.018923 -0.095835 +v 0.041700 0.015801 -0.095857 +v 0.037828 0.015971 -0.095976 +v 0.033526 0.018029 -0.095976 +v 0.029919 0.014893 -0.095882 +v 0.029801 0.018853 -0.095830 +v 0.031804 0.021726 -0.095884 +v 0.034898 0.023080 -0.095860 +v 0.034414 0.015067 -0.095976 +v 0.032167 0.011932 -0.095856 +v 0.039619 0.012203 -0.095879 +v 0.035604 0.010882 -0.095836 +v 0.036940 0.018933 -0.095976 +v 0.039091 0.022185 -0.095854 +v 0.036704 0.019400 -0.077975 +v 0.036654 0.014559 -0.077971 +v 0.038597 0.017043 -0.078129 +v 0.034642 0.014319 -0.078141 +v 0.033016 0.015671 -0.078184 +v 0.033874 0.018945 -0.077969 +v 0.038650 0.016216 -0.092672 +v 0.037279 0.014246 -0.078457 +v 0.036654 0.013952 -0.092669 +v 0.033212 0.015013 -0.092672 +v 0.032813 0.018307 -0.092668 +v 0.032856 0.018246 -0.078472 +v 0.034715 0.019930 -0.078472 +v 0.035209 0.020072 -0.092676 +v 0.037509 0.019539 -0.078467 +v 0.038109 0.019041 -0.092668 +v 0.035232 0.014657 -0.093676 +v 0.033870 0.018556 -0.093676 +v 0.037928 0.017786 -0.093676 +v 0.018828 -0.018029 -0.095976 +v 0.020979 -0.021379 -0.095836 +v 0.017742 -0.023053 -0.095870 +v 0.021958 -0.013927 -0.095877 +v 0.022853 -0.017439 -0.095833 +v 0.014526 -0.015971 -0.095976 +v 0.010644 -0.017782 -0.095825 +v 0.010862 -0.015059 -0.095879 +v 0.017940 -0.015067 -0.095976 +v 0.016627 -0.010886 -0.095886 +v 0.019593 -0.011605 -0.095848 +v 0.014144 -0.022574 -0.095893 +v 0.011787 -0.020683 -0.095838 +v 0.015414 -0.018933 -0.095976 +v 0.013132 -0.011971 -0.095859 +v 0.019014 -0.015387 -0.078033 +v 0.017476 -0.019737 -0.078082 +v 0.019561 -0.017269 -0.078164 +v 0.014889 -0.019355 -0.078133 +v 0.014340 -0.015203 -0.078130 +v 0.016088 -0.014414 -0.077969 +v 0.019383 -0.018447 -0.092674 +v 0.018747 -0.019286 -0.078472 +v 0.016978 -0.020187 -0.092669 +v 0.013649 -0.018124 -0.092670 +v 0.013575 -0.017172 -0.078470 +v 0.014388 -0.014921 -0.092673 +v 0.016994 -0.013885 -0.078467 +v 0.017407 -0.013875 -0.092665 +v 0.019649 -0.016150 -0.092673 +v 0.014426 -0.017786 -0.093676 +v 0.017121 -0.014657 -0.093676 +v 0.018483 -0.018556 -0.093676 +v 0.029796 -0.018764 -0.095871 +v 0.029809 -0.015332 -0.095842 +v 0.033710 -0.018348 -0.095976 +v 0.037828 -0.018029 -0.095976 +v 0.040485 -0.020778 -0.095908 +v 0.037930 -0.022721 -0.095862 +v 0.035225 -0.023068 -0.095854 +v 0.032113 -0.022023 -0.095830 +v 0.035493 -0.014623 -0.095976 +v 0.037826 -0.011319 -0.095856 +v 0.040673 -0.013347 -0.095834 +v 0.041820 -0.017505 -0.095856 +v 0.034682 -0.010931 -0.095820 +v 0.031832 -0.012146 -0.095911 +v 0.035658 -0.014166 -0.078016 +v 0.035841 -0.019869 -0.078114 +v 0.038073 -0.018677 -0.078086 +v 0.033388 -0.018207 -0.077974 +v 0.032722 -0.016823 -0.078150 +v 0.037824 -0.015012 -0.078157 +v 0.037557 -0.019488 -0.092671 +v 0.035120 -0.020018 -0.092674 +v 0.033845 -0.019539 -0.078467 +v 0.033028 -0.018646 -0.092671 +v 0.032885 -0.015506 -0.092672 +v 0.033829 -0.014473 -0.078467 +v 0.035576 -0.013884 -0.092671 +v 0.038235 -0.015188 -0.092674 +v 0.038737 -0.017152 -0.078473 +v 0.038681 -0.017496 -0.092671 +v 0.033426 -0.017786 -0.093676 +v 0.034634 -0.014939 -0.093676 +v 0.036720 -0.019061 -0.093676 +v 0.037928 -0.016214 -0.093676 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.0070 -0.0000 1.0000 +vn 0.0033 -0.0009 1.0000 +vn 0.1982 -0.0014 0.9802 +vn 0.2087 0.0012 0.9780 +vn 0.3877 -0.0006 0.9218 +vn 0.4072 0.0012 0.9133 +vn -0.0116 -0.0033 -0.9999 +vn -0.0565 -0.0173 -0.9983 +vn -0.1093 -0.0327 -0.9935 +vn -0.0002 -0.0006 -1.0000 +vn -0.0004 0.0025 -1.0000 +vn -0.0016 0.0001 -1.0000 +vn -0.0001 0.0012 -1.0000 +vn -0.0091 0.0584 -0.9983 +vn -0.0108 0.0647 -0.9978 +vn -0.0023 0.0261 -0.9997 +vn -0.0008 0.0000 -1.0000 +vn 0.0001 0.0009 -1.0000 +vn -0.0009 0.0011 -1.0000 +vn -0.0011 0.0004 -1.0000 +vn -0.0005 -0.0007 -1.0000 +vn -0.0000 -0.0010 -1.0000 +vn 0.0004 -0.0075 -1.0000 +vn -0.0315 -0.0768 -0.9965 +vn -0.0136 -0.0370 -0.9992 +vn -0.0021 0.0016 -1.0000 +vn -0.0424 -0.1006 -0.9940 +vn 0.0004 -0.0009 -1.0000 +vn 0.0131 -0.0004 -0.9999 +vn 0.0003 -0.0004 -1.0000 +vn -0.0001 0.0004 -1.0000 +vn -0.0006 0.0007 -1.0000 +vn 0.0042 0.0003 -1.0000 +vn 0.0015 0.0077 -1.0000 +vn 0.0033 0.0019 -1.0000 +vn 0.0019 -0.0004 -1.0000 +vn -0.0078 0.0045 -1.0000 +vn 0.0006 0.0008 -1.0000 +vn 0.0004 0.0003 -1.0000 +vn -0.0004 -0.0023 -1.0000 +vn 0.0004 -0.0006 -1.0000 +vn -0.0004 -0.0011 -1.0000 +vn 0.0020 -0.0003 -1.0000 +vn -0.0022 -0.3689 -0.9295 +vn -0.0024 0.0036 -1.0000 +vn -0.0126 -0.0064 -0.9999 +vn -0.0029 -0.0044 -1.0000 +vn 0.0046 -0.0001 -1.0000 +vn 0.0048 0.0034 -1.0000 +vn -0.0008 -0.0034 -1.0000 +vn 0.0129 -0.3845 -0.9230 +vn 0.0057 0.0060 -1.0000 +vn -0.0002 0.0076 -1.0000 +vn 0.0004 0.0006 -1.0000 +vn 0.0004 0.0018 -1.0000 +vn 0.0022 0.0001 -1.0000 +vn -0.0000 -0.0014 -1.0000 +vn 0.0001 -0.0016 -1.0000 +vn -0.0013 -0.0026 -1.0000 +vn 0.0003 0.0004 -1.0000 +vn -0.0325 0.0081 -0.9994 +vn -0.3917 0.4846 -0.7821 +vn -0.0008 -0.0011 -1.0000 +vn 0.0034 0.0004 -1.0000 +vn -0.0005 0.0004 -1.0000 +vn -0.0004 -0.0006 -1.0000 +vn -0.0005 0.0034 -1.0000 +vn 0.0001 -0.0043 -1.0000 +vn -0.0001 0.0022 -1.0000 +vn -0.0005 -0.0013 -1.0000 +vn -0.9576 -0.0261 -0.2868 +vn -0.9999 -0.0145 -0.0059 +vn -0.9993 -0.0065 -0.0374 +vn -0.8923 0.1092 -0.4380 +vn -0.9950 0.0175 0.0980 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn -0.0256 0.9983 0.0517 +vn -0.0306 0.9972 0.0675 +vn -0.0028 0.9997 -0.0260 +vn -0.0024 0.9999 -0.0133 +vn -0.0001 1.0000 -0.0010 +vn 0.0001 1.0000 0.0006 +vn 0.0004 1.0000 0.0009 +vn -0.0030 -0.9955 -0.0949 +vn -0.0337 -0.9994 0.0097 +vn -0.0283 -0.9996 -0.0060 +vn -0.0006 -1.0000 -0.0033 +vn 0.0002 -1.0000 0.0017 +vn -0.0072 -0.9992 -0.0398 +vn 0.0011 -1.0000 0.0027 +vn -0.8371 0.5420 -0.0747 +vn -0.0021 -0.7396 -0.6731 +vn -0.0021 -0.7409 -0.6716 +vn -0.0001 -0.7595 -0.6506 +vn -0.0297 -0.7086 -0.7050 +vn -0.0373 -0.7345 -0.6776 +vn -0.6653 0.2347 -0.7087 +vn -0.7345 0.0018 -0.6786 +vn -0.9446 -0.0067 -0.3282 +vn -0.8249 -0.0179 -0.5650 +vn -0.6884 -0.0007 -0.7253 +vn -0.6659 0.0005 -0.7461 +vn -0.7081 -0.0466 -0.7046 +vn -0.6581 0.4213 -0.6240 +vn -0.0003 0.7498 -0.6617 +vn -0.0099 0.6733 -0.7393 +vn -0.0093 0.6777 -0.7353 +vn 0.0000 0.7094 -0.7048 +vn -0.0015 0.7231 -0.6908 +vn -0.0001 0.7106 -0.7036 +vn 0.6491 -0.0000 -0.7607 +vn 0.6406 0.0003 -0.7679 +vn 0.6492 -0.0000 -0.7606 +vn 0.6403 0.0003 -0.7681 +vn 0.9999 -0.0012 0.0135 +vn 0.9998 0.0003 -0.0210 +vn 0.9998 0.0002 -0.0200 +vn 0.9999 -0.0013 0.0145 +vn -0.9805 -0.1869 0.0607 +vn -0.8816 -0.4713 -0.0260 +vn -0.8066 -0.5886 0.0533 +vn -0.7189 -0.6950 -0.0115 +vn -0.4587 -0.8847 0.0832 +vn 0.0353 -0.9920 -0.1213 +vn 0.7741 -0.6168 0.1426 +vn 0.9029 -0.4298 0.0050 +vn 0.8734 -0.4851 0.0434 +vn 0.9596 -0.2616 -0.1034 +vn 0.6999 0.7071 0.1002 +vn 0.6358 0.7710 0.0365 +vn 0.6566 0.7521 0.0564 +vn 0.5771 0.8165 -0.0164 +vn -0.5498 0.8334 0.0562 +vn -0.3901 0.9200 -0.0381 +vn -0.4846 0.8746 0.0163 +vn -0.6117 0.7852 0.0962 +vn -0.9378 0.3407 -0.0665 +vn 0.9522 -0.3015 0.0499 +vn 0.9758 -0.2185 -0.0121 +vn 0.9702 -0.2424 0.0055 +vn 0.9857 -0.1593 -0.0552 +vn 0.6700 0.7418 0.0300 +vn 0.5453 0.8369 -0.0467 +vn 0.5991 0.8005 -0.0150 +vn 0.4799 0.8734 -0.0827 +vn 0.0021 -0.9998 -0.0221 +vn 0.0310 -0.9995 0.0074 +vn 0.0338 -0.9994 0.0102 +vn 0.0637 -0.9971 0.0406 +vn -0.7612 0.6473 -0.0390 +vn -0.6026 0.7835 -0.1515 +vn -0.6966 0.7120 -0.0889 +vn -0.8567 0.5132 0.0519 +vn -0.9346 -0.3544 0.0316 +vn -0.8928 -0.4488 -0.0378 +vn -0.9096 -0.4152 -0.0125 +vn -0.8634 -0.4985 -0.0769 +vn -0.0619 0.9941 0.0890 +vn 0.9275 -0.3643 0.0840 +vn 0.8769 -0.4738 -0.0807 +vn 0.9026 -0.4304 -0.0122 +vn 0.8393 -0.5198 -0.1594 +vn 0.3153 -0.9378 0.1450 +vn 0.1495 -0.9877 -0.0467 +vn 0.2195 -0.9751 0.0324 +vn 0.0495 -0.9866 -0.1555 +vn -0.5023 -0.8531 0.1412 +vn -0.8793 -0.4700 -0.0766 +vn -0.9201 -0.3903 0.0321 +vn -0.8218 -0.5399 -0.1823 +vn -0.9444 -0.2915 0.1523 +vn -0.8339 0.5165 -0.1944 +vn -0.7968 0.6003 -0.0684 +vn -0.7305 0.6784 0.0780 +vn -0.6584 0.7265 0.1968 +vn -0.0495 0.9863 -0.1573 +vn 0.0555 0.9975 -0.0436 +vn 0.1268 0.9913 0.0350 +vn 0.2335 0.9599 0.1549 +vn 0.8504 0.5167 -0.0990 +vn 0.8714 0.4884 -0.0462 +vn 0.8260 0.5429 -0.1516 +vn 0.8936 0.4483 0.0235 +vn 0.4607 -0.4907 -0.7395 +vn 0.6981 0.0448 -0.7146 +vn 0.6841 -0.2382 -0.6894 +vn 0.7178 0.1900 -0.6698 +vn 0.6020 0.2966 -0.7413 +vn 0.2485 0.7255 -0.6417 +vn 0.2176 0.7172 -0.6620 +vn 0.2188 0.7175 -0.6612 +vn 0.1687 0.7021 -0.6918 +vn -0.4372 0.5969 -0.6727 +vn -0.4486 0.5634 -0.6938 +vn -0.4488 0.5626 -0.6942 +vn -0.4625 0.5177 -0.7198 +vn -0.7827 -0.0145 -0.6222 +vn -0.7251 -0.1014 -0.6811 +vn -0.6349 -0.3288 -0.6992 +vn -0.5226 -0.4421 -0.7290 +vn -0.1947 -0.6843 -0.7027 +vn -0.0810 -0.6712 -0.7368 +vn 0.2890 -0.6546 -0.6986 +vn 0.8973 -0.4162 0.1472 +vn 0.9022 -0.3707 0.2207 +vn 0.8765 -0.4803 0.0317 +vn 0.8486 -0.5255 -0.0614 +vn 0.0160 -0.9998 -0.0071 +vn 0.0060 -0.9999 0.0114 +vn -0.0048 -0.9995 0.0311 +vn -0.0142 -0.9987 0.0483 +vn -0.8967 -0.4343 -0.0855 +vn -0.8791 -0.4765 -0.0073 +vn -0.9077 -0.3827 -0.1722 +vn -0.9097 -0.3484 -0.2261 +vn -0.8839 0.3932 0.2531 +vn -0.4058 0.8811 -0.2428 +vn -0.3606 0.9204 -0.1513 +vn -0.4345 0.8475 -0.3048 +vn -0.3015 0.9526 -0.0412 +vn 0.6886 0.7238 0.0441 +vn 0.6291 0.7592 0.1669 +vn 0.7520 0.6441 -0.1399 +vn 0.7738 0.5835 -0.2463 +vn 0.7269 0.2563 -0.6371 +vn 0.5594 0.4458 -0.6988 +vn 0.5255 0.4545 -0.7192 +vn 0.4069 0.5636 -0.7188 +vn 0.4597 0.5632 -0.6866 +vn -0.2273 0.7227 -0.6527 +vn -0.2279 0.7219 -0.6534 +vn -0.2289 0.7204 -0.6547 +vn -0.6173 0.2750 -0.7371 +vn -0.6963 -0.0034 -0.7177 +vn -0.7332 0.1695 -0.6585 +vn -0.6661 -0.2807 -0.6910 +vn -0.3479 -0.5679 -0.7460 +vn -0.1489 -0.6981 -0.7004 +vn 0.0781 -0.7039 -0.7060 +vn 0.1623 -0.7342 -0.6592 +vn 0.6303 -0.3676 -0.6838 +vn 0.6252 -0.3175 -0.7129 +vn 0.6251 -0.3160 -0.7138 +vn 0.6166 -0.2572 -0.7441 +vn 0.8888 -0.4581 -0.0109 +vn 0.9081 -0.4144 0.0602 +vn 0.8690 -0.4904 -0.0657 +vn 0.8435 -0.5223 -0.1253 +vn 0.1683 -0.9849 0.0396 +vn 0.2295 -0.9655 0.1234 +vn 0.1146 -0.9929 -0.0323 +vn 0.0498 -0.9919 -0.1172 +vn -0.7573 -0.6513 0.0475 +vn -0.7131 -0.6875 0.1373 +vn -0.8017 -0.5937 -0.0691 +vn -0.8253 -0.5425 -0.1568 +vn -0.9000 0.4269 0.0877 +vn -0.9105 0.3798 0.1634 +vn -0.8759 0.4823 -0.0104 +vn -0.8464 0.5242 -0.0934 +vn -0.0678 0.9962 0.0551 +vn -0.0752 0.9948 0.0686 +vn -0.0592 0.9974 0.0413 +vn -0.0502 0.9984 0.0258 +vn 0.8448 0.5335 -0.0414 +vn 0.8572 0.5150 -0.0015 +vn 0.8333 0.5477 -0.0751 +vn 0.8665 0.4980 0.0347 +vn 0.6621 0.0125 -0.7493 +vn 0.5677 0.4563 -0.6852 +vn 0.6761 0.1901 -0.7118 +vn 0.5548 0.5435 -0.6299 +vn -0.0537 0.7003 -0.7118 +vn -0.0517 0.6992 -0.7130 +vn -0.3661 0.5449 -0.7543 +vn -0.2730 0.6499 -0.7093 +vn -0.6572 0.2735 -0.7024 +vn -0.6999 0.1116 -0.7055 +vn -0.7775 -0.0284 -0.6282 +vn -0.4763 -0.5154 -0.7124 +vn -0.4894 -0.4702 -0.7344 +vn -0.1941 -0.6321 -0.7502 +vn -0.2771 -0.6568 -0.7013 +vn 0.2064 -0.6774 -0.7060 +vn 0.4310 -0.5069 -0.7466 +vn 0.6101 -0.3793 -0.6956 +vn 0.8103 -0.5757 -0.1095 +vn 0.7648 -0.6442 0.0079 +vn 0.7151 -0.6911 0.1050 +vn 0.6578 -0.7270 0.1967 +vn 0.0158 -0.9846 -0.1739 +vn -0.3105 -0.9183 0.2456 +vn -0.8572 -0.4531 -0.2447 +vn -0.9691 -0.0545 0.2405 +vn -0.8091 0.5329 -0.2479 +vn -0.7735 0.6191 -0.1355 +vn -0.7277 0.6851 -0.0324 +vn -0.6273 0.7669 0.1354 +vn 0.2362 0.9599 -0.1508 +vn 0.1619 0.9863 -0.0328 +vn 0.0649 0.9912 0.1150 +vn 0.2990 0.9198 -0.2543 +vn 0.9198 0.3586 0.1595 +vn 0.8920 0.3925 0.2243 +vn 0.9467 0.3128 0.0768 +vn 0.9665 0.2560 -0.0200 +vn 0.6950 0.1924 -0.6928 +vn 0.6500 0.2337 -0.7231 +vn 0.5813 0.3982 -0.7096 +vn 0.3707 0.5381 -0.7570 +vn 0.1202 0.7042 -0.6997 +vn -0.2065 0.6474 -0.7336 +vn -0.4479 0.5611 -0.6961 +vn -0.6059 0.2811 -0.7442 +vn -0.7065 0.0273 -0.7072 +vn -0.5155 -0.3966 -0.7596 +vn -0.5679 -0.4557 -0.6855 +vn -0.1359 -0.6934 -0.7076 +vn 0.1347 -0.6399 -0.7566 +vn 0.4174 -0.5795 -0.7000 +vn 0.5495 -0.4476 -0.7055 +vn 0.6519 -0.3943 -0.6477 +vn 0.8383 -0.5192 -0.1664 +vn 0.8015 -0.5930 -0.0770 +vn 0.7638 -0.6454 -0.0058 +vn 0.6970 -0.7104 0.0976 +vn 0.0496 -0.9878 -0.1475 +vn -0.0440 -0.9987 -0.0272 +vn -0.1252 -0.9890 0.0783 +vn -0.2092 -0.9594 0.1893 +vn -0.8670 -0.4979 -0.0178 +vn -0.9094 -0.4042 0.0980 +vn -0.7897 -0.5936 -0.1552 +vn -0.9304 -0.2927 0.2205 +vn -0.9434 0.2500 -0.2178 +vn -0.5857 0.7716 0.2481 +vn -0.3301 0.9244 -0.1910 +vn 0.5170 0.8237 0.2329 +vn 0.7676 0.5788 -0.2754 +vn 0.9764 0.0149 0.2155 +vn 0.7140 0.0302 -0.6995 +vn 0.5772 0.3243 -0.7494 +vn 0.4309 0.5705 -0.6991 +vn 0.2729 0.6506 -0.7087 +vn 0.1846 0.7372 -0.6499 +vn -0.4103 0.5838 -0.7006 +vn -0.4147 0.5707 -0.7088 +vn -0.4149 0.5701 -0.7091 +vn -0.4202 0.5539 -0.7188 +vn -0.7956 0.0004 -0.6059 +vn -0.7332 -0.0815 -0.6751 +vn -0.7239 -0.0926 -0.6837 +vn -0.6213 -0.1996 -0.7577 +vn -0.3604 -0.6713 -0.6477 +vn -0.2593 -0.6688 -0.6967 +vn -0.0780 -0.7156 -0.6942 +vn 0.1828 -0.6379 -0.7481 +vn 0.4656 -0.5494 -0.6938 +vn 0.6288 -0.2670 -0.7303 +vn 0.7982 -0.5672 -0.2030 +vn 0.2213 -0.9687 0.1121 +vn 0.2921 -0.9327 0.2117 +vn 0.1391 -0.9903 0.0003 +vn 0.0498 -0.9919 -0.1171 +vn -0.7320 -0.6812 -0.0093 +vn -0.6522 -0.7496 0.1131 +vn -0.7795 -0.6182 -0.1013 +vn -0.8187 -0.5379 -0.2012 +vn -0.9755 -0.0072 0.2199 +vn -0.7697 0.5802 -0.2665 +vn -0.7415 0.6505 -0.1645 +vn -0.6865 0.7267 -0.0271 +vn -0.6094 0.7843 0.1163 +vn 0.3279 0.9447 0.0071 +vn 0.3236 0.9460 0.0163 +vn 0.3326 0.9431 -0.0030 +vn 0.3367 0.9416 -0.0118 +vn 0.9628 0.2550 -0.0899 +vn 0.9863 0.1532 0.0606 +vn 0.9798 0.0597 0.1908 +vn 0.9562 -0.0168 0.2923 +vn 0.6892 0.0375 -0.7236 +vn 0.6521 -0.0159 -0.7579 +vn 0.6936 0.0442 -0.7190 +vn 0.7236 0.0923 -0.6841 +vn 0.4921 0.5789 -0.6502 +vn 0.3393 0.6068 -0.7188 +vn 0.1948 0.6829 -0.7040 +vn -0.1141 0.6522 -0.7494 +vn -0.3907 0.6026 -0.6959 +vn -0.6033 0.2987 -0.7395 +vn -0.7147 0.0490 -0.6978 +vn -0.6177 -0.2854 -0.7328 +vn -0.4687 -0.5529 -0.6889 +vn -0.1524 -0.6537 -0.7412 +vn 0.1856 -0.6888 -0.7008 +vn 0.4045 -0.5873 -0.7011 +vn 0.5797 -0.5439 -0.6068 +vn 0.0315 0.9989 0.0342 +vn 0.0310 0.9991 0.0299 +vn 0.0257 0.9996 -0.0070 +vn 0.0251 0.9996 -0.0113 +vn 0.9880 -0.0037 0.1542 +vn 0.9908 -0.0001 0.1357 +vn 0.9995 0.0282 -0.0102 +vn 0.9989 0.0325 -0.0325 +vn 0.6278 -0.7618 -0.1601 +vn -0.0202 -0.9904 -0.1367 +vn -0.0243 -0.9864 -0.1627 +vn 0.0250 -0.9879 0.1530 +vn 0.0290 -0.9835 0.1788 +vn -0.6242 -0.7621 0.1722 +vn -0.9998 0.0039 0.0188 +vn -1.0000 -0.0007 -0.0035 +vn -0.9900 -0.0284 -0.1384 +vn -0.9871 -0.0322 -0.1567 +vn -0.6378 0.7699 -0.0202 +vn -0.6183 0.7859 -0.0001 +vn -0.6224 0.7827 -0.0042 +vn -0.6023 0.7981 0.0159 +vn -0.7109 0.7030 0.0202 +vn -0.8905 0.4171 -0.1818 +vn -0.7405 0.6719 0.0153 +vn -0.9191 0.3762 -0.1175 +vn -0.9851 -0.1709 0.0176 +vn -0.8931 -0.4367 -0.1081 +vn -0.8485 -0.5292 0.0080 +vn -0.6804 -0.7289 -0.0758 +vn -0.5771 -0.8166 -0.0020 +vn -0.3965 -0.9172 -0.0394 +vn 0.2549 -0.9667 0.0238 +vn 0.4577 -0.8711 -0.1780 +vn 0.2894 -0.9570 0.0190 +vn 0.5455 -0.8369 -0.0442 +vn 0.9559 -0.2339 -0.1774 +vn 0.9387 -0.3445 0.0121 +vn 0.9307 -0.3654 0.0147 +vn 0.9896 -0.1368 -0.0441 +vn 0.8283 0.5369 -0.1605 +vn 0.7441 0.6681 0.0011 +vn 0.9260 0.3775 0.0114 +vn 0.6563 0.7488 -0.0920 +vn 0.4336 0.9010 -0.0124 +vn 0.4793 0.8776 -0.0079 +vn -0.2036 0.9774 -0.0561 +vn -0.1067 0.9943 -0.0082 +vn -0.1977 0.9787 -0.0554 +vn -0.0980 0.9952 -0.0074 +vn -0.3745 -0.9226 -0.0925 +vn -0.8887 -0.3605 -0.2831 +vn -0.8281 0.4195 -0.3719 +vn -0.8865 0.3836 -0.2588 +vn -0.2417 0.9583 -0.1522 +vn 0.8416 0.3827 -0.3812 +vn 0.9580 -0.2087 -0.1966 +vn 0.8392 -0.3557 -0.4114 +vn 0.3266 -0.8516 -0.4100 +vn 0.4947 -0.8520 -0.1712 +vn 0.2471 -0.1521 -0.9570 +vn 0.2876 -0.3219 -0.9020 +vn -0.0299 -0.3930 -0.9191 +vn 0.3438 0.0395 -0.9382 +vn -0.1739 0.3022 -0.9373 +vn -0.2670 0.0793 -0.9604 +vn -0.3882 -0.0429 -0.9206 +vn -0.1306 -0.2539 -0.9584 +vn -0.3069 -0.2841 -0.9083 +vn 0.2438 0.2614 -0.9339 +vn 0.1312 0.2317 -0.9639 +vn 0.0442 0.3971 -0.9167 +vn 0.0144 0.0286 -0.9995 +vn 0.0002 -0.1427 0.9898 +vn 0.0174 0.0803 0.9966 +vn -0.2806 0.1204 0.9522 +vn -0.4029 0.1205 0.9073 +vn -0.3973 -0.2353 0.8870 +vn -0.2606 -0.2160 0.9410 +vn -0.2019 0.4111 0.8890 +vn -0.0713 0.3520 0.9333 +vn 0.1023 0.4419 0.8912 +vn 0.2289 0.2316 0.9455 +vn 0.3339 0.3009 0.8933 +vn 0.4073 0.0120 0.9132 +vn 0.2746 -0.0965 0.9567 +vn 0.2994 -0.3124 0.9015 +vn 0.1032 -0.4279 0.8979 +vn -0.1041 -0.4405 0.8917 +vn 0.4322 0.9018 0.0013 +vn 0.2966 0.9549 -0.0157 +vn 0.0667 0.9978 -0.0059 +vn 0.0399 0.9992 -0.0023 +vn -0.5125 0.8587 0.0034 +vn -0.4674 0.8645 -0.1848 +vn -0.5191 0.8547 0.0026 +vn -0.5856 0.8096 -0.0408 +vn -0.9558 0.2939 0.0097 +vn -0.9546 0.2322 -0.1868 +vn -0.9598 0.2806 0.0077 +vn -0.9643 0.2110 -0.1599 +vn -0.8825 -0.4702 -0.0123 +vn -0.8850 -0.4655 0.0104 +vn -0.8828 -0.4697 -0.0014 +vn -0.8825 -0.4701 -0.0124 +vn -0.4452 -0.8953 0.0142 +vn -0.0804 -0.9967 -0.0068 +vn -0.1124 -0.9936 0.0137 +vn -0.0400 -0.9992 -0.0071 +vn 0.2309 -0.9728 0.0154 +vn 0.9232 -0.3653 -0.1194 +vn 0.9243 -0.3810 0.0212 +vn 0.7131 -0.6999 -0.0402 +vn 0.9831 0.1826 0.0154 +vn 0.9758 0.1941 -0.1004 +vn 0.6930 0.7206 -0.0195 +vn -0.5131 -0.7204 -0.4666 +vn -0.8941 -0.4424 0.0696 +vn -0.8431 0.3351 -0.4205 +vn -0.4762 0.8538 -0.2104 +vn -0.2563 0.8797 -0.4005 +vn 0.8968 -0.2233 -0.3820 +vn 0.7109 -0.6971 -0.0928 +vn 0.3402 -0.7879 -0.5132 +vn 0.0347 -0.5028 -0.8637 +vn 0.3666 -0.3960 -0.8419 +vn -0.0612 -0.9981 0.0099 +vn 0.1746 -0.3357 -0.9256 +vn 0.3201 0.3356 -0.8859 +vn 0.4173 0.0792 -0.9053 +vn 0.2139 0.2616 -0.9412 +vn 0.0493 0.4180 -0.9071 +vn -0.4294 -0.0134 -0.9030 +vn -0.2937 -0.0455 -0.9548 +vn -0.3160 -0.2459 -0.9163 +vn 0.2655 -0.0328 -0.9636 +vn -0.0459 0.1858 -0.9815 +vn -0.2337 0.2751 -0.9326 +vn -0.0724 -0.1777 -0.9814 +vn -0.3376 0.2782 0.8992 +vn -0.4498 -0.0463 0.8919 +vn -0.3137 0.1168 0.9423 +vn -0.0658 0.3068 0.9495 +vn 0.0215 -0.0038 0.9998 +vn -0.1106 0.4360 0.8931 +vn 0.1857 0.3972 0.8988 +vn 0.2486 0.1936 0.9491 +vn 0.4271 0.0894 0.8998 +vn 0.3717 -0.1692 0.9128 +vn 0.2792 -0.3456 0.8959 +vn 0.0385 -0.2859 0.9575 +vn -0.0625 -0.4096 0.9101 +vn -0.2704 -0.1953 0.9427 +vn -0.3174 -0.3403 0.8851 +vn 0.0173 -0.0138 -0.9998 +vn 0.0159 -0.0342 -0.9993 +vn 0.0220 -0.0299 -0.9993 +vn 0.0229 0.0156 -0.9996 +vn 0.0165 -0.0193 -0.9997 +vn -0.0179 0.0154 -0.9997 +vn -0.0212 -0.0114 -0.9997 +vn -0.0293 0.0106 -0.9995 +vn -0.0114 -0.0207 -0.9997 +vn -0.0038 -0.0259 -0.9997 +vn -0.0241 -0.0329 -0.9992 +vn 0.0137 0.0193 -0.9997 +vn 0.0089 0.0232 -0.9997 +vn 0.0309 0.0285 -0.9991 +vn -0.0154 0.0334 -0.9993 +vn -0.0171 0.0228 -0.9996 +vn 0.0285 -0.0345 0.9990 +vn 0.0343 -0.0320 0.9989 +vn 0.0796 -0.0457 0.9958 +vn 0.0410 -0.0328 0.9986 +vn 0.1156 -0.0587 0.9916 +vn 0.1696 -0.9855 -0.0064 +vn 0.1109 -0.9938 0.0054 +vn 0.1618 -0.9868 -0.0049 +vn 0.1010 -0.9949 0.0074 +vn -0.7902 -0.6127 -0.0152 +vn -0.6685 -0.7434 0.0200 +vn -0.6894 -0.7242 0.0144 +vn -0.8058 -0.5919 -0.0203 +vn -0.8484 0.5287 -0.0254 +vn -0.9674 0.2513 0.0295 +vn -0.9551 0.2957 0.0201 +vn -0.8241 0.5655 -0.0325 +vn -0.3750 0.9266 0.0284 +vn -0.3736 0.9228 0.0940 +vn -0.3707 0.9154 0.1567 +vn 0.1437 0.9893 -0.0242 +vn 0.5686 0.8223 0.0227 +vn 0.5175 0.8557 -0.0096 +vn 0.7946 0.6067 0.0210 +vn 0.8100 0.5865 0.0024 +vn 0.9294 0.3689 0.0142 +vn 0.9741 -0.2252 -0.0208 +vn 0.8934 -0.4489 0.0205 +vn 0.9660 -0.2582 -0.0149 +vn 0.8767 -0.4803 0.0266 +vn 0.5575 -0.4827 0.6754 +vn 0.4507 -0.4802 0.7525 +vn 0.2552 -0.6661 0.7008 +vn -0.2445 -0.6160 0.7488 +vn -0.0558 -0.7169 0.6950 +vn -0.4519 -0.5479 0.7040 +vn -0.6564 -0.0210 0.7541 +vn -0.6803 -0.2609 0.6850 +vn -0.7202 0.1177 0.6837 +vn -0.5747 0.4137 0.7061 +vn -0.2544 0.6174 0.7444 +vn -0.2859 0.6672 0.6878 +vn 0.1779 0.7043 0.6872 +vn 0.3523 0.5888 0.7275 +vn 0.5418 0.4837 0.6874 +vn 0.6699 0.1465 0.7278 +vn 0.7163 0.1265 0.6862 +vn 0.6857 -0.2100 0.6969 +vn 0.9579 0.2872 0.0000 +vn 0.9726 0.2021 -0.1152 +vn 0.9698 0.2323 -0.0748 +vn 0.9719 0.1515 -0.1801 +vn -0.2518 0.9509 0.1801 +vn -0.1765 0.9815 0.0746 +vn -0.2057 0.9718 0.1152 +vn -0.1219 0.9925 0.0000 +vn -0.9579 -0.2872 0.0000 +vn -0.9726 -0.2020 -0.1154 +vn -0.9697 -0.2326 -0.0748 +vn -0.9719 -0.1513 -0.1804 +vn 0.2518 -0.9509 0.1802 +vn 0.1765 -0.9815 0.0747 +vn 0.2057 -0.9718 0.1153 +vn 0.1219 -0.9925 0.0000 +vn -0.4014 -0.2981 0.8660 +vn -0.9668 0.2513 0.0473 +vn -0.3120 0.3326 0.8900 +vn -0.3354 0.8268 0.4515 +vn 0.2385 0.4983 0.8336 +vn 0.3874 -0.1141 0.9148 +vn 0.5012 -0.0015 0.8654 +vn 0.5029 -0.0005 0.8643 +vn 0.5120 0.0067 0.8590 +vn 0.5116 0.0085 0.8592 +vn 0.7012 0.0146 0.7128 +vn -0.4842 0.0091 0.8749 +vn -0.4896 0.0075 0.8719 +vn -0.5117 0.0009 0.8591 +vn -0.5176 -0.0008 0.8556 +vn 0.0056 -1.0000 -0.0028 +vn 0.0148 -0.9998 0.0163 +vn 0.0938 -0.9838 0.1525 +vn 0.0110 -0.9999 0.0057 +vn 0.0034 -1.0000 0.0060 +vn 0.0092 -0.9998 -0.0202 +vn 0.0896 -0.9615 -0.2599 +vn -0.1932 -0.9722 0.1325 +vn 0.1302 -0.9001 0.4157 +vn -0.0029 -1.0000 -0.0001 +vn 0.0247 -0.9451 -0.3257 +vn -0.1734 -0.9700 -0.1703 +vn 0.7890 0.0081 0.6143 +vn 0.2465 -0.2153 0.9449 +vn 0.6397 -0.2560 0.7248 +vn 0.8045 0.0068 0.5940 +vn 0.8205 -0.0484 0.5696 +vn 0.9541 -0.2252 0.1976 +vn 0.8073 -0.0058 0.5901 +vn 0.8084 0.0143 0.5885 +vn 0.8093 0.0168 0.5872 +vn 0.3518 -0.3106 -0.8831 +vn 0.4529 -0.0081 -0.8915 +vn 0.5770 -0.0093 -0.8167 +vn 0.4755 -0.0121 -0.8796 +vn 0.1625 -0.0186 -0.9865 +vn 0.2121 -0.2540 -0.9437 +vn 0.1104 -0.0105 -0.9938 +vn -0.1329 -0.0376 -0.9904 +vn 0.2772 -0.2734 -0.9211 +vn -0.1269 -0.0062 -0.9919 +vn -0.2171 -0.0002 -0.9761 +vn -0.2938 -0.0409 -0.9550 +vn -0.4752 0.0794 -0.8763 +vn -0.7257 -0.0041 -0.6880 +vn -0.7433 -0.0317 -0.6682 +vn -0.9067 0.0057 -0.4217 +vn -0.9366 -0.0101 -0.3502 +vn -0.9961 0.0077 -0.0881 +vn -0.9999 -0.0092 0.0127 +vn -0.9820 0.0071 0.1887 +vn -0.9415 -0.0083 0.3368 +vn -0.8976 0.0074 0.4408 +vn -0.8160 -0.0071 0.5781 +vn -0.7327 0.0084 0.6805 +vn -0.6349 -0.0080 0.7726 +vn -0.5001 0.0087 0.8659 +vn -0.3753 -0.0106 0.9269 +vn -0.2246 0.0093 0.9744 +vn -0.0277 -0.0093 0.9996 +vn 0.0699 0.0066 0.9975 +vn 0.2976 -0.0046 0.9547 +vn 0.3267 0.0020 0.9451 +vn 0.5461 -0.0021 0.8377 +vn 0.5636 0.0023 0.8260 +vn 0.7567 -0.0024 0.6537 +vn 0.7651 0.0008 0.6440 +vn 0.8214 0.0381 -0.5691 +vn 0.7554 -0.2433 -0.6084 +vn 0.7310 0.0421 -0.6811 +vn 0.4633 -0.2000 -0.8633 +vn 0.9878 -0.0052 -0.1557 +vn 0.9962 0.0122 -0.0861 +vn 0.9509 -0.0122 0.3093 +vn 0.9264 0.0076 0.3766 +vn 0.9413 0.0098 -0.3375 +vn 0.9405 0.0069 -0.3398 +vn 0.8382 -0.0073 0.5453 +vn 0.8376 -0.0048 0.5463 +vn 0.8419 0.0025 0.5397 +vn 0.8394 0.0049 0.5434 +vn -0.0027 0.0023 -1.0000 +vn 0.2587 0.0021 -0.9660 +vn 0.2996 -0.0011 -0.9541 +vn 0.3284 -0.0143 -0.9444 +vn 0.0036 0.0026 -1.0000 +vn 0.0079 0.0049 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.6756 0.0005 -0.7373 +vn 0.6476 0.0068 -0.7619 +vn 0.8834 0.0119 -0.4685 +vn 0.8712 -0.0144 -0.4906 +vn 0.9880 -0.0049 -0.1542 +vn 0.9974 0.0128 -0.0704 +vn 0.9635 -0.0106 0.2675 +vn 0.9493 0.0186 0.3138 +vn 0.8218 -0.0019 0.5697 +vn 0.5917 -0.0028 0.8061 +vn 0.5168 0.0027 -0.8561 +vn 0.5185 -0.0020 -0.8551 +vn 0.6239 0.0023 0.7815 +vn 0.6281 -0.0047 0.7781 +vn 0.8510 0.0047 0.5252 +vn 0.8666 -0.0060 0.4990 +vn 0.9933 0.0066 0.1149 +vn 0.9968 -0.0109 0.0795 +vn 0.9495 0.0134 -0.3135 +vn 0.9175 -0.0154 -0.3974 +vn 0.6963 -0.0024 -0.7178 +vn 0.6541 -0.0197 -0.7561 +vn 0.5750 -0.0023 -0.8181 +vn 0.5152 -0.0030 -0.8571 +vn 0.5118 0.0014 -0.8591 +vn 0.5131 -0.0086 0.8583 +vn -0.9933 -0.0214 0.1136 +vn -0.9466 0.0282 0.3211 +vn -0.9810 0.0241 -0.1923 +vn -0.8411 -0.0153 0.5407 +vn -0.5907 0.0111 0.8068 +vn -0.4970 -0.0064 0.8677 +vn -0.2922 0.0054 0.9563 +vn -0.3139 -0.0122 0.9494 +vn 0.2548 0.0286 0.9666 +vn 0.3053 -0.0049 0.9522 +vn 0.5378 0.0086 0.8430 +vn 0.5625 -0.0150 0.8267 +vn 0.8490 -0.0038 0.5284 +vn 0.8756 0.0113 0.4829 +vn 0.9892 -0.0162 0.1455 +vn 0.9989 0.0136 0.0447 +vn 0.9311 -0.0179 -0.3644 +vn 0.8866 0.0123 -0.4624 +vn 0.6004 -0.0194 -0.7995 +vn 0.6026 0.0070 -0.7980 +vn 0.2132 0.0123 -0.9769 +vn 0.0619 -0.0292 -0.9977 +vn -0.2788 0.0218 -0.9601 +vn -0.5440 -0.0327 -0.8385 +vn -0.7418 0.0262 -0.6702 +vn -0.9199 -0.0275 -0.3911 +vn 0.9606 0.0108 -0.2776 +vn 0.9839 -0.0201 -0.1778 +vn 0.8807 -0.0095 -0.4736 +vn 0.8636 0.0116 -0.5040 +vn 0.4350 0.0187 -0.9002 +vn 0.4803 -0.0115 -0.8770 +vn 0.2352 -0.0195 -0.9718 +vn 0.0797 0.0282 -0.9964 +vn -0.3718 -0.0247 -0.9280 +vn -0.5713 0.0376 -0.8199 +vn -0.8282 -0.0251 -0.5599 +vn -0.9534 0.0288 -0.3003 +vn -0.9972 -0.0240 -0.0711 +vn -0.9678 0.0234 0.2506 +vn -0.9134 -0.0228 0.4065 +vn -0.7228 0.0229 0.6907 +vn -0.5654 -0.0260 0.8244 +vn -0.2467 0.0289 0.9687 +vn -0.0414 -0.0274 0.9988 +vn 0.3455 0.0288 0.9380 +vn 0.5403 -0.0288 0.8410 +vn 0.8110 0.0225 0.5847 +vn 0.9223 -0.0298 0.3853 +vn 0.9848 0.0149 0.1729 +vn 0.7229 -0.0199 -0.6907 +vn 0.9267 0.0159 -0.3754 +vn 0.7414 -0.0175 -0.6708 +vn 0.9372 0.0186 -0.3483 +vn 0.9949 -0.0082 -0.1006 +vn 0.9995 0.0055 0.0321 +vn 0.9958 -0.0072 -0.0909 +vn 0.9991 0.0064 0.0414 +vn 0.3959 0.0413 -0.9173 +vn 0.3996 0.0351 -0.9160 +vn 0.4799 -0.0024 -0.8773 +vn 0.2143 0.0264 -0.9764 +vn 0.2582 0.2244 -0.9397 +vn 0.0661 0.0042 -0.9978 +vn -0.0738 0.0123 -0.9972 +vn -0.0941 -0.0027 -0.9956 +vn -0.0405 0.2935 -0.9551 +vn 0.1776 -0.0031 -0.9841 +vn -0.8076 0.0149 -0.5896 +vn -0.7438 0.0017 -0.6684 +vn -0.9252 0.0016 -0.3794 +vn -0.8371 0.0233 -0.5465 +vn -0.8519 -0.0035 -0.5236 +vn -0.9355 0.0076 -0.3531 +vn -0.9817 0.0211 -0.1892 +vn -0.9928 0.0013 -0.1194 +vn -0.9999 0.0100 -0.0095 +vn -0.9997 0.0137 -0.0183 +vn -0.8440 0.0013 -0.5364 +vn -0.7899 0.2308 -0.5681 +vn -0.8415 0.0021 -0.5403 +vn -0.5021 0.2631 -0.8238 +vn -0.1284 0.0027 -0.9917 +vn -0.1287 0.0026 -0.9917 +vn -0.1501 0.2340 -0.9606 +vn 0.4022 0.1581 -0.9018 +vn 0.8109 -0.0108 -0.5851 +vn 0.8821 0.3322 -0.3338 +vn 0.9759 -0.0068 -0.2180 +vn 0.9325 0.1584 0.3247 +vn 0.6348 0.3632 0.6819 +vn 0.8053 -0.0009 0.5929 +vn 0.7961 0.0136 0.6050 +vn 0.5620 0.0318 0.8265 +vn 0.0082 -0.0026 1.0000 +vn 0.0065 0.0041 1.0000 +vn 0.0004 0.0286 0.9996 +vn 0.0037 0.0980 0.9952 +vn 0.0027 0.0549 0.9985 +vn -0.6577 0.0019 0.7533 +vn -0.6272 -0.0061 0.7788 +vn -0.6545 0.0010 0.7561 +vn -0.6225 -0.0073 0.7826 +vn -0.9988 -0.0123 0.0467 +vn -0.7964 0.3630 0.4837 +vn -0.9963 0.0859 -0.0000 +vn -0.1952 0.9654 -0.1730 +vn -0.1827 0.9568 0.2261 +vn 0.1286 0.9642 0.2320 +vn -0.0102 0.9999 -0.0014 +vn -0.0136 0.9716 -0.2362 +vn -0.0000 1.0000 -0.0071 +vn 0.0260 0.9835 -0.1793 +vn -0.1530 0.9880 -0.0220 +vn 0.9873 0.0004 -0.1588 +vn 0.9852 -0.0086 -0.1713 +vn 0.9860 -0.0052 -0.1665 +vn 0.9836 -0.0147 -0.1796 +vn 0.5513 -0.0297 0.8338 +vn 0.8510 0.0322 0.5242 +vn 0.5321 0.0213 0.8464 +vn 0.4641 -0.0321 0.8852 +vn 0.1132 0.0171 0.9934 +vn -0.5164 -0.0011 0.8564 +vn -0.5051 -0.0080 0.8630 +vn -0.5111 -0.0043 0.8595 +vn -0.5001 -0.0110 0.8659 +vn -0.9945 -0.0050 0.1045 +vn -0.9860 0.0058 0.1665 +vn -0.9874 0.0044 0.1583 +vn -0.9953 -0.0064 0.0966 +vn -0.8417 0.0036 -0.5399 +vn -0.8379 -0.0000 -0.5458 +vn -0.8336 -0.0042 -0.5524 +vn -0.8298 -0.0078 -0.5581 +vn -0.1679 -0.0070 -0.9858 +vn -0.2937 0.0145 -0.9558 +vn -0.2786 0.0119 -0.9603 +vn -0.1504 -0.0100 -0.9886 +vn 0.5707 -0.0044 -0.8211 +vn 0.6294 0.0093 -0.7770 +vn 0.5791 -0.0025 -0.8152 +vn 0.6365 0.0110 -0.7712 +vn -0.9981 0.0053 -0.0620 +vn -0.9704 -0.0060 -0.2416 +vn -0.9977 0.0076 -0.0672 +vn -0.9650 -0.1628 -0.2058 +vn -0.8351 -0.4071 -0.3700 +vn -0.8195 -0.2710 -0.5049 +vn -0.8169 -0.0145 -0.5766 +vn -0.7354 -0.0026 -0.6776 +vn -0.8071 -0.0078 -0.5903 +vn -0.8986 0.0007 -0.4389 +vn -0.9636 -0.2289 -0.1381 +vn -0.9959 0.0133 -0.0897 +vn -0.9156 -0.2036 0.3467 +vn -0.6470 0.0087 0.7625 +vn -0.6394 -0.2878 0.7130 +vn -0.3329 0.0023 0.9430 +vn -0.1983 -0.0112 0.9801 +vn 0.0045 0.0024 -1.0000 +vn 0.0814 -0.0808 0.9934 +vn 0.0022 0.0000 -1.0000 +vn 0.0030 0.0082 1.0000 +vn 0.1510 -0.3607 0.9204 +vn 0.0010 0.1837 0.9830 +vn 0.0947 0.3672 0.9253 +vn 0.5108 -0.0135 0.8596 +vn -0.3156 -0.0026 -0.9489 +vn 0.0175 -0.3541 -0.9350 +vn -0.3028 0.0003 -0.9530 +vn -0.1926 -0.0864 -0.9775 +vn -0.8002 -0.0310 -0.5990 +vn -0.7460 -0.2440 -0.6197 +vn -0.7704 -0.2106 -0.6018 +vn 0.9852 0.0049 -0.1715 +vn 0.9836 0.0007 -0.1802 +vn 0.9846 0.0032 -0.1750 +vn 0.9830 -0.0011 -0.1838 +vn 0.2595 0.0033 -0.9657 +vn 0.2356 -0.0013 -0.9718 +vn 0.2564 0.0027 -0.9666 +vn 0.2324 -0.0019 -0.9726 +vn -0.8190 -0.0007 -0.5739 +vn -0.8194 -0.0004 -0.5732 +vn -0.8209 0.0004 -0.5711 +vn -0.8214 0.0007 -0.5704 +vn 0.5325 0.0205 0.8462 +vn 0.1249 -0.0130 0.9921 +vn 0.5117 -0.0129 0.8590 +vn 0.5812 0.0199 0.8135 +vn 0.8136 -0.0150 0.5812 +vn 0.9324 -0.2883 -0.2182 +vn 0.9583 0.0049 -0.2856 +vn 0.9950 -0.0573 0.0819 +vn 0.7205 -0.2785 -0.6351 +vn 0.8090 0.0035 -0.5878 +vn 0.9994 -0.0227 -0.0255 +vn 0.9509 -0.2778 -0.1364 +vn 0.9608 -0.0126 -0.2769 +vn 0.9622 -0.2217 -0.1579 +vn 0.7008 -0.2527 -0.6671 +vn 0.6845 0.0036 -0.7290 +vn 0.6066 -0.0318 -0.7944 +vn 0.6380 -0.3485 -0.6867 +vn -0.0104 -0.9958 -0.0909 +vn 0.0030 -0.9999 -0.0099 +vn 0.0039 -0.9514 -0.3079 +vn 0.0339 -0.9988 -0.0345 +vn 0.7694 -0.2511 0.5874 +vn 0.7881 -0.0553 0.6130 +vn 0.5712 -0.1930 0.7978 +vn 0.6994 0.0097 0.7146 +vn 0.0140 0.0094 0.9999 +vn 0.0966 -0.2468 0.9642 +vn 0.0693 -0.0115 0.9975 +vn 0.1463 -0.2120 0.9663 +vn -0.5349 -0.0551 0.8431 +vn -0.3123 -0.2884 0.9051 +vn -0.5487 -0.0307 0.8355 +vn -0.5472 -0.2058 0.8113 +vn 0.1770 -0.9248 0.3368 +vn -0.0092 -0.7649 0.6441 +vn -0.0175 -0.9982 0.0569 +vn 0.2806 0.0505 0.9585 +vn 0.9209 0.0168 -0.3895 +vn -0.5137 0.7719 0.3745 +vn -0.4622 0.8582 -0.2232 +vn -0.7985 0.5951 0.0907 +vn -0.1880 0.6508 0.7356 +vn -0.8106 0.5394 -0.2279 +vn -0.6490 0.6459 -0.4020 +vn -0.4848 0.5183 0.7045 +vn -0.8087 0.5086 -0.2956 +vn -0.7044 0.6698 -0.2350 +vn -0.7979 0.5992 -0.0656 +vn -0.6303 0.5322 -0.5653 +vn -0.5280 0.7117 -0.4634 +vn -0.6609 0.5988 -0.4524 +vn -0.5923 0.7264 -0.3487 +vn -0.6517 0.7385 -0.1728 +vn -0.7891 0.6141 -0.0110 +vn -0.7802 0.6254 -0.0154 +vn -0.2852 0.9533 -0.0996 +vn -0.9897 -0.1429 -0.0024 +vn -0.2878 0.9569 -0.0398 +vn 0.2574 0.7700 0.5839 +vn -0.4478 0.6431 -0.6212 +vn -0.2459 0.6194 -0.7456 +vn -0.2257 0.7885 -0.5722 +vn 0.1374 0.6706 -0.7289 +vn 0.0772 0.5424 -0.8366 +vn 0.0461 0.6519 -0.7569 +vn -0.0657 0.5446 -0.8361 +vn 0.3593 0.5663 -0.7418 +vn 0.3330 0.7480 -0.5741 +vn 0.2734 0.7353 -0.6201 +vn -0.1022 0.7383 -0.6667 +vn -0.0601 0.6927 -0.7187 +vn 0.2931 0.8292 -0.4759 +vn 0.1378 0.8209 -0.5542 +vn 0.7771 0.5724 0.2618 +vn 0.3367 0.9102 0.2413 +vn 0.6072 0.5683 -0.5553 +vn 0.5773 0.6779 -0.4552 +vn 0.6479 0.7056 -0.2869 +vn 0.4715 0.8041 -0.3621 +vn -0.1869 -0.6606 0.7271 +vn -0.3336 -0.7913 0.5124 +vn -0.6890 -0.5956 -0.4130 +vn -0.6787 -0.5929 -0.4335 +vn -0.7350 -0.6678 0.1174 +vn -0.3266 -0.9416 -0.0823 +vn 0.4636 -0.6386 0.6142 +vn -0.8895 -0.4560 -0.0296 +vn -0.7826 -0.6135 -0.1062 +vn -0.7178 -0.6291 -0.2983 +vn -0.6049 -0.6806 -0.4134 +vn -0.6423 -0.5029 -0.5784 +vn -0.7726 -0.6168 -0.1504 +vn -0.6360 -0.7266 -0.2599 +vn -0.4062 -0.8462 -0.3449 +vn -0.1231 -0.9922 0.0199 +vn -0.8517 -0.4861 -0.1956 +vn 0.1994 -0.8543 0.4800 +vn 0.7273 -0.4009 0.5571 +vn 0.1200 -0.7563 -0.6431 +vn -0.3144 -0.5918 -0.7423 +vn 0.0879 -0.4041 0.9105 +vn -0.3925 -0.4870 0.7803 +vn 0.0855 -0.7906 0.6064 +vn 0.1202 -0.7584 0.6407 +vn 0.2795 -0.5197 0.8073 +vn 0.2298 -0.7557 -0.6133 +vn 0.2839 -0.6954 -0.6602 +vn 0.1041 -0.7092 -0.6973 +vn 0.3881 -0.8605 -0.3300 +vn -0.3941 -0.7433 0.5405 +vn -0.1511 -0.8172 0.5562 +vn -0.2536 -0.6493 0.7169 +vn 0.6101 -0.7428 -0.2757 +vn 0.7227 -0.6435 -0.2522 +vn 0.0602 -0.5595 0.8267 +vn 0.4746 -0.8522 -0.2204 +vn 0.6851 -0.6990 0.2052 +vn 0.6725 -0.5335 0.5130 +vn 0.5747 -0.6930 0.4353 +vn 0.6462 -0.7292 0.2253 +vn 0.4367 -0.8358 0.3328 +vn 0.2958 -0.8796 -0.3726 +vn 0.6015 -0.7246 -0.3364 +vn 0.2690 -0.7123 0.6482 +vn 0.5440 -0.6784 0.4939 +vn 0.6878 -0.6646 0.2920 +vn 0.4175 -0.8550 0.3078 +vn 0.4950 -0.8688 -0.0142 +vn 0.4201 -0.8534 0.3087 +vn 0.5036 -0.6225 -0.5991 +vn 0.7233 -0.6441 -0.2489 +vn 0.5132 -0.7813 -0.3553 +vn -0.0599 -0.9308 -0.3605 +vn -0.1250 -0.7098 -0.6932 +vn -0.1174 -0.7146 -0.6896 +vn -0.1389 -0.5754 -0.8060 +vn -0.0225 -0.7217 -0.6919 +vn -0.0791 -0.5915 -0.8024 +vn 0.9565 0.0149 -0.2914 +vn 0.9383 -0.0039 -0.3459 +vn 0.9520 0.0099 -0.3060 +vn 0.9327 -0.0090 -0.3606 +vn 0.9527 0.0199 -0.3033 +vn 0.9418 -0.0038 -0.3361 +vn 0.9459 0.0047 -0.3244 +vn 0.9341 -0.0187 -0.3565 +vn -0.9809 0.0006 0.1943 +vn -0.9800 -0.0006 0.1992 +vn -0.9808 0.0004 0.1952 +vn -0.9798 -0.0008 0.2001 +vn -0.9244 0.0106 0.3813 +vn -0.8612 -0.0607 0.5046 +vn -0.8934 -0.0276 0.4485 +vn -0.8275 -0.0911 0.5541 +vn -0.8102 0.0024 -0.5862 +vn -0.8108 0.0008 -0.5853 +vn -0.8087 0.0011 -0.5882 +vn -0.8115 0.0047 -0.5844 +vn 0.0323 0.0074 -0.9995 +vn 0.0239 -0.0064 -0.9997 +vn 0.0228 -0.0109 -0.9997 +vn -0.0256 -0.0122 -0.9996 +vn -0.0355 -0.0078 -0.9993 +vn -0.0195 0.0118 -0.9997 +vn -0.0113 -0.0172 -0.9998 +vn 0.0020 -0.0264 -0.9997 +vn -0.0176 0.0089 -0.9998 +vn 0.0196 -0.0325 -0.9993 +vn -0.0081 0.0320 -0.9995 +vn 0.0110 0.0195 -0.9997 +vn 0.0137 0.0138 -0.9998 +vn -0.0062 0.0325 -0.9995 +vn -0.0106 0.0066 0.9999 +vn -0.0946 -0.0802 0.9923 +vn -0.0059 0.0112 0.9999 +vn -0.0920 -0.0728 0.9931 +vn 0.0639 0.1083 0.9921 +vn 0.0621 0.1006 0.9930 +vn 0.7245 -0.6886 -0.0308 +vn 0.3674 -0.9297 0.0273 +vn 0.6826 -0.7304 -0.0230 +vn 0.3106 -0.9499 0.0352 +vn -0.2467 -0.9691 -0.0093 +vn -0.3027 -0.9531 -0.0014 +vn -0.2517 -0.9678 -0.0086 +vn -0.3123 -0.9500 -0.0001 +vn -0.9353 -0.3540 0.0017 +vn -0.9234 -0.3837 0.0066 +vn -0.9250 -0.3798 0.0060 +vn -0.9365 -0.3506 0.0012 +vn -0.9140 0.4055 0.0152 +vn -0.9242 0.3817 0.0103 +vn -0.9152 0.4028 0.0146 +vn -0.9254 0.3788 0.0098 +vn -0.2524 0.9676 -0.0017 +vn -0.4571 0.8891 0.0254 +vn -0.2069 0.9781 0.0211 +vn 0.1767 0.9842 -0.0090 +vn 0.4955 0.8684 0.0177 +vn 0.8274 0.5616 -0.0089 +vn 0.9644 0.2633 0.0251 +vn 0.9828 0.1844 0.0003 +vn 0.9952 -0.0922 0.0337 +vn 0.6814 -0.2532 0.6868 +vn 0.6586 -0.1850 0.7294 +vn 0.3661 -0.6169 0.6967 +vn 0.1882 -0.6441 0.7414 +vn -0.1396 -0.7172 0.6828 +vn -0.4665 -0.5039 0.7269 +vn -0.5635 -0.4500 0.6928 +vn -0.6981 0.0137 0.7158 +vn -0.7184 -0.0030 0.6956 +vn -0.6418 0.3445 0.6852 +vn -0.4359 0.5329 0.7253 +vn -0.3678 0.6145 0.6980 +vn 0.1150 0.6838 0.7205 +vn 0.0273 0.7186 0.6949 +vn 0.4474 0.5729 0.6867 +vn 0.5674 0.3897 0.7254 +vn 0.6985 0.2026 0.6863 +vn 0.9697 0.2328 -0.0746 +vn 0.9719 0.1512 -0.1804 +vn -0.2057 0.9718 0.1155 +vn -0.9726 -0.2021 -0.1151 +vn 0.2912 -0.6146 0.7332 +vn -0.2746 -0.2522 0.9279 +vn 0.2044 0.3375 0.9189 +vn 0.7934 -0.1361 0.5932 +vn 0.0171 -0.0142 -0.9998 +vn 0.0252 0.0057 -0.9997 +vn 0.0310 -0.0133 -0.9994 +vn -0.0217 0.0120 -0.9997 +vn -0.0048 0.0235 -0.9997 +vn -0.0213 0.0074 -0.9997 +vn -0.0074 -0.0213 -0.9997 +vn 0.0041 -0.0230 -0.9997 +vn -0.0333 -0.0080 -0.9994 +vn -0.0430 -0.0088 -0.9990 +vn -0.0302 -0.0136 -0.9995 +vn 0.0102 0.0238 -0.9997 +vn 0.0034 0.0293 -0.9996 +vn 0.0188 0.0297 -0.9994 +vn -0.0094 -0.0208 -0.9997 +vn 0.0013 -0.0300 -0.9995 +vn 0.1044 -0.1442 0.9840 +vn 0.1543 -0.0485 0.9868 +vn -0.0716 -0.0562 0.9958 +vn -0.0424 0.0935 0.9947 +vn -0.0608 -0.0192 0.9980 +vn 0.0409 0.1427 0.9889 +vn 0.3024 -0.9531 -0.0059 +vn 0.5188 -0.8546 0.0203 +vn 0.2300 -0.9730 0.0212 +vn 0.2553 -0.9668 -0.0057 +vn -0.0405 -0.9989 0.0244 +vn -0.5942 -0.8043 0.0003 +vn -0.5965 -0.8026 0.0009 +vn -0.5947 -0.8040 0.0005 +vn -0.5968 -0.8024 0.0009 +vn -0.9825 0.1857 -0.0122 +vn -0.9976 -0.0672 0.0147 +vn -0.9821 0.1881 0.0128 +vn -0.9748 0.2227 -0.0118 +vn -0.9151 0.4029 0.0151 +vn -0.2713 0.9624 -0.0114 +vn -0.4114 0.9113 0.0149 +vn -0.3932 0.9194 0.0114 +vn -0.2540 0.9671 -0.0145 +vn 0.6048 0.7963 -0.0032 +vn 0.5296 0.8475 0.0346 +vn 0.5390 0.8418 0.0288 +vn 0.6162 0.7876 -0.0058 +vn 0.9924 -0.1230 -0.0090 +vn 0.9975 -0.0636 0.0298 +vn 0.9968 -0.0718 0.0347 +vn 0.9911 -0.1324 -0.0110 +vn 0.6615 -0.2600 0.7035 +vn 0.5150 -0.4330 0.7398 +vn 0.3693 -0.6254 0.6874 +vn 0.0676 -0.7070 0.7039 +vn -0.1302 -0.6671 0.7335 +vn -0.2839 -0.6553 0.7000 +vn -0.6137 -0.2513 0.7485 +vn -0.5003 -0.5079 0.7013 +vn -0.7027 -0.1954 0.6842 +vn -0.6956 0.1301 0.7065 +vn -0.4739 0.4699 0.7447 +vn -0.6087 0.4006 0.6848 +vn -0.3470 0.6375 0.6879 +vn 0.0010 0.7172 0.6968 +vn 0.1311 0.6704 0.7303 +vn 0.4748 0.5512 0.6861 +vn 0.6337 0.2417 0.7349 +vn 0.7053 0.1232 0.6982 +vn 0.9726 0.2019 -0.1154 +vn 0.9697 0.2325 -0.0748 +vn 0.9719 0.1513 -0.1803 +vn -0.9726 -0.2021 -0.1149 +vn 0.3683 -0.3290 0.8696 +vn -0.4044 -0.2292 0.8854 +vn -0.0798 0.4505 0.8892 +vn 0.5256 0.8415 0.1251 +vn 0.4040 0.1959 0.8935 +vn 0.9817 -0.0627 0.1797 +vn 0.0312 0.0121 -0.9994 +vn 0.0307 0.0005 -0.9995 +vn 0.0206 -0.0095 -0.9997 +vn -0.0213 0.0113 -0.9997 +vn -0.0260 -0.0066 -0.9996 +vn -0.0370 0.0098 -0.9993 +vn -0.0167 0.0171 -0.9997 +vn 0.0002 0.0270 -0.9996 +vn -0.0079 -0.0234 -0.9997 +vn -0.0125 -0.0293 -0.9995 +vn 0.0110 -0.0205 -0.9997 +vn -0.0003 -0.0311 -0.9995 +vn 0.0150 0.0205 -0.9997 +vn 0.0198 0.0244 -0.9995 +vn 0.1706 0.0968 0.9806 +vn -0.0388 0.0013 0.9992 +vn 0.1392 0.0477 0.9891 +vn -0.0604 -0.0081 0.9981 +vn -0.0262 -0.0301 0.9992 +vn 0.0135 -0.0692 0.9975 +vn 0.7738 -0.6333 -0.0131 +vn 0.8881 -0.4592 0.0220 +vn 0.7500 -0.6612 -0.0193 +vn -0.2652 -0.9641 -0.0124 +vn -0.0251 -0.9994 0.0218 +vn -0.3611 -0.9323 0.0219 +vn -0.3278 -0.9447 -0.0129 +vn -0.6395 -0.7683 0.0262 +vn -0.9927 -0.1202 -0.0080 +vn -0.9975 -0.0705 0.0011 +vn -0.9935 -0.1137 -0.0068 +vn -0.9981 -0.0617 0.0028 +vn -0.6021 0.7984 -0.0106 +vn -0.6698 0.7394 0.0692 +vn -0.6621 0.7467 0.0641 +vn -0.5931 0.8050 -0.0126 +vn 0.3115 0.9501 -0.0148 +vn 0.1384 0.9872 0.0796 +vn 0.1566 0.9784 0.1350 +vn 0.3350 0.9420 -0.0189 +vn 0.9769 0.2134 -0.0035 +vn 0.9152 0.4023 0.0246 +vn 0.9267 0.3754 0.0205 +vn 0.9821 0.1881 -0.0071 +vn 0.9030 -0.4288 0.0277 +vn 0.4692 -0.5562 0.6859 +vn 0.1778 -0.6451 0.7431 +vn -0.0188 -0.7151 0.6988 +vn -0.5114 -0.4261 0.7463 +vn -0.3918 -0.5936 0.7030 +vn -0.6857 -0.2298 0.6907 +vn -0.6199 0.2636 0.7391 +vn -0.6926 0.1972 0.6938 +vn -0.4546 0.5659 0.6878 +vn -0.0955 0.6750 0.7316 +vn -0.0768 0.7210 0.6887 +vn 0.3827 0.6138 0.6905 +vn 0.5134 0.4388 0.7375 +vn 0.6866 0.2338 0.6884 +vn 0.6582 -0.1792 0.7312 +vn 0.7027 -0.1586 0.6936 +vn 0.9201 0.2757 -0.2783 +vn 0.9225 0.3073 -0.2337 +vn 0.9219 0.2961 -0.2498 +vn 0.9226 0.3223 -0.2118 +vn -0.2475 0.9348 0.2547 +vn -0.6824 0.5880 -0.4343 +vn -0.9252 -0.2774 0.2591 +vn -0.1725 -0.9091 -0.3793 +vn 0.0475 -0.8113 0.5827 +vn -0.4791 0.0681 0.8751 +vn -0.6378 0.7041 0.3124 +vn -0.0796 0.5064 0.8586 +vn 0.1230 0.8839 0.4511 +vn 0.4558 0.3116 0.8338 +vn 0.4768 -0.3209 0.8184 +vn 0.0249 -0.0129 -0.9996 +vn 0.0298 -0.0226 -0.9993 +vn 0.0113 -0.0243 -0.9996 +vn 0.0248 0.0123 -0.9996 +vn 0.0368 -0.0090 -0.9993 +vn -0.0223 0.0067 -0.9997 +vn -0.0331 -0.0124 -0.9994 +vn -0.0263 0.0006 -0.9997 +vn 0.0119 0.0185 -0.9998 +vn 0.0012 0.0240 -0.9997 +vn 0.0180 0.0284 -0.9994 +vn -0.0137 -0.0180 -0.9997 +vn -0.0334 -0.0100 -0.9994 +vn -0.0155 -0.0162 -0.9997 +vn -0.0174 0.0232 -0.9996 +vn 0.0104 -0.0334 0.9994 +vn 0.0802 -0.0709 0.9942 +vn 0.1315 -0.0783 0.9882 +vn -0.0764 -0.0111 0.9970 +vn -0.0868 -0.0397 0.9954 +vn -0.0261 -0.1442 0.9892 +vn 0.5860 -0.8100 -0.0216 +vn 0.3672 -0.9300 0.0133 +vn 0.0377 -0.9990 -0.0233 +vn 0.0825 -0.9962 0.0279 +vn -0.5381 -0.8423 0.0302 +vn -0.5687 -0.8223 -0.0211 +vn -0.8584 -0.5121 0.0299 +vn -0.9742 0.2248 -0.0201 +vn -0.9389 0.3441 0.0008 +vn -0.9711 0.2380 -0.0179 +vn -0.9325 0.3611 0.0039 +vn -0.3427 0.9394 -0.0056 +vn -0.4405 0.8970 0.0363 +vn -0.4274 0.9031 0.0407 +vn -0.3273 0.9449 -0.0089 +vn 0.7004 0.7138 -0.0032 +vn 0.5941 0.8042 0.0178 +vn 0.8257 0.5637 0.0218 +vn 0.9460 0.3241 -0.0032 +vn 0.9992 -0.0319 0.0234 +vn 0.9902 -0.1396 -0.0008 +vn 0.9261 -0.3767 0.0192 +vn 0.5107 -0.5112 0.6913 +vn 0.5925 -0.3453 0.7278 +vn 0.0343 -0.6625 0.7483 +vn 0.1268 -0.7238 0.6783 +vn -0.2921 -0.6467 0.7046 +vn -0.6059 -0.2457 0.7567 +vn -0.5604 -0.4517 0.6942 +vn -0.7261 -0.0843 0.6824 +vn -0.6746 0.2442 0.6966 +vn -0.4958 0.4564 0.7388 +vn -0.4042 0.5921 0.6972 +vn 0.1522 0.6563 0.7390 +vn -0.0406 0.7275 0.6849 +vn 0.3656 0.6206 0.6937 +vn 0.6125 0.3723 0.6972 +vn 0.6424 0.2292 0.7313 +vn 0.7239 -0.0629 0.6870 +vn 0.6825 -0.5879 -0.4342 +vn 0.9252 0.2774 0.2591 +vn 0.1725 0.9091 -0.3792 +vn -0.9200 -0.2758 -0.2784 +vn -0.9224 -0.3072 -0.2341 +vn -0.9218 -0.2960 -0.2501 +vn -0.9226 -0.3223 -0.2122 +vn 0.2476 -0.9348 0.2545 +vn -0.3133 -0.0421 0.9487 +vn -0.4183 0.8897 0.1830 +vn 0.1818 0.4908 0.8521 +vn 0.3722 -0.2851 0.8833 +vn -0.0260 -0.0074 -0.9996 +vn -0.0319 0.0031 -0.9995 +vn -0.0168 -0.0146 -0.9998 +vn 0.0157 -0.0042 -0.9999 +vn 0.0134 -0.0118 -0.9998 +vn 0.0003 -0.0243 -0.9997 +vn -0.0058 -0.0271 -0.9996 +vn -0.0205 -0.0308 -0.9993 +vn 0.0049 0.0216 -0.9998 +vn 0.0106 0.0288 -0.9995 +vn 0.0247 0.0166 -0.9996 +vn 0.0288 0.0092 -0.9995 +vn 0.0037 0.0430 -0.9991 +vn -0.0102 0.0195 -0.9998 +vn -0.0468 0.0678 0.9966 +vn -0.0273 -0.0920 0.9954 +vn 0.0990 0.0029 0.9951 +vn -0.0573 -0.0731 0.9957 +vn -0.1415 0.1068 0.9842 +vn 0.1296 0.0282 0.9912 +vn 0.2409 -0.9706 0.0030 +vn 0.4705 -0.8818 0.0324 +vn 0.1768 -0.9839 0.0254 +vn -0.1757 -0.9844 -0.0101 +vn -0.2041 -0.9788 0.0145 +vn -0.5483 -0.8360 -0.0210 +vn -0.9961 -0.0879 -0.0100 +vn -0.9202 -0.3872 0.0571 +vn -0.9989 -0.0107 0.0453 +vn -0.9999 0.0061 -0.0107 +vn -0.9028 0.4292 0.0288 +vn -0.5160 0.8561 -0.0280 +vn -0.2118 0.9772 0.0145 +vn -0.4901 0.8713 -0.0241 +vn -0.1703 0.9852 0.0199 +vn 0.4328 0.9015 0.0030 +vn 0.3650 0.9309 0.0159 +vn 0.3740 0.9273 0.0141 +vn 0.4403 0.8978 0.0016 +vn 0.9776 0.2106 -0.0054 +vn 0.9207 0.3897 0.0213 +vn 0.9282 0.3717 0.0185 +vn 0.9818 0.1897 -0.0085 +vn 0.8746 -0.4849 -0.0028 +vn 0.9174 -0.3979 0.0060 +vn 0.9127 -0.4085 0.0050 +vn 0.8709 -0.4914 -0.0035 +vn 0.5807 -0.4248 0.6945 +vn 0.4332 -0.5474 0.7161 +vn 0.2692 -0.6698 0.6920 +vn -0.1191 -0.6768 0.7264 +vn -0.0589 -0.7214 0.6900 +vn -0.4278 -0.5864 0.6878 +vn -0.5946 -0.3329 0.7318 +vn -0.6906 -0.2008 0.6948 +vn -0.5983 0.3110 0.7385 +vn -0.6991 0.1899 0.6893 +vn -0.4556 0.5557 0.6954 +vn -0.0252 0.6705 0.7415 +vn -0.1190 0.7072 0.6969 +vn 0.2682 0.6717 0.6906 +vn 0.5560 0.4084 0.7239 +vn 0.5871 0.4153 0.6949 +vn 0.7077 -0.0615 0.7038 +vn 0.7053 -0.1374 0.6955 +vn 0.8816 -0.4217 0.2122 +vn 0.8837 -0.3956 0.2502 +vn 0.8830 -0.4069 0.2340 +vn 0.8841 -0.3751 0.2787 +vn -0.0715 0.9224 0.3795 +vn 0.3547 0.9174 -0.1803 +vn -0.8890 0.3775 -0.2593 +vn -0.7430 -0.5093 0.4342 +vn -0.3491 -0.9019 -0.2543 +vn -0.2237 -0.4049 0.8866 +vn -0.8853 -0.3947 0.2459 +vn -0.2715 0.2531 0.9286 +vn 0.4217 0.0465 0.9056 +vn 0.0001 -0.0003 1.0000 +vn 0.0008 -0.0021 1.0000 +vn 0.0002 0.0002 1.0000 +vn 0.0004 0.0010 1.0000 +vn -0.0045 -0.0008 1.0000 +vn -0.0002 0.0002 1.0000 +vn -0.0009 0.0003 1.0000 +vn -0.0008 0.0004 1.0000 +vn 0.0014 0.0005 1.0000 +vn 0.0007 0.0019 1.0000 +s 1 +f 1/1/1 2/2/1 3/3/1 +f 4/4/1 2/2/1 1/1/1 +f 5/5/2 6/6/2 7/7/2 +f 5/5/2 7/7/2 8/8/2 +f 9/9/3 10/10/4 11/11/5 +f 9/9/3 11/11/5 12/12/6 +f 12/12/6 11/11/5 13/13/7 +f 12/12/6 13/13/7 14/14/8 +f 15/15/9 16/16/10 17/17/11 +f 18/18/12 16/16/10 15/15/9 +f 19/19/13 20/20/14 21/21/15 +f 22/22/16 23/23/17 24/24/18 +f 18/18/12 25/25/19 16/16/10 +f 22/22/16 24/24/18 21/21/15 +f 21/21/15 24/24/18 19/19/13 +f 20/20/14 25/25/19 18/18/12 +f 26/26/20 27/27/21 28/28/22 +f 28/28/22 29/29/23 30/30/24 +f 29/29/23 31/31/25 30/30/24 +f 30/30/24 31/31/25 32/32/26 +f 32/32/26 31/31/25 33/33/27 +f 34/34/28 27/27/21 15/15/9 +f 32/32/26 33/33/27 35/35/29 +f 36/36/30 37/37/31 38/38/32 +f 39/39/33 37/37/31 40/40/34 +f 38/38/32 37/37/31 39/39/33 +f 41/41/35 42/42/36 43/43/37 +f 42/42/36 36/36/30 38/38/32 +f 43/43/37 42/42/36 38/38/32 +f 44/44/38 45/45/39 43/43/37 +f 43/43/37 45/45/39 41/41/35 +f 40/40/34 46/46/40 47/47/41 +f 39/39/33 40/40/34 47/47/41 +f 47/47/41 46/46/40 45/45/39 +f 48/48/42 49/49/43 50/50/44 +f 50/50/44 49/49/43 51/51/45 +f 52/52/46 51/51/45 53/53/47 +f 50/50/44 51/51/45 52/52/46 +f 44/44/38 54/54/48 55/55/49 +f 48/48/42 55/55/49 49/49/43 +f 56/56/50 57/57/51 58/58/52 +f 56/56/50 58/58/52 44/44/38 +f 44/44/38 58/58/52 54/54/48 +f 52/52/46 53/53/47 59/59/53 +f 56/56/50 59/59/54 57/57/51 +f 60/60/55 21/21/15 61/61/56 +f 52/52/46 21/21/15 60/60/55 +f 60/60/55 62/62/57 52/52/46 +f 63/63/58 61/61/56 21/21/15 +f 64/64/59 18/18/12 65/65/60 +f 18/18/12 64/64/59 63/63/58 +f 52/52/46 62/62/57 66/66/61 +f 52/52/46 66/66/61 50/50/44 +f 50/50/44 66/66/61 65/65/60 +f 50/50/44 65/65/60 18/18/12 +f 21/21/15 20/20/14 18/18/12 +f 21/21/15 18/18/12 63/63/58 +f 67/67/62 68/68/1 47/47/41 +f 47/47/41 68/68/1 48/48/1 +f 48/48/1 68/68/1 69/69/1 +f 45/45/39 44/44/38 70/70/63 +f 45/45/39 67/67/62 47/47/41 +f 55/55/49 48/48/42 44/44/38 +f 44/44/64 48/48/64 69/69/64 +f 70/70/63 67/67/62 45/45/39 +f 15/15/9 71/71/1 72/72/1 +f 18/18/12 73/73/1 74/74/1 +f 75/75/1 71/71/1 15/15/9 +f 15/15/9 72/72/1 18/18/12 +f 18/18/12 72/72/1 73/73/1 +f 18/18/12 74/74/1 26/26/20 +f 26/26/20 74/74/1 76/76/1 +f 26/26/20 76/76/1 75/75/1 +f 27/27/21 26/26/20 15/15/9 +f 15/15/9 26/26/20 75/75/1 +f 77/77/65 78/78/66 30/30/24 +f 38/38/32 79/79/67 80/80/68 +f 80/80/68 81/81/69 38/38/32 +f 30/30/24 82/82/70 77/77/65 +f 79/79/67 38/38/32 39/39/33 +f 38/38/32 81/81/69 82/82/70 +f 38/38/32 82/82/70 30/30/24 +f 26/26/20 78/78/66 83/83/71 +f 79/79/67 39/39/33 84/84/72 +f 26/26/20 83/83/71 39/39/33 +f 39/39/33 83/83/71 84/84/72 +f 26/26/20 28/28/22 30/30/24 +f 26/26/20 30/30/24 78/78/66 +f 85/85/73 86/86/74 87/87/75 +f 85/85/73 87/87/75 88/88/76 +f 88/88/76 87/87/75 89/89/77 +f 2/2/78 6/6/78 5/5/78 +f 4/4/78 6/6/78 2/2/78 +f 3/3/79 5/5/79 8/8/79 +f 2/2/79 5/5/79 3/3/79 +f 4/4/80 7/7/80 6/6/80 +f 1/1/80 7/7/80 4/4/80 +f 90/90/81 89/89/82 91/91/83 +f 90/90/81 91/91/83 92/92/84 +f 90/90/81 92/92/84 93/93/85 +f 92/92/84 12/12/86 93/93/85 +f 93/93/85 12/12/86 14/14/87 +f 94/94/88 86/86/89 85/85/90 +f 95/95/91 11/11/92 96/96/93 +f 95/95/91 96/96/93 85/85/90 +f 85/85/90 96/96/93 94/94/88 +f 95/95/91 13/13/94 11/11/92 +f 89/89/95 90/90/95 88/88/95 +f 85/85/96 22/22/97 21/21/98 +f 85/85/96 21/21/98 52/52/46 +f 85/85/96 52/52/46 95/95/99 +f 52/52/46 59/59/53 95/95/99 +f 95/95/99 59/59/53 56/56/100 +f 32/32/101 35/35/102 88/88/76 +f 88/88/76 17/17/103 85/85/73 +f 17/17/103 23/23/104 85/85/73 +f 15/15/105 17/17/103 35/35/102 +f 15/15/105 35/35/102 34/34/106 +f 35/35/102 17/17/103 88/88/76 +f 23/23/104 22/22/107 85/85/73 +f 32/32/101 88/88/76 90/90/108 +f 30/30/109 32/32/110 90/90/111 +f 43/43/112 38/38/113 93/93/114 +f 93/93/114 38/38/113 90/90/111 +f 90/90/111 38/38/113 30/30/109 +f 56/56/115 93/93/116 95/95/117 +f 56/56/115 43/43/118 93/93/116 +f 56/56/50 44/44/38 43/43/37 +f 95/95/119 93/93/120 14/14/121 +f 95/95/119 14/14/121 13/13/122 +f 44/44/123 97/97/124 70/70/125 +f 70/70/125 97/97/124 98/98/126 +f 70/70/125 98/98/126 67/67/127 +f 67/67/128 98/98/128 99/99/128 +f 67/67/129 99/99/130 68/68/131 +f 68/68/131 99/99/130 100/100/132 +f 68/68/133 100/100/134 69/69/135 +f 69/69/135 100/100/134 101/101/136 +f 69/69/137 101/101/138 102/102/139 +f 69/69/137 102/102/139 44/44/140 +f 44/44/141 102/102/141 97/97/141 +f 75/75/142 103/103/143 71/71/144 +f 71/71/144 103/103/143 104/104/145 +f 71/71/146 104/104/147 72/72/148 +f 72/72/148 104/104/147 105/105/149 +f 75/75/150 76/76/151 103/103/152 +f 103/103/152 76/76/151 106/106/153 +f 73/73/154 105/105/155 107/107/156 +f 73/73/154 107/107/156 74/74/157 +f 74/74/158 107/107/159 76/76/160 +f 76/76/160 107/107/159 106/106/161 +f 73/73/162 72/72/162 105/105/162 +f 108/108/163 109/109/164 110/110/165 +f 110/110/165 109/109/164 111/111/166 +f 109/109/167 112/112/168 111/111/169 +f 111/111/169 112/112/168 113/113/170 +f 113/113/171 112/112/171 114/114/171 +f 114/114/172 115/115/173 113/113/174 +f 115/115/173 114/114/172 116/116/175 +f 115/115/176 116/116/177 117/117/178 +f 117/117/178 116/116/177 118/118/179 +f 117/117/180 118/118/181 119/119/182 +f 119/119/182 118/118/181 120/120/183 +f 120/120/184 110/110/185 119/119/186 +f 110/110/185 120/120/184 108/108/187 +f 109/109/188 108/108/189 35/35/190 +f 35/35/190 108/108/189 34/34/191 +f 34/34/191 108/108/189 120/120/192 +f 34/34/193 120/120/194 27/27/195 +f 120/120/194 118/118/196 27/27/195 +f 27/27/197 118/118/198 28/28/199 +f 28/28/199 118/118/198 116/116/200 +f 28/28/201 116/116/202 29/29/203 +f 116/116/202 114/114/204 29/29/203 +f 29/29/203 114/114/204 31/31/205 +f 114/114/204 112/112/206 31/31/205 +f 31/31/205 112/112/206 33/33/207 +f 33/33/207 112/112/206 109/109/188 +f 33/33/207 109/109/188 35/35/190 +f 121/121/208 122/122/209 123/123/210 +f 121/121/208 123/123/210 124/124/211 +f 124/124/212 123/123/213 125/125/214 +f 126/126/215 125/125/214 123/123/213 +f 125/125/216 126/126/217 127/127/218 +f 125/125/216 127/127/218 128/128/219 +f 128/128/220 127/127/220 129/129/220 +f 129/129/221 130/130/222 128/128/223 +f 129/129/221 131/131/224 130/130/222 +f 130/130/225 131/131/226 122/122/227 +f 122/122/227 121/121/228 130/130/225 +f 37/37/229 122/122/230 40/40/231 +f 40/40/231 122/122/230 46/46/232 +f 122/122/230 131/131/233 46/46/232 +f 46/46/234 131/131/235 45/45/235 +f 45/45/235 131/131/235 129/129/236 +f 129/129/237 127/127/238 45/45/239 +f 45/45/239 127/127/238 41/41/240 +f 127/127/238 126/126/241 41/41/240 +f 41/41/240 126/126/241 42/42/242 +f 42/42/242 126/126/241 123/123/243 +f 42/42/242 123/123/243 36/36/244 +f 36/36/245 123/123/246 37/37/247 +f 123/123/246 122/122/248 37/37/247 +f 132/132/249 133/133/250 134/134/251 +f 132/132/249 134/134/251 135/135/252 +f 135/135/253 134/134/254 136/136/255 +f 135/135/253 136/136/255 137/137/256 +f 137/137/257 136/136/258 138/138/259 +f 138/138/259 139/139/260 137/137/257 +f 139/139/261 138/138/262 140/140/263 +f 139/139/261 140/140/263 141/141/264 +f 141/141/265 140/140/266 142/142/267 +f 141/141/265 142/142/267 143/143/268 +f 142/142/269 132/132/270 143/143/271 +f 132/132/270 142/142/269 133/133/272 +f 133/133/273 142/142/274 78/78/275 +f 78/78/275 142/142/274 83/83/276 +f 83/83/277 142/142/278 140/140/279 +f 83/83/277 140/140/279 84/84/280 +f 84/84/280 140/140/279 79/79/281 +f 140/140/279 138/138/282 79/79/281 +f 79/79/281 138/138/282 80/80/283 +f 80/80/284 138/138/285 136/136/286 +f 80/80/284 136/136/286 81/81/287 +f 81/81/287 136/136/286 82/82/288 +f 136/136/286 134/134/289 82/82/288 +f 82/82/288 134/134/289 77/77/290 +f 134/134/289 133/133/273 77/77/290 +f 77/77/290 133/133/273 78/78/275 +f 144/144/291 145/145/292 146/146/293 +f 146/146/293 145/145/292 147/147/294 +f 146/146/295 147/147/295 148/148/295 +f 148/148/296 147/147/296 149/149/296 +f 148/148/297 149/149/297 10/10/297 +f 150/150/298 10/10/298 149/149/298 +f 10/10/299 150/150/300 151/151/301 +f 151/151/301 150/150/300 152/152/302 +f 153/153/303 151/151/304 152/152/305 +f 153/153/303 154/154/306 151/151/304 +f 154/154/307 153/153/308 145/145/309 +f 154/154/307 145/145/309 144/144/310 +f 51/51/311 145/145/312 53/53/313 +f 145/145/312 153/153/314 53/53/313 +f 53/53/313 153/153/314 59/59/315 +f 153/153/314 152/152/316 59/59/315 +f 59/59/315 152/152/316 57/57/317 +f 57/57/317 152/152/316 150/150/318 +f 57/57/317 150/150/318 58/58/319 +f 58/58/319 150/150/318 149/149/320 +f 58/58/319 149/149/320 54/54/321 +f 54/54/321 149/149/320 55/55/322 +f 149/149/320 147/147/323 55/55/322 +f 55/55/322 147/147/323 49/49/324 +f 145/145/325 49/49/324 147/147/323 +f 49/49/324 145/145/325 51/51/326 +f 155/155/327 156/156/328 157/157/329 +f 158/158/330 157/157/329 156/156/328 +f 157/157/331 158/158/332 159/159/333 +f 159/159/333 158/158/332 160/160/334 +f 160/160/335 161/161/336 159/159/337 +f 160/160/335 162/162/338 161/161/336 +f 162/162/339 163/163/339 161/161/339 +f 163/163/340 162/162/340 164/164/340 +f 164/164/341 165/165/341 163/163/341 +f 165/165/342 164/164/342 166/166/342 +f 166/166/343 155/155/343 165/165/343 +f 155/155/344 166/166/344 156/156/344 +f 63/63/345 166/166/346 61/61/347 +f 166/166/346 164/164/348 61/61/347 +f 61/61/347 164/164/348 60/60/349 +f 60/60/350 164/164/351 62/62/352 +f 62/62/352 164/164/351 162/162/353 +f 62/62/354 162/162/355 66/66/356 +f 66/66/356 162/162/355 160/160/357 +f 66/66/358 160/160/359 65/65/360 +f 160/160/359 158/158/361 65/65/360 +f 65/65/360 158/158/361 64/64/362 +f 64/64/362 158/158/361 156/156/363 +f 64/64/362 156/156/363 63/63/345 +f 63/63/345 156/156/363 166/166/346 +f 167/167/364 168/168/364 169/169/364 +f 169/169/365 168/168/366 170/170/367 +f 169/169/365 170/170/367 171/171/368 +f 171/171/369 170/170/370 172/172/371 +f 172/172/371 173/173/372 171/171/369 +f 172/172/373 174/174/373 173/173/373 +f 173/173/374 174/174/375 175/175/376 +f 175/175/376 174/174/375 176/176/377 +f 175/175/378 176/176/379 177/177/380 +f 177/177/380 178/178/381 175/175/378 +f 178/178/382 177/177/383 167/167/384 +f 167/167/384 177/177/383 168/168/385 +f 17/17/386 168/168/387 177/177/388 +f 17/17/386 177/177/388 23/23/389 +f 23/23/390 177/177/391 24/24/392 +f 177/177/391 176/176/393 24/24/392 +f 24/24/392 176/176/393 19/19/394 +f 19/19/394 176/176/393 174/174/395 +f 19/19/394 174/174/395 20/20/396 +f 174/174/395 172/172/397 20/20/396 +f 20/20/396 172/172/397 25/25/398 +f 25/25/398 172/172/397 170/170/399 +f 25/25/398 170/170/399 16/16/400 +f 170/170/399 168/168/401 16/16/400 +f 168/168/401 17/17/402 16/16/400 +f 18/18/403 179/179/404 50/50/405 +f 50/50/405 179/179/404 180/180/406 +f 26/26/407 181/181/408 18/18/409 +f 18/18/409 181/181/408 179/179/410 +f 181/181/411 26/26/411 182/182/411 +f 39/39/412 183/183/413 182/182/414 +f 39/39/412 182/182/414 26/26/415 +f 183/183/416 39/39/416 47/47/416 +f 48/48/417 184/184/418 47/47/419 +f 47/47/419 184/184/418 183/183/420 +f 184/184/421 48/48/422 180/180/423 +f 180/180/423 48/48/422 50/50/424 +f 184/184/1 180/180/1 179/179/1 +f 181/181/1 182/182/1 183/183/1 +f 183/183/1 179/179/1 181/181/1 +f 183/183/1 184/184/1 179/179/1 +f 185/185/425 186/186/426 187/187/427 +f 187/187/427 186/186/426 188/188/428 +f 187/187/429 188/188/430 189/189/431 +f 189/189/431 188/188/430 190/190/432 +f 189/189/431 190/190/432 191/191/433 +f 191/191/433 190/190/432 192/192/434 +f 191/191/435 192/192/436 193/193/437 +f 194/194/438 193/193/437 192/192/436 +f 194/194/439 195/195/440 193/193/441 +f 196/196/442 195/195/440 194/194/439 +f 196/196/443 197/197/444 195/195/445 +f 198/198/446 197/197/444 196/196/443 +f 199/199/447 200/200/448 198/198/446 +f 198/198/446 200/200/448 197/197/444 +f 186/186/449 185/185/450 199/199/451 +f 199/199/451 185/185/450 200/200/452 +f 190/190/432 201/201/453 192/192/434 +f 188/188/430 202/202/454 190/190/432 +f 186/186/426 203/203/455 202/202/456 +f 186/186/426 202/202/456 188/188/428 +f 199/199/451 203/203/457 186/186/449 +f 196/196/443 204/204/458 198/198/446 +f 194/194/439 204/204/459 196/196/442 +f 194/194/439 205/205/460 204/204/459 +f 201/201/461 205/205/462 192/192/436 +f 192/192/436 205/205/462 194/194/438 +f 206/206/463 205/205/464 201/201/465 +f 205/205/464 206/206/463 204/204/466 +f 203/203/467 207/207/468 202/202/469 +f 202/202/469 208/208/470 190/190/471 +f 190/190/471 208/208/470 201/201/465 +f 201/201/465 208/208/470 206/206/463 +f 198/198/472 209/209/473 199/199/474 +f 199/199/474 209/209/473 203/203/467 +f 202/202/469 207/207/468 208/208/470 +f 204/204/466 206/206/463 198/198/472 +f 206/206/463 209/209/473 198/198/472 +f 203/203/467 209/209/473 207/207/468 +f 206/206/463 210/210/475 209/209/473 +f 209/209/473 210/210/475 207/207/468 +f 207/207/468 210/210/475 208/208/470 +f 208/208/470 210/210/475 206/206/463 +f 211/211/476 212/212/477 213/213/478 +f 187/187/479 189/189/480 214/214/481 +f 213/213/478 187/187/479 214/214/481 +f 214/214/481 211/211/476 213/213/478 +f 185/185/482 187/187/479 213/213/478 +f 215/215/483 185/185/482 213/213/478 +f 212/212/477 215/215/483 213/213/478 +f 200/200/484 185/185/482 215/215/483 +f 216/216/485 215/215/483 212/212/477 +f 216/216/485 200/200/484 215/215/483 +f 197/197/486 200/200/484 216/216/485 +f 195/195/487 197/197/486 216/216/485 +f 217/217/488 195/195/487 216/216/485 +f 217/217/488 216/216/485 212/212/477 +f 193/193/489 195/195/487 217/217/488 +f 211/211/476 217/217/488 212/212/477 +f 218/218/490 193/193/489 217/217/488 +f 218/218/490 217/217/488 211/211/476 +f 191/191/491 193/193/489 218/218/490 +f 214/214/481 218/218/490 211/211/476 +f 214/214/481 191/191/491 218/218/490 +f 189/189/480 191/191/491 214/214/481 +f 219/219/492 220/220/493 221/221/494 +f 219/219/492 221/221/494 222/222/495 +f 222/222/496 221/221/497 223/223/498 +f 223/223/498 221/221/497 224/224/499 +f 223/223/500 224/224/501 225/225/502 +f 225/225/502 224/224/501 226/226/503 +f 225/225/504 226/226/505 227/227/506 +f 225/225/504 227/227/506 228/228/507 +f 228/228/508 227/227/509 229/229/510 +f 230/230/511 231/231/512 229/229/510 +f 230/230/511 229/229/510 227/227/509 +f 232/232/513 231/231/514 230/230/515 +f 232/232/513 233/233/516 231/231/514 +f 234/234/517 233/233/516 232/232/513 +f 235/235/518 233/233/516 234/234/517 +f 235/235/518 219/219/492 233/233/516 +f 220/220/493 219/219/492 235/235/518 +f 227/227/519 236/236/519 237/237/519 +f 226/226/505 236/236/520 227/227/506 +f 224/224/501 238/238/521 226/226/503 +f 221/221/497 238/238/522 224/224/499 +f 221/221/497 220/220/523 238/238/522 +f 232/232/513 239/239/524 234/234/517 +f 230/230/515 239/239/525 232/232/513 +f 230/230/526 237/237/527 239/239/528 +f 227/227/509 237/237/529 230/230/511 +f 239/239/528 237/237/527 240/240/530 +f 235/235/531 234/234/532 241/241/533 +f 235/235/531 241/241/533 220/220/534 +f 226/226/535 242/242/536 236/236/537 +f 236/236/537 242/242/536 237/237/527 +f 239/239/528 243/243/538 234/234/532 +f 234/234/532 243/243/538 241/241/533 +f 241/241/533 244/244/539 220/220/534 +f 220/220/534 244/244/539 238/238/540 +f 238/238/540 242/242/536 226/226/535 +f 240/240/530 243/243/538 239/239/528 +f 238/238/540 244/244/539 242/242/536 +f 242/242/536 245/245/541 237/237/527 +f 245/245/541 240/240/530 237/237/527 +f 240/240/530 245/245/541 243/243/538 +f 243/243/538 244/244/539 241/241/533 +f 242/242/536 244/244/539 245/245/541 +f 245/245/541 244/244/539 243/243/538 +f 223/223/542 225/225/543 246/246/544 +f 247/247/545 246/246/544 248/248/546 +f 223/223/542 246/246/544 247/247/545 +f 247/247/545 222/222/547 223/223/542 +f 219/219/548 222/222/547 247/247/545 +f 249/249/549 219/219/548 247/247/545 +f 249/249/549 247/247/545 248/248/546 +f 233/233/550 219/219/548 249/249/549 +f 250/250/551 233/233/550 249/249/549 +f 248/248/546 250/250/551 249/249/549 +f 231/231/552 233/233/550 250/250/551 +f 251/251/553 250/250/551 248/248/546 +f 251/251/553 231/231/552 250/250/551 +f 229/229/554 231/231/552 251/251/553 +f 252/252/555 229/229/554 251/251/553 +f 252/252/555 228/228/556 229/229/554 +f 252/252/555 251/251/553 248/248/546 +f 225/225/543 228/228/556 252/252/555 +f 248/248/546 246/246/544 252/252/555 +f 246/246/544 225/225/543 252/252/555 +f 253/253/557 254/254/558 255/255/559 +f 253/253/557 256/256/560 257/257/561 +f 258/258/562 259/259/563 260/260/564 +f 261/261/565 262/262/566 263/263/567 +f 264/264/568 265/265/569 266/266/570 +f 258/258/562 267/267/571 265/265/569 +f 268/268/572 267/267/571 258/258/562 +f 253/253/557 255/255/559 262/262/566 +f 258/258/562 265/265/569 264/264/568 +f 260/260/564 268/268/572 258/258/562 +f 263/263/567 259/259/563 261/261/565 +f 261/261/565 259/259/563 258/258/562 +f 253/253/557 262/262/566 261/261/565 +f 257/257/561 254/254/558 253/253/557 +f 266/266/570 256/256/560 264/264/568 +f 264/264/568 256/256/560 253/253/557 +f 269/269/573 270/270/574 271/271/575 +f 269/269/573 272/272/576 270/270/574 +f 269/269/573 271/271/575 273/273/577 +f 274/274/578 271/271/579 275/275/580 +f 275/275/580 271/271/579 270/270/581 +f 275/275/582 270/270/583 276/276/584 +f 275/275/582 276/276/584 277/277/585 +f 277/277/586 276/276/587 278/278/588 +f 277/277/586 278/278/588 279/279/589 +f 279/279/590 278/278/591 280/280/592 +f 279/279/593 280/280/594 281/281/595 +f 281/281/595 280/280/594 273/273/596 +f 281/281/595 273/273/596 282/282/597 +f 282/282/597 273/273/596 283/283/598 +f 282/282/599 283/283/600 274/274/601 +f 274/274/601 283/283/600 271/271/602 +f 254/254/603 274/274/604 255/255/605 +f 255/255/605 274/274/604 275/275/606 +f 255/255/605 275/275/606 262/262/607 +f 262/262/607 275/275/606 263/263/608 +f 263/263/608 275/275/606 277/277/609 +f 263/263/608 277/277/609 259/259/610 +f 259/259/610 277/277/609 260/260/611 +f 260/260/611 277/277/609 268/268/612 +f 268/268/612 277/277/609 279/279/613 +f 268/268/612 279/279/613 267/267/614 +f 267/267/614 279/279/613 265/265/615 +f 265/265/615 279/279/613 281/281/616 +f 265/265/615 281/281/616 266/266/617 +f 266/266/617 281/281/616 282/282/618 +f 266/266/617 282/282/618 256/256/619 +f 256/256/619 282/282/618 257/257/620 +f 257/257/620 282/282/618 274/274/604 +f 257/257/620 274/274/604 254/254/603 +f 261/261/621 258/258/622 284/284/623 +f 284/284/623 258/258/622 285/285/624 +f 253/253/625 261/261/626 286/286/627 +f 286/286/627 261/261/626 284/284/628 +f 264/264/629 253/253/630 287/287/631 +f 287/287/631 253/253/630 286/286/632 +f 258/258/633 264/264/634 285/285/635 +f 285/285/635 264/264/634 287/287/636 +f 284/284/1 285/285/1 286/286/1 +f 286/286/1 285/285/1 287/287/1 +f 276/276/637 270/270/637 272/272/637 +f 276/276/587 272/272/638 278/278/588 +f 278/278/639 272/272/639 269/269/639 +f 278/278/591 269/269/640 280/280/592 +f 280/280/641 269/269/641 273/273/641 +f 283/283/642 273/273/577 271/271/575 +f 288/288/79 289/289/79 290/290/79 +f 289/289/79 288/288/79 291/291/79 +f 291/291/79 288/288/79 292/292/79 +f 291/291/79 292/292/79 293/293/79 +f 294/294/79 295/295/79 296/296/79 +f 297/297/79 298/298/79 299/299/79 +f 293/293/79 300/300/79 301/301/79 +f 302/302/79 300/300/79 294/294/79 +f 303/303/79 300/300/79 304/304/79 +f 300/300/79 303/303/79 295/295/79 +f 300/300/79 305/305/79 304/304/79 +f 300/300/79 295/295/79 294/294/79 +f 304/304/79 305/305/79 306/306/79 +f 301/301/79 300/300/79 302/302/79 +f 307/307/79 306/306/79 305/305/79 +f 305/305/79 308/308/79 307/307/79 +f 294/294/79 296/296/79 309/309/79 +f 310/310/79 311/311/79 312/312/79 +f 300/300/79 293/293/79 292/292/79 +f 307/307/79 308/308/79 313/313/79 +f 308/308/79 314/314/79 313/313/79 +f 313/313/79 314/314/79 296/296/79 +f 315/315/79 299/299/79 316/316/79 +f 299/299/79 296/296/79 314/314/79 +f 299/299/79 314/314/79 316/316/79 +f 298/298/79 309/309/79 299/299/79 +f 317/317/79 315/315/79 318/318/79 +f 309/309/79 296/296/79 299/299/79 +f 309/309/79 298/298/79 319/319/79 +f 298/298/79 297/297/79 320/320/79 +f 317/317/79 318/318/79 321/321/79 +f 309/309/79 319/319/79 310/310/79 +f 321/321/79 318/318/79 322/322/79 +f 321/321/79 322/322/79 323/323/79 +f 322/322/79 324/324/79 323/323/79 +f 324/324/79 325/325/79 323/323/79 +f 323/323/79 325/325/79 326/326/79 +f 326/326/79 325/325/79 327/327/79 +f 325/325/79 328/328/79 327/327/79 +f 329/329/79 327/327/79 328/328/79 +f 316/316/79 318/318/79 315/315/79 +f 309/309/79 310/310/79 312/312/79 +f 330/330/80 331/331/80 332/332/80 +f 333/333/80 334/334/80 335/335/80 +f 334/334/80 336/336/80 337/337/80 +f 336/336/80 338/338/80 337/337/80 +f 338/338/80 336/336/80 339/339/80 +f 338/338/80 339/339/80 340/340/80 +f 341/341/80 338/338/80 340/340/80 +f 342/342/80 338/338/80 343/343/80 +f 344/344/80 345/345/80 342/342/80 +f 343/343/80 346/346/80 332/332/80 +f 345/345/80 344/344/80 347/347/80 +f 334/334/80 337/337/80 335/335/80 +f 346/346/80 348/348/80 332/332/80 +f 330/330/80 349/349/80 331/331/80 +f 345/345/80 347/347/80 349/349/80 +f 343/343/80 341/341/80 346/346/80 +f 348/348/80 330/330/80 332/332/80 +f 349/349/80 347/347/80 331/331/80 +f 345/345/80 338/338/80 342/342/80 +f 343/343/80 338/338/80 341/341/80 +f 348/348/80 346/346/80 350/350/80 +f 348/348/80 350/350/80 351/351/80 +f 351/351/80 352/352/80 348/348/80 +f 352/352/80 351/351/80 353/353/80 +f 354/354/79 355/355/79 356/356/79 +f 356/356/79 355/355/79 357/357/79 +f 356/356/79 357/357/79 358/358/79 +f 359/359/79 360/360/79 361/361/79 +f 361/361/79 360/360/79 357/357/79 +f 361/361/79 357/357/79 355/355/79 +f 359/359/643 361/361/644 362/362/645 +f 362/362/645 361/361/644 328/328/646 +f 328/328/646 363/363/647 362/362/645 +f 331/331/648 347/347/649 364/364/650 +f 364/364/650 347/347/649 365/365/651 +f 366/366/80 367/367/80 368/368/80 +f 366/366/80 365/365/80 367/367/80 +f 366/366/80 364/364/80 365/365/80 +f 368/368/80 367/367/80 369/369/80 +f 364/364/80 366/366/80 370/370/80 +f 371/371/652 372/372/653 373/373/654 +f 371/371/652 374/374/655 375/375/656 +f 375/375/656 372/372/653 371/371/652 +f 376/376/657 371/371/652 377/377/658 +f 378/378/659 373/373/654 379/379/660 +f 371/371/652 380/380/661 381/381/662 +f 371/371/652 381/381/662 377/377/658 +f 382/382/663 380/380/661 371/371/652 +f 382/382/663 371/371/652 378/378/659 +f 371/371/652 373/373/654 378/378/659 +f 383/383/664 384/384/665 385/385/666 +f 383/383/664 385/385/666 386/386/667 +f 386/386/667 385/385/666 387/387/668 +f 388/388/669 386/386/667 389/389/670 +f 389/389/670 386/386/667 387/387/668 +f 389/389/670 387/387/668 390/390/671 +f 390/390/671 387/387/668 391/391/672 +f 392/392/673 393/393/674 394/394/675 +f 348/348/676 392/392/673 394/394/675 +f 352/352/677 395/395/678 348/348/676 +f 348/348/676 395/395/678 392/392/673 +f 396/396/679 352/352/677 353/353/680 +f 395/395/678 352/352/677 397/397/681 +f 397/397/681 352/352/677 396/396/679 +f 353/353/680 398/398/682 396/396/679 +f 398/398/682 353/353/680 399/399/683 +f 399/399/683 353/353/680 400/400/684 +f 353/353/680 351/351/685 400/400/684 +f 400/400/684 351/351/685 401/401/686 +f 401/401/686 351/351/685 350/350/687 +f 401/401/686 350/350/687 309/309/688 +f 309/309/688 350/350/687 346/346/689 +f 309/309/688 346/346/689 294/294/690 +f 294/294/690 346/346/689 341/341/691 +f 294/294/690 341/341/691 302/302/692 +f 302/302/692 341/341/691 340/340/693 +f 302/302/692 340/340/693 301/301/694 +f 301/301/694 340/340/693 339/339/695 +f 301/301/694 339/339/695 293/293/696 +f 293/293/696 339/339/695 336/336/697 +f 293/293/696 336/336/697 291/291/698 +f 291/291/698 336/336/697 334/334/699 +f 291/291/698 334/334/699 289/289/700 +f 289/289/700 334/334/699 333/333/701 +f 289/289/700 333/333/701 290/290/702 +f 290/290/702 333/333/701 335/335/703 +f 290/290/702 335/335/703 288/288/704 +f 288/288/704 335/335/703 337/337/705 +f 288/288/704 337/337/705 292/292/706 +f 292/292/706 337/337/705 338/338/707 +f 292/292/706 338/338/707 300/300/708 +f 386/386/709 388/388/669 402/402/710 +f 386/386/709 402/402/710 400/400/711 +f 400/400/711 402/402/710 399/399/712 +f 403/403/713 404/404/714 405/405/715 +f 405/405/715 404/404/714 406/406/716 +f 404/404/714 403/403/713 407/407/717 +f 407/407/717 403/403/713 408/408/718 +f 338/338/707 345/345/719 300/300/708 +f 300/300/708 345/345/719 409/409/720 +f 305/305/721 300/300/708 410/410/722 +f 410/410/722 300/300/708 409/409/720 +f 410/410/722 409/409/720 406/406/716 +f 406/406/716 409/409/720 405/405/715 +f 411/411/723 412/412/724 407/407/725 +f 411/411/723 407/407/725 408/408/726 +f 412/412/724 411/411/723 413/413/727 +f 412/412/724 413/413/727 360/360/728 +f 358/358/729 357/357/729 414/414/729 +f 414/414/729 357/357/729 415/415/729 +f 414/414/1 416/416/1 358/358/1 +f 358/358/1 416/416/1 356/356/1 +f 417/417/80 418/418/80 419/419/80 +f 419/419/80 418/418/80 394/394/80 +f 413/413/80 420/420/80 421/421/80 +f 421/421/80 383/383/80 413/413/80 +f 386/386/80 400/400/80 401/401/80 +f 413/413/80 383/383/80 415/415/80 +f 415/415/80 383/383/80 416/416/80 +f 415/415/80 416/416/80 414/414/80 +f 416/416/80 383/383/80 386/386/80 +f 386/386/80 401/401/80 416/416/80 +f 422/422/80 423/423/80 424/424/80 +f 424/424/80 423/423/80 420/420/80 +f 413/413/80 424/424/80 420/420/80 +f 425/425/80 426/426/80 422/422/80 +f 422/422/80 426/426/80 423/423/80 +f 417/417/80 419/419/80 427/427/80 +f 427/427/80 419/419/80 428/428/80 +f 427/427/80 428/428/80 425/425/80 +f 425/425/80 428/428/80 426/426/80 +f 314/314/730 429/429/731 430/430/732 +f 314/314/730 430/430/732 316/316/733 +f 316/316/733 430/430/732 318/318/734 +f 318/318/734 430/430/732 431/431/735 +f 318/318/734 431/431/735 322/322/736 +f 322/322/736 431/431/735 432/432/737 +f 322/322/736 432/432/737 324/324/738 +f 324/324/738 432/432/737 363/363/647 +f 324/324/738 363/363/647 325/325/739 +f 433/433/740 429/429/731 308/308/741 +f 308/308/741 429/429/731 314/314/730 +f 407/407/79 412/412/79 362/362/79 +f 407/407/79 362/362/79 404/404/79 +f 433/433/79 410/410/79 406/406/79 +f 434/434/79 363/363/79 432/432/79 +f 434/434/79 432/432/79 435/435/79 +f 436/436/79 363/363/79 434/434/79 +f 363/363/79 436/436/79 362/362/79 +f 362/362/79 436/436/79 437/437/79 +f 362/362/79 438/438/79 404/404/79 +f 438/438/79 439/439/79 404/404/79 +f 404/404/79 439/439/79 440/440/79 +f 432/432/79 431/431/79 435/435/79 +f 435/435/79 431/431/79 441/441/79 +f 441/441/79 431/431/79 430/430/79 +f 437/437/79 438/438/79 362/362/79 +f 404/404/79 440/440/79 442/442/79 +f 433/433/79 406/406/79 404/404/79 +f 433/433/79 404/404/79 442/442/79 +f 429/429/79 433/433/79 443/443/79 +f 441/441/79 430/430/79 444/444/79 +f 444/444/79 430/430/79 429/429/79 +f 444/444/79 429/429/79 443/443/79 +f 442/442/79 443/443/79 433/433/79 +f 422/422/742 445/445/743 425/425/744 +f 425/425/744 445/445/743 446/446/745 +f 425/425/744 446/446/745 427/427/746 +f 427/427/746 446/446/745 447/447/747 +f 427/427/746 447/447/747 417/417/748 +f 417/417/748 447/447/747 448/448/749 +f 417/417/748 448/448/749 418/418/750 +f 418/418/750 448/448/749 449/449/751 +f 330/330/752 418/418/750 449/449/751 +f 449/449/751 450/450/753 330/330/752 +f 330/330/752 450/450/753 349/349/754 +f 424/424/755 445/445/743 422/422/742 +f 405/405/80 409/409/80 450/450/80 +f 451/451/80 411/411/80 408/408/80 +f 451/451/80 452/452/80 453/453/80 +f 451/451/80 408/408/80 403/403/80 +f 451/451/80 403/403/80 454/454/80 +f 451/451/80 454/454/80 452/452/80 +f 453/453/80 455/455/80 451/451/80 +f 451/451/80 455/455/80 445/445/80 +f 456/456/80 457/457/80 405/405/80 +f 405/405/80 457/457/80 403/403/80 +f 403/403/80 457/457/80 454/454/80 +f 445/445/80 455/455/80 458/458/80 +f 445/445/80 458/458/80 446/446/80 +f 459/459/80 448/448/80 460/460/80 +f 450/450/80 449/449/80 459/459/80 +f 461/461/80 462/462/80 450/450/80 +f 460/460/80 448/448/80 447/447/80 +f 460/460/80 447/447/80 463/463/80 +f 463/463/80 447/447/80 446/446/80 +f 463/463/80 446/446/80 458/458/80 +f 448/448/80 459/459/80 449/449/80 +f 459/459/80 461/461/80 450/450/80 +f 450/450/80 462/462/80 405/405/80 +f 405/405/80 462/462/80 456/456/80 +f 464/464/756 460/460/757 463/463/758 +f 460/460/757 464/464/756 465/465/759 +f 460/460/757 465/465/759 459/459/760 +f 459/459/760 465/465/759 466/466/761 +f 459/459/760 466/466/761 467/467/762 +f 459/459/760 467/467/762 461/461/763 +f 461/461/764 467/467/765 462/462/766 +f 467/467/765 468/468/767 462/462/766 +f 468/468/767 469/469/768 462/462/766 +f 462/462/766 469/469/768 456/456/769 +f 456/456/769 469/469/768 470/470/770 +f 456/456/769 470/470/770 457/457/771 +f 457/457/771 470/470/770 471/471/772 +f 457/457/771 471/471/772 454/454/773 +f 471/471/772 472/472/774 454/454/773 +f 454/454/773 472/472/774 452/452/775 +f 452/452/775 472/472/774 453/453/776 +f 453/453/776 472/472/774 473/473/777 +f 453/453/776 473/473/777 455/455/778 +f 455/455/778 473/473/777 474/474/779 +f 455/455/778 474/474/779 458/458/780 +f 474/474/779 475/475/781 458/458/780 +f 458/458/780 475/475/781 463/463/758 +f 475/475/781 464/464/756 463/463/758 +f 476/476/782 439/439/783 438/438/784 +f 476/476/782 438/438/784 477/477/785 +f 477/477/786 438/438/787 437/437/788 +f 477/477/786 437/437/788 478/478/789 +f 478/478/789 437/437/788 436/436/790 +f 478/478/789 436/436/790 479/479/791 +f 479/479/791 436/436/790 434/434/792 +f 479/479/791 434/434/792 480/480/793 +f 480/480/793 434/434/792 435/435/794 +f 480/480/793 435/435/794 481/481/795 +f 481/481/795 435/435/794 441/441/796 +f 481/481/795 441/441/796 482/482/797 +f 482/482/797 441/441/796 444/444/798 +f 482/482/797 444/444/798 483/483/799 +f 483/483/799 444/444/798 443/443/800 +f 483/483/799 443/443/800 484/484/801 +f 484/484/801 443/443/800 442/442/802 +f 484/484/801 442/442/802 485/485/803 +f 485/485/803 442/442/802 440/440/804 +f 485/485/803 440/440/804 486/486/805 +f 486/486/805 440/440/804 439/439/783 +f 486/486/805 439/439/783 476/476/782 +f 413/413/806 411/411/807 424/424/808 +f 424/424/808 411/411/807 451/451/809 +f 412/412/810 360/360/811 362/362/812 +f 362/362/812 360/360/811 359/359/813 +f 487/487/814 299/299/815 488/488/816 +f 299/299/815 487/487/814 297/297/817 +f 489/489/818 297/297/817 487/487/814 +f 490/490/819 297/297/817 489/489/818 +f 297/297/817 490/490/819 320/320/820 +f 491/491/821 320/320/820 490/490/819 +f 320/320/820 491/491/821 492/492/822 +f 492/492/822 298/298/823 320/320/820 +f 493/493/824 494/494/825 326/326/826 +f 326/326/826 494/494/825 323/323/827 +f 495/495/828 323/323/827 494/494/825 +f 323/323/827 495/495/828 496/496/829 +f 496/496/829 321/321/830 323/323/827 +f 321/321/830 496/496/829 497/497/831 +f 498/498/832 317/317/833 497/497/831 +f 497/497/831 317/317/833 321/321/830 +f 317/317/834 498/498/835 315/315/836 +f 315/315/836 498/498/835 499/499/837 +f 315/315/838 499/499/837 299/299/839 +f 299/299/839 499/499/837 488/488/840 +f 298/298/823 492/492/822 500/500/841 +f 298/298/823 500/500/841 319/319/842 +f 319/319/842 500/500/841 501/501/843 +f 319/319/842 501/501/843 310/310/844 +f 310/310/844 501/501/843 502/502/845 +f 502/502/845 503/503/846 310/310/847 +f 310/310/847 503/503/846 311/311/848 +f 311/311/848 503/503/846 504/504/849 +f 328/328/850 361/361/851 329/329/852 +f 329/329/852 361/361/851 355/355/853 +f 329/329/852 355/355/853 311/311/854 +f 329/329/855 505/505/856 327/327/857 +f 327/327/857 505/505/856 506/506/858 +f 327/327/859 506/506/860 507/507/861 +f 327/327/859 507/507/861 326/326/826 +f 326/326/826 507/507/861 493/493/824 +f 508/508/862 509/509/863 510/510/864 +f 511/511/865 508/508/862 510/510/864 +f 511/511/865 512/512/866 513/513/867 +f 510/510/864 514/514/868 512/512/866 +f 511/511/865 510/510/864 512/512/866 +f 511/511/865 513/513/867 515/515/869 +f 295/295/870 516/516/871 296/296/872 +f 296/296/872 516/516/871 517/517/873 +f 296/296/874 517/517/875 518/518/876 +f 296/296/874 518/518/876 313/313/877 +f 313/313/877 518/518/876 519/519/878 +f 520/520/879 307/307/880 519/519/881 +f 519/519/881 307/307/880 313/313/882 +f 307/307/883 520/520/884 521/521/885 +f 307/307/883 521/521/885 306/306/886 +f 521/521/887 522/522/888 306/306/889 +f 306/306/889 522/522/888 304/304/890 +f 304/304/891 522/522/892 523/523/893 +f 304/304/891 523/523/893 303/303/894 +f 303/303/895 523/523/896 295/295/897 +f 295/295/897 523/523/896 516/516/898 +f 516/516/79 520/520/79 517/517/79 +f 517/517/79 520/520/79 519/519/79 +f 521/521/79 520/520/79 516/516/79 +f 518/518/79 517/517/79 519/519/79 +f 521/521/79 516/516/79 522/522/79 +f 522/522/79 516/516/79 523/523/79 +f 394/394/675 418/418/750 348/348/676 +f 348/348/676 418/418/750 330/330/752 +f 524/524/899 428/428/900 419/419/901 +f 428/428/900 524/524/899 525/525/902 +f 428/428/900 525/525/902 526/526/903 +f 527/527/904 426/426/905 428/428/900 +f 527/527/904 428/428/900 526/526/903 +f 426/426/905 527/527/904 528/528/906 +f 529/529/907 423/423/908 528/528/906 +f 528/528/906 423/423/908 426/426/905 +f 423/423/908 529/529/907 530/530/909 +f 423/423/908 530/530/909 420/420/910 +f 420/420/910 530/530/909 531/531/911 +f 420/420/912 531/531/911 532/532/913 +f 420/420/912 532/532/913 421/421/914 +f 421/421/914 532/532/913 533/533/915 +f 413/413/727 357/357/916 360/360/728 +f 534/534/917 421/421/914 533/533/915 +f 357/357/916 413/413/727 415/415/918 +f 383/383/919 421/421/914 534/534/917 +f 534/534/917 384/384/665 383/383/919 +f 533/533/915 535/535/920 534/534/917 +f 505/505/921 329/329/852 311/311/854 +f 311/311/854 504/504/922 505/505/921 +f 424/424/755 451/451/923 445/445/743 +f 328/328/646 325/325/739 363/363/647 +f 394/394/924 393/393/925 419/419/926 +f 419/419/926 393/393/925 536/536/927 +f 419/419/928 536/536/929 524/524/930 +f 332/332/931 366/366/932 343/343/933 +f 343/343/933 366/366/932 368/368/934 +f 343/343/935 368/368/936 342/342/937 +f 342/342/937 368/368/936 369/369/938 +f 369/369/939 367/367/940 342/342/941 +f 342/342/941 367/367/940 344/344/942 +f 331/331/943 364/364/944 370/370/945 +f 331/331/943 370/370/945 332/332/946 +f 332/332/946 370/370/945 366/366/947 +f 537/537/948 389/389/949 390/390/950 +f 538/538/951 539/539/952 537/537/948 +f 537/537/948 539/539/952 389/389/949 +f 540/540/953 541/541/954 542/542/955 +f 542/542/955 541/541/954 543/543/956 +f 544/544/957 542/542/955 543/543/956 +f 544/544/957 545/545/958 542/542/955 +f 544/544/957 396/396/679 545/545/958 +f 396/396/679 544/544/957 397/397/681 +f 539/539/952 538/538/951 540/540/959 +f 540/540/959 538/538/951 546/546/960 +f 547/547/961 539/539/962 542/542/963 +f 542/542/963 539/539/962 540/540/964 +f 548/548/965 549/549/966 550/550/967 +f 550/550/967 549/549/966 551/551/968 +f 550/550/967 534/534/917 535/535/920 +f 551/551/968 534/534/917 550/550/967 +f 552/552/969 553/553/970 387/387/971 +f 387/387/971 553/553/970 391/391/972 +f 549/549/973 554/554/974 552/552/975 +f 552/552/975 554/554/974 553/553/976 +f 552/552/977 551/551/978 549/549/979 +f 549/549/980 548/548/980 554/554/980 +f 546/546/981 541/541/954 540/540/953 +f 555/555/982 509/509/863 556/556/983 +f 557/557/984 555/555/982 556/556/983 +f 558/558/985 509/509/863 555/555/982 +f 507/507/986 557/557/984 493/493/987 +f 493/493/987 557/557/984 556/556/983 +f 505/505/988 558/558/985 506/506/860 +f 506/506/860 558/558/985 555/555/982 +f 506/506/860 555/555/982 557/557/984 +f 506/506/860 557/557/984 507/507/861 +f 496/496/989 559/559/990 497/497/991 +f 494/494/992 493/493/987 560/560/993 +f 494/494/992 560/560/993 495/495/994 +f 496/496/989 495/495/994 561/561/995 +f 496/496/989 561/561/995 559/559/990 +f 497/497/991 559/559/990 562/562/996 +f 497/497/991 562/562/996 498/498/997 +f 498/498/997 562/562/996 563/563/998 +f 493/493/987 556/556/983 560/560/993 +f 495/495/994 560/560/993 561/561/995 +f 559/559/990 561/561/995 562/562/996 +f 560/560/993 556/556/983 508/508/862 +f 560/560/993 508/508/862 561/561/995 +f 561/561/995 511/511/999 562/562/996 +f 556/556/983 509/509/863 508/508/862 +f 561/561/995 508/508/862 511/511/999 +f 562/562/1000 511/511/1000 563/563/1000 +f 563/563/1001 511/511/865 515/515/869 +f 505/505/921 504/504/922 558/558/985 +f 558/558/985 504/504/922 564/564/1002 +f 558/558/985 564/564/1002 509/509/863 +f 509/509/863 564/564/1002 510/510/864 +f 498/498/835 563/563/1003 499/499/837 +f 488/488/840 499/499/837 565/565/1004 +f 565/565/1004 499/499/837 563/563/1003 +f 565/565/1004 563/563/1003 515/515/1005 +f 503/503/846 564/564/1002 504/504/922 +f 489/489/818 566/566/1006 490/490/1007 +f 490/490/1007 567/567/1008 491/491/1009 +f 488/488/1010 565/565/1011 487/487/1012 +f 489/489/818 487/487/814 566/566/1006 +f 490/490/1007 566/566/1006 567/567/1008 +f 491/491/1009 567/567/1008 568/568/1013 +f 491/491/1009 568/568/1013 492/492/822 +f 492/492/822 568/568/1013 569/569/1014 +f 565/565/1011 515/515/1015 487/487/1012 +f 487/487/1012 515/515/1015 513/513/1016 +f 487/487/1012 513/513/1016 566/566/1006 +f 566/566/1006 513/513/1016 567/567/1008 +f 568/568/1013 567/567/1008 512/512/866 +f 568/568/1013 512/512/866 569/569/1014 +f 569/569/1014 512/512/866 514/514/868 +f 567/567/1008 513/513/1016 512/512/866 +f 503/503/846 502/502/845 570/570/1017 +f 503/503/846 570/570/1017 564/564/1002 +f 564/564/1002 570/570/1017 571/571/1018 +f 564/564/1002 571/571/1018 510/510/864 +f 510/510/864 571/571/1018 514/514/868 +f 492/492/822 569/569/1014 500/500/841 +f 501/501/843 500/500/1019 569/569/1020 +f 571/571/1021 501/501/843 569/569/1020 +f 571/571/1021 569/569/1020 514/514/1022 +f 570/570/1017 502/502/845 501/501/843 +f 571/571/1021 570/570/1017 501/501/843 +f 535/535/920 533/533/1023 379/379/660 +f 379/379/660 533/533/1023 572/572/1024 +f 379/379/660 572/572/1024 378/378/659 +f 529/529/1025 573/573/1026 574/574/1027 +f 530/530/909 529/529/1025 574/574/1027 +f 530/530/909 574/574/1027 531/531/911 +f 532/532/913 531/531/911 574/574/1027 +f 572/572/1024 532/532/913 574/574/1027 +f 572/572/1024 574/574/1027 378/378/659 +f 378/378/659 574/574/1027 573/573/1028 +f 533/533/1023 532/532/913 572/572/1024 +f 379/379/660 575/575/1029 535/535/920 +f 535/535/920 575/575/1029 550/550/967 +f 525/525/902 524/524/1030 576/576/1031 +f 525/525/902 576/576/1031 526/526/903 +f 524/524/1030 577/577/1032 576/576/1031 +f 527/527/904 526/526/903 578/578/1033 +f 527/527/904 578/578/1033 528/528/1034 +f 528/528/1034 578/578/1033 573/573/1026 +f 528/528/1034 573/573/1026 529/529/1025 +f 576/576/1031 579/579/1035 380/380/1036 +f 576/576/1031 380/380/1036 526/526/903 +f 526/526/903 380/380/1036 578/578/1033 +f 577/577/1032 580/580/1037 576/576/1031 +f 576/576/1031 580/580/1037 579/579/1035 +f 578/578/1033 380/380/1036 382/382/663 +f 578/578/1033 382/382/663 573/573/1028 +f 580/580/1038 381/381/1038 579/579/1038 +f 579/579/1035 381/381/1039 380/380/1036 +f 382/382/663 378/378/659 573/573/1028 +f 373/373/654 581/581/1040 379/379/660 +f 379/379/660 581/581/1040 575/575/1029 +f 575/575/1029 581/581/1041 548/548/965 +f 575/575/1029 548/548/965 550/550/967 +f 393/393/925 582/582/1042 583/583/1043 +f 536/536/927 393/393/925 583/583/1043 +f 524/524/930 536/536/929 577/577/1032 +f 577/577/1032 536/536/929 583/583/1043 +f 580/580/1037 583/583/1043 582/582/1042 +f 580/580/1037 582/582/1042 381/381/662 +f 577/577/1032 583/583/1043 580/580/1037 +f 581/581/1044 584/584/1045 554/554/974 +f 372/372/1046 584/584/1047 581/581/1040 +f 554/554/974 548/548/1048 581/581/1044 +f 581/581/1040 373/373/654 372/372/1046 +f 392/392/673 585/585/1049 393/393/925 +f 397/397/681 586/586/1050 395/395/678 +f 395/395/678 586/586/1050 587/587/1051 +f 395/395/678 587/587/1051 392/392/673 +f 393/393/925 585/585/1049 582/582/1042 +f 392/392/673 587/587/1051 585/585/1049 +f 586/586/1050 376/376/1052 587/587/1051 +f 587/587/1051 376/376/1052 377/377/658 +f 585/585/1049 377/377/658 381/381/662 +f 585/585/1049 381/381/662 582/582/1042 +f 587/587/1051 377/377/658 585/585/1049 +f 372/372/1053 375/375/1054 588/588/1055 +f 372/372/1053 588/588/1055 584/584/1045 +f 584/584/1045 588/588/1055 553/553/976 +f 584/584/1045 553/553/976 554/554/974 +f 397/397/681 544/544/957 586/586/1050 +f 541/541/954 589/589/1056 543/543/956 +f 543/543/956 589/589/1056 590/590/1057 +f 543/543/956 590/590/1057 544/544/957 +f 586/586/1050 544/544/957 590/590/1057 +f 586/586/1050 590/590/1057 376/376/1052 +f 591/591/1058 588/588/1055 375/375/1054 +f 553/553/970 588/588/1055 591/591/1058 +f 553/553/970 591/591/1058 391/391/972 +f 590/590/1057 589/589/1056 371/371/1059 +f 590/590/1057 371/371/1059 376/376/1052 +f 541/541/954 546/546/960 589/589/1056 +f 390/390/1060 391/391/1061 591/591/1062 +f 390/390/1060 591/591/1062 374/374/1063 +f 374/374/1063 591/591/1062 375/375/1064 +f 374/374/1065 371/371/1059 589/589/1056 +f 374/374/1065 589/589/1056 592/592/1066 +f 592/592/1066 589/589/1056 538/538/951 +f 538/538/951 589/589/1056 546/546/960 +f 390/390/1060 374/374/1063 592/592/1066 +f 537/537/948 390/390/1060 592/592/1066 +f 538/538/951 537/537/948 592/592/1066 +f 551/551/978 552/552/977 593/593/1067 +f 384/384/665 534/534/917 593/593/1067 +f 593/593/1067 534/534/917 551/551/978 +f 385/385/666 384/384/665 593/593/1067 +f 593/593/1067 552/552/977 387/387/1068 +f 385/385/666 593/593/1067 387/387/1068 +f 594/594/1069 389/389/1070 547/547/1071 +f 547/547/1071 389/389/1070 539/539/1072 +f 389/389/670 594/594/1069 388/388/669 +f 595/595/1073 399/399/712 402/402/710 +f 595/595/1073 402/402/710 596/596/1074 +f 597/597/1075 595/595/1073 547/547/1071 +f 547/547/1071 595/595/1073 596/596/1074 +f 596/596/1074 594/594/1069 547/547/1071 +f 402/402/710 388/388/669 596/596/1074 +f 596/596/1074 388/388/669 594/594/1069 +f 547/547/961 542/542/963 597/597/1076 +f 597/597/1076 542/542/963 595/595/1077 +f 595/595/1077 542/542/963 398/398/1078 +f 595/595/1077 398/398/1078 399/399/1079 +f 542/542/963 545/545/1080 398/398/1078 +f 398/398/1078 545/545/1080 396/396/1081 +f 409/409/1082 345/345/1083 450/450/1084 +f 450/450/1084 345/345/1083 349/349/1085 +f 305/305/1086 410/410/1087 308/308/1088 +f 308/308/1088 410/410/1087 433/433/1089 +f 466/466/80 468/468/80 467/467/80 +f 468/468/80 470/470/80 469/469/80 +f 468/468/80 466/466/80 470/470/80 +f 470/470/80 465/465/80 464/464/80 +f 464/464/80 472/472/80 470/470/80 +f 475/475/80 472/472/80 464/464/80 +f 472/472/80 471/471/80 470/470/80 +f 474/474/80 472/472/80 475/475/80 +f 466/466/80 465/465/80 470/470/80 +f 472/472/80 474/474/80 473/473/80 +f 482/482/79 486/486/79 476/476/79 +f 484/484/79 486/486/79 483/483/79 +f 486/486/79 482/482/79 483/483/79 +f 481/481/79 482/482/79 480/480/79 +f 480/480/79 482/482/79 476/476/79 +f 480/480/79 476/476/79 479/479/79 +f 486/486/79 484/484/79 485/485/79 +f 476/476/79 477/477/79 479/479/79 +f 479/479/79 477/477/79 478/478/79 +f 344/344/1090 367/367/1091 347/347/1092 +f 347/347/1092 367/367/1091 365/365/1093 +f 354/354/1094 312/312/1095 355/355/1096 +f 355/355/1096 312/312/1095 311/311/1097 +f 312/312/1098 356/356/1099 416/416/1100 +f 356/356/1099 312/312/1098 354/354/1101 +f 312/312/1098 401/401/686 309/309/688 +f 401/401/686 312/312/1098 416/416/1100 +f 598/598/1102 599/599/1103 600/600/1104 +f 601/601/1105 602/602/1106 603/603/1107 +f 604/604/1108 605/605/1109 601/601/1105 +f 603/603/1107 602/602/1106 606/606/1110 +f 600/600/1104 607/607/1111 605/605/1109 +f 600/600/1104 599/599/1103 607/607/1111 +f 603/603/1107 608/608/1112 609/609/1113 +f 609/609/1113 608/608/1112 610/610/1114 +f 603/603/1107 606/606/1110 611/611/1115 +f 604/604/1108 601/601/1105 603/603/1107 +f 600/600/1104 605/605/1109 604/604/1108 +f 609/609/1113 610/610/1114 598/598/1102 +f 609/609/1113 598/598/1102 600/600/1104 +f 603/603/1107 611/611/1115 608/608/1112 +f 612/612/1116 613/613/1117 614/614/1118 +f 612/612/1116 615/615/1119 613/613/1117 +f 612/612/1116 616/616/1120 617/617/1121 +f 612/612/1116 614/614/1118 616/616/1120 +f 618/618/1122 619/619/1123 620/620/1124 +f 620/620/1124 619/619/1123 613/613/1125 +f 620/620/1126 613/613/1127 621/621/1128 +f 621/621/1128 613/613/1127 622/622/1129 +f 621/621/1130 622/622/1131 615/615/1132 +f 621/621/1130 615/615/1132 623/623/1133 +f 623/623/1134 615/615/1135 624/624/1136 +f 624/624/1136 615/615/1135 612/612/1137 +f 624/624/1138 612/612/1139 617/617/1140 +f 624/624/1138 617/617/1140 625/625/1141 +f 625/625/1141 617/617/1140 626/626/1142 +f 625/625/1141 626/626/1142 627/627/1143 +f 627/627/1143 626/626/1142 616/616/1144 +f 627/627/1143 616/616/1144 618/618/1145 +f 618/618/1145 616/616/1144 619/619/1146 +f 599/599/1147 618/618/1148 607/607/1149 +f 607/607/1149 618/618/1148 620/620/1150 +f 607/607/1149 620/620/1150 605/605/1151 +f 605/605/1151 620/620/1150 621/621/1152 +f 605/605/1151 621/621/1152 601/601/1153 +f 601/601/1153 621/621/1152 623/623/1154 +f 601/601/1153 623/623/1154 602/602/1155 +f 602/602/1155 623/623/1154 606/606/1156 +f 606/606/1156 623/623/1154 624/624/1157 +f 606/606/1156 624/624/1157 611/611/1158 +f 611/611/1158 624/624/1157 625/625/1159 +f 611/611/1158 625/625/1159 608/608/1160 +f 608/608/1160 625/625/1159 610/610/1161 +f 610/610/1161 625/625/1159 627/627/1162 +f 610/610/1161 627/627/1162 598/598/1163 +f 598/598/1163 627/627/1162 618/618/1148 +f 598/598/1163 618/618/1148 599/599/1147 +f 604/604/621 603/603/622 628/628/1164 +f 628/628/1164 603/603/622 629/629/1165 +f 600/600/625 604/604/626 630/630/1166 +f 630/630/1166 604/604/626 628/628/628 +f 609/609/629 600/600/1167 631/631/631 +f 631/631/631 600/600/1167 630/630/632 +f 603/603/633 609/609/634 629/629/635 +f 629/629/635 609/609/634 631/631/636 +f 628/628/1 629/629/1 630/630/1 +f 630/630/1 629/629/1 631/631/1 +f 619/619/1168 614/614/1168 613/613/1168 +f 622/622/1169 613/613/1117 615/615/1119 +f 626/626/1170 617/617/1121 616/616/1120 +f 616/616/1171 614/614/1171 619/619/1171 +f 632/632/1172 633/633/1173 634/634/1174 +f 635/635/1175 636/636/1176 637/637/1177 +f 638/638/1178 639/639/1179 640/640/1180 +f 637/637/1177 641/641/1181 642/642/1182 +f 643/643/1183 644/644/1184 645/645/1185 +f 637/637/1177 642/642/1182 635/635/1175 +f 632/632/1172 646/646/1186 647/647/1187 +f 637/637/1177 644/644/1184 643/643/1183 +f 638/638/1178 640/640/1180 637/637/1177 +f 637/637/1177 640/640/1180 641/641/1181 +f 632/632/1172 647/647/1187 638/638/1178 +f 638/638/1178 647/647/1187 639/639/1179 +f 634/634/1174 646/646/1186 632/632/1172 +f 645/645/1185 633/633/1173 643/643/1183 +f 643/643/1183 633/633/1173 632/632/1172 +f 637/637/1177 636/636/1176 644/644/1184 +f 648/648/1188 649/649/1189 650/650/1190 +f 651/651/1191 652/652/1192 650/650/1190 +f 650/650/1190 653/653/1193 651/651/1191 +f 650/650/1190 649/649/1189 653/653/1193 +f 654/654/1194 655/655/1195 648/648/1196 +f 654/654/1194 648/648/1196 656/656/1197 +f 656/656/1197 648/648/1196 650/650/1198 +f 656/656/1199 650/650/1200 657/657/1201 +f 657/657/1201 650/650/1200 658/658/1202 +f 657/657/1203 658/658/1204 652/652/1205 +f 657/657/1203 652/652/1205 659/659/1206 +f 659/659/1206 652/652/1205 651/651/1207 +f 659/659/1208 651/651/1209 660/660/1210 +f 659/659/1208 660/660/1210 661/661/1211 +f 661/661/1212 660/660/1213 662/662/1214 +f 661/661/1212 662/662/1214 663/663/1215 +f 663/663/1216 662/662/1217 655/655/1218 +f 663/663/1216 655/655/1218 654/654/1219 +f 634/634/1220 654/654/1221 646/646/1222 +f 646/646/1222 654/654/1221 647/647/1223 +f 647/647/1223 654/654/1221 656/656/1224 +f 647/647/1223 656/656/1224 639/639/1225 +f 639/639/1225 656/656/1224 657/657/1226 +f 639/639/1225 657/657/1226 640/640/1227 +f 640/640/1227 657/657/1226 641/641/1228 +f 641/641/1228 657/657/1226 642/642/1229 +f 642/642/1229 657/657/1226 659/659/1230 +f 642/642/1229 659/659/1230 635/635/1231 +f 635/635/1231 659/659/1230 636/636/1232 +f 636/636/1232 659/659/1230 644/644/1233 +f 644/644/1233 659/659/1230 661/661/1234 +f 644/644/1233 661/661/1234 645/645/1235 +f 645/645/1235 661/661/1234 663/663/1236 +f 645/645/1235 663/663/1236 633/633/1237 +f 633/633/1237 663/663/1236 654/654/1221 +f 633/633/1237 654/654/1221 634/634/1220 +f 638/638/621 637/637/1238 664/664/1239 +f 664/664/1239 637/637/1238 665/665/1240 +f 632/632/625 638/638/626 666/666/627 +f 666/666/627 638/638/626 664/664/628 +f 643/643/629 632/632/1241 667/667/631 +f 667/667/631 632/632/1241 666/666/632 +f 637/637/633 643/643/634 665/665/635 +f 665/665/635 643/643/634 667/667/636 +f 664/664/1 665/665/1 666/666/1 +f 666/666/1 665/665/1 667/667/1 +f 655/655/1242 649/649/1189 648/648/1188 +f 658/658/1243 650/650/1190 652/652/1192 +f 660/660/1244 651/651/1191 653/653/1193 +f 660/660/1213 653/653/1245 662/662/1214 +f 662/662/1246 653/653/1193 649/649/1189 +f 662/662/1217 649/649/1247 655/655/1218 +f 668/668/1248 669/669/1249 670/670/1250 +f 671/671/1251 672/672/1252 673/673/1253 +f 671/671/1251 674/674/1254 675/675/1255 +f 676/676/1256 677/677/1257 672/672/1252 +f 678/678/1258 679/679/1259 670/670/1250 +f 670/670/1250 669/669/1249 678/678/1258 +f 671/671/1251 675/675/1255 680/680/1260 +f 680/680/1260 675/675/1255 681/681/1261 +f 673/673/1253 674/674/1254 671/671/1251 +f 676/676/1256 672/672/1252 671/671/1251 +f 670/670/1250 679/679/1259 676/676/1256 +f 676/676/1256 679/679/1259 677/677/1257 +f 680/680/1260 681/681/1261 668/668/1248 +f 680/680/1260 668/668/1248 670/670/1250 +f 682/682/1262 683/683/1263 684/684/1264 +f 682/682/1262 685/685/1265 683/683/1263 +f 682/682/1262 686/686/1266 685/685/1265 +f 682/682/1262 687/687/1267 686/686/1266 +f 688/688/1268 689/689/1269 690/690/1270 +f 690/690/1271 689/689/1272 685/685/1273 +f 690/690/1271 685/685/1273 691/691/1274 +f 691/691/1274 685/685/1273 686/686/1275 +f 691/691/1276 686/686/1277 692/692/1278 +f 692/692/1278 686/686/1277 693/693/1279 +f 692/692/1280 693/693/1281 694/694/1282 +f 692/692/1280 694/694/1282 695/695/1283 +f 695/695/1284 694/694/1285 696/696/1286 +f 695/695/1284 696/696/1286 697/697/1287 +f 697/697/1288 696/696/1289 684/684/1290 +f 697/697/1288 684/684/1290 688/688/1291 +f 688/688/1268 684/684/1292 689/689/1269 +f 678/678/1293 690/690/1294 679/679/1295 +f 679/679/1295 690/690/1294 691/691/1296 +f 679/679/1295 691/691/1296 677/677/1297 +f 677/677/1297 691/691/1296 672/672/1298 +f 672/672/1298 691/691/1296 692/692/1299 +f 672/672/1298 692/692/1299 673/673/1300 +f 673/673/1300 692/692/1299 674/674/1301 +f 674/674/1301 692/692/1299 695/695/1302 +f 674/674/1301 695/695/1302 675/675/1303 +f 675/675/1303 695/695/1302 681/681/1304 +f 681/681/1304 695/695/1302 697/697/1305 +f 681/681/1304 697/697/1305 668/668/1306 +f 668/668/1306 697/697/1305 688/688/1307 +f 668/668/1306 688/688/1307 669/669/1308 +f 669/669/1308 688/688/1307 678/678/1293 +f 678/678/1293 688/688/1307 690/690/1294 +f 676/676/1309 671/671/1310 698/698/1311 +f 698/698/1311 671/671/1310 699/699/1312 +f 670/670/1313 676/676/1313 698/698/1313 +f 700/700/1314 670/670/1314 698/698/1314 +f 680/680/1315 670/670/1315 700/700/1315 +f 671/671/633 680/680/633 699/699/633 +f 699/699/1316 680/680/1316 700/700/1316 +f 698/698/1 699/699/1 700/700/1 +f 689/689/1317 683/683/1317 685/685/1317 +f 693/693/1318 686/686/1318 687/687/1318 +f 693/693/1281 687/687/1319 694/694/1282 +f 694/694/1320 687/687/1320 682/682/1320 +f 694/694/1285 682/682/1321 696/696/1286 +f 696/696/1322 682/682/1262 684/684/1264 +f 689/689/1323 684/684/1323 683/683/1323 +f 701/701/1324 702/702/1325 703/703/1326 +f 704/704/1327 705/705/1328 701/701/1324 +f 706/706/1329 707/707/1330 708/708/1331 +f 709/709/1332 710/710/1333 711/711/1334 +f 712/712/1335 713/713/1336 714/714/1337 +f 705/705/1328 702/702/1325 701/701/1324 +f 706/706/1329 710/710/1333 709/709/1332 +f 706/706/1329 708/708/1331 715/715/1338 +f 714/714/1337 713/713/1336 706/706/1329 +f 706/706/1329 713/713/1336 707/707/1330 +f 701/701/1324 703/703/1326 714/714/1337 +f 714/714/1337 703/703/1326 712/712/1335 +f 711/711/1334 704/704/1327 709/709/1332 +f 709/709/1332 704/704/1327 701/701/1324 +f 706/706/1329 715/715/1338 710/710/1333 +f 716/716/1339 717/717/1340 718/718/1341 +f 716/716/1339 719/719/1342 717/717/1340 +f 716/716/1339 720/720/1343 719/719/1342 +f 721/721/1344 720/720/1343 716/716/1339 +f 722/722/1345 723/723/1346 724/724/1347 +f 724/724/1347 723/723/1346 717/717/1348 +f 724/724/1347 717/717/1348 719/719/1349 +f 724/724/1347 719/719/1349 725/725/1350 +f 725/725/1350 719/719/1349 726/726/1351 +f 725/725/1352 726/726/1353 727/727/1354 +f 727/727/1354 726/726/1353 720/720/1355 +f 727/727/1356 720/720/1357 728/728/1358 +f 727/727/1356 728/728/1358 729/729/1359 +f 729/729/1360 728/728/1361 716/716/1362 +f 729/729/1360 716/716/1362 730/730/1363 +f 730/730/1363 716/716/1362 718/718/1364 +f 730/730/1363 718/718/1364 722/722/1365 +f 722/722/1365 718/718/1364 723/723/1366 +f 702/702/1367 722/722/1368 724/724/1369 +f 702/702/1367 724/724/1369 703/703/1370 +f 703/703/1370 724/724/1369 712/712/1371 +f 712/712/1371 724/724/1369 725/725/1372 +f 712/712/1371 725/725/1372 713/713/1373 +f 713/713/1373 725/725/1372 707/707/1374 +f 707/707/1374 725/725/1372 708/708/1375 +f 708/708/1375 725/725/1372 727/727/1376 +f 708/708/1375 727/727/1376 715/715/1377 +f 715/715/1377 727/727/1376 729/729/1378 +f 715/715/1377 729/729/1378 710/710/1379 +f 710/710/1379 729/729/1378 711/711/1380 +f 711/711/1380 729/729/1378 704/704/1381 +f 704/704/1381 729/729/1378 730/730/1382 +f 704/704/1381 730/730/1382 705/705/1383 +f 705/705/1383 730/730/1382 722/722/1368 +f 705/705/1383 722/722/1368 702/702/1367 +f 731/731/1384 706/706/1384 732/732/1384 +f 714/714/1385 706/706/1385 731/731/1385 +f 701/701/625 714/714/625 733/733/625 +f 733/733/1386 714/714/1386 731/731/1386 +f 709/709/1387 701/701/1388 732/732/1389 +f 732/732/1389 701/701/1388 733/733/1390 +f 706/706/1391 709/709/1391 732/732/1391 +f 733/733/1 731/731/1 732/732/1 +f 726/726/1392 719/719/1342 720/720/1343 +f 720/720/1357 721/721/1393 728/728/1358 +f 728/728/1394 721/721/1394 716/716/1394 +f 723/723/1395 718/718/1341 717/717/1340 +f 734/734/1396 735/735/1397 736/736/1398 +f 737/737/1399 738/738/1400 739/739/1401 +f 740/740/1402 741/741/1403 736/736/1398 +f 742/742/1404 743/743/1405 744/744/1406 +f 736/736/1398 741/741/1403 734/734/1396 +f 737/737/1399 745/745/1407 738/738/1400 +f 742/742/1404 746/746/1408 743/743/1405 +f 736/736/1398 735/735/1397 747/747/1409 +f 736/736/1398 747/747/1409 742/742/1404 +f 737/737/1399 739/739/1401 740/740/1402 +f 737/737/1399 740/740/1402 736/736/1398 +f 742/742/1404 744/744/1406 737/737/1399 +f 737/737/1399 744/744/1406 745/745/1407 +f 742/742/1404 747/747/1409 746/746/1408 +f 748/748/1410 749/749/1411 750/750/1412 +f 748/748/1410 751/751/1413 749/749/1411 +f 748/748/1410 752/752/1414 751/751/1413 +f 750/750/1412 753/753/1415 748/748/1410 +f 754/754/1416 750/750/1417 749/749/1418 +f 754/754/1416 749/749/1418 755/755/1419 +f 755/755/1419 749/749/1418 756/756/1420 +f 755/755/1419 756/756/1420 757/757/1421 +f 757/757/1422 756/756/1423 752/752/1424 +f 757/757/1422 752/752/1424 758/758/1425 +f 758/758/1425 752/752/1424 759/759/1426 +f 758/758/1427 759/759/1428 760/760/1429 +f 760/760/1429 759/759/1428 748/748/1430 +f 760/760/1431 748/748/1432 753/753/1433 +f 760/760/1431 753/753/1433 761/761/1434 +f 761/761/1435 753/753/1436 762/762/1437 +f 761/761/1435 762/762/1437 763/763/1438 +f 763/763/1439 762/762/1440 750/750/1441 +f 763/763/1439 750/750/1441 754/754/1442 +f 738/738/1443 754/754/1444 739/739/1445 +f 739/739/1445 754/754/1444 755/755/1446 +f 739/739/1445 755/755/1446 740/740/1447 +f 740/740/1447 755/755/1446 741/741/1448 +f 741/741/1448 755/755/1446 757/757/1449 +f 741/741/1448 757/757/1449 734/734/1450 +f 734/734/1450 757/757/1449 758/758/1451 +f 734/734/1450 758/758/1451 735/735/1452 +f 735/735/1452 758/758/1451 747/747/1453 +f 747/747/1453 758/758/1451 760/760/1454 +f 747/747/1453 760/760/1454 746/746/1455 +f 746/746/1455 760/760/1454 743/743/1456 +f 743/743/1456 760/760/1454 761/761/1457 +f 743/743/1456 761/761/1457 744/744/1458 +f 744/744/1458 761/761/1457 745/745/1459 +f 745/745/1459 761/761/1457 763/763/1460 +f 745/745/1459 763/763/1460 754/754/1444 +f 745/745/1459 754/754/1444 738/738/1443 +f 736/736/1461 742/742/1462 764/764/1463 +f 764/764/1463 742/742/1462 765/765/1464 +f 737/737/1465 736/736/1465 766/766/1465 +f 766/766/1466 736/736/1466 764/764/1466 +f 767/767/1467 737/737/1467 766/766/1467 +f 742/742/1468 737/737/1468 767/767/1468 +f 765/765/1469 742/742/1469 767/767/1469 +f 766/766/1 764/764/1 765/765/1 +f 766/766/1 765/765/1 767/767/1 +f 756/756/1470 749/749/1411 751/751/1413 +f 756/756/1423 751/751/1471 752/752/1424 +f 759/759/1472 752/752/1414 748/748/1410 +f 762/762/1473 753/753/1415 750/750/1412 +f 96/96/1474 144/144/2 161/161/2 +f 165/165/2 94/94/2 96/96/1474 +f 10/10/4 151/151/1475 11/11/5 +f 178/178/2 167/167/2 86/86/2 +f 96/96/1474 151/151/1475 154/154/2 +f 165/165/2 96/96/1474 163/163/2 +f 94/94/2 165/165/2 155/155/2 +f 151/151/1475 96/96/1474 11/11/5 +f 173/173/2 175/175/2 94/94/2 +f 92/92/1476 139/139/2 121/121/2 +f 163/163/2 96/96/1474 161/161/2 +f 100/100/2 159/159/2 146/146/2 +f 87/87/2 86/86/2 167/167/2 +f 146/146/2 159/159/2 144/144/2 +f 157/157/2 105/105/2 155/155/2 +f 169/169/2 87/87/2 167/167/2 +f 86/86/2 175/175/2 178/178/2 +f 92/92/1476 124/124/1477 12/12/6 +f 146/146/2 148/148/1478 101/101/1479 +f 171/171/2 87/87/2 169/169/2 +f 97/97/1480 102/102/1481 10/10/4 +f 102/102/1481 101/101/1479 10/10/4 +f 119/119/2 87/87/2 103/103/2 +f 105/105/2 104/104/2 87/87/2 +f 106/106/2 143/143/2 132/132/2 +f 105/105/2 171/171/2 173/173/2 +f 105/105/2 157/157/2 107/107/2 +f 107/107/2 141/141/2 143/143/2 +f 175/175/2 86/86/2 94/94/2 +f 103/103/2 87/87/2 104/104/2 +f 99/99/2 141/141/2 100/100/2 +f 106/106/2 132/132/2 115/115/2 +f 141/141/2 107/107/2 100/100/2 +f 9/9/3 98/98/2 97/97/1480 +f 10/10/4 9/9/3 97/97/1480 +f 130/130/2 99/99/2 9/9/3 +f 9/9/3 99/99/2 98/98/2 +f 12/12/6 128/128/1482 9/9/3 +f 128/128/1482 130/130/2 9/9/3 +f 119/119/2 110/110/2 87/87/2 +f 103/103/2 106/106/2 117/117/2 +f 157/157/2 159/159/2 107/107/2 +f 99/99/2 130/130/2 141/141/2 +f 106/106/2 107/107/2 143/143/2 +f 121/121/2 141/141/2 130/130/2 +f 121/121/2 139/139/2 141/141/2 +f 105/105/2 173/173/2 155/155/2 +f 117/117/2 106/106/2 115/115/2 +f 159/159/2 161/161/2 144/144/2 +f 94/94/2 155/155/2 173/173/2 +f 12/12/6 125/125/1483 128/128/1482 +f 159/159/2 100/100/2 107/107/2 +f 124/124/1477 92/92/1476 121/121/2 +f 113/113/2 115/115/2 91/91/2 +f 135/135/2 91/91/2 132/132/2 +f 111/111/2 89/89/2 110/110/2 +f 92/92/1476 137/137/2 139/139/2 +f 105/105/2 87/87/2 171/171/2 +f 96/96/1474 154/154/2 144/144/2 +f 137/137/2 91/91/2 135/135/2 +f 12/12/6 124/124/1477 125/125/1483 +f 111/111/2 113/113/2 89/89/2 +f 101/101/1479 148/148/1478 10/10/4 +f 101/101/1479 100/100/2 146/146/2 +f 117/117/2 119/119/2 103/103/2 +f 110/110/2 89/89/2 87/87/2 +f 91/91/2 115/115/2 132/132/2 +f 137/137/2 92/92/1476 91/91/2 +f 89/89/2 113/113/2 91/91/2 +f 8/8/729 7/7/729 1/1/729 +f 8/8/729 1/1/729 3/3/729 diff --git a/examples/Cassie/urdf/meshes/agility/pelvis.obj b/examples/Cassie/urdf/meshes/agility/pelvis.obj index 94f62d9246..f616aac0eb 100644 --- a/examples/Cassie/urdf/meshes/agility/pelvis.obj +++ b/examples/Cassie/urdf/meshes/agility/pelvis.obj @@ -1,46992 +1,51368 @@ -#### -# -# OBJ File Generated by Meshlab -# -#### -# Object pelvis.obj -# -# Vertices: 15983 -# Faces: 30993 -# -#### -v -0.005200 -0.078860 0.099115 -v -0.005200 -0.079803 0.101430 -v -0.005200 -0.081140 0.100885 -v -0.005200 -0.078663 0.100545 -v -0.005200 -0.081337 0.099455 -v -0.005195 -0.081681 0.098516 -v -0.003781 -0.076496 0.101374 -v -0.003000 -0.076842 0.102012 -v -0.003856 -0.078115 0.103176 -v -0.003001 -0.079013 0.103791 -v -0.003678 -0.080453 0.103804 -v -0.003000 -0.082423 0.103092 -v -0.003826 -0.082722 0.102535 -v -0.003632 -0.083933 0.100169 -v -0.003000 -0.083138 0.097930 -v -0.003000 -0.081001 0.096200 -v -0.003000 -0.077171 0.097169 -v -0.003570 -0.082612 0.097155 -v -0.003716 -0.079878 0.096167 -v -0.005200 -0.079166 0.098008 -v -0.003655 -0.077055 0.097495 -v -0.005189 -0.077760 0.099519 -v -0.003000 -0.076224 0.100102 -v -0.005207 -0.079418 0.102285 -v -0.005170 -0.082253 0.100721 -v -0.004000 -0.078663 0.100545 -v -0.004000 -0.081140 0.100885 -v -0.004000 -0.079803 0.101430 -v -0.004000 -0.081337 0.099455 -v -0.005200 -0.080197 0.098570 -v -0.004000 -0.080197 0.098570 -v -0.004000 -0.078860 0.099115 -v -0.005200 -0.080421 -0.006381 -v -0.005200 -0.079015 -0.006055 -v -0.005200 -0.079579 -0.003619 -v -0.005210 -0.081411 -0.005321 -v -0.005200 -0.080985 -0.003945 -v -0.003000 -0.076242 -0.004882 -v -0.003000 -0.083741 -0.004626 -v -0.003501 -0.078736 -0.008736 -v -0.003496 -0.076280 -0.006301 -v -0.003633 -0.083535 -0.006533 -v -0.005200 -0.081560 -0.006402 -v -0.003618 -0.081796 -0.008376 -v -0.005159 -0.079802 -0.007450 -v -0.005186 -0.077664 -0.005628 -v -0.003513 -0.076695 -0.002953 -v -0.005160 -0.078744 -0.002909 -v -0.003432 -0.079678 -0.001095 -v -0.005180 -0.080975 -0.002894 -v -0.003001 -0.082520 -0.001876 -v -0.004108 -0.083512 -0.004264 -v -0.005200 -0.078594 -0.004674 -v -0.004000 -0.078594 -0.004674 -v -0.004000 -0.080985 -0.003945 -v -0.004000 -0.080421 -0.006381 -v -0.004000 -0.079015 -0.006055 -v -0.004000 -0.081406 -0.005326 -v -0.004000 -0.079579 -0.003619 -v -0.005200 0.079015 -0.006055 -v -0.005202 0.081751 -0.003371 -v -0.005200 0.081406 -0.005326 -v -0.005200 0.080985 -0.003945 -v -0.005261 0.078578 -0.004671 -v -0.005200 0.079579 -0.003619 -v -0.003819 0.082584 -0.002310 -v -0.003001 0.076150 -0.003765 -v -0.003000 0.076348 -0.005611 -v -0.003000 0.077343 -0.007804 -v -0.003000 0.083426 -0.006547 -v -0.003001 0.078631 -0.001287 -v -0.003718 0.077625 -0.007961 -v -0.003830 0.076528 -0.006296 -v -0.005199 0.078817 -0.006782 -v -0.004496 0.080127 -0.008075 -v -0.003741 0.082756 -0.007667 -v -0.005204 0.081654 -0.006440 -v -0.003590 0.083865 -0.004629 -v -0.003002 0.081819 -0.001423 -v -0.003816 0.079538 -0.001284 -v -0.005152 0.077905 -0.003590 -v -0.004000 0.080985 -0.003945 -v -0.004000 0.081406 -0.005326 -v -0.005200 0.080421 -0.006381 -v -0.004000 0.079015 -0.006055 -v -0.004000 0.080421 -0.006381 -v -0.004000 0.078594 -0.004674 -v -0.004000 0.079579 -0.003619 -v -0.005200 0.081140 0.100885 -v -0.005260 0.080203 0.098548 -v -0.005200 0.081337 0.099455 -v -0.005200 0.078860 0.099115 -v -0.005200 0.078663 0.100545 -v -0.003000 0.083577 -0.004036 -v -0.003000 0.082289 -0.008084 -v -0.003000 -0.077292 -0.002101 -v -0.003028 0.079941 -0.008962 -v -0.003000 -0.082322 -0.008211 -v -0.003000 -0.077224 -0.007900 -v -0.003000 -0.083685 0.100385 -v -0.003000 0.082434 0.103191 -v -0.003000 0.077756 0.103280 -v -0.003000 0.082459 0.096828 -v -0.003660 0.076437 0.101470 -v -0.003644 0.076445 0.098498 -v -0.005193 0.078296 0.098496 -v -0.003845 0.078476 0.096592 -v -0.003605 0.080568 0.096232 -v -0.003634 0.082779 0.097295 -v -0.005021 0.082554 0.099670 -v -0.003000 0.083723 0.099960 -v -0.005201 0.081565 0.101506 -v -0.003838 0.079180 0.103698 -v -0.003841 0.082431 0.102976 -v -0.005183 0.078493 0.101733 -v -0.005201 0.077878 0.100019 -v -0.004000 0.081140 0.100885 -v -0.005200 0.079803 0.101430 -v -0.004000 0.079803 0.101430 -v -0.004000 0.078860 0.099115 -v -0.004000 0.080197 0.098570 -v -0.004000 0.081337 0.099455 -v -0.004000 0.078663 0.100545 -v -0.003000 0.077831 0.096682 -v -0.003000 0.076317 0.099917 -v 0.000000 -0.069506 0.047500 -v -0.004184 -0.069140 -0.013350 -v -0.005898 -0.068990 0.085836 -v -0.003630 -0.069188 0.075482 -v -0.003630 -0.069188 0.019518 -v -0.001613 -0.069365 0.024398 -v -0.005898 -0.068990 -0.009843 -v -0.021323 -0.066894 0.116238 -v -0.015417 -0.067951 0.112736 -v -0.005649 -0.068836 0.112841 -v -0.005898 -0.068968 0.110787 -v -0.003673 -0.068076 0.117851 -v -0.003586 -0.068042 0.118022 -v -0.029424 -0.064436 0.121385 -v -0.029633 -0.064281 0.121679 -v -0.001809 -0.067245 0.120916 -v -0.030925 -0.062704 0.124434 -v -0.001641 -0.067162 0.121170 -v -0.029856 -0.064116 0.121991 -v 0.000000 -0.066639 0.122760 -v -0.030375 -0.063582 0.122964 -v -0.031472 -0.061140 0.126695 -v 0.000000 -0.064128 0.127235 -v -0.031327 -0.058901 0.129337 -v -0.031494 -0.059764 0.128416 -v -0.031632 -0.060387 0.127650 -v -0.030691 -0.055109 0.132823 -v -0.030743 -0.055478 0.132538 -v 0.000000 -0.060923 0.131243 -v -0.030278 -0.051545 0.135104 -v -0.005776 0.069000 0.083703 -v -0.001613 0.069365 0.070602 -v -0.005898 0.068990 0.009164 -v -0.003630 0.069188 0.019518 -v -0.010131 0.068619 -0.024813 -v 0.000000 0.069130 -0.031598 -v -0.021482 0.067227 -0.031378 -v -0.019308 0.066094 -0.038945 -v -0.024068 0.066776 -0.033369 -v -0.017773 0.065977 -0.040071 -v 0.000000 0.067764 -0.039345 -v -0.011896 -0.048546 -0.077901 -v -0.011760 -0.050579 -0.076432 -v 0.000000 -0.049890 -0.078252 -v 0.000000 -0.052556 -0.076035 -v -0.011349 -0.053770 -0.073179 -v 0.000000 -0.056657 -0.070472 -v -0.068658 -0.026889 -0.079513 -v -0.064167 -0.024790 -0.081096 -v -0.066230 -0.042693 -0.067865 -v -0.069868 -0.041471 -0.066876 -v -0.075365 -0.039489 -0.065256 -v -0.076231 -0.037760 -0.068011 -v -0.067744 -0.023712 -0.080069 -v -0.086160 -0.020712 -0.073379 -v -0.084120 -0.018118 -0.074450 -v -0.079486 -0.019807 -0.076220 -v -0.080472 -0.022852 -0.075586 -v -0.077481 -0.020497 -0.076911 -v -0.075856 -0.039312 -0.065111 -v -0.082063 -0.035484 -0.066058 -v -0.087678 -0.033128 -0.063973 -v -0.091661 -0.018542 -0.070998 -v -0.085160 -0.017738 -0.074052 -v -0.097508 -0.029953 -0.056851 -v -0.096931 -0.016397 -0.068438 -v -0.090667 -0.015643 -0.071710 -v -0.100586 -0.011770 -0.066704 -v -0.101300 -0.014601 -0.066055 -v -0.065968 -0.041344 -0.071021 -v -0.065842 -0.039438 -0.073813 -v -0.070344 -0.037944 -0.072530 -v -0.070217 -0.039924 -0.069829 -v -0.076374 -0.035792 -0.070669 -v -0.087874 -0.031186 -0.066519 -v -0.093030 -0.030735 -0.061758 -v -0.093268 -0.028805 -0.064230 -v -0.098057 -0.028366 -0.059426 -v -0.098350 -0.026447 -0.061808 -v -0.102473 -0.024466 -0.059599 -v -0.105995 -0.022744 -0.057480 -v -0.076279 -0.033459 -0.073015 -v -0.087815 -0.028914 -0.068784 -v -0.087504 -0.026369 -0.070712 -v -0.093246 -0.026565 -0.066439 -v -0.102402 -0.019876 -0.063444 -v -0.109177 -0.019176 -0.057365 -v -0.064917 -0.031403 -0.079749 -v -0.074631 -0.024920 -0.077628 -v -0.086947 -0.023612 -0.072256 -v -0.092433 -0.021372 -0.069863 -v -0.097665 -0.019155 -0.067298 -v -0.101976 -0.017297 -0.064921 -v -0.105734 -0.015685 -0.062594 -v -0.105133 -0.013047 -0.063711 -v -0.108927 -0.014353 -0.060370 -v -0.101505 -0.027979 -0.054847 -v -0.102115 -0.026378 -0.057313 -v -0.105563 -0.024652 -0.055302 -v -0.104882 -0.026269 -0.052959 -v -0.108398 -0.023225 -0.053447 -v -0.108914 -0.021318 -0.055502 -v -0.111332 -0.020148 -0.053668 -v -0.106169 -0.020583 -0.059446 -v -0.102569 -0.022283 -0.061658 -v -0.098382 -0.024238 -0.063946 -v -0.082145 -0.031227 -0.070976 -v -0.082227 -0.033529 -0.068665 -v -0.070246 -0.035583 -0.074907 -v -0.111510 -0.018003 -0.055622 -v -0.109181 -0.016839 -0.058998 -v -0.106081 -0.018214 -0.061163 -v -0.098152 -0.021789 -0.065790 -v -0.092965 -0.024068 -0.068332 -v -0.081257 -0.025819 -0.074480 -v -0.075397 -0.027952 -0.076541 -v -0.081819 -0.028635 -0.072931 -v -0.075951 -0.030823 -0.074990 -v -0.069391 -0.029980 -0.078446 -v -0.069926 -0.032904 -0.076897 -v -0.065390 -0.034375 -0.078214 -v -0.108419 -0.011767 -0.061455 -v -0.117911 -0.005236 -0.052230 -v -0.120650 -0.006262 -0.042119 -v -0.120370 -0.006744 -0.044972 -v -0.119996 -0.008596 -0.045591 -v -0.120184 -0.009176 -0.043072 -v -0.119328 -0.010893 -0.046433 -v -0.117548 -0.014663 -0.048046 -v -0.116646 -0.016067 -0.048723 -v -0.114785 -0.019605 -0.047396 -v -0.113870 -0.019317 -0.050488 -v -0.116348 -0.005501 -0.054514 -v -0.114504 -0.008745 -0.056398 -v -0.113215 -0.006772 -0.057795 -v -0.112475 -0.007310 -0.058458 -v -0.119490 -0.007960 -0.048051 -v -0.118322 -0.013230 -0.047399 -v -0.117708 -0.012543 -0.049951 -v -0.115396 -0.017719 -0.049561 -v -0.114108 -0.017296 -0.052662 -v -0.110619 -0.008146 -0.060010 -v -0.111884 -0.010563 -0.058757 -v -0.116930 -0.008240 -0.053359 -v -0.119132 -0.005279 -0.049792 -v -0.116439 -0.012192 -0.052702 -v -0.115185 -0.011081 -0.055049 -v -0.113372 -0.015726 -0.055086 -v -0.113085 -0.013210 -0.056772 -v -0.111765 -0.013265 -0.058122 -v -0.111810 -0.015723 -0.056921 -v -0.118534 -0.007767 -0.050598 -v -0.117660 -0.010019 -0.051552 -v -0.118881 -0.009940 -0.048797 -v -0.116519 -0.014446 -0.050939 -v -0.115143 -0.013896 -0.053786 -v -0.115423 -0.015893 -0.051767 -v -0.112855 -0.018428 -0.053451 -v -0.112423 -0.020595 -0.051275 -v -0.113102 -0.021299 -0.048238 -v -0.110726 -0.022065 -0.051730 -v -0.109874 -0.023721 -0.049673 -v -0.065165 -0.043038 -0.068144 -v -0.060759 -0.029657 -0.081365 -v -0.062614 -0.031010 -0.080618 -v -0.063863 -0.028376 -0.080904 -v -0.061975 -0.027394 -0.081532 -v -0.063123 -0.025094 -0.081385 -v -0.065693 -0.037076 -0.076222 -v -0.062836 -0.038837 -0.075930 -v -0.065387 -0.035953 -0.077124 -v -0.062398 -0.036524 -0.077990 -v -0.062614 -0.033865 -0.079481 -v -0.119740 0.004898 -0.048164 -v -0.116929 0.003110 -0.053780 -v -0.114979 -0.001200 -0.056101 -v -0.117029 -0.001277 -0.053665 -v -0.118661 0.001931 -0.050960 -v -0.118677 -0.001351 -0.050941 -v -0.119869 0.002032 -0.048011 -v -0.119883 -0.001422 -0.047995 -v -0.120605 0.002126 -0.044910 -v -0.119996 -0.005678 -0.047240 -v -0.120618 -0.001488 -0.044897 -v -0.120556 -0.005160 -0.044507 -v -0.055898 -0.039500 -0.077408 -v -0.056808 -0.041503 -0.075422 -v -0.063752 -0.040586 -0.073602 -v -0.062842 -0.043991 -0.068049 -v -0.058881 -0.045614 -0.067888 -v -0.052682 -0.047904 -0.067648 -v -0.064572 -0.041988 -0.070980 -v -0.054907 -0.037244 -0.079056 -v -0.048298 -0.037381 -0.079816 -v -0.053857 -0.034784 -0.080332 -v -0.043974 -0.041827 -0.078083 -v -0.043181 -0.039512 -0.079388 -v -0.046978 -0.049791 -0.067456 -v -0.040680 -0.050530 -0.069781 -v -0.058316 -0.044593 -0.070612 -v -0.051574 -0.045543 -0.072722 -v -0.052183 -0.046892 -0.070275 -v -0.046545 -0.048786 -0.070005 -v -0.023313 -0.053040 -0.071783 -v -0.029162 -0.053283 -0.069567 -v -0.034889 -0.052025 -0.069631 -v -0.036896 -0.052584 -0.067241 -v -0.038526 -0.043721 -0.077702 -v -0.037855 -0.041465 -0.079014 -v -0.032593 -0.043129 -0.078731 -v -0.027385 -0.044517 -0.078554 -v -0.022221 -0.045638 -0.078490 -v -0.017302 -0.048629 -0.077234 -v -0.050866 -0.043883 -0.074940 -v -0.050074 -0.041943 -0.076885 -v -0.033659 -0.047363 -0.075820 -v -0.034126 -0.049172 -0.073969 -v -0.022840 -0.049750 -0.075602 -v -0.017488 -0.050582 -0.075670 -v -0.017842 -0.055120 -0.069724 -v -0.023485 -0.054312 -0.069595 -v -0.028225 -0.048680 -0.075654 -v -0.022547 -0.047782 -0.077174 -v -0.027823 -0.046688 -0.077237 -v -0.033145 -0.045338 -0.077416 -v -0.039154 -0.045790 -0.076092 -v -0.044720 -0.043949 -0.076460 -v -0.049212 -0.039762 -0.078521 -v -0.060822 -0.034366 -0.079626 -v -0.017642 -0.052332 -0.073879 -v -0.023097 -0.051512 -0.073795 -v -0.028900 -0.052004 -0.071788 -v -0.028586 -0.050461 -0.073827 -v -0.034538 -0.050735 -0.071895 -v -0.039729 -0.047635 -0.074213 -v -0.040241 -0.049224 -0.072097 -v -0.045406 -0.045838 -0.074548 -v -0.046017 -0.047460 -0.072384 -v -0.057620 -0.043213 -0.073141 -v -0.017760 -0.053852 -0.071887 -v -0.010230 -0.000063 -0.090615 -v -0.062620 -0.024856 -0.081514 -v -0.057501 -0.030535 -0.081491 -v -0.052501 -0.027239 -0.083010 -v -0.038864 -0.015155 -0.086776 -v -0.039473 -0.013929 -0.086713 -v -0.030227 -0.011704 -0.088151 -v -0.030665 -0.010838 -0.088153 -v -0.027951 -0.008480 -0.088549 -v -0.022636 -0.005961 -0.089290 -v -0.021212 -0.006155 -0.089450 -v -0.022250 -0.006730 -0.089318 -v -0.038241 -0.016375 -0.086750 -v -0.046186 -0.021026 -0.085108 -v -0.047002 -0.019446 -0.085172 -v -0.053542 -0.025362 -0.083344 -v -0.054551 -0.023441 -0.083455 -v -0.012557 -0.001553 -0.090399 -v -0.020856 -0.006857 -0.089449 -v -0.111492 0.011056 -0.058999 -v -0.113268 0.009935 -0.057506 -v -0.112199 0.020774 -0.051391 -v -0.114557 0.019853 -0.047520 -v -0.116958 0.016800 -0.046072 -v -0.118229 0.013417 -0.047481 -v -0.118248 0.014577 -0.045115 -v -0.113621 0.006383 -0.057420 -v -0.118892 0.011976 -0.046868 -v -0.119602 0.011299 -0.043830 -v -0.112032 0.013942 -0.057599 -v -0.117658 0.006297 -0.052551 -v -0.115412 0.007593 -0.055507 -v -0.118518 0.004654 -0.051134 -v -0.112257 0.016580 -0.055879 -v -0.114075 0.012283 -0.056005 -v -0.116161 0.009737 -0.054129 -v -0.119050 0.005728 -0.049908 -v -0.119186 0.009062 -0.048440 -v -0.118393 0.008222 -0.050757 -v -0.117501 0.010353 -0.051710 -v -0.116533 0.012048 -0.052616 -v -0.116035 0.015111 -0.051312 -v -0.115143 0.013888 -0.053794 -v -0.113862 0.015220 -0.054755 -v -0.112661 0.018587 -0.053568 -v -0.113658 0.019518 -0.050608 -v -0.113925 0.017474 -0.052781 -v -0.114968 0.018182 -0.049836 -v -0.115060 0.016297 -0.052019 -v -0.116091 0.016828 -0.049110 -v -0.117262 0.015162 -0.048273 -v -0.117052 0.013664 -0.050512 -v -0.118176 0.011614 -0.049515 -v -0.119871 0.006249 -0.047483 -v -0.120481 0.005124 -0.045038 -v -0.119681 0.009819 -0.046014 -v -0.120197 0.009045 -0.043031 -v -0.120418 0.007992 -0.042672 -v -0.120653 0.006222 -0.042106 -v -0.120328 0.007065 -0.045000 -v -0.012149 -0.054440 -0.072125 -v -0.011252 -0.055313 -0.070888 -v -0.010539 -0.056270 -0.069154 -v -0.011665 -0.051965 -0.075185 -v -0.012097 -0.055721 -0.069966 -v -0.012033 -0.051190 -0.075872 -v -0.011948 -0.052956 -0.074091 -v -0.011964 -0.047115 -0.078729 -v -0.012035 -0.049235 -0.077424 -v -0.108677 0.008793 -0.061471 -v -0.109181 0.016839 -0.058998 -v -0.096931 0.016397 -0.068438 -v -0.087678 0.033128 -0.063973 -v -0.064167 0.024790 -0.081096 -v -0.064903 0.031407 -0.079753 -v -0.065387 0.035953 -0.077124 -v -0.065520 0.037123 -0.076260 -v -0.066589 0.036784 -0.075963 -v -0.066230 0.042693 -0.067865 -v -0.066565 0.041149 -0.070847 -v -0.070344 0.037944 -0.072530 -v -0.065828 0.039447 -0.073813 -v -0.065386 0.034376 -0.078215 -v -0.068658 0.026889 -0.079513 -v -0.064290 0.028247 -0.080780 -v -0.070217 0.039924 -0.069829 -v -0.076231 0.037760 -0.068011 -v -0.070246 0.035583 -0.074907 -v -0.069926 0.032904 -0.076897 -v -0.075951 0.030823 -0.074990 -v -0.069391 0.029980 -0.078446 -v -0.074631 0.024920 -0.077628 -v -0.067744 0.023712 -0.080069 -v -0.081656 0.037042 -0.063221 -v -0.082063 0.035484 -0.066058 -v -0.076374 0.035792 -0.070669 -v -0.076279 0.033459 -0.073015 -v -0.080472 0.022852 -0.075586 -v -0.075397 0.027952 -0.076541 -v -0.073675 0.021807 -0.078222 -v -0.087234 0.034693 -0.061207 -v -0.082227 0.033529 -0.068665 -v -0.087815 0.028914 -0.068784 -v -0.082145 0.031227 -0.070976 -v -0.087504 0.026369 -0.070712 -v -0.081819 0.028635 -0.072931 -v -0.081257 0.025819 -0.074480 -v -0.086160 0.020712 -0.073379 -v -0.084120 0.018118 -0.074450 -v -0.087500 0.034574 -0.061101 -v -0.087874 0.031186 -0.066519 -v -0.093268 0.028805 -0.064230 -v -0.093246 0.026565 -0.066439 -v -0.092965 0.024068 -0.068332 -v -0.086947 0.023612 -0.072256 -v -0.091661 0.018542 -0.070998 -v -0.090192 0.015824 -0.071912 -v -0.085160 0.017738 -0.074052 -v -0.092433 0.021372 -0.069863 -v -0.097665 0.019155 -0.067298 -v -0.098152 0.021789 -0.065790 -v -0.093030 0.030735 -0.061758 -v -0.099189 0.029123 -0.056008 -v -0.097508 0.029953 -0.056851 -v -0.101976 0.017297 -0.064921 -v -0.102569 0.022283 -0.061658 -v -0.108927 0.014353 -0.060370 -v -0.108914 0.021318 -0.055502 -v -0.100586 0.011770 -0.066704 -v -0.105133 0.013047 -0.063711 -v -0.108419 0.011767 -0.061455 -v -0.107667 0.009129 -0.062232 -v -0.105734 0.015685 -0.062594 -v -0.106081 0.018214 -0.061163 -v -0.105995 0.022744 -0.057480 -v -0.106169 0.020583 -0.059446 -v -0.109177 0.019176 -0.057365 -v -0.111482 0.019474 -0.054251 -v -0.100387 0.011846 -0.066823 -v -0.101300 0.014601 -0.066055 -v -0.102402 0.019876 -0.063444 -v -0.098382 0.024238 -0.063946 -v -0.098350 0.026447 -0.061808 -v -0.098057 0.028366 -0.059426 -v -0.102473 0.024466 -0.059599 -v -0.102115 0.026378 -0.057313 -v -0.101505 0.027979 -0.054847 -v -0.105563 0.024652 -0.055302 -v -0.108398 0.023225 -0.053447 -v -0.104882 0.026269 -0.052959 -v -0.110766 0.021811 -0.052108 -v -0.109874 0.023721 -0.049673 -v -0.062614 0.033865 -0.079481 -v -0.062398 0.036524 -0.077990 -v -0.060822 0.034366 -0.079626 -v -0.065562 0.038161 -0.075215 -v -0.062614 0.031010 -0.080618 -v -0.062484 0.027644 -0.081399 -v -0.057501 0.030535 -0.081491 -v -0.060759 0.029662 -0.081364 -v -0.062620 0.024856 -0.081514 -v -0.054551 0.023441 -0.083455 -v -0.052501 0.027239 -0.083010 -v -0.045350 0.022582 -0.084892 -v -0.046186 0.021026 -0.085108 -v -0.038864 0.015155 -0.086776 -v -0.039473 0.013929 -0.086713 -v -0.047002 0.019446 -0.085172 -v -0.047792 0.017854 -0.085084 -v -0.038241 0.016375 -0.086750 -v -0.030227 0.011704 -0.088151 -v -0.029783 0.012566 -0.088103 -v -0.027951 0.008480 -0.088549 -v -0.031097 0.009971 -0.088110 -v -0.037066 0.012791 -0.087114 -v -0.022121 0.006987 -0.089322 -v -0.020856 0.006857 -0.089449 -v -0.012557 0.001553 -0.090399 -v -0.012717 0.001237 -0.090387 -v -0.010131 0.000000 -0.090624 -v -0.022636 0.005961 -0.089290 -v -0.030665 0.010838 -0.088153 -v -0.053542 0.025362 -0.083344 -v -0.018672 0.004074 -0.089738 -v -0.021212 0.006155 -0.089450 -v -0.065165 0.043038 -0.068144 -v -0.062842 0.043991 -0.068049 -v -0.064540 0.042002 -0.070977 -v -0.062837 0.038837 -0.075930 -v -0.054907 0.037244 -0.079056 -v -0.049212 0.039762 -0.078521 -v -0.048298 0.037381 -0.079816 -v -0.043974 0.041827 -0.078083 -v -0.058881 0.045614 -0.067888 -v -0.046545 0.048786 -0.070005 -v -0.041040 0.051530 -0.067304 -v -0.036896 0.052584 -0.067241 -v -0.063760 0.040582 -0.073602 -v -0.058316 0.044593 -0.070612 -v -0.057620 0.043213 -0.073141 -v -0.052183 0.046892 -0.070275 -v -0.051574 0.045543 -0.072722 -v -0.046017 0.047460 -0.072384 -v -0.040680 0.050530 -0.069781 -v -0.034889 0.052025 -0.069631 -v -0.034539 0.050735 -0.071895 -v -0.029162 0.053283 -0.069567 -v -0.023313 0.053040 -0.071783 -v -0.023485 0.054312 -0.069595 -v -0.017760 0.053852 -0.071887 -v -0.055898 0.039500 -0.077408 -v -0.050074 0.041943 -0.076885 -v -0.039729 0.047635 -0.074213 -v -0.034126 0.049172 -0.073969 -v -0.028586 0.050461 -0.073827 -v -0.023097 0.051512 -0.073795 -v -0.028225 0.048680 -0.075654 -v -0.017642 0.052332 -0.073879 -v -0.022840 0.049750 -0.075602 -v -0.035173 0.053023 -0.067215 -v -0.029367 0.054279 -0.067199 -v -0.023610 0.055308 -0.067266 -v -0.017842 0.055120 -0.069724 -v -0.011993 0.054462 -0.072124 -v -0.028900 0.052004 -0.071788 -v -0.040241 0.049224 -0.072097 -v -0.045406 0.045838 -0.074548 -v -0.050866 0.043883 -0.074940 -v -0.056808 0.041503 -0.075422 -v -0.017488 0.050582 -0.075670 -v -0.044720 0.043949 -0.076460 -v -0.039154 0.045790 -0.076092 -v -0.038526 0.043721 -0.077702 -v -0.033659 0.047363 -0.075820 -v -0.037855 0.041465 -0.079014 -v -0.033145 0.045338 -0.077416 -v -0.032593 0.043129 -0.078731 -v -0.027823 0.046688 -0.077237 -v -0.022547 0.047782 -0.077174 -v -0.022221 0.045638 -0.078490 -v -0.017302 0.048629 -0.077234 -v -0.017086 0.046502 -0.078546 -v -0.011542 0.053753 -0.073174 -v -0.011817 0.051958 -0.075174 -v -0.011853 0.053892 -0.072980 -v -0.012039 0.049233 -0.077424 -v -0.011974 0.050574 -0.076413 -v -0.012117 0.051183 -0.075867 -v -0.012050 0.052941 -0.074092 -v -0.012007 0.055730 -0.069970 -v -0.016221 0.067983 -0.028345 -v -0.010228 0.068611 -0.024870 -v -0.010235 0.068610 -0.024851 -v -0.025806 0.066743 -0.031992 -v -0.026202 0.066424 -0.034135 -v -0.024368 0.066920 -0.031383 -v -0.024209 0.065959 -0.037494 -v -0.025616 0.065706 -0.037627 -v -0.010131 0.064964 -0.045546 -v -0.018651 0.065328 -0.041825 -v -0.018215 0.065677 -0.040956 -v -0.012531 0.065334 -0.043843 -v -0.023435 0.066409 -0.035921 -v -0.010131 -0.064964 -0.045546 -v -0.010216 -0.064969 -0.045511 -v -0.012669 -0.065228 -0.044115 -v -0.018215 -0.065677 -0.040956 -v -0.024938 -0.066922 -0.031383 -v -0.024209 -0.065959 -0.037494 -v -0.010228 -0.068611 -0.024870 -v -0.016677 -0.067973 -0.027144 -v -0.038841 -0.055412 0.130099 -v -0.039248 -0.049810 0.133491 -v -0.039447 -0.052084 0.132164 -v -0.035318 -0.054610 0.132274 -v -0.037613 -0.051900 0.133158 -v -0.036092 -0.057289 0.129776 -v -0.037043 -0.054827 0.131513 -v -0.037090 -0.060716 0.125048 -v -0.035284 -0.059089 0.128212 -v -0.032712 -0.058786 0.129294 -v -0.028783 -0.064773 0.120740 -v -0.028270 -0.064972 0.120372 -v -0.034130 -0.064526 0.118724 -v -0.032929 -0.064323 0.120339 -v -0.031435 -0.065360 0.117907 -v -0.029746 -0.065360 0.118792 -v -0.029837 -0.066053 0.115599 -v -0.033892 -0.063323 0.122254 -v -0.035465 -0.063257 0.121277 -v -0.030924 -0.064672 0.120380 -v -0.030053 -0.063937 0.122323 -v -0.030664 -0.063175 0.123666 -v -0.031739 -0.063943 0.121857 -v -0.031071 -0.062382 0.124935 -v -0.031284 -0.061804 0.125785 -v -0.034887 -0.062027 0.124253 -v -0.032602 -0.062739 0.123989 -v -0.034258 -0.060969 0.126228 -v -0.036563 -0.061975 0.123274 -v -0.023219 -0.066370 0.117366 -v -0.014184 -0.068171 0.112005 -v -0.010131 -0.068619 0.109630 -v -0.014289 -0.068220 0.110990 -v -0.014488 -0.068206 0.110402 -v -0.012968 -0.068357 0.110136 -v -0.010241 -0.068610 0.109650 -v -0.029626 -0.066257 0.112816 -v -0.021894 -0.067293 0.113214 -v -0.028761 -0.065722 0.117922 -v -0.021615 -0.067151 0.114735 -v -0.038912 0.046545 0.134907 -v -0.038235 0.049665 0.134008 -v -0.039885 0.047403 0.134129 -v -0.036274 0.051790 0.133701 -v -0.037889 0.051960 0.133001 -v -0.039451 0.052059 0.132178 -v -0.035284 0.059089 0.128212 -v -0.038841 0.055412 0.130099 -v -0.037075 0.054815 0.131509 -v -0.032712 0.058786 0.129294 -v -0.036092 0.057288 0.129776 -v -0.028761 0.065722 0.117922 -v -0.028270 0.064972 0.120372 -v -0.030581 0.064913 0.119850 -v -0.030826 0.066015 0.114134 -v -0.033426 0.064953 0.117662 -v -0.029633 0.064281 0.121679 -v -0.030375 0.063582 0.122964 -v -0.030664 0.063175 0.123666 -v -0.030925 0.062704 0.124434 -v -0.031071 0.062382 0.124935 -v -0.036042 0.062526 0.122500 -v -0.034723 0.063406 0.121586 -v -0.036641 0.061106 0.124743 -v -0.031548 0.065285 0.118092 -v -0.033026 0.064292 0.120368 -v -0.034216 0.060988 0.126216 -v -0.032182 0.063464 0.122773 -v -0.034280 0.061965 0.124684 -v -0.031632 0.060387 0.127650 -v -0.029216 0.066153 0.115390 -v -0.010131 0.068619 0.109630 -v -0.014184 0.068171 0.112005 -v -0.014287 0.068197 0.111471 -v -0.015417 0.067951 0.112736 -v -0.021894 0.067293 0.113214 -v -0.014488 0.068206 0.110402 -v -0.012969 0.068357 0.110136 -v -0.021615 0.067151 0.114735 -v -0.021323 0.066894 0.116238 -v -0.033671 -0.056999 0.130811 -v -0.037175 -0.049569 0.134462 -v -0.031095 -0.057704 0.130615 -v -0.030760 -0.055598 0.132447 -v -0.036945 -0.048881 0.134825 -v -0.036421 -0.047587 0.135479 -v -0.032740 -0.053032 0.133907 -v -0.030471 -0.053372 0.134031 -v -0.030295 -0.051737 0.135006 -v -0.032405 -0.051263 0.134958 -v -0.030154 -0.050189 0.135798 -v -0.030052 -0.048843 0.136394 -v -0.032198 -0.049865 0.135667 -v -0.034165 -0.048299 0.135903 -v -0.034644 -0.050426 0.134866 -v -0.035113 -0.052102 0.133880 -v -0.033150 -0.055064 0.132467 -v -0.032170 -0.047971 0.136459 -v -0.038567 -0.044922 0.135432 -v -0.039398 -0.041531 0.135590 -v -0.037242 -0.042809 0.136359 -v -0.023431 -0.038002 0.140842 -v -0.026758 -0.030913 0.141748 -v -0.019258 -0.015750 0.145442 -v -0.021484 -0.014835 0.144778 -v -0.020322 -0.018556 0.144942 -v -0.022585 -0.017475 0.144274 -v -0.021557 -0.021398 0.144352 -v -0.025442 -0.023071 0.142927 -v -0.017549 -0.018409 0.145592 -v -0.019177 -0.022624 0.144759 -v -0.023084 -0.024510 0.143607 -v -0.018146 -0.027279 0.144084 -v -0.016748 -0.023813 0.144897 -v -0.014641 -0.017526 0.146086 -v -0.019608 -0.030529 0.143214 -v -0.020643 -0.025918 0.143994 -v -0.027247 -0.026068 0.142049 -v -0.019744 -0.030834 0.143133 -v -0.022318 -0.029298 0.143098 -v -0.024830 -0.027703 0.142735 -v -0.028911 -0.028583 0.141219 -v -0.031410 -0.032101 0.139941 -v -0.021509 -0.034409 0.142053 -v -0.024169 -0.032698 0.142082 -v -0.028859 -0.034139 0.140641 -v -0.031125 -0.037378 0.139412 -v -0.036248 -0.038166 0.137345 -v -0.026186 -0.036116 0.140943 -v -0.033546 -0.040626 0.138059 -v -0.035908 -0.045465 0.136313 -v -0.033742 -0.045937 0.136769 -v -0.025503 -0.041610 0.139497 -v -0.028360 -0.039550 0.139678 -v -0.030683 -0.042996 0.138283 -v -0.053580 -0.061517 0.101752 -v -0.073039 -0.034775 0.116842 -v -0.101802 -0.025525 0.093966 -v -0.106757 -0.023625 0.089171 -v -0.042633 -0.045515 0.133302 -v -0.039701 -0.043611 0.135198 -v -0.041835 -0.041555 0.134426 -v -0.039552 -0.046962 0.134484 -v -0.042634 -0.049402 0.131851 -v -0.042346 -0.053039 0.129876 -v -0.039066 -0.054261 0.130898 -v -0.041774 -0.056337 0.127424 -v -0.037758 -0.059110 0.126886 -v -0.038337 -0.057336 0.128580 -v -0.040934 -0.059215 0.124557 -v -0.039845 -0.061603 0.121343 -v -0.032948 -0.065263 0.116779 -v -0.035381 -0.065306 0.110445 -v -0.030671 -0.066060 0.113937 -v -0.031779 -0.065730 0.115307 -v -0.037034 -0.064686 0.114199 -v -0.105180 -0.041502 0.077329 -v -0.107049 -0.040650 0.075528 -v -0.109591 -0.035423 0.079849 -v -0.108571 -0.038167 0.077685 -v -0.108266 -0.033265 0.083822 -v -0.110278 -0.032391 0.081769 -v -0.110561 -0.027324 0.084149 -v -0.103345 -0.028668 0.091932 -v -0.108513 -0.026607 0.086849 -v -0.103123 -0.035408 0.088844 -v -0.108577 -0.030013 0.085489 -v -0.102457 -0.038471 0.086845 -v -0.107587 -0.036302 0.081881 -v -0.106551 -0.039065 0.079703 -v -0.098418 -0.045729 0.079511 -v -0.103499 -0.043565 0.074806 -v -0.101540 -0.045216 0.072180 -v -0.098013 -0.030684 0.096845 -v -0.103421 -0.032119 0.090551 -v -0.098098 -0.034181 0.095446 -v -0.097812 -0.037507 0.093702 -v -0.101437 -0.041248 0.084593 -v -0.100081 -0.043683 0.082132 -v -0.091257 -0.049428 0.081229 -v -0.096478 -0.047346 0.076782 -v -0.094302 -0.048501 0.073998 -v -0.092520 -0.032648 0.101586 -v -0.097160 -0.040596 0.091647 -v -0.090705 -0.045470 0.093891 -v -0.096154 -0.043386 0.089323 -v -0.094816 -0.045819 0.086777 -v -0.087766 -0.049908 0.088452 -v -0.085878 -0.051453 0.085519 -v -0.093173 -0.047846 0.084061 -v -0.086697 -0.051420 0.080224 -v -0.089108 -0.050531 0.078338 -v -0.083760 -0.052503 0.082523 -v -0.078262 -0.054410 0.086554 -v -0.080342 -0.053414 0.089652 -v -0.089386 -0.047900 0.091262 -v -0.083793 -0.049918 0.095587 -v -0.091694 -0.042669 0.096285 -v -0.086063 -0.044679 0.100758 -v -0.086691 -0.041539 0.102917 -v -0.092334 -0.039554 0.098393 -v -0.086961 -0.038138 0.104729 -v -0.092611 -0.036190 0.100172 -v -0.086867 -0.034550 0.106154 -v -0.086411 -0.030850 0.107163 -v -0.092062 -0.028999 0.102604 -v -0.081147 -0.040017 0.109115 -v -0.080882 -0.043454 0.107274 -v -0.085090 -0.047492 0.098297 -v -0.076471 -0.053833 0.096758 -v -0.082199 -0.051907 0.092684 -v -0.081054 -0.036383 0.110550 -v -0.080265 -0.046619 0.105066 -v -0.077596 -0.049996 0.103744 -v -0.076329 -0.052417 0.100932 -v -0.079309 -0.049443 0.102540 -v -0.078035 -0.051865 0.099750 -v -0.074774 -0.054379 0.097914 -v -0.074650 -0.055303 0.093629 -v -0.071799 -0.056496 0.090964 -v -0.079333 -0.036903 0.111797 -v -0.079425 -0.040550 0.110359 -v -0.079161 -0.043997 0.108510 -v -0.072691 -0.048959 0.110277 -v -0.078547 -0.047169 0.106288 -v -0.071758 -0.051797 0.107672 -v -0.067090 -0.036321 0.120697 -v -0.071612 -0.035146 0.117767 -v -0.073472 -0.038592 0.115863 -v -0.067319 -0.047434 0.116385 -v -0.073558 -0.042282 0.114419 -v -0.073296 -0.045764 0.112543 -v -0.066723 -0.050652 0.114078 -v -0.070516 -0.054213 0.104786 -v -0.068994 -0.056154 0.101683 -v -0.067226 -0.057576 0.098433 -v -0.055441 -0.060751 0.105258 -v -0.059463 -0.060033 0.098516 -v -0.061436 -0.041680 0.123411 -v -0.067505 -0.040186 0.119733 -v -0.061499 -0.045454 0.121960 -v -0.067582 -0.043919 0.118285 -v -0.061234 -0.049002 0.120039 -v -0.060645 -0.052242 0.117691 -v -0.059748 -0.055098 0.114973 -v -0.058562 -0.057503 0.111947 -v -0.065807 -0.053499 0.111415 -v -0.064593 -0.055910 0.108457 -v -0.063107 -0.057830 0.105272 -v -0.057115 -0.059402 0.108683 -v -0.061384 -0.059215 0.101933 -v -0.065251 -0.058447 0.095109 -v -0.072965 -0.055838 0.094756 -v -0.047604 -0.062894 0.104817 -v -0.049401 -0.062178 0.108410 -v -0.052426 -0.058986 0.115257 -v -0.053581 -0.056587 0.118349 -v -0.054460 -0.053723 0.121120 -v -0.055042 -0.050463 0.123504 -v -0.055266 -0.043070 0.126897 -v -0.052032 -0.039682 0.129335 -v -0.054903 -0.039113 0.127826 -v -0.043265 -0.063491 0.111390 -v -0.041289 -0.064204 0.107824 -v -0.038534 -0.063442 0.117862 -v -0.046186 -0.060355 0.118389 -v -0.047309 -0.057961 0.121543 -v -0.048169 -0.055090 0.124364 -v -0.041537 -0.064158 0.107714 -v -0.051021 -0.060865 0.111918 -v -0.044827 -0.062213 0.114977 -v -0.048745 -0.051810 0.126783 -v -0.055313 -0.046883 0.125445 -v -0.049024 -0.048201 0.128742 -v -0.048998 -0.044350 0.130194 -v -0.042341 -0.041473 0.134192 -v -0.011082 -0.003672 0.147520 -v -0.012762 -0.003119 0.147329 -v -0.020708 -0.012673 0.145130 -v -0.018508 -0.013454 0.145790 -v -0.011923 -0.003396 0.147439 -v -0.014672 -0.008629 0.146878 -v -0.016235 -0.014182 0.146242 -v -0.013954 -0.014970 0.146465 -v -0.114593 -0.032795 0.069434 -v -0.114593 -0.029708 0.075718 -v -0.114593 -0.031734 0.072813 -v -0.115578 -0.027834 0.074068 -v -0.112695 -0.028481 0.080732 -v -0.110618 -0.025584 0.084708 -v -0.112667 -0.024176 0.082287 -v -0.112695 -0.026416 0.081677 -v -0.110597 -0.029160 0.083411 -v -0.110355 -0.034205 0.080002 -v -0.103520 -0.044352 0.070296 -v -0.104908 -0.043404 0.070856 -v -0.107620 -0.041497 0.070769 -v -0.105511 -0.042674 0.072853 -v -0.110355 -0.039141 0.067663 -v -0.108626 -0.040780 0.067663 -v -0.107620 -0.040792 0.073803 -v -0.110355 -0.038934 0.070376 -v -0.112695 -0.030379 0.079485 -v -0.112695 -0.032066 0.077964 -v -0.110355 -0.035927 0.077895 -v -0.112695 -0.033503 0.076205 -v -0.112695 -0.034657 0.074249 -v -0.110355 -0.037308 0.075551 -v -0.112695 -0.035500 0.072140 -v -0.110355 -0.038319 0.073026 -v -0.112695 -0.036187 0.067663 -v -0.114593 -0.026905 0.077883 -v -0.114593 -0.028389 0.076907 -v -0.114593 -0.030832 0.074343 -v -0.114593 -0.032393 0.071164 -v -0.112695 -0.036014 0.069928 -v -0.101313 -0.045579 0.067663 -v -0.104544 -0.043912 0.067663 -v -0.107525 -0.041811 -0.001018 -v -0.105164 -0.043473 0.067663 -v -0.108626 -0.040780 -0.001018 -v -0.107620 -0.041734 0.067663 -v -0.111609 -0.037565 -0.001018 -v -0.111605 -0.037563 0.067663 -v -0.114035 -0.033912 -0.001018 -v -0.114024 -0.033906 0.067663 -v -0.114593 -0.032930 0.067663 -v -0.115351 -0.027283 0.075623 -v -0.115893 -0.029159 0.070150 -v -0.117390 -0.025022 0.066674 -v -0.117941 -0.022994 0.066317 -v -0.112697 -0.023212 0.082492 -v -0.111559 -0.017892 0.084460 -v -0.117867 -0.022037 0.070268 -v -0.120296 -0.010136 0.064770 -v -0.119923 -0.011009 0.068742 -v -0.120557 -0.007652 0.064596 -v -0.115905 -0.009224 0.079536 -v -0.120596 0.007167 0.064570 -v -0.116265 0.005749 0.079197 -v -0.113910 0.005339 0.082257 -v -0.115958 0.008800 0.079486 -v -0.115513 0.011898 0.079904 -v -0.120335 0.006862 0.068431 -v -0.111898 0.016708 0.084147 -v -0.114938 0.014959 0.080439 -v -0.114280 -0.025472 0.079234 -v -0.113888 -0.019281 0.081408 -v -0.114848 -0.015382 0.080523 -v -0.115445 -0.012303 0.079968 -v -0.117302 -0.013153 0.076583 -v -0.117776 -0.009860 0.076158 -v -0.116233 -0.006138 0.079228 -v -0.118113 -0.006561 0.075854 -v -0.116429 -0.003038 0.079042 -v -0.118315 -0.003248 0.075672 -v -0.116493 0.000082 0.078982 -v -0.118329 0.002887 0.075659 -v -0.116443 0.002701 0.079030 -v -0.117372 0.012720 0.076520 -v -0.114231 0.018004 0.081093 -v -0.113389 0.021036 0.081864 -v -0.115665 -0.026336 0.075358 -v -0.115698 -0.020715 0.078004 -v -0.117192 -0.020945 0.074125 -v -0.116688 -0.016446 0.077129 -v -0.119125 -0.010460 0.072533 -v -0.119478 -0.006960 0.072239 -v -0.119689 -0.003445 0.072062 -v -0.118380 0.000087 0.075613 -v -0.119704 0.003062 0.072050 -v -0.118146 0.006145 0.075824 -v -0.117830 0.009407 0.076109 -v -0.119182 0.009979 0.072486 -v -0.118702 0.013493 0.072885 -v -0.116781 0.015994 0.077047 -v -0.118083 0.016966 0.073396 -v -0.117320 0.020422 0.074021 -v -0.116053 0.019252 0.077691 -v -0.115185 0.022497 0.078451 -v -0.116412 0.023864 0.074758 -v -0.119473 0.014201 0.069078 -v -0.119983 0.010503 0.068696 -v -0.120538 0.003224 0.068278 -v -0.119512 0.006519 0.072210 -v -0.119758 0.000093 0.072004 -v -0.120596 0.000098 0.068234 -v -0.120523 -0.003627 0.068289 -v -0.120298 -0.007326 0.068459 -v -0.119395 -0.014684 0.069137 -v -0.118628 -0.013953 0.072946 -v -0.118711 -0.018358 0.069645 -v -0.117986 -0.017446 0.073476 -v -0.117354 -0.023986 0.070643 -v -0.116709 -0.022800 0.074517 -v -0.116246 -0.027699 0.071449 -v -0.115934 -0.028659 0.071664 -v -0.117039 0.025104 0.070874 -v -0.118960 0.018636 0.065652 -v -0.118815 0.017853 0.069568 -v -0.118004 0.021487 0.070167 -v -0.118088 0.022422 0.066222 -v -0.114455 -0.033207 -0.001018 -v -0.104492 -0.043788 -0.003668 -v -0.104492 -0.043943 -0.001018 -v -0.105163 -0.043472 -0.001018 -v -0.107525 -0.041250 -0.005787 -v -0.107525 -0.041671 -0.003419 -v -0.110230 -0.038785 -0.005199 -v -0.112505 -0.035985 -0.004546 -v -0.112555 -0.036287 -0.002786 -v -0.110230 -0.039154 -0.003123 -v -0.110230 -0.039277 -0.001018 -v -0.112555 -0.036390 -0.001018 -v -0.114455 -0.033126 -0.002414 -v -0.114593 0.026905 0.077883 -v -0.104539 0.043490 0.071635 -v -0.107620 0.041497 0.070769 -v -0.105485 0.042688 0.072879 -v -0.106287 0.041704 0.074060 -v -0.107620 0.040792 0.073803 -v -0.110355 0.038319 0.073026 -v -0.107742 0.039610 0.076330 -v -0.110355 0.034205 0.080002 -v -0.112695 0.028481 0.080732 -v -0.112695 0.026416 0.081677 -v -0.110601 0.029161 0.083406 -v -0.112680 0.024298 0.082230 -v -0.112412 0.024044 0.082749 -v -0.114175 0.025723 0.079330 -v -0.114579 0.026249 0.078060 -v -0.114593 0.028389 0.076907 -v -0.115369 0.027249 0.075592 -v -0.114593 0.031734 0.072813 -v -0.115941 0.028600 0.071710 -v -0.114593 0.032795 0.069434 -v -0.115871 0.029538 0.068902 -v -0.114593 0.032930 0.067663 -v -0.104544 0.043650 0.071099 -v -0.104544 0.043912 0.067663 -v -0.107173 0.040618 0.075363 -v -0.107620 0.041734 0.067663 -v -0.108626 0.040780 0.067663 -v -0.110279 0.032391 0.081767 -v -0.112695 0.030379 0.079485 -v -0.110355 0.035926 0.077895 -v -0.112695 0.034657 0.074249 -v -0.110355 0.037308 0.075551 -v -0.112695 0.035500 0.072140 -v -0.112695 0.036014 0.069928 -v -0.110355 0.038934 0.070376 -v -0.112695 0.032066 0.077964 -v -0.114593 0.029708 0.075718 -v -0.114593 0.030832 0.074343 -v -0.112695 0.033503 0.076205 -v -0.114593 0.032393 0.071164 -v -0.112695 0.036187 0.067663 -v -0.029237 -0.066317 -0.029533 -v -0.024881 -0.066954 -0.030020 -v -0.024952 -0.066573 -0.034595 -v -0.025616 -0.065706 -0.037627 -v -0.104505 -0.043362 -0.006075 -v -0.100969 -0.043941 -0.012011 -v -0.099710 -0.045469 -0.009537 -v -0.099187 -0.044703 -0.013193 -v -0.089116 -0.050335 -0.012814 -v -0.093743 -0.048529 -0.009990 -v -0.096648 -0.047547 -0.004404 -v -0.101313 -0.045579 -0.001018 -v -0.103017 -0.044633 -0.003552 -v -0.091543 -0.047868 -0.018010 -v -0.095116 -0.047390 -0.012582 -v -0.085600 -0.051079 -0.018141 -v -0.079535 -0.053792 -0.017943 -v -0.084381 -0.052090 -0.015465 -v -0.092212 -0.049331 -0.007361 -v -0.087497 -0.049427 -0.020275 -v -0.081666 -0.051567 -0.023299 -v -0.080675 -0.052840 -0.020658 -v -0.075362 -0.053704 -0.026183 -v -0.074576 -0.055435 -0.020250 -v -0.078263 -0.054409 -0.015190 -v -0.061781 -0.059232 -0.025232 -v -0.060829 -0.059670 -0.022356 -v -0.071322 -0.055005 -0.027887 -v -0.070476 -0.056172 -0.025174 -v -0.065198 -0.057736 -0.027174 -v -0.062628 -0.058458 -0.028070 -v -0.063361 -0.057358 -0.030831 -v -0.058009 -0.058802 -0.032546 -v -0.057354 -0.059861 -0.029755 -v -0.055732 -0.060989 -0.023983 -v -0.051333 -0.061871 -0.028369 -v -0.050568 -0.062227 -0.025435 -v -0.046595 -0.062401 -0.032594 -v -0.041530 -0.062569 -0.036613 -v -0.036897 -0.063440 -0.037436 -v -0.035896 -0.063628 -0.037613 -v -0.030191 -0.064583 -0.038435 -v -0.029615 -0.066081 -0.032554 -v -0.029688 -0.065544 -0.035547 -v -0.035147 -0.065169 -0.031767 -v -0.035557 -0.064566 -0.034730 -v -0.041111 -0.063531 -0.033750 -v -0.040611 -0.064161 -0.030808 -v -0.046006 -0.063061 -0.029675 -v -0.052009 -0.061176 -0.031263 -v -0.056591 -0.060594 -0.026888 -v -0.064308 -0.058532 -0.024352 -v -0.069502 -0.057017 -0.022386 -v -0.075634 -0.054539 -0.023002 -v -0.090413 -0.049262 -0.015449 -v -0.098263 -0.046677 -0.006989 -v -0.120297 -0.010136 -0.033087 -v -0.120413 -0.009212 -0.034716 -v -0.111666 -0.022473 -0.048926 -v -0.114972 -0.021937 -0.039957 -v -0.117484 -0.015961 -0.045704 -v -0.116462 -0.017523 -0.046400 -v -0.115291 -0.019028 -0.047112 -v -0.117052 -0.019068 -0.038741 -v -0.118352 -0.014367 -0.045029 -v -0.119154 -0.012551 -0.044304 -v -0.119738 -0.010868 -0.043672 -v -0.120503 -0.007459 -0.042498 -v -0.114867 -0.031063 -0.009461 -v -0.114430 -0.033047 -0.002786 -v -0.113280 -0.033345 -0.010747 -v -0.113565 -0.034563 -0.003672 -v -0.112002 -0.036659 -0.004959 -v -0.110183 -0.038569 -0.006198 -v -0.108130 -0.040269 -0.007375 -v -0.106890 -0.038890 -0.014224 -v -0.109264 -0.037285 -0.013144 -v -0.111403 -0.035428 -0.011980 -v -0.114426 -0.029948 -0.016956 -v -0.116032 -0.027473 -0.015670 -v -0.118609 -0.020146 -0.016065 -v -0.108511 -0.033095 -0.026794 -v -0.111115 -0.031209 -0.025758 -v -0.110269 -0.034232 -0.019336 -v -0.115406 -0.026577 -0.023395 -v -0.112495 -0.032212 -0.018184 -v -0.117291 -0.024824 -0.014344 -v -0.118254 -0.021057 -0.020776 -v -0.118184 -0.022039 -0.012998 -v -0.117097 -0.026030 -0.006799 -v -0.116145 -0.028614 -0.008139 -v -0.114865 -0.032274 -0.002335 -v -0.116335 -0.022756 -0.031032 -v -0.113426 -0.029024 -0.024619 -v -0.117025 -0.023907 -0.022107 -v -0.119075 -0.018073 -0.019422 -v -0.112474 -0.024498 -0.041068 -v -0.111895 -0.027790 -0.033376 -v -0.114302 -0.025415 -0.032251 -v -0.118672 -0.015948 -0.037445 -v -0.117958 -0.019859 -0.029741 -v -0.119799 -0.012641 -0.036094 -v -0.119142 -0.016778 -0.028400 -v -0.114455 0.033207 -0.001018 -v -0.114035 0.033912 -0.001018 -v -0.114024 0.033906 0.067663 -v -0.112555 0.036390 -0.001018 -v -0.111605 0.037563 0.067663 -v -0.110230 0.039277 -0.001018 -v -0.110355 0.039141 0.067663 -v -0.108626 0.040780 -0.001018 -v -0.107525 0.041811 -0.001018 -v -0.105164 0.043473 0.067663 -v -0.101313 0.045579 -0.001018 -v -0.101313 0.045579 0.067663 -v -0.067536 0.040178 0.119714 -v -0.078918 0.033127 0.112768 -v -0.092881 0.048793 0.079877 -v -0.099671 0.030069 0.095351 -v -0.037787 0.059098 0.126881 -v -0.038340 0.057334 0.128579 -v -0.041784 0.056335 0.127420 -v -0.039078 0.054226 0.130918 -v -0.039719 0.049779 0.133252 -v -0.042644 0.049400 0.131847 -v -0.042642 0.045513 0.133297 -v -0.039914 0.041963 0.135307 -v -0.035391 0.065304 0.110441 -v -0.032400 0.065476 0.116152 -v -0.031779 0.065730 0.115307 -v -0.034447 0.064243 0.119364 -v -0.039854 0.061601 0.121339 -v -0.104953 0.028037 0.090386 -v -0.110528 0.025756 0.084777 -v -0.105026 0.031474 0.089010 -v -0.110561 0.027324 0.084149 -v -0.108586 0.038162 0.077662 -v -0.109591 0.035423 0.079849 -v -0.101669 0.043016 0.080670 -v -0.100000 0.045067 0.078079 -v -0.098054 0.046694 0.075382 -v -0.103520 0.044352 0.070296 -v -0.094804 0.047200 0.082677 -v -0.098808 0.039948 0.090186 -v -0.103030 0.040580 0.083104 -v -0.104055 0.037807 0.085334 -v -0.104725 0.034752 0.087315 -v -0.099754 0.033551 0.093958 -v -0.087548 0.050837 0.084217 -v -0.096454 0.045167 0.085365 -v -0.091073 0.047267 0.089900 -v -0.097798 0.042733 0.087884 -v -0.093392 0.042038 0.094877 -v -0.094036 0.038931 0.096969 -v -0.099464 0.036866 0.092225 -v -0.083924 0.051301 0.091402 -v -0.089445 0.049281 0.087119 -v -0.085527 0.049306 0.094277 -v -0.092398 0.044836 0.092504 -v -0.087809 0.044069 0.099403 -v -0.088441 0.040936 0.101546 -v -0.088713 0.037547 0.103348 -v -0.094315 0.035579 0.098738 -v -0.094226 0.032050 0.100147 -v -0.093768 0.028418 0.101167 -v -0.076410 0.054733 0.092427 -v -0.082058 0.052820 0.088400 -v -0.086831 0.046878 0.096962 -v -0.088619 0.033973 0.104771 -v -0.082852 0.035830 0.109222 -v -0.072995 0.055828 0.094736 -v -0.074805 0.054369 0.097893 -v -0.078242 0.053251 0.095527 -v -0.079816 0.051277 0.098492 -v -0.081097 0.048853 0.101258 -v -0.082059 0.046032 0.103764 -v -0.082679 0.042875 0.105957 -v -0.082945 0.039450 0.107790 -v -0.065281 0.058438 0.095090 -v -0.070548 0.054203 0.104766 -v -0.076360 0.052407 0.100910 -v -0.077627 0.049986 0.103722 -v -0.071789 0.051787 0.107651 -v -0.078578 0.047159 0.106266 -v -0.079192 0.043987 0.108487 -v -0.073590 0.042273 0.114398 -v -0.079456 0.040540 0.110337 -v -0.079364 0.036893 0.111774 -v -0.059492 0.060026 0.098499 -v -0.061414 0.059207 0.101916 -v -0.067257 0.057566 0.098414 -v -0.069025 0.056144 0.101663 -v -0.065838 0.053491 0.111396 -v -0.066754 0.050644 0.114059 -v -0.067350 0.047426 0.116366 -v -0.072723 0.048950 0.110256 -v -0.073328 0.045754 0.112522 -v -0.073503 0.038583 0.115841 -v -0.071612 0.035146 0.117767 -v -0.053607 0.061511 0.101737 -v -0.056643 0.060745 0.100067 -v -0.063137 0.057822 0.105254 -v -0.064623 0.055902 0.108439 -v -0.067613 0.043911 0.118266 -v -0.061464 0.041674 0.123394 -v -0.055469 0.060744 0.105243 -v -0.049424 0.062172 0.108398 -v -0.057143 0.059395 0.108668 -v -0.052449 0.058981 0.115245 -v -0.058590 0.057496 0.111931 -v -0.059776 0.055090 0.114957 -v -0.060674 0.052235 0.117675 -v -0.061262 0.048995 0.120022 -v -0.061527 0.045447 0.121944 -v -0.054926 0.039108 0.127813 -v -0.047627 0.062889 0.104806 -v -0.051045 0.060860 0.111906 -v -0.048187 0.055086 0.124355 -v -0.053605 0.056581 0.118336 -v -0.054484 0.053717 0.121107 -v -0.048763 0.051806 0.126774 -v -0.049041 0.048197 0.128733 -v -0.055066 0.050457 0.123491 -v -0.055336 0.046878 0.125432 -v -0.052032 0.039682 0.129335 -v -0.055290 0.043065 0.126884 -v -0.037044 0.064684 0.114195 -v -0.038544 0.063440 0.117858 -v -0.043282 0.063488 0.111382 -v -0.044845 0.062209 0.114969 -v -0.046204 0.060351 0.118380 -v -0.040943 0.059214 0.124552 -v -0.047327 0.057957 0.121534 -v -0.042355 0.053037 0.129872 -v -0.049015 0.044346 0.130185 -v -0.104527 0.043352 -0.006066 -v -0.114455 0.033126 -0.002414 -v -0.107525 0.041250 -0.005787 -v -0.104492 0.043788 -0.003668 -v -0.104492 0.043943 -0.001018 -v -0.105163 0.043472 -0.001018 -v -0.110230 0.038785 -0.005199 -v -0.112555 0.036287 -0.002786 -v -0.110230 0.039154 -0.003123 -v -0.107525 0.041671 -0.003419 -v -0.115849 0.029915 -0.001018 -v -0.111609 0.037565 -0.001018 -v -0.031327 0.058901 0.129337 -v -0.033704 0.056976 0.130823 -v -0.039637 0.043457 0.135260 -v -0.036945 0.048881 0.134825 -v -0.035329 0.053921 0.132720 -v -0.034749 0.055101 0.132059 -v -0.031494 0.059764 0.128416 -v -0.031095 0.057704 0.130615 -v -0.038385 0.044731 0.135539 -v -0.035113 0.052102 0.133880 -v -0.033150 0.055064 0.132467 -v -0.030760 0.055598 0.132447 -v -0.032736 0.053070 0.133899 -v -0.032405 0.051263 0.134958 -v -0.034285 0.048999 0.135584 -v -0.034056 0.047878 0.136071 -v -0.036468 0.047703 0.135428 -v -0.034650 0.050469 0.134853 -v -0.030691 0.055109 0.132823 -v -0.030471 0.053372 0.134031 -v -0.037242 0.042809 0.136359 -v -0.035671 0.044753 0.136540 -v -0.036019 0.046376 0.135996 -v -0.033987 0.046309 0.136615 -v -0.032198 0.049865 0.135667 -v -0.119058 0.012775 -0.044393 -v -0.120056 0.009718 -0.043260 -v -0.120722 0.005325 -0.041833 -v -0.118691 0.015826 -0.037691 -v -0.119817 0.012512 -0.036340 -v -0.117522 0.015877 -0.045668 -v -0.114990 0.021828 -0.040203 -v -0.117071 0.018953 -0.038987 -v -0.115832 0.018365 -0.046793 -v -0.112489 0.024396 -0.041314 -v -0.113069 0.021324 -0.048243 -v -0.111412 0.022665 -0.049037 -v -0.110265 0.038369 -0.006559 -v -0.113652 0.034341 -0.004033 -v -0.115027 0.031836 -0.003075 -v -0.116018 0.029421 -0.001739 -v -0.115059 0.030506 -0.010406 -v -0.112174 0.036237 -0.005681 -v -0.109431 0.036810 -0.014087 -v -0.108206 0.040079 -0.007735 -v -0.107904 0.035528 -0.021371 -v -0.112650 0.031716 -0.019167 -v -0.111583 0.034928 -0.012925 -v -0.113468 0.032817 -0.011692 -v -0.116335 0.028026 -0.009084 -v -0.118612 0.020147 -0.016058 -v -0.118334 0.021423 -0.013979 -v -0.117278 0.025411 -0.007744 -v -0.111215 0.030812 -0.026623 -v -0.115524 0.026134 -0.024263 -v -0.114350 0.025192 -0.032735 -v -0.117143 0.023438 -0.022974 -v -0.118368 0.020561 -0.021642 -v -0.110411 0.033761 -0.020317 -v -0.113537 0.028606 -0.025486 -v -0.114588 0.029424 -0.017940 -v -0.116197 0.026919 -0.016653 -v -0.117452 0.024238 -0.015326 -v -0.119190 0.016513 -0.028883 -v -0.120426 0.009076 -0.034961 -v -0.118009 0.019609 -0.030224 -v -0.116386 0.022520 -0.031516 -v -0.109619 0.026603 -0.042297 -v -0.111938 0.027578 -0.033859 -v -0.109193 0.029635 -0.034868 -v -0.024963 0.065356 -0.039025 -v -0.030143 0.064590 -0.038441 -v -0.029887 0.065508 -0.035540 -v -0.024881 0.066954 -0.030020 -v -0.025768 0.066824 -0.029921 -v -0.029191 0.066324 -0.029539 -v -0.029569 0.066088 -0.032560 -v -0.098709 0.046689 -0.002945 -v -0.100362 0.045787 -0.005508 -v -0.094317 0.048495 -0.005988 -v -0.089811 0.050262 -0.008861 -v -0.086699 0.051424 -0.010681 -v -0.091297 0.049495 -0.011513 -v -0.105867 0.041740 -0.008475 -v -0.101844 0.044545 -0.008034 -v -0.099191 0.044706 -0.013204 -v -0.093791 0.046968 -0.016669 -v -0.088938 0.048884 -0.019498 -v -0.086589 0.051283 -0.014258 -v -0.078853 0.052545 -0.024637 -v -0.071796 0.056488 -0.018132 -v -0.074905 0.055515 -0.016778 -v -0.075360 0.053701 -0.026177 -v -0.072160 0.055651 -0.024490 -v -0.071158 0.056512 -0.021713 -v -0.070038 0.057038 -0.018898 -v -0.066120 0.058015 -0.023691 -v -0.065090 0.058493 -0.020842 -v -0.056644 0.060750 -0.023684 -v -0.060062 0.059875 -0.022614 -v -0.061000 0.059443 -0.025494 -v -0.061835 0.058676 -0.028336 -v -0.054953 0.061182 -0.024214 -v -0.050513 0.062061 -0.028582 -v -0.049763 0.062412 -0.025645 -v -0.039695 0.064338 -0.030981 -v -0.044491 0.063559 -0.026906 -v -0.051742 0.060354 -0.034301 -v -0.050003 0.060746 -0.034721 -v -0.051176 0.061372 -0.031480 -v -0.039137 0.064622 -0.027996 -v -0.033700 0.065596 -0.028916 -v -0.034159 0.065340 -0.031921 -v -0.040180 0.063713 -0.033927 -v -0.045720 0.062588 -0.032791 -v -0.045146 0.063243 -0.029868 -v -0.056547 0.060067 -0.029995 -v -0.055798 0.060793 -0.027124 -v -0.067039 0.057203 -0.026502 -v -0.077550 0.053905 -0.022138 -v -0.076461 0.054822 -0.019399 -v -0.082937 0.052044 -0.019531 -v -0.081761 0.053022 -0.016833 -v -0.087845 0.050244 -0.016915 -v -0.092630 0.048391 -0.014128 -v -0.097296 0.046490 -0.011168 -v -0.095888 0.047661 -0.008597 -v -0.103021 0.044631 -0.003546 -v -0.040586 0.062755 -0.036794 -v -0.034553 0.064741 -0.034887 -v -0.026084 0.066075 -0.035979 -v -0.032905 0.034060 0.139156 -v -0.030729 0.036823 0.139629 -v -0.038886 0.041192 0.135862 -v -0.030333 0.030630 0.140498 -v -0.030052 0.048843 0.136394 -v -0.028218 0.046023 0.137670 -v -0.032047 0.047665 0.136579 -v -0.025854 0.042182 0.139261 -v -0.025527 0.041650 0.139481 -v -0.024755 0.040334 0.139988 -v -0.025184 0.034452 0.141513 -v -0.019622 0.030525 0.143202 -v -0.021178 0.027035 0.143710 -v -0.018657 0.028453 0.143783 -v -0.017103 0.024734 0.144692 -v -0.019550 0.023500 0.144566 -v -0.015775 0.021120 0.145451 -v -0.034096 0.041339 0.137745 -v -0.031211 0.043752 0.137960 -v -0.027960 0.038943 0.139922 -v -0.027816 0.032568 0.141194 -v -0.025596 0.029012 0.142346 -v -0.023054 0.030684 0.142698 -v -0.023642 0.025565 0.143331 -v -0.021946 0.022225 0.144164 -v -0.019407 0.016170 0.145373 -v -0.018158 0.020065 0.145281 -v -0.028039 0.027296 0.141657 -v -0.026018 0.024062 0.142649 -v -0.024265 0.020924 0.143489 -v -0.022765 0.017872 0.144191 -v -0.020495 0.018979 0.144860 -v -0.014778 0.017993 0.146010 -v -0.017113 0.017094 0.145808 -v -0.012762 0.003119 0.147329 -v -0.011923 0.003396 0.147439 -v -0.010148 0.000022 0.147653 -v -0.013954 0.014970 0.146465 -v -0.016250 0.014222 0.146237 -v -0.014672 0.008629 0.146878 -v -0.011082 0.003672 0.147520 -v -0.018508 0.013454 0.145790 -v -0.031382 0.028517 0.140200 -v -0.023863 -0.020146 0.143678 -v -0.033750 -0.035131 0.138705 -v -0.031382 -0.028517 0.140200 -v -0.048668 -0.040349 0.131103 -v -0.061044 -0.037769 0.124358 -v -0.052045 -0.027875 0.130287 -v -0.080774 -0.032581 0.111421 -v -0.071623 -0.027104 0.118383 -v -0.078887 -0.033136 0.112790 -v -0.080945 -0.026672 0.111720 -v -0.097557 -0.027088 0.097870 -v -0.089908 -0.029705 0.104342 -v -0.112508 -0.014277 0.083578 -v -0.102896 -0.025123 0.092961 -v -0.108075 -0.023114 0.087878 -v -0.110243 -0.021914 0.085668 -v -0.113554 -0.008564 0.082594 -v -0.112997 -0.011911 0.083120 -v -0.113606 0.008171 0.082545 -v -0.114110 0.001273 0.082066 -v -0.114073 -0.002822 0.082102 -v -0.106749 0.023623 0.089163 -v -0.110102 0.022300 0.085796 -v -0.111066 0.019516 0.084915 -v -0.112597 0.013885 0.083495 -v -0.106773 0.012610 0.089700 -v -0.104508 0.024509 0.091414 -v -0.099217 0.026488 0.096378 -v -0.080945 0.026672 0.111720 -v -0.082400 0.032094 0.110224 -v -0.088162 0.030289 0.105783 -v -0.073071 0.034767 0.116821 -v -0.071623 0.027104 0.118383 -v -0.067121 0.036314 0.120678 -v -0.061982 0.027505 0.124577 -v -0.061072 0.037762 0.124341 -v -0.048685 0.040346 0.131094 -v -0.033777 0.035165 0.138691 -v -0.036816 0.038831 0.137030 -v -0.042351 0.041471 0.134187 -v -0.031381 0.032028 0.139951 -v -0.020708 0.012673 0.145130 -v -0.021638 0.015230 0.144708 -v -0.031382 0.014266 0.140892 -v -0.098542 0.025722 0.097055 -v -0.101785 0.025527 0.093968 -v -0.089926 0.026211 0.104605 -v -0.089926 0.013113 0.105241 -v -0.080945 0.013343 0.112368 -v -0.061982 0.013760 0.125244 -v -0.052045 0.027875 0.130287 -v -0.041836 0.028213 0.135499 -v -0.113166 0.011046 0.082961 -v -0.106773 -0.000000 0.089904 -v -0.098542 0.012868 0.097679 -v -0.089926 -0.000000 0.105453 -v -0.071623 0.000000 0.119260 -v -0.071623 0.013559 0.119041 -v -0.052045 0.013945 0.130963 -v -0.041836 0.014114 0.136183 -v -0.031382 0.000000 0.141122 -v -0.113879 -0.005699 0.082287 -v -0.106773 -0.012610 0.089700 -v -0.098542 -0.000000 0.097887 -v -0.098542 -0.012868 0.097679 -v -0.080945 0.000000 0.112583 -v -0.071623 -0.013559 0.119041 -v -0.061982 -0.000000 0.125467 -v -0.052045 -0.000000 0.131189 -v -0.052045 -0.013945 0.130963 -v -0.041836 0.000000 0.136412 -v -0.031382 -0.014266 0.140892 -v -0.098542 -0.025722 0.097055 -v -0.089926 -0.013113 0.105241 -v -0.080945 -0.013343 0.112368 -v -0.089926 -0.026211 0.104605 -v -0.061982 -0.013760 0.125244 -v -0.061982 -0.027505 0.124577 -v -0.041836 -0.014114 0.136183 -v -0.041836 -0.028213 0.135499 -v -0.013671 0.004205 0.147131 -v -0.013677 -0.000000 0.147190 -v -0.017234 0.000000 0.146404 -v -0.016778 0.007916 0.146453 -v -0.016778 -0.007916 0.146453 -v -0.017228 -0.008461 0.146301 -v -0.020708 0.000000 0.145310 -v -0.104910 -0.010130 -0.064077 -v -0.111247 -0.007924 -0.059500 -v -0.110619 0.008146 -0.060010 -v -0.108677 -0.008793 -0.061471 -v -0.107667 -0.009129 -0.062232 -v -0.104910 0.010130 -0.064077 -v -0.104292 -0.010354 -0.064491 -v -0.104292 0.010354 -0.064491 -v -0.100387 -0.011846 -0.066823 -v -0.095968 -0.013574 -0.069183 -v -0.095681 0.013686 -0.069321 -v -0.095968 0.013574 -0.069183 -v -0.090667 0.015643 -0.071710 -v -0.090192 -0.015824 -0.071912 -v -0.070301 0.022891 -0.079273 -v -0.070301 -0.022891 -0.079273 -v -0.073675 -0.021807 -0.078222 -v -0.077481 0.020497 -0.076911 -v -0.079486 0.019807 -0.076220 -v -0.055517 -0.021499 -0.083341 -v -0.055517 0.021499 -0.083341 -v -0.054475 0.021007 -0.083576 -v -0.054475 -0.021007 -0.083576 -v -0.047792 -0.017854 -0.085084 -v -0.045932 -0.016976 -0.085448 -v -0.045932 0.016976 -0.085448 -v -0.037066 -0.012791 -0.087114 -v -0.031097 -0.009971 -0.088110 -v -0.021564 -0.005452 -0.089423 -v -0.021564 0.005452 -0.089423 -v -0.018672 -0.004074 -0.089738 -v -0.114765 0.004132 -0.056317 -v -0.111885 -0.007637 -0.058966 -v -0.111749 0.007705 -0.059081 -v -0.112535 0.007267 -0.058403 -v -0.114202 -0.005606 -0.056867 -v -0.114958 0.001715 -0.056122 -v -0.016677 0.067973 -0.027144 -v -0.010241 0.068610 0.109650 -v -0.041289 0.064204 0.107824 -v -0.022160 0.067318 0.111685 -v -0.025765 0.066805 0.112231 -v -0.029626 0.066257 0.112816 -v -0.041287 0.064195 -0.027558 -v -0.041554 0.064155 0.107706 -v -0.070971 0.056753 0.091508 -v -0.071798 0.056494 0.090959 -v -0.079965 0.053832 0.085333 -v -0.075584 0.055295 -0.016466 -v -0.074359 0.055690 0.089259 -v -0.080449 0.053666 -0.014098 -v -0.085420 0.051903 0.081253 -v -0.085189 0.051987 -0.011563 -v -0.086699 0.051423 0.080232 -v -0.095870 0.047866 0.072631 -v -0.090722 0.049912 0.077019 -v -0.010131 -0.068619 -0.024813 -v -0.010235 -0.068610 -0.024851 -v -0.025768 -0.066824 -0.029921 -v -0.022160 -0.067318 0.111685 -v -0.025765 -0.066805 0.112231 -v -0.041287 -0.064198 -0.027564 -v -0.040037 -0.064450 -0.027826 -v -0.034670 -0.065430 -0.028765 -v -0.056645 -0.060753 -0.023691 -v -0.056643 -0.060745 0.100067 -v -0.045336 -0.063382 -0.026716 -v -0.063311 -0.058993 -0.021492 -v -0.071796 -0.056488 -0.018133 -v -0.070941 -0.056762 0.091527 -v -0.068411 -0.057527 -0.019560 -v -0.072613 -0.056244 0.090429 -v -0.083021 -0.052766 -0.012751 -v -0.073394 -0.055998 -0.017459 -v -0.086700 -0.051426 -0.010687 -v -0.087670 -0.051072 -0.010142 -v -0.099341 -0.046422 0.069504 -v -0.012806 0.065117 -0.044386 -v -0.017885 0.056116 -0.067422 -v -0.010131 0.056896 -0.067712 -v -0.012174 0.056709 -0.067671 -v -0.010216 0.064969 -0.045511 -v -0.046978 0.049791 -0.067456 -v -0.046207 0.061602 -0.035636 -v -0.050002 0.048790 -0.067558 -v -0.023584 0.065350 -0.039637 -v -0.034877 0.063807 -0.037774 -v -0.036895 0.063435 -0.037428 -v -0.057191 0.059013 -0.032790 -v -0.052682 0.047904 -0.067648 -v -0.062555 0.057583 -0.031102 -v -0.067834 0.056066 -0.029236 -v -0.069868 0.041471 -0.066876 -v -0.062849 0.057498 -0.030998 -v -0.083960 0.050745 -0.022154 -v -0.075856 0.039312 -0.065111 -v -0.075365 0.039489 -0.065256 -v -0.073029 0.054467 -0.027192 -v -0.078140 0.052788 -0.024966 -v -0.092539 0.032310 -0.059079 -v -0.087494 0.049424 -0.020268 -v -0.103133 0.042983 -0.010487 -v -0.107637 0.024859 -0.051238 -v -0.108596 0.032716 -0.027656 -v -0.098521 0.044999 -0.013666 -v -0.107039 0.038438 -0.015164 -v -0.120296 0.010136 -0.033088 -v -0.120815 0.003367 0.064424 -v -0.120864 -0.001547 -0.041722 -v -0.120859 -0.000000 -0.041726 -v -0.120799 -0.003788 0.064435 -v -0.120851 0.002210 -0.041733 -v -0.120875 0.000000 0.064384 -v -0.120877 0.000102 0.064382 -v -0.119668 0.014827 0.065186 -v -0.120218 0.010969 0.064822 -v -0.119178 0.017551 -0.020287 -v -0.120301 0.010136 0.064767 -v -0.119907 0.013289 -0.027517 -v -0.115849 0.029915 0.067663 -v -0.118612 0.020146 0.065879 -v -0.117050 0.026186 0.066893 -v -0.118615 -0.020147 0.065877 -v -0.118848 -0.019162 0.065725 -v -0.119584 -0.015332 0.065241 -v -0.119866 -0.013568 -0.027035 -v -0.120152 -0.011497 0.064865 -v -0.120722 -0.005325 -0.041833 -v -0.115849 -0.029915 0.067663 -v -0.115849 -0.029915 -0.001018 -v -0.116199 -0.028884 0.067440 -v -0.017885 -0.056116 -0.067422 -v -0.012174 -0.056709 -0.067671 -v -0.010131 -0.056896 -0.067712 -v -0.012806 -0.065117 -0.044386 -v -0.023610 -0.055308 -0.067266 -v -0.018651 -0.065328 -0.041825 -v -0.023584 -0.065350 -0.039637 -v -0.024963 -0.065356 -0.039025 -v -0.029367 -0.054279 -0.067199 -v -0.035173 -0.053023 -0.067215 -v -0.041040 -0.051530 -0.067304 -v -0.047094 -0.061410 -0.035436 -v -0.050002 -0.048790 -0.067558 -v -0.050002 -0.060745 -0.034718 -v -0.052587 -0.060153 -0.034080 -v -0.065967 -0.056615 -0.029920 -v -0.062848 -0.057497 -0.030995 -v -0.087500 -0.034574 -0.061101 -v -0.086662 -0.049748 -0.020742 -v -0.076554 -0.053320 -0.025680 -v -0.087234 -0.034693 -0.061207 -v -0.081656 -0.037042 -0.063221 -v -0.092539 -0.032310 -0.059079 -v -0.109159 -0.029836 -0.034386 -v -0.099189 -0.029123 -0.056008 -v -0.096311 -0.045931 -0.015101 -v -0.107637 -0.024859 -0.051238 -v -0.109607 -0.026701 -0.042052 -v -0.105867 -0.041740 -0.008475 -v -0.107781 -0.035977 -0.020394 -v -0.000000 0.057729 -0.068015 -v -0.010215 0.056788 -0.067981 -v -0.011083 0.056242 -0.069104 -v -0.011280 0.055304 -0.070897 -v -0.000000 0.052556 -0.076035 -v -0.000000 0.049890 -0.078252 -v -0.011896 0.048546 -0.077901 -v -0.037608 0.017585 -0.086633 -v -0.027385 0.044517 -0.078554 -v -0.011964 0.047115 -0.078729 -v -0.059494 0.031848 -0.080886 -v -0.000000 0.032141 -0.086287 -v -0.053857 0.034784 -0.080332 -v -0.043181 0.039512 -0.079388 -v -0.039575 0.040834 -0.079135 -v -0.042631 0.020827 -0.085503 -v -0.021860 0.007499 -0.089315 -v -0.026740 0.010619 -0.088568 -v -0.000000 0.021635 -0.089177 -v -0.000000 -0.010880 -0.090925 -v -0.021860 -0.007499 -0.089315 -v -0.000000 0.000000 -0.091510 -v -0.000000 0.010880 -0.090925 -v -0.026740 -0.010619 -0.088568 -v -0.029783 -0.012566 -0.088103 -v -0.045350 -0.022582 -0.084892 -v -0.000000 -0.021635 -0.089177 -v -0.042631 -0.020827 -0.085503 -v -0.037608 -0.017585 -0.086633 -v -0.039575 -0.040834 -0.079135 -v -0.059495 -0.031846 -0.080886 -v -0.000000 -0.032141 -0.086287 -v 0.000000 -0.042276 -0.082287 -v -0.017086 -0.046502 -0.078546 -v 0.000000 -0.069130 -0.031598 -v -0.019308 -0.066094 -0.038945 -v -0.012531 -0.065334 -0.043843 -v -0.017773 -0.065977 -0.040071 -v 0.000000 -0.067764 -0.039345 -v -0.021482 -0.067227 -0.031378 -v -0.023855 -0.066887 -0.032747 -v -0.016221 -0.067983 -0.028345 -v -0.030154 0.050189 0.135798 -v -0.000000 0.052791 0.137448 -v -0.030295 0.051737 0.135006 -v -0.000000 0.060923 0.131243 -v -0.031472 0.061140 0.126695 -v 0.000000 0.064128 0.127235 -v -0.031284 0.061804 0.125785 -v -0.030053 0.063937 0.122323 -v -0.001641 0.067162 0.121170 -v 0.000000 0.066639 0.122760 -v -0.029176 0.064573 0.121123 -v -0.023219 0.066370 0.117366 -v -0.005500 0.068775 0.113554 -v -0.025853 -0.042182 0.139262 -v 0.000000 -0.049830 0.138830 -v -0.027716 -0.045229 0.138013 -v -0.014940 -0.018483 0.145919 -v -0.015616 -0.020650 0.145541 -v 0.000000 -0.030930 0.144886 -v -0.011728 -0.006191 0.147339 -v 0.000000 -0.018668 0.147221 -v -0.012533 -0.009333 0.147113 -v 0.000000 -0.006241 0.148394 -v -0.012533 0.009333 0.147113 -v -0.000000 0.006241 0.148394 -v -0.011728 0.006191 0.147339 -v 0.000000 0.018668 0.147221 -v -0.022477 0.036252 0.141448 -v -0.020445 0.032291 0.142707 -v -0.000000 0.030930 0.144886 -v -0.000000 0.042918 0.141409 -v -0.000000 0.049830 0.138830 -v 0.000000 -0.057729 -0.068015 -v 0.000000 0.067242 0.121357 -v -0.001732 0.083303 0.105499 -v 0.000000 0.083467 0.105569 -v -0.000764 0.084833 0.104368 -v 0.000000 0.085761 0.103138 -v 0.000000 0.086559 0.099891 -v 0.000000 0.084203 0.094963 -v -0.001619 0.069599 0.074088 -v 0.000000 0.079859 0.091984 -v 0.000000 0.076826 0.089163 -v -0.001812 0.070292 0.077706 -v 0.000000 0.074251 0.085918 -v -0.001887 0.075084 0.087361 -v 0.000000 0.069506 0.070461 -v 0.000000 0.071745 0.113859 -v 0.000000 0.069160 0.117485 -v 0.000000 0.074881 0.110696 -v 0.000000 0.078485 0.108081 -v 0.000000 0.083280 0.000681 -v 0.000000 0.084217 0.000025 -v -0.000732 0.085964 -0.002370 -v -0.000000 0.086460 -0.006139 -v -0.001726 0.084921 -0.009115 -v 0.000000 0.084217 -0.010025 -v -0.000000 0.083280 -0.010681 -v -0.000001 0.081800 -0.011331 -v -0.001613 0.069365 0.024398 -v 0.000000 0.069506 0.024539 -v -0.001894 0.069561 0.021034 -v 0.000000 0.069792 0.020580 -v 0.000000 0.070693 0.016537 -v 0.000000 0.072191 0.012675 -v 0.000000 0.074251 0.009082 -v 0.000000 0.076826 0.005837 -v 0.000000 0.079859 0.003016 -v -0.001704 0.084028 -0.000003 -v -0.002770 0.079717 0.002055 -v -0.002293 0.071232 0.013899 -v -0.003000 0.073827 0.006735 -v -0.003000 0.079235 0.001324 -v -0.002910 0.072083 0.010372 -v -0.002874 0.074314 0.007141 -v -0.002059 0.077416 0.004910 -v -0.002894 0.076730 0.004381 -v -0.002484 0.072710 0.010550 -v -0.001711 0.075148 0.007578 -v -0.001645 0.071454 0.013977 -v -0.001646 0.070292 0.017423 -v -0.001764 0.073037 0.010728 -v -0.002410 0.074822 0.007524 -v -0.001909 0.080146 0.002566 -v -0.002880 0.083429 -0.000739 -v -0.002163 0.086248 -0.003804 -v -0.002002 0.082170 -0.010999 -v -0.001551 0.080000 -0.011424 -v -0.002109 0.086355 -0.005656 -v -0.002109 0.085749 -0.007787 -v -0.002110 0.083583 -0.010289 -v -0.002428 0.083844 -0.000255 -v -0.002613 0.084941 -0.001604 -v -0.002957 0.085464 -0.005021 -v -0.002930 0.083841 -0.008895 -v -0.002910 0.072177 -0.010371 -v -0.002978 0.080000 -0.010103 -v -0.002833 0.080940 -0.010584 -v -0.002491 0.080000 -0.011008 -v -0.002050 0.080933 -0.011305 -v -0.002205 0.072361 -0.011211 -v -0.002508 0.072893 0.111795 -v -0.002864 0.072211 0.111776 -v -0.003000 0.081819 0.104488 -v -0.003000 0.078293 0.106201 -v -0.003000 0.075027 0.108369 -v -0.002874 0.078585 0.106764 -v -0.002395 0.078895 0.107334 -v -0.002355 0.070500 0.114718 -v -0.002769 0.075511 0.109100 -v -0.001757 0.073163 0.112078 -v -0.001945 0.076112 0.109458 -v -0.001752 0.078954 0.107611 -v -0.001748 0.070720 0.114895 -v -0.002109 0.085888 0.102477 -v -0.002109 0.086378 0.100351 -v -0.002109 0.086124 0.098183 -v -0.001972 0.085163 0.096211 -v -0.001999 0.083996 0.095020 -v -0.002817 0.083085 0.104830 -v -0.002829 0.083495 0.095622 -v -0.002723 0.084438 0.103901 -v -0.002926 0.085367 0.100763 -v -0.003000 0.083825 0.102423 -v -0.002892 0.084894 0.097314 -v -0.002491 0.071162 0.081246 -v -0.001717 0.071402 0.080927 -v -0.001551 0.072120 0.082358 -v -0.002060 0.072808 0.083999 -v -0.002878 0.072386 0.084920 -v -0.001779 0.077487 0.090075 -v -0.002769 0.074559 0.087782 -v -0.001793 0.080218 0.092466 -v -0.002401 0.077243 0.090271 -v -0.002894 0.076882 0.090771 -v -0.002705 0.079898 0.092933 -v -0.003000 0.079235 0.093676 -v 0.000000 -0.069506 0.070461 -v -0.001613 -0.069365 0.070602 -v -0.001731 -0.084026 0.095004 -v -0.000001 -0.085310 0.096111 -v 0.000000 -0.086444 0.098772 -v 0.000000 -0.085761 0.103138 -v 0.000000 -0.083467 0.105569 -v 0.000000 -0.082464 0.106080 -v 0.000000 -0.069160 0.117485 -v -0.001978 -0.070703 0.114836 -v 0.000000 -0.074881 0.110696 -v 0.000000 -0.067242 0.121357 -v 0.000000 -0.072191 0.082325 -v 0.000000 -0.073000 0.083736 -v 0.000000 -0.076826 0.089163 -v -0.001551 -0.080000 -0.011424 -v -0.000001 -0.081608 -0.011383 -v 0.000000 -0.086560 -0.005000 -v 0.000000 -0.086164 -0.002756 -v -0.001619 -0.069599 0.020912 -v 0.000000 -0.079859 0.003016 -v -0.001793 -0.080218 0.002534 -v 0.000000 -0.076826 0.005837 -v 0.000000 -0.074251 0.009082 -v 0.000000 -0.069792 0.020580 -v -0.001812 -0.070292 0.017294 -v -0.003000 0.073827 0.088265 -v -0.003000 0.076353 0.091148 -v -0.003000 0.083065 -0.001347 -v -0.003000 0.082909 -0.007977 -v -0.003000 0.080000 -0.009843 -v -0.003000 0.072153 -0.009843 -v -0.003000 0.076353 0.003852 -v -0.003000 0.072153 0.009164 -v -0.003000 -0.083882 0.101612 -v -0.003000 -0.079238 0.093679 -v -0.003000 -0.072153 0.109630 -v -0.001887 -0.075084 0.007639 -v -0.001806 -0.072997 0.010782 -v -0.003000 -0.072153 0.009164 -v -0.002491 -0.071162 0.013753 -v -0.001750 -0.071480 0.013853 -v -0.002394 -0.072789 0.010547 -v -0.002878 -0.072386 0.010080 -v -0.001779 -0.077487 0.004925 -v -0.002769 -0.074559 0.007218 -v -0.003000 -0.076353 0.003852 -v -0.003000 -0.073827 0.006735 -v -0.002401 -0.077243 0.004729 -v -0.002894 -0.076882 0.004229 -v -0.003000 -0.079235 0.001324 -v -0.002930 -0.083599 -0.000974 -v -0.002705 -0.079898 0.002067 -v -0.002818 -0.080759 -0.010610 -v -0.002491 -0.080000 -0.011008 -v -0.002109 -0.086355 -0.004344 -v -0.002301 -0.084654 -0.000702 -v -0.001688 -0.084015 0.000007 -v -0.001898 -0.082190 -0.011004 -v -0.002005 -0.083740 -0.010197 -v -0.002164 -0.084813 -0.009158 -v -0.002104 -0.085832 -0.007617 -v -0.002163 -0.086248 -0.006196 -v -0.002109 -0.085749 -0.002213 -v -0.002978 -0.080000 -0.010103 -v -0.003000 -0.081656 -0.009551 -v -0.002885 -0.082925 -0.009799 -v -0.002947 -0.085106 -0.006696 -v -0.002886 -0.085347 -0.003498 -v -0.003000 -0.080000 -0.009843 -v -0.003000 -0.084130 -0.002616 -v -0.003000 -0.082421 -0.000806 -v -0.001551 -0.072533 -0.011424 -v -0.002026 -0.080934 -0.011319 -v -0.002431 -0.072302 -0.011053 -v -0.002922 -0.072085 -0.010314 -v -0.001815 -0.068738 0.117874 -v -0.002710 -0.069061 0.116326 -v -0.002606 -0.070258 0.114647 -v -0.001806 -0.073103 0.112126 -v -0.001884 -0.076015 0.109561 -v -0.002396 -0.072972 0.111835 -v -0.002769 -0.075606 0.109027 -v -0.002973 -0.072351 0.111379 -v -0.003000 -0.078293 0.106201 -v -0.003000 -0.075027 0.108369 -v -0.003000 -0.081819 0.104488 -v -0.002874 -0.078630 0.106739 -v -0.002881 -0.083093 0.104610 -v -0.002500 -0.078889 0.107214 -v -0.001790 -0.079111 0.107529 -v -0.002966 -0.083651 0.096213 -v -0.002548 -0.083646 0.095224 -v -0.002109 -0.085262 0.096378 -v -0.002163 -0.086357 0.099807 -v -0.002109 -0.086181 0.101615 -v -0.002105 -0.086178 0.098363 -v -0.002109 -0.085275 0.103603 -v -0.002007 -0.083601 0.105313 -v -0.002917 -0.084985 0.097711 -v -0.002933 -0.085191 0.101838 -v -0.002909 -0.072092 0.084639 -v -0.001895 -0.069564 0.073994 -v -0.002294 -0.071240 0.081124 -v -0.003000 -0.073836 0.088277 -v -0.003000 -0.076360 0.091155 -v -0.002392 -0.072792 0.084411 -v -0.002851 -0.079608 0.092996 -v -0.002874 -0.074323 0.087870 -v -0.002769 -0.076935 0.090493 -v -0.002409 -0.074830 0.087487 -v -0.001910 -0.080148 0.092435 -v -0.001962 -0.077388 0.090040 -v -0.001551 -0.074187 0.085962 -v -0.001712 -0.075158 0.087434 -v -0.001706 -0.073118 0.084406 -v -0.001646 -0.071462 0.081042 -v -0.001805 -0.070278 0.077586 -v -0.000000 0.069506 -0.014723 -v -0.002392 0.069766 -0.012765 -v -0.002412 0.069382 -0.013684 -v -0.002625 0.072251 -0.010858 -v -0.003380 0.070646 -0.009843 -v -0.003171 0.071125 -0.009843 -v -0.001551 0.072533 -0.011424 -v -0.002038 0.071096 -0.011630 -v -0.003666 0.070208 -0.009843 -v -0.004019 0.069822 -0.009843 -v -0.003249 0.070497 -0.010681 -v -0.004430 0.069500 -0.009843 -v -0.004889 0.069250 -0.009843 -v -0.005898 0.068990 -0.009843 -v -0.004673 0.069224 -0.011458 -v -0.004011 0.069155 -0.013577 -v -0.002371 0.069298 -0.014442 -v -0.003043 0.071632 -0.009843 -v -0.003043 0.071632 0.009164 -v -0.003171 0.071125 0.009164 -v -0.003380 0.070646 0.009164 -v -0.004430 0.069500 0.009164 -v -0.004889 0.069250 0.009164 -v -0.005383 0.069078 0.009164 -v -0.005383 0.069078 -0.009843 -v -0.005099 0.069104 0.012363 -v -0.005776 0.069000 0.011297 -v -0.001991 0.069332 0.023529 -v -0.003313 0.069604 0.015868 -v -0.002364 0.070047 0.017312 -v -0.002863 0.070536 0.013884 -v -0.003692 0.069947 0.011850 -v -0.003794 0.069335 0.016018 -v -0.004441 0.069360 0.012254 -v -0.004721 0.069092 0.016300 -v -0.004019 0.069822 0.009164 -v -0.003666 0.070208 0.009164 -v -0.003188 0.070843 0.010913 -v 0.000000 -0.072834 -0.011560 -v -0.002386 -0.069443 -0.013436 -v 0.000000 -0.069929 -0.013140 -v -0.001955 -0.072427 -0.011328 -v -0.001999 -0.071573 -0.011494 -v -0.002714 -0.072228 -0.010751 -v -0.003000 -0.072153 -0.009843 -v -0.003043 -0.071632 -0.009843 -v -0.003171 -0.071125 -0.009843 -v -0.003243 -0.070508 -0.010843 -v -0.003380 -0.070646 -0.009843 -v -0.002059 -0.070406 -0.012103 -v -0.003665 -0.070208 -0.009843 -v -0.004019 -0.069822 -0.009843 -v -0.004307 -0.069307 -0.011796 -v -0.001552 -0.069370 -0.014587 -v -0.005898 -0.068990 0.009164 -v -0.005383 -0.069078 -0.009843 -v -0.004889 -0.069250 0.009164 -v -0.004430 -0.069500 0.009164 -v -0.004889 -0.069250 -0.009843 -v -0.004430 -0.069500 -0.009843 -v -0.003665 -0.070208 0.009164 -v -0.003171 -0.071125 0.009164 -v -0.003043 -0.071632 0.009164 -v -0.001991 -0.069332 0.023529 -v -0.002073 -0.069476 0.021085 -v -0.002452 -0.069883 0.017597 -v -0.004721 -0.069092 0.016300 -v -0.005409 -0.069033 0.013592 -v -0.003328 -0.069610 0.015763 -v -0.003709 -0.069225 0.017747 -v -0.005776 -0.069000 0.011297 -v -0.003943 -0.069735 0.011802 -v -0.003181 -0.070671 0.011657 -v -0.003380 -0.070646 0.009164 -v -0.004019 -0.069822 0.009164 -v -0.005383 -0.069078 0.009164 -v -0.004898 -0.069179 0.012336 -v -0.001991 -0.069332 0.071471 -v -0.004721 -0.069092 0.078700 -v -0.003794 -0.069335 0.078982 -v -0.002619 -0.069798 0.077585 -v -0.002863 -0.070536 0.081123 -v -0.003692 -0.069947 0.083152 -v -0.004441 -0.069360 0.082746 -v -0.005099 -0.069104 0.082637 -v -0.003043 -0.071632 0.085836 -v -0.005383 -0.069078 0.085836 -v -0.005776 -0.069000 0.083703 -v -0.004430 -0.069500 0.085836 -v -0.004019 -0.069822 0.085836 -v -0.003665 -0.070208 0.085836 -v -0.003380 -0.070646 0.085836 -v -0.003188 -0.070843 0.084087 -v -0.005383 -0.069078 0.109630 -v -0.004889 -0.069250 0.109630 -v -0.004889 -0.069250 0.085836 -v -0.004019 -0.069822 0.109630 -v -0.003665 -0.070208 0.109630 -v -0.003380 -0.070646 0.109630 -v -0.003171 -0.071125 0.109630 -v -0.003171 -0.071125 0.085836 -v -0.003000 -0.072153 0.085836 -v -0.003043 -0.071632 0.109630 -v -0.004430 -0.069500 0.109630 -v -0.005898 -0.068990 0.109630 -v -0.002737 -0.068160 0.118166 -v -0.003024 -0.067805 0.118993 -v -0.004281 -0.068870 0.114555 -v -0.004557 -0.068423 0.116116 -v -0.005265 -0.068687 0.114329 -v -0.005500 -0.068775 0.113554 -v -0.003295 -0.069871 0.113616 -v -0.003174 -0.070908 0.111545 -v -0.003874 -0.069878 0.111463 -v -0.004809 -0.069197 0.111605 -v -0.005572 -0.068917 0.112134 -v -0.001991 0.069332 0.071471 -v -0.003630 0.069188 0.075482 -v -0.002073 0.069476 0.073915 -v -0.004721 0.069092 0.078700 -v -0.003709 0.069225 0.077253 -v -0.002452 0.069883 0.077403 -v -0.005409 0.069033 0.081408 -v -0.003328 0.069610 0.079236 -v -0.003181 0.070671 0.083343 -v -0.003000 0.072153 0.085836 -v -0.003043 0.071632 0.085836 -v -0.003665 0.070208 0.085836 -v -0.004019 0.069822 0.085836 -v -0.004430 0.069500 0.085836 -v -0.003943 0.069735 0.083198 -v -0.005383 0.069078 0.085836 -v -0.005898 0.068990 0.085836 -v -0.004898 0.069179 0.082664 -v -0.003043 0.071632 0.109630 -v -0.003171 0.071125 0.085836 -v -0.003380 0.070646 0.109630 -v -0.003380 0.070646 0.085836 -v -0.004889 0.069250 0.085836 -v -0.003000 0.072153 0.109630 -v -0.003171 0.071125 0.109630 -v -0.003665 0.070208 0.109630 -v -0.004019 0.069822 0.109630 -v -0.004430 0.069500 0.109630 -v -0.004889 0.069250 0.109630 -v -0.005383 0.069078 0.109630 -v -0.005898 0.068990 0.109630 -v -0.003023 0.071267 0.111445 -v -0.002597 0.068130 0.118343 -v -0.003024 0.067805 0.118993 -v -0.001809 0.067245 0.120916 -v -0.001765 0.068673 0.118017 -v -0.004557 0.068423 0.116116 -v -0.003586 0.068042 0.118022 -v -0.003140 0.069559 0.114698 -v -0.004074 0.068996 0.114317 -v -0.005265 0.068687 0.114329 -v -0.005798 0.068897 0.112130 -v -0.005898 0.068968 0.110787 -v -0.004909 0.069147 0.111623 -v -0.003883 0.069876 0.111523 -v 0.042000 0.020848 -0.087803 -v 0.028165 0.016660 -0.088602 -v 0.027783 0.016649 -0.088604 -v -0.000000 0.016441 -0.088639 -v 0.042000 0.053042 -0.077600 -v 0.042000 0.049830 -0.077489 -v 0.032122 0.046749 -0.078403 -v 0.002000 0.050161 0.146466 -v -0.000000 0.029108 0.150941 -v 0.040000 0.017547 0.152896 -v 0.002159 -0.004962 0.153898 -v 0.042000 0.005863 0.153877 -v 0.039759 0.004737 0.153920 -v 0.002936 0.003515 0.153956 -v 0.005303 0.002109 0.153984 -v 0.036000 0.002060 0.153985 -v 0.036000 -0.002060 0.153985 -v 0.036606 0.002100 0.153984 -v 0.037285 0.002269 0.153982 -v 0.037373 -0.002294 0.153981 -v 0.038504 0.002947 0.153969 -v 0.039064 0.003515 0.153956 -v 0.002241 0.004737 0.153920 -v 0.002061 0.005420 0.153895 -v 0.040000 -0.029108 0.150941 -v 0.042000 -0.005863 0.153877 -v 0.040000 -0.005527 0.153916 -v 0.000000 -0.005863 0.153877 -v 0.000000 -0.017547 0.152896 -v 0.000000 -0.029108 0.150941 -v -0.000000 0.005863 0.153877 -v 0.002000 0.006124 0.153866 -v 0.042000 0.058696 0.143232 -v 0.040000 0.054552 0.145175 -v 0.042000 0.054552 0.145175 -v 0.042000 0.062496 0.140681 -v 0.039464 0.060832 0.141902 -v 0.039759 0.060266 0.142279 -v 0.006000 0.062600 0.140598 -v 0.037093 0.062471 0.140704 -v 0.037851 0.062206 0.140907 -v 0.002241 0.060266 0.142279 -v -0.000000 0.062496 0.140681 -v 0.004707 0.062419 0.140752 -v 0.003496 0.061835 0.141189 -v -0.000000 0.058696 0.143232 -v 0.002000 0.054552 0.145175 -v 0.042000 0.141521 0.041997 -v 0.042000 0.095076 0.056031 -v 0.042000 0.095000 0.056899 -v 0.042000 -0.094699 0.033154 -v 0.042000 -0.138556 0.044899 -v 0.042000 -0.138255 0.046610 -v 0.042000 -0.095125 0.046012 -v 0.042000 -0.095008 0.045180 -v 0.042000 -0.095195 0.043515 -v 0.042000 0.146309 0.041472 -v 0.042000 -0.095922 0.042006 -v 0.042000 -0.095495 0.042730 -v 0.042000 -0.093283 0.032280 -v 0.042000 -0.093383 0.035544 -v 0.042000 -0.091881 0.030231 -v 0.042000 -0.095766 0.047560 -v 0.042000 -0.096272 0.048231 -v 0.042000 -0.095076 0.056031 -v 0.042000 -0.095670 0.054399 -v 0.042000 0.126474 0.067744 -v 0.042000 0.138556 0.044899 -v 0.042000 0.138556 0.044477 -v 0.042000 0.126864 0.066052 -v 0.042000 0.136770 0.048730 -v 0.042000 0.138255 0.046610 -v 0.042000 -0.146556 0.051049 -v 0.042000 -0.136056 0.049230 -v 0.042000 -0.096786 0.053069 -v 0.042000 -0.126834 0.065181 -v 0.042000 -0.126864 0.066052 -v 0.042000 -0.126743 0.066915 -v 0.042000 -0.097160 0.033487 -v 0.042000 -0.097473 0.033441 -v 0.042000 -0.126326 0.063520 -v 0.042000 -0.126653 0.064329 -v 0.042000 0.100287 0.092603 -v 0.042000 0.095670 0.054399 -v 0.042000 -0.095267 0.088026 -v 0.042000 0.102873 0.092513 -v 0.042000 -0.126065 0.068514 -v 0.042000 -0.104420 0.091724 -v 0.042000 -0.103681 0.092186 -v 0.042000 -0.094454 0.106923 -v 0.042000 -0.101150 0.092724 -v 0.042000 -0.084172 0.117948 -v 0.042000 -0.099458 0.092334 -v 0.042000 -0.095000 0.086415 -v 0.042000 -0.114513 0.052398 -v 0.042000 0.092214 0.096133 -v 0.042000 0.115162 0.052774 -v 0.042000 0.113816 0.052123 -v 0.042000 -0.096883 0.048809 -v 0.042000 0.104420 0.091724 -v 0.042000 0.105068 0.091141 -v 0.042000 0.091881 0.030231 -v 0.042000 0.092231 0.030990 -v 0.042000 0.093954 0.032777 -v 0.042000 0.095922 0.042006 -v 0.042000 0.095495 0.042730 -v 0.042000 0.095195 0.043515 -v 0.042000 0.095000 0.049381 -v 0.042000 0.098290 0.052201 -v 0.042000 0.097581 0.049276 -v 0.042000 -0.100000 0.049899 -v 0.042000 -0.115747 0.053243 -v 0.042000 -0.095593 0.088778 -v 0.042000 0.134425 0.049824 -v 0.042000 0.125865 0.062781 -v 0.042000 0.133556 0.049899 -v 0.042000 0.099132 0.051975 -v 0.042000 0.098349 0.049619 -v 0.042000 0.100000 0.051899 -v 0.042000 0.100000 0.049899 -v 0.042000 0.063767 0.130717 -v 0.042000 0.084115 0.112526 -v 0.042000 0.098688 0.091924 -v 0.042000 0.098001 0.091388 -v 0.042000 0.095067 0.087231 -v 0.042000 0.095267 0.088026 -v 0.042000 0.095593 0.088778 -v 0.042000 0.097160 0.033487 -v 0.042000 -0.088792 0.104640 -v 0.042000 -0.098001 0.091388 -v 0.042000 0.099964 0.037864 -v 0.042001 0.100372 0.036645 -v 0.042000 -0.078290 0.119607 -v 0.042000 -0.062496 0.140681 -v 0.042000 0.051796 0.136500 -v 0.042000 0.026425 0.144349 -v 0.042000 0.029108 0.150941 -v 0.042000 0.013279 0.146335 -v 0.042000 0.017547 0.152896 -v 0.042000 -0.017547 0.152896 -v 0.042000 -0.026425 0.144349 -v 0.042000 -0.050161 0.146466 -v 0.042000 -0.054552 0.145175 -v 0.042000 -0.058696 0.143232 -v 0.004695 0.090721 -0.015556 -v 0.011071 0.090376 -0.015556 -v 0.004000 0.082218 -0.015556 -v 0.019000 0.089536 -0.015556 -v 0.017878 0.090437 -0.015556 -v 0.038000 0.082218 -0.015556 -v 0.032000 0.089536 -0.015556 -v 0.024071 0.090376 -0.015556 -v 0.030878 0.090437 -0.015556 -v 0.017104 0.092026 -0.015557 -v 0.024900 0.092024 -0.015558 -v 0.040185 0.095315 0.000016 -v 0.040082 0.095420 0.000434 -v 0.032291 0.094827 -0.001099 -v 0.031514 0.092703 -0.003064 -v 0.031638 0.092178 -0.003275 -v 0.022242 0.095163 -0.000438 -v 0.009915 0.094607 -0.001442 -v 0.010349 0.093855 -0.002285 -v 0.019048 0.091431 -0.003473 -v 0.010266 0.091945 -0.003350 -v 0.010456 0.092520 -0.003143 -v 0.009566 0.091046 -0.003530 -v 0.009201 0.090802 -0.003549 -v 0.040021 0.095488 0.000851 -v 0.007000 0.095521 0.001281 -v 0.035915 0.094607 -0.001442 -v 0.036149 0.094272 -0.001865 -v 0.041287 0.094263 -0.001876 -v 0.041844 0.092976 -0.002913 -v 0.042000 0.092613 -0.003099 -v 0.042000 0.090523 -0.003556 -v 0.042000 0.091374 -0.003483 -v 0.042000 0.092200 -0.003267 -v 0.035566 0.091045 -0.003530 -v 0.024731 0.150556 0.043472 -v 0.041999 0.102970 0.029935 -v 0.042000 0.104648 0.031859 -v 0.042000 0.093003 -0.006521 -v 0.042000 0.077983 -0.012212 -v 0.042000 0.083510 -0.002387 -v 0.042000 0.082894 -0.001770 -v 0.042000 0.092563 -0.011556 -v 0.042000 0.081724 0.001444 -v 0.037000 0.098416 -0.008238 -v 0.037000 0.097783 -0.004601 -v 0.005000 0.097783 -0.004601 -v 0.005000 0.097678 -0.002007 -v 0.037000 0.097678 -0.002007 -v 0.037000 0.097533 0.001580 -v 0.005000 0.097533 0.001580 -v 0.037000 0.097869 0.004255 -v 0.005000 0.097869 0.004255 -v 0.037000 0.099102 0.010397 -v 0.037000 0.100072 0.013647 -v 0.005000 0.100072 0.013647 -v 0.005000 0.101344 0.016247 -v 0.037000 0.102791 0.019204 -v 0.005000 0.108574 0.026426 -v 0.037000 0.115795 0.032209 -v 0.037000 0.121353 0.034928 -v 0.005000 0.118753 0.033656 -v 0.005000 0.121353 0.034928 -v 0.037000 0.127281 0.036697 -v 0.005000 0.127281 0.036697 -v 0.037000 0.130745 0.037131 -v 0.005000 0.130745 0.037131 -v 0.037000 0.137007 0.037322 -v 0.037000 0.139601 0.037217 -v 0.037000 0.143238 0.036584 -v 0.004183 0.150738 0.043820 -v 0.004004 0.150560 0.042459 -v 0.033145 0.132940 0.065651 -v 0.033566 0.136221 0.062132 -v 0.034434 0.132863 0.065733 -v 0.031651 0.135125 0.063308 -v 0.032085 0.135638 0.062758 -v 0.032393 0.133236 0.065333 -v 0.032085 0.133446 0.065108 -v 0.031835 0.133690 0.064847 -v 0.031651 0.133959 0.064558 -v 0.034855 0.136144 0.062215 -v 0.042000 0.146556 0.051049 -v 0.036165 0.135395 0.063019 -v 0.036165 0.133690 0.064847 -v 0.035607 0.133236 0.065333 -v 0.035250 0.133066 0.065516 -v 0.036462 0.134838 0.063615 -v 0.036500 0.134542 0.063933 -v 0.036349 0.133959 0.064558 -v 0.022575 0.074134 0.128712 -v 0.020566 0.070067 0.133074 -v 0.021000 0.070093 0.133046 -v 0.022575 0.065864 0.137581 -v 0.022049 0.066837 0.136538 -v 0.020145 0.066786 0.136592 -v 0.019393 0.069694 0.133474 -v 0.020145 0.069990 0.133156 -v 0.019085 0.067292 0.136049 -v 0.018538 0.068092 0.135192 -v 0.018651 0.068971 0.134249 -v 0.023165 0.067536 0.135788 -v 0.022915 0.067292 0.136049 -v 0.023349 0.068971 0.134249 -v 0.021434 0.132863 0.065733 -v 0.019750 0.133066 0.065516 -v 0.021000 0.136247 0.062104 -v 0.021434 0.136221 0.062132 -v 0.021855 0.136144 0.062215 -v 0.019085 0.133446 0.065108 -v 0.018835 0.135395 0.063019 -v 0.019085 0.135638 0.062758 -v 0.019393 0.135848 0.062532 -v 0.022575 0.148944 0.048488 -v 0.027500 0.148944 0.048488 -v 0.022915 0.135638 0.062758 -v 0.023349 0.135125 0.063308 -v 0.023500 0.134542 0.063933 -v 0.027500 0.117492 0.082217 -v 0.023165 0.133690 0.064847 -v 0.021434 0.102121 0.098700 -v 0.022606 0.099135 0.101902 -v 0.022044 0.098890 0.102166 -v 0.022575 0.117492 0.082217 -v 0.020145 0.098840 0.102219 -v 0.018425 0.094454 0.106923 -v 0.020145 0.102044 0.098782 -v 0.018651 0.101025 0.099875 -v 0.019085 0.101538 0.099325 -v 0.018538 0.100146 0.100818 -v 0.022915 0.101538 0.099325 -v 0.023165 0.101295 0.099586 -v 0.023462 0.100146 0.100818 -v 0.023349 0.099859 0.101126 -v 0.023462 0.100738 0.100183 -v 0.023500 0.100442 0.100501 -v 0.000000 0.112945 0.087093 -v 0.000000 0.110789 0.089405 -v 0.000000 0.091171 0.110443 -v 0.000000 0.094454 0.106923 -v 0.008434 0.132863 0.065733 -v 0.008000 0.132837 0.065761 -v 0.007566 0.132863 0.065733 -v 0.007145 0.132940 0.065651 -v 0.007566 0.136221 0.062132 -v 0.008000 0.136247 0.062104 -v 0.002750 0.148944 0.048488 -v 0.014425 0.148944 0.048488 -v 0.009915 0.135638 0.062758 -v 0.010349 0.135125 0.063308 -v 0.009607 0.133236 0.065333 -v 0.005835 0.135395 0.063019 -v 0.006085 0.135638 0.062758 -v 0.007145 0.136144 0.062215 -v 0.006085 0.133446 0.065108 -v 0.002750 0.117492 0.082217 -v 0.010462 0.134246 0.064250 -v 0.005500 0.134542 0.063933 -v 0.002750 0.094454 0.106923 -v 0.007145 0.098840 0.102219 -v 0.009915 0.099346 0.101676 -v 0.009250 0.098966 0.102084 -v 0.006393 0.099136 0.101901 -v 0.006393 0.101748 0.099100 -v 0.006750 0.101919 0.098917 -v 0.009250 0.101919 0.098917 -v 0.009607 0.101748 0.099100 -v 0.010462 0.100146 0.100818 -v 0.008000 0.102147 0.098672 -v 0.008855 0.102044 0.098782 -v 0.010165 0.101295 0.099586 -v 0.005538 0.100146 0.100818 -v 0.005538 0.100738 0.100183 -v 0.005835 0.101295 0.099586 -v 0.008434 0.070067 0.133074 -v 0.006750 0.069865 0.133291 -v 0.014425 0.074134 0.128712 -v 0.002750 0.084172 0.117948 -v 0.014425 0.094454 0.106923 -v 0.008434 0.098763 0.102301 -v 0.007145 0.066786 0.136592 -v 0.008855 0.069990 0.133156 -v 0.009250 0.069865 0.133291 -v 0.014425 0.066274 0.137142 -v 0.009250 0.066912 0.136458 -v 0.010462 0.068092 0.135192 -v 0.006085 0.067292 0.136049 -v 0.005835 0.067536 0.135788 -v 0.005651 0.067805 0.135499 -v 0.010349 0.067805 0.135499 -v 0.010165 0.067536 0.135788 -v 0.005538 0.068092 0.135192 -v 0.005500 0.068388 0.134874 -v 0.002750 0.074134 0.128712 -v 0.005538 0.068684 0.134557 -v 0.018425 0.117492 0.082217 -v 0.014425 0.117492 0.082217 -v 0.010349 0.068971 0.134249 -v 0.022915 0.099346 0.101676 -v 0.036500 0.100442 0.100501 -v 0.034434 0.098763 0.102301 -v 0.033566 0.098763 0.102301 -v 0.036462 0.100738 0.100183 -v 0.042000 0.094454 0.106923 -v 0.036349 0.101025 0.099875 -v 0.035607 0.101748 0.099100 -v 0.042000 0.117492 0.082217 -v 0.027500 0.094454 0.106923 -v 0.033566 0.102121 0.098700 -v 0.031651 0.101025 0.099875 -v 0.034000 0.066683 0.136703 -v 0.034434 0.070067 0.133074 -v 0.042000 0.066274 0.137142 -v 0.042000 0.084172 0.117948 -v 0.034855 0.098840 0.102219 -v 0.042000 0.074134 0.128712 -v 0.036165 0.067536 0.135788 -v 0.032393 0.069694 0.133474 -v 0.032750 0.069865 0.133291 -v 0.033145 0.069990 0.133156 -v 0.035915 0.069484 0.133699 -v 0.036165 0.069241 0.133960 -v 0.036462 0.068684 0.134557 -v 0.027500 0.074134 0.128712 -v 0.031835 0.069241 0.133960 -v 0.031500 0.068388 0.134874 -v 0.002750 0.065864 0.137581 -v 0.014425 0.065864 0.137581 -v 0.018425 0.066274 0.137142 -v 0.027500 0.065864 0.137581 -v 0.027500 0.066274 0.137142 -v 0.042000 0.065864 0.137581 -v 0.040000 0.029108 0.150941 -v 0.040000 0.050161 0.146466 -v 0.042000 0.050161 0.146466 -v 0.032000 0.051604 -0.074854 -v -0.000000 0.051604 -0.074854 -v -0.000000 0.053528 -0.072642 -v -0.000000 0.055108 -0.070172 -v 0.032000 0.056310 -0.067498 -v 0.042000 0.056702 -0.066421 -v 0.003931 0.072417 -0.023246 -v 0.034000 0.058366 -0.061851 -v 0.002882 0.071159 -0.026703 -v 0.041840 0.076086 -0.013164 -v 0.001715 0.070380 -0.028841 -v -0.000000 0.064382 -0.045322 -v -0.000000 0.056310 -0.067498 -v 0.007550 0.090534 -0.003556 -v 0.040000 0.103023 0.023189 -v 0.007000 0.100497 0.019229 -v 0.040000 0.100008 0.018154 -v 0.007000 0.099987 0.018172 -v 0.040000 0.099428 0.017173 -v 0.040000 0.097060 0.010990 -v 0.007000 0.097697 0.012775 -v 0.007000 0.096936 0.010553 -v 0.040000 0.095757 0.004499 -v 0.007000 0.103731 0.027671 -v 0.041426 0.103914 0.026909 -v 0.007000 0.103914 0.026909 -v 0.007000 0.103976 0.026127 -v 0.007000 0.103915 0.025345 -v 0.007000 0.103433 0.023858 -v 0.040018 0.103243 0.023519 -v 0.040274 0.103732 0.024583 -v 0.007000 0.103021 0.029064 -v 0.042000 0.103411 0.028432 -v 0.041706 0.103021 0.029064 -v 0.041042 0.102624 0.029538 -v 0.007000 0.102511 0.029660 -v 0.041599 0.097798 0.033364 -v 0.041378 0.097978 0.033321 -v 0.040162 0.099477 0.032596 -v 0.040342 0.099141 0.032814 -v 0.007000 0.097978 0.033321 -v 0.007000 0.098758 0.033022 -v 0.007000 0.092231 0.030990 -v 0.042000 0.092703 0.031679 -v 0.007000 0.092703 0.031679 -v 0.042000 0.093283 0.032280 -v 0.007000 0.093283 0.032280 -v 0.042000 0.094700 0.033154 -v 0.042000 0.095497 0.033403 -v 0.042000 0.096325 0.033515 -v 0.007000 0.096325 0.033515 -v 0.007000 0.097160 0.033487 -v 0.042000 0.091382 0.028860 -v 0.007000 0.091881 0.030231 -v 0.042000 0.085856 -0.003480 -v 0.042000 0.085014 -0.003255 -v 0.042000 0.084224 -0.002886 -v 0.007000 0.084224 -0.002886 -v 0.007000 0.082894 -0.001770 -v 0.042000 0.082394 -0.001056 -v 0.042000 0.082025 -0.000266 -v 0.042000 0.081800 0.000575 -v 0.007000 0.082025 -0.000266 -v 0.042000 0.081800 0.002312 -v 0.007000 0.081724 0.001444 -v 0.042000 0.082025 0.003154 -v 0.007000 0.082025 0.003154 -v 0.008341 0.090523 -0.003556 -v 0.007000 0.086724 -0.003556 -v 0.008000 0.090500 -0.003556 -v 0.042000 0.086724 -0.003556 -v 0.021000 0.090500 -0.003556 -v 0.002000 0.091009 0.006714 -v 0.002000 0.092117 0.011889 -v 0.002000 0.093832 0.016895 -v 0.042000 0.095000 0.086415 -v 0.002000 0.095000 0.086415 -v 0.002000 0.095067 0.087231 -v 0.002000 0.095267 0.088026 -v 0.002000 0.095593 0.088778 -v 0.042000 0.096039 0.089466 -v 0.002000 0.095000 0.056899 -v 0.042000 0.095000 0.078062 -v 0.002000 0.099132 0.051975 -v 0.042000 0.097500 0.052569 -v 0.042000 0.096786 0.053069 -v 0.002000 0.097500 0.052569 -v 0.002000 0.096786 0.053069 -v 0.042000 0.096170 0.053686 -v 0.002000 0.096170 0.053686 -v 0.002000 0.095302 0.055189 -v 0.042000 0.095302 0.055189 -v 0.002000 0.095076 0.056031 -v 0.042000 0.112337 0.051899 -v 0.042000 0.114513 0.052398 -v 0.002000 0.113816 0.052123 -v 0.042000 0.113085 0.051956 -v 0.042000 0.115747 0.053243 -v 0.042000 0.125281 0.062134 -v 0.002000 0.125528 0.069200 -v 0.042000 0.126065 0.068514 -v 0.002000 0.126065 0.068514 -v 0.042000 0.126743 0.066915 -v 0.002000 0.126864 0.066052 -v 0.042000 0.126834 0.065181 -v 0.002000 0.126834 0.065181 -v 0.042000 0.126653 0.064329 -v 0.002000 0.126326 0.063520 -v 0.042000 0.126326 0.063520 -v 0.002000 0.125865 0.062781 -v 0.002000 0.125281 0.062134 -v 0.042000 0.125528 0.069200 -v 0.042000 0.099458 0.092334 -v 0.002000 0.100287 0.092603 -v 0.002000 0.101150 0.092724 -v 0.042000 0.101150 0.092724 -v 0.042000 0.102021 0.092694 -v 0.002000 0.102873 0.092513 -v 0.042000 0.103681 0.092186 -v 0.002000 0.103681 0.092186 -v 0.002000 0.105068 0.091141 -v 0.002000 0.096590 0.090072 -v 0.042000 0.096590 0.090072 -v 0.002000 0.115747 0.053243 -v 0.002000 0.113085 0.051956 -v 0.002000 0.096039 0.089466 -v 0.002000 0.112337 0.051899 -v 0.002000 0.114513 0.052398 -v 0.002000 0.115162 0.052774 -v 0.002000 0.095670 0.054399 -v 0.002000 0.102021 0.092694 -v 0.002000 0.100000 0.051899 -v 0.002000 0.098290 0.052201 -v 0.002000 0.126653 0.064329 -v 0.002000 0.126743 0.066915 -v 0.002000 0.126474 0.067744 -v 0.002000 0.104420 0.091724 -v 0.002000 0.099458 0.092334 -v 0.002000 0.098688 0.091924 -v 0.002000 0.098001 0.091388 -v 0.042000 0.135266 0.049598 -v 0.042000 0.136056 0.049230 -v 0.007000 0.136770 0.048730 -v 0.042000 0.137387 0.048113 -v 0.007000 0.137387 0.048113 -v 0.042000 0.137886 0.047399 -v 0.007000 0.137886 0.047399 -v 0.007000 0.138255 0.046610 -v 0.042000 0.138480 0.045768 -v 0.042000 0.096464 0.041364 -v 0.007000 0.095495 0.042730 -v 0.042000 0.095031 0.044340 -v 0.042000 0.095008 0.045180 -v 0.007000 0.095031 0.044340 -v 0.007000 0.095008 0.045180 -v 0.042000 0.095125 0.046012 -v 0.042000 0.095381 0.046813 -v 0.007000 0.095381 0.046813 -v 0.042000 0.095766 0.047560 -v 0.007000 0.096272 0.048231 -v 0.042000 0.096272 0.048231 -v 0.042000 0.096883 0.048809 -v 0.007000 0.096883 0.048809 -v 0.007000 0.097581 0.049276 -v 0.007000 0.098349 0.049619 -v 0.042000 0.099162 0.049829 -v 0.040880 0.105340 0.032489 -v 0.040000 0.103772 0.034057 -v 0.007000 0.105340 0.032489 -v 0.040000 0.111811 0.031977 -v 0.040018 0.111481 0.031757 -v 0.007000 0.110417 0.031268 -v 0.007000 0.109655 0.031085 -v 0.007000 0.108873 0.031024 -v 0.041293 0.108527 0.031036 -v 0.007000 0.108091 0.031086 -v 0.007000 0.107329 0.031269 -v 0.041426 0.108091 0.031086 -v 0.042000 0.106131 0.031844 -v 0.040000 0.130501 0.039243 -v 0.007000 0.129041 0.039048 -v 0.040000 0.127908 0.038723 -v 0.007000 0.127893 0.038802 -v 0.040000 0.124010 0.037940 -v 0.007000 0.124447 0.038064 -v 0.007000 0.122225 0.037303 -v 0.040000 0.122243 0.037263 -v 0.040000 0.117827 0.035572 -v 0.007000 0.116828 0.035013 -v 0.035782 0.136215 0.040230 -v 0.041540 0.137433 0.041318 -v 0.042000 0.138099 0.042387 -v 0.041844 0.137913 0.042024 -v 0.035954 0.138474 0.043567 -v 0.042000 0.138483 0.043626 -v 0.042000 0.138267 0.042800 -v 0.036329 0.138311 0.042936 -v 0.035511 0.138533 0.044001 -v 0.040000 0.133719 0.039479 -v 0.022245 0.135446 0.039840 -v 0.019752 0.135447 0.039842 -v 0.019085 0.136442 0.040393 -v 0.018651 0.137285 0.041145 -v 0.010160 0.136878 0.040742 -v 0.009952 0.138473 0.043569 -v 0.018544 0.138143 0.042480 -v 0.009607 0.138525 0.043915 -v 0.032390 0.135950 0.040087 -v 0.032085 0.136442 0.040393 -v 0.022915 0.136442 0.040393 -v 0.023486 0.138064 0.042297 -v 0.031860 0.138417 0.043300 -v 0.022607 0.138525 0.043915 -v 0.032092 0.138482 0.043617 -v 0.033609 0.138556 0.044473 -v 0.007725 0.138555 0.044492 -v 0.034000 0.138556 0.044500 -v 0.002000 0.118105 0.041168 -v 0.002000 0.128286 0.043991 -v 0.038000 0.092563 -0.015556 -v 0.038000 0.094483 -0.015241 -v 0.037572 0.094319 -0.015313 -v 0.038000 0.095380 -0.014854 -v 0.033685 0.095947 -0.014509 -v 0.021865 0.095908 -0.014540 -v 0.038000 0.096202 -0.014327 -v 0.019811 0.095825 -0.014594 -v 0.018917 0.095483 -0.014798 -v 0.004000 0.096202 -0.014327 -v 0.038000 0.096928 -0.013673 -v 0.004000 0.097538 -0.012910 -v 0.038000 0.097538 -0.012910 -v 0.038000 0.098350 -0.011141 -v 0.004000 0.098515 -0.010312 -v 0.037356 0.098562 -0.009467 -v 0.004941 0.098506 -0.008735 -v 0.037222 0.098552 -0.009205 -v 0.037118 0.098531 -0.008941 -v 0.004255 0.093973 -0.015394 -v 0.004000 0.095380 -0.014854 -v 0.018179 0.095028 -0.015028 -v 0.017158 0.093811 -0.015445 -v 0.011740 0.094093 -0.015389 -v 0.030695 0.094629 -0.015204 -v 0.037818 0.150737 0.043819 -v 0.003732 0.150288 0.046171 -v 0.032676 0.150427 0.045637 -v 0.022704 0.150452 0.045524 -v 0.034980 0.150406 0.045737 -v 0.038598 0.149958 0.047008 -v 0.018425 0.148944 0.048488 -v 0.002951 0.149507 0.047786 -v 0.039612 0.148944 0.048488 -v 0.031540 0.150517 0.045144 -v 0.004000 0.149854 0.039620 -v 0.023821 0.150028 0.039972 -v 0.038000 0.149327 0.038798 -v 0.038000 0.149854 0.039620 -v 0.017814 0.150160 0.040277 -v 0.004000 0.150241 0.040517 -v 0.004000 0.148673 0.038072 -v 0.004000 0.147910 0.037462 -v 0.038000 0.147059 0.036984 -v 0.004000 0.147059 0.036984 -v 0.004000 0.146141 0.036650 -v 0.037880 0.145181 0.036470 -v 0.004643 0.144467 0.036438 -v 0.004778 0.144205 0.036448 -v 0.037015 0.143487 0.036533 -v 0.037309 0.150203 0.040380 -v 0.037945 0.150532 0.041459 -v 0.038000 0.150241 0.040517 -v 0.038000 0.079193 -0.016025 -v 0.038000 0.077770 -0.016600 -v 0.038000 0.077232 -0.016921 -v 0.038000 0.076452 -0.017386 -v 0.004000 0.075803 -0.017910 -v 0.004000 0.074791 -0.018860 -v 0.038000 0.074251 -0.019512 -v 0.038000 0.073572 -0.020566 -v 0.038000 0.072821 -0.022136 -v 0.004000 0.072821 -0.022136 -v 0.002000 0.096579 0.028521 -v 0.003392 0.098567 0.031457 -v 0.005997 0.103016 0.029010 -v 0.002670 0.094230 0.029376 -v 0.003170 0.093559 0.029620 -v 0.003339 0.094466 0.031325 -v 0.004500 0.092510 0.030002 -v 0.003786 0.092980 0.029831 -v 0.004151 0.093174 0.030885 -v 0.002560 0.095797 0.030972 -v 0.005787 0.092725 0.031558 -v 0.005282 0.094132 0.032628 -v 0.007000 0.100115 0.032057 -v 0.005632 0.099445 0.032476 -v 0.004611 0.099111 0.032198 -v 0.002423 0.097716 0.030288 -v 0.002073 0.096707 0.029585 -v 0.007000 0.093954 0.032777 -v 0.007000 0.094700 0.033154 -v 0.007000 0.095497 0.033403 -v 0.005218 0.095692 0.033196 -v 0.005713 0.097559 0.033289 -v 0.004013 0.096919 0.032600 -v 0.007000 0.099477 0.032596 -v 0.002301 0.100518 0.026997 -v 0.002930 0.101301 0.027948 -v 0.003871 0.102344 0.028255 -v 0.003134 0.102118 0.026829 -v 0.003167 0.101993 0.024895 -v 0.002075 0.100073 0.026244 -v 0.003819 0.102632 0.024702 -v 0.002647 0.101525 0.025555 -v 0.002302 0.100360 0.025121 -v 0.004552 0.103401 0.026625 -v 0.004500 0.102786 0.024062 -v 0.006133 0.103318 0.023792 -v 0.005716 0.103706 0.024983 -v 0.004948 0.102207 0.029369 -v 0.007000 0.103023 0.023189 -v 0.007000 0.103732 0.024583 -v 0.005832 0.103850 0.026783 -v 0.007000 0.103430 0.028396 -v 0.002076 0.095763 0.028818 -v 0.002302 0.085117 0.002029 -v 0.002302 0.094972 0.029106 -v 0.003786 0.083125 0.002754 -v 0.005290 0.092164 0.030128 -v 0.006132 0.091952 0.030205 -v 0.006132 0.095877 0.005971 -v 0.007000 0.095952 0.005959 -v 0.006132 0.100430 0.019266 -v 0.007000 0.098458 0.014997 -v 0.004500 0.095290 0.006060 -v 0.003783 0.094275 0.000531 -v 0.003170 0.094186 0.006229 -v 0.002670 0.093481 0.006336 -v 0.003169 0.093673 0.000680 -v 0.002668 0.092967 0.001032 -v 0.002302 0.092700 0.006456 -v 0.002302 0.092233 0.001388 -v 0.002076 0.091868 0.006583 -v 0.002077 0.091325 0.000573 -v 0.007000 0.096198 0.007107 -v 0.006132 0.096863 0.010573 -v 0.005290 0.095654 0.006005 -v 0.005290 0.096645 0.010633 -v 0.004500 0.096290 0.010732 -v 0.003786 0.095808 0.010865 -v 0.003786 0.094796 0.006136 -v 0.002670 0.094527 0.011221 -v 0.002076 0.092954 0.011657 -v 0.006132 0.098387 0.015026 -v 0.004500 0.097838 0.015251 -v 0.003786 0.097376 0.015441 -v 0.003170 0.096805 0.015675 -v 0.003170 0.095215 0.011030 -v 0.002302 0.093765 0.011432 -v 0.005290 0.100233 0.019376 -v 0.005290 0.098179 0.015112 -v 0.004500 0.099911 0.019555 -v 0.003786 0.099475 0.019799 -v 0.002670 0.098313 0.020446 -v 0.002302 0.097623 0.020831 -v 0.002670 0.096145 0.015946 -v 0.002302 0.095414 0.016246 -v 0.002076 0.096887 0.021241 -v 0.002076 0.094635 0.016566 -v 0.002000 0.096129 0.021663 -v 0.005290 0.103117 0.023897 -v 0.003170 0.098936 0.020099 -v 0.002000 0.098976 0.026125 -v 0.002072 0.086061 0.000594 -v 0.003231 0.085883 -0.001832 -v 0.004152 0.082953 -0.000281 -v 0.004898 0.084772 -0.002692 -v 0.005411 0.083520 -0.002172 -v 0.006166 0.085887 -0.003477 -v 0.005299 0.086263 -0.003256 -v 0.005702 0.082119 -0.000218 -v 0.006132 0.082097 0.003128 -v 0.005710 0.081875 0.001879 -v 0.005290 0.082309 0.003051 -v 0.004500 0.082655 0.002925 -v 0.004138 0.082560 0.001481 -v 0.003170 0.083704 0.002543 -v 0.002670 0.084375 0.002299 -v 0.002783 0.083924 0.001285 -v 0.002076 0.085908 0.001741 -v 0.007000 0.085856 -0.003480 -v 0.007000 0.085014 -0.003255 -v 0.007000 0.083510 -0.002387 -v 0.007000 0.082394 -0.001056 -v 0.007000 0.081800 0.000575 -v 0.007000 0.081800 0.002312 -v 0.002930 0.084544 -0.000767 -v 0.006085 0.094607 -0.001293 -v 0.002000 0.090523 0.001444 -v 0.005538 0.093434 -0.002350 -v 0.004319 0.093944 -0.001164 -v 0.004812 0.090900 -0.003069 -v 0.003165 0.092657 -0.001099 -v 0.007000 0.095420 0.000434 -v 0.004500 0.094808 0.000936 -v 0.005260 0.095092 0.000104 -v 0.006129 0.095379 0.000585 -v 0.002845 0.091057 -0.001366 -v 0.002000 0.086724 0.001444 -v 0.002298 0.091116 -0.000252 -v 0.002489 0.086338 -0.000751 -v 0.003873 0.091648 -0.002449 -v 0.004188 0.086320 -0.002710 -v 0.003786 0.097292 0.042191 -v 0.005290 0.096678 0.041577 -v 0.006132 0.105393 0.032542 -v 0.006132 0.096518 0.041418 -v 0.007000 0.096464 0.041364 -v 0.003167 0.110074 0.032989 -v 0.003765 0.110095 0.032295 -v 0.005391 0.109671 0.031274 -v 0.004500 0.105813 0.032962 -v 0.003786 0.106167 0.033316 -v 0.004180 0.107462 0.032025 -v 0.003170 0.106603 0.033752 -v 0.002670 0.107107 0.034256 -v 0.002302 0.107666 0.034815 -v 0.002076 0.108751 0.034918 -v 0.005289 0.111100 0.031881 -v 0.002862 0.107997 0.033234 -v 0.005290 0.105553 0.032702 -v 0.005712 0.106324 0.031882 -v 0.005713 0.107727 0.031296 -v 0.007000 0.105936 0.031979 -v 0.007000 0.106604 0.031570 -v 0.007000 0.111142 0.031567 -v 0.006131 0.111206 0.031682 -v 0.002076 0.098794 0.044881 -v 0.002670 0.098232 0.043132 -v 0.002302 0.098791 0.043690 -v 0.002870 0.097393 0.046206 -v 0.002000 0.100000 0.044899 -v 0.003170 0.097727 0.042627 -v 0.004137 0.096236 0.043129 -v 0.004141 0.096166 0.046522 -v 0.003411 0.098731 0.048223 -v 0.004500 0.096938 0.041838 -v 0.005390 0.095184 0.045127 -v 0.005318 0.098798 0.049534 -v 0.002450 0.099041 0.046854 -v 0.005702 0.095584 0.042792 -v 0.006132 0.100000 0.049824 -v 0.004500 0.100000 0.049230 -v 0.002302 0.100000 0.046610 -v 0.007000 0.095922 0.042006 -v 0.007000 0.095195 0.043515 -v 0.007000 0.095125 0.046012 -v 0.007000 0.095766 0.047560 -v 0.005560 0.097190 0.048888 -v 0.005711 0.095681 0.047143 -v 0.003136 0.096753 0.044217 -v 0.007000 0.099162 0.049829 -v 0.004200 0.097362 0.048164 -v 0.007000 0.133719 0.039479 -v 0.006132 0.124427 0.038137 -v 0.007000 0.111811 0.031977 -v 0.007000 0.115771 0.034503 -v 0.007000 0.120003 0.036542 -v 0.004500 0.115445 0.035089 -v 0.003786 0.115201 0.035525 -v 0.004499 0.110932 0.032210 -v 0.003170 0.114901 0.036064 -v 0.002670 0.109950 0.033749 -v 0.002302 0.114169 0.037377 -v 0.002302 0.109432 0.034357 -v 0.002076 0.113759 0.038113 -v 0.002000 0.108875 0.036024 -v 0.006132 0.115734 0.034570 -v 0.005290 0.115624 0.034767 -v 0.004500 0.119749 0.037162 -v 0.003786 0.119559 0.037624 -v 0.002670 0.114554 0.036687 -v 0.002302 0.118754 0.039586 -v 0.002076 0.118434 0.040365 -v 0.002000 0.113337 0.038871 -v 0.006132 0.119974 0.036613 -v 0.005290 0.119888 0.036821 -v 0.005290 0.124367 0.038355 -v 0.003170 0.123970 0.039785 -v 0.003170 0.119325 0.038195 -v 0.002670 0.123779 0.040473 -v 0.002670 0.119054 0.038855 -v 0.002302 0.123568 0.041235 -v 0.002076 0.123343 0.042046 -v 0.006132 0.129029 0.039123 -v 0.005290 0.128995 0.039346 -v 0.004500 0.128940 0.039710 -v 0.003786 0.128864 0.040204 -v 0.004500 0.124268 0.038710 -v 0.003786 0.124135 0.039192 -v 0.003170 0.128771 0.040813 -v 0.002302 0.128544 0.042300 -v 0.002076 0.128417 0.043132 -v 0.002000 0.123111 0.042883 -v 0.002670 0.128664 0.041519 -v 0.002297 0.134495 0.042864 -v 0.002076 0.100000 0.045768 -v 0.002076 0.133556 0.045768 -v 0.002670 0.100000 0.047399 -v 0.003170 0.100000 0.048113 -v 0.003786 0.100000 0.048730 -v 0.003786 0.133556 0.048730 -v 0.004500 0.133556 0.049230 -v 0.005290 0.100000 0.049598 -v 0.005290 0.133556 0.049598 -v 0.007000 0.100000 0.049899 -v 0.006085 0.136292 0.040393 -v 0.006127 0.138411 0.043665 -v 0.006500 0.138515 0.044009 -v 0.003239 0.136913 0.043916 -v 0.004731 0.137913 0.043440 -v 0.002076 0.133584 0.043609 -v 0.003128 0.136236 0.042603 -v 0.005538 0.137880 0.042434 -v 0.004537 0.137168 0.042020 -v 0.004405 0.135817 0.040751 -v 0.005538 0.137350 0.041566 -v 0.005834 0.136682 0.040752 -v 0.002669 0.134273 0.042040 -v 0.005289 0.134667 0.039872 -v 0.006121 0.134679 0.039648 -v 0.006393 0.135868 0.040085 -v 0.003160 0.134703 0.041375 -v 0.003786 0.134202 0.040697 -v 0.007000 0.134566 0.039580 -v 0.004500 0.134300 0.040205 -v 0.002000 0.133556 0.044899 -v 0.002670 0.133556 0.047399 -v 0.002302 0.133556 0.046610 -v 0.002445 0.134670 0.046767 -v 0.003170 0.133556 0.048113 -v 0.003151 0.136389 0.046670 -v 0.003482 0.134833 0.048281 -v 0.004120 0.137666 0.045443 -v 0.004791 0.135006 0.049205 -v 0.005303 0.136817 0.048398 -v 0.006105 0.135266 0.049565 -v 0.007000 0.138480 0.045768 -v 0.005318 0.137894 0.046902 -v 0.007000 0.136056 0.049230 -v 0.007000 0.135266 0.049598 -v 0.006132 0.133556 0.049824 -v 0.007000 0.134425 0.049824 -v 0.007000 0.133556 0.049899 -v 0.002097 0.134774 0.044968 -v 0.005627 0.138381 0.045331 -v 0.007000 0.138556 0.044899 -v 0.038000 0.073420 -0.020803 -v 0.038467 0.073878 -0.019230 -v 0.039125 0.074488 -0.017555 -v 0.038000 0.074576 -0.019146 -v 0.038000 0.075269 -0.018364 -v 0.040177 0.075197 -0.015608 -v 0.038000 0.075808 -0.017918 -v 0.038000 0.078806 -0.016181 -v 0.042000 0.082218 -0.011556 -v 0.038000 0.080687 -0.015674 -v 0.042000 0.080075 -0.011721 -v 0.038000 0.080484 -0.015722 -v 0.038268 0.150288 0.046171 -v 0.042000 0.146556 0.042437 -v 0.038417 0.150139 0.046595 -v 0.039049 0.149507 0.047786 -v 0.037993 0.098514 -0.010315 -v 0.038000 0.098016 -0.012059 -v 0.042000 0.093339 -0.011415 -v 0.038000 0.093536 -0.015477 -v 0.038000 0.146141 0.036650 -v 0.038699 0.144471 0.037081 -v 0.038000 0.147910 0.037462 -v 0.038000 0.148673 0.038072 -v 0.042000 0.146521 0.042052 -v 0.040602 0.094906 -0.001013 -v 0.038707 0.096975 -0.002045 -v 0.041060 0.103976 0.026127 -v 0.040609 0.103915 0.025345 -v 0.040428 0.103840 0.024966 -v 0.040069 0.103433 0.023858 -v 0.040156 0.103598 0.024217 -v 0.038707 0.105847 0.024696 -v 0.040000 0.102796 0.022873 -v 0.038707 0.100709 0.016554 -v 0.040000 0.097737 0.012757 -v 0.038707 0.098425 0.010594 -v 0.038707 0.097611 0.007865 -v 0.040000 0.096277 0.007092 -v 0.038707 0.097169 0.004335 -v 0.038707 0.096827 0.001610 -v 0.040000 0.095521 0.001281 -v 0.040069 0.111142 0.031567 -v 0.040156 0.110783 0.031402 -v 0.041060 0.108873 0.031024 -v 0.041293 0.106245 0.028755 -v 0.040609 0.109655 0.031085 -v 0.038707 0.108076 0.026924 -v 0.038707 0.110304 0.029153 -v 0.040429 0.110033 0.031160 -v 0.040274 0.110417 0.031268 -v 0.038707 0.137045 0.038025 -v 0.040695 0.136133 0.040180 -v 0.040265 0.135249 0.039764 -v 0.040082 0.134566 0.039580 -v 0.038707 0.133390 0.038173 -v 0.040021 0.134148 0.039512 -v 0.038707 0.127135 0.037389 -v 0.038707 0.124406 0.036575 -v 0.038707 0.121095 0.035587 -v 0.038707 0.118446 0.034291 -v 0.038707 0.115433 0.032817 -v 0.040000 0.116846 0.034992 -v 0.040000 0.112127 0.032204 -v 0.038707 0.097082 -0.004688 -v 0.041294 0.136887 0.040750 -v 0.003580 0.071819 -0.024889 -v 0.004000 0.080553 -0.015696 -v 0.004000 0.078932 -0.016112 -v 0.004000 0.078802 -0.016169 -v 0.004000 0.077404 -0.016791 -v -0.000000 0.075478 -0.013285 -v 0.004000 0.077226 -0.016909 -v 0.004000 0.076011 -0.017716 -v 0.004000 0.074576 -0.019143 -v 0.000000 0.070403 -0.018045 -v 0.004000 0.073779 -0.020191 -v 0.004000 0.073581 -0.020569 -v 0.004000 0.073003 -0.021672 -v 0.004000 0.098350 -0.011141 -v 0.000707 0.095204 -0.008962 -v 0.004000 0.098016 -0.012059 -v 0.004000 0.096928 -0.013673 -v -0.000000 0.093527 -0.011309 -v 0.004000 0.094483 -0.015241 -v 0.004000 0.093536 -0.015477 -v 0.003299 0.097081 -0.004645 -v 0.000709 0.094469 -0.004553 -v 0.000709 0.094266 0.002096 -v 0.003299 0.096832 0.001638 -v 0.000705 0.100006 0.020972 -v 0.003293 0.110295 0.029145 -v 0.000707 0.108600 0.031098 -v 0.003297 0.121072 0.035576 -v 0.000709 0.119957 0.037914 -v 0.003299 0.127101 0.037379 -v 0.003301 0.133348 0.038167 -v 0.003303 0.139615 0.037921 -v 0.003301 0.144088 0.037148 -v 0.000702 0.144559 0.039701 -v 0.004000 0.149327 0.038798 -v 0.004052 0.150528 0.041451 -v 0.000000 0.146556 0.051049 -v 0.002388 0.148944 0.048488 -v 0.000000 0.146556 0.042437 -v 0.003402 0.149958 0.047008 -v 0.003583 0.150139 0.046595 -v 0.041492 0.145235 0.040013 -v 0.041902 0.145914 0.040818 -v 0.041299 0.144372 0.039728 -v 0.041293 0.141259 0.040310 -v 0.041293 0.103964 0.026473 -v 0.042000 0.106568 0.031589 -v 0.041985 0.103427 0.028394 -v 0.041691 0.107329 0.031269 -v 0.041691 0.103731 0.027671 -v -0.000000 0.092763 -0.004721 -v 0.000087 0.094151 -0.010932 -v 0.000582 0.095113 -0.010076 -v 0.000165 0.145785 0.040620 -v 0.000000 0.143879 0.041452 -v 0.000709 0.139545 0.040534 -v 0.000709 0.132900 0.040734 -v 0.000707 0.126306 0.039856 -v 0.000707 0.123688 0.039057 -v -0.000000 0.119323 0.039503 -v -0.000000 0.113119 0.036434 -v 0.000708 0.113995 0.034967 -v 0.000707 0.103916 0.026415 -v 0.000000 0.101645 0.026173 -v 0.000707 0.101852 0.023543 -v 0.000000 0.098566 0.021881 -v -0.000000 0.095497 0.015677 -v 0.000707 0.097084 0.015048 -v 0.000709 0.095147 0.008687 -v -0.000000 0.093476 0.009058 -v 0.004120 0.098530 -0.010181 -v 0.004485 0.098560 -0.009718 -v 0.004825 0.098543 -0.009089 -v 0.004643 0.098562 -0.009467 -v 0.004007 0.145315 0.036486 -v 0.005000 0.143238 0.036584 -v 0.004973 0.143599 0.036513 -v 0.004401 0.144837 0.036444 -v 0.004882 0.143941 0.036469 -v 0.005000 0.139601 0.037217 -v 0.005000 0.137007 0.037322 -v 0.005000 0.133420 0.037467 -v 0.005000 0.124602 0.035898 -v 0.003295 0.115417 0.032806 -v 0.005000 0.115795 0.032209 -v 0.005000 0.113359 0.030469 -v 0.005000 0.110761 0.028613 -v 0.003291 0.105840 0.024688 -v 0.005000 0.106387 0.024239 -v 0.005000 0.104531 0.021641 -v 0.003290 0.102178 0.019560 -v 0.005000 0.102791 0.019205 -v 0.003293 0.099413 0.013905 -v 0.005000 0.099102 0.010397 -v 0.003298 0.097620 0.007893 -v 0.005000 0.098303 0.007719 -v 0.003301 0.097919 -0.009471 -v 0.005000 0.098416 -0.008238 -v 0.004985 0.098467 -0.008487 -v 0.041540 0.093682 -0.002433 -v 0.041293 0.094690 -0.006259 -v 0.041293 0.094281 -0.002187 -v 0.041295 0.095278 -0.009364 -v 0.041861 0.094241 -0.010904 -v 0.041496 0.094994 -0.010175 -v 0.038000 0.145312 0.036485 -v 0.037515 0.144718 0.036440 -v 0.037059 0.143735 0.036494 -v 0.037171 0.144095 0.036454 -v 0.037357 0.144467 0.036438 -v 0.037027 0.098487 -0.008599 -v 0.037599 0.098556 -0.009837 -v 0.038707 0.139688 0.037918 -v 0.037000 0.133420 0.037467 -v 0.038707 0.130665 0.037831 -v 0.037000 0.124602 0.035898 -v 0.037000 0.118753 0.033656 -v 0.037000 0.113359 0.030469 -v 0.038707 0.112951 0.031044 -v 0.037000 0.110761 0.028613 -v 0.037000 0.108574 0.026426 -v 0.037000 0.106387 0.024239 -v 0.037000 0.104531 0.021641 -v 0.038707 0.103956 0.022049 -v 0.038707 0.102183 0.019567 -v 0.037000 0.101344 0.016247 -v 0.038707 0.099413 0.013905 -v 0.037000 0.098303 0.007719 -v 0.038710 0.097842 -0.009052 -v 0.020795 0.135556 0.039508 -v 0.021000 0.149056 0.044500 -v 0.021338 0.138556 0.044477 -v 0.021434 0.149056 0.044462 -v 0.021852 0.138556 0.044359 -v 0.022349 0.138543 0.044108 -v 0.022250 0.149056 0.044165 -v 0.022607 0.149056 0.043915 -v 0.023165 0.149056 0.043250 -v 0.022952 0.138473 0.043569 -v 0.022915 0.149056 0.043607 -v 0.023462 0.149056 0.042434 -v 0.023362 0.138275 0.042822 -v 0.023349 0.149056 0.042855 -v 0.023222 0.138379 0.043151 -v 0.023500 0.149056 0.042000 -v 0.023349 0.149056 0.041145 -v 0.023477 0.137672 0.041632 -v 0.022915 0.149056 0.040393 -v 0.023160 0.136878 0.040742 -v 0.023349 0.137286 0.041146 -v 0.022607 0.149056 0.040085 -v 0.019390 0.135950 0.040087 -v 0.019085 0.149056 0.040393 -v 0.018835 0.149056 0.040750 -v 0.018651 0.149056 0.041145 -v 0.018852 0.136862 0.040725 -v 0.018538 0.149056 0.042434 -v 0.018517 0.137699 0.041664 -v 0.018734 0.138350 0.043055 -v 0.018651 0.149056 0.042855 -v 0.019393 0.149056 0.043915 -v 0.019434 0.138530 0.043955 -v 0.019085 0.149056 0.043607 -v 0.019092 0.138482 0.043617 -v 0.018860 0.138417 0.043300 -v 0.020145 0.149056 0.044349 -v 0.019799 0.138549 0.044198 -v 0.021000 0.138556 0.044500 -v 0.020609 0.138556 0.044473 -v 0.020201 0.138556 0.044374 -v 0.022709 0.136099 0.040173 -v 0.022250 0.149056 0.039835 -v 0.021855 0.149056 0.039651 -v 0.022000 0.135556 0.039709 -v 0.021205 0.135556 0.039508 -v 0.021611 0.135556 0.039576 -v 0.021434 0.149056 0.039538 -v 0.020566 0.149056 0.039538 -v 0.019750 0.149056 0.039835 -v 0.020000 0.135556 0.039709 -v 0.020389 0.135556 0.039576 -v 0.018500 0.149056 0.042000 -v 0.017027 0.150517 0.041579 -v 0.018538 0.149056 0.041566 -v 0.022189 0.149594 0.039175 -v 0.021000 0.149056 0.039500 -v 0.020762 0.149507 0.039048 -v 0.020145 0.149056 0.039651 -v 0.019393 0.149056 0.040085 -v 0.019311 0.149690 0.039324 -v 0.023083 0.149798 0.039517 -v 0.023165 0.149056 0.040750 -v 0.024960 0.150499 0.041401 -v 0.023462 0.149056 0.041566 -v 0.019676 0.150427 0.045637 -v 0.020333 0.150395 0.045780 -v 0.020566 0.149056 0.044462 -v 0.021000 0.150383 0.045827 -v 0.021667 0.150395 0.045780 -v 0.021855 0.149056 0.044349 -v 0.019750 0.149056 0.044165 -v 0.018535 0.150517 0.045140 -v 0.023961 0.150554 0.044721 -v 0.018835 0.149056 0.043250 -v 0.017320 0.150556 0.043627 -v 0.007779 0.135556 0.039510 -v 0.007370 0.135556 0.039581 -v 0.005835 0.149056 0.040750 -v 0.005651 0.137032 0.041145 -v 0.005500 0.137633 0.042000 -v 0.005723 0.138183 0.043060 -v 0.006085 0.149056 0.043607 -v 0.007175 0.138568 0.044361 -v 0.007145 0.149056 0.044349 -v 0.006750 0.149056 0.044165 -v 0.007566 0.149056 0.044462 -v 0.008000 0.149056 0.044500 -v 0.008450 0.138556 0.044466 -v 0.008855 0.149056 0.044349 -v 0.009197 0.138551 0.044208 -v 0.009250 0.149056 0.044165 -v 0.010165 0.149056 0.043250 -v 0.010222 0.138379 0.043151 -v 0.010362 0.138275 0.042822 -v 0.010349 0.149056 0.042855 -v 0.010462 0.149056 0.041566 -v 0.010477 0.137672 0.041632 -v 0.010486 0.138064 0.042297 -v 0.010165 0.149056 0.040750 -v 0.010349 0.137286 0.041146 -v 0.009709 0.136099 0.040173 -v 0.009915 0.149056 0.040393 -v 0.009915 0.136442 0.040393 -v 0.009254 0.135459 0.039846 -v 0.009250 0.149056 0.039835 -v 0.008996 0.135556 0.039707 -v 0.008603 0.135556 0.039574 -v 0.008000 0.149056 0.039500 -v 0.008194 0.135556 0.039508 -v 0.007566 0.149056 0.039538 -v 0.006853 0.135321 0.039774 -v 0.007145 0.149056 0.039651 -v 0.005538 0.149056 0.041566 -v 0.005500 0.149056 0.042000 -v 0.006085 0.149056 0.040393 -v 0.005651 0.149056 0.041145 -v 0.009821 0.149735 0.039409 -v 0.008627 0.149523 0.039071 -v 0.008855 0.149056 0.039651 -v 0.008434 0.149056 0.039538 -v 0.006946 0.149573 0.039141 -v 0.006750 0.149056 0.039835 -v 0.006393 0.149056 0.040085 -v 0.005201 0.150010 0.039890 -v 0.011266 0.150184 0.040316 -v 0.009607 0.149056 0.040085 -v 0.010349 0.149056 0.041145 -v 0.011996 0.150537 0.041797 -v 0.010500 0.149056 0.042000 -v 0.009915 0.149056 0.043607 -v 0.008304 0.150383 0.045829 -v 0.008434 0.149056 0.044462 -v 0.009704 0.150452 0.045523 -v 0.009607 0.149056 0.043915 -v 0.010961 0.150554 0.044721 -v 0.006244 0.150443 0.045553 -v 0.006393 0.149056 0.043915 -v 0.005835 0.149056 0.043250 -v 0.011731 0.150556 0.043472 -v 0.010462 0.149056 0.042434 -v 0.005538 0.149056 0.042434 -v 0.005651 0.149056 0.042855 -v 0.032752 0.135445 0.039842 -v 0.033389 0.135556 0.039576 -v 0.034000 0.149056 0.044500 -v 0.034338 0.138556 0.044477 -v 0.034852 0.138556 0.044359 -v 0.035250 0.149056 0.044165 -v 0.035915 0.149056 0.043607 -v 0.035607 0.149056 0.043915 -v 0.036500 0.149056 0.042000 -v 0.036494 0.138035 0.042224 -v 0.036462 0.149056 0.041566 -v 0.036352 0.137276 0.041151 -v 0.036477 0.137676 0.041637 -v 0.035607 0.149056 0.040085 -v 0.035915 0.149056 0.040393 -v 0.036163 0.136888 0.040747 -v 0.031852 0.136862 0.040725 -v 0.031835 0.149056 0.040750 -v 0.031651 0.137285 0.041145 -v 0.031500 0.149056 0.042000 -v 0.031517 0.137699 0.041664 -v 0.031538 0.149056 0.041566 -v 0.031651 0.149056 0.042855 -v 0.031734 0.138350 0.043055 -v 0.031544 0.138143 0.042480 -v 0.032085 0.149056 0.043607 -v 0.032434 0.138530 0.043954 -v 0.031835 0.149056 0.043250 -v 0.033145 0.149056 0.044349 -v 0.032750 0.149056 0.044165 -v 0.032799 0.138549 0.044198 -v 0.032393 0.149056 0.043915 -v 0.033201 0.138556 0.044374 -v 0.035258 0.135467 0.039848 -v 0.035000 0.135556 0.039709 -v 0.034855 0.149056 0.039651 -v 0.034205 0.135556 0.039508 -v 0.034611 0.135556 0.039576 -v 0.034000 0.149056 0.039500 -v 0.033795 0.135556 0.039508 -v 0.032393 0.149056 0.040085 -v 0.032750 0.149056 0.039835 -v 0.033145 0.149056 0.039651 -v 0.033000 0.135556 0.039709 -v 0.030027 0.150517 0.041579 -v 0.031538 0.149056 0.042434 -v 0.030706 0.150205 0.040400 -v 0.031651 0.149056 0.041145 -v 0.035250 0.149056 0.039835 -v 0.034434 0.149056 0.039538 -v 0.033764 0.149506 0.039049 -v 0.033566 0.149056 0.039538 -v 0.031870 0.149797 0.039492 -v 0.032085 0.149056 0.040393 -v 0.035461 0.149628 0.039238 -v 0.036165 0.149056 0.040750 -v 0.036349 0.149056 0.041145 -v 0.036462 0.149056 0.042434 -v 0.033633 0.150384 0.045824 -v 0.033566 0.149056 0.044462 -v 0.034434 0.149056 0.044462 -v 0.034855 0.149056 0.044349 -v 0.036294 0.150504 0.045248 -v 0.036165 0.149056 0.043250 -v 0.036349 0.149056 0.042855 -v 0.037996 0.150561 0.042454 -v 0.030320 0.150556 0.043627 -v 0.019747 0.095155 -0.000458 -v 0.020389 0.095424 -0.000556 -v 0.020795 0.095492 -0.000556 -v 0.021205 0.095492 -0.000556 -v 0.021000 0.090500 -0.014056 -v 0.020566 0.090538 -0.014056 -v 0.020551 0.090533 -0.003556 -v 0.020145 0.090651 -0.014056 -v 0.019803 0.090792 -0.003551 -v 0.019393 0.091085 -0.003525 -v 0.018835 0.091750 -0.014056 -v 0.019085 0.091393 -0.014056 -v 0.019393 0.091085 -0.014056 -v 0.018778 0.091849 -0.003379 -v 0.018638 0.092178 -0.003275 -v 0.018651 0.092145 -0.014056 -v 0.018500 0.093000 -0.014056 -v 0.018538 0.092566 -0.014056 -v 0.018514 0.092703 -0.003064 -v 0.018651 0.093854 -0.002286 -v 0.018523 0.093368 -0.002672 -v 0.018840 0.094258 -0.001878 -v 0.019291 0.094827 -0.001099 -v 0.019085 0.094607 -0.001442 -v 0.022915 0.094607 -0.001442 -v 0.022915 0.094607 -0.014056 -v 0.023148 0.094275 -0.001862 -v 0.023349 0.093855 -0.002285 -v 0.023500 0.093000 -0.014056 -v 0.023483 0.093336 -0.002699 -v 0.023266 0.091945 -0.003350 -v 0.023456 0.092520 -0.003143 -v 0.022915 0.091393 -0.014056 -v 0.022908 0.091383 -0.003482 -v 0.023140 0.091700 -0.003417 -v 0.022201 0.090802 -0.003549 -v 0.022566 0.091046 -0.003530 -v 0.021341 0.090523 -0.003556 -v 0.021434 0.090538 -0.014056 -v 0.021802 0.090629 -0.003556 -v 0.020000 0.095291 -0.000556 -v 0.019750 0.095165 -0.014056 -v 0.020566 0.095462 -0.014056 -v 0.021000 0.095500 -0.014056 -v 0.021611 0.095424 -0.000556 -v 0.022610 0.094913 -0.000950 -v 0.022250 0.095165 -0.014056 -v 0.022000 0.095291 -0.000556 -v 0.023349 0.093855 -0.014056 -v 0.023462 0.093434 -0.014056 -v 0.024807 0.093890 -0.015430 -v 0.023165 0.094250 -0.014056 -v 0.020145 0.095349 -0.014056 -v 0.021434 0.095462 -0.014056 -v 0.021855 0.095349 -0.014056 -v 0.023083 0.095483 -0.014798 -v 0.022607 0.094915 -0.014056 -v 0.023881 0.094972 -0.015050 -v 0.019085 0.094607 -0.014056 -v 0.019393 0.094915 -0.014056 -v 0.018651 0.093855 -0.014056 -v 0.018835 0.094250 -0.014056 -v 0.018538 0.093434 -0.014056 -v 0.023462 0.092566 -0.014056 -v 0.023349 0.092145 -0.014056 -v 0.023165 0.091750 -0.014056 -v 0.022607 0.091085 -0.014056 -v 0.022250 0.090835 -0.014056 -v 0.023000 0.089536 -0.015556 -v 0.021855 0.090651 -0.014056 -v 0.022017 0.089116 -0.015556 -v 0.021000 0.089000 -0.015556 -v 0.019928 0.089131 -0.015556 -v 0.019750 0.090835 -0.014056 -v 0.009249 0.095157 -0.000449 -v 0.006393 0.094915 -0.000868 -v 0.006393 0.094915 -0.014056 -v 0.008000 0.090500 -0.014056 -v 0.007145 0.090651 -0.014056 -v 0.006740 0.090825 -0.003538 -v 0.006750 0.090835 -0.014056 -v 0.006085 0.091393 -0.014056 -v 0.006393 0.091085 -0.014056 -v 0.005538 0.092566 -0.014056 -v 0.005668 0.092086 -0.003120 -v 0.005835 0.091750 -0.014056 -v 0.006054 0.091413 -0.003460 -v 0.005500 0.093000 -0.014056 -v 0.005538 0.092566 -0.002880 -v 0.005500 0.093000 -0.002633 -v 0.005835 0.094250 -0.014056 -v 0.005834 0.094248 -0.001675 -v 0.005651 0.093855 -0.014056 -v 0.005651 0.093855 -0.002032 -v 0.010148 0.094275 -0.001862 -v 0.010462 0.093434 -0.014056 -v 0.010349 0.093855 -0.014056 -v 0.010483 0.093336 -0.002699 -v 0.010349 0.092145 -0.014056 -v 0.010462 0.092566 -0.014056 -v 0.009915 0.091393 -0.014056 -v 0.009908 0.091383 -0.003482 -v 0.010140 0.091700 -0.003417 -v 0.009607 0.091085 -0.014056 -v 0.008802 0.090629 -0.003556 -v 0.008855 0.090651 -0.014056 -v 0.006865 0.095231 -0.000274 -v 0.007779 0.095490 -0.000556 -v 0.007566 0.095462 -0.014056 -v 0.007370 0.095419 -0.000556 -v 0.008194 0.095492 -0.000556 -v 0.008434 0.095462 -0.014056 -v 0.009610 0.094913 -0.000950 -v 0.009607 0.094915 -0.014056 -v 0.008996 0.095293 -0.000556 -v 0.008855 0.095349 -0.014056 -v 0.008603 0.095426 -0.000556 -v 0.010500 0.093000 -0.014056 -v 0.010165 0.094250 -0.014056 -v 0.006750 0.095165 -0.014056 -v 0.007145 0.095349 -0.014056 -v 0.005960 0.095591 -0.014745 -v 0.008000 0.095500 -0.014056 -v 0.008236 0.095951 -0.014506 -v 0.010130 0.095508 -0.014797 -v 0.009250 0.095165 -0.014056 -v 0.009915 0.094607 -0.014056 -v 0.006085 0.094607 -0.014056 -v 0.005538 0.093434 -0.014056 -v 0.011900 0.092024 -0.015558 -v 0.010165 0.091750 -0.014056 -v 0.009250 0.090835 -0.014056 -v 0.008434 0.090538 -0.014056 -v 0.009684 0.089388 -0.015556 -v 0.007566 0.090538 -0.014056 -v 0.007593 0.088946 -0.015556 -v 0.005675 0.089727 -0.015556 -v 0.005651 0.092145 -0.014056 -v 0.003999 0.092419 -0.015556 -v 0.032756 0.095161 -0.000446 -v 0.033795 0.095492 -0.000556 -v 0.035238 0.095165 -0.000434 -v 0.034000 0.090500 -0.003556 -v 0.033566 0.090538 -0.014056 -v 0.033551 0.090533 -0.003556 -v 0.033145 0.090651 -0.014056 -v 0.032803 0.090792 -0.003551 -v 0.032085 0.091393 -0.014056 -v 0.032393 0.091085 -0.014056 -v 0.032393 0.091085 -0.003525 -v 0.031778 0.091849 -0.003379 -v 0.032047 0.091431 -0.003473 -v 0.031500 0.093000 -0.014056 -v 0.031538 0.092566 -0.014056 -v 0.031651 0.093854 -0.002286 -v 0.031523 0.093368 -0.002672 -v 0.031538 0.093434 -0.014056 -v 0.031840 0.094258 -0.001878 -v 0.032750 0.095165 -0.014056 -v 0.032085 0.094607 -0.001442 -v 0.032085 0.094607 -0.014056 -v 0.035609 0.094914 -0.000943 -v 0.035915 0.094607 -0.014056 -v 0.036165 0.094250 -0.014056 -v 0.036349 0.093855 -0.014056 -v 0.036353 0.093846 -0.002278 -v 0.036462 0.092566 -0.014056 -v 0.036469 0.092602 -0.003100 -v 0.036500 0.093000 -0.014056 -v 0.036485 0.093317 -0.002710 -v 0.036462 0.093434 -0.014056 -v 0.036342 0.092116 -0.003295 -v 0.036349 0.092145 -0.014056 -v 0.035915 0.091393 -0.014056 -v 0.036054 0.091553 -0.003464 -v 0.035250 0.090835 -0.014056 -v 0.035201 0.090802 -0.003549 -v 0.035607 0.091085 -0.014056 -v 0.034389 0.090527 -0.003556 -v 0.034799 0.090626 -0.003556 -v 0.033000 0.095291 -0.000556 -v 0.033145 0.095349 -0.014056 -v 0.033389 0.095424 -0.000556 -v 0.034000 0.095500 -0.014056 -v 0.034205 0.095492 -0.000556 -v 0.034434 0.095462 -0.014056 -v 0.034611 0.095424 -0.000556 -v 0.035250 0.095165 -0.014056 -v 0.034855 0.095349 -0.014056 -v 0.035000 0.095291 -0.000556 -v 0.033566 0.095462 -0.014056 -v 0.035607 0.094915 -0.014056 -v 0.035741 0.095694 -0.014669 -v 0.032281 0.095660 -0.014698 -v 0.032393 0.094915 -0.014056 -v 0.031835 0.094250 -0.014056 -v 0.031651 0.093855 -0.014056 -v 0.029894 0.092873 -0.015561 -v 0.037477 0.090944 -0.015556 -v 0.036165 0.091750 -0.014056 -v 0.035981 0.089480 -0.015556 -v 0.034855 0.090651 -0.014056 -v 0.034434 0.090538 -0.014056 -v 0.034321 0.088998 -0.015556 -v 0.034000 0.090500 -0.014056 -v 0.032932 0.089130 -0.015556 -v 0.032750 0.090835 -0.014056 -v 0.031835 0.091750 -0.014056 -v 0.031651 0.092145 -0.014056 -v 0.040000 0.101368 0.032865 -v 0.040000 0.100943 0.031228 -v 0.040409 0.102015 0.030156 -v 0.040880 0.102511 0.029660 -v 0.041278 0.102789 0.029359 -v 0.040973 0.102828 0.030630 -v 0.040364 0.104765 0.033064 -v 0.040966 0.104526 0.032225 -v 0.041278 0.105641 0.032211 -v 0.040110 0.102587 0.032424 -v 0.040001 0.100115 0.032057 -v 0.040070 0.099722 0.032410 -v 0.040612 0.098758 0.033022 -v 0.040973 0.098356 0.033195 -v 0.042000 0.098511 0.033829 -v 0.040534 0.099444 0.033478 -v 0.040149 0.101241 0.034822 -v 0.042000 0.099528 0.035141 -v 0.040012 0.102298 0.035530 -v 0.040472 0.101334 0.036495 -v 0.041030 0.100616 0.035981 -v 0.008000 0.059370 0.129883 -v 0.009915 0.059979 0.129229 -v 0.010349 0.060492 0.128679 -v 0.010462 0.061371 0.127737 -v 0.010500 0.061075 0.128054 -v 0.009915 0.062171 0.126879 -v 0.009607 0.062381 0.126654 -v 0.008434 0.062754 0.126254 -v 0.006750 0.062551 0.126471 -v 0.006393 0.062381 0.126654 -v 0.005651 0.061658 0.127429 -v 0.005538 0.060779 0.128372 -v 0.008000 0.059976 0.127030 -v 0.005538 0.061371 0.127737 -v 0.005651 0.060492 0.128679 -v 0.008000 0.066683 0.136703 -v 0.008434 0.059396 0.129855 -v 0.008434 0.066709 0.136675 -v 0.008855 0.059473 0.129772 -v 0.008855 0.066786 0.136592 -v 0.009250 0.059598 0.129638 -v 0.009607 0.059769 0.129455 -v 0.009607 0.067082 0.136275 -v 0.009915 0.067292 0.136049 -v 0.010165 0.060222 0.128968 -v 0.010462 0.060779 0.128372 -v 0.010500 0.068388 0.134874 -v 0.010349 0.061658 0.127429 -v 0.010462 0.068684 0.134557 -v 0.010165 0.061927 0.127140 -v 0.010165 0.069241 0.133960 -v 0.009915 0.069484 0.133699 -v 0.009607 0.069694 0.133474 -v 0.009250 0.062551 0.126471 -v 0.008855 0.062677 0.126336 -v 0.008000 0.062780 0.126226 -v 0.008000 0.070093 0.133046 -v 0.007566 0.062754 0.126254 -v 0.007566 0.070067 0.133074 -v 0.007145 0.062677 0.126336 -v 0.007145 0.069990 0.133156 -v 0.006393 0.069694 0.133474 -v 0.006085 0.062171 0.126879 -v 0.006085 0.069484 0.133699 -v 0.005835 0.061927 0.127140 -v 0.005835 0.069241 0.133960 -v 0.005651 0.068971 0.134249 -v 0.005500 0.061075 0.128054 -v 0.005835 0.060222 0.128968 -v 0.006085 0.059979 0.129229 -v 0.006393 0.059769 0.129455 -v 0.006393 0.067082 0.136275 -v 0.006750 0.059598 0.129638 -v 0.006750 0.066912 0.136458 -v 0.007145 0.059473 0.129772 -v 0.007566 0.059396 0.129855 -v 0.007566 0.066709 0.136675 -v 0.021855 0.059473 0.129772 -v 0.021434 0.059396 0.129855 -v 0.022607 0.059769 0.129455 -v 0.023165 0.060222 0.128968 -v 0.022915 0.059979 0.129229 -v 0.023462 0.061371 0.127737 -v 0.022607 0.062381 0.126654 -v 0.023165 0.061927 0.127140 -v 0.022250 0.062551 0.126471 -v 0.021000 0.062780 0.126226 -v 0.020566 0.062754 0.126254 -v 0.021000 0.059976 0.127030 -v 0.019750 0.062551 0.126471 -v 0.018651 0.061658 0.127429 -v 0.018538 0.060779 0.128372 -v 0.018500 0.061075 0.128054 -v 0.018538 0.061371 0.127737 -v 0.021000 0.059370 0.129883 -v 0.022609 0.067083 0.136274 -v 0.023349 0.060492 0.128679 -v 0.023462 0.060779 0.128372 -v 0.023349 0.067805 0.135499 -v 0.023462 0.068092 0.135192 -v 0.023500 0.061075 0.128054 -v 0.023500 0.068388 0.134874 -v 0.023462 0.068684 0.134557 -v 0.023349 0.061658 0.127429 -v 0.023165 0.069241 0.133960 -v 0.022915 0.062171 0.126879 -v 0.022915 0.069484 0.133699 -v 0.022603 0.069697 0.133471 -v 0.022250 0.069865 0.133291 -v 0.021855 0.062677 0.126336 -v 0.021855 0.069990 0.133156 -v 0.021434 0.062754 0.126254 -v 0.021434 0.070067 0.133074 -v 0.020145 0.062677 0.126336 -v 0.019750 0.069865 0.133291 -v 0.019393 0.062381 0.126654 -v 0.019085 0.062171 0.126879 -v 0.019085 0.069484 0.133699 -v 0.018835 0.061927 0.127140 -v 0.018835 0.069241 0.133960 -v 0.018538 0.068684 0.134557 -v 0.018500 0.068388 0.134874 -v 0.018651 0.067805 0.135499 -v 0.018651 0.060492 0.128679 -v 0.018835 0.067536 0.135788 -v 0.018835 0.060222 0.128968 -v 0.019085 0.059979 0.129229 -v 0.019393 0.059769 0.129455 -v 0.019393 0.067082 0.136275 -v 0.019750 0.059598 0.129638 -v 0.019750 0.066912 0.136458 -v 0.020145 0.059473 0.129772 -v 0.020566 0.059396 0.129855 -v 0.020566 0.066709 0.136675 -v 0.021000 0.066683 0.136703 -v 0.021434 0.066709 0.136675 -v 0.022250 0.059598 0.129638 -v 0.035607 0.059769 0.129455 -v 0.034855 0.059473 0.129772 -v 0.036349 0.061658 0.127429 -v 0.036500 0.061075 0.128054 -v 0.036165 0.061927 0.127140 -v 0.034855 0.062677 0.126336 -v 0.034434 0.062754 0.126254 -v 0.034000 0.059976 0.127030 -v 0.032085 0.062171 0.126879 -v 0.033145 0.062677 0.126336 -v 0.031651 0.061658 0.127429 -v 0.031835 0.061927 0.127140 -v 0.033145 0.059473 0.129772 -v 0.032750 0.059598 0.129638 -v 0.034000 0.059370 0.129883 -v 0.034434 0.059396 0.129855 -v 0.034434 0.066709 0.136675 -v 0.034855 0.066786 0.136592 -v 0.035250 0.059598 0.129638 -v 0.035250 0.066912 0.136458 -v 0.035915 0.059979 0.129229 -v 0.035607 0.067082 0.136275 -v 0.035915 0.067292 0.136049 -v 0.036165 0.060222 0.128968 -v 0.036349 0.060492 0.128679 -v 0.036349 0.067805 0.135499 -v 0.036462 0.060779 0.128372 -v 0.036462 0.068092 0.135192 -v 0.036462 0.061371 0.127737 -v 0.036500 0.068388 0.134874 -v 0.036349 0.068971 0.134249 -v 0.035915 0.062171 0.126879 -v 0.035607 0.062381 0.126654 -v 0.035607 0.069694 0.133474 -v 0.035250 0.069865 0.133291 -v 0.035250 0.062551 0.126471 -v 0.034855 0.069990 0.133156 -v 0.034000 0.062780 0.126226 -v 0.034000 0.070093 0.133046 -v 0.033566 0.062754 0.126254 -v 0.033566 0.070067 0.133074 -v 0.032750 0.062551 0.126471 -v 0.032393 0.062381 0.126654 -v 0.032085 0.069484 0.133699 -v 0.031651 0.068971 0.134249 -v 0.031538 0.068684 0.134557 -v 0.031538 0.061371 0.127737 -v 0.031500 0.061075 0.128054 -v 0.031538 0.060779 0.128372 -v 0.031538 0.068092 0.135192 -v 0.031651 0.067805 0.135499 -v 0.031651 0.060492 0.128679 -v 0.031835 0.060222 0.128968 -v 0.031835 0.067536 0.135788 -v 0.032085 0.059979 0.129229 -v 0.032393 0.059769 0.129455 -v 0.032085 0.067292 0.136049 -v 0.032393 0.067082 0.136275 -v 0.032750 0.066912 0.136458 -v 0.033145 0.066786 0.136592 -v 0.033566 0.059396 0.129855 -v 0.033566 0.066709 0.136675 -v 0.021434 0.125550 0.058913 -v 0.021855 0.125626 0.058831 -v 0.023165 0.126376 0.058027 -v 0.022915 0.126133 0.058288 -v 0.023462 0.127525 0.056795 -v 0.022607 0.128535 0.055712 -v 0.023165 0.128081 0.056199 -v 0.022250 0.128705 0.055529 -v 0.021000 0.128934 0.055284 -v 0.019750 0.128705 0.055529 -v 0.019393 0.128535 0.055712 -v 0.020145 0.128831 0.055395 -v 0.018651 0.127812 0.056488 -v 0.018651 0.126645 0.057738 -v 0.018538 0.127525 0.056795 -v 0.018835 0.126376 0.058027 -v 0.020145 0.125626 0.058831 -v 0.020566 0.125550 0.058913 -v 0.021000 0.125524 0.058941 -v 0.021000 0.126130 0.056088 -v 0.022607 0.125923 0.058513 -v 0.022915 0.133446 0.065108 -v 0.023349 0.126645 0.057738 -v 0.023462 0.126933 0.057430 -v 0.023349 0.133959 0.064558 -v 0.023462 0.134246 0.064250 -v 0.023500 0.127229 0.057113 -v 0.023462 0.134838 0.063615 -v 0.023349 0.127812 0.056488 -v 0.023165 0.135395 0.063019 -v 0.022915 0.128325 0.055938 -v 0.022575 0.135864 0.062516 -v 0.022250 0.136019 0.062349 -v 0.021855 0.128831 0.055395 -v 0.021434 0.128908 0.055312 -v 0.020566 0.128908 0.055312 -v 0.020566 0.136221 0.062132 -v 0.020145 0.136144 0.062215 -v 0.019750 0.136019 0.062349 -v 0.019085 0.128325 0.055938 -v 0.018835 0.128081 0.056199 -v 0.018651 0.135125 0.063308 -v 0.018538 0.134838 0.063615 -v 0.018500 0.127229 0.057113 -v 0.018500 0.134542 0.063933 -v 0.018538 0.126933 0.057430 -v 0.018538 0.134246 0.064250 -v 0.018651 0.133959 0.064558 -v 0.018835 0.133690 0.064847 -v 0.019085 0.126133 0.058288 -v 0.019393 0.125923 0.058513 -v 0.019750 0.125752 0.058696 -v 0.019393 0.133236 0.065333 -v 0.020145 0.132940 0.065651 -v 0.020566 0.132863 0.065733 -v 0.021000 0.132837 0.065761 -v 0.021855 0.132940 0.065651 -v 0.022250 0.125752 0.058696 -v 0.022250 0.133066 0.065516 -v 0.022607 0.133236 0.065333 -v 0.023349 0.092546 0.094306 -v 0.023165 0.092276 0.094595 -v 0.022915 0.094225 0.092505 -v 0.021434 0.094808 0.091880 -v 0.021000 0.094834 0.091852 -v 0.019085 0.094225 0.092505 -v 0.019393 0.094435 0.092280 -v 0.018651 0.093712 0.093055 -v 0.018835 0.093981 0.092766 -v 0.018651 0.092546 0.094306 -v 0.018538 0.093425 0.093363 -v 0.019085 0.092033 0.094856 -v 0.021000 0.092030 0.092656 -v 0.020145 0.091527 0.095399 -v 0.019750 0.091652 0.095264 -v 0.022250 0.091652 0.095264 -v 0.022607 0.091823 0.095081 -v 0.022915 0.092033 0.094856 -v 0.023165 0.099590 0.101415 -v 0.023462 0.092833 0.093998 -v 0.023500 0.093129 0.093681 -v 0.023462 0.093425 0.093363 -v 0.023349 0.093712 0.093055 -v 0.023349 0.101025 0.099875 -v 0.023165 0.093981 0.092766 -v 0.022607 0.094435 0.092280 -v 0.022250 0.094605 0.092097 -v 0.022575 0.101764 0.099084 -v 0.022250 0.101919 0.098917 -v 0.021855 0.094731 0.091962 -v 0.021855 0.102044 0.098782 -v 0.021000 0.102147 0.098672 -v 0.020566 0.094808 0.091880 -v 0.020145 0.094731 0.091962 -v 0.020566 0.102121 0.098700 -v 0.019750 0.094605 0.092097 -v 0.019750 0.101919 0.098917 -v 0.019393 0.101748 0.099100 -v 0.018835 0.101295 0.099586 -v 0.018500 0.093129 0.093681 -v 0.018538 0.100738 0.100183 -v 0.018538 0.092833 0.093998 -v 0.018500 0.100442 0.100501 -v 0.018835 0.092276 0.094595 -v 0.018651 0.099859 0.101126 -v 0.018835 0.099590 0.101415 -v 0.019085 0.099346 0.101676 -v 0.019393 0.091823 0.095081 -v 0.019393 0.099136 0.101901 -v 0.019750 0.098966 0.102084 -v 0.020566 0.091450 0.095481 -v 0.021000 0.091424 0.095509 -v 0.020566 0.098763 0.102301 -v 0.021000 0.098737 0.102329 -v 0.021434 0.091450 0.095481 -v 0.021434 0.098763 0.102301 -v 0.021855 0.091527 0.095399 -v 0.008434 0.125550 0.058913 -v 0.008855 0.125626 0.058831 -v 0.009915 0.126133 0.058288 -v 0.010462 0.126933 0.057430 -v 0.010462 0.127525 0.056795 -v 0.010349 0.127812 0.056488 -v 0.010165 0.128081 0.056199 -v 0.006393 0.128535 0.055712 -v 0.006750 0.128705 0.055529 -v 0.005835 0.128081 0.056199 -v 0.006085 0.128325 0.055938 -v 0.008000 0.126130 0.056088 -v 0.005538 0.126933 0.057430 -v 0.005500 0.127229 0.057113 -v 0.007145 0.125626 0.058831 -v 0.008000 0.125524 0.058941 -v 0.008855 0.132940 0.065651 -v 0.009250 0.125752 0.058696 -v 0.009250 0.133066 0.065516 -v 0.009607 0.125923 0.058513 -v 0.009915 0.133446 0.065108 -v 0.010165 0.126376 0.058027 -v 0.010349 0.126645 0.057738 -v 0.010165 0.133690 0.064847 -v 0.010349 0.133959 0.064558 -v 0.010500 0.127229 0.057113 -v 0.010500 0.134542 0.063933 -v 0.010462 0.134838 0.063615 -v 0.010165 0.135395 0.063019 -v 0.009915 0.128325 0.055938 -v 0.009607 0.128535 0.055712 -v 0.009607 0.135848 0.062532 -v 0.009250 0.128705 0.055529 -v 0.009250 0.136019 0.062349 -v 0.008855 0.128831 0.055395 -v 0.008855 0.136144 0.062215 -v 0.008434 0.128908 0.055312 -v 0.008434 0.136221 0.062132 -v 0.008000 0.128934 0.055284 -v 0.007566 0.128908 0.055312 -v 0.007145 0.128831 0.055395 -v 0.006750 0.136019 0.062349 -v 0.006393 0.135848 0.062532 -v 0.005651 0.127812 0.056488 -v 0.005651 0.135125 0.063308 -v 0.005538 0.127525 0.056795 -v 0.005538 0.134838 0.063615 -v 0.005538 0.134246 0.064250 -v 0.005651 0.126645 0.057738 -v 0.005835 0.126376 0.058027 -v 0.005651 0.133959 0.064558 -v 0.005835 0.133690 0.064847 -v 0.006085 0.126133 0.058288 -v 0.006393 0.125923 0.058513 -v 0.006393 0.133236 0.065333 -v 0.006750 0.125752 0.058696 -v 0.006750 0.133066 0.065516 -v 0.007566 0.125550 0.058913 -v 0.034434 0.125550 0.058913 -v 0.035607 0.125923 0.058513 -v 0.036165 0.126376 0.058027 -v 0.036462 0.127525 0.056795 -v 0.036349 0.127812 0.056488 -v 0.036500 0.127229 0.057113 -v 0.035915 0.128325 0.055938 -v 0.036165 0.128081 0.056199 -v 0.034000 0.126130 0.056088 -v 0.034434 0.128908 0.055312 -v 0.034855 0.128831 0.055395 -v 0.035250 0.128705 0.055529 -v 0.033566 0.128908 0.055312 -v 0.034000 0.128934 0.055284 -v 0.032085 0.128325 0.055938 -v 0.031538 0.127525 0.056795 -v 0.031651 0.126645 0.057738 -v 0.033145 0.125626 0.058831 -v 0.033566 0.125550 0.058913 -v 0.034855 0.125626 0.058831 -v 0.034855 0.132940 0.065651 -v 0.035250 0.125752 0.058696 -v 0.035915 0.126133 0.058288 -v 0.035915 0.133446 0.065108 -v 0.036349 0.126645 0.057738 -v 0.036462 0.126933 0.057430 -v 0.036462 0.134246 0.064250 -v 0.036349 0.135125 0.063308 -v 0.035915 0.135638 0.062758 -v 0.035607 0.128535 0.055712 -v 0.035607 0.135848 0.062532 -v 0.035250 0.136019 0.062349 -v 0.034434 0.136221 0.062132 -v 0.034000 0.136247 0.062104 -v 0.033145 0.136144 0.062215 -v 0.033145 0.128831 0.055395 -v 0.032750 0.136019 0.062349 -v 0.032750 0.128705 0.055529 -v 0.032393 0.135848 0.062532 -v 0.032393 0.128535 0.055712 -v 0.031835 0.128081 0.056199 -v 0.031835 0.135395 0.063019 -v 0.031651 0.127812 0.056488 -v 0.031538 0.134838 0.063615 -v 0.031500 0.127229 0.057113 -v 0.031500 0.134542 0.063933 -v 0.031538 0.134246 0.064250 -v 0.031538 0.126933 0.057430 -v 0.031835 0.126376 0.058027 -v 0.032085 0.126133 0.058288 -v 0.032393 0.125923 0.058513 -v 0.032750 0.125752 0.058696 -v 0.032750 0.133066 0.065516 -v 0.033566 0.132863 0.065733 -v 0.034000 0.125524 0.058941 -v 0.034000 0.132837 0.065761 -v 0.008855 0.091527 0.095399 -v 0.009607 0.091823 0.095081 -v 0.010349 0.092546 0.094306 -v 0.010462 0.093425 0.093363 -v 0.010349 0.093712 0.093055 -v 0.010500 0.093129 0.093681 -v 0.010165 0.093981 0.092766 -v 0.008855 0.094731 0.091962 -v 0.008434 0.094808 0.091880 -v 0.008000 0.092030 0.092656 -v 0.006750 0.094605 0.092097 -v 0.006393 0.094435 0.092280 -v 0.005651 0.093712 0.093055 -v 0.005835 0.093981 0.092766 -v 0.005538 0.092833 0.093998 -v 0.006085 0.092033 0.094856 -v 0.006393 0.091823 0.095081 -v 0.005835 0.092276 0.094595 -v 0.005651 0.092546 0.094306 -v 0.008000 0.091424 0.095509 -v 0.008000 0.098737 0.102329 -v 0.008434 0.091450 0.095481 -v 0.008855 0.098840 0.102219 -v 0.009250 0.091652 0.095264 -v 0.009607 0.099136 0.101901 -v 0.009915 0.092033 0.094856 -v 0.010165 0.092276 0.094595 -v 0.010165 0.099590 0.101415 -v 0.010349 0.099859 0.101126 -v 0.010462 0.092833 0.093998 -v 0.010500 0.100442 0.100501 -v 0.010462 0.100738 0.100183 -v 0.010349 0.101025 0.099875 -v 0.009915 0.094225 0.092505 -v 0.009607 0.094435 0.092280 -v 0.009915 0.101538 0.099325 -v 0.009250 0.094605 0.092097 -v 0.008434 0.102121 0.098700 -v 0.008000 0.094834 0.091852 -v 0.007566 0.094808 0.091880 -v 0.007566 0.102121 0.098700 -v 0.007145 0.094731 0.091962 -v 0.007145 0.102044 0.098782 -v 0.006085 0.094225 0.092505 -v 0.006085 0.101538 0.099325 -v 0.005651 0.101025 0.099875 -v 0.005538 0.093425 0.093363 -v 0.005500 0.093129 0.093681 -v 0.005500 0.100442 0.100501 -v 0.005651 0.099859 0.101126 -v 0.005835 0.099590 0.101415 -v 0.006085 0.099346 0.101676 -v 0.006750 0.098966 0.102084 -v 0.006750 0.091652 0.095264 -v 0.007145 0.091527 0.095399 -v 0.007566 0.091450 0.095481 -v 0.007566 0.098763 0.102301 -v 0.034000 0.091424 0.095509 -v 0.035915 0.092033 0.094856 -v 0.036349 0.093712 0.093055 -v 0.036500 0.093129 0.093681 -v 0.036462 0.092833 0.093998 -v 0.036165 0.093981 0.092766 -v 0.035250 0.094605 0.092097 -v 0.034000 0.092030 0.092656 -v 0.032085 0.094225 0.092505 -v 0.033145 0.094731 0.091962 -v 0.031835 0.093981 0.092766 -v 0.031538 0.092833 0.093998 -v 0.031651 0.092546 0.094306 -v 0.031500 0.093129 0.093681 -v 0.032085 0.092033 0.094856 -v 0.031835 0.092276 0.094595 -v 0.033145 0.091527 0.095399 -v 0.033566 0.091450 0.095481 -v 0.034434 0.091450 0.095481 -v 0.034855 0.091527 0.095399 -v 0.035250 0.098966 0.102084 -v 0.035250 0.091652 0.095264 -v 0.035607 0.091823 0.095081 -v 0.035607 0.099136 0.101901 -v 0.035915 0.099346 0.101676 -v 0.036165 0.099590 0.101415 -v 0.036165 0.092276 0.094595 -v 0.036349 0.092546 0.094306 -v 0.036349 0.099859 0.101126 -v 0.036462 0.100146 0.100818 -v 0.036462 0.093425 0.093363 -v 0.036165 0.101295 0.099586 -v 0.035915 0.094225 0.092505 -v 0.035915 0.101538 0.099325 -v 0.035607 0.094435 0.092280 -v 0.035250 0.101919 0.098917 -v 0.034855 0.094731 0.091962 -v 0.034855 0.102044 0.098782 -v 0.034434 0.094808 0.091880 -v 0.034434 0.102121 0.098700 -v 0.034000 0.094834 0.091852 -v 0.034000 0.102147 0.098672 -v 0.033566 0.094808 0.091880 -v 0.032750 0.094605 0.092097 -v 0.033145 0.102044 0.098782 -v 0.032750 0.101919 0.098917 -v 0.032393 0.094435 0.092280 -v 0.032393 0.101748 0.099100 -v 0.032085 0.101538 0.099325 -v 0.031835 0.101295 0.099586 -v 0.031651 0.093712 0.093055 -v 0.031538 0.093425 0.093363 -v 0.031538 0.100738 0.100183 -v 0.031500 0.100442 0.100501 -v 0.031538 0.100146 0.100818 -v 0.031651 0.099859 0.101126 -v 0.031835 0.099590 0.101415 -v 0.032393 0.091823 0.095081 -v 0.032085 0.099346 0.101676 -v 0.032393 0.099136 0.101901 -v 0.032750 0.091652 0.095264 -v 0.032750 0.098966 0.102084 -v 0.033145 0.098840 0.102219 -v 0.034000 0.098737 0.102329 -v 0.042000 0.016441 -0.088639 -v 0.029007 0.016175 -0.088688 -v 0.028718 0.016441 -0.088639 -v 0.029242 0.015632 -0.088830 -v 0.031482 0.014673 -0.089225 -v 0.032357 0.014835 -0.089146 -v 0.042000 0.015429 -0.088900 -v 0.042000 0.013615 -0.089925 -v -0.000000 0.015429 -0.088900 -v -0.000000 0.014477 -0.089333 -v 0.042000 0.012868 -0.090657 -v -0.000000 0.012260 -0.091508 -v -0.000000 0.013615 -0.089925 -v 0.042000 0.014477 -0.089333 -v 0.042000 -0.012868 -0.090657 -v 0.042000 0.005421 -0.089853 -v 0.042000 0.011399 -0.092000 -v 0.042000 0.011738 -0.091941 -v 0.042000 0.011895 -0.091868 -v 0.042000 0.012162 -0.091645 -v 0.042000 -0.012037 -0.091770 -v 0.042000 -0.011571 -0.091985 -v 0.042000 -0.012260 -0.091508 -v -0.000000 0.016199 -0.088679 -v -0.000000 -0.005421 -0.089853 -v -0.000000 0.012868 -0.090657 -v -0.000000 0.012037 -0.091770 -v -0.000000 0.011399 -0.092000 -v -0.000000 -0.011399 -0.092000 -v -0.000000 -0.012037 -0.091770 -v 0.000000 -0.012161 -0.091646 -v -0.000000 0.011571 -0.091985 -v 0.042000 0.011571 -0.091985 -v -0.000000 0.011738 -0.091941 -v -0.000000 0.011895 -0.091868 -v -0.000000 0.012160 -0.091649 -v 0.042000 0.012037 -0.091770 -v 0.035000 0.057474 -0.073073 -v 0.035000 0.057469 -0.072630 -v 0.032589 0.056610 -0.066965 -v 0.032000 0.056702 -0.066421 -v 0.034242 0.056582 -0.069449 -v 0.042000 0.056584 -0.069485 -v 0.042000 0.056878 -0.070996 -v 0.042000 0.037058 -0.082880 -v 0.042000 0.054851 -0.078114 -v 0.042000 0.024629 -0.088230 -v 0.042000 0.025470 -0.088707 -v 0.042000 0.045361 -0.079488 -v 0.042000 0.048254 -0.077820 -v 0.042000 0.051440 -0.077415 -v 0.042000 0.044274 -0.081079 -v 0.042000 0.043937 -0.081985 -v 0.042000 0.026223 -0.089312 -v 0.042000 0.043425 -0.083816 -v 0.042000 0.026743 -0.089668 -v 0.042000 0.027038 -0.089780 -v 0.042000 0.042733 -0.084453 -v 0.042000 0.043749 -0.082934 -v 0.042000 0.042996 -0.084278 -v 0.042000 0.043229 -0.084064 -v 0.042000 0.055382 -0.078011 -v 0.042000 0.027663 -0.089859 -v 0.042000 0.027348 -0.089844 -v 0.042000 0.026469 -0.089511 -v 0.039731 0.056145 -0.076722 -v 0.040074 0.056328 -0.076220 -v 0.035000 0.055850 -0.077532 -v 0.037203 0.056646 -0.075348 -v 0.037433 0.056806 -0.074906 -v 0.037808 0.056930 -0.074566 -v 0.037991 0.048509 -0.071389 -v 0.038285 0.057003 -0.074366 -v 0.038492 0.048558 -0.071254 -v 0.038808 0.057015 -0.074332 -v 0.039307 0.056967 -0.074466 -v 0.039733 0.056860 -0.074757 -v 0.040023 0.056714 -0.075160 -v 0.040148 0.056545 -0.075624 -v 0.040112 0.047889 -0.073019 -v 0.039825 0.047646 -0.073508 -v 0.039302 0.056038 -0.077015 -v 0.038649 0.055985 -0.077162 -v 0.038017 0.056036 -0.077022 -v 0.037954 0.047421 -0.073853 -v 0.037583 0.056139 -0.076739 -v 0.037351 0.056247 -0.076443 -v 0.037500 0.047626 -0.073548 -v 0.037155 0.056419 -0.075969 -v 0.042000 0.057458 -0.073117 -v 0.042000 0.057483 -0.072668 -v 0.035000 0.054897 -0.078127 -v 0.035000 0.055555 -0.077914 -v 0.042000 0.055812 -0.077634 -v 0.033417 0.056524 -0.067936 -v 0.032000 0.046895 -0.078322 -v 0.033228 0.048239 -0.077826 -v 0.034119 0.049891 -0.077465 -v 0.033739 0.051928 -0.075297 -v 0.034916 0.052266 -0.077483 -v 0.034667 0.051223 -0.077410 -v 0.035000 0.053054 -0.077603 -v 0.032000 0.055108 -0.070172 -v 0.032774 0.055188 -0.070213 -v 0.032804 0.049448 -0.076830 -v 0.032782 0.051670 -0.074918 -v 0.032000 0.049377 -0.076761 -v 0.034621 0.054775 -0.073452 -v 0.034912 0.056974 -0.071352 -v 0.034578 0.056710 -0.070279 -v 0.033878 0.055727 -0.070364 -v 0.032000 0.053528 -0.072642 -v 0.032784 0.053604 -0.072695 -v 0.033729 0.053961 -0.072957 -v 0.034481 0.052511 -0.075781 -v 0.034954 0.055513 -0.074128 -v 0.021000 -0.000150 0.143589 -v 0.006000 0.002060 0.153985 -v 0.002000 0.017547 0.152896 -v 0.002000 0.059030 0.143040 -v 0.002000 0.058696 0.143232 -v 0.002000 0.029108 0.150941 -v 0.040000 0.058863 0.143136 -v 0.040000 0.056583 0.131530 -v 0.036000 0.060496 0.130698 -v 0.040000 0.003763 0.142757 -v 0.040000 0.006124 0.153866 -v 0.039939 0.005420 0.153895 -v 0.039759 0.002425 0.143041 -v 0.039464 0.001807 0.143173 -v 0.039464 0.004095 0.153940 -v 0.037368 0.000086 0.143538 -v 0.038000 0.000375 0.143477 -v 0.037923 0.002554 0.153977 -v 0.036695 -0.000090 0.143576 -v 0.036000 -0.000150 0.143589 -v 0.004632 0.000086 0.143538 -v 0.004308 0.002436 0.153979 -v 0.003429 0.000766 0.143394 -v 0.003493 0.002949 0.153970 -v 0.002936 0.001248 0.143292 -v 0.002536 0.001807 0.143173 -v 0.002241 0.002425 0.143041 -v 0.002536 0.004095 0.153940 -v 0.002061 0.003084 0.142901 -v 0.002000 0.003763 0.142757 -v 0.036000 0.062600 0.140598 -v 0.036695 0.060436 0.130711 -v 0.037368 0.060260 0.130748 -v 0.038509 0.061832 0.141190 -v 0.039064 0.059098 0.130995 -v 0.039064 0.061341 0.141547 -v 0.039464 0.058539 0.131114 -v 0.039759 0.057921 0.131245 -v 0.039939 0.059660 0.142663 -v 0.002061 0.059660 0.142663 -v 0.002536 0.060832 0.141902 -v 0.002936 0.061341 0.141547 -v 0.004079 0.062176 0.140930 -v 0.005398 0.062567 0.140625 -v 0.010870 0.064264 -0.055904 -v 0.029135 0.064260 -0.055905 -v 0.010197 0.062416 -0.056820 -v 0.009529 0.061313 -0.057629 -v 0.031402 0.060211 -0.058715 -v 0.032168 0.059548 -0.059619 -v 0.007008 0.059127 -0.060230 -v 0.033245 0.058796 -0.060919 -v 0.033729 0.058497 -0.061510 -v 0.029000 0.072521 -0.053643 -v 0.024000 0.070308 -0.037658 -v 0.029000 0.073935 -0.051194 -v 0.026128 0.073432 -0.049317 -v 0.010999 0.074008 -0.051472 -v 0.013872 0.073432 -0.049317 -v 0.025142 0.070515 -0.038430 -v 0.020000 0.070031 -0.036623 -v 0.018611 0.070062 -0.036740 -v 0.017264 0.070156 -0.037089 -v 0.027518 0.072810 -0.046993 -v 0.029000 0.071153 -0.040809 -v 0.027878 0.071742 -0.043008 -v 0.027518 0.071393 -0.041707 -v 0.026928 0.071066 -0.040486 -v 0.013872 0.070771 -0.039383 -v 0.016000 0.070308 -0.037658 -v 0.009992 0.069794 -0.035739 -v 0.014858 0.070515 -0.038430 -v 0.007090 0.069655 -0.031153 -v 0.009213 0.069518 -0.034278 -v 0.031816 0.069498 -0.032717 -v 0.008246 0.069460 -0.032785 -v 0.030000 0.065280 -0.054548 -v 0.030000 0.073111 -0.051985 -v 0.010000 0.072969 -0.051452 -v 0.018615 0.073983 -0.051979 -v 0.017264 0.055137 -0.056678 -v 0.018092 0.073996 -0.051886 -v 0.020000 0.073958 -0.052135 -v 0.020695 0.073965 -0.052102 -v 0.021389 0.073982 -0.052002 -v 0.022736 0.055137 -0.056678 -v 0.022736 0.074002 -0.051624 -v 0.023885 0.073917 -0.051119 -v 0.016099 0.073915 -0.051108 -v 0.014858 0.054777 -0.055337 -v 0.014858 0.073688 -0.050269 -v 0.013872 0.054522 -0.054384 -v 0.013072 0.054226 -0.053281 -v 0.013072 0.073137 -0.048214 -v 0.012482 0.072810 -0.046993 -v 0.012122 0.053550 -0.050759 -v 0.012122 0.072461 -0.045692 -v 0.012000 0.072102 -0.044350 -v 0.012122 0.071742 -0.043008 -v 0.012482 0.071393 -0.041707 -v 0.013072 0.071066 -0.040486 -v 0.013872 0.051860 -0.044450 -v 0.016000 0.051398 -0.042725 -v 0.017264 0.051245 -0.042156 -v 0.018611 0.051152 -0.041807 -v 0.020000 0.051120 -0.041690 -v 0.021389 0.070062 -0.036740 -v 0.022736 0.051245 -0.042156 -v 0.022736 0.070156 -0.037089 -v 0.025142 0.051605 -0.043497 -v 0.026128 0.070771 -0.039383 -v 0.026128 0.051860 -0.044450 -v 0.026928 0.052156 -0.045553 -v 0.028000 0.072102 -0.044350 -v 0.028000 0.053191 -0.049417 -v 0.027878 0.053550 -0.050759 -v 0.027878 0.072461 -0.045692 -v 0.026928 0.073137 -0.048214 -v 0.025142 0.073688 -0.050269 -v 0.021908 0.073996 -0.051886 -v 0.022931 0.073988 -0.051538 -v 0.029000 0.074009 -0.051674 -v 0.019305 0.073965 -0.052102 -v 0.017036 0.073996 -0.051535 -v 0.011000 0.072521 -0.053643 -v 0.011000 0.072821 -0.053536 -v 0.028999 0.073810 -0.052578 -v 0.011000 0.073960 -0.052126 -v 0.032880 0.059230 -0.059943 -v 0.032428 0.069351 -0.032611 -v 0.032946 0.059179 -0.060056 -v 0.032954 0.069553 -0.031629 -v 0.033341 0.058874 -0.060729 -v 0.033628 0.058653 -0.061217 -v 0.032447 0.059701 -0.059225 -v 0.031841 0.060361 -0.058218 -v 0.032305 0.069335 -0.032865 -v 0.031712 0.060556 -0.058001 -v 0.031498 0.060879 -0.057642 -v 0.031044 0.061564 -0.056880 -v 0.031196 0.069314 -0.035268 -v 0.030811 0.069376 -0.036238 -v 0.030627 0.069479 -0.036724 -v 0.030164 0.069834 -0.038755 -v 0.030185 0.063743 -0.055251 -v 0.030000 0.070187 -0.041068 -v 0.009823 0.069842 -0.038955 -v 0.009195 0.069379 -0.036250 -v 0.008391 0.069265 -0.034317 -v 0.008186 0.069248 -0.033853 -v 0.007689 0.059840 -0.058998 -v 0.007335 0.059277 -0.060017 -v 0.006000 0.070057 -0.029730 -v 0.006331 0.058594 -0.061280 -v 0.006000 0.058366 -0.061851 -v 0.030008 0.069794 -0.035739 -v 0.030468 0.069602 -0.034866 -v 0.031863 0.069504 -0.032649 -v 0.031425 0.069454 -0.033283 -v 0.031710 0.069262 -0.034090 -v 0.030884 0.069537 -0.034177 -v 0.031547 0.069242 -0.034426 -v 0.034000 0.070057 -0.029730 -v 0.033461 0.069749 -0.030682 -v 0.032674 0.069595 -0.031474 -v 0.033133 0.069622 -0.031296 -v 0.032991 0.069705 -0.031058 -v 0.029076 0.070770 -0.039381 -v 0.030053 0.070064 -0.040317 -v 0.029361 0.070338 -0.037768 -v 0.030000 0.072262 -0.052677 -v 0.029000 0.072821 -0.053536 -v 0.029000 0.073089 -0.053391 -v 0.029000 0.073342 -0.053198 -v 0.029000 0.073559 -0.052969 -v 0.029000 0.073960 -0.052126 -v 0.029000 0.065539 -0.055514 -v 0.032519 0.059244 -0.060032 -v 0.030028 0.064694 -0.054778 -v 0.029009 0.065174 -0.055612 -v 0.029094 0.064536 -0.055815 -v 0.029372 0.063408 -0.056269 -v 0.030530 0.061227 -0.057701 -v 0.030505 0.062715 -0.055913 -v 0.029811 0.062385 -0.056840 -v 0.008815 0.069302 -0.035276 -v 0.008968 0.069315 -0.035623 -v 0.007132 0.069488 -0.031769 -v 0.009563 0.069645 -0.034953 -v 0.007696 0.069359 -0.032885 -v 0.007054 0.069528 -0.031629 -v 0.006869 0.069620 -0.031296 -v 0.009599 0.069632 -0.037644 -v 0.010000 0.070187 -0.041068 -v 0.011000 0.071153 -0.040809 -v 0.010424 0.070102 -0.036886 -v 0.010839 0.070584 -0.038687 -v 0.009975 0.070042 -0.040149 -v 0.009706 0.069692 -0.038040 -v 0.011000 0.073870 -0.052430 -v 0.011000 0.073735 -0.052711 -v 0.011000 0.073560 -0.052968 -v 0.010000 0.072719 -0.052554 -v 0.011000 0.073342 -0.053198 -v 0.011000 0.073089 -0.053391 -v 0.009991 0.064953 -0.054684 -v 0.010000 0.065280 -0.054548 -v 0.011000 0.065539 -0.055514 -v 0.011002 0.065117 -0.055630 -v 0.009921 0.064388 -0.054932 -v 0.009053 0.061742 -0.056712 -v 0.010608 0.063345 -0.056299 -v 0.009589 0.062968 -0.055740 -v 0.009817 0.063817 -0.055224 -v 0.009879 0.064065 -0.055079 -v 0.006789 0.058822 -0.060879 -v 0.008569 0.060182 -0.058749 -v 0.008260 0.060493 -0.058051 -v 0.008655 0.061117 -0.057384 -v 0.028709 0.016452 -0.082000 -v 0.027891 0.016663 -0.088602 -v 0.027887 0.016667 -0.082000 -v 0.027566 0.016594 -0.088614 -v 0.027186 0.016376 -0.088650 -v 0.026909 0.016036 -0.088721 -v 0.026766 0.015646 -0.088829 -v 0.026833 0.015936 -0.082000 -v 0.026750 0.015432 -0.088900 -v 0.026759 0.015309 -0.082000 -v 0.026791 0.015081 -0.089034 -v 0.026970 0.014706 -0.089210 -v 0.027180 0.014477 -0.089334 -v 0.026904 0.014786 -0.082000 -v 0.027477 0.014271 -0.089454 -v 0.028078 0.014157 -0.089528 -v 0.028108 0.014168 -0.082000 -v 0.028696 0.014362 -0.089397 -v 0.029169 0.014917 -0.089104 -v 0.029237 0.015168 -0.082000 -v 0.029163 0.015948 -0.082000 -v 0.031997 0.014638 -0.089246 -v 0.032620 0.015332 -0.088928 -v 0.032489 0.015886 -0.088754 -v 0.031990 0.016197 -0.088685 -v 0.031735 0.016222 -0.080223 -v 0.031533 0.016176 -0.088689 -v 0.031282 0.016022 -0.080223 -v 0.031048 0.015706 -0.088805 -v 0.042000 0.021807 -0.087678 -v -0.000000 0.022773 -0.087709 -v 0.042000 0.022773 -0.087709 -v 0.042000 0.023722 -0.087894 -v -0.000000 0.024629 -0.088230 -v 0.020316 0.037130 -0.086519 -v 0.022000 0.033736 -0.087754 -v 0.004538 0.034956 -0.087310 -v 0.022286 0.033924 -0.087685 -v 0.035855 0.037571 -0.086358 -v 0.000000 0.042446 -0.084584 -v 0.019714 0.036804 -0.086637 -v 0.021000 0.033484 -0.087845 -v 0.020653 0.033513 -0.087835 -v 0.021347 0.037215 -0.086488 -v 0.042000 0.042446 -0.084584 -v 0.021000 0.037243 -0.086477 -v 0.004500 0.035364 -0.087161 -v 0.022286 0.036804 -0.086637 -v 0.034145 0.037571 -0.086358 -v 0.033750 0.037398 -0.086421 -v 0.033085 0.036874 -0.086612 -v 0.019714 0.033924 -0.087685 -v 0.020000 0.033736 -0.087754 -v 0.032835 0.036538 -0.086734 -v 0.032651 0.036167 -0.086869 -v 0.032651 0.034560 -0.087454 -v 0.022879 0.034721 -0.087395 -v 0.037349 0.036167 -0.086869 -v 0.036915 0.036874 -0.086612 -v 0.008607 0.037163 -0.086506 -v 0.019268 0.036304 -0.086819 -v 0.033750 0.033329 -0.087902 -v 0.034145 0.033156 -0.087965 -v 0.042000 0.028282 -0.089739 -v 0.035000 0.033015 -0.088016 -v 0.036250 0.033329 -0.087902 -v 0.036607 0.033564 -0.087816 -v 0.037165 0.034189 -0.087589 -v 0.037349 0.034560 -0.087454 -v 0.032538 0.034956 -0.087310 -v 0.022996 0.035166 -0.087233 -v 0.032538 0.035772 -0.087013 -v 0.008915 0.033854 -0.087711 -v 0.009349 0.036167 -0.086869 -v 0.009165 0.036538 -0.086734 -v 0.008250 0.037398 -0.086421 -v 0.007855 0.037571 -0.086358 -v 0.037462 0.034956 -0.087310 -v 0.037462 0.035772 -0.087013 -v 0.019121 0.036007 -0.086927 -v 0.006145 0.033156 -0.087965 -v 0.019468 0.034156 -0.087601 -v 0.008607 0.033564 -0.087816 -v -0.000000 0.043749 -0.082934 -v 0.042000 0.044753 -0.080240 -v -0.000000 0.044274 -0.081079 -v -0.000000 0.046081 -0.078843 -v 0.042000 0.046081 -0.078843 -v -0.000000 0.045361 -0.079488 -v -0.000000 0.023722 -0.087894 -v -0.000000 0.021807 -0.087678 -v -0.000000 0.044753 -0.080240 -v -0.000000 0.043937 -0.081985 -v 0.000000 0.037058 -0.082880 -v -0.000000 0.025470 -0.088707 -v -0.000000 0.028282 -0.089739 -v -0.000000 0.043688 -0.083244 -v -0.000000 0.026223 -0.089312 -v -0.000000 0.027348 -0.089844 -v -0.000000 0.042733 -0.084452 -v -0.000000 0.042996 -0.084278 -v -0.000000 0.043229 -0.084064 -v -0.000000 0.043425 -0.083816 -v -0.000000 0.043579 -0.083540 -v 0.042000 0.043579 -0.083540 -v 0.042000 0.043688 -0.083244 -v -0.000000 0.026469 -0.089511 -v -0.000000 0.026743 -0.089668 -v -0.000000 0.027038 -0.089780 -v -0.000000 0.027663 -0.089859 -v -0.000000 0.027977 -0.089823 -v 0.042000 0.027977 -0.089823 -v 0.035434 0.034257 -0.076922 -v 0.036250 0.033978 -0.077024 -v 0.037165 0.033118 -0.077337 -v 0.037462 0.031536 -0.077913 -v 0.037462 0.032352 -0.077616 -v 0.037165 0.030769 -0.078192 -v 0.036250 0.029909 -0.078505 -v 0.034145 0.029736 -0.078568 -v 0.035000 0.029594 -0.078619 -v 0.034566 0.029630 -0.078606 -v 0.035434 0.029630 -0.078606 -v 0.033393 0.030144 -0.078419 -v 0.035000 0.031430 -0.076353 -v 0.032538 0.031536 -0.077913 -v 0.033085 0.033454 -0.077215 -v 0.032651 0.032747 -0.077472 -v 0.032835 0.033118 -0.077337 -v 0.033393 0.033743 -0.077109 -v 0.033750 0.033978 -0.077024 -v 0.034566 0.034257 -0.076922 -v 0.035000 0.034293 -0.076909 -v 0.035000 0.037713 -0.086306 -v 0.035855 0.034151 -0.076961 -v 0.035434 0.037677 -0.086319 -v 0.036250 0.037398 -0.086421 -v 0.036607 0.033743 -0.077109 -v 0.036607 0.037163 -0.086506 -v 0.036915 0.033454 -0.077215 -v 0.037165 0.036538 -0.086734 -v 0.037349 0.032747 -0.077472 -v 0.037500 0.031944 -0.077764 -v 0.037500 0.035364 -0.087161 -v 0.037349 0.031140 -0.078057 -v 0.036915 0.030434 -0.078314 -v 0.036915 0.033854 -0.087711 -v 0.036607 0.030144 -0.078419 -v 0.035855 0.029736 -0.078568 -v 0.035855 0.033156 -0.087965 -v 0.035434 0.033050 -0.088003 -v 0.034566 0.033050 -0.088003 -v 0.033750 0.029909 -0.078505 -v 0.033393 0.033564 -0.087816 -v 0.033085 0.030434 -0.078314 -v 0.033085 0.033854 -0.087711 -v 0.032835 0.034189 -0.087589 -v 0.032835 0.030769 -0.078192 -v 0.032651 0.031140 -0.078057 -v 0.032500 0.031944 -0.077764 -v 0.032538 0.032352 -0.077616 -v 0.032500 0.035364 -0.087161 -v 0.033393 0.037163 -0.086506 -v 0.034145 0.034151 -0.076961 -v 0.034566 0.037677 -0.086319 -v 0.007000 0.034293 -0.076909 -v 0.008607 0.033743 -0.077109 -v 0.008250 0.033978 -0.077024 -v 0.009462 0.031536 -0.077913 -v 0.009500 0.031944 -0.077764 -v 0.008607 0.030144 -0.078419 -v 0.007434 0.029630 -0.078606 -v 0.008250 0.029909 -0.078505 -v 0.005393 0.030144 -0.078419 -v 0.005085 0.030434 -0.078314 -v 0.004835 0.030769 -0.078192 -v 0.004538 0.032352 -0.077616 -v 0.004500 0.031944 -0.077764 -v 0.007000 0.031430 -0.076353 -v 0.007000 0.037713 -0.086306 -v 0.007434 0.034257 -0.076922 -v 0.007434 0.037677 -0.086319 -v 0.007855 0.034151 -0.076961 -v 0.008915 0.033454 -0.077215 -v 0.008915 0.036874 -0.086612 -v 0.009165 0.033118 -0.077337 -v 0.009349 0.032747 -0.077472 -v 0.009462 0.032352 -0.077616 -v 0.009462 0.035772 -0.087013 -v 0.009500 0.035364 -0.087161 -v 0.009349 0.031140 -0.078057 -v 0.009462 0.034956 -0.087310 -v 0.009165 0.030769 -0.078192 -v 0.009349 0.034560 -0.087454 -v 0.008915 0.030434 -0.078314 -v 0.009165 0.034189 -0.087589 -v 0.008250 0.033329 -0.087902 -v 0.007855 0.033156 -0.087965 -v 0.007855 0.029736 -0.078568 -v 0.007434 0.033050 -0.088003 -v 0.007000 0.029594 -0.078619 -v 0.006566 0.029630 -0.078606 -v 0.007000 0.033015 -0.088016 -v 0.006145 0.029736 -0.078568 -v 0.006566 0.033050 -0.088003 -v 0.005750 0.029909 -0.078505 -v 0.005750 0.033329 -0.087902 -v 0.005393 0.033564 -0.087816 -v 0.005085 0.033854 -0.087711 -v 0.004835 0.034189 -0.087589 -v 0.004651 0.034560 -0.087454 -v 0.004651 0.031140 -0.078057 -v 0.004538 0.031536 -0.077913 -v 0.004538 0.035772 -0.087013 -v 0.004651 0.036167 -0.086869 -v 0.004651 0.032747 -0.077472 -v 0.004835 0.033118 -0.077337 -v 0.004835 0.036538 -0.086734 -v 0.005085 0.033454 -0.077215 -v 0.005085 0.036874 -0.086612 -v 0.005393 0.033743 -0.077109 -v 0.005750 0.033978 -0.077024 -v 0.005393 0.037163 -0.086506 -v 0.005750 0.037398 -0.086421 -v 0.006145 0.034151 -0.076961 -v 0.006566 0.034257 -0.076922 -v 0.006145 0.037571 -0.086358 -v 0.006566 0.037677 -0.086319 -v 0.022804 0.032769 -0.077463 -v 0.022948 0.031488 -0.077929 -v 0.021548 0.030130 -0.078424 -v 0.019030 0.031617 -0.077883 -v 0.019468 0.033152 -0.077325 -v 0.021000 0.031533 -0.076635 -v 0.021140 0.033824 -0.077079 -v 0.021684 0.037130 -0.086519 -v 0.021818 0.033666 -0.077137 -v 0.022000 0.036991 -0.086569 -v 0.022396 0.033298 -0.077271 -v 0.022663 0.036419 -0.086777 -v 0.022947 0.035820 -0.086995 -v 0.022996 0.032140 -0.077692 -v 0.022663 0.030888 -0.078148 -v 0.022627 0.034260 -0.087563 -v 0.022177 0.030415 -0.078320 -v 0.021684 0.033598 -0.087804 -v 0.021347 0.033513 -0.087835 -v 0.021000 0.030064 -0.078448 -v 0.020512 0.030115 -0.078429 -v 0.020316 0.033598 -0.087804 -v 0.020000 0.030316 -0.078357 -v 0.019605 0.030588 -0.078257 -v 0.019268 0.034424 -0.087503 -v 0.019052 0.034909 -0.087327 -v 0.019196 0.031117 -0.078064 -v 0.019004 0.035560 -0.087090 -v 0.018998 0.032083 -0.077713 -v 0.019170 0.032716 -0.077482 -v 0.019468 0.036572 -0.086722 -v 0.019821 0.033470 -0.077208 -v 0.020000 0.036991 -0.086569 -v 0.020446 0.033756 -0.077105 -v 0.020653 0.037215 -0.086488 -v 0.027282 -0.016441 -0.088639 -v 0.027624 -0.016612 -0.088610 -v 0.033215 -0.048287 -0.077811 -v 0.042000 -0.051440 -0.077415 -v 0.035001 -0.052999 -0.077586 -v 0.042000 -0.049830 -0.077489 -v 0.002000 -0.029108 0.150941 -v 0.002000 -0.050161 0.146466 -v 0.003548 -0.061879 0.141156 -v 0.000000 -0.062496 0.140681 -v 0.002000 -0.058696 0.143232 -v 0.027500 -0.065864 0.137581 -v 0.014425 -0.065864 0.137581 -v 0.006000 -0.062600 0.140598 -v 0.040000 -0.054552 0.145175 -v 0.006019 -0.089480 -0.015556 -v 0.038000 -0.082218 -0.015556 -v 0.008040 -0.088961 -0.015556 -v 0.004000 -0.082218 -0.015556 -v 0.021000 -0.089000 -0.015556 -v 0.010571 -0.089936 -0.015556 -v 0.024124 -0.090440 -0.015556 -v 0.011899 -0.092035 -0.015557 -v 0.030439 -0.091062 -0.015556 -v 0.041844 -0.092976 -0.002913 -v 0.035915 -0.094607 -0.001442 -v 0.040580 -0.094929 -0.000961 -v 0.040185 -0.095315 0.000016 -v 0.040082 -0.095420 0.000434 -v 0.040021 -0.095488 0.000851 -v 0.007000 -0.095420 0.000434 -v 0.010349 -0.093855 -0.002285 -v 0.019085 -0.094607 -0.001442 -v 0.010139 -0.094293 -0.001841 -v 0.018651 -0.093855 -0.002285 -v 0.018523 -0.093375 -0.002667 -v 0.010475 -0.093383 -0.002661 -v 0.010492 -0.092720 -0.003055 -v 0.010266 -0.091945 -0.003350 -v 0.018498 -0.092795 -0.003020 -v 0.009510 -0.090998 -0.003537 -v 0.019393 -0.091085 -0.003525 -v 0.008838 -0.090635 -0.003556 -v 0.008341 -0.090523 -0.003556 -v 0.022234 -0.095167 -0.000422 -v 0.022612 -0.094911 -0.000951 -v 0.022915 -0.094607 -0.001442 -v 0.031651 -0.093855 -0.002285 -v 0.031523 -0.093375 -0.002668 -v 0.022510 -0.090998 -0.003537 -v 0.022989 -0.091471 -0.003470 -v 0.032769 -0.090819 -0.003549 -v 0.021341 -0.090523 -0.003556 -v 0.032393 -0.091085 -0.003525 -v 0.021838 -0.090635 -0.003556 -v 0.042000 -0.091374 -0.003483 -v 0.036346 -0.092121 -0.003293 -v 0.042000 -0.092200 -0.003267 -v 0.042000 -0.090523 -0.003556 -v 0.034450 -0.090533 -0.003556 -v 0.035510 -0.090998 -0.003533 -v 0.035988 -0.091469 -0.003470 -v 0.011849 -0.150558 0.043193 -v 0.030372 -0.150557 0.043769 -v 0.042000 -0.105086 0.032033 -v 0.042000 -0.081800 0.002312 -v 0.042000 -0.081724 0.001444 -v 0.042000 -0.086724 -0.003556 -v 0.042000 -0.080075 -0.011721 -v 0.042000 -0.084224 -0.002886 -v 0.042000 -0.085856 -0.003480 -v 0.037000 -0.139601 0.037217 -v 0.037000 -0.133420 0.037467 -v 0.037000 -0.130745 0.037131 -v 0.005000 -0.130745 0.037131 -v 0.037000 -0.127281 0.036697 -v 0.005000 -0.127281 0.036697 -v 0.005000 -0.121353 0.034928 -v 0.037000 -0.115795 0.032209 -v 0.005000 -0.113359 0.030469 -v 0.037000 -0.108574 0.026426 -v 0.005000 -0.108574 0.026426 -v 0.037000 -0.106387 0.024239 -v 0.005000 -0.106387 0.024239 -v 0.005000 -0.104531 0.021641 -v 0.005000 -0.102791 0.019205 -v 0.005000 -0.100072 0.013647 -v 0.037000 -0.099102 0.010397 -v 0.005000 -0.097869 0.004255 -v 0.037000 -0.097533 0.001580 -v 0.005000 -0.097678 -0.002007 -v 0.037000 -0.098416 -0.008238 -v 0.042000 -0.065864 0.137581 -v 0.034000 -0.136247 0.062104 -v 0.032750 -0.133066 0.065516 -v 0.034434 -0.136221 0.062132 -v 0.031835 -0.135395 0.063019 -v 0.042000 -0.117492 0.082217 -v 0.035250 -0.133066 0.065516 -v 0.035915 -0.135638 0.062758 -v 0.036165 -0.135395 0.063019 -v 0.035250 -0.136019 0.062349 -v 0.034855 -0.136144 0.062215 -v 0.031651 -0.133959 0.064558 -v 0.036165 -0.133690 0.064847 -v 0.031651 -0.135125 0.063308 -v 0.027500 -0.148944 0.048488 -v 0.031500 -0.134542 0.063933 -v 0.036462 -0.134838 0.063615 -v 0.008000 -0.136247 0.062104 -v 0.007145 -0.136144 0.062215 -v 0.000000 -0.146556 0.051049 -v 0.005835 -0.135395 0.063019 -v 0.005651 -0.135125 0.063308 -v 0.006085 -0.133446 0.065108 -v 0.007566 -0.132863 0.065733 -v 0.007145 -0.132940 0.065651 -v 0.008434 -0.132863 0.065733 -v 0.009250 -0.133066 0.065516 -v 0.009607 -0.133236 0.065333 -v 0.009915 -0.133446 0.065108 -v 0.010165 -0.133690 0.064847 -v 0.010165 -0.135395 0.063019 -v 0.009915 -0.135638 0.062758 -v 0.009607 -0.135848 0.062532 -v 0.014425 -0.148944 0.048488 -v 0.008855 -0.136144 0.062215 -v 0.005500 -0.134542 0.063933 -v 0.005651 -0.133959 0.064558 -v 0.010462 -0.134246 0.064250 -v 0.021434 -0.070067 0.133074 -v 0.022575 -0.074134 0.128712 -v 0.019750 -0.066912 0.136458 -v 0.020145 -0.066786 0.136592 -v 0.020566 -0.066709 0.136675 -v 0.021000 -0.066683 0.136703 -v 0.018425 -0.074134 0.128712 -v 0.019085 -0.069484 0.133699 -v 0.018425 -0.066274 0.137142 -v 0.019085 -0.067292 0.136049 -v 0.018651 -0.067805 0.135499 -v 0.022250 -0.066912 0.136458 -v 0.022608 -0.067082 0.136274 -v 0.027500 -0.066274 0.137142 -v 0.022915 -0.067292 0.136049 -v 0.023349 -0.067805 0.135499 -v 0.023462 -0.068092 0.135192 -v 0.023500 -0.068388 0.134874 -v 0.023349 -0.068971 0.134249 -v 0.020566 -0.132863 0.065733 -v 0.021855 -0.136144 0.062215 -v 0.020566 -0.136221 0.062132 -v 0.019393 -0.135848 0.062532 -v 0.019085 -0.135638 0.062758 -v 0.018425 -0.148944 0.048488 -v 0.018835 -0.135395 0.063019 -v 0.019085 -0.133446 0.065108 -v 0.018835 -0.133690 0.064847 -v 0.022575 -0.148944 0.048488 -v 0.022607 -0.135848 0.062532 -v 0.022250 -0.136019 0.062349 -v 0.023349 -0.135125 0.063308 -v 0.023165 -0.135395 0.063019 -v 0.022915 -0.135638 0.062758 -v 0.021855 -0.132940 0.065651 -v 0.022250 -0.133066 0.065516 -v 0.027500 -0.117492 0.082217 -v 0.023349 -0.133959 0.064558 -v 0.023462 -0.134838 0.063615 -v 0.022250 -0.101919 0.098917 -v 0.022575 -0.094454 0.106923 -v 0.021000 -0.098737 0.102329 -v 0.019750 -0.098966 0.102084 -v 0.020145 -0.098840 0.102219 -v 0.020566 -0.098763 0.102301 -v 0.019750 -0.101919 0.098917 -v 0.019393 -0.101748 0.099100 -v 0.018835 -0.101295 0.099586 -v 0.021434 -0.102121 0.098700 -v 0.021000 -0.102147 0.098672 -v 0.020566 -0.102121 0.098700 -v 0.019393 -0.099136 0.101901 -v 0.018425 -0.094454 0.106923 -v 0.022915 -0.099346 0.101676 -v 0.022575 -0.117492 0.082217 -v 0.023349 -0.099859 0.101126 -v 0.023500 -0.100442 0.100501 -v 0.027500 -0.094454 0.106923 -v 0.034434 -0.098763 0.102301 -v 0.035915 -0.101538 0.099325 -v 0.033145 -0.098840 0.102219 -v 0.033566 -0.102121 0.098700 -v 0.033145 -0.102044 0.098782 -v 0.034855 -0.102044 0.098782 -v 0.034000 -0.102147 0.098672 -v 0.032750 -0.101919 0.098917 -v 0.032085 -0.101538 0.099325 -v 0.031651 -0.101025 0.099875 -v 0.032085 -0.099346 0.101676 -v 0.036462 -0.100146 0.100818 -v 0.036500 -0.100442 0.100501 -v 0.036462 -0.100738 0.100183 -v 0.036165 -0.101295 0.099586 -v 0.034434 -0.070067 0.133074 -v 0.042000 -0.074134 0.128712 -v 0.034000 -0.098737 0.102329 -v 0.033566 -0.098763 0.102301 -v 0.034855 -0.066786 0.136592 -v 0.042000 -0.066274 0.137142 -v 0.035915 -0.067292 0.136049 -v 0.036165 -0.069241 0.133960 -v 0.032750 -0.066912 0.136458 -v 0.034434 -0.066709 0.136675 -v 0.036349 -0.068971 0.134249 -v 0.033145 -0.069990 0.133156 -v 0.032393 -0.069694 0.133474 -v 0.031538 -0.068092 0.135192 -v 0.031651 -0.067805 0.135499 -v 0.032085 -0.067292 0.136049 -v 0.032393 -0.067082 0.136275 -v 0.027500 -0.074134 0.128712 -v 0.031500 -0.068388 0.134874 -v 0.022250 -0.098966 0.102084 -v 0.014425 -0.117492 0.082217 -v 0.010462 -0.134838 0.063615 -v 0.006750 -0.098966 0.102084 -v 0.014425 -0.094454 0.106923 -v 0.008434 -0.098763 0.102301 -v 0.009250 -0.101919 0.098917 -v 0.006750 -0.101919 0.098917 -v 0.006085 -0.101538 0.099325 -v 0.005835 -0.101295 0.099586 -v 0.006393 -0.099136 0.101901 -v 0.010165 -0.101295 0.099586 -v 0.009915 -0.101538 0.099325 -v 0.008000 -0.102147 0.098672 -v 0.000000 -0.117492 0.082217 -v 0.000000 -0.112945 0.087093 -v 0.000000 -0.110789 0.089405 -v 0.010165 -0.099590 0.101415 -v 0.010349 -0.099859 0.101126 -v 0.010462 -0.100146 0.100818 -v 0.018425 -0.117492 0.082217 -v 0.010462 -0.100738 0.100183 -v 0.005538 -0.100738 0.100183 -v 0.014425 -0.084172 0.117948 -v 0.007145 -0.098840 0.102219 -v 0.008000 -0.070093 0.133046 -v 0.000000 -0.074134 0.128712 -v 0.007566 -0.070067 0.133074 -v 0.007145 -0.069990 0.133156 -v 0.010165 -0.069241 0.133960 -v 0.006393 -0.069694 0.133474 -v 0.014425 -0.074134 0.128712 -v 0.009607 -0.067082 0.136275 -v 0.009915 -0.067292 0.136049 -v 0.000000 -0.066274 0.137142 -v 0.010349 -0.067805 0.135499 -v 0.014425 -0.066274 0.137142 -v 0.010462 -0.068092 0.135192 -v 0.005538 -0.068092 0.135192 -v 0.006085 -0.069484 0.133699 -v 0.005538 -0.068684 0.134557 -v 0.005500 -0.068388 0.134874 -v 0.022575 -0.065864 0.137581 -v 0.018425 -0.065864 0.137581 -v 0.042000 -0.029108 0.150941 -v 0.032000 -0.055108 -0.070172 -v 0.032000 -0.053528 -0.072642 -v 0.000000 -0.051604 -0.074854 -v 0.032000 -0.049377 -0.076761 -v 0.000000 -0.049377 -0.076761 -v 0.032000 -0.056702 -0.066421 -v 0.006000 -0.058366 -0.061851 -v 0.000000 -0.069470 -0.031343 -v 0.000000 -0.056310 -0.067498 -v 0.003580 -0.071819 -0.024889 -v 0.002882 -0.071159 -0.026703 -v 0.001715 -0.070380 -0.028841 -v 0.041840 -0.076086 -0.013164 -v 0.034000 -0.070057 -0.029730 -v 0.034000 -0.058366 -0.061851 -v 0.040000 -0.095521 0.001281 -v 0.007000 -0.095521 0.001281 -v 0.040000 -0.095757 0.004499 -v 0.007000 -0.096198 0.007107 -v 0.040000 -0.097060 0.010990 -v 0.040000 -0.097737 0.012757 -v 0.007000 -0.098458 0.014997 -v 0.040000 -0.099428 0.017173 -v 0.007000 -0.099987 0.018172 -v 0.007000 -0.100497 0.019229 -v 0.007000 -0.103023 0.023189 -v 0.040000 -0.103023 0.023189 -v 0.007000 -0.103021 0.029064 -v 0.040609 -0.103915 0.025345 -v 0.040274 -0.103732 0.024583 -v 0.007000 -0.103430 0.028396 -v 0.042000 -0.103411 0.028432 -v 0.041426 -0.103914 0.026909 -v 0.041293 -0.103964 0.026473 -v 0.007000 -0.102511 0.029660 -v 0.040162 -0.099477 0.032596 -v 0.040016 -0.099960 0.032205 -v 0.007000 -0.098758 0.033022 -v 0.007000 -0.099477 0.032596 -v 0.041599 -0.097798 0.033364 -v 0.007000 -0.092231 0.030990 -v 0.042000 -0.092231 0.030990 -v 0.042000 -0.092703 0.031679 -v 0.007000 -0.093954 0.032777 -v 0.042000 -0.093954 0.032777 -v 0.042000 -0.095497 0.033403 -v 0.042000 -0.096325 0.033515 -v 0.007000 -0.096325 0.033515 -v 0.042000 -0.081800 0.000575 -v 0.042000 -0.082025 -0.000266 -v 0.042000 -0.082394 -0.001056 -v 0.042000 -0.082894 -0.001770 -v 0.007000 -0.082394 -0.001056 -v 0.042000 -0.083510 -0.002387 -v 0.007000 -0.084224 -0.002886 -v 0.042000 -0.085014 -0.003255 -v 0.007000 -0.085014 -0.003255 -v 0.007000 -0.086724 -0.003556 -v 0.002000 -0.096129 0.021663 -v 0.002000 -0.093832 0.016895 -v 0.002000 -0.091009 0.006714 -v 0.002000 -0.096590 0.090072 -v 0.042000 -0.096039 0.089466 -v 0.002000 -0.095593 0.088778 -v 0.002000 -0.095267 0.088026 -v 0.042000 -0.095067 0.087231 -v 0.002000 -0.095067 0.087231 -v 0.002000 -0.095000 0.056899 -v 0.042000 -0.095000 0.078062 -v 0.042000 -0.095000 0.056899 -v 0.002000 -0.095076 0.056031 -v 0.042000 -0.095302 0.055189 -v 0.002000 -0.095302 0.055189 -v 0.042000 -0.096170 0.053686 -v 0.002000 -0.096170 0.053686 -v 0.002000 -0.096786 0.053069 -v 0.042000 -0.097500 0.052569 -v 0.042000 -0.098290 0.052201 -v 0.042000 -0.099132 0.051975 -v 0.002000 -0.099132 0.051975 -v 0.002000 -0.100000 0.051899 -v 0.042000 -0.100000 0.051899 -v 0.042000 -0.112337 0.051899 -v 0.042000 -0.113085 0.051956 -v 0.042000 -0.113816 0.052123 -v 0.002000 -0.113816 0.052123 -v 0.002000 -0.114513 0.052398 -v 0.042000 -0.115162 0.052774 -v 0.002000 -0.115747 0.053243 -v 0.042000 -0.125281 0.062134 -v 0.042000 -0.125865 0.062781 -v 0.002000 -0.125865 0.062781 -v 0.002000 -0.126326 0.063520 -v 0.002000 -0.126653 0.064329 -v 0.002000 -0.126834 0.065181 -v 0.002000 -0.126864 0.066052 -v 0.042000 -0.126474 0.067744 -v 0.002000 -0.126743 0.066915 -v 0.002000 -0.126474 0.067744 -v 0.042000 -0.125528 0.069200 -v 0.042000 -0.105068 0.091141 -v 0.002000 -0.104420 0.091724 -v 0.002000 -0.103681 0.092186 -v 0.042000 -0.102873 0.092513 -v 0.042000 -0.102021 0.092694 -v 0.002000 -0.102873 0.092513 -v 0.002000 -0.102021 0.092694 -v 0.002000 -0.101150 0.092724 -v 0.042000 -0.100287 0.092603 -v 0.042000 -0.098688 0.091924 -v 0.002000 -0.098688 0.091924 -v 0.042000 -0.096590 0.090072 -v 0.002000 -0.098001 0.091388 -v 0.002000 -0.095670 0.054399 -v 0.002000 -0.125281 0.062134 -v 0.002000 -0.115162 0.052774 -v 0.002000 -0.113085 0.051956 -v 0.002000 -0.098290 0.052201 -v 0.002000 -0.097500 0.052569 -v 0.002000 -0.112337 0.051899 -v 0.002000 -0.095000 0.086415 -v 0.002000 -0.096039 0.089466 -v 0.002000 -0.126065 0.068514 -v 0.002000 -0.125528 0.069200 -v 0.002000 -0.105068 0.091141 -v 0.002000 -0.099458 0.092334 -v 0.002000 -0.100287 0.092603 -v 0.042000 -0.138480 0.045768 -v 0.007000 -0.138255 0.046610 -v 0.042000 -0.137886 0.047399 -v 0.007000 -0.137886 0.047399 -v 0.042000 -0.137387 0.048113 -v 0.042000 -0.136770 0.048730 -v 0.042000 -0.135266 0.049598 -v 0.007000 -0.134425 0.049824 -v 0.042000 -0.134425 0.049824 -v 0.042000 -0.133556 0.049899 -v 0.007000 -0.133556 0.049899 -v 0.042000 -0.099162 0.049829 -v 0.042000 -0.098349 0.049619 -v 0.007000 -0.098349 0.049619 -v 0.042000 -0.097581 0.049276 -v 0.007000 -0.097581 0.049276 -v 0.042000 -0.095381 0.046813 -v 0.007000 -0.095766 0.047560 -v 0.007000 -0.095125 0.046012 -v 0.042000 -0.095031 0.044340 -v 0.007000 -0.095008 0.045180 -v 0.007000 -0.095031 0.044340 -v 0.007000 -0.095495 0.042730 -v 0.042000 -0.096464 0.041364 -v 0.007000 -0.095922 0.042006 -v 0.040862 -0.105324 0.032504 -v 0.007000 -0.105340 0.032489 -v 0.040000 -0.102495 0.035333 -v 0.007000 -0.096464 0.041364 -v 0.041042 -0.105462 0.032376 -v 0.007000 -0.105936 0.031979 -v 0.042000 -0.106568 0.031589 -v 0.007000 -0.106604 0.031570 -v 0.007000 -0.108091 0.031086 -v 0.041426 -0.108091 0.031086 -v 0.007000 -0.109655 0.031085 -v 0.040609 -0.109655 0.031085 -v 0.040429 -0.110033 0.031160 -v 0.007000 -0.111142 0.031567 -v 0.040156 -0.110783 0.031402 -v 0.040000 -0.116846 0.034992 -v 0.007000 -0.115771 0.034503 -v 0.040000 -0.117827 0.035572 -v 0.007000 -0.116828 0.035013 -v 0.007000 -0.120003 0.036542 -v 0.040000 -0.122243 0.037263 -v 0.007000 -0.122225 0.037303 -v 0.007000 -0.124447 0.038064 -v 0.040000 -0.127908 0.038723 -v 0.007000 -0.127893 0.038802 -v 0.007000 -0.129041 0.039048 -v 0.007000 -0.133719 0.039479 -v 0.040000 -0.130501 0.039243 -v 0.040000 -0.133719 0.039479 -v 0.040082 -0.134566 0.039580 -v 0.033625 -0.138556 0.044474 -v 0.021788 -0.138556 0.044378 -v 0.032490 -0.138537 0.044002 -v 0.031734 -0.138350 0.043055 -v 0.022902 -0.138483 0.043623 -v 0.031508 -0.138055 0.042281 -v 0.023477 -0.137668 0.041625 -v 0.022715 -0.136104 0.040178 -v 0.032388 -0.135951 0.040089 -v 0.018651 -0.137285 0.041145 -v 0.019388 -0.135951 0.040089 -v 0.010163 -0.136882 0.040746 -v 0.010349 -0.137285 0.041145 -v 0.010341 -0.138302 0.042893 -v 0.018734 -0.138350 0.043055 -v 0.020143 -0.138556 0.044357 -v 0.009607 -0.138525 0.043915 -v 0.009231 -0.138549 0.044181 -v 0.007000 -0.134566 0.039580 -v 0.040265 -0.135249 0.039765 -v 0.040739 -0.136210 0.040222 -v 0.035790 -0.136234 0.040243 -v 0.041999 -0.138139 0.042399 -v 0.036344 -0.138291 0.042880 -v 0.042000 -0.138483 0.043626 -v 0.042000 -0.138556 0.044477 -v 0.007000 -0.138556 0.044899 -v 0.021369 -0.138556 0.044475 -v 0.002000 -0.118105 0.041168 -v 0.024893 -0.093602 -0.015479 -v 0.004000 -0.096202 -0.014327 -v 0.008627 -0.095929 -0.014523 -v 0.038000 -0.096202 -0.014327 -v 0.033764 -0.095951 -0.014506 -v 0.011096 -0.094820 -0.015123 -v 0.017695 -0.094630 -0.015203 -v 0.011893 -0.093602 -0.015479 -v 0.004428 -0.094319 -0.015313 -v 0.004000 -0.094483 -0.015241 -v 0.037599 -0.098556 -0.009837 -v 0.004120 -0.098530 -0.010181 -v 0.004985 -0.098467 -0.008487 -v 0.037222 -0.098552 -0.009205 -v 0.004906 -0.098520 -0.008855 -v 0.037356 -0.098562 -0.009467 -v 0.004000 -0.098515 -0.010312 -v 0.004000 -0.098350 -0.011141 -v 0.038000 -0.098350 -0.011141 -v 0.004000 -0.098016 -0.012059 -v 0.004000 -0.097538 -0.012910 -v 0.038000 -0.097538 -0.012910 -v 0.004000 -0.096928 -0.013673 -v 0.038000 -0.095380 -0.014854 -v 0.037745 -0.093973 -0.015394 -v 0.038000 -0.093536 -0.015477 -v 0.038000 -0.092563 -0.015556 -v 0.002388 -0.148944 0.048488 -v 0.005706 -0.150504 0.045248 -v 0.003732 -0.150288 0.046171 -v 0.022324 -0.150427 0.045637 -v 0.031652 -0.150506 0.045212 -v 0.021000 -0.150383 0.045827 -v 0.021667 -0.150395 0.045780 -v 0.010961 -0.150554 0.044721 -v 0.004182 -0.150737 0.043819 -v 0.003402 -0.149958 0.047008 -v 0.038418 -0.150139 0.046595 -v 0.038598 -0.149958 0.047008 -v 0.004644 -0.144467 0.036438 -v 0.037000 -0.143238 0.036584 -v 0.037015 -0.143487 0.036533 -v 0.004778 -0.144205 0.036448 -v 0.037094 -0.143854 0.036480 -v 0.037880 -0.145181 0.036470 -v 0.004000 -0.145312 0.036485 -v 0.038000 -0.146141 0.036650 -v 0.038000 -0.147910 0.037462 -v 0.038000 -0.148673 0.038072 -v 0.004000 -0.148673 0.038072 -v 0.038000 -0.149854 0.039620 -v 0.004000 -0.149327 0.038798 -v 0.004691 -0.150203 0.040380 -v 0.004055 -0.150532 0.041459 -v 0.038000 -0.080484 -0.015722 -v 0.038000 -0.079193 -0.016025 -v 0.004000 -0.078932 -0.016112 -v 0.038000 -0.078806 -0.016181 -v 0.004000 -0.077404 -0.016791 -v 0.038000 -0.076452 -0.017386 -v 0.004000 -0.077226 -0.016909 -v 0.038000 -0.075808 -0.017918 -v 0.038000 -0.075269 -0.018364 -v 0.004000 -0.074791 -0.018860 -v 0.038000 -0.074251 -0.019512 -v 0.004000 -0.074576 -0.019143 -v 0.004000 -0.073779 -0.020191 -v 0.038000 -0.073572 -0.020566 -v 0.004000 -0.073581 -0.020569 -v 0.038000 -0.073420 -0.020803 -v 0.004000 -0.073003 -0.021672 -v 0.004064 -0.102280 0.028569 -v 0.002938 -0.098193 0.031066 -v 0.002175 -0.097238 0.029803 -v 0.002331 -0.095610 0.030210 -v 0.004184 -0.099236 0.031735 -v 0.003113 -0.096013 0.031747 -v 0.004823 -0.097924 0.032931 -v 0.005776 -0.099454 0.032517 -v 0.004200 -0.096391 0.032714 -v 0.005290 -0.092164 0.030128 -v 0.004759 -0.093148 0.031478 -v 0.004500 -0.092510 0.030002 -v 0.003786 -0.092980 0.029831 -v 0.003266 -0.094043 0.030851 -v 0.003170 -0.093559 0.029620 -v 0.002670 -0.094230 0.029376 -v 0.002302 -0.094972 0.029106 -v 0.007000 -0.100115 0.032057 -v 0.007000 -0.097978 0.033321 -v 0.005807 -0.096224 0.033421 -v 0.007000 -0.097160 0.033487 -v 0.007000 -0.095497 0.033403 -v 0.007000 -0.094699 0.033154 -v 0.005315 -0.094400 0.032770 -v 0.007000 -0.093283 0.032280 -v 0.007000 -0.092703 0.031679 -v 0.005802 -0.092705 0.031540 -v 0.002302 -0.100360 0.025121 -v 0.002075 -0.100070 0.026242 -v 0.002665 -0.101621 0.025663 -v 0.003154 -0.101696 0.027915 -v 0.003784 -0.102473 0.024503 -v 0.004178 -0.103214 0.026234 -v 0.002424 -0.100721 0.027287 -v 0.002000 -0.098976 0.026125 -v 0.004499 -0.102790 0.024068 -v 0.005631 -0.102379 0.029548 -v 0.005712 -0.103118 0.028676 -v 0.005713 -0.103704 0.027273 -v 0.005708 -0.103807 0.025378 -v 0.005289 -0.103119 0.023900 -v 0.007000 -0.103731 0.027671 -v 0.007000 -0.103914 0.026909 -v 0.007000 -0.103976 0.026127 -v 0.007000 -0.103915 0.025345 -v 0.007000 -0.103732 0.024583 -v 0.007000 -0.103433 0.023858 -v 0.007000 -0.082025 0.003154 -v 0.006132 -0.082097 0.003128 -v 0.007000 -0.091881 0.030231 -v 0.006132 -0.091952 0.030205 -v 0.005290 -0.082309 0.003051 -v 0.004500 -0.082655 0.002925 -v 0.003786 -0.083125 0.002754 -v 0.003170 -0.083704 0.002543 -v 0.002302 -0.085117 0.002029 -v 0.002076 -0.095763 0.028818 -v 0.002000 -0.096579 0.028521 -v 0.007000 -0.095952 0.005959 -v 0.006132 -0.096863 0.010573 -v 0.007000 -0.097697 0.012775 -v 0.007000 -0.096936 0.010553 -v 0.006132 -0.100430 0.019266 -v 0.006131 -0.103318 0.023794 -v 0.004500 -0.099911 0.019555 -v 0.003786 -0.099475 0.019799 -v 0.003170 -0.101709 0.024453 -v 0.002670 -0.098313 0.020446 -v 0.002076 -0.096887 0.021241 -v 0.005290 -0.098179 0.015112 -v 0.005290 -0.100233 0.019376 -v 0.004500 -0.097838 0.015251 -v 0.003170 -0.098936 0.020099 -v 0.002302 -0.095414 0.016246 -v 0.002076 -0.094635 0.016566 -v 0.002302 -0.097623 0.020831 -v 0.006132 -0.098387 0.015026 -v 0.003786 -0.097376 0.015441 -v 0.003170 -0.096805 0.015675 -v 0.002670 -0.094527 0.011221 -v 0.002670 -0.096145 0.015946 -v 0.002076 -0.092954 0.011657 -v 0.002000 -0.092117 0.011889 -v 0.006132 -0.095877 0.005971 -v 0.005290 -0.095654 0.006005 -v 0.005290 -0.096645 0.010633 -v 0.004500 -0.096290 0.010732 -v 0.003786 -0.095808 0.010865 -v 0.003170 -0.095215 0.011030 -v 0.002670 -0.093481 0.006336 -v 0.002076 -0.091868 0.006583 -v 0.002302 -0.093765 0.011432 -v 0.005343 -0.095137 0.000238 -v 0.004498 -0.094767 0.000427 -v 0.004500 -0.095290 0.006060 -v 0.003784 -0.094279 0.000557 -v 0.003786 -0.094796 0.006136 -v 0.003169 -0.093676 0.000711 -v 0.003170 -0.094186 0.006229 -v 0.002302 -0.092233 0.001388 -v 0.002302 -0.092700 0.006456 -v 0.002000 -0.086724 0.001444 -v 0.002076 -0.085908 0.001741 -v 0.002904 -0.084785 -0.000763 -v 0.002681 -0.084080 0.001229 -v 0.002670 -0.084375 0.002299 -v 0.004153 -0.082590 0.001780 -v 0.004119 -0.084026 -0.001697 -v 0.005710 -0.081873 0.001853 -v 0.005711 -0.082025 0.000171 -v 0.005700 -0.082983 -0.001715 -v 0.006117 -0.086240 -0.003474 -v 0.004816 -0.086285 -0.003071 -v 0.002132 -0.086095 0.000232 -v 0.007000 -0.081800 0.002312 -v 0.007000 -0.081724 0.001444 -v 0.007000 -0.081800 0.000575 -v 0.007000 -0.082025 -0.000266 -v 0.007000 -0.082894 -0.001770 -v 0.007000 -0.083510 -0.002387 -v 0.005317 -0.084724 -0.002894 -v 0.007000 -0.085856 -0.003480 -v 0.003876 -0.083045 -0.000144 -v 0.005500 -0.093000 -0.002633 -v 0.003791 -0.091159 -0.002387 -v 0.004539 -0.091260 -0.002901 -v 0.005290 -0.090523 -0.003255 -v 0.002000 -0.090523 0.001444 -v 0.003276 -0.092703 -0.001210 -v 0.004538 -0.092979 -0.002170 -v 0.004485 -0.094181 -0.000985 -v 0.002074 -0.091305 0.000587 -v 0.002669 -0.092961 0.000727 -v 0.006134 -0.095380 0.000587 -v 0.006151 -0.091306 -0.003480 -v 0.003768 -0.086102 -0.002367 -v 0.002927 -0.091103 -0.001484 -v 0.002844 -0.086180 -0.001365 -v 0.002315 -0.091455 -0.000291 -v 0.003786 -0.106167 0.033316 -v 0.002077 -0.108752 0.034915 -v 0.002000 -0.108875 0.036024 -v 0.002302 -0.107666 0.034815 -v 0.003170 -0.106603 0.033752 -v 0.002670 -0.107107 0.034256 -v 0.003232 -0.107747 0.032827 -v 0.003785 -0.110518 0.032539 -v 0.004494 -0.106269 0.032511 -v 0.003170 -0.110547 0.033290 -v 0.002686 -0.109390 0.033367 -v 0.005710 -0.106346 0.031869 -v 0.004499 -0.110722 0.032078 -v 0.004492 -0.108472 0.031608 -v 0.005716 -0.110017 0.031294 -v 0.005290 -0.105553 0.032702 -v 0.007000 -0.111811 0.031977 -v 0.007000 -0.110417 0.031268 -v 0.007000 -0.108873 0.031024 -v 0.005832 -0.108217 0.031150 -v 0.007000 -0.107329 0.031269 -v 0.006132 -0.105393 0.032542 -v 0.002670 -0.100000 0.047399 -v 0.002302 -0.100000 0.046610 -v 0.002219 -0.098869 0.046266 -v 0.003759 -0.098232 0.048398 -v 0.002000 -0.100000 0.044899 -v 0.004500 -0.100000 0.049230 -v 0.004887 -0.095515 0.045900 -v 0.006106 -0.095407 0.046785 -v 0.006132 -0.096518 0.041418 -v 0.005290 -0.096678 0.041577 -v 0.004500 -0.096938 0.041838 -v 0.003786 -0.097292 0.042191 -v 0.003170 -0.097727 0.042627 -v 0.002670 -0.098232 0.043132 -v 0.002305 -0.098183 0.044286 -v 0.002076 -0.099386 0.044286 -v 0.007000 -0.099162 0.049829 -v 0.006132 -0.100000 0.049824 -v 0.005316 -0.098785 0.049518 -v 0.007000 -0.096883 0.048809 -v 0.007000 -0.096272 0.048231 -v 0.005560 -0.096737 0.048527 -v 0.007000 -0.095381 0.046813 -v 0.007000 -0.095195 0.043515 -v 0.002956 -0.097373 0.046445 -v 0.005410 -0.095219 0.044229 -v 0.003434 -0.096524 0.043845 -v 0.003995 -0.096434 0.046886 -v 0.005317 -0.095900 0.042451 -v 0.006133 -0.111208 0.031682 -v 0.006132 -0.124427 0.038137 -v 0.006132 -0.115734 0.034570 -v 0.006132 -0.129029 0.039123 -v 0.005290 -0.128995 0.039346 -v 0.004500 -0.128940 0.039710 -v 0.003786 -0.128864 0.040204 -v 0.002302 -0.128544 0.042300 -v 0.002300 -0.134305 0.042837 -v 0.002076 -0.128417 0.043132 -v 0.002000 -0.128286 0.043991 -v 0.004500 -0.124268 0.038710 -v 0.003170 -0.123970 0.039785 -v 0.003170 -0.128771 0.040813 -v 0.002670 -0.128664 0.041519 -v 0.002000 -0.123111 0.042883 -v 0.005290 -0.119888 0.036821 -v 0.005290 -0.124367 0.038355 -v 0.003786 -0.124135 0.039192 -v 0.002670 -0.119054 0.038855 -v 0.002670 -0.123779 0.040473 -v 0.002302 -0.123568 0.041235 -v 0.002302 -0.118754 0.039586 -v 0.002076 -0.118434 0.040365 -v 0.002076 -0.123343 0.042046 -v 0.005290 -0.115624 0.034767 -v 0.006132 -0.119974 0.036613 -v 0.004500 -0.115445 0.035089 -v 0.004500 -0.119749 0.037162 -v 0.003786 -0.119559 0.037624 -v 0.003170 -0.114901 0.036064 -v 0.003170 -0.119325 0.038195 -v 0.002302 -0.114169 0.037377 -v 0.002076 -0.113759 0.038113 -v 0.005291 -0.111103 0.031883 -v 0.003786 -0.115201 0.035525 -v 0.002670 -0.114554 0.036687 -v 0.002302 -0.109469 0.034380 -v 0.002000 -0.113337 0.038871 -v 0.007000 -0.100000 0.049899 -v 0.006132 -0.133556 0.049824 -v 0.005290 -0.100000 0.049598 -v 0.004500 -0.133556 0.049230 -v 0.003786 -0.100000 0.048730 -v 0.003170 -0.100000 0.048113 -v 0.002670 -0.133556 0.047399 -v 0.002076 -0.100000 0.045768 -v 0.002302 -0.133556 0.046610 -v 0.005651 -0.137032 0.041145 -v 0.003097 -0.136723 0.043781 -v 0.005834 -0.136675 0.040752 -v 0.004619 -0.136688 0.041365 -v 0.005500 -0.137633 0.042000 -v 0.003899 -0.137059 0.042465 -v 0.006393 -0.135868 0.040085 -v 0.002678 -0.134742 0.042071 -v 0.003170 -0.134090 0.041304 -v 0.004498 -0.134306 0.040207 -v 0.006129 -0.134415 0.039621 -v 0.002062 -0.134485 0.043776 -v 0.003833 -0.134887 0.040724 -v 0.005260 -0.134896 0.039908 -v 0.002000 -0.133556 0.044899 -v 0.002142 -0.134416 0.045975 -v 0.002759 -0.136275 0.045383 -v 0.004107 -0.137326 0.046702 -v 0.003786 -0.133556 0.048730 -v 0.003170 -0.133556 0.048113 -v 0.002864 -0.135209 0.047371 -v 0.002076 -0.133556 0.045768 -v 0.005290 -0.133556 0.049598 -v 0.004106 -0.135285 0.048703 -v 0.005711 -0.134804 0.049606 -v 0.005712 -0.136339 0.048895 -v 0.005712 -0.137538 0.047702 -v 0.005716 -0.138257 0.046169 -v 0.007000 -0.135266 0.049598 -v 0.007000 -0.136056 0.049230 -v 0.007000 -0.136770 0.048730 -v 0.007000 -0.137387 0.048113 -v 0.007000 -0.138480 0.045768 -v 0.006720 -0.138600 0.044163 -v 0.004577 -0.138001 0.044397 -v 0.038467 -0.073878 -0.019230 -v 0.038000 -0.072821 -0.022136 -v 0.042000 -0.077983 -0.012212 -v 0.038000 -0.077770 -0.016600 -v 0.038000 -0.077232 -0.016921 -v 0.040177 -0.075197 -0.015608 -v 0.039125 -0.074488 -0.017555 -v 0.038000 -0.074576 -0.019146 -v 0.038000 -0.080687 -0.015674 -v 0.042000 -0.082218 -0.011556 -v 0.039612 -0.148944 0.048488 -v 0.039049 -0.149507 0.047786 -v 0.038268 -0.150288 0.046171 -v 0.042000 -0.146556 0.042437 -v 0.037817 -0.150738 0.043820 -v 0.038419 -0.098173 -0.009745 -v 0.038000 -0.098016 -0.012059 -v 0.038000 -0.096928 -0.013673 -v 0.041816 -0.094387 -0.010816 -v 0.038000 -0.094483 -0.015241 -v 0.042000 -0.093379 -0.011395 -v 0.042000 -0.092563 -0.011556 -v 0.041772 -0.145836 0.040578 -v 0.038000 -0.147059 0.036984 -v 0.038000 -0.145312 0.036485 -v 0.042000 -0.146415 0.041662 -v 0.038000 -0.149327 0.038798 -v 0.038000 -0.150241 0.040517 -v 0.037948 -0.150528 0.041451 -v 0.040021 -0.134148 0.039512 -v 0.041293 -0.108527 0.031036 -v 0.041060 -0.108873 0.031024 -v 0.040274 -0.110417 0.031268 -v 0.040018 -0.111481 0.031757 -v 0.038707 -0.112876 0.031150 -v 0.040069 -0.111142 0.031567 -v 0.040000 -0.111811 0.031977 -v 0.040000 -0.112127 0.032204 -v 0.038707 -0.115502 0.032701 -v 0.038707 -0.118389 0.034407 -v 0.038707 -0.121143 0.035462 -v 0.040000 -0.124010 0.037940 -v 0.038707 -0.130649 0.037959 -v 0.038707 -0.133394 0.038042 -v 0.040018 -0.103243 0.023519 -v 0.040069 -0.103433 0.023858 -v 0.040156 -0.103598 0.024217 -v 0.040428 -0.103840 0.024966 -v 0.038707 -0.105950 0.024609 -v 0.041060 -0.103976 0.026127 -v 0.038707 -0.107983 0.027017 -v 0.038707 -0.096848 -0.002050 -v 0.038707 -0.096958 0.001606 -v 0.040000 -0.096277 0.007092 -v 0.038707 -0.098302 0.010630 -v 0.038707 -0.099538 0.013857 -v 0.038707 -0.102299 0.019498 -v 0.040000 -0.100008 0.018154 -v 0.040000 -0.102796 0.022873 -v 0.038706 -0.143839 0.037210 -v 0.041293 -0.141240 0.040173 -v 0.041295 -0.136912 0.040774 -v 0.038707 -0.137050 0.038152 -v 0.041310 -0.095277 -0.009613 -v 0.041293 -0.094827 -0.006240 -v 0.041293 -0.094228 -0.001911 -v 0.004000 -0.072821 -0.022136 -v 0.003931 -0.072417 -0.023246 -v 0.000000 -0.068727 -0.029300 -v 0.000000 -0.070403 -0.018045 -v 0.004000 -0.075803 -0.017910 -v 0.004000 -0.076011 -0.017716 -v 0.000000 -0.082218 -0.011556 -v 0.004000 -0.080555 -0.015696 -v 0.004000 -0.078802 -0.016169 -v 0.004000 -0.095380 -0.014854 -v 0.004000 -0.093536 -0.015477 -v 0.000000 -0.092563 -0.011556 -v 0.003293 -0.097726 -0.008394 -v 0.000707 -0.094588 -0.004513 -v 0.003293 -0.096848 -0.002050 -v 0.003293 -0.097041 0.004351 -v 0.003293 -0.097741 0.007838 -v 0.000707 -0.098257 0.017718 -v 0.003293 -0.099538 0.013857 -v 0.003293 -0.100593 0.016611 -v 0.000707 -0.101732 0.023606 -v 0.003293 -0.103850 0.022124 -v 0.003293 -0.105950 0.024609 -v 0.000707 -0.117265 0.036736 -v 0.000707 -0.120003 0.037785 -v 0.000707 -0.123650 0.039182 -v 0.003293 -0.121143 0.035462 -v 0.000707 -0.126333 0.039721 -v 0.003293 -0.127162 0.037259 -v 0.000707 -0.130354 0.040527 -v 0.000707 -0.132895 0.040604 -v 0.003293 -0.130649 0.037959 -v 0.003293 -0.133394 0.038042 -v 0.003293 -0.137050 0.038152 -v 0.004000 -0.146141 0.036650 -v 0.004000 -0.147059 0.036984 -v 0.004000 -0.147910 0.037462 -v 0.000112 -0.145787 0.040678 -v 0.004000 -0.149854 0.039620 -v 0.004000 -0.150241 0.040517 -v 0.000000 -0.146556 0.042437 -v 0.003583 -0.150139 0.046595 -v 0.002951 -0.149507 0.047786 -v 0.041297 -0.144622 0.039710 -v 0.042000 -0.141521 0.041997 -v 0.041540 -0.137433 0.041318 -v 0.041691 -0.103731 0.027671 -v 0.041985 -0.106606 0.031573 -v 0.041293 -0.106155 0.028845 -v 0.041691 -0.107329 0.031269 -v 0.000365 -0.094695 -0.010591 -v 0.000017 -0.093988 -0.010986 -v 0.000705 -0.144617 0.039707 -v 0.000707 -0.139513 0.040412 -v 0.000000 -0.143879 0.041452 -v 0.000705 -0.095293 -0.009619 -v 0.000707 -0.094266 -0.002189 -v 0.000000 -0.092557 0.002198 -v 0.000707 -0.094472 0.004632 -v 0.000000 -0.093476 0.009058 -v 0.000707 -0.095813 0.011332 -v 0.000000 -0.098566 0.021881 -v 0.000000 -0.107495 0.032399 -v 0.000707 -0.104012 0.026308 -v 0.000707 -0.106155 0.028845 -v 0.000707 -0.108692 0.030988 -v 0.000707 -0.111378 0.033258 -v 0.000000 -0.113119 0.036434 -v 0.000707 -0.114070 0.034848 -v 0.000000 -0.119323 0.039503 -v 0.000000 -0.132802 0.042443 -v 0.000000 -0.139721 0.042237 -v 0.000707 -0.137189 0.040734 -v 0.004882 -0.143941 0.036469 -v 0.003804 -0.145044 0.036646 -v 0.004401 -0.144837 0.036444 -v 0.004711 -0.098557 -0.009336 -v 0.004485 -0.098560 -0.009718 -v 0.003792 -0.098343 -0.010019 -v 0.004970 -0.143577 0.036518 -v 0.005000 -0.143238 0.036584 -v 0.003299 -0.143771 0.037213 -v 0.003293 -0.139670 0.037789 -v 0.005000 -0.139601 0.037217 -v 0.005000 -0.137007 0.037322 -v 0.005000 -0.133420 0.037467 -v 0.005000 -0.124602 0.035898 -v 0.003293 -0.124370 0.036698 -v 0.005000 -0.118753 0.033656 -v 0.003293 -0.118389 0.034407 -v 0.005000 -0.115795 0.032209 -v 0.003293 -0.115502 0.032701 -v 0.005000 -0.110761 0.028613 -v 0.003293 -0.112876 0.031150 -v 0.003293 -0.110391 0.029050 -v 0.003293 -0.107983 0.027017 -v 0.003293 -0.102299 0.019498 -v 0.005000 -0.101344 0.016247 -v 0.005000 -0.099102 0.010397 -v 0.005000 -0.098303 0.007719 -v 0.003293 -0.098302 0.010630 -v 0.005000 -0.097533 0.001580 -v 0.003293 -0.096958 0.001606 -v 0.005000 -0.097783 -0.004601 -v 0.003293 -0.097211 -0.004670 -v 0.005000 -0.098416 -0.008238 -v 0.042000 -0.092613 -0.003099 -v 0.041540 -0.093682 -0.002433 -v 0.042000 -0.093003 -0.006521 -v 0.037118 -0.098531 -0.008941 -v 0.038000 -0.098515 -0.010312 -v 0.037296 -0.144357 0.036440 -v 0.037515 -0.144718 0.036440 -v 0.038208 -0.145019 0.036657 -v 0.037030 -0.098482 -0.008577 -v 0.038707 -0.097726 -0.008394 -v 0.037000 -0.097783 -0.004601 -v 0.038707 -0.097211 -0.004670 -v 0.037000 -0.097678 -0.002007 -v 0.037000 -0.097869 0.004255 -v 0.038707 -0.097041 0.004351 -v 0.038707 -0.097741 0.007838 -v 0.037000 -0.098303 0.007719 -v 0.037000 -0.100072 0.013647 -v 0.037000 -0.101344 0.016247 -v 0.038707 -0.100593 0.016611 -v 0.037000 -0.102791 0.019204 -v 0.038707 -0.103850 0.022124 -v 0.037000 -0.104531 0.021641 -v 0.037000 -0.110761 0.028613 -v 0.038707 -0.110391 0.029050 -v 0.037000 -0.113359 0.030469 -v 0.037000 -0.118753 0.033656 -v 0.037000 -0.121353 0.034928 -v 0.037000 -0.124602 0.035898 -v 0.038707 -0.124370 0.036698 -v 0.038707 -0.127162 0.037259 -v 0.037000 -0.137007 0.037322 -v 0.038707 -0.139670 0.037789 -v 0.022245 -0.135446 0.039840 -v 0.022915 -0.136442 0.040393 -v 0.023163 -0.136882 0.040746 -v 0.023349 -0.149056 0.041145 -v 0.023349 -0.137285 0.041145 -v 0.023462 -0.149056 0.042434 -v 0.023502 -0.138020 0.042205 -v 0.023136 -0.138419 0.043307 -v 0.023349 -0.149056 0.042855 -v 0.023341 -0.138302 0.042893 -v 0.022250 -0.149056 0.044165 -v 0.022231 -0.138549 0.044181 -v 0.022607 -0.149056 0.043915 -v 0.022607 -0.138525 0.043915 -v 0.022915 -0.149056 0.043607 -v 0.021855 -0.149056 0.044349 -v 0.021000 -0.149056 0.044500 -v 0.021000 -0.138556 0.044500 -v 0.021434 -0.149056 0.044462 -v 0.020566 -0.149056 0.044462 -v 0.020625 -0.138556 0.044474 -v 0.019393 -0.149056 0.043915 -v 0.019490 -0.138537 0.044002 -v 0.019750 -0.149056 0.044165 -v 0.019011 -0.138470 0.043530 -v 0.018633 -0.138269 0.042805 -v 0.018538 -0.149056 0.042434 -v 0.018525 -0.137661 0.041617 -v 0.018508 -0.138055 0.042281 -v 0.018651 -0.149056 0.041145 -v 0.018835 -0.149056 0.040750 -v 0.018861 -0.136842 0.040707 -v 0.019085 -0.136442 0.040393 -v 0.019752 -0.135447 0.039842 -v 0.019750 -0.149056 0.039835 -v 0.020389 -0.135556 0.039576 -v 0.020145 -0.149056 0.039651 -v 0.020000 -0.135556 0.039709 -v 0.021000 -0.149056 0.039500 -v 0.020566 -0.149056 0.039538 -v 0.021205 -0.135556 0.039508 -v 0.020795 -0.135556 0.039508 -v 0.021611 -0.135556 0.039576 -v 0.022607 -0.149056 0.040085 -v 0.022250 -0.149056 0.039835 -v 0.022000 -0.135556 0.039709 -v 0.021855 -0.149056 0.039651 -v 0.023500 -0.149056 0.042000 -v 0.023462 -0.149056 0.041566 -v 0.023165 -0.149056 0.040750 -v 0.024933 -0.150486 0.041315 -v 0.019393 -0.149056 0.040085 -v 0.020686 -0.149510 0.039052 -v 0.022092 -0.149579 0.039151 -v 0.021434 -0.149056 0.039538 -v 0.023084 -0.149798 0.039517 -v 0.022915 -0.149056 0.040393 -v 0.023828 -0.150031 0.039983 -v 0.019085 -0.149056 0.040393 -v 0.018611 -0.149870 0.039621 -v 0.017212 -0.150420 0.041095 -v 0.018500 -0.149056 0.042000 -v 0.018538 -0.149056 0.041566 -v 0.020333 -0.150395 0.045780 -v 0.019304 -0.150451 0.045526 -v 0.020145 -0.149056 0.044349 -v 0.023465 -0.150518 0.045140 -v 0.023165 -0.149056 0.043250 -v 0.018075 -0.150551 0.044757 -v 0.019085 -0.149056 0.043607 -v 0.018835 -0.149056 0.043250 -v 0.018651 -0.149056 0.042855 -v 0.017091 -0.150559 0.043027 -v 0.024681 -0.150556 0.043624 -v 0.006862 -0.135287 0.039771 -v 0.008194 -0.135556 0.039508 -v 0.009254 -0.135460 0.039846 -v 0.008000 -0.149056 0.044500 -v 0.008000 -0.138556 0.044500 -v 0.007539 -0.138556 0.044466 -v 0.006750 -0.149056 0.044165 -v 0.006393 -0.149056 0.043915 -v 0.006037 -0.138379 0.043567 -v 0.005835 -0.149056 0.043250 -v 0.005538 -0.149056 0.042434 -v 0.005538 -0.137880 0.042434 -v 0.005668 -0.138120 0.042914 -v 0.005538 -0.137350 0.041566 -v 0.005835 -0.149056 0.040750 -v 0.006085 -0.136293 0.040393 -v 0.006393 -0.149056 0.040085 -v 0.009915 -0.136442 0.040393 -v 0.010165 -0.149056 0.040750 -v 0.010462 -0.149056 0.041566 -v 0.010477 -0.137668 0.041625 -v 0.010462 -0.149056 0.042434 -v 0.010500 -0.149056 0.042000 -v 0.010349 -0.149056 0.042855 -v 0.010502 -0.138020 0.042205 -v 0.009915 -0.149056 0.043607 -v 0.010165 -0.149056 0.043250 -v 0.009902 -0.138483 0.043623 -v 0.010136 -0.138419 0.043307 -v 0.008788 -0.138556 0.044378 -v 0.009250 -0.149056 0.044165 -v 0.009607 -0.149056 0.043915 -v 0.008434 -0.149056 0.044462 -v 0.008369 -0.138556 0.044475 -v 0.008855 -0.149056 0.044349 -v 0.007779 -0.135556 0.039510 -v 0.007370 -0.135556 0.039581 -v 0.008000 -0.149056 0.039500 -v 0.008603 -0.135556 0.039574 -v 0.008434 -0.149056 0.039538 -v 0.009715 -0.136104 0.040178 -v 0.009607 -0.149056 0.040085 -v 0.009250 -0.149056 0.039835 -v 0.008996 -0.135556 0.039707 -v 0.010349 -0.149056 0.041145 -v 0.011921 -0.150498 0.041558 -v 0.011262 -0.150182 0.040310 -v 0.006750 -0.149056 0.039835 -v 0.006767 -0.149573 0.039149 -v 0.007145 -0.149056 0.039651 -v 0.007566 -0.149056 0.039538 -v 0.008516 -0.149526 0.039075 -v 0.008855 -0.149056 0.039651 -v 0.009821 -0.149735 0.039409 -v 0.009915 -0.149056 0.040393 -v 0.006085 -0.149056 0.040393 -v 0.005651 -0.149056 0.041145 -v 0.005500 -0.149056 0.042000 -v 0.005538 -0.149056 0.041566 -v 0.008367 -0.150384 0.045824 -v 0.007019 -0.150406 0.045737 -v 0.007566 -0.149056 0.044462 -v 0.007145 -0.149056 0.044349 -v 0.010043 -0.150480 0.045358 -v 0.009324 -0.150427 0.045637 -v 0.006085 -0.149056 0.043607 -v 0.005651 -0.149056 0.042855 -v 0.004004 -0.150561 0.042454 -v 0.032752 -0.135445 0.039842 -v 0.035000 -0.135556 0.039709 -v 0.035258 -0.135467 0.039848 -v 0.036504 -0.138008 0.042175 -v 0.036500 -0.149056 0.042000 -v 0.035915 -0.149056 0.040393 -v 0.036166 -0.136891 0.040751 -v 0.036165 -0.149056 0.040750 -v 0.036349 -0.137285 0.041145 -v 0.036349 -0.149056 0.041145 -v 0.036461 -0.137633 0.041554 -v 0.036462 -0.149056 0.042434 -v 0.036349 -0.149056 0.042855 -v 0.035607 -0.149056 0.043915 -v 0.035566 -0.138530 0.043955 -v 0.035915 -0.149056 0.043607 -v 0.036054 -0.138464 0.043446 -v 0.034855 -0.149056 0.044349 -v 0.034788 -0.138556 0.044378 -v 0.035250 -0.149056 0.044165 -v 0.035198 -0.138549 0.044200 -v 0.033566 -0.149056 0.044462 -v 0.034000 -0.149056 0.044500 -v 0.034000 -0.138556 0.044500 -v 0.034369 -0.138556 0.044475 -v 0.032750 -0.149056 0.044165 -v 0.033145 -0.149056 0.044349 -v 0.033143 -0.138556 0.044357 -v 0.032393 -0.149056 0.043915 -v 0.032011 -0.138470 0.043529 -v 0.031835 -0.149056 0.043250 -v 0.031633 -0.138269 0.042805 -v 0.031538 -0.149056 0.042434 -v 0.031500 -0.149056 0.042000 -v 0.031651 -0.137285 0.041145 -v 0.031651 -0.149056 0.041145 -v 0.031538 -0.149056 0.041566 -v 0.031525 -0.137661 0.041617 -v 0.032085 -0.149056 0.040393 -v 0.031861 -0.136842 0.040707 -v 0.032393 -0.149056 0.040085 -v 0.032085 -0.136442 0.040393 -v 0.032750 -0.149056 0.039835 -v 0.033145 -0.149056 0.039651 -v 0.033566 -0.149056 0.039538 -v 0.033000 -0.135556 0.039709 -v 0.034000 -0.149056 0.039500 -v 0.033389 -0.135556 0.039576 -v 0.033795 -0.135556 0.039508 -v 0.034611 -0.135556 0.039576 -v 0.034205 -0.135556 0.039508 -v 0.034855 -0.149056 0.039651 -v 0.036462 -0.149056 0.041566 -v 0.033685 -0.149509 0.039053 -v 0.035053 -0.149572 0.039140 -v 0.034434 -0.149056 0.039538 -v 0.035250 -0.149056 0.039835 -v 0.035607 -0.149056 0.040085 -v 0.036799 -0.150009 0.039889 -v 0.030816 -0.150160 0.040276 -v 0.032273 -0.149701 0.039343 -v 0.031835 -0.149056 0.040750 -v 0.030018 -0.150522 0.041603 -v 0.034434 -0.149056 0.044462 -v 0.033696 -0.150383 0.045829 -v 0.032676 -0.150427 0.045637 -v 0.035756 -0.150443 0.045553 -v 0.036165 -0.149056 0.043250 -v 0.032085 -0.149056 0.043607 -v 0.031651 -0.149056 0.042855 -v 0.037996 -0.150560 0.042459 -v 0.021205 -0.095492 -0.000556 -v 0.020389 -0.095424 -0.000556 -v 0.020000 -0.095291 -0.000556 -v 0.019285 -0.094822 -0.001104 -v 0.019393 -0.094915 -0.014056 -v 0.018837 -0.094254 -0.001882 -v 0.018651 -0.093855 -0.014056 -v 0.018500 -0.093000 -0.014056 -v 0.019085 -0.091393 -0.014056 -v 0.018864 -0.091693 -0.003419 -v 0.018651 -0.092145 -0.014056 -v 0.018659 -0.092107 -0.003302 -v 0.019393 -0.091085 -0.014056 -v 0.019769 -0.090819 -0.003549 -v 0.019098 -0.091377 -0.003483 -v 0.020212 -0.090622 -0.003556 -v 0.020145 -0.090651 -0.014056 -v 0.019750 -0.090835 -0.014056 -v 0.021000 -0.090500 -0.003556 -v 0.020659 -0.090523 -0.003556 -v 0.021855 -0.090651 -0.014056 -v 0.021434 -0.090538 -0.014056 -v 0.022607 -0.091085 -0.014056 -v 0.022915 -0.091393 -0.014056 -v 0.023266 -0.091945 -0.003350 -v 0.023367 -0.092195 -0.003269 -v 0.023349 -0.092145 -0.014056 -v 0.023462 -0.092566 -0.014056 -v 0.023500 -0.093000 -0.014056 -v 0.023492 -0.092720 -0.003055 -v 0.023475 -0.093383 -0.002661 -v 0.023139 -0.094293 -0.001842 -v 0.023349 -0.093855 -0.002285 -v 0.022250 -0.095165 -0.014056 -v 0.021434 -0.095462 -0.014056 -v 0.022000 -0.095291 -0.000556 -v 0.021000 -0.095500 -0.014056 -v 0.021611 -0.095424 -0.000556 -v 0.020566 -0.095462 -0.014056 -v 0.020795 -0.095492 -0.000556 -v 0.019745 -0.095153 -0.000462 -v 0.020145 -0.095349 -0.014056 -v 0.018538 -0.093434 -0.014056 -v 0.017009 -0.093224 -0.015533 -v 0.018835 -0.094250 -0.014056 -v 0.021855 -0.095349 -0.014056 -v 0.022188 -0.095826 -0.014594 -v 0.020762 -0.095952 -0.014507 -v 0.019750 -0.095165 -0.014056 -v 0.019085 -0.094607 -0.014056 -v 0.019321 -0.095680 -0.014687 -v 0.022915 -0.094607 -0.014056 -v 0.024096 -0.094820 -0.015123 -v 0.022607 -0.094915 -0.014056 -v 0.023084 -0.095483 -0.014798 -v 0.023165 -0.094250 -0.014056 -v 0.023349 -0.093855 -0.014056 -v 0.023462 -0.093434 -0.014056 -v 0.018538 -0.092566 -0.014056 -v 0.017439 -0.091062 -0.015556 -v 0.018835 -0.091750 -0.014056 -v 0.018719 -0.089696 -0.015556 -v 0.019632 -0.089241 -0.015556 -v 0.020566 -0.090538 -0.014056 -v 0.020305 -0.089061 -0.015556 -v 0.021000 -0.090500 -0.014056 -v 0.021695 -0.089061 -0.015556 -v 0.022250 -0.090835 -0.014056 -v 0.022722 -0.089373 -0.015556 -v 0.023165 -0.091750 -0.014056 -v 0.024899 -0.092035 -0.015557 -v 0.009249 -0.095158 -0.000449 -v 0.006085 -0.094607 -0.001292 -v 0.006393 -0.094915 -0.014056 -v 0.005538 -0.093434 -0.002350 -v 0.005651 -0.093855 -0.014056 -v 0.005651 -0.093855 -0.002032 -v 0.005835 -0.094250 -0.014056 -v 0.005834 -0.094248 -0.001682 -v 0.005538 -0.093434 -0.014056 -v 0.005500 -0.093000 -0.014056 -v 0.005538 -0.092566 -0.002880 -v 0.005651 -0.092145 -0.014056 -v 0.005723 -0.091940 -0.003183 -v 0.006500 -0.090991 -0.003516 -v 0.006085 -0.091393 -0.014056 -v 0.007166 -0.090637 -0.003565 -v 0.006750 -0.090835 -0.014056 -v 0.007742 -0.090507 -0.003556 -v 0.009989 -0.091471 -0.003470 -v 0.010165 -0.091750 -0.014056 -v 0.010367 -0.092195 -0.003269 -v 0.010462 -0.093434 -0.014056 -v 0.009607 -0.094915 -0.014056 -v 0.009612 -0.094911 -0.000951 -v 0.009915 -0.094607 -0.014056 -v 0.009915 -0.094607 -0.001442 -v 0.009250 -0.095165 -0.014056 -v 0.008996 -0.095293 -0.000556 -v 0.008434 -0.095462 -0.014056 -v 0.008603 -0.095426 -0.000556 -v 0.008000 -0.095500 -0.014056 -v 0.008194 -0.095492 -0.000556 -v 0.007145 -0.095349 -0.014056 -v 0.007370 -0.095419 -0.000556 -v 0.007566 -0.095462 -0.014056 -v 0.007779 -0.095490 -0.000556 -v 0.006393 -0.094915 -0.000868 -v 0.006854 -0.095226 -0.000313 -v 0.009811 -0.095602 -0.014729 -v 0.008855 -0.095349 -0.014056 -v 0.006750 -0.095165 -0.014056 -v 0.006085 -0.094607 -0.014056 -v 0.006259 -0.095694 -0.014669 -v 0.010165 -0.094250 -0.014056 -v 0.010349 -0.093855 -0.014056 -v 0.010500 -0.093000 -0.014056 -v 0.005538 -0.092566 -0.014056 -v 0.004000 -0.092563 -0.015556 -v 0.005835 -0.091750 -0.014056 -v 0.004523 -0.090944 -0.015556 -v 0.006393 -0.091085 -0.014056 -v 0.007145 -0.090651 -0.014056 -v 0.007566 -0.090538 -0.014056 -v 0.008000 -0.090500 -0.014056 -v 0.008434 -0.090538 -0.014056 -v 0.009368 -0.089241 -0.015556 -v 0.008855 -0.090651 -0.014056 -v 0.009250 -0.090835 -0.014056 -v 0.009607 -0.091085 -0.014056 -v 0.009915 -0.091393 -0.014056 -v 0.011264 -0.090714 -0.015556 -v 0.010349 -0.092145 -0.014056 -v 0.010462 -0.092566 -0.014056 -v 0.035236 -0.095166 -0.000431 -v 0.032755 -0.095161 -0.000446 -v 0.032085 -0.094607 -0.001442 -v 0.032393 -0.094915 -0.014056 -v 0.032085 -0.094607 -0.014056 -v 0.031837 -0.094254 -0.001882 -v 0.031651 -0.093855 -0.014056 -v 0.031538 -0.093434 -0.014056 -v 0.031498 -0.092795 -0.003020 -v 0.032085 -0.091393 -0.014056 -v 0.032098 -0.091377 -0.003483 -v 0.031864 -0.091693 -0.003419 -v 0.031651 -0.092145 -0.014056 -v 0.031659 -0.092107 -0.003302 -v 0.033212 -0.090622 -0.003556 -v 0.032750 -0.090835 -0.014056 -v 0.034000 -0.090500 -0.014056 -v 0.034000 -0.090500 -0.003556 -v 0.033566 -0.090538 -0.014056 -v 0.033659 -0.090523 -0.003556 -v 0.034434 -0.090538 -0.014056 -v 0.034855 -0.090651 -0.014056 -v 0.034962 -0.090690 -0.003554 -v 0.035607 -0.091085 -0.014056 -v 0.035915 -0.091393 -0.014056 -v 0.036478 -0.092637 -0.003085 -v 0.036500 -0.093000 -0.014056 -v 0.036494 -0.093237 -0.002752 -v 0.036351 -0.093850 -0.002275 -v 0.035915 -0.094607 -0.014056 -v 0.036139 -0.094293 -0.001841 -v 0.035620 -0.094904 -0.000947 -v 0.035250 -0.095165 -0.014056 -v 0.035000 -0.095291 -0.000556 -v 0.034855 -0.095349 -0.014056 -v 0.034611 -0.095424 -0.000556 -v 0.034205 -0.095492 -0.000556 -v 0.034434 -0.095462 -0.014056 -v 0.034000 -0.095500 -0.014056 -v 0.033145 -0.095349 -0.014056 -v 0.033389 -0.095424 -0.000556 -v 0.033795 -0.095492 -0.000556 -v 0.032285 -0.094822 -0.001104 -v 0.033000 -0.095291 -0.000556 -v 0.031538 -0.092566 -0.014056 -v 0.030009 -0.093224 -0.015533 -v 0.031500 -0.093000 -0.014056 -v 0.031835 -0.094250 -0.014056 -v 0.030695 -0.094630 -0.015203 -v 0.035607 -0.094915 -0.014056 -v 0.036040 -0.095591 -0.014744 -v 0.033566 -0.095462 -0.014056 -v 0.032750 -0.095165 -0.014056 -v 0.032321 -0.095680 -0.014687 -v 0.036165 -0.094250 -0.014056 -v 0.036462 -0.093434 -0.014056 -v 0.036349 -0.093855 -0.014056 -v 0.036462 -0.092566 -0.014056 -v 0.031835 -0.091750 -0.014056 -v 0.032393 -0.091085 -0.014056 -v 0.031429 -0.089936 -0.015556 -v 0.033145 -0.090651 -0.014056 -v 0.032632 -0.089241 -0.015556 -v 0.034407 -0.088946 -0.015556 -v 0.035250 -0.090835 -0.014056 -v 0.036325 -0.089727 -0.015556 -v 0.036165 -0.091750 -0.014056 -v 0.036349 -0.092145 -0.014056 -v 0.037519 -0.091017 -0.015556 -v 0.040000 -0.103772 0.034057 -v 0.040000 -0.100943 0.031228 -v 0.041278 -0.102789 0.029359 -v 0.040880 -0.102511 0.029660 -v 0.041999 -0.103114 0.028938 -v 0.042000 -0.103105 0.030270 -v 0.040878 -0.102768 0.030587 -v 0.041278 -0.105641 0.032211 -v 0.040364 -0.104765 0.033064 -v 0.040003 -0.102386 0.032567 -v 0.041722 -0.105941 0.031987 -v 0.041039 -0.104411 0.032160 -v 0.041378 -0.097978 0.033321 -v 0.040973 -0.098356 0.033195 -v 0.040612 -0.098758 0.033022 -v 0.040357 -0.099113 0.032832 -v 0.040070 -0.099722 0.032410 -v 0.040001 -0.100115 0.032057 -v 0.042000 -0.098368 0.033816 -v 0.040727 -0.099229 0.033660 -v 0.040070 -0.100594 0.033432 -v 0.042000 -0.099528 0.035141 -v 0.042000 -0.100529 0.037294 -v 0.040232 -0.101668 0.036160 -v 0.041134 -0.100591 0.037238 -v 0.040541 -0.100895 0.035817 -v 0.006750 -0.059598 0.129638 -v 0.006393 -0.059769 0.129455 -v 0.007145 -0.059473 0.129772 -v 0.006085 -0.059979 0.129229 -v 0.005835 -0.060222 0.128968 -v 0.005835 -0.061927 0.127140 -v 0.007566 -0.062754 0.126254 -v 0.007145 -0.062677 0.126336 -v 0.008855 -0.062677 0.126336 -v 0.008000 -0.062780 0.126226 -v 0.009250 -0.062551 0.126471 -v 0.010462 -0.061371 0.127737 -v 0.010349 -0.061658 0.127429 -v 0.010165 -0.061927 0.127140 -v 0.010349 -0.060492 0.128679 -v 0.010500 -0.061075 0.128054 -v 0.009915 -0.059979 0.129229 -v 0.008000 -0.059976 0.127030 -v 0.009250 -0.059598 0.129638 -v 0.008855 -0.059473 0.129772 -v 0.009607 -0.059769 0.129455 -v 0.008000 -0.066683 0.136703 -v 0.007566 -0.059396 0.129855 -v 0.007566 -0.066709 0.136675 -v 0.007145 -0.066786 0.136592 -v 0.006750 -0.066912 0.136458 -v 0.006393 -0.067082 0.136275 -v 0.006085 -0.067292 0.136049 -v 0.005835 -0.067536 0.135788 -v 0.005651 -0.060492 0.128679 -v 0.005538 -0.060779 0.128372 -v 0.005651 -0.067805 0.135499 -v 0.005500 -0.061075 0.128054 -v 0.005538 -0.061371 0.127737 -v 0.005651 -0.061658 0.127429 -v 0.005651 -0.068971 0.134249 -v 0.005835 -0.069241 0.133960 -v 0.006085 -0.062171 0.126879 -v 0.006393 -0.062381 0.126654 -v 0.006750 -0.069865 0.133291 -v 0.006750 -0.062551 0.126471 -v 0.008434 -0.070067 0.133074 -v 0.008434 -0.062754 0.126254 -v 0.008855 -0.069990 0.133156 -v 0.009250 -0.069865 0.133291 -v 0.009607 -0.069694 0.133474 -v 0.009607 -0.062381 0.126654 -v 0.009915 -0.062171 0.126879 -v 0.009915 -0.069484 0.133699 -v 0.010349 -0.068971 0.134249 -v 0.010462 -0.068684 0.134557 -v 0.010500 -0.068388 0.134874 -v 0.010462 -0.060779 0.128372 -v 0.010165 -0.060222 0.128968 -v 0.010165 -0.067536 0.135788 -v 0.009250 -0.066912 0.136458 -v 0.008855 -0.066786 0.136592 -v 0.008434 -0.059396 0.129855 -v 0.008434 -0.066709 0.136675 -v 0.008000 -0.059370 0.129883 -v 0.020566 -0.059396 0.129855 -v 0.018538 -0.060779 0.128372 -v 0.018835 -0.060222 0.128968 -v 0.019393 -0.062381 0.126654 -v 0.018651 -0.061658 0.127429 -v 0.019750 -0.062551 0.126471 -v 0.021000 -0.059976 0.127030 -v 0.021434 -0.062754 0.126254 -v 0.021855 -0.062677 0.126336 -v 0.023462 -0.061371 0.127737 -v 0.023165 -0.061927 0.127140 -v 0.023500 -0.061075 0.128054 -v 0.022607 -0.059769 0.129455 -v 0.022250 -0.059598 0.129638 -v 0.022250 -0.062551 0.126471 -v 0.022604 -0.069696 0.133472 -v 0.022607 -0.062381 0.126654 -v 0.022915 -0.062171 0.126879 -v 0.022915 -0.069484 0.133699 -v 0.023165 -0.069241 0.133960 -v 0.023349 -0.061658 0.127429 -v 0.023462 -0.068684 0.134557 -v 0.023462 -0.060779 0.128372 -v 0.023349 -0.060492 0.128679 -v 0.023165 -0.060222 0.128968 -v 0.022915 -0.059979 0.129229 -v 0.023165 -0.067536 0.135788 -v 0.021855 -0.059473 0.129772 -v 0.021855 -0.066786 0.136592 -v 0.021434 -0.059396 0.129855 -v 0.021000 -0.059370 0.129883 -v 0.021434 -0.066709 0.136675 -v 0.020145 -0.059473 0.129772 -v 0.019750 -0.059598 0.129638 -v 0.019393 -0.059769 0.129455 -v 0.019393 -0.067082 0.136275 -v 0.019085 -0.059979 0.129229 -v 0.018835 -0.067536 0.135788 -v 0.018651 -0.060492 0.128679 -v 0.018538 -0.068092 0.135192 -v 0.018500 -0.061075 0.128054 -v 0.018500 -0.068388 0.134874 -v 0.018538 -0.061371 0.127737 -v 0.018538 -0.068684 0.134557 -v 0.018651 -0.068971 0.134249 -v 0.018835 -0.061927 0.127140 -v 0.019085 -0.062171 0.126879 -v 0.018835 -0.069241 0.133960 -v 0.019393 -0.069694 0.133474 -v 0.019750 -0.069865 0.133291 -v 0.020145 -0.062677 0.126336 -v 0.020145 -0.069990 0.133156 -v 0.020566 -0.062754 0.126254 -v 0.020566 -0.070067 0.133074 -v 0.021000 -0.062780 0.126226 -v 0.021000 -0.070093 0.133046 -v 0.022045 -0.069940 0.133210 -v 0.034000 -0.059370 0.129883 -v 0.033566 -0.059396 0.129855 -v 0.032393 -0.059769 0.129455 -v 0.033145 -0.059473 0.129772 -v 0.031835 -0.060222 0.128968 -v 0.032085 -0.059979 0.129229 -v 0.031538 -0.061371 0.127737 -v 0.031651 -0.061658 0.127429 -v 0.031500 -0.061075 0.128054 -v 0.032085 -0.062171 0.126879 -v 0.033145 -0.062677 0.126336 -v 0.032393 -0.062381 0.126654 -v 0.032750 -0.062551 0.126471 -v 0.034000 -0.062780 0.126226 -v 0.034000 -0.059976 0.127030 -v 0.033566 -0.062754 0.126254 -v 0.035915 -0.062171 0.126879 -v 0.036165 -0.060222 0.128968 -v 0.036349 -0.060492 0.128679 -v 0.034000 -0.066683 0.136703 -v 0.033566 -0.066709 0.136675 -v 0.033145 -0.066786 0.136592 -v 0.032750 -0.059598 0.129638 -v 0.031651 -0.060492 0.128679 -v 0.031835 -0.067536 0.135788 -v 0.031538 -0.060779 0.128372 -v 0.031538 -0.068684 0.134557 -v 0.031651 -0.068971 0.134249 -v 0.031835 -0.061927 0.127140 -v 0.031835 -0.069241 0.133960 -v 0.032085 -0.069484 0.133699 -v 0.032750 -0.069865 0.133291 -v 0.033566 -0.070067 0.133074 -v 0.034000 -0.070093 0.133046 -v 0.034434 -0.062754 0.126254 -v 0.034855 -0.062677 0.126336 -v 0.034855 -0.069990 0.133156 -v 0.035250 -0.062551 0.126471 -v 0.035250 -0.069865 0.133291 -v 0.035607 -0.062381 0.126654 -v 0.035607 -0.069694 0.133474 -v 0.035915 -0.069484 0.133699 -v 0.036165 -0.061927 0.127140 -v 0.036349 -0.061658 0.127429 -v 0.036462 -0.068684 0.134557 -v 0.036462 -0.061371 0.127737 -v 0.036500 -0.061075 0.128054 -v 0.036500 -0.068388 0.134874 -v 0.036462 -0.060779 0.128372 -v 0.036462 -0.068092 0.135192 -v 0.036349 -0.067805 0.135499 -v 0.036165 -0.067536 0.135788 -v 0.035915 -0.059979 0.129229 -v 0.035607 -0.059769 0.129455 -v 0.035607 -0.067082 0.136275 -v 0.035250 -0.059598 0.129638 -v 0.035250 -0.066912 0.136458 -v 0.034855 -0.059473 0.129772 -v 0.034434 -0.059396 0.129855 -v 0.020566 -0.125550 0.058913 -v 0.019085 -0.126133 0.058288 -v 0.018538 -0.127525 0.056795 -v 0.018500 -0.127229 0.057113 -v 0.018651 -0.127812 0.056488 -v 0.020145 -0.128831 0.055395 -v 0.022250 -0.128705 0.055529 -v 0.023462 -0.127525 0.056795 -v 0.023165 -0.128081 0.056199 -v 0.023165 -0.126376 0.058027 -v 0.021000 -0.126130 0.056088 -v 0.021855 -0.125626 0.058831 -v 0.022607 -0.128535 0.055712 -v 0.022915 -0.128325 0.055938 -v 0.023349 -0.127812 0.056488 -v 0.023500 -0.127229 0.057113 -v 0.023500 -0.134542 0.063933 -v 0.023462 -0.134246 0.064250 -v 0.023462 -0.126933 0.057430 -v 0.023349 -0.126645 0.057738 -v 0.022915 -0.126133 0.058288 -v 0.023165 -0.133690 0.064847 -v 0.022915 -0.133446 0.065108 -v 0.022607 -0.125923 0.058513 -v 0.022575 -0.133221 0.065350 -v 0.022250 -0.125752 0.058696 -v 0.021434 -0.125550 0.058913 -v 0.021434 -0.132863 0.065733 -v 0.021000 -0.125524 0.058941 -v 0.021000 -0.132837 0.065761 -v 0.020145 -0.125626 0.058831 -v 0.019750 -0.125752 0.058696 -v 0.020145 -0.132940 0.065651 -v 0.019750 -0.133066 0.065516 -v 0.019393 -0.125923 0.058513 -v 0.019393 -0.133236 0.065333 -v 0.018835 -0.126376 0.058027 -v 0.018651 -0.126645 0.057738 -v 0.018651 -0.133959 0.064558 -v 0.018538 -0.126933 0.057430 -v 0.018538 -0.134246 0.064250 -v 0.018500 -0.134542 0.063933 -v 0.018538 -0.134838 0.063615 -v 0.018651 -0.135125 0.063308 -v 0.018835 -0.128081 0.056199 -v 0.019085 -0.128325 0.055938 -v 0.019393 -0.128535 0.055712 -v 0.019750 -0.128705 0.055529 -v 0.019750 -0.136019 0.062349 -v 0.020566 -0.128908 0.055312 -v 0.020145 -0.136144 0.062215 -v 0.021000 -0.136247 0.062104 -v 0.021000 -0.128934 0.055284 -v 0.021434 -0.128908 0.055312 -v 0.021855 -0.128831 0.055395 -v 0.021434 -0.136221 0.062132 -v 0.020566 -0.091450 0.095481 -v 0.021000 -0.091424 0.095509 -v 0.019750 -0.091652 0.095264 -v 0.019393 -0.091823 0.095081 -v 0.021000 -0.092030 0.092656 -v 0.020145 -0.091527 0.095399 -v 0.018651 -0.092546 0.094306 -v 0.018835 -0.092276 0.094595 -v 0.018538 -0.093425 0.093363 -v 0.018835 -0.093981 0.092766 -v 0.019393 -0.094435 0.092280 -v 0.022607 -0.094435 0.092280 -v 0.022250 -0.094605 0.092097 -v 0.023349 -0.093712 0.093055 -v 0.023500 -0.093129 0.093681 -v 0.023462 -0.092833 0.093998 -v 0.023165 -0.092276 0.094595 -v 0.023349 -0.092546 0.094306 -v 0.022607 -0.091823 0.095081 -v 0.022915 -0.094225 0.092505 -v 0.022915 -0.101538 0.099325 -v 0.023165 -0.101295 0.099586 -v 0.023165 -0.093981 0.092766 -v 0.023349 -0.101025 0.099875 -v 0.023462 -0.093425 0.093363 -v 0.023462 -0.100738 0.100183 -v 0.023462 -0.100146 0.100818 -v 0.023165 -0.099590 0.101415 -v 0.022915 -0.092033 0.094856 -v 0.022250 -0.091652 0.095264 -v 0.022603 -0.099134 0.101904 -v 0.021855 -0.091527 0.095399 -v 0.021855 -0.098840 0.102219 -v 0.021434 -0.091450 0.095481 -v 0.021434 -0.098763 0.102301 -v 0.019085 -0.092033 0.094856 -v 0.019085 -0.099346 0.101676 -v 0.018835 -0.099590 0.101415 -v 0.018651 -0.099859 0.101126 -v 0.018538 -0.092833 0.093998 -v 0.018538 -0.100146 0.100818 -v 0.018500 -0.100442 0.100501 -v 0.018500 -0.093129 0.093681 -v 0.018538 -0.100738 0.100183 -v 0.018651 -0.093712 0.093055 -v 0.018651 -0.101025 0.099875 -v 0.019085 -0.101538 0.099325 -v 0.019085 -0.094225 0.092505 -v 0.019750 -0.094605 0.092097 -v 0.020145 -0.094731 0.091962 -v 0.020145 -0.102044 0.098782 -v 0.020566 -0.094808 0.091880 -v 0.021000 -0.094834 0.091852 -v 0.021434 -0.094808 0.091880 -v 0.021855 -0.094731 0.091962 -v 0.021855 -0.102044 0.098782 -v 0.022607 -0.101748 0.099100 -v 0.007566 -0.125550 0.058913 -v 0.007145 -0.125626 0.058831 -v 0.008000 -0.125524 0.058941 -v 0.006393 -0.125923 0.058513 -v 0.005651 -0.126645 0.057738 -v 0.005538 -0.126933 0.057430 -v 0.005651 -0.127812 0.056488 -v 0.005538 -0.127525 0.056795 -v 0.008000 -0.126130 0.056088 -v 0.005500 -0.127229 0.057113 -v 0.005835 -0.128081 0.056199 -v 0.006085 -0.128325 0.055938 -v 0.008434 -0.128908 0.055312 -v 0.007566 -0.128908 0.055312 -v 0.009607 -0.128535 0.055712 -v 0.010165 -0.128081 0.056199 -v 0.009915 -0.128325 0.055938 -v 0.010349 -0.126645 0.057738 -v 0.010500 -0.127229 0.057113 -v 0.009607 -0.125923 0.058513 -v 0.008434 -0.125550 0.058913 -v 0.008000 -0.132837 0.065761 -v 0.006750 -0.125752 0.058696 -v 0.006750 -0.133066 0.065516 -v 0.006393 -0.133236 0.065333 -v 0.006085 -0.126133 0.058288 -v 0.005835 -0.126376 0.058027 -v 0.005835 -0.133690 0.064847 -v 0.005538 -0.134246 0.064250 -v 0.005538 -0.134838 0.063615 -v 0.006085 -0.135638 0.062758 -v 0.006393 -0.128535 0.055712 -v 0.006393 -0.135848 0.062532 -v 0.006750 -0.128705 0.055529 -v 0.006750 -0.136019 0.062349 -v 0.007145 -0.128831 0.055395 -v 0.008000 -0.128934 0.055284 -v 0.007566 -0.136221 0.062132 -v 0.008434 -0.136221 0.062132 -v 0.008855 -0.128831 0.055395 -v 0.009250 -0.128705 0.055529 -v 0.009250 -0.136019 0.062349 -v 0.010349 -0.127812 0.056488 -v 0.010462 -0.127525 0.056795 -v 0.010349 -0.135125 0.063308 -v 0.010500 -0.134542 0.063933 -v 0.010462 -0.126933 0.057430 -v 0.010349 -0.133959 0.064558 -v 0.010165 -0.126376 0.058027 -v 0.009915 -0.126133 0.058288 -v 0.009250 -0.125752 0.058696 -v 0.008855 -0.125626 0.058831 -v 0.008855 -0.132940 0.065651 -v 0.033566 -0.125550 0.058913 -v 0.032085 -0.126133 0.058288 -v 0.032750 -0.125752 0.058696 -v 0.032393 -0.125923 0.058513 -v 0.033145 -0.125626 0.058831 -v 0.031651 -0.126645 0.057738 -v 0.031651 -0.127812 0.056488 -v 0.033566 -0.128908 0.055312 -v 0.033145 -0.128831 0.055395 -v 0.032393 -0.128535 0.055712 -v 0.034434 -0.128908 0.055312 -v 0.034855 -0.128831 0.055395 -v 0.035250 -0.128705 0.055529 -v 0.035607 -0.128535 0.055712 -v 0.036462 -0.127525 0.056795 -v 0.036462 -0.126933 0.057430 -v 0.036500 -0.127229 0.057113 -v 0.034000 -0.126130 0.056088 -v 0.035915 -0.126133 0.058288 -v 0.034855 -0.125626 0.058831 -v 0.034434 -0.125550 0.058913 -v 0.034000 -0.125524 0.058941 -v 0.034000 -0.132837 0.065761 -v 0.033566 -0.132863 0.065733 -v 0.033145 -0.132940 0.065651 -v 0.032393 -0.133236 0.065333 -v 0.032085 -0.133446 0.065108 -v 0.031835 -0.126376 0.058027 -v 0.031835 -0.133690 0.064847 -v 0.031538 -0.126933 0.057430 -v 0.031538 -0.134246 0.064250 -v 0.031500 -0.127229 0.057113 -v 0.031538 -0.127525 0.056795 -v 0.031538 -0.134838 0.063615 -v 0.031835 -0.128081 0.056199 -v 0.032085 -0.128325 0.055938 -v 0.032085 -0.135638 0.062758 -v 0.032393 -0.135848 0.062532 -v 0.032750 -0.128705 0.055529 -v 0.032750 -0.136019 0.062349 -v 0.033145 -0.136144 0.062215 -v 0.033566 -0.136221 0.062132 -v 0.034000 -0.128934 0.055284 -v 0.035607 -0.135848 0.062532 -v 0.035915 -0.128325 0.055938 -v 0.036165 -0.128081 0.056199 -v 0.036349 -0.127812 0.056488 -v 0.036349 -0.135125 0.063308 -v 0.036500 -0.134542 0.063933 -v 0.036462 -0.134246 0.064250 -v 0.036349 -0.126645 0.057738 -v 0.036349 -0.133959 0.064558 -v 0.036165 -0.126376 0.058027 -v 0.035915 -0.133446 0.065108 -v 0.035607 -0.125923 0.058513 -v 0.035607 -0.133236 0.065333 -v 0.035250 -0.125752 0.058696 -v 0.034855 -0.132940 0.065651 -v 0.034434 -0.132863 0.065733 -v 0.007566 -0.091450 0.095481 -v 0.008000 -0.092030 0.092656 -v 0.006085 -0.092033 0.094856 -v 0.006750 -0.091652 0.095264 -v 0.005651 -0.092546 0.094306 -v 0.005538 -0.093425 0.093363 -v 0.006393 -0.094435 0.092280 -v 0.009915 -0.094225 0.092505 -v 0.008855 -0.094731 0.091962 -v 0.010349 -0.093712 0.093055 -v 0.010349 -0.092546 0.094306 -v 0.010500 -0.093129 0.093681 -v 0.009607 -0.091823 0.095081 -v 0.010165 -0.092276 0.094595 -v 0.008434 -0.091450 0.095481 -v 0.008855 -0.091527 0.095399 -v 0.008000 -0.091424 0.095509 -v 0.007566 -0.098763 0.102301 -v 0.007145 -0.091527 0.095399 -v 0.006393 -0.091823 0.095081 -v 0.006085 -0.099346 0.101676 -v 0.005835 -0.092276 0.094595 -v 0.005835 -0.099590 0.101415 -v 0.005538 -0.092833 0.093998 -v 0.005651 -0.099859 0.101126 -v 0.005500 -0.093129 0.093681 -v 0.005538 -0.100146 0.100818 -v 0.005500 -0.100442 0.100501 -v 0.005651 -0.101025 0.099875 -v 0.005651 -0.093712 0.093055 -v 0.005835 -0.093981 0.092766 -v 0.006085 -0.094225 0.092505 -v 0.006750 -0.094605 0.092097 -v 0.006393 -0.101748 0.099100 -v 0.007145 -0.094731 0.091962 -v 0.007566 -0.094808 0.091880 -v 0.007145 -0.102044 0.098782 -v 0.007566 -0.102121 0.098700 -v 0.008000 -0.094834 0.091852 -v 0.008434 -0.094808 0.091880 -v 0.008434 -0.102121 0.098700 -v 0.008855 -0.102044 0.098782 -v 0.009250 -0.094605 0.092097 -v 0.009607 -0.094435 0.092280 -v 0.009607 -0.101748 0.099100 -v 0.010165 -0.093981 0.092766 -v 0.010462 -0.093425 0.093363 -v 0.010349 -0.101025 0.099875 -v 0.010500 -0.100442 0.100501 -v 0.010462 -0.092833 0.093998 -v 0.009915 -0.092033 0.094856 -v 0.009915 -0.099346 0.101676 -v 0.009607 -0.099136 0.101901 -v 0.009250 -0.091652 0.095264 -v 0.009250 -0.098966 0.102084 -v 0.008855 -0.098840 0.102219 -v 0.008000 -0.098737 0.102329 -v 0.034000 -0.091424 0.095509 -v 0.032750 -0.091652 0.095264 -v 0.032085 -0.092033 0.094856 -v 0.031835 -0.092276 0.094595 -v 0.031500 -0.093129 0.093681 -v 0.031835 -0.093981 0.092766 -v 0.032393 -0.094435 0.092280 -v 0.034434 -0.094808 0.091880 -v 0.034855 -0.094731 0.091962 -v 0.033566 -0.094808 0.091880 -v 0.034000 -0.094834 0.091852 -v 0.035915 -0.094225 0.092505 -v 0.036349 -0.093712 0.093055 -v 0.036349 -0.092546 0.094306 -v 0.036500 -0.093129 0.093681 -v 0.034000 -0.092030 0.092656 -v 0.035250 -0.091652 0.095264 -v 0.033566 -0.091450 0.095481 -v 0.033145 -0.091527 0.095399 -v 0.032750 -0.098966 0.102084 -v 0.032393 -0.091823 0.095081 -v 0.032393 -0.099136 0.101901 -v 0.031835 -0.099590 0.101415 -v 0.031651 -0.092546 0.094306 -v 0.031538 -0.092833 0.093998 -v 0.031651 -0.099859 0.101126 -v 0.031538 -0.100146 0.100818 -v 0.031500 -0.100442 0.100501 -v 0.031538 -0.093425 0.093363 -v 0.031538 -0.100738 0.100183 -v 0.031651 -0.093712 0.093055 -v 0.031835 -0.101295 0.099586 -v 0.032085 -0.094225 0.092505 -v 0.032750 -0.094605 0.092097 -v 0.032393 -0.101748 0.099100 -v 0.033145 -0.094731 0.091962 -v 0.034434 -0.102121 0.098700 -v 0.035250 -0.101919 0.098917 -v 0.035250 -0.094605 0.092097 -v 0.035607 -0.094435 0.092280 -v 0.035607 -0.101748 0.099100 -v 0.036165 -0.093981 0.092766 -v 0.036349 -0.101025 0.099875 -v 0.036462 -0.093425 0.093363 -v 0.036462 -0.092833 0.093998 -v 0.036349 -0.099859 0.101126 -v 0.036165 -0.092276 0.094595 -v 0.035915 -0.092033 0.094856 -v 0.036165 -0.099590 0.101415 -v 0.035915 -0.099346 0.101676 -v 0.035607 -0.091823 0.095081 -v 0.035607 -0.099136 0.101901 -v 0.035250 -0.098966 0.102084 -v 0.034855 -0.091527 0.095399 -v 0.034434 -0.091450 0.095481 -v 0.034855 -0.098840 0.102219 -v 0.040110 -0.048171 -0.072318 -v 0.039172 -0.047364 -0.073938 -v 0.038428 -0.047329 -0.073985 -v 0.037961 -0.047419 -0.073856 -v 0.039986 0.048296 -0.071975 -v 0.039448 0.047452 -0.073807 -v 0.038910 0.047334 -0.073978 -v 0.039008 0.048544 -0.071286 -v 0.038428 0.047329 -0.073985 -v 0.039492 0.048473 -0.071488 -v 0.037567 0.048403 -0.071679 -v 0.037218 0.048216 -0.072198 -v 0.028000 -0.053191 -0.049417 -v 0.037178 0.047915 -0.072977 -v 0.027518 -0.052483 -0.046774 -v 0.025142 -0.051605 -0.043497 -v 0.026128 -0.054522 -0.054384 -v 0.021389 -0.051152 -0.041807 -v 0.024000 -0.054984 -0.056109 -v 0.021389 -0.055230 -0.057027 -v 0.014858 -0.054777 -0.055337 -v 0.013872 -0.054522 -0.054384 -v 0.013072 -0.052156 -0.045553 -v 0.012482 -0.052483 -0.046774 -v 0.012122 -0.053550 -0.050759 -v 0.020000 -0.055261 -0.057144 -v 0.022736 -0.055137 -0.056678 -v 0.026928 0.054226 -0.053281 -v 0.024000 0.054984 -0.056109 -v 0.027518 0.052483 -0.046774 -v 0.027878 0.052831 -0.048075 -v 0.026128 0.054522 -0.054384 -v 0.024000 0.051398 -0.042725 -v 0.021389 0.055230 -0.057027 -v 0.020000 0.055261 -0.057144 -v 0.021389 0.051152 -0.041807 -v 0.014858 0.051605 -0.043497 -v 0.016000 0.054984 -0.056109 -v 0.013072 0.052156 -0.045553 -v 0.018611 0.055230 -0.057027 -v 0.012482 0.053899 -0.052060 -v 0.027518 0.053899 -0.052060 -v 0.025142 0.054777 -0.055337 -v 0.012122 0.052831 -0.048075 -v 0.012482 0.052483 -0.046774 -v 0.012000 0.053191 -0.049417 -v 0.039759 -0.004145 0.151135 -v 0.038339 -0.061502 0.138943 -v 0.040000 -0.031893 0.145237 -v 0.036000 -0.062216 0.138792 -v 0.006000 -0.001571 0.151682 -v 0.006000 -0.062216 0.138792 -v 0.004995 -0.001681 0.151658 -v 0.002000 -0.031893 0.145237 -v 0.002936 -0.060818 0.139089 -v 0.002241 -0.004145 0.151135 -v 0.002536 -0.060260 0.139207 -v 0.021000 -0.062216 0.138792 -v 0.002000 0.056583 0.131530 -v 0.039939 0.003084 0.142901 -v 0.040000 0.030173 0.137143 -v 0.038571 0.059580 0.130893 -v 0.039064 0.001248 0.143292 -v 0.038000 0.059971 0.130810 -v 0.038571 0.000766 0.143394 -v 0.039939 0.057262 0.131385 -v 0.021000 0.060496 0.130698 -v 0.006000 0.060496 0.130698 -v 0.002000 0.030173 0.137143 -v 0.006000 -0.000150 0.143589 -v 0.005305 0.060436 0.130711 -v 0.004632 0.060260 0.130748 -v 0.005305 -0.000090 0.143576 -v 0.004000 0.059971 0.130810 -v 0.003429 0.059580 0.130893 -v 0.004000 0.000375 0.143477 -v 0.002536 0.058539 0.131114 -v 0.002936 0.059098 0.130995 -v 0.002241 0.057921 0.131245 -v 0.002061 0.057262 0.131385 -v 0.002000 -0.005483 0.150850 -v 0.014425 0.084172 0.117948 -v 0.027500 0.084172 0.117948 -v 0.022575 0.094454 0.106923 -v 0.027500 -0.084172 0.117948 -v 0.018425 0.074134 0.128712 -v 0.027074 -0.016261 -0.088672 -v 0.027145 -0.014493 -0.089321 -v -0.000000 -0.015429 -0.088900 -v 0.042000 -0.013615 -0.089925 -v -0.000000 -0.014477 -0.089333 -v 0.042000 -0.014477 -0.089333 -v 0.031879 -0.014605 -0.089263 -v 0.028713 -0.014376 -0.089402 -v 0.031962 -0.016210 -0.088682 -v 0.032419 -0.015951 -0.088740 -v 0.042000 -0.016441 -0.088639 -v 0.042000 -0.015429 -0.088900 -v -0.000000 -0.013615 -0.089925 -v -0.000000 -0.012868 -0.090657 -v 0.042000 -0.012160 -0.091649 -v -0.000000 -0.011895 -0.091868 -v 0.042000 -0.011895 -0.091868 -v -0.000000 -0.011738 -0.091941 -v 0.042000 -0.011738 -0.091941 -v -0.000000 -0.011571 -0.091985 -v 0.042000 -0.011399 -0.092000 -v 0.035000 -0.055315 -0.078048 -v 0.042000 -0.056878 -0.070996 -v 0.042000 -0.057468 -0.072625 -v 0.034300 -0.056595 -0.069692 -v 0.042000 -0.056584 -0.069486 -v 0.042000 -0.056702 -0.066421 -v 0.042000 -0.056525 -0.067949 -v 0.042000 -0.053042 -0.077600 -v 0.042000 -0.023722 -0.087894 -v 0.042000 -0.020848 -0.087803 -v 0.042000 -0.048252 -0.077821 -v 0.042000 -0.044753 -0.080240 -v 0.042000 -0.043749 -0.082934 -v 0.042000 -0.026223 -0.089312 -v 0.042000 -0.024629 -0.088230 -v 0.042000 -0.054669 -0.078063 -v 0.042000 -0.043688 -0.083244 -v 0.042000 -0.043579 -0.083540 -v 0.042000 -0.027038 -0.089780 -v 0.042000 -0.026743 -0.089668 -v 0.042000 -0.043229 -0.084064 -v 0.042000 -0.037058 -0.082880 -v 0.042000 -0.042996 -0.084278 -v 0.037225 -0.056328 -0.076221 -v 0.040079 -0.056332 -0.076209 -v 0.038102 -0.056987 -0.074412 -v 0.042000 -0.057474 -0.073073 -v 0.039832 -0.048370 -0.071770 -v 0.039943 -0.056773 -0.074998 -v 0.039308 -0.048509 -0.071389 -v 0.039376 -0.056958 -0.074490 -v 0.038813 -0.048559 -0.071255 -v 0.038762 -0.057016 -0.074328 -v 0.038286 -0.048545 -0.071288 -v 0.037808 -0.048473 -0.071488 -v 0.037567 -0.056860 -0.074757 -v 0.037312 -0.048295 -0.071978 -v 0.037274 -0.056712 -0.075165 -v 0.037152 -0.056544 -0.075626 -v 0.037216 -0.047822 -0.073133 -v 0.037604 -0.047562 -0.073634 -v 0.037656 -0.056112 -0.076813 -v 0.038263 -0.056005 -0.077106 -v 0.038783 -0.055990 -0.077148 -v 0.039282 -0.056036 -0.077022 -v 0.039717 -0.056139 -0.076739 -v 0.039800 -0.047623 -0.073547 -v 0.040149 -0.056555 -0.075598 -v 0.040123 -0.047916 -0.072973 -v 0.035000 -0.057522 -0.072938 -v 0.042000 -0.055805 -0.077652 -v 0.035000 -0.055813 -0.077634 -v 0.042000 -0.055196 -0.078096 -v 0.035000 -0.054794 -0.078098 -v 0.032000 -0.056310 -0.067498 -v 0.034899 -0.052178 -0.077474 -v 0.034744 -0.051390 -0.077420 -v 0.034598 -0.052661 -0.075919 -v 0.034169 -0.049944 -0.077465 -v 0.032411 -0.047174 -0.078228 -v 0.032607 -0.056611 -0.066954 -v 0.033312 -0.056524 -0.067774 -v 0.033725 -0.051964 -0.075246 -v 0.032959 -0.049356 -0.076946 -v 0.032000 -0.051604 -0.074854 -v 0.034912 -0.056983 -0.071377 -v 0.034469 -0.054537 -0.073425 -v 0.033749 -0.055597 -0.070427 -v 0.032829 -0.055195 -0.070233 -v 0.032783 -0.051667 -0.074922 -v 0.032783 -0.053600 -0.072699 -v 0.033730 -0.053953 -0.072969 -v 0.034298 -0.052359 -0.075615 -v 0.034819 -0.055108 -0.073825 -v 0.035000 -0.054823 -0.075712 -v 0.006000 -0.002060 0.153985 -v 0.021000 -0.001571 0.151682 -v 0.002000 -0.054552 0.145175 -v 0.002000 -0.006124 0.153866 -v 0.002000 -0.017547 0.152896 -v 0.002000 -0.058303 0.139623 -v 0.040000 -0.005483 0.150850 -v 0.040000 -0.058303 0.139623 -v 0.040000 -0.050161 0.146466 -v 0.040000 -0.017547 0.152896 -v 0.036000 -0.001571 0.151682 -v 0.037035 -0.001689 0.151657 -v 0.038297 -0.002264 0.151535 -v 0.038445 -0.002892 0.153971 -v 0.039064 -0.002968 0.151385 -v 0.039464 -0.003527 0.151266 -v 0.039331 -0.003852 0.153944 -v 0.039939 -0.004804 0.150995 -v 0.002061 -0.004804 0.150995 -v 0.002536 -0.003527 0.151266 -v 0.002936 -0.002968 0.151385 -v 0.002742 -0.003746 0.153950 -v 0.004000 -0.002095 0.151571 -v 0.003693 -0.002783 0.153972 -v 0.003429 -0.002486 0.151488 -v 0.004952 -0.002183 0.153984 -v 0.039939 -0.058983 0.139479 -v 0.040002 -0.059170 0.143002 -v 0.039759 -0.059642 0.139339 -v 0.039464 -0.060260 0.139207 -v 0.039622 -0.060590 0.142067 -v 0.039064 -0.060818 0.139089 -v 0.038858 -0.061553 0.141396 -v 0.036000 -0.062600 0.140598 -v 0.037451 -0.062401 0.140768 -v 0.037018 -0.062102 0.138816 -v 0.004962 -0.062098 0.138817 -v 0.004951 -0.062510 0.140669 -v 0.003693 -0.061517 0.138940 -v 0.002665 -0.061040 0.141761 -v 0.002241 -0.059642 0.139339 -v 0.002061 -0.058983 0.139479 -v 0.002104 -0.059905 0.142515 -v 0.010900 -0.064450 -0.055835 -v 0.029130 -0.064312 -0.055885 -v 0.009642 -0.061473 -0.057496 -v 0.032390 -0.059341 -0.059879 -v 0.033629 -0.058655 -0.061219 -v 0.033793 -0.058465 -0.061590 -v 0.029000 -0.065539 -0.055514 -v 0.029009 -0.065174 -0.055612 -v 0.026928 -0.073137 -0.048214 -v 0.016000 -0.070308 -0.037658 -v 0.029001 -0.074008 -0.051469 -v 0.010999 -0.074006 -0.051461 -v 0.012122 -0.072461 -0.045692 -v 0.012000 -0.072102 -0.044350 -v 0.020000 -0.070031 -0.036623 -v 0.022736 -0.070156 -0.037089 -v 0.024000 -0.070308 -0.037658 -v 0.025142 -0.070515 -0.038430 -v 0.026128 -0.070771 -0.039383 -v 0.027878 -0.071742 -0.043008 -v 0.027878 -0.072461 -0.045692 -v 0.026928 -0.071066 -0.040486 -v 0.012122 -0.071742 -0.043008 -v 0.012482 -0.071393 -0.041707 -v 0.011000 -0.071153 -0.040809 -v 0.013872 -0.070771 -0.039383 -v 0.007362 -0.069587 -0.031524 -v 0.008049 -0.069472 -0.032538 -v 0.030951 -0.069493 -0.034037 -v 0.030128 -0.069733 -0.035500 -v 0.009563 -0.069645 -0.034953 -v 0.009199 -0.069518 -0.034287 -v 0.030000 -0.072262 -0.052677 -v 0.010000 -0.072969 -0.051452 -v 0.010000 -0.072719 -0.052554 -v 0.019305 -0.073965 -0.052102 -v 0.018611 -0.055230 -0.057027 -v 0.017264 -0.055137 -0.056678 -v 0.023887 -0.073917 -0.051117 -v 0.025142 -0.073688 -0.050269 -v 0.025142 -0.054777 -0.055337 -v 0.026128 -0.073432 -0.049317 -v 0.026928 -0.054226 -0.053281 -v 0.027518 -0.053899 -0.052060 -v 0.027518 -0.072810 -0.046993 -v 0.027878 -0.053550 -0.050759 -v 0.028000 -0.072102 -0.044350 -v 0.027878 -0.052831 -0.048075 -v 0.027518 -0.071393 -0.041707 -v 0.026928 -0.052156 -0.045553 -v 0.026128 -0.051860 -0.044450 -v 0.024000 -0.051398 -0.042725 -v 0.022736 -0.051245 -0.042156 -v 0.020000 -0.051120 -0.041690 -v 0.021389 -0.070062 -0.036740 -v 0.018611 -0.051152 -0.041807 -v 0.017264 -0.051245 -0.042156 -v 0.018611 -0.070062 -0.036740 -v 0.017264 -0.070156 -0.037089 -v 0.016000 -0.051398 -0.042725 -v 0.014858 -0.070515 -0.038430 -v 0.014858 -0.051605 -0.043497 -v 0.013872 -0.051860 -0.044450 -v 0.013072 -0.071066 -0.040486 -v 0.012122 -0.052831 -0.048075 -v 0.012000 -0.053191 -0.049417 -v 0.012482 -0.072810 -0.046993 -v 0.012482 -0.053899 -0.052060 -v 0.013072 -0.054226 -0.053281 -v 0.013072 -0.073137 -0.048214 -v 0.013872 -0.073432 -0.049317 -v 0.014858 -0.073688 -0.050269 -v 0.016000 -0.054984 -0.056109 -v 0.016101 -0.073914 -0.051109 -v 0.018093 -0.073996 -0.051886 -v 0.017036 -0.073995 -0.051535 -v 0.021389 -0.073982 -0.052002 -v 0.021908 -0.073996 -0.051886 -v 0.022736 -0.073999 -0.051625 -v 0.020695 -0.073965 -0.052102 -v 0.020000 -0.073958 -0.052135 -v 0.029001 -0.073957 -0.052134 -v 0.011000 -0.073960 -0.052126 -v 0.029000 -0.073735 -0.052711 -v 0.011001 -0.073810 -0.052578 -v 0.011000 -0.073342 -0.053198 -v 0.029000 -0.073342 -0.053198 -v 0.011000 -0.073089 -0.053391 -v 0.029000 -0.072821 -0.053536 -v 0.011000 -0.072521 -0.053643 -v 0.030801 -0.069383 -0.036251 -v 0.030626 -0.069480 -0.036728 -v 0.030413 -0.069631 -0.037659 -v 0.030056 -0.070065 -0.040318 -v 0.030000 -0.065280 -0.054548 -v 0.009992 -0.064963 -0.054677 -v 0.009823 -0.069842 -0.038955 -v 0.009970 -0.070032 -0.040170 -v 0.009875 -0.064032 -0.055106 -v 0.009766 -0.069769 -0.038506 -v 0.009707 -0.069692 -0.038031 -v 0.009260 -0.069432 -0.036439 -v 0.007180 -0.069471 -0.031860 -v 0.006000 -0.070057 -0.029730 -v 0.030008 -0.069794 -0.035739 -v 0.031196 -0.069314 -0.035268 -v 0.031300 -0.069459 -0.033477 -v 0.031544 -0.069242 -0.034433 -v 0.032298 -0.069341 -0.032883 -v 0.031820 -0.069507 -0.032717 -v 0.032486 -0.069366 -0.032498 -v 0.032615 -0.069581 -0.031556 -v 0.032992 -0.069711 -0.031059 -v 0.033135 -0.069646 -0.031303 -v 0.033788 -0.069927 -0.030101 -v 0.030182 -0.069795 -0.038678 -v 0.030000 -0.070187 -0.041068 -v 0.029429 -0.070238 -0.037397 -v 0.030000 -0.073111 -0.051984 -v 0.029000 -0.071153 -0.040809 -v 0.029000 -0.073870 -0.052430 -v 0.029000 -0.073560 -0.052968 -v 0.029000 -0.073089 -0.053391 -v 0.029000 -0.072521 -0.053643 -v 0.030048 -0.064613 -0.054827 -v 0.030965 -0.061709 -0.056743 -v 0.029748 -0.062519 -0.056755 -v 0.030145 -0.063919 -0.055163 -v 0.029359 -0.063442 -0.056252 -v 0.030432 -0.062908 -0.055780 -v 0.032818 -0.059288 -0.059839 -v 0.032166 -0.059542 -0.059615 -v 0.032315 -0.059848 -0.059006 -v 0.031762 -0.060464 -0.058087 -v 0.031706 -0.060551 -0.057993 -v 0.031299 -0.060317 -0.058595 -v 0.030444 -0.061366 -0.057584 -v 0.031191 -0.061355 -0.057125 -v 0.009993 -0.069794 -0.035738 -v 0.008799 -0.069321 -0.035265 -v 0.008977 -0.069391 -0.034581 -v 0.007691 -0.069372 -0.032885 -v 0.007008 -0.069709 -0.031058 -v 0.008495 -0.069265 -0.034543 -v 0.008365 -0.069241 -0.034234 -v 0.009600 -0.069630 -0.037650 -v 0.010000 -0.070187 -0.041068 -v 0.010616 -0.070330 -0.037738 -v 0.009194 -0.069394 -0.036204 -v 0.011000 -0.072821 -0.053536 -v 0.011000 -0.073559 -0.052969 -v 0.011000 -0.065539 -0.055514 -v 0.010000 -0.065280 -0.054548 -v 0.010990 -0.065174 -0.055612 -v 0.007552 -0.059712 -0.059227 -v 0.007390 -0.059179 -0.060141 -v 0.008293 -0.060552 -0.057994 -v 0.008233 -0.060458 -0.058095 -v 0.008614 -0.060228 -0.058696 -v 0.007829 -0.059555 -0.059623 -v 0.009921 -0.064388 -0.054931 -v 0.010673 -0.063537 -0.056208 -v 0.010265 -0.062550 -0.056737 -v 0.009598 -0.062995 -0.055715 -v 0.007055 -0.059173 -0.060052 -v 0.006754 -0.058807 -0.060923 -v 0.006372 -0.058651 -0.061216 -v 0.009068 -0.061771 -0.056686 -v 0.008502 -0.060880 -0.057642 -v 0.027891 -0.016663 -0.088602 -v 0.028405 -0.016622 -0.088610 -v 0.029137 -0.016014 -0.088717 -v 0.029195 -0.015832 -0.082001 -v 0.029240 -0.015196 -0.082000 -v 0.029220 -0.015014 -0.089057 -v 0.028622 -0.014320 -0.082000 -v 0.028077 -0.014157 -0.089528 -v 0.028000 -0.014156 -0.082000 -v 0.027539 -0.014250 -0.089467 -v 0.026854 -0.014906 -0.089112 -v 0.026769 -0.015201 -0.088986 -v 0.026780 -0.015054 -0.082000 -v 0.026750 -0.015422 -0.088903 -v 0.026807 -0.015832 -0.088770 -v 0.027282 -0.016473 -0.082000 -v 0.031062 -0.015751 -0.088794 -v 0.031526 -0.016168 -0.088691 -v 0.031738 -0.016222 -0.080223 -v 0.032451 -0.014924 -0.089102 -v 0.031136 -0.014926 -0.089103 -v -0.000000 -0.025470 -0.088707 -v 0.042000 -0.025470 -0.088707 -v 0.042000 -0.022773 -0.087709 -v -0.000000 -0.023722 -0.087894 -v 0.042000 -0.021807 -0.087678 -v -0.000000 -0.022773 -0.087709 -v -0.000000 -0.020848 -0.087803 -v 0.021684 -0.037130 -0.086519 -v 0.020316 -0.033598 -0.087804 -v 0.019714 -0.033924 -0.087685 -v 0.019468 -0.034156 -0.087601 -v 0.021347 -0.033513 -0.087835 -v 0.021000 -0.033484 -0.087845 -v 0.020653 -0.037215 -0.086488 -v 0.008250 -0.037398 -0.086421 -v 0.008607 -0.037163 -0.086506 -v 0.008915 -0.036874 -0.086612 -v 0.009349 -0.034560 -0.087454 -v -0.000000 -0.028282 -0.089739 -v 0.007855 -0.033156 -0.087965 -v 0.034145 -0.037571 -0.086358 -v 0.037462 -0.034956 -0.087310 -v 0.037349 -0.034560 -0.087454 -v 0.036607 -0.033564 -0.087816 -v 0.036250 -0.033329 -0.087902 -v 0.009349 -0.036167 -0.086869 -v 0.009500 -0.035364 -0.087161 -v 0.033393 -0.037163 -0.086506 -v 0.035000 -0.037713 -0.086306 -v 0.042000 -0.042446 -0.084584 -v 0.035855 -0.037571 -0.086358 -v 0.042000 -0.028282 -0.089739 -v 0.035434 -0.033050 -0.088003 -v 0.005750 -0.033329 -0.087902 -v 0.005393 -0.033564 -0.087816 -v 0.004835 -0.034189 -0.087589 -v 0.022532 -0.034156 -0.087601 -v 0.032835 -0.034189 -0.087589 -v 0.036607 -0.037163 -0.086506 -v 0.037165 -0.036538 -0.086734 -v 0.037462 -0.035772 -0.087013 -v 0.037500 -0.035364 -0.087161 -v 0.035000 -0.033015 -0.088016 -v 0.022286 -0.033924 -0.087685 -v 0.034566 -0.033050 -0.088003 -v 0.034145 -0.033156 -0.087965 -v 0.004651 -0.036167 -0.086869 -v 0.005393 -0.037163 -0.086506 -v 0.006145 -0.037571 -0.086358 -v 0.019714 -0.036804 -0.086637 -v 0.020316 -0.037130 -0.086519 -v 0.004651 -0.034560 -0.087454 -v 0.004500 -0.035364 -0.087161 -v 0.019268 -0.034424 -0.087503 -v 0.005085 -0.036874 -0.086612 -v 0.032651 -0.036167 -0.086869 -v 0.032835 -0.036538 -0.086734 -v 0.000000 -0.042446 -0.084584 -v 0.032538 -0.035772 -0.087013 -v 0.032500 -0.035364 -0.087161 -v 0.022996 -0.035560 -0.087090 -v 0.032538 -0.034956 -0.087310 -v 0.032651 -0.034560 -0.087454 -v 0.022948 -0.034909 -0.087327 -v 0.022732 -0.034424 -0.087503 -v 0.007855 -0.037571 -0.086358 -v 0.000000 -0.046895 -0.078322 -v 0.000000 -0.046081 -0.078843 -v 0.032000 -0.046895 -0.078322 -v 0.032122 -0.046749 -0.078403 -v 0.042000 -0.046081 -0.078843 -v 0.042000 -0.045361 -0.079488 -v 0.000000 -0.045361 -0.079488 -v 0.042000 -0.044274 -0.081079 -v 0.042000 -0.043937 -0.081985 -v 0.000000 -0.044274 -0.081079 -v -0.000000 -0.021807 -0.087678 -v -0.000000 -0.026786 -0.086346 -v 0.000000 -0.043937 -0.081985 -v 0.000000 -0.044753 -0.080240 -v -0.000000 -0.024629 -0.088230 -v 0.000000 -0.037058 -0.082880 -v 0.000000 -0.042996 -0.084278 -v -0.000000 -0.027977 -0.089823 -v 0.000000 -0.043749 -0.082934 -v 0.000000 -0.043579 -0.083540 -v -0.000000 -0.026223 -0.089312 -v -0.000000 -0.027348 -0.089844 -v 0.000000 -0.043688 -0.083244 -v 0.000000 -0.043425 -0.083816 -v 0.000000 -0.043229 -0.084064 -v 0.042000 -0.043425 -0.083816 -v 0.000000 -0.042733 -0.084452 -v 0.042000 -0.042733 -0.084453 -v -0.000000 -0.027663 -0.089859 -v 0.042000 -0.027977 -0.089823 -v 0.042000 -0.027663 -0.089859 -v 0.042000 -0.027348 -0.089844 -v -0.000000 -0.027038 -0.089780 -v -0.000000 -0.026743 -0.089668 -v -0.000000 -0.026469 -0.089511 -v 0.042000 -0.026469 -0.089511 -v 0.034566 -0.034257 -0.076922 -v 0.033393 -0.033743 -0.077109 -v 0.033085 -0.033454 -0.077215 -v 0.033750 -0.033978 -0.077024 -v 0.032538 -0.032352 -0.077616 -v 0.035000 -0.031430 -0.076353 -v 0.032538 -0.031536 -0.077913 -v 0.032835 -0.030769 -0.078192 -v 0.034145 -0.029736 -0.078568 -v 0.033750 -0.029909 -0.078505 -v 0.036607 -0.030144 -0.078419 -v 0.037349 -0.031140 -0.078057 -v 0.036915 -0.030434 -0.078314 -v 0.037462 -0.032352 -0.077616 -v 0.036915 -0.033454 -0.077215 -v 0.035855 -0.034151 -0.076961 -v 0.036250 -0.033978 -0.077024 -v 0.035434 -0.034257 -0.076922 -v 0.035000 -0.034293 -0.076909 -v 0.034145 -0.034151 -0.076961 -v 0.034566 -0.037677 -0.086319 -v 0.033750 -0.037398 -0.086421 -v 0.033085 -0.036874 -0.086612 -v 0.032835 -0.033118 -0.077337 -v 0.032651 -0.032747 -0.077472 -v 0.032500 -0.031944 -0.077764 -v 0.032651 -0.031140 -0.078057 -v 0.033085 -0.030434 -0.078314 -v 0.033393 -0.030144 -0.078419 -v 0.033085 -0.033854 -0.087711 -v 0.033393 -0.033564 -0.087816 -v 0.033750 -0.033329 -0.087902 -v 0.034566 -0.029630 -0.078606 -v 0.035000 -0.029594 -0.078619 -v 0.035434 -0.029630 -0.078606 -v 0.035855 -0.029736 -0.078568 -v 0.036250 -0.029909 -0.078505 -v 0.035855 -0.033156 -0.087965 -v 0.036915 -0.033854 -0.087711 -v 0.037165 -0.030769 -0.078192 -v 0.037165 -0.034189 -0.087589 -v 0.037462 -0.031536 -0.077913 -v 0.037500 -0.031944 -0.077764 -v 0.037349 -0.032747 -0.077472 -v 0.037349 -0.036167 -0.086869 -v 0.037165 -0.033118 -0.077337 -v 0.036607 -0.033743 -0.077109 -v 0.036915 -0.036874 -0.086612 -v 0.036250 -0.037398 -0.086421 -v 0.035434 -0.037677 -0.086319 -v 0.006566 -0.034257 -0.076922 -v 0.006145 -0.034151 -0.076961 -v 0.004835 -0.033118 -0.077337 -v 0.007000 -0.031430 -0.076353 -v 0.004538 -0.031536 -0.077913 -v 0.004651 -0.031140 -0.078057 -v 0.004500 -0.031944 -0.077764 -v 0.006566 -0.029630 -0.078606 -v 0.007000 -0.029594 -0.078619 -v 0.008915 -0.030434 -0.078314 -v 0.008250 -0.029909 -0.078505 -v 0.008607 -0.030144 -0.078419 -v 0.009165 -0.030769 -0.078192 -v 0.009500 -0.031944 -0.077764 -v 0.009462 -0.032352 -0.077616 -v 0.008915 -0.033454 -0.077215 -v 0.009349 -0.032747 -0.077472 -v 0.009165 -0.033118 -0.077337 -v 0.007855 -0.034151 -0.076961 -v 0.006566 -0.037677 -0.086319 -v 0.005750 -0.033978 -0.077024 -v 0.005393 -0.033743 -0.077109 -v 0.005750 -0.037398 -0.086421 -v 0.005085 -0.033454 -0.077215 -v 0.004835 -0.036538 -0.086734 -v 0.004651 -0.032747 -0.077472 -v 0.004538 -0.032352 -0.077616 -v 0.004538 -0.035772 -0.087013 -v 0.004538 -0.034956 -0.087310 -v 0.004835 -0.030769 -0.078192 -v 0.005085 -0.030434 -0.078314 -v 0.005085 -0.033854 -0.087711 -v 0.005393 -0.030144 -0.078419 -v 0.005750 -0.029909 -0.078505 -v 0.006145 -0.033156 -0.087965 -v 0.006145 -0.029736 -0.078568 -v 0.006566 -0.033050 -0.088003 -v 0.007434 -0.029630 -0.078606 -v 0.007000 -0.033015 -0.088016 -v 0.007434 -0.033050 -0.088003 -v 0.007855 -0.029736 -0.078568 -v 0.008250 -0.033329 -0.087902 -v 0.008607 -0.033564 -0.087816 -v 0.008915 -0.033854 -0.087711 -v 0.009165 -0.034189 -0.087589 -v 0.009349 -0.031140 -0.078057 -v 0.009462 -0.031536 -0.077913 -v 0.009462 -0.034956 -0.087310 -v 0.009462 -0.035772 -0.087013 -v 0.009165 -0.036538 -0.086734 -v 0.008607 -0.033743 -0.077109 -v 0.008250 -0.033978 -0.077024 -v 0.007434 -0.037677 -0.086319 -v 0.007434 -0.034257 -0.076922 -v 0.007000 -0.034293 -0.076909 -v 0.007000 -0.037713 -0.086306 -v 0.021000 -0.031533 -0.076635 -v 0.020452 -0.030130 -0.078424 -v 0.021000 -0.030064 -0.078448 -v 0.022000 -0.030316 -0.078357 -v 0.021000 -0.037243 -0.086477 -v 0.020182 -0.033666 -0.077137 -v 0.020000 -0.036991 -0.086569 -v 0.019604 -0.033298 -0.077271 -v 0.019337 -0.036419 -0.086777 -v 0.019196 -0.032769 -0.077463 -v 0.019121 -0.036007 -0.086927 -v 0.019004 -0.032140 -0.077692 -v 0.018998 -0.035503 -0.087111 -v 0.019068 -0.034852 -0.087347 -v 0.019052 -0.031488 -0.077929 -v 0.019337 -0.030888 -0.078148 -v 0.019823 -0.030415 -0.078320 -v 0.020000 -0.033736 -0.087754 -v 0.020653 -0.033513 -0.087835 -v 0.021488 -0.030115 -0.078429 -v 0.021684 -0.033598 -0.087804 -v 0.022000 -0.033736 -0.087754 -v 0.022395 -0.030588 -0.078257 -v 0.022804 -0.031117 -0.078064 -v 0.022970 -0.031617 -0.077883 -v 0.023002 -0.032083 -0.077713 -v 0.022830 -0.032716 -0.077482 -v 0.022804 -0.036189 -0.086860 -v 0.022532 -0.033152 -0.077325 -v 0.022532 -0.036572 -0.086722 -v 0.022179 -0.033470 -0.077208 -v 0.022286 -0.036804 -0.086637 -v 0.022000 -0.036991 -0.086569 -v 0.021554 -0.033756 -0.077105 -v 0.021347 -0.037215 -0.086488 -v 0.020860 -0.033824 -0.077079 -v 0.032614 -0.015474 -0.088879 -v 0.032202 -0.016117 -0.080223 -v 0.031214 -0.015970 -0.080224 -v 0.031034 -0.015192 -0.080243 -v 0.031301 -0.014800 -0.080223 -v 0.031810 -0.014601 -0.080223 -v 0.032448 -0.014906 -0.080224 -v 0.028732 -0.016463 -0.082000 -v 0.029029 -0.014698 -0.082000 -v 0.027281 -0.014368 -0.082000 -v 0.028006 -0.016680 -0.082000 -v 0.026808 -0.015842 -0.082000 -v 0.032530 -0.015775 -0.080227 -v 0.032586 0.015192 -0.080243 -v 0.032319 0.014800 -0.080224 -v 0.031914 0.014621 -0.080222 -v 0.031433 0.014699 -0.080225 -v 0.031093 0.015052 -0.089049 -v 0.031011 0.015379 -0.080252 -v 0.032192 0.016124 -0.080223 -v 0.032546 0.015754 -0.080233 -v 0.029017 0.014683 -0.082000 -v 0.028313 0.016633 -0.082000 -v 0.028628 0.014321 -0.082000 -v 0.027370 0.016512 -0.082000 -v 0.027468 0.014261 -0.082000 -v 0.124653 0.086004 0.030817 -v 0.123994 0.086490 0.032030 -v 0.120967 0.088560 0.038778 -v 0.121736 0.088058 0.036806 -v 0.042131 0.096496 0.049380 -v 0.119039 0.089744 0.047763 -v 0.042131 0.096081 0.042241 -v 0.119722 0.089335 0.043029 -v 0.042131 0.094839 0.035199 -v 0.119763 0.089311 0.042830 -v 0.119773 0.089305 0.085652 -v 0.119856 0.089254 0.086001 -v 0.118991 0.089772 0.079060 -v 0.119183 0.089659 0.082306 -v 0.121152 0.088441 0.090168 -v 0.042131 0.094306 0.095326 -v 0.122544 0.087511 0.093462 -v 0.126170 0.084834 0.100230 -v 0.042131 0.091605 0.103095 -v 0.042131 0.087892 0.110433 -v 0.130378 0.081197 0.106586 -v 0.129314 0.072599 0.117637 -v 0.042131 0.071423 0.128609 -v 0.123849 0.067181 0.122841 -v 0.126433 0.069855 0.120463 -v 0.042131 0.077710 0.123306 -v 0.137314 0.077535 0.010787 -v 0.133224 0.080697 0.018430 -v 0.123026 0.057102 -0.049011 -v 0.117794 0.056625 -0.051659 -v 0.079271 0.055356 -0.064999 -v 0.113587 0.056301 -0.053626 -v 0.102491 0.055680 -0.058170 -v 0.096810 0.055485 -0.060160 -v 0.160006 0.057105 0.029137 -v 0.158384 0.058230 0.002879 -v 0.158608 0.058585 0.006007 -v 0.158942 0.058236 0.010023 -v 0.156802 0.050006 -0.019624 -v 0.155997 0.046371 -0.027279 -v 0.155542 0.046362 -0.029851 -v 0.155336 0.024276 -0.039762 -v 0.153367 0.031703 -0.047261 -v 0.153904 0.036928 -0.043012 -v 0.155662 0.016160 -0.039710 -v 0.155857 0.007826 -0.039679 -v 0.153298 -0.004211 -0.051862 -v 0.153228 -0.009050 -0.051788 -v 0.155837 -0.009051 -0.039682 -v 0.155622 -0.017362 -0.039716 -v 0.153367 -0.031703 -0.047261 -v 0.153518 -0.033171 -0.046067 -v 0.156561 -0.040494 -0.027171 -v 0.155837 -0.047085 -0.027805 -v 0.154524 -0.043866 -0.036921 -v 0.157808 -0.047313 -0.014486 -v 0.155911 -0.047309 -0.027176 -v 0.158468 -0.040494 -0.014337 -v 0.158608 -0.058585 0.006007 -v 0.160319 -0.053580 0.023992 -v 0.160006 -0.057105 0.029137 -v 0.161132 0.046371 0.024261 -v 0.161228 0.047636 0.037165 -v 0.161368 0.046371 0.037216 -v 0.161869 0.040827 0.037400 -v 0.161763 0.039463 0.024470 -v 0.162419 0.033525 0.037602 -v 0.162301 0.032073 0.024648 -v 0.162523 0.032073 0.037641 -v 0.162731 0.024276 0.024790 -v 0.162949 0.024276 0.037797 -v 0.163258 0.016160 0.037911 -v 0.163044 0.016160 0.024894 -v 0.163408 0.009437 0.037966 -v 0.163444 0.007826 0.037979 -v 0.163232 0.007826 0.024956 -v 0.163439 -0.007438 0.037978 -v 0.163288 -0.000616 0.024975 -v 0.163213 -0.009051 0.024950 -v 0.163425 -0.009051 0.037972 -v 0.163260 -0.015781 0.037912 -v 0.163006 -0.017362 0.024882 -v 0.162535 -0.031723 0.037645 -v 0.162452 -0.033179 0.037614 -v 0.162229 -0.033179 0.024624 -v 0.159833 -0.017362 -0.014028 -v 0.157936 -0.017362 -0.026906 -v 0.160123 -0.000616 -0.013962 -v 0.158169 0.007826 -0.026861 -v 0.157652 0.024276 -0.026961 -v 0.159551 0.024276 -0.014092 -v 0.159108 0.032073 -0.014192 -v 0.158556 0.039463 -0.014317 -v 0.157908 0.046371 -0.014463 -v 0.157131 -0.033179 -0.027061 -v 0.154813 -0.033179 -0.039845 -v 0.155278 -0.025438 -0.039771 -v 0.157594 -0.025438 -0.026972 -v 0.158149 -0.009051 -0.026865 -v 0.155915 -0.000616 -0.039670 -v 0.158228 -0.000616 -0.026850 -v 0.157975 0.016160 -0.026899 -v 0.154888 0.032073 -0.039833 -v 0.157206 0.032073 -0.027047 -v 0.154329 0.039463 -0.039922 -v 0.156650 0.039463 -0.027154 -v 0.161907 -0.040494 0.037414 -v 0.159303 -0.047313 -0.001618 -v 0.159034 -0.033179 -0.014209 -v 0.160519 -0.033179 -0.001301 -v 0.159493 -0.025438 -0.014105 -v 0.161312 -0.017362 -0.001095 -v 0.160045 -0.009051 -0.013980 -v 0.161522 -0.009051 -0.001040 -v 0.161599 -0.000616 -0.001020 -v 0.160065 0.007826 -0.013975 -v 0.159872 0.016160 -0.014019 -v 0.159401 0.046371 -0.001593 -v 0.157495 0.052736 -0.012070 -v 0.158677 0.052744 -0.001781 -v 0.161036 -0.047313 0.024229 -v 0.161272 -0.047313 0.037181 -v 0.160694 -0.052420 0.036969 -v 0.160563 -0.053580 0.036921 -v 0.160120 -0.056981 0.036758 -v 0.161027 -0.040494 0.011483 -v 0.161677 -0.040494 0.024441 -v 0.161584 -0.033179 0.011647 -v 0.162675 -0.025438 0.024772 -v 0.162370 -0.017362 0.011880 -v 0.162578 -0.009051 0.011941 -v 0.162408 0.016160 0.011891 -v 0.161114 0.039463 0.011508 -v 0.160476 0.046371 0.011320 -v 0.160422 0.052744 0.024026 -v 0.159654 -0.053580 0.011078 -v 0.158572 -0.053580 -0.001808 -v 0.160379 -0.047313 0.011291 -v 0.159957 -0.040494 -0.001448 -v 0.162035 -0.025438 0.011781 -v 0.160974 -0.025438 -0.001183 -v 0.161541 0.007826 -0.001035 -v 0.162655 -0.000616 0.011964 -v 0.162597 0.007826 0.011947 -v 0.161350 0.016160 -0.001084 -v 0.161031 0.024276 -0.001168 -v 0.162092 0.024276 0.011798 -v 0.160592 0.032073 -0.001282 -v 0.161657 0.032073 0.011669 -v 0.160044 0.039463 -0.001425 -v 0.158198 0.056522 -0.001718 -v 0.159759 0.052744 0.011108 -v 0.158609 0.058581 0.069781 -v 0.159233 0.053902 0.070065 -v 0.160147 -0.052422 0.059102 -v 0.159831 -0.057294 0.052038 -v 0.158722 -0.058466 0.068646 -v 0.158676 -0.058216 0.069806 -v 0.158963 -0.058215 0.065816 -v 0.154357 -0.062689 0.100263 -v 0.157011 -0.052422 0.092152 -v 0.155126 -0.055569 0.102057 -v 0.158246 -0.039127 0.092812 -v 0.157665 -0.046046 0.092501 -v 0.156491 -0.041748 0.102942 -v 0.156095 -0.046041 0.102674 -v 0.157516 -0.023910 0.103755 -v 0.157916 -0.010666 0.104097 -v 0.157781 -0.015780 0.103980 -v 0.159421 -0.015781 0.093441 -v 0.159637 0.001007 0.093556 -v 0.158008 -0.000074 0.104179 -v 0.157892 0.011946 0.104077 -v 0.157735 0.017737 0.103940 -v 0.159364 0.017738 0.093410 -v 0.157276 0.029563 0.103553 -v 0.159051 0.025800 0.093243 -v 0.158631 0.033525 0.093018 -v 0.158115 0.040828 0.092742 -v 0.157513 0.047637 0.092420 -v 0.155967 0.047636 0.102581 -v 0.156841 0.053902 0.092061 -v 0.154590 0.059586 0.101780 -v 0.157620 0.059586 0.078898 -v 0.159831 0.057294 0.052038 -v 0.160120 0.056981 0.036758 -v 0.160400 0.053902 0.047969 -v 0.160666 0.052744 0.036958 -v 0.161992 0.039463 0.037445 -v 0.161741 0.040828 0.048505 -v 0.161108 0.047637 0.048252 -v 0.163198 0.017737 0.037889 -v 0.162866 0.025800 0.037767 -v 0.162286 0.033525 0.048722 -v 0.163057 0.017738 0.049030 -v 0.163295 -0.007438 0.049126 -v 0.163344 0.001007 0.049145 -v 0.163500 -0.000616 0.038000 -v 0.163489 0.001007 0.037996 -v 0.162817 -0.023911 0.048934 -v 0.162894 -0.025438 0.037777 -v 0.162956 -0.023911 0.037800 -v 0.163221 -0.017362 0.037897 -v 0.163117 -0.015781 0.049055 -v 0.161390 -0.046045 0.037224 -v 0.161880 -0.039127 0.048560 -v 0.162009 -0.039126 0.037452 -v 0.162400 -0.031723 0.048768 -v 0.160828 -0.046046 0.059395 -v 0.161433 -0.039127 0.059657 -v 0.160080 -0.046046 0.070459 -v 0.160677 -0.039127 0.070736 -v 0.161592 -0.023911 0.071162 -v 0.162656 -0.015781 0.060185 -v 0.161886 -0.015781 0.071299 -v 0.162059 -0.007438 0.071380 -v 0.162801 0.009437 0.060248 -v 0.162029 0.009437 0.071366 -v 0.162271 0.025800 0.060019 -v 0.161505 0.025800 0.071122 -v 0.161296 0.040828 0.059597 -v 0.160542 0.040828 0.070674 -v 0.160670 0.047637 0.059327 -v 0.159924 0.047637 0.070386 -v 0.161268 -0.046046 0.048316 -v 0.161947 -0.031723 0.059879 -v 0.162359 -0.023911 0.060057 -v 0.162832 -0.007438 0.060261 -v 0.162880 0.001007 0.060282 -v 0.163264 0.009437 0.049113 -v 0.162596 0.017738 0.060159 -v 0.162728 0.025800 0.048899 -v 0.161834 0.033525 0.059830 -v 0.159970 0.053902 0.059025 -v 0.160579 -0.052422 0.048041 -v 0.156299 -0.058216 0.091772 -v 0.158362 -0.052422 0.081166 -v 0.159025 -0.046046 0.081497 -v 0.160117 -0.031723 0.082042 -v 0.160517 -0.023911 0.082242 -v 0.158741 -0.031723 0.093076 -v 0.159136 -0.023911 0.093288 -v 0.159590 -0.007438 0.093531 -v 0.161026 0.001007 0.082496 -v 0.159561 0.009437 0.093515 -v 0.160949 0.009437 0.082458 -v 0.160749 0.017738 0.082358 -v 0.160432 0.025800 0.082199 -v 0.159482 0.040828 0.081724 -v 0.158871 0.047637 0.081420 -v 0.158189 0.053902 0.081079 -v 0.156112 0.059588 0.091672 -v 0.157640 -0.058216 0.080806 -v 0.159408 -0.052422 0.070146 -v 0.159615 -0.039127 0.081791 -v 0.161186 -0.031723 0.070973 -v 0.160807 -0.015781 0.082387 -v 0.160978 -0.007438 0.082472 -v 0.162107 0.001007 0.071402 -v 0.161827 0.017738 0.071271 -v 0.161074 0.033525 0.070921 -v 0.160006 0.033525 0.081986 -v 0.129894 -0.059307 0.124483 -v 0.151670 0.038193 0.112976 -v 0.108379 0.042243 0.135631 -v 0.065421 0.006898 0.147257 -v 0.058936 0.001770 0.148012 -v 0.080404 0.014398 0.144798 -v 0.095760 0.031906 0.140342 -v 0.101804 0.036859 0.138243 -v 0.112783 0.042062 0.134207 -v 0.117482 0.041851 0.132533 -v 0.121924 0.053340 0.129080 -v 0.126850 0.057255 0.126302 -v 0.137252 0.054160 0.121427 -v 0.133813 0.054477 0.123310 -v 0.144000 0.065394 0.114922 -v 0.143351 0.053518 0.117617 -v 0.149588 0.054190 0.112572 -v 0.150620 0.039497 0.113824 -v 0.148440 0.039737 0.115733 -v 0.150620 0.026369 0.115199 -v 0.153450 0.010693 0.113274 -v 0.153023 0.020977 0.113215 -v 0.150620 -0.026369 0.115199 -v 0.150620 -0.039497 0.113824 -v 0.151265 -0.041912 0.112897 -v 0.151515 -0.039389 0.112945 -v 0.148440 -0.052875 0.113800 -v 0.146019 -0.053196 0.115706 -v 0.143086 -0.065980 0.115451 -v 0.126156 -0.055097 0.126991 -v 0.126850 -0.057255 0.126302 -v 0.130114 -0.054790 0.125168 -v 0.121943 -0.041633 0.130796 -v 0.121924 -0.053340 0.129080 -v 0.126156 -0.041407 0.129005 -v 0.112783 -0.042062 0.134207 -v 0.112777 -0.045844 0.133697 -v 0.113463 -0.046406 0.133395 -v 0.117482 -0.041851 0.132533 -v 0.117469 -0.049688 0.131428 -v 0.101804 -0.036859 0.138243 -v 0.107857 -0.028217 0.137279 -v 0.107856 -0.041814 0.135862 -v 0.091872 -0.028576 0.141569 -v 0.095760 -0.031906 0.140342 -v 0.097383 -0.028464 0.140237 -v 0.091872 -0.014300 0.142464 -v 0.086201 -0.024057 0.143133 -v 0.089592 -0.026844 0.142222 -v 0.080404 -0.014398 0.144798 -v 0.080399 -0.019281 0.144533 -v 0.086204 -0.014351 0.143689 -v 0.080404 0.000000 0.145098 -v 0.074496 0.000000 0.146084 -v 0.068502 -0.009451 0.146780 -v 0.071954 -0.012311 0.146246 -v 0.057207 -0.000074 0.148175 -v 0.062460 0.000000 0.147662 -v 0.068506 0.000000 0.146940 -v 0.062458 -0.004434 0.147604 -v 0.065421 -0.006898 0.147257 -v 0.126156 0.041407 0.129005 -v 0.126156 0.055097 0.126991 -v 0.130114 0.041176 0.127170 -v 0.130114 0.054790 0.125168 -v 0.133813 0.040941 0.125301 -v 0.140430 0.053840 0.119526 -v 0.146019 0.053196 0.115706 -v 0.148440 0.052875 0.113800 -v 0.150720 0.046368 0.112789 -v 0.124238 -0.055237 0.127814 -v 0.133813 -0.054477 0.123310 -v 0.137252 -0.054160 0.121427 -v 0.137252 -0.040703 0.123406 -v 0.140430 -0.040462 0.121494 -v 0.140430 -0.053840 0.119526 -v 0.143351 -0.053518 0.117617 -v 0.143351 -0.040220 0.119574 -v 0.150612 -0.046872 0.112769 -v 0.107709 0.041695 0.135926 -v 0.107857 0.028217 0.137279 -v 0.121943 0.041633 0.130796 -v 0.121943 0.027795 0.132245 -v 0.130114 0.027491 0.128603 -v 0.137252 0.040703 0.123406 -v 0.137252 0.027175 0.124823 -v 0.140430 0.040462 0.121494 -v 0.140430 0.027014 0.122903 -v 0.143351 0.040220 0.119574 -v 0.146019 0.026691 0.119042 -v 0.146019 0.039978 0.117651 -v 0.148440 0.026530 0.117115 -v 0.152439 0.029715 0.113119 -v 0.108379 -0.042243 0.135631 -v 0.112783 -0.028082 0.135671 -v 0.126156 -0.027645 0.130446 -v 0.130114 -0.041176 0.127170 -v 0.130114 -0.027491 0.128603 -v 0.133813 -0.040941 0.125301 -v 0.133813 -0.027334 0.126726 -v 0.140430 -0.027014 0.122903 -v 0.146019 -0.026691 0.119042 -v 0.146019 -0.039978 0.117651 -v 0.148440 -0.039737 0.115733 -v 0.091872 0.028576 0.141569 -v 0.091872 0.014300 0.142464 -v 0.097383 0.014244 0.141128 -v 0.097383 0.028464 0.140237 -v 0.107857 0.014121 0.138163 -v 0.102718 0.028344 0.138804 -v 0.112783 0.014053 0.136551 -v 0.112783 0.028082 0.135671 -v 0.117482 0.027941 0.133990 -v 0.117482 0.013983 0.134865 -v 0.126156 0.013835 0.131312 -v 0.126156 0.027645 0.130446 -v 0.130114 0.013757 0.129464 -v 0.133813 0.013679 0.127582 -v 0.133813 0.027334 0.126726 -v 0.137252 0.013599 0.125674 -v 0.140430 0.013519 0.123749 -v 0.143351 0.013438 0.121814 -v 0.143351 0.026853 0.120973 -v 0.148440 0.013276 0.117946 -v 0.152569 0.026210 0.113298 -v 0.097383 -0.014244 0.141128 -v 0.102718 -0.028344 0.138804 -v 0.102718 -0.014184 0.139692 -v 0.112783 -0.014053 0.136551 -v 0.117482 -0.013983 0.134865 -v 0.117482 -0.027941 0.133990 -v 0.121943 -0.013910 0.133115 -v 0.121943 -0.027795 0.132245 -v 0.126156 -0.013835 0.131312 -v 0.137252 -0.027175 0.124823 -v 0.140430 -0.013519 0.123749 -v 0.143351 -0.026852 0.120973 -v 0.143351 -0.013438 0.121814 -v 0.148440 -0.026530 0.117115 -v 0.152569 -0.026210 0.113298 -v 0.153002 -0.021363 0.113211 -v 0.086204 0.000000 0.143989 -v 0.086204 0.014351 0.143689 -v 0.091872 0.000000 0.142762 -v 0.097383 0.000000 0.141426 -v 0.102718 0.000000 0.139988 -v 0.102718 0.014184 0.139692 -v 0.112783 0.000000 0.136844 -v 0.121943 0.000000 0.133406 -v 0.121943 0.013910 0.133115 -v 0.130114 0.000000 0.129751 -v 0.133813 0.000000 0.127867 -v 0.137252 0.000000 0.125958 -v 0.143351 0.000000 0.122095 -v 0.146019 0.000000 0.120157 -v 0.146019 0.013357 0.119878 -v 0.148440 0.000000 0.118223 -v 0.150620 0.000000 0.116300 -v 0.150620 0.013196 0.116025 -v 0.152569 0.013117 0.114118 -v 0.107857 -0.014121 0.138163 -v 0.107857 0.000000 0.138458 -v 0.117482 0.000000 0.135157 -v 0.126156 0.000000 0.131601 -v 0.130114 -0.013757 0.129464 -v 0.133813 -0.013679 0.127582 -v 0.137252 -0.013599 0.125674 -v 0.140430 0.000000 0.124031 -v 0.146019 -0.013357 0.119878 -v 0.148440 -0.013276 0.117946 -v 0.150620 -0.013196 0.116025 -v 0.152569 -0.013117 0.114118 -v 0.152569 0.000000 0.114392 -v 0.042131 -0.096081 0.042241 -v 0.119290 -0.089596 0.045325 -v 0.042131 -0.094839 0.035199 -v 0.123360 -0.086946 0.033259 -v 0.121748 -0.088048 0.036809 -v 0.042131 -0.071423 0.128609 -v 0.126433 -0.069855 0.120463 -v 0.042131 -0.077710 0.123306 -v 0.129314 -0.072599 0.117637 -v 0.126170 -0.084834 0.100230 -v 0.126165 -0.084838 0.100221 -v 0.128185 -0.083167 0.103401 -v 0.130315 -0.081253 0.106495 -v 0.042131 -0.083232 0.117211 -v 0.119955 -0.089193 0.086357 -v 0.118991 -0.089772 0.079060 -v 0.119039 -0.089744 0.080684 -v 0.119183 -0.089659 0.082306 -v 0.139744 -0.062105 -0.030987 -v 0.140669 -0.064863 -0.023173 -v 0.142018 -0.070961 -0.006071 -v 0.142260 -0.073030 -0.000326 -v 0.125389 -0.085610 0.029923 -v 0.067190 -0.055658 -0.067261 -v 0.042131 -0.092788 0.028348 -v 0.085197 -0.055322 -0.063577 -v 0.113587 -0.056301 -0.053626 -v 0.074612 0.047909 -0.075275 -v 0.063332 0.048522 -0.076895 -v 0.081418 0.039401 -0.079448 -v 0.095053 0.030803 -0.081224 -v 0.098589 0.036699 -0.076714 -v 0.110404 0.034997 -0.074043 -v 0.122089 0.033054 -0.070992 -v 0.122078 0.032336 -0.071409 -v 0.117010 0.031537 -0.073834 -v 0.122041 0.041601 -0.065373 -v 0.133573 0.039419 -0.061948 -v 0.134639 0.034023 -0.065108 -v 0.133337 0.047689 -0.055933 -v 0.143142 0.045639 -0.052662 -v 0.117397 0.049961 -0.061080 -v 0.119991 0.050184 -0.059849 -v 0.105641 0.049212 -0.065964 -v 0.098552 0.045244 -0.071092 -v 0.068231 0.049035 -0.075709 -v 0.086630 0.046700 -0.073377 -v 0.081034 0.048746 -0.073290 -v 0.087315 0.048733 -0.071766 -v 0.121830 0.049866 -0.059351 -v 0.110362 0.043544 -0.068423 -v 0.086661 0.038155 -0.079000 -v 0.062366 0.047684 -0.077564 -v 0.042131 0.050268 -0.077966 -v 0.042131 0.047601 -0.079644 -v 0.062605 0.050724 -0.075284 -v 0.062329 0.049583 -0.076270 -v 0.063229 0.052015 -0.073924 -v 0.042131 0.056426 -0.070885 -v 0.064212 0.053309 -0.072209 -v 0.066299 0.055112 -0.068789 -v 0.067190 0.055658 -0.067261 -v 0.092624 -0.015726 -0.085798 -v 0.042131 -0.037616 -0.084270 -v 0.069711 -0.043081 -0.079230 -v 0.085985 -0.032103 -0.082234 -v 0.093951 -0.025973 -0.083409 -v 0.093725 -0.018470 -0.085209 -v 0.042131 -0.027189 -0.087789 -v 0.091013 -0.010541 -0.086649 -v 0.091672 -0.012914 -0.086302 -v 0.089811 -0.003152 -0.087276 -v 0.090032 -0.005275 -0.087161 -v 0.090466 -0.008060 -0.086935 -v 0.089931 0.004474 -0.087214 -v 0.042131 0.016442 -0.090158 -v 0.092498 0.027123 -0.083226 -v 0.096461 0.023988 -0.083724 -v 0.092622 0.015727 -0.085799 -v 0.042131 0.037616 -0.084270 -v 0.080060 0.036385 -0.081181 -v 0.042131 0.027189 -0.087789 -v 0.074254 0.040301 -0.080084 -v 0.079631 0.036695 -0.081105 -v 0.062567 0.046762 -0.078065 -v 0.064114 -0.053180 -0.072380 -v 0.042131 -0.056426 -0.070885 -v 0.065625 -0.054599 -0.069898 -v 0.066299 -0.055112 -0.068789 -v 0.062291 -0.049222 -0.076546 -v 0.042131 -0.050268 -0.077966 -v 0.118896 0.061265 0.127133 -v 0.098541 0.040599 0.138033 -v 0.103922 0.045963 0.135628 -v 0.042131 0.053503 0.138394 -v 0.042131 0.064485 0.133027 -v 0.109122 0.051199 0.133005 -v 0.075416 0.017882 0.145335 -v 0.042131 0.042079 0.142742 -v 0.087312 0.029525 0.142159 -v 0.063283 0.006023 0.147482 -v 0.042131 -0.006112 0.149355 -v 0.058936 -0.001770 0.148012 -v 0.042131 -0.018285 0.148246 -v 0.076984 -0.019414 0.145003 -v 0.082958 -0.025257 0.143463 -v 0.092998 -0.035117 0.140213 -v 0.042131 -0.042079 0.142742 -v 0.042131 -0.030307 0.146035 -v 0.087312 -0.029525 0.142159 -v 0.042131 -0.053503 0.138394 -v 0.042131 -0.064485 0.133027 -v 0.109122 -0.051199 0.133005 -v 0.074612 -0.047909 -0.075275 -v 0.081034 -0.048746 -0.073290 -v 0.086630 -0.046700 -0.073377 -v 0.093511 -0.048807 -0.070036 -v 0.119991 -0.050184 -0.059849 -v 0.110362 -0.043544 -0.068423 -v 0.111568 -0.049543 -0.063623 -v 0.127397 -0.050905 -0.056115 -v 0.138031 -0.052265 -0.049897 -v 0.133337 -0.047689 -0.055933 -v 0.142021 -0.034760 -0.061150 -v 0.098589 -0.036699 -0.076714 -v 0.095053 -0.030803 -0.081224 -v 0.062962 -0.047506 -0.077612 -v 0.074636 -0.043223 -0.078424 -v 0.133573 -0.039419 -0.061948 -v 0.121830 -0.049866 -0.059351 -v 0.124339 -0.032692 -0.070327 -v 0.081418 -0.039401 -0.079448 -v 0.086661 -0.038155 -0.079000 -v 0.098552 -0.045244 -0.071092 -v 0.110404 -0.034997 -0.074043 -v 0.122089 -0.033054 -0.070992 -v 0.122041 -0.041601 -0.065373 -v 0.144289 0.000000 -0.063703 -v 0.132257 0.000000 -0.069910 -v 0.106991 0.000000 -0.081342 -v 0.106991 0.013961 -0.081116 -v 0.098631 0.015662 -0.084390 -v 0.094749 0.004394 -0.086123 -v 0.096588 0.011234 -0.085309 -v 0.095504 -0.007890 -0.085790 -v 0.106984 -0.021434 -0.080791 -v 0.106991 -0.013961 -0.081116 -v 0.097456 -0.013294 -0.084920 -v 0.111652 -0.022336 -0.078808 -v 0.119723 -0.013783 -0.075621 -v 0.132257 -0.013591 -0.069690 -v 0.144121 -0.014859 -0.063526 -v 0.144276 -0.004234 -0.063688 -v 0.136449 0.025825 -0.067007 -v 0.119723 0.013783 -0.075621 -v 0.132257 0.013591 -0.069690 -v 0.129095 0.024999 -0.070715 -v 0.132248 0.025353 -0.069125 -v 0.104265 0.020909 -0.081946 -v 0.119723 0.000000 -0.075844 -v 0.144205 0.010548 -0.063614 -v 0.152965 0.069358 0.073579 -v 0.155324 0.066948 0.044099 -v 0.155392 0.066875 0.036814 -v 0.155258 0.067018 0.029534 -v 0.148680 0.073251 0.014394 -v 0.151770 0.070513 0.081431 -v 0.148061 0.073878 0.098652 -v 0.142158 0.078466 0.024563 -v 0.127580 0.087017 0.043568 -v 0.126475 0.087525 0.042954 -v 0.124926 0.088209 0.081275 -v 0.125412 0.087998 0.083491 -v 0.133041 0.084227 0.092909 -v 0.130668 0.085499 0.037756 -v 0.141160 -0.079164 0.099222 -v 0.143363 -0.077585 0.022866 -v 0.148706 -0.073281 0.014466 -v 0.153406 -0.068920 0.005806 -v 0.151770 -0.070513 0.081431 -v 0.150313 -0.071867 0.089395 -v 0.153870 -0.068453 0.066191 -v 0.154369 -0.067945 0.014869 -v 0.154918 -0.067375 0.022227 -v 0.155050 -0.067237 0.051409 -v 0.137969 -0.081303 0.029963 -v 0.133032 -0.084211 0.035368 -v 0.132404 -0.084581 0.036056 -v 0.129446 -0.086117 0.089400 -v 0.126225 -0.087638 0.085098 -v 0.127999 -0.086819 0.043165 -v 0.124926 -0.088209 0.081275 -v 0.124439 -0.088417 0.079060 -v 0.124959 -0.088195 0.046186 -v 0.065048 -0.007344 0.147283 -v 0.063283 -0.006023 0.147482 -v 0.064860 -0.007567 0.147289 -v 0.075416 -0.017882 0.145335 -v 0.077475 -0.018837 0.145030 -v 0.074510 -0.014422 0.145750 -v 0.071620 -0.012713 0.146272 -v 0.078447 -0.017673 0.144988 -v 0.084886 -0.022977 0.143486 -v 0.083608 -0.024505 0.143525 -v 0.088083 -0.028643 0.142255 -v 0.093936 -0.034068 0.140364 -v 0.094859 -0.032995 0.140407 -v 0.097375 -0.033229 0.139781 -v 0.091863 -0.028708 0.141530 -v 0.106489 -0.043163 0.136020 -v 0.100745 -0.038136 0.138320 -v 0.107709 -0.041695 0.135926 -v 0.102712 -0.037602 0.137886 -v 0.098477 -0.040536 0.138059 -v 0.098541 -0.040599 0.138033 -v 0.103922 -0.045963 0.135628 -v 0.105222 -0.044591 0.135920 -v 0.117485 -0.052846 0.130798 -v 0.114117 -0.056299 0.130173 -v 0.120066 -0.060181 0.127468 -v 0.120847 -0.059458 0.127691 -v 0.070946 -0.013515 0.146279 -v 0.077963 -0.018256 0.145025 -v 0.084252 -0.023744 0.143532 -v 0.088844 -0.027749 0.142276 -v 0.099655 -0.039386 0.138250 -v 0.110620 -0.049675 0.133380 -v 0.112074 -0.048069 0.133511 -v 0.115831 -0.054629 0.130637 -v 0.119049 -0.050982 0.130652 -v 0.136677 -0.063106 0.120128 -v 0.140192 -0.064759 0.117647 -v 0.138403 -0.073419 0.114493 -v 0.137422 -0.069505 0.117446 -v 0.138904 -0.067196 0.117723 -v 0.134016 -0.073524 0.115871 -v 0.136416 -0.075217 0.113631 -v 0.134645 -0.077009 0.112019 -v 0.134265 -0.076904 0.112206 -v 0.132172 -0.075140 0.114609 -v 0.135446 -0.065283 0.120212 -v 0.135780 -0.071631 0.116824 -v 0.134067 -0.067360 0.119997 -v 0.132049 -0.063208 0.122504 -v 0.130762 -0.065056 0.122355 -v 0.129122 -0.072417 0.117824 -v 0.133223 -0.061284 0.122406 -v 0.129382 -0.066798 0.121960 -v 0.127570 -0.062607 0.124515 -v 0.128774 -0.060986 0.124600 -v 0.122717 -0.057496 0.127879 -v 0.125780 -0.058702 0.126441 -v 0.124646 -0.060106 0.126416 -v 0.132565 -0.069295 0.119489 -v 0.130971 -0.071053 0.118697 -v 0.126295 -0.064150 0.124229 -v 0.123459 -0.061452 0.126228 -v 0.122231 -0.062728 0.125878 -v 0.127932 -0.068406 0.121326 -v 0.123849 -0.067181 0.122841 -v 0.124967 -0.065596 0.123744 -v 0.123602 -0.066925 0.123069 -v 0.120975 -0.063921 0.125369 -v 0.118896 -0.061265 0.127133 -v 0.136025 -0.080526 0.105386 -v 0.138664 -0.078421 0.108081 -v 0.137799 -0.080511 0.103337 -v 0.134127 -0.080179 0.107290 -v 0.132149 -0.079480 0.109006 -v 0.130378 -0.081197 0.106586 -v 0.132226 -0.081763 0.104976 -v 0.139409 -0.080136 0.101189 -v 0.140819 -0.079409 0.098992 -v 0.138614 -0.080887 0.097408 -v 0.137233 -0.081575 0.099396 -v 0.134549 -0.083228 0.097039 -v 0.135885 -0.082593 0.095313 -v 0.132092 -0.084630 0.094696 -v 0.129880 -0.083576 0.101944 -v 0.127731 -0.085107 0.098939 -v 0.125825 -0.086367 0.096010 -v 0.124381 -0.086207 0.097127 -v 0.123014 -0.087190 0.094481 -v 0.122544 -0.087511 0.093462 -v 0.122065 -0.087840 0.092423 -v 0.121152 -0.088441 0.090168 -v 0.120426 -0.088902 0.088047 -v 0.119856 -0.089254 0.086001 -v 0.119773 -0.089305 0.085652 -v 0.119425 -0.089515 0.083953 -v 0.134008 -0.082017 0.103217 -v 0.131523 -0.083723 0.100381 -v 0.123869 -0.087568 0.092551 -v 0.122013 -0.088629 0.088472 -v 0.120776 -0.089295 0.084518 -v 0.121919 -0.089111 0.084140 -v 0.120237 -0.089574 0.081340 -v 0.135688 -0.081954 0.101345 -v 0.129251 -0.085165 0.097575 -v 0.127239 -0.086351 0.094843 -v 0.125177 -0.087481 0.091619 -v 0.128607 -0.086158 0.093637 -v 0.123222 -0.088482 0.087820 -v 0.133088 -0.083606 0.098737 -v 0.130710 -0.085005 0.096155 -v 0.129914 -0.085789 0.092405 -v 0.126451 -0.087258 0.090663 -v 0.127680 -0.086898 0.089692 -v 0.124407 -0.088233 0.087156 -v 0.121902 -0.089239 0.081101 -v 0.123387 -0.088823 0.079060 -v 0.133376 -0.084046 0.093219 -v 0.133041 -0.084227 0.092909 -v 0.131148 -0.085250 0.091161 -v 0.128265 -0.086692 0.088026 -v 0.127129 -0.087226 0.086519 -v 0.125560 -0.087882 0.086485 -v 0.123608 -0.088669 0.083594 -v 0.125464 -0.087975 0.083608 -v 0.140186 -0.077306 0.108962 -v 0.142822 -0.076045 0.108258 -v 0.142822 -0.068380 0.114925 -v 0.142822 -0.077108 0.105899 -v 0.140454 -0.078566 0.105677 -v 0.142414 -0.077990 0.103552 -v 0.136517 -0.078005 0.110093 -v 0.142822 -0.070702 0.113783 -v 0.141746 -0.068636 0.115533 -v 0.140291 -0.071217 0.115103 -v 0.140186 -0.073742 0.113349 -v 0.140186 -0.075713 0.111310 -v 0.142822 -0.072794 0.112259 -v 0.137347 -0.076478 0.111931 -v 0.142822 -0.074593 0.110399 -v 0.071954 0.012311 0.146246 -v 0.071620 0.012713 0.146272 -v 0.062458 0.004434 0.147604 -v 0.068502 0.009451 0.146780 -v 0.064860 0.007567 0.147289 -v 0.070946 0.013515 0.146279 -v 0.074529 0.014438 0.145747 -v 0.077719 0.018546 0.145028 -v 0.076984 0.019414 0.145003 -v 0.083608 0.024505 0.143525 -v 0.089592 0.026844 0.142222 -v 0.084886 0.022977 0.143486 -v 0.084252 0.023744 0.143532 -v 0.078447 0.017673 0.144988 -v 0.088844 0.027749 0.142276 -v 0.091705 0.028578 0.141578 -v 0.082958 0.025257 0.143463 -v 0.088083 0.028643 0.142255 -v 0.087203 0.029418 0.142191 -v 0.093936 0.034068 0.140364 -v 0.094859 0.032995 0.140407 -v 0.097375 0.033229 0.139781 -v 0.092998 0.035117 0.140213 -v 0.099655 0.039386 0.138250 -v 0.098477 0.040536 0.138059 -v 0.100745 0.038136 0.138320 -v 0.106489 0.043163 0.136020 -v 0.112074 0.048069 0.133511 -v 0.113463 0.046406 0.133395 -v 0.119049 0.050982 0.130652 -v 0.117485 0.052846 0.130798 -v 0.124238 0.055237 0.127814 -v 0.120847 0.059458 0.127691 -v 0.109095 0.051172 0.133018 -v 0.105222 0.044591 0.135920 -v 0.110620 0.049675 0.133380 -v 0.115831 0.054629 0.130637 -v 0.114117 0.056299 0.130173 -v 0.118991 -0.089772 0.049380 -v 0.120110 -0.089639 0.079060 -v 0.122313 -0.089163 0.079060 -v 0.121219 -0.089436 0.079060 -v 0.146000 -0.064072 0.113658 -v 0.149026 -0.072043 0.103643 -v 0.147271 -0.063231 0.112854 -v 0.149182 -0.069005 0.107906 -v 0.148876 -0.067163 0.109757 -v 0.149464 -0.070450 0.105720 -v 0.148462 -0.065070 0.111270 -v 0.145003 -0.070084 0.112211 -v 0.144000 -0.065394 0.114922 -v 0.144497 -0.067910 0.113797 -v 0.145319 -0.072034 0.110304 -v 0.145383 -0.073738 0.108161 -v 0.145192 -0.075168 0.105833 -v 0.148698 -0.073071 0.101243 -v 0.144751 -0.076289 0.103359 -v 0.143954 -0.077164 0.100828 -v 0.138403 0.073419 0.114493 -v 0.136464 0.075383 0.113443 -v 0.134265 0.076904 0.112206 -v 0.137422 0.069505 0.117446 -v 0.143086 0.065980 0.115451 -v 0.140192 0.064759 0.117647 -v 0.138904 0.067196 0.117723 -v 0.132172 0.075140 0.114609 -v 0.134016 0.073524 0.115871 -v 0.129123 0.072417 0.117824 -v 0.136677 0.063106 0.120128 -v 0.123602 0.066925 0.123069 -v 0.120975 0.063921 0.125369 -v 0.135446 0.065283 0.120212 -v 0.132049 0.063208 0.122504 -v 0.128774 0.060986 0.124600 -v 0.129894 0.059307 0.124483 -v 0.133223 0.061284 0.122406 -v 0.122231 0.062728 0.125878 -v 0.120066 0.060181 0.127468 -v 0.130971 0.071053 0.118697 -v 0.135780 0.071631 0.116824 -v 0.132565 0.069295 0.119489 -v 0.127932 0.068406 0.121326 -v 0.124967 0.065596 0.123744 -v 0.126295 0.064150 0.124229 -v 0.123459 0.061452 0.126228 -v 0.127570 0.062607 0.124515 -v 0.130762 0.065056 0.122355 -v 0.129382 0.066798 0.121960 -v 0.134067 0.067360 0.119997 -v 0.122717 0.057496 0.127879 -v 0.125780 0.058702 0.126441 -v 0.124646 0.060106 0.126416 -v 0.121762 -0.089284 0.049380 -v 0.120851 -0.089511 0.049380 -v 0.119004 -0.089765 0.048549 -v 0.119098 -0.089709 0.046952 -v 0.120968 -0.089455 0.047212 -v 0.119527 -0.089454 0.043937 -v 0.119731 -0.089330 0.043030 -v 0.119930 -0.089209 0.042146 -v 0.120455 -0.088884 0.040300 -v 0.121095 -0.088478 0.038427 -v 0.121224 -0.088394 0.038080 -v 0.124379 -0.087727 0.037141 -v 0.122673 -0.089058 0.049380 -v 0.121308 -0.089293 0.045139 -v 0.122167 -0.088873 0.042093 -v 0.123299 -0.088299 0.039280 -v 0.124855 -0.088100 0.041396 -v 0.125647 -0.087026 0.034955 -v 0.124653 -0.086004 0.030817 -v 0.122207 -0.087744 0.035694 -v 0.128606 -0.086279 0.035782 -v 0.124439 -0.088417 0.049380 -v 0.123053 -0.088896 0.046297 -v 0.126577 -0.087476 0.042846 -v 0.126472 -0.087346 0.038653 -v 0.129160 -0.086254 0.039386 -v 0.131488 -0.085072 0.036950 -v 0.150192 -0.071777 0.098706 -v 0.151630 -0.069805 0.099812 -v 0.154114 -0.062907 0.101553 -v 0.148099 -0.073834 0.098771 -v 0.155332 -0.063719 0.091378 -v 0.155825 -0.061334 0.091802 -v 0.158380 -0.060597 0.067275 -v 0.156582 -0.062477 0.083104 -v 0.158069 -0.059138 0.075246 -v 0.157058 -0.060146 0.083466 -v 0.159424 -0.057730 0.059739 -v 0.158977 -0.059948 0.059564 -v 0.159473 -0.057678 0.058814 -v 0.151983 -0.070119 0.089915 -v 0.154722 -0.066828 0.082299 -v 0.155369 -0.066726 0.066473 -v 0.156033 -0.066018 0.058973 -v 0.157268 -0.064125 0.059178 -v 0.157706 -0.063637 0.051675 -v 0.153843 -0.065137 0.099776 -v 0.152881 -0.067564 0.099852 -v 0.154517 -0.066007 0.090916 -v 0.155799 -0.064717 0.082713 -v 0.156848 -0.063621 0.074627 -v 0.157605 -0.061421 0.074948 -v 0.157643 -0.062766 0.067020 -v 0.158255 -0.062091 0.059375 -v 0.159389 -0.059492 0.051924 -v 0.159959 -0.057156 0.047800 -v 0.159623 -0.059231 0.044333 -v 0.160062 -0.057044 0.044385 -v 0.148711 -0.073286 0.096861 -v 0.153371 -0.068771 0.081869 -v 0.152965 -0.069358 0.073579 -v 0.154508 -0.067623 0.073936 -v 0.154568 -0.067739 0.058765 -v 0.156491 -0.065520 0.051543 -v 0.155324 -0.066948 0.044099 -v 0.155392 -0.066875 0.036814 -v 0.156750 -0.065235 0.044160 -v 0.157954 -0.063358 0.044220 -v 0.158917 -0.061346 0.044278 -v 0.158677 -0.061618 0.051803 -v 0.156634 -0.064820 0.066751 -v 0.155810 -0.065700 0.074288 -v 0.153393 -0.068154 0.090425 -v 0.158977 -0.061277 0.036779 -v 0.150115 -0.064200 0.109804 -v 0.149840 -0.062931 0.110527 -v 0.153206 -0.062993 0.104806 -v 0.150115 -0.071172 0.102659 -v 0.150115 -0.070322 0.104533 -v 0.150115 -0.069161 0.106233 -v 0.150115 -0.067723 0.107706 -v 0.150115 -0.066053 0.108908 -v 0.151881 -0.064832 0.106859 -v 0.153420 -0.063533 0.104069 -v 0.151881 -0.066167 0.105898 -v 0.153223 -0.065024 0.103384 -v 0.151881 -0.067315 0.104721 -v 0.153232 -0.065940 0.102067 -v 0.151881 -0.068243 0.103363 -v 0.151881 -0.068923 0.101865 -v 0.151372 -0.063006 0.108516 -v 0.150115 -0.071686 0.100665 -v 0.140312 0.071232 0.115087 -v 0.142822 0.072759 0.112290 -v 0.142822 0.077078 0.105985 -v 0.142091 0.068721 0.115295 -v 0.136534 0.078081 0.109969 -v 0.140435 0.078575 0.105686 -v 0.142524 0.077912 0.103640 -v 0.142822 0.070676 0.113799 -v 0.140186 0.073703 0.113382 -v 0.140186 0.075671 0.111362 -v 0.134825 0.076761 0.112249 -v 0.140186 0.077264 0.109036 -v 0.142822 0.074554 0.110447 -v 0.142822 0.076008 0.108325 -v 0.137347 0.076433 0.111987 -v 0.131133 -0.085157 0.034773 -v 0.128361 -0.085760 0.032264 -v 0.129780 -0.085552 0.033505 -v 0.140024 -0.079341 0.020266 -v 0.144887 -0.075665 0.012159 -v 0.146807 -0.074700 0.013461 -v 0.148531 -0.073444 0.014789 -v 0.141768 -0.078588 0.021555 -v 0.141132 -0.079123 0.025802 -v 0.138344 -0.076664 0.008656 -v 0.136205 -0.080047 0.017835 -v 0.134193 -0.079990 0.016733 -v 0.129860 -0.082976 0.023831 -v 0.127073 -0.086198 0.032757 -v 0.140614 -0.076657 0.009733 -v 0.138160 -0.079830 0.019019 -v 0.131616 -0.083092 0.024955 -v 0.133328 -0.082980 0.026147 -v 0.126892 -0.085779 0.031066 -v 0.142809 -0.076322 0.010908 -v 0.147894 -0.072241 0.002257 -v 0.149502 -0.071648 0.003141 -v 0.134972 -0.082641 0.027390 -v 0.136526 -0.082079 0.028668 -v 0.157992 -0.061396 0.006331 -v 0.156933 -0.064068 0.006685 -v 0.159719 -0.057414 0.021487 -v 0.158651 -0.060681 0.014031 -v 0.159255 -0.057908 0.013785 -v 0.159681 -0.059165 0.036768 -v 0.159414 -0.059831 0.029228 -v 0.158105 -0.062775 0.021838 -v 0.157616 -0.063321 0.014299 -v 0.159123 -0.060159 0.021656 -v 0.158408 -0.062434 0.029326 -v 0.158017 -0.063287 0.036790 -v 0.157011 -0.064849 0.029429 -v 0.155365 -0.066629 0.006230 -v 0.153603 -0.068723 0.007440 -v 0.156177 -0.065763 0.014580 -v 0.156692 -0.065201 0.022030 -v 0.155258 -0.067018 0.029534 -v 0.156816 -0.065163 0.036802 -v 0.148035 -0.062713 0.112326 -v 0.150227 0.060693 0.110622 -v 0.153864 0.060759 0.104131 -v 0.148452 0.060626 0.112384 -v 0.155297 0.054133 0.102155 -v 0.156112 0.046222 0.102674 -v 0.156543 0.040826 0.102987 -v 0.156766 0.038024 0.103149 -v 0.156256 0.038105 0.105338 -v 0.157037 0.033524 0.103364 -v 0.152621 0.026997 0.113148 -v 0.157179 0.020906 0.105929 -v 0.156787 0.029626 0.105672 -v 0.157650 0.020862 0.103867 -v 0.157438 0.025799 0.103689 -v 0.154720 0.012013 0.111662 -v 0.157433 0.011971 0.106098 -v 0.157459 0.010655 0.106115 -v 0.157999 0.001007 0.104171 -v 0.157927 0.009437 0.104107 -v 0.157556 -0.000074 0.106179 -v 0.157944 -0.007438 0.104122 -v 0.157458 -0.010688 0.106114 -v 0.153364 0.013081 0.113262 -v 0.153599 -0.000074 0.113292 -v 0.154755 0.010691 0.111669 -v 0.154754 -0.010725 0.111669 -v 0.153449 -0.010727 0.113273 -v 0.152614 -0.026887 0.113146 -v 0.153705 -0.031795 0.111432 -v 0.157165 -0.021291 0.105919 -v 0.157165 -0.031630 0.103463 -v 0.157636 -0.021245 0.103855 -v 0.152270 -0.031789 0.113089 -v 0.155969 -0.041835 0.105166 -v 0.156672 -0.031699 0.105598 -v 0.156666 -0.039125 0.103077 -v 0.152800 -0.041935 0.111204 -v 0.151055 -0.055683 0.110786 -v 0.149990 -0.051601 0.112647 -v 0.154754 0.046378 0.107122 -v 0.155531 0.020964 0.109817 -v 0.155837 0.012005 0.109916 -v 0.156773 0.010672 0.108066 -v 0.155867 -0.010718 0.109925 -v 0.156772 -0.010706 0.108066 -v 0.155514 -0.021350 0.109811 -v 0.154929 -0.031781 0.109612 -v 0.155923 -0.031749 0.107658 -v 0.154184 -0.051661 0.106886 -v 0.152505 -0.055723 0.108829 -v 0.153680 -0.055717 0.106695 -v 0.155591 -0.051505 0.102332 -v 0.149357 -0.055599 0.112531 -v 0.151733 0.060770 0.108633 -v 0.152702 0.054297 0.108885 -v 0.151268 0.054265 0.110833 -v 0.152305 0.046404 0.111079 -v 0.153657 0.046408 0.109179 -v 0.154441 0.038197 0.109444 -v 0.153166 0.038207 0.111297 -v 0.153857 0.029719 0.111468 -v 0.155065 0.029705 0.109659 -v 0.154377 0.020976 0.111589 -v 0.155867 0.010684 0.109926 -v 0.155985 -0.000074 0.109962 -v 0.154887 -0.000074 0.111695 -v 0.154358 -0.021362 0.111585 -v 0.151637 -0.051661 0.110917 -v 0.154109 -0.041929 0.109330 -v 0.153044 -0.051681 0.108986 -v 0.152596 -0.063006 0.106353 -v 0.154559 -0.055666 0.104424 -v 0.155038 -0.051602 0.104655 -v 0.155171 -0.041896 0.107307 -v 0.156454 -0.021326 0.107914 -v 0.156878 -0.000074 0.108116 -v 0.156745 0.011991 0.108053 -v 0.156469 0.020941 0.107921 -v 0.156047 0.029674 0.107718 -v 0.155477 0.038163 0.107447 -v 0.155577 0.046316 0.104941 -v 0.154736 0.054230 0.104506 -v 0.153865 0.054285 0.106763 -v 0.152953 0.060792 0.106455 -v 0.154762 -0.058211 0.101875 -v 0.148905 0.067145 0.109735 -v 0.149265 0.070617 0.105831 -v 0.149730 0.062975 0.110639 -v 0.147271 0.063231 0.112854 -v 0.148442 0.065068 0.111289 -v 0.144792 0.076258 0.103341 -v 0.145205 0.075160 0.105824 -v 0.148878 0.072165 0.103726 -v 0.144986 0.070100 0.112217 -v 0.148680 0.073089 0.101247 -v 0.149389 0.068846 0.107771 -v 0.145388 0.073735 0.108158 -v 0.145310 0.072042 0.110306 -v 0.146000 0.064072 0.113658 -v 0.144459 0.067911 0.113829 -v 0.144020 0.077112 0.100850 -v 0.141160 0.079164 0.099222 -v 0.134454 0.077064 0.111988 -v 0.132149 0.079480 0.109006 -v 0.130315 0.081253 0.106495 -v 0.128185 0.083167 0.103401 -v 0.129880 0.083576 0.101944 -v 0.139409 0.080136 0.101189 -v 0.140819 0.079409 0.098992 -v 0.138614 0.080887 0.097408 -v 0.137233 0.081575 0.099396 -v 0.135885 0.082593 0.095313 -v 0.133376 0.084046 0.093219 -v 0.132092 0.084630 0.094696 -v 0.124381 0.086207 0.097127 -v 0.123014 0.087190 0.094481 -v 0.122065 0.087840 0.092423 -v 0.131148 0.085250 0.091161 -v 0.129446 0.086117 0.089400 -v 0.128265 0.086692 0.088026 -v 0.127129 0.087226 0.086519 -v 0.126225 0.087638 0.085098 -v 0.124172 0.088491 0.083433 -v 0.137799 0.080511 0.103337 -v 0.134549 0.083228 0.097039 -v 0.133088 0.083606 0.098737 -v 0.130710 0.085005 0.096155 -v 0.128607 0.086158 0.093637 -v 0.129914 0.085789 0.092405 -v 0.128255 0.086622 0.090452 -v 0.126000 0.087685 0.087268 -v 0.124439 0.088417 0.079060 -v 0.122313 0.089163 0.079060 -v 0.138664 0.078421 0.108081 -v 0.136025 0.080526 0.105386 -v 0.135688 0.081954 0.101345 -v 0.134008 0.082017 0.103217 -v 0.131523 0.083723 0.100381 -v 0.129251 0.085165 0.097575 -v 0.127239 0.086351 0.094843 -v 0.127005 0.086984 0.091495 -v 0.124407 0.088233 0.087156 -v 0.123222 0.088482 0.087820 -v 0.122751 0.088856 0.084880 -v 0.121902 0.089239 0.081101 -v 0.134127 0.080179 0.107290 -v 0.132226 0.081763 0.104976 -v 0.127731 0.085107 0.098939 -v 0.125825 0.086367 0.096010 -v 0.125707 0.087200 0.092520 -v 0.124646 0.087763 0.090717 -v 0.123955 0.087513 0.092841 -v 0.120776 0.089295 0.084518 -v 0.120426 0.088902 0.088047 -v 0.119955 0.089193 0.086357 -v 0.122013 0.088629 0.088472 -v 0.119425 0.089515 0.083953 -v 0.119039 0.089744 0.080684 -v 0.120237 0.089574 0.081340 -v 0.120110 0.089639 0.079060 -v 0.068231 -0.049035 -0.075709 -v 0.067523 -0.054509 -0.069722 -v 0.065254 -0.054316 -0.070509 -v 0.064796 -0.051933 -0.073807 -v 0.064212 -0.053309 -0.072209 -v 0.063370 -0.051170 -0.074788 -v 0.063229 -0.052015 -0.073924 -v 0.065747 -0.050528 -0.074984 -v 0.062884 -0.051380 -0.074626 -v 0.062605 -0.050724 -0.075284 -v 0.062477 -0.050311 -0.075661 -v 0.062329 -0.049583 -0.076270 -v 0.062283 -0.048474 -0.077072 -v 0.062567 -0.046762 -0.078065 -v 0.066138 -0.053619 -0.071465 -v 0.068049 -0.051159 -0.073995 -v 0.067811 -0.052998 -0.071984 -v 0.063219 -0.048675 -0.076807 -v 0.158441 -0.058757 0.004297 -v 0.157719 -0.061470 0.003342 -v 0.147981 -0.071582 0.000009 -v 0.144787 -0.072953 0.000721 -v 0.146017 -0.072719 0.001310 -v 0.147220 -0.072489 0.001886 -v 0.150542 -0.070719 0.001863 -v 0.150523 -0.071059 0.003788 -v 0.154927 -0.067101 0.004369 -v 0.152904 -0.069290 0.004081 -v 0.152887 -0.069355 0.005423 -v 0.151580 -0.070449 0.004458 -v 0.156629 -0.064408 0.004134 -v 0.152933 -0.068801 0.001835 -v 0.150115 0.071672 0.100750 -v 0.151881 0.068903 0.101921 -v 0.154114 0.062907 0.101553 -v 0.150115 0.064188 0.109809 -v 0.151372 0.062960 0.108531 -v 0.150115 0.066032 0.108921 -v 0.150115 0.067695 0.107730 -v 0.150115 0.070292 0.104586 -v 0.150062 0.071195 0.102812 -v 0.153233 0.065524 0.102745 -v 0.151881 0.067291 0.104751 -v 0.151881 0.066145 0.105917 -v 0.153305 0.063892 0.104142 -v 0.152607 0.062987 0.106334 -v 0.151796 0.069589 0.099794 -v 0.151881 0.068219 0.103406 -v 0.150115 0.069130 0.106270 -v 0.151899 0.064741 0.106881 -v 0.118991 0.089772 0.049380 -v 0.123387 0.088823 0.079060 -v 0.124439 0.088417 0.049380 -v 0.121219 0.089436 0.079060 -v 0.122673 0.089058 0.049380 -v 0.099206 -0.028009 -0.081639 -v 0.093802 -0.029027 -0.082378 -v 0.092498 -0.027123 -0.083226 -v 0.086650 -0.036191 -0.080185 -v 0.088151 -0.035269 -0.080397 -v 0.080537 -0.038089 -0.080358 -v 0.075719 -0.042656 -0.078586 -v 0.074995 -0.041511 -0.079395 -v 0.070903 -0.045174 -0.077866 -v 0.066848 -0.047076 -0.077308 -v 0.066372 -0.046147 -0.077972 -v 0.080060 -0.036385 -0.081181 -v 0.087087 -0.033739 -0.081429 -v 0.079631 -0.036695 -0.081105 -v 0.074254 -0.040301 -0.080084 -v 0.070313 -0.044153 -0.078594 -v 0.065885 -0.045175 -0.078564 -v 0.074406 -0.050969 -0.072907 -v 0.137871 -0.058958 -0.040113 -v 0.138487 -0.059053 -0.039694 -v 0.139927 -0.058040 -0.041571 -v 0.141225 -0.056680 -0.043361 -v 0.142277 -0.055018 -0.045015 -v 0.143670 -0.053140 -0.046174 -v 0.136934 -0.054198 -0.048555 -v 0.132790 -0.051546 -0.053092 -v 0.131762 -0.053508 -0.051702 -v 0.135724 -0.055865 -0.046975 -v 0.134426 -0.057231 -0.045190 -v 0.133067 -0.058269 -0.043236 -v 0.126441 -0.052895 -0.054681 -v 0.125378 -0.054615 -0.052994 -v 0.130625 -0.055203 -0.050067 -v 0.124232 -0.056027 -0.051090 -v 0.129401 -0.056593 -0.048221 -v 0.128118 -0.057650 -0.046203 -v 0.121854 -0.050345 -0.058965 -v 0.118919 -0.055534 -0.053796 -v 0.117794 -0.056625 -0.051659 -v 0.123026 -0.057102 -0.049011 -v 0.120972 -0.052360 -0.057489 -v 0.108085 -0.055952 -0.055992 -v 0.114647 -0.055199 -0.055805 -v 0.109060 -0.054838 -0.058221 -v 0.115650 -0.053753 -0.057802 -v 0.119986 -0.054102 -0.055753 -v 0.117397 -0.049961 -0.061080 -v 0.116573 -0.051994 -0.059573 -v 0.104972 -0.051284 -0.064386 -v 0.110821 -0.051597 -0.062079 -v 0.104212 -0.053078 -0.062533 -v 0.103379 -0.054555 -0.060445 -v 0.109978 -0.053375 -0.060265 -v 0.105641 -0.049212 -0.065964 -v 0.098355 -0.052862 -0.064604 -v 0.097609 -0.054350 -0.062477 -v 0.096810 -0.055485 -0.060160 -v 0.102491 -0.055680 -0.058170 -v 0.099621 -0.048966 -0.068101 -v 0.099031 -0.051054 -0.066493 -v 0.092410 -0.052727 -0.066480 -v 0.093001 -0.050907 -0.068400 -v 0.086381 -0.052672 -0.068158 -v 0.085814 -0.054177 -0.065964 -v 0.091753 -0.054224 -0.064318 -v 0.091045 -0.055365 -0.061963 -v 0.087315 -0.048733 -0.071766 -v 0.080269 -0.052699 -0.069636 -v 0.086885 -0.050844 -0.070107 -v 0.079794 -0.054208 -0.067416 -v 0.074079 -0.052807 -0.070913 -v 0.080686 -0.050864 -0.071609 -v 0.073696 -0.054318 -0.068669 -v 0.073268 -0.055468 -0.066229 -v 0.079271 -0.055356 -0.064999 -v 0.074672 -0.048846 -0.074606 -v 0.154692 -0.064216 -0.004301 -v 0.144946 -0.070440 -0.006035 -v 0.145182 -0.072528 -0.000241 -v 0.154947 -0.066623 0.002300 -v 0.156304 -0.061839 -0.003530 -v 0.156553 -0.063997 0.002468 -v 0.158198 -0.056522 -0.001718 -v 0.147751 -0.069472 -0.005832 -v 0.144393 -0.067357 -0.014643 -v 0.147201 -0.066359 -0.014509 -v 0.150356 -0.068086 -0.005468 -v 0.152691 -0.066317 -0.004953 -v 0.149809 -0.064941 -0.014209 -v 0.152144 -0.063142 -0.013752 -v 0.154142 -0.061011 -0.013149 -v 0.154941 -0.055401 -0.021337 -v 0.155147 -0.049860 -0.028691 -v 0.156921 -0.055994 -0.011580 -v 0.156802 -0.050006 -0.019624 -v 0.157263 -0.051823 -0.014595 -v 0.157625 -0.053247 -0.010656 -v 0.142671 -0.061504 -0.031158 -v 0.143600 -0.064286 -0.023280 -v 0.141461 -0.067907 -0.014607 -v 0.144203 -0.057351 -0.040002 -v 0.145475 -0.060454 -0.031155 -v 0.149013 -0.061814 -0.022979 -v 0.146407 -0.063260 -0.023215 -v 0.150583 -0.070219 0.000417 -v 0.148076 -0.058984 -0.030977 -v 0.150403 -0.057133 -0.030630 -v 0.151345 -0.059986 -0.022579 -v 0.153340 -0.057829 -0.022027 -v 0.152393 -0.054954 -0.030124 -v 0.157484 -0.059251 -0.002661 -v 0.155749 -0.058606 -0.012419 -v 0.156106 -0.052769 -0.020529 -v 0.153989 -0.052507 -0.029471 -v 0.152737 0.067707 0.100520 -v 0.153462 0.065882 0.101024 -v 0.150192 0.071777 0.098706 -v 0.154357 0.062689 0.100263 -v 0.155332 0.063719 0.091378 -v 0.155825 0.061334 0.091802 -v 0.156582 0.062477 0.083104 -v 0.157058 0.060146 0.083466 -v 0.157450 0.059588 0.080711 -v 0.158069 0.059138 0.075246 -v 0.158834 0.058351 0.067512 -v 0.158380 0.060597 0.067275 -v 0.158977 0.059948 0.059564 -v 0.159424 0.057730 0.059739 -v 0.159623 0.059231 0.044333 -v 0.160062 0.057044 0.044385 -v 0.151809 0.069664 0.098675 -v 0.152988 0.067478 0.099244 -v 0.156848 0.063621 0.074627 -v 0.157643 0.062766 0.067020 -v 0.156634 0.064820 0.066751 -v 0.158255 0.062091 0.059375 -v 0.158677 0.061618 0.051803 -v 0.157706 0.063637 0.051675 -v 0.158917 0.061346 0.044278 -v 0.159389 0.059492 0.051924 -v 0.157605 0.061421 0.074948 -v 0.155799 0.064717 0.082713 -v 0.154517 0.066007 0.090916 -v 0.153843 0.065137 0.099776 -v 0.157954 0.063358 0.044220 -v 0.153393 0.068154 0.090425 -v 0.151983 0.070119 0.089915 -v 0.153371 0.068771 0.081869 -v 0.154722 0.066828 0.082299 -v 0.155810 0.065700 0.074288 -v 0.155369 0.066726 0.066473 -v 0.157268 0.064125 0.059178 -v 0.156033 0.066018 0.058973 -v 0.156491 0.065520 0.051543 -v 0.156750 0.065235 0.044160 -v 0.148711 0.073286 0.096861 -v 0.150313 0.071867 0.089395 -v 0.154508 0.067623 0.073936 -v 0.153870 0.068454 0.066191 -v 0.154568 0.067739 0.058765 -v 0.155050 0.067237 0.051409 -v 0.126346 0.086625 0.033850 -v 0.122688 0.087416 0.034641 -v 0.123959 0.087952 0.037934 -v 0.121825 0.088000 0.036578 -v 0.120287 0.088989 0.040851 -v 0.119421 0.089517 0.044507 -v 0.119181 0.089660 0.046147 -v 0.121509 0.089196 0.044279 -v 0.120851 0.089511 0.049380 -v 0.124908 0.087439 0.036196 -v 0.123016 0.088444 0.039906 -v 0.124604 0.088214 0.041885 -v 0.120981 0.089449 0.047215 -v 0.121762 0.089284 0.049380 -v 0.131488 0.085072 0.036950 -v 0.128591 0.086292 0.035776 -v 0.126530 0.087315 0.038587 -v 0.128504 0.086576 0.040142 -v 0.123098 0.088877 0.046193 -v 0.124887 0.088225 0.046645 -v 0.096461 -0.023988 -0.083724 -v 0.098485 -0.025707 -0.082896 -v 0.098677 -0.022868 -0.083651 -v 0.099893 -0.021562 -0.083522 -v 0.143959 -0.053657 -0.045529 -v 0.153737 -0.045739 -0.038886 -v 0.150819 -0.049831 -0.042120 -v 0.141210 -0.057554 -0.041923 -v 0.141408 -0.058427 -0.039936 -v 0.146679 -0.055609 -0.040614 -v 0.152688 -0.049315 -0.038535 -v 0.153786 -0.046548 -0.038132 -v 0.150852 -0.051254 -0.040485 -v 0.148785 -0.051344 -0.043577 -v 0.146436 -0.052604 -0.044782 -v 0.148843 -0.052912 -0.041754 -v 0.146526 -0.054293 -0.042810 -v 0.151099 -0.051781 -0.039145 -v 0.149051 -0.053868 -0.039963 -v 0.143959 -0.055360 -0.043627 -v 0.143959 -0.056751 -0.041485 -v 0.153406 0.068920 0.005806 -v 0.156933 0.064068 0.006685 -v 0.157992 0.061396 0.006331 -v 0.155365 0.066629 0.006230 -v 0.154369 0.067945 0.014869 -v 0.154918 0.067375 0.022227 -v 0.156177 0.065763 0.014580 -v 0.157616 0.063321 0.014299 -v 0.156692 0.065201 0.022030 -v 0.158651 0.060681 0.014031 -v 0.159123 0.060159 0.021656 -v 0.159255 0.057908 0.013785 -v 0.159719 0.057414 0.021487 -v 0.156816 0.065163 0.036802 -v 0.158017 0.063287 0.036790 -v 0.159414 0.059832 0.029228 -v 0.158977 0.061278 0.036779 -v 0.159681 0.059165 0.036768 -v 0.157011 0.064849 0.029429 -v 0.158105 0.062775 0.021838 -v 0.158408 0.062434 0.029326 -v 0.143686 0.073983 0.003241 -v 0.151220 0.070759 0.004935 -v 0.152121 0.070178 0.008318 -v 0.150319 0.071631 0.006975 -v 0.147250 0.074529 0.016920 -v 0.140595 0.079416 0.023256 -v 0.135179 0.080769 0.019538 -v 0.146055 0.073555 0.004408 -v 0.141654 0.077241 0.013048 -v 0.137078 0.080576 0.020724 -v 0.132378 0.083546 0.027408 -v 0.133978 0.083234 0.028651 -v 0.130713 0.083640 0.026215 -v 0.129005 0.083513 0.025087 -v 0.139519 0.077545 0.011871 -v 0.141228 0.074040 0.002185 -v 0.127073 0.086198 0.032757 -v 0.129374 0.085884 0.034822 -v 0.148282 0.072765 0.005662 -v 0.145556 0.075719 0.015597 -v 0.143679 0.076628 0.014298 -v 0.138893 0.080123 0.021970 -v 0.141145 0.079141 0.025846 -v 0.136906 0.081971 0.031219 -v 0.135494 0.082706 0.029926 -v 0.130219 0.085559 0.035673 -v 0.133022 0.084193 0.035327 -v 0.074995 0.041511 -0.079395 -v 0.093951 0.025973 -0.083409 -v 0.093802 0.029027 -0.082378 -v 0.085985 0.032103 -0.082234 -v 0.080537 0.038089 -0.080358 -v 0.082783 0.038563 -0.079640 -v 0.087087 0.033739 -0.081429 -v 0.088151 0.035269 -0.080397 -v 0.075719 0.042656 -0.078586 -v 0.065885 0.045175 -0.078564 -v 0.069711 0.043081 -0.079230 -v 0.070903 0.045174 -0.077866 -v 0.070313 0.044153 -0.078594 -v 0.066372 0.046147 -0.077972 -v 0.066848 0.047076 -0.077308 -v 0.101495 -0.020327 -0.083079 -v 0.099323 -0.016862 -0.084075 -v 0.096751 -0.020261 -0.084465 -v 0.095048 -0.021312 -0.084495 -v 0.092603 -0.015676 -0.085809 -v 0.094260 -0.014901 -0.085694 -v 0.090067 -0.005603 -0.087143 -v 0.095401 -0.012862 -0.085617 -v 0.096481 -0.010954 -0.085357 -v 0.093954 -0.008369 -0.086278 -v 0.094666 -0.003714 -0.086159 -v 0.091415 -0.002996 -0.087067 -v 0.089699 -0.000692 -0.087334 -v 0.089694 -0.000307 -0.087337 -v 0.089744 0.002080 -0.087311 -v 0.091323 0.000751 -0.087111 -v 0.090105 0.005882 -0.087123 -v 0.090518 0.008327 -0.086908 -v 0.091073 0.010779 -0.086617 -v 0.091774 0.013245 -0.086248 -v 0.093923 0.014056 -0.085861 -v 0.094439 0.000736 -0.086259 -v 0.095564 0.008105 -0.085764 -v 0.094012 0.008597 -0.086252 -v 0.097477 0.013338 -0.084911 -v 0.093726 0.018472 -0.085209 -v 0.095015 0.021245 -0.084513 -v 0.095403 -0.017558 -0.085133 -v 0.097729 -0.017896 -0.084539 -v 0.092956 -0.011205 -0.086328 -v 0.091879 -0.006493 -0.086846 -v 0.093126 -0.003939 -0.086654 -v 0.091606 0.004991 -0.086975 -v 0.092899 0.000712 -0.086756 -v 0.093207 0.004659 -0.086617 -v 0.092422 0.009224 -0.086586 -v 0.095404 0.017560 -0.085133 -v 0.096718 0.020197 -0.084482 -v 0.095464 0.013035 -0.085589 -v 0.097713 0.017867 -0.084547 -v 0.099981 0.018008 -0.083776 -v 0.104265 -0.020909 -0.081946 -v 0.100903 -0.022987 -0.082966 -v 0.102924 -0.026175 -0.081335 -v 0.103666 -0.023582 -0.081833 -v 0.102057 -0.028627 -0.080465 -v 0.109536 -0.030175 -0.077235 -v 0.110385 -0.027689 -0.078142 -v 0.117010 -0.031537 -0.073834 -v 0.119035 -0.023584 -0.075502 -v 0.118522 -0.026347 -0.075338 -v 0.122078 -0.032336 -0.071409 -v 0.125291 -0.030167 -0.071241 -v 0.100125 -0.025560 -0.082489 -v 0.111096 -0.025055 -0.078670 -v 0.117842 -0.029019 -0.074778 -v 0.128643 -0.027817 -0.070514 -v 0.128004 -0.030540 -0.069909 -v 0.136449 -0.025825 -0.067007 -v 0.132248 -0.025353 -0.069125 -v 0.129095 -0.024999 -0.070715 -v 0.125941 -0.027457 -0.071834 -v 0.126409 -0.024654 -0.072025 -v 0.136041 -0.028681 -0.066776 -v 0.127195 -0.033098 -0.068916 -v 0.135433 -0.031437 -0.066138 -v 0.134584 -0.034017 -0.065137 -v 0.152487 -0.048061 -0.040473 -v 0.154204 -0.040135 -0.040254 -v 0.153904 -0.036928 -0.043012 -v 0.143423 -0.048898 -0.049899 -v 0.146025 -0.047887 -0.049012 -v 0.148378 -0.046623 -0.047809 -v 0.145755 -0.044898 -0.051560 -v 0.150145 -0.042186 -0.048839 -v 0.151818 -0.040549 -0.047083 -v 0.142319 -0.037564 -0.059038 -v 0.145214 -0.039412 -0.055995 -v 0.142620 -0.040399 -0.056903 -v 0.143128 -0.045618 -0.052684 -v 0.147560 -0.038191 -0.054757 -v 0.148106 -0.043649 -0.050345 -v 0.150418 -0.045139 -0.046320 -v 0.149597 -0.036771 -0.053220 -v 0.151272 -0.035188 -0.051427 -v 0.153354 -0.041672 -0.042652 -v 0.152091 -0.043474 -0.044586 -v 0.151915 -0.027887 -0.053664 -v 0.153082 -0.038780 -0.045123 -v 0.152539 -0.033484 -0.049423 -v 0.147981 0.071582 0.000009 -v 0.145182 0.072528 -0.000241 -v 0.147220 0.072489 0.001886 -v 0.152946 0.068786 0.001827 -v 0.150583 0.070219 0.000417 -v 0.152904 0.069290 0.004081 -v 0.154927 0.067101 0.004369 -v 0.149502 0.071648 0.003141 -v 0.157766 0.061666 0.004238 -v 0.156634 0.064405 0.004189 -v 0.154949 0.066650 0.002373 -v 0.150542 0.070719 0.001863 -v 0.068049 0.051159 -0.073995 -v 0.066599 0.053966 -0.070836 -v 0.065254 0.054316 -0.070509 -v 0.065666 0.050525 -0.074999 -v 0.065422 0.051834 -0.073795 -v 0.063306 0.050258 -0.075614 -v 0.067523 0.054509 -0.069722 -v 0.064911 0.052732 -0.072847 -v 0.062884 0.051380 -0.074626 -v 0.062279 0.048568 -0.077008 -v 0.097987 0.026030 -0.082853 -v 0.099910 0.021580 -0.083516 -v 0.101495 0.020327 -0.083079 -v 0.100904 0.022988 -0.082965 -v 0.099251 0.027999 -0.081632 -v 0.098681 0.022861 -0.083652 -v 0.099528 0.025482 -0.082711 -v 0.142800 -0.032148 -0.062217 -v 0.148924 -0.027713 -0.058792 -v 0.146872 -0.028108 -0.060796 -v 0.146307 -0.026508 -0.061474 -v 0.144519 -0.028434 -0.062450 -v 0.143742 -0.026468 -0.063149 -v 0.146890 -0.032042 -0.059389 -v 0.144611 -0.033790 -0.060228 -v 0.152770 -0.026364 -0.051319 -v 0.150631 -0.027786 -0.056373 -v 0.143378 -0.029360 -0.062889 -v 0.150631 -0.029681 -0.055641 -v 0.148924 -0.029223 -0.058389 -v 0.146872 -0.029880 -0.060322 -v 0.148948 -0.030884 -0.057664 -v 0.144519 -0.030424 -0.061918 -v 0.144519 -0.032325 -0.061126 -v 0.157719 0.061470 0.003342 -v 0.156304 0.061839 -0.003530 -v 0.156553 0.063997 0.002468 -v 0.142260 0.073030 -0.000326 -v 0.157484 0.059251 -0.002661 -v 0.157625 0.053247 -0.010656 -v 0.156921 0.055994 -0.011580 -v 0.157263 0.051823 -0.014595 -v 0.156106 0.052769 -0.020529 -v 0.155147 0.049860 -0.028691 -v 0.154142 0.061011 -0.013149 -v 0.154941 0.055401 -0.021337 -v 0.150356 0.068086 -0.005468 -v 0.149809 0.064941 -0.014209 -v 0.151345 0.059986 -0.022579 -v 0.150403 0.057133 -0.030630 -v 0.149013 0.061814 -0.022979 -v 0.148076 0.058984 -0.030977 -v 0.144393 0.067357 -0.014643 -v 0.146407 0.063260 -0.023215 -v 0.145475 0.060454 -0.031155 -v 0.155867 0.047176 -0.027550 -v 0.153989 0.052507 -0.029471 -v 0.155749 0.058606 -0.012419 -v 0.154692 0.064216 -0.004301 -v 0.152691 0.066318 -0.004953 -v 0.152144 0.063142 -0.013752 -v 0.153340 0.057829 -0.022027 -v 0.152393 0.054955 -0.030124 -v 0.147201 0.066359 -0.014509 -v 0.147751 0.069472 -0.005832 -v 0.144946 0.070440 -0.006035 -v 0.142018 0.070961 -0.006071 -v 0.141461 0.067907 -0.014607 -v 0.140669 0.064863 -0.023173 -v 0.143600 0.064286 -0.023280 -v 0.142671 0.061504 -0.031158 -v 0.139744 0.062105 -0.030987 -v 0.138487 0.059053 -0.039694 -v 0.143117 0.053063 -0.046532 -v 0.142275 0.055016 -0.045018 -v 0.138031 0.052265 -0.049897 -v 0.132790 0.051546 -0.053092 -v 0.127397 0.050905 -0.056115 -v 0.121854 0.050345 -0.058965 -v 0.110821 0.051597 -0.062079 -v 0.111568 0.049543 -0.063623 -v 0.099031 0.051054 -0.066493 -v 0.099621 0.048966 -0.068101 -v 0.093511 0.048807 -0.070036 -v 0.093001 0.050907 -0.068400 -v 0.086885 0.050844 -0.070107 -v 0.074672 0.048846 -0.074606 -v 0.136934 0.054198 -0.048555 -v 0.130625 0.055203 -0.050067 -v 0.131762 0.053508 -0.051702 -v 0.126441 0.052895 -0.054681 -v 0.120972 0.052360 -0.057489 -v 0.116573 0.051994 -0.059573 -v 0.115650 0.053753 -0.057802 -v 0.109978 0.053375 -0.060265 -v 0.104972 0.051284 -0.064386 -v 0.092410 0.052727 -0.066480 -v 0.086381 0.052672 -0.068158 -v 0.080686 0.050864 -0.071609 -v 0.074406 0.050969 -0.072907 -v 0.139627 0.057991 -0.041773 -v 0.135724 0.055865 -0.046975 -v 0.134426 0.057231 -0.045190 -v 0.129401 0.056593 -0.048221 -v 0.125378 0.054615 -0.052994 -v 0.119986 0.054102 -0.055753 -v 0.118919 0.055534 -0.053796 -v 0.114647 0.055199 -0.055805 -v 0.104212 0.053079 -0.062533 -v 0.098355 0.052862 -0.064604 -v 0.085814 0.054177 -0.065964 -v 0.080269 0.052699 -0.069636 -v 0.073696 0.054318 -0.068669 -v 0.074079 0.052807 -0.070913 -v 0.067340 0.052991 -0.072094 -v 0.137871 0.058958 -0.040113 -v 0.133067 0.058269 -0.043236 -v 0.128118 0.057650 -0.046203 -v 0.124232 0.056027 -0.051090 -v 0.109060 0.054838 -0.058221 -v 0.108085 0.055952 -0.055992 -v 0.103379 0.054555 -0.060445 -v 0.097609 0.054350 -0.062477 -v 0.091753 0.054224 -0.064318 -v 0.091045 0.055365 -0.061963 -v 0.085197 0.055322 -0.063577 -v 0.079794 0.054208 -0.067416 -v 0.073267 0.055468 -0.066229 -v 0.102057 0.028627 -0.080465 -v 0.102924 0.026175 -0.081335 -v 0.103666 0.023582 -0.081833 -v 0.106984 0.021434 -0.080791 -v 0.109536 0.030175 -0.077235 -v 0.110385 0.027689 -0.078142 -v 0.111652 0.022336 -0.078808 -v 0.111096 0.025055 -0.078670 -v 0.118522 0.026347 -0.075338 -v 0.124476 0.032714 -0.070262 -v 0.125291 0.030167 -0.071241 -v 0.119035 0.023584 -0.075502 -v 0.117842 0.029019 -0.074778 -v 0.127195 0.033098 -0.068916 -v 0.128004 0.030540 -0.069909 -v 0.125941 0.027457 -0.071834 -v 0.128643 0.027817 -0.070514 -v 0.126409 0.024654 -0.072025 -v 0.135433 0.031437 -0.066138 -v 0.142800 0.032148 -0.062217 -v 0.136041 0.028681 -0.066776 -v 0.133624 0.033897 -0.065628 -v 0.152036 0.021010 -0.054439 -v 0.150617 0.021053 -0.057154 -v 0.146513 0.021068 -0.061676 -v 0.152848 0.024276 -0.051398 -v 0.152974 0.020944 -0.051522 -v 0.153090 0.016159 -0.051644 -v 0.153228 0.010492 -0.051787 -v 0.152290 0.010527 -0.054703 -v 0.153249 0.007825 -0.051810 -v 0.152374 0.000000 -0.054793 -v 0.153311 0.000000 -0.051877 -v 0.143948 0.021039 -0.063351 -v 0.144135 0.013392 -0.063542 -v 0.146854 0.000000 -0.062028 -v 0.150872 0.010550 -0.057418 -v 0.150956 0.000000 -0.057508 -v 0.150942 -0.004235 -0.057493 -v 0.152361 -0.004225 -0.054778 -v 0.148758 0.021073 -0.059590 -v 0.149014 0.010561 -0.059854 -v 0.146770 0.010561 -0.061939 -v 0.146841 -0.004239 -0.062014 -v 0.153145 -0.014785 -0.051699 -v 0.152800 -0.025438 -0.051350 -v 0.151831 -0.026444 -0.054236 -v 0.153061 -0.017361 -0.051615 -v 0.152207 -0.014832 -0.054615 -v 0.150411 -0.026496 -0.056951 -v 0.150789 -0.014864 -0.057331 -v 0.149085 -0.004239 -0.059929 -v 0.149098 0.000000 -0.059943 -v 0.148552 -0.026517 -0.059388 -v 0.148930 -0.014880 -0.059766 -v 0.144142 -0.013392 -0.063549 -v 0.146686 -0.014878 -0.061851 -v 0.146432 0.052574 -0.044810 -v 0.143901 0.053595 -0.045640 -v 0.148782 0.051326 -0.043595 -v 0.150816 0.049829 -0.042126 -v 0.154524 0.043866 -0.036921 -v 0.153748 0.046389 -0.038460 -v 0.152488 0.048122 -0.040429 -v 0.148843 0.052912 -0.041754 -v 0.150852 0.051254 -0.040485 -v 0.151099 0.051781 -0.039145 -v 0.144203 0.057351 -0.040002 -v 0.141408 0.058427 -0.039936 -v 0.141210 0.057554 -0.041923 -v 0.143959 0.056751 -0.041485 -v 0.149117 0.053981 -0.039601 -v 0.146690 0.055634 -0.040543 -v 0.146526 0.054293 -0.042810 -v 0.141103 0.056661 -0.043443 -v 0.143959 0.055360 -0.043627 -v 0.152688 0.049315 -0.038535 -v 0.150631 0.029682 -0.055640 -v 0.148952 0.030909 -0.057644 -v 0.146899 0.032069 -0.059364 -v 0.144519 0.032325 -0.061126 -v 0.142021 0.034760 -0.061150 -v 0.146872 0.028108 -0.060796 -v 0.146311 0.026524 -0.061470 -v 0.150411 0.026496 -0.056951 -v 0.148552 0.026517 -0.059388 -v 0.151831 0.026444 -0.054236 -v 0.150634 0.028198 -0.056245 -v 0.146872 0.029880 -0.060322 -v 0.152770 0.026364 -0.051319 -v 0.148924 0.029223 -0.058389 -v 0.148924 0.027713 -0.058792 -v 0.144519 0.030424 -0.061918 -v 0.144519 0.028434 -0.062450 -v 0.143378 0.029360 -0.062889 -v 0.143742 0.026468 -0.063149 -v 0.154235 0.040498 -0.039930 -v 0.152091 0.043474 -0.044586 -v 0.153354 0.041672 -0.042652 -v 0.148106 0.043649 -0.050345 -v 0.150145 0.042186 -0.048839 -v 0.148378 0.046623 -0.047809 -v 0.142319 0.037564 -0.059038 -v 0.142620 0.040399 -0.056903 -v 0.151934 0.028069 -0.053528 -v 0.153082 0.038781 -0.045123 -v 0.152539 0.033484 -0.049423 -v 0.151818 0.040549 -0.047083 -v 0.151272 0.035188 -0.051427 -v 0.150418 0.045139 -0.046320 -v 0.149598 0.036771 -0.053220 -v 0.145755 0.044898 -0.051560 -v 0.146025 0.047887 -0.049012 -v 0.143423 0.048898 -0.049899 -v 0.147560 0.038191 -0.054757 -v 0.145214 0.039412 -0.055995 -v 0.144610 0.033795 -0.060226 -v 0.042131 0.006112 0.149355 -v 0.042131 0.018285 0.148246 -v 0.042131 0.030307 0.146035 -v 0.042131 0.095946 0.087266 -v 0.042131 0.096496 0.079060 -v 0.042131 0.083232 0.117211 -v 0.042131 0.052661 -0.075916 -v 0.042131 -0.094306 0.095326 -v 0.042131 -0.095946 0.087266 -v 0.042131 -0.091605 0.103095 -v 0.042131 -0.087892 0.110433 -v 0.042131 -0.047601 -0.079644 -v 0.042131 -0.096496 0.079060 -v 0.042131 0.092788 0.028348 -v 0.042131 0.054729 -0.073539 -v 0.042131 -0.096496 0.049380 -v 0.042131 0.005502 -0.091349 -v 0.042131 -0.052661 -0.075916 -v 0.042131 0.057718 -0.068011 -v 0.042131 -0.057718 -0.068011 -v 0.042131 -0.016442 -0.090158 -v 0.042131 -0.054729 -0.073539 -v -0.000000 0.080000 -0.011560 -v 0.000000 -0.070693 0.078463 -v 0.000000 -0.042918 0.141409 -v 0.000000 -0.085681 -0.001720 -v 0.000000 -0.057111 0.134678 -v 0.000000 0.070693 0.078463 -v 0.000000 0.084368 0.104895 -v 0.000000 -0.083280 0.000681 -v 0.000000 -0.073000 0.112593 -v 0.000000 -0.074251 0.085918 -v 0.000000 -0.071745 0.113859 -v -0.000000 0.085681 -0.001720 -v -0.000001 -0.084852 0.104448 -v 0.000000 -0.069554 -0.014173 -v 0.042131 -0.005502 -0.091349 -v -0.000000 -0.086414 0.101481 -v -0.000000 0.086367 0.101669 -v 0.000000 -0.086139 0.097688 -v 0.000000 0.086139 0.097688 -v -0.000000 -0.084723 -0.000415 -v 0.000000 -0.083742 0.094641 -v 0.000000 -0.078485 0.108081 -v 0.000000 -0.079859 0.091984 -v 0.000000 0.083280 0.094319 -v 0.000000 0.082464 0.106080 -v 0.000000 -0.080000 -0.011560 -v 0.000000 -0.070338 -0.012587 -v 0.000000 -0.070693 0.016537 -v -0.000000 0.071330 -0.011856 -v 0.000000 -0.071330 -0.011856 -v 0.000000 -0.073000 0.011264 -v 0.000000 0.086444 0.098772 -v -0.000000 0.069554 -0.014173 -v 0.000000 -0.069506 -0.014723 -v 0.000000 -0.069506 -0.024813 -v 0.000000 -0.065796 -0.045850 -v -0.000000 0.069506 -0.024813 -v -0.000000 0.069929 -0.013140 -v -0.000000 0.065796 -0.045850 -v 0.000000 -0.054832 -0.073419 -v -0.000000 0.056657 -0.070472 -v 0.000000 0.072191 0.082325 -v -0.000000 0.047606 -0.079654 -v -0.000000 0.054832 -0.073419 -v -0.000000 0.020848 -0.087803 -v 0.000000 -0.047606 -0.079654 -v 0.042000 -0.013279 0.146335 -v 0.042000 0.039306 0.141059 -v 0.042000 -0.039306 0.141059 -v 0.042000 -0.092214 0.096133 -v 0.042000 -0.084115 0.112526 -v 0.042000 -0.071454 0.125718 -v 0.042000 -0.082025 0.003154 -v 0.042000 0.078290 0.119607 -v 0.042000 0.071454 0.125718 -v 0.042000 0.046750 -0.078402 -v 0.000000 0.042276 -0.082287 -v 0.042000 -0.051796 0.136500 -v 0.042000 -0.095000 0.049381 -v 0.042000 0.000000 0.147000 -v 0.042000 -0.063767 0.130717 -v 0.042000 0.093383 0.035544 -v 0.042000 -0.091382 0.028860 -v 0.042000 0.016199 -0.088679 -v 0.042000 -0.094299 0.087205 -v 0.042000 0.088792 0.104640 -v 0.042000 0.056525 -0.067948 -v 0.042000 -0.026786 -0.086346 -v 0.042000 -0.055108 -0.070172 -v 0.042000 -0.046750 -0.078402 -v 0.042000 0.026786 -0.086346 -v 0.042000 -0.076172 -0.012929 -v 0.042000 -0.016199 -0.088679 -v 0.042000 0.076172 -0.012929 -v 0.000000 -0.095497 0.015677 -v -0.000000 0.073528 -0.014580 -v -0.000000 0.050161 0.146466 -v -0.000000 0.065874 0.137571 -v 0.000000 0.074134 0.128712 -v 0.000000 -0.084172 0.117948 -v -0.000000 0.054552 0.145175 -v 0.000000 -0.065864 0.137581 -v 0.000000 -0.058696 0.143232 -v 0.000000 -0.073528 -0.014580 -v 0.000000 -0.050161 0.146466 -v 0.000000 0.084172 0.117948 -v 0.000000 0.101645 0.099211 -v 0.000000 -0.105021 0.095590 -v 0.000000 -0.125825 0.041488 -v 0.000000 0.132802 0.042443 -v 0.000000 0.139721 0.042237 -v 0.000000 -0.114103 0.036921 -v 0.000000 0.125825 0.041488 -v -0.000001 -0.146474 0.041790 -v -0.000000 0.107495 0.032399 -v -0.000000 0.068727 -0.029300 -v 0.000000 -0.069792 0.074420 -v -0.000003 0.146413 0.041663 -v 0.000000 -0.114103 0.085851 -v 0.000000 0.102601 0.027505 -v 0.000000 0.104345 0.029249 -v 0.000000 -0.094454 0.106923 -v 0.000000 -0.102601 0.027505 -v 0.000000 0.017547 0.152896 -v -0.000000 -0.093338 -0.011415 -v -0.000000 0.092830 -0.011548 -v 0.000000 -0.092763 -0.004721 -v 0.000000 -0.054552 0.145175 -v -0.000000 0.082218 -0.011556 -v -0.000000 0.091171 -0.011556 -v -0.000000 0.079885 -0.011752 -v -0.000000 0.077617 -0.012334 -v -0.000000 0.092557 0.002198 -v 0.000000 -0.077617 -0.012334 -v 0.000000 -0.079885 -0.011752 -v 0.000000 -0.075478 -0.013285 -v 0.000000 0.071820 -0.016181 -v 0.000000 0.104345 0.096315 -v 0.000000 0.105021 0.095590 -v 0.000000 -0.071820 -0.016181 -v 0.000000 -0.000000 0.153877 -v 0.000000 0.069317 -0.020118 -v 0.000000 -0.069317 -0.020118 -v 0.000000 -0.068591 -0.022344 -v 0.000000 -0.068246 -0.024659 -v -0.000000 0.068591 -0.022344 -v -0.000000 0.068246 -0.024659 -v -0.000000 0.068291 -0.026994 -v -0.000000 -0.016441 -0.088639 -v 0.000000 -0.064382 -0.045322 -v -0.000000 0.117492 0.082217 -v -0.000000 -0.068291 -0.026994 -v -0.000000 -0.016199 -0.088679 -v -0.000000 0.057111 0.134678 -v 0.042000 -0.005421 -0.089853 -v -0.000000 0.005421 -0.089853 -v 0.000000 0.069470 -0.031343 -v 0.000000 0.069792 0.074420 -v 0.000000 0.069506 0.047500 -v 0.000000 -0.069506 0.024539 -v 0.000000 -0.055108 -0.070172 -v 0.000000 -0.053528 -0.072642 -v 0.000000 -0.072191 0.012675 -v -0.000000 0.070431 -0.012485 -v 0.000000 -0.072118 -0.011608 -v -0.000000 0.072669 -0.011560 -v -0.000434 0.084991 -0.000792 -v -0.000001 0.085423 0.096270 -v 0.000000 -0.086460 -0.006139 -v -0.000000 -0.084585 -0.009723 -v 0.000000 -0.083280 -0.010681 -v -0.000000 0.086560 -0.005000 -v -0.000000 0.086460 -0.003861 -v 0.000000 -0.086460 -0.003861 -v 0.000000 -0.086164 -0.007244 -v 0.000000 -0.085681 -0.008280 -v -0.000000 0.086164 -0.007244 -v 0.000000 -0.052791 0.137448 -v -0.000000 0.085681 -0.008280 -v 0.000000 -0.086559 0.099891 -v -0.000000 0.049377 -0.076761 -v -0.000000 0.046895 -0.078322 -v -0.000000 0.026786 -0.086346 -v 0.013286 0.072627 -0.046018 -v 0.009839 0.072859 -0.046885 -v 0.013387 0.072685 -0.046233 -v 0.009824 0.072960 -0.047261 -v 0.011803 0.072142 -0.044206 -v 0.017323 0.070502 -0.038089 -v 0.013812 0.071367 -0.041316 -v 0.014983 0.070945 -0.039740 -v 0.019190 0.073956 -0.050978 -v 0.028928 0.071682 -0.042490 -v 0.024821 0.073474 -0.049177 -v 0.022015 0.073898 -0.050764 -v 0.020567 0.074406 -0.052658 -v 0.014763 0.074326 -0.048496 -v 0.010658 0.074375 -0.048678 -v 0.009537 0.073427 -0.045141 -v 0.015609 0.071213 -0.036877 -v 0.012647 0.072076 -0.040100 -v 0.018995 0.075343 -0.052294 -v 0.011339 0.073040 -0.043695 -v 0.018534 0.070905 -0.035726 -v 0.021227 0.070864 -0.035574 -v 0.023448 0.071003 -0.036090 -v 0.026146 0.071394 -0.037553 -v 0.018998 0.074922 -0.050722 -v 0.012847 0.074388 -0.048727 -v 0.022238 0.074846 -0.050436 -v 0.027391 0.074473 -0.049043 -v 0.014134 0.073143 -0.047945 -v 0.013351 0.073654 -0.045986 -v 0.015863 0.073608 -0.049678 -v 0.017268 0.073818 -0.050462 -v 0.016652 0.074705 -0.049911 -v 0.025296 0.074323 -0.048484 -v 0.026573 0.072766 -0.046535 -v 0.026908 0.072030 -0.043788 -v 0.026941 0.073362 -0.044897 -v 0.026521 0.072534 -0.041806 -v 0.026132 0.071324 -0.041154 -v 0.025045 0.071900 -0.039442 -v 0.021928 0.071401 -0.037578 -v 0.023976 0.070697 -0.038815 -v 0.020950 0.070391 -0.037672 -v 0.018277 0.071396 -0.037559 -v 0.015743 0.071725 -0.038788 -v 0.014371 0.072103 -0.040199 -v 0.013591 0.072472 -0.041574 -v 0.013114 0.071971 -0.043573 -v 0.013043 0.073100 -0.043920 -v 0.009839 0.073825 -0.046627 -v 0.013323 0.073591 -0.045751 -v 0.009517 0.072406 -0.045195 -v 0.013073 0.070891 -0.039540 -v 0.013659 0.071680 -0.038620 -v 0.015071 0.070360 -0.037559 -v 0.016595 0.070117 -0.036650 -v 0.018753 0.069927 -0.035942 -v 0.021449 0.069904 -0.035856 -v 0.024897 0.070194 -0.036938 -v 0.027769 0.070929 -0.039679 -v 0.028282 0.072150 -0.040374 -v 0.029035 0.072501 -0.045547 -v 0.029113 0.072930 -0.043286 -v 0.028767 0.073745 -0.046326 -v 0.027759 0.073370 -0.048789 -v 0.025969 0.073877 -0.050684 -v 0.023639 0.074251 -0.052080 -v 0.024311 0.075149 -0.051567 -v 0.021210 0.075358 -0.052344 -v 0.018362 0.074340 -0.052411 -v 0.016468 0.075114 -0.051507 -v 0.015875 0.074076 -0.051426 -v 0.009937 0.073917 -0.046968 -v 0.010441 0.073091 -0.043887 -v 0.010424 0.072100 -0.044054 -v 0.011105 0.072556 -0.045753 -v 0.010734 0.073496 -0.045399 -v 0.011979 0.072311 -0.044839 -v 0.012076 0.073245 -0.044462 -v 0.011531 0.073058 -0.047629 -v 0.011466 0.074061 -0.047508 -v 0.011838 0.073496 -0.049262 -v 0.012820 0.073405 -0.048921 -v 0.012922 0.074086 -0.047601 -v 0.013044 0.073189 -0.048116 -v 0.009593 0.072825 -0.042894 -v 0.011926 0.071513 -0.041860 -v 0.009568 0.071860 -0.043158 -v 0.011684 0.073841 -0.050548 -v 0.011704 0.074808 -0.050292 -v 0.014517 0.073823 -0.050480 -v 0.014523 0.074789 -0.050221 -v 0.014031 0.081246 -0.046417 -v 0.014736 0.081644 -0.047921 -v 0.018623 0.082006 -0.049258 -v 0.016602 0.081967 -0.049110 -v 0.023612 0.081940 -0.049009 -v 0.025849 0.081303 -0.046632 -v 0.025695 0.081550 -0.047552 -v 0.027089 0.081028 -0.045615 -v 0.015601 0.078565 -0.036415 -v 0.017656 0.077736 -0.035537 -v 0.014692 0.078229 -0.037379 -v 0.013128 0.079383 -0.039466 -v 0.012657 0.080414 -0.043315 -v 0.012738 0.079926 -0.043680 -v 0.015823 0.081686 -0.048063 -v 0.019866 0.081474 -0.049492 -v 0.022615 0.081917 -0.048923 -v 0.027381 0.080344 -0.043053 -v 0.027071 0.079582 -0.040210 -v 0.026794 0.078826 -0.039604 -v 0.025969 0.078987 -0.037987 -v 0.024178 0.078547 -0.036343 -v 0.021377 0.078226 -0.035147 -v 0.018420 0.078254 -0.035253 -v 0.021140 0.077669 -0.035295 -v 0.027431 0.079602 -0.042499 -v 0.015225 0.081029 -0.047799 -v 0.023442 0.077879 -0.036062 -v 0.025499 0.078285 -0.037578 -v 0.025307 0.080894 -0.047323 -v 0.023302 0.081264 -0.048710 -v 0.017446 0.081349 -0.049025 -v 0.012885 0.079006 -0.040274 -v 0.013559 0.080512 -0.045761 -v 0.019574 0.079672 -0.049933 -v 0.014857 0.078880 -0.046909 -v 0.025829 0.077345 -0.040475 -v 0.019638 0.076128 -0.036479 -v 0.017225 0.076858 -0.037501 -v 0.026561 0.078175 -0.044276 -v 0.015425 0.076680 -0.038516 -v 0.013829 0.077811 -0.041879 -v 0.014532 0.079040 -0.044839 -v 0.016537 0.079757 -0.047385 -v 0.024132 0.079127 -0.047783 -v 0.025962 0.078454 -0.042437 -v 0.020680 0.077385 -0.036840 -v 0.025333 0.079407 -0.045153 -v 0.022915 0.079977 -0.047662 -v 0.023752 0.077095 -0.038091 -v 0.020141 0.079779 -0.048474 -v 0.018366 0.077775 -0.036625 -v 0.024516 0.080580 -0.046758 -v 0.018276 0.080935 -0.048266 -v 0.014366 0.078613 -0.040099 -v 0.013922 0.079475 -0.043363 -v 0.026316 0.080025 -0.044163 -v 0.016301 0.078181 -0.037431 -v 0.021761 0.081004 -0.048374 -v 0.015536 0.080507 -0.046725 -v 0.021560 0.081422 -0.049287 -v 0.024462 0.078249 -0.037864 -v 0.026725 0.080344 -0.045250 -v 0.026176 0.079018 -0.040849 -v 0.027383 0.077875 -0.043206 -v 0.025320 0.076438 -0.037873 -v 0.023284 0.076276 -0.037208 -v 0.020888 0.075873 -0.035741 -v 0.018420 0.075910 -0.035882 -v 0.017608 0.079576 -0.049559 -v 0.021574 0.079635 -0.049781 -v 0.015428 0.079278 -0.048443 -v 0.016542 0.076090 -0.036548 -v 0.014918 0.076393 -0.037681 -v 0.013666 0.076801 -0.039200 -v 0.012739 0.077406 -0.041490 -v 0.012636 0.076639 -0.043034 -v 0.012715 0.078055 -0.043880 -v 0.013493 0.078676 -0.046221 -v 0.015231 0.078125 -0.048585 -v 0.017441 0.078450 -0.049799 -v 0.022821 0.078432 -0.049729 -v 0.025305 0.078003 -0.048099 -v 0.023946 0.079391 -0.048870 -v 0.026422 0.078742 -0.046445 -v 0.027189 0.077365 -0.041375 -v 0.026722 0.076995 -0.039923 -v 0.023315 0.076072 -0.036477 -v 0.018595 0.074792 -0.036143 -v 0.022377 0.074260 -0.035939 -v 0.026161 0.077005 -0.037843 -v 0.027242 0.075308 -0.040193 -v 0.027567 0.076747 -0.045560 -v 0.021535 0.080318 -0.050205 -v 0.019533 0.080346 -0.050310 -v 0.012109 0.078185 -0.042243 -v 0.014980 0.074551 -0.037367 -v 0.017832 0.074242 -0.035893 -v 0.026746 0.078449 -0.043213 -v 0.012087 0.079031 -0.042487 -v 0.020091 0.080719 -0.048846 -v 0.026198 0.079610 -0.044755 -v 0.026673 0.078826 -0.041735 -v 0.025352 0.080556 -0.048182 -v 0.013927 0.079306 -0.044900 -v 0.025238 0.077572 -0.038788 -v 0.016625 0.079782 -0.048103 -v 0.013841 0.077673 -0.040224 -v 0.019688 0.077304 -0.036094 -v 0.023812 0.080079 -0.047732 -v 0.023031 0.076761 -0.036900 -v 0.017638 0.076640 -0.036467 -v 0.015566 0.077681 -0.037469 -v 0.018307 0.077110 -0.034976 -v 0.018833 0.078082 -0.034611 -v 0.021935 0.078120 -0.034754 -v 0.024323 0.078400 -0.035798 -v 0.025856 0.078736 -0.037054 -v 0.027306 0.079304 -0.039172 -v 0.026552 0.077959 -0.038145 -v 0.027963 0.080232 -0.042636 -v 0.019064 0.082158 -0.049821 -v 0.021650 0.082120 -0.049681 -v 0.013168 0.081165 -0.046113 -v 0.012140 0.080417 -0.043327 -v 0.014673 0.078599 -0.036543 -v 0.013988 0.077689 -0.037490 -v 0.016386 0.078292 -0.035397 -v 0.027667 0.078807 -0.044564 -v 0.027944 0.078131 -0.042044 -v 0.023990 0.076524 -0.036046 -v 0.012194 0.078653 -0.043995 -v 0.012388 0.076784 -0.045338 -v 0.015132 0.079931 -0.048768 -v 0.017669 0.080263 -0.049998 -v 0.024102 0.078937 -0.049532 -v 0.013672 0.079528 -0.047256 -v 0.027283 0.077504 -0.039704 -v 0.012492 0.077647 -0.040235 -v 0.018646 0.076283 -0.035147 -v 0.027038 0.079247 -0.046209 -v 0.024925 0.079901 -0.048660 -v 0.013940 0.076975 -0.037750 -v 0.021289 0.076274 -0.035113 -v 0.024398 0.077319 -0.036106 -v 0.020502 0.081083 -0.050153 -v 0.017479 0.080979 -0.049766 -v 0.015338 0.080684 -0.048664 -v 0.012668 0.079855 -0.045565 -v 0.012229 0.079711 -0.040718 -v 0.027814 0.079423 -0.043958 -v 0.021515 0.077007 -0.034945 -v 0.013028 0.079119 -0.038530 -v 0.022896 0.080939 -0.049616 -v 0.024151 0.077615 -0.037225 -v 0.015875 0.077282 -0.035968 -v 0.027629 0.078483 -0.040453 -v 0.020600 0.074763 -0.036037 -v 0.027309 0.076429 -0.042248 -v 0.027283 0.076948 -0.044192 -v 0.026716 0.077447 -0.046047 -v 0.023065 0.074923 -0.036629 -v 0.026626 0.075816 -0.039959 -v 0.025089 0.075304 -0.037981 -v 0.023157 0.078176 -0.048816 -v 0.019866 0.078577 -0.050268 -v 0.012933 0.076125 -0.041121 -v 0.013422 0.076590 -0.042940 -v 0.013760 0.075652 -0.039348 -v 0.013123 0.077400 -0.045849 -v 0.015047 0.075261 -0.037860 -v 0.016700 0.074959 -0.036767 -v 0.014806 0.076015 -0.047361 -v 0.020511 0.076631 -0.050124 -v 0.023003 0.076578 -0.050138 -v 0.019435 0.072957 -0.036519 -v 0.017447 0.073520 -0.038022 -v 0.013374 0.074709 -0.042899 -v 0.026133 0.075570 -0.046131 -v 0.025962 0.074105 -0.040624 -v 0.015267 0.074430 -0.040037 -v 0.014130 0.075394 -0.042441 -v 0.024344 0.076595 -0.047385 -v 0.014259 0.076554 -0.044955 -v 0.025872 0.075962 -0.044521 -v 0.016225 0.077215 -0.047811 -v 0.022648 0.073442 -0.037998 -v 0.020235 0.077994 -0.049239 -v 0.019900 0.073755 -0.037694 -v 0.018468 0.076828 -0.049305 -v 0.018105 0.074726 -0.037640 -v 0.021693 0.077114 -0.048925 -v 0.022429 0.074624 -0.037890 -v 0.014768 0.075529 -0.039480 -v 0.025661 0.077311 -0.046108 -v 0.026239 0.076350 -0.042365 -v 0.025060 0.075112 -0.040343 -v 0.023682 0.075209 -0.037762 -v 0.018942 0.074885 -0.036514 -v 0.015990 0.078117 -0.048597 -v 0.027007 0.075486 -0.045885 -v 0.025483 0.076160 -0.048397 -v 0.025322 0.073543 -0.038651 -v 0.023318 0.073174 -0.037255 -v 0.021420 0.073004 -0.036626 -v 0.012993 0.074265 -0.041329 -v 0.016174 0.076498 -0.049669 -v 0.018124 0.076726 -0.050514 -v 0.012633 0.075037 -0.044214 -v 0.020586 0.076775 -0.050699 -v 0.013277 0.075653 -0.046512 -v 0.017459 0.073085 -0.036929 -v 0.014037 0.072634 -0.039682 -v 0.014827 0.073493 -0.038451 -v 0.014675 0.076202 -0.048562 -v 0.014228 0.074949 -0.048324 -v 0.020410 0.075668 -0.051008 -v 0.026501 0.074676 -0.047304 -v 0.027367 0.074713 -0.043000 -v 0.026723 0.074098 -0.040702 -v 0.021141 0.071876 -0.036848 -v 0.018597 0.071894 -0.036920 -v 0.017683 0.072617 -0.036380 -v 0.021099 0.071288 -0.036422 -v 0.027842 0.073846 -0.042772 -v 0.027843 0.073605 -0.045428 -v 0.022576 0.077336 -0.050723 -v 0.016567 0.075098 -0.050936 -v 0.014761 0.076946 -0.049214 -v 0.012229 0.074998 -0.041945 -v 0.012739 0.072405 -0.040949 -v 0.013894 0.071936 -0.039196 -v 0.014180 0.075312 -0.040240 -v 0.016831 0.077646 -0.048943 -v 0.021417 0.074433 -0.036947 -v 0.016878 0.074581 -0.037490 -v 0.013349 0.076553 -0.044865 -v 0.013303 0.075584 -0.044109 -v 0.026310 0.076226 -0.044874 -v 0.015832 0.076828 -0.048763 -v 0.024832 0.076868 -0.047670 -v 0.024677 0.073758 -0.037312 -v 0.019711 0.073360 -0.035828 -v 0.015146 0.074153 -0.038761 -v 0.021061 0.077135 -0.049895 -v 0.022133 0.073749 -0.037200 -v 0.026184 0.075540 -0.041122 -v 0.022024 0.077822 -0.049601 -v 0.025287 0.076951 -0.049229 -v 0.026160 0.074008 -0.038645 -v 0.022239 0.073428 -0.036080 -v 0.015602 0.073700 -0.037095 -v 0.012961 0.074463 -0.039944 -v 0.012129 0.075735 -0.044696 -v 0.018385 0.077415 -0.050961 -v 0.020230 0.076098 -0.051464 -v 0.027889 0.075531 -0.043937 -v 0.013968 0.073987 -0.038556 -v 0.027439 0.074702 -0.040833 -v 0.013418 0.074393 -0.048309 -v 0.027301 0.076211 -0.046521 -v 0.026508 0.074971 -0.038936 -v 0.026306 0.078345 -0.047636 -v 0.016424 0.077976 -0.050149 -v 0.013078 0.078186 -0.046688 -v 0.012086 0.076123 -0.043232 -v 0.013237 0.075063 -0.039277 -v 0.012376 0.075578 -0.041199 -v 0.014173 0.077526 -0.048464 -v 0.016308 0.075720 -0.036104 -v 0.025637 0.077568 -0.048629 -v 0.020044 0.074084 -0.035626 -v 0.025004 0.074541 -0.037325 -v 0.019650 0.078182 -0.050919 -v 0.022175 0.078103 -0.050622 -v 0.027931 0.075916 -0.042458 -v 0.027013 0.073166 -0.041641 -v 0.023951 0.072149 -0.037868 -v 0.025774 0.072581 -0.039487 -v 0.012791 0.073355 -0.042317 -v 0.024952 0.075176 -0.049171 -v 0.022823 0.075535 -0.050504 -v 0.018411 0.075628 -0.050851 -v 0.016046 0.075383 -0.049939 -v 0.012691 0.074001 -0.044784 -v 0.016272 0.072114 -0.037737 -v 0.013896 0.070889 -0.040358 -v 0.024900 0.073114 -0.048535 -v 0.018526 0.070354 -0.038154 -v 0.022720 0.070443 -0.038582 -v 0.020473 0.073745 -0.050623 -v 0.018607 0.071210 -0.038560 -v 0.024770 0.071327 -0.040429 -v 0.014182 0.072808 -0.045957 -v 0.021444 0.071319 -0.038598 -v 0.015393 0.073758 -0.047818 -v 0.026152 0.072418 -0.044426 -v 0.023496 0.072319 -0.038955 -v 0.023932 0.073815 -0.048516 -v 0.015090 0.071425 -0.040732 -v 0.014273 0.072284 -0.042573 -v 0.018576 0.074505 -0.049832 -v 0.025878 0.073800 -0.045777 -v 0.025723 0.072835 -0.041692 -v 0.018788 0.075368 -0.050096 -v 0.014681 0.072727 -0.040181 -v 0.013761 0.073376 -0.043373 -v 0.013221 0.074529 -0.046672 -v 0.014351 0.074588 -0.047133 -v 0.022977 0.075088 -0.049284 -v 0.017868 0.072146 -0.038006 -v 0.027359 0.073952 -0.044578 -v 0.021123 0.072049 -0.037684 -v 0.023740 0.070328 -0.038222 -v 0.023459 0.073647 -0.050666 -v 0.015430 0.073483 -0.049997 -v 0.016056 0.073369 -0.049472 -v 0.017609 0.073779 -0.051113 -v 0.019584 0.073882 -0.051486 -v 0.021584 0.073839 -0.051331 -v 0.018355 0.070100 -0.037382 -v 0.013750 0.072986 -0.048147 -v 0.012738 0.071617 -0.043040 -v 0.015682 0.070432 -0.038619 -v 0.012789 0.072387 -0.045960 -v 0.013894 0.071955 -0.048705 -v 0.015693 0.072416 -0.050452 -v 0.020412 0.072758 -0.051789 -v 0.024184 0.072438 -0.050535 -v 0.025698 0.072076 -0.049192 -v 0.025483 0.073262 -0.049174 -v 0.026787 0.072714 -0.047147 -v 0.026723 0.071648 -0.047586 -v 0.027377 0.071030 -0.045188 -v 0.027502 0.071931 -0.044240 -v 0.027365 0.071957 -0.044305 -v 0.025661 0.070757 -0.039832 -v 0.026704 0.071164 -0.041454 -v 0.025761 0.069681 -0.040247 -v 0.021419 0.070106 -0.037403 -v 0.019948 0.068019 -0.037248 -v 0.018245 0.070513 -0.036795 -v 0.025122 0.070858 -0.038405 -v 0.027440 0.071805 -0.041616 -v 0.027646 0.072993 -0.046425 -v 0.019652 0.072467 -0.052450 -v 0.019796 0.074556 -0.051882 -v 0.017256 0.072007 -0.052055 -v 0.015443 0.074094 -0.050545 -v 0.012248 0.070525 -0.046440 -v 0.026184 0.071865 -0.041810 -v 0.026145 0.072431 -0.041059 -v 0.022467 0.071599 -0.037951 -v 0.013363 0.073565 -0.045292 -v 0.024147 0.074615 -0.049228 -v 0.020193 0.074975 -0.050562 -v 0.015597 0.074539 -0.048951 -v 0.017124 0.071559 -0.037802 -v 0.014370 0.072016 -0.040873 -v 0.026387 0.073222 -0.045348 -v 0.023154 0.070967 -0.038474 -v 0.018099 0.071121 -0.038071 -v 0.013476 0.072200 -0.043059 -v 0.017474 0.074163 -0.050404 -v 0.013843 0.073185 -0.046744 -v 0.023334 0.074088 -0.050119 -v 0.019008 0.075265 -0.051622 -v 0.012109 0.073077 -0.043448 -v 0.025947 0.073865 -0.049308 -v 0.020542 0.070462 -0.036602 -v 0.015875 0.070760 -0.037717 -v 0.012124 0.072299 -0.043458 -v 0.012243 0.072945 -0.045873 -v 0.012950 0.071135 -0.048343 -v 0.017669 0.074467 -0.051551 -v 0.023684 0.074330 -0.051042 -v 0.013812 0.073783 -0.048995 -v 0.012387 0.069573 -0.042796 -v 0.022453 0.069475 -0.037252 -v 0.012988 0.070783 -0.040883 -v 0.026582 0.071376 -0.040012 -v 0.014216 0.071107 -0.039015 -v 0.024485 0.074919 -0.050334 -v 0.012285 0.073714 -0.045830 -v 0.021847 0.075224 -0.051473 -v 0.023815 0.071430 -0.037309 -v 0.025911 0.074599 -0.049135 -v 0.015444 0.071556 -0.037780 -v 0.014977 0.074815 -0.049943 -v 0.018867 0.071208 -0.036484 -v 0.026040 0.071898 -0.039057 -v 0.027375 0.072485 -0.041248 -v 0.024133 0.068321 -0.038365 -v 0.025823 0.068664 -0.039703 -v 0.027243 0.069213 -0.041737 -v 0.027574 0.070713 -0.047144 -v 0.026156 0.071419 -0.049707 -v 0.014334 0.068672 -0.039505 -v 0.012104 0.070019 -0.044583 -v 0.027924 0.071137 -0.044059 -v 0.024144 0.071868 -0.051391 -v 0.014632 0.071566 -0.050582 -v 0.022077 0.072091 -0.052259 -v 0.027004 0.070256 -0.042393 -v 0.023905 0.069253 -0.038612 -v 0.019586 0.068967 -0.037576 -v 0.022381 0.072674 -0.051412 -v 0.021586 0.068992 -0.037735 -v 0.017940 0.072717 -0.051538 -v 0.016916 0.068200 -0.037807 -v 0.017618 0.069066 -0.037948 -v 0.015023 0.069445 -0.039346 -v 0.013277 0.070090 -0.041774 -v 0.012715 0.070587 -0.043628 -v 0.012738 0.071227 -0.046024 -v 0.014134 -0.073143 -0.047945 -v 0.011979 -0.072311 -0.044839 -v 0.013387 -0.072685 -0.046233 -v 0.013812 -0.071367 -0.041316 -v 0.009824 -0.072960 -0.047261 -v 0.014517 -0.073823 -0.050480 -v 0.009568 -0.071860 -0.043158 -v 0.010424 -0.072100 -0.044054 -v 0.020567 -0.074406 -0.052658 -v 0.017323 -0.070502 -0.038089 -v 0.014983 -0.070945 -0.039740 -v 0.016595 -0.070117 -0.036650 -v 0.023976 -0.070697 -0.038815 -v 0.018753 -0.069927 -0.035942 -v 0.022377 -0.069931 -0.035955 -v 0.027968 -0.071027 -0.040048 -v 0.026132 -0.071324 -0.041154 -v 0.024821 -0.073474 -0.049177 -v 0.013043 -0.073100 -0.043920 -v 0.013323 -0.073591 -0.045751 -v 0.009839 -0.073825 -0.046627 -v 0.018995 -0.075343 -0.052294 -v 0.010658 -0.074375 -0.048678 -v 0.009937 -0.073917 -0.046968 -v 0.013351 -0.073654 -0.045986 -v 0.011339 -0.073040 -0.043695 -v 0.011704 -0.074808 -0.050292 -v 0.015609 -0.071213 -0.036877 -v 0.025045 -0.071900 -0.039442 -v 0.018534 -0.070905 -0.035726 -v 0.026941 -0.073362 -0.044897 -v 0.026521 -0.072534 -0.041806 -v 0.028767 -0.073745 -0.046326 -v 0.012847 -0.074388 -0.048727 -v 0.021210 -0.075358 -0.052344 -v 0.014763 -0.074326 -0.048496 -v 0.015863 -0.073608 -0.049678 -v 0.017267 -0.073818 -0.050461 -v 0.016653 -0.074705 -0.049912 -v 0.019190 -0.073956 -0.050978 -v 0.018999 -0.074922 -0.050722 -v 0.022238 -0.074846 -0.050436 -v 0.022015 -0.073898 -0.050764 -v 0.025296 -0.074323 -0.048484 -v 0.026573 -0.072766 -0.046535 -v 0.026908 -0.072030 -0.043788 -v 0.021928 -0.071401 -0.037578 -v 0.020950 -0.070391 -0.037672 -v 0.018277 -0.071396 -0.037559 -v 0.015743 -0.071725 -0.038788 -v 0.014371 -0.072103 -0.040199 -v 0.013591 -0.072472 -0.041574 -v 0.013114 -0.071971 -0.043573 -v 0.013286 -0.072627 -0.046018 -v 0.009839 -0.072859 -0.046885 -v 0.009537 -0.073427 -0.045141 -v 0.009517 -0.072406 -0.045195 -v 0.013073 -0.070891 -0.039540 -v 0.012647 -0.072076 -0.040100 -v 0.013659 -0.071680 -0.038620 -v 0.015071 -0.070360 -0.037559 -v 0.021227 -0.070864 -0.035574 -v 0.024661 -0.071125 -0.036548 -v 0.025976 -0.070402 -0.037716 -v 0.027626 -0.071838 -0.039211 -v 0.028928 -0.071682 -0.042490 -v 0.029099 -0.072811 -0.042841 -v 0.029035 -0.072501 -0.045547 -v 0.027759 -0.073370 -0.048789 -v 0.027391 -0.074473 -0.049043 -v 0.025969 -0.073877 -0.050684 -v 0.023639 -0.074251 -0.052080 -v 0.024311 -0.075149 -0.051567 -v 0.018362 -0.074340 -0.052411 -v 0.016468 -0.075114 -0.051507 -v 0.015875 -0.074076 -0.051426 -v 0.010441 -0.073091 -0.043887 -v 0.010734 -0.073496 -0.045399 -v 0.011105 -0.072556 -0.045753 -v 0.012076 -0.073245 -0.044462 -v 0.011803 -0.072142 -0.044206 -v 0.011466 -0.074061 -0.047508 -v 0.011838 -0.073496 -0.049262 -v 0.012820 -0.073405 -0.048921 -v 0.012922 -0.074086 -0.047601 -v 0.013044 -0.073189 -0.048116 -v 0.011531 -0.073058 -0.047629 -v 0.009593 -0.072825 -0.042894 -v 0.011926 -0.071513 -0.041860 -v 0.011684 -0.073841 -0.050548 -v 0.014523 -0.074789 -0.050221 -v 0.014031 -0.081246 -0.046417 -v 0.014144 -0.081496 -0.047351 -v 0.025695 -0.081550 -0.047552 -v 0.027071 -0.079582 -0.040210 -v 0.021935 -0.078120 -0.034754 -v 0.021376 -0.078226 -0.035147 -v 0.018420 -0.078254 -0.035253 -v 0.015601 -0.078565 -0.036415 -v 0.016269 -0.077910 -0.036185 -v 0.013128 -0.079383 -0.039466 -v 0.012657 -0.080414 -0.043315 -v 0.013559 -0.080512 -0.045761 -v 0.015820 -0.081686 -0.048060 -v 0.018622 -0.082006 -0.049258 -v 0.022615 -0.081917 -0.048923 -v 0.025849 -0.081303 -0.046632 -v 0.027431 -0.079602 -0.042499 -v 0.027381 -0.080344 -0.043053 -v 0.025969 -0.078987 -0.037987 -v 0.024175 -0.078546 -0.036341 -v 0.021660 -0.077687 -0.035353 -v 0.026794 -0.078826 -0.039604 -v 0.026725 -0.080344 -0.045250 -v 0.025185 -0.078183 -0.037207 -v 0.025307 -0.080894 -0.047323 -v 0.022818 -0.081330 -0.048954 -v 0.019866 -0.081474 -0.049492 -v 0.015975 -0.081200 -0.048442 -v 0.012717 -0.079277 -0.041286 -v 0.013729 -0.078529 -0.038497 -v 0.018593 -0.077691 -0.035367 -v 0.012738 -0.079926 -0.043680 -v 0.015631 -0.079098 -0.047656 -v 0.025380 -0.078689 -0.045789 -v 0.026013 -0.078247 -0.042810 -v 0.025362 -0.076785 -0.038962 -v 0.020499 -0.076047 -0.036319 -v 0.013829 -0.077811 -0.041879 -v 0.014532 -0.079040 -0.044839 -v 0.016908 -0.080064 -0.047640 -v 0.019233 -0.079484 -0.049072 -v 0.024487 -0.077739 -0.038859 -v 0.014687 -0.077916 -0.040019 -v 0.021317 -0.077059 -0.036925 -v 0.016923 -0.077189 -0.037730 -v 0.022138 -0.079752 -0.048200 -v 0.019430 -0.077794 -0.036252 -v 0.020689 -0.080528 -0.048268 -v 0.024178 -0.078160 -0.037188 -v 0.013852 -0.079382 -0.042987 -v 0.015536 -0.080507 -0.046725 -v 0.025972 -0.080091 -0.044627 -v 0.025931 -0.078893 -0.041161 -v 0.015143 -0.078349 -0.037930 -v 0.018660 -0.081194 -0.048548 -v 0.023189 -0.080998 -0.047861 -v 0.027366 -0.077608 -0.042224 -v 0.025765 -0.078960 -0.047257 -v 0.023946 -0.079391 -0.048870 -v 0.023712 -0.079254 -0.048297 -v 0.021121 -0.079664 -0.049890 -v 0.016542 -0.076090 -0.036548 -v 0.015426 -0.079277 -0.048440 -v 0.014918 -0.076393 -0.037681 -v 0.015258 -0.076513 -0.038093 -v 0.016274 -0.075010 -0.036960 -v 0.013666 -0.076801 -0.039200 -v 0.012636 -0.076639 -0.043034 -v 0.012739 -0.077406 -0.041490 -v 0.012715 -0.078055 -0.043880 -v 0.013493 -0.078676 -0.046221 -v 0.015229 -0.078125 -0.048583 -v 0.018117 -0.079624 -0.049736 -v 0.017440 -0.078450 -0.049799 -v 0.026716 -0.077447 -0.046047 -v 0.027007 -0.078385 -0.045110 -v 0.027283 -0.076948 -0.044192 -v 0.026722 -0.076995 -0.039923 -v 0.025321 -0.076438 -0.037874 -v 0.023319 -0.076072 -0.036478 -v 0.021141 -0.074774 -0.036071 -v 0.020888 -0.075873 -0.035741 -v 0.018595 -0.074792 -0.036143 -v 0.018420 -0.075910 -0.035882 -v 0.027242 -0.075308 -0.040193 -v 0.027667 -0.078807 -0.044564 -v 0.026764 -0.077203 -0.047261 -v 0.026748 -0.079401 -0.046783 -v 0.021535 -0.080318 -0.050205 -v 0.019533 -0.080346 -0.050310 -v 0.017118 -0.078041 -0.050394 -v 0.014760 -0.077698 -0.049015 -v 0.013335 -0.077238 -0.047390 -v 0.013195 -0.079352 -0.046600 -v 0.012086 -0.076123 -0.043232 -v 0.013237 -0.075063 -0.039277 -v 0.014980 -0.074551 -0.037367 -v 0.017832 -0.074242 -0.035893 -v 0.013241 -0.080096 -0.046473 -v 0.014983 -0.080031 -0.046901 -v 0.020373 -0.080728 -0.048868 -v 0.025059 -0.080086 -0.046524 -v 0.013163 -0.078981 -0.042326 -v 0.024307 -0.077449 -0.037786 -v 0.026263 -0.078224 -0.040763 -v 0.026713 -0.079045 -0.042552 -v 0.019688 -0.077304 -0.036094 -v 0.014249 -0.077400 -0.039298 -v 0.022162 -0.079927 -0.048699 -v 0.023031 -0.076761 -0.036900 -v 0.016397 -0.079795 -0.048224 -v 0.013289 -0.078639 -0.043919 -v 0.027790 -0.077931 -0.041306 -v 0.027278 -0.077500 -0.039693 -v 0.017638 -0.076640 -0.036467 -v 0.022432 -0.080976 -0.049757 -v 0.015566 -0.077681 -0.037469 -v 0.018833 -0.078082 -0.034611 -v 0.024323 -0.078400 -0.035798 -v 0.025856 -0.078736 -0.037054 -v 0.026552 -0.077959 -0.038145 -v 0.027306 -0.079304 -0.039172 -v 0.027963 -0.080232 -0.042636 -v 0.027089 -0.081028 -0.045615 -v 0.023651 -0.081928 -0.048987 -v 0.021159 -0.082145 -0.049785 -v 0.018064 -0.082111 -0.049651 -v 0.015121 -0.081708 -0.048264 -v 0.017068 -0.080934 -0.049596 -v 0.012954 -0.081051 -0.045692 -v 0.012083 -0.079314 -0.043542 -v 0.012140 -0.080417 -0.043327 -v 0.014673 -0.078599 -0.036543 -v 0.016386 -0.078292 -0.035397 -v 0.027916 -0.077243 -0.043084 -v 0.026161 -0.077005 -0.037843 -v 0.023990 -0.076524 -0.036046 -v 0.012056 -0.078477 -0.043332 -v 0.012388 -0.076784 -0.045338 -v 0.015714 -0.080029 -0.049127 -v 0.017669 -0.080263 -0.049998 -v 0.024114 -0.079003 -0.049508 -v 0.012492 -0.077647 -0.040235 -v 0.024924 -0.079906 -0.048664 -v 0.018646 -0.076283 -0.035147 -v 0.013940 -0.076975 -0.037750 -v 0.021289 -0.076274 -0.035113 -v 0.024398 -0.077319 -0.036106 -v 0.027814 -0.079423 -0.043957 -v 0.019170 -0.081068 -0.050098 -v 0.012229 -0.079711 -0.040718 -v 0.013988 -0.077689 -0.037490 -v 0.018307 -0.077110 -0.034976 -v 0.021515 -0.077007 -0.034945 -v 0.013028 -0.079119 -0.038530 -v 0.025451 -0.080527 -0.048080 -v 0.015875 -0.077282 -0.035968 -v 0.027666 -0.078522 -0.040592 -v 0.027309 -0.076429 -0.042248 -v 0.023473 -0.074982 -0.036854 -v 0.025099 -0.075288 -0.037994 -v 0.025305 -0.078003 -0.048099 -v 0.022821 -0.078432 -0.049729 -v 0.019866 -0.078576 -0.050268 -v 0.012933 -0.076125 -0.041121 -v 0.014039 -0.075532 -0.038903 -v 0.013123 -0.077400 -0.045849 -v 0.013374 -0.074709 -0.042899 -v 0.014542 -0.075907 -0.045872 -v 0.016489 -0.076399 -0.048846 -v 0.024788 -0.076130 -0.048254 -v 0.024973 -0.074288 -0.040050 -v 0.016415 -0.073442 -0.038187 -v 0.026651 -0.074733 -0.043010 -v 0.015071 -0.073934 -0.039575 -v 0.014130 -0.075394 -0.042441 -v 0.020935 -0.076602 -0.049755 -v 0.016806 -0.077274 -0.048153 -v 0.024344 -0.076595 -0.047385 -v 0.022838 -0.074045 -0.038356 -v 0.020098 -0.077652 -0.049143 -v 0.015485 -0.074828 -0.039609 -v 0.025879 -0.075793 -0.044465 -v 0.025651 -0.075568 -0.041072 -v 0.020007 -0.073793 -0.037689 -v 0.013532 -0.076228 -0.041636 -v 0.017697 -0.078371 -0.049524 -v 0.023571 -0.078004 -0.048299 -v 0.017992 -0.074508 -0.037934 -v 0.025661 -0.077311 -0.046108 -v 0.026517 -0.076687 -0.043275 -v 0.014030 -0.077339 -0.045801 -v 0.026622 -0.075834 -0.039952 -v 0.022898 -0.075109 -0.037580 -v 0.017661 -0.074945 -0.036752 -v 0.027007 -0.075486 -0.045885 -v 0.022826 -0.073098 -0.037011 -v 0.023050 -0.076619 -0.050112 -v 0.017459 -0.073085 -0.036929 -v 0.013277 -0.075653 -0.046512 -v 0.014827 -0.073493 -0.038451 -v 0.015827 -0.072196 -0.038041 -v 0.014037 -0.072634 -0.039682 -v 0.012993 -0.074265 -0.041329 -v 0.012791 -0.073355 -0.042317 -v 0.012633 -0.075037 -0.044214 -v 0.013186 -0.074502 -0.046579 -v 0.014228 -0.074949 -0.048324 -v 0.015025 -0.076303 -0.048942 -v 0.016046 -0.075382 -0.049938 -v 0.018123 -0.076726 -0.050514 -v 0.020586 -0.076775 -0.050699 -v 0.025483 -0.076160 -0.048397 -v 0.025314 -0.075117 -0.048854 -v 0.027367 -0.074713 -0.043000 -v 0.026723 -0.074098 -0.040702 -v 0.025662 -0.073657 -0.039055 -v 0.024662 -0.073405 -0.038118 -v 0.021593 -0.071904 -0.036958 -v 0.019887 -0.072953 -0.036469 -v 0.019593 -0.071863 -0.036801 -v 0.017624 -0.071961 -0.037170 -v 0.017768 -0.073364 -0.036155 -v 0.020683 -0.071754 -0.036232 -v 0.025241 -0.073866 -0.037716 -v 0.027625 -0.073789 -0.046117 -v 0.016435 -0.076077 -0.050602 -v 0.013670 -0.076654 -0.048122 -v 0.012079 -0.074051 -0.043560 -v 0.012229 -0.074998 -0.041945 -v 0.012961 -0.074463 -0.039944 -v 0.018548 -0.077116 -0.049831 -v 0.020882 -0.073708 -0.037092 -v 0.022552 -0.074481 -0.037126 -v 0.013661 -0.075543 -0.041097 -v 0.013665 -0.076746 -0.045570 -v 0.020464 -0.077842 -0.049680 -v 0.024663 -0.077378 -0.047949 -v 0.026542 -0.075730 -0.043252 -v 0.016969 -0.074610 -0.037650 -v 0.013494 -0.074886 -0.041506 -v 0.025171 -0.074299 -0.039311 -v 0.014336 -0.076398 -0.047146 -v 0.023191 -0.076951 -0.049209 -v 0.026025 -0.076184 -0.046348 -v 0.025777 -0.075264 -0.040049 -v 0.016216 -0.077556 -0.048615 -v 0.026580 -0.074273 -0.039233 -v 0.022239 -0.073428 -0.036080 -v 0.015602 -0.073700 -0.037095 -v 0.018904 -0.077448 -0.051087 -v 0.012411 -0.075983 -0.045620 -v 0.027889 -0.075531 -0.043937 -v 0.025464 -0.076916 -0.049099 -v 0.014333 -0.071803 -0.038671 -v 0.027439 -0.074702 -0.040833 -v 0.015330 -0.077056 -0.049623 -v 0.022377 -0.074260 -0.035939 -v 0.026508 -0.074971 -0.038936 -v 0.027625 -0.076688 -0.045340 -v 0.012376 -0.075578 -0.041199 -v 0.016308 -0.075720 -0.036104 -v 0.025004 -0.074541 -0.037325 -v 0.020044 -0.074084 -0.035626 -v 0.022569 -0.078168 -0.050501 -v 0.025637 -0.077568 -0.048629 -v 0.027689 -0.075655 -0.041489 -v 0.027865 -0.076324 -0.043982 -v 0.019650 -0.078182 -0.050919 -v 0.027012 -0.073159 -0.041640 -v 0.027364 -0.073790 -0.043998 -v 0.026922 -0.074437 -0.046414 -v 0.023951 -0.072149 -0.037868 -v 0.022823 -0.075535 -0.050504 -v 0.020287 -0.075683 -0.051008 -v 0.018411 -0.075628 -0.050851 -v 0.012691 -0.074001 -0.044784 -v 0.017258 -0.070500 -0.038707 -v 0.013896 -0.070889 -0.040358 -v 0.025523 -0.072954 -0.047304 -v 0.013963 -0.072676 -0.046459 -v 0.016704 -0.073499 -0.049887 -v 0.020883 -0.070059 -0.037301 -v 0.020042 -0.074388 -0.049810 -v 0.025951 -0.072515 -0.043888 -v 0.018314 -0.071133 -0.038706 -v 0.014359 -0.073707 -0.046005 -v 0.017628 -0.074528 -0.049353 -v 0.023266 -0.073604 -0.049373 -v 0.023998 -0.070769 -0.039552 -v 0.015393 -0.073758 -0.047818 -v 0.024989 -0.074013 -0.047268 -v 0.025110 -0.072495 -0.040784 -v 0.014273 -0.072284 -0.042573 -v 0.020822 -0.071034 -0.038518 -v 0.015090 -0.071425 -0.040732 -v 0.013761 -0.073376 -0.043373 -v 0.022503 -0.071846 -0.038719 -v 0.014681 -0.072727 -0.040181 -v 0.023061 -0.074755 -0.049074 -v 0.023466 -0.072261 -0.038349 -v 0.026562 -0.073869 -0.044351 -v 0.025781 -0.072590 -0.039495 -v 0.018716 -0.072054 -0.037742 -v 0.027115 -0.072467 -0.046223 -v 0.027197 -0.071590 -0.042942 -v 0.025791 -0.071376 -0.041800 -v 0.023414 -0.073660 -0.050688 -v 0.025483 -0.073262 -0.049174 -v 0.025322 -0.070648 -0.039426 -v 0.014029 -0.073106 -0.048595 -v 0.015817 -0.073548 -0.050239 -v 0.017608 -0.073779 -0.051112 -v 0.019584 -0.073882 -0.051486 -v 0.017888 -0.070143 -0.037540 -v 0.015682 -0.070432 -0.038619 -v 0.012738 -0.071617 -0.043040 -v 0.012789 -0.072387 -0.045960 -v 0.017939 -0.072717 -0.051538 -v 0.021584 -0.073839 -0.051331 -v 0.025698 -0.072076 -0.049192 -v 0.026533 -0.072844 -0.047635 -v 0.027365 -0.071957 -0.044305 -v 0.026723 -0.071200 -0.041478 -v 0.023316 -0.070276 -0.038030 -v 0.019948 -0.068019 -0.037248 -v 0.021116 -0.070483 -0.036679 -v 0.025823 -0.068664 -0.039703 -v 0.027243 -0.069213 -0.041737 -v 0.027440 -0.071805 -0.041616 -v 0.019760 -0.072474 -0.052459 -v 0.015443 -0.074094 -0.050545 -v 0.012950 -0.071135 -0.048343 -v 0.012124 -0.072299 -0.043458 -v 0.023637 -0.070984 -0.038545 -v 0.014907 -0.074454 -0.048612 -v 0.026145 -0.072431 -0.041059 -v 0.026288 -0.073697 -0.045942 -v 0.022992 -0.071683 -0.038321 -v 0.014579 -0.072249 -0.040423 -v 0.020894 -0.075015 -0.050702 -v 0.013433 -0.072978 -0.044979 -v 0.023667 -0.074243 -0.049341 -v 0.018636 -0.070964 -0.037926 -v 0.015383 -0.073885 -0.048730 -v 0.019219 -0.074258 -0.050747 -v 0.026219 -0.071892 -0.041916 -v 0.018236 -0.071534 -0.037710 -v 0.013262 -0.073075 -0.043462 -v 0.024133 -0.074168 -0.050783 -v 0.025122 -0.070858 -0.038405 -v 0.012465 -0.073125 -0.046550 -v 0.017669 -0.074467 -0.051551 -v 0.019796 -0.074556 -0.051882 -v 0.013812 -0.073783 -0.048995 -v 0.012156 -0.072680 -0.045265 -v 0.012387 -0.069573 -0.042796 -v 0.019050 -0.070465 -0.036617 -v 0.022453 -0.069475 -0.037252 -v 0.022726 -0.074426 -0.051400 -v 0.012988 -0.070783 -0.040883 -v 0.015871 -0.070761 -0.037719 -v 0.026582 -0.071376 -0.040012 -v 0.027050 -0.073472 -0.047843 -v 0.014216 -0.071107 -0.039015 -v 0.014659 -0.071531 -0.040589 -v 0.024842 -0.071615 -0.038002 -v 0.027925 -0.073649 -0.043383 -v 0.027362 -0.076165 -0.046352 -v 0.022576 -0.077339 -0.050723 -v 0.018765 -0.075281 -0.051678 -v 0.012739 -0.072405 -0.040949 -v 0.012375 -0.073823 -0.046235 -v 0.024485 -0.074919 -0.050334 -v 0.014158 -0.074639 -0.049288 -v 0.017016 -0.071321 -0.036904 -v 0.021847 -0.075224 -0.051473 -v 0.025911 -0.074599 -0.049135 -v 0.027375 -0.072485 -0.041248 -v 0.026319 -0.072001 -0.039439 -v 0.023175 -0.071360 -0.037049 -v 0.024133 -0.068321 -0.038365 -v 0.027574 -0.070713 -0.047144 -v 0.022527 -0.072066 -0.052146 -v 0.017256 -0.072007 -0.052055 -v 0.012248 -0.070525 -0.046440 -v 0.012104 -0.070019 -0.044583 -v 0.026116 -0.071518 -0.049734 -v 0.014334 -0.068672 -0.039505 -v 0.027886 -0.071533 -0.045255 -v 0.025079 -0.073259 -0.050357 -v 0.014632 -0.071567 -0.050582 -v 0.027898 -0.071430 -0.043760 -v 0.027377 -0.071030 -0.045188 -v 0.027004 -0.070256 -0.042393 -v 0.025761 -0.069681 -0.040247 -v 0.024184 -0.072438 -0.050535 -v 0.023905 -0.069253 -0.038612 -v 0.022381 -0.072674 -0.051412 -v 0.021586 -0.068992 -0.037735 -v 0.020412 -0.072758 -0.051789 -v 0.019586 -0.068967 -0.037576 -v 0.016916 -0.068200 -0.037807 -v 0.017618 -0.069066 -0.037948 -v 0.026723 -0.071648 -0.047586 -v 0.015690 -0.072416 -0.050449 -v 0.013277 -0.070090 -0.041774 -v 0.013894 -0.071955 -0.048705 -v 0.015023 -0.069445 -0.039346 -v 0.012715 -0.070587 -0.043628 -v 0.012738 -0.071227 -0.046024 -v 0.030231 -0.014410 -0.098424 -v 0.026983 -0.014212 -0.097668 -v 0.027707 -0.014861 -0.095105 -v 0.030665 -0.014215 -0.095024 -v 0.029372 0.015336 -0.096717 -v 0.030269 0.014242 -0.098664 -v 0.029463 0.014568 -0.094285 -v 0.026692 0.014250 -0.096677 -v 0.034504 0.014285 -0.096609 -v 0.037668 0.014560 -0.097208 -v 0.033963 0.014452 -0.099284 -v 0.037043 0.014446 -0.100289 -v 0.035160 0.014189 -0.100448 -v 0.034542 -0.014287 -0.100147 -v 0.037280 -0.014940 -0.099926 -v 0.037075 -0.014235 -0.096634 -v 0.034144 -0.014392 -0.097053 -v 0.033902 -0.014021 -0.099007 -v 0.018039 -0.014586 -0.095664 -v 0.017767 -0.014391 -0.098527 -v 0.014470 -0.014489 -0.097550 -v 0.015355 -0.014260 -0.095192 -v 0.016125 -0.014021 -0.098790 -v 0.058975 -0.009524 -0.094292 -v 0.055458 -0.009609 -0.094055 -v 0.058006 -0.009640 -0.098088 -v 0.057291 -0.010733 -0.095448 -v 0.058856 0.009269 -0.095654 -v 0.058833 0.009269 -0.095918 -v 0.058766 -0.009368 -0.096174 -v 0.058766 0.009269 -0.096174 -v 0.058657 -0.009368 -0.096416 -v 0.058657 0.009269 -0.096416 -v 0.058509 -0.009368 -0.096635 -v 0.058509 0.009269 -0.096635 -v 0.058326 -0.009368 -0.096826 -v 0.058326 0.009269 -0.096826 -v 0.058113 0.009269 -0.096984 -v 0.058113 -0.009368 -0.096984 -v 0.057876 -0.009368 -0.097103 -v 0.057876 0.009269 -0.097103 -v 0.057623 -0.009368 -0.097181 -v 0.057623 0.009269 -0.097181 -v 0.057360 -0.009368 -0.097215 -v 0.057095 -0.009368 -0.097203 -v 0.057360 0.009269 -0.097215 -v 0.056836 -0.009368 -0.097147 -v 0.057095 0.009269 -0.097203 -v 0.056836 0.009269 -0.097147 -v 0.056590 -0.009368 -0.097049 -v 0.056590 0.009269 -0.097049 -v 0.056365 -0.009368 -0.096910 -v 0.056365 0.009269 -0.096910 -v 0.056166 0.009269 -0.096735 -v 0.056166 -0.009368 -0.096735 -v 0.055999 0.009269 -0.096529 -v 0.055999 -0.009368 -0.096529 -v 0.055870 -0.009368 -0.096297 -v 0.055870 0.009269 -0.096297 -v 0.055782 -0.009368 -0.096047 -v 0.055782 0.009269 -0.096047 -v 0.055737 -0.009368 -0.095786 -v 0.055737 0.009269 -0.095786 -v 0.055737 -0.009368 -0.095521 -v 0.055737 0.009269 -0.095521 -v 0.055782 -0.009368 -0.095260 -v 0.055782 0.009269 -0.095260 -v 0.055870 -0.009368 -0.095010 -v 0.055999 -0.009368 -0.094779 -v 0.055870 0.009269 -0.095010 -v 0.056166 -0.009368 -0.094573 -v 0.055999 0.009269 -0.094779 -v 0.056166 0.009269 -0.094573 -v 0.056365 -0.009368 -0.094398 -v 0.056365 0.009269 -0.094398 -v 0.056590 -0.009368 -0.094259 -v 0.056836 -0.009368 -0.094160 -v 0.056590 0.009269 -0.094259 -v 0.056836 0.009269 -0.094160 -v 0.057095 0.009269 -0.094104 -v 0.057095 -0.009368 -0.094104 -v 0.057360 0.009269 -0.094093 -v 0.057360 -0.009368 -0.094093 -v 0.057623 -0.009368 -0.094127 -v 0.057876 -0.009368 -0.094204 -v 0.057623 0.009269 -0.094127 -v 0.057876 0.009269 -0.094204 -v 0.058113 -0.009368 -0.094324 -v 0.058113 0.009269 -0.094324 -v 0.058326 -0.009368 -0.094481 -v 0.058509 -0.009368 -0.094673 -v 0.058326 0.009269 -0.094481 -v 0.058509 0.009269 -0.094673 -v 0.058657 -0.009368 -0.094892 -v 0.058766 -0.009368 -0.095133 -v 0.058657 0.009269 -0.094892 -v 0.058766 0.009269 -0.095133 -v 0.058833 -0.009368 -0.095390 -v 0.058833 0.009269 -0.095390 -v 0.058856 -0.009368 -0.095654 -v 0.058833 -0.009368 -0.095918 -v 0.058771 0.009639 -0.097365 -v 0.056827 0.009747 -0.093402 -v 0.055513 0.010041 -0.096397 -v 0.057302 0.009269 -0.097781 -v 0.059300 0.009351 -0.094869 -v 0.069532 -0.006462 -0.093524 -v 0.069732 -0.005936 -0.092000 -v 0.061029 -0.006350 -0.093524 -v 0.061029 0.006350 -0.093524 -v 0.064924 -0.002176 -0.093524 -v 0.058224 0.006350 -0.093524 -v 0.067137 0.007936 -0.093524 -v 0.063717 0.004676 -0.093524 -v 0.063415 0.007937 -0.093524 -v 0.068745 0.007281 -0.093524 -v 0.069900 -0.004762 -0.093524 -v 0.067010 0.002917 -0.093524 -v 0.069900 0.004763 -0.093524 -v 0.065634 -0.005929 -0.093524 -v 0.065968 0.002109 -0.093524 -v 0.067422 -0.007931 -0.093524 -v 0.067138 -0.003136 -0.093524 -v 0.067746 0.007928 -0.092000 -v 0.069783 0.005734 -0.093524 -v 0.067130 -0.007936 -0.092000 -v 0.063944 -0.003078 -0.092000 -v 0.061029 0.006350 -0.092000 -v 0.068555 -0.007397 -0.092000 -v 0.063413 -0.007936 -0.092000 -v 0.065404 -0.005866 -0.092000 -v 0.063873 0.005046 -0.092000 -v 0.065792 0.005825 -0.092000 -v 0.065081 0.002152 -0.092000 -v 0.061614 0.007132 -0.092000 -v 0.061861 0.007360 -0.093524 -v 0.063199 0.007934 -0.092000 -v 0.057326 0.006350 -0.100386 -v 0.056087 0.006350 -0.097629 -v 0.054795 0.006350 -0.098439 -v 0.055893 0.006350 -0.097304 -v 0.054555 0.006350 -0.098034 -v 0.057476 0.006350 -0.093634 -v 0.055633 0.006350 -0.095830 -v 0.055704 0.006350 -0.095458 -v 0.054178 0.006350 -0.095292 -v 0.054472 0.006350 -0.094400 -v 0.056004 0.006350 -0.094763 -v 0.056226 0.006350 -0.094456 -v 0.055748 0.006350 -0.096953 -v 0.054363 0.006350 -0.097605 -v 0.054220 0.006350 -0.097157 -v 0.055617 0.006350 -0.096209 -v 0.054093 0.006350 -0.096227 -v 0.054693 0.006350 -0.093985 -v 0.055616 0.006350 -0.092927 -v 0.055997 0.006350 -0.092651 -v 0.056840 0.006350 -0.092239 -v 0.057292 0.006350 -0.092107 -v 0.056327 -0.006350 -0.097923 -v 0.056728 0.006350 -0.098280 -v 0.056327 0.006350 -0.097923 -v 0.056087 -0.006350 -0.097629 -v 0.055748 -0.006350 -0.096953 -v 0.055655 0.006350 -0.096586 -v 0.055704 -0.006350 -0.095458 -v 0.055829 0.006350 -0.095100 -v 0.055829 -0.006350 -0.095100 -v 0.056490 -0.006350 -0.094184 -v 0.056490 0.006350 -0.094184 -v 0.056791 -0.006350 -0.093953 -v 0.056791 0.006350 -0.093953 -v 0.057122 -0.006350 -0.093768 -v 0.057122 0.006350 -0.093768 -v 0.057476 -0.006350 -0.093634 -v 0.057846 0.006350 -0.093552 -v 0.057846 -0.006350 -0.093552 -v 0.056745 -0.006350 -0.098289 -v 0.055403 -0.006350 -0.099153 -v 0.054220 -0.006350 -0.097157 -v 0.055893 -0.006350 -0.097304 -v 0.054363 -0.006350 -0.097605 -v 0.055079 -0.006350 -0.098813 -v 0.058224 -0.006350 -0.093524 -v 0.058224 -0.006350 -0.092000 -v 0.055633 -0.006350 -0.095830 -v 0.054109 -0.006350 -0.095757 -v 0.055617 -0.006350 -0.096209 -v 0.055655 -0.006350 -0.096586 -v 0.056226 -0.006350 -0.094456 -v 0.054960 -0.006350 -0.093598 -v 0.054693 -0.006350 -0.093985 -v 0.056004 -0.006350 -0.094763 -v 0.054472 -0.006350 -0.094400 -v 0.054300 -0.006350 -0.094838 -v 0.054178 -0.006350 -0.095292 -v 0.055616 -0.006350 -0.092927 -v 0.063373 -0.007936 -0.093524 -v 0.061866 -0.007363 -0.092000 -v 0.061763 -0.007284 -0.093524 -v 0.061029 -0.006350 -0.092000 -v 0.058224 0.006350 -0.092000 -v 0.057755 0.006350 -0.092027 -v 0.057755 -0.006350 -0.092027 -v 0.057292 -0.006350 -0.092107 -v 0.056840 -0.006350 -0.092239 -v 0.056407 0.006350 -0.092421 -v 0.056407 -0.006350 -0.092421 -v 0.055997 -0.006350 -0.092651 -v 0.055269 0.006350 -0.093244 -v 0.055269 -0.006350 -0.093244 -v 0.054960 0.006350 -0.093598 -v 0.054300 0.006350 -0.094838 -v 0.054109 0.006350 -0.095757 -v 0.054093 -0.006350 -0.096227 -v 0.054130 -0.006350 -0.096696 -v 0.054130 0.006350 -0.096696 -v 0.054555 -0.006350 -0.098034 -v 0.054795 -0.006350 -0.098439 -v 0.055079 0.006350 -0.098813 -v 0.055403 0.006350 -0.099153 -v 0.055909 0.006350 -0.099565 -v 0.055950 -0.006350 -0.099590 -v 0.057326 -0.006350 -0.100386 -v 0.058088 0.006350 -0.099066 -v 0.058088 -0.006350 -0.099066 -v 0.069900 -0.004762 -0.092000 -v 0.069899 0.005644 -0.092000 -v 0.067369 0.003753 -0.093524 -v 0.066992 0.005134 -0.093524 -v 0.065406 0.005867 -0.093524 -v 0.064132 0.002652 -0.093524 -v 0.063913 0.002978 -0.092000 -v 0.066821 0.002529 -0.092000 -v 0.067319 0.004676 -0.092000 -v 0.067346 -0.004507 -0.093524 -v 0.066693 -0.002491 -0.092000 -v 0.066350 -0.002296 -0.093524 -v 0.064951 -0.002141 -0.092000 -v 0.064117 -0.002787 -0.093524 -v 0.063667 -0.003758 -0.093524 -v 0.063812 -0.004816 -0.092000 -v 0.063967 -0.004994 -0.093524 -v 0.066993 -0.005133 -0.092000 -v 0.067369 -0.003753 -0.092000 -v 0.014031 -0.002671 -0.093027 -v 0.013591 -0.002066 -0.094789 -v 0.016867 0.001111 -0.095011 -v 0.014455 0.001007 -0.096452 -v 0.016279 0.001659 -0.094963 -v 0.016431 0.001543 -0.098626 -v 0.014309 0.002025 -0.097442 -v 0.018407 0.001456 -0.097969 -v 0.015149 0.000987 -0.098634 -v 0.017342 0.002383 -0.094645 -v 0.015889 0.001470 -0.098754 -v 0.016231 0.001737 -0.094669 -v 0.017838 0.002041 -0.098292 -v 0.018038 0.001995 -0.097644 -v 0.015230 0.002387 -0.095263 -v 0.017828 0.002559 -0.097878 -v 0.016615 0.001038 -0.098317 -v 0.018324 0.001214 -0.095694 -v 0.016975 0.000449 -0.099001 -v 0.017908 0.000777 -0.098294 -v 0.014658 0.000819 -0.095639 -v 0.016310 0.000058 -0.098808 -v 0.014914 0.000574 -0.097423 -v 0.018184 -0.000066 -0.096429 -v 0.016957 0.000551 -0.094837 -v 0.014929 0.000875 -0.098095 -v 0.017749 0.000895 -0.096077 -v 0.014460 0.000168 -0.097900 -v 0.014645 -0.000391 -0.095850 -v 0.018617 0.000499 -0.096434 -v 0.015277 -0.000698 -0.098883 -v 0.017107 -0.000304 -0.094954 -v 0.017621 -0.000408 -0.098758 -v 0.014646 -0.000873 -0.097422 -v 0.017923 -0.000513 -0.097833 -v 0.015761 0.000326 -0.094885 -v 0.014609 -0.000303 -0.096415 -v 0.014831 0.000162 -0.096579 -v 0.018555 -0.001089 -0.097556 -v 0.015610 -0.000851 -0.095039 -v 0.017505 0.000119 -0.098443 -v 0.017674 -0.001154 -0.095804 -v 0.018271 -0.000189 -0.095870 -v 0.014653 -0.001533 -0.095686 -v 0.018030 -0.000521 -0.098171 -v 0.014997 -0.002298 -0.097710 -v 0.015067 -0.000870 -0.095441 -v 0.017814 -0.002511 -0.098176 -v 0.017426 -0.002675 -0.094902 -v 0.016907 -0.002068 -0.099112 -v 0.017351 -0.002431 -0.095556 -v 0.017367 -0.001492 -0.098219 -v 0.016589 -0.001701 -0.095467 -v 0.018428 -0.001275 -0.097643 -v 0.018003 -0.001920 -0.095168 -v 0.014940 -0.001646 -0.098353 -v 0.015738 -0.001533 -0.094927 -v 0.015047 -0.001062 -0.098319 -v 0.014400 -0.002158 -0.097304 -v 0.017385 -0.001042 -0.095087 -v 0.015477 -0.001719 -0.098811 -v 0.016699 0.001530 -0.095425 -v 0.010418 0.002050 -0.100707 -v 0.010514 0.002708 -0.100851 -v 0.017586 0.002590 -0.098481 -v 0.010593 0.002190 -0.101111 -v 0.015961 0.002230 -0.098497 -v 0.010346 0.002348 -0.100511 -v 0.013485 -0.002270 -0.096098 -v 0.018071 -0.009906 -0.093364 -v 0.017796 -0.005080 -0.093091 -v 0.015171 -0.009906 -0.092770 -v 0.015463 -0.009906 -0.094766 -v 0.017120 -0.009906 -0.092773 -v 0.018440 -0.009906 -0.094062 -v 0.017637 -0.009906 -0.095521 -v 0.018841 -0.009906 -0.096331 -v 0.017925 -0.009906 -0.096362 -v 0.016188 -0.009906 -0.094667 -v 0.016966 -0.009906 -0.094879 -v 0.015363 -0.010312 -0.091403 -v 0.015386 -0.010148 -0.090980 -v 0.014409 -0.005080 -0.091431 -v 0.016535 -0.005080 -0.092522 -v 0.016916 -0.010191 -0.091862 -v 0.016535 -0.010148 -0.092522 -v 0.015171 -0.009906 -0.095088 -v 0.015171 -0.005080 -0.095122 -v 0.015176 -0.005080 -0.097276 -v 0.016454 -0.009934 -0.098195 -v 0.015332 -0.010163 -0.097568 -v 0.015171 -0.009934 -0.096909 -v 0.015874 -0.010248 -0.098053 -v 0.015013 -0.010246 -0.091462 -v 0.015170 -0.010035 -0.091735 -v 0.015085 -0.010260 -0.098434 -v 0.015306 -0.010312 -0.091376 -v 0.014409 -0.009934 -0.091735 -v 0.014502 -0.010245 -0.091299 -v 0.016747 -0.010274 -0.098931 -v 0.014409 -0.009934 -0.096909 -v 0.014464 -0.010145 -0.097452 -v 0.014976 -0.005081 -0.098358 -v 0.015675 -0.010106 -0.098800 -v 0.016794 -0.005080 -0.098910 -v 0.016916 -0.005080 -0.091862 -v 0.015261 -0.005080 -0.090909 -v 0.016044 -0.005081 -0.098919 -v 0.015171 -0.005080 -0.091735 -v 0.015418 -0.005080 -0.094784 -v 0.015171 -0.005080 -0.092770 -v 0.016287 -0.005080 -0.098222 -v 0.015624 -0.005080 -0.097881 -v 0.017891 -0.005080 -0.096231 -v 0.018841 -0.005080 -0.096331 -v 0.016200 -0.005080 -0.094663 -v 0.016904 -0.005080 -0.092771 -v 0.014526 -0.005080 -0.097588 -v 0.014409 -0.005080 -0.096909 -v 0.018212 -0.005080 -0.096441 -v 0.017317 -0.005080 -0.095083 -v 0.018424 -0.005080 -0.093970 -v 0.019111 -0.005080 -0.098181 -v 0.019085 -0.009934 -0.098145 -v 0.018574 -0.005080 -0.097824 -v 0.018551 -0.009934 -0.097827 -v 0.019744 -0.008081 -0.105485 -v 0.020135 -0.007772 -0.105588 -v 0.019562 0.010303 -0.103116 -v 0.020099 0.009169 -0.105401 -v 0.019960 0.007773 -0.105601 -v 0.019805 0.007773 -0.105538 -v 0.019518 0.010202 -0.103980 -v 0.019692 0.007773 -0.105414 -v 0.019648 0.007773 -0.105295 -v 0.018403 0.010313 -0.098236 -v 0.019941 0.010257 -0.103431 -v 0.018777 0.010142 -0.097908 -v 0.019126 0.010137 -0.098198 -v 0.019645 0.010313 -0.103101 -v 0.018470 0.010157 -0.098614 -v 0.018470 -0.010175 -0.098614 -v 0.019272 0.009934 -0.103167 -v 0.018470 -0.005080 -0.098614 -v 0.018470 0.005080 -0.098614 -v 0.018832 -0.010312 -0.098487 -v 0.019648 -0.007772 -0.105295 -v 0.019878 -0.007772 -0.105578 -v 0.019272 -0.009934 -0.103167 -v 0.018847 -0.010312 -0.098548 -v 0.019220 -0.010117 -0.098482 -v 0.019635 -0.010306 -0.104261 -v 0.020023 -0.009934 -0.103034 -v 0.020340 -0.007772 -0.105436 -v 0.020227 0.007773 -0.105545 -v 0.020397 -0.007772 -0.105290 -v 0.020398 0.007773 -0.105163 -v 0.020380 0.007773 -0.105332 -v 0.019650 0.010313 -0.103100 -v 0.019220 0.009934 -0.098482 -v 0.020023 0.009934 -0.103034 -v 0.019220 0.005080 -0.098482 -v 0.020348 -0.008725 -0.104877 -v 0.019220 -0.005080 -0.098482 -v 0.020398 -0.007772 -0.105163 -v 0.018212 0.009906 -0.096441 -v 0.016167 0.005080 -0.094665 -v 0.016219 0.009906 -0.094666 -v 0.015171 0.005080 -0.095088 -v 0.015455 0.005080 -0.094771 -v 0.015322 0.009906 -0.094818 -v 0.015171 0.009906 -0.092770 -v 0.017891 0.009906 -0.096231 -v 0.017317 0.009906 -0.095083 -v 0.018422 0.009906 -0.093966 -v 0.018841 0.009906 -0.096331 -v 0.017796 0.009906 -0.093091 -v 0.018071 0.005080 -0.093364 -v 0.016899 0.009906 -0.092771 -v 0.014790 0.010313 -0.095608 -v 0.014976 0.010272 -0.091405 -v 0.016250 0.009935 -0.098227 -v 0.015171 0.010106 -0.097121 -v 0.015306 0.010313 -0.091376 -v 0.014409 0.005080 -0.091413 -v 0.014409 0.009934 -0.096909 -v 0.015286 0.005080 -0.090923 -v 0.014409 0.010171 -0.091474 -v 0.016535 0.005080 -0.092522 -v 0.016535 0.010149 -0.092522 -v 0.016916 0.005080 -0.091862 -v 0.016916 0.010194 -0.091862 -v 0.015171 0.010039 -0.091735 -v 0.015171 0.009906 -0.095237 -v 0.016407 0.005080 -0.098203 -v 0.015172 0.005080 -0.097166 -v 0.018399 0.009934 -0.097853 -v 0.015171 0.005080 -0.091735 -v 0.015171 0.005080 -0.092770 -v 0.014409 0.005080 -0.096909 -v 0.014515 0.005081 -0.097595 -v 0.015580 0.005081 -0.097870 -v 0.017127 0.005080 -0.092776 -v 0.016966 0.005080 -0.094879 -v 0.019059 0.005080 -0.098104 -v 0.018441 0.005080 -0.094066 -v 0.017637 0.005080 -0.095521 -v 0.018522 0.005080 -0.097832 -v 0.018841 0.005080 -0.096331 -v 0.017925 0.005080 -0.096362 -v 0.015235 0.005082 -0.098581 -v 0.016794 0.005080 -0.098910 -v 0.016249 0.005084 -0.098935 -v 0.016791 0.010217 -0.098915 -v 0.015746 0.010083 -0.098824 -v 0.014877 0.010180 -0.098214 -v 0.014435 0.010101 -0.097267 -v 0.015363 0.010313 -0.091403 -v 0.015226 0.010169 -0.090892 -v 0.059616 -0.009318 -0.094522 -v 0.059925 -0.007794 -0.095905 -v 0.057300 -0.007794 -0.093929 -v 0.058969 -0.007794 -0.095466 -v 0.052439 -0.007794 -0.095994 -v 0.033341 -0.007794 -0.101074 -v 0.055617 -0.007794 -0.095804 -v 0.056582 -0.007794 -0.093048 -v 0.059065 -0.007794 -0.093739 -v 0.058761 -0.007794 -0.097801 -v 0.057237 -0.007794 -0.097461 -v 0.042272 -0.007794 -0.101074 -v 0.042272 -0.009318 -0.101074 -v 0.044103 -0.007794 -0.101035 -v 0.044103 -0.009318 -0.101035 -v 0.046975 -0.009318 -0.100826 -v 0.046677 -0.007794 -0.100858 -v 0.050338 -0.007794 -0.100322 -v 0.054636 -0.007794 -0.099289 -v 0.054192 -0.009318 -0.099402 -v 0.058530 -0.009318 -0.097918 -v 0.032947 -0.009318 -0.101074 -v 0.058423 -0.009318 -0.094232 -v 0.050621 -0.009318 -0.100267 -v 0.055758 -0.009318 -0.096004 -v 0.055949 -0.009318 -0.096509 -v 0.056220 -0.009318 -0.093308 -v 0.058013 -0.009318 -0.093112 -v 0.057813 -0.009318 -0.097465 -v 0.059790 -0.009318 -0.096411 -v 0.052439 -0.009318 -0.095994 -v 0.032947 -0.009318 -0.095994 -v 0.031767 0.007717 -0.095994 -v 0.031767 -0.007816 -0.095994 -v 0.032045 -0.008811 -0.095994 -v 0.033341 -0.007794 -0.095994 -v 0.032158 0.008893 -0.095994 -v 0.033341 0.007694 -0.095994 -v 0.050337 0.009269 -0.100322 -v 0.058530 0.007694 -0.097918 -v 0.058761 0.009269 -0.097801 -v 0.059790 0.007694 -0.096411 -v 0.057300 0.009269 -0.093929 -v 0.054641 0.009269 -0.099287 -v 0.046676 0.009269 -0.100858 -v 0.044103 0.009269 -0.101035 -v 0.042272 0.009269 -0.101074 -v 0.033341 0.009269 -0.095994 -v 0.033341 0.009269 -0.101074 -v 0.059590 0.009269 -0.094560 -v 0.052439 0.009269 -0.095994 -v 0.055617 0.009269 -0.095804 -v 0.056298 0.009269 -0.093246 -v 0.059787 0.009269 -0.096326 -v 0.057237 0.009269 -0.097461 -v 0.058337 0.009269 -0.093262 -v 0.056124 0.007694 -0.093369 -v 0.033341 0.007694 -0.101074 -v 0.052439 0.007694 -0.095994 -v 0.050622 0.007694 -0.100267 -v 0.055949 0.007694 -0.096509 -v 0.046975 0.007694 -0.100826 -v 0.056069 0.007694 -0.094263 -v 0.059438 0.007694 -0.094113 -v 0.059201 0.007694 -0.095648 -v 0.056983 0.007694 -0.097238 -v 0.054192 0.007694 -0.099402 -v 0.057580 0.007694 -0.093086 -v 0.042272 0.007694 -0.101074 -v 0.055758 0.007694 -0.096004 -v 0.044103 0.007694 -0.101035 -v 0.048172 0.007112 -0.094318 -v 0.048172 0.007112 -0.101049 -v 0.048172 -0.007112 -0.094318 -v 0.048172 -0.007112 -0.101049 -v 0.047410 -0.007112 -0.094318 -v 0.047410 -0.007112 -0.102126 -v 0.047410 -0.007112 -0.101430 -v 0.047874 -0.007112 -0.101818 -v 0.047410 0.009652 -0.095227 -v 0.046267 0.009652 -0.094089 -v 0.046267 -0.009652 -0.094089 -v 0.023331 -0.010414 -0.094089 -v 0.046267 -0.009652 -0.094851 -v 0.030604 -0.009652 -0.096198 -v 0.030395 -0.009652 -0.095695 -v 0.030086 -0.009652 -0.095310 -v 0.047407 -0.009652 -0.094543 -v 0.027225 -0.009652 -0.096607 -v 0.030623 -0.009652 -0.096733 -v 0.029501 -0.009652 -0.094969 -v 0.027872 -0.009652 -0.095263 -v 0.023331 -0.009652 -0.101430 -v 0.030314 -0.009652 -0.097548 -v 0.030546 -0.009652 -0.097084 -v 0.028069 -0.009652 -0.098023 -v 0.029239 -0.009652 -0.098195 -v 0.029801 -0.009652 -0.098002 -v 0.047410 -0.010414 -0.095227 -v 0.027479 -0.010414 -0.095605 -v 0.027580 -0.010414 -0.097394 -v 0.030623 -0.010414 -0.096733 -v 0.047410 -0.010414 -0.102192 -v 0.030490 -0.010414 -0.097251 -v 0.030073 -0.010414 -0.097809 -v 0.029585 -0.010414 -0.098098 -v 0.023331 -0.010414 -0.102192 -v 0.028559 -0.010414 -0.098201 -v 0.029548 -0.010414 -0.094990 -v 0.030083 -0.010414 -0.095307 -v 0.030493 -0.010414 -0.095862 -v 0.030623 -0.010414 -0.096373 -v 0.046267 -0.010414 -0.094089 -v 0.023331 -0.009652 -0.094851 -v 0.047410 0.007112 -0.094318 -v 0.047874 0.007112 -0.101818 -v 0.047410 0.007112 -0.101430 -v 0.048036 0.007112 -0.101589 -v 0.047661 -0.007112 -0.102001 -v 0.047661 0.007112 -0.102001 -v 0.048036 -0.007112 -0.101589 -v 0.048137 -0.007112 -0.101327 -v 0.048137 0.007112 -0.101327 -v 0.047410 -0.009652 -0.101430 -v 0.047410 0.007112 -0.102126 -v 0.023331 0.010414 -0.094089 -v 0.023331 0.010414 -0.102192 -v 0.047410 0.010414 -0.102192 -v 0.029059 0.010414 -0.094892 -v 0.029059 0.010414 -0.098214 -v 0.047410 0.010414 -0.095227 -v 0.046267 0.010414 -0.094089 -v 0.046884 0.010414 -0.094241 -v 0.030302 0.010414 -0.095385 -v 0.030594 0.010414 -0.096911 -v 0.030142 0.010414 -0.097664 -v 0.027279 0.009652 -0.096254 -v 0.027777 0.010414 -0.097864 -v 0.028124 0.009652 -0.095067 -v 0.027703 0.010414 -0.095258 -v 0.047090 0.009652 -0.094336 -v 0.023331 0.009652 -0.101430 -v 0.023331 0.009652 -0.094851 -v 0.027901 0.009652 -0.097888 -v 0.029414 0.009652 -0.094950 -v 0.029059 0.009652 -0.094892 -v 0.046267 0.009652 -0.094851 -v 0.047410 0.009652 -0.101430 -v 0.030176 0.009652 -0.095342 -v 0.030575 0.009652 -0.096728 -v 0.029414 0.009652 -0.098156 -v 0.035878 0.014021 -0.092921 -v 0.038109 0.012764 -0.093593 -v 0.035878 0.012764 -0.092921 -v 0.039838 0.014021 -0.096269 -v 0.039829 0.014021 -0.101275 -v 0.039840 0.012764 -0.100850 -v 0.033767 0.012764 -0.102445 -v 0.031112 0.012764 -0.101234 -v 0.032053 0.012764 -0.100869 -v 0.011707 0.012734 -0.102524 -v 0.013647 0.013688 -0.102446 -v 0.013576 0.013238 -0.102446 -v 0.013435 0.012936 -0.100922 -v 0.004237 0.014288 -0.104384 -v 0.005232 0.014288 -0.102360 -v 0.007276 0.014288 -0.103314 -v 0.006868 0.014288 -0.101845 -v 0.008843 0.014288 -0.102935 -v 0.000017 0.010478 -0.106732 -v -0.000855 0.010478 -0.105482 -v 0.000259 0.012235 -0.106558 -v -0.000730 0.011686 -0.105395 -v 0.000017 -0.010477 -0.106732 -v -0.000855 -0.010477 -0.105482 -v 0.000315 -0.012377 -0.106520 -v 0.001207 -0.014019 -0.104187 -v 0.002014 -0.013993 -0.105482 -v 0.002430 -0.014158 -0.105253 -v 0.013647 -0.014021 -0.102446 -v 0.012782 0.012471 -0.102459 -v 0.012883 -0.012576 -0.102458 -v 0.010867 -0.013820 -0.102609 -v 0.008843 -0.014287 -0.102935 -v 0.010407 0.014259 -0.102667 -v 0.011347 0.013255 -0.102557 -v 0.010867 0.013821 -0.102609 -v 0.001880 0.013931 -0.105556 -v 0.002288 0.014108 -0.105330 -v 0.001369 -0.013589 -0.105855 -v 0.000686 -0.012033 -0.106282 -v 0.001369 0.013589 -0.105855 -v 0.000686 0.012033 -0.106282 -v 0.003171 -0.014288 -0.104870 -v 0.002778 0.014241 -0.105071 -v 0.003317 0.014288 -0.104803 -v 0.004237 -0.014287 -0.104384 -v 0.005738 -0.014287 -0.103797 -v 0.005738 0.014288 -0.103797 -v 0.010147 0.014288 -0.102704 -v 0.007276 -0.014287 -0.103314 -v 0.008535 -0.014287 -0.101443 -v 0.003634 -0.014287 -0.102984 -v 0.011023 -0.013977 -0.101401 -v 0.010248 -0.014288 -0.102686 -v 0.010183 -0.014287 -0.101159 -v 0.013646 -0.013607 -0.102446 -v 0.013435 -0.012936 -0.102445 -v 0.012751 -0.012488 -0.100933 -v 0.012453 -0.012476 -0.102475 -v 0.011599 -0.012803 -0.102531 -v 0.013647 -0.014021 -0.100922 -v 0.035878 -0.014021 -0.092921 -v 0.015628 -0.012763 -0.092921 -v 0.031104 -0.014021 -0.102446 -v 0.031109 -0.010715 -0.102446 -v 0.031109 -0.010715 -0.100922 -v 0.031112 -0.012763 -0.101292 -v 0.031305 -0.014021 -0.101118 -v 0.038245 -0.012763 -0.102445 -v 0.039840 -0.014021 -0.100850 -v 0.039829 -0.012763 -0.101275 -v 0.039838 -0.012763 -0.096269 -v 0.039834 -0.014021 -0.096186 -v 0.038661 -0.014021 -0.093961 -v 0.037328 -0.012763 -0.093155 -v 0.015666 -0.014021 -0.097877 -v 0.017582 -0.014021 -0.097214 -v 0.017510 -0.014021 -0.096356 -v 0.027362 -0.014021 -0.096984 -v 0.028148 -0.014021 -0.098001 -v 0.027610 -0.014021 -0.097531 -v 0.030611 -0.014021 -0.096082 -v 0.034419 -0.014021 -0.097612 -v 0.034214 -0.014021 -0.098477 -v 0.030453 -0.014021 -0.097372 -v 0.029643 -0.014021 -0.098092 -v 0.017464 -0.014021 -0.097499 -v 0.017276 -0.014021 -0.097744 -v 0.016991 -0.014021 -0.097957 -v 0.035433 -0.014021 -0.100195 -v 0.033460 -0.014021 -0.102443 -v 0.027306 -0.014021 -0.096553 -v 0.016730 -0.014021 -0.095803 -v 0.015601 -0.014021 -0.095983 -v 0.037376 -0.014021 -0.097522 -v 0.027362 -0.014021 -0.096122 -v 0.015628 -0.014021 -0.092921 -v 0.027623 -0.014021 -0.095556 -v 0.037236 -0.014021 -0.099538 -v 0.032377 -0.014021 -0.100932 -v 0.035046 -0.014021 -0.097036 -v 0.035892 -0.014021 -0.096780 -v 0.036846 -0.014021 -0.093027 -v 0.038669 -0.014021 -0.102435 -v 0.016441 -0.014021 -0.098090 -v 0.034271 -0.014021 -0.098908 -v 0.028231 -0.014021 -0.095053 -v 0.028969 -0.014021 -0.094889 -v 0.014809 -0.012763 -0.093063 -v 0.014142 -0.014021 -0.093412 -v 0.013647 -0.014021 -0.094899 -v 0.017464 -0.012763 -0.096318 -v 0.034171 -0.012763 -0.098683 -v 0.027408 -0.012763 -0.095944 -v 0.027306 -0.012763 -0.096553 -v 0.017523 -0.012763 -0.097356 -v 0.037575 -0.012763 -0.097868 -v 0.030460 -0.012763 -0.097372 -v 0.033404 -0.012763 -0.102438 -v 0.030308 -0.012763 -0.095544 -v 0.029608 -0.012763 -0.094996 -v 0.029309 -0.012763 -0.098234 -v 0.035120 -0.012763 -0.096990 -v 0.032307 -0.012763 -0.100877 -v 0.035218 -0.012763 -0.100076 -v 0.036939 -0.012763 -0.099835 -v 0.030605 -0.012763 -0.096337 -v 0.038998 -0.012763 -0.094378 -v 0.035878 -0.012763 -0.092921 -v 0.027920 -0.012763 -0.095241 -v 0.017621 -0.012763 -0.096715 -v 0.017276 -0.012763 -0.096073 -v 0.015829 -0.012763 -0.095767 -v 0.027410 -0.012763 -0.097168 -v 0.027793 -0.012763 -0.097729 -v 0.013648 -0.012763 -0.094285 -v 0.015590 -0.012763 -0.097862 -v 0.013647 -0.012763 -0.100922 -v 0.017197 -0.012763 -0.097827 -v 0.013647 0.012764 -0.100922 -v 0.018022 -0.010715 -0.100922 -v 0.031109 -0.012763 -0.100922 -v 0.034960 0.012764 -0.099903 -v 0.015632 0.012764 -0.097840 -v 0.039834 0.012764 -0.096185 -v 0.037236 0.012764 -0.099538 -v 0.016441 0.012764 -0.098090 -v 0.034214 0.012764 -0.098477 -v 0.034282 0.012764 -0.098948 -v 0.015628 0.012764 -0.092921 -v 0.030633 0.012764 -0.096553 -v 0.037429 0.012764 -0.097646 -v 0.013647 0.012764 -0.094513 -v 0.015513 0.012764 -0.096040 -v 0.014489 0.012764 -0.093209 -v 0.027362 0.012764 -0.096122 -v 0.027623 0.012764 -0.095556 -v 0.035191 0.012764 -0.096945 -v 0.016441 0.012764 -0.095727 -v 0.027306 0.012764 -0.096553 -v 0.017336 0.012764 -0.096102 -v 0.034393 0.012764 -0.097659 -v 0.030453 0.012764 -0.097372 -v 0.017582 0.012764 -0.097214 -v 0.027362 0.012764 -0.096984 -v 0.017622 0.012764 -0.096758 -v 0.029643 0.012764 -0.098092 -v 0.028231 0.012764 -0.095053 -v 0.028969 0.012764 -0.094889 -v 0.029680 0.012764 -0.095037 -v 0.028148 0.012764 -0.098001 -v 0.027610 0.012764 -0.097531 -v 0.017464 0.012764 -0.097499 -v 0.017276 0.012764 -0.097744 -v 0.016991 0.012764 -0.097957 -v 0.031109 0.012764 -0.100922 -v 0.036846 0.012764 -0.093027 -v 0.030477 0.012764 -0.095761 -v 0.039112 0.012764 -0.094619 -v 0.038669 0.012764 -0.102435 -v 0.032734 0.012764 -0.101611 -v 0.031109 0.010716 -0.100922 -v 0.031109 0.010716 -0.102446 -v 0.018022 0.010716 -0.100922 -v 0.018022 -0.010715 -0.102446 -v 0.018022 0.010716 -0.102446 -v 0.013647 0.014021 -0.102446 -v 0.037673 0.014021 -0.093270 -v 0.039112 0.014021 -0.094619 -v 0.028969 0.014021 -0.094889 -v 0.028231 0.014021 -0.095053 -v 0.013648 0.014021 -0.094464 -v 0.015989 0.014021 -0.098039 -v 0.029680 0.014021 -0.095037 -v 0.016747 0.014021 -0.098049 -v 0.017191 0.014021 -0.097832 -v 0.017582 0.014021 -0.097214 -v 0.031262 0.014021 -0.101147 -v 0.017464 0.014021 -0.097499 -v 0.031108 0.014021 -0.102446 -v 0.030481 0.014021 -0.095762 -v 0.027623 0.014021 -0.095556 -v 0.015628 0.014021 -0.092921 -v 0.016353 0.014021 -0.095671 -v 0.014601 0.014021 -0.093138 -v 0.015110 0.014021 -0.096773 -v 0.017464 0.014021 -0.096318 -v 0.027362 0.014021 -0.096122 -v 0.017622 0.014021 -0.096756 -v 0.027306 0.014021 -0.096553 -v 0.027410 0.014021 -0.097168 -v 0.037575 0.014021 -0.097868 -v 0.030633 0.014021 -0.096553 -v 0.035191 0.014021 -0.096945 -v 0.034099 0.014021 -0.102446 -v 0.034921 0.014021 -0.100013 -v 0.038245 0.014021 -0.102445 -v 0.036939 0.014021 -0.099835 -v 0.027875 0.014021 -0.097817 -v 0.031938 0.014021 -0.100882 -v 0.029240 0.014021 -0.098206 -v 0.032463 0.014021 -0.101079 -v 0.034186 0.014021 -0.098017 -v 0.030339 0.014021 -0.097572 -v 0.033096 0.014021 -0.102153 -v 0.013647 0.014021 -0.100922 -v 0.012753 0.012510 -0.100935 -v 0.013530 -0.013098 -0.100921 -v 0.011347 -0.013254 -0.101026 -v 0.011787 0.012703 -0.100990 -v 0.011792 -0.012681 -0.100990 -v 0.011407 0.013125 -0.101021 -v 0.002434 0.014288 -0.103538 -v 0.001583 0.014195 -0.103973 -v 0.002075 -0.014274 -0.103718 -v 0.000584 -0.013659 -0.104549 -v 0.000695 0.013748 -0.104480 -v -0.000121 0.012962 -0.104988 -v -0.000109 -0.012971 -0.104980 -v -0.000756 -0.011587 -0.105412 -v 0.002434 -0.014287 -0.103538 -v 0.003634 0.014288 -0.102984 -v 0.005232 -0.014287 -0.102360 -v 0.006868 -0.014287 -0.101845 -v 0.008535 0.014288 -0.101443 -v 0.010181 0.014288 -0.101159 -v 0.011026 0.013975 -0.101366 -v 0.015294 -0.014021 -0.097191 -v 0.015395 -0.014021 -0.097457 -v 0.015557 0.015342 -0.097692 -v 0.015557 -0.014021 -0.097692 -v 0.015770 -0.014021 -0.097881 -v 0.016022 -0.014021 -0.098013 -v 0.016022 0.015342 -0.098013 -v 0.016298 0.015342 -0.098081 -v 0.016298 -0.014021 -0.098081 -v 0.016583 -0.014021 -0.098081 -v 0.016860 0.015342 -0.098013 -v 0.016860 -0.014021 -0.098013 -v 0.017112 0.015342 -0.097881 -v 0.017112 -0.014021 -0.097881 -v 0.017325 0.015342 -0.097692 -v 0.017325 -0.014021 -0.097692 -v 0.017487 0.015342 -0.097457 -v 0.017487 -0.014021 -0.097457 -v 0.017588 -0.014021 -0.097191 -v 0.017588 0.015342 -0.097191 -v 0.017622 -0.014021 -0.096909 -v 0.017588 -0.014021 -0.096626 -v 0.017487 -0.014021 -0.096360 -v 0.017325 -0.014021 -0.096125 -v 0.017325 0.015342 -0.096125 -v 0.017112 -0.014021 -0.095937 -v 0.016860 0.015342 -0.095804 -v 0.016860 -0.014021 -0.095804 -v 0.016583 0.015342 -0.095736 -v 0.016583 -0.014021 -0.095736 -v 0.016298 0.015342 -0.095736 -v 0.016298 -0.014021 -0.095736 -v 0.016022 0.015342 -0.095804 -v 0.016022 -0.014021 -0.095804 -v 0.015770 -0.014021 -0.095937 -v 0.015557 0.015342 -0.096125 -v 0.015557 -0.014021 -0.096125 -v 0.015395 -0.014021 -0.096360 -v 0.015294 -0.014021 -0.096626 -v 0.015260 -0.014021 -0.096909 -v 0.015294 0.015342 -0.096626 -v 0.015260 0.015342 -0.096909 -v 0.015294 0.015342 -0.097191 -v 0.015770 0.015342 -0.097881 -v 0.015395 0.015342 -0.097457 -v 0.016583 0.015342 -0.098081 -v 0.017487 0.015342 -0.096360 -v 0.017588 0.015342 -0.096626 -v 0.017622 0.015342 -0.096909 -v 0.017112 0.015342 -0.095937 -v 0.015770 0.015342 -0.095937 -v 0.015395 0.015342 -0.096360 -v 0.037230 0.012294 -0.099565 -v 0.037259 0.012294 -0.097404 -v 0.035956 0.012294 -0.096836 -v 0.034760 0.012294 -0.097199 -v 0.034541 0.012294 -0.102281 -v 0.035705 0.012294 -0.100188 -v 0.038674 0.012294 -0.102291 -v 0.031917 0.012294 -0.099362 -v 0.034213 0.012294 -0.099088 -v 0.032730 0.012294 -0.101037 -v 0.016822 0.010716 -0.092000 -v 0.016822 0.002312 -0.092000 -v 0.016822 0.010716 -0.093575 -v 0.029862 0.010015 -0.093575 -v 0.030315 0.009662 -0.092000 -v 0.030633 0.009654 -0.093575 -v 0.031337 0.009837 -0.092000 -v 0.031715 0.010127 -0.093575 -v 0.031916 0.012294 -0.092000 -v 0.031916 0.010719 -0.093575 -v 0.034552 0.010719 -0.099778 -v 0.034628 0.010719 -0.102293 -v 0.038408 0.010719 -0.102295 -v 0.037274 0.010719 -0.099599 -v 0.034486 0.010719 -0.097497 -v 0.032636 0.010719 -0.100954 -v 0.031916 0.010719 -0.099216 -v 0.035878 0.010719 -0.096716 -v 0.037265 0.010719 -0.097491 -v 0.038354 -0.010719 -0.102300 -v 0.039840 -0.012293 -0.100959 -v 0.031916 -0.012293 -0.098727 -v 0.032730 -0.010719 -0.101037 -v 0.034628 -0.012293 -0.102293 -v 0.034616 -0.012293 -0.097304 -v 0.031916 -0.012293 -0.092000 -v 0.036251 -0.012293 -0.096769 -v 0.039841 -0.012293 -0.092000 -v 0.034552 -0.012293 -0.099778 -v 0.038408 -0.012293 -0.102295 -v 0.037274 -0.012293 -0.099599 -v 0.032636 -0.012293 -0.100954 -v 0.037279 -0.012293 -0.097562 -v 0.039839 0.010719 -0.100962 -v 0.039841 0.012294 -0.100318 -v 0.039841 -0.010719 -0.093575 -v 0.039840 -0.010719 -0.101010 -v 0.037233 -0.010719 -0.099565 -v 0.037442 -0.010719 -0.097885 -v 0.036812 -0.010719 -0.097053 -v 0.035705 -0.010719 -0.100188 -v 0.034541 -0.010719 -0.102281 -v 0.034960 -0.010719 -0.096995 -v 0.034213 -0.010719 -0.099088 -v 0.031918 -0.010719 -0.099369 -v 0.031207 -0.009694 -0.093575 -v 0.029721 -0.010167 -0.093575 -v 0.016822 -0.010715 -0.093575 -v 0.016822 -0.010715 -0.092000 -v 0.018715 -0.008558 -0.093575 -v 0.020098 -0.008959 -0.093575 -v 0.021850 -0.007369 -0.093575 -v 0.021615 -0.006230 -0.093575 -v 0.031916 -0.010719 -0.092000 -v 0.021121 -0.008691 -0.092000 -v 0.031912 0.010519 -0.092000 -v 0.020098 0.008960 -0.092000 -v 0.021615 0.006230 -0.092000 -v 0.029494 0.010716 -0.092000 -v 0.030429 -0.009672 -0.092000 -v 0.031149 -0.009726 -0.092000 -v 0.019554 -0.008945 -0.092000 -v 0.029721 0.010168 -0.092000 -v 0.018811 0.005647 -0.092000 -v 0.039841 0.012294 -0.092000 -v 0.031718 -0.010170 -0.092000 -v 0.021653 -0.006340 -0.092000 -v 0.021860 -0.007279 -0.092000 -v 0.018420 -0.008162 -0.092000 -v 0.016822 -0.002311 -0.092000 -v 0.018200 -0.006601 -0.092000 -v 0.019252 -0.005419 -0.092000 -v 0.029721 -0.010167 -0.092000 -v 0.018145 0.007094 -0.092000 -v 0.029505 -0.010715 -0.092000 -v 0.020830 -0.005457 -0.092000 -v 0.021850 0.007370 -0.092000 -v 0.016822 -0.002311 -0.093575 -v 0.019682 -0.002286 -0.094859 -v 0.019592 0.002286 -0.094892 -v 0.015535 -0.002286 -0.093758 -v 0.015535 0.002286 -0.093758 -v 0.018712 0.002286 -0.094914 -v 0.014996 -0.002286 -0.095238 -v 0.014996 0.002286 -0.095238 -v 0.023056 0.002312 -0.093575 -v 0.021656 0.002286 -0.095226 -v 0.020355 0.002286 -0.094337 -v 0.019195 0.002286 -0.096742 -v 0.022791 0.002312 -0.092000 -v 0.021798 0.002286 -0.092361 -v 0.021169 0.002286 -0.092943 -v 0.021144 -0.002286 -0.092981 -v 0.022791 -0.002311 -0.092000 -v 0.018803 -0.002286 -0.096615 -v 0.018735 -0.002286 -0.094922 -v 0.020362 -0.002286 -0.094321 -v 0.021732 -0.002286 -0.092405 -v 0.022385 -0.002286 -0.092103 -v 0.031916 -0.010719 -0.093575 -v 0.016822 0.002312 -0.093575 -v 0.031851 -0.010432 -0.093575 -v 0.039841 0.010719 -0.093575 -v 0.029494 -0.010715 -0.093575 -v 0.018812 -0.005647 -0.093575 -v 0.018145 -0.007093 -0.093575 -v 0.020098 -0.005328 -0.093575 -v 0.023056 -0.002311 -0.093575 -v 0.021417 -0.002286 -0.095595 -v 0.031286 0.009779 -0.093575 -v 0.019551 0.008944 -0.093575 -v 0.029505 0.010716 -0.093575 -v 0.030154 -0.009777 -0.093575 -v 0.020677 -0.005445 -0.093575 -v 0.021860 0.007279 -0.093575 -v 0.019249 0.005420 -0.093575 -v 0.021174 -0.008612 -0.093575 -v 0.018200 0.006600 -0.093575 -v 0.020098 0.005328 -0.092000 -v 0.020828 0.005456 -0.093575 -v 0.020852 0.005537 -0.092000 -v 0.021653 0.006340 -0.093575 -v 0.021120 0.008693 -0.093575 -v 0.021174 0.008613 -0.092000 -v 0.018420 0.008163 -0.093575 -v 0.018715 0.008559 -0.092000 -v 0.030002 -0.078947 0.132954 -v 0.027286 -0.076358 0.130636 -v 0.031025 -0.076670 0.131264 -v 0.027697 -0.078694 0.133057 -v 0.030531 -0.096868 0.111010 -v 0.030499 -0.097098 0.111224 -v 0.030405 -0.078194 0.131938 -v 0.030405 -0.097318 0.111430 -v 0.030251 -0.097520 0.111618 -v 0.030251 -0.078396 0.132127 -v 0.030046 -0.078571 0.132290 -v 0.029796 -0.078713 0.132422 -v 0.030046 -0.097696 0.111782 -v 0.029512 -0.078815 0.132517 -v 0.029796 -0.097837 0.111914 -v 0.029512 -0.097939 0.112009 -v 0.029206 -0.097997 0.112063 -v 0.029206 -0.078873 0.132571 -v 0.028890 -0.098009 0.112074 -v 0.028890 -0.078884 0.132582 -v 0.028578 -0.078849 0.132549 -v 0.028578 -0.097974 0.112041 -v 0.028281 -0.078769 0.132475 -v 0.028281 -0.097893 0.111966 -v 0.028013 -0.078647 0.132361 -v 0.027784 -0.078487 0.132212 -v 0.028013 -0.097771 0.111852 -v 0.027784 -0.097612 0.111704 -v 0.027604 -0.078298 0.132035 -v 0.027604 -0.097422 0.111527 -v 0.027479 -0.097210 0.111329 -v 0.027479 -0.078085 0.131837 -v 0.027415 -0.096983 0.111118 -v 0.027415 -0.077859 0.131626 -v 0.027415 -0.077628 0.131410 -v 0.027415 -0.096752 0.110902 -v 0.027479 -0.077401 0.131199 -v 0.027479 -0.096526 0.110691 -v 0.027604 -0.077189 0.131001 -v 0.027604 -0.096313 0.110493 -v 0.027784 -0.076999 0.130824 -v 0.027784 -0.096123 0.110316 -v 0.028013 -0.076840 0.130676 -v 0.028013 -0.095964 0.110167 -v 0.028281 -0.095842 0.110053 -v 0.028281 -0.076718 0.130562 -v 0.028578 -0.076637 0.130487 -v 0.028890 -0.076602 0.130454 -v 0.028578 -0.095762 0.109978 -v 0.028890 -0.095727 0.109946 -v 0.029206 -0.076614 0.130465 -v 0.029206 -0.095738 0.109957 -v 0.029512 -0.095796 0.110011 -v 0.029512 -0.076672 0.130519 -v 0.029796 -0.076774 0.130614 -v 0.029796 -0.095898 0.110106 -v 0.030046 -0.096040 0.110238 -v 0.030046 -0.076915 0.130746 -v 0.030251 -0.077091 0.130909 -v 0.030251 -0.096215 0.110401 -v 0.030405 -0.096417 0.110590 -v 0.030405 -0.077293 0.131098 -v 0.030499 -0.077513 0.131304 -v 0.030500 -0.096638 0.110795 -v 0.030531 -0.077743 0.131518 -v 0.030499 -0.077973 0.131733 -v 0.028572 -0.098745 0.112412 -v 0.030574 -0.097662 0.110224 -v 0.030122 -0.095618 0.109613 -v 0.027016 -0.096129 0.109939 -v 0.037814 -0.097795 0.111712 -v 0.037701 -0.099390 0.112950 -v 0.033990 -0.099692 0.112819 -v 0.036093 -0.097152 0.110445 -v 0.034715 -0.096984 0.111118 -v 0.034280 -0.080153 0.134204 -v 0.034034 -0.078151 0.132141 -v 0.035957 -0.078201 0.133851 -v 0.036973 -0.077498 0.131701 -v 0.037830 -0.079900 0.133727 -v 0.014400 -0.078232 0.132521 -v 0.015535 -0.076504 0.130834 -v 0.018136 -0.076838 0.131313 -v 0.016987 -0.076659 0.130506 -v 0.017551 -0.079267 0.132939 -v 0.017506 -0.078936 0.133383 -v 0.059038 -0.081037 0.128718 -v 0.058898 -0.078992 0.126702 -v 0.056784 -0.078378 0.126841 -v 0.056177 -0.081437 0.128993 -v 0.055161 -0.079759 0.127295 -v 0.058856 -0.092969 0.113872 -v 0.058833 -0.093162 0.114052 -v 0.058766 -0.093350 0.114227 -v 0.058766 -0.080639 0.127857 -v 0.058657 -0.080816 0.128022 -v 0.058509 -0.080976 0.128172 -v 0.058657 -0.093526 0.114392 -v 0.058509 -0.093687 0.114541 -v 0.058326 -0.081116 0.128302 -v 0.058113 -0.081231 0.128410 -v 0.058326 -0.093827 0.114672 -v 0.058113 -0.093942 0.114779 -v 0.057876 -0.081319 0.128491 -v 0.057876 -0.094029 0.114861 -v 0.057623 -0.094086 0.114914 -v 0.057623 -0.081375 0.128544 -v 0.057360 -0.081400 0.128567 -v 0.057360 -0.094110 0.114937 -v 0.057095 -0.081392 0.128559 -v 0.057095 -0.094102 0.114929 -v 0.056836 -0.081351 0.128521 -v 0.056590 -0.081279 0.128454 -v 0.056836 -0.094061 0.114891 -v 0.056590 -0.093989 0.114823 -v 0.056365 -0.093888 0.114729 -v 0.056365 -0.081177 0.128359 -v 0.056166 -0.081049 0.128240 -v 0.056166 -0.093760 0.114609 -v 0.055999 -0.080898 0.128099 -v 0.055999 -0.093609 0.114469 -v 0.055870 -0.080729 0.127941 -v 0.055870 -0.093440 0.114311 -v 0.055782 -0.080546 0.127771 -v 0.055782 -0.093257 0.114141 -v 0.055737 -0.080355 0.127593 -v 0.055737 -0.093066 0.113962 -v 0.055737 -0.080162 0.127412 -v 0.055782 -0.079971 0.127234 -v 0.055737 -0.092872 0.113782 -v 0.055782 -0.092681 0.113604 -v 0.055870 -0.092498 0.113433 -v 0.055870 -0.079788 0.127064 -v 0.055999 -0.092329 0.113276 -v 0.055999 -0.079619 0.126906 -v 0.056166 -0.092179 0.113135 -v 0.056166 -0.079468 0.126765 -v 0.056365 -0.079340 0.126646 -v 0.056365 -0.092051 0.113016 -v 0.056590 -0.079238 0.126551 -v 0.056836 -0.079166 0.126484 -v 0.056590 -0.091949 0.112921 -v 0.056836 -0.091877 0.112853 -v 0.057095 -0.091836 0.112815 -v 0.057095 -0.079125 0.126446 -v 0.057360 -0.079117 0.126438 -v 0.057360 -0.091828 0.112808 -v 0.057623 -0.091852 0.112831 -v 0.057623 -0.079142 0.126461 -v 0.057876 -0.079198 0.126514 -v 0.057876 -0.091909 0.112884 -v 0.058113 -0.091996 0.112965 -v 0.058113 -0.079286 0.126595 -v 0.058326 -0.079401 0.126703 -v 0.058326 -0.092111 0.113072 -v 0.058509 -0.079541 0.126833 -v 0.058509 -0.092251 0.113203 -v 0.058657 -0.092412 0.113353 -v 0.058657 -0.079701 0.126983 -v 0.058766 -0.092588 0.113517 -v 0.058766 -0.079878 0.127148 -v 0.058833 -0.092776 0.113692 -v 0.058833 -0.080065 0.127323 -v 0.058856 -0.080258 0.127503 -v 0.058833 -0.080452 0.127683 -v 0.055285 -0.092132 0.112729 -v 0.057724 -0.094884 0.115351 -v 0.059128 -0.092220 0.112857 -v 0.057240 -0.093971 0.112941 -v 0.059363 -0.092846 0.113757 -v 0.061029 -0.089421 0.114554 -v 0.064926 -0.083606 0.120789 -v 0.058224 -0.080759 0.123842 -v 0.063418 -0.090503 0.113393 -v 0.061029 -0.080759 0.123842 -v 0.069900 -0.088787 0.115233 -v 0.061763 -0.080122 0.124525 -v 0.063373 -0.079678 0.125002 -v 0.069532 -0.080683 0.123925 -v 0.069900 -0.081842 0.122681 -v 0.067420 -0.079681 0.124998 -v 0.067347 -0.082017 0.122494 -v 0.067141 -0.082988 0.121453 -v 0.067134 -0.090503 0.113394 -v 0.068743 -0.090057 0.113872 -v 0.065942 -0.082509 0.119731 -v 0.064098 -0.082202 0.120061 -v 0.061029 -0.079645 0.122803 -v 0.069899 -0.087825 0.114032 -v 0.069899 -0.080274 0.122129 -v 0.068743 -0.079009 0.123485 -v 0.067130 -0.078563 0.123963 -v 0.061762 -0.088943 0.112832 -v 0.067747 -0.089382 0.112361 -v 0.065403 -0.085379 0.116653 -v 0.061029 -0.088306 0.113515 -v 0.061865 -0.090111 0.113814 -v 0.063370 -0.089388 0.112355 -v 0.057326 -0.094440 0.119234 -v 0.055403 -0.093538 0.118393 -v 0.056327 -0.092638 0.117554 -v 0.056087 -0.092423 0.117354 -v 0.054795 -0.093015 0.117906 -v 0.055893 -0.092185 0.117132 -v 0.058224 -0.088306 0.113515 -v 0.054178 -0.090714 0.115760 -v 0.055704 -0.090835 0.115873 -v 0.054300 -0.090382 0.115450 -v 0.054472 -0.090062 0.115152 -v 0.056004 -0.090327 0.115399 -v 0.056226 -0.090102 0.115190 -v 0.054363 -0.092406 0.117337 -v 0.055655 -0.091660 0.116642 -v 0.054220 -0.092078 0.117032 -v 0.055617 -0.091384 0.116385 -v 0.054093 -0.091398 0.116397 -v 0.055633 -0.091107 0.116127 -v 0.054109 -0.091054 0.116077 -v 0.056490 -0.089904 0.115004 -v 0.056791 -0.089735 0.114847 -v 0.055616 -0.088984 0.114147 -v 0.055997 -0.088783 0.113959 -v 0.057122 -0.089600 0.114721 -v 0.057476 -0.089501 0.114629 -v 0.056327 -0.083977 0.126842 -v 0.056727 -0.092899 0.117797 -v 0.056087 -0.083762 0.126642 -v 0.055748 -0.091929 0.116893 -v 0.055748 -0.083268 0.126181 -v 0.055829 -0.090573 0.115629 -v 0.056791 -0.081073 0.124135 -v 0.057122 -0.080938 0.124009 -v 0.057846 -0.089441 0.114573 -v 0.058224 -0.089421 0.114554 -v 0.056744 -0.084244 0.127091 -v 0.055945 -0.085194 0.127977 -v 0.055403 -0.084876 0.127681 -v 0.055655 -0.082999 0.125930 -v 0.054220 -0.083416 0.126320 -v 0.054363 -0.083744 0.126626 -v 0.054555 -0.084058 0.126918 -v 0.055893 -0.083524 0.126420 -v 0.055079 -0.084628 0.127450 -v 0.057846 -0.080780 0.123861 -v 0.055633 -0.082446 0.125415 -v 0.055617 -0.082723 0.125673 -v 0.054093 -0.082736 0.125686 -v 0.054130 -0.083079 0.126005 -v 0.054960 -0.080814 0.123893 -v 0.056226 -0.081441 0.124478 -v 0.056004 -0.081666 0.124687 -v 0.054693 -0.081097 0.124157 -v 0.055829 -0.081912 0.124917 -v 0.055704 -0.082174 0.125161 -v 0.054300 -0.081720 0.124738 -v 0.057755 -0.079664 0.122821 -v 0.057292 -0.079723 0.122876 -v 0.057476 -0.080840 0.123917 -v 0.056490 -0.081242 0.124292 -v 0.055616 -0.080323 0.123435 -v 0.061865 -0.078954 0.123543 -v 0.063413 -0.078563 0.123963 -v 0.058224 -0.079645 0.122803 -v 0.057755 -0.088326 0.113533 -v 0.057292 -0.088384 0.113587 -v 0.056840 -0.088481 0.113677 -v 0.056840 -0.079819 0.122966 -v 0.056407 -0.088614 0.113802 -v 0.056407 -0.079953 0.123090 -v 0.055997 -0.080121 0.123247 -v 0.055269 -0.089216 0.114363 -v 0.054960 -0.089475 0.114605 -v 0.055269 -0.080555 0.123651 -v 0.054693 -0.089758 0.114869 -v 0.054472 -0.081400 0.124440 -v 0.054178 -0.082053 0.125048 -v 0.054109 -0.082393 0.125365 -v 0.054130 -0.091740 0.116717 -v 0.054555 -0.092719 0.117630 -v 0.054795 -0.084354 0.127194 -v 0.055079 -0.093289 0.118161 -v 0.055905 -0.093836 0.118672 -v 0.057326 -0.085778 0.128522 -v 0.058088 -0.093474 0.118334 -v 0.058088 -0.084813 0.127622 -v 0.067369 -0.087649 0.116454 -v 0.066993 -0.088591 0.115444 -v 0.065794 -0.087948 0.113899 -v 0.065404 -0.089092 0.114908 -v 0.063873 -0.087417 0.114468 -v 0.063717 -0.088278 0.115779 -v 0.064134 -0.086898 0.117260 -v 0.063913 -0.086007 0.115980 -v 0.065479 -0.086533 0.117650 -v 0.066704 -0.086796 0.117369 -v 0.067010 -0.085895 0.116100 -v 0.067319 -0.087165 0.114739 -v 0.067318 -0.081761 0.120533 -v 0.066346 -0.083526 0.120876 -v 0.064117 -0.083190 0.121236 -v 0.063667 -0.082528 0.121945 -v 0.063813 -0.080691 0.121681 -v 0.063969 -0.081683 0.122852 -v 0.065404 -0.079974 0.122449 -v 0.065634 -0.081047 0.123534 -v 0.066993 -0.080475 0.121913 -v 0.013781 -0.085628 0.122269 -v 0.017516 -0.084592 0.122389 -v 0.013774 -0.084870 0.122776 -v 0.014986 -0.087639 0.120203 -v 0.017937 -0.089508 0.120624 -v 0.014947 -0.089330 0.121089 -v 0.014460 -0.088108 0.119678 -v 0.015342 -0.089452 0.122049 -v 0.016582 -0.087120 0.118650 -v 0.016177 -0.090441 0.121367 -v 0.018414 -0.089540 0.121083 -v 0.017795 -0.087395 0.119731 -v 0.017144 -0.087370 0.118932 -v 0.014611 -0.087471 0.119741 -v 0.016556 -0.090049 0.121828 -v 0.018510 -0.089477 0.120232 -v 0.017369 -0.087888 0.118436 -v 0.014339 -0.089333 0.120071 -v 0.014689 -0.088676 0.120338 -v 0.018160 -0.088600 0.120674 -v 0.018446 -0.087580 0.120296 -v 0.016571 -0.087033 0.119932 -v 0.018154 -0.088647 0.121599 -v 0.015211 -0.086427 0.119778 -v 0.015025 -0.089221 0.121821 -v 0.016532 -0.088983 0.122812 -v 0.015430 -0.086991 0.119534 -v 0.015577 -0.088697 0.122391 -v 0.017205 -0.089232 0.121638 -v 0.018413 -0.088584 0.122151 -v 0.015418 -0.088925 0.121808 -v 0.014347 -0.087192 0.122231 -v 0.018715 -0.086947 0.121707 -v 0.015739 -0.085667 0.120489 -v 0.017959 -0.087464 0.123135 -v 0.014311 -0.087139 0.121527 -v 0.017514 -0.086067 0.121294 -v 0.016097 -0.089232 0.122969 -v 0.016260 -0.086641 0.120410 -v 0.018455 -0.086912 0.120346 -v 0.014674 -0.087136 0.120593 -v 0.015552 -0.088442 0.123504 -v 0.014320 -0.087288 0.121707 -v 0.018355 -0.085603 0.121547 -v 0.017279 -0.086036 0.120979 -v 0.016493 -0.085080 0.122138 -v 0.016339 -0.088657 0.123153 -v 0.018189 -0.086935 0.120979 -v 0.018531 -0.086722 0.121847 -v 0.016511 -0.084513 0.121767 -v 0.015333 -0.087463 0.123523 -v 0.017085 -0.087247 0.124545 -v 0.015541 -0.087903 0.124156 -v 0.015298 -0.085450 0.121593 -v 0.017936 -0.086514 0.122503 -v 0.016905 -0.085200 0.121243 -v 0.014233 -0.086396 0.122434 -v 0.016405 -0.085556 0.120746 -v 0.018580 -0.085963 0.123027 -v 0.016982 -0.087309 0.124037 -v 0.016561 -0.088306 0.123991 -v 0.014588 -0.086253 0.123364 -v 0.018504 -0.085961 0.122613 -v 0.014849 -0.087937 0.123328 -v 0.010535 -0.092006 0.122794 -v 0.010365 -0.091711 0.122425 -v 0.010554 -0.092379 0.122416 -v 0.017460 -0.090408 0.120465 -v 0.017525 -0.090388 0.120961 -v 0.016565 -0.090060 0.120862 -v 0.010381 -0.092027 0.122132 -v 0.013717 -0.082778 0.120878 -v 0.013864 -0.083298 0.120316 -v 0.017585 -0.077932 0.126068 -v 0.015171 -0.077783 0.125929 -v 0.015462 -0.079243 0.127290 -v 0.016876 -0.077783 0.125929 -v 0.018392 -0.078543 0.126639 -v 0.017228 -0.079454 0.127487 -v 0.017926 -0.080409 0.128379 -v 0.018841 -0.080387 0.128357 -v 0.017709 -0.079909 0.127911 -v 0.016331 -0.079170 0.127223 -v 0.015171 -0.082795 0.124004 -v 0.015306 -0.076486 0.125275 -v 0.015363 -0.076506 0.125293 -v 0.015350 -0.079749 0.121164 -v 0.014562 -0.079934 0.121336 -v 0.014409 -0.077007 0.125243 -v 0.016535 -0.080893 0.122230 -v 0.016916 -0.080410 0.121780 -v 0.016916 -0.076947 0.125494 -v 0.016535 -0.077435 0.125937 -v 0.016725 -0.077083 0.125832 -v 0.015170 -0.076921 0.125334 -v 0.015171 -0.080317 0.121693 -v 0.015171 -0.079479 0.127510 -v 0.016512 -0.081724 0.129643 -v 0.015174 -0.084288 0.125397 -v 0.015171 -0.080791 0.128772 -v 0.015331 -0.081127 0.129376 -v 0.014805 -0.076218 0.125070 -v 0.015321 -0.076281 0.124860 -v 0.014480 -0.076563 0.125212 -v 0.016371 -0.082191 0.130260 -v 0.015567 -0.081905 0.130293 -v 0.014409 -0.080791 0.128772 -v 0.014409 -0.084341 0.125445 -v 0.014529 -0.081210 0.129359 -v 0.014977 -0.085156 0.126214 -v 0.016617 -0.085601 0.126623 -v 0.015416 -0.082548 0.123774 -v 0.016384 -0.085051 0.126107 -v 0.017949 -0.083716 0.124862 -v 0.014409 -0.080317 0.121693 -v 0.015171 -0.081074 0.122399 -v 0.015740 -0.085496 0.126522 -v 0.015613 -0.084821 0.125895 -v 0.018841 -0.083678 0.124828 -v 0.018402 -0.081865 0.123137 -v 0.016353 -0.082459 0.123690 -v 0.016901 -0.081075 0.122400 -v 0.019018 -0.084924 0.125989 -v 0.017654 -0.081252 0.122566 -v 0.017146 -0.082709 0.123924 -v 0.017675 -0.083134 0.124320 -v 0.018434 -0.084788 0.125861 -v 0.018549 -0.081462 0.129398 -v 0.019648 -0.088399 0.132911 -v 0.019715 -0.087954 0.133633 -v 0.019878 -0.088605 0.133103 -v 0.019960 -0.099223 0.121751 -v 0.020002 -0.088627 0.133124 -v 0.019645 -0.099127 0.118188 -v 0.019805 -0.099178 0.121707 -v 0.019692 -0.099087 0.121623 -v 0.019272 -0.098917 0.118509 -v 0.020113 -0.100015 0.120614 -v 0.019648 -0.099000 0.121542 -v 0.019832 -0.099421 0.118462 -v 0.018844 -0.095204 0.114817 -v 0.019220 -0.095491 0.115314 -v 0.019133 -0.095464 0.114976 -v 0.019521 -0.099159 0.118258 -v 0.018470 -0.095740 0.115241 -v 0.019484 -0.099678 0.118943 -v 0.018470 -0.081874 0.130111 -v 0.018470 -0.092277 0.118954 -v 0.018470 -0.085348 0.126385 -v 0.018726 -0.081516 0.129958 -v 0.019272 -0.085368 0.133040 -v 0.019046 -0.081718 0.130129 -v 0.019180 -0.081777 0.129692 -v 0.020023 -0.085271 0.132949 -v 0.019976 -0.085825 0.133960 -v 0.020179 -0.088602 0.133101 -v 0.020227 -0.099183 0.121712 -v 0.020394 -0.087943 0.133497 -v 0.020398 -0.098903 0.121452 -v 0.020402 -0.098975 0.121519 -v 0.019650 -0.099127 0.118187 -v 0.020358 -0.099078 0.121615 -v 0.020023 -0.098821 0.118419 -v 0.019220 -0.085252 0.126295 -v 0.020398 -0.088302 0.132820 -v 0.019220 -0.092181 0.118864 -v 0.015171 -0.093099 0.113122 -v 0.015171 -0.089732 0.116581 -v 0.015403 -0.089480 0.116346 -v 0.015171 -0.091295 0.111439 -v 0.015322 -0.092792 0.112836 -v 0.016369 -0.092682 0.112733 -v 0.018841 -0.093899 0.113868 -v 0.017652 -0.091473 0.111605 -v 0.017949 -0.093936 0.113902 -v 0.017675 -0.093355 0.113360 -v 0.017147 -0.092931 0.112964 -v 0.018841 -0.090607 0.117397 -v 0.018399 -0.092082 0.112173 -v 0.018441 -0.088951 0.115853 -v 0.018071 -0.088438 0.115374 -v 0.016901 -0.091295 0.111439 -v 0.016018 -0.095397 0.114891 -v 0.015170 -0.094552 0.114136 -v 0.016724 -0.095776 0.115059 -v 0.016595 -0.095263 0.115102 -v 0.014792 -0.094599 0.113964 -v 0.015306 -0.090552 0.110191 -v 0.015363 -0.090572 0.110209 -v 0.016683 -0.091213 0.110786 -v 0.014409 -0.090556 0.110713 -v 0.015350 -0.086678 0.113734 -v 0.016916 -0.087339 0.114350 -v 0.015438 -0.090093 0.110146 -v 0.016535 -0.091199 0.111178 -v 0.016916 -0.090765 0.110676 -v 0.015170 -0.090700 0.110557 -v 0.015363 -0.094963 0.114632 -v 0.018395 -0.095032 0.114886 -v 0.019059 -0.091905 0.118607 -v 0.016535 -0.087822 0.114800 -v 0.015171 -0.088003 0.114969 -v 0.015171 -0.087246 0.114263 -v 0.014409 -0.087246 0.114263 -v 0.014563 -0.086863 0.113905 -v 0.015173 -0.091297 0.118040 -v 0.015624 -0.091742 0.118455 -v 0.017126 -0.088008 0.114973 -v 0.017452 -0.089831 0.116673 -v 0.016460 -0.089391 0.116263 -v 0.018522 -0.091706 0.118421 -v 0.017946 -0.090620 0.117407 -v 0.016302 -0.091990 0.118686 -v 0.016743 -0.092509 0.119168 -v 0.014409 -0.091030 0.117791 -v 0.014435 -0.094717 0.114361 -v 0.014566 -0.091666 0.118383 -v 0.015955 -0.095965 0.115412 -v 0.015538 -0.092387 0.119055 -v 0.014731 -0.095430 0.114742 -v 0.014409 -0.094340 0.114241 -v 0.016739 -0.095872 0.115165 -v 0.014647 -0.090387 0.110054 -v 0.015040 -0.090229 0.109958 -v 0.056401 -0.078482 0.125777 -v 0.058761 -0.082903 0.127815 -v 0.059863 -0.081671 0.126667 -v 0.054624 -0.083993 0.128832 -v 0.044103 -0.085268 0.130021 -v 0.042272 -0.085297 0.130047 -v 0.033341 -0.085297 0.130047 -v 0.057300 -0.080072 0.125175 -v 0.056300 -0.079571 0.124708 -v 0.055616 -0.081442 0.126453 -v 0.057905 -0.079512 0.124654 -v 0.059362 -0.080169 0.125266 -v 0.056638 -0.082409 0.127355 -v 0.059054 -0.081764 0.126753 -v 0.042272 -0.084257 0.131163 -v 0.044103 -0.084228 0.131136 -v 0.046706 -0.085136 0.129897 -v 0.047005 -0.084073 0.130991 -v 0.050339 -0.084746 0.129534 -v 0.058531 -0.081948 0.129010 -v 0.032947 -0.084257 0.131163 -v 0.052439 -0.080541 0.127698 -v 0.032947 -0.080541 0.127698 -v 0.056069 -0.079275 0.126517 -v 0.050622 -0.083666 0.130612 -v 0.059615 -0.079464 0.126694 -v 0.058408 -0.078589 0.125876 -v 0.055758 -0.080549 0.127705 -v 0.055950 -0.080918 0.128050 -v 0.056983 -0.081451 0.128547 -v 0.054179 -0.083036 0.130025 -v 0.059790 -0.080847 0.127982 -v 0.059202 -0.080288 0.127462 -v 0.052439 -0.081581 0.126583 -v 0.052439 -0.092144 0.115256 -v 0.052439 -0.093218 0.114104 -v 0.031768 -0.092751 0.114605 -v 0.031767 -0.081096 0.127103 -v 0.033341 -0.081581 0.126583 -v 0.033341 -0.092144 0.115256 -v 0.050330 -0.096384 0.117057 -v 0.052420 -0.094980 0.117900 -v 0.054628 -0.095630 0.116353 -v 0.046692 -0.096773 0.117420 -v 0.044103 -0.096905 0.117542 -v 0.042272 -0.096933 0.117569 -v 0.033341 -0.093218 0.114104 -v 0.033341 -0.096933 0.117569 -v 0.056298 -0.091208 0.112230 -v 0.055617 -0.093079 0.113974 -v 0.059866 -0.092525 0.113458 -v 0.057914 -0.091684 0.112674 -v 0.056638 -0.094046 0.114876 -v 0.059428 -0.094029 0.114861 -v 0.058651 -0.093741 0.114592 -v 0.058478 -0.094621 0.115414 -v 0.058338 -0.091220 0.112241 -v 0.059935 -0.091980 0.115103 -v 0.049564 -0.095405 0.118297 -v 0.055949 -0.092520 0.115606 -v 0.047005 -0.095675 0.118549 -v 0.056543 -0.090013 0.113269 -v 0.055951 -0.091114 0.114296 -v 0.058964 -0.092319 0.115420 -v 0.058818 -0.093443 0.116468 -v 0.056982 -0.093054 0.116104 -v 0.055938 -0.094240 0.117210 -v 0.058965 -0.090430 0.113657 -v 0.058009 -0.090806 0.114009 -v 0.033341 -0.095859 0.118720 -v 0.042272 -0.095859 0.118721 -v 0.055758 -0.092151 0.115263 -v 0.044103 -0.095831 0.118694 -v 0.048172 -0.090521 0.114538 -v 0.048172 -0.080820 0.124941 -v 0.048172 -0.085743 0.129531 -v 0.047410 -0.086022 0.129791 -v 0.047661 -0.086440 0.130181 -v 0.047874 -0.086306 0.130056 -v 0.048137 -0.085947 0.129721 -v 0.047410 -0.092918 0.113300 -v 0.046884 -0.092717 0.112071 -v 0.023331 -0.092606 0.111967 -v 0.046267 -0.092086 0.112525 -v 0.046267 -0.078921 0.126643 -v 0.030604 -0.080463 0.128081 -v 0.030395 -0.080095 0.127738 -v 0.046267 -0.079478 0.127162 -v 0.030087 -0.079814 0.127475 -v 0.047407 -0.079253 0.126952 -v 0.027225 -0.080762 0.128360 -v 0.023331 -0.079478 0.127162 -v 0.030623 -0.080854 0.128446 -v 0.047410 -0.084289 0.131649 -v 0.029501 -0.079564 0.127243 -v 0.027870 -0.079780 0.127444 -v 0.030313 -0.081452 0.129002 -v 0.030546 -0.081111 0.128685 -v 0.028068 -0.081797 0.129325 -v 0.029239 -0.081923 0.129443 -v 0.029800 -0.081784 0.129312 -v 0.047410 -0.079233 0.127976 -v 0.023331 -0.078401 0.127200 -v 0.027479 -0.079509 0.128233 -v 0.027531 -0.080869 0.129500 -v 0.030084 -0.079292 0.128031 -v 0.047410 -0.084327 0.132726 -v 0.030491 -0.080711 0.129354 -v 0.030076 -0.081120 0.129735 -v 0.029585 -0.081333 0.129934 -v 0.028558 -0.081408 0.130005 -v 0.029431 -0.079023 0.127780 -v 0.030493 -0.079699 0.128410 -v 0.030623 -0.080335 0.129003 -v 0.030623 -0.080072 0.128758 -v 0.046267 -0.078401 0.127200 -v 0.023331 -0.098532 0.117493 -v 0.023331 -0.084327 0.132726 -v 0.023331 -0.084289 0.131649 -v 0.047410 -0.080820 0.124941 -v 0.048036 -0.095839 0.119497 -v 0.047410 -0.095722 0.119388 -v 0.047410 -0.096232 0.119864 -v 0.047410 -0.090521 0.114538 -v 0.048172 -0.095444 0.119129 -v 0.048137 -0.095648 0.119319 -v 0.047661 -0.096140 0.119778 -v 0.047874 -0.096007 0.119653 -v 0.048036 -0.086138 0.129900 -v 0.047410 -0.086531 0.130266 -v 0.027633 -0.095269 0.114451 -v 0.047410 -0.098532 0.117493 -v 0.047410 -0.093438 0.112743 -v 0.030594 -0.094669 0.113892 -v 0.046267 -0.092606 0.111967 -v 0.030391 -0.094619 0.114887 -v 0.030063 -0.095396 0.114568 -v 0.029059 -0.095623 0.114781 -v 0.027176 -0.094372 0.114655 -v 0.027703 -0.093461 0.112765 -v 0.029414 -0.092716 0.113112 -v 0.029236 -0.093214 0.112535 -v 0.030527 -0.093326 0.113680 -v 0.030392 -0.093677 0.112967 -v 0.023331 -0.092643 0.113044 -v 0.047089 -0.092266 0.112692 -v 0.046267 -0.092643 0.113044 -v 0.028122 -0.092802 0.113192 -v 0.023331 -0.097455 0.117531 -v 0.029161 -0.095085 0.115322 -v 0.047410 -0.097455 0.117531 -v 0.013647 -0.094520 0.110539 -v 0.014488 -0.093565 0.109649 -v 0.014808 -0.094316 0.108630 -v 0.035878 -0.094211 0.108533 -v 0.038109 -0.093845 0.109910 -v 0.039829 -0.100321 0.114230 -v 0.034099 -0.101177 0.115029 -v 0.033096 -0.100964 0.114829 -v 0.031112 -0.099434 0.115122 -v 0.013576 -0.100643 0.115601 -v 0.011837 -0.099157 0.115053 -v 0.005232 -0.101296 0.114775 -v 0.007276 -0.101994 0.115426 -v 0.006868 -0.100920 0.114424 -v 0.008535 -0.100626 0.114149 -v 0.000017 -0.101896 0.120543 -v 0.002132 -0.103377 0.117021 -v 0.002898 -0.103217 0.116599 -v 0.002434 -0.102158 0.115578 -v 0.000017 -0.087604 0.135869 -v -0.000855 -0.086690 0.135016 -v 0.001444 -0.084761 0.137564 -v 0.002255 -0.084114 0.137580 -v 0.001561 -0.083080 0.136698 -v 0.013647 -0.100950 0.115272 -v 0.013640 -0.082419 0.135143 -v 0.012318 -0.083133 0.134430 -v 0.012773 -0.100128 0.116173 -v 0.011493 -0.100481 0.115915 -v 0.010867 -0.082309 0.135502 -v 0.010197 -0.101542 0.115003 -v 0.010427 -0.082054 0.135857 -v 0.010867 -0.101160 0.115286 -v 0.000316 -0.086153 0.137114 -v 0.000686 -0.086214 0.136700 -v 0.000807 -0.103244 0.118321 -v 0.001369 -0.103376 0.117669 -v 0.000116 -0.102599 0.119687 -v 0.003179 -0.083641 0.137384 -v 0.003317 -0.103083 0.116441 -v 0.004237 -0.102777 0.116155 -v 0.005738 -0.102348 0.115755 -v 0.008843 -0.101717 0.115167 -v 0.008843 -0.082229 0.136066 -v 0.006868 -0.081432 0.135323 -v 0.007276 -0.082506 0.136324 -v 0.005738 -0.082860 0.136654 -v 0.005232 -0.081808 0.135673 -v 0.004237 -0.083289 0.137054 -v 0.010147 -0.082060 0.135908 -v 0.011023 -0.081320 0.134793 -v 0.013324 -0.082861 0.134673 -v 0.012883 -0.083047 0.134489 -v 0.011533 -0.082895 0.134768 -v 0.011347 -0.081537 0.134009 -v 0.031109 -0.082053 0.135537 -v 0.031109 -0.084307 0.133120 -v 0.032308 -0.081763 0.133548 -v 0.038249 -0.082909 0.134616 -v 0.038298 -0.082051 0.135535 -v 0.039098 -0.076279 0.130152 -v 0.037328 -0.076116 0.128280 -v 0.035878 -0.075944 0.128121 -v 0.027306 -0.077743 0.131518 -v 0.013647 -0.080938 0.134498 -v 0.015668 -0.078713 0.132422 -v 0.017582 -0.078227 0.131969 -v 0.027611 -0.078460 0.132185 -v 0.017510 -0.077600 0.131384 -v 0.027362 -0.078058 0.131812 -v 0.017622 -0.078003 0.131761 -v 0.028148 -0.078802 0.132505 -v 0.030611 -0.077399 0.131197 -v 0.034421 -0.078516 0.132239 -v 0.030453 -0.078343 0.132077 -v 0.017464 -0.078435 0.132163 -v 0.029644 -0.078868 0.132568 -v 0.017276 -0.078614 0.132330 -v 0.036567 -0.080313 0.133914 -v 0.033460 -0.082051 0.135535 -v 0.015602 -0.077325 0.131128 -v 0.016731 -0.077195 0.131007 -v 0.027362 -0.077428 0.131224 -v 0.037491 -0.075280 0.129221 -v 0.027624 -0.077013 0.130837 -v 0.037205 -0.078339 0.132074 -v 0.039834 -0.077476 0.131268 -v 0.037516 -0.079487 0.133144 -v 0.039836 -0.081148 0.134694 -v 0.035023 -0.080221 0.133829 -v 0.013647 -0.082053 0.135537 -v 0.035892 -0.077909 0.131673 -v 0.035878 -0.075087 0.129041 -v 0.016991 -0.078770 0.132476 -v 0.016441 -0.078867 0.132566 -v 0.034214 -0.079150 0.132830 -v 0.034271 -0.079465 0.133124 -v 0.032377 -0.080946 0.134504 -v 0.015628 -0.075087 0.129041 -v 0.028232 -0.076647 0.130495 -v 0.028969 -0.076527 0.130383 -v 0.035046 -0.078097 0.131848 -v 0.014143 -0.075445 0.129376 -v 0.013647 -0.076536 0.130392 -v 0.039829 -0.082054 0.133819 -v 0.017464 -0.078429 0.130438 -v 0.017598 -0.079104 0.131069 -v 0.031109 -0.081796 0.133578 -v 0.031116 -0.081178 0.134721 -v 0.027408 -0.078155 0.130183 -v 0.017582 -0.078637 0.130633 -v 0.027307 -0.078759 0.130746 -v 0.039838 -0.078393 0.130405 -v 0.037574 -0.079563 0.131495 -v 0.030459 -0.079201 0.131158 -v 0.034386 -0.079349 0.131295 -v 0.033404 -0.082904 0.134612 -v 0.034244 -0.080320 0.132202 -v 0.030584 -0.078242 0.130264 -v 0.029308 -0.079829 0.131745 -v 0.035200 -0.078885 0.130864 -v 0.035218 -0.081177 0.133000 -v 0.036939 -0.081001 0.132837 -v 0.038997 -0.077009 0.129116 -v 0.029847 -0.077533 0.129603 -v 0.027918 -0.077642 0.129705 -v 0.014806 -0.076050 0.128220 -v 0.015828 -0.078026 0.130062 -v 0.015628 -0.075944 0.128121 -v 0.017276 -0.078250 0.130271 -v 0.027650 -0.079365 0.131311 -v 0.013648 -0.076942 0.129052 -v 0.015589 -0.079559 0.131491 -v 0.017140 -0.079570 0.131503 -v 0.013647 -0.099205 0.114909 -v 0.018022 -0.083193 0.132080 -v 0.034958 -0.098459 0.114213 -v 0.015633 -0.096952 0.112807 -v 0.027362 -0.095695 0.111636 -v 0.035193 -0.096297 0.112197 -v 0.039834 -0.095741 0.111678 -v 0.039836 -0.099415 0.115105 -v 0.037236 -0.098194 0.113966 -v 0.038297 -0.100318 0.115946 -v 0.016441 -0.097134 0.112977 -v 0.034282 -0.097761 0.113562 -v 0.037428 -0.096810 0.112674 -v 0.031109 -0.099205 0.114909 -v 0.015513 -0.095635 0.111580 -v 0.015628 -0.093354 0.109452 -v 0.027623 -0.095280 0.111248 -v 0.016441 -0.095406 0.111366 -v 0.027306 -0.096010 0.111929 -v 0.017336 -0.095680 0.111622 -v 0.034394 -0.096818 0.112683 -v 0.030453 -0.096609 0.112489 -v 0.028148 -0.097069 0.112917 -v 0.029642 -0.097136 0.112979 -v 0.027362 -0.096325 0.112223 -v 0.017622 -0.096160 0.112069 -v 0.017582 -0.096494 0.112380 -v 0.034214 -0.097417 0.113241 -v 0.035878 -0.093354 0.109452 -v 0.028376 -0.094851 0.110849 -v 0.027611 -0.096725 0.112597 -v 0.017464 -0.096702 0.112575 -v 0.017276 -0.096881 0.112741 -v 0.016991 -0.097037 0.112887 -v 0.032377 -0.099213 0.114916 -v 0.029679 -0.094901 0.110896 -v 0.030314 -0.095277 0.111245 -v 0.036850 -0.093432 0.109525 -v 0.030608 -0.095797 0.111730 -v 0.039099 -0.094546 0.110563 -v 0.036309 -0.098593 0.114337 -v 0.033460 -0.100318 0.115946 -v 0.031109 -0.097809 0.116407 -v 0.018022 -0.097809 0.116407 -v 0.031109 -0.083193 0.132080 -v 0.018022 -0.084307 0.133120 -v 0.018022 -0.098923 0.117446 -v 0.031109 -0.098923 0.117446 -v 0.017464 -0.097560 0.111655 -v 0.039167 -0.095474 0.109710 -v 0.037674 -0.094466 0.108771 -v 0.028378 -0.095709 0.109929 -v 0.015988 -0.097954 0.112024 -v 0.030610 -0.096666 0.110821 -v 0.030115 -0.095934 0.110139 -v 0.013647 -0.101177 0.115029 -v 0.016747 -0.097962 0.112030 -v 0.031109 -0.101177 0.115029 -v 0.017188 -0.097804 0.111884 -v 0.031112 -0.100335 0.114243 -v 0.017582 -0.097351 0.111461 -v 0.039838 -0.096660 0.110817 -v 0.015110 -0.097030 0.111160 -v 0.017601 -0.096871 0.111013 -v 0.027623 -0.096137 0.110329 -v 0.016352 -0.096223 0.110408 -v 0.015628 -0.094211 0.108533 -v 0.013649 -0.095207 0.109462 -v 0.027309 -0.096680 0.110834 -v 0.027410 -0.097317 0.111429 -v 0.037574 -0.097830 0.111907 -v 0.035192 -0.097154 0.111277 -v 0.034922 -0.099398 0.113370 -v 0.036939 -0.099268 0.113248 -v 0.038248 -0.101176 0.115028 -v 0.027978 -0.097868 0.111943 -v 0.031935 -0.100033 0.113962 -v 0.029246 -0.098076 0.112136 -v 0.032463 -0.100179 0.114097 -v 0.030338 -0.097613 0.111705 -v 0.034186 -0.097938 0.112008 -v 0.013647 -0.100063 0.113989 -v 0.012935 -0.099066 0.115071 -v 0.013136 -0.081836 0.133542 -v 0.013647 -0.081796 0.133578 -v 0.013530 -0.081567 0.133823 -v 0.012268 -0.082022 0.133388 -v 0.010180 -0.100418 0.113956 -v 0.011407 -0.099524 0.114712 -v 0.010172 -0.080931 0.134855 -v 0.008535 -0.081137 0.135048 -v 0.002434 -0.082670 0.136477 -v 0.002082 -0.082813 0.136583 -v 0.001580 -0.102414 0.115946 -v 0.000700 -0.102479 0.116611 -v -0.000558 -0.102122 0.118157 -v -0.000855 -0.100982 0.119691 -v -0.000144 -0.101716 0.118201 -v -0.000756 -0.085883 0.135780 -v -0.000109 -0.084622 0.136498 -v 0.000689 -0.083729 0.136728 -v 0.003634 -0.082265 0.136099 -v 0.003634 -0.101753 0.115201 -v 0.011025 -0.100358 0.114326 -v 0.015260 -0.078003 0.131761 -v 0.015294 -0.078210 0.131953 -v 0.015395 -0.078405 0.132135 -v 0.015557 -0.098601 0.110820 -v 0.015557 -0.078576 0.132295 -v 0.015770 -0.098739 0.110949 -v 0.015770 -0.078714 0.132424 -v 0.016022 -0.078811 0.132514 -v 0.016298 -0.078861 0.132560 -v 0.016583 -0.078861 0.132560 -v 0.016860 -0.078811 0.132514 -v 0.016860 -0.098836 0.111039 -v 0.017112 -0.098739 0.110949 -v 0.017112 -0.078714 0.132424 -v 0.017325 -0.098601 0.110820 -v 0.017325 -0.078576 0.132295 -v 0.017487 -0.098430 0.110661 -v 0.017487 -0.078405 0.132135 -v 0.017588 -0.078210 0.131953 -v 0.017622 -0.098028 0.110286 -v 0.017588 -0.077797 0.131568 -v 0.017487 -0.097627 0.109912 -v 0.017487 -0.077602 0.131386 -v 0.017325 -0.097456 0.109752 -v 0.017325 -0.077431 0.131226 -v 0.017112 -0.097318 0.109623 -v 0.017112 -0.077292 0.131098 -v 0.016860 -0.077196 0.131007 -v 0.016583 -0.077146 0.130961 -v 0.016298 -0.077146 0.130961 -v 0.016022 -0.077196 0.131007 -v 0.015770 -0.077292 0.131098 -v 0.015557 -0.097456 0.109752 -v 0.015395 -0.097627 0.109912 -v 0.015557 -0.077431 0.131226 -v 0.015395 -0.077602 0.131386 -v 0.015294 -0.077797 0.131568 -v 0.015260 -0.098028 0.110286 -v 0.015395 -0.098430 0.110661 -v 0.015294 -0.098235 0.110479 -v 0.016298 -0.098886 0.111086 -v 0.016022 -0.098836 0.111039 -v 0.016583 -0.098886 0.111086 -v 0.017588 -0.098235 0.110479 -v 0.017588 -0.097822 0.110094 -v 0.016583 -0.097171 0.109487 -v 0.016860 -0.097221 0.109533 -v 0.015770 -0.097318 0.109623 -v 0.016022 -0.097221 0.109533 -v 0.016298 -0.097171 0.109487 -v 0.015294 -0.097822 0.110094 -v 0.033044 -0.099259 0.115601 -v 0.031916 -0.096563 0.115241 -v 0.031917 -0.097744 0.114189 -v 0.039841 -0.098715 0.115094 -v 0.038741 -0.098802 0.117328 -v 0.037231 -0.097892 0.114327 -v 0.037260 -0.096313 0.112854 -v 0.034968 -0.099891 0.116190 -v 0.035956 -0.095897 0.112466 -v 0.039841 -0.092360 0.109168 -v 0.031916 -0.092360 0.109168 -v 0.035706 -0.098348 0.114752 -v 0.038674 -0.099886 0.116186 -v 0.034759 -0.096163 0.112714 -v 0.034213 -0.097544 0.114002 -v 0.016822 -0.085552 0.116468 -v 0.029721 -0.090910 0.110723 -v 0.030315 -0.090565 0.111093 -v 0.031149 -0.090609 0.111045 -v 0.031716 -0.092034 0.111826 -v 0.031907 -0.091068 0.110554 -v 0.037274 -0.096843 0.115502 -v 0.035296 -0.097202 0.115836 -v 0.034835 -0.098817 0.117343 -v 0.032787 -0.097997 0.116577 -v 0.031916 -0.092438 0.111394 -v 0.037163 -0.095183 0.113953 -v 0.034036 -0.095913 0.114634 -v 0.035488 -0.094774 0.113572 -v 0.039841 -0.097612 0.116218 -v 0.038741 -0.083107 0.134158 -v 0.031918 -0.082055 0.131025 -v 0.031916 -0.075591 0.127150 -v 0.034406 -0.079733 0.131011 -v 0.031916 -0.080866 0.132069 -v 0.035506 -0.079080 0.130402 -v 0.037136 -0.079468 0.130765 -v 0.039841 -0.081913 0.133045 -v 0.034552 -0.081280 0.132454 -v 0.034628 -0.083119 0.134169 -v 0.037274 -0.081149 0.132332 -v 0.032637 -0.082142 0.133258 -v 0.037234 -0.082197 0.131157 -v 0.039841 -0.083021 0.131925 -v 0.039841 -0.077817 0.127072 -v 0.037300 -0.080651 0.129715 -v 0.035947 -0.080204 0.129297 -v 0.031916 -0.077817 0.127072 -v 0.034543 -0.084184 0.133010 -v 0.035703 -0.082654 0.131582 -v 0.038674 -0.084192 0.133017 -v 0.034738 -0.080481 0.129556 -v 0.034213 -0.081849 0.130832 -v 0.032732 -0.083277 0.132163 -v 0.031718 -0.077040 0.125597 -v 0.031128 -0.077385 0.125226 -v 0.029937 -0.077174 0.125453 -v 0.030154 -0.078459 0.126384 -v 0.029721 -0.078193 0.126669 -v 0.016822 -0.083551 0.120923 -v 0.018145 -0.080289 0.124420 -v 0.018715 -0.079290 0.125493 -v 0.019555 -0.077875 0.124701 -v 0.021850 -0.080101 0.124623 -v 0.021860 -0.079010 0.123483 -v 0.018200 -0.079474 0.122986 -v 0.031915 -0.076744 0.125913 -v 0.039841 -0.075591 0.127150 -v 0.021395 -0.087958 0.113889 -v 0.029494 -0.091284 0.110322 -v 0.030429 -0.077379 0.125233 -v 0.016822 -0.082399 0.119849 -v 0.021654 -0.079651 0.122796 -v 0.021120 -0.078047 0.124516 -v 0.018420 -0.078409 0.124128 -v 0.016822 -0.076668 0.125996 -v 0.019249 -0.080279 0.122123 -v 0.029505 -0.076668 0.125996 -v 0.016822 -0.091284 0.110322 -v 0.018145 -0.088813 0.112971 -v 0.020830 -0.080254 0.122150 -v 0.021850 -0.089002 0.112769 -v 0.022791 -0.082399 0.119849 -v 0.020362 -0.084114 0.121414 -v 0.019592 -0.087649 0.118459 -v 0.019683 -0.084507 0.121780 -v 0.015535 -0.083702 0.121030 -v 0.018736 -0.084554 0.121824 -v 0.015535 -0.086820 0.117686 -v 0.014996 -0.087903 0.118695 -v 0.021654 -0.087896 0.118689 -v 0.018710 -0.087665 0.118474 -v 0.019194 -0.089002 0.119721 -v 0.020355 -0.087243 0.118081 -v 0.022791 -0.085552 0.116468 -v 0.021796 -0.085800 0.116734 -v 0.021168 -0.086225 0.117131 -v 0.022791 -0.083551 0.120923 -v 0.023056 -0.083568 0.120905 -v 0.014996 -0.084785 0.122039 -v 0.019195 -0.085884 0.123065 -v 0.021145 -0.083133 0.120499 -v 0.021733 -0.082712 0.120106 -v 0.022385 -0.082491 0.119901 -v 0.030634 -0.091711 0.112173 -v 0.031851 -0.078012 0.126863 -v 0.020098 -0.079018 0.125785 -v 0.018810 -0.081276 0.123363 -v 0.016822 -0.077819 0.127070 -v 0.029862 -0.091958 0.111908 -v 0.039841 -0.092438 0.111394 -v 0.020098 -0.081493 0.123130 -v 0.021824 -0.084582 0.121850 -v 0.022376 -0.085611 0.116559 -v 0.023056 -0.086704 0.117542 -v 0.031286 -0.091797 0.112081 -v 0.029505 -0.092435 0.111396 -v 0.031207 -0.078516 0.126322 -v 0.020677 -0.081414 0.123215 -v 0.021616 -0.080877 0.123791 -v 0.018200 -0.089628 0.114405 -v 0.016822 -0.086704 0.117542 -v 0.021172 -0.079253 0.125532 -v 0.029494 -0.077819 0.127070 -v 0.016822 -0.092435 0.111396 -v 0.019249 -0.088824 0.115269 -v 0.018676 -0.087937 0.113911 -v 0.020029 -0.087611 0.114261 -v 0.020828 -0.088848 0.115242 -v 0.021653 -0.089451 0.114596 -v 0.021860 -0.090092 0.113909 -v 0.021174 -0.089849 0.111860 -v 0.021120 -0.091056 0.112875 -v 0.019553 -0.091228 0.112691 -v 0.020098 -0.090086 0.111606 -v 0.018420 -0.090694 0.113263 -v 0.018715 -0.089813 0.111899 -v 0.030116 0.095835 0.109276 -v 0.030725 0.098391 0.111611 -v 0.027504 0.098495 0.110794 -v 0.027402 0.096094 0.109631 -v 0.030499 0.078170 0.131521 -v 0.030405 0.078391 0.131727 -v 0.030405 0.097515 0.111219 -v 0.030251 0.097717 0.111407 -v 0.030046 0.097893 0.111571 -v 0.030251 0.078593 0.131915 -v 0.030046 0.078768 0.132079 -v 0.029796 0.098034 0.111703 -v 0.029796 0.078910 0.132211 -v 0.029512 0.098136 0.111797 -v 0.029512 0.079012 0.132306 -v 0.029206 0.098194 0.111852 -v 0.029206 0.079070 0.132360 -v 0.028890 0.098206 0.111862 -v 0.028578 0.098171 0.111830 -v 0.028890 0.079081 0.132371 -v 0.028578 0.079046 0.132338 -v 0.028281 0.098090 0.111755 -v 0.028281 0.078966 0.132263 -v 0.028013 0.078844 0.132149 -v 0.028013 0.097968 0.111641 -v 0.027784 0.097809 0.111492 -v 0.027784 0.078684 0.132001 -v 0.027604 0.097619 0.111315 -v 0.027479 0.097407 0.111117 -v 0.027604 0.078495 0.131824 -v 0.027415 0.097180 0.110906 -v 0.027479 0.078282 0.131626 -v 0.027415 0.078056 0.131415 -v 0.027415 0.077825 0.131199 -v 0.027415 0.096949 0.110691 -v 0.027479 0.096723 0.110480 -v 0.027479 0.077598 0.130988 -v 0.027604 0.096510 0.110281 -v 0.027784 0.096320 0.110105 -v 0.027604 0.077386 0.130790 -v 0.027784 0.077196 0.130613 -v 0.028013 0.096161 0.109956 -v 0.028013 0.077037 0.130464 -v 0.028281 0.096039 0.109842 -v 0.028281 0.076915 0.130350 -v 0.028578 0.095959 0.109767 -v 0.028578 0.076834 0.130275 -v 0.028890 0.076799 0.130243 -v 0.028890 0.095924 0.109734 -v 0.029206 0.095935 0.109745 -v 0.029512 0.095993 0.109799 -v 0.029206 0.076811 0.130254 -v 0.029796 0.096095 0.109894 -v 0.029512 0.076869 0.130308 -v 0.029796 0.076971 0.130403 -v 0.030046 0.096237 0.110026 -v 0.030251 0.096412 0.110190 -v 0.030046 0.077112 0.130535 -v 0.030405 0.096614 0.110378 -v 0.030251 0.077288 0.130698 -v 0.030499 0.096835 0.110584 -v 0.030405 0.077490 0.130887 -v 0.030499 0.077710 0.131092 -v 0.030531 0.097065 0.110798 -v 0.030531 0.077940 0.131307 -v 0.030499 0.097295 0.111013 -v 0.028938 0.076970 0.132299 -v 0.028960 0.079347 0.132994 -v 0.031102 0.076947 0.130805 -v 0.026597 0.077376 0.131253 -v 0.028803 0.076449 0.129917 -v 0.030562 0.078927 0.132226 -v 0.038108 0.078911 0.132623 -v 0.034612 0.077618 0.131389 -v 0.035242 0.079669 0.134478 -v 0.036951 0.080670 0.133852 -v 0.033989 0.079962 0.133192 -v 0.033837 0.099268 0.112495 -v 0.037118 0.100321 0.113055 -v 0.035891 0.097040 0.110092 -v 0.014970 0.096488 0.109790 -v 0.018507 0.096892 0.110262 -v 0.017682 0.098862 0.111338 -v 0.015224 0.098787 0.112125 -v 0.056447 0.094877 0.114763 -v 0.058400 0.091968 0.112122 -v 0.058768 0.094322 0.112941 -v 0.055134 0.092769 0.112789 -v 0.058350 0.094553 0.114816 -v 0.058833 0.080717 0.127398 -v 0.058766 0.093615 0.113943 -v 0.058766 0.080904 0.127573 -v 0.058657 0.093791 0.114107 -v 0.058657 0.081081 0.127738 -v 0.058509 0.093952 0.114257 -v 0.058509 0.081241 0.127887 -v 0.058326 0.094092 0.114387 -v 0.058326 0.081381 0.128018 -v 0.058113 0.094207 0.114495 -v 0.058113 0.081497 0.128125 -v 0.057876 0.094294 0.114576 -v 0.057876 0.081584 0.128207 -v 0.057623 0.094351 0.114629 -v 0.057623 0.081641 0.128259 -v 0.057360 0.094376 0.114652 -v 0.057360 0.081665 0.128282 -v 0.057095 0.094368 0.114644 -v 0.057095 0.081657 0.128275 -v 0.056836 0.081616 0.128237 -v 0.056836 0.094327 0.114606 -v 0.056590 0.081544 0.128169 -v 0.056590 0.094254 0.114539 -v 0.056365 0.094153 0.114444 -v 0.056166 0.094025 0.114325 -v 0.056365 0.081442 0.128075 -v 0.056166 0.081314 0.127955 -v 0.055999 0.093874 0.114184 -v 0.055870 0.093705 0.114026 -v 0.055999 0.081163 0.127815 -v 0.055870 0.080994 0.127657 -v 0.055782 0.093522 0.113856 -v 0.055782 0.080812 0.127487 -v 0.055737 0.093331 0.113678 -v 0.055737 0.080621 0.127308 -v 0.055737 0.080427 0.127128 -v 0.055737 0.093137 0.113497 -v 0.055782 0.092946 0.113319 -v 0.055782 0.080236 0.126950 -v 0.055870 0.092764 0.113149 -v 0.055870 0.080053 0.126779 -v 0.055999 0.092595 0.112991 -v 0.055999 0.079884 0.126621 -v 0.056166 0.079733 0.126481 -v 0.056166 0.092444 0.112850 -v 0.056365 0.092316 0.112731 -v 0.056365 0.079605 0.126362 -v 0.056590 0.092214 0.112636 -v 0.056590 0.079504 0.126267 -v 0.056836 0.092142 0.112569 -v 0.056836 0.079431 0.126199 -v 0.057095 0.079391 0.126161 -v 0.057095 0.092101 0.112531 -v 0.057360 0.092093 0.112523 -v 0.057360 0.079382 0.126154 -v 0.057623 0.092118 0.112546 -v 0.057623 0.079407 0.126177 -v 0.057876 0.092174 0.112599 -v 0.057876 0.079464 0.126230 -v 0.058113 0.079551 0.126311 -v 0.058113 0.092262 0.112680 -v 0.058326 0.092377 0.112788 -v 0.058326 0.079666 0.126418 -v 0.058509 0.092517 0.112918 -v 0.058509 0.079806 0.126549 -v 0.058657 0.092677 0.113068 -v 0.058657 0.079967 0.126698 -v 0.058766 0.092854 0.113233 -v 0.058766 0.080143 0.126863 -v 0.058833 0.080331 0.127038 -v 0.058833 0.093041 0.113408 -v 0.058856 0.093234 0.113588 -v 0.058856 0.080524 0.127218 -v 0.058833 0.093427 0.113768 -v 0.058870 0.079116 0.126597 -v 0.059287 0.081044 0.128051 -v 0.055390 0.081090 0.128594 -v 0.056370 0.078980 0.126065 -v 0.069532 0.089694 0.114261 -v 0.068741 0.089141 0.112620 -v 0.067419 0.090697 0.113187 -v 0.061029 0.089618 0.114343 -v 0.058224 0.080957 0.123631 -v 0.061029 0.080957 0.123631 -v 0.066993 0.081786 0.122741 -v 0.064344 0.089068 0.114932 -v 0.069900 0.088535 0.115504 -v 0.066706 0.083581 0.120817 -v 0.069900 0.081590 0.122951 -v 0.065477 0.083844 0.120535 -v 0.066265 0.089154 0.114841 -v 0.067136 0.079875 0.124791 -v 0.068743 0.080320 0.124313 -v 0.069899 0.080324 0.122076 -v 0.063416 0.079874 0.124791 -v 0.065943 0.085639 0.116375 -v 0.058224 0.079842 0.122592 -v 0.061029 0.079842 0.122592 -v 0.063417 0.089585 0.112143 -v 0.067227 0.080752 0.121616 -v 0.063201 0.078762 0.123750 -v 0.067746 0.078766 0.123746 -v 0.067318 0.086387 0.115572 -v 0.069899 0.087874 0.113978 -v 0.061615 0.079309 0.123164 -v 0.061862 0.080267 0.124370 -v 0.055079 0.084825 0.127238 -v 0.054795 0.084551 0.126983 -v 0.055893 0.083721 0.126209 -v 0.054555 0.084255 0.126707 -v 0.057292 0.079920 0.122664 -v 0.057846 0.080977 0.123650 -v 0.055704 0.082371 0.124950 -v 0.055829 0.082109 0.124705 -v 0.054693 0.081294 0.123946 -v 0.056226 0.081638 0.124267 -v 0.054960 0.081011 0.123682 -v 0.055997 0.080318 0.123036 -v 0.057476 0.081037 0.123706 -v 0.056327 0.092835 0.117343 -v 0.056327 0.084174 0.126631 -v 0.056087 0.092620 0.117143 -v 0.056087 0.083959 0.126431 -v 0.055893 0.092382 0.116921 -v 0.055748 0.083465 0.125970 -v 0.055655 0.083196 0.125719 -v 0.055617 0.082920 0.125462 -v 0.055633 0.082643 0.125204 -v 0.055829 0.090770 0.115417 -v 0.056004 0.081863 0.124476 -v 0.056490 0.081439 0.124081 -v 0.056791 0.089932 0.114635 -v 0.056791 0.081270 0.123924 -v 0.057122 0.081135 0.123798 -v 0.057476 0.089698 0.114418 -v 0.057846 0.089638 0.114362 -v 0.056740 0.093100 0.117590 -v 0.055951 0.094056 0.118480 -v 0.055655 0.091857 0.116431 -v 0.055748 0.092126 0.116682 -v 0.054795 0.093212 0.117695 -v 0.055403 0.093735 0.118182 -v 0.061029 0.088503 0.113303 -v 0.058224 0.088503 0.113303 -v 0.058224 0.089618 0.114343 -v 0.055633 0.091304 0.115915 -v 0.054109 0.091251 0.115866 -v 0.055617 0.091581 0.116174 -v 0.054093 0.091595 0.116186 -v 0.054130 0.091937 0.116506 -v 0.056490 0.090101 0.114793 -v 0.055269 0.089413 0.114152 -v 0.056226 0.090299 0.114978 -v 0.056004 0.090524 0.115188 -v 0.054693 0.089955 0.114658 -v 0.055704 0.091032 0.115662 -v 0.054300 0.090579 0.115239 -v 0.057122 0.089797 0.114509 -v 0.055997 0.088980 0.113748 -v 0.063375 0.090700 0.113183 -v 0.061761 0.090254 0.113660 -v 0.061865 0.089194 0.112563 -v 0.067128 0.089585 0.112143 -v 0.057755 0.088523 0.113322 -v 0.057755 0.079862 0.122610 -v 0.057292 0.088581 0.113376 -v 0.056840 0.080016 0.122754 -v 0.056840 0.088678 0.113466 -v 0.056407 0.080150 0.122879 -v 0.056407 0.088811 0.113591 -v 0.055616 0.080520 0.123224 -v 0.055616 0.089181 0.113936 -v 0.055269 0.080752 0.123440 -v 0.054960 0.089672 0.114393 -v 0.054472 0.090259 0.114941 -v 0.054472 0.081598 0.124229 -v 0.054300 0.081917 0.124527 -v 0.054178 0.082250 0.124837 -v 0.054178 0.090911 0.115549 -v 0.054109 0.082590 0.125154 -v 0.054093 0.082933 0.125474 -v 0.054130 0.083276 0.125794 -v 0.054220 0.083614 0.126109 -v 0.054220 0.092275 0.116820 -v 0.054363 0.092603 0.117126 -v 0.054363 0.083941 0.126414 -v 0.054555 0.092916 0.117419 -v 0.055079 0.093486 0.117950 -v 0.055403 0.085074 0.127470 -v 0.055907 0.085373 0.127750 -v 0.057326 0.085975 0.128311 -v 0.058088 0.085010 0.127411 -v 0.057326 0.094637 0.119023 -v 0.056726 0.084434 0.126874 -v 0.058088 0.093671 0.118123 -v 0.064806 0.080242 0.122163 -v 0.065404 0.081286 0.123277 -v 0.063708 0.081173 0.121165 -v 0.063717 0.082099 0.122406 -v 0.064134 0.083480 0.120924 -v 0.063914 0.082142 0.120125 -v 0.065405 0.082769 0.119453 -v 0.067009 0.082254 0.120005 -v 0.067369 0.082728 0.121732 -v 0.067347 0.088361 0.115691 -v 0.067142 0.087391 0.116731 -v 0.066348 0.086852 0.117309 -v 0.064923 0.086772 0.117396 -v 0.064098 0.085946 0.116045 -v 0.064117 0.087188 0.116949 -v 0.063667 0.087850 0.116239 -v 0.063812 0.087458 0.114425 -v 0.065404 0.088174 0.113657 -v 0.066992 0.087674 0.114193 -v 0.013638 0.087215 0.117066 -v 0.013913 0.087886 0.118564 -v 0.018130 0.086336 0.122583 -v 0.014624 0.087304 0.122035 -v 0.015344 0.087144 0.123272 -v 0.014044 0.086339 0.122118 -v 0.017709 0.085943 0.121242 -v 0.018427 0.085940 0.121748 -v 0.016305 0.088220 0.123887 -v 0.018189 0.087172 0.123493 -v 0.017986 0.085119 0.121848 -v 0.014386 0.087517 0.122662 -v 0.017417 0.085040 0.122096 -v 0.015431 0.085393 0.121010 -v 0.018246 0.086346 0.122606 -v 0.017056 0.088321 0.123661 -v 0.014545 0.085550 0.122257 -v 0.017580 0.086954 0.124224 -v 0.016703 0.086688 0.121331 -v 0.014544 0.086495 0.122207 -v 0.015424 0.085727 0.120846 -v 0.018501 0.087768 0.122223 -v 0.017133 0.089019 0.122581 -v 0.018225 0.086124 0.121390 -v 0.016064 0.089593 0.122422 -v 0.014094 0.087235 0.121147 -v 0.017456 0.086263 0.120023 -v 0.014917 0.086321 0.120436 -v 0.017694 0.088550 0.122888 -v 0.014764 0.088199 0.122838 -v 0.018411 0.088378 0.120939 -v 0.018477 0.088176 0.119840 -v 0.015311 0.087015 0.119475 -v 0.017763 0.089081 0.122455 -v 0.016965 0.086726 0.120256 -v 0.017208 0.088538 0.122605 -v 0.016485 0.088854 0.122220 -v 0.016910 0.089670 0.122280 -v 0.018147 0.087473 0.120110 -v 0.014806 0.088124 0.121136 -v 0.014959 0.087387 0.121352 -v 0.018484 0.086916 0.121293 -v 0.017151 0.087090 0.120129 -v 0.017828 0.086535 0.119982 -v 0.014816 0.089228 0.121260 -v 0.017486 0.089085 0.121294 -v 0.014474 0.088799 0.121376 -v 0.014476 0.088644 0.119244 -v 0.018428 0.089734 0.119745 -v 0.015361 0.086931 0.119268 -v 0.015867 0.090917 0.121218 -v 0.016662 0.087410 0.119404 -v 0.015895 0.090313 0.120631 -v 0.016714 0.087215 0.118823 -v 0.017446 0.090103 0.121798 -v 0.014750 0.089847 0.120994 -v 0.014903 0.089392 0.121398 -v 0.017720 0.088303 0.118073 -v 0.018552 0.089527 0.120520 -v 0.015249 0.089144 0.120955 -v 0.014401 0.089073 0.120111 -v 0.018033 0.088757 0.119781 -v 0.018240 0.089341 0.120219 -v 0.015322 0.088535 0.118855 -v 0.017164 0.087760 0.118438 -v 0.010547 0.089014 0.125323 -v 0.010710 0.089148 0.125926 -v 0.010555 0.089345 0.125598 -v 0.010444 0.088756 0.125911 -v 0.010460 0.088718 0.125505 -v 0.018122 0.088679 0.115204 -v 0.017498 0.088327 0.114875 -v 0.017121 0.091494 0.111230 -v 0.018440 0.092436 0.112109 -v 0.018071 0.091927 0.111634 -v 0.018841 0.094096 0.113656 -v 0.016478 0.092885 0.112527 -v 0.017559 0.093398 0.113005 -v 0.017925 0.094118 0.113677 -v 0.015359 0.092977 0.112613 -v 0.015435 0.090587 0.109892 -v 0.015363 0.090769 0.109998 -v 0.016668 0.091422 0.110599 -v 0.014409 0.087443 0.114051 -v 0.014570 0.087064 0.113696 -v 0.016916 0.090981 0.110444 -v 0.016916 0.087536 0.114138 -v 0.016535 0.091387 0.110976 -v 0.015171 0.091492 0.111228 -v 0.015171 0.093296 0.112911 -v 0.015171 0.094537 0.114030 -v 0.016289 0.092188 0.118476 -v 0.015177 0.091482 0.117817 -v 0.015624 0.091939 0.118243 -v 0.016594 0.095461 0.114891 -v 0.015977 0.095521 0.114741 -v 0.015170 0.090822 0.110428 -v 0.015411 0.095280 0.114336 -v 0.018403 0.095767 0.114659 -v 0.015306 0.090749 0.109980 -v 0.014915 0.090480 0.109728 -v 0.015440 0.090270 0.109957 -v 0.014409 0.090754 0.110501 -v 0.014449 0.090718 0.110168 -v 0.016794 0.096280 0.115095 -v 0.014409 0.094537 0.114030 -v 0.014447 0.094989 0.114190 -v 0.014409 0.091467 0.117804 -v 0.014679 0.095537 0.114461 -v 0.015414 0.096021 0.115019 -v 0.014977 0.092287 0.118567 -v 0.016544 0.092727 0.118978 -v 0.016260 0.096118 0.115326 -v 0.015349 0.086876 0.113522 -v 0.016535 0.088019 0.114588 -v 0.015171 0.087443 0.114051 -v 0.015173 0.089772 0.116223 -v 0.018644 0.091889 0.118196 -v 0.017949 0.090842 0.117220 -v 0.015171 0.088200 0.114757 -v 0.015740 0.092622 0.118881 -v 0.018841 0.090804 0.117186 -v 0.016902 0.088201 0.114758 -v 0.016352 0.089585 0.116048 -v 0.019147 0.092212 0.118499 -v 0.018470 0.092474 0.118743 -v 0.018445 0.089165 0.115657 -v 0.017676 0.090261 0.116679 -v 0.017149 0.089836 0.116284 -v 0.019185 0.095554 0.114957 -v 0.018551 0.095209 0.114656 -v 0.019905 0.085719 0.133464 -v 0.019648 0.099197 0.121331 -v 0.019648 0.088596 0.132699 -v 0.019807 0.099708 0.121149 -v 0.019462 0.085550 0.133251 -v 0.019960 0.088819 0.132907 -v 0.019805 0.088773 0.132865 -v 0.019692 0.088682 0.132780 -v 0.018473 0.081669 0.129196 -v 0.018470 0.082009 0.129966 -v 0.018840 0.081906 0.129934 -v 0.019183 0.081888 0.129594 -v 0.019645 0.085258 0.133060 -v 0.019272 0.085565 0.132828 -v 0.018470 0.095930 0.115038 -v 0.018470 0.085545 0.126174 -v 0.018726 0.095772 0.114671 -v 0.019456 0.100052 0.118824 -v 0.019692 0.099284 0.121411 -v 0.020002 0.099425 0.121544 -v 0.018936 0.095985 0.114859 -v 0.020023 0.099018 0.118208 -v 0.020179 0.099401 0.121521 -v 0.020086 0.088820 0.132909 -v 0.020394 0.099902 0.120671 -v 0.020402 0.088571 0.132676 -v 0.020398 0.088499 0.132609 -v 0.020381 0.088642 0.132742 -v 0.020243 0.088765 0.132858 -v 0.020038 0.087649 0.133832 -v 0.020023 0.085468 0.132738 -v 0.019220 0.085449 0.126083 -v 0.020398 0.099100 0.121240 -v 0.019220 0.092378 0.118653 -v 0.017289 0.079688 0.127310 -v 0.015171 0.079664 0.127291 -v 0.015475 0.079438 0.127077 -v 0.018841 0.080584 0.128146 -v 0.016372 0.079368 0.127012 -v 0.017910 0.080571 0.128133 -v 0.018268 0.080661 0.128218 -v 0.017731 0.080141 0.127733 -v 0.018121 0.078458 0.126164 -v 0.018444 0.078942 0.126614 -v 0.018071 0.081706 0.122594 -v 0.017500 0.078106 0.125836 -v 0.016897 0.077980 0.125717 -v 0.016724 0.081903 0.129935 -v 0.016452 0.081928 0.129438 -v 0.015874 0.081654 0.129520 -v 0.015170 0.080918 0.128730 -v 0.014870 0.076609 0.125004 -v 0.016535 0.077633 0.125726 -v 0.015306 0.076683 0.125064 -v 0.015171 0.077132 0.125109 -v 0.014409 0.080279 0.121263 -v 0.016535 0.081090 0.122019 -v 0.016916 0.077119 0.125310 -v 0.015171 0.077980 0.125717 -v 0.015333 0.081373 0.129117 -v 0.015624 0.085010 0.125674 -v 0.019117 0.085244 0.125893 -v 0.018615 0.084963 0.125631 -v 0.016916 0.080607 0.121569 -v 0.015286 0.079920 0.120929 -v 0.014409 0.084298 0.125010 -v 0.015171 0.080514 0.121482 -v 0.015171 0.081271 0.122188 -v 0.015174 0.082842 0.123653 -v 0.015173 0.084565 0.125259 -v 0.014528 0.084887 0.125561 -v 0.017127 0.081276 0.122192 -v 0.016461 0.082660 0.123482 -v 0.017452 0.083098 0.123892 -v 0.018441 0.082219 0.123072 -v 0.017946 0.083888 0.124627 -v 0.015127 0.085431 0.126067 -v 0.016301 0.085258 0.125905 -v 0.015740 0.085693 0.126311 -v 0.016084 0.085761 0.126375 -v 0.018841 0.083875 0.124616 -v 0.014987 0.081882 0.129716 -v 0.015417 0.085582 0.126208 -v 0.016794 0.085762 0.126375 -v 0.016439 0.085784 0.126396 -v 0.016791 0.082322 0.130071 -v 0.015859 0.082257 0.130088 -v 0.014525 0.081321 0.129213 -v 0.014409 0.076871 0.125006 -v 0.014409 0.080988 0.128560 -v 0.015363 0.076703 0.125082 -v 0.015227 0.076427 0.124629 -v 0.059722 0.091563 0.114182 -v 0.058369 0.090366 0.113066 -v 0.059863 0.092985 0.113424 -v 0.052439 0.092409 0.114971 -v 0.042272 0.096124 0.118436 -v 0.033341 0.096124 0.118436 -v 0.056161 0.090470 0.113164 -v 0.059787 0.092653 0.115198 -v 0.057300 0.090899 0.113563 -v 0.055616 0.092270 0.114841 -v 0.054622 0.094822 0.117221 -v 0.059054 0.092592 0.115141 -v 0.058759 0.093732 0.116205 -v 0.056638 0.093237 0.115743 -v 0.042272 0.097164 0.117321 -v 0.044103 0.096096 0.118409 -v 0.044103 0.097136 0.117294 -v 0.046689 0.095966 0.118287 -v 0.051574 0.096440 0.116646 -v 0.050336 0.095574 0.117923 -v 0.032947 0.097164 0.117321 -v 0.032947 0.093449 0.113856 -v 0.056070 0.092182 0.112675 -v 0.056123 0.091530 0.112067 -v 0.055949 0.093825 0.114207 -v 0.058849 0.092653 0.113114 -v 0.059111 0.091858 0.112373 -v 0.059136 0.094637 0.114964 -v 0.055758 0.093456 0.113863 -v 0.046974 0.096983 0.117152 -v 0.057579 0.091323 0.111873 -v 0.055918 0.095550 0.115815 -v 0.057635 0.094501 0.114837 -v 0.052439 0.093449 0.113856 -v 0.033341 0.092409 0.114971 -v 0.031768 0.081239 0.126950 -v 0.031767 0.092895 0.114451 -v 0.033341 0.081847 0.126298 -v 0.044103 0.084459 0.130888 -v 0.042272 0.085562 0.129763 -v 0.046683 0.084329 0.130767 -v 0.054622 0.083185 0.129699 -v 0.057300 0.079262 0.126042 -v 0.050331 0.083939 0.130403 -v 0.033341 0.080773 0.127450 -v 0.042272 0.084488 0.130915 -v 0.033341 0.084488 0.130915 -v 0.058969 0.080386 0.127090 -v 0.056162 0.078833 0.125641 -v 0.052439 0.080773 0.127450 -v 0.055617 0.080633 0.127320 -v 0.059696 0.081173 0.127824 -v 0.058760 0.082095 0.128683 -v 0.057237 0.081845 0.128450 -v 0.059438 0.080470 0.125015 -v 0.059727 0.079771 0.126516 -v 0.057926 0.078672 0.125491 -v 0.033341 0.085562 0.129763 -v 0.052439 0.081847 0.126298 -v 0.055803 0.081202 0.125697 -v 0.054180 0.084342 0.128625 -v 0.050616 0.084973 0.129213 -v 0.055950 0.082223 0.126650 -v 0.056129 0.079925 0.124507 -v 0.057705 0.080305 0.124861 -v 0.058849 0.082143 0.126574 -v 0.059790 0.082152 0.126584 -v 0.056985 0.082757 0.127147 -v 0.058532 0.083253 0.127610 -v 0.057584 0.079721 0.124316 -v 0.055758 0.081854 0.126305 -v 0.044103 0.085533 0.129736 -v 0.046983 0.085379 0.129593 -v 0.048172 0.090718 0.114327 -v 0.048172 0.081017 0.124730 -v 0.047661 0.096337 0.119567 -v 0.048036 0.096036 0.119286 -v 0.047410 0.095920 0.119177 -v 0.047410 0.079950 0.127207 -v 0.046884 0.078710 0.127093 -v 0.047090 0.079298 0.126600 -v 0.046267 0.092283 0.112313 -v 0.046267 0.079118 0.126431 -v 0.030623 0.093954 0.113871 -v 0.030495 0.093583 0.113525 -v 0.030087 0.093176 0.113146 -v 0.046267 0.092841 0.112833 -v 0.027225 0.094125 0.114031 -v 0.023331 0.097652 0.117320 -v 0.030623 0.094217 0.114116 -v 0.029497 0.092926 0.112913 -v 0.027872 0.093142 0.113114 -v 0.047410 0.097652 0.117320 -v 0.030312 0.094814 0.114674 -v 0.030546 0.094474 0.114356 -v 0.028071 0.095161 0.114997 -v 0.029239 0.095286 0.115113 -v 0.029800 0.095146 0.114983 -v 0.027479 0.093911 0.112790 -v 0.023331 0.098729 0.117282 -v 0.027531 0.095270 0.114057 -v 0.030084 0.093694 0.112586 -v 0.030491 0.095113 0.113911 -v 0.030076 0.095522 0.114291 -v 0.047410 0.098729 0.117282 -v 0.029585 0.095735 0.114490 -v 0.028558 0.095810 0.114561 -v 0.023331 0.092803 0.111756 -v 0.029435 0.093426 0.112337 -v 0.030493 0.094100 0.112965 -v 0.030623 0.094473 0.113314 -v 0.030623 0.094736 0.113559 -v 0.047410 0.093635 0.112532 -v 0.046267 0.092803 0.111756 -v 0.023331 0.092841 0.112833 -v 0.023331 0.079675 0.126951 -v 0.023331 0.084524 0.132515 -v 0.047410 0.090718 0.114327 -v 0.047410 0.081017 0.124730 -v 0.048172 0.085940 0.129320 -v 0.047661 0.086637 0.129970 -v 0.047410 0.086219 0.129580 -v 0.048137 0.086144 0.129510 -v 0.047410 0.096429 0.119652 -v 0.047874 0.086503 0.129845 -v 0.047874 0.096204 0.119442 -v 0.048036 0.086335 0.129689 -v 0.048137 0.095845 0.119107 -v 0.048172 0.095641 0.118917 -v 0.047410 0.084524 0.132515 -v 0.047407 0.092616 0.112623 -v 0.047410 0.086728 0.130055 -v 0.046267 0.078598 0.126989 -v 0.023331 0.078598 0.126989 -v 0.027703 0.079453 0.127786 -v 0.047410 0.079430 0.127764 -v 0.030594 0.080662 0.128913 -v 0.029393 0.081559 0.129750 -v 0.027633 0.081262 0.129472 -v 0.029236 0.079206 0.127556 -v 0.030392 0.079670 0.127988 -v 0.046267 0.079675 0.126951 -v 0.027175 0.081403 0.128562 -v 0.023331 0.084486 0.131438 -v 0.028121 0.079834 0.127099 -v 0.029162 0.082117 0.129228 -v 0.047410 0.084486 0.131438 -v 0.029414 0.079747 0.127018 -v 0.030527 0.080357 0.127587 -v 0.030392 0.081650 0.128792 -v 0.013647 0.081993 0.133367 -v 0.037675 0.075540 0.129069 -v 0.035878 0.075284 0.128830 -v 0.038297 0.083106 0.134404 -v 0.038247 0.082249 0.135325 -v 0.039829 0.081394 0.134527 -v 0.039836 0.082203 0.133563 -v 0.034099 0.082250 0.135326 -v 0.032462 0.081250 0.134393 -v 0.004237 0.083486 0.136843 -v 0.002434 0.082867 0.136266 -v 0.005232 0.082005 0.135462 -v 0.005738 0.083057 0.136443 -v 0.008843 0.082426 0.135855 -v 0.006868 0.081629 0.135111 -v -0.000730 0.086000 0.135629 -v 0.001880 0.084586 0.137381 -v 0.001586 0.083247 0.136494 -v 0.000017 0.102093 0.120332 -v -0.000855 0.086887 0.134805 -v -0.000855 0.101179 0.119480 -v 0.000584 0.102666 0.116516 -v 0.002236 0.103559 0.116742 -v 0.002434 0.102355 0.115367 -v 0.002881 0.103414 0.116402 -v 0.013647 0.082477 0.135082 -v 0.012568 0.083315 0.134218 -v 0.012883 0.100398 0.115882 -v 0.013465 0.082976 0.134547 -v 0.010867 0.082506 0.135290 -v 0.011026 0.081493 0.134557 -v 0.011023 0.100581 0.114137 -v 0.011538 0.083130 0.134514 -v 0.011388 0.100772 0.115616 -v 0.001369 0.085038 0.137335 -v 0.000686 0.102824 0.118887 -v 0.001369 0.103573 0.117458 -v 0.000315 0.103234 0.118798 -v 0.000017 0.087801 0.135657 -v 0.000069 0.087241 0.136205 -v 0.000648 0.085888 0.137084 -v 0.002467 0.084178 0.137343 -v 0.003272 0.083806 0.137143 -v 0.004237 0.102974 0.115944 -v 0.005738 0.102545 0.115544 -v 0.007276 0.102191 0.115214 -v 0.007276 0.082703 0.136113 -v 0.008843 0.101914 0.114956 -v 0.006868 0.101117 0.114213 -v 0.005232 0.101493 0.114564 -v 0.003317 0.103280 0.116230 -v 0.010147 0.101745 0.114799 -v 0.010433 0.101692 0.114796 -v 0.013640 0.101008 0.115210 -v 0.013530 0.099631 0.114452 -v 0.013326 0.100569 0.115682 -v 0.013136 0.099369 0.114740 -v 0.012301 0.100347 0.115972 -v 0.031109 0.099120 0.117235 -v 0.031116 0.100500 0.114002 -v 0.038245 0.100516 0.115736 -v 0.038298 0.101372 0.114815 -v 0.039834 0.096796 0.110548 -v 0.039099 0.095601 0.109434 -v 0.038998 0.094617 0.110235 -v 0.037330 0.093723 0.109401 -v 0.016731 0.096516 0.110287 -v 0.015667 0.098034 0.111703 -v 0.016441 0.098188 0.111846 -v 0.027306 0.097065 0.110798 -v 0.017510 0.096921 0.110665 -v 0.027362 0.097380 0.111092 -v 0.017622 0.097325 0.111041 -v 0.017582 0.097548 0.111249 -v 0.028148 0.098123 0.111785 -v 0.027611 0.097781 0.111467 -v 0.030611 0.096721 0.110477 -v 0.034420 0.097838 0.111519 -v 0.030453 0.097665 0.111358 -v 0.029643 0.098190 0.111848 -v 0.017464 0.097757 0.111444 -v 0.017276 0.097935 0.111611 -v 0.036567 0.099635 0.113195 -v 0.033459 0.101372 0.114815 -v 0.027362 0.096750 0.110505 -v 0.014142 0.094768 0.108656 -v 0.015602 0.096647 0.110409 -v 0.037491 0.094601 0.108501 -v 0.027623 0.096334 0.110118 -v 0.037205 0.097660 0.111354 -v 0.037516 0.098808 0.112424 -v 0.039836 0.100470 0.113974 -v 0.032377 0.100267 0.113785 -v 0.035023 0.099543 0.113110 -v 0.035892 0.097230 0.110954 -v 0.035878 0.094408 0.108321 -v 0.016993 0.098091 0.111756 -v 0.034214 0.098472 0.112111 -v 0.034271 0.098787 0.112404 -v 0.015628 0.094408 0.108321 -v 0.028234 0.095967 0.109775 -v 0.028969 0.095848 0.109664 -v 0.035046 0.097418 0.111128 -v 0.015628 0.093551 0.109241 -v 0.013648 0.094548 0.110171 -v 0.013647 0.095857 0.109672 -v 0.017464 0.096035 0.111558 -v 0.017599 0.096711 0.112187 -v 0.034386 0.096954 0.112415 -v 0.039829 0.099660 0.114938 -v 0.017582 0.096244 0.111752 -v 0.027408 0.095762 0.111303 -v 0.027307 0.096365 0.111866 -v 0.027650 0.096971 0.112431 -v 0.037575 0.097169 0.112615 -v 0.030460 0.096807 0.112277 -v 0.033405 0.100511 0.115732 -v 0.030307 0.095469 0.111030 -v 0.029610 0.095069 0.110656 -v 0.031109 0.099402 0.114698 -v 0.029308 0.097436 0.112864 -v 0.039838 0.096000 0.111525 -v 0.035201 0.096492 0.111984 -v 0.034245 0.097927 0.113322 -v 0.032307 0.099369 0.114666 -v 0.035217 0.098783 0.114120 -v 0.036941 0.098607 0.113956 -v 0.030615 0.096020 0.111544 -v 0.035878 0.093551 0.109241 -v 0.027920 0.095248 0.110824 -v 0.017276 0.095856 0.111391 -v 0.014807 0.093656 0.109339 -v 0.015829 0.095632 0.111182 -v 0.015590 0.097165 0.112612 -v 0.013647 0.099402 0.114698 -v 0.017140 0.097176 0.112622 -v 0.031109 0.081993 0.133367 -v 0.031109 0.098006 0.116195 -v 0.034958 0.081247 0.132671 -v 0.015632 0.079739 0.131265 -v 0.035192 0.079084 0.130655 -v 0.037235 0.080982 0.132424 -v 0.016441 0.079922 0.131435 -v 0.034214 0.080205 0.131699 -v 0.034282 0.080549 0.132021 -v 0.037428 0.079598 0.131132 -v 0.013647 0.077307 0.128997 -v 0.014486 0.076353 0.128108 -v 0.016441 0.078194 0.129824 -v 0.015514 0.078422 0.130037 -v 0.015628 0.076141 0.127910 -v 0.027362 0.078483 0.130094 -v 0.027623 0.078067 0.129707 -v 0.027306 0.078798 0.130387 -v 0.017336 0.078468 0.130080 -v 0.034394 0.079607 0.131141 -v 0.030453 0.079397 0.130947 -v 0.017582 0.079281 0.130838 -v 0.028148 0.079857 0.131375 -v 0.027362 0.079113 0.130681 -v 0.017622 0.078947 0.130526 -v 0.029642 0.079924 0.131437 -v 0.028378 0.077639 0.129307 -v 0.035878 0.076141 0.127910 -v 0.039834 0.078529 0.130136 -v 0.027611 0.079513 0.131055 -v 0.017464 0.079490 0.131033 -v 0.017276 0.079669 0.131199 -v 0.016991 0.079825 0.131345 -v 0.032054 0.081954 0.133331 -v 0.032732 0.082495 0.133835 -v 0.029676 0.077688 0.129353 -v 0.030314 0.078064 0.129703 -v 0.036847 0.076219 0.127982 -v 0.030608 0.078585 0.130188 -v 0.039100 0.077335 0.129023 -v 0.038112 0.076634 0.128369 -v 0.033769 0.083108 0.134406 -v 0.031109 0.083390 0.131869 -v 0.031112 0.082221 0.133580 -v 0.018022 0.083390 0.131869 -v 0.018022 0.098006 0.116195 -v 0.018022 0.084504 0.132908 -v 0.031109 0.101374 0.114817 -v 0.018022 0.099120 0.117235 -v 0.013647 0.101374 0.114817 -v 0.013647 0.082250 0.135326 -v 0.031109 0.084504 0.132908 -v 0.031109 0.082250 0.135326 -v 0.039167 0.076547 0.130008 -v 0.028378 0.076782 0.130226 -v 0.013648 0.076414 0.129883 -v 0.015989 0.079027 0.132321 -v 0.039838 0.077734 0.131114 -v 0.030610 0.077738 0.131118 -v 0.030114 0.077007 0.130435 -v 0.016747 0.079035 0.132327 -v 0.017190 0.078876 0.132179 -v 0.031112 0.081408 0.134540 -v 0.017582 0.078424 0.131758 -v 0.017464 0.078632 0.131952 -v 0.015628 0.075284 0.128830 -v 0.027624 0.077210 0.130625 -v 0.016351 0.077296 0.130705 -v 0.014599 0.075444 0.128978 -v 0.015110 0.078102 0.131458 -v 0.017601 0.077944 0.131310 -v 0.027309 0.077752 0.131131 -v 0.027410 0.078390 0.131726 -v 0.037574 0.078902 0.132204 -v 0.035192 0.078227 0.131574 -v 0.034920 0.080471 0.133667 -v 0.036939 0.080341 0.133545 -v 0.031935 0.081106 0.134259 -v 0.027978 0.078941 0.132240 -v 0.029246 0.079149 0.132433 -v 0.034186 0.079011 0.132305 -v 0.030338 0.078686 0.132002 -v 0.033097 0.082037 0.135127 -v 0.013647 0.081135 0.134286 -v 0.013592 0.081641 0.133744 -v 0.012939 0.082143 0.133218 -v 0.012465 0.099229 0.114922 -v 0.011832 0.082131 0.133312 -v 0.013647 0.100260 0.113778 -v 0.011528 0.099530 0.114685 -v 0.011407 0.081819 0.133698 -v 0.010170 0.100616 0.113746 -v 0.010181 0.081127 0.134643 -v 0.003634 0.082462 0.135888 -v 0.001173 0.102668 0.116007 -v 0.002074 0.102479 0.115499 -v -0.000121 0.084832 0.136285 -v 0.000698 0.083922 0.136514 -v -0.000756 0.101884 0.118620 -v -0.000033 0.102544 0.117205 -v 0.003634 0.101950 0.114989 -v 0.008535 0.081335 0.134837 -v 0.008535 0.100823 0.113938 -v 0.010201 0.082249 0.135691 -v 0.015294 0.097531 0.111234 -v 0.015395 0.097726 0.111415 -v 0.015557 0.097897 0.111575 -v 0.015557 0.077872 0.133049 -v 0.015770 0.078010 0.133178 -v 0.015770 0.098036 0.111704 -v 0.016298 0.078157 0.133315 -v 0.016022 0.098132 0.111794 -v 0.016298 0.098182 0.111841 -v 0.016583 0.078157 0.133315 -v 0.016583 0.098182 0.111841 -v 0.016860 0.098132 0.111794 -v 0.017112 0.098036 0.111704 -v 0.017112 0.078010 0.133178 -v 0.017325 0.097897 0.111575 -v 0.017325 0.077872 0.133049 -v 0.017487 0.077701 0.132890 -v 0.017487 0.097726 0.111415 -v 0.017588 0.077506 0.132708 -v 0.017588 0.097531 0.111234 -v 0.017588 0.097118 0.110848 -v 0.017487 0.096923 0.110667 -v 0.017487 0.076898 0.132141 -v 0.017325 0.076727 0.131981 -v 0.017325 0.096752 0.110507 -v 0.017112 0.096614 0.110378 -v 0.016860 0.076492 0.131762 -v 0.016860 0.096517 0.110288 -v 0.016583 0.076442 0.131716 -v 0.016583 0.096467 0.110241 -v 0.016298 0.096467 0.110241 -v 0.016022 0.076492 0.131762 -v 0.015770 0.076589 0.131852 -v 0.016022 0.096517 0.110288 -v 0.015770 0.096614 0.110378 -v 0.015557 0.096752 0.110507 -v 0.015395 0.076898 0.132141 -v 0.015395 0.096923 0.110667 -v 0.015294 0.097118 0.110848 -v 0.015294 0.077093 0.132323 -v 0.015260 0.097325 0.111041 -v 0.015294 0.077506 0.132708 -v 0.015395 0.077701 0.132890 -v 0.016022 0.078107 0.133268 -v 0.016860 0.078107 0.133268 -v 0.017622 0.077300 0.132515 -v 0.015260 0.077300 0.132515 -v 0.017588 0.077093 0.132323 -v 0.017112 0.076589 0.131852 -v 0.016298 0.076442 0.131716 -v 0.015557 0.076727 0.131981 -v 0.037230 0.081322 0.132098 -v 0.037260 0.079741 0.130625 -v 0.035704 0.081777 0.132522 -v 0.035956 0.079326 0.130237 -v 0.032730 0.082398 0.133102 -v 0.034541 0.083307 0.133950 -v 0.038674 0.083315 0.133957 -v 0.034759 0.079591 0.130485 -v 0.034213 0.080972 0.131772 -v 0.031917 0.081173 0.131959 -v 0.016822 0.076865 0.125784 -v 0.031286 0.078655 0.126174 -v 0.031715 0.078418 0.126428 -v 0.031916 0.075788 0.126938 -v 0.037274 0.082420 0.130969 -v 0.034552 0.082551 0.131091 -v 0.034628 0.084390 0.132806 -v 0.038741 0.084378 0.132795 -v 0.039841 0.078014 0.126861 -v 0.039841 0.083188 0.131686 -v 0.032637 0.083412 0.131894 -v 0.031916 0.082140 0.130708 -v 0.034486 0.080883 0.129536 -v 0.035878 0.080312 0.129003 -v 0.037265 0.080879 0.129532 -v 0.038741 0.100073 0.115965 -v 0.039841 0.097839 0.116035 -v 0.031916 0.097832 0.113876 -v 0.032546 0.097944 0.116133 -v 0.034615 0.096437 0.112575 -v 0.036248 0.096045 0.112209 -v 0.034551 0.098245 0.114260 -v 0.034628 0.100085 0.115976 -v 0.037274 0.098114 0.114139 -v 0.032635 0.099105 0.115063 -v 0.037343 0.096690 0.112811 -v 0.039841 0.092557 0.108957 -v 0.039841 0.098878 0.114851 -v 0.039841 0.082144 0.132865 -v 0.039841 0.092635 0.111182 -v 0.038673 0.099009 0.117127 -v 0.037233 0.097015 0.115267 -v 0.037300 0.095469 0.113826 -v 0.034541 0.099002 0.117120 -v 0.031916 0.092635 0.111182 -v 0.035948 0.095021 0.113407 -v 0.035705 0.097471 0.115692 -v 0.034737 0.095299 0.113667 -v 0.031917 0.096723 0.114994 -v 0.034213 0.096667 0.114942 -v 0.031130 0.090764 0.110880 -v 0.030429 0.090769 0.110873 -v 0.029721 0.092259 0.111585 -v 0.019552 0.090273 0.111405 -v 0.021121 0.090100 0.111590 -v 0.021850 0.090350 0.113632 -v 0.021616 0.089573 0.114464 -v 0.020829 0.087894 0.113957 -v 0.020098 0.088959 0.115124 -v 0.019249 0.087869 0.113984 -v 0.018813 0.089175 0.114892 -v 0.031915 0.091404 0.110193 -v 0.031916 0.092557 0.108957 -v 0.031718 0.091109 0.110509 -v 0.031907 0.077080 0.125553 -v 0.031149 0.077539 0.125061 -v 0.022791 0.085749 0.116257 -v 0.029937 0.090974 0.110654 -v 0.016822 0.091481 0.110111 -v 0.018200 0.088674 0.113121 -v 0.030311 0.077583 0.125014 -v 0.016822 0.082596 0.119638 -v 0.039841 0.075788 0.126938 -v 0.021654 0.088498 0.113309 -v 0.021860 0.089137 0.112624 -v 0.018419 0.089738 0.111978 -v 0.016822 0.085749 0.116257 -v 0.020028 0.080537 0.121846 -v 0.018145 0.079335 0.123135 -v 0.029505 0.091481 0.110111 -v 0.029494 0.076865 0.125784 -v 0.029721 0.077238 0.125384 -v 0.019683 0.087822 0.118225 -v 0.014996 0.088100 0.118484 -v 0.015535 0.087017 0.117475 -v 0.021655 0.084974 0.121820 -v 0.014996 0.084982 0.121828 -v 0.015535 0.083899 0.120818 -v 0.019195 0.086081 0.122853 -v 0.018710 0.084744 0.121606 -v 0.020355 0.084323 0.121213 -v 0.019592 0.084728 0.121591 -v 0.022376 0.082690 0.119691 -v 0.022385 0.085806 0.116345 -v 0.021799 0.082877 0.119866 -v 0.021170 0.083302 0.120262 -v 0.022791 0.082596 0.119638 -v 0.019195 0.089199 0.119510 -v 0.018736 0.087869 0.118269 -v 0.020362 0.087429 0.117859 -v 0.021145 0.086447 0.116943 -v 0.021734 0.086027 0.116551 -v 0.031916 0.078014 0.126861 -v 0.029864 0.078495 0.126345 -v 0.031851 0.092439 0.111392 -v 0.018716 0.091162 0.112762 -v 0.020098 0.091434 0.112469 -v 0.029494 0.092632 0.111185 -v 0.016822 0.086901 0.117331 -v 0.018145 0.090162 0.113833 -v 0.031209 0.091937 0.111932 -v 0.022791 0.086901 0.117331 -v 0.021827 0.087894 0.118292 -v 0.023056 0.083748 0.120712 -v 0.030636 0.078740 0.126082 -v 0.023056 0.086883 0.117350 -v 0.019553 0.079224 0.125564 -v 0.016822 0.092632 0.111185 -v 0.029505 0.078016 0.126858 -v 0.016822 0.078016 0.126858 -v 0.020677 0.089038 0.115039 -v 0.030154 0.091993 0.111871 -v 0.019249 0.081628 0.122985 -v 0.021172 0.091199 0.112722 -v 0.016822 0.083748 0.120712 -v 0.018200 0.080822 0.123849 -v 0.018677 0.080212 0.122195 -v 0.020829 0.081603 0.123012 -v 0.021654 0.080999 0.123660 -v 0.021396 0.080191 0.122218 -v 0.021860 0.080360 0.124346 -v 0.021850 0.079146 0.123337 -v 0.021121 0.079397 0.125379 -v 0.021172 0.078298 0.124247 -v 0.020098 0.078063 0.124500 -v 0.018420 0.079758 0.124992 -v 0.018715 0.078336 0.124207 -v 0.036735 -0.006730 0.152433 -v 0.036404 -0.004801 0.152843 -v 0.039300 -0.006028 0.152579 -v 0.037139 -0.005672 0.152658 -v 0.035596 -0.006917 0.152394 -v 0.035265 -0.004988 0.152804 -v 0.036889 -0.006187 0.147943 -v 0.034976 -0.006618 0.150698 -v 0.035170 -0.004239 0.151204 -v 0.036294 -0.007006 0.150610 -v 0.037372 -0.006172 0.150793 -v 0.037371 -0.004717 0.151100 -v 0.038128 -0.003359 0.153142 -v 0.036187 -0.004024 0.151246 -v 0.037750 -0.008635 0.152004 -v 0.035353 -0.008951 0.151959 -v 0.036110 -0.002715 0.153284 -v 0.034270 -0.003114 0.153189 -v 0.032979 -0.004746 0.152853 -v 0.034422 -0.005407 0.150976 -v 0.033636 -0.008081 0.152142 -v 0.037139 -0.005527 0.151973 -v 0.036735 -0.006585 0.151749 -v 0.035596 -0.006772 0.151709 -v 0.034861 -0.006046 0.152579 -v 0.034861 -0.005900 0.151894 -v 0.035265 -0.004842 0.152119 -v 0.036404 -0.004656 0.152159 -v 0.037564 -0.004619 0.147864 -v 0.036744 -0.003561 0.148066 -v 0.034623 -0.004232 0.148061 -v 0.035548 -0.003472 0.148522 -v 0.034600 -0.005478 0.147768 -v 0.035523 -0.006349 0.147911 -v 0.036735 -0.057808 0.141576 -v 0.035265 -0.059550 0.141206 -v 0.037139 -0.058866 0.141351 -v 0.036404 -0.059737 0.141166 -v 0.032786 -0.059200 0.141276 -v 0.035596 -0.057621 0.141616 -v 0.034861 -0.058492 0.141431 -v 0.037529 -0.057624 0.137012 -v 0.037017 -0.056619 0.137227 -v 0.034903 -0.058698 0.136434 -v 0.034434 -0.058381 0.139689 -v 0.035288 -0.056933 0.140002 -v 0.036672 -0.056986 0.139989 -v 0.037074 -0.059393 0.139480 -v 0.037558 -0.058018 0.139771 -v 0.037987 -0.056107 0.141924 -v 0.035120 -0.059551 0.139446 -v 0.036124 -0.059804 0.139390 -v 0.036004 -0.061861 0.140706 -v 0.038422 -0.060907 0.140911 -v 0.039258 -0.058326 0.141462 -v 0.035292 -0.055524 0.142057 -v 0.033186 -0.057032 0.141737 -v 0.033890 -0.061135 0.140865 -v 0.037139 -0.058720 0.140667 -v 0.034861 -0.058347 0.140746 -v 0.035596 -0.057476 0.140931 -v 0.035265 -0.059405 0.140521 -v 0.036404 -0.059592 0.140482 -v 0.036735 -0.057662 0.140892 -v 0.036062 -0.059258 0.136664 -v 0.037193 -0.058592 0.136463 -v 0.035723 -0.056164 0.136894 -v 0.034451 -0.057390 0.137057 -v 0.005265 -0.057808 0.141576 -v 0.006404 -0.057621 0.141616 -v 0.004861 -0.058866 0.141351 -v 0.005596 -0.059737 0.141166 -v 0.007139 -0.058492 0.141431 -v 0.006735 -0.059550 0.141206 -v 0.004676 -0.056881 0.137165 -v 0.004608 -0.058233 0.136430 -v 0.005519 -0.059184 0.136680 -v 0.007375 -0.058301 0.136517 -v 0.007026 -0.057206 0.139946 -v 0.007505 -0.058106 0.139751 -v 0.007137 -0.059406 0.139476 -v 0.005809 -0.059797 0.139391 -v 0.004628 -0.057650 0.139851 -v 0.004629 -0.059105 0.139539 -v 0.004779 -0.055741 0.142012 -v 0.008593 -0.060122 0.140801 -v 0.005704 -0.056815 0.140023 -v 0.003690 -0.056737 0.141571 -v 0.002781 -0.058172 0.141496 -v 0.003288 -0.060518 0.140995 -v 0.005336 -0.061799 0.140724 -v 0.007259 -0.061600 0.140765 -v 0.009190 -0.057828 0.141568 -v 0.007211 -0.055647 0.142029 -v 0.004861 -0.058720 0.140667 -v 0.006735 -0.059405 0.140521 -v 0.007139 -0.058347 0.140746 -v 0.006404 -0.057476 0.140931 -v 0.005596 -0.059592 0.140482 -v 0.005265 -0.057662 0.140892 -v 0.006660 -0.059084 0.136703 -v 0.007386 -0.057024 0.137138 -v 0.006145 -0.056184 0.137009 -v 0.029863 -0.011045 0.151291 -v 0.031249 -0.010038 0.151506 -v 0.029146 -0.004574 0.154200 -v 0.027367 -0.004431 0.152697 -v 0.026101 -0.005149 0.152545 -v 0.024886 -0.007658 0.153545 -v 0.026131 -0.007178 0.153647 -v 0.031461 -0.005961 0.153905 -v 0.031321 -0.010264 0.152991 -v 0.032114 -0.008505 0.153365 -v 0.030752 -0.006747 0.153738 -v 0.027250 -0.004783 0.154156 -v 0.025821 -0.005707 0.153959 -v 0.029994 -0.011302 0.152770 -v 0.027852 -0.011589 0.152709 -v 0.025538 -0.010201 0.153004 -v 0.027556 -0.006247 0.156260 -v 0.027175 -0.005963 0.153905 -v 0.028776 -0.005608 0.153981 -v 0.030870 -0.008983 0.153263 -v 0.029826 -0.010200 0.153004 -v 0.028224 -0.010555 0.152929 -v 0.028567 -0.011012 0.154907 -v 0.026656 -0.009851 0.153102 -v 0.025963 -0.008322 0.153412 -v 0.031094 -0.008403 0.155760 -v 0.030272 -0.010326 0.155273 -v 0.029748 -0.006390 0.156370 -v 0.026264 -0.007390 0.155861 -v 0.029385 -0.010270 0.156555 -v 0.028982 -0.007670 0.157422 -v 0.026880 -0.009598 0.156823 -v 0.010949 -0.010276 0.151455 -v 0.012083 -0.011315 0.152767 -v 0.014021 -0.011604 0.152706 -v 0.014364 -0.011184 0.151261 -v 0.017069 -0.008780 0.153306 -v 0.017168 -0.007890 0.151962 -v 0.016884 -0.006891 0.153708 -v 0.015947 -0.005478 0.154008 -v 0.013975 -0.004560 0.154203 -v 0.010770 -0.005451 0.152480 -v 0.010075 -0.008842 0.151759 -v 0.010381 -0.009973 0.153052 -v 0.009912 -0.007857 0.153502 -v 0.011814 -0.004953 0.154120 -v 0.010396 -0.006267 0.153841 -v 0.015987 -0.010648 0.152909 -v 0.010969 -0.008329 0.153402 -v 0.011338 -0.006779 0.153731 -v 0.013133 -0.005543 0.153999 -v 0.015943 -0.007412 0.153597 -v 0.014185 -0.010507 0.152939 -v 0.011955 -0.010120 0.153021 -v 0.015764 -0.007605 0.156274 -v 0.015010 -0.006073 0.153896 -v 0.011226 -0.009643 0.155552 -v 0.015000 -0.010668 0.155446 -v 0.015856 -0.009106 0.153243 -v 0.012279 -0.006341 0.156090 -v 0.012463 -0.010885 0.155282 -v 0.011071 -0.008003 0.156433 -v 0.013445 -0.010221 0.156830 -v 0.014343 -0.007298 0.157325 -v 0.025076 -0.001901 0.153235 -v 0.009663 -0.001901 0.153235 -v 0.007170 -0.003064 0.152987 -v 0.005450 -0.002901 0.153021 -v 0.036240 -0.002769 0.153041 -v 0.003815 -0.003718 0.152844 -v 0.007500 -0.008355 0.151863 -v 0.006554 -0.008727 0.151784 -v 0.002000 -0.012795 0.150919 -v 0.038233 -0.002987 0.153004 -v 0.038810 -0.004503 0.152667 -v 0.003130 -0.003632 0.152867 -v 0.002018 -0.005912 0.152382 -v 0.032955 -0.005564 0.152457 -v 0.040000 -0.006792 0.152195 -v 0.032338 -0.001901 0.153235 -v 0.008298 -0.007700 0.152002 -v 0.040000 -0.009812 0.151553 -v 0.008298 -0.056747 0.141577 -v 0.034072 -0.008061 0.151925 -v 0.040000 -0.012795 0.150919 -v 0.002000 -0.009812 0.151553 -v 0.033702 -0.007700 0.152002 -v 0.040000 -0.038092 0.145542 -v 0.035500 -0.008736 0.151782 -v 0.007008 -0.055839 0.141770 -v 0.007928 -0.056386 0.141654 -v 0.002000 -0.056465 0.141637 -v 0.002000 -0.057655 0.141384 -v 0.040000 -0.056465 0.141637 -v 0.009044 -0.058889 0.141122 -v 0.039578 -0.059663 0.140957 -v 0.038907 -0.059633 0.140956 -v 0.025076 -0.062546 0.140344 -v 0.038539 -0.056840 0.141552 -v 0.003456 -0.061126 0.140646 -v 0.037085 -0.061455 0.140569 -v 0.017597 -0.062546 0.140344 -v 0.034733 -0.061354 0.140598 -v 0.035927 -0.062523 0.140349 -v 0.007827 -0.061122 0.140645 -v 0.036643 -0.055799 0.141778 -v 0.024548 -0.008342 0.151866 -v 0.017515 -0.008637 0.151803 -v 0.020177 -0.011194 0.151259 -v 0.014570 -0.004412 0.152701 -v 0.012398 -0.004402 0.152703 -v 0.016242 -0.005427 0.152485 -v 0.009936 -0.007174 0.152114 -v 0.016079 -0.010283 0.151453 -v 0.012429 -0.011128 0.151273 -v 0.031826 -0.006433 0.152272 -v 0.025122 -0.006510 0.152255 -v 0.029555 -0.004388 0.152707 -v 0.031007 -0.005248 0.152524 -v 0.024943 -0.008400 0.151853 -v 0.032094 -0.008337 0.151867 -v 0.025803 -0.010124 0.151487 -v 0.027442 -0.011152 0.151269 -v 0.035400 -0.012465 0.150989 -v 0.004600 -0.036527 0.145875 -v 0.037400 -0.036527 0.145875 -v 0.035892 -0.038431 0.145470 -v 0.035400 -0.038484 0.145459 -v 0.035951 -0.012534 0.150974 -v 0.006253 -0.038454 0.145465 -v 0.005550 -0.038214 0.145516 -v 0.035000 -0.038484 0.145459 -v 0.006513 -0.038536 0.145448 -v 0.005000 -0.040440 0.145043 -v 0.037000 -0.050221 0.142964 -v 0.036128 -0.051845 0.142619 -v 0.037000 -0.040440 0.145043 -v 0.005132 -0.051014 0.142796 -v 0.007000 -0.052178 0.142548 -v 0.018547 -0.010712 0.152896 -v 0.018438 -0.010299 0.151449 -v 0.021918 -0.011513 0.152725 -v 0.022349 -0.011051 0.151291 -v 0.023895 -0.009888 0.151537 -v 0.024438 -0.006676 0.152220 -v 0.023358 -0.005089 0.152557 -v 0.021823 -0.004345 0.152715 -v 0.019884 -0.004425 0.152698 -v 0.020183 -0.004555 0.154204 -v 0.018426 -0.005286 0.152515 -v 0.017478 -0.006971 0.152158 -v 0.017720 -0.006471 0.153797 -v 0.018393 -0.008449 0.153377 -v 0.024284 -0.006648 0.153759 -v 0.023058 -0.005145 0.154079 -v 0.024610 -0.008282 0.153412 -v 0.023851 -0.010296 0.152984 -v 0.020297 -0.011531 0.152721 -v 0.019748 -0.010247 0.152994 -v 0.017469 -0.008839 0.153293 -v 0.019146 -0.006385 0.153815 -v 0.020590 -0.005626 0.153977 -v 0.019591 -0.006471 0.156052 -v 0.022253 -0.005916 0.153915 -v 0.023506 -0.008760 0.153311 -v 0.021814 -0.010490 0.152943 -v 0.023322 -0.007085 0.153678 -v 0.022739 -0.006898 0.156490 -v 0.018453 -0.008051 0.155480 -v 0.019207 -0.010348 0.155025 -v 0.023401 -0.009580 0.155797 -v 0.021295 -0.006063 0.156103 -v 0.021267 -0.011038 0.155239 -v 0.019527 -0.009478 0.157030 -v 0.020864 -0.007490 0.157480 -v 0.005000 -0.050221 0.142964 -v 0.035000 -0.052178 0.142548 -v 0.007000 -0.052593 0.144505 -v 0.035730 -0.052479 0.144529 -v 0.032957 -0.049855 0.145087 -v 0.035000 -0.052593 0.144505 -v 0.009043 -0.041638 0.146833 -v 0.005000 -0.050922 0.144859 -v 0.005596 -0.052081 0.144613 -v 0.009208 -0.041808 0.147631 -v 0.009208 -0.050024 0.145884 -v 0.031865 -0.042340 0.150136 -v 0.032339 -0.050331 0.147326 -v 0.032339 -0.042114 0.149072 -v 0.012991 -0.050285 0.147112 -v 0.015480 -0.042052 0.148779 -v 0.020449 -0.042117 0.149087 -v 0.022909 -0.042199 0.149473 -v 0.012991 -0.042069 0.148858 -v 0.017970 -0.042068 0.148855 -v 0.032957 -0.041638 0.146833 -v 0.025338 -0.042314 0.150013 -v 0.027726 -0.042461 0.150702 -v 0.032704 -0.041879 0.147967 -v 0.009486 -0.042014 0.148605 -v 0.010176 -0.042126 0.149124 -v 0.015480 -0.050268 0.147033 -v 0.009043 -0.049855 0.145087 -v 0.025338 -0.050530 0.148266 -v 0.022909 -0.050416 0.147727 -v 0.020449 -0.050334 0.147341 -v 0.017970 -0.050285 0.147109 -v 0.027726 -0.050677 0.148956 -v 0.032704 -0.050096 0.146221 -v 0.010347 -0.050338 0.147363 -v 0.031865 -0.050557 0.148390 -v 0.030208 -0.050866 0.149845 -v 0.031256 -0.050784 0.149460 -v 0.031263 -0.042565 0.151193 -v 0.030981 -0.042623 0.151464 -v 0.030808 -0.050860 0.149820 -v 0.030340 -0.042660 0.151638 -v 0.009816 -0.050303 0.147200 -v 0.009460 -0.050214 0.146777 -v 0.037000 -0.040418 0.147092 -v 0.036868 -0.039647 0.145211 -v 0.036128 -0.039196 0.147352 -v 0.036181 -0.038852 0.145381 -v 0.035545 -0.038551 0.145445 -v 0.006533 -0.038957 0.147403 -v 0.005868 -0.038819 0.145388 -v 0.005173 -0.039561 0.145230 -v 0.005000 -0.040174 0.147144 -v 0.005822 -0.051811 0.142627 -v 0.006448 -0.052109 0.142563 -v 0.035491 -0.052125 0.142559 -v 0.036828 -0.051100 0.142777 -v 0.037000 -0.051320 0.144775 -v 0.037400 -0.014421 0.150574 -v 0.006600 -0.012881 0.152946 -v 0.009043 -0.016451 0.152187 -v 0.004600 -0.036943 0.147831 -v 0.032957 -0.035329 0.148174 -v 0.037400 -0.036943 0.147831 -v 0.009043 -0.035329 0.148174 -v 0.005870 -0.012996 0.152922 -v 0.035000 -0.038899 0.147415 -v 0.009208 -0.016620 0.152984 -v 0.031288 -0.017369 0.156504 -v 0.032035 -0.017079 0.155140 -v 0.032595 -0.016771 0.153693 -v 0.032595 -0.035649 0.149680 -v 0.012991 -0.016881 0.154212 -v 0.015480 -0.035743 0.150120 -v 0.017970 -0.035759 0.150196 -v 0.017970 -0.016881 0.154209 -v 0.020449 -0.035808 0.150428 -v 0.027726 -0.017273 0.156056 -v 0.027726 -0.036152 0.152043 -v 0.015480 -0.016865 0.154133 -v 0.020449 -0.016930 0.154441 -v 0.032957 -0.016451 0.152187 -v 0.022909 -0.017012 0.154827 -v 0.025338 -0.017127 0.155366 -v 0.010419 -0.016933 0.154456 -v 0.009429 -0.016787 0.153769 -v 0.009208 -0.035499 0.148972 -v 0.012991 -0.035760 0.150199 -v 0.022909 -0.035890 0.150814 -v 0.025338 -0.036005 0.151354 -v 0.032035 -0.035957 0.151128 -v 0.030065 -0.036330 0.152881 -v 0.010512 -0.035810 0.150434 -v 0.010267 -0.035810 0.150438 -v 0.009982 -0.035793 0.150357 -v 0.031288 -0.036247 0.152491 -v 0.031154 -0.017405 0.156675 -v 0.030891 -0.017444 0.156856 -v 0.031134 -0.036287 0.152681 -v 0.030891 -0.036321 0.152844 -v 0.030598 -0.036341 0.152937 -v 0.030598 -0.017463 0.156949 -v 0.030299 -0.017465 0.156958 -v 0.030276 -0.036342 0.152942 -v 0.030065 -0.017451 0.156894 -v 0.010128 -0.016926 0.154420 -v 0.009911 -0.016908 0.154339 -v 0.009724 -0.016883 0.154216 -v 0.009706 -0.035757 0.150188 -v 0.009528 -0.016834 0.153988 -v 0.009514 -0.035707 0.149952 -v 0.009429 -0.035665 0.149756 -v 0.037400 -0.014837 0.152530 -v 0.037282 -0.014122 0.152682 -v 0.036528 -0.013178 0.152882 -v 0.037269 -0.013629 0.150742 -v 0.036577 -0.012831 0.150912 -v 0.035400 -0.012881 0.152946 -v 0.006600 -0.012465 0.150989 -v 0.006110 -0.012518 0.150978 -v 0.005472 -0.012798 0.150919 -v 0.004772 -0.013544 0.150760 -v 0.004905 -0.013732 0.152765 -v 0.004600 -0.014421 0.150574 -v 0.004600 -0.014837 0.152530 -v 0.004718 -0.037657 0.147679 -v 0.004732 -0.037320 0.145707 -v 0.005617 -0.038713 0.147455 -v 0.006800 -0.038484 0.145459 -v 0.036008 -0.038842 0.147427 -v 0.036534 -0.038147 0.145530 -v 0.037227 -0.037406 0.145688 -v 0.037094 -0.038048 0.147596 -v 0.005596 -0.004801 0.152843 -v 0.005265 -0.006730 0.152433 -v 0.004861 -0.005672 0.152658 -v 0.006404 -0.006917 0.152394 -v 0.006597 -0.003471 0.148187 -v 0.006894 -0.006050 0.147536 -v 0.005368 -0.003556 0.148505 -v 0.005361 -0.006324 0.147914 -v 0.006453 -0.004068 0.151240 -v 0.007292 -0.006310 0.150763 -v 0.004467 -0.005453 0.150946 -v 0.005089 -0.004253 0.151195 -v 0.003022 -0.004514 0.152900 -v 0.002836 -0.006553 0.152468 -v 0.004996 -0.006692 0.150693 -v 0.006007 -0.008760 0.151769 -v 0.006362 -0.006960 0.150626 -v 0.007472 -0.004973 0.151042 -v 0.007113 -0.003066 0.152970 -v 0.004958 -0.002791 0.153266 -v 0.004496 -0.008667 0.152018 -v 0.007538 -0.008647 0.152018 -v 0.008878 -0.007360 0.152296 -v 0.009216 -0.005340 0.152725 -v 0.008455 -0.003812 0.153047 -v 0.005265 -0.006585 0.151749 -v 0.006404 -0.006772 0.151709 -v 0.004861 -0.005527 0.151973 -v 0.005596 -0.004656 0.152159 -v 0.006735 -0.004988 0.152804 -v 0.007139 -0.006046 0.152579 -v 0.007139 -0.005900 0.151894 -v 0.006735 -0.004842 0.152119 -v 0.004575 -0.004368 0.148333 -v 0.004565 -0.005281 0.147758 -v 0.007585 -0.004802 0.148235 -v 0.032338 -0.062546 0.140344 -v 0.022163 -0.062546 0.140344 -v 0.017250 -0.062216 0.138792 -v 0.009663 -0.062546 0.140344 -v 0.009013 -0.062216 0.138792 -v 0.040000 -0.008846 0.150136 -v 0.040000 -0.012465 0.149366 -v 0.040000 -0.037762 0.143989 -v 0.040000 -0.053510 0.140642 -v 0.024750 -0.001571 0.151682 -v 0.009013 -0.001571 0.151682 -v 0.017250 -0.001571 0.151682 -v 0.018679 -0.001901 0.153235 -v 0.022163 -0.001901 0.153235 -v 0.002000 -0.053510 0.140642 -v 0.002000 -0.038092 0.145542 -v 0.007334 -0.004782 0.151001 -v 0.005170 -0.006681 0.150596 -v 0.004799 -0.004609 0.151042 -v 0.002916 -0.005846 0.152392 -v 0.004330 -0.005896 0.151035 -v 0.004236 -0.008342 0.151865 -v 0.006505 -0.007116 0.150744 -v 0.007928 -0.008061 0.151925 -v 0.007515 -0.006313 0.150947 -v 0.008958 -0.006566 0.152243 -v 0.008805 -0.004631 0.152655 -v 0.034573 -0.005094 0.150933 -v 0.033813 -0.003714 0.152849 -v 0.034559 -0.006438 0.150920 -v 0.033292 -0.007049 0.152140 -v 0.034500 -0.008355 0.151863 -v 0.035778 -0.007133 0.150684 -v 0.037314 -0.008512 0.151829 -v 0.038781 -0.007053 0.152139 -v 0.036938 -0.004287 0.151107 -v 0.036588 -0.056999 0.139901 -v 0.034907 -0.057030 0.139894 -v 0.034915 -0.059478 0.139471 -v 0.033702 -0.056747 0.141577 -v 0.034306 -0.058141 0.139930 -v 0.033044 -0.057872 0.141338 -v 0.033210 -0.059858 0.140916 -v 0.034947 -0.055855 0.141766 -v 0.035264 -0.056932 0.140011 -v 0.034072 -0.056386 0.141654 -v 0.037404 -0.057848 0.139724 -v 0.007093 -0.057030 0.139894 -v 0.005174 -0.057104 0.139883 -v 0.004489 -0.058435 0.139596 -v 0.006401 -0.059676 0.139331 -v 0.005262 -0.061528 0.140558 -v 0.003012 -0.058147 0.141279 -v 0.003344 -0.060153 0.140844 -v 0.006441 -0.056750 0.140182 -v 0.005739 -0.055721 0.141795 -v 0.004974 -0.055876 0.141762 -v 0.003815 -0.056537 0.141621 -v 0.007408 -0.058787 0.139521 -v 0.007544 -0.057672 0.140008 -v 0.008716 -0.057361 0.141447 -v 0.002296 -0.059447 0.141003 -v 0.002577 -0.059706 0.139325 -v 0.004888 -0.061774 0.138886 -v 0.004878 -0.062111 0.140437 -v 0.006440 -0.062535 0.140345 -v 0.007000 -0.062216 0.138792 -v 0.006474 -0.001906 0.153234 -v 0.004810 -0.002374 0.153134 -v 0.036710 -0.061921 0.138854 -v 0.038226 -0.061474 0.140559 -v 0.039105 -0.060138 0.139233 -v 0.039974 -0.058226 0.141262 -v 0.039979 -0.005663 0.150813 -v 0.039750 -0.005166 0.152541 -v 0.035831 -0.001920 0.153231 -v 0.033883 0.039335 0.141626 -v 0.033226 0.041095 0.146933 -v 0.032074 0.040067 0.141471 -v 0.031070 0.040405 0.147079 -v 0.032711 0.038153 0.147558 -v 0.033925 0.040445 0.147071 -v 0.031076 0.038948 0.147389 -v 0.033375 0.038386 0.147525 -v 0.033930 0.038989 0.147380 -v 0.034092 0.039636 0.147243 -v 0.031900 0.038228 0.147541 -v 0.030908 0.039758 0.147217 -v 0.031735 0.041090 0.146934 -v 0.032567 0.041254 0.146899 -v 0.035529 0.036628 0.147325 -v 0.031737 0.036129 0.147956 -v 0.029305 0.036465 0.146904 -v 0.029177 0.039530 0.147264 -v 0.028114 0.039411 0.146645 -v 0.029620 0.042694 0.145886 -v 0.031464 0.043521 0.144388 -v 0.032427 0.043805 0.145695 -v 0.032357 0.043268 0.146470 -v 0.035211 0.042898 0.145978 -v 0.035856 0.039287 0.147315 -v 0.036803 0.038777 0.146645 -v 0.034874 0.043016 0.144496 -v 0.035680 0.036208 0.145943 -v 0.030532 0.035311 0.146134 -v 0.030369 0.040517 0.145027 -v 0.028515 0.041322 0.144856 -v 0.028291 0.037902 0.145582 -v 0.033443 0.035012 0.146200 -v 0.034713 0.040372 0.145058 -v 0.032941 0.036901 0.145795 -v 0.036985 0.040038 0.145130 -v 0.034692 0.038214 0.145516 -v 0.032584 0.041734 0.144768 -v 0.030417 0.037865 0.145590 -v 0.031784 0.036635 0.144229 -v 0.031180 0.037629 0.141989 -v 0.029912 0.036241 0.142291 -v 0.032088 0.037013 0.142120 -v 0.030889 0.038674 0.141767 -v 0.033191 0.037112 0.142099 -v 0.033970 0.037883 0.141934 -v 0.031265 0.039540 0.141583 -v 0.034085 0.038697 0.141762 -v 0.033176 0.039978 0.141490 -v 0.035135 0.036692 0.142189 -v 0.035919 0.036087 0.143079 -v 0.036794 0.038147 0.142534 -v 0.034713 0.040984 0.141276 -v 0.036353 0.040599 0.142071 -v 0.034780 0.042799 0.142918 -v 0.033966 0.042723 0.141709 -v 0.031200 0.042808 0.141669 -v 0.029690 0.040866 0.141316 -v 0.028981 0.038193 0.141884 -v 0.029139 0.036055 0.144350 -v 0.031757 0.034392 0.143556 -v 0.033748 0.035404 0.142470 -v 0.036514 0.036964 0.144159 -v 0.036755 0.040154 0.143481 -v 0.031156 0.043093 0.142856 -v 0.027906 0.038552 0.143812 -v 0.031524 0.034753 0.144629 -v 0.034299 0.034947 0.144586 -v 0.030118 0.038292 0.143877 -v 0.030743 0.040701 0.143364 -v 0.034709 0.040111 0.143490 -v 0.034404 0.037312 0.144085 -v 0.028926 0.041553 0.143182 -v 0.032862 0.041303 0.143237 -v 0.018633 0.057028 0.143204 -v 0.020494 0.057745 0.143052 -v 0.019056 0.055977 0.143427 -v 0.020198 0.055810 0.143463 -v 0.020917 0.056694 0.143275 -v 0.018799 0.055356 0.141873 -v 0.020359 0.053947 0.136241 -v 0.020913 0.055528 0.141836 -v 0.021254 0.055005 0.136016 -v 0.021173 0.055900 0.135636 -v 0.021256 0.056868 0.141551 -v 0.020486 0.056618 0.135673 -v 0.019970 0.057985 0.141314 -v 0.018387 0.057106 0.141501 -v 0.018270 0.056283 0.141676 -v 0.018264 0.055222 0.135773 -v 0.016828 0.056317 0.141668 -v 0.019010 0.057823 0.141348 -v 0.019575 0.055059 0.141936 -v 0.020743 0.057669 0.141381 -v 0.021231 0.056149 0.141704 -v 0.020184 0.055094 0.141928 -v 0.018385 0.059280 0.141048 -v 0.021599 0.058760 0.141149 -v 0.022803 0.056234 0.141689 -v 0.021211 0.053988 0.142165 -v 0.018213 0.054018 0.142158 -v 0.021465 0.056949 0.143212 -v 0.021838 0.055339 0.142842 -v 0.019908 0.053858 0.142833 -v 0.020342 0.055219 0.143591 -v 0.016872 0.056484 0.142267 -v 0.018593 0.055488 0.143507 -v 0.019223 0.057974 0.143099 -v 0.021514 0.058959 0.141738 -v 0.018633 0.056893 0.142568 -v 0.020494 0.057610 0.142416 -v 0.020917 0.056559 0.142639 -v 0.019352 0.057777 0.142380 -v 0.020198 0.055675 0.142827 -v 0.019056 0.055842 0.142792 -v 0.018572 0.054375 0.136148 -v 0.019517 0.053803 0.136071 -v 0.020942 0.054332 0.135965 -v 0.019666 0.056758 0.135448 -v 0.018876 0.056501 0.135697 -v 0.018413 0.055954 0.135814 -v 0.009680 0.033883 0.148202 -v 0.009864 0.032691 0.148377 -v 0.010615 0.034504 0.147992 -v 0.011845 0.032962 0.148320 -v 0.009969 0.030594 0.141205 -v 0.010355 0.031621 0.146918 -v 0.011203 0.031613 0.146920 -v 0.012015 0.030989 0.141120 -v 0.011812 0.031977 0.146842 -v 0.012191 0.032355 0.140830 -v 0.011249 0.033233 0.140644 -v 0.010234 0.034436 0.146319 -v 0.009569 0.033935 0.146426 -v 0.009237 0.033039 0.146617 -v 0.009332 0.035536 0.146085 -v 0.009638 0.032051 0.146826 -v 0.009195 0.030451 0.147184 -v 0.012188 0.033636 0.146489 -v 0.011319 0.034450 0.146316 -v 0.012221 0.032574 0.146715 -v 0.007869 0.034017 0.146426 -v 0.011505 0.030219 0.147221 -v 0.007886 0.032213 0.146799 -v 0.011814 0.031312 0.148251 -v 0.009222 0.032504 0.148438 -v 0.010118 0.035921 0.146547 -v 0.011756 0.034136 0.148194 -v 0.012787 0.035446 0.146118 -v 0.013799 0.032244 0.146795 -v 0.009705 0.033675 0.147504 -v 0.010943 0.032265 0.148476 -v 0.009864 0.032556 0.147741 -v 0.011686 0.033945 0.147446 -v 0.010615 0.034369 0.147356 -v 0.011845 0.032826 0.147684 -v 0.010935 0.032132 0.147831 -v 0.009452 0.031060 0.140912 -v 0.010526 0.030378 0.141252 -v 0.011364 0.030423 0.141047 -v 0.012275 0.031611 0.140793 -v 0.011781 0.032899 0.140514 -v 0.010541 0.033269 0.140441 -v 0.009682 0.032874 0.140720 -v 0.009263 0.031984 0.140715 -v 0.020586 0.031227 0.148731 -v 0.020586 0.032429 0.148579 -v 0.022602 0.031108 0.148714 -v 0.021736 0.032879 0.148344 -v 0.020271 0.030798 0.147093 -v 0.020873 0.028929 0.141558 -v 0.022333 0.030084 0.147244 -v 0.022586 0.028983 0.141355 -v 0.022960 0.030642 0.147126 -v 0.021429 0.032879 0.146650 -v 0.020189 0.030580 0.141208 -v 0.020148 0.031726 0.146895 -v 0.018544 0.031535 0.146954 -v 0.019917 0.033877 0.146439 -v 0.020665 0.032527 0.146725 -v 0.020817 0.030157 0.147229 -v 0.022490 0.032664 0.146696 -v 0.021625 0.029925 0.147278 -v 0.023161 0.031687 0.146903 -v 0.023728 0.033719 0.146477 -v 0.024197 0.029832 0.147298 -v 0.020951 0.028420 0.147620 -v 0.019121 0.029666 0.147352 -v 0.023093 0.029190 0.148116 -v 0.021307 0.034261 0.147062 -v 0.022723 0.032308 0.148523 -v 0.024611 0.031420 0.147570 -v 0.021741 0.032738 0.147703 -v 0.022692 0.032098 0.147839 -v 0.022602 0.030972 0.148078 -v 0.021564 0.030616 0.148830 -v 0.021559 0.030486 0.148181 -v 0.020698 0.032252 0.147806 -v 0.020608 0.031126 0.148045 -v 0.020162 0.029979 0.141336 -v 0.020363 0.029381 0.141261 -v 0.021680 0.028708 0.141605 -v 0.023121 0.029809 0.141371 -v 0.023065 0.030710 0.140983 -v 0.021986 0.031651 0.140980 -v 0.022608 0.031292 0.140857 -v 0.021250 0.031616 0.140988 -v 0.020618 0.031255 0.140870 -v 0.011690 0.009097 0.153492 -v 0.012362 0.007162 0.153836 -v 0.013594 0.007491 0.153820 -v 0.012638 0.005232 0.146595 -v 0.013694 0.006858 0.152181 -v 0.013886 0.005884 0.146458 -v 0.014083 0.007456 0.152054 -v 0.013476 0.007935 0.145828 -v 0.011185 0.008294 0.151876 -v 0.012469 0.009409 0.151639 -v 0.011599 0.009007 0.151725 -v 0.011234 0.007341 0.152078 -v 0.014109 0.008405 0.151853 -v 0.013416 0.009217 0.151680 -v 0.015484 0.008653 0.151799 -v 0.011994 0.006584 0.152239 -v 0.012100 0.005114 0.152552 -v 0.009667 0.007169 0.152115 -v 0.012952 0.006468 0.152264 -v 0.009631 0.008358 0.152264 -v 0.011442 0.010702 0.151364 -v 0.014108 0.005559 0.152995 -v 0.014850 0.005916 0.152381 -v 0.011155 0.005607 0.153042 -v 0.011900 0.010727 0.152014 -v 0.014304 0.010497 0.151427 -v 0.015448 0.008450 0.152599 -v 0.011517 0.007971 0.153656 -v 0.012959 0.009383 0.153360 -v 0.013767 0.008422 0.152871 -v 0.013769 0.008560 0.153513 -v 0.013461 0.007333 0.153103 -v 0.012956 0.009226 0.152700 -v 0.011839 0.008940 0.152761 -v 0.012344 0.007048 0.153163 -v 0.011533 0.007851 0.152992 -v 0.011166 0.006400 0.146152 -v 0.011617 0.005567 0.146324 -v 0.013450 0.005428 0.146360 -v 0.014160 0.006524 0.146321 -v 0.014020 0.007309 0.145960 -v 0.012419 0.008210 0.145962 -v 0.011570 0.007718 0.145872 -v 0.011201 0.007147 0.146189 -v 0.036735 0.057808 0.141576 -v 0.035596 0.057621 0.141616 -v 0.034861 0.058492 0.141431 -v 0.032810 0.057828 0.141568 -v 0.036296 0.056815 0.140023 -v 0.034495 0.058106 0.139751 -v 0.034863 0.059406 0.139476 -v 0.037372 0.057650 0.139851 -v 0.037371 0.059105 0.139539 -v 0.036191 0.059797 0.139391 -v 0.033407 0.060122 0.140801 -v 0.034974 0.057206 0.139946 -v 0.037221 0.055741 0.142012 -v 0.038310 0.056737 0.141571 -v 0.039219 0.058172 0.141496 -v 0.038712 0.060518 0.140995 -v 0.036664 0.061799 0.140724 -v 0.034741 0.061600 0.140765 -v 0.034789 0.055647 0.142029 -v 0.036404 0.059737 0.141166 -v 0.035265 0.059550 0.141206 -v 0.036404 0.059592 0.140482 -v 0.037139 0.058720 0.140667 -v 0.037139 0.058866 0.141351 -v 0.035596 0.057476 0.140931 -v 0.035265 0.059405 0.140521 -v 0.034861 0.058347 0.140746 -v 0.036735 0.057662 0.140892 -v 0.037324 0.056881 0.137165 -v 0.037392 0.058233 0.136430 -v 0.036481 0.059184 0.136680 -v 0.035340 0.059084 0.136703 -v 0.034625 0.058301 0.136517 -v 0.034614 0.057024 0.137138 -v 0.035855 0.056184 0.137009 -v 0.037139 0.005672 0.152658 -v 0.033545 0.003812 0.153047 -v 0.036404 0.004801 0.152843 -v 0.032784 0.005340 0.152725 -v 0.034861 0.006046 0.152579 -v 0.036735 0.006730 0.152433 -v 0.035265 0.004988 0.152804 -v 0.037352 0.005602 0.147721 -v 0.035638 0.006960 0.150626 -v 0.035547 0.004068 0.151240 -v 0.036911 0.004253 0.151195 -v 0.037533 0.005453 0.150946 -v 0.037042 0.002791 0.153266 -v 0.034708 0.006310 0.150763 -v 0.034528 0.004973 0.151042 -v 0.038978 0.004514 0.152900 -v 0.039164 0.006553 0.152468 -v 0.037004 0.006692 0.150693 -v 0.037504 0.008667 0.152018 -v 0.035993 0.008760 0.151769 -v 0.034462 0.008647 0.152018 -v 0.033122 0.007360 0.152296 -v 0.034887 0.003066 0.152970 -v 0.035596 0.006917 0.152394 -v 0.036735 0.006585 0.151749 -v 0.034861 0.005900 0.151894 -v 0.035265 0.004842 0.152119 -v 0.035596 0.006772 0.151709 -v 0.036404 0.004656 0.152159 -v 0.037139 0.005527 0.151973 -v 0.036632 0.003556 0.148505 -v 0.037425 0.004368 0.148333 -v 0.036057 0.006438 0.147891 -v 0.034934 0.005866 0.147566 -v 0.034415 0.004802 0.148235 -v 0.035403 0.003471 0.148187 -v 0.006404 0.006917 0.152394 -v 0.005265 0.006730 0.152433 -v 0.006735 0.004988 0.152804 -v 0.007139 0.006046 0.152579 -v 0.005255 0.003561 0.148066 -v 0.005706 0.007006 0.150610 -v 0.005813 0.004024 0.151246 -v 0.004628 0.006172 0.150793 -v 0.004629 0.004717 0.151100 -v 0.007730 0.003114 0.153189 -v 0.006830 0.004239 0.151204 -v 0.009021 0.004746 0.152853 -v 0.008364 0.008081 0.152142 -v 0.007024 0.006618 0.150698 -v 0.006647 0.008951 0.151959 -v 0.002700 0.006028 0.152579 -v 0.003872 0.003359 0.153142 -v 0.005890 0.002715 0.153284 -v 0.007578 0.005407 0.150976 -v 0.004250 0.008635 0.152004 -v 0.005596 0.004801 0.152843 -v 0.004861 0.005527 0.151973 -v 0.005596 0.004656 0.152159 -v 0.004861 0.005672 0.152658 -v 0.006404 0.006772 0.151709 -v 0.007139 0.005900 0.151894 -v 0.006735 0.004842 0.152119 -v 0.005265 0.006585 0.151749 -v 0.004436 0.004619 0.147864 -v 0.007377 0.004232 0.148061 -v 0.006452 0.003472 0.148522 -v 0.007400 0.005478 0.147768 -v 0.006477 0.006349 0.147911 -v 0.005111 0.006187 0.147943 -v 0.005596 0.059737 0.141166 -v 0.006735 0.059550 0.141206 -v 0.004861 0.058866 0.141351 -v 0.009214 0.059200 0.141276 -v 0.006404 0.057621 0.141616 -v 0.007139 0.058492 0.141431 -v 0.006277 0.056164 0.136894 -v 0.004983 0.056619 0.137227 -v 0.007549 0.057390 0.137057 -v 0.006880 0.059551 0.139446 -v 0.007566 0.058381 0.139689 -v 0.005876 0.059804 0.139390 -v 0.005328 0.056986 0.139989 -v 0.004926 0.059393 0.139480 -v 0.004442 0.058018 0.139771 -v 0.005992 0.061579 0.140516 -v 0.006708 0.055524 0.142057 -v 0.006712 0.056933 0.140002 -v 0.002675 0.058667 0.141387 -v 0.003883 0.061131 0.140867 -v 0.004013 0.056107 0.141924 -v 0.008814 0.057032 0.141737 -v 0.008096 0.061149 0.140863 -v 0.005265 0.057662 0.140892 -v 0.004861 0.058720 0.140667 -v 0.005265 0.057808 0.141576 -v 0.005596 0.059592 0.140482 -v 0.006404 0.057476 0.140931 -v 0.007139 0.058347 0.140746 -v 0.006735 0.059405 0.140521 -v 0.005938 0.059258 0.136664 -v 0.004807 0.058592 0.136463 -v 0.004471 0.057624 0.137012 -v 0.007097 0.058698 0.136434 -v 0.035000 0.001901 0.153235 -v 0.031550 0.001901 0.153235 -v 0.027813 0.001901 0.153235 -v 0.024775 0.000091 0.144722 -v 0.019113 0.000091 0.144722 -v 0.015810 0.001901 0.153235 -v 0.040000 0.031065 0.147036 -v 0.040000 0.035002 0.137301 -v 0.040000 0.031979 0.137944 -v 0.040000 0.028861 0.147504 -v 0.040000 0.010472 0.151413 -v 0.035000 0.060736 0.131831 -v 0.024775 0.060736 0.131831 -v 0.019761 0.062546 0.140344 -v 0.019113 0.060736 0.131831 -v 0.002000 0.055846 0.132871 -v 0.002000 0.004982 0.143682 -v 0.002000 0.010472 0.151413 -v 0.002000 0.010267 0.142559 -v 0.002000 0.027051 0.138991 -v 0.002000 0.028861 0.147504 -v 0.002000 0.035002 0.137301 -v 0.002000 0.045444 0.135082 -v 0.005998 0.059847 0.139366 -v 0.004679 0.058989 0.139482 -v 0.004791 0.057412 0.139819 -v 0.004033 0.060884 0.140695 -v 0.003043 0.059375 0.141015 -v 0.006559 0.055722 0.141795 -v 0.008182 0.056541 0.141621 -v 0.007441 0.057913 0.139710 -v 0.007348 0.059360 0.139639 -v 0.037072 0.059359 0.139404 -v 0.035383 0.059863 0.139482 -v 0.034625 0.058810 0.139520 -v 0.033084 0.059632 0.140964 -v 0.033046 0.058124 0.141284 -v 0.035921 0.056740 0.140074 -v 0.034974 0.055876 0.141762 -v 0.037392 0.057717 0.139754 -v 0.034481 0.005190 0.150917 -v 0.037689 0.005743 0.151042 -v 0.036569 0.006881 0.150572 -v 0.034967 0.006848 0.150799 -v 0.033019 0.005284 0.152516 -v 0.033861 0.003679 0.152857 -v 0.035650 0.003936 0.151382 -v 0.037100 0.004481 0.151068 -v 0.036309 0.002775 0.153039 -v 0.038341 0.003934 0.152801 -v 0.037778 0.008338 0.151865 -v 0.007003 0.004399 0.151092 -v 0.005280 0.004130 0.151168 -v 0.007431 0.006042 0.150734 -v 0.005951 0.007088 0.150639 -v 0.006406 0.008755 0.151778 -v 0.007068 0.003040 0.152992 -v 0.008521 0.004125 0.152761 -v 0.008954 0.006323 0.152295 -v 0.002076 0.005942 0.152376 -v 0.002302 0.005119 0.152551 -v 0.002670 0.002537 0.144202 -v 0.003170 0.003648 0.152864 -v 0.003786 0.001236 0.144478 -v 0.004500 0.000747 0.144582 -v 0.006132 0.060662 0.131847 -v 0.005290 0.060442 0.131894 -v 0.004500 0.061891 0.140484 -v 0.004500 0.060081 0.131970 -v 0.003786 0.061402 0.140588 -v 0.003786 0.059592 0.132074 -v 0.003170 0.060799 0.140716 -v 0.003168 0.058987 0.132203 -v 0.002302 0.057518 0.132515 -v 0.002076 0.056695 0.132690 -v 0.002076 0.058505 0.141203 -v 0.035000 0.000091 0.144722 -v 0.035868 0.000166 0.144706 -v 0.035868 0.001975 0.153219 -v 0.038214 0.001236 0.144478 -v 0.038214 0.003045 0.152992 -v 0.038830 0.003648 0.152864 -v 0.039330 0.004346 0.152715 -v 0.039698 0.005119 0.152551 -v 0.040000 0.004982 0.143682 -v 0.040000 0.006792 0.152195 -v 0.040000 0.057655 0.141384 -v 0.039698 0.057518 0.132515 -v 0.037500 0.061891 0.140484 -v 0.036710 0.062251 0.140407 -v 0.035868 0.060662 0.131847 -v 0.019761 0.036686 0.145841 -v 0.008930 0.036356 0.144288 -v 0.019112 0.052545 0.140847 -v 0.016213 0.052545 0.140847 -v 0.023100 0.011450 0.151205 -v 0.008452 0.011458 0.151203 -v 0.010113 0.011120 0.149652 -v 0.008930 0.011120 0.149652 -v 0.008000 0.011651 0.149539 -v 0.008000 0.021678 0.149031 -v 0.025370 0.027883 0.147712 -v 0.024038 0.027883 0.147712 -v 0.022163 0.027883 0.147712 -v 0.010113 0.027883 0.147712 -v 0.026300 0.021678 0.149031 -v 0.026300 0.026643 0.146353 -v 0.026300 0.012360 0.151012 -v 0.022110 0.052419 0.140874 -v 0.022550 0.037596 0.145648 -v 0.022085 0.036808 0.145815 -v 0.008506 0.036436 0.144272 -v 0.008000 0.026973 0.147906 -v 0.008221 0.027141 0.146017 -v 0.008401 0.027700 0.147751 -v 0.008675 0.011152 0.149645 -v 0.008000 0.012360 0.151012 -v 0.012804 0.040641 0.140657 -v 0.011590 0.040434 0.139682 -v 0.013587 0.041737 0.142267 -v 0.013590 0.045405 0.140702 -v 0.012939 0.046640 0.139562 -v 0.016004 0.050172 0.143274 -v 0.016012 0.050421 0.143252 -v 0.014037 0.050420 0.143242 -v 0.011991 0.042986 0.146916 -v 0.012140 0.043510 0.146466 -v 0.013570 0.043813 0.142515 -v 0.012780 0.044507 0.144185 -v 0.013176 0.043915 0.141399 -v 0.011592 0.043391 0.138937 -v 0.012122 0.044877 0.146361 -v 0.012938 0.044653 0.139983 -v 0.012140 0.046130 0.147046 -v 0.012099 0.045672 0.145872 -v 0.012140 0.045729 0.147132 -v 0.013105 0.045719 0.140114 -v 0.012112 0.046774 0.145674 -v 0.011913 0.047124 0.146835 -v 0.012140 0.047486 0.145621 -v 0.012140 0.047887 0.145536 -v 0.011590 0.048815 0.144905 -v 0.012140 0.048479 0.145410 -v 0.012140 0.048880 0.145325 -v 0.012140 0.048711 0.146498 -v 0.013579 0.044965 0.142703 -v 0.013005 0.044354 0.139519 -v 0.012729 0.044161 0.139869 -v 0.013030 0.047356 0.142924 -v 0.012697 0.047076 0.143809 -v 0.013655 0.046698 0.141109 -v 0.013171 0.046331 0.140309 -v 0.013188 0.041731 0.143101 -v 0.012870 0.045195 0.139846 -v 0.013039 0.047232 0.138944 -v 0.013572 0.048019 0.142090 -v 0.012783 0.044641 0.144878 -v 0.012729 0.043167 0.140082 -v 0.012781 0.041525 0.144819 -v 0.013593 0.041191 0.143453 -v 0.012869 0.040226 0.140902 -v 0.013136 0.042803 0.141057 -v 0.012780 0.043514 0.144398 -v 0.013590 0.042588 0.142159 -v 0.014036 0.039511 0.145539 -v 0.016011 0.039513 0.145548 -v 0.014028 0.050173 0.143283 -v 0.016020 0.050408 0.145193 -v 0.014020 0.050649 0.145107 -v 0.018365 0.041263 0.142724 -v 0.017525 0.040486 0.139066 -v 0.018400 0.042622 0.149091 -v 0.017116 0.046655 0.137754 -v 0.018400 0.048774 0.147783 -v 0.013186 0.041064 0.142647 -v 0.013129 0.040407 0.140679 -v 0.011590 0.042155 0.147891 -v 0.012065 0.041945 0.146908 -v 0.012130 0.041681 0.147628 -v 0.013106 0.041744 0.140959 -v 0.012957 0.042411 0.145076 -v 0.012780 0.042520 0.144608 -v 0.012140 0.042703 0.147227 -v 0.011590 0.043846 0.145961 -v 0.013072 0.043528 0.144505 -v 0.012868 0.042359 0.139837 -v 0.012076 0.043936 0.146503 -v 0.011694 0.043845 0.147532 -v 0.013057 0.043424 0.139807 -v 0.012140 0.044735 0.147343 -v 0.012975 0.045424 0.143615 -v 0.011590 0.046130 0.147046 -v 0.011590 0.045729 0.147132 -v 0.011590 0.046827 0.145328 -v 0.012780 0.046495 0.143763 -v 0.013070 0.046331 0.143965 -v 0.012140 0.046723 0.146920 -v 0.012779 0.047628 0.144250 -v 0.011590 0.048301 0.145070 -v 0.011595 0.047889 0.145544 -v 0.012140 0.048118 0.146624 -v 0.011590 0.048118 0.146624 -v 0.012140 0.047717 0.146709 -v 0.012569 0.048556 0.143686 -v 0.013250 0.047985 0.141002 -v 0.012140 0.049112 0.146413 -v 0.011590 0.044173 0.138372 -v 0.011590 0.043964 0.138943 -v 0.013226 0.044832 0.143028 -v 0.011590 0.046395 0.138406 -v 0.011591 0.046254 0.137898 -v 0.011590 0.047434 0.145383 -v 0.011590 0.045699 0.138607 -v 0.011590 0.040979 0.139557 -v 0.012834 0.041192 0.140564 -v 0.011602 0.042462 0.146535 -v 0.011590 0.045061 0.138205 -v 0.011590 0.044958 0.138732 -v 0.013186 0.045615 0.141827 -v 0.012697 0.046082 0.144021 -v 0.011590 0.047367 0.138091 -v 0.011590 0.047054 0.137744 -v 0.013086 0.047919 0.142888 -v 0.012870 0.047182 0.139423 -v 0.011590 0.046945 0.138309 -v 0.011590 0.042655 0.139238 -v 0.011592 0.044436 0.145969 -v 0.013239 0.043752 0.142831 -v 0.013166 0.040826 0.143724 -v 0.011590 0.042322 0.138805 -v 0.013171 0.042357 0.141154 -v 0.012697 0.043100 0.144655 -v 0.011590 0.041761 0.139444 -v 0.016003 0.039272 0.145612 -v 0.014020 0.039771 0.149556 -v 0.014028 0.039275 0.145622 -v 0.014020 0.040075 0.147388 -v 0.016020 0.039821 0.147409 -v 0.014020 0.039821 0.147409 -v 0.020770 0.039827 0.152394 -v 0.019170 0.052670 0.149664 -v 0.014020 0.050408 0.145193 -v 0.016020 0.051475 0.146900 -v 0.016020 0.050649 0.145107 -v 0.017435 0.047427 0.141414 -v 0.017115 0.050184 0.140828 -v 0.017115 0.047805 0.141333 -v 0.021660 0.042622 0.149091 -v 0.015655 0.049094 0.135702 -v 0.015655 0.037357 0.138197 -v 0.017115 0.049406 0.137169 -v 0.021660 0.048774 0.147783 -v 0.020045 0.048866 0.148070 -v 0.017116 0.041250 0.142727 -v 0.018365 0.038446 0.143323 -v 0.011590 0.041754 0.147977 -v 0.011590 0.044735 0.147343 -v 0.011590 0.049171 0.141323 -v 0.011590 0.048025 0.135929 -v 0.011591 0.048892 0.145494 -v 0.011590 0.048711 0.146498 -v 0.011590 0.049112 0.146413 -v 0.011590 0.046235 0.136310 -v 0.011590 0.047717 0.146709 -v 0.011590 0.047381 0.141703 -v 0.011590 0.045241 0.136521 -v 0.011590 0.046723 0.146920 -v 0.011590 0.044247 0.136732 -v 0.011590 0.044407 0.138828 -v 0.011590 0.046403 0.145426 -v 0.011590 0.043253 0.136944 -v 0.011590 0.044848 0.145752 -v 0.011590 0.045136 0.147258 -v 0.011590 0.045406 0.145640 -v 0.011590 0.041266 0.137366 -v 0.011590 0.046442 0.148278 -v 0.011590 0.045813 0.145550 -v 0.011590 0.051471 0.146885 -v 0.011590 0.040272 0.137577 -v 0.011594 0.041081 0.138882 -v 0.011590 0.041418 0.142971 -v 0.011590 0.043149 0.147680 -v 0.011590 0.042852 0.146173 -v 0.011590 0.042748 0.147765 -v 0.011590 0.040110 0.139216 -v 0.011590 0.039985 0.139768 -v 0.011590 0.041463 0.146577 -v 0.011590 0.043427 0.146084 -v 0.011590 0.037357 0.138197 -v 0.017115 0.038446 0.143323 -v 0.016020 0.040075 0.147388 -v 0.011495 0.039819 0.149783 -v 0.019170 0.039827 0.152394 -v 0.019170 0.042370 0.151853 -v 0.020770 0.042370 0.151853 -v 0.020770 0.052670 0.149664 -v 0.019170 0.050127 0.150204 -v 0.020770 0.050127 0.150204 -v 0.011590 0.049094 0.135702 -v 0.016020 0.051323 0.146185 -v 0.018365 0.050184 0.140828 -v 0.011590 0.050241 0.141095 -v 0.014020 0.051323 0.146185 -v 0.014020 0.051475 0.146900 -v 0.011495 0.051557 0.147288 -v 0.018365 0.047425 0.141414 -v 0.021725 0.043740 0.149159 -v 0.021725 0.042653 0.149390 -v 0.018365 0.043070 0.151346 -v 0.018385 0.042592 0.149097 -v 0.020045 0.042655 0.149390 -v 0.021660 0.040490 0.139065 -v 0.021660 0.046643 0.137757 -v 0.017115 0.037668 0.139664 -v 0.017115 0.040170 0.139133 -v 0.018400 0.046643 0.137757 -v 0.015655 0.037668 0.139664 -v 0.015655 0.049406 0.137169 -v 0.018400 0.040490 0.139065 -v 0.018365 0.049282 0.150026 -v 0.021725 0.048867 0.148069 -v 0.018400 0.048807 0.147791 -v 0.020045 0.047721 0.148313 -v 0.020045 0.043740 0.149159 -v 0.011590 0.038503 0.143590 -v 0.011590 0.039800 0.149690 -v 0.014020 0.039619 0.148841 -v 0.011495 0.040278 0.151940 -v 0.016020 0.039771 0.149556 -v 0.016020 0.039619 0.148841 -v 0.021103 0.039453 0.152160 -v 0.021091 0.052926 0.149297 -v 0.018859 0.052916 0.149303 -v 0.018864 0.049761 0.149976 -v 0.021103 0.049761 0.149970 -v 0.021115 0.039500 0.152463 -v 0.011145 0.040008 0.152355 -v 0.008775 0.042336 0.151860 -v 0.018855 0.039500 0.152463 -v 0.020050 0.043086 0.151470 -v 0.021725 0.043887 0.151531 -v 0.020056 0.049313 0.150150 -v 0.020057 0.048208 0.150524 -v 0.011145 0.052431 0.149715 -v 0.021775 0.053304 0.149529 -v 0.021115 0.049819 0.150270 -v 0.008775 0.050161 0.150197 -v 0.011145 0.050161 0.150197 -v 0.011495 0.052016 0.149445 -v 0.018365 0.052016 0.149445 -v 0.018715 0.052431 0.149715 -v 0.018819 0.049813 0.150353 -v 0.021725 0.047721 0.148313 -v 0.021725 0.040461 0.139071 -v 0.021725 0.048552 0.150539 -v 0.021725 0.046672 0.137751 -v 0.021725 0.048137 0.150270 -v 0.021725 0.044156 0.151116 -v 0.020066 0.044199 0.151365 -v 0.018365 0.040278 0.151940 -v 0.018715 0.040008 0.152355 -v 0.011145 0.042336 0.151860 -v 0.021090 0.042613 0.151491 -v 0.021115 0.042679 0.151788 -v 0.018863 0.039447 0.152166 -v 0.018860 0.042608 0.151497 -v 0.018812 0.042722 0.151849 -v 0.018855 0.052998 0.149594 -v 0.021115 0.052998 0.149594 -v 0.009375 0.038320 0.152203 -v 0.009375 0.038913 0.152588 -v 0.008448 0.038772 0.152107 -v 0.008775 0.039239 0.152519 -v 0.008780 0.053585 0.149469 -v 0.021775 0.039500 0.152463 -v 0.021758 0.038442 0.152181 -v 0.021175 0.038320 0.152203 -v 0.021175 0.038913 0.152588 -v 0.021175 0.053585 0.149469 -v 0.008275 0.039396 0.151974 -v 0.009375 0.037390 0.147902 -v 0.008900 0.036694 0.144217 -v 0.008260 0.038481 0.147670 -v 0.009375 0.053970 0.148876 -v 0.008762 0.053834 0.148904 -v 0.008275 0.053174 0.149046 -v 0.022275 0.039396 0.151974 -v 0.022228 0.039056 0.152039 -v 0.022275 0.052894 0.149105 -v 0.021842 0.053808 0.148918 -v 0.021175 0.053970 0.148876 -v 0.021175 0.053070 0.144569 -v 0.021175 0.037390 0.147902 -v 0.009012 0.038371 0.152190 -v 0.008260 0.051979 0.144801 -v 0.022290 0.051200 0.141133 -v 0.021175 0.036610 0.144234 -v 0.008430 0.037099 0.144243 -v 0.008260 0.051200 0.141133 -v 0.008260 0.037701 0.144002 -v 0.021175 0.052290 0.140901 -v 0.009375 0.053070 0.144569 -v 0.008851 0.052222 0.141017 -v 0.022290 0.038481 0.147670 -v 0.022290 0.051979 0.144801 -v 0.018000 0.019072 0.152542 -v 0.011551 0.025368 0.149589 -v 0.013766 0.017915 0.148168 -v 0.013759 0.019887 0.147736 -v 0.013463 0.022233 0.147130 -v 0.013469 0.023216 0.146943 -v 0.010996 0.024747 0.149721 -v 0.011505 0.024931 0.149982 -v 0.011074 0.014800 0.151853 -v 0.011489 0.014512 0.151897 -v 0.018000 0.015381 0.153347 -v 0.018000 0.025163 0.151268 -v 0.018649 0.013905 0.153136 -v 0.021963 0.022233 0.147130 -v 0.021969 0.023216 0.146943 -v 0.021963 0.019788 0.147650 -v 0.022261 0.019882 0.147740 -v 0.021963 0.017832 0.148066 -v 0.021963 0.015386 0.148585 -v 0.022267 0.015469 0.148688 -v 0.021324 0.014868 0.146147 -v 0.020005 0.024931 0.149982 -v 0.015652 0.026440 0.150548 -v 0.015650 0.014248 0.152346 -v 0.015208 0.023227 0.146924 -v 0.014721 0.023337 0.147872 -v 0.015032 0.023334 0.147847 -v 0.015072 0.016700 0.150016 -v 0.015043 0.017449 0.149128 -v 0.013577 0.023124 0.146507 -v 0.012824 0.022845 0.145198 -v 0.013577 0.020678 0.147027 -v 0.012824 0.020248 0.145003 -v 0.012824 0.018902 0.148290 -v 0.013469 0.018815 0.147879 -v 0.013668 0.018774 0.147689 -v 0.013668 0.016329 0.148209 -v 0.012824 0.015998 0.146654 -v 0.012824 0.013738 0.148261 -v 0.012604 0.015069 0.152078 -v 0.012604 0.024932 0.149982 -v 0.013469 0.016369 0.148399 -v 0.012824 0.015020 0.146862 -v 0.013463 0.015386 0.148585 -v 0.012824 0.014868 0.146147 -v 0.013767 0.015469 0.148688 -v 0.013463 0.017832 0.148066 -v 0.013469 0.020771 0.147463 -v 0.013463 0.019788 0.147650 -v 0.012824 0.020400 0.145718 -v 0.012824 0.020128 0.148029 -v 0.013759 0.022333 0.147217 -v 0.010996 0.023103 0.141987 -v 0.011124 0.025162 0.149634 -v 0.011076 0.023462 0.141911 -v 0.011524 0.023724 0.141855 -v 0.011503 0.015069 0.152078 -v 0.010996 0.015132 0.151765 -v 0.018650 0.014270 0.152445 -v 0.018649 0.026427 0.150479 -v 0.019184 0.015347 0.148476 -v 0.019184 0.017325 0.148056 -v 0.022697 0.024706 0.143594 -v 0.022168 0.016329 0.148209 -v 0.021969 0.016369 0.148399 -v 0.021969 0.018815 0.147879 -v 0.022168 0.018774 0.147689 -v 0.022133 0.020710 0.147178 -v 0.021969 0.020771 0.147463 -v 0.021324 0.022386 0.147846 -v 0.022077 0.023124 0.146507 -v 0.021324 0.013738 0.148261 -v 0.021324 0.014498 0.151837 -v 0.021104 0.015069 0.152078 -v 0.021104 0.024932 0.149982 -v 0.021324 0.022845 0.145198 -v 0.022259 0.022333 0.147217 -v 0.021324 0.020400 0.145718 -v 0.021324 0.017466 0.146342 -v 0.022266 0.017915 0.148168 -v 0.021324 0.015508 0.149159 -v 0.019496 0.023336 0.141937 -v 0.019496 0.024884 0.149692 -v 0.019707 0.025222 0.149637 -v 0.020020 0.025368 0.149589 -v 0.020003 0.015069 0.152078 -v 0.020020 0.012867 0.144163 -v 0.019945 0.014513 0.151900 -v 0.019496 0.021682 0.148652 -v 0.019496 0.015514 0.149009 -v 0.013336 0.013031 0.146948 -v 0.010502 0.021201 0.147363 -v 0.015504 0.026080 0.149578 -v 0.015650 0.025790 0.149892 -v 0.015217 0.017339 0.148180 -v 0.015228 0.015347 0.148476 -v 0.015038 0.015654 0.149458 -v 0.014844 0.016480 0.148941 -v 0.014817 0.021554 0.148244 -v 0.015503 0.020264 0.144111 -v 0.015504 0.022835 0.143552 -v 0.015275 0.022642 0.148970 -v 0.015504 0.021833 0.149134 -v 0.012824 0.020492 0.142542 -v 0.012824 0.015846 0.145939 -v 0.012824 0.018292 0.145419 -v 0.012824 0.018444 0.146134 -v 0.012824 0.017466 0.146342 -v 0.012824 0.017312 0.145625 -v 0.012824 0.019422 0.145926 -v 0.012824 0.019269 0.145210 -v 0.012824 0.021867 0.145406 -v 0.012824 0.021713 0.144690 -v 0.012824 0.014498 0.151837 -v 0.012824 0.015508 0.149159 -v 0.012824 0.016457 0.148809 -v 0.012824 0.016517 0.149094 -v 0.012824 0.017954 0.148641 -v 0.012824 0.021017 0.150424 -v 0.012824 0.019940 0.148366 -v 0.012824 0.018985 0.148565 -v 0.012824 0.022386 0.147846 -v 0.012824 0.021633 0.147905 -v 0.012824 0.025360 0.149550 -v 0.012824 0.023352 0.147581 -v 0.012824 0.022696 0.144480 -v 0.023829 0.023305 0.146912 -v 0.023829 0.021199 0.147357 -v 0.023647 0.023500 0.148499 -v 0.023829 0.015300 0.148610 -v 0.021652 0.013129 0.145639 -v 0.018908 0.014400 0.145450 -v 0.018921 0.015973 0.150476 -v 0.018908 0.017345 0.148229 -v 0.019496 0.017492 0.149501 -v 0.019496 0.023275 0.147337 -v 0.018908 0.023233 0.146977 -v 0.019491 0.023359 0.148065 -v 0.018910 0.022836 0.143579 -v 0.019257 0.021449 0.147909 -v 0.018908 0.021773 0.148943 -v 0.018908 0.020258 0.144100 -v 0.018908 0.021287 0.147391 -v 0.019496 0.021395 0.147736 -v 0.019135 0.022642 0.148970 -v 0.022697 0.012669 0.146153 -v 0.023434 0.024699 0.143595 -v 0.023434 0.012706 0.146144 -v 0.021324 0.017312 0.145625 -v 0.021324 0.015846 0.145939 -v 0.021324 0.015998 0.146654 -v 0.021324 0.015020 0.146862 -v 0.021324 0.018292 0.145419 -v 0.021324 0.018444 0.146134 -v 0.021324 0.019269 0.145210 -v 0.021324 0.020248 0.145003 -v 0.021324 0.019422 0.145926 -v 0.021324 0.022693 0.144483 -v 0.021324 0.021867 0.145406 -v 0.021324 0.021713 0.144690 -v 0.021324 0.016457 0.148810 -v 0.021324 0.016517 0.149094 -v 0.021324 0.017954 0.148641 -v 0.021324 0.020128 0.148029 -v 0.021324 0.021017 0.150424 -v 0.021324 0.019940 0.148366 -v 0.021324 0.018985 0.148565 -v 0.021324 0.018902 0.148290 -v 0.021324 0.021633 0.147905 -v 0.021324 0.023352 0.147581 -v 0.021324 0.025360 0.149550 -v 0.019496 0.014940 0.151806 -v 0.019493 0.015767 0.149817 -v 0.019496 0.017389 0.148610 -v 0.012123 0.013016 0.146806 -v 0.013616 0.013424 0.150144 -v 0.012950 0.013107 0.145650 -v 0.013329 0.012742 0.146935 -v 0.010718 0.013804 0.151935 -v 0.010318 0.013922 0.151827 -v 0.010265 0.012409 0.144261 -v 0.010502 0.017411 0.148162 -v 0.010509 0.017636 0.149996 -v 0.010814 0.017497 0.148859 -v 0.010502 0.015302 0.148617 -v 0.010671 0.015572 0.149500 -v 0.010986 0.015572 0.149500 -v 0.010793 0.021406 0.148032 -v 0.010684 0.021668 0.148889 -v 0.010502 0.023305 0.146909 -v 0.010265 0.023328 0.147103 -v 0.010265 0.023504 0.148531 -v 0.010674 0.023412 0.147786 -v 0.010916 0.023384 0.147556 -v 0.010288 0.015895 0.150559 -v 0.012117 0.024966 0.144337 -v 0.012648 0.024012 0.143370 -v 0.011830 0.025648 0.147544 -v 0.013609 0.025631 0.147466 -v 0.013280 0.024517 0.143856 -v 0.012100 0.024742 0.144582 -v 0.015504 0.016750 0.150215 -v 0.015504 0.015399 0.148642 -v 0.015504 0.014400 0.145450 -v 0.015504 0.016959 0.144906 -v 0.015504 0.021769 0.148930 -v 0.015504 0.017531 0.149831 -v 0.015504 0.015881 0.150182 -v 0.015504 0.023432 0.148686 -v 0.015504 0.023233 0.146977 -v 0.015504 0.017345 0.148229 -v 0.015504 0.021287 0.147391 -v 0.012824 0.023724 0.141855 -v 0.010996 0.013488 0.144031 -v 0.012824 0.012867 0.144163 -v 0.011121 0.013088 0.144116 -v 0.011520 0.012867 0.144163 -v 0.010467 0.012184 0.144308 -v 0.010265 0.024177 0.141759 -v 0.010460 0.024407 0.141710 -v 0.021943 0.024621 0.144189 -v 0.020751 0.024964 0.144328 -v 0.021063 0.024067 0.143299 -v 0.020744 0.024709 0.144465 -v 0.022245 0.025637 0.147499 -v 0.021962 0.024964 0.144328 -v 0.024065 0.024192 0.141756 -v 0.024063 0.025637 0.149407 -v 0.023541 0.023392 0.147622 -v 0.024065 0.023504 0.148531 -v 0.024063 0.021961 0.149207 -v 0.023658 0.021457 0.148200 -v 0.023327 0.021473 0.148250 -v 0.024062 0.016053 0.150501 -v 0.023658 0.015558 0.149454 -v 0.023337 0.015564 0.149472 -v 0.023829 0.017411 0.148165 -v 0.023541 0.017498 0.148875 -v 0.023647 0.017607 0.149754 -v 0.024065 0.017610 0.149784 -v 0.021979 0.013043 0.147068 -v 0.020762 0.013011 0.146735 -v 0.018908 0.017543 0.149937 -v 0.018908 0.021833 0.149134 -v 0.018908 0.026049 0.149433 -v 0.018907 0.023427 0.148644 -v 0.018908 0.016959 0.144906 -v 0.018908 0.015881 0.150182 -v 0.018908 0.015417 0.148701 -v 0.022697 0.024321 0.141729 -v 0.021324 0.017741 0.143127 -v 0.021324 0.012867 0.144163 -v 0.024065 0.012324 0.144278 -v 0.021324 0.023724 0.141855 -v 0.018908 0.024407 0.141710 -v 0.023434 0.024321 0.141729 -v 0.019496 0.013359 0.144058 -v 0.019989 0.023724 0.141855 -v 0.023434 0.012271 0.144290 -v 0.018908 0.012184 0.144308 -v 0.022697 0.012271 0.144290 -v 0.019707 0.013017 0.144131 -v 0.024065 0.014218 0.151816 -v 0.015504 0.012184 0.144308 -v 0.012117 0.012742 0.146935 -v 0.011831 0.013422 0.150131 -v 0.010265 0.022975 0.144228 -v 0.010265 0.014346 0.151876 -v 0.010265 0.014511 0.146027 -v 0.010266 0.020411 0.144778 -v 0.010265 0.017080 0.145475 -v 0.010265 0.021253 0.147531 -v 0.010265 0.017433 0.148343 -v 0.010265 0.015359 0.148800 -v 0.010265 0.015778 0.150173 -v 0.010265 0.017620 0.149857 -v 0.010265 0.021713 0.149037 -v 0.010301 0.023559 0.148976 -v 0.015504 0.024407 0.141710 -v 0.013329 0.024966 0.144337 -v 0.023442 0.026049 0.149434 -v 0.023760 0.024407 0.141710 -v 0.020467 0.025640 0.147509 -v 0.024065 0.017433 0.148343 -v 0.024065 0.022976 0.144235 -v 0.024065 0.014513 0.146034 -v 0.024065 0.015778 0.150173 -v 0.024065 0.015357 0.148796 -v 0.024065 0.023328 0.147099 -v 0.024065 0.021253 0.147531 -v 0.024065 0.017083 0.145488 -v 0.024065 0.020412 0.144781 -v 0.023760 0.012184 0.144308 -v 0.020751 0.012740 0.146926 -v 0.021962 0.012740 0.146926 -v 0.023442 0.013826 0.152032 -v 0.020467 0.013415 0.150098 -v 0.022246 0.013416 0.150104 -v 0.018908 0.013825 0.152031 -v 0.010219 0.013766 0.152452 -v 0.010265 0.025570 0.149458 -v 0.010150 0.014583 0.152236 -v 0.010341 0.025893 0.149282 -v 0.010152 0.026276 0.149790 -v 0.010570 0.026013 0.149263 -v 0.018792 0.026274 0.149767 -v 0.023944 0.025938 0.149273 -v 0.024065 0.021713 0.149037 -v 0.024148 0.026269 0.149751 -v 0.023950 0.013870 0.151838 -v 0.018814 0.013756 0.152407 -v 0.024148 0.013755 0.152418 -v 0.015504 0.013858 0.152184 -v 0.018650 0.025812 0.149992 -v 0.024151 0.026150 0.150533 -v 0.024150 0.019989 0.151039 -v 0.018142 0.013467 0.153753 -v 0.015650 0.014366 0.152898 -v 0.015747 0.013860 0.153399 -v 0.016034 0.026890 0.150852 -v 0.015336 0.013767 0.152485 -v 0.010149 0.013907 0.153143 -v 0.009641 0.013546 0.153736 -v 0.009975 0.014456 0.153324 -v 0.009601 0.026948 0.150888 -v 0.009825 0.026024 0.150993 -v 0.010150 0.026426 0.150476 -v 0.018181 0.027064 0.150863 -v 0.018485 0.020226 0.152088 -v 0.021312 0.026751 0.150796 -v 0.024678 0.013581 0.153728 -v 0.024616 0.027027 0.150871 -v 0.024334 0.020230 0.152108 -v 0.024151 0.013915 0.153165 -v 0.018896 0.013756 0.153557 -v 0.008925 0.012189 0.153361 -v 0.008925 0.012248 0.153519 -v 0.008439 0.012479 0.153760 -v 0.008598 0.027891 0.150605 -v 0.008925 0.028084 0.149982 -v 0.025853 0.028003 0.150456 -v 0.026002 0.027650 0.150270 -v 0.016300 0.015381 0.153347 -v 0.016300 0.025163 0.151268 -v 0.025471 0.027691 0.150729 -v 0.025476 0.012847 0.153885 -v 0.025375 0.012189 0.153361 -v 0.026025 0.012825 0.153226 -v 0.025976 0.012626 0.153555 -v 0.025575 0.012245 0.153521 -v 0.008925 0.012384 0.153700 -v 0.025375 0.012384 0.153700 -v 0.008925 0.012572 0.153822 -v 0.008275 0.027449 0.150118 -v 0.008292 0.012718 0.153411 -v 0.008299 0.027484 0.150281 -v 0.008398 0.027913 0.150412 -v 0.008812 0.012859 0.153882 -v 0.008275 0.026440 0.145374 -v 0.025375 0.028084 0.149982 -v 0.025625 0.028089 0.150240 -v 0.008616 0.028075 0.150309 -v 0.025727 0.027908 0.150581 -v 0.008861 0.027698 0.150728 -v 0.025756 0.026999 0.145273 -v 0.026025 0.027449 0.150118 -v 0.025748 0.012567 0.153825 -v 0.008925 0.011181 0.148617 -v 0.008275 0.011817 0.148482 -v 0.008275 0.012825 0.153226 -v 0.008925 0.027076 0.145238 -v 0.025375 0.027076 0.145238 -v 0.026025 0.011817 0.148482 -v 0.026150 0.011866 0.148471 -v 0.026025 0.026440 0.145374 -v 0.025300 0.027223 0.145207 -v 0.008540 0.026988 0.145279 -v 0.008150 0.026391 0.145384 -v 0.008150 0.011866 0.148471 -v 0.025740 0.011284 0.148624 -v 0.025375 0.011181 0.148617 -v 0.025300 0.011034 0.148648 -v 0.009000 0.011034 0.148648 -v 0.008150 0.012074 0.149450 -v 0.008150 0.026599 0.146362 -v 0.009000 0.027223 0.145207 -v 0.009000 0.027431 0.146185 -v 0.026150 0.026599 0.146362 -v 0.026098 0.027121 0.146026 -v 0.025300 0.027431 0.146185 -v 0.026150 0.026391 0.145384 -v 0.026150 0.012074 0.149450 -v 0.009000 0.011242 0.149626 -v 0.032038 0.014776 0.160530 -v 0.030060 0.015862 0.160299 -v 0.029327 0.017962 0.159853 -v 0.029495 0.018852 0.159664 -v 0.029378 0.018413 0.159757 -v 0.030946 0.020557 0.159301 -v 0.030560 0.020307 0.159354 -v 0.030214 0.020005 0.159419 -v 0.031366 0.020750 0.159260 -v 0.032732 0.020946 0.159218 -v 0.034440 0.020307 0.159354 -v 0.034054 0.020557 0.159301 -v 0.033634 0.020750 0.159260 -v 0.035324 0.019269 0.159575 -v 0.035082 0.019656 0.159493 -v 0.035656 0.017509 0.159949 -v 0.035673 0.017962 0.159853 -v 0.034619 0.015536 0.160368 -v 0.032962 0.014776 0.160530 -v 0.032500 0.012373 0.149386 -v 0.032038 0.012406 0.149379 -v 0.031585 0.014875 0.160509 -v 0.031152 0.012667 0.149324 -v 0.031152 0.015037 0.160474 -v 0.030748 0.015259 0.160427 -v 0.030381 0.015536 0.160368 -v 0.030381 0.013166 0.149217 -v 0.029790 0.016231 0.160221 -v 0.029578 0.014264 0.148984 -v 0.029578 0.016634 0.160135 -v 0.029428 0.017063 0.160044 -v 0.029344 0.017509 0.159949 -v 0.029327 0.015592 0.148702 -v 0.029378 0.016043 0.148606 -v 0.029495 0.016482 0.148513 -v 0.029676 0.016899 0.148424 -v 0.029676 0.019269 0.159575 -v 0.029918 0.019656 0.159493 -v 0.029918 0.017286 0.148342 -v 0.030946 0.018187 0.148150 -v 0.031366 0.018379 0.148109 -v 0.031810 0.020880 0.159232 -v 0.032268 0.020946 0.159218 -v 0.032268 0.018576 0.148067 -v 0.033190 0.020880 0.159232 -v 0.033634 0.018379 0.148109 -v 0.034054 0.018187 0.148150 -v 0.034786 0.020005 0.159419 -v 0.035324 0.016899 0.148424 -v 0.035505 0.018852 0.159664 -v 0.035505 0.016482 0.148513 -v 0.035622 0.018413 0.159757 -v 0.035673 0.015592 0.148702 -v 0.035572 0.017063 0.160044 -v 0.035422 0.014264 0.148984 -v 0.035422 0.016634 0.160135 -v 0.035210 0.016231 0.160221 -v 0.035210 0.013861 0.149070 -v 0.034940 0.013492 0.149148 -v 0.034940 0.015862 0.160299 -v 0.034619 0.013166 0.149217 -v 0.034252 0.015259 0.160427 -v 0.033848 0.015037 0.160474 -v 0.033848 0.012667 0.149324 -v 0.033415 0.014875 0.160509 -v 0.032962 0.012406 0.149379 -v 0.032500 0.014743 0.160537 -v 0.036500 0.017738 0.148246 -v 0.032500 0.019290 0.144440 -v 0.036500 0.012513 0.145880 -v 0.036500 0.013220 0.149206 -v 0.028500 0.017031 0.144920 -v 0.032500 0.010254 0.146360 -v 0.036500 0.017031 0.144920 -v 0.028500 0.012513 0.145880 -v 0.031810 0.018510 0.148082 -v 0.032732 0.018576 0.148067 -v 0.032500 0.010961 0.149686 -v 0.033415 0.012505 0.149358 -v 0.032500 0.019997 0.147766 -v 0.033190 0.018510 0.148082 -v 0.035656 0.015139 0.148798 -v 0.035572 0.014693 0.148893 -v 0.034252 0.012889 0.149276 -v 0.030060 0.013492 0.149148 -v 0.029790 0.013861 0.149070 -v 0.029428 0.014693 0.148893 -v 0.029344 0.015139 0.148798 -v 0.030214 0.017634 0.148268 -v 0.034440 0.017937 0.148203 -v 0.034786 0.017634 0.148268 -v 0.035082 0.017286 0.148342 -v 0.031585 0.012505 0.149358 -v 0.030748 0.012889 0.149276 -v 0.028500 0.013220 0.149206 -v 0.030560 0.017937 0.148203 -v 0.028500 0.017738 0.148246 -v 0.035622 0.016043 0.148606 -v 0.032500 0.026481 0.158042 -v 0.032962 0.026514 0.158035 -v 0.030060 0.027600 0.157804 -v 0.030748 0.026997 0.157932 -v 0.029428 0.028801 0.157549 -v 0.029578 0.028372 0.157640 -v 0.029790 0.027969 0.157726 -v 0.029378 0.030151 0.157262 -v 0.029495 0.030589 0.157169 -v 0.030946 0.032295 0.156806 -v 0.030214 0.031742 0.156924 -v 0.031810 0.032618 0.156737 -v 0.031366 0.032487 0.156765 -v 0.033190 0.032618 0.156737 -v 0.034440 0.032045 0.156859 -v 0.034054 0.032295 0.156806 -v 0.035082 0.031394 0.156998 -v 0.035673 0.029700 0.157358 -v 0.035505 0.030589 0.157169 -v 0.035422 0.028372 0.157640 -v 0.029344 0.029247 0.157454 -v 0.035656 0.029247 0.157454 -v 0.034940 0.027600 0.157804 -v 0.035210 0.027969 0.157726 -v 0.032038 0.024144 0.146884 -v 0.031585 0.026613 0.158014 -v 0.031585 0.024243 0.146863 -v 0.031152 0.026775 0.157979 -v 0.030748 0.024626 0.146781 -v 0.030381 0.027274 0.157873 -v 0.030381 0.024904 0.146723 -v 0.029790 0.025599 0.146575 -v 0.029327 0.029700 0.157358 -v 0.029676 0.031007 0.157080 -v 0.029676 0.028637 0.145929 -v 0.029918 0.031394 0.156998 -v 0.030560 0.032045 0.156859 -v 0.030560 0.029675 0.145708 -v 0.030946 0.029925 0.145655 -v 0.032268 0.030314 0.145573 -v 0.032268 0.032684 0.156723 -v 0.032732 0.032684 0.156723 -v 0.032732 0.030314 0.145573 -v 0.033634 0.032487 0.156765 -v 0.033634 0.030117 0.145614 -v 0.034440 0.029675 0.145708 -v 0.034786 0.031742 0.156924 -v 0.035082 0.029024 0.145847 -v 0.035324 0.031007 0.157080 -v 0.035622 0.027781 0.146111 -v 0.035622 0.030151 0.157262 -v 0.035656 0.026877 0.146303 -v 0.035572 0.028801 0.157549 -v 0.035572 0.026431 0.146398 -v 0.034619 0.027274 0.157873 -v 0.034619 0.024904 0.146723 -v 0.034252 0.026997 0.157932 -v 0.033848 0.026775 0.157979 -v 0.033415 0.026613 0.158014 -v 0.033415 0.024243 0.146863 -v 0.032962 0.024144 0.146884 -v 0.032500 0.024111 0.146891 -v 0.032038 0.026514 0.158035 -v 0.032500 0.031028 0.141945 -v 0.032500 0.031734 0.145271 -v 0.036500 0.028769 0.142425 -v 0.036500 0.024251 0.143385 -v 0.028500 0.028769 0.142425 -v 0.032500 0.021992 0.143866 -v 0.028500 0.024251 0.143385 -v 0.036500 0.024958 0.146711 -v 0.032500 0.022699 0.147191 -v 0.033848 0.024405 0.146829 -v 0.034054 0.029925 0.145655 -v 0.033190 0.030248 0.145587 -v 0.035422 0.026002 0.146489 -v 0.035210 0.025599 0.146575 -v 0.034940 0.025230 0.146653 -v 0.034252 0.024626 0.146781 -v 0.030060 0.025230 0.146653 -v 0.029578 0.026002 0.146489 -v 0.029428 0.026431 0.146398 -v 0.029344 0.026877 0.146303 -v 0.029327 0.027330 0.146207 -v 0.029378 0.027781 0.146111 -v 0.029495 0.028219 0.146018 -v 0.028500 0.029475 0.145751 -v 0.029918 0.029024 0.145847 -v 0.030214 0.029372 0.145773 -v 0.034786 0.029372 0.145773 -v 0.036500 0.029475 0.145751 -v 0.031152 0.024405 0.146829 -v 0.028500 0.024958 0.146711 -v 0.031366 0.030117 0.145614 -v 0.031810 0.030248 0.145587 -v 0.035324 0.028637 0.145929 -v 0.035505 0.028219 0.146018 -v 0.035673 0.027330 0.146207 -v 0.038214 -0.061072 0.139035 -v 0.035436 -0.062216 0.138792 -v 0.003786 -0.061072 0.139035 -v 0.035419 -0.056741 0.139955 -v 0.036371 -0.001741 0.151646 -v 0.024750 -0.062216 0.138792 -v 0.034083 -0.058597 0.139561 -v 0.002003 -0.057760 0.139738 -v 0.039989 -0.058190 0.139647 -v 0.036299 -0.059703 0.139326 -v 0.006581 -0.056741 0.139955 -v 0.002000 -0.037762 0.143989 -v 0.002000 -0.012465 0.149366 -v 0.034907 -0.006757 0.150580 -v 0.002000 -0.008846 0.150136 -v 0.037204 -0.059147 0.139451 -v 0.006053 -0.001605 0.151675 -v 0.002009 -0.005706 0.150804 -v 0.007093 -0.006757 0.150580 -v 0.037375 -0.006170 0.150705 -v 0.002886 -0.003639 0.151242 -v 0.035384 -0.004185 0.151133 -v 0.037941 -0.002485 0.151488 -v 0.005396 -0.059619 0.139354 -v 0.039151 -0.003703 0.151229 -v 0.035000 -0.001571 0.151682 -v 0.004083 -0.002480 0.151489 -v 0.006023 -0.004043 0.151160 -v 0.008764 0.052530 0.140850 -v 0.021710 0.052545 0.140847 -v 0.022041 0.051974 0.140986 -v 0.008475 0.051949 0.140962 -v 0.008001 0.052056 0.140952 -v 0.022550 0.051894 0.140986 -v 0.008000 0.046923 0.142042 -v 0.022550 0.046923 0.142042 -v 0.022290 0.037701 0.144002 -v 0.022550 0.036921 0.144168 -v 0.008000 0.037027 0.144146 -v 0.021985 0.036946 0.144323 -v 0.021565 0.036658 0.144217 -v 0.009375 0.036610 0.144234 -v 0.008769 0.027539 0.146162 -v 0.021869 0.036384 0.144283 -v 0.021620 0.036356 0.144288 -v 0.009375 0.052290 0.140901 -v 0.016213 0.027553 0.146159 -v 0.008547 0.027476 0.146175 -v 0.025584 0.027553 0.146159 -v 0.008000 0.026643 0.146353 -v 0.026300 0.012030 0.149459 -v 0.008496 0.011393 0.149116 -v 0.026073 0.011431 0.149342 -v 0.025300 0.011242 0.149626 -v 0.025370 0.011120 0.149652 -v 0.019761 0.011450 0.151205 -v 0.025672 0.011160 0.149644 -v 0.022163 0.062546 0.140344 -v 0.006132 0.062472 0.140360 -v 0.035868 0.062472 0.140360 -v 0.005291 0.062251 0.140407 -v 0.015810 0.062546 0.140344 -v 0.008980 0.059168 0.141063 -v 0.035000 0.062546 0.140344 -v 0.034676 0.061327 0.140603 -v 0.007961 0.060968 0.140679 -v 0.031550 0.062546 0.140344 -v 0.038214 0.061402 0.140588 -v 0.021620 0.052875 0.142400 -v 0.010113 0.062546 0.140344 -v 0.007000 0.062546 0.140344 -v 0.039330 0.060101 0.140864 -v 0.002670 0.060101 0.140864 -v 0.002302 0.059328 0.141028 -v 0.039698 0.059328 0.141028 -v 0.029712 0.062546 0.140344 -v 0.039924 0.058505 0.141203 -v 0.038978 0.059171 0.141061 -v 0.010113 0.036686 0.145841 -v 0.002000 0.057655 0.141384 -v 0.038692 0.057152 0.141490 -v 0.024038 0.062546 0.140344 -v 0.003342 0.057095 0.141502 -v 0.036825 0.055756 0.141787 -v 0.022332 0.052550 0.142469 -v 0.040000 0.053914 0.142179 -v 0.008954 0.058124 0.141284 -v 0.015810 0.052875 0.142400 -v 0.005018 0.055830 0.141772 -v 0.002000 0.055326 0.141879 -v 0.026082 0.027558 0.147781 -v 0.038830 0.060799 0.140716 -v 0.002000 0.053914 0.142179 -v 0.006132 0.001975 0.153219 -v 0.008640 0.052873 0.142400 -v 0.027813 0.062546 0.140344 -v 0.040000 0.055326 0.141879 -v 0.040000 0.036812 0.145814 -v 0.022550 0.051965 0.142593 -v 0.008000 0.037596 0.145648 -v 0.040000 0.035647 0.146062 -v 0.002000 0.036812 0.145814 -v 0.002000 0.035647 0.146062 -v 0.021620 0.036686 0.145841 -v 0.015810 0.036686 0.145841 -v 0.015810 0.027883 0.147712 -v 0.008000 0.051965 0.142593 -v 0.005703 0.061607 0.140542 -v 0.008478 0.036820 0.145812 -v 0.038137 0.060764 0.140719 -v 0.033278 0.057374 0.141444 -v 0.036497 0.061555 0.140554 -v 0.035479 0.008703 0.151789 -v 0.019761 0.052875 0.142400 -v 0.040000 0.021678 0.149031 -v 0.003077 0.006764 0.152199 -v 0.002000 0.007982 0.151942 -v 0.024038 0.001901 0.153235 -v 0.002000 0.031065 0.147036 -v 0.019761 0.027883 0.147712 -v 0.033345 0.007231 0.152102 -v 0.033046 0.006323 0.152295 -v 0.026300 0.026973 0.147906 -v 0.025570 0.011481 0.151198 -v 0.035479 0.055744 0.141790 -v 0.002000 0.021678 0.149031 -v 0.004544 0.008419 0.151849 -v 0.008145 0.007951 0.151948 -v 0.034070 0.056350 0.141662 -v 0.025835 0.027761 0.147738 -v 0.040000 0.007982 0.151942 -v 0.034481 0.008375 0.151859 -v 0.026211 0.011913 0.151107 -v 0.002000 0.006792 0.152195 -v 0.015810 0.011450 0.151205 -v 0.039084 0.005846 0.152392 -v 0.039924 0.005942 0.152376 -v 0.002670 0.004346 0.152715 -v 0.003350 0.004274 0.152722 -v 0.019761 0.001901 0.153235 -v 0.003786 0.003045 0.152992 -v 0.004500 0.002556 0.153096 -v 0.036710 0.002196 0.153172 -v 0.005241 0.002920 0.153015 -v 0.005291 0.002196 0.153172 -v 0.037500 0.002556 0.153096 -v 0.007000 0.001901 0.153235 -v 0.022163 0.001901 0.153235 -v 0.029713 0.001901 0.153235 -v 0.010113 0.001901 0.153235 -v 0.004524 0.005939 0.150758 -v 0.034704 0.057606 0.139782 -v 0.006334 0.056859 0.139953 -v 0.032200 0.060736 0.131831 -v 0.016213 0.060736 0.131831 -v 0.010113 0.060736 0.131831 -v 0.007038 0.000091 0.144722 -v 0.007057 0.060736 0.131831 -v 0.037500 0.060081 0.131970 -v 0.005290 0.000386 0.144659 -v 0.039924 0.004133 0.143863 -v 0.039330 0.058291 0.132351 -v 0.039924 0.056695 0.132690 -v 0.040000 0.054152 0.133231 -v 0.036714 0.060440 0.131894 -v 0.040000 0.052104 0.133666 -v 0.029713 0.060736 0.131831 -v 0.040000 0.045444 0.135082 -v 0.002000 0.031979 0.137944 -v 0.002000 0.029255 0.138523 -v 0.040000 0.029255 0.138523 -v 0.040000 0.027052 0.138991 -v 0.040000 0.006675 0.143322 -v 0.002076 0.004133 0.143863 -v 0.002000 0.052104 0.133666 -v 0.010113 0.000091 0.144722 -v 0.038214 0.059592 0.132074 -v 0.040000 0.055846 0.132871 -v 0.002302 0.003309 0.144038 -v 0.039698 0.003308 0.144038 -v 0.039330 0.002537 0.144202 -v 0.038830 0.001838 0.144350 -v 0.036709 0.000385 0.144659 -v 0.002000 0.007668 0.143111 -v 0.038830 0.058989 0.132202 -v 0.006132 0.000166 0.144706 -v 0.037500 0.000747 0.144582 -v 0.032200 0.000091 0.144722 -v 0.003170 0.001838 0.144350 -v 0.016213 0.000091 0.144722 -v 0.040000 0.010267 0.142559 -v 0.029713 0.000091 0.144722 -v 0.002670 0.058291 0.132351 -# 15983 vertices, 0 vertices normals - -f 1 20 30 -f 1 22 20 -f 4 22 1 -f 4 24 22 -f 3 25 24 -f 2 24 4 -f 30 20 6 -f 6 25 5 -f 5 25 3 -f 30 6 5 -f 3 24 2 -f 7 8 23 -f 7 9 8 -f 8 9 10 -f 10 11 12 -f 12 11 13 -f 14 12 13 -f 12 14 100 -f 14 15 100 -f 14 18 15 -f 15 18 16 -f 18 19 16 -f 16 19 17 -f 17 19 21 -f 17 21 23 -f 25 6 14 -f 18 14 6 -f 18 6 19 -f 6 20 19 -f 21 19 20 -f 22 21 20 -f 21 22 23 -f 7 23 22 -f 22 24 7 -f 9 7 24 -f 10 9 11 -f 11 9 24 -f 13 11 24 -f 25 13 24 -f 25 14 13 -f 4 1 26 -f 26 1 32 -f 2 4 28 -f 28 4 26 -f 3 2 27 -f 27 2 28 -f 5 3 29 -f 29 3 27 -f 30 5 31 -f 31 5 29 -f 1 30 32 -f 32 30 31 -f 31 29 32 -f 32 29 27 -f 32 27 26 -f 26 27 28 -f 33 45 43 -f 34 45 33 -f 34 46 45 -f 53 46 34 -f 35 50 48 -f 35 48 53 -f 53 48 46 -f 36 50 37 -f 33 43 36 -f 37 50 35 -f 41 38 99 -f 47 38 41 -f 38 47 96 -f 47 49 96 -f 51 52 39 -f 52 42 39 -f 39 42 98 -f 98 42 44 -f 40 98 44 -f 41 99 40 -f 49 47 48 -f 36 43 52 -f 42 52 43 -f 44 42 43 -f 43 45 44 -f 40 44 45 -f 40 45 46 -f 41 40 46 -f 47 41 46 -f 47 46 48 -f 50 49 48 -f 49 50 51 -f 52 51 50 -f 36 52 50 -f 53 34 54 -f 54 34 57 -f 35 53 59 -f 59 53 54 -f 37 35 55 -f 55 35 59 -f 36 37 58 -f 58 37 55 -f 33 36 56 -f 56 36 58 -f 34 33 57 -f 57 33 56 -f 56 58 57 -f 57 58 55 -f 57 55 54 -f 54 55 59 -f 62 77 84 -f 63 61 62 -f 62 61 77 -f 65 81 61 -f 65 61 63 -f 60 74 64 -f 84 77 74 -f 84 74 60 -f 64 81 65 -f 78 66 94 -f 94 66 79 -f 79 80 71 -f 68 67 73 -f 73 69 68 -f 73 72 69 -f 72 97 69 -f 76 95 97 -f 95 76 70 -f 70 76 78 -f 78 94 70 -f 67 71 81 -f 64 74 73 -f 73 74 72 -f 72 75 97 -f 75 72 74 -f 75 74 77 -f 75 76 97 -f 77 76 75 -f 78 76 77 -f 61 78 77 -f 66 78 61 -f 61 79 66 -f 61 80 79 -f 81 80 61 -f 81 71 80 -f 81 73 67 -f 73 81 64 -f 63 62 82 -f 82 62 83 -f 65 63 88 -f 88 63 82 -f 64 65 87 -f 87 65 88 -f 60 64 85 -f 85 64 87 -f 84 60 86 -f 86 60 85 -f 62 84 83 -f 83 84 86 -f 86 85 83 -f 83 85 87 -f 83 87 82 -f 82 87 88 -f 118 115 112 -f 110 90 91 -f 89 112 91 -f 91 112 110 -f 93 116 115 -f 118 112 89 -f 92 106 116 -f 92 116 93 -f 90 106 92 -f 93 115 118 -f 68 69 70 -f 94 79 67 -f 94 68 70 -f 67 68 94 -f 70 69 95 -f 71 67 79 -f 97 95 69 -f 51 96 49 -f 96 51 39 -f 38 96 39 -f 99 38 39 -f 39 98 99 -f 98 40 99 -f 23 100 15 -f 8 10 12 -f 8 12 100 -f 111 114 101 -f 114 113 101 -f 102 113 104 -f 102 104 125 -f 125 104 105 -f 125 105 124 -f 124 105 107 -f 107 108 124 -f 108 109 103 -f 109 111 103 -f 106 105 116 -f 107 105 106 -f 106 90 107 -f 108 107 90 -f 109 108 90 -f 90 110 109 -f 111 109 110 -f 114 111 110 -f 114 110 112 -f 113 114 112 -f 115 113 112 -f 113 115 104 -f 115 116 104 -f 105 104 116 -f 89 91 117 -f 117 91 122 -f 118 89 119 -f 119 89 117 -f 93 118 123 -f 123 118 119 -f 92 93 120 -f 120 93 123 -f 90 92 121 -f 121 92 120 -f 91 90 122 -f 122 90 121 -f 121 120 122 -f 122 120 123 -f 122 123 117 -f 117 123 119 -f 8 100 23 -f 17 23 15 -f 17 15 16 -f 113 102 101 -f 102 125 111 -f 101 102 111 -f 125 124 103 -f 111 125 103 -f 124 108 103 -f 126 1942 1943 -f 131 9589 126 -f 2164 668 128 -f 128 668 2147 -f 126 1943 131 -f 131 1943 2137 -f 131 2137 129 -f 9483 2113 9484 -f 9484 2113 1658 -f 1658 2113 127 -f 2127 2126 668 -f 668 2126 130 -f 131 2147 668 -f 131 668 2123 -f 2123 668 130 -f 129 2138 131 -f 131 2138 2147 -f 1658 127 132 -f 1658 132 2114 -f 1658 2114 668 -f 668 2114 2130 -f 668 2130 2127 -f 719 149 154 -f 143 1953 145 -f 668 2164 672 -f 672 2164 136 -f 2169 666 2170 -f 2170 666 133 -f 2170 133 135 -f 135 133 134 -f 135 134 2175 -f 2175 134 667 -f 2175 667 136 -f 136 667 669 -f 136 669 672 -f 139 647 138 -f 2169 2168 666 -f 666 2168 137 -f 666 137 648 -f 648 137 138 -f 648 138 647 -f 139 138 140 -f 140 138 2166 -f 140 2166 141 -f 660 142 148 -f 148 142 658 -f 148 658 146 -f 141 143 140 -f 140 143 145 -f 140 145 144 -f 144 145 148 -f 144 148 657 -f 657 148 146 -f 151 147 148 -f 154 149 148 -f 148 149 150 -f 148 150 151 -f 147 661 148 -f 148 661 660 -f 724 152 9454 -f 9454 152 153 -f 9454 153 154 -f 154 153 720 -f 154 720 719 -f 9607 1819 728 -f 728 727 9607 -f 9607 727 155 -f 9607 155 9454 -f 9454 155 725 -f 9454 725 724 -f 9588 1865 1864 -f 2206 2192 708 -f 708 2192 156 -f 708 156 160 -f 157 1851 9588 -f 156 2182 160 -f 160 2182 2179 -f 2179 2177 160 -f 160 2177 2176 -f 160 2176 157 -f 2094 2086 157 -f 9588 1864 157 -f 157 1864 2087 -f 157 2087 159 -f 157 2086 160 -f 160 2086 158 -f 160 158 2073 -f 160 2075 2076 -f 160 2076 9486 -f 9486 2076 2060 -f 159 2094 157 -f 2073 2075 160 -f 1681 624 1763 -f 1763 624 9488 -f 162 161 166 -f 160 9486 617 -f 617 9486 161 -f 617 161 616 -f 616 161 162 -f 164 163 628 -f 164 162 163 -f 163 162 166 -f 163 166 165 -f 165 166 627 -f 9488 624 166 -f 166 624 1683 -f 166 1683 627 -f 433 9495 167 -f 167 9495 169 -f 167 169 168 -f 168 169 170 -f 168 170 429 -f 9489 171 170 -f 170 171 429 -f 172 427 9489 -f 9489 427 171 -f 1837 1735 172 -f 172 1735 428 -f 172 428 427 -f 195 288 175 -f 246 296 294 -f 174 293 291 -f 174 291 173 -f 174 173 179 -f 195 175 176 -f 195 176 198 -f 198 176 177 -f 198 177 178 -f 183 184 214 -f 214 184 1618 -f 214 1618 173 -f 173 1618 1617 -f 173 1617 179 -f 180 181 183 -f 183 181 182 -f 183 182 184 -f 177 185 178 -f 178 185 1754 -f 178 1754 186 -f 186 1754 1753 -f 186 1753 187 -f 187 1753 1750 -f 187 1750 201 -f 188 1615 180 -f 180 1615 189 -f 180 189 181 -f 1750 1755 201 -f 201 1755 190 -f 201 190 203 -f 203 190 1757 -f 203 1757 223 -f 194 1611 191 -f 191 1611 188 -f 188 1611 192 -f 188 192 1615 -f 220 193 194 -f 194 193 1610 -f 194 1610 1611 -f 196 195 198 -f 196 198 197 -f 197 198 178 -f 197 178 199 -f 199 178 186 -f 199 186 233 -f 233 186 187 -f 233 187 200 -f 200 187 201 -f 200 201 202 -f 202 201 203 -f 202 203 204 -f 204 203 223 -f 204 223 205 -f 205 223 224 -f 205 224 206 -f 206 224 226 -f 206 226 227 -f 246 294 234 -f 246 234 245 -f 245 234 207 -f 245 207 243 -f 243 207 232 -f 243 232 242 -f 242 232 208 -f 242 208 209 -f 209 208 210 -f 209 210 239 -f 239 210 231 -f 239 231 238 -f 238 231 230 -f 238 230 211 -f 211 230 229 -f 211 229 237 -f 237 229 212 -f 237 212 236 -f 291 213 244 -f 291 244 173 -f 173 244 241 -f 173 241 214 -f 214 241 240 -f 214 240 183 -f 183 240 215 -f 183 215 180 -f 180 215 216 -f 180 216 188 -f 188 216 217 -f 188 217 191 -f 191 217 218 -f 191 218 194 -f 194 218 219 -f 194 219 220 -f 220 219 221 -f 220 221 247 -f 1605 1606 247 -f 247 1606 1602 -f 247 1602 220 -f 220 1602 1608 -f 220 1608 193 -f 1757 222 223 -f 223 222 225 -f 223 225 224 -f 224 225 1759 -f 224 1759 226 -f 226 1759 287 -f 287 286 226 -f 226 286 227 -f 227 286 228 -f 228 212 227 -f 227 212 229 -f 227 229 206 -f 206 229 230 -f 206 230 205 -f 205 230 231 -f 205 231 204 -f 204 231 210 -f 204 210 202 -f 202 210 208 -f 202 208 200 -f 200 208 232 -f 200 232 233 -f 233 232 207 -f 233 207 199 -f 199 207 234 -f 199 234 197 -f 197 234 294 -f 197 294 196 -f 228 235 212 -f 212 235 236 -f 236 235 276 -f 236 276 275 -f 275 221 236 -f 236 221 219 -f 236 219 237 -f 237 219 218 -f 237 218 211 -f 211 218 217 -f 211 217 238 -f 238 217 216 -f 238 216 239 -f 239 216 215 -f 239 215 209 -f 209 215 240 -f 209 240 242 -f 242 240 241 -f 242 241 243 -f 243 241 244 -f 243 244 245 -f 245 244 213 -f 245 213 246 -f 267 1605 268 -f 268 1605 247 -f 268 247 221 -f 268 221 275 -f 276 235 273 -f 310 250 1729 -f 1729 250 249 -f 249 250 1161 -f 1161 250 252 -f 252 250 251 -f 252 251 253 -f 252 253 1160 -f 1160 253 1159 -f 1159 253 263 -f 1159 263 1158 -f 1158 263 1154 -f 1154 263 254 -f 1154 254 255 -f 1154 255 1155 -f 1155 255 1156 -f 1156 255 265 -f 1156 265 256 -f 256 265 257 -f 256 257 285 -f 258 1637 259 -f 259 1637 260 -f 259 260 261 -f 259 261 1634 -f 259 1634 268 -f 268 1634 1603 -f 310 308 250 -f 250 308 262 -f 250 262 251 -f 251 262 279 -f 251 279 253 -f 253 279 264 -f 253 264 263 -f 263 264 254 -f 254 264 280 -f 254 280 255 -f 255 280 282 -f 255 282 265 -f 265 282 266 -f 265 266 257 -f 257 266 283 -f 257 283 284 -f 1603 267 268 -f 248 258 269 -f 269 258 259 -f 269 259 272 -f 272 259 268 -f 272 268 274 -f 274 268 275 -f 270 248 277 -f 277 248 269 -f 277 269 278 -f 278 269 272 -f 278 272 271 -f 271 272 281 -f 281 272 274 -f 281 274 273 -f 273 274 275 -f 273 275 276 -f 308 270 277 -f 308 277 262 -f 262 277 279 -f 279 277 278 -f 279 278 264 -f 264 278 271 -f 264 271 280 -f 280 271 281 -f 280 281 282 -f 282 281 273 -f 282 273 266 -f 266 273 283 -f 283 273 235 -f 235 228 283 -f 283 228 284 -f 284 228 286 -f 285 257 284 -f 285 284 1152 -f 1152 284 286 -f 1152 286 287 -f 195 317 288 -f 1793 290 289 -f 289 290 291 -f 291 292 289 -f 293 292 291 -f 291 290 213 -f 290 1793 298 -f 290 298 213 -f 317 195 313 -f 313 195 196 -f 313 196 295 -f 295 196 294 -f 295 294 296 -f 295 296 297 -f 297 296 246 -f 297 246 298 -f 298 246 213 -f 1793 354 298 -f 298 354 297 -f 299 398 303 -f 301 300 1638 -f 1638 300 1633 -f 306 309 307 -f 301 258 302 -f 301 302 300 -f 300 302 303 -f 300 303 398 -f 258 248 302 -f 302 248 304 -f 302 304 303 -f 303 304 305 -f 303 305 299 -f 248 270 304 -f 304 270 306 -f 304 306 305 -f 305 306 307 -f 305 307 299 -f 299 307 420 -f 270 308 306 -f 306 308 309 -f 309 308 310 -f 1368 420 1713 -f 1713 420 307 -f 1713 307 1711 -f 1711 307 309 -f 1711 309 1710 -f 1710 309 310 -f 1710 310 1729 -f 295 297 311 -f 364 313 295 -f 325 317 313 -f 314 288 317 -f 314 317 315 -f 1745 316 327 -f 327 316 315 -f 327 315 325 -f 325 315 317 -f 322 353 319 -f 319 353 318 -f 319 318 320 -f 320 318 354 -f 320 354 1793 -f 1792 333 322 -f 322 333 321 -f 322 321 353 -f 1745 327 323 -f 323 327 328 -f 323 328 324 -f 313 364 325 -f 325 364 326 -f 325 326 327 -f 327 326 363 -f 327 363 328 -f 328 363 361 -f 328 361 324 -f 324 361 359 -f 324 359 331 -f 331 359 357 -f 331 357 330 -f 330 357 329 -f 330 329 346 -f 346 1737 1741 -f 346 1741 330 -f 330 1741 1742 -f 330 1742 331 -f 331 1742 332 -f 331 332 324 -f 324 332 1743 -f 324 1743 323 -f 1792 334 333 -f 333 334 335 -f 333 335 350 -f 350 335 336 -f 350 336 349 -f 349 336 337 -f 349 337 348 -f 348 337 1796 -f 348 1796 338 -f 295 311 312 -f 312 311 340 -f 312 340 339 -f 339 340 352 -f 339 352 362 -f 362 352 351 -f 362 351 360 -f 360 351 341 -f 360 341 342 -f 342 341 347 -f 342 347 358 -f 358 347 343 -f 358 343 356 -f 356 343 344 -f 356 344 355 -f 1733 1737 345 -f 345 1737 346 -f 345 346 365 -f 365 346 329 -f 1796 433 338 -f 338 433 434 -f 434 344 338 -f 338 344 343 -f 338 343 348 -f 348 343 347 -f 348 347 349 -f 349 347 341 -f 349 341 350 -f 350 341 351 -f 350 351 333 -f 333 351 352 -f 333 352 321 -f 321 352 340 -f 321 340 353 -f 353 340 311 -f 353 311 318 -f 318 311 297 -f 318 297 354 -f 434 431 344 -f 344 431 355 -f 355 431 432 -f 355 432 426 -f 426 365 355 -f 355 365 329 -f 355 329 356 -f 356 329 357 -f 356 357 358 -f 358 357 359 -f 358 359 342 -f 342 359 361 -f 342 361 360 -f 360 361 363 -f 360 363 362 -f 362 363 326 -f 362 326 339 -f 339 326 364 -f 339 364 312 -f 312 364 295 -f 1734 1733 430 -f 430 1733 345 -f 430 345 365 -f 430 365 426 -f 382 292 367 -f 367 292 293 -f 368 1793 289 -f 368 289 369 -f 367 1621 382 -f 382 1621 1624 -f 382 1624 380 -f 1790 1788 379 -f 379 1788 369 -f 379 369 381 -f 381 369 289 -f 381 289 292 -f 1624 1625 380 -f 380 1625 1626 -f 380 1626 370 -f 1626 371 370 -f 370 371 1628 -f 370 1628 373 -f 1790 379 1791 -f 1791 379 378 -f 1791 378 372 -f 1628 1629 373 -f 373 1629 374 -f 373 374 377 -f 374 375 377 -f 377 375 1630 -f 377 1630 376 -f 376 1630 1632 -f 376 1632 383 -f 377 372 373 -f 373 372 378 -f 373 378 370 -f 370 378 379 -f 370 379 380 -f 380 379 381 -f 380 381 382 -f 382 381 292 -f 383 384 376 -f 376 384 1783 -f 376 1783 377 -f 377 1783 1786 -f 377 1786 372 -f 372 1786 1787 -f 372 1787 1791 -f 516 503 410 -f 410 503 399 -f 385 1604 1635 -f 385 1635 386 -f 517 516 1377 -f 1377 516 387 -f 1377 387 1376 -f 1376 387 411 -f 1376 411 413 -f 413 1374 388 -f 413 388 1376 -f 413 415 1374 -f 1374 415 416 -f 1374 416 389 -f 389 416 1371 -f 1371 416 390 -f 1371 390 391 -f 391 390 393 -f 391 393 1366 -f 1635 1636 386 -f 386 1636 392 -f 386 392 397 -f 397 392 1633 -f 1366 393 421 -f 1366 421 394 -f 394 421 1367 -f 395 385 386 -f 395 386 400 -f 400 386 397 -f 400 397 401 -f 401 397 396 -f 396 397 300 -f 397 1633 300 -f 396 300 398 -f 399 395 400 -f 399 400 409 -f 409 400 408 -f 408 400 401 -f 408 401 406 -f 406 401 405 -f 405 401 396 -f 405 396 404 -f 404 396 402 -f 402 396 398 -f 402 398 299 -f 299 419 402 -f 402 419 403 -f 402 403 404 -f 404 403 418 -f 404 418 405 -f 405 418 417 -f 405 417 406 -f 406 417 407 -f 406 407 408 -f 408 407 414 -f 408 414 412 -f 408 412 409 -f 409 412 410 -f 409 410 399 -f 419 299 420 -f 516 410 387 -f 387 410 412 -f 387 412 411 -f 411 412 414 -f 411 414 413 -f 413 414 407 -f 413 407 415 -f 415 407 417 -f 415 417 416 -f 416 417 418 -f 416 418 390 -f 390 418 393 -f 393 418 403 -f 393 403 421 -f 421 403 419 -f 421 419 425 -f 425 419 420 -f 1367 421 422 -f 422 421 425 -f 422 425 423 -f 423 425 424 -f 424 425 420 -f 424 420 1368 -f 432 429 171 -f 432 171 427 -f 431 167 168 -f 431 168 429 -f 428 1735 1734 -f 428 1734 430 -f 427 428 430 -f 427 430 426 -f 426 432 427 -f 432 431 429 -f 433 167 434 -f 434 167 431 -f 435 1604 385 -f 501 499 436 -f 506 490 498 -f 1612 1613 437 -f 475 466 438 -f 482 1614 481 -f 474 483 473 -f 1619 1620 463 -f 1698 1694 451 -f 523 439 450 -f 441 448 443 -f 441 443 442 -f 443 447 521 -f 443 521 442 -f 445 444 551 -f 1694 444 451 -f 451 444 445 -f 451 445 446 -f 446 445 447 -f 446 447 453 -f 453 447 443 -f 453 443 454 -f 454 443 448 -f 454 448 456 -f 456 448 440 -f 456 440 449 -f 449 440 450 -f 449 450 458 -f 458 450 439 -f 1697 1698 452 -f 452 1698 451 -f 452 451 461 -f 461 451 446 -f 461 446 462 -f 462 446 453 -f 462 453 455 -f 455 453 454 -f 455 454 464 -f 464 454 456 -f 464 456 457 -f 457 456 449 -f 457 449 1616 -f 1616 449 458 -f 1619 463 465 -f 459 1697 460 -f 460 1697 452 -f 460 452 467 -f 467 452 461 -f 467 461 469 -f 469 461 462 -f 469 462 471 -f 471 462 455 -f 471 455 472 -f 472 455 464 -f 472 464 463 -f 463 464 457 -f 463 457 465 -f 465 457 1616 -f 466 459 438 -f 438 459 460 -f 438 460 476 -f 476 460 467 -f 476 467 468 -f 468 467 469 -f 468 469 470 -f 470 469 471 -f 470 471 480 -f 480 471 472 -f 480 472 473 -f 473 472 463 -f 473 463 474 -f 474 463 1620 -f 1701 475 487 -f 487 475 438 -f 487 438 477 -f 477 438 476 -f 477 476 478 -f 478 476 468 -f 478 468 479 -f 479 468 470 -f 479 470 484 -f 484 470 480 -f 484 480 481 -f 481 480 473 -f 481 473 482 -f 482 473 483 -f 1614 1612 481 -f 481 1612 437 -f 481 437 484 -f 484 437 485 -f 484 485 479 -f 479 485 486 -f 479 486 478 -f 478 486 507 -f 478 507 477 -f 477 507 508 -f 477 508 487 -f 487 508 509 -f 487 509 1701 -f 512 488 509 -f 509 488 489 -f 509 489 1701 -f 504 494 505 -f 505 494 495 -f 505 495 490 -f 506 499 491 -f 491 499 501 -f 491 501 510 -f 490 495 498 -f 498 495 496 -f 498 496 492 -f 502 493 500 -f 494 1609 495 -f 495 1609 1607 -f 495 1607 496 -f 496 1607 497 -f 496 497 435 -f 435 385 496 -f 496 385 492 -f 492 385 395 -f 506 498 499 -f 499 498 492 -f 499 492 436 -f 436 492 395 -f 436 395 399 -f 436 399 502 -f 436 502 501 -f 501 502 500 -f 501 500 510 -f 510 500 511 -f 502 399 503 -f 502 503 493 -f 493 503 516 -f 511 500 513 -f 513 500 493 -f 513 493 514 -f 514 493 516 -f 1613 504 437 -f 437 504 505 -f 437 505 485 -f 485 505 490 -f 485 490 486 -f 486 490 506 -f 486 506 507 -f 507 506 491 -f 507 491 508 -f 508 491 510 -f 508 510 509 -f 509 510 511 -f 509 511 512 -f 512 511 513 -f 512 513 515 -f 515 513 514 -f 515 514 1704 -f 1704 514 516 -f 1704 516 517 -f 1773 522 518 -f 519 520 518 -f 518 520 1773 -f 442 521 554 -f 554 521 563 -f 563 521 447 -f 563 447 553 -f 553 447 445 -f 553 445 551 -f 442 554 441 -f 441 554 519 -f 441 519 448 -f 448 519 518 -f 448 518 440 -f 440 518 522 -f 440 522 450 -f 450 522 523 -f 1773 525 522 -f 522 525 523 -f 1773 524 525 -f 525 524 528 -f 526 523 1622 -f 1622 523 527 -f 1622 527 1623 -f 1623 527 533 -f 1623 533 534 -f 525 528 548 -f 548 528 529 -f 548 529 530 -f 530 529 1778 -f 530 1778 535 -f 531 532 533 -f 533 532 1627 -f 533 1627 534 -f 1778 1770 535 -f 535 1770 537 -f 535 537 536 -f 536 537 1780 -f 536 1780 541 -f 546 538 547 -f 547 538 539 -f 547 539 531 -f 531 539 540 -f 531 540 532 -f 1780 1779 541 -f 541 1779 542 -f 541 542 550 -f 550 542 543 -f 550 543 544 -f 544 543 545 -f 550 546 541 -f 541 546 547 -f 541 547 536 -f 536 547 531 -f 536 531 535 -f 535 531 533 -f 535 533 530 -f 530 533 527 -f 530 527 548 -f 548 527 523 -f 548 523 525 -f 544 549 550 -f 550 549 1631 -f 550 1631 546 -f 551 552 553 -f 553 552 564 -f 553 564 563 -f 576 519 554 -f 555 520 519 -f 1775 1773 520 -f 520 555 1775 -f 1775 555 556 -f 1775 556 557 -f 557 556 558 -f 557 558 1776 -f 552 559 564 -f 564 559 1691 -f 564 1691 566 -f 566 1691 1686 -f 566 1686 560 -f 560 1686 1684 -f 560 1684 561 -f 562 570 561 -f 561 570 569 -f 561 569 560 -f 563 564 565 -f 565 564 566 -f 565 566 567 -f 567 566 560 -f 567 560 568 -f 568 560 569 -f 568 569 591 -f 591 569 570 -f 591 570 571 -f 571 570 572 -f 571 572 590 -f 590 572 574 -f 590 574 573 -f 573 574 588 -f 573 588 575 -f 554 594 576 -f 576 594 593 -f 576 593 577 -f 577 593 592 -f 577 592 596 -f 596 592 578 -f 596 578 597 -f 597 578 579 -f 597 579 599 -f 599 579 580 -f 599 580 582 -f 582 580 581 -f 582 581 584 -f 584 581 583 -f 584 583 595 -f 562 585 570 -f 570 585 586 -f 570 586 572 -f 572 586 587 -f 572 587 574 -f 574 587 588 -f 588 587 1680 -f 588 1680 1682 -f 1682 615 588 -f 588 615 575 -f 575 615 589 -f 589 583 575 -f 575 583 581 -f 575 581 573 -f 573 581 580 -f 573 580 590 -f 590 580 579 -f 590 579 571 -f 571 579 578 -f 571 578 591 -f 591 578 592 -f 591 592 568 -f 568 592 593 -f 568 593 567 -f 567 593 594 -f 567 594 565 -f 565 594 554 -f 565 554 563 -f 589 614 583 -f 583 614 613 -f 583 613 595 -f 595 613 611 -f 519 576 555 -f 555 576 577 -f 555 577 556 -f 556 577 596 -f 556 596 558 -f 558 596 597 -f 558 597 598 -f 598 597 599 -f 598 599 601 -f 601 599 582 -f 601 582 603 -f 603 582 584 -f 603 584 604 -f 604 584 595 -f 604 595 606 -f 606 595 611 -f 1776 558 1777 -f 1777 558 598 -f 1777 598 600 -f 600 598 601 -f 600 601 602 -f 602 601 603 -f 602 603 1771 -f 1771 603 604 -f 1771 604 605 -f 605 604 606 -f 605 606 607 -f 607 606 611 -f 607 611 1772 -f 1764 1765 1681 -f 610 1765 1766 -f 609 610 608 -f 608 610 1766 -f 609 612 610 -f 610 589 1765 -f 612 1769 611 -f 611 1769 1772 -f 611 613 612 -f 612 613 614 -f 612 614 610 -f 610 614 589 -f 1765 589 615 -f 1681 1765 1682 -f 1682 1765 615 -f 164 621 162 -f 162 621 616 -f 160 617 618 -f 618 617 616 -f 618 616 1639 -f 1639 616 621 -f 1639 621 1414 -f 1414 621 619 -f 620 622 1471 -f 621 164 619 -f 619 164 620 -f 620 164 622 -f 622 164 628 -f 1471 622 623 -f 623 622 1411 -f 1687 1411 622 -f 1679 625 626 -f 163 165 626 -f 626 165 627 -f 626 627 1679 -f 1679 627 1683 -f 1687 622 625 -f 625 622 626 -f 626 622 628 -f 626 628 163 -f 630 631 1736 -f 1736 631 632 -f 1736 632 1738 -f 1096 634 1798 -f 1798 634 632 -f 1798 632 1800 -f 1800 632 631 -f 1800 631 1799 -f 1799 631 630 -f 1738 632 1739 -f 1739 632 634 -f 1739 634 1740 -f 1096 1137 1097 -f 1096 1097 634 -f 634 1097 1740 -f 1803 633 1096 -f 1658 1659 635 -f 635 1659 636 -f 635 636 1804 -f 633 1803 1802 -f 1804 636 1802 -f 1802 636 1095 -f 1802 1095 633 -f 779 735 777 -f 641 718 638 -f 638 718 779 -f 638 639 641 -f 641 639 782 -f 641 782 643 -f 643 782 637 -f 643 640 641 -f 717 640 642 -f 642 640 643 -f 642 643 785 -f 785 643 637 -f 644 664 784 -f 642 785 784 -f 642 784 645 -f 645 784 664 -f 717 642 645 -f 717 645 646 -f 646 645 664 -f 646 664 151 -f 662 665 655 -f 139 652 647 -f 647 652 675 -f 647 675 648 -f 673 653 790 -f 790 653 651 -f 790 651 791 -f 140 656 139 -f 139 656 652 -f 791 651 788 -f 788 651 650 -f 788 650 649 -f 663 654 650 -f 663 650 659 -f 659 650 651 -f 659 651 656 -f 656 651 652 -f 652 651 653 -f 652 653 675 -f 649 650 654 -f 649 654 655 -f 140 144 656 -f 656 144 657 -f 656 657 146 -f 656 146 659 -f 659 146 658 -f 659 658 142 -f 659 142 663 -f 663 142 660 -f 663 660 661 -f 663 661 147 -f 655 654 662 -f 662 654 663 -f 662 663 664 -f 664 663 147 -f 664 147 151 -f 644 665 664 -f 664 665 662 -f 666 648 675 -f 133 676 134 -f 134 676 669 -f 134 669 667 -f 669 676 674 -f 1662 1661 674 -f 674 1661 670 -f 674 670 669 -f 669 670 671 -f 669 671 672 -f 673 1662 653 -f 653 1662 674 -f 653 674 675 -f 675 674 676 -f 675 676 666 -f 666 676 133 -f 677 1343 1349 -f 678 679 677 -f 681 1217 678 -f 678 1217 679 -f 678 680 681 -f 681 680 1345 -f 681 1345 685 -f 685 1216 681 -f 681 1216 682 -f 681 682 1217 -f 685 1345 1346 -f 685 1346 687 -f 683 1213 1214 -f 683 1214 687 -f 687 1214 685 -f 685 1214 684 -f 685 684 1216 -f 706 703 686 -f 686 703 683 -f 686 683 1342 -f 1342 683 687 -f 1342 687 1346 -f 700 1213 703 -f 703 1213 683 -f 707 1644 691 -f 689 688 1815 -f 1815 688 690 -f 707 691 1223 -f 707 1223 701 -f 701 1223 1222 -f 1222 692 701 -f 701 692 702 -f 702 692 1224 -f 702 1224 699 -f 1815 690 693 -f 693 690 1812 -f 1812 690 704 -f 1812 704 694 -f 694 704 695 -f 695 704 696 -f 696 704 697 -f 700 705 698 -f 698 705 699 -f 705 700 703 -f 688 707 701 -f 688 701 690 -f 690 701 702 -f 690 702 704 -f 704 702 699 -f 704 699 705 -f 697 704 1811 -f 1811 704 705 -f 1811 705 703 -f 1811 703 1809 -f 1809 703 706 -f 1643 1644 707 -f 711 709 710 -f 710 712 715 -f 710 715 711 -f 711 715 716 -f 1643 707 1642 -f 688 715 707 -f 707 715 712 -f 707 712 1642 -f 1642 712 710 -f 1642 710 713 -f 713 710 714 -f 714 710 1640 -f 688 689 715 -f 715 689 1816 -f 715 1816 716 -f 641 640 732 -f 646 151 150 -f 733 640 717 -f 641 732 718 -f 735 779 721 -f 721 779 718 -f 736 777 735 -f 646 150 717 -f 717 150 149 -f 717 149 733 -f 149 719 733 -f 733 719 720 -f 733 720 723 -f 723 720 153 -f 718 732 721 -f 721 732 731 -f 721 731 722 -f 722 731 730 -f 722 730 767 -f 153 152 723 -f 723 152 724 -f 723 724 726 -f 726 724 725 -f 726 725 729 -f 729 725 155 -f 729 155 734 -f 734 155 727 -f 734 727 728 -f 734 730 729 -f 729 730 726 -f 726 730 731 -f 726 731 723 -f 723 731 732 -f 723 732 733 -f 733 732 640 -f 734 768 730 -f 730 768 767 -f 735 721 722 -f 735 722 767 -f 735 767 737 -f 736 735 737 -f 737 767 766 -f 770 769 738 -f 761 739 762 -f 915 741 916 -f 916 741 740 -f 916 740 919 -f 919 746 920 -f 740 741 743 -f 740 743 742 -f 742 743 1515 -f 742 1515 744 -f 744 1515 745 -f 744 745 748 -f 919 740 746 -f 746 740 742 -f 746 742 744 -f 746 744 747 -f 747 744 748 -f 747 748 753 -f 752 749 753 -f 753 749 750 -f 753 750 747 -f 747 750 1822 -f 747 1822 746 -f 746 1822 1821 -f 746 1821 751 -f 746 751 920 -f 755 752 756 -f 756 752 753 -f 756 753 757 -f 757 753 748 -f 757 748 754 -f 754 748 745 -f 760 755 761 -f 761 755 756 -f 761 756 739 -f 739 756 757 -f 739 757 758 -f 758 757 754 -f 739 758 759 -f 739 759 762 -f 762 759 1516 -f 760 761 765 -f 765 761 762 -f 765 762 763 -f 763 762 1516 -f 763 1516 764 -f 766 771 770 -f 736 737 764 -f 764 737 766 -f 764 766 763 -f 763 766 770 -f 763 770 765 -f 765 770 738 -f 765 738 760 -f 766 767 768 -f 766 768 771 -f 771 768 734 -f 769 770 1818 -f 1818 770 771 -f 1818 771 1820 -f 1820 771 734 -f 1820 734 728 -f 900 789 792 -f 1519 863 876 -f 1667 772 873 -f 864 773 865 -f 1521 841 840 -f 827 829 825 -f 774 1528 800 -f 775 1529 801 -f 776 779 777 -f 776 777 778 -f 778 777 736 -f 780 638 776 -f 776 638 779 -f 638 780 639 -f 639 780 781 -f 639 781 782 -f 782 781 783 -f 782 783 637 -f 786 784 785 -f 786 785 783 -f 783 785 637 -f 787 665 786 -f 786 665 644 -f 786 644 784 -f 649 655 901 -f 901 655 787 -f 787 655 665 -f 792 788 649 -f 792 649 901 -f 789 673 790 -f 789 790 791 -f 789 791 792 -f 792 791 788 -f 953 1678 931 -f 931 1678 809 -f 931 809 932 -f 932 809 808 -f 932 808 934 -f 934 808 793 -f 934 793 794 -f 806 794 793 -f 805 796 806 -f 806 796 794 -f 797 798 805 -f 805 798 795 -f 805 795 796 -f 798 797 929 -f 929 797 803 -f 801 926 799 -f 801 799 803 -f 803 799 929 -f 926 801 1529 -f 926 1529 1530 -f 1528 775 800 -f 800 775 801 -f 800 801 811 -f 811 801 803 -f 811 803 802 -f 802 803 797 -f 802 797 804 -f 804 797 805 -f 804 805 814 -f 814 805 806 -f 814 806 815 -f 815 806 793 -f 815 793 807 -f 807 793 808 -f 807 808 817 -f 817 808 809 -f 817 809 818 -f 818 809 1678 -f 1525 774 810 -f 810 774 800 -f 810 800 812 -f 812 800 811 -f 812 811 813 -f 813 811 802 -f 813 802 820 -f 820 802 804 -f 820 804 822 -f 822 804 814 -f 822 814 823 -f 823 814 815 -f 823 815 826 -f 826 815 807 -f 826 807 816 -f 816 807 817 -f 816 817 828 -f 828 817 818 -f 842 1525 819 -f 819 1525 810 -f 819 810 839 -f 839 810 812 -f 839 812 837 -f 837 812 813 -f 837 813 834 -f 834 813 820 -f 834 820 821 -f 821 820 822 -f 821 822 832 -f 832 822 823 -f 832 823 824 -f 824 823 826 -f 824 826 825 -f 825 826 816 -f 825 816 827 -f 827 816 828 -f 829 830 825 -f 825 830 831 -f 825 831 824 -f 824 831 847 -f 824 847 832 -f 832 847 833 -f 832 833 821 -f 821 833 845 -f 821 845 834 -f 834 845 835 -f 834 835 837 -f 837 835 836 -f 837 836 839 -f 839 836 838 -f 839 838 819 -f 819 838 840 -f 840 841 819 -f 819 841 1526 -f 819 1526 842 -f 848 1521 840 -f 848 840 843 -f 843 840 838 -f 843 838 844 -f 844 838 836 -f 844 836 849 -f 849 836 835 -f 849 835 852 -f 852 835 845 -f 852 845 853 -f 853 845 833 -f 853 833 846 -f 846 833 847 -f 846 847 855 -f 855 847 831 -f 855 831 1673 -f 1673 831 830 -f 1523 1521 857 -f 857 1521 848 -f 857 848 858 -f 858 848 843 -f 858 843 859 -f 859 843 844 -f 859 844 861 -f 861 844 849 -f 861 849 850 -f 850 849 852 -f 850 852 851 -f 851 852 853 -f 851 853 854 -f 854 853 846 -f 854 846 889 -f 889 846 855 -f 889 855 856 -f 856 855 1673 -f 773 1523 865 -f 865 1523 857 -f 865 857 867 -f 867 857 858 -f 867 858 868 -f 868 858 859 -f 868 859 860 -f 860 859 861 -f 860 861 862 -f 862 861 850 -f 862 850 870 -f 870 850 851 -f 870 851 871 -f 871 851 854 -f 871 854 872 -f 872 854 889 -f 863 864 876 -f 876 864 865 -f 876 865 878 -f 878 865 867 -f 878 867 866 -f 866 867 868 -f 866 868 869 -f 869 868 860 -f 869 860 883 -f 883 860 862 -f 883 862 884 -f 884 862 870 -f 884 870 885 -f 885 870 871 -f 885 871 887 -f 887 871 872 -f 1667 873 874 -f 875 1519 876 -f 875 876 877 -f 877 876 878 -f 877 878 879 -f 879 878 866 -f 879 866 880 -f 880 866 869 -f 880 869 881 -f 881 869 883 -f 881 883 882 -f 882 883 884 -f 882 884 886 -f 886 884 885 -f 886 885 873 -f 873 885 887 -f 873 887 874 -f 874 887 872 -f 874 872 888 -f 888 872 889 -f 888 889 1671 -f 1671 889 856 -f 772 890 873 -f 873 890 891 -f 873 891 886 -f 886 891 906 -f 886 906 882 -f 882 906 892 -f 882 892 881 -f 881 892 893 -f 881 893 880 -f 880 893 894 -f 880 894 879 -f 879 894 895 -f 879 895 877 -f 877 895 909 -f 877 909 875 -f 875 909 896 -f 875 896 1519 -f 1518 897 896 -f 896 897 898 -f 896 898 1519 -f 905 900 899 -f 899 900 792 -f 899 792 907 -f 907 792 901 -f 907 901 902 -f 902 901 787 -f 902 787 903 -f 903 787 786 -f 903 786 904 -f 904 786 783 -f 904 783 908 -f 908 783 781 -f 908 781 910 -f 910 781 780 -f 910 780 911 -f 911 780 776 -f 890 905 891 -f 891 905 899 -f 891 899 906 -f 906 899 907 -f 906 907 892 -f 892 907 902 -f 892 902 893 -f 893 902 903 -f 893 903 894 -f 894 903 904 -f 894 904 895 -f 895 904 908 -f 895 908 909 -f 909 908 910 -f 909 910 896 -f 896 910 911 -f 896 911 1518 -f 1518 911 776 -f 1518 776 912 -f 912 776 778 -f 917 913 1508 -f 917 1508 914 -f 917 914 918 -f 918 1599 1600 -f 1600 915 916 -f 1600 916 918 -f 918 916 919 -f 913 917 1824 -f 1824 917 918 -f 1824 918 1826 -f 1826 918 919 -f 1826 919 920 -f 983 964 948 -f 923 965 951 -f 951 965 921 -f 949 924 922 -f 922 924 1033 -f 922 1033 950 -f 950 1033 923 -f 923 1033 965 -f 948 964 949 -f 949 964 924 -f 983 925 928 -f 983 928 927 -f 926 927 799 -f 799 927 928 -f 799 928 929 -f 929 928 925 -f 798 930 795 -f 795 930 941 -f 795 941 796 -f 796 941 944 -f 796 944 794 -f 933 932 934 -f 933 934 937 -f 937 934 794 -f 953 931 954 -f 954 931 932 -f 954 932 956 -f 956 932 933 -f 956 933 958 -f 960 935 938 -f 938 935 936 -f 794 944 946 -f 794 946 937 -f 937 946 938 -f 937 938 933 -f 933 938 936 -f 933 936 958 -f 929 925 798 -f 798 925 939 -f 798 939 940 -f 798 940 930 -f 930 940 942 -f 930 942 941 -f 941 942 943 -f 941 943 944 -f 944 943 945 -f 944 945 946 -f 946 945 952 -f 946 952 938 -f 938 952 947 -f 938 947 960 -f 965 1730 921 -f 921 1730 963 -f 921 963 962 -f 983 948 925 -f 925 948 949 -f 925 949 939 -f 939 949 922 -f 939 922 940 -f 940 922 950 -f 940 950 942 -f 942 950 923 -f 942 923 943 -f 943 923 951 -f 943 951 945 -f 945 951 921 -f 945 921 952 -f 952 921 962 -f 952 962 947 -f 1105 953 1041 -f 1041 953 954 -f 1041 954 1042 -f 1042 954 956 -f 1042 956 955 -f 955 956 958 -f 955 958 957 -f 957 958 936 -f 957 936 1049 -f 1049 936 935 -f 1049 935 959 -f 959 935 960 -f 959 960 1050 -f 1050 960 947 -f 1050 947 961 -f 961 947 962 -f 961 962 1039 -f 1039 962 963 -f 1039 963 1731 -f 1731 963 1730 -f 1073 1721 1723 -f 1067 1069 1017 -f 983 927 968 -f 968 927 926 -f 968 926 1530 -f 924 964 999 -f 1732 1730 965 -f 1032 965 1033 -f 965 1032 1732 -f 1732 1032 1030 -f 1732 1030 966 -f 966 1030 970 -f 966 970 967 -f 968 1530 969 -f 968 969 984 -f 984 969 1527 -f 984 1527 985 -f 985 1527 1532 -f 985 1532 986 -f 967 970 1724 -f 1724 970 1028 -f 1724 1028 1725 -f 1725 1028 1026 -f 1725 1026 1726 -f 1726 1026 972 -f 1726 972 1728 -f 1728 972 971 -f 971 972 1025 -f 971 1025 973 -f 973 1025 1024 -f 973 1024 1712 -f 986 1532 1531 -f 986 1531 974 -f 974 1531 1576 -f 974 1576 989 -f 989 1576 1535 -f 989 1535 991 -f 991 1535 1534 -f 991 1534 993 -f 1712 1024 1714 -f 1714 1024 1023 -f 1714 1023 1715 -f 1715 1023 1020 -f 1715 1020 1709 -f 1709 1020 980 -f 1709 980 975 -f 993 1534 995 -f 995 1534 977 -f 995 977 976 -f 976 977 1533 -f 976 1533 978 -f 978 1533 1567 -f 978 1567 979 -f 979 1567 1539 -f 979 1539 982 -f 975 980 1719 -f 1719 980 1019 -f 1719 1019 1717 -f 1717 1019 1018 -f 1717 1018 1716 -f 1716 1018 1036 -f 1716 1036 1035 -f 982 1539 981 -f 982 981 997 -f 997 981 1538 -f 997 1538 998 -f 983 968 984 -f 983 984 1000 -f 1000 984 985 -f 1000 985 1002 -f 1002 985 986 -f 1002 986 987 -f 987 986 974 -f 987 974 988 -f 988 974 989 -f 988 989 990 -f 990 989 991 -f 990 991 992 -f 992 991 993 -f 992 993 1006 -f 1006 993 995 -f 1006 995 994 -f 994 995 976 -f 994 976 1008 -f 1008 976 978 -f 1008 978 1009 -f 1009 978 979 -f 1009 979 996 -f 996 979 982 -f 996 982 1012 -f 1012 982 997 -f 1012 997 1015 -f 1015 997 998 -f 1015 998 1016 -f 1538 1537 998 -f 998 1537 1065 -f 998 1065 1064 -f 998 1064 1066 -f 998 1066 1016 -f 1016 1066 1067 -f 964 983 999 -f 999 983 1000 -f 999 1000 1031 -f 1031 1000 1001 -f 1001 1000 1002 -f 1001 1002 1029 -f 1029 1002 987 -f 1029 987 1027 -f 1027 987 988 -f 1027 988 1003 -f 1003 988 990 -f 1003 990 1004 -f 1004 990 992 -f 1004 992 1005 -f 1005 992 1006 -f 1005 1006 1022 -f 1022 1006 994 -f 1022 994 1007 -f 1007 994 1008 -f 1007 1008 1021 -f 1021 1008 1009 -f 1021 1009 1010 -f 1010 1009 996 -f 1010 996 1011 -f 1011 996 1012 -f 1011 1012 1013 -f 1013 1012 1015 -f 1013 1015 1014 -f 1014 1015 1016 -f 1014 1016 1017 -f 1017 1016 1067 -f 1017 1069 1071 -f 1071 1034 1017 -f 1017 1034 1037 -f 1017 1037 1014 -f 1014 1037 1036 -f 1014 1036 1013 -f 1013 1036 1018 -f 1013 1018 1011 -f 1011 1018 1019 -f 1011 1019 1010 -f 1010 1019 980 -f 1010 980 1021 -f 1021 980 1020 -f 1021 1020 1007 -f 1007 1020 1023 -f 1007 1023 1022 -f 1022 1023 1024 -f 1022 1024 1005 -f 1005 1024 1025 -f 1005 1025 1004 -f 1004 1025 972 -f 1004 972 1003 -f 1003 972 1026 -f 1003 1026 1027 -f 1027 1026 1028 -f 1027 1028 1029 -f 1029 1028 970 -f 1029 970 1001 -f 1001 970 1030 -f 1001 1030 1031 -f 1031 1030 1032 -f 1031 1032 999 -f 999 1032 1033 -f 999 1033 924 -f 1034 1071 1073 -f 1035 1036 1722 -f 1722 1036 1037 -f 1722 1037 1038 -f 1038 1037 1034 -f 1038 1034 1723 -f 1723 1034 1073 -f 1106 1040 1098 -f 1106 1105 1041 -f 1043 1168 1761 -f 1045 1167 1043 -f 1043 1167 1168 -f 1046 1166 1045 -f 1045 1166 1167 -f 1165 1047 1163 -f 1163 1047 1051 -f 1163 1051 1185 -f 1185 1051 1039 -f 1185 1039 1731 -f 1098 1040 1044 -f 1106 1041 1040 -f 1040 1041 1042 -f 1040 1042 1044 -f 1761 1098 1043 -f 1043 1098 1044 -f 1043 1044 1045 -f 1045 1044 1048 -f 1045 1048 1046 -f 1046 1048 1047 -f 1046 1047 1165 -f 1042 955 1044 -f 1044 955 957 -f 1044 957 1048 -f 1048 957 1049 -f 1048 1049 1047 -f 1049 959 1047 -f 1047 959 1050 -f 1047 1050 1051 -f 1051 1050 961 -f 1051 961 1039 -f 1199 1074 1072 -f 1064 1062 1066 -f 1235 1075 1053 -f 1235 1208 1076 -f 1053 1075 1055 -f 1055 1075 1054 -f 1055 1054 1056 -f 1057 1059 1077 -f 1057 1058 1059 -f 1059 1058 1084 -f 1059 1084 1230 -f 1230 1084 1082 -f 1060 1080 1231 -f 1060 1231 1082 -f 1082 1231 1230 -f 1063 1080 1061 -f 1061 1080 1081 -f 1063 1061 1062 -f 1063 1062 1229 -f 1229 1062 1227 -f 1227 1062 1064 -f 1227 1064 1065 -f 1227 1065 1537 -f 1066 1062 1061 -f 1066 1061 1067 -f 1067 1052 1069 -f 1069 1052 1068 -f 1069 1068 1089 -f 1069 1089 1071 -f 1071 1089 1090 -f 1071 1090 1070 -f 1071 1070 1092 -f 1071 1092 1073 -f 1073 1092 1072 -f 1073 1072 1074 -f 1073 1074 1721 -f 1235 1076 1075 -f 1075 1076 1206 -f 1075 1206 1054 -f 1077 1056 1057 -f 1057 1056 1054 -f 1057 1054 1058 -f 1058 1054 1087 -f 1206 1078 1054 -f 1054 1078 1079 -f 1054 1079 1087 -f 1087 1079 1203 -f 1087 1203 1201 -f 1081 1080 1060 -f 1081 1060 1088 -f 1088 1060 1082 -f 1088 1082 1091 -f 1091 1082 1084 -f 1091 1084 1083 -f 1083 1084 1058 -f 1083 1058 1085 -f 1085 1058 1087 -f 1085 1087 1086 -f 1086 1087 1201 -f 1086 1201 1093 -f 1067 1061 1052 -f 1052 1061 1081 -f 1052 1081 1068 -f 1068 1081 1088 -f 1068 1088 1089 -f 1089 1088 1091 -f 1089 1091 1090 -f 1090 1091 1083 -f 1090 1083 1070 -f 1070 1083 1085 -f 1070 1085 1092 -f 1092 1085 1086 -f 1092 1086 1072 -f 1072 1086 1093 -f 1072 1093 1199 -f 1135 1137 1139 -f 1098 1761 1099 -f 1094 633 1660 -f 1660 633 1095 -f 1136 1096 633 -f 1740 1097 1135 -f 1097 1137 1135 -f 1098 1099 1100 -f 1100 1099 1101 -f 1100 1101 1108 -f 1102 1112 1103 -f 1103 1112 1104 -f 1103 1104 1149 -f 1149 1104 1105 -f 1149 1105 1106 -f 1101 1758 1108 -f 1108 1758 1107 -f 1108 1107 1148 -f 1148 1107 1113 -f 1148 1113 1109 -f 1117 1118 1110 -f 1110 1118 1674 -f 1110 1674 1111 -f 1111 1674 1676 -f 1111 1676 1102 -f 1102 1676 1677 -f 1102 1677 1112 -f 1113 1751 1109 -f 1109 1751 1114 -f 1109 1114 1115 -f 1115 1114 1752 -f 1115 1752 1147 -f 1147 1752 1116 -f 1147 1116 1122 -f 1672 1670 1117 -f 1117 1670 1675 -f 1117 1675 1118 -f 1117 1146 1672 -f 1672 1146 1145 -f 1672 1145 1669 -f 1669 1145 1119 -f 1669 1119 1120 -f 1116 1121 1122 -f 1122 1121 1748 -f 1122 1748 1123 -f 1123 1748 1125 -f 1123 1125 1124 -f 1124 1125 1749 -f 1124 1749 1127 -f 1749 1126 1127 -f 1127 1126 1747 -f 1127 1747 1143 -f 1143 1747 1746 -f 1143 1746 1131 -f 1120 1119 1666 -f 1666 1119 1144 -f 1666 1144 1128 -f 1128 1144 1129 -f 1128 1129 1130 -f 1130 1129 1142 -f 1130 1142 1668 -f 1746 1744 1131 -f 1131 1744 1132 -f 1131 1132 1140 -f 1140 1132 1133 -f 1140 1133 1139 -f 1139 1133 1134 -f 1139 1134 1135 -f 1096 1136 1137 -f 1137 1136 1138 -f 1137 1138 1139 -f 1139 1138 1141 -f 1139 1141 1140 -f 1140 1141 1142 -f 1140 1142 1131 -f 1131 1142 1129 -f 1131 1129 1143 -f 1143 1129 1144 -f 1143 1144 1127 -f 1127 1144 1119 -f 1127 1119 1124 -f 1124 1119 1145 -f 1124 1145 1123 -f 1123 1145 1146 -f 1123 1146 1122 -f 1122 1146 1117 -f 1122 1117 1147 -f 1147 1117 1110 -f 1147 1110 1115 -f 1115 1110 1111 -f 1115 1111 1109 -f 1109 1111 1102 -f 1109 1102 1148 -f 1148 1102 1103 -f 1148 1103 1108 -f 1108 1103 1149 -f 1108 1149 1100 -f 1100 1149 1106 -f 1100 1106 1098 -f 1668 1142 1663 -f 1663 1142 1141 -f 1663 1141 1664 -f 1664 1141 1138 -f 1664 1138 1665 -f 1665 1138 1136 -f 1665 1136 1094 -f 1094 1136 633 -f 1150 1151 1195 -f 1174 1189 1181 -f 1190 285 1760 -f 1760 285 1152 -f 1760 1152 287 -f 285 1190 256 -f 256 1190 1153 -f 256 1153 1156 -f 1157 1154 1155 -f 1157 1155 1153 -f 1153 1155 1156 -f 1154 1157 1158 -f 1158 1157 1193 -f 1158 1193 1159 -f 1159 1193 1160 -f 1160 1193 1195 -f 1160 1195 252 -f 1729 249 1151 -f 1151 249 1161 -f 1151 1161 1195 -f 1195 1161 252 -f 1162 1163 1184 -f 1184 1163 1185 -f 1166 1046 1164 -f 1164 1046 1162 -f 1162 1046 1165 -f 1162 1165 1163 -f 1166 1164 1167 -f 1167 1164 1171 -f 1167 1171 1168 -f 1168 1171 1170 -f 1168 1170 1169 -f 1168 1169 1761 -f 1762 1169 1177 -f 1177 1169 1170 -f 1177 1170 1179 -f 1179 1170 1171 -f 1179 1171 1172 -f 1172 1171 1164 -f 1172 1164 1173 -f 1173 1164 1162 -f 1173 1162 1180 -f 1180 1162 1184 -f 1174 1181 1182 -f 1175 1762 1176 -f 1176 1762 1177 -f 1176 1177 1187 -f 1187 1177 1179 -f 1187 1179 1178 -f 1178 1179 1172 -f 1178 1172 1188 -f 1188 1172 1173 -f 1188 1173 1181 -f 1181 1173 1180 -f 1181 1180 1182 -f 1182 1180 1184 -f 1182 1184 1183 -f 1183 1184 1185 -f 1183 1185 1731 -f 1756 1175 1191 -f 1191 1175 1176 -f 1191 1176 1192 -f 1192 1176 1187 -f 1192 1187 1186 -f 1186 1187 1178 -f 1186 1178 1194 -f 1194 1178 1188 -f 1194 1188 1196 -f 1196 1188 1181 -f 1196 1181 1727 -f 1727 1181 1189 -f 1760 1756 1190 -f 1190 1756 1191 -f 1190 1191 1153 -f 1153 1191 1192 -f 1153 1192 1157 -f 1157 1192 1186 -f 1157 1186 1193 -f 1193 1186 1194 -f 1193 1194 1195 -f 1195 1194 1196 -f 1195 1196 1150 -f 1150 1196 1727 -f 1339 1721 1197 -f 1197 1721 1074 -f 1197 1074 1198 -f 1198 1074 1199 -f 1198 1199 1200 -f 1200 1199 1093 -f 1200 1093 1340 -f 1340 1093 1201 -f 1340 1201 1202 -f 1202 1201 1203 -f 1202 1203 1204 -f 1204 1203 1079 -f 1204 1079 1205 -f 1205 1079 1078 -f 1205 1078 1334 -f 1334 1078 1206 -f 1334 1206 1333 -f 1333 1206 1076 -f 1333 1076 1207 -f 1207 1076 1208 -f 1641 1646 1322 -f 1318 1551 1328 -f 1294 1282 1283 -f 1292 1548 1209 -f 1648 1651 1259 -f 1544 1210 1281 -f 1655 1657 1211 -f 1560 1542 1212 -f 700 1225 1325 -f 700 1325 1213 -f 1213 1325 1214 -f 1214 1325 1215 -f 1327 1216 1215 -f 1215 1216 684 -f 1215 684 1214 -f 1218 682 1327 -f 1327 682 1216 -f 677 679 1219 -f 1219 679 1217 -f 1219 1217 1218 -f 1218 1217 682 -f 1554 1220 1219 -f 1219 1220 1343 -f 1219 1343 677 -f 1644 1221 691 -f 1320 692 1222 -f 1320 1222 1221 -f 1221 1222 1223 -f 1221 1223 691 -f 699 1224 1321 -f 1321 1224 1320 -f 1320 1224 692 -f 700 698 1225 -f 1225 698 1321 -f 1321 698 699 -f 1226 1227 1537 -f 1226 1537 1536 -f 1228 1229 1226 -f 1226 1229 1227 -f 1240 1080 1063 -f 1240 1063 1228 -f 1228 1063 1229 -f 1239 1231 1240 -f 1240 1231 1080 -f 1238 1230 1239 -f 1239 1230 1231 -f 1077 1059 1232 -f 1232 1059 1238 -f 1238 1059 1230 -f 1077 1232 1056 -f 1056 1232 1233 -f 1056 1233 1055 -f 1055 1233 1053 -f 1053 1233 1234 -f 1053 1234 1235 -f 1656 1208 1234 -f 1234 1208 1235 -f 1560 1212 1541 -f 1657 1656 1211 -f 1211 1656 1234 -f 1211 1234 1236 -f 1236 1234 1233 -f 1236 1233 1243 -f 1243 1233 1232 -f 1243 1232 1245 -f 1245 1232 1238 -f 1245 1238 1237 -f 1237 1238 1239 -f 1237 1239 1248 -f 1248 1239 1240 -f 1248 1240 1241 -f 1241 1240 1228 -f 1241 1228 1212 -f 1212 1228 1226 -f 1212 1226 1541 -f 1541 1226 1536 -f 1653 1655 1242 -f 1242 1655 1211 -f 1242 1211 1250 -f 1250 1211 1236 -f 1250 1236 1244 -f 1244 1236 1243 -f 1244 1243 1252 -f 1252 1243 1245 -f 1252 1245 1246 -f 1246 1245 1237 -f 1246 1237 1247 -f 1247 1237 1248 -f 1247 1248 1256 -f 1256 1248 1241 -f 1256 1241 1257 -f 1257 1241 1212 -f 1257 1212 1542 -f 1545 1262 1258 -f 1649 1653 1260 -f 1260 1653 1242 -f 1260 1242 1249 -f 1249 1242 1250 -f 1249 1250 1251 -f 1251 1250 1244 -f 1251 1244 1261 -f 1261 1244 1252 -f 1261 1252 1253 -f 1253 1252 1246 -f 1253 1246 1254 -f 1254 1246 1247 -f 1254 1247 1255 -f 1255 1247 1256 -f 1255 1256 1262 -f 1262 1256 1257 -f 1262 1257 1258 -f 1258 1257 1542 -f 1651 1649 1259 -f 1259 1649 1260 -f 1259 1260 1266 -f 1266 1260 1249 -f 1266 1249 1267 -f 1267 1249 1251 -f 1267 1251 1268 -f 1268 1251 1261 -f 1268 1261 1269 -f 1269 1261 1253 -f 1269 1253 1270 -f 1270 1253 1254 -f 1270 1254 1271 -f 1271 1254 1255 -f 1271 1255 1263 -f 1263 1255 1262 -f 1263 1262 1544 -f 1544 1262 1545 -f 1647 1648 1264 -f 1264 1648 1259 -f 1264 1259 1265 -f 1265 1259 1266 -f 1265 1266 1274 -f 1274 1266 1267 -f 1274 1267 1275 -f 1275 1267 1268 -f 1275 1268 1277 -f 1277 1268 1269 -f 1277 1269 1278 -f 1278 1269 1270 -f 1278 1270 1280 -f 1280 1270 1271 -f 1280 1271 1281 -f 1281 1271 1263 -f 1281 1263 1544 -f 1272 1647 1284 -f 1284 1647 1264 -f 1284 1264 1285 -f 1285 1264 1265 -f 1285 1265 1273 -f 1273 1265 1274 -f 1273 1274 1276 -f 1276 1274 1275 -f 1276 1275 1289 -f 1289 1275 1277 -f 1289 1277 1290 -f 1290 1277 1278 -f 1290 1278 1279 -f 1279 1278 1280 -f 1279 1280 1291 -f 1291 1280 1281 -f 1291 1281 1546 -f 1546 1281 1210 -f 1282 1272 1283 -f 1283 1272 1284 -f 1283 1284 1295 -f 1295 1284 1285 -f 1295 1285 1296 -f 1296 1285 1273 -f 1296 1273 1286 -f 1286 1273 1276 -f 1286 1276 1287 -f 1287 1276 1289 -f 1287 1289 1288 -f 1288 1289 1290 -f 1288 1290 1297 -f 1297 1290 1279 -f 1297 1279 1209 -f 1209 1279 1291 -f 1209 1291 1292 -f 1292 1291 1546 -f 1293 1294 1299 -f 1299 1294 1283 -f 1299 1283 1301 -f 1301 1283 1295 -f 1301 1295 1303 -f 1303 1295 1296 -f 1303 1296 1304 -f 1304 1296 1286 -f 1304 1286 1305 -f 1305 1286 1287 -f 1305 1287 1306 -f 1306 1287 1288 -f 1306 1288 1307 -f 1307 1288 1297 -f 1307 1297 1298 -f 1298 1297 1209 -f 1298 1209 1550 -f 1550 1209 1548 -f 1309 1293 1300 -f 1300 1293 1299 -f 1300 1299 1310 -f 1310 1299 1301 -f 1310 1301 1302 -f 1302 1301 1303 -f 1302 1303 1312 -f 1312 1303 1304 -f 1312 1304 1313 -f 1313 1304 1305 -f 1313 1305 1316 -f 1316 1305 1306 -f 1316 1306 1317 -f 1317 1306 1307 -f 1317 1307 1319 -f 1319 1307 1298 -f 1319 1298 1308 -f 1308 1298 1550 -f 1646 1309 1322 -f 1322 1309 1300 -f 1322 1300 1323 -f 1323 1300 1310 -f 1323 1310 1324 -f 1324 1310 1302 -f 1324 1302 1326 -f 1326 1302 1312 -f 1326 1312 1311 -f 1311 1312 1313 -f 1311 1313 1314 -f 1314 1313 1316 -f 1314 1316 1315 -f 1315 1316 1317 -f 1315 1317 1328 -f 1328 1317 1319 -f 1328 1319 1318 -f 1318 1319 1308 -f 1221 1641 1320 -f 1320 1641 1322 -f 1320 1322 1321 -f 1321 1322 1323 -f 1321 1323 1225 -f 1225 1323 1324 -f 1225 1324 1325 -f 1325 1324 1326 -f 1325 1326 1215 -f 1215 1326 1311 -f 1215 1311 1327 -f 1327 1311 1314 -f 1327 1314 1218 -f 1218 1314 1315 -f 1218 1315 1219 -f 1219 1315 1328 -f 1219 1328 1554 -f 1554 1328 1551 -f 1337 1338 1331 -f 1329 1331 1338 -f 1329 1338 1332 -f 1329 1332 1468 -f 1330 1380 1339 -f 1336 1379 1330 -f 1330 1379 1380 -f 1335 1378 1383 -f 1329 1424 1331 -f 1331 1424 1385 -f 1207 1468 1333 -f 1333 1468 1332 -f 1333 1332 1334 -f 1334 1332 1338 -f 1334 1338 1205 -f 1385 1378 1331 -f 1331 1378 1335 -f 1331 1335 1337 -f 1337 1335 1383 -f 1337 1383 1336 -f 1336 1383 1379 -f 1336 1340 1337 -f 1337 1340 1202 -f 1337 1202 1338 -f 1338 1202 1204 -f 1338 1204 1205 -f 1339 1197 1330 -f 1330 1197 1198 -f 1330 1198 1336 -f 1336 1198 1200 -f 1336 1200 1340 -f 1341 1347 1342 -f 1349 1343 1220 -f 1349 1344 677 -f 677 1344 678 -f 1350 680 1344 -f 1344 680 678 -f 1351 1346 1345 -f 1351 1345 1350 -f 1350 1345 680 -f 686 1342 1347 -f 686 1347 706 -f 1346 1351 1342 -f 1342 1351 1348 -f 1342 1348 1341 -f 1344 1349 1357 -f 1344 1357 1350 -f 1350 1357 1358 -f 1350 1358 1351 -f 1351 1358 1353 -f 1351 1353 1348 -f 1359 1352 1353 -f 1353 1352 1348 -f 1357 1349 1363 -f 1357 1363 1358 -f 1358 1363 1355 -f 1358 1355 1353 -f 1353 1355 1354 -f 1355 1363 1356 -f 1355 1356 1354 -f 1354 1356 1365 -f 1359 1353 1354 -f 1359 1354 1360 -f 1360 1354 1365 -f 1805 1807 1365 -f 1365 1807 1360 -f 1220 1474 1349 -f 1349 1474 1361 -f 1349 1361 1362 -f 1363 1349 1362 -f 1363 1362 1356 -f 1356 1362 1364 -f 1356 1364 1365 -f 1365 1364 1478 -f 1365 1478 1805 -f 1805 1478 1476 -f 1367 422 1370 -f 424 1368 1405 -f 1370 422 1405 -f 1405 422 423 -f 1405 423 424 -f 1369 1366 1370 -f 1370 1366 394 -f 1370 394 1367 -f 1373 1371 1369 -f 1369 1371 391 -f 1369 391 1366 -f 388 1374 1372 -f 1372 1374 1373 -f 1373 1374 389 -f 1373 389 1371 -f 388 1372 1376 -f 1376 1372 1375 -f 1376 1375 1377 -f 1377 1375 1408 -f 1377 1408 517 -f 1380 1381 1339 -f 1393 1381 1390 -f 1390 1381 1380 -f 1390 1380 1382 -f 1382 1380 1379 -f 1382 1379 1389 -f 1389 1379 1383 -f 1389 1383 1388 -f 1388 1383 1378 -f 1388 1378 1384 -f 1384 1378 1385 -f 1384 1385 1707 -f 1707 1385 1424 -f 1707 1386 1384 -f 1384 1386 1399 -f 1384 1399 1388 -f 1388 1399 1387 -f 1388 1387 1389 -f 1389 1387 1401 -f 1389 1401 1382 -f 1382 1401 1402 -f 1382 1402 1390 -f 1390 1402 1403 -f 1390 1403 1393 -f 1718 1391 1403 -f 1403 1391 1392 -f 1403 1392 1393 -f 1705 1410 1394 -f 1394 1410 1409 -f 1394 1409 1400 -f 1400 1409 1396 -f 1400 1396 1395 -f 1395 1396 1407 -f 1395 1407 1397 -f 1397 1407 1406 -f 1397 1406 1398 -f 1398 1406 1404 -f 1386 1705 1399 -f 1399 1705 1394 -f 1399 1394 1387 -f 1387 1394 1400 -f 1387 1400 1401 -f 1401 1400 1395 -f 1401 1395 1402 -f 1402 1395 1397 -f 1402 1397 1403 -f 1403 1397 1398 -f 1403 1398 1718 -f 1718 1398 1404 -f 1718 1404 1720 -f 1720 1404 1708 -f 1405 1708 1370 -f 1370 1708 1404 -f 1370 1404 1369 -f 1369 1404 1406 -f 1369 1406 1373 -f 1373 1406 1407 -f 1373 1407 1372 -f 1372 1407 1396 -f 1372 1396 1375 -f 1375 1396 1409 -f 1375 1409 1408 -f 1408 1409 1410 -f 623 1411 1412 -f 1413 620 1471 -f 1417 619 620 -f 1415 1414 619 -f 1415 619 1416 -f 1468 1207 1418 -f 1425 1329 1468 -f 1468 1418 1419 -f 1419 1418 1420 -f 1419 1420 1467 -f 1467 1420 1421 -f 1467 1421 1423 -f 1423 1421 1422 -f 1423 1422 1429 -f 1424 1329 1703 -f 1703 1329 1425 -f 1703 1425 1426 -f 1426 1425 1466 -f 1426 1466 1706 -f 1706 1466 1465 -f 1706 1465 1427 -f 1427 1465 1464 -f 1427 1464 1428 -f 1422 1654 1429 -f 1429 1654 1652 -f 1429 1652 1463 -f 1463 1652 1650 -f 1463 1650 1461 -f 1461 1650 1432 -f 1428 1464 1702 -f 1702 1464 1462 -f 1702 1462 1696 -f 1696 1462 1460 -f 1696 1460 1430 -f 1430 1460 1700 -f 1431 1435 1432 -f 1432 1435 1461 -f 1700 1460 1433 -f 1433 1460 1434 -f 1433 1434 1699 -f 1699 1434 1459 -f 1699 1459 1693 -f 1431 1436 1435 -f 1435 1436 1438 -f 1435 1438 1437 -f 1437 1438 1440 -f 1439 1458 1440 -f 1440 1458 1441 -f 1440 1441 1437 -f 1693 1459 1695 -f 1695 1459 1442 -f 1695 1442 1692 -f 1692 1442 1457 -f 1692 1457 1690 -f 1690 1457 1450 -f 1690 1450 1448 -f 1439 1443 1458 -f 1458 1443 1445 -f 1458 1445 1444 -f 1444 1445 1447 -f 1645 1446 1447 -f 1447 1446 1456 -f 1447 1456 1444 -f 1448 1450 1449 -f 1449 1450 1455 -f 1449 1455 1685 -f 1685 1455 1454 -f 1685 1454 1469 -f 1645 1451 1446 -f 1446 1451 1452 -f 1446 1452 1453 -f 1453 1452 1416 -f 1453 1416 1417 -f 1417 1416 619 -f 620 1413 1417 -f 1417 1413 1470 -f 1417 1470 1453 -f 1453 1470 1454 -f 1453 1454 1446 -f 1446 1454 1455 -f 1446 1455 1456 -f 1456 1455 1450 -f 1456 1450 1444 -f 1444 1450 1457 -f 1444 1457 1458 -f 1458 1457 1442 -f 1458 1442 1441 -f 1441 1442 1459 -f 1441 1459 1437 -f 1437 1459 1434 -f 1437 1434 1435 -f 1435 1434 1460 -f 1435 1460 1461 -f 1461 1460 1462 -f 1461 1462 1463 -f 1463 1462 1464 -f 1463 1464 1429 -f 1429 1464 1465 -f 1429 1465 1423 -f 1423 1465 1466 -f 1423 1466 1467 -f 1467 1466 1425 -f 1467 1425 1419 -f 1419 1425 1468 -f 1469 1454 1689 -f 1689 1454 1470 -f 1689 1470 1688 -f 1688 1470 1413 -f 1688 1413 1412 -f 1412 1413 1471 -f 1412 1471 623 -f 1364 1362 1489 -f 1489 1362 1361 -f 1478 1364 1490 -f 1492 1473 1472 -f 1472 1473 1552 -f 1552 1473 1489 -f 1552 1489 1553 -f 1553 1489 1361 -f 1553 1361 1474 -f 1472 1555 1492 -f 1492 1555 1475 -f 1492 1475 1493 -f 1493 1475 1499 -f 1476 1478 1477 -f 1477 1478 1490 -f 1477 1490 1479 -f 1479 1490 1491 -f 1479 1491 1480 -f 1480 1491 1481 -f 1481 1491 1482 -f 1481 1482 1832 -f 1832 1482 1494 -f 1832 1494 1833 -f 1833 1494 1483 -f 1483 1494 1484 -f 1483 1484 1485 -f 1485 1484 1487 -f 1485 1487 1486 -f 1486 1487 1498 -f 1486 1498 1488 -f 1364 1489 1490 -f 1490 1489 1473 -f 1490 1473 1491 -f 1491 1473 1492 -f 1491 1492 1482 -f 1482 1492 1493 -f 1482 1493 1494 -f 1494 1493 1495 -f 1494 1495 1484 -f 1484 1495 1496 -f 1484 1496 1487 -f 1487 1496 1503 -f 1487 1503 1498 -f 1498 1503 1497 -f 1498 1497 1505 -f 1488 1498 1504 -f 1504 1498 1505 -f 1493 1499 1500 -f 1493 1500 1495 -f 1495 1500 1501 -f 1495 1501 1496 -f 1496 1501 1502 -f 1496 1502 1503 -f 1503 1502 1557 -f 1503 1557 1497 -f 1509 1504 1510 -f 1510 1504 1505 -f 1510 1505 1513 -f 1513 1505 1497 -f 1513 1497 1557 -f 1513 1557 1556 -f 1508 1507 1506 -f 1506 1507 1595 -f 1598 1595 1511 -f 1511 1595 1507 -f 1511 1507 1512 -f 1512 1507 1508 -f 1509 1510 1828 -f 1828 1510 1511 -f 1828 1511 1830 -f 1830 1511 1512 -f 1556 1598 1513 -f 1513 1598 1511 -f 1513 1511 1510 -f 915 1601 1575 -f 758 754 1586 -f 1586 754 745 -f 1586 745 1515 -f 1515 743 1586 -f 1586 743 741 -f 778 736 1594 -f 1594 736 764 -f 764 1516 1594 -f 1594 1516 759 -f 1594 759 1517 -f 1517 759 758 -f 1520 1518 1594 -f 1594 1518 912 -f 1594 912 778 -f 1592 1519 898 -f 1592 898 1520 -f 1520 898 897 -f 1520 897 1518 -f 1519 1592 863 -f 863 1592 1522 -f 863 1522 864 -f 1524 1521 1523 -f 1524 1523 1522 -f 1522 1523 773 -f 1522 773 864 -f 1590 1526 1524 -f 1524 1526 841 -f 1524 841 1521 -f 774 1525 1587 -f 1587 1525 1590 -f 1590 1525 842 -f 1590 842 1526 -f 1527 969 1577 -f 1577 969 1530 -f 1528 1579 775 -f 775 1579 1577 -f 775 1577 1529 -f 1529 1577 1530 -f 1531 1532 1577 -f 1577 1532 1527 -f 1535 1576 1568 -f 1567 1533 1568 -f 1568 1533 977 -f 1568 977 1534 -f 1568 1534 1535 -f 1536 1537 1540 -f 1540 1537 1538 -f 1538 981 1540 -f 1540 981 1539 -f 1536 1540 1541 -f 1541 1540 1569 -f 1541 1569 1560 -f 1542 1559 1258 -f 1258 1559 1561 -f 1258 1561 1545 -f 1210 1544 1543 -f 1543 1544 1561 -f 1561 1544 1545 -f 1210 1543 1546 -f 1546 1543 1547 -f 1546 1547 1292 -f 1292 1547 1548 -f 1548 1547 1549 -f 1548 1549 1550 -f 1565 1308 1549 -f 1549 1308 1550 -f 1566 1554 1551 -f 1566 1551 1565 -f 1565 1551 1318 -f 1565 1318 1308 -f 1552 1553 1566 -f 1566 1553 1474 -f 1474 1220 1566 -f 1220 1554 1566 -f 1499 1475 1514 -f 1514 1475 1555 -f 1514 1555 1566 -f 1566 1555 1472 -f 1566 1472 1552 -f 1556 1557 1558 -f 1557 1502 1558 -f 1558 1502 1501 -f 1558 1501 1500 -f 1542 1560 1559 -f 1559 1560 1569 -f 1559 1569 1561 -f 1561 1569 1562 -f 1561 1562 1543 -f 1543 1562 1563 -f 1543 1563 1547 -f 1547 1563 1572 -f 1547 1572 1549 -f 1549 1572 1564 -f 1549 1564 1565 -f 1565 1564 1573 -f 1565 1573 1566 -f 1566 1573 1574 -f 1566 1574 1514 -f 1514 1574 1558 -f 1514 1558 1499 -f 1499 1558 1500 -f 1539 1567 1540 -f 1540 1567 1568 -f 1540 1568 1569 -f 1569 1568 1578 -f 1569 1578 1562 -f 1562 1578 1570 -f 1562 1570 1563 -f 1563 1570 1580 -f 1563 1580 1572 -f 1572 1580 1571 -f 1572 1571 1564 -f 1564 1571 1582 -f 1564 1582 1573 -f 1573 1582 1583 -f 1573 1583 1574 -f 1574 1583 1585 -f 1574 1585 1558 -f 1558 1585 1575 -f 1558 1575 1556 -f 1556 1575 1601 -f 1576 1531 1568 -f 1568 1531 1577 -f 1568 1577 1578 -f 1578 1577 1579 -f 1578 1579 1570 -f 1570 1579 1588 -f 1570 1588 1580 -f 1580 1588 1589 -f 1580 1589 1571 -f 1571 1589 1581 -f 1571 1581 1582 -f 1582 1581 1591 -f 1582 1591 1583 -f 1583 1591 1584 -f 1583 1584 1585 -f 1585 1584 1593 -f 1585 1593 1575 -f 1575 1593 1586 -f 1575 1586 915 -f 915 1586 741 -f 1528 774 1579 -f 1579 774 1587 -f 1579 1587 1588 -f 1588 1587 1590 -f 1588 1590 1589 -f 1589 1590 1524 -f 1589 1524 1581 -f 1581 1524 1522 -f 1581 1522 1591 -f 1591 1522 1592 -f 1591 1592 1584 -f 1584 1592 1520 -f 1584 1520 1593 -f 1593 1520 1594 -f 1593 1594 1586 -f 1586 1594 1517 -f 1586 1517 758 -f 1601 1597 1556 -f 1556 1597 1598 -f 1508 1506 1596 -f 1596 1506 1595 -f 1596 1595 1597 -f 1597 1595 1598 -f 918 914 1596 -f 1596 914 1508 -f 918 1596 1599 -f 1599 1596 1597 -f 1599 1597 1600 -f 1600 1597 1601 -f 1600 1601 915 -f 1607 1602 1606 -f 1634 1635 1603 -f 1603 1635 1604 -f 1603 1604 267 -f 267 1604 1605 -f 1605 1604 435 -f 1605 435 1606 -f 1606 435 497 -f 1606 497 1607 -f 1602 1607 1608 -f 1608 1607 1609 -f 1608 1609 494 -f 504 1610 494 -f 494 1610 193 -f 494 193 1608 -f 1612 1611 1610 -f 1612 1610 1613 -f 1613 1610 504 -f 1611 1612 192 -f 192 1612 1614 -f 192 1614 1615 -f 474 189 483 -f 483 189 1615 -f 483 1615 482 -f 482 1615 1614 -f 367 293 526 -f 526 293 174 -f 523 526 439 -f 439 526 174 -f 439 174 458 -f 458 174 179 -f 458 179 1616 -f 1616 179 1617 -f 1616 1617 465 -f 465 1617 1618 -f 465 1618 1619 -f 1619 1618 184 -f 1619 184 1620 -f 1620 184 182 -f 1620 182 474 -f 474 182 181 -f 474 181 189 -f 367 526 1621 -f 1621 526 1622 -f 1621 1622 1624 -f 1622 1623 1624 -f 1624 1623 534 -f 1624 534 1625 -f 1625 534 1627 -f 1625 1627 1626 -f 1626 1627 532 -f 1626 532 371 -f 371 532 540 -f 371 540 1628 -f 1628 540 539 -f 1628 539 1629 -f 1629 539 538 -f 1629 538 374 -f 374 538 546 -f 374 546 375 -f 375 546 1630 -f 1630 546 1631 -f 1630 1631 1632 -f 1631 549 1632 -f 1632 549 544 -f 1632 544 383 -f 383 544 545 -f 383 545 366 -f 392 260 1637 -f 392 1637 1633 -f 1634 261 1635 -f 1635 261 1636 -f 260 392 261 -f 261 392 1636 -f 258 301 1637 -f 1637 301 1638 -f 1637 1638 1633 -f 1642 713 1415 -f 1415 713 714 -f 1415 714 1640 -f 1640 708 160 -f 1414 1415 1639 -f 1639 1415 1640 -f 1639 1640 618 -f 618 1640 160 -f 1221 1415 1416 -f 1416 1452 1221 -f 1221 1452 1451 -f 1221 1451 1641 -f 1641 1451 1645 -f 1641 1645 1646 -f 1642 1415 1643 -f 1643 1415 1221 -f 1643 1221 1644 -f 1447 1293 1645 -f 1645 1293 1309 -f 1645 1309 1646 -f 1447 1445 1293 -f 1293 1445 1443 -f 1293 1443 1294 -f 1294 1443 1439 -f 1294 1439 1282 -f 1440 1438 1647 -f 1647 1438 1436 -f 1647 1436 1648 -f 1440 1647 1439 -f 1439 1647 1272 -f 1439 1272 1282 -f 1436 1431 1648 -f 1648 1431 1432 -f 1648 1432 1650 -f 1653 1649 1650 -f 1650 1649 1651 -f 1650 1651 1648 -f 1650 1652 1653 -f 1653 1652 1654 -f 1653 1654 1655 -f 1655 1654 1422 -f 1655 1422 1421 -f 1421 1420 1655 -f 1655 1420 1418 -f 1655 1418 1657 -f 1207 1208 1418 -f 1418 1208 1656 -f 1418 1656 1657 -f 1094 1660 789 -f 789 1660 673 -f 1658 668 1659 -f 1659 668 672 -f 1659 672 636 -f 636 672 1095 -f 1095 672 1660 -f 1660 672 671 -f 1660 671 670 -f 670 1661 1660 -f 1660 1661 1662 -f 1660 1662 673 -f 905 1663 900 -f 900 1663 1664 -f 900 1664 789 -f 789 1664 1665 -f 789 1665 1094 -f 905 890 1663 -f 1663 890 772 -f 1663 772 1668 -f 874 1666 1667 -f 1667 1666 1128 -f 1667 1128 772 -f 772 1128 1130 -f 772 1130 1668 -f 874 888 1666 -f 1666 888 1671 -f 1666 1671 1120 -f 1120 1671 1669 -f 856 1670 1671 -f 1671 1670 1672 -f 1671 1672 1669 -f 856 1673 1670 -f 1670 1673 830 -f 1670 830 829 -f 1674 1118 829 -f 829 1118 1675 -f 829 1675 1670 -f 1674 829 1676 -f 1676 829 827 -f 1676 827 828 -f 828 818 1676 -f 1676 818 1678 -f 1676 1678 1677 -f 1677 1678 1112 -f 953 1105 1678 -f 1678 1105 1104 -f 1678 1104 1112 -f 1683 1680 1679 -f 1679 1680 625 -f 1683 624 1681 -f 1683 1682 1680 -f 1683 1681 1682 -f 1469 1684 1685 -f 1685 1684 1686 -f 1685 1686 1449 -f 625 1680 1687 -f 1687 1680 587 -f 1687 587 1411 -f 1411 587 1412 -f 1412 587 586 -f 1412 586 1688 -f 1688 586 585 -f 1688 585 1689 -f 1689 585 562 -f 1689 562 1469 -f 1469 562 561 -f 1469 561 1684 -f 552 1690 559 -f 559 1690 1448 -f 1449 1686 1448 -f 1448 1686 1691 -f 1448 1691 559 -f 551 1695 552 -f 552 1695 1692 -f 552 1692 1690 -f 1698 1693 1694 -f 1694 1693 1695 -f 1694 1695 444 -f 444 1695 551 -f 475 1702 1696 -f 1697 1433 1698 -f 1698 1433 1699 -f 1698 1699 1693 -f 1696 1430 475 -f 475 1430 1700 -f 475 1700 466 -f 466 1700 1433 -f 466 1433 459 -f 459 1433 1697 -f 1706 1427 488 -f 488 1427 1428 -f 488 1428 489 -f 489 1428 1702 -f 489 1702 1701 -f 1701 1702 475 -f 1408 488 512 -f 512 515 1408 -f 1408 515 1704 -f 1408 1704 517 -f 1408 1410 488 -f 488 1410 1705 -f 488 1705 1386 -f 1706 488 1426 -f 1426 488 1386 -f 1426 1386 1703 -f 1703 1386 1707 -f 1703 1707 1424 -f 1368 1713 1405 -f 1405 1713 1709 -f 1405 1709 1708 -f 1708 1709 975 -f 1708 975 1719 -f 1710 1712 1711 -f 1711 1712 1714 -f 1711 1714 1713 -f 1713 1714 1715 -f 1713 1715 1709 -f 1716 1391 1717 -f 1717 1391 1718 -f 1717 1718 1719 -f 1719 1718 1720 -f 1719 1720 1708 -f 1723 1721 1339 -f 1381 1393 1722 -f 1381 1722 1339 -f 1339 1722 1038 -f 1339 1038 1723 -f 1716 1035 1391 -f 1391 1035 1722 -f 1391 1722 1392 -f 1392 1722 1393 -f 1724 1725 1174 -f 1174 1725 1726 -f 1174 1726 1189 -f 1189 1726 1728 -f 1189 1728 1727 -f 1727 1728 971 -f 1727 971 1150 -f 1150 971 973 -f 1150 973 1151 -f 1151 973 1712 -f 1151 1712 1729 -f 1729 1712 1710 -f 1731 1730 1732 -f 1174 1182 1724 -f 1724 1182 1183 -f 1724 1183 967 -f 967 1183 1731 -f 967 1731 966 -f 966 1731 1732 -f 1121 1116 177 -f 1733 1734 630 -f 1735 629 630 -f 1735 630 1734 -f 630 1736 1733 -f 1733 1736 1738 -f 1733 1738 1737 -f 1737 1738 1739 -f 1737 1739 1740 -f 1737 1740 1741 -f 1741 1740 1135 -f 1741 1135 1742 -f 1742 1135 1134 -f 1742 1134 1133 -f 1745 323 1132 -f 1132 323 1743 -f 1132 1743 1133 -f 1133 1743 332 -f 1133 332 1742 -f 1132 1744 1745 -f 1745 1744 1746 -f 1745 1746 316 -f 316 1746 1747 -f 316 1747 315 -f 315 1747 314 -f 1121 177 1748 -f 1747 1126 314 -f 314 1126 1749 -f 314 1749 288 -f 1748 177 1125 -f 1125 177 176 -f 1125 176 1749 -f 1749 176 175 -f 1749 175 288 -f 1752 1114 1750 -f 1750 1114 1751 -f 1750 1751 1113 -f 1750 1753 1752 -f 1752 1753 1754 -f 1752 1754 1116 -f 1116 1754 185 -f 1116 185 177 -f 1758 1757 1107 -f 1107 1757 190 -f 1107 190 1113 -f 1113 190 1755 -f 1113 1755 1750 -f 222 1757 1760 -f 1760 1757 1756 -f 1175 1756 1099 -f 1099 1756 1757 -f 1099 1757 1101 -f 1101 1757 1758 -f 287 1759 1760 -f 1760 1759 225 -f 1760 225 222 -f 1761 1169 1099 -f 1099 1169 1762 -f 1099 1762 1175 -f 1681 1763 1764 -f 1764 1763 9490 -f 1764 9490 1765 -f 9493 1766 9490 -f 9490 1766 1765 -f 1767 609 608 -f 1767 608 9493 -f 9493 608 1766 -f 609 1767 612 -f 612 1767 1768 -f 612 1768 1769 -f 1769 1768 9492 -f 1769 9492 1772 -f 1770 1778 1781 -f 600 602 9506 -f 9506 602 1771 -f 9506 1771 605 -f 605 607 9506 -f 9506 607 1772 -f 9506 1772 9492 -f 528 524 1774 -f 1774 524 1773 -f 1774 1773 1775 -f 1775 557 1774 -f 1774 557 1776 -f 1774 1776 9506 -f 9506 1776 1777 -f 9506 1777 600 -f 1781 1778 1774 -f 1774 1778 529 -f 1774 529 528 -f 1785 543 542 -f 542 1779 1785 -f 1785 1779 1780 -f 1785 1780 1781 -f 1781 1780 537 -f 1781 537 1770 -f 384 1782 1783 -f 1783 1782 1786 -f 384 383 1782 -f 1782 383 366 -f 1782 366 1784 -f 1784 366 545 -f 1784 545 1785 -f 1785 545 543 -f 1786 1782 1787 -f 1787 1782 1789 -f 1787 1789 1791 -f 368 369 1794 -f 1794 369 1788 -f 1794 1788 1789 -f 1789 1788 1790 -f 1789 1790 1791 -f 322 1794 1792 -f 1792 1794 1795 -f 1792 1795 334 -f 1793 368 320 -f 320 368 1794 -f 320 1794 319 -f 319 1794 322 -f 337 336 1795 -f 1795 336 335 -f 1795 335 334 -f 9495 433 1795 -f 1795 433 1796 -f 1795 1796 337 -f 1804 1802 1797 -f 1801 1798 1800 -f 629 9485 630 -f 630 9485 1801 -f 630 1801 1799 -f 1799 1801 1800 -f 1797 1802 1801 -f 1801 1802 1798 -f 1798 1802 1803 -f 1803 1096 1798 -f 9484 1658 1797 -f 1797 1658 635 -f 1797 635 1804 -f 1476 1836 1805 -f 1805 1836 1806 -f 9583 1352 1359 -f 1359 1360 9583 -f 9583 1360 1807 -f 9583 1807 1806 -f 1806 1807 1805 -f 1352 9583 1808 -f 1352 1808 1348 -f 1811 1809 1810 -f 1809 706 1810 -f 1810 706 1347 -f 1810 1347 1808 -f 1808 1347 1341 -f 1808 1341 1348 -f 696 697 1810 -f 1810 697 1811 -f 1814 693 1810 -f 1810 693 1812 -f 1812 694 1810 -f 1810 694 695 -f 1810 695 696 -f 2210 693 1813 -f 1813 693 1814 -f 1813 1814 1838 -f 2213 689 1815 -f 2210 2209 693 -f 693 2209 2213 -f 693 2213 1815 -f 689 2213 1816 -f 1816 2213 2212 -f 2212 2216 1816 -f 1816 2216 1817 -f 1816 1817 716 -f 716 1817 711 -f 711 1817 2217 -f 2218 2206 708 -f 708 1640 2218 -f 2218 1640 710 -f 2218 710 2217 -f 2217 710 709 -f 2217 709 711 -f 751 1821 1825 -f 9452 760 738 -f 738 769 9452 -f 9452 769 1818 -f 9452 1818 1819 -f 1819 1818 1820 -f 1819 1820 728 -f 1825 1821 1823 -f 1823 1821 1822 -f 1823 1822 750 -f 750 749 1823 -f 1823 749 752 -f 1823 752 9452 -f 9452 752 755 -f 9452 755 760 -f 913 1824 1827 -f 1827 1824 1826 -f 1827 1826 1825 -f 1825 1826 920 -f 1825 920 751 -f 1512 1508 1829 -f 1829 1508 1827 -f 1827 1508 913 -f 1504 1509 1831 -f 1831 1509 1828 -f 1831 1828 1829 -f 1829 1828 1830 -f 1829 1830 1512 -f 1485 1486 1834 -f 1834 1486 1488 -f 1834 1488 1831 -f 1831 1488 1504 -f 1481 1835 1480 -f 1480 1835 1479 -f 1481 1832 1835 -f 1835 1832 1833 -f 1835 1833 1834 -f 1834 1833 1483 -f 1834 1483 1485 -f 1479 1835 1477 -f 1477 1835 1836 -f 1477 1836 1476 -f 1735 1837 629 -f 629 1837 9485 -f 1838 2211 2208 -f 2208 2210 1838 -f 1838 2210 1813 -f 1839 9474 1840 -f 1839 1840 9456 -f 1839 9456 1841 -f 1841 1842 1919 -f 1919 1842 9466 -f 1919 9466 1920 -f 1920 9466 1843 -f 1920 1843 9481 -f 1920 9481 1921 -f 1921 9481 9468 -f 1921 9468 9597 -f 1921 9597 1922 -f 1922 9597 1844 -f 1922 1844 1923 -f 1923 1844 9473 -f 1923 9473 1937 -f 1937 9473 1846 -f 1937 1846 1935 -f 1935 1846 1847 -f 1935 1847 1850 -f 1850 1847 1849 -f 9491 9455 1848 -f 1848 1931 9491 -f 9491 1931 1932 -f 9491 1932 1849 -f 1849 1932 1933 -f 1849 1933 1850 -f 1851 1845 9587 -f 9587 1845 9455 -f 9455 1845 1848 -f 2178 1845 1851 -f 1851 157 2178 -f 2211 1838 1853 -f 1852 1918 1853 -f 1853 1918 2211 -f 1916 1915 1854 -f 1854 1915 1852 -f 1852 1915 1918 -f 1916 1854 1917 -f 1917 1854 1855 -f 1917 1855 9474 -f 1917 9474 1839 -f 1873 1856 1857 -f 1873 1857 9596 -f 9596 9461 1858 -f 1858 9602 1890 -f 1890 9602 9601 -f 1890 9601 1893 -f 1893 9601 1859 -f 1893 1859 9606 -f 1893 9606 1894 -f 1894 9606 9608 -f 1894 9608 1860 -f 1860 1861 1895 -f 1895 1861 1862 -f 1895 1862 1863 -f 1895 1863 1891 -f 1891 1863 1904 -f 1904 1863 9450 -f 1904 9450 1892 -f 2066 1892 9595 -f 9595 1892 9450 -f 2087 1864 1865 -f 1865 1866 2087 -f 1969 1968 2199 -f 1941 1969 1909 -f 1866 1865 1867 -f 1866 1867 1885 -f 1885 1867 1868 -f 1885 1868 1884 -f 1884 1868 1869 -f 1884 1869 1886 -f 1886 1869 1870 -f 1871 1880 1870 -f 1870 1880 1883 -f 1870 1883 1886 -f 1880 1871 1888 -f 1888 1871 1872 -f 1888 1872 1856 -f 1888 1856 1873 -f 1875 2090 2089 -f 1975 1878 1876 -f 1876 1881 1974 -f 1974 1881 1877 -f 1878 1879 1876 -f 1876 1879 1881 -f 1881 1874 1877 -f 1877 1874 1889 -f 1877 1889 1970 -f 1874 1881 1880 -f 1880 1881 1887 -f 1896 1874 1888 -f 1888 1874 1880 -f 1875 1882 2090 -f 2090 1882 1878 -f 1878 1882 1887 -f 1878 1887 1879 -f 1879 1887 1881 -f 1874 1896 1889 -f 1875 1886 1882 -f 1882 1886 1887 -f 1866 1885 2089 -f 2089 1885 1884 -f 2089 1884 1875 -f 1875 1884 1886 -f 1886 1883 1887 -f 1887 1883 1880 -f 1888 1873 1896 -f 1896 1873 9596 -f 1896 9596 1897 -f 1897 9596 1858 -f 1897 1858 1890 -f 1891 1904 1902 -f 1902 1904 1903 -f 1894 1860 1899 -f 1899 1860 1895 -f 1895 1891 1902 -f 1889 1896 1897 -f 1897 1890 1898 -f 1898 1890 1893 -f 1898 1893 1894 -f 1898 1894 1899 -f 1899 1895 1902 -f 1970 1889 1897 -f 1970 1897 1898 -f 1971 1898 1899 -f 1971 1899 1902 -f 1902 1901 1972 -f 1973 1972 1901 -f 1973 1901 1900 -f 1900 1902 2063 -f 1902 1900 1901 -f 2063 1902 1903 -f 2063 1903 1905 -f 1905 1903 1904 -f 1905 1904 2066 -f 2066 1904 1892 -f 1917 1912 1916 -f 2214 2211 1913 -f 2214 1913 1907 -f 1908 1909 1924 -f 1924 1909 1911 -f 1924 1911 1912 -f 1909 1910 1911 -f 1911 1910 1914 -f 1911 1914 1912 -f 1910 2207 1907 -f 1910 1907 1914 -f 1914 1907 1906 -f 1907 1913 1906 -f 1906 1916 1914 -f 1914 1916 1912 -f 1839 1912 1917 -f 2211 1918 1913 -f 1913 1918 1915 -f 1913 1915 1906 -f 1906 1915 1916 -f 1924 1912 1839 -f 1839 1841 1926 -f 1926 1841 1919 -f 1924 1839 1926 -f 1921 1922 1929 -f 1929 1922 1923 -f 1929 1923 1925 -f 1926 1919 1927 -f 1927 1919 1920 -f 1927 1920 1921 -f 1927 1921 1929 -f 1908 1924 1928 -f 1928 1924 1926 -f 1928 1926 1927 -f 1928 1927 1929 -f 1928 1929 1925 -f 1928 1925 1941 -f 2185 1968 1934 -f 1934 1930 2184 -f 2178 2181 1848 -f 2178 1848 1845 -f 2181 1930 1848 -f 1848 1930 1931 -f 1930 1934 1933 -f 1930 1933 1931 -f 1931 1933 1932 -f 1850 1933 1936 -f 1936 1933 1934 -f 1936 1934 1968 -f 1935 1850 1938 -f 1938 1850 1936 -f 1938 1936 1939 -f 1939 1936 1968 -f 1939 1968 1969 -f 1937 1935 1940 -f 1940 1935 1938 -f 1940 1938 1939 -f 1940 1939 1941 -f 1941 1939 1969 -f 1940 1941 1925 -f 1940 1925 1923 -f 1940 1923 1937 -f 1942 2044 2137 -f 1942 2137 1943 -f 1944 9470 1945 -f 1944 1945 2035 -f 2035 1945 9467 -f 2035 9467 2038 -f 2038 9467 1946 -f 2038 1946 9609 -f 2038 9609 2036 -f 2036 9609 9465 -f 2036 9465 2037 -f 2037 9465 1947 -f 2037 1947 2039 -f 2039 1947 9462 -f 2039 9462 2040 -f 2040 9462 1948 -f 2040 1948 1949 -f 2040 1949 2032 -f 2032 1949 9471 -f 1952 2022 9471 -f 9471 2022 2032 -f 1953 2018 1950 -f 1950 2018 9460 -f 2018 1951 9460 -f 9460 1951 9458 -f 9458 1951 2021 -f 9458 2021 1952 -f 1952 2021 2022 -f 1953 143 141 -f 1953 141 2018 -f 2044 1942 9546 -f 9451 2059 9546 -f 9546 2059 2044 -f 1954 2058 9451 -f 9451 2058 2059 -f 1956 2054 9459 -f 2054 2056 9459 -f 9459 2056 2055 -f 9459 2055 1955 -f 1955 2055 2057 -f 1955 2057 1954 -f 1954 2057 2058 -f 2054 1956 2053 -f 2053 1956 9472 -f 2053 9472 9470 -f 2053 9470 1944 -f 131 2124 9589 -f 9589 2124 1961 -f 9475 1957 2098 -f 2098 1957 2014 -f 1957 9475 1958 -f 1957 1958 2015 -f 2015 1958 2000 -f 2000 1958 9600 -f 2000 9600 2001 -f 2001 9600 9599 -f 2001 9599 2002 -f 2002 9599 9605 -f 2002 9605 2003 -f 2003 9605 9604 -f 2003 9604 9598 -f 2003 9598 2004 -f 2004 9598 1959 -f 2004 1959 1997 -f 1997 1959 9603 -f 1997 9603 1960 -f 1997 1960 2005 -f 2005 1960 9453 -f 2005 9453 9469 -f 2005 9469 1998 -f 1998 9469 1999 -f 1999 9469 9457 -f 1999 9457 1963 -f 1963 9457 1962 -f 1964 1986 1962 -f 1962 1986 1963 -f 1965 1979 1964 -f 1964 1979 1986 -f 9592 9477 1967 -f 1967 1983 9592 -f 9592 1983 9480 -f 9480 1983 1980 -f 9480 1980 1965 -f 1965 1980 1979 -f 9589 1961 1966 -f 1966 1961 9477 -f 9477 1961 1967 -f 1968 2185 2199 -f 1908 1928 1941 -f 1908 1941 1909 -f 1909 1969 1910 -f 1910 1969 2199 -f 1972 1973 1877 -f 1970 1898 1971 -f 1902 1972 1971 -f 1972 1970 1971 -f 2199 2207 1910 -f 1970 1972 1877 -f 1973 1974 1877 -f 1973 1876 1974 -f 2007 2009 2012 -f 1973 1975 1876 -f 2011 2007 2013 -f 1993 2013 2012 -f 2007 2012 2013 -f 2011 2013 1992 -f 2104 2011 1992 -f 2104 1992 1988 -f 2104 1988 1989 -f 1977 2033 1976 -f 1976 2028 1977 -f 2047 1977 2026 -f 1977 2028 2026 -f 2047 2027 1978 -f 2104 1989 1981 -f 2046 2047 1978 -f 2047 2026 2027 -f 2161 2046 1978 -f 1978 2027 2025 -f 1981 1989 1985 -f 1985 1982 2132 -f 2124 2125 1967 -f 2124 1967 1961 -f 2125 1982 1967 -f 1967 1982 1983 -f 1982 1985 1984 -f 1982 1984 1980 -f 1982 1980 1983 -f 1979 1980 1984 -f 1979 1984 1987 -f 1987 1984 1985 -f 1987 1985 1989 -f 1986 1979 1990 -f 1990 1979 1987 -f 1990 1987 1991 -f 1991 1987 1989 -f 1991 1989 1988 -f 1963 1986 1994 -f 1994 1986 1990 -f 1994 1990 1991 -f 1994 1991 1992 -f 1992 1991 1988 -f 1992 2013 1993 -f 1992 1993 1994 -f 1994 1993 1998 -f 1994 1998 1963 -f 1963 1998 1999 -f 2011 2006 2007 -f 1996 2015 1995 -f 1995 2015 2000 -f 1995 2000 2008 -f 2008 2000 2001 -f 2008 2001 2002 -f 2008 2002 2003 -f 2008 2003 2009 -f 2009 2003 2004 -f 2009 2004 1997 -f 2009 1997 2010 -f 2010 1997 2005 -f 2010 2005 1998 -f 2010 1998 1993 -f 2006 1995 2007 -f 2007 1995 2008 -f 2009 2010 2012 -f 2012 2010 1993 -f 2007 2008 2009 -f 2014 1957 2015 -f 2015 2101 2014 -f 1996 2016 2015 -f 2015 2016 2101 -f 1995 2016 1996 -f 1995 2103 2016 -f 2103 1995 2017 -f 2006 2017 1995 -f 2017 2006 2104 -f 2104 2006 2011 -f 1951 2019 2020 -f 2018 141 2019 -f 2018 2019 1951 -f 2020 2025 2023 -f 2020 2023 1951 -f 1951 2023 2021 -f 2022 2021 2023 -f 2022 2023 2024 -f 2024 2023 2025 -f 2024 2025 2027 -f 2032 2022 2031 -f 2031 2022 2024 -f 2031 2024 2029 -f 2029 2024 2026 -f 2026 2024 2027 -f 2026 2028 2030 -f 2026 2030 2029 -f 2029 2030 2031 -f 2031 2030 2040 -f 2031 2040 2032 -f 2034 1944 2035 -f 2039 2040 2030 -f 2034 2035 2041 -f 2041 2035 2038 -f 2041 2038 2036 -f 2041 2036 2042 -f 2042 2036 2037 -f 2042 2037 2039 -f 2042 2039 2030 -f 2033 2034 2041 -f 1976 2033 2041 -f 1976 2041 2042 -f 1976 2042 2030 -f 1976 2030 2028 -f 2045 2141 2140 -f 2161 2043 2046 -f 2047 2049 1977 -f 1977 2049 2033 -f 2043 2050 2046 -f 2046 2050 2051 -f 2046 2051 2047 -f 2047 2051 2049 -f 2049 2034 2033 -f 2034 2049 2053 -f 2053 2049 2051 -f 2053 2051 2054 -f 2054 2051 2052 -f 2045 2048 2141 -f 2141 2048 2043 -f 2043 2048 2052 -f 2043 2052 2050 -f 2050 2052 2051 -f 2044 2059 2140 -f 2140 2059 2045 -f 2057 2055 2056 -f 2059 2058 2045 -f 2045 2058 2057 -f 2045 2057 2048 -f 2048 2057 2056 -f 2048 2056 2052 -f 2052 2056 2054 -f 2053 1944 2034 -f 2060 2076 2062 -f 2060 2062 9482 -f 2061 9593 9487 -f 2061 9487 2062 -f 2062 9487 9482 -f 9593 2061 2067 -f 9593 2067 9478 -f 9478 2067 9595 -f 9595 2067 2066 -f 2065 2077 2070 -f 2077 1973 2070 -f 2070 1973 1900 -f 1900 2063 2070 -f 2070 2063 2067 -f 2063 1905 2067 -f 2067 1905 2066 -f 2064 2065 2070 -f 2064 2070 2068 -f 2067 2061 2070 -f 2068 2070 2069 -f 2069 2070 2071 -f 2070 2061 2074 -f 2070 2074 2071 -f 2071 2074 2072 -f 2072 2074 2084 -f 2061 2062 2074 -f 2084 2074 2073 -f 2073 2074 2075 -f 2075 2074 2062 -f 2075 2062 2076 -f 1975 1973 2078 -f 2078 1973 2077 -f 2078 2077 2079 -f 2079 2077 2065 -f 2079 2065 2080 -f 2080 2065 2064 -f 2080 2064 2096 -f 2096 2064 2068 -f 2096 2068 2095 -f 2095 2068 2069 -f 2095 2069 2081 -f 2081 2069 2071 -f 2081 2071 2082 -f 2082 2071 2072 -f 2082 2072 2083 -f 2083 2072 2084 -f 2083 2084 158 -f 158 2084 2073 -f 1878 1975 2078 -f 2085 2086 2094 -f 2087 1866 159 -f 159 1866 2092 -f 1866 2089 2088 -f 1866 2088 2092 -f 2089 2090 2091 -f 2089 2091 2088 -f 2088 2091 2093 -f 2088 2093 2092 -f 2092 2093 2085 -f 2092 2085 159 -f 159 2085 2094 -f 1878 2097 2090 -f 2090 2097 2091 -f 158 2086 2083 -f 2083 2086 2085 -f 2083 2085 2082 -f 2082 2085 2093 -f 2082 2093 2081 -f 2081 2093 2095 -f 2095 2093 2091 -f 2095 2091 2096 -f 2096 2091 2080 -f 2080 2091 2079 -f 2079 2091 2097 -f 2079 2097 2078 -f 2078 2097 1878 -f 9476 9479 2109 -f 2098 2014 2102 -f 2098 2102 9594 -f 2109 9479 2102 -f 2102 9479 9594 -f 9476 2109 2099 -f 9476 2099 2100 -f 2100 2099 9463 -f 9463 2099 2113 -f 9463 2113 9483 -f 2102 2014 2101 -f 2102 2101 2016 -f 2102 2016 2103 -f 2102 2103 2017 -f 2104 2105 2017 -f 2017 2105 2107 -f 2017 2107 2102 -f 2105 2106 2107 -f 2106 2108 2107 -f 2102 2107 2109 -f 2108 2110 2107 -f 2107 2112 2109 -f 2110 2111 2107 -f 2107 2111 2112 -f 2109 2112 2099 -f 2111 2119 2112 -f 2119 2118 2112 -f 2112 2118 2115 -f 2113 2099 127 -f 127 2099 2112 -f 127 2112 2115 -f 127 2115 132 -f 2114 132 2135 -f 2135 132 2115 -f 2135 2115 2116 -f 2116 2115 2118 -f 2116 2118 2117 -f 2117 2118 2119 -f 2117 2119 2134 -f 2134 2119 2111 -f 2134 2111 2120 -f 2120 2111 2110 -f 2120 2110 2133 -f 2133 2110 2108 -f 2133 2108 2121 -f 2121 2108 2106 -f 2121 2106 2122 -f 2122 2106 2105 -f 2122 2105 1981 -f 1981 2105 2104 -f 2124 131 2123 -f 2129 2124 2123 -f 2129 2123 130 -f 2129 130 2126 -f 2125 2124 2128 -f 2128 2124 2129 -f 2129 2126 2127 -f 1982 2125 2132 -f 2132 2125 2128 -f 2131 2128 2129 -f 2131 2129 2136 -f 2136 2129 2127 -f 2136 2127 2130 -f 2131 2132 2128 -f 1981 1985 2122 -f 2122 1985 2132 -f 2122 2132 2121 -f 2121 2132 2133 -f 2133 2132 2120 -f 2120 2132 2131 -f 2120 2131 2134 -f 2134 2131 2117 -f 2117 2131 2136 -f 2117 2136 2116 -f 2116 2136 2135 -f 2135 2136 2114 -f 2114 2136 2130 -f 2043 2161 2145 -f 2137 2044 129 -f 129 2044 2139 -f 2044 2140 2139 -f 2140 2141 2142 -f 2140 2142 2143 -f 2140 2143 2139 -f 2139 2143 2144 -f 2139 2144 129 -f 129 2144 2138 -f 2043 2152 2141 -f 2141 2152 2142 -f 2144 2147 2138 -f 128 2147 2146 -f 2146 2147 2144 -f 2146 2144 2155 -f 2155 2144 2143 -f 2155 2143 2148 -f 2148 2143 2149 -f 2149 2143 2142 -f 2149 2142 2150 -f 2150 2142 2151 -f 2151 2142 2160 -f 2160 2142 2152 -f 2160 2152 2145 -f 2145 2152 2043 -f 2164 128 2153 -f 2153 128 2146 -f 2153 2146 2154 -f 2154 2146 2155 -f 2154 2155 2163 -f 2163 2155 2148 -f 2163 2148 2156 -f 2156 2148 2149 -f 2156 2149 2157 -f 2157 2149 2150 -f 2157 2150 2158 -f 2158 2150 2151 -f 2158 2151 2159 -f 2159 2151 2160 -f 2159 2160 2162 -f 2162 2160 2145 -f 2162 2145 1978 -f 1978 2145 2161 -f 1978 2025 2172 -f 1978 2172 2162 -f 2162 2172 2159 -f 2159 2172 2158 -f 2158 2172 2173 -f 2158 2173 2157 -f 2157 2173 2156 -f 2156 2173 2174 -f 2156 2174 2163 -f 2163 2174 2154 -f 2154 2174 2153 -f 2153 2174 136 -f 2153 136 2164 -f 141 2165 2019 -f 2165 2167 2019 -f 141 2166 2165 -f 2165 2166 138 -f 2165 138 137 -f 2165 137 2167 -f 2167 137 2168 -f 2167 2168 2169 -f 2171 2025 2020 -f 2020 2019 2171 -f 2171 2019 2167 -f 2167 2169 2170 -f 135 2175 2170 -f 2170 2175 2167 -f 2167 2175 2174 -f 2167 2174 2173 -f 2167 2173 2171 -f 2171 2173 2172 -f 2171 2172 2025 -f 2174 2175 136 -f 2178 157 2176 -f 2180 2178 2176 -f 2180 2176 2177 -f 2180 2177 2179 -f 2181 2178 2183 -f 2183 2178 2180 -f 2180 2179 2182 -f 1930 2181 2184 -f 2184 2181 2183 -f 2190 2183 2180 -f 2190 2180 2193 -f 2193 2180 2182 -f 2193 2182 156 -f 2190 2184 2183 -f 2185 1934 2186 -f 2186 1934 2184 -f 2186 2184 2195 -f 2195 2184 2197 -f 2197 2184 2187 -f 2187 2184 2190 -f 2187 2190 2188 -f 2188 2190 2189 -f 2189 2190 2193 -f 2189 2193 2198 -f 2198 2193 2191 -f 2191 2193 2192 -f 2192 2193 156 -f 2199 2185 2194 -f 2194 2185 2186 -f 2194 2186 2200 -f 2200 2186 2195 -f 2200 2195 2196 -f 2196 2195 2197 -f 2196 2197 2201 -f 2201 2197 2187 -f 2201 2187 2202 -f 2202 2187 2188 -f 2202 2188 2203 -f 2203 2188 2189 -f 2203 2189 2204 -f 2204 2189 2198 -f 2204 2198 2205 -f 2205 2198 2191 -f 2205 2191 2206 -f 2206 2191 2192 -f 2207 2199 2194 -f 2207 2194 2200 -f 2207 2200 2196 -f 2207 2196 2201 -f 2207 2201 2220 -f 2220 2201 2202 -f 2220 2202 2203 -f 2220 2203 2219 -f 2219 2203 2204 -f 2219 2204 2205 -f 2219 2205 2206 -f 2219 2206 2218 -f 2215 1817 2216 -f 2208 2213 2209 -f 2209 2210 2208 -f 2211 2214 2208 -f 2208 2214 2215 -f 2215 2212 2208 -f 2208 2212 2213 -f 2215 2216 2212 -f 1907 2207 2214 -f 2214 2207 2220 -f 2214 2220 2215 -f 2215 2220 2219 -f 2215 2219 2217 -f 2215 2217 1817 -f 2218 2217 2219 -f 2221 4323 4325 -f 2221 4325 2222 -f 2221 2222 4659 -f 2221 4659 9494 -f 9494 4659 2223 -f 9494 2223 2224 -f 2224 2223 4661 -f 2224 4661 4662 -f 2225 4424 4368 -f 4368 4424 4414 -f 4423 4422 4373 -f 4373 4422 2225 -f 2225 4422 4424 -f 4420 4423 2226 -f 2226 4423 4373 -f 4419 4420 4372 -f 4372 4420 2226 -f 9505 2227 4419 -f 9505 4419 4372 -f 4418 4419 2227 -f 9526 2229 2228 -f 2228 2229 4444 -f 4444 2229 9553 -f 2357 2597 2230 -f 2248 2231 9570 -f 9570 2231 7107 -f 4449 4450 2232 -f 2232 4450 2233 -f 2232 2233 2246 -f 2246 2233 4453 -f 2246 4453 2242 -f 4462 2234 9570 -f 2237 2239 2238 -f 7109 4462 9570 -f 7109 9570 7107 -f 7111 2235 4460 -f 4462 7109 7111 -f 4462 7111 4460 -f 2235 7111 4440 -f 4440 7111 7086 -f 4440 7086 2236 -f 2236 7086 2237 -f 2236 2237 2238 -f 2239 2237 4456 -f 4456 2237 2240 -f 2240 2241 4456 -f 2241 2240 7099 -f 2241 7099 7102 -f 2241 7102 2242 -f 2242 7102 2246 -f 2246 7102 2247 -f 2234 4466 9570 -f 9570 4466 2243 -f 9570 2243 2251 -f 2251 2243 2244 -f 4449 2232 2230 -f 2230 2232 2359 -f 2230 2359 2357 -f 2245 5187 2360 -f 2246 2247 2360 -f 2360 2247 7095 -f 2360 7095 2245 -f 7090 7089 2248 -f 2248 7089 2231 -f 2248 2249 7090 -f 7090 2249 2250 -f 7090 2250 4927 -f 2244 2252 2251 -f 2251 2252 9553 -f 9553 2252 4441 -f 9553 4441 4444 -f 2253 4445 2254 -f 2253 2254 2255 -f 2255 2254 2598 -f 2255 2598 2599 -f 2261 4472 2256 -f 2256 4472 4474 -f 4474 2257 2256 -f 2256 2257 2258 -f 2256 2258 2253 -f 2253 2258 4477 -f 2253 4477 4445 -f 2264 4482 2591 -f 2591 4482 2259 -f 2591 2259 2592 -f 2596 2594 4469 -f 4469 2594 2458 -f 4469 2458 2259 -f 2259 2458 2592 -f 4469 2260 2596 -f 2596 2260 2256 -f 2256 2260 2261 -f 2262 2263 4478 -f 4478 2263 2266 -f 4478 2266 4442 -f 2262 4479 2263 -f 2263 4479 4480 -f 2263 4480 2265 -f 2591 9527 2264 -f 2264 9527 2263 -f 2264 2263 4481 -f 2263 2265 4481 -f 4442 2266 4443 -f 4443 2266 9530 -f 4443 9530 2267 -f 2267 9530 9526 -f 2267 9526 2228 -f 2795 2791 2268 -f 5394 5853 5392 -f 5395 2272 5756 -f 2292 2748 2447 -f 9508 5257 2285 -f 2273 5317 2293 -f 2269 2270 2328 -f 2447 2748 3170 -f 5394 5768 5853 -f 5853 5768 5765 -f 5233 2271 2281 -f 5756 2272 2293 -f 2293 2272 5315 -f 2293 5315 2273 -f 2706 2708 2447 -f 5395 5756 5394 -f 5394 5756 5768 -f 2268 3265 2277 -f 9508 2283 5331 -f 5331 2274 9508 -f 9508 2274 2275 -f 2275 5334 2281 -f 2281 5334 2276 -f 2286 5261 2319 -f 2269 2328 2691 -f 2795 2268 2794 -f 2794 2268 2277 -f 5338 6385 2278 -f 5234 5233 2278 -f 2278 5233 2281 -f 2278 2281 2279 -f 2279 2281 2276 -f 2271 5232 2281 -f 2281 5232 2280 -f 2281 2280 5230 -f 5230 5229 2281 -f 2281 5229 2282 -f 2281 2282 9512 -f 2283 9508 2284 -f 2284 9508 2285 -f 2284 2285 2319 -f 2319 2285 5259 -f 2319 5259 2286 -f 2287 2702 2447 -f 2447 2741 2291 -f 2748 2288 3170 -f 3170 2288 2289 -f 3170 2289 3181 -f 3181 2289 2794 -f 3181 2794 2277 -f 2702 2290 2447 -f 2447 2290 2704 -f 2447 2704 2706 -f 2291 2743 2447 -f 2447 2743 2745 -f 2447 2745 2292 -f 5317 5319 2293 -f 2293 5319 5320 -f 2293 5320 2294 -f 5261 2295 2319 -f 2319 2295 5264 -f 2319 5264 5265 -f 2296 2297 2293 -f 2293 2297 2298 -f 2293 2298 5284 -f 2741 2447 2740 -f 2740 2447 2708 -f 2740 2708 2334 -f 5234 2278 2299 -f 2299 2278 6382 -f 2299 6382 2300 -f 2294 5321 2301 -f 2301 5321 5323 -f 2294 2301 2293 -f 2293 2301 2302 -f 2293 2302 2296 -f 2712 2303 2568 -f 2568 2303 2715 -f 2685 2688 2328 -f 2328 2688 2304 -f 2328 2304 2691 -f 6385 6382 2278 -f 2305 5253 9499 -f 2715 2716 2568 -f 2568 2716 2306 -f 2568 2306 2718 -f 5284 2307 2293 -f 2293 2307 5287 -f 2293 5287 5018 -f 5018 5287 5288 -f 5018 5288 2310 -f 2310 5288 2308 -f 2310 2308 2309 -f 5338 6386 6385 -f 2309 5291 2310 -f 2310 5291 5292 -f 2310 5292 2311 -f 2311 5296 2310 -f 2310 5296 2313 -f 2310 2313 2312 -f 2312 2313 5297 -f 2312 5297 5125 -f 9499 5253 9514 -f 9514 5253 2314 -f 9514 2314 5256 -f 2712 2568 2343 -f 2343 2568 2578 -f 2343 2578 2580 -f 5272 2315 5324 -f 5324 2315 5275 -f 2675 2345 2316 -f 2317 2694 2336 -f 2336 2694 2318 -f 2331 5326 5266 -f 5266 5326 5327 -f 5266 5327 5265 -f 5265 5327 5329 -f 5265 5329 2319 -f 2324 9511 2645 -f 2645 9511 2643 -f 2328 2756 2758 -f 2718 2320 2568 -f 2568 2320 2321 -f 2568 2321 2571 -f 2571 2321 2711 -f 2571 2711 2447 -f 2447 2711 2700 -f 2447 2700 2287 -f 2652 2322 9511 -f 9511 2322 2323 -f 9511 2323 2643 -f 2324 2647 9511 -f 9511 2647 2325 -f 9511 2325 2326 -f 2327 2751 2326 -f 2326 2751 2752 -f 2326 2752 2328 -f 2328 2752 2755 -f 2328 2755 2756 -f 2685 2328 2684 -f 2684 2328 2758 -f 2684 2758 2329 -f 2329 2758 2760 -f 2329 2760 2337 -f 2337 2760 2761 -f 2337 2761 2330 -f 5266 5269 2331 -f 2331 5269 5270 -f 2331 5270 5324 -f 5324 5270 5271 -f 5324 5271 5272 -f 5275 2332 5324 -f 5324 2332 5277 -f 5324 5277 5323 -f 5323 5277 5278 -f 5323 5278 2301 -f 5299 5250 9499 -f 9499 5250 2333 -f 9499 2333 2305 -f 2708 2335 2334 -f 2334 2335 2698 -f 2334 2698 2336 -f 2336 2698 2697 -f 2336 2697 2317 -f 2647 2648 2325 -f 2325 2648 2649 -f 2325 2649 2348 -f 2330 2338 2337 -f 2337 2338 2765 -f 2337 2765 2339 -f 2339 2765 2340 -f 2339 2340 2693 -f 2693 2340 2336 -f 2693 2336 2696 -f 2696 2336 2318 -f 2325 3785 3788 -f 2325 3788 2749 -f 2341 9504 2580 -f 9504 9503 2580 -f 2580 9503 2342 -f 2580 2342 2343 -f 2343 2342 9515 -f 2343 9515 2344 -f 2344 9515 2722 -f 2345 2346 2316 -f 2316 2346 2347 -f 2316 2347 9515 -f 9515 2347 2680 -f 9515 2680 2722 -f 2348 3785 2325 -f 5299 9499 2350 -f 2350 9499 2349 -f 2350 2349 5297 -f 5297 2349 9500 -f 5297 9500 5125 -f 3788 2352 2351 -f 3788 2351 2749 -f 9500 2353 5125 -f 5125 2353 9501 -f 5125 9501 5129 -f 5129 9501 9510 -f 5129 9510 5013 -f 5013 9510 2354 -f 2354 9510 9507 -f 2354 9507 2364 -f 2580 2577 2341 -f 2341 2577 2596 -f 2341 2596 2355 -f 2355 2596 2256 -f 2256 2253 2355 -f 2355 2253 2255 -f 2355 2255 9497 -f 9497 2255 2599 -f 9497 2599 2356 -f 2356 2599 2357 -f 2356 2357 2358 -f 2358 2357 2359 -f 2358 2359 9509 -f 2359 2232 9509 -f 9509 2232 2246 -f 9509 2246 9496 -f 9496 2246 2360 -f 9496 2360 2361 -f 2361 2360 5187 -f 2361 5187 9498 -f 9498 5187 2362 -f 9498 2362 9507 -f 9507 2362 2363 -f 9507 2363 2364 -f 3632 3630 2370 -f 2368 3695 2366 -f 2367 2368 3634 -f 3700 2365 2367 -f 2365 3698 2367 -f 2367 3698 3697 -f 3695 2368 2367 -f 3695 2367 3697 -f 2369 2366 2374 -f 2368 2366 2369 -f 2367 3634 3633 -f 2367 3633 2370 -f 2370 3633 3632 -f 2371 3630 2372 -f 2370 3762 3760 -f 3767 3765 2370 -f 2370 3765 3762 -f 2819 2370 3760 -f 3759 2373 2372 -f 3630 2371 2370 -f 2370 2371 3767 -f 2371 2372 2373 -f 2366 3691 2374 -f 2372 2375 3759 -f 3703 3182 2376 -f 3703 2376 2377 -f 3607 2378 3701 -f 3607 3701 2381 -f 3586 3588 3719 -f 2378 3607 3586 -f 2378 3586 3721 -f 3721 3586 3719 -f 3719 3588 3589 -f 3719 3589 3716 -f 3716 3589 3591 -f 3716 3591 3717 -f 3717 3591 2379 -f 2379 3591 3593 -f 3592 3713 3712 -f 3592 3712 2380 -f 3592 2380 3593 -f 3593 2380 2379 -f 3713 3592 3596 -f 3706 3708 3599 -f 3598 3597 3711 -f 3596 3595 3713 -f 3713 3595 3711 -f 3711 3595 3598 -f 3711 3597 3601 -f 3599 3708 3711 -f 3599 3711 3601 -f 2381 3701 3003 -f 2381 3003 3562 -f 3562 3003 3636 -f 3674 3584 3562 -f 3674 3562 3636 -f 2382 3656 3583 -f 3584 3674 2382 -f 3584 2382 3585 -f 3585 2382 3583 -f 3583 3656 2383 -f 3583 2383 3581 -f 3581 2383 3659 -f 3581 3659 3582 -f 3582 3659 3580 -f 3580 3659 2386 -f 2385 2384 3575 -f 2385 3575 3576 -f 2385 3576 2386 -f 2386 3576 3580 -f 2384 2385 3664 -f 3568 3570 2667 -f 2387 2388 3571 -f 3664 3663 2384 -f 2384 3663 3571 -f 3571 3663 2387 -f 3571 2388 3666 -f 2667 3570 3571 -f 2667 3571 3666 -f 3003 3668 3636 -f 3198 2390 2389 -f 2389 2390 3003 -f 2389 3003 2377 -f 2377 3003 3701 -f 2377 3701 3703 -f 3182 3703 3723 -f 3182 3723 2391 -f 3182 2391 2392 -f 3182 2392 2393 -f 2393 2392 3727 -f 2393 3727 3322 -f 3727 3731 3322 -f 3322 3731 2394 -f 2394 3731 2395 -f 2395 3731 3729 -f 2395 3729 2398 -f 2399 3738 2396 -f 2396 3738 3741 -f 2396 3741 3740 -f 3729 3733 2398 -f 2398 3733 2397 -f 2397 3733 3736 -f 2397 3736 2396 -f 2396 3736 2399 -f 3487 3427 3491 -f 3405 3480 3427 -f 3427 3480 3491 -f 3425 3561 2400 -f 3539 3415 3561 -f 3561 3415 2400 -f 3269 2402 2632 -f 2632 2402 2401 -f 3269 2778 2402 -f 2397 2403 2398 -f 2398 2403 2395 -f 2670 2654 3165 -f 3165 2654 2655 -f 3165 2655 3167 -f 3167 2655 2656 -f 3167 2656 2404 -f 2404 2656 9523 -f 9523 2656 2405 -f 9523 2405 2406 -f 2670 3165 2396 -f 2396 3165 2407 -f 2396 2407 2397 -f 2397 2407 3175 -f 2406 2659 9523 -f 9523 2659 2660 -f 9523 2660 2661 -f 2661 2408 9523 -f 9523 2408 2663 -f 9523 2663 2665 -f 3326 2403 3175 -f 3175 2403 2397 -f 2409 3320 2410 -f 2410 3320 2411 -f 2410 2411 2413 -f 2413 2411 2412 -f 2413 2412 2414 -f 2414 2412 2415 -f 2414 2415 2416 -f 2416 2415 2417 -f 2416 2417 3350 -f 3350 2417 3318 -f 3350 3318 2418 -f 2418 3318 3316 -f 2418 3316 2419 -f 2419 3316 2420 -f 2419 2420 3348 -f 3348 2420 2421 -f 3348 2421 2422 -f 2422 2421 3314 -f 2422 3314 3345 -f 3345 3314 3312 -f 3345 3312 3344 -f 3344 3312 3311 -f 3344 3311 3343 -f 3343 3311 2423 -f 3343 2423 3342 -f 3342 2423 3309 -f 3342 3309 3340 -f 3340 3309 3308 -f 3340 3308 2424 -f 2424 3308 3307 -f 2424 3307 3339 -f 3339 3307 2426 -f 3339 2426 2425 -f 2425 2426 2427 -f 2425 2427 3338 -f 3338 2427 3305 -f 3338 3305 2428 -f 2428 3305 2429 -f 2428 2429 2430 -f 2430 2429 2431 -f 2430 2431 3336 -f 3336 2431 3304 -f 3336 3304 2432 -f 2432 3304 3303 -f 2432 3303 2433 -f 2433 3303 3302 -f 2433 3302 2434 -f 2434 3302 3298 -f 2511 3260 3259 -f 2483 4201 4199 -f 4199 2437 2483 -f 2483 2437 4198 -f 2483 4198 2442 -f 4180 2438 2479 -f 4201 2483 2439 -f 2439 2483 2571 -f 2439 2571 4166 -f 2479 2438 2852 -f 2438 4179 2852 -f 2852 4179 4178 -f 2852 4178 2447 -f 2441 2479 4187 -f 4187 2479 2440 -f 2441 4184 2479 -f 2479 4184 4182 -f 2479 4182 4180 -f 2449 4169 2571 -f 2442 2443 2483 -f 2483 2443 2444 -f 2483 2444 2445 -f 2445 4192 2483 -f 2483 4192 4191 -f 2483 4191 2479 -f 2479 4191 4189 -f 2479 4189 2440 -f 4178 2446 2447 -f 2447 2446 4177 -f 2447 4177 4176 -f 4176 4174 2447 -f 2447 4174 2448 -f 2447 2448 4173 -f 2449 2571 2454 -f 4169 2450 2571 -f 2571 2450 2451 -f 2571 2451 4166 -f 4173 2452 2447 -f 2447 2452 2453 -f 2447 2453 2571 -f 2571 2453 4172 -f 2571 4172 2454 -f 2462 2456 6989 -f 3880 2455 3882 -f 3882 2455 3884 -f 6989 2456 2455 -f 2455 2456 2457 -f 2455 2457 3884 -f 3867 2459 2458 -f 2460 3902 2593 -f 2459 3907 2458 -f 2458 3907 3906 -f 2458 3906 2593 -f 2593 3906 3905 -f 2593 3905 2460 -f 3891 3889 6989 -f 3889 2461 6989 -f 6989 2461 3886 -f 6989 3886 2462 -f 3902 3900 2593 -f 2593 3900 2463 -f 2593 2463 3896 -f 3896 3894 2593 -f 2593 3894 2464 -f 2593 2464 3893 -f 3893 3892 6989 -f 6989 3892 2465 -f 6989 2465 3891 -f 2588 3879 3878 -f 3867 2458 2595 -f 3867 2595 2467 -f 3873 3871 2595 -f 3871 3870 2595 -f 2595 3870 2466 -f 2595 2466 2467 -f 3878 3876 2588 -f 2588 3876 2468 -f 2588 2468 2595 -f 2595 2468 3874 -f 2595 3874 3873 -f 4026 4025 2560 -f 4008 4007 2850 -f 4029 4027 2488 -f 2488 4027 2469 -f 2488 2469 4026 -f 4025 4024 2560 -f 2560 4024 2470 -f 2560 2470 4023 -f 2850 4007 2478 -f 4007 2471 2478 -f 2478 2471 2472 -f 2478 2472 2473 -f 4023 2474 2560 -f 2560 2474 4019 -f 2560 4019 4018 -f 4018 4017 2560 -f 2560 4017 4015 -f 2560 4015 2850 -f 2850 4015 4013 -f 4013 4012 2850 -f 2850 4012 2475 -f 2850 2475 2476 -f 2476 2477 2850 -f 2850 2477 4009 -f 2850 4009 4008 -f 2473 4003 2478 -f 2478 4003 4002 -f 2478 4002 2479 -f 2483 4030 2488 -f 2488 4030 4029 -f 4002 2480 2479 -f 2479 2480 4000 -f 2479 4000 2481 -f 2481 3998 2479 -f 2479 3998 2482 -f 2479 2482 2483 -f 2483 2482 3996 -f 2483 3996 3995 -f 3995 2484 2483 -f 2483 2484 3992 -f 2483 3992 4030 -f 4061 2488 2485 -f 2485 2488 4062 -f 6987 2486 2487 -f 2487 4086 6987 -f 6987 4086 4084 -f 6987 4084 2490 -f 2490 4084 4083 -f 4026 2560 2488 -f 2488 2560 4065 -f 2488 4065 4062 -f 4083 2489 2490 -f 2490 2489 4080 -f 2490 4080 4079 -f 4068 4067 2560 -f 2560 4067 2491 -f 2560 2491 4065 -f 2492 4069 2560 -f 2560 4069 2493 -f 2560 2493 4068 -f 4079 4077 2490 -f 2490 4077 4076 -f 2490 4076 4075 -f 4075 2494 2490 -f 2490 2494 4073 -f 2490 4073 2560 -f 2560 4073 4071 -f 2560 4071 2492 -f 2495 2496 2483 -f 4061 4059 2488 -f 2488 4059 4058 -f 2488 4058 2483 -f 2483 4058 2495 -f 2497 2498 2572 -f 2572 2498 4049 -f 2572 4049 2563 -f 2496 4054 2483 -f 2483 4054 2499 -f 2483 2499 2572 -f 2572 2499 2500 -f 2572 2500 2497 -f 2511 3259 2520 -f 2520 3259 9580 -f 2520 9580 2501 -f 2501 2502 2520 -f 2520 2502 9568 -f 2520 9568 2523 -f 2523 9568 9567 -f 2523 9567 9536 -f 9527 2591 9528 -f 9528 2591 2558 -f 9528 2558 9535 -f 9535 2558 2542 -f 9535 2542 2503 -f 2503 2542 2523 -f 2503 2523 2504 -f 2504 2523 9536 -f 2515 4106 2561 -f 4106 4104 2561 -f 2561 4104 2505 -f 2561 2505 2520 -f 2520 2505 2506 -f 2520 2506 2507 -f 2507 2508 2520 -f 2520 2508 4144 -f 2520 4144 4142 -f 2518 2509 2511 -f 2511 2509 2510 -f 2511 2510 2512 -f 2512 2510 4125 -f 4125 4123 2512 -f 2512 4123 4121 -f 2512 4121 4119 -f 4119 2513 2512 -f 2512 2513 4116 -f 2512 4116 2514 -f 4112 4111 2561 -f 2561 4111 4108 -f 2561 4108 2515 -f 2517 2511 2516 -f 2516 2511 4132 -f 2517 4130 2511 -f 2511 4130 4129 -f 2511 4129 2518 -f 4142 2519 2520 -f 2520 2519 4139 -f 2520 4139 4138 -f 2514 4115 2512 -f 2512 4115 4114 -f 2512 4114 2561 -f 2561 4114 2521 -f 2561 2521 4112 -f 4138 4135 2520 -f 2520 4135 2522 -f 2520 2522 2511 -f 2511 2522 4134 -f 2511 4134 4132 -f 2544 4222 2523 -f 2523 4222 4258 -f 2523 4258 2524 -f 2525 4226 2543 -f 2543 4226 2526 -f 2543 2526 4224 -f 2524 4254 2523 -f 2523 4254 2527 -f 2523 2527 4253 -f 2520 2538 4246 -f 4246 2528 2520 -f 2520 2528 2529 -f 2520 2529 4244 -f 2561 2534 2530 -f 2530 2531 2561 -f 2561 2531 4237 -f 2561 4237 2535 -f 2532 4230 2543 -f 2543 4230 4229 -f 2543 4229 2525 -f 4244 4242 2520 -f 2520 4242 2533 -f 2520 2533 2561 -f 2561 2533 4239 -f 2561 4239 2534 -f 2535 4234 2561 -f 2561 4234 4233 -f 2561 4233 2543 -f 2543 4233 4232 -f 2543 4232 2532 -f 4253 4252 2523 -f 2523 4252 4251 -f 2523 4251 2536 -f 2536 4250 2523 -f 2523 4250 2537 -f 2523 2537 2520 -f 2520 2537 4247 -f 2520 4247 2538 -f 3828 2539 2541 -f 3833 2540 2558 -f 2558 2540 3832 -f 2558 3832 3830 -f 3830 3828 2558 -f 2558 3828 2541 -f 2558 2541 2542 -f 2542 2541 6985 -f 2542 6985 2523 -f 2523 6985 2543 -f 2523 2543 2544 -f 2544 2543 4224 -f 3811 3809 2548 -f 2548 3809 3807 -f 2548 3807 2591 -f 2591 3807 3848 -f 3848 2545 2591 -f 2591 2545 3845 -f 2591 3845 3843 -f 3838 3837 2558 -f 2558 3837 3835 -f 2558 3835 3833 -f 2539 2546 2541 -f 2541 2546 2547 -f 2541 2547 3824 -f 3815 3814 2548 -f 2548 3814 2549 -f 2548 2549 3811 -f 3824 3823 2541 -f 2541 3823 3822 -f 2541 3822 2562 -f 2550 2548 3818 -f 3818 2548 3820 -f 3843 2551 2591 -f 2591 2551 2552 -f 2591 2552 2553 -f 2550 2554 2548 -f 2548 2554 2555 -f 2548 2555 3815 -f 2553 2556 2591 -f 2591 2556 2557 -f 2591 2557 2558 -f 2558 2557 2559 -f 2558 2559 3838 -f 2543 2490 2561 -f 2561 2490 2560 -f 2561 2560 2512 -f 2512 2560 2850 -f 3893 6989 2593 -f 2593 6989 2541 -f 2593 2541 2548 -f 2548 2541 2562 -f 2548 2562 3820 -f 3880 3879 2455 -f 2455 3879 2588 -f 6987 2572 2486 -f 2486 2572 2563 -f 2564 4288 2568 -f 2565 4322 2572 -f 2572 4322 2566 -f 2572 2566 4321 -f 4296 4294 2571 -f 2571 4294 2570 -f 2564 2568 2567 -f 2567 2568 2571 -f 2567 2571 2569 -f 4288 4287 2568 -f 2568 4287 4284 -f 2568 4284 4283 -f 2570 4292 2571 -f 2571 4292 4290 -f 2571 4290 2569 -f 4283 4282 2568 -f 2568 4282 4279 -f 2568 4279 2579 -f 4321 4320 2572 -f 2572 4320 4318 -f 2572 4318 4317 -f 2483 4308 4307 -f 4307 4306 2483 -f 2483 4306 4304 -f 2483 4304 4303 -f 4303 2573 2483 -f 2483 2573 4300 -f 2483 4300 2571 -f 2571 4300 4298 -f 2571 4298 4296 -f 4317 4315 2572 -f 2572 4315 4314 -f 2572 4314 4313 -f 4313 4312 2572 -f 2572 4312 4311 -f 2572 4311 2483 -f 2483 4311 2574 -f 2483 2574 4308 -f 2584 3949 2588 -f 3938 3936 2577 -f 3968 3967 2595 -f 3926 3925 2577 -f 2577 3925 2575 -f 2577 2575 2595 -f 2595 2575 3970 -f 2595 3970 3968 -f 2590 3954 2595 -f 3947 2576 2580 -f 2580 2576 3945 -f 3931 3930 2577 -f 2577 3930 3928 -f 2577 3928 3926 -f 2589 3952 2588 -f 3949 3947 2588 -f 2588 3947 2580 -f 2588 2580 6986 -f 6986 2580 2578 -f 6986 2578 2572 -f 2572 2578 2568 -f 2572 2568 2565 -f 2565 2568 2579 -f 3945 3943 2580 -f 2580 3943 3942 -f 2580 3942 2585 -f 3936 3934 2577 -f 2577 3934 2581 -f 2577 2581 3931 -f 3952 2582 2588 -f 2588 2582 2583 -f 2588 2583 2584 -f 2585 2586 2580 -f 2580 2586 3939 -f 2580 3939 2577 -f 2577 3939 2587 -f 2577 2587 3938 -f 3967 3966 2595 -f 2595 3966 3965 -f 2595 3965 3962 -f 2595 3954 2588 -f 2588 3954 3953 -f 2588 3953 2589 -f 3962 3959 2595 -f 2595 3959 3958 -f 2595 3958 2590 -f 2591 2592 2548 -f 2548 2592 2593 -f 2593 2592 2458 -f 2458 2594 2595 -f 2595 2594 2596 -f 2595 2596 2577 -f 2597 2357 2598 -f 2598 2357 2599 -f 4418 9611 9610 -f 4418 9610 4429 -f 4429 9610 2601 -f 4429 2601 2600 -f 2600 2601 2602 -f 2600 2602 4434 -f 4434 2602 2603 -f 4434 2603 4425 -f 4425 2603 2612 -f 4425 2612 2604 -f 2609 9523 2605 -f 2606 2881 2880 -f 4601 2605 2607 -f 2607 2605 4363 -f 2607 4363 4593 -f 3223 4601 2608 -f 2608 4601 4591 -f 2608 4591 2610 -f 3158 3159 2605 -f 2605 3159 3162 -f 2605 3162 2609 -f 9586 2610 2611 -f 2611 2610 4591 -f 2611 4591 2612 -f 2612 4591 4593 -f 2612 4593 2604 -f 2604 4593 4363 -f 3223 2606 4601 -f 4601 2606 2880 -f 4601 2880 2605 -f 2605 2880 3158 -f 2614 2920 3190 -f 3190 2920 2615 -f 3190 2615 2616 -f 2616 2615 2617 -f 2616 2617 2618 -f 2618 2617 2933 -f 2618 2933 3192 -f 3192 2933 2620 -f 3192 2620 2619 -f 2619 2620 2621 -f 2619 2621 3195 -f 3195 2621 2944 -f 3195 2944 2622 -f 2622 2944 2931 -f 2622 2931 3198 -f 3198 2931 2390 -f 2632 2401 2633 -f 3270 2632 2631 -f 2625 3272 2623 -f 2623 3272 3270 -f 2623 3270 2923 -f 2923 3270 2631 -f 3184 3268 2625 -f 2625 3268 2624 -f 2625 2624 3272 -f 2625 2626 3184 -f 3184 2626 2627 -f 3184 2627 3185 -f 2921 2630 2627 -f 2627 2630 3186 -f 2627 3186 3185 -f 2628 2920 2614 -f 2614 2629 2628 -f 2628 2629 3187 -f 2628 3187 2921 -f 2921 3187 3188 -f 2921 3188 2630 -f 2633 3775 2631 -f 2632 2633 2631 -f 3774 2635 2634 -f 2634 2635 2631 -f 2634 2631 3775 -f 2635 3774 3773 -f 2635 3773 3772 -f 2635 3772 2894 -f 2894 3772 3781 -f 2636 3785 2348 -f 2640 2637 2651 -f 2651 2637 2636 -f 2640 3784 2637 -f 2905 2638 2639 -f 2639 3783 2641 -f 2641 3783 2640 -f 2640 3783 3784 -f 2905 2639 2641 -f 2894 3781 2905 -f 2905 3781 3782 -f 2905 3782 2638 -f 2322 2653 2323 -f 2323 2653 2642 -f 2323 2642 2643 -f 2643 2642 2644 -f 2643 2644 2645 -f 2645 2644 2646 -f 2645 2646 2324 -f 2324 2646 2899 -f 2324 2899 2647 -f 2647 2899 2900 -f 2647 2900 2648 -f 2648 2900 2901 -f 2648 2901 2649 -f 2649 2901 2650 -f 2649 2650 2348 -f 2348 2650 2651 -f 2348 2651 2636 -f 2665 2666 2652 -f 2652 2666 2653 -f 2652 2653 2322 -f 2670 2668 2654 -f 2654 2668 2990 -f 2654 2990 2655 -f 2655 2990 2991 -f 2655 2991 2656 -f 2656 2991 2657 -f 2656 2657 2405 -f 2405 2657 2992 -f 2405 2992 2406 -f 2406 2992 2658 -f 2406 2658 2659 -f 2659 2658 2993 -f 2659 2993 2660 -f 2660 2993 2662 -f 2660 2662 2661 -f 2661 2662 2994 -f 2661 2994 2408 -f 2408 2994 2664 -f 2408 2664 2663 -f 2663 2664 2995 -f 2663 2995 2665 -f 2665 2995 2666 -f 2613 3641 2668 -f 3704 2670 3740 -f 3740 2670 2396 -f 3568 2667 2668 -f 2668 2667 2669 -f 2668 2669 2613 -f 3704 3706 2670 -f 2670 3706 3599 -f 2670 3599 2668 -f 2668 3599 2671 -f 2668 2671 3568 -f 3008 2998 2672 -f 2672 2673 3008 -f 3008 2673 2674 -f 3008 2674 2882 -f 2882 2674 2969 -f 2882 2969 2972 -f 2675 2676 2345 -f 2345 2676 2677 -f 2345 2677 2346 -f 2346 2677 2678 -f 2346 2678 2347 -f 2347 2678 2679 -f 2347 2679 2680 -f 2680 2679 2725 -f 2680 2725 2722 -f 2722 2725 2721 -f 2270 2681 2682 -f 2682 2681 2676 -f 2682 2676 2675 -f 2339 2731 2337 -f 2337 2731 2683 -f 2337 2683 2329 -f 2329 2683 2732 -f 2329 2732 2684 -f 2684 2732 2686 -f 2684 2686 2685 -f 2685 2686 2687 -f 2685 2687 2688 -f 2688 2687 2689 -f 2688 2689 2304 -f 2304 2689 2729 -f 2304 2729 2691 -f 2691 2729 2690 -f 2691 2690 2269 -f 2269 2690 2692 -f 2269 2692 2270 -f 2270 2692 2681 -f 2731 2339 2726 -f 2726 2339 2693 -f 2697 2723 2317 -f 2317 2723 2728 -f 2317 2728 2694 -f 2694 2728 2727 -f 2694 2727 2318 -f 2318 2727 2695 -f 2318 2695 2696 -f 2696 2695 2724 -f 2696 2724 2693 -f 2693 2724 2726 -f 2723 2697 2710 -f 2710 2697 2698 -f 2711 2699 2700 -f 2700 2699 2701 -f 2700 2701 2287 -f 2287 2701 2735 -f 2287 2735 2702 -f 2702 2735 2734 -f 2702 2734 2290 -f 2290 2734 2703 -f 2290 2703 2704 -f 2704 2703 2705 -f 2704 2705 2706 -f 2706 2705 2733 -f 2706 2733 2708 -f 2708 2733 2707 -f 2708 2707 2335 -f 2335 2707 2709 -f 2335 2709 2698 -f 2698 2709 2710 -f 2699 2711 2720 -f 2720 2711 2321 -f 2344 2739 2343 -f 2343 2739 2738 -f 2343 2738 2712 -f 2712 2738 2737 -f 2712 2737 2303 -f 2303 2737 2713 -f 2303 2713 2715 -f 2715 2713 2714 -f 2715 2714 2716 -f 2716 2714 2730 -f 2716 2730 2306 -f 2306 2730 2717 -f 2306 2717 2718 -f 2718 2717 2719 -f 2718 2719 2320 -f 2320 2719 2736 -f 2320 2736 2321 -f 2321 2736 2720 -f 2739 2344 2721 -f 2721 2344 2722 -f 2739 2721 2720 -f 2720 2723 2710 -f 2726 2724 2720 -f 2720 2724 2695 -f 2721 2725 2720 -f 2720 2725 2679 -f 2720 2679 2678 -f 2678 2677 2720 -f 2720 2677 2676 -f 2720 2676 2726 -f 2726 2676 2681 -f 2726 2681 2731 -f 2695 2727 2720 -f 2720 2727 2728 -f 2720 2728 2723 -f 2735 2701 2710 -f 2710 2701 2699 -f 2710 2699 2720 -f 2690 2729 2689 -f 2714 2736 2730 -f 2730 2736 2719 -f 2730 2719 2717 -f 2689 2687 2690 -f 2690 2687 2686 -f 2690 2686 2732 -f 2681 2692 2731 -f 2731 2692 2690 -f 2731 2690 2683 -f 2683 2690 2732 -f 2709 2707 2703 -f 2703 2707 2733 -f 2703 2733 2705 -f 2709 2703 2710 -f 2710 2703 2734 -f 2710 2734 2735 -f 2714 2713 2736 -f 2736 2713 2737 -f 2736 2737 2720 -f 2720 2737 2738 -f 2720 2738 2739 -f 2336 3153 2334 -f 2334 3153 3152 -f 2334 3152 2740 -f 2740 3152 3150 -f 2740 3150 2741 -f 2741 3150 3149 -f 2741 3149 2291 -f 2291 3149 2742 -f 2291 2742 2743 -f 2743 2742 2744 -f 2743 2744 2745 -f 2745 2744 2746 -f 2745 2746 2292 -f 2292 2746 2747 -f 2292 2747 2748 -f 2748 2747 3147 -f 2748 3147 2288 -f 2288 3147 3156 -f 3153 2336 3115 -f 3115 2336 2340 -f 2749 3017 2325 -f 2325 3017 3054 -f 2325 3054 2326 -f 2326 3054 2750 -f 2326 2750 2327 -f 2327 2750 3055 -f 2327 3055 2751 -f 2751 3055 2753 -f 2751 2753 2752 -f 2752 2753 2754 -f 2752 2754 2755 -f 2755 2754 3056 -f 2755 3056 2756 -f 2756 3056 2757 -f 2756 2757 2758 -f 2758 2757 3057 -f 2758 3057 2760 -f 2760 3057 2759 -f 2760 2759 2761 -f 2761 2759 2762 -f 2761 2762 2330 -f 2330 2762 2763 -f 2330 2763 2338 -f 2338 2763 2764 -f 2338 2764 2765 -f 2765 2764 3061 -f 2765 3061 2340 -f 2340 3061 3115 -f 3017 3790 3789 -f 2768 3777 2766 -f 3017 3789 2768 -f 2768 3789 2767 -f 2768 2767 3777 -f 2351 3790 3017 -f 2749 2351 3017 -f 2769 3065 2770 -f 2770 3065 3035 -f 2770 3035 3199 -f 3199 3035 3200 -f 3200 3035 2771 -f 3200 2771 3207 -f 3207 2771 3206 -f 3206 2771 2772 -f 3206 2772 3203 -f 3203 2772 2773 -f 3203 2773 3201 -f 3201 2773 2774 -f 2774 2773 2775 -f 2774 2775 2777 -f 2777 2775 2776 -f 2777 2776 3271 -f 3271 2776 3034 -f 3271 3034 3269 -f 3269 3034 3033 -f 3269 3033 2778 -f 2768 2766 3033 -f 2766 3779 3033 -f 3033 3779 2778 -f 2798 3063 2779 -f 2779 3063 2780 -f 2779 2780 2781 -f 2781 2780 2782 -f 2781 2782 2783 -f 2783 2782 2784 -f 2783 2784 2786 -f 2784 2785 2786 -f 2786 2785 3067 -f 2786 3067 2787 -f 2787 3067 2788 -f 2787 2788 3219 -f 3219 2788 3066 -f 3219 3066 3220 -f 3220 3066 3065 -f 3220 3065 2769 -f 3507 3506 2790 -f 2807 3393 2799 -f 2807 2799 3495 -f 3456 3463 3134 -f 3209 2789 3210 -f 3210 2789 3528 -f 3211 3210 3495 -f 3495 3210 3528 -f 2789 3209 3510 -f 3510 3209 3222 -f 2790 3506 3222 -f 3222 3506 3510 -f 2795 3504 2791 -f 2791 3504 2792 -f 2792 3504 2790 -f 2790 3504 3507 -f 2794 2793 2796 -f 2794 2796 2795 -f 2795 2796 3504 -f 3499 2289 3498 -f 2289 3499 2797 -f 2289 2797 2794 -f 2794 2797 2793 -f 3063 2798 3134 -f 3134 2798 3213 -f 3134 3213 3211 -f 3495 2799 3211 -f 3211 2799 3134 -f 3134 2799 2800 -f 3134 2800 3456 -f 3374 3453 3456 -f 3374 3456 2800 -f 2801 3378 2803 -f 3453 3374 2801 -f 3453 2801 3455 -f 3455 2801 2803 -f 2803 3378 2802 -f 2803 2802 3452 -f 3452 2802 3380 -f 3452 3380 3449 -f 3449 3380 3450 -f 3450 3380 2805 -f 3381 2804 3445 -f 3381 3445 3446 -f 3381 3446 2805 -f 2805 3446 3450 -f 2804 3381 3387 -f 3440 3442 3391 -f 3384 3389 2806 -f 3387 3386 2804 -f 2804 3386 2806 -f 2806 3386 3384 -f 2806 3389 3392 -f 3391 3442 2806 -f 3391 2806 3392 -f 2808 3511 3371 -f 3393 2807 2808 -f 3393 2808 2809 -f 2809 2808 3371 -f 3371 3511 3513 -f 3371 3513 3372 -f 3372 3513 3515 -f 3372 3515 3369 -f 3369 3515 2810 -f 2810 3515 3519 -f 3518 3361 3366 -f 3518 3366 3364 -f 3518 3364 3519 -f 3519 3364 2810 -f 3361 3518 2811 -f 3356 2814 3354 -f 2814 3356 3357 -f 3521 3525 2812 -f 2811 2813 3361 -f 3361 2813 2812 -f 2812 2813 3521 -f 2812 3525 3527 -f 2814 3357 2812 -f 2814 2812 3527 -f 3435 2815 3156 -f 3156 2815 3440 -f 3440 3391 3156 -f 3156 3391 3390 -f 3156 3390 2288 -f 3354 2814 3390 -f 3390 2814 2816 -f 3390 2816 2288 -f 2288 2816 3498 -f 2288 3498 2289 -f 3076 3084 3041 -f 3041 3084 2817 -f 3121 3136 2818 -f 2818 3136 3041 -f 2818 3041 3103 -f 3103 3041 2817 -f 3176 2819 2821 -f 3176 2821 2820 -f 2820 2821 2822 -f 2821 3754 2822 -f 2822 3754 2825 -f 2825 3754 2823 -f 2826 2827 2828 -f 2824 2825 3617 -f 3617 2825 2823 -f 3617 2823 3755 -f 2824 2826 2828 -f 2827 3686 3685 -f 2827 3685 2828 -f 2828 3685 3683 -f 3683 2839 2828 -f 2824 2828 2825 -f 2825 2828 3239 -f 2825 3239 2829 -f 2829 3239 2830 -f 2829 2830 2831 -f 2831 2830 3238 -f 2831 3238 3174 -f 3174 3238 3236 -f 3174 3236 2832 -f 2832 3236 3173 -f 3173 3236 2833 -f 3173 2833 3293 -f 3173 3293 3334 -f 3334 3293 3294 -f 3334 3294 2834 -f 2834 3294 3296 -f 2834 3296 2836 -f 2836 3296 3295 -f 3295 2835 2836 -f 2836 2835 3321 -f 2836 3321 2837 -f 2837 3321 3333 -f 3320 2409 3321 -f 3321 2409 3333 -f 3242 2838 3700 -f 3241 2838 3242 -f 2839 3683 3241 -f 3241 3683 2838 -f 3686 2827 2840 -f 2841 2842 2840 -f 2840 2842 3686 -f 2374 3691 2841 -f 2841 3691 2842 -f 3617 3755 2843 -f 3612 2843 3759 -f 2843 3612 3619 -f 2843 3619 3617 -f 3759 2375 3612 -f 2844 3557 3169 -f 3169 3557 2848 -f 2845 3553 2846 -f 2845 2846 3420 -f 2853 2847 2846 -f 2846 2847 3421 -f 2846 3421 3420 -f 3424 3485 3417 -f 3417 3485 3483 -f 3483 3488 2845 -f 3420 3418 2845 -f 2845 3418 3417 -f 2845 3417 3483 -f 2845 3488 2435 -f 2848 3553 3169 -f 3169 3553 2845 -f 3169 2845 3171 -f 3171 2845 3263 -f 3171 3263 2849 -f 3263 3262 2849 -f 2849 3262 2851 -f 2849 2851 3172 -f 3260 2511 2851 -f 2851 2511 2512 -f 2512 2850 2851 -f 2851 2850 2478 -f 2851 2478 3172 -f 3172 2478 2479 -f 3172 2479 2852 -f 3485 3424 3487 -f 3427 3487 3424 -f 2847 2853 3425 -f 3561 3425 2853 -f 3539 3541 3415 -f 3415 3541 2855 -f 2855 3541 3547 -f 3407 3413 2856 -f 2854 3476 3257 -f 3257 3476 3473 -f 3257 3473 3470 -f 3470 3409 2856 -f 2856 3409 3407 -f 2855 3547 3413 -f 3413 3547 3545 -f 3413 3545 2856 -f 2856 3545 3549 -f 3549 2857 2856 -f 3470 3469 3409 -f 3409 3469 3412 -f 3412 3469 3477 -f 3405 3477 3480 -f 3405 2858 3477 -f 3477 2858 3412 -f 3258 3476 2859 -f 2859 3476 2854 -f 3470 2856 3257 -f 3257 2856 3180 -f 3257 3180 2860 -f 2860 3180 3179 -f 2860 3179 2861 -f 2861 3179 2862 -f 2861 2862 2863 -f 2863 2862 3177 -f 2863 3177 2864 -f 2864 3177 3297 -f 3297 3177 3328 -f 3297 3328 2865 -f 3297 2865 3300 -f 3300 2865 3329 -f 3300 3329 2866 -f 2866 3329 3332 -f 2866 3332 2867 -f 2867 3332 3331 -f 3331 3330 2867 -f 2867 3330 2868 -f 2867 2868 3301 -f 3301 2868 3299 -f 2434 3298 2868 -f 2868 3298 3299 -f 2871 2869 2870 -f 3549 2869 2857 -f 2857 2869 2871 -f 2367 2370 3224 -f 3224 2370 3166 -f 3224 3166 3168 -f 3224 3168 3225 -f 3225 3168 2872 -f 3225 2872 3226 -f 2872 3164 3226 -f 3226 3164 2873 -f 3226 2873 3227 -f 3227 2873 2874 -f 3227 2874 3229 -f 3229 2874 2875 -f 3229 2875 3230 -f 3230 2875 3163 -f 3230 3163 2876 -f 2876 3163 3161 -f 2876 3161 2877 -f 2877 3161 3160 -f 2877 3160 3231 -f 3231 3160 2878 -f 3231 2878 3233 -f 3233 2878 2879 -f 3233 2879 3234 -f 3234 2879 3157 -f 3234 3157 3235 -f 3235 3157 2880 -f 3235 2880 2881 -f 2882 2972 2898 -f 2898 2972 2911 -f 2898 2911 2897 -f 2897 2911 2906 -f 2897 2906 2907 -f 2897 2907 2883 -f 2883 2907 2908 -f 2883 2908 2896 -f 2896 2908 2919 -f 2896 2919 2895 -f 2895 2919 2884 -f 2895 2884 2894 -f 2894 2884 2635 -f 2882 2898 2924 -f 2926 2924 2891 -f 2891 2924 2898 -f 2885 2926 2891 -f 2886 2885 2887 -f 2887 2885 2891 -f 2897 2891 2898 -f 2889 2886 2890 -f 2890 2886 2887 -f 2904 2891 2883 -f 2888 2889 2890 -f 2893 2890 2887 -f 2893 2887 2902 -f 2902 2887 2904 -f 2896 2904 2883 -f 2883 2891 2897 -f 2928 2888 2892 -f 2892 2888 2890 -f 2892 2890 2893 -f 2929 2928 2892 -f 2653 2929 2642 -f 2642 2929 2892 -f 2642 2892 2644 -f 2644 2892 2646 -f 2646 2892 2899 -f 2899 2892 2893 -f 2899 2893 2900 -f 2900 2893 2901 -f 2901 2893 2902 -f 2901 2902 2650 -f 2650 2902 2651 -f 2651 2902 2903 -f 2651 2903 2640 -f 2640 2903 2641 -f 2905 2641 2895 -f 2895 2641 2903 -f 2904 2903 2902 -f 2891 2904 2887 -f 2894 2905 2895 -f 2896 2895 2903 -f 2896 2903 2904 -f 2913 2906 2911 -f 2907 2906 2913 -f 2909 2907 2913 -f 2908 2907 2909 -f 2908 2909 2915 -f 2915 2909 2912 -f 2914 2913 2911 -f 2884 2919 2908 -f 2884 2908 2915 -f 2922 2915 2918 -f 2918 2915 2912 -f 2918 2912 2970 -f 2916 2970 2912 -f 2910 2912 2909 -f 2910 2909 2913 -f 2970 2917 2918 -f 2915 2922 2884 -f 2917 2920 2628 -f 2917 2628 2918 -f 2918 2628 2921 -f 2918 2921 2627 -f 2918 2627 2922 -f 2922 2627 2626 -f 2922 2626 2625 -f 2922 2625 2623 -f 2922 2623 2884 -f 2884 2623 2923 -f 2884 2923 2631 -f 2884 2631 2635 -f 3008 2882 2989 -f 2989 2882 2924 -f 2989 2924 2925 -f 2925 2924 2926 -f 2925 2926 2987 -f 2987 2926 2885 -f 2987 2885 2986 -f 2986 2885 2886 -f 2986 2886 2927 -f 2927 2886 2889 -f 2927 2889 2984 -f 2984 2889 2888 -f 2984 2888 2983 -f 2983 2888 2928 -f 2983 2928 2981 -f 2981 2928 2929 -f 2981 2929 2666 -f 2666 2929 2653 -f 2615 2920 2917 -f 2617 2615 2932 -f 2620 2933 2953 -f 2944 2621 2945 -f 2390 2931 2930 -f 2930 2931 2944 -f 2620 2953 2621 -f 2617 2932 2933 -f 2390 2930 3006 -f 3006 2930 2946 -f 3006 2946 3005 -f 3005 2946 2934 -f 3005 2934 3004 -f 3004 2934 2950 -f 3004 2950 2935 -f 2935 2950 2936 -f 2935 2936 2938 -f 2938 2936 2937 -f 2938 2937 2939 -f 2939 2937 2940 -f 2939 2940 2941 -f 2941 2940 2942 -f 2941 2942 2943 -f 2943 2942 2672 -f 2943 2672 2998 -f 2944 2945 2930 -f 2930 2945 2947 -f 2930 2947 2946 -f 2946 2947 2948 -f 2946 2948 2934 -f 2934 2948 2949 -f 2934 2949 2950 -f 2950 2949 2957 -f 2950 2957 2936 -f 2936 2957 2951 -f 2936 2951 2937 -f 2937 2951 2958 -f 2937 2958 2940 -f 2940 2958 2952 -f 2940 2952 2942 -f 2942 2952 2673 -f 2942 2673 2672 -f 2621 2953 2945 -f 2945 2953 2960 -f 2945 2960 2947 -f 2947 2960 2954 -f 2947 2954 2948 -f 2948 2954 2955 -f 2948 2955 2949 -f 2949 2955 2956 -f 2949 2956 2957 -f 2957 2956 2965 -f 2957 2965 2951 -f 2951 2965 2966 -f 2951 2966 2958 -f 2958 2966 2968 -f 2958 2968 2952 -f 2952 2968 2674 -f 2952 2674 2673 -f 2933 2932 2953 -f 2953 2932 2959 -f 2953 2959 2960 -f 2960 2959 2961 -f 2960 2961 2954 -f 2954 2961 2962 -f 2954 2962 2955 -f 2955 2962 2971 -f 2955 2971 2956 -f 2956 2971 2963 -f 2956 2963 2965 -f 2965 2963 2964 -f 2965 2964 2966 -f 2966 2964 2967 -f 2966 2967 2968 -f 2968 2967 2969 -f 2968 2969 2674 -f 2615 2917 2932 -f 2932 2917 2970 -f 2932 2970 2959 -f 2959 2970 2916 -f 2959 2916 2961 -f 2961 2916 2912 -f 2961 2912 2962 -f 2962 2912 2910 -f 2962 2910 2971 -f 2971 2910 2913 -f 2971 2913 2963 -f 2963 2913 2914 -f 2963 2914 2964 -f 2964 2914 2911 -f 2964 2911 2967 -f 2967 2911 2972 -f 2967 2972 2969 -f 3010 2973 2996 -f 2974 3010 2996 -f 2975 2996 2988 -f 2985 2975 2988 -f 2988 2996 2973 -f 3012 2974 2976 -f 2976 2974 2996 -f 2976 2996 2977 -f 2977 2996 2975 -f 2979 3012 2976 -f 2980 2977 2975 -f 2978 2979 2976 -f 2978 2976 2977 -f 2666 2982 2981 -f 2981 2982 2983 -f 2983 2982 2985 -f 2983 2985 2984 -f 2984 2985 2927 -f 2927 2985 2988 -f 2927 2988 2986 -f 2986 2988 2987 -f 2987 2988 2925 -f 2925 2988 2973 -f 2925 2973 2989 -f 2989 2973 3008 -f 2668 2978 2990 -f 2990 2978 2991 -f 2991 2978 2657 -f 2657 2978 2977 -f 2657 2977 2992 -f 2992 2977 2658 -f 2658 2977 2993 -f 2993 2977 2980 -f 2993 2980 2662 -f 2662 2980 2994 -f 2994 2980 2664 -f 2664 2980 2982 -f 2664 2982 2995 -f 2666 2995 2982 -f 2982 2980 2985 -f 2985 2980 2975 -f 3650 3651 3011 -f 3655 3653 3000 -f 3668 3005 3637 -f 2997 3005 3653 -f 3655 3000 2999 -f 3651 2999 3000 -f 3005 3000 3653 -f 3011 3651 3000 -f 3646 3650 3011 -f 3011 3000 3002 -f 3648 3646 3001 -f 3001 3646 3011 -f 3009 3002 2943 -f 2943 3002 2939 -f 2939 3002 2938 -f 2938 3002 3000 -f 2938 3000 2935 -f 3005 2997 3637 -f 2941 2943 2939 -f 3006 3003 2390 -f 2935 3000 3004 -f 3004 3000 3005 -f 3006 3005 3668 -f 3006 3668 3003 -f 3007 3011 3002 -f 3007 3002 3009 -f 2998 3008 2943 -f 2943 3008 2973 -f 2943 2973 3009 -f 3009 2973 3010 -f 3009 3010 3007 -f 3007 3010 2974 -f 3007 2974 3011 -f 3011 2974 3012 -f 3011 3012 3001 -f 3001 3012 2979 -f 3001 2979 3648 -f 3648 2979 2978 -f 3648 2978 3641 -f 3641 2978 2668 -f 3076 3041 3027 -f 3027 3041 3037 -f 3027 3037 3026 -f 3026 3037 3039 -f 3026 3039 3025 -f 3025 3039 3038 -f 3025 3038 3024 -f 3024 3038 3042 -f 3024 3042 3022 -f 3022 3042 3013 -f 3022 3013 3021 -f 3021 3013 3046 -f 3021 3046 3030 -f 3030 3046 3014 -f 3030 3014 3015 -f 3015 3014 3016 -f 3015 3016 2768 -f 2768 3016 3017 -f 3029 3074 3027 -f 3072 3074 3029 -f 3018 3072 3029 -f 3019 3018 3029 -f 3019 3029 3023 -f 3029 3027 3026 -f 3070 3019 3020 -f 3020 3019 3023 -f 3030 3023 3021 -f 3021 3023 3022 -f 3022 3023 3029 -f 3022 3029 3024 -f 3024 3029 3025 -f 3025 3029 3026 -f 3028 3070 3020 -f 3020 3023 3032 -f 3032 3023 3031 -f 3030 3031 3023 -f 3030 3015 3031 -f 3028 3020 3036 -f 3015 2768 3031 -f 3031 2768 3033 -f 3031 3033 3034 -f 3031 3034 3032 -f 3032 3034 2776 -f 3032 2776 2775 -f 3032 2775 3020 -f 3020 2775 2773 -f 3020 2773 2772 -f 3020 2772 2771 -f 3020 2771 3036 -f 3036 2771 3035 -f 3036 3035 3065 -f 3040 3037 3049 -f 3038 3039 3060 -f 3060 3039 3037 -f 3042 3038 3060 -f 3062 3040 3045 -f 3045 3040 3049 -f 3013 3042 3043 -f 3043 3042 3060 -f 3046 3013 3043 -f 3047 3043 3060 -f 3047 3060 3044 -f 3058 3062 3048 -f 3048 3062 3045 -f 3014 3046 3050 -f 3050 3046 3043 -f 3050 3043 3047 -f 3047 3044 3059 -f 3016 3014 3050 -f 3115 3048 3051 -f 3051 3048 3113 -f 3113 3048 3052 -f 3052 3048 3045 -f 3052 3045 3110 -f 3110 3045 3109 -f 3109 3045 3049 -f 3109 3049 3108 -f 3108 3049 3053 -f 3053 3049 3037 -f 3053 3037 3106 -f 3106 3037 3041 -f 3017 3016 3054 -f 3054 3016 3050 -f 3054 3050 2750 -f 2750 3050 3055 -f 3055 3050 2753 -f 2753 3050 3047 -f 2753 3047 2754 -f 2754 3047 3056 -f 3056 3047 2757 -f 2757 3047 3059 -f 2757 3059 3057 -f 3057 3059 2759 -f 2759 3059 3058 -f 2759 3058 2762 -f 2763 2762 3058 -f 3058 3059 3044 -f 3040 3044 3060 -f 3040 3060 3037 -f 2764 2763 3058 -f 3062 3058 3044 -f 3061 2764 3048 -f 3048 2764 3058 -f 3062 3044 3040 -f 3115 3061 3048 -f 2780 3063 3130 -f 2782 2780 3094 -f 2785 2784 3064 -f 3065 3066 3077 -f 3077 3066 2788 -f 2788 3067 3085 -f 3085 3067 2785 -f 2782 3094 2784 -f 3065 3077 3036 -f 3036 3077 3078 -f 3036 3078 3028 -f 3028 3078 3068 -f 3028 3068 3070 -f 3070 3068 3069 -f 3070 3069 3019 -f 3019 3069 3071 -f 3019 3071 3018 -f 3018 3071 3081 -f 3018 3081 3072 -f 3072 3081 3073 -f 3072 3073 3074 -f 3074 3073 3075 -f 3074 3075 3027 -f 3027 3075 3084 -f 3027 3084 3076 -f 2788 3085 3077 -f 3077 3085 3086 -f 3077 3086 3078 -f 3078 3086 3079 -f 3078 3079 3068 -f 3068 3079 3080 -f 3068 3080 3069 -f 3069 3080 3089 -f 3069 3089 3071 -f 3071 3089 3091 -f 3071 3091 3081 -f 3081 3091 3082 -f 3081 3082 3073 -f 3073 3082 3083 -f 3073 3083 3075 -f 3075 3083 2817 -f 3075 2817 3084 -f 2785 3064 3085 -f 3085 3064 3087 -f 3085 3087 3086 -f 3086 3087 3098 -f 3086 3098 3079 -f 3079 3098 3099 -f 3079 3099 3080 -f 3080 3099 3088 -f 3080 3088 3089 -f 3089 3088 3090 -f 3089 3090 3091 -f 3091 3090 3092 -f 3091 3092 3082 -f 3082 3092 3093 -f 3082 3093 3083 -f 3083 3093 3103 -f 3083 3103 2817 -f 2784 3094 3064 -f 3064 3094 3095 -f 3064 3095 3087 -f 3087 3095 3096 -f 3087 3096 3098 -f 3098 3096 3097 -f 3098 3097 3099 -f 3099 3097 3100 -f 3099 3100 3088 -f 3088 3100 3104 -f 3088 3104 3090 -f 3090 3104 3101 -f 3090 3101 3092 -f 3092 3101 3102 -f 3092 3102 3093 -f 3093 3102 2818 -f 3093 2818 3103 -f 2780 3130 3094 -f 3094 3130 3129 -f 3094 3129 3095 -f 3095 3129 3135 -f 3095 3135 3096 -f 3096 3135 3133 -f 3096 3133 3097 -f 3097 3133 3132 -f 3097 3132 3100 -f 3100 3132 3128 -f 3100 3128 3104 -f 3104 3128 3105 -f 3104 3105 3101 -f 3101 3105 3121 -f 3101 3121 3102 -f 3102 3121 2818 -f 3041 3136 3106 -f 3106 3136 3107 -f 3106 3107 3053 -f 3053 3107 3138 -f 3053 3138 3108 -f 3108 3138 3137 -f 3108 3137 3109 -f 3109 3137 3140 -f 3109 3140 3110 -f 3110 3140 3111 -f 3110 3111 3052 -f 3052 3111 3112 -f 3052 3112 3113 -f 3113 3112 3114 -f 3113 3114 3051 -f 3051 3114 3151 -f 3051 3151 3115 -f 3115 3151 3153 -f 3123 3433 3120 -f 3155 3117 3118 -f 3118 3435 3155 -f 3120 3433 3117 -f 3125 3127 3431 -f 3125 3116 3127 -f 3130 3463 3131 -f 3119 3120 3143 -f 3143 3120 3155 -f 3155 3120 3117 -f 3154 3105 3122 -f 3154 3122 3119 -f 3119 3122 3124 -f 3119 3124 3120 -f 3120 3124 3432 -f 3120 3432 3123 -f 3124 3126 3432 -f 3122 3132 3125 -f 3122 3125 3124 -f 3124 3125 3431 -f 3124 3431 3126 -f 3154 3121 3105 -f 3105 3128 3122 -f 3122 3128 3132 -f 3125 3129 3130 -f 3125 3130 3131 -f 3125 3131 3116 -f 3132 3133 3125 -f 3125 3133 3135 -f 3125 3135 3129 -f 3130 3134 3463 -f 3130 3063 3134 -f 3136 3154 3107 -f 3138 3107 3139 -f 3139 3107 3154 -f 3137 3138 3139 -f 3140 3137 3142 -f 3142 3137 3139 -f 3142 3139 3141 -f 3141 3139 3154 -f 3111 3140 3142 -f 3112 3111 3144 -f 3144 3111 3142 -f 3144 3142 3145 -f 3145 3142 3141 -f 3145 3141 3148 -f 3119 3143 3141 -f 3119 3141 3154 -f 3114 3112 3144 -f 3143 3155 3148 -f 3143 3148 3141 -f 3145 3146 3144 -f 3144 3146 3114 -f 3114 3146 3151 -f 3155 3156 3147 -f 3155 3147 3148 -f 3148 3147 2747 -f 3148 2747 2746 -f 3148 2746 3145 -f 3145 2746 2744 -f 3145 2744 2742 -f 3145 2742 3146 -f 3146 2742 3149 -f 3146 3149 3150 -f 3146 3150 3152 -f 3146 3152 3151 -f 3151 3152 3153 -f 3136 3121 3154 -f 3156 3155 3435 -f 2880 3157 2879 -f 2880 2879 3158 -f 3158 2879 2878 -f 3158 2878 3159 -f 2878 3160 3159 -f 3159 3160 3161 -f 3159 3161 3162 -f 3161 3163 3162 -f 3162 3163 2875 -f 3162 2875 2609 -f 2609 2875 2874 -f 2609 2874 2873 -f 2873 3164 2609 -f 2609 3164 2404 -f 2609 2404 9523 -f 2370 3165 3166 -f 3166 3165 3167 -f 3166 3167 3168 -f 3168 3167 2404 -f 3168 2404 2872 -f 2872 2404 3164 -f 2819 2407 2370 -f 2370 2407 3165 -f 3170 3560 2844 -f 2844 3169 3170 -f 3170 3169 3171 -f 3170 3171 2849 -f 2849 3172 3170 -f 3170 3172 2852 -f 3170 2852 2447 -f 3351 3325 3173 -f 2825 2829 3326 -f 3326 2829 2831 -f 3174 3326 2831 -f 3173 3325 3327 -f 3173 3327 2832 -f 2832 3327 3174 -f 3174 3327 3326 -f 3326 3175 2825 -f 2825 3175 2822 -f 2822 3175 2820 -f 2820 3175 3176 -f 3176 3175 2407 -f 3176 2407 2819 -f 3178 3328 3177 -f 3177 3264 3178 -f 3178 3264 3266 -f 3264 3177 2862 -f 3264 2862 3265 -f 3265 2862 3179 -f 3265 3179 3180 -f 3265 3180 2856 -f 3265 2856 2277 -f 2277 2856 2857 -f 2277 2857 2871 -f 2277 2871 3181 -f 3181 2871 2870 -f 3181 2870 3560 -f 3181 3560 3170 -f 3197 2389 3183 -f 3183 2389 2377 -f 3183 2377 2376 -f 2376 3182 3183 -f 2393 3324 3182 -f 3204 3202 3268 -f 3268 3184 3204 -f 3204 3184 3185 -f 3204 3185 3189 -f 3189 3185 3186 -f 3189 3186 2630 -f 2629 3346 3187 -f 3187 3346 3189 -f 3187 3189 3188 -f 3188 3189 2630 -f 2629 2614 3346 -f 3346 2614 3190 -f 3346 3190 3347 -f 3347 3190 2616 -f 3347 2616 3191 -f 3191 2616 2618 -f 3191 2618 3349 -f 3349 2618 3192 -f 3349 3192 3193 -f 3193 3192 2619 -f 3193 2619 3194 -f 3194 2619 3195 -f 3194 3195 3196 -f 3196 3195 2622 -f 3196 2622 3197 -f 3197 2622 3198 -f 3197 3198 2389 -f 2769 2770 3341 -f 3341 2770 3205 -f 2770 3199 3205 -f 3205 3199 3200 -f 3205 3200 3207 -f 2774 3202 3201 -f 3201 3202 3204 -f 3201 3204 3203 -f 3203 3204 3205 -f 3203 3205 3206 -f 3206 3205 3207 -f 3209 3210 3208 -f 3208 3222 3209 -f 3208 3210 3211 -f 3208 3211 3212 -f 3211 3213 3212 -f 3212 3213 2798 -f 3212 2798 3337 -f 3337 2798 2779 -f 3337 2779 3214 -f 3214 2779 2781 -f 3214 2781 3215 -f 3215 2781 2783 -f 3215 2783 3216 -f 3216 2783 2786 -f 3216 2786 3217 -f 3217 2786 2787 -f 3217 2787 3218 -f 3218 2787 3219 -f 3218 3219 3341 -f 3341 3219 3220 -f 3341 3220 2769 -f 3183 3182 3324 -f 3183 3324 3221 -f 3221 3324 3323 -f 3221 3323 3351 -f 3351 3323 3325 -f 3178 3266 3335 -f 3335 3266 3267 -f 3335 3267 3208 -f 3208 3267 3222 -f 9586 9545 2610 -f 2610 9545 9577 -f 2610 9577 2608 -f 2608 9577 3223 -f 3223 9577 9576 -f 3223 9576 9575 -f 9571 2881 9575 -f 9575 2881 2606 -f 9575 2606 3223 -f 9560 9558 2367 -f 2367 3224 9560 -f 9560 3224 9561 -f 3224 3225 9561 -f 9561 3225 3226 -f 9561 3226 3228 -f 3226 3227 3228 -f 3228 3227 3229 -f 3228 3229 9525 -f 3229 3230 9525 -f 9525 3230 2876 -f 9525 2876 9566 -f 2876 2877 9566 -f 9566 2877 3231 -f 9566 3231 3232 -f 3231 3233 3232 -f 3232 3233 3234 -f 3232 3234 9571 -f 9571 3234 3235 -f 9571 3235 2881 -f 9555 3700 9559 -f 9559 3700 2367 -f 9559 2367 9558 -f 3319 2833 3236 -f 3236 3275 3319 -f 3319 3275 3237 -f 3275 3236 3238 -f 3275 3238 3274 -f 3274 3238 2830 -f 3274 2830 3239 -f 3274 3239 2828 -f 3274 2828 3240 -f 3240 2828 2839 -f 3240 2839 3241 -f 3240 3241 9555 -f 9555 3241 3242 -f 9555 3242 3700 -f 3319 3237 3243 -f 3243 3237 3244 -f 3243 3244 3246 -f 3246 3244 3245 -f 3246 3245 3317 -f 3317 3245 3291 -f 3317 3291 3315 -f 3315 3291 3290 -f 3315 3290 3313 -f 3313 3290 3247 -f 3313 3247 3310 -f 3310 3247 3287 -f 3310 3287 3285 -f 3310 3285 3248 -f 3248 3285 3249 -f 3248 3249 3306 -f 3306 3249 3284 -f 3306 3284 3250 -f 3250 3284 3251 -f 3250 3251 3252 -f 3252 3251 3281 -f 3252 3281 3280 -f 3252 3280 3253 -f 3253 3280 3279 -f 3253 3279 3254 -f 3254 3279 3278 -f 3254 3278 3255 -f 3255 3278 3256 -f 3255 3256 3297 -f 3257 2860 3276 -f 3276 2860 2861 -f 2863 3276 2861 -f 3297 3256 2864 -f 2864 3256 3276 -f 2864 3276 2863 -f 2854 9547 2859 -f 2859 9547 3258 -f 3258 9547 3261 -f 3258 3261 2436 -f 3276 9547 3257 -f 3257 9547 2854 -f 3261 3259 3260 -f 3260 2851 3261 -f 3261 2851 3262 -f 3261 3262 3263 -f 3263 2845 3261 -f 3261 2845 2435 -f 3261 2435 2436 -f 3264 3265 2268 -f 2791 3267 2268 -f 2268 3267 3266 -f 2268 3266 3264 -f 2791 2792 3267 -f 3267 2792 2790 -f 3267 2790 3222 -f 2624 3268 3202 -f 3271 3202 2777 -f 2777 3202 2774 -f 3269 2632 3270 -f 3269 3270 3271 -f 3271 3270 3202 -f 3202 3270 3272 -f 3202 3272 2624 -f 3275 3274 3273 -f 3273 3244 3237 -f 3273 3237 3275 -f 3277 3276 3256 -f 3277 3256 9540 -f 3256 3278 9540 -f 9540 3278 9539 -f 3278 3279 9539 -f 9539 3279 9542 -f 9542 3279 3280 -f 9542 3280 3281 -f 9542 3281 3282 -f 3281 3251 3282 -f 3282 3251 3283 -f 3251 3284 3283 -f 3283 3284 9544 -f 9544 3284 3249 -f 9544 3249 9550 -f 9550 3249 3285 -f 9550 3285 9549 -f 9549 3285 3286 -f 3286 3285 3287 -f 3286 3287 3288 -f 3288 3287 3247 -f 3288 3247 3289 -f 3289 3247 3290 -f 3289 3290 3292 -f 3290 3291 3292 -f 3292 3291 9562 -f 3291 3245 9562 -f 9562 3245 3273 -f 3273 3245 3244 -f 2833 3319 3293 -f 3293 3319 3294 -f 2835 3295 3319 -f 3319 3295 3296 -f 3294 3319 3296 -f 3301 3299 3255 -f 3255 3299 3298 -f 3255 3297 3300 -f 3255 3300 2866 -f 3255 2866 2867 -f 3255 2867 3301 -f 3255 3298 3254 -f 3254 3298 3302 -f 3254 3302 3303 -f 3254 3303 3253 -f 3253 3303 3304 -f 3253 3304 2431 -f 3253 2431 3252 -f 3252 2431 2429 -f 3252 2429 3305 -f 3252 3305 3250 -f 3250 3305 2427 -f 3250 2427 2426 -f 3250 2426 3306 -f 3306 2426 3307 -f 3306 3307 3308 -f 3306 3308 3248 -f 3248 3308 3309 -f 3248 3309 2423 -f 3248 2423 3310 -f 3310 2423 3311 -f 3310 3311 3312 -f 3310 3312 3313 -f 3313 3312 3314 -f 3313 3314 2421 -f 3313 2421 3315 -f 3315 2421 2420 -f 3315 2420 3317 -f 3317 2420 3316 -f 3317 3316 3318 -f 3317 3318 3246 -f 3246 3318 2417 -f 3246 2417 2415 -f 3246 2415 3243 -f 3243 2415 2412 -f 3243 2412 2411 -f 3243 2411 3319 -f 3319 2411 3320 -f 3319 3320 3321 -f 3319 3321 2835 -f 2394 3323 3322 -f 3322 3323 3324 -f 3322 3324 2393 -f 3326 3327 3325 -f 3326 3325 3323 -f 3326 3323 2403 -f 2403 3323 2394 -f 2403 2394 2395 -f 3328 3178 2865 -f 2865 3178 3329 -f 3330 3331 3178 -f 3330 3178 2868 -f 3178 3331 3332 -f 3329 3178 3332 -f 2837 3333 3351 -f 3351 3333 2409 -f 3351 3173 3334 -f 3351 3334 2834 -f 3351 2834 2836 -f 3351 2836 2837 -f 2868 3178 2434 -f 2434 3178 2433 -f 2433 3178 3335 -f 2433 3335 2432 -f 2432 3335 3208 -f 2432 3208 3336 -f 3336 3208 3212 -f 3336 3212 2430 -f 2430 3212 3337 -f 2430 3337 2428 -f 2428 3337 3214 -f 2428 3214 3338 -f 3338 3214 3215 -f 3338 3215 2425 -f 2425 3215 3216 -f 2425 3216 3339 -f 3339 3216 3217 -f 3339 3217 2424 -f 2424 3217 3218 -f 2424 3218 3340 -f 3340 3218 3341 -f 3340 3341 3342 -f 3342 3341 3205 -f 3342 3205 3343 -f 3343 3205 3204 -f 3343 3204 3344 -f 3344 3204 3189 -f 3344 3189 3345 -f 3345 3189 3346 -f 3345 3346 2422 -f 2422 3346 3347 -f 2422 3347 3348 -f 3348 3347 3191 -f 3348 3191 2419 -f 2419 3191 3349 -f 2419 3349 2418 -f 2418 3349 3193 -f 2418 3193 3350 -f 3350 3193 3194 -f 3350 3194 2416 -f 2416 3194 3196 -f 2416 3196 2414 -f 2414 3196 3197 -f 2414 3197 2413 -f 2413 3197 3183 -f 2413 3183 2410 -f 2410 3183 3221 -f 2410 3221 2409 -f 2409 3221 3351 -f 2799 3396 3398 -f 2799 3398 3397 -f 2799 3397 2800 -f 2800 3397 3352 -f 2800 3352 3403 -f 2800 3403 3402 -f 3419 3353 3390 -f 3390 3353 3354 -f 3354 3353 3355 -f 3354 3355 3356 -f 3356 3355 3422 -f 3356 3422 3358 -f 3356 3358 3357 -f 3357 3358 3359 -f 3357 3359 2812 -f 3360 3361 3362 -f 3362 3361 3359 -f 3359 3361 2812 -f 3365 3366 3360 -f 3360 3366 3361 -f 3363 2810 3364 -f 3363 3364 3365 -f 3365 3364 3366 -f 3416 3369 3367 -f 3367 3369 2810 -f 3367 2810 3363 -f 3414 3372 3368 -f 3368 3372 3416 -f 3416 3372 3369 -f 3370 3371 3414 -f 3414 3371 3372 -f 3394 3393 3373 -f 3373 3393 3370 -f 3370 3393 2809 -f 3370 2809 3371 -f 3374 3411 2801 -f 2801 3411 3375 -f 2801 3375 3378 -f 3375 3376 3378 -f 3378 3376 3377 -f 3378 3377 2802 -f 3406 3380 3377 -f 3377 3380 2802 -f 3379 2805 3404 -f 2805 3380 3404 -f 3404 3380 3406 -f 3382 3426 3387 -f 3387 3381 3382 -f 3382 3381 2805 -f 3382 2805 3379 -f 3385 3383 3384 -f 3384 3386 3385 -f 3385 3386 3426 -f 3426 3386 3387 -f 3423 3388 3392 -f 3392 3389 3423 -f 3423 3389 3383 -f 3383 3389 3384 -f 3390 3391 3419 -f 3419 3391 3388 -f 3388 3391 3392 -f 2799 3393 3394 -f 2799 3394 3396 -f 3396 3394 3395 -f 3399 3398 3395 -f 3395 3398 3396 -f 3408 3397 3399 -f 3399 3397 3398 -f 3400 3352 3408 -f 3408 3352 3397 -f 3410 3403 3400 -f 3400 3403 3352 -f 3411 3374 2800 -f 3411 2800 3401 -f 3401 2800 3402 -f 3401 3402 3410 -f 3410 3402 3403 -f 3404 3405 3379 -f 3377 3405 3406 -f 3406 3405 3404 -f 3375 2858 3376 -f 3376 2858 3377 -f 3377 2858 3405 -f 3373 3407 3394 -f 3394 3407 3395 -f 3395 3407 3399 -f 3399 3407 3409 -f 3399 3409 3408 -f 3408 3409 3400 -f 3400 3409 3412 -f 3400 3412 3410 -f 3410 3412 3401 -f 3401 3412 3411 -f 3411 3412 3375 -f 3375 3412 2858 -f 3414 2855 3370 -f 3370 2855 3373 -f 3373 2855 3413 -f 3373 3413 3407 -f 3368 3415 3414 -f 3414 3415 2855 -f 3416 3415 3368 -f 3367 3415 3416 -f 3415 3367 3363 -f 3425 3362 3359 -f 3423 3417 3388 -f 3388 3417 3418 -f 3388 3418 3419 -f 3419 3418 3420 -f 3419 3420 3353 -f 3353 3420 3421 -f 3353 3421 3355 -f 3355 3421 2847 -f 3355 2847 3422 -f 3422 2847 3358 -f 3358 2847 3359 -f 3359 2847 3425 -f 3383 3424 3423 -f 3423 3424 3417 -f 3385 3424 3383 -f 3426 3427 3385 -f 3385 3427 3424 -f 3362 3425 3360 -f 3360 3425 2400 -f 3360 2400 3365 -f 3365 2400 3363 -f 3363 2400 3415 -f 3379 3405 3427 -f 3379 3427 3382 -f 3382 3427 3426 -f 3456 3458 3459 -f 3456 3459 3463 -f 3459 3461 3463 -f 3463 3461 3428 -f 3463 3428 3429 -f 3475 3467 3116 -f 3116 3467 3430 -f 3116 3430 3127 -f 3468 3126 3431 -f 3468 3431 3430 -f 3430 3431 3127 -f 3468 3465 3126 -f 3126 3465 3466 -f 3126 3466 3432 -f 3432 3466 3493 -f 3432 3493 3123 -f 3123 3493 3494 -f 3123 3494 3433 -f 3490 3433 3494 -f 3434 3117 3490 -f 3490 3117 3433 -f 3489 3437 3118 -f 3489 3118 3434 -f 3434 3118 3117 -f 3438 2815 3436 -f 2815 3435 3436 -f 3436 3435 3437 -f 3437 3435 3118 -f 2815 3438 3439 -f 2815 3439 3440 -f 3440 3439 3484 -f 3440 3484 3441 -f 3440 3441 3442 -f 3442 3441 3443 -f 3442 3443 3486 -f 3442 3486 2806 -f 3444 2804 3482 -f 3482 2804 3486 -f 3486 2804 2806 -f 3447 3445 3444 -f 3444 3445 2804 -f 3492 3450 3446 -f 3492 3446 3447 -f 3447 3446 3445 -f 3448 3449 3481 -f 3481 3449 3450 -f 3481 3450 3492 -f 3451 3452 3479 -f 3479 3452 3448 -f 3448 3452 3449 -f 3454 2803 3451 -f 3451 2803 3452 -f 3457 3453 3478 -f 3478 3453 3454 -f 3454 3453 3455 -f 3454 3455 2803 -f 3456 3453 3457 -f 3456 3457 3458 -f 3458 3457 3471 -f 3472 3459 3471 -f 3471 3459 3458 -f 3460 3461 3472 -f 3472 3461 3459 -f 3462 3428 3460 -f 3460 3428 3461 -f 3464 3429 3462 -f 3462 3429 3428 -f 3116 3131 3475 -f 3475 3131 3463 -f 3475 3463 3474 -f 3474 3463 3464 -f 3464 3463 3429 -f 3258 2436 3466 -f 3466 2436 3493 -f 3468 3258 3465 -f 3465 3258 3466 -f 3467 3476 3430 -f 3430 3476 3468 -f 3468 3476 3258 -f 3478 3469 3457 -f 3457 3469 3470 -f 3457 3470 3471 -f 3471 3470 3472 -f 3472 3470 3460 -f 3460 3470 3473 -f 3460 3473 3462 -f 3462 3473 3464 -f 3464 3473 3474 -f 3474 3473 3476 -f 3474 3476 3475 -f 3475 3476 3467 -f 3451 3477 3454 -f 3454 3477 3478 -f 3478 3477 3469 -f 3479 3477 3451 -f 3448 3477 3479 -f 3481 3480 3448 -f 3448 3480 3477 -f 3480 3481 3492 -f 3487 3482 3486 -f 3437 3488 3436 -f 3436 3488 3438 -f 3438 3488 3483 -f 3438 3483 3439 -f 3439 3483 3484 -f 3484 3483 3485 -f 3484 3485 3441 -f 3441 3485 3443 -f 3443 3485 3486 -f 3486 3485 3487 -f 3489 3488 3437 -f 3434 3488 3489 -f 3490 2435 3434 -f 3434 2435 3488 -f 3482 3487 3444 -f 3444 3487 3491 -f 3444 3491 3447 -f 3447 3491 3492 -f 3492 3491 3480 -f 3493 2436 3494 -f 3494 2436 2435 -f 3494 2435 3490 -f 3528 3529 3532 -f 3528 3532 3495 -f 3495 3532 3531 -f 3495 3531 3534 -f 3495 3534 3496 -f 3495 3496 3538 -f 3554 3497 2816 -f 2816 3497 3498 -f 3498 3497 3555 -f 3498 3555 3499 -f 3499 3555 3556 -f 3499 3556 3500 -f 3499 3500 2797 -f 2797 3500 3502 -f 3558 2793 3501 -f 3501 2793 3502 -f 3502 2793 2797 -f 3559 2796 3558 -f 3558 2796 2793 -f 3552 3504 2796 -f 3552 2796 3559 -f 3505 3507 3503 -f 3503 3507 3504 -f 3503 3504 3552 -f 3550 3506 3551 -f 3551 3506 3505 -f 3505 3506 3507 -f 3509 3510 3550 -f 3550 3510 3506 -f 3543 2789 3508 -f 3508 2789 3509 -f 3509 2789 3510 -f 2807 3535 2808 -f 2808 3535 3548 -f 2808 3548 3511 -f 3548 3512 3511 -f 3511 3512 3542 -f 3511 3542 3513 -f 3516 3515 3542 -f 3542 3515 3513 -f 3540 3519 3514 -f 3519 3515 3514 -f 3514 3515 3516 -f 3517 3522 2811 -f 2811 3518 3517 -f 3517 3518 3519 -f 3517 3519 3540 -f 3520 3526 3521 -f 3521 2813 3520 -f 3520 2813 3522 -f 3522 2813 2811 -f 3524 3523 3527 -f 3527 3525 3524 -f 3524 3525 3526 -f 3526 3525 3521 -f 2816 2814 3554 -f 3554 2814 3523 -f 3523 2814 3527 -f 3528 2789 3543 -f 3528 3543 3529 -f 3529 3543 3530 -f 3544 3532 3530 -f 3530 3532 3529 -f 3533 3531 3544 -f 3544 3531 3532 -f 3546 3534 3533 -f 3533 3534 3531 -f 3537 3496 3546 -f 3546 3496 3534 -f 3535 2807 3495 -f 3535 3495 3536 -f 3536 3495 3538 -f 3536 3538 3537 -f 3537 3538 3496 -f 3514 3539 3540 -f 3542 3539 3516 -f 3516 3539 3514 -f 3548 3541 3512 -f 3512 3541 3542 -f 3542 3541 3539 -f 3508 3549 3543 -f 3543 3549 3530 -f 3530 3549 3544 -f 3544 3549 3545 -f 3544 3545 3533 -f 3533 3545 3546 -f 3546 3545 3547 -f 3546 3547 3537 -f 3537 3547 3536 -f 3536 3547 3535 -f 3535 3547 3548 -f 3548 3547 3541 -f 3550 2869 3509 -f 3509 2869 3549 -f 3509 3549 3508 -f 3551 2869 3550 -f 3505 2869 3551 -f 3560 2870 3503 -f 3503 2870 3505 -f 3505 2870 2869 -f 3560 3503 3552 -f 3557 3501 3502 -f 3524 2846 3523 -f 3523 2846 3553 -f 3523 3553 3554 -f 3554 3553 3497 -f 3497 3553 2848 -f 3497 2848 3555 -f 3555 2848 3556 -f 3556 2848 3557 -f 3556 3557 3500 -f 3500 3557 3502 -f 3526 2853 3524 -f 3524 2853 2846 -f 3520 2853 3526 -f 3522 3561 3520 -f 3520 3561 2853 -f 3557 2844 3501 -f 3501 2844 3558 -f 3558 2844 3559 -f 3559 2844 3552 -f 3552 2844 3560 -f 3540 3539 3561 -f 3540 3561 3517 -f 3517 3561 3522 -f 3602 3563 3562 -f 3562 3563 3564 -f 3562 3564 2381 -f 2381 3564 3565 -f 2381 3565 3606 -f 2381 3606 3609 -f 3600 3566 2671 -f 2671 3566 3568 -f 3568 3566 3567 -f 3568 3567 3569 -f 3568 3569 3570 -f 3570 3569 3635 -f 3570 3635 3574 -f 3570 3574 3571 -f 3572 2384 3573 -f 3573 2384 3574 -f 3574 2384 3571 -f 3577 3575 3572 -f 3572 3575 2384 -f 3579 3580 3576 -f 3579 3576 3577 -f 3577 3576 3575 -f 3624 3582 3578 -f 3578 3582 3580 -f 3578 3580 3579 -f 3623 3581 3622 -f 3622 3581 3624 -f 3624 3581 3582 -f 3620 3583 3623 -f 3623 3583 3581 -f 3603 3584 3621 -f 3621 3584 3620 -f 3620 3584 3585 -f 3620 3585 3583 -f 3607 3618 3586 -f 3586 3618 3587 -f 3586 3587 3588 -f 3587 3613 3588 -f 3588 3613 3610 -f 3588 3610 3589 -f 3611 3591 3610 -f 3610 3591 3589 -f 3625 3593 3590 -f 3593 3591 3590 -f 3590 3591 3611 -f 3626 3627 3596 -f 3596 3592 3626 -f 3626 3592 3593 -f 3626 3593 3625 -f 3594 3628 3598 -f 3598 3595 3594 -f 3594 3595 3627 -f 3627 3595 3596 -f 3629 3631 3601 -f 3601 3597 3629 -f 3629 3597 3628 -f 3628 3597 3598 -f 2671 3599 3600 -f 3600 3599 3601 -f 3600 3601 3631 -f 3562 3584 3603 -f 3562 3603 3602 -f 3602 3603 3614 -f 3604 3563 3614 -f 3614 3563 3602 -f 3605 3564 3604 -f 3604 3564 3563 -f 3615 3565 3605 -f 3605 3565 3564 -f 3616 3606 3615 -f 3615 3606 3565 -f 3618 3607 2381 -f 3618 2381 3608 -f 3608 2381 3609 -f 3608 3609 3616 -f 3616 3609 3606 -f 3590 3612 2375 -f 3590 2375 3625 -f 3610 3612 3611 -f 3611 3612 3590 -f 3587 3619 3613 -f 3613 3619 3612 -f 3613 3612 3610 -f 3621 2826 3603 -f 3603 2826 3614 -f 3614 2826 3604 -f 3604 2826 2824 -f 3604 2824 3605 -f 3605 2824 3615 -f 3615 2824 3616 -f 3616 2824 3608 -f 3608 2824 3617 -f 3608 3617 3618 -f 3618 3617 3587 -f 3587 3617 3619 -f 3623 2840 3620 -f 3620 2840 3621 -f 3621 2840 2827 -f 3621 2827 2826 -f 3622 2841 3623 -f 3623 2841 2840 -f 3624 2841 3622 -f 3578 2841 3624 -f 2841 3578 2374 -f 2374 3578 3579 -f 3625 2375 3626 -f 3626 2375 3627 -f 3627 2375 2372 -f 3627 2372 3594 -f 3594 2372 3628 -f 3628 2372 3629 -f 3629 2372 3630 -f 3629 3630 3631 -f 3631 3630 3632 -f 3631 3632 3600 -f 3600 3632 3566 -f 3566 3632 3633 -f 3566 3633 3567 -f 3567 3633 3634 -f 3567 3634 3569 -f 3569 3634 3635 -f 3635 3634 2368 -f 3635 2368 3574 -f 3574 2368 2369 -f 3574 2369 3573 -f 3573 2369 3572 -f 3572 2369 3577 -f 3577 2369 2374 -f 3577 2374 3579 -f 3671 3669 3668 -f 3668 3669 3672 -f 3668 3672 3636 -f 3636 3672 3678 -f 3636 3678 3676 -f 3637 3638 3681 -f 3696 2613 3639 -f 3639 2613 2669 -f 3639 2669 3694 -f 3640 2613 3696 -f 3642 3641 3640 -f 3640 3641 2613 -f 3644 3641 3642 -f 3643 3648 3644 -f 3644 3648 3641 -f 3647 3648 3643 -f 3645 3646 3699 -f 3699 3646 3647 -f 3647 3646 3648 -f 3690 3651 3649 -f 3649 3651 3645 -f 3645 3651 3650 -f 3645 3650 3646 -f 3654 2999 3690 -f 3690 2999 3651 -f 3689 3653 3652 -f 3652 3653 3654 -f 3654 3653 3655 -f 3654 3655 2999 -f 3637 2997 3638 -f 3638 2997 3689 -f 3689 2997 3653 -f 3674 3675 2382 -f 2382 3675 3688 -f 2382 3688 3656 -f 3688 3680 3656 -f 3656 3680 3658 -f 3656 3658 2383 -f 3657 3659 3658 -f 3658 3659 2383 -f 3661 2386 3679 -f 2386 3659 3679 -f 3679 3659 3657 -f 3660 3692 3664 -f 3664 2385 3660 -f 3660 2385 2386 -f 3660 2386 3661 -f 3662 3665 2387 -f 2387 3663 3662 -f 3662 3663 3692 -f 3692 3663 3664 -f 3693 3667 3666 -f 3666 2388 3693 -f 3693 2388 3665 -f 3665 2388 2387 -f 2669 2667 3694 -f 3694 2667 3666 -f 3694 3666 3667 -f 3668 3637 3681 -f 3668 3681 3682 -f 3670 3671 3682 -f 3682 3671 3668 -f 3684 3669 3670 -f 3670 3669 3671 -f 3673 3672 3684 -f 3684 3672 3669 -f 3677 3678 3673 -f 3673 3678 3672 -f 3675 3674 3636 -f 3675 3636 3687 -f 3687 3636 3676 -f 3687 3676 3677 -f 3677 3676 3678 -f 3679 2842 3691 -f 3679 3691 3661 -f 3658 2842 3657 -f 3657 2842 3679 -f 3688 2842 3680 -f 3680 2842 3658 -f 3638 3683 3681 -f 3681 3683 3682 -f 3682 3683 3670 -f 3670 3683 3685 -f 3670 3685 3684 -f 3684 3685 3673 -f 3673 3685 3686 -f 3673 3686 3677 -f 3677 3686 3687 -f 3687 3686 3675 -f 3675 3686 3688 -f 3688 3686 2842 -f 3652 3683 3689 -f 3689 3683 3638 -f 3654 2838 3652 -f 3652 2838 3683 -f 3690 2838 3654 -f 3700 2838 3649 -f 3649 2838 3690 -f 3700 3649 3645 -f 3661 3691 3660 -f 3660 3691 3692 -f 3692 3691 2366 -f 3692 2366 3662 -f 3662 2366 3665 -f 3665 2366 3693 -f 3693 2366 3695 -f 3693 3695 3667 -f 3667 3695 3694 -f 3694 3695 3697 -f 3694 3697 3639 -f 3639 3697 3696 -f 3696 3697 3640 -f 3640 3697 3642 -f 3642 3697 3698 -f 3642 3698 3644 -f 3644 3698 3643 -f 3643 3698 2365 -f 3643 2365 3647 -f 3647 2365 3699 -f 3699 2365 3700 -f 3699 3700 3645 -f 3742 3744 3701 -f 3701 3744 3702 -f 3701 3702 3746 -f 3701 3746 3703 -f 3703 3746 3748 -f 3703 3748 3751 -f 3764 3766 3704 -f 3704 3766 3706 -f 3706 3766 3705 -f 3706 3705 3707 -f 3706 3707 3708 -f 3708 3707 3768 -f 3708 3768 3710 -f 3708 3710 3711 -f 3769 3713 3709 -f 3709 3713 3710 -f 3710 3713 3711 -f 3770 3712 3769 -f 3769 3712 3713 -f 3715 2379 2380 -f 3715 2380 3770 -f 3770 2380 3712 -f 3718 3717 3714 -f 3714 3717 2379 -f 3714 2379 3715 -f 3757 3716 3758 -f 3758 3716 3718 -f 3718 3716 3717 -f 3722 3719 3757 -f 3757 3719 3716 -f 3720 2378 3756 -f 3756 2378 3722 -f 3722 2378 3721 -f 3722 3721 3719 -f 3723 3753 2391 -f 2391 3753 3724 -f 2391 3724 2392 -f 3724 3725 2392 -f 2392 3725 3726 -f 2392 3726 3727 -f 3732 3731 3726 -f 3726 3731 3727 -f 3728 3729 3730 -f 3729 3731 3730 -f 3730 3731 3732 -f 3734 3761 3736 -f 3736 3733 3734 -f 3734 3733 3728 -f 3728 3733 3729 -f 3735 3739 2399 -f 2399 3736 3735 -f 3735 3736 3761 -f 3737 3763 3741 -f 3741 3738 3737 -f 3737 3738 3739 -f 3739 3738 2399 -f 3704 3740 3764 -f 3764 3740 3763 -f 3763 3740 3741 -f 3701 2378 3720 -f 3701 3720 3742 -f 3742 3720 3743 -f 3752 3744 3743 -f 3743 3744 3742 -f 3745 3702 3752 -f 3752 3702 3744 -f 3747 3746 3745 -f 3745 3746 3702 -f 3750 3748 3747 -f 3747 3748 3746 -f 3753 3723 3703 -f 3753 3703 3749 -f 3749 3703 3751 -f 3749 3751 3750 -f 3750 3751 3748 -f 3730 2819 3728 -f 3726 2821 3732 -f 3732 2821 3730 -f 3730 2821 2819 -f 3724 2821 3725 -f 3725 2821 3726 -f 3756 3755 3720 -f 3720 3755 3743 -f 3743 3755 2823 -f 3743 2823 3752 -f 3752 2823 3745 -f 3745 2823 3754 -f 3745 3754 3747 -f 3747 3754 3750 -f 3750 3754 3749 -f 3749 3754 3753 -f 3753 3754 3724 -f 3724 3754 2821 -f 3757 2843 3722 -f 3722 2843 3755 -f 3722 3755 3756 -f 3758 2843 3757 -f 3718 2843 3758 -f 3714 3759 3718 -f 3718 3759 2843 -f 3759 3714 3715 -f 3728 2819 3734 -f 3734 2819 3760 -f 3734 3760 3761 -f 3761 3760 3735 -f 3735 3760 3739 -f 3739 3760 3762 -f 3739 3762 3737 -f 3737 3762 3763 -f 3763 3762 3764 -f 3764 3762 3765 -f 3764 3765 3766 -f 3766 3765 3705 -f 3705 3765 3767 -f 3705 3767 3707 -f 3707 3767 3768 -f 3768 3767 2371 -f 3768 2371 3710 -f 3710 2371 2373 -f 3710 2373 3709 -f 3709 2373 3769 -f 3769 2373 3770 -f 3770 2373 3759 -f 3770 3759 3715 -f 2767 3789 3771 -f 3781 3772 3771 -f 2401 2402 3776 -f 3775 2633 3776 -f 3776 3773 3774 -f 3780 3772 3773 -f 3772 3780 3771 -f 2401 3776 2633 -f 3780 3773 3776 -f 3776 3774 2634 -f 3776 2634 3775 -f 3771 3780 2767 -f 3780 3777 2767 -f 3777 3780 3778 -f 3777 3778 2766 -f 3778 2778 3779 -f 3778 3779 2766 -f 2402 2778 3778 -f 2402 3778 3776 -f 3776 3778 3780 -f 3784 3785 2637 -f 2639 3786 3783 -f 3787 3781 3771 -f 3781 3787 3782 -f 3782 3787 2638 -f 2638 3787 3786 -f 2638 3786 2639 -f 3783 3786 3784 -f 3784 3786 3785 -f 2637 3785 2636 -f 3791 3786 3787 -f 3786 3791 3785 -f 3785 3791 3788 -f 2352 3788 3791 -f 3791 3790 2351 -f 3790 3791 3787 -f 3789 3790 3787 -f 3771 3789 3787 -f 2351 2352 3791 -f 3804 3808 3810 -f 3792 3808 3804 -f 3804 3813 3793 -f 3812 3813 3804 -f 3810 3812 3804 -f 3804 3794 3817 -f 3816 3794 3804 -f 3793 3816 3804 -f 3804 3795 3819 -f 3796 3795 3804 -f 3817 3796 3804 -f 3804 3797 3798 -f 3821 3797 3804 -f 3819 3821 3804 -f 3804 3826 3799 -f 3825 3826 3804 -f 3798 3825 3804 -f 3804 3829 3831 -f 3827 3829 3804 -f 3799 3827 3804 -f 3804 3801 3834 -f 3800 3801 3804 -f 3831 3800 3804 -f 3804 3802 3805 -f 3836 3802 3804 -f 3834 3836 3804 -f 3804 3803 3806 -f 3839 3803 3804 -f 3805 3839 3804 -f 3804 3841 3842 -f 3840 3841 3804 -f 3806 3840 3804 -f 3804 3846 3847 -f 3844 3846 3804 -f 3842 3844 3804 -f 3847 3792 3804 -f 3792 3807 3808 -f 3808 3807 3809 -f 3808 3809 3810 -f 3810 3809 3811 -f 3810 3811 3812 -f 3812 3811 2549 -f 3812 2549 3813 -f 3813 2549 3814 -f 3813 3814 3793 -f 3793 3814 3815 -f 3793 3815 3816 -f 3816 3815 2555 -f 3816 2555 3794 -f 3794 2555 2554 -f 3794 2554 3817 -f 3817 2554 2550 -f 3817 2550 3796 -f 3796 2550 3818 -f 3796 3818 3795 -f 3795 3818 3820 -f 3795 3820 3819 -f 3819 3820 2562 -f 3819 2562 3821 -f 3821 2562 3822 -f 3821 3822 3797 -f 3797 3822 3823 -f 3797 3823 3798 -f 3798 3823 3824 -f 3798 3824 3825 -f 3825 3824 2547 -f 3825 2547 3826 -f 3826 2547 2546 -f 3826 2546 3799 -f 3799 2546 2539 -f 3799 2539 3827 -f 3827 2539 3828 -f 3827 3828 3829 -f 3829 3828 3830 -f 3829 3830 3831 -f 3831 3830 3832 -f 3831 3832 3800 -f 3800 3832 2540 -f 3800 2540 3801 -f 3801 2540 3833 -f 3801 3833 3834 -f 3834 3833 3835 -f 3834 3835 3836 -f 3836 3835 3837 -f 3836 3837 3802 -f 3802 3837 3838 -f 3802 3838 3805 -f 3805 3838 2559 -f 3805 2559 3839 -f 3839 2559 2557 -f 3839 2557 3803 -f 3803 2557 2556 -f 3803 2556 3806 -f 3806 2556 2553 -f 3806 2553 3840 -f 3840 2553 2552 -f 3840 2552 3841 -f 3841 2552 2551 -f 3841 2551 3842 -f 3842 2551 3843 -f 3842 3843 3844 -f 3844 3843 3845 -f 3844 3845 3846 -f 3846 3845 2545 -f 3846 2545 3847 -f 3847 2545 3848 -f 3847 3848 3792 -f 3792 3848 3807 -f 3860 3850 3849 -f 3866 3850 3860 -f 3860 3851 3853 -f 3908 3851 3860 -f 3849 3908 3860 -f 3860 3868 3869 -f 3852 3868 3860 -f 3853 3852 3860 -f 3860 3854 3875 -f 3872 3854 3860 -f 3869 3872 3860 -f 3860 3877 3855 -f 3856 3877 3860 -f 3875 3856 3860 -f 3860 3881 3883 -f 3857 3881 3860 -f 3855 3857 3860 -f 3860 3859 3885 -f 3858 3859 3860 -f 3883 3858 3860 -f 3860 3887 3888 -f 3861 3887 3860 -f 3885 3861 3860 -f 3860 3862 3865 -f 3890 3862 3860 -f 3888 3890 3860 -f 3860 3863 3895 -f 3864 3863 3860 -f 3865 3864 3860 -f 3860 3898 3899 -f 3897 3898 3860 -f 3895 3897 3860 -f 3860 3903 3904 -f 3901 3903 3860 -f 3899 3901 3860 -f 3904 3866 3860 -f 3908 3867 3851 -f 3851 3867 3853 -f 3853 3867 2467 -f 3853 2467 3852 -f 3852 2467 2466 -f 3852 2466 3868 -f 3868 2466 3870 -f 3868 3870 3869 -f 3869 3870 3871 -f 3869 3871 3872 -f 3872 3871 3873 -f 3872 3873 3854 -f 3854 3873 3874 -f 3854 3874 3875 -f 3875 3874 2468 -f 3875 2468 3856 -f 3856 2468 3876 -f 3856 3876 3877 -f 3877 3876 3878 -f 3877 3878 3855 -f 3855 3878 3879 -f 3855 3879 3857 -f 3857 3879 3880 -f 3857 3880 3881 -f 3881 3880 3882 -f 3881 3882 3883 -f 3883 3882 3884 -f 3883 3884 3858 -f 3858 3884 2457 -f 3858 2457 3859 -f 3859 2457 2456 -f 3859 2456 3885 -f 3885 2456 2462 -f 3885 2462 3861 -f 3861 2462 3886 -f 3861 3886 3887 -f 3887 3886 2461 -f 3887 2461 3888 -f 3888 2461 3889 -f 3888 3889 3890 -f 3890 3889 3891 -f 3890 3891 3862 -f 3862 3891 2465 -f 3862 2465 3865 -f 3865 2465 3892 -f 3865 3892 3864 -f 3864 3892 3893 -f 3864 3893 3863 -f 3863 3893 2464 -f 3863 2464 3895 -f 3895 2464 3894 -f 3895 3894 3897 -f 3897 3894 3896 -f 3897 3896 3898 -f 3898 3896 2463 -f 3898 2463 3899 -f 3899 2463 3900 -f 3899 3900 3901 -f 3901 3900 3902 -f 3901 3902 3903 -f 3903 3902 2460 -f 3903 2460 3904 -f 3904 2460 3905 -f 3904 3905 3866 -f 3866 3905 3906 -f 3866 3906 3850 -f 3850 3906 3907 -f 3850 3907 3849 -f 3849 3907 2459 -f 3849 2459 3908 -f 3908 2459 3867 -f 3916 3924 3910 -f 3923 3924 3916 -f 3916 3909 3929 -f 3927 3909 3916 -f 3910 3927 3916 -f 3916 3933 3935 -f 3932 3933 3916 -f 3929 3932 3916 -f 3916 3937 3911 -f 3912 3937 3916 -f 3935 3912 3916 -f 3916 3940 3941 -f 3913 3940 3916 -f 3911 3913 3916 -f 3916 3914 3915 -f 3944 3914 3916 -f 3941 3944 3916 -f 3916 3948 3918 -f 3946 3948 3916 -f 3915 3946 3916 -f 3916 3951 3917 -f 3950 3951 3916 -f 3918 3950 3916 -f 3916 3919 3955 -f 3920 3919 3916 -f 3917 3920 3916 -f 3916 3957 3960 -f 3956 3957 3916 -f 3955 3956 3916 -f 3916 3963 3964 -f 3961 3963 3916 -f 3960 3961 3916 -f 3916 3921 3969 -f 3922 3921 3916 -f 3964 3922 3916 -f 3969 3923 3916 -f 3923 2575 3924 -f 3924 2575 3925 -f 3924 3925 3910 -f 3910 3925 3926 -f 3910 3926 3927 -f 3927 3926 3928 -f 3927 3928 3909 -f 3909 3928 3930 -f 3909 3930 3929 -f 3929 3930 3931 -f 3929 3931 3932 -f 3932 3931 2581 -f 3932 2581 3933 -f 3933 2581 3934 -f 3933 3934 3935 -f 3935 3934 3936 -f 3935 3936 3912 -f 3912 3936 3938 -f 3912 3938 3937 -f 3937 3938 2587 -f 3937 2587 3911 -f 3911 2587 3939 -f 3911 3939 3913 -f 3913 3939 2586 -f 3913 2586 3940 -f 3940 2586 2585 -f 3940 2585 3941 -f 3941 2585 3942 -f 3941 3942 3944 -f 3944 3942 3943 -f 3944 3943 3914 -f 3914 3943 3945 -f 3914 3945 3915 -f 3915 3945 2576 -f 3915 2576 3946 -f 3946 2576 3947 -f 3946 3947 3948 -f 3948 3947 3949 -f 3948 3949 3918 -f 3918 3949 2584 -f 3918 2584 3950 -f 3950 2584 2583 -f 3950 2583 3951 -f 3951 2583 2582 -f 3951 2582 3917 -f 3917 2582 3952 -f 3917 3952 3920 -f 3920 3952 2589 -f 3920 2589 3919 -f 3919 2589 3953 -f 3919 3953 3955 -f 3955 3953 3954 -f 3955 3954 3956 -f 3956 3954 2590 -f 3956 2590 3957 -f 3957 2590 3958 -f 3957 3958 3960 -f 3960 3958 3959 -f 3960 3959 3961 -f 3961 3959 3962 -f 3961 3962 3963 -f 3963 3962 3965 -f 3963 3965 3964 -f 3964 3965 3966 -f 3964 3966 3922 -f 3922 3966 3967 -f 3922 3967 3921 -f 3921 3967 3968 -f 3921 3968 3969 -f 3969 3968 3970 -f 3969 3970 3923 -f 3923 3970 2575 -f 3990 3971 3972 -f 3989 3971 3990 -f 3990 3991 3974 -f 4028 3991 3990 -f 3972 4028 3990 -f 3990 3993 3994 -f 3973 3993 3990 -f 3974 3973 3990 -f 3990 3975 3999 -f 3997 3975 3990 -f 3994 3997 3990 -f 3990 4001 3976 -f 3977 4001 3990 -f 3999 3977 3990 -f 3990 4004 4005 -f 3978 4004 3990 -f 3976 3978 3990 -f 3990 4006 3982 -f 3979 4006 3990 -f 4005 3979 3990 -f 3990 3981 4010 -f 3980 3981 3990 -f 3982 3980 3990 -f 3990 3983 3985 -f 4011 3983 3990 -f 4010 4011 3990 -f 3990 4016 3984 -f 4014 4016 3990 -f 3985 4014 3990 -f 3990 4020 4021 -f 3986 4020 3990 -f 3984 3986 3990 -f 3990 3987 3988 -f 4022 3987 3990 -f 4021 4022 3990 -f 3988 3989 3990 -f 4028 4030 3991 -f 3991 4030 3974 -f 3974 4030 3992 -f 3974 3992 3973 -f 3973 3992 2484 -f 3973 2484 3993 -f 3993 2484 3995 -f 3993 3995 3994 -f 3994 3995 3996 -f 3994 3996 3997 -f 3997 3996 2482 -f 3997 2482 3975 -f 3975 2482 3998 -f 3975 3998 3999 -f 3999 3998 2481 -f 3999 2481 3977 -f 3977 2481 4000 -f 3977 4000 4001 -f 4001 4000 2480 -f 4001 2480 3976 -f 3976 2480 4002 -f 3976 4002 3978 -f 3978 4002 4003 -f 3978 4003 4004 -f 4004 4003 2473 -f 4004 2473 4005 -f 4005 2473 2472 -f 4005 2472 3979 -f 3979 2472 2471 -f 3979 2471 4006 -f 4006 2471 4007 -f 4006 4007 3982 -f 3982 4007 4008 -f 3982 4008 3980 -f 3980 4008 4009 -f 3980 4009 3981 -f 3981 4009 2477 -f 3981 2477 4010 -f 4010 2477 2476 -f 4010 2476 4011 -f 4011 2476 2475 -f 4011 2475 3983 -f 3983 2475 4012 -f 3983 4012 3985 -f 3985 4012 4013 -f 3985 4013 4014 -f 4014 4013 4015 -f 4014 4015 4016 -f 4016 4015 4017 -f 4016 4017 3984 -f 3984 4017 4018 -f 3984 4018 3986 -f 3986 4018 4019 -f 3986 4019 4020 -f 4020 4019 2474 -f 4020 2474 4021 -f 4021 2474 4023 -f 4021 4023 4022 -f 4022 4023 2470 -f 4022 2470 3987 -f 3987 2470 4024 -f 3987 4024 3988 -f 3988 4024 4025 -f 3988 4025 3989 -f 3989 4025 4026 -f 3989 4026 3971 -f 3971 4026 2469 -f 3971 2469 3972 -f 3972 2469 4027 -f 3972 4027 4028 -f 4028 4027 4029 -f 4028 4029 4030 -f 4043 4085 4087 -f 4082 4085 4043 -f 4043 4047 4048 -f 4046 4047 4043 -f 4087 4046 4043 -f 4043 4031 4050 -f 4032 4031 4043 -f 4048 4032 4043 -f 4043 4052 4053 -f 4051 4052 4043 -f 4050 4051 4043 -f 4043 4033 4056 -f 4055 4033 4043 -f 4053 4055 4043 -f 4043 4060 4034 -f 4057 4060 4043 -f 4056 4057 4043 -f 4043 4063 4064 -f 4035 4063 4043 -f 4034 4035 4043 -f 4043 4037 4036 -f 4066 4037 4043 -f 4064 4066 4043 -f 4043 4038 4041 -f 4039 4038 4043 -f 4036 4039 4043 -f 4043 4072 4040 -f 4070 4072 4043 -f 4041 4070 4043 -f 4043 4042 4078 -f 4074 4042 4043 -f 4040 4074 4043 -f 4043 4044 4081 -f 4045 4044 4043 -f 4078 4045 4043 -f 4081 4082 4043 -f 4046 2486 4047 -f 4047 2486 4048 -f 4048 2486 2563 -f 4048 2563 4032 -f 4032 2563 4049 -f 4032 4049 4031 -f 4031 4049 2498 -f 4031 2498 4050 -f 4050 2498 2497 -f 4050 2497 4051 -f 4051 2497 2500 -f 4051 2500 4052 -f 4052 2500 2499 -f 4052 2499 4053 -f 4053 2499 4054 -f 4053 4054 4055 -f 4055 4054 2496 -f 4055 2496 4033 -f 4033 2496 2495 -f 4033 2495 4056 -f 4056 2495 4058 -f 4056 4058 4057 -f 4057 4058 4059 -f 4057 4059 4060 -f 4060 4059 4061 -f 4060 4061 4034 -f 4034 4061 2485 -f 4034 2485 4035 -f 4035 2485 4062 -f 4035 4062 4063 -f 4063 4062 4065 -f 4063 4065 4064 -f 4064 4065 2491 -f 4064 2491 4066 -f 4066 2491 4067 -f 4066 4067 4037 -f 4037 4067 4068 -f 4037 4068 4036 -f 4036 4068 2493 -f 4036 2493 4039 -f 4039 2493 4069 -f 4039 4069 4038 -f 4038 4069 2492 -f 4038 2492 4041 -f 4041 2492 4071 -f 4041 4071 4070 -f 4070 4071 4073 -f 4070 4073 4072 -f 4072 4073 2494 -f 4072 2494 4040 -f 4040 2494 4075 -f 4040 4075 4074 -f 4074 4075 4076 -f 4074 4076 4042 -f 4042 4076 4077 -f 4042 4077 4078 -f 4078 4077 4079 -f 4078 4079 4045 -f 4045 4079 4080 -f 4045 4080 4044 -f 4044 4080 2489 -f 4044 2489 4081 -f 4081 2489 4083 -f 4081 4083 4082 -f 4082 4083 4084 -f 4082 4084 4085 -f 4085 4084 4086 -f 4085 4086 4087 -f 4087 4086 2487 -f 4087 2487 4046 -f 4046 2487 2486 -f 4099 4088 4089 -f 4103 4088 4099 -f 4099 4107 4090 -f 4105 4107 4099 -f 4089 4105 4099 -f 4099 4110 4091 -f 4109 4110 4099 -f 4090 4109 4099 -f 4099 4092 4093 -f 4113 4092 4099 -f 4091 4113 4099 -f 4099 4117 4118 -f 4094 4117 4099 -f 4093 4094 4099 -f 4099 4122 4124 -f 4120 4122 4099 -f 4118 4120 4099 -f 4099 4127 4128 -f 4126 4127 4099 -f 4124 4126 4099 -f 4099 4095 4098 -f 4096 4095 4099 -f 4128 4096 4099 -f 4099 4131 4133 -f 4097 4131 4099 -f 4098 4097 4099 -f 4099 4100 4136 -f 4101 4100 4099 -f 4133 4101 4099 -f 4099 4140 4141 -f 4137 4140 4099 -f 4136 4137 4099 -f 4099 4102 4145 -f 4143 4102 4099 -f 4141 4143 4099 -f 4145 4103 4099 -f 4103 2506 4088 -f 4088 2506 2505 -f 4088 2505 4089 -f 4089 2505 4104 -f 4089 4104 4105 -f 4105 4104 4106 -f 4105 4106 4107 -f 4107 4106 2515 -f 4107 2515 4090 -f 4090 2515 4108 -f 4090 4108 4109 -f 4109 4108 4111 -f 4109 4111 4110 -f 4110 4111 4112 -f 4110 4112 4091 -f 4091 4112 2521 -f 4091 2521 4113 -f 4113 2521 4114 -f 4113 4114 4092 -f 4092 4114 4115 -f 4092 4115 4093 -f 4093 4115 2514 -f 4093 2514 4094 -f 4094 2514 4116 -f 4094 4116 4117 -f 4117 4116 2513 -f 4117 2513 4118 -f 4118 2513 4119 -f 4118 4119 4120 -f 4120 4119 4121 -f 4120 4121 4122 -f 4122 4121 4123 -f 4122 4123 4124 -f 4124 4123 4125 -f 4124 4125 4126 -f 4126 4125 2510 -f 4126 2510 4127 -f 4127 2510 2509 -f 4127 2509 4128 -f 4128 2509 2518 -f 4128 2518 4096 -f 4096 2518 4129 -f 4096 4129 4095 -f 4095 4129 4130 -f 4095 4130 4098 -f 4098 4130 2517 -f 4098 2517 4097 -f 4097 2517 2516 -f 4097 2516 4131 -f 4131 2516 4132 -f 4131 4132 4133 -f 4133 4132 4134 -f 4133 4134 4101 -f 4101 4134 2522 -f 4101 2522 4100 -f 4100 2522 4135 -f 4100 4135 4136 -f 4136 4135 4138 -f 4136 4138 4137 -f 4137 4138 4139 -f 4137 4139 4140 -f 4140 4139 2519 -f 4140 2519 4141 -f 4141 2519 4142 -f 4141 4142 4143 -f 4143 4142 4144 -f 4143 4144 4102 -f 4102 4144 2508 -f 4102 2508 4145 -f 4145 2508 2507 -f 4145 2507 4103 -f 4103 2507 2506 -f 4154 4146 4165 -f 4200 4146 4154 -f 4154 4147 4168 -f 4167 4147 4154 -f 4165 4167 4154 -f 4154 4170 4171 -f 4148 4170 4154 -f 4168 4148 4154 -f 4154 4149 4150 -f 4151 4149 4154 -f 4171 4151 4154 -f 4154 4152 4175 -f 4153 4152 4154 -f 4150 4153 4154 -f 4154 4156 4155 -f 4157 4156 4154 -f 4175 4157 4154 -f 4154 4158 4181 -f 4159 4158 4154 -f 4155 4159 4154 -f 4154 4185 4160 -f 4183 4185 4154 -f 4181 4183 4154 -f 4154 4188 4161 -f 4186 4188 4154 -f 4160 4186 4154 -f 4154 4193 4162 -f 4190 4193 4154 -f 4161 4190 4154 -f 4154 4195 4196 -f 4194 4195 4154 -f 4162 4194 4154 -f 4154 4163 4164 -f 4197 4163 4154 -f 4196 4197 4154 -f 4164 4200 4154 -f 4200 4201 4146 -f 4146 4201 2439 -f 4146 2439 4165 -f 4165 2439 4166 -f 4165 4166 4167 -f 4167 4166 2451 -f 4167 2451 4147 -f 4147 2451 2450 -f 4147 2450 4168 -f 4168 2450 4169 -f 4168 4169 4148 -f 4148 4169 2449 -f 4148 2449 4170 -f 4170 2449 2454 -f 4170 2454 4171 -f 4171 2454 4172 -f 4171 4172 4151 -f 4151 4172 2453 -f 4151 2453 4149 -f 4149 2453 2452 -f 4149 2452 4150 -f 4150 2452 4173 -f 4150 4173 4153 -f 4153 4173 2448 -f 4153 2448 4152 -f 4152 2448 4174 -f 4152 4174 4175 -f 4175 4174 4176 -f 4175 4176 4157 -f 4157 4176 4177 -f 4157 4177 4156 -f 4156 4177 2446 -f 4156 2446 4155 -f 4155 2446 4178 -f 4155 4178 4159 -f 4159 4178 4179 -f 4159 4179 4158 -f 4158 4179 2438 -f 4158 2438 4181 -f 4181 2438 4180 -f 4181 4180 4183 -f 4183 4180 4182 -f 4183 4182 4185 -f 4185 4182 4184 -f 4185 4184 4160 -f 4160 4184 2441 -f 4160 2441 4186 -f 4186 2441 4187 -f 4186 4187 4188 -f 4188 4187 2440 -f 4188 2440 4161 -f 4161 2440 4189 -f 4161 4189 4190 -f 4190 4189 4191 -f 4190 4191 4193 -f 4193 4191 4192 -f 4193 4192 4162 -f 4162 4192 2445 -f 4162 2445 4194 -f 4194 2445 2444 -f 4194 2444 4195 -f 4195 2444 2443 -f 4195 2443 4196 -f 4196 2443 2442 -f 4196 2442 4197 -f 4197 2442 4198 -f 4197 4198 4163 -f 4163 4198 2437 -f 4163 2437 4164 -f 4164 2437 4199 -f 4164 4199 4200 -f 4200 4199 4201 -f 4211 4223 4202 -f 4221 4223 4211 -f 4211 4203 4227 -f 4225 4203 4211 -f 4202 4225 4211 -f 4211 4204 4231 -f 4228 4204 4211 -f 4227 4228 4211 -f 4211 4205 4206 -f 4207 4205 4211 -f 4231 4207 4211 -f 4211 4235 4236 -f 4208 4235 4211 -f 4206 4208 4211 -f 4211 4209 4210 -f 4238 4209 4211 -f 4236 4238 4211 -f 4211 4241 4243 -f 4240 4241 4211 -f 4210 4240 4211 -f 4211 4213 4245 -f 4212 4213 4211 -f 4243 4212 4211 -f 4211 4214 4248 -f 4215 4214 4211 -f 4245 4215 4211 -f 4211 4216 4220 -f 4249 4216 4211 -f 4248 4249 4211 -f 4211 4217 4218 -f 4219 4217 4211 -f 4220 4219 4211 -f 4211 4256 4257 -f 4255 4256 4211 -f 4218 4255 4211 -f 4257 4221 4211 -f 4221 4222 4223 -f 4223 4222 2544 -f 4223 2544 4202 -f 4202 2544 4224 -f 4202 4224 4225 -f 4225 4224 2526 -f 4225 2526 4203 -f 4203 2526 4226 -f 4203 4226 4227 -f 4227 4226 2525 -f 4227 2525 4228 -f 4228 2525 4229 -f 4228 4229 4204 -f 4204 4229 4230 -f 4204 4230 4231 -f 4231 4230 2532 -f 4231 2532 4207 -f 4207 2532 4232 -f 4207 4232 4205 -f 4205 4232 4233 -f 4205 4233 4206 -f 4206 4233 4234 -f 4206 4234 4208 -f 4208 4234 2535 -f 4208 2535 4235 -f 4235 2535 4237 -f 4235 4237 4236 -f 4236 4237 2531 -f 4236 2531 4238 -f 4238 2531 2530 -f 4238 2530 4209 -f 4209 2530 2534 -f 4209 2534 4210 -f 4210 2534 4239 -f 4210 4239 4240 -f 4240 4239 2533 -f 4240 2533 4241 -f 4241 2533 4242 -f 4241 4242 4243 -f 4243 4242 4244 -f 4243 4244 4212 -f 4212 4244 2529 -f 4212 2529 4213 -f 4213 2529 2528 -f 4213 2528 4245 -f 4245 2528 4246 -f 4245 4246 4215 -f 4215 4246 2538 -f 4215 2538 4214 -f 4214 2538 4247 -f 4214 4247 4248 -f 4248 4247 2537 -f 4248 2537 4249 -f 4249 2537 4250 -f 4249 4250 4216 -f 4216 4250 2536 -f 4216 2536 4220 -f 4220 2536 4251 -f 4220 4251 4219 -f 4219 4251 4252 -f 4219 4252 4217 -f 4217 4252 4253 -f 4217 4253 4218 -f 4218 4253 2527 -f 4218 2527 4255 -f 4255 2527 4254 -f 4255 4254 4256 -f 4256 4254 2524 -f 4256 2524 4257 -f 4257 2524 4258 -f 4257 4258 4221 -f 4221 4258 4222 -f 4266 4277 4278 -f 4259 4277 4266 -f 4266 4281 4260 -f 4280 4281 4266 -f 4278 4280 4266 -f 4266 4286 4263 -f 4285 4286 4266 -f 4260 4285 4266 -f 4266 4289 4261 -f 4262 4289 4266 -f 4263 4262 4266 -f 4266 4291 4293 -f 4264 4291 4266 -f 4261 4264 4266 -f 4266 4295 4297 -f 4265 4295 4266 -f 4293 4265 4266 -f 4266 4301 4268 -f 4299 4301 4266 -f 4297 4299 4266 -f 4266 4305 4267 -f 4302 4305 4266 -f 4268 4302 4266 -f 4266 4309 4310 -f 4269 4309 4266 -f 4267 4269 4266 -f 4266 4270 4271 -f 4272 4270 4266 -f 4310 4272 4266 -f 4266 4273 4316 -f 4274 4273 4266 -f 4271 4274 4266 -f 4266 4275 4276 -f 4319 4275 4266 -f 4316 4319 4266 -f 4276 4259 4266 -f 4259 4322 4277 -f 4277 4322 2565 -f 4277 2565 4278 -f 4278 2565 2579 -f 4278 2579 4280 -f 4280 2579 4279 -f 4280 4279 4281 -f 4281 4279 4282 -f 4281 4282 4260 -f 4260 4282 4283 -f 4260 4283 4285 -f 4285 4283 4284 -f 4285 4284 4286 -f 4286 4284 4287 -f 4286 4287 4263 -f 4263 4287 4288 -f 4263 4288 4262 -f 4262 4288 2564 -f 4262 2564 4289 -f 4289 2564 2567 -f 4289 2567 4261 -f 4261 2567 2569 -f 4261 2569 4264 -f 4264 2569 4290 -f 4264 4290 4291 -f 4291 4290 4292 -f 4291 4292 4293 -f 4293 4292 2570 -f 4293 2570 4265 -f 4265 2570 4294 -f 4265 4294 4295 -f 4295 4294 4296 -f 4295 4296 4297 -f 4297 4296 4298 -f 4297 4298 4299 -f 4299 4298 4300 -f 4299 4300 4301 -f 4301 4300 2573 -f 4301 2573 4268 -f 4268 2573 4303 -f 4268 4303 4302 -f 4302 4303 4304 -f 4302 4304 4305 -f 4305 4304 4306 -f 4305 4306 4267 -f 4267 4306 4307 -f 4267 4307 4269 -f 4269 4307 4308 -f 4269 4308 4309 -f 4309 4308 2574 -f 4309 2574 4310 -f 4310 2574 4311 -f 4310 4311 4272 -f 4272 4311 4312 -f 4272 4312 4270 -f 4270 4312 4313 -f 4270 4313 4271 -f 4271 4313 4314 -f 4271 4314 4274 -f 4274 4314 4315 -f 4274 4315 4273 -f 4273 4315 4317 -f 4273 4317 4316 -f 4316 4317 4318 -f 4316 4318 4319 -f 4319 4318 4320 -f 4319 4320 4275 -f 4275 4320 4321 -f 4275 4321 4276 -f 4276 4321 2566 -f 4276 2566 4259 -f 4259 2566 4322 -f 4323 4329 4680 -f 4680 4681 4323 -f 4681 4682 4323 -f 4323 4682 4325 -f 4325 4682 4684 -f 4325 4684 4686 -f 4686 4326 4324 -f 4325 4686 4324 -f 7580 4676 4686 -f 4686 4676 4326 -f 4675 4676 7580 -f 4675 7580 4327 -f 4336 4679 4328 -f 4336 4328 4680 -f 4336 4680 4329 -f 4335 4672 4673 -f 4670 4672 4335 -f 4673 4675 4336 -f 4330 4673 4336 -f 4327 4679 4675 -f 4675 4679 4336 -f 4670 4335 4332 -f 4670 4332 4669 -f 4332 4668 4669 -f 2224 4662 4663 -f 2224 4663 4664 -f 2224 4664 4331 -f 4331 4664 4666 -f 4331 4666 4332 -f 4332 4666 4668 -f 4342 4334 4333 -f 4333 4334 4348 -f 4333 4348 4330 -f 4330 4348 4335 -f 4330 4335 4673 -f 9522 7000 7001 -f 9522 7001 9584 -f 9584 7001 6995 -f 9584 6995 6993 -f 4323 9513 4329 -f 4329 9513 4338 -f 4329 4338 4336 -f 4336 4338 4330 -f 7010 4342 4345 -f 4345 4342 4333 -f 4345 4333 4337 -f 4337 4333 4330 -f 4337 4330 6993 -f 6993 4330 4338 -f 6993 4338 9584 -f 7010 4339 4342 -f 4342 4339 4355 -f 4342 4355 4340 -f 4340 4341 4342 -f 4342 4341 4359 -f 7006 4345 4343 -f 4343 4345 7004 -f 7006 7008 4345 -f 4345 7008 4344 -f 4345 4344 7010 -f 4332 9585 4331 -f 4331 9585 4346 -f 4331 4346 2224 -f 7003 7002 4347 -f 7003 4347 4353 -f 9578 9582 6992 -f 6992 9582 4347 -f 6992 4347 6994 -f 6994 4347 7002 -f 4332 4335 9585 -f 9585 4335 4348 -f 9585 4348 4334 -f 4358 4349 4334 -f 4334 4349 4357 -f 4334 4357 4356 -f 4356 4354 4334 -f 4334 4354 4350 -f 4334 4350 9585 -f 9585 4350 4351 -f 9585 4351 4347 -f 4347 4351 4353 -f 4353 4351 7009 -f 4353 7009 7007 -f 7007 7005 4353 -f 4353 7005 4352 -f 4339 4350 4354 -f 4339 4354 4355 -f 4355 4354 4356 -f 4355 4356 4340 -f 4340 4356 4357 -f 4340 4357 4341 -f 4341 4357 4349 -f 4341 4349 4359 -f 4359 4349 4358 -f 4359 4358 4342 -f 4342 4358 4334 -f 4361 4414 4424 -f 4360 4390 4361 -f 4390 4415 4361 -f 4361 4415 4414 -f 9516 4417 2605 -f 2605 4417 4362 -f 4362 4363 2605 -f 4365 4364 9516 -f 9516 4364 4417 -f 4432 4365 4366 -f 4432 4364 4365 -f 4366 4431 4432 -f 4361 4431 4413 -f 4413 4431 4366 -f 4367 9520 4370 -f 4374 4742 4370 -f 4413 4366 4368 -f 4689 9520 4687 -f 4687 9520 2221 -f 4689 4690 9520 -f 9520 4690 4369 -f 9520 4369 4370 -f 4368 4366 2225 -f 4742 4371 4370 -f 4370 4371 4745 -f 4370 4745 4367 -f 4367 4745 9505 -f 4372 2226 4373 -f 4372 4373 4365 -f 4365 4373 2225 -f 4365 2225 4366 -f 4416 4412 4413 -f 4769 4721 4376 -f 4769 4376 4385 -f 4374 4370 4375 -f 4375 4370 4376 -f 4375 4376 4381 -f 4381 4376 4721 -f 4381 4721 4702 -f 4377 4762 4763 -f 4378 4379 4386 -f 4413 4368 4416 -f 4702 4380 4381 -f 4381 4380 4382 -f 4381 4382 4763 -f 4763 4382 4383 -f 4763 4383 4377 -f 4368 4384 4416 -f 4385 4376 4386 -f 4386 4376 4387 -f 4386 4387 4378 -f 4398 4397 4412 -f 4412 4397 4360 -f 4397 4395 4360 -f 4360 4395 4393 -f 4416 4404 4388 -f 4360 4393 4392 -f 4390 4411 4409 -f 4390 4409 4408 -f 4390 4408 4406 -f 4406 4405 4390 -f 4390 4405 4416 -f 4416 4405 4404 -f 4416 4388 4389 -f 4416 4389 4401 -f 4416 4401 4412 -f 4401 4400 4412 -f 4412 4400 4399 -f 4392 4391 4360 -f 4360 4391 4390 -f 4390 4391 4411 -f 4412 4399 4398 -f 4411 4391 6915 -f 6915 4391 4392 -f 6915 4392 6914 -f 6914 4392 4393 -f 6914 4393 4394 -f 4394 4393 4395 -f 4394 4395 4396 -f 4396 4395 4397 -f 4396 4397 6911 -f 6911 4397 4398 -f 6911 4398 6913 -f 6913 4398 4399 -f 6913 4399 6908 -f 6908 4399 4400 -f 6908 4400 4401 -f 4402 4401 4389 -f 4402 4389 4403 -f 4403 4389 4388 -f 4403 4388 6909 -f 6909 4388 4404 -f 6909 4404 6910 -f 6910 4404 4405 -f 6910 4405 6912 -f 6912 4405 4406 -f 6912 4406 4407 -f 4407 4406 4408 -f 4407 4408 4410 -f 4410 4408 4409 -f 4411 6917 4409 -f 4409 6917 4410 -f 4411 6915 6917 -f 4412 4360 4413 -f 4413 4360 4361 -f 4368 4414 4384 -f 4384 4414 4415 -f 4384 4415 4416 -f 4416 4415 4390 -f 4363 4362 2604 -f 2600 4434 4435 -f 4429 4427 4418 -f 4418 4427 4419 -f 4427 4421 4419 -f 4419 4421 4420 -f 4437 4423 4420 -f 4437 4420 4421 -f 4422 4423 4437 -f 4361 4438 4431 -f 4431 4438 4430 -f 4432 4433 4364 -f 4364 4433 4417 -f 4417 4433 4426 -f 2604 4362 4425 -f 4425 4362 4426 -f 4426 4362 4417 -f 4421 4427 4428 -f 4428 4427 4429 -f 4428 4429 2600 -f 4431 4430 4432 -f 4432 4430 4433 -f 4433 4430 4436 -f 4433 4436 4435 -f 4433 4435 4426 -f 4426 4435 4434 -f 4426 4434 4425 -f 2600 4435 4428 -f 4428 4435 4436 -f 4428 4436 4421 -f 4421 4436 4430 -f 4421 4430 4437 -f 4437 4430 4422 -f 4422 4430 4438 -f 4422 4438 4361 -f 4422 4361 4424 -f 6973 4440 4439 -f 4439 4440 2236 -f 4439 2236 4458 -f 2252 4468 4441 -f 4441 4468 6972 -f 6962 4442 4443 -f 4443 2267 6962 -f 6962 2267 2228 -f 6962 2228 6972 -f 6972 2228 4444 -f 6972 4444 4441 -f 6964 4448 4449 -f 4445 4446 2254 -f 4449 2230 6964 -f 6964 2230 2597 -f 6964 2597 4446 -f 4446 2597 2598 -f 4446 2598 2254 -f 4447 4469 6970 -f 6970 4469 2259 -f 6970 2259 6971 -f 4449 4448 6963 -f 4449 6963 4450 -f 4450 6963 4451 -f 4450 4451 2233 -f 2233 4451 4452 -f 2233 4452 4453 -f 4453 4452 6966 -f 4453 6966 2242 -f 2242 6966 6968 -f 2242 6968 2241 -f 4455 4454 2239 -f 2239 4456 4455 -f 4455 4456 6968 -f 6968 4456 2241 -f 4457 4458 2236 -f 2236 2238 4457 -f 4457 2238 4454 -f 4454 2238 2239 -f 4440 6973 2235 -f 2235 6973 6976 -f 2235 6976 4459 -f 2235 4459 4460 -f 4460 4459 6979 -f 4460 6979 4462 -f 4462 6979 4461 -f 4462 4461 4463 -f 4462 4463 2234 -f 2234 4463 4464 -f 2234 4464 4466 -f 4466 4464 4465 -f 4466 4465 2243 -f 2243 4465 4467 -f 2243 4467 2244 -f 2244 4467 2252 -f 2252 4467 4468 -f 4469 4447 4470 -f 4469 4470 2260 -f 2260 4470 4471 -f 2260 4471 2261 -f 2261 4471 6967 -f 2261 6967 4472 -f 4472 6967 6965 -f 4472 6965 4473 -f 4472 4473 4474 -f 4474 4473 4475 -f 4474 4475 2257 -f 2257 4475 4476 -f 2257 4476 2258 -f 2258 4476 6969 -f 2258 6969 4477 -f 4477 6969 4446 -f 4477 4446 4445 -f 4442 6962 6983 -f 4442 6983 4478 -f 4478 6983 6982 -f 4478 6982 2262 -f 2262 6982 6980 -f 2262 6980 4479 -f 4479 6980 6981 -f 4479 6981 4480 -f 4480 6981 6978 -f 4480 6978 2265 -f 6977 6975 2264 -f 2264 4481 6977 -f 6977 4481 6978 -f 6978 4481 2265 -f 6974 6971 2259 -f 2259 4482 6974 -f 6974 4482 6975 -f 6975 4482 2264 -f 4487 4488 4655 -f 4619 4483 4618 -f 4618 4483 4647 -f 4619 4484 4483 -f 4483 4484 4650 -f 4650 4484 4620 -f 4650 4620 4485 -f 4485 4620 4623 -f 4623 4486 4485 -f 4487 4486 4621 -f 4623 4621 4486 -f 4486 4487 4655 -f 4489 4490 4654 -f 4488 4590 4655 -f 4488 4616 4590 -f 4590 4616 4489 -f 4489 4616 4490 -f 4654 4490 4593 -f 4593 4490 4491 -f 4593 4491 2607 -f 4618 4647 4646 -f 4563 4492 4646 -f 4646 4492 4615 -f 4646 4615 4618 -f 4493 4547 4594 -f 4557 4494 4526 -f 4557 4495 4494 -f 4494 4495 4556 -f 4494 4556 4502 -f 4535 4533 4496 -f 4527 4496 4529 -f 4533 4532 4496 -f 4496 4532 4497 -f 4496 4497 4529 -f 4608 4549 4594 -f 4594 4549 4498 -f 4594 4498 4493 -f 4547 4545 4594 -f 4594 4545 4499 -f 4594 4499 4509 -f 4509 4499 4500 -f 4509 4500 4501 -f 4535 4496 4536 -f 4536 4496 4633 -f 4536 4633 4537 -f 4502 4555 4494 -f 4494 4555 4552 -f 4494 4552 4503 -f 4549 4608 4506 -f 4552 4504 4503 -f 4503 4504 4505 -f 4503 4505 4606 -f 4606 4505 4506 -f 4606 4506 4608 -f 4635 4507 4539 -f 4635 4539 4633 -f 4633 4539 4538 -f 4633 4538 4537 -f 4501 4508 4509 -f 4509 4508 4510 -f 4509 4510 4634 -f 4634 4510 4507 -f 4634 4507 4635 -f 4627 4512 4595 -f 4601 4605 4591 -f 4591 4605 4511 -f 4596 4513 4514 -f 4511 4605 4603 -f 4511 4603 4596 -f 4511 4596 4514 -f 4513 4512 4514 -f 4513 4597 4512 -f 4512 4597 4599 -f 4512 4599 4595 -f 4627 4595 4509 -f 4509 4595 4594 -f 4584 4515 4609 -f 4584 4609 4516 -f 4645 4632 4517 -f 4517 4641 4645 -f 4561 4518 6943 -f 4519 4562 6941 -f 6943 4518 4519 -f 4519 4518 4520 -f 4519 4520 4562 -f 4561 6943 4521 -f 4521 6943 6938 -f 4521 6938 4522 -f 4522 6938 6937 -f 4522 6937 4523 -f 4523 6937 4558 -f 4558 6937 4524 -f 4558 4524 4525 -f 4525 4524 4559 -f 4559 4524 6932 -f 4559 6932 4526 -f 4562 4527 6941 -f 6941 4527 4528 -f 4528 4527 4529 -f 4528 4529 4530 -f 4530 4529 4497 -f 4530 4497 4531 -f 4531 4497 4532 -f 4531 4532 6944 -f 6944 4532 4533 -f 6944 4533 4534 -f 4534 4533 4535 -f 4534 4535 6949 -f 6949 4535 4536 -f 6949 4536 6947 -f 6947 4536 4537 -f 6947 4537 6948 -f 6948 4537 4538 -f 6948 4538 6942 -f 6942 4538 4539 -f 6942 4539 4540 -f 4540 4539 4507 -f 4540 4507 6940 -f 6940 4507 4510 -f 6940 4510 4541 -f 4541 4510 4508 -f 4541 4508 4542 -f 4542 4508 4501 -f 4542 4501 4543 -f 4543 4501 4500 -f 4543 4500 4544 -f 4544 4500 4499 -f 4544 4499 6939 -f 6939 4499 4545 -f 6939 4545 4546 -f 4546 4545 4547 -f 4546 4547 6936 -f 6936 4547 4493 -f 6936 4493 4548 -f 4548 4493 4498 -f 4548 4498 4550 -f 4550 4498 4549 -f 4550 4549 4551 -f 4551 4549 4506 -f 4551 4506 6933 -f 6933 4506 4505 -f 6933 4505 6934 -f 6934 4505 4504 -f 6934 4504 4553 -f 4553 4504 4552 -f 4553 4552 4554 -f 4554 4552 4555 -f 4554 4555 6945 -f 6945 4555 4502 -f 6945 4502 6931 -f 6931 4502 4556 -f 6931 4556 6935 -f 6935 4556 4495 -f 6935 4495 6946 -f 6946 4495 4557 -f 6946 4557 6932 -f 6932 4557 4526 -f 4559 4526 4494 -f 4560 4558 4525 -f 4494 4560 4559 -f 4559 4560 4525 -f 4520 4518 4566 -f 4566 4518 4561 -f 4614 4521 4522 -f 4614 4522 4560 -f 4560 4522 4523 -f 4560 4523 4558 -f 4566 4496 4520 -f 4520 4496 4562 -f 4496 4527 4562 -f 4492 4563 4610 -f 4610 4563 4564 -f 4610 4564 4611 -f 4611 4564 4643 -f 4611 4643 4612 -f 4612 4643 4642 -f 4612 4642 4613 -f 4613 4642 4640 -f 4613 4640 4565 -f 4565 4640 4639 -f 4565 4639 4638 -f 4565 4638 4614 -f 4614 4638 4566 -f 4614 4566 4521 -f 4521 4566 4561 -f 4600 4598 4576 -f 2607 4572 4601 -f 4601 4572 4602 -f 4573 4575 4567 -f 4567 4575 4568 -f 4567 4568 4569 -f 4569 4568 4570 -f 4569 4570 4571 -f 4571 4570 4604 -f 4571 4604 4572 -f 4572 4604 4602 -f 4575 4573 4574 -f 4576 4598 4574 -f 4574 4598 4575 -f 4600 4576 4577 -f 4600 4577 4579 -f 4579 4577 4578 -f 4622 4580 4578 -f 4578 4580 4579 -f 4580 4622 4581 -f 4581 4622 4582 -f 4583 4582 4622 -f 4583 4617 4582 -f 4582 4617 4607 -f 4515 4584 4617 -f 4617 4584 4607 -f 4636 4632 4645 -f 4645 4644 4636 -f 4636 4644 4648 -f 4636 4648 4585 -f 4648 4653 4585 -f 4585 4653 4637 -f 4637 4653 4652 -f 4637 4652 4631 -f 4652 4651 4631 -f 4631 4651 4586 -f 4649 4624 4625 -f 4651 4649 4586 -f 4586 4649 4625 -f 4589 4628 4588 -f 4589 4588 4656 -f 4624 4649 4657 -f 4624 4657 4587 -f 4587 4657 4656 -f 4587 4656 4588 -f 4590 4629 4589 -f 4589 4629 4626 -f 4589 4626 4628 -f 4629 4590 4489 -f 4629 4489 4630 -f 4630 4489 4592 -f 4630 4592 4591 -f 4591 4592 4593 -f 4580 4594 4579 -f 4579 4594 4595 -f 4579 4595 4600 -f 4600 4595 4599 -f 4568 4575 4596 -f 4596 4575 4513 -f 4513 4575 4597 -f 4597 4575 4598 -f 4597 4598 4599 -f 4599 4598 4600 -f 4601 4602 4605 -f 4605 4602 4604 -f 4568 4596 4570 -f 4570 4596 4603 -f 4570 4603 4604 -f 4604 4603 4605 -f 4608 4582 4606 -f 4594 4580 4608 -f 4584 4503 4607 -f 4607 4503 4606 -f 4607 4606 4582 -f 4580 4581 4608 -f 4608 4581 4582 -f 4516 4494 4584 -f 4584 4494 4503 -f 4609 4492 4610 -f 4609 4610 4516 -f 4610 4611 4516 -f 4611 4612 4516 -f 4612 4613 4516 -f 4613 4565 4516 -f 4516 4565 4614 -f 4516 4614 4560 -f 4516 4560 4494 -f 4515 4615 4609 -f 4609 4615 4492 -f 4515 4617 4615 -f 4615 4617 4618 -f 4616 4488 4573 -f 4573 4488 4487 -f 4573 4487 4574 -f 4574 4487 4576 -f 4576 4487 4621 -f 4576 4621 4577 -f 4617 4484 4619 -f 4617 4619 4618 -f 4617 4583 4484 -f 4484 4583 4620 -f 4620 4583 4622 -f 4573 4567 4616 -f 4616 4567 4569 -f 4616 4569 4490 -f 4490 4569 4571 -f 4490 4571 4572 -f 4490 4572 4491 -f 4491 4572 2607 -f 4577 4621 4578 -f 4578 4621 4622 -f 4622 4621 4623 -f 4622 4623 4620 -f 4512 4586 4625 -f 4587 4512 4624 -f 4624 4512 4625 -f 4629 4511 4626 -f 4626 4511 4628 -f 4512 4587 4588 -f 4512 4588 4628 -f 4509 4586 4627 -f 4627 4586 4512 -f 4514 4512 4628 -f 4629 4630 4511 -f 4511 4630 4591 -f 4628 4511 4514 -f 4586 4509 4634 -f 4635 4637 4631 -f 4633 4632 4636 -f 4633 4636 4635 -f 4635 4631 4634 -f 4634 4631 4586 -f 4635 4636 4585 -f 4635 4585 4637 -f 4496 4517 4633 -f 4633 4517 4632 -f 4517 4496 4641 -f 4496 4566 4641 -f 4566 4638 4641 -f 4638 4639 4641 -f 4641 4639 4640 -f 4641 4640 4642 -f 4641 4642 4643 -f 4641 4643 4564 -f 4641 4564 4563 -f 4646 4645 4563 -f 4563 4645 4641 -f 4644 4645 4647 -f 4647 4645 4646 -f 4644 4647 4648 -f 4648 4647 4653 -f 4486 4649 4485 -f 4485 4649 4651 -f 4485 4651 4650 -f 4650 4651 4652 -f 4650 4652 4483 -f 4483 4652 4653 -f 4483 4653 4647 -f 4593 4592 4654 -f 4654 4592 4489 -f 4590 4589 4655 -f 4655 4589 4656 -f 4655 4656 4486 -f 4486 4656 4657 -f 4486 4657 4649 -f 2222 4325 7585 -f 7585 4325 4658 -f 4660 4659 2222 -f 4660 2222 7585 -f 7587 4661 4660 -f 4660 4661 2223 -f 4660 2223 4659 -f 7587 4662 4661 -f 4665 4662 7587 -f 4665 4663 4662 -f 4665 4664 4663 -f 4665 4666 4664 -f 4665 4667 4666 -f 4666 4667 4668 -f 4668 4667 4671 -f 4668 4671 4669 -f 4669 4671 4670 -f 4670 4671 7588 -f 4670 7588 4672 -f 4672 7588 4673 -f 4673 7588 4674 -f 4673 4674 7586 -f 4673 7586 4675 -f 4675 7586 7584 -f 4675 7584 4676 -f 4676 7584 4677 -f 4676 4677 4326 -f 4326 4677 4678 -f 4678 4324 4326 -f 4658 4325 4324 -f 4658 4324 4678 -f 4686 7581 7580 -f 7580 7579 4327 -f 4327 7579 7578 -f 4327 7578 4679 -f 4679 7578 7577 -f 4679 7577 4328 -f 4328 7577 7576 -f 4328 7576 4680 -f 4680 7576 7583 -f 4680 7583 4681 -f 7582 4681 7583 -f 4683 4682 7582 -f 7582 4682 4681 -f 4682 4683 4684 -f 4684 4683 4685 -f 4684 4685 4686 -f 2221 9494 4687 -f 4687 9494 4748 -f 4687 4748 4689 -f 4689 4748 4688 -f 4689 4688 4690 -f 4690 4688 4747 -f 4690 4747 4369 -f 4369 4747 4691 -f 4369 4691 4370 -f 4370 4691 4752 -f 4370 4752 4376 -f 4376 4752 4755 -f 4796 4794 4702 -f 4692 4918 4697 -f 4904 4903 4721 -f 4721 4903 4693 -f 4721 4693 4695 -f 4837 4885 4697 -f 4697 4885 4884 -f 4697 4884 4881 -f 4867 4753 4868 -f 4868 4753 4694 -f 4695 4901 4721 -f 4721 4901 4714 -f 4794 4696 4702 -f 4702 4696 4793 -f 4702 4793 4791 -f 4881 4880 4697 -f 4697 4880 4877 -f 4697 4877 4875 -f 4918 4698 4697 -f 4697 4698 4916 -f 4697 4916 4718 -f 4904 4721 4699 -f 4699 4721 4753 -f 4699 4753 4700 -f 4893 4701 4702 -f 4702 4701 4703 -f 4702 4703 4697 -f 4697 4703 4920 -f 4697 4920 4692 -f 4875 4872 4697 -f 4697 4872 4871 -f 4697 4871 4753 -f 4753 4871 4704 -f 4753 4704 4694 -f 4753 4739 4709 -f 4893 4702 4895 -f 4895 4702 4791 -f 4895 4791 4705 -f 4705 4791 4822 -f 4705 4822 4706 -f 4706 4707 4705 -f 4705 4707 4820 -f 4705 4820 4708 -f 4709 4710 4753 -f 4753 4710 4907 -f 4753 4907 4700 -f 4708 4711 4705 -f 4705 4711 4712 -f 4705 4712 4897 -f 4713 4814 4714 -f 4714 4814 4813 -f 4714 4813 4811 -f 4721 4722 4808 -f 4715 4798 4702 -f 4702 4798 4716 -f 4702 4716 4796 -f 4842 4717 4718 -f 4811 4719 4714 -f 4714 4719 4720 -f 4714 4720 4721 -f 4721 4720 4809 -f 4721 4809 4722 -f 4808 4807 4721 -f 4721 4807 4723 -f 4721 4723 4724 -f 4724 4804 4721 -f 4721 4804 4725 -f 4721 4725 4726 -f 4911 4910 4849 -f 4849 4910 4739 -f 4849 4739 4851 -f 4713 4714 4727 -f 4727 4714 4728 -f 4727 4728 4819 -f 4819 4728 4729 -f 4729 4728 4898 -f 4729 4898 4712 -f 4712 4898 4897 -f 4740 4730 4739 -f 4739 4730 4853 -f 4739 4853 4851 -f 4846 4731 4718 -f 4718 4731 4732 -f 4718 4732 4842 -f 4717 4733 4718 -f 4718 4733 4734 -f 4718 4734 4697 -f 4697 4734 4839 -f 4697 4839 4837 -f 4726 4735 4721 -f 4721 4735 4801 -f 4721 4801 4702 -f 4702 4801 4736 -f 4702 4736 4715 -f 4867 4866 4753 -f 4753 4866 4865 -f 4753 4865 4864 -f 4718 4737 4846 -f 4846 4737 4913 -f 4846 4913 4847 -f 4847 4913 4849 -f 4849 4913 4911 -f 4864 4738 4753 -f 4753 4738 4862 -f 4753 4862 4860 -f 4860 4857 4753 -f 4753 4857 4855 -f 4753 4855 4739 -f 4739 4855 4854 -f 4739 4854 4740 -f 2227 9505 4745 -f 9611 4418 4744 -f 4381 4741 4375 -f 4375 4741 4750 -f 4375 4750 4374 -f 4374 4750 4743 -f 4374 4743 4742 -f 4742 4743 4749 -f 4742 4749 4371 -f 4371 4749 4746 -f 4371 4746 4745 -f 4745 4746 4744 -f 4745 4744 2227 -f 2227 4744 4418 -f 9611 4744 4751 -f 4751 4744 4746 -f 4751 4746 4749 -f 9612 4691 4747 -f 4747 4688 9612 -f 9612 4688 4748 -f 9612 4748 9494 -f 4749 4743 4751 -f 4751 4743 4750 -f 4751 4750 4741 -f 4751 4755 9612 -f 9612 4755 4752 -f 9612 4752 4691 -f 4753 4755 4697 -f 4697 4755 4751 -f 4697 4751 4757 -f 4741 4754 4751 -f 4751 4754 4761 -f 4751 4761 4760 -f 4760 4759 4751 -f 4751 4759 4758 -f 4751 4758 4757 -f 4753 4768 4755 -f 4755 4768 4767 -f 4755 4767 4756 -f 4766 4765 4756 -f 4756 4765 4764 -f 4756 4764 4755 -f 4702 4697 4757 -f 4702 4757 4380 -f 4380 4757 4758 -f 4380 4758 4382 -f 4382 4758 4759 -f 4382 4759 4383 -f 4383 4759 4760 -f 4383 4760 4377 -f 4377 4760 4761 -f 4377 4761 4762 -f 4762 4761 4754 -f 4762 4754 4763 -f 4763 4754 4741 -f 4763 4741 4381 -f 4376 4755 4764 -f 4376 4764 4387 -f 4387 4764 4765 -f 4387 4765 4378 -f 4378 4765 4766 -f 4378 4766 4379 -f 4379 4766 4756 -f 4379 4756 4386 -f 4386 4756 4767 -f 4386 4767 4385 -f 4385 4767 4768 -f 4385 4768 4769 -f 4769 4768 4753 -f 4769 4753 4721 -f 4782 4770 4792 -f 4790 4770 4782 -f 4782 4795 4797 -f 4771 4795 4782 -f 4792 4771 4782 -f 4782 4799 4774 -f 4772 4799 4782 -f 4797 4772 4782 -f 4782 4773 4802 -f 4800 4773 4782 -f 4774 4800 4782 -f 4782 4803 4805 -f 4775 4803 4782 -f 4802 4775 4782 -f 4782 4806 4780 -f 4776 4806 4782 -f 4805 4776 4782 -f 4782 4779 4777 -f 4778 4779 4782 -f 4780 4778 4782 -f 4782 4781 4812 -f 4810 4781 4782 -f 4777 4810 4782 -f 4782 4816 4783 -f 4815 4816 4782 -f 4812 4815 4782 -f 4782 4818 4785 -f 4817 4818 4782 -f 4783 4817 4782 -f 4782 4784 4787 -f 4786 4784 4782 -f 4785 4786 4782 -f 4782 4821 4789 -f 4788 4821 4782 -f 4787 4788 4782 -f 4789 4790 4782 -f 4790 4791 4770 -f 4770 4791 4793 -f 4770 4793 4792 -f 4792 4793 4696 -f 4792 4696 4771 -f 4771 4696 4794 -f 4771 4794 4795 -f 4795 4794 4796 -f 4795 4796 4797 -f 4797 4796 4716 -f 4797 4716 4772 -f 4772 4716 4798 -f 4772 4798 4799 -f 4799 4798 4715 -f 4799 4715 4774 -f 4774 4715 4736 -f 4774 4736 4800 -f 4800 4736 4801 -f 4800 4801 4773 -f 4773 4801 4735 -f 4773 4735 4802 -f 4802 4735 4726 -f 4802 4726 4775 -f 4775 4726 4725 -f 4775 4725 4803 -f 4803 4725 4804 -f 4803 4804 4805 -f 4805 4804 4724 -f 4805 4724 4776 -f 4776 4724 4723 -f 4776 4723 4806 -f 4806 4723 4807 -f 4806 4807 4780 -f 4780 4807 4808 -f 4780 4808 4778 -f 4778 4808 4722 -f 4778 4722 4779 -f 4779 4722 4809 -f 4779 4809 4777 -f 4777 4809 4720 -f 4777 4720 4810 -f 4810 4720 4719 -f 4810 4719 4781 -f 4781 4719 4811 -f 4781 4811 4812 -f 4812 4811 4813 -f 4812 4813 4815 -f 4815 4813 4814 -f 4815 4814 4816 -f 4816 4814 4713 -f 4816 4713 4783 -f 4783 4713 4727 -f 4783 4727 4817 -f 4817 4727 4819 -f 4817 4819 4818 -f 4818 4819 4729 -f 4818 4729 4785 -f 4785 4729 4712 -f 4785 4712 4786 -f 4786 4712 4711 -f 4786 4711 4784 -f 4784 4711 4708 -f 4784 4708 4787 -f 4787 4708 4820 -f 4787 4820 4788 -f 4788 4820 4707 -f 4788 4707 4821 -f 4821 4707 4706 -f 4821 4706 4789 -f 4789 4706 4822 -f 4789 4822 4790 -f 4790 4822 4791 -f 4836 4838 4840 -f 4823 4838 4836 -f 4836 4824 4841 -f 4825 4824 4836 -f 4840 4825 4836 -f 4836 4844 4845 -f 4843 4844 4836 -f 4841 4843 4836 -f 4836 4826 4848 -f 4827 4826 4836 -f 4845 4827 4836 -f 4836 4852 4828 -f 4850 4852 4836 -f 4848 4850 4836 -f 4836 4856 4829 -f 4830 4856 4836 -f 4828 4830 4836 -f 4836 4859 4861 -f 4858 4859 4836 -f 4829 4858 4836 -f 4836 4831 4832 -f 4863 4831 4836 -f 4861 4863 4836 -f 4836 4869 4870 -f 4833 4869 4836 -f 4832 4833 4836 -f 4836 4834 4873 -f 4835 4834 4836 -f 4870 4835 4836 -f 4836 4876 4878 -f 4874 4876 4836 -f 4873 4874 4836 -f 4836 4882 4883 -f 4879 4882 4836 -f 4878 4879 4836 -f 4883 4823 4836 -f 4823 4837 4838 -f 4838 4837 4839 -f 4838 4839 4840 -f 4840 4839 4734 -f 4840 4734 4825 -f 4825 4734 4733 -f 4825 4733 4824 -f 4824 4733 4717 -f 4824 4717 4841 -f 4841 4717 4842 -f 4841 4842 4843 -f 4843 4842 4732 -f 4843 4732 4844 -f 4844 4732 4731 -f 4844 4731 4845 -f 4845 4731 4846 -f 4845 4846 4827 -f 4827 4846 4847 -f 4827 4847 4826 -f 4826 4847 4849 -f 4826 4849 4848 -f 4848 4849 4851 -f 4848 4851 4850 -f 4850 4851 4853 -f 4850 4853 4852 -f 4852 4853 4730 -f 4852 4730 4828 -f 4828 4730 4740 -f 4828 4740 4830 -f 4830 4740 4854 -f 4830 4854 4856 -f 4856 4854 4855 -f 4856 4855 4829 -f 4829 4855 4857 -f 4829 4857 4858 -f 4858 4857 4860 -f 4858 4860 4859 -f 4859 4860 4862 -f 4859 4862 4861 -f 4861 4862 4738 -f 4861 4738 4863 -f 4863 4738 4864 -f 4863 4864 4831 -f 4831 4864 4865 -f 4831 4865 4832 -f 4832 4865 4866 -f 4832 4866 4833 -f 4833 4866 4867 -f 4833 4867 4869 -f 4869 4867 4868 -f 4869 4868 4870 -f 4870 4868 4694 -f 4870 4694 4835 -f 4835 4694 4704 -f 4835 4704 4834 -f 4834 4704 4871 -f 4834 4871 4873 -f 4873 4871 4872 -f 4873 4872 4874 -f 4874 4872 4875 -f 4874 4875 4876 -f 4876 4875 4877 -f 4876 4877 4878 -f 4878 4877 4880 -f 4878 4880 4879 -f 4879 4880 4881 -f 4879 4881 4882 -f 4882 4881 4884 -f 4882 4884 4883 -f 4883 4884 4885 -f 4883 4885 4823 -f 4823 4885 4837 -f 4891 4892 4894 -f 4894 4896 4891 -f 4891 4886 4899 -f 4896 4886 4891 -f 4899 4887 4891 -f 4891 4900 4902 -f 4887 4900 4891 -f 4902 4888 4891 -f 4905 4906 4891 -f 4888 4905 4891 -f 4908 4909 4891 -f 4906 4908 4891 -f 4891 4912 4889 -f 4909 4912 4891 -f 4891 4914 4915 -f 4889 4914 4891 -f 4891 4890 4917 -f 4915 4890 4891 -f 4917 4919 4891 -f 4919 4892 4891 -f 4892 4703 4701 -f 4892 4701 4894 -f 4894 4701 4893 -f 4894 4893 4895 -f 4894 4895 4896 -f 4896 4895 4705 -f 4896 4705 4897 -f 4896 4897 4886 -f 4886 4897 4898 -f 4886 4898 4899 -f 4899 4898 4728 -f 4899 4728 4887 -f 4887 4728 4714 -f 4887 4714 4900 -f 4900 4714 4901 -f 4900 4901 4902 -f 4902 4901 4695 -f 4902 4695 4693 -f 4902 4693 4888 -f 4888 4693 4903 -f 4888 4903 4904 -f 4888 4904 4905 -f 4905 4904 4699 -f 4905 4699 4906 -f 4906 4699 4700 -f 4906 4700 4907 -f 4906 4907 4908 -f 4908 4907 4710 -f 4908 4710 4909 -f 4909 4710 4709 -f 4909 4709 4739 -f 4909 4739 4912 -f 4912 4739 4910 -f 4912 4910 4911 -f 4912 4911 4889 -f 4889 4911 4914 -f 4914 4911 4913 -f 4914 4913 4915 -f 4915 4913 4737 -f 4915 4737 4718 -f 4915 4718 4890 -f 4890 4718 4916 -f 4890 4916 4917 -f 4917 4916 4698 -f 4917 4698 4918 -f 4917 4918 4919 -f 4919 4918 4692 -f 4919 4692 4920 -f 4919 4920 4892 -f 4892 4920 4703 -f 9578 4921 7325 -f 7325 4921 4922 -f 7299 7000 7020 -f 7325 4922 7298 -f 7325 7298 7020 -f 7020 7298 7299 -f 7021 4923 9519 -f 4923 7070 9519 -f 9519 7070 7388 -f 7069 4923 7021 -f 7069 4926 7067 -f 4926 7069 7021 -f 7066 4924 7018 -f 7066 7018 4925 -f 7066 7067 4924 -f 4924 7067 4926 -f 7026 7064 7018 -f 7018 7064 4925 -f 7388 7070 7387 -f 2250 9534 4927 -f 4927 9534 4928 -f 9532 4931 7088 -f 9532 7088 9557 -f 9557 7088 4928 -f 9557 4928 9534 -f 4930 7123 4929 -f 4930 4929 7125 -f 4930 7125 7128 -f 4930 7128 9532 -f 9532 7128 4931 -f 4934 7123 9531 -f 5013 7120 7119 -f 5013 7119 4932 -f 9531 4933 4934 -f 4934 4933 5186 -f 4934 5186 7119 -f 7119 5186 5185 -f 7119 5185 4932 -f 9531 7123 4930 -f 7116 2354 7113 -f 7113 2354 2364 -f 2354 7116 7118 -f 2354 7120 5013 -f 2354 7118 7120 -f 7113 2364 2363 -f 7113 2363 4935 -f 4935 2363 2362 -f 4935 2362 7094 -f 6292 4941 6222 -f 6281 4939 4936 -f 4937 6363 6360 -f 6363 4937 5425 -f 6360 6358 4937 -f 4941 6287 4937 -f 4937 6287 4939 -f 4939 6287 4938 -f 4938 4936 4939 -f 6279 4939 6281 -f 6355 4942 6229 -f 6227 4940 4937 -f 4937 4940 6225 -f 4937 6225 4941 -f 4941 6225 6223 -f 4941 6223 6222 -f 4937 6358 6357 -f 4937 6357 6227 -f 6227 6357 6355 -f 6227 6355 6229 -f 6292 6222 6220 -f 4942 6355 4944 -f 6204 4943 6220 -f 6220 4943 6292 -f 6340 6231 4944 -f 4944 6231 4942 -f 4946 6326 4947 -f 6322 5916 4945 -f 6322 4945 5915 -f 6322 5915 6320 -f 6320 5915 4978 -f 5916 6322 6323 -f 5916 6323 5808 -f 5808 6323 6325 -f 4946 4947 6325 -f 6325 4947 5808 -f 6326 6295 4947 -f 4947 6295 4948 -f 4948 6295 4949 -f 4951 5204 5203 -f 6295 6296 4949 -f 4949 6296 4951 -f 4949 4951 4950 -f 4950 4951 5203 -f 6232 6269 4951 -f 4952 6166 4955 -f 4952 4955 4957 -f 6232 4965 6201 -f 6232 6201 6255 -f 6255 6201 6164 -f 6255 6164 6257 -f 6257 6164 4953 -f 6257 4953 4954 -f 4954 4953 6166 -f 4954 6166 4952 -f 4957 4955 4956 -f 4957 4956 4958 -f 4958 4956 4960 -f 4958 4960 6252 -f 6252 4960 6172 -f 6252 6172 4959 -f 4959 6172 6170 -f 6175 6250 4959 -f 6175 4959 6170 -f 4962 4963 4961 -f 4962 4961 6175 -f 6175 4961 6250 -f 6174 4964 4962 -f 4962 4964 4963 -f 4964 6174 6176 -f 4964 6176 6180 -f 4965 6232 4951 -f 4965 4951 6296 -f 6193 6300 4968 -f 6193 4968 6191 -f 4965 6296 4966 -f 4966 6296 6337 -f 4966 6337 4967 -f 4967 6337 6297 -f 4967 6297 6192 -f 6192 6297 6300 -f 6192 6300 6193 -f 6191 4968 4969 -f 6191 4969 6190 -f 6190 4969 6303 -f 6190 6303 6186 -f 6186 6303 6308 -f 6186 6308 6185 -f 6185 6308 6306 -f 6305 4971 6185 -f 6305 6185 6306 -f 4974 4975 4970 -f 4974 4970 6305 -f 6305 4970 4971 -f 4972 4973 4974 -f 4974 4973 4975 -f 4973 4972 6309 -f 4973 6309 6314 -f 4982 4977 4976 -f 4976 4977 4978 -f 4978 4977 6320 -f 4980 6317 4979 -f 4979 6317 4981 -f 4979 4981 4976 -f 4976 4981 4982 -f 6016 5433 6020 -f 4983 6020 5433 -f 6021 5998 6152 -f 6152 4984 6021 -f 6369 5219 6368 -f 5219 6369 5346 -f 5346 6369 4985 -f 4978 5915 5917 -f 5763 5764 4976 -f 5745 9521 4986 -f 4986 9521 9502 -f 5745 4986 4989 -f 4989 4986 4987 -f 4989 4987 5236 -f 4978 5917 4976 -f 4976 5764 4979 -f 4979 5764 4988 -f 4988 5764 5752 -f 4988 5752 4991 -f 5917 5761 5763 -f 5236 5237 4989 -f 4989 5237 5238 -f 4989 5238 5239 -f 5917 5763 4976 -f 5239 5241 4989 -f 4989 5241 4990 -f 4989 4990 5752 -f 5752 4990 5243 -f 5752 5243 4991 -f 5439 5889 4992 -f 4992 5889 5892 -f 4992 5892 5946 -f 5946 5892 5893 -f 5946 5893 4993 -f 4993 5893 5894 -f 4993 5894 4994 -f 4994 5894 4995 -f 4994 4995 4996 -f 4996 4995 4997 -f 4996 4997 5943 -f 5943 4997 5895 -f 5943 5895 5942 -f 5942 5895 4998 -f 5942 4998 5941 -f 5941 4998 5897 -f 5941 5897 4999 -f 4999 5897 5899 -f 4999 5899 5940 -f 5940 5899 5000 -f 5940 5000 5938 -f 5938 5000 5901 -f 5938 5901 5001 -f 5001 5901 5002 -f 5001 5002 5003 -f 5003 5002 5004 -f 5003 5004 5937 -f 5937 5004 5005 -f 5937 5005 5935 -f 5935 5005 5006 -f 5935 5006 5933 -f 5933 5006 5906 -f 5933 5906 5932 -f 5932 5906 5007 -f 5932 5007 5008 -f 5008 5007 5907 -f 5008 5907 5931 -f 5931 5907 5908 -f 5931 5908 5928 -f 5928 5908 5009 -f 5928 5009 5010 -f 5010 5009 5910 -f 5010 5910 5927 -f 5927 5910 5011 -f 5927 5011 5925 -f 5925 5011 5912 -f 5925 5912 5012 -f 5012 5912 5914 -f 5163 5103 5147 -f 5129 5013 4932 -f 5753 5014 5027 -f 5027 5014 6773 -f 6757 5015 5087 -f 5087 5015 6756 -f 2293 5023 5753 -f 5753 5023 5016 -f 5753 5016 5014 -f 6773 6772 5027 -f 5027 6772 6771 -f 5027 6771 6769 -f 6769 6768 5027 -f 5027 6768 5017 -f 5027 5017 5026 -f 6756 6755 5087 -f 5087 6755 6754 -f 5087 6754 5018 -f 5018 6754 6790 -f 6790 6789 5018 -f 5018 6789 5019 -f 5018 5019 6787 -f 5020 2293 5021 -f 5021 2293 6779 -f 5020 6775 2293 -f 2293 6775 5022 -f 2293 5022 5023 -f 5024 6760 5087 -f 5087 6760 6758 -f 5087 6758 6757 -f 6787 6785 5018 -f 5018 6785 5025 -f 5018 5025 6783 -f 5026 6765 5027 -f 5027 6765 5028 -f 5027 5028 5087 -f 5087 5028 6762 -f 5087 6762 5024 -f 6783 6781 5018 -f 5018 6781 6780 -f 5018 6780 2293 -f 2293 6780 5029 -f 2293 5029 6779 -f 5426 5030 6716 -f 5426 6716 5032 -f 6703 6702 5157 -f 5030 5426 6717 -f 6717 5426 5046 -f 6717 5046 5047 -f 6716 5031 5032 -f 5032 5031 6713 -f 5032 6713 6711 -f 6711 6709 5032 -f 5032 6709 5033 -f 5032 5033 5034 -f 5049 6706 5157 -f 5157 6706 5035 -f 5157 5035 6703 -f 6700 5144 5036 -f 5036 5144 5157 -f 5036 5157 5037 -f 5037 5157 6702 -f 6700 5038 5144 -f 5144 5038 6731 -f 5144 6731 5039 -f 5039 5040 5144 -f 5144 5040 5041 -f 5144 5041 5042 -f 5145 6723 5046 -f 5046 6723 5043 -f 5046 5043 5044 -f 5044 5045 5046 -f 5046 5045 6720 -f 5046 6720 5047 -f 5034 6708 5032 -f 5032 6708 5048 -f 5032 5048 5157 -f 5157 5048 6707 -f 5157 6707 5049 -f 5042 6726 5144 -f 5144 6726 5050 -f 5144 5050 6724 -f 5052 6465 6506 -f 6503 5057 6505 -f 6505 5057 5052 -f 6505 5052 5051 -f 5051 5052 6506 -f 6485 5053 5059 -f 5059 5053 5054 -f 5054 5055 5059 -f 5059 5055 5056 -f 5059 5056 5185 -f 5185 5056 6481 -f 5185 6481 6478 -f 6503 6501 5057 -f 5057 6501 6499 -f 5057 6499 6498 -f 6498 5058 5057 -f 5057 5058 6497 -f 5057 6497 6494 -f 5061 6487 5059 -f 5059 6487 5060 -f 5059 5060 6485 -f 6494 6493 5057 -f 5057 6493 6491 -f 5057 6491 5059 -f 5059 6491 6489 -f 5059 6489 5061 -f 6469 6468 5141 -f 6478 5062 5185 -f 5185 5062 5063 -f 5185 5063 5064 -f 5064 5063 5065 -f 5065 6476 5064 -f 5064 6476 5066 -f 5064 5066 5067 -f 5067 5068 5064 -f 5064 5068 6471 -f 5064 6471 5141 -f 5141 6471 5069 -f 5141 5069 6469 -f 5105 6593 5085 -f 6599 6598 5163 -f 5163 6598 5070 -f 5163 5070 5105 -f 5105 5070 6595 -f 5105 6595 6593 -f 5079 5081 5071 -f 5071 6621 5079 -f 5079 6621 6617 -f 5079 6617 5075 -f 5075 6617 5072 -f 5075 5072 6616 -f 6616 6614 5075 -f 5075 6614 5073 -f 5075 5073 5074 -f 5074 5076 5075 -f 5075 5076 6609 -f 5075 6609 6608 -f 5078 5077 5163 -f 5163 5077 6601 -f 5163 6601 6599 -f 6607 6606 5163 -f 5163 6606 6604 -f 5163 6604 5078 -f 5027 5080 5079 -f 5079 5080 5081 -f 5082 5083 5027 -f 5027 5083 5084 -f 5027 5084 5080 -f 5085 5086 5105 -f 5105 5086 6590 -f 5105 6590 5087 -f 6590 6588 5087 -f 5087 6588 6587 -f 5087 6587 5088 -f 5088 6583 5087 -f 5087 6583 6582 -f 5087 6582 5027 -f 5027 6582 5089 -f 5027 5089 5082 -f 5090 6677 5105 -f 5092 6656 5091 -f 5091 6656 6654 -f 5091 6654 5143 -f 5091 5103 5095 -f 5091 5095 5092 -f 5102 5093 5103 -f 5103 5093 5094 -f 5103 5094 5095 -f 5097 5163 5096 -f 5096 5163 6672 -f 5097 6668 5163 -f 5163 6668 5098 -f 5163 5098 6667 -f 6677 5099 5105 -f 5105 5099 5100 -f 5105 5100 5163 -f 5163 5100 5101 -f 5163 5101 6672 -f 6660 6659 5103 -f 5103 6659 6658 -f 5103 6658 5102 -f 6667 6665 5163 -f 5163 6665 6663 -f 5163 6663 5103 -f 5103 6663 6662 -f 5103 6662 6660 -f 5108 6652 5104 -f 6643 6642 5087 -f 5087 6642 6678 -f 5087 6678 5105 -f 5105 6678 5090 -f 5104 6649 5108 -f 5108 6649 5106 -f 5108 5106 6648 -f 6648 5107 5108 -f 5108 5107 6647 -f 5108 6647 5087 -f 5087 6647 6645 -f 5087 6645 6643 -f 5119 6869 5108 -f 5117 6879 5087 -f 5109 6903 2310 -f 5123 5110 5018 -f 5018 5110 6888 -f 5018 6888 6885 -f 6869 6867 5108 -f 5108 6867 5111 -f 5108 5111 5127 -f 5112 5113 5087 -f 5109 2310 5126 -f 6885 5114 5018 -f 5018 5114 6884 -f 5018 6884 5087 -f 5087 6884 5115 -f 5087 5115 5112 -f 5113 5116 5087 -f 5087 5116 6882 -f 5087 6882 5117 -f 6879 5118 5087 -f 5087 5118 6877 -f 5087 6877 5108 -f 5108 6877 6875 -f 5108 6875 6874 -f 6874 6873 5108 -f 5108 6873 6870 -f 5108 6870 5119 -f 6903 6900 2310 -f 2310 6900 6899 -f 2310 6899 6897 -f 6897 6896 2310 -f 2310 6896 6893 -f 2310 6893 5120 -f 5120 5121 2310 -f 2310 5121 5122 -f 2310 5122 5018 -f 5018 5122 6890 -f 5018 6890 5123 -f 6543 5124 5125 -f 5125 5124 5141 -f 5125 5141 2312 -f 2312 5141 6988 -f 2312 6988 2310 -f 2310 6988 5108 -f 2310 5108 5126 -f 5126 5108 5127 -f 5124 6540 5141 -f 5141 6540 6539 -f 5141 6539 5135 -f 5128 6563 5129 -f 5129 6563 6561 -f 5129 6561 5130 -f 5131 6548 5125 -f 5140 5132 5064 -f 5064 5132 6528 -f 6528 6527 5064 -f 5064 6527 6526 -f 5064 6526 5129 -f 5129 6526 5133 -f 5129 5133 5128 -f 5130 6558 5129 -f 5129 6558 6557 -f 5129 6557 6556 -f 6548 6547 5125 -f 5125 6547 6545 -f 5125 6545 6543 -f 6556 6554 5129 -f 5129 6554 6551 -f 5129 6551 5125 -f 5125 6551 5134 -f 5125 5134 5131 -f 5135 6538 5141 -f 5141 6538 5136 -f 5141 5136 6537 -f 5137 5138 5064 -f 5137 5064 5142 -f 5138 6531 5064 -f 5064 6531 5139 -f 5064 5139 5140 -f 6537 6536 5141 -f 5141 6536 6534 -f 5141 6534 5064 -f 5064 6534 6533 -f 5064 6533 5142 -f 6468 6465 5141 -f 5141 6465 5052 -f 5108 5091 6652 -f 6652 5091 5143 -f 5075 5144 5046 -f 5046 5144 6724 -f 5046 6724 5145 -f 5059 5179 5057 -f 5057 5179 5174 -f 6808 6847 5147 -f 5167 9551 5146 -f 5146 9551 5153 -f 6847 5148 5147 -f 5147 5148 6846 -f 5147 6846 6845 -f 5155 6835 5144 -f 5144 6835 5149 -f 5144 5149 6832 -f 6824 9537 5150 -f 5150 9537 5159 -f 5150 5159 6827 -f 6824 5151 9537 -f 9537 5151 5152 -f 9537 5152 6819 -f 6815 6813 9551 -f 9551 6813 6811 -f 9551 6811 5153 -f 5164 6838 5144 -f 5144 6838 5154 -f 5144 5154 5155 -f 6832 6831 5144 -f 5144 6831 5156 -f 5144 5156 5157 -f 5157 5156 6828 -f 5157 6828 9548 -f 9548 6828 6827 -f 9548 6827 5158 -f 5158 6827 5159 -f 6845 6843 5147 -f 5147 6843 6842 -f 5147 6842 5160 -f 5160 5161 5147 -f 5147 5161 5162 -f 5147 5162 6839 -f 6608 6607 5075 -f 5075 6607 5163 -f 5075 5163 5144 -f 5144 5163 5147 -f 5144 5147 5164 -f 5164 5147 6839 -f 6819 5165 9537 -f 9537 5165 6818 -f 9537 6818 9551 -f 9551 6818 6817 -f 9551 6817 6815 -f 5174 5169 5166 -f 5166 5169 9529 -f 5166 9529 5147 -f 5147 9529 9551 -f 5147 9551 6808 -f 6808 9551 5167 -f 6433 6431 5174 -f 5174 6431 5168 -f 5174 5168 5169 -f 5169 5168 5170 -f 5169 5170 5171 -f 6446 6445 5179 -f 6441 6440 5179 -f 6414 6413 5177 -f 5177 6413 6411 -f 5177 6411 5179 -f 5179 6411 6448 -f 5179 6448 6446 -f 5172 6438 5174 -f 5171 6429 5169 -f 5169 6429 5173 -f 5169 5173 5182 -f 6438 6435 5174 -f 5174 6435 6434 -f 5174 6434 6433 -f 6417 6416 5177 -f 5177 6416 6415 -f 5177 6415 6414 -f 6445 5175 5179 -f 5179 5175 5176 -f 5179 5176 6444 -f 5179 6440 5174 -f 5174 6440 6439 -f 5174 6439 5172 -f 5184 5181 5177 -f 6444 5178 5179 -f 5179 5178 5180 -f 5179 5180 6441 -f 5181 6421 5177 -f 5177 6421 6418 -f 5177 6418 6417 -f 5182 6426 5169 -f 5169 6426 6425 -f 5169 6425 5177 -f 5177 6425 5183 -f 5177 5183 5184 -f 5129 4932 5064 -f 5064 4932 5185 -f 5185 5186 5059 -f 5059 5186 4933 -f 5059 4933 5179 -f 5179 4933 9531 -f 5179 9531 5177 -f 5187 2245 2362 -f 2362 2245 7094 -f 7065 5196 9590 -f 7065 9590 5188 -f 5188 9590 9591 -f 5188 9591 5189 -f 5189 9591 5190 -f 5189 5190 7075 -f 7075 5190 5192 -f 7075 5192 5191 -f 5191 5192 7385 -f 5191 7385 7387 -f 7016 5202 5193 -f 5193 5202 5194 -f 5193 5194 7065 -f 5199 5195 7232 -f 7232 5195 9579 -f 7232 9579 5194 -f 5194 9579 5196 -f 5194 5196 7065 -f 5201 5744 5809 -f 5809 5810 5201 -f 5201 5810 5197 -f 5201 5197 7232 -f 7232 5197 5198 -f 7232 5198 5199 -f 7016 9521 5200 -f 5743 7016 5749 -f 5749 7016 5200 -f 5749 5200 5748 -f 5201 5202 5744 -f 5744 5202 7016 -f 5744 7016 5743 -f 5203 5204 5205 -f 5205 5204 5528 -f 5205 5528 5796 -f 5796 5528 5206 -f 5796 5206 5207 -f 5207 5206 5531 -f 5207 5531 5208 -f 5531 5530 5208 -f 5208 5530 5209 -f 5208 5209 5210 -f 5210 5209 5211 -f 5210 5211 5800 -f 5800 5211 5212 -f 5800 5212 5801 -f 5801 5212 5213 -f 5801 5213 5214 -f 5215 6368 5219 -f 5215 5219 5218 -f 5215 5222 6367 -f 5215 6367 6366 -f 6366 6368 5215 -f 5214 5213 5787 -f 5787 5213 5516 -f 5515 5789 5516 -f 5516 5789 5788 -f 5516 5788 5787 -f 5513 5216 5514 -f 5514 5216 5790 -f 5514 5790 5515 -f 5515 5790 5217 -f 5515 5217 5789 -f 5218 5219 5855 -f 5218 5855 5511 -f 5511 5855 5220 -f 5511 5220 5512 -f 5512 5220 5221 -f 5512 5221 5513 -f 5513 5221 5792 -f 5513 5792 5216 -f 5487 6381 5222 -f 5222 6381 6365 -f 5222 6365 6367 -f 5226 5223 6380 -f 6381 5487 5224 -f 5224 5487 5226 -f 5224 5226 6380 -f 6378 6379 5225 -f 5225 6379 5226 -f 5226 6379 5223 -f 6376 6377 5488 -f 5488 6377 5225 -f 5225 6377 6378 -f 2300 5227 5490 -f 5490 5227 5488 -f 5488 5227 6376 -f 5519 2282 5228 -f 5228 2282 5229 -f 5228 5229 5495 -f 5495 5229 5230 -f 5495 5230 5494 -f 5494 5230 2280 -f 5494 2280 5231 -f 5231 2280 5232 -f 5231 5232 5492 -f 5492 5232 2271 -f 5492 2271 5491 -f 5491 2271 5233 -f 5491 5233 5235 -f 5235 5233 5234 -f 5235 5234 5490 -f 5490 5234 2299 -f 5490 2299 2300 -f 2282 5519 9512 -f 9512 5519 5517 -f 9512 5517 9502 -f 9502 5517 4986 -f 4986 5517 5584 -f 4986 5584 4987 -f 4987 5584 5585 -f 4987 5585 5236 -f 5236 5585 5586 -f 5236 5586 5237 -f 5237 5586 5587 -f 5237 5587 5238 -f 5238 5587 5240 -f 5238 5240 5239 -f 5239 5240 5588 -f 5239 5588 5241 -f 5241 5588 5589 -f 5241 5589 4990 -f 4990 5589 5242 -f 4990 5242 5243 -f 5243 5242 5244 -f 5243 5244 4991 -f 4991 5244 5591 -f 4991 5591 4988 -f 4988 5591 5245 -f 5245 6247 6249 -f 5245 6249 4964 -f 5245 4964 6180 -f 4979 4988 4980 -f 4980 4988 6312 -f 6180 6179 5245 -f 5245 6179 4973 -f 5245 4973 4988 -f 4988 4973 6314 -f 4988 6314 6312 -f 5248 5597 5571 -f 5504 5246 5527 -f 5527 5246 5247 -f 5527 5247 5571 -f 5571 5247 5552 -f 5571 5552 5248 -f 5299 5249 5250 -f 5250 5249 5309 -f 5250 5309 2333 -f 2333 5309 5251 -f 2333 5251 2305 -f 2305 5251 5252 -f 2305 5252 5253 -f 5253 5252 5254 -f 5253 5254 2314 -f 2314 5254 5308 -f 2314 5308 5256 -f 5256 5308 5255 -f 5256 5255 5257 -f 5257 5255 2285 -f 2285 5255 5258 -f 2285 5258 5259 -f 5259 5258 5260 -f 5259 5260 2286 -f 2286 5260 5301 -f 2286 5301 5261 -f 5261 5301 5262 -f 5261 5262 2295 -f 2295 5262 5263 -f 2295 5263 5264 -f 5264 5263 5306 -f 5264 5306 5265 -f 5265 5306 5305 -f 5265 5305 5266 -f 5266 5305 5267 -f 5266 5267 5269 -f 5269 5267 5268 -f 5269 5268 5270 -f 5270 5268 5307 -f 5270 5307 5271 -f 5271 5307 5304 -f 5271 5304 5272 -f 5272 5304 5273 -f 5272 5273 2315 -f 2315 5273 5274 -f 2315 5274 5275 -f 5275 5274 5303 -f 5275 5303 2332 -f 2332 5303 5276 -f 2332 5276 5277 -f 5277 5276 5302 -f 5277 5302 5278 -f 5278 5302 5279 -f 5278 5279 2301 -f 2301 5279 5280 -f 2301 5280 2302 -f 2302 5280 5281 -f 2302 5281 2296 -f 2296 5281 5282 -f 2296 5282 2297 -f 2297 5282 5283 -f 2297 5283 2298 -f 2298 5283 5285 -f 2298 5285 5284 -f 5284 5285 5286 -f 5284 5286 2307 -f 2307 5286 5310 -f 2307 5310 5287 -f 5287 5310 5311 -f 5287 5311 5288 -f 5288 5311 5312 -f 5288 5312 2308 -f 2308 5312 5289 -f 2308 5289 2309 -f 2309 5289 5290 -f 2309 5290 5291 -f 5291 5290 5293 -f 5291 5293 5292 -f 5292 5293 5294 -f 5292 5294 2311 -f 2311 5294 5295 -f 2311 5295 5296 -f 5296 5295 5314 -f 5296 5314 2313 -f 2313 5314 5313 -f 2313 5313 5297 -f 5297 5313 5298 -f 5297 5298 2350 -f 2350 5298 5300 -f 2350 5300 5299 -f 5299 5300 5249 -f 5304 5307 5312 -f 5312 5249 5300 -f 5301 5260 5268 -f 5254 5252 5312 -f 5280 5279 5311 -f 5311 5279 5302 -f 5311 5302 5312 -f 5312 5302 5276 -f 5312 5276 5303 -f 5303 5274 5312 -f 5312 5274 5273 -f 5312 5273 5304 -f 5305 5306 5263 -f 5260 5258 5268 -f 5268 5258 5255 -f 5268 5255 5307 -f 5307 5255 5312 -f 5312 5255 5308 -f 5312 5308 5254 -f 5252 5251 5312 -f 5312 5251 5309 -f 5312 5309 5249 -f 5305 5263 5267 -f 5310 5286 5285 -f 5285 5283 5310 -f 5310 5283 5282 -f 5310 5282 5311 -f 5311 5282 5281 -f 5311 5281 5280 -f 5267 5263 5268 -f 5268 5263 5262 -f 5268 5262 5301 -f 5293 5290 5294 -f 5294 5290 5289 -f 5294 5289 5295 -f 5300 5298 5312 -f 5312 5298 5313 -f 5312 5313 5289 -f 5289 5313 5314 -f 5289 5314 5295 -f 2272 5396 5315 -f 5315 5396 5740 -f 5315 5740 2273 -f 2273 5740 5316 -f 2273 5316 5317 -f 5317 5316 5318 -f 5317 5318 5319 -f 5319 5318 5739 -f 5319 5739 5320 -f 5320 5739 5738 -f 5320 5738 2294 -f 2294 5738 5737 -f 2294 5737 5321 -f 5321 5737 5736 -f 5321 5736 5323 -f 5323 5736 5322 -f 5323 5322 5324 -f 5324 5322 5325 -f 5324 5325 2331 -f 2331 5325 5699 -f 2331 5699 5326 -f 5326 5699 5647 -f 5326 5647 5327 -f 5327 5647 5328 -f 5327 5328 5329 -f 5329 5328 5330 -f 5329 5330 2319 -f 2319 5330 5650 -f 2319 5650 2284 -f 2284 5650 5651 -f 2284 5651 2283 -f 2283 5651 5332 -f 2283 5332 5331 -f 5331 5332 5653 -f 5331 5653 2274 -f 2274 5653 5333 -f 2274 5333 2275 -f 2275 5333 5335 -f 2275 5335 5334 -f 5334 5335 5336 -f 5334 5336 2276 -f 2276 5336 5654 -f 2276 5654 2279 -f 2279 5654 5337 -f 2279 5337 2278 -f 2278 5337 5339 -f 2278 5339 5338 -f 5338 5339 5343 -f 5341 5340 6372 -f 5343 5342 6387 -f 6372 6364 5341 -f 5341 6364 5342 -f 5341 5342 5343 -f 6387 6388 5343 -f 5343 6388 5338 -f 6388 6386 5338 -f 6371 5345 6374 -f 5340 5341 5344 -f 5344 5341 5345 -f 5344 5345 6371 -f 5856 5346 5345 -f 6374 5345 5346 -f 6374 5346 4985 -f 5348 5858 5629 -f 5629 5858 5856 -f 5629 5856 5347 -f 5347 5856 5345 -f 5774 5773 5348 -f 5348 5773 5349 -f 5348 5349 5858 -f 5348 5627 5774 -f 5774 5627 5350 -f 5774 5350 5351 -f 5626 5775 5350 -f 5350 5775 5352 -f 5350 5352 5351 -f 5353 5625 5779 -f 5779 5776 5353 -f 5353 5776 5778 -f 5353 5778 5626 -f 5626 5778 5354 -f 5626 5354 5775 -f 5779 5625 5780 -f 5780 5625 5356 -f 5780 5356 5355 -f 5355 5356 5358 -f 5355 5358 5357 -f 5357 5358 5359 -f 5357 5359 5360 -f 5360 5359 5361 -f 5360 5361 5784 -f 5784 5361 5362 -f 5784 5362 5363 -f 5362 5364 5363 -f 5363 5364 5365 -f 5363 5365 5367 -f 5367 5365 5366 -f 5367 5366 5368 -f 6090 5389 5369 -f 5961 6117 5372 -f 5959 5370 5961 -f 5961 5370 6117 -f 5370 5959 5371 -f 5370 5371 5397 -f 5961 5372 5374 -f 5374 5372 6119 -f 5955 5373 5957 -f 5374 6119 5373 -f 5374 5373 5955 -f 5957 5373 6121 -f 5957 6121 5954 -f 5954 6121 5375 -f 5954 5375 5376 -f 5376 5375 6127 -f 6124 5950 5952 -f 6124 5952 6127 -f 6127 5952 5376 -f 6124 6129 5950 -f 5950 6129 5949 -f 5949 6129 6131 -f 5949 6131 5377 -f 5377 6131 5378 -f 5377 5378 5948 -f 5948 5378 6090 -f 5388 6022 6024 -f 5948 6090 5369 -f 5948 5388 5981 -f 5981 5388 6024 -f 5379 5381 5382 -f 5379 5382 5975 -f 5981 6024 5380 -f 5380 6024 6062 -f 5380 6062 5980 -f 5980 6062 6039 -f 5980 6039 5979 -f 5979 6039 5381 -f 5979 5381 5379 -f 5975 5382 6042 -f 5975 6042 5976 -f 5976 6042 6046 -f 5976 6046 5973 -f 5973 6046 5383 -f 5973 5383 5384 -f 5384 5383 6050 -f 6049 5972 5384 -f 6049 5384 6050 -f 5386 5385 5970 -f 5386 5970 6049 -f 6049 5970 5972 -f 5387 5968 5386 -f 5386 5968 5385 -f 5968 5387 6051 -f 5968 6051 6055 -f 5368 5366 5772 -f 5772 5366 5388 -f 5772 5388 5369 -f 5369 5388 5948 -f 5389 6090 6092 -f 5389 6092 5391 -f 5389 5391 5390 -f 5390 5391 6096 -f 5390 6096 5804 -f 5804 6096 6098 -f 5804 6098 6100 -f 5804 6100 5854 -f 5854 6100 6093 -f 5854 6093 5392 -f 6104 6110 5395 -f 5395 6110 6108 -f 5395 6108 6114 -f 6106 5394 5393 -f 5392 6093 5393 -f 5392 5393 5394 -f 5394 6106 5395 -f 5395 6106 6104 -f 6027 5741 5396 -f 2272 5965 5396 -f 5396 5965 5968 -f 5968 6055 5396 -f 5396 6055 6026 -f 5396 6026 6027 -f 5395 6114 2272 -f 2272 6114 6113 -f 2272 6113 5965 -f 5965 6113 5370 -f 5965 5370 5397 -f 5675 5398 5635 -f 5635 5398 5698 -f 5635 5698 5611 -f 5675 5635 5670 -f 5670 5635 5722 -f 5670 5722 5719 -f 5405 6211 5404 -f 6231 6340 5399 -f 6343 6213 5399 -f 5399 6340 6343 -f 5818 6274 5400 -f 6207 6215 5402 -f 5400 6274 5401 -f 5401 6208 5402 -f 5402 6208 6207 -f 5404 6211 6270 -f 5401 6270 6208 -f 6208 6270 6211 -f 6213 6343 6348 -f 6213 6348 6215 -f 6215 6348 5403 -f 6215 5403 5402 -f 5402 5403 6345 -f 6345 5422 5402 -f 5405 5404 5406 -f 5405 5406 6204 -f 4943 6204 5406 -f 5819 5407 5408 -f 5408 5407 5818 -f 5818 5407 6274 -f 5819 6279 5407 -f 5410 5919 5409 -f 5410 5409 5886 -f 5886 5409 5414 -f 5012 5914 5923 -f 5923 5914 5411 -f 5413 5412 5411 -f 5411 5412 5918 -f 5411 5918 5923 -f 5412 5413 5885 -f 5412 5885 5414 -f 5414 5885 5886 -f 5410 5415 5919 -f 5919 5415 5416 -f 5919 5416 5417 -f 5417 5416 5418 -f 5417 5418 5759 -f 5759 5418 5419 -f 5759 5419 5420 -f 5420 5419 5421 -f 5420 5421 5760 -f 5760 5421 5400 -f 5760 5400 5402 -f 5402 5400 5401 -f 5422 6345 5762 -f 5762 6345 5423 -f 5423 5424 5762 -f 5424 5423 5425 -f 5046 5426 5851 -f 6021 4984 6014 -f 6014 4984 5430 -f 5434 5427 5428 -f 5428 5427 6082 -f 6011 6086 6012 -f 6012 6086 6085 -f 5755 6081 6086 -f 5755 6086 5431 -f 5431 6086 6011 -f 6154 6156 5755 -f 6014 5430 5429 -f 5429 5430 6155 -f 5429 6155 6154 -f 5431 5432 5755 -f 5755 5432 5429 -f 5755 5429 6154 -f 5755 6156 5757 -f 6012 6085 6016 -f 6016 6085 5433 -f 6082 6081 5428 -f 5428 6081 5755 -f 5428 5755 5850 -f 5850 5755 5436 -f 5850 5436 5435 -f 5436 5437 5435 -f 5435 5437 5754 -f 5435 5754 5851 -f 5753 5027 5754 -f 5754 5027 5079 -f 5754 5079 5851 -f 5851 5079 5075 -f 5851 5075 5046 -f 5443 5444 5884 -f 5443 5884 5921 -f 5921 5884 5438 -f 5889 5439 5888 -f 5888 5439 5440 -f 5442 5441 5440 -f 5440 5441 5882 -f 5440 5882 5888 -f 5441 5442 5920 -f 5441 5920 5438 -f 5438 5920 5921 -f 5443 5767 5444 -f 5444 5767 5445 -f 5444 5445 5843 -f 5843 5445 5766 -f 5843 5766 5844 -f 5844 5766 5446 -f 5844 5446 5845 -f 5845 5446 5447 -f 5845 5447 5448 -f 5448 5447 5769 -f 5448 5769 5450 -f 5449 6148 5769 -f 6007 6075 6000 -f 6075 6007 6068 -f 5769 6148 6144 -f 5769 6144 6143 -f 6001 5769 6003 -f 6003 5769 6143 -f 6003 6143 6150 -f 5769 6001 6000 -f 6000 6075 6073 -f 6000 6073 5769 -f 5769 6073 5450 -f 5450 6073 6070 -f 6070 5847 5450 -f 6070 5451 5847 -f 5847 5451 5848 -f 5452 5848 5451 -f 6007 6008 6068 -f 6068 6008 6067 -f 6020 4983 6067 -f 6020 6067 6008 -f 6149 5998 6005 -f 6149 6005 6150 -f 6150 6005 6003 -f 5998 6149 6152 -f 5771 6148 5770 -f 5770 6148 5449 -f 4937 4939 5751 -f 5751 4939 5816 -f 5751 5816 5453 -f 5453 5816 5454 -f 5454 5816 5455 -f 5454 5455 5456 -f 5456 5455 5817 -f 5456 5817 5746 -f 5746 5817 5457 -f 5746 5457 5747 -f 5747 5457 5459 -f 5747 5459 5458 -f 5458 5459 5814 -f 5458 5814 5460 -f 5460 5814 5813 -f 5460 5813 5461 -f 5461 5813 5462 -f 5461 5462 5750 -f 5750 5462 5464 -f 5750 5464 5463 -f 5463 5464 5465 -f 5463 5465 5466 -f 5466 5465 5467 -f 5466 5467 5468 -f 5468 5467 5469 -f 5468 5469 5744 -f 5744 5469 5809 -f 5487 5222 5477 -f 5477 5222 5506 -f 5477 5506 5474 -f 5474 5506 5470 -f 5474 5470 5471 -f 5471 5470 5500 -f 5471 5500 5503 -f 5471 5503 5472 -f 5472 5503 5498 -f 5472 5498 5527 -f 5527 5498 5504 -f 5473 5472 5527 -f 5471 5472 5475 -f 5483 5475 5473 -f 5474 5471 5476 -f 5476 5471 5478 -f 5478 5471 5475 -f 5478 5475 5493 -f 5477 5474 5476 -f 5476 5478 5489 -f 5489 5478 5493 -f 5519 5496 5520 -f 5520 5496 5479 -f 5479 5496 5480 -f 5479 5480 5481 -f 5481 5480 5483 -f 5481 5483 5482 -f 5482 5483 5484 -f 5484 5483 5485 -f 5485 5483 5473 -f 5485 5473 5486 -f 5486 5473 5526 -f 5526 5473 5527 -f 5487 5477 5226 -f 5226 5477 5225 -f 5225 5477 5488 -f 5488 5477 5476 -f 5488 5476 5490 -f 5490 5476 5489 -f 5490 5489 5235 -f 5235 5489 5491 -f 5491 5489 5492 -f 5492 5489 5493 -f 5492 5493 5231 -f 5231 5493 5494 -f 5494 5493 5496 -f 5494 5496 5495 -f 5228 5495 5496 -f 5480 5496 5493 -f 5519 5228 5496 -f 5480 5493 5483 -f 5483 5493 5475 -f 5473 5475 5472 -f 5497 5498 5499 -f 5503 5499 5498 -f 5500 5499 5503 -f 5501 5536 5499 -f 5501 5499 5502 -f 5505 5501 5502 -f 5510 5505 5509 -f 5509 5505 5502 -f 5509 5502 5508 -f 5508 5502 5507 -f 5507 5502 5470 -f 5506 5507 5470 -f 5470 5502 5500 -f 5500 5502 5499 -f 5510 5509 5533 -f 5506 5222 5507 -f 5507 5222 5215 -f 5507 5215 5218 -f 5507 5218 5508 -f 5508 5218 5511 -f 5508 5511 5512 -f 5508 5512 5509 -f 5509 5512 5513 -f 5509 5513 5514 -f 5509 5514 5515 -f 5509 5515 5533 -f 5533 5515 5516 -f 5533 5516 5213 -f 5517 5519 5518 -f 5518 5519 5520 -f 5518 5520 5521 -f 5521 5520 5479 -f 5521 5479 5522 -f 5522 5479 5481 -f 5522 5481 5523 -f 5523 5481 5482 -f 5523 5482 5524 -f 5524 5482 5484 -f 5524 5484 5575 -f 5575 5484 5485 -f 5575 5485 5525 -f 5525 5485 5486 -f 5525 5486 5572 -f 5572 5486 5526 -f 5572 5526 5571 -f 5571 5526 5527 -f 5528 5204 5603 -f 5206 5528 5553 -f 5530 5531 5529 -f 5213 5212 5532 -f 5532 5212 5211 -f 5211 5209 5546 -f 5546 5209 5530 -f 5206 5553 5531 -f 5213 5532 5533 -f 5533 5532 5540 -f 5533 5540 5510 -f 5510 5540 5534 -f 5510 5534 5505 -f 5505 5534 5535 -f 5505 5535 5501 -f 5501 5535 5542 -f 5501 5542 5536 -f 5536 5542 5537 -f 5536 5537 5499 -f 5499 5537 5545 -f 5499 5545 5497 -f 5497 5545 5538 -f 5497 5538 5498 -f 5498 5538 5246 -f 5498 5246 5504 -f 5211 5546 5532 -f 5532 5546 5539 -f 5532 5539 5540 -f 5540 5539 5541 -f 5540 5541 5534 -f 5534 5541 5547 -f 5534 5547 5535 -f 5535 5547 5548 -f 5535 5548 5542 -f 5542 5548 5550 -f 5542 5550 5537 -f 5537 5550 5543 -f 5537 5543 5545 -f 5545 5543 5544 -f 5545 5544 5538 -f 5538 5544 5247 -f 5538 5247 5246 -f 5530 5529 5546 -f 5546 5529 5555 -f 5546 5555 5539 -f 5539 5555 5556 -f 5539 5556 5541 -f 5541 5556 5557 -f 5541 5557 5547 -f 5547 5557 5558 -f 5547 5558 5548 -f 5548 5558 5549 -f 5548 5549 5550 -f 5550 5549 5561 -f 5550 5561 5543 -f 5543 5561 5551 -f 5543 5551 5544 -f 5544 5551 5552 -f 5544 5552 5247 -f 5531 5553 5529 -f 5529 5553 5554 -f 5529 5554 5555 -f 5555 5554 5564 -f 5555 5564 5556 -f 5556 5564 5566 -f 5556 5566 5557 -f 5557 5566 5568 -f 5557 5568 5558 -f 5558 5568 5559 -f 5558 5559 5549 -f 5549 5559 5570 -f 5549 5570 5561 -f 5561 5570 5560 -f 5561 5560 5551 -f 5551 5560 5248 -f 5551 5248 5552 -f 5528 5603 5553 -f 5553 5603 5562 -f 5553 5562 5554 -f 5554 5562 5563 -f 5554 5563 5564 -f 5564 5563 5565 -f 5564 5565 5566 -f 5566 5565 5567 -f 5566 5567 5568 -f 5568 5567 5602 -f 5568 5602 5559 -f 5559 5602 5569 -f 5559 5569 5570 -f 5570 5569 5601 -f 5570 5601 5560 -f 5560 5601 5597 -f 5560 5597 5248 -f 5571 5583 5572 -f 5525 5572 5574 -f 5574 5572 5583 -f 5575 5525 5574 -f 5573 5574 5583 -f 5524 5575 5574 -f 5523 5524 5576 -f 5576 5524 5574 -f 5576 5574 5592 -f 5607 5573 5583 -f 5522 5523 5576 -f 5590 5577 5605 -f 5605 5577 5573 -f 5605 5573 5607 -f 5521 5522 5578 -f 5578 5522 5576 -f 5578 5576 5579 -f 5579 5576 5592 -f 5579 5592 5580 -f 5580 5592 5577 -f 5580 5577 5590 -f 5581 5590 5582 -f 5582 5590 5605 -f 5518 5521 5578 -f 5517 5518 5584 -f 5584 5518 5578 -f 5584 5578 5585 -f 5585 5578 5586 -f 5586 5578 5579 -f 5586 5579 5587 -f 5587 5579 5240 -f 5240 5579 5580 -f 5240 5580 5588 -f 5588 5580 5589 -f 5589 5580 5242 -f 5242 5580 5590 -f 5242 5590 5244 -f 5244 5590 5591 -f 5245 5591 5581 -f 5581 5591 5590 -f 5577 5592 5573 -f 5573 5592 5574 -f 6242 6244 5595 -f 5562 6269 6268 -f 6245 6247 5604 -f 5595 6244 5604 -f 5600 6239 6237 -f 5600 6233 6239 -f 5596 5595 5604 -f 5606 5598 5594 -f 5594 5598 5599 -f 5594 5599 5595 -f 5595 5599 5593 -f 5595 5593 6242 -f 5606 5608 5598 -f 5599 6235 5593 -f 5598 5600 5599 -f 5599 5600 6237 -f 5599 6237 6235 -f 5608 5602 5598 -f 5601 5569 5608 -f 5608 5569 5602 -f 5602 5567 5598 -f 5598 5567 5565 -f 5598 5565 5600 -f 5600 5565 5563 -f 5600 5563 5562 -f 5600 5562 6268 -f 5600 6268 6233 -f 5562 5603 4951 -f 5562 4951 6269 -f 5603 5204 4951 -f 6247 5245 5604 -f 5604 5245 5581 -f 5604 5581 5596 -f 5596 5581 5582 -f 5596 5582 5595 -f 5595 5582 5594 -f 5594 5582 5605 -f 5594 5605 5606 -f 5606 5605 5607 -f 5606 5607 5608 -f 5608 5607 5583 -f 5608 5583 5601 -f 5601 5583 5597 -f 5597 5583 5571 -f 5341 5343 5630 -f 5630 5343 5639 -f 5630 5639 5624 -f 5624 5639 5640 -f 5624 5640 5617 -f 5617 5640 5641 -f 5617 5641 5609 -f 5609 5641 5642 -f 5609 5642 5613 -f 5613 5642 5643 -f 5613 5643 5614 -f 5614 5643 5644 -f 5614 5644 5612 -f 5612 5644 5645 -f 5612 5645 5610 -f 5610 5645 5646 -f 5610 5646 5611 -f 5611 5646 5635 -f 5619 5610 5697 -f 5614 5612 5615 -f 5615 5612 5610 -f 5615 5610 5619 -f 5613 5614 5615 -f 5609 5613 5617 -f 5617 5613 5615 -f 5615 5619 5622 -f 5616 5619 5618 -f 5617 5615 5622 -f 5624 5617 5620 -f 5620 5617 5622 -f 5628 5622 5623 -f 5623 5622 5621 -f 5623 5621 5694 -f 5616 5621 5622 -f 5616 5622 5619 -f 5694 5660 5623 -f 5622 5628 5620 -f 5624 5620 5630 -f 5660 5625 5353 -f 5660 5353 5623 -f 5623 5353 5626 -f 5623 5626 5350 -f 5623 5350 5628 -f 5628 5350 5627 -f 5628 5627 5348 -f 5628 5348 5629 -f 5628 5629 5620 -f 5620 5629 5347 -f 5620 5347 5345 -f 5620 5345 5630 -f 5630 5345 5341 -f 5635 5633 5706 -f 5632 5706 5633 -f 5655 5633 5645 -f 5631 5632 5633 -f 5657 5655 5645 -f 5704 5631 5634 -f 5634 5631 5633 -f 5634 5633 5655 -f 5703 5704 5634 -f 5634 5655 5658 -f 5636 5703 5649 -f 5649 5703 5634 -f 5659 5656 5657 -f 5701 5636 5649 -f 5652 5649 5634 -f 5652 5634 5658 -f 5652 5658 5637 -f 5648 5701 5649 -f 5638 5652 5637 -f 5638 5637 5656 -f 5343 5659 5639 -f 5639 5659 5640 -f 5640 5659 5641 -f 5641 5659 5657 -f 5641 5657 5642 -f 5642 5657 5643 -f 5643 5657 5645 -f 5643 5645 5644 -f 5645 5633 5646 -f 5646 5633 5635 -f 5699 5648 5647 -f 5647 5648 5649 -f 5647 5649 5328 -f 5328 5649 5330 -f 5330 5649 5652 -f 5330 5652 5650 -f 5650 5652 5651 -f 5651 5652 5332 -f 5332 5652 5638 -f 5332 5638 5653 -f 5653 5638 5333 -f 5333 5638 5335 -f 5335 5638 5656 -f 5335 5656 5336 -f 5654 5336 5656 -f 5337 5654 5656 -f 5339 5337 5659 -f 5659 5337 5656 -f 5656 5637 5657 -f 5657 5637 5658 -f 5657 5658 5655 -f 5343 5339 5659 -f 5356 5625 5660 -f 5358 5356 5662 -f 5361 5359 5686 -f 5366 5365 5663 -f 5663 5365 5364 -f 5364 5362 5661 -f 5661 5362 5361 -f 5358 5662 5359 -f 5366 5663 5718 -f 5718 5663 5664 -f 5718 5664 5721 -f 5721 5664 5665 -f 5721 5665 5717 -f 5717 5665 5666 -f 5717 5666 5720 -f 5720 5666 5673 -f 5720 5673 5716 -f 5716 5673 5674 -f 5716 5674 5715 -f 5715 5674 5667 -f 5715 5667 5668 -f 5668 5667 5669 -f 5668 5669 5719 -f 5719 5669 5670 -f 5364 5661 5663 -f 5663 5661 5677 -f 5663 5677 5664 -f 5664 5677 5671 -f 5664 5671 5665 -f 5665 5671 5678 -f 5665 5678 5666 -f 5666 5678 5672 -f 5666 5672 5673 -f 5673 5672 5680 -f 5673 5680 5674 -f 5674 5680 5681 -f 5674 5681 5667 -f 5667 5681 5684 -f 5667 5684 5669 -f 5669 5684 5675 -f 5669 5675 5670 -f 5361 5686 5661 -f 5661 5686 5676 -f 5661 5676 5677 -f 5677 5676 5688 -f 5677 5688 5671 -f 5671 5688 5689 -f 5671 5689 5678 -f 5678 5689 5691 -f 5678 5691 5672 -f 5672 5691 5679 -f 5672 5679 5680 -f 5680 5679 5682 -f 5680 5682 5681 -f 5681 5682 5683 -f 5681 5683 5684 -f 5684 5683 5398 -f 5684 5398 5675 -f 5359 5662 5686 -f 5686 5662 5685 -f 5686 5685 5676 -f 5676 5685 5687 -f 5676 5687 5688 -f 5688 5687 5695 -f 5688 5695 5689 -f 5689 5695 5690 -f 5689 5690 5691 -f 5691 5690 5696 -f 5691 5696 5679 -f 5679 5696 5692 -f 5679 5692 5682 -f 5682 5692 5693 -f 5682 5693 5683 -f 5683 5693 5698 -f 5683 5698 5398 -f 5356 5660 5662 -f 5662 5660 5694 -f 5662 5694 5685 -f 5685 5694 5621 -f 5685 5621 5687 -f 5687 5621 5616 -f 5687 5616 5695 -f 5695 5616 5618 -f 5695 5618 5690 -f 5690 5618 5619 -f 5690 5619 5696 -f 5696 5619 5697 -f 5696 5697 5692 -f 5692 5697 5610 -f 5692 5610 5693 -f 5693 5610 5611 -f 5693 5611 5698 -f 5699 5325 5648 -f 5648 5325 5700 -f 5648 5700 5701 -f 5701 5700 5730 -f 5701 5730 5636 -f 5636 5730 5702 -f 5636 5702 5703 -f 5703 5702 5726 -f 5703 5726 5704 -f 5704 5726 5727 -f 5704 5727 5631 -f 5631 5727 5705 -f 5631 5705 5632 -f 5632 5705 5707 -f 5632 5707 5706 -f 5706 5707 5729 -f 5706 5729 5635 -f 5635 5729 5722 -f 6033 5712 5713 -f 5708 5710 5711 -f 6022 5721 5714 -f 6037 5721 5710 -f 5708 5711 6035 -f 5712 6035 5711 -f 5709 5668 5719 -f 5742 5709 5724 -f 5720 5711 5721 -f 5721 5711 5710 -f 5713 5712 5711 -f 5713 5711 5720 -f 5713 5720 5715 -f 6034 6033 5713 -f 6030 6034 5742 -f 5742 6034 5713 -f 5741 6030 5742 -f 5742 5713 5709 -f 5721 6037 5714 -f 5718 5388 5366 -f 5716 5715 5720 -f 5717 5720 5721 -f 5718 5721 6022 -f 5718 6022 5388 -f 5709 5713 5715 -f 5709 5715 5668 -f 5728 5724 5723 -f 5742 5724 5725 -f 5725 5724 5728 -f 5725 5728 5731 -f 5730 5731 5702 -f 5702 5731 5726 -f 5726 5731 5728 -f 5726 5728 5727 -f 5727 5728 5705 -f 5705 5728 5723 -f 5705 5723 5707 -f 5707 5723 5729 -f 5729 5723 5722 -f 5735 5742 5725 -f 5735 5725 5734 -f 5734 5725 5733 -f 5733 5725 5731 -f 5733 5731 5732 -f 5730 5732 5731 -f 5730 5700 5732 -f 5742 5735 5741 -f 5700 5325 5732 -f 5732 5325 5322 -f 5732 5322 5736 -f 5732 5736 5733 -f 5733 5736 5737 -f 5733 5737 5738 -f 5733 5738 5734 -f 5734 5738 5739 -f 5734 5739 5318 -f 5734 5318 5735 -f 5735 5318 5316 -f 5735 5316 5740 -f 5735 5740 5741 -f 5741 5740 5396 -f 5724 5709 5719 -f 5724 5719 5723 -f 5723 5719 5722 -f 5743 5468 5744 -f 9521 5745 5200 -f 5200 5745 5456 -f 5456 5746 5200 -f 5200 5746 5747 -f 5200 5747 5748 -f 5747 5458 5748 -f 5748 5458 5460 -f 5748 5460 5749 -f 5460 5461 5749 -f 5749 5461 5750 -f 5749 5750 5743 -f 5743 5750 5463 -f 5743 5463 5466 -f 5743 5466 5468 -f 4989 5752 4937 -f 4937 5751 4989 -f 4989 5751 5453 -f 4989 5453 5745 -f 5745 5453 5454 -f 5745 5454 5456 -f 5764 5425 5752 -f 5752 5425 4937 -f 5756 2293 5753 -f 5753 5754 5756 -f 5756 5754 5437 -f 5756 5437 5436 -f 5436 5755 5756 -f 5756 5755 5757 -f 5756 5757 6160 -f 5758 5919 5417 -f 5806 5924 5758 -f 5806 5758 5417 -f 5806 5417 5761 -f 5761 5417 5759 -f 5761 5759 5420 -f 5761 5420 5760 -f 5761 5760 5402 -f 5761 5402 5763 -f 5763 5402 5422 -f 5763 5422 5762 -f 5763 5762 5424 -f 5763 5424 5764 -f 5764 5424 5425 -f 5769 5447 5765 -f 5765 5447 5446 -f 5766 5765 5446 -f 5445 5767 5922 -f 5802 5852 5922 -f 5922 5852 5445 -f 5445 5852 5765 -f 5445 5765 5766 -f 5765 5768 5769 -f 5769 5768 5449 -f 5449 5768 5770 -f 5770 5768 5771 -f 5771 5768 5756 -f 5771 5756 6160 -f 5805 5786 5772 -f 5772 5369 5805 -f 5805 5369 5389 -f 5389 5390 5805 -f 5793 5857 5773 -f 5773 5774 5793 -f 5793 5774 5351 -f 5793 5351 5939 -f 5939 5351 5352 -f 5939 5352 5775 -f 5776 5777 5778 -f 5778 5777 5939 -f 5778 5939 5354 -f 5354 5939 5775 -f 5776 5779 5777 -f 5777 5779 5780 -f 5777 5780 5781 -f 5781 5780 5355 -f 5781 5355 5782 -f 5782 5355 5357 -f 5782 5357 5783 -f 5783 5357 5360 -f 5783 5360 5944 -f 5944 5360 5784 -f 5944 5784 5945 -f 5945 5784 5363 -f 5945 5363 5785 -f 5785 5363 5367 -f 5785 5367 5786 -f 5786 5367 5368 -f 5786 5368 5772 -f 5214 5787 5936 -f 5936 5787 5791 -f 5791 5787 5788 -f 5791 5788 5789 -f 5789 5217 5791 -f 5791 5217 5790 -f 5791 5790 5793 -f 5221 5857 5792 -f 5792 5857 5793 -f 5792 5793 5216 -f 5216 5793 5790 -f 5794 5808 4947 -f 4947 4948 5794 -f 5794 4948 4949 -f 5794 4949 5795 -f 4949 4950 5795 -f 5795 4950 5203 -f 5795 5203 5929 -f 5929 5203 5205 -f 5929 5205 5930 -f 5930 5205 5796 -f 5930 5796 5797 -f 5797 5796 5207 -f 5797 5207 5798 -f 5798 5207 5208 -f 5798 5208 5934 -f 5934 5208 5210 -f 5934 5210 5799 -f 5799 5210 5800 -f 5799 5800 5936 -f 5936 5800 5801 -f 5936 5801 5214 -f 5852 5802 5803 -f 5803 5802 5947 -f 5803 5947 5804 -f 5804 5947 5805 -f 5804 5805 5390 -f 5924 5806 5926 -f 5926 5806 5807 -f 5926 5807 5794 -f 5794 5807 5808 -f 5809 9572 9573 -f 5809 9573 5810 -f 5810 9573 9574 -f 5810 9574 5197 -f 5197 9574 9581 -f 5197 9581 5198 -f 5195 5199 5811 -f 5811 5199 5198 -f 5811 5198 9581 -f 5809 5469 9572 -f 9572 5469 5467 -f 9572 5467 5812 -f 5467 5465 5812 -f 5812 5465 5464 -f 5812 5464 9569 -f 5464 5462 9569 -f 9569 5462 5813 -f 9569 5813 9533 -f 5813 5814 9533 -f 9533 5814 5459 -f 9533 5459 9565 -f 5459 5457 9565 -f 9565 5457 5817 -f 9565 5817 9563 -f 4939 5815 5816 -f 5816 5815 9564 -f 5816 9564 9563 -f 5816 9563 5455 -f 5455 9563 5817 -f 6279 5820 4939 -f 4939 5820 5815 -f 5400 5421 5860 -f 5860 5421 5419 -f 5860 5419 5859 -f 5418 5859 5419 -f 5416 5415 5887 -f 5821 5864 5887 -f 5887 5864 5416 -f 5416 5864 5859 -f 5416 5859 5418 -f 5860 9554 5400 -f 5400 9554 5818 -f 5818 9554 5408 -f 5408 9554 5819 -f 5819 9554 5820 -f 5819 5820 6279 -f 5864 5821 5822 -f 5822 5821 5913 -f 5822 5913 5865 -f 5865 5913 5823 -f 5865 5823 5867 -f 5867 5823 5911 -f 5867 5911 5824 -f 5867 5824 5869 -f 5869 5824 5825 -f 5869 5825 5909 -f 5869 5909 5826 -f 5826 5909 5827 -f 5826 5827 5828 -f 5826 5828 5829 -f 5829 5828 5905 -f 5829 5905 5830 -f 5829 5830 5872 -f 5872 5830 5831 -f 5872 5831 5873 -f 5873 5831 5904 -f 5873 5904 5874 -f 5874 5904 5903 -f 5874 5903 5875 -f 5875 5903 5902 -f 5875 5902 5877 -f 5877 5902 5900 -f 5877 5900 5832 -f 5832 5900 5898 -f 5832 5898 5833 -f 5833 5898 5835 -f 5833 5835 5834 -f 5834 5835 5896 -f 5834 5896 5836 -f 5836 5896 5837 -f 5836 5837 5838 -f 5838 5837 5840 -f 5838 5840 5839 -f 5839 5840 5841 -f 5839 5841 5881 -f 5881 5841 5842 -f 5881 5842 5862 -f 5862 5842 5891 -f 5862 5891 5861 -f 5861 5891 5890 -f 5883 5444 5843 -f 5861 5890 5883 -f 5861 5883 5843 -f 5861 5843 5846 -f 5846 5843 5844 -f 5846 5844 5845 -f 5846 5845 5448 -f 5846 5448 5450 -f 5846 5450 9543 -f 9543 5450 5847 -f 9543 5847 5848 -f 9543 5848 5452 -f 9543 5452 6089 -f 9543 6089 5849 -f 5849 6089 5434 -f 5434 5428 5849 -f 5849 5428 5850 -f 5849 5850 5435 -f 5435 5851 5849 -f 5849 5851 5426 -f 5849 5426 5032 -f 5852 5803 5765 -f 5765 5803 5853 -f 5392 5853 5803 -f 5392 5803 5854 -f 5854 5803 5804 -f 5855 5857 5220 -f 5220 5857 5221 -f 5855 5219 5858 -f 5858 5219 5856 -f 5856 5219 5346 -f 5855 5858 5857 -f 5857 5858 5349 -f 5857 5349 5773 -f 9556 5860 5859 -f 5863 5861 5846 -f 5880 5862 5863 -f 5863 5862 5861 -f 5859 5864 5822 -f 5859 5822 9556 -f 9556 5822 5865 -f 9556 5865 5866 -f 5865 5867 5866 -f 5866 5867 5868 -f 5867 5869 5868 -f 5868 5869 9524 -f 5869 5826 9524 -f 9524 5826 5870 -f 5826 5829 5870 -f 5870 5829 9552 -f 9552 5829 5872 -f 9552 5872 5871 -f 5872 5873 5871 -f 5871 5873 5874 -f 5871 5874 5876 -f 5874 5875 5876 -f 5876 5875 5877 -f 5876 5877 9541 -f 9541 5877 5832 -f 9541 5832 5878 -f 5878 5832 5833 -f 5878 5833 9538 -f 9538 5833 5834 -f 9538 5834 5836 -f 9538 5836 5879 -f 5836 5838 5879 -f 5879 5838 5839 -f 5879 5839 5880 -f 5880 5839 5881 -f 5880 5881 5862 -f 5890 5888 5882 -f 5882 5441 5890 -f 5890 5441 5438 -f 5890 5438 5884 -f 5444 5883 5884 -f 5884 5883 5890 -f 5821 5885 5413 -f 5821 5413 5411 -f 5821 5411 5914 -f 5885 5821 5887 -f 5885 5887 5886 -f 5886 5887 5410 -f 5410 5887 5415 -f 5888 5890 5889 -f 5889 5890 5892 -f 5892 5890 5891 -f 5892 5891 5893 -f 5893 5891 5842 -f 5893 5842 5894 -f 5894 5842 5841 -f 5894 5841 4995 -f 4995 5841 5840 -f 4995 5840 4997 -f 4997 5840 5837 -f 4997 5837 5895 -f 5895 5837 5896 -f 5895 5896 4998 -f 4998 5896 5835 -f 4998 5835 5897 -f 5897 5835 5898 -f 5897 5898 5899 -f 5899 5898 5900 -f 5899 5900 5000 -f 5000 5900 5902 -f 5000 5902 5901 -f 5901 5902 5903 -f 5901 5903 5002 -f 5002 5903 5904 -f 5002 5904 5004 -f 5004 5904 5831 -f 5004 5831 5005 -f 5005 5831 5830 -f 5005 5830 5006 -f 5006 5830 5905 -f 5006 5905 5906 -f 5906 5905 5828 -f 5906 5828 5007 -f 5007 5828 5827 -f 5007 5827 5907 -f 5907 5827 5909 -f 5907 5909 5908 -f 5908 5909 5825 -f 5908 5825 5009 -f 5009 5825 5824 -f 5009 5824 5910 -f 5910 5824 5911 -f 5910 5911 5011 -f 5011 5911 5823 -f 5011 5823 5912 -f 5912 5823 5913 -f 5912 5913 5914 -f 5914 5913 5821 -f 5915 4945 5807 -f 5807 4945 5916 -f 5807 5916 5808 -f 5806 5761 5917 -f 5915 5807 5917 -f 5917 5807 5806 -f 5758 5923 5918 -f 5918 5412 5758 -f 5758 5412 5414 -f 5758 5414 5409 -f 5919 5758 5409 -f 5802 5920 5442 -f 5802 5442 5440 -f 5802 5440 5439 -f 5920 5802 5922 -f 5920 5922 5921 -f 5921 5922 5443 -f 5443 5922 5767 -f 5923 5758 5012 -f 5012 5758 5924 -f 5012 5924 5925 -f 5925 5924 5926 -f 5925 5926 5927 -f 5927 5926 5794 -f 5927 5794 5010 -f 5010 5794 5795 -f 5010 5795 5928 -f 5928 5795 5929 -f 5928 5929 5931 -f 5931 5929 5930 -f 5931 5930 5008 -f 5008 5930 5797 -f 5008 5797 5932 -f 5932 5797 5798 -f 5932 5798 5933 -f 5933 5798 5934 -f 5933 5934 5935 -f 5935 5934 5799 -f 5935 5799 5937 -f 5937 5799 5936 -f 5937 5936 5003 -f 5003 5936 5791 -f 5003 5791 5001 -f 5001 5791 5793 -f 5001 5793 5938 -f 5938 5793 5939 -f 5938 5939 5940 -f 5940 5939 5777 -f 5940 5777 4999 -f 4999 5777 5781 -f 4999 5781 5941 -f 5941 5781 5782 -f 5941 5782 5942 -f 5942 5782 5783 -f 5942 5783 5943 -f 5943 5783 5944 -f 5943 5944 4996 -f 4996 5944 5945 -f 4996 5945 4994 -f 4994 5945 5785 -f 4994 5785 4993 -f 4993 5785 5786 -f 4993 5786 5946 -f 5946 5786 5805 -f 5946 5805 4992 -f 4992 5805 5947 -f 4992 5947 5439 -f 5439 5947 5802 -f 5985 5983 5981 -f 5981 5983 5989 -f 5981 5989 5948 -f 5948 5989 5988 -f 5948 5988 5990 -f 5948 5990 5993 -f 5377 5991 5949 -f 5949 5991 6004 -f 5949 6004 5950 -f 6004 5997 5950 -f 5950 5997 5951 -f 5950 5951 5952 -f 5995 5954 5996 -f 5954 5376 5996 -f 5996 5376 5951 -f 5951 5376 5952 -f 5953 5956 5957 -f 5953 5957 5954 -f 5953 5954 5995 -f 6015 5962 5374 -f 5374 5955 6015 -f 6015 5955 5956 -f 5956 5955 5957 -f 5960 5958 5959 -f 5960 5959 5961 -f 5960 5961 5962 -f 5962 5961 5374 -f 5963 5966 5397 -f 5397 5371 5963 -f 5963 5371 5958 -f 5958 5371 5959 -f 5967 5968 5964 -f 5964 5968 5965 -f 5964 5965 5966 -f 5966 5965 5397 -f 6013 5385 5967 -f 5967 5385 5968 -f 5971 5385 6013 -f 5972 5970 5969 -f 5969 5970 5971 -f 5971 5970 5385 -f 5972 5969 6017 -f 5972 6017 6018 -f 5972 6018 5384 -f 5384 6018 6019 -f 5384 6019 5973 -f 5973 6019 5974 -f 5973 5974 5976 -f 5976 5974 6009 -f 6010 5975 6009 -f 6009 5975 5976 -f 5978 5379 5977 -f 5977 5379 5975 -f 5977 5975 6010 -f 6006 5979 5978 -f 5978 5979 5379 -f 5982 5380 5999 -f 5999 5380 6006 -f 6006 5380 5980 -f 6006 5980 5979 -f 5981 5380 5982 -f 5981 5982 5985 -f 5985 5982 5984 -f 5987 5983 5984 -f 5984 5983 5985 -f 5986 5989 5987 -f 5987 5989 5983 -f 6002 5988 5986 -f 5986 5988 5989 -f 5994 5990 6002 -f 6002 5990 5988 -f 5991 5377 5948 -f 5991 5948 5992 -f 5992 5948 5993 -f 5992 5993 5994 -f 5994 5993 5990 -f 5995 5998 5953 -f 5951 5998 5996 -f 5996 5998 5995 -f 6004 6005 5997 -f 5997 6005 5998 -f 5997 5998 5951 -f 5999 6007 5982 -f 5982 6007 5984 -f 5984 6007 6000 -f 5984 6000 5987 -f 5987 6000 5986 -f 5986 6000 6001 -f 5986 6001 6002 -f 6002 6001 5994 -f 5994 6001 5992 -f 5992 6001 6003 -f 5992 6003 5991 -f 5991 6003 6004 -f 6004 6003 6005 -f 5978 6007 6006 -f 6006 6007 5999 -f 5977 6008 5978 -f 5978 6008 6007 -f 6010 6008 5977 -f 6020 6008 6009 -f 6009 6008 6010 -f 6020 6009 5974 -f 6016 6017 5969 -f 5958 5429 5963 -f 5963 5429 5432 -f 5963 5432 5966 -f 5966 5432 5431 -f 5966 5431 5964 -f 5964 5431 6011 -f 5964 6011 5967 -f 5967 6011 6012 -f 5967 6012 6013 -f 6013 6012 5971 -f 5971 6012 5969 -f 5969 6012 6016 -f 5960 6014 5958 -f 5958 6014 5429 -f 5962 6014 5960 -f 6015 6021 5962 -f 5962 6021 6014 -f 6017 6016 6018 -f 6018 6016 6020 -f 6018 6020 6019 -f 6019 6020 5974 -f 5953 5998 6021 -f 5953 6021 5956 -f 5956 6021 6015 -f 6058 6057 6022 -f 6022 6057 6023 -f 6022 6023 6024 -f 6024 6023 6060 -f 6024 6060 6065 -f 5714 6038 6069 -f 6083 6027 6025 -f 6025 6027 6026 -f 6025 6026 6054 -f 6084 6027 6083 -f 6028 5741 6084 -f 6084 5741 6027 -f 6029 5741 6028 -f 6087 6030 6029 -f 6029 6030 5741 -f 6031 6030 6087 -f 6032 6034 6088 -f 6088 6034 6031 -f 6031 6034 6030 -f 6080 5712 6079 -f 6079 5712 6032 -f 6032 5712 6033 -f 6032 6033 6034 -f 6078 6035 6080 -f 6080 6035 5712 -f 6077 5710 6036 -f 6036 5710 6078 -f 6078 5710 5708 -f 6078 5708 6035 -f 5714 6037 6038 -f 6038 6037 6077 -f 6077 6037 5710 -f 6062 6063 6039 -f 6039 6063 6076 -f 6039 6076 5381 -f 6076 6040 5381 -f 5381 6040 6066 -f 5381 6066 5382 -f 6044 6046 6041 -f 6046 6042 6041 -f 6041 6042 6066 -f 6066 6042 5382 -f 6043 6046 6044 -f 6045 6048 6050 -f 6050 5383 6045 -f 6045 5383 6043 -f 6043 5383 6046 -f 6047 6053 5386 -f 5386 6049 6047 -f 6047 6049 6048 -f 6048 6049 6050 -f 6052 6056 6051 -f 6051 5387 6052 -f 6052 5387 6053 -f 6053 5387 5386 -f 6026 6055 6054 -f 6054 6055 6056 -f 6056 6055 6051 -f 6022 5714 6069 -f 6022 6069 6071 -f 6072 6058 6071 -f 6071 6058 6022 -f 6059 6057 6072 -f 6072 6057 6058 -f 6061 6023 6059 -f 6059 6023 6057 -f 6074 6060 6061 -f 6061 6060 6023 -f 6063 6062 6024 -f 6063 6024 6064 -f 6064 6024 6065 -f 6064 6065 6074 -f 6074 6065 6060 -f 6044 6067 4983 -f 6044 4983 6043 -f 6066 6068 6041 -f 6041 6068 6067 -f 6041 6067 6044 -f 6076 6068 6040 -f 6040 6068 6066 -f 6038 6070 6069 -f 6069 6070 6071 -f 6071 6070 6072 -f 6072 6070 6059 -f 6059 6070 6073 -f 6059 6073 6061 -f 6061 6073 6074 -f 6074 6073 6075 -f 6074 6075 6064 -f 6064 6075 6063 -f 6063 6075 6068 -f 6063 6068 6076 -f 6036 5451 6077 -f 6077 5451 6070 -f 6077 6070 6038 -f 6078 5451 6036 -f 6080 5451 6078 -f 6089 5452 6079 -f 6079 5452 6080 -f 6080 5452 5451 -f 6089 6079 6032 -f 5427 6087 6029 -f 6052 6086 6056 -f 6056 6086 6081 -f 6056 6081 6054 -f 6054 6081 6025 -f 6025 6081 6082 -f 6025 6082 6083 -f 6083 6082 6084 -f 6084 6082 5427 -f 6084 5427 6028 -f 6028 5427 6029 -f 6053 6085 6052 -f 6052 6085 6086 -f 6047 5433 6053 -f 6053 5433 6085 -f 6048 5433 6047 -f 5427 5434 6087 -f 6087 5434 6031 -f 6031 5434 6088 -f 6088 5434 6032 -f 6032 5434 6089 -f 6043 4983 6045 -f 6045 4983 6048 -f 6048 4983 5433 -f 6135 6137 6090 -f 6090 6137 6138 -f 6090 6138 6140 -f 6090 6140 6139 -f 6090 6139 6092 -f 6092 6139 6091 -f 5391 6147 6095 -f 5391 6095 6096 -f 6095 6097 6096 -f 6096 6097 6099 -f 6096 6099 6098 -f 6094 6093 6142 -f 6093 6100 6142 -f 6142 6100 6099 -f 6099 6100 6098 -f 6101 6102 5393 -f 6101 5393 6093 -f 6101 6093 6094 -f 6157 6105 6106 -f 6157 6106 6102 -f 6102 6106 5393 -f 6103 6109 6110 -f 6110 6104 6103 -f 6103 6104 6105 -f 6105 6104 6106 -f 6107 6153 6114 -f 6114 6108 6107 -f 6107 6108 6109 -f 6109 6108 6110 -f 6111 5370 6112 -f 6112 5370 6113 -f 6112 6113 6153 -f 6153 6113 6114 -f 6116 6117 6111 -f 6111 6117 5370 -f 6115 6117 6116 -f 6119 5372 6118 -f 6118 5372 6115 -f 6115 5372 6117 -f 6119 6118 6158 -f 6119 6158 6120 -f 6119 6120 5373 -f 5373 6120 6159 -f 5373 6159 6121 -f 6121 6159 6122 -f 6121 6122 5375 -f 5375 6122 6123 -f 6126 6127 6123 -f 6123 6127 5375 -f 6151 6124 6125 -f 6125 6124 6127 -f 6125 6127 6126 -f 6128 6129 6151 -f 6151 6129 6124 -f 6132 5378 6130 -f 6130 5378 6128 -f 6128 5378 6131 -f 6128 6131 6129 -f 6090 5378 6132 -f 6090 6132 6135 -f 6135 6132 6133 -f 6134 6137 6133 -f 6133 6137 6135 -f 6136 6138 6134 -f 6134 6138 6137 -f 6145 6140 6136 -f 6136 6140 6138 -f 6141 6139 6145 -f 6145 6139 6140 -f 6147 5391 6092 -f 6147 6092 6146 -f 6146 6092 6091 -f 6146 6091 6141 -f 6141 6091 6139 -f 5771 6160 6094 -f 6094 6160 6101 -f 6099 5771 6142 -f 6142 5771 6094 -f 6095 6148 6097 -f 6097 6148 6099 -f 6099 6148 5771 -f 6130 6150 6132 -f 6132 6150 6133 -f 6133 6150 6143 -f 6133 6143 6134 -f 6134 6143 6136 -f 6136 6143 6144 -f 6136 6144 6145 -f 6145 6144 6141 -f 6141 6144 6146 -f 6146 6144 6148 -f 6146 6148 6147 -f 6147 6148 6095 -f 6151 6149 6128 -f 6128 6149 6150 -f 6128 6150 6130 -f 6125 6149 6151 -f 6126 6152 6125 -f 6125 6152 6149 -f 6123 6152 6126 -f 6152 6123 6122 -f 5430 6158 6118 -f 6109 6156 6107 -f 6107 6156 6153 -f 6153 6156 6154 -f 6153 6154 6112 -f 6112 6154 6111 -f 6111 6154 6155 -f 6111 6155 6116 -f 6116 6155 5430 -f 6116 5430 6115 -f 6115 5430 6118 -f 6103 6156 6109 -f 6105 6156 6103 -f 6157 5757 6105 -f 6105 5757 6156 -f 5430 4984 6158 -f 6158 4984 6120 -f 6120 4984 6159 -f 6159 4984 6122 -f 6122 4984 6152 -f 6101 6160 6102 -f 6102 6160 5757 -f 6102 5757 6157 -f 6196 6198 4965 -f 4965 6198 6161 -f 4965 6161 6200 -f 4965 6200 6162 -f 4965 6162 6163 -f 4965 6163 6201 -f 6164 6165 4953 -f 4953 6165 6210 -f 4953 6210 6166 -f 6210 6205 6166 -f 6166 6205 6167 -f 6166 6167 4955 -f 6168 4960 6203 -f 4960 4956 6203 -f 6203 4956 6167 -f 6167 4956 4955 -f 6219 6171 6172 -f 6219 6172 4960 -f 6219 4960 6168 -f 6221 6169 6175 -f 6175 6170 6221 -f 6221 6170 6171 -f 6171 6170 6172 -f 6173 6178 6174 -f 6173 6174 4962 -f 6173 4962 6169 -f 6169 4962 6175 -f 6177 6224 6180 -f 6180 6176 6177 -f 6177 6176 6178 -f 6178 6176 6174 -f 6182 4973 6226 -f 6226 4973 6179 -f 6226 6179 6224 -f 6224 6179 6180 -f 6181 4975 6182 -f 6182 4975 4973 -f 6228 4975 6181 -f 4971 4970 6183 -f 6183 4970 6228 -f 6228 4970 4975 -f 4971 6183 6184 -f 4971 6184 6230 -f 4971 6230 6185 -f 6185 6230 6187 -f 6185 6187 6186 -f 6186 6187 6188 -f 6186 6188 6190 -f 6190 6188 6189 -f 6218 6191 6189 -f 6189 6191 6190 -f 6216 6193 6217 -f 6217 6193 6191 -f 6217 6191 6218 -f 6212 6192 6216 -f 6216 6192 6193 -f 6194 4966 6214 -f 6214 4966 6212 -f 6212 4966 4967 -f 6212 4967 6192 -f 4965 4966 6194 -f 4965 6194 6196 -f 6196 6194 6206 -f 6195 6198 6206 -f 6206 6198 6196 -f 6197 6161 6195 -f 6195 6161 6198 -f 6199 6200 6197 -f 6197 6200 6161 -f 6202 6162 6199 -f 6199 6162 6200 -f 6165 6164 6201 -f 6165 6201 6209 -f 6209 6201 6163 -f 6209 6163 6202 -f 6202 6163 6162 -f 6168 6204 6219 -f 6167 5405 6203 -f 6203 5405 6204 -f 6203 6204 6168 -f 6210 5405 6205 -f 6205 5405 6167 -f 6214 6207 6194 -f 6194 6207 6206 -f 6206 6207 6195 -f 6195 6207 6208 -f 6195 6208 6197 -f 6197 6208 6199 -f 6199 6208 6211 -f 6199 6211 6202 -f 6202 6211 6209 -f 6209 6211 6165 -f 6165 6211 6210 -f 6210 6211 5405 -f 6216 6213 6212 -f 6212 6213 6214 -f 6214 6213 6215 -f 6214 6215 6207 -f 6217 6213 6216 -f 6218 5399 6217 -f 6217 5399 6213 -f 6189 5399 6218 -f 5399 6189 6231 -f 6231 6189 6188 -f 6219 6204 6220 -f 6219 6220 6171 -f 6171 6220 6221 -f 6221 6220 6169 -f 6169 6220 6173 -f 6173 6220 6222 -f 6173 6222 6178 -f 6178 6222 6177 -f 6177 6222 6223 -f 6177 6223 6224 -f 6224 6223 6225 -f 6224 6225 6226 -f 6226 6225 4940 -f 6226 4940 6182 -f 6182 4940 6227 -f 6182 6227 6181 -f 6181 6227 6229 -f 6181 6229 6228 -f 6228 6229 6183 -f 6183 6229 4942 -f 6183 4942 6184 -f 6184 4942 6230 -f 6230 4942 6187 -f 6187 4942 6231 -f 6187 6231 6188 -f 6259 6261 6232 -f 6232 6261 6263 -f 6232 6263 6269 -f 6269 6263 6267 -f 6269 6267 6265 -f 6234 6273 6233 -f 6233 6273 6238 -f 6233 6238 6239 -f 6236 6235 6237 -f 6236 6237 6238 -f 6238 6237 6239 -f 6236 6240 6235 -f 6235 6240 6241 -f 6235 6241 5593 -f 5593 6241 6278 -f 5593 6278 6242 -f 6242 6278 6243 -f 6242 6243 6244 -f 6280 6244 6243 -f 6246 5604 6280 -f 6280 5604 6244 -f 6282 6248 6245 -f 6282 6245 6246 -f 6246 6245 5604 -f 6283 6284 6249 -f 6249 6247 6283 -f 6283 6247 6248 -f 6248 6247 6245 -f 6286 4964 6285 -f 6285 4964 6249 -f 6285 6249 6284 -f 6288 4963 6286 -f 6286 4963 4964 -f 6289 4963 6288 -f 6250 4961 6290 -f 6290 4961 6289 -f 6289 4961 4963 -f 6250 6290 6291 -f 6250 6291 6251 -f 6250 6251 4959 -f 4959 6251 6293 -f 4959 6293 6252 -f 6252 6293 6294 -f 6252 6294 4958 -f 4958 6294 6277 -f 6253 4957 6277 -f 6277 4957 4958 -f 6275 4952 6276 -f 6276 4952 4957 -f 6276 4957 6253 -f 6256 4954 6275 -f 6275 4954 4952 -f 6258 6255 6254 -f 6254 6255 6256 -f 6256 6255 6257 -f 6256 6257 4954 -f 6232 6255 6258 -f 6232 6258 6259 -f 6259 6258 6271 -f 6260 6261 6271 -f 6271 6261 6259 -f 6262 6263 6260 -f 6260 6263 6261 -f 6266 6267 6262 -f 6262 6267 6263 -f 6264 6265 6266 -f 6266 6265 6267 -f 6233 6268 6234 -f 6234 6268 6269 -f 6234 6269 6272 -f 6272 6269 6264 -f 6264 6269 6265 -f 6241 6279 6278 -f 6236 5407 6240 -f 6240 5407 6241 -f 6241 5407 6279 -f 6273 5407 6238 -f 6238 5407 6236 -f 6254 6270 6258 -f 6258 6270 5401 -f 6258 5401 6271 -f 6271 5401 6260 -f 6260 5401 6262 -f 6262 5401 6274 -f 6262 6274 6266 -f 6266 6274 6264 -f 6264 6274 6272 -f 6272 6274 6234 -f 6234 6274 6273 -f 6273 6274 5407 -f 6275 5404 6256 -f 6256 5404 6254 -f 6254 5404 6270 -f 6276 5404 6275 -f 6253 5406 6276 -f 6276 5406 5404 -f 6277 5406 6253 -f 5406 6277 4943 -f 4943 6277 6294 -f 6278 6279 6243 -f 6243 6279 6281 -f 6243 6281 6280 -f 6280 6281 6246 -f 6246 6281 6282 -f 6282 6281 4936 -f 6282 4936 6248 -f 6248 4936 6283 -f 6283 4936 6284 -f 6284 4936 4938 -f 6284 4938 6285 -f 6285 4938 6286 -f 6286 4938 6288 -f 6288 4938 6287 -f 6288 6287 6289 -f 6289 6287 6290 -f 6290 6287 4941 -f 6290 4941 6291 -f 6291 4941 6292 -f 6291 6292 6251 -f 6251 6292 6293 -f 6293 6292 4943 -f 6293 4943 6294 -f 6328 6330 6295 -f 6295 6330 6331 -f 6295 6331 6336 -f 6295 6336 6296 -f 6296 6336 6335 -f 6296 6335 6338 -f 6337 6298 6297 -f 6297 6298 6299 -f 6297 6299 6300 -f 6299 6342 6300 -f 6300 6342 6301 -f 6300 6301 4968 -f 6341 6303 6302 -f 6303 4969 6302 -f 6302 4969 6301 -f 6301 4969 4968 -f 6339 6307 6308 -f 6339 6308 6303 -f 6339 6303 6341 -f 6353 6304 6305 -f 6305 6306 6353 -f 6353 6306 6307 -f 6307 6306 6308 -f 6354 6310 4972 -f 6354 4972 4974 -f 6354 4974 6304 -f 6304 4974 6305 -f 6356 6313 6314 -f 6314 6309 6356 -f 6356 6309 6310 -f 6310 6309 4972 -f 6315 4980 6311 -f 6311 4980 6312 -f 6311 6312 6313 -f 6313 6312 6314 -f 6316 4980 6315 -f 6359 6317 6316 -f 6316 6317 4980 -f 4982 4981 6318 -f 6318 4981 6359 -f 6359 4981 6317 -f 4982 6318 6319 -f 4982 6319 6361 -f 4982 6361 4977 -f 4977 6361 6362 -f 4977 6362 6352 -f 4977 6352 6320 -f 6320 6352 6321 -f 6320 6321 6322 -f 6350 6322 6321 -f 6349 6323 6351 -f 6351 6323 6350 -f 6350 6323 6322 -f 6324 6325 6349 -f 6349 6325 6323 -f 6327 6326 6344 -f 6344 6326 6324 -f 6324 6326 4946 -f 6324 4946 6325 -f 6295 6326 6327 -f 6295 6327 6328 -f 6328 6327 6329 -f 6332 6330 6329 -f 6329 6330 6328 -f 6333 6331 6332 -f 6332 6331 6330 -f 6346 6336 6333 -f 6333 6336 6331 -f 6334 6335 6346 -f 6346 6335 6336 -f 6298 6337 6296 -f 6298 6296 6347 -f 6347 6296 6338 -f 6347 6338 6334 -f 6334 6338 6335 -f 6341 6340 6339 -f 6301 6343 6302 -f 6302 6343 6340 -f 6302 6340 6341 -f 6299 6343 6342 -f 6342 6343 6301 -f 6344 6345 6327 -f 6327 6345 6329 -f 6329 6345 6332 -f 6332 6345 5403 -f 6332 5403 6333 -f 6333 5403 6346 -f 6346 5403 6348 -f 6346 6348 6334 -f 6334 6348 6347 -f 6347 6348 6298 -f 6298 6348 6299 -f 6299 6348 6343 -f 6349 6345 6324 -f 6324 6345 6344 -f 6351 5423 6349 -f 6349 5423 6345 -f 6350 5423 6351 -f 5425 5423 6321 -f 6321 5423 6350 -f 5425 6321 6352 -f 6339 6340 4944 -f 6339 4944 6307 -f 6307 4944 6353 -f 6353 4944 6304 -f 6304 4944 6354 -f 6354 4944 6355 -f 6354 6355 6310 -f 6310 6355 6357 -f 6310 6357 6356 -f 6356 6357 6313 -f 6313 6357 6358 -f 6313 6358 6311 -f 6311 6358 6315 -f 6315 6358 6316 -f 6316 6358 6359 -f 6359 6358 6360 -f 6359 6360 6318 -f 6318 6360 6319 -f 6319 6360 6363 -f 6319 6363 6361 -f 6361 6363 6362 -f 6362 6363 6352 -f 6352 6363 5425 -f 6365 6381 6373 -f 5342 6364 6373 -f 6370 6367 6373 -f 6373 6367 6365 -f 6369 6368 6366 -f 6369 6366 6370 -f 6370 6366 6367 -f 6369 6370 6375 -f 6375 6370 6373 -f 4985 6369 6375 -f 6371 6374 6375 -f 5340 5344 6375 -f 6375 5344 6371 -f 6373 6372 6375 -f 6375 6372 5340 -f 6373 6364 6372 -f 4985 6375 6374 -f 5224 6380 6384 -f 6383 6377 6376 -f 6383 6376 6382 -f 6382 6376 5227 -f 6383 6379 6378 -f 6383 6378 6377 -f 6379 6383 6384 -f 6379 6384 5223 -f 6384 6380 5223 -f 5224 6384 6381 -f 6381 6384 6373 -f 2300 6382 5227 -f 6389 6383 6382 -f 6389 6382 6385 -f 6385 6386 6389 -f 6388 6389 6386 -f 6387 6389 6388 -f 5342 6373 6389 -f 6387 5342 6389 -f 6383 6389 6384 -f 6384 6389 6373 -f 6407 6412 6392 -f 6449 6412 6407 -f 6407 6391 6393 -f 6390 6391 6407 -f 6392 6390 6407 -f 6407 6419 6420 -f 6394 6419 6407 -f 6393 6394 6407 -f 6407 6423 6424 -f 6422 6423 6407 -f 6420 6422 6407 -f 6407 6427 6428 -f 6395 6427 6407 -f 6424 6395 6407 -f 6407 6397 6396 -f 6430 6397 6407 -f 6428 6430 6407 -f 6407 6432 6398 -f 6399 6432 6407 -f 6396 6399 6407 -f 6407 6436 6437 -f 6400 6436 6407 -f 6398 6400 6407 -f 6407 6402 6401 -f 6403 6402 6407 -f 6437 6403 6407 -f 6407 6442 6404 -f 6405 6442 6407 -f 6401 6405 6407 -f 6407 6406 6410 -f 6443 6406 6407 -f 6404 6443 6407 -f 6407 6409 6447 -f 6408 6409 6407 -f 6410 6408 6407 -f 6447 6449 6407 -f 6449 6411 6412 -f 6412 6411 6413 -f 6412 6413 6392 -f 6392 6413 6414 -f 6392 6414 6390 -f 6390 6414 6415 -f 6390 6415 6391 -f 6391 6415 6416 -f 6391 6416 6393 -f 6393 6416 6417 -f 6393 6417 6394 -f 6394 6417 6418 -f 6394 6418 6419 -f 6419 6418 6421 -f 6419 6421 6420 -f 6420 6421 5181 -f 6420 5181 6422 -f 6422 5181 5184 -f 6422 5184 6423 -f 6423 5184 5183 -f 6423 5183 6424 -f 6424 5183 6425 -f 6424 6425 6395 -f 6395 6425 6426 -f 6395 6426 6427 -f 6427 6426 5182 -f 6427 5182 6428 -f 6428 5182 5173 -f 6428 5173 6430 -f 6430 5173 6429 -f 6430 6429 6397 -f 6397 6429 5171 -f 6397 5171 6396 -f 6396 5171 5170 -f 6396 5170 6399 -f 6399 5170 5168 -f 6399 5168 6432 -f 6432 5168 6431 -f 6432 6431 6398 -f 6398 6431 6433 -f 6398 6433 6400 -f 6400 6433 6434 -f 6400 6434 6436 -f 6436 6434 6435 -f 6436 6435 6437 -f 6437 6435 6438 -f 6437 6438 6403 -f 6403 6438 5172 -f 6403 5172 6402 -f 6402 5172 6439 -f 6402 6439 6401 -f 6401 6439 6440 -f 6401 6440 6405 -f 6405 6440 6441 -f 6405 6441 6442 -f 6442 6441 5180 -f 6442 5180 6404 -f 6404 5180 5178 -f 6404 5178 6443 -f 6443 5178 6444 -f 6443 6444 6406 -f 6406 6444 5176 -f 6406 5176 6410 -f 6410 5176 5175 -f 6410 5175 6408 -f 6408 5175 6445 -f 6408 6445 6409 -f 6409 6445 6446 -f 6409 6446 6447 -f 6447 6446 6448 -f 6447 6448 6449 -f 6449 6448 6411 -f 6456 6450 6482 -f 6480 6450 6456 -f 6456 6484 6486 -f 6483 6484 6456 -f 6482 6483 6456 -f 6456 6488 6451 -f 6452 6488 6456 -f 6486 6452 6456 -f 6456 6492 6454 -f 6490 6492 6456 -f 6451 6490 6456 -f 6456 6496 6453 -f 6495 6496 6456 -f 6454 6495 6456 -f 6456 6500 6502 -f 6455 6500 6456 -f 6453 6455 6456 -f 6456 6457 6458 -f 6504 6457 6456 -f 6502 6504 6456 -f 6456 6466 6467 -f 6464 6466 6456 -f 6458 6464 6456 -f 6456 6470 6459 -f 6460 6470 6456 -f 6467 6460 6456 -f 6456 6472 6473 -f 6461 6472 6456 -f 6459 6461 6456 -f 6456 6475 6462 -f 6474 6475 6456 -f 6473 6474 6456 -f 6456 6477 6479 -f 6463 6477 6456 -f 6462 6463 6456 -f 6479 6480 6456 -f 6464 6465 6466 -f 6466 6465 6467 -f 6467 6465 6468 -f 6467 6468 6460 -f 6460 6468 6469 -f 6460 6469 6470 -f 6470 6469 5069 -f 6470 5069 6459 -f 6459 5069 6471 -f 6459 6471 6461 -f 6461 6471 5068 -f 6461 5068 6472 -f 6472 5068 5067 -f 6472 5067 6473 -f 6473 5067 5066 -f 6473 5066 6474 -f 6474 5066 6476 -f 6474 6476 6475 -f 6475 6476 5065 -f 6475 5065 6462 -f 6462 5065 5063 -f 6462 5063 6463 -f 6463 5063 5062 -f 6463 5062 6477 -f 6477 5062 6478 -f 6477 6478 6479 -f 6479 6478 6481 -f 6479 6481 6480 -f 6480 6481 5056 -f 6480 5056 6450 -f 6450 5056 5055 -f 6450 5055 6482 -f 6482 5055 5054 -f 6482 5054 6483 -f 6483 5054 5053 -f 6483 5053 6484 -f 6484 5053 6485 -f 6484 6485 6486 -f 6486 6485 5060 -f 6486 5060 6452 -f 6452 5060 6487 -f 6452 6487 6488 -f 6488 6487 5061 -f 6488 5061 6451 -f 6451 5061 6489 -f 6451 6489 6490 -f 6490 6489 6491 -f 6490 6491 6492 -f 6492 6491 6493 -f 6492 6493 6454 -f 6454 6493 6494 -f 6454 6494 6495 -f 6495 6494 6497 -f 6495 6497 6496 -f 6496 6497 5058 -f 6496 5058 6453 -f 6453 5058 6498 -f 6453 6498 6455 -f 6455 6498 6499 -f 6455 6499 6500 -f 6500 6499 6501 -f 6500 6501 6502 -f 6502 6501 6503 -f 6502 6503 6504 -f 6504 6503 6505 -f 6504 6505 6457 -f 6457 6505 5051 -f 6457 5051 6458 -f 6458 5051 6506 -f 6458 6506 6464 -f 6464 6506 6465 -f 6521 6508 6510 -f 6507 6508 6521 -f 6521 6509 6512 -f 6529 6509 6521 -f 6510 6529 6521 -f 6521 6530 6532 -f 6511 6530 6521 -f 6512 6511 6521 -f 6521 6513 6514 -f 6515 6513 6521 -f 6532 6515 6521 -f 6521 6516 6518 -f 6535 6516 6521 -f 6514 6535 6521 -f 6521 6517 6522 -f 6519 6517 6521 -f 6518 6519 6521 -f 6521 6541 6542 -f 6520 6541 6521 -f 6522 6520 6521 -f 6521 6546 6523 -f 6544 6546 6521 -f 6542 6544 6521 -f 6521 6550 6552 -f 6549 6550 6521 -f 6523 6549 6521 -f 6521 6555 6525 -f 6553 6555 6521 -f 6552 6553 6521 -f 6521 6559 6560 -f 6524 6559 6521 -f 6525 6524 6521 -f 6521 6564 6565 -f 6562 6564 6521 -f 6560 6562 6521 -f 6565 6507 6521 -f 6507 6526 6508 -f 6508 6526 6527 -f 6508 6527 6510 -f 6510 6527 6528 -f 6510 6528 6529 -f 6529 6528 5132 -f 6529 5132 6509 -f 6509 5132 5140 -f 6509 5140 6512 -f 6512 5140 5139 -f 6512 5139 6511 -f 6511 5139 6531 -f 6511 6531 6530 -f 6530 6531 5138 -f 6530 5138 6532 -f 6532 5138 5137 -f 6532 5137 6515 -f 6515 5137 5142 -f 6515 5142 6513 -f 6513 5142 6533 -f 6513 6533 6514 -f 6514 6533 6534 -f 6514 6534 6535 -f 6535 6534 6536 -f 6535 6536 6516 -f 6516 6536 6537 -f 6516 6537 6518 -f 6518 6537 5136 -f 6518 5136 6519 -f 6519 5136 6538 -f 6519 6538 6517 -f 6517 6538 5135 -f 6517 5135 6522 -f 6522 5135 6539 -f 6522 6539 6520 -f 6520 6539 6540 -f 6520 6540 6541 -f 6541 6540 5124 -f 6541 5124 6542 -f 6542 5124 6543 -f 6542 6543 6544 -f 6544 6543 6545 -f 6544 6545 6546 -f 6546 6545 6547 -f 6546 6547 6523 -f 6523 6547 6548 -f 6523 6548 6549 -f 6549 6548 5131 -f 6549 5131 6550 -f 6550 5131 5134 -f 6550 5134 6552 -f 6552 5134 6551 -f 6552 6551 6553 -f 6553 6551 6554 -f 6553 6554 6555 -f 6555 6554 6556 -f 6555 6556 6525 -f 6525 6556 6557 -f 6525 6557 6524 -f 6524 6557 6558 -f 6524 6558 6559 -f 6559 6558 5130 -f 6559 5130 6560 -f 6560 5130 6561 -f 6560 6561 6562 -f 6562 6561 6563 -f 6562 6563 6564 -f 6564 6563 5128 -f 6564 5128 6565 -f 6565 5128 5133 -f 6565 5133 6507 -f 6507 5133 6526 -f 6576 6566 6596 -f 6594 6566 6576 -f 6576 6600 6567 -f 6597 6600 6576 -f 6596 6597 6576 -f 6576 6603 6605 -f 6602 6603 6576 -f 6567 6602 6576 -f 6576 6568 6570 -f 6569 6568 6576 -f 6605 6569 6576 -f 6576 6611 6612 -f 6610 6611 6576 -f 6570 6610 6576 -f 6576 6571 6615 -f 6613 6571 6576 -f 6612 6613 6576 -f 6576 6619 6620 -f 6618 6619 6576 -f 6615 6618 6576 -f 6576 6578 6579 -f 6572 6578 6576 -f 6620 6572 6576 -f 6576 6580 6573 -f 6574 6580 6576 -f 6579 6574 6576 -f 6576 6584 6585 -f 6581 6584 6576 -f 6573 6581 6576 -f 6576 6586 6589 -f 6575 6586 6576 -f 6585 6575 6576 -f 6576 6577 6592 -f 6591 6577 6576 -f 6589 6591 6576 -f 6592 6594 6576 -f 6572 5080 6578 -f 6578 5080 6579 -f 6579 5080 5084 -f 6579 5084 6574 -f 6574 5084 5083 -f 6574 5083 6580 -f 6580 5083 5082 -f 6580 5082 6573 -f 6573 5082 5089 -f 6573 5089 6581 -f 6581 5089 6582 -f 6581 6582 6584 -f 6584 6582 6583 -f 6584 6583 6585 -f 6585 6583 5088 -f 6585 5088 6575 -f 6575 5088 6587 -f 6575 6587 6586 -f 6586 6587 6588 -f 6586 6588 6589 -f 6589 6588 6590 -f 6589 6590 6591 -f 6591 6590 5086 -f 6591 5086 6577 -f 6577 5086 5085 -f 6577 5085 6592 -f 6592 5085 6593 -f 6592 6593 6594 -f 6594 6593 6595 -f 6594 6595 6566 -f 6566 6595 5070 -f 6566 5070 6596 -f 6596 5070 6598 -f 6596 6598 6597 -f 6597 6598 6599 -f 6597 6599 6600 -f 6600 6599 6601 -f 6600 6601 6567 -f 6567 6601 5077 -f 6567 5077 6602 -f 6602 5077 5078 -f 6602 5078 6603 -f 6603 5078 6604 -f 6603 6604 6605 -f 6605 6604 6606 -f 6605 6606 6569 -f 6569 6606 6607 -f 6569 6607 6568 -f 6568 6607 6608 -f 6568 6608 6570 -f 6570 6608 6609 -f 6570 6609 6610 -f 6610 6609 5076 -f 6610 5076 6611 -f 6611 5076 5074 -f 6611 5074 6612 -f 6612 5074 5073 -f 6612 5073 6613 -f 6613 5073 6614 -f 6613 6614 6571 -f 6571 6614 6616 -f 6571 6616 6615 -f 6615 6616 5072 -f 6615 5072 6618 -f 6618 5072 6617 -f 6618 6617 6619 -f 6619 6617 6621 -f 6619 6621 6620 -f 6620 6621 5071 -f 6620 5071 6572 -f 6572 5071 5081 -f 6572 5081 5080 -f 6626 6622 6627 -f 6623 6622 6626 -f 6626 6625 6657 -f 6624 6625 6626 -f 6627 6624 6626 -f 6626 6628 6661 -f 6629 6628 6626 -f 6657 6629 6626 -f 6626 6630 6666 -f 6664 6630 6626 -f 6661 6664 6626 -f 6626 6669 6632 -f 6631 6669 6626 -f 6666 6631 6626 -f 6626 6671 6673 -f 6670 6671 6626 -f 6632 6670 6626 -f 6626 6675 6676 -f 6674 6675 6626 -f 6673 6674 6626 -f 6626 6633 6641 -f 6634 6633 6626 -f 6676 6634 6626 -f 6626 6635 6646 -f 6644 6635 6626 -f 6641 6644 6626 -f 6626 6637 6639 -f 6636 6637 6626 -f 6646 6636 6626 -f 6626 6650 6640 -f 6638 6650 6626 -f 6639 6638 6626 -f 6626 6653 6655 -f 6651 6653 6626 -f 6640 6651 6626 -f 6655 6623 6626 -f 6634 6678 6633 -f 6633 6678 6641 -f 6641 6678 6642 -f 6641 6642 6644 -f 6644 6642 6643 -f 6644 6643 6635 -f 6635 6643 6645 -f 6635 6645 6646 -f 6646 6645 6647 -f 6646 6647 6636 -f 6636 6647 5107 -f 6636 5107 6637 -f 6637 5107 6648 -f 6637 6648 6639 -f 6639 6648 5106 -f 6639 5106 6638 -f 6638 5106 6649 -f 6638 6649 6650 -f 6650 6649 5104 -f 6650 5104 6640 -f 6640 5104 6652 -f 6640 6652 6651 -f 6651 6652 5143 -f 6651 5143 6653 -f 6653 5143 6654 -f 6653 6654 6655 -f 6655 6654 6656 -f 6655 6656 6623 -f 6623 6656 5092 -f 6623 5092 6622 -f 6622 5092 5095 -f 6622 5095 6627 -f 6627 5095 5094 -f 6627 5094 6624 -f 6624 5094 5093 -f 6624 5093 6625 -f 6625 5093 5102 -f 6625 5102 6657 -f 6657 5102 6658 -f 6657 6658 6629 -f 6629 6658 6659 -f 6629 6659 6628 -f 6628 6659 6660 -f 6628 6660 6661 -f 6661 6660 6662 -f 6661 6662 6664 -f 6664 6662 6663 -f 6664 6663 6630 -f 6630 6663 6665 -f 6630 6665 6666 -f 6666 6665 6667 -f 6666 6667 6631 -f 6631 6667 5098 -f 6631 5098 6669 -f 6669 5098 6668 -f 6669 6668 6632 -f 6632 6668 5097 -f 6632 5097 6670 -f 6670 5097 5096 -f 6670 5096 6671 -f 6671 5096 6672 -f 6671 6672 6673 -f 6673 6672 5101 -f 6673 5101 6674 -f 6674 5101 5100 -f 6674 5100 6675 -f 6675 5100 5099 -f 6675 5099 6676 -f 6676 5099 6677 -f 6676 6677 6634 -f 6634 6677 5090 -f 6634 5090 6678 -f 6687 6679 6680 -f 6681 6679 6687 -f 6687 6682 6704 -f 6701 6682 6687 -f 6680 6701 6687 -f 6687 6683 6684 -f 6705 6683 6687 -f 6704 6705 6687 -f 6687 6686 6685 -f 6688 6686 6687 -f 6684 6688 6687 -f 6687 6690 6710 -f 6689 6690 6687 -f 6685 6689 6687 -f 6687 6714 6692 -f 6712 6714 6687 -f 6710 6712 6687 -f 6687 6691 6718 -f 6715 6691 6687 -f 6692 6715 6687 -f 6687 6693 6695 -f 6719 6693 6687 -f 6718 6719 6687 -f 6687 6721 6722 -f 6694 6721 6687 -f 6695 6694 6687 -f 6687 6725 6696 -f 6697 6725 6687 -f 6722 6697 6687 -f 6687 6728 6698 -f 6727 6728 6687 -f 6696 6727 6687 -f 6687 6730 6699 -f 6729 6730 6687 -f 6698 6729 6687 -f 6699 6681 6687 -f 6681 6700 6679 -f 6679 6700 5036 -f 6679 5036 6680 -f 6680 5036 5037 -f 6680 5037 6701 -f 6701 5037 6702 -f 6701 6702 6682 -f 6682 6702 6703 -f 6682 6703 6704 -f 6704 6703 5035 -f 6704 5035 6705 -f 6705 5035 6706 -f 6705 6706 6683 -f 6683 6706 5049 -f 6683 5049 6684 -f 6684 5049 6707 -f 6684 6707 6688 -f 6688 6707 5048 -f 6688 5048 6686 -f 6686 5048 6708 -f 6686 6708 6685 -f 6685 6708 5034 -f 6685 5034 6689 -f 6689 5034 5033 -f 6689 5033 6690 -f 6690 5033 6709 -f 6690 6709 6710 -f 6710 6709 6711 -f 6710 6711 6712 -f 6712 6711 6713 -f 6712 6713 6714 -f 6714 6713 5031 -f 6714 5031 6692 -f 6692 5031 6716 -f 6692 6716 6715 -f 6715 6716 5030 -f 6715 5030 6691 -f 6691 5030 6717 -f 6691 6717 6718 -f 6718 6717 5047 -f 6718 5047 6719 -f 6719 5047 6720 -f 6719 6720 6693 -f 6693 6720 5045 -f 6693 5045 6695 -f 6695 5045 5044 -f 6695 5044 6694 -f 6694 5044 5043 -f 6694 5043 6721 -f 6721 5043 6723 -f 6721 6723 6722 -f 6722 6723 5145 -f 6722 5145 6697 -f 6697 5145 6724 -f 6697 6724 6725 -f 6725 6724 5050 -f 6725 5050 6696 -f 6696 5050 6726 -f 6696 6726 6727 -f 6727 6726 5042 -f 6727 5042 6728 -f 6728 5042 5041 -f 6728 5041 6698 -f 6698 5041 5040 -f 6698 5040 6729 -f 6729 5040 5039 -f 6729 5039 6730 -f 6730 5039 6731 -f 6730 6731 6699 -f 6699 6731 5038 -f 6699 5038 6681 -f 6681 5038 6700 -f 6749 6732 6736 -f 6753 6732 6749 -f 6749 6735 6733 -f 6734 6735 6749 -f 6736 6734 6749 -f 6749 6737 6761 -f 6759 6737 6749 -f 6733 6759 6749 -f 6749 6764 6738 -f 6763 6764 6749 -f 6761 6763 6749 -f 6749 6767 6741 -f 6766 6767 6749 -f 6738 6766 6749 -f 6749 6740 6739 -f 6770 6740 6749 -f 6741 6770 6749 -f 6749 6742 6743 -f 6774 6742 6749 -f 6739 6774 6749 -f 6749 6745 6776 -f 6744 6745 6749 -f 6743 6744 6749 -f 6749 6778 6746 -f 6777 6778 6749 -f 6776 6777 6749 -f 6749 6747 6782 -f 6748 6747 6749 -f 6746 6748 6749 -f 6749 6750 6786 -f 6784 6750 6749 -f 6782 6784 6749 -f 6749 6751 6752 -f 6788 6751 6749 -f 6786 6788 6749 -f 6752 6753 6749 -f 6753 6754 6732 -f 6732 6754 6755 -f 6732 6755 6736 -f 6736 6755 6756 -f 6736 6756 6734 -f 6734 6756 5015 -f 6734 5015 6735 -f 6735 5015 6757 -f 6735 6757 6733 -f 6733 6757 6758 -f 6733 6758 6759 -f 6759 6758 6760 -f 6759 6760 6737 -f 6737 6760 5024 -f 6737 5024 6761 -f 6761 5024 6762 -f 6761 6762 6763 -f 6763 6762 5028 -f 6763 5028 6764 -f 6764 5028 6765 -f 6764 6765 6738 -f 6738 6765 5026 -f 6738 5026 6766 -f 6766 5026 5017 -f 6766 5017 6767 -f 6767 5017 6768 -f 6767 6768 6741 -f 6741 6768 6769 -f 6741 6769 6770 -f 6770 6769 6771 -f 6770 6771 6740 -f 6740 6771 6772 -f 6740 6772 6739 -f 6739 6772 6773 -f 6739 6773 6774 -f 6774 6773 5014 -f 6774 5014 6742 -f 6742 5014 5016 -f 6742 5016 6743 -f 6743 5016 5023 -f 6743 5023 6744 -f 6744 5023 5022 -f 6744 5022 6745 -f 6745 5022 6775 -f 6745 6775 6776 -f 6776 6775 5020 -f 6776 5020 6777 -f 6777 5020 5021 -f 6777 5021 6778 -f 6778 5021 6779 -f 6778 6779 6746 -f 6746 6779 5029 -f 6746 5029 6748 -f 6748 5029 6780 -f 6748 6780 6747 -f 6747 6780 6781 -f 6747 6781 6782 -f 6782 6781 6783 -f 6782 6783 6784 -f 6784 6783 5025 -f 6784 5025 6750 -f 6750 5025 6785 -f 6750 6785 6786 -f 6786 6785 6787 -f 6786 6787 6788 -f 6788 6787 5019 -f 6788 5019 6751 -f 6751 5019 6789 -f 6751 6789 6752 -f 6752 6789 6790 -f 6752 6790 6753 -f 6753 6790 6754 -f 6792 6791 6809 -f 6807 6791 6792 -f 6792 6810 6793 -f 6794 6810 6792 -f 6809 6794 6792 -f 6792 6795 6814 -f 6812 6795 6792 -f 6793 6812 6792 -f 6792 6796 6820 -f 6816 6796 6792 -f 6814 6816 6792 -f 6792 6822 6797 -f 6821 6822 6792 -f 6820 6821 6792 -f 6792 6825 6826 -f 6823 6825 6792 -f 6797 6823 6792 -f 6792 6830 6799 -f 6829 6830 6792 -f 6826 6829 6792 -f 6792 6834 6798 -f 6833 6834 6792 -f 6799 6833 6792 -f 6792 6800 6837 -f 6836 6800 6792 -f 6798 6836 6792 -f 6792 6840 6801 -f 6802 6840 6792 -f 6837 6802 6792 -f 6792 6841 6803 -f 6804 6841 6792 -f 6801 6804 6792 -f 6792 6806 6805 -f 6844 6806 6792 -f 6803 6844 6792 -f 6805 6807 6792 -f 6807 6847 6791 -f 6791 6847 6808 -f 6791 6808 6809 -f 6809 6808 5167 -f 6809 5167 6794 -f 6794 5167 5146 -f 6794 5146 6810 -f 6810 5146 5153 -f 6810 5153 6793 -f 6793 5153 6811 -f 6793 6811 6812 -f 6812 6811 6813 -f 6812 6813 6795 -f 6795 6813 6815 -f 6795 6815 6814 -f 6814 6815 6817 -f 6814 6817 6816 -f 6816 6817 6818 -f 6816 6818 6796 -f 6796 6818 5165 -f 6796 5165 6820 -f 6820 5165 6819 -f 6820 6819 6821 -f 6821 6819 5152 -f 6821 5152 6822 -f 6822 5152 5151 -f 6822 5151 6797 -f 6797 5151 6824 -f 6797 6824 6823 -f 6823 6824 5150 -f 6823 5150 6825 -f 6825 5150 6827 -f 6825 6827 6826 -f 6826 6827 6828 -f 6826 6828 6829 -f 6829 6828 5156 -f 6829 5156 6830 -f 6830 5156 6831 -f 6830 6831 6799 -f 6799 6831 6832 -f 6799 6832 6833 -f 6833 6832 5149 -f 6833 5149 6834 -f 6834 5149 6835 -f 6834 6835 6798 -f 6798 6835 5155 -f 6798 5155 6836 -f 6836 5155 5154 -f 6836 5154 6800 -f 6800 5154 6838 -f 6800 6838 6837 -f 6837 6838 5164 -f 6837 5164 6802 -f 6802 5164 6839 -f 6802 6839 6840 -f 6840 6839 5162 -f 6840 5162 6801 -f 6801 5162 5161 -f 6801 5161 6804 -f 6804 5161 5160 -f 6804 5160 6841 -f 6841 5160 6842 -f 6841 6842 6803 -f 6803 6842 6843 -f 6803 6843 6844 -f 6844 6843 6845 -f 6844 6845 6806 -f 6806 6845 6846 -f 6806 6846 6805 -f 6805 6846 5148 -f 6805 5148 6807 -f 6807 5148 6847 -f 6863 6865 6866 -f 6848 6865 6863 -f 6863 6868 6850 -f 6849 6868 6863 -f 6866 6849 6863 -f 6863 6871 6872 -f 6851 6871 6863 -f 6850 6851 6863 -f 6863 6876 6878 -f 6852 6876 6863 -f 6872 6852 6863 -f 6863 6880 6854 -f 6853 6880 6863 -f 6878 6853 6863 -f 6863 6883 6857 -f 6881 6883 6863 -f 6854 6881 6863 -f 6863 6855 6856 -f 6858 6855 6863 -f 6857 6858 6863 -f 6863 6887 6859 -f 6886 6887 6863 -f 6856 6886 6863 -f 6863 6860 6891 -f 6889 6860 6863 -f 6859 6889 6863 -f 6863 6892 6861 -f 6862 6892 6863 -f 6891 6862 6863 -f 6863 6895 6898 -f 6894 6895 6863 -f 6861 6894 6863 -f 6863 6901 6902 -f 6864 6901 6863 -f 6898 6864 6863 -f 6902 6848 6863 -f 6848 5126 6865 -f 6865 5126 5127 -f 6865 5127 6866 -f 6866 5127 5111 -f 6866 5111 6849 -f 6849 5111 6867 -f 6849 6867 6868 -f 6868 6867 6869 -f 6868 6869 6850 -f 6850 6869 5119 -f 6850 5119 6851 -f 6851 5119 6870 -f 6851 6870 6871 -f 6871 6870 6873 -f 6871 6873 6872 -f 6872 6873 6874 -f 6872 6874 6852 -f 6852 6874 6875 -f 6852 6875 6876 -f 6876 6875 6877 -f 6876 6877 6878 -f 6878 6877 5118 -f 6878 5118 6853 -f 6853 5118 6879 -f 6853 6879 6880 -f 6880 6879 5117 -f 6880 5117 6854 -f 6854 5117 6882 -f 6854 6882 6881 -f 6881 6882 5116 -f 6881 5116 6883 -f 6883 5116 5113 -f 6883 5113 6857 -f 6857 5113 5112 -f 6857 5112 6858 -f 6858 5112 5115 -f 6858 5115 6855 -f 6855 5115 6884 -f 6855 6884 6856 -f 6856 6884 5114 -f 6856 5114 6886 -f 6886 5114 6885 -f 6886 6885 6887 -f 6887 6885 6888 -f 6887 6888 6859 -f 6859 6888 5110 -f 6859 5110 6889 -f 6889 5110 5123 -f 6889 5123 6860 -f 6860 5123 6890 -f 6860 6890 6891 -f 6891 6890 5122 -f 6891 5122 6862 -f 6862 5122 5121 -f 6862 5121 6892 -f 6892 5121 5120 -f 6892 5120 6861 -f 6861 5120 6893 -f 6861 6893 6894 -f 6894 6893 6896 -f 6894 6896 6895 -f 6895 6896 6897 -f 6895 6897 6898 -f 6898 6897 6899 -f 6898 6899 6864 -f 6864 6899 6900 -f 6864 6900 6901 -f 6901 6900 6903 -f 6901 6903 6902 -f 6902 6903 5109 -f 6902 5109 6848 -f 6848 5109 5126 -f 7040 7042 7057 -f 7059 6904 7057 -f 7057 6904 7038 -f 7045 7047 7050 -f 7038 7040 7057 -f 7042 7044 7050 -f 7042 6905 7057 -f 6905 7042 6906 -f 6906 7042 6907 -f 6907 7042 7051 -f 7044 7045 7050 -f 7051 7042 7050 -f 7050 7047 7049 -f 4402 6908 4401 -f 4402 4403 6908 -f 6913 6908 4403 -f 4394 4396 4410 -f 4396 6911 4410 -f 4403 6909 6911 -f 6910 6911 6909 -f 6910 6912 6911 -f 6911 6912 4407 -f 6911 4407 4410 -f 6914 4394 4410 -f 6911 6913 4403 -f 4410 6915 6914 -f 4410 6917 6915 -f 6919 7174 6918 -f 6916 7176 7174 -f 7201 7191 7197 -f 7174 6919 7171 -f 7174 7176 6918 -f 6918 7178 7179 -f 6919 6918 7179 -f 7172 7174 7171 -f 6920 6919 6922 -f 7169 6920 6922 -f 7180 7181 6919 -f 6919 7181 6921 -f 6919 6920 7171 -f 6922 6919 6921 -f 6929 6922 6921 -f 6923 6930 6929 -f 7182 7184 6921 -f 7184 6929 6921 -f 7165 6929 7184 -f 7184 7166 7165 -f 7184 7185 7166 -f 7185 7201 7166 -f 7185 7188 7201 -f 7188 7191 7201 -f 7190 7191 7188 -f 7197 6926 6927 -f 6924 7201 6925 -f 6925 7201 7197 -f 7191 6926 7197 -f 6927 7193 7194 -f 7196 7197 6927 -f 6927 6928 7196 -f 6929 6930 6922 -f 4551 6933 4550 -f 4553 4554 6934 -f 6946 6945 6931 -f 6933 6932 4550 -f 4531 6944 6948 -f 6932 6933 6934 -f 6935 6946 6931 -f 6948 4534 6949 -f 4531 6940 6941 -f 6946 6932 4554 -f 4548 4550 6932 -f 4548 6932 6936 -f 6936 6932 4524 -f 6936 4524 4546 -f 4524 6937 6938 -f 4546 4524 6939 -f 6939 4524 6938 -f 6938 4543 6939 -f 4543 4544 6939 -f 6932 6934 4554 -f 4543 6943 4519 -f 4543 4519 4542 -f 4542 4519 6941 -f 6941 6940 4542 -f 4531 6941 4530 -f 6940 4541 4542 -f 6928 6927 7194 -f 6940 4531 6942 -f 6941 4528 4530 -f 4540 6940 6942 -f 6938 6943 4543 -f 6942 4531 6948 -f 6948 6944 4534 -f 6945 6946 4554 -f 6947 6948 6949 -f 6957 7127 7126 -f 6952 7092 7103 -f 7093 6952 7112 -f 6952 7103 6950 -f 7112 6952 7114 -f 6952 6950 7101 -f 7114 6952 7115 -f 6952 7101 7100 -f 7115 6952 7117 -f 6952 7100 7098 -f 7117 6952 6951 -f 6952 7098 7097 -f 6951 6952 7121 -f 6952 7097 7096 -f 7121 6952 6953 -f 6952 7096 7087 -f 6957 6952 7087 -f 6953 6952 6961 -f 6954 6957 7087 -f 6957 6955 6961 -f 6956 6957 6954 -f 6957 7122 6955 -f 7108 6957 6956 -f 6957 7124 7122 -f 7110 6957 7108 -f 7106 6957 7110 -f 6957 6958 7124 -f 7105 6957 7106 -f 6957 6960 6958 -f 6959 6957 7105 -f 6957 7126 6960 -f 7104 6957 6959 -f 6952 6957 6961 -f 7091 7127 6957 -f 6983 6962 6972 -f 6964 4447 6970 -f 6964 6969 4476 -f 4448 6964 6963 -f 6964 4476 4475 -f 6963 6964 4451 -f 6964 4475 4473 -f 4451 6964 4452 -f 6964 4473 6965 -f 4452 6964 6966 -f 6964 6965 6967 -f 6966 6964 6968 -f 6964 6967 4471 -f 6968 6964 4455 -f 6964 4471 4470 -f 4455 6964 4454 -f 6964 4470 4447 -f 4454 6964 4457 -f 6964 6972 4439 -f 4457 6964 4458 -f 6972 6964 6970 -f 6964 4446 6969 -f 6971 6972 6970 -f 4458 6964 4439 -f 6974 6972 6971 -f 6972 6973 4439 -f 6975 6972 6974 -f 6972 6976 6973 -f 6977 6972 6975 -f 6972 4459 6976 -f 6978 6972 6977 -f 6972 6979 4459 -f 6981 6972 6978 -f 6972 4461 6979 -f 6980 6972 6981 -f 6972 4463 4461 -f 6982 6972 6980 -f 6972 4464 4463 -f 6983 6972 6982 -f 6972 4465 4464 -f 6972 4467 4465 -f 7104 6984 6957 -f 6986 2572 6987 -f 6987 6985 6986 -f 2490 2543 6985 -f 2588 6986 2455 -f 2490 6985 6987 -f 6985 2455 6986 -f 6985 6989 2455 -f 4467 6972 4468 -f 5166 5103 5091 -f 6988 5141 5052 -f 5108 6988 5091 -f 5052 5166 6988 -f 6989 6985 2541 -f 5057 5166 5052 -f 5166 5091 6988 -f 5147 5103 5166 -f 5057 5174 5166 -f 6992 7311 9578 -f 9578 7311 7312 -f 9578 7312 6990 -f 9578 6990 4921 -f 6994 6991 7308 -f 6994 7308 7309 -f 6994 7309 6992 -f 6992 7309 7311 -f 6997 7305 6993 -f 7002 7305 7307 -f 7307 6991 7002 -f 7002 6991 6994 -f 6995 7563 7317 -f 6995 7317 6996 -f 6995 6996 6997 -f 6995 6997 6993 -f 6996 7318 6997 -f 6997 7318 7303 -f 7303 7318 7314 -f 7303 7314 7300 -f 7300 7314 7299 -f 7299 7314 7315 -f 7299 7315 6998 -f 7299 6998 7000 -f 7000 6998 6999 -f 6999 7563 7000 -f 7000 7563 7001 -f 7001 7563 6995 -f 6993 7305 7002 -f 6993 7002 4337 -f 4337 7002 7003 -f 4337 7003 4345 -f 4345 7003 4353 -f 4345 4353 7004 -f 7004 4353 4352 -f 7004 4352 4343 -f 4343 4352 7005 -f 4343 7005 7006 -f 7006 7005 7007 -f 7006 7007 7008 -f 7008 7007 7009 -f 7008 7009 4344 -f 4344 7009 4351 -f 4344 4351 7010 -f 7076 7085 7060 -f 7085 4925 7064 -f 7064 7011 7085 -f 7085 7011 7062 -f 7085 7062 7060 -f 7012 7076 7013 -f 7015 7014 7012 -f 7012 7014 7076 -f 7014 7015 7017 -f 7014 7017 7072 -f 5193 7071 7016 -f 7016 7071 7072 -f 7016 7072 7017 -f 4924 9518 7018 -f 9518 7015 7012 -f 9517 7025 7019 -f 7019 7321 9517 -f 9517 7321 7323 -f 9517 7323 7020 -f 7015 9518 7017 -f 7017 9518 7016 -f 7018 9518 7026 -f 7026 9518 7012 -f 7026 7012 7013 -f 7021 4924 4926 -f 9519 7389 7032 -f 7032 7389 7390 -f 7032 7390 7022 -f 7022 7392 7032 -f 7032 7392 7393 -f 7032 7393 7023 -f 7032 7024 9517 -f 9517 7024 7320 -f 9517 7320 7025 -f 7412 7348 7032 -f 7061 7026 7037 -f 7037 7026 7013 -f 7032 7348 7024 -f 7024 7348 7350 -f 7024 7350 7414 -f 7061 7063 7026 -f 7023 7027 7032 -f 7032 7027 7028 -f 7032 7028 7410 -f 7416 7029 7030 -f 7410 7031 7032 -f 7032 7031 7033 -f 7032 7033 7412 -f 7414 7415 7024 -f 7024 7415 7416 -f 7024 7416 7420 -f 7420 7416 7030 -f 7053 7062 7054 -f 7054 7062 7061 -f 7062 7053 7052 -f 7062 7052 7034 -f 7056 7055 7061 -f 7061 7055 7054 -f 7062 7034 7049 -f 7062 7049 7060 -f 7061 7035 7056 -f 7049 7048 7060 -f 7060 7048 7046 -f 7060 7046 7036 -f 7060 7036 7043 -f 7060 7043 7037 -f 7037 7043 7041 -f 7037 7039 7058 -f 7037 7058 7061 -f 7061 7058 7035 -f 7037 7041 7039 -f 6904 7058 7039 -f 6904 7039 7038 -f 7038 7039 7041 -f 7038 7041 7040 -f 7040 7041 7042 -f 7042 7041 7043 -f 7042 7043 7044 -f 7044 7043 7036 -f 7044 7036 7045 -f 7045 7036 7046 -f 7045 7046 7047 -f 7047 7046 7048 -f 7047 7048 7049 -f 7050 7049 7034 -f 7050 7034 7052 -f 7050 7052 7051 -f 7051 7052 6907 -f 6907 7052 7053 -f 6907 7053 6906 -f 6906 7053 7054 -f 6906 7054 6905 -f 6905 7054 7055 -f 6905 7055 7056 -f 6905 7056 7057 -f 7057 7056 7035 -f 7035 7059 7057 -f 7058 6904 7059 -f 7058 7059 7035 -f 7013 7076 7060 -f 7013 7060 7037 -f 7061 7062 7011 -f 7061 7011 7063 -f 7063 7011 7064 -f 7063 7064 7026 -f 5193 7065 7071 -f 5189 7075 7080 -f 7079 7078 7072 -f 7072 7078 7014 -f 7084 7085 7076 -f 4925 7085 7066 -f 7067 7066 7068 -f 7067 7068 7083 -f 7067 7083 7069 -f 7069 7083 7073 -f 7069 7074 4923 -f 4923 7074 7070 -f 7070 7074 5191 -f 7070 5191 7387 -f 7065 5188 7071 -f 7071 5188 7079 -f 7071 7079 7072 -f 7069 7073 7074 -f 7074 7073 7080 -f 7074 7080 7075 -f 7074 7075 5191 -f 7084 7076 7014 -f 7084 7014 7077 -f 7077 7014 7078 -f 7077 7078 7082 -f 7082 7078 7079 -f 7082 7079 7081 -f 7081 7079 5188 -f 7081 5188 5189 -f 5189 7080 7081 -f 7081 7080 7073 -f 7081 7073 7082 -f 7082 7073 7083 -f 7082 7083 7077 -f 7077 7083 7068 -f 7077 7068 7066 -f 7077 7066 7084 -f 7084 7066 7085 -f 7096 2237 7087 -f 7087 2237 7086 -f 7087 7086 6954 -f 6957 6984 7089 -f 4931 7091 7088 -f 7089 7090 6957 -f 6957 7090 4927 -f 6957 4927 7091 -f 7091 4927 4928 -f 7091 4928 7088 -f 2247 7092 7095 -f 7095 7092 6952 -f 7113 4935 7093 -f 7093 4935 7094 -f 7093 7094 6952 -f 6952 7094 2245 -f 6952 2245 7095 -f 6955 4934 6961 -f 6961 4934 7119 -f 6961 7119 6953 -f 2237 7096 7097 -f 2237 7097 2240 -f 2240 7097 7098 -f 2240 7098 7099 -f 7099 7098 7100 -f 7099 7100 7102 -f 7102 7100 7101 -f 7102 7101 6950 -f 7102 6950 2247 -f 2247 6950 7103 -f 2247 7103 7092 -f 7089 6984 7104 -f 7089 7104 2231 -f 2231 7104 6959 -f 2231 6959 7105 -f 2231 7105 7107 -f 7107 7105 7106 -f 7107 7106 7110 -f 7107 7110 7109 -f 7108 6956 7111 -f 7111 7109 7108 -f 7108 7109 7110 -f 6956 6954 7086 -f 7086 7111 6956 -f 7113 7093 7112 -f 7113 7112 7114 -f 7113 7114 7116 -f 7116 7114 7115 -f 7116 7115 7117 -f 7116 7117 7118 -f 7118 7117 6951 -f 6951 7121 7120 -f 6951 7120 7118 -f 7121 6953 7119 -f 7119 7120 7121 -f 4934 6955 7123 -f 7123 6955 7122 -f 7123 7122 7124 -f 7123 7124 4929 -f 4929 7124 6958 -f 4929 6958 7125 -f 7125 6958 6960 -f 7125 6960 7126 -f 7125 7126 7128 -f 7128 7126 7127 -f 7128 7127 7091 -f 7128 7091 4931 -f 7136 7282 7130 -f 7130 7282 7129 -f 7290 7257 7130 -f 7290 7130 7129 -f 7290 7255 7257 -f 7291 7255 7290 -f 7291 7265 7255 -f 7291 7131 7265 -f 7265 7131 7264 -f 7131 7287 7264 -f 7264 7287 7260 -f 7260 7287 7288 -f 7260 7288 7132 -f 7132 7288 7284 -f 7294 7133 7132 -f 7294 7132 7284 -f 7133 7294 7134 -f 7134 7294 5194 -f 7134 5194 5202 -f 7252 7218 7135 -f 7135 7218 7280 -f 7135 7280 7136 -f 7136 7280 7282 -f 7138 7187 7267 -f 7137 7170 7139 -f 7200 7140 7202 -f 7138 7267 7189 -f 7137 7139 7173 -f 7170 7168 7139 -f 7139 7168 7167 -f 7200 7199 7140 -f 7140 7199 7198 -f 7140 7198 7195 -f 7195 7141 7140 -f 7140 7141 7142 -f 7140 7142 7153 -f 7150 7177 7248 -f 7187 7186 7267 -f 7267 7186 7143 -f 7267 7143 7233 -f 7233 7143 7183 -f 7233 7183 7144 -f 7144 7145 7233 -f 7233 7145 7146 -f 7233 7146 7246 -f 7246 7146 7147 -f 7177 7148 7248 -f 7248 7148 7175 -f 7248 7175 7139 -f 7139 7175 7149 -f 7139 7149 7173 -f 7150 7248 7147 -f 7147 7248 7246 -f 7142 7151 7153 -f 7153 7151 7152 -f 7153 7152 7192 -f 7153 7192 7276 -f 7276 7192 7154 -f 7189 7267 7154 -f 7154 7267 7276 -f 7232 7271 5201 -f 5201 7271 7241 -f 7155 7156 7240 -f 7155 7240 7271 -f 7156 7238 7240 -f 7271 7240 7241 -f 7157 7160 7158 -f 7156 7160 7238 -f 7238 7160 7235 -f 7235 7160 7157 -f 7267 7233 7159 -f 7159 7233 7158 -f 7159 7158 7160 -f 7161 7223 7245 -f 7245 7247 7161 -f 7275 7281 7162 -f 7162 7281 7163 -f 7208 7205 6923 -f 6930 7207 6922 -f 6923 7205 6930 -f 6930 7205 7206 -f 6930 7206 7207 -f 7208 6923 7209 -f 7209 6923 6929 -f 7209 6929 7164 -f 7164 6929 7165 -f 7164 7165 7203 -f 7203 7165 7166 -f 7203 7166 7204 -f 7204 7166 7201 -f 7204 7201 7202 -f 7207 7167 6922 -f 6922 7167 7169 -f 7169 7167 7168 -f 7169 7168 6920 -f 6920 7168 7170 -f 6920 7170 7171 -f 7171 7170 7137 -f 7171 7137 7172 -f 7172 7137 7173 -f 7172 7173 7174 -f 7174 7173 7149 -f 7174 7149 6916 -f 6916 7149 7175 -f 6916 7175 7176 -f 7176 7175 7148 -f 7176 7148 6918 -f 6918 7148 7177 -f 6918 7177 7178 -f 7178 7177 7150 -f 7178 7150 7179 -f 7179 7150 7147 -f 7179 7147 6919 -f 6919 7147 7146 -f 6919 7146 7180 -f 7180 7146 7145 -f 7180 7145 7181 -f 7181 7145 7144 -f 7181 7144 6921 -f 6921 7144 7183 -f 6921 7183 7182 -f 7182 7183 7143 -f 7182 7143 7184 -f 7184 7143 7186 -f 7184 7186 7185 -f 7185 7186 7187 -f 7185 7187 7188 -f 7188 7187 7138 -f 7188 7138 7190 -f 7190 7138 7189 -f 7190 7189 7191 -f 7191 7189 7154 -f 7191 7154 6926 -f 6926 7154 7192 -f 6926 7192 6927 -f 6927 7192 7152 -f 6927 7152 7193 -f 7193 7152 7151 -f 7193 7151 7194 -f 7194 7151 7142 -f 7194 7142 6928 -f 6928 7142 7141 -f 6928 7141 7196 -f 7196 7141 7195 -f 7196 7195 7197 -f 7197 7195 7198 -f 7197 7198 6925 -f 6925 7198 7199 -f 6925 7199 6924 -f 6924 7199 7200 -f 6924 7200 7201 -f 7201 7200 7202 -f 7204 7202 7140 -f 7164 7211 7209 -f 7164 7203 7211 -f 7211 7203 7140 -f 7140 7203 7204 -f 7208 7210 7205 -f 7205 7210 7206 -f 7206 7210 7139 -f 7206 7139 7207 -f 7139 7167 7207 -f 7208 7209 7210 -f 7210 7209 7211 -f 7210 7211 7249 -f 7249 7211 7213 -f 7249 7213 7212 -f 7212 7213 7250 -f 7250 7213 7279 -f 7250 7279 7215 -f 7215 7279 7214 -f 7215 7214 7251 -f 7251 7214 7216 -f 7251 7216 7217 -f 7217 7216 7278 -f 7217 7278 7252 -f 7252 7278 7218 -f 5202 5201 7243 -f 5202 7243 7133 -f 7133 7243 7242 -f 7239 7259 7242 -f 7242 7259 7133 -f 7262 7237 7263 -f 7262 7261 7237 -f 7237 7261 7239 -f 7239 7261 7259 -f 7237 7236 7263 -f 7263 7236 7266 -f 7266 7236 7234 -f 7266 7234 7254 -f 7254 7234 7219 -f 7258 7254 7219 -f 7219 7220 7258 -f 7258 7220 7221 -f 7258 7221 7256 -f 7221 7244 7256 -f 7256 7244 7253 -f 7253 7244 7222 -f 7245 7223 7222 -f 7222 7223 7253 -f 7281 7275 7224 -f 7224 7275 7226 -f 7225 7227 7226 -f 7226 7227 7289 -f 7224 7226 7289 -f 7228 7292 7227 -f 7228 7227 7225 -f 7228 7229 7292 -f 7292 7229 7274 -f 7292 7274 7230 -f 7297 7296 7268 -f 7292 7230 7296 -f 7296 7230 7277 -f 7296 7277 7268 -f 7297 7268 7272 -f 7297 7272 7285 -f 7283 7286 7270 -f 7272 7273 7285 -f 7285 7273 7286 -f 7286 7273 7270 -f 7293 7283 7270 -f 7270 7231 7293 -f 7293 7231 7295 -f 7231 7232 7295 -f 7295 7232 5194 -f 7233 7219 7158 -f 7158 7219 7234 -f 7158 7234 7236 -f 7158 7236 7157 -f 7157 7236 7235 -f 7235 7236 7237 -f 7235 7237 7238 -f 7243 5201 7241 -f 7238 7237 7239 -f 7238 7239 7240 -f 7240 7239 7242 -f 7240 7242 7241 -f 7241 7242 7243 -f 7246 7248 7244 -f 7219 7233 7246 -f 7219 7246 7220 -f 7244 7248 7222 -f 7222 7248 7245 -f 7246 7244 7221 -f 7246 7221 7220 -f 7139 7247 7248 -f 7248 7247 7245 -f 7139 7210 7247 -f 7210 7249 7247 -f 7249 7212 7247 -f 7247 7212 7250 -f 7247 7250 7215 -f 7247 7215 7251 -f 7247 7251 7217 -f 7247 7217 7161 -f 7161 7217 7252 -f 7135 7223 7252 -f 7252 7223 7161 -f 7136 7253 7223 -f 7135 7136 7223 -f 7253 7130 7256 -f 7253 7136 7130 -f 7265 7254 7255 -f 7255 7254 7258 -f 7256 7130 7257 -f 7256 7257 7258 -f 7258 7257 7255 -f 7133 7134 5202 -f 7133 7259 7132 -f 7132 7259 7260 -f 7260 7259 7261 -f 7260 7261 7264 -f 7264 7261 7262 -f 7264 7262 7263 -f 7264 7263 7266 -f 7264 7266 7265 -f 7265 7266 7254 -f 7277 7267 7268 -f 7268 7267 7269 -f 7270 7156 7231 -f 7231 7156 7271 -f 7269 7273 7272 -f 7269 7272 7268 -f 7269 7267 7159 -f 7269 7159 7160 -f 7160 7156 7269 -f 7269 7156 7273 -f 7273 7156 7270 -f 7271 7232 7231 -f 7156 7155 7271 -f 7275 7153 7226 -f 7274 7276 7230 -f 7230 7276 7267 -f 7230 7267 7277 -f 7274 7229 7276 -f 7276 7229 7228 -f 7276 7228 7225 -f 7276 7225 7153 -f 7153 7225 7226 -f 7162 7140 7275 -f 7275 7140 7153 -f 7163 7218 7278 -f 7278 7216 7163 -f 7216 7214 7163 -f 7214 7279 7163 -f 7279 7213 7163 -f 7163 7213 7211 -f 7163 7211 7140 -f 7163 7140 7162 -f 7281 7280 7163 -f 7163 7280 7218 -f 7280 7281 7224 -f 7280 7224 7282 -f 7287 7297 7285 -f 7287 7285 7286 -f 7287 7286 7283 -f 7287 7283 7288 -f 7288 7283 7284 -f 7224 7129 7282 -f 7224 7289 7129 -f 7129 7289 7227 -f 7129 7227 7290 -f 7290 7227 7292 -f 7291 7292 7131 -f 7290 7292 7291 -f 7283 7293 7284 -f 7284 7293 7294 -f 7294 7293 7295 -f 7294 7295 5194 -f 7292 7296 7131 -f 7131 7296 7297 -f 7131 7297 7287 -f 7573 4922 7313 -f 7573 7299 7298 -f 7573 7298 4922 -f 7570 7299 7573 -f 7570 7300 7299 -f 7301 7300 7570 -f 7301 7303 7300 -f 7301 7302 7303 -f 7303 7302 7571 -f 7303 7571 6997 -f 6997 7571 7304 -f 6997 7304 7305 -f 7305 7304 7306 -f 7305 7306 7307 -f 7307 7306 7572 -f 7307 7572 6991 -f 6991 7572 7310 -f 6991 7310 7308 -f 7308 7310 7309 -f 7309 7310 7311 -f 7311 7310 7574 -f 7311 7574 7312 -f 7574 7313 6990 -f 6990 7312 7574 -f 4922 4921 7313 -f 7313 4921 6990 -f 7315 7314 7565 -f 7316 7315 7565 -f 7316 6998 7315 -f 7564 6998 7316 -f 7564 6999 6998 -f 7575 6999 7564 -f 7575 7563 6999 -f 7569 7317 7563 -f 7568 6996 7569 -f 7569 6996 7317 -f 7567 7318 7568 -f 7568 7318 6996 -f 7566 7314 7318 -f 7566 7318 7567 -f 7024 7405 7320 -f 7320 7405 7319 -f 7320 7319 7025 -f 7025 7319 7399 -f 7025 7399 7019 -f 7019 7399 7322 -f 7019 7322 7321 -f 7321 7322 7324 -f 7321 7324 7323 -f 7323 7324 7395 -f 7323 7395 7020 -f 7020 7395 7325 -f 7559 7558 7348 -f 7559 7348 7326 -f 7513 7350 7514 -f 7514 7350 7515 -f 7364 7452 7362 -f 7544 7384 7327 -f 7327 7384 7333 -f 7544 7328 7384 -f 7384 7328 7329 -f 7384 7329 7372 -f 7547 7330 7350 -f 7350 7330 7331 -f 7350 7331 7545 -f 7369 7332 7376 -f 7376 7332 7531 -f 7376 7531 7348 -f 7348 7531 7561 -f 7348 7561 7326 -f 7333 7334 7327 -f 7327 7334 7335 -f 7327 7335 7520 -f 7515 7350 7336 -f 7336 7350 7545 -f 7336 7545 7518 -f 7518 7545 7327 -f 7518 7327 7345 -f 7513 7512 7350 -f 7350 7512 7338 -f 7350 7338 7337 -f 7337 7338 7510 -f 7337 7510 7509 -f 7509 7507 7337 -f 7337 7507 7505 -f 7337 7505 7352 -f 7558 7339 7348 -f 7348 7339 7441 -f 7348 7441 7347 -f 7340 7341 7350 -f 7350 7341 7461 -f 7461 7459 7350 -f 7350 7459 7342 -f 7350 7342 7343 -f 7520 7344 7327 -f 7327 7344 7519 -f 7327 7519 7345 -f 7443 7346 7558 -f 7558 7346 7442 -f 7558 7442 7339 -f 7347 7470 7348 -f 7348 7470 7349 -f 7348 7349 7469 -f 7343 7458 7350 -f 7350 7458 7351 -f 7350 7351 7361 -f 7352 7353 7337 -f 7337 7353 7502 -f 7337 7502 7354 -f 7362 7452 7355 -f 7355 7452 7451 -f 7355 7451 7450 -f 7450 7356 7355 -f 7355 7356 7381 -f 7355 7381 7383 -f 7469 7357 7348 -f 7348 7357 7468 -f 7348 7468 7358 -f 7358 7465 7348 -f 7348 7465 7359 -f 7348 7359 7350 -f 7350 7359 7360 -f 7350 7360 7340 -f 7547 7350 7548 -f 7548 7350 7361 -f 7548 7361 7362 -f 7362 7361 7363 -f 7362 7363 7364 -f 7498 7365 7376 -f 7366 7493 7376 -f 7376 7493 7367 -f 7376 7367 7490 -f 7535 7368 7376 -f 7376 7368 7533 -f 7376 7533 7369 -f 7354 7370 7337 -f 7337 7370 7499 -f 7337 7499 7376 -f 7376 7499 7371 -f 7376 7371 7498 -f 7372 7540 7384 -f 7384 7540 7539 -f 7365 7495 7376 -f 7376 7495 7373 -f 7376 7373 7366 -f 7556 7374 7558 -f 7558 7374 7375 -f 7558 7375 7443 -f 7490 7526 7376 -f 7376 7526 7523 -f 7376 7523 7384 -f 7556 7554 7374 -f 7374 7554 7377 -f 7377 7554 7379 -f 7377 7379 7378 -f 7378 7379 7380 -f 7380 7379 7382 -f 7380 7382 7381 -f 7381 7382 7383 -f 7384 7539 7537 -f 7384 7537 7376 -f 7376 7537 7535 -f 7387 7385 7386 -f 7387 7386 7388 -f 9519 7388 7389 -f 7389 7388 7386 -f 7389 7386 7390 -f 7390 7386 7391 -f 7390 7391 7022 -f 7022 7391 7398 -f 7022 7398 7392 -f 7392 7398 7394 -f 7392 7394 7393 -f 7393 7394 7397 -f 7393 7397 7023 -f 7023 7397 7403 -f 7324 7396 7395 -f 7395 7396 7325 -f 7324 7322 7396 -f 7396 7322 7399 -f 7396 7399 7400 -f 7399 7397 7394 -f 7399 7319 7397 -f 7397 7319 7405 -f 7397 7405 7403 -f 7394 7398 7399 -f 7399 7398 7391 -f 7399 7391 7400 -f 7400 7391 7386 -f 7400 7386 7385 -f 7407 7403 7401 -f 7401 7403 7411 -f 7413 7402 7405 -f 7405 7402 7337 -f 7405 7337 7403 -f 7403 7337 7376 -f 7403 7376 7411 -f 7418 7417 7406 -f 7409 7408 7401 -f 7401 7408 7404 -f 7401 7404 7407 -f 7413 7405 7406 -f 7406 7405 7419 -f 7406 7419 7418 -f 7023 7403 7407 -f 7023 7407 7027 -f 7027 7407 7404 -f 7027 7404 7028 -f 7028 7404 7408 -f 7028 7408 7410 -f 7410 7408 7409 -f 7410 7409 7031 -f 7031 7409 7401 -f 7031 7401 7033 -f 7033 7401 7411 -f 7033 7411 7412 -f 7412 7411 7376 -f 7412 7376 7348 -f 7350 7337 7402 -f 7350 7402 7414 -f 7414 7402 7413 -f 7414 7413 7415 -f 7415 7413 7406 -f 7415 7406 7416 -f 7416 7406 7417 -f 7416 7417 7029 -f 7029 7417 7418 -f 7029 7418 7030 -f 7030 7418 7419 -f 7030 7419 7420 -f 7420 7419 7405 -f 7420 7405 7024 -f 7426 7421 7440 -f 7439 7421 7426 -f 7426 7422 7423 -f 7424 7422 7426 -f 7440 7424 7426 -f 7426 7445 7425 -f 7444 7445 7426 -f 7423 7444 7426 -f 7426 7427 7447 -f 7446 7427 7426 -f 7425 7446 7426 -f 7426 7448 7449 -f 7428 7448 7426 -f 7447 7428 7426 -f 7426 7429 7453 -f 7430 7429 7426 -f 7449 7430 7426 -f 7426 7455 7456 -f 7454 7455 7426 -f 7453 7454 7426 -f 7426 7431 7433 -f 7457 7431 7426 -f 7456 7457 7426 -f 7426 7432 7462 -f 7460 7432 7426 -f 7433 7460 7426 -f 7426 7434 7464 -f 7463 7434 7426 -f 7462 7463 7426 -f 7426 7435 7467 -f 7466 7435 7426 -f 7464 7466 7426 -f 7426 7436 7438 -f 7437 7436 7426 -f 7467 7437 7426 -f 7438 7439 7426 -f 7439 7347 7421 -f 7421 7347 7441 -f 7421 7441 7440 -f 7440 7441 7339 -f 7440 7339 7424 -f 7424 7339 7442 -f 7424 7442 7422 -f 7422 7442 7346 -f 7422 7346 7423 -f 7423 7346 7443 -f 7423 7443 7444 -f 7444 7443 7375 -f 7444 7375 7445 -f 7445 7375 7374 -f 7445 7374 7425 -f 7425 7374 7377 -f 7425 7377 7446 -f 7446 7377 7378 -f 7446 7378 7427 -f 7427 7378 7380 -f 7427 7380 7447 -f 7447 7380 7381 -f 7447 7381 7428 -f 7428 7381 7356 -f 7428 7356 7448 -f 7448 7356 7450 -f 7448 7450 7449 -f 7449 7450 7451 -f 7449 7451 7430 -f 7430 7451 7452 -f 7430 7452 7429 -f 7429 7452 7364 -f 7429 7364 7453 -f 7453 7364 7363 -f 7453 7363 7454 -f 7454 7363 7361 -f 7454 7361 7455 -f 7455 7361 7351 -f 7455 7351 7456 -f 7456 7351 7458 -f 7456 7458 7457 -f 7457 7458 7343 -f 7457 7343 7431 -f 7431 7343 7342 -f 7431 7342 7433 -f 7433 7342 7459 -f 7433 7459 7460 -f 7460 7459 7461 -f 7460 7461 7432 -f 7432 7461 7341 -f 7432 7341 7462 -f 7462 7341 7340 -f 7462 7340 7463 -f 7463 7340 7360 -f 7463 7360 7434 -f 7434 7360 7359 -f 7434 7359 7464 -f 7464 7359 7465 -f 7464 7465 7466 -f 7466 7465 7358 -f 7466 7358 7435 -f 7435 7358 7468 -f 7435 7468 7467 -f 7467 7468 7357 -f 7467 7357 7437 -f 7437 7357 7469 -f 7437 7469 7436 -f 7436 7469 7349 -f 7436 7349 7438 -f 7438 7349 7470 -f 7438 7470 7439 -f 7439 7470 7347 -f 7474 7471 7472 -f 7525 7471 7474 -f 7474 7492 7494 -f 7491 7492 7474 -f 7472 7491 7474 -f 7474 7496 7497 -f 7473 7496 7474 -f 7494 7473 7474 -f 7474 7475 7476 -f 7477 7475 7474 -f 7497 7477 7474 -f 7474 7501 7503 -f 7500 7501 7474 -f 7476 7500 7474 -f 7474 7506 7478 -f 7504 7506 7474 -f 7503 7504 7474 -f 7474 7508 7511 -f 7479 7508 7474 -f 7478 7479 7474 -f 7474 7482 7480 -f 7481 7482 7474 -f 7511 7481 7474 -f 7474 7516 7517 -f 7483 7516 7474 -f 7480 7483 7474 -f 7474 7485 7487 -f 7484 7485 7474 -f 7517 7484 7474 -f 7474 7486 7521 -f 7488 7486 7474 -f 7487 7488 7474 -f 7474 7489 7524 -f 7522 7489 7474 -f 7521 7522 7474 -f 7524 7525 7474 -f 7525 7526 7471 -f 7471 7526 7490 -f 7471 7490 7472 -f 7472 7490 7367 -f 7472 7367 7491 -f 7491 7367 7493 -f 7491 7493 7492 -f 7492 7493 7366 -f 7492 7366 7494 -f 7494 7366 7373 -f 7494 7373 7473 -f 7473 7373 7495 -f 7473 7495 7496 -f 7496 7495 7365 -f 7496 7365 7497 -f 7497 7365 7498 -f 7497 7498 7477 -f 7477 7498 7371 -f 7477 7371 7475 -f 7475 7371 7499 -f 7475 7499 7476 -f 7476 7499 7370 -f 7476 7370 7500 -f 7500 7370 7354 -f 7500 7354 7501 -f 7501 7354 7502 -f 7501 7502 7503 -f 7503 7502 7353 -f 7503 7353 7504 -f 7504 7353 7352 -f 7504 7352 7506 -f 7506 7352 7505 -f 7506 7505 7478 -f 7478 7505 7507 -f 7478 7507 7479 -f 7479 7507 7509 -f 7479 7509 7508 -f 7508 7509 7510 -f 7508 7510 7511 -f 7511 7510 7338 -f 7511 7338 7481 -f 7481 7338 7512 -f 7481 7512 7482 -f 7482 7512 7513 -f 7482 7513 7480 -f 7480 7513 7514 -f 7480 7514 7483 -f 7483 7514 7515 -f 7483 7515 7516 -f 7516 7515 7336 -f 7516 7336 7517 -f 7517 7336 7518 -f 7517 7518 7484 -f 7484 7518 7345 -f 7484 7345 7485 -f 7485 7345 7519 -f 7485 7519 7487 -f 7487 7519 7344 -f 7487 7344 7488 -f 7488 7344 7520 -f 7488 7520 7486 -f 7486 7520 7335 -f 7486 7335 7521 -f 7521 7335 7334 -f 7521 7334 7522 -f 7522 7334 7333 -f 7522 7333 7489 -f 7489 7333 7384 -f 7489 7384 7524 -f 7524 7384 7523 -f 7524 7523 7525 -f 7525 7523 7526 -f 7527 7562 7532 -f 7532 7534 7527 -f 7527 7536 7538 -f 7534 7536 7527 -f 7538 7541 7527 -f 7527 7542 7543 -f 7541 7542 7527 -f 7543 7528 7527 -f 7529 7546 7527 -f 7528 7529 7527 -f 7530 7549 7527 -f 7546 7530 7527 -f 7527 7550 7551 -f 7549 7550 7527 -f 7527 7552 7553 -f 7551 7552 7527 -f 7527 7555 7557 -f 7553 7555 7527 -f 7557 7560 7527 -f 7560 7562 7527 -f 7562 7531 7332 -f 7562 7332 7532 -f 7532 7332 7369 -f 7532 7369 7533 -f 7532 7533 7534 -f 7534 7533 7368 -f 7534 7368 7535 -f 7534 7535 7536 -f 7536 7535 7537 -f 7536 7537 7538 -f 7538 7537 7539 -f 7538 7539 7541 -f 7541 7539 7540 -f 7541 7540 7542 -f 7542 7540 7372 -f 7542 7372 7329 -f 7542 7329 7543 -f 7543 7329 7328 -f 7543 7328 7544 -f 7543 7544 7528 -f 7528 7544 7327 -f 7528 7327 7545 -f 7528 7545 7529 -f 7529 7545 7331 -f 7529 7331 7546 -f 7546 7331 7330 -f 7546 7330 7547 -f 7546 7547 7530 -f 7530 7547 7548 -f 7530 7548 7549 -f 7549 7548 7362 -f 7549 7362 7355 -f 7549 7355 7550 -f 7550 7355 7383 -f 7550 7383 7382 -f 7550 7382 7551 -f 7551 7382 7552 -f 7552 7382 7379 -f 7552 7379 7553 -f 7553 7379 7554 -f 7553 7554 7555 -f 7555 7554 7556 -f 7555 7556 7557 -f 7557 7556 7558 -f 7557 7558 7559 -f 7557 7559 7560 -f 7560 7559 7326 -f 7560 7326 7561 -f 7560 7561 7562 -f 7562 7561 7531 -f 7565 7314 7566 -f 7569 7563 7575 -f 7010 4350 4339 -f 7302 7301 7571 -f 7571 7301 7570 -f 7304 7571 7570 -f 7010 4351 4350 -f 7304 7570 7573 -f 7306 7573 7313 -f 7306 7304 7573 -f 7306 7313 7572 -f 7572 7313 7574 -f 7572 7574 7310 -f 7575 7564 7569 -f 7564 7316 7568 -f 7568 7569 7564 -f 7568 7316 7567 -f 7316 7565 7567 -f 7565 7566 7567 -f 7579 7580 7581 -f 7581 4686 4685 -f 7576 7577 7583 -f 7577 7582 7583 -f 7577 7578 7582 -f 7578 4683 7582 -f 4683 7578 4685 -f 7578 7579 4685 -f 7579 7581 4685 -f 4677 7584 4678 -f 7584 4658 4678 -f 7584 7586 4658 -f 4674 7588 7587 -f 4658 7586 7585 -f 7585 7586 4660 -f 7586 4674 4660 -f 4660 4674 7587 -f 7587 7588 4665 -f 7588 4671 4665 -f 4671 4667 4665 -f 8811 7593 7601 -f 7601 7593 9432 -f 7589 9441 7590 -f 7590 9441 8978 -f 8981 7591 7597 -f 7597 7591 7592 -f 7597 7592 9441 -f 9441 7592 8980 -f 9441 8980 8978 -f 7593 8811 7595 -f 7595 8811 7594 -f 7595 7594 8983 -f 8983 8982 7595 -f 7595 8982 7596 -f 7595 7596 7597 -f 7597 7596 7598 -f 7597 7598 8981 -f 7599 8757 9431 -f 7599 9431 7600 -f 7601 9432 8758 -f 8758 9432 9431 -f 8758 9431 7602 -f 7602 9431 8757 -f 8717 7603 7604 -f 7604 7603 8754 -f 7604 8754 9431 -f 9431 8754 8755 -f 9431 8755 7600 -f 7606 8715 7607 -f 7607 8715 8716 -f 7607 8716 7604 -f 7604 8716 7605 -f 7604 7605 8717 -f 7606 7607 7608 -f 7606 7608 8706 -f 8703 8704 9433 -f 9433 8704 7609 -f 9433 7609 7608 -f 7608 7609 8705 -f 7608 8705 8706 -f 7614 8425 9433 -f 9433 8425 7610 -f 7610 8423 9433 -f 9433 8423 8418 -f 9433 8418 8703 -f 8119 8115 7611 -f 7611 8115 8428 -f 8428 8427 7611 -f 7611 8427 7612 -f 7611 7612 7614 -f 7614 7612 7613 -f 7614 7613 8425 -f 9054 9220 9249 -f 7615 9054 9441 -f 9254 9255 9298 -f 9251 9254 9441 -f 7589 9052 9441 -f 9441 9052 7616 -f 9441 7616 7615 -f 9054 9249 9441 -f 9441 9249 9250 -f 9441 9250 9251 -f 9300 7617 9441 -f 9441 7617 7618 -f 9441 7618 7620 -f 7622 9307 9441 -f 9441 9307 9308 -f 9441 9308 7619 -f 7619 9310 9441 -f 9441 9310 8085 -f 9441 8085 9446 -f 9254 9298 9441 -f 9441 9298 9299 -f 9441 9299 9300 -f 7620 9303 9441 -f 9441 9303 7621 -f 9441 7621 7622 -f 8912 8911 7644 -f 7632 9407 7693 -f 9030 7623 7723 -f 7723 7623 7774 -f 7723 7774 7776 -f 9179 7625 7624 -f 7624 7625 7626 -f 7624 7626 7740 -f 7740 7626 9029 -f 7627 9224 7682 -f 7682 9224 7707 -f 9238 7628 7629 -f 7629 7628 7694 -f 7629 7694 9372 -f 7691 7632 7693 -f 9336 9400 7630 -f 7630 9400 7631 -f 7630 7631 7691 -f 7691 7631 7632 -f 9336 7630 9337 -f 9337 7630 7633 -f 9337 7633 9338 -f 9338 7633 9339 -f 9339 7633 7634 -f 9339 7634 9341 -f 9341 7634 9343 -f 9343 7634 7688 -f 9343 7688 7635 -f 7635 7688 7637 -f 7635 7637 7636 -f 7636 7637 9355 -f 9355 7637 7638 -f 9355 7638 9358 -f 9358 7638 7685 -f 9358 7685 9356 -f 9208 9356 7639 -f 7639 9356 7685 -f 7639 7685 7640 -f 7640 7685 7684 -f 7640 7684 9150 -f 9150 7684 9149 -f 7645 7642 7641 -f 7641 7642 7643 -f 7641 7643 9149 -f 8911 8910 7644 -f 7644 8910 7645 -f 7644 7645 7646 -f 7725 8912 7696 -f 8779 8898 7725 -f 7725 8898 8912 -f 7724 7647 8779 -f 8583 8585 7724 -f 7724 8585 7647 -f 7713 7649 7648 -f 7648 7649 8583 -f 7723 7776 7651 -f 7723 7651 7650 -f 7651 7652 7650 -f 7650 7652 7653 -f 7650 7653 7654 -f 7653 7777 7654 -f 7654 7777 7655 -f 7654 7655 7656 -f 7655 7657 7656 -f 7656 7657 7781 -f 7656 7781 7658 -f 7781 7659 7658 -f 7658 7659 7780 -f 7658 7780 7661 -f 7780 7660 7661 -f 7661 7660 7662 -f 7661 7662 7664 -f 7662 7663 7664 -f 7664 7663 7787 -f 7664 7787 7666 -f 7787 7786 7666 -f 7666 7786 7665 -f 7666 7665 7667 -f 7665 7668 7667 -f 7667 7668 7669 -f 7667 7669 7670 -f 7669 7791 7670 -f 7670 7791 7790 -f 7670 7790 7717 -f 7790 7789 7717 -f 7717 7789 7671 -f 7717 7671 7673 -f 7671 7672 7673 -f 7673 7672 7795 -f 7673 7795 7715 -f 7645 7641 7646 -f 7646 7641 7683 -f 7646 7683 7697 -f 7697 7683 7686 -f 7697 7686 7699 -f 7699 7686 7675 -f 7699 7675 7674 -f 7674 7675 7687 -f 7674 7687 7701 -f 7701 7687 7689 -f 7701 7689 7676 -f 7676 7689 7677 -f 7676 7677 7704 -f 7704 7677 7690 -f 7704 7690 7705 -f 7705 7690 7678 -f 7705 7678 7679 -f 7679 7678 7692 -f 7679 7692 7680 -f 7680 7692 7694 -f 7680 7694 7681 -f 7681 7694 7628 -f 7681 7628 7682 -f 7682 7628 9238 -f 7682 9238 7627 -f 7641 9149 7684 -f 7641 7684 7683 -f 7683 7684 7685 -f 7683 7685 7686 -f 7686 7685 7638 -f 7686 7638 7675 -f 7675 7638 7637 -f 7675 7637 7687 -f 7687 7637 7688 -f 7687 7688 7689 -f 7689 7688 7634 -f 7689 7634 7677 -f 7677 7634 7633 -f 7677 7633 7690 -f 7690 7633 7630 -f 7690 7630 7678 -f 7678 7630 7691 -f 7678 7691 7692 -f 7692 7691 7693 -f 7692 7693 7694 -f 7694 7693 9407 -f 7694 9407 9372 -f 7795 7695 7715 -f 7715 7695 7793 -f 7715 7793 7709 -f 8912 7644 7696 -f 7696 7644 7646 -f 7696 7646 7727 -f 7727 7646 7697 -f 7727 7697 7698 -f 7698 7697 7699 -f 7698 7699 7729 -f 7729 7699 7674 -f 7729 7674 7700 -f 7700 7674 7701 -f 7700 7701 7702 -f 7702 7701 7676 -f 7702 7676 7703 -f 7703 7676 7704 -f 7703 7704 7730 -f 7730 7704 7705 -f 7730 7705 7733 -f 7733 7705 7679 -f 7733 7679 7734 -f 7734 7679 7680 -f 7734 7680 7736 -f 7736 7680 7681 -f 7736 7681 7738 -f 7738 7681 7682 -f 7738 7682 7706 -f 7706 7682 7707 -f 7706 7707 7708 -f 7708 7707 9222 -f 7708 9222 7739 -f 7793 7710 7709 -f 7709 7710 7711 -f 7709 7711 7648 -f 7648 7711 7712 -f 7648 7712 7713 -f 8583 7724 7648 -f 7648 7724 7726 -f 7648 7726 7709 -f 7709 7726 7714 -f 7709 7714 7715 -f 7715 7714 7716 -f 7715 7716 7673 -f 7673 7716 7728 -f 7673 7728 7717 -f 7717 7728 7718 -f 7717 7718 7670 -f 7670 7718 7719 -f 7670 7719 7667 -f 7667 7719 7731 -f 7667 7731 7666 -f 7666 7731 7732 -f 7666 7732 7664 -f 7664 7732 7720 -f 7664 7720 7661 -f 7661 7720 7735 -f 7661 7735 7658 -f 7658 7735 7737 -f 7658 7737 7656 -f 7656 7737 7721 -f 7656 7721 7654 -f 7654 7721 7722 -f 7654 7722 7650 -f 7650 7722 7740 -f 7650 7740 7723 -f 7723 7740 9029 -f 7723 9029 9030 -f 8779 7725 7724 -f 7724 7725 7696 -f 7724 7696 7726 -f 7726 7696 7727 -f 7726 7727 7714 -f 7714 7727 7698 -f 7714 7698 7716 -f 7716 7698 7729 -f 7716 7729 7728 -f 7728 7729 7700 -f 7728 7700 7718 -f 7718 7700 7702 -f 7718 7702 7719 -f 7719 7702 7703 -f 7719 7703 7731 -f 7731 7703 7730 -f 7731 7730 7732 -f 7732 7730 7733 -f 7732 7733 7720 -f 7720 7733 7734 -f 7720 7734 7735 -f 7735 7734 7736 -f 7735 7736 7737 -f 7737 7736 7738 -f 7737 7738 7721 -f 7721 7738 7706 -f 7721 7706 7722 -f 7722 7706 7708 -f 7722 7708 7740 -f 7740 7708 7739 -f 7740 7739 7624 -f 8940 7741 7742 -f 8485 7745 7746 -f 8487 8489 7743 -f 7823 8507 7713 -f 8489 7744 7823 -f 7823 7744 8505 -f 7823 8505 8507 -f 8487 7743 7747 -f 7746 7745 7747 -f 7746 7747 7842 -f 8482 8486 7841 -f 7841 8486 8485 -f 8482 7824 7748 -f 8479 7748 8685 -f 8685 7748 7824 -f 8685 7824 7750 -f 7750 7824 7749 -f 7752 8652 7749 -f 7749 8652 7750 -f 7829 8636 7751 -f 7751 8636 7753 -f 7751 7753 7752 -f 7752 7753 7754 -f 7752 7754 8652 -f 7830 8631 7829 -f 7829 8631 8636 -f 7758 8632 7830 -f 7830 8632 7755 -f 7830 7755 8631 -f 7831 7756 7758 -f 7758 7756 7757 -f 7758 7757 8632 -f 7833 8618 7759 -f 7759 8618 7760 -f 7759 7760 7831 -f 7831 7760 8621 -f 7831 8621 7756 -f 7761 8619 7833 -f 7833 8619 8618 -f 7761 7833 7762 -f 7762 7833 7763 -f 7762 7763 8613 -f 8613 7763 7765 -f 8613 7765 8614 -f 8614 7765 7764 -f 7764 7765 7766 -f 7764 7766 8609 -f 8609 7766 8607 -f 8607 7766 7767 -f 8607 7767 8606 -f 8606 7767 8605 -f 8605 7767 7768 -f 8605 7768 7769 -f 7769 7768 7770 -f 7769 7770 8604 -f 7840 7771 7770 -f 7770 7771 8604 -f 8795 7771 8933 -f 8933 7771 8935 -f 8935 7771 7840 -f 7772 8938 7839 -f 7772 7839 8939 -f 7775 8945 7773 -f 7776 7774 7775 -f 7775 7774 8945 -f 7779 7651 7775 -f 7775 7651 7776 -f 7778 7782 7655 -f 7655 7777 7778 -f 7778 7777 7653 -f 7778 7653 7779 -f 7779 7653 7652 -f 7779 7652 7651 -f 7820 7783 7780 -f 7780 7659 7820 -f 7820 7659 7781 -f 7820 7781 7782 -f 7782 7781 7657 -f 7782 7657 7655 -f 7818 7785 7787 -f 7787 7663 7818 -f 7818 7663 7662 -f 7818 7662 7783 -f 7783 7662 7660 -f 7783 7660 7780 -f 7784 7792 7669 -f 7669 7668 7784 -f 7784 7668 7665 -f 7784 7665 7785 -f 7785 7665 7786 -f 7785 7786 7787 -f 7788 7796 7671 -f 7671 7789 7788 -f 7788 7789 7790 -f 7788 7790 7792 -f 7792 7790 7791 -f 7792 7791 7669 -f 7794 7813 7793 -f 7793 7695 7794 -f 7794 7695 7795 -f 7794 7795 7796 -f 7796 7795 7672 -f 7796 7672 7671 -f 7747 7743 7842 -f 7842 7743 7797 -f 7842 7797 7799 -f 7799 7797 7798 -f 7799 7798 7800 -f 7800 7798 7814 -f 7800 7814 7844 -f 7844 7814 7815 -f 7844 7815 7801 -f 7801 7815 7802 -f 7801 7802 7803 -f 7803 7802 7816 -f 7803 7816 7804 -f 7804 7816 7817 -f 7804 7817 7847 -f 7847 7817 7805 -f 7847 7805 7806 -f 7806 7805 7819 -f 7806 7819 7848 -f 7848 7819 7807 -f 7848 7807 7808 -f 7808 7807 7821 -f 7808 7821 7849 -f 7849 7821 7809 -f 7849 7809 7810 -f 7810 7809 7811 -f 7810 7811 7812 -f 7812 7811 7822 -f 7812 7822 7742 -f 7742 7822 8943 -f 7742 8943 8940 -f 8489 7823 7743 -f 7743 7823 7813 -f 7743 7813 7797 -f 7797 7813 7794 -f 7797 7794 7798 -f 7798 7794 7796 -f 7798 7796 7814 -f 7814 7796 7788 -f 7814 7788 7815 -f 7815 7788 7792 -f 7815 7792 7802 -f 7802 7792 7784 -f 7802 7784 7816 -f 7816 7784 7785 -f 7816 7785 7817 -f 7817 7785 7818 -f 7817 7818 7805 -f 7805 7818 7783 -f 7805 7783 7819 -f 7819 7783 7820 -f 7819 7820 7807 -f 7807 7820 7782 -f 7807 7782 7821 -f 7821 7782 7778 -f 7821 7778 7809 -f 7809 7778 7779 -f 7809 7779 7811 -f 7811 7779 7775 -f 7811 7775 7822 -f 7822 7775 7773 -f 7822 7773 8943 -f 7713 7712 7823 -f 7823 7712 7711 -f 7823 7711 7813 -f 7813 7711 7710 -f 7813 7710 7793 -f 8482 7841 7824 -f 7824 7841 7825 -f 7824 7825 7749 -f 7749 7825 7826 -f 7749 7826 7752 -f 7752 7826 7843 -f 7752 7843 7751 -f 7751 7843 7827 -f 7751 7827 7829 -f 7829 7827 7828 -f 7829 7828 7830 -f 7830 7828 7845 -f 7830 7845 7758 -f 7758 7845 7846 -f 7758 7846 7831 -f 7831 7846 7832 -f 7831 7832 7759 -f 7759 7832 7834 -f 7759 7834 7833 -f 7833 7834 7835 -f 7833 7835 7763 -f 7763 7835 7836 -f 7763 7836 7765 -f 7765 7836 7850 -f 7765 7850 7766 -f 7766 7850 7837 -f 7766 7837 7767 -f 7767 7837 7838 -f 7767 7838 7768 -f 7768 7838 7839 -f 7768 7839 7770 -f 7770 7839 8938 -f 7770 8938 7840 -f 7840 8938 8937 -f 7840 8937 8935 -f 8485 7746 7841 -f 7841 7746 7842 -f 7841 7842 7825 -f 7825 7842 7799 -f 7825 7799 7826 -f 7826 7799 7800 -f 7826 7800 7843 -f 7843 7800 7844 -f 7843 7844 7827 -f 7827 7844 7801 -f 7827 7801 7828 -f 7828 7801 7803 -f 7828 7803 7845 -f 7845 7803 7804 -f 7845 7804 7846 -f 7846 7804 7847 -f 7846 7847 7832 -f 7832 7847 7806 -f 7832 7806 7834 -f 7834 7806 7848 -f 7834 7848 7835 -f 7835 7848 7808 -f 7835 7808 7836 -f 7836 7808 7849 -f 7836 7849 7850 -f 7850 7849 7810 -f 7850 7810 7837 -f 7837 7810 7812 -f 7837 7812 7838 -f 7838 7812 7742 -f 7838 7742 7839 -f 7839 7742 7741 -f 7839 7741 8939 -f 7887 7886 7944 -f 7853 7859 8386 -f 8358 8361 7909 -f 7909 8361 7854 -f 7909 7854 7908 -f 7908 7854 8360 -f 7908 8360 7855 -f 7904 8364 8358 -f 8364 7856 8371 -f 8371 7856 8369 -f 8369 7856 7993 -f 8369 7993 8368 -f 8368 7993 7956 -f 8368 7956 8373 -f 8373 7955 7857 -f 7857 7955 7958 -f 7857 7958 8379 -f 8379 7958 7858 -f 7858 7958 7960 -f 7858 7960 7930 -f 7930 7960 7931 -f 8386 7859 7860 -f 8386 7860 8387 -f 8387 7860 7932 -f 8387 7932 7861 -f 8389 7913 7862 -f 7862 7913 7915 -f 7862 7915 8432 -f 7864 8433 7915 -f 7915 8433 8432 -f 7863 8426 7864 -f 7864 8426 8433 -f 7917 8421 7863 -f 7863 8421 8426 -f 7865 8420 7866 -f 7866 8420 7917 -f 7917 8420 8421 -f 7918 7919 8603 -f 7865 7866 8699 -f 8699 7866 7918 -f 8699 7918 8689 -f 8689 7918 8603 -f 8689 8603 8688 -f 7919 7867 8603 -f 7852 7920 7868 -f 7868 7920 7869 -f 7943 7870 8610 -f 8610 7870 7975 -f 7871 8623 8010 -f 8010 8623 7872 -f 7990 8628 7991 -f 8628 7990 7873 -f 8628 7873 8633 -f 7954 7929 7874 -f 7874 7929 7875 -f 7874 7875 7876 -f 7878 8400 8402 -f 8402 8600 7878 -f 7878 8600 7877 -f 7877 8600 8653 -f 7877 8653 8639 -f 8400 7878 8408 -f 8408 7878 7927 -f 8408 7927 7879 -f 7879 7927 7926 -f 7879 7926 8255 -f 8255 7926 7923 -f 8255 7923 8254 -f 8254 7923 7922 -f 8254 7922 8270 -f 7882 7851 7922 -f 7922 7851 8270 -f 7921 7881 7880 -f 7880 7881 7882 -f 7882 7881 7851 -f 7883 7884 7885 -f 7885 7884 7921 -f 7886 7887 7889 -f 7887 7888 7889 -f 7889 7888 7890 -f 7889 7890 7883 -f 7883 7890 8253 -f 7883 8253 7884 -f 7892 7893 7945 -f 7945 7893 7944 -f 7977 7896 8231 -f 8231 7891 7977 -f 7977 7891 8236 -f 7977 8236 7892 -f 7892 8236 8235 -f 7892 8235 7893 -f 7899 8232 7894 -f 7894 8232 7896 -f 7896 8232 7895 -f 7896 7895 8231 -f 7902 7898 7897 -f 7897 7898 7899 -f 8223 8225 7900 -f 7900 8225 7901 -f 7900 7901 7902 -f 7902 7901 8226 -f 7902 8226 7898 -f 8223 7903 7904 -f 8223 7904 7906 -f 8358 7909 7904 -f 7904 7909 7905 -f 7904 7905 7906 -f 7855 7907 7908 -f 7907 8126 7908 -f 7908 8126 7910 -f 7908 7910 7909 -f 7909 7910 7911 -f 7909 7911 7905 -f 7861 7932 8389 -f 8389 7932 7912 -f 8389 7912 7913 -f 7913 7912 7914 -f 7913 7914 7915 -f 7915 7914 7916 -f 7915 7916 7864 -f 7864 7916 7935 -f 7864 7935 7863 -f 7863 7935 7937 -f 7863 7937 7917 -f 7917 7937 7939 -f 7917 7939 7866 -f 7866 7939 7941 -f 7866 7941 7918 -f 7918 7941 7869 -f 7918 7869 7919 -f 7919 7869 7920 -f 7919 7920 7867 -f 7921 7880 7885 -f 7885 7880 7882 -f 7885 7882 7947 -f 7947 7882 7922 -f 7947 7922 7949 -f 7949 7922 7923 -f 7949 7923 7924 -f 7924 7923 7926 -f 7924 7926 7925 -f 7925 7926 7927 -f 7925 7927 7928 -f 7928 7927 7878 -f 7928 7878 7953 -f 7953 7878 7877 -f 7953 7877 7954 -f 7954 7877 8639 -f 7954 8639 7929 -f 7930 7931 7853 -f 7853 7931 7962 -f 7853 7962 7859 -f 7859 7962 7963 -f 7859 7963 7860 -f 7860 7963 7933 -f 7860 7933 7932 -f 7932 7933 7966 -f 7932 7966 7912 -f 7912 7966 7934 -f 7912 7934 7914 -f 7914 7934 7969 -f 7914 7969 7916 -f 7916 7969 7936 -f 7916 7936 7935 -f 7935 7936 7938 -f 7935 7938 7937 -f 7937 7938 7973 -f 7937 7973 7939 -f 7939 7973 7940 -f 7939 7940 7941 -f 7941 7940 7942 -f 7941 7942 7869 -f 7869 7942 7870 -f 7869 7870 7868 -f 7868 7870 7943 -f 7868 7943 7852 -f 7944 7886 7945 -f 7945 7886 7889 -f 7945 7889 7981 -f 7981 7889 7883 -f 7981 7883 7983 -f 7983 7883 7885 -f 7983 7885 7946 -f 7946 7885 7947 -f 7946 7947 7948 -f 7948 7947 7949 -f 7948 7949 7950 -f 7950 7949 7924 -f 7950 7924 7985 -f 7985 7924 7925 -f 7985 7925 7951 -f 7951 7925 7928 -f 7951 7928 7987 -f 7987 7928 7953 -f 7987 7953 7952 -f 7952 7953 7954 -f 7952 7954 7989 -f 7989 7954 7874 -f 7989 7874 7873 -f 7873 7874 7876 -f 7873 7876 8633 -f 8373 7956 7955 -f 7955 7956 7957 -f 7955 7957 7958 -f 7958 7957 7997 -f 7958 7997 7960 -f 7960 7997 7959 -f 7960 7959 7931 -f 7931 7959 7961 -f 7931 7961 7962 -f 7962 7961 7964 -f 7962 7964 7963 -f 7963 7964 8000 -f 7963 8000 7933 -f 7933 8000 7965 -f 7933 7965 7966 -f 7966 7965 7967 -f 7966 7967 7934 -f 7934 7967 7968 -f 7934 7968 7969 -f 7969 7968 7970 -f 7969 7970 7936 -f 7936 7970 7971 -f 7936 7971 7938 -f 7938 7971 7972 -f 7938 7972 7973 -f 7973 7972 8006 -f 7973 8006 7940 -f 7940 8006 7974 -f 7940 7974 7942 -f 7942 7974 8009 -f 7942 8009 7870 -f 7870 8009 8010 -f 7870 8010 7975 -f 7975 8010 7872 -f 7975 7872 8610 -f 7899 7894 7897 -f 7897 7894 7896 -f 7897 7896 7976 -f 7976 7896 7977 -f 7976 7977 7978 -f 7978 7977 7892 -f 7978 7892 8011 -f 8011 7892 7945 -f 8011 7945 7979 -f 7979 7945 7981 -f 7979 7981 7980 -f 7980 7981 7983 -f 7980 7983 7982 -f 7982 7983 7946 -f 7982 7946 7984 -f 7984 7946 7948 -f 7984 7948 8015 -f 8015 7948 7950 -f 8015 7950 8016 -f 8016 7950 7985 -f 8016 7985 8017 -f 8017 7985 7951 -f 8017 7951 7986 -f 7986 7951 7987 -f 7986 7987 7988 -f 7988 7987 7952 -f 7988 7952 8019 -f 8019 7952 7989 -f 8019 7989 8020 -f 8020 7989 7873 -f 8020 7873 8021 -f 8021 7873 7990 -f 8021 7990 8022 -f 8022 7990 7991 -f 8022 7991 8627 -f 8364 7904 7903 -f 8364 7903 7856 -f 7856 7903 7992 -f 7856 7992 7993 -f 7993 7992 7994 -f 7993 7994 7956 -f 7956 7994 7995 -f 7956 7995 7957 -f 7957 7995 7996 -f 7957 7996 7997 -f 7997 7996 8012 -f 7997 8012 7959 -f 7959 8012 7998 -f 7959 7998 7961 -f 7961 7998 8013 -f 7961 8013 7964 -f 7964 8013 7999 -f 7964 7999 8000 -f 8000 7999 8014 -f 8000 8014 7965 -f 7965 8014 8001 -f 7965 8001 7967 -f 7967 8001 8002 -f 7967 8002 7968 -f 7968 8002 8003 -f 7968 8003 7970 -f 7970 8003 8018 -f 7970 8018 7971 -f 7971 8018 8004 -f 7971 8004 7972 -f 7972 8004 8005 -f 7972 8005 8006 -f 8006 8005 8007 -f 8006 8007 7974 -f 7974 8007 8008 -f 7974 8008 8009 -f 8009 8008 8023 -f 8009 8023 8010 -f 8010 8023 8624 -f 8010 8624 7871 -f 8223 7900 7903 -f 7903 7900 7902 -f 7903 7902 7992 -f 7992 7902 7897 -f 7992 7897 7994 -f 7994 7897 7976 -f 7994 7976 7995 -f 7995 7976 7978 -f 7995 7978 7996 -f 7996 7978 8011 -f 7996 8011 8012 -f 8012 8011 7979 -f 8012 7979 7998 -f 7998 7979 7980 -f 7998 7980 8013 -f 8013 7980 7982 -f 8013 7982 7999 -f 7999 7982 7984 -f 7999 7984 8014 -f 8014 7984 8015 -f 8014 8015 8001 -f 8001 8015 8016 -f 8001 8016 8002 -f 8002 8016 8017 -f 8002 8017 8003 -f 8003 8017 7986 -f 8003 7986 8018 -f 8018 7986 7988 -f 8018 7988 8004 -f 8004 7988 8019 -f 8004 8019 8005 -f 8005 8019 8020 -f 8005 8020 8007 -f 8007 8020 8021 -f 8007 8021 8008 -f 8008 8021 8022 -f 8008 8022 8023 -f 8023 8022 8627 -f 8023 8627 8624 -f 8039 9440 8396 -f 8396 9440 9443 -f 8455 8025 8024 -f 8396 9443 8452 -f 8452 9443 8024 -f 8452 8024 8453 -f 8453 8024 8025 -f 8026 8460 8459 -f 8459 8458 8026 -f 8026 8458 8457 -f 8026 8457 8024 -f 8024 8457 8456 -f 8024 8456 8455 -f 8468 8027 8048 -f 8048 8027 8469 -f 8048 8469 8026 -f 8026 8469 8028 -f 8026 8028 8460 -f 8287 8135 8286 -f 8286 8135 8029 -f 8286 8029 8285 -f 8285 8029 8283 -f 8283 8029 8030 -f 8030 8029 8031 -f 8030 8031 8269 -f 8269 8031 8032 -f 8032 8031 8037 -f 8032 8037 8263 -f 8263 8037 8262 -f 8262 8037 8292 -f 8262 8292 8261 -f 8033 9438 8034 -f 8034 9438 9437 -f 8034 9437 8305 -f 8033 8035 9438 -f 9438 8035 8036 -f 9438 8036 8037 -f 8037 8036 8293 -f 8037 8293 8292 -f 9436 8038 9435 -f 9435 8038 8310 -f 9435 8310 8309 -f 8309 8308 9435 -f 9435 8308 8307 -f 9435 8307 9437 -f 9437 8307 8306 -f 9437 8306 8305 -f 9436 9440 8039 -f 8039 8040 9436 -f 9436 8040 8041 -f 9436 8041 8313 -f 8313 8312 9436 -f 9436 8312 8311 -f 9436 8311 8038 -f 8835 8042 8048 -f 8048 8042 8043 -f 8045 8566 8048 -f 8048 8566 8568 -f 8048 8890 8049 -f 8043 8915 8048 -f 8048 8915 8044 -f 8048 8044 8045 -f 8568 8569 8048 -f 8048 8569 8046 -f 8048 8046 8468 -f 9447 8047 8048 -f 8048 8047 8889 -f 8048 8889 8890 -f 8854 8855 8048 -f 8048 8855 8851 -f 8851 8845 8048 -f 8048 8845 8834 -f 8048 8834 8835 -f 8049 8881 8048 -f 8048 8881 8872 -f 8048 8872 8873 -f 8873 8857 8048 -f 8048 8857 8050 -f 8048 8050 8854 -f 8051 9074 9077 -f 8051 8052 8069 -f 9077 9080 8051 -f 8051 9080 8052 -f 9074 8051 8070 -f 9074 8070 8053 -f 9197 8054 8055 -f 8055 8054 9073 -f 8055 9073 8075 -f 8075 9073 9071 -f 9311 9197 8055 -f 9311 8055 9315 -f 9315 8055 8056 -f 8057 9320 8058 -f 8057 8058 8056 -f 8056 8058 8059 -f 8056 8059 9315 -f 9324 9320 8060 -f 9324 8060 9332 -f 9413 9392 8061 -f 8061 9392 8062 -f 8063 8064 8061 -f 8061 8064 9414 -f 8061 9414 9413 -f 8063 9259 8064 -f 8064 9259 9258 -f 8064 9258 9424 -f 9424 9258 9256 -f 9424 9256 9369 -f 9261 9260 8063 -f 8063 9260 9259 -f 8074 9263 8060 -f 9263 8065 8060 -f 8060 8065 8066 -f 8060 8066 8073 -f 8073 8066 9261 -f 9266 9265 8068 -f 8068 9265 8074 -f 8074 9265 8067 -f 8074 8067 9263 -f 9266 8068 8072 -f 8072 8068 8070 -f 8069 9269 8051 -f 8051 9269 8070 -f 8070 9269 8071 -f 8070 8071 8072 -f 8073 9261 8063 -f 8073 8063 8060 -f 8060 8063 8061 -f 8060 8061 9332 -f 9332 8061 8062 -f 9320 8057 8060 -f 8060 8057 8056 -f 8060 8056 8074 -f 8074 8056 8055 -f 8074 8055 8068 -f 8068 8055 8075 -f 8068 8075 8070 -f 8070 8075 9071 -f 8070 9071 8053 -f 8078 8076 8108 -f 9192 8076 8078 -f 8080 9192 8077 -f 8077 9192 8078 -f 8079 9188 8077 -f 8077 9188 8080 -f 9442 8081 9434 -f 9434 8081 9191 -f 9434 9191 8077 -f 8077 9191 8079 -f 8082 9185 8083 -f 8082 8083 9442 -f 9442 8083 8081 -f 9185 8082 8084 -f 8084 8082 9446 -f 8084 9446 8085 -f 9085 8086 9448 -f 8087 8829 8830 -f 8774 9439 8832 -f 8832 9439 8087 -f 8832 8087 8088 -f 8088 8087 8830 -f 8090 8818 8092 -f 8092 8818 8089 -f 8092 8089 8087 -f 8087 8089 8827 -f 8087 8827 8829 -f 9448 8086 8092 -f 8997 8090 9084 -f 9084 8090 8092 -f 9084 8092 8091 -f 8091 8092 8086 -f 8097 8093 9448 -f 9448 8093 8094 -f 9448 8094 9085 -f 9093 8095 9464 -f 9464 8095 8096 -f 9464 8096 9448 -f 9448 8096 9087 -f 9448 9087 8097 -f 8098 9095 9444 -f 9444 9095 9464 -f 9464 9095 9094 -f 9464 9094 9093 -f 9100 9099 8099 -f 9099 9098 8099 -f 8099 9098 9097 -f 8099 9097 9444 -f 9444 9097 8098 -f 8100 9067 8105 -f 8105 9067 8101 -f 8105 8101 9107 -f 9107 9106 8105 -f 8105 9106 8102 -f 8105 8102 8099 -f 8099 8102 9100 -f 8103 8104 8105 -f 8105 8104 9069 -f 8105 9069 8100 -f 9076 8106 8103 -f 8103 8106 8107 -f 8103 8107 8104 -f 8078 8108 8103 -f 8103 8108 9075 -f 8103 9075 9076 -f 9449 8109 8110 -f 8110 8109 8765 -f 8765 8763 8110 -f 8110 8763 8111 -f 8110 8111 9447 -f 9447 8111 8112 -f 9447 8112 8047 -f 8770 8769 9445 -f 9445 8769 9449 -f 9449 8769 8767 -f 9449 8767 8109 -f 8772 8771 9445 -f 9445 8771 8770 -f 8774 8150 9439 -f 8150 8773 9439 -f 9439 8773 8114 -f 8773 8113 8114 -f 8114 8113 9445 -f 9445 8113 8772 -f 8395 8115 8119 -f 8116 8118 8382 -f 8382 8118 8122 -f 8382 8122 8380 -f 8116 8117 8118 -f 8118 8117 8391 -f 8118 8391 8119 -f 8119 8391 8120 -f 8119 8120 8395 -f 8366 9430 8121 -f 8121 9430 9429 -f 8121 9429 8363 -f 8366 8374 9430 -f 9430 8374 8376 -f 9430 8376 8122 -f 8122 8376 8123 -f 8122 8123 8380 -f 8125 8126 7907 -f 7907 7855 9428 -f 9428 7855 8124 -f 9428 8124 9429 -f 9429 8124 8362 -f 9429 8362 8363 -f 8125 7907 9428 -f 8221 8245 8127 -f 8127 8245 8220 -f 8127 8220 8125 -f 8125 8220 8219 -f 8125 8219 8126 -f 8221 8127 8128 -f 8128 8127 8132 -f 8128 8132 8129 -f 8237 8130 8131 -f 8131 8130 8133 -f 8131 8133 8132 -f 8132 8133 8129 -f 8237 8131 8238 -f 8238 8131 8134 -f 8238 8134 8239 -f 8287 8242 8135 -f 8135 8242 8136 -f 8135 8136 8134 -f 8134 8136 8239 -f 8149 8816 8148 -f 8154 8159 9132 -f 8137 8891 8761 -f 8137 8761 8778 -f 8891 8137 8138 -f 8138 8137 8139 -f 8138 8139 8882 -f 8157 8874 8140 -f 8157 8140 8139 -f 8139 8140 8882 -f 8142 8143 8869 -f 8142 8869 8157 -f 8157 8869 8874 -f 8153 8141 8160 -f 8160 8141 8862 -f 8160 8862 8142 -f 8142 8862 8143 -f 8145 8841 8146 -f 8144 8852 8153 -f 8153 8852 8141 -f 9151 8839 8145 -f 9151 8145 9160 -f 9145 9147 8152 -f 9160 8145 8146 -f 9160 8146 9159 -f 9159 8146 8152 -f 9159 8152 9157 -f 9157 8152 9147 -f 9157 9147 8147 -f 9132 8159 9129 -f 9129 8159 8158 -f 9129 8158 9127 -f 8148 8816 9126 -f 8148 9126 8158 -f 8158 9126 9127 -f 8156 8155 8819 -f 8156 8819 8148 -f 8148 8819 8820 -f 8148 8820 8149 -f 8150 8825 8778 -f 8778 8825 8137 -f 8825 8824 8137 -f 8137 8824 8151 -f 8137 8151 8139 -f 8139 8151 8822 -f 8139 8822 8155 -f 8841 8144 8146 -f 8146 8144 8153 -f 8146 8153 8152 -f 8152 8153 8160 -f 8152 8160 9145 -f 9145 8160 8154 -f 8155 8156 8139 -f 8139 8156 8148 -f 8139 8148 8157 -f 8157 8148 8158 -f 8157 8158 8142 -f 8142 8158 8159 -f 8142 8159 8160 -f 8160 8159 8154 -f 8184 8161 8162 -f 9139 9140 8174 -f 9121 9195 8182 -f 8164 9105 8165 -f 8164 8165 9121 -f 8163 9102 8166 -f 8166 9103 8163 -f 8163 9103 8167 -f 8171 9089 8163 -f 9089 8168 8163 -f 8163 8168 9091 -f 8163 9091 9102 -f 8169 9122 8170 -f 8170 9122 9081 -f 9081 9082 8170 -f 8170 9082 8171 -f 8169 8170 8172 -f 8172 8170 8173 -f 8172 8173 9130 -f 9140 9141 8174 -f 8174 9141 9143 -f 8174 9143 8173 -f 8173 9143 9130 -f 9205 9139 8175 -f 8175 9139 8174 -f 8175 8174 9366 -f 9366 8174 8176 -f 8177 9406 9344 -f 9345 8179 9344 -f 9344 8179 8181 -f 9344 8181 8177 -f 8178 9322 9328 -f 8178 9328 8179 -f 8179 9328 8180 -f 8179 8180 8181 -f 9121 8182 8164 -f 8164 8182 9314 -f 8164 9314 8178 -f 8178 9314 9317 -f 8178 9317 9322 -f 8170 8171 8163 -f 8170 8163 8173 -f 8173 8163 8183 -f 8173 8183 8174 -f 8174 8183 8162 -f 8174 8162 8176 -f 8176 8162 8161 -f 8167 9105 8163 -f 8163 9105 8164 -f 8163 8164 8183 -f 8183 8164 8178 -f 8183 8178 8162 -f 8162 8178 8179 -f 8162 8179 8184 -f 8184 8179 9345 -f 8190 8185 8189 -f 8189 8185 8974 -f 8189 8974 8975 -f 8975 8976 8189 -f 8189 8976 8186 -f 8189 8186 8187 -f 8187 8188 8189 -f 8189 8188 9023 -f 8189 9023 9041 -f 9041 9023 9022 -f 9041 9022 9018 -f 9043 8971 8189 -f 8189 8971 8972 -f 8189 8972 8190 -f 8971 8702 8191 -f 8191 8702 8701 -f 9043 8192 8971 -f 8971 8192 9061 -f 8971 9061 8702 -f 8702 9061 9062 -f 8712 8710 9062 -f 9062 8710 8709 -f 9062 8709 8702 -f 9065 8197 9062 -f 9062 8197 8713 -f 9062 8713 8712 -f 8194 8996 8193 -f 8193 8198 8994 -f 8193 8994 8194 -f 8193 8996 8813 -f 8193 8813 8732 -f 8723 8196 8195 -f 8732 8723 8195 -f 8722 8721 8198 -f 8198 8721 8720 -f 8198 8720 8719 -f 8732 8195 8193 -f 8193 8195 8196 -f 8193 8196 8198 -f 8198 8196 8722 -f 9065 8991 8197 -f 8197 8991 8198 -f 8197 8198 8718 -f 8718 8198 8719 -f 8563 8201 8508 -f 8199 8565 8200 -f 8415 8199 8480 -f 8480 8199 8508 -f 8508 8199 8200 -f 8508 8200 8563 -f 8201 8202 8595 -f 8510 8203 8201 -f 8201 8203 8204 -f 8201 8204 8508 -f 8208 8512 8201 -f 8201 8512 8205 -f 8201 8205 8510 -f 8595 8206 8201 -f 8201 8206 8207 -f 8201 8207 8598 -f 8598 8515 8201 -f 8201 8515 8514 -f 8201 8514 8208 -f 8565 8199 8209 -f 8209 8199 8296 -f 8209 8296 8297 -f 8297 8300 8209 -f 8209 8300 8335 -f 8209 8335 8210 -f 8210 8335 8336 -f 8210 8336 8211 -f 8211 8336 8476 -f 8476 8336 8214 -f 8214 8336 8337 -f 8214 8337 8212 -f 8212 8338 8214 -f 8214 8338 8339 -f 8214 8339 8213 -f 8213 8342 8214 -f 8214 8342 8215 -f 8215 8342 8341 -f 8215 8341 8334 -f 8473 8475 8214 -f 8214 8475 8476 -f 8215 8334 8216 -f 8215 8216 8214 -f 8214 8216 8471 -f 8471 8217 8214 -f 8217 8473 8214 -f 8242 8252 8250 -f 8232 7899 8248 -f 8218 7910 8126 -f 8126 8219 8218 -f 8218 8219 8220 -f 8218 8220 8245 -f 8223 7906 8224 -f 8224 7906 7905 -f 8224 7905 8218 -f 8218 7905 7911 -f 8218 7911 7910 -f 8221 8222 8245 -f 8223 8224 8246 -f 8223 8246 8225 -f 8225 8246 7901 -f 7901 8246 8247 -f 7901 8247 8226 -f 8221 8128 8222 -f 8222 8128 8129 -f 8222 8129 8227 -f 8227 8129 8133 -f 8227 8133 8228 -f 8248 7899 8247 -f 8247 7899 7898 -f 8247 7898 8226 -f 8228 8133 8130 -f 8228 8130 8229 -f 8229 8130 8237 -f 8229 8237 8249 -f 8230 8234 7891 -f 7891 8231 8230 -f 8230 8231 7895 -f 8230 7895 8248 -f 8248 7895 8232 -f 7944 8233 7887 -f 7887 8233 8251 -f 7887 8251 7888 -f 7944 7893 8233 -f 8233 7893 8235 -f 8233 8235 8234 -f 8234 8235 8236 -f 8234 8236 7891 -f 8237 8238 8249 -f 8249 8238 8239 -f 8249 8239 8240 -f 8240 8239 8136 -f 8240 8136 8250 -f 8250 8136 8242 -f 7888 8251 7890 -f 7890 8251 8241 -f 7890 8241 8253 -f 8242 8287 8243 -f 8242 8243 8252 -f 8252 8243 8244 -f 8218 8245 8224 -f 8224 8245 8222 -f 8224 8222 8246 -f 8246 8222 8227 -f 8246 8227 8247 -f 8247 8227 8228 -f 8247 8228 8248 -f 8248 8228 8229 -f 8248 8229 8230 -f 8230 8229 8249 -f 8230 8249 8234 -f 8234 8249 8240 -f 8234 8240 8233 -f 8233 8240 8250 -f 8233 8250 8251 -f 8251 8250 8252 -f 8251 8252 8241 -f 8241 8252 8244 -f 8241 8244 8274 -f 8253 8241 7884 -f 7884 8241 8274 -f 7884 8274 7921 -f 7921 8274 7881 -f 8268 8267 8273 -f 8351 8255 8258 -f 8260 8256 8265 -f 8265 8256 8352 -f 8265 8352 8257 -f 8257 8352 8258 -f 8258 8352 8351 -f 8261 8260 8259 -f 8262 8261 8263 -f 8255 8254 8258 -f 8258 8254 8264 -f 8258 8264 8257 -f 8257 8264 8266 -f 8257 8266 8265 -f 8265 8266 8277 -f 8261 8259 8263 -f 8263 8259 8278 -f 8263 8278 8032 -f 8254 8270 8264 -f 8264 8270 8267 -f 8264 8267 8266 -f 8266 8267 8268 -f 8266 8268 8277 -f 8277 8268 8271 -f 8032 8278 8269 -f 8269 8278 8282 -f 8269 8282 8030 -f 8272 8279 8271 -f 8267 8270 7851 -f 8267 7851 8273 -f 8273 7851 7881 -f 8280 8279 8276 -f 8276 8279 8272 -f 8276 8272 8275 -f 8271 8268 8272 -f 8272 8268 8273 -f 8272 8273 8275 -f 8275 8273 7881 -f 7881 8274 8275 -f 8275 8274 8276 -f 8276 8274 8280 -f 8280 8274 8244 -f 8260 8265 8259 -f 8259 8265 8277 -f 8259 8277 8278 -f 8278 8277 8271 -f 8278 8271 8282 -f 8282 8271 8279 -f 8282 8279 8284 -f 8284 8279 8280 -f 8284 8280 8281 -f 8281 8280 8244 -f 8281 8244 8243 -f 8030 8282 8283 -f 8283 8282 8284 -f 8283 8284 8285 -f 8285 8284 8281 -f 8285 8281 8286 -f 8286 8281 8243 -f 8286 8243 8287 -f 8347 8289 8288 -f 8349 8261 8292 -f 8289 8349 8291 -f 8348 8347 8290 -f 8349 8292 8291 -f 8291 8292 8293 -f 8291 8293 8294 -f 8294 8293 8036 -f 8294 8036 8302 -f 8415 8348 8199 -f 8199 8348 8295 -f 8199 8295 8296 -f 8296 8295 8298 -f 8296 8298 8297 -f 8297 8298 8299 -f 8297 8299 8300 -f 8300 8299 8301 -f 8300 8301 8335 -f 8036 8035 8302 -f 8302 8035 8033 -f 8302 8033 8303 -f 8303 8033 8034 -f 8303 8034 8304 -f 8034 8305 8304 -f 8304 8305 8306 -f 8304 8306 8316 -f 8316 8306 8307 -f 8307 8308 8316 -f 8316 8308 8309 -f 8316 8309 8317 -f 8317 8309 8310 -f 8317 8310 8038 -f 8317 8038 8318 -f 8038 8311 8318 -f 8318 8311 8312 -f 8318 8312 8313 -f 8318 8313 8041 -f 8318 8041 8320 -f 8320 8041 8040 -f 8289 8291 8288 -f 8288 8291 8294 -f 8288 8294 8314 -f 8314 8294 8302 -f 8314 8302 8315 -f 8315 8302 8303 -f 8315 8303 8322 -f 8322 8303 8304 -f 8322 8304 8323 -f 8323 8304 8316 -f 8323 8316 8324 -f 8324 8316 8317 -f 8324 8317 8326 -f 8326 8317 8318 -f 8326 8318 8319 -f 8319 8318 8320 -f 8319 8320 8333 -f 8040 8039 8320 -f 8320 8039 8397 -f 8320 8397 8333 -f 8333 8397 8399 -f 8333 8399 8398 -f 8347 8288 8290 -f 8290 8288 8314 -f 8290 8314 8321 -f 8321 8314 8315 -f 8321 8315 8327 -f 8327 8315 8322 -f 8327 8322 8328 -f 8328 8322 8323 -f 8328 8323 8325 -f 8325 8323 8324 -f 8325 8324 8330 -f 8330 8324 8326 -f 8330 8326 8332 -f 8332 8326 8319 -f 8332 8319 8341 -f 8341 8319 8333 -f 8348 8290 8295 -f 8295 8290 8321 -f 8295 8321 8298 -f 8298 8321 8327 -f 8298 8327 8299 -f 8299 8327 8328 -f 8299 8328 8301 -f 8301 8328 8325 -f 8301 8325 8329 -f 8329 8325 8330 -f 8329 8330 8331 -f 8331 8330 8332 -f 8331 8332 8340 -f 8340 8332 8341 -f 8341 8333 8334 -f 8334 8333 8398 -f 8335 8301 8336 -f 8336 8301 8329 -f 8336 8329 8337 -f 8337 8329 8331 -f 8337 8331 8212 -f 8212 8331 8338 -f 8338 8331 8340 -f 8338 8340 8339 -f 8339 8340 8213 -f 8213 8340 8341 -f 8213 8341 8342 -f 8343 8344 8357 -f 8260 8261 8356 -f 8350 8407 8409 -f 8350 8409 8345 -f 8345 8409 7879 -f 8412 8411 8344 -f 8344 8411 8357 -f 8357 8411 8410 -f 8412 8346 8414 -f 8414 8346 8348 -f 8414 8348 8415 -f 8346 8347 8348 -f 8356 8261 8349 -f 8260 8356 8354 -f 8352 8256 8353 -f 7879 8255 8345 -f 8345 8255 8351 -f 8345 8351 8350 -f 8350 8351 8352 -f 8346 8412 8344 -f 8346 8344 8347 -f 8347 8344 8343 -f 8347 8343 8289 -f 8289 8343 8349 -f 8256 8260 8353 -f 8353 8260 8354 -f 8353 8354 8355 -f 8410 8407 8355 -f 8355 8407 8350 -f 8355 8350 8353 -f 8353 8350 8352 -f 8356 8349 8343 -f 8356 8343 8354 -f 8354 8343 8357 -f 8354 8357 8355 -f 8355 8357 8410 -f 8358 8359 8361 -f 8361 8359 7854 -f 7855 8360 7854 -f 8124 7855 7854 -f 8124 7854 8362 -f 8362 7854 8363 -f 8358 8364 8359 -f 8359 8364 8365 -f 8364 8371 8365 -f 8365 8371 8370 -f 8121 8363 8365 -f 8121 8365 8366 -f 8366 8365 8367 -f 8366 8367 8374 -f 8368 8372 8369 -f 8369 8372 8370 -f 8369 8370 8371 -f 8368 8373 8372 -f 8372 8373 8378 -f 8374 8367 8376 -f 8376 8367 8375 -f 8376 8375 8123 -f 8123 8375 8377 -f 8123 8377 8380 -f 8373 7857 8378 -f 8378 7857 8379 -f 8378 8379 8383 -f 8380 8377 8382 -f 8382 8377 8381 -f 8382 8381 8116 -f 8116 8381 8392 -f 8116 8392 8117 -f 8379 7858 8383 -f 8383 7858 8384 -f 8384 7858 7930 -f 7930 7853 8384 -f 8384 7853 8386 -f 8384 8386 8385 -f 8385 8386 8388 -f 7854 8359 8363 -f 8363 8359 8365 -f 8365 8370 8367 -f 8367 8370 8372 -f 8367 8372 8375 -f 8375 8372 8378 -f 8375 8378 8377 -f 8377 8378 8383 -f 8377 8383 8381 -f 8381 8383 8384 -f 8381 8384 8392 -f 8392 8384 8385 -f 8392 8385 8393 -f 8393 8385 8388 -f 8393 8388 8394 -f 8386 8387 8388 -f 8388 8387 8447 -f 8387 7861 8447 -f 8447 7861 8389 -f 8447 8389 7862 -f 8388 8447 8390 -f 8388 8390 8394 -f 8394 8390 8435 -f 8117 8392 8391 -f 8391 8392 8393 -f 8391 8393 8120 -f 8120 8393 8394 -f 8120 8394 8395 -f 8395 8394 8435 -f 8395 8435 8115 -f 8471 8216 8334 -f 8039 8396 8397 -f 8397 8396 8451 -f 8471 8334 8462 -f 8462 8334 8398 -f 8462 8398 8450 -f 8450 8398 8451 -f 8451 8398 8399 -f 8451 8399 8397 -f 8401 8405 8411 -f 8400 8408 8409 -f 8600 8402 8406 -f 8402 8400 8406 -f 8406 8400 8409 -f 8406 8409 8404 -f 8404 8409 8407 -f 8404 8407 8403 -f 8403 8407 8410 -f 8412 8414 8413 -f 7879 8409 8408 -f 8405 8403 8410 -f 8405 8410 8411 -f 8411 8412 8401 -f 8401 8412 8413 -f 8480 8413 8414 -f 8480 8414 8415 -f 8428 8434 8440 -f 8416 8417 8424 -f 8424 8417 8418 -f 8418 8417 8552 -f 8418 8552 8703 -f 8422 8545 8542 -f 8420 8545 8421 -f 8421 8545 8422 -f 8421 8422 8426 -f 8426 8422 8429 -f 8418 8423 8424 -f 8424 8423 7610 -f 8424 7610 8436 -f 8436 7610 8425 -f 8436 8425 8439 -f 8430 8433 8429 -f 8429 8433 8426 -f 8425 7613 8439 -f 8439 7613 7612 -f 8439 7612 8440 -f 8440 7612 8427 -f 8440 8427 8428 -f 8542 8419 8422 -f 8422 8419 8446 -f 8422 8446 8429 -f 8429 8446 8444 -f 8429 8444 8430 -f 8430 8444 8443 -f 8430 8443 8431 -f 8431 8443 8449 -f 8431 8449 8448 -f 8448 7862 8432 -f 8448 8432 8431 -f 8431 8432 8430 -f 8430 8432 8433 -f 8428 8115 8434 -f 8434 8115 8435 -f 8434 8435 8390 -f 8416 8424 8437 -f 8437 8424 8436 -f 8437 8436 8438 -f 8438 8436 8439 -f 8438 8439 8445 -f 8445 8439 8440 -f 8445 8440 8441 -f 8441 8440 8434 -f 8441 8434 8442 -f 8442 8434 8390 -f 8390 8449 8442 -f 8442 8449 8443 -f 8442 8443 8441 -f 8441 8443 8444 -f 8441 8444 8445 -f 8445 8444 8446 -f 8445 8446 8438 -f 8438 8446 8419 -f 8438 8419 8437 -f 8437 8419 8542 -f 8437 8542 8416 -f 8447 7862 8448 -f 8447 8448 8449 -f 8447 8449 8390 -f 8450 8451 8454 -f 8451 8396 8452 -f 8450 8454 8462 -f 8471 8462 8472 -f 8451 8452 8454 -f 8454 8452 8453 -f 8454 8453 8025 -f 8454 8025 8463 -f 8463 8025 8455 -f 8463 8455 8456 -f 8463 8456 8464 -f 8456 8457 8464 -f 8464 8457 8458 -f 8464 8458 8459 -f 8464 8459 8465 -f 8465 8459 8460 -f 8465 8460 8028 -f 8465 8028 8461 -f 8462 8454 8472 -f 8472 8454 8463 -f 8472 8463 8464 -f 8472 8464 8466 -f 8466 8464 8465 -f 8466 8465 8461 -f 8466 8461 8474 -f 8474 8461 8467 -f 8474 8467 8470 -f 8027 8468 8570 -f 8028 8469 8461 -f 8461 8469 8027 -f 8461 8027 8467 -f 8467 8027 8570 -f 8467 8570 8470 -f 8471 8472 8217 -f 8217 8472 8466 -f 8217 8466 8473 -f 8473 8466 8474 -f 8473 8474 8475 -f 8475 8474 8470 -f 8475 8470 8476 -f 8477 8480 8508 -f 8477 8508 8490 -f 8479 8496 7748 -f 7748 8496 8481 -f 7748 8481 8482 -f 8482 8481 8484 -f 8482 8484 8486 -f 7747 7745 8483 -f 8483 7745 8501 -f 8501 7745 8485 -f 8501 8485 8484 -f 8484 8485 8486 -f 7747 8483 8487 -f 8487 8483 8488 -f 8487 8488 8489 -f 8489 8488 8504 -f 8489 8504 7744 -f 8478 8477 8490 -f 8478 8490 8522 -f 8522 8490 8509 -f 8522 8509 8491 -f 8491 8509 8511 -f 8491 8511 8521 -f 8521 8511 8492 -f 8521 8492 8520 -f 8520 8492 8493 -f 8520 8493 8494 -f 8494 8493 8513 -f 8494 8513 8495 -f 8495 8513 8516 -f 8495 8516 8517 -f 8496 8497 8498 -f 8496 8498 8481 -f 8481 8498 8499 -f 8481 8499 8484 -f 8484 8499 8500 -f 8484 8500 8501 -f 8501 8500 8502 -f 8501 8502 8483 -f 8483 8502 8503 -f 8483 8503 8488 -f 8488 8503 8519 -f 8488 8519 8504 -f 8504 8519 8518 -f 8504 8518 8506 -f 7744 8504 8505 -f 8505 8504 8506 -f 8505 8506 8507 -f 8508 8204 8490 -f 8490 8204 8203 -f 8490 8203 8509 -f 8509 8203 8510 -f 8509 8510 8511 -f 8511 8510 8205 -f 8511 8205 8492 -f 8492 8205 8512 -f 8492 8512 8493 -f 8493 8512 8208 -f 8493 8208 8513 -f 8513 8208 8514 -f 8513 8514 8516 -f 8516 8514 8515 -f 8515 8599 8516 -f 8516 8599 8517 -f 8517 8599 8592 -f 8592 8518 8517 -f 8517 8518 8519 -f 8517 8519 8495 -f 8495 8519 8503 -f 8495 8503 8494 -f 8494 8503 8502 -f 8494 8502 8520 -f 8520 8502 8500 -f 8520 8500 8521 -f 8521 8500 8499 -f 8521 8499 8491 -f 8491 8499 8498 -f 8491 8498 8522 -f 8522 8498 8497 -f 8522 8497 8478 -f 7713 8507 8586 -f 8586 8507 8506 -f 8586 8506 8518 -f 8586 8518 8523 -f 8523 8518 8592 -f 8524 8540 8525 -f 8671 8540 8532 -f 8671 8532 8526 -f 8533 8535 8479 -f 8479 8535 8537 -f 8479 8537 8496 -f 8537 8497 8496 -f 8497 8539 8478 -f 8541 8477 8478 -f 8480 8477 8413 -f 8413 8477 8541 -f 8413 8541 8527 -f 8528 8405 8401 -f 8528 8401 8527 -f 8527 8401 8413 -f 8405 8528 8529 -f 8405 8529 8403 -f 8403 8529 8530 -f 8403 8530 8404 -f 8404 8530 8531 -f 8404 8531 8406 -f 8406 8531 8524 -f 8406 8524 8525 -f 8406 8525 8600 -f 8526 8532 8533 -f 8533 8532 8534 -f 8533 8534 8535 -f 8535 8534 8536 -f 8535 8536 8538 -f 8535 8538 8537 -f 8537 8538 8539 -f 8537 8539 8497 -f 8540 8524 8531 -f 8540 8531 8532 -f 8532 8531 8530 -f 8532 8530 8534 -f 8534 8530 8529 -f 8534 8529 8536 -f 8536 8529 8528 -f 8536 8528 8538 -f 8538 8528 8527 -f 8538 8527 8539 -f 8539 8527 8541 -f 8539 8541 8478 -f 8694 8698 8543 -f 8698 8697 8554 -f 8544 8692 8691 -f 8544 8691 8548 -f 8548 8691 8701 -f 8694 8549 8700 -f 8700 8549 8545 -f 8700 8545 8420 -f 8549 8542 8545 -f 8703 8552 8546 -f 8546 8552 8556 -f 8734 8546 8553 -f 8734 8553 8547 -f 8547 8544 8548 -f 8549 8694 8543 -f 8549 8543 8542 -f 8542 8543 8550 -f 8542 8550 8416 -f 8416 8550 8417 -f 8543 8698 8554 -f 8543 8554 8550 -f 8550 8554 8551 -f 8550 8551 8417 -f 8417 8551 8556 -f 8417 8556 8552 -f 8697 8692 8555 -f 8555 8692 8544 -f 8555 8544 8553 -f 8553 8544 8547 -f 8554 8697 8555 -f 8554 8555 8551 -f 8551 8555 8553 -f 8551 8553 8556 -f 8556 8553 8546 -f 8570 8558 8470 -f 8211 8476 8557 -f 8557 8476 8470 -f 8470 8558 8559 -f 8559 8558 8574 -f 8559 8574 8579 -f 8579 8574 8572 -f 8579 8572 8560 -f 8560 8572 8576 -f 8560 8576 8561 -f 8201 8563 8562 -f 8562 8563 8200 -f 8562 8200 8564 -f 8564 8200 8565 -f 8564 8565 8580 -f 8580 8565 8209 -f 8580 8209 8557 -f 8557 8209 8210 -f 8557 8210 8211 -f 8045 8571 8566 -f 8566 8571 8567 -f 8566 8567 8568 -f 8568 8567 8573 -f 8568 8573 8569 -f 8569 8573 8575 -f 8569 8575 8046 -f 8046 8575 8570 -f 8046 8570 8468 -f 8045 8782 8571 -f 8571 8782 8783 -f 8783 8576 8571 -f 8571 8576 8572 -f 8571 8572 8567 -f 8567 8572 8574 -f 8567 8574 8573 -f 8573 8574 8558 -f 8573 8558 8575 -f 8575 8558 8570 -f 8783 8784 8576 -f 8576 8784 8577 -f 8576 8577 8561 -f 8561 8577 8578 -f 8561 8578 8786 -f 8470 8559 8557 -f 8557 8559 8579 -f 8557 8579 8580 -f 8580 8579 8560 -f 8580 8560 8564 -f 8564 8560 8561 -f 8564 8561 8562 -f 8562 8561 8786 -f 8202 8201 8789 -f 8789 8201 8562 -f 8789 8562 8790 -f 8790 8562 8786 -f 8780 8779 7647 -f 8595 8202 8594 -f 8581 8780 7647 -f 8581 7647 8584 -f 8584 7647 8585 -f 7649 8587 8583 -f 8583 8587 8590 -f 8583 8590 8584 -f 8583 8584 8585 -f 8791 8582 8594 -f 8594 8582 8589 -f 8594 8589 8596 -f 8596 8589 8588 -f 8596 8588 8597 -f 8597 8588 8591 -f 8597 8591 8593 -f 7649 7713 8586 -f 7649 8586 8587 -f 8587 8586 8523 -f 8523 8591 8587 -f 8587 8591 8588 -f 8587 8588 8590 -f 8590 8588 8589 -f 8590 8589 8584 -f 8584 8589 8582 -f 8584 8582 8581 -f 8581 8582 8791 -f 8581 8791 8780 -f 8523 8592 8591 -f 8591 8592 8593 -f 8593 8592 8599 -f 8595 8594 8596 -f 8595 8596 8206 -f 8206 8596 8597 -f 8206 8597 8207 -f 8207 8597 8593 -f 8207 8593 8598 -f 8598 8593 8599 -f 8598 8599 8515 -f 8617 8619 7761 -f 7762 8613 8611 -f 8688 8603 8601 -f 8654 8797 8688 -f 8684 8806 8797 -f 8795 8805 8602 -f 7771 8795 8602 -f 7771 8602 8682 -f 7771 8682 8604 -f 8601 8603 7867 -f 8601 7867 8656 -f 8656 7867 8657 -f 8604 8682 7769 -f 7769 8682 8681 -f 7769 8681 8605 -f 7867 7920 8657 -f 8657 7920 8660 -f 8660 7920 7852 -f 8605 8681 8606 -f 8606 8681 8608 -f 8606 8608 8607 -f 8660 7852 7943 -f 8660 7943 8661 -f 8607 8608 8609 -f 8609 8608 8612 -f 8609 8612 7764 -f 7943 8610 8661 -f 8661 8610 8663 -f 8611 8613 8612 -f 8612 8613 8614 -f 8612 8614 7764 -f 8610 7872 8663 -f 8663 7872 8623 -f 8663 8623 8615 -f 7762 8611 7761 -f 7761 8611 8616 -f 7761 8616 8617 -f 8620 7760 8618 -f 8620 8618 8617 -f 8617 8618 8619 -f 7760 8620 8621 -f 8621 8620 8622 -f 8621 8622 7756 -f 8615 8623 7871 -f 8615 7871 8625 -f 8625 7871 8624 -f 8625 8624 8666 -f 8666 8624 8627 -f 8666 8627 8626 -f 8626 8627 8667 -f 8627 7991 8667 -f 8667 7991 8628 -f 8667 8628 8629 -f 8630 8635 8631 -f 8631 7755 8630 -f 8630 7755 8632 -f 8630 8632 8622 -f 8622 8632 7757 -f 8622 7757 7756 -f 8629 8628 8633 -f 8629 8633 8637 -f 7754 7753 8634 -f 8634 7753 8636 -f 8634 8636 8635 -f 8635 8636 8631 -f 8633 7876 8637 -f 8637 7876 7875 -f 8637 7875 8668 -f 8668 7875 7929 -f 8653 8638 8639 -f 8639 8638 8668 -f 8639 8668 7929 -f 8797 8654 8684 -f 8684 8654 8655 -f 8684 8655 8683 -f 8683 8655 8658 -f 8683 8658 8640 -f 8640 8658 8659 -f 8640 8659 8680 -f 8680 8659 8662 -f 8680 8662 8679 -f 8679 8662 8641 -f 8679 8641 8678 -f 8678 8641 8642 -f 8678 8642 8677 -f 8677 8642 8664 -f 8677 8664 8643 -f 8643 8664 8665 -f 8643 8665 8676 -f 8676 8665 8644 -f 8676 8644 8645 -f 8645 8644 8646 -f 8645 8646 8675 -f 8675 8646 8647 -f 8675 8647 8648 -f 8648 8647 8669 -f 8648 8669 8674 -f 8674 8669 8670 -f 8674 8670 8649 -f 8649 8670 8650 -f 8649 8650 8651 -f 7754 8634 8652 -f 8652 8634 8673 -f 8652 8673 8672 -f 8652 8672 7750 -f 8525 8638 8653 -f 8525 8653 8600 -f 8688 8601 8654 -f 8654 8601 8656 -f 8654 8656 8655 -f 8655 8656 8657 -f 8655 8657 8658 -f 8658 8657 8660 -f 8658 8660 8659 -f 8659 8660 8661 -f 8659 8661 8662 -f 8662 8661 8663 -f 8662 8663 8641 -f 8641 8663 8615 -f 8641 8615 8642 -f 8642 8615 8625 -f 8642 8625 8664 -f 8664 8625 8666 -f 8664 8666 8665 -f 8665 8666 8626 -f 8665 8626 8644 -f 8644 8626 8667 -f 8644 8667 8646 -f 8646 8667 8629 -f 8646 8629 8647 -f 8647 8629 8637 -f 8647 8637 8669 -f 8669 8637 8668 -f 8669 8668 8670 -f 8670 8668 8638 -f 8670 8638 8650 -f 8650 8638 8525 -f 8650 8525 8540 -f 8650 8540 8671 -f 8650 8671 8651 -f 8651 8671 8526 -f 8526 8672 8651 -f 8651 8672 8673 -f 8651 8673 8649 -f 8649 8673 8634 -f 8649 8634 8674 -f 8674 8634 8635 -f 8674 8635 8648 -f 8648 8635 8630 -f 8648 8630 8675 -f 8675 8630 8622 -f 8675 8622 8645 -f 8645 8622 8620 -f 8645 8620 8676 -f 8676 8620 8617 -f 8676 8617 8643 -f 8643 8617 8616 -f 8643 8616 8677 -f 8677 8616 8611 -f 8677 8611 8678 -f 8678 8611 8612 -f 8678 8612 8679 -f 8679 8612 8608 -f 8679 8608 8680 -f 8680 8608 8681 -f 8680 8681 8640 -f 8640 8681 8682 -f 8640 8682 8683 -f 8683 8682 8602 -f 8683 8602 8684 -f 8684 8602 8805 -f 8684 8805 8806 -f 8526 8533 8672 -f 8672 8533 7750 -f 7750 8533 8685 -f 8685 8533 8479 -f 8686 8696 8698 -f 8687 8801 8693 -f 8688 8690 8689 -f 8689 8690 8699 -f 8701 8695 8191 -f 8691 8692 8693 -f 8687 8693 8692 -f 8687 8692 8697 -f 8694 8700 8690 -f 8701 8691 8695 -f 8695 8691 8693 -f 8695 8693 8801 -f 8696 8687 8697 -f 8696 8697 8698 -f 8698 8694 8686 -f 8686 8694 8690 -f 8699 8690 7865 -f 7865 8690 8700 -f 7865 8700 8420 -f 8546 8734 8735 -f 8701 8702 8548 -f 8548 8702 8708 -f 8734 8547 8724 -f 8724 8547 8548 -f 8703 8546 8746 -f 8703 8746 8704 -f 8704 8746 8747 -f 8704 8747 7609 -f 7609 8747 8705 -f 8705 8747 8707 -f 8705 8707 8706 -f 8706 8707 8748 -f 8706 8748 7606 -f 8702 8709 8708 -f 8708 8709 8710 -f 8708 8710 8711 -f 8711 8710 8712 -f 8711 8712 8725 -f 8725 8712 8713 -f 8725 8713 8714 -f 8714 8713 8197 -f 8714 8197 8729 -f 7606 8748 8749 -f 7606 8749 8715 -f 8715 8749 8752 -f 8715 8752 8716 -f 8716 8752 7605 -f 7605 8752 8717 -f 8717 8752 8756 -f 8717 8756 7603 -f 7603 8756 8754 -f 8197 8718 8729 -f 8729 8718 8719 -f 8729 8719 8730 -f 8730 8719 8720 -f 8730 8720 8721 -f 8730 8721 8731 -f 8731 8721 8722 -f 8731 8722 8196 -f 8731 8196 8723 -f 8548 8708 8724 -f 8724 8708 8711 -f 8724 8711 8736 -f 8736 8711 8725 -f 8736 8725 8726 -f 8726 8725 8714 -f 8726 8714 8727 -f 8727 8714 8729 -f 8727 8729 8728 -f 8728 8729 8730 -f 8728 8730 8741 -f 8741 8730 8731 -f 8741 8731 8742 -f 8742 8731 8723 -f 8742 8723 8744 -f 8744 8723 8745 -f 8723 8732 8812 -f 8723 8812 8745 -f 8745 8812 8733 -f 8745 8733 8814 -f 8734 8724 8735 -f 8735 8724 8736 -f 8735 8736 8737 -f 8737 8736 8726 -f 8737 8726 8738 -f 8738 8726 8727 -f 8738 8727 8739 -f 8739 8727 8728 -f 8739 8728 8740 -f 8740 8728 8741 -f 8740 8741 8750 -f 8750 8741 8751 -f 8751 8741 8742 -f 8751 8742 8743 -f 8743 8742 8744 -f 8546 8735 8746 -f 8746 8735 8737 -f 8746 8737 8747 -f 8747 8737 8738 -f 8747 8738 8707 -f 8707 8738 8739 -f 8707 8739 8748 -f 8748 8739 8740 -f 8748 8740 8749 -f 8749 8740 8750 -f 8749 8750 8752 -f 8752 8750 8751 -f 8752 8751 8743 -f 8752 8743 8756 -f 8756 8743 8744 -f 8756 8744 8753 -f 8753 8744 8745 -f 8753 8745 8759 -f 8759 8745 8814 -f 8759 8814 8760 -f 8754 8756 8755 -f 8755 8756 8753 -f 8755 8753 7600 -f 7600 8753 7599 -f 7599 8753 8757 -f 8757 8753 8759 -f 8757 8759 7602 -f 7602 8759 8758 -f 8758 8759 8760 -f 8758 8760 7601 -f 8762 8047 8112 -f 8777 8762 8775 -f 8762 8112 8775 -f 8775 8112 8111 -f 8111 8763 8775 -f 8775 8763 8765 -f 8775 8765 8764 -f 8764 8765 8109 -f 8764 8109 8766 -f 8109 8767 8766 -f 8766 8767 8769 -f 8761 8776 8768 -f 8761 8768 8778 -f 8766 8769 8770 -f 8766 8770 8778 -f 8778 8770 8771 -f 8778 8771 8772 -f 8778 8772 8113 -f 8150 8113 8773 -f 8777 8775 8764 -f 8776 8777 8764 -f 8776 8764 8768 -f 8768 8764 8766 -f 8768 8766 8778 -f 8778 8113 8150 -f 8783 8782 8894 -f 8791 8895 8897 -f 8791 8897 8780 -f 8920 8785 8781 -f 8894 8782 8045 -f 8894 8781 8783 -f 8783 8781 8784 -f 8784 8781 8577 -f 8577 8781 8578 -f 8578 8781 8785 -f 8578 8785 8786 -f 8920 8792 8785 -f 8785 8792 8786 -f 8787 8202 8788 -f 8788 8202 8789 -f 8788 8789 8790 -f 8791 8594 8787 -f 8787 8594 8202 -f 8895 8791 8787 -f 8895 8787 8792 -f 8792 8787 8788 -f 8792 8788 8786 -f 8786 8788 8790 -f 8807 8932 8793 -f 8930 8807 8794 -f 8930 8794 8931 -f 8805 8795 8802 -f 8931 8802 8795 -f 8806 8810 8797 -f 8796 8688 8797 -f 8690 8688 8796 -f 8690 8796 8798 -f 8799 8696 8686 -f 8799 8686 8798 -f 8798 8686 8690 -f 8696 8799 8809 -f 8696 8809 8687 -f 8687 8809 8800 -f 8687 8800 8801 -f 8695 8801 8793 -f 8695 8793 8932 -f 8695 8932 8191 -f 8931 8794 8808 -f 8931 8808 8802 -f 8802 8808 8803 -f 8802 8803 8804 -f 8802 8804 8805 -f 8805 8804 8810 -f 8805 8810 8806 -f 8807 8793 8801 -f 8807 8801 8794 -f 8794 8801 8800 -f 8794 8800 8808 -f 8808 8800 8809 -f 8808 8809 8803 -f 8803 8809 8799 -f 8803 8799 8804 -f 8804 8799 8798 -f 8804 8798 8810 -f 8810 8798 8796 -f 8810 8796 8797 -f 8811 7601 8760 -f 8732 8813 8812 -f 8812 8813 8815 -f 8811 8760 8985 -f 8985 8760 8814 -f 8985 8814 8990 -f 8990 8814 8815 -f 8815 8814 8733 -f 8815 8733 8812 -f 8825 8826 8831 -f 8090 8997 8817 -f 8817 8997 8998 -f 8090 8817 8818 -f 8818 8817 8828 -f 8818 8828 8089 -f 8155 8821 8819 -f 8819 8821 8828 -f 8819 8828 8820 -f 8820 8828 8817 -f 8820 8817 8149 -f 8149 8817 8998 -f 8149 8998 8816 -f 8821 8155 8822 -f 8821 8822 8823 -f 8823 8822 8151 -f 8823 8151 8831 -f 8831 8151 8824 -f 8831 8824 8825 -f 8825 8150 8826 -f 8089 8828 8827 -f 8827 8828 8821 -f 8827 8821 8829 -f 8829 8821 8823 -f 8829 8823 8830 -f 8830 8823 8831 -f 8830 8831 8088 -f 8088 8831 8826 -f 8088 8826 8832 -f 8832 8826 8150 -f 8832 8150 8774 -f 8841 8145 8840 -f 8834 8836 8835 -f 8145 8839 8840 -f 8840 8839 8838 -f 8840 8838 8843 -f 8843 8838 8837 -f 8843 8837 8844 -f 8844 8837 8836 -f 8844 8836 8845 -f 8845 8836 8834 -f 8842 8841 8840 -f 8842 8840 8848 -f 8848 8840 8843 -f 8848 8843 8850 -f 8850 8843 8844 -f 8850 8844 8851 -f 8851 8844 8845 -f 8144 8841 8846 -f 8846 8841 8842 -f 8846 8842 8847 -f 8847 8842 8848 -f 8847 8848 8849 -f 8849 8848 8850 -f 8849 8850 8855 -f 8855 8850 8851 -f 8852 8144 8856 -f 8856 8144 8846 -f 8856 8846 8861 -f 8861 8846 8847 -f 8861 8847 8853 -f 8853 8847 8849 -f 8853 8849 8854 -f 8854 8849 8855 -f 8862 8141 8856 -f 8856 8141 8852 -f 8050 8857 8858 -f 8858 8857 8859 -f 8858 8859 8860 -f 8860 8859 8868 -f 8860 8868 8863 -f 8863 8868 8865 -f 8854 8050 8853 -f 8853 8050 8858 -f 8853 8858 8861 -f 8861 8858 8860 -f 8861 8860 8856 -f 8856 8860 8863 -f 8856 8863 8862 -f 8862 8863 8865 -f 8862 8865 8143 -f 8869 8143 8864 -f 8864 8143 8865 -f 8864 8865 8866 -f 8866 8865 8868 -f 8866 8868 8867 -f 8867 8868 8859 -f 8867 8859 8873 -f 8873 8859 8857 -f 8874 8869 8875 -f 8875 8869 8864 -f 8875 8864 8870 -f 8870 8864 8866 -f 8870 8866 8871 -f 8871 8866 8867 -f 8871 8867 8872 -f 8872 8867 8873 -f 8140 8874 8877 -f 8877 8874 8875 -f 8877 8875 8876 -f 8876 8875 8870 -f 8876 8870 8880 -f 8880 8870 8871 -f 8880 8871 8881 -f 8881 8871 8872 -f 8882 8140 8884 -f 8884 8140 8877 -f 8884 8877 8878 -f 8878 8877 8876 -f 8878 8876 8879 -f 8879 8876 8880 -f 8879 8880 8049 -f 8049 8880 8881 -f 8138 8882 8887 -f 8887 8882 8884 -f 8887 8884 8883 -f 8883 8884 8878 -f 8883 8878 8885 -f 8885 8878 8879 -f 8885 8879 8890 -f 8890 8879 8049 -f 8891 8138 8833 -f 8833 8138 8887 -f 8833 8887 8886 -f 8886 8887 8883 -f 8886 8883 8888 -f 8888 8883 8885 -f 8888 8885 8889 -f 8889 8885 8890 -f 8761 8891 8776 -f 8776 8891 8833 -f 8776 8833 8777 -f 8777 8833 8886 -f 8777 8886 8762 -f 8762 8886 8888 -f 8762 8888 8047 -f 8047 8888 8889 -f 8781 8894 8893 -f 8920 8902 8792 -f 8895 8792 8903 -f 8897 8895 8896 -f 8926 8780 8897 -f 8780 8926 8898 -f 8780 8898 8779 -f 8898 8926 8912 -f 8912 8926 8909 -f 8781 8893 8899 -f 8899 8893 8900 -f 8899 8900 8901 -f 8901 8900 8914 -f 8901 8914 8919 -f 8919 8914 8913 -f 8919 8913 8917 -f 8792 8902 8903 -f 8903 8902 8904 -f 8903 8904 8905 -f 8905 8904 8918 -f 8905 8918 8923 -f 8923 8918 8921 -f 8923 8921 8922 -f 8895 8892 8896 -f 8896 8892 8906 -f 8896 8906 8927 -f 8927 8906 8924 -f 8927 8924 8907 -f 8907 8924 8925 -f 8907 8925 8929 -f 7642 7645 8908 -f 8908 7645 8928 -f 8928 7645 8910 -f 8928 8910 8909 -f 8909 8910 8911 -f 8909 8911 8912 -f 8042 8835 9005 -f 9005 8913 8042 -f 8042 8913 8914 -f 8042 8914 8043 -f 8043 8914 8900 -f 8043 8900 8915 -f 8915 8900 8893 -f 8915 8893 8044 -f 8044 8893 8894 -f 8044 8894 8045 -f 8913 9005 8916 -f 8913 8916 8917 -f 8917 8916 9006 -f 9006 8921 8917 -f 8917 8921 8918 -f 8917 8918 8919 -f 8919 8918 8904 -f 8919 8904 8901 -f 8901 8904 8902 -f 8901 8902 8899 -f 8899 8902 8920 -f 8899 8920 8781 -f 8921 9006 9015 -f 8921 9015 8922 -f 8895 8903 8892 -f 8892 8903 8905 -f 8892 8905 8906 -f 8906 8905 8923 -f 8906 8923 8924 -f 8924 8923 8922 -f 8924 8922 8925 -f 8925 8922 9015 -f 8925 9015 9014 -f 8925 9014 9007 -f 8925 9007 8929 -f 8897 8896 8926 -f 8926 8896 8927 -f 8926 8927 8909 -f 8909 8927 8907 -f 8909 8907 8928 -f 8928 8907 8929 -f 8928 8929 8908 -f 8908 8929 9007 -f 8908 9007 9008 -f 7643 7642 8908 -f 7643 8908 9008 -f 8795 8933 8931 -f 8932 8807 8946 -f 8946 8807 8930 -f 8931 8933 8959 -f 8959 8933 8935 -f 8959 8935 8934 -f 8934 8935 8936 -f 8935 8937 8936 -f 8936 8937 8938 -f 8936 8938 8956 -f 8938 7772 8956 -f 8956 7772 8939 -f 8956 8939 8941 -f 8941 8939 7741 -f 7741 8940 8941 -f 8941 8940 8943 -f 8941 8943 8942 -f 8942 8943 8955 -f 8955 8943 7773 -f 8955 7773 8944 -f 8944 7773 8945 -f 8930 8947 8946 -f 8946 8947 8958 -f 8946 8958 8961 -f 8961 8958 8957 -f 8961 8957 8964 -f 8964 8957 8948 -f 8964 8948 8965 -f 8965 8948 8949 -f 8965 8949 8950 -f 8950 8949 8951 -f 8950 8951 8967 -f 8967 8951 8952 -f 8967 8952 8953 -f 8953 8952 8954 -f 8953 8954 8960 -f 8945 7774 8944 -f 8944 7774 9035 -f 9035 8954 8944 -f 8944 8954 8952 -f 8944 8952 8955 -f 8955 8952 8951 -f 8955 8951 8942 -f 8942 8951 8949 -f 8942 8949 8941 -f 8941 8949 8948 -f 8941 8948 8956 -f 8956 8948 8957 -f 8956 8957 8936 -f 8936 8957 8958 -f 8936 8958 8934 -f 8934 8958 8947 -f 8934 8947 8959 -f 8959 8947 8930 -f 8959 8930 8931 -f 9035 9034 8954 -f 8954 9034 9032 -f 8954 9032 8960 -f 8960 9032 9031 -f 8932 8946 8961 -f 8932 8961 8962 -f 8962 8961 8964 -f 8962 8964 8963 -f 8963 8964 8965 -f 8963 8965 8973 -f 8973 8965 8950 -f 8973 8950 8966 -f 8966 8950 8967 -f 8966 8967 8968 -f 8968 8967 8953 -f 8968 8953 8969 -f 8969 8953 8960 -f 8969 8960 8970 -f 8970 8960 9031 -f 8191 8932 8971 -f 8971 8932 8962 -f 8971 8962 8972 -f 8972 8962 8963 -f 8972 8963 8190 -f 8190 8963 8973 -f 8190 8973 8185 -f 8185 8973 8966 -f 8185 8966 8974 -f 8974 8966 8968 -f 8974 8968 8975 -f 8975 8968 8969 -f 8975 8969 8976 -f 8976 8969 8970 -f 8976 8970 8186 -f 8186 8970 9031 -f 8186 9031 8187 -f 9055 7589 7590 -f 8992 9056 9055 -f 8991 9064 8992 -f 8992 9064 9056 -f 9055 7590 8977 -f 8977 7590 8978 -f 8977 8978 8986 -f 8986 8978 8980 -f 8986 8980 8979 -f 8979 8980 7592 -f 8979 7592 8987 -f 7592 7591 8987 -f 8987 7591 8981 -f 8987 8981 7598 -f 8987 7598 8984 -f 8984 7598 7596 -f 7596 8982 8984 -f 8984 8982 8983 -f 8984 8983 8989 -f 8989 8983 7594 -f 7594 8811 8989 -f 8989 8811 8985 -f 8989 8985 8990 -f 9055 8977 8992 -f 8992 8977 8986 -f 8992 8986 8993 -f 8993 8986 8979 -f 8993 8979 8987 -f 8993 8987 8988 -f 8988 8987 8984 -f 8988 8984 8995 -f 8995 8984 8989 -f 8995 8989 8990 -f 8995 8990 8815 -f 8991 8992 8198 -f 8198 8992 8993 -f 8198 8993 8994 -f 8994 8993 8988 -f 8994 8988 8194 -f 8194 8988 8995 -f 8194 8995 8996 -f 8996 8995 8815 -f 8996 8815 8813 -f 9000 9081 9123 -f 8998 8997 8999 -f 8816 8998 9134 -f 9134 8998 9123 -f 9123 8998 8999 -f 9123 8999 9000 -f 8837 8838 9016 -f 8838 8839 9001 -f 9008 9148 9002 -f 9008 9002 7643 -f 9011 9001 8839 -f 9004 8836 8837 -f 9004 8837 9017 -f 8835 8836 9005 -f 9005 8836 9004 -f 9005 9004 9017 -f 9006 8916 9017 -f 9017 8916 9005 -f 9014 9009 9007 -f 9008 9007 9148 -f 9148 9007 9003 -f 9003 9007 9009 -f 9003 9009 9010 -f 9010 9009 9012 -f 9010 9012 9011 -f 9011 9012 9013 -f 9011 9013 9001 -f 9001 9013 9016 -f 9001 9016 8838 -f 9009 9014 9015 -f 9009 9015 9012 -f 9012 9015 9013 -f 9013 9015 9006 -f 9013 9006 9016 -f 9016 9006 9017 -f 9016 9017 8837 -f 7626 7625 9020 -f 9019 9180 9021 -f 9020 9179 9180 -f 9020 9180 9019 -f 9179 9020 7625 -f 9027 9029 7626 -f 9027 7626 9020 -f 9027 9020 9025 -f 9025 9020 9019 -f 9025 9019 9024 -f 9024 9019 9021 -f 9024 9021 9022 -f 9022 9021 9018 -f 9022 9023 9024 -f 9024 9023 9026 -f 9024 9026 9025 -f 9025 9026 9037 -f 9025 9037 9027 -f 9027 9037 9028 -f 9027 9028 9029 -f 7623 9030 9028 -f 9028 9030 9029 -f 8187 9031 8188 -f 8188 9031 9036 -f 9036 9031 9032 -f 9036 9032 9038 -f 9038 9032 9034 -f 9038 9034 9033 -f 9033 9034 9035 -f 9023 8188 9026 -f 9026 8188 9036 -f 9026 9036 9037 -f 9037 9036 9038 -f 9037 9038 9028 -f 9028 9038 9033 -f 9028 9033 7623 -f 7623 9033 9035 -f 7623 9035 7774 -f 9172 9039 9173 -f 9040 9178 9057 -f 9057 9178 9173 -f 9018 9040 9042 -f 9041 9018 9042 -f 9041 9042 8189 -f 8189 9042 9058 -f 8189 9058 9043 -f 9043 9058 9044 -f 9043 9044 8192 -f 8192 9044 9061 -f 9173 9039 9046 -f 9046 9039 9053 -f 9046 9053 9047 -f 9047 9053 9045 -f 9047 9045 9048 -f 9048 9045 9051 -f 9048 9051 9049 -f 9173 9046 9057 -f 9057 9046 9047 -f 9057 9047 9059 -f 9059 9047 9048 -f 9059 9048 9060 -f 9060 9048 9049 -f 9060 9049 9050 -f 7589 9051 9052 -f 9052 9051 9045 -f 9052 9045 7616 -f 7616 9045 9053 -f 7616 9053 7615 -f 7615 9053 9039 -f 7615 9039 9054 -f 9054 9039 9172 -f 9054 9172 9220 -f 7589 9055 9051 -f 9051 9055 9049 -f 9049 9055 9050 -f 9050 9055 9056 -f 9040 9057 9042 -f 9042 9057 9059 -f 9042 9059 9058 -f 9058 9059 9060 -f 9058 9060 9044 -f 9044 9060 9050 -f 9044 9050 9063 -f 9063 9050 9056 -f 9063 9056 9064 -f 9061 9044 9062 -f 9062 9044 9063 -f 9062 9063 9065 -f 9065 9063 9064 -f 9065 9064 8991 -f 8106 9066 9070 -f 8101 9067 9193 -f 9193 9067 9068 -f 9193 9068 9197 -f 9197 9068 8054 -f 8054 9068 9072 -f 8054 9072 9073 -f 9067 8100 9068 -f 9068 8100 9069 -f 9068 9069 9072 -f 9072 9069 8104 -f 9072 8104 9070 -f 9070 8104 8107 -f 9070 8107 8106 -f 9066 8053 9070 -f 9070 8053 9071 -f 9070 9071 9072 -f 9072 9071 9073 -f 9077 9074 9066 -f 9066 9074 8053 -f 9079 9078 9075 -f 9075 9078 9076 -f 9075 8108 9079 -f 8106 9076 9066 -f 9066 9076 9078 -f 9066 9078 9077 -f 9077 9078 9079 -f 9077 9079 9080 -f 9080 9079 8052 -f 8999 8997 9084 -f 9000 8999 9083 -f 9000 9109 9081 -f 9081 9109 9082 -f 8999 9084 9083 -f 9083 9084 8091 -f 9083 8091 9108 -f 9108 8091 8086 -f 9108 8086 9086 -f 8086 9085 9086 -f 9086 9085 8094 -f 9086 8094 9110 -f 9110 8094 8093 -f 9110 8093 8097 -f 9110 8097 9111 -f 9111 8097 9087 -f 9111 9087 8096 -f 9111 8096 9092 -f 9082 9109 8171 -f 8171 9109 9088 -f 8171 9088 9089 -f 9089 9088 9090 -f 9089 9090 8168 -f 8168 9090 9112 -f 8168 9112 9091 -f 9091 9112 9114 -f 9091 9114 9102 -f 8096 8095 9092 -f 9092 8095 9093 -f 9092 9093 9096 -f 9096 9093 9094 -f 9096 9094 9095 -f 9096 9095 8098 -f 9096 8098 9113 -f 9113 8098 9097 -f 9113 9097 9098 -f 9113 9098 9116 -f 9116 9098 9099 -f 9116 9099 9100 -f 9116 9100 9101 -f 9101 9100 8102 -f 9102 9114 9115 -f 9102 9115 8166 -f 8166 9115 9104 -f 8166 9104 9103 -f 9103 9104 9119 -f 9103 9119 8167 -f 8167 9119 9105 -f 9101 8102 9106 -f 9101 9106 9117 -f 9117 9106 9107 -f 9117 9107 9118 -f 9107 8101 9198 -f 9107 9198 9118 -f 9118 9198 9194 -f 9000 9083 9109 -f 9109 9083 9108 -f 9109 9108 9086 -f 9109 9086 9088 -f 9088 9086 9110 -f 9088 9110 9090 -f 9090 9110 9111 -f 9090 9111 9112 -f 9112 9111 9092 -f 9112 9092 9096 -f 9112 9096 9114 -f 9114 9096 9113 -f 9114 9113 9115 -f 9115 9113 9116 -f 9115 9116 9104 -f 9104 9116 9101 -f 9104 9101 9119 -f 9119 9101 9117 -f 9119 9117 9120 -f 9120 9117 9118 -f 9120 9118 9194 -f 9105 9119 9120 -f 9105 9120 8165 -f 8165 9120 9121 -f 9121 9120 9194 -f 9121 9194 9195 -f 9123 9081 9122 -f 9134 9123 9125 -f 9134 9124 8816 -f 9123 9122 9125 -f 9125 9122 8169 -f 9125 8169 9135 -f 8816 9124 9126 -f 9126 9124 9128 -f 9126 9128 9127 -f 9127 9128 9136 -f 9127 9136 9129 -f 8169 8172 9135 -f 9135 8172 9130 -f 9135 9130 9131 -f 9131 9130 9142 -f 9129 9136 9132 -f 9132 9136 9133 -f 9132 9133 8154 -f 8154 9133 9138 -f 8154 9138 9145 -f 9134 9125 9124 -f 9124 9125 9135 -f 9124 9135 9128 -f 9128 9135 9131 -f 9128 9131 9136 -f 9136 9131 9142 -f 9136 9142 9133 -f 9133 9142 9137 -f 9133 9137 9138 -f 9138 9137 9144 -f 9138 9144 9146 -f 9205 9210 9139 -f 9139 9210 9144 -f 9139 9144 9140 -f 9140 9144 9137 -f 9140 9137 9141 -f 9141 9137 9142 -f 9141 9142 9143 -f 9143 9142 9130 -f 9144 9210 9200 -f 9144 9200 9146 -f 9145 9138 9147 -f 9147 9138 9146 -f 9147 9146 9200 -f 9147 9200 8147 -f 9152 9011 8839 -f 9153 9010 9011 -f 9163 9003 9010 -f 9167 9148 9003 -f 9002 9148 9166 -f 9149 7643 9002 -f 9149 9002 9166 -f 9149 9166 9169 -f 9149 9169 9150 -f 8839 9151 9152 -f 9152 9151 9160 -f 9152 9160 9154 -f 9154 9160 9158 -f 9011 9152 9153 -f 9153 9152 9154 -f 9153 9154 9162 -f 9162 9154 9158 -f 9162 9158 9161 -f 9003 9163 9167 -f 9167 9163 9155 -f 9167 9155 9156 -f 9156 9155 9164 -f 9156 9164 9165 -f 8147 9207 9157 -f 9157 9207 9158 -f 9157 9158 9159 -f 9159 9158 9160 -f 9158 9207 9206 -f 9158 9206 9161 -f 9161 9206 9214 -f 9214 9164 9161 -f 9161 9164 9155 -f 9161 9155 9162 -f 9162 9155 9163 -f 9162 9163 9153 -f 9153 9163 9010 -f 9164 9214 9211 -f 9164 9211 9165 -f 9211 9170 9165 -f 9165 9170 9169 -f 9165 9169 9156 -f 9156 9169 9166 -f 9156 9166 9167 -f 9167 9166 9148 -f 9211 9168 9170 -f 9150 9169 7640 -f 7640 9169 9170 -f 7640 9170 7639 -f 7639 9170 9168 -f 7639 9168 9208 -f 9172 9173 9171 -f 9182 9174 9175 -f 9217 9219 9180 -f 9177 9021 9180 -f 9176 9018 9177 -f 9177 9018 9021 -f 9176 9040 9018 -f 9173 9178 9171 -f 9171 9178 9182 -f 9171 9182 9175 -f 9179 9217 9180 -f 9180 9219 9181 -f 9177 9180 9181 -f 9177 9181 9176 -f 9176 9181 9174 -f 9176 9174 9040 -f 9040 9174 9182 -f 9040 9182 9178 -f 9190 8083 9185 -f 9185 8084 9184 -f 9184 8084 8085 -f 9184 8085 9189 -f 9185 9184 9190 -f 9191 8081 9190 -f 9190 8081 8083 -f 9183 8069 9186 -f 9186 8069 9188 -f 9188 8069 8052 -f 9191 9188 8079 -f 8080 9188 8052 -f 9297 9183 9186 -f 9297 9186 9187 -f 9187 9186 9188 -f 9189 9297 9184 -f 9184 9297 9187 -f 9184 9187 9190 -f 9190 9187 9188 -f 9190 9188 9191 -f 8080 8052 9192 -f 9192 8052 8076 -f 8076 8052 9079 -f 8076 9079 8108 -f 9198 8101 9193 -f 9193 9197 9199 -f 9195 9194 9196 -f 9196 9194 9198 -f 9196 9198 9199 -f 9199 9198 9193 -f 9209 9360 9357 -f 9360 9209 9364 -f 9364 9209 9201 -f 9364 9201 9202 -f 9364 9202 9203 -f 9203 9202 9204 -f 9203 9204 9205 -f 9205 9204 9210 -f 8147 9200 9207 -f 9207 9200 9216 -f 9207 9216 9206 -f 9168 9357 9208 -f 9357 9168 9209 -f 9201 9209 9212 -f 9201 9212 9202 -f 9202 9212 9213 -f 9202 9213 9204 -f 9204 9213 9215 -f 9204 9215 9210 -f 9210 9215 9200 -f 9168 9211 9209 -f 9209 9211 9212 -f 9212 9211 9214 -f 9212 9214 9213 -f 9213 9214 9206 -f 9213 9206 9215 -f 9215 9206 9216 -f 9215 9216 9200 -f 9221 9217 7624 -f 7624 9217 9179 -f 9181 9219 9218 -f 9174 9181 9241 -f 9229 9175 9174 -f 9248 9172 9171 -f 9249 9220 9172 -f 9222 9223 7739 -f 7739 9223 9221 -f 7739 9221 7624 -f 9222 7707 9223 -f 9223 7707 9224 -f 9223 9224 9225 -f 9224 7627 9225 -f 9225 7627 9238 -f 9225 9238 9226 -f 9181 9218 9241 -f 9241 9218 9240 -f 9241 9240 9227 -f 9227 9240 9228 -f 9227 9228 9244 -f 9244 9228 9239 -f 9244 9239 9245 -f 9174 9242 9229 -f 9229 9242 9243 -f 9229 9243 9230 -f 9230 9243 9231 -f 9230 9231 9233 -f 9233 9231 9232 -f 9233 9232 9234 -f 9171 9247 9248 -f 9248 9247 9246 -f 9248 9246 9235 -f 9235 9246 9236 -f 9235 9236 9252 -f 9252 9236 9237 -f 9252 9237 9253 -f 9372 9373 7629 -f 7629 9373 9226 -f 7629 9226 9238 -f 9226 9373 9387 -f 9387 9239 9226 -f 9226 9239 9228 -f 9226 9228 9225 -f 9225 9228 9240 -f 9225 9240 9223 -f 9223 9240 9218 -f 9223 9218 9221 -f 9221 9218 9219 -f 9221 9219 9217 -f 9239 9387 9245 -f 9245 9387 9377 -f 9174 9241 9242 -f 9242 9241 9227 -f 9242 9227 9243 -f 9243 9227 9244 -f 9243 9244 9231 -f 9231 9244 9245 -f 9231 9245 9232 -f 9232 9245 9377 -f 9232 9377 9382 -f 9232 9382 9234 -f 9234 9382 9383 -f 9383 9237 9234 -f 9234 9237 9236 -f 9234 9236 9233 -f 9233 9236 9246 -f 9233 9246 9230 -f 9230 9246 9247 -f 9230 9247 9229 -f 9229 9247 9171 -f 9229 9171 9175 -f 9383 9378 9237 -f 9237 9378 9253 -f 9253 9378 9379 -f 9172 9248 9249 -f 9249 9248 9235 -f 9249 9235 9250 -f 9250 9235 9252 -f 9250 9252 9251 -f 9251 9252 9253 -f 9251 9253 9254 -f 9254 9253 9379 -f 9254 9379 9255 -f 9257 9369 9256 -f 9257 9256 9258 -f 9257 9258 9270 -f 9270 9258 9259 -f 9270 9259 9272 -f 9272 9259 9260 -f 9272 9260 9273 -f 9273 9260 9261 -f 9273 9261 9274 -f 9274 9261 8066 -f 9274 8066 9275 -f 8066 8065 9275 -f 9275 8065 9263 -f 9275 9263 9262 -f 9262 9263 9278 -f 9263 8067 9278 -f 9278 8067 9265 -f 9278 9265 9264 -f 9264 9265 9267 -f 9265 9266 9267 -f 9267 9266 8072 -f 9267 8072 9268 -f 9268 8072 9281 -f 8069 9183 9269 -f 9269 9183 9282 -f 9269 9282 9281 -f 9269 9281 8071 -f 8071 9281 8072 -f 9385 9257 9270 -f 9385 9270 9284 -f 9284 9270 9272 -f 9284 9272 9271 -f 9271 9272 9273 -f 9271 9273 9287 -f 9287 9273 9274 -f 9287 9274 9288 -f 9288 9274 9275 -f 9288 9275 9276 -f 9276 9275 9262 -f 9276 9262 9277 -f 9277 9262 9278 -f 9277 9278 9291 -f 9291 9278 9264 -f 9291 9264 9292 -f 9292 9264 9267 -f 9292 9267 9279 -f 9279 9267 9268 -f 9279 9268 9280 -f 9280 9268 9281 -f 9280 9281 9294 -f 9294 9281 9282 -f 9294 9282 9296 -f 9296 9282 9183 -f 9296 9183 9297 -f 9283 9385 9284 -f 9283 9284 9285 -f 9285 9284 9271 -f 9285 9271 9286 -f 9286 9271 9287 -f 9286 9287 9301 -f 9301 9287 9288 -f 9301 9288 9289 -f 9289 9288 9276 -f 9289 9276 9290 -f 9290 9276 9277 -f 9290 9277 9302 -f 9302 9277 9291 -f 9302 9291 9304 -f 9304 9291 9292 -f 9304 9292 9305 -f 9305 9292 9279 -f 9305 9279 9306 -f 9306 9279 9280 -f 9306 9280 9293 -f 9293 9280 9294 -f 9293 9294 9309 -f 9309 9294 9296 -f 9309 9296 9295 -f 9295 9296 9297 -f 9295 9297 9189 -f 9255 9283 9298 -f 9298 9283 9285 -f 9298 9285 9299 -f 9299 9285 9286 -f 9299 9286 9300 -f 9300 9286 9301 -f 9300 9301 7617 -f 7617 9301 9289 -f 7617 9289 7618 -f 7618 9289 9290 -f 7618 9290 7620 -f 7620 9290 9302 -f 7620 9302 9303 -f 9303 9302 9304 -f 9303 9304 7621 -f 7621 9304 9305 -f 7621 9305 7622 -f 7622 9305 9306 -f 7622 9306 9307 -f 9307 9306 9293 -f 9307 9293 9308 -f 9308 9293 9309 -f 9308 9309 7619 -f 7619 9309 9295 -f 7619 9295 9310 -f 9310 9295 9189 -f 9310 9189 8085 -f 9197 9311 9199 -f 9199 9311 9312 -f 9199 9312 9313 -f 9199 9313 9196 -f 9195 9196 8182 -f 8182 9196 9313 -f 8182 9313 9314 -f 9314 9313 9317 -f 9316 9315 9323 -f 9316 9323 9318 -f 9318 9323 9319 -f 9311 9315 9312 -f 9312 9315 9316 -f 9312 9316 9313 -f 9313 9316 9318 -f 9313 9318 9317 -f 9317 9318 9319 -f 9317 9319 9322 -f 8059 8058 9321 -f 9321 8058 9320 -f 9328 9322 9326 -f 9326 9322 9319 -f 9326 9319 9321 -f 9321 9319 9323 -f 9321 9323 8059 -f 8059 9323 9315 -f 9320 9324 9321 -f 9321 9324 9325 -f 9321 9325 9326 -f 9326 9325 9327 -f 9326 9327 9328 -f 8177 8181 9327 -f 9327 8181 8180 -f 9327 8180 9328 -f 9392 9330 8062 -f 8062 9330 9329 -f 8062 9329 9332 -f 9329 9330 9331 -f 9331 9330 9405 -f 9324 9332 9325 -f 9325 9332 9329 -f 9325 9329 9327 -f 9327 9329 9331 -f 9327 9331 8177 -f 8177 9331 9405 -f 8177 9405 9406 -f 9400 9336 9397 -f 9397 9336 9333 -f 9397 9333 9395 -f 9394 9396 9351 -f 9406 9394 9335 -f 9336 9337 9333 -f 9333 9337 9338 -f 9333 9338 9340 -f 9338 9339 9340 -f 9340 9339 9341 -f 9340 9341 9342 -f 9341 9343 9342 -f 9342 9343 9350 -f 9344 9406 9335 -f 9344 9335 9345 -f 9345 9335 9353 -f 9345 9353 8184 -f 8184 9353 9346 -f 8184 9346 8161 -f 8161 9346 9354 -f 8161 9354 8176 -f 9395 9333 9334 -f 9334 9333 9340 -f 9334 9340 9347 -f 9347 9340 9342 -f 9347 9342 9348 -f 9348 9342 9350 -f 9348 9350 9349 -f 9349 9350 9359 -f 9349 9359 9361 -f 9394 9351 9335 -f 9335 9351 9352 -f 9335 9352 9353 -f 9353 9352 9363 -f 9353 9363 9346 -f 9346 9363 9362 -f 9346 9362 9354 -f 9354 9362 9365 -f 9354 9365 9367 -f 9358 9356 9357 -f 9343 7635 9350 -f 9350 7635 7636 -f 9350 7636 9359 -f 9359 7636 9355 -f 9359 9355 9358 -f 9208 9357 9356 -f 9358 9357 9359 -f 9359 9357 9360 -f 9359 9360 9361 -f 9361 9360 9364 -f 9364 9365 9361 -f 9361 9365 9362 -f 9361 9362 9349 -f 9349 9362 9363 -f 9349 9363 9348 -f 9348 9363 9352 -f 9348 9352 9347 -f 9347 9352 9351 -f 9347 9351 9334 -f 9334 9351 9396 -f 9334 9396 9395 -f 9365 9364 9203 -f 9365 9203 9367 -f 9367 9203 9205 -f 8176 9354 9366 -f 9366 9354 9367 -f 9366 9367 8175 -f 8175 9367 9205 -f 9283 9380 9385 -f 9283 9255 9379 -f 9373 9374 9387 -f 9376 9377 9387 -f 9375 9382 9376 -f 9376 9382 9377 -f 9378 9383 9381 -f 9378 9381 9379 -f 9379 9381 9380 -f 9379 9380 9283 -f 9385 9380 9381 -f 9382 9375 9383 -f 9383 9375 9384 -f 9383 9384 9381 -f 9381 9384 9386 -f 9381 9386 9385 -f 9385 9386 9257 -f 9387 9374 9376 -f 9376 9374 9371 -f 9376 9371 9375 -f 9375 9371 9370 -f 9375 9370 9384 -f 9384 9370 9368 -f 9384 9368 9386 -f 9386 9368 9369 -f 9386 9369 9257 -f 9405 9330 9403 -f 9398 9388 9415 -f 9427 9390 9391 -f 9427 9391 9330 -f 9427 9330 9392 -f 9406 9404 9394 -f 9394 9404 9393 -f 9402 9396 9393 -f 9393 9396 9394 -f 9398 9395 9402 -f 9402 9395 9396 -f 9398 9397 9395 -f 9388 9398 9389 -f 9389 9398 9401 -f 9389 9401 9390 -f 9390 9401 9399 -f 9390 9399 9391 -f 9391 9399 9403 -f 9391 9403 9330 -f 9415 9400 9397 -f 9415 9397 9398 -f 9401 9398 9402 -f 9401 9402 9399 -f 9399 9402 9393 -f 9399 9393 9403 -f 9403 9393 9404 -f 9403 9404 9405 -f 9405 9404 9406 -f 9423 9412 9410 -f 9372 9407 9373 -f 9373 9407 9409 -f 9374 9373 9409 -f 9371 9374 9408 -f 9369 9368 9423 -f 9423 9368 9412 -f 9412 9368 9370 -f 9407 7632 9409 -f 9409 7632 9416 -f 9421 9410 9411 -f 9411 9410 9412 -f 9411 9412 9420 -f 9420 9412 9370 -f 9420 9370 9371 -f 9425 9426 9422 -f 9413 9414 9426 -f 9426 9414 8064 -f 9426 8064 9422 -f 9422 8064 9424 -f 9400 9415 7631 -f 7631 9415 9417 -f 7631 9417 9416 -f 7631 9416 7632 -f 9374 9409 9408 -f 9408 9409 9416 -f 9408 9416 9418 -f 9418 9416 9417 -f 9418 9417 9419 -f 9419 9417 9415 -f 9415 9388 9419 -f 9371 9408 9420 -f 9420 9408 9418 -f 9420 9418 9411 -f 9411 9418 9419 -f 9411 9419 9421 -f 9421 9419 9388 -f 9421 9388 9389 -f 9421 9389 9425 -f 9421 9425 9410 -f 9410 9425 9422 -f 9410 9422 9423 -f 9423 9422 9424 -f 9423 9424 9369 -f 9389 9390 9425 -f 9425 9390 9426 -f 9426 9390 9427 -f 9426 9427 9413 -f 9413 9427 9392 -f 8135 9436 8029 -f 9429 7593 9428 -f 9436 8135 9440 -f 9430 7593 9429 -f 7593 9441 9428 -f 8122 7593 9430 -f 8132 8127 9443 -f 8118 8119 9432 -f 8122 9432 7593 -f 7611 9433 7608 -f 8119 9431 9432 -f 7614 9433 7611 -f 7608 9431 7611 -f 8131 9440 8134 -f 9442 9434 8077 -f 8037 8031 8029 -f 7607 7604 7608 -f 9436 9435 9437 -f 8037 8029 9438 -f 8135 8134 9440 -f 9447 9439 9449 -f 9431 8119 7611 -f 9436 9438 8029 -f 8131 8132 9443 -f 9436 9437 9438 -f 8127 8125 9443 -f 9432 8122 8118 -f 9449 9439 8114 -f 9440 8131 9443 -f 7595 9441 7593 -f 9443 8125 8048 -f 7597 9441 7595 -f 8125 9441 8048 -f 9441 8125 9428 -f 8026 8024 8048 -f 8048 9441 9446 -f 8048 9446 9447 -f 9447 8092 8087 -f 8099 9444 9446 -f 8078 9446 9442 -f 8105 8099 9446 -f 9446 8082 9442 -f 8078 9442 8077 -f 8078 8103 9446 -f 8024 9443 8048 -f 8105 9446 8103 -f 9447 9444 9464 -f 9445 9449 8114 -f 9444 9447 9446 -f 8087 9439 9447 -f 7608 7604 9431 -f 8092 9447 9448 -f 8110 9447 9449 -f 9450 1856 1872 -f 1953 9452 1819 -f 1834 9455 1835 -f 9476 9480 1965 -f 1955 1954 9460 -f 9452 1953 1950 -f 9451 9452 1950 -f 1814 1810 1838 -f 1835 1838 1836 -f 1953 9607 148 -f 1810 1836 1838 -f 154 148 9454 -f 148 9607 9454 -f 1862 1859 9602 -f 9600 9475 9598 -f 145 1953 148 -f 1831 9455 1834 -f 9455 9491 1853 -f 1829 9587 1831 -f 1954 9451 1950 -f 1838 1835 1853 -f 1842 1841 9456 -f 9457 9598 9475 -f 9491 1852 1853 -f 9458 9459 9460 -f 1823 9452 9451 -f 1844 9468 9473 -f 1849 1854 1852 -f 9458 1952 9459 -f 9461 1857 9602 -f 1954 1950 9460 -f 9462 1947 1948 -f 1949 1948 9465 -f 1840 9474 9466 -f 1840 9466 9456 -f 9482 9463 9483 -f 9448 9447 9464 -f 9474 1843 9466 -f 1810 1808 9583 -f 1946 9467 9609 -f 9474 9468 1843 -f 1862 9602 1857 -f 9469 9453 9603 -f 9467 1945 9470 -f 1829 1827 9587 -f 9474 1855 1846 -f 1949 9467 9470 -f 9471 9472 1956 -f 9597 9468 1844 -f 9471 1949 9472 -f 9473 9474 1846 -f 9459 1955 9460 -f 1846 1855 1847 -f 1952 9471 1956 -f 1849 1847 1854 -f 1952 1956 9459 -f 1949 9470 9472 -f 1825 9451 9546 -f 1870 9478 1871 -f 1962 9457 9475 -f 2098 1962 9475 -f 1825 1823 9451 -f 9479 9476 1965 -f 9478 1870 9593 -f 1862 9450 1863 -f 2100 9463 9477 -f 9478 9595 1871 -f 9592 9476 2100 -f 9578 7325 9579 -f 9479 1965 1964 -f 1870 1869 9593 -f 9463 1966 9477 -f 9477 9592 2100 -f 9482 9487 1868 -f 1869 1868 9487 -f 9468 9481 1843 -f 9466 1842 9456 -f 9482 1966 9463 -f 1948 1947 9465 -f 2060 9482 9483 -f 9483 9486 2060 -f 9483 9484 9486 -f 9484 1784 9486 -f 1797 9485 9484 -f 1784 9488 9486 -f 9485 1784 9484 -f 9488 161 9486 -f 166 161 9488 -f 1837 1794 9485 -f 1774 1763 9488 -f 1781 1774 9488 -f 1837 172 9489 -f 1763 1774 9506 -f 1768 1767 9493 -f 9489 170 169 -f 9493 9490 1763 -f 1837 9489 9495 -f 1849 1852 9491 -f 9492 9493 1763 -f 2611 9494 2224 -f 1795 1837 9495 -f 9587 9455 1831 -f 1797 1801 9485 -f 1794 1837 1795 -f 9485 1782 1784 -f 9485 1794 1789 -f 1785 1781 9488 -f 9485 1789 1782 -f 1784 1785 9488 -f 9504 2341 2682 -f 2682 2675 2316 -f 5257 9512 9496 -f 2270 2356 2358 -f 9496 2361 5257 -f 2270 9497 2356 -f 2361 9498 5257 -f 9509 2652 2358 -f 2270 2355 9497 -f 9499 9514 2349 -f 9500 2349 2353 -f 2353 2349 9501 -f 2349 5256 9501 -f 2665 9502 9521 -f 9504 2682 2342 -f 2342 9503 9504 -f 2328 2652 9511 -f 2341 2355 2682 -f 9516 9505 4372 -f 7032 7016 9519 -f 1763 9506 9492 -f 9507 9510 5256 -f 2270 2682 2355 -f 9507 5256 5257 -f 9498 9507 5257 -f 9508 9512 5257 -f 9522 9521 7016 -f 9512 9509 9496 -f 9508 2275 9512 -f 9512 2652 9509 -f 5256 9510 9501 -f 2326 2328 9511 -f 2275 2281 9512 -f 2652 2328 2270 -f 9515 2682 2316 -f 2665 2652 9502 -f 9518 4924 7021 -f 9523 2665 9521 -f 9513 4323 2605 -f 7020 7000 7016 -f 9523 9513 2605 -f 4323 2221 2605 -f 2605 9520 4367 -f 2652 2270 2358 -f 2605 4367 9505 -f 9519 9518 7021 -f 2652 9512 9502 -f 2349 9514 5256 -f 2682 9515 2342 -f 7000 9522 7016 -f 9516 2605 9505 -f 9517 7016 7032 -f 7016 9518 9519 -f 7020 7016 9517 -f 2605 2221 9520 -f 4372 4365 9516 -f 1835 9455 1853 -f 9523 9521 4338 -f 9521 9522 9584 -f 9513 9523 4338 -f 5879 5032 5157 -f 9533 9524 2250 -f 9569 9533 2249 -f 3289 9525 2229 -f 2248 9570 9569 -f 9534 2250 5169 -f 9526 9527 9528 -f 2250 9524 9529 -f 2263 9527 2266 -f 9526 9530 2266 -f 9611 4751 2612 -f 9531 4930 9532 -f 9610 2603 2601 -f 9534 9531 9532 -f 2229 9526 9528 -f 2249 9533 2250 -f 2248 9569 2249 -f 5177 9534 5169 -f 2229 9528 9535 -f 5177 9531 9534 -f 9580 3282 3283 -f 2503 3288 9535 -f 9561 3292 9562 -f 2504 3288 2503 -f 9536 9549 2504 -f 9567 9549 9536 -f 5870 9551 9529 -f 3288 3289 9535 -f 3289 2229 9535 -f 3277 9540 3259 -f 5159 9537 5871 -f 5158 5159 5871 -f 9548 5876 5157 -f 9580 3259 9539 -f 3261 3277 3259 -f 9580 9539 9542 -f 9538 5879 5157 -f 5032 5879 5880 -f 5849 5032 5880 -f 9539 3259 9540 -f 5880 9543 5849 -f 9547 3277 3261 -f 5876 9541 5157 -f 2501 9580 9544 -f 9580 9542 3282 -f 5880 5863 9543 -f 5169 2250 9529 -f 2502 2501 9544 -f 9577 9545 2611 -f 5863 5846 9543 -f 1827 1825 9546 -f 9547 3276 3277 -f 9538 5157 5878 -f 9568 9544 9550 -f 5878 5157 9541 -f 9548 5158 5871 -f 9568 2502 9544 -f 5876 9548 5871 -f 9549 3286 2504 -f 9549 9567 9550 -f 5871 9537 9552 -f 3286 3288 2504 -f 9537 9551 9552 -f 9524 5870 9529 -f 9551 5870 9552 -f 3228 9525 3289 -f 9566 2251 9553 -f 9527 9526 2266 -f 9524 9565 5868 -f 9556 5815 5820 -f 5868 9563 5866 -f 9558 9560 9562 -f 9562 3273 9558 -f 3273 3274 3240 -f 3273 3240 9555 -f 9525 9553 2229 -f 5815 9556 5866 -f 9532 9557 9534 -f 9554 9556 5820 -f 9564 5815 5866 -f 9558 3273 9559 -f 9559 3273 9555 -f 9560 9561 9562 -f 9563 9564 5866 -f 9561 3228 3292 -f 3228 3289 3292 -f 9533 9565 9524 -f 9565 9563 5868 -f 9525 9566 9553 -f 9570 2251 9566 -f 9567 9568 9550 -f 9569 9570 9566 -f 9566 5812 9569 -f 9566 3232 5812 -f 3232 9572 5812 -f 3232 9571 9572 -f 9571 9573 9572 -f 9571 9575 9573 -f 9575 9574 9573 -f 9575 9576 9574 -f 9576 4347 9574 -f 9576 2611 9585 -f 9576 9577 2611 -f 9574 4347 9579 -f 9582 9578 9579 -f 9579 5811 9581 -f 9579 1797 5811 -f 9545 161 2611 -f 9554 5860 9556 -f 9581 9574 9579 -f 1855 1854 1847 -f 2612 4751 2611 -f 7396 7400 9579 -f 7325 7396 9579 -f 2603 9610 2612 -f 7400 5196 9579 -f 9580 3283 9544 -f 2611 2224 4346 -f 1860 9608 1861 -f 1958 9475 9600 -f 2611 4346 9585 -f 1861 1859 1862 -f 9582 9579 4347 -f 9468 9474 9473 -f 1806 1836 9583 -f 4338 9521 9584 -f 4347 9576 9585 -f 7385 5192 5196 -f 5195 5811 1797 -f 161 9545 9586 -f 9579 5195 1797 -f 161 9586 2611 -f 9587 1827 9546 -f 9546 1851 9587 -f 9546 1942 1851 -f 1942 9588 1851 -f 1942 126 9588 -f 126 1865 9588 -f 126 9589 1865 -f 9589 1867 1865 -f 9589 1966 1867 -f 1966 9482 1867 -f 5192 9590 5196 -f 1867 9482 1868 -f 9593 1869 9487 -f 9591 9590 5190 -f 5190 9590 5192 -f 9592 9480 9476 -f 9594 9479 1964 -f 2098 9594 1964 -f 9595 1872 1871 -f 1964 1962 2098 -f 9595 9450 1872 -f 9469 9603 9457 -f 1857 1856 9450 -f 1836 1810 9583 -f 2603 2602 2601 -f 9450 1862 1857 -f 9489 169 9495 -f 9596 1857 9461 -f 9492 1768 9493 -f 9457 9603 9598 -f 1858 9461 9602 -f 9609 1949 9465 -f 9603 1959 9598 -f 9599 9600 9598 -f 9601 9602 1859 -f 9453 1960 9603 -f 9598 9604 9605 -f 9605 9599 9598 -f 9606 1859 9608 -f 7400 7385 5196 -f 1953 1819 9607 -f 1861 9608 1859 -f 9467 1949 9609 -f 9610 9611 2612 -f 4751 9612 2611 -f 9690 9619 9617 -f 9619 9690 9660 -f 9688 9614 9613 -f 9703 9694 9701 -f 9664 9614 9688 -f 9701 9694 9616 -f 9613 9660 9688 -f 9660 9690 9688 -f 9664 9688 9687 -f 9616 9694 9692 -f 9641 9615 9697 -f 9615 9692 9697 -f 9615 9616 9692 -f 9699 9700 9687 -f 9703 9695 9694 -f 9687 9617 9699 -f 9700 9664 9687 -f 9668 9667 9617 -f 9699 9617 9665 -f 9617 9667 9665 -f 9684 9683 9682 -f 9684 9682 9703 -f 9682 9695 9703 -f 9682 9625 9695 -f 9641 9695 9643 -f 9697 9695 9641 -f 9668 9620 9618 -f 9619 9668 9617 -f 9619 9620 9668 -f 9655 9654 9671 -f 9654 9651 9671 -f 9618 9669 9668 -f 9618 9655 9669 -f 9655 9670 9669 -f 9655 9671 9670 -f 9695 9644 9643 -f 9695 9625 9644 -f 9625 9621 9644 -f 9671 9651 9672 -f 9651 9622 9672 -f 9651 9648 9622 -f 9622 9648 9674 -f 9648 9647 9674 -f 9647 9677 9674 -f 9647 9623 9677 -f 9623 9678 9677 -f 9623 9679 9678 -f 9623 9624 9679 -f 9624 9625 9679 -f 9624 9621 9625 -f 9691 9663 9689 -f 9698 9686 9628 -f 9693 9642 9696 -f 9642 9626 9696 -f 9638 9702 9627 -f 9661 9663 9691 -f 9663 9662 9689 -f 9628 9686 9689 -f 9626 9638 9696 -f 9627 9685 9693 -f 9698 9632 9686 -f 9638 9704 9702 -f 9693 9685 9642 -f 9662 9628 9689 -f 9632 9698 9630 -f 9632 9666 9629 -f 9632 9630 9666 -f 9638 9681 9631 -f 9638 9631 9704 -f 9631 9683 9704 -f 9691 9632 9661 -f 9632 9659 9661 -f 9632 9658 9659 -f 9632 9629 9658 -f 9629 9657 9658 -f 9652 9653 9636 -f 9629 9656 9657 -f 9629 9633 9656 -f 9633 9634 9656 -f 9634 9653 9656 -f 9634 9635 9653 -f 9635 9636 9653 -f 9649 9650 9675 -f 9650 9673 9675 -f 9650 9652 9673 -f 9652 9636 9673 -f 9646 9649 9640 -f 9649 9676 9640 -f 9649 9675 9676 -f 9637 9639 9681 -f 9681 9645 9637 -f 9638 9645 9681 -f 9638 9626 9645 -f 9639 9680 9681 -f 9639 9646 9680 -f 9646 9640 9680 -f 9615 9641 9642 -f 9641 9626 9642 -f 9641 9643 9626 -f 9643 9645 9626 -f 9643 9644 9645 -f 9644 9637 9645 -f 9644 9621 9637 -f 9621 9624 9637 -f 9624 9639 9637 -f 9624 9623 9639 -f 9623 9646 9639 -f 9623 9647 9646 -f 9647 9649 9646 -f 9647 9648 9649 -f 9648 9650 9649 -f 9648 9651 9650 -f 9651 9652 9650 -f 9651 9654 9652 -f 9654 9653 9652 -f 9654 9655 9653 -f 9655 9656 9653 -f 9655 9618 9656 -f 9618 9657 9656 -f 9618 9620 9657 -f 9620 9658 9657 -f 9620 9619 9658 -f 9619 9659 9658 -f 9619 9660 9659 -f 9660 9661 9659 -f 9660 9613 9661 -f 9613 9663 9661 -f 9614 9662 9613 -f 9662 9663 9613 -f 9614 9628 9662 -f 9614 9664 9628 -f 9664 9698 9628 -f 9664 9700 9698 -f 9699 9698 9700 -f 9665 9666 9630 -f 9665 9629 9666 -f 9665 9667 9629 -f 9667 9668 9629 -f 9668 9633 9629 -f 9668 9669 9633 -f 9669 9634 9633 -f 9669 9670 9634 -f 9670 9635 9634 -f 9670 9671 9635 -f 9671 9636 9635 -f 9671 9672 9636 -f 9672 9673 9636 -f 9672 9622 9673 -f 9622 9675 9673 -f 9622 9674 9675 -f 9674 9676 9675 -f 9674 9677 9676 -f 9677 9640 9676 -f 9677 9678 9640 -f 9678 9680 9640 -f 9678 9679 9680 -f 9679 9681 9680 -f 9679 9625 9681 -f 9625 9631 9681 -f 9625 9682 9631 -f 9682 9683 9631 -f 9684 9704 9683 -f 9684 9703 9704 -f 9701 9702 9703 -f 9702 9704 9703 -f 9701 9627 9702 -f 9701 9616 9627 -f 9616 9685 9627 -f 9615 9642 9616 -f 9642 9685 9616 -f 9687 9689 9686 -f 9687 9688 9689 -f 9688 9691 9689 -f 9688 9690 9691 -f 9690 9617 9691 -f 9617 9632 9691 -f 9617 9687 9632 -f 9687 9686 9632 -f 9692 9627 9693 -f 9692 9694 9627 -f 9694 9638 9627 -f 9694 9695 9638 -f 9695 9697 9638 -f 9697 9696 9638 -f 9697 9692 9696 -f 9692 9693 9696 -f 9699 9630 9698 -f 9699 9665 9630 -f 9717 9828 9829 -f 9717 9705 9828 -f 9705 9706 9828 -f 9705 9719 9706 -f 9719 9708 9706 -f 9719 9707 9708 -f 9707 9826 9708 -f 9707 9721 9826 -f 9721 9827 9826 -f 9721 9709 9827 -f 9721 9710 9709 -f 9710 9711 9709 -f 9710 9712 9711 -f 9710 9722 9712 -f 9722 9825 9712 -f 9722 9723 9825 -f 9825 9723 9823 -f 9723 9725 9823 -f 9725 9822 9823 -f 9725 9726 9822 -f 9726 9821 9822 -f 9726 9727 9821 -f 9727 9820 9821 -f 9727 9819 9820 -f 9727 9728 9819 -f 9728 9713 9819 -f 9713 9832 9819 -f 9713 9830 9832 -f 9713 9716 9830 -f 9716 9857 9830 -f 9716 9854 9857 -f 9716 9717 9854 -f 9717 9829 9854 -f 9714 9713 9728 -f 9714 9715 9713 -f 9715 9716 9713 -f 9715 9737 9716 -f 9737 9717 9716 -f 9737 9718 9717 -f 9718 9738 9717 -f 9738 9705 9717 -f 9738 9731 9705 -f 9731 9719 9705 -f 9731 9736 9719 -f 9736 9707 9719 -f 9736 9720 9707 -f 9720 9721 9707 -f 9720 9765 9721 -f 9765 9735 9721 -f 9735 9734 9721 -f 9734 9710 9721 -f 9734 9767 9710 -f 9767 9722 9710 -f 9767 9730 9722 -f 9730 9723 9722 -f 9730 9724 9723 -f 9724 9725 9723 -f 9724 9733 9725 -f 9733 9726 9725 -f 9733 9732 9726 -f 9732 9727 9726 -f 9732 9729 9727 -f 9729 9714 9727 -f 9714 9728 9727 -f 9714 9729 9732 -f 9730 9767 9761 -f 9736 9731 9765 -f 9733 9724 9766 -f 9734 9735 9765 -f 9720 9736 9765 -f 9737 9715 9762 -f 9715 9714 9762 -f 9739 9775 9755 -f 9775 9749 9755 -f 9775 9788 9749 -f 9772 9773 9742 -f 9773 9745 9742 -f 9745 9780 9746 -f 9780 9783 9746 -f 9783 9747 9746 -f 9783 9740 9747 -f 9739 9755 9748 -f 9790 9770 9741 -f 9770 9754 9741 -f 9770 9771 9754 -f 9742 9745 9743 -f 9790 9741 9744 -f 9739 9748 9740 -f 9742 9743 9751 -f 9747 9740 9748 -f 9755 9749 9753 -f 9744 9750 9752 -f 9744 9741 9750 -f 9771 9742 9754 -f 9749 9752 9753 -f 9749 9744 9752 -f 9750 9741 9766 -f 9741 9754 9766 -f 9745 9746 9759 -f 9754 9742 9751 -f 9743 9745 9762 -f 9759 9746 9760 -f 9746 9747 9760 -f 9762 9745 9759 -f 9751 9743 9756 -f 9743 9762 9756 -f 9748 9755 9758 -f 9752 9757 9753 -f 9754 9751 9766 -f 9747 9748 9764 -f 9752 9750 9761 -f 9750 9768 9761 -f 9750 9766 9768 -f 9748 9758 9764 -f 9755 9763 9758 -f 9755 9753 9763 -f 9763 9753 9757 -f 9747 9764 9760 -f 9757 9752 9761 -f 9760 9764 9738 -f 9751 9756 9732 -f 9759 9760 9718 -f 9760 9738 9718 -f 9738 9764 9731 -f 9764 9758 9731 -f 9758 9765 9731 -f 9758 9763 9765 -f 9763 9757 9765 -f 9757 9761 9767 -f 9766 9732 9733 -f 9766 9751 9732 -f 9756 9762 9714 -f 9759 9737 9762 -f 9759 9718 9737 -f 9757 9734 9765 -f 9757 9767 9734 -f 9761 9768 9730 -f 9768 9724 9730 -f 9768 9766 9724 -f 9756 9714 9732 -f 9789 9744 9749 -f 9789 9769 9744 -f 9769 9790 9744 -f 9791 9770 9790 -f 9788 9789 9749 -f 9770 9792 9771 -f 9792 9772 9771 -f 9772 9742 9771 -f 9776 9739 9740 -f 9776 9774 9739 -f 9782 9783 9780 -f 9773 9777 9745 -f 9777 9778 9745 -f 9783 9776 9740 -f 9778 9779 9745 -f 9779 9780 9745 -f 9793 9876 9773 -f 9876 9777 9773 -f 9876 9875 9777 -f 9875 9778 9777 -f 9875 9873 9778 -f 9873 9779 9778 -f 9873 9871 9779 -f 9871 9780 9779 -f 9871 9781 9780 -f 9781 9782 9780 -f 9781 9874 9782 -f 9874 9783 9782 -f 9874 9784 9783 -f 9784 9776 9783 -f 9784 9785 9776 -f 9785 9774 9776 -f 9785 9870 9774 -f 9870 9739 9774 -f 9870 9775 9739 -f 9870 9786 9775 -f 9786 9788 9775 -f 9786 9787 9788 -f 9787 9789 9788 -f 9787 9865 9789 -f 9865 9864 9789 -f 9864 9769 9789 -f 9864 9863 9769 -f 9863 9790 9769 -f 9863 9867 9790 -f 9867 9791 9790 -f 9867 9770 9791 -f 9867 9868 9770 -f 9868 9866 9770 -f 9866 9792 9770 -f 9866 9772 9792 -f 9866 9862 9772 -f 9862 9793 9772 -f 9793 9773 9772 -f 9802 9844 9974 -f 9802 9976 9844 -f 9976 9848 9844 -f 9976 9794 9848 -f 9794 9835 9848 -f 9794 9977 9835 -f 9977 9795 9835 -f 9977 9966 9795 -f 9966 9796 9795 -f 9796 9842 9795 -f 9796 9980 9842 -f 9980 9834 9842 -f 9980 9797 9834 -f 9797 9833 9834 -f 9797 9845 9833 -f 9797 9967 9845 -f 9975 9846 9967 -f 9975 9840 9846 -f 9979 9798 9840 -f 9979 9978 9798 -f 9978 9799 9798 -f 9978 9839 9799 -f 9978 9968 9839 -f 9968 9838 9839 -f 9968 9973 9838 -f 9973 9841 9838 -f 9973 9969 9841 -f 9837 9970 9836 -f 9970 9800 9836 -f 9970 9972 9800 -f 9972 9843 9800 -f 9972 9971 9843 -f 9971 9847 9843 -f 9801 9974 9847 -f 9803 9842 9834 -f 9803 9795 9842 -f 9815 9835 9795 -f 9803 9845 9846 -f 9803 9833 9845 -f 9803 9834 9833 -f 9811 9838 9841 -f 9838 9811 9839 -f 9811 9799 9839 -f 9811 9846 9799 -f 9846 9798 9799 -f 9812 9843 9847 -f 9812 9836 9843 -f 9836 9800 9843 -f 9811 9841 9836 -f 9835 9815 9848 -f 9815 9816 9848 -f 9816 9844 9848 -f 9851 9805 9811 -f 9856 9859 9849 -f 9856 9813 9859 -f 9853 9809 9804 -f 9853 9852 9809 -f 9852 9811 9809 -f 9852 9851 9811 -f 9808 9806 9814 -f 9831 9812 9817 -f 9831 9804 9812 -f 9804 9809 9812 -f 9859 9810 9807 -f 9808 9814 9805 -f 9807 9803 9806 -f 9807 9810 9803 -f 9813 9815 9859 -f 9817 9816 9813 -f 9859 9815 9810 -f 9816 9817 9812 -f 9805 9814 9846 -f 9813 9816 9815 -f 9809 9836 9812 -f 9805 9846 9811 -f 9814 9806 9846 -f 9806 9803 9846 -f 9812 9847 9816 -f 9810 9815 9795 -f 9809 9811 9836 -f 9810 9795 9803 -f 9807 9855 9861 -f 9807 9806 9855 -f 9806 9808 9855 -f 9807 9861 9859 -f 9808 9805 9858 -f 9805 9850 9858 -f 9805 9851 9850 -f 9817 9860 9831 -f 9813 9856 9817 -f 9820 9819 9856 -f 9819 9818 9856 -f 9821 9820 9849 -f 9820 9856 9849 -f 9822 9821 9849 -f 9849 9824 9822 -f 9824 9823 9822 -f 9823 9824 9861 -f 9825 9823 9861 -f 9855 9712 9825 -f 9711 9712 9808 -f 9808 9709 9711 -f 9709 9808 9858 -f 9827 9709 9858 -f 9827 9858 9850 -f 9826 9827 9850 -f 9850 9851 9826 -f 9851 9708 9826 -f 9706 9708 9852 -f 9708 9851 9852 -f 9706 9853 9828 -f 9829 9828 9853 -f 9829 9853 9804 -f 9854 9829 9804 -f 9830 9857 9831 -f 9831 9860 9830 -f 9860 9832 9830 -f 9819 9832 9818 -f 9832 9860 9818 -f 9836 9969 9837 -f 9969 9836 9841 -f 9847 9974 9816 -f 9840 9798 9846 -f 9816 9974 9844 -f 9967 9846 9845 -f 9861 9855 9825 -f 9712 9855 9808 -f 9853 9706 9852 -f 9818 9860 9817 -f 9857 9854 9831 -f 9854 9804 9831 -f 9861 9824 9859 -f 9824 9849 9859 -f 9818 9817 9856 -f 9793 9862 9903 -f 9862 9866 9903 -f 9863 9864 9900 -f 9864 9865 9900 -f 9785 9784 9904 -f 9866 9868 9902 -f 9781 9871 9872 -f 9787 9786 9869 -f 9786 9870 9869 -f 9870 9785 9904 -f 9871 9873 9872 -f 9876 9793 9903 -f 9784 9874 9904 -f 9876 9903 9875 -f 9918 9885 9881 -f 9918 9910 9885 -f 9910 9882 9885 -f 9913 9877 9882 -f 9913 9915 9877 -f 9915 9919 9877 -f 9919 9911 9877 -f 9911 9894 9877 -f 9911 9912 9894 -f 9912 9878 9894 -f 9909 9880 9891 -f 9916 9881 9880 -f 9907 9891 9884 -f 9891 9880 9893 -f 9893 9880 9881 -f 9894 9878 9896 -f 9878 9879 9896 -f 9879 9883 9887 -f 9883 9884 9889 -f 9882 9886 9885 -f 9879 9887 9896 -f 9887 9883 9889 -f 9882 9877 9888 -f 9877 9894 9890 -f 9901 9884 9897 -f 9882 9888 9886 -f 9877 9890 9888 -f 9889 9884 9901 -f 9884 9891 9897 -f 9889 9901 9900 -f 9894 9896 9892 -f 9891 9893 9897 -f 9893 9881 9895 -f 9895 9881 9898 -f 9881 9885 9898 -f 9894 9892 9890 -f 9887 9899 9896 -f 9893 9895 9897 -f 9885 9886 9898 -f 9886 9872 9898 -f 9886 9888 9872 -f 9888 9890 9904 -f 9887 9889 9899 -f 9889 9900 9899 -f 9890 9892 9904 -f 9892 9896 9869 -f 9896 9899 9869 -f 9901 9897 9902 -f 9902 9897 9903 -f 9895 9898 9903 -f 9897 9895 9903 -f 9901 9868 9900 -f 9901 9902 9868 -f 9903 9898 9875 -f 9872 9888 9874 -f 9888 9904 9874 -f 9892 9869 9904 -f 9869 9899 9787 -f 9875 9898 9873 -f 9898 9872 9873 -f 9872 9874 9781 -f 9904 9869 9870 -f 9787 9899 9865 -f 9899 9900 9865 -f 9900 9867 9863 -f 9900 9868 9867 -f 9902 9903 9866 -f 9906 9905 9883 -f 9905 9923 9883 -f 9923 9884 9883 -f 9923 9924 9884 -f 9924 9907 9884 -f 9906 9883 9879 -f 9907 9908 9891 -f 9908 9909 9891 -f 9910 9913 9882 -f 9912 9914 9878 -f 9879 9878 9914 -f 9916 9918 9881 -f 9926 9990 9916 -f 9990 9918 9916 -f 9990 9917 9918 -f 9917 9910 9918 -f 9917 9984 9910 -f 9984 9913 9910 -f 9984 9989 9913 -f 9989 10012 9913 -f 10012 9915 9913 -f 10012 9920 9915 -f 9920 9919 9915 -f 9920 9988 9919 -f 9988 9911 9919 -f 9988 9912 9911 -f 9988 9987 9912 -f 9987 9921 9912 -f 9921 9914 9912 -f 9921 9986 9914 -f 9986 9879 9914 -f 9986 9985 9879 -f 9985 9906 9879 -f 9985 9922 9906 -f 9922 9905 9906 -f 9922 10016 9905 -f 10016 9923 9905 -f 10016 9981 9923 -f 9981 9924 9923 -f 9981 9983 9924 -f 9983 9907 9924 -f 9983 9982 9907 -f 9982 9908 9907 -f 9982 9925 9908 -f 9925 9909 9908 -f 9925 9880 9909 -f 9925 9926 9880 -f 9926 9916 9880 -f 10094 9947 9927 -f 10094 9928 9947 -f 9928 9955 9947 -f 9928 10090 9955 -f 10090 9946 9955 -f 10090 10095 9946 -f 10095 9954 9946 -f 10095 10096 9954 -f 10096 9963 9954 -f 10096 9929 9963 -f 9930 9961 9929 -f 9930 9965 9961 -f 10091 9953 9965 -f 10091 10087 9953 -f 10087 9931 9953 -f 10089 9960 9931 -f 10071 9959 9960 -f 9932 10093 9933 -f 10093 9964 9933 -f 10088 9958 9964 -f 10088 10072 9958 -f 10072 9934 9958 -f 10072 9935 9934 -f 9935 9957 9934 -f 9935 9936 9957 -f 9936 9962 9957 -f 9936 10092 9962 -f 10092 9956 9962 -f 10092 9927 9956 -f 9961 9946 9963 -f 9949 9953 9931 -f 9949 9959 9944 -f 9948 9942 9957 -f 9942 9934 9957 -f 9942 9958 9934 -f 9942 9944 9958 -f 9946 9950 9955 -f 9950 9947 9955 -f 9947 9948 9956 -f 9971 9937 9940 -f 9973 9938 9941 -f 9952 9797 9945 -f 9797 9943 9945 -f 9797 9951 9943 -f 9939 9950 9951 -f 9939 9940 9950 -f 9940 9937 9948 -f 9941 9942 9937 -f 9938 9952 9944 -f 9952 9949 9944 -f 9941 9938 9944 -f 9937 9942 9948 -f 9952 9945 9949 -f 9940 9948 9950 -f 9941 9944 9942 -f 9951 9961 9943 -f 9951 9946 9961 -f 9943 9961 9945 -f 9950 9946 9951 -f 9948 9947 9950 -f 9945 9953 9949 -f 9945 9965 9953 -f 9945 9961 9965 -f 9951 9797 9980 -f 9952 9975 9797 -f 9952 9979 9975 -f 9939 9966 9977 -f 9939 9951 9966 -f 9951 9796 9966 -f 9951 9980 9796 -f 9952 9978 9979 -f 9952 9938 9978 -f 9938 9968 9978 -f 9938 9973 9968 -f 9940 9801 9971 -f 9939 9976 9940 -f 9941 9937 9970 -f 9937 9972 9970 -f 9937 9971 9972 -f 9962 9956 9948 -f 9954 9963 9946 -f 9931 9960 9949 -f 9959 9932 9944 -f 9932 9933 9944 -f 9933 9964 9944 -f 9964 9958 9944 -f 9957 9962 9948 -f 9929 9961 9963 -f 9960 9959 9949 -f 9927 9947 9956 -f 9801 9847 9971 -f 9802 9974 9940 -f 9974 9801 9940 -f 9837 9941 9970 -f 9837 9969 9941 -f 9840 9975 9979 -f 9967 9797 9975 -f 9794 9976 9939 -f 9976 9802 9940 -f 9941 9969 9973 -f 9977 9794 9939 -f 9988 10013 10009 -f 9988 9920 10013 -f 9925 9982 10017 -f 9922 9985 10016 -f 9982 9983 10002 -f 9983 9981 10002 -f 10016 9985 10014 -f 9985 9986 10014 -f 9921 10009 9986 -f 9921 9987 10009 -f 9988 10009 9987 -f 9989 9984 10012 -f 9917 10010 9984 -f 9990 9926 10015 -f 9926 9925 10015 -f 9920 10012 10013 -f 9917 9990 10010 -f 10028 10004 9993 -f 10028 9991 10004 -f 9991 10027 10029 -f 10029 10026 9998 -f 10026 10021 9998 -f 10022 9995 10021 -f 10024 10019 9995 -f 9992 10036 10001 -f 10041 9994 10042 -f 10044 9993 9994 -f 10036 10039 10001 -f 10039 10042 10001 -f 9991 10029 10005 -f 10029 9998 10005 -f 9995 10019 10003 -f 10019 9992 10003 -f 9991 10005 10004 -f 10042 9997 10001 -f 10042 9994 9997 -f 9998 10021 10000 -f 9994 9993 9999 -f 10021 10006 10000 -f 9994 9999 9997 -f 9993 10004 9996 -f 10021 9995 10006 -f 9999 9993 9996 -f 9995 10014 10006 -f 9995 10003 10014 -f 10003 9992 10007 -f 9992 10001 10007 -f 9997 10002 10008 -f 10001 9997 10008 -f 9997 9999 10002 -f 10005 9998 10011 -f 9998 10013 10011 -f 10007 10001 10008 -f 10004 10010 9996 -f 10004 10005 10010 -f 9998 10000 10013 -f 10006 10014 10009 -f 9999 9996 10015 -f 10000 10006 10013 -f 10003 10007 10014 -f 10002 9999 10017 -f 9996 10010 10015 -f 10005 10011 10010 -f 9999 10015 10017 -f 10011 10013 10012 -f 10006 10009 10013 -f 10007 10008 10016 -f 10010 10011 9984 -f 10007 10016 10014 -f 9984 10011 10012 -f 10016 10008 9981 -f 10008 10002 9981 -f 10015 10010 9990 -f 10009 10014 9986 -f 10002 10017 9982 -f 10017 10015 9925 -f 10035 10036 9992 -f 10035 9992 10019 -f 10041 10018 9994 -f 10018 10044 9994 -f 10044 10025 9993 -f 10020 10022 10021 -f 10022 10023 9995 -f 10023 10024 9995 -f 10025 10028 9993 -f 10020 10021 10026 -f 10115 10116 10025 -f 10116 10028 10025 -f 10116 9991 10028 -f 10116 10117 9991 -f 10117 10027 9991 -f 10117 10118 10027 -f 10118 10119 10027 -f 10119 10029 10027 -f 10119 10030 10029 -f 10030 10026 10029 -f 10030 10020 10026 -f 10030 10031 10020 -f 10031 10113 10020 -f 10113 10022 10020 -f 10113 10023 10022 -f 10113 10032 10023 -f 10032 10024 10023 -f 10032 10111 10024 -f 10111 10019 10024 -f 10111 10033 10019 -f 10033 10035 10019 -f 10033 10034 10035 -f 10034 10037 10035 -f 10037 10036 10035 -f 10037 10038 10036 -f 10038 10039 10036 -f 10038 10040 10039 -f 10038 10108 10040 -f 10108 10039 10040 -f 10108 10042 10039 -f 10108 10043 10042 -f 10043 10041 10042 -f 10043 10109 10041 -f 10109 10018 10041 -f 10109 10112 10018 -f 10112 10044 10018 -f 10112 10110 10044 -f 10110 10025 10044 -f 10110 10115 10025 -f 10114 10045 10046 -f 10045 10074 10046 -f 10045 10083 10074 -f 10097 10047 10083 -f 10097 10098 10047 -f 10098 10085 10047 -f 10098 10099 10085 -f 10099 10048 10085 -f 10099 10104 10048 -f 10104 10100 10049 -f 10100 10101 10049 -f 10101 10073 10049 -f 10101 10105 10073 -f 10105 10080 10073 -f 10105 10107 10080 -f 10050 10051 10107 -f 10050 10079 10051 -f 10050 10052 10079 -f 10052 10053 10079 -f 10052 10106 10053 -f 10106 10081 10053 -f 10106 10078 10081 -f 10078 10054 10077 -f 10054 10103 10077 -f 10103 10076 10077 -f 10103 10082 10076 -f 10102 10086 10084 -f 10102 10075 10086 -f 10102 10114 10075 -f 10055 10085 10048 -f 10055 10065 10085 -f 10069 10068 10081 -f 10068 10051 10079 -f 10070 10080 10051 -f 10075 10076 10086 -f 10075 10067 10076 -f 10067 10069 10076 -f 10069 10081 10077 -f 9935 10063 10062 -f 9935 10072 10063 -f 10091 9930 10064 -f 9930 10056 10064 -f 10095 10057 10056 -f 10072 10058 10063 -f 10071 10060 10061 -f 10091 10064 10059 -f 10063 10058 10067 -f 10061 10069 10058 -f 10062 10063 10066 -f 10057 10062 10065 -f 10058 10069 10067 -f 10056 10065 10055 -f 10056 10057 10065 -f 10060 10070 10068 -f 10060 10059 10070 -f 10056 10055 10064 -f 10062 10066 10065 -f 10061 10060 10068 -f 10059 10064 10070 -f 10061 10068 10069 -f 10063 10067 10075 -f 10064 10055 10048 -f 10066 10075 10046 -f 10066 10063 10075 -f 10068 10070 10051 -f 10064 10073 10070 -f 10064 10048 10073 -f 10066 10074 10065 -f 10066 10046 10074 -f 10059 10087 10091 -f 10059 10060 10087 -f 10057 10095 10090 -f 10056 10096 10095 -f 10056 9930 10096 -f 10087 10060 10089 -f 10060 10071 10089 -f 10071 10093 9932 -f 10071 10061 10093 -f 10062 10092 9936 -f 10062 10094 10092 -f 10062 10057 10094 -f 10093 10061 9964 -f 10061 10058 9964 -f 10058 10088 9964 -f 10058 10072 10088 -f 10062 9936 9935 -f 10082 10084 10076 -f 10114 10046 10075 -f 10107 10051 10080 -f 10104 10049 10048 -f 10079 10053 10068 -f 10053 10081 10068 -f 10078 10077 10081 -f 10077 10076 10069 -f 10084 10086 10076 -f 10074 10083 10065 -f 10083 10047 10065 -f 10049 10073 10048 -f 10073 10080 10070 -f 10047 10085 10065 -f 9932 9959 10071 -f 9930 9929 10096 -f 9927 10092 10094 -f 9965 9930 10091 -f 9928 10057 10090 -f 9928 10094 10057 -f 10071 9960 10089 -f 9931 10087 10089 -f 10084 10082 10102 -f 10052 10050 10113 -f 10050 10032 10113 -f 10050 10107 10032 -f 10101 10100 10034 -f 10104 10038 10100 -f 10104 10099 10038 -f 10097 10083 10109 -f 10083 10112 10109 -f 10083 10045 10112 -f 10100 10037 10034 -f 10105 10111 10107 -f 10099 10108 10038 -f 10098 10109 10043 -f 10038 10037 10100 -f 10030 10054 10078 -f 10098 10043 10099 -f 10099 10043 10108 -f 10097 10109 10098 -f 10034 10033 10101 -f 10033 10105 10101 -f 10033 10111 10105 -f 10045 10110 10112 -f 10111 10032 10107 -f 10045 10114 10110 -f 10114 10115 10110 -f 10114 10116 10115 -f 10113 10031 10052 -f 10031 10106 10052 -f 10114 10102 10116 -f 10031 10030 10106 -f 10102 10082 10117 -f 10119 10054 10030 -f 10118 10117 10082 -f 10116 10102 10117 -f 10118 10103 10119 -f 10119 10103 10054 -f 10030 10078 10106 -f 10082 10103 10118 -f 10121 10200 10123 -f 10123 10172 10121 -f 10198 10173 10174 -f 10125 10209 10202 -f 10176 10198 10174 -f 10209 10124 10202 -f 10173 10198 10172 -f 10172 10198 10121 -f 10176 10127 10198 -f 10124 10206 10202 -f 10120 10205 10122 -f 10122 10205 10206 -f 10122 10206 10124 -f 10208 10127 10126 -f 10125 10202 10203 -f 10127 10208 10200 -f 10126 10127 10176 -f 10131 10200 10180 -f 10208 10177 10200 -f 10200 10177 10180 -f 10195 10193 10194 -f 10195 10125 10193 -f 10193 10125 10203 -f 10193 10203 10128 -f 10120 10156 10203 -f 10205 10120 10203 -f 10131 10129 10130 -f 10123 10200 10131 -f 10123 10131 10130 -f 10167 10134 10132 -f 10132 10134 10183 -f 10132 10183 10136 -f 10129 10131 10133 -f 10129 10133 10167 -f 10167 10133 10134 -f 10203 10156 10157 -f 10203 10157 10128 -f 10128 10157 10159 -f 10136 10183 10135 -f 10136 10135 10185 -f 10136 10185 10165 -f 10185 10187 10165 -f 10165 10187 10164 -f 10164 10187 10188 -f 10164 10188 10137 -f 10137 10188 10190 -f 10137 10190 10191 -f 10137 10191 10162 -f 10162 10191 10128 -f 10162 10128 10159 -f 10199 10197 10139 -f 10207 10175 10196 -f 10201 10204 10144 -f 10144 10204 10155 -f 10153 10142 10146 -f 10138 10199 10139 -f 10139 10197 10140 -f 10175 10197 10196 -f 10155 10204 10153 -f 10142 10201 10143 -f 10207 10196 10145 -f 10153 10146 10210 -f 10201 10144 10143 -f 10140 10197 10175 -f 10145 10178 10207 -f 10145 10147 10179 -f 10145 10179 10178 -f 10153 10141 10154 -f 10153 10210 10141 -f 10141 10210 10194 -f 10199 10138 10145 -f 10145 10138 10171 -f 10145 10171 10170 -f 10145 10170 10147 -f 10147 10170 10169 -f 10148 10184 10182 -f 10148 10182 10166 -f 10147 10169 10168 -f 10147 10168 10149 -f 10149 10168 10181 -f 10181 10168 10166 -f 10181 10166 10182 -f 10150 10186 10151 -f 10151 10186 10184 -f 10151 10184 10148 -f 10163 10189 10150 -f 10150 10189 10152 -f 10150 10152 10186 -f 10160 10154 10161 -f 10154 10160 10158 -f 10153 10154 10158 -f 10153 10158 10155 -f 10161 10154 10192 -f 10161 10192 10163 -f 10163 10192 10189 -f 10122 10144 10120 -f 10120 10144 10155 -f 10120 10155 10156 -f 10156 10155 10158 -f 10156 10158 10157 -f 10157 10158 10160 -f 10157 10160 10159 -f 10159 10160 10162 -f 10162 10160 10161 -f 10162 10161 10137 -f 10137 10161 10163 -f 10137 10163 10164 -f 10164 10163 10150 -f 10164 10150 10165 -f 10165 10150 10151 -f 10165 10151 10136 -f 10136 10151 10148 -f 10136 10148 10132 -f 10132 10148 10166 -f 10132 10166 10167 -f 10167 10166 10168 -f 10167 10168 10129 -f 10129 10168 10169 -f 10129 10169 10130 -f 10130 10169 10170 -f 10130 10170 10123 -f 10123 10170 10171 -f 10123 10171 10172 -f 10172 10171 10138 -f 10172 10138 10173 -f 10173 10138 10139 -f 10174 10173 10140 -f 10140 10173 10139 -f 10174 10140 10175 -f 10174 10175 10176 -f 10176 10175 10207 -f 10176 10207 10126 -f 10208 10126 10207 -f 10177 10178 10179 -f 10177 10179 10147 -f 10177 10147 10180 -f 10180 10147 10131 -f 10131 10147 10149 -f 10131 10149 10133 -f 10133 10149 10181 -f 10133 10181 10134 -f 10134 10181 10182 -f 10134 10182 10183 -f 10183 10182 10184 -f 10183 10184 10135 -f 10135 10184 10186 -f 10135 10186 10185 -f 10185 10186 10187 -f 10187 10186 10152 -f 10187 10152 10188 -f 10188 10152 10189 -f 10188 10189 10190 -f 10190 10189 10192 -f 10190 10192 10191 -f 10191 10192 10154 -f 10191 10154 10128 -f 10128 10154 10141 -f 10128 10141 10193 -f 10193 10141 10194 -f 10195 10194 10210 -f 10195 10210 10125 -f 10209 10125 10146 -f 10146 10125 10210 -f 10209 10146 10142 -f 10209 10142 10124 -f 10124 10142 10143 -f 10122 10124 10144 -f 10144 10124 10143 -f 10127 10196 10197 -f 10127 10197 10198 -f 10198 10197 10199 -f 10198 10199 10121 -f 10121 10199 10200 -f 10200 10199 10145 -f 10200 10145 10127 -f 10127 10145 10196 -f 10206 10201 10142 -f 10206 10142 10202 -f 10202 10142 10153 -f 10202 10153 10203 -f 10203 10153 10205 -f 10205 10153 10204 -f 10205 10204 10206 -f 10206 10204 10201 -f 10208 10207 10178 -f 10208 10178 10177 -f 10221 10342 10340 -f 10221 10340 10211 -f 10211 10340 10212 -f 10211 10212 10223 -f 10223 10212 10338 -f 10223 10338 10224 -f 10224 10338 10337 -f 10224 10337 10336 -f 10224 10336 10225 -f 10225 10336 10335 -f 10225 10335 10226 -f 10226 10335 10213 -f 10226 10213 10334 -f 10226 10334 10228 -f 10228 10334 10333 -f 10228 10333 10214 -f 10333 10332 10214 -f 10214 10332 10229 -f 10229 10332 10330 -f 10229 10330 10230 -f 10230 10330 10329 -f 10230 10329 10216 -f 10216 10329 10215 -f 10216 10215 10328 -f 10216 10328 10217 -f 10217 10328 10218 -f 10218 10328 10344 -f 10218 10344 10343 -f 10218 10343 10220 -f 10220 10343 10365 -f 10220 10365 10361 -f 10220 10361 10221 -f 10221 10361 10342 -f 10241 10217 10219 -f 10219 10217 10218 -f 10219 10218 10240 -f 10240 10218 10220 -f 10240 10220 10239 -f 10239 10220 10221 -f 10239 10221 10242 -f 10242 10221 10222 -f 10222 10221 10211 -f 10222 10211 10238 -f 10238 10211 10223 -f 10238 10223 10224 -f 10238 10224 10237 -f 10237 10224 10225 -f 10237 10225 10236 -f 10236 10225 10235 -f 10235 10225 10226 -f 10235 10226 10233 -f 10233 10226 10228 -f 10233 10228 10227 -f 10227 10228 10214 -f 10227 10214 10232 -f 10232 10214 10229 -f 10232 10229 10234 -f 10234 10229 10230 -f 10234 10230 10231 -f 10231 10230 10216 -f 10231 10216 10241 -f 10241 10216 10217 -f 10241 10257 10231 -f 10227 10262 10233 -f 10234 10259 10232 -f 10235 10266 10236 -f 10236 10266 10237 -f 10237 10266 10265 -f 10237 10265 10238 -f 10240 10264 10219 -f 10271 10251 10270 -f 10271 10270 10269 -f 10292 10247 10294 -f 10294 10247 10275 -f 10275 10248 10279 -f 10279 10248 10281 -f 10281 10248 10249 -f 10281 10249 10243 -f 10244 10245 10267 -f 10267 10245 10246 -f 10247 10255 10275 -f 10275 10255 10253 -f 10251 10256 10270 -f 10247 10254 10255 -f 10275 10253 10248 -f 10249 10250 10243 -f 10270 10256 10244 -f 10246 10254 10247 -f 10251 10243 10258 -f 10252 10254 10246 -f 10251 10258 10256 -f 10245 10263 10246 -f 10246 10263 10252 -f 10243 10250 10258 -f 10253 10260 10248 -f 10248 10260 10249 -f 10244 10262 10245 -f 10254 10257 10255 -f 10256 10266 10244 -f 10244 10266 10262 -f 10249 10261 10250 -f 10256 10258 10266 -f 10245 10262 10263 -f 10255 10264 10253 -f 10250 10261 10265 -f 10250 10265 10258 -f 10255 10257 10264 -f 10253 10264 10260 -f 10249 10260 10261 -f 10263 10259 10252 -f 10254 10259 10257 -f 10258 10265 10266 -f 10252 10259 10254 -f 10260 10222 10261 -f 10260 10242 10222 -f 10222 10238 10261 -f 10261 10238 10265 -f 10266 10233 10262 -f 10257 10241 10264 -f 10264 10241 10219 -f 10264 10240 10260 -f 10260 10240 10239 -f 10260 10239 10242 -f 10266 10235 10233 -f 10262 10227 10263 -f 10263 10227 10232 -f 10263 10232 10259 -f 10259 10234 10231 -f 10259 10231 10257 -f 10268 10270 10286 -f 10286 10270 10244 -f 10286 10244 10267 -f 10267 10246 10288 -f 10288 10246 10289 -f 10269 10270 10268 -f 10289 10246 10290 -f 10290 10246 10247 -f 10290 10247 10292 -f 10273 10243 10283 -f 10283 10243 10251 -f 10280 10279 10281 -f 10251 10271 10283 -f 10294 10275 10272 -f 10272 10275 10274 -f 10281 10243 10273 -f 10274 10275 10277 -f 10277 10275 10279 -f 10293 10294 10276 -f 10276 10294 10272 -f 10276 10272 10274 -f 10276 10274 10376 -f 10376 10274 10277 -f 10376 10277 10375 -f 10375 10277 10279 -f 10375 10279 10278 -f 10278 10279 10280 -f 10278 10280 10377 -f 10377 10280 10281 -f 10377 10281 10282 -f 10282 10281 10273 -f 10282 10273 10284 -f 10284 10273 10283 -f 10284 10283 10374 -f 10374 10283 10271 -f 10374 10271 10373 -f 10373 10271 10269 -f 10373 10269 10372 -f 10372 10269 10268 -f 10372 10268 10285 -f 10285 10268 10286 -f 10285 10286 10287 -f 10287 10286 10267 -f 10287 10267 10369 -f 10369 10267 10403 -f 10403 10267 10288 -f 10403 10288 10289 -f 10403 10289 10371 -f 10371 10289 10370 -f 10370 10289 10290 -f 10370 10290 10291 -f 10291 10290 10292 -f 10291 10292 10293 -f 10293 10292 10294 -f 10308 10472 10355 -f 10308 10355 10474 -f 10474 10355 10357 -f 10474 10357 10468 -f 10468 10357 10347 -f 10468 10347 10473 -f 10473 10347 10346 -f 10473 10346 10469 -f 10469 10346 10295 -f 10295 10346 10324 -f 10295 10324 10477 -f 10477 10324 10323 -f 10477 10323 10345 -f 10478 10345 10470 -f 10470 10345 10296 -f 10470 10296 10298 -f 10470 10298 10297 -f 10297 10298 10476 -f 10476 10298 10354 -f 10476 10354 10352 -f 10475 10352 10299 -f 10475 10299 10479 -f 10479 10299 10300 -f 10479 10300 10351 -f 10479 10351 10301 -f 10301 10351 10350 -f 10301 10350 10302 -f 10303 10302 10304 -f 10303 10304 10349 -f 10349 10348 10305 -f 10305 10348 10471 -f 10471 10348 10353 -f 10471 10353 10306 -f 10306 10353 10356 -f 10307 10356 10472 -f 10320 10346 10347 -f 10319 10299 10354 -f 10319 10354 10323 -f 10323 10354 10298 -f 10323 10298 10296 -f 10322 10304 10350 -f 10321 10350 10351 -f 10321 10351 10300 -f 10321 10300 10319 -f 10319 10300 10299 -f 10318 10356 10353 -f 10318 10353 10322 -f 10322 10353 10348 -f 10322 10348 10304 -f 10347 10357 10320 -f 10320 10357 10325 -f 10325 10357 10355 -f 10339 10310 10311 -f 10359 10312 10316 -f 10364 10358 10314 -f 10364 10314 10317 -f 10313 10310 10309 -f 10309 10310 10339 -f 10312 10311 10319 -f 10358 10368 10314 -f 10362 10327 10313 -f 10362 10313 10341 -f 10316 10315 10368 -f 10368 10315 10314 -f 10311 10310 10321 -f 10317 10314 10320 -f 10327 10317 10325 -f 10313 10322 10310 -f 10327 10318 10313 -f 10325 10318 10327 -f 10313 10318 10322 -f 10310 10322 10321 -f 10316 10312 10323 -f 10316 10323 10315 -f 10317 10320 10325 -f 10311 10321 10319 -f 10312 10319 10323 -f 10315 10323 10324 -f 10315 10324 10314 -f 10318 10325 10356 -f 10314 10346 10320 -f 10321 10322 10350 -f 10314 10324 10346 -f 10316 10368 10359 -f 10359 10366 10312 -f 10312 10366 10326 -f 10312 10326 10311 -f 10311 10326 10360 -f 10311 10360 10339 -f 10327 10362 10367 -f 10317 10327 10364 -f 10215 10364 10328 -f 10328 10364 10363 -f 10329 10358 10215 -f 10215 10358 10364 -f 10330 10358 10329 -f 10358 10330 10331 -f 10331 10330 10332 -f 10332 10368 10331 -f 10333 10368 10332 -f 10359 10333 10334 -f 10213 10366 10334 -f 10366 10213 10335 -f 10336 10326 10335 -f 10337 10360 10336 -f 10360 10337 10339 -f 10338 10339 10337 -f 10338 10212 10309 -f 10309 10212 10340 -f 10342 10341 10340 -f 10340 10341 10309 -f 10361 10341 10342 -f 10343 10362 10365 -f 10362 10343 10367 -f 10367 10343 10344 -f 10328 10363 10344 -f 10344 10363 10367 -f 10348 10349 10304 -f 10345 10323 10296 -f 10302 10350 10304 -f 10356 10325 10472 -f 10352 10354 10299 -f 10325 10355 10472 -f 10368 10333 10359 -f 10334 10366 10359 -f 10360 10326 10336 -f 10335 10326 10366 -f 10363 10327 10367 -f 10365 10362 10361 -f 10361 10362 10341 -f 10341 10313 10309 -f 10338 10309 10339 -f 10331 10368 10358 -f 10363 10364 10327 -f 10293 10405 10291 -f 10369 10401 10287 -f 10287 10401 10285 -f 10284 10397 10282 -f 10370 10291 10404 -f 10370 10404 10371 -f 10404 10403 10371 -f 10278 10396 10375 -f 10372 10398 10373 -f 10398 10397 10373 -f 10373 10397 10374 -f 10374 10397 10284 -f 10375 10396 10376 -f 10276 10405 10293 -f 10397 10402 10282 -f 10282 10402 10377 -f 10376 10405 10276 -f 10411 10383 10385 -f 10411 10385 10414 -f 10414 10385 10378 -f 10416 10378 10379 -f 10416 10379 10410 -f 10410 10379 10419 -f 10419 10379 10380 -f 10419 10380 10421 -f 10421 10380 10387 -f 10407 10395 10430 -f 10409 10430 10383 -f 10384 10381 10393 -f 10428 10384 10382 -f 10428 10382 10407 -f 10407 10382 10390 -f 10407 10390 10395 -f 10430 10395 10383 -f 10395 10399 10383 -f 10383 10399 10385 -f 10378 10385 10386 -f 10381 10387 10389 -f 10389 10393 10381 -f 10379 10388 10380 -f 10385 10392 10386 -f 10378 10386 10379 -f 10380 10388 10391 -f 10380 10391 10387 -f 10393 10394 10384 -f 10384 10394 10382 -f 10385 10399 10392 -f 10386 10402 10379 -f 10391 10398 10387 -f 10382 10394 10390 -f 10379 10397 10388 -f 10387 10398 10389 -f 10389 10398 10400 -f 10390 10404 10395 -f 10399 10405 10392 -f 10392 10396 10386 -f 10386 10396 10402 -f 10379 10402 10397 -f 10389 10400 10393 -f 10393 10400 10401 -f 10393 10401 10394 -f 10394 10404 10390 -f 10404 10405 10395 -f 10392 10405 10396 -f 10388 10397 10391 -f 10395 10405 10399 -f 10391 10397 10398 -f 10401 10403 10394 -f 10394 10403 10404 -f 10396 10377 10402 -f 10398 10372 10400 -f 10405 10376 10396 -f 10396 10278 10377 -f 10372 10285 10400 -f 10400 10285 10401 -f 10401 10369 10403 -f 10404 10291 10405 -f 10423 10381 10406 -f 10406 10381 10384 -f 10406 10384 10425 -f 10425 10384 10426 -f 10426 10384 10428 -f 10426 10428 10427 -f 10408 10387 10381 -f 10408 10381 10423 -f 10414 10378 10416 -f 10421 10387 10422 -f 10408 10422 10387 -f 10409 10383 10411 -f 10432 10409 10412 -f 10412 10409 10411 -f 10412 10411 10413 -f 10413 10411 10414 -f 10413 10414 10415 -f 10415 10414 10416 -f 10415 10416 10487 -f 10487 10416 10417 -f 10417 10416 10410 -f 10417 10410 10418 -f 10418 10410 10419 -f 10418 10419 10420 -f 10420 10419 10421 -f 10420 10421 10486 -f 10486 10421 10485 -f 10485 10421 10422 -f 10485 10422 10484 -f 10484 10422 10408 -f 10484 10408 10424 -f 10424 10408 10423 -f 10424 10423 10482 -f 10482 10423 10406 -f 10482 10406 10481 -f 10481 10406 10425 -f 10481 10425 10480 -f 10480 10425 10426 -f 10480 10426 10513 -f 10513 10426 10427 -f 10513 10427 10483 -f 10483 10427 10428 -f 10483 10428 10407 -f 10483 10407 10429 -f 10429 10407 10430 -f 10429 10430 10431 -f 10431 10430 10432 -f 10432 10430 10409 -f 10586 10433 10434 -f 10434 10459 10591 -f 10591 10459 10577 -f 10577 10459 10435 -f 10577 10435 10590 -f 10590 10435 10458 -f 10590 10458 10589 -f 10589 10458 10466 -f 10589 10466 10578 -f 10578 10463 10436 -f 10436 10463 10579 -f 10579 10464 10588 -f 10588 10464 10584 -f 10584 10464 10580 -f 10587 10580 10581 -f 10581 10580 10461 -f 10581 10461 10437 -f 10437 10467 10585 -f 10585 10467 10438 -f 10585 10438 10583 -f 10583 10438 10462 -f 10583 10462 10439 -f 10439 10440 10582 -f 10582 10440 10441 -f 10582 10441 10465 -f 10465 10460 10586 -f 10586 10460 10433 -f 10463 10466 10458 -f 10452 10458 10435 -f 10454 10580 10464 -f 10454 10464 10455 -f 10455 10464 10579 -f 10453 10438 10467 -f 10453 10467 10442 -f 10442 10461 10454 -f 10454 10461 10580 -f 10451 10441 10440 -f 10451 10440 10453 -f 10453 10440 10462 -f 10453 10462 10438 -f 10435 10459 10443 -f 10443 10460 10451 -f 10306 10450 10445 -f 10303 10446 10457 -f 10297 10448 10478 -f 10478 10448 10449 -f 10478 10449 10456 -f 10447 10454 10448 -f 10444 10443 10450 -f 10445 10451 10446 -f 10446 10453 10457 -f 10457 10442 10447 -f 10449 10448 10455 -f 10456 10452 10444 -f 10446 10451 10453 -f 10447 10442 10454 -f 10456 10449 10452 -f 10457 10453 10442 -f 10445 10450 10451 -f 10444 10452 10443 -f 10448 10454 10455 -f 10449 10463 10452 -f 10450 10443 10451 -f 10449 10455 10463 -f 10455 10579 10463 -f 10452 10463 10458 -f 10452 10435 10443 -f 10478 10470 10297 -f 10297 10476 10448 -f 10444 10473 10469 -f 10444 10469 10456 -f 10456 10469 10295 -f 10456 10295 10477 -f 10456 10477 10478 -f 10447 10448 10479 -f 10447 10479 10457 -f 10457 10479 10301 -f 10457 10301 10302 -f 10457 10302 10303 -f 10450 10306 10307 -f 10444 10450 10474 -f 10445 10446 10305 -f 10445 10305 10471 -f 10445 10471 10306 -f 10465 10451 10460 -f 10461 10442 10437 -f 10437 10442 10467 -f 10439 10462 10440 -f 10441 10451 10465 -f 10433 10443 10434 -f 10434 10443 10459 -f 10578 10466 10463 -f 10433 10460 10443 -f 10307 10306 10356 -f 10308 10450 10472 -f 10472 10450 10307 -f 10349 10305 10446 -f 10349 10446 10303 -f 10475 10479 10448 -f 10475 10448 10352 -f 10352 10448 10476 -f 10345 10478 10477 -f 10468 10444 10474 -f 10474 10450 10308 -f 10473 10444 10468 -f 10431 10511 10429 -f 10480 10512 10481 -f 10481 10512 10482 -f 10512 10424 10482 -f 10420 10485 10417 -f 10420 10417 10418 -f 10429 10511 10483 -f 10480 10513 10512 -f 10483 10511 10513 -f 10420 10486 10485 -f 10487 10417 10415 -f 10413 10415 10509 -f 10432 10514 10431 -f 10413 10509 10412 -f 10432 10412 10514 -f 10526 10488 10506 -f 10526 10506 10489 -f 10489 10528 10527 -f 10528 10491 10521 -f 10521 10491 10492 -f 10523 10492 10518 -f 10532 10490 10515 -f 10517 10500 10520 -f 10525 10493 10488 -f 10518 10499 10532 -f 10532 10499 10490 -f 10515 10490 10495 -f 10515 10495 10516 -f 10516 10495 10517 -f 10489 10504 10528 -f 10528 10504 10491 -f 10518 10494 10499 -f 10493 10500 10505 -f 10493 10505 10496 -f 10493 10496 10488 -f 10489 10506 10504 -f 10492 10494 10518 -f 10491 10501 10492 -f 10492 10501 10498 -f 10499 10502 10490 -f 10488 10496 10506 -f 10504 10497 10491 -f 10491 10497 10501 -f 10494 10510 10499 -f 10517 10503 10500 -f 10492 10498 10494 -f 10490 10502 10495 -f 10500 10503 10508 -f 10499 10510 10502 -f 10500 10508 10505 -f 10495 10503 10517 -f 10504 10507 10497 -f 10505 10514 10496 -f 10506 10496 10509 -f 10506 10509 10504 -f 10497 10417 10501 -f 10501 10417 10498 -f 10502 10512 10495 -f 10508 10514 10505 -f 10496 10514 10509 -f 10504 10509 10507 -f 10512 10513 10495 -f 10495 10513 10503 -f 10503 10511 10508 -f 10507 10417 10497 -f 10498 10417 10485 -f 10510 10424 10502 -f 10509 10415 10507 -f 10498 10485 10494 -f 10494 10485 10510 -f 10502 10424 10512 -f 10508 10511 10514 -f 10415 10417 10507 -f 10503 10513 10511 -f 10514 10412 10509 -f 10485 10484 10510 -f 10510 10484 10424 -f 10511 10431 10514 -f 10515 10516 10533 -f 10516 10517 10534 -f 10534 10517 10520 -f 10519 10518 10532 -f 10520 10500 10535 -f 10535 10500 10493 -f 10521 10492 10522 -f 10522 10492 10523 -f 10523 10518 10524 -f 10524 10518 10530 -f 10525 10488 10526 -f 10614 10525 10619 -f 10619 10525 10526 -f 10619 10526 10489 -f 10619 10489 10617 -f 10617 10489 10527 -f 10617 10527 10620 -f 10620 10527 10621 -f 10621 10527 10528 -f 10621 10528 10618 -f 10618 10528 10521 -f 10618 10521 10616 -f 10616 10521 10522 -f 10616 10522 10529 -f 10529 10522 10523 -f 10529 10523 10524 -f 10529 10524 10611 -f 10611 10524 10530 -f 10611 10530 10609 -f 10609 10530 10518 -f 10609 10518 10607 -f 10607 10518 10519 -f 10607 10519 10531 -f 10531 10519 10615 -f 10615 10519 10532 -f 10615 10532 10515 -f 10615 10515 10604 -f 10604 10515 10533 -f 10604 10533 10605 -f 10605 10533 10516 -f 10605 10516 10534 -f 10605 10534 10606 -f 10606 10534 10520 -f 10606 10520 10608 -f 10608 10520 10535 -f 10608 10535 10610 -f 10610 10535 10493 -f 10610 10493 10612 -f 10612 10493 10525 -f 10612 10525 10614 -f 10613 10568 10536 -f 10536 10568 10537 -f 10536 10537 10569 -f 10592 10569 10561 -f 10592 10561 10538 -f 10538 10561 10573 -f 10538 10573 10539 -f 10539 10573 10540 -f 10539 10540 10603 -f 10593 10600 10574 -f 10593 10574 10598 -f 10598 10574 10601 -f 10601 10560 10594 -f 10594 10560 10570 -f 10541 10594 10564 -f 10541 10564 10563 -f 10541 10563 10595 -f 10595 10563 10542 -f 10595 10542 10602 -f 10602 10542 10565 -f 10602 10565 10543 -f 10543 10562 10596 -f 10596 10562 10566 -f 10596 10566 10597 -f 10597 10566 10544 -f 10597 10544 10567 -f 10599 10571 10575 -f 10599 10575 10572 -f 10599 10572 10613 -f 10557 10540 10573 -f 10557 10573 10545 -f 10562 10565 10556 -f 10556 10563 10564 -f 10576 10575 10544 -f 10576 10544 10562 -f 10568 10572 10576 -f 10582 10550 10559 -f 10577 10547 10549 -f 10581 10546 10551 -f 10588 10551 10553 -f 10588 10553 10548 -f 10546 10559 10552 -f 10559 10550 10552 -f 10551 10556 10553 -f 10547 10557 10549 -f 10546 10555 10556 -f 10547 10548 10557 -f 10546 10552 10555 -f 10546 10556 10551 -f 10549 10557 10545 -f 10558 10554 10576 -f 10558 10576 10550 -f 10549 10545 10558 -f 10550 10576 10552 -f 10558 10545 10554 -f 10553 10570 10548 -f 10552 10562 10555 -f 10553 10556 10570 -f 10548 10540 10557 -f 10554 10568 10576 -f 10552 10576 10562 -f 10555 10562 10556 -f 10548 10574 10540 -f 10556 10564 10570 -f 10548 10570 10574 -f 10554 10545 10537 -f 10554 10537 10568 -f 10547 10436 10548 -f 10548 10436 10588 -f 10551 10588 10584 -f 10549 10591 10577 -f 10547 10577 10590 -f 10547 10590 10589 -f 10547 10589 10436 -f 10584 10587 10551 -f 10551 10587 10581 -f 10550 10465 10558 -f 10558 10465 10586 -f 10549 10558 10591 -f 10559 10546 10583 -f 10550 10582 10465 -f 10567 10544 10571 -f 10613 10572 10568 -f 10594 10570 10564 -f 10603 10540 10600 -f 10563 10556 10542 -f 10542 10556 10565 -f 10543 10565 10562 -f 10566 10562 10544 -f 10571 10544 10575 -f 10575 10576 10572 -f 10537 10545 10569 -f 10569 10545 10561 -f 10600 10540 10574 -f 10574 10570 10601 -f 10601 10570 10560 -f 10561 10545 10573 -f 10439 10582 10559 -f 10439 10559 10583 -f 10585 10546 10437 -f 10437 10546 10581 -f 10579 10588 10436 -f 10578 10436 10589 -f 10434 10591 10558 -f 10434 10558 10586 -f 10583 10546 10585 -f 10580 10587 10584 -f 10571 10599 10567 -f 10594 10598 10601 -f 10595 10529 10541 -f 10541 10529 10611 -f 10541 10611 10594 -f 10598 10531 10593 -f 10600 10593 10604 -f 10600 10604 10603 -f 10603 10604 10539 -f 10592 10608 10569 -f 10569 10608 10610 -f 10569 10610 10536 -f 10593 10531 10615 -f 10539 10604 10605 -f 10538 10606 10608 -f 10604 10593 10615 -f 10618 10543 10596 -f 10538 10539 10606 -f 10539 10605 10606 -f 10592 10538 10608 -f 10531 10598 10607 -f 10607 10594 10609 -f 10536 10610 10612 -f 10609 10594 10611 -f 10598 10594 10607 -f 10536 10612 10613 -f 10613 10612 10614 -f 10613 10614 10619 -f 10529 10595 10616 -f 10616 10595 10602 -f 10613 10619 10599 -f 10616 10602 10618 -f 10599 10617 10567 -f 10621 10618 10596 -f 10620 10567 10617 -f 10619 10617 10599 -f 10620 10621 10597 -f 10621 10596 10597 -f 10618 10602 10543 -f 10567 10620 10597 -f 10625 10624 10622 -f 10622 10624 10623 -f 10627 10629 10626 -f 10628 10627 10626 -f 10626 10629 10628 -f 10631 10633 10632 -f 10634 10632 10633 -f 10630 10631 10632 -f 10638 10635 10636 -f 10638 10636 10637 -f 10638 10639 10635 -f 10643 10642 10640 -f 10642 10641 10640 -f 10641 10642 10644 -f 10648 10645 10646 -f 10647 10645 10648 -f 10647 10648 10646 -f 10649 10722 10650 -f 10650 10722 10651 -f 10650 10651 10652 -f 10652 10651 10653 -f 10652 10653 10654 -f 10654 10653 10655 -f 10654 10655 10656 -f 10656 10655 10657 -f 10656 10657 10658 -f 10658 10657 10660 -f 10658 10660 10659 -f 10659 10660 10661 -f 10659 10661 10662 -f 10662 10661 10663 -f 10662 10663 10664 -f 10664 10663 10665 -f 10664 10665 10667 -f 10667 10665 10666 -f 10667 10666 10669 -f 10669 10666 10668 -f 10669 10668 10670 -f 10670 10668 10671 -f 10670 10671 10672 -f 10672 10671 10673 -f 10672 10673 10674 -f 10674 10673 10676 -f 10674 10676 10675 -f 10675 10676 10678 -f 10675 10678 10677 -f 10677 10678 10679 -f 10677 10679 10680 -f 10680 10679 10681 -f 10680 10681 10682 -f 10682 10681 10683 -f 10682 10683 10684 -f 10684 10683 10685 -f 10684 10685 10686 -f 10686 10685 10687 -f 10686 10687 10688 -f 10688 10687 10689 -f 10688 10689 10691 -f 10691 10689 10690 -f 10691 10690 10693 -f 10693 10690 10692 -f 10693 10692 10694 -f 10694 10692 10695 -f 10694 10695 10696 -f 10696 10695 10697 -f 10696 10697 10699 -f 10699 10697 10698 -f 10699 10698 10700 -f 10700 10698 10702 -f 10700 10702 10701 -f 10701 10702 10704 -f 10701 10704 10703 -f 10703 10704 10705 -f 10703 10705 10707 -f 10707 10705 10706 -f 10707 10706 10708 -f 10708 10706 10709 -f 10708 10709 10710 -f 10710 10709 10711 -f 10710 10711 10713 -f 10713 10711 10712 -f 10713 10712 10714 -f 10714 10712 10715 -f 10714 10715 10717 -f 10717 10715 10716 -f 10717 10716 10718 -f 10718 10716 10719 -f 10718 10719 10720 -f 10720 10719 10721 -f 10720 10721 10649 -f 10649 10721 10722 -f 10724 10727 10723 -f 10724 10723 10725 -f 10725 10723 10726 -f 10738 10848 10729 -f 10738 10729 10728 -f 10728 10729 10750 -f 10728 10750 10743 -f 10743 10750 10747 -f 10853 10859 10732 -f 10861 10862 10730 -f 10732 10733 10731 -f 10730 10805 10861 -f 10861 10805 10733 -f 10861 10733 10732 -f 10736 10734 10852 -f 10731 10735 10853 -f 10731 10853 10732 -f 10736 10852 10735 -f 10735 10757 10736 -f 10731 10757 10735 -f 10737 10851 10734 -f 10730 10862 10864 -f 10741 10819 10864 -f 10864 10819 10821 -f 10853 10744 10859 -f 10742 10739 10738 -f 10738 10739 10740 -f 10740 10739 10850 -f 10740 10850 10746 -f 10746 10850 10851 -f 10737 10746 10851 -f 10734 10851 10852 -f 10864 10821 10730 -f 10819 10741 10743 -f 10728 10857 10738 -f 10741 10857 10728 -f 10744 10853 10742 -f 10743 10741 10728 -f 10738 10857 10744 -f 10744 10742 10738 -f 10734 10745 10737 -f 10737 10745 10849 -f 10737 10849 10746 -f 10746 10849 10740 -f 10734 10736 10745 -f 10745 10736 10758 -f 10860 10755 10854 -f 10854 10749 10860 -f 10822 10748 10823 -f 10822 10823 10806 -f 10748 10860 10823 -f 10823 10860 10749 -f 10747 10752 10751 -f 10822 10863 10748 -f 10849 10856 10855 -f 10849 10855 10848 -f 10749 10854 10753 -f 10749 10753 10756 -f 10865 10750 10729 -f 10745 10758 10754 -f 10752 10747 10865 -f 10865 10747 10750 -f 10751 10752 10863 -f 10863 10820 10751 -f 10822 10820 10863 -f 10753 10758 10756 -f 10758 10753 10754 -f 10745 10754 10856 -f 10855 10858 10848 -f 10848 10858 10866 -f 10855 10860 10858 -f 10848 10866 10729 -f 10729 10866 10865 -f 10856 10849 10745 -f 10860 10855 10755 -f 10731 10749 10756 -f 10731 10756 10757 -f 10757 10756 10758 -f 10757 10758 10736 -f 10846 10759 10782 -f 10782 10759 10843 -f 10782 10843 10842 -f 10782 10842 10783 -f 10783 10842 10841 -f 10783 10841 10760 -f 10760 10841 10761 -f 10760 10761 10762 -f 10762 10761 10763 -f 10762 10763 10771 -f 10749 10731 10823 -f 10823 10731 10733 -f 10823 10733 10824 -f 10824 10733 10797 -f 10824 10797 10780 -f 10780 10797 10764 -f 10765 10767 10766 -f 10766 10767 10834 -f 10766 10834 10788 -f 10788 10834 10768 -f 10788 10768 10769 -f 10769 10768 10776 -f 10769 10776 10770 -f 10763 10772 10771 -f 10771 10772 10773 -f 10771 10773 10786 -f 10786 10773 10838 -f 10786 10838 10774 -f 10774 10838 10775 -f 10774 10775 10765 -f 10765 10775 10835 -f 10765 10835 10767 -f 10776 10833 10770 -f 10770 10833 10831 -f 10770 10831 10791 -f 10791 10831 10777 -f 10791 10777 10793 -f 10793 10777 10778 -f 10793 10778 10795 -f 10795 10778 10828 -f 10795 10828 10764 -f 10764 10828 10779 -f 10764 10779 10780 -f 10799 10782 10781 -f 10781 10782 10783 -f 10781 10783 10784 -f 10784 10783 10760 -f 10784 10760 10802 -f 10802 10760 10762 -f 10802 10762 10785 -f 10785 10762 10771 -f 10785 10771 10810 -f 10810 10771 10786 -f 10810 10786 10809 -f 10809 10786 10774 -f 10809 10774 10807 -f 10807 10774 10765 -f 10807 10765 10787 -f 10787 10765 10766 -f 10787 10766 10789 -f 10789 10766 10788 -f 10789 10788 10814 -f 10814 10788 10769 -f 10814 10769 10811 -f 10811 10769 10770 -f 10811 10770 10790 -f 10790 10770 10791 -f 10790 10791 10792 -f 10792 10791 10793 -f 10792 10793 10794 -f 10794 10793 10795 -f 10794 10795 10796 -f 10796 10795 10764 -f 10796 10764 10798 -f 10798 10764 10797 -f 10798 10797 10805 -f 10805 10797 10733 -f 10845 10847 10844 -f 10844 10847 10799 -f 10844 10799 10800 -f 10800 10799 10781 -f 10810 10801 10785 -f 10785 10801 10803 -f 10785 10803 10802 -f 10802 10803 10839 -f 10802 10839 10784 -f 10784 10839 10840 -f 10784 10840 10781 -f 10781 10840 10804 -f 10781 10804 10800 -f 10730 10822 10805 -f 10805 10822 10806 -f 10805 10806 10798 -f 10787 10817 10807 -f 10807 10817 10808 -f 10807 10808 10809 -f 10809 10808 10836 -f 10809 10836 10810 -f 10810 10836 10837 -f 10810 10837 10801 -f 10790 10832 10811 -f 10811 10832 10812 -f 10811 10812 10814 -f 10814 10812 10813 -f 10814 10813 10789 -f 10789 10813 10815 -f 10789 10815 10787 -f 10787 10815 10816 -f 10787 10816 10817 -f 10806 10825 10798 -f 10798 10825 10826 -f 10798 10826 10796 -f 10796 10826 10827 -f 10796 10827 10794 -f 10794 10827 10829 -f 10794 10829 10792 -f 10792 10829 10830 -f 10792 10830 10790 -f 10790 10830 10818 -f 10790 10818 10832 -f 10819 10751 10820 -f 10819 10820 10821 -f 10821 10820 10822 -f 10821 10822 10730 -f 10751 10819 10747 -f 10747 10819 10743 -f 10806 10823 10824 -f 10806 10824 10825 -f 10825 10824 10780 -f 10825 10780 10826 -f 10826 10780 10779 -f 10826 10779 10827 -f 10827 10779 10828 -f 10827 10828 10829 -f 10829 10828 10778 -f 10829 10778 10830 -f 10830 10778 10777 -f 10830 10777 10818 -f 10818 10777 10831 -f 10818 10831 10832 -f 10832 10831 10833 -f 10832 10833 10812 -f 10812 10833 10776 -f 10812 10776 10813 -f 10813 10776 10768 -f 10813 10768 10815 -f 10815 10768 10834 -f 10815 10834 10816 -f 10816 10834 10767 -f 10816 10767 10817 -f 10817 10767 10835 -f 10817 10835 10808 -f 10808 10835 10775 -f 10808 10775 10836 -f 10836 10775 10838 -f 10836 10838 10837 -f 10837 10838 10773 -f 10837 10773 10801 -f 10801 10773 10772 -f 10801 10772 10803 -f 10803 10772 10763 -f 10803 10763 10839 -f 10839 10763 10761 -f 10839 10761 10840 -f 10840 10761 10841 -f 10840 10841 10804 -f 10804 10841 10842 -f 10804 10842 10800 -f 10800 10842 10843 -f 10800 10843 10844 -f 10843 10759 10844 -f 10844 10759 10845 -f 10759 10846 10845 -f 10845 10846 10847 -f 10846 10782 10847 -f 10847 10782 10799 -f 10848 10738 10849 -f 10849 10738 10740 -f 10850 10856 10851 -f 10851 10856 10754 -f 10851 10754 10852 -f 10852 10754 10753 -f 10852 10753 10735 -f 10735 10753 10854 -f 10735 10854 10853 -f 10853 10854 10755 -f 10853 10755 10742 -f 10742 10755 10855 -f 10742 10855 10739 -f 10739 10855 10850 -f 10850 10855 10856 -f 10857 10866 10744 -f 10744 10866 10858 -f 10744 10858 10859 -f 10859 10858 10860 -f 10859 10860 10732 -f 10732 10860 10861 -f 10861 10860 10748 -f 10861 10748 10862 -f 10862 10748 10863 -f 10862 10863 10864 -f 10864 10863 10741 -f 10741 10863 10752 -f 10741 10752 10865 -f 10741 10865 10857 -f 10857 10865 10866 -f 10868 10921 10935 -f 10867 10935 10915 -f 10867 10915 10868 -f 10921 10868 10915 -f 10921 10917 10925 -f 10933 10929 10879 -f 10870 10883 10877 -f 10870 10877 10928 -f 10880 10871 10882 -f 10880 10882 10933 -f 10928 10872 10874 -f 10881 10871 10872 -f 10875 10883 10870 -f 10880 10879 10871 -f 10869 10870 10928 -f 10917 10935 10925 -f 10869 10928 10874 -f 10873 10872 10871 -f 10870 10869 10878 -f 10878 10869 10874 -f 10876 10871 10879 -f 10932 10931 10879 -f 10877 10886 10875 -f 10879 10874 10872 -f 10879 10872 10873 -f 10873 10871 10876 -f 10880 10878 10874 -f 10882 10876 10879 -f 10882 10879 10931 -f 10876 10881 10873 -f 10879 10880 10874 -f 10884 10886 10877 -f 10875 10870 10878 -f 10873 10881 10933 -f 10873 10933 10879 -f 10877 10875 10878 -f 10882 10881 10876 -f 10930 10882 10931 -f 10880 10928 10878 -f 10882 10871 10881 -f 10893 10884 10883 -f 10883 10884 10877 -f 10872 10933 10881 -f 10877 10878 10928 -f 10928 10880 10872 -f 10886 10883 10875 -f 10885 10890 10888 -f 10896 10890 10885 -f 10891 10889 10893 -f 10886 10893 10883 -f 10887 10892 10888 -f 10887 10888 10891 -f 10893 10889 10884 -f 10884 10891 10886 -f 10891 10888 10889 -f 10886 10891 10893 -f 10888 10896 10889 -f 10889 10885 10892 -f 10889 10887 10884 -f 10892 10885 10888 -f 10889 10892 10887 -f 10896 10895 10890 -f 10896 10885 10889 -f 10884 10887 10891 -f 10907 10899 10894 -f 10896 10902 10895 -f 10909 10898 10901 -f 10900 10911 10903 -f 10894 10895 10902 -f 10897 10905 10900 -f 10901 10907 10904 -f 10905 10908 10900 -f 10899 10909 10901 -f 10903 10911 10897 -f 10906 10900 10909 -f 10894 10899 10895 -f 10900 10903 10898 -f 10898 10903 10906 -f 10895 10899 10904 -f 10904 10894 10902 -f 10890 10902 10888 -f 10898 10906 10901 -f 10899 10901 10904 -f 10902 10896 10888 -f 10895 10904 10890 -f 10911 10905 10897 -f 10901 10906 10907 -f 10907 10909 10899 -f 10904 10902 10890 -f 10906 10909 10907 -f 10904 10907 10894 -f 10900 10908 10911 -f 10903 10897 10906 -f 10918 10919 10923 -f 10909 10900 10898 -f 10918 10923 10920 -f 10913 10924 10910 -f 10913 10926 10911 -f 10897 10900 10906 -f 10923 10921 10920 -f 10920 10921 10927 -f 10911 10926 10905 -f 10921 10915 10914 -f 10922 10916 10925 -f 10919 10912 10923 -f 10924 10920 10927 -f 10926 10913 10910 -f 10925 10916 10912 -f 10914 10917 10922 -f 10908 10926 10910 -f 10921 10919 10918 -f 10916 10914 10912 -f 10917 10921 10922 -f 10922 10921 10916 -f 10912 10922 10923 -f 10923 10935 10921 -f 10927 10918 10913 -f 10915 10917 10914 -f 10918 10924 10913 -f 10908 10913 10911 -f 10922 10925 10923 -f 10923 10925 10935 -f 10912 10914 10922 -f 10910 10927 10908 -f 10935 10917 10915 -f 10925 10919 10921 -f 10916 10921 10914 -f 10921 10918 10927 -f 10918 10920 10924 -f 10925 10912 10919 -f 10924 10927 10910 -f 10908 10927 10913 -f 10926 10908 10905 -f 10880 10933 10872 -f 10932 10879 10929 -f 10934 10933 10882 -f 10934 10882 10930 -f 10930 10931 10932 -f 10929 10933 10934 -f 10930 10932 10934 -f 10934 10932 10929 -f 10868 10935 10867 -f 10956 10992 10978 -f 10978 10992 10991 -f 10938 10940 10977 -f 10977 10940 10983 -f 10941 10988 10936 -f 10936 10988 10937 -f 10936 10937 10940 -f 10940 10937 10983 -f 10941 10943 10988 -f 10988 10943 10981 -f 10938 10953 10939 -f 10938 10939 10945 -f 10938 10945 10940 -f 10946 10936 10940 -f 10940 10945 10946 -f 10946 10941 10936 -f 10946 10942 10941 -f 10941 10942 10943 -f 10943 10942 10944 -f 10944 10980 10986 -f 10944 10986 10943 -f 10945 10982 10946 -f 10946 10982 10987 -f 10946 10987 10942 -f 10942 10987 10980 -f 10942 10980 10944 -f 10945 10939 10982 -f 10982 10939 10976 -f 10953 10954 10976 -f 10953 10976 10939 -f 10961 10952 10960 -f 10952 10951 10963 -f 10963 10948 10952 -f 10952 10948 10960 -f 10947 10951 10948 -f 10967 10964 10985 -f 10985 10964 10949 -f 10965 10973 10949 -f 10965 10949 10964 -f 10948 10951 10973 -f 10973 10951 10972 -f 10950 10972 10952 -f 10952 10972 10951 -f 10952 10961 10950 -f 10950 10961 10975 -f 10977 10975 10938 -f 10938 10975 10961 -f 10938 10961 10953 -f 10953 10961 10958 -f 10953 10958 10954 -f 10954 10958 10955 -f 10956 10978 10959 -f 10979 10957 10959 -f 10979 10959 10978 -f 10955 10957 10979 -f 10959 10966 10956 -f 10957 10955 10958 -f 10957 10958 10961 -f 10957 10961 10960 -f 10957 10960 10962 -f 10960 10965 10962 -f 10957 10962 10959 -f 10963 10947 10948 -f 10960 10948 10965 -f 10948 10973 10965 -f 10964 10967 10965 -f 10965 10967 10968 -f 10962 10965 10968 -f 10966 10959 10970 -f 10959 10962 10970 -f 10966 10970 10974 -f 10968 10969 10962 -f 10967 10985 10968 -f 10968 10985 10984 -f 10969 10968 10984 -f 10962 10969 10970 -f 10970 10969 10974 -f 10966 10974 10971 -f 10972 10950 10973 -f 10973 10950 10975 -f 10977 10976 10954 -f 10975 10949 10973 -f 10982 10976 10977 -f 10974 10978 10971 -f 10971 10978 11010 -f 11010 10978 10991 -f 10954 10985 10977 -f 10977 10985 10949 -f 10977 10949 10975 -f 10978 10974 10969 -f 10978 10969 10979 -f 10979 10969 10955 -f 10986 10980 10981 -f 10981 10980 10988 -f 10982 10977 10983 -f 10982 10983 10987 -f 10955 10969 10984 -f 10955 10984 10985 -f 10955 10985 10954 -f 11010 10991 10989 -f 10983 10937 10987 -f 11010 10989 11030 -f 10980 10987 10988 -f 10988 10987 10937 -f 11017 11030 10989 -f 11017 10989 10990 -f 10990 10989 10991 -f 10990 10991 10992 -f 11006 11025 10995 -f 10995 11025 11003 -f 10995 11003 10999 -f 10997 10996 11021 -f 10997 11021 10994 -f 11013 11001 11000 -f 11013 11000 10993 -f 10993 11000 10998 -f 10993 10998 11014 -f 11014 10998 10997 -f 11014 10997 10994 -f 10996 10997 10998 -f 10996 10998 11000 -f 11009 10999 10996 -f 11009 10996 11000 -f 11009 11000 11001 -f 11003 11005 11027 -f 11027 11005 11026 -f 11002 11063 11004 -f 11003 11006 10995 -f 11004 11005 11007 -f 11007 11005 11003 -f 11003 10995 11007 -f 10995 10999 11007 -f 11007 10999 11009 -f 11009 11001 11011 -f 11010 11015 11008 -f 11011 11001 11010 -f 11010 11001 11013 -f 11010 11013 11015 -f 11007 11009 11011 -f 11018 11012 11008 -f 11008 11015 11018 -f 11014 10994 10993 -f 11029 11018 10993 -f 11013 10993 11015 -f 11015 10993 11018 -f 10993 10994 11029 -f 11016 11018 11017 -f 11017 11018 11019 -f 11018 11029 11019 -f 11029 10994 11020 -f 11029 11020 11022 -f 11029 11022 11031 -f 10994 11021 11020 -f 11020 11021 11024 -f 11020 11024 11022 -f 11022 11024 11023 -f 11022 11023 11031 -f 11023 11024 10996 -f 11024 11021 10996 -f 10996 10999 11003 -f 11023 10996 11027 -f 11027 10996 11003 -f 11028 11027 11026 -f 11017 11019 11030 -f 11030 11029 11031 -f 11030 11031 11028 -f 11028 11031 11023 -f 11028 11023 11027 -f 11030 11019 11029 -f 11076 11039 11032 -f 11076 11032 11075 -f 11033 11034 11070 -f 11070 11034 11040 -f 11070 11040 11073 -f 11073 11040 11039 -f 11073 11039 11076 -f 11036 11037 11033 -f 11033 11037 11034 -f 11035 11060 11037 -f 11035 11037 11036 -f 11037 11060 11038 -f 11034 11037 11038 -f 11034 11038 11045 -f 11034 11045 11040 -f 11042 11039 11041 -f 11045 11043 11040 -f 11042 11032 11039 -f 11039 11040 11041 -f 11040 11043 11041 -f 11075 11042 11072 -f 11072 11042 11041 -f 11072 11041 11044 -f 11044 11041 11043 -f 11044 11043 11069 -f 11069 11043 11045 -f 11069 11045 11065 -f 11065 11045 11038 -f 11049 11046 11047 -f 11049 11068 11048 -f 11054 11047 11046 -f 11049 11047 11059 -f 11056 11047 11085 -f 11056 11085 11050 -f 11056 11050 11058 -f 11047 11056 11059 -f 11084 11085 11058 -f 11051 11054 11066 -f 11066 11054 11052 -f 11053 11085 11051 -f 11051 11085 11054 -f 11057 11058 11053 -f 11053 11058 11085 -f 11058 11055 11056 -f 11057 11055 11058 -f 11064 11059 11055 -f 11055 11059 11056 -f 11060 11035 11062 -f 11059 11064 11065 -f 11065 11038 11059 -f 11059 11038 11060 -f 11059 11060 11049 -f 11049 11060 11062 -f 11061 11048 11068 -f 11049 11062 11068 -f 11074 11063 11061 -f 11061 11063 11048 -f 11026 11005 11028 -f 11028 11005 11071 -f 11005 11004 11071 -f 11071 11004 11074 -f 11063 11074 11004 -f 11055 11057 11064 -f 11064 11057 11053 -f 11064 11051 11065 -f 11065 11051 11066 -f 11065 11066 11035 -f 11064 11053 11051 -f 11066 11062 11035 -f 11065 11035 11036 -f 11066 11067 11062 -f 11062 11067 11068 -f 11068 11067 11077 -f 11065 11036 11033 -f 11065 11033 11069 -f 11069 11033 11070 -f 11070 11044 11069 -f 11011 11028 11071 -f 11070 11072 11044 -f 11011 11071 11074 -f 11070 11073 11072 -f 11072 11073 11075 -f 11075 11073 11076 -f 11068 11077 11061 -f 11061 11077 11079 -f 11061 11079 11078 -f 11061 11078 11074 -f 11074 11078 11011 -f 11052 11083 11066 -f 11066 11083 11067 -f 11067 11082 11077 -f 11077 11081 11079 -f 11080 11078 11079 -f 11082 11067 11083 -f 11077 11082 11081 -f 11079 11081 11080 -f 11080 11081 11082 -f 11080 11082 11083 -f 11083 11054 11046 -f 11054 11083 11052 -f 11085 11084 11050 -f 11054 11085 11047 -f 11090 11116 11093 -f 11093 11116 11112 -f 11115 11087 11086 -f 11086 11087 11094 -f 11086 11094 11113 -f 11113 11094 11093 -f 11113 11093 11112 -f 11106 11095 11115 -f 11115 11095 11087 -f 11104 11103 11090 -f 11090 11103 11102 -f 11090 11102 11099 -f 11090 11099 11121 -f 11121 11099 11097 -f 11121 11097 11091 -f 11093 11088 11092 -f 11093 11092 11090 -f 11090 11092 11104 -f 11095 11104 11096 -f 11089 11087 11096 -f 11093 11094 11088 -f 11088 11094 11089 -f 11089 11094 11087 -f 11092 11096 11104 -f 11087 11095 11096 -f 11098 11097 11099 -f 11098 11099 11100 -f 11100 11099 11102 -f 11100 11102 11101 -f 11101 11102 11103 -f 11101 11103 11109 -f 11109 11103 11104 -f 11109 11104 11105 -f 11105 11104 11106 -f 11106 11104 11095 -f 11107 11110 11116 -f 11107 11116 11117 -f 11110 11112 11116 -f 11101 11109 11111 -f 11114 11115 11108 -f 11115 11086 11108 -f 11108 11086 11113 -f 11105 11111 11109 -f 11107 11098 11110 -f 11110 11098 11100 -f 11110 11100 11111 -f 11111 11100 11101 -f 11112 11108 11113 -f 11106 11114 11105 -f 11105 11114 11111 -f 11114 11106 11115 -f 11116 11090 11117 -f 11117 11090 11121 -f 11117 11121 11120 -f 11144 11136 11123 -f 11123 11136 11133 -f 11121 11123 11118 -f 11118 11119 11121 -f 11121 11119 11120 -f 11123 11122 11118 -f 11133 11122 11123 -f 11154 11132 11131 -f 11154 11131 11156 -f 11156 11131 11130 -f 11156 11130 11147 -f 11147 11130 11124 -f 11147 11124 11145 -f 11145 11124 11129 -f 11145 11129 11152 -f 11152 11129 11125 -f 11125 11129 11126 -f 11125 11126 11127 -f 11127 11126 11139 -f 11129 11124 11136 -f 11136 11124 11130 -f 11136 11130 11131 -f 11136 11131 11133 -f 11133 11131 11132 -f 11133 11132 11134 -f 11138 11128 11137 -f 11138 11137 11136 -f 11128 11138 11141 -f 11136 11137 11129 -f 11126 11129 11140 -f 11135 11139 11140 -f 11128 11141 11135 -f 11137 11140 11129 -f 11139 11126 11140 -f 11127 11139 11135 -f 11127 11135 11149 -f 11149 11135 11141 -f 11149 11141 11153 -f 11153 11141 11138 -f 11153 11138 11142 -f 11136 11144 11138 -f 11138 11144 11142 -f 11143 11155 11144 -f 11143 11144 11123 -f 11155 11148 11144 -f 11144 11148 11142 -f 11152 11146 11145 -f 11145 11146 11147 -f 11142 11148 11153 -f 11127 11149 11150 -f 11150 11125 11127 -f 11125 11150 11151 -f 11125 11151 11152 -f 11152 11151 11146 -f 11150 11149 11153 -f 11150 11153 11148 -f 11143 11154 11155 -f 11155 11154 11156 -f 11155 11156 11146 -f 11146 11156 11147 -f 11161 11159 11200 -f 11200 11159 11157 -f 11159 11160 11157 -f 11157 11160 11158 -f 11159 11161 11160 -f 11160 11161 11163 -f 11162 11204 11163 -f 11163 11204 11164 -f 11164 11206 11163 -f 11163 11206 11207 -f 11163 11207 11160 -f 11165 11216 11226 -f 11226 11216 11218 -f 11226 11218 11217 -f 11226 11217 11166 -f 11217 11211 11166 -f 11166 11211 11168 -f 11166 11168 11167 -f 11167 11168 11198 -f 11169 11232 11167 -f 11167 11232 11166 -f 11169 11167 11173 -f 11170 11171 11169 -f 11199 11177 11174 -f 11171 11172 11169 -f 11169 11172 11176 -f 11174 11181 11178 -f 11169 11173 11209 -f 11199 11174 11178 -f 11170 11169 11175 -f 11175 11169 11209 -f 11175 11209 11180 -f 11169 11176 11199 -f 11199 11176 11177 -f 11183 11179 11209 -f 11209 11179 11180 -f 11178 11181 11182 -f 11178 11182 11209 -f 11209 11182 11183 -f 11173 11167 11198 -f 11192 11186 11168 -f 11168 11186 11185 -f 11192 11193 11186 -f 11194 11195 11198 -f 11187 11189 11188 -f 11188 11189 11190 -f 11188 11190 11191 -f 11188 11191 11192 -f 11192 11191 11193 -f 11168 11185 11194 -f 11168 11194 11198 -f 11195 11196 11198 -f 11198 11196 11197 -f 11188 11184 11187 -f 11187 11184 11197 -f 11197 11184 11198 -f 11198 11184 11173 -f 11188 11192 11213 -f 11213 11192 11212 -f 11199 11168 11228 -f 11228 11168 11211 -f 11228 11211 11227 -f 11227 11211 11212 -f 11227 11212 11178 -f 11178 11212 11192 -f 11178 11192 11199 -f 11199 11192 11168 -f 11202 11233 11227 -f 11202 11227 11163 -f 11163 11227 11178 -f 11163 11178 11209 -f 11161 11200 11163 -f 11163 11200 11202 -f 11200 11157 11158 -f 11203 11201 11202 -f 11202 11201 11205 -f 11202 11205 11210 -f 11200 11158 11202 -f 11202 11158 11208 -f 11202 11208 11203 -f 11162 11210 11205 -f 11162 11205 11204 -f 11204 11205 11201 -f 11204 11201 11164 -f 11164 11201 11203 -f 11164 11203 11206 -f 11206 11203 11208 -f 11206 11208 11207 -f 11207 11208 11158 -f 11207 11158 11160 -f 11162 11163 11209 -f 11216 11165 11213 -f 11213 11165 11233 -f 11173 11184 11209 -f 11209 11184 11188 -f 11209 11188 11162 -f 11162 11188 11213 -f 11162 11213 11210 -f 11210 11213 11233 -f 11210 11233 11202 -f 11211 11225 11223 -f 11211 11223 11212 -f 11212 11223 11215 -f 11212 11215 11213 -f 11217 11219 11214 -f 11217 11214 11211 -f 11211 11214 11225 -f 11215 11221 11213 -f 11220 11216 11213 -f 11220 11213 11221 -f 11218 11216 11220 -f 11218 11220 11217 -f 11217 11220 11219 -f 11235 11220 11221 -f 11235 11221 11236 -f 11236 11221 11215 -f 11236 11215 11223 -f 11236 11223 11229 -f 11229 11223 11222 -f 11222 11223 11225 -f 11222 11225 11224 -f 11224 11225 11231 -f 11231 11225 11214 -f 11231 11214 11230 -f 11230 11214 11219 -f 11230 11219 11234 -f 11234 11219 11235 -f 11235 11219 11220 -f 11165 11226 11232 -f 11227 11229 11222 -f 11227 11222 11228 -f 11232 11226 11166 -f 11228 11222 11224 -f 11236 11229 11227 -f 11228 11224 11231 -f 11233 11236 11227 -f 11234 11233 11230 -f 11230 11233 11165 -f 11230 11165 11231 -f 11231 11165 11232 -f 11231 11232 11228 -f 11234 11235 11233 -f 11233 11235 11236 -f 11169 11199 11232 -f 11232 11199 11228 -f 11376 11389 11462 -f 11462 11389 11428 -f 11428 11389 11391 -f 11428 11391 11441 -f 11441 11391 11386 -f 11441 11386 11439 -f 11386 11239 11439 -f 11439 11239 11237 -f 11381 11240 11425 -f 11381 11425 11415 -f 11415 11425 11424 -f 11415 11424 11238 -f 11238 11424 11413 -f 11413 11424 11237 -f 11413 11237 11239 -f 11381 11242 11240 -f 11240 11242 11241 -f 11416 11453 11241 -f 11416 11241 11242 -f 11416 11243 11453 -f 11453 11243 11451 -f 11417 11461 11243 -f 11243 11461 11451 -f 11244 11436 11434 -f 11244 11434 11456 -f 11244 11456 11245 -f 11245 11456 11458 -f 11245 11458 11417 -f 11417 11458 11461 -f 11271 11483 11468 -f 11271 11468 11246 -f 11246 11468 11466 -f 11462 11247 11248 -f 11462 11248 11249 -f 11249 11248 11266 -f 11249 11266 11463 -f 11463 11266 11466 -f 11466 11266 11246 -f 11281 11469 11250 -f 11250 11469 11478 -f 11250 11478 11284 -f 11284 11478 11251 -f 11284 11251 11252 -f 11252 11251 11253 -f 11252 11253 11254 -f 11254 11253 11481 -f 11254 11481 11285 -f 11285 11481 11482 -f 11255 11256 11257 -f 11257 11256 11258 -f 11257 11258 11474 -f 11257 11474 11277 -f 11277 11474 11473 -f 11277 11473 11273 -f 11273 11473 11470 -f 11273 11470 11274 -f 11274 11470 11280 -f 11280 11470 11281 -f 11281 11470 11469 -f 11255 11259 11256 -f 11256 11259 11260 -f 11260 11259 11476 -f 11476 11259 11261 -f 11476 11261 11475 -f 11475 11261 11472 -f 11472 11261 11275 -f 11472 11275 11262 -f 11262 11275 11263 -f 11262 11263 11264 -f 11262 11264 11471 -f 11471 11264 11279 -f 11471 11279 11477 -f 11246 11266 11296 -f 11247 11265 11292 -f 11292 11293 11247 -f 11247 11293 11267 -f 11296 11266 11295 -f 11295 11266 11267 -f 11266 11248 11267 -f 11267 11248 11247 -f 11272 11270 11483 -f 11296 11271 11246 -f 11268 11290 11271 -f 11268 11289 11290 -f 11271 11296 11268 -f 11268 11296 11289 -f 11269 11285 11290 -f 11290 11285 11270 -f 11290 11270 11272 -f 11290 11272 11271 -f 11271 11272 11483 -f 11274 11280 11264 -f 11264 11280 11279 -f 11273 11263 11275 -f 11273 11275 11277 -f 11263 11273 11264 -f 11264 11273 11274 -f 11276 11275 11261 -f 11261 11259 11276 -f 11276 11259 11255 -f 11276 11255 11278 -f 11275 11276 11277 -f 11277 11276 11278 -f 11277 11278 11257 -f 11255 11257 11278 -f 11279 11280 11281 -f 11279 11281 11282 -f 11282 11281 11250 -f 11282 11250 11283 -f 11283 11250 11284 -f 11283 11284 11286 -f 11286 11284 11252 -f 11286 11252 11269 -f 11269 11252 11254 -f 11269 11254 11285 -f 11290 11291 11269 -f 11269 11291 11287 -f 11269 11287 11286 -f 11286 11287 11480 -f 11286 11480 11283 -f 11283 11480 11479 -f 11283 11479 11282 -f 11282 11479 11288 -f 11282 11288 11279 -f 11279 11288 11477 -f 11291 11290 11289 -f 11292 11297 11464 -f 11292 11464 11293 -f 11293 11464 11294 -f 11293 11294 11267 -f 11267 11294 11295 -f 11467 11295 11294 -f 11465 11296 11467 -f 11467 11296 11295 -f 11465 11289 11296 -f 11292 11265 11297 -f 11374 11297 11372 -f 11372 11297 11347 -f 11365 11299 11298 -f 11298 11299 11333 -f 11303 11300 11301 -f 11303 11301 11378 -f 11378 11301 11302 -f 11300 11303 11304 -f 11304 11303 11360 -f 11304 11360 11336 -f 11336 11360 11355 -f 11336 11355 11327 -f 11355 11305 11327 -f 11327 11305 11340 -f 11340 11305 11307 -f 11340 11307 11306 -f 11307 11308 11306 -f 11306 11308 11309 -f 11309 11308 11364 -f 11309 11364 11310 -f 11310 11364 11311 -f 11310 11311 11339 -f 11339 11311 11365 -f 11339 11365 11298 -f 11328 11329 11314 -f 11335 11326 11340 -f 11336 11327 11326 -f 11312 11297 11265 -f 11312 11265 11341 -f 11523 11347 11312 -f 11312 11347 11297 -f 11315 11313 11317 -f 11328 11314 11315 -f 11315 11314 11504 -f 11315 11504 11313 -f 11322 11316 11313 -f 11313 11316 11317 -f 11340 11326 11327 -f 11319 11318 11321 -f 11319 11321 11320 -f 11321 11322 11320 -f 11265 11300 11304 -f 11313 11323 11322 -f 11322 11323 11324 -f 11322 11324 11320 -f 11320 11324 11325 -f 11523 11330 11347 -f 11347 11330 11346 -f 11328 11332 11329 -f 11329 11332 11333 -f 11329 11333 11330 -f 11330 11333 11346 -f 11310 11338 11331 -f 11331 11309 11310 -f 11332 11334 11333 -f 11333 11334 11343 -f 11309 11331 11306 -f 11306 11331 11335 -f 11306 11335 11340 -f 11342 11336 11326 -f 11337 11338 11298 -f 11298 11338 11339 -f 11339 11338 11310 -f 11325 11341 11320 -f 11320 11341 11265 -f 11320 11265 11342 -f 11342 11265 11304 -f 11342 11304 11336 -f 11333 11343 11344 -f 11333 11344 11298 -f 11298 11344 11337 -f 11337 11344 11318 -f 11337 11318 11319 -f 11333 11299 11345 -f 11333 11345 11346 -f 11346 11345 11372 -f 11372 11347 11346 -f 11353 11308 11307 -f 11353 11307 11362 -f 11366 11350 11367 -f 11365 11367 11348 -f 11352 11378 11375 -f 11349 11378 11359 -f 11359 11378 11354 -f 11367 11350 11351 -f 11367 11351 11370 -f 11367 11370 11352 -f 11359 11354 11363 -f 11355 11360 11361 -f 11361 11360 11349 -f 11364 11308 11363 -f 11365 11356 11357 -f 11378 11358 11354 -f 11308 11353 11359 -f 11308 11359 11363 -f 11378 11349 11360 -f 11378 11360 11303 -f 11355 11361 11305 -f 11305 11361 11362 -f 11305 11362 11307 -f 11363 11311 11364 -f 11365 11357 11366 -f 11365 11366 11367 -f 11348 11368 11365 -f 11365 11368 11299 -f 11372 11345 11369 -f 11369 11345 11299 -f 11369 11299 11368 -f 11370 11371 11352 -f 11352 11371 11378 -f 11378 11371 11358 -f 11356 11365 11363 -f 11363 11365 11311 -f 11372 11369 11373 -f 11372 11373 11374 -f 11374 11373 11375 -f 11374 11375 11378 -f 11418 11412 11420 -f 11420 11412 11376 -f 11420 11376 11377 -f 11377 11376 11374 -f 11377 11374 11302 -f 11302 11374 11378 -f 11417 11379 11412 -f 11380 11376 11383 -f 11390 11389 11380 -f 11380 11389 11376 -f 11412 11379 11385 -f 11412 11385 11376 -f 11395 11396 11392 -f 11394 11388 11381 -f 11381 11388 11242 -f 11242 11388 11382 -f 11242 11382 11416 -f 11411 11383 11384 -f 11384 11383 11376 -f 11384 11376 11385 -f 11393 11404 11386 -f 11389 11390 11391 -f 11395 11386 11390 -f 11390 11386 11391 -f 11395 11392 11386 -f 11386 11392 11393 -f 11398 11394 11387 -f 11395 11397 11396 -f 11398 11387 11399 -f 11398 11399 11384 -f 11407 11400 11403 -f 11396 11397 11402 -f 11396 11402 11401 -f 11401 11402 11400 -f 11399 11403 11384 -f 11386 11404 11405 -f 11386 11405 11239 -f 11239 11405 11406 -f 11394 11381 11387 -f 11407 11408 11400 -f 11400 11408 11401 -f 11400 11409 11403 -f 11403 11409 11410 -f 11403 11410 11384 -f 11384 11410 11411 -f 11412 11244 11245 -f 11412 11245 11417 -f 11406 11414 11239 -f 11239 11414 11413 -f 11413 11414 11238 -f 11381 11415 11387 -f 11387 11415 11414 -f 11414 11415 11238 -f 11417 11416 11382 -f 11417 11243 11416 -f 11412 11418 11244 -f 11244 11418 11419 -f 11244 11419 11436 -f 11418 11420 11419 -f 11419 11420 11422 -f 11420 11377 11422 -f 11422 11377 11421 -f 11377 11302 11421 -f 11421 11302 11301 -f 11301 11300 11421 -f 11421 11300 11265 -f 11421 11265 11422 -f 11422 11265 11423 -f 11422 11423 11419 -f 11419 11423 11436 -f 11435 11436 11432 -f 11237 11430 11426 -f 11425 11449 11437 -f 11437 11424 11425 -f 11237 11426 11439 -f 11426 11427 11439 -f 11439 11427 11438 -f 11428 11442 11462 -f 11462 11442 11429 -f 11462 11429 11423 -f 11425 11240 11449 -f 11237 11437 11430 -f 11443 11440 11439 -f 11423 11429 11431 -f 11423 11431 11436 -f 11436 11431 11432 -f 11433 11434 11435 -f 11435 11434 11436 -f 11448 11240 11241 -f 11448 11241 11454 -f 11442 11428 11441 -f 11442 11441 11440 -f 11437 11237 11424 -f 11444 11443 11439 -f 11444 11439 11438 -f 11439 11440 11441 -f 11443 11444 11445 -f 11445 11444 11446 -f 11445 11446 11447 -f 11445 11447 11433 -f 11433 11447 11455 -f 11433 11456 11434 -f 11240 11448 11450 -f 11240 11450 11449 -f 11452 11460 11459 -f 11451 11452 11453 -f 11453 11452 11454 -f 11453 11454 11241 -f 11433 11455 11456 -f 11456 11455 11457 -f 11456 11457 11460 -f 11456 11460 11458 -f 11460 11452 11451 -f 11460 11451 11458 -f 11450 11459 11449 -f 11449 11459 11460 -f 11451 11461 11458 -f 11423 11247 11462 -f 11462 11249 11376 -f 11376 11249 11374 -f 11294 11463 11466 -f 11467 11294 11466 -f 11463 11294 11374 -f 11463 11374 11249 -f 11294 11464 11374 -f 11374 11464 11297 -f 11466 11465 11467 -f 11468 11483 11482 -f 11466 11468 11291 -f 11289 11465 11291 -f 11291 11465 11466 -f 11291 11468 11482 -f 11291 11482 11287 -f 11477 11478 11469 -f 11477 11469 11471 -f 11469 11470 11471 -f 11471 11470 11473 -f 11473 11472 11262 -f 11473 11262 11471 -f 11258 11256 11474 -f 11474 11256 11260 -f 11474 11260 11475 -f 11475 11472 11474 -f 11474 11472 11473 -f 11260 11476 11475 -f 11477 11288 11478 -f 11478 11288 11479 -f 11478 11479 11251 -f 11251 11479 11480 -f 11251 11480 11253 -f 11253 11480 11287 -f 11253 11287 11481 -f 11481 11287 11482 -f 11285 11482 11270 -f 11270 11482 11483 -f 11523 11526 11484 -f 11484 11526 11528 -f 11484 11528 11485 -f 11485 11528 11486 -f 11485 11486 11487 -f 11487 11486 11527 -f 11487 11527 11488 -f 11488 11527 11490 -f 11488 11490 11489 -f 11489 11490 11491 -f 11489 11491 11492 -f 11492 11491 11529 -f 11492 11529 11493 -f 11493 11529 11494 -f 11493 11494 11495 -f 11495 11494 11496 -f 11495 11496 11497 -f 11497 11496 11498 -f 11497 11498 11499 -f 11499 11498 11500 -f 11499 11500 11501 -f 11501 11500 11503 -f 11501 11503 11502 -f 11502 11503 11532 -f 11502 11532 11504 -f 11504 11532 11531 -f 11504 11531 11505 -f 11505 11531 11530 -f 11505 11530 11506 -f 11506 11530 11508 -f 11506 11508 11507 -f 11507 11508 11533 -f 11507 11533 11509 -f 11509 11533 11510 -f 11509 11510 11511 -f 11511 11510 11512 -f 11511 11512 11513 -f 11513 11512 11514 -f 11513 11514 11515 -f 11515 11514 11516 -f 11515 11516 11517 -f 11517 11516 11534 -f 11517 11534 11518 -f 11518 11534 11519 -f 11518 11519 11520 -f 11520 11519 11535 -f 11520 11535 11521 -f 11521 11535 11524 -f 11521 11524 11522 -f 11522 11524 11525 -f 11522 11525 11523 -f 11523 11525 11526 -f 11525 11524 11529 -f 11525 11529 11526 -f 11527 11486 11529 -f 11529 11486 11528 -f 11529 11528 11526 -f 11529 11491 11490 -f 11529 11490 11527 -f 11498 11496 11529 -f 11529 11496 11494 -f 11532 11503 11529 -f 11529 11503 11500 -f 11529 11500 11498 -f 11508 11530 11529 -f 11529 11530 11531 -f 11529 11531 11532 -f 11512 11510 11529 -f 11529 11510 11533 -f 11529 11533 11508 -f 11534 11516 11529 -f 11529 11516 11514 -f 11529 11514 11512 -f 11524 11535 11529 -f 11529 11535 11519 -f 11529 11519 11534 -f 11540 11557 11561 -f 11540 11561 11545 -f 11545 11561 11543 -f 11543 11561 11562 -f 11540 11542 11557 -f 11557 11542 11558 -f 11580 11579 11542 -f 11542 11579 11558 -f 11580 11542 11536 -f 11580 11536 11537 -f 11580 11537 11610 -f 11544 11541 11540 -f 11538 11554 11610 -f 11538 11610 11537 -f 11554 11538 11539 -f 11544 11540 11545 -f 11540 11541 11542 -f 11542 11541 11536 -f 11554 11539 11543 -f 11539 11544 11543 -f 11544 11545 11543 -f 11646 11631 11547 -f 11547 11631 11635 -f 11548 11646 11546 -f 11546 11646 11547 -f 11657 11548 11604 -f 11604 11548 11546 -f 11657 11604 11549 -f 11549 11604 11608 -f 11549 11608 11550 -f 11549 11550 11551 -f 11551 11550 11552 -f 11551 11552 11655 -f 11655 11552 11553 -f 11553 11552 11601 -f 11553 11601 11555 -f 11543 11562 11554 -f 11554 11562 11555 -f 11554 11555 11601 -f 11559 11558 11579 -f 11556 11557 11559 -f 11559 11557 11558 -f 11560 11563 11555 -f 11556 11562 11561 -f 11564 11648 11563 -f 11556 11561 11557 -f 11562 11556 11560 -f 11562 11560 11555 -f 11555 11563 11648 -f 11648 11564 11579 -f 11579 11564 11559 -f 11575 11565 11582 -f 11575 11582 11566 -f 11575 11569 11565 -f 11565 11569 11587 -f 11567 11590 11577 -f 11577 11590 11568 -f 11577 11568 11587 -f 11577 11587 11569 -f 11572 11578 11573 -f 11576 11575 11566 -f 11574 11567 11577 -f 11567 11574 11570 -f 11567 11570 11571 -f 11570 11572 11571 -f 11571 11572 11573 -f 11574 11569 11576 -f 11576 11569 11575 -f 11574 11577 11569 -f 11573 11578 11566 -f 11566 11578 11576 -f 11579 11580 11648 -f 11648 11580 11610 -f 11648 11610 11581 -f 11581 11610 11573 -f 11581 11573 11582 -f 11582 11573 11566 -f 11582 11583 11584 -f 11582 11584 11581 -f 11583 11582 11565 -f 11581 11584 11585 -f 11589 11586 11587 -f 11581 11585 11645 -f 11645 11585 11588 -f 11589 11587 11568 -f 11587 11586 11565 -f 11565 11586 11583 -f 11645 11588 11590 -f 11588 11589 11590 -f 11589 11568 11590 -f 11590 11567 11645 -f 11645 11567 11571 -f 11645 11571 11599 -f 11645 11599 11647 -f 11647 11599 11611 -f 11647 11611 11591 -f 11591 11611 11606 -f 11591 11606 11605 -f 11591 11605 11658 -f 11658 11605 11618 -f 11658 11618 11592 -f 11592 11618 11649 -f 11649 11618 11620 -f 11593 11649 11594 -f 11594 11649 11620 -f 11623 11593 11615 -f 11615 11593 11594 -f 11651 11616 11614 -f 11651 11614 11595 -f 11595 11614 11607 -f 11595 11607 11596 -f 11596 11607 11600 -f 11596 11600 11662 -f 11662 11600 11597 -f 11597 11600 11613 -f 11597 11613 11598 -f 11598 11613 11612 -f 11598 11612 11621 -f 11598 11621 11659 -f 11659 11621 11652 -f 11652 11621 11617 -f 11652 11617 11650 -f 11650 11617 11616 -f 11650 11616 11651 -f 11599 11571 11573 -f 11610 11611 11573 -f 11573 11611 11599 -f 11554 11601 11610 -f 11601 11552 11610 -f 11610 11552 11635 -f 11635 11552 11550 -f 11602 11604 11546 -f 11602 11546 11671 -f 11639 11618 11605 -f 11639 11605 11635 -f 11635 11605 11610 -f 11610 11605 11606 -f 11620 11600 11594 -f 11594 11600 11607 -f 11615 11616 11617 -f 11635 11550 11608 -f 11635 11664 11547 -f 11547 11664 11609 -f 11610 11606 11611 -f 11620 11612 11613 -f 11620 11613 11600 -f 11607 11614 11594 -f 11594 11614 11616 -f 11594 11616 11615 -f 11639 11615 11618 -f 11618 11615 11621 -f 11618 11621 11620 -f 11620 11621 11612 -f 11603 11666 11608 -f 11608 11666 11635 -f 11635 11666 11664 -f 11609 11619 11547 -f 11547 11619 11546 -f 11546 11619 11671 -f 11617 11621 11615 -f 11602 11669 11604 -f 11608 11622 11603 -f 11604 11669 11622 -f 11604 11622 11608 -f 11653 11623 11639 -f 11639 11623 11615 -f 11642 11638 11633 -f 11633 11638 11637 -f 11642 11633 11624 -f 11624 11633 11625 -f 11624 11625 11641 -f 11641 11625 11628 -f 11626 11641 11627 -f 11627 11641 11628 -f 11629 11626 11630 -f 11630 11626 11627 -f 11631 11632 11635 -f 11625 11634 11628 -f 11632 11633 11637 -f 11630 11627 11634 -f 11634 11627 11628 -f 11633 11632 11625 -f 11625 11632 11634 -f 11637 11636 11632 -f 11632 11636 11635 -f 11644 11635 11636 -f 11644 11636 11643 -f 11643 11636 11637 -f 11643 11637 11638 -f 11654 11653 11644 -f 11644 11653 11639 -f 11644 11639 11635 -f 11641 11626 11629 -f 11629 11640 11641 -f 11641 11640 11624 -f 11624 11640 11654 -f 11624 11654 11642 -f 11642 11654 11638 -f 11638 11654 11643 -f 11643 11654 11644 -f 11631 11549 11551 -f 11553 11555 11648 -f 11665 11657 11549 -f 11581 11645 11647 -f 11581 11647 11648 -f 11648 11647 11591 -f 11653 11652 11623 -f 11623 11652 11650 -f 11596 11662 11649 -f 11650 11651 11623 -f 11623 11651 11593 -f 11593 11651 11595 -f 11657 11668 11548 -f 11646 11665 11549 -f 11646 11549 11631 -f 11659 11652 11648 -f 11648 11652 11653 -f 11631 11551 11653 -f 11653 11551 11655 -f 11653 11655 11648 -f 11648 11655 11553 -f 11668 11656 11548 -f 11596 11649 11593 -f 11596 11593 11595 -f 11665 11667 11657 -f 11657 11667 11660 -f 11657 11660 11668 -f 11656 11670 11548 -f 11591 11658 11648 -f 11648 11658 11659 -f 11659 11658 11592 -f 11592 11597 11598 -f 11592 11598 11659 -f 11646 11663 11661 -f 11646 11661 11665 -f 11649 11662 11597 -f 11649 11597 11592 -f 11548 11670 11663 -f 11548 11663 11646 -f 11663 11619 11609 -f 11663 11609 11661 -f 11661 11609 11664 -f 11661 11664 11665 -f 11665 11664 11666 -f 11665 11666 11603 -f 11665 11603 11667 -f 11667 11603 11660 -f 11660 11603 11622 -f 11660 11622 11668 -f 11668 11622 11669 -f 11668 11669 11602 -f 11668 11602 11656 -f 11656 11602 11671 -f 11656 11671 11670 -f 11670 11671 11619 -f 11670 11619 11663 -f 11672 11674 11675 -f 11673 11675 11674 -f 11676 11737 11677 -f 11677 11737 11678 -f 11677 11678 11679 -f 11679 11678 11681 -f 11679 11681 11680 -f 11680 11681 11682 -f 11680 11682 11684 -f 11684 11682 11683 -f 11684 11683 11686 -f 11686 11683 11685 -f 11686 11685 11687 -f 11687 11685 11689 -f 11687 11689 11688 -f 11688 11689 11691 -f 11688 11691 11690 -f 11690 11691 11692 -f 11690 11692 11693 -f 11693 11692 11694 -f 11693 11694 11695 -f 11695 11694 11696 -f 11695 11696 11698 -f 11698 11696 11697 -f 11698 11697 11699 -f 11699 11697 11700 -f 11699 11700 11701 -f 11701 11700 11703 -f 11701 11703 11702 -f 11702 11703 11705 -f 11702 11705 11704 -f 11704 11705 11706 -f 11704 11706 11707 -f 11707 11706 11708 -f 11707 11708 11709 -f 11709 11708 11710 -f 11709 11710 11711 -f 11711 11710 11712 -f 11711 11712 11713 -f 11713 11712 11714 -f 11713 11714 11715 -f 11715 11714 11717 -f 11715 11717 11716 -f 11716 11717 11718 -f 11716 11718 11720 -f 11720 11718 11719 -f 11720 11719 11721 -f 11721 11719 11722 -f 11721 11722 11723 -f 11723 11722 11725 -f 11723 11725 11724 -f 11724 11725 11726 -f 11724 11726 11727 -f 11727 11726 11729 -f 11727 11729 11728 -f 11728 11729 11730 -f 11728 11730 11731 -f 11731 11730 11733 -f 11731 11733 11732 -f 11732 11733 11734 -f 11732 11734 11735 -f 11735 11734 11736 -f 11735 11736 11676 -f 11676 11736 11737 -f 11738 11741 11739 -f 11741 11740 11739 -f 11742 11743 11745 -f 11743 11744 11745 -f 11746 11745 11744 -f 11748 11747 11749 -f 11747 11751 11749 -f 11750 11749 11751 -f 11748 11749 11750 -f 11754 11753 11752 -f 11752 11757 11754 -f 11755 11753 11754 -f 11754 11757 11756 -f 11756 11757 11752 -f 11762 11761 11760 -f 11759 11760 11758 -f 11758 11760 11761 -f 11763 11836 11764 -f 11764 11836 11766 -f 11764 11766 11765 -f 11765 11766 11767 -f 11765 11767 11769 -f 11769 11767 11768 -f 11769 11768 11770 -f 11770 11768 11771 -f 11770 11771 11773 -f 11773 11771 11772 -f 11773 11772 11774 -f 11774 11772 11775 -f 11774 11775 11776 -f 11776 11775 11778 -f 11776 11778 11777 -f 11777 11778 11779 -f 11777 11779 11780 -f 11780 11779 11781 -f 11780 11781 11782 -f 11782 11781 11783 -f 11782 11783 11785 -f 11785 11783 11784 -f 11785 11784 11786 -f 11786 11784 11788 -f 11786 11788 11787 -f 11787 11788 11789 -f 11787 11789 11790 -f 11790 11789 11791 -f 11790 11791 11792 -f 11792 11791 11793 -f 11792 11793 11794 -f 11794 11793 11795 -f 11794 11795 11796 -f 11796 11795 11797 -f 11796 11797 11798 -f 11798 11797 11799 -f 11798 11799 11801 -f 11801 11799 11800 -f 11801 11800 11802 -f 11802 11800 11804 -f 11802 11804 11803 -f 11803 11804 11806 -f 11803 11806 11805 -f 11805 11806 11808 -f 11805 11808 11807 -f 11807 11808 11809 -f 11807 11809 11810 -f 11810 11809 11811 -f 11810 11811 11813 -f 11813 11811 11812 -f 11813 11812 11814 -f 11814 11812 11816 -f 11814 11816 11815 -f 11815 11816 11817 -f 11815 11817 11818 -f 11818 11817 11820 -f 11818 11820 11819 -f 11819 11820 11821 -f 11819 11821 11822 -f 11822 11821 11824 -f 11822 11824 11823 -f 11823 11824 11825 -f 11823 11825 11826 -f 11826 11825 11827 -f 11826 11827 11828 -f 11828 11827 11830 -f 11828 11830 11829 -f 11829 11830 11832 -f 11829 11832 11831 -f 11831 11832 11834 -f 11831 11834 11833 -f 11833 11834 11835 -f 11833 11835 11763 -f 11763 11835 11836 -f 11838 11837 11840 -f 11839 11838 11840 -f 11837 11839 11840 -f 11839 11841 11838 -f 11851 11861 11850 -f 11850 11861 11862 -f 11850 11862 11852 -f 11852 11862 11863 -f 11963 11970 11843 -f 11971 11972 11846 -f 11843 11905 11842 -f 11846 11844 11971 -f 11971 11844 11905 -f 11971 11905 11843 -f 11845 11855 11960 -f 11842 11962 11963 -f 11842 11963 11843 -f 11845 11960 11962 -f 11962 11868 11845 -f 11842 11868 11962 -f 11856 11958 11855 -f 11846 11972 11974 -f 11976 11849 11974 -f 11974 11849 11848 -f 11963 11854 11970 -f 11851 11966 11847 -f 11847 11966 11957 -f 11847 11957 11958 -f 11856 11847 11958 -f 11855 11958 11960 -f 11974 11848 11846 -f 11849 11976 11852 -f 11850 11853 11851 -f 11976 11853 11850 -f 11854 11963 11965 -f 11852 11976 11850 -f 11851 11853 11854 -f 11854 11965 11966 -f 11854 11966 11851 -f 11855 11865 11856 -f 11856 11865 11860 -f 11856 11860 11847 -f 11855 11845 11865 -f 11865 11845 11869 -f 11858 11857 11867 -f 11857 11866 11964 -f 11964 11867 11857 -f 11859 11858 11876 -f 11859 11876 11934 -f 11876 11858 11867 -f 11863 11975 11933 -f 11859 11973 11858 -f 11860 11968 11967 -f 11860 11967 11861 -f 11867 11964 11961 -f 11867 11961 11864 -f 11862 11861 11977 -f 11865 11869 11959 -f 11975 11863 11977 -f 11977 11863 11862 -f 11933 11975 11973 -f 11973 11932 11933 -f 11859 11932 11973 -f 11869 11864 11961 -f 11869 11961 11959 -f 11865 11959 11968 -f 11857 11969 11967 -f 11967 11969 11861 -f 11861 11969 11977 -f 11968 11860 11865 -f 11967 11866 11857 -f 11842 11867 11864 -f 11842 11864 11868 -f 11868 11864 11869 -f 11868 11869 11845 -f 11955 11870 11897 -f 11897 11870 11953 -f 11897 11953 11871 -f 11897 11871 11872 -f 11872 11871 11952 -f 11872 11952 11873 -f 11873 11952 11874 -f 11873 11874 11875 -f 11875 11874 11950 -f 11875 11950 11899 -f 11867 11842 11876 -f 11876 11842 11905 -f 11876 11905 11935 -f 11935 11905 11904 -f 11935 11904 11936 -f 11936 11904 11895 -f 11888 11877 11878 -f 11878 11877 11879 -f 11878 11879 11901 -f 11901 11879 11880 -f 11901 11880 11881 -f 11881 11880 11945 -f 11881 11945 11882 -f 11950 11883 11899 -f 11899 11883 11885 -f 11899 11885 11884 -f 11884 11885 11949 -f 11884 11949 11886 -f 11886 11949 11887 -f 11886 11887 11888 -f 11888 11887 11889 -f 11888 11889 11877 -f 11945 11943 11882 -f 11882 11943 11942 -f 11882 11942 11890 -f 11890 11942 11892 -f 11890 11892 11891 -f 11891 11892 11893 -f 11891 11893 11894 -f 11894 11893 11939 -f 11894 11939 11895 -f 11895 11939 11937 -f 11895 11937 11936 -f 11906 11897 11896 -f 11896 11897 11872 -f 11896 11872 11898 -f 11898 11872 11873 -f 11898 11873 11913 -f 11913 11873 11875 -f 11913 11875 11900 -f 11900 11875 11899 -f 11900 11899 11909 -f 11909 11899 11884 -f 11909 11884 11917 -f 11917 11884 11886 -f 11917 11886 11916 -f 11916 11886 11888 -f 11916 11888 11925 -f 11925 11888 11878 -f 11925 11878 11924 -f 11924 11878 11901 -f 11924 11901 11922 -f 11922 11901 11881 -f 11922 11881 11921 -f 11921 11881 11882 -f 11921 11882 11930 -f 11930 11882 11890 -f 11930 11890 11902 -f 11902 11890 11891 -f 11902 11891 11903 -f 11903 11891 11894 -f 11903 11894 11929 -f 11929 11894 11895 -f 11929 11895 11915 -f 11915 11895 11904 -f 11915 11904 11844 -f 11844 11904 11905 -f 11954 11956 11907 -f 11907 11956 11906 -f 11907 11906 11908 -f 11908 11906 11896 -f 11909 11910 11900 -f 11900 11910 11911 -f 11900 11911 11913 -f 11913 11911 11912 -f 11913 11912 11898 -f 11898 11912 11951 -f 11898 11951 11896 -f 11896 11951 11914 -f 11896 11914 11908 -f 11846 11859 11844 -f 11844 11859 11934 -f 11844 11934 11915 -f 11925 11947 11916 -f 11916 11947 11948 -f 11916 11948 11917 -f 11917 11948 11918 -f 11917 11918 11909 -f 11909 11918 11919 -f 11909 11919 11910 -f 11930 11944 11921 -f 11921 11944 11920 -f 11921 11920 11922 -f 11922 11920 11923 -f 11922 11923 11924 -f 11924 11923 11946 -f 11924 11946 11925 -f 11925 11946 11926 -f 11925 11926 11947 -f 11934 11927 11915 -f 11915 11927 11928 -f 11915 11928 11929 -f 11929 11928 11938 -f 11929 11938 11903 -f 11903 11938 11940 -f 11903 11940 11902 -f 11902 11940 11941 -f 11902 11941 11930 -f 11930 11941 11931 -f 11930 11931 11944 -f 11849 11933 11932 -f 11849 11932 11848 -f 11848 11932 11859 -f 11848 11859 11846 -f 11933 11849 11863 -f 11863 11849 11852 -f 11934 11876 11935 -f 11934 11935 11927 -f 11927 11935 11936 -f 11927 11936 11928 -f 11928 11936 11937 -f 11928 11937 11938 -f 11938 11937 11939 -f 11938 11939 11940 -f 11940 11939 11893 -f 11940 11893 11941 -f 11941 11893 11892 -f 11941 11892 11931 -f 11931 11892 11942 -f 11931 11942 11944 -f 11944 11942 11943 -f 11944 11943 11920 -f 11920 11943 11945 -f 11920 11945 11923 -f 11923 11945 11880 -f 11923 11880 11946 -f 11946 11880 11879 -f 11946 11879 11926 -f 11926 11879 11877 -f 11926 11877 11947 -f 11947 11877 11889 -f 11947 11889 11948 -f 11948 11889 11887 -f 11948 11887 11918 -f 11918 11887 11949 -f 11918 11949 11919 -f 11919 11949 11885 -f 11919 11885 11910 -f 11910 11885 11883 -f 11910 11883 11911 -f 11911 11883 11950 -f 11911 11950 11912 -f 11912 11950 11874 -f 11912 11874 11951 -f 11951 11874 11952 -f 11951 11952 11914 -f 11914 11952 11871 -f 11914 11871 11908 -f 11908 11871 11953 -f 11908 11953 11907 -f 11953 11870 11907 -f 11907 11870 11954 -f 11870 11955 11954 -f 11954 11955 11956 -f 11955 11897 11956 -f 11956 11897 11906 -f 11861 11851 11860 -f 11860 11851 11847 -f 11957 11968 11958 -f 11958 11968 11959 -f 11958 11959 11960 -f 11960 11959 11961 -f 11960 11961 11962 -f 11962 11961 11964 -f 11962 11964 11963 -f 11963 11964 11866 -f 11963 11866 11965 -f 11965 11866 11966 -f 11966 11866 11967 -f 11966 11967 11957 -f 11957 11967 11968 -f 11853 11969 11854 -f 11854 11969 11970 -f 11970 11969 11857 -f 11970 11857 11843 -f 11843 11857 11858 -f 11843 11858 11971 -f 11971 11858 11972 -f 11972 11858 11973 -f 11972 11973 11974 -f 11974 11973 11976 -f 11976 11973 11975 -f 11976 11975 11977 -f 11976 11977 11853 -f 11853 11977 11969 -f 12050 12049 12027 -f 11980 12049 11978 -f 12050 12027 11978 -f 11978 12023 11980 -f 11980 11979 12027 -f 12027 12049 11980 -f 11980 12023 11979 -f 11989 11981 11997 -f 11982 12045 12047 -f 12006 11996 11981 -f 11981 11989 11991 -f 11982 11986 11984 -f 11981 11985 12006 -f 11982 11993 11986 -f 11989 11997 11988 -f 11988 11997 11983 -f 11985 11992 12000 -f 11985 11981 11991 -f 11990 11991 11989 -f 11987 11988 11983 -f 11987 11983 11984 -f 11995 11984 11986 -f 12046 11993 11982 -f 11982 11987 12046 -f 11992 11985 11996 -f 11996 11985 11991 -f 11987 11984 11995 -f 11994 11986 11993 -f 11990 11989 11988 -f 12047 11987 11995 -f 11995 11986 11994 -f 11993 12046 12045 -f 12046 12044 12045 -f 11993 12045 11994 -f 11996 11991 11990 -f 11990 11988 11982 -f 11998 12000 11992 -f 11992 12006 11998 -f 12047 11995 11982 -f 11990 11982 11997 -f 11990 11997 11981 -f 11990 11981 11996 -f 11992 11996 12006 -f 11983 11995 11994 -f 12048 12047 12045 -f 11997 11982 11983 -f 11983 11982 11995 -f 11983 11994 11984 -f 11982 11984 11994 -f 11982 11994 12045 -f 12004 12008 12002 -f 12004 12002 12001 -f 11985 12000 12006 -f 12006 11999 12004 -f 12006 12004 11998 -f 12002 12003 12001 -f 12004 12001 11998 -f 12003 12008 12001 -f 12001 12008 11999 -f 11998 11999 12000 -f 12008 12007 12002 -f 12010 12022 12005 -f 12003 12017 12008 -f 12002 12007 12003 -f 12016 12005 12018 -f 12017 12018 12020 -f 12008 12004 11999 -f 11998 12001 11999 -f 12000 11999 12006 -f 12022 12025 12005 -f 12005 12025 12015 -f 12008 12017 12007 -f 12019 12026 12012 -f 12019 12012 12013 -f 12005 12015 12018 -f 12018 12015 12020 -f 12010 12005 12020 -f 12020 12005 12016 -f 12016 12018 12017 -f 12012 12014 12024 -f 12017 12020 12007 -f 12026 12033 12012 -f 12007 12020 12016 -f 12012 12033 12014 -f 12011 12022 12010 -f 12015 12025 12010 -f 12007 12016 12003 -f 12024 12014 12026 -f 12024 12026 12019 -f 12015 12010 12020 -f 12003 12016 12017 -f 12013 12009 12011 -f 12013 12012 12024 -f 12013 12024 12009 -f 12022 12013 12025 -f 12034 12028 12033 -f 12014 12035 12026 -f 12033 12028 12014 -f 12009 12024 12019 -f 12011 12019 12022 -f 12009 12019 12011 -f 12022 12019 12013 -f 12013 12011 12025 -f 12032 12023 12021 -f 12025 12011 12010 -f 12023 12039 12031 -f 12023 12031 12021 -f 11979 12037 12029 -f 12021 12027 12040 -f 12034 12038 12028 -f 12041 12034 12035 -f 12039 12030 12029 -f 12027 12032 12040 -f 12032 12038 12041 -f 12036 12027 11979 -f 12027 12023 12032 -f 12039 12029 12037 -f 12039 12037 12031 -f 12021 12031 12027 -f 12032 12021 12038 -f 12035 12034 12033 -f 12031 11978 12027 -f 12038 12021 12040 -f 12038 12040 12028 -f 12030 12037 12036 -f 12031 12037 12030 -f 12031 12030 11978 -f 12030 12036 12029 -f 11979 12023 12037 -f 11978 12030 12039 -f 12037 12023 12027 -f 11978 12039 12023 -f 12014 12028 12035 -f 12026 12035 12033 -f 12037 12027 12036 -f 12041 12038 12034 -f 12029 12036 11979 -f 12028 12040 12032 -f 12028 12032 12041 -f 12035 12028 12041 -f 11987 11982 11988 -f 12042 11987 12047 -f 12042 12047 12043 -f 12043 12047 12048 -f 12048 12045 12044 -f 12046 12042 12044 -f 12046 11987 12042 -f 12048 12044 12042 -f 12048 12042 12043 -f 12050 11978 12049 -f 12075 12105 12090 -f 12090 12105 12104 -f 12052 12054 12093 -f 12093 12054 12099 -f 12055 12097 12101 -f 12055 12101 12051 -f 12051 12101 12099 -f 12051 12099 12054 -f 12055 12058 12097 -f 12097 12058 12096 -f 12052 12074 12053 -f 12052 12053 12060 -f 12052 12060 12054 -f 12051 12060 12056 -f 12056 12055 12051 -f 12054 12060 12051 -f 12055 12056 12059 -f 12055 12059 12058 -f 12058 12059 12057 -f 12057 12091 12058 -f 12060 12098 12056 -f 12056 12098 12102 -f 12056 12102 12103 -f 12056 12103 12059 -f 12059 12103 12057 -f 12057 12103 12091 -f 12060 12053 12098 -f 12098 12053 12089 -f 12074 12061 12089 -f 12074 12089 12053 -f 12072 12070 12079 -f 12070 12071 12062 -f 12062 12080 12070 -f 12080 12079 12070 -f 12063 12071 12069 -f 12063 12069 12080 -f 12084 12066 12085 -f 12085 12066 12092 -f 12065 12080 12064 -f 12065 12079 12080 -f 12079 12065 12081 -f 12081 12065 12092 -f 12081 12092 12066 -f 12080 12069 12064 -f 12064 12069 12068 -f 12067 12068 12070 -f 12070 12068 12069 -f 12069 12071 12070 -f 12070 12072 12067 -f 12067 12072 12073 -f 12093 12073 12052 -f 12052 12073 12072 -f 12052 12072 12074 -f 12074 12072 12077 -f 12074 12077 12061 -f 12061 12077 12076 -f 12076 12078 12095 -f 12075 12090 12095 -f 12095 12078 12075 -f 12078 12076 12077 -f 12078 12077 12072 -f 12078 12072 12079 -f 12083 12075 12078 -f 12079 12081 12078 -f 12078 12081 12083 -f 12062 12063 12080 -f 12066 12084 12081 -f 12086 12083 12084 -f 12083 12081 12084 -f 12087 12083 12086 -f 12075 12083 12082 -f 12075 12082 12088 -f 12084 12085 12086 -f 12087 12086 12085 -f 12083 12087 12094 -f 12088 12083 12094 -f 12088 12082 12083 -f 12068 12067 12064 -f 12064 12067 12073 -f 12065 12064 12073 -f 12093 12089 12061 -f 12098 12089 12093 -f 12088 12090 12126 -f 12126 12090 12104 -f 12061 12085 12093 -f 12093 12085 12092 -f 12093 12092 12073 -f 12073 12092 12065 -f 12090 12088 12094 -f 12090 12094 12095 -f 12095 12094 12087 -f 12095 12087 12076 -f 12096 12091 12103 -f 12096 12103 12097 -f 12098 12093 12099 -f 12076 12087 12085 -f 12076 12085 12061 -f 12104 12100 12126 -f 12099 12101 12098 -f 12098 12101 12102 -f 12126 12100 12141 -f 12102 12101 12097 -f 12097 12103 12102 -f 12130 12141 12100 -f 12130 12100 12105 -f 12105 12100 12104 -f 12111 12138 12121 -f 12121 12138 12117 -f 12121 12117 12123 -f 12109 12115 12134 -f 12109 12134 12110 -f 12110 12134 12133 -f 12106 12116 12113 -f 12106 12113 12107 -f 12107 12113 12112 -f 12107 12112 12108 -f 12108 12112 12109 -f 12108 12109 12110 -f 12115 12109 12112 -f 12115 12112 12113 -f 12114 12123 12115 -f 12114 12115 12113 -f 12114 12113 12116 -f 12117 12120 12140 -f 12140 12120 12119 -f 12176 12118 12120 -f 12117 12111 12121 -f 12122 12120 12117 -f 12117 12121 12122 -f 12122 12121 12123 -f 12122 12123 12114 -f 12114 12116 12125 -f 12126 12128 12124 -f 12125 12116 12126 -f 12126 12116 12106 -f 12126 12106 12128 -f 12122 12114 12125 -f 12124 12129 12127 -f 12108 12110 12107 -f 12107 12110 12133 -f 12128 12132 12129 -f 12128 12129 12124 -f 12106 12107 12128 -f 12128 12107 12132 -f 12107 12133 12135 -f 12132 12131 12129 -f 12129 12131 12130 -f 12132 12107 12135 -f 12131 12132 12135 -f 12131 12135 12142 -f 12133 12134 12135 -f 12135 12134 12139 -f 12135 12139 12137 -f 12135 12137 12136 -f 12135 12136 12142 -f 12136 12137 12115 -f 12137 12139 12115 -f 12139 12134 12115 -f 12115 12123 12117 -f 12115 12117 12140 -f 12136 12115 12140 -f 12143 12140 12119 -f 12130 12131 12141 -f 12141 12131 12142 -f 12141 12142 12143 -f 12143 12142 12136 -f 12143 12136 12140 -f 12189 12152 12155 -f 12187 12149 12154 -f 12187 12154 12186 -f 12186 12154 12153 -f 12186 12153 12189 -f 12189 12153 12152 -f 12146 12148 12187 -f 12187 12148 12149 -f 12145 12144 12148 -f 12145 12148 12146 -f 12148 12144 12147 -f 12152 12153 12150 -f 12149 12148 12147 -f 12149 12147 12159 -f 12150 12153 12156 -f 12159 12151 12149 -f 12149 12151 12154 -f 12156 12153 12154 -f 12154 12151 12156 -f 12155 12150 12157 -f 12157 12150 12156 -f 12157 12156 12158 -f 12158 12156 12151 -f 12158 12151 12185 -f 12185 12151 12159 -f 12185 12159 12179 -f 12179 12159 12147 -f 12160 12161 12175 -f 12162 12160 12163 -f 12200 12174 12197 -f 12197 12174 12161 -f 12197 12161 12164 -f 12167 12174 12201 -f 12167 12201 12165 -f 12174 12167 12172 -f 12166 12201 12167 -f 12167 12201 12173 -f 12173 12201 12171 -f 12181 12168 12192 -f 12192 12168 12198 -f 12169 12171 12201 -f 12169 12201 12182 -f 12182 12201 12200 -f 12200 12168 12182 -f 12168 12181 12182 -f 12170 12173 12169 -f 12169 12173 12171 -f 12167 12178 12172 -f 12170 12178 12173 -f 12173 12178 12167 -f 12180 12174 12178 -f 12178 12174 12172 -f 12144 12145 12183 -f 12174 12180 12179 -f 12179 12147 12174 -f 12174 12147 12144 -f 12174 12144 12161 -f 12161 12144 12183 -f 12160 12190 12163 -f 12190 12160 12184 -f 12184 12160 12175 -f 12184 12175 12183 -f 12161 12183 12175 -f 12188 12176 12190 -f 12190 12176 12163 -f 12119 12120 12143 -f 12143 12120 12177 -f 12120 12118 12177 -f 12177 12118 12188 -f 12176 12188 12118 -f 12178 12170 12180 -f 12180 12170 12169 -f 12180 12182 12181 -f 12180 12181 12179 -f 12179 12181 12192 -f 12179 12192 12145 -f 12169 12182 12180 -f 12192 12183 12145 -f 12145 12146 12179 -f 12192 12194 12183 -f 12183 12194 12184 -f 12184 12194 12196 -f 12184 12196 12190 -f 12179 12146 12187 -f 12179 12187 12185 -f 12186 12158 12187 -f 12187 12158 12185 -f 12125 12143 12177 -f 12186 12157 12158 -f 12125 12177 12188 -f 12157 12186 12155 -f 12155 12186 12189 -f 12190 12196 12191 -f 12190 12191 12188 -f 12188 12191 12125 -f 12198 12193 12192 -f 12192 12193 12194 -f 12194 12193 12197 -f 12194 12197 12196 -f 12196 12195 12191 -f 12199 12191 12195 -f 12195 12196 12197 -f 12200 12197 12193 -f 12200 12193 12168 -f 12168 12193 12198 -f 12201 12166 12165 -f 12200 12201 12174 -f 12235 12223 12210 -f 12210 12223 12202 -f 12233 12204 12227 -f 12227 12204 12213 -f 12227 12213 12228 -f 12228 12213 12212 -f 12228 12212 12202 -f 12202 12212 12210 -f 12221 12203 12233 -f 12233 12203 12204 -f 12205 12220 12235 -f 12235 12220 12218 -f 12235 12218 12206 -f 12235 12206 12240 -f 12240 12206 12207 -f 12240 12207 12208 -f 12210 12209 12211 -f 12210 12211 12235 -f 12215 12213 12204 -f 12209 12210 12212 -f 12235 12211 12205 -f 12203 12205 12214 -f 12209 12212 12213 -f 12209 12213 12215 -f 12211 12214 12205 -f 12204 12203 12215 -f 12215 12203 12214 -f 12216 12207 12206 -f 12216 12206 12217 -f 12217 12206 12218 -f 12217 12218 12219 -f 12219 12218 12220 -f 12219 12220 12226 -f 12226 12220 12205 -f 12226 12205 12232 -f 12232 12205 12221 -f 12221 12205 12203 -f 12222 12229 12223 -f 12222 12223 12224 -f 12229 12225 12223 -f 12223 12225 12202 -f 12219 12226 12230 -f 12234 12228 12225 -f 12233 12227 12234 -f 12234 12227 12228 -f 12221 12234 12231 -f 12232 12230 12226 -f 12222 12216 12229 -f 12229 12216 12217 -f 12229 12217 12230 -f 12230 12217 12219 -f 12202 12225 12228 -f 12221 12231 12232 -f 12232 12231 12230 -f 12234 12221 12233 -f 12223 12235 12224 -f 12224 12235 12240 -f 12224 12240 12239 -f 12236 12237 12241 -f 12241 12237 12248 -f 12240 12241 12238 -f 12238 12239 12240 -f 12248 12238 12241 -f 12272 12247 12246 -f 12272 12246 12274 -f 12274 12246 12245 -f 12274 12245 12262 -f 12262 12245 12242 -f 12262 12242 12260 -f 12260 12242 12243 -f 12243 12242 12244 -f 12243 12244 12268 -f 12268 12244 12257 -f 12268 12257 12266 -f 12266 12257 12255 -f 12266 12255 12259 -f 12259 12255 12252 -f 12244 12242 12237 -f 12237 12242 12245 -f 12237 12245 12246 -f 12237 12246 12248 -f 12248 12246 12247 -f 12248 12247 12249 -f 12253 12252 12256 -f 12250 12253 12251 -f 12250 12251 12237 -f 12253 12250 12258 -f 12237 12251 12244 -f 12257 12244 12254 -f 12256 12252 12255 -f 12253 12258 12252 -f 12251 12254 12244 -f 12256 12255 12257 -f 12256 12257 12254 -f 12259 12252 12269 -f 12269 12252 12258 -f 12269 12258 12263 -f 12263 12258 12250 -f 12237 12236 12250 -f 12250 12236 12263 -f 12271 12273 12236 -f 12271 12236 12241 -f 12273 12264 12236 -f 12236 12264 12263 -f 12268 12261 12243 -f 12243 12261 12260 -f 12260 12261 12262 -f 12263 12264 12270 -f 12265 12259 12269 -f 12265 12269 12270 -f 12265 12266 12259 -f 12266 12265 12267 -f 12266 12267 12268 -f 12268 12267 12261 -f 12270 12269 12263 -f 12271 12272 12273 -f 12273 12272 12274 -f 12273 12274 12261 -f 12261 12274 12262 -f 12321 12276 12325 -f 12325 12276 12275 -f 12276 12277 12275 -f 12275 12277 12326 -f 12276 12321 12277 -f 12277 12321 12278 -f 12331 12279 12278 -f 12278 12279 12280 -f 12280 12330 12278 -f 12278 12330 12281 -f 12278 12281 12277 -f 12282 12334 12347 -f 12347 12334 12283 -f 12347 12283 12336 -f 12347 12336 12285 -f 12336 12284 12285 -f 12285 12284 12304 -f 12285 12304 12286 -f 12286 12304 12317 -f 12289 12348 12286 -f 12286 12348 12285 -f 12289 12286 12291 -f 12287 12288 12289 -f 12293 12297 12292 -f 12288 12290 12289 -f 12289 12290 12296 -f 12292 12300 12320 -f 12289 12291 12295 -f 12293 12292 12320 -f 12287 12289 12294 -f 12294 12289 12295 -f 12294 12295 12299 -f 12289 12296 12293 -f 12293 12296 12297 -f 12302 12298 12295 -f 12295 12298 12299 -f 12320 12300 12301 -f 12320 12301 12295 -f 12295 12301 12302 -f 12291 12286 12317 -f 12319 12306 12304 -f 12304 12306 12305 -f 12319 12312 12306 -f 12313 12307 12317 -f 12315 12309 12308 -f 12308 12309 12310 -f 12308 12310 12311 -f 12308 12311 12319 -f 12319 12311 12312 -f 12304 12305 12313 -f 12304 12313 12317 -f 12307 12314 12317 -f 12317 12314 12316 -f 12308 12303 12315 -f 12315 12303 12316 -f 12316 12303 12317 -f 12317 12303 12291 -f 12308 12319 12333 -f 12333 12319 12318 -f 12293 12304 12346 -f 12346 12304 12284 -f 12346 12284 12350 -f 12350 12284 12318 -f 12350 12318 12320 -f 12320 12318 12319 -f 12320 12319 12293 -f 12293 12319 12304 -f 12323 12352 12350 -f 12323 12350 12278 -f 12278 12350 12320 -f 12278 12320 12295 -f 12321 12325 12278 -f 12278 12325 12323 -f 12325 12275 12326 -f 12322 12329 12323 -f 12323 12329 12328 -f 12323 12328 12324 -f 12325 12326 12323 -f 12323 12326 12327 -f 12323 12327 12322 -f 12331 12324 12328 -f 12331 12328 12279 -f 12279 12328 12329 -f 12279 12329 12280 -f 12280 12329 12322 -f 12280 12322 12330 -f 12330 12322 12327 -f 12330 12327 12281 -f 12281 12327 12326 -f 12281 12326 12277 -f 12331 12278 12295 -f 12334 12282 12333 -f 12333 12282 12352 -f 12291 12303 12295 -f 12295 12303 12308 -f 12295 12308 12331 -f 12331 12308 12333 -f 12331 12333 12324 -f 12324 12333 12352 -f 12324 12352 12323 -f 12284 12341 12332 -f 12284 12332 12318 -f 12318 12332 12339 -f 12318 12339 12333 -f 12333 12339 12338 -f 12345 12343 12336 -f 12336 12343 12284 -f 12284 12343 12341 -f 12335 12334 12333 -f 12335 12333 12338 -f 12283 12334 12335 -f 12283 12335 12336 -f 12336 12335 12345 -f 12344 12335 12337 -f 12337 12335 12338 -f 12337 12338 12351 -f 12351 12338 12339 -f 12351 12339 12332 -f 12351 12332 12340 -f 12340 12332 12341 -f 12340 12341 12349 -f 12349 12341 12342 -f 12342 12341 12343 -f 12342 12343 12345 -f 12342 12345 12344 -f 12344 12345 12335 -f 12282 12347 12348 -f 12350 12340 12346 -f 12348 12347 12285 -f 12346 12340 12349 -f 12351 12340 12350 -f 12346 12349 12342 -f 12352 12337 12351 -f 12352 12351 12350 -f 12342 12352 12282 -f 12342 12282 12348 -f 12342 12348 12346 -f 12342 12344 12352 -f 12352 12344 12337 -f 12289 12293 12348 -f 12348 12293 12346 -f 12487 12353 12568 -f 12568 12353 12554 -f 12554 12353 12354 -f 12554 12354 12355 -f 12355 12354 12502 -f 12355 12502 12553 -f 12502 12515 12553 -f 12553 12515 12356 -f 12493 12548 12536 -f 12493 12536 12526 -f 12526 12536 12537 -f 12526 12537 12357 -f 12357 12537 12524 -f 12524 12537 12356 -f 12524 12356 12515 -f 12493 12494 12548 -f 12548 12494 12358 -f 12496 12561 12358 -f 12496 12358 12494 -f 12496 12528 12561 -f 12561 12528 12359 -f 12521 12360 12528 -f 12528 12360 12359 -f 12361 12546 12563 -f 12361 12563 12521 -f 12521 12563 12565 -f 12521 12565 12360 -f 12381 12590 12575 -f 12381 12575 12363 -f 12568 12377 12362 -f 12568 12362 12569 -f 12569 12362 12380 -f 12569 12380 12363 -f 12363 12380 12381 -f 12392 12371 12393 -f 12393 12371 12589 -f 12393 12589 12394 -f 12394 12589 12364 -f 12394 12364 12365 -f 12365 12364 12366 -f 12365 12366 12395 -f 12395 12366 12367 -f 12395 12367 12383 -f 12383 12367 12574 -f 12368 12583 12390 -f 12390 12583 12582 -f 12390 12582 12388 -f 12388 12582 12389 -f 12389 12582 12581 -f 12389 12581 12369 -f 12369 12581 12580 -f 12369 12580 12370 -f 12370 12580 12371 -f 12370 12371 12392 -f 12368 12372 12583 -f 12583 12372 12373 -f 12373 12372 12585 -f 12585 12372 12386 -f 12585 12386 12586 -f 12586 12386 12587 -f 12587 12386 12374 -f 12587 12374 12375 -f 12587 12375 12376 -f 12376 12375 12391 -f 12376 12391 12579 -f 12579 12391 12578 -f 12381 12380 12379 -f 12542 12443 12377 -f 12377 12443 12378 -f 12377 12378 12404 -f 12377 12404 12405 -f 12379 12380 12405 -f 12380 12362 12405 -f 12405 12362 12377 -f 12385 12383 12590 -f 12406 12381 12379 -f 12382 12384 12381 -f 12382 12403 12384 -f 12381 12406 12382 -f 12382 12406 12403 -f 12396 12383 12402 -f 12402 12383 12384 -f 12384 12383 12385 -f 12384 12385 12381 -f 12381 12385 12590 -f 12369 12370 12375 -f 12375 12370 12391 -f 12369 12375 12374 -f 12369 12374 12389 -f 12387 12374 12386 -f 12386 12372 12387 -f 12387 12372 12368 -f 12387 12368 12388 -f 12374 12387 12389 -f 12389 12387 12388 -f 12368 12390 12388 -f 12391 12370 12392 -f 12391 12392 12401 -f 12401 12392 12393 -f 12401 12393 12399 -f 12399 12393 12394 -f 12399 12394 12398 -f 12398 12394 12365 -f 12398 12365 12396 -f 12396 12365 12395 -f 12396 12395 12383 -f 12402 12576 12396 -f 12396 12576 12577 -f 12396 12577 12398 -f 12398 12577 12397 -f 12398 12397 12399 -f 12399 12397 12400 -f 12399 12400 12401 -f 12401 12400 12588 -f 12401 12588 12391 -f 12391 12588 12578 -f 12576 12402 12384 -f 12576 12384 12403 -f 12378 12417 12572 -f 12378 12572 12404 -f 12404 12572 12570 -f 12404 12570 12405 -f 12405 12570 12379 -f 12379 12570 12573 -f 12407 12406 12573 -f 12573 12406 12379 -f 12407 12403 12406 -f 12378 12443 12417 -f 12571 12417 12484 -f 12484 12417 12456 -f 12415 12481 12445 -f 12445 12481 12451 -f 12461 12408 12409 -f 12461 12409 12460 -f 12460 12409 12531 -f 12461 12410 12450 -f 12450 12410 12469 -f 12450 12469 12432 -f 12469 12411 12432 -f 12432 12411 12412 -f 12412 12411 12457 -f 12412 12457 12441 -f 12457 12465 12441 -f 12441 12465 12439 -f 12439 12465 12476 -f 12439 12476 12413 -f 12413 12476 12436 -f 12436 12476 12414 -f 12436 12414 12415 -f 12436 12415 12445 -f 12416 12434 12421 -f 12450 12432 12442 -f 12418 12417 12443 -f 12418 12443 12447 -f 12591 12456 12418 -f 12418 12456 12417 -f 12422 12419 12420 -f 12416 12421 12422 -f 12422 12421 12423 -f 12422 12423 12419 -f 12429 12424 12419 -f 12419 12424 12420 -f 12412 12431 12432 -f 12426 12425 12427 -f 12426 12427 12448 -f 12427 12429 12448 -f 12408 12461 12443 -f 12419 12428 12429 -f 12429 12428 12430 -f 12429 12430 12448 -f 12448 12430 12446 -f 12432 12431 12442 -f 12591 12433 12456 -f 12456 12433 12455 -f 12416 12435 12434 -f 12434 12435 12451 -f 12434 12451 12433 -f 12433 12451 12455 -f 12436 12444 12438 -f 12438 12413 12436 -f 12438 12439 12413 -f 12435 12437 12451 -f 12451 12437 12452 -f 12439 12438 12440 -f 12439 12440 12441 -f 12441 12440 12431 -f 12449 12450 12442 -f 12454 12444 12445 -f 12445 12444 12436 -f 12431 12412 12441 -f 12446 12447 12448 -f 12448 12447 12443 -f 12448 12443 12449 -f 12449 12443 12461 -f 12449 12461 12450 -f 12451 12452 12453 -f 12451 12453 12445 -f 12445 12453 12454 -f 12454 12453 12425 -f 12454 12425 12426 -f 12451 12481 12479 -f 12451 12479 12455 -f 12455 12479 12484 -f 12484 12456 12455 -f 12466 12465 12457 -f 12466 12457 12475 -f 12478 12462 12463 -f 12415 12463 12458 -f 12459 12460 12486 -f 12468 12460 12467 -f 12460 12468 12470 -f 12463 12462 12464 -f 12463 12464 12459 -f 12459 12464 12483 -f 12468 12467 12473 -f 12473 12467 12471 -f 12469 12410 12474 -f 12474 12410 12470 -f 12476 12465 12471 -f 12471 12477 12415 -f 12460 12472 12467 -f 12465 12466 12473 -f 12465 12473 12471 -f 12460 12470 12410 -f 12460 12410 12461 -f 12469 12474 12411 -f 12411 12474 12475 -f 12411 12475 12457 -f 12471 12414 12476 -f 12415 12477 12478 -f 12415 12478 12463 -f 12458 12482 12415 -f 12415 12482 12481 -f 12484 12479 12480 -f 12480 12479 12481 -f 12480 12481 12482 -f 12459 12483 12460 -f 12460 12483 12472 -f 12471 12415 12414 -f 12484 12480 12485 -f 12484 12485 12571 -f 12571 12485 12486 -f 12571 12486 12460 -f 12529 12500 12530 -f 12530 12500 12487 -f 12530 12487 12488 -f 12488 12487 12571 -f 12488 12571 12531 -f 12531 12571 12460 -f 12527 12489 12500 -f 12490 12487 12497 -f 12501 12353 12490 -f 12490 12353 12487 -f 12500 12489 12498 -f 12500 12498 12487 -f 12504 12505 12491 -f 12492 12499 12493 -f 12493 12499 12494 -f 12494 12499 12495 -f 12495 12496 12494 -f 12520 12497 12514 -f 12514 12497 12487 -f 12514 12487 12498 -f 12503 12516 12502 -f 12353 12501 12354 -f 12504 12502 12501 -f 12501 12502 12354 -f 12504 12491 12502 -f 12502 12491 12503 -f 12507 12492 12525 -f 12504 12506 12505 -f 12507 12525 12508 -f 12507 12508 12514 -f 12509 12513 12510 -f 12505 12506 12512 -f 12505 12512 12511 -f 12511 12512 12513 -f 12508 12510 12514 -f 12502 12516 12515 -f 12515 12516 12522 -f 12492 12493 12525 -f 12509 12517 12513 -f 12513 12517 12511 -f 12513 12518 12510 -f 12510 12518 12519 -f 12510 12519 12514 -f 12514 12519 12520 -f 12500 12361 12521 -f 12500 12521 12527 -f 12522 12523 12515 -f 12515 12523 12524 -f 12524 12523 12525 -f 12524 12525 12357 -f 12493 12526 12525 -f 12525 12526 12357 -f 12527 12496 12495 -f 12527 12528 12496 -f 12521 12528 12527 -f 12500 12529 12361 -f 12361 12529 12534 -f 12361 12534 12546 -f 12546 12534 12544 -f 12529 12530 12534 -f 12534 12530 12533 -f 12530 12488 12533 -f 12533 12488 12532 -f 12488 12531 12532 -f 12532 12531 12409 -f 12409 12408 12532 -f 12532 12408 12443 -f 12532 12443 12533 -f 12533 12443 12542 -f 12533 12542 12534 -f 12534 12542 12544 -f 12546 12544 12535 -f 12535 12544 12545 -f 12356 12541 12538 -f 12540 12537 12536 -f 12356 12538 12553 -f 12553 12538 12551 -f 12554 12549 12568 -f 12568 12549 12539 -f 12568 12539 12542 -f 12536 12548 12540 -f 12550 12552 12553 -f 12542 12539 12543 -f 12542 12543 12544 -f 12544 12543 12545 -f 12547 12546 12535 -f 12557 12548 12358 -f 12557 12358 12560 -f 12549 12554 12552 -f 12541 12356 12540 -f 12540 12356 12537 -f 12555 12550 12553 -f 12555 12553 12551 -f 12553 12552 12355 -f 12355 12552 12554 -f 12550 12555 12556 -f 12550 12556 12547 -f 12547 12556 12562 -f 12547 12563 12546 -f 12548 12557 12558 -f 12548 12558 12540 -f 12559 12566 12567 -f 12359 12559 12561 -f 12561 12559 12560 -f 12561 12560 12358 -f 12547 12562 12563 -f 12563 12562 12564 -f 12563 12564 12566 -f 12563 12566 12565 -f 12566 12559 12359 -f 12566 12359 12565 -f 12558 12567 12540 -f 12540 12567 12566 -f 12359 12360 12565 -f 12542 12377 12568 -f 12487 12568 12569 -f 12487 12569 12571 -f 12573 12569 12363 -f 12569 12573 12570 -f 12569 12570 12571 -f 12570 12572 12571 -f 12571 12572 12417 -f 12363 12407 12573 -f 12575 12590 12574 -f 12363 12575 12576 -f 12403 12407 12576 -f 12576 12407 12363 -f 12576 12575 12574 -f 12576 12574 12577 -f 12578 12589 12371 -f 12578 12371 12579 -f 12371 12580 12579 -f 12579 12580 12581 -f 12581 12587 12376 -f 12581 12376 12579 -f 12582 12583 12584 -f 12584 12583 12373 -f 12584 12373 12586 -f 12586 12587 12584 -f 12584 12587 12581 -f 12584 12581 12582 -f 12373 12585 12586 -f 12578 12588 12589 -f 12589 12588 12400 -f 12589 12400 12364 -f 12364 12400 12397 -f 12364 12397 12366 -f 12366 12397 12577 -f 12366 12577 12367 -f 12367 12577 12574 -f 12383 12574 12590 -f 12591 12630 12592 -f 12592 12630 12629 -f 12592 12629 12593 -f 12593 12629 12594 -f 12593 12594 12595 -f 12595 12594 12596 -f 12595 12596 12597 -f 12597 12596 12632 -f 12597 12632 12598 -f 12598 12632 12631 -f 12598 12631 12599 -f 12599 12631 12633 -f 12599 12633 12600 -f 12600 12633 12602 -f 12600 12602 12601 -f 12601 12602 12603 -f 12601 12603 12604 -f 12604 12603 12605 -f 12604 12605 12606 -f 12606 12605 12607 -f 12606 12607 12608 -f 12608 12607 12634 -f 12608 12634 12609 -f 12609 12634 12610 -f 12609 12610 12423 -f 12423 12610 12635 -f 12423 12635 12611 -f 12611 12635 12612 -f 12611 12612 12613 -f 12613 12612 12614 -f 12613 12614 12615 -f 12615 12614 12616 -f 12615 12616 12617 -f 12617 12616 12637 -f 12617 12637 12618 -f 12618 12637 12636 -f 12618 12636 12619 -f 12619 12636 12640 -f 12619 12640 12620 -f 12620 12640 12639 -f 12620 12639 12621 -f 12621 12639 12638 -f 12621 12638 12622 -f 12622 12638 12623 -f 12622 12623 12625 -f 12625 12623 12624 -f 12625 12624 12626 -f 12626 12624 12641 -f 12626 12641 12627 -f 12627 12641 12628 -f 12627 12628 12591 -f 12591 12628 12630 -f 12628 12641 12636 -f 12628 12636 12630 -f 12596 12594 12636 -f 12636 12594 12629 -f 12636 12629 12630 -f 12633 12631 12636 -f 12636 12631 12632 -f 12636 12632 12596 -f 12605 12603 12636 -f 12636 12603 12602 -f 12636 12602 12633 -f 12610 12634 12636 -f 12636 12634 12607 -f 12636 12607 12605 -f 12614 12612 12636 -f 12636 12612 12635 -f 12636 12635 12610 -f 12636 12637 12616 -f 12636 12616 12614 -f 12638 12639 12636 -f 12636 12639 12640 -f 12641 12624 12636 -f 12636 12624 12623 -f 12636 12623 12638 -f 12649 12665 12642 -f 12642 12665 12666 -f 12642 12666 12644 -f 12644 12666 12643 -f 12649 12654 12665 -f 12665 12654 12646 -f 12645 12671 12646 -f 12645 12646 12654 -f 12645 12654 12647 -f 12645 12647 12648 -f 12645 12648 12651 -f 12656 12653 12642 -f 12642 12653 12649 -f 12650 12652 12651 -f 12650 12651 12648 -f 12652 12650 12655 -f 12649 12653 12654 -f 12654 12653 12647 -f 12652 12655 12644 -f 12655 12656 12644 -f 12656 12642 12644 -f 12763 12756 12657 -f 12657 12756 12736 -f 12766 12763 12720 -f 12720 12763 12657 -f 12758 12766 12711 -f 12711 12766 12720 -f 12758 12711 12751 -f 12751 12711 12658 -f 12751 12658 12659 -f 12751 12659 12746 -f 12746 12659 12660 -f 12746 12660 12757 -f 12757 12660 12661 -f 12661 12660 12662 -f 12661 12662 12667 -f 12644 12643 12652 -f 12652 12643 12667 -f 12652 12667 12662 -f 12664 12665 12663 -f 12663 12665 12646 -f 12669 12643 12666 -f 12670 12667 12669 -f 12646 12671 12663 -f 12669 12666 12664 -f 12664 12666 12665 -f 12643 12669 12667 -f 12667 12670 12752 -f 12752 12670 12668 -f 12752 12668 12671 -f 12671 12668 12663 -f 12672 12692 12685 -f 12672 12685 12679 -f 12672 12681 12692 -f 12692 12681 12690 -f 12676 12673 12683 -f 12683 12673 12695 -f 12683 12695 12690 -f 12683 12690 12681 -f 12677 12674 12675 -f 12680 12676 12683 -f 12676 12680 12675 -f 12676 12675 12674 -f 12674 12677 12709 -f 12709 12677 12678 -f 12672 12679 12682 -f 12680 12681 12682 -f 12682 12681 12672 -f 12680 12683 12681 -f 12709 12678 12679 -f 12679 12678 12682 -f 12671 12645 12752 -f 12752 12645 12651 -f 12752 12651 12686 -f 12686 12651 12709 -f 12686 12709 12685 -f 12685 12709 12679 -f 12684 12685 12692 -f 12685 12684 12687 -f 12685 12687 12686 -f 12694 12691 12690 -f 12686 12687 12688 -f 12686 12688 12689 -f 12689 12688 12693 -f 12694 12690 12695 -f 12690 12691 12692 -f 12692 12691 12684 -f 12689 12693 12673 -f 12693 12694 12673 -f 12694 12695 12673 -f 12673 12676 12689 -f 12689 12676 12674 -f 12689 12674 12708 -f 12689 12708 12747 -f 12747 12708 12696 -f 12747 12696 12759 -f 12759 12696 12697 -f 12759 12697 12699 -f 12699 12697 12712 -f 12699 12712 12698 -f 12699 12698 12700 -f 12700 12698 12765 -f 12765 12698 12719 -f 12750 12765 12717 -f 12717 12765 12719 -f 12701 12750 12713 -f 12713 12750 12717 -f 12702 12707 12716 -f 12702 12716 12703 -f 12703 12716 12704 -f 12703 12704 12748 -f 12748 12704 12715 -f 12748 12715 12764 -f 12764 12715 12705 -f 12705 12715 12706 -f 12705 12706 12761 -f 12761 12706 12714 -f 12761 12714 12722 -f 12761 12722 12760 -f 12760 12722 12753 -f 12753 12722 12718 -f 12753 12718 12749 -f 12749 12718 12707 -f 12749 12707 12702 -f 12708 12674 12709 -f 12651 12696 12709 -f 12709 12696 12708 -f 12652 12662 12651 -f 12651 12662 12660 -f 12651 12660 12736 -f 12736 12660 12659 -f 12776 12711 12720 -f 12776 12720 12778 -f 12724 12698 12736 -f 12736 12698 12712 -f 12736 12712 12651 -f 12651 12712 12697 -f 12719 12715 12717 -f 12717 12715 12704 -f 12713 12707 12718 -f 12736 12659 12658 -f 12736 12769 12657 -f 12657 12769 12768 -f 12651 12697 12696 -f 12719 12714 12706 -f 12719 12706 12715 -f 12704 12716 12717 -f 12717 12716 12707 -f 12717 12707 12713 -f 12724 12713 12698 -f 12698 12713 12722 -f 12698 12722 12719 -f 12719 12722 12714 -f 12658 12710 12736 -f 12736 12710 12769 -f 12768 12721 12657 -f 12657 12721 12720 -f 12720 12721 12778 -f 12718 12722 12713 -f 12776 12773 12711 -f 12658 12723 12710 -f 12711 12773 12723 -f 12711 12723 12658 -f 12739 12701 12724 -f 12724 12701 12713 -f 12725 12743 12735 -f 12735 12743 12738 -f 12725 12735 12727 -f 12727 12735 12726 -f 12727 12726 12729 -f 12729 12726 12733 -f 12728 12729 12730 -f 12730 12729 12733 -f 12741 12728 12731 -f 12731 12728 12730 -f 12756 12732 12755 -f 12726 12734 12733 -f 12732 12735 12738 -f 12731 12730 12734 -f 12734 12730 12733 -f 12735 12732 12726 -f 12726 12732 12734 -f 12738 12737 12732 -f 12732 12737 12755 -f 12745 12736 12755 -f 12745 12755 12737 -f 12745 12737 12744 -f 12744 12737 12738 -f 12744 12738 12743 -f 12754 12739 12745 -f 12745 12739 12724 -f 12745 12724 12736 -f 12755 12736 12756 -f 12729 12728 12741 -f 12741 12742 12729 -f 12729 12742 12727 -f 12727 12742 12754 -f 12727 12754 12725 -f 12725 12754 12743 -f 12743 12754 12744 -f 12744 12754 12745 -f 12756 12751 12746 -f 12661 12667 12752 -f 12770 12758 12751 -f 12686 12689 12747 -f 12686 12747 12752 -f 12752 12747 12759 -f 12739 12753 12701 -f 12701 12753 12749 -f 12748 12764 12765 -f 12749 12702 12701 -f 12701 12702 12750 -f 12750 12702 12703 -f 12758 12774 12766 -f 12763 12770 12751 -f 12763 12751 12756 -f 12760 12753 12752 -f 12752 12753 12740 -f 12740 12753 12739 -f 12740 12739 12754 -f 12756 12746 12740 -f 12740 12746 12757 -f 12740 12757 12752 -f 12752 12757 12661 -f 12774 12775 12766 -f 12748 12765 12750 -f 12748 12750 12703 -f 12770 12771 12758 -f 12758 12771 12772 -f 12758 12772 12774 -f 12775 12777 12766 -f 12759 12699 12752 -f 12752 12699 12760 -f 12760 12699 12700 -f 12700 12705 12761 -f 12700 12761 12760 -f 12763 12762 12767 -f 12763 12767 12770 -f 12765 12764 12705 -f 12765 12705 12700 -f 12766 12777 12762 -f 12766 12762 12763 -f 12762 12721 12768 -f 12762 12768 12767 -f 12767 12768 12769 -f 12767 12769 12770 -f 12770 12769 12710 -f 12770 12710 12771 -f 12771 12710 12772 -f 12772 12710 12723 -f 12772 12723 12774 -f 12774 12723 12773 -f 12774 12773 12776 -f 12774 12776 12775 -f 12775 12776 12778 -f 12775 12778 12777 -f 12777 12778 12721 -f 12777 12721 12762 -f 12782 12781 12779 -f 12779 12781 12780 -f 12843 12844 12783 -f 12783 12844 12785 -f 12783 12785 12784 -f 12784 12785 12786 -f 12784 12786 12788 -f 12788 12786 12787 -f 12788 12787 12789 -f 12789 12787 12790 -f 12789 12790 12791 -f 12791 12790 12792 -f 12791 12792 12793 -f 12793 12792 12794 -f 12793 12794 12795 -f 12795 12794 12796 -f 12795 12796 12798 -f 12798 12796 12797 -f 12798 12797 12799 -f 12799 12797 12800 -f 12799 12800 12801 -f 12801 12800 12803 -f 12801 12803 12802 -f 12802 12803 12804 -f 12802 12804 12805 -f 12805 12804 12806 -f 12805 12806 12808 -f 12808 12806 12807 -f 12808 12807 12810 -f 12810 12807 12809 -f 12810 12809 12811 -f 12811 12809 12813 -f 12811 12813 12812 -f 12812 12813 12814 -f 12812 12814 12815 -f 12815 12814 12816 -f 12815 12816 12818 -f 12818 12816 12817 -f 12818 12817 12819 -f 12819 12817 12820 -f 12819 12820 12821 -f 12821 12820 12822 -f 12821 12822 12823 -f 12823 12822 12824 -f 12823 12824 12825 -f 12825 12824 12827 -f 12825 12827 12826 -f 12826 12827 12828 -f 12826 12828 12830 -f 12830 12828 12829 -f 12830 12829 12832 -f 12832 12829 12831 -f 12832 12831 12833 -f 12833 12831 12834 -f 12833 12834 12836 -f 12836 12834 12835 -f 12836 12835 12838 -f 12838 12835 12837 -f 12838 12837 12840 -f 12840 12837 12839 -f 12840 12839 12841 -f 12841 12839 12842 -f 12841 12842 12843 -f 12843 12842 12844 -f 12846 12848 12845 -f 12847 12846 12845 -f 12848 12847 12845 -f 12849 12847 12848 -f 12847 12850 12846 -f 12851 12853 12852 -f 12854 12853 12851 -f 12855 12852 12853 -f 12856 12857 12858 -f 12860 12859 12861 -f 12859 12862 12861 -f 12860 12861 12862 -f 12865 12864 12866 -f 12863 12865 12866 -f 12867 12865 12863 -f 12940 12941 12868 -f 12868 12941 12869 -f 12868 12869 12870 -f 12870 12869 12871 -f 12870 12871 12872 -f 12872 12871 12873 -f 12872 12873 12874 -f 12874 12873 12875 -f 12874 12875 12876 -f 12876 12875 12877 -f 12876 12877 12878 -f 12878 12877 12879 -f 12878 12879 12880 -f 12880 12879 12881 -f 12880 12881 12882 -f 12882 12881 12883 -f 12882 12883 12884 -f 12884 12883 12885 -f 12884 12885 12886 -f 12886 12885 12888 -f 12886 12888 12887 -f 12887 12888 12890 -f 12887 12890 12889 -f 12889 12890 12891 -f 12889 12891 12893 -f 12893 12891 12892 -f 12893 12892 12894 -f 12894 12892 12895 -f 12894 12895 12897 -f 12897 12895 12896 -f 12897 12896 12898 -f 12898 12896 12899 -f 12898 12899 12900 -f 12900 12899 12901 -f 12900 12901 12902 -f 12902 12901 12904 -f 12902 12904 12903 -f 12903 12904 12905 -f 12903 12905 12906 -f 12906 12905 12907 -f 12906 12907 12908 -f 12908 12907 12909 -f 12908 12909 12910 -f 12910 12909 12912 -f 12910 12912 12911 -f 12911 12912 12913 -f 12911 12913 12914 -f 12914 12913 12915 -f 12914 12915 12916 -f 12916 12915 12917 -f 12916 12917 12918 -f 12918 12917 12920 -f 12918 12920 12919 -f 12919 12920 12921 -f 12919 12921 12922 -f 12922 12921 12923 -f 12922 12923 12924 -f 12924 12923 12925 -f 12924 12925 12926 -f 12926 12925 12928 -f 12926 12928 12927 -f 12927 12928 12929 -f 12927 12929 12930 -f 12930 12929 12931 -f 12930 12931 12932 -f 12932 12931 12933 -f 12932 12933 12934 -f 12934 12933 12935 -f 12934 12935 12936 -f 12936 12935 12938 -f 12936 12938 12937 -f 12937 12938 12939 -f 12937 12939 12940 -f 12940 12939 12941 -f 12942 12943 12944 -f 12945 12942 12944 -f 12954 12971 12946 -f 12946 12971 12947 -f 12946 12947 12948 -f 12948 12947 13030 -f 13067 13074 13075 -f 13077 13078 12949 -f 13075 12950 12951 -f 12949 13012 13077 -f 13077 13012 12950 -f 13077 12950 13075 -f 12962 12959 13064 -f 12951 13066 13067 -f 12951 13067 13075 -f 12962 13064 13066 -f 13066 12973 12962 -f 12951 12973 13066 -f 12960 12952 12959 -f 12949 13078 12953 -f 12953 13027 13028 -f 13067 13073 13074 -f 12954 12955 12956 -f 12956 12955 13071 -f 12956 13071 12952 -f 12960 12956 12952 -f 12959 12952 13064 -f 12953 13028 12949 -f 13027 12953 12948 -f 12946 13072 12954 -f 12958 13072 12946 -f 13073 13067 12957 -f 12948 12953 12958 -f 12948 12958 12946 -f 12954 13072 13073 -f 13073 12957 12955 -f 13073 12955 12954 -f 12959 12969 12960 -f 12960 12969 12961 -f 12960 12961 12956 -f 12959 12962 12969 -f 12969 12962 12968 -f 13076 12963 12965 -f 12963 13069 13068 -f 13068 12965 12963 -f 13010 13076 12964 -f 13010 12964 13011 -f 12964 13076 12965 -f 13030 13080 12966 -f 13010 13079 13076 -f 12961 12967 13070 -f 12961 13070 12971 -f 12965 13068 13065 -f 12965 13065 12972 -f 12947 12971 13081 -f 12969 12968 13063 -f 13080 13030 13081 -f 13081 13030 12947 -f 12966 13080 13079 -f 13079 13029 12966 -f 13010 13029 13079 -f 13063 12968 12972 -f 13063 12972 13065 -f 12969 13063 12967 -f 12963 12970 13070 -f 13070 12970 12971 -f 12971 12970 13081 -f 12967 12961 12969 -f 13070 13069 12963 -f 12951 12965 12972 -f 12951 12972 12973 -f 12973 12972 12968 -f 12973 12968 12962 -f 13059 13058 13061 -f 13061 13058 13057 -f 13061 13057 13056 -f 13061 13056 12988 -f 12988 13056 12974 -f 12988 12974 12990 -f 12990 12974 12975 -f 12990 12975 12976 -f 12976 12975 12977 -f 12976 12977 12992 -f 12965 12951 12964 -f 12964 12951 12950 -f 12964 12950 13032 -f 13032 12950 12979 -f 13032 12979 12978 -f 12978 12979 12986 -f 12995 13045 12980 -f 12980 13045 13044 -f 12980 13044 12981 -f 12981 13044 13043 -f 12981 13043 12997 -f 12997 13043 12982 -f 12997 12982 12983 -f 12977 13053 12992 -f 12992 13053 13050 -f 12992 13050 12993 -f 12993 13050 13049 -f 12993 13049 12994 -f 12994 13049 13048 -f 12994 13048 12995 -f 12995 13048 13047 -f 12995 13047 13045 -f 12982 12984 12983 -f 12983 12984 13040 -f 12983 13040 12998 -f 12998 13040 13038 -f 12998 13038 13000 -f 13000 13038 12985 -f 13000 12985 13001 -f 13001 12985 13036 -f 13001 13036 12986 -f 12986 13036 13034 -f 12986 13034 12978 -f 13004 13061 12987 -f 12987 13061 12988 -f 12987 12988 12989 -f 12989 12988 12990 -f 12989 12990 12991 -f 12991 12990 12976 -f 12991 12976 13007 -f 13007 12976 12992 -f 13007 12992 13006 -f 13006 12992 12993 -f 13006 12993 13015 -f 13015 12993 12994 -f 13015 12994 13013 -f 13013 12994 12995 -f 13013 12995 13023 -f 13023 12995 12980 -f 13023 12980 12996 -f 12996 12980 12981 -f 12996 12981 13021 -f 13021 12981 12997 -f 13021 12997 13020 -f 13020 12997 12983 -f 13020 12983 13018 -f 13018 12983 12998 -f 13018 12998 12999 -f 12999 12998 13000 -f 12999 13000 13025 -f 13025 13000 13001 -f 13025 13001 13002 -f 13002 13001 12986 -f 13002 12986 13003 -f 13003 12986 12979 -f 13003 12979 13012 -f 13012 12979 12950 -f 13060 13062 13005 -f 13005 13062 13004 -f 13005 13004 13009 -f 13009 13004 12987 -f 13006 13051 13007 -f 13007 13051 13052 -f 13007 13052 12991 -f 12991 13052 13054 -f 12991 13054 12989 -f 12989 13054 13008 -f 12989 13008 12987 -f 12987 13008 13055 -f 12987 13055 13009 -f 12949 13010 13012 -f 13012 13010 13011 -f 13012 13011 13003 -f 13023 13046 13013 -f 13013 13046 13014 -f 13013 13014 13015 -f 13015 13014 13016 -f 13015 13016 13006 -f 13006 13016 13017 -f 13006 13017 13051 -f 13018 13019 13020 -f 13020 13019 13041 -f 13020 13041 13021 -f 13021 13041 13022 -f 13021 13022 12996 -f 12996 13022 13042 -f 12996 13042 13023 -f 13023 13042 13024 -f 13023 13024 13046 -f 13011 13031 13003 -f 13003 13031 13033 -f 13003 13033 13002 -f 13002 13033 13035 -f 13002 13035 13025 -f 13025 13035 13037 -f 13025 13037 12999 -f 12999 13037 13026 -f 12999 13026 13018 -f 13018 13026 13039 -f 13018 13039 13019 -f 13027 12966 13029 -f 13027 13029 13028 -f 13028 13029 13010 -f 13028 13010 12949 -f 12966 13027 13030 -f 13030 13027 12948 -f 13011 12964 13032 -f 13011 13032 13031 -f 13031 13032 12978 -f 13031 12978 13033 -f 13033 12978 13034 -f 13033 13034 13035 -f 13035 13034 13036 -f 13035 13036 13037 -f 13037 13036 12985 -f 13037 12985 13026 -f 13026 12985 13038 -f 13026 13038 13039 -f 13039 13038 13040 -f 13039 13040 13019 -f 13019 13040 12984 -f 13019 12984 13041 -f 13041 12984 12982 -f 13041 12982 13022 -f 13022 12982 13043 -f 13022 13043 13042 -f 13042 13043 13044 -f 13042 13044 13024 -f 13024 13044 13045 -f 13024 13045 13046 -f 13046 13045 13047 -f 13046 13047 13014 -f 13014 13047 13048 -f 13014 13048 13016 -f 13016 13048 13049 -f 13016 13049 13017 -f 13017 13049 13050 -f 13017 13050 13051 -f 13051 13050 13053 -f 13051 13053 13052 -f 13052 13053 12977 -f 13052 12977 13054 -f 13054 12977 12975 -f 13054 12975 13008 -f 13008 12975 12974 -f 13008 12974 13055 -f 13055 12974 13056 -f 13055 13056 13009 -f 13009 13056 13057 -f 13009 13057 13005 -f 13057 13058 13005 -f 13005 13058 13060 -f 13058 13059 13060 -f 13060 13059 13062 -f 13059 13061 13062 -f 13062 13061 13004 -f 12971 12954 12961 -f 12961 12954 12956 -f 13071 12967 12952 -f 12952 12967 13064 -f 13064 12967 13063 -f 13064 13063 13066 -f 13066 13063 13065 -f 13066 13065 13068 -f 13066 13068 13067 -f 13067 13068 13069 -f 13067 13069 12957 -f 12957 13069 12955 -f 12955 13069 13070 -f 12955 13070 13071 -f 13071 13070 12967 -f 13072 12970 13073 -f 13073 12970 13074 -f 13074 12970 12963 -f 13074 12963 13075 -f 13075 12963 13076 -f 13075 13076 13077 -f 13077 13076 13078 -f 13078 13076 13079 -f 13078 13079 12953 -f 12953 13079 13080 -f 12953 13080 12958 -f 12958 13080 13081 -f 12958 13081 13072 -f 13072 13081 12970 -f 13083 13129 13145 -f 13082 13139 13083 -f 13082 13083 13145 -f 13082 13145 13139 -f 13083 13146 13129 -f 13146 13083 13139 -f 13090 13147 13149 -f 13090 13149 13091 -f 13088 13096 13086 -f 13103 13101 13085 -f 13085 13101 13088 -f 13088 13101 13096 -f 13089 13088 13086 -f 13087 13086 13094 -f 13147 13091 13151 -f 13151 13091 13084 -f 13090 13089 13086 -f 13087 13094 13084 -f 13090 13086 13087 -f 13095 13085 13088 -f 13091 13089 13090 -f 13092 13087 13084 -f 13149 13148 13091 -f 13097 13103 13085 -f 13097 13085 13093 -f 13095 13093 13085 -f 13095 13088 13089 -f 13092 13084 13091 -f 13096 13089 13091 -f 13098 13087 13092 -f 13099 13091 13148 -f 13094 13098 13092 -f 13094 13092 13091 -f 13087 13098 13090 -f 13095 13101 13093 -f 13101 13095 13089 -f 13091 13099 13094 -f 13090 13098 13147 -f 13098 13094 13086 -f 13098 13086 13147 -f 13093 13101 13097 -f 13097 13101 13100 -f 13101 13089 13096 -f 13096 13091 13086 -f 13094 13099 13084 -f 13084 13099 13151 -f 13100 13117 13111 -f 13097 13105 13103 -f 13110 13123 13104 -f 13111 13109 13102 -f 13105 13100 13102 -f 13103 13100 13101 -f 13109 13111 13104 -f 13117 13110 13111 -f 13103 13105 13109 -f 13104 13100 13109 -f 13102 13109 13105 -f 13106 13122 13108 -f 13108 13116 13117 -f 13104 13117 13100 -f 13120 13124 13106 -f 13123 13107 13108 -f 13100 13111 13102 -f 13103 13109 13100 -f 13106 13125 13118 -f 13116 13122 13107 -f 13100 13105 13097 -f 13107 13115 13106 -f 13111 13110 13104 -f 13106 13124 13125 -f 13126 13127 13121 -f 13123 13108 13117 -f 13125 13120 13115 -f 13115 13120 13106 -f 13107 13106 13108 -f 13113 13127 13126 -f 13108 13122 13116 -f 13119 13112 13113 -f 13121 13127 13119 -f 13118 13115 13107 -f 13116 13107 13123 -f 13125 13114 13120 -f 13117 13116 13110 -f 13106 13118 13122 -f 13113 13133 13127 -f 13128 13119 13126 -f 13118 13125 13115 -f 13116 13123 13110 -f 13121 13114 13125 -f 13120 13114 13124 -f 13127 13112 13119 -f 13122 13118 13107 -f 13121 13128 13114 -f 13123 13117 13104 -f 13133 13112 13127 -f 13119 13113 13126 -f 13143 13135 13136 -f 13121 13119 13128 -f 13136 13135 13140 -f 13141 13140 13138 -f 13131 13138 13142 -f 13114 13128 13126 -f 13112 13131 13113 -f 13124 13114 13126 -f 13146 13145 13143 -f 13124 13126 13121 -f 13124 13121 13125 -f 13142 13141 13133 -f 13130 13146 13139 -f 13134 13139 13144 -f 13134 13144 13137 -f 13129 13132 13134 -f 13145 13137 13135 -f 13129 13134 13145 -f 13131 13142 13113 -f 13140 13146 13143 -f 13144 13132 13137 -f 13136 13140 13142 -f 13141 13138 13133 -f 13133 13138 13131 -f 13113 13142 13133 -f 13137 13129 13135 -f 13145 13134 13137 -f 13142 13140 13141 -f 13133 13131 13112 -f 13135 13129 13146 -f 13144 13130 13132 -f 13139 13145 13144 -f 13140 13143 13138 -f 13132 13130 13134 -f 13138 13136 13142 -f 13144 13146 13130 -f 13143 13145 13135 -f 13143 13136 13138 -f 13144 13145 13146 -f 13130 13139 13134 -f 13137 13132 13129 -f 13135 13146 13140 -f 13091 13147 13086 -f 13150 13151 13099 -f 13150 13099 13148 -f 13151 13148 13149 -f 13151 13150 13148 -f 13149 13147 13151 -f 13176 13212 13173 -f 13173 13212 13199 -f 13170 13154 13201 -f 13201 13154 13204 -f 13155 13208 13152 -f 13155 13152 13156 -f 13156 13152 13153 -f 13156 13153 13154 -f 13154 13153 13204 -f 13155 13157 13208 -f 13208 13157 13203 -f 13170 13171 13161 -f 13170 13161 13158 -f 13170 13158 13154 -f 13159 13156 13158 -f 13158 13156 13154 -f 13159 13155 13156 -f 13155 13159 13157 -f 13157 13159 13160 -f 13160 13200 13157 -f 13158 13205 13210 -f 13158 13210 13159 -f 13159 13210 13209 -f 13159 13209 13160 -f 13160 13209 13200 -f 13158 13161 13205 -f 13205 13161 13198 -f 13171 13198 13161 -f 13178 13169 13164 -f 13178 13164 13182 -f 13181 13162 13164 -f 13162 13182 13164 -f 13163 13164 13162 -f 13162 13164 13167 -f 13162 13167 13183 -f 13187 13184 13189 -f 13189 13184 13165 -f 13195 13182 13183 -f 13166 13182 13195 -f 13185 13166 13165 -f 13185 13165 13184 -f 13183 13167 13195 -f 13195 13167 13168 -f 13196 13168 13169 -f 13169 13168 13167 -f 13169 13167 13164 -f 13169 13178 13196 -f 13196 13178 13197 -f 13201 13197 13170 -f 13170 13197 13178 -f 13170 13178 13171 -f 13171 13178 13172 -f 13171 13172 13198 -f 13198 13172 13174 -f 13176 13173 13177 -f 13179 13177 13175 -f 13175 13177 13173 -f 13174 13179 13175 -f 13179 13174 13172 -f 13179 13172 13178 -f 13179 13178 13182 -f 13176 13177 13186 -f 13186 13177 13179 -f 13182 13185 13190 -f 13182 13190 13179 -f 13186 13180 13176 -f 13191 13186 13179 -f 13179 13190 13191 -f 13181 13163 13162 -f 13182 13166 13185 -f 13162 13183 13182 -f 13184 13187 13188 -f 13184 13188 13185 -f 13185 13188 13190 -f 13186 13191 13194 -f 13191 13190 13192 -f 13187 13189 13188 -f 13192 13190 13189 -f 13189 13190 13188 -f 13191 13192 13202 -f 13193 13194 13202 -f 13202 13194 13191 -f 13194 13193 13186 -f 13168 13196 13195 -f 13195 13196 13197 -f 13166 13195 13197 -f 13205 13198 13201 -f 13193 13173 13207 -f 13207 13173 13199 -f 13198 13189 13201 -f 13201 13189 13165 -f 13201 13165 13197 -f 13197 13165 13166 -f 13173 13193 13202 -f 13173 13202 13192 -f 13173 13192 13175 -f 13175 13192 13174 -f 13203 13200 13209 -f 13203 13209 13208 -f 13205 13201 13204 -f 13174 13192 13189 -f 13174 13189 13198 -f 13204 13153 13205 -f 13205 13153 13210 -f 13199 13206 13207 -f 13207 13206 13246 -f 13153 13152 13210 -f 13208 13209 13210 -f 13208 13210 13152 -f 13211 13246 13206 -f 13211 13206 13199 -f 13211 13199 13212 -f 13225 13213 13217 -f 13242 13241 13236 -f 13232 13236 13235 -f 13214 13215 13220 -f 13214 13220 13231 -f 13231 13220 13219 -f 13231 13219 13216 -f 13216 13219 13218 -f 13216 13218 13232 -f 13232 13218 13236 -f 13242 13236 13218 -f 13217 13213 13242 -f 13242 13218 13219 -f 13242 13219 13220 -f 13226 13217 13242 -f 13226 13242 13220 -f 13226 13220 13215 -f 13223 13222 13213 -f 13213 13222 13224 -f 13213 13224 13243 -f 13221 13275 13224 -f 13224 13222 13221 -f 13223 13225 13217 -f 13223 13217 13222 -f 13222 13217 13226 -f 13226 13215 13228 -f 13207 13230 13227 -f 13228 13215 13207 -f 13207 13215 13214 -f 13207 13214 13230 -f 13222 13226 13228 -f 13227 13233 13229 -f 13233 13227 13230 -f 13214 13231 13216 -f 13216 13232 13235 -f 13237 13230 13216 -f 13214 13216 13230 -f 13216 13235 13237 -f 13230 13234 13233 -f 13233 13234 13211 -f 13230 13237 13234 -f 13245 13234 13237 -f 13235 13236 13241 -f 13235 13241 13237 -f 13237 13241 13240 -f 13237 13240 13238 -f 13237 13238 13239 -f 13237 13239 13245 -f 13239 13238 13242 -f 13238 13240 13242 -f 13240 13241 13242 -f 13242 13213 13243 -f 13239 13242 13243 -f 13244 13243 13224 -f 13211 13234 13246 -f 13246 13245 13244 -f 13244 13245 13239 -f 13244 13239 13243 -f 13246 13234 13245 -f 13288 13252 13253 -f 13288 13253 13293 -f 13285 13251 13247 -f 13285 13247 13286 -f 13286 13247 13254 -f 13286 13254 13288 -f 13288 13254 13252 -f 13281 13249 13285 -f 13285 13249 13251 -f 13281 13248 13249 -f 13249 13248 13271 -f 13252 13254 13250 -f 13251 13249 13271 -f 13251 13271 13259 -f 13250 13254 13256 -f 13259 13258 13251 -f 13251 13258 13247 -f 13250 13253 13252 -f 13256 13254 13247 -f 13258 13255 13247 -f 13247 13255 13256 -f 13293 13250 13287 -f 13287 13250 13256 -f 13287 13256 13255 -f 13287 13255 13257 -f 13257 13255 13258 -f 13257 13258 13284 -f 13284 13258 13259 -f 13284 13259 13280 -f 13280 13259 13271 -f 13260 13262 13261 -f 13263 13272 13262 -f 13263 13262 13264 -f 13263 13264 13267 -f 13265 13264 13304 -f 13265 13304 13266 -f 13265 13266 13270 -f 13264 13265 13267 -f 13303 13304 13270 -f 13268 13301 13278 -f 13278 13301 13302 -f 13277 13304 13268 -f 13268 13304 13301 -f 13276 13270 13277 -f 13277 13270 13304 -f 13270 13269 13265 -f 13276 13269 13270 -f 13279 13267 13269 -f 13269 13267 13265 -f 13248 13281 13282 -f 13267 13279 13280 -f 13280 13271 13267 -f 13267 13271 13248 -f 13267 13248 13263 -f 13263 13248 13282 -f 13262 13272 13273 -f 13290 13261 13262 -f 13290 13262 13273 -f 13273 13272 13282 -f 13263 13282 13272 -f 13275 13221 13290 -f 13290 13221 13261 -f 13244 13224 13274 -f 13274 13224 13275 -f 13269 13276 13279 -f 13279 13276 13277 -f 13279 13268 13280 -f 13280 13268 13278 -f 13280 13278 13281 -f 13279 13277 13268 -f 13278 13282 13281 -f 13278 13283 13282 -f 13282 13283 13273 -f 13273 13283 13289 -f 13273 13289 13290 -f 13280 13281 13285 -f 13280 13285 13284 -f 13286 13257 13285 -f 13285 13257 13284 -f 13228 13244 13274 -f 13286 13287 13257 -f 13228 13274 13275 -f 13287 13286 13293 -f 13293 13286 13288 -f 13289 13295 13290 -f 13290 13295 13291 -f 13290 13291 13292 -f 13290 13292 13297 -f 13290 13297 13296 -f 13290 13296 13275 -f 13275 13296 13228 -f 13302 13283 13278 -f 13283 13300 13294 -f 13283 13294 13289 -f 13289 13294 13295 -f 13295 13294 13299 -f 13295 13299 13291 -f 13291 13299 13292 -f 13292 13299 13297 -f 13298 13296 13297 -f 13298 13297 13299 -f 13283 13302 13300 -f 13300 13302 13301 -f 13299 13294 13300 -f 13300 13301 13264 -f 13264 13301 13304 -f 13304 13303 13266 -f 13308 13338 13311 -f 13311 13338 13328 -f 13307 13312 13305 -f 13307 13305 13331 -f 13331 13305 13306 -f 13331 13306 13335 -f 13335 13306 13311 -f 13335 13311 13328 -f 13332 13317 13312 -f 13332 13312 13307 -f 13315 13324 13308 -f 13308 13324 13322 -f 13308 13322 13320 -f 13308 13320 13339 -f 13339 13320 13309 -f 13339 13309 13310 -f 13311 13313 13314 -f 13311 13314 13308 -f 13316 13305 13312 -f 13313 13311 13306 -f 13308 13314 13315 -f 13317 13315 13318 -f 13313 13306 13316 -f 13316 13306 13305 -f 13314 13318 13315 -f 13312 13317 13316 -f 13316 13317 13318 -f 13319 13309 13320 -f 13319 13320 13321 -f 13321 13320 13322 -f 13321 13322 13334 -f 13334 13322 13324 -f 13334 13324 13323 -f 13323 13324 13315 -f 13323 13315 13336 -f 13336 13315 13317 -f 13336 13317 13332 -f 13325 13333 13338 -f 13325 13338 13326 -f 13333 13327 13338 -f 13338 13327 13328 -f 13334 13323 13329 -f 13337 13332 13330 -f 13330 13332 13307 -f 13330 13331 13335 -f 13330 13335 13327 -f 13330 13307 13331 -f 13332 13337 13336 -f 13336 13329 13323 -f 13325 13319 13333 -f 13333 13319 13321 -f 13333 13321 13329 -f 13329 13321 13334 -f 13328 13327 13335 -f 13336 13337 13329 -f 13338 13308 13326 -f 13326 13308 13339 -f 13326 13339 13341 -f 13363 13354 13342 -f 13342 13354 13349 -f 13339 13342 13340 -f 13340 13341 13339 -f 13349 13340 13342 -f 13344 13350 13343 -f 13344 13343 13376 -f 13376 13343 13345 -f 13376 13345 13377 -f 13377 13345 13348 -f 13377 13348 13366 -f 13366 13348 13346 -f 13366 13346 13365 -f 13365 13346 13373 -f 13373 13346 13357 -f 13373 13357 13371 -f 13371 13357 13356 -f 13371 13356 13360 -f 13346 13348 13354 -f 13354 13348 13345 -f 13354 13345 13343 -f 13354 13343 13349 -f 13349 13343 13350 -f 13349 13350 13351 -f 13353 13347 13355 -f 13353 13355 13354 -f 13347 13353 13361 -f 13354 13355 13346 -f 13357 13346 13358 -f 13360 13356 13352 -f 13352 13356 13358 -f 13347 13361 13360 -f 13347 13360 13352 -f 13355 13358 13346 -f 13356 13357 13358 -f 13371 13360 13359 -f 13359 13360 13361 -f 13359 13361 13374 -f 13374 13361 13353 -f 13374 13353 13368 -f 13354 13363 13353 -f 13353 13363 13368 -f 13362 13375 13363 -f 13362 13363 13342 -f 13375 13364 13363 -f 13363 13364 13368 -f 13365 13367 13366 -f 13366 13367 13377 -f 13368 13364 13369 -f 13368 13369 13374 -f 13371 13359 13370 -f 13370 13359 13369 -f 13370 13373 13371 -f 13373 13370 13372 -f 13373 13372 13365 -f 13365 13372 13367 -f 13369 13359 13374 -f 13362 13344 13375 -f 13375 13344 13376 -f 13375 13376 13367 -f 13367 13376 13377 -f 13422 13378 13423 -f 13423 13378 13379 -f 13378 13433 13379 -f 13379 13433 13424 -f 13378 13422 13433 -f 13433 13422 13382 -f 13428 13380 13382 -f 13382 13380 13430 -f 13430 13381 13382 -f 13382 13381 13432 -f 13382 13432 13433 -f 13383 13440 13385 -f 13385 13440 13384 -f 13385 13384 13437 -f 13385 13437 13387 -f 13437 13438 13387 -f 13387 13438 13412 -f 13387 13412 13386 -f 13386 13412 13418 -f 13391 13446 13386 -f 13386 13446 13387 -f 13391 13386 13435 -f 13419 13396 13392 -f 13389 13391 13388 -f 13389 13390 13391 -f 13391 13390 13395 -f 13392 13400 13393 -f 13391 13435 13397 -f 13419 13392 13393 -f 13388 13391 13394 -f 13394 13391 13397 -f 13394 13397 13399 -f 13391 13395 13419 -f 13419 13395 13396 -f 13402 13398 13397 -f 13397 13398 13399 -f 13393 13400 13401 -f 13393 13401 13397 -f 13397 13401 13402 -f 13435 13386 13418 -f 13404 13405 13412 -f 13412 13405 13403 -f 13404 13411 13405 -f 13413 13406 13418 -f 13416 13407 13409 -f 13409 13407 13408 -f 13409 13408 13410 -f 13409 13410 13404 -f 13404 13410 13411 -f 13412 13403 13413 -f 13412 13413 13418 -f 13406 13414 13418 -f 13418 13414 13415 -f 13409 13417 13416 -f 13416 13417 13415 -f 13415 13417 13418 -f 13418 13417 13435 -f 13409 13404 13434 -f 13434 13404 13421 -f 13419 13412 13420 -f 13420 13412 13438 -f 13420 13438 13448 -f 13448 13438 13421 -f 13448 13421 13393 -f 13393 13421 13404 -f 13393 13404 13419 -f 13419 13404 13412 -f 13426 13451 13448 -f 13426 13448 13382 -f 13382 13448 13393 -f 13382 13393 13397 -f 13422 13423 13382 -f 13382 13423 13426 -f 13423 13379 13424 -f 13431 13429 13426 -f 13426 13429 13425 -f 13426 13425 13436 -f 13423 13424 13426 -f 13426 13424 13427 -f 13426 13427 13431 -f 13428 13436 13425 -f 13428 13425 13380 -f 13380 13425 13429 -f 13380 13429 13430 -f 13430 13429 13431 -f 13430 13431 13381 -f 13381 13431 13427 -f 13381 13427 13432 -f 13432 13427 13424 -f 13432 13424 13433 -f 13428 13382 13397 -f 13440 13383 13434 -f 13434 13383 13451 -f 13435 13417 13397 -f 13397 13417 13409 -f 13397 13409 13428 -f 13428 13409 13434 -f 13428 13434 13436 -f 13436 13434 13451 -f 13436 13451 13426 -f 13438 13439 13443 -f 13438 13443 13421 -f 13421 13443 13442 -f 13421 13442 13434 -f 13445 13444 13437 -f 13437 13444 13438 -f 13438 13444 13439 -f 13434 13442 13441 -f 13441 13440 13434 -f 13384 13440 13441 -f 13384 13441 13437 -f 13437 13441 13445 -f 13453 13441 13454 -f 13454 13441 13442 -f 13454 13442 13450 -f 13450 13442 13443 -f 13450 13443 13447 -f 13447 13443 13439 -f 13447 13439 13449 -f 13449 13439 13452 -f 13452 13439 13444 -f 13452 13444 13445 -f 13452 13445 13453 -f 13453 13445 13441 -f 13383 13385 13446 -f 13448 13447 13420 -f 13446 13385 13387 -f 13420 13447 13449 -f 13450 13447 13448 -f 13420 13449 13452 -f 13451 13454 13450 -f 13451 13450 13448 -f 13452 13451 13383 -f 13452 13383 13446 -f 13452 13446 13420 -f 13452 13453 13451 -f 13451 13453 13454 -f 13391 13419 13446 -f 13446 13419 13420 -f 13455 13601 13674 -f 13674 13601 13646 -f 13646 13601 13602 -f 13646 13602 13659 -f 13659 13602 13605 -f 13659 13605 13656 -f 13605 13618 13656 -f 13656 13618 13457 -f 13619 13648 13644 -f 13619 13644 13630 -f 13630 13644 13456 -f 13630 13456 13631 -f 13631 13456 13628 -f 13628 13456 13457 -f 13628 13457 13618 -f 13619 13461 13648 -f 13648 13461 13460 -f 13458 13459 13460 -f 13458 13460 13461 -f 13458 13632 13459 -f 13459 13632 13462 -f 13625 13673 13632 -f 13632 13673 13462 -f 13634 13653 13668 -f 13634 13668 13624 -f 13624 13668 13463 -f 13624 13463 13625 -f 13625 13463 13673 -f 13487 13485 13681 -f 13487 13681 13678 -f 13674 13480 13675 -f 13675 13480 13483 -f 13675 13483 13676 -f 13676 13483 13481 -f 13676 13481 13678 -f 13678 13481 13487 -f 13497 13465 13464 -f 13464 13465 13684 -f 13464 13684 13467 -f 13467 13684 13466 -f 13467 13466 13501 -f 13501 13466 13469 -f 13501 13469 13468 -f 13468 13469 13692 -f 13468 13692 13694 -f 13694 13692 13683 -f 13493 13474 13494 -f 13494 13474 13470 -f 13494 13470 13495 -f 13495 13470 13687 -f 13495 13687 13489 -f 13489 13687 13688 -f 13489 13688 13471 -f 13471 13688 13472 -f 13471 13472 13496 -f 13496 13472 13497 -f 13497 13472 13465 -f 13493 13473 13474 -f 13474 13473 13475 -f 13475 13473 13689 -f 13689 13473 13492 -f 13689 13492 13690 -f 13690 13492 13476 -f 13476 13492 13491 -f 13476 13491 13685 -f 13685 13491 13477 -f 13685 13477 13686 -f 13686 13477 13479 -f 13686 13479 13478 -f 13478 13479 13505 -f 13641 13640 13480 -f 13480 13640 13508 -f 13480 13508 13510 -f 13480 13510 13482 -f 13512 13487 13481 -f 13512 13481 13482 -f 13482 13481 13483 -f 13482 13483 13480 -f 13484 13694 13485 -f 13488 13487 13512 -f 13488 13507 13487 -f 13488 13486 13507 -f 13502 13694 13506 -f 13506 13694 13507 -f 13507 13694 13484 -f 13507 13484 13487 -f 13487 13484 13485 -f 13477 13496 13479 -f 13471 13477 13491 -f 13471 13491 13489 -f 13477 13471 13496 -f 13490 13491 13492 -f 13492 13473 13490 -f 13490 13473 13493 -f 13490 13493 13495 -f 13491 13490 13489 -f 13489 13490 13495 -f 13493 13494 13495 -f 13479 13496 13497 -f 13479 13497 13505 -f 13505 13497 13498 -f 13498 13497 13464 -f 13498 13464 13499 -f 13499 13464 13467 -f 13499 13467 13500 -f 13500 13467 13501 -f 13500 13501 13502 -f 13502 13501 13468 -f 13502 13468 13694 -f 13506 13682 13502 -f 13502 13682 13693 -f 13502 13693 13500 -f 13500 13693 13503 -f 13500 13503 13499 -f 13499 13503 13504 -f 13499 13504 13498 -f 13498 13504 13691 -f 13498 13691 13505 -f 13505 13691 13478 -f 13682 13506 13507 -f 13682 13507 13486 -f 13508 13679 13509 -f 13508 13509 13510 -f 13510 13509 13511 -f 13510 13511 13482 -f 13482 13511 13512 -f 13512 13511 13677 -f 13680 13512 13677 -f 13680 13488 13512 -f 13680 13486 13488 -f 13508 13640 13679 -f 13589 13679 13559 -f 13559 13679 13560 -f 13583 13558 13550 -f 13550 13558 13554 -f 13514 13638 13513 -f 13514 13513 13574 -f 13574 13513 13592 -f 13514 13579 13547 -f 13547 13579 13571 -f 13547 13571 13538 -f 13571 13515 13538 -f 13538 13515 13516 -f 13516 13515 13564 -f 13516 13564 13546 -f 13564 13576 13546 -f 13546 13576 13517 -f 13517 13576 13519 -f 13517 13519 13518 -f 13518 13519 13542 -f 13542 13519 13520 -f 13542 13520 13583 -f 13542 13583 13550 -f 13524 13521 13525 -f 13547 13538 13548 -f 13522 13679 13640 -f 13522 13640 13523 -f 13735 13560 13522 -f 13522 13560 13679 -f 13526 13528 13530 -f 13524 13525 13526 -f 13526 13525 13527 -f 13526 13527 13528 -f 13534 13529 13528 -f 13528 13529 13530 -f 13516 13537 13538 -f 13532 13531 13533 -f 13532 13533 13552 -f 13533 13534 13552 -f 13638 13514 13640 -f 13528 13535 13534 -f 13534 13535 13536 -f 13534 13536 13552 -f 13552 13536 13551 -f 13538 13537 13548 -f 13735 13541 13560 -f 13560 13541 13540 -f 13524 13539 13521 -f 13521 13539 13554 -f 13521 13554 13541 -f 13541 13554 13540 -f 13542 13549 13544 -f 13544 13518 13542 -f 13544 13517 13518 -f 13539 13543 13554 -f 13554 13543 13555 -f 13517 13544 13545 -f 13517 13545 13546 -f 13546 13545 13537 -f 13553 13547 13548 -f 13557 13549 13550 -f 13550 13549 13542 -f 13537 13516 13546 -f 13551 13523 13552 -f 13552 13523 13640 -f 13552 13640 13553 -f 13553 13640 13514 -f 13553 13514 13547 -f 13554 13555 13556 -f 13554 13556 13550 -f 13550 13556 13557 -f 13557 13556 13531 -f 13557 13531 13532 -f 13554 13558 13586 -f 13554 13586 13540 -f 13540 13586 13559 -f 13559 13560 13540 -f 13569 13576 13564 -f 13569 13564 13581 -f 13584 13566 13565 -f 13583 13565 13561 -f 13562 13574 13590 -f 13563 13574 13570 -f 13574 13563 13578 -f 13565 13566 13567 -f 13565 13567 13562 -f 13562 13567 13568 -f 13563 13570 13577 -f 13577 13570 13582 -f 13571 13579 13580 -f 13580 13579 13578 -f 13519 13576 13582 -f 13583 13572 13573 -f 13574 13575 13570 -f 13576 13569 13577 -f 13576 13577 13582 -f 13574 13578 13579 -f 13574 13579 13514 -f 13571 13580 13515 -f 13515 13580 13581 -f 13515 13581 13564 -f 13582 13520 13519 -f 13583 13573 13584 -f 13583 13584 13565 -f 13561 13585 13583 -f 13583 13585 13558 -f 13559 13586 13587 -f 13587 13586 13558 -f 13587 13558 13585 -f 13562 13568 13574 -f 13574 13568 13575 -f 13572 13583 13582 -f 13582 13583 13520 -f 13559 13587 13588 -f 13559 13588 13589 -f 13589 13588 13590 -f 13589 13590 13574 -f 13633 13591 13635 -f 13635 13591 13455 -f 13635 13455 13636 -f 13636 13455 13589 -f 13636 13589 13592 -f 13592 13589 13574 -f 13625 13593 13591 -f 13594 13455 13597 -f 13604 13601 13594 -f 13594 13601 13455 -f 13591 13593 13599 -f 13591 13599 13455 -f 13603 13608 13606 -f 13595 13600 13619 -f 13619 13600 13461 -f 13461 13600 13596 -f 13596 13458 13461 -f 13623 13597 13598 -f 13598 13597 13455 -f 13598 13455 13599 -f 13607 13617 13605 -f 13601 13604 13602 -f 13603 13605 13604 -f 13604 13605 13602 -f 13603 13606 13605 -f 13605 13606 13607 -f 13610 13595 13629 -f 13603 13609 13608 -f 13610 13629 13611 -f 13610 13611 13598 -f 13613 13612 13616 -f 13608 13609 13615 -f 13608 13615 13614 -f 13614 13615 13612 -f 13611 13616 13598 -f 13605 13617 13618 -f 13618 13617 13626 -f 13595 13619 13629 -f 13613 13620 13612 -f 13612 13620 13614 -f 13612 13621 13616 -f 13616 13621 13622 -f 13616 13622 13598 -f 13598 13622 13623 -f 13591 13634 13624 -f 13591 13624 13625 -f 13626 13627 13618 -f 13618 13627 13628 -f 13628 13627 13629 -f 13628 13629 13631 -f 13619 13630 13629 -f 13629 13630 13631 -f 13625 13458 13596 -f 13625 13632 13458 -f 13591 13633 13634 -f 13634 13633 13642 -f 13634 13642 13653 -f 13653 13642 13643 -f 13633 13635 13642 -f 13642 13635 13637 -f 13635 13636 13637 -f 13637 13636 13639 -f 13636 13592 13639 -f 13639 13592 13513 -f 13513 13638 13639 -f 13639 13638 13640 -f 13639 13640 13637 -f 13637 13640 13641 -f 13637 13641 13642 -f 13642 13641 13643 -f 13653 13643 13655 -f 13655 13643 13652 -f 13457 13650 13645 -f 13649 13456 13644 -f 13457 13645 13656 -f 13656 13645 13657 -f 13646 13660 13674 -f 13674 13660 13647 -f 13674 13647 13641 -f 13644 13648 13649 -f 13661 13658 13656 -f 13641 13647 13651 -f 13641 13651 13643 -f 13643 13651 13652 -f 13654 13653 13655 -f 13664 13648 13460 -f 13664 13460 13667 -f 13660 13646 13659 -f 13660 13659 13658 -f 13650 13457 13649 -f 13649 13457 13456 -f 13662 13661 13656 -f 13662 13656 13657 -f 13656 13658 13659 -f 13661 13662 13663 -f 13661 13663 13654 -f 13654 13663 13669 -f 13654 13668 13653 -f 13648 13664 13665 -f 13648 13665 13649 -f 13666 13672 13671 -f 13462 13666 13459 -f 13459 13666 13667 -f 13459 13667 13460 -f 13654 13669 13668 -f 13668 13669 13670 -f 13668 13670 13672 -f 13668 13672 13463 -f 13672 13666 13462 -f 13672 13462 13463 -f 13665 13671 13649 -f 13649 13671 13672 -f 13462 13673 13463 -f 13641 13480 13674 -f 13675 13455 13674 -f 13455 13675 13676 -f 13455 13676 13589 -f 13677 13676 13678 -f 13680 13677 13678 -f 13676 13677 13511 -f 13676 13511 13589 -f 13511 13509 13589 -f 13589 13509 13679 -f 13681 13485 13683 -f 13681 13682 13678 -f 13486 13680 13682 -f 13682 13680 13678 -f 13682 13681 13683 -f 13682 13683 13693 -f 13478 13684 13465 -f 13478 13465 13686 -f 13465 13472 13686 -f 13686 13472 13688 -f 13476 13685 13688 -f 13688 13685 13686 -f 13470 13474 13687 -f 13687 13474 13475 -f 13687 13475 13690 -f 13690 13476 13687 -f 13687 13476 13688 -f 13475 13689 13690 -f 13478 13691 13684 -f 13684 13691 13504 -f 13684 13504 13466 -f 13466 13504 13503 -f 13466 13503 13469 -f 13469 13503 13693 -f 13469 13693 13692 -f 13692 13693 13683 -f 13694 13683 13485 -f 13735 13736 13695 -f 13695 13736 13737 -f 13695 13737 13696 -f 13696 13737 13698 -f 13696 13698 13697 -f 13697 13698 13699 -f 13697 13699 13700 -f 13700 13699 13738 -f 13700 13738 13702 -f 13702 13738 13701 -f 13702 13701 13703 -f 13703 13701 13704 -f 13703 13704 13705 -f 13705 13704 13739 -f 13705 13739 13706 -f 13706 13739 13708 -f 13706 13708 13707 -f 13707 13708 13710 -f 13707 13710 13709 -f 13709 13710 13711 -f 13709 13711 13712 -f 13712 13711 13713 -f 13712 13713 13714 -f 13714 13713 13740 -f 13714 13740 13527 -f 13527 13740 13742 -f 13527 13742 13715 -f 13715 13742 13717 -f 13715 13717 13716 -f 13716 13717 13718 -f 13716 13718 13719 -f 13719 13718 13743 -f 13719 13743 13720 -f 13720 13743 13721 -f 13720 13721 13722 -f 13722 13721 13723 -f 13722 13723 13724 -f 13724 13723 13744 -f 13724 13744 13725 -f 13725 13744 13726 -f 13725 13726 13728 -f 13728 13726 13727 -f 13728 13727 13729 -f 13729 13727 13745 -f 13729 13745 13730 -f 13730 13745 13731 -f 13730 13731 13732 -f 13732 13731 13734 -f 13732 13734 13733 -f 13733 13734 13741 -f 13733 13741 13735 -f 13735 13741 13736 -f 13699 13698 13741 -f 13741 13698 13737 -f 13741 13737 13736 -f 13704 13701 13741 -f 13741 13701 13738 -f 13741 13738 13699 -f 13710 13708 13741 -f 13741 13708 13739 -f 13741 13739 13704 -f 13740 13713 13741 -f 13741 13713 13711 -f 13741 13711 13710 -f 13718 13717 13741 -f 13741 13717 13742 -f 13741 13742 13740 -f 13723 13721 13741 -f 13741 13721 13743 -f 13741 13743 13718 -f 13727 13726 13741 -f 13741 13726 13744 -f 13741 13744 13723 -f 13734 13731 13741 -f 13741 13731 13745 -f 13741 13745 13727 -f 13751 13762 13766 -f 13751 13766 13750 -f 13750 13766 13755 -f 13755 13766 13767 -f 13751 13752 13762 -f 13762 13752 13763 -f 13784 13765 13763 -f 13784 13763 13752 -f 13784 13752 13746 -f 13784 13746 13747 -f 13784 13747 13818 -f 13754 13748 13751 -f 13749 13759 13818 -f 13749 13818 13747 -f 13759 13749 13753 -f 13754 13751 13750 -f 13751 13748 13752 -f 13752 13748 13746 -f 13759 13753 13755 -f 13753 13754 13755 -f 13754 13750 13755 -f 13870 13859 13817 -f 13817 13859 13842 -f 13865 13870 13756 -f 13756 13870 13817 -f 13864 13865 13826 -f 13826 13865 13756 -f 13864 13826 13849 -f 13849 13826 13827 -f 13849 13827 13816 -f 13849 13816 13860 -f 13860 13816 13811 -f 13860 13811 13757 -f 13757 13811 13758 -f 13758 13811 13810 -f 13758 13810 13848 -f 13755 13767 13759 -f 13759 13767 13848 -f 13759 13848 13810 -f 13761 13762 13760 -f 13760 13762 13763 -f 13768 13769 13848 -f 13761 13767 13766 -f 13770 13764 13769 -f 13763 13765 13760 -f 13761 13766 13762 -f 13767 13761 13768 -f 13767 13768 13848 -f 13848 13769 13764 -f 13764 13770 13765 -f 13765 13770 13760 -f 13771 13786 13772 -f 13771 13772 13783 -f 13771 13778 13786 -f 13786 13778 13789 -f 13773 13794 13774 -f 13773 13774 13780 -f 13780 13774 13789 -f 13780 13789 13778 -f 13776 13781 13782 -f 13777 13773 13780 -f 13773 13777 13775 -f 13773 13775 13808 -f 13775 13776 13808 -f 13808 13776 13782 -f 13771 13783 13779 -f 13777 13778 13779 -f 13779 13778 13771 -f 13777 13780 13778 -f 13782 13781 13783 -f 13783 13781 13779 -f 13765 13784 13764 -f 13764 13784 13818 -f 13764 13818 13785 -f 13785 13818 13782 -f 13785 13782 13772 -f 13772 13782 13783 -f 13787 13772 13786 -f 13772 13787 13788 -f 13772 13788 13785 -f 13795 13792 13789 -f 13785 13788 13791 -f 13785 13791 13790 -f 13790 13791 13793 -f 13795 13789 13774 -f 13789 13792 13786 -f 13786 13792 13787 -f 13790 13793 13794 -f 13793 13795 13794 -f 13795 13774 13794 -f 13794 13773 13790 -f 13790 13773 13808 -f 13790 13808 13807 -f 13790 13807 13850 -f 13850 13807 13809 -f 13850 13809 13856 -f 13856 13809 13796 -f 13856 13796 13867 -f 13867 13796 13797 -f 13867 13797 13813 -f 13867 13813 13798 -f 13798 13813 13853 -f 13853 13813 13825 -f 13863 13853 13814 -f 13814 13853 13825 -f 13854 13863 13822 -f 13822 13863 13814 -f 13855 13815 13821 -f 13855 13821 13851 -f 13851 13821 13799 -f 13851 13799 13852 -f 13852 13799 13800 -f 13852 13800 13869 -f 13869 13800 13801 -f 13801 13800 13820 -f 13801 13820 13802 -f 13802 13820 13819 -f 13802 13819 13803 -f 13802 13803 13866 -f 13866 13803 13804 -f 13804 13803 13805 -f 13804 13805 13806 -f 13806 13805 13815 -f 13806 13815 13855 -f 13807 13808 13782 -f 13818 13809 13782 -f 13782 13809 13807 -f 13759 13810 13818 -f 13818 13810 13811 -f 13818 13811 13842 -f 13842 13811 13816 -f 13880 13826 13756 -f 13880 13756 13882 -f 13812 13813 13842 -f 13842 13813 13797 -f 13842 13797 13818 -f 13818 13797 13796 -f 13825 13800 13814 -f 13814 13800 13799 -f 13822 13815 13805 -f 13842 13816 13827 -f 13842 13823 13817 -f 13817 13823 13872 -f 13818 13796 13809 -f 13825 13819 13820 -f 13825 13820 13800 -f 13799 13821 13814 -f 13814 13821 13815 -f 13814 13815 13822 -f 13812 13822 13813 -f 13813 13822 13803 -f 13813 13803 13825 -f 13825 13803 13819 -f 13827 13875 13842 -f 13842 13875 13823 -f 13872 13824 13817 -f 13817 13824 13756 -f 13756 13824 13882 -f 13805 13803 13822 -f 13880 13879 13826 -f 13827 13877 13875 -f 13826 13879 13877 -f 13826 13877 13827 -f 13857 13854 13812 -f 13812 13854 13822 -f 13845 13846 13836 -f 13836 13846 13841 -f 13845 13836 13828 -f 13828 13836 13837 -f 13828 13837 13844 -f 13844 13837 13835 -f 13830 13844 13833 -f 13833 13844 13835 -f 13829 13830 13832 -f 13832 13830 13833 -f 13859 13831 13838 -f 13837 13834 13835 -f 13831 13836 13841 -f 13832 13833 13834 -f 13834 13833 13835 -f 13836 13831 13837 -f 13837 13831 13834 -f 13841 13840 13831 -f 13831 13840 13838 -f 13839 13842 13838 -f 13839 13838 13840 -f 13839 13840 13847 -f 13847 13840 13841 -f 13847 13841 13846 -f 13858 13857 13839 -f 13839 13857 13812 -f 13839 13812 13842 -f 13838 13842 13859 -f 13844 13830 13829 -f 13829 13843 13844 -f 13844 13843 13828 -f 13828 13843 13858 -f 13828 13858 13845 -f 13845 13858 13846 -f 13846 13858 13847 -f 13847 13858 13839 -f 13859 13849 13860 -f 13758 13848 13764 -f 13873 13864 13849 -f 13785 13790 13850 -f 13785 13850 13764 -f 13764 13850 13856 -f 13857 13804 13854 -f 13854 13804 13806 -f 13852 13869 13853 -f 13806 13855 13854 -f 13854 13855 13863 -f 13863 13855 13851 -f 13864 13878 13865 -f 13870 13873 13849 -f 13870 13849 13859 -f 13866 13804 13764 -f 13764 13804 13861 -f 13861 13804 13857 -f 13861 13857 13858 -f 13859 13860 13861 -f 13861 13860 13757 -f 13861 13757 13764 -f 13764 13757 13758 -f 13878 13862 13865 -f 13852 13853 13863 -f 13852 13863 13851 -f 13873 13874 13864 -f 13864 13874 13876 -f 13864 13876 13878 -f 13862 13881 13865 -f 13856 13867 13764 -f 13764 13867 13866 -f 13866 13867 13798 -f 13798 13801 13802 -f 13798 13802 13866 -f 13870 13871 13868 -f 13870 13868 13873 -f 13853 13869 13801 -f 13853 13801 13798 -f 13865 13881 13871 -f 13865 13871 13870 -f 13871 13824 13872 -f 13871 13872 13868 -f 13868 13872 13823 -f 13868 13823 13873 -f 13873 13823 13875 -f 13873 13875 13874 -f 13874 13875 13876 -f 13876 13875 13877 -f 13876 13877 13878 -f 13878 13877 13879 -f 13878 13879 13880 -f 13878 13880 13862 -f 13862 13880 13882 -f 13862 13882 13881 -f 13881 13882 13824 -f 13881 13824 13871 -f 13883 13897 13885 -f 13887 13903 13898 -f 13895 13899 13884 -f 13885 13895 13886 -f 13886 13895 13884 -f 13883 13885 13886 -f 13887 13898 13883 -f 13883 13898 13897 -f 13901 13903 13907 -f 13900 13901 13888 -f 13888 13901 13907 -f 13884 13899 13888 -f 13888 13899 13900 -f 13907 13903 13887 -f 13911 13915 13912 -f 13915 13913 13912 -f 13892 13889 13893 -f 13893 13889 13911 -f 13893 13911 13894 -f 13894 13911 13912 -f 13894 13912 13896 -f 13896 13912 13914 -f 13896 13914 13891 -f 13891 13914 13913 -f 13891 13913 13902 -f 13902 13913 13915 -f 13902 13915 13890 -f 13890 13915 13916 -f 13890 13916 13892 -f 13892 13916 13889 -f 13897 13892 13893 -f 13897 13893 13885 -f 13885 13893 13894 -f 13885 13894 13895 -f 13895 13894 13896 -f 13895 13896 13899 -f 13899 13896 13900 -f 13900 13896 13891 -f 13900 13891 13902 -f 13900 13902 13901 -f 13903 13902 13890 -f 13903 13890 13898 -f 13898 13890 13892 -f 13898 13892 13897 -f 13901 13902 13903 -f 13884 13888 13910 -f 13910 13888 13909 -f 13886 13884 13904 -f 13904 13884 13910 -f 13883 13886 13905 -f 13905 13886 13904 -f 13887 13883 13906 -f 13906 13883 13905 -f 13907 13887 13908 -f 13908 13887 13906 -f 13888 13907 13909 -f 13909 13907 13908 -f 13908 13906 13909 -f 13909 13906 13905 -f 13909 13905 13910 -f 13910 13905 13904 -f 13914 13912 13913 -f 13916 13915 13911 -f 13916 13911 13889 -f 13920 13935 13936 -f 13921 13940 13918 -f 13919 13937 13917 -f 13917 13937 13932 -f 13920 13936 13919 -f 13919 13936 13937 -f 13918 13940 13920 -f 13920 13940 13935 -f 13923 13939 13921 -f 13922 13938 13939 -f 13922 13939 13923 -f 13932 13938 13917 -f 13917 13938 13922 -f 13923 13921 13918 -f 13949 13948 13926 -f 13934 13947 13930 -f 13930 13947 13948 -f 13930 13948 13931 -f 13931 13948 13924 -f 13931 13924 13925 -f 13931 13925 13929 -f 13929 13925 13949 -f 13929 13949 13928 -f 13928 13949 13950 -f 13928 13950 13927 -f 13927 13950 13926 -f 13927 13926 13933 -f 13933 13926 13947 -f 13933 13947 13934 -f 13935 13934 13936 -f 13936 13934 13930 -f 13936 13930 13931 -f 13936 13931 13937 -f 13937 13931 13932 -f 13932 13931 13929 -f 13932 13929 13938 -f 13938 13929 13928 -f 13938 13928 13939 -f 13939 13928 13927 -f 13939 13927 13921 -f 13921 13927 13940 -f 13940 13927 13933 -f 13940 13933 13935 -f 13935 13933 13934 -f 13917 13922 13946 -f 13946 13922 13943 -f 13919 13917 13941 -f 13941 13917 13946 -f 13920 13919 13945 -f 13945 13919 13941 -f 13918 13920 13944 -f 13944 13920 13945 -f 13923 13918 13942 -f 13942 13918 13944 -f 13922 13923 13943 -f 13943 13923 13942 -f 13942 13944 13943 -f 13943 13944 13945 -f 13943 13945 13946 -f 13946 13945 13941 -f 13947 13926 13948 -f 13924 13948 13949 -f 13924 13949 13925 -f 13950 13949 13926 -f 13954 13972 13973 -f 13951 13967 13971 -f 13971 13972 13953 -f 13953 13972 13954 -f 13951 13971 13953 -f 13952 13976 13967 -f 13952 13967 13951 -f 13974 13975 13956 -f 13956 13975 13955 -f 13954 13973 13956 -f 13956 13973 13974 -f 13975 13976 13955 -f 13955 13976 13952 -f 13985 13960 13958 -f 13969 13985 13957 -f 13969 13957 13965 -f 13965 13957 13966 -f 13966 13957 13958 -f 13966 13958 13959 -f 13966 13959 13964 -f 13964 13959 13983 -f 13964 13983 13963 -f 13963 13983 13960 -f 13963 13960 13962 -f 13962 13960 13984 -f 13962 13984 13961 -f 13961 13984 13985 -f 13961 13985 13969 -f 13967 13969 13970 -f 13970 13969 13965 -f 13970 13965 13971 -f 13971 13965 13966 -f 13971 13966 13972 -f 13972 13966 13973 -f 13973 13966 13964 -f 13973 13964 13974 -f 13974 13964 13963 -f 13974 13963 13968 -f 13968 13963 13962 -f 13968 13962 13975 -f 13975 13962 13961 -f 13975 13961 13976 -f 13976 13961 13969 -f 13976 13969 13967 -f 13967 13970 13971 -f 13974 13968 13975 -f 13954 13956 13981 -f 13981 13956 13978 -f 13953 13954 13977 -f 13977 13954 13981 -f 13951 13953 13982 -f 13982 13953 13977 -f 13952 13951 13980 -f 13980 13951 13982 -f 13955 13952 13979 -f 13979 13952 13980 -f 13956 13955 13978 -f 13978 13955 13979 -f 13979 13980 13978 -f 13978 13980 13982 -f 13978 13982 13981 -f 13981 13982 13977 -f 13957 13985 13958 -f 13959 13958 13960 -f 13959 13960 13983 -f 13984 13960 13985 -f 13991 14102 14105 -f 13991 14105 14001 -f 14001 14105 14107 -f 14001 14107 14108 -f 14001 14108 14000 -f 14000 13986 13999 -f 13999 13986 13987 -f 13999 13987 13994 -f 13994 13987 14106 -f 13994 14106 13995 -f 13995 14106 14101 -f 13995 14101 13993 -f 13993 14101 14104 -f 13993 14104 14103 -f 13993 14103 13988 -f 13988 13989 13997 -f 13997 13989 13990 -f 13997 13990 13998 -f 13998 13990 14102 -f 13998 14102 13991 -f 14003 13998 13992 -f 13992 13998 13991 -f 13992 13991 14010 -f 13996 13993 13988 -f 13996 13988 14004 -f 13996 13995 13993 -f 14006 13994 14005 -f 14005 13994 13995 -f 14005 13995 13996 -f 14004 13988 13997 -f 14004 13997 14003 -f 14003 13997 13998 -f 14007 14000 13999 -f 14007 13999 14006 -f 14006 13999 13994 -f 14009 14001 14000 -f 14009 14000 14007 -f 14010 13991 14001 -f 14010 14001 14009 -f 13992 14014 14003 -f 14002 14003 14014 -f 14002 14004 14003 -f 14013 14004 14002 -f 14013 13996 14004 -f 14011 13996 14013 -f 13996 14011 14005 -f 14012 14005 14011 -f 14005 14012 14006 -f 14006 14012 14008 -f 14008 14007 14006 -f 14009 14007 14008 -f 13992 14010 14014 -f 14009 14017 14010 -f 14010 14017 14014 -f 14012 14015 14008 -f 14008 14017 14009 -f 14008 14015 14017 -f 14014 14017 14002 -f 14002 14016 14013 -f 14013 14016 14011 -f 14011 14015 14012 -f 14002 14017 14016 -f 14011 14016 14015 -f 14015 14016 14017 -f 14029 14028 14018 -f 14029 14018 14019 -f 14019 14018 14100 -f 14019 14100 14020 -f 14020 14021 14099 -f 14020 14099 14033 -f 14033 14099 14022 -f 14022 14099 14023 -f 14022 14023 14024 -f 14024 14023 14097 -f 14024 14097 14025 -f 14025 14097 14095 -f 14025 14095 14026 -f 14026 14096 14031 -f 14031 14096 14027 -f 14031 14027 14032 -f 14032 14027 14098 -f 14032 14098 14030 -f 14030 14098 14028 -f 14030 14028 14029 -f 14035 14030 14034 -f 14034 14030 14029 -f 14034 14029 14039 -f 14036 14026 14031 -f 14037 14025 14041 -f 14041 14025 14026 -f 14041 14026 14036 -f 14044 14022 14037 -f 14037 14022 14024 -f 14037 14024 14025 -f 14036 14031 14035 -f 14035 14031 14032 -f 14035 14032 14030 -f 14038 14033 14044 -f 14044 14033 14022 -f 14039 14020 14038 -f 14038 14020 14033 -f 14039 14029 14019 -f 14039 14019 14020 -f 14034 14047 14035 -f 14035 14047 14045 -f 14045 14036 14035 -f 14041 14040 14037 -f 14043 14038 14044 -f 14038 14046 14039 -f 14042 14039 14046 -f 14039 14042 14034 -f 14034 14042 14047 -f 14046 14038 14043 -f 14044 14037 14040 -f 14044 14040 14043 -f 14045 14049 14036 -f 14036 14049 14041 -f 14041 14049 14040 -f 14043 14048 14046 -f 14046 14048 14042 -f 14042 14048 14047 -f 14045 14047 14049 -f 14040 14049 14043 -f 14043 14049 14048 -f 14047 14048 14049 -f 14050 14063 14065 -f 14063 14050 14360 -f 14065 14358 14405 -f 14398 14053 14397 -f 14059 14405 14054 -f 14398 14061 14055 -f 14052 14356 14051 -f 14358 14054 14405 -f 14052 14051 14397 -f 14053 14398 14055 -f 14054 14060 14059 -f 14056 14057 14058 -f 14063 14358 14065 -f 14404 14059 14060 -f 14343 14360 14050 -f 14342 14051 14356 -f 14061 14349 14055 -f 14061 14062 14349 -f 14342 14356 14355 -f 14060 14364 14404 -f 14364 14064 14404 -f 14090 14381 14395 -f 14342 14355 14066 -f 14062 14351 14349 -f 14070 14067 14363 -f 14072 14343 14066 -f 14062 14071 14351 -f 14363 14067 14364 -f 14375 14076 14068 -f 14069 14072 14353 -f 14353 14073 14069 -f 14343 14342 14066 -f 14073 14361 14069 -f 14375 14373 14073 -f 14345 14056 14058 -f 14074 14070 14363 -f 14074 14361 14070 -f 14353 14056 14345 -f 14071 14058 14351 -f 14073 14353 14345 -f 14072 14066 14353 -f 14345 14385 14075 -f 14345 14386 14385 -f 14084 14079 14091 -f 14361 14073 14070 -f 14345 14075 14076 -f 14345 14077 14386 -f 14375 14073 14076 -f 14053 14052 14397 -f 14077 14387 14386 -f 14369 14375 14068 -f 14068 14331 14369 -f 14390 14087 14068 -f 14387 14077 14078 -f 14331 14371 14369 -f 14073 14345 14076 -f 14079 14084 14402 -f 14382 14387 14078 -f 14331 14083 14371 -f 14080 14087 14390 -f 14078 14391 14382 -f 14084 14082 14402 -f 14072 14360 14343 -f 14402 14082 14081 -f 14383 14382 14391 -f 14090 14333 14080 -f 14383 14391 14085 -f 14083 14372 14371 -f 14058 14057 14351 -f 14081 14082 14400 -f 14082 14086 14400 -f 14083 14330 14372 -f 14067 14064 14364 -f 14330 14088 14372 -f 14085 14381 14383 -f 14373 14091 14073 -f 14085 14394 14381 -f 14087 14331 14068 -f 14088 14330 14089 -f 14381 14394 14395 -f 14089 14400 14086 -f 14079 14073 14091 -f 14086 14088 14089 -f 14333 14087 14080 -f 14134 14132 14133 -f 14133 14132 14135 -f 14333 14090 14395 -f 14135 14131 14130 -f 14136 14135 14130 -f 14093 14136 14092 -f 14136 14130 14092 -f 14126 14129 14128 -f 14093 14092 14129 -f 14132 14131 14135 -f 14126 14093 14129 -f 14126 14128 14094 -f 14026 14095 14096 -f 14097 14023 14098 -f 14095 14097 14096 -f 14097 14027 14096 -f 14097 14098 14027 -f 14098 14023 14028 -f 14023 14099 14028 -f 14018 14028 14099 -f 14094 14128 14127 -f 14100 14018 14099 -f 14099 14021 14100 -f 14103 13989 13988 -f 13987 13986 14108 -f 13990 13989 14103 -f 14103 14104 13990 -f 14021 14020 14100 -f 14102 13990 14101 -f 14104 14101 13990 -f 14102 14101 14105 -f 14106 13987 14105 -f 14107 14105 13987 -f 14101 14106 14105 -f 14107 13987 14108 -f 14109 14114 14279 -f 14277 14276 14279 -f 14114 14277 14279 -f 14123 14161 14162 -f 14110 14292 14291 -f 14276 14219 14279 -f 14219 14280 14279 -f 14219 14282 14281 -f 14219 14284 14282 -f 14219 14111 14284 -f 14111 14110 14284 -f 14111 14292 14110 -f 14110 14291 14112 -f 14110 14112 14113 -f 13986 14000 14108 -f 14116 14287 14113 -f 14208 14206 14289 -f 14115 14116 14113 -f 14113 14117 14115 -f 14117 14289 14115 -f 14117 14209 14289 -f 14215 14214 14162 -f 14209 14208 14289 -f 14122 14211 14118 -f 14161 14217 14121 -f 14206 14122 14289 -f 14122 14118 14289 -f 14122 14212 14211 -f 14122 14119 14212 -f 14122 14120 14119 -f 14120 14161 14119 -f 14120 14217 14161 -f 14161 14121 14216 -f 14161 14216 14162 -f 14287 14110 14113 -f 14214 14123 14162 -f 14219 14281 14280 -f 14162 14124 14215 -f 14145 14093 14126 -f 14145 14126 14125 -f 14125 14126 14094 -f 14125 14094 14143 -f 14143 14094 14127 -f 14127 14128 14142 -f 14142 14128 14129 -f 14142 14129 14092 -f 14142 14092 14141 -f 14141 14092 14130 -f 14141 14130 14139 -f 14139 14130 14131 -f 14139 14131 14140 -f 14140 14131 14132 -f 14140 14132 14134 -f 14134 14133 14135 -f 14134 14135 14137 -f 14137 14135 14136 -f 14137 14136 14145 -f 14145 14136 14093 -f 14146 14137 14138 -f 14138 14137 14145 -f 14149 14140 14134 -f 14149 14134 14147 -f 14152 14139 14140 -f 14152 14140 14149 -f 14150 14142 14141 -f 14150 14141 14152 -f 14152 14141 14139 -f 14147 14134 14146 -f 14146 14134 14137 -f 14151 14127 14142 -f 14151 14142 14150 -f 14144 14143 14151 -f 14151 14143 14127 -f 14138 14145 14125 -f 14138 14125 14144 -f 14144 14125 14143 -f 14138 14154 14146 -f 14148 14146 14154 -f 14148 14147 14146 -f 14157 14147 14148 -f 14157 14149 14147 -f 14149 14157 14153 -f 14149 14153 14152 -f 14152 14156 14150 -f 14150 14156 14151 -f 14155 14144 14158 -f 14158 14144 14151 -f 14144 14155 14138 -f 14138 14155 14154 -f 14158 14151 14156 -f 14155 14159 14154 -f 14154 14159 14148 -f 14148 14160 14157 -f 14152 14153 14156 -f 14158 14159 14155 -f 14157 14160 14153 -f 14159 14160 14148 -f 14156 14159 14158 -f 14153 14160 14156 -f 14156 14160 14159 -f 14205 14218 14122 -f 14122 14218 14120 -f 14119 14161 14213 -f 14213 14161 14168 -f 14124 14162 14163 -f 14163 14162 14166 -f 14165 14218 14181 -f 14181 14218 14205 -f 14164 14218 14165 -f 14188 14163 14165 -f 14165 14163 14166 -f 14165 14166 14164 -f 14188 14167 14213 -f 14210 14167 14227 -f 14227 14167 14181 -f 14227 14181 14207 -f 14181 14205 14207 -f 14213 14168 14188 -f 14168 14169 14188 -f 14188 14169 14163 -f 14210 14213 14167 -f 14167 14188 14171 -f 14167 14171 14170 -f 14170 14171 14204 -f 14170 14204 14185 -f 14199 14198 14196 -f 14199 14196 14172 -f 14172 14196 14173 -f 14172 14173 14174 -f 14174 14173 14194 -f 14174 14194 14184 -f 14184 14194 14165 -f 14184 14165 14181 -f 14186 14195 14179 -f 14179 14195 14175 -f 14179 14175 14176 -f 14176 14175 14187 -f 14176 14187 14180 -f 14180 14187 14192 -f 14180 14192 14177 -f 14177 14192 14191 -f 14177 14191 14178 -f 14178 14191 14190 -f 14178 14190 14182 -f 14182 14190 14189 -f 14182 14189 14183 -f 14183 14189 14193 -f 14183 14193 14202 -f 14202 14193 14197 -f 14186 14179 14167 -f 14179 14176 14167 -f 14167 14176 14180 -f 14167 14180 14181 -f 14180 14177 14181 -f 14181 14177 14178 -f 14181 14178 14182 -f 14182 14183 14181 -f 14181 14183 14202 -f 14181 14202 14184 -f 14184 14202 14174 -f 14167 14170 14186 -f 14186 14170 14185 -f 14200 14199 14202 -f 14202 14199 14172 -f 14202 14172 14174 -f 14171 14188 14195 -f 14195 14188 14175 -f 14165 14193 14189 -f 14165 14192 14188 -f 14188 14192 14187 -f 14188 14187 14175 -f 14189 14190 14165 -f 14165 14190 14191 -f 14165 14191 14192 -f 14193 14165 14197 -f 14197 14165 14194 -f 14197 14194 14173 -f 14203 14204 14195 -f 14195 14204 14171 -f 14173 14196 14197 -f 14197 14196 14198 -f 14197 14198 14201 -f 14198 14199 14200 -f 14198 14200 14201 -f 14201 14200 14202 -f 14201 14202 14197 -f 14195 14186 14203 -f 14203 14186 14185 -f 14203 14185 14204 -f 14205 14122 14206 -f 14205 14206 14207 -f 14207 14206 14208 -f 14207 14208 14209 -f 14207 14209 14227 -f 14227 14209 14117 -f 14210 14289 14118 -f 14210 14118 14211 -f 14210 14211 14213 -f 14213 14211 14212 -f 14213 14212 14119 -f 14168 14161 14123 -f 14168 14123 14169 -f 14169 14123 14214 -f 14169 14214 14215 -f 14169 14215 14163 -f 14163 14215 14124 -f 14166 14162 14216 -f 14166 14216 14164 -f 14164 14216 14121 -f 14164 14121 14218 -f 14218 14121 14217 -f 14218 14217 14120 -f 14273 14224 14219 -f 14219 14224 14111 -f 14109 14279 14278 -f 14278 14279 14220 -f 14284 14110 14285 -f 14285 14110 14222 -f 14227 14117 14113 -f 14290 14227 14113 -f 14223 14224 14242 -f 14242 14224 14273 -f 14242 14273 14274 -f 14210 14223 14225 -f 14210 14225 14288 -f 14290 14293 14223 -f 14242 14274 14275 -f 14221 14285 14225 -f 14225 14285 14222 -f 14225 14222 14286 -f 14275 14278 14242 -f 14242 14278 14221 -f 14221 14278 14220 -f 14223 14293 14224 -f 14225 14286 14288 -f 14220 14226 14221 -f 14226 14283 14221 -f 14221 14283 14285 -f 14223 14227 14290 -f 14223 14210 14227 -f 14221 14225 14247 -f 14221 14247 14228 -f 14228 14247 14272 -f 14228 14272 14246 -f 14229 14256 14251 -f 14229 14251 14230 -f 14230 14251 14232 -f 14230 14232 14231 -f 14231 14232 14223 -f 14231 14223 14242 -f 14245 14253 14233 -f 14233 14253 14248 -f 14233 14248 14240 -f 14240 14248 14234 -f 14240 14234 14236 -f 14236 14234 14235 -f 14236 14235 14241 -f 14241 14235 14237 -f 14241 14237 14243 -f 14243 14237 14249 -f 14243 14249 14244 -f 14244 14249 14250 -f 14244 14250 14238 -f 14238 14250 14239 -f 14238 14239 14265 -f 14265 14239 14252 -f 14245 14233 14221 -f 14233 14240 14221 -f 14221 14240 14236 -f 14221 14236 14242 -f 14236 14241 14242 -f 14242 14241 14243 -f 14242 14243 14244 -f 14244 14238 14242 -f 14242 14238 14265 -f 14242 14265 14231 -f 14270 14268 14245 -f 14221 14228 14245 -f 14245 14228 14246 -f 14245 14246 14270 -f 14268 14267 14245 -f 14245 14267 14266 -f 14263 14257 14229 -f 14263 14229 14265 -f 14265 14229 14230 -f 14265 14230 14231 -f 14257 14263 14262 -f 14257 14262 14258 -f 14247 14225 14253 -f 14253 14225 14248 -f 14223 14235 14225 -f 14225 14235 14234 -f 14225 14234 14248 -f 14250 14249 14223 -f 14223 14249 14237 -f 14223 14237 14235 -f 14232 14252 14223 -f 14223 14252 14239 -f 14223 14239 14250 -f 14232 14251 14252 -f 14252 14251 14256 -f 14252 14256 14264 -f 14264 14256 14259 -f 14269 14271 14254 -f 14254 14271 14253 -f 14253 14271 14272 -f 14253 14272 14247 -f 14260 14261 14259 -f 14259 14261 14264 -f 14254 14255 14269 -f 14256 14229 14257 -f 14256 14257 14259 -f 14259 14257 14258 -f 14259 14258 14260 -f 14260 14258 14262 -f 14260 14262 14261 -f 14261 14262 14263 -f 14261 14263 14264 -f 14264 14263 14265 -f 14264 14265 14252 -f 14253 14245 14254 -f 14254 14245 14266 -f 14254 14266 14255 -f 14255 14266 14267 -f 14255 14267 14268 -f 14255 14268 14269 -f 14269 14268 14270 -f 14269 14270 14271 -f 14271 14270 14246 -f 14271 14246 14272 -f 14273 14219 14276 -f 14273 14276 14274 -f 14274 14276 14275 -f 14275 14276 14277 -f 14275 14277 14114 -f 14275 14114 14278 -f 14278 14114 14109 -f 14220 14279 14280 -f 14220 14280 14226 -f 14226 14280 14281 -f 14226 14281 14283 -f 14283 14281 14282 -f 14283 14282 14285 -f 14285 14282 14284 -f 14222 14110 14287 -f 14222 14287 14286 -f 14286 14287 14288 -f 14288 14287 14116 -f 14288 14116 14115 -f 14288 14115 14289 -f 14288 14289 14210 -f 14290 14113 14112 -f 14290 14112 14291 -f 14290 14291 14293 -f 14293 14291 14292 -f 14293 14292 14224 -f 14224 14292 14111 -f 14295 14307 14314 -f 14294 14313 14306 -f 14296 14307 14295 -f 14294 14306 14296 -f 14296 14306 14307 -f 14323 14318 14313 -f 14323 14313 14294 -f 14324 14316 14317 -f 14315 14316 14297 -f 14314 14315 14297 -f 14297 14316 14324 -f 14295 14314 14297 -f 14324 14317 14323 -f 14323 14317 14318 -f 14328 14298 14299 -f 14302 14298 14300 -f 14302 14300 14305 -f 14305 14300 14327 -f 14305 14327 14304 -f 14304 14327 14328 -f 14304 14328 14308 -f 14308 14328 14301 -f 14308 14301 14310 -f 14310 14301 14299 -f 14310 14299 14303 -f 14303 14299 14329 -f 14303 14329 14311 -f 14311 14329 14298 -f 14311 14298 14302 -f 14312 14302 14313 -f 14313 14302 14305 -f 14313 14305 14306 -f 14306 14305 14304 -f 14306 14304 14307 -f 14307 14304 14308 -f 14314 14308 14309 -f 14309 14308 14310 -f 14309 14310 14315 -f 14315 14310 14303 -f 14315 14303 14316 -f 14316 14303 14311 -f 14316 14311 14317 -f 14317 14311 14318 -f 14318 14311 14302 -f 14318 14302 14312 -f 14307 14308 14314 -f 14314 14309 14315 -f 14318 14312 14313 -f 14295 14297 14319 -f 14319 14297 14320 -f 14296 14295 14321 -f 14321 14295 14319 -f 14294 14296 14322 -f 14322 14296 14321 -f 14323 14294 14326 -f 14326 14294 14322 -f 14324 14323 14325 -f 14325 14323 14326 -f 14297 14324 14320 -f 14320 14324 14325 -f 14325 14326 14320 -f 14320 14326 14322 -f 14320 14322 14319 -f 14319 14322 14321 -f 14300 14298 14328 -f 14300 14328 14327 -f 14301 14328 14299 -f 14329 14299 14298 -f 15792 14089 14330 -f 15792 14330 15796 -f 14330 14083 15796 -f 15796 14083 14331 -f 15796 14331 14332 -f 14395 14396 14333 -f 14333 14396 14334 -f 14333 14334 14087 -f 14087 14334 14332 -f 14087 14332 14331 -f 14403 14064 14335 -f 14335 14064 14067 -f 14335 14067 14336 -f 14336 14067 14070 -f 14336 14070 14337 -f 14337 14070 14073 -f 14337 14073 14338 -f 14338 14073 14079 -f 14338 14079 15799 -f 15799 14079 14402 -f 14339 14050 15816 -f 15816 14050 14065 -f 15816 14065 14405 -f 15807 14397 14340 -f 14340 14397 14051 -f 14340 14051 14341 -f 14051 14342 14341 -f 14341 14342 14339 -f 14339 14342 14343 -f 14339 14343 14050 -f 15798 14078 14344 -f 14344 14078 14077 -f 14344 14077 15802 -f 15802 14077 14345 -f 15802 14345 15803 -f 15803 14345 14058 -f 15803 14058 15805 -f 15805 14058 14071 -f 15805 14071 15808 -f 15808 14071 14062 -f 14346 15809 14354 -f 14354 15809 14352 -f 14352 15809 14347 -f 14350 14347 14348 -f 14346 14356 14052 -f 14346 14052 15818 -f 15818 14052 14053 -f 15818 14053 14348 -f 14348 14053 14055 -f 14348 14055 14349 -f 14348 14349 14350 -f 14350 14349 14351 -f 14350 14351 14347 -f 14347 14351 14352 -f 14352 14351 14057 -f 14352 14057 14056 -f 14352 14056 14353 -f 14352 14353 14354 -f 14354 14353 14066 -f 14354 14066 14355 -f 14354 14355 14346 -f 14346 14355 14356 -f 14362 15810 15804 -f 14362 15804 14359 -f 14359 15804 14357 -f 14365 14060 14054 -f 14365 14054 15812 -f 15812 14054 14358 -f 15812 14358 14357 -f 14357 14358 14063 -f 14357 14063 14359 -f 14359 14063 14360 -f 14359 14360 14072 -f 14359 14072 14069 -f 14359 14069 14362 -f 14362 14069 14361 -f 14362 14361 14074 -f 14362 14074 14363 -f 14362 14363 15810 -f 15810 14363 14364 -f 15810 14364 14060 -f 15810 14060 14365 -f 14366 14374 15794 -f 15794 14374 14367 -f 14367 14374 15797 -f 15797 14374 14370 -f 15797 14370 14368 -f 15797 14368 15800 -f 14368 14088 15800 -f 15800 14088 14086 -f 14374 14375 14369 -f 14374 14369 14371 -f 14374 14371 14370 -f 14370 14371 14372 -f 14370 14372 14368 -f 14368 14372 14088 -f 14376 14084 14366 -f 14366 14084 14091 -f 14366 14091 14374 -f 14374 14091 14373 -f 14374 14373 14375 -f 15800 14086 15806 -f 15806 14086 14082 -f 15806 14082 14376 -f 14376 14082 14084 -f 14388 14389 14377 -f 14377 14389 14384 -f 14377 14384 15801 -f 15801 14384 14378 -f 15814 14383 14381 -f 15814 14381 14380 -f 14380 14381 14090 -f 14378 14387 14379 -f 14379 14387 14382 -f 14379 14382 14383 -f 14379 14383 15814 -f 14389 14076 14384 -f 14384 14076 14075 -f 14384 14075 14385 -f 14384 14385 14378 -f 14378 14385 14386 -f 14378 14386 14387 -f 14380 14090 14388 -f 14388 14090 14080 -f 14388 14080 14389 -f 14389 14080 14390 -f 14389 14390 14068 -f 14389 14068 14076 -f 14078 15798 14391 -f 14391 15798 14392 -f 14391 14392 14085 -f 14085 14392 15793 -f 14085 15793 14394 -f 15793 14393 14394 -f 14394 14393 14395 -f 14397 15807 14398 -f 15807 15817 14398 -f 14398 15817 14061 -f 14061 15817 15811 -f 14061 15811 14062 -f 15811 15808 14062 -f 14089 15792 14399 -f 14089 14399 14400 -f 14400 15791 14401 -f 14400 14401 14081 -f 14081 14401 15799 -f 14081 15799 14402 -f 14064 14403 14404 -f 14404 14403 15815 -f 14404 15815 14059 -f 14059 15815 15813 -f 14059 15813 15795 -f 14059 15795 14405 -f 14405 15795 15816 -f 14450 14413 14451 -f 14451 14413 14414 -f 14451 14414 14415 -f 14451 14415 14453 -f 14453 14415 14411 -f 14453 14411 14406 -f 14406 14411 14454 -f 14454 14411 14407 -f 14454 14407 14419 -f 14454 14419 14408 -f 14408 14419 14418 -f 14408 14418 14452 -f 14452 14418 14409 -f 14452 14409 14449 -f 14449 14409 14417 -f 14449 14417 14412 -f 14449 14412 14446 -f 14446 14412 14416 -f 14446 14416 14448 -f 14448 14416 14410 -f 14448 14410 14450 -f 14450 14410 14413 -f 14430 14411 14415 -f 14411 14430 14428 -f 14416 14421 14413 -f 14416 14413 14410 -f 14423 14412 14417 -f 14414 14430 14415 -f 14413 14430 14414 -f 14412 14423 14421 -f 14412 14421 14416 -f 14419 14428 14418 -f 14409 14423 14417 -f 14411 14428 14407 -f 14418 14428 14423 -f 14418 14423 14409 -f 14407 14428 14419 -f 14429 14430 14431 -f 14429 14431 14441 -f 14433 14420 14438 -f 14421 14420 14413 -f 14420 14421 14438 -f 14438 14421 14434 -f 14422 14434 14421 -f 14421 14424 14422 -f 14423 14424 14421 -f 14424 14423 14425 -f 14425 14436 14424 -f 14428 14425 14423 -f 14426 14425 14427 -f 14427 14425 14428 -f 14429 14427 14428 -f 14430 14429 14428 -f 14420 14431 14430 -f 14420 14430 14413 -f 14422 14437 14434 -f 14422 14424 14437 -f 14437 14424 14436 -f 14436 14425 14426 -f 14426 14427 14432 -f 14429 14432 14427 -f 14432 14429 14441 -f 14441 14431 14433 -f 14431 14420 14433 -f 14440 14434 14444 -f 14444 14436 14435 -f 14444 14437 14436 -f 14444 14434 14437 -f 14440 14433 14438 -f 14439 14441 14442 -f 14439 14432 14441 -f 14443 14432 14439 -f 14440 14438 14434 -f 14442 14433 14440 -f 14442 14441 14433 -f 14443 14426 14432 -f 14435 14436 14426 -f 14435 14426 14443 -f 14442 14477 14476 -f 14442 14476 14439 -f 14439 14476 14443 -f 14443 14476 14479 -f 14443 14479 14475 -f 14443 14475 14435 -f 14435 14475 14474 -f 14435 14474 14444 -f 14444 14474 14445 -f 14444 14445 14440 -f 14440 14445 14477 -f 14440 14477 14442 -f 14446 14464 14449 -f 14448 14447 14446 -f 14446 14447 14464 -f 14447 14448 14467 -f 14455 14450 14451 -f 14406 14458 14453 -f 14450 14467 14448 -f 14450 14455 14467 -f 14454 14458 14406 -f 14458 14408 14463 -f 14449 14464 14463 -f 14449 14463 14452 -f 14452 14463 14408 -f 14458 14455 14453 -f 14453 14455 14451 -f 14408 14458 14454 -f 14459 14469 14457 -f 14458 14463 14462 -f 14458 14462 14461 -f 14463 14471 14478 -f 14464 14447 14471 -f 14467 14455 14456 -f 14457 14456 14455 -f 14455 14458 14457 -f 14459 14457 14458 -f 14461 14460 14459 -f 14459 14458 14461 -f 14478 14462 14463 -f 14463 14464 14471 -f 14465 14471 14447 -f 14466 14465 14447 -f 14447 14467 14466 -f 14473 14466 14467 -f 14473 14467 14456 -f 14456 14457 14468 -f 14468 14457 14469 -f 14459 14460 14469 -f 14462 14470 14460 -f 14462 14460 14461 -f 14470 14462 14478 -f 14465 14466 14472 -f 14472 14466 14473 -f 14468 14473 14456 -f 14477 14473 14468 -f 14475 14478 14471 -f 14475 14471 14474 -f 14476 14469 14460 -f 14445 14472 14473 -f 14445 14473 14477 -f 14479 14460 14470 -f 14479 14470 14475 -f 14474 14471 14465 -f 14470 14478 14475 -f 14476 14460 14479 -f 14477 14468 14476 -f 14476 14468 14469 -f 14474 14465 14445 -f 14445 14465 14472 -f 14480 14512 14482 -f 14513 14512 14480 -f 14482 14512 14510 -f 14482 14510 14483 -f 14484 14507 14481 -f 14481 14507 14513 -f 14483 14510 14484 -f 14484 14510 14507 -f 14522 14489 14523 -f 14522 14524 14489 -f 14522 14495 14524 -f 14494 14521 14485 -f 14485 14521 14522 -f 14485 14522 14498 -f 14498 14522 14501 -f 14501 14522 14486 -f 14501 14486 14487 -f 14487 14486 14523 -f 14487 14523 14488 -f 14487 14488 14500 -f 14500 14488 14490 -f 14490 14488 14489 -f 14490 14489 14499 -f 14499 14489 14491 -f 14499 14491 14492 -f 14492 14491 14524 -f 14492 14524 14497 -f 14497 14524 14525 -f 14497 14525 14526 -f 14497 14526 14493 -f 14493 14526 14495 -f 14493 14495 14494 -f 14494 14495 14521 -f 14499 14503 14490 -f 14490 14503 14504 -f 14494 14496 14493 -f 14485 14506 14496 -f 14485 14496 14494 -f 14497 14502 14492 -f 14493 14502 14497 -f 14493 14496 14502 -f 14498 14506 14485 -f 14492 14502 14503 -f 14492 14503 14499 -f 14500 14504 14487 -f 14501 14505 14498 -f 14498 14505 14506 -f 14487 14504 14505 -f 14487 14505 14501 -f 14490 14504 14500 -f 14496 14511 14502 -f 14502 14514 14503 -f 14503 14514 14504 -f 14505 14509 14506 -f 14506 14511 14496 -f 14505 14504 14508 -f 14504 14514 14507 -f 14508 14504 14507 -f 14510 14508 14507 -f 14510 14509 14508 -f 14505 14508 14509 -f 14512 14509 14510 -f 14512 14506 14509 -f 14511 14506 14512 -f 14513 14511 14512 -f 14502 14511 14513 -f 14514 14502 14513 -f 14507 14514 14513 -f 14480 14482 14515 -f 14515 14482 14520 -f 14513 14480 14518 -f 14518 14480 14515 -f 14481 14513 14516 -f 14516 14513 14518 -f 14484 14481 14517 -f 14517 14481 14516 -f 14483 14484 14519 -f 14519 14484 14517 -f 14482 14483 14520 -f 14520 14483 14519 -f 14516 14518 14517 -f 14517 14518 14515 -f 14517 14515 14519 -f 14519 14515 14520 -f 14521 14495 14522 -f 14486 14522 14523 -f 14488 14523 14489 -f 14491 14489 14524 -f 14525 14524 14495 -f 14525 14495 14526 -f 14527 14551 14528 -f 14553 14527 14529 -f 14528 14551 14557 -f 14530 14557 14553 -f 14567 14565 14563 -f 14566 14565 14567 -f 14567 14570 14568 -f 14563 14570 14567 -f 14540 14563 14542 -f 14542 14563 14531 -f 14542 14531 14532 -f 14532 14531 14564 -f 14532 14564 14533 -f 14533 14564 14565 -f 14533 14565 14535 -f 14535 14565 14534 -f 14535 14534 14546 -f 14546 14534 14566 -f 14546 14566 14544 -f 14544 14566 14536 -f 14544 14536 14567 -f 14544 14567 14545 -f 14545 14567 14537 -f 14545 14537 14568 -f 14545 14568 14538 -f 14538 14568 14569 -f 14538 14569 14539 -f 14539 14569 14570 -f 14539 14570 14540 -f 14540 14570 14563 -f 14544 14554 14555 -f 14540 14547 14539 -f 14542 14549 14540 -f 14540 14549 14547 -f 14538 14541 14554 -f 14538 14554 14545 -f 14539 14541 14538 -f 14539 14547 14541 -f 14542 14543 14549 -f 14532 14543 14542 -f 14545 14554 14544 -f 14546 14555 14535 -f 14533 14548 14532 -f 14532 14548 14543 -f 14535 14555 14548 -f 14535 14548 14533 -f 14544 14555 14546 -f 14547 14552 14541 -f 14541 14552 14554 -f 14555 14553 14550 -f 14553 14557 14550 -f 14548 14555 14550 -f 14551 14550 14557 -f 14543 14548 14550 -f 14550 14551 14543 -f 14549 14543 14551 -f 14547 14549 14551 -f 14527 14547 14551 -f 14552 14547 14527 -f 14553 14552 14527 -f 14554 14552 14553 -f 14555 14554 14553 -f 14527 14528 14556 -f 14556 14528 14558 -f 14529 14527 14560 -f 14560 14527 14556 -f 14553 14529 14559 -f 14559 14529 14560 -f 14530 14553 14561 -f 14561 14553 14559 -f 14557 14530 14562 -f 14562 14530 14561 -f 14528 14557 14558 -f 14558 14557 14562 -f 14559 14560 14561 -f 14561 14560 14556 -f 14561 14556 14562 -f 14562 14556 14558 -f 14531 14563 14565 -f 14531 14565 14564 -f 14565 14566 14534 -f 14536 14566 14567 -f 14567 14568 14537 -f 14569 14568 14570 -f 14601 14596 14573 -f 14609 14578 14606 -f 14606 14611 14609 -f 14613 14611 14606 -f 14582 14605 14575 -f 14575 14605 14606 -f 14575 14606 14586 -f 14586 14606 14576 -f 14586 14576 14607 -f 14586 14607 14588 -f 14588 14607 14577 -f 14577 14607 14578 -f 14577 14578 14579 -f 14579 14578 14608 -f 14579 14608 14589 -f 14589 14608 14609 -f 14589 14609 14587 -f 14587 14609 14611 -f 14587 14611 14610 -f 14587 14610 14580 -f 14580 14610 14612 -f 14580 14612 14613 -f 14580 14613 14585 -f 14585 14613 14582 -f 14582 14613 14581 -f 14582 14581 14605 -f 14589 14590 14591 -f 14582 14584 14585 -f 14575 14583 14582 -f 14582 14583 14584 -f 14580 14584 14590 -f 14580 14590 14587 -f 14585 14584 14580 -f 14586 14593 14575 -f 14575 14593 14583 -f 14587 14590 14589 -f 14579 14591 14577 -f 14588 14592 14586 -f 14586 14592 14593 -f 14577 14591 14592 -f 14577 14592 14588 -f 14589 14591 14579 -f 14595 14590 14584 -f 14590 14597 14591 -f 14594 14591 14597 -f 14591 14594 14592 -f 14594 14597 14596 -f 14601 14594 14596 -f 14592 14594 14601 -f 14601 14571 14592 -f 14593 14592 14571 -f 14571 14583 14593 -f 14571 14572 14583 -f 14572 14584 14583 -f 14595 14584 14572 -f 14595 14572 14574 -f 14595 14574 14596 -f 14590 14595 14596 -f 14597 14590 14596 -f 14572 14571 14603 -f 14603 14571 14604 -f 14574 14572 14598 -f 14598 14572 14603 -f 14596 14574 14599 -f 14599 14574 14598 -f 14573 14596 14600 -f 14600 14596 14599 -f 14601 14573 14602 -f 14602 14573 14600 -f 14571 14601 14604 -f 14604 14601 14602 -f 14599 14598 14600 -f 14600 14598 14603 -f 14600 14603 14602 -f 14602 14603 14604 -f 14581 14606 14605 -f 14576 14606 14607 -f 14607 14606 14578 -f 14578 14609 14608 -f 14610 14611 14612 -f 14612 14611 14613 -f 14581 14613 14606 -f 14651 14650 14656 -f 14654 14652 14651 -f 14651 14621 14654 -f 14656 14621 14651 -f 14622 14657 14650 -f 14622 14650 14625 -f 14625 14650 14651 -f 14625 14651 14629 -f 14629 14651 14617 -f 14629 14617 14632 -f 14632 14617 14652 -f 14632 14652 14618 -f 14618 14652 14619 -f 14618 14619 14620 -f 14620 14619 14653 -f 14620 14653 14626 -f 14626 14653 14654 -f 14626 14654 14621 -f 14626 14621 14627 -f 14627 14621 14655 -f 14627 14655 14623 -f 14623 14655 14624 -f 14624 14655 14656 -f 14624 14656 14657 -f 14624 14657 14622 -f 14626 14628 14620 -f 14620 14628 14636 -f 14622 14634 14624 -f 14625 14631 14622 -f 14622 14631 14634 -f 14623 14634 14627 -f 14627 14634 14639 -f 14624 14634 14623 -f 14629 14631 14625 -f 14627 14639 14626 -f 14626 14639 14628 -f 14618 14636 14632 -f 14629 14630 14631 -f 14632 14636 14630 -f 14632 14630 14629 -f 14620 14636 14618 -f 14631 14633 14634 -f 14638 14634 14633 -f 14638 14639 14634 -f 14640 14628 14639 -f 14628 14640 14636 -f 14636 14640 14635 -f 14636 14635 14630 -f 14635 14637 14630 -f 14630 14637 14631 -f 14637 14633 14631 -f 14635 14640 14616 -f 14616 14615 14635 -f 14635 14615 14637 -f 14641 14637 14615 -f 14633 14637 14641 -f 14633 14641 14614 -f 14638 14633 14614 -f 14642 14638 14614 -f 14638 14642 14639 -f 14640 14639 14642 -f 14642 14644 14640 -f 14640 14644 14616 -f 14614 14641 14647 -f 14647 14641 14649 -f 14642 14614 14646 -f 14646 14614 14647 -f 14644 14642 14643 -f 14643 14642 14646 -f 14616 14644 14645 -f 14645 14644 14643 -f 14615 14616 14648 -f 14648 14616 14645 -f 14641 14615 14649 -f 14649 14615 14648 -f 14643 14646 14645 -f 14645 14646 14647 -f 14645 14647 14648 -f 14648 14647 14649 -f 14617 14651 14652 -f 14619 14652 14653 -f 14653 14652 14654 -f 14655 14621 14656 -f 14657 14656 14650 -f 14677 14673 14674 -f 14658 14670 14672 -f 14672 14673 14681 -f 14681 14673 14677 -f 14658 14672 14681 -f 14659 14676 14670 -f 14659 14670 14658 -f 14675 14661 14678 -f 14678 14661 14660 -f 14677 14674 14678 -f 14678 14674 14675 -f 14661 14676 14660 -f 14660 14676 14659 -f 14692 14690 14687 -f 14662 14692 14686 -f 14662 14686 14665 -f 14665 14686 14666 -f 14666 14686 14687 -f 14666 14687 14688 -f 14666 14688 14667 -f 14667 14688 14689 -f 14667 14689 14664 -f 14664 14689 14690 -f 14664 14690 14663 -f 14663 14690 14691 -f 14663 14691 14669 -f 14669 14691 14692 -f 14669 14692 14662 -f 14670 14662 14671 -f 14671 14662 14665 -f 14671 14665 14672 -f 14672 14665 14666 -f 14672 14666 14673 -f 14673 14666 14674 -f 14674 14666 14667 -f 14674 14667 14675 -f 14675 14667 14664 -f 14675 14664 14668 -f 14668 14664 14663 -f 14668 14663 14661 -f 14661 14663 14669 -f 14661 14669 14676 -f 14676 14669 14662 -f 14676 14662 14670 -f 14670 14671 14672 -f 14675 14668 14661 -f 14677 14678 14679 -f 14679 14678 14683 -f 14681 14677 14680 -f 14680 14677 14679 -f 14658 14681 14685 -f 14685 14681 14680 -f 14659 14658 14682 -f 14682 14658 14685 -f 14660 14659 14684 -f 14684 14659 14682 -f 14678 14660 14683 -f 14683 14660 14684 -f 14684 14682 14683 -f 14683 14682 14685 -f 14683 14685 14679 -f 14679 14685 14680 -f 14686 14692 14687 -f 14688 14687 14690 -f 14688 14690 14689 -f 14691 14690 14692 -f 14698 14709 14711 -f 14695 14705 14708 -f 14693 14709 14698 -f 14695 14708 14693 -f 14693 14708 14709 -f 14699 14694 14705 -f 14699 14705 14695 -f 14697 14714 14696 -f 14713 14714 14716 -f 14711 14713 14716 -f 14716 14714 14697 -f 14698 14711 14716 -f 14697 14696 14699 -f 14699 14696 14694 -f 14700 14728 14726 -f 14702 14728 14723 -f 14702 14723 14703 -f 14703 14723 14724 -f 14703 14724 14704 -f 14704 14724 14700 -f 14704 14700 14710 -f 14710 14700 14725 -f 14710 14725 14701 -f 14701 14725 14726 -f 14701 14726 14706 -f 14706 14726 14727 -f 14706 14727 14707 -f 14707 14727 14728 -f 14707 14728 14702 -f 14715 14702 14705 -f 14705 14702 14703 -f 14705 14703 14708 -f 14708 14703 14704 -f 14708 14704 14709 -f 14709 14704 14710 -f 14711 14710 14712 -f 14712 14710 14701 -f 14712 14701 14713 -f 14713 14701 14706 -f 14713 14706 14714 -f 14714 14706 14707 -f 14714 14707 14696 -f 14696 14707 14694 -f 14694 14707 14702 -f 14694 14702 14715 -f 14709 14710 14711 -f 14711 14712 14713 -f 14694 14715 14705 -f 14698 14716 14717 -f 14717 14716 14720 -f 14693 14698 14722 -f 14722 14698 14717 -f 14695 14693 14721 -f 14721 14693 14722 -f 14699 14695 14719 -f 14719 14695 14721 -f 14697 14699 14718 -f 14718 14699 14719 -f 14716 14697 14720 -f 14720 14697 14718 -f 14718 14719 14720 -f 14720 14719 14721 -f 14720 14721 14717 -f 14717 14721 14722 -f 14723 14728 14700 -f 14723 14700 14724 -f 14725 14700 14726 -f 14727 14726 14728 -f 14730 14748 14744 -f 14729 14741 14743 -f 14745 14746 14749 -f 14744 14745 14752 -f 14752 14745 14749 -f 14730 14744 14752 -f 14729 14743 14730 -f 14730 14743 14748 -f 14740 14741 14732 -f 14738 14740 14731 -f 14731 14740 14732 -f 14749 14746 14731 -f 14731 14746 14738 -f 14732 14741 14729 -f 14757 14760 14733 -f 14760 14758 14733 -f 14734 14762 14736 -f 14736 14762 14757 -f 14736 14757 14737 -f 14737 14757 14733 -f 14737 14733 14735 -f 14735 14733 14759 -f 14735 14759 14739 -f 14739 14759 14758 -f 14739 14758 14747 -f 14747 14758 14760 -f 14747 14760 14742 -f 14742 14760 14761 -f 14742 14761 14734 -f 14734 14761 14762 -f 14748 14734 14736 -f 14748 14736 14744 -f 14744 14736 14737 -f 14744 14737 14745 -f 14745 14737 14735 -f 14745 14735 14746 -f 14746 14735 14738 -f 14738 14735 14739 -f 14738 14739 14747 -f 14738 14747 14740 -f 14741 14747 14742 -f 14741 14742 14743 -f 14743 14742 14734 -f 14743 14734 14748 -f 14740 14747 14741 -f 14749 14731 14751 -f 14751 14731 14755 -f 14752 14749 14750 -f 14750 14749 14751 -f 14730 14752 14756 -f 14756 14752 14750 -f 14729 14730 14753 -f 14753 14730 14756 -f 14732 14729 14754 -f 14754 14729 14753 -f 14731 14732 14755 -f 14755 14732 14754 -f 14754 14753 14755 -f 14755 14753 14756 -f 14755 14756 14751 -f 14751 14756 14750 -f 14759 14733 14758 -f 14761 14760 14757 -f 14761 14757 14762 -f 14766 14785 14764 -f 14765 14781 14788 -f 14788 14781 14783 -f 14763 14782 14765 -f 14765 14782 14781 -f 14764 14785 14763 -f 14763 14785 14782 -f 14768 14784 14766 -f 14767 14779 14784 -f 14767 14784 14768 -f 14783 14779 14788 -f 14788 14779 14767 -f 14768 14766 14764 -f 14769 14794 14796 -f 14774 14793 14776 -f 14776 14793 14794 -f 14776 14794 14777 -f 14777 14794 14795 -f 14777 14795 14770 -f 14777 14770 14775 -f 14775 14770 14769 -f 14775 14769 14780 -f 14780 14769 14771 -f 14780 14771 14773 -f 14773 14771 14796 -f 14773 14796 14772 -f 14772 14796 14793 -f 14772 14793 14774 -f 14778 14774 14782 -f 14782 14774 14776 -f 14782 14776 14781 -f 14781 14776 14777 -f 14781 14777 14783 -f 14783 14777 14775 -f 14783 14775 14779 -f 14779 14775 14780 -f 14779 14780 14784 -f 14784 14780 14773 -f 14784 14773 14766 -f 14766 14773 14785 -f 14785 14773 14772 -f 14785 14772 14778 -f 14778 14772 14774 -f 14785 14778 14782 -f 14788 14767 14786 -f 14786 14767 14790 -f 14765 14788 14787 -f 14787 14788 14786 -f 14763 14765 14789 -f 14789 14765 14787 -f 14764 14763 14792 -f 14792 14763 14789 -f 14768 14764 14791 -f 14791 14764 14792 -f 14767 14768 14790 -f 14790 14768 14791 -f 14791 14792 14790 -f 14790 14792 14789 -f 14790 14789 14786 -f 14786 14789 14787 -f 14793 14796 14794 -f 14795 14794 14769 -f 14795 14769 14770 -f 14771 14769 14796 -f 14873 14797 15978 -f 15978 14797 14798 -f 15978 14798 15982 -f 14798 15939 15982 -f 15982 15939 14799 -f 15982 14799 14800 -f 14799 15908 14800 -f 14800 15908 15938 -f 14800 15938 14801 -f 14801 15938 15930 -f 14801 15930 15980 -f 15980 15930 14802 -f 15980 14802 15966 -f 15966 14802 15940 -f 15966 15940 15947 -f 15947 15940 15937 -f 15891 14803 15961 -f 15961 14803 15962 -f 15968 14883 15954 -f 15954 14883 15887 -f 15954 15887 15956 -f 15956 15887 15876 -f 15956 15876 15958 -f 15958 15876 15888 -f 15958 15888 14804 -f 14804 15888 15891 -f 14804 15891 14805 -f 14805 15891 15961 -f 14807 15981 15905 -f 15905 15981 15962 -f 15905 15962 14806 -f 14806 15962 14803 -f 14882 14881 15921 -f 15921 14881 15963 -f 15921 15963 14807 -f 14807 15963 15981 -f 15957 14809 15872 -f 15872 14809 15848 -f 15854 14808 15857 -f 15857 14808 15944 -f 15857 15944 15866 -f 15866 15944 15957 -f 15866 15957 15886 -f 15886 15957 15872 -f 15848 14809 14810 -f 14810 14809 14811 -f 14810 14811 15852 -f 15852 14811 15945 -f 15852 15945 15860 -f 15860 15945 15946 -f 15948 15861 15860 -f 15948 15860 15946 -f 15870 14812 15880 -f 15880 14812 15965 -f 15880 15965 15883 -f 14813 15924 15974 -f 15974 15924 15907 -f 15974 15907 14814 -f 15974 14814 14815 -f 14815 14814 15916 -f 14815 15916 14816 -f 14816 15916 14817 -f 14816 14817 15960 -f 15960 14817 15909 -f 15960 15909 15959 -f 15959 15909 15893 -f 15959 15893 14818 -f 14818 15893 15892 -f 14818 15892 14819 -f 14819 15892 15883 -f 14819 15883 15965 -f 14827 14828 14820 -f 14820 15898 14823 -f 14820 14823 14821 -f 14821 14823 14824 -f 14821 14824 14822 -f 14822 14824 15873 -f 14822 15873 15879 -f 14822 15879 15943 -f 15943 15879 14825 -f 15943 14825 14826 -f 15943 14826 14827 -f 14827 14826 15877 -f 14827 15877 15853 -f 14827 15853 14828 -f 14828 15853 15856 -f 14828 15856 14820 -f 14820 15856 15898 -f 14836 15868 14829 -f 14829 15868 15900 -f 14829 15900 15902 -f 14829 15902 14830 -f 14830 15902 15855 -f 14830 15855 14832 -f 14830 14832 14831 -f 14831 14832 15942 -f 15942 14832 14833 -f 15942 14833 15901 -f 15942 15901 15919 -f 15942 15919 14834 -f 14834 15919 14835 -f 14834 14835 15915 -f 14834 15915 15874 -f 14834 15874 14836 -f 14836 15874 15871 -f 14836 15871 15868 -f 14840 14837 14839 -f 14838 14839 14844 -f 14839 14847 15903 -f 14839 15903 14840 -f 14840 15903 15922 -f 14840 15922 15911 -f 14840 15911 14837 -f 14837 15911 15912 -f 14837 15912 14841 -f 14837 14841 14842 -f 14837 14842 14843 -f 14843 14842 14845 -f 14843 14845 14844 -f 14844 14845 14846 -f 14844 14846 15926 -f 14844 15926 14838 -f 14838 15926 14847 -f 14838 14847 14839 -f 15941 15917 15906 -f 15941 15906 15929 -f 15941 15929 14849 -f 14849 15929 15934 -f 14851 14852 15917 -f 14851 15917 15941 -f 14850 15918 14851 -f 14851 15918 14852 -f 14849 15934 14853 -f 14849 14853 14848 -f 14848 14853 14854 -f 14848 14854 14850 -f 14850 14854 14855 -f 14850 14855 15918 -f 15924 14813 15964 -f 15924 15964 14856 -f 14856 15964 15969 -f 14856 15969 14857 -f 14857 15969 14858 -f 14857 14858 15928 -f 15928 14858 15979 -f 15928 15979 14859 -f 14859 15979 14860 -f 14859 14860 15931 -f 15931 14860 14861 -f 15931 14861 15932 -f 15932 14861 15950 -f 15932 15950 15935 -f 15935 15950 15976 -f 15935 15976 15884 -f 15884 15976 15947 -f 15884 15947 15937 -f 15948 14862 15861 -f 15861 14862 15849 -f 15849 14862 15851 -f 15851 14862 14863 -f 15851 14863 14865 -f 15851 14865 14864 -f 14864 14865 14867 -f 14864 14867 14866 -f 14866 14867 14869 -f 14866 14869 14868 -f 14868 14869 15863 -f 14869 15983 15863 -f 15863 15983 14870 -f 15863 14870 15864 -f 15864 14870 14871 -f 15864 14871 14872 -f 14872 14871 14812 -f 14872 14812 15870 -f 14797 14873 14874 -f 14797 14874 14875 -f 14875 14874 15973 -f 14875 15973 15933 -f 15933 15973 15977 -f 15933 15977 15936 -f 15936 15977 14876 -f 15936 14876 14877 -f 14877 14876 15972 -f 14877 15972 14878 -f 14878 15972 15971 -f 14878 15971 14879 -f 14879 15971 15970 -f 14879 15970 14880 -f 14880 15970 15927 -f 15970 15951 15927 -f 15927 15951 14881 -f 15927 14881 14882 -f 14883 15968 15953 -f 14883 15953 15867 -f 15867 15953 14884 -f 15867 14884 15865 -f 15865 14884 15952 -f 15865 15952 15862 -f 15862 15952 15975 -f 15862 15975 15882 -f 15882 15975 15967 -f 15882 15967 15858 -f 15858 15967 15949 -f 15858 15949 14885 -f 14885 15949 15955 -f 14885 15955 14886 -f 14886 15955 15850 -f 15955 14887 15850 -f 15850 14887 14808 -f 15850 14808 15854 -f 15894 15835 14888 -f 15890 15829 15897 -f 15897 15829 15825 -f 15897 15825 15823 -f 15820 15859 14890 -f 14890 15859 15904 -f 14890 15904 14891 -f 14891 15904 15878 -f 14891 15878 15885 -f 15828 14906 15826 -f 15826 14906 15889 -f 15826 15889 15824 -f 14892 15914 15845 -f 14893 15925 14894 -f 14893 14894 14895 -f 14913 14896 14897 -f 14897 14896 15840 -f 14897 15840 14909 -f 14898 14899 15839 -f 15839 14899 14900 -f 15839 14900 15910 -f 15837 15910 15896 -f 15837 15896 14901 -f 15913 14903 14902 -f 14902 14903 15841 -f 14902 15841 14904 -f 15897 15823 15885 -f 15885 15823 15819 -f 15859 15820 14905 -f 15859 14905 15875 -f 15824 15889 15875 -f 15824 15875 14905 -f 14906 15828 14907 -f 15835 15894 15834 -f 15834 15894 14907 -f 15834 14907 15828 -f 15869 14889 14908 -f 15869 14908 15899 -f 15899 14908 15829 -f 15899 15829 15890 -f 14909 15840 14910 -f 14909 14910 14911 -f 14910 15838 14911 -f 14911 15838 14901 -f 14901 15838 15833 -f 14898 15839 15920 -f 15920 15839 15590 -f 15920 15590 15881 -f 15881 15590 15913 -f 15913 15590 14903 -f 14893 14895 14912 -f 14893 14912 14896 -f 14893 14896 14913 -f 15923 14904 15841 -f 15841 15843 15923 -f 15923 15843 15914 -f 15914 15843 15847 -f 15914 15847 15845 -f 14963 14921 14919 -f 14919 14921 14920 -f 15081 14914 14972 -f 14914 15081 14915 -f 14976 14916 15076 -f 14976 15076 15029 -f 15026 14958 14982 -f 15022 14958 15026 -f 15067 14927 14985 -f 14927 14926 14985 -f 15003 14929 14943 -f 15013 14933 14917 -f 14933 15013 15009 -f 15007 14918 14947 -f 15018 15017 14951 -f 15017 15001 14951 -f 14962 15030 14961 -f 14961 15030 15032 -f 14963 14919 15038 -f 15038 14919 14964 -f 14965 15040 14920 -f 14920 14921 14965 -f 15083 14974 14955 -f 15079 14922 14978 -f 15012 14922 14979 -f 14980 14983 14959 -f 14923 15084 14983 -f 14923 14983 14984 -f 15073 14931 14987 -f 15065 14929 15003 -f 14931 14930 14932 -f 14990 14934 14991 -f 14934 14935 14993 -f 14996 15008 14994 -f 14995 14994 14945 -f 14918 15007 15006 -f 15008 14996 14936 -f 14936 14996 14937 -f 14937 14997 14936 -f 14936 14997 14999 -f 14995 15056 14939 -f 14939 15056 14940 -f 14940 15002 14939 -f 14939 15002 14941 -f 14944 14929 15004 -f 15070 15073 14987 -f 15070 14987 15005 -f 15005 14987 14929 -f 15005 14929 14944 -f 15070 15005 14931 -f 14944 14942 15005 -f 14931 15005 14942 -f 14942 14944 14943 -f 14943 14944 15003 -f 14948 14918 15009 -f 15008 14995 14946 -f 14946 14995 14945 -f 14946 14945 14948 -f 14948 14945 14918 -f 15008 14946 14994 -f 14946 14948 14947 -f 14994 14946 14947 -f 14947 14948 15007 -f 15012 15079 14978 -f 15012 14978 14949 -f 14949 14978 14976 -f 14949 14976 15011 -f 15012 14977 14922 -f 15011 14916 14949 -f 14977 14949 14916 -f 15012 14949 14977 -f 14916 15011 15076 -f 14950 14933 15014 -f 15066 14990 15016 -f 15016 14990 14991 -f 15016 14991 15015 -f 15015 14991 14933 -f 15015 14933 14950 -f 15066 14992 14934 -f 14950 14917 15015 -f 15016 14917 14992 -f 15066 15016 14992 -f 14917 14950 15013 -f 15020 15001 15017 -f 15020 15017 15021 -f 14995 14938 15019 -f 15019 14938 15000 -f 15019 15000 15001 -f 15019 15001 15020 -f 15020 14951 14952 -f 15020 14952 15019 -f 15056 15019 14952 -f 14951 15020 15018 -f 14954 14926 14927 -f 14954 14927 15022 -f 15023 15068 14925 -f 15023 14925 15024 -f 15024 14925 14926 -f 15024 14926 14954 -f 15023 14953 14928 -f 15023 15024 14953 -f 14954 14924 15024 -f 14953 15024 14924 -f 14924 14954 14985 -f 14954 15022 14985 -f 14957 14914 15082 -f 15083 14955 15025 -f 15025 14955 14971 -f 15025 14971 14957 -f 14957 14971 14914 -f 15083 15025 14956 -f 15083 14956 14975 -f 14975 14956 14974 -f 14957 14972 14956 -f 14957 14956 15025 -f 15081 14957 15082 -f 14972 14957 15081 -f 15027 14958 15022 -f 15027 15022 15029 -f 15084 14980 15028 -f 15028 14980 14959 -f 15028 14959 15027 -f 15027 14959 14958 -f 14981 15028 14960 -f 14983 15028 14981 -f 15084 15028 14983 -f 14960 15027 14982 -f 14961 15033 15087 -f 14962 14961 15087 -f 15034 15035 15032 -f 15032 15030 15034 -f 15100 15099 15038 -f 15038 15099 14965 -f 14921 14963 14965 -f 14965 14963 15038 -f 14919 14920 14964 -f 14964 14920 15040 -f 15096 15039 15040 -f 15040 15039 14964 -f 14967 15050 14966 -f 14967 14966 14968 -f 14967 14968 15115 -f 14969 15041 15043 -f 15112 14970 14969 -f 15102 15041 14969 -f 15102 14969 14970 -f 15102 14970 15118 -f 14914 14971 14956 -f 14972 14914 14956 -f 14956 14955 14974 -f 14971 14955 14956 -f 15083 14973 14974 -f 14974 14973 14975 -f 14975 14973 15052 -f 14916 14976 14977 -f 14978 14922 14977 -f 14976 14978 14977 -f 14922 15078 14979 -f 14979 15078 15080 -f 14981 14959 14983 -f 14958 14959 14960 -f 14960 14959 14981 -f 14982 14958 14960 -f 14984 15084 14923 -f 14953 15068 14928 -f 14953 14925 15068 -f 14926 14925 14924 -f 14924 14925 14953 -f 14985 14926 14924 -f 15068 15069 14928 -f 14928 15069 14986 -f 14986 15069 15053 -f 15053 15023 14986 -f 14986 15023 14928 -f 14942 14987 14931 -f 14929 14987 14942 -f 14943 14929 14942 -f 15073 14988 14930 -f 15073 14930 14931 -f 14930 14988 14932 -f 14932 14988 14989 -f 14989 15070 14932 -f 14932 15070 14931 -f 14991 14934 14992 -f 14933 14991 14992 -f 14917 14933 14992 -f 14993 14935 15063 -f 15063 15066 14993 -f 14993 15066 14934 -f 14994 14995 14996 -f 14947 14945 14994 -f 14918 14945 14947 -f 14996 14998 14997 -f 14996 14997 14937 -f 14997 14998 14999 -f 14999 14998 15060 -f 15060 15008 14999 -f 14999 15008 14936 -f 14938 15056 15000 -f 14952 15000 15056 -f 14952 15001 15000 -f 14951 15001 14952 -f 15056 15058 15002 -f 15056 15002 14940 -f 15002 15058 14941 -f 14941 15058 15057 -f 15057 14995 14941 -f 14941 14995 14939 -f 14944 15004 15003 -f 15004 14929 15065 -f 14948 15009 15007 -f 15009 14918 15006 -f 14976 15029 15011 -f 15011 15029 15010 -f 15010 15076 15011 -f 14950 15014 15013 -f 14933 15009 15014 -f 15015 14917 15016 -f 15020 15021 15018 -f 15019 15056 14995 -f 14985 15022 15067 -f 14914 14915 15082 -f 15026 14982 15029 -f 15027 15029 14982 -f 15027 14960 15028 -f 15050 14967 15111 -f 15125 15126 15087 -f 15087 15126 15034 -f 15030 14962 15034 -f 15034 14962 15087 -f 15123 15031 15035 -f 15035 15031 15033 -f 14961 15032 15033 -f 15033 15032 15035 -f 15091 15090 15036 -f 15036 15090 15089 -f 15094 15092 15093 -f 15093 15092 15037 -f 15100 15038 15039 -f 15039 15038 14964 -f 15096 15040 15099 -f 15099 15040 14965 -f 15097 15041 15102 -f 15043 15041 15097 -f 15097 15042 15043 -f 15104 15108 15044 -f 14966 15106 14968 -f 15106 15104 14968 -f 14968 15104 15044 -f 14968 15044 15115 -f 15115 15044 15108 -f 15114 15045 15113 -f 15113 15045 15046 -f 15047 14969 15042 -f 15042 14969 15043 -f 15048 14970 15109 -f 15109 14970 15112 -f 15117 15118 15048 -f 15048 15118 14970 -f 15152 15117 15109 -f 15109 15117 15048 -f 15119 15139 15049 -f 15049 15139 15138 -f 15107 15136 15120 -f 15120 15136 15155 -f 15050 15086 15051 -f 15051 14966 15050 -f 15083 14975 15052 -f 15098 15074 15054 -f 15098 15054 15095 -f 15095 15054 15055 -f 15055 15018 15059 -f 15017 15018 15055 -f 15059 15018 15021 -f 15059 15021 15061 -f 15061 15021 15054 -f 15054 15021 15017 -f 15054 15017 15055 -f 14995 15057 15074 -f 15074 15057 15058 -f 15074 15058 15056 -f 15054 14938 15061 -f 15061 14938 14995 -f 15074 15056 15054 -f 15054 15056 14938 -f 15059 15006 15007 -f 15059 15007 15062 -f 15007 15009 15062 -f 15061 15009 15006 -f 15061 15006 15059 -f 15072 15008 15060 -f 15072 15060 14995 -f 14995 15060 14998 -f 14995 14998 14996 -f 15061 14995 15009 -f 15009 14995 15008 -f 15009 15008 15072 -f 15062 15009 15013 -f 15062 15013 15064 -f 15013 15014 15064 -f 15064 15014 15066 -f 15066 15014 15009 -f 15072 14934 14990 -f 15072 14935 14934 -f 15073 15066 15063 -f 15073 15063 15072 -f 15072 15063 14935 -f 15072 14990 15009 -f 15009 14990 15066 -f 15064 15003 15067 -f 15067 15003 15004 -f 15067 15004 15070 -f 15070 15004 15066 -f 15066 15004 15065 -f 15066 15065 15064 -f 15064 15065 15003 -f 15068 15070 14989 -f 15068 14989 15073 -f 15073 14989 14988 -f 15066 15073 15070 -f 15070 15022 14927 -f 15070 14927 15067 -f 15072 15023 15053 -f 15072 15053 15068 -f 15068 15053 15069 -f 15070 15068 15022 -f 15022 15068 15023 -f 15022 15023 15072 -f 15022 15026 15067 -f 15067 15026 15071 -f 15026 15029 15071 -f 15072 14983 14980 -f 15072 14984 14983 -f 15084 14984 15072 -f 15072 14980 15022 -f 15022 14980 15029 -f 15029 14980 15084 -f 15122 15084 15072 -f 15072 15068 15073 -f 15072 14995 15074 -f 15029 15076 15071 -f 15071 15076 15075 -f 15075 15076 15010 -f 15075 15010 15077 -f 15077 15010 15029 -f 15080 15078 15084 -f 15084 14922 15079 -f 15078 14922 15084 -f 14979 15080 15012 -f 15012 15080 15084 -f 15084 15079 15029 -f 15029 15079 15077 -f 15077 15079 15012 -f 15077 15012 15084 -f 14915 15081 15075 -f 15075 15081 15085 -f 15085 15081 15082 -f 15085 15082 15121 -f 15121 15082 15077 -f 15077 15082 14915 -f 15077 14915 15075 -f 15122 15083 15052 -f 15122 15052 15084 -f 15084 15052 14973 -f 15084 14973 15083 -f 15084 15083 15077 -f 15077 15083 15121 -f 15121 15083 15122 -f 15075 15085 15046 -f 15075 15046 15071 -f 15095 15055 15045 -f 15045 15055 15059 -f 15045 15059 15062 -f 15062 15064 15045 -f 15045 15064 15067 -f 15045 15067 15046 -f 15046 15067 15071 -f 15086 15050 15110 -f 15110 15050 15111 -f 15125 15087 15031 -f 15031 15087 15033 -f 15123 15035 15126 -f 15126 15035 15034 -f 15088 15122 15072 -f 15088 15072 15101 -f 15101 15072 15074 -f 15127 15159 15036 -f 15036 15159 15091 -f 15161 15127 15089 -f 15089 15127 15036 -f 15089 15090 15161 -f 15161 15090 15162 -f 15159 15162 15091 -f 15091 15162 15090 -f 15037 15092 15129 -f 15129 15092 15128 -f 15131 15128 15094 -f 15094 15128 15092 -f 15130 15131 15093 -f 15093 15131 15094 -f 15129 15130 15037 -f 15037 15130 15093 -f 15095 15045 15098 -f 15098 15045 15114 -f 15099 15042 15096 -f 15096 15042 15097 -f 15096 15097 15039 -f 15039 15097 15146 -f 15039 15146 15100 -f 15100 15146 15145 -f 15114 15047 15098 -f 15098 15047 15042 -f 15098 15042 15074 -f 15074 15042 15099 -f 15074 15099 15100 -f 15074 15100 15101 -f 15101 15100 15145 -f 15097 15102 15146 -f 15146 15102 15116 -f 15103 15104 15120 -f 15120 15104 15107 -f 15105 15136 15107 -f 15106 14966 15105 -f 15106 15105 15107 -f 15106 15107 15104 -f 15104 15150 15108 -f 14969 15047 15114 -f 15150 15152 15108 -f 15108 15152 15109 -f 15108 15109 15115 -f 15115 15109 15112 -f 15113 15110 15111 -f 15111 15112 15113 -f 15112 15111 14967 -f 15112 14969 15113 -f 15113 14969 15114 -f 15112 14967 15115 -f 15118 15116 15102 -f 15117 15049 15118 -f 15118 15049 15138 -f 15118 15138 15116 -f 15119 15049 15149 -f 15149 15049 15117 -f 15149 15153 15119 -f 15119 15153 15139 -f 15120 15155 15103 -f 15103 15155 15154 -f 15051 15156 14966 -f 14966 15156 15105 -f 15122 15088 15124 -f 15086 15110 15113 -f 15123 15121 15122 -f 15123 15122 15031 -f 15031 15122 15124 -f 15031 15124 15125 -f 15125 15124 15156 -f 15125 15156 15126 -f 15126 15156 15051 -f 15126 15051 15123 -f 15123 15051 15086 -f 15123 15086 15121 -f 15121 15086 15113 -f 15121 15113 15085 -f 15085 15113 15046 -f 15088 15101 15124 -f 15124 15101 15145 -f 15133 15158 15134 -f 15167 15174 15169 -f 15169 15174 15171 -f 15169 15171 15132 -f 15169 15132 15135 -f 15135 15133 15169 -f 15160 15137 15155 -f 15135 15157 15133 -f 15169 15133 15134 -f 15132 15171 15160 -f 15157 15135 15163 -f 15163 15160 15136 -f 15160 15171 15137 -f 15139 15151 15142 -f 15136 15160 15155 -f 15137 15171 15151 -f 15138 15142 15148 -f 15138 15139 15142 -f 15134 15158 15143 -f 15143 15144 15140 -f 15151 15171 15141 -f 15142 15151 15141 -f 15142 15141 15165 -f 15147 15148 15164 -f 15140 15147 15164 -f 15140 15164 15170 -f 15143 15140 15170 -f 15165 15141 15170 -f 15164 15165 15170 -f 15158 15144 15143 -f 15170 15141 15175 -f 15145 15146 15140 -f 15140 15146 15147 -f 15147 15146 15148 -f 15148 15146 15116 -f 15116 15138 15148 -f 15153 15151 15139 -f 15149 15117 15152 -f 15150 15104 15103 -f 15137 15151 15153 -f 15152 15150 15149 -f 15149 15150 15103 -f 15149 15103 15153 -f 15153 15103 15154 -f 15153 15154 15137 -f 15154 15155 15137 -f 15105 15163 15136 -f 15156 15157 15105 -f 15105 15157 15163 -f 15124 15133 15156 -f 15156 15133 15157 -f 15140 15144 15145 -f 15145 15144 15158 -f 15145 15158 15124 -f 15124 15158 15133 -f 15162 15159 15163 -f 15163 15159 15160 -f 15159 15127 15160 -f 15160 15127 15132 -f 15127 15161 15132 -f 15132 15161 15135 -f 15161 15162 15135 -f 15135 15162 15163 -f 15129 15128 15164 -f 15164 15128 15165 -f 15128 15131 15165 -f 15165 15131 15142 -f 15131 15130 15142 -f 15142 15130 15148 -f 15130 15129 15148 -f 15148 15129 15164 -f 15190 15166 15167 -f 15190 15167 15169 -f 15190 15169 15168 -f 15168 15169 15176 -f 15182 15170 15181 -f 15181 15170 15180 -f 15184 15183 15171 -f 15171 15174 15184 -f 15184 15174 15172 -f 15172 15174 15173 -f 15186 15187 15175 -f 15186 15175 15141 -f 15186 15141 15185 -f 15166 15173 15167 -f 15167 15173 15174 -f 15143 15170 15182 -f 15143 15182 15134 -f 15134 15182 15176 -f 15134 15176 15169 -f 15177 15166 15190 -f 15178 15190 15168 -f 15178 15168 15194 -f 15194 15168 15179 -f 15179 15168 15176 -f 15170 15175 15180 -f 15180 15175 15187 -f 15180 15198 15181 -f 15181 15198 15199 -f 15182 15181 15199 -f 15183 15185 15171 -f 15171 15185 15141 -f 15173 15189 15172 -f 15172 15189 15831 -f 15172 15831 15830 -f 15200 15183 15184 -f 15830 15184 15172 -f 15185 15201 15821 -f 15185 15821 15186 -f 15186 15188 15187 -f 15173 15166 15189 -f 15189 15166 15177 -f 15176 15182 15179 -f 15179 15182 15191 -f 15194 15179 15196 -f 15832 15177 15178 -f 15178 15177 15190 -f 15180 15187 15198 -f 15198 15187 15188 -f 15199 15198 15836 -f 15182 15822 15191 -f 15191 15822 15195 -f 15831 15189 15193 -f 15184 15830 15827 -f 15184 15827 15200 -f 15185 15183 15201 -f 15201 15183 15200 -f 15192 15821 15201 -f 15197 15188 15821 -f 15821 15188 15186 -f 15832 15193 15177 -f 15177 15193 15189 -f 15195 15196 15191 -f 15191 15196 15179 -f 15197 15836 15188 -f 15188 15836 15198 -f 15822 15182 15199 -f 15827 15192 15200 -f 15200 15192 15201 -f 15212 15202 15544 -f 15202 15545 15544 -f 15202 15213 15545 -f 15202 15212 15213 -f 15545 15529 15521 -f 15224 15519 15520 -f 15224 15520 15521 -f 15521 15544 15545 -f 15211 15315 15258 -f 15258 15315 15241 -f 15242 15325 15209 -f 15209 15325 15203 -f 15247 15246 15238 -f 15238 15246 15306 -f 15204 15310 15237 -f 15237 15310 15307 -f 15205 15312 15233 -f 15233 15312 15234 -f 15253 15314 15231 -f 15231 15314 15327 -f 15203 15255 15209 -f 15209 15255 15208 -f 15241 15242 15258 -f 15258 15242 15209 -f 15258 15259 15210 -f 15210 15211 15258 -f 15212 15544 15518 -f 15212 15518 15213 -f 15214 15261 15530 -f 15530 15529 15518 -f 15518 15529 15213 -f 15289 15274 15287 -f 15287 15274 15275 -f 15276 15372 15223 -f 15223 15372 15286 -f 15278 15361 15272 -f 15272 15361 15359 -f 15218 15356 15269 -f 15269 15356 15357 -f 15281 15350 15268 -f 15268 15350 15354 -f 15221 15222 15265 -f 15265 15222 15351 -f 15223 15286 15285 -f 15285 15284 15223 -f 15275 15276 15287 -f 15287 15276 15223 -f 15287 15373 15289 -f 15386 15383 15385 -f 15386 15385 15388 -f 15388 15385 15384 -f 15293 15391 15395 -f 15293 15395 15389 -f 15389 15395 15390 -f 15390 15395 15479 -f 15295 15225 15224 -f 15224 15225 15519 -f 15296 15297 15299 -f 15300 15226 15301 -f 15226 15300 15227 -f 15300 15303 15227 -f 15230 15298 15412 -f 15253 15326 15323 -f 15206 15324 15207 -f 15207 15324 15326 -f 15207 15326 15253 -f 15207 15253 15231 -f 15207 15231 15232 -f 15232 15231 15327 -f 15205 15324 15321 -f 15250 15252 15249 -f 15252 15324 15249 -f 15249 15324 15205 -f 15249 15205 15233 -f 15249 15233 15251 -f 15251 15233 15234 -f 15204 15322 15319 -f 15248 15319 15236 -f 15236 15319 15235 -f 15235 15322 15236 -f 15236 15322 15204 -f 15236 15204 15237 -f 15236 15237 15308 -f 15308 15237 15307 -f 15247 15318 15316 -f 15245 15316 15243 -f 15243 15316 15317 -f 15317 15318 15243 -f 15243 15318 15247 -f 15243 15247 15238 -f 15243 15238 15239 -f 15239 15238 15306 -f 15418 15416 15240 -f 15418 15240 15211 -f 15211 15240 15315 -f 15241 15315 15320 -f 15241 15320 15242 -f 15325 15242 15320 -f 15203 15325 15257 -f 15257 15325 15414 -f 15243 15239 15245 -f 15245 15239 15244 -f 15244 15246 15245 -f 15245 15246 15247 -f 15245 15247 15316 -f 15236 15308 15248 -f 15248 15308 15309 -f 15309 15310 15248 -f 15248 15310 15204 -f 15248 15204 15319 -f 15249 15251 15250 -f 15250 15251 15311 -f 15311 15312 15250 -f 15250 15312 15205 -f 15250 15205 15252 -f 15252 15205 15321 -f 15207 15232 15206 -f 15206 15232 15313 -f 15313 15314 15206 -f 15206 15314 15253 -f 15206 15253 15324 -f 15324 15253 15323 -f 15254 15208 15256 -f 15256 15208 15255 -f 15256 15255 15257 -f 15257 15255 15203 -f 15209 15208 15258 -f 15258 15208 15259 -f 15259 15415 15210 -f 15210 15415 15417 -f 15210 15417 15211 -f 15211 15417 15418 -f 15328 15329 15434 -f 15328 15434 15430 -f 15430 15434 15330 -f 15438 15331 15437 -f 15438 15437 15439 -f 15439 15437 15440 -f 15214 15260 15261 -f 15261 15260 15515 -f 15263 15291 15262 -f 15337 15345 15341 -f 15337 15341 15340 -f 15342 15339 15341 -f 15290 15339 15346 -f 15449 15375 15374 -f 15374 15375 15450 -f 15334 15374 15336 -f 15348 15264 15349 -f 15349 15264 15347 -f 15221 15363 15282 -f 15220 15282 15266 -f 15266 15282 15362 -f 15362 15363 15266 -f 15266 15363 15221 -f 15266 15221 15265 -f 15266 15265 15352 -f 15352 15265 15351 -f 15281 15368 15364 -f 15219 15364 15267 -f 15267 15364 15369 -f 15369 15368 15267 -f 15267 15368 15281 -f 15267 15281 15268 -f 15267 15268 15355 -f 15355 15268 15354 -f 15218 15370 15367 -f 15217 15365 15270 -f 15365 15370 15270 -f 15270 15370 15218 -f 15270 15218 15269 -f 15270 15269 15279 -f 15279 15269 15357 -f 15278 15371 15271 -f 15215 15370 15216 -f 15216 15370 15371 -f 15216 15371 15278 -f 15216 15278 15272 -f 15216 15272 15277 -f 15277 15272 15359 -f 15288 15453 15273 -f 15288 15273 15289 -f 15289 15273 15274 -f 15275 15274 15366 -f 15275 15366 15276 -f 15372 15276 15366 -f 15286 15372 15459 -f 15459 15372 15455 -f 15216 15277 15215 -f 15215 15277 15360 -f 15360 15361 15215 -f 15215 15361 15278 -f 15215 15278 15370 -f 15370 15278 15271 -f 15270 15279 15217 -f 15217 15279 15358 -f 15358 15356 15217 -f 15217 15356 15218 -f 15217 15218 15365 -f 15365 15218 15367 -f 15267 15355 15219 -f 15219 15355 15280 -f 15280 15350 15219 -f 15219 15350 15281 -f 15219 15281 15364 -f 15266 15352 15220 -f 15220 15352 15353 -f 15353 15222 15220 -f 15220 15222 15221 -f 15220 15221 15282 -f 15283 15284 15285 -f 15283 15285 15459 -f 15459 15285 15286 -f 15223 15284 15287 -f 15287 15284 15373 -f 15373 15458 15463 -f 15373 15463 15289 -f 15289 15463 15288 -f 15291 15263 15375 -f 15378 15466 15376 -f 15376 15292 15378 -f 15385 15475 15387 -f 15384 15396 15388 -f 15389 15394 15473 -f 15402 15398 15401 -f 15401 15398 15397 -f 15520 15225 15514 -f 15514 15225 15295 -f 15514 15295 15294 -f 15294 15295 15224 -f 15296 15406 15297 -f 15297 15406 15405 -f 15406 15296 15412 -f 15412 15296 15230 -f 15230 15296 15299 -f 15230 15299 15229 -f 15230 15229 15408 -f 15408 15229 15403 -f 15412 15298 15404 -f 15297 15405 15404 -f 15403 15229 15409 -f 15409 15229 15298 -f 15298 15229 15299 -f 15298 15299 15297 -f 15298 15297 15404 -f 15304 15303 15407 -f 15407 15303 15300 -f 15413 15300 15301 -f 15302 15301 15226 -f 15302 15226 15411 -f 15411 15226 15228 -f 15228 15226 15227 -f 15228 15227 15410 -f 15410 15227 15303 -f 15413 15411 15228 -f 15413 15228 15300 -f 15300 15228 15407 -f 15407 15228 15410 -f 15410 15303 15304 -f 15298 15230 15409 -f 15409 15230 15408 -f 15414 15327 15305 -f 15305 15327 15314 -f 15305 15314 15312 -f 15305 15312 15310 -f 15305 15310 15416 -f 15244 15240 15246 -f 15246 15240 15416 -f 15246 15416 15306 -f 15306 15416 15310 -f 15306 15310 15239 -f 15239 15310 15318 -f 15239 15318 15244 -f 15244 15318 15240 -f 15307 15310 15312 -f 15307 15312 15308 -f 15308 15312 15322 -f 15308 15322 15309 -f 15309 15322 15318 -f 15309 15318 15310 -f 15234 15312 15314 -f 15234 15314 15251 -f 15251 15314 15324 -f 15251 15324 15311 -f 15311 15324 15322 -f 15311 15322 15312 -f 15232 15327 15325 -f 15232 15325 15313 -f 15313 15325 15324 -f 15313 15324 15314 -f 15318 15315 15316 -f 15316 15315 15240 -f 15316 15240 15317 -f 15317 15240 15318 -f 15322 15235 15318 -f 15318 15235 15319 -f 15318 15319 15315 -f 15315 15319 15320 -f 15320 15319 15322 -f 15322 15252 15321 -f 15252 15322 15324 -f 15324 15320 15321 -f 15321 15320 15322 -f 15326 15325 15323 -f 15323 15325 15320 -f 15323 15320 15324 -f 15326 15324 15325 -f 15327 15414 15325 -f 15208 15254 15259 -f 15259 15254 15415 -f 15422 15425 15424 -f 15422 15424 15423 -f 15422 15423 15427 -f 15432 15330 15434 -f 15437 15435 15440 -f 15443 15442 15332 -f 15332 15495 15443 -f 15512 15507 15515 -f 15515 15507 15261 -f 15515 15260 15512 -f 15512 15260 15214 -f 15512 15446 15507 -f 15446 15512 15500 -f 15262 15333 15263 -f 15263 15333 15448 -f 15334 15449 15374 -f 15333 15262 15450 -f 15450 15262 15291 -f 15450 15291 15374 -f 15335 15450 15375 -f 15263 15448 15335 -f 15444 15336 15375 -f 15375 15263 15335 -f 15339 15337 15338 -f 15447 15346 15339 -f 15340 15338 15337 -f 15343 15340 15341 -f 15342 15290 15346 -f 15342 15346 15445 -f 15343 15341 15344 -f 15342 15341 15290 -f 15290 15341 15345 -f 15341 15339 15338 -f 15341 15338 15344 -f 15342 15447 15339 -f 15447 15445 15346 -f 15449 15444 15375 -f 15334 15336 15444 -f 15349 15347 15460 -f 15460 15347 15462 -f 15451 15462 15264 -f 15264 15462 15347 -f 15264 15348 15451 -f 15451 15348 15457 -f 15460 15457 15349 -f 15349 15457 15348 -f 15452 15455 15361 -f 15452 15361 15356 -f 15452 15356 15350 -f 15452 15350 15453 -f 15353 15273 15222 -f 15222 15273 15453 -f 15222 15453 15351 -f 15351 15453 15350 -f 15351 15350 15352 -f 15352 15350 15363 -f 15352 15363 15353 -f 15353 15363 15273 -f 15354 15350 15356 -f 15354 15356 15355 -f 15355 15356 15368 -f 15355 15368 15280 -f 15280 15368 15363 -f 15280 15363 15350 -f 15358 15368 15356 -f 15357 15356 15361 -f 15357 15361 15279 -f 15279 15361 15370 -f 15279 15370 15358 -f 15358 15370 15368 -f 15359 15361 15455 -f 15359 15455 15277 -f 15277 15455 15372 -f 15277 15372 15360 -f 15360 15372 15370 -f 15360 15370 15361 -f 15363 15274 15282 -f 15282 15274 15273 -f 15282 15273 15362 -f 15362 15273 15363 -f 15368 15369 15363 -f 15363 15369 15364 -f 15363 15364 15274 -f 15274 15364 15366 -f 15366 15364 15368 -f 15368 15365 15367 -f 15365 15368 15370 -f 15370 15366 15367 -f 15367 15366 15368 -f 15371 15372 15271 -f 15271 15372 15366 -f 15271 15366 15370 -f 15371 15370 15372 -f 15345 15337 15283 -f 15283 15337 15284 -f 15284 15337 15339 -f 15284 15339 15290 -f 15336 15374 15373 -f 15373 15374 15291 -f 15373 15291 15458 -f 15458 15291 15375 -f 15373 15284 15336 -f 15336 15284 15290 -f 15336 15290 15375 -f 15375 15290 15345 -f 15375 15345 15458 -f 15458 15345 15283 -f 15379 15466 15378 -f 15467 15376 15466 -f 15292 15376 15377 -f 15377 15376 15467 -f 15292 15377 15379 -f 15378 15292 15379 -f 15381 15380 15419 -f 15381 15419 15382 -f 15470 15472 15383 -f 15470 15383 15386 -f 15472 15474 15383 -f 15477 15384 15385 -f 15385 15383 15474 -f 15475 15385 15474 -f 15475 15470 15386 -f 15475 15386 15387 -f 15387 15386 15388 -f 15387 15388 15476 -f 15476 15388 15396 -f 15473 15394 15392 -f 15473 15471 15293 -f 15473 15293 15389 -f 15389 15390 15478 -f 15471 15468 15391 -f 15471 15391 15293 -f 15468 15392 15391 -f 15393 15479 15394 -f 15394 15479 15395 -f 15394 15395 15391 -f 15394 15391 15392 -f 15476 15477 15387 -f 15387 15477 15385 -f 15396 15384 15477 -f 15478 15393 15389 -f 15389 15393 15394 -f 15390 15479 15478 -f 15401 15397 15481 -f 15400 15401 15481 -f 15400 15399 15402 -f 15400 15402 15401 -f 15402 15399 15397 -f 15397 15398 15402 -f 15304 15408 15403 -f 15404 15405 15465 -f 15465 15405 15406 -f 15465 15406 15480 -f 15411 15407 15410 -f 15304 15407 15408 -f 15408 15407 15411 -f 15408 15411 15409 -f 15409 15411 15413 -f 15406 15301 15480 -f 15480 15301 15302 -f 15410 15294 15480 -f 15410 15480 15411 -f 15411 15480 15302 -f 15410 15304 15294 -f 15294 15304 15403 -f 15294 15403 15514 -f 15514 15403 15409 -f 15465 15514 15404 -f 15404 15514 15409 -f 15404 15409 15412 -f 15412 15409 15413 -f 15412 15413 15406 -f 15406 15413 15301 -f 15480 15421 15414 -f 15414 15421 15257 -f 15480 15414 15305 -f 15480 15305 15465 -f 15256 15257 15421 -f 15465 15305 15416 -f 15465 15416 15419 -f 15419 15416 15418 -f 15382 15415 15420 -f 15420 15415 15254 -f 15420 15254 15256 -f 15256 15421 15420 -f 15382 15419 15417 -f 15382 15417 15415 -f 15419 15418 15417 -f 15504 15502 15420 -f 15421 15504 15420 -f 15421 15506 15504 -f 15425 15422 15484 -f 15484 15422 15426 -f 15425 15484 15423 -f 15423 15424 15425 -f 15426 15422 15427 -f 15508 15482 15483 -f 15508 15483 15428 -f 15508 15428 15429 -f 15491 15490 15430 -f 15491 15430 15433 -f 15490 15486 15328 -f 15490 15328 15430 -f 15430 15330 15431 -f 15431 15330 15432 -f 15329 15328 15493 -f 15493 15328 15486 -f 15493 15491 15329 -f 15509 15432 15434 -f 15509 15434 15433 -f 15433 15434 15329 -f 15433 15329 15491 -f 15433 15430 15509 -f 15509 15430 15431 -f 15331 15438 15487 -f 15487 15438 15492 -f 15487 15489 15331 -f 15488 15435 15437 -f 15488 15437 15436 -f 15436 15437 15331 -f 15436 15331 15489 -f 15489 15485 15439 -f 15489 15439 15436 -f 15485 15492 15438 -f 15485 15438 15439 -f 15439 15440 15441 -f 15441 15440 15435 -f 15436 15439 15488 -f 15488 15439 15441 -f 15498 15499 15442 -f 15498 15442 15443 -f 15442 15499 15496 -f 15332 15442 15496 -f 15496 15495 15332 -f 15498 15443 15495 -f 15448 15333 15461 -f 15344 15444 15343 -f 15445 15447 15446 -f 15338 15340 15456 -f 15456 15340 15343 -f 15461 15456 15448 -f 15448 15456 15343 -f 15448 15343 15335 -f 15335 15343 15444 -f 15335 15444 15450 -f 15450 15444 15449 -f 15333 15450 15461 -f 15461 15450 15449 -f 15461 15449 15500 -f 15500 15449 15334 -f 15500 15334 15444 -f 15446 15500 15445 -f 15445 15500 15444 -f 15445 15444 15342 -f 15342 15444 15344 -f 15342 15344 15447 -f 15447 15344 15338 -f 15447 15338 15446 -f 15446 15338 15456 -f 15494 15454 15460 -f 15455 15452 15451 -f 15451 15452 15462 -f 15462 15452 15453 -f 15460 15454 15457 -f 15457 15454 15428 -f 15457 15428 15483 -f 15459 15455 15456 -f 15456 15455 15451 -f 15456 15451 15483 -f 15483 15451 15457 -f 15461 15458 15456 -f 15456 15458 15283 -f 15283 15459 15456 -f 15461 15288 15463 -f 15494 15460 15462 -f 15494 15462 15461 -f 15461 15462 15453 -f 15461 15453 15288 -f 15461 15463 15458 -f 15454 15511 15464 -f 15497 15511 15494 -f 15494 15511 15454 -f 15377 15514 15379 -f 15379 15514 15465 -f 15379 15465 15466 -f 15466 15465 15419 -f 15466 15419 15467 -f 15467 15419 15380 -f 15467 15380 15377 -f 15377 15380 15514 -f 15420 15468 15471 -f 15469 15381 15382 -f 15420 15502 15393 -f 15472 15470 15382 -f 15382 15470 15475 -f 15476 15396 15469 -f 15473 15474 15471 -f 15471 15474 15472 -f 15471 15472 15420 -f 15420 15472 15382 -f 15468 15420 15392 -f 15392 15420 15393 -f 15392 15393 15473 -f 15473 15393 15478 -f 15473 15478 15474 -f 15474 15478 15477 -f 15474 15477 15475 -f 15475 15477 15476 -f 15475 15476 15382 -f 15476 15469 15382 -f 15396 15477 15469 -f 15469 15477 15478 -f 15469 15478 15502 -f 15502 15478 15479 -f 15502 15479 15393 -f 15294 15400 15480 -f 15480 15400 15481 -f 15480 15481 15421 -f 15421 15481 15397 -f 15421 15397 15506 -f 15506 15397 15399 -f 15400 15294 15399 -f 15399 15294 15506 -f 15482 15484 15426 -f 15482 15426 15483 -f 15483 15426 15427 -f 15483 15427 15456 -f 15456 15427 15423 -f 15456 15423 15446 -f 15423 15484 15446 -f 15446 15484 15482 -f 15441 15509 15485 -f 15493 15486 15428 -f 15428 15486 15490 -f 15489 15487 15454 -f 15454 15487 15492 -f 15509 15429 15432 -f 15441 15485 15488 -f 15432 15429 15431 -f 15454 15464 15488 -f 15454 15488 15489 -f 15489 15488 15485 -f 15509 15441 15435 -f 15509 15435 15464 -f 15464 15435 15488 -f 15491 15509 15490 -f 15490 15509 15431 -f 15490 15431 15428 -f 15428 15431 15429 -f 15485 15509 15491 -f 15485 15491 15492 -f 15492 15491 15493 -f 15492 15493 15454 -f 15454 15493 15428 -f 15497 15494 15496 -f 15496 15494 15495 -f 15495 15494 15461 -f 15495 15461 15498 -f 15498 15461 15500 -f 15496 15499 15497 -f 15498 15500 15499 -f 15499 15500 15497 -f 15514 15380 15522 -f 15522 15380 15501 -f 15380 15381 15501 -f 15503 15501 15469 -f 15469 15501 15381 -f 15469 15502 15503 -f 15503 15502 15505 -f 15505 15504 15506 -f 15505 15502 15504 -f 15294 15224 15505 -f 15294 15505 15506 -f 15510 15507 15482 -f 15482 15507 15446 -f 15508 15510 15482 -f 15429 15510 15508 -f 15509 15464 15517 -f 15517 15464 15513 -f 15517 15510 15429 -f 15517 15429 15509 -f 15464 15511 15513 -f 15512 15513 15497 -f 15512 15497 15500 -f 15513 15511 15497 -f 15519 15225 15520 -f 15523 15522 15501 -f 15505 15528 15503 -f 15503 15528 15523 -f 15503 15523 15501 -f 15505 15224 15528 -f 15261 15507 15510 -f 15535 15516 15517 -f 15516 15510 15517 -f 15517 15513 15535 -f 15512 15214 15513 -f 15513 15214 15535 -f 15522 15520 15514 -f 15544 15520 15518 -f 15518 15520 15524 -f 15521 15520 15544 -f 15523 15520 15522 -f 15524 15520 15523 -f 15525 15524 15523 -f 15523 15528 15525 -f 15525 15528 15527 -f 15525 15527 15524 -f 15524 15527 15526 -f 15526 15528 15224 -f 15526 15527 15528 -f 15526 15224 15521 -f 15526 15521 15529 -f 15529 15530 15261 -f 15531 15529 15261 -f 15531 15261 15516 -f 15516 15261 15510 -f 15534 15533 15516 -f 15533 15531 15516 -f 15532 15533 15534 -f 15535 15534 15516 -f 15536 15532 15535 -f 15534 15535 15532 -f 15518 15532 15536 -f 15536 15535 15214 -f 15518 15536 15214 -f 15518 15214 15530 -f 15539 15842 15537 -f 15537 15538 15539 -f 15539 15538 15552 -f 15539 15552 15554 -f 15539 15554 15559 -f 15540 15563 15558 -f 15541 15578 15563 -f 15558 15560 15555 -f 15558 15555 15557 -f 15561 15562 15566 -f 15545 15213 15529 -f 15526 15529 15565 -f 15565 15529 15546 -f 15546 15529 15531 -f 15546 15531 15533 -f 15546 15533 15547 -f 15547 15533 15532 -f 15559 15524 15565 -f 15565 15524 15526 -f 15547 15518 15559 -f 15559 15518 15524 -f 15547 15532 15518 -f 15551 15581 15550 -f 15551 15550 15568 -f 15553 15551 15568 -f 15537 15548 15551 -f 15537 15551 15538 -f 15538 15551 15553 -f 15538 15553 15552 -f 15552 15553 15568 -f 15552 15568 15554 -f 15554 15568 15547 -f 15554 15547 15559 -f 15569 15537 15842 -f 15842 15539 15570 -f 15570 15539 15556 -f 15570 15556 15571 -f 15555 15571 15556 -f 15555 15556 15557 -f 15557 15556 15539 -f 15557 15539 15558 -f 15558 15539 15540 -f 15540 15539 15559 -f 15540 15559 15565 -f 15560 15558 15578 -f 15578 15558 15563 -f 15572 15578 15541 -f 15561 15541 15562 -f 15562 15541 15563 -f 15562 15563 15542 -f 15542 15563 15540 -f 15542 15540 15564 -f 15564 15540 15565 -f 15564 15565 15546 -f 15573 15561 15566 -f 15566 15562 15542 -f 15566 15542 15576 -f 15576 15542 15543 -f 15576 15543 15567 -f 15567 15543 15549 -f 15549 15543 15550 -f 15550 15543 15542 -f 15564 15568 15542 -f 15542 15568 15550 -f 15546 15547 15564 -f 15564 15547 15568 -f 15574 15549 15550 -f 15574 15550 15581 -f 15581 15551 15582 -f 15582 15551 15548 -f 15582 15548 15569 -f 15569 15548 15537 -f 15570 15571 15560 -f 15560 15571 15555 -f 15572 15541 15573 -f 15573 15541 15561 -f 15576 15567 15574 -f 15574 15567 15549 -f 15573 15587 15572 -f 15572 15587 14910 -f 15581 15843 15574 -f 15574 15843 15575 -f 15574 15575 15576 -f 15576 15575 15592 -f 15576 15592 15590 -f 15576 15590 15566 -f 15566 15590 15573 -f 15573 15590 15577 -f 15573 15577 15587 -f 15572 14910 15578 -f 15578 14910 15560 -f 15560 14910 15579 -f 15560 15579 15570 -f 15570 15579 15580 -f 15570 15580 15842 -f 15581 15582 15843 -f 15843 15582 15583 -f 15583 15582 15569 -f 15583 15569 15584 -f 15584 15569 15842 -f 15580 15585 15842 -f 15584 15842 15594 -f 15579 15586 15580 -f 15580 15586 15585 -f 15587 15588 14910 -f 15579 14910 15586 -f 15577 15591 15587 -f 15587 15591 15588 -f 15592 15589 15590 -f 15577 15590 15591 -f 15575 15593 15592 -f 15592 15593 15589 -f 15583 15844 15843 -f 15575 15843 15593 -f 15584 15594 15583 -f 15583 15594 15844 -f 15661 15613 15609 -f 15618 15616 15609 -f 15609 15616 15595 -f 15609 15595 15661 -f 15596 15620 15609 -f 15609 15620 15619 -f 15609 15619 15618 -f 15625 15624 15609 -f 15609 15624 15622 -f 15609 15622 15596 -f 15599 15597 15609 -f 15609 15597 15626 -f 15609 15626 15625 -f 15632 15631 15609 -f 15609 15631 15598 -f 15609 15598 15599 -f 15600 15601 15609 -f 15609 15601 15602 -f 15609 15602 15632 -f 15637 15636 15609 -f 15609 15636 15603 -f 15609 15603 15600 -f 15607 15639 15609 -f 15609 15639 15604 -f 15609 15604 15637 -f 15642 15605 15609 -f 15609 15605 15606 -f 15609 15606 15607 -f 15644 15608 15609 -f 15610 15611 15609 -f 15609 15611 15646 -f 15609 15646 15644 -f 15651 15650 15609 -f 15609 15650 15648 -f 15609 15648 15610 -f 15656 15612 15609 -f 15609 15612 15654 -f 15609 15654 15651 -f 15613 15659 15609 -f 15609 15659 15657 -f 15609 15657 15656 -f 15614 15595 15615 -f 15615 15595 15616 -f 15615 15616 15687 -f 15687 15616 15618 -f 15687 15618 15617 -f 15617 15618 15619 -f 15617 15619 15688 -f 15688 15619 15620 -f 15688 15620 15621 -f 15621 15620 15596 -f 15621 15596 15679 -f 15679 15596 15622 -f 15679 15622 15680 -f 15680 15622 15624 -f 15680 15624 15623 -f 15623 15624 15625 -f 15623 15625 15681 -f 15681 15625 15626 -f 15681 15626 15682 -f 15682 15626 15597 -f 15682 15597 15627 -f 15627 15597 15599 -f 15627 15599 15628 -f 15628 15599 15598 -f 15628 15598 15629 -f 15629 15598 15631 -f 15629 15631 15630 -f 15630 15631 15632 -f 15630 15632 15633 -f 15633 15632 15602 -f 15633 15602 15683 -f 15683 15602 15601 -f 15683 15601 15690 -f 15690 15601 15600 -f 15690 15600 15634 -f 15634 15600 15603 -f 15634 15603 15635 -f 15635 15603 15636 -f 15635 15636 15670 -f 15670 15636 15637 -f 15670 15637 15638 -f 15638 15637 15604 -f 15638 15604 15671 -f 15671 15604 15639 -f 15671 15639 15675 -f 15675 15639 15607 -f 15675 15607 15640 -f 15640 15607 15606 -f 15640 15606 15641 -f 15641 15606 15605 -f 15641 15605 15684 -f 15684 15605 15642 -f 15684 15642 15685 -f 15685 15642 15609 -f 15685 15609 15686 -f 15686 15609 15608 -f 15686 15608 15643 -f 15643 15608 15644 -f 15643 15644 15645 -f 15645 15644 15646 -f 15645 15646 15692 -f 15692 15646 15611 -f 15692 15611 15647 -f 15647 15611 15610 -f 15647 15610 15676 -f 15676 15610 15648 -f 15676 15648 15677 -f 15677 15648 15650 -f 15677 15650 15649 -f 15649 15650 15651 -f 15649 15651 15652 -f 15652 15651 15654 -f 15652 15654 15653 -f 15653 15654 15612 -f 15653 15612 15655 -f 15655 15612 15656 -f 15655 15656 15678 -f 15678 15656 15657 -f 15678 15657 15658 -f 15658 15657 15659 -f 15658 15659 15673 -f 15673 15659 15613 -f 15673 15613 15660 -f 15660 15613 15661 -f 15660 15661 15614 -f 15614 15661 15595 -f 15663 15666 15674 -f 15674 15666 15691 -f 15668 15663 15662 -f 15662 15663 15674 -f 15664 15668 15665 -f 15665 15668 15662 -f 15667 15664 15672 -f 15672 15664 15665 -f 15669 15667 15689 -f 15689 15667 15672 -f 15666 15669 15691 -f 15691 15669 15689 -f 15664 15667 15668 -f 15668 15667 15669 -f 15668 15669 15663 -f 15663 15669 15666 -f 15670 15638 15674 -f 15674 15638 15671 -f 15674 15671 15675 -f 15673 15660 15672 -f 15672 15660 15614 -f 15672 15614 15615 -f 15665 15678 15672 -f 15672 15678 15658 -f 15672 15658 15673 -f 15691 15628 15629 -f 15684 15662 15641 -f 15641 15662 15674 -f 15641 15674 15640 -f 15640 15674 15675 -f 15662 15647 15665 -f 15665 15647 15676 -f 15676 15677 15665 -f 15665 15677 15649 -f 15665 15649 15652 -f 15652 15653 15665 -f 15665 15653 15655 -f 15665 15655 15678 -f 15621 15679 15689 -f 15689 15679 15680 -f 15689 15680 15623 -f 15623 15681 15689 -f 15689 15681 15682 -f 15689 15682 15691 -f 15691 15682 15627 -f 15691 15627 15628 -f 15629 15630 15691 -f 15691 15630 15633 -f 15691 15633 15683 -f 15684 15685 15662 -f 15662 15685 15686 -f 15662 15686 15643 -f 15615 15687 15672 -f 15672 15687 15617 -f 15672 15617 15689 -f 15689 15617 15688 -f 15689 15688 15621 -f 15683 15690 15691 -f 15691 15690 15634 -f 15691 15634 15674 -f 15674 15634 15635 -f 15674 15635 15670 -f 15643 15645 15662 -f 15662 15645 15692 -f 15662 15692 15647 -f 15693 15694 15713 -f 15720 15718 15713 -f 15713 15718 15755 -f 15713 15755 15693 -f 15695 15722 15713 -f 15713 15722 15696 -f 15713 15696 15720 -f 15697 15698 15713 -f 15713 15698 15699 -f 15713 15699 15695 -f 15700 15725 15713 -f 15728 15726 15713 -f 15713 15726 15701 -f 15713 15701 15700 -f 15702 15729 15713 -f 15713 15729 15703 -f 15713 15703 15728 -f 15733 15704 15713 -f 15713 15704 15705 -f 15713 15705 15702 -f 15736 15706 15713 -f 15713 15706 15734 -f 15713 15734 15733 -f 15739 15707 15713 -f 15713 15707 15708 -f 15713 15708 15736 -f 15711 15741 15713 -f 15713 15741 15709 -f 15713 15709 15739 -f 15714 15710 15713 -f 15713 15710 15743 -f 15713 15743 15711 -f 15716 15712 15713 -f 15713 15712 15745 -f 15713 15745 15714 -f 15749 15747 15713 -f 15713 15747 15715 -f 15713 15715 15716 -f 15694 15751 15713 -f 15713 15751 15750 -f 15713 15750 15749 -f 15754 15755 15717 -f 15717 15755 15718 -f 15717 15718 15719 -f 15719 15718 15720 -f 15719 15720 15784 -f 15784 15720 15696 -f 15784 15696 15721 -f 15721 15696 15722 -f 15721 15722 15723 -f 15723 15722 15695 -f 15723 15695 15772 -f 15772 15695 15699 -f 15772 15699 15724 -f 15724 15699 15698 -f 15724 15698 15773 -f 15773 15698 15697 -f 15773 15697 15774 -f 15774 15697 15713 -f 15774 15713 15775 -f 15775 15713 15725 -f 15775 15725 15776 -f 15776 15725 15700 -f 15776 15700 15777 -f 15777 15700 15701 -f 15777 15701 15778 -f 15778 15701 15726 -f 15778 15726 15727 -f 15727 15726 15728 -f 15727 15728 15780 -f 15780 15728 15703 -f 15780 15703 15781 -f 15781 15703 15729 -f 15781 15729 15730 -f 15730 15729 15702 -f 15730 15702 15731 -f 15731 15702 15705 -f 15731 15705 15786 -f 15786 15705 15704 -f 15786 15704 15787 -f 15787 15704 15733 -f 15787 15733 15732 -f 15732 15733 15734 -f 15732 15734 15735 -f 15735 15734 15706 -f 15735 15706 15767 -f 15767 15706 15736 -f 15767 15736 15737 -f 15737 15736 15708 -f 15737 15708 15766 -f 15766 15708 15707 -f 15766 15707 15738 -f 15738 15707 15739 -f 15738 15739 15782 -f 15782 15739 15709 -f 15782 15709 15740 -f 15740 15709 15741 -f 15740 15741 15788 -f 15788 15741 15711 -f 15788 15711 15789 -f 15789 15711 15743 -f 15789 15743 15742 -f 15742 15743 15710 -f 15742 15710 15790 -f 15790 15710 15714 -f 15790 15714 15744 -f 15744 15714 15745 -f 15744 15745 15746 -f 15746 15745 15712 -f 15746 15712 15768 -f 15768 15712 15716 -f 15768 15716 15769 -f 15769 15716 15715 -f 15769 15715 15770 -f 15770 15715 15747 -f 15770 15747 15748 -f 15748 15747 15749 -f 15748 15749 15771 -f 15771 15749 15750 -f 15771 15750 15765 -f 15765 15750 15751 -f 15765 15751 15752 -f 15752 15751 15694 -f 15752 15694 15753 -f 15753 15694 15693 -f 15753 15693 15754 -f 15754 15693 15755 -f 15756 15760 15757 -f 15757 15760 15779 -f 15758 15756 15783 -f 15783 15756 15757 -f 15759 15758 15763 -f 15763 15758 15783 -f 15761 15759 15764 -f 15764 15759 15763 -f 15762 15761 15785 -f 15785 15761 15764 -f 15760 15762 15779 -f 15779 15762 15785 -f 15759 15761 15758 -f 15758 15761 15762 -f 15758 15762 15756 -f 15756 15762 15760 -f 15787 15732 15757 -f 15757 15732 15735 -f 15757 15735 15767 -f 15752 15753 15764 -f 15764 15753 15754 -f 15764 15754 15717 -f 15763 15771 15764 -f 15764 15771 15765 -f 15764 15765 15752 -f 15779 15777 15778 -f 15738 15783 15766 -f 15766 15783 15757 -f 15766 15757 15737 -f 15737 15757 15767 -f 15783 15790 15763 -f 15763 15790 15744 -f 15744 15746 15763 -f 15763 15746 15768 -f 15763 15768 15769 -f 15769 15770 15763 -f 15763 15770 15748 -f 15763 15748 15771 -f 15723 15772 15785 -f 15785 15772 15724 -f 15785 15724 15773 -f 15773 15774 15785 -f 15785 15774 15775 -f 15785 15775 15779 -f 15779 15775 15776 -f 15779 15776 15777 -f 15778 15727 15779 -f 15779 15727 15780 -f 15779 15780 15781 -f 15738 15782 15783 -f 15783 15782 15740 -f 15783 15740 15788 -f 15717 15719 15764 -f 15764 15719 15784 -f 15764 15784 15785 -f 15785 15784 15721 -f 15785 15721 15723 -f 15781 15730 15779 -f 15779 15730 15731 -f 15779 15731 15757 -f 15757 15731 15786 -f 15757 15786 15787 -f 15788 15789 15783 -f 15783 15789 15742 -f 15783 15742 15790 -f 14395 14393 14396 -f 15805 15808 14347 -f 14334 14393 15793 -f 15796 15802 14337 -f 15791 14399 15792 -f 14332 14334 15793 -f 15814 14380 15793 -f 15817 15807 15818 -f 14388 14377 14332 -f 15793 14392 15814 -f 15791 15800 15806 -f 14340 14341 15809 -f 15796 15791 15792 -f 14332 14380 14388 -f 15800 15796 15797 -f 14401 15791 15806 -f 14366 15794 14338 -f 15814 14392 14379 -f 14332 14377 15802 -f 14401 15806 14376 -f 15791 14400 14399 -f 15803 15805 14347 -f 15799 14401 14376 -f 14392 15798 14379 -f 14366 15799 14376 -f 14344 14379 15798 -f 14366 14338 15799 -f 15796 14332 15802 -f 15797 15796 14367 -f 15796 15800 15791 -f 14344 14378 14379 -f 15801 15802 14377 -f 14367 15796 14337 -f 15794 14367 14337 -f 14393 14334 14396 -f 15801 14378 14344 -f 15802 15801 14344 -f 15803 14337 15802 -f 15803 14336 14337 -f 14336 15809 15804 -f 15811 15817 15818 -f 14347 15809 15803 -f 14335 14336 15804 -f 15804 15810 14335 -f 15809 14336 15803 -f 15804 14341 14339 -f 14403 14335 15810 -f 14332 15793 14380 -f 15794 14337 14338 -f 15807 14340 14346 -f 15808 14348 14347 -f 14346 14340 15809 -f 14339 14357 15804 -f 15808 15811 14348 -f 15815 14403 15810 -f 15795 15813 14365 -f 14365 15815 15810 -f 15811 15818 14348 -f 14339 15816 14357 -f 14346 15818 15807 -f 15813 15815 14365 -f 15812 15816 15795 -f 15816 15812 14357 -f 14341 15804 15809 -f 14365 15812 15795 -f 14891 15885 15819 -f 15819 14890 14891 -f 15819 15820 14890 -f 15820 15823 15836 -f 14905 15820 15836 -f 14908 15828 15193 -f 15836 15823 15199 -f 15824 14905 15197 -f 15197 14905 15836 -f 15824 15197 15821 -f 15822 15199 15823 -f 15822 15823 15195 -f 15195 15823 15825 -f 15826 15824 15192 -f 15192 15824 15821 -f 15196 15195 15825 -f 15826 15192 15827 -f 15196 15825 15829 -f 15828 15826 15827 -f 15194 15196 15829 -f 15828 15827 15830 -f 15178 15194 15829 -f 15828 15830 15831 -f 15178 15829 14908 -f 15832 15178 14908 -f 15193 15832 14908 -f 15828 15831 15193 -f 15819 15823 15820 -f 15834 15828 14908 -f 14908 14889 15834 -f 15835 15834 14889 -f 15835 14889 15869 -f 15835 15869 15895 -f 15835 15895 14888 -f 15837 14901 15833 -f 15910 15837 15833 -f 15839 15910 15833 -f 15833 15838 15839 -f 15593 15841 14903 -f 15839 15838 15588 -f 15588 15838 14910 -f 15839 15588 15591 -f 15590 15839 15591 -f 15586 14910 15840 -f 14903 15590 15589 -f 14896 15585 15840 -f 15589 15593 14903 -f 15585 15586 15840 -f 15842 15585 14896 -f 15841 15593 15843 -f 15594 15842 14896 -f 15847 15843 15844 -f 15844 15594 14896 -f 15844 14896 14912 -f 15847 15844 14912 -f 14912 14895 15847 -f 15845 15847 14894 -f 14894 15847 14895 -f 15845 14894 15846 -f 15846 14894 15925 -f 15845 15846 14892 -f 15857 15855 15854 -f 15866 14832 15857 -f 15886 14832 15866 -f 15859 15872 15848 -f 14832 15855 15857 -f 15853 15852 15860 -f 15854 15855 15850 -f 15898 15861 15849 -f 15902 14886 15850 -f 15851 14864 15898 -f 14866 15898 14864 -f 15848 14810 15859 -f 14885 14886 15902 -f 15858 14885 15900 -f 14866 14868 14823 -f 14877 14878 14846 -f 15856 15853 15860 -f 15882 15858 15900 -f 15863 14824 14868 -f 15920 15891 14907 -f 15856 15860 15861 -f 15900 15868 15862 -f 14823 15898 14866 -f 15864 14824 15863 -f 14810 15852 15878 -f 14872 14824 15864 -f 15934 15935 15884 -f 15868 15867 15865 -f 15871 15867 15868 -f 14872 15873 14824 -f 15871 14883 15867 -f 15870 15873 14872 -f 14832 15886 14833 -f 15880 15873 15870 -f 14835 15889 15888 -f 14826 14825 15885 -f 15874 15887 15871 -f 15909 14817 14911 -f 15904 14810 15878 -f 15880 15879 15873 -f 15859 15875 15872 -f 15880 15883 15879 -f 15900 15862 15882 -f 14904 15903 15905 -f 15883 15892 15897 -f 15937 14853 15884 -f 14845 14797 14875 -f 14835 15919 15889 -f 15877 14826 15885 -f 15885 14825 15897 -f 15875 14833 15886 -f 15878 15877 15885 -f 14911 14901 15869 -f 14806 14803 15913 -f 15901 15875 15889 -f 15875 15886 15872 -f 15871 15887 14883 -f 15876 15915 15888 -f 14906 15888 15889 -f 15892 15890 15897 -f 15892 15899 15890 -f 14907 15891 14906 -f 14899 14898 14907 -f 15893 15899 15892 -f 15893 15909 15899 -f 15894 14900 14907 -f 14888 15910 15894 -f 15895 15896 14888 -f 15869 15896 15895 -f 14842 14798 14797 -f 15874 15915 15876 -f 15911 15914 15912 -f 14825 15879 15897 -f 15898 15856 15861 -f 14892 15846 15938 -f 14911 15869 15899 -f 14900 14899 14907 -f 15919 15901 15889 -f 14901 15896 15869 -f 15910 14900 15894 -f 15855 15902 15850 -f 14807 15905 15903 -f 15891 15888 14906 -f 14852 15918 14893 -f 15859 14810 15904 -f 14911 14817 14909 -f 15905 14806 15913 -f 14902 15905 15913 -f 15916 14897 14909 -f 14902 14904 15905 -f 15916 14913 14897 -f 14814 14913 15916 -f 15923 15922 14904 -f 14814 14852 14913 -f 15909 14911 15899 -f 15896 15910 14888 -f 15922 15903 14904 -f 15878 15852 15877 -f 15876 15887 15874 -f 15923 15914 15911 -f 14803 15881 15913 -f 14803 15891 15881 -f 15914 14892 15908 -f 15912 15914 14799 -f 15846 15925 15930 -f 15925 14893 14855 -f 15915 14835 15888 -f 15903 14847 14807 -f 15917 14852 14814 -f 14898 15920 14907 -f 14817 15916 14909 -f 15879 15883 15897 -f 15901 14833 15875 -f 14814 15907 15917 -f 15918 14855 14893 -f 15921 14807 14847 -f 15891 15920 15881 -f 15922 15923 15911 -f 15907 15906 15917 -f 15924 15906 15907 -f 14882 15921 14847 -f 15908 14892 15938 -f 15936 14877 14845 -f 15926 14882 14847 -f 14802 15925 14855 -f 15926 15927 14882 -f 14856 15906 15924 -f 15926 14880 15927 -f 14857 15906 14856 -f 15852 15853 15877 -f 14857 15929 15906 -f 14799 15914 15908 -f 15926 14879 14880 -f 15928 15929 14857 -f 14846 14879 15926 -f 14799 14841 15912 -f 14846 14878 14879 -f 14799 15939 14841 -f 14854 14853 15940 -f 15928 14859 15929 -f 14824 14823 14868 -f 14852 14893 14913 -f 15931 15929 14859 -f 14845 14877 14846 -f 14845 14842 14797 -f 15931 15934 15929 -f 15930 15925 14802 -f 15931 15932 15934 -f 15939 14798 14841 -f 15868 15865 15862 -f 14885 15902 15900 -f 14853 15934 15884 -f 15932 15935 15934 -f 15933 15936 14845 -f 14875 15933 14845 -f 14798 14842 14841 -f 15940 14853 15937 -f 15851 15898 15849 -f 15938 15846 15930 -f 14802 14855 15940 -f 14855 14854 15940 -f 14850 14851 15941 -f 14848 14850 15941 -f 14848 15941 14849 -f 14837 14844 14839 -f 14843 14844 14837 -f 14829 14830 14831 -f 14836 14831 15942 -f 14836 14829 14831 -f 14836 15942 14834 -f 14827 14820 14821 -f 14822 14827 14821 -f 14822 15943 14827 -f 15946 14869 15948 -f 15945 15965 15946 -f 14811 14819 15945 -f 14808 15954 15944 -f 14819 15965 15945 -f 15946 15965 14812 -f 14887 15955 14808 -f 15976 15979 15947 -f 15955 15954 14808 -f 14862 15948 14863 -f 15958 14809 15957 -f 14811 14809 15958 -f 14865 14863 14867 -f 15955 15949 15967 -f 15950 14860 15979 -f 15956 15958 15957 -f 15970 15973 15951 -f 14871 14870 14869 -f 14884 15967 15952 -f 14863 15948 14869 -f 15953 15968 14884 -f 14812 14871 14869 -f 15970 15972 14876 -f 14869 15946 14812 -f 15954 15955 15968 -f 15954 15956 15944 -f 15951 15973 14881 -f 15956 15957 15944 -f 14819 14811 15958 -f 14818 14819 15958 -f 14818 15958 14804 -f 15959 14818 14804 -f 15959 14804 14805 -f 15960 15959 14805 -f 15960 14805 15961 -f 14816 15960 15961 -f 14816 15961 15962 -f 15962 14801 14816 -f 15981 14800 15962 -f 14816 14801 14815 -f 14800 14801 15962 -f 15980 15966 14815 -f 15981 15963 15978 -f 15966 15969 15964 -f 15974 15966 14813 -f 15955 15967 15968 -f 15966 15974 14815 -f 15973 15963 14881 -f 15967 14884 15968 -f 15979 14858 15969 -f 15970 15971 15972 -f 15966 15964 14813 -f 15967 15975 15952 -f 15976 15950 15979 -f 15970 14876 15977 -f 14863 14869 14867 -f 14861 14860 15950 -f 15973 14874 14873 -f 15982 15981 15978 -f 15963 15973 14873 -f 15973 15970 15977 -f 15978 15963 14873 -f 15966 15979 15969 -f 15947 15979 15966 -f 14801 15980 14815 -f 14800 15981 15982 -f 14870 15983 14869 -f 2611 9612 9494 -# 30993 faces, 0 coords texture - -# End of File \ No newline at end of file +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o pelvis +v -0.005177 0.102116 0.079207 +v -0.005174 0.100563 0.077681 +v -0.005197 0.098584 0.078182 +v -0.003161 0.097403 0.083015 +v -0.003819 0.096224 0.080406 +v -0.003182 0.096225 0.078599 +v -0.003191 0.099731 0.083979 +v -0.005116 0.100100 0.082432 +v -0.005167 0.098113 0.081388 +v -0.003249 0.098157 0.076471 +v -0.003197 0.101126 0.076119 +v -0.003203 0.103542 0.078162 +v -0.003281 0.103871 0.081098 +v -0.005130 0.102030 0.081246 +v -0.003203 0.101983 0.083416 +v -0.004000 0.098608 0.080472 +v -0.004000 0.101442 0.080375 +v -0.003175 -0.007349 0.083178 +v -0.003801 -0.008381 0.081594 +v -0.003106 -0.008970 0.079934 +v -0.005199 -0.002896 0.080817 +v -0.005113 -0.005971 0.082229 +v -0.004486 -0.003489 0.082770 +v -0.003158 -0.004807 0.083984 +v -0.005257 -0.006618 0.081030 +v -0.005129 -0.007380 0.079616 +v -0.003247 -0.007872 0.077220 +v -0.004528 -0.006565 0.077306 +v -0.005213 -0.004292 0.077812 +v -0.003204 -0.004952 0.076013 +v -0.003399 -0.001989 0.077332 +v -0.005222 -0.003226 0.078837 +v -0.003187 -0.001026 0.079915 +v -0.003284 -0.001863 0.082472 +v -0.004000 -0.005619 0.078644 +v -0.004000 -0.003756 0.080782 +v -0.005169 -0.003774 -0.081871 +v -0.005044 -0.005807 -0.082392 +v -0.005114 -0.007238 -0.081012 +v -0.005011 -0.007400 -0.079228 +v -0.005165 -0.005959 -0.077821 +v -0.005071 -0.003090 -0.078527 +v -0.005064 -0.002544 -0.080563 +v -0.003162 -0.002803 -0.076573 +v -0.003735 -0.004244 -0.076300 +v -0.003207 -0.007408 -0.076776 +v -0.003206 -0.008884 -0.079353 +v -0.003177 -0.008207 -0.082425 +v -0.003229 -0.005476 -0.083928 +v -0.003233 -0.003090 -0.083526 +v -0.003232 -0.001220 -0.081169 +v -0.003128 -0.001372 -0.078307 +v -0.004000 -0.004757 -0.081470 +v -0.004000 -0.003848 -0.079055 +v -0.004000 -0.006395 -0.079475 +v -0.005252 0.101709 -0.081061 +v -0.005067 0.099806 -0.082425 +v -0.005226 0.097930 -0.080822 +v -0.005106 0.098470 -0.078224 +v -0.005147 0.100017 -0.077705 +v -0.003155 0.102469 -0.076817 +v -0.003543 0.100903 -0.076236 +v -0.003187 0.098220 -0.076426 +v -0.003410 0.096323 -0.078516 +v -0.003189 0.096157 -0.081107 +v -0.003447 0.097686 -0.083234 +v -0.003156 0.100900 -0.083929 +v -0.004624 0.102467 -0.081857 +v -0.003177 0.103208 -0.082401 +v -0.003165 0.103914 -0.079071 +v -0.005155 0.102029 -0.078674 +v -0.004000 0.099198 -0.081232 +v -0.004000 0.101287 -0.079249 +v -0.024503 -0.031640 0.067042 +v -0.002890 -0.013373 0.069345 +v -0.004400 -0.010912 0.069331 +v -0.004650 0.113138 0.069084 +v -0.015861 0.113308 0.068022 +v -0.004554 0.081419 0.069210 +v -0.000332 0.024517 0.069527 +v -0.000101 0.070522 0.069501 +v 0.000001 -0.012200 0.070218 +v -0.004386 0.011704 0.069320 +v -0.002270 0.118819 0.068007 +v -0.032096 0.120315 0.064606 +v -0.000089 0.121372 0.067288 +v 0.000000 0.131420 0.061351 +v -0.034878 0.126625 0.060793 +v -0.035710 0.131288 0.056193 +v -0.033797 0.135359 0.050247 +v 0.000002 0.139717 0.048181 +v -0.004279 0.112969 -0.069239 +v -0.004515 0.081030 -0.069199 +v -0.018059 0.113262 -0.067815 +v -0.013327 -0.026298 -0.068295 +v -0.000187 0.070469 -0.069545 +v -0.004740 0.012181 -0.069192 +v -0.004703 -0.011672 -0.069188 +v -0.000033 -0.013474 -0.069737 +v 0.000065 -0.032575 -0.069203 +v -0.000606 0.024508 -0.069566 +v -0.011728 -0.071096 -0.055330 +v -0.016409 -0.041485 -0.065787 +v -0.000001 -0.072881 -0.055576 +v -0.025821 -0.033642 -0.066623 +v -0.011705 -0.076215 0.051113 +v 0.000000 -0.079559 0.047989 +v 0.000000 -0.072930 0.055534 +v -0.011755 -0.070247 0.055717 +v -0.064732 -0.075202 0.038918 +v -0.057848 -0.071073 0.044943 +v -0.081520 -0.065222 0.036563 +v -0.085154 -0.068960 0.031363 +v -0.101026 -0.059584 0.026257 +v -0.062475 -0.079895 0.033693 +v -0.085931 -0.072045 0.026141 +v -0.104150 -0.063315 0.017719 +v -0.114305 -0.053971 0.016098 +v -0.060193 -0.082175 0.027457 +v -0.081857 -0.075355 0.022335 +v -0.103056 -0.065372 0.012809 +v -0.111723 -0.050191 0.022056 +v -0.114495 -0.056516 0.009813 +v -0.120250 -0.044325 0.009298 +v -0.118793 -0.050338 0.008334 +v -0.116779 -0.047716 0.016684 +v -0.113791 -0.057275 -0.008587 +v -0.117819 -0.052557 -0.007021 +v -0.120627 -0.045168 -0.005844 +v -0.042782 -0.076754 0.044385 +v -0.027223 -0.070922 0.053234 +v -0.113589 -0.055834 -0.014399 +v -0.118686 -0.047488 -0.012807 +v -0.114749 -0.050830 -0.018229 +v -0.084242 -0.067422 -0.033634 +v -0.066602 -0.071209 -0.041136 +v -0.063307 -0.078073 -0.036359 +v -0.079788 -0.075865 -0.025243 +v -0.062888 -0.081163 -0.029372 +v -0.102509 -0.062809 -0.021376 +v -0.094073 -0.070270 -0.016250 +v -0.105211 -0.063719 -0.014109 +v -0.101814 -0.058105 -0.026520 +v -0.111277 -0.050638 -0.022328 +v -0.040629 -0.077695 -0.043559 +v -0.048526 -0.071806 -0.047473 +v -0.028389 -0.071155 -0.052877 +v -0.011952 -0.077075 -0.049911 +v -0.039073 0.135171 0.045962 +v -0.030792 0.115840 0.065953 +v -0.038486 0.135150 -0.046932 +v -0.033313 0.135201 -0.050884 +v -0.035947 0.132008 -0.055054 +v -0.033265 0.125780 -0.061715 +v -0.037374 0.128096 -0.058492 +v -0.032342 0.120199 -0.064618 +v -0.032230 0.114761 -0.065815 +v -0.017234 0.146244 0.014044 +v -0.026295 0.142451 0.027206 +v -0.024136 0.141579 0.035620 +v -0.058078 0.120438 0.052104 +v -0.049329 0.109560 0.062323 +v -0.056023 0.114911 0.057753 +v -0.094433 0.100826 0.027437 +v -0.111644 0.084175 0.023135 +v -0.096725 0.097095 0.034630 +v -0.114117 0.079023 0.028096 +v -0.110003 0.081041 0.033958 +v -0.094849 0.092014 0.043120 +v -0.111836 0.073854 0.036821 +v -0.106945 0.072940 0.041917 +v -0.081112 0.088245 0.053505 +v -0.103367 0.069668 0.044602 +v -0.080017 0.111565 0.037107 +v -0.082767 0.104866 0.044414 +v -0.076659 0.100270 0.052930 +v -0.060089 0.124535 0.042387 +v -0.115289 0.070957 0.031237 +v -0.106068 -0.004529 0.042933 +v -0.111329 -0.004433 0.037816 +v -0.115240 -0.002646 0.031669 +v -0.112926 0.081797 -0.026018 +v -0.114932 0.073905 -0.030919 +v -0.117213 0.075469 -0.019023 +v -0.116530 0.079471 0.002250 +v -0.119526 0.073567 0.002219 +v -0.120473 0.066704 -0.011055 +v -0.120003 0.067998 0.013353 +v -0.114358 0.069259 -0.033685 +v -0.110042 0.081141 -0.033761 +v -0.108004 0.076694 -0.039571 +v -0.106438 0.070060 -0.042837 +v -0.022422 -0.039217 0.065870 +v -0.044595 -0.031904 0.063333 +v -0.115882 -0.023079 0.026184 +v -0.119054 -0.024513 0.018047 +v -0.115010 -0.002464 -0.032100 +v -0.112240 -0.005232 -0.036616 +v -0.105809 -0.004338 -0.043160 +v -0.051405 0.113963 -0.060245 +v -0.098492 0.095623 -0.034037 +v -0.096851 0.098534 -0.029005 +v -0.095453 0.092304 -0.042346 +v -0.090463 0.083404 -0.049792 +v -0.077529 0.099252 -0.052706 +v -0.076136 0.091398 -0.055090 +v -0.072309 0.109602 -0.050253 +v -0.078262 0.110424 -0.042740 +v -0.083099 0.109718 -0.033279 +v -0.054469 0.105469 -0.061196 +v -0.067940 0.120157 -0.038167 +v -0.055874 0.118603 -0.055209 +v -0.058392 0.123046 -0.048148 +v -0.040195 0.135212 -0.042828 +v -0.118476 -0.022826 -0.020583 +v -0.038556 -0.033045 -0.064508 +v -0.080845 -0.018663 -0.053448 +v -0.091612 -0.015708 -0.048645 +v -0.028175 0.140896 -0.035557 +v -0.057278 0.128717 0.000059 +v -0.075169 0.116848 0.011497 +v -0.099562 0.097340 -0.005763 +v -0.037403 0.138702 -0.002089 +v -0.018055 0.145806 -0.017250 +v -0.012106 0.147491 -0.000219 +v -0.042496 -0.086206 -0.018239 +v -0.029577 -0.088387 0.010957 +v -0.000062 -0.091673 -0.000727 +v -0.058923 -0.028171 -0.059961 +v -0.060927 -0.026997 0.059483 +v -0.083794 -0.017883 0.052371 +v 0.000000 -0.079603 -0.047923 +v 0.000002 -0.089820 -0.021267 +v 0.000000 -0.087845 0.027875 +v -0.000029 -0.032778 0.069312 +v 0.000001 0.130996 -0.061748 +v 0.000000 0.139359 -0.049003 +v -0.000105 0.121370 -0.067287 +v -0.002237 0.118842 -0.068004 +v -0.000004 0.148576 0.011578 +v 0.000000 0.146482 -0.023946 +v -0.002785 0.104368 -0.084271 +v -0.000005 0.103379 -0.086291 +v -0.002191 0.100480 -0.086526 +v -0.000001 0.095906 -0.085348 +v -0.002010 0.095676 -0.084753 +v -0.002208 0.090130 -0.077169 +v 0.000000 0.090483 -0.078039 +v -0.000001 0.080803 -0.071196 +v -0.002369 0.076298 -0.069717 +v -0.002755 0.081514 -0.071075 +v 0.000004 0.111989 -0.072970 +v -0.002771 0.113314 -0.071276 +v -0.002700 0.107833 -0.077746 +v -0.002747 -0.001295 -0.084930 +v -0.000006 -0.002584 -0.086741 +v -0.002582 -0.005377 -0.086215 +v -0.000002 -0.010856 -0.083717 +v -0.002793 -0.008414 -0.084907 +v -0.002687 -0.010801 -0.082212 +v -0.002174 -0.011468 -0.071050 +v 0.000000 -0.011626 -0.071819 +v -0.002442 0.016977 -0.070035 +v -0.000001 0.008981 -0.073846 +v -0.002228 0.009023 -0.073868 +v -0.002658 0.003405 -0.078508 +v -0.003077 0.011384 -0.070896 +v -0.003106 -0.010469 -0.070796 +v -0.002910 0.097471 -0.085177 +v -0.002938 0.091123 -0.076852 +v -0.002713 0.096323 0.084978 +v -0.000005 0.097517 0.086697 +v -0.002010 0.100457 0.086439 +v -0.000001 0.104788 0.084736 +v -0.002165 0.104518 0.084586 +v -0.002698 0.107833 0.077745 +v 0.000004 0.111912 0.073126 +v -0.001908 0.113346 0.071882 +v -0.000005 0.087710 0.075292 +v -0.002442 0.078035 0.070037 +v -0.002733 0.091688 0.078528 +v -0.002741 0.083532 0.071871 +v -0.000004 -0.010420 0.084652 +v -0.002737 -0.010833 0.081858 +v -0.002153 -0.011488 0.071012 +v -0.002850 -0.008967 0.084489 +v -0.002489 -0.006885 0.085953 +v -0.000003 -0.001770 0.086148 +v -0.002264 -0.003844 0.086212 +v -0.002764 -0.000945 0.084542 +v -0.002040 0.004842 0.077249 +v 0.000000 0.005922 0.076508 +v -0.002226 0.018994 0.069712 +v -0.002701 0.012709 0.071516 +v -0.000001 0.015649 0.070780 +v -0.002906 0.004104 0.076793 +v -0.003009 -0.010397 0.071313 +v -0.002910 0.102852 0.085143 +v -0.003105 0.113001 0.070567 +v 0.042000 -0.087417 -0.021599 +v 0.027737 -0.088543 -0.016903 +v 0.000000 -0.087576 -0.023421 +v 0.000000 -0.089086 -0.014727 +v 0.042000 -0.077809 -0.055626 +v 0.034937 -0.077425 -0.052115 +v 0.035000 -0.078062 -0.055646 +v 0.033317 -0.077695 -0.048333 +v 0.042000 -0.078980 -0.045302 +v -0.000001 0.144902 -0.055674 +v 0.000000 0.152536 -0.020745 +v 0.001809 0.143890 -0.058074 +v 0.001986 0.154187 -0.005331 +v 0.000004 0.154027 0.009718 +v 0.001834 0.154204 0.007135 +v 0.003970 0.153981 0.002393 +v 0.041999 0.154104 -0.010277 +v 0.040118 0.154147 -0.006683 +v 0.038031 0.153981 -0.002393 +v 0.004507 0.153983 -0.002230 +v 0.039132 0.153980 0.002861 +v 0.042000 0.152632 0.019893 +v 0.040000 0.152398 0.021471 +v 0.041998 0.142707 -0.060586 +v 0.038142 0.140863 -0.062288 +v 0.040206 0.144070 -0.057686 +v 0.000000 0.139457 -0.064088 +v 0.003970 0.140839 -0.062320 +v 0.010412 0.135836 -0.067503 +v 0.032567 0.136472 -0.066906 +v 0.022422 0.136578 -0.066810 +v 0.018500 0.135800 -0.067537 +v 0.042000 0.051049 -0.146556 +v 0.042000 0.046870 -0.138492 +v 0.041948 0.040694 -0.146227 +v 0.041949 0.040686 0.146224 +v 0.042000 0.046701 0.138527 +v 0.042000 0.051049 0.146556 +v 0.041904 0.041619 0.137847 +v 0.042000 0.049363 0.097061 +v 0.042000 0.043324 0.094900 +v 0.042000 0.052978 0.096079 +v 0.042000 0.049790 -0.134920 +v 0.041849 0.041472 -0.137820 +v 0.042000 0.049739 0.135109 +v 0.042000 0.065713 -0.127447 +v 0.042000 0.032846 0.093333 +v 0.041761 0.033477 0.098168 +v 0.042000 0.065478 0.127439 +v 0.041976 0.036415 0.100351 +v 0.042000 0.082217 0.117492 +v 0.042000 0.092773 0.102976 +v 0.042000 0.115126 0.086803 +v 0.042000 0.089752 0.095613 +v 0.042000 0.098672 -0.102148 +v 0.042000 0.093307 -0.101488 +v 0.042000 0.032394 -0.092985 +v 0.042000 0.043521 -0.094944 +v 0.042000 0.052874 -0.096141 +v 0.042000 0.049230 -0.096855 +v 0.042000 0.052090 0.114150 +v 0.042000 0.052146 -0.114291 +v 0.041840 0.033502 -0.098172 +v 0.041776 0.036131 -0.100210 +v 0.042000 0.088310 -0.095173 +v 0.041999 0.140440 0.063047 +v 0.041930 0.037824 -0.100010 +v 0.003853 -0.015553 -0.093224 +v 0.007151 -0.015546 -0.088861 +v 0.003967 -0.015603 -0.080362 +v 0.012444 -0.015649 -0.092151 +v 0.021656 -0.015510 -0.088532 +v 0.016754 -0.015605 -0.092725 +v 0.038031 -0.015594 -0.080502 +v 0.037999 -0.015528 -0.093369 +v 0.036069 -0.015526 -0.089168 +v 0.030489 -0.015556 -0.090533 +v 0.025094 -0.015532 -0.093496 +v 0.033847 -0.000399 -0.095466 +v 0.021799 -0.000456 -0.095359 +v 0.023387 -0.002281 -0.093930 +v 0.031363 -0.002899 -0.093171 +v 0.022966 -0.003595 -0.091087 +v 0.033641 -0.003601 -0.090206 +v 0.019648 -0.000528 -0.095139 +v 0.004614 -0.000561 -0.094823 +v 0.007513 -0.000403 -0.095427 +v 0.010320 -0.002097 -0.094169 +v 0.018363 -0.002899 -0.093171 +v 0.009965 -0.003596 -0.091087 +v 0.019640 -0.003564 -0.090788 +v 0.040154 -0.000100 -0.095339 +v 0.036726 -0.003061 -0.093010 +v 0.041994 -0.003109 -0.093140 +v 0.010121 0.045684 -0.150450 +v 0.018892 0.045534 -0.150476 +v 0.016903 0.041508 -0.150534 +v 0.012007 0.041505 -0.150519 +v 0.023683 0.045200 -0.150519 +v 0.032180 0.045725 -0.150440 +v 0.029902 0.041531 -0.150533 +v 0.025007 0.041505 -0.150519 +v 0.042016 -0.012451 -0.076540 +v 0.042000 -0.003490 -0.085466 +v 0.042000 -0.000157 -0.081589 +v 0.041898 -0.011065 -0.094411 +v 0.037961 -0.010332 -0.098580 +v 0.004056 -0.010351 -0.098589 +v 0.038113 -0.000025 -0.097182 +v 0.004105 -0.000131 -0.097244 +v 0.037932 0.011608 -0.099023 +v 0.004107 0.011704 -0.099081 +v 0.038089 0.021824 -0.104172 +v 0.004095 0.024573 -0.106164 +v 0.038050 0.030144 -0.112178 +v 0.004059 0.033567 -0.117616 +v 0.037899 0.035886 -0.123194 +v 0.004080 0.036877 -0.127216 +v 0.038103 0.037802 -0.135059 +v 0.004056 0.037778 -0.135199 +v 0.037944 0.036411 -0.145351 +v 0.004042 0.036420 -0.145334 +v 0.025037 0.082217 -0.117492 +v 0.034310 0.065889 -0.132718 +v 0.031146 0.063993 -0.134486 +v 0.025037 0.048488 -0.148944 +v 0.033926 0.061997 -0.136347 +v 0.038639 0.047308 -0.149917 +v 0.036779 0.063696 -0.134763 +v 0.023336 0.133825 -0.069367 +v 0.010151 0.065178 -0.133381 +v 0.021549 0.065831 -0.132772 +v 0.018203 0.064355 -0.134149 +v 0.020494 0.062105 -0.136423 +v 0.023806 0.063467 -0.134977 +v 0.023244 0.099293 -0.101568 +v 0.019178 0.099001 -0.101841 +v 0.023000 0.112435 -0.089313 +v 0.023010 0.101679 -0.099343 +v 0.019398 0.102282 -0.098781 +v 0.003363 0.047355 -0.149920 +v 0.000000 0.051049 -0.146556 +v 0.005761 0.099205 -0.101651 +v 0.005824 0.133823 -0.069368 +v 0.005661 0.065206 -0.133355 +v 0.006793 0.062172 -0.136184 +v 0.009980 0.062647 -0.135741 +v 0.010245 0.099279 -0.101581 +v 0.009894 0.101812 -0.099219 +v 0.006697 0.102266 -0.098796 +v 0.009109 0.132996 -0.070140 +v 0.006228 0.136512 -0.066861 +v 0.019793 0.133113 -0.070030 +v 0.035606 0.102081 -0.098968 +v 0.031395 0.101457 -0.099550 +v 0.036500 0.099957 -0.100949 +v 0.033676 0.098468 -0.102338 +v 0.035606 0.136455 -0.066914 +v 0.035845 0.133168 -0.069980 +v 0.031396 0.134242 -0.068978 +v 0.000000 -0.079749 -0.044866 +v 0.000000 -0.073156 -0.053715 +v 0.033484 -0.073979 -0.053075 +v 0.033510 -0.068065 -0.056362 +v 0.031794 -0.033103 -0.069266 +v 0.042000 -0.066816 -0.056591 +v 0.032463 -0.059569 -0.059446 +v 0.007402 -0.059772 -0.059337 +v 0.008059 -0.032943 -0.069265 +v 0.038177 -0.018830 -0.074334 +v 0.004061 -0.019091 -0.074246 +v 0.040578 0.025185 -0.104014 +v 0.005667 0.025160 -0.103926 +v 0.005676 0.015083 -0.098216 +v 0.039920 0.012704 -0.097358 +v 0.004789 0.006566 -0.095772 +v 0.042101 0.029552 -0.102989 +v 0.006140 0.028632 -0.103372 +v 0.040224 0.030321 -0.101950 +v 0.005643 0.032982 -0.098845 +v 0.040218 0.032772 -0.099328 +v 0.005097 0.031272 -0.092609 +v 0.005337 0.033199 -0.094911 +v 0.005604 0.001297 -0.081724 +v 0.005582 -0.003351 -0.085462 +v 0.005673 -0.001811 -0.082945 +v 0.006695 -0.003564 -0.090771 +v 0.002241 0.000201 -0.092056 +v 0.002394 0.014061 -0.094861 +v 0.002121 0.001103 -0.085285 +v 0.002216 0.030051 -0.095372 +v 0.002181 0.026524 -0.100574 +v 0.002000 0.053041 -0.095975 +v 0.002000 0.088481 -0.095248 +v 0.002000 0.052090 -0.114150 +v 0.002000 0.065478 -0.127439 +v 0.002000 0.093298 -0.101723 +v 0.005075 0.049298 -0.135802 +v 0.005837 0.046515 -0.138344 +v 0.006590 0.044199 -0.138583 +v 0.005566 0.049595 -0.098310 +v 0.005458 0.043048 -0.095238 +v 0.004774 0.047147 -0.095780 +v 0.040085 0.035895 -0.101894 +v 0.005987 0.031370 -0.106751 +v 0.040384 0.032888 -0.104696 +v 0.040424 0.030966 -0.109901 +v 0.005025 0.031229 -0.109902 +v 0.042077 0.032023 -0.105259 +v 0.040082 0.039597 -0.134759 +v 0.005194 0.039813 -0.134858 +v 0.039959 0.037678 -0.122262 +v 0.005644 0.038754 -0.126594 +v 0.005695 0.035848 -0.118029 +v 0.034152 0.039524 -0.135408 +v 0.036705 0.042111 -0.138104 +v 0.033947 0.044730 -0.138573 +v 0.008892 0.039667 -0.135425 +v 0.006557 0.039896 -0.135571 +v 0.021154 0.039537 -0.135397 +v 0.018219 0.042336 -0.138243 +v 0.010637 0.041829 -0.137899 +v 0.009360 0.044212 -0.138563 +v 0.021002 0.044599 -0.138559 +v 0.031274 0.041989 -0.138050 +v 0.023725 0.042508 -0.138323 +v 0.002300 0.033904 -0.108938 +v 0.002371 0.038717 -0.118347 +v 0.002263 0.044685 -0.097764 +v 0.002072 0.044092 -0.135119 +v 0.035335 -0.014472 -0.095644 +v 0.038025 -0.013815 -0.097020 +v 0.022308 -0.014474 -0.095547 +v 0.031237 -0.014951 -0.095041 +v 0.020028 -0.014485 -0.095741 +v 0.008699 -0.014393 -0.095760 +v 0.006884 -0.014467 -0.095815 +v 0.004016 -0.013591 -0.097170 +v 0.037848 0.044297 -0.150641 +v 0.004333 0.044398 -0.150642 +v 0.021747 0.039192 -0.149420 +v 0.032317 0.039653 -0.149509 +v 0.004104 0.040587 -0.150382 +v 0.008224 0.039023 -0.149348 +v 0.004025 0.037720 -0.148500 +v 0.037983 0.037839 -0.148603 +v 0.035212 0.039346 -0.149451 +v 0.037897 0.041023 -0.150468 +v 0.019322 0.039610 -0.149532 +v 0.003110 0.031991 -0.097297 +v 0.003658 0.027673 -0.102551 +v 0.003348 0.024747 -0.102277 +v 0.003383 0.000590 -0.083026 +v 0.002720 -0.001134 -0.085373 +v 0.005313 -0.002938 -0.092741 +v 0.003619 -0.002160 -0.091722 +v 0.003661 0.032768 -0.106865 +v 0.002743 0.047497 -0.098678 +v 0.002829 0.040731 -0.126298 +v 0.003238 0.041513 -0.135462 +v 0.002812 0.047600 -0.134891 +v 0.005290 0.042161 -0.137852 +v 0.003386 0.045477 -0.137155 +v 0.000003 -0.016838 -0.070974 +v 0.000002 -0.025510 -0.068032 +v 0.000002 -0.011995 -0.078076 +v 0.000065 -0.011117 -0.094348 +v 0.000177 -0.000537 -0.093331 +v 0.000193 0.019133 -0.097454 +v 0.000761 0.029472 -0.106208 +v 0.000229 0.038616 -0.118895 +v 0.000301 0.041480 -0.135295 +v 0.000013 0.040760 -0.146195 +v 0.020551 0.044686 -0.148994 +v 0.023749 0.042248 -0.148992 +v 0.018483 0.042515 -0.149045 +v 0.005318 0.041862 -0.149051 +v 0.007516 0.044694 -0.149007 +v 0.010290 0.043194 -0.149048 +v 0.010178 0.040433 -0.149021 +v 0.035169 0.044411 -0.149047 +v 0.036561 0.042048 -0.149045 +v 0.031671 0.043418 -0.148997 +v 0.020049 -0.014011 -0.090447 +v 0.018400 -0.014050 -0.093458 +v 0.023567 -0.014030 -0.092046 +v 0.007257 -0.014034 -0.090415 +v 0.005397 -0.014060 -0.092773 +v 0.010093 -0.014028 -0.091460 +v 0.010348 -0.014069 -0.094248 +v 0.031331 -0.014044 -0.093232 +v 0.033498 -0.014012 -0.090322 +v 0.036595 -0.014048 -0.092289 +v 0.006189 0.129543 -0.059660 +v 0.010245 0.129245 -0.059924 +v 0.008000 0.127030 -0.059976 +v 0.009749 0.126596 -0.062423 +v 0.006076 0.126556 -0.062431 +v 0.021000 0.127030 -0.059976 +v 0.020267 0.129880 -0.059365 +v 0.023337 0.129083 -0.060088 +v 0.021811 0.125982 -0.062918 +v 0.018263 0.127992 -0.061106 +v 0.034874 0.129939 -0.059291 +v 0.036602 0.127929 -0.061185 +v 0.034000 0.127030 -0.059976 +v 0.034541 0.126078 -0.062891 +v 0.031108 0.128145 -0.060907 +v 0.021000 0.056088 -0.126130 +v 0.021627 0.058964 -0.125499 +v 0.023673 0.057323 -0.127016 +v 0.020830 0.054953 -0.129163 +v 0.018443 0.057909 -0.126446 +v 0.021841 0.095507 -0.091413 +v 0.023716 0.093161 -0.093582 +v 0.021000 0.092656 -0.092030 +v 0.020127 0.091769 -0.094884 +v 0.018443 0.094477 -0.092346 +v 0.009046 0.058856 -0.125597 +v 0.010707 0.056800 -0.127494 +v 0.008000 0.056088 -0.126130 +v 0.006841 0.055129 -0.128995 +v 0.005860 0.058349 -0.126049 +v 0.035924 0.058571 -0.125829 +v 0.035947 0.055747 -0.128485 +v 0.034000 0.056088 -0.126130 +v 0.031868 0.055708 -0.128480 +v 0.032252 0.058560 -0.125868 +v 0.005586 0.094811 -0.091991 +v 0.010054 0.094991 -0.091880 +v 0.008000 0.092656 -0.092030 +v 0.010170 0.092620 -0.094111 +v 0.007126 0.091769 -0.094884 +v 0.035159 0.095581 -0.091273 +v 0.036437 0.093075 -0.093690 +v 0.034000 0.092656 -0.092030 +v 0.033576 0.091595 -0.095015 +v 0.031386 0.094135 -0.092688 +v 0.032392 -0.088673 -0.016177 +v 0.030867 -0.088842 -0.015537 +v 0.029271 -0.089236 -0.014563 +v 0.032112 -0.089263 -0.014600 +v 0.042000 -0.089751 -0.013713 +v 0.026830 -0.089196 -0.014673 +v 0.042000 -0.091916 -0.011906 +v 0.000000 -0.091925 -0.011902 +v 0.042000 -0.088866 0.015431 +v 0.042001 -0.091729 0.011726 +v 0.000000 -0.091916 0.011906 +v 0.000000 -0.089225 0.014444 +v 0.035106 -0.072548 -0.057457 +v 0.042000 -0.072974 -0.057443 +v 0.042000 -0.090010 -0.027383 +v 0.042000 -0.084200 -0.043313 +v 0.002775 0.143404 -0.000720 +v 0.039048 0.143447 -0.000519 +v 0.002148 0.131161 -0.058320 +v 0.039503 0.130914 -0.059478 +v 0.004974 0.130713 -0.060427 +v 0.010163 -0.055632 -0.063885 +v 0.029720 -0.055594 -0.064182 +v 0.009492 -0.057028 -0.061846 +v 0.030614 -0.057044 -0.061781 +v 0.010964 -0.052829 -0.073850 +v 0.029031 -0.052811 -0.073876 +v 0.009829 -0.036347 -0.069723 +v 0.029971 -0.037913 -0.070071 +v 0.030007 -0.052275 -0.072942 +v 0.009993 -0.052242 -0.072961 +v 0.026674 -0.082000 -0.015825 +v 0.028839 -0.082000 -0.016610 +v 0.028286 -0.082000 -0.013952 +v 0.031554 -0.080222 -0.014566 +v 0.032662 -0.080222 -0.015668 +v 0.031224 -0.080222 -0.016189 +v 0.000000 -0.090010 -0.027388 +v 0.021809 -0.086464 -0.037281 +v 0.018763 -0.087004 -0.035797 +v 0.000000 -0.084203 -0.043326 +v 0.020574 -0.087871 -0.033414 +v 0.023040 -0.087438 -0.034604 +v 0.005588 -0.086266 -0.037824 +v 0.005902 -0.088107 -0.032766 +v 0.036207 -0.086338 -0.037626 +v 0.032207 -0.086876 -0.036149 +v 0.034922 -0.088099 -0.032787 +v 0.037594 -0.087343 -0.034864 +v 0.009793 -0.087105 -0.035518 +v 0.035000 -0.076353 -0.031430 +v 0.036311 -0.076924 -0.034196 +v 0.037533 -0.077970 -0.031363 +v 0.035067 -0.078682 -0.029365 +v 0.032183 -0.077474 -0.032562 +v 0.008773 -0.076964 -0.034018 +v 0.008811 -0.078449 -0.030007 +v 0.007000 -0.076353 -0.031430 +v 0.005555 -0.078502 -0.029903 +v 0.004443 -0.077355 -0.032983 +v 0.021507 -0.077040 -0.033905 +v 0.023156 -0.077980 -0.031251 +v 0.021000 -0.076635 -0.031533 +v 0.020138 -0.078429 -0.030087 +v 0.018924 -0.077511 -0.032595 +v 0.027675 -0.088549 0.016873 +v 0.000000 -0.087521 0.023141 +v 0.042000 -0.087553 0.023366 +v 0.033283 -0.077657 0.048449 +v 0.042000 -0.077526 0.048540 +v 0.034917 -0.077406 0.051974 +v 0.042000 -0.078077 0.055640 +v 0.035000 -0.078096 0.055525 +v -0.000002 0.145015 0.055538 +v 0.001903 0.143041 0.059562 +v -0.000001 0.139508 0.064012 +v 0.004507 0.140719 0.062456 +v 0.038034 0.140841 0.062317 +v 0.034170 0.137004 0.066405 +v 0.019398 0.136465 0.066918 +v 0.023603 0.135832 0.067506 +v 0.040151 0.143671 0.058383 +v 0.042000 0.145649 0.053392 +v 0.038074 -0.015527 0.093516 +v 0.034878 -0.015527 0.088732 +v 0.038042 -0.015592 0.080485 +v 0.010290 -0.015535 0.089283 +v 0.003934 -0.015984 0.077941 +v 0.005136 -0.015550 0.089975 +v 0.004168 -0.015335 0.094651 +v 0.018926 -0.015535 0.089158 +v 0.030281 -0.015564 0.091095 +v 0.025355 -0.015665 0.091602 +v 0.017005 -0.015497 0.093679 +v 0.011981 -0.015502 0.093680 +v 0.036414 -0.003409 0.091959 +v 0.035742 -0.000750 0.095107 +v 0.041991 -0.003137 0.093069 +v 0.039615 0.001059 0.095930 +v 0.032929 -0.000451 0.095275 +v 0.004493 -0.000381 0.094836 +v 0.019935 -0.000453 0.095280 +v 0.009333 -0.000533 0.095145 +v 0.006858 -0.000460 0.095259 +v 0.010499 -0.002520 0.093678 +v 0.018560 -0.002431 0.093746 +v 0.019265 -0.003607 0.090829 +v 0.009849 -0.003557 0.091135 +v 0.006877 -0.003587 0.090593 +v 0.022335 -0.000534 0.095144 +v 0.023498 -0.002520 0.093678 +v 0.031560 -0.002431 0.093746 +v 0.031792 -0.003476 0.091625 +v 0.022849 -0.003557 0.091135 +v 0.034094 -0.003561 0.090389 +v 0.037892 0.040588 0.150381 +v 0.038258 0.046645 0.150299 +v 0.036896 0.044932 0.150548 +v 0.012096 0.041527 0.150531 +v 0.017019 0.041320 0.150502 +v 0.018317 0.045200 0.150519 +v 0.009829 0.045726 0.150446 +v 0.025106 0.041737 0.150554 +v 0.031876 0.045685 0.150453 +v 0.023108 0.045534 0.150476 +v 0.030019 0.041336 0.150500 +v 0.041929 0.028822 0.103220 +v 0.041966 0.031287 0.103808 +v 0.042072 0.031804 0.106161 +v 0.041885 -0.011027 0.094449 +v 0.042000 -0.003478 0.085351 +v 0.042000 -0.012404 0.076380 +v 0.042000 -0.000006 0.081578 +v 0.037954 0.036420 0.145336 +v 0.004057 0.036412 0.145351 +v 0.038079 0.037825 0.134980 +v 0.004270 0.037691 0.135396 +v 0.037907 0.035841 0.122986 +v 0.004135 0.036687 0.125576 +v 0.038078 0.031531 0.114253 +v 0.004132 0.031592 0.114112 +v 0.038185 0.024933 0.106446 +v 0.004041 0.023534 0.105339 +v 0.037867 0.015369 0.100383 +v 0.004093 0.012014 0.099159 +v 0.038024 -0.000731 0.097259 +v 0.004107 -0.000051 0.097217 +v 0.037943 -0.010351 0.098588 +v 0.004046 -0.010336 0.098580 +v 0.033844 0.062029 0.136318 +v 0.025038 0.048488 0.148944 +v 0.031419 0.063370 0.135067 +v 0.031592 0.099618 0.101265 +v 0.033914 0.066108 0.132514 +v 0.036604 0.063301 0.135132 +v 0.003362 0.047304 0.149918 +v 0.008274 0.062109 0.136423 +v 0.000000 0.051049 0.146556 +v 0.005905 0.062797 0.135602 +v 0.006439 0.065785 0.132815 +v 0.010854 0.063993 0.134486 +v 0.000000 0.090334 0.109923 +v 0.022150 0.133170 0.069978 +v 0.020486 0.065777 0.132822 +v 0.023163 0.065099 0.133454 +v 0.020767 0.061982 0.136361 +v 0.018207 0.064053 0.134430 +v 0.023211 0.062935 0.135473 +v 0.022641 0.102007 0.099038 +v 0.018755 0.133653 0.069527 +v 0.019394 0.102081 0.098968 +v 0.018592 0.099618 0.101265 +v 0.021226 0.098609 0.102206 +v 0.023488 0.099763 0.101130 +v 0.032561 0.102209 0.098849 +v 0.036793 0.101112 0.099872 +v 0.034532 0.098604 0.102211 +v 0.033613 0.132958 0.070175 +v 0.036604 0.134242 0.068978 +v 0.031325 0.134647 0.068600 +v 0.006242 0.101949 0.099092 +v 0.009482 0.102145 0.098909 +v 0.010120 0.099037 0.101807 +v 0.005664 0.099448 0.101423 +v 0.000000 0.115126 0.086803 +v 0.010333 0.133524 0.069647 +v 0.005207 0.134263 0.068958 +v 0.008415 0.136940 0.066461 +v 0.033253 -0.067563 0.056454 +v 0.000000 -0.072923 0.053782 +v 0.032960 -0.072717 0.053782 +v 0.000000 -0.079804 0.044778 +v 0.042000 -0.068287 0.056284 +v 0.032347 -0.059401 0.059539 +v 0.007697 -0.059487 0.059500 +v 0.008112 -0.032916 0.069294 +v 0.032723 -0.031611 0.069542 +v 0.038142 -0.018766 0.074426 +v 0.004124 -0.022882 0.072430 +v 0.039978 0.012652 0.097293 +v 0.005644 0.008406 0.096246 +v 0.005326 0.017066 0.099131 +v 0.040440 0.025105 0.104036 +v 0.005586 0.024824 0.103796 +v 0.006183 0.028528 0.103467 +v 0.005289 0.032804 0.098989 +v 0.040094 0.032583 0.099582 +v 0.040201 0.030559 0.101715 +v 0.005679 0.033458 0.095606 +v 0.004799 0.031471 0.092827 +v 0.004643 0.001923 0.082051 +v 0.005595 -0.001126 0.082415 +v 0.004724 -0.003169 0.085497 +v 0.002178 0.016154 0.095090 +v 0.002375 -0.000658 0.091807 +v 0.002308 0.000112 0.084820 +v 0.002187 0.026017 0.100620 +v 0.002171 0.029879 0.095460 +v 0.002000 0.088399 0.095229 +v 0.002000 0.052934 0.096034 +v 0.002000 0.052146 0.114291 +v 0.002000 0.065713 0.127447 +v 0.002000 0.093307 0.101488 +v 0.005769 0.046479 0.138365 +v 0.005194 0.049411 0.135582 +v 0.005460 0.049457 0.097873 +v 0.004510 0.046439 0.095577 +v 0.006217 0.042914 0.095215 +v 0.005980 0.031342 0.106792 +v 0.040153 0.033241 0.104521 +v 0.040260 0.036181 0.101451 +v 0.040529 0.030983 0.109831 +v 0.005472 0.031319 0.110358 +v 0.004784 0.035946 0.117828 +v 0.039932 0.037818 0.122692 +v 0.005608 0.038739 0.126440 +v 0.005078 0.039858 0.134944 +v 0.040160 0.039675 0.135109 +v 0.022736 0.044171 0.138606 +v 0.035058 0.044434 0.138571 +v 0.032151 0.043865 0.138557 +v 0.031502 0.041322 0.137520 +v 0.023440 0.041254 0.137431 +v 0.022065 0.039720 0.135453 +v 0.034100 0.039518 0.135405 +v 0.009054 0.039706 0.135473 +v 0.019665 0.039856 0.135534 +v 0.018502 0.041322 0.137520 +v 0.010692 0.042138 0.138102 +v 0.019151 0.043865 0.138557 +v 0.008294 0.044661 0.138577 +v 0.006619 0.039863 0.135523 +v 0.036636 0.041826 0.137909 +v 0.002086 0.045174 0.098504 +v 0.002285 0.040619 0.122564 +v 0.002406 0.033543 0.109066 +v 0.001983 0.044387 0.134580 +v 0.030818 -0.015107 0.095074 +v 0.022157 -0.014497 0.095823 +v 0.003996 -0.013828 0.097036 +v 0.009124 -0.014478 0.095813 +v 0.037983 -0.013603 0.097161 +v 0.020320 -0.014360 0.095744 +v 0.035160 -0.014478 0.095806 +v 0.004151 0.044297 0.150640 +v 0.037978 0.037761 0.148549 +v 0.003994 0.038030 0.148845 +v 0.032989 0.039110 0.149440 +v 0.022209 0.039425 0.149498 +v 0.008724 0.039199 0.149451 +v 0.004413 0.040208 0.150259 +v 0.019919 0.039262 0.149433 +v 0.003218 0.026691 0.102620 +v 0.002807 0.031679 0.096651 +v 0.002836 0.010882 0.094700 +v 0.005340 -0.002923 0.092790 +v 0.003408 0.032564 0.107528 +v 0.003707 0.043022 0.096597 +v 0.003153 0.047981 0.098492 +v 0.002781 0.042052 0.135037 +v 0.002759 0.047625 0.134460 +v 0.005254 0.042488 0.137997 +v 0.003919 0.042879 0.137397 +v 0.002825 0.045754 0.136441 +v 0.000003 -0.016838 0.070974 +v 0.000002 -0.025510 0.068032 +v 0.000002 -0.011995 0.078076 +v 0.000106 -0.011071 0.094391 +v 0.000207 0.011016 0.094439 +v 0.000732 0.019617 0.099160 +v 0.000217 0.032247 0.108477 +v 0.000727 0.038457 0.121093 +v 0.000205 0.041768 0.130789 +v 0.000019 0.040740 0.146192 +v 0.023443 0.041180 0.149058 +v 0.022971 0.043755 0.149026 +v 0.020056 0.044465 0.149043 +v 0.018418 0.042267 0.149044 +v 0.006647 0.044259 0.149052 +v 0.009848 0.043938 0.149016 +v 0.005424 0.041990 0.149061 +v 0.006684 0.039706 0.149034 +v 0.010443 0.041180 0.149058 +v 0.034515 0.039402 0.149048 +v 0.036443 0.041180 0.149058 +v 0.035971 0.043755 0.149026 +v 0.033056 0.044465 0.149043 +v 0.031418 0.042267 0.149044 +v 0.018326 -0.014057 0.093170 +v 0.020097 -0.014037 0.090521 +v 0.023486 -0.013962 0.091800 +v 0.006750 -0.014015 0.095502 +v 0.005501 -0.014054 0.092222 +v 0.008271 -0.013990 0.090243 +v 0.010581 -0.014042 0.092730 +v 0.033485 -0.014048 0.095598 +v 0.031248 -0.013989 0.092433 +v 0.034713 -0.014026 0.090417 +v 0.036581 -0.014042 0.092730 +v 0.008000 0.127030 0.059976 +v 0.008733 0.129881 0.059365 +v 0.005663 0.129084 0.060088 +v 0.006404 0.126462 0.062542 +v 0.009445 0.126464 0.062551 +v 0.010616 0.128339 0.060798 +v 0.022371 0.129694 0.059528 +v 0.018755 0.129245 0.059924 +v 0.021000 0.127030 0.059976 +v 0.019574 0.126332 0.062654 +v 0.023499 0.127125 0.061902 +v 0.033576 0.130081 0.059126 +v 0.031405 0.127402 0.061656 +v 0.034000 0.127030 0.059976 +v 0.034633 0.126134 0.062848 +v 0.036684 0.128170 0.060950 +v 0.021781 0.059045 0.125383 +v 0.018536 0.057812 0.126566 +v 0.021000 0.056088 0.126130 +v 0.019574 0.055390 0.128808 +v 0.023499 0.056184 0.128056 +v 0.022473 0.095414 0.091445 +v 0.018451 0.094398 0.092433 +v 0.021000 0.092656 0.092030 +v 0.019805 0.091910 0.094763 +v 0.023166 0.092508 0.094203 +v 0.008288 0.059004 0.125458 +v 0.005451 0.057830 0.126533 +v 0.008000 0.056088 0.126130 +v 0.007676 0.054966 0.129148 +v 0.010707 0.057399 0.126935 +v 0.034999 0.058964 0.125476 +v 0.031324 0.057669 0.126670 +v 0.034000 0.056088 0.126130 +v 0.033241 0.055217 0.128979 +v 0.036549 0.056369 0.127896 +v 0.008000 0.092656 0.092030 +v 0.008067 0.095669 0.091248 +v 0.005602 0.094362 0.092489 +v 0.006189 0.092165 0.094515 +v 0.009856 0.092248 0.094448 +v 0.010437 0.094282 0.092564 +v 0.034759 0.095559 0.091359 +v 0.032066 0.094920 0.091968 +v 0.034000 0.092656 0.092030 +v 0.031535 0.092884 0.093854 +v 0.034167 0.091775 0.094899 +v 0.036684 0.093272 0.093483 +v 0.039962 0.139421 0.059252 +v 0.039225 0.151497 0.002441 +v 0.002705 0.151516 0.002354 +v 0.002641 0.138991 0.061274 +v 0.037764 0.138836 0.062007 +v 0.027386 -0.089557 0.014022 +v 0.032796 -0.089028 0.015015 +v 0.030972 -0.089022 0.015039 +v 0.029331 -0.088873 0.015465 +v 0.031624 -0.088672 0.016249 +v 0.035134 -0.072469 0.057400 +v 0.042000 -0.072864 0.057530 +v 0.042000 -0.080482 0.044486 +v 0.042000 -0.084197 0.043329 +v 0.042000 -0.090013 0.027395 +v 0.029274 -0.056212 0.063335 +v 0.010729 -0.056208 0.063326 +v 0.029047 -0.052810 0.073865 +v 0.010975 -0.052803 0.073885 +v 0.009788 -0.035991 0.069668 +v 0.030265 -0.036235 0.069678 +v 0.030007 -0.052242 0.072961 +v 0.030171 -0.055288 0.063457 +v 0.009806 -0.055335 0.063361 +v 0.009993 -0.052275 0.072941 +v 0.029363 -0.082000 0.015164 +v 0.028026 -0.082000 0.016846 +v 0.027790 -0.082000 0.014068 +v 0.026669 -0.082000 0.015444 +v 0.031084 -0.080222 0.014807 +v 0.031855 -0.080222 0.016434 +v 0.032634 -0.080222 0.015194 +v 0.000000 -0.090001 0.027334 +v 0.021248 -0.087893 0.033353 +v 0.019134 -0.087480 0.034487 +v 0.005439 -0.086295 0.037743 +v 0.000000 -0.084221 0.043302 +v 0.019664 -0.086547 0.037051 +v 0.023234 -0.086933 0.035992 +v 0.009581 -0.086898 0.036088 +v 0.008387 -0.087933 0.033245 +v 0.005150 -0.087831 0.033525 +v 0.034423 -0.086205 0.037992 +v 0.037594 -0.086979 0.035864 +v 0.036207 -0.087985 0.033101 +v 0.032499 -0.087590 0.034185 +v 0.035000 -0.076353 0.031430 +v 0.035067 -0.076810 0.034509 +v 0.032602 -0.077442 0.032821 +v 0.033053 -0.078387 0.030196 +v 0.036708 -0.078478 0.029926 +v 0.037437 -0.077479 0.032718 +v 0.007070 -0.076752 0.034600 +v 0.004288 -0.077961 0.031318 +v 0.007000 -0.076353 0.031430 +v 0.007167 -0.078650 0.029497 +v 0.009684 -0.077931 0.031429 +v 0.021607 -0.077049 0.033880 +v 0.018960 -0.077476 0.032689 +v 0.021000 -0.076635 0.031533 +v 0.020370 -0.078475 0.029924 +v 0.023147 -0.077898 0.031532 +v 0.121573 0.044178 -0.089299 +v 0.042132 0.036540 -0.095613 +v 0.122441 0.084491 -0.089135 +v 0.042132 0.092220 -0.095505 +v 0.126563 0.036372 -0.087356 +v 0.126388 0.094247 -0.086828 +v 0.132630 0.103219 -0.082718 +v 0.042130 0.114609 -0.085465 +v 0.136610 0.111628 -0.077022 +v 0.042131 0.126861 -0.073846 +v 0.131588 0.119727 -0.069836 +v 0.042131 0.136594 -0.057718 +v 0.127047 0.125336 -0.061983 +v 0.145682 0.000495 -0.072769 +v 0.112968 -0.057865 -0.054618 +v 0.065752 -0.071763 -0.053639 +v 0.042133 -0.075449 -0.053804 +v 0.142099 -0.040768 -0.058087 +v 0.159088 0.011539 0.059239 +v 0.156502 -0.019657 0.052898 +v 0.160602 -0.006052 0.029509 +v 0.159319 0.010446 -0.057527 +v 0.159951 0.048658 -0.058026 +v 0.162472 0.034734 -0.035300 +v 0.162885 0.054728 -0.024424 +v 0.163205 0.019767 0.003107 +v 0.163521 0.048217 0.003872 +v 0.162398 0.036334 0.036370 +v 0.154245 -0.037722 0.045355 +v 0.153316 -0.050789 0.022060 +v 0.159970 -0.016335 -0.010059 +v 0.153185 -0.052896 -0.005808 +v 0.152069 -0.053657 -0.028282 +v 0.156177 -0.022976 -0.051689 +v 0.153033 -0.042644 -0.044617 +v 0.161525 0.005207 -0.028569 +v 0.159910 0.051945 0.058059 +v 0.153157 0.102240 0.066762 +v 0.156790 0.084251 0.061562 +v 0.155453 0.105920 0.047384 +v 0.158089 0.105121 0.002454 +v 0.160967 0.074600 0.034854 +v 0.161137 0.082638 -0.009974 +v 0.155642 0.105774 -0.045594 +v 0.158947 0.083378 -0.046458 +v 0.157330 0.080551 -0.060840 +v 0.153238 0.102277 -0.066582 +v 0.102512 0.137627 -0.040546 +v 0.087542 0.142928 -0.025578 +v 0.109255 0.137645 -0.019606 +v 0.139647 0.122353 -0.040989 +v 0.141804 0.115884 -0.068008 +v 0.150617 0.110749 -0.059771 +v 0.150517 0.109823 0.063873 +v 0.143757 0.118603 0.046566 +v 0.142736 0.115179 0.068093 +v 0.128296 0.125106 0.061054 +v 0.115818 0.131796 0.052200 +v 0.131855 0.127224 0.034651 +v 0.072927 0.146200 0.013186 +v 0.089069 0.142323 0.027494 +v 0.090611 0.143282 0.000800 +v 0.066008 0.147360 -0.005527 +v 0.114613 0.132380 -0.050880 +v 0.152337 0.113811 -0.027246 +v 0.152331 0.112316 0.039652 +v 0.128399 0.130089 -0.020790 +v 0.100079 0.138807 0.037323 +v 0.125212 0.132108 0.012535 +v 0.143671 0.121466 0.019699 +v 0.142136 0.123030 -0.006806 +v 0.109539 0.138035 0.005438 +v 0.151770 0.115326 0.006070 +v 0.122683 0.084229 0.089090 +v 0.042132 0.091664 0.095572 +v 0.122050 0.045398 0.089270 +v 0.042131 0.036499 0.095620 +v 0.124712 0.034870 0.087311 +v 0.042132 0.132031 0.067549 +v 0.129086 0.120837 0.069229 +v 0.042131 0.113595 0.086078 +v 0.136657 0.111875 0.076865 +v 0.131735 0.102792 0.083059 +v 0.127902 0.093492 0.086723 +v 0.146002 0.000962 0.072784 +v 0.140820 -0.040567 0.058424 +v 0.042131 -0.073957 0.054805 +v 0.065928 -0.072026 0.053468 +v 0.088280 -0.066153 0.053872 +v 0.063534 -0.076469 -0.049129 +v 0.092142 -0.068731 -0.051181 +v 0.084242 -0.080840 -0.036175 +v 0.121254 -0.073013 -0.030310 +v 0.121550 -0.058893 -0.051036 +v 0.144516 -0.061031 -0.033016 +v 0.146114 -0.052681 -0.043411 +v 0.146692 -0.043283 -0.054295 +v 0.101128 -0.082819 -0.024703 +v 0.062370 -0.076712 0.048960 +v 0.042143 -0.078638 0.049458 +v 0.042128 -0.088678 0.026185 +v 0.083498 -0.080693 0.036869 +v 0.097693 -0.084426 0.020763 +v 0.092605 -0.086948 0.003072 +v 0.042132 -0.091540 -0.005437 +v 0.093684 -0.086250 -0.012363 +v 0.042129 -0.086422 -0.032471 +v 0.042132 0.145132 -0.034255 +v 0.042135 0.149906 0.000569 +v 0.042131 0.145010 0.034852 +v 0.145307 -0.055630 0.040466 +v 0.144364 -0.042825 0.056101 +v 0.129776 -0.051773 0.054597 +v 0.099369 -0.082516 0.026237 +v 0.121010 -0.073717 0.029315 +v 0.078156 -0.073653 0.049358 +v 0.108538 -0.064055 0.050745 +v 0.145506 -0.061619 0.030307 +v 0.121147 -0.074934 0.021702 +v 0.145757 -0.063015 0.001466 +v 0.120918 -0.074671 -0.025528 +v 0.146940 -0.060925 -0.029297 +v 0.149695 0.102475 -0.072144 +v 0.155619 0.074522 -0.066442 +v 0.153063 0.003014 -0.069315 +v 0.138283 0.024194 -0.080952 +v 0.143471 0.103042 -0.077424 +v 0.133664 0.096344 -0.083930 +v 0.149467 0.099927 0.072570 +v 0.142611 0.102889 0.078080 +v 0.139510 0.022549 0.080141 +v 0.153230 0.002610 0.069106 +v 0.156773 0.067122 0.065120 +v 0.157644 0.027391 0.064061 +v 0.129000 0.036862 0.086323 +v 0.142076 0.113271 0.072830 +v 0.142581 0.107472 0.076985 +v 0.149966 0.105735 0.070064 +v 0.141863 0.113478 -0.072779 +v 0.142678 0.108610 -0.076324 +v 0.157301 0.003751 0.063073 +v 0.156060 0.110123 0.011648 +v 0.150953 0.108490 -0.065565 +v 0.156094 0.108551 -0.025774 +v 0.152185 -0.018188 0.061504 +v 0.148186 -0.042497 0.053338 +v 0.151765 -0.041011 0.049562 +v 0.158813 0.031446 -0.062184 +v 0.157299 0.003819 -0.063097 +v 0.148794 -0.058897 0.029021 +v 0.151470 -0.054984 0.027916 +v 0.151937 -0.018707 -0.061535 +v 0.151844 -0.040215 -0.050068 +v 0.150581 -0.058401 -0.002651 +v 0.012130 -0.045413 -0.072465 +v 0.013350 -0.041960 -0.071540 +v 0.011038 -0.043547 -0.071965 +v 0.011705 -0.050467 -0.073819 +v 0.012390 -0.049537 -0.073570 +v 0.009842 -0.047300 -0.072970 +v 0.011331 -0.047807 -0.073106 +v 0.012968 -0.047780 -0.073099 +v 0.009529 -0.043315 -0.071903 +v 0.010105 -0.045174 -0.072401 +v 0.015293 -0.049611 -0.073590 +v 0.014273 -0.037921 -0.070458 +v 0.017664 -0.037805 -0.070426 +v 0.019621 -0.052776 -0.074438 +v 0.022053 -0.050943 -0.073947 +v 0.023712 -0.038497 -0.070612 +v 0.027854 -0.039108 -0.070775 +v 0.020520 -0.035585 -0.070220 +v 0.026223 -0.040851 -0.071777 +v 0.026543 -0.046965 -0.072881 +v 0.029035 -0.045542 -0.072499 +v 0.026462 -0.050647 -0.073867 +v 0.011162 -0.045417 -0.073501 +v 0.011997 -0.043967 -0.073113 +v 0.012865 -0.044559 -0.073271 +v 0.009614 -0.042970 -0.072846 +v 0.010181 -0.044207 -0.073177 +v 0.009718 -0.046612 -0.073821 +v 0.011297 -0.047572 -0.074079 +v 0.013302 -0.046039 -0.073668 +v 0.012790 -0.047507 -0.074061 +v 0.011944 -0.041364 -0.072415 +v 0.016948 -0.050385 -0.074833 +v 0.012989 -0.048557 -0.074343 +v 0.011476 -0.050136 -0.074766 +v 0.011572 -0.048902 -0.074435 +v 0.014499 -0.050345 -0.074822 +v 0.015969 -0.036624 -0.071145 +v 0.020367 -0.052501 -0.075399 +v 0.015339 -0.038978 -0.071776 +v 0.020719 -0.037202 -0.071300 +v 0.025122 -0.036643 -0.071150 +v 0.027161 -0.044915 -0.073367 +v 0.029433 -0.043248 -0.072920 +v 0.023435 -0.050061 -0.074746 +v 0.026296 -0.050448 -0.074849 +v 0.011690 -0.045568 0.072506 +v 0.011034 -0.043546 0.071964 +v 0.013876 -0.040371 0.071114 +v 0.013258 -0.045826 0.073278 +v 0.010147 -0.045264 0.072425 +v 0.014531 -0.050388 0.074300 +v 0.011723 -0.050346 0.074304 +v 0.012622 -0.049177 0.073474 +v 0.009842 -0.047300 0.072970 +v 0.011112 -0.048294 0.073237 +v 0.013219 -0.047655 0.073066 +v 0.009529 -0.043315 0.071903 +v 0.018685 -0.052770 0.074436 +v 0.014980 -0.037346 0.070303 +v 0.020563 -0.037505 0.070346 +v 0.022908 -0.035803 0.069890 +v 0.026699 -0.041365 0.071380 +v 0.019975 -0.051299 0.074042 +v 0.028756 -0.041193 0.071334 +v 0.027600 -0.049809 0.073643 +v 0.025725 -0.048368 0.073257 +v 0.009614 -0.042970 0.072846 +v 0.009718 -0.046612 0.073821 +v 0.010274 -0.043970 0.073113 +v 0.011944 -0.041364 0.072415 +v 0.012209 -0.044123 0.073154 +v 0.011344 -0.045472 0.073516 +v 0.013302 -0.046039 0.073668 +v 0.012322 -0.047128 0.073960 +v 0.017312 -0.050615 0.074894 +v 0.012818 -0.048825 0.074414 +v 0.011015 -0.048444 0.074312 +v 0.015969 -0.036624 0.071145 +v 0.018982 -0.052561 0.075416 +v 0.018175 -0.037256 0.071315 +v 0.024829 -0.039059 0.071798 +v 0.027386 -0.038831 0.071737 +v 0.022142 -0.035435 0.070827 +v 0.027170 -0.045333 0.073479 +v 0.029324 -0.044153 0.073162 +v 0.026296 -0.050448 0.074849 +v 0.023383 -0.049984 0.074725 +v 0.032661 0.116806 0.098255 +v 0.039433 0.115885 0.099577 +v 0.039413 0.117024 0.098489 +v 0.032687 0.115636 0.099310 +v 0.057197 0.110746 0.090255 +v 0.059070 0.112829 0.092559 +v 0.055685 0.111659 0.092015 +v 0.056429 0.113569 0.093289 +v 0.057057 0.127903 0.079291 +v 0.059222 0.126995 0.079121 +v 0.057847 0.125153 0.077183 +v 0.055142 0.126055 0.077905 +v 0.011084 0.115410 0.100953 +v 0.010454 0.113777 0.100274 +v 0.011647 0.114975 0.099202 +v -0.000172 0.136841 0.084256 +v 0.010040 0.134806 0.080801 +v -0.000192 0.117127 0.102662 +v 0.011627 0.133608 0.081828 +v 0.013313 0.133483 0.081831 +v 0.013381 0.114887 0.099179 +v 0.031924 0.125699 0.076897 +v 0.032661 0.133636 0.082561 +v 0.039841 0.127119 0.075572 +v 0.038936 0.129537 0.075633 +v 0.013697 0.135188 0.081691 +v 0.031694 0.134407 0.080855 +v 0.039841 0.114292 0.095559 +v 0.031777 0.114747 0.095134 +v 0.039413 0.133854 0.082795 +v 0.031109 0.117069 0.098533 +v 0.013558 0.114882 0.101029 +v 0.031665 0.113852 0.099929 +v 0.018022 0.116896 0.098347 +v 0.018022 0.132569 0.083731 +v 0.031109 0.132396 0.083545 +v 0.031664 0.114718 0.099014 +v 0.031355 0.129136 0.081716 +v 0.039841 0.129970 0.080939 +v 0.032687 0.132466 0.083615 +v 0.039384 0.134329 0.082615 +v 0.033281 0.134951 0.082360 +v 0.039068 0.128707 0.076587 +v 0.039433 0.132716 0.083883 +v 0.039463 0.135195 0.081700 +v 0.031612 0.133388 0.081606 +v 0.013984 0.129336 0.075419 +v 0.014015 0.128379 0.076236 +v 0.011559 0.134692 0.082917 +v 0.013223 0.134450 0.083020 +v 0.010485 0.135765 0.081899 +v 0.000693 0.137722 0.085144 +v 0.004088 0.116027 0.102788 +v 0.000436 0.118549 0.103290 +v 0.013256 0.116013 0.100208 +v 0.033281 0.115382 0.100608 +v 0.039463 0.115606 0.099967 +v 0.039384 0.114741 0.100882 +v 0.039068 0.109119 0.094853 +v 0.038936 0.109948 0.093900 +v 0.014011 0.108793 0.094504 +v 0.013984 0.109748 0.093685 +v 0.024002 0.133778 0.085469 +v 0.023167 0.128281 0.079575 +v 0.023167 0.113049 0.093779 +v 0.024002 0.118545 0.099674 +v 0.046762 0.126444 0.078204 +v 0.046774 0.111817 0.091872 +v 0.047532 0.116904 0.097168 +v 0.048320 0.129476 0.085697 +v 0.048319 0.118942 0.095257 +v 0.047902 0.131461 0.083543 +v 0.047875 0.129153 0.085351 +v 0.047520 0.113899 0.089849 +v 0.047520 0.124301 0.080148 +v 0.059406 0.115021 0.091906 +v 0.057959 0.111769 0.088419 +v 0.052316 0.114283 0.091115 +v 0.059769 0.112080 0.091061 +v 0.057622 0.114666 0.093834 +v 0.056794 0.110711 0.089593 +v 0.052316 0.113132 0.092189 +v 0.042751 0.118033 0.096126 +v 0.042600 0.113991 0.092728 +v 0.020207 0.134324 0.087333 +v 0.018763 0.134367 0.087461 +v 0.018766 0.120343 0.100571 +v 0.020196 0.120224 0.100361 +v 0.017926 0.128607 0.080439 +v 0.018784 0.113680 0.094163 +v 0.056910 0.124355 0.076970 +v 0.052316 0.125610 0.080552 +v 0.042181 0.126883 0.080803 +v 0.052841 0.129397 0.082377 +v 0.059500 0.126058 0.081033 +v 0.059989 0.126359 0.079119 +v 0.043391 0.130020 0.085281 +v 0.042749 0.130944 0.084037 +v 0.057984 0.123074 0.077832 +v 0.029470 0.129923 0.080983 +v 0.016822 0.129968 0.080941 +v 0.016822 0.114294 0.095557 +v 0.029810 0.114861 0.095028 +v 0.037195 0.110868 0.097214 +v 0.037316 0.113146 0.099771 +v 0.036202 0.111207 0.098757 +v 0.034150 0.111121 0.097625 +v 0.034354 0.112951 0.099561 +v 0.030062 0.111705 0.098479 +v 0.028692 0.109163 0.096068 +v 0.030927 0.110252 0.096616 +v 0.061471 -0.091325 0.007558 +v 0.063411 -0.091139 0.002826 +v 0.063370 -0.091143 0.005208 +v 0.055899 -0.092213 -0.006350 +v 0.066376 -0.090854 0.002336 +v 0.060423 -0.091426 -0.006383 +v 0.055785 -0.092352 0.006350 +v 0.062166 -0.091259 -0.007837 +v 0.068613 -0.090639 -0.007250 +v 0.064483 -0.091036 -0.005879 +v 0.062954 -0.091183 -0.003490 +v 0.068666 -0.090634 0.007217 +v 0.065390 -0.090949 -0.002046 +v 0.066919 -0.090802 -0.004436 +v 0.066015 -0.090889 0.005607 +v 0.068489 -0.089120 -0.007272 +v 0.061270 -0.089814 -0.007514 +v 0.063392 -0.089610 -0.002475 +v 0.063621 -0.089588 0.002381 +v 0.061119 -0.089828 0.007389 +v 0.056001 -0.090461 -0.006350 +v 0.056252 -0.090428 0.006350 +v 0.068436 -0.089125 0.007302 +v 0.063447 -0.089604 0.005669 +v 0.066621 -0.089300 -0.002971 +v 0.063365 -0.089612 -0.005316 +v 0.066686 -0.089293 0.004595 +v 0.065708 -0.089387 -0.005666 +v 0.065837 -0.089375 0.002370 +v 0.055677 -0.095881 -0.006350 +v 0.056354 -0.098473 -0.006350 +v 0.053652 -0.093739 -0.006350 +v 0.055704 -0.095883 0.006350 +v 0.054988 -0.097333 0.006350 +v 0.057859 -0.097682 0.006350 +v 0.053621 -0.093395 0.006350 +v 0.039384 -0.102069 -0.014036 +v 0.033281 -0.102306 -0.013380 +v 0.031665 -0.100766 -0.014036 +v 0.038936 -0.093694 -0.012778 +v 0.013984 -0.093400 -0.012778 +v 0.013597 -0.100919 -0.013099 +v 0.039463 -0.101990 -0.012778 +v 0.031664 -0.100687 -0.012778 +v 0.014015 -0.093345 0.012748 +v 0.031240 -0.101033 0.012749 +v 0.013669 -0.100922 0.013387 +v 0.039068 -0.093826 0.012749 +v 0.029792 -0.092001 -0.009989 +v 0.016822 -0.092001 -0.010730 +v 0.029810 -0.092001 0.009925 +v 0.029947 -0.097869 -0.009803 +v 0.016822 -0.097869 -0.010730 +v 0.031960 -0.092001 -0.010455 +v 0.031720 -0.098070 -0.010575 +v 0.032687 -0.101530 -0.012308 +v 0.039841 -0.092001 -0.012308 +v 0.039433 -0.101895 -0.012308 +v 0.039068 -0.093826 -0.014036 +v 0.014011 -0.093348 -0.014036 +v 0.013451 -0.102443 -0.012838 +v 0.039413 -0.101876 0.012279 +v 0.032661 -0.101556 0.012279 +v 0.039433 -0.101895 0.010704 +v 0.032687 -0.101530 0.010704 +v 0.039413 -0.101876 -0.010734 +v 0.039841 -0.097869 -0.010734 +v 0.039841 -0.097869 0.010704 +v 0.039841 -0.092001 0.012279 +v 0.031626 -0.097869 0.009825 +v 0.031924 -0.092001 0.010337 +v 0.029536 -0.097869 0.010343 +v 0.016822 -0.097869 0.010701 +v 0.016822 -0.092001 0.010701 +v 0.038075 -0.098406 0.014452 +v 0.035388 -0.098238 0.015111 +v 0.035565 -0.100531 0.014505 +v 0.035867 -0.096394 0.014371 +v 0.033732 -0.098109 0.014330 +v 0.028507 -0.096761 0.015124 +v 0.030855 -0.097722 0.014516 +v 0.028503 -0.094320 0.014461 +v 0.027174 -0.097798 0.014330 +v 0.015212 -0.095860 0.014808 +v 0.017978 -0.098307 0.014544 +v 0.017473 -0.095188 0.014531 +v 0.014817 -0.098095 0.014531 +v 0.033765 -0.098807 -0.014461 +v 0.035577 -0.099972 -0.014991 +v 0.036380 -0.096324 -0.014585 +v 0.037822 -0.099152 -0.014502 +v 0.027207 -0.096712 -0.014842 +v 0.029368 -0.098664 -0.014658 +v 0.028235 -0.094598 -0.014443 +v 0.030651 -0.095413 -0.014602 +v 0.014757 -0.097087 0.013023 +v 0.016398 -0.098548 0.013024 +v 0.016653 -0.095168 0.013023 +v 0.018053 -0.097380 0.013024 +v 0.015237 -0.098517 -0.014577 +v 0.015749 -0.098517 -0.013007 +v 0.014846 -0.096579 -0.013006 +v 0.015084 -0.095870 -0.014841 +v 0.016667 -0.095246 -0.013006 +v 0.017631 -0.095294 -0.014577 +v 0.018105 -0.097554 -0.013006 +v 0.018046 -0.098103 -0.014577 +v 0.056943 -0.092100 0.010219 +v 0.055051 -0.094192 0.009818 +v 0.056971 -0.095708 0.009949 +v 0.055837 -0.095331 0.008143 +v 0.055578 -0.092620 0.008143 +v 0.057679 -0.091846 0.008143 +v 0.059303 -0.093700 0.009797 +v 0.058706 -0.095071 0.008143 +v 0.055684 -0.095105 -0.007795 +v 0.055089 -0.092850 -0.009737 +v 0.057448 -0.095987 -0.009773 +v 0.055392 -0.092771 -0.007795 +v 0.057719 -0.091995 -0.007795 +v 0.058704 -0.092376 -0.009814 +v 0.058969 -0.093836 -0.007795 +v 0.058167 -0.095557 -0.007796 +v 0.047902 -0.100791 0.010018 +v 0.047875 -0.100539 0.007097 +v 0.046439 -0.100671 0.009637 +v 0.048319 -0.100820 -0.007127 +v 0.047532 -0.100828 -0.009921 +v 0.046774 -0.093485 -0.010029 +v 0.044623 -0.094245 -0.009667 +v 0.046762 -0.093465 0.009990 +v 0.044623 -0.094245 0.009637 +v 0.042181 -0.095665 0.008539 +v 0.042749 -0.100800 0.009304 +v 0.056910 -0.091138 0.009304 +v 0.043390 -0.101079 0.007779 +v 0.018784 -0.096432 -0.010229 +v 0.020196 -0.105427 -0.009670 +v 0.018766 -0.105662 -0.009726 +v 0.017926 -0.096574 0.010047 +v 0.018763 -0.105639 0.009472 +v 0.020207 -0.105516 0.009528 +v 0.052316 -0.094614 0.007779 +v 0.057014 -0.090997 0.007779 +v 0.059655 -0.092961 0.009304 +v 0.059998 -0.094607 0.007779 +v 0.058308 -0.096502 0.009304 +v 0.052316 -0.094614 -0.007709 +v 0.052316 -0.094614 -0.009283 +v 0.042600 -0.095594 -0.009022 +v 0.043073 -0.101154 -0.009283 +v 0.043984 -0.101141 -0.007697 +v 0.058658 -0.095902 -0.009283 +v 0.059581 -0.095039 -0.007709 +v 0.059769 -0.093072 -0.009283 +v 0.057959 -0.090927 -0.007709 +v 0.056794 -0.091064 -0.009283 +v 0.047520 -0.093426 0.007097 +v 0.048320 -0.101013 0.007097 +v 0.047520 -0.093426 -0.007127 +v 0.023167 -0.095720 -0.010429 +v 0.023167 -0.095720 0.010399 +v 0.024002 -0.103780 0.010399 +v 0.024002 -0.103780 -0.010429 +v 0.011695 -0.100996 -0.012662 +v 0.011084 -0.102577 -0.013594 +v 0.004088 -0.104340 -0.014394 +v -0.000192 -0.104998 -0.013504 +v 0.010454 -0.100967 -0.014326 +v 0.000436 -0.106428 -0.012893 +v 0.000171 -0.106620 0.012001 +v -0.000172 -0.104982 0.013466 +v 0.002194 -0.105357 0.014171 +v 0.013651 -0.102447 0.014006 +v 0.013223 -0.102447 0.012561 +v 0.010744 -0.102571 0.013951 +v 0.010735 -0.100983 0.014241 +v 0.012313 -0.100953 0.012382 +v 0.013984 -0.093400 0.014005 +v 0.038936 -0.093694 0.014006 +v 0.031200 -0.101206 0.014006 +v 0.031109 -0.101430 0.010701 +v 0.032981 -0.101836 0.012749 +v 0.033169 -0.102067 0.014006 +v 0.039384 -0.102069 0.012749 +v 0.039463 -0.101990 0.014006 +v 0.031109 -0.101938 -0.010730 +v 0.018022 -0.101684 -0.010730 +v 0.018022 -0.101684 0.010701 +v 0.033957 -0.102107 -0.010734 +v 0.026942 0.111097 0.097764 +v 0.018317 0.111426 0.098141 +v 0.015237 0.111922 0.098654 +v 0.014996 0.110131 0.097139 +v 0.016923 0.109495 0.096051 +v 0.056531 -0.093810 -0.010331 +v 0.046439 0.131100 0.083715 +v 0.044623 0.112600 0.092181 +v 0.044623 0.126718 0.079015 +v 0.030121 0.111045 0.090561 +v 0.032140 0.109975 0.091559 +v 0.039841 0.109137 0.092341 +v 0.016822 0.110291 0.091265 +v 0.016822 0.125965 0.076648 +v 0.029810 0.125398 0.077178 +v 0.055676 0.114500 0.091474 +v 0.058246 0.126427 0.080893 +v 0.054987 0.125469 0.079867 +v 0.056331 0.124145 0.078447 +v 0.055570 0.112746 0.089593 +v 0.058630 0.112797 0.089648 +v 0.058817 0.124620 0.078956 +v 0.058244 0.114724 0.091714 +v 0.017079 0.132085 0.079806 +v 0.014846 0.111749 0.096165 +v 0.015749 0.113071 0.097583 +v 0.014721 0.131368 0.079036 +v 0.017635 0.130175 0.077758 +v 0.016667 0.110840 0.095190 +v 0.018105 0.112414 0.096878 +v 0.015781 0.129754 0.077306 +v 0.017978 0.133077 0.078640 +v 0.015389 0.133147 0.078328 +v 0.017473 0.130940 0.076367 +v 0.014716 0.131403 0.076864 +v 0.027131 0.132789 0.078320 +v 0.031059 0.132266 0.077982 +v 0.028879 0.130306 0.075804 +v 0.037118 0.134299 0.080030 +v 0.034450 0.134110 0.079963 +v 0.037380 0.132031 0.077653 +v 0.034095 0.132510 0.078024 +v 0.028983 0.132633 0.077314 +v 0.035983 0.133589 0.078394 +v 0.065162 0.118642 0.081414 +v 0.057277 0.112897 0.087644 +v 0.061824 0.111827 0.088098 +v 0.061967 0.122791 0.077860 +v 0.056799 0.122316 0.079122 +v 0.063356 0.120049 0.080281 +v 0.069123 0.111609 0.087582 +v 0.066611 0.112981 0.086551 +v 0.064427 0.115451 0.084463 +v 0.067587 0.119654 0.080232 +v 0.063665 0.113480 0.086376 +v 0.065385 0.121409 0.078812 +v 0.069176 0.122188 0.077713 +v 0.067077 0.115007 0.084615 +v 0.069035 0.110556 0.086484 +v 0.061802 0.110734 0.087031 +v 0.064236 0.117707 0.080288 +v 0.066772 0.114276 0.083238 +v 0.063121 0.113172 0.084627 +v 0.061650 0.121641 0.076875 +v 0.057172 0.111841 0.086511 +v 0.055639 0.121513 0.078262 +v 0.068982 0.121217 0.076548 +v 0.064453 0.120486 0.077675 +v 0.067370 0.118545 0.079198 +v 0.066280 0.111820 0.085577 +v 0.058087 0.116851 0.091884 +v 0.055071 0.116442 0.091446 +v 0.055570 0.114451 0.089311 +v 0.054268 0.113471 0.088259 +v 0.055703 0.124599 0.081571 +v 0.054299 0.125190 0.082204 +v 0.058204 0.126183 0.083269 +v 0.017465 0.133118 -0.079088 +v 0.014468 0.132427 -0.078329 +v 0.015925 0.131106 -0.076524 +v 0.018157 0.131240 -0.077074 +v 0.028081 0.132880 -0.079029 +v 0.026954 0.131005 -0.076939 +v 0.028950 0.132110 -0.077175 +v 0.029819 0.130314 -0.076279 +v 0.030946 0.132269 -0.078295 +v 0.036932 0.134179 -0.080465 +v 0.034354 0.133875 -0.080097 +v 0.036168 0.133622 -0.078782 +v 0.034150 0.132071 -0.078136 +v 0.037435 0.132019 -0.077903 +v 0.064498 0.115427 -0.084470 +v 0.055394 0.122555 -0.079803 +v 0.061174 0.122589 -0.078238 +v 0.061316 0.111609 -0.088458 +v 0.056166 0.112993 -0.088171 +v 0.062747 0.114055 -0.085985 +v 0.068456 0.121960 -0.077845 +v 0.065771 0.121186 -0.078929 +v 0.062724 0.119439 -0.080967 +v 0.066837 0.114090 -0.085401 +v 0.064896 0.112560 -0.087089 +v 0.068508 0.111375 -0.087708 +v 0.066020 0.118568 -0.081336 +v 0.068329 0.120940 -0.076720 +v 0.061962 0.121788 -0.076786 +v 0.063644 0.117490 -0.080567 +v 0.060174 0.120916 -0.077839 +v 0.065751 0.114147 -0.083401 +v 0.060960 0.110712 -0.087249 +v 0.062658 0.113586 -0.084341 +v 0.055174 0.121371 -0.078533 +v 0.054975 0.112212 -0.087333 +v 0.068275 0.110285 -0.086663 +v 0.064340 0.111540 -0.086022 +v 0.066823 0.118809 -0.078909 +v 0.063249 0.120002 -0.078277 +v 0.066373 0.112300 -0.085039 +v 0.053708 0.125108 -0.082540 +v 0.057102 0.125986 -0.083482 +v 0.055158 0.115295 -0.090640 +v 0.053776 0.115911 -0.091299 +v 0.057718 0.116834 -0.092289 +v 0.031411 0.129006 -0.081885 +v 0.031355 0.114945 -0.094998 +v 0.029512 0.129630 -0.081303 +v 0.016822 0.114113 -0.095773 +v 0.016822 0.129787 -0.081157 +v 0.039841 0.129789 -0.081155 +v 0.039841 0.114111 -0.095775 +v 0.029470 0.114158 -0.095731 +v 0.052316 0.114030 -0.091399 +v 0.056910 0.110544 -0.089897 +v 0.057984 0.111493 -0.088679 +v 0.059745 0.111925 -0.091378 +v 0.059331 0.114839 -0.092268 +v 0.057546 0.114545 -0.094187 +v 0.042798 0.117882 -0.096276 +v 0.042181 0.114191 -0.092686 +v 0.052316 0.125357 -0.080837 +v 0.052316 0.126508 -0.079763 +v 0.042600 0.126986 -0.080658 +v 0.017926 0.113708 -0.094380 +v 0.018784 0.128440 -0.080448 +v 0.018766 0.134367 -0.087541 +v 0.018763 0.120311 -0.100617 +v 0.020207 0.120186 -0.100565 +v 0.020196 0.134166 -0.087407 +v 0.051993 0.128259 -0.083949 +v 0.042713 0.130239 -0.084684 +v 0.052305 0.129308 -0.082765 +v 0.059775 0.126538 -0.079795 +v 0.059617 0.125524 -0.081016 +v 0.057959 0.122842 -0.078140 +v 0.057484 0.123982 -0.077053 +v 0.047520 0.113718 -0.090065 +v 0.048320 0.118892 -0.095614 +v 0.047520 0.124121 -0.080364 +v 0.048319 0.129164 -0.085772 +v 0.047875 0.118569 -0.095268 +v 0.046774 0.126284 -0.078429 +v 0.023167 0.128101 -0.079791 +v 0.023167 0.112868 -0.093995 +v 0.046762 0.111629 -0.092067 +v 0.024002 0.118365 -0.099890 +v 0.047902 0.116605 -0.097444 +v 0.047532 0.131212 -0.083873 +v 0.024002 0.133597 -0.085685 +v 0.013597 0.133599 -0.081772 +v 0.013984 0.128237 -0.076492 +v 0.014011 0.129120 -0.075596 +v 0.038936 0.128437 -0.076706 +v 0.039068 0.129446 -0.075945 +v 0.039463 0.134095 -0.082774 +v 0.039384 0.135068 -0.081974 +v 0.033281 0.134750 -0.082595 +v 0.031664 0.133206 -0.081821 +v 0.031665 0.134180 -0.081021 +v 0.013675 0.134809 -0.082730 +v 0.011858 0.134257 -0.083331 +v 0.011695 0.133332 -0.082125 +v 0.004088 0.136880 -0.083391 +v -0.000192 0.136677 -0.084479 +v 0.010454 0.134529 -0.080970 +v 0.010846 0.135537 -0.082273 +v 0.000436 0.137205 -0.085941 +v 0.000693 0.117766 -0.103801 +v -0.000172 0.116941 -0.102860 +v 0.013651 0.114817 -0.101374 +v 0.013223 0.115875 -0.100389 +v 0.011559 0.115755 -0.100624 +v 0.010485 0.114665 -0.101622 +v 0.010735 0.113648 -0.100464 +v 0.013669 0.114230 -0.099837 +v 0.012312 0.114986 -0.099175 +v 0.014015 0.109530 -0.093860 +v 0.013984 0.108649 -0.094758 +v 0.039068 0.109858 -0.094212 +v 0.038936 0.108848 -0.094973 +v 0.031612 0.114538 -0.099231 +v 0.031098 0.114083 -0.100587 +v 0.031109 0.116542 -0.098377 +v 0.032972 0.114390 -0.100916 +v 0.033240 0.115625 -0.100397 +v 0.039384 0.115480 -0.100241 +v 0.039463 0.114506 -0.101040 +v 0.031109 0.132562 -0.084133 +v 0.018022 0.132389 -0.083947 +v 0.018022 0.116715 -0.098563 +v 0.039433 0.116857 -0.098720 +v 0.032687 0.116607 -0.098452 +v 0.039413 0.115691 -0.099779 +v 0.039841 0.108957 -0.092557 +v 0.032661 0.115474 -0.099546 +v 0.032661 0.132304 -0.083851 +v 0.039413 0.132522 -0.084085 +v 0.032153 0.109871 -0.091704 +v 0.057140 0.111539 -0.092630 +v 0.059211 0.112247 -0.092393 +v 0.057004 0.110463 -0.090626 +v 0.056751 0.113442 -0.093675 +v 0.059181 0.126562 -0.079248 +v 0.056178 0.127607 -0.080316 +v 0.057199 0.126734 -0.078442 +v 0.057973 0.124923 -0.077518 +v 0.055414 0.125465 -0.077936 +v 0.032687 0.133437 -0.082758 +v 0.039433 0.133687 -0.083025 +v 0.029792 0.125243 -0.077370 +v 0.016822 0.125784 -0.076865 +v 0.030096 0.110884 -0.090760 +v 0.031960 0.125583 -0.077052 +v 0.039841 0.126938 -0.075788 +v 0.016822 0.110111 -0.091481 +v 0.036404 0.152743 0.004780 +v 0.039082 0.152509 0.006041 +v 0.037937 0.153072 0.003307 +v 0.035596 0.152293 0.006896 +v 0.037891 0.152001 0.008317 +v 0.034453 0.151958 0.008602 +v 0.032893 0.152495 0.005986 +v 0.034181 0.153086 0.003264 +v 0.035571 0.147530 0.006187 +v 0.036740 0.148071 0.003665 +v 0.037311 0.147807 0.005438 +v 0.034619 0.147921 0.004753 +v 0.036312 0.150622 0.007028 +v 0.037685 0.150983 0.005369 +v 0.035831 0.151283 0.003918 +v 0.035501 0.148519 0.003399 +v 0.034317 0.150871 0.005872 +v 0.039126 0.141383 0.058325 +v 0.037639 0.141852 0.056073 +v 0.036735 0.141476 0.057787 +v 0.035265 0.141106 0.059529 +v 0.037704 0.140729 0.061334 +v 0.034142 0.140782 0.061197 +v 0.034612 0.141908 0.055837 +v 0.032877 0.141370 0.058436 +v 0.036312 0.136297 0.059072 +v 0.035434 0.136978 0.056334 +v 0.037404 0.136858 0.057121 +v 0.034627 0.136549 0.057977 +v 0.035886 0.139385 0.059893 +v 0.037480 0.139600 0.058910 +v 0.036828 0.140024 0.056905 +v 0.034277 0.139789 0.057978 +v 0.006735 0.141106 0.059529 +v 0.003252 0.140962 0.060243 +v 0.006561 0.140665 0.061780 +v 0.006151 0.141983 0.055466 +v 0.003230 0.141611 0.057257 +v 0.005265 0.141476 0.057787 +v 0.009329 0.141306 0.058578 +v 0.006742 0.136325 0.058735 +v 0.004620 0.136513 0.058403 +v 0.005473 0.137000 0.056370 +v 0.007470 0.136823 0.057135 +v 0.005673 0.140061 0.056714 +v 0.004400 0.139651 0.058675 +v 0.006516 0.139380 0.059912 +v 0.007539 0.139815 0.057888 +v 0.024915 0.153649 0.007165 +v 0.025836 0.152613 0.004826 +v 0.025384 0.151555 0.009804 +v 0.025962 0.152869 0.010838 +v 0.029174 0.151212 0.011420 +v 0.031053 0.152826 0.011039 +v 0.032041 0.151760 0.008838 +v 0.031795 0.153825 0.006338 +v 0.031160 0.152549 0.005126 +v 0.027908 0.154244 0.004368 +v 0.027025 0.153967 0.005670 +v 0.026243 0.153172 0.009411 +v 0.030757 0.153737 0.006753 +v 0.029975 0.152942 0.010493 +v 0.026354 0.156453 0.007891 +v 0.027840 0.156429 0.006231 +v 0.029838 0.156507 0.006714 +v 0.030745 0.156137 0.007735 +v 0.030858 0.155272 0.009594 +v 0.029061 0.155694 0.010955 +v 0.027412 0.155721 0.010755 +v 0.026251 0.155914 0.009597 +v 0.030025 0.156898 0.009114 +v 0.028226 0.157400 0.007907 +v 0.028186 0.157063 0.009610 +v 0.010339 0.152981 0.010312 +v 0.009655 0.151793 0.008684 +v 0.013887 0.151203 0.011460 +v 0.015302 0.152749 0.011401 +v 0.016948 0.151705 0.009099 +v 0.017134 0.153409 0.008295 +v 0.016219 0.152552 0.005113 +v 0.015284 0.154189 0.004627 +v 0.011891 0.152691 0.004460 +v 0.010571 0.153940 0.005797 +v 0.010893 0.153535 0.007703 +v 0.012103 0.152990 0.010266 +v 0.015931 0.153136 0.009578 +v 0.013909 0.154048 0.005291 +v 0.011095 0.155890 0.009032 +v 0.011574 0.156296 0.007124 +v 0.013459 0.156423 0.006181 +v 0.015309 0.155823 0.006760 +v 0.015962 0.155975 0.008766 +v 0.014697 0.155362 0.010744 +v 0.012299 0.155335 0.010755 +v 0.014491 0.156927 0.009734 +v 0.012825 0.156668 0.010198 +v 0.014816 0.157087 0.007860 +v 0.012830 0.157385 0.007909 +v 0.021785 0.157113 0.009247 +v 0.020447 0.157311 0.007492 +v 0.019885 0.157110 0.009010 +v 0.007932 0.153226 0.001987 +v 0.034530 0.152993 0.002905 +v 0.037713 0.153142 0.002568 +v 0.033004 0.152214 0.006684 +v 0.008341 0.151933 0.007975 +v 0.002748 0.152854 0.004134 +v 0.002162 0.141565 0.056886 +v 0.003718 0.151872 0.008172 +v 0.036093 0.151704 0.009007 +v 0.040000 0.148389 0.024698 +v 0.039705 0.152567 0.005300 +v 0.034308 0.141738 0.055909 +v 0.038579 0.141560 0.056775 +v 0.008433 0.141608 0.056523 +v 0.033595 0.140373 0.062446 +v 0.007970 0.140598 0.061213 +v 0.039626 0.141046 0.059595 +v 0.017210 0.152011 0.007657 +v 0.020849 0.152823 0.003841 +v 0.024771 0.152071 0.007377 +v 0.023046 0.151345 0.010792 +v 0.004308 0.140550 0.061831 +v 0.019404 0.151283 0.011085 +v 0.037010 0.150895 0.012911 +v 0.036528 0.145435 0.038596 +v 0.005056 0.150908 0.012846 +v 0.005459 0.145435 0.038596 +v 0.036544 0.142629 0.051796 +v 0.005390 0.142643 0.051731 +v 0.017343 0.153286 0.008877 +v 0.019663 0.152809 0.011120 +v 0.023293 0.152799 0.011165 +v 0.024513 0.153726 0.006807 +v 0.022144 0.154112 0.004988 +v 0.018596 0.154052 0.005271 +v 0.018522 0.153642 0.007202 +v 0.019185 0.153058 0.009950 +v 0.022815 0.153852 0.006213 +v 0.023478 0.153268 0.008961 +v 0.018788 0.155982 0.007349 +v 0.020790 0.156468 0.006204 +v 0.022545 0.155984 0.006608 +v 0.023524 0.155730 0.008250 +v 0.023006 0.155875 0.009938 +v 0.020912 0.154962 0.011056 +v 0.018769 0.155250 0.009746 +v 0.021099 0.156281 0.010639 +v 0.019109 0.156353 0.009660 +v 0.022373 0.157031 0.007697 +v 0.036541 0.147391 0.039012 +v 0.036610 0.144599 0.052147 +v 0.005472 0.147391 0.039012 +v 0.005456 0.144586 0.052212 +v 0.033088 0.145094 0.049856 +v 0.033057 0.146838 0.041639 +v 0.009043 0.145087 0.049855 +v 0.009043 0.146833 0.041638 +v 0.009692 0.147214 0.050307 +v 0.009723 0.148989 0.042096 +v 0.030885 0.151638 0.042660 +v 0.030844 0.149903 0.050878 +v 0.020095 0.148734 0.042042 +v 0.022047 0.147477 0.050363 +v 0.036944 0.152865 0.013262 +v 0.004990 0.152851 0.013327 +v 0.033188 0.148189 0.035332 +v 0.033133 0.152198 0.016453 +v 0.009043 0.148174 0.035329 +v 0.009043 0.152187 0.016451 +v 0.009692 0.150301 0.035781 +v 0.009724 0.154338 0.016908 +v 0.030795 0.157003 0.017475 +v 0.030787 0.152982 0.036351 +v 0.021348 0.154468 0.016936 +v 0.023307 0.150736 0.035874 +v 0.005265 0.152333 0.006709 +v 0.002705 0.152634 0.005399 +v 0.005179 0.151867 0.008920 +v 0.005824 0.153201 0.002714 +v 0.006735 0.152703 0.004967 +v 0.008876 0.152815 0.004487 +v 0.008568 0.152166 0.007645 +v 0.005497 0.147536 0.006250 +v 0.004690 0.148025 0.004351 +v 0.006271 0.148270 0.003404 +v 0.007414 0.147792 0.005056 +v 0.006742 0.151250 0.004092 +v 0.004712 0.151155 0.004539 +v 0.004825 0.150711 0.006609 +v 0.007414 0.150734 0.006516 +v 0.038939 0.139019 0.061144 +v 0.036294 0.140465 0.062289 +v 0.021000 0.138792 0.062216 +v 0.004844 0.138842 0.061977 +v 0.039859 0.150988 0.004837 +v 0.040000 0.145841 0.029051 +v 0.015006 0.151682 0.001571 +v 0.036849 0.151645 0.001747 +v 0.003796 0.151532 0.002279 +v 0.006068 0.153248 0.002259 +v 0.002141 0.139532 0.058731 +v 0.002291 0.141106 0.059212 +v 0.002000 0.145841 0.029051 +v 0.002014 0.150761 0.005906 +v 0.007196 0.151210 0.004303 +v 0.005258 0.151269 0.003881 +v 0.004311 0.150811 0.006083 +v 0.005996 0.150584 0.007203 +v 0.007676 0.150804 0.006118 +v 0.036808 0.151255 0.003938 +v 0.034272 0.151093 0.004783 +v 0.035730 0.150540 0.007317 +v 0.037746 0.150875 0.005754 +v 0.035506 0.139352 0.060041 +v 0.037414 0.139509 0.059267 +v 0.034344 0.139906 0.057348 +v 0.037441 0.139953 0.057177 +v 0.005120 0.139401 0.059841 +v 0.007040 0.139445 0.059671 +v 0.004269 0.139809 0.057848 +v 0.006064 0.140080 0.056534 +v 0.007731 0.139784 0.057977 +v 0.034289 0.141894 -0.038076 +v 0.034377 0.147275 -0.039484 +v 0.032342 0.141427 -0.040273 +v 0.031940 0.146879 -0.041346 +v 0.030924 0.142025 -0.037460 +v 0.031127 0.147500 -0.038427 +v 0.032089 0.147907 -0.036095 +v 0.035687 0.147568 -0.037845 +v 0.035229 0.146701 -0.042042 +v 0.029109 0.147368 -0.038878 +v 0.031043 0.146447 -0.043005 +v 0.029987 0.147457 -0.036483 +v 0.028212 0.146485 -0.038361 +v 0.029892 0.146240 -0.035711 +v 0.028469 0.146261 -0.040977 +v 0.029511 0.145787 -0.042553 +v 0.034293 0.147180 -0.035619 +v 0.031957 0.146374 -0.034934 +v 0.031468 0.144615 -0.043672 +v 0.033545 0.145534 -0.043604 +v 0.035782 0.145599 -0.042420 +v 0.036892 0.146270 -0.039538 +v 0.036501 0.145997 -0.037224 +v 0.034679 0.146099 -0.035472 +v 0.027973 0.144983 -0.040721 +v 0.036063 0.144665 -0.042216 +v 0.030217 0.145572 -0.037953 +v 0.030810 0.144912 -0.041055 +v 0.034541 0.144892 -0.041153 +v 0.033819 0.145749 -0.037120 +v 0.034685 0.144083 -0.037323 +v 0.033451 0.143220 -0.041382 +v 0.030095 0.143544 -0.039856 +v 0.030981 0.144150 -0.037005 +v 0.031269 0.142484 -0.035432 +v 0.028964 0.142057 -0.037614 +v 0.035484 0.142390 -0.036256 +v 0.036181 0.141798 -0.038821 +v 0.031533 0.141109 -0.041821 +v 0.036165 0.144163 -0.036387 +v 0.034683 0.143569 -0.035028 +v 0.036918 0.142898 -0.038730 +v 0.036842 0.143282 -0.040310 +v 0.035014 0.141447 -0.041544 +v 0.035110 0.142841 -0.042513 +v 0.033189 0.141725 -0.042868 +v 0.030351 0.141797 -0.042434 +v 0.033004 0.142803 -0.043315 +v 0.028435 0.142130 -0.040052 +v 0.028110 0.143752 -0.037745 +v 0.029698 0.144475 -0.035468 +v 0.030329 0.143343 -0.035003 +v 0.032694 0.143389 -0.034516 +v 0.029462 0.143028 -0.042285 +v 0.033393 0.144645 -0.034676 +v 0.019654 0.143594 -0.055141 +v 0.021656 0.143203 -0.056346 +v 0.021317 0.143021 -0.057616 +v 0.019771 0.136151 -0.053684 +v 0.018262 0.135848 -0.055235 +v 0.019525 0.135462 -0.056814 +v 0.021323 0.135793 -0.055465 +v 0.018452 0.141832 -0.055548 +v 0.021382 0.141801 -0.055692 +v 0.019280 0.141269 -0.058194 +v 0.016840 0.141955 -0.056068 +v 0.017943 0.142219 -0.054223 +v 0.017012 0.141919 -0.057576 +v 0.019289 0.141151 -0.059553 +v 0.020336 0.142412 -0.053639 +v 0.022264 0.141470 -0.058223 +v 0.022494 0.142229 -0.055235 +v 0.018008 0.143057 -0.055312 +v 0.018243 0.143283 -0.056693 +v 0.019004 0.142882 -0.058365 +v 0.020379 0.142749 -0.058592 +v 0.010924 0.141089 -0.030328 +v 0.011128 0.140515 -0.033299 +v 0.012328 0.140847 -0.031677 +v 0.009117 0.140777 -0.031865 +v 0.009485 0.146380 -0.034151 +v 0.009768 0.146874 -0.031827 +v 0.012041 0.146847 -0.031955 +v 0.011879 0.146375 -0.034175 +v 0.013630 0.146580 -0.033903 +v 0.008164 0.147170 -0.031582 +v 0.007945 0.146491 -0.034078 +v 0.010576 0.146429 -0.036017 +v 0.010088 0.147394 -0.030267 +v 0.012421 0.146366 -0.035541 +v 0.013631 0.147090 -0.032283 +v 0.012132 0.147313 -0.030477 +v 0.008834 0.146914 -0.035079 +v 0.011589 0.148223 -0.031156 +v 0.012233 0.148365 -0.032661 +v 0.012133 0.148072 -0.034351 +v 0.009889 0.148587 -0.031984 +v 0.009073 0.148189 -0.033469 +v 0.010039 0.147937 -0.034686 +v 0.023039 0.141263 -0.029435 +v 0.020616 0.141414 -0.028965 +v 0.020383 0.141002 -0.030985 +v 0.022333 0.140877 -0.031605 +v 0.020097 0.147082 -0.030849 +v 0.022014 0.147288 -0.029881 +v 0.023304 0.146898 -0.031715 +v 0.021145 0.146636 -0.032945 +v 0.019122 0.146761 -0.033082 +v 0.018889 0.147543 -0.030248 +v 0.021970 0.146638 -0.034361 +v 0.021366 0.147844 -0.028491 +v 0.023767 0.147028 -0.033466 +v 0.024614 0.147096 -0.031774 +v 0.024058 0.147517 -0.029647 +v 0.020175 0.147180 -0.033802 +v 0.022563 0.148821 -0.030189 +v 0.023306 0.148612 -0.031681 +v 0.020399 0.148835 -0.030674 +v 0.019989 0.148448 -0.032203 +v 0.021550 0.148256 -0.033305 +v 0.012514 0.146471 -0.005073 +v 0.011154 0.146068 -0.007125 +v 0.012778 0.145804 -0.008160 +v 0.014197 0.146121 -0.006877 +v 0.011154 0.152086 -0.007306 +v 0.013372 0.152270 -0.006440 +v 0.014048 0.151770 -0.008793 +v 0.011838 0.151661 -0.009306 +v 0.015535 0.152455 -0.007125 +v 0.009642 0.152084 -0.008148 +v 0.010736 0.151628 -0.010305 +v 0.013750 0.151525 -0.010701 +v 0.011194 0.152743 -0.005440 +v 0.015239 0.151788 -0.009349 +v 0.013527 0.152780 -0.005088 +v 0.010233 0.152836 -0.006713 +v 0.014136 0.153687 -0.007780 +v 0.013232 0.153826 -0.006491 +v 0.011118 0.153781 -0.007513 +v 0.011474 0.153292 -0.009437 +v 0.012565 0.153077 -0.010070 +v 0.014226 0.153302 -0.009237 +v 0.036200 0.141973 -0.055536 +v 0.039170 0.141446 -0.057941 +v 0.036735 0.141476 -0.057787 +v 0.033320 0.141653 -0.057053 +v 0.037161 0.140658 -0.061690 +v 0.035265 0.141106 -0.059529 +v 0.033268 0.140964 -0.060324 +v 0.035887 0.136817 -0.056262 +v 0.034769 0.136465 -0.058686 +v 0.036898 0.136393 -0.058708 +v 0.037571 0.139868 -0.057613 +v 0.037374 0.137152 -0.056876 +v 0.036309 0.139381 -0.059931 +v 0.034468 0.139625 -0.058782 +v 0.035162 0.140011 -0.056964 +v 0.036404 0.152743 -0.004780 +v 0.038901 0.152779 -0.004718 +v 0.038402 0.152067 -0.007986 +v 0.035596 0.152293 -0.006896 +v 0.036352 0.153202 -0.002696 +v 0.033308 0.152877 -0.004253 +v 0.033062 0.152333 -0.006803 +v 0.034893 0.151932 -0.008736 +v 0.034622 0.147854 -0.004639 +v 0.036723 0.147536 -0.006018 +v 0.036241 0.148106 -0.003467 +v 0.036338 0.151292 -0.003869 +v 0.037434 0.148349 -0.004256 +v 0.037576 0.150868 -0.005885 +v 0.035513 0.150606 -0.007101 +v 0.035542 0.147870 -0.006452 +v 0.034451 0.151032 -0.005126 +v 0.005596 0.152743 -0.004780 +v 0.003426 0.152938 -0.004005 +v 0.005846 0.153161 -0.002824 +v 0.006404 0.152293 -0.006896 +v 0.003308 0.152161 -0.007595 +v 0.008541 0.152142 -0.007709 +v 0.006112 0.151889 -0.008865 +v 0.008725 0.152928 -0.004081 +v 0.007498 0.147807 -0.004921 +v 0.005424 0.148157 -0.003438 +v 0.005142 0.147601 -0.006124 +v 0.005905 0.150608 -0.007131 +v 0.004341 0.150998 -0.005257 +v 0.006589 0.151278 -0.003940 +v 0.007525 0.150860 -0.005921 +v 0.006735 0.141106 -0.059529 +v 0.006492 0.140620 -0.061859 +v 0.002975 0.141090 -0.059732 +v 0.009071 0.141171 -0.059275 +v 0.005265 0.141476 -0.057787 +v 0.004297 0.141892 -0.055888 +v 0.008184 0.141788 -0.056412 +v 0.006462 0.136863 -0.056359 +v 0.004572 0.136606 -0.057495 +v 0.006760 0.136334 -0.058714 +v 0.007692 0.139586 -0.058898 +v 0.005103 0.136698 -0.059047 +v 0.005184 0.139436 -0.059673 +v 0.004439 0.139797 -0.057974 +v 0.006032 0.140067 -0.056722 +v 0.007588 0.137057 -0.057273 +v 0.037289 0.144646 -0.000446 +v 0.036159 0.153230 -0.002020 +v 0.006142 0.144720 -0.000101 +v 0.005039 0.153208 -0.002251 +v 0.039658 0.132398 -0.058068 +v 0.039605 0.141080 -0.059445 +v 0.039979 0.143931 -0.003811 +v 0.039911 0.141548 -0.056965 +v 0.039563 0.152690 -0.004705 +v 0.037396 0.140522 -0.061968 +v 0.036224 0.131838 -0.060704 +v 0.005731 0.140450 -0.062395 +v 0.004535 0.131880 -0.060507 +v 0.002224 0.144167 -0.002701 +v 0.002438 0.152684 -0.004866 +v 0.002163 0.141078 -0.059324 +v 0.002011 0.132686 -0.056716 +v 0.005288 0.139341 -0.060041 +v 0.004688 0.139974 -0.056954 +v 0.006998 0.141812 -0.055417 +v 0.007277 0.139934 -0.057162 +v 0.007633 0.139545 -0.059081 +v 0.008996 0.140987 -0.059504 +v 0.037892 0.139693 -0.058310 +v 0.036020 0.139332 -0.060042 +v 0.033392 0.140814 -0.060317 +v 0.034297 0.139603 -0.058819 +v 0.033553 0.141613 -0.056502 +v 0.035450 0.140071 -0.056556 +v 0.037816 0.150915 -0.005501 +v 0.036547 0.151709 -0.008985 +v 0.036498 0.150583 -0.007110 +v 0.034707 0.150678 -0.006684 +v 0.032863 0.152227 -0.006598 +v 0.034534 0.151131 -0.004501 +v 0.036447 0.151280 -0.003865 +v 0.004652 0.150683 -0.006676 +v 0.004140 0.151847 -0.008381 +v 0.004439 0.151051 -0.004807 +v 0.006462 0.151305 -0.003704 +v 0.007567 0.150679 -0.006593 +v 0.009231 0.152073 -0.007038 +v 0.008276 0.145819 -0.036788 +v 0.008205 0.137805 -0.035176 +v 0.008204 0.142432 -0.052726 +v 0.008204 0.134437 -0.051023 +v 0.022354 0.134436 -0.051029 +v 0.022314 0.142427 -0.052747 +v 0.022306 0.137813 -0.035138 +v 0.022280 0.145821 -0.036781 +v 0.024775 0.149652 -0.011120 +v 0.026049 0.151182 -0.011557 +v 0.025370 0.149652 -0.011120 +v 0.019113 0.149652 -0.011120 +v 0.008255 0.151183 -0.011555 +v 0.016213 0.149652 -0.011120 +v 0.010113 0.149652 -0.011120 +v 0.008257 0.149602 -0.011360 +v 0.008202 0.147740 -0.027753 +v 0.008279 0.146203 -0.027346 +v 0.025994 0.146195 -0.027386 +v 0.026095 0.147738 -0.027763 +v 0.026072 0.149591 -0.011408 +v 0.011605 0.138820 -0.042289 +v 0.012231 0.139621 -0.042520 +v 0.013094 0.140051 -0.042560 +v 0.012752 0.139265 -0.044437 +v 0.013132 0.140022 -0.044665 +v 0.013247 0.140192 -0.044266 +v 0.013199 0.139121 -0.047543 +v 0.013117 0.139205 -0.047143 +v 0.011620 0.137822 -0.047002 +v 0.014103 0.143331 -0.050305 +v 0.016038 0.143751 -0.050169 +v 0.014020 0.145835 -0.050772 +v 0.014020 0.145507 -0.050889 +v 0.012990 0.145201 -0.041564 +v 0.011666 0.146803 -0.041909 +v 0.012755 0.145664 -0.041273 +v 0.012900 0.140364 -0.040134 +v 0.012928 0.140315 -0.040554 +v 0.013617 0.142909 -0.040701 +v 0.013554 0.142597 -0.041029 +v 0.011688 0.146671 -0.042485 +v 0.011541 0.139206 -0.040333 +v 0.011605 0.139243 -0.040299 +v 0.013110 0.140447 -0.041177 +v 0.012934 0.140099 -0.041536 +v 0.013495 0.141815 -0.041886 +v 0.013401 0.144053 -0.041951 +v 0.013460 0.143176 -0.042198 +v 0.013007 0.144920 -0.042554 +v 0.011593 0.146724 -0.042900 +v 0.011649 0.146485 -0.043469 +v 0.012026 0.139670 -0.041470 +v 0.011566 0.138985 -0.041279 +v 0.011645 0.146468 -0.043881 +v 0.013068 0.144603 -0.043533 +v 0.012903 0.139946 -0.042117 +v 0.013527 0.141965 -0.042552 +v 0.013542 0.142519 -0.043073 +v 0.013150 0.144421 -0.043075 +v 0.011745 0.146260 -0.044487 +v 0.013105 0.140027 -0.043161 +v 0.012913 0.139655 -0.043521 +v 0.013625 0.142603 -0.044129 +v 0.013425 0.143450 -0.043901 +v 0.011766 0.146135 -0.044902 +v 0.012599 0.139517 -0.043537 +v 0.013626 0.142377 -0.045121 +v 0.013490 0.143129 -0.044836 +v 0.011807 0.145966 -0.045801 +v 0.012567 0.144850 -0.045688 +v 0.011590 0.145539 -0.045834 +v 0.011604 0.138421 -0.044296 +v 0.011653 0.138518 -0.044878 +v 0.012883 0.139301 -0.045097 +v 0.012928 0.139282 -0.045536 +v 0.013515 0.141256 -0.045513 +v 0.013496 0.140970 -0.045861 +v 0.013371 0.143368 -0.045962 +v 0.013385 0.143002 -0.046316 +v 0.011803 0.145726 -0.046863 +v 0.011590 0.145328 -0.046827 +v 0.012943 0.139186 -0.046097 +v 0.012939 0.139043 -0.046508 +v 0.013595 0.142371 -0.046790 +v 0.013557 0.141281 -0.046982 +v 0.013016 0.143855 -0.047518 +v 0.012482 0.144737 -0.047301 +v 0.011621 0.145430 -0.048438 +v 0.011670 0.145538 -0.047867 +v 0.012210 0.138765 -0.046471 +v 0.011604 0.137989 -0.046277 +v 0.011624 0.145446 -0.048854 +v 0.012980 0.143743 -0.048529 +v 0.013482 0.142230 -0.047806 +v 0.013496 0.141644 -0.048109 +v 0.011646 0.145082 -0.048852 +v 0.011657 0.137872 -0.047318 +v 0.011562 0.146189 -0.045537 +v 0.011702 0.138617 -0.043890 +v 0.011600 0.145870 -0.047646 +v 0.011608 0.138100 -0.045883 +v 0.011608 0.139149 -0.040917 +v 0.011594 0.145943 -0.046534 +v 0.012740 0.144097 -0.048192 +v 0.011558 0.137689 -0.046888 +v 0.011605 0.138555 -0.043179 +v 0.012830 0.140753 -0.040161 +v 0.011555 0.147056 -0.041580 +v 0.011610 0.139370 -0.039920 +v 0.011688 0.139034 -0.041916 +v 0.017406 0.139064 -0.040492 +v 0.017497 0.142716 -0.041301 +v 0.018323 0.149495 -0.042657 +v 0.017465 0.141420 -0.047396 +v 0.017383 0.137753 -0.046660 +v 0.018417 0.148193 -0.048869 +v 0.011775 0.147301 -0.044934 +v 0.011552 0.137804 -0.045073 +v 0.011619 0.138244 -0.045306 +v 0.011557 0.138385 -0.042910 +v 0.020546 0.151623 -0.043176 +v 0.018889 0.151676 -0.042644 +v 0.021539 0.152544 -0.039129 +v 0.018730 0.152283 -0.039903 +v 0.020549 0.150322 -0.049400 +v 0.021526 0.149514 -0.053381 +v 0.018863 0.150149 -0.049830 +v 0.018734 0.149608 -0.052528 +v 0.021048 0.149366 -0.042687 +v 0.021693 0.139069 -0.040468 +v 0.016385 0.139664 -0.037668 +v 0.016020 0.136436 -0.049250 +v 0.015655 0.138197 -0.037357 +v 0.017532 0.140828 -0.050184 +v 0.021272 0.148028 -0.048677 +v 0.021686 0.137753 -0.046661 +v 0.011576 0.147209 -0.051540 +v 0.011590 0.135702 -0.049094 +v 0.011590 0.147920 -0.048122 +v 0.011590 0.148344 -0.046143 +v 0.011590 0.136944 -0.043253 +v 0.011594 0.149686 -0.039801 +v 0.011590 0.138197 -0.037357 +v 0.017740 0.143323 -0.038446 +v 0.011288 0.149691 -0.052189 +v 0.021725 0.150365 -0.047635 +v 0.021725 0.149938 -0.044198 +v 0.014000 0.146016 -0.039663 +v 0.011332 0.152222 -0.040262 +v 0.016038 0.145974 -0.039692 +v 0.008522 0.152429 -0.038803 +v 0.008548 0.149236 -0.053741 +v 0.022050 0.152161 -0.038547 +v 0.022079 0.148972 -0.053669 +v 0.008554 0.138003 -0.035483 +v 0.022019 0.134745 -0.050812 +v 0.022035 0.137998 -0.035505 +v 0.008515 0.134753 -0.050770 +v 0.018492 0.153657 -0.013784 +v 0.015646 0.150841 -0.026499 +v 0.015647 0.153504 -0.013986 +v 0.018648 0.150845 -0.026500 +v 0.013398 0.148757 -0.015423 +v 0.012722 0.144079 -0.013639 +v 0.013649 0.148468 -0.016384 +v 0.012824 0.145884 -0.016985 +v 0.013500 0.148310 -0.017884 +v 0.013521 0.147903 -0.018820 +v 0.012824 0.145442 -0.019063 +v 0.013509 0.147727 -0.019805 +v 0.013649 0.147533 -0.020786 +v 0.012824 0.144948 -0.021386 +v 0.013509 0.147207 -0.022250 +v 0.013649 0.147013 -0.023231 +v 0.012790 0.141952 -0.023518 +v 0.012792 0.151937 -0.014535 +v 0.012801 0.149444 -0.024842 +v 0.011194 0.151999 -0.014735 +v 0.011203 0.149745 -0.025219 +v 0.018721 0.153268 -0.014009 +v 0.022009 0.147207 -0.022250 +v 0.021324 0.144948 -0.021386 +v 0.022149 0.147013 -0.023231 +v 0.021300 0.141923 -0.023512 +v 0.021930 0.147803 -0.019821 +v 0.021324 0.145442 -0.019063 +v 0.022149 0.147533 -0.020786 +v 0.021898 0.148237 -0.017868 +v 0.021324 0.145884 -0.016985 +v 0.022019 0.148075 -0.018856 +v 0.022000 0.148830 -0.015439 +v 0.021344 0.144141 -0.013450 +v 0.022021 0.148423 -0.016374 +v 0.021267 0.151960 -0.014549 +v 0.021287 0.149435 -0.024843 +v 0.019670 0.151994 -0.014745 +v 0.019665 0.149766 -0.025201 +v 0.010979 0.149340 -0.015523 +v 0.010392 0.147942 -0.017384 +v 0.010786 0.149121 -0.017529 +v 0.015530 0.149650 -0.026122 +v 0.015531 0.152261 -0.013846 +v 0.014927 0.149302 -0.015605 +v 0.014720 0.148988 -0.017433 +v 0.015375 0.148329 -0.017356 +v 0.015341 0.147089 -0.021154 +v 0.014874 0.147675 -0.023314 +v 0.015362 0.147061 -0.023275 +v 0.014918 0.148764 -0.021717 +v 0.015149 0.148335 -0.021583 +v 0.015491 0.147460 -0.021309 +v 0.015483 0.148822 -0.023447 +v 0.015475 0.150071 -0.017559 +v 0.015498 0.150398 -0.015948 +v 0.015080 0.149122 -0.017448 +v 0.015491 0.148711 -0.015421 +v 0.012824 0.147657 -0.022346 +v 0.013288 0.147033 -0.023235 +v 0.012824 0.145198 -0.022845 +v 0.012824 0.148158 -0.020919 +v 0.012824 0.148328 -0.019421 +v 0.013288 0.147553 -0.020790 +v 0.012824 0.145718 -0.020400 +v 0.013390 0.148071 -0.017833 +v 0.012824 0.148796 -0.017220 +v 0.012824 0.146134 -0.018444 +v 0.013288 0.148488 -0.016388 +v 0.012824 0.146654 -0.015998 +v 0.011147 0.144140 -0.012977 +v 0.012824 0.148261 -0.013738 +v 0.011138 0.141882 -0.023598 +v 0.023351 0.147666 -0.023398 +v 0.023937 0.147146 -0.021135 +v 0.023544 0.148281 -0.021482 +v 0.018823 0.152371 -0.013826 +v 0.018826 0.149742 -0.026187 +v 0.019331 0.148249 -0.021556 +v 0.019275 0.148471 -0.023406 +v 0.019123 0.147034 -0.023262 +v 0.018919 0.147464 -0.021310 +v 0.019331 0.149501 -0.015668 +v 0.019435 0.148759 -0.017406 +v 0.018924 0.148306 -0.017354 +v 0.019145 0.148752 -0.015433 +v 0.018913 0.150393 -0.015947 +v 0.019493 0.149885 -0.015788 +v 0.018998 0.150152 -0.017568 +v 0.021442 0.149705 -0.016647 +v 0.021890 0.148591 -0.015388 +v 0.021324 0.149232 -0.014471 +v 0.021324 0.146654 -0.015998 +v 0.021883 0.147884 -0.018816 +v 0.021577 0.147753 -0.020696 +v 0.021324 0.146134 -0.018444 +v 0.021324 0.147860 -0.021622 +v 0.021324 0.145718 -0.020400 +v 0.021788 0.147033 -0.023235 +v 0.021324 0.145198 -0.022845 +v 0.019612 0.144136 -0.012995 +v 0.019622 0.141882 -0.023601 +v 0.018948 0.149194 -0.021852 +v 0.019528 0.147921 -0.021453 +v 0.010364 0.148371 -0.015227 +v 0.010745 0.147637 -0.023395 +v 0.010987 0.148105 -0.021428 +v 0.010354 0.147088 -0.021117 +v 0.010260 0.150018 -0.017639 +v 0.010343 0.150439 -0.015859 +v 0.010325 0.148811 -0.023538 +v 0.010268 0.149159 -0.021751 +v 0.015504 0.149831 -0.017531 +v 0.012824 0.146115 -0.023835 +v 0.021999 0.144770 -0.024945 +v 0.020723 0.144664 -0.024873 +v 0.020851 0.143353 -0.024036 +v 0.021875 0.143467 -0.024229 +v 0.020824 0.143596 -0.024388 +v 0.023965 0.146663 -0.023274 +v 0.024071 0.149145 -0.021746 +v 0.024006 0.148811 -0.023538 +v 0.023585 0.149313 -0.015514 +v 0.023343 0.148939 -0.017506 +v 0.023986 0.147856 -0.017373 +v 0.024006 0.150443 -0.015861 +v 0.024062 0.150033 -0.017641 +v 0.018908 0.144906 -0.016959 +v 0.018908 0.149831 -0.017531 +v 0.018909 0.144133 -0.020271 +v 0.018908 0.148579 -0.023419 +v 0.023997 0.144296 -0.012240 +v 0.023072 0.145994 -0.012770 +v 0.023920 0.141715 -0.024384 +v 0.023059 0.143489 -0.024558 +v 0.021324 0.146115 -0.023835 +v 0.010265 0.148343 -0.017433 +v 0.010658 0.149385 -0.015537 +v 0.010265 0.150173 -0.015778 +v 0.010658 0.148132 -0.021436 +v 0.010265 0.147091 -0.023327 +v 0.010265 0.148531 -0.023504 +v 0.015504 0.144308 -0.012184 +v 0.015504 0.141710 -0.024407 +v 0.010308 0.141724 -0.024342 +v 0.010309 0.144294 -0.012250 +v 0.010706 0.149259 -0.026105 +v 0.010219 0.149507 -0.025445 +v 0.024065 0.147531 -0.021253 +v 0.023673 0.147713 -0.023403 +v 0.024065 0.148531 -0.023504 +v 0.024065 0.150173 -0.015778 +v 0.024065 0.148785 -0.015354 +v 0.023673 0.148966 -0.017510 +v 0.018908 0.144308 -0.012184 +v 0.018908 0.141710 -0.024407 +v 0.023506 0.151939 -0.013719 +v 0.024115 0.151798 -0.014325 +v 0.013275 0.146082 -0.013065 +v 0.012183 0.146090 -0.013049 +v 0.010218 0.151766 -0.013998 +v 0.011002 0.152174 -0.013799 +v 0.013275 0.143685 -0.024315 +v 0.012183 0.143693 -0.024350 +v 0.024086 0.149237 -0.025786 +v 0.023304 0.149643 -0.026167 +v 0.024074 0.150785 -0.019935 +v 0.021897 0.146104 -0.013036 +v 0.020818 0.146067 -0.013070 +v 0.010152 0.153496 -0.013985 +v 0.010153 0.150835 -0.026499 +v 0.024148 0.150836 -0.026498 +v 0.024146 0.153495 -0.013985 +v 0.025776 0.150479 -0.028004 +v 0.008534 0.150485 -0.028008 +v 0.025788 0.153786 -0.012477 +v 0.008522 0.153776 -0.012466 +v 0.025898 0.144388 -0.010434 +v 0.008423 0.144393 -0.010413 +v 0.008402 0.141071 -0.026039 +v 0.025877 0.141067 -0.026060 +v 0.008344 0.139902 -0.025926 +v 0.008316 0.143268 -0.010089 +v 0.025984 0.139908 -0.025898 +v 0.025956 0.143274 -0.010061 +v 0.030140 0.159355 -0.020305 +v 0.029487 0.160160 -0.016515 +v 0.033093 0.160594 -0.014474 +v 0.035889 0.159834 -0.018049 +v 0.033821 0.159254 -0.020777 +v 0.035010 0.149258 -0.012973 +v 0.032103 0.149491 -0.011879 +v 0.029188 0.149005 -0.014166 +v 0.029902 0.148219 -0.017864 +v 0.032770 0.147969 -0.019040 +v 0.035867 0.148493 -0.016574 +v 0.035409 0.144614 -0.018468 +v 0.028500 0.144920 -0.017031 +v 0.036500 0.145880 -0.012513 +v 0.029591 0.146186 -0.011075 +v 0.035574 0.157034 -0.031225 +v 0.031460 0.156720 -0.032700 +v 0.029030 0.157479 -0.029131 +v 0.033627 0.158097 -0.026220 +v 0.033034 0.146955 -0.023810 +v 0.029750 0.146661 -0.025194 +v 0.029317 0.145960 -0.028491 +v 0.031926 0.145514 -0.030591 +v 0.035314 0.145819 -0.029155 +v 0.035448 0.146641 -0.025286 +v 0.030682 0.141989 -0.030822 +v 0.037227 0.143036 -0.025894 +v 0.029591 0.143691 -0.022813 +v 0.064553 0.114719 -0.076967 +v 0.063800 0.116954 -0.075062 +v 0.062637 0.115483 -0.076517 +v 0.065774 0.115876 -0.075755 +v 0.063717 0.120980 -0.079427 +v 0.066325 0.120032 -0.079979 +v 0.064366 0.118571 -0.081603 +v 0.067520 0.119061 -0.081048 +v 0.061806 0.119636 -0.081156 +v 0.063398 0.122057 -0.078647 +v 0.063961 0.117964 -0.082637 +v 0.066170 0.117937 -0.082159 +v 0.067346 0.120976 -0.079211 +v 0.062237 0.121243 -0.080122 +v 0.065801 0.122088 -0.078951 +v 0.066681 0.120648 -0.081539 +v 0.065861 0.121790 -0.080655 +v 0.063862 0.122048 -0.080730 +v 0.063269 0.120521 -0.082131 +v 0.064038 0.119945 -0.082592 +v 0.065838 0.119881 -0.082435 +v 0.065507 0.110554 -0.080700 +v 0.063224 0.110838 -0.080782 +v 0.062778 0.109611 -0.081922 +v 0.064689 0.108780 -0.082518 +v 0.063227 0.113355 -0.086574 +v 0.064685 0.115196 -0.084658 +v 0.066407 0.113454 -0.086070 +v 0.062932 0.115915 -0.084442 +v 0.061818 0.113794 -0.086466 +v 0.062977 0.112508 -0.087775 +v 0.065456 0.116316 -0.084120 +v 0.065690 0.111887 -0.087776 +v 0.067752 0.113826 -0.085745 +v 0.067010 0.115409 -0.084410 +v 0.067120 0.112835 -0.087098 +v 0.062423 0.115572 -0.085642 +v 0.066667 0.115007 -0.086795 +v 0.066065 0.115766 -0.086182 +v 0.064396 0.116291 -0.085936 +v 0.063349 0.114801 -0.087517 +v 0.064469 0.113153 -0.088220 +v 0.065848 0.113914 -0.087921 +v 0.064100 0.114869 0.087435 +v 0.065663 0.113926 0.087945 +v 0.066950 0.114383 0.087394 +v 0.065605 0.109112 0.082108 +v 0.064517 0.111352 0.080224 +v 0.066322 0.110509 0.080784 +v 0.063391 0.109875 0.081727 +v 0.064094 0.115181 0.084848 +v 0.065663 0.112875 0.086783 +v 0.066880 0.114672 0.084962 +v 0.063234 0.112984 0.087216 +v 0.062480 0.114854 0.085667 +v 0.063810 0.116244 0.084084 +v 0.064926 0.112228 0.087733 +v 0.065541 0.116526 0.083648 +v 0.067736 0.115529 0.084182 +v 0.068535 0.114029 0.085673 +v 0.066901 0.112392 0.087430 +v 0.067331 0.115232 0.086587 +v 0.066860 0.116314 0.085156 +v 0.063717 0.116032 0.085787 +v 0.065485 0.116613 0.085587 +v 0.064522 0.115402 0.085958 +v 0.063609 0.115468 0.076400 +v 0.066350 0.116352 0.075299 +v 0.065743 0.115025 0.076602 +v 0.064302 0.117188 0.074769 +v 0.063802 0.120062 0.080295 +v 0.066361 0.118864 0.081077 +v 0.066104 0.121236 0.078912 +v 0.063347 0.118757 0.081838 +v 0.062542 0.120875 0.080008 +v 0.063953 0.122111 0.078518 +v 0.065976 0.118010 0.082228 +v 0.065757 0.122443 0.078295 +v 0.067795 0.121406 0.078764 +v 0.068473 0.120148 0.079998 +v 0.067637 0.118505 0.081457 +v 0.067272 0.120668 0.081539 +v 0.065859 0.119957 0.082402 +v 0.064414 0.119278 0.082371 +v 0.064049 0.120776 0.081800 +v 0.064238 0.122085 0.080632 +v 0.066593 0.122142 0.080216 +v 0.063979 -0.085114 -0.005499 +v 0.062816 -0.085223 -0.003536 +v 0.064626 -0.085022 -0.002522 +v 0.065966 -0.084924 -0.004207 +v 0.064688 -0.090995 -0.005852 +v 0.066240 -0.090866 -0.002839 +v 0.063544 -0.091118 -0.003152 +v 0.062008 -0.091446 -0.004516 +v 0.063466 -0.091293 -0.006750 +v 0.065417 -0.091217 -0.001038 +v 0.062428 -0.091371 -0.002411 +v 0.063721 -0.091595 -0.001441 +v 0.067451 -0.090926 -0.002448 +v 0.067762 -0.091067 -0.005055 +v 0.066278 -0.090943 -0.006700 +v 0.066736 -0.092457 -0.003819 +v 0.065930 -0.092425 -0.005673 +v 0.064352 -0.092636 -0.005681 +v 0.063240 -0.092783 -0.003956 +v 0.064485 -0.092707 -0.002550 +v 0.066164 -0.092476 -0.002651 +v 0.063782 -0.092708 0.002918 +v 0.064790 -0.092565 0.002237 +v 0.066771 -0.092367 0.003242 +v 0.065100 -0.084981 0.005440 +v 0.064489 -0.085070 0.002471 +v 0.062740 -0.085204 0.004230 +v 0.065804 -0.084930 0.003600 +v 0.063876 -0.091070 0.002688 +v 0.066230 -0.090850 0.003016 +v 0.065793 -0.090906 0.005480 +v 0.063613 -0.091107 0.004837 +v 0.062111 -0.091372 0.004998 +v 0.063514 -0.091222 0.001236 +v 0.064402 -0.091393 0.006957 +v 0.066931 -0.090880 0.006308 +v 0.067663 -0.090826 0.002578 +v 0.062207 -0.091613 0.003254 +v 0.067612 -0.091332 0.004945 +v 0.066082 -0.091588 0.001493 +v 0.066602 -0.092489 0.004043 +v 0.063306 -0.092713 0.004548 +v 0.064541 -0.092668 0.005530 +v 0.065979 -0.092489 0.005491 +v 0.035596 0.112352 -0.100162 +v 0.037938 0.112274 -0.099312 +v 0.035777 0.110268 -0.097252 +v 0.033805 0.111861 -0.098778 +v 0.028985 0.110024 -0.097831 +v 0.028596 0.111927 -0.098877 +v 0.031057 0.110732 -0.097594 +v 0.028849 0.108948 -0.095827 +v 0.026879 0.110542 -0.097363 +v 0.015936 0.111495 -0.098987 +v 0.018397 0.111125 -0.098204 +v 0.016736 0.109301 -0.096229 +v 0.014450 0.110448 -0.097459 +v 0.014748 0.112276 -0.097208 +v 0.015538 0.110819 -0.095646 +v 0.018105 0.111357 -0.096223 +v 0.016984 0.112861 -0.097836 +v 0.015584 0.131779 -0.079956 +v 0.015139 0.129950 -0.077994 +v 0.017067 0.129839 -0.077875 +v 0.018071 0.131209 -0.079345 +v 0.055034 0.112056 -0.092162 +v 0.057058 0.114574 -0.092517 +v 0.055208 0.112884 -0.090704 +v 0.057276 0.111910 -0.089660 +v 0.059032 0.113012 -0.090842 +v 0.055676 0.125700 -0.081078 +v 0.055791 0.123802 -0.079043 +v 0.058522 0.123779 -0.079018 +v 0.058244 0.125924 -0.081318 +v 0.046439 0.116802 -0.097096 +v 0.044623 0.126537 -0.079232 +v 0.044623 0.112419 -0.092397 +v 0.075900 0.034990 0.102104 +v 0.075830 0.036841 0.101284 +v 0.075848 0.034370 0.105350 +v 0.075900 0.032648 0.100076 +v 0.075825 0.029811 0.100695 +v 0.075849 0.033392 0.098010 +v 0.075900 0.032063 0.103118 +v 0.075823 0.030431 0.103930 +v 0.041948 0.031334 0.102008 +v 0.042169 0.035184 0.102633 +v 0.041987 0.034192 0.100112 +v 0.042031 0.032742 0.103584 +v 0.071824 0.035111 0.100577 +v 0.071830 0.032826 0.099659 +v 0.042379 0.031822 0.100148 +v 0.071823 0.031047 0.101358 +v 0.071834 0.032000 0.103515 +v 0.071819 0.034607 0.103562 +v 0.071951 0.031924 0.098316 +v 0.071942 0.036614 0.100132 +v 0.071965 0.035937 0.103983 +v 0.071957 0.032967 0.105388 +v 0.071951 0.029609 0.102457 +v 0.072900 0.032226 0.100288 +v 0.072900 0.032458 0.103377 +v 0.072900 0.035017 0.101632 +v 0.075946 0.030509 0.169940 +v 0.075900 0.034586 0.169405 +v 0.075837 0.033402 0.171927 +v 0.075823 0.035619 0.165616 +v 0.075830 0.036788 0.169015 +v 0.075900 0.033572 0.166478 +v 0.075825 0.029811 0.167163 +v 0.075825 0.032450 0.164734 +v 0.041959 0.034905 0.169257 +v 0.042037 0.032860 0.166313 +v 0.042041 0.031255 0.168037 +v 0.042029 0.032731 0.170084 +v 0.071787 0.032517 0.170507 +v 0.071824 0.035481 0.168381 +v 0.042379 0.034852 0.166822 +v 0.071834 0.034145 0.166297 +v 0.071811 0.031410 0.166831 +v 0.071942 0.035926 0.170851 +v 0.071957 0.036180 0.166111 +v 0.071961 0.031485 0.171357 +v 0.071957 0.029612 0.167967 +v 0.071957 0.032247 0.164739 +v 0.072900 0.034845 0.169010 +v 0.072900 0.033100 0.166451 +v 0.072900 0.031756 0.169242 +v 0.080699 0.000467 0.193353 +v 0.080711 -0.001720 0.198014 +v 0.080671 -0.002621 0.194700 +v 0.080592 0.000578 0.198725 +v 0.080626 0.002569 0.197136 +v 0.080725 0.002405 0.195153 +v 0.065768 -0.001175 0.196772 +v 0.065803 0.001388 0.196221 +v 0.065787 -0.000826 0.194882 +v 0.077630 -0.001546 0.195346 +v 0.077622 -0.000819 0.197517 +v 0.066190 0.000333 0.197550 +v 0.077627 0.001510 0.196798 +v 0.077614 0.000692 0.194388 +v 0.066184 0.000626 0.194516 +v 0.077724 0.001921 0.193797 +v 0.077788 0.002568 0.197128 +v 0.077777 -0.001297 0.193549 +v 0.077751 -0.002838 0.195937 +v 0.077742 -0.000465 0.198924 +v 0.078700 -0.000503 0.197403 +v 0.078700 0.001466 0.195734 +v 0.078700 -0.000964 0.194863 +v 0.070700 -0.031491 0.100173 +v 0.071900 -0.033286 0.099419 +v 0.071900 -0.030990 0.101168 +v 0.070700 -0.035523 0.100533 +v 0.071900 -0.035675 0.101609 +v 0.070700 -0.033393 0.104244 +v 0.071900 -0.033730 0.104032 +v 0.071900 -0.030539 0.102236 +v 0.070700 -0.030934 0.102011 +v 0.070700 -0.029988 0.103511 +v 0.071900 -0.031163 0.104984 +v 0.070700 -0.034443 0.105354 +v 0.071900 -0.035578 0.104560 +v 0.070700 -0.036956 0.100704 +v 0.071900 -0.036724 0.100091 +v 0.070700 -0.032947 0.098099 +v 0.071900 -0.032705 0.098186 +v 0.071900 -0.029851 0.100439 +v 0.070700 -0.029697 0.100762 +v 0.070700 0.034827 0.103509 +v 0.071900 0.035644 0.102183 +v 0.071900 0.033485 0.104019 +v 0.070700 0.034467 0.099477 +v 0.071900 0.034101 0.099642 +v 0.071900 0.031592 0.100088 +v 0.070700 0.030679 0.101932 +v 0.071900 0.031484 0.103435 +v 0.070700 0.033180 0.104032 +v 0.070971 0.032561 0.105357 +v 0.070700 0.029448 0.101689 +v 0.071900 0.030606 0.104339 +v 0.071900 0.029770 0.100531 +v 0.070700 0.032046 0.098318 +v 0.071900 0.032299 0.098296 +v 0.071900 0.035930 0.099163 +v 0.070700 0.035210 0.098764 +v 0.070700 0.036911 0.101680 +v 0.071900 0.036634 0.103006 +v 0.070700 0.034468 0.105236 +v 0.071900 0.034093 0.105279 +v 0.075900 -0.033820 0.166544 +v 0.075900 -0.034405 0.169586 +v 0.075849 -0.036817 0.169370 +v 0.075848 -0.034370 0.164650 +v 0.075837 -0.032428 0.171842 +v 0.075900 -0.031478 0.168572 +v 0.075864 -0.029501 0.167400 +v 0.042008 -0.031819 0.166803 +v 0.041945 -0.034939 0.169130 +v 0.042061 -0.031574 0.169196 +v 0.042088 -0.034452 0.166686 +v 0.071811 -0.035481 0.168730 +v 0.042367 -0.033382 0.170412 +v 0.071787 -0.031954 0.170244 +v 0.071824 -0.031677 0.166607 +v 0.071834 -0.034132 0.166291 +v 0.071942 -0.032854 0.171969 +v 0.071961 -0.036581 0.169502 +v 0.071963 -0.036154 0.166243 +v 0.071961 -0.033281 0.164655 +v 0.071965 -0.030581 0.165957 +v 0.071961 -0.029701 0.168809 +v 0.072900 -0.031603 0.168906 +v 0.072900 -0.034865 0.167562 +v 0.070700 -0.034492 0.166287 +v 0.070700 -0.035306 0.169534 +v 0.071900 -0.034580 0.166316 +v 0.071900 -0.035128 0.169727 +v 0.070700 -0.032014 0.170275 +v 0.071900 -0.031928 0.170222 +v 0.070700 -0.030981 0.167939 +v 0.071900 -0.031003 0.167697 +v 0.070700 -0.032651 0.165981 +v 0.071900 -0.033307 0.165437 +v 0.070700 -0.032452 0.164695 +v 0.071900 -0.030761 0.165554 +v 0.070700 -0.029585 0.167559 +v 0.071900 -0.029777 0.169878 +v 0.070700 -0.032149 0.171997 +v 0.071900 -0.033567 0.171837 +v 0.071900 -0.036634 0.169721 +v 0.070700 -0.036782 0.169441 +v 0.071900 -0.036011 0.165870 +v 0.070700 -0.035784 0.165666 +v 0.071300 -0.033556 0.164715 +v 0.070700 0.031287 0.169492 +v 0.071900 0.032969 0.170703 +v 0.071900 0.030981 0.168485 +v 0.070700 0.033776 0.170464 +v 0.070700 0.035735 0.167686 +v 0.071900 0.035607 0.168387 +v 0.071900 0.034017 0.166051 +v 0.070700 0.032335 0.166032 +v 0.071900 0.031268 0.166970 +v 0.070700 0.030968 0.168180 +v 0.071194 0.029681 0.168196 +v 0.070700 0.030910 0.165423 +v 0.071900 0.030661 0.165606 +v 0.071900 0.034098 0.164720 +v 0.070700 0.034770 0.164855 +v 0.071900 0.036545 0.166773 +v 0.070700 0.036940 0.169498 +v 0.071900 0.036097 0.170652 +v 0.070700 0.032386 0.171847 +v 0.071900 0.032529 0.171758 +v 0.071900 0.029851 0.169561 +v 0.070700 0.029637 0.168853 +v 0.080673 0.039019 0.127157 +v 0.080680 0.040289 0.131579 +v 0.080618 0.038381 0.130144 +v 0.080675 0.043669 0.128473 +v 0.080619 0.041517 0.126176 +v 0.080601 0.042957 0.131039 +v 0.069779 0.040037 0.127975 +v 0.069938 0.039926 0.130175 +v 0.069885 0.041958 0.130061 +v 0.069928 0.042182 0.127908 +v 0.077591 0.041298 0.130714 +v 0.077609 0.039315 0.128998 +v 0.077598 0.041032 0.127277 +v 0.077613 0.042632 0.128830 +v 0.077762 0.043126 0.126875 +v 0.077779 0.038159 0.128755 +v 0.077775 0.039432 0.131310 +v 0.077743 0.042885 0.131293 +v 0.077766 0.039710 0.126553 +v 0.078700 0.042261 0.129756 +v 0.078700 0.039739 0.128244 +v 0.051629 0.019947 0.174418 +v 0.051200 0.016925 0.178915 +v 0.051200 0.008453 0.178112 +v 0.051200 0.030157 0.167613 +v 0.051200 0.030521 0.169930 +v 0.049000 0.030526 0.169943 +v 0.049001 0.030197 0.167468 +v 0.049000 0.016658 0.178911 +v 0.049001 0.011001 0.177757 +v 0.053465 0.022023 0.173413 +v 0.052717 0.015532 0.178786 +v 0.053200 0.008453 0.178112 +v 0.053200 0.030225 0.167099 +v 0.053200 0.030521 0.169930 +v 0.052700 0.023419 0.175315 +v 0.052200 0.030526 0.169943 +v 0.052200 0.008520 0.178110 +v 0.052200 0.030353 0.166791 +v 0.055465 0.022023 0.173413 +v 0.054717 0.015532 0.178786 +v 0.055200 0.008453 0.178112 +v 0.055200 0.030225 0.167099 +v 0.055200 0.030521 0.169930 +v 0.054700 0.023419 0.175316 +v 0.054200 0.030526 0.169943 +v 0.054200 0.007443 0.178510 +v 0.054200 0.030353 0.166791 +v 0.057465 0.022023 0.173413 +v 0.056717 0.015532 0.178786 +v 0.057200 0.008453 0.178112 +v 0.057200 0.030225 0.167099 +v 0.057200 0.030521 0.169930 +v 0.056700 0.023419 0.175315 +v 0.056200 0.030526 0.169943 +v 0.056200 0.007443 0.178510 +v 0.056200 0.030353 0.166791 +v 0.059465 0.022023 0.173413 +v 0.058717 0.015532 0.178786 +v 0.059200 0.008453 0.178112 +v 0.059200 0.030225 0.167099 +v 0.059200 0.030521 0.169930 +v 0.058700 0.023419 0.175315 +v 0.058200 0.030526 0.169943 +v 0.058200 0.007443 0.178510 +v 0.058200 0.030353 0.166791 +v 0.061200 0.022089 0.173489 +v 0.060717 0.015532 0.178786 +v 0.061200 0.008453 0.178112 +v 0.061200 0.030225 0.167099 +v 0.061200 0.030521 0.169930 +v 0.060700 0.023419 0.175315 +v 0.060200 0.030526 0.169943 +v 0.060200 0.007443 0.178510 +v 0.060200 0.030353 0.166791 +v 0.063201 0.022132 0.173440 +v 0.062717 0.015532 0.178786 +v 0.063201 0.008516 0.178079 +v 0.063200 0.030225 0.167105 +v 0.063200 0.030521 0.169930 +v 0.062700 0.023419 0.175315 +v 0.062200 0.030488 0.169969 +v 0.062200 0.029963 0.168110 +v 0.062200 0.008520 0.178110 +v 0.051200 -0.006644 0.178616 +v 0.051200 0.003031 0.181356 +v 0.051200 -0.002947 0.181431 +v 0.051200 0.042346 0.121244 +v 0.051200 0.032237 0.104805 +v 0.051200 0.034931 0.104479 +v 0.051200 0.040920 0.112548 +v 0.051200 0.046474 0.129212 +v 0.051700 0.044000 0.137428 +v 0.051200 0.034949 0.165520 +v 0.051629 0.041784 0.149344 +v 0.051200 0.043965 0.151718 +v 0.051200 0.032257 0.165260 +v 0.049001 -0.006913 0.178547 +v 0.049000 0.002884 0.181425 +v 0.049000 -0.003056 0.181362 +v 0.049000 0.037910 0.157677 +v 0.049000 0.032218 0.165204 +v 0.049000 0.034931 0.165521 +v 0.049000 0.042833 0.123575 +v 0.048376 0.043764 0.142710 +v 0.049000 0.043965 0.118282 +v 0.049000 0.031675 0.104423 +v 0.049000 0.034949 0.104480 +v 0.049000 0.046474 0.140788 +v 0.049000 0.040920 0.157451 +v 0.053200 -0.006644 0.178616 +v 0.052717 0.002969 0.181405 +v 0.052719 -0.002982 0.181408 +v 0.053200 0.042346 0.121244 +v 0.053200 0.032237 0.104805 +v 0.053200 0.034931 0.104479 +v 0.053200 0.040920 0.112548 +v 0.053200 0.046474 0.129212 +v 0.053200 0.043279 0.145457 +v 0.053200 0.034949 0.165520 +v 0.053200 0.043965 0.151718 +v 0.053200 0.032559 0.165235 +v 0.052200 -0.006835 0.178565 +v 0.052200 0.042458 0.122272 +v 0.052200 0.043965 0.118282 +v 0.052200 0.032559 0.104765 +v 0.052200 0.034949 0.104480 +v 0.052200 0.046474 0.140788 +v 0.052200 0.040920 0.157452 +v 0.052200 0.032906 0.165161 +v 0.052200 0.034931 0.165521 +v 0.055200 -0.006644 0.178616 +v 0.054717 0.002969 0.181405 +v 0.054719 -0.002982 0.181408 +v 0.055200 0.039309 0.114517 +v 0.055714 0.032010 0.104709 +v 0.055200 0.034931 0.104479 +v 0.055200 0.040920 0.112548 +v 0.055200 0.046474 0.129212 +v 0.055575 0.043749 0.129230 +v 0.055200 0.034949 0.165520 +v 0.055200 0.042709 0.147077 +v 0.055200 0.043965 0.151718 +v 0.055200 0.032559 0.165235 +v 0.054200 -0.008545 0.177920 +v 0.054200 0.038648 0.113295 +v 0.054200 0.044214 0.131865 +v 0.054200 0.043965 0.118282 +v 0.054200 0.034949 0.104480 +v 0.054200 0.031771 0.104560 +v 0.054200 0.046474 0.140788 +v 0.054200 0.041972 0.148762 +v 0.054200 0.040920 0.157452 +v 0.054200 0.032906 0.165161 +v 0.054200 0.034931 0.165521 +v 0.057200 -0.006644 0.178616 +v 0.056717 0.002969 0.181405 +v 0.056719 -0.002982 0.181408 +v 0.057200 0.040920 0.112548 +v 0.057200 0.032512 0.104874 +v 0.057200 0.034931 0.104479 +v 0.057200 0.041972 0.121237 +v 0.057200 0.046474 0.129212 +v 0.057200 0.044214 0.138135 +v 0.057200 0.034949 0.165520 +v 0.057700 0.041700 0.149575 +v 0.057200 0.043965 0.151718 +v 0.057200 0.032559 0.165235 +v 0.056200 -0.008545 0.177920 +v 0.056200 0.038648 0.113295 +v 0.056200 0.043965 0.118282 +v 0.056200 0.043379 0.144721 +v 0.056200 0.034949 0.104480 +v 0.056200 0.046474 0.140788 +v 0.056200 0.040920 0.157452 +v 0.056200 0.032906 0.165161 +v 0.056200 0.034931 0.165521 +v 0.059200 -0.006644 0.178616 +v 0.058717 0.002969 0.181405 +v 0.058719 -0.002982 0.181408 +v 0.059200 0.040920 0.112548 +v 0.059200 0.032512 0.104874 +v 0.059200 0.034931 0.104479 +v 0.059200 0.042836 0.123609 +v 0.059200 0.046474 0.129212 +v 0.059200 0.043279 0.145457 +v 0.059200 0.034949 0.165520 +v 0.059200 0.043965 0.151718 +v 0.059200 0.032559 0.165235 +v 0.058200 -0.008545 0.177920 +v 0.058200 0.038648 0.113295 +v 0.058200 0.044214 0.131865 +v 0.058200 0.043965 0.118282 +v 0.058200 0.034949 0.104480 +v 0.058200 0.031771 0.104560 +v 0.058200 0.046474 0.140788 +v 0.058200 0.040920 0.157452 +v 0.058200 0.032906 0.165161 +v 0.058200 0.034931 0.165521 +v 0.061200 -0.006644 0.178616 +v 0.060717 0.002970 0.181405 +v 0.060719 -0.002982 0.181408 +v 0.061200 0.040920 0.112548 +v 0.061200 0.032512 0.104874 +v 0.061200 0.034931 0.104479 +v 0.061678 0.042535 0.122596 +v 0.061200 0.046474 0.129212 +v 0.061200 0.043279 0.145457 +v 0.061200 0.034949 0.165520 +v 0.061200 0.043965 0.151718 +v 0.061200 0.032559 0.165235 +v 0.060200 -0.008545 0.177920 +v 0.060200 0.038648 0.113295 +v 0.060200 0.044214 0.131865 +v 0.060200 0.043965 0.118282 +v 0.060200 0.034949 0.104480 +v 0.060200 0.031771 0.104560 +v 0.060200 0.046474 0.140788 +v 0.060200 0.041972 0.148763 +v 0.060200 0.040920 0.157452 +v 0.060200 0.032906 0.165161 +v 0.060200 0.034931 0.165521 +v 0.063200 -0.006139 0.178800 +v 0.062717 0.002969 0.181405 +v 0.062719 -0.002982 0.181408 +v 0.062557 0.032199 0.165252 +v 0.063200 0.038606 0.156716 +v 0.063200 0.040582 0.116756 +v 0.063200 0.032208 0.104796 +v 0.063200 0.034931 0.104479 +v 0.063200 0.040920 0.112548 +v 0.063200 0.046474 0.129212 +v 0.063609 0.044070 0.139984 +v 0.063200 0.034949 0.165520 +v 0.063200 0.043965 0.151718 +v 0.062200 -0.006835 0.178565 +v 0.062200 0.039308 0.155483 +v 0.062200 0.034931 0.165521 +v 0.062200 0.044291 0.136748 +v 0.062200 0.043965 0.118282 +v 0.062200 0.032092 0.104681 +v 0.062200 0.034949 0.104480 +v 0.062200 0.046474 0.140788 +v 0.062200 0.040920 0.157452 +v 0.064335 0.043511 0.151264 +v 0.064389 0.037168 0.164276 +v 0.070701 0.043498 0.151265 +v 0.070788 0.037404 0.162482 +v 0.064356 0.032149 0.173711 +v 0.064325 0.019270 0.197242 +v 0.070468 0.032288 0.173657 +v 0.070701 0.018874 0.197677 +v 0.051200 0.030066 0.101991 +v 0.051629 0.010990 0.092032 +v 0.051200 0.021329 0.093484 +v 0.051200 0.004353 0.088370 +v 0.051200 -0.010207 0.091866 +v 0.051200 -0.018146 0.091605 +v 0.051200 -0.030099 0.102214 +v 0.051200 -0.030502 0.100059 +v 0.051200 0.030520 0.100051 +v 0.049000 -0.030526 0.100055 +v 0.049000 -0.030221 0.102669 +v 0.049000 -0.017519 0.094444 +v 0.048514 0.018837 0.094700 +v 0.049000 0.030457 0.100057 +v 0.049000 -0.000857 0.090673 +v 0.049000 -0.016718 0.091035 +v 0.049000 0.005788 0.088526 +v 0.049000 0.022452 0.094080 +v 0.053200 -0.030502 0.100059 +v 0.053200 -0.019392 0.095142 +v 0.053200 -0.031104 0.104176 +v 0.053200 0.030066 0.101991 +v 0.053629 0.010990 0.092032 +v 0.052671 0.021896 0.093772 +v 0.052700 0.005072 0.088435 +v 0.053867 -0.002243 0.090786 +v 0.052700 -0.010026 0.089524 +v 0.052700 -0.021896 0.093772 +v 0.053200 0.030520 0.100051 +v 0.052200 -0.030526 0.100055 +v 0.052200 -0.030226 0.102696 +v 0.052200 -0.018301 0.094799 +v 0.052200 -0.001915 0.090716 +v 0.052200 0.030314 0.102852 +v 0.052200 0.030457 0.100057 +v 0.055700 0.015719 0.093718 +v 0.055200 0.004352 0.090889 +v 0.054671 0.021895 0.093772 +v 0.054700 0.005072 0.088435 +v 0.055200 -0.012601 0.092665 +v 0.054700 -0.010025 0.089524 +v 0.054700 -0.021896 0.093772 +v 0.055200 -0.030099 0.102214 +v 0.055200 -0.030502 0.100059 +v 0.055200 0.030263 0.102594 +v 0.055200 0.030520 0.100051 +v 0.054200 -0.030488 0.100029 +v 0.054200 -0.031450 0.104527 +v 0.054200 -0.020631 0.095769 +v 0.054200 0.030164 0.102359 +v 0.054200 0.030521 0.100069 +v 0.057200 -0.030502 0.100059 +v 0.057575 -0.019957 0.095564 +v 0.057200 -0.031292 0.104404 +v 0.057600 0.017701 0.094645 +v 0.057629 0.004653 0.090985 +v 0.056671 0.021895 0.093772 +v 0.056700 0.005072 0.088435 +v 0.057700 -0.008452 0.091730 +v 0.056700 -0.010025 0.089524 +v 0.056700 -0.021896 0.093772 +v 0.057200 0.030263 0.102594 +v 0.057200 0.030520 0.100051 +v 0.056200 -0.030488 0.100029 +v 0.056200 -0.031450 0.104527 +v 0.056200 -0.020632 0.095769 +v 0.056200 -0.001915 0.090716 +v 0.056200 0.030164 0.102359 +v 0.056200 0.030521 0.100069 +v 0.059200 -0.030502 0.100059 +v 0.059200 -0.019392 0.095142 +v 0.059200 -0.031104 0.104176 +v 0.059700 0.015719 0.093718 +v 0.059200 0.001966 0.090519 +v 0.058671 0.021895 0.093772 +v 0.058700 0.005072 0.088435 +v 0.058700 -0.010026 0.089524 +v 0.058700 -0.021896 0.093772 +v 0.059200 0.030263 0.102594 +v 0.059200 0.030520 0.100051 +v 0.058200 -0.030526 0.100055 +v 0.058200 -0.030226 0.102696 +v 0.058200 0.030164 0.102359 +v 0.058200 0.030521 0.100069 +v 0.061200 -0.030502 0.100059 +v 0.061200 -0.019392 0.095142 +v 0.061200 -0.031292 0.104404 +v 0.061200 0.030066 0.101991 +v 0.061629 0.010990 0.092032 +v 0.060671 0.021895 0.093772 +v 0.060700 0.005072 0.088435 +v 0.061867 -0.002243 0.090786 +v 0.060700 -0.010026 0.089524 +v 0.060700 -0.021896 0.093772 +v 0.061200 0.030520 0.100051 +v 0.060200 -0.030488 0.100029 +v 0.060200 -0.031450 0.104527 +v 0.060200 -0.020632 0.095769 +v 0.060200 -0.001915 0.090716 +v 0.060200 0.030164 0.102359 +v 0.060200 0.030521 0.100069 +v 0.063200 -0.030502 0.100059 +v 0.063200 -0.019348 0.095155 +v 0.063200 -0.030445 0.103074 +v 0.063200 0.013181 0.092632 +v 0.062700 0.005072 0.088435 +v 0.062671 0.021896 0.093772 +v 0.063825 -0.001183 0.090852 +v 0.062700 -0.010026 0.089524 +v 0.062700 -0.021896 0.093772 +v 0.063200 0.030267 0.102612 +v 0.063200 0.030520 0.100051 +v 0.062200 -0.030488 0.100029 +v 0.062200 -0.031450 0.104527 +v 0.062200 -0.020632 0.095769 +v 0.062200 0.030164 0.102359 +v 0.062200 0.030521 0.100069 +v 0.064330 0.046344 0.139285 +v 0.070701 0.046078 0.139991 +v 0.070710 0.045936 0.128077 +v 0.064242 0.044891 0.121956 +v 0.070699 0.042934 0.117353 +v 0.064392 0.037085 0.106389 +v 0.070762 0.037174 0.107465 +v 0.064200 0.018524 0.094660 +v 0.064201 0.036572 0.109407 +v 0.064200 -0.015455 0.093524 +v 0.064198 -0.031356 0.103525 +v 0.063199 -0.032580 0.104874 +v 0.063825 -0.042652 0.122862 +v 0.063198 -0.032214 0.165204 +v 0.063644 -0.040092 0.153920 +v 0.064200 -0.028159 0.169139 +v 0.063200 -0.030056 0.167848 +v 0.063507 -0.012034 0.177722 +v 0.064201 -0.001564 0.179218 +v 0.064205 0.019249 0.175145 +v 0.064201 0.036291 0.160550 +v 0.064200 0.043831 0.129534 +v 0.061652 -0.040092 0.116080 +v 0.061700 -0.040092 0.153920 +v 0.062200 -0.031292 0.165596 +v 0.061200 -0.032206 0.165204 +v 0.061200 -0.030170 0.167602 +v 0.062200 -0.021554 0.173555 +v 0.061200 -0.011774 0.177740 +v 0.059652 -0.040092 0.116080 +v 0.060200 -0.031199 0.165815 +v 0.059200 -0.032206 0.165204 +v 0.059644 -0.040445 0.152978 +v 0.059200 -0.030170 0.167602 +v 0.060200 -0.021554 0.173555 +v 0.059200 -0.011774 0.177740 +v 0.058200 -0.032206 0.104796 +v 0.057652 -0.040092 0.116080 +v 0.057700 -0.040092 0.153920 +v 0.058200 -0.031292 0.165596 +v 0.057200 -0.032206 0.165204 +v 0.057200 -0.030170 0.167602 +v 0.058200 -0.021554 0.173554 +v 0.057200 -0.011774 0.177740 +v 0.055200 -0.032222 0.104774 +v 0.055719 -0.040445 0.117022 +v 0.055700 -0.040092 0.153920 +v 0.056200 -0.031292 0.165596 +v 0.055200 -0.032206 0.165204 +v 0.055200 -0.030170 0.167602 +v 0.056200 -0.021554 0.173555 +v 0.055200 -0.011774 0.177740 +v 0.053652 -0.040092 0.116080 +v 0.053700 -0.040092 0.153920 +v 0.054200 -0.031292 0.165596 +v 0.053200 -0.032206 0.165204 +v 0.053200 -0.030170 0.167602 +v 0.054200 -0.021554 0.173555 +v 0.053200 -0.011774 0.177740 +v 0.052200 -0.032206 0.104796 +v 0.051200 -0.032222 0.104774 +v 0.051719 -0.040445 0.117022 +v 0.051700 -0.040092 0.153920 +v 0.052200 -0.031292 0.165596 +v 0.051200 -0.032206 0.165204 +v 0.051200 -0.030170 0.167602 +v 0.052200 -0.021554 0.173555 +v 0.051200 -0.011774 0.177740 +v 0.070757 0.027511 0.097824 +v 0.064328 0.019457 0.092912 +v 0.064381 0.028460 0.097885 +v 0.070730 0.016604 0.091622 +v 0.064326 0.007602 0.089125 +v 0.070765 0.002732 0.088506 +v 0.064297 -0.005303 0.088926 +v 0.070727 -0.014844 0.090852 +v 0.064353 -0.016811 0.091627 +v 0.064377 -0.028514 0.097910 +v 0.070714 -0.027265 0.097684 +v 0.064323 -0.014660 0.200080 +v 0.070712 -0.014761 0.200096 +v 0.064363 0.014380 0.200158 +v 0.070687 0.014204 0.200152 +v 0.064475 0.034828 0.097983 +v 0.070539 0.037048 0.100799 +v 0.070559 0.034845 0.098089 +v 0.064329 0.036947 0.100420 +v 0.064403 0.036874 0.170115 +v 0.064371 -0.034847 0.098070 +v 0.064431 -0.037059 0.100771 +v 0.064408 -0.037163 0.106543 +v 0.064317 -0.042413 0.116193 +v 0.070554 0.036812 0.170166 +v 0.070577 -0.036787 0.170051 +v 0.070932 -0.030301 0.165350 +v 0.070858 -0.029363 0.168799 +v 0.070788 -0.037416 0.162614 +v 0.070835 -0.030860 0.175090 +v 0.070913 -0.030444 0.104681 +v 0.070755 -0.037181 0.107495 +v 0.070593 -0.036919 0.100343 +v 0.070471 -0.034838 0.098003 +v 0.064423 -0.046357 0.129735 +v 0.063726 -0.044047 0.137883 +v 0.064337 -0.044685 0.148467 +v 0.064289 -0.019166 0.197301 +v 0.064401 -0.037161 0.164323 +v 0.064359 -0.036821 0.170146 +v 0.064375 -0.032066 0.173852 +v 0.051200 -0.016723 0.178891 +v 0.051200 -0.030488 0.169969 +v 0.049000 -0.019742 0.174397 +v 0.049000 -0.030188 0.167393 +v 0.049000 -0.016925 0.178915 +v 0.049000 -0.030521 0.169930 +v 0.052733 -0.023419 0.175315 +v 0.052664 -0.015529 0.178792 +v 0.053200 -0.030488 0.169969 +v 0.052200 -0.030502 0.169939 +v 0.055200 -0.030465 0.170384 +v 0.054756 -0.015588 0.178821 +v 0.054200 -0.030450 0.170644 +v 0.056733 -0.023419 0.175315 +v 0.056720 -0.015494 0.178809 +v 0.057200 -0.030488 0.169969 +v 0.056200 -0.030502 0.169939 +v 0.059200 -0.030465 0.170384 +v 0.058756 -0.015588 0.178821 +v 0.058200 -0.030450 0.170644 +v 0.061200 -0.030465 0.170384 +v 0.060756 -0.015588 0.178821 +v 0.060200 -0.030450 0.170644 +v 0.063200 -0.030465 0.170384 +v 0.063200 -0.015655 0.178826 +v 0.062200 -0.030502 0.169939 +v 0.062200 -0.016925 0.178915 +v 0.051200 -0.034931 0.165521 +v 0.051200 -0.034945 0.104474 +v 0.051200 -0.043965 0.118282 +v 0.051700 -0.044332 0.135000 +v 0.051200 -0.046474 0.140788 +v 0.051200 -0.040920 0.157452 +v 0.049000 -0.034931 0.104479 +v 0.049000 -0.041228 0.118150 +v 0.049000 -0.032227 0.104797 +v 0.049002 -0.032643 0.165119 +v 0.049000 -0.043925 0.142372 +v 0.049000 -0.043965 0.151718 +v 0.049000 -0.046474 0.129212 +v 0.049000 -0.040920 0.112548 +v 0.049000 -0.034949 0.165520 +v 0.053200 -0.034931 0.165521 +v 0.053200 -0.034949 0.104480 +v 0.053200 -0.043965 0.118282 +v 0.053700 -0.044332 0.135000 +v 0.053200 -0.046474 0.140788 +v 0.053200 -0.040920 0.157451 +v 0.052200 -0.034931 0.104479 +v 0.052200 -0.034945 0.165526 +v 0.052200 -0.043965 0.151718 +v 0.052200 -0.046474 0.129212 +v 0.052200 -0.040920 0.112548 +v 0.055200 -0.034931 0.165521 +v 0.055200 -0.034945 0.104474 +v 0.055200 -0.043965 0.118282 +v 0.055700 -0.044332 0.135000 +v 0.055200 -0.046474 0.140788 +v 0.055200 -0.040920 0.157452 +v 0.054200 -0.034931 0.104479 +v 0.054200 -0.034945 0.165526 +v 0.054200 -0.043965 0.151718 +v 0.054200 -0.046474 0.129212 +v 0.054200 -0.040920 0.112548 +v 0.057200 -0.034931 0.165521 +v 0.057200 -0.034945 0.104474 +v 0.057200 -0.043965 0.118282 +v 0.057700 -0.044332 0.135000 +v 0.057200 -0.046474 0.140788 +v 0.057200 -0.040920 0.157452 +v 0.056200 -0.034931 0.104479 +v 0.056200 -0.034945 0.165526 +v 0.056200 -0.043965 0.151718 +v 0.056200 -0.046474 0.129212 +v 0.056200 -0.040920 0.112549 +v 0.059200 -0.034931 0.165521 +v 0.059200 -0.034949 0.104480 +v 0.059200 -0.043965 0.118282 +v 0.059700 -0.044332 0.135000 +v 0.059200 -0.046474 0.140788 +v 0.059200 -0.040920 0.157452 +v 0.058200 -0.034931 0.104479 +v 0.058200 -0.034945 0.165526 +v 0.058200 -0.043965 0.151718 +v 0.058200 -0.046474 0.129212 +v 0.058200 -0.040920 0.112548 +v 0.061200 -0.034931 0.165521 +v 0.061200 -0.034945 0.104474 +v 0.061200 -0.043965 0.118282 +v 0.061700 -0.044332 0.135000 +v 0.061200 -0.046474 0.140788 +v 0.061200 -0.040920 0.157452 +v 0.060200 -0.034931 0.104479 +v 0.060200 -0.034949 0.165520 +v 0.060200 -0.043965 0.151718 +v 0.060200 -0.046474 0.129212 +v 0.060200 -0.040920 0.112549 +v 0.063200 -0.034931 0.165521 +v 0.063200 -0.034945 0.104474 +v 0.063200 -0.043965 0.118282 +v 0.063200 -0.046474 0.140788 +v 0.063200 -0.040920 0.157451 +v 0.062200 -0.034931 0.104479 +v 0.062200 -0.034945 0.165526 +v 0.062200 -0.043965 0.151718 +v 0.062200 -0.046474 0.129212 +v 0.062200 -0.040920 0.112548 +v 0.070708 -0.043670 0.150654 +v 0.070700 -0.019165 0.197292 +v 0.070703 -0.044451 0.120976 +v 0.070724 -0.046326 0.138859 +v 0.102810 0.026972 0.121596 +v 0.096804 0.037071 0.109457 +v 0.096314 0.043721 0.122692 +v 0.097964 0.040692 0.125911 +v 0.096591 0.044039 0.128188 +v 0.099276 0.037943 0.128548 +v 0.097502 0.042340 0.131800 +v 0.096014 0.045217 0.137552 +v 0.099996 0.035582 0.143826 +v 0.098887 0.039184 0.131374 +v 0.095987 0.042547 0.150207 +v 0.100587 0.025528 0.158177 +v 0.096092 0.035550 0.161999 +v 0.097695 0.027535 0.165711 +v 0.087569 0.022005 0.189911 +v 0.095994 0.015611 0.177384 +v 0.092750 0.028751 0.177013 +v 0.089746 0.010205 0.190210 +v 0.082805 0.017257 0.197974 +v 0.082040 0.013002 0.199856 +v 0.083818 -0.000029 0.199217 +v 0.086078 0.003158 0.196100 +v 0.086212 -0.003157 0.195916 +v 0.082620 -0.011230 0.199704 +v 0.092152 -0.026085 0.180764 +v 0.092915 -0.028944 0.176518 +v 0.096608 -0.027264 0.168800 +v 0.100656 -0.015720 0.165926 +v 0.097481 -0.029720 0.163925 +v 0.096355 -0.034651 0.162244 +v 0.097751 -0.041858 0.131904 +v 0.095975 -0.044686 0.142224 +v 0.096718 -0.044139 0.129458 +v 0.101716 -0.030140 0.146081 +v 0.099024 -0.038827 0.131145 +v 0.096425 -0.042497 0.119109 +v 0.100968 -0.030885 0.118574 +v 0.099127 -0.038338 0.127178 +v 0.097130 -0.042648 0.126385 +v 0.096890 -0.036167 0.108595 +v 0.096877 -0.025047 0.097106 +v 0.101339 -0.010203 0.100648 +v 0.097271 -0.027132 0.099770 +v 0.097187 -0.011937 0.091333 +v 0.097323 -0.000366 0.089905 +v 0.100900 0.012677 0.100455 +v 0.097277 0.009567 0.090885 +v 0.097080 0.018353 0.093565 +v 0.097080 0.026452 0.098686 +v 0.093965 -0.003504 0.184238 +v 0.088444 0.000062 0.192832 +v 0.083324 -0.018119 0.197174 +v 0.100891 0.007767 0.167778 +v 0.104724 0.000042 0.155064 +v 0.098442 0.029250 0.105518 +v 0.104605 0.007745 0.112950 +v 0.104400 -0.013487 0.114902 +v 0.098858 -0.029039 0.106368 +v 0.104337 0.012880 0.152295 +v 0.105127 -0.010273 0.149809 +v 0.095852 -0.039558 0.157216 +v 0.104047 0.023036 0.140364 +v 0.106523 0.005974 0.125559 +v 0.106834 0.002584 0.136625 +v 0.105722 -0.016354 0.131185 +v 0.094374 0.038681 0.160721 +v 0.083218 0.020430 0.195545 +v 0.070863 0.030862 0.175095 +v 0.090339 0.029896 0.177781 +v 0.094008 0.042790 0.152967 +v 0.094002 0.046009 0.142486 +v 0.094383 0.046144 0.129765 +v 0.094244 0.044478 0.121482 +v 0.094569 0.039586 0.110463 +v 0.095057 0.025737 0.096374 +v 0.095023 0.018726 0.092482 +v 0.095139 0.010444 0.089678 +v 0.095280 -0.001748 0.088471 +v 0.095207 -0.015125 0.090974 +v 0.094760 -0.025354 0.096012 +v 0.080938 -0.013924 0.200388 +v 0.080401 0.014311 0.200330 +v 0.081689 0.018912 0.197634 +v 0.077700 0.003234 0.195300 +v 0.077700 -0.000264 0.192984 +v 0.077700 -0.000716 0.199262 +v 0.077700 -0.002899 0.194955 +v 0.077700 0.044105 0.129657 +v 0.077700 0.040056 0.132094 +v 0.077700 0.038104 0.127418 +v 0.077700 0.042335 0.126263 +v 0.070931 0.030332 0.104658 +v 0.095995 0.031257 0.105139 +v 0.096055 0.029684 0.103341 +v 0.091813 0.030716 0.173330 +v 0.093592 0.029421 0.168951 +v 0.070899 0.029183 0.167471 +v 0.094638 0.029728 0.166576 +v 0.070860 0.031520 0.164721 +v 0.095332 0.031739 0.164574 +v 0.095619 0.035519 0.106672 +v 0.095253 0.028532 0.099528 +v 0.093871 0.035346 0.163677 +v 0.095974 0.028543 0.167656 +v 0.093768 0.029219 0.173529 +v 0.094160 -0.043327 0.151927 +v 0.093775 -0.038155 0.161587 +v 0.071183 -0.038644 0.161238 +v 0.082150 -0.019554 0.197031 +v 0.090569 -0.030053 0.177461 +v 0.095052 -0.038413 0.109093 +v 0.094344 -0.042543 0.116157 +v 0.094759 -0.045247 0.124783 +v 0.094104 -0.046538 0.137600 +v 0.077700 -0.043816 0.127712 +v 0.077700 -0.040210 0.125974 +v 0.077700 -0.037984 0.128736 +v 0.077700 -0.039601 0.131778 +v 0.077700 -0.043194 0.131104 +v 0.096172 -0.029751 0.103551 +v 0.095817 -0.031291 0.105132 +v 0.095390 -0.031473 0.164688 +v 0.094956 -0.030046 0.166090 +v 0.094383 -0.029230 0.168599 +v 0.095150 -0.036095 0.106869 +v 0.095132 -0.028519 0.099465 +v 0.092107 -0.030581 0.172932 +v 0.094138 -0.034570 0.163940 +v 0.097681 -0.030135 0.105417 +v 0.064187 -0.011744 0.179530 +v 0.063699 -0.010897 0.177878 +v 0.063487 -0.010965 0.181488 +v 0.064187 -0.009589 0.179309 +v 0.064187 -0.008577 0.180901 +v 0.063703 -0.010607 0.181537 +v 0.064187 -0.006784 0.178941 +v 0.064187 -0.007540 0.179793 +v 0.064187 -0.010409 0.177903 +v 0.064187 -0.012669 0.180742 +v 0.064187 -0.014954 0.182616 +v 0.064187 -0.013464 0.179093 +v 0.063712 -0.015446 0.181303 +v 0.063687 -0.014572 0.178691 +v 0.064187 -0.019158 0.185463 +v 0.064187 -0.002550 0.186172 +v 0.064187 -0.006501 0.182946 +v 0.064187 -0.018382 0.189552 +v 0.063701 -0.019646 0.190808 +v 0.064187 -0.015686 0.196614 +v 0.064187 -0.003977 0.188049 +v 0.064187 -0.012374 0.195582 +v 0.064187 -0.005822 0.193427 +v 0.064187 -0.008391 0.197395 +v 0.064187 -0.003072 0.193030 +v 0.063187 -0.013052 0.178782 +v 0.063187 -0.011763 0.180075 +v 0.063187 -0.013120 0.180607 +v 0.063187 -0.007804 0.180133 +v 0.063187 -0.005323 0.182248 +v 0.063187 -0.006843 0.178832 +v 0.063187 -0.009555 0.180637 +v 0.063187 -0.008940 0.178818 +v 0.063187 -0.018700 0.184311 +v 0.063187 -0.002099 0.189716 +v 0.063187 -0.016036 0.183511 +v 0.063187 -0.018037 0.188401 +v 0.063187 -0.015062 0.194649 +v 0.063187 -0.015947 0.196450 +v 0.063187 -0.006804 0.197054 +v 0.063187 -0.007740 0.194795 +v 0.063187 -0.003635 0.188740 +v 0.080602 -0.041587 0.131812 +v 0.080677 -0.043663 0.129562 +v 0.080641 -0.038934 0.130807 +v 0.080700 -0.039514 0.128890 +v 0.080643 -0.042870 0.126957 +v 0.080625 -0.038374 0.127753 +v 0.080580 -0.040696 0.126259 +v 0.069779 -0.040780 0.130516 +v 0.069845 -0.039541 0.128785 +v 0.069800 -0.041512 0.127592 +v 0.077601 -0.042697 0.128903 +v 0.077608 -0.040860 0.127332 +v 0.077595 -0.039265 0.129213 +v 0.077611 -0.041250 0.130648 +v 0.070176 -0.042581 0.129252 +v 0.077749 -0.038009 0.129317 +v 0.077775 -0.043256 0.130644 +v 0.077778 -0.043538 0.127624 +v 0.077773 -0.040826 0.131815 +v 0.077759 -0.040456 0.126199 +v 0.078700 -0.041890 0.130170 +v 0.078700 -0.040110 0.127830 +v 0.075900 -0.032896 0.100010 +v 0.075830 -0.033716 0.098159 +v 0.075848 -0.029650 0.100630 +v 0.075864 -0.037056 0.101939 +v 0.075900 -0.034924 0.102351 +v 0.075864 -0.032400 0.105499 +v 0.075900 -0.031882 0.102937 +v 0.041996 -0.034608 0.103179 +v 0.042136 -0.031927 0.103298 +v 0.042012 -0.031441 0.101191 +v 0.041996 -0.034668 0.100440 +v 0.071834 -0.033413 0.099633 +v 0.042387 -0.032727 0.099713 +v 0.071827 -0.035329 0.101052 +v 0.071803 -0.033992 0.103948 +v 0.071832 -0.031448 0.102923 +v 0.071827 -0.031340 0.100620 +v 0.071961 -0.035064 0.098690 +v 0.071963 -0.036758 0.101502 +v 0.071951 -0.030901 0.098906 +v 0.071963 -0.029809 0.102638 +v 0.071957 -0.032247 0.105261 +v 0.071963 -0.035702 0.104296 +v 0.072900 -0.034712 0.102773 +v 0.072900 -0.031623 0.102542 +v 0.072900 -0.033368 0.099983 +v 0.064187 0.009753 0.180200 +v 0.064187 0.009194 0.178893 +v 0.064187 0.010601 0.181510 +v 0.064187 0.015979 0.181621 +v 0.064187 0.013224 0.180614 +v 0.063687 0.014573 0.178691 +v 0.064187 0.013218 0.179021 +v 0.063675 0.010897 0.177878 +v 0.064187 0.006719 0.182969 +v 0.064187 0.011654 0.179568 +v 0.064187 0.007770 0.180233 +v 0.064187 0.012192 0.181448 +v 0.063674 0.006070 0.181674 +v 0.064187 0.006910 0.178735 +v 0.064187 0.002411 0.185947 +v 0.064187 0.019795 0.187881 +v 0.064187 0.003635 0.188740 +v 0.063582 0.003115 0.192981 +v 0.064187 0.007740 0.194795 +v 0.064187 0.017871 0.186302 +v 0.064187 0.006931 0.196798 +v 0.064187 0.015470 0.194469 +v 0.064187 0.014255 0.197316 +v 0.063616 0.019142 0.192418 +v 0.063187 0.006784 0.178941 +v 0.063187 0.008152 0.179063 +v 0.063187 0.010409 0.177903 +v 0.063187 0.006798 0.182636 +v 0.063187 0.009767 0.180124 +v 0.063187 0.008350 0.180769 +v 0.063187 0.013749 0.179456 +v 0.063187 0.011677 0.179418 +v 0.063187 0.012514 0.180960 +v 0.063187 0.002769 0.185241 +v 0.063187 0.019263 0.185424 +v 0.063187 0.003977 0.188049 +v 0.063187 0.005822 0.193427 +v 0.063187 0.008391 0.197395 +v 0.063187 0.012807 0.195561 +v 0.063187 0.014796 0.196946 +v 0.063187 0.014954 0.182616 +v 0.063187 0.018344 0.189107 +v 0.010008 0.046890 0.168075 +v 0.009743 0.044418 0.168156 +v 0.013084 0.042431 0.168058 +v 0.005035 0.042301 0.168156 +v 0.002987 0.042193 0.168055 +v 0.004351 0.038322 0.168058 +v 0.009222 0.039282 0.168156 +v 0.011804 0.038666 0.168051 +v 0.008608 0.036981 0.168056 +v 0.004490 0.045746 0.168064 +v 0.005119 0.041800 0.142200 +v 0.010822 0.040513 0.142402 +v 0.006384 0.039289 0.142355 +v 0.009587 0.044627 0.142316 +v 0.006192 0.044300 0.142317 +v 0.010984 0.040336 0.162061 +v 0.006677 0.039035 0.162086 +v 0.004746 0.042819 0.162070 +v 0.009120 0.045228 0.162061 +v 0.009594 0.037099 0.162228 +v 0.013148 0.041167 0.162221 +v 0.006768 0.047003 0.162225 +v 0.003458 0.044209 0.162231 +v 0.011316 0.045871 0.162228 +v 0.005645 0.037577 0.162228 +v 0.003213 0.040247 0.162228 +v 0.005685 0.040123 0.163156 +v 0.005902 0.043983 0.163156 +v 0.010098 0.040017 0.163156 +v 0.010315 0.043877 0.163156 +v 0.005217 -0.033156 0.091934 +v 0.003511 -0.033056 0.090675 +v 0.006859 -0.033118 0.088048 +v 0.003246 -0.033061 0.094999 +v 0.007332 -0.033156 0.095808 +v 0.010783 -0.033156 0.094067 +v 0.006997 -0.033054 0.098025 +v 0.011624 -0.033058 0.096671 +v 0.010666 -0.033061 0.088768 +v 0.013020 -0.033061 0.091819 +v 0.007866 -0.007222 0.090011 +v 0.005307 -0.007258 0.091729 +v 0.006435 -0.007400 0.095780 +v 0.009985 -0.007291 0.095151 +v 0.010893 -0.007423 0.091899 +v 0.004841 -0.027061 0.094301 +v 0.008391 -0.027090 0.096134 +v 0.010830 -0.027088 0.094491 +v 0.010438 -0.027078 0.090779 +v 0.006511 -0.027086 0.090114 +v 0.002968 -0.027228 0.092186 +v 0.004155 -0.027228 0.096347 +v 0.013216 -0.027215 0.093844 +v 0.010136 -0.027217 0.088166 +v 0.005121 -0.027227 0.088852 +v 0.008874 -0.027223 0.098142 +v 0.006257 -0.028156 0.095418 +v 0.010965 -0.028156 0.093301 +v 0.006778 -0.028156 0.090282 +v 0.009988 0.039217 0.162156 +v 0.010974 0.040311 0.160556 +v 0.008512 0.038736 0.160556 +v 0.010820 0.044407 0.162156 +v 0.010680 0.044188 0.160556 +v 0.005626 0.044848 0.160556 +v 0.006313 0.044897 0.162156 +v 0.004494 0.041444 0.162156 +v 0.005863 0.039204 0.160556 +v 0.007866 0.038590 0.162156 +v 0.006852 0.036991 0.162156 +v 0.007887 0.036839 0.160556 +v 0.003587 0.039407 0.160556 +v 0.003342 0.040047 0.162156 +v 0.003583 0.044930 0.160556 +v 0.003394 0.044321 0.162156 +v 0.007805 0.047198 0.162156 +v 0.009206 0.047060 0.160556 +v 0.012065 0.045050 0.162156 +v 0.012857 0.043615 0.160556 +v 0.012684 0.039287 0.162156 +v 0.012125 0.038904 0.160556 +v 0.008754 0.037067 0.161138 +v 0.034240 0.045439 0.162156 +v 0.032390 0.045164 0.160556 +v 0.035914 0.044693 0.160556 +v 0.030480 0.042461 0.162156 +v 0.030668 0.041229 0.160556 +v 0.033791 0.038353 0.162156 +v 0.034172 0.038404 0.160556 +v 0.037439 0.041619 0.162156 +v 0.037482 0.042507 0.160556 +v 0.036177 0.044486 0.162156 +v 0.037379 0.045740 0.162156 +v 0.037874 0.045448 0.160556 +v 0.039157 0.041890 0.162156 +v 0.038819 0.040275 0.160556 +v 0.037202 0.038094 0.162156 +v 0.035092 0.036914 0.160556 +v 0.033091 0.036923 0.162156 +v 0.030734 0.038148 0.160556 +v 0.029206 0.040097 0.162156 +v 0.028890 0.041717 0.160556 +v 0.029631 0.044596 0.162156 +v 0.030656 0.045875 0.160556 +v 0.033128 0.047043 0.162156 +v 0.035706 0.046848 0.160556 +v 0.036909 0.046108 0.162156 +v 0.008499 -0.026090 0.096244 +v 0.011045 -0.025556 0.094642 +v 0.010894 -0.027156 0.094895 +v 0.010444 -0.027156 0.090425 +v 0.010217 -0.025556 0.090228 +v 0.005958 -0.027156 0.090207 +v 0.005728 -0.025556 0.090391 +v 0.004697 -0.027156 0.093885 +v 0.004717 -0.025556 0.093524 +v 0.007093 -0.025556 0.096318 +v 0.008308 -0.027156 0.097025 +v 0.006499 -0.025556 0.097934 +v 0.004971 -0.027156 0.097126 +v 0.003069 -0.025556 0.094231 +v 0.002785 -0.027156 0.092054 +v 0.003831 -0.025556 0.090031 +v 0.006380 -0.027156 0.088183 +v 0.007297 -0.025556 0.087998 +v 0.011813 -0.027156 0.089240 +v 0.011417 -0.025556 0.089137 +v 0.013071 -0.025556 0.093342 +v 0.012734 -0.027156 0.094946 +v 0.010043 -0.025556 0.097791 +v 0.009235 -0.027156 0.097947 +v 0.034807 -0.025556 0.089698 +v 0.031946 -0.027156 0.089980 +v 0.035914 -0.027156 0.090307 +v 0.030362 -0.025556 0.092287 +v 0.030967 -0.027156 0.094580 +v 0.033580 -0.025556 0.096478 +v 0.033946 -0.027156 0.096384 +v 0.036982 -0.027156 0.094675 +v 0.036987 -0.025556 0.094591 +v 0.036637 -0.025556 0.090809 +v 0.036695 -0.027156 0.090968 +v 0.037282 -0.026356 0.089230 +v 0.039248 -0.025556 0.093113 +v 0.039125 -0.027156 0.092417 +v 0.037371 -0.027156 0.096851 +v 0.036160 -0.025556 0.097684 +v 0.033527 -0.027156 0.098029 +v 0.030442 -0.025556 0.096928 +v 0.029972 -0.027156 0.096157 +v 0.029233 -0.027156 0.090684 +v 0.029085 -0.025556 0.091574 +v 0.032845 -0.025556 0.087880 +v 0.035025 -0.027156 0.087921 +v 0.036911 -0.025556 0.088944 +v 0.047775 0.047684 0.160484 +v 0.037345 0.046766 0.160731 +v 0.039761 0.043038 0.161938 +v 0.047739 0.038299 0.163299 +v 0.038485 0.038674 0.163165 +v 0.036939 -0.025700 0.087898 +v 0.047772 -0.025466 0.087296 +v 0.039499 -0.027807 0.095045 +v 0.047710 -0.028475 0.097018 +v 0.006981 0.047544 0.160615 +v 0.000500 0.047486 0.160690 +v 0.003958 0.045925 0.160790 +v 0.010661 0.046962 0.160763 +v 0.013706 0.043171 0.161902 +v 0.030968 0.047031 0.160719 +v 0.039453 0.007729 0.171856 +v 0.035170 0.036514 0.163756 +v 0.030757 0.037318 0.163532 +v 0.002339 0.041850 0.162270 +v 0.000075 0.007513 0.171722 +v 0.011384 0.037386 0.163513 +v 0.005437 0.036783 0.163681 +v 0.028339 0.041850 0.162270 +v 0.042209 -0.010781 0.089677 +v 0.047782 0.005323 0.088486 +v 0.047795 -0.011431 0.089677 +v 0.042127 0.003482 0.088516 +v 0.042262 0.019425 0.092708 +v 0.047836 0.020810 0.093539 +v 0.047776 0.029323 0.098640 +v 0.042172 0.029278 0.098656 +v 0.042154 -0.036314 0.164337 +v 0.047804 -0.044345 0.150073 +v 0.047799 -0.036302 0.164429 +v 0.042210 -0.042660 0.153561 +v 0.042119 -0.046268 0.139403 +v 0.047886 -0.046400 0.131605 +v 0.042232 -0.044508 0.120390 +v 0.047837 -0.042646 0.116468 +v 0.047804 -0.036286 0.105544 +v 0.042167 -0.036290 0.105607 +v 0.000214 -0.025489 0.087324 +v 0.004894 -0.025728 0.088011 +v 0.002339 -0.027186 0.092850 +v 0.031129 -0.025766 0.088065 +v 0.028339 -0.027186 0.092850 +v 0.011282 -0.025765 0.088197 +v 0.000149 -0.037526 0.130832 +v 0.004616 -0.028513 0.097614 +v 0.010563 -0.028681 0.098217 +v 0.039423 -0.037656 0.130698 +v 0.030616 -0.028513 0.097614 +v 0.035170 -0.028756 0.098486 +v 0.013661 -0.027270 0.093150 +v 0.042174 0.029453 0.171275 +v 0.047736 0.017036 0.178458 +v 0.047820 0.029395 0.171296 +v 0.042210 0.018560 0.177660 +v 0.042112 0.001998 0.181578 +v 0.047926 -0.001422 0.181675 +v 0.042210 -0.014802 0.179105 +v 0.047837 -0.018531 0.177646 +v 0.042170 -0.029460 0.171296 +v 0.047798 -0.028673 0.171647 +v 0.004024 -0.014080 0.099879 +v 0.003995 -0.005170 0.097588 +v 0.037986 -0.013736 0.099866 +v 0.038001 -0.005152 0.097588 +v 0.004027 0.007615 0.098014 +v 0.037976 0.007664 0.098025 +v 0.004003 0.017914 0.101844 +v 0.037978 0.017889 0.101838 +v 0.004021 0.025512 0.107282 +v 0.037897 0.025028 0.106827 +v 0.004027 0.032378 0.115570 +v 0.037949 0.032463 0.115752 +v 0.004024 0.036977 0.127348 +v 0.037966 0.036578 0.125955 +v 0.037972 0.037688 0.135547 +v 0.004000 0.037417 0.140123 +v 0.037959 0.036654 0.143439 +v 0.004046 0.035124 0.148676 +v 0.037985 0.035134 0.148745 +v 0.039188 -0.000444 0.172749 +v 0.000361 -0.005019 0.172424 +v 0.038886 -0.010533 0.171139 +v 0.039943 -0.017813 0.168370 +v 0.000171 -0.019071 0.167356 +v 0.039493 -0.025773 0.162696 +v 0.000085 -0.027886 0.159851 +v 0.039463 -0.031529 0.155637 +v 0.000243 -0.035094 0.148854 +v 0.040059 -0.035210 0.148997 +v 0.039846 -0.037647 0.139239 +v 0.042146 0.036262 0.105552 +v 0.042210 0.042563 0.116238 +v 0.047811 0.036306 0.105545 +v 0.047880 0.044165 0.120526 +v 0.042122 0.046539 0.132391 +v 0.047791 0.046505 0.133988 +v 0.047775 0.045332 0.146189 +v 0.042332 0.045526 0.147845 +v 0.041894 0.015783 0.096311 +v 0.041904 0.027016 0.103369 +v 0.042179 0.034594 0.098482 +v 0.042149 0.036596 0.101269 +v 0.041895 0.034899 0.112226 +v 0.041906 -0.013983 0.095733 +v 0.042059 -0.014328 0.088680 +v 0.041906 0.041831 0.137191 +v 0.041903 0.039263 0.148980 +v 0.041893 0.039725 0.122663 +v 0.041894 -0.002356 0.093165 +v 0.047934 0.028962 0.101311 +v 0.047838 0.034074 0.098443 +v 0.047762 0.036629 0.100720 +v 0.046038 0.032247 0.166729 +v 0.046038 0.032188 0.169963 +v 0.046038 0.035080 0.167670 +v 0.041874 -0.039484 0.144586 +v 0.041793 -0.030975 0.160256 +v 0.041911 0.034799 0.167190 +v 0.042110 0.034404 0.171562 +v 0.041997 0.036413 0.166489 +v 0.042016 0.033022 0.170279 +v 0.042034 -0.034683 0.102888 +v 0.042255 -0.036630 0.100383 +v 0.041833 -0.017995 0.171485 +v 0.042084 -0.033645 0.099902 +v 0.042146 -0.034169 0.098484 +v 0.042120 -0.036563 0.169036 +v 0.042202 -0.034278 0.171611 +v 0.041774 -0.039376 0.128342 +v 0.041794 0.005909 0.174670 +v 0.033145 -0.025557 0.098932 +v 0.009016 -0.025557 0.098941 +v 0.002576 -0.025556 0.095110 +v 0.047791 -0.016085 0.087308 +v 0.000185 -0.015863 0.087330 +v 0.000434 -0.013862 0.096227 +v 0.000361 -0.000869 0.093821 +v 0.000342 0.010927 0.095427 +v 0.000297 0.021709 0.100031 +v 0.000423 0.035024 0.112956 +v 0.000301 0.040109 0.126289 +v 0.000374 0.040919 0.139211 +v 0.000424 0.038759 0.148909 +v 0.013601 -0.025556 0.093835 +v 0.039487 -0.025557 0.094932 +v 0.028177 -0.025556 0.093162 +v 0.037748 -0.015294 0.098967 +v 0.040544 -0.015545 0.087658 +v 0.004453 -0.015442 0.098608 +v 0.000400 -0.015356 0.095159 +v 0.040950 -0.015362 0.095358 +v 0.031567 0.036802 0.160557 +v 0.028399 0.041165 0.160556 +v 0.037399 0.037348 0.160556 +v 0.039563 0.041513 0.160556 +v 0.047773 0.047720 0.151126 +v 0.000135 0.047784 0.160100 +v 0.000182 0.047652 0.150856 +v 0.002399 0.041165 0.160556 +v 0.005146 0.037103 0.160556 +v 0.011243 0.037075 0.160556 +v 0.013601 0.042835 0.160556 +v 0.004182 0.035917 0.150228 +v 0.041067 0.047207 0.150418 +v 0.037686 0.036042 0.150308 +v 0.000355 0.039714 0.150347 +v 0.041046 0.039327 0.150278 +v 0.047820 -0.034339 0.171531 +v 0.047758 -0.036652 0.169005 +v 0.047848 0.039751 0.114820 +v 0.047934 -0.028169 0.169263 +v 0.047862 -0.015725 0.176561 +v 0.047883 -0.036974 0.159452 +v 0.047812 -0.042791 0.146995 +v 0.047861 -0.044352 0.134592 +v 0.047852 -0.002440 0.179180 +v 0.047907 0.038893 0.156721 +v 0.047857 -0.042158 0.121337 +v 0.047856 -0.036084 0.109015 +v 0.047921 0.026747 0.170511 +v 0.047823 0.011644 0.177893 +v 0.047779 -0.036653 0.101413 +v 0.047696 -0.034913 0.098486 +v 0.042028 -0.031750 0.098599 +v 0.042494 0.036313 0.170097 +v 0.047757 0.036575 0.169472 +v 0.047702 0.033977 0.171692 +v 0.044260 -0.031892 0.103099 +v 0.044260 -0.034806 0.102741 +v 0.041247 -0.031518 0.102699 +v 0.044260 -0.031939 0.100618 +v 0.044259 -0.034034 0.100138 +v 0.041509 0.031721 0.167096 +v 0.040739 -0.029528 0.097873 +v 0.041081 -0.008081 0.173098 +v 0.040791 0.037047 0.164655 +v 0.047730 -0.030808 0.098468 +v 0.047690 0.036577 0.165601 +v 0.029123 -0.033057 0.091500 +v 0.031121 -0.033156 0.092228 +v 0.029528 -0.033056 0.095325 +v 0.038906 -0.033071 0.091301 +v 0.036108 -0.033156 0.090893 +v 0.035092 -0.033050 0.087992 +v 0.031420 -0.033056 0.088698 +v 0.034771 -0.033156 0.095879 +v 0.037821 -0.033061 0.096464 +v 0.032896 -0.033058 0.098063 +v 0.034516 -0.007204 0.090193 +v 0.031627 -0.007286 0.091200 +v 0.031448 -0.007322 0.094817 +v 0.035663 -0.007439 0.095678 +v 0.036847 -0.007321 0.091805 +v 0.035260 -0.027061 0.089824 +v 0.030654 -0.027061 0.092310 +v 0.033331 -0.027080 0.096231 +v 0.037064 -0.027078 0.094220 +v 0.032175 -0.027227 0.088292 +v 0.036143 -0.027228 0.088375 +v 0.030492 -0.027215 0.096951 +v 0.036573 -0.027221 0.097536 +v 0.039182 -0.027223 0.092406 +v 0.029115 -0.027228 0.091358 +v 0.031019 -0.028156 0.093009 +v 0.033627 -0.028156 0.095863 +v 0.034373 -0.028156 0.090137 +v 0.036981 -0.028156 0.092991 +v 0.035498 0.039423 0.168156 +v 0.031867 0.037396 0.168051 +v 0.037052 0.037684 0.168075 +v 0.031019 0.041991 0.168156 +v 0.028984 0.040804 0.168061 +v 0.034114 0.047217 0.168067 +v 0.029948 0.045028 0.168051 +v 0.035482 0.044586 0.168156 +v 0.038968 0.043720 0.168078 +v 0.034161 0.044879 0.142216 +v 0.031651 0.040029 0.142324 +v 0.031545 0.043799 0.142399 +v 0.035295 0.039268 0.142350 +v 0.037007 0.042837 0.142332 +v 0.033810 0.038589 0.162061 +v 0.030755 0.041891 0.162086 +v 0.032548 0.044851 0.162088 +v 0.035478 0.044791 0.162090 +v 0.037293 0.041820 0.162078 +v 0.029561 0.039263 0.162221 +v 0.029456 0.044310 0.162228 +v 0.037654 0.045555 0.162228 +v 0.039071 0.041087 0.162225 +v 0.035172 0.036847 0.162217 +v 0.033227 0.047094 0.162225 +v 0.034373 0.044863 0.163156 +v 0.036879 0.041228 0.163156 +v 0.031121 0.042772 0.163156 +v 0.033627 0.039137 0.163156 +v 0.047917 -0.013598 0.092670 +v 0.047825 0.044088 0.130254 +v 0.047841 0.003938 0.090623 +v 0.047944 -0.027395 0.100063 +v 0.075900 0.034990 -0.102104 +v 0.075823 0.036693 -0.102523 +v 0.075830 0.035687 -0.099078 +v 0.075837 0.034040 -0.105374 +v 0.075900 0.032648 -0.100076 +v 0.075823 0.032160 -0.098392 +v 0.075825 0.029811 -0.100695 +v 0.075900 0.032063 -0.103118 +v 0.075823 0.030431 -0.103930 +v 0.041979 0.031870 -0.103316 +v 0.041982 0.033966 -0.099972 +v 0.042064 0.034464 -0.103234 +v 0.042035 0.031562 -0.100797 +v 0.071824 0.035111 -0.100577 +v 0.042379 0.035341 -0.101352 +v 0.071830 0.032826 -0.099659 +v 0.071823 0.031047 -0.101357 +v 0.071834 0.032000 -0.103516 +v 0.071819 0.034607 -0.103562 +v 0.071929 0.030272 -0.099351 +v 0.071951 0.035567 -0.098906 +v 0.071951 0.036455 -0.103567 +v 0.071965 0.033273 -0.105262 +v 0.071961 0.030523 -0.104103 +v 0.072900 0.032226 -0.100288 +v 0.072900 0.032458 -0.103377 +v 0.072900 0.035017 -0.101632 +v 0.075900 0.031544 -0.168820 +v 0.075849 0.031219 -0.171408 +v 0.075900 0.034586 -0.169405 +v 0.075823 0.035398 -0.171037 +v 0.075837 0.036842 -0.167428 +v 0.075837 0.033066 -0.164541 +v 0.075900 0.033572 -0.166478 +v 0.075825 0.029811 -0.167163 +v 0.041965 0.031838 -0.166990 +v 0.042108 0.034448 -0.166509 +v 0.042030 0.034631 -0.169643 +v 0.042145 0.031751 -0.169757 +v 0.071787 0.032517 -0.170507 +v 0.071824 0.035481 -0.168381 +v 0.071834 0.034145 -0.166297 +v 0.071811 0.031410 -0.166831 +v 0.071961 0.036751 -0.167566 +v 0.071951 0.035123 -0.171404 +v 0.071942 0.030189 -0.170430 +v 0.071951 0.030823 -0.165440 +v 0.071963 0.034687 -0.165013 +v 0.072900 0.034845 -0.169010 +v 0.072900 0.033100 -0.166451 +v 0.072900 0.031756 -0.169242 +v 0.080714 -0.001632 -0.194015 +v 0.080626 -0.002808 -0.196091 +v 0.080724 -0.001420 -0.198144 +v 0.080601 0.000677 -0.193238 +v 0.080725 0.002405 -0.195153 +v 0.080592 0.000578 -0.198725 +v 0.080626 0.002569 -0.197136 +v 0.065840 0.000270 -0.197387 +v 0.065887 -0.001337 -0.196590 +v 0.065809 -0.000432 -0.194550 +v 0.065909 0.001489 -0.195930 +v 0.077630 -0.001546 -0.195346 +v 0.077622 -0.000819 -0.197517 +v 0.077627 0.001510 -0.196798 +v 0.077614 0.000692 -0.194388 +v 0.077724 0.001921 -0.193797 +v 0.077788 0.002568 -0.197128 +v 0.077759 -0.002260 -0.194092 +v 0.077753 0.000354 -0.198780 +v 0.077764 -0.002262 -0.197651 +v 0.078700 -0.000503 -0.197403 +v 0.078700 0.001466 -0.195734 +v 0.078700 -0.000964 -0.194863 +v 0.070700 -0.031491 -0.100173 +v 0.071900 -0.031561 -0.100079 +v 0.070700 -0.035523 -0.100533 +v 0.071900 -0.035038 -0.100216 +v 0.071900 -0.034662 -0.103844 +v 0.070700 -0.033393 -0.104244 +v 0.071900 -0.031185 -0.102849 +v 0.070700 -0.030934 -0.102011 +v 0.071194 -0.029681 -0.101804 +v 0.071900 -0.031163 -0.104984 +v 0.070700 -0.031460 -0.105111 +v 0.071900 -0.035578 -0.104560 +v 0.070700 -0.036424 -0.103881 +v 0.071900 -0.036724 -0.100091 +v 0.070700 -0.036152 -0.099625 +v 0.070700 -0.032564 -0.098079 +v 0.071900 -0.033072 -0.098198 +v 0.071900 -0.030042 -0.099968 +v 0.070700 -0.029637 -0.101147 +v 0.070700 0.034309 -0.103803 +v 0.071900 0.033485 -0.104019 +v 0.071900 0.035644 -0.102183 +v 0.070700 0.035311 -0.100268 +v 0.071900 0.034101 -0.099642 +v 0.070700 0.031533 -0.100104 +v 0.071900 0.031592 -0.100088 +v 0.071900 0.031484 -0.103435 +v 0.070700 0.031700 -0.103580 +v 0.071036 0.032924 -0.105375 +v 0.071900 0.030606 -0.104339 +v 0.070700 0.029376 -0.102080 +v 0.071900 0.029770 -0.100531 +v 0.070700 0.032046 -0.098318 +v 0.071900 0.032299 -0.098296 +v 0.071900 0.035930 -0.099163 +v 0.070700 0.035210 -0.098764 +v 0.070700 0.036911 -0.101680 +v 0.071900 0.036634 -0.103006 +v 0.070700 0.034468 -0.105236 +v 0.071900 0.034093 -0.105279 +v 0.075900 -0.033820 -0.166544 +v 0.075822 -0.036709 -0.167791 +v 0.075900 -0.034405 -0.169586 +v 0.075830 -0.035687 -0.170922 +v 0.075848 -0.034370 -0.164650 +v 0.075825 -0.031854 -0.171544 +v 0.075864 -0.029501 -0.167400 +v 0.075900 -0.031478 -0.168572 +v 0.042096 -0.032070 -0.166482 +v 0.042066 -0.031863 -0.169771 +v 0.042001 -0.034958 -0.169270 +v 0.042066 -0.034628 -0.166952 +v 0.071811 -0.035481 -0.168730 +v 0.071787 -0.031954 -0.170244 +v 0.071824 -0.031677 -0.166607 +v 0.071834 -0.034132 -0.166291 +v 0.071957 -0.033501 -0.171856 +v 0.071961 -0.036581 -0.169502 +v 0.071965 -0.036281 -0.166520 +v 0.071951 -0.033285 -0.164544 +v 0.071961 -0.029887 -0.166966 +v 0.071963 -0.030314 -0.170225 +v 0.072900 -0.031603 -0.168906 +v 0.072900 -0.034865 -0.167562 +v 0.070700 -0.034492 -0.166287 +v 0.071900 -0.034580 -0.166316 +v 0.070700 -0.035306 -0.169534 +v 0.071900 -0.035128 -0.169727 +v 0.070700 -0.032014 -0.170275 +v 0.071900 -0.031928 -0.170222 +v 0.070700 -0.030981 -0.167939 +v 0.071900 -0.031003 -0.167697 +v 0.070700 -0.032651 -0.165981 +v 0.071900 -0.033307 -0.165437 +v 0.070700 -0.032452 -0.164695 +v 0.071900 -0.030761 -0.165554 +v 0.070700 -0.029585 -0.167559 +v 0.071900 -0.029777 -0.169878 +v 0.070700 -0.032149 -0.171997 +v 0.071900 -0.033567 -0.171837 +v 0.071900 -0.036634 -0.169721 +v 0.070700 -0.036782 -0.169441 +v 0.071900 -0.036011 -0.165870 +v 0.070700 -0.035784 -0.165666 +v 0.071300 -0.033556 -0.164715 +v 0.070700 0.031287 -0.169492 +v 0.071900 0.030981 -0.168485 +v 0.071900 0.032969 -0.170703 +v 0.070700 0.035132 -0.170011 +v 0.071900 0.035607 -0.168387 +v 0.070700 0.034285 -0.166064 +v 0.071900 0.034017 -0.166051 +v 0.071900 0.031268 -0.166970 +v 0.070700 0.031115 -0.167255 +v 0.071194 0.029681 -0.168196 +v 0.071900 0.030661 -0.165606 +v 0.070700 0.030910 -0.165423 +v 0.071900 0.034098 -0.164720 +v 0.070700 0.034770 -0.164855 +v 0.071900 0.036545 -0.166773 +v 0.070700 0.036940 -0.169498 +v 0.071900 0.036097 -0.170652 +v 0.070700 0.032386 -0.171847 +v 0.071900 0.032529 -0.171758 +v 0.071900 0.029851 -0.169561 +v 0.070700 0.029637 -0.168853 +v 0.080661 0.041383 -0.126228 +v 0.080587 0.038795 -0.127274 +v 0.080689 0.038378 -0.129172 +v 0.080603 0.039420 -0.131328 +v 0.080657 0.041693 -0.131582 +v 0.080683 0.043203 -0.130503 +v 0.080609 0.043690 -0.128192 +v 0.069820 0.041864 -0.130124 +v 0.069956 0.039921 -0.130198 +v 0.069779 0.040037 -0.127974 +v 0.069972 0.042174 -0.127880 +v 0.077612 0.040757 -0.130623 +v 0.077609 0.039315 -0.128998 +v 0.077574 0.041390 -0.127249 +v 0.077610 0.042534 -0.129682 +v 0.077771 0.042114 -0.131590 +v 0.077757 0.038621 -0.130772 +v 0.077773 0.042076 -0.126425 +v 0.077768 0.043886 -0.128888 +v 0.077767 0.039052 -0.126869 +v 0.078700 0.042261 -0.129756 +v 0.078700 0.039739 -0.128244 +v 0.051629 0.019947 -0.174418 +v 0.051200 0.008453 -0.178112 +v 0.051200 0.016925 -0.178915 +v 0.051200 0.030157 -0.167613 +v 0.051200 0.030521 -0.169930 +v 0.049000 0.030526 -0.169943 +v 0.049000 0.016658 -0.178911 +v 0.049001 0.030197 -0.167468 +v 0.049001 0.011001 -0.177757 +v 0.053465 0.022023 -0.173413 +v 0.053200 0.008453 -0.178112 +v 0.052717 0.015532 -0.178786 +v 0.053200 0.030521 -0.169930 +v 0.053200 0.030225 -0.167099 +v 0.052700 0.023419 -0.175315 +v 0.052200 0.030526 -0.169943 +v 0.052200 0.008520 -0.178110 +v 0.052200 0.030353 -0.166791 +v 0.055465 0.022023 -0.173413 +v 0.055200 0.008453 -0.178112 +v 0.054717 0.015532 -0.178786 +v 0.055200 0.030521 -0.169930 +v 0.055200 0.030225 -0.167099 +v 0.054700 0.023419 -0.175316 +v 0.054200 0.030526 -0.169943 +v 0.054200 0.007443 -0.178510 +v 0.054200 0.030353 -0.166791 +v 0.057465 0.022023 -0.173413 +v 0.057200 0.008453 -0.178112 +v 0.056717 0.015532 -0.178786 +v 0.057200 0.030521 -0.169930 +v 0.057200 0.030225 -0.167099 +v 0.056700 0.023419 -0.175315 +v 0.056200 0.030526 -0.169943 +v 0.056200 0.007443 -0.178510 +v 0.056200 0.030353 -0.166791 +v 0.059465 0.022023 -0.173413 +v 0.059200 0.008453 -0.178112 +v 0.058717 0.015532 -0.178786 +v 0.059200 0.030521 -0.169930 +v 0.059200 0.030225 -0.167099 +v 0.058700 0.023419 -0.175315 +v 0.058200 0.030526 -0.169943 +v 0.058200 0.007443 -0.178510 +v 0.058200 0.030353 -0.166791 +v 0.061200 0.022089 -0.173489 +v 0.061200 0.008453 -0.178112 +v 0.060717 0.015532 -0.178786 +v 0.061200 0.030521 -0.169930 +v 0.061200 0.030225 -0.167099 +v 0.060700 0.023419 -0.175315 +v 0.060200 0.030526 -0.169943 +v 0.060200 0.007443 -0.178510 +v 0.060200 0.030353 -0.166791 +v 0.063201 0.022132 -0.173440 +v 0.063201 0.008516 -0.178079 +v 0.062717 0.015532 -0.178786 +v 0.063200 0.030521 -0.169930 +v 0.063200 0.030225 -0.167105 +v 0.062700 0.023419 -0.175315 +v 0.062200 0.030488 -0.169969 +v 0.062200 0.029963 -0.168110 +v 0.062200 0.008520 -0.178110 +v 0.051200 -0.006644 -0.178616 +v 0.051200 0.003031 -0.181356 +v 0.051200 -0.002947 -0.181431 +v 0.051200 0.042346 -0.121244 +v 0.051200 0.034931 -0.104479 +v 0.051200 0.032237 -0.104805 +v 0.051200 0.040920 -0.112548 +v 0.051200 0.046474 -0.129212 +v 0.051700 0.044000 -0.137428 +v 0.051200 0.034949 -0.165520 +v 0.051200 0.043965 -0.151718 +v 0.051629 0.041784 -0.149344 +v 0.051200 0.032257 -0.165260 +v 0.049001 -0.006913 -0.178547 +v 0.049000 0.002884 -0.181425 +v 0.049000 -0.003056 -0.181362 +v 0.049000 0.039276 -0.155558 +v 0.049000 0.034931 -0.165521 +v 0.049000 0.032218 -0.165204 +v 0.049000 0.037910 -0.112323 +v 0.049000 0.043965 -0.118282 +v 0.049000 0.043669 -0.127695 +v 0.049000 0.031338 -0.104320 +v 0.049000 0.034949 -0.104480 +v 0.049000 0.046474 -0.140788 +v 0.048405 0.044020 -0.140735 +v 0.049000 0.040920 -0.157451 +v 0.053200 -0.006644 -0.178616 +v 0.052717 0.002969 -0.181405 +v 0.052719 -0.002982 -0.181408 +v 0.053658 0.041374 -0.119277 +v 0.053200 0.034931 -0.104479 +v 0.053200 0.032237 -0.104805 +v 0.053200 0.040920 -0.112548 +v 0.053200 0.046474 -0.129212 +v 0.053700 0.044265 -0.137442 +v 0.053200 0.034949 -0.165520 +v 0.053200 0.043965 -0.151718 +v 0.053600 0.040827 -0.151583 +v 0.053200 0.032559 -0.165235 +v 0.052200 -0.006835 -0.178565 +v 0.052200 0.042458 -0.122272 +v 0.052200 0.043965 -0.118282 +v 0.052200 0.032559 -0.104765 +v 0.052200 0.034949 -0.104480 +v 0.052200 0.046474 -0.140788 +v 0.052200 0.040920 -0.157452 +v 0.052200 0.032906 -0.165161 +v 0.052200 0.034931 -0.165521 +v 0.055200 -0.006644 -0.178616 +v 0.054717 0.002969 -0.181405 +v 0.054719 -0.002982 -0.181408 +v 0.055200 0.039309 -0.114517 +v 0.055200 0.034931 -0.104479 +v 0.055714 0.032010 -0.104709 +v 0.055200 0.040920 -0.112548 +v 0.055200 0.046474 -0.129212 +v 0.055575 0.043749 -0.129230 +v 0.055200 0.034949 -0.165520 +v 0.055200 0.043965 -0.151718 +v 0.055200 0.042709 -0.147077 +v 0.055200 0.032559 -0.165235 +v 0.054200 -0.008545 -0.177920 +v 0.054200 0.043965 -0.118282 +v 0.054200 0.032092 -0.104681 +v 0.054200 0.034949 -0.104480 +v 0.054200 0.046474 -0.140788 +v 0.054200 0.040920 -0.157452 +v 0.054200 0.032906 -0.165161 +v 0.054200 0.034931 -0.165521 +v 0.057200 -0.006644 -0.178616 +v 0.056717 0.002969 -0.181405 +v 0.056719 -0.002982 -0.181408 +v 0.057200 0.040920 -0.112548 +v 0.057200 0.034931 -0.104479 +v 0.057200 0.032512 -0.104874 +v 0.057750 0.041784 -0.120656 +v 0.057200 0.046474 -0.129212 +v 0.057700 0.044265 -0.137442 +v 0.057200 0.034949 -0.165520 +v 0.057200 0.043965 -0.151718 +v 0.057600 0.040827 -0.151583 +v 0.057200 0.032559 -0.165235 +v 0.056200 -0.008545 -0.177920 +v 0.056200 0.038648 -0.113295 +v 0.056200 0.043965 -0.118282 +v 0.056200 0.043379 -0.144721 +v 0.056200 0.034949 -0.104480 +v 0.056200 0.046474 -0.140788 +v 0.056200 0.040920 -0.157452 +v 0.056200 0.032906 -0.165161 +v 0.056200 0.034931 -0.165521 +v 0.059200 -0.006644 -0.178616 +v 0.058717 0.002969 -0.181405 +v 0.058719 -0.002982 -0.181408 +v 0.059200 0.040920 -0.112548 +v 0.059200 0.034931 -0.104479 +v 0.059200 0.032512 -0.104874 +v 0.059200 0.042836 -0.123609 +v 0.059200 0.046474 -0.129212 +v 0.059200 0.043279 -0.145457 +v 0.059200 0.034949 -0.165520 +v 0.059200 0.043965 -0.151718 +v 0.059200 0.032559 -0.165235 +v 0.058200 -0.008545 -0.177920 +v 0.058200 0.043965 -0.118282 +v 0.058200 0.032092 -0.104681 +v 0.058200 0.034949 -0.104480 +v 0.058200 0.046474 -0.140788 +v 0.058200 0.040920 -0.157451 +v 0.058200 0.032906 -0.165161 +v 0.058200 0.034931 -0.165521 +v 0.061200 -0.006644 -0.178616 +v 0.060717 0.002969 -0.181405 +v 0.060719 -0.002982 -0.181408 +v 0.061200 0.040920 -0.112548 +v 0.061200 0.034931 -0.104479 +v 0.061200 0.032512 -0.104874 +v 0.061750 0.041784 -0.120656 +v 0.061200 0.046474 -0.129212 +v 0.061700 0.044265 -0.137442 +v 0.061200 0.034949 -0.165520 +v 0.061200 0.043965 -0.151718 +v 0.061854 0.039412 -0.155164 +v 0.061700 0.032351 -0.165214 +v 0.060200 -0.008545 -0.177920 +v 0.060200 0.038648 -0.113295 +v 0.060200 0.043965 -0.118282 +v 0.060200 0.044214 -0.131865 +v 0.060200 0.031771 -0.104560 +v 0.060200 0.034949 -0.104480 +v 0.060200 0.046474 -0.140788 +v 0.060200 0.041972 -0.148763 +v 0.060200 0.040920 -0.157452 +v 0.060200 0.032906 -0.165161 +v 0.060200 0.034931 -0.165521 +v 0.063200 -0.006139 -0.178800 +v 0.062717 0.002970 -0.181405 +v 0.062719 -0.002982 -0.181408 +v 0.063200 0.037895 -0.112344 +v 0.063200 0.034931 -0.104479 +v 0.063200 0.032208 -0.104796 +v 0.063200 0.040920 -0.112548 +v 0.063700 0.043728 -0.127703 +v 0.063200 0.046474 -0.129212 +v 0.063200 0.034949 -0.165520 +v 0.063200 0.043965 -0.151718 +v 0.063575 0.042732 -0.146707 +v 0.063200 0.032746 -0.165186 +v 0.062200 -0.006835 -0.178565 +v 0.062200 0.034931 -0.165521 +v 0.062200 0.043965 -0.118282 +v 0.062200 0.032092 -0.104681 +v 0.062200 0.034949 -0.104480 +v 0.062200 0.046474 -0.140788 +v 0.062200 0.040920 -0.157452 +v 0.064334 0.043511 -0.151264 +v 0.070701 0.043498 -0.151264 +v 0.064389 0.037168 -0.164276 +v 0.070788 0.037404 -0.162482 +v 0.064356 0.032149 -0.173711 +v 0.070468 0.032288 -0.173657 +v 0.064325 0.019270 -0.197242 +v 0.070701 0.018874 -0.197678 +v 0.051200 0.030066 -0.101991 +v 0.051200 0.021329 -0.093484 +v 0.051629 0.010990 -0.092032 +v 0.051200 0.004353 -0.088370 +v 0.051200 -0.010207 -0.091866 +v 0.051200 -0.018146 -0.091605 +v 0.051200 -0.030099 -0.102214 +v 0.051200 -0.030502 -0.100059 +v 0.051200 0.030520 -0.100051 +v 0.049000 -0.030526 -0.100055 +v 0.049000 -0.017520 -0.094444 +v 0.049000 -0.030221 -0.102669 +v 0.048514 0.018837 -0.094700 +v 0.049000 0.030457 -0.100057 +v 0.049000 -0.016718 -0.091035 +v 0.049000 -0.000857 -0.090673 +v 0.049000 0.005788 -0.088526 +v 0.049000 0.022452 -0.094080 +v 0.053200 -0.030502 -0.100059 +v 0.053200 -0.031104 -0.104176 +v 0.053200 -0.019392 -0.095142 +v 0.053200 0.030066 -0.101991 +v 0.052671 0.021896 -0.093772 +v 0.053629 0.010990 -0.092032 +v 0.052700 0.005072 -0.088435 +v 0.053867 -0.002243 -0.090786 +v 0.052700 -0.010026 -0.089524 +v 0.052700 -0.021896 -0.093772 +v 0.053200 0.030520 -0.100051 +v 0.052200 -0.030526 -0.100055 +v 0.052200 -0.018301 -0.094799 +v 0.052200 -0.030226 -0.102696 +v 0.052200 -0.001915 -0.090716 +v 0.052200 0.030314 -0.102852 +v 0.052200 0.030457 -0.100057 +v 0.055700 0.015719 -0.093718 +v 0.054671 0.021895 -0.093772 +v 0.055200 0.004352 -0.090889 +v 0.054700 0.005072 -0.088435 +v 0.055200 -0.012601 -0.092665 +v 0.054700 -0.010025 -0.089524 +v 0.054700 -0.021896 -0.093772 +v 0.055200 -0.030099 -0.102214 +v 0.055200 -0.030502 -0.100059 +v 0.055200 0.030263 -0.102594 +v 0.055200 0.030520 -0.100051 +v 0.054200 -0.030488 -0.100029 +v 0.054200 -0.020631 -0.095769 +v 0.054200 -0.031450 -0.104527 +v 0.054200 0.030164 -0.102359 +v 0.054200 0.030521 -0.100069 +v 0.057200 -0.030502 -0.100059 +v 0.057200 -0.031292 -0.104404 +v 0.057575 -0.019957 -0.095564 +v 0.057600 0.017701 -0.094645 +v 0.056671 0.021895 -0.093772 +v 0.057629 0.004653 -0.090985 +v 0.056700 0.005072 -0.088435 +v 0.057700 -0.008452 -0.091730 +v 0.056700 -0.010025 -0.089524 +v 0.056700 -0.021896 -0.093772 +v 0.057200 0.030263 -0.102594 +v 0.057200 0.030520 -0.100051 +v 0.056200 -0.030488 -0.100029 +v 0.056200 -0.020632 -0.095769 +v 0.056200 -0.031450 -0.104527 +v 0.056200 -0.001915 -0.090716 +v 0.056200 0.030164 -0.102359 +v 0.056200 0.030521 -0.100069 +v 0.059200 -0.030502 -0.100059 +v 0.059200 -0.031104 -0.104176 +v 0.059200 -0.019392 -0.095142 +v 0.059700 0.015719 -0.093718 +v 0.058671 0.021895 -0.093772 +v 0.059200 0.001966 -0.090519 +v 0.058700 0.005072 -0.088435 +v 0.058700 -0.010026 -0.089524 +v 0.058700 -0.021896 -0.093772 +v 0.059200 0.030263 -0.102594 +v 0.059200 0.030520 -0.100051 +v 0.058200 -0.030526 -0.100055 +v 0.058200 -0.030226 -0.102696 +v 0.058200 0.030164 -0.102359 +v 0.058200 0.030521 -0.100069 +v 0.061200 -0.030502 -0.100059 +v 0.061200 -0.031292 -0.104404 +v 0.061200 -0.019392 -0.095142 +v 0.061200 0.030066 -0.101991 +v 0.060671 0.021895 -0.093772 +v 0.061629 0.010990 -0.092032 +v 0.060700 0.005072 -0.088435 +v 0.061867 -0.002243 -0.090786 +v 0.060700 -0.010026 -0.089524 +v 0.060700 -0.021896 -0.093772 +v 0.061200 0.030520 -0.100051 +v 0.060200 -0.030488 -0.100029 +v 0.060200 -0.020632 -0.095769 +v 0.060200 -0.031450 -0.104527 +v 0.060200 -0.001915 -0.090716 +v 0.060200 0.030164 -0.102359 +v 0.060200 0.030521 -0.100069 +v 0.063200 -0.030502 -0.100059 +v 0.063200 -0.030445 -0.103074 +v 0.063200 -0.019348 -0.095155 +v 0.063200 0.013181 -0.092632 +v 0.062671 0.021896 -0.093772 +v 0.062700 0.005072 -0.088435 +v 0.063825 -0.001183 -0.090852 +v 0.062700 -0.010026 -0.089524 +v 0.062700 -0.021896 -0.093772 +v 0.063200 0.030267 -0.102612 +v 0.063200 0.030520 -0.100051 +v 0.062200 -0.030488 -0.100029 +v 0.062200 -0.020632 -0.095769 +v 0.062200 -0.031450 -0.104527 +v 0.062200 0.030164 -0.102359 +v 0.062200 0.030521 -0.100069 +v 0.064330 0.046344 -0.139285 +v 0.070701 0.046078 -0.139991 +v 0.070710 0.045936 -0.128077 +v 0.064242 0.044891 -0.121956 +v 0.070699 0.042934 -0.117353 +v 0.064391 0.037085 -0.106389 +v 0.070762 0.037174 -0.107465 +v 0.064200 0.018524 -0.094660 +v 0.064200 0.035135 -0.107757 +v 0.064200 -0.015455 -0.093524 +v 0.064198 -0.031355 -0.103525 +v 0.063199 -0.032580 -0.104874 +v 0.063700 -0.041804 -0.120649 +v 0.063198 -0.032214 -0.165204 +v 0.064200 -0.028159 -0.169139 +v 0.063644 -0.040092 -0.153920 +v 0.063200 -0.030056 -0.167848 +v 0.063507 -0.012034 -0.177722 +v 0.064201 -0.001564 -0.179218 +v 0.064205 0.019249 -0.175145 +v 0.064201 0.036291 -0.160550 +v 0.061652 -0.040092 -0.116080 +v 0.061700 -0.040092 -0.153920 +v 0.061200 -0.032206 -0.165204 +v 0.062200 -0.031292 -0.165596 +v 0.061200 -0.030170 -0.167602 +v 0.062200 -0.021554 -0.173555 +v 0.061200 -0.011774 -0.177740 +v 0.059652 -0.040092 -0.116080 +v 0.060200 -0.031199 -0.165815 +v 0.059644 -0.040445 -0.152978 +v 0.059200 -0.032206 -0.165204 +v 0.059200 -0.030170 -0.167602 +v 0.060200 -0.021554 -0.173555 +v 0.059200 -0.011774 -0.177740 +v 0.058200 -0.032206 -0.104796 +v 0.057652 -0.040092 -0.116080 +v 0.057700 -0.040092 -0.153920 +v 0.057200 -0.032206 -0.165204 +v 0.058200 -0.031292 -0.165596 +v 0.057200 -0.030170 -0.167602 +v 0.058200 -0.021554 -0.173554 +v 0.057200 -0.011774 -0.177740 +v 0.055200 -0.032222 -0.104774 +v 0.055719 -0.040445 -0.117022 +v 0.055700 -0.040092 -0.153920 +v 0.055200 -0.032206 -0.165204 +v 0.056200 -0.031292 -0.165596 +v 0.055200 -0.030170 -0.167602 +v 0.056200 -0.021554 -0.173555 +v 0.055200 -0.011774 -0.177740 +v 0.053652 -0.040092 -0.116080 +v 0.053700 -0.040092 -0.153920 +v 0.053200 -0.032206 -0.165204 +v 0.054200 -0.031292 -0.165596 +v 0.053200 -0.030170 -0.167602 +v 0.054200 -0.021554 -0.173555 +v 0.053200 -0.011774 -0.177740 +v 0.052200 -0.032206 -0.104796 +v 0.051200 -0.032222 -0.104774 +v 0.051719 -0.040445 -0.117022 +v 0.051700 -0.040092 -0.153920 +v 0.051200 -0.032206 -0.165204 +v 0.052200 -0.031292 -0.165596 +v 0.051200 -0.030170 -0.167602 +v 0.052200 -0.021554 -0.173555 +v 0.051200 -0.011774 -0.177740 +v 0.070757 0.027511 -0.097824 +v 0.064381 0.028460 -0.097885 +v 0.064326 0.015298 -0.090921 +v 0.070729 0.016605 -0.091622 +v 0.070765 0.002732 -0.088506 +v 0.064338 -0.002238 -0.088615 +v 0.070727 -0.014844 -0.090852 +v 0.064326 -0.016731 -0.091613 +v 0.064377 -0.028514 -0.097910 +v 0.070714 -0.027265 -0.097684 +v 0.064323 -0.014660 -0.200080 +v 0.064363 0.014380 -0.200158 +v 0.070712 -0.014761 -0.200096 +v 0.070687 0.014204 -0.200152 +v 0.064475 0.034828 -0.097983 +v 0.070559 0.034845 -0.098089 +v 0.070539 0.037048 -0.100799 +v 0.064329 0.036947 -0.100420 +v 0.064403 0.036874 -0.170115 +v 0.064371 -0.034847 -0.098070 +v 0.064431 -0.037059 -0.100771 +v 0.064408 -0.037163 -0.106543 +v 0.064397 -0.044165 -0.119905 +v 0.070554 0.036812 -0.170166 +v 0.070577 -0.036787 -0.170051 +v 0.070858 -0.029363 -0.168799 +v 0.070932 -0.030301 -0.165350 +v 0.070788 -0.037416 -0.162614 +v 0.070835 -0.030860 -0.175090 +v 0.070913 -0.030444 -0.104681 +v 0.070593 -0.036919 -0.100343 +v 0.070755 -0.037181 -0.107495 +v 0.070471 -0.034838 -0.098003 +v 0.063840 -0.044207 -0.136071 +v 0.064299 -0.046342 -0.133520 +v 0.064382 -0.044495 -0.149021 +v 0.064289 -0.019166 -0.197301 +v 0.064401 -0.037161 -0.164323 +v 0.064362 -0.036820 -0.170170 +v 0.064366 -0.032137 -0.173738 +v 0.051200 -0.016723 -0.178891 +v 0.051200 -0.030488 -0.169969 +v 0.049000 -0.019740 -0.174397 +v 0.049000 -0.016925 -0.178915 +v 0.049000 -0.030188 -0.167393 +v 0.049000 -0.030521 -0.169930 +v 0.052733 -0.023419 -0.175315 +v 0.052664 -0.015529 -0.178792 +v 0.053200 -0.030488 -0.169969 +v 0.052200 -0.030502 -0.169939 +v 0.055200 -0.030465 -0.170384 +v 0.054756 -0.015588 -0.178821 +v 0.054200 -0.030450 -0.170644 +v 0.056733 -0.023419 -0.175315 +v 0.056720 -0.015494 -0.178809 +v 0.057200 -0.030488 -0.169969 +v 0.056200 -0.030502 -0.169939 +v 0.059200 -0.030465 -0.170384 +v 0.058756 -0.015588 -0.178821 +v 0.058200 -0.030450 -0.170644 +v 0.061200 -0.030465 -0.170384 +v 0.060756 -0.015588 -0.178821 +v 0.060200 -0.030450 -0.170644 +v 0.063200 -0.030465 -0.170384 +v 0.063200 -0.015655 -0.178826 +v 0.062200 -0.030502 -0.169939 +v 0.062200 -0.016925 -0.178915 +v 0.051200 -0.034931 -0.165521 +v 0.051200 -0.034945 -0.104474 +v 0.051200 -0.043965 -0.118282 +v 0.051700 -0.044332 -0.135000 +v 0.051200 -0.046474 -0.140788 +v 0.051200 -0.040920 -0.157452 +v 0.049000 -0.041228 -0.151850 +v 0.049000 -0.031945 -0.165382 +v 0.049000 -0.034949 -0.165520 +v 0.049000 -0.043965 -0.151718 +v 0.049000 -0.043925 -0.127628 +v 0.049000 -0.046474 -0.129212 +v 0.049000 -0.040920 -0.112548 +v 0.049002 -0.032711 -0.104905 +v 0.049000 -0.034931 -0.104479 +v 0.053200 -0.034931 -0.165521 +v 0.053200 -0.034949 -0.104480 +v 0.053200 -0.043965 -0.118282 +v 0.053700 -0.044332 -0.135000 +v 0.053200 -0.046474 -0.140788 +v 0.053200 -0.040920 -0.157451 +v 0.052200 -0.034931 -0.104479 +v 0.052200 -0.034945 -0.165526 +v 0.052200 -0.043965 -0.151718 +v 0.052200 -0.046474 -0.129212 +v 0.052200 -0.040920 -0.112548 +v 0.055200 -0.034931 -0.165521 +v 0.055200 -0.034945 -0.104474 +v 0.055200 -0.043965 -0.118282 +v 0.055700 -0.044332 -0.135000 +v 0.055200 -0.046474 -0.140788 +v 0.055200 -0.040920 -0.157452 +v 0.054200 -0.034931 -0.104479 +v 0.054200 -0.034945 -0.165526 +v 0.054200 -0.043965 -0.151718 +v 0.054200 -0.046474 -0.129212 +v 0.054200 -0.040920 -0.112548 +v 0.057200 -0.034931 -0.165521 +v 0.057200 -0.034945 -0.104474 +v 0.057200 -0.043965 -0.118282 +v 0.057700 -0.044332 -0.135000 +v 0.057200 -0.046474 -0.140788 +v 0.057200 -0.040920 -0.157452 +v 0.056200 -0.034931 -0.104479 +v 0.056200 -0.034945 -0.165526 +v 0.056200 -0.043965 -0.151718 +v 0.056200 -0.046474 -0.129212 +v 0.056200 -0.040920 -0.112548 +v 0.059200 -0.034931 -0.165521 +v 0.059200 -0.034949 -0.104480 +v 0.059200 -0.043965 -0.118282 +v 0.059700 -0.044332 -0.135000 +v 0.059200 -0.046474 -0.140788 +v 0.059200 -0.040920 -0.157452 +v 0.058200 -0.034931 -0.104479 +v 0.058200 -0.034945 -0.165526 +v 0.058200 -0.043965 -0.151718 +v 0.058200 -0.046474 -0.129212 +v 0.058200 -0.040920 -0.112548 +v 0.061200 -0.034931 -0.165521 +v 0.061200 -0.034945 -0.104474 +v 0.061200 -0.043965 -0.118282 +v 0.061700 -0.044332 -0.135000 +v 0.061200 -0.046474 -0.140788 +v 0.061200 -0.040920 -0.157452 +v 0.060200 -0.034931 -0.104479 +v 0.060200 -0.034949 -0.165520 +v 0.060200 -0.043965 -0.151718 +v 0.060200 -0.046474 -0.129212 +v 0.060200 -0.040920 -0.112549 +v 0.063200 -0.034931 -0.165521 +v 0.063200 -0.034945 -0.104474 +v 0.063200 -0.043965 -0.118282 +v 0.063200 -0.046474 -0.140788 +v 0.063200 -0.040920 -0.157451 +v 0.062200 -0.034931 -0.104479 +v 0.062200 -0.034945 -0.165526 +v 0.062200 -0.043965 -0.151718 +v 0.062200 -0.046474 -0.129212 +v 0.062200 -0.040920 -0.112548 +v 0.070708 -0.043670 -0.150654 +v 0.070700 -0.019165 -0.197292 +v 0.070703 -0.044451 -0.120976 +v 0.070724 -0.046326 -0.138859 +v 0.102115 0.028626 -0.120240 +v 0.096314 0.043722 -0.122693 +v 0.096814 0.037222 -0.109719 +v 0.097964 0.040692 -0.125911 +v 0.096591 0.044040 -0.128188 +v 0.099276 0.037943 -0.128548 +v 0.097502 0.042340 -0.131800 +v 0.096014 0.045217 -0.137552 +v 0.099998 0.035574 -0.143831 +v 0.098887 0.039184 -0.131374 +v 0.095885 0.042810 -0.149803 +v 0.095754 0.036873 -0.161384 +v 0.086872 0.020399 -0.191805 +v 0.092822 0.029088 -0.176572 +v 0.096055 0.009968 -0.179349 +v 0.081393 0.014280 -0.200156 +v 0.082492 0.016905 -0.198430 +v 0.083810 -0.000095 -0.199283 +v 0.086078 0.003158 -0.196100 +v 0.089669 -0.010131 -0.190328 +v 0.081683 -0.012568 -0.200286 +v 0.086213 -0.003157 -0.195916 +v 0.082914 -0.017873 -0.197620 +v 0.100887 -0.025507 -0.156906 +v 0.096161 -0.036190 -0.161135 +v 0.097360 -0.028589 -0.165474 +v 0.099030 -0.039178 -0.131525 +v 0.096756 -0.043913 -0.130478 +v 0.096046 -0.045311 -0.138387 +v 0.096468 -0.042773 -0.120169 +v 0.097130 -0.042648 -0.126385 +v 0.099101 -0.038234 -0.127281 +v 0.096877 -0.025047 -0.097106 +v 0.097271 -0.027132 -0.099770 +v 0.101339 -0.010201 -0.100651 +v 0.097187 -0.011937 -0.091333 +v 0.097323 -0.000366 -0.089905 +v 0.100900 0.012669 -0.100454 +v 0.097196 0.013844 -0.091737 +v 0.088521 0.000083 -0.192825 +v 0.088032 -0.023080 -0.188570 +v 0.097048 0.026497 -0.098590 +v 0.095353 -0.012987 -0.179654 +v 0.093212 -0.028177 -0.176670 +v 0.096564 0.027402 -0.168720 +v 0.100111 0.015971 -0.166846 +v 0.100317 -0.013928 -0.167593 +v 0.097993 0.029521 -0.163211 +v 0.102745 0.000242 -0.162613 +v 0.098471 0.029537 -0.105848 +v 0.104605 0.007746 -0.112953 +v 0.104400 -0.013483 -0.114902 +v 0.098678 -0.029366 -0.106171 +v 0.104321 0.012137 -0.153021 +v 0.104759 -0.017271 -0.146540 +v 0.095876 -0.041642 -0.152837 +v 0.106304 -0.003799 -0.144381 +v 0.101008 -0.032590 -0.144290 +v 0.103796 0.023793 -0.141039 +v 0.105398 0.016256 -0.125610 +v 0.106505 0.008516 -0.135968 +v 0.106710 -0.005139 -0.127549 +v 0.103211 -0.025603 -0.123718 +v 0.096827 -0.036541 -0.108901 +v 0.093784 0.038346 -0.161410 +v 0.093862 0.042572 -0.153586 +v 0.082052 0.019503 -0.197086 +v 0.070863 0.030862 -0.175095 +v 0.090249 0.029800 -0.178053 +v 0.094002 0.046009 -0.142485 +v 0.094383 0.046144 -0.129765 +v 0.094244 0.044478 -0.121482 +v 0.094569 0.039586 -0.110463 +v 0.095424 0.026116 -0.096751 +v 0.095023 0.018726 -0.092482 +v 0.095139 0.010445 -0.089678 +v 0.095280 -0.001748 -0.088471 +v 0.095207 -0.015125 -0.090974 +v 0.094760 -0.025354 -0.096012 +v 0.080437 -0.014332 -0.200316 +v 0.077700 0.003234 -0.195300 +v 0.077700 -0.000264 -0.192984 +v 0.077700 -0.000716 -0.199262 +v 0.077700 -0.002899 -0.194955 +v 0.077700 0.044105 -0.129657 +v 0.077700 0.040056 -0.132094 +v 0.077700 0.038104 -0.127418 +v 0.077700 0.042335 -0.126263 +v 0.070931 0.030332 -0.104658 +v 0.096055 0.029684 -0.103341 +v 0.096107 0.031258 -0.105162 +v 0.093691 0.029503 -0.169408 +v 0.070899 0.029183 -0.167471 +v 0.095099 0.029299 -0.167481 +v 0.095592 0.031094 -0.164801 +v 0.070860 0.031520 -0.164721 +v 0.095619 0.035519 -0.106672 +v 0.095212 0.028567 -0.099581 +v 0.091812 0.030643 -0.173893 +v 0.094072 0.034613 -0.163932 +v 0.094109 -0.043336 -0.151964 +v 0.071183 -0.038644 -0.161238 +v 0.094341 -0.038522 -0.160899 +v 0.081547 -0.019703 -0.197007 +v 0.091059 -0.029997 -0.177312 +v 0.095051 -0.038414 -0.109093 +v 0.094377 -0.042518 -0.116111 +v 0.094262 -0.046204 -0.128906 +v 0.093971 -0.046095 -0.140978 +v 0.077700 -0.043667 -0.127231 +v 0.077700 -0.039457 -0.126337 +v 0.077700 -0.038013 -0.129000 +v 0.077700 -0.039601 -0.131778 +v 0.077700 -0.043194 -0.131104 +v 0.095907 -0.031281 -0.105139 +v 0.096063 -0.029690 -0.103355 +v 0.095388 -0.029958 -0.166095 +v 0.094704 -0.031684 -0.164712 +v 0.093682 -0.029349 -0.168626 +v 0.095211 -0.036046 -0.106850 +v 0.095132 -0.028519 -0.099465 +v 0.091541 -0.030657 -0.172756 +v 0.093891 -0.035375 -0.163660 +v 0.097610 -0.030159 -0.105334 +v 0.096449 -0.031954 -0.163701 +v 0.095501 -0.028407 -0.169267 +v 0.093374 -0.029509 -0.174281 +v 0.064187 -0.011744 -0.179530 +v 0.063487 -0.010965 -0.181488 +v 0.063699 -0.010897 -0.177878 +v 0.064187 -0.009589 -0.179309 +v 0.064187 -0.009819 -0.181468 +v 0.064187 -0.008577 -0.180901 +v 0.064187 -0.006784 -0.178941 +v 0.064187 -0.010409 -0.177903 +v 0.064187 -0.007540 -0.179793 +v 0.064187 -0.012669 -0.180742 +v 0.064187 -0.014954 -0.182616 +v 0.064187 -0.013464 -0.179093 +v 0.063712 -0.015446 -0.181303 +v 0.063687 -0.014572 -0.178691 +v 0.064187 -0.019158 -0.185463 +v 0.064187 -0.002550 -0.186172 +v 0.063507 -0.018047 -0.187729 +v 0.064187 -0.017646 -0.191131 +v 0.063701 -0.019646 -0.190808 +v 0.064187 -0.015686 -0.196614 +v 0.064187 -0.004703 -0.185245 +v 0.064187 -0.012374 -0.195582 +v 0.064187 -0.008391 -0.197395 +v 0.064187 -0.004850 -0.192559 +v 0.064187 -0.003072 -0.193030 +v 0.063187 -0.013201 -0.178891 +v 0.063187 -0.013120 -0.180607 +v 0.063187 -0.011684 -0.179920 +v 0.063187 -0.007804 -0.180133 +v 0.063187 -0.006843 -0.178832 +v 0.063187 -0.005323 -0.182248 +v 0.063187 -0.009555 -0.180637 +v 0.063187 -0.010601 -0.181510 +v 0.063187 -0.008940 -0.178818 +v 0.063187 -0.018700 -0.184311 +v 0.063187 -0.002099 -0.189716 +v 0.063187 -0.016036 -0.183511 +v 0.063187 -0.015062 -0.194649 +v 0.063187 -0.015947 -0.196450 +v 0.063187 -0.006804 -0.197054 +v 0.063187 -0.007740 -0.194795 +v 0.063187 -0.003635 -0.188740 +v 0.080700 -0.039739 -0.128244 +v 0.080623 -0.041038 -0.126156 +v 0.080677 -0.043663 -0.129562 +v 0.080583 -0.043173 -0.127301 +v 0.080652 -0.040142 -0.131625 +v 0.080588 -0.042411 -0.131353 +v 0.080599 -0.038572 -0.127609 +v 0.080594 -0.038393 -0.129949 +v 0.069857 -0.039639 -0.128419 +v 0.069845 -0.040646 -0.130512 +v 0.069759 -0.042434 -0.128945 +v 0.070195 -0.041387 -0.127388 +v 0.077600 -0.042057 -0.127604 +v 0.077602 -0.039515 -0.128146 +v 0.077599 -0.040322 -0.130591 +v 0.077613 -0.042399 -0.129858 +v 0.077775 -0.043256 -0.130644 +v 0.077778 -0.043538 -0.127624 +v 0.077749 -0.038009 -0.129317 +v 0.077773 -0.040826 -0.131815 +v 0.077759 -0.040456 -0.126199 +v 0.078700 -0.041890 -0.130170 +v 0.078700 -0.040110 -0.127830 +v 0.075900 -0.032896 -0.100010 +v 0.075830 -0.030781 -0.099078 +v 0.075823 -0.034308 -0.098392 +v 0.075900 -0.034924 -0.102351 +v 0.075849 -0.036990 -0.101608 +v 0.075825 -0.034305 -0.105189 +v 0.075900 -0.031882 -0.102937 +v 0.075848 -0.030060 -0.103781 +v 0.042064 -0.032351 -0.103475 +v 0.042200 -0.034688 -0.103253 +v 0.041953 -0.034564 -0.100201 +v 0.042088 -0.031303 -0.101039 +v 0.071834 -0.033413 -0.099633 +v 0.071827 -0.035329 -0.101052 +v 0.071803 -0.033992 -0.103948 +v 0.071832 -0.031448 -0.102923 +v 0.071827 -0.031340 -0.100620 +v 0.071963 -0.036758 -0.101502 +v 0.071951 -0.034544 -0.098316 +v 0.071961 -0.030523 -0.099429 +v 0.071942 -0.030129 -0.103876 +v 0.071951 -0.035035 -0.104987 +v 0.072900 -0.034712 -0.102773 +v 0.072900 -0.031623 -0.102542 +v 0.072900 -0.033368 -0.099983 +v 0.063530 0.010424 -0.181448 +v 0.064187 0.009323 -0.178959 +v 0.064187 0.009073 -0.180951 +v 0.064187 0.015979 -0.181621 +v 0.063687 0.014573 -0.178691 +v 0.064187 0.013224 -0.180614 +v 0.064187 0.013218 -0.179021 +v 0.064187 0.010870 -0.177887 +v 0.064187 0.011654 -0.179568 +v 0.064187 0.012192 -0.181448 +v 0.063674 0.006070 -0.181674 +v 0.064187 0.007770 -0.180233 +v 0.064187 0.006910 -0.178735 +v 0.064187 0.002411 -0.185947 +v 0.064187 0.019795 -0.187881 +v 0.064187 0.003635 -0.188740 +v 0.063582 0.003115 -0.192981 +v 0.064187 0.007740 -0.194795 +v 0.064187 0.017871 -0.186302 +v 0.064187 0.006931 -0.196798 +v 0.064187 0.015470 -0.194469 +v 0.064187 0.014255 -0.197316 +v 0.063616 0.019142 -0.192418 +v 0.063187 0.006784 -0.178941 +v 0.063187 0.010409 -0.177903 +v 0.063187 0.008152 -0.179063 +v 0.063187 0.010892 -0.181563 +v 0.063187 0.011797 -0.180385 +v 0.063187 0.014954 -0.182616 +v 0.063187 0.008350 -0.180769 +v 0.063187 0.009735 -0.179986 +v 0.063187 0.013851 -0.179743 +v 0.063187 0.012479 -0.178589 +v 0.063187 0.002769 -0.185241 +v 0.063187 0.004103 -0.185905 +v 0.063187 0.005822 -0.193427 +v 0.063187 0.008391 -0.197395 +v 0.063187 0.012807 -0.195561 +v 0.063187 0.014796 -0.196946 +v 0.063187 0.019263 -0.185424 +v 0.063187 0.018344 -0.189107 +v 0.002944 0.042415 -0.168123 +v 0.005292 0.046325 -0.168057 +v 0.006778 0.044718 -0.168156 +v 0.009222 0.039282 -0.168156 +v 0.012841 0.041345 -0.168144 +v 0.011804 0.038666 -0.168051 +v 0.008114 0.036877 -0.168054 +v 0.004452 0.038423 -0.168061 +v 0.008985 0.046938 -0.168044 +v 0.012161 0.044954 -0.168057 +v 0.009607 0.039325 -0.142277 +v 0.010774 0.043257 -0.142340 +v 0.005119 0.041800 -0.142200 +v 0.008504 0.044845 -0.142248 +v 0.006154 0.044319 -0.142373 +v 0.011150 0.041212 -0.162086 +v 0.007457 0.038627 -0.162061 +v 0.005845 0.039674 -0.142637 +v 0.004746 0.042819 -0.162070 +v 0.009120 0.045228 -0.162061 +v 0.011748 0.038544 -0.162228 +v 0.013042 0.042297 -0.162231 +v 0.006980 0.036886 -0.162221 +v 0.006387 0.046959 -0.162221 +v 0.003041 0.043179 -0.162228 +v 0.011316 0.045871 -0.162228 +v 0.003594 0.039610 -0.162232 +v 0.005217 0.043067 -0.163156 +v 0.008468 0.039056 -0.163156 +v 0.010315 0.043877 -0.163156 +v 0.005217 -0.033156 -0.091934 +v 0.006859 -0.033118 -0.088048 +v 0.003647 -0.033050 -0.090475 +v 0.010783 -0.033156 -0.094067 +v 0.013038 -0.033056 -0.092576 +v 0.011306 -0.033061 -0.089140 +v 0.003031 -0.033054 -0.094167 +v 0.007332 -0.033156 -0.095808 +v 0.005925 -0.033064 -0.097696 +v 0.011297 -0.033065 -0.097079 +v 0.007866 -0.007222 -0.090011 +v 0.006435 -0.007400 -0.095780 +v 0.005307 -0.007258 -0.091729 +v 0.009985 -0.007291 -0.095151 +v 0.010893 -0.007423 -0.091899 +v 0.004841 -0.027061 -0.094301 +v 0.008391 -0.027090 -0.096134 +v 0.010830 -0.027088 -0.094491 +v 0.010438 -0.027078 -0.090779 +v 0.006511 -0.027086 -0.090114 +v 0.003257 -0.027231 -0.094737 +v 0.003543 -0.027225 -0.090414 +v 0.006267 -0.027225 -0.097852 +v 0.010693 -0.027231 -0.088727 +v 0.013284 -0.027215 -0.093075 +v 0.007154 -0.027231 -0.088021 +v 0.010569 -0.027231 -0.097349 +v 0.006257 -0.028156 -0.095418 +v 0.010965 -0.028156 -0.093301 +v 0.006778 -0.028156 -0.090282 +v 0.010672 0.039711 -0.162156 +v 0.009578 0.038944 -0.160556 +v 0.011330 0.042601 -0.160556 +v 0.010217 0.044772 -0.162156 +v 0.008450 0.045521 -0.160556 +v 0.006313 0.044897 -0.162156 +v 0.004930 0.043423 -0.160556 +v 0.004542 0.041893 -0.162156 +v 0.005863 0.039204 -0.160556 +v 0.007380 0.038621 -0.162156 +v 0.006852 0.036991 -0.162156 +v 0.007000 0.036889 -0.160556 +v 0.002896 0.041000 -0.162156 +v 0.002603 0.042421 -0.160556 +v 0.004865 0.046150 -0.162156 +v 0.008166 0.047411 -0.160556 +v 0.011124 0.046349 -0.162156 +v 0.012857 0.043615 -0.160556 +v 0.012684 0.039287 -0.162156 +v 0.012125 0.038904 -0.160556 +v 0.008754 0.037067 -0.161138 +v 0.032299 0.045173 -0.162156 +v 0.035908 0.044689 -0.161356 +v 0.032390 0.045164 -0.160556 +v 0.030668 0.041229 -0.160556 +v 0.030746 0.040948 -0.162156 +v 0.034172 0.038404 -0.160556 +v 0.034246 0.038459 -0.162156 +v 0.037439 0.041619 -0.162156 +v 0.037482 0.042507 -0.160556 +v 0.036177 0.044486 -0.162156 +v 0.037325 0.045769 -0.161498 +v 0.039125 0.042583 -0.160556 +v 0.039157 0.041890 -0.162156 +v 0.037537 0.038351 -0.160556 +v 0.037202 0.038094 -0.162156 +v 0.032179 0.036964 -0.160556 +v 0.033091 0.036923 -0.162156 +v 0.029803 0.039240 -0.162156 +v 0.028890 0.041717 -0.160556 +v 0.028980 0.043184 -0.162156 +v 0.030656 0.045875 -0.160556 +v 0.032600 0.047009 -0.162156 +v 0.035706 0.046848 -0.160556 +v 0.036909 0.046108 -0.162156 +v 0.010672 -0.025556 -0.095289 +v 0.009310 -0.027156 -0.096176 +v 0.011352 -0.027156 -0.093038 +v 0.010217 -0.025556 -0.090228 +v 0.009845 -0.027156 -0.090121 +v 0.005174 -0.027156 -0.090685 +v 0.005728 -0.025556 -0.090391 +v 0.004717 -0.025556 -0.093524 +v 0.006108 -0.027156 -0.095921 +v 0.007093 -0.025556 -0.096318 +v 0.006499 -0.025556 -0.097934 +v 0.008294 -0.027156 -0.097983 +v 0.004971 -0.027156 -0.097126 +v 0.003069 -0.025556 -0.094231 +v 0.002932 -0.027156 -0.093376 +v 0.003831 -0.025556 -0.090031 +v 0.004729 -0.027156 -0.088956 +v 0.007297 -0.025556 -0.087998 +v 0.009686 -0.027156 -0.088168 +v 0.011417 -0.025556 -0.089137 +v 0.012607 -0.027156 -0.090930 +v 0.013071 -0.025556 -0.093342 +v 0.012734 -0.027156 -0.094946 +v 0.010043 -0.025556 -0.097791 +v 0.009235 -0.027156 -0.097947 +v 0.033961 -0.025556 -0.089520 +v 0.035914 -0.027156 -0.090307 +v 0.031946 -0.027156 -0.089980 +v 0.030726 -0.025556 -0.092143 +v 0.030967 -0.027156 -0.094580 +v 0.031947 -0.025556 -0.095839 +v 0.035536 -0.027156 -0.096374 +v 0.036615 -0.025556 -0.095401 +v 0.037026 -0.027156 -0.091451 +v 0.036637 -0.025556 -0.090809 +v 0.038520 -0.025556 -0.090518 +v 0.038078 -0.027156 -0.089774 +v 0.038619 -0.027156 -0.095205 +v 0.038165 -0.025556 -0.096042 +v 0.034570 -0.027156 -0.098170 +v 0.034389 -0.025556 -0.098036 +v 0.030135 -0.025556 -0.096481 +v 0.029972 -0.027156 -0.096157 +v 0.029233 -0.027156 -0.090684 +v 0.029085 -0.025556 -0.091574 +v 0.032845 -0.025556 -0.087880 +v 0.035025 -0.027156 -0.087921 +v 0.036911 -0.025556 -0.088944 +v 0.047775 0.047684 -0.160484 +v 0.038376 0.045717 -0.160748 +v 0.036021 0.047222 -0.160740 +v 0.047740 0.038051 -0.163430 +v 0.039129 0.039633 -0.162893 +v 0.036939 -0.025700 -0.087898 +v 0.039499 -0.027807 -0.095045 +v 0.047772 -0.025466 -0.087296 +v 0.047710 -0.028475 -0.097018 +v 0.006981 0.047544 -0.160615 +v 0.003108 0.045042 -0.161002 +v 0.000500 0.047486 -0.160690 +v 0.010662 0.046962 -0.160763 +v 0.030968 0.047031 -0.160719 +v 0.013706 0.043171 -0.161902 +v 0.003476 0.038416 -0.163226 +v 0.010068 0.036396 -0.163789 +v 0.000153 0.004280 -0.172497 +v 0.039452 0.007730 -0.171856 +v 0.028368 0.039837 -0.162830 +v 0.034721 0.036208 -0.163841 +v 0.042209 -0.010781 -0.089677 +v 0.047795 -0.011431 -0.089677 +v 0.047782 0.005323 -0.088486 +v 0.042127 0.003482 -0.088516 +v 0.042262 0.019425 -0.092708 +v 0.047836 0.020810 -0.093539 +v 0.047804 0.029454 -0.098714 +v 0.042173 0.029278 -0.098655 +v 0.042154 -0.036314 -0.164337 +v 0.047799 -0.036302 -0.164429 +v 0.047837 -0.042283 -0.154348 +v 0.042210 -0.042660 -0.153561 +v 0.047833 -0.046837 -0.135426 +v 0.042119 -0.046268 -0.139403 +v 0.042182 -0.044949 -0.122494 +v 0.047837 -0.042646 -0.116468 +v 0.042176 -0.036299 -0.105539 +v 0.047804 -0.036286 -0.105544 +v 0.000214 -0.025489 -0.087324 +v 0.002339 -0.027186 -0.092850 +v 0.004894 -0.025728 -0.088011 +v 0.031129 -0.025766 -0.088065 +v 0.011282 -0.025765 -0.088197 +v 0.028339 -0.027186 -0.092850 +v 0.000149 -0.037526 -0.130832 +v 0.010563 -0.028681 -0.098217 +v 0.004616 -0.028513 -0.097614 +v 0.039088 -0.036940 -0.127806 +v 0.035170 -0.028756 -0.098486 +v 0.030616 -0.028513 -0.097614 +v 0.013661 -0.027270 -0.093150 +v 0.042174 0.029453 -0.171275 +v 0.047811 0.029462 -0.171306 +v 0.042210 0.018560 -0.177660 +v 0.047833 0.010169 -0.180721 +v 0.042112 0.001998 -0.181578 +v 0.047840 -0.014134 -0.179616 +v 0.042210 -0.014802 -0.179104 +v 0.042170 -0.029460 -0.171296 +v 0.047798 -0.028673 -0.171647 +v 0.004058 -0.014028 -0.099893 +v 0.037969 -0.013656 -0.099872 +v 0.003995 -0.005170 -0.097588 +v 0.038001 -0.005152 -0.097588 +v 0.004004 0.005956 -0.097788 +v 0.038003 0.005988 -0.097793 +v 0.003999 0.016580 -0.101075 +v 0.038003 0.016629 -0.101100 +v 0.004023 0.026667 -0.108288 +v 0.038013 0.026850 -0.108440 +v 0.004006 0.033136 -0.117053 +v 0.037983 0.033202 -0.117198 +v 0.004024 0.036977 -0.127348 +v 0.037966 0.036578 -0.125956 +v 0.037972 0.037688 -0.135547 +v 0.004000 0.037417 -0.140123 +v 0.037958 0.036654 -0.143439 +v 0.004046 0.035124 -0.148676 +v 0.037989 0.035144 -0.149247 +v 0.039188 -0.000444 -0.172749 +v 0.038887 -0.010536 -0.171140 +v 0.000186 -0.011266 -0.170861 +v 0.039567 -0.020425 -0.166857 +v 0.000296 -0.025030 -0.163199 +v 0.039309 -0.028668 -0.159490 +v 0.039238 -0.034348 -0.150697 +v 0.000066 -0.034624 -0.150046 +v 0.039827 -0.036791 -0.143602 +v 0.039723 -0.037815 -0.135876 +v 0.042146 0.036262 -0.105552 +v 0.047811 0.036306 -0.105545 +v 0.042210 0.042563 -0.116238 +v 0.047880 0.044165 -0.120526 +v 0.042122 0.046539 -0.132391 +v 0.047791 0.046505 -0.133988 +v 0.047775 0.045332 -0.146189 +v 0.042332 0.045526 -0.147845 +v 0.041897 0.040959 -0.142299 +v 0.041860 0.039194 -0.149133 +v 0.041894 0.015783 -0.096311 +v 0.041904 0.027016 -0.103371 +v 0.042149 0.034127 -0.098451 +v 0.042184 0.036589 -0.100746 +v 0.041895 0.034899 -0.112226 +v 0.041876 -0.014145 -0.095747 +v 0.041983 -0.014533 -0.088582 +v 0.041890 0.041211 -0.127495 +v 0.041894 -0.002356 -0.093165 +v 0.046038 0.032247 -0.166729 +v 0.046038 0.035080 -0.167670 +v 0.046038 0.032188 -0.169963 +v 0.041668 -0.035742 -0.152144 +v 0.041911 0.034799 -0.167190 +v 0.041997 0.036413 -0.166489 +v 0.042110 0.034404 -0.171562 +v 0.042016 0.033022 -0.170279 +v 0.042237 -0.036679 -0.100976 +v 0.042034 -0.034683 -0.102888 +v 0.041860 -0.013771 -0.173158 +v 0.041767 -0.027854 -0.163776 +v 0.042084 -0.033645 -0.099902 +v 0.042198 -0.034463 -0.098498 +v 0.042120 -0.036563 -0.169036 +v 0.042202 -0.034278 -0.171611 +v 0.041904 -0.041007 -0.133965 +v 0.041794 0.005909 -0.174670 +v 0.033145 -0.025557 -0.098932 +v 0.002576 -0.025556 -0.095110 +v 0.009016 -0.025557 -0.098941 +v 0.047791 -0.016085 -0.087308 +v 0.000185 -0.015863 -0.087330 +v 0.000434 -0.013862 -0.096227 +v 0.000361 -0.000869 -0.093821 +v 0.000342 0.010927 -0.095427 +v 0.000297 0.021709 -0.100031 +v 0.000423 0.035024 -0.112957 +v 0.000301 0.040109 -0.126289 +v 0.000374 0.040919 -0.139211 +v 0.000421 0.038766 -0.148591 +v 0.013601 -0.025556 -0.093835 +v 0.039487 -0.025557 -0.094932 +v 0.028177 -0.025556 -0.093162 +v 0.037920 -0.015221 -0.099067 +v 0.004291 -0.015410 -0.098650 +v 0.040383 -0.015570 -0.087633 +v 0.000400 -0.015356 -0.095159 +v 0.040924 -0.015398 -0.095063 +v 0.031567 0.036802 -0.160557 +v 0.028399 0.041165 -0.160556 +v 0.039563 0.041513 -0.160556 +v 0.037399 0.037348 -0.160556 +v 0.000135 0.047784 -0.160100 +v 0.047773 0.047720 -0.151126 +v 0.000182 0.047652 -0.150856 +v 0.002399 0.041165 -0.160556 +v 0.005146 0.037103 -0.160556 +v 0.011243 0.037075 -0.160556 +v 0.013601 0.042835 -0.160556 +v 0.004148 0.035931 -0.150233 +v 0.037415 0.036505 -0.150479 +v 0.041067 0.047207 -0.150418 +v 0.000403 0.039671 -0.150302 +v 0.040911 0.039970 -0.150414 +v 0.047820 -0.034339 -0.171531 +v 0.047758 -0.036652 -0.169005 +v 0.047934 0.028962 -0.101311 +v 0.047848 0.039751 -0.114820 +v 0.047934 -0.028168 -0.169262 +v 0.047862 -0.015725 -0.176561 +v 0.047883 -0.036974 -0.159451 +v 0.047812 -0.042791 -0.146995 +v 0.047861 -0.044352 -0.134592 +v 0.047866 -0.000391 -0.179364 +v 0.047899 0.039792 -0.155313 +v 0.047857 -0.042158 -0.121337 +v 0.047856 -0.036084 -0.109015 +v 0.047921 0.026748 -0.170511 +v 0.047798 0.011863 -0.177803 +v 0.047781 -0.036634 -0.100837 +v 0.047686 -0.034340 -0.098365 +v 0.042028 -0.031750 -0.098599 +v 0.047763 0.034575 -0.098418 +v 0.047863 0.036578 -0.100846 +v 0.047757 0.036575 -0.169472 +v 0.042494 0.036313 -0.170097 +v 0.047702 0.033977 -0.171692 +v 0.044260 -0.034806 -0.102741 +v 0.044260 -0.031892 -0.103099 +v 0.041247 -0.031518 -0.102699 +v 0.044260 -0.031939 -0.100618 +v 0.044259 -0.034034 -0.100138 +v 0.041509 0.031721 -0.167096 +v 0.040739 -0.029528 -0.097873 +v 0.041276 -0.038809 -0.129111 +v 0.041081 -0.008081 -0.173097 +v 0.040649 0.037191 -0.164446 +v 0.047730 -0.030808 -0.098468 +v 0.047665 0.036586 -0.165613 +v 0.047885 0.044367 -0.131510 +v 0.038866 -0.033064 -0.094636 +v 0.038369 -0.033056 -0.090456 +v 0.036108 -0.033156 -0.090893 +v 0.035618 -0.033057 -0.097840 +v 0.034771 -0.033156 -0.095879 +v 0.031884 -0.033050 -0.097566 +v 0.035092 -0.033050 -0.087992 +v 0.031121 -0.033156 -0.092228 +v 0.029944 -0.033078 -0.089655 +v 0.029261 -0.033054 -0.094896 +v 0.036106 -0.007337 -0.095097 +v 0.033303 -0.007417 -0.095920 +v 0.030931 -0.007234 -0.093142 +v 0.036778 -0.007403 -0.091619 +v 0.033745 -0.007268 -0.089987 +v 0.036904 -0.027078 -0.091437 +v 0.033256 -0.027086 -0.089840 +v 0.030650 -0.027070 -0.093195 +v 0.033080 -0.027090 -0.096022 +v 0.036225 -0.027086 -0.095365 +v 0.034736 -0.027221 -0.087837 +v 0.039192 -0.027217 -0.092017 +v 0.030348 -0.027231 -0.089511 +v 0.036573 -0.027221 -0.097536 +v 0.030832 -0.027221 -0.097142 +v 0.028952 -0.027231 -0.092838 +v 0.031019 -0.028156 -0.093009 +v 0.033627 -0.028156 -0.095863 +v 0.034373 -0.028156 -0.090137 +v 0.036981 -0.028156 -0.092991 +v 0.032518 0.039414 -0.168156 +v 0.035181 0.037159 -0.168119 +v 0.031005 0.037868 -0.168057 +v 0.037421 0.045670 -0.168055 +v 0.039049 0.042579 -0.168061 +v 0.035482 0.044586 -0.168156 +v 0.028843 0.042030 -0.168061 +v 0.031074 0.045987 -0.168137 +v 0.034348 0.047065 -0.168047 +v 0.037917 0.038770 -0.168047 +v 0.032691 0.044623 -0.142222 +v 0.031081 0.042461 -0.142340 +v 0.031901 0.039887 -0.142328 +v 0.035882 0.039437 -0.142340 +v 0.036408 0.043990 -0.142316 +v 0.030730 0.041011 -0.162061 +v 0.032548 0.044851 -0.162088 +v 0.035478 0.044791 -0.162090 +v 0.037293 0.041820 -0.162078 +v 0.034671 0.038823 -0.162086 +v 0.029037 0.041060 -0.162231 +v 0.031207 0.037736 -0.162228 +v 0.030025 0.045278 -0.162225 +v 0.038923 0.042932 -0.162228 +v 0.037097 0.046049 -0.162228 +v 0.038205 0.039021 -0.162228 +v 0.034752 0.037046 -0.162228 +v 0.033611 0.046997 -0.162232 +v 0.034373 0.044863 -0.163156 +v 0.036879 0.041228 -0.163156 +v 0.031121 0.042772 -0.163156 +v 0.033627 0.039137 -0.163156 +v 0.047917 -0.013597 -0.092670 +v 0.047841 0.003938 -0.090623 +v 0.047944 -0.027395 -0.100063 +v 0.032594 0.107157 -0.123474 +v 0.033456 0.106755 -0.121312 +v 0.031965 0.107093 -0.122365 +v 0.032377 0.107363 -0.124811 +v 0.036365 0.106864 -0.125032 +v 0.033501 0.106634 -0.120453 +v 0.034049 0.107211 -0.125334 +v 0.034974 0.106397 -0.120133 +v 0.035772 0.106407 -0.121010 +v 0.036431 0.106961 -0.125832 +v 0.034466 0.107267 -0.126173 +v 0.035728 0.106313 -0.120257 +v 0.037949 0.106430 -0.123352 +v 0.037227 0.106462 -0.122870 +v 0.037512 0.106261 -0.121642 +v 0.037371 0.106726 -0.125002 +v 0.030420 0.091624 -0.124205 +v 0.031873 0.091239 -0.122761 +v 0.033121 0.091052 -0.122599 +v 0.034937 0.090946 -0.123617 +v 0.035506 0.091081 -0.125196 +v 0.034424 0.091514 -0.127374 +v 0.032411 0.091838 -0.127805 +v 0.030944 0.091924 -0.126982 +v 0.030250 0.091812 -0.125452 +v 0.030941 0.091787 -0.122825 +v 0.032487 0.103445 -0.121274 +v 0.031773 0.091611 -0.122330 +v 0.033319 0.103268 -0.120779 +v 0.034270 0.103115 -0.120576 +v 0.033213 0.091395 -0.122142 +v 0.033695 0.091343 -0.122236 +v 0.035241 0.103001 -0.120685 +v 0.036520 0.102927 -0.121402 +v 0.035308 0.091273 -0.123317 +v 0.036854 0.102931 -0.121766 +v 0.035965 0.091428 -0.125139 +v 0.037511 0.103086 -0.123588 +v 0.035653 0.091658 -0.126555 +v 0.037199 0.103316 -0.125004 +v 0.035087 0.091838 -0.127340 +v 0.036633 0.103496 -0.125789 +v 0.034716 0.091929 -0.127653 +v 0.033369 0.092178 -0.128180 +v 0.034915 0.103835 -0.126629 +v 0.032393 0.092303 -0.128149 +v 0.033939 0.103960 -0.126598 +v 0.030701 0.092401 -0.127200 +v 0.032247 0.104059 -0.125649 +v 0.029900 0.092272 -0.125435 +v 0.031446 0.103930 -0.123884 +v 0.029953 0.092136 -0.124461 +v 0.031500 0.103793 -0.122910 +v 0.030096 0.092055 -0.123996 +v 0.039383 0.103258 -0.126742 +v 0.028693 0.104230 -0.123390 +v 0.029747 0.103666 -0.120202 +v 0.032185 0.104497 -0.128880 +v 0.030014 0.104563 -0.127214 +v 0.029274 0.104507 -0.126051 +v 0.033067 0.102930 -0.117984 +v 0.034861 0.104209 -0.129384 +v 0.036844 0.103884 -0.128922 +v 0.036438 0.102514 -0.118215 +v 0.034423 0.102730 -0.117835 +v 0.038702 0.102418 -0.119751 +v 0.040179 0.102629 -0.122812 +v 0.028861 0.104771 -0.122463 +v 0.028780 0.104909 -0.123425 +v 0.029279 0.105157 -0.125784 +v 0.029495 0.105187 -0.126221 +v 0.032319 0.105157 -0.128812 +v 0.033714 0.105027 -0.129226 +v 0.034680 0.104909 -0.129304 +v 0.037019 0.104531 -0.128795 +v 0.037448 0.104445 -0.128579 +v 0.039502 0.103910 -0.126604 +v 0.040332 0.103436 -0.123867 +v 0.040292 0.103313 -0.122900 +v 0.038933 0.103084 -0.119826 +v 0.038602 0.103080 -0.119467 +v 0.037019 0.103140 -0.118340 +v 0.036573 0.103173 -0.118145 +v 0.033714 0.103506 -0.117795 +v 0.033239 0.103580 -0.117877 +v 0.030692 0.104089 -0.119164 +v 0.029745 0.104358 -0.120244 +v 0.031270 0.104419 -0.119008 +v 0.038482 0.103539 -0.119587 +v 0.038799 0.103543 -0.119930 +v 0.038490 0.104838 -0.120678 +v 0.038250 0.104829 -0.120371 +v 0.033586 0.104842 -0.118537 +v 0.032799 0.104979 -0.118779 +v 0.033537 0.106322 -0.119988 +v 0.033274 0.106373 -0.120107 +v 0.031726 0.105201 -0.119380 +v 0.031152 0.104902 -0.119456 +v 0.031192 0.106611 -0.121905 +v 0.030297 0.106113 -0.122098 +v 0.031031 0.106715 -0.122528 +v 0.030217 0.106174 -0.122475 +v 0.030723 0.106506 -0.125472 +v 0.030923 0.106524 -0.125805 +v 0.033993 0.106080 -0.128245 +v 0.034373 0.107093 -0.126621 +v 0.034662 0.107060 -0.126656 +v 0.034405 0.106032 -0.128295 +v 0.036613 0.106283 -0.127154 +v 0.036354 0.106796 -0.126363 +v 0.036611 0.106745 -0.126233 +v 0.037187 0.105583 -0.127691 +v 0.037536 0.105507 -0.127475 +v 0.037229 0.106156 -0.126809 +v 0.032421 0.105850 -0.123648 +v 0.033283 0.105448 -0.121486 +v 0.033875 0.105905 -0.125507 +v 0.036192 0.105557 -0.125206 +v 0.037053 0.105155 -0.123044 +v 0.035599 0.105101 -0.121184 +v 0.126880 -0.032968 -0.181461 +v 0.120239 -0.016066 -0.189411 +v 0.119395 -0.011192 -0.187106 +v 0.093104 0.024385 -0.203450 +v 0.000000 0.102973 -0.154371 +v 0.003317 0.102940 -0.154324 +v 0.036639 0.080923 -0.184610 +v 0.040273 0.080226 -0.183445 +v 0.036972 0.082097 -0.182440 +v 0.036665 0.082580 -0.181810 +v 0.037302 0.090477 -0.166692 +v 0.036958 0.081239 -0.183891 +v 0.037072 0.081639 -0.183150 +v 0.035527 0.083491 -0.180946 +v 0.033962 0.084121 -0.180788 +v 0.032387 0.084297 -0.181374 +v 0.031700 0.084186 -0.181937 +v 0.031225 0.083973 -0.182549 +v 0.030904 0.083648 -0.183264 +v 0.028457 0.082389 -0.186526 +v 0.030790 0.083243 -0.184001 +v 0.030890 0.082785 -0.184712 +v 0.031197 0.082307 -0.185344 +v 0.031765 0.081864 -0.185778 +v 0.036135 0.080712 -0.185259 +v 0.042733 0.068710 -0.199443 +v 0.032339 0.081416 -0.186218 +v 0.033908 0.080799 -0.186384 +v 0.035481 0.080618 -0.185795 +v 0.011164 0.084624 -0.188303 +v 0.011617 0.085444 -0.186898 +v 0.016299 0.083798 -0.188532 +v 0.011515 0.085893 -0.186184 +v 0.011199 0.086327 -0.185527 +v 0.010689 0.086717 -0.184972 +v 0.010021 0.087034 -0.184556 +v 0.009237 0.087256 -0.184306 +v 0.008397 0.087367 -0.184239 +v 0.006761 0.087233 -0.184661 +v 0.005218 0.086276 -0.186387 +v 0.005098 0.085840 -0.187108 +v 0.003947 0.084436 -0.189440 +v 0.005199 0.085393 -0.187822 +v 0.005518 0.084965 -0.188484 +v 0.005908 0.086911 -0.185282 +v 0.005553 0.086672 -0.185710 +v 0.006030 0.084585 -0.189044 +v 0.006699 0.084278 -0.189466 +v 0.008326 0.083957 -0.189788 +v 0.009959 0.084082 -0.189362 +v 0.062331 0.094086 -0.114355 +v 0.059496 0.095453 -0.118606 +v 0.048758 0.099374 -0.130163 +v 0.032738 0.103090 -0.140347 +v 0.026561 0.104052 -0.142875 +v 0.013838 0.105358 -0.146239 +v 0.000000 0.105832 -0.147444 +v 0.004378 0.060671 -0.221235 +v 0.018077 0.059964 -0.220229 +v 0.006327 0.059393 -0.222560 +v 0.033759 0.055616 -0.220313 +v 0.024756 0.057461 -0.221376 +v 0.042599 0.053163 -0.218978 +v 0.055420 0.048329 -0.216554 +v 0.082024 0.032227 -0.209618 +v 0.071042 0.040019 -0.212823 +v 0.090283 0.038747 -0.190021 +v 0.088970 0.026286 -0.207268 +v 0.102405 0.018229 -0.194686 +v 0.099625 0.015292 -0.202964 +v 0.111015 0.000184 -0.196803 +v 0.123966 -0.024582 -0.185316 +v 0.130543 -0.043625 -0.171227 +v 0.128934 -0.040594 -0.178135 +v 0.132282 -0.047713 -0.157939 +v 0.105039 0.042900 -0.106908 +v 0.105727 0.040612 -0.103222 +v 0.107539 0.034619 -0.097468 +v 0.106593 0.037745 -0.099994 +v 0.104307 0.045699 -0.121362 +v 0.104347 0.045638 -0.121006 +v 0.104326 0.045415 -0.115018 +v 0.104566 0.044506 -0.110869 +v 0.103131 0.047393 -0.127353 +v 0.098325 0.053720 -0.134123 +v 0.100341 0.051124 -0.132214 +v 0.102500 0.047159 -0.136365 +v 0.101880 0.049092 -0.130033 +v 0.103976 0.046201 -0.124286 +v 0.090287 0.063649 -0.136379 +v 0.093164 0.060148 -0.136326 +v 0.095962 0.056694 -0.135515 +v 0.078229 0.079445 -0.121037 +v 0.079263 0.078040 -0.123648 +v 0.080221 0.076357 -0.127919 +v 0.081416 0.074648 -0.130508 +v 0.082930 0.071083 -0.139079 +v 0.082993 0.072584 -0.132623 +v 0.084995 0.070081 -0.134370 +v 0.089535 0.059287 -0.153633 +v 0.087561 0.066950 -0.135721 +v 0.068732 0.088947 -0.114651 +v 0.071750 0.086224 -0.115490 +v 0.074428 0.083618 -0.116879 +v 0.076548 0.081390 -0.118691 +v 0.023505 0.083111 -0.187397 +v 0.024019 0.083376 -0.186776 +v 0.024463 0.084146 -0.185345 +v 0.024051 0.085059 -0.183990 +v 0.022893 0.085869 -0.183073 +v 0.021629 0.086290 -0.182823 +v 0.021298 0.086351 -0.182836 +v 0.020468 0.086423 -0.182999 +v 0.019693 0.086372 -0.183340 +v 0.019024 0.086203 -0.183835 +v 0.018508 0.085928 -0.184451 +v 0.018062 0.085146 -0.185876 +v 0.018476 0.084239 -0.187234 +v 0.018979 0.083815 -0.187771 +v 0.019637 0.083448 -0.188161 +v 0.020406 0.083164 -0.188377 +v 0.021234 0.082979 -0.188405 +v 0.022064 0.082906 -0.188241 +v 0.022838 0.082951 -0.187897 +v 0.057728 0.084476 -0.158147 +v 0.075398 0.076068 -0.146176 +v 0.081403 0.064669 -0.161295 +v 0.054760 0.065640 -0.195073 +v 0.066132 0.061834 -0.189654 +v 0.076712 0.057337 -0.183251 +v 0.086374 0.052203 -0.175940 +v 0.095003 0.046492 -0.167810 +v 0.099302 0.032778 -0.181522 +v 0.102495 0.040275 -0.158957 +v 0.107133 0.026279 -0.172269 +v 0.108761 0.033624 -0.149487 +v 0.113682 0.019327 -0.162371 +v 0.117234 0.004358 -0.174936 +v 0.113725 0.026619 -0.139514 +v 0.122585 -0.003192 -0.164186 +v 0.117328 0.019345 -0.129157 +v 0.126469 -0.011033 -0.153022 +v 0.108738 0.030973 -0.095454 +v 0.125991 -0.024138 -0.075700 +v 0.131383 -0.042315 -0.082210 +v 0.132121 -0.044325 -0.087652 +v 0.126853 -0.027296 -0.074944 +v 0.130161 -0.038449 -0.077929 +v 0.128553 -0.033147 -0.075340 +v 0.133326 -0.047400 -0.109594 +v 0.133048 -0.049553 -0.145187 +v 0.127432 -0.038575 -0.182548 +v 0.125334 -0.036271 -0.186776 +v 0.124930 -0.035901 -0.187386 +v 0.122414 -0.033596 -0.191187 +v 0.118642 -0.030849 -0.195573 +v 0.115008 -0.028871 -0.198892 +v 0.110965 -0.027355 -0.201776 +v 0.109812 -0.027042 -0.202458 +v 0.065936 -0.009906 -0.224830 +v 0.000000 0.009870 -0.237210 +v 0.036276 -0.000941 -0.233990 +v 0.041087 -0.002386 -0.232886 +v 0.018408 0.004402 -0.236707 +v -0.073131 0.017722 -0.231574 +v -0.090494 0.012499 -0.229865 +v -0.054960 0.020028 -0.233212 +v -0.042430 0.019759 -0.234283 +v -0.027536 0.017749 -0.235503 +v -0.036539 0.019267 -0.234776 +v -0.093790 0.010682 -0.229125 +v -0.092771 0.011457 -0.229431 +v -0.095309 0.009223 -0.228456 +v -0.101079 -0.001799 -0.221366 +v -0.099146 0.003747 -0.225441 +v -0.099036 0.003911 -0.225533 +v -0.095788 0.008762 -0.228245 +v -0.102352 -0.009852 -0.215003 +v -0.105772 -0.022632 -0.194537 +v -0.104858 -0.020349 -0.200296 +v -0.103961 -0.017339 -0.205785 +v -0.103103 -0.013696 -0.210826 +v -0.106841 -0.024318 -0.187686 +v -0.110449 -0.026360 -0.159145 +v -0.108079 -0.026494 -0.152638 +v -0.111931 -0.027074 -0.145487 +v -0.113436 -0.024442 -0.081413 +v -0.108756 -0.025544 -0.174745 +v -0.113675 -0.026658 -0.110546 +v -0.113391 -0.024159 -0.079881 +v -0.113364 -0.023642 -0.078411 +v -0.112162 -0.006847 -0.049710 +v -0.104292 0.072627 -0.053328 +v -0.111694 0.021464 -0.049935 +v -0.103183 0.075710 -0.053533 +v -0.101402 0.078502 -0.053978 +v -0.099268 0.080648 -0.054569 +v -0.096548 0.082397 -0.055364 +v -0.094378 0.083243 -0.056016 +v -0.070720 0.089693 -0.064225 +v -0.010930 0.101926 -0.097932 +v -0.012491 0.101020 -0.092963 +v -0.014769 0.100096 -0.088279 +v -0.017712 0.099173 -0.083984 +v -0.021255 0.098266 -0.080172 +v -0.025319 0.097393 -0.076926 +v -0.034634 0.095812 -0.072395 +v -0.029812 0.096570 -0.074315 +v 0.000000 0.104499 -0.113551 +v -0.001315 0.104484 -0.113465 +v -0.003992 0.104363 -0.112727 +v -0.006373 0.104125 -0.111282 +v -0.008259 0.103793 -0.109250 +v -0.009522 0.103390 -0.106769 +v 0.049796 0.099579 -0.113551 +v 0.033516 0.102282 -0.113551 +v 0.016795 0.103944 -0.113551 +v 0.053653 0.098527 -0.113804 +v 0.054572 0.098276 -0.113864 +v 0.059087 0.096211 -0.114151 +v 0.056363 0.097457 -0.113978 +v -0.045229 0.104893 -0.134662 +v 0.000000 0.107332 -0.136525 +v -0.094428 0.083666 -0.057765 +v -0.094428 0.083669 -0.057780 +v 0.008528 0.105253 -0.120084 +v 0.006900 0.105358 -0.120509 +v 0.006260 0.105437 -0.120987 +v 0.005708 0.105541 -0.121686 +v 0.005383 0.105647 -0.122462 +v 0.005273 0.105756 -0.123296 +v 0.005384 0.105858 -0.124132 +v 0.011671 0.105441 -0.122487 +v 0.011346 0.105355 -0.121708 +v 0.010155 0.105251 -0.120523 +v 0.005709 0.105948 -0.124910 +v 0.006902 0.106064 -0.126094 +v 0.006217 0.107228 -0.136250 +v 0.008530 0.106068 -0.126532 +v 0.011970 0.106946 -0.135496 +v 0.010157 0.105957 -0.126107 +v 0.016966 0.106543 -0.134411 +v 0.010831 0.105867 -0.125598 +v 0.011347 0.105763 -0.124933 +v 0.011672 0.105652 -0.124157 +v 0.011783 0.105542 -0.123323 +v 0.021515 0.104485 -0.120060 +v 0.019895 0.104671 -0.120476 +v 0.019157 0.104803 -0.121050 +v 0.018710 0.104913 -0.121645 +v 0.018387 0.105248 -0.124088 +v 0.018276 0.105151 -0.123253 +v 0.018386 0.105037 -0.122419 +v 0.032827 0.103335 -0.120523 +v 0.032176 0.103483 -0.121008 +v 0.024320 0.104447 -0.121702 +v 0.031647 0.103637 -0.121684 +v 0.031325 0.103777 -0.122456 +v 0.031326 0.103990 -0.124126 +v 0.023136 0.105110 -0.126094 +v 0.023807 0.104986 -0.125588 +v 0.024321 0.104856 -0.124926 +v 0.024644 0.104728 -0.124153 +v 0.031215 0.103897 -0.123289 +v 0.024754 0.104612 -0.123319 +v 0.024643 0.104516 -0.122483 +v 0.031648 0.104048 -0.124908 +v 0.022355 0.105217 -0.126408 +v 0.021517 0.105302 -0.126509 +v 0.017554 0.106495 -0.134283 +v 0.019897 0.105379 -0.126061 +v 0.018711 0.105322 -0.124869 +v 0.023134 0.104402 -0.120509 +v 0.032160 0.104067 -0.125583 +v 0.032829 0.104046 -0.126107 +v 0.034441 0.103888 -0.126565 +v 0.035503 0.103738 -0.126535 +v 0.035500 0.103723 -0.126403 +v 0.036052 0.103615 -0.126160 +v 0.037751 0.103228 -0.125034 +v 0.037231 0.103301 -0.125000 +v 0.037552 0.103157 -0.124229 +v 0.037661 0.103035 -0.123395 +v 0.037551 0.102944 -0.122559 +v 0.037229 0.102890 -0.121776 +v 0.036717 0.102877 -0.121099 +v 0.036050 0.102904 -0.120576 +v 0.034438 0.103067 -0.120117 +v -0.112219 -0.011057 -0.052111 +v -0.112154 -0.009956 -0.050846 +v -0.112136 -0.008498 -0.050014 +v -0.111467 0.034186 -0.059724 +v -0.104452 0.074277 -0.059731 +v -0.045973 0.103351 -0.145522 +v -0.090916 0.096004 -0.139797 +v -0.093618 0.077595 -0.176278 +v -0.093321 0.088150 -0.156362 +v -0.093234 0.089837 -0.152943 +v -0.092660 0.095616 -0.139493 +v -0.093058 0.063109 -0.198324 +v -0.091408 0.046426 -0.219006 +v -0.049860 0.055634 -0.221641 +v -0.048015 0.077040 -0.194799 +v -0.047881 0.087146 -0.178684 +v -0.111593 -0.013286 -0.159354 +v -0.104469 0.074601 -0.061132 +v -0.111310 0.045622 -0.078168 +v -0.113075 0.030935 -0.078233 +v -0.101283 0.008756 -0.220307 +v -0.100596 0.034991 -0.215738 +v -0.100635 0.037592 -0.214243 +v -0.101669 0.047241 -0.203297 +v -0.106150 0.045622 -0.179554 +v -0.102818 0.069584 -0.171589 +v -0.101917 0.088044 -0.131188 +v -0.101815 0.087438 -0.135783 +v -0.104299 0.082182 -0.096024 +v -0.107866 0.030935 -0.179974 +v -0.110627 0.030935 -0.159160 +v -0.111923 0.045622 -0.097890 +v -0.113504 0.030935 -0.118138 +v -0.114544 0.016186 -0.118259 +v -0.111654 0.016186 -0.159367 +v 0.040218 0.042462 -0.226289 +v 0.101829 -0.010039 -0.208665 +v 0.043823 0.008113 -0.231426 +v 0.029612 0.010513 -0.234380 +v 0.057676 0.004908 -0.227489 +v 0.091899 0.005276 -0.213519 +v 0.070884 0.013681 -0.221921 +v 0.088272 0.009836 -0.214899 +v 0.066354 0.029785 -0.221189 +v 0.059382 0.034101 -0.222754 +v 0.031960 0.044793 -0.227454 +v 0.023493 0.046537 -0.228399 +v 0.000000 0.048476 -0.229550 +v 0.006024 0.048353 -0.229472 +v -0.089876 0.034773 -0.226018 +v -0.076913 0.038448 -0.227042 +v -0.020549 0.019759 -0.235478 +v -0.091045 0.043994 -0.221378 +v -0.090310 0.038410 -0.224808 +v -0.090633 0.040964 -0.223515 +v -0.049257 0.050565 -0.225940 +v -0.014423 0.054159 -0.226811 +v 0.000000 0.052577 -0.227966 +v 0.114668 -0.023115 -0.199566 +v 0.118287 -0.019444 -0.195047 +v 0.122026 -0.027742 -0.191106 +v 0.006263 0.056174 -0.225554 +v 0.006161 0.052450 -0.227886 +v 0.024480 0.054274 -0.224400 +v 0.024054 0.050588 -0.226770 +v 0.041251 0.046428 -0.224563 +v 0.042055 0.050039 -0.222096 +v 0.054641 0.045267 -0.219804 +v 0.069938 0.037040 -0.216343 +v 0.068353 0.033580 -0.219171 +v 0.087478 0.023372 -0.211296 +v 0.085274 0.019976 -0.214542 +v 0.097922 0.012360 -0.207422 +v 0.095295 0.008955 -0.211010 +v 0.105998 -0.006376 -0.205901 +v 0.113974 -0.011023 -0.198634 +v 0.109135 -0.002885 -0.201850 +v 0.110592 -0.014592 -0.202921 +v -0.091997 0.097162 -0.129277 +v -0.092226 0.097163 -0.132922 +v -0.092431 0.096681 -0.136081 +v -0.090333 0.097465 -0.134531 +v -0.045679 0.104773 -0.140179 +v 0.000000 0.107241 -0.142075 +v 0.055532 0.097928 -0.115257 +v 0.045584 0.101402 -0.126002 +v 0.040965 0.102628 -0.129562 +v 0.024872 0.105620 -0.137825 +v 0.012963 0.106808 -0.140954 +v 0.006732 0.107124 -0.141775 +v -0.099123 0.009336 -0.224955 +v -0.095207 0.022265 -0.226622 +v -0.095331 0.009783 -0.228422 +v -0.094698 0.034664 -0.224252 +v -0.095614 0.044692 -0.217942 +v -0.095344 0.042606 -0.220005 +v -0.098684 0.040377 -0.217520 +v -0.095081 0.040009 -0.221900 +v -0.094903 0.037811 -0.223082 +v -0.098500 0.036616 -0.219910 +v -0.099855 0.091109 -0.137340 +v -0.096684 0.093943 -0.138625 +v -0.097714 0.075911 -0.175299 +v -0.100907 0.073131 -0.173672 +v -0.097209 0.061407 -0.197295 +v -0.100425 0.058670 -0.195464 +v -0.096527 0.094879 -0.135710 +v -0.094999 0.096127 -0.129110 +v -0.096368 0.095423 -0.129863 +v -0.098231 0.093885 -0.129736 +v -0.097678 0.094458 -0.129602 +v -0.101363 0.089624 -0.130634 +v -0.099824 0.092246 -0.130529 +v -0.096429 0.095340 -0.133005 +v -0.099757 0.092189 -0.132976 +v -0.102073 0.088349 -0.112301 +v -0.097438 0.082648 -0.057935 +v -0.103053 0.077397 -0.059026 +v -0.103349 0.081422 -0.076295 +v -0.102032 0.079031 -0.058665 +v -0.101055 0.084278 -0.075677 +v -0.100115 0.080954 -0.058262 +v -0.103691 0.076375 -0.059252 +v -0.102330 0.078498 -0.058723 +v -0.098830 0.081711 -0.058025 +v 0.019275 0.108532 -0.123492 +v 0.020142 0.108179 -0.121324 +v 0.018556 0.108507 -0.122889 +v 0.023745 0.108439 -0.125366 +v 0.023068 0.108445 -0.125022 +v 0.020187 0.108063 -0.120464 +v 0.020738 0.108664 -0.125341 +v 0.018810 0.108685 -0.124383 +v 0.022471 0.107960 -0.121004 +v 0.021158 0.108743 -0.126177 +v 0.022427 0.107864 -0.120251 +v 0.023934 0.108092 -0.122853 +v 0.024640 0.108135 -0.123583 +v 0.022178 0.108663 -0.126166 +v 0.024221 0.107908 -0.121623 +v 0.024597 0.108004 -0.122570 +v 0.018397 0.092774 -0.123498 +v 0.019829 0.092551 -0.122640 +v 0.021875 0.092446 -0.123021 +v 0.023076 0.092638 -0.125172 +v 0.021988 0.093010 -0.127359 +v 0.019963 0.093223 -0.127805 +v 0.018488 0.093228 -0.126994 +v 0.017790 0.093080 -0.125468 +v 0.018116 0.093167 -0.123181 +v 0.018462 0.093095 -0.122836 +v 0.019355 0.104821 -0.121288 +v 0.019298 0.092965 -0.122335 +v 0.020192 0.104691 -0.120787 +v 0.019768 0.092910 -0.122191 +v 0.021232 0.092804 -0.122226 +v 0.022125 0.104530 -0.120679 +v 0.022129 0.092789 -0.122631 +v 0.022854 0.092821 -0.123295 +v 0.023748 0.104547 -0.121747 +v 0.023515 0.093010 -0.125112 +v 0.024408 0.104737 -0.123564 +v 0.023202 0.093222 -0.126531 +v 0.024095 0.104948 -0.124983 +v 0.022633 0.093369 -0.127320 +v 0.023526 0.105095 -0.125773 +v 0.022259 0.093439 -0.127636 +v 0.020904 0.093614 -0.128174 +v 0.021798 0.105340 -0.126626 +v 0.019923 0.093685 -0.128150 +v 0.020817 0.105411 -0.126602 +v 0.019890 0.105438 -0.126271 +v 0.018221 0.093691 -0.127214 +v 0.019114 0.105418 -0.125666 +v 0.017415 0.093520 -0.125454 +v 0.018309 0.105247 -0.123906 +v 0.017469 0.093388 -0.124480 +v 0.018362 0.105114 -0.122933 +v 0.026291 0.105008 -0.126705 +v 0.015595 0.105301 -0.122751 +v 0.016237 0.104997 -0.120816 +v 0.019053 0.105849 -0.128898 +v 0.016125 0.105701 -0.126090 +v 0.018063 0.104593 -0.118815 +v 0.019938 0.104342 -0.117994 +v 0.021744 0.105708 -0.129382 +v 0.023738 0.105493 -0.128905 +v 0.023328 0.104111 -0.118199 +v 0.025606 0.104138 -0.119719 +v 0.027091 0.104427 -0.122768 +v 0.015671 0.105945 -0.122506 +v 0.015589 0.106079 -0.123468 +v 0.016092 0.106351 -0.125824 +v 0.016847 0.106458 -0.127070 +v 0.019150 0.106515 -0.128830 +v 0.021524 0.106397 -0.129303 +v 0.022010 0.106356 -0.129278 +v 0.023877 0.106148 -0.128778 +v 0.025802 0.105812 -0.127344 +v 0.026373 0.105666 -0.126567 +v 0.027168 0.105307 -0.124305 +v 0.027167 0.105116 -0.122857 +v 0.025800 0.104815 -0.119792 +v 0.025467 0.104794 -0.119436 +v 0.023426 0.104777 -0.118129 +v 0.022008 0.104839 -0.117784 +v 0.020073 0.105000 -0.117886 +v 0.018708 0.105169 -0.118378 +v 0.018286 0.105233 -0.118616 +v 0.016308 0.105657 -0.120692 +v 0.017379 0.106862 -0.127216 +v 0.025324 0.105246 -0.119557 +v 0.025642 0.105267 -0.119898 +v 0.026990 0.105673 -0.123756 +v 0.026951 0.105737 -0.124217 +v 0.025043 0.107871 -0.123672 +v 0.025067 0.107832 -0.123383 +v 0.025268 0.106542 -0.120650 +v 0.025027 0.106520 -0.120345 +v 0.023362 0.106862 -0.119452 +v 0.023032 0.106868 -0.119311 +v 0.023224 0.106088 -0.118753 +v 0.022011 0.106142 -0.118458 +v 0.020236 0.107753 -0.119998 +v 0.019972 0.107789 -0.120119 +v 0.019188 0.106424 -0.118966 +v 0.018827 0.106478 -0.119169 +v 0.016348 0.106666 -0.122062 +v 0.017029 0.107365 -0.122132 +v 0.017731 0.108006 -0.122558 +v 0.016948 0.107421 -0.122509 +v 0.017690 0.108051 -0.122879 +v 0.016182 0.106850 -0.123366 +v 0.018013 0.108278 -0.124778 +v 0.017658 0.107806 -0.125835 +v 0.018327 0.108329 -0.125348 +v 0.017325 0.107195 -0.126639 +v 0.018140 0.107850 -0.126444 +v 0.020568 0.108125 -0.127407 +v 0.021078 0.108563 -0.126626 +v 0.021368 0.108546 -0.126659 +v 0.021276 0.108085 -0.127517 +v 0.021991 0.108030 -0.127509 +v 0.024661 0.107095 -0.127208 +v 0.024971 0.107035 -0.126934 +v 0.025736 0.106542 -0.126546 +v 0.019175 0.107218 -0.123666 +v 0.020042 0.106865 -0.121497 +v 0.020638 0.107350 -0.125515 +v 0.022968 0.107131 -0.125195 +v 0.023834 0.106778 -0.123027 +v 0.022371 0.106646 -0.121178 +v 0.006145 0.109166 -0.123516 +v 0.007013 0.108856 -0.121342 +v 0.006244 0.108853 -0.121091 +v 0.009946 0.109213 -0.125026 +v 0.007612 0.109345 -0.125359 +v 0.006078 0.109366 -0.125064 +v 0.005679 0.109297 -0.124410 +v 0.008542 0.108644 -0.120142 +v 0.009347 0.108724 -0.121010 +v 0.010013 0.109313 -0.125826 +v 0.008033 0.109435 -0.126193 +v 0.010813 0.108903 -0.122852 +v 0.011521 0.108969 -0.123579 +v 0.010623 0.108677 -0.121019 +v 0.005293 0.093551 -0.124584 +v 0.006154 0.093336 -0.123153 +v 0.008139 0.093182 -0.122536 +v 0.009969 0.093239 -0.123531 +v 0.010544 0.093417 -0.125104 +v 0.010272 0.093585 -0.126335 +v 0.008694 0.093816 -0.127677 +v 0.007011 0.093876 -0.127646 +v 0.005946 0.093828 -0.126951 +v 0.005270 0.093832 -0.123538 +v 0.005719 0.105590 -0.122040 +v 0.005903 0.093713 -0.122793 +v 0.006741 0.093616 -0.122287 +v 0.007190 0.105374 -0.120789 +v 0.008193 0.093535 -0.122080 +v 0.008679 0.093527 -0.122168 +v 0.009127 0.105285 -0.120670 +v 0.010305 0.093600 -0.123229 +v 0.010753 0.105358 -0.121731 +v 0.010968 0.093806 -0.125043 +v 0.011416 0.105564 -0.123545 +v 0.010654 0.093999 -0.126465 +v 0.011102 0.105757 -0.124967 +v 0.010084 0.094122 -0.127257 +v 0.010532 0.105880 -0.125759 +v 0.008833 0.094266 -0.128013 +v 0.009281 0.106024 -0.126515 +v 0.007369 0.094333 -0.128102 +v 0.007818 0.106091 -0.126604 +v 0.006892 0.094335 -0.127976 +v 0.005663 0.094280 -0.127175 +v 0.006111 0.106038 -0.125677 +v 0.004855 0.094087 -0.125418 +v 0.005304 0.105845 -0.123920 +v 0.004909 0.093961 -0.124444 +v 0.013304 0.105891 -0.126678 +v 0.002528 0.105893 -0.123462 +v 0.002555 0.105979 -0.124147 +v 0.003590 0.105444 -0.120258 +v 0.006051 0.106452 -0.128911 +v 0.003116 0.106209 -0.126118 +v 0.004511 0.105280 -0.119246 +v 0.006934 0.105028 -0.117996 +v 0.011926 0.106137 -0.128192 +v 0.008748 0.106409 -0.129381 +v 0.013730 0.105205 -0.121416 +v 0.010332 0.104922 -0.118182 +v 0.009670 0.104922 -0.117985 +v 0.012614 0.105028 -0.119691 +v 0.014061 0.105621 -0.124779 +v 0.002553 0.106577 -0.123500 +v 0.002573 0.106638 -0.123984 +v 0.003057 0.106858 -0.125854 +v 0.003814 0.106987 -0.127097 +v 0.006123 0.107122 -0.128846 +v 0.006580 0.107127 -0.129016 +v 0.008502 0.107090 -0.129306 +v 0.012092 0.106786 -0.127996 +v 0.014075 0.106297 -0.124752 +v 0.014156 0.106234 -0.124275 +v 0.013792 0.105884 -0.121420 +v 0.012784 0.105711 -0.119766 +v 0.011699 0.105629 -0.118792 +v 0.010405 0.105592 -0.118115 +v 0.008983 0.105603 -0.117778 +v 0.007044 0.105691 -0.117890 +v 0.006118 0.105764 -0.118185 +v 0.003524 0.106133 -0.120305 +v 0.003055 0.106259 -0.121151 +v 0.011177 0.106060 -0.118693 +v 0.011572 0.106077 -0.118943 +v 0.013962 0.106595 -0.123728 +v 0.013923 0.106656 -0.124189 +v 0.011934 0.108720 -0.123664 +v 0.011958 0.108682 -0.123375 +v 0.013695 0.106945 -0.123224 +v 0.010911 0.108388 -0.120749 +v 0.010694 0.108371 -0.120554 +v 0.009354 0.106894 -0.118520 +v 0.009249 0.107664 -0.119114 +v 0.008941 0.106902 -0.118457 +v 0.008536 0.107681 -0.119037 +v 0.006102 0.108221 -0.120157 +v 0.005617 0.108294 -0.120588 +v 0.004566 0.107720 -0.120760 +v 0.005212 0.108374 -0.121094 +v 0.004192 0.107820 -0.121435 +v 0.003135 0.107426 -0.123838 +v 0.003191 0.107480 -0.124275 +v 0.003856 0.108170 -0.124078 +v 0.004193 0.108298 -0.125186 +v 0.004002 0.107708 -0.126310 +v 0.004568 0.108370 -0.125864 +v 0.004262 0.107744 -0.126667 +v 0.007674 0.109255 -0.126585 +v 0.007962 0.109251 -0.126641 +v 0.010546 0.108038 -0.127858 +v 0.009958 0.109138 -0.126357 +v 0.010217 0.109112 -0.126224 +v 0.011600 0.107914 -0.127198 +v 0.006095 0.107848 -0.123684 +v 0.006962 0.107538 -0.121510 +v 0.007561 0.108027 -0.125526 +v 0.009896 0.107895 -0.125194 +v 0.010763 0.107585 -0.123020 +v 0.009297 0.107407 -0.121178 +v 0.032884 0.085071 -0.186142 +v 0.033455 0.086122 -0.184106 +v 0.032144 0.085379 -0.186034 +v 0.032146 0.085778 -0.185377 +v 0.032681 0.084512 -0.187169 +v 0.036695 0.083623 -0.186465 +v 0.033396 0.086586 -0.183374 +v 0.034504 0.083821 -0.187321 +v 0.034774 0.086531 -0.182722 +v 0.035647 0.085923 -0.183249 +v 0.036855 0.083173 -0.187118 +v 0.035005 0.083295 -0.187915 +v 0.037267 0.084674 -0.184428 +v 0.037395 0.085303 -0.183325 +v 0.037934 0.083786 -0.185527 +v 0.028372 0.072944 -0.177246 +v 0.029597 0.073509 -0.175657 +v 0.031592 0.073148 -0.175174 +v 0.032646 0.072558 -0.175575 +v 0.033381 0.071601 -0.176750 +v 0.032600 0.070575 -0.178858 +v 0.030715 0.070656 -0.179744 +v 0.029206 0.071338 -0.179437 +v 0.028357 0.072287 -0.178335 +v 0.028774 0.073936 -0.176217 +v 0.031977 0.083693 -0.182153 +v 0.029515 0.074077 -0.175585 +v 0.032719 0.083834 -0.181522 +v 0.031352 0.073826 -0.175006 +v 0.034556 0.083583 -0.180942 +v 0.031817 0.073660 -0.175027 +v 0.033032 0.072979 -0.175491 +v 0.036236 0.082736 -0.181427 +v 0.033881 0.071876 -0.176846 +v 0.037085 0.081633 -0.182782 +v 0.033750 0.071147 -0.178114 +v 0.036954 0.080904 -0.184050 +v 0.033299 0.070806 -0.178920 +v 0.036503 0.080562 -0.184856 +v 0.032980 0.070692 -0.179278 +v 0.031747 0.070614 -0.180072 +v 0.034950 0.080371 -0.186008 +v 0.030805 0.070785 -0.180300 +v 0.034008 0.080542 -0.186236 +v 0.033537 0.080689 -0.186249 +v 0.029064 0.071572 -0.179946 +v 0.032268 0.081329 -0.185882 +v 0.031929 0.081590 -0.185636 +v 0.028084 0.072667 -0.178675 +v 0.031287 0.082424 -0.184612 +v 0.028019 0.073192 -0.177846 +v 0.031223 0.082949 -0.183782 +v 0.028101 0.073426 -0.177419 +v 0.028687 0.082748 -0.185482 +v 0.028732 0.084160 -0.183137 +v 0.032593 0.079565 -0.188606 +v 0.030306 0.080821 -0.187775 +v 0.031967 0.079835 -0.188499 +v 0.029563 0.084934 -0.181416 +v 0.032143 0.085407 -0.179246 +v 0.038124 0.079001 -0.186548 +v 0.034567 0.078978 -0.188504 +v 0.035413 0.084751 -0.178560 +v 0.037773 0.083551 -0.179257 +v 0.039670 0.080191 -0.183758 +v 0.039558 0.081639 -0.181437 +v 0.028860 0.084604 -0.183686 +v 0.028780 0.084373 -0.184108 +v 0.028854 0.083346 -0.185757 +v 0.029538 0.082242 -0.187203 +v 0.030409 0.081437 -0.188056 +v 0.032376 0.080287 -0.188884 +v 0.034683 0.079547 -0.188856 +v 0.036507 0.079338 -0.188215 +v 0.038427 0.079594 -0.186758 +v 0.039778 0.080589 -0.184394 +v 0.039877 0.080813 -0.183972 +v 0.039786 0.082094 -0.181916 +v 0.039651 0.082369 -0.181536 +v 0.038113 0.083995 -0.179694 +v 0.037751 0.084244 -0.179480 +v 0.035642 0.085289 -0.178901 +v 0.034244 0.085705 -0.178971 +v 0.032404 0.085959 -0.179546 +v 0.031971 0.085966 -0.179769 +v 0.029815 0.085525 -0.181657 +v 0.029326 0.085209 -0.182440 +v 0.034782 0.080026 -0.188854 +v 0.039323 0.083161 -0.182808 +v 0.039510 0.082820 -0.182511 +v 0.039388 0.083070 -0.182166 +v 0.039061 0.083634 -0.182173 +v 0.038629 0.084197 -0.182847 +v 0.038096 0.084804 -0.182138 +v 0.037871 0.084999 -0.181938 +v 0.034985 0.086149 -0.180239 +v 0.035182 0.086413 -0.181667 +v 0.034583 0.086250 -0.180289 +v 0.034243 0.086608 -0.181854 +v 0.033009 0.086468 -0.180781 +v 0.031620 0.086371 -0.181690 +v 0.031923 0.086478 -0.182060 +v 0.032316 0.086530 -0.183023 +v 0.031265 0.085756 -0.184862 +v 0.029511 0.084891 -0.184503 +v 0.030327 0.085304 -0.184851 +v 0.031185 0.085439 -0.185426 +v 0.030295 0.085110 -0.185187 +v 0.029474 0.084670 -0.184886 +v 0.032128 0.084428 -0.187124 +v 0.030557 0.083288 -0.187331 +v 0.030779 0.083054 -0.187596 +v 0.032458 0.084102 -0.187480 +v 0.034649 0.082955 -0.188184 +v 0.034332 0.080130 -0.188927 +v 0.034930 0.082877 -0.188160 +v 0.034874 0.080506 -0.188817 +v 0.032525 0.083977 -0.185477 +v 0.033096 0.085028 -0.183441 +v 0.034145 0.082728 -0.186656 +v 0.036336 0.082529 -0.185799 +v 0.036908 0.083580 -0.183763 +v 0.035288 0.084830 -0.182584 +v 0.019665 0.087281 -0.188219 +v 0.020248 0.088391 -0.186218 +v 0.018888 0.087663 -0.187857 +v 0.019466 0.088588 -0.186160 +v 0.019459 0.086700 -0.189233 +v 0.024271 0.085923 -0.188887 +v 0.023565 0.086162 -0.188735 +v 0.021324 0.086166 -0.189477 +v 0.021597 0.088921 -0.184905 +v 0.022490 0.088387 -0.185475 +v 0.021335 0.085784 -0.190095 +v 0.024148 0.087272 -0.186734 +v 0.024929 0.086823 -0.187204 +v 0.022835 0.085609 -0.189878 +v 0.024279 0.087918 -0.185640 +v 0.016601 0.074666 -0.179435 +v 0.017576 0.075481 -0.177783 +v 0.019134 0.075552 -0.177148 +v 0.021045 0.074868 -0.177621 +v 0.021798 0.073970 -0.178830 +v 0.021001 0.072866 -0.180892 +v 0.019073 0.072778 -0.181679 +v 0.017529 0.073331 -0.181296 +v 0.018400 0.085284 -0.185349 +v 0.016744 0.075745 -0.178426 +v 0.018790 0.085698 -0.184545 +v 0.017396 0.076029 -0.177745 +v 0.017799 0.076114 -0.177473 +v 0.019845 0.086067 -0.183593 +v 0.019193 0.076111 -0.177011 +v 0.019678 0.076025 -0.176989 +v 0.021724 0.085978 -0.183108 +v 0.021398 0.075322 -0.177558 +v 0.023443 0.085275 -0.183678 +v 0.022267 0.074286 -0.178952 +v 0.024313 0.084239 -0.185072 +v 0.022134 0.073540 -0.180210 +v 0.024180 0.083493 -0.186330 +v 0.021673 0.073155 -0.180990 +v 0.023719 0.083108 -0.187110 +v 0.021347 0.073012 -0.181332 +v 0.020086 0.072823 -0.182060 +v 0.022132 0.082776 -0.188180 +v 0.019122 0.072911 -0.182240 +v 0.021168 0.082864 -0.188359 +v 0.017341 0.073548 -0.181798 +v 0.019387 0.083502 -0.187918 +v 0.018752 0.083986 -0.187342 +v 0.016337 0.074565 -0.180481 +v 0.018383 0.084518 -0.186601 +v 0.016270 0.075089 -0.179651 +v 0.016354 0.075331 -0.179229 +v 0.026541 0.082391 -0.187332 +v 0.015636 0.085704 -0.185590 +v 0.019722 0.081753 -0.190650 +v 0.016512 0.083499 -0.188883 +v 0.016916 0.083148 -0.189320 +v 0.017037 0.087115 -0.182827 +v 0.018635 0.087543 -0.181596 +v 0.022416 0.081285 -0.190510 +v 0.024310 0.081392 -0.189702 +v 0.022598 0.087232 -0.180777 +v 0.020569 0.087584 -0.180883 +v 0.025014 0.086234 -0.181593 +v 0.026991 0.084091 -0.184417 +v 0.026842 0.084466 -0.183857 +v 0.015747 0.086249 -0.185974 +v 0.015744 0.085485 -0.187218 +v 0.016524 0.084168 -0.189098 +v 0.018155 0.082998 -0.190456 +v 0.019886 0.082305 -0.191006 +v 0.022269 0.081867 -0.190921 +v 0.024508 0.081973 -0.190000 +v 0.024903 0.082060 -0.189727 +v 0.026681 0.082983 -0.187632 +v 0.027100 0.083652 -0.186402 +v 0.027005 0.084935 -0.184348 +v 0.026230 0.085982 -0.182905 +v 0.025291 0.086702 -0.182047 +v 0.022763 0.087785 -0.181131 +v 0.021332 0.088080 -0.181129 +v 0.020853 0.088136 -0.181199 +v 0.017103 0.087658 -0.183230 +v 0.026832 0.083839 -0.187003 +v 0.026929 0.084063 -0.186605 +v 0.026142 0.085044 -0.187471 +v 0.025306 0.086557 -0.187042 +v 0.025974 0.086148 -0.186371 +v 0.025295 0.086712 -0.186794 +v 0.021555 0.088643 -0.182465 +v 0.021512 0.088946 -0.184424 +v 0.020738 0.088720 -0.182613 +v 0.021227 0.088967 -0.184486 +v 0.019136 0.088708 -0.185079 +v 0.018715 0.088512 -0.185537 +v 0.016370 0.086367 -0.187165 +v 0.016406 0.086130 -0.187538 +v 0.018000 0.085442 -0.189547 +v 0.018250 0.084064 -0.190283 +v 0.018784 0.084879 -0.190200 +v 0.018597 0.083871 -0.190480 +v 0.021214 0.085374 -0.190333 +v 0.022074 0.085216 -0.190303 +v 0.024609 0.083493 -0.189819 +v 0.025491 0.083819 -0.188995 +v 0.019436 0.086165 -0.187533 +v 0.020019 0.087276 -0.185532 +v 0.021095 0.085051 -0.188791 +v 0.023336 0.085047 -0.188049 +v 0.023919 0.086157 -0.186048 +v 0.022261 0.087272 -0.184790 +v 0.005389 0.087619 -0.190022 +v 0.005971 0.087864 -0.189597 +v 0.005257 0.088612 -0.188558 +v 0.006577 0.089108 -0.187683 +v 0.010630 0.086907 -0.190534 +v 0.009917 0.087086 -0.190342 +v 0.007640 0.086853 -0.190926 +v 0.008853 0.089341 -0.187099 +v 0.006692 0.086697 -0.191256 +v 0.009865 0.086566 -0.191121 +v 0.009219 0.089673 -0.186567 +v 0.009910 0.089454 -0.186821 +v 0.007449 0.089788 -0.186581 +v 0.010523 0.088330 -0.188428 +v 0.009167 0.086420 -0.191411 +v 0.011148 0.088506 -0.188103 +v 0.004774 0.075641 -0.179813 +v 0.006054 0.076496 -0.178408 +v 0.008521 0.076407 -0.178283 +v 0.009711 0.075687 -0.179231 +v 0.009840 0.074520 -0.180953 +v 0.009142 0.073960 -0.181858 +v 0.007183 0.073663 -0.182505 +v 0.005622 0.074087 -0.182036 +v 0.004750 0.074932 -0.180869 +v 0.005108 0.076742 -0.178875 +v 0.005796 0.086569 -0.185483 +v 0.005880 0.077044 -0.178345 +v 0.006805 0.077185 -0.178040 +v 0.007494 0.087012 -0.184648 +v 0.007788 0.077150 -0.177990 +v 0.008476 0.086976 -0.184598 +v 0.008726 0.076942 -0.178201 +v 0.009524 0.076583 -0.178652 +v 0.010213 0.086410 -0.185260 +v 0.010100 0.076110 -0.179295 +v 0.010394 0.075572 -0.180065 +v 0.011082 0.085399 -0.186673 +v 0.010376 0.075024 -0.180882 +v 0.011064 0.084850 -0.187490 +v 0.010249 0.074764 -0.181282 +v 0.009776 0.074305 -0.182013 +v 0.010465 0.084132 -0.188621 +v 0.009443 0.074118 -0.182326 +v 0.008624 0.073854 -0.182804 +v 0.009312 0.083681 -0.189412 +v 0.008364 0.083584 -0.189655 +v 0.007183 0.073775 -0.183072 +v 0.007871 0.083601 -0.189680 +v 0.005382 0.074265 -0.182531 +v 0.006071 0.084091 -0.189139 +v 0.004376 0.075240 -0.181185 +v 0.005064 0.085067 -0.187793 +v 0.004315 0.075791 -0.180372 +v 0.005003 0.085618 -0.186980 +v 0.004403 0.076058 -0.179966 +v 0.013320 0.083668 -0.189013 +v 0.002259 0.085271 -0.187782 +v 0.002937 0.087099 -0.184992 +v 0.006388 0.082265 -0.191822 +v 0.003151 0.083783 -0.189901 +v 0.005989 0.088442 -0.182677 +v 0.008434 0.082038 -0.191947 +v 0.009118 0.082053 -0.191853 +v 0.011043 0.082368 -0.191184 +v 0.009380 0.088404 -0.182381 +v 0.011820 0.087597 -0.183326 +v 0.013753 0.084378 -0.187913 +v 0.013654 0.085909 -0.185645 +v 0.002324 0.086575 -0.187047 +v 0.002311 0.085760 -0.188260 +v 0.003087 0.084442 -0.190140 +v 0.003353 0.084201 -0.190471 +v 0.005566 0.083052 -0.191949 +v 0.006476 0.082814 -0.192208 +v 0.009369 0.082626 -0.192186 +v 0.010298 0.082745 -0.191912 +v 0.011165 0.082951 -0.191516 +v 0.013385 0.084256 -0.189343 +v 0.013568 0.084500 -0.188962 +v 0.013739 0.086369 -0.186164 +v 0.013602 0.086637 -0.185780 +v 0.012021 0.088069 -0.183815 +v 0.011649 0.088262 -0.183567 +v 0.009469 0.088954 -0.182765 +v 0.007050 0.089111 -0.182784 +v 0.006110 0.089014 -0.183025 +v 0.004811 0.088706 -0.183619 +v 0.002901 0.087583 -0.185489 +v 0.013356 0.084907 -0.189133 +v 0.010651 0.083316 -0.191781 +v 0.010227 0.083227 -0.191957 +v 0.013495 0.085149 -0.188759 +v 0.012665 0.086265 -0.189221 +v 0.011316 0.088909 -0.185429 +v 0.011018 0.089064 -0.185231 +v 0.007351 0.089741 -0.184606 +v 0.006601 0.089664 -0.184799 +v 0.005159 0.089126 -0.184432 +v 0.004804 0.088995 -0.184664 +v 0.005254 0.089303 -0.185476 +v 0.003750 0.088134 -0.187371 +v 0.002898 0.087189 -0.187547 +v 0.003582 0.087718 -0.188007 +v 0.002858 0.086945 -0.187915 +v 0.003726 0.086635 -0.189602 +v 0.004480 0.087241 -0.189756 +v 0.004584 0.087063 -0.190009 +v 0.004402 0.085825 -0.190737 +v 0.005498 0.085161 -0.191610 +v 0.005967 0.086003 -0.191441 +v 0.006240 0.085891 -0.191579 +v 0.006028 0.085465 -0.191693 +v 0.009941 0.084664 -0.191887 +v 0.010632 0.084828 -0.191570 +v 0.010947 0.086542 -0.190611 +v 0.012227 0.085684 -0.190132 +v 0.011274 0.086796 -0.190198 +v 0.005893 0.086762 -0.188856 +v 0.006500 0.088006 -0.186943 +v 0.007563 0.085752 -0.190185 +v 0.009839 0.085985 -0.189601 +v 0.010446 0.087229 -0.187688 +v 0.008776 0.088240 -0.186359 +v 0.032594 0.107157 0.123474 +v 0.033456 0.106755 0.121312 +v 0.031965 0.107093 0.122365 +v 0.032377 0.107363 0.124811 +v 0.036365 0.106864 0.125032 +v 0.033501 0.106634 0.120453 +v 0.034049 0.107211 0.125334 +v 0.035772 0.106407 0.121010 +v 0.036431 0.106961 0.125832 +v 0.034466 0.107267 0.126173 +v 0.035728 0.106313 0.120257 +v 0.037949 0.106430 0.123352 +v 0.037227 0.106462 0.122870 +v 0.037512 0.106261 0.121642 +v 0.030420 0.091624 0.124205 +v 0.031873 0.091239 0.122761 +v 0.033121 0.091052 0.122599 +v 0.034937 0.090946 0.123617 +v 0.035506 0.091081 0.125196 +v 0.035236 0.091280 0.126423 +v 0.033669 0.091663 0.127743 +v 0.031612 0.091905 0.127512 +v 0.030473 0.091891 0.126271 +v 0.030941 0.091787 0.122825 +v 0.032487 0.103445 0.121274 +v 0.031773 0.091611 0.122330 +v 0.033319 0.103268 0.120779 +v 0.033213 0.091395 0.122142 +v 0.033695 0.091343 0.122236 +v 0.035241 0.103001 0.120685 +v 0.035308 0.091273 0.123317 +v 0.036854 0.102931 0.121766 +v 0.035965 0.091428 0.125139 +v 0.037511 0.103086 0.123588 +v 0.035653 0.091658 0.126555 +v 0.037199 0.103316 0.125004 +v 0.035087 0.091838 0.127340 +v 0.036633 0.103496 0.125789 +v 0.036262 0.103586 0.126102 +v 0.035845 0.103675 0.126350 +v 0.033846 0.092101 0.128078 +v 0.033369 0.092178 0.128180 +v 0.034915 0.103835 0.126629 +v 0.032393 0.092303 0.128149 +v 0.033939 0.103960 0.126598 +v 0.031472 0.092380 0.127811 +v 0.030701 0.092401 0.127200 +v 0.032247 0.104059 0.125649 +v 0.030158 0.092364 0.126380 +v 0.029900 0.092272 0.125435 +v 0.031446 0.103930 0.123884 +v 0.029953 0.092136 0.124461 +v 0.031500 0.103793 0.122910 +v 0.030096 0.092055 0.123996 +v 0.039383 0.103258 0.126742 +v 0.028693 0.104230 0.123390 +v 0.029747 0.103666 0.120202 +v 0.032185 0.104497 0.128880 +v 0.030014 0.104563 0.127214 +v 0.029274 0.104507 0.126051 +v 0.033067 0.102930 0.117984 +v 0.037451 0.103763 0.128615 +v 0.034861 0.104209 0.129384 +v 0.036844 0.103884 0.128922 +v 0.036438 0.102514 0.118215 +v 0.038702 0.102418 0.119751 +v 0.040179 0.102629 0.122812 +v 0.028861 0.104771 0.122463 +v 0.028780 0.104909 0.123425 +v 0.029279 0.105157 0.125784 +v 0.029495 0.105187 0.126221 +v 0.032319 0.105157 0.128812 +v 0.033714 0.105027 0.129226 +v 0.034680 0.104909 0.129304 +v 0.037019 0.104531 0.128795 +v 0.037448 0.104445 0.128579 +v 0.039502 0.103910 0.126604 +v 0.040332 0.103436 0.123867 +v 0.040292 0.103313 0.122900 +v 0.038933 0.103084 0.119826 +v 0.038602 0.103080 0.119467 +v 0.037019 0.103140 0.118340 +v 0.036573 0.103173 0.118145 +v 0.033714 0.103506 0.117795 +v 0.033239 0.103580 0.117877 +v 0.030692 0.104089 0.119164 +v 0.029745 0.104358 0.120244 +v 0.031270 0.104419 0.119008 +v 0.038482 0.103539 0.119587 +v 0.038799 0.103543 0.119930 +v 0.038490 0.104838 0.120678 +v 0.038250 0.104829 0.120371 +v 0.033586 0.104842 0.118537 +v 0.032799 0.104979 0.118779 +v 0.033537 0.106322 0.119988 +v 0.033274 0.106373 0.120107 +v 0.031726 0.105201 0.119380 +v 0.031152 0.104902 0.119456 +v 0.031192 0.106611 0.121905 +v 0.030297 0.106113 0.122098 +v 0.031031 0.106715 0.122528 +v 0.030217 0.106174 0.122475 +v 0.030723 0.106506 0.125472 +v 0.030923 0.106524 0.125805 +v 0.033993 0.106080 0.128245 +v 0.034373 0.107093 0.126621 +v 0.034662 0.107060 0.126656 +v 0.034405 0.106032 0.128295 +v 0.036613 0.106283 0.127154 +v 0.036354 0.106796 0.126363 +v 0.036611 0.106745 0.126233 +v 0.037187 0.105583 0.127691 +v 0.037536 0.105507 0.127475 +v 0.037229 0.106156 0.126809 +v 0.032421 0.105850 0.123648 +v 0.033283 0.105448 0.121486 +v 0.033875 0.105905 0.125507 +v 0.036192 0.105557 0.125206 +v 0.037053 0.105155 0.123044 +v 0.035599 0.105101 0.121184 +v 0.126880 -0.032968 0.181461 +v 0.120239 -0.016066 0.189411 +v 0.119395 -0.011192 0.187106 +v 0.093104 0.024385 0.203450 +v 0.000000 0.102973 0.154371 +v 0.003317 0.102940 0.154324 +v 0.036639 0.080923 0.184610 +v 0.040273 0.080226 0.183445 +v 0.036972 0.082097 0.182440 +v 0.036665 0.082580 0.181810 +v 0.037302 0.090477 0.166692 +v 0.036958 0.081239 0.183891 +v 0.037072 0.081639 0.183150 +v 0.035527 0.083491 0.180946 +v 0.033962 0.084121 0.180788 +v 0.032387 0.084297 0.181374 +v 0.031700 0.084186 0.181937 +v 0.031225 0.083973 0.182549 +v 0.030904 0.083648 0.183264 +v 0.028457 0.082389 0.186526 +v 0.030790 0.083243 0.184001 +v 0.030890 0.082785 0.184712 +v 0.031197 0.082307 0.185344 +v 0.031765 0.081864 0.185778 +v 0.036135 0.080712 0.185259 +v 0.042733 0.068710 0.199443 +v 0.032339 0.081416 0.186218 +v 0.033908 0.080799 0.186384 +v 0.035481 0.080618 0.185795 +v 0.011164 0.084624 0.188303 +v 0.011617 0.085444 0.186898 +v 0.016299 0.083798 0.188532 +v 0.011515 0.085893 0.186184 +v 0.011199 0.086327 0.185527 +v 0.010689 0.086717 0.184972 +v 0.010021 0.087034 0.184556 +v 0.009237 0.087256 0.184306 +v 0.008397 0.087367 0.184239 +v 0.006761 0.087233 0.184661 +v 0.005218 0.086276 0.186387 +v 0.005098 0.085840 0.187108 +v 0.003947 0.084436 0.189440 +v 0.005199 0.085393 0.187822 +v 0.005518 0.084965 0.188484 +v 0.005908 0.086911 0.185282 +v 0.005553 0.086672 0.185710 +v 0.006030 0.084585 0.189044 +v 0.006699 0.084278 0.189466 +v 0.008326 0.083957 0.189788 +v 0.009959 0.084082 0.189362 +v 0.062331 0.094086 0.114355 +v 0.059496 0.095453 0.118606 +v 0.048758 0.099374 0.130163 +v 0.032738 0.103090 0.140347 +v 0.026561 0.104052 0.142875 +v 0.013838 0.105358 0.146239 +v 0.000000 0.105832 0.147444 +v 0.004378 0.060671 0.221235 +v 0.018077 0.059964 0.220229 +v 0.006327 0.059393 0.222560 +v 0.033759 0.055616 0.220313 +v 0.024756 0.057461 0.221376 +v 0.042599 0.053163 0.218978 +v 0.055420 0.048329 0.216554 +v 0.082024 0.032227 0.209618 +v 0.071042 0.040019 0.212823 +v 0.090283 0.038747 0.190021 +v 0.088970 0.026286 0.207268 +v 0.102405 0.018229 0.194686 +v 0.099625 0.015292 0.202964 +v 0.111015 0.000184 0.196803 +v 0.123966 -0.024582 0.185316 +v 0.130543 -0.043625 0.171227 +v 0.128934 -0.040594 0.178135 +v 0.132282 -0.047713 0.157939 +v 0.105039 0.042900 0.106908 +v 0.105727 0.040612 0.103222 +v 0.107539 0.034619 0.097468 +v 0.106593 0.037745 0.099994 +v 0.104307 0.045699 0.121362 +v 0.104347 0.045638 0.121006 +v 0.104326 0.045415 0.115018 +v 0.104566 0.044506 0.110869 +v 0.103131 0.047393 0.127353 +v 0.098325 0.053720 0.134123 +v 0.100341 0.051124 0.132214 +v 0.102500 0.047159 0.136365 +v 0.101880 0.049092 0.130033 +v 0.103976 0.046201 0.124286 +v 0.090287 0.063649 0.136379 +v 0.093164 0.060148 0.136326 +v 0.095962 0.056694 0.135515 +v 0.078229 0.079445 0.121037 +v 0.079263 0.078040 0.123648 +v 0.080221 0.076357 0.127919 +v 0.081416 0.074648 0.130508 +v 0.082930 0.071083 0.139079 +v 0.082993 0.072584 0.132623 +v 0.084995 0.070081 0.134370 +v 0.089535 0.059287 0.153633 +v 0.087561 0.066950 0.135721 +v 0.068732 0.088947 0.114651 +v 0.071750 0.086224 0.115490 +v 0.074428 0.083618 0.116879 +v 0.076548 0.081390 0.118691 +v 0.023505 0.083111 0.187397 +v 0.024019 0.083376 0.186776 +v 0.024463 0.084146 0.185345 +v 0.024051 0.085059 0.183990 +v 0.022893 0.085869 0.183073 +v 0.021629 0.086290 0.182823 +v 0.021298 0.086351 0.182836 +v 0.020468 0.086423 0.182999 +v 0.019693 0.086372 0.183340 +v 0.019024 0.086203 0.183835 +v 0.018508 0.085928 0.184451 +v 0.018062 0.085146 0.185876 +v 0.018476 0.084239 0.187234 +v 0.018979 0.083815 0.187771 +v 0.019637 0.083448 0.188161 +v 0.020406 0.083164 0.188377 +v 0.021234 0.082979 0.188405 +v 0.022064 0.082906 0.188241 +v 0.022838 0.082951 0.187897 +v 0.057728 0.084476 0.158147 +v 0.075398 0.076068 0.146176 +v 0.081403 0.064669 0.161295 +v 0.054760 0.065640 0.195073 +v 0.066132 0.061834 0.189654 +v 0.076712 0.057337 0.183251 +v 0.086374 0.052203 0.175940 +v 0.095003 0.046492 0.167810 +v 0.099302 0.032778 0.181522 +v 0.102495 0.040275 0.158957 +v 0.107133 0.026279 0.172269 +v 0.108761 0.033624 0.149487 +v 0.113682 0.019327 0.162371 +v 0.117234 0.004358 0.174936 +v 0.113725 0.026619 0.139514 +v 0.122585 -0.003192 0.164186 +v 0.117328 0.019345 0.129157 +v 0.126469 -0.011033 0.153022 +v 0.108738 0.030973 0.095454 +v 0.125991 -0.024138 0.075700 +v 0.131383 -0.042315 0.082210 +v 0.132121 -0.044325 0.087652 +v 0.126853 -0.027296 0.074944 +v 0.130161 -0.038449 0.077929 +v 0.128553 -0.033147 0.075340 +v 0.133326 -0.047400 0.109594 +v 0.133048 -0.049553 0.145187 +v 0.127432 -0.038575 0.182548 +v 0.125334 -0.036271 0.186776 +v 0.124930 -0.035901 0.187386 +v 0.122414 -0.033596 0.191187 +v 0.118642 -0.030849 0.195573 +v 0.115008 -0.028871 0.198892 +v 0.110965 -0.027355 0.201776 +v 0.109812 -0.027042 0.202458 +v 0.065936 -0.009906 0.224830 +v 0.000000 0.009870 0.237210 +v 0.036276 -0.000941 0.233990 +v 0.041087 -0.002386 0.232886 +v 0.018408 0.004402 0.236707 +v -0.073131 0.017722 0.231574 +v -0.090494 0.012499 0.229865 +v -0.054960 0.020028 0.233212 +v -0.042430 0.019759 0.234283 +v -0.027536 0.017749 0.235503 +v -0.036539 0.019267 0.234776 +v -0.093790 0.010682 0.229125 +v -0.092771 0.011457 0.229431 +v -0.095309 0.009223 0.228456 +v -0.101079 -0.001799 0.221366 +v -0.099146 0.003747 0.225441 +v -0.099036 0.003911 0.225533 +v -0.095788 0.008762 0.228245 +v -0.102352 -0.009852 0.215003 +v -0.105772 -0.022632 0.194537 +v -0.104858 -0.020349 0.200296 +v -0.103961 -0.017339 0.205785 +v -0.103103 -0.013696 0.210826 +v -0.106841 -0.024318 0.187686 +v -0.110449 -0.026360 0.159145 +v -0.108079 -0.026494 0.152638 +v -0.111931 -0.027074 0.145487 +v -0.113436 -0.024442 0.081413 +v -0.108756 -0.025544 0.174745 +v -0.113675 -0.026658 0.110546 +v -0.113391 -0.024159 0.079881 +v -0.113364 -0.023642 0.078411 +v -0.112162 -0.006847 0.049710 +v -0.104292 0.072627 0.053328 +v -0.111694 0.021464 0.049935 +v -0.103183 0.075710 0.053533 +v -0.101402 0.078502 0.053978 +v -0.099268 0.080648 0.054569 +v -0.096548 0.082397 0.055364 +v -0.094378 0.083243 0.056016 +v -0.070720 0.089693 0.064225 +v -0.010930 0.101926 0.097932 +v -0.012491 0.101020 0.092963 +v -0.014769 0.100096 0.088279 +v -0.017712 0.099173 0.083984 +v -0.021255 0.098266 0.080172 +v -0.025319 0.097393 0.076926 +v -0.034634 0.095812 0.072395 +v -0.029812 0.096570 0.074315 +v 0.000000 0.104499 0.113551 +v -0.001315 0.104484 0.113465 +v -0.003992 0.104363 0.112727 +v -0.006373 0.104125 0.111282 +v -0.008259 0.103793 0.109250 +v -0.009522 0.103390 0.106769 +v 0.049796 0.099579 0.113551 +v 0.033516 0.102282 0.113551 +v 0.016795 0.103944 0.113551 +v 0.053653 0.098527 0.113804 +v 0.054572 0.098276 0.113864 +v 0.059087 0.096211 0.114151 +v 0.056363 0.097457 0.113978 +v -0.045229 0.104893 0.134662 +v 0.000000 0.107332 0.136525 +v -0.094428 0.083666 0.057765 +v -0.094428 0.083669 0.057780 +v 0.008528 0.105253 0.120084 +v 0.006900 0.105358 0.120509 +v 0.006260 0.105437 0.120987 +v 0.005708 0.105541 0.121686 +v 0.005383 0.105647 0.122462 +v 0.005273 0.105756 0.123296 +v 0.005384 0.105858 0.124132 +v 0.011671 0.105441 0.122487 +v 0.011346 0.105355 0.121708 +v 0.010155 0.105251 0.120523 +v 0.005709 0.105948 0.124910 +v 0.006902 0.106064 0.126094 +v 0.006217 0.107228 0.136250 +v 0.008530 0.106068 0.126532 +v 0.011970 0.106946 0.135496 +v 0.010157 0.105957 0.126107 +v 0.016966 0.106543 0.134411 +v 0.010831 0.105867 0.125598 +v 0.011347 0.105763 0.124933 +v 0.011672 0.105652 0.124157 +v 0.011783 0.105542 0.123323 +v 0.021515 0.104485 0.120060 +v 0.019895 0.104671 0.120476 +v 0.019157 0.104803 0.121050 +v 0.018710 0.104913 0.121645 +v 0.018387 0.105248 0.124088 +v 0.018276 0.105151 0.123253 +v 0.018386 0.105037 0.122419 +v 0.032827 0.103335 0.120523 +v 0.032176 0.103483 0.121008 +v 0.024320 0.104447 0.121702 +v 0.031647 0.103637 0.121684 +v 0.031325 0.103777 0.122456 +v 0.031326 0.103990 0.124126 +v 0.023136 0.105110 0.126094 +v 0.023807 0.104986 0.125588 +v 0.024321 0.104856 0.124926 +v 0.024644 0.104728 0.124153 +v 0.031215 0.103897 0.123289 +v 0.024754 0.104612 0.123319 +v 0.024643 0.104516 0.122483 +v 0.031648 0.104048 0.124908 +v 0.022355 0.105217 0.126408 +v 0.021517 0.105302 0.126509 +v 0.017554 0.106495 0.134283 +v 0.019897 0.105379 0.126061 +v 0.018711 0.105322 0.124869 +v 0.023134 0.104402 0.120509 +v 0.032160 0.104067 0.125583 +v 0.032829 0.104046 0.126107 +v 0.034441 0.103888 0.126565 +v 0.035503 0.103738 0.126535 +v 0.035500 0.103723 0.126403 +v 0.036052 0.103615 0.126160 +v 0.037751 0.103228 0.125034 +v 0.037231 0.103301 0.125000 +v 0.037552 0.103157 0.124229 +v 0.037661 0.103035 0.123395 +v 0.037551 0.102944 0.122559 +v 0.037229 0.102890 0.121776 +v 0.036717 0.102877 0.121099 +v 0.036050 0.102904 0.120576 +v 0.034438 0.103067 0.120117 +v -0.112219 -0.011057 0.052111 +v -0.112154 -0.009956 0.050846 +v -0.112136 -0.008498 0.050014 +v -0.111467 0.034186 0.059724 +v -0.104452 0.074277 0.059731 +v -0.045973 0.103351 0.145522 +v -0.090916 0.096004 0.139797 +v -0.093618 0.077595 0.176278 +v -0.093321 0.088150 0.156362 +v -0.093234 0.089837 0.152943 +v -0.092660 0.095616 0.139493 +v -0.093058 0.063109 0.198324 +v -0.091408 0.046426 0.219006 +v -0.049860 0.055634 0.221641 +v -0.048015 0.077040 0.194799 +v -0.047881 0.087146 0.178684 +v -0.111593 -0.013286 0.159354 +v -0.104469 0.074601 0.061132 +v -0.111310 0.045622 0.078168 +v -0.113075 0.030935 0.078233 +v -0.101283 0.008756 0.220307 +v -0.100596 0.034991 0.215738 +v -0.100635 0.037592 0.214243 +v -0.101669 0.047241 0.203297 +v -0.106150 0.045622 0.179554 +v -0.102818 0.069584 0.171589 +v -0.101917 0.088044 0.131188 +v -0.101815 0.087438 0.135783 +v -0.104299 0.082182 0.096024 +v -0.107866 0.030935 0.179974 +v -0.110627 0.030935 0.159160 +v -0.111923 0.045622 0.097890 +v -0.113504 0.030935 0.118138 +v -0.114544 0.016186 0.118259 +v -0.111654 0.016186 0.159367 +v 0.040218 0.042462 0.226289 +v 0.101829 -0.010039 0.208665 +v 0.043823 0.008113 0.231426 +v 0.029612 0.010513 0.234380 +v 0.057676 0.004908 0.227489 +v 0.091899 0.005276 0.213519 +v 0.070884 0.013681 0.221921 +v 0.088272 0.009836 0.214899 +v 0.066354 0.029785 0.221189 +v 0.059382 0.034101 0.222754 +v 0.031960 0.044793 0.227454 +v 0.023493 0.046537 0.228399 +v 0.000000 0.048476 0.229550 +v 0.006024 0.048353 0.229472 +v -0.089876 0.034773 0.226018 +v -0.076913 0.038448 0.227042 +v -0.020549 0.019759 0.235478 +v -0.091045 0.043994 0.221378 +v -0.090310 0.038410 0.224808 +v -0.090633 0.040964 0.223515 +v -0.049257 0.050565 0.225940 +v -0.014423 0.054159 0.226811 +v 0.000000 0.052577 0.227966 +v 0.114668 -0.023115 0.199566 +v 0.118287 -0.019444 0.195047 +v 0.122026 -0.027742 0.191106 +v 0.006263 0.056174 0.225554 +v 0.006161 0.052450 0.227886 +v 0.024480 0.054274 0.224400 +v 0.024054 0.050588 0.226770 +v 0.041251 0.046428 0.224563 +v 0.042055 0.050039 0.222096 +v 0.054641 0.045267 0.219804 +v 0.069938 0.037040 0.216343 +v 0.068353 0.033580 0.219171 +v 0.087478 0.023372 0.211296 +v 0.085274 0.019976 0.214542 +v 0.097922 0.012360 0.207422 +v 0.095295 0.008955 0.211010 +v 0.105998 -0.006376 0.205901 +v 0.113974 -0.011023 0.198634 +v 0.109135 -0.002885 0.201850 +v 0.110592 -0.014592 0.202921 +v -0.091997 0.097162 0.129277 +v -0.092226 0.097163 0.132922 +v -0.092431 0.096681 0.136081 +v -0.090333 0.097465 0.134531 +v -0.045679 0.104773 0.140179 +v 0.000000 0.107241 0.142075 +v 0.055532 0.097928 0.115257 +v 0.045584 0.101402 0.126002 +v 0.040965 0.102628 0.129562 +v 0.024872 0.105620 0.137825 +v 0.012963 0.106808 0.140954 +v 0.006732 0.107124 0.141775 +v -0.099123 0.009336 0.224955 +v -0.095207 0.022265 0.226622 +v -0.095331 0.009783 0.228422 +v -0.094698 0.034664 0.224252 +v -0.095614 0.044692 0.217942 +v -0.095344 0.042606 0.220005 +v -0.098684 0.040377 0.217520 +v -0.095081 0.040009 0.221900 +v -0.094903 0.037811 0.223082 +v -0.098500 0.036616 0.219910 +v -0.099855 0.091109 0.137340 +v -0.096684 0.093943 0.138625 +v -0.097714 0.075911 0.175299 +v -0.100907 0.073131 0.173672 +v -0.097209 0.061407 0.197295 +v -0.100425 0.058670 0.195464 +v -0.096527 0.094879 0.135710 +v -0.094999 0.096127 0.129110 +v -0.096368 0.095423 0.129863 +v -0.098231 0.093885 0.129736 +v -0.097678 0.094458 0.129602 +v -0.101363 0.089624 0.130634 +v -0.099824 0.092246 0.130529 +v -0.096429 0.095340 0.133005 +v -0.099757 0.092189 0.132976 +v -0.102073 0.088349 0.112301 +v -0.097438 0.082648 0.057935 +v -0.103053 0.077397 0.059026 +v -0.103349 0.081422 0.076295 +v -0.102032 0.079031 0.058665 +v -0.101055 0.084278 0.075677 +v -0.100115 0.080954 0.058262 +v -0.103691 0.076375 0.059252 +v -0.102330 0.078498 0.058723 +v -0.098830 0.081711 0.058025 +v 0.019275 0.108532 0.123492 +v 0.020142 0.108179 0.121324 +v 0.018556 0.108507 0.122889 +v 0.019057 0.108281 0.121465 +v 0.023745 0.108439 0.125366 +v 0.023068 0.108445 0.125022 +v 0.020187 0.108063 0.120464 +v 0.020738 0.108664 0.125341 +v 0.018810 0.108685 0.124383 +v 0.021668 0.107906 0.120133 +v 0.022471 0.107960 0.121004 +v 0.021158 0.108743 0.126177 +v 0.022427 0.107864 0.120251 +v 0.023934 0.108092 0.122853 +v 0.024640 0.108135 0.123583 +v 0.024221 0.107908 0.121623 +v 0.017961 0.092902 0.124220 +v 0.019042 0.092653 0.122953 +v 0.020677 0.092480 0.122593 +v 0.022504 0.092474 0.123597 +v 0.023076 0.092638 0.125172 +v 0.021988 0.093010 0.127359 +v 0.019963 0.093223 0.127805 +v 0.018488 0.093228 0.126994 +v 0.017790 0.093080 0.125468 +v 0.018462 0.093095 0.122836 +v 0.019355 0.104821 0.121288 +v 0.018859 0.093027 0.122552 +v 0.019298 0.092965 0.122335 +v 0.020192 0.104691 0.120787 +v 0.020747 0.092829 0.122136 +v 0.021232 0.092804 0.122226 +v 0.022125 0.104530 0.120679 +v 0.022854 0.092821 0.123295 +v 0.023748 0.104547 0.121747 +v 0.023515 0.093010 0.125112 +v 0.024408 0.104737 0.123564 +v 0.023202 0.093222 0.126531 +v 0.024095 0.104948 0.124983 +v 0.022633 0.093369 0.127320 +v 0.023526 0.105095 0.125773 +v 0.022259 0.093439 0.127636 +v 0.022733 0.105231 0.126340 +v 0.020904 0.093614 0.128174 +v 0.021798 0.105340 0.126626 +v 0.019923 0.093685 0.128150 +v 0.020817 0.105411 0.126602 +v 0.018221 0.093691 0.127214 +v 0.019114 0.105418 0.125666 +v 0.017415 0.093520 0.125454 +v 0.018309 0.105247 0.123906 +v 0.017469 0.093388 0.124480 +v 0.018362 0.105114 0.122933 +v 0.017613 0.093315 0.124014 +v 0.026291 0.105008 0.126705 +v 0.015595 0.105301 0.122751 +v 0.016237 0.104997 0.120816 +v 0.019053 0.105849 0.128898 +v 0.016125 0.105701 0.126090 +v 0.018063 0.104593 0.118815 +v 0.019938 0.104342 0.117994 +v 0.024348 0.105405 0.128593 +v 0.025894 0.105111 0.127261 +v 0.021744 0.105708 0.129382 +v 0.023738 0.105493 0.128905 +v 0.023328 0.104111 0.118199 +v 0.025606 0.104138 0.119719 +v 0.027091 0.104427 0.122768 +v 0.015671 0.105945 0.122506 +v 0.015589 0.106079 0.123468 +v 0.016092 0.106351 0.125824 +v 0.016847 0.106458 0.127070 +v 0.019150 0.106515 0.128830 +v 0.021524 0.106397 0.129303 +v 0.022010 0.106356 0.129278 +v 0.023877 0.106148 0.128778 +v 0.025802 0.105812 0.127344 +v 0.026373 0.105666 0.126567 +v 0.027168 0.105307 0.124305 +v 0.027167 0.105116 0.122857 +v 0.025800 0.104815 0.119792 +v 0.025467 0.104794 0.119436 +v 0.023426 0.104777 0.118129 +v 0.022008 0.104839 0.117784 +v 0.020073 0.105000 0.117886 +v 0.018708 0.105169 0.118378 +v 0.018286 0.105233 0.118616 +v 0.016308 0.105657 0.120692 +v 0.017379 0.106862 0.127216 +v 0.025324 0.105246 0.119557 +v 0.025642 0.105267 0.119898 +v 0.026990 0.105673 0.123756 +v 0.026951 0.105737 0.124217 +v 0.025043 0.107871 0.123672 +v 0.025067 0.107832 0.123383 +v 0.025268 0.106542 0.120650 +v 0.025027 0.106520 0.120345 +v 0.023362 0.106862 0.119452 +v 0.023032 0.106868 0.119311 +v 0.023224 0.106088 0.118753 +v 0.022011 0.106142 0.118458 +v 0.020236 0.107753 0.119998 +v 0.019972 0.107789 0.120119 +v 0.019188 0.106424 0.118966 +v 0.018827 0.106478 0.119169 +v 0.016348 0.106666 0.122062 +v 0.017029 0.107365 0.122132 +v 0.017731 0.108006 0.122558 +v 0.016948 0.107421 0.122509 +v 0.017690 0.108051 0.122879 +v 0.016182 0.106850 0.123366 +v 0.018013 0.108278 0.124778 +v 0.017658 0.107806 0.125835 +v 0.018327 0.108329 0.125348 +v 0.017325 0.107195 0.126639 +v 0.018140 0.107850 0.126444 +v 0.020568 0.108125 0.127407 +v 0.021078 0.108563 0.126626 +v 0.021368 0.108546 0.126659 +v 0.021276 0.108085 0.127517 +v 0.021991 0.108030 0.127509 +v 0.024661 0.107095 0.127208 +v 0.024971 0.107035 0.126934 +v 0.025736 0.106542 0.126546 +v 0.019175 0.107218 0.123666 +v 0.020042 0.106865 0.121497 +v 0.020638 0.107350 0.125515 +v 0.022968 0.107131 0.125195 +v 0.023834 0.106778 0.123027 +v 0.022371 0.106646 0.121178 +v 0.006145 0.109166 0.123516 +v 0.007013 0.108856 0.121342 +v 0.006244 0.108853 0.121091 +v 0.009946 0.109213 0.125026 +v 0.007612 0.109345 0.125359 +v 0.005679 0.109297 0.124410 +v 0.008542 0.108644 0.120142 +v 0.009347 0.108724 0.121010 +v 0.010013 0.109313 0.125826 +v 0.008033 0.109435 0.126193 +v 0.010813 0.108903 0.122852 +v 0.011521 0.108969 0.123579 +v 0.011330 0.109070 0.124317 +v 0.010623 0.108677 0.121019 +v 0.005606 0.093439 0.123799 +v 0.006881 0.093253 0.122715 +v 0.008139 0.093182 0.122536 +v 0.009969 0.093239 0.123531 +v 0.010544 0.093417 0.125104 +v 0.009454 0.093739 0.127298 +v 0.007851 0.093863 0.127797 +v 0.006262 0.093853 0.127238 +v 0.005246 0.093661 0.125429 +v 0.005270 0.093832 0.123538 +v 0.005719 0.105590 0.122040 +v 0.006750 0.105419 0.121008 +v 0.006741 0.093616 0.122287 +v 0.007190 0.105374 0.120789 +v 0.008193 0.093535 0.122080 +v 0.008679 0.093527 0.122168 +v 0.009127 0.105285 0.120670 +v 0.010305 0.093600 0.123229 +v 0.010753 0.105358 0.121731 +v 0.011028 0.105400 0.122139 +v 0.010968 0.093806 0.125043 +v 0.011416 0.105564 0.123545 +v 0.010654 0.093999 0.126465 +v 0.011102 0.105757 0.124967 +v 0.010084 0.094122 0.127257 +v 0.010532 0.105880 0.125759 +v 0.009710 0.094177 0.127575 +v 0.008833 0.094266 0.128013 +v 0.009281 0.106024 0.126515 +v 0.007860 0.094321 0.128151 +v 0.007369 0.094333 0.128102 +v 0.007818 0.106091 0.126604 +v 0.006028 0.094308 0.127506 +v 0.005663 0.094280 0.127175 +v 0.006111 0.106038 0.125677 +v 0.004855 0.094087 0.125418 +v 0.005304 0.105845 0.123920 +v 0.013304 0.105891 0.126678 +v 0.002528 0.105893 0.123462 +v 0.003590 0.105444 0.120258 +v 0.006051 0.106452 0.128911 +v 0.003116 0.106209 0.126118 +v 0.005056 0.105206 0.118828 +v 0.006934 0.105028 0.117996 +v 0.011926 0.106137 0.128192 +v 0.008748 0.106409 0.129381 +v 0.013730 0.105205 0.121416 +v 0.010332 0.104922 0.118182 +v 0.012614 0.105028 0.119691 +v 0.014061 0.105621 0.124779 +v 0.002553 0.106577 0.123500 +v 0.002573 0.106638 0.123984 +v 0.003057 0.106858 0.125854 +v 0.003814 0.106987 0.127097 +v 0.006123 0.107122 0.128846 +v 0.006580 0.107127 0.129016 +v 0.008502 0.107090 0.129306 +v 0.012092 0.106786 0.127996 +v 0.014075 0.106297 0.124752 +v 0.014156 0.106234 0.124275 +v 0.013792 0.105884 0.121420 +v 0.012784 0.105711 0.119766 +v 0.011699 0.105629 0.118792 +v 0.010405 0.105592 0.118115 +v 0.008983 0.105603 0.117778 +v 0.007044 0.105691 0.117890 +v 0.006118 0.105764 0.118185 +v 0.003524 0.106133 0.120305 +v 0.003055 0.106259 0.121151 +v 0.011177 0.106060 0.118693 +v 0.011572 0.106077 0.118943 +v 0.013962 0.106595 0.123728 +v 0.013923 0.106656 0.124189 +v 0.011934 0.108720 0.123664 +v 0.011958 0.108682 0.123375 +v 0.013695 0.106945 0.123224 +v 0.010911 0.108388 0.120749 +v 0.010694 0.108371 0.120554 +v 0.009354 0.106894 0.118520 +v 0.009249 0.107664 0.119114 +v 0.008941 0.106902 0.118457 +v 0.008536 0.107681 0.119037 +v 0.006102 0.108221 0.120157 +v 0.005617 0.108294 0.120588 +v 0.004566 0.107720 0.120760 +v 0.005212 0.108374 0.121094 +v 0.004192 0.107820 0.121435 +v 0.003135 0.107426 0.123838 +v 0.003191 0.107480 0.124275 +v 0.003856 0.108170 0.124078 +v 0.004193 0.108298 0.125186 +v 0.004002 0.107708 0.126310 +v 0.004568 0.108370 0.125864 +v 0.004262 0.107744 0.126667 +v 0.007674 0.109255 0.126585 +v 0.007962 0.109251 0.126641 +v 0.010546 0.108038 0.127858 +v 0.009958 0.109138 0.126357 +v 0.010217 0.109112 0.126224 +v 0.011600 0.107914 0.127198 +v 0.006095 0.107848 0.123684 +v 0.006962 0.107538 0.121510 +v 0.007561 0.108027 0.125526 +v 0.009896 0.107895 0.125194 +v 0.010763 0.107585 0.123020 +v 0.009297 0.107407 0.121178 +v 0.032884 0.085071 0.186142 +v 0.033455 0.086122 0.184106 +v 0.032146 0.085778 0.185377 +v 0.032681 0.084512 0.187169 +v 0.036695 0.083623 0.186465 +v 0.033396 0.086586 0.183374 +v 0.034504 0.083821 0.187321 +v 0.035647 0.085923 0.183249 +v 0.036855 0.083173 0.187118 +v 0.035005 0.083295 0.187915 +v 0.035996 0.086167 0.182661 +v 0.036665 0.085835 0.182845 +v 0.037267 0.084674 0.184428 +v 0.037395 0.085303 0.183325 +v 0.037934 0.083786 0.185527 +v 0.028372 0.072944 0.177246 +v 0.029597 0.073509 0.175657 +v 0.030778 0.073402 0.175196 +v 0.032646 0.072558 0.175575 +v 0.033381 0.071601 0.176750 +v 0.032600 0.070575 0.178858 +v 0.030715 0.070656 0.179744 +v 0.028669 0.071802 0.178964 +v 0.028774 0.073936 0.176217 +v 0.031977 0.083693 0.182153 +v 0.029515 0.074077 0.175585 +v 0.032719 0.083834 0.181522 +v 0.030878 0.073953 0.175053 +v 0.031352 0.073826 0.175006 +v 0.034556 0.083583 0.180942 +v 0.033032 0.072979 0.175491 +v 0.036236 0.082736 0.181427 +v 0.033881 0.071876 0.176846 +v 0.037085 0.081633 0.182782 +v 0.033750 0.071147 0.178114 +v 0.036954 0.080904 0.184050 +v 0.033299 0.070806 0.178920 +v 0.036503 0.080562 0.184856 +v 0.032980 0.070692 0.179278 +v 0.031747 0.070614 0.180072 +v 0.034950 0.080371 0.186008 +v 0.030805 0.070785 0.180300 +v 0.034008 0.080542 0.186236 +v 0.029879 0.071115 0.180257 +v 0.033082 0.080872 0.186193 +v 0.029064 0.071572 0.179946 +v 0.032268 0.081329 0.185882 +v 0.028444 0.072107 0.179400 +v 0.031648 0.081864 0.185336 +v 0.028084 0.072667 0.178675 +v 0.031287 0.082424 0.184612 +v 0.028019 0.073192 0.177846 +v 0.031223 0.082949 0.183782 +v 0.028101 0.073426 0.177419 +v 0.028687 0.082748 0.185482 +v 0.028732 0.084160 0.183137 +v 0.033902 0.079133 0.188609 +v 0.030306 0.080821 0.187775 +v 0.031967 0.079835 0.188499 +v 0.029128 0.081966 0.186529 +v 0.029563 0.084934 0.181416 +v 0.032143 0.085407 0.179246 +v 0.038124 0.079001 0.186548 +v 0.034567 0.078978 0.188504 +v 0.035413 0.084751 0.178560 +v 0.037773 0.083551 0.179257 +v 0.039670 0.080191 0.183758 +v 0.039558 0.081639 0.181437 +v 0.028860 0.084604 0.183686 +v 0.028780 0.084373 0.184108 +v 0.028854 0.083346 0.185757 +v 0.029538 0.082242 0.187203 +v 0.030409 0.081437 0.188056 +v 0.032376 0.080287 0.188884 +v 0.034683 0.079547 0.188856 +v 0.036507 0.079338 0.188215 +v 0.038427 0.079594 0.186758 +v 0.039778 0.080589 0.184394 +v 0.039877 0.080813 0.183972 +v 0.039786 0.082094 0.181916 +v 0.039651 0.082369 0.181536 +v 0.038113 0.083995 0.179694 +v 0.037751 0.084244 0.179480 +v 0.035642 0.085289 0.178901 +v 0.034244 0.085705 0.178971 +v 0.032404 0.085959 0.179546 +v 0.031971 0.085966 0.179769 +v 0.029815 0.085525 0.181657 +v 0.029326 0.085209 0.182440 +v 0.034782 0.080026 0.188854 +v 0.039323 0.083161 0.182808 +v 0.039510 0.082820 0.182511 +v 0.039388 0.083070 0.182166 +v 0.039061 0.083634 0.182173 +v 0.038629 0.084197 0.182847 +v 0.038096 0.084804 0.182138 +v 0.037871 0.084999 0.181938 +v 0.036107 0.086095 0.181691 +v 0.034985 0.086149 0.180239 +v 0.035182 0.086413 0.181667 +v 0.034583 0.086250 0.180289 +v 0.033009 0.086468 0.180781 +v 0.033098 0.086626 0.182988 +v 0.031620 0.086371 0.181690 +v 0.031923 0.086478 0.182060 +v 0.032316 0.086530 0.183023 +v 0.031265 0.085756 0.184862 +v 0.029511 0.084891 0.184503 +v 0.030327 0.085304 0.184851 +v 0.031185 0.085439 0.185426 +v 0.030295 0.085110 0.185187 +v 0.029474 0.084670 0.184886 +v 0.032128 0.084428 0.187124 +v 0.030557 0.083288 0.187331 +v 0.030779 0.083054 0.187596 +v 0.032458 0.084102 0.187480 +v 0.034649 0.082955 0.188184 +v 0.034332 0.080130 0.188927 +v 0.034930 0.082877 0.188160 +v 0.034874 0.080506 0.188817 +v 0.032525 0.083977 0.185477 +v 0.033096 0.085028 0.183441 +v 0.034145 0.082728 0.186656 +v 0.036336 0.082529 0.185799 +v 0.036908 0.083580 0.183763 +v 0.035288 0.084830 0.182584 +v 0.019665 0.087281 0.188219 +v 0.020248 0.088391 0.186218 +v 0.018888 0.087663 0.187857 +v 0.019466 0.088588 0.186160 +v 0.019459 0.086700 0.189233 +v 0.024271 0.085923 0.188887 +v 0.023565 0.086162 0.188735 +v 0.021324 0.086166 0.189477 +v 0.021597 0.088921 0.184905 +v 0.022490 0.088387 0.185475 +v 0.021335 0.085784 0.190095 +v 0.024148 0.087272 0.186734 +v 0.024929 0.086823 0.187204 +v 0.024279 0.087918 0.185640 +v 0.024832 0.086438 0.187863 +v 0.016601 0.074666 0.179435 +v 0.017576 0.075481 0.177783 +v 0.019134 0.075552 0.177148 +v 0.021045 0.074868 0.177621 +v 0.021798 0.073970 0.178830 +v 0.021001 0.072866 0.180892 +v 0.019073 0.072778 0.181679 +v 0.016979 0.073751 0.180797 +v 0.018400 0.085284 0.185349 +v 0.016744 0.075745 0.178426 +v 0.018790 0.085698 0.184545 +v 0.017041 0.075905 0.178065 +v 0.019087 0.085858 0.184185 +v 0.017396 0.076029 0.177745 +v 0.019441 0.085982 0.183865 +v 0.017799 0.076114 0.177473 +v 0.019845 0.086067 0.183593 +v 0.019193 0.076111 0.177011 +v 0.019678 0.076025 0.176989 +v 0.021724 0.085978 0.183108 +v 0.021398 0.075322 0.177558 +v 0.023443 0.085275 0.183678 +v 0.022267 0.074286 0.178952 +v 0.024313 0.084239 0.185072 +v 0.022134 0.073540 0.180210 +v 0.024180 0.083493 0.186330 +v 0.021673 0.073155 0.180990 +v 0.023719 0.083108 0.187110 +v 0.021347 0.073012 0.181332 +v 0.020086 0.072823 0.182060 +v 0.022132 0.082776 0.188180 +v 0.019122 0.072911 0.182240 +v 0.021168 0.082864 0.188359 +v 0.017341 0.073548 0.181798 +v 0.019387 0.083502 0.187918 +v 0.016707 0.074033 0.181222 +v 0.016337 0.074565 0.180481 +v 0.018383 0.084518 0.186601 +v 0.016270 0.075089 0.179651 +v 0.016354 0.075331 0.179229 +v 0.026541 0.082391 0.187332 +v 0.015636 0.085704 0.185590 +v 0.019722 0.081753 0.190650 +v 0.016512 0.083499 0.188883 +v 0.018054 0.087442 0.181955 +v 0.017037 0.087115 0.182827 +v 0.022416 0.081285 0.190510 +v 0.024310 0.081392 0.189702 +v 0.022598 0.087232 0.180777 +v 0.020569 0.087584 0.180883 +v 0.025014 0.086234 0.181593 +v 0.026842 0.084466 0.183857 +v 0.015747 0.086249 0.185974 +v 0.015744 0.085485 0.187218 +v 0.016524 0.084168 0.189098 +v 0.018155 0.082998 0.190456 +v 0.019886 0.082305 0.191006 +v 0.022269 0.081867 0.190921 +v 0.024508 0.081973 0.190000 +v 0.024903 0.082060 0.189727 +v 0.026681 0.082983 0.187632 +v 0.027100 0.083652 0.186402 +v 0.027005 0.084935 0.184348 +v 0.026230 0.085982 0.182905 +v 0.025291 0.086702 0.182047 +v 0.022763 0.087785 0.181131 +v 0.021332 0.088080 0.181129 +v 0.020853 0.088136 0.181199 +v 0.017103 0.087658 0.183230 +v 0.026832 0.083839 0.187003 +v 0.026929 0.084063 0.186605 +v 0.026142 0.085044 0.187471 +v 0.025306 0.086557 0.187042 +v 0.025974 0.086148 0.186371 +v 0.025295 0.086712 0.186794 +v 0.021555 0.088643 0.182465 +v 0.021512 0.088946 0.184424 +v 0.020738 0.088720 0.182613 +v 0.021227 0.088967 0.184486 +v 0.019136 0.088708 0.185079 +v 0.018715 0.088512 0.185537 +v 0.016370 0.086367 0.187165 +v 0.016406 0.086130 0.187538 +v 0.018000 0.085442 0.189547 +v 0.018250 0.084064 0.190283 +v 0.018784 0.084879 0.190200 +v 0.018597 0.083871 0.190480 +v 0.021214 0.085374 0.190333 +v 0.022074 0.085216 0.190303 +v 0.024609 0.083493 0.189819 +v 0.025491 0.083819 0.188995 +v 0.019436 0.086165 0.187533 +v 0.020019 0.087276 0.185532 +v 0.021095 0.085051 0.188791 +v 0.023336 0.085047 0.188049 +v 0.023919 0.086157 0.186048 +v 0.022261 0.087272 0.184790 +v 0.005389 0.087619 0.190022 +v 0.005971 0.087864 0.189597 +v 0.005257 0.088612 0.188558 +v 0.006577 0.089108 0.187683 +v 0.010630 0.086907 0.190534 +v 0.009917 0.087086 0.190342 +v 0.007640 0.086853 0.190926 +v 0.008853 0.089341 0.187099 +v 0.006692 0.086697 0.191256 +v 0.009865 0.086566 0.191121 +v 0.009910 0.089454 0.186821 +v 0.007449 0.089788 0.186581 +v 0.010523 0.088330 0.188428 +v 0.011148 0.088506 0.188103 +v 0.011206 0.087514 0.189571 +v 0.004774 0.075641 0.179813 +v 0.006054 0.076496 0.178408 +v 0.008124 0.076515 0.178164 +v 0.009212 0.076096 0.178674 +v 0.009966 0.075220 0.179898 +v 0.009142 0.073960 0.181858 +v 0.007183 0.073663 0.182505 +v 0.005622 0.074087 0.182036 +v 0.004750 0.074932 0.180869 +v 0.005108 0.076742 0.178875 +v 0.005796 0.086569 0.185483 +v 0.005880 0.077044 0.178345 +v 0.006805 0.077185 0.178040 +v 0.007494 0.087012 0.184648 +v 0.007788 0.077150 0.177990 +v 0.008476 0.086976 0.184598 +v 0.008269 0.077066 0.178064 +v 0.009524 0.076583 0.178652 +v 0.010213 0.086410 0.185260 +v 0.010394 0.075572 0.180065 +v 0.011082 0.085399 0.186673 +v 0.010376 0.075024 0.180882 +v 0.011064 0.084850 0.187490 +v 0.009776 0.074305 0.182013 +v 0.010465 0.084132 0.188621 +v 0.009443 0.074118 0.182326 +v 0.008624 0.073854 0.182804 +v 0.009312 0.083681 0.189412 +v 0.007183 0.073775 0.183072 +v 0.007871 0.083601 0.189680 +v 0.005382 0.074265 0.182531 +v 0.006071 0.084091 0.189139 +v 0.004376 0.075240 0.181185 +v 0.005064 0.085067 0.187793 +v 0.004315 0.075791 0.180372 +v 0.005003 0.085618 0.186980 +v 0.004403 0.076058 0.179966 +v 0.013320 0.083668 0.189013 +v 0.002259 0.085271 0.187782 +v 0.002937 0.087099 0.184992 +v 0.006388 0.082265 0.191822 +v 0.003151 0.083783 0.189901 +v 0.005989 0.088442 0.182677 +v 0.009118 0.082053 0.191853 +v 0.011043 0.082368 0.191184 +v 0.009380 0.088404 0.182381 +v 0.008701 0.088502 0.182305 +v 0.007324 0.088563 0.182357 +v 0.011820 0.087597 0.183326 +v 0.013753 0.084378 0.187913 +v 0.013654 0.085909 0.185645 +v 0.002324 0.086575 0.187047 +v 0.002311 0.085760 0.188260 +v 0.003087 0.084442 0.190140 +v 0.003353 0.084201 0.190471 +v 0.005566 0.083052 0.191949 +v 0.006476 0.082814 0.192208 +v 0.009369 0.082626 0.192186 +v 0.010298 0.082745 0.191912 +v 0.011165 0.082951 0.191516 +v 0.013385 0.084256 0.189343 +v 0.013568 0.084500 0.188962 +v 0.013739 0.086369 0.186164 +v 0.013602 0.086637 0.185780 +v 0.012021 0.088069 0.183815 +v 0.011649 0.088262 0.183567 +v 0.009469 0.088954 0.182765 +v 0.007050 0.089111 0.182784 +v 0.006110 0.089014 0.183025 +v 0.004811 0.088706 0.183619 +v 0.002901 0.087583 0.185489 +v 0.013356 0.084907 0.189133 +v 0.010651 0.083316 0.191781 +v 0.010227 0.083227 0.191957 +v 0.013495 0.085149 0.188759 +v 0.012665 0.086265 0.189221 +v 0.011316 0.088909 0.185429 +v 0.011018 0.089064 0.185231 +v 0.007351 0.089741 0.184606 +v 0.006601 0.089664 0.184799 +v 0.005159 0.089126 0.184432 +v 0.004804 0.088995 0.184664 +v 0.005254 0.089303 0.185476 +v 0.003750 0.088134 0.187371 +v 0.002898 0.087189 0.187547 +v 0.003582 0.087718 0.188007 +v 0.002858 0.086945 0.187915 +v 0.003726 0.086635 0.189602 +v 0.004480 0.087241 0.189756 +v 0.004584 0.087063 0.190009 +v 0.004402 0.085825 0.190737 +v 0.005498 0.085161 0.191610 +v 0.005967 0.086003 0.191441 +v 0.006240 0.085891 0.191579 +v 0.006028 0.085465 0.191693 +v 0.009941 0.084664 0.191887 +v 0.010632 0.084828 0.191570 +v 0.010947 0.086542 0.190611 +v 0.012227 0.085684 0.190132 +v 0.011274 0.086796 0.190198 +v 0.005893 0.086762 0.188856 +v 0.006500 0.088006 0.186943 +v 0.007563 0.085752 0.190185 +v 0.009839 0.085985 0.189601 +v 0.010446 0.087229 0.187688 +v 0.008776 0.088240 0.186359 +v -0.048920 0.050619 -0.224570 +v 0.000038 0.048543 -0.228159 +v -0.099987 0.037725 -0.212945 +v -0.107174 0.031108 -0.178883 +v -0.095903 0.094665 -0.134888 +v -0.099212 0.090918 -0.136508 +v -0.099114 0.091991 -0.132170 +v 0.113074 0.026818 -0.138668 +v 0.125741 -0.010606 -0.152094 +v -0.101261 0.087871 -0.130393 +v -0.111207 0.045706 -0.097297 +v -0.112778 0.031108 -0.117422 +v -0.101159 0.087269 -0.134960 +v -0.109918 0.031108 -0.158196 +v -0.102156 0.069523 -0.170549 +v -0.105469 0.045706 -0.178466 +v -0.113811 0.016449 -0.117542 +v -0.112351 0.031108 -0.077759 +v -0.090045 0.041077 -0.222160 +v -0.076408 0.038575 -0.225666 +v 0.016731 0.103674 -0.112863 +v 0.008515 0.104976 -0.119356 +v -0.103024 0.076273 -0.058893 +v -0.101375 0.078913 -0.058310 +v 0.005523 0.084810 -0.187341 +v 0.003962 0.084285 -0.188292 +v -0.100631 0.009064 -0.218972 +v -0.105093 -0.022135 -0.193358 +v 0.057416 0.084324 -0.157188 +v 0.040067 0.080100 -0.182333 +v 0.040755 0.102367 -0.128777 +v 0.035326 0.103470 -0.125768 +v 0.029471 0.010810 -0.232959 +v 0.023390 0.046616 -0.227015 +v 0.024760 0.105340 -0.136990 +v 0.017486 0.106210 -0.133469 +v 0.012923 0.106521 -0.140100 +v 0.011936 0.106658 -0.134675 +v 0.006730 0.106836 -0.140916 +v 0.016902 0.106257 -0.133596 +v -0.094591 0.022490 -0.225248 +v -0.092170 0.011748 -0.228040 +v -0.089293 0.034923 -0.224648 +v -0.089907 0.012784 -0.228472 +v 0.048501 0.099132 -0.129374 +v -0.098484 0.009640 -0.223592 +v 0.101250 -0.009617 -0.207400 +v 0.109960 -0.014143 -0.201691 +v -0.106155 -0.023810 -0.186548 +v 0.006162 0.052493 -0.226504 +v -0.100257 0.073048 -0.172619 +v -0.096581 0.061395 -0.196099 +v 0.054348 0.045353 -0.218472 +v 0.041040 0.046507 -0.223202 +v 0.067978 0.033737 -0.217842 +v -0.096059 0.093734 -0.137785 +v -0.092630 0.089653 -0.152016 +v -0.092717 0.087976 -0.155414 +v -0.097083 0.075811 -0.174237 +v 0.040012 0.042565 -0.224918 +v 0.043596 0.008424 -0.230024 +v 0.059060 0.034255 -0.221404 +v 0.036095 -0.000574 -0.232571 +v -0.101014 0.047315 -0.202065 +v -0.098047 0.040493 -0.216201 +v -0.099777 0.058675 -0.194279 +v 0.037115 0.090289 -0.165682 +v -0.014297 0.054191 -0.225436 +v -0.049519 0.055657 -0.220298 +v 0.006327 0.059393 -0.221211 +v 0.031805 0.044882 -0.226075 +v 0.023946 0.050642 -0.225395 +v -0.095746 0.095205 -0.129076 +v -0.091628 0.096934 -0.132117 +v 0.121325 -0.027213 -0.189947 +v 0.123253 -0.024073 -0.184193 +v 0.109184 -0.026517 -0.201231 +v 0.065575 -0.009485 -0.223467 +v 0.087776 0.010137 -0.213596 +v 0.091380 0.005605 -0.212225 +v 0.125266 -0.023631 -0.075241 +v 0.131358 -0.043695 -0.087121 +v 0.132557 -0.046752 -0.108930 +v 0.116655 0.019588 -0.128374 +v 0.126123 -0.026770 -0.074490 +v 0.127813 -0.032585 -0.074883 +v 0.129411 -0.037855 -0.077457 +v 0.000039 0.104226 -0.112863 +v 0.005712 0.105261 -0.120948 +v 0.080961 0.074556 -0.129717 +v 0.074979 0.075967 -0.145290 +v -0.094385 0.095905 -0.128327 +v -0.093818 0.083523 -0.057430 +v 0.089774 0.038873 -0.188869 +v 0.088470 0.026487 -0.206012 +v 0.081566 0.032392 -0.208347 +v 0.076285 0.057350 -0.182140 +v 0.005105 0.085680 -0.185974 +v 0.106522 0.026481 -0.171225 +v 0.094466 0.046571 -0.166793 +v 0.101822 0.018479 -0.193506 +v 0.110381 0.000544 -0.195610 +v 0.098738 0.032940 -0.180422 +v 0.121880 -0.002812 -0.163191 +v 0.113031 0.019571 -0.161386 +v -0.103781 0.074188 -0.059369 +v -0.102519 0.075612 -0.053209 +v 0.084519 0.070017 -0.133555 +v 0.082466 0.071013 -0.138236 +v 0.082528 0.072504 -0.131820 +v 0.049533 0.099336 -0.112863 +v 0.036533 0.102614 -0.120365 +v -0.111444 -0.006445 -0.049409 +v 0.041838 0.050096 -0.220750 +v 0.033592 0.055640 -0.218978 +v 0.024370 0.054305 -0.223040 +v -0.110979 0.021694 -0.049632 +v 0.006264 0.056195 -0.224186 +v 0.000038 0.052618 -0.226584 +v 0.024644 0.057473 -0.220034 +v 0.028322 0.082251 -0.185396 +v 0.004390 0.060664 -0.219894 +v 0.018006 0.059961 -0.218894 +v 0.021969 0.082764 -0.187100 +v 0.022738 0.082809 -0.186758 +v 0.008314 0.083808 -0.188638 +v 0.021144 0.082836 -0.187263 +v 0.009937 0.083933 -0.188214 +v 0.016239 0.083651 -0.187390 +v 0.018402 0.084089 -0.186099 +v 0.018902 0.083667 -0.186633 +v 0.020320 0.083020 -0.187235 +v 0.019557 0.083303 -0.187021 +v -0.100404 0.084128 -0.075218 +v -0.096809 0.082507 -0.057584 +v 0.068353 0.088769 -0.113956 +v 0.059174 0.095235 -0.117887 +v 0.080948 0.064637 -0.160318 +v 0.065769 0.061820 -0.188504 +v -0.101671 0.078383 -0.058367 +v -0.099470 0.080824 -0.057909 +v -0.103621 0.072548 -0.053005 +v -0.110753 0.034339 -0.059362 +v 0.089778 0.063624 -0.135552 +v 0.087069 0.066905 -0.134898 +v 0.022258 0.104940 -0.125641 +v 0.021425 0.105024 -0.125742 +v 0.032578 0.102826 -0.139497 +v 0.026438 0.103782 -0.142009 +v -0.097048 0.094246 -0.128817 +v -0.097597 0.093677 -0.128950 +v -0.089724 0.038537 -0.223445 +v 0.126698 -0.037981 -0.181441 +v 0.124612 -0.035690 -0.185644 +v -0.100710 0.089441 -0.129842 +v -0.101415 0.088174 -0.111621 +v -0.094693 0.009527 -0.227072 +v -0.094714 0.010084 -0.227038 +v -0.099181 0.092048 -0.129738 +v 0.085889 0.052247 -0.174874 +v -0.103798 0.074509 -0.060761 +v 0.013793 0.105080 -0.145353 +v 0.065990 0.029965 -0.219848 +v -0.098193 0.081576 -0.057673 +v 0.037560 0.102963 -0.124276 +v 0.034270 0.103619 -0.125798 +v 0.035323 0.103455 -0.125637 +v 0.032668 0.103776 -0.125342 +v -0.092060 0.095397 -0.138648 +v -0.093183 0.010977 -0.227736 +v 0.035872 0.103348 -0.125395 +v -0.092456 0.063087 -0.197122 +v -0.047686 0.076933 -0.193619 +v 0.079773 0.076254 -0.127143 +v -0.098507 0.004084 -0.224075 +v -0.098397 0.004248 -0.224166 +v -0.093012 0.077485 -0.175209 +v 0.033794 0.083972 -0.179692 +v 0.032229 0.084147 -0.180275 +v 0.018947 0.086041 -0.182720 +v 0.114350 -0.028336 -0.197686 +v 0.114011 -0.022614 -0.198356 +v 0.019612 0.086209 -0.182229 +v 0.022792 0.085709 -0.181963 +v 0.020382 0.086260 -0.181890 +v 0.021536 0.086127 -0.181715 +v 0.031546 0.084036 -0.180834 +v 0.006218 0.106939 -0.135424 +v 0.031074 0.083824 -0.181442 +v 0.118710 -0.010764 -0.185972 +v 0.021207 0.086188 -0.181728 +v 0.023943 0.084904 -0.182875 +v 0.030755 0.083501 -0.182153 +v 0.024353 0.083996 -0.184221 +v -0.095806 0.095122 -0.132199 +v 0.030641 0.083099 -0.182886 +v 0.030741 0.082644 -0.183592 +v 0.031047 0.082169 -0.184221 +v 0.023912 0.083231 -0.185644 +v 0.023701 0.104710 -0.124827 +v 0.024212 0.104581 -0.124169 +v 0.089030 0.059288 -0.152702 +v 0.019815 0.105100 -0.125296 +v 0.023034 0.104833 -0.125329 +v -0.099948 0.035140 -0.214431 +v 0.124211 -0.035323 -0.186251 +v 0.121710 -0.033031 -0.190028 +v 0.023401 0.082968 -0.186262 +v 0.000038 0.105551 -0.146550 +v 0.078821 0.077928 -0.122899 +v -0.100428 -0.001427 -0.220025 +v 0.035305 0.080490 -0.184668 +v 0.037363 0.102892 -0.123476 +v 0.037472 0.102771 -0.122648 +v 0.106926 0.034770 -0.096877 +v 0.108117 0.031146 -0.094875 +v 0.031495 0.103777 -0.124151 +v 0.032004 0.103797 -0.124822 +v 0.037362 0.102681 -0.121816 +v 0.037042 0.102627 -0.121038 +v 0.117961 -0.030301 -0.194387 +v 0.117608 -0.018966 -0.193864 +v -0.042135 0.020000 -0.232863 +v -0.044916 0.104618 -0.133845 +v -0.070253 0.089510 -0.063835 +v -0.034385 0.095592 -0.071956 +v -0.029593 0.096345 -0.073865 +v -0.025127 0.097163 -0.076460 +v -0.021088 0.098031 -0.079686 +v -0.017566 0.098932 -0.083475 +v -0.014641 0.099850 -0.087743 +v -0.012377 0.100768 -0.092399 +v -0.010825 0.101668 -0.097338 +v -0.009426 0.103124 -0.106122 +v -0.093817 0.083519 -0.057415 +v -0.091401 0.096934 -0.128493 +v -0.098628 0.080519 -0.054238 +v -0.095925 0.082258 -0.055028 +v -0.003929 0.104091 -0.112044 +v 0.005390 0.105577 -0.123380 +v 0.000038 0.107042 -0.135698 +v -0.006296 0.103855 -0.110607 +v 0.005279 0.105475 -0.122549 +v -0.001269 0.104212 -0.112777 +v -0.008170 0.103525 -0.108588 +v 0.037043 0.103036 -0.124242 +v 0.024533 0.104454 -0.123401 +v 0.024642 0.104339 -0.122572 +v 0.042379 0.053201 -0.217651 +v 0.069553 0.037176 -0.215031 +v 0.055123 0.048397 -0.215242 +v 0.101917 0.047234 -0.135538 +v 0.099771 0.051175 -0.131413 +v 0.101912 0.040391 -0.157993 +v 0.108140 0.033780 -0.148581 +v 0.095419 0.056711 -0.134694 +v 0.084795 0.020215 -0.213241 +v 0.097767 0.053755 -0.133310 +v 0.045346 0.101148 -0.125238 +v 0.110330 -0.026829 -0.200553 +v 0.061991 0.093876 -0.113662 +v 0.024532 0.104244 -0.121740 +v -0.102684 0.081289 -0.075833 +v -0.093768 0.083099 -0.055676 +v 0.054279 0.098041 -0.113174 +v 0.056060 0.097227 -0.113287 +v -0.089747 0.097234 -0.133716 +v 0.128191 -0.039987 -0.177055 +v 0.011639 0.105372 -0.123405 +v 0.011750 0.105263 -0.122575 +v -0.110597 0.045706 -0.077694 +v 0.011317 0.105482 -0.124176 +v 0.101301 0.049155 -0.129245 +v -0.095169 0.009070 -0.226862 +v 0.018204 0.104874 -0.122506 +v -0.027330 0.018002 -0.234075 +v -0.036279 0.019510 -0.233353 +v 0.103384 0.046282 -0.123532 +v 0.102544 0.047466 -0.126581 +v 0.058768 0.095989 -0.113459 +v 0.099060 0.015560 -0.201734 +v 0.097366 0.012646 -0.206165 +v 0.070650 0.040137 -0.211533 +v 0.036886 0.081505 -0.182040 +v -0.094086 0.034814 -0.222893 +v -0.097865 0.036754 -0.218577 +v -0.045656 0.103086 -0.144640 +v -0.090326 0.095783 -0.138949 +v -0.091832 0.096455 -0.135256 +v 0.024211 0.104174 -0.120965 +v 0.023033 0.104129 -0.119779 +v 0.086986 0.023591 -0.210015 +v -0.090816 0.046505 -0.217679 +v -0.094996 0.044782 -0.216621 +v 0.008384 0.087198 -0.183123 +v 0.006759 0.087065 -0.183542 +v -0.111500 -0.010629 -0.051795 +v -0.111436 -0.009535 -0.050537 +v 0.021423 0.104212 -0.119333 +v 0.019813 0.104397 -0.119746 +v 0.033741 0.080670 -0.185254 +v 0.042512 0.068654 -0.198234 +v 0.126149 -0.032408 -0.180361 +v 0.000038 0.102709 -0.153436 +v 0.092578 0.024597 -0.202217 +v 0.055234 0.097695 -0.114558 +v 0.019079 0.104528 -0.120317 +v 0.018635 0.104638 -0.120907 +v 0.119548 -0.015608 -0.188263 +v -0.102390 0.077289 -0.058668 +v 0.018313 0.104761 -0.121677 +v 0.010663 0.086552 -0.183851 +v 0.009998 0.086867 -0.183437 +v 0.005910 0.086745 -0.184159 +v 0.011169 0.086165 -0.184403 +v 0.018314 0.104971 -0.123336 +v 0.031174 0.103720 -0.123374 +v 0.031174 0.103509 -0.121714 +v 0.031065 0.103628 -0.122542 +v 0.009220 0.087088 -0.183189 +v -0.103628 0.082045 -0.095442 +v -0.108059 -0.025029 -0.173686 +v -0.110878 -0.012845 -0.158388 +v -0.109741 -0.025839 -0.158180 +v -0.111214 -0.026549 -0.144606 +v -0.111418 -0.008085 -0.049711 +v 0.105985 0.037876 -0.099388 +v 0.070492 0.013958 -0.220575 +v 0.000038 0.106951 -0.141214 +v 0.031494 0.103370 -0.120946 +v 0.103713 0.045783 -0.120626 +v 0.011134 0.084472 -0.187161 +v 0.011585 0.085287 -0.185766 +v 0.011484 0.085733 -0.185055 +v 0.018636 0.105044 -0.124112 +v -0.102440 -0.013253 -0.209548 +v -0.101693 -0.009432 -0.213700 +v 0.032019 0.103216 -0.120274 +v 0.033351 0.102023 -0.112863 +v 0.032666 0.103069 -0.119792 +v 0.034268 0.102803 -0.119389 +v 0.035870 0.102641 -0.119845 +v 0.005206 0.085236 -0.186684 +v 0.074016 0.083472 -0.116171 +v 0.076122 0.081257 -0.117972 +v 0.103753 0.045722 -0.120273 +v -0.054589 0.020267 -0.231798 +v 0.116562 0.004692 -0.173876 +v 0.006026 0.048421 -0.228082 +v -0.112710 -0.023934 -0.080920 +v 0.103732 0.045500 -0.114321 +v 0.071354 0.086062 -0.114790 +v -0.100749 0.078386 -0.053651 +v 0.103970 0.044596 -0.110197 +v 0.113322 -0.010595 -0.197430 +v -0.090455 0.044088 -0.220036 +v -0.094728 0.042709 -0.218671 +v -0.112665 -0.023652 -0.079397 +v 0.094756 0.009261 -0.209731 +v 0.031611 0.081728 -0.184652 +v 0.035350 0.083346 -0.179850 +v -0.020386 0.020000 -0.234051 +v 0.108512 -0.002507 -0.200627 +v -0.047553 0.086978 -0.177601 +v 0.040877 -0.002011 -0.231475 +v -0.094467 0.040127 -0.220555 +v -0.094289 0.037943 -0.221730 +v 0.105394 -0.005977 -0.204653 +v 0.032182 0.081283 -0.185089 +v 0.035955 0.080583 -0.184136 +v 0.036786 0.081960 -0.181334 +v -0.107386 -0.025973 -0.151713 +v 0.000038 0.010170 -0.235772 +v 0.036481 0.082440 -0.180708 +v -0.112948 -0.026136 -0.109876 +v 0.006898 0.105781 -0.125330 +v 0.018335 0.004736 -0.235272 +v 0.010132 0.104974 -0.119792 +v 0.006260 0.105159 -0.120253 +v 0.104441 0.043000 -0.106260 +v -0.045364 0.104499 -0.139329 +v 0.006897 0.105080 -0.119779 +v 0.054466 0.065603 -0.193890 +v 0.053367 0.098290 -0.113114 +v -0.112638 -0.023138 -0.077936 +v 0.003335 0.102676 -0.153389 +v 0.130625 -0.041698 -0.081711 +v 0.105125 0.040727 -0.102596 +v 0.010803 0.105586 -0.124837 +v 0.036456 0.080793 -0.183491 +v 0.005225 0.086114 -0.185257 +v 0.005558 0.086507 -0.184584 +v 0.129790 -0.043000 -0.170190 +v 0.057364 0.005239 -0.226110 +v -0.072649 0.017975 -0.230170 +v -0.104184 -0.019865 -0.199082 +v 0.131519 -0.047063 -0.156982 +v 0.006031 0.084433 -0.187899 +v -0.110939 0.016449 -0.158401 +v 0.036773 0.081107 -0.182776 +v 0.010134 0.105675 -0.125343 +v 0.005713 0.105666 -0.124153 +v 0.017991 0.084990 -0.184749 +v 0.018434 0.085768 -0.183333 +v 0.008516 0.105785 -0.125766 +v -0.103292 -0.016873 -0.204537 +v 0.006697 0.084128 -0.188318 +v 0.092638 0.060144 -0.135500 +v 0.005389 0.105368 -0.121719 +v 0.077793 0.079324 -0.120304 +v 0.011639 0.105162 -0.121745 +v 0.011316 0.105077 -0.120971 +v 0.132280 -0.048892 -0.144307 +v -0.048920 0.050619 0.224570 +v 0.000038 0.048543 0.228159 +v -0.099987 0.037725 0.212945 +v -0.107174 0.031108 0.178883 +v -0.095903 0.094665 0.134888 +v -0.099212 0.090918 0.136508 +v -0.099114 0.091991 0.132170 +v 0.113074 0.026818 0.138668 +v 0.125741 -0.010606 0.152094 +v -0.101261 0.087871 0.130393 +v -0.111207 0.045706 0.097297 +v -0.112778 0.031108 0.117422 +v -0.101159 0.087269 0.134960 +v -0.109918 0.031108 0.158196 +v -0.102156 0.069523 0.170549 +v -0.105469 0.045706 0.178466 +v -0.113811 0.016449 0.117542 +v -0.112351 0.031108 0.077759 +v -0.090045 0.041077 0.222160 +v -0.076408 0.038575 0.225666 +v 0.016731 0.103674 0.112863 +v 0.008515 0.104976 0.119356 +v -0.103024 0.076273 0.058893 +v -0.101375 0.078913 0.058310 +v 0.005523 0.084810 0.187341 +v 0.003962 0.084285 0.188292 +v -0.100631 0.009064 0.218972 +v -0.105093 -0.022135 0.193358 +v 0.057416 0.084324 0.157188 +v 0.040067 0.080100 0.182333 +v 0.040755 0.102367 0.128777 +v 0.035326 0.103470 0.125768 +v 0.029471 0.010810 0.232959 +v 0.023390 0.046616 0.227015 +v 0.024760 0.105340 0.136990 +v 0.017486 0.106210 0.133469 +v 0.012923 0.106521 0.140100 +v 0.011936 0.106658 0.134675 +v 0.006730 0.106836 0.140916 +v 0.016902 0.106257 0.133596 +v -0.094591 0.022490 0.225248 +v -0.092170 0.011748 0.228040 +v -0.089293 0.034923 0.224648 +v -0.089907 0.012784 0.228472 +v 0.048501 0.099132 0.129374 +v -0.098484 0.009640 0.223592 +v 0.101250 -0.009617 0.207400 +v 0.109960 -0.014143 0.201691 +v -0.106155 -0.023810 0.186548 +v 0.006162 0.052493 0.226504 +v -0.100257 0.073048 0.172619 +v -0.096581 0.061395 0.196099 +v 0.054348 0.045353 0.218472 +v 0.041040 0.046507 0.223202 +v 0.067978 0.033737 0.217842 +v -0.096059 0.093734 0.137785 +v -0.092630 0.089653 0.152016 +v -0.092717 0.087976 0.155414 +v -0.097083 0.075811 0.174237 +v 0.040012 0.042565 0.224918 +v 0.043596 0.008424 0.230024 +v 0.059060 0.034255 0.221404 +v 0.036095 -0.000574 0.232571 +v -0.101014 0.047315 0.202065 +v -0.098047 0.040493 0.216201 +v -0.099777 0.058675 0.194279 +v 0.037115 0.090289 0.165682 +v -0.014297 0.054191 0.225436 +v -0.049519 0.055657 0.220298 +v 0.006327 0.059393 0.221211 +v 0.031805 0.044882 0.226075 +v 0.023946 0.050642 0.225395 +v -0.095746 0.095205 0.129076 +v -0.091628 0.096934 0.132117 +v 0.121325 -0.027213 0.189947 +v 0.123253 -0.024073 0.184193 +v 0.109184 -0.026517 0.201231 +v 0.065575 -0.009485 0.223467 +v 0.087776 0.010137 0.213596 +v 0.091380 0.005605 0.212225 +v 0.125266 -0.023631 0.075241 +v 0.131358 -0.043695 0.087121 +v 0.132557 -0.046752 0.108930 +v 0.116655 0.019588 0.128374 +v 0.126123 -0.026770 0.074490 +v 0.127813 -0.032585 0.074883 +v 0.129411 -0.037855 0.077457 +v 0.000039 0.104226 0.112863 +v 0.005712 0.105261 0.120948 +v 0.080961 0.074556 0.129717 +v 0.074979 0.075967 0.145290 +v -0.094385 0.095905 0.128327 +v -0.093818 0.083523 0.057430 +v 0.089774 0.038873 0.188869 +v 0.088470 0.026487 0.206012 +v 0.081566 0.032392 0.208347 +v 0.076285 0.057350 0.182140 +v 0.005105 0.085680 0.185974 +v 0.106522 0.026481 0.171225 +v 0.094466 0.046571 0.166793 +v 0.101822 0.018479 0.193506 +v 0.110381 0.000544 0.195610 +v 0.098738 0.032940 0.180422 +v 0.121880 -0.002812 0.163191 +v 0.113031 0.019571 0.161386 +v -0.103781 0.074188 0.059369 +v -0.102519 0.075612 0.053209 +v 0.084519 0.070017 0.133555 +v 0.082466 0.071013 0.138236 +v 0.082528 0.072504 0.131820 +v 0.049533 0.099336 0.112863 +v 0.036533 0.102614 0.120365 +v -0.111444 -0.006445 0.049409 +v 0.041838 0.050096 0.220750 +v 0.033592 0.055640 0.218978 +v 0.024370 0.054305 0.223040 +v -0.110979 0.021694 0.049632 +v 0.006264 0.056195 0.224186 +v 0.000038 0.052618 0.226584 +v 0.024644 0.057473 0.220034 +v 0.028322 0.082251 0.185396 +v 0.004390 0.060664 0.219894 +v 0.018006 0.059961 0.218894 +v 0.021969 0.082764 0.187100 +v 0.022738 0.082809 0.186758 +v 0.008314 0.083808 0.188638 +v 0.021144 0.082836 0.187263 +v 0.009937 0.083933 0.188214 +v 0.016239 0.083651 0.187390 +v 0.018402 0.084089 0.186099 +v 0.018902 0.083667 0.186633 +v 0.020320 0.083020 0.187235 +v 0.019557 0.083303 0.187021 +v -0.100404 0.084128 0.075218 +v -0.096809 0.082507 0.057584 +v 0.068353 0.088769 0.113956 +v 0.059174 0.095235 0.117887 +v 0.080948 0.064637 0.160318 +v 0.065769 0.061820 0.188504 +v -0.101671 0.078383 0.058367 +v -0.099470 0.080824 0.057909 +v -0.103621 0.072548 0.053005 +v -0.110753 0.034339 0.059362 +v 0.089778 0.063624 0.135552 +v 0.087069 0.066905 0.134898 +v 0.022258 0.104940 0.125641 +v 0.021425 0.105024 0.125742 +v 0.032578 0.102826 0.139497 +v 0.026438 0.103782 0.142009 +v -0.097048 0.094246 0.128817 +v -0.097597 0.093677 0.128950 +v -0.089724 0.038537 0.223445 +v 0.126698 -0.037981 0.181441 +v 0.124612 -0.035690 0.185644 +v -0.100710 0.089441 0.129842 +v -0.101415 0.088174 0.111621 +v -0.094693 0.009527 0.227072 +v -0.094714 0.010084 0.227038 +v -0.099181 0.092048 0.129738 +v 0.085889 0.052247 0.174874 +v -0.103798 0.074509 0.060761 +v 0.013793 0.105080 0.145353 +v 0.065990 0.029965 0.219848 +v -0.098193 0.081576 0.057673 +v 0.037560 0.102963 0.124276 +v 0.034270 0.103619 0.125798 +v 0.035323 0.103455 0.125637 +v 0.032668 0.103776 0.125342 +v -0.092060 0.095397 0.138648 +v -0.093183 0.010977 0.227736 +v 0.035872 0.103348 0.125395 +v -0.092456 0.063087 0.197122 +v -0.047686 0.076933 0.193619 +v 0.079773 0.076254 0.127143 +v -0.098507 0.004084 0.224075 +v -0.098397 0.004248 0.224166 +v -0.093012 0.077485 0.175209 +v 0.033794 0.083972 0.179692 +v 0.032229 0.084147 0.180275 +v 0.018947 0.086041 0.182720 +v 0.114350 -0.028336 0.197686 +v 0.114011 -0.022614 0.198356 +v 0.019612 0.086209 0.182229 +v 0.022792 0.085709 0.181963 +v 0.020382 0.086260 0.181890 +v 0.021536 0.086127 0.181715 +v 0.031546 0.084036 0.180834 +v 0.006218 0.106939 0.135424 +v 0.031074 0.083824 0.181442 +v 0.118710 -0.010764 0.185972 +v 0.021207 0.086188 0.181728 +v 0.023943 0.084904 0.182875 +v 0.030755 0.083501 0.182153 +v 0.024353 0.083996 0.184221 +v -0.095806 0.095122 0.132199 +v 0.030641 0.083099 0.182886 +v 0.030741 0.082644 0.183592 +v 0.031047 0.082169 0.184221 +v 0.023912 0.083231 0.185644 +v 0.023701 0.104710 0.124827 +v 0.024212 0.104581 0.124169 +v 0.089030 0.059288 0.152702 +v 0.019815 0.105100 0.125296 +v 0.023034 0.104833 0.125329 +v -0.099948 0.035140 0.214431 +v 0.124211 -0.035323 0.186251 +v 0.121710 -0.033031 0.190028 +v 0.023401 0.082968 0.186262 +v 0.000038 0.105551 0.146550 +v 0.078821 0.077928 0.122899 +v -0.100428 -0.001427 0.220025 +v 0.035305 0.080490 0.184668 +v 0.037363 0.102892 0.123476 +v 0.037472 0.102771 0.122648 +v 0.106926 0.034770 0.096877 +v 0.108117 0.031146 0.094875 +v 0.031495 0.103777 0.124151 +v 0.032004 0.103797 0.124822 +v 0.037362 0.102681 0.121816 +v 0.037042 0.102627 0.121038 +v 0.117961 -0.030301 0.194387 +v 0.117608 -0.018966 0.193864 +v -0.042135 0.020000 0.232863 +v -0.044916 0.104618 0.133845 +v -0.070253 0.089510 0.063835 +v -0.034385 0.095592 0.071956 +v -0.029593 0.096345 0.073865 +v -0.025127 0.097163 0.076460 +v -0.021088 0.098031 0.079686 +v -0.017566 0.098932 0.083475 +v -0.014641 0.099850 0.087743 +v -0.012377 0.100768 0.092399 +v -0.010825 0.101668 0.097338 +v -0.009426 0.103124 0.106122 +v -0.093817 0.083519 0.057415 +v -0.091401 0.096934 0.128493 +v -0.098628 0.080519 0.054238 +v -0.095925 0.082258 0.055028 +v -0.003929 0.104091 0.112044 +v 0.005390 0.105577 0.123380 +v 0.000038 0.107042 0.135698 +v -0.006296 0.103855 0.110607 +v 0.005279 0.105475 0.122549 +v -0.001269 0.104212 0.112777 +v -0.008170 0.103525 0.108588 +v 0.037043 0.103036 0.124242 +v 0.024533 0.104454 0.123401 +v 0.024642 0.104339 0.122572 +v 0.042379 0.053201 0.217651 +v 0.069553 0.037176 0.215031 +v 0.055123 0.048397 0.215242 +v 0.101917 0.047234 0.135538 +v 0.099771 0.051175 0.131413 +v 0.101912 0.040391 0.157993 +v 0.108140 0.033780 0.148581 +v 0.095419 0.056711 0.134694 +v 0.084795 0.020215 0.213241 +v 0.097767 0.053755 0.133310 +v 0.045346 0.101148 0.125238 +v 0.110330 -0.026829 0.200553 +v 0.061991 0.093876 0.113662 +v 0.024532 0.104244 0.121740 +v -0.102684 0.081289 0.075833 +v -0.093768 0.083099 0.055676 +v 0.054279 0.098041 0.113174 +v 0.056060 0.097227 0.113287 +v -0.089747 0.097234 0.133716 +v 0.128191 -0.039987 0.177055 +v 0.011639 0.105372 0.123405 +v 0.011750 0.105263 0.122575 +v -0.110597 0.045706 0.077694 +v 0.011317 0.105482 0.124176 +v 0.101301 0.049155 0.129245 +v -0.095169 0.009070 0.226862 +v 0.018204 0.104874 0.122506 +v -0.027330 0.018002 0.234075 +v -0.036279 0.019510 0.233353 +v 0.103384 0.046282 0.123532 +v 0.102544 0.047466 0.126581 +v 0.058768 0.095989 0.113459 +v 0.099060 0.015560 0.201734 +v 0.097366 0.012646 0.206165 +v 0.070650 0.040137 0.211533 +v 0.036886 0.081505 0.182040 +v -0.094086 0.034814 0.222893 +v -0.097865 0.036754 0.218577 +v -0.045656 0.103086 0.144640 +v -0.090326 0.095783 0.138949 +v -0.091832 0.096455 0.135256 +v 0.024211 0.104174 0.120965 +v 0.023033 0.104129 0.119779 +v 0.086986 0.023591 0.210015 +v -0.090816 0.046505 0.217679 +v -0.094996 0.044782 0.216621 +v 0.008384 0.087198 0.183123 +v 0.006759 0.087065 0.183542 +v -0.111500 -0.010629 0.051795 +v -0.111436 -0.009535 0.050537 +v 0.021423 0.104212 0.119333 +v 0.019813 0.104397 0.119746 +v 0.033741 0.080670 0.185254 +v 0.042512 0.068654 0.198234 +v 0.126149 -0.032408 0.180361 +v 0.000038 0.102709 0.153436 +v 0.092578 0.024597 0.202217 +v 0.055234 0.097695 0.114558 +v 0.019079 0.104528 0.120317 +v 0.018635 0.104638 0.120907 +v 0.119548 -0.015608 0.188263 +v -0.102390 0.077289 0.058668 +v 0.018313 0.104761 0.121677 +v 0.010663 0.086552 0.183851 +v 0.009998 0.086867 0.183437 +v 0.005910 0.086745 0.184159 +v 0.011169 0.086165 0.184403 +v 0.018314 0.104971 0.123336 +v 0.031174 0.103720 0.123374 +v 0.031174 0.103509 0.121714 +v 0.031065 0.103628 0.122542 +v 0.009220 0.087088 0.183189 +v -0.103628 0.082045 0.095442 +v -0.108059 -0.025029 0.173686 +v -0.110878 -0.012845 0.158388 +v -0.109741 -0.025839 0.158180 +v -0.111214 -0.026549 0.144606 +v -0.111418 -0.008085 0.049711 +v 0.105985 0.037876 0.099388 +v 0.070492 0.013958 0.220575 +v 0.000038 0.106951 0.141214 +v 0.031494 0.103370 0.120946 +v 0.103713 0.045783 0.120626 +v 0.011134 0.084472 0.187161 +v 0.011585 0.085287 0.185766 +v 0.011484 0.085733 0.185055 +v 0.018636 0.105044 0.124112 +v -0.102440 -0.013253 0.209548 +v -0.101693 -0.009432 0.213700 +v 0.032019 0.103216 0.120274 +v 0.033351 0.102023 0.112863 +v 0.032666 0.103069 0.119792 +v 0.034268 0.102803 0.119389 +v 0.035870 0.102641 0.119845 +v 0.005206 0.085236 0.186684 +v 0.074016 0.083472 0.116171 +v 0.076122 0.081257 0.117972 +v 0.103753 0.045722 0.120273 +v -0.054589 0.020267 0.231798 +v 0.116562 0.004692 0.173876 +v 0.006026 0.048421 0.228082 +v -0.112710 -0.023934 0.080920 +v 0.103732 0.045500 0.114321 +v 0.071354 0.086062 0.114790 +v -0.100749 0.078386 0.053651 +v 0.103970 0.044596 0.110197 +v 0.113322 -0.010595 0.197430 +v -0.090455 0.044088 0.220036 +v -0.094728 0.042709 0.218671 +v -0.112665 -0.023652 0.079397 +v 0.094756 0.009261 0.209731 +v 0.031611 0.081728 0.184652 +v 0.035350 0.083346 0.179850 +v -0.020386 0.020000 0.234051 +v 0.108512 -0.002507 0.200627 +v -0.047553 0.086978 0.177601 +v 0.040877 -0.002011 0.231475 +v -0.094467 0.040127 0.220555 +v -0.094289 0.037943 0.221730 +v 0.105394 -0.005977 0.204653 +v 0.032182 0.081283 0.185089 +v 0.035955 0.080583 0.184136 +v 0.036786 0.081960 0.181334 +v -0.107386 -0.025973 0.151713 +v 0.000038 0.010170 0.235772 +v 0.036481 0.082440 0.180708 +v -0.112948 -0.026136 0.109876 +v 0.006898 0.105781 0.125330 +v 0.018335 0.004736 0.235272 +v 0.010132 0.104974 0.119792 +v 0.006260 0.105159 0.120253 +v 0.104441 0.043000 0.106260 +v -0.045364 0.104499 0.139329 +v 0.006897 0.105080 0.119779 +v 0.054466 0.065603 0.193890 +v 0.053367 0.098290 0.113114 +v -0.112638 -0.023138 0.077936 +v 0.003335 0.102676 0.153389 +v 0.130625 -0.041698 0.081711 +v 0.105125 0.040727 0.102596 +v 0.010803 0.105586 0.124837 +v 0.036456 0.080793 0.183491 +v 0.005225 0.086114 0.185257 +v 0.005558 0.086507 0.184584 +v 0.129790 -0.043000 0.170190 +v 0.057364 0.005239 0.226110 +v -0.072649 0.017975 0.230170 +v -0.104184 -0.019865 0.199082 +v 0.131519 -0.047063 0.156982 +v 0.006031 0.084433 0.187899 +v -0.110939 0.016449 0.158401 +v 0.036773 0.081107 0.182776 +v 0.010134 0.105675 0.125343 +v 0.005713 0.105666 0.124153 +v 0.017991 0.084990 0.184749 +v 0.018434 0.085768 0.183333 +v 0.008516 0.105785 0.125766 +v -0.103292 -0.016873 0.204537 +v 0.006697 0.084128 0.188318 +v 0.092638 0.060144 0.135500 +v 0.005389 0.105368 0.121719 +v 0.077793 0.079324 0.120304 +v 0.011639 0.105162 0.121745 +v 0.011316 0.105077 0.120971 +v 0.132280 -0.048892 0.144307 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.250000 0.250000 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vt 0.750018 0.750008 +vn -0.8871 -0.0369 0.4601 +vn -0.9999 0.0088 -0.0110 +vn -0.9383 -0.0914 0.3334 +vn 0.5862 -0.7835 0.2062 +vn -0.6423 -0.4566 0.6156 +vn -0.6335 -0.0770 0.7699 +vn -0.6841 0.0157 0.7292 +vn -0.6472 -0.4897 0.5842 +vn -0.5994 -0.6618 0.4502 +vn -0.8295 -0.5537 -0.0736 +vn -0.7311 -0.4574 -0.5062 +vn -0.7768 -0.6080 -0.1638 +vn -0.6768 -0.6418 -0.3606 +vn -0.6408 -0.3504 -0.6831 +vn -0.6364 -0.1265 -0.7609 +vn -0.6030 -0.0835 -0.7933 +vn -0.6532 0.6611 -0.3692 +vn -0.6187 0.5064 -0.6006 +vn -0.6386 0.5148 -0.5720 +vn -0.6881 0.6722 -0.2730 +vn -0.6530 0.7303 0.2007 +vn -0.6933 0.6108 0.3825 +vn -0.6311 0.4024 0.6632 +vn -0.8387 -0.0875 0.5376 +vn -0.4772 -0.8784 -0.0260 +vn -0.9103 -0.2215 -0.3497 +vn -0.6190 -0.0269 -0.7849 +vn -0.6657 0.3604 -0.6534 +vn -0.2902 0.9464 0.1418 +vn -0.6971 0.0245 0.7166 +vn 0.3092 -0.8481 0.4303 +vn -0.7627 0.6207 0.1820 +vn -0.7448 -0.2553 0.6165 +vn -0.8056 0.2658 0.5295 +vn -0.6249 -0.1148 0.7722 +vn -0.6128 -0.3877 0.6886 +vn -0.7070 -0.6407 0.2994 +vn -0.7792 -0.5439 0.3115 +vn -0.7542 -0.6442 -0.1270 +vn -0.5994 -0.7893 -0.1334 +vn -0.6219 -0.7034 -0.3441 +vn -0.8261 -0.4284 -0.3661 +vn -0.9259 -0.2090 -0.3146 +vn -0.4075 -0.3437 -0.8461 +vn -0.5321 -0.2189 -0.8179 +vn -0.5965 0.0224 -0.8023 +vn -0.6792 0.2652 -0.6844 +vn -0.6948 0.5545 -0.4579 +vn -0.6892 0.6647 -0.2885 +vn -0.6875 0.7256 -0.0292 +vn -0.6487 0.6908 0.3194 +vn -0.3540 0.4152 0.8380 +vn -0.0416 0.5031 0.8632 +vn -0.8215 -0.3988 0.4075 +vn -0.8016 -0.4383 0.4065 +vn -0.8012 -0.4391 0.4065 +vn -0.7869 -0.4652 0.4054 +vn -0.5743 -0.8064 0.1411 +vn -0.3144 -0.4034 -0.8593 +vn -0.8942 0.3850 -0.2284 +vn -0.9140 0.3926 -0.1021 +vn -0.8946 0.3714 -0.2485 +vn -0.8702 0.3965 -0.2924 +vn -0.8764 0.3718 -0.3060 +vn -0.9952 -0.0381 -0.0900 +vn -0.9880 -0.1481 0.0436 +vn -0.9994 0.0342 0.0057 +vn 0.5153 -0.0428 0.8559 +vn -0.6458 -0.7206 0.2522 +vn -0.6250 -0.4974 0.6017 +vn -0.7164 -0.2479 0.6521 +vn -0.5969 -0.7933 0.1201 +vn -0.6384 -0.7042 -0.3107 +vn -0.6039 -0.6385 -0.4770 +vn -0.5999 -0.4577 -0.6562 +vn -0.5434 -0.4127 -0.7310 +vn -0.6673 0.3668 -0.6481 +vn -0.6541 0.1246 -0.7461 +vn -0.6636 0.1353 -0.7357 +vn -0.6740 0.3902 -0.6272 +vn -0.6222 0.6056 -0.4961 +vn -0.6110 0.6203 -0.4919 +vn -0.6243 0.7221 0.2980 +vn -0.5705 0.8188 0.0642 +vn -0.6166 0.7772 0.1253 +vn -0.7216 0.5373 0.4366 +vn -0.6562 0.4966 0.5681 +vn -0.7251 0.1499 0.6721 +vn -0.1313 0.2366 0.9627 +vn -0.8822 -0.3056 0.3582 +vn -0.7869 -0.5320 0.3127 +vn -0.8052 -0.4986 0.3211 +vn -0.6722 -0.6929 0.2608 +vn 0.3083 -0.6011 -0.7373 +vn -0.8014 0.0973 -0.5901 +vn -0.1817 0.9118 -0.3683 +vn -0.8251 0.4367 0.3585 +vn -1.0000 -0.0000 0.0000 +vn -0.9179 0.1683 -0.3593 +vn -0.8479 -0.0426 -0.5285 +vn -0.9933 -0.0141 -0.1150 +vn -0.9974 -0.0450 0.0554 +vn 0.9985 0.0424 -0.0340 +vn 0.9997 -0.0230 -0.0125 +vn 0.9999 0.0048 -0.0136 +vn 0.9999 -0.0114 0.0069 +vn 0.9999 0.0154 0.0031 +vn 1.0000 -0.0042 -0.0019 +vn 0.9998 -0.0159 -0.0073 +vn 1.0000 0.0057 -0.0050 +vn 0.9997 0.0017 -0.0224 +vn 0.9998 0.0188 -0.0111 +vn 0.9995 0.0280 -0.0115 +vn 0.9999 0.0011 -0.0122 +vn 0.9999 0.0064 -0.0087 +vn 0.9966 0.0807 -0.0191 +vn 0.9996 0.0258 -0.0081 +vn 0.9855 -0.1689 -0.0179 +vn 0.9999 0.0126 0.0037 +vn 0.9977 0.0648 0.0192 +vn 0.9999 0.0142 0.0033 +vn 1.0000 -0.0086 -0.0020 +vn 1.0000 0.0066 -0.0049 +vn 1.0000 -0.0028 -0.0067 +vn 0.9998 0.0185 -0.0113 +vn 0.7567 0.0543 0.6516 +vn -0.6908 0.1639 0.7042 +vn -0.7080 0.0071 0.7061 +vn -0.6445 -0.3486 0.6805 +vn -0.7182 -0.4859 0.4980 +vn -0.6978 -0.6672 0.2607 +vn -0.7453 -0.6300 -0.2181 +vn -0.6593 -0.7261 -0.1950 +vn -0.6831 -0.4187 -0.5984 +vn -0.6216 0.1725 -0.7641 +vn -0.6942 0.3387 -0.6351 +vn -0.5114 0.4711 -0.7187 +vn -0.6283 0.7644 0.1449 +vn -0.5007 0.8472 -0.1778 +vn -0.6382 0.7635 -0.0992 +vn -0.7165 0.6049 0.3475 +vn -0.7938 0.6062 -0.0490 +vn -0.6368 0.5296 0.5604 +vn 0.2575 0.0628 0.9642 +vn -0.7884 -0.4235 0.4461 +vn -0.4869 -0.8629 0.1355 +vn -0.5887 -0.3527 -0.7274 +vn -0.7247 0.5809 -0.3706 +vn -0.8229 0.4328 -0.3681 +vn -0.7787 0.5061 -0.3708 +vn -0.8668 0.3433 -0.3616 +vn 0.9997 0.0227 -0.0108 +vn 1.0000 0.0062 -0.0020 +vn 0.9991 -0.0405 -0.0142 +vn 0.9999 0.0134 -0.0064 +vn 1.0000 -0.0030 0.0005 +vn 0.9992 -0.0394 0.0024 +vn 0.9705 -0.2209 0.0969 +vn 0.9981 0.0564 -0.0253 +vn 0.9986 -0.0383 -0.0351 +vn -0.1434 -0.0994 0.9847 +vn -0.0731 -0.0392 0.9966 +vn -0.0992 -0.0137 0.9950 +vn -0.0917 0.1237 0.9881 +vn -0.1079 0.1171 0.9872 +vn -0.1062 -0.0018 0.9943 +vn -0.0687 0.0048 0.9976 +vn -0.0631 0.0009 0.9980 +vn -0.4033 0.3718 0.8361 +vn -0.1071 0.0007 0.9942 +vn -0.1762 0.3876 0.9048 +vn -0.1897 0.3554 0.9153 +vn -0.1426 0.4626 0.8750 +vn -0.0859 0.6924 0.7164 +vn -0.2485 0.5533 0.7951 +vn -0.2847 0.7496 0.5975 +vn -0.2138 0.8844 0.4149 +vn -0.0715 0.9157 0.3955 +vn -0.0992 0.1282 -0.9868 +vn -0.0994 -0.0003 -0.9950 +vn -0.1118 0.1169 -0.9868 +vn -0.1066 -0.0270 -0.9939 +vn -0.0844 -0.0014 -0.9964 +vn -0.1154 0.0029 -0.9933 +vn -0.1072 0.0025 -0.9942 +vn -0.1003 -0.0079 -0.9949 +vn -0.0656 -0.1596 -0.9850 +vn -0.0940 0.0013 -0.9956 +vn -0.1073 -0.5043 -0.8568 +vn -0.1016 -0.2923 -0.9509 +vn -0.0677 -0.5560 -0.8284 +vn -0.1481 -0.1513 -0.9773 +vn -0.1012 -0.7396 0.6654 +vn -0.0689 -0.8542 0.5154 +vn -0.0656 -0.5523 0.8311 +vn -0.1009 -0.4645 0.8798 +vn -0.3489 -0.6629 0.6624 +vn -0.2935 -0.4877 0.8222 +vn -0.4527 -0.4196 0.7868 +vn -0.4886 -0.6306 0.6030 +vn -0.5732 -0.4869 0.6591 +vn -0.2619 -0.8714 0.4147 +vn -0.4863 -0.7891 0.3752 +vn -0.5953 -0.7254 0.3456 +vn -0.7537 -0.5111 0.4132 +vn -0.2138 -0.9635 0.1614 +vn -0.3909 -0.9083 0.1490 +vn -0.5391 -0.8358 0.1036 +vn -0.6724 -0.3339 0.6606 +vn -0.7335 -0.6664 0.1336 +vn -0.9734 -0.1376 0.1832 +vn -0.9055 -0.3988 0.1448 +vn -0.8515 -0.2559 0.4578 +vn -0.7015 -0.7074 -0.0869 +vn -0.8615 -0.4964 -0.1069 +vn -0.9825 -0.1662 -0.0847 +vn -0.1551 -0.7727 0.6155 +vn -0.1708 -0.5171 0.8387 +vn -0.7420 -0.5828 -0.3312 +vn -0.9065 -0.2654 -0.3283 +vn -0.7817 -0.3693 -0.5026 +vn -0.4838 -0.5429 -0.6864 +vn -0.3717 -0.4962 -0.7846 +vn -0.2796 -0.7946 -0.5389 +vn -0.4114 -0.8740 -0.2586 +vn -0.2395 -0.9444 -0.2252 +vn -0.5853 -0.6753 -0.4489 +vn -0.4768 -0.8647 -0.1582 +vn -0.5864 -0.7921 -0.1693 +vn -0.5721 -0.4327 -0.6968 +vn -0.6601 -0.3487 -0.6654 +vn -0.1319 -0.8291 -0.5433 +vn -0.2471 -0.5281 -0.8124 +vn -0.1668 -0.5316 -0.8304 +vn -0.0994 -0.7683 -0.6324 +vn -0.4004 0.8784 0.2609 +vn -0.1636 0.1399 0.9766 +vn -0.3753 0.8751 -0.3055 +vn -0.1825 0.8840 -0.4305 +vn -0.2779 0.7667 -0.5788 +vn -0.1998 0.5433 -0.8154 +vn -0.3367 0.6179 -0.7105 +vn -0.1946 0.3332 -0.9226 +vn -0.1882 0.1195 -0.9748 +vn -0.2246 0.9715 0.0760 +vn -0.3164 0.9435 0.0987 +vn -0.1643 0.9590 0.2310 +vn -0.4983 0.6556 0.5673 +vn -0.2908 0.1627 0.9428 +vn -0.4264 0.4249 0.7985 +vn -0.6657 0.7412 0.0868 +vn -0.7752 0.6192 0.1251 +vn -0.6924 0.6477 0.3180 +vn -0.8657 0.4249 0.2647 +vn -0.7400 0.4888 0.4620 +vn -0.6278 0.4447 0.6388 +vn -0.7831 0.2131 0.5842 +vn -0.6293 0.1702 0.7583 +vn -0.3966 0.1122 0.9111 +vn -0.4883 0.0514 0.8712 +vn -0.6045 0.7610 0.2356 +vn -0.6002 0.5949 0.5346 +vn -0.4856 0.3500 0.8011 +vn -0.5206 0.8171 0.2475 +vn -0.9216 0.1170 0.3700 +vn -0.5700 -0.1163 0.8134 +vn -0.7624 -0.1114 0.6374 +vn -0.9095 -0.0298 0.4146 +vn -0.8161 0.5455 -0.1908 +vn -0.8997 0.2376 -0.3661 +vn -0.9281 0.3447 -0.1406 +vn -0.8262 0.5634 0.0079 +vn -0.9517 0.3066 0.0174 +vn -0.9878 0.1068 -0.1136 +vn -0.9816 0.1350 0.1351 +vn -0.8742 0.0747 -0.4798 +vn -0.7618 0.4659 -0.4501 +vn -0.6914 0.2925 -0.6606 +vn -0.6007 0.0835 -0.7951 +vn -0.1344 -0.2738 0.9524 +vn -0.2356 -0.1747 0.9560 +vn -0.8408 -0.1490 0.5205 +vn -0.9623 -0.0488 0.2677 +vn -0.9130 -0.0279 -0.4070 +vn -0.7809 -0.1102 -0.6148 +vn -0.5690 -0.1041 -0.8157 +vn -0.3657 0.3407 -0.8661 +vn -0.6960 0.6410 -0.3236 +vn -0.6801 0.7247 -0.1109 +vn -0.6287 0.4650 -0.6233 +vn -0.4701 0.1605 -0.8679 +vn -0.4901 0.3292 -0.8071 +vn -0.3562 0.0965 -0.9294 +vn -0.5356 0.5372 -0.6516 +vn -0.6112 0.6778 -0.4086 +vn -0.6206 0.7708 -0.1442 +vn -0.3009 0.1210 -0.9460 +vn -0.5515 0.8161 -0.1729 +vn -0.4610 0.5521 -0.6948 +vn -0.5078 0.7499 -0.4241 +vn -0.4355 0.8898 -0.1365 +vn -0.9401 -0.0734 -0.3329 +vn -0.2143 -0.1757 -0.9608 +vn -0.3824 -0.1536 -0.9111 +vn -0.4726 -0.2127 -0.8552 +vn -0.2431 0.9533 -0.1791 +vn -0.4991 0.8665 -0.0001 +vn -0.5812 0.8135 0.0202 +vn -0.6798 0.7333 -0.0126 +vn -0.4097 0.9122 -0.0031 +vn -0.2113 0.9737 -0.0848 +vn -0.1192 0.9921 -0.0392 +vn -0.1515 -0.9819 -0.1138 +vn -0.1214 -0.9892 0.0827 +vn -0.0855 -0.9963 0.0114 +vn -0.3005 -0.1699 -0.9385 +vn -0.3118 -0.1627 0.9361 +vn -0.4082 -0.1593 0.8989 +vn -0.0705 -0.8590 -0.5071 +vn -0.0882 -0.9709 -0.2228 +vn -0.0765 -0.9613 0.2648 +vn -0.0784 -0.1728 0.9818 +vn -0.0943 -0.0437 0.9946 +vn -0.0855 0.6809 -0.7274 +vn -0.0802 0.9073 -0.4128 +vn -0.1409 0.4561 -0.8787 +vn -0.1813 0.3872 -0.9040 +vn -0.0816 0.9927 0.0884 +vn -0.0788 0.9819 -0.1724 +vn -0.4421 0.3985 -0.8036 +vn 0.2629 -0.1207 -0.9572 +vn -0.2412 -0.3440 -0.9075 +vn -0.2301 -0.3446 -0.9101 +vn -0.2369 -0.3442 -0.9085 +vn -0.0827 -0.8034 -0.5897 +vn -0.0866 -0.8026 -0.5902 +vn -0.1771 -0.6593 -0.7307 +vn -0.1534 -0.7168 -0.6801 +vn -0.1759 -0.3803 -0.9080 +vn -0.2741 -0.1669 -0.9471 +vn -0.1519 -0.4377 -0.8862 +vn -0.3118 -0.1444 -0.9391 +vn -0.1428 0.7052 -0.6945 +vn -0.1918 0.5955 -0.7801 +vn -0.2538 0.8074 -0.5327 +vn -0.1195 0.8645 -0.4883 +vn -0.0263 0.8830 -0.4686 +vn -0.4482 0.2519 -0.8577 +vn 0.1520 -0.3499 -0.9244 +vn 0.1775 -0.3378 -0.9243 +vn 0.1119 -0.3681 -0.9230 +vn 0.0428 -0.3977 -0.9165 +vn -0.3572 -0.7061 -0.6114 +vn -0.0918 -0.9942 -0.0552 +vn -0.0601 -0.9962 -0.0635 +vn -0.0871 -0.9946 -0.0564 +vn -0.0565 -0.9963 -0.0645 +vn -0.6656 0.2012 -0.7187 +vn -0.6196 0.1983 -0.7594 +vn -0.5910 0.1929 -0.7832 +vn 0.0171 0.4344 -0.9005 +vn -0.0321 0.5642 -0.8250 +vn 0.0185 0.5394 -0.8418 +vn -0.3003 0.7063 -0.6411 +vn -0.1191 0.7843 -0.6089 +vn -0.0106 0.8070 -0.5905 +vn -0.9070 0.1628 -0.3884 +vn -0.8026 0.1134 -0.5856 +vn -0.5933 0.5391 -0.5978 +vn -0.7321 -0.6812 -0.0071 +vn -0.2587 -0.3430 -0.9030 +vn -0.7914 -0.4848 -0.3723 +vn -0.7920 -0.4840 -0.3720 +vn -0.7838 -0.4364 -0.4418 +vn -0.9984 0.0232 -0.0523 +vn -0.9326 0.0636 -0.3553 +vn -0.9971 0.0274 -0.0707 +vn -0.7677 -0.4061 -0.4958 +vn -0.7368 -0.3586 -0.5732 +vn -0.4475 -0.2294 0.8643 +vn 0.1464 0.2972 0.9435 +vn 0.2493 0.2521 0.9351 +vn -0.0119 0.3707 0.9287 +vn -0.1377 0.4068 0.9031 +vn -0.1412 0.8865 0.4406 +vn -0.1941 0.8698 0.4537 +vn -0.2994 0.8054 0.5115 +vn -0.0400 0.7037 0.7094 +vn -0.0504 0.6152 0.7867 +vn -0.5794 -0.2715 0.7685 +vn -0.6545 -0.2582 0.7106 +vn -0.6380 -0.2507 0.7280 +vn -0.2430 -0.7219 0.6479 +vn -0.0031 -0.6323 0.7747 +vn -0.0636 -0.6556 0.7524 +vn -0.6930 -0.1731 0.6999 +vn -0.1050 -0.7926 0.6006 +vn -0.0124 -0.8120 0.5835 +vn 0.0248 -0.9922 0.1224 +vn -0.0009 -0.9932 0.1164 +vn -0.2403 -0.9690 0.0573 +vn -0.2998 -0.9531 0.0414 +vn -0.4130 -0.7511 0.5150 +vn -0.3784 -0.6695 0.6392 +vn -0.3586 -0.6247 0.6937 +vn -0.3070 -0.5112 0.8027 +vn 0.2407 -0.1535 0.9584 +vn 0.2637 -0.1644 0.9505 +vn 0.1970 -0.1328 0.9714 +vn 0.1130 -0.0926 0.9893 +vn -0.3601 0.4183 0.8339 +vn -0.2599 0.6079 0.7503 +vn -0.2017 0.6860 0.6991 +vn -0.1258 0.7182 0.6844 +vn -0.1019 0.6446 0.7577 +vn -0.2208 0.1603 0.9621 +vn -0.2241 0.4527 0.8630 +vn -0.1475 0.3068 0.9403 +vn -0.2706 0.1248 0.9546 +vn -0.9998 0.0048 0.0208 +vn -0.9995 -0.0003 0.0312 +vn -0.9999 0.0092 -0.0067 +vn -0.9998 0.0136 -0.0128 +vn -1.0000 0.0074 -0.0058 +vn -0.9990 0.0083 -0.0430 +vn -0.9993 0.0029 -0.0370 +vn -1.0000 -0.0000 -0.0014 +vn -0.9998 0.0065 0.0164 +vn -0.9893 0.0059 -0.1458 +vn -0.9999 0.0107 0.0105 +vn -0.9978 0.0018 0.0659 +vn -1.0000 0.0002 0.0017 +vn -0.9984 0.0011 -0.0561 +vn -1.0000 0.0067 -0.0029 +vn -0.9999 0.0009 0.0163 +vn -0.9999 -0.0103 0.0133 +vn -0.9948 -0.0325 0.0969 +vn -0.9946 -0.0140 0.1028 +vn -0.9994 0.0038 0.0344 +vn -0.9990 -0.0007 0.0447 +vn -0.9998 0.0135 -0.0169 +vn -0.9998 -0.0117 0.0155 +vn -0.6944 0.4879 0.5290 +vn -0.6700 0.3996 0.6256 +vn -0.6988 0.5100 0.5016 +vn -0.7075 0.5862 0.3949 +vn -0.9698 0.0129 0.2434 +vn -0.9363 0.0396 0.3490 +vn -0.7874 -0.6164 -0.0052 +vn -0.7024 0.4976 0.5088 +vn -0.6734 0.3766 0.6362 +vn -0.7060 0.3097 0.6369 +vn -0.6711 0.5831 0.4579 +vn -0.8530 -0.0389 0.5205 +vn -0.2236 0.3975 0.8899 +vn -0.8326 0.4702 0.2927 +vn -0.3134 -0.7311 -0.6060 +vn -0.3278 -0.7369 -0.5913 +vn -0.2784 -0.7161 -0.6400 +vn -0.3543 -0.7467 -0.5630 +vn -0.5467 -0.3125 -0.7768 +vn -0.6706 -0.0935 -0.7359 +vn -0.6447 -0.1472 -0.7501 +vn -0.6886 0.1075 -0.7172 +vn 0.0499 -0.6725 0.7384 +vn -0.5714 -0.6022 0.5575 +vn -0.6048 -0.4582 0.6514 +vn -0.5994 -0.4890 0.6337 +vn -0.6152 -0.3735 0.6943 +vn -0.8074 0.0751 0.5852 +vn -0.8171 0.0054 0.5765 +vn -0.8151 0.1277 0.5651 +vn -0.8192 0.0059 0.5734 +vn -0.8478 0.2756 -0.4531 +vn -0.8198 0.2144 0.5310 +vn -0.7430 -0.1698 0.6473 +vn -0.6698 0.1969 0.7160 +vn -0.8062 -0.3105 -0.5036 +vn -0.8227 -0.3218 -0.4687 +vn -0.7137 -0.1208 -0.6900 +vn -0.7159 -0.0946 -0.6918 +vn -0.8048 0.1825 -0.5649 +vn -0.8037 0.1712 -0.5698 +vn -0.7740 0.3762 -0.5093 +vn -0.0190 -0.9665 -0.2559 +vn 0.0116 -0.9731 -0.2299 +vn 0.0067 -0.9846 -0.1744 +vn 0.0059 -0.8870 -0.4617 +vn -0.0665 -0.9974 -0.0274 +vn -0.0677 -0.9973 -0.0270 +vn 0.0350 -0.9834 0.1780 +vn -0.0254 -0.9133 -0.4065 +vn -0.0797 -0.9792 -0.1868 +vn 0.2544 0.9448 -0.2065 +vn 0.5627 0.8109 -0.1605 +vn 0.2857 0.9366 -0.2031 +vn 0.5673 0.8079 -0.1596 +vn -0.1559 0.9865 -0.0508 +vn -0.3986 0.8900 -0.2214 +vn 0.0026 1.0000 -0.0026 +vn 0.7464 0.5435 0.3842 +vn 0.0313 0.9995 0.0098 +vn -0.3136 0.9490 -0.0312 +vn -0.0126 0.9999 0.0028 +vn 0.1023 0.9943 0.0313 +vn 0.0712 0.9972 0.0249 +vn -0.0089 0.9929 0.1186 +vn 0.0101 0.9854 0.1700 +vn -0.4114 0.9104 -0.0445 +vn -0.1069 0.8006 -0.5896 +vn -0.0910 0.7797 -0.6195 +vn -0.1794 0.8430 -0.5071 +vn -0.0130 0.7482 -0.6634 +vn 0.0087 0.7651 -0.6438 +vn 0.0033 0.7049 -0.7093 +vn -0.0012 0.7111 -0.7031 +vn -0.0009 0.7109 -0.7033 +vn -0.0045 0.6974 -0.7166 +vn -0.1955 0.8166 -0.5431 +vn -0.2435 0.8143 -0.5270 +vn 1.0000 -0.0023 -0.0012 +vn 1.0000 -0.0079 0.0028 +vn 0.9999 -0.0132 0.0038 +vn 1.0000 -0.0098 -0.0010 +vn 1.0000 -0.0059 -0.0011 +vn 1.0000 -0.0022 0.0012 +vn 0.9998 -0.0179 -0.0074 +vn 1.0000 -0.0000 0.0000 +vn 1.0000 -0.0041 0.0019 +vn 0.9996 -0.0262 0.0142 +vn 0.9999 -0.0023 0.0154 +vn 0.9997 -0.0206 0.0111 +vn 0.9982 -0.0393 -0.0454 +vn 1.0000 -0.0000 -0.0001 +vn 1.0000 -0.0016 -0.0091 +vn 1.0000 -0.0036 -0.0038 +vn 0.9994 -0.0050 -0.0339 +vn 0.9997 -0.0251 -0.0074 +vn 1.0000 0.0001 0.0002 +vn 0.9897 -0.1020 0.1010 +vn 0.0074 -1.0000 -0.0040 +vn 0.0047 -1.0000 0.0001 +vn 0.0039 -0.9666 -0.2562 +vn -0.0037 -0.9908 -0.1353 +vn -0.0002 -1.0000 -0.0024 +vn -0.0168 -0.9794 -0.2014 +vn -0.0014 -0.9699 -0.2435 +vn -0.0121 -0.9999 -0.0051 +vn -0.0032 -1.0000 -0.0071 +vn 0.0149 -0.9993 -0.0339 +vn -0.0028 -0.9732 -0.2299 +vn -0.0115 0.6698 0.7425 +vn 0.0041 0.6187 0.7856 +vn 0.0131 0.7611 0.6485 +vn -0.0144 0.8619 0.5069 +vn 0.0093 0.9937 0.1120 +vn -0.0080 0.9985 0.0533 +vn 0.0019 -0.9558 -0.2941 +vn 0.0196 0.2802 0.9597 +vn -0.0035 -0.9632 -0.2689 +vn 0.0029 0.7220 0.6919 +vn -0.0269 0.6363 0.7710 +vn -0.0133 0.5818 0.8132 +vn -0.0158 0.8466 0.5320 +vn 0.0090 0.9939 0.1095 +vn 0.0019 0.9987 0.0506 +vn 0.0194 -0.7092 0.7047 +vn -0.0035 0.6208 0.7840 +vn -0.0461 0.6500 0.7585 +vn -0.0198 0.6322 0.7746 +vn 0.0252 0.5998 0.7997 +vn -0.0300 0.9962 0.0815 +vn 0.0140 0.9789 0.2039 +vn -0.0011 0.2308 -0.9730 +vn -0.0016 0.2110 -0.9775 +vn 0.0031 -0.2462 -0.9692 +vn -0.0028 -0.2355 -0.9719 +vn 0.0012 0.0988 -0.9951 +vn 0.0048 0.2352 -0.9719 +vn 0.0088 -0.2495 -0.9683 +vn -0.0014 -0.2487 -0.9686 +vn 1.0000 -0.0004 -0.0008 +vn 1.0000 0.0010 -0.0008 +vn 1.0000 0.0006 -0.0002 +vn 1.0000 -0.0076 -0.0056 +vn 0.9999 -0.0109 -0.0074 +vn 0.0002 0.1344 -0.9909 +vn 0.0012 0.1312 -0.9914 +vn 0.0014 -0.0117 -0.9999 +vn 0.0015 -0.0114 -0.9999 +vn 0.0012 -0.3062 -0.9520 +vn 0.0056 -0.3195 -0.9476 +vn -0.0048 -0.5748 -0.8183 +vn 0.0129 -0.6458 -0.7634 +vn -0.0101 -0.7998 -0.6002 +vn 0.0119 -0.8793 -0.4760 +vn -0.0105 -0.9497 -0.3130 +vn 0.0045 -0.9761 -0.2172 +vn -0.0041 -0.9999 -0.0097 +vn 0.0005 -0.9999 0.0110 +vn 0.0010 -0.9904 -0.1383 +vn -0.0003 -0.9917 -0.1283 +vn -0.0000 0.6820 -0.7314 +vn 0.0019 0.6822 -0.7312 +vn 0.0023 0.6619 -0.7496 +vn 0.0001 0.6813 -0.7320 +vn 0.0060 0.5275 -0.8495 +vn -0.0124 0.6770 -0.7358 +vn 0.0000 0.6815 -0.7318 +vn -0.0028 0.6839 -0.7296 +vn -0.0001 0.6820 -0.7313 +vn 0.0030 0.6978 -0.7163 +vn 0.0127 0.6857 -0.7278 +vn 0.0088 0.6823 -0.7310 +vn -0.0001 0.6820 -0.7314 +vn -0.0003 0.6820 -0.7313 +vn -0.0055 0.5343 -0.8453 +vn 0.0149 0.6810 -0.7322 +vn -0.0012 0.6821 -0.7313 +vn -0.0023 0.6820 -0.7313 +vn -0.0166 0.6818 -0.7313 +vn -0.0077 0.6823 -0.7310 +vn -0.0100 0.7020 -0.7121 +vn -0.0000 0.6818 -0.7315 +vn 0.0002 0.6820 -0.7314 +vn -0.0001 0.6815 -0.7318 +vn -0.0021 0.6832 -0.7303 +vn -0.0002 0.6818 -0.7315 +vn -0.0000 0.6820 -0.7313 +vn -0.0001 0.6821 -0.7313 +vn 0.0290 0.6963 -0.7172 +vn 0.0284 0.6842 -0.7288 +vn 0.0001 0.6815 -0.7318 +vn -0.3295 0.9261 -0.1835 +vn 0.3587 0.9104 -0.2062 +vn -0.0111 -0.8099 -0.5865 +vn -0.0204 -0.6100 -0.7922 +vn -0.0015 -0.6507 -0.7593 +vn 0.0027 -0.2631 -0.9648 +vn 0.0140 -0.3422 -0.9395 +vn -0.0094 -0.1286 -0.9916 +vn 0.0098 -0.4111 -0.9115 +vn -0.0979 -0.4108 -0.9064 +vn 0.0013 0.1926 -0.9813 +vn -0.0034 0.1627 -0.9867 +vn 0.0012 0.1774 -0.9841 +vn 0.0231 -0.3417 -0.9395 +vn 0.0329 -0.3443 -0.9383 +vn -0.0237 -0.3564 -0.9340 +vn -0.2321 -0.3358 -0.9129 +vn -0.0077 -0.3483 -0.9374 +vn -0.0056 -0.3446 -0.9387 +vn 0.0087 0.4749 0.8800 +vn 0.2549 0.1653 0.9527 +vn 0.3219 0.3811 0.8667 +vn 0.0125 0.3208 0.9471 +vn 0.0058 0.1961 0.9806 +vn 0.0167 0.1529 0.9881 +vn 0.0127 0.1317 0.9912 +vn 0.0019 -0.2237 0.9747 +vn 0.1991 -0.4644 0.8630 +vn 0.0026 -0.2294 0.9733 +vn 0.0137 -0.7917 0.6108 +vn 0.0104 -0.7678 0.6406 +vn 0.2605 -0.8720 0.4144 +vn 0.0034 -0.8044 0.5940 +vn -0.0060 -0.9997 0.0234 +vn -0.0091 -0.9726 -0.2324 +vn 0.0168 -0.7676 -0.6408 +vn 0.1067 -0.9636 -0.2452 +vn -0.0097 -0.3304 -0.9438 +vn -0.0042 -0.3361 -0.9418 +vn -0.0049 -0.3354 -0.9421 +vn 0.0008 -0.3413 -0.9399 +vn -0.0194 0.9429 -0.3325 +vn 0.3125 0.9159 -0.2521 +vn 0.2625 0.6343 -0.7272 +vn -0.0086 0.7405 -0.6720 +vn 0.1824 0.3630 -0.9138 +vn 0.2068 0.9784 0.0041 +vn 0.9169 0.2552 0.3070 +vn 0.9190 0.1224 0.3747 +vn 0.9601 0.0534 -0.2746 +vn 0.9869 -0.1332 0.0906 +vn 0.9451 -0.0810 0.3167 +vn -0.0040 0.0273 -0.9996 +vn -0.0008 0.0236 -0.9997 +vn -0.0013 0.0242 -0.9997 +vn 0.0020 0.0205 -0.9998 +vn 0.0040 0.9986 -0.0523 +vn -0.0000 0.9991 -0.0434 +vn 0.0025 0.9988 -0.0490 +vn -0.0015 0.9992 -0.0401 +vn 0.0015 0.7045 0.7097 +vn -0.0024 0.6985 0.7156 +vn -0.0000 0.7021 0.7120 +vn -0.0039 0.6961 0.7179 +vn 0.0041 -0.6788 0.7343 +vn -0.0001 -0.6821 0.7312 +vn 0.0001 -0.6819 0.7315 +vn -0.0041 -0.6852 0.7283 +vn 0.0037 -0.8023 -0.5969 +vn -0.0014 -0.7865 -0.6176 +vn 0.0029 -0.8001 -0.5999 +vn -0.0022 -0.7842 -0.6205 +vn -0.0048 -0.7742 0.6329 +vn 0.0084 -0.6826 0.7308 +vn -0.0039 -0.7682 0.6402 +vn 0.0096 -0.6729 0.7396 +vn -0.0358 0.0955 0.9948 +vn 0.2388 -0.0225 0.9708 +vn 0.2357 -0.0177 0.9717 +vn 0.0131 -0.9999 0.0077 +vn 0.0021 -1.0000 -0.0033 +vn 0.0016 -1.0000 -0.0037 +vn -0.0094 -0.9998 -0.0147 +vn -0.0083 -0.3046 -0.9524 +vn 0.0097 -0.1295 -0.9915 +vn 0.0143 -0.4412 -0.8973 +vn -0.0079 -0.3436 -0.9391 +vn 0.0204 -0.7217 -0.6919 +vn 0.3416 0.6481 -0.6807 +vn 0.0090 0.6916 -0.7223 +vn 0.3089 0.7711 -0.5568 +vn 0.0196 0.6188 -0.7853 +vn 0.0012 0.6790 -0.7342 +vn -0.0026 0.6645 -0.7473 +vn -0.0078 0.9775 -0.2110 +vn 0.0074 0.9989 -0.0470 +vn 0.0063 0.9982 -0.0593 +vn -0.0086 0.9757 -0.2191 +vn 0.0233 0.5770 -0.8164 +vn 0.0055 0.9913 0.1314 +vn 0.3508 0.8889 0.2947 +vn 0.0080 0.9479 0.3185 +vn 0.0035 0.9766 0.2152 +vn -0.0006 0.9092 0.4165 +vn 0.0110 0.8773 0.4799 +vn 0.0064 0.8691 0.4945 +vn -0.0192 0.8069 0.5904 +vn -0.0022 0.7813 0.6241 +vn -0.0647 0.8672 0.4938 +vn 0.0473 0.6980 0.7145 +vn -0.0107 0.0324 0.9994 +vn -0.0421 0.1270 0.9910 +vn -0.0375 0.1377 0.9898 +vn 0.0425 0.9918 -0.1209 +vn 0.1426 0.9482 0.2838 +vn 0.0009 0.9928 -0.1198 +vn 0.0067 0.9579 -0.2871 +vn -0.0113 0.7444 0.6677 +vn 0.0060 0.7160 0.6980 +vn 0.0019 0.7228 0.6910 +vn -0.0214 0.7602 0.6493 +vn -0.0018 0.1601 0.9871 +vn -0.0011 0.2388 0.9711 +vn 0.0248 0.2806 0.9595 +vn -0.0015 0.0242 0.9997 +vn 0.0147 0.7057 0.7083 +vn 0.0013 0.7319 0.6814 +vn 0.0049 0.7249 0.6888 +vn 0.0215 0.6920 0.7216 +vn -0.0024 0.1229 0.9924 +vn -0.0211 0.2072 0.9781 +vn 1.0000 -0.0029 0.0061 +vn 0.9996 0.0285 -0.0030 +vn 0.9947 -0.1025 -0.0008 +vn 0.9706 -0.1843 0.1546 +vn 0.0038 -0.9053 -0.4247 +vn -0.0010 -0.8970 -0.4420 +vn 0.0019 -0.9033 -0.4290 +vn 0.0134 -0.9660 -0.2583 +vn 0.0121 -0.8636 -0.5041 +vn -0.0021 -0.8718 -0.4898 +vn -0.0056 -0.5052 0.8630 +vn -0.0138 -0.3566 0.9342 +vn -0.0286 -0.0417 0.9987 +vn -0.0186 -0.8572 -0.5147 +vn -0.0421 -0.8785 -0.4758 +vn -0.0618 -0.8927 -0.4464 +vn 0.0005 -0.4082 -0.9129 +vn 0.0014 -0.4012 -0.9160 +vn 0.0013 -0.4017 -0.9158 +vn 0.0005 -0.4088 -0.9126 +vn -0.0213 -0.9369 -0.3489 +vn -0.0071 -0.9467 -0.3221 +vn 0.0229 0.2280 -0.9734 +vn -0.0191 0.2312 -0.9727 +vn 0.0021 -0.4799 -0.8773 +vn 0.0025 -0.2455 -0.9694 +vn 0.0015 -0.5488 -0.8360 +vn 0.0002 -0.5278 -0.8493 +vn 0.0010 -0.5477 -0.8367 +vn -0.0059 -0.5008 -0.8655 +vn -0.0010 -0.4832 -0.8755 +vn -0.0110 -0.5056 -0.8627 +vn 0.0006 -0.3094 -0.9509 +vn -0.0003 -0.9244 -0.3813 +vn 0.0020 -0.9156 -0.4020 +vn -0.0008 -0.8834 -0.4686 +vn 0.0054 -0.8686 -0.4955 +vn 0.8051 -0.4483 0.3883 +vn 0.6441 -0.3097 0.6994 +vn 0.7105 -0.4181 -0.5661 +vn 0.7280 -0.4432 -0.5231 +vn 0.6813 -0.6180 -0.3922 +vn 0.6951 -0.6418 -0.3239 +vn 0.4061 -0.9102 0.0818 +vn 0.7070 0.2145 0.6739 +vn 0.6883 0.1365 -0.7124 +vn 0.5500 -0.2768 -0.7879 +vn 0.7440 0.3110 0.5913 +vn 0.7041 0.1249 0.6990 +vn 0.7966 0.5512 -0.2483 +vn 0.1154 0.6735 0.7301 +vn 0.7652 0.5534 0.3290 +vn 0.5931 0.6221 0.5111 +vn 0.3662 0.9254 -0.0977 +vn 0.4365 0.8995 -0.0185 +vn 0.7994 0.6008 0.0001 +vn 0.7011 0.4829 -0.5246 +vn 0.6609 0.6495 -0.3760 +vn 0.6644 0.7386 0.1142 +vn 0.6010 -0.7723 -0.2060 +vn 0.6751 -0.3395 -0.6549 +vn 0.6830 -0.6508 -0.3316 +vn 0.6201 -0.0003 -0.7845 +vn 0.7036 -0.1596 -0.6925 +vn 0.5844 0.7264 0.3617 +vn 0.6218 0.7236 0.2997 +vn 0.5782 0.7977 0.1713 +vn 0.6378 0.7467 0.1890 +vn 0.7111 0.6540 0.2581 +vn 0.9018 0.4240 0.0842 +vn 0.9853 -0.1710 -0.0022 +vn 0.8716 -0.3410 0.3523 +vn 0.5996 -0.8003 -0.0015 +vn 0.5998 -0.8002 -0.0015 +vn 0.3775 0.7227 0.5789 +vn 0.5887 0.1699 0.7903 +vn 0.5873 0.1612 0.7932 +vn 0.7103 0.2550 0.6562 +vn 0.7065 0.2304 0.6691 +vn 0.7220 -0.3823 0.5766 +vn 0.5808 -0.4876 0.6519 +vn 0.5392 -0.4827 0.6901 +vn 0.7609 -0.5670 -0.3155 +vn 0.7137 -0.6847 -0.1478 +vn 0.7197 -0.6662 -0.1955 +vn 0.7332 -0.6690 -0.1218 +vn 0.7186 -0.6848 -0.1212 +vn 0.7224 -0.0245 -0.6910 +vn 0.7217 -0.0249 -0.6918 +vn 0.7953 -0.4511 -0.4050 +vn 0.7210 -0.0256 -0.6925 +vn 0.7182 -0.0765 -0.6917 +vn 0.7291 -0.0311 -0.6837 +vn 0.6687 -0.2937 -0.6831 +vn 0.6799 -0.6657 -0.3075 +vn 0.7208 -0.6891 -0.0747 +vn 0.6834 -0.5439 -0.4870 +vn 0.7067 -0.1655 -0.6879 +vn 0.6514 -0.6173 -0.4412 +vn 0.7552 -0.4234 -0.5003 +vn 0.6346 -0.4274 -0.6439 +vn 0.6868 -0.2395 -0.6863 +vn 0.6925 -0.2055 -0.6916 +vn 0.6965 -0.0416 -0.7164 +vn 0.6626 -0.1234 -0.7388 +vn 0.7457 -0.5043 -0.4354 +vn 0.7177 -0.6945 0.0506 +vn 0.6763 -0.7324 -0.0792 +vn 0.6982 -0.7151 -0.0335 +vn 0.6896 -0.6842 -0.2373 +vn 0.6946 -0.6863 -0.2157 +vn 0.7436 0.0635 -0.6656 +vn -0.6992 -0.4293 -0.5716 +vn -0.7450 -0.4161 -0.5214 +vn -0.9702 0.0017 -0.2423 +vn -0.9951 0.0088 -0.0980 +vn -0.7241 -0.6696 -0.1652 +vn -0.7092 -0.6672 -0.2278 +vn -0.7985 -0.3879 -0.4603 +vn -0.7368 -0.6629 -0.1333 +vn -0.7204 -0.0680 -0.6902 +vn -0.6887 -0.4827 -0.5410 +vn -0.7087 -0.0196 -0.7053 +vn -0.6970 -0.0166 -0.7169 +vn -0.6782 -0.1898 -0.7099 +vn -0.7396 -0.2954 -0.6048 +vn -0.7205 -0.4509 -0.5269 +vn -0.7210 -0.5157 -0.4629 +vn -0.7117 -0.6091 -0.3501 +vn -0.7102 -0.6540 -0.2605 +vn -0.6082 -0.7851 -0.1174 +vn -0.6913 -0.7225 -0.0134 +vn -0.7083 -0.7057 -0.0164 +vn -0.7171 -0.6932 -0.0731 +vn -0.7960 -0.4417 -0.4138 +vn -0.6887 -0.5568 -0.4644 +vn -0.7081 -0.1726 -0.6847 +vn -0.7207 -0.0252 -0.6928 +vn -0.7105 -0.0360 -0.7028 +vn -0.7021 -0.0355 -0.7112 +vn 0.9268 -0.2536 -0.2770 +vn 0.9234 -0.2547 -0.2870 +vn 0.9545 -0.2215 -0.1997 +vn -0.6100 -0.7921 0.0198 +vn -0.6069 -0.7945 0.0184 +vn -0.6091 -0.7929 0.0193 +vn -0.6062 -0.7951 0.0180 +vn -0.8323 0.5521 -0.0488 +vn -0.7849 0.6191 -0.0264 +vn -0.8218 0.5681 -0.0436 +vn -0.7645 0.6444 -0.0174 +vn 0.7322 0.6749 -0.0914 +vn 0.9293 0.3693 0.0016 +vn 0.7687 0.6348 -0.0782 +vn 0.9616 0.2730 0.0280 +vn 0.7057 -0.7085 -0.0018 +vn 0.6469 -0.7621 -0.0263 +vn 0.7240 -0.6898 0.0063 +vn 0.6282 -0.7773 -0.0336 +vn 0.1706 0.9852 -0.0170 +vn 0.5517 0.2904 -0.7818 +vn -0.5602 0.4631 -0.6868 +vn -0.0664 -0.8963 -0.4385 +vn -0.3341 -0.4389 -0.8341 +vn 0.6759 -0.3884 -0.6263 +vn 0.5752 -0.4127 -0.7063 +vn 0.4697 -0.4293 -0.7714 +vn -0.8032 -0.2878 -0.5216 +vn 0.7511 -0.3631 -0.5514 +vn 0.7003 0.7127 0.0396 +vn 0.7242 0.6887 0.0339 +vn 0.8313 0.5558 0.0047 +vn 0.8772 0.4800 -0.0106 +vn 0.7890 -0.6130 0.0410 +vn 0.8365 -0.5477 0.0206 +vn 0.7979 -0.6017 0.0374 +vn 0.8456 -0.5335 0.0164 +vn 0.0050 -0.9989 -0.0470 +vn -0.4061 -0.9134 0.0295 +vn -0.0814 -0.9962 -0.0316 +vn -0.4747 -0.8791 0.0432 +vn -0.8773 -0.4789 -0.0313 +vn -0.9985 0.0409 0.0361 +vn -0.5894 0.8049 -0.0696 +vn -0.7646 0.6435 -0.0361 +vn -0.8004 0.5980 -0.0420 +vn -0.5813 0.8131 -0.0323 +vn 0.1006 0.9936 -0.0508 +vn 0.3787 0.4710 -0.7967 +vn -0.5691 0.8146 -0.1119 +vn -0.7115 -0.1204 -0.6922 +vn -0.6400 0.0184 -0.7682 +vn -0.7527 -0.2268 -0.6181 +vn 0.2178 -0.9425 -0.2534 +vn -0.2750 -0.4858 -0.8297 +vn 0.6591 -0.1990 -0.7252 +vn 0.5831 -0.2570 -0.7707 +vn 0.4545 -0.3400 -0.8233 +vn -0.7829 -0.3448 -0.5179 +vn 0.7770 -0.0892 -0.6232 +vn -0.8303 -0.5574 -0.0006 +vn -0.7170 -0.6956 -0.0456 +vn -0.6823 -0.7288 -0.0574 +vn -0.8615 -0.5075 0.0143 +vn -0.8693 0.4942 -0.0060 +vn -0.7640 0.6428 -0.0561 +vn -0.8952 0.4456 0.0092 +vn -0.7431 0.6661 -0.0645 +vn 0.6913 0.7177 -0.0834 +vn 0.9853 0.1613 0.0568 +vn 0.7080 -0.7031 -0.0661 +vn 0.2734 -0.9600 0.0611 +vn 0.1055 0.9944 -0.0046 +vn 0.5109 0.2013 -0.8357 +vn -0.6224 0.0303 -0.7821 +vn -0.6550 0.1688 -0.7365 +vn -0.5245 0.3766 -0.7636 +vn -0.6162 -0.1898 -0.7644 +vn 0.1436 -0.5474 -0.8245 +vn -0.2411 -0.9089 -0.3401 +vn -0.4979 -0.2940 -0.8158 +vn 0.8081 -0.4300 -0.4024 +vn -0.1618 -0.0153 -0.9867 +vn -0.3536 0.0416 -0.9345 +vn -0.0898 -0.0360 -0.9953 +vn 0.8769 0.0153 -0.4804 +vn 0.8820 0.0184 -0.4708 +vn 0.8779 0.0159 -0.4786 +vn 0.8835 0.0193 -0.4681 +vn 0.7980 -0.1168 0.5913 +vn 0.8363 -0.0090 0.5482 +vn 0.7642 -0.2583 0.5911 +vn 0.8433 -0.0110 0.5373 +vn -0.6903 -0.0348 0.7227 +vn -0.9231 0.0308 0.3834 +vn -0.8793 -0.0331 0.4751 +vn -0.9633 0.0281 0.2671 +vn -0.9854 -0.0416 -0.1651 +vn -0.4128 0.0598 -0.9089 +vn -0.0667 -0.0187 0.9976 +vn 0.0838 -0.0377 0.9958 +vn 0.1030 -0.0401 0.9939 +vn -0.0847 -0.0164 0.9963 +vn -0.5181 -0.8052 0.2884 +vn 0.6830 -0.4527 0.5733 +vn -0.7906 -0.2764 -0.5464 +vn -0.2221 -0.8495 -0.4786 +vn 0.6308 -0.2584 -0.7316 +vn 0.5779 -0.7563 -0.3067 +vn -0.3068 -0.0015 -0.9518 +vn -0.0965 -0.0390 -0.9946 +vn -0.1412 -0.0271 -0.9896 +vn 0.7851 0.0077 -0.6194 +vn 0.8149 0.0214 -0.5792 +vn 0.7903 0.0100 -0.6126 +vn 0.8221 0.0248 -0.5688 +vn 0.8810 -0.0061 0.4731 +vn 0.8113 -0.0449 0.5829 +vn 0.8987 0.0055 0.4386 +vn 0.7962 -0.0522 0.6028 +vn -0.9958 -0.0090 -0.0909 +vn -0.9937 -0.0025 -0.1120 +vn -0.9954 -0.0076 -0.0955 +vn -0.9933 -0.0016 -0.1152 +vn -0.3452 -0.0517 -0.9371 +vn -0.0292 -0.0263 0.9992 +vn -0.6649 0.0113 0.7469 +vn -0.4125 -0.0070 0.9109 +vn -0.4561 -0.0178 0.8898 +vn -0.6702 -0.0458 0.7408 +vn -0.5752 -0.8170 -0.0406 +vn -0.6813 0.0641 0.7292 +vn 0.5828 -0.7178 0.3809 +vn -0.3438 -0.1006 -0.9336 +vn -0.4156 -0.6376 -0.6487 +vn 0.6627 -0.5547 -0.5031 +vn 0.6616 -0.5595 -0.4992 +vn 0.6649 -0.5443 -0.5115 +vn 0.6673 -0.5328 -0.5205 +vn 0.8001 -0.0032 -0.5999 +vn 0.7948 0.0000 -0.6068 +vn 0.8021 -0.0044 -0.5972 +vn 0.7931 0.0011 -0.6091 +vn 0.9714 -0.2287 0.0642 +vn 0.9838 -0.1754 0.0368 +vn 0.9640 -0.2543 0.0774 +vn 0.6818 -0.0060 0.7315 +vn -0.6896 -0.0820 0.7195 +vn -0.9021 0.0104 0.4314 +vn -0.7330 -0.0669 0.6769 +vn -0.9370 0.0340 0.3476 +vn -0.6435 -0.0295 -0.7649 +vn -0.6681 -0.0408 -0.7429 +vn -0.5690 0.0031 -0.8224 +vn -0.5359 0.0168 -0.8441 +vn 0.1452 0.0028 0.9894 +vn -0.5669 -0.7635 0.3094 +vn 0.9399 -0.3222 0.1127 +vn -0.7937 -0.4870 -0.3644 +vn -0.2950 -0.8434 -0.4491 +vn 0.2270 -0.3165 -0.9210 +vn 0.4496 -0.8317 -0.3257 +vn 0.9992 0.0246 0.0312 +vn 0.9992 0.0246 0.0304 +vn 0.9965 0.0240 0.0805 +vn 0.9995 0.0251 -0.0212 +vn 0.5466 0.5869 0.5973 +vn 0.5089 0.5850 0.6315 +vn 0.5298 0.5863 0.6129 +vn 0.5627 0.5873 0.5818 +vn 0.6486 -0.4601 -0.6064 +vn 0.6996 -0.2361 -0.6744 +vn 0.6433 -0.4592 -0.6126 +vn 0.6907 -0.3191 -0.6489 +vn 0.7041 0.0198 -0.7098 +vn -0.0587 0.0828 -0.9948 +vn -0.5895 0.6099 -0.5295 +vn -0.0103 0.9833 -0.1818 +vn 0.6202 0.5207 -0.5866 +vn -0.0976 -0.7149 -0.6924 +vn -0.1883 -0.7306 -0.6563 +vn -0.1284 -0.7210 -0.6809 +vn -0.2173 -0.7342 -0.6433 +vn -0.9906 0.1132 0.0766 +vn -0.9599 0.1847 0.2107 +vn -0.9837 0.1356 0.1182 +vn -0.9470 0.2043 0.2479 +vn -0.0098 0.7693 0.6388 +vn 0.2548 0.6904 0.6770 +vn 0.0611 0.7541 0.6540 +vn 0.3253 0.6588 0.6783 +vn 0.9989 -0.0308 -0.0350 +vn 0.9935 -0.0585 -0.0974 +vn 0.9958 -0.0497 -0.0775 +vn 0.9996 -0.0226 -0.0164 +vn -0.1868 0.1598 -0.9693 +vn -0.6131 0.6755 -0.4096 +vn 0.3996 0.8928 -0.2079 +vn 0.4516 0.2966 -0.8415 +vn -0.9695 -0.2183 -0.1115 +vn -0.9358 0.3140 0.1606 +vn -0.2638 0.6427 0.7193 +vn 0.6046 0.6417 0.4719 +vn 0.9409 0.1978 0.2748 +vn 0.7867 -0.4066 -0.4646 +vn 0.2613 -0.7540 -0.6027 +vn -0.3300 -0.6523 -0.6824 +vn -0.4899 0.3366 -0.8042 +vn -0.4475 0.8223 -0.3516 +vn 0.4105 0.8866 -0.2134 +vn 0.3446 0.1158 -0.9316 +vn -0.8472 -0.3609 -0.3899 +vn -0.9869 -0.1518 -0.0543 +vn -0.9067 -0.3031 -0.2934 +vn -0.9948 -0.0978 0.0273 +vn -0.7716 0.5151 0.3733 +vn 0.5604 0.6229 0.5458 +vn 0.3127 0.6422 0.6998 +vn 0.4034 0.6417 0.6523 +vn 0.6391 0.6026 0.4780 +vn 0.9315 -0.3055 -0.1976 +vn 0.5368 -0.5531 -0.6371 +vn -0.0060 -0.7598 -0.6501 +vn -0.4163 0.2805 -0.8649 +vn -0.4782 0.8310 -0.2842 +vn 0.5761 0.7544 -0.3146 +vn 0.2324 0.1598 -0.9594 +vn -0.7376 -0.4949 -0.4594 +vn -0.8051 -0.4569 -0.3783 +vn -0.7579 -0.4847 -0.4367 +vn -0.8192 -0.4473 -0.3589 +vn -0.7459 0.5332 0.3991 +vn -0.5770 0.5884 0.5663 +vn -0.6985 0.5537 0.4533 +vn -0.5143 0.5989 0.6138 +vn 0.8483 0.4129 0.3316 +vn 0.8125 0.4336 0.3896 +vn 0.8257 0.4265 0.3692 +vn 0.8587 0.4059 0.3129 +vn 0.4330 -0.6600 -0.6139 +vn 0.5163 -0.6488 -0.5590 +vn 0.4937 -0.6526 -0.5748 +vn 0.4066 -0.6621 -0.6295 +vn -0.5141 0.3236 -0.7944 +vn -0.2895 0.9356 -0.2022 +vn 0.5644 0.7235 -0.3975 +vn 0.2214 0.1435 -0.9646 +vn -0.8610 -0.3319 -0.3853 +vn -0.9854 -0.1435 -0.0914 +vn -0.9027 -0.2899 -0.3179 +vn -0.9960 -0.0889 -0.0094 +vn -0.4681 0.6873 0.5554 +vn -0.1887 0.6947 0.6941 +vn -0.3854 0.6969 0.6048 +vn -0.0977 0.6833 0.7236 +vn 0.9087 0.3451 0.2348 +vn 0.9966 0.0090 0.0814 +vn 0.9533 0.2374 0.1869 +vn 0.9949 -0.0959 0.0313 +vn 0.3767 -0.6163 -0.6916 +vn -0.2221 -0.7533 -0.6190 +vn -0.4930 0.3405 -0.8007 +vn -0.3323 0.9267 -0.1758 +vn 0.6351 0.6177 -0.4637 +vn 0.1163 0.1453 -0.9825 +vn 0.1530 -0.7310 -0.6650 +vn 0.0352 -0.7658 -0.6422 +vn -0.0085 -0.7756 -0.6311 +vn -0.8582 -0.3321 -0.3915 +vn -0.9966 -0.0088 0.0816 +vn -0.5014 0.6844 0.5294 +vn -0.2800 0.7033 0.6535 +vn -0.4454 0.6938 0.5659 +vn -0.1996 0.6993 0.6864 +vn 0.9729 0.1778 0.1476 +vn 0.9647 0.1912 0.1809 +vn 0.9678 0.1864 0.1689 +vn 0.9755 0.1730 0.1358 +vn 0.2084 -0.7103 -0.6723 +vn -0.6078 0.5414 -0.5809 +vn -0.0096 0.9885 -0.1511 +vn 0.6032 0.4930 -0.6270 +vn 0.0102 0.1125 -0.9936 +vn -0.7693 -0.5196 -0.3717 +vn -0.9965 0.0530 -0.0650 +vn -0.6300 0.5209 0.5760 +vn -0.0067 0.7819 0.6233 +vn 0.6978 0.4593 0.5497 +vn 0.9909 -0.0107 -0.1339 +vn 0.6319 -0.6165 -0.4697 +vn 0.0098 -0.6843 -0.7292 +vn 0.0230 0.0439 -0.9988 +vn -0.5754 0.5453 -0.6095 +vn -0.2068 0.9505 -0.2321 +vn 0.6069 0.6871 -0.3994 +vn 0.0455 -0.6772 -0.7344 +vn -0.1303 -0.7141 -0.6879 +vn -0.0014 -0.6893 -0.7244 +vn -0.1905 -0.7211 -0.6661 +vn -0.9988 -0.0350 -0.0351 +vn -0.9948 -0.0847 -0.0570 +vn -0.9961 -0.0720 -0.0514 +vn -0.9993 -0.0215 -0.0292 +vn -0.3533 0.7001 0.6205 +vn -0.0891 0.6833 0.7247 +vn -0.2713 0.7009 0.6597 +vn -0.0226 0.6706 0.7415 +vn 0.9339 0.3188 0.1619 +vn 0.9720 -0.2202 -0.0826 +vn -0.5608 0.4086 -0.7201 +vn -0.3399 0.9003 -0.2717 +vn 0.5265 0.7747 -0.3502 +vn 0.3070 0.1226 -0.9438 +vn -0.9422 -0.2364 -0.2375 +vn -0.9554 -0.1960 -0.2210 +vn -0.9519 -0.2072 -0.2257 +vn -0.9388 -0.2460 -0.2413 +vn -0.5702 0.5986 0.5626 +vn -0.5818 0.5961 0.5534 +vn -0.5734 0.5980 0.5601 +vn -0.5849 0.5954 0.5508 +vn 0.8519 0.3623 0.3782 +vn 0.8732 0.3494 0.3398 +vn 0.8660 0.3539 0.3532 +vn 0.8432 0.3671 0.3928 +vn 0.4722 -0.6031 -0.6429 +vn 0.2703 -0.7228 -0.6360 +vn 0.4059 -0.6479 -0.6446 +vn 0.1983 -0.7544 -0.6257 +vn -0.0053 -0.9639 -0.2661 +vn 0.0079 -0.9514 -0.3077 +vn 0.0104 -0.9020 -0.4316 +vn -0.0139 -0.9315 -0.3634 +vn -0.0157 -0.8294 -0.5584 +vn -0.0034 -0.9607 -0.2775 +vn 0.0001 -0.6408 -0.7677 +vn 0.0057 -0.7027 -0.7115 +vn 1.0000 -0.0001 0.0000 +vn 1.0000 0.0001 -0.0000 +vn 1.0000 0.0004 -0.0000 +vn -1.0000 0.0001 -0.0001 +vn -1.0000 -0.0000 -0.0001 +vn -0.9997 0.0126 -0.0201 +vn -0.0268 0.1705 -0.9850 +vn 0.0170 0.2429 -0.9699 +vn 1.0000 -0.0002 -0.0001 +vn 1.0000 -0.0003 -0.0001 +vn 0.0010 -0.3343 -0.9425 +vn -0.0039 -0.3282 -0.9446 +vn -0.0173 -0.3117 -0.9500 +vn 0.0154 -0.3517 -0.9360 +vn -0.8018 -0.4482 -0.3953 +vn -0.8102 -0.4472 -0.3790 +vn -0.8164 -0.3984 -0.4179 +vn -0.8897 -0.2188 -0.4008 +vn -0.8672 -0.2794 -0.4122 +vn 0.0057 -0.1422 -0.9898 +vn 0.0038 -0.1480 -0.9890 +vn -0.0027 -0.1688 -0.9856 +vn -0.0048 -0.1756 -0.9845 +vn 0.9981 0.0583 -0.0223 +vn 0.9977 0.0627 -0.0242 +vn 0.8983 0.1127 0.4246 +vn 0.9876 0.0233 0.1553 +vn -0.9939 0.0427 0.1020 +vn -0.9917 0.0266 -0.1259 +vn -0.9847 -0.0048 -0.1742 +vn -0.9918 0.0363 0.1227 +vn -0.0280 0.2681 0.9630 +vn -0.0233 0.2534 0.9671 +vn -0.0059 0.1991 0.9800 +vn -0.0010 0.1837 0.9830 +vn -0.8847 -0.1631 -0.4367 +vn 0.7514 -0.2122 -0.6248 +vn -0.9104 -0.0077 0.4137 +vn 0.8611 0.0472 0.5063 +vn 0.6057 0.2038 0.7691 +vn -0.0041 -0.8972 -0.4416 +vn -0.0008 -0.9101 -0.4144 +vn -0.0010 -0.7392 -0.6735 +vn 0.0015 -0.7525 -0.6586 +vn 0.0006 -0.9627 -0.2707 +vn -0.0014 -0.9617 -0.2742 +vn 0.0003 0.1807 -0.9835 +vn -0.0010 0.2041 -0.9790 +vn 0.8669 -0.1810 -0.4644 +vn 0.9441 -0.1162 -0.3086 +vn 0.9995 -0.0038 0.0313 +vn -0.9998 -0.0131 0.0138 +vn -0.0016 0.2428 -0.9701 +vn 0.0007 0.2453 -0.9694 +vn 0.7806 -0.2212 -0.5846 +vn 0.5943 -0.2665 -0.7588 +vn 0.6761 -0.2458 -0.6946 +vn -0.6382 -0.2332 -0.7337 +vn -0.8833 -0.1841 -0.4311 +vn -0.6600 -0.2568 -0.7061 +vn 0.6383 0.1524 -0.7545 +vn 0.6407 -0.7247 -0.2536 +vn -0.6163 0.1511 -0.7729 +vn -0.6592 -0.7084 -0.2522 +vn 0.3392 -0.0990 0.9355 +vn 0.9144 0.0833 0.3963 +vn 0.7550 -0.0877 -0.6498 +vn 0.0463 0.0903 -0.9948 +vn -0.9725 -0.1153 -0.2023 +vn -0.8155 0.1119 0.5678 +vn 0.6096 0.0406 -0.7917 +vn -0.9863 0.0411 -0.1597 +vn -0.3403 -0.0457 0.9392 +vn 0.3813 0.0540 0.9229 +vn -0.0143 -0.9124 0.4090 +vn -0.0014 -0.8586 0.5127 +vn -0.0133 -0.9087 0.4173 +vn -0.0001 -0.8524 0.5230 +vn -0.0002 -0.9376 -0.3478 +vn -0.0013 -0.9394 -0.3429 +vn -0.0044 -0.9379 -0.3468 +vn 0.0049 -0.9413 -0.3376 +vn -0.0003 -0.9415 -0.3369 +vn 0.0007 -0.9404 -0.3400 +vn -0.0042 -0.9411 -0.3381 +vn 0.0052 -0.9376 -0.3478 +vn -0.0035 -0.9378 -0.3471 +vn -0.0020 -0.9418 -0.3362 +vn 0.0030 -0.9373 -0.3485 +vn 0.0000 -0.9397 -0.3420 +vn 0.0001 -0.9423 -0.3348 +vn 0.0091 -0.9398 -0.3416 +vn -0.0001 -0.9397 -0.3420 +vn 0.0003 -0.3561 -0.9345 +vn -0.0035 -0.3293 -0.9442 +vn 0.0000 -0.3540 -0.9353 +vn -0.0038 -0.3268 -0.9451 +vn -1.0000 0.0009 -0.0001 +vn -0.5349 -0.8412 -0.0799 +vn -0.3778 -0.6203 -0.6874 +vn 0.4914 -0.5698 -0.6586 +vn 0.2436 -0.9205 0.3055 +vn -0.9227 -0.1367 0.3605 +vn -0.9043 -0.1373 0.4042 +vn -0.9091 -0.1372 0.3934 +vn -0.9270 -0.1365 0.3494 +vn -0.6521 0.2616 -0.7116 +vn -0.6403 0.2698 -0.7192 +vn -0.6490 0.2637 -0.7136 +vn -0.6374 0.2718 -0.7210 +vn 0.7641 0.2099 -0.6100 +vn 0.7882 0.2154 -0.5765 +vn 0.7730 0.2119 -0.5979 +vn 0.7965 0.2173 -0.5642 +vn 0.3851 -0.3281 0.8626 +vn 0.3709 -0.3238 0.8704 +vn 0.3802 -0.3266 0.8653 +vn 0.3657 -0.3222 0.8732 +vn -0.6345 -0.7268 -0.2631 +vn -0.0169 -0.5716 -0.8204 +vn 0.5516 -0.6967 -0.4586 +vn 0.1631 -0.9294 0.3311 +vn -0.5001 -0.1757 0.8480 +vn -0.9950 -0.0962 -0.0262 +vn -0.5972 0.3814 -0.7055 +vn -0.0352 0.2843 -0.9581 +vn 0.9472 0.1225 -0.2963 +vn 0.9884 0.1326 -0.0737 +vn 0.9690 0.1272 -0.2117 +vn 0.9909 0.1342 -0.0127 +vn 0.2462 -0.4381 0.8646 +vn -0.5319 -0.8462 0.0308 +vn -0.2315 -0.5407 -0.8088 +vn 0.5422 -0.6696 -0.5076 +vn 0.2817 -0.9340 0.2197 +vn -0.8626 -0.1949 0.4669 +vn -0.9081 -0.1371 0.3958 +vn -0.8743 -0.1813 0.4503 +vn -0.9179 -0.1226 0.3775 +vn -0.3949 0.2935 -0.8706 +vn -0.4568 0.3022 -0.8367 +vn -0.4422 0.3003 -0.8452 +vn -0.3817 0.2914 -0.8771 +vn 0.8945 0.1394 -0.4247 +vn 0.8134 0.2264 -0.5358 +vn 0.8333 0.2075 -0.5123 +vn 0.9101 0.1185 -0.3971 +vn 0.4744 -0.2886 0.8317 +vn 0.4628 -0.2867 0.8388 +vn 0.4715 -0.2881 0.8335 +vn 0.4602 -0.2863 0.8404 +vn 0.0064 -0.8755 0.4832 +vn -0.0033 -0.9769 0.2138 +vn 0.0058 -0.9824 0.1868 +vn -0.0129 -0.9187 0.3947 +vn -0.0044 -0.9869 0.1610 +vn 0.0077 -0.8958 0.4445 +vn -0.0225 -0.9582 0.2852 +vn -0.0063 -0.9987 -0.0496 +vn -0.0363 -0.9931 -0.1116 +vn 0.0058 -0.9816 -0.1909 +vn 0.1748 0.9661 0.1900 +vn 0.4945 0.8503 0.1802 +vn 0.1983 0.9615 0.1901 +vn 0.4987 0.8479 0.1799 +vn -0.0255 0.7432 0.6686 +vn 0.0138 0.7631 0.6461 +vn -0.1955 0.8071 0.5571 +vn -0.2716 0.8070 0.5244 +vn 0.0199 0.7689 0.6390 +vn -0.0294 0.7675 0.6404 +vn -0.0055 0.7138 0.7003 +vn 0.0017 0.7095 0.7047 +vn 0.0037 0.6981 0.7160 +vn 0.2462 0.8396 0.4841 +vn 0.3221 0.8332 0.4495 +vn -0.0075 -1.0000 0.0050 +vn -0.0032 -1.0000 0.0044 +vn -0.0116 -0.9718 0.2355 +vn 0.0056 -0.9997 0.0256 +vn 0.0163 -0.8966 0.4425 +vn -0.0182 -0.9991 0.0379 +vn -0.0323 -0.9987 0.0392 +vn 0.0008 -1.0000 0.0025 +vn 0.0124 -0.9996 0.0263 +vn -0.0053 -0.9989 0.0463 +vn 0.0010 -0.9593 0.2823 +vn 0.0064 -0.9652 0.2615 +vn 0.0882 0.7702 -0.6317 +vn -0.0144 0.3936 -0.9192 +vn 0.0070 0.6598 -0.7514 +vn -0.0183 0.3343 -0.9423 +vn -0.0103 0.2394 -0.9709 +vn 0.0142 0.1541 -0.9879 +vn 0.0013 0.6122 -0.7907 +vn 0.0019 0.7889 -0.6145 +vn 0.0004 0.8461 -0.5330 +vn 0.0050 0.5983 -0.8013 +vn -0.0001 0.6129 -0.7902 +vn -0.0073 0.9266 -0.3759 +vn -0.0071 0.9268 -0.3754 +vn 0.0025 0.9973 -0.0735 +vn -0.0003 0.9854 -0.1704 +vn 0.1622 0.9867 0.0065 +vn 0.0001 -0.9866 -0.1633 +vn 0.0008 -0.9822 -0.1881 +vn 0.0008 -0.9825 -0.1860 +vn 0.0001 -0.9866 -0.1631 +vn -0.0003 0.8566 -0.5160 +vn 0.0012 0.6116 -0.7912 +vn 0.0012 0.7976 -0.6032 +vn 0.0072 0.7786 -0.6274 +vn -0.0028 0.7568 -0.6536 +vn -0.0043 0.9772 -0.2122 +vn 0.0035 0.9745 -0.2242 +vn -0.0131 0.9998 -0.0127 +vn -0.0417 0.9985 -0.0350 +vn -0.0389 0.9983 -0.0433 +vn 0.1766 0.0027 0.9843 +vn 0.0297 0.4491 0.8930 +vn 0.0931 0.0703 0.9932 +vn -0.0083 -0.2190 0.9757 +vn 0.0036 -0.2686 0.9632 +vn -0.0003 0.0935 0.9956 +vn -0.0075 0.2255 0.9742 +vn -0.0093 -0.2015 0.9794 +vn 0.0020 0.1207 0.9927 +vn 0.0006 0.1219 0.9925 +vn -0.0008 -0.2509 0.9680 +vn 0.9406 -0.2517 0.2279 +vn 0.9990 -0.0045 -0.0440 +vn 0.9348 -0.2711 0.2294 +vn 0.9999 -0.0131 0.0017 +vn 0.9999 -0.0099 0.0044 +vn 1.0000 -0.0054 0.0032 +vn 1.0000 -0.0011 0.0012 +vn 0.0002 -0.9909 -0.1344 +vn 0.0019 -0.9917 -0.1287 +vn 0.0033 -0.9999 0.0162 +vn -0.0048 -1.0000 -0.0073 +vn 0.0069 -0.9512 0.3083 +vn -0.0094 -0.9673 0.2535 +vn 0.0020 -0.8384 0.5451 +vn 0.0014 -0.8379 0.5458 +vn 0.3654 -0.6087 0.7043 +vn 0.0097 -0.6146 0.7888 +vn 0.2082 -0.4617 0.8623 +vn 0.0106 -0.4354 0.9002 +vn -0.0050 -0.2977 0.9547 +vn 0.2175 0.4498 0.8662 +vn 0.0005 0.0847 0.9964 +vn -0.0044 -0.1589 0.9873 +vn -0.0022 -0.0151 0.9999 +vn 0.0012 0.1358 0.9907 +vn -0.0002 0.1314 0.9913 +vn 0.0002 0.6800 0.7332 +vn 0.0054 0.6449 0.7643 +vn -0.0311 0.6692 0.7425 +vn -0.0001 0.6820 0.7313 +vn -0.0000 0.6820 0.7314 +vn 0.0000 0.6820 0.7313 +vn 0.0001 0.6820 0.7314 +vn -0.0072 0.5248 0.8512 +vn -0.0139 0.6891 0.7245 +vn 0.0038 0.6749 0.7379 +vn -0.0166 0.6863 0.7271 +vn -0.0002 0.6988 0.7153 +vn 0.0001 0.6816 0.7317 +vn 0.0062 0.6840 0.7295 +vn 0.0046 0.6871 0.7266 +vn 0.0027 0.6822 0.7312 +vn -0.0001 0.6820 0.7314 +vn -0.0000 0.6813 0.7320 +vn 0.0000 0.6819 0.7314 +vn 0.0010 0.6822 0.7312 +vn 0.0102 0.6842 0.7292 +vn 0.0002 0.6817 0.7317 +vn -0.0003 0.6819 0.7314 +vn -0.0004 0.6821 0.7313 +vn -0.0003 0.6818 0.7315 +vn -0.0036 0.6830 0.7304 +vn -0.0012 0.6866 0.7270 +vn -0.3748 0.9020 0.2142 +vn -0.3835 0.8984 0.2140 +vn -0.0148 -0.3906 0.9204 +vn -0.0202 -0.6065 0.7948 +vn -0.1107 -0.5337 0.8384 +vn -0.0149 -0.7971 0.6036 +vn -0.0012 -0.3487 0.9372 +vn 0.0758 -0.4273 0.9009 +vn -0.0301 -0.4458 0.8946 +vn -0.0028 -0.2341 0.9722 +vn -0.0091 -0.3270 0.9450 +vn -0.0262 -0.2748 0.9611 +vn 0.0284 -0.5157 0.8563 +vn 0.0117 -0.4456 0.8951 +vn 0.0812 -0.3373 0.9379 +vn 0.0166 0.3084 -0.9511 +vn 0.0014 0.2288 -0.9735 +vn -0.0021 0.4218 -0.9067 +vn 0.0119 0.4823 -0.8759 +vn 0.0017 0.5153 -0.8570 +vn 0.0843 -0.3744 -0.9234 +vn -0.0028 -0.4203 -0.9074 +vn -0.0043 -0.2058 -0.9786 +vn 0.1581 -0.1126 -0.9810 +vn 0.1489 -0.9146 -0.3758 +vn 0.0054 -0.8009 -0.5988 +vn 0.0035 -0.6858 -0.7277 +vn -0.0041 -0.9953 -0.0968 +vn 0.2541 -0.9465 0.1990 +vn 0.0223 -0.8166 0.5768 +vn -0.0068 -0.9876 0.1569 +vn -0.0031 -0.3395 0.9406 +vn -0.0001 -0.3426 0.9395 +vn 0.0068 -0.1442 0.9895 +vn -0.0042 -0.3147 0.9492 +vn 0.0190 0.1244 0.9921 +vn -0.0071 0.7358 0.6771 +vn 0.0078 0.8256 0.5641 +vn -0.0060 0.7426 0.6697 +vn 0.0091 0.8323 0.5543 +vn 0.4759 0.8789 0.0326 +vn -0.0241 0.9996 -0.0170 +vn 1.0000 0.0017 0.0080 +vn 0.9999 0.0133 -0.0081 +vn 0.9999 0.0111 -0.0047 +vn 0.9669 -0.1808 -0.1802 +vn 0.9871 -0.1275 -0.0968 +vn -0.0054 0.0173 0.9998 +vn -0.0104 0.0227 0.9997 +vn -0.0060 0.0179 0.9998 +vn -0.0011 0.0127 0.9999 +vn -0.0012 0.9988 0.0491 +vn 0.0008 0.9990 0.0447 +vn -0.0004 0.9989 0.0475 +vn 0.0016 0.9991 0.0431 +vn -0.0015 0.7045 -0.7097 +vn 0.0024 0.6985 -0.7156 +vn 0.0000 0.7021 -0.7120 +vn 0.0039 0.6961 -0.7179 +vn -0.0041 -0.6674 -0.7447 +vn 0.0076 -0.6768 -0.7361 +vn 0.0065 -0.6760 -0.7368 +vn 0.0179 -0.6851 -0.7282 +vn -0.0265 -0.9248 0.3795 +vn 0.0149 -0.8072 0.5901 +vn -0.0207 -0.9116 0.4104 +vn 0.0207 -0.7867 0.6169 +vn -0.0012 -0.7434 -0.6688 +vn 0.0075 -0.6876 -0.7260 +vn 0.0067 -0.6930 -0.7209 +vn -0.0019 -0.7474 -0.6643 +vn 0.0090 -0.9999 0.0099 +vn 0.0034 -1.0000 0.0045 +vn 0.0031 -1.0000 0.0042 +vn -0.0026 -1.0000 -0.0012 +vn -0.0093 -0.3553 0.9347 +vn 0.0161 -0.6086 0.7933 +vn 0.0120 -0.3868 0.9221 +vn -0.0098 -0.3231 0.9463 +vn 0.0099 -0.0974 0.9952 +vn 0.2327 0.8895 0.3933 +vn 0.0036 0.7399 0.6727 +vn 0.0900 0.6805 0.7272 +vn 0.1812 0.6955 0.6953 +vn 0.0461 0.6691 0.7418 +vn 0.3867 0.5704 0.7246 +vn -0.0043 0.9087 0.4174 +vn -0.0078 0.9789 0.2043 +vn 0.4186 0.8987 -0.1312 +vn 0.0150 0.8783 -0.4779 +vn 0.0002 0.8501 -0.5266 +vn -0.0011 0.9060 -0.4233 +vn 0.0108 0.9505 -0.3105 +vn 0.0028 0.9767 -0.2144 +vn 0.0163 0.9936 -0.1118 +vn 0.0058 0.9895 -0.1441 +vn 0.0052 0.0667 -0.9978 +vn -0.0103 0.0520 -0.9986 +vn -0.0002 0.1520 -0.9884 +vn 0.0073 0.3758 -0.9267 +vn 0.0071 0.3751 -0.9270 +vn 0.0001 0.7902 -0.6129 +vn 0.0092 0.7696 -0.6384 +vn 0.0028 0.7842 -0.6205 +vn 0.0103 0.7670 -0.6416 +vn 0.0149 0.7243 0.6893 +vn 0.0046 0.9932 0.1161 +vn 0.0285 0.9831 0.1806 +vn -0.0019 0.4872 -0.8733 +vn 0.0171 0.7415 -0.6707 +vn -0.0036 0.5831 -0.8124 +vn -0.0142 0.6312 -0.7755 +vn 0.0153 0.4608 -0.8874 +vn -0.0030 0.1789 -0.9839 +vn 0.0381 -0.0133 -0.9992 +vn 0.0619 0.9928 -0.1030 +vn -0.0487 0.8288 -0.5574 +vn -0.0097 0.7731 -0.6342 +vn -0.0227 0.7926 -0.6094 +vn 0.0204 0.7248 -0.6887 +vn -0.0018 0.2450 -0.9695 +vn -0.0387 0.1595 -0.9864 +vn -0.0399 0.1001 -0.9942 +vn 0.3740 -0.1701 -0.9117 +vn 0.9471 -0.0590 0.3154 +vn 0.9153 0.3854 -0.1169 +vn 0.9730 0.1690 0.1569 +vn 0.9734 0.0422 -0.2250 +vn 0.0001 -0.8710 0.4912 +vn -0.0112 -0.8619 0.5070 +vn 0.0176 -0.8504 0.5259 +vn 0.0206 -0.8445 0.5351 +vn 0.0066 -0.8703 0.4924 +vn 0.0341 -0.8710 0.4901 +vn 0.0374 -0.0733 -0.9966 +vn -0.0001 -0.5002 -0.8659 +vn 0.0106 -0.3486 -0.9372 +vn 0.0163 -0.8514 0.5243 +vn 0.0494 -0.8828 0.4672 +vn 0.0060 -0.8850 0.4655 +vn 0.0122 -0.8950 0.4460 +vn -0.0007 -0.4020 0.9156 +vn -0.0004 -0.4044 0.9146 +vn -0.0004 -0.4042 0.9147 +vn -0.0007 -0.4018 0.9157 +vn -0.0240 0.2274 0.9735 +vn -0.0033 -0.9085 0.4179 +vn 0.0004 -0.9228 0.3852 +vn 0.0001 -0.9218 0.3877 +vn -0.0035 -0.9074 0.4202 +vn 0.0010 -0.5434 0.8394 +vn 0.0029 -0.5438 0.8392 +vn -0.0095 -0.5551 0.8317 +vn 0.0015 -0.4443 0.8959 +vn 0.0059 -0.4763 0.8792 +vn 0.0284 -0.5481 0.8359 +vn 0.0235 -0.5335 0.8455 +vn 0.0042 -0.4672 0.8841 +vn 0.6568 -0.5370 -0.5294 +vn 0.5287 -0.5587 -0.6390 +vn 0.7262 -0.4721 -0.4998 +vn 0.8569 -0.3847 -0.3432 +vn 0.7236 -0.4653 0.5098 +vn 0.6401 -0.7325 0.2320 +vn 0.7620 -0.3713 0.5305 +vn 0.3506 -0.1388 -0.9262 +vn 0.8051 -0.1971 0.5594 +vn 0.8089 -0.1946 0.5548 +vn 0.6349 0.3824 -0.6713 +vn 0.6967 0.3131 -0.6454 +vn 0.7085 0.3511 -0.6122 +vn 0.7467 0.2207 -0.6275 +vn 0.8085 0.2872 -0.5136 +vn 0.6905 0.1632 -0.7047 +vn 0.5673 0.1362 -0.8122 +vn 0.7692 0.1056 -0.6302 +vn 0.8053 0.1137 -0.5819 +vn 0.6331 0.4280 0.6450 +vn 0.6335 0.2837 0.7198 +vn 0.6321 0.4429 0.6359 +vn 0.6149 0.5661 0.5490 +vn 0.1548 0.6502 -0.7438 +vn 0.6804 0.7076 -0.1904 +vn 0.6255 0.6050 -0.4927 +vn 0.5743 0.7864 -0.2275 +vn 0.7981 0.5997 0.0584 +vn 0.4645 0.6229 0.6295 +vn 0.3831 0.6622 0.6440 +vn 0.8720 0.3416 0.3507 +vn 0.7547 0.1912 0.6276 +vn 0.5427 0.8395 -0.0265 +vn 0.6327 0.7326 -0.2510 +vn 0.6952 -0.1934 0.6923 +vn 0.5446 -0.6096 0.5760 +vn 0.6833 -0.4641 0.5636 +vn 0.4820 0.1447 0.8641 +vn 0.5253 0.7483 -0.4050 +vn 0.6021 0.7870 -0.1345 +vn 0.8153 0.4848 -0.3168 +vn 0.6390 0.6874 -0.3451 +vn 0.5395 -0.8420 0.0028 +vn 0.5888 -0.8083 -0.0012 +vn 0.5419 -0.8405 0.0026 +vn 0.5919 -0.8060 -0.0015 +vn 0.9347 -0.3553 0.0067 +vn 0.8786 -0.3834 -0.2846 +vn 0.2387 0.7289 -0.6417 +vn 0.4114 0.6787 -0.6084 +vn 0.3195 0.0460 -0.9465 +vn 0.8630 0.1702 -0.4758 +vn 0.7834 -0.2046 -0.5869 +vn 0.5114 0.6513 -0.5605 +vn 0.4792 -0.0103 -0.8776 +vn 0.5956 -0.5280 -0.6053 +vn 0.6911 -0.7141 0.1117 +vn 0.7693 -0.5606 0.3064 +vn 0.7355 -0.6558 0.1703 +vn 0.8037 -0.3603 0.4736 +vn 0.7218 -0.6715 0.1672 +vn 0.7978 -0.4506 0.4005 +vn 0.7219 -0.0257 0.6915 +vn 0.7198 -0.0285 0.6936 +vn 0.7043 -0.1941 0.6828 +vn 0.7161 -0.0738 0.6941 +vn 0.6919 -0.4823 0.5374 +vn 0.7209 -0.6895 0.0691 +vn 0.6851 -0.5557 0.4710 +vn 0.6907 -0.7221 0.0384 +vn 0.6569 -0.7464 0.1072 +vn 0.7229 -0.6889 -0.0528 +vn 0.7461 -0.5129 0.4246 +vn 0.6151 -0.6710 0.4141 +vn 0.6861 -0.6936 0.2195 +vn 0.6968 -0.6796 0.2295 +vn 0.7468 -0.4061 0.5268 +vn 0.7245 0.0099 0.6892 +vn 0.7431 0.0654 0.6660 +vn 0.6966 -0.0908 0.7117 +vn 0.7800 -0.0971 0.6182 +vn 0.5443 -0.4488 0.7087 +vn -0.7232 -0.2279 0.6520 +vn -0.7091 -0.4301 0.5588 +vn -0.7276 -0.0067 0.6860 +vn -0.7584 0.1162 0.6414 +vn -0.7209 -0.6262 0.2969 +vn -0.6929 -0.6900 0.2092 +vn -0.7182 -0.6736 0.1745 +vn -0.7874 -0.4042 0.4655 +vn -0.7208 -0.0678 0.6898 +vn -0.7002 -0.4872 0.5219 +vn -0.6339 -0.0015 0.7734 +vn -0.7172 -0.1652 0.6770 +vn -0.7323 -0.2358 0.6389 +vn -0.7037 -0.3535 0.6164 +vn -0.6557 -0.4613 0.5977 +vn -0.6945 -0.5499 0.4640 +vn -0.6818 -0.6239 0.3819 +vn -0.6837 -0.6755 0.2763 +vn -0.6968 -0.6884 0.2014 +vn -0.7102 -0.7009 0.0663 +vn -0.7083 -0.7054 -0.0249 +vn -0.7133 -0.6999 0.0369 +vn -0.7235 -0.6874 0.0638 +vn -0.6666 -0.6809 0.3033 +vn -0.7025 -0.1135 0.7026 +vn -0.6654 -0.3122 0.6781 +vn -0.6785 -0.1995 0.7070 +vn -0.7088 -0.0559 0.7032 +vn -0.7218 -0.0250 0.6917 +vn -0.7211 -0.0258 0.6924 +vn 0.8397 -0.2998 0.4528 +vn 0.8269 -0.5170 0.2211 +vn -0.7612 0.6485 0.0075 +vn -0.7870 0.5946 0.1646 +vn -0.7454 0.6017 0.2870 +vn -0.7475 0.6643 0.0044 +vn -0.9835 -0.1801 0.0150 +vn -0.9738 -0.2273 0.0008 +vn -0.9817 -0.1899 0.0121 +vn -0.9722 -0.2341 -0.0012 +vn -0.2367 -0.9710 -0.0334 +vn -0.1725 -0.9849 -0.0166 +vn 0.0286 -0.9990 0.0355 +vn 0.0843 -0.9952 0.0497 +vn 0.9526 -0.3035 0.0203 +vn 0.8013 -0.5972 -0.0350 +vn 0.8330 -0.5527 -0.0260 +vn 0.9657 -0.2580 0.0282 +vn 0.8856 0.4638 -0.0251 +vn 0.8047 0.5937 0.0070 +vn 0.8957 0.4436 -0.0298 +vn 0.7910 0.6117 0.0117 +vn -0.0716 0.9972 0.0217 +vn 0.0443 0.9982 0.0395 +vn -0.0580 0.9980 0.0238 +vn 0.0579 0.9975 0.0416 +vn -0.6445 -0.1087 0.7569 +vn -0.6953 -0.2169 0.6852 +vn -0.7271 -0.3027 0.6162 +vn -0.6441 0.5784 0.5006 +vn 0.5400 0.3677 0.7570 +vn -0.1461 -0.6182 0.7723 +vn -0.0775 -0.7130 0.6969 +vn 0.0070 -0.8086 0.5883 +vn 0.0645 -0.8609 0.5047 +vn 0.5029 -0.3744 0.7790 +vn 0.6145 -0.3375 0.7131 +vn 0.6962 -0.3032 0.6506 +vn 0.7757 -0.2620 0.5741 +vn -0.7490 -0.3830 0.5407 +vn -0.1002 -0.9935 -0.0539 +vn 0.8335 -0.5523 -0.0165 +vn 0.6310 -0.7745 0.0446 +vn 0.5731 -0.8174 0.0587 +vn 0.8797 -0.4743 -0.0349 +vn 0.8777 0.4792 0.0071 +vn 0.8864 0.4629 0.0018 +vn 0.8756 0.4829 0.0083 +vn 0.8876 0.4605 0.0011 +vn -0.8254 0.5641 0.0232 +vn -0.7547 0.6561 0.0060 +vn -0.7669 0.6417 0.0088 +vn -0.8428 0.5375 0.0278 +vn -0.9766 -0.2113 -0.0407 +vn -0.7180 -0.6935 0.0589 +vn 0.2268 0.9733 0.0367 +vn 0.2333 0.9716 0.0397 +vn -0.6448 -0.1276 0.7536 +vn -0.7009 -0.2290 0.6756 +vn -0.7471 -0.3363 0.5734 +vn 0.2341 0.9715 0.0359 +vn -0.5919 0.6166 0.5190 +vn 0.6446 -0.0049 0.7645 +vn 0.6333 0.1510 0.7590 +vn 0.5026 0.2675 0.8221 +vn 0.6316 -0.1693 0.7566 +vn -0.0538 -0.6240 0.7795 +vn 0.2370 -0.8882 0.3937 +vn 0.5134 -0.2735 0.8134 +vn -0.7683 -0.4048 0.4959 +vn -0.6866 0.7265 0.0294 +vn -0.6778 0.7348 0.0269 +vn -0.6795 0.7331 0.0274 +vn -0.6888 0.7243 0.0300 +vn -0.9707 -0.2398 -0.0165 +vn -0.8808 -0.4725 0.0293 +vn -0.9832 -0.1806 -0.0275 +vn -0.8503 -0.5247 0.0402 +vn -0.2367 -0.9707 -0.0424 +vn -0.1667 -0.9856 -0.0289 +vn 0.1207 -0.9923 0.0260 +vn 0.1918 -0.9806 0.0396 +vn 0.8605 0.5093 -0.0128 +vn 0.6532 0.7549 0.0586 +vn 0.8964 0.4423 -0.0297 +vn 0.6073 0.7913 0.0711 +vn -0.1845 0.9827 0.0140 +vn -0.2002 0.9784 -0.0507 +vn -0.2186 0.9671 -0.1305 +vn -0.6955 -0.1187 0.7086 +vn -0.7262 -0.1538 0.6701 +vn -0.7473 -0.1796 0.6397 +vn -0.2398 0.9429 -0.2313 +vn -0.4641 0.4992 0.7317 +vn 0.5435 0.3653 0.7558 +vn -0.1384 -0.7617 0.6330 +vn -0.1244 -0.7469 0.6532 +vn -0.1630 -0.7864 0.5958 +vn -0.1958 -0.8167 0.5428 +vn 0.5165 -0.3846 0.7650 +vn 0.6215 -0.3683 0.6915 +vn 0.7179 -0.3454 0.6045 +vn 0.7772 -0.3260 0.5383 +vn -0.7619 -0.1984 0.6165 +vn 0.7491 0.0141 -0.6623 +vn 0.7906 0.0015 -0.6123 +vn 0.7858 0.0030 -0.6185 +vn 0.7322 0.0190 -0.6808 +vn 0.8615 0.0361 0.5066 +vn 0.9552 -0.0197 0.2952 +vn 0.9685 -0.0317 0.2469 +vn 0.8301 0.0498 0.5554 +vn -0.3536 0.0381 0.9346 +vn -0.1413 -0.0209 0.9897 +vn -0.2998 0.0229 0.9537 +vn -0.0845 -0.0361 0.9958 +vn -0.9638 -0.0422 0.2632 +vn -0.9382 0.0436 -0.3433 +vn -0.8234 -0.0094 -0.5674 +vn -0.9503 0.0514 -0.3071 +vn -0.7958 -0.0193 -0.6052 +vn -0.0497 -0.0361 -0.9981 +vn -0.0577 -0.0349 -0.9977 +vn 0.5429 -0.6748 -0.5000 +vn -0.6583 -0.6865 -0.3088 +vn 0.7048 -0.6250 0.3356 +vn 0.7514 -0.5748 0.3241 +vn 0.6227 -0.6995 0.3508 +vn 0.5473 -0.7555 0.3602 +vn -0.2945 -0.5069 0.8101 +vn -0.3071 -0.4850 0.8188 +vn -0.3207 -0.4605 0.8277 +vn -0.3248 -0.4530 0.8303 +vn 0.8588 -0.0160 -0.5120 +vn 0.9237 0.0239 -0.3824 +vn 0.8705 -0.0097 -0.4921 +vn 0.9339 0.0317 -0.3560 +vn 0.6215 0.0401 0.7824 +vn 0.7837 -0.0063 0.6212 +vn 0.8168 -0.0176 0.5767 +vn 0.5798 0.0503 0.8132 +vn -0.1786 -0.0570 0.9823 +vn -0.9446 -0.0161 0.3278 +vn -0.7311 0.0524 0.6802 +vn -0.7774 0.0412 0.6277 +vn -0.9657 -0.0281 0.2583 +vn -0.8946 0.0232 -0.4462 +vn -0.8088 -0.0120 -0.5879 +vn -0.9053 0.0284 -0.4238 +vn -0.7940 -0.0172 -0.6077 +vn -0.0281 -0.0211 -0.9994 +vn 0.1332 0.0175 -0.9909 +vn 0.1477 0.1384 -0.9793 +vn -0.0465 -0.0175 -0.9988 +vn 0.4938 -0.8512 -0.1779 +vn 0.1761 0.2665 -0.9476 +vn -0.5428 -0.7571 -0.3636 +vn 0.8421 -0.5019 0.1974 +vn 0.3588 -0.8028 0.4762 +vn 0.1229 -0.4029 0.9070 +vn -0.4364 -0.8116 0.3884 +vn -0.5558 -0.7447 0.3695 +vn -0.6882 -0.6428 0.3365 +vn -0.7787 -0.5491 0.3036 +vn 0.7430 0.0479 -0.6676 +vn 0.8166 0.0197 -0.5768 +vn 0.8075 0.0235 -0.5894 +vn 0.7027 0.0616 -0.7089 +vn 0.9908 -0.0414 0.1288 +vn 0.5029 0.0321 0.8638 +vn 0.4804 0.0406 0.8761 +vn 0.4983 0.0338 0.8664 +vn 0.4738 0.0431 0.8796 +vn -0.7470 0.0232 0.6644 +vn -0.6010 -0.0198 0.7990 +vn -0.5588 -0.0308 0.8287 +vn -0.7774 0.0333 0.6281 +vn -0.9086 0.0173 -0.4173 +vn -0.9685 -0.0167 -0.2483 +vn -0.9227 0.0107 -0.3855 +vn -0.9823 -0.0289 -0.1853 +vn 0.1186 -0.0184 -0.9928 +vn 0.1249 0.0404 -0.9913 +vn 0.8733 -0.4832 -0.0624 +vn 0.1499 0.1087 -0.9827 +vn 0.4024 -0.8647 -0.3005 +vn -0.5544 -0.7492 -0.3623 +vn 0.3320 -0.7102 0.6208 +vn 0.3219 -0.7200 0.6149 +vn 0.3488 -0.6936 0.6303 +vn 0.3646 -0.6773 0.6390 +vn -0.6133 -0.6186 0.4910 +vn -0.6623 -0.5651 0.4920 +vn -0.7112 -0.5039 0.4901 +vn -0.7311 -0.4765 0.4884 +vn 0.9992 0.0353 -0.0166 +vn 0.9999 -0.0052 -0.0113 +vn 0.9999 -0.0106 -0.0105 +vn 0.9991 -0.0429 -0.0062 +vn 0.7300 0.1482 -0.6672 +vn 0.5932 0.6972 -0.4024 +vn 0.6857 0.7039 -0.1855 +vn 0.5737 0.6921 -0.4381 +vn 0.4571 0.6469 -0.6104 +vn 0.6538 -0.4095 0.6362 +vn 0.5864 -0.4729 0.6576 +vn 0.7080 -0.3510 0.6128 +vn 0.5057 -0.5381 0.6744 +vn 0.1868 0.1597 0.9693 +vn 0.5837 0.6366 0.5040 +vn -0.0013 0.9765 0.2154 +vn -0.5087 0.7357 0.4472 +vn -0.4165 0.2916 0.8611 +vn 0.3303 -0.6617 0.6731 +vn 0.7472 -0.5565 0.3633 +vn 0.9754 0.2086 -0.0716 +vn 0.0583 0.6918 -0.7198 +vn 0.1923 0.6408 -0.7432 +vn 0.1564 0.6559 -0.7384 +vn 0.0016 0.7088 -0.7054 +vn -0.9077 0.3487 -0.2334 +vn -0.8045 -0.4562 0.3802 +vn -0.9194 -0.3515 0.1766 +vn -0.8970 -0.3791 0.2272 +vn -0.7453 -0.4891 0.4531 +vn 0.0936 0.1181 0.9886 +vn 0.6076 0.6273 0.4871 +vn -0.1647 0.9723 0.1657 +vn -0.5661 0.4115 0.7143 +vn -0.9251 0.2132 -0.3141 +vn -0.9480 -0.1642 0.2727 +vn 0.0748 -0.7201 0.6898 +vn -0.2008 -0.7612 0.6166 +vn -0.1235 -0.7559 0.6429 +vn 0.1630 -0.6939 0.7014 +vn 0.9923 0.1129 -0.0518 +vn 0.9848 -0.1579 0.0725 +vn 0.9966 -0.0753 0.0346 +vn 0.9774 0.1921 -0.0882 +vn -0.1776 0.7497 -0.6375 +vn 0.1908 0.6831 -0.7049 +vn 0.0864 0.7129 -0.6960 +vn -0.2675 0.7494 -0.6056 +vn 0.5488 0.2943 0.7825 +vn 0.2816 0.9319 0.2287 +vn -0.4718 0.8068 0.3557 +vn -0.4060 0.1925 0.8934 +vn 0.8359 -0.3898 0.3865 +vn 0.7490 -0.5096 0.4235 +vn 0.7804 -0.4703 0.4121 +vn 0.8611 -0.3468 0.3717 +vn 0.5241 0.6448 -0.5564 +vn 0.7100 0.4914 -0.5045 +vn 0.6642 0.5356 -0.5215 +vn 0.4739 0.6763 -0.5639 +vn -0.7534 0.5032 -0.4234 +vn -0.5055 0.5952 -0.6247 +vn -0.5747 0.5778 -0.5795 +vn -0.8038 0.4705 -0.3639 +vn -0.7038 -0.5074 0.4973 +vn -0.8388 -0.4382 0.3231 +vn -0.7994 -0.4635 0.3822 +vn -0.6472 -0.5253 0.5524 +vn 0.2822 0.1642 0.9452 +vn 0.5594 0.6794 0.4749 +vn -0.1650 0.9723 0.1656 +vn -0.5822 0.3403 0.7384 +vn -0.9400 -0.2019 0.2750 +vn -0.9995 -0.0316 -0.0101 +vn -0.9938 -0.0828 0.0748 +vn -0.9126 -0.2364 0.3336 +vn -0.3267 -0.7284 0.6023 +vn 0.4656 -0.6143 0.6370 +vn 0.6706 -0.5528 0.4947 +vn 0.5191 -0.6029 0.6058 +vn 0.7186 -0.5298 0.4505 +vn 0.9525 0.2566 -0.1638 +vn 0.7968 0.4123 -0.4416 +vn 0.9209 0.3038 -0.2442 +vn 0.7402 0.4443 -0.5047 +vn -0.2677 0.7465 -0.6092 +vn -0.4242 0.6711 -0.6080 +vn -0.3039 0.7314 -0.6106 +vn -0.4703 0.6435 -0.6039 +vn 0.2158 0.0909 0.9722 +vn 0.5538 0.7095 0.4358 +vn -0.1384 0.9691 0.2040 +vn -0.6119 0.4628 0.6414 +vn -0.9846 -0.0960 0.1463 +vn -0.9699 -0.1676 0.1769 +vn -0.9813 -0.1147 0.1544 +vn -0.9639 -0.1901 0.1864 +vn 0.2631 -0.6660 0.6980 +vn -0.0313 -0.7544 0.6557 +vn 0.0586 -0.7351 0.6754 +vn 0.3318 -0.6345 0.6981 +vn 0.9708 -0.2131 0.1104 +vn 0.9272 0.3159 -0.2015 +vn 0.4634 0.6128 -0.6401 +vn -0.2365 0.7442 -0.6247 +vn -0.5104 0.6198 -0.5962 +vn -0.2952 0.7240 -0.6235 +vn -0.5719 0.5796 -0.5805 +vn 0.2784 0.1895 0.9416 +vn 0.5667 0.7506 0.3399 +vn -0.4823 0.8367 0.2593 +vn -0.3828 0.2432 0.8912 +vn 0.4872 -0.5777 0.6549 +vn 0.9886 -0.1475 0.0313 +vn 0.8645 0.4214 -0.2741 +vn 0.4112 0.6333 -0.6556 +vn -0.7321 0.5188 -0.4414 +vn -0.7220 0.5224 -0.4536 +vn -0.7255 0.5212 -0.4495 +vn -0.7351 0.5177 -0.4377 +vn -0.6696 -0.5529 0.4959 +vn -0.5230 -0.6744 0.5213 +vn -0.6203 -0.5985 0.5070 +vn -0.4831 -0.7010 0.5247 +vn 0.2665 0.1247 0.9557 +vn 0.5265 0.7636 0.3737 +vn -0.2559 0.9414 0.2196 +vn -0.5573 0.3634 0.7466 +vn 0.4305 -0.5994 0.6748 +vn 0.8285 -0.4676 0.3081 +vn 0.8669 0.4078 -0.2867 +vn 0.6719 0.5336 -0.5136 +vn 0.8294 0.4412 -0.3427 +vn 0.6028 0.5595 -0.5688 +vn -0.4310 0.6787 -0.5946 +vn -0.5113 0.6282 -0.5864 +vn -0.4519 0.6664 -0.5930 +vn -0.5331 0.6130 -0.5832 +vn -0.9163 -0.2856 0.2806 +vn -0.8438 -0.4231 0.3303 +vn -0.8934 -0.3352 0.2990 +vn -0.8172 -0.4627 0.3436 +vn 0.3379 0.2294 0.9128 +vn 0.5562 0.6388 0.5316 +vn -0.0190 0.9834 0.1805 +vn -0.5480 0.6473 0.5298 +vn -0.3590 0.2419 0.9014 +vn 0.0823 -0.7686 0.6345 +vn 0.5898 -0.5579 0.5839 +vn 0.9924 0.1039 -0.0661 +vn 0.9850 -0.1529 0.0802 +vn 0.9943 -0.0953 0.0474 +vn 0.9805 0.1677 -0.1023 +vn 0.0118 0.7245 -0.6891 +vn 0.1251 0.6875 -0.7153 +vn 0.0907 0.6999 -0.7085 +vn -0.0290 0.7352 -0.6772 +vn -0.9784 0.1682 -0.1201 +vn -0.9946 -0.1021 0.0184 +vn -0.9928 0.0895 -0.0801 +vn -0.9863 -0.1581 0.0475 +vn -0.6273 -0.5338 0.5671 +vn 0.1768 0.1775 0.9681 +vn 0.5482 0.4869 0.6800 +vn 0.2825 0.9215 0.2665 +vn -0.3617 0.8851 0.2929 +vn -0.5068 0.3177 0.8014 +vn 0.3113 -0.6634 0.6804 +vn 0.9815 -0.1622 0.1012 +vn 0.9681 -0.1925 0.1606 +vn 0.9783 -0.1705 0.1174 +vn 0.9645 -0.1990 0.1734 +vn 0.5010 0.6386 -0.5841 +vn 0.4407 0.6485 -0.6207 +vn 0.4866 0.6413 -0.5933 +vn 0.4266 0.6503 -0.6286 +vn -0.6332 0.5812 -0.5112 +vn -0.7999 0.4038 -0.4439 +vn -0.6871 0.5323 -0.4946 +vn -0.8330 0.3564 -0.4231 +vn -0.8483 -0.3274 0.4162 +vn -0.3325 -0.7516 0.5697 +vn 0.0001 0.9782 0.2079 +vn 0.0000 0.9781 0.2079 +vn 0.0000 0.9781 -0.2079 +vn 0.0000 0.9781 -0.2080 +vn -0.0007 -0.8258 0.5639 +vn -0.0022 -0.9116 0.4112 +vn -0.0181 -0.7804 0.6250 +vn 0.0058 -0.9231 0.3844 +vn -0.0146 -0.9600 0.2796 +vn 0.0000 -0.9792 0.2030 +vn 0.0062 -0.6861 0.7275 +vn -0.9895 -0.0852 0.1171 +vn -0.9995 0.0150 0.0263 +vn -0.9398 -0.2332 0.2497 +vn 0.0119 0.2395 0.9708 +vn 0.0236 0.2214 0.9749 +vn -0.0032 0.2627 0.9649 +vn 0.0358 0.2024 0.9786 +vn -0.0147 -0.3158 0.9487 +vn -0.0271 -0.3294 0.9438 +vn -0.0244 -0.3264 0.9449 +vn -0.0374 -0.3406 0.9395 +vn -0.7826 -0.4797 0.3969 +vn -0.9085 -0.2904 0.3005 +vn -0.2428 -0.4356 0.8668 +vn -0.0024 -0.1669 0.9860 +vn -0.0029 -0.1603 0.9871 +vn -0.0126 -0.0189 0.9997 +vn -0.0133 -0.0090 0.9999 +vn 0.9726 0.2273 0.0494 +vn 0.9728 0.2265 0.0491 +vn 0.9794 0.1978 0.0410 +vn 0.9799 0.1956 0.0404 +vn -0.9981 -0.0446 0.0428 +vn -0.9989 -0.0206 0.0417 +vn -0.9946 0.0976 0.0351 +vn -0.9984 0.0537 0.0174 +vn -0.9988 0.0475 0.0153 +vn 0.0199 0.5498 -0.8351 +vn 0.0193 0.5406 -0.8411 +vn -0.0038 0.1684 -0.9857 +vn -0.0047 0.1534 -0.9882 +vn 0.8174 -0.4256 0.3882 +vn -0.8581 -0.0660 -0.5092 +vn -0.8447 0.0084 -0.5352 +vn -0.8269 0.0790 -0.5568 +vn -0.7864 0.1964 -0.5857 +vn 0.6468 -0.1939 -0.7376 +vn 0.1357 -0.7784 0.6129 +vn 0.0007 -0.8577 0.5142 +vn -0.0000 -0.9516 0.3074 +vn -0.0002 -0.9517 0.3071 +vn -0.0074 0.1628 0.9866 +vn 0.0007 0.1213 0.9926 +vn 0.9997 -0.0118 0.0210 +vn -0.9997 -0.0081 0.0221 +vn 0.0019 0.2441 0.9698 +vn 0.0012 0.2448 0.9696 +vn 0.5761 -0.2837 0.7665 +vn 0.5854 -0.2803 0.7608 +vn 0.6501 -0.3148 0.6915 +vn -0.6399 -0.3209 0.6982 +vn -0.6160 -0.2447 0.7487 +vn -0.6392 -0.2415 0.7302 +vn -0.6568 -0.3069 0.6888 +vn 0.6310 0.1461 0.7619 +vn 0.6809 -0.6925 0.2384 +vn 0.6792 -0.6941 0.2386 +vn 0.6556 -0.7156 0.2412 +vn 0.6524 -0.7184 0.2415 +vn -0.6450 0.1428 0.7508 +vn -0.6623 -0.7099 0.2397 +vn -0.6598 -0.7118 0.2407 +vn -0.6358 -0.7302 0.2500 +vn -0.6342 -0.7314 0.2506 +vn -0.4317 -0.4869 0.7594 +vn -0.7826 -0.0236 -0.6221 +vn -0.6753 0.0199 -0.7373 +vn -0.7583 -0.0130 -0.6517 +vn -0.6439 0.0314 -0.7645 +vn -0.6039 0.0377 0.7962 +vn -0.5780 0.0280 0.8156 +vn -0.5976 0.0353 0.8010 +vn -0.5715 0.0256 0.8202 +vn 0.7745 -0.0452 0.6310 +vn 0.9826 0.1199 -0.1420 +vn 0.7179 -0.0413 -0.6949 +vn 0.8853 -0.0152 -0.4648 +vn 0.9034 -0.0228 -0.4281 +vn 0.9014 -0.0219 -0.4324 +vn 0.8819 -0.0138 -0.4712 +vn -0.8332 0.0001 -0.5529 +vn -0.7369 0.0301 -0.6753 +vn -0.7196 0.0349 -0.6935 +vn -0.8468 -0.0048 -0.5320 +vn -0.2100 -0.0177 0.9775 +vn 0.0132 0.0262 0.9996 +vn -0.0162 0.0205 0.9997 +vn 0.0005 -0.8535 -0.5211 +vn 0.0020 -0.8602 -0.5099 +vn 0.0006 -0.8540 -0.5202 +vn 0.0021 -0.8607 -0.5091 +vn -0.0065 -0.9484 0.3169 +vn 0.0001 -0.9396 0.3422 +vn -0.0035 -0.9382 0.3460 +vn -0.0050 -0.9383 0.3458 +vn 0.0003 -0.9379 0.3470 +vn 0.0047 -0.9377 0.3475 +vn 0.0005 -0.9387 0.3446 +vn 0.0006 -0.9396 0.3422 +vn -0.0002 -0.9424 0.3345 +vn 0.0044 -0.9412 0.3377 +vn -0.0060 -0.9422 0.3351 +vn -0.0070 -0.9416 0.3366 +vn -0.0005 -0.9365 0.3507 +vn 0.0082 -0.9391 0.3436 +vn 0.0022 -0.9414 0.3373 +vn 0.0000 -0.9397 0.3421 +vn -0.0089 -0.8080 0.5891 +vn 0.0018 -0.2974 0.9548 +vn -0.0003 -0.3158 0.9488 +vn 0.0017 -0.2987 0.9543 +vn -0.0004 -0.3169 0.9484 +vn -1.0000 -0.0006 0.0003 +vn -1.0000 -0.0005 0.0001 +vn 0.3380 -0.9299 -0.1454 +vn 0.5521 -0.7498 0.3648 +vn 0.0478 -0.5512 0.8330 +vn -0.5511 -0.7296 0.4049 +vn -0.3587 -0.9244 -0.1294 +vn 0.5899 -0.3159 -0.7431 +vn 0.8597 -0.1150 -0.4976 +vn 0.6837 -0.2602 -0.6818 +vn 0.9001 -0.0670 -0.4305 +vn 0.9862 0.0122 0.1651 +vn 0.1287 0.3258 0.9366 +vn 0.2969 0.3647 0.8826 +vn 0.2499 0.3548 0.9009 +vn 0.0777 0.3121 0.9469 +vn -0.9609 0.0840 0.2637 +vn -0.9039 0.1776 0.3891 +vn -0.9194 0.1563 0.3609 +vn -0.9709 0.0607 0.2318 +vn -0.6277 -0.2540 -0.7358 +vn -0.5899 -0.2489 -0.7681 +vn -0.6170 -0.2526 -0.7453 +vn -0.5808 -0.2477 -0.7754 +vn 0.5100 -0.8520 -0.1185 +vn 0.3228 -0.5956 0.7356 +vn -0.3616 -0.6156 0.7002 +vn -0.5045 -0.8580 -0.0969 +vn 0.7783 -0.3124 -0.5447 +vn 0.9935 0.0662 -0.0922 +vn 0.5588 0.2271 0.7976 +vn 0.1892 0.3594 0.9138 +vn 0.4801 0.2619 0.8372 +vn 0.0916 0.3831 0.9191 +vn -0.6326 0.2170 0.7434 +vn -0.8907 0.1905 0.4128 +vn -0.7036 0.2143 0.6775 +vn -0.9286 0.1794 0.3247 +vn -0.7895 -0.2758 -0.5483 +vn -0.3897 -0.2273 -0.8925 +vn 0.2557 -0.9386 -0.2317 +vn 0.5602 -0.6456 0.5190 +vn -0.3268 -0.5562 0.7641 +vn -0.5069 -0.8617 -0.0209 +vn 0.4304 -0.3638 -0.8261 +vn 0.9804 -0.0182 -0.1960 +vn 0.9001 0.0922 0.4257 +vn 0.4953 0.3376 0.8004 +vn -0.5235 0.2480 0.8151 +vn -0.7689 0.2531 0.5872 +vn -0.5909 0.2519 0.7664 +vn -0.8152 0.2501 0.5225 +vn -0.8493 -0.2403 -0.4701 +vn -0.3000 -0.2463 -0.9216 +vn -0.2422 -0.0242 0.9699 +vn 0.0016 -1.0000 0.0054 +vn 0.0031 -1.0000 0.0028 +vn 0.0002 -1.0000 0.0079 +vn 0.0000 -1.0000 -0.0000 +vn 0.0045 -1.0000 0.0004 +vn -0.7046 -0.0408 -0.7084 +vn 0.9784 -0.0556 -0.1989 +vn 0.1990 -0.0615 -0.9781 +vn 0.0831 -0.1758 -0.9809 +vn 0.2313 0.0647 -0.9707 +vn 0.0817 0.2094 -0.9744 +vn 0.2741 -0.1562 -0.9489 +vn 0.2093 0.2171 -0.9534 +vn 0.2479 0.3653 -0.8973 +vn 0.0845 0.5567 -0.8264 +vn 0.2287 0.5940 -0.7713 +vn 0.0881 0.7762 -0.6243 +vn 0.2276 0.7974 -0.5589 +vn 0.0854 0.8980 -0.4315 +vn 0.2878 0.8929 -0.3463 +vn 0.3133 -0.2882 -0.9049 +vn 0.1632 -0.5069 -0.8464 +vn 0.1073 -0.5474 -0.8300 +vn 0.0689 -0.6620 -0.7464 +vn 0.2848 -0.4326 -0.8554 +vn 0.9722 -0.0529 0.2281 +vn 0.9390 -0.1954 0.2829 +vn 0.9923 -0.1099 0.0576 +vn 0.9804 -0.0653 -0.1858 +vn 0.9720 0.0296 -0.2330 +vn 0.9973 -0.0128 -0.0725 +vn 0.9979 0.0427 -0.0489 +vn 0.9989 -0.0463 0.0055 +vn 0.9996 0.0265 0.0096 +vn 0.9972 -0.0072 0.0749 +vn 0.9474 -0.2548 0.1936 +vn 0.9623 -0.2685 0.0432 +vn 0.9899 -0.1404 -0.0200 +vn 0.9503 -0.3111 -0.0135 +vn 0.9047 -0.4036 -0.1364 +vn 0.9412 -0.2012 -0.2714 +vn 0.8886 -0.3764 -0.2622 +vn 0.9949 -0.0831 -0.0578 +vn 0.9714 0.0253 0.2360 +vn 0.9030 0.2276 0.3644 +vn 0.9655 0.1004 0.2402 +vn 0.9328 0.3436 0.1089 +vn 0.9659 0.2590 0.0007 +vn 0.9932 0.0934 0.0692 +vn 0.9934 0.1128 -0.0198 +vn 0.9313 0.3500 -0.1007 +vn 0.9887 0.1137 -0.0980 +vn 0.9665 0.0906 -0.2402 +vn 0.9064 0.2299 -0.3543 +vn 0.1931 0.9555 -0.2232 +vn 0.1596 0.9781 -0.1335 +vn 0.3120 0.9484 -0.0561 +vn 0.5259 0.8435 -0.1090 +vn 0.5272 0.7972 -0.2941 +vn 0.7418 0.6526 -0.1543 +vn 0.7697 0.5882 0.2480 +vn 0.5732 0.8102 0.1225 +vn 0.5397 0.7877 0.2971 +vn 0.3413 0.8910 0.2994 +vn 0.2352 0.9287 0.2867 +vn 0.4491 0.8885 0.0947 +vn 0.1240 0.9886 0.0849 +vn 0.1681 0.9763 0.1362 +vn 0.2199 0.9755 0.0031 +vn 0.1111 0.9919 -0.0609 +vn 0.2432 0.9297 -0.2765 +vn 0.7261 0.6845 -0.0654 +vn 0.7541 0.6509 0.0877 +vn 0.4242 0.9037 -0.0581 +vn 0.1980 0.9586 0.2045 +vn 0.4063 0.9130 0.0360 +vn 0.5750 0.8166 0.0491 +vn 0.5565 0.8307 -0.0175 +vn 0.3082 0.9511 0.0199 +vn 0.7026 0.7115 0.0070 +vn 0.2266 0.0649 0.9718 +vn 0.0817 0.2024 0.9759 +vn 0.2189 -0.0520 0.9744 +vn 0.0839 -0.1760 0.9808 +vn 0.1776 -0.2221 0.9587 +vn 0.0832 0.8344 0.5449 +vn 0.2084 0.8023 0.5594 +vn 0.0801 0.5611 0.8239 +vn 0.2374 0.6005 0.7636 +vn 0.2385 0.3552 0.9039 +vn 0.2960 0.1617 0.9414 +vn 0.3205 -0.2853 0.9033 +vn 0.2172 -0.3941 0.8930 +vn 0.0877 -0.5665 0.8194 +vn 0.1037 -0.5595 0.8223 +vn 0.1335 -0.5188 0.8444 +vn 0.1107 -0.8158 -0.5676 +vn 0.1967 -0.6955 -0.6911 +vn 0.1600 -0.8828 -0.4416 +vn 0.3380 -0.8441 -0.4162 +vn 0.2870 -0.7038 -0.6498 +vn 0.4899 -0.7697 -0.4093 +vn 0.5640 -0.6625 -0.4930 +vn 0.5371 -0.5308 -0.6556 +vn 0.2726 -0.9235 -0.2698 +vn 0.0991 -0.8253 0.5559 +vn 0.0933 -0.8434 0.5292 +vn 0.0838 -0.9648 0.2495 +vn 0.1592 -0.8830 0.4416 +vn 0.2301 -0.9599 0.1601 +vn 0.2249 -0.9741 0.0244 +vn 0.0782 -0.9958 -0.0484 +vn 0.2243 -0.9703 -0.0911 +vn 0.0751 -0.9445 -0.3199 +vn 0.0794 0.9671 -0.2416 +vn 0.0768 0.9970 -0.0005 +vn 0.0776 0.9619 0.2622 +vn 0.5390 -0.6878 0.4862 +vn 0.4176 -0.5179 0.7466 +vn 0.2526 -0.6103 0.7508 +vn 0.2396 -0.9021 0.3590 +vn 0.3579 -0.8655 0.3505 +vn 0.1721 -0.7542 0.6337 +vn 0.2411 -0.7048 0.6672 +vn 0.5440 -0.7948 0.2690 +vn 0.4095 -0.9092 0.0757 +vn 0.5749 -0.8182 0.0061 +vn 0.4027 -0.9038 -0.1450 +vn 0.6521 -0.7322 -0.1966 +vn 0.7436 0.2032 -0.6370 +vn 0.8424 0.0311 -0.5379 +vn 0.6736 -0.1645 -0.7205 +vn 0.4469 -0.1161 -0.8870 +vn 0.5663 0.1370 -0.8127 +vn 0.4340 0.1053 -0.8947 +vn 0.7297 0.0957 0.6770 +vn 0.5465 0.1237 0.8283 +vn 0.4470 -0.1191 0.8866 +vn 0.6782 -0.1724 0.7144 +vn 0.8612 0.0320 0.5072 +vn 0.8683 -0.0071 0.4959 +vn 0.3912 -0.0751 0.9172 +vn 0.4998 0.6732 0.5450 +vn 0.5242 0.3726 0.7658 +vn 0.7587 0.3787 0.5301 +vn 0.5000 0.6768 -0.5403 +vn 0.5323 0.4197 -0.7352 +vn 0.9062 -0.1227 0.4047 +vn 0.8696 0.4925 0.0360 +vn 0.7882 0.5220 -0.3259 +vn 0.9175 0.3942 -0.0524 +vn 0.6803 -0.2959 0.6706 +vn 0.6251 -0.4958 0.6028 +vn 0.8147 -0.4048 0.4152 +vn 0.9087 -0.0107 -0.4173 +vn 0.9045 -0.1219 -0.4087 +vn 0.7495 -0.6330 0.1940 +vn 0.8902 -0.4329 0.1417 +vn 0.6802 -0.2979 -0.6697 +vn 0.7973 -0.3994 -0.4527 +vn 0.8102 -0.5862 -0.0032 +vn -1.0000 -0.0001 0.0001 +vn -1.0000 -0.0002 0.0003 +vn -1.0000 -0.0001 0.0000 +vn -1.0000 -0.0001 -0.0002 +vn -1.0000 0.0001 0.0000 +vn -1.0000 0.0009 0.0003 +vn -1.0000 0.0004 -0.0001 +vn -1.0000 -0.0065 0.0035 +vn 1.0000 0.0001 -0.0004 +vn 1.0000 0.0003 -0.0006 +vn 0.9979 0.0107 0.0639 +vn 1.0000 -0.0001 0.0001 +vn 1.0000 -0.0069 -0.0001 +vn 1.0000 -0.0003 -0.0003 +vn 1.0000 -0.0003 0.0002 +vn 0.9999 0.0155 -0.0011 +vn 1.0000 0.0000 0.0001 +vn 1.0000 -0.0018 -0.0005 +vn 0.9991 0.0274 0.0311 +vn 1.0000 -0.0001 -0.0005 +vn 1.0000 -0.0037 -0.0018 +vn 0.9999 -0.0140 -0.0086 +vn 0.9998 -0.0178 0.0117 +vn 0.9988 0.0326 -0.0378 +vn 1.0000 -0.0008 0.0002 +vn 1.0000 -0.0012 -0.0090 +vn 1.0000 0.0017 -0.0020 +vn 1.0000 -0.0001 -0.0002 +vn 1.0000 -0.0004 0.0003 +vn 1.0000 0.0006 0.0003 +vn 1.0000 -0.0004 0.0004 +vn 1.0000 -0.0001 0.0002 +vn 1.0000 -0.0001 0.0003 +vn 0.9999 0.0011 0.0109 +vn 0.9999 0.0082 0.0058 +vn -1.0000 0.0029 -0.0035 +vn 1.0000 0.0020 0.0001 +vn 1.0000 -0.0000 0.0006 +vn 1.0000 -0.0009 0.0004 +vn 1.0000 0.0008 -0.0004 +vn 1.0000 0.0021 -0.0021 +vn 1.0000 0.0011 0.0025 +vn 1.0000 -0.0018 -0.0010 +vn -1.0000 0.0012 -0.0000 +vn -1.0000 -0.0050 -0.0049 +vn -0.9999 -0.0051 -0.0100 +vn -1.0000 -0.0041 -0.0037 +vn -1.0000 0.0019 0.0008 +vn -1.0000 0.0017 0.0043 +vn -1.0000 -0.0003 0.0002 +vn -1.0000 0.0005 -0.0044 +vn -1.0000 0.0014 -0.0006 +vn -1.0000 -0.0004 -0.0002 +vn -1.0000 -0.0002 -0.0002 +vn -1.0000 -0.0021 -0.0012 +vn -1.0000 0.0021 0.0013 +vn -1.0000 -0.0003 0.0001 +vn -1.0000 -0.0020 0.0006 +vn -1.0000 0.0002 0.0002 +vn -0.9999 0.0096 0.0037 +vn -0.9999 0.0019 -0.0100 +vn -0.9997 -0.0003 0.0264 +vn -0.9999 -0.0062 0.0112 +vn -0.9998 -0.0091 0.0190 +vn -1.0000 -0.0004 -0.0035 +vn -0.9999 -0.0014 -0.0122 +vn -1.0000 -0.0025 0.0021 +vn -0.9999 0.0143 -0.0076 +vn -1.0000 0.0046 0.0061 +vn -0.9999 0.0109 -0.0033 +vn -1.0000 0.0009 -0.0010 +vn -1.0000 -0.0010 0.0008 +vn 0.9999 -0.0138 -0.0006 +vn 1.0000 0.0047 0.0049 +vn 0.9999 0.0169 -0.0020 +vn 0.0001 -0.2588 0.9659 +vn 0.0000 -0.2588 0.9659 +vn 0.0002 -0.2588 0.9659 +vn 0.0001 -0.2589 0.9659 +vn 0.0001 -0.2587 0.9660 +vn 0.0293 -0.0756 0.9967 +vn -0.0001 -0.2588 0.9659 +vn 0.0411 0.0002 0.9992 +vn -0.0011 -0.2359 0.9718 +vn -0.0007 -0.1226 0.9925 +vn -0.0000 -0.2587 0.9659 +vn -0.0001 -0.2586 0.9660 +vn 0.0123 -0.1741 0.9847 +vn -0.1084 -0.3262 0.9391 +vn 0.0150 -0.1099 0.9938 +vn -0.2444 -0.3012 0.9217 +vn -0.0208 -0.2555 0.9666 +vn -0.0003 -0.2588 0.9659 +vn -0.0002 -0.2587 0.9660 +vn 0.0002 0.2584 -0.9660 +vn 0.0002 0.2587 -0.9660 +vn 0.0004 0.2584 -0.9660 +vn 0.0004 0.2587 -0.9660 +vn 0.0001 0.2586 -0.9660 +vn 0.0004 0.2585 -0.9660 +vn -0.0000 0.2586 -0.9660 +vn 0.0001 0.2587 -0.9660 +vn -0.0002 0.2590 -0.9659 +vn -0.0008 0.2574 -0.9663 +vn 0.0001 0.2591 -0.9658 +vn 0.0000 0.2589 -0.9659 +vn 0.0020 0.2589 -0.9659 +vn 0.0010 0.2590 -0.9659 +vn 0.0001 0.2589 -0.9659 +vn 0.0066 0.3098 -0.9508 +vn 0.0000 0.2584 -0.9660 +vn -0.0001 0.2589 -0.9659 +vn -0.1980 0.1331 -0.9711 +vn 0.0003 0.4581 -0.8889 +vn -0.0366 0.2125 -0.9765 +vn 0.0030 0.5557 -0.8314 +vn -0.0205 0.2850 -0.9583 +vn -0.0900 0.2859 -0.9540 +vn 0.0002 0.2585 -0.9660 +vn 0.0002 0.2586 -0.9660 +vn 0.2422 0.2591 0.9350 +vn 0.6231 0.3624 0.6931 +vn 0.2781 0.2900 0.9157 +vn 0.6626 0.3834 0.6435 +vn 0.1625 0.9200 -0.3566 +vn -0.0448 0.7084 0.7044 +vn -0.6144 0.7549 -0.2293 +vn -0.7161 0.3579 0.5992 +vn -0.7608 0.0766 -0.6445 +vn -0.4365 -0.7275 0.5293 +vn -0.0958 -0.6307 -0.7701 +vn 0.2711 -0.9073 0.3215 +vn 0.6077 -0.4567 -0.6497 +vn 0.7610 -0.4520 0.4654 +vn 0.8314 -0.4071 0.3783 +vn 0.7464 -0.4598 0.4812 +vn 0.8476 -0.3945 0.3549 +vn -0.0591 -0.6933 0.7182 +vn 0.5569 -0.7709 -0.3090 +vn -0.7211 -0.3788 0.5801 +vn -0.9958 -0.0040 -0.0912 +vn 0.0672 0.1746 0.9823 +vn -0.5807 0.7800 0.2330 +vn -0.8611 0.4173 0.2906 +vn -0.6542 0.6562 -0.3760 +vn -0.2923 0.7173 0.6325 +vn 0.2732 0.4334 0.8588 +vn 0.5711 0.5387 -0.6194 +vn 0.7842 -0.0222 0.6202 +vn 0.7831 -0.2411 -0.5733 +vn 0.9084 -0.3322 -0.2540 +vn 0.8287 -0.2700 -0.4902 +vn 0.9141 -0.3385 -0.2231 +vn 0.3340 -0.9167 -0.2193 +vn 0.3030 -0.9514 -0.0542 +vn 0.3375 -0.9099 -0.2414 +vn 0.3000 -0.9531 -0.0399 +vn -0.3505 -0.8122 -0.4663 +vn -0.4149 -0.8976 -0.1487 +vn -0.3422 -0.7991 -0.4943 +vn -0.4180 -0.9001 -0.1232 +vn 0.7941 -0.4878 -0.3625 +vn -0.0517 -0.8765 0.4785 +vn -0.8582 -0.5125 0.0284 +vn -0.5762 0.1738 -0.7986 +vn 0.0845 0.2948 0.9518 +vn -0.3724 0.6616 -0.6509 +vn 0.8404 -0.3778 -0.3885 +vn 0.7007 0.4122 0.5823 +vn 0.1131 0.9875 -0.1095 +vn -0.7112 0.2320 0.6636 +vn -0.7821 -0.3133 -0.5387 +vn 0.1046 -0.9026 0.4176 +vn 0.9799 0.1989 0.0138 +vn 0.7681 0.5556 -0.3185 +vn -0.2115 0.6817 0.7004 +vn -0.9010 0.3609 -0.2406 +vn -0.9693 -0.2155 0.1182 +vn 0.0170 -0.9610 -0.2759 +vn 0.0346 -0.9674 -0.2510 +vn 0.0267 -0.9646 -0.2622 +vn 0.0451 -0.9707 -0.2360 +vn 0.2479 -0.3466 -0.9047 +vn 0.0003 -0.2589 -0.9659 +vn 0.0263 -0.2691 -0.9627 +vn -0.1964 -0.9779 0.0722 +vn -0.0098 -0.5739 -0.8189 +vn -0.0918 -0.5346 -0.8401 +vn -0.0828 -0.5338 -0.8415 +vn -0.0885 -0.3624 -0.9278 +vn -0.1223 -0.4088 -0.9044 +vn 0.3578 -0.3791 -0.8534 +vn 0.0002 -0.2592 -0.9658 +vn 0.0289 -0.0748 -0.9968 +vn 0.0400 -0.0031 -0.9992 +vn -0.0006 -0.2589 -0.9659 +vn -0.4826 -0.8247 0.2949 +vn -0.5221 -0.7891 0.3237 +vn -0.4899 -0.8618 -0.1313 +vn 0.0001 -0.2590 -0.9659 +vn 0.0000 -0.2589 -0.9659 +vn 0.0000 -0.2588 -0.9659 +vn -0.0001 -0.2589 -0.9659 +vn -0.0000 -0.2587 -0.9659 +vn -0.0000 -0.2587 -0.9660 +vn 0.0007 0.2584 0.9660 +vn 0.0391 0.2062 0.9777 +vn 0.0006 0.2586 0.9660 +vn 0.0001 0.2587 0.9660 +vn 0.2370 0.1978 0.9512 +vn 0.3089 0.2570 0.9157 +vn 0.0975 0.1515 0.9836 +vn -0.1049 0.3494 0.9311 +vn -0.0038 0.2622 0.9650 +vn 0.0000 0.2590 0.9659 +vn -0.0002 0.2584 0.9660 +vn -0.0000 0.2587 0.9659 +vn -0.0274 -0.0525 0.9982 +vn -0.0313 -0.0497 0.9983 +vn 0.0003 -0.0724 0.9974 +vn -0.3463 0.5356 0.7702 +vn -0.0622 -0.0274 0.9977 +vn -0.0002 0.2589 0.9659 +vn -0.4423 -0.5372 0.7182 +vn -0.4807 -0.7995 0.3603 +vn -0.0002 0.2591 0.9659 +vn 0.0000 0.2588 0.9659 +vn -0.0000 0.2587 0.9660 +vn -0.0000 0.2589 0.9659 +vn 0.0004 0.2587 0.9659 +vn 0.0003 0.2588 0.9659 +vn 0.0001 0.2588 0.9659 +vn 0.3451 0.3120 -0.8852 +vn 0.2922 0.3206 -0.9010 +vn 0.5475 0.2673 -0.7930 +vn 0.3599 0.7971 0.4849 +vn -0.0867 0.6269 -0.7743 +vn -0.3960 0.8618 0.3169 +vn -0.6617 0.3630 -0.6560 +vn -0.6838 0.2761 0.6754 +vn -0.6520 -0.4136 -0.6355 +vn -0.4355 -0.4900 0.7551 +vn -0.2260 -0.9199 -0.3205 +vn 0.2928 -0.4582 0.8392 +vn 0.4469 -0.5724 -0.6875 +vn 0.3870 0.3018 0.8713 +vn 0.0564 -0.7268 -0.6845 +vn -0.7116 -0.3833 -0.5888 +vn -0.9958 -0.0040 0.0912 +vn 0.0667 0.1752 -0.9823 +vn -0.5807 0.7800 -0.2330 +vn -0.8230 0.4219 -0.3805 +vn -0.7023 0.6647 0.2550 +vn -0.1889 0.8451 -0.5001 +vn -0.1884 0.8439 -0.5023 +vn -0.1909 0.8500 -0.4910 +vn -0.1910 0.8504 -0.4902 +vn 0.5284 0.8430 0.1009 +vn 0.5843 0.4537 -0.6728 +vn 0.8196 0.4065 0.4036 +vn 0.7040 -0.2704 -0.6567 +vn 0.7111 -0.1585 0.6849 +vn 0.2685 -0.9486 -0.1674 +vn 0.2545 -0.9409 -0.2233 +vn 0.3184 -0.9444 0.0818 +vn 0.3218 -0.9412 0.1032 +vn -0.8310 -0.3113 0.4610 +vn 0.0629 0.3456 -0.9363 +vn -0.3509 0.5387 0.7659 +vn 0.8408 -0.3162 0.4395 +vn 0.6711 0.2956 -0.6799 +vn 0.1946 0.9805 -0.0266 +vn -0.8328 0.4461 -0.3277 +vn -0.7226 -0.0496 0.6895 +vn -0.0648 -0.9215 -0.3829 +vn 0.7043 -0.7090 -0.0354 +vn 0.4787 0.8626 0.1636 +vn 0.2117 0.8999 -0.3812 +vn -0.9249 0.3767 0.0518 +vn -0.7560 -0.3661 -0.5427 +vn 0.2642 -0.6912 0.6726 +vn -0.0530 0.6712 0.7394 +vn -0.0483 0.6864 0.7256 +vn -0.0473 0.6895 0.7227 +vn -0.0540 0.6680 0.7422 +vn 0.1841 -0.7989 0.5726 +vn 0.1260 -0.6941 0.7088 +vn 0.1362 -0.7135 0.6873 +vn 0.0660 -0.5714 0.8180 +vn 0.1032 0.6236 -0.7749 +vn 0.2064 0.6319 -0.7470 +vn 0.0839 0.6213 -0.7791 +vn -0.0099 0.6065 -0.7950 +vn 0.8026 -0.4650 0.3736 +vn -0.3569 -0.6382 -0.6821 +vn -0.2522 -0.6608 -0.7069 +vn -0.2435 -0.6610 -0.7098 +vn -0.3541 -0.6380 -0.6837 +vn -0.0045 -0.6804 -0.7328 +vn -0.0445 -0.6813 -0.7306 +vn 0.0322 -0.7184 -0.6949 +vn 0.0370 -0.6417 -0.7661 +vn -0.2345 0.5790 -0.7809 +vn -0.1027 0.6727 -0.7327 +vn -0.1450 0.6449 -0.7504 +vn -0.0134 0.7508 -0.6604 +vn -0.0000 0.7312 -0.6822 +vn 0.0765 0.7799 -0.6212 +vn 0.0250 0.7634 -0.6454 +vn 0.0549 0.7990 -0.5988 +vn 0.0000 0.7314 -0.6820 +vn 0.0761 0.8222 -0.5640 +vn 0.0785 0.4082 0.9095 +vn 0.0461 0.7584 0.6502 +vn 0.0770 0.7315 0.6774 +vn -0.0190 0.8144 0.5800 +vn 0.0724 0.6793 0.7303 +vn 0.0633 0.6851 0.7257 +vn 0.0267 0.7798 0.6254 +vn 0.0191 0.7988 0.6013 +vn 0.9279 0.2714 0.2558 +vn 0.1288 -0.5296 0.8384 +vn 0.0428 -0.6709 0.7403 +vn 0.0953 -0.5880 0.8032 +vn -0.1023 -0.7248 0.6813 +vn 0.0660 -0.6437 0.7624 +vn -0.0145 -0.7108 0.7032 +vn 0.0000 -0.7313 0.6821 +vn 0.0779 0.8076 -0.5845 +vn -0.1008 0.7320 -0.6738 +vn -0.0107 -0.8911 -0.4536 +vn -0.0102 -0.8891 -0.4575 +vn 0.0586 -0.8352 -0.5468 +vn 0.0640 -0.4969 -0.8654 +vn 0.0132 -0.2164 -0.9762 +vn 0.0165 -0.1967 -0.9803 +vn 0.0694 -0.6772 0.7325 +vn 0.9979 -0.0641 0.0043 +vn 0.9947 0.0191 -0.1011 +vn 0.9932 0.0284 -0.1127 +vn 0.9972 -0.0736 0.0164 +vn 0.0450 0.7236 0.6887 +vn -0.6877 0.4657 0.5569 +vn 0.9308 0.1654 0.3261 +vn 0.0189 -0.7501 -0.6611 +vn 0.0120 -0.6525 -0.7577 +vn 0.0118 -0.6490 -0.7607 +vn 0.0191 -0.7530 -0.6578 +vn -0.9991 -0.0155 -0.0388 +vn -0.9549 0.1751 -0.2396 +vn -0.9992 -0.0397 -0.0086 +vn -0.9436 0.1903 -0.2709 +vn 0.1050 0.7406 -0.6637 +vn 0.1456 0.7057 -0.6934 +vn 0.0996 0.7450 -0.6596 +vn 0.0587 0.7766 -0.6272 +vn -0.9530 0.1956 -0.2313 +vn 0.7627 0.4200 -0.4919 +vn 0.7401 0.4094 -0.5335 +vn 0.8090 0.4411 -0.3886 +vn 0.6884 0.3847 -0.6150 +vn -0.0751 0.7456 -0.6622 +vn -0.0618 0.7620 -0.6446 +vn -0.0763 0.7440 -0.6638 +vn -0.0603 0.7638 -0.6426 +vn 0.2414 0.6538 0.7171 +vn 0.3643 0.6360 0.6803 +vn 0.1675 0.6755 0.7180 +vn 0.3687 0.6206 0.6921 +vn 0.4967 0.5931 0.6337 +vn 0.0138 0.6827 0.7306 +vn 0.4752 0.6020 0.6417 +vn 0.3265 0.6450 0.6909 +vn 0.5152 0.5852 0.6262 +vn 0.6968 0.4922 0.5218 +vn -0.9136 0.2855 0.2895 +vn -0.8265 0.3849 0.4108 +vn -0.8224 0.3887 0.4154 +vn -0.9173 0.2801 0.2830 +vn -0.1190 -0.3567 0.9266 +vn 0.1916 -0.4389 0.8779 +vn -0.2490 -0.9444 0.2146 +vn 0.3563 -0.8736 0.3316 +vn -0.0245 -0.6759 0.7366 +vn -0.9738 -0.2078 0.0926 +vn -0.9785 -0.1889 0.0832 +vn -0.9767 -0.1933 0.0929 +vn -0.6985 0.5193 0.4923 +vn 0.0451 0.7240 0.6883 +vn 0.9947 0.0192 -0.1012 +vn 0.9979 -0.0642 0.0043 +vn 0.9971 -0.0737 0.0164 +vn 0.9932 0.0285 -0.1128 +vn 0.0120 -0.6542 -0.7562 +vn 0.0187 -0.7502 -0.6609 +vn 0.0190 -0.7530 -0.6577 +vn 0.0118 -0.6507 -0.7592 +vn -0.9979 -0.0636 -0.0134 +vn -0.9985 -0.0487 -0.0239 +vn -0.9947 0.0703 0.0754 +vn 0.0171 0.7300 -0.6832 +vn 0.0168 0.7294 -0.6839 +vn 0.0156 0.7276 -0.6858 +vn 0.0218 -0.7247 0.6887 +vn 0.0232 -0.7227 0.6908 +vn 0.0180 -0.7306 0.6826 +vn 0.0167 -0.7325 0.6806 +vn -0.4096 0.6288 0.6610 +vn 0.0020 0.6739 0.7388 +vn 0.0577 0.6709 0.7393 +vn -0.4162 0.6270 0.6585 +vn 0.7276 -0.4283 -0.5359 +vn -0.9977 0.0395 0.0553 +vn -0.9957 0.0468 0.0800 +vn -0.9938 0.0521 0.0982 +vn -0.9988 0.0340 0.0364 +vn 0.1243 0.6765 0.7259 +vn 0.1243 0.6766 0.7258 +vn 0.1245 0.6767 0.7257 +vn 0.1241 0.6764 0.7260 +vn 0.0152 0.7270 -0.6864 +vn -0.0948 -0.6794 -0.7277 +vn -0.0947 -0.6793 -0.7277 +vn -0.0952 -0.6797 -0.7273 +vn -0.0942 -0.6790 -0.7281 +vn -0.0006 0.7314 -0.6820 +vn 0.9943 -0.0720 -0.0786 +vn 0.9944 -0.0717 -0.0776 +vn 0.9942 -0.0723 -0.0795 +vn 0.9945 -0.0715 -0.0767 +vn -0.0039 0.7482 -0.6634 +vn -0.0000 0.7313 -0.6820 +vn -0.0282 0.7598 -0.6496 +vn 0.0000 -0.7313 0.6820 +vn -0.0105 -0.7143 0.6998 +vn -0.0234 -0.6842 0.7289 +vn -0.1174 0.6745 -0.7289 +vn -0.1445 0.6399 -0.7547 +vn -0.5353 -0.3420 -0.7724 +vn -0.6079 -0.4988 -0.6178 +vn -0.5191 -0.3116 -0.7959 +vn -0.6212 -0.5346 -0.5730 +vn 0.5030 -0.8282 -0.2471 +vn 0.7823 0.2593 -0.5664 +vn -0.0197 -0.6493 0.7603 +vn -0.0144 -0.6431 0.7656 +vn 0.7394 -0.1000 0.6658 +vn 0.2607 0.8774 0.4028 +vn 0.0886 0.6800 0.7278 +vn 0.0848 0.6805 0.7279 +vn 0.1584 0.6702 0.7251 +vn 0.1622 0.6696 0.7248 +vn -0.9978 0.0357 0.0563 +vn -0.9991 -0.0307 0.0291 +vn -0.9992 -0.0059 0.0393 +vn -0.9958 0.0627 0.0673 +vn -0.1004 -0.6788 -0.7275 +vn -0.1177 -0.9746 0.1905 +vn -0.0578 -0.8693 0.4909 +vn -0.0919 -0.8375 0.5386 +vn 0.4740 0.8432 0.2537 +vn 0.2997 0.2245 0.9272 +vn 0.2117 0.8337 0.5100 +vn -0.0699 -0.7919 0.6066 +vn -0.0000 -0.7314 0.6819 +vn -0.0001 0.7313 -0.6820 +vn -0.0137 0.7175 -0.6964 +vn -0.0000 -0.7315 0.6819 +vn -0.0694 0.6565 -0.7511 +vn 0.5916 -0.0457 -0.8050 +vn 0.8247 -0.5519 0.1239 +vn -0.5318 -0.7322 -0.4255 +vn -0.0000 0.6815 0.7318 +vn 0.0001 0.6820 0.7313 +vn 0.5959 -0.6134 0.5183 +vn -0.0575 -0.9822 0.1788 +vn -0.1924 -0.5716 0.7977 +vn -0.3389 -0.6656 0.6649 +vn -0.1831 -0.5649 0.8046 +vn -0.0339 -0.4478 0.8935 +vn 0.0672 -0.7054 0.7056 +vn 0.0626 -0.7044 0.7071 +vn 0.1935 -0.7280 0.6577 +vn 0.1416 -0.9897 0.0192 +vn 0.1273 -0.9917 0.0181 +vn 0.0955 -0.9954 0.0001 +vn 0.1546 -0.9877 -0.0229 +vn 0.1007 -0.9949 0.0029 +vn 0.1382 -0.9900 -0.0294 +vn 0.1595 -0.9872 0.0053 +vn 0.0956 -0.9954 0.0002 +vn 0.0957 -0.9954 -0.0000 +vn 0.0957 -0.9954 0.0001 +vn 0.0954 -0.9954 0.0001 +vn 0.0956 -0.9954 0.0000 +vn 0.0913 -0.0070 -0.9958 +vn 0.0203 0.1988 -0.9798 +vn 0.0796 0.0280 -0.9964 +vn 0.0111 0.2247 -0.9744 +vn -0.0957 0.9954 0.0000 +vn -0.1094 0.9940 0.0032 +vn -0.1031 0.9947 -0.0019 +vn -0.1081 0.9941 -0.0017 +vn -0.1182 0.9930 0.0024 +vn -0.1223 0.9925 -0.0002 +vn -0.0956 0.9954 -0.0000 +vn -0.0958 0.9954 -0.0000 +vn -0.0959 0.9954 -0.0000 +vn -0.0951 0.9955 -0.0003 +vn -0.0955 0.9954 0.0000 +vn -0.0956 0.9954 -0.0001 +vn -0.6142 -0.2108 -0.7605 +vn -0.1212 -0.5266 -0.8414 +vn -0.0053 0.0003 -1.0000 +vn -0.0074 0.0004 -1.0000 +vn -0.0022 0.0001 -1.0000 +vn -0.0000 -0.0000 -1.0000 +vn 0.9997 -0.0229 -0.0021 +vn 0.9985 -0.0539 0.0065 +vn 0.9996 -0.0296 -0.0003 +vn 0.9981 -0.0604 0.0083 +vn 0.0000 -0.0000 1.0000 +vn -0.0987 0.0773 0.9921 +vn -0.1178 0.0832 0.9895 +vn -0.0557 0.0139 0.9984 +vn -0.1719 0.0417 0.9842 +vn 0.0454 -0.0275 0.9986 +vn 0.0519 -0.0483 0.9975 +vn -0.7481 0.6634 0.0131 +vn -0.8011 0.5985 -0.0119 +vn -0.7614 0.6483 0.0071 +vn -0.8127 0.5824 -0.0178 +vn -0.9268 -0.3721 -0.0506 +vn -0.8684 -0.4957 0.0113 +vn -0.8868 -0.4621 -0.0061 +vn -0.9423 -0.3271 -0.0720 +vn -0.1203 -0.9898 0.0759 +vn 0.9594 0.2506 -0.1293 +vn 0.6409 0.7677 -0.0012 +vn 0.9886 0.1505 0.0036 +vn 0.9893 0.1460 0.0032 +vn 0.9963 0.0860 -0.0032 +vn 0.9967 0.0813 -0.0037 +vn -0.8377 -0.4574 0.2985 +vn -0.5096 0.2731 0.8159 +vn 0.1663 -0.2469 0.9547 +vn 0.7622 0.3959 0.5122 +vn 0.9648 -0.2629 -0.0090 +vn 0.4394 0.3975 -0.8056 +vn -0.0964 -0.4312 -0.8971 +vn -0.8060 0.3236 -0.4957 +vn -0.8785 -0.3281 0.3473 +vn 0.0592 0.0936 0.9938 +vn 0.0069 -0.0205 0.9998 +vn 0.0978 0.1780 0.9792 +vn 0.1335 0.2566 0.9573 +vn 0.9939 -0.1022 0.0426 +vn 0.9915 -0.1194 0.0519 +vn 0.9963 -0.0803 0.0307 +vn 0.9983 -0.0551 0.0171 +vn 0.1169 0.2796 -0.9530 +vn -0.2432 -0.4444 -0.8622 +vn -0.9383 0.3311 -0.1000 +vn -0.0114 -0.0675 -0.9977 +vn -0.0774 -0.4583 -0.8854 +vn -0.0188 -0.0905 -0.9957 +vn -0.0186 -0.0301 0.9994 +vn -0.0005 -0.0426 0.9991 +vn -0.0036 -0.0318 0.9995 +vn 0.0658 -0.1125 0.9915 +vn -0.0966 -0.0061 0.9953 +vn 0.0591 -0.0615 0.9964 +vn -0.0275 -0.0617 -0.9977 +vn -0.0042 -0.0096 -0.9999 +vn -0.0367 -0.0823 -0.9959 +vn 0.0000 1.0000 0.0000 +vn -0.1567 -0.0045 -0.9876 +vn 0.0607 -0.0080 -0.9981 +vn -0.0702 -0.0294 -0.9971 +vn 0.0570 0.0000 -0.9984 +vn -0.2489 -0.0222 -0.9683 +vn -0.3958 0.0338 -0.9177 +vn -0.8326 0.0438 -0.5521 +vn -0.1392 0.1045 -0.9847 +vn -0.0980 0.0736 -0.9925 +vn -0.2256 0.1694 -0.9594 +vn -0.1011 -0.1441 -0.9844 +vn -0.0386 -0.0919 -0.9950 +vn -0.1203 -0.1564 -0.9803 +vn -0.0473 -0.9988 0.0115 +vn -0.0530 -0.9985 -0.0132 +vn -0.0483 -0.9988 0.0072 +vn -0.0540 -0.9984 -0.0174 +vn 0.9942 -0.1062 0.0139 +vn 0.9955 -0.0907 -0.0259 +vn 0.9963 -0.0301 -0.0799 +vn 0.9996 -0.0069 -0.0256 +vn 0.9742 -0.0585 0.2179 +vn 0.9996 -0.0111 0.0264 +vn 0.9976 -0.0491 0.0498 +vn 0.9990 -0.0433 0.0132 +vn -0.9589 -0.2828 -0.0205 +vn -0.9735 -0.2021 0.1069 +vn -0.9343 -0.0257 0.3555 +vn -0.9151 0.0113 0.4030 +vn 0.1485 0.0291 0.9885 +vn -0.1907 -0.0757 0.9787 +vn -0.0218 0.0088 0.9997 +vn 0.1430 0.0540 0.9883 +vn 0.0281 -0.0000 0.9996 +vn 0.0368 0.0188 0.9991 +vn 0.2178 -0.2336 0.9476 +vn 0.2448 0.3057 0.9201 +vn -0.3585 0.4264 0.8305 +vn -0.4283 -0.2616 0.8649 +vn 0.3365 0.2473 0.9086 +vn -0.6140 0.2059 0.7619 +vn -0.0289 -0.5840 0.8113 +vn 0.0513 -0.0496 0.9974 +vn 0.0529 -0.0478 0.9975 +vn 0.1149 0.0227 0.9931 +vn -0.0122 -0.1209 0.9926 +vn -0.7875 -0.6162 0.0123 +vn -0.5604 -0.8281 -0.0145 +vn -0.5441 -0.8389 -0.0161 +vn -0.7978 -0.6028 0.0137 +vn -0.6312 0.7756 -0.0099 +vn -0.6852 0.7282 -0.0178 +vn -0.6889 0.7246 -0.0184 +vn -0.6261 0.7797 -0.0092 +vn 0.8801 0.4744 -0.0174 +vn 0.6732 0.7393 0.0137 +vn 0.6913 0.7224 0.0114 +vn 0.8909 0.4537 -0.0195 +vn 0.3666 -0.9302 -0.0157 +vn 0.6463 -0.7630 0.0140 +vn 0.6322 -0.7747 0.0124 +vn 0.3464 -0.9379 -0.0176 +vn -0.6687 -0.7430 -0.0284 +vn -0.9029 0.4297 0.0049 +vn -0.9342 0.3565 0.0122 +vn -0.9326 0.3608 0.0118 +vn -0.8996 0.4367 0.0041 +vn 0.3189 0.9477 -0.0121 +vn 0.8216 0.5687 0.0393 +vn 0.9298 -0.3663 -0.0356 +vn 0.0191 -0.9993 0.0313 +vn -0.6010 -0.6753 -0.4275 +vn -0.6521 -0.7326 -0.1953 +vn -0.6662 -0.7276 -0.1637 +vn -0.9776 0.1551 0.1426 +vn -0.6810 0.6729 -0.2889 +vn -0.7039 0.7034 -0.0990 +vn -0.7072 0.6988 -0.1075 +vn -0.2638 0.9519 0.1561 +vn 0.7699 0.4871 -0.4122 +vn 0.8384 0.5306 -0.1244 +vn 0.8294 0.5245 -0.1922 +vn 0.9766 0.1587 0.1450 +vn 0.5219 -0.7395 -0.4252 +vn 0.5689 -0.8061 -0.1631 +vn 0.5585 -0.8052 -0.1991 +vn -0.0661 -0.9726 0.2230 +vn -0.8692 -0.4051 0.2835 +vn -0.8964 -0.4178 0.1479 +vn -0.8952 -0.4336 0.1031 +vn -0.9851 -0.0725 -0.1558 +vn -0.5750 0.7855 0.2289 +vn -0.5923 0.7993 0.1009 +vn -0.5888 0.8044 0.0792 +vn -0.2027 0.9671 -0.1539 +vn 0.7577 0.4721 0.4505 +vn 0.8305 0.5175 0.2059 +vn 0.8403 0.5239 0.1391 +vn 0.9854 0.1456 -0.0879 +vn 0.2919 -0.9395 0.1793 +vn 0.3743 -0.9159 0.1450 +vn 0.2977 -0.9539 0.0388 +vn 0.1456 -0.9882 -0.0475 +vn 0.0170 -0.0745 0.9971 +vn -0.1267 -0.0750 0.9891 +vn -0.0016 -0.0746 0.9972 +vn -0.6130 -0.7568 0.2269 +vn -0.9235 -0.0882 -0.3734 +vn -0.9868 -0.0961 -0.1306 +vn -0.9854 -0.0941 -0.1419 +vn -0.7306 0.5974 0.3307 +vn -0.3457 0.9383 -0.0077 +vn -0.3457 0.9383 -0.0088 +vn -0.3439 0.9390 -0.0087 +vn 0.5717 0.7651 0.2963 +vn 0.8187 0.2607 -0.5116 +vn 0.6236 -0.6975 0.3531 +vn 0.0873 -0.9628 -0.2558 +vn 0.0738 -0.9934 -0.0883 +vn 0.0900 -0.9934 -0.0710 +vn -0.7315 -0.5454 -0.4092 +vn -0.6824 -0.5071 -0.5265 +vn -0.6955 -0.5173 -0.4988 +vn -0.9798 -0.1226 0.1579 +vn -0.9909 -0.1218 0.0572 +vn -0.9887 -0.1237 0.0849 +vn -0.2358 0.9660 -0.1060 +vn -0.3163 0.9486 0.0032 +vn -0.2494 0.9637 -0.0956 +vn -0.1312 0.9605 -0.2452 +vn 0.7929 0.5384 0.2853 +vn 0.8212 0.5576 0.1214 +vn 0.8349 0.5390 0.1110 +vn 0.8799 -0.3514 -0.3197 +vn 0.8803 -0.4101 -0.2388 +vn 0.9065 -0.3825 -0.1785 +vn 0.9107 -0.3197 -0.2617 +vn -0.1724 -0.9476 0.2688 +vn -0.1612 -0.9801 0.1159 +vn -0.1784 -0.9802 0.0858 +vn 0.9063 -0.4223 -0.0178 +vn 0.9443 0.3272 0.0356 +vn 0.9521 0.3032 0.0392 +vn 0.0594 0.9946 0.0853 +vn -0.0854 0.9963 0.0019 +vn 0.0136 0.9981 0.0596 +vn 0.0539 0.9984 -0.0180 +vn 0.0145 0.9997 -0.0173 +vn 0.1554 0.0306 0.9874 +vn 0.1639 0.0409 -0.9856 +vn 0.2546 0.0359 -0.9664 +vn 0.2368 0.0369 -0.9709 +vn 0.1478 0.0418 -0.9881 +vn 0.3339 -0.9426 0.0001 +vn 0.3424 -0.9395 0.0011 +vn 0.3418 -0.9398 0.0011 +vn 0.3331 -0.9429 0.0000 +vn 0.9259 0.3759 0.0380 +vn 0.9533 0.3018 0.0108 +vn 0.9143 0.4022 0.0479 +vn 0.9623 0.2719 0.0000 +vn -0.0932 0.1366 0.9862 +vn -0.0717 0.1051 0.9919 +vn -0.0126 0.0184 0.9998 +vn -0.9205 -0.1552 -0.3585 +vn 0.0480 -0.0544 -0.9974 +vn -0.0330 -0.0663 0.9973 +vn 0.9834 0.1812 0.0125 +vn 0.9687 0.2446 0.0427 +vn 0.9747 0.2211 0.0314 +vn 0.9879 0.1551 0.0002 +vn 0.0998 0.0147 -0.9949 +vn 0.0569 -0.0424 -0.9975 +vn 0.0573 -0.0419 -0.9975 +vn 0.0145 -0.0984 -0.9950 +vn 0.0397 0.0787 -0.9961 +vn 0.0432 0.0696 -0.9966 +vn -0.0018 0.1863 -0.9825 +vn 0.0740 -0.0120 -0.9972 +vn -0.1879 0.1494 -0.9708 +vn 0.0135 0.1077 -0.9941 +vn -0.0176 0.1144 -0.9933 +vn 0.1887 0.0675 -0.9797 +vn -0.0001 -1.0000 0.0013 +vn -0.0569 -0.9984 0.0049 +vn -0.0313 -0.9995 0.0097 +vn 0.0188 -0.9998 0.0075 +vn -0.6097 0.7920 0.0316 +vn 0.6854 0.5666 -0.4574 +vn 0.5496 0.8276 0.1140 +vn 0.8036 -0.3057 0.5107 +vn -0.0711 0.0982 -0.9926 +vn -0.0919 0.1774 -0.9798 +vn -0.0570 0.2309 -0.9713 +vn 0.2558 -0.9262 0.2770 +vn 0.2897 -0.7435 -0.6028 +vn -0.1177 0.5253 -0.8428 +vn -0.1004 0.9950 0.0000 +vn -0.9978 -0.0655 -0.0123 +vn -0.9991 -0.0004 -0.0423 +vn -0.9992 -0.0247 -0.0311 +vn -0.9958 -0.0919 -0.0000 +vn 0.0886 -0.9961 0.0009 +vn 0.0848 -0.9964 0.0012 +vn 0.1586 -0.9873 -0.0044 +vn 0.1623 -0.9867 -0.0047 +vn -0.8627 -0.0967 0.4963 +vn 0.3179 -0.9361 -0.1505 +vn 0.3145 -0.9333 -0.1730 +vn 0.3495 -0.8989 0.2643 +vn 0.3495 -0.8927 0.2845 +vn 0.8798 -0.3454 -0.3265 +vn -0.0043 0.0061 -1.0000 +vn -0.0245 0.0346 -0.9991 +vn -0.0313 0.0442 -0.9985 +vn 0.8083 0.3188 0.4950 +vn 0.5031 0.7454 -0.4373 +vn -0.6212 0.7836 0.0000 +vn -0.6079 0.7920 0.0568 +vn -0.5353 0.7980 0.2768 +vn -0.5191 0.7945 0.3151 +vn -0.1209 0.1562 0.9803 +vn -0.0240 0.0321 0.9992 +vn -0.1506 0.1940 0.9694 +vn 0.0000 0.0005 1.0000 +vn 0.9945 0.1049 0.0000 +vn 0.9944 0.1057 0.0004 +vn 0.9943 0.1066 0.0010 +vn 0.9942 0.1074 0.0014 +vn -0.0947 0.9955 -0.0006 +vn -0.0943 0.9955 0.0000 +vn -0.0947 0.9955 -0.0005 +vn -0.0952 0.9955 -0.0011 +vn 0.0168 0.0026 0.9999 +vn 0.0152 0.0062 0.9999 +vn 0.0156 0.0053 0.9999 +vn 0.1241 -0.9923 -0.0005 +vn 0.1243 -0.9922 -0.0002 +vn 0.1243 -0.9922 -0.0003 +vn 0.1245 -0.9922 0.0000 +vn -0.9988 -0.0498 0.0000 +vn -0.9957 -0.0904 -0.0204 +vn -0.9977 -0.0674 -0.0088 +vn -0.9938 -0.1074 -0.0289 +vn 0.7281 0.6835 0.0522 +vn -0.4102 -0.9119 0.0091 +vn -0.4169 -0.9089 0.0094 +vn 0.0024 -0.9999 -0.0110 +vn 0.0582 -0.9982 -0.0135 +vn 0.0218 -0.0094 -0.9997 +vn 0.0180 -0.0010 -0.9998 +vn 0.0168 0.0017 -0.9999 +vn 0.0231 -0.0123 -0.9997 +vn 0.0172 0.0018 0.9999 +vn -0.9947 -0.1030 0.0000 +vn -0.9984 0.0522 -0.0193 +vn 0.0118 0.9991 0.0415 +vn 0.0188 0.9950 -0.0981 +vn 0.0120 0.9992 0.0370 +vn 0.0190 0.9946 -0.1024 +vn 0.9932 0.0631 0.0976 +vn 0.9979 0.0406 -0.0498 +vn 0.9947 0.0609 0.0829 +vn 0.9972 0.0382 -0.0650 +vn 0.0452 -0.9972 0.0598 +vn -0.6986 -0.7142 0.0443 +vn -0.2160 -0.1447 -0.9656 +vn 0.2552 0.4159 -0.8729 +vn -0.2489 0.4867 -0.8373 +vn 0.1916 -0.3431 -0.9195 +vn -0.1190 -0.4339 -0.8931 +vn -0.9135 -0.4067 -0.0129 +vn -0.9774 -0.2112 0.0005 +vn -0.9181 -0.3961 -0.0121 +vn -0.9786 -0.2057 0.0008 +vn -0.3076 -0.6693 0.6763 +vn 0.0857 -0.9956 0.0375 +vn 0.1105 -0.9927 -0.0474 +vn 0.0215 -0.9998 0.0000 +vn 0.2028 -0.9792 -0.0064 +vn 0.1634 -0.9866 0.0022 +vn 0.3942 -0.9190 -0.0085 +vn 0.4985 -0.8669 0.0019 +vn 0.3632 -0.9317 0.0008 +vn 0.5303 -0.8478 -0.0009 +vn 0.0834 -0.1786 0.9804 +vn -0.2061 0.3881 0.8982 +vn -0.9512 0.1256 0.2818 +vn -0.5720 -0.2550 0.7796 +vn 0.7584 -0.1129 0.6419 +vn 0.4410 0.3667 0.8192 +vn -0.9988 0.0437 -0.0227 +vn 0.0191 0.9946 -0.1024 +vn 0.0120 0.9992 0.0394 +vn 0.0189 0.9950 -0.0981 +vn 0.0118 0.9990 0.0440 +vn 0.9607 -0.2776 -0.0076 +vn -0.4088 -0.9039 -0.1262 +vn -0.4149 -0.8995 -0.1370 +vn -0.2451 -0.9585 -0.1459 +vn -0.1968 -0.9714 -0.1327 +vn 0.0063 -0.9994 0.0327 +vn 0.0122 -0.9980 0.0620 +vn 0.9971 0.0382 -0.0651 +vn 0.9947 0.0609 0.0830 +vn 0.9932 0.0631 0.0977 +vn -0.0796 0.1947 0.9776 +vn -0.0049 -0.0010 1.0000 +vn -0.0010 -0.0818 0.9966 +vn 0.0165 0.8513 0.5245 +vn 0.0120 0.8652 0.5014 +vn 0.0671 0.9773 0.2009 +vn 0.0422 0.9974 0.0580 +vn 0.0687 0.9835 -0.1675 +vn 0.0600 0.9964 -0.0599 +vn -0.0024 0.9796 -0.2012 +vn -0.0007 0.9817 -0.1903 +vn -0.1084 0.3130 0.9435 +vn 0.0342 -0.0669 -0.9972 +vn 0.0759 -0.1482 -0.9860 +vn 0.1042 -0.2035 -0.9735 +vn 0.9279 -0.3722 0.0241 +vn 0.0194 -0.9976 0.0671 +vn 0.0276 -0.9990 0.0346 +vn 0.1157 -0.9914 -0.0616 +vn 0.0616 -0.9740 0.2179 +vn -0.0180 -0.9276 0.3730 +vn 0.0656 -0.9439 -0.3236 +vn -0.1450 0.1090 0.9834 +vn -0.1027 0.0771 0.9917 +vn 0.0144 -0.0127 0.9998 +vn 0.0096 -0.0223 0.9997 +vn 0.0016 -0.0385 0.9993 +vn 0.0196 -0.0021 0.9998 +vn -0.2345 0.1762 0.9560 +vn -0.0219 0.9998 -0.0006 +vn -0.0039 1.0000 -0.0001 +vn -0.2418 0.9703 0.0023 +vn -0.2448 0.9696 0.0007 +vn -0.3468 0.9379 0.0029 +vn -0.3541 0.9352 -0.0003 +vn -0.0364 -0.6773 0.7348 +vn 0.0643 -0.7085 0.7027 +vn 0.0226 -0.6474 0.7618 +vn 0.0650 -0.7095 0.7017 +vn 0.1064 -0.7647 0.6355 +vn 0.8013 0.0422 -0.5968 +vn 0.1274 -0.0730 0.9892 +vn 0.3015 -0.1156 -0.9464 +vn -0.0766 0.4389 -0.8953 +vn -0.5707 -0.4211 -0.7050 +vn -0.7697 -0.4446 0.4581 +vn -0.0514 -0.9504 -0.3069 +vn 0.0250 -0.9986 -0.0476 +vn -0.0399 -0.9625 -0.2684 +vn 0.0423 -0.9990 0.0126 +vn 0.9834 -0.1144 -0.1410 +vn 0.9687 -0.1356 -0.2081 +vn 0.9747 -0.1278 -0.1832 +vn 0.9879 -0.1057 -0.1135 +vn -0.0329 0.7747 -0.6315 +vn 0.0481 -0.6923 0.7200 +vn -0.9203 -0.1568 0.3585 +vn -0.0932 0.6282 -0.7725 +vn 0.9533 -0.1980 -0.2281 +vn 0.9259 -0.2286 -0.3009 +vn 0.9623 -0.1855 -0.1989 +vn 0.9143 -0.2393 -0.3268 +vn 0.3339 0.6429 0.6893 +vn 0.3424 0.6416 0.6863 +vn 0.3418 0.6417 0.6866 +vn 0.3331 0.6431 0.6896 +vn 0.1638 -0.7488 0.6422 +vn 0.2548 -0.7312 0.6327 +vn 0.2369 -0.7352 0.6351 +vn 0.1477 -0.7512 0.6433 +vn 0.1553 0.7012 -0.6958 +vn -0.0849 -0.6781 -0.7300 +vn 0.0542 -0.6941 -0.7179 +vn 0.0148 -0.6944 -0.7194 +vn 0.0140 -0.6372 -0.7706 +vn 0.0597 -0.6160 -0.7855 +vn 0.0000 -0.6820 -0.7314 +vn -0.0001 -0.6820 -0.7314 +vn 0.0001 -0.6820 -0.7314 +vn -0.0001 -0.6820 -0.7313 +vn 0.0001 -0.6820 -0.7313 +vn -0.1476 0.7614 0.6313 +vn -0.3798 0.6026 0.7019 +vn -0.3955 0.6112 0.6856 +vn -0.8201 -0.4394 -0.3665 +vn -0.8134 -0.4907 -0.3124 +vn -0.8137 -0.4891 -0.3141 +vn -0.9980 0.0636 -0.0031 +vn -0.9990 0.0394 0.0196 +vn -0.9896 0.0509 0.1344 +vn 0.2490 -0.7491 -0.6139 +vn 0.0401 -0.5596 -0.8278 +vn 0.0242 -0.5628 -0.8262 +vn 0.2671 -0.7509 -0.6040 +vn 0.9832 0.1811 0.0224 +vn 0.9650 0.0249 0.2612 +vn 0.9627 0.0064 0.2704 +vn 0.9791 0.2033 -0.0067 +vn -0.1262 0.7475 0.6521 +vn -0.1212 0.8619 0.4924 +vn 0.3586 0.5061 0.7844 +vn 0.9291 0.3407 -0.1442 +vn 0.7982 -0.5915 -0.1141 +vn 0.0221 -0.2979 -0.9543 +vn -0.7041 -0.6597 -0.2627 +vn -0.9740 0.0394 0.2230 +vn -0.9065 0.0762 0.4152 +vn -0.3914 0.5135 0.7636 +vn 0.3734 0.8037 0.4633 +vn 0.8848 -0.1807 0.4294 +vn 0.8574 -0.1113 -0.5025 +vn 0.2506 -0.8808 -0.4018 +vn -0.3688 -0.4589 -0.8083 +vn -0.7955 -0.5605 -0.2303 +vn -0.7379 0.6604 0.1390 +vn -0.9055 0.3219 0.2765 +vn -0.9454 0.2552 0.2028 +vn -0.8948 0.4015 0.1955 +vn -0.4073 0.5992 0.6893 +vn -0.2853 0.6488 0.7055 +vn -0.4054 0.5453 0.7337 +vn -0.5858 -0.4953 -0.6416 +vn -0.5143 -0.5659 -0.6444 +vn -0.5186 -0.5637 -0.6429 +vn -0.5756 -0.5091 -0.6399 +vn 0.8485 -0.3771 -0.3712 +vn 0.8680 -0.3039 -0.3927 +vn 0.8438 -0.2796 -0.4581 +vn 0.9804 0.1559 0.1207 +vn 0.3785 0.6179 0.6892 +vn 0.3193 0.6419 0.6972 +vn 0.3770 0.6956 0.6115 +vn 0.3227 0.7143 0.6210 +vn 0.2248 0.6089 0.7607 +vn 0.8544 -0.2115 -0.4747 +vn 0.8970 -0.2624 -0.3558 +vn -0.5697 -0.4838 -0.6644 +vn -0.5433 -0.5235 -0.6563 +vn -0.9516 0.2785 0.1301 +vn -0.9879 0.0018 0.1551 +vn -0.0002 -0.7313 0.6821 +vn -0.0539 0.7807 0.6226 +vn -0.2793 0.5994 0.7501 +vn 0.8568 -0.2400 0.4564 +vn 0.9857 -0.0699 -0.1533 +vn 0.3045 -0.8192 -0.4860 +vn -0.2260 -0.3857 -0.8945 +vn -0.8392 -0.5438 -0.0068 +vn -0.9351 0.3543 0.0079 +vn 0.1220 0.6947 0.7089 +vn -0.2880 0.6406 0.7118 +vn -0.2523 0.6502 0.7167 +vn 0.1529 0.6940 0.7036 +vn 0.9390 0.2189 0.2653 +vn 0.4855 -0.6052 -0.6309 +vn 0.7873 -0.4035 -0.4662 +vn 0.8022 -0.3885 -0.4533 +vn 0.4577 -0.6173 -0.6399 +vn -0.8319 -0.3792 -0.4051 +vn -0.8961 -0.2920 -0.3344 +vn -0.8919 -0.2985 -0.3398 +vn -0.8256 -0.3866 -0.4110 +vn -0.0945 0.6768 0.7300 +vn -0.0665 0.6804 0.7298 +vn -0.0684 0.6802 0.7298 +vn -0.0963 0.6766 0.7300 +vn 0.9996 -0.0223 -0.0162 +vn 0.9975 0.0527 0.0478 +vn 0.9968 0.0592 0.0534 +vn 0.9994 -0.0288 -0.0217 +vn -0.1556 -0.6696 -0.7262 +vn -0.1789 -0.6650 -0.7251 +vn -0.1772 -0.6653 -0.7252 +vn -0.1537 -0.6700 -0.7263 +vn -0.9968 0.0528 0.0600 +vn -0.9901 0.0977 0.1006 +vn -0.9907 0.0948 0.0981 +vn -0.9971 0.0502 0.0576 +vn 0.0415 0.6853 -0.7271 +vn 0.0403 0.6847 -0.7277 +vn -0.0281 0.6490 -0.7602 +vn 0.1028 0.7132 -0.6934 +vn -0.3748 0.5164 -0.7700 +vn 0.3441 0.5002 -0.7946 +vn 0.1401 0.9845 0.1053 +vn -0.1873 0.8629 -0.4695 +vn -0.1988 0.8554 -0.4783 +vn -0.0567 0.9296 -0.3641 +vn -0.3223 0.7583 -0.5667 +vn -0.0460 0.3951 -0.9175 +vn 0.4364 0.6745 -0.5955 +vn 0.0200 0.7086 -0.7054 +vn 0.2645 0.6453 -0.7167 +vn 0.1460 0.6431 -0.7517 +vn 0.0049 0.7314 -0.6820 +vn 0.4941 0.5810 -0.6468 +vn -0.1900 0.7886 -0.5849 +vn -0.8870 0.3199 -0.3329 +vn -0.9373 0.2215 0.2690 +vn 0.9975 0.0699 0.0019 +vn 0.9996 0.0269 -0.0099 +vn 0.9990 0.0392 0.0226 +vn 0.9742 0.1992 -0.1058 +vn 0.9996 -0.0141 0.0225 +vn 0.9964 -0.0378 0.0765 +vn 0.9955 0.0429 0.0841 +vn 0.9942 0.0826 0.0682 +vn -0.0483 0.6866 0.7254 +vn -0.0532 0.6710 0.7396 +vn -0.0542 0.6677 0.7425 +vn -0.0473 0.6898 0.7224 +vn -0.0001 -0.7312 0.6822 +vn 0.0000 -0.7314 0.6820 +vn -0.0127 -0.6780 0.7349 +vn -0.0001 -0.7311 0.6823 +vn -0.0114 -0.6836 0.7297 +vn -0.0617 -0.7607 0.6461 +vn -0.1463 -0.7939 0.5902 +vn -0.0893 -0.7725 0.6287 +vn -0.6037 -0.5069 0.6153 +vn -0.7539 -0.4297 0.4970 +vn -0.7334 -0.4425 0.5161 +vn -0.9983 0.0249 0.0522 +vn -0.5834 -0.5149 0.6281 +vn -0.0073 -0.7606 0.6492 +vn 0.0390 -0.7526 0.6573 +vn -0.0788 -0.7607 0.6443 +vn 0.0727 -0.7366 0.6724 +vn 0.0773 -0.7291 0.6800 +vn 0.0034 -0.7369 0.6760 +vn 0.0045 -0.7385 0.6742 +vn -0.0129 0.7501 -0.6612 +vn 0.0001 0.7306 -0.6828 +vn 0.0704 0.7774 -0.6250 +vn 0.0659 0.8018 -0.5940 +vn -0.0964 0.7321 -0.6744 +vn 0.0000 0.7303 -0.6831 +vn -0.0773 -0.3350 0.9390 +vn 0.0746 0.6809 0.7286 +vn 0.0898 0.6750 0.7324 +vn 0.0800 0.6777 0.7310 +vn 0.0955 0.6856 0.7217 +vn 0.1051 0.6765 0.7289 +vn 0.0891 0.6798 0.7280 +vn 0.0720 0.6802 0.7295 +vn 0.0720 0.6801 0.7295 +vn 0.0709 0.6805 0.7293 +vn 0.0718 0.6802 0.7295 +vn 0.0715 0.6803 0.7295 +vn 0.0717 0.6802 0.7295 +vn 0.0719 0.6802 0.7295 +vn 0.0273 -0.7226 0.6908 +vn -0.1084 -0.6974 0.7085 +vn 0.0285 -0.7194 0.6940 +vn -0.0966 -0.6943 0.7132 +vn -0.0740 -0.6805 -0.7290 +vn -0.0718 -0.6802 -0.7295 +vn -0.0721 -0.6802 -0.7294 +vn -0.0764 -0.6792 -0.7300 +vn -0.1041 -0.6719 -0.7333 +vn -0.0967 -0.6740 -0.7323 +vn -0.1566 -0.6552 -0.7391 +vn -0.0717 -0.6802 -0.7295 +vn -0.0719 -0.6801 -0.7296 +vn -0.0719 -0.6802 -0.7295 +vn -0.0716 -0.6803 -0.7295 +vn 0.0001 -0.7313 0.6820 +vn -0.0003 -0.7314 0.6819 +vn -0.1472 -0.7139 0.6846 +vn -0.0912 -0.7243 0.6835 +vn -0.0003 -0.7315 0.6818 +vn 0.7096 -0.4747 -0.5207 +vn 0.7928 -0.3850 -0.4725 +vn 0.8123 -0.3604 -0.4585 +vn 0.9496 0.1822 0.2552 +vn 0.8313 0.3870 0.3990 +vn 0.9351 0.2170 0.2803 +vn 0.8002 0.4242 0.4240 +vn 0.0002 0.7312 -0.6822 +vn 0.0002 0.7311 -0.6823 +vn 0.0002 0.7312 -0.6821 +vn -0.1035 0.6718 -0.7334 +vn -0.1171 0.6780 -0.7257 +vn -0.0832 0.7695 -0.6333 +vn -0.0716 0.7755 -0.6273 +vn 0.0447 0.7495 -0.6604 +vn 0.0507 0.7630 -0.6444 +vn -0.6349 -0.5571 -0.5353 +vn -0.9681 -0.1130 -0.2237 +vn -0.9968 0.0390 0.0703 +vn -0.9867 -0.0725 -0.1453 +vn -0.9823 0.0881 0.1654 +vn -0.1947 0.7042 0.6828 +vn -0.2262 0.6925 0.6851 +vn -0.3260 0.6494 0.6870 +vn -0.3494 0.6379 0.6863 +vn 0.6804 -0.5017 -0.5342 +vn 0.9919 -0.0839 -0.0953 +vn 0.9925 -0.0812 -0.0917 +vn 0.9980 -0.0449 -0.0435 +vn 0.9983 -0.0420 -0.0397 +vn -0.9577 0.2806 0.0632 +vn -0.9621 0.2665 0.0574 +vn -0.9671 0.2493 0.0504 +vn -0.9702 0.2381 0.0459 +vn 0.1496 0.6101 -0.7781 +vn 0.4488 0.8458 -0.2885 +vn 0.8486 -0.4989 -0.1761 +vn 0.3929 -0.1600 0.9056 +vn -0.1713 -0.8540 0.4913 +vn -0.4291 0.7229 -0.5416 +vn -0.3976 0.6661 -0.6310 +vn -0.4625 0.7842 -0.4137 +vn -0.4848 0.8261 -0.2873 +vn 0.6429 0.2394 -0.7275 +vn 0.8523 0.3215 0.4127 +vn 0.6145 -0.7784 0.1282 +vn -0.6512 -0.2325 0.7225 +vn -0.6492 -0.3083 0.6954 +vn -0.6403 -0.4040 0.6533 +vn -0.6316 -0.4590 0.6248 +vn 0.0383 0.7748 0.6310 +vn -0.0298 0.7950 0.6059 +vn 0.0393 0.7745 0.6314 +vn 0.1168 0.7461 0.6556 +vn -0.3736 0.7815 0.4997 +vn -0.1134 0.3991 0.9099 +vn 0.3740 0.5525 0.7449 +vn 0.1136 0.9353 0.3352 +vn -0.0723 0.9562 0.2836 +vn -0.2394 0.8374 0.4914 +vn -0.1561 0.7435 0.6502 +vn -0.2208 0.6057 0.7644 +vn -0.0563 0.4454 0.8935 +vn 0.5442 0.6910 0.4757 +vn 0.1191 0.6723 -0.7306 +vn 0.1632 0.6771 -0.7176 +vn 0.1491 0.6876 -0.7106 +vn 0.1218 0.6696 -0.7327 +vn 0.1388 0.6599 -0.7384 +vn 0.1257 0.6638 -0.7373 +vn 0.0981 0.6788 -0.7278 +vn 0.0980 0.6788 -0.7277 +vn 0.0984 0.6789 -0.7276 +vn 0.0978 0.6787 -0.7279 +vn 0.0980 0.6787 -0.7278 +vn 0.0979 0.6787 -0.7278 +vn 0.0980 0.6787 -0.7279 +vn 0.0275 0.7390 0.6731 +vn 0.0984 0.8706 0.4821 +vn 0.0397 0.7645 0.6434 +vn 0.1147 0.8948 0.4314 +vn -0.0980 -0.6787 0.7278 +vn -0.1281 -0.6820 0.7201 +vn -0.0979 -0.6787 0.7278 +vn -0.1333 -0.6765 0.7243 +vn -0.1149 -0.6749 0.7289 +vn -0.1603 -0.6809 0.7146 +vn -0.1803 -0.6794 0.7112 +vn -0.0978 -0.6788 0.7278 +vn -0.0980 -0.6788 0.7278 +vn -0.0978 -0.6786 0.7280 +vn -0.0977 -0.6787 0.7279 +vn -0.0980 -0.6786 0.7279 +vn -0.0974 -0.6786 0.7280 +vn -0.0979 -0.6784 0.7281 +vn -0.6074 0.5086 0.6102 +vn -0.1056 0.2900 0.9512 +vn -0.1411 0.7362 0.6619 +vn -0.1813 0.7348 0.6536 +vn -0.0563 0.7351 0.6756 +vn 0.0002 0.7313 0.6820 +vn 0.0001 0.7313 0.6821 +vn 0.9429 -0.2860 0.1710 +vn 0.9570 0.2308 -0.1755 +vn -0.0006 -0.7311 -0.6823 +vn -0.0003 -0.7308 -0.6825 +vn -0.0006 -0.7312 -0.6822 +vn -0.1055 -0.7764 -0.6214 +vn -0.1188 -0.7688 -0.6284 +vn -0.0813 -0.6838 -0.7251 +vn -0.0697 -0.6785 -0.7313 +vn 0.0454 -0.7118 -0.7009 +vn 0.0519 -0.6969 -0.7153 +vn -0.9738 -0.1568 0.1645 +vn -0.9660 -0.1680 0.1967 +vn -0.9689 -0.1640 0.1852 +vn -0.9764 -0.1527 0.1528 +vn -0.3547 0.6434 -0.6784 +vn -0.3488 0.6437 -0.6812 +vn -0.3301 0.6443 -0.6899 +vn -0.3248 0.6444 -0.6923 +vn 0.6610 -0.4968 0.5625 +vn 0.9883 -0.1067 0.1090 +vn 0.9890 -0.1034 0.1061 +vn 0.9961 -0.0577 0.0665 +vn 0.9965 -0.0542 0.0634 +vn -0.2052 -0.0990 -0.9737 +vn 0.4439 -0.8905 0.0998 +vn 0.8941 0.3703 -0.2520 +vn 0.1792 0.2782 0.9437 +vn -0.4015 0.9149 0.0420 +vn -0.8660 -0.3805 0.3243 +vn -0.8699 0.1292 -0.4760 +vn -0.5581 -0.7808 -0.2808 +vn 0.3319 -0.3918 -0.8581 +vn 0.6921 -0.7031 -0.1631 +vn 0.8300 0.5229 0.1941 +vn 0.6184 0.3816 0.6870 +vn -0.6096 0.6022 0.5156 +vn -0.4956 0.7422 0.4512 +vn -0.6928 0.4578 0.5572 +vn -0.7515 0.3123 0.5811 +vn 0.0001 0.6820 -0.7314 +vn 0.0000 0.6816 -0.7318 +vn -0.5319 -0.3735 0.7600 +vn 0.7826 0.2809 0.5556 +vn 0.5116 -0.8356 0.2000 +vn 0.7361 -0.0999 -0.6694 +vn -0.0612 0.5776 0.8140 +vn -0.0031 0.7441 0.6680 +vn -0.0651 0.7173 0.6937 +vn -0.0851 0.6540 0.7517 +vn -0.0373 -0.7234 -0.6894 +vn -0.0490 -0.7268 -0.6851 +vn -0.0001 -0.7313 -0.6821 +vn -0.0431 -0.7014 -0.7114 +vn 0.0001 0.7314 0.6819 +vn 0.2547 0.8919 -0.3736 +vn -0.1177 0.2581 0.9589 +vn -0.3612 -0.6467 0.6718 +vn -0.3556 -0.6376 0.6833 +vn -0.1004 -0.6788 0.7274 +vn -0.9978 0.0537 -0.0396 +vn -0.9991 0.0312 0.0286 +vn -0.9992 0.0396 0.0032 +vn -0.9958 0.0627 -0.0672 +vn 0.0888 0.6786 -0.7291 +vn 0.0850 0.6786 -0.7295 +vn 0.1586 0.6766 -0.7191 +vn 0.1624 0.6763 -0.7185 +vn 0.3291 0.6652 -0.6703 +vn 0.2043 0.7054 -0.6788 +vn 0.3667 0.6463 -0.6692 +vn 0.4663 0.6437 -0.6069 +vn 0.4645 0.6508 -0.6006 +vn -0.0409 0.7306 0.6816 +vn -0.0315 0.7659 0.6422 +vn -0.0205 0.7373 0.6753 +vn -0.0196 0.7779 0.6280 +vn 0.9123 -0.3653 0.1853 +vn 0.9067 -0.3252 0.2687 +vn 0.8578 -0.2118 0.4683 +vn 0.8275 -0.1665 0.5362 +vn -0.5458 -0.6713 0.5015 +vn -0.5389 -0.6880 0.4860 +vn -0.1306 -0.7593 -0.6375 +vn -0.0447 -0.7379 -0.6735 +vn -0.1403 -0.7682 -0.6246 +vn -0.0667 -0.7332 -0.6768 +vn 0.0000 -0.7313 -0.6820 +vn 0.0000 0.7314 0.6820 +vn 0.9945 -0.0715 0.0767 +vn 0.9944 -0.0724 0.0770 +vn 0.9943 -0.0734 0.0773 +vn 0.9942 -0.0743 0.0776 +vn 0.0007 -0.7314 -0.6819 +vn -0.0947 -0.6785 0.7285 +vn -0.0943 -0.6789 0.7281 +vn -0.0947 -0.6786 0.7284 +vn -0.0952 -0.6781 0.7288 +vn 0.0168 -0.7331 -0.6800 +vn 0.0152 -0.7355 -0.6774 +vn 0.0156 -0.7349 -0.6780 +vn 0.1241 0.6771 -0.7254 +vn 0.1243 0.6769 -0.7255 +vn 0.1245 0.6767 -0.7256 +vn -0.9988 0.0340 -0.0365 +vn -0.9957 0.0766 -0.0522 +vn -0.9977 0.0525 -0.0433 +vn -0.9938 0.0944 -0.0588 +vn 0.7276 -0.5047 0.4646 +vn -0.4093 0.6156 -0.6734 +vn -0.4159 0.6133 -0.6715 +vn 0.0023 0.6900 -0.7238 +vn 0.0580 0.6907 -0.7208 +vn 0.0218 0.7376 0.6749 +vn 0.0180 0.7319 0.6811 +vn 0.0168 0.7301 0.6832 +vn 0.0232 0.7396 0.6727 +vn 0.0171 -0.7325 -0.6806 +vn -0.9947 0.0703 -0.0754 +vn -0.9985 -0.0215 0.0513 +vn 0.0117 -0.7124 0.7017 +vn 0.0187 -0.6071 0.7944 +vn 0.0120 -0.7091 0.7050 +vn 0.0190 -0.6036 0.7970 +vn 0.9932 -0.1145 -0.0205 +vn 0.9979 0.0087 0.0637 +vn 0.9947 -0.1022 -0.0121 +vn 0.9972 0.0215 0.0723 +vn 0.0452 0.6366 -0.7698 +vn -0.6986 0.4546 -0.5526 +vn -0.1522 0.7114 0.6861 +vn -0.2324 0.6129 0.7552 +vn -0.3024 0.7094 0.6367 +vn -0.2175 0.7885 0.5754 +vn -0.2490 0.2805 0.9270 +vn 0.0527 0.7821 0.6209 +vn -0.1191 0.9491 0.2916 +vn -0.9173 0.2627 -0.2992 +vn -0.8266 0.3828 -0.4125 +vn -0.9137 0.2688 -0.3049 +vn -0.8225 0.3872 -0.4166 +vn 0.0821 0.6429 -0.7616 +vn 0.1076 0.7146 -0.6912 +vn 0.0219 0.6820 -0.7310 +vn 0.0101 0.6827 -0.7306 +vn 0.0658 0.6787 -0.7314 +vn 0.2414 0.6704 -0.7017 +vn 0.2077 0.6631 -0.7192 +vn 0.3687 0.6471 -0.6673 +vn 0.4966 0.5908 -0.6359 +vn 0.3631 0.6348 -0.6820 +vn -0.0966 -0.7581 -0.6450 +vn -0.0928 -0.7536 -0.6508 +vn -0.0675 -0.7224 -0.6882 +vn -0.0655 -0.7197 -0.6912 +vn 0.7801 -0.3447 -0.5221 +vn 0.8033 -0.3507 -0.4814 +vn 0.7712 -0.3423 -0.5368 +vn -0.9513 -0.2915 -0.1002 +vn -0.5713 -0.3961 -0.7188 +vn 0.7505 -0.3367 -0.5687 +vn 0.1341 -0.8448 -0.5180 +vn -0.9988 -0.0132 0.0474 +vn 0.0191 -0.6032 0.7973 +vn 0.0120 -0.7107 0.7034 +vn 0.0189 -0.6068 0.7947 +vn 0.0117 -0.7140 0.7001 +vn 0.8101 0.3899 -0.4379 +vn -0.1983 0.9494 -0.2434 +vn -0.6951 0.4014 -0.5963 +vn 0.0325 0.3812 -0.9239 +vn -0.0188 0.6041 -0.7967 +vn 0.0243 0.4190 -0.9076 +vn -0.0261 0.6327 -0.7739 +vn 0.9971 0.0215 0.0723 +vn 0.9947 -0.1022 -0.0120 +vn 0.9979 0.0088 0.0637 +vn 0.9932 -0.1144 -0.0204 +vn -0.0797 -0.8478 -0.5243 +vn -0.0048 -0.7307 -0.6827 +vn -0.0010 -0.6731 -0.7396 +vn -0.0036 0.7372 0.6756 +vn 0.0165 -0.9642 0.2646 +vn 0.0120 -0.9568 0.2905 +vn 0.0671 -0.8136 0.5776 +vn 0.0424 -0.7227 0.6899 +vn 0.0688 -0.5481 0.8336 +vn 0.0587 -0.6297 0.7746 +vn -0.0237 -0.4000 0.9162 +vn -0.0242 -0.3971 0.9175 +vn 0.0000 -0.7314 -0.6820 +vn 0.0001 -0.7313 -0.6820 +vn -0.1078 -0.9029 -0.4162 +vn 0.0428 0.7853 0.6177 +vn 0.0953 0.8422 0.5306 +vn -0.0001 0.7314 0.6820 +vn 0.1288 0.8733 0.4699 +vn 0.9279 0.2360 -0.2885 +vn 0.0194 0.6683 -0.7437 +vn 0.0260 0.6875 -0.7257 +vn 0.1113 0.7269 -0.6777 +vn 0.0683 0.5435 -0.8366 +vn -0.0185 0.4225 -0.9062 +vn 0.0754 0.8791 -0.4706 +vn -0.0975 -0.7759 -0.6233 +vn -0.0674 -0.7633 -0.6425 +vn 0.0408 -0.6741 -0.7375 +vn 0.1223 -0.5420 -0.8314 +vn 0.0903 -0.5969 -0.7972 +vn -0.0000 -0.7313 -0.6821 +vn -0.1593 -0.7983 -0.5807 +vn -0.0221 -0.6814 0.7316 +vn -0.0040 -0.6819 0.7314 +vn -0.2418 -0.6635 0.7081 +vn -0.2449 -0.6617 0.7086 +vn -0.3467 -0.6418 0.6840 +vn -0.3541 -0.6376 0.6842 +vn 0.8197 0.3463 0.4562 +vn 0.7952 0.3399 0.5022 +vn 0.8282 0.3484 0.4390 +vn 0.8517 0.3539 0.3865 +vn 0.3358 -0.8392 -0.4278 +vn 0.2457 -0.4275 -0.8700 +vn 0.2092 0.9251 0.3170 +vn 0.1487 0.4991 0.8537 +vn 0.3567 0.5410 0.7616 +vn 0.1589 0.5017 0.8503 +vn -0.0546 0.4352 0.8987 +vn -0.3740 0.7459 0.5512 +vn -0.0541 0.6939 -0.7180 +vn -0.0483 0.6758 -0.7355 +vn -0.0531 0.6908 -0.7211 +vn -0.0473 0.6727 -0.7384 +vn -0.0113 0.7757 0.6310 +vn -0.0773 0.9602 0.2683 +vn -0.0189 0.7859 0.6181 +vn -0.0186 -0.7104 -0.7035 +vn -0.0005 -0.7017 -0.7125 +vn -0.0036 -0.7093 -0.7049 +vn 0.0658 -0.6485 -0.7584 +vn -0.0965 -0.7238 -0.6833 +vn 0.0591 -0.6868 -0.7244 +vn -0.0263 0.7727 0.6343 +vn -0.0344 0.7846 0.6190 +vn -0.0002 -0.6820 0.7314 +vn 0.0000 -0.6820 0.7313 +vn -0.0001 -0.6820 0.7313 +vn 0.2091 0.6601 0.7215 +vn 0.0461 0.7140 0.6987 +vn 0.1001 0.6823 0.7242 +vn 0.0570 0.7301 0.6810 +vn 0.4091 0.6235 0.6663 +vn -0.2086 0.7868 0.5809 +vn -0.9972 0.0625 -0.0410 +vn -0.7010 0.5420 0.4635 +vn -0.1392 0.6489 0.7480 +vn -0.0001 0.7313 0.6820 +vn -0.0981 0.6756 0.7307 +vn -0.2256 0.5862 0.7781 +vn 0.0000 0.7313 0.6820 +vn -0.0386 0.7903 0.6115 +vn -0.0471 0.6720 -0.7390 +vn -0.0532 0.6910 -0.7209 +vn -0.0481 0.6753 -0.7360 +vn -0.0542 0.6942 -0.7177 +vn 0.9942 0.0622 -0.0872 +vn 0.9955 0.0809 -0.0487 +vn 0.9964 0.0789 0.0324 +vn 0.9996 0.0234 0.0124 +vn 0.9742 -0.1195 -0.1914 +vn 0.9996 -0.0118 -0.0261 +vn 0.9975 -0.0030 -0.0699 +vn 0.9990 0.0198 -0.0407 +vn -0.9373 0.2530 -0.2397 +vn -0.8954 -0.3329 -0.2958 +vn -0.5537 -0.5129 -0.6560 +vn 0.4934 -0.6966 -0.5209 +vn 0.1640 -0.8142 -0.5569 +vn 0.2635 -0.7759 -0.5732 +vn 0.0049 -0.7314 -0.6820 +vn 0.0255 -0.7607 -0.6486 +vn -0.0024 0.9776 0.2106 +vn -0.0100 0.9780 0.2085 +vn -0.0066 0.9774 0.2115 +vn 0.0008 0.9791 0.2036 +vn -0.0044 0.9781 0.2082 +vn 0.0056 0.9805 0.1963 +vn 0.0032 0.9782 0.2077 +vn 0.0030 0.9768 0.2140 +vn 0.0054 -0.9782 -0.2074 +vn -0.0596 -0.9474 -0.3144 +vn 0.0820 -0.9816 -0.1726 +vn -0.0929 -0.9457 -0.3114 +vn 0.6743 -0.1670 0.7193 +vn 0.4171 -0.3303 0.8467 +vn 0.5597 -0.2480 0.7907 +vn 0.7763 -0.0778 0.6255 +vn 0.9400 -0.1176 -0.3203 +vn 0.6224 0.2349 -0.7466 +vn 0.4202 0.1888 -0.8876 +vn 0.5439 0.2178 -0.8104 +vn 0.2586 0.1484 -0.9545 +vn -0.7943 0.2024 -0.5728 +vn -0.8308 0.1463 -0.5369 +vn -0.8172 0.1683 -0.5513 +vn -0.8539 0.1058 -0.5095 +vn -0.8347 -0.2679 0.4811 +vn -0.5086 -0.1104 0.8539 +vn 0.5992 -0.7688 0.2236 +vn 0.5148 -0.8208 0.2475 +vn 0.6030 -0.7661 0.2224 +vn 0.6784 -0.7078 0.1970 +vn 0.7539 -0.5053 -0.4198 +vn 0.5957 -0.5995 -0.5346 +vn 0.5738 -0.6094 -0.5472 +vn 0.3865 -0.6711 -0.6326 +vn 0.0096 -0.3332 -0.9428 +vn -0.5958 -0.6272 -0.5016 +vn -0.5146 -0.6666 -0.5393 +vn -0.6158 -0.6161 -0.4911 +vn -0.6872 -0.5710 -0.4491 +vn -0.7091 -0.6422 0.2910 +vn -0.5440 -0.7699 0.3337 +vn -0.5157 -0.7868 0.3390 +vn -0.3202 -0.8746 0.3642 +vn 0.0662 -0.7208 0.6900 +vn -0.1972 -0.8428 -0.5007 +vn -0.0090 0.9779 0.2088 +vn -0.0036 0.9772 0.2125 +vn -0.0022 0.9776 0.2105 +vn 0.0074 0.9790 0.2039 +vn -0.0015 0.9790 0.2037 +vn 0.0116 0.9801 0.1982 +vn 0.0062 0.9772 0.2122 +vn 0.0133 0.9782 0.2073 +vn 0.0298 -0.9677 -0.2502 +vn 0.0299 -0.9677 -0.2503 +vn 0.0426 -0.9663 -0.2540 +vn 0.0148 -0.9692 -0.2458 +vn 0.5335 -0.1478 0.8328 +vn 0.8686 -0.2874 0.4036 +vn 0.9488 0.1538 -0.2760 +vn 0.3712 0.0042 -0.9285 +vn -0.3911 0.3394 -0.8555 +vn -0.8834 -0.0953 -0.4588 +vn -0.7000 -0.1925 0.6877 +vn -0.5502 -0.0597 0.8329 +vn -0.6544 -0.1491 0.7413 +vn -0.7654 -0.2619 0.5879 +vn -0.0377 -0.7066 0.7066 +vn 0.5791 -0.7582 0.2996 +vn 0.3445 -0.8628 0.3700 +vn 0.5829 -0.7559 0.2982 +vn 0.7517 -0.6217 0.2201 +vn 0.6438 -0.6201 -0.4484 +vn 0.6278 -0.6947 -0.3511 +vn 0.6445 -0.6148 -0.4546 +vn 0.6499 -0.5343 -0.5404 +vn 0.0619 -0.4361 -0.8978 +vn -0.0808 -0.5617 -0.8234 +vn -0.1076 -0.5831 -0.8053 +vn -0.2334 -0.6726 -0.7022 +vn -0.6949 -0.4538 -0.5578 +vn -0.7099 -0.6808 0.1803 +vn -0.6207 -0.7562 0.2072 +vn -0.5952 -0.7746 0.2140 +vn -0.4929 -0.8370 0.2375 +vn -0.0015 0.9800 0.1991 +vn 0.0035 0.9790 0.2038 +vn -0.0026 0.9814 0.1921 +vn 0.0027 0.9767 0.2144 +vn 0.0091 0.9768 0.2139 +vn 0.0043 0.9773 0.2118 +vn -0.0017 0.9788 0.2047 +vn -0.0114 -0.9631 -0.2688 +vn -0.0464 -0.9669 -0.2511 +vn -0.0140 -0.9635 -0.2675 +vn 0.0250 -0.9577 -0.2867 +vn -0.8782 0.0335 -0.4771 +vn -0.9258 0.1014 -0.3641 +vn -0.8944 0.0541 -0.4439 +vn -0.8376 -0.0114 -0.5461 +vn -0.5121 -0.1097 0.8519 +vn -0.3178 -0.2685 0.9094 +vn -0.3922 -0.2118 0.8952 +vn -0.1754 -0.3652 0.9143 +vn 0.9035 -0.1122 0.4137 +vn 0.9166 -0.0829 0.3912 +vn 0.9089 -0.1004 0.4047 +vn 0.8960 -0.1277 0.4254 +vn 0.5406 0.1936 -0.8187 +vn 0.4360 0.1261 -0.8911 +vn 0.4751 0.1510 -0.8669 +vn 0.3628 0.0806 -0.9284 +vn -0.4381 -0.4104 -0.7998 +vn -0.4929 -0.5370 -0.6847 +vn -0.6399 -0.5956 -0.4856 +vn -0.7006 -0.6426 -0.3101 +vn -0.8127 -0.5705 -0.1180 +vn -0.3417 -0.8061 0.4831 +vn -0.3579 -0.8285 0.4307 +vn -0.3349 -0.7964 0.5036 +vn -0.3214 -0.7765 0.5419 +vn 0.6399 -0.6402 0.4250 +vn 0.6356 -0.6939 0.3384 +vn 0.6280 -0.7295 0.2710 +vn 0.6027 -0.7863 0.1356 +vn 0.5982 -0.3956 -0.6969 +vn 0.5389 -0.4503 -0.7119 +vn 0.4871 -0.4933 -0.7207 +vn 0.3833 -0.5682 -0.7282 +vn -0.8947 -0.4135 -0.1691 +vn -0.9369 0.1730 0.3038 +vn -0.3830 -0.4613 0.8003 +vn -0.0357 0.2688 0.9625 +vn 0.6055 -0.5750 0.5503 +vn 0.8997 0.3758 0.2219 +vn 0.9396 -0.2128 -0.2682 +vn 0.4343 0.4973 -0.7511 +vn 0.0492 -0.3275 -0.9436 +vn -0.5989 0.6178 -0.5095 +vn -0.0000 0.9781 0.2081 +vn -0.0001 0.9782 0.2078 +vn 0.0000 0.9782 0.2077 +vn 0.0002 0.9782 0.2078 +vn -0.0000 0.9781 0.2080 +vn 0.0000 0.9782 0.2078 +vn 0.0001 0.9782 0.2077 +vn -0.6895 0.3701 -0.6226 +vn 0.2606 0.1058 -0.9596 +vn 0.2272 0.1442 -0.9631 +vn 0.2625 0.1036 -0.9594 +vn 0.2824 0.0802 -0.9560 +vn 0.7672 0.2462 -0.5923 +vn 0.9878 -0.1492 0.0455 +vn 0.9985 0.0251 -0.0490 +vn 0.9818 -0.1794 0.0621 +vn 0.9427 -0.3063 0.1320 +vn 0.6128 0.0714 0.7870 +vn 0.6204 0.2845 0.7309 +vn 0.3613 0.5325 0.7654 +vn -0.2278 -0.2975 0.9271 +vn -0.1212 -0.2034 0.9716 +vn -0.2165 -0.2876 0.9330 +vn -0.2810 -0.3436 0.8961 +vn -0.7092 -0.0457 0.7035 +vn -0.9794 0.0165 -0.2012 +vn -0.9846 -0.0605 -0.1641 +vn -0.9843 -0.0497 -0.1694 +vn -0.9800 -0.1651 -0.1113 +vn 0.4161 0.8605 0.2941 +vn 0.8541 0.4895 0.1758 +vn -0.4144 0.8256 -0.3829 +vn 0.5354 0.8260 -0.1763 +vn 0.3294 0.8934 -0.3055 +vn 0.0912 0.8524 -0.5148 +vn 0.2211 0.9584 -0.1806 +vn -0.1320 0.8853 0.4459 +vn -0.2661 0.7099 0.6521 +vn -0.4758 0.7971 0.3717 +vn -0.4768 0.8548 0.2048 +vn -0.4464 0.8797 0.1636 +vn -0.5000 -0.5860 0.6377 +vn -0.1994 0.2189 0.9552 +vn 0.5777 -0.5043 0.6418 +vn 0.8357 0.1571 0.5263 +vn 0.9536 -0.2072 -0.2184 +vn 0.8546 0.3844 -0.3493 +vn 0.1394 -0.2078 -0.9682 +vn -0.2234 0.5924 -0.7740 +vn -0.8067 -0.3221 -0.4955 +vn -0.8932 0.4470 0.0491 +vn 0.0003 0.9782 0.2078 +vn 0.0004 0.9782 0.2076 +vn 0.0004 0.9783 0.2071 +vn -0.0005 0.9782 0.2076 +vn -0.0002 0.9781 0.2080 +vn 0.0001 0.9781 0.2079 +vn -0.0001 0.9782 0.2076 +vn -0.0000 0.9782 0.2076 +vn -0.9603 0.1950 -0.1996 +vn -0.6235 -0.0102 -0.7818 +vn -0.5645 0.0833 -0.8212 +vn -0.5551 0.0970 -0.8261 +vn -0.4473 0.2383 -0.8621 +vn 0.5328 0.5757 -0.6202 +vn 0.3874 0.3870 -0.8368 +vn 0.1760 0.7146 -0.6770 +vn 0.8420 -0.2852 -0.4578 +vn 0.8856 -0.2226 -0.4077 +vn 0.9016 -0.1958 -0.3857 +vn 0.9486 -0.0966 -0.3015 +vn 0.8103 0.1529 0.5656 +vn 0.7454 0.4852 0.4571 +vn 0.7621 0.2921 0.5779 +vn 0.1200 -0.3071 0.9441 +vn 0.1807 -0.2152 0.9597 +vn 0.1011 -0.3345 0.9369 +vn 0.0093 -0.4600 0.8879 +vn -0.8753 -0.1032 0.4725 +vn -0.8260 -0.0481 0.5617 +vn -0.8746 -0.1023 0.4740 +vn -0.9062 -0.1462 0.3967 +vn 0.3974 0.8482 0.3503 +vn 0.0804 0.4804 0.8734 +vn 0.0602 0.4572 0.8873 +vn -0.0001 0.3856 0.9227 +vn 0.4888 0.7389 -0.4638 +vn 0.7752 0.5588 -0.2947 +vn -0.1013 0.8531 -0.5118 +vn 0.1437 0.5499 0.8228 +vn -0.6274 0.4978 0.5988 +vn -0.4266 0.8077 0.4070 +vn -0.6204 0.7327 0.2797 +vn -0.3169 0.9329 0.1710 +vn -0.6540 0.7565 -0.0032 +vn -0.3259 0.7706 -0.5477 +vn 0.3694 0.9183 0.1425 +vn 0.2817 0.9030 0.3244 +vn 0.0550 0.9960 0.0704 +vn -0.1221 0.9089 0.3986 +vn 0.0000 0.9773 0.2119 +vn -0.0028 0.9471 0.3208 +vn -0.0046 0.9298 0.3681 +vn 0.0007 0.9778 0.2095 +vn -0.0012 0.9780 0.2085 +vn 0.1128 0.9714 0.2091 +vn 0.0038 0.9777 0.2102 +vn 0.0704 0.9755 0.2086 +vn -0.0078 0.9778 0.2096 +vn -0.0018 0.9782 0.2078 +vn -0.0172 0.9774 0.2108 +vn -0.0005 0.9783 0.2071 +vn -0.0481 0.9774 0.2060 +vn 0.0023 0.9774 0.2114 +vn -0.0002 0.9791 0.2034 +vn 0.0020 0.9904 0.1383 +vn -0.0719 0.9762 0.2046 +vn 0.0000 -0.9781 -0.2079 +vn 0.0001 -0.9781 -0.2081 +vn 0.0001 -0.9781 -0.2080 +vn 0.0000 -0.9782 -0.2079 +vn 0.0039 0.9949 0.1004 +vn -0.0001 -0.9782 -0.2077 +vn -0.0000 -0.9781 -0.2080 +vn -0.0000 -0.9782 -0.2078 +vn -0.0000 -0.9782 -0.2076 +vn -0.8217 -0.3470 0.4522 +vn -0.6811 0.0990 0.7255 +vn -0.0125 -0.0208 0.9997 +vn 0.0124 -0.0845 0.9963 +vn 0.0573 -0.1987 0.9784 +vn 0.0818 -0.2607 0.9620 +vn 0.9143 -0.1333 0.3824 +vn 0.8844 -0.2512 0.3933 +vn 0.9296 0.1597 0.3320 +vn 0.9174 0.2498 0.3099 +vn 0.6424 -0.1204 -0.7569 +vn 0.6445 -0.1572 -0.7483 +vn 0.6322 -0.0211 -0.7745 +vn 0.6152 0.0798 -0.7843 +vn -0.0685 0.7007 -0.7101 +vn -0.6329 -0.3671 -0.6817 +vn -0.9110 0.3307 -0.2463 +vn -0.0002 0.9782 0.2077 +vn -0.0001 0.9782 0.2079 +vn -0.0002 0.9781 0.2082 +vn -0.0001 0.9782 0.2077 +vn 0.0003 0.9781 0.2081 +vn 0.0001 0.9781 0.2082 +vn -0.0003 0.9781 0.2083 +vn -0.5288 0.1130 -0.8412 +vn -0.5247 0.1220 -0.8425 +vn -0.5232 0.1254 -0.8430 +vn -0.5169 0.1390 -0.8447 +vn 0.7571 0.5851 -0.2906 +vn 0.2737 0.2086 -0.9389 +vn 0.9087 0.1854 -0.3740 +vn 0.9324 0.0379 -0.3595 +vn 0.8310 0.3357 -0.4435 +vn 0.9635 -0.0907 -0.2517 +vn 0.9555 0.0652 0.2876 +vn 0.5003 -0.2230 0.8366 +vn 0.5120 -0.2403 0.8247 +vn 0.5183 -0.2498 0.8179 +vn 0.5467 -0.2939 0.7840 +vn -0.7804 0.4652 0.4178 +vn -0.5078 0.1085 0.8546 +vn -0.5234 -0.0201 0.8518 +vn -0.4734 0.1771 0.8628 +vn -0.9662 -0.1649 0.1981 +vn -0.9900 0.0872 0.1110 +vn -0.9943 -0.0139 0.1053 +vn -0.8564 0.5013 -0.1236 +vn 0.3785 0.2298 0.8966 +vn -0.4640 0.2511 0.8495 +vn -0.8634 0.5031 0.0392 +vn -0.4076 0.3273 0.8525 +vn -0.5640 0.7429 -0.3606 +vn -0.4853 0.6667 -0.5656 +vn 0.3380 0.7046 -0.6240 +vn 0.2460 0.7916 -0.5593 +vn 0.2690 0.7717 -0.5763 +vn 0.7673 0.5185 -0.3773 +vn -0.6661 0.7431 -0.0647 +vn 0.7056 0.6910 0.1572 +vn 0.6716 0.7185 0.1810 +vn 0.5768 0.7358 0.3548 +vn 0.0656 0.8135 0.5779 +vn 0.1766 0.8445 -0.5057 +vn -0.2599 0.7685 0.5847 +vn 0.1436 0.9896 0.0022 +vn 1.0000 -0.0068 0.0052 +vn 0.9995 -0.0296 -0.0079 +vn 0.9999 -0.0090 0.0050 +vn 0.9995 -0.0321 -0.0080 +vn -1.0000 0.0041 0.0075 +vn -0.9995 0.0302 0.0048 +vn -0.9999 0.0062 0.0083 +vn -0.9995 0.0325 0.0057 +vn -0.0021 -0.2402 0.9707 +vn 0.0020 -0.1781 0.9840 +vn -0.0020 -0.2377 0.9713 +vn 0.0021 -0.1755 0.9845 +vn 0.0011 0.9778 0.2095 +vn 0.0013 0.9779 0.2090 +vn 0.0007 0.9784 0.2067 +vn 0.0014 0.9780 0.2086 +vn -0.0001 0.9781 0.2079 +vn -0.9560 0.2873 0.0589 +vn -0.9582 0.2797 0.0594 +vn -0.9578 0.2813 0.0593 +vn -0.9556 0.2889 0.0588 +vn 0.9127 0.3998 0.0841 +vn 0.9097 0.4053 0.0901 +vn 0.9114 0.4022 0.0867 +vn 0.9144 0.3966 0.0807 +vn 0.0251 0.9771 0.2113 +vn 0.0048 0.9824 0.1867 +vn -0.1178 0.9749 0.1887 +vn -0.1663 0.9685 0.1853 +vn -0.2678 0.9423 0.2011 +vn -0.2653 0.9436 0.1979 +vn 0.0000 0.2078 -0.9782 +vn 0.0000 0.2079 -0.9781 +vn 0.0000 0.2080 -0.9781 +vn 0.0000 0.2081 -0.9781 +vn 0.0000 -0.2079 0.9782 +vn 0.0001 -0.2079 0.9782 +vn 0.0000 -0.2080 0.9781 +vn 0.9993 0.0296 0.0219 +vn 0.9994 0.0277 0.0217 +vn 0.0021 0.1755 -0.9845 +vn -0.0019 0.2377 -0.9713 +vn 0.0019 0.1780 -0.9840 +vn -0.0021 0.2402 -0.9707 +vn -0.9993 -0.0359 0.0080 +vn -0.9994 -0.0341 0.0085 +vn 0.0025 0.9778 0.2096 +vn 0.0012 0.9786 0.2059 +vn 0.0014 0.9784 0.2065 +vn -0.0003 0.9782 0.2076 +vn -0.9555 0.2889 0.0603 +vn -0.9582 0.2797 0.0595 +vn -0.9580 0.2805 0.0595 +vn -0.9552 0.2896 0.0603 +vn 0.9021 0.4226 0.0877 +vn 0.8980 0.4303 0.0920 +vn 0.8989 0.4286 0.0911 +vn 0.9029 0.4209 0.0867 +vn -0.0114 0.9778 0.2091 +vn -0.0253 0.9793 0.2009 +vn -0.1352 0.9683 0.2098 +vn -0.1684 0.9649 0.2016 +vn -0.2717 0.9393 0.2094 +vn -0.2934 0.9350 0.1991 +vn 0.0000 -0.2081 0.9781 +vn 0.0001 -0.2079 0.9781 +vn 0.0014 0.9783 0.2072 +vn 0.0070 0.9774 0.2112 +vn -0.0024 0.9785 0.2061 +vn 0.0031 0.9767 0.2146 +vn -0.0014 0.9778 0.2094 +vn -0.0048 0.9784 0.2068 +vn -0.0076 0.9792 0.2027 +vn -0.0166 -0.9671 -0.2539 +vn 0.0006 -0.9684 -0.2496 +vn -0.0163 -0.9671 -0.2539 +vn -0.0315 -0.9657 -0.2576 +vn -0.2193 0.2523 -0.9425 +vn -0.4172 0.1285 -0.8997 +vn -0.3270 0.1877 -0.9262 +vn -0.5193 0.0549 -0.8528 +vn -0.9985 0.0037 0.0553 +vn -0.9605 -0.1492 0.2349 +vn -0.9837 -0.0843 0.1590 +vn -0.9154 -0.2310 0.3295 +vn 0.0366 -0.1046 0.9938 +vn 0.5253 -0.3783 0.7622 +vn 0.9630 0.1198 -0.2415 +vn 0.8981 0.0528 -0.4367 +vn 0.9274 0.0783 -0.3657 +vn 0.8225 0.0013 -0.5687 +vn -0.3585 -0.5053 -0.7849 +vn -0.1421 -0.6148 -0.7758 +vn -0.4244 -0.4633 -0.7780 +vn -0.5743 -0.3486 -0.7407 +vn -0.6239 -0.7704 -0.1312 +vn -0.7307 -0.5592 0.3916 +vn 0.1421 -0.8379 0.5270 +vn 0.0239 -0.8956 0.4443 +vn 0.1943 -0.8053 0.5602 +vn 0.2970 -0.7272 0.6188 +vn 0.7954 -0.6043 -0.0466 +vn 0.7221 -0.6711 -0.1680 +vn 0.6954 -0.6887 -0.2052 +vn 0.5979 -0.7340 -0.3220 +vn 0.4289 -0.3778 -0.8206 +vn 0.0614 -0.5552 0.8294 +vn 0.0672 -0.5409 0.8384 +vn 0.0575 -0.5648 0.8232 +vn 0.0563 -0.5677 0.8213 +vn -0.0205 0.0788 0.9967 +vn -0.0203 0.0756 0.9969 +vn -0.0174 0.0210 0.9996 +vn -0.0149 -0.0269 0.9995 +vn 0.9960 0.0896 0.0047 +vn 0.9954 0.0955 0.0054 +vn 0.9999 -0.0082 -0.0061 +vn 0.9998 0.0172 0.0130 +vn 0.9385 -0.3428 -0.0423 +vn 0.9356 -0.3504 -0.0435 +vn 0.0082 0.2950 -0.9555 +vn 0.0109 0.3423 -0.9395 +vn 0.0183 0.4680 -0.8836 +vn 0.0185 0.4726 -0.8811 +vn -0.0638 0.0729 -0.9953 +vn -0.0695 0.0411 -0.9967 +vn -0.0796 -0.0166 -0.9967 +vn -0.1377 -0.3850 -0.9126 +vn -0.9959 0.0878 0.0234 +vn -0.6568 -0.7459 -0.1108 +vn -0.9939 0.1083 0.0224 +vn -0.9618 0.2689 0.0513 +vn -0.9221 0.3804 0.0713 +vn -0.9206 0.3837 0.0719 +vn -0.0487 0.6937 0.7186 +vn 0.0213 0.7138 0.7000 +vn -0.1403 0.6613 0.7368 +vn 0.4626 0.6337 0.6200 +vn 0.3856 0.4853 0.7847 +vn 0.4698 0.6484 0.5991 +vn 0.5206 0.7633 0.3826 +vn 0.8187 0.5713 -0.0577 +vn 0.3466 0.8724 -0.3447 +vn -0.0428 0.5512 -0.8333 +vn -0.3609 0.8486 -0.3867 +vn -0.9058 0.3875 0.1711 +vn -0.9347 0.3288 0.1348 +vn -0.8536 0.4707 0.2231 +vn -0.7023 0.6322 0.3272 +vn 0.1067 0.7329 0.6719 +vn 0.1200 0.6188 0.7764 +vn 0.0604 0.5673 0.8213 +vn 0.1330 0.6294 0.7656 +vn 0.1936 0.6763 0.7108 +vn 0.8664 0.2866 0.4089 +vn 0.5406 0.8313 -0.1296 +vn 0.5488 0.7856 -0.2859 +vn 0.5438 0.7268 -0.4196 +vn 0.5248 0.6442 -0.5564 +vn -0.4639 0.7730 -0.4327 +vn -0.5372 0.7108 -0.4541 +vn -0.5993 0.6482 -0.4697 +vn -0.6351 0.6072 -0.4775 +vn -0.5438 0.6811 0.4903 +vn -0.4926 0.7066 0.5079 +vn -0.5489 0.6783 0.4884 +vn -0.6269 0.6317 0.4560 +vn -0.1618 0.9057 -0.3917 +vn -0.2088 0.8842 -0.4179 +vn -0.3873 0.8280 -0.4055 +vn 0.9833 0.1239 0.1331 +vn 0.4571 0.8893 -0.0143 +vn -0.0556 0.9024 -0.4273 +vn -0.1135 0.4352 0.8931 +vn -0.1719 0.3519 0.9201 +vn -0.0357 0.5364 0.8432 +vn 0.0340 0.6178 0.7856 +vn -0.4748 0.7731 -0.4205 +vn -0.5792 0.7989 0.1622 +vn -0.6507 0.7110 0.2666 +vn -0.6590 0.6981 0.2799 +vn -0.7108 0.5966 0.3726 +vn -0.0904 0.8359 -0.5414 +vn -0.1001 0.8434 -0.5278 +vn -0.0865 0.8327 -0.5469 +vn -0.0693 0.8185 -0.5703 +vn 0.5688 0.8206 -0.0560 +vn 0.6018 0.7892 0.1224 +vn 0.5305 0.8469 -0.0360 +vn 0.5493 0.8205 -0.1580 +vn 0.6768 0.7226 -0.1411 +vn 0.0582 -0.0830 0.9949 +vn 0.3309 0.7268 0.6019 +vn -0.6780 0.7232 -0.1318 +vn -0.8250 0.5595 -0.0798 +vn -0.8932 0.4473 -0.0466 +vn -0.9378 0.3466 -0.0179 +vn -0.4221 0.6588 0.6227 +vn -0.7807 -0.1353 0.6101 +vn -0.7753 -0.1159 0.6209 +vn -0.7902 -0.1731 0.5879 +vn -0.7963 -0.2011 0.5705 +vn -0.4497 0.5875 -0.6728 +vn -0.8892 -0.0708 -0.4519 +vn 0.5370 0.3898 0.7482 +vn 0.8081 0.2370 -0.5393 +vn 0.7894 0.1630 -0.5918 +vn 0.7402 0.0299 -0.6717 +vn 0.7131 -0.0274 -0.7005 +vn -0.7549 0.1775 0.6313 +vn -0.6616 0.1306 0.7384 +vn -0.7137 0.1562 0.6828 +vn -0.6146 0.1085 0.7813 +vn 0.8954 0.1486 0.4198 +vn 0.9462 0.0569 0.3185 +vn 0.9222 0.1050 0.3723 +vn 0.9639 0.0113 0.2661 +vn -0.1838 -0.1644 -0.9691 +vn -0.2701 -0.2111 -0.9394 +vn -0.2305 -0.1897 -0.9544 +vn -0.3153 -0.2354 -0.9193 +vn -0.0500 0.9910 -0.1239 +vn 0.0173 0.9822 -0.1872 +vn -0.0146 0.9834 -0.1810 +vn 0.0208 0.9795 -0.2002 +vn 0.3814 0.7849 -0.4883 +vn -0.4238 0.9010 -0.0926 +vn -0.0137 0.9719 -0.2348 +vn -0.1162 0.9125 -0.3922 +vn -0.5258 0.8067 0.2698 +vn -0.7662 0.6370 0.0845 +vn -0.7616 0.3885 0.5187 +vn -0.7207 0.5733 -0.3899 +vn -0.4627 0.7169 -0.5215 +vn 0.2371 0.9210 0.3090 +vn -0.1075 0.5454 0.8312 +vn 0.1509 0.3488 0.9250 +vn -0.1319 0.6056 0.7847 +vn -0.3018 0.5574 0.7735 +vn -0.3295 0.5240 0.7854 +vn -0.2021 0.2933 -0.9344 +vn -0.3688 0.2413 -0.8977 +vn -0.2701 0.2735 -0.9232 +vn -0.1096 0.3175 -0.9419 +vn 0.1737 0.6900 -0.7027 +vn 0.7280 0.4029 -0.5547 +vn 0.6484 0.7052 -0.2867 +vn 0.5490 0.8046 -0.2261 +vn 0.7591 0.5108 0.4037 +vn 0.8349 0.5122 0.2015 +vn 0.7521 0.5394 0.3787 +vn 0.6700 0.4201 0.6121 +vn 0.2097 0.2049 0.9561 +vn -0.7342 -0.5366 0.4159 +vn -0.9018 0.2849 -0.3251 +vn -0.7914 0.1908 -0.5807 +vn -0.6199 -0.3793 -0.6869 +vn 0.2612 -0.5308 -0.8062 +vn 0.4683 -0.0517 -0.8820 +vn 0.9016 0.1860 -0.3905 +vn 0.8295 -0.5534 0.0749 +vn 0.6642 0.3285 0.6716 +vn -0.0511 -0.9641 0.2607 +vn -0.0177 -0.9818 0.1893 +vn -0.0058 -0.9904 0.1383 +vn -0.0317 -0.9650 0.2603 +vn -0.0521 -0.9591 0.2782 +vn 0.0098 -0.9810 0.1936 +vn -0.0003 -0.9780 0.2085 +vn 0.0875 -0.9744 0.2073 +vn 0.0354 -0.9747 0.2207 +vn 0.0218 -0.9802 0.1968 +vn -0.0117 -0.9928 0.1193 +vn 0.8886 0.4543 0.0625 +vn 0.8380 -0.5267 -0.1428 +vn -0.0251 0.1517 -0.9881 +vn -0.4017 -0.4758 -0.7824 +vn -0.9307 0.2785 -0.2372 +vn -0.9046 -0.2615 0.3367 +vn -0.2218 0.4556 0.8621 +vn 0.0839 -0.0774 0.9935 +vn -0.1223 -0.8295 0.5449 +vn -0.1135 -0.9807 0.1590 +vn -0.0163 -0.9758 0.2181 +vn 0.0238 -0.9738 0.2263 +vn 0.0802 -0.9122 0.4018 +vn 0.0468 -0.9820 0.1831 +vn 0.0103 -0.9806 0.1959 +vn -0.1147 -0.9672 -0.2265 +vn 0.7911 -0.3116 0.5263 +vn 0.7974 -0.2662 0.5416 +vn 0.7058 -0.2214 0.6729 +vn 0.8481 -0.5158 0.1211 +vn 0.8133 -0.5815 0.0196 +vn 0.7873 -0.5400 -0.2976 +vn 0.6636 -0.5144 -0.5432 +vn 0.5752 -0.4530 -0.6811 +vn 0.0974 -0.9952 -0.0100 +vn 0.1361 -0.6539 -0.7443 +vn -0.2363 -0.3177 -0.9183 +vn 0.0489 -0.3318 -0.9421 +vn -0.3171 -0.9484 -0.0079 +vn -0.4103 -0.8884 -0.2059 +vn -0.8363 -0.3917 0.3838 +vn -0.8318 -0.3624 0.4204 +vn -0.8841 -0.4316 0.1789 +vn -0.7771 -0.1863 0.6011 +vn -0.7711 -0.2461 0.5873 +vn -0.3068 -0.6722 0.6738 +vn -0.4012 -0.7211 0.5649 +vn 0.0758 -0.7223 0.6874 +vn 0.2486 -0.6126 0.7503 +vn 0.9027 0.4260 0.0601 +vn -0.2833 -0.0890 -0.9549 +vn -0.7225 -0.4592 -0.5169 +vn -0.9123 0.2633 -0.3137 +vn -0.0582 0.1579 0.9857 +vn 0.0570 0.0992 0.9934 +vn -0.2113 0.2605 0.9421 +vn -0.2137 0.2669 0.9397 +vn 0.2506 -0.0162 0.9679 +vn 0.5316 0.3917 0.7509 +vn 0.0514 0.9781 -0.2015 +vn 0.0588 0.9728 -0.2241 +vn 0.0383 0.9743 -0.2220 +vn 0.0140 0.9795 -0.2010 +vn 0.0690 0.9788 -0.1927 +vn -0.0373 0.9759 -0.2151 +vn -0.0361 0.9712 -0.2355 +vn -0.0640 0.9796 -0.1904 +vn -0.0231 0.9790 -0.2027 +vn -0.0830 0.9750 -0.2059 +vn 0.0619 0.9702 -0.2343 +vn 0.0276 0.9758 -0.2169 +vn -0.1595 0.9620 0.2215 +vn 0.0923 0.9819 -0.1654 +vn 0.0457 0.9746 -0.2192 +vn -0.0021 -0.9766 0.2151 +vn -0.0270 -0.9758 0.2169 +vn -0.0022 -0.9766 0.2151 +vn 0.0197 -0.9768 0.2135 +vn -0.7212 0.0590 0.6902 +vn 0.0499 0.3218 0.9455 +vn 0.7555 0.0173 0.6549 +vn 0.7686 -0.0317 -0.6390 +vn 0.6643 -0.1199 -0.7378 +vn 0.7356 -0.0617 -0.6746 +vn 0.6111 -0.1585 -0.7756 +vn -0.9300 -0.0255 -0.3667 +vn -0.7893 -0.1733 -0.5890 +vn -0.8454 -0.1247 -0.5193 +vn -0.9534 0.0145 -0.3014 +vn -0.0814 -0.9694 0.2315 +vn -0.1797 -0.9747 0.1327 +vn -0.0956 -0.9906 0.0976 +vn -0.0505 -0.9637 0.2621 +vn -0.2735 -0.9618 0.0078 +vn -0.0698 -0.9939 0.0858 +vn 0.1582 -0.9508 0.2662 +vn 0.0473 -0.9510 0.3056 +vn 0.1096 -0.9822 0.1528 +vn 0.2346 -0.9259 0.2962 +vn 0.6660 0.5869 -0.4605 +vn 0.8176 0.5302 -0.2247 +vn 0.6434 0.5056 -0.5748 +vn 0.8418 0.5042 -0.1929 +vn 0.4061 0.8168 0.4097 +vn 0.4018 0.8061 0.4346 +vn 0.4031 0.8093 0.4273 +vn 0.3993 0.7998 0.4482 +vn -0.2629 0.7403 0.6188 +vn -0.2195 0.7158 0.6629 +vn -0.4567 0.8542 0.2487 +vn -0.7529 0.5425 0.3725 +vn -0.4059 0.8994 -0.1623 +vn -0.6231 0.6870 -0.3739 +vn -0.6511 0.7534 -0.0923 +vn -0.3852 0.5777 -0.7196 +vn -0.3281 0.4972 -0.8032 +vn -0.0830 0.5546 -0.8280 +vn 0.3659 0.2835 -0.8864 +vn 0.4277 0.3959 -0.8126 +vn 0.0416 0.9514 -0.3052 +vn 0.0211 0.9693 -0.2450 +vn 0.0105 -0.9817 0.1904 +vn 0.0139 -0.9816 0.1906 +vn 0.0077 -0.9817 0.1902 +vn -0.9896 0.1051 0.0982 +vn -0.6530 0.0650 0.7545 +vn 0.0574 0.2611 0.9636 +vn 0.6972 0.0664 0.7138 +vn 0.9957 0.0438 -0.0820 +vn 0.8076 -0.1871 -0.5592 +vn -0.0102 -0.1466 -0.9891 +vn -0.5818 -0.2742 -0.7657 +vn 0.0482 -0.9967 0.0654 +vn 0.1247 -0.9755 0.1815 +vn 0.1159 -0.9526 0.2812 +vn -0.0899 -0.9526 0.2905 +vn -0.1152 -0.9549 0.2737 +vn -0.0645 -0.9967 0.0486 +vn -0.0625 -0.9824 0.1760 +vn -0.0249 -0.9993 -0.0287 +vn -0.0380 -0.9471 0.3188 +vn 0.0258 -0.9995 0.0168 +vn 0.2029 -0.9350 0.2908 +vn 0.0604 -0.9530 0.2968 +vn -0.5119 -0.5279 -0.6777 +vn -0.2005 0.7517 0.6283 +vn 0.1039 0.6339 0.7664 +vn 0.0068 0.7256 0.6881 +vn 0.6606 0.7469 0.0763 +vn 0.6879 0.7241 0.0501 +vn 0.5126 0.6670 -0.5407 +vn 0.6001 0.7045 0.3790 +vn 0.6064 0.6752 0.4200 +vn 0.0434 0.9915 -0.1230 +vn 0.1363 0.9791 0.1507 +vn 0.0456 0.9950 -0.0886 +vn -0.4268 0.8006 0.4205 +vn -0.6583 0.7206 0.2175 +vn -0.6870 0.7050 -0.1761 +vn -0.7657 0.5957 -0.2426 +vn -0.4952 0.6545 -0.5713 +vn -0.2099 0.6934 -0.6893 +vn 0.0191 0.6289 -0.7773 +vn 0.4179 0.5662 -0.7105 +vn 0.7112 0.6073 -0.3540 +vn -0.0441 0.9708 -0.2360 +vn -0.0129 0.9764 -0.2155 +vn -0.0365 0.9850 -0.1686 +vn -0.0143 -0.9817 0.1898 +vn -0.0218 -0.9791 0.2022 +vn -0.0146 -0.9816 0.1903 +vn -0.0067 -0.9841 0.1773 +vn -0.4579 0.2424 0.8553 +vn 0.1957 0.1055 0.9750 +vn 0.8222 0.1799 0.5401 +vn 0.9469 -0.1578 -0.2800 +vn 0.5015 -0.0966 -0.8597 +vn -0.3073 -0.2753 -0.9109 +vn -0.8967 -0.0323 -0.4415 +vn -0.9910 -0.0494 0.1244 +vn -0.1608 -0.9440 0.2881 +vn -0.1103 -0.9838 0.1413 +vn 0.0078 -0.9992 0.0392 +vn -0.1967 -0.9280 0.3164 +vn 0.1044 -0.9928 0.0594 +vn -0.0462 -0.9278 0.3702 +vn 0.1355 -0.9864 0.0932 +vn 0.1496 -0.9888 -0.0014 +vn 0.1533 -0.9823 0.1077 +vn 0.0937 -0.9535 0.2864 +vn 0.0164 -0.9388 0.3439 +vn -0.3847 -0.4335 -0.8149 +vn 0.3581 0.6776 0.6424 +vn 0.7415 0.6500 -0.1663 +vn 0.6397 0.7470 -0.1811 +vn 0.6918 0.7108 0.1269 +vn 0.6044 0.7730 0.1927 +vn -0.3180 0.8024 0.5051 +vn -0.2592 0.8311 0.4921 +vn -0.0942 0.8902 0.4458 +vn -0.4612 0.7131 0.5280 +vn -0.7494 0.6511 -0.1203 +vn -0.6527 0.7574 -0.0167 +vn -0.6621 0.6737 -0.3283 +vn -0.7110 0.5758 -0.4037 +vn -0.3748 0.6284 -0.6816 +vn 0.0270 0.6783 -0.7342 +vn 0.1125 0.5634 -0.8185 +vn 0.4579 0.6709 -0.5833 +vn -0.0455 0.9713 -0.2336 +vn 0.0190 0.9782 -0.2069 +vn -0.0080 0.9803 -0.1975 +vn -0.0494 0.9855 -0.1626 +vn 0.0078 0.9835 -0.1809 +vn -0.0002 -0.9774 0.2112 +vn -0.0257 -0.9776 0.2090 +vn 0.0254 -0.9767 0.2132 +vn -0.8349 0.0165 0.5501 +vn -0.3697 0.2647 0.8907 +vn 0.9262 0.0984 0.3638 +vn 0.7351 0.0506 0.6760 +vn 0.8074 0.0667 0.5863 +vn 0.9612 0.1110 0.2526 +vn 0.6809 -0.2191 -0.6989 +vn 0.2306 -0.1511 -0.9613 +vn -0.5491 -0.2445 -0.7992 +vn -0.9468 -0.0097 -0.3217 +vn 0.0952 -0.9776 0.1875 +vn 0.1606 -0.9487 0.2725 +vn 0.0816 -0.9434 0.3216 +vn -0.1252 -0.9512 0.2820 +vn -0.1143 -0.9715 0.2075 +vn -0.0746 -0.9895 0.1237 +vn -0.0584 -0.9912 0.1185 +vn 0.0246 -0.9938 0.1082 +vn -0.0775 -0.9375 0.3392 +vn 0.1062 -0.9749 0.1959 +vn 0.0513 -0.9363 0.3473 +vn -0.7375 -0.4237 0.5258 +vn 0.6359 0.7671 0.0847 +vn 0.5482 0.7459 0.3783 +vn 0.6885 0.7222 0.0660 +vn 0.5466 0.7223 0.4236 +vn -0.1656 0.8294 0.5336 +vn -0.3277 0.8399 0.4326 +vn -0.2655 0.8304 0.4898 +vn -0.1043 0.7867 0.6085 +vn -0.4667 0.7838 0.4096 +vn -0.7463 0.6644 -0.0408 +vn -0.7023 0.6843 -0.1963 +vn -0.7098 0.6441 -0.2850 +vn -0.5567 0.6109 -0.5629 +vn -0.4694 0.5075 -0.7226 +vn -0.2077 0.4064 -0.8898 +vn -0.1143 0.2980 -0.9477 +vn 0.6257 0.5887 -0.5118 +vn 0.4415 0.4971 -0.7470 +vn 0.3126 0.5527 -0.7725 +vn 0.7018 0.5066 -0.5008 +vn -0.0233 0.9755 -0.2188 +vn 0.0179 0.9557 -0.2938 +vn 0.0370 0.9729 -0.2281 +vn -0.2293 0.9375 -0.2619 +vn -0.0006 0.9770 -0.2132 +vn 0.0904 0.9691 -0.2296 +vn 0.0025 0.9766 -0.2150 +vn -0.0012 0.9779 -0.2090 +vn 0.0006 0.9774 -0.2113 +vn 0.0073 0.9775 -0.2110 +vn 0.0012 0.9793 -0.2025 +vn 0.0054 0.9789 -0.2041 +vn 0.0109 0.9793 -0.2023 +vn 0.1534 -0.9610 0.2300 +vn -0.0317 -0.9869 0.1580 +vn 0.0977 -0.9730 0.2091 +vn 0.9228 -0.0587 -0.3808 +vn 0.9717 -0.1249 -0.2007 +vn 0.9390 -0.0762 -0.3354 +vn 0.8799 -0.0208 -0.4747 +vn -0.0225 -0.3825 -0.9237 +vn -0.5352 -0.0765 -0.8413 +vn -0.9259 -0.0770 0.3698 +vn -0.9072 -0.0981 0.4091 +vn -0.9135 -0.0913 0.3966 +vn -0.8965 -0.1091 0.4293 +vn 0.2655 0.2641 0.9273 +vn 0.2985 0.2439 0.9227 +vn 0.2834 0.2532 0.9250 +vn 0.3281 0.2251 0.9174 +vn 0.3314 -0.5445 0.7705 +vn 0.4063 -0.4939 0.7688 +vn 0.5372 -0.3887 0.7486 +vn 0.6656 -0.7173 -0.2059 +vn 0.6636 -0.7191 -0.2061 +vn 0.6618 -0.7208 -0.2062 +vn 0.6585 -0.7237 -0.2065 +vn -0.2834 -0.7056 -0.6495 +vn -0.3154 -0.7501 -0.5813 +vn -0.3346 -0.7756 -0.5352 +vn -0.3743 -0.8244 -0.4246 +vn -0.8094 -0.5719 0.1333 +vn -0.7413 -0.6260 0.2420 +vn -0.7287 -0.6338 0.2596 +vn -0.6249 -0.6803 0.3830 +vn -0.3931 -0.3960 0.8298 +vn 0.1653 -0.6360 0.7537 +vn 0.3226 -0.9012 0.2895 +vn -0.0012 0.9772 -0.2124 +vn -0.0088 0.9770 -0.2128 +vn -0.0026 0.9788 -0.2048 +vn 0.0042 0.9793 -0.2025 +vn -0.0006 0.9766 -0.2151 +vn 0.0067 0.9774 -0.2114 +vn 0.0079 0.9788 -0.2047 +vn 0.0061 0.9808 -0.1948 +vn -0.0740 -0.9905 0.1156 +vn -0.0039 -0.9953 0.0966 +vn 0.1585 -0.9568 0.2437 +vn 0.7777 0.2118 0.5919 +vn 0.5367 0.0895 0.8390 +vn 0.6716 0.1548 0.7246 +vn 0.8471 0.2541 0.4668 +vn 0.9348 -0.2285 -0.2718 +vn 0.5145 -0.0977 -0.8519 +vn 0.3902 -0.1657 -0.9057 +vn 0.4639 -0.1265 -0.8768 +vn 0.2815 -0.2186 -0.9343 +vn -0.8851 -0.1165 -0.4506 +vn -0.8853 -0.1162 -0.4503 +vn -0.8852 -0.1164 -0.4505 +vn -0.8850 -0.1167 -0.4507 +vn -0.5732 0.1098 0.8120 +vn -0.5932 0.0907 0.7999 +vn -0.5811 0.1022 0.8074 +vn -0.5618 0.1204 0.8185 +vn 0.5063 -0.4540 0.7332 +vn 0.5340 -0.5575 0.6356 +vn 0.5398 -0.5847 0.6055 +vn 0.5536 -0.6786 0.4827 +vn 0.8222 -0.5692 -0.0016 +vn 0.2611 -0.8224 -0.5055 +vn 0.3274 -0.8703 -0.3680 +vn 0.2342 -0.7988 -0.5541 +vn 0.1690 -0.7332 -0.6587 +vn -0.5630 -0.7333 -0.3812 +vn -0.5765 -0.7720 -0.2676 +vn -0.6786 -0.7287 -0.0920 +vn -0.6936 -0.7202 0.0158 +vn -0.7876 -0.5827 0.2003 +vn -0.3767 -0.5372 0.7547 +vn -0.3942 -0.5811 0.7120 +vn -0.3710 -0.5235 0.7670 +vn -0.3559 -0.4872 0.7975 +vn 0.3591 -0.8941 0.2676 +vn -0.2276 -0.9658 -0.1240 +vn 0.0013 0.9777 -0.2098 +vn 0.0123 0.9773 -0.2114 +vn -0.0010 0.9779 -0.2089 +vn -0.0036 0.9786 -0.2059 +vn 0.0068 0.9784 -0.2065 +vn -0.0095 0.9783 -0.2067 +vn -0.0008 0.9796 -0.2009 +vn -0.0111 0.9776 -0.2102 +vn -0.0189 -0.9787 0.2046 +vn -0.7695 -0.0185 -0.6384 +vn -0.9521 -0.2639 0.1546 +vn -0.5084 0.3185 0.8001 +vn 0.5706 -0.0815 0.8172 +vn 0.9070 0.1238 0.4024 +vn 0.6039 -0.2529 -0.7559 +vn 0.5057 -0.3385 -0.7935 +vn 0.5385 -0.3115 -0.7829 +vn 0.4463 -0.3839 -0.8083 +vn -0.3366 -0.7377 -0.5852 +vn -0.4077 -0.8086 -0.4242 +vn -0.4195 -0.8187 -0.3921 +vn -0.4723 -0.8545 -0.2164 +vn -0.8598 -0.4925 0.1349 +vn -0.3286 -0.5974 0.7315 +vn -0.3388 -0.6178 0.7096 +vn -0.3271 -0.5945 0.7346 +vn -0.3162 -0.5729 0.7562 +vn 0.3456 -0.3738 0.8607 +vn 0.7128 -0.6494 0.2649 +vn 0.5722 -0.7049 0.4191 +vn 0.7434 -0.6304 0.2236 +vn 0.8310 -0.5509 0.0772 +vn 0.3711 -0.8092 -0.4555 +vn 0.4057 -0.8362 -0.3690 +vn 0.3696 -0.8080 -0.4588 +vn 0.3349 -0.7765 -0.5337 +vn -0.0004 0.9784 -0.2065 +vn 0.0024 0.9789 -0.2044 +vn 0.0083 0.9787 -0.2049 +vn -0.0045 0.9779 -0.2092 +vn 0.0034 0.9778 -0.2093 +vn 0.0037 0.9772 -0.2122 +vn -0.0040 0.9771 -0.2128 +vn 0.1536 -0.9598 0.2350 +vn -0.0790 -0.9937 0.0800 +vn 0.0439 -0.9910 0.1261 +vn 0.2551 -0.1797 -0.9501 +vn 0.2267 -0.1536 -0.9618 +vn 0.3000 -0.2210 -0.9280 +vn -0.9188 -0.0619 -0.3897 +vn -0.9342 -0.0798 -0.3476 +vn -0.9268 -0.0708 -0.3689 +vn -0.9408 -0.0883 -0.3271 +vn -0.6248 0.0904 0.7755 +vn -0.5574 0.0500 0.8287 +vn -0.5855 0.0665 0.8079 +vn -0.5177 0.0274 0.8551 +vn 0.7403 0.2700 0.6157 +vn 0.6034 0.1693 0.7793 +vn 0.6901 0.2312 0.6858 +vn 0.7877 0.3097 0.5325 +vn 0.8867 -0.2752 -0.3715 +vn 0.1737 -0.1052 -0.9792 +vn -0.4598 -0.6361 -0.6196 +vn -0.5953 -0.7983 -0.0914 +vn -0.8241 -0.4267 0.3725 +vn -0.3900 -0.6628 0.6392 +vn 0.1183 -0.3175 0.9409 +vn 0.6032 -0.6525 0.4586 +vn 0.4845 -0.7002 0.5244 +vn 0.6362 -0.6357 0.4372 +vn 0.7458 -0.5650 0.3528 +vn 0.6076 -0.6404 -0.4699 +vn 0.4481 -0.7718 -0.4511 +vn 0.3649 -0.8231 -0.4353 +vn 0.1737 -0.9057 -0.3867 +vn -0.1894 -0.9742 -0.1225 +vn 0.3561 -0.9011 0.2475 +vn 0.0113 0.1818 0.9833 +vn 0.0082 0.1923 0.9813 +vn -0.0043 0.2342 0.9722 +vn -0.0074 0.2446 0.9696 +vn 1.0000 0.0050 -0.0070 +vn 0.7621 -0.6468 0.0280 +vn 0.9989 0.0471 -0.0034 +vn 0.0137 -0.1458 -0.9892 +vn 0.0104 -0.1571 -0.9875 +vn -0.0031 -0.2031 -0.9791 +vn -0.0064 -0.2143 -0.9767 +vn -0.9997 0.0243 -0.0003 +vn -0.9997 0.0250 -0.0003 +vn -0.9998 0.0189 0.0000 +vn -0.9998 0.0181 0.0001 +vn 0.5111 0.7365 0.4431 +vn 0.2154 0.9640 -0.1558 +vn 0.4682 0.8791 -0.0893 +vn 0.2221 0.9628 -0.1537 +vn 0.6349 -0.1672 -0.7543 +vn -0.0486 0.6760 -0.7353 +vn -0.9818 0.0288 -0.1880 +vn -0.7098 0.5373 -0.4555 +vn -0.4587 0.7545 0.4693 +vn -0.5519 0.6680 0.4992 +vn -0.3708 0.8197 0.4366 +vn -0.2328 0.8959 0.3783 +vn -0.5341 0.8318 0.1512 +vn -0.5843 0.8051 0.1019 +vn -0.4515 0.8551 0.2550 +vn -0.4044 0.8786 0.2540 +vn 0.3525 0.7331 0.5817 +vn 0.3192 0.6872 0.6526 +vn 0.3763 0.7644 0.5234 +vn 0.4163 0.8135 0.4062 +vn 0.7823 0.5725 -0.2454 +vn 0.8672 0.4788 -0.1369 +vn 0.6981 0.6365 -0.3280 +vn 0.5614 0.7058 -0.4320 +vn -0.0731 -0.0550 -0.9958 +vn -0.3029 0.7531 -0.5840 +vn -0.6526 0.7552 -0.0620 +vn -0.7183 0.5745 0.3925 +vn -0.6893 0.6105 0.3902 +vn -0.6374 0.6678 0.3844 +vn 0.1662 0.8434 0.5109 +vn 0.3347 0.7307 0.5950 +vn 0.4144 0.6597 0.6270 +vn 0.5037 0.5632 0.6551 +vn 0.6365 0.7637 -0.1080 +vn 0.8000 0.0829 -0.5942 +vn 0.1794 0.6900 -0.7012 +vn -0.6081 0.4964 -0.6196 +vn -0.4757 0.6110 -0.6328 +vn -0.4524 0.6281 -0.6331 +vn -0.3920 0.6690 -0.6315 +vn -0.7372 0.5491 0.3937 +vn 0.7144 0.6910 0.1099 +vn 0.7443 0.6341 0.2094 +vn 0.6976 0.7135 0.0645 +vn 0.6317 0.7711 -0.0798 +vn 0.3856 0.4432 -0.8092 +vn 0.4068 0.6286 -0.6629 +vn 0.4077 0.6454 -0.6459 +vn 0.4085 0.7269 -0.5520 +vn -0.1923 0.6111 0.7678 +vn -0.0931 0.7424 0.6634 +vn -0.0150 0.8237 0.5668 +vn -0.2369 0.5405 0.8073 +vn -0.7588 -0.0733 -0.6471 +vn -0.6504 0.6519 -0.3900 +vn -0.7149 0.1891 0.6732 +vn -0.6030 0.1487 0.7837 +vn -0.6715 0.1732 0.7205 +vn -0.5610 0.1340 0.8169 +vn -0.6580 -0.0733 -0.7495 +vn -0.7895 -0.1263 -0.6006 +vn -0.7186 -0.0968 -0.6886 +vn -0.8374 -0.1483 -0.5260 +vn 0.6254 0.2196 0.7487 +vn 0.7458 0.1346 0.6525 +vn 0.6759 0.1864 0.7130 +vn 0.7874 0.0995 0.6083 +vn 0.7594 -0.0974 -0.6433 +vn 0.6528 -0.1724 -0.7377 +vn 0.7226 -0.1252 -0.6798 +vn 0.6170 -0.1943 -0.7626 +vn 1.0000 -0.0094 -0.0025 +vn 1.0000 -0.0066 -0.0018 +vn 1.0000 -0.0028 -0.0008 +vn 0.0004 0.2102 0.9777 +vn 0.0008 0.2096 0.9778 +vn 0.0012 0.2090 0.9779 +vn 0.0015 0.2083 0.9781 +vn -1.0000 -0.0037 -0.0022 +vn -1.0000 -0.0042 -0.0019 +vn -1.0000 -0.0048 -0.0014 +vn -1.0000 -0.0052 -0.0010 +vn 0.0000 -0.2746 -0.9615 +vn -0.1099 -0.2275 -0.9676 +vn -0.1467 -0.2110 -0.9664 +vn -0.0001 -0.2741 -0.9617 +vn 0.0723 -0.1904 -0.9790 +vn 0.0000 -0.2733 -0.9619 +vn 0.0296 -0.2398 -0.9704 +vn 0.1305 -0.1212 -0.9840 +vn 1.0000 0.0008 -0.0035 +vn 1.0000 0.0063 -0.0022 +vn 0.9990 0.0448 -0.0084 +vn 0.9996 0.0292 -0.0047 +vn -0.0000 0.2333 0.9724 +vn 0.0006 0.2373 0.9714 +vn 0.0022 0.2550 0.9669 +vn 0.0023 0.2383 0.9712 +vn -0.9983 0.0584 -0.0080 +vn -0.9994 0.0334 -0.0022 +vn -1.0000 0.0014 -0.0016 +vn -0.9999 -0.0144 0.0002 +vn -0.3848 -0.0916 -0.9185 +vn 0.1458 -0.3776 -0.9144 +vn 0.1234 -0.3345 -0.9343 +vn 0.0654 -0.2259 -0.9720 +vn 0.8850 -0.4618 -0.0583 +vn 0.9233 -0.3683 -0.1092 +vn 0.9379 -0.3198 -0.1341 +vn 0.6648 -0.7042 0.2494 +vn 0.6653 -0.6914 0.2816 +vn 0.6352 -0.7724 -0.0006 +vn -0.1076 0.1788 0.9780 +vn 0.1902 0.2335 0.9536 +vn 0.0074 0.3153 0.9489 +vn 0.1223 -0.2529 -0.9597 +vn 0.7730 0.5869 -0.2410 +vn 0.7707 0.6127 -0.1749 +vn 0.7672 0.5756 -0.2830 +vn 0.9636 -0.2506 0.0935 +vn 0.9638 -0.2509 0.0902 +vn 0.9655 -0.2530 0.0614 +vn 0.9658 -0.2534 0.0555 +vn 0.9395 0.1392 -0.3129 +vn 0.5317 -0.0584 -0.8449 +vn 0.7777 0.6186 -0.1121 +vn 0.5837 -0.7683 -0.2628 +vn 0.6226 -0.7696 0.1419 +vn 0.6116 -0.7799 -0.1334 +vn 0.9333 -0.3327 -0.1351 +vn 0.9565 0.1476 -0.2518 +vn 0.8514 0.0509 0.5221 +vn 0.9979 0.0643 0.0099 +vn 0.9171 0.1640 -0.3634 +vn 0.8519 0.4999 -0.1563 +vn 0.9286 0.3538 -0.1120 +vn 0.7797 0.5763 0.2451 +vn 0.5302 -0.0352 -0.8471 +vn 0.7912 0.5877 -0.1690 +vn 0.0483 -0.2892 -0.9561 +vn 0.0380 -0.2258 -0.9734 +vn 0.0410 -0.2938 -0.9550 +vn 0.0491 -0.2181 -0.9747 +vn 0.0697 -0.2212 -0.9727 +vn 0.7986 0.5996 -0.0521 +vn 0.7980 0.6023 -0.0190 +vn 0.8681 0.4959 0.0207 +vn 0.9151 -0.2085 0.3451 +vn 0.9555 -0.2153 -0.2014 +vn 0.9420 0.3354 -0.0130 +vn 0.9576 0.1976 0.2098 +vn 0.7994 0.5964 -0.0728 +vn 0.0431 -0.2086 -0.9771 +vn 0.0308 -0.2088 -0.9775 +vn 0.9371 -0.2715 -0.2192 +vn 0.7967 0.3622 -0.4839 +vn 0.9929 0.1188 0.0064 +vn 0.7523 0.3310 -0.5696 +vn 0.0308 -0.1982 -0.9797 +vn 0.0350 -0.1995 -0.9793 +vn 0.2416 -0.4791 -0.8438 +vn 0.9561 -0.2346 -0.1756 +vn 0.9085 0.0059 0.4179 +vn 0.8200 0.3265 -0.4702 +vn 0.0546 -0.2009 -0.9781 +vn 0.1485 0.0010 -0.9889 +vn 0.7158 -0.6960 -0.0558 +vn 0.1446 -0.3512 -0.9251 +vn 0.9524 -0.2845 0.1099 +vn 0.9515 -0.2843 0.1178 +vn 0.9976 -0.0694 -0.0024 +vn 0.9812 -0.1700 0.0909 +vn 0.9983 0.0509 -0.0274 +vn 0.9986 0.0515 -0.0137 +vn 0.8295 0.4044 -0.3853 +vn 0.0974 -0.1413 -0.9852 +vn -0.3496 -0.1509 -0.9247 +vn -0.2020 -0.1772 -0.9632 +vn 0.0781 -0.2138 -0.9738 +vn 0.9805 -0.1885 0.0560 +vn 0.9776 -0.1841 0.1018 +vn 0.9068 -0.1452 0.3957 +vn 0.8429 -0.1217 0.5242 +vn 0.5248 -0.0664 -0.8486 +vn 0.8414 0.0652 -0.5364 +vn 0.7368 0.0141 -0.6760 +vn 0.8543 0.4558 0.2497 +vn 0.4847 -0.0795 -0.8711 +vn 0.7861 0.5915 -0.1793 +vn 0.7829 0.5275 -0.3298 +vn 0.7784 0.5663 -0.2709 +vn 0.0546 -0.2711 -0.9610 +vn 0.0362 -0.2247 -0.9738 +vn 0.0607 -0.2864 -0.9562 +vn 0.0327 -0.2157 -0.9759 +vn 0.7792 0.6261 0.0297 +vn 0.7791 0.6268 0.0150 +vn 0.8713 0.4724 0.1333 +vn 0.9786 -0.0728 0.1923 +vn 0.9747 -0.0708 0.2122 +vn 0.9796 -0.0733 0.1871 +vn 0.9409 0.1730 -0.2912 +vn 0.2248 -0.0111 -0.9743 +vn 0.0617 -0.1755 -0.9825 +vn 0.0538 -0.1832 -0.9816 +vn 0.2443 0.0094 -0.9697 +vn 0.0385 -0.2230 -0.9740 +vn -0.7216 -0.3132 0.6174 +vn -0.2581 -0.5363 -0.8036 +vn -0.5563 0.1094 0.8237 +vn -0.4820 0.0073 -0.8761 +vn 0.7885 0.5567 0.2615 +vn 0.6147 -0.4480 0.6492 +vn -0.7973 -0.5364 0.2768 +vn -0.8260 -0.4316 0.3625 +vn -0.8397 -0.2849 0.4623 +vn -0.8371 -0.2139 0.5035 +vn -0.4673 -0.2243 -0.8552 +vn -0.6069 0.5330 0.5896 +vn -0.5979 0.4542 0.6605 +vn -0.6002 0.6979 0.3907 +vn 0.7664 0.4600 -0.4484 +vn 0.7699 0.5392 -0.3414 +vn 0.6340 -0.7344 0.2422 +vn 0.6349 -0.7316 0.2483 +vn 0.6292 -0.7478 0.2118 +vn -0.8895 -0.4412 0.1187 +vn -0.4015 -0.2753 -0.8735 +vn -0.4756 0.3611 0.8021 +vn 0.8331 0.0510 0.5508 +vn 0.7650 0.5640 0.3111 +vn 0.6476 -0.6807 0.3424 +vn 0.7623 -0.6165 0.1969 +vn 0.6470 -0.6857 0.3335 +vn -0.6291 -0.3310 0.7033 +vn -0.5402 -0.3845 -0.7485 +vn -0.4979 0.3315 0.8014 +vn -0.2743 0.3342 0.9017 +vn -0.0722 0.3208 0.9444 +vn -0.0328 0.3167 0.9480 +vn -0.3843 -0.1440 -0.9119 +vn 0.9824 0.1612 0.0944 +vn 0.8031 0.5823 0.1262 +vn 0.8523 0.4687 0.2323 +vn -0.7344 -0.5408 0.4102 +vn -0.6130 -0.1628 0.7732 +vn -0.6018 -0.2115 -0.7702 +vn -0.4509 0.3884 0.8037 +vn 0.9742 -0.0705 0.2145 +vn 0.8183 0.5744 -0.0206 +vn 0.8913 0.3988 0.2158 +vn 0.5750 -0.6703 -0.4691 +vn -0.8602 -0.4763 0.1821 +vn 0.8633 0.4441 -0.2396 +vn -0.2095 0.2253 0.9515 +vn -0.3285 0.1916 0.9249 +vn -0.5921 0.0982 0.7998 +vn -0.6431 0.0762 0.7620 +vn 0.8265 0.0441 0.5612 +vn 0.6553 -0.6720 0.3449 +vn -0.5147 0.5059 -0.6922 +vn -0.7649 -0.6255 0.1537 +vn -0.8040 -0.1640 0.5716 +vn -0.5036 -0.1981 -0.8409 +vn -0.8996 0.1624 -0.4053 +vn 0.7628 0.6108 -0.2123 +vn 0.2411 0.1235 0.9626 +vn 0.1385 0.0933 0.9860 +vn 0.0690 0.2186 0.9734 +vn 0.9188 0.3319 0.2139 +vn 0.6187 -0.7745 0.1316 +vn 0.6363 -0.7389 0.2215 +vn -0.9233 -0.3841 -0.0022 +vn 0.2973 -0.2869 -0.9106 +vn -0.2951 0.2875 0.9112 +vn -0.4278 0.2768 0.8605 +vn -0.5507 0.2606 0.7930 +vn -0.5850 0.2548 0.7700 +vn -0.5475 0.7901 0.2757 +vn 0.9516 0.1964 0.2362 +vn 0.6171 -0.7779 0.1187 +vn 0.6065 -0.7917 0.0738 +vn 0.7595 -0.6259 0.1773 +vn -0.9979 -0.0217 0.0609 +vn 0.0099 -0.2093 -0.9778 +vn 0.2114 -0.2164 -0.9531 +vn -0.0723 -0.1535 -0.9855 +vn 0.1379 0.1919 0.9717 +vn 0.0069 0.2063 0.9785 +vn -0.0844 0.2768 0.9572 +vn 0.9829 0.1482 -0.1094 +vn 0.1751 -0.2894 -0.9411 +vn 0.9978 0.0370 -0.0558 +vn 0.4198 0.3698 0.8289 +vn 0.5947 -0.7708 0.2285 +vn -0.7101 0.7033 -0.0352 +vn 0.0488 0.1864 0.9813 +vn 0.6281 -0.7506 0.2051 +vn -0.5802 0.7671 0.2736 +vn 0.0023 0.2122 0.9772 +vn 0.6705 -0.7019 0.2402 +vn -0.6078 0.7535 0.2505 +vn 0.0142 0.2087 0.9779 +vn 0.3449 -0.2924 0.8919 +vn 0.6289 -0.7714 0.0978 +vn 0.5070 -0.4624 -0.7274 +vn -0.6131 0.6866 -0.3908 +vn -0.0150 0.2069 0.9782 +vn 0.6242 -0.7797 -0.0503 +vn -0.6763 0.7209 0.1511 +vn 0.0234 0.2113 0.9771 +vn 0.6681 -0.6770 -0.3087 +vn 0.2962 -0.5865 -0.7538 +vn -0.7240 0.6887 0.0402 +vn -0.7547 0.6432 -0.1293 +vn 0.0979 0.0864 0.9914 +vn 0.0615 0.2213 0.9733 +vn 0.8748 -0.4445 0.1926 +vn 0.0375 0.2136 0.9762 +vn 0.0527 0.9708 -0.2339 +vn -0.0348 0.9760 -0.2148 +vn -0.0080 0.9729 -0.2310 +vn -0.0207 0.9692 -0.2456 +vn 0.0957 0.9798 -0.1754 +vn 0.0068 0.9826 -0.1855 +vn -0.0395 0.9781 -0.2045 +vn -0.0200 0.9835 -0.1798 +vn -0.0172 -0.2091 -0.9777 +vn 0.0057 -0.2103 -0.9776 +vn -0.8991 0.4281 -0.0910 +vn -0.8874 0.3653 0.2812 +vn -0.9511 0.2515 0.1792 +vn -0.9888 0.1469 0.0279 +vn -0.9968 0.0708 -0.0371 +vn -0.0520 0.2306 0.9716 +vn -0.0091 0.2042 0.9789 +vn 0.9998 0.0091 -0.0158 +vn 0.9993 0.0349 0.0100 +vn 0.9999 0.0094 0.0136 +vn 0.9996 -0.0287 -0.0040 +vn 0.9944 -0.0197 0.1035 +vn 0.9649 -0.1912 0.1799 +vn 0.9425 -0.2413 0.2310 +vn 0.9983 0.0034 0.0574 +vn 0.9709 0.0506 0.2341 +vn 0.9992 0.0053 -0.0408 +vn 0.9993 0.0168 -0.0345 +vn 0.9892 -0.1458 0.0175 +vn 0.9394 -0.3295 0.0947 +vn 0.9964 -0.0847 0.0089 +vn 0.8779 -0.4527 0.1562 +vn 0.9968 -0.0802 -0.0050 +vn 0.9998 0.0083 0.0198 +vn 0.4886 0.2864 0.8242 +vn 0.6935 -0.1469 -0.7053 +vn 0.7949 -0.5662 0.2182 +vn 0.9950 0.0270 0.0959 +vn 0.9994 0.0340 0.0038 +vn 1.0000 0.0022 -0.0035 +vn 0.9978 0.0427 0.0506 +vn 0.9451 -0.0887 -0.3144 +vn -0.2198 0.2039 0.9540 +vn 0.9973 -0.0114 -0.0719 +vn 0.9998 0.0029 -0.0220 +vn 0.9976 -0.0102 -0.0679 +vn 0.9928 -0.0989 -0.0673 +vn 0.9763 -0.1310 -0.1724 +vn 0.9942 -0.0680 -0.0830 +vn 0.9968 -0.0797 -0.0034 +vn 0.8800 0.1164 0.4606 +vn 0.9992 0.0149 0.0359 +vn 0.9987 0.0075 -0.0503 +vn 0.9989 0.0078 -0.0470 +vn 0.9862 -0.1551 0.0572 +vn 0.7867 0.1576 0.5969 +vn 0.1736 -0.1247 -0.9769 +vn -0.3787 0.1215 0.9175 +vn 0.9982 0.0168 0.0574 +vn 0.9861 -0.0168 0.1654 +vn 0.9842 -0.0571 -0.1677 +vn 0.2185 0.3112 0.9249 +vn 0.3184 -0.2265 -0.9205 +vn 0.3776 -0.0460 0.9248 +vn 0.9992 0.0189 0.0338 +vn 0.9919 0.0666 -0.1078 +vn 0.9448 -0.1000 -0.3120 +vn 0.8546 -0.4540 0.2520 +vn 0.9078 -0.4068 0.1015 +vn 0.9805 0.0450 0.1912 +vn 0.9819 0.0435 0.1842 +vn 0.9953 0.0247 0.0937 +vn 0.9958 0.0237 0.0887 +vn 0.5695 0.2716 0.7759 +vn 0.6945 -0.1572 -0.7021 +vn 0.7905 -0.5286 0.3092 +vn 0.9999 0.0052 0.0105 +vn 0.9438 -0.2536 0.2118 +vn 0.8295 -0.5385 0.1477 +vn 0.9995 -0.0249 -0.0182 +vn 0.9947 0.0107 0.1022 +vn 0.9993 0.0161 0.0343 +vn 0.9992 -0.0182 -0.0362 +vn 0.6464 0.2475 0.7218 +vn 0.0191 -0.2804 -0.9597 +vn 0.9931 0.0937 -0.0705 +vn 0.9691 -0.1786 0.1704 +vn 0.5851 -0.7650 -0.2690 +vn 0.9999 -0.0027 0.0097 +vn 0.9996 -0.0265 -0.0043 +vn 0.9989 -0.0288 -0.0363 +vn 0.7485 -0.3791 0.5441 +vn 0.9992 -0.0035 0.0390 +vn 0.9988 0.0244 0.0429 +vn 0.9999 -0.0038 -0.0163 +vn 0.0000 0.9470 0.3211 +vn 0.3688 0.9072 -0.2022 +vn 0.4212 0.8674 -0.2649 +vn 0.4327 0.8573 -0.2789 +vn -0.1450 0.7341 -0.6634 +vn 0.2400 0.9689 -0.0606 +vn 0.5550 0.7565 0.3459 +vn -0.0881 0.9850 -0.1485 +vn 0.7972 0.1570 -0.5830 +vn 0.4573 0.8338 -0.3092 +vn -0.9721 0.2323 0.0333 +vn -0.9774 0.2087 0.0337 +vn -0.9374 0.3483 0.0057 +vn -0.9426 -0.0497 -0.3302 +vn 0.5441 0.8208 -0.1740 +vn 0.5446 0.8205 -0.1739 +vn 0.7515 0.6453 -0.1376 +vn 0.8300 0.5453 -0.1169 +vn -0.0000 0.2079 0.9781 +vn -0.1124 0.0974 0.9889 +vn -0.3651 -0.1633 0.9165 +vn -0.0625 0.1553 0.9859 +vn -0.5247 -0.2724 0.8065 +vn 0.3801 0.1896 0.9053 +vn 0.1241 0.3304 0.9357 +vn -0.0253 0.3290 0.9440 +vn -0.4363 -0.3023 0.8475 +vn -0.1714 0.2306 0.9578 +vn -0.9860 0.1651 -0.0238 +vn -0.9875 0.1553 -0.0255 +vn -0.1472 -0.0866 -0.9853 +vn 0.0000 0.9782 -0.2079 +vn -0.0001 0.9782 -0.2079 +vn -0.2520 0.9405 -0.2279 +vn -0.1658 0.9607 -0.2226 +vn -0.4097 0.8820 -0.2329 +vn -0.1416 0.3708 0.9179 +vn -0.8281 -0.0864 0.5539 +vn -0.8632 -0.2015 -0.4630 +vn -0.8579 -0.4269 -0.2859 +vn -0.8738 -0.3912 -0.2889 +vn -0.9846 0.1733 -0.0233 +vn -0.9873 0.1584 -0.0144 +vn -0.0897 -0.2179 -0.9718 +vn -0.0153 -0.2449 -0.9694 +vn -0.2485 -0.1986 -0.9480 +vn -0.0245 -0.0932 -0.9953 +vn 0.1300 -0.2449 -0.9608 +vn 0.1197 -0.0841 -0.9892 +vn 0.1264 -0.2822 -0.9510 +vn 0.0002 -0.2079 -0.9782 +vn 0.0000 -0.2074 -0.9783 +vn 0.9949 0.0987 -0.0224 +vn 0.9939 0.1071 -0.0261 +vn 0.9947 0.1000 -0.0229 +vn 0.9938 0.1083 -0.0267 +vn -0.0268 0.9802 -0.1964 +vn -0.0171 0.9850 -0.1719 +vn -0.0308 0.9741 -0.2238 +vn 0.1032 0.9641 -0.2447 +vn -0.8819 -0.4610 0.0988 +vn 0.1901 0.9702 -0.1503 +vn -0.0214 0.9689 -0.2464 +vn -0.9748 0.2232 0.0019 +vn -0.2630 0.4731 0.8409 +vn -0.8791 -0.1524 -0.4516 +vn -0.9992 -0.0384 0.0093 +vn -0.9993 -0.0182 0.0314 +vn -0.9968 0.0612 0.0512 +vn -0.9950 0.0717 0.0700 +vn -0.9833 0.1806 0.0224 +vn -0.8363 -0.5441 -0.0676 +vn -0.3022 0.0841 -0.9495 +vn -0.9618 0.2503 -0.1112 +vn 0.0063 0.8378 0.5459 +vn 0.0140 0.4803 -0.8770 +vn 0.6950 0.7038 -0.1471 +vn 0.6497 0.7434 -0.1585 +vn 0.6940 0.7047 -0.1474 +vn 0.6476 0.7452 -0.1590 +vn -0.0066 0.2175 0.9760 +vn -0.0140 0.2242 0.9744 +vn -0.0058 0.2168 0.9762 +vn -0.0008 -0.1988 -0.9800 +vn 0.0014 -0.1969 -0.9804 +vn -0.0010 -0.1990 -0.9800 +vn 0.0017 0.2100 0.9777 +vn -1.0000 0.0027 0.0020 +vn -1.0000 0.0000 0.0004 +vn -1.0000 0.0002 0.0004 +vn -1.0000 -0.0025 -0.0012 +vn -0.0032 -0.2009 -0.9796 +vn 1.0000 -0.0012 -0.0008 +vn 1.0000 -0.0025 0.0010 +vn 1.0000 -0.0024 0.0009 +vn 1.0000 -0.0037 0.0027 +vn -0.0323 0.9773 -0.2092 +vn -0.0030 0.9753 -0.2206 +vn -0.0378 0.9774 -0.2080 +vn -0.0002 0.9737 -0.2279 +vn 0.9639 -0.0388 0.2634 +vn 0.9921 -0.1251 -0.0039 +vn 0.9838 -0.1319 0.1214 +vn 0.9846 -0.1742 -0.0163 +vn 0.9670 -0.2251 0.1196 +vn 0.9646 -0.2458 0.0959 +vn 0.9867 -0.1570 0.0416 +vn 0.9566 -0.2278 0.1816 +vn 0.9543 -0.2691 0.1304 +vn 0.9842 -0.1441 0.1032 +vn 0.9583 -0.2215 0.1806 +vn 0.9582 -0.2018 0.2026 +vn 0.9901 -0.0888 0.1089 +vn 0.0670 0.9698 -0.2345 +vn 0.2138 0.9546 -0.2073 +vn 0.0820 0.9693 -0.2320 +vn 0.2276 0.9520 -0.2045 +vn 0.9232 0.3762 -0.0784 +vn 0.9870 0.1570 -0.0332 +vn 0.8268 0.5513 -0.1118 +vn 0.9853 -0.1381 0.1008 +vn 0.9582 -0.2005 0.2040 +vn 0.9915 -0.0788 0.1032 +vn 0.9519 -0.1605 0.2610 +vn 0.9902 -0.1328 0.0426 +vn 0.9566 -0.2313 0.1773 +vn 0.9844 0.0519 0.1679 +vn 0.9906 -0.1355 -0.0206 +vn 0.9870 -0.1221 0.1046 +vn 0.9916 -0.1091 0.0698 +vn 0.9938 -0.1043 -0.0388 +vn 0.9875 -0.1575 -0.0020 +vn 0.0498 0.9700 -0.2378 +vn 0.2223 0.9530 -0.2059 +vn 0.0677 0.9697 -0.2349 +vn 0.2385 0.9498 -0.2025 +vn 0.8904 -0.4515 0.0583 +vn 0.9215 -0.3884 0.0011 +vn 0.9449 -0.3226 -0.0557 +vn -0.9902 0.1381 -0.0198 +vn -0.9986 0.0530 -0.0064 +vn -0.9957 0.0909 -0.0192 +vn -0.9957 0.0908 -0.0192 +vn -0.7068 -0.6795 0.1968 +vn -0.9418 -0.3148 0.1182 +vn -0.8887 -0.4532 0.0692 +vn -0.7829 -0.6222 0.0005 +vn -0.9687 -0.1917 0.1574 +vn 0.8287 0.5231 -0.1989 +vn 0.9251 0.2819 -0.2544 +vn 0.8982 0.3704 -0.2367 +vn 0.7763 0.6059 -0.1739 +vn -0.8635 0.4274 -0.2677 +vn -0.8216 0.5609 -0.1021 +vn -0.8510 0.5227 -0.0505 +vn -0.8626 0.5051 -0.0277 +vn -0.8841 0.4668 0.0199 +vn 0.8976 0.4305 -0.0947 +vn 0.7245 0.6892 -0.0072 +vn 0.7982 0.6011 -0.0400 +vn 0.9348 0.3336 -0.1219 +vn 0.9293 0.3643 0.0606 +vn 0.4136 0.7421 0.5275 +vn -0.5552 -0.7888 0.2639 +vn -0.0115 -0.3914 -0.9202 +vn -0.0217 -0.5575 -0.8299 +vn -0.0115 -0.3917 -0.9200 +vn -0.0007 -0.2077 -0.9782 +vn -0.6787 0.1559 -0.7176 +vn 0.6095 0.7898 -0.0692 +vn 0.6184 0.7820 -0.0777 +vn 0.6214 0.7794 -0.0805 +vn 0.6288 0.7726 -0.0877 +vn -0.5486 -0.7935 0.2633 +vn -0.6090 -0.7608 0.2243 +vn -0.6675 -0.7219 0.1824 +vn -0.0007 -0.2085 -0.9780 +vn -0.0007 -0.2091 -0.9779 +vn -0.0007 -0.2082 -0.9781 +vn -0.8964 0.3494 -0.2729 +vn 0.6660 0.6894 -0.2849 +vn -0.7882 -0.6154 0.0002 +vn -0.6972 -0.7108 0.0930 +vn -0.6522 -0.7464 0.1325 +vn -0.6130 -0.7728 0.1643 +vn -0.9407 0.2893 -0.1774 +vn -0.9249 0.3212 -0.2035 +vn -0.9024 0.2873 -0.3212 +vn 0.4811 0.8663 -0.1348 +vn -0.2193 -0.9484 -0.2289 +vn -0.2584 -0.9440 -0.2054 +vn -0.0488 -0.9452 -0.3227 +vn -0.0007 -0.2078 -0.9782 +vn -0.8963 0.3496 -0.2727 +vn 0.3879 0.0124 0.9216 +vn -0.0946 0.2179 0.9714 +vn -0.0972 0.2167 0.9714 +vn -0.1084 0.2118 0.9713 +vn -0.1134 0.2096 0.9712 +vn 0.1748 -0.1759 -0.9688 +vn 0.1956 -0.1709 -0.9657 +vn 0.0735 -0.1984 -0.9774 +vn 0.0559 -0.2020 -0.9778 +vn -0.9667 0.2530 0.0397 +vn -0.9623 0.2184 0.1619 +vn -0.9666 0.2374 0.0966 +vn -0.9593 0.2104 0.1882 +vn -0.9464 0.3076 -0.0985 +vn -0.9626 0.2669 0.0457 +vn -0.5939 0.4198 0.6863 +vn 0.6431 -0.1352 0.7537 +vn -0.9475 0.2745 0.1641 +vn -0.9505 0.2981 0.0879 +vn -0.9496 0.2856 0.1289 +vn -0.9502 0.3053 0.0630 +vn -0.9505 0.3002 0.0806 +vn -0.9499 0.2874 0.1232 +vn -0.9498 0.3082 0.0528 +vn -0.8904 -0.4362 0.1303 +vn -0.9216 -0.3550 0.1571 +vn -0.9450 -0.2715 0.1823 +vn 0.9974 0.0722 -0.0042 +vn 0.9847 0.1728 -0.0223 +vn -0.9473 0.3041 -0.1011 +vn -0.9922 0.0971 -0.0785 +vn -0.9734 0.0425 -0.2252 +vn -0.8929 0.4110 -0.1839 +vn -0.6443 0.6887 -0.3325 +vn -0.9653 0.2559 0.0516 +vn 0.6686 0.7399 -0.0749 +vn 0.9129 0.3813 -0.1455 +vn 0.9719 0.2129 -0.1002 +vn 0.9249 0.3307 -0.1877 +vn -0.7372 -0.6755 0.0172 +vn -0.8588 -0.5023 -0.1010 +vn -0.8685 -0.4827 -0.1129 +vn -0.8904 -0.4324 -0.1423 +vn -0.9609 0.2750 -0.0309 +vn -0.9261 0.3238 -0.1935 +vn -0.9191 0.3106 -0.2423 +vn -0.8859 -0.4300 0.1741 +vn 0.8024 -0.5901 -0.0895 +vn 0.0078 -0.2103 -0.9776 +vn -0.9173 0.2655 -0.2968 +vn 0.4794 0.8673 -0.1339 +vn -0.3603 -0.9328 -0.0094 +vn -0.1981 -0.1169 -0.9732 +vn 0.9273 0.3695 0.0593 +vn 0.8601 0.4799 0.1728 +vn 0.8494 0.4934 0.1874 +vn 0.7818 0.5637 0.2666 +vn -0.5296 -0.8070 0.2614 +vn -0.0116 -0.3926 -0.9196 +vn -0.0218 -0.5593 -0.8287 +vn -0.0116 -0.3923 -0.9198 +vn -0.6734 0.1523 -0.7234 +vn 0.2378 0.1957 0.9514 +vn 0.2489 0.1914 0.9494 +vn 0.1494 0.1804 0.9722 +vn -0.0086 0.0936 0.9956 +vn -0.1212 0.0258 0.9923 +vn 0.9759 0.1844 -0.1169 +vn 0.9748 0.2215 -0.0257 +vn 0.1602 -0.1758 -0.9713 +vn 0.1789 -0.1714 -0.9688 +vn 0.0724 -0.1955 -0.9780 +vn 0.0568 -0.1989 -0.9784 +vn -0.9177 0.1666 0.3607 +vn -0.9615 0.2450 0.1242 +vn -0.9433 0.2007 0.2645 +vn -0.9628 0.2647 0.0546 +vn -0.9541 0.2854 -0.0912 +vn -0.9654 0.2604 0.0113 +vn -0.9612 0.2731 -0.0393 +vn -0.9668 0.2520 0.0432 +vn -0.9570 0.2886 -0.0285 +vn -0.9535 0.2108 0.2154 +vn -0.5048 0.3960 0.7671 +vn 0.7561 -0.2162 0.6178 +vn 0.7887 -0.1237 0.6022 +vn 0.8214 0.0079 0.5703 +vn 0.9917 0.1279 -0.0103 +vn 0.9101 0.4143 -0.0012 +vn 0.9230 0.3844 0.0154 +vn 0.9377 0.2685 -0.2205 +vn 0.8541 -0.5078 0.1121 +vn 0.9696 -0.2163 0.1143 +vn 0.8515 -0.5239 0.0199 +vn 0.9971 -0.0736 0.0212 +vn 0.9905 0.1300 -0.0438 +vn 0.9389 0.3240 -0.1162 +vn 0.8661 0.4776 -0.1472 +vn 0.8749 0.4651 -0.1349 +vn 0.9317 0.3104 -0.1885 +vn 0.9913 0.1004 -0.0855 +vn 0.8803 0.4581 -0.1229 +vn 0.9877 0.1547 -0.0221 +vn 0.0013 -0.1148 -0.9934 +vn 0.0015 -0.1156 -0.9933 +vn 0.0020 -0.1166 -0.9932 +vn 0.0006 -0.1160 -0.9932 +vn 0.0004 -0.1158 -0.9933 +vn 0.0051 0.3007 0.9537 +vn 0.0803 0.3296 0.9407 +vn 0.1141 0.3420 0.9327 +vn 0.1159 0.3426 0.9323 +vn 0.8844 -0.4653 0.0369 +vn 0.8953 -0.4300 0.1163 +vn 0.8717 -0.4656 0.1532 +vn 0.8848 -0.4466 0.1333 +vn 0.8535 -0.4895 0.1786 +vn 0.9966 0.0409 0.0717 +vn 1.0000 -0.0037 0.0044 +vn 0.9999 -0.0129 0.0115 +vn 0.9997 -0.0245 -0.0038 +vn 1.0000 -0.0040 -0.0037 +vn 0.9997 -0.0099 -0.0234 +vn 0.9940 -0.0284 -0.1055 +vn 0.9223 0.2565 -0.2890 +vn 0.9357 0.0825 0.3430 +vn 0.7807 -0.6193 0.0836 +vn -0.3583 -0.9228 -0.1418 +vn 0.2715 -0.6238 0.7329 +vn 0.9685 0.2424 -0.0578 +vn 0.4000 -0.8974 -0.1864 +vn -0.6956 -0.7002 0.1606 +vn 0.7976 0.5691 -0.1998 +vn 0.9999 0.0124 -0.0018 +vn 1.0000 0.0086 -0.0030 +vn 0.9999 0.0099 -0.0026 +vn 0.9999 0.0133 -0.0015 +vn 0.4059 -0.6348 0.6574 +vn 0.8733 -0.1355 -0.4680 +vn 0.9233 -0.1053 -0.3693 +vn -1.0000 0.0077 -0.0025 +vn -1.0000 0.0070 -0.0017 +vn -1.0000 0.0066 -0.0013 +vn -1.0000 0.0059 -0.0004 +vn 0.0114 0.2680 0.9634 +vn 0.0123 0.3848 0.9229 +vn 0.0617 0.5030 0.8621 +vn 0.1126 0.4703 0.8753 +vn 0.0234 -0.6951 -0.7185 +vn 0.0543 -0.5690 -0.8205 +vn -0.0152 -0.8234 -0.5673 +vn -0.8539 -0.5099 0.1040 +vn -0.8605 0.5056 -0.0630 +vn -0.8668 0.4940 -0.0674 +vn -0.8641 0.4991 -0.0655 +vn -0.8695 0.4890 -0.0693 +vn -0.9698 -0.2431 -0.0186 +vn -0.8538 -0.4830 0.1944 +vn -0.9972 -0.0740 0.0124 +vn -0.9315 0.3610 0.0454 +vn -0.9905 0.1346 0.0297 +vn -0.8801 0.4690 -0.0741 +vn -0.9892 0.1418 -0.0359 +vn 0.9826 -0.1177 0.1440 +vn 0.9930 -0.0911 0.0755 +vn 0.9997 -0.0229 0.0102 +vn -0.0006 0.2985 0.9544 +vn -0.0003 0.2984 0.9545 +vn -0.0055 0.3004 0.9538 +vn -0.0069 0.3009 0.9536 +vn 0.0012 -0.1154 -0.9933 +vn 0.0017 -0.1150 -0.9934 +vn 0.9996 -0.0283 -0.0040 +vn 0.9993 -0.0021 -0.0374 +vn 0.9729 -0.1968 -0.1213 +vn -0.0031 0.2979 0.9546 +vn -0.0003 0.2988 0.9543 +vn -0.0039 0.2975 0.9547 +vn 0.0007 0.2978 0.9546 +vn 0.0005 0.2980 0.9546 +vn -0.9316 -0.3296 0.1531 +vn -0.2773 -0.9549 -0.1062 +vn -0.2641 -0.9288 -0.2599 +vn -0.2680 -0.9374 -0.2223 +vn -0.9127 -0.3842 0.1392 +vn -0.9014 -0.4126 0.1316 +vn -0.9066 -0.3999 0.1350 +vn -0.8959 -0.4255 0.1280 +vn -0.4170 0.0560 0.9072 +vn -0.8897 -0.4427 -0.1114 +vn -0.6954 0.7031 -0.1486 +vn 0.8866 0.4513 -0.1015 +vn 0.8980 0.4301 -0.0929 +vn 0.8878 0.4490 -0.1006 +vn 0.8993 0.4275 -0.0918 +vn 1.0000 0.0029 -0.0050 +vn 0.9972 0.0016 0.0754 +vn 0.9995 -0.0168 0.0284 +vn 0.9884 -0.1519 0.0018 +vn 0.9974 -0.0702 0.0143 +vn 0.9447 -0.2694 -0.1869 +vn 0.9969 -0.0725 0.0315 +vn 0.9848 -0.1733 0.0125 +vn 0.9927 -0.0874 -0.0826 +vn 1.0000 -0.0028 -0.0026 +vn 0.9997 -0.0075 -0.0237 +vn 0.9933 -0.0276 -0.1120 +vn 0.8259 0.0334 0.5629 +vn 0.9866 0.0226 0.1618 +vn 0.9235 -0.3816 -0.0395 +vn 0.7823 -0.5560 -0.2808 +vn 0.9562 0.2915 -0.0277 +vn -0.6637 -0.6822 0.3067 +vn 0.7160 0.6378 -0.2836 +vn 0.6015 -0.6273 0.4947 +vn 0.8722 -0.1332 -0.4707 +vn 0.9220 -0.1030 -0.3731 +vn -0.9995 -0.0179 0.0267 +vn -0.9570 -0.1103 0.2684 +vn -0.9974 -0.0374 0.0614 +vn -0.9325 -0.0670 -0.3550 +vn -0.9627 -0.0010 -0.2705 +vn -0.7569 0.5969 0.2661 +vn -0.9993 -0.0054 -0.0357 +vn -0.9780 0.1525 -0.1424 +vn -0.9901 0.1177 -0.0762 +vn -0.9428 0.2080 -0.2605 +vn -0.9392 0.0813 0.3337 +vn -0.9976 -0.0611 -0.0338 +vn -0.9741 -0.1745 -0.1438 +vn -0.9983 0.0539 -0.0225 +vn -0.0012 -0.1217 -0.9926 +vn -0.9345 0.3559 -0.0019 +vn -0.8314 0.5413 -0.1252 +vn -0.8793 0.4701 -0.0761 +vn -0.9564 0.2893 0.0392 +vn -0.0007 0.2923 0.9563 +vn -0.0007 0.2925 0.9563 +vn -0.0008 0.2923 0.9563 +vn -0.0013 0.2917 0.9565 +vn -0.0014 0.2916 0.9565 +vn -0.9303 0.3667 -0.0085 +vn -0.7487 0.6341 -0.1935 +vn -0.8319 0.5407 -0.1248 +vn -0.9561 0.2903 0.0389 +vn 0.0008 0.2928 0.9562 +vn 0.0007 0.2920 0.9564 +vn 0.0008 0.2927 0.9562 +vn 0.0009 0.2935 0.9559 +vn 0.0007 -0.1207 -0.9927 +vn -0.8989 -0.4365 0.0388 +vn -0.8734 -0.4867 0.0188 +vn -0.8876 -0.4597 0.0296 +vn -0.8632 -0.5048 0.0114 +vn -0.9398 -0.3211 0.1166 +vn -0.9030 -0.4200 0.0906 +vn -0.9240 -0.3677 0.1047 +vn -0.8823 -0.4642 0.0781 +vn -0.8905 -0.3953 0.2254 +vn -0.9748 -0.1410 0.1730 +vn -0.9816 -0.0996 0.1628 +vn 0.3377 0.5582 0.7579 +vn -0.9968 -0.0735 -0.0322 +vn -0.9696 -0.2042 -0.1346 +vn -0.9994 -0.0047 -0.0344 +vn -0.9997 -0.0199 -0.0146 +vn -0.9832 0.0203 -0.1814 +vn -0.9853 0.0518 -0.1630 +vn -0.9953 0.0223 -0.0943 +vn -0.8611 -0.4479 0.2408 +vn -0.8466 -0.4710 0.2481 +vn -0.9712 0.2232 -0.0836 +vn -0.9854 -0.1474 0.0854 +vn -0.9998 0.0144 0.0134 +vn -0.9995 -0.0050 0.0301 +vn -0.9962 0.0840 -0.0239 +vn -0.9998 -0.0006 -0.0177 +vn -0.6474 -0.7248 -0.2357 +vn -0.8834 0.4677 -0.0287 +vn -0.9972 0.0741 -0.0080 +vn -0.9999 0.0059 0.0121 +vn -0.9996 0.0115 0.0265 +vn 0.0160 0.9752 -0.2210 +vn -0.0088 0.9774 -0.2110 +vn 0.0051 0.9715 -0.2371 +vn -0.0171 0.9818 -0.1894 +vn 0.0097 0.9828 -0.1846 +vn 0.0194 0.9813 -0.1916 +vn -0.0123 0.9792 -0.2025 +vn -0.0512 0.9634 -0.2631 +vn 0.8173 0.0900 0.5692 +vn 0.8225 0.2266 0.5217 +vn 0.8219 0.2425 0.5154 +vn -0.9961 -0.0867 0.0166 +vn 0.0722 -0.4856 -0.8712 +vn 0.8796 0.4600 -0.1214 +vn 0.9567 0.2472 -0.1535 +vn 0.9348 0.3252 -0.1429 +vn 0.8315 0.5454 -0.1054 +vn 0.0025 -0.1227 -0.9924 +vn 0.0023 -0.1213 -0.9926 +vn 0.0022 -0.1221 -0.9925 +vn -0.0007 -0.1211 -0.9926 +vn -0.0011 -0.1208 -0.9927 +vn 0.0011 0.2927 0.9562 +vn 0.8627 -0.4663 0.1958 +vn 0.8878 -0.4317 0.1598 +vn 0.8732 -0.4524 0.1813 +vn 0.8994 -0.4136 0.1414 +vn -0.0005 0.2937 0.9559 +vn 0.8333 0.5425 -0.1060 +vn 0.9559 0.2507 -0.1528 +vn 0.9302 0.3392 -0.1406 +vn 0.7496 0.6569 -0.0811 +vn -0.0020 -0.1220 -0.9925 +vn -0.0020 -0.1230 -0.9924 +vn -0.0020 -0.1222 -0.9925 +vn -0.0021 -0.1211 -0.9926 +vn 0.8821 -0.4561 0.1182 +vn 0.9243 -0.3778 0.0541 +vn 0.9030 -0.4205 0.0886 +vn 0.9402 -0.3398 0.0240 +vn 0.9991 -0.0416 -0.0052 +vn 0.9999 0.0101 -0.0002 +vn 0.9975 0.0660 0.0269 +vn 0.9780 -0.0854 0.1901 +vn -0.2504 -0.8952 -0.3687 +vn 0.9994 -0.0285 -0.0174 +vn 0.9990 0.0029 -0.0450 +vn 0.9496 0.1933 0.2469 +vn 0.9984 0.0427 0.0377 +vn 0.9923 0.0644 0.1055 +vn 0.9939 0.1063 0.0301 +vn 0.9972 0.0420 -0.0623 +vn 0.0044 0.9756 -0.2194 +vn 0.0015 0.9749 -0.2228 +vn 0.0059 0.9765 -0.2153 +vn -0.0071 0.9792 -0.2027 +vn -0.0046 0.9777 -0.2101 +vn -0.0181 0.9798 -0.1991 +vn -0.0374 0.9705 -0.2383 +vn 0.0009 0.9916 -0.1291 +vn -0.0060 0.9898 -0.1422 +vn -0.7145 -0.1769 -0.6769 +vn -0.7075 -0.0197 -0.7064 +vn -0.7081 -0.0252 -0.7057 +vn 0.0576 -0.2830 -0.9574 +vn 0.0203 -0.1283 -0.9915 +vn 0.1233 -0.3076 -0.9435 +vn -0.0583 -0.2727 -0.9603 +vn -0.0887 -0.3261 -0.9412 +vn 0.2172 -0.0524 -0.9747 +vn 0.1098 -0.0865 -0.9902 +vn 0.9982 -0.0393 0.0462 +vn 0.9999 0.0076 -0.0105 +vn 0.9993 0.0334 -0.0148 +vn 0.9984 -0.0362 -0.0439 +vn 0.9951 0.0956 -0.0243 +vn 0.9960 0.0517 0.0724 +vn 0.9999 -0.0010 0.0167 +vn 0.9979 -0.0207 0.0612 +vn 0.9527 -0.2135 0.2162 +vn 0.9994 -0.0072 0.0328 +vn 0.9954 0.0884 -0.0363 +vn -0.3283 0.1730 -0.9286 +vn 1.0000 0.0001 0.0010 +vn 0.9984 0.0544 -0.0154 +vn 0.0051 0.2912 0.9566 +vn 0.0607 0.1503 0.9868 +vn 0.1286 0.0991 0.9867 +vn -0.1163 0.1052 0.9876 +vn -0.1011 0.1805 0.9784 +vn -0.0309 0.2676 0.9630 +vn -0.2281 0.3235 0.9183 +vn -0.0015 0.1797 0.9837 +vn -0.0047 0.1778 0.9841 +vn 0.7014 -0.7124 -0.0218 +vn -0.2154 0.2092 0.9539 +vn 0.5276 0.3921 0.7536 +vn 0.0007 0.2635 0.9647 +vn -0.1114 0.3070 0.9452 +vn -0.9998 -0.0094 0.0190 +vn -0.9938 0.1103 -0.0150 +vn -0.9977 0.0288 -0.0609 +vn -0.9999 0.0088 -0.0080 +vn 0.3290 0.5349 0.7783 +vn -0.9987 -0.0446 -0.0267 +vn -0.9996 0.0287 -0.0050 +vn -0.9996 0.0267 -0.0119 +vn -0.9979 -0.0511 -0.0390 +vn -0.9985 -0.0169 0.0516 +vn -0.9993 -0.0223 -0.0306 +vn -0.9999 0.0133 0.0028 +vn -0.9997 0.0220 0.0085 +vn -0.9999 -0.0035 -0.0115 +vn -0.9958 0.0912 -0.0054 +vn 0.0306 -0.1538 -0.9876 +vn 0.1126 -0.2983 -0.9478 +vn 0.0944 -0.2282 -0.9690 +vn -0.0744 -0.2600 -0.9627 +vn -0.1384 -0.3215 -0.9367 +vn -0.0169 -0.1704 -0.9852 +vn -0.0000 -0.1119 -0.9937 +vn 0.0808 -0.0836 -0.9932 +vn 0.9991 0.0424 -0.0084 +vn 0.9992 0.0382 -0.0080 +vn 0.8042 0.3935 0.4455 +vn -0.0167 0.2906 0.9567 +vn -0.0003 0.2424 0.9702 +vn 0.0001 0.2730 0.9620 +vn -0.0830 0.3213 0.9433 +vn -0.9997 0.0236 0.0013 +vn -0.9993 0.0365 -0.0110 +vn -0.6783 0.1562 -0.7180 +vn 0.0056 -0.1939 -0.9810 +vn 0.0116 -0.1731 -0.9848 +vn -0.0168 0.4932 -0.8698 +vn 0.0115 0.9757 -0.2187 +vn 0.0119 0.9756 -0.2191 +vn -0.0100 0.9761 -0.2170 +vn -0.0093 0.9762 -0.2165 +vn 0.0191 0.9777 -0.2091 +vn 0.0190 0.9776 -0.2094 +vn -0.0027 0.9860 -0.1670 +vn -0.0129 0.9807 -0.1949 +vn -0.0135 0.9807 -0.1949 +vn -0.0134 0.9953 -0.0961 +vn 0.0205 0.9773 -0.2109 +vn -0.0733 0.9460 0.3157 +vn 0.0012 0.2124 0.9772 +vn 0.0010 0.2129 0.9771 +vn 0.0007 0.2133 0.9770 +vn 0.0005 0.2137 0.9769 +vn -0.9999 0.0104 -0.0009 +vn -0.9999 0.0114 -0.0018 +vn -0.9999 0.0123 -0.0026 +vn -0.9999 0.0133 -0.0036 +vn -0.0012 -0.2047 -0.9788 +vn -0.0008 -0.2039 -0.9790 +vn -0.0003 -0.2031 -0.9792 +vn 0.0002 -0.2023 -0.9793 +vn 0.9999 0.0100 -0.0035 +vn 0.9999 0.0104 -0.0034 +vn 0.9999 0.0107 -0.0032 +vn 0.9999 0.0110 -0.0031 +vn 0.9999 0.0102 -0.0004 +vn 1.0000 0.0094 -0.0005 +vn -0.0016 0.2303 0.9731 +vn 0.0014 0.2222 0.9750 +vn -0.9998 0.0172 -0.0054 +vn -1.0000 0.0061 0.0020 +vn 0.0016 -0.1967 -0.9805 +vn 0.0006 -0.1994 -0.9799 +vn -0.0018 -0.2059 -0.9786 +vn -0.0028 -0.2085 -0.9780 +vn -0.0001 0.9782 -0.2078 +vn 0.0000 0.9782 -0.2078 +vn 0.0001 0.9781 -0.2079 +vn 0.0002 0.9781 -0.2081 +vn 0.3587 0.2394 0.9022 +vn 0.3591 0.1819 0.9154 +vn 0.2961 0.1568 0.9422 +vn -0.5978 0.3531 0.7197 +vn -0.4999 0.2391 0.8324 +vn -0.5260 0.2271 0.8196 +vn -0.6135 0.3509 0.7074 +vn -0.9743 -0.1675 -0.1507 +vn -0.9858 -0.0089 -0.1679 +vn -0.9851 -0.0112 -0.1716 +vn -0.9816 -0.0829 -0.1719 +vn -0.3628 -0.0951 -0.9270 +vn -0.1300 -0.2096 -0.9691 +vn -0.1753 -0.1926 -0.9655 +vn -0.3155 -0.1883 -0.9301 +vn 0.6363 0.0691 -0.7684 +vn 0.8026 -0.1631 -0.5738 +vn 0.7698 -0.1506 -0.6203 +vn 0.6149 0.0644 -0.7860 +vn 0.9572 -0.1345 0.2564 +vn 0.8396 0.1767 0.5136 +vn 0.9523 -0.0028 0.3053 +vn 0.7913 0.2099 0.5743 +vn -0.2065 -0.3201 -0.9246 +vn -0.2900 -0.2092 -0.9339 +vn 0.5598 0.3093 -0.7688 +vn 0.8995 0.3638 -0.2421 +vn 0.9307 -0.2433 0.2732 +vn 0.2065 0.0803 0.9751 +vn 0.2768 0.1710 0.9456 +vn -0.5629 0.5728 0.5958 +vn -0.9099 0.4069 0.0802 +vn -0.9534 -0.2742 -0.1258 +vn -0.0000 -0.9781 0.2080 +vn -0.0001 -0.9781 0.2079 +vn -0.0001 0.9781 -0.2080 +vn 0.0000 0.9782 -0.2077 +vn -0.3897 0.3572 0.8488 +vn -0.5143 0.2480 0.8209 +vn -0.4086 0.4045 0.8182 +vn -0.5415 0.2554 0.8009 +vn -0.9908 0.0716 0.1149 +vn -0.9909 -0.0173 0.1338 +vn -0.9922 -0.1193 0.0364 +vn -0.6611 -0.0062 -0.7503 +vn -0.8306 -0.0515 -0.5545 +vn -0.8010 -0.0729 -0.5942 +vn -0.6222 0.0411 -0.7818 +vn 0.3911 -0.1208 -0.9124 +vn 0.3439 -0.1598 -0.9253 +vn 0.3548 -0.1630 -0.9206 +vn 0.4904 -0.2688 -0.8290 +vn 0.9842 0.1630 -0.0687 +vn 0.9577 0.1339 0.2546 +vn 0.9765 0.2150 -0.0152 +vn 0.9297 0.1742 0.3246 +vn 0.5295 0.1322 0.8379 +vn 0.5299 0.1522 0.8343 +vn 0.4618 0.0344 0.8863 +vn -0.5794 0.2552 -0.7740 +vn 0.5895 -0.4101 -0.6959 +vn 0.5071 -0.2550 -0.8233 +vn 0.8807 0.4561 -0.1274 +vn 0.3647 -0.1020 0.9255 +vn 0.4335 -0.0153 0.9010 +vn -0.3566 0.5959 0.7195 +vn -0.9552 -0.2879 -0.0689 +vn -0.9953 -0.0967 0.0094 +vn -0.0000 -0.9782 0.2079 +vn -0.0003 -0.9777 -0.2099 +vn 0.0013 -0.9779 -0.2091 +vn -0.0013 -0.9779 -0.2090 +vn 0.0588 -0.9676 -0.2456 +vn -0.0027 -0.9719 -0.2355 +vn 0.0189 -0.9690 -0.2464 +vn -0.0068 -0.9793 -0.2024 +vn 0.0294 -0.9764 -0.2140 +vn 0.0814 -0.9889 -0.1243 +vn -0.0031 -0.9681 -0.2507 +vn 0.0063 -0.9789 -0.2042 +vn 0.0310 -0.9783 -0.2049 +vn 0.0067 -0.9767 -0.2144 +vn 0.0138 -0.9791 -0.2030 +vn -0.0338 -0.9776 -0.2076 +vn -0.0305 -0.9715 -0.2353 +vn -0.0065 -0.9777 -0.2099 +vn -0.0087 -0.9771 -0.2124 +vn -0.0292 -0.9790 -0.2018 +vn 0.0384 -0.9726 -0.2293 +vn -0.0652 -0.9610 -0.2688 +vn -0.0015 -0.9817 -0.1906 +vn 0.0033 -0.9806 -0.1959 +vn 0.0211 -0.9836 -0.1791 +vn -0.0041 -0.9831 -0.1829 +vn -0.0403 -0.9743 -0.2216 +vn -0.0173 -0.9839 -0.1780 +vn -0.0102 -0.9842 -0.1769 +vn 0.0178 -0.9839 -0.1778 +vn 0.0013 -0.1997 -0.9799 +vn 0.0028 -0.1972 -0.9804 +vn 0.0020 -0.1985 -0.9801 +vn 0.0005 -0.2010 -0.9796 +vn 0.0000 0.9783 -0.2072 +vn 0.0000 0.9783 -0.2071 +vn 0.0001 0.9789 -0.2044 +vn -0.1098 0.4949 -0.8620 +vn 0.0217 0.5150 -0.8569 +vn -0.0072 0.9824 -0.1865 +vn 0.0010 0.9825 -0.1860 +vn 0.0001 0.9848 -0.1739 +vn -0.0008 0.9782 -0.2078 +vn -0.0021 0.9776 -0.2104 +vn -0.0004 0.9782 -0.2078 +vn -0.0032 0.9752 -0.2212 +vn 0.0000 0.9785 -0.2063 +vn 0.0083 0.9761 -0.2171 +vn -0.0107 0.9780 -0.2082 +vn 0.0010 0.9779 -0.2092 +vn -0.0225 0.9859 -0.1657 +vn 0.0269 0.9728 -0.2300 +vn 0.0076 0.9760 -0.2175 +vn 0.0162 0.9766 -0.2145 +vn 0.0052 0.9781 -0.2079 +vn 0.0053 0.9781 -0.2079 +vn -0.0000 0.9796 -0.2010 +vn 0.0306 0.9782 -0.2054 +vn 0.0017 0.9769 -0.2135 +vn -0.0003 0.9781 -0.2080 +vn 0.0499 0.9768 -0.2084 +vn -0.0220 0.9778 -0.2086 +vn 0.0010 0.9732 -0.2299 +vn 0.0068 0.9813 -0.1924 +vn 0.0001 0.9790 -0.2038 +vn -0.0003 0.9789 -0.2043 +vn -0.0060 0.9768 -0.2140 +vn 0.0028 0.9791 -0.2035 +vn 0.0010 0.9779 -0.2091 +vn 0.0032 0.9788 -0.2046 +vn 0.0007 0.9779 -0.2089 +vn -0.0028 0.9755 -0.2200 +vn 0.0048 0.9784 -0.2068 +vn 0.0052 0.9778 -0.2094 +vn 0.0045 0.9788 -0.2047 +vn -0.0019 0.9797 -0.2003 +vn -0.0008 0.9800 -0.1988 +vn -0.0000 -0.9781 0.2079 +vn 0.0001 -0.9781 0.2079 +vn -0.0000 -0.9782 0.2078 +vn -0.0969 -0.6643 0.7411 +vn -0.0968 -0.6643 0.7411 +vn -0.0901 -0.6635 0.7428 +vn -0.1037 -0.6652 0.7394 +vn -0.8717 0.3518 0.3411 +vn 0.4160 0.6356 0.6504 +vn 0.5393 0.6241 0.5654 +vn 0.4940 0.6301 0.5991 +vn 0.3741 0.6362 0.6748 +vn 0.7400 -0.5252 -0.4202 +vn 0.7891 -0.4632 -0.4035 +vn 0.7557 -0.5064 -0.4153 +vn 0.8074 -0.4373 -0.3959 +vn -0.4163 -0.7075 -0.5711 +vn -0.9507 0.0231 -0.3092 +vn -0.1385 -0.7728 0.6194 +vn 0.0172 -0.7143 0.6996 +vn 0.0124 -0.6722 0.7403 +vn -0.1491 -0.6226 0.7682 +vn -0.1904 -0.7012 0.6870 +vn -0.1273 -0.6062 0.7850 +vn -0.1819 -0.8152 0.5498 +vn -0.0462 -0.7297 0.6822 +vn 0.0065 -0.6348 0.7727 +vn -0.6870 -0.2538 0.6809 +vn 0.1260 -0.0565 0.9904 +vn 0.7941 0.5279 -0.3012 +vn 0.7170 0.6549 -0.2388 +vn 0.8780 0.3704 -0.3030 +vn 0.4419 0.8734 -0.2046 +vn 0.2880 0.9517 -0.1065 +vn -0.2844 0.9299 -0.2331 +vn -0.2212 0.9738 -0.0535 +vn -0.5694 0.7272 -0.3835 +vn -0.6035 0.5997 -0.5255 +vn -0.6687 0.5208 -0.5307 +vn -0.5374 0.0214 -0.8430 +vn -0.5597 0.0125 -0.8286 +vn -0.5384 0.0210 -0.8424 +vn -0.4922 0.0389 -0.8696 +vn 0.4286 0.0090 -0.9035 +vn 0.1518 -0.0446 -0.9874 +vn 0.0876 0.0192 -0.9960 +vn 0.4228 -0.0562 -0.9045 +vn 0.6503 0.0520 -0.7579 +vn 0.6668 0.1253 -0.7346 +vn 0.0507 0.6644 -0.7456 +vn 0.1014 0.6642 -0.7406 +vn 0.0833 0.6702 -0.7375 +vn 0.1569 0.6725 -0.7233 +vn 0.1070 0.6774 -0.7278 +vn 0.1171 0.6703 -0.7328 +vn -0.0921 -0.6782 0.7291 +vn -0.1084 -0.6552 0.7476 +vn -0.0925 -0.6777 0.7295 +vn -0.0796 -0.6953 0.7143 +vn -0.8830 0.4307 0.1867 +vn -0.9396 0.3141 0.1360 +vn -0.8595 0.4690 0.2034 +vn 0.0542 0.6534 0.7551 +vn 0.7931 0.4704 0.3869 +vn 0.9250 -0.3768 -0.0485 +vn 0.1405 -0.6313 -0.7627 +vn -0.4701 -0.6649 -0.5805 +vn -0.9623 0.2495 0.1079 +vn -0.0822 -0.5250 0.8471 +vn -0.1339 -0.5821 0.8020 +vn -0.1633 -0.7295 0.6642 +vn -0.1622 -0.6934 0.7020 +vn -0.1857 -0.7844 0.5918 +vn -0.0583 -0.3994 0.9149 +vn -0.0047 -0.7049 0.7093 +vn -0.0370 -0.7605 0.6483 +vn 0.0481 -0.7010 0.7116 +vn -0.0296 -0.5814 0.8131 +vn 0.3357 -0.8278 0.4495 +vn -0.9247 0.1532 0.3485 +vn 0.6562 0.1123 -0.7462 +vn 0.7712 0.4666 -0.4330 +vn 0.8242 0.4079 -0.3929 +vn 0.6434 0.7496 -0.1553 +vn 0.5201 0.8359 -0.1754 +vn 0.2189 0.9740 -0.0589 +vn -0.1240 0.9768 -0.1744 +vn -0.2783 0.9600 -0.0311 +vn -0.4797 0.7852 -0.3915 +vn -0.3346 0.5253 -0.7824 +vn -0.6739 0.3401 -0.6559 +vn -0.4917 0.1757 -0.8528 +vn -0.1658 0.2895 -0.9427 +vn 0.2679 -0.1807 -0.9464 +vn -0.0939 -0.4089 -0.9077 +vn 0.0514 -0.2860 -0.9568 +vn 0.0731 0.5817 -0.8101 +vn 0.5012 0.0394 -0.8644 +vn 0.1055 0.6741 -0.7311 +vn 0.1128 0.6775 -0.7268 +vn 0.1098 0.6860 -0.7192 +vn 0.1533 0.8573 0.4914 +vn 0.1160 0.6143 0.7805 +vn 0.1419 0.7811 0.6080 +vn -0.0929 -0.6669 -0.7393 +vn -0.0794 -0.6639 -0.7436 +vn -0.1041 -0.6693 -0.7357 +vn -0.8558 -0.1733 0.4874 +vn -0.3520 -0.7270 0.5895 +vn 0.9083 -0.3455 0.2360 +vn 0.9364 -0.2789 0.2129 +vn 0.9271 -0.3027 0.2212 +vn 0.8995 -0.3637 0.2422 +vn 0.2340 0.7375 -0.6335 +vn 0.4775 0.5897 -0.6514 +vn 0.3979 0.6462 -0.6512 +vn 0.1655 0.7670 -0.6200 +vn -0.8819 0.3203 -0.3459 +vn -0.0528 -0.7613 -0.6462 +vn -0.1700 -0.7070 -0.6865 +vn -0.1771 -0.6330 -0.7537 +vn -0.2304 -0.6580 -0.7169 +vn -0.1544 -0.6035 -0.7823 +vn -0.1050 -0.7822 -0.6142 +vn -0.0181 -0.6719 -0.7404 +vn -0.0886 -0.6113 -0.7864 +vn -0.0370 -0.6522 -0.7572 +vn 0.0270 -0.7756 -0.6307 +vn 0.7658 0.6085 0.2080 +vn 0.7668 0.6084 0.2046 +vn 0.7670 0.6084 0.2038 +vn 0.7423 0.1084 0.6613 +vn 0.7361 0.2627 0.6239 +vn 0.6373 0.0709 0.7674 +vn 0.4510 -0.0727 0.8896 +vn 0.0346 -0.0478 0.9983 +vn -0.1088 -0.0715 0.9915 +vn -0.2936 0.0160 0.9558 +vn -0.2843 0.0192 0.9585 +vn -0.6663 0.4334 0.6068 +vn -0.7145 0.2524 0.6525 +vn -0.5740 0.5112 0.6397 +vn -0.3875 0.7084 0.5900 +vn -0.3771 0.9256 0.0338 +vn -0.6913 0.7207 0.0520 +vn -0.5258 0.8471 0.0767 +vn -0.1893 0.7810 0.5952 +vn -0.0530 0.9986 -0.0019 +vn 0.0873 0.9905 -0.1059 +vn 0.3505 0.9197 -0.1772 +vn 0.4524 0.8479 -0.2765 +vn 0.1520 0.7049 0.6929 +vn 0.3304 0.8020 0.4977 +vn -0.0153 0.6636 0.7479 +vn 0.7680 0.6083 0.2004 +vn 0.7825 -0.6226 -0.0011 +vn -0.0572 0.6056 0.7937 +vn -0.2873 0.4820 0.8277 +vn 0.1610 0.9128 0.3754 +vn -0.0774 -0.6744 -0.7343 +vn -0.0774 -0.6745 -0.7342 +vn -0.0726 -0.6817 -0.7280 +vn -0.0815 -0.6683 -0.7394 +vn -0.4704 -0.5591 0.6827 +vn -0.2891 -0.6857 0.6680 +vn -0.4162 -0.6017 0.6818 +vn -0.2127 -0.7269 0.6530 +vn 1.0000 -0.0009 -0.0015 +vn 0.9438 -0.3038 0.1303 +vn 0.9777 -0.1933 0.0822 +vn 0.9965 0.0761 -0.0350 +vn 0.4133 0.5549 -0.7220 +vn -0.5980 0.6876 -0.4117 +vn -0.9598 0.2038 -0.1929 +vn -0.2140 -0.6821 -0.6992 +vn -0.1753 -0.7345 -0.6555 +vn -0.2544 -0.6478 -0.7181 +vn -0.1263 -0.5974 -0.7919 +vn -0.0332 -0.5721 -0.8195 +vn -0.0457 -0.7398 -0.6712 +vn -0.0997 -0.7828 -0.6142 +vn -0.0270 -0.4611 -0.8869 +vn -0.0026 -0.6419 -0.7668 +vn 0.0247 -0.6791 -0.7337 +vn 0.0038 -0.7205 -0.6934 +vn 0.6005 0.0381 0.7987 +vn 0.8018 0.1131 0.5868 +vn 0.6569 0.0824 0.7495 +vn 0.1707 0.2901 0.9417 +vn 0.1999 -0.1297 0.9712 +vn -0.2661 -0.0218 0.9637 +vn -0.2449 -0.4013 0.8826 +vn -0.3647 0.5018 0.7844 +vn -0.6317 0.2335 0.7392 +vn -0.6832 0.5937 0.4252 +vn -0.4346 0.8633 0.2567 +vn -0.3507 0.9346 0.0588 +vn -0.0815 0.9917 0.0989 +vn 0.0032 0.9882 0.1534 +vn 0.6346 0.7600 0.1401 +vn 0.4642 0.8835 -0.0636 +vn 0.6236 0.7674 0.1493 +vn 0.7099 0.6363 0.3019 +vn 0.7032 0.6262 0.3368 +vn 0.1166 0.6518 0.7494 +vn 0.0924 0.6758 0.7313 +vn 0.0813 0.6909 0.7183 +vn -0.0967 0.9953 -0.0097 +vn -0.1061 0.9943 -0.0077 +vn -0.0966 0.9953 -0.0098 +vn -0.0876 0.9961 -0.0117 +vn -0.8988 -0.1226 -0.4209 +vn -0.8737 -0.0917 -0.4777 +vn -0.8563 -0.0725 -0.5114 +vn 0.5338 0.1146 -0.8378 +vn 0.8883 -0.0638 -0.4548 +vn 0.7652 0.1778 0.6188 +vn -0.1072 -0.0834 0.9907 +vn -0.3957 -0.0246 0.9180 +vn -0.1894 -0.0676 0.9796 +vn -0.4885 -0.0035 0.8726 +vn -0.9097 -0.1379 -0.3917 +vn -0.1011 0.9918 -0.0778 +vn -0.1940 0.9806 -0.0272 +vn -0.1629 0.9803 0.1114 +vn -0.1733 0.9808 -0.0896 +vn -0.1333 0.9720 0.1934 +vn -0.0056 0.9976 0.0692 +vn -0.1257 0.9813 0.1457 +vn -0.2011 0.9380 0.2823 +vn 0.0340 0.9983 0.0478 +vn 0.0361 0.9990 -0.0255 +vn -0.0225 0.9996 0.0191 +vn 0.7158 -0.5693 0.4043 +vn 0.7632 -0.6436 0.0583 +vn 0.7373 -0.6287 -0.2472 +vn 0.6250 -0.6392 -0.4481 +vn 0.6014 -0.5457 -0.5836 +vn 0.0852 -0.5831 -0.8079 +vn 0.0825 -0.5867 -0.8056 +vn 0.0848 -0.5837 -0.8076 +vn 0.0867 -0.5811 -0.8092 +vn -0.5688 -0.7058 -0.4224 +vn -0.5677 -0.7064 -0.4227 +vn -0.5636 -0.7091 -0.4237 +vn -0.5720 -0.7036 -0.4215 +vn -0.5847 -0.7280 0.3580 +vn -0.7594 -0.6270 0.1739 +vn -0.6142 -0.7168 0.3301 +vn -0.4653 -0.7627 0.4492 +vn -0.4610 -0.7651 0.4496 +vn 0.2375 -0.6793 0.6943 +vn -0.0094 -0.7093 0.7048 +vn 0.0758 -0.7332 0.6758 +vn 0.4878 -0.6637 0.5671 +vn 0.0906 -0.9955 -0.0264 +vn 0.1206 -0.9923 -0.0276 +vn 0.1207 -0.9923 -0.0271 +vn -0.0011 -0.9999 -0.0168 +vn 0.1002 -0.9947 -0.0245 +vn 0.1109 -0.9935 -0.0260 +vn 0.0848 -0.9961 -0.0255 +vn 0.1170 -0.9925 -0.0352 +vn 0.1240 -0.9866 -0.1060 +vn -0.0918 0.9957 -0.0110 +vn -0.0919 0.9957 -0.0109 +vn -0.0881 0.9960 -0.0117 +vn -0.0976 0.9952 -0.0097 +vn -0.7101 0.0471 -0.7025 +vn 0.1424 -0.0503 -0.9885 +vn 0.6392 0.1209 -0.7595 +vn 0.9830 0.0534 0.1756 +vn 0.9443 0.0971 0.3143 +vn 0.9748 0.0654 0.2134 +vn 0.9272 0.1109 0.3578 +vn -0.3328 0.0285 0.9426 +vn -0.4522 -0.0469 0.8907 +vn -0.4146 -0.0226 0.9097 +vn -0.2872 0.0559 0.9562 +vn -0.9799 -0.1575 -0.1226 +vn -0.1604 0.9854 -0.0569 +vn -0.2231 0.9740 0.0388 +vn -0.1595 0.9809 0.1113 +vn -0.1805 0.9798 -0.0861 +vn -0.1477 0.9718 0.1836 +vn -0.0975 0.9891 0.1100 +vn -0.0835 0.9930 0.0835 +vn -0.0381 0.9976 -0.0580 +vn -0.0306 0.9989 -0.0343 +vn -0.4835 0.8631 -0.1459 +vn 0.7429 0.6512 0.1552 +vn 0.1681 0.6746 -0.7187 +vn 0.6923 -0.6697 -0.2687 +vn 0.7131 -0.6584 0.2408 +vn 0.6886 -0.7112 0.1413 +vn 0.7557 -0.5736 -0.3161 +vn 0.3383 -0.7111 -0.6163 +vn -0.0248 -0.7371 -0.6753 +vn -0.3160 -0.6875 -0.6538 +vn -0.4995 -0.7484 -0.4362 +vn -0.6509 -0.7272 -0.2181 +vn -0.6636 -0.7449 -0.0696 +vn -0.7367 -0.6742 0.0526 +vn -0.4718 -0.6650 0.5790 +vn -0.5018 -0.6418 0.5799 +vn -0.4797 -0.6590 0.5793 +vn -0.4333 -0.6926 0.5766 +vn 0.4169 -0.6906 0.5910 +vn 0.2246 -0.6490 0.7269 +vn 0.1097 -0.7359 0.6682 +vn 0.4765 -0.6056 0.6374 +vn 0.0791 -0.9968 0.0106 +vn 0.0315 -0.9995 0.0061 +vn 0.1106 -0.9925 -0.0520 +vn 0.1248 -0.9907 0.0537 +vn 0.0001 -0.9781 0.2080 +vn 0.0088 -0.8127 -0.5826 +vn 0.1840 -0.7937 -0.5798 +vn -0.0135 -0.8133 -0.5816 +vn -0.2133 -0.8005 -0.5600 +vn 0.2457 -0.4279 -0.8698 +vn 0.3357 -0.8392 -0.4278 +vn -0.3145 -0.6821 -0.6601 +vn -0.3146 -0.6954 -0.6461 +vn -0.3076 -0.8295 -0.4662 +vn -0.3038 -0.5059 -0.8073 +vn 0.0137 -0.7806 -0.6249 +vn 0.0868 -0.7672 -0.6355 +vn 0.0123 -0.7808 -0.6247 +vn -0.0690 -0.7904 -0.6087 +vn -0.2033 0.6614 -0.7220 +vn -0.1743 0.6496 -0.7400 +vn -0.6062 0.5233 -0.5989 +vn -0.9970 0.0634 -0.0454 +vn -0.7454 -0.4700 0.4726 +vn -0.0635 -0.6606 0.7480 +vn 0.7993 -0.4323 0.4175 +vn 0.9883 0.1231 -0.0903 +vn -0.1587 0.6668 -0.7281 +vn 0.2826 0.6330 -0.7207 +vn -0.9210 0.2756 -0.2753 +vn -0.7669 0.4313 -0.4752 +vn -0.7797 0.4218 -0.4627 +vn -0.9278 0.2652 -0.2623 +vn -0.7469 -0.4683 0.4720 +vn -0.3155 -0.6327 0.7072 +vn 0.9188 -0.2627 0.2947 +vn 0.7509 -0.4640 0.4699 +vn 0.7650 -0.4515 0.4592 +vn 0.9279 -0.2461 0.2800 +vn 0.3341 0.6510 -0.6816 +vn 0.5802 0.5452 -0.6051 +vn 0.5643 0.5540 -0.6120 +vn 0.3155 0.6566 -0.6850 +vn -0.7687 0.2083 -0.6048 +vn -0.8616 0.0715 0.5025 +vn -0.9320 -0.0973 0.3492 +vn -0.9216 -0.0966 0.3760 +vn -0.5864 -0.6490 0.4847 +vn 0.2497 -0.1691 0.9534 +vn 0.8178 -0.5451 0.1844 +vn 0.7792 0.6254 0.0416 +vn 0.3316 0.4461 -0.8313 +vn -0.3536 0.7464 -0.5638 +vn -0.3567 0.7026 -0.6157 +vn -0.3567 0.7035 -0.6147 +vn -0.8392 -0.2896 -0.4603 +vn -0.8195 -0.1471 0.5539 +vn 0.0667 -0.6990 0.7120 +vn -0.0840 -0.7141 0.6950 +vn 0.0217 -0.6877 0.7256 +vn 0.2240 -0.6092 0.7607 +vn 0.7951 -0.6061 -0.0218 +vn 0.8784 -0.4376 0.1921 +vn 0.8831 -0.4176 0.2140 +vn 0.9508 0.3072 -0.0402 +vn 0.2791 0.2146 -0.9360 +vn 0.3097 0.4581 -0.8332 +vn 0.3126 0.4952 -0.8106 +vn -0.3157 0.7870 -0.5300 +vn -0.3579 0.6733 -0.6470 +vn 0.3183 0.6204 -0.7168 +vn 0.8913 0.2946 -0.3447 +vn 0.8943 -0.2889 0.3416 +vn 0.2770 -0.6678 0.6909 +vn 0.2937 -0.6651 0.6866 +vn -0.9906 0.0832 -0.1083 +vn -0.9864 0.0999 -0.1306 +vn -0.3142 -0.6821 -0.6603 +vn -0.3143 -0.6953 -0.6464 +vn -0.3073 -0.8296 -0.4663 +vn -0.3036 -0.5056 -0.8076 +vn -0.7875 0.4779 -0.3892 +vn -0.7546 0.5579 -0.3453 +vn -0.7682 0.5790 -0.2732 +vn -0.7965 0.4857 -0.3601 +vn -0.6398 -0.5400 0.5469 +vn -0.7439 -0.5391 0.3949 +vn -0.6371 -0.4525 0.6239 +vn -0.5656 -0.4893 0.6639 +vn 0.7076 -0.5227 0.4754 +vn 0.7063 -0.5382 0.4599 +vn 0.6771 -0.5095 0.5309 +vn 0.7440 -0.5612 0.3627 +vn 0.6912 0.6197 -0.3718 +vn 0.6961 0.4972 -0.5179 +vn 0.7505 0.5401 -0.3808 +vn 0.5787 0.5012 -0.6434 +vn -0.9626 0.1688 0.2118 +vn -0.9850 0.0948 0.1441 +vn -0.9947 0.0408 0.0942 +vn -0.9501 -0.0077 -0.3119 +vn -0.1130 -0.6757 0.7284 +vn -0.0124 -0.6081 0.7938 +vn -0.0798 -0.6948 0.7148 +vn -0.2576 -0.8115 0.5246 +vn 0.8763 -0.1703 0.4506 +vn 0.9096 -0.2432 -0.3368 +vn 0.9890 -0.0278 -0.1455 +vn 0.9844 -0.0527 -0.1681 +vn 0.4304 0.7892 -0.4381 +vn -0.1196 0.3954 -0.9107 +vn -0.1263 0.6065 -0.7850 +vn -0.1256 0.5701 -0.8119 +vn -0.1267 0.7034 -0.6994 +vn 0.7569 0.4172 -0.5030 +vn 0.9954 0.0886 -0.0377 +vn 0.6767 -0.5296 0.5115 +vn -0.0124 -0.6668 0.7451 +vn -0.5678 -0.5865 0.5775 +vn -0.9986 -0.0035 0.0532 +vn -0.8007 0.3782 -0.4646 +vn -0.0002 -0.6820 0.7313 +vn 0.0001 -0.6820 0.7313 +vn 0.0595 -0.7407 0.6692 +vn -0.0852 -0.6809 0.7274 +vn 0.0137 -0.7243 0.6893 +vn 0.0540 -0.6677 0.7425 +vn 0.0146 -0.6692 0.7429 +vn 0.1556 -0.7430 -0.6509 +vn 0.1638 0.6929 0.7022 +vn 0.2549 0.6822 0.6853 +vn 0.2370 0.6848 0.6892 +vn 0.1477 0.6941 0.7045 +vn 0.3338 0.6428 -0.6895 +vn 0.3425 0.6399 -0.6879 +vn 0.3418 0.6401 -0.6880 +vn 0.3331 0.6431 -0.6896 +vn 0.9259 -0.2842 0.2490 +vn 0.9533 -0.2137 0.2134 +vn 0.9143 -0.3093 0.2615 +vn 0.9623 -0.1855 0.1989 +vn -0.0356 -0.6937 -0.7194 +vn 0.0477 0.7665 0.6404 +vn -0.0330 -0.6841 -0.7287 +vn 0.9834 -0.1327 0.1240 +vn 0.9687 -0.1981 0.1498 +vn 0.9747 -0.1738 0.1403 +vn 0.9879 -0.1059 0.1133 +vn 0.9995 0.0311 0.0055 +vn 0.9994 0.0348 -0.0066 +vn 0.9996 0.0076 0.0261 +vn 0.9996 -0.0142 -0.0232 +vn 0.9994 -0.0332 -0.0081 +vn 0.9997 0.0021 -0.0260 +vn 0.9995 -0.0227 0.0222 +vn 0.9991 -0.0354 0.0237 +vn -0.9971 -0.0215 -0.0731 +vn -0.9980 0.0515 0.0355 +vn -0.9989 -0.0154 -0.0438 +vn -0.9984 0.0570 0.0016 +vn -0.0230 0.9309 -0.3646 +vn 0.0030 0.3728 -0.9279 +vn 0.0020 0.3546 -0.9350 +vn -0.0150 0.0045 -0.9999 +vn -0.0160 -0.0178 -0.9997 +vn 0.0115 -0.6906 -0.7231 +vn -0.0149 -0.9663 -0.2570 +vn 0.0000 -0.9147 0.4041 +vn -0.0008 -0.9090 0.4167 +vn -0.0162 -0.7555 0.6549 +vn -0.0170 -0.7452 0.6666 +vn 0.0019 -0.0180 0.9998 +vn 0.0006 0.0030 1.0000 +vn -0.0208 0.3437 0.9389 +vn -0.0221 0.3639 0.9312 +vn 0.0140 0.9859 0.1665 +vn -0.9955 0.0068 -0.0942 +vn -0.9964 0.0609 -0.0590 +vn -0.9961 -0.0301 -0.0828 +vn -0.9969 0.0716 -0.0337 +vn -0.9947 0.0642 0.0797 +vn -0.9941 0.0896 0.0618 +vn -0.9958 -0.0100 0.0915 +vn -0.9934 -0.0703 0.0902 +vn -0.9957 -0.0907 0.0199 +vn -0.9925 -0.1134 -0.0458 +vn 0.1719 0.6787 -0.7140 +vn -0.2046 0.3531 -0.9129 +vn 0.1613 -0.5927 -0.7891 +vn -0.1737 -0.8596 -0.4805 +vn 0.1356 -0.9730 0.1866 +vn -0.0133 -0.5136 0.8579 +vn -0.0062 -0.5056 0.8628 +vn -0.1455 -0.6504 0.7455 +vn 0.1306 -0.3370 0.9324 +vn -0.1440 0.4235 0.8944 +vn 0.1602 0.8438 0.5121 +vn 0.0310 0.9336 0.3570 +vn 0.0357 0.9311 0.3630 +vn -0.1083 0.9790 0.1728 +vn -0.1238 0.9744 0.1874 +vn -0.0016 0.9982 0.0592 +vn 0.0017 0.9984 0.0557 +vn 0.1239 0.9895 -0.0743 +vn -0.1239 -0.6496 0.7501 +vn -0.0017 -0.5505 0.8348 +vn 0.0016 -0.5476 0.8367 +vn 0.1237 -0.4305 0.8941 +vn -0.1237 -0.3248 -0.9376 +vn -0.0015 -0.4477 -0.8942 +vn 0.0018 -0.4508 -0.8926 +vn 0.1240 -0.5590 -0.8198 +vn -0.9513 -0.1613 -0.2628 +vn 0.9994 0.0155 0.0322 +vn 0.9993 0.0315 0.0217 +vn 0.9992 0.0210 0.0348 +vn 0.9994 0.0265 -0.0244 +vn 0.9995 0.0323 0.0031 +vn 0.9995 0.0064 -0.0320 +vn 0.9991 -0.0261 -0.0342 +vn 0.9993 -0.0111 -0.0358 +vn 0.9990 -0.0266 -0.0368 +vn -0.9973 0.0501 -0.0535 +vn -0.9956 0.0624 -0.0698 +vn -0.9998 -0.0210 -0.0044 +vn -0.9995 -0.0270 0.0136 +vn 0.0115 0.5723 0.8199 +vn -0.0089 0.3738 0.9275 +vn -0.0107 0.3552 0.9347 +vn 0.0126 0.5827 0.8126 +vn -0.0200 0.9995 -0.0252 +vn 0.0106 0.8418 -0.5396 +vn 0.0069 -0.1732 -0.9849 +vn -0.0101 0.2224 -0.9749 +vn -0.0113 0.2494 -0.9683 +vn 0.0077 -0.1917 -0.9814 +vn -0.0238 -0.7317 -0.6812 +vn 0.0167 -0.9574 0.2884 +vn 0.0151 -0.9522 0.3052 +vn -0.0117 -0.8261 0.5634 +vn -0.0141 -0.8111 0.5848 +vn -0.9898 0.1426 0.0069 +vn -0.9963 0.0624 0.0594 +vn -0.9955 0.0757 -0.0565 +vn -0.9911 -0.0241 0.1311 +vn -0.9908 -0.0742 0.1127 +vn -0.9955 -0.0949 -0.0012 +vn -0.9910 -0.1064 -0.0809 +vn -0.9954 -0.0214 -0.0939 +vn -0.9943 0.0390 -0.0990 +vn 0.2086 0.6379 0.7413 +vn -0.0614 0.9902 -0.1254 +vn -0.0614 0.9902 -0.1255 +vn -0.1927 0.9799 0.0519 +vn 0.0951 0.9413 -0.3239 +vn -0.0453 0.2998 -0.9529 +vn -0.0471 0.3017 -0.9522 +vn -0.0729 0.3285 -0.9417 +vn -0.0153 0.2681 -0.9633 +vn 0.0346 -0.6768 -0.7353 +vn -0.0309 -0.7292 -0.6836 +vn -0.0317 -0.7299 -0.6829 +vn -0.0912 -0.7714 -0.6297 +vn 0.0993 -0.9661 0.2385 +vn 0.0830 -0.8281 0.5544 +vn 0.0124 -0.9195 0.3929 +vn 0.0408 -0.7656 0.6421 +vn 0.1545 -0.5554 0.8171 +vn -0.1977 0.1101 0.9741 +vn -0.1237 -0.9376 0.3248 +vn -0.0015 -0.8942 0.4477 +vn 0.0018 -0.8926 0.4508 +vn 0.1240 -0.8198 0.5590 +vn 0.1722 -0.1263 -0.9769 +vn 0.1521 -0.1046 -0.9828 +vn 0.1481 -0.1003 -0.9839 +vn 0.1239 -0.0743 -0.9895 +vn -0.1227 0.7425 0.6585 +vn 0.0223 0.8119 0.5834 +vn 0.0661 0.8278 0.5571 +vn 0.2602 0.8700 0.4189 +vn -0.9629 0.2089 -0.1706 +vn 0.9999 -0.0128 -0.0086 +vn 0.9975 0.0325 0.0620 +vn 0.9980 0.0311 0.0555 +vn 0.9983 0.0301 0.0506 +vn 0.9984 0.0295 0.0474 +vn -0.9911 0.0407 0.1264 +vn -0.9954 0.0922 0.0268 +vn -0.9888 0.0823 -0.1243 +vn 0.0024 -0.9627 0.2705 +vn -0.0460 -0.9911 -0.1250 +vn -0.0526 -0.9819 -0.1818 +vn 0.0085 -0.9482 0.3176 +vn -0.0426 -0.4486 0.8927 +vn 0.0325 0.2948 0.9550 +vn -0.0387 0.7771 0.6282 +vn 0.0059 0.9469 -0.3214 +vn 0.0043 0.9438 -0.3304 +vn -0.0075 0.9179 -0.3968 +vn -0.0099 0.9121 -0.4098 +vn 0.0104 -0.3817 -0.9242 +vn -0.0063 -0.2648 -0.9643 +vn -0.0095 -0.2420 -0.9702 +vn 0.0121 -0.3934 -0.9193 +vn -0.9935 0.0196 -0.1119 +vn -0.9916 0.1112 0.0661 +vn -0.9953 0.0694 -0.0674 +vn -0.9895 0.1320 0.0595 +vn -0.9933 -0.0997 -0.0579 +vn -0.9927 -0.0578 -0.1060 +vn -0.9940 -0.1092 -0.0009 +vn -0.9947 -0.0074 0.1023 +vn -0.9917 -0.0856 0.0959 +vn -0.1655 -0.8278 -0.5360 +vn 0.1791 -0.9499 0.2561 +vn 0.0032 -0.8824 0.4704 +vn 0.0296 -0.8972 0.4407 +vn -0.1391 -0.7756 0.6157 +vn 0.1696 -0.2833 0.9439 +vn -0.0715 0.5610 0.8247 +vn -0.0691 0.5634 0.8233 +vn -0.1260 0.5069 0.8528 +vn -0.0024 0.6238 0.7816 +vn -0.0563 0.9881 -0.1428 +vn -0.0459 0.9874 -0.1517 +vn 0.0002 0.9817 -0.1907 +vn -0.1198 0.9889 -0.0878 +vn 0.2170 0.6628 -0.7167 +vn -0.1115 0.0745 -0.9910 +vn 0.1779 -0.3948 -0.9014 +vn -0.0946 -0.5671 -0.8182 +vn -0.0538 -0.5874 -0.8075 +vn -0.0013 -0.6114 -0.7913 +vn 0.0807 -0.6445 -0.7603 +vn -0.3103 0.8603 0.4045 +vn 0.5448 0.8251 -0.1497 +vn 0.4659 -0.6055 0.6452 +vn 0.5959 -0.4277 0.6797 +vn 0.5972 -0.4255 0.6799 +vn 0.6898 -0.2443 0.6816 +vn -0.9361 0.0861 0.3409 +vn -0.9388 0.1832 -0.2917 +vn -0.4519 -0.4487 0.7710 +vn -0.3767 -0.5613 0.7369 +vn -0.4805 -0.3995 0.7807 +vn 0.6045 0.0708 0.7934 +vn -0.4987 0.5857 0.6389 +vn 0.4861 0.7579 -0.4350 +vn 0.2215 0.7848 -0.5788 +vn 0.4306 0.7700 -0.4707 +vn 0.1078 0.7753 -0.6223 +vn -0.2800 -0.4709 -0.8366 +vn 0.3388 -0.6325 -0.6965 +vn -0.1756 0.8327 -0.5251 +vn 0.5640 0.8053 0.1829 +vn -0.6051 0.3044 0.7357 +vn 0.4940 -0.0831 0.8655 +vn -0.4596 -0.7813 0.4223 +vn 0.2997 -0.9241 0.2370 +vn -0.3074 -0.5185 -0.7979 +vn 0.0751 -0.4464 -0.8917 +vn -0.2460 -0.5122 -0.8229 +vn 0.1502 -0.4235 -0.8934 +vn -0.0807 0.6207 -0.7799 +vn -0.1164 0.6272 -0.7701 +vn -0.0679 0.6182 -0.7831 +vn -0.1259 0.6288 -0.7673 +vn -0.5494 -0.2606 0.7939 +vn 0.2837 0.5169 0.8076 +vn -0.3720 -0.6013 -0.7071 +vn 0.6133 -0.7867 0.0702 +vn -0.3152 -0.8112 0.4926 +vn -0.0817 0.1744 0.9813 +vn 0.6588 0.4092 0.6313 +vn -0.5794 0.8146 0.0263 +vn 0.4668 0.5687 -0.6773 +vn 0.8674 0.4732 0.1541 +vn 0.9794 0.1753 0.1005 +vn 0.8276 0.5541 0.0896 +vn -0.6228 -0.5732 0.5325 +vn 0.4246 -0.8843 0.1941 +vn -0.3524 -0.7413 -0.5713 +vn 0.0203 -0.6914 -0.7222 +vn -0.2806 -0.7411 -0.6100 +vn 0.1249 -0.6570 -0.7435 +vn 0.0001 0.2126 -0.9771 +vn 0.1509 0.1654 -0.9746 +vn -0.0667 0.2317 -0.9705 +vn 0.2384 0.1356 -0.9617 +vn -0.3310 0.8151 -0.4755 +vn 0.3920 0.9049 -0.1658 +vn -0.3992 0.7557 0.5192 +vn 0.1787 0.6560 0.7333 +vn -0.7101 -0.6894 -0.1433 +vn -0.2847 -0.8634 0.4166 +vn -0.9986 -0.0170 0.0509 +vn -0.9994 -0.0066 0.0334 +vn -0.9855 -0.1029 0.1345 +vn -0.9821 -0.1211 0.1443 +vn 0.9722 0.1679 0.1631 +vn 0.9997 -0.0088 -0.0210 +vn 0.9995 -0.0166 0.0265 +vn 0.9997 -0.0248 0.0075 +vn 0.9997 -0.0093 -0.0247 +vn 0.9996 0.0058 0.0289 +vn 0.9997 0.0216 0.0129 +vn 0.9998 0.0191 -0.0038 +vn -0.9999 0.0095 -0.0143 +vn -0.9970 0.0103 0.0773 +vn -0.9945 0.0323 0.0997 +vn -0.9976 -0.0275 -0.0638 +vn 0.0233 -0.4056 0.9138 +vn 0.0006 -0.6198 0.7847 +vn -0.0012 -0.6354 0.7721 +vn 0.0244 -0.3942 0.9187 +vn -0.0222 0.5554 0.8313 +vn -0.0032 0.9978 0.0667 +vn 0.0147 0.9960 -0.0883 +vn 0.0163 0.9946 -0.1022 +vn -0.0042 0.9971 0.0759 +vn -0.0141 0.1229 -0.9923 +vn -0.0072 0.0485 -0.9988 +vn -0.0068 0.0442 -0.9990 +vn -0.0145 0.1276 -0.9917 +vn 0.0030 -0.8751 -0.4840 +vn 0.0018 -0.8827 -0.4699 +vn -0.0191 -0.9768 -0.2134 +vn -0.0204 -0.9803 -0.1965 +vn -0.9875 0.1039 0.1182 +vn -0.9950 -0.0965 0.0247 +vn -0.9954 -0.0016 0.0959 +vn -0.9936 -0.1017 0.0482 +vn -0.9954 -0.0778 -0.0553 +vn -0.9957 -0.0426 -0.0828 +vn -0.9957 -0.0018 -0.0923 +vn -0.9955 0.0669 -0.0664 +vn -0.9938 0.0865 -0.0698 +vn -0.9955 0.0946 0.0104 +vn 0.0348 -0.5238 0.8511 +vn 0.0456 -0.5160 0.8554 +vn -0.0052 -0.5520 0.8338 +vn 0.0818 -0.4889 0.8685 +vn 0.0422 0.7692 0.6377 +vn 0.0700 0.7846 0.6160 +vn -0.0543 0.7070 0.7051 +vn 0.1542 0.8246 0.5443 +vn -0.1536 0.9441 -0.2915 +vn 0.1650 0.4623 -0.8712 +vn 0.1642 0.4630 -0.8710 +vn 0.2085 0.4246 -0.8811 +vn 0.1353 0.4869 -0.8629 +vn -0.1354 -0.4794 -0.8671 +vn 0.2139 -0.8672 -0.4496 +vn 0.0941 -0.9437 -0.3171 +vn 0.0963 -0.9426 -0.3196 +vn -0.0645 -0.9895 -0.1297 +vn -0.0912 -0.3260 -0.9410 +vn 0.4922 0.3316 -0.8049 +vn -0.2678 0.9461 0.1819 +vn 0.1108 -0.6506 0.7513 +vn 0.2714 -0.5054 0.8191 +vn 0.2795 -0.4970 0.8215 +vn 0.4077 -0.3479 0.8443 +vn -0.9590 0.0275 0.2822 +vn 0.0586 0.9242 0.3774 +vn -0.1218 0.9770 0.1750 +vn 0.0295 0.9332 0.3582 +vn -0.1695 0.9731 0.1563 +vn 0.1234 0.2179 -0.9681 +vn -0.0148 0.1678 -0.9857 +vn 0.0866 0.2049 -0.9749 +vn -0.0545 0.1526 -0.9868 +vn 0.0476 -0.9135 -0.4040 +vn -0.0517 -0.9318 -0.3593 +vn 0.0106 -0.9216 -0.3879 +vn -0.0863 -0.9355 -0.3427 +vn 0.1161 -0.7557 0.6445 +vn -0.0215 -0.7135 0.7003 +vn 0.0690 -0.7432 0.6655 +vn -0.0591 -0.6990 0.7126 +vn -0.5205 -0.8438 -0.1306 +vn 0.5452 0.0385 -0.8374 +vn -0.4396 0.6348 -0.6354 +vn 0.5048 0.8417 -0.1915 +vn -0.6378 0.6669 0.3853 +vn 0.5514 0.3830 0.7411 +vn -0.3926 -0.4976 0.7735 +vn -0.1963 -0.4850 0.8522 +vn -0.4895 -0.4952 0.7178 +vn -0.1432 -0.4781 0.8666 +vn 0.1045 -0.9788 -0.1762 +vn -0.0854 -0.9676 -0.2376 +vn 0.1570 -0.9749 -0.1577 +vn -0.1381 -0.9575 -0.2531 +vn 0.0772 -0.4089 -0.9093 +vn 0.0496 0.8497 0.5249 +vn -0.9882 0.0662 -0.1378 +vn -0.9498 0.1355 -0.2819 +vn -0.9924 0.0532 -0.1108 +vn 0.9867 0.0483 -0.1551 +vn 0.9939 0.0327 -0.1049 +vn 0.9504 0.0926 -0.2970 +vn -0.4508 0.5488 -0.7040 +vn -0.3472 0.6983 -0.6259 +vn -0.4795 0.4978 -0.7227 +vn 0.3952 0.3342 -0.8557 +vn -0.3987 -0.7495 -0.5285 +vn 0.3459 -0.6190 -0.7051 +vn -0.3848 -0.7630 0.5194 +vn 0.5138 -0.3753 0.7715 +vn -0.4175 0.2881 0.8618 +vn 0.3138 0.8010 0.5098 +vn 0.6528 0.2594 0.7117 +vn -0.1316 -0.9148 -0.3820 +vn 0.0392 -0.2292 -0.9726 +vn -0.1411 -0.1622 -0.9766 +vn 0.0954 -0.2485 -0.9639 +vn -0.1894 -0.1430 -0.9714 +vn 0.2640 0.6199 -0.7389 +vn -0.5527 0.7550 -0.3528 +vn 0.5066 0.8565 0.0989 +vn -0.4701 0.4046 0.7844 +vn 0.0356 0.2959 0.9546 +vn 0.0483 -0.6562 0.7530 +vn -0.1961 -0.7063 0.6803 +vn 0.1318 -0.6287 0.7664 +vn -0.2586 -0.7116 0.6533 +vn -0.5682 0.2972 -0.7674 +vn 0.4821 -0.6042 -0.6345 +vn -0.9970 -0.0780 0.0016 +vn -0.9646 -0.2638 0.0056 +vn -0.9336 -0.3583 0.0075 +vn 0.9838 -0.1639 0.0729 +vn 0.9402 -0.3113 0.1385 +vn 0.9920 -0.1156 0.0514 +vn 0.9992 -0.0399 0.0099 +vn 0.9994 0.0088 -0.0326 +vn 0.9985 0.0375 0.0392 +vn -0.9993 0.0252 0.0276 +vn -0.9972 -0.0220 0.0710 +vn -0.9993 0.0226 0.0300 +vn -0.9975 0.0689 -0.0128 +vn 0.0638 -0.6527 0.7549 +vn -0.0860 -0.9953 -0.0440 +vn 0.0270 -0.7076 -0.7061 +vn -0.0857 -0.0252 -0.9960 +vn 0.0453 0.6956 -0.7170 +vn -0.0703 0.9923 0.1018 +vn -0.0553 0.9803 0.1895 +vn 0.0057 0.8615 0.5077 +vn 0.0209 0.8158 0.5779 +vn -0.0797 0.0538 0.9954 +vn -0.9848 0.0031 -0.1734 +vn -0.9712 0.2384 0.0023 +vn -0.9916 0.0943 -0.0882 +vn -0.9920 -0.1260 0.0059 +vn -0.9897 -0.1428 -0.0128 +vn -0.9909 -0.0819 0.1069 +vn -0.9855 0.0019 0.1698 +vn -0.9918 0.0871 0.0933 +vn -0.9905 -0.0721 -0.1173 +vn -0.1465 -0.8855 0.4410 +vn 0.1745 -0.9636 -0.2026 +vn 0.0476 -0.9130 -0.4051 +vn 0.0627 -0.9218 -0.3825 +vn -0.0746 -0.8155 -0.5740 +vn 0.1065 -0.3615 -0.9263 +vn -0.1875 0.0920 -0.9780 +vn 0.2346 0.7065 -0.6677 +vn -0.2107 0.9762 0.0523 +vn -0.1148 0.9815 0.1535 +vn -0.1325 0.9819 0.1352 +vn -0.0005 0.9636 0.2674 +vn 0.0817 0.2000 0.9764 +vn -0.0100 0.0984 0.9951 +vn -0.0150 0.0927 0.9956 +vn -0.0934 0.0040 0.9956 +vn 0.1035 -0.6000 0.7933 +vn 0.6338 -0.2109 0.7442 +vn 0.5539 -0.2889 0.7809 +vn 0.4668 -0.3626 0.8066 +vn 0.2740 -0.4945 0.8249 +vn 0.0040 -0.6766 -0.7363 +vn 0.7930 0.3132 -0.5225 +vn 0.1947 0.9427 -0.2710 +vn 0.9706 0.1464 0.1910 +vn 0.9949 0.0140 0.0996 +vn 0.9960 -0.0085 0.0893 +vn 0.9995 0.0200 0.0234 +vn -1.0000 -0.0002 -0.0004 +vn -1.0000 -0.0002 -0.0003 +vn 0.9604 0.1185 0.2521 +vn 0.9771 0.0572 0.2051 +vn 0.9797 0.0483 0.1947 +vn 0.9995 0.0299 -0.0031 +vn 0.9985 0.0447 0.0330 +vn 0.9497 0.1363 0.2819 +vn -0.9967 0.0707 0.0400 +vn -0.8802 0.1364 0.4545 +vn -0.9169 0.1732 0.3596 +vn -0.9572 0.0841 0.2770 +vn -0.9986 0.0527 -0.0029 +vn -0.9884 0.0594 0.1398 +vn 0.9604 0.1185 0.2520 +vn 0.9497 0.1362 0.2818 +vn -0.9931 0.1062 0.0498 +vn -0.8966 0.1661 0.4105 +vn -0.8929 0.1800 0.4126 +vn -0.9564 0.0858 0.2793 +vn -0.9964 0.0842 -0.0046 +vn -0.9887 0.0585 0.1378 +vn -0.8965 0.1662 0.4106 +vn -0.8929 0.1800 0.4128 +vn 0.9801 0.0782 0.1825 +vn 0.9855 0.0565 0.1598 +vn 0.9865 0.0526 0.1550 +vn 0.9996 0.0104 0.0247 +vn 0.9752 0.0883 0.2028 +vn 0.9805 0.0772 0.1808 +vn 0.9857 0.0564 0.1589 +vn 0.9866 0.0525 0.1542 +vn 0.9996 0.0105 0.0247 +vn 0.9757 0.0872 0.2009 +vn -0.9982 -0.0582 0.0164 +vn -0.9986 -0.0260 0.0457 +vn -0.9922 0.0487 0.1145 +vn -0.9898 0.0576 0.1302 +vn -0.0614 0.5427 0.8377 +vn -0.0001 0.5506 0.8347 +vn -0.0673 0.5418 0.8378 +vn 0.0062 0.5513 0.8343 +vn 0.0134 0.6035 0.7972 +vn 0.0134 0.6036 0.7972 +vn 0.0112 0.6037 0.7972 +vn 1.0000 0.0078 -0.0040 +vn 0.9958 0.0862 -0.0311 +vn 0.9621 0.2716 0.0258 +vn 0.9995 0.0078 0.0298 +vn 0.9896 0.1361 0.0475 +vn 0.9891 0.1340 0.0617 +vn 0.9997 -0.0025 0.0255 +vn -1.0000 -0.0000 -0.0003 +vn -1.0000 0.0000 -0.0004 +vn -0.9999 0.0011 0.0141 +vn -0.9949 -0.0982 -0.0210 +vn -0.9674 0.2461 0.0594 +vn -1.0000 0.0001 -0.0031 +vn -0.9736 0.2280 0.0054 +vn -0.9993 0.0161 0.0326 +vn 0.9868 0.0026 0.1620 +vn 0.9881 0.0051 0.1535 +vn 0.9879 0.0046 0.1552 +vn 0.9856 0.0004 0.1692 +vn -0.9851 0.0021 0.1720 +vn -0.9863 0.0043 0.1648 +vn -0.9866 0.0048 0.1629 +vn -0.9837 -0.0002 0.1799 +vn -0.9985 -0.0517 -0.0195 +vn -0.9782 0.2072 -0.0136 +vn -0.9995 0.0321 -0.0080 +vn -0.9728 0.2303 0.0247 +vn -0.9620 0.2580 0.0894 +vn -0.9875 0.1314 0.0868 +vn -0.9997 0.0179 0.0186 +vn 0.9998 0.0174 -0.0079 +vn 0.9832 0.1673 -0.0730 +vn 0.9866 0.1496 -0.0653 +vn 0.9914 0.1296 -0.0194 +vn 0.9908 0.1322 -0.0280 +vn 0.9987 -0.0500 0.0135 +vn 1.0000 0.0001 0.0023 +vn -0.9862 -0.0030 0.1657 +vn -0.9874 -0.0052 0.1582 +vn -0.9845 -0.0002 0.1754 +vn -0.9877 -0.0058 0.1562 +vn 0.9999 0.0123 0.0002 +vn 0.9993 0.0087 0.0350 +vn 0.9836 0.1771 0.0346 +vn 0.9862 0.1546 0.0586 +vn 0.9995 -0.0036 0.0298 +vn -0.9997 0.0196 -0.0132 +vn -0.9971 0.0524 -0.0559 +vn -0.9976 0.0475 -0.0506 +vn 0.0426 0.9988 0.0221 +vn -0.9877 0.1441 -0.0605 +vn -0.9853 0.1578 -0.0662 +vn -1.0000 0.0078 -0.0020 +vn -0.9942 0.1076 0.0003 +vn -0.9729 0.2191 0.0744 +vn -0.9893 0.1228 0.0793 +vn -0.9997 0.0159 0.0166 +vn 0.9922 0.1050 -0.0668 +vn 0.9998 0.0132 -0.0145 +vn 0.9729 0.2202 -0.0704 +vn 0.9917 0.1288 -0.0017 +vn 1.0000 0.0056 0.0011 +vn 0.9854 0.0036 0.1701 +vn 0.9877 0.0076 0.1564 +vn 0.9872 0.0068 0.1591 +vn 0.9835 0.0004 0.1809 +vn 0.4919 0.6757 0.5491 +vn 0.4248 0.6893 0.5869 +vn 0.5017 0.6733 0.5431 +vn 1.0000 0.0044 -0.0021 +vn 0.9957 0.0912 -0.0177 +vn 0.9620 0.2713 0.0297 +vn 0.9765 -0.1991 -0.0827 +vn 0.9999 -0.0114 -0.0016 +vn 0.9969 0.0714 0.0342 +vn 0.9716 -0.2184 -0.0907 +vn -1.0000 -0.0078 -0.0034 +vn -0.9908 -0.1241 -0.0541 +vn -0.9927 -0.1109 -0.0483 +vn -0.9590 0.2827 -0.0222 +vn -0.9670 0.2543 -0.0164 +vn -0.9871 0.1451 -0.0671 +vn -0.9996 -0.0020 -0.0280 +vn -0.9994 0.0090 -0.0326 +vn 0.0310 0.8075 0.5891 +vn 0.2377 0.8107 0.5351 +vn -0.0063 0.8030 0.5959 +vn 0.2574 0.8090 0.5285 +vn -0.4393 0.8522 0.2841 +vn 0.5036 0.8586 0.0957 +vn -0.5036 0.8586 -0.0957 +vn 0.4393 0.8523 -0.2841 +vn -0.2379 0.8106 -0.5351 +vn -0.0311 0.8075 -0.5891 +vn -0.2576 0.8089 -0.5284 +vn 0.0063 0.8030 -0.5960 +vn -0.0139 0.8029 0.5959 +vn 0.5060 0.7221 0.4717 +vn -0.7324 0.6459 0.2153 +vn 0.7886 0.6111 0.0681 +vn -0.7886 0.6111 -0.0681 +vn 0.7324 0.6459 -0.2153 +vn -0.5060 0.7221 -0.4717 +vn 0.0138 0.8029 -0.5959 +vn -0.0172 -0.0054 0.9998 +vn 0.0170 0.0074 0.9998 +vn -0.0308 -0.0106 0.9995 +vn 0.0305 0.0125 0.9995 +vn 0.0019 0.9419 0.3360 +vn 0.0161 0.9736 0.2277 +vn 0.0026 0.9374 0.3483 +vn 0.0240 0.8353 0.5493 +vn -0.0099 0.7613 0.6483 +vn 0.0160 0.8736 0.4864 +vn -0.0087 0.7577 0.6525 +vn 0.0210 0.8730 0.4873 +vn 0.9999 0.0107 -0.0110 +vn 0.9764 0.0597 -0.2078 +vn 0.9972 0.0473 -0.0583 +vn 0.9957 -0.0112 -0.0922 +vn 1.0000 -0.0013 -0.0055 +vn -0.9745 0.0805 -0.2093 +vn -0.9988 0.0479 -0.0134 +vn -0.9983 0.0531 -0.0246 +vn -1.0000 -0.0022 -0.0067 +vn -0.9986 -0.0094 -0.0530 +vn -0.9809 0.1037 -0.1644 +vn -0.0060 0.5959 -0.8030 +vn 0.0123 0.4987 -0.8667 +vn -0.0193 0.5982 -0.8011 +vn -0.0290 0.4079 -0.9126 +vn 0.0276 0.1651 -0.9859 +vn -0.0493 0.0161 -0.9987 +vn 0.1476 -0.1393 -0.9792 +vn 0.1619 -0.1404 -0.9768 +vn -0.1271 -0.5437 -0.8296 +vn -0.0059 -0.5630 -0.8264 +vn -0.1368 -0.5418 -0.8293 +vn 0.0077 -0.5647 -0.8253 +vn 0.9998 -0.0081 -0.0184 +vn 0.9769 -0.0767 -0.1996 +vn 0.9986 -0.0130 -0.0513 +vn 0.8938 0.1348 -0.4277 +vn 0.9767 0.1074 -0.1859 +vn 0.9315 0.0491 -0.3603 +vn 0.8760 -0.0363 -0.4809 +vn 0.9548 -0.0951 -0.2816 +vn 0.9757 -0.0841 -0.2024 +vn 0.9986 -0.0523 -0.0122 +vn -0.9997 -0.0089 -0.0208 +vn -0.9792 -0.0694 -0.1906 +vn -0.9851 -0.0398 -0.1675 +vn -0.9776 -0.0803 -0.1947 +vn -0.9160 -0.0022 -0.4012 +vn -0.9572 0.0017 -0.2893 +vn -0.8794 0.1331 -0.4571 +vn -0.9784 0.1112 -0.1742 +vn -0.9988 -0.0038 -0.0483 +vn -0.9986 -0.0530 -0.0027 +vn -0.0420 0.5898 -0.8065 +vn 0.0174 -0.5892 -0.8078 +vn 0.7926 0.1319 -0.5953 +vn 0.7298 0.1347 -0.6702 +vn 0.9317 0.1581 -0.3272 +vn 0.9805 0.0130 -0.1960 +vn 0.9814 0.0244 -0.1905 +vn 0.9814 0.0596 -0.1825 +vn 0.9780 -0.0629 -0.1988 +vn 0.9839 -0.0248 -0.1770 +vn 0.9901 -0.0620 -0.1258 +vn 0.9990 0.0224 -0.0374 +vn 0.9987 0.0510 -0.0095 +vn 0.9995 0.0324 0.0033 +vn 0.9984 0.0470 -0.0310 +vn -0.9998 -0.0078 -0.0180 +vn -0.9808 -0.0707 -0.1817 +vn -0.9731 -0.0684 -0.2200 +vn -0.9776 -0.0775 -0.1957 +vn -0.9261 -0.0303 -0.3761 +vn -0.9415 0.0229 -0.3362 +vn -0.8771 0.1397 -0.4595 +vn -0.9766 0.1135 -0.1826 +vn -0.9988 -0.0056 -0.0494 +vn -0.9988 -0.0490 -0.0076 +vn -0.0140 0.5891 -0.8080 +vn 0.0160 -0.5892 -0.8078 +vn 0.9981 -0.0507 -0.0357 +vn 0.9474 -0.1260 -0.2941 +vn 0.9992 -0.0385 -0.0070 +vn 0.9228 0.1188 -0.3665 +vn 0.9399 0.0438 -0.3387 +vn 0.9414 0.1430 -0.3053 +vn 0.9398 0.0461 -0.3385 +vn 0.9266 -0.0635 -0.3707 +vn 0.9296 -0.0876 -0.3581 +vn 0.9414 -0.1421 -0.3060 +vn 0.9995 0.0299 0.0030 +vn 0.9986 0.0440 -0.0304 +vn -0.9817 -0.0683 -0.1775 +vn -0.9864 -0.0401 -0.1597 +vn -0.9690 -0.0184 -0.2464 +vn -0.9753 0.0121 -0.2206 +vn -0.9090 0.1334 -0.3950 +vn -0.9651 0.1410 -0.2207 +vn -0.9986 -0.0025 -0.0524 +vn 0.9795 -0.0702 -0.1890 +vn 0.7836 0.1308 -0.6073 +vn 0.6886 0.1404 -0.7114 +vn 0.9312 0.1580 -0.3285 +vn 0.9737 -0.0044 -0.2278 +vn 0.9832 0.0385 -0.1785 +vn 0.9859 0.0521 -0.1589 +vn 0.9881 -0.0325 -0.1501 +vn -0.9966 -0.0744 -0.0363 +vn -0.9984 -0.0563 0.0064 +vn -0.9187 -0.1584 -0.3618 +vn -0.9255 -0.0805 -0.3701 +vn -0.9092 -0.1811 -0.3748 +vn -0.9243 -0.0579 -0.3773 +vn -0.9217 0.0414 -0.3857 +vn -0.9235 0.0356 -0.3820 +vn -0.9097 0.1482 -0.3880 +vn -0.9493 0.1685 -0.2654 +vn -0.9982 0.0048 -0.0594 +vn 0.0174 -0.5891 -0.8078 +vn 0.9998 -0.0080 -0.0181 +vn 0.9769 -0.0766 -0.1993 +vn 0.8938 0.1349 -0.4278 +vn 0.9767 0.1075 -0.1859 +vn -0.9864 -0.0401 -0.1596 +vn 0.9998 -0.0087 -0.0198 +vn 0.9774 -0.0753 -0.1975 +vn 0.8812 0.1037 -0.4612 +vn 0.9549 0.0622 -0.2904 +vn 0.9747 0.0861 -0.2062 +vn 0.8970 -0.0223 -0.4414 +vn 0.9634 -0.0831 -0.2549 +vn 0.9762 -0.0829 -0.2003 +vn 0.9997 0.0094 -0.0219 +vn -0.9808 -0.0708 -0.1817 +vn -0.8772 0.1397 -0.4594 +vn -0.0140 0.5891 -0.8079 +vn 0.0076 0.9962 0.0869 +vn 0.0106 0.9942 0.1066 +vn -0.0104 0.9917 -0.1281 +vn 0.0097 0.9610 -0.2763 +vn -0.0011 0.9178 -0.3970 +vn 0.0075 0.9718 -0.2358 +vn 0.0130 0.8370 -0.5471 +vn -0.6863 0.3668 -0.6280 +vn 0.7861 0.3911 -0.4787 +vn 0.0499 0.7633 -0.6441 +vn -0.1361 0.7405 -0.6581 +vn -0.1948 0.7331 -0.6516 +vn -0.6807 0.6001 -0.4202 +vn 0.7375 0.1146 -0.6655 +vn -0.6252 -0.1595 -0.7640 +vn 0.5692 -0.4378 -0.6959 +vn -0.2148 -0.6121 -0.7611 +vn -0.2178 -0.5897 -0.7777 +vn -0.1603 -0.5734 -0.8035 +vn -0.3491 -0.6039 -0.7165 +vn 0.3620 -0.8079 -0.4650 +vn 0.6639 -0.5988 0.4480 +vn 0.6718 -0.5946 0.4417 +vn 0.6002 -0.6284 0.4948 +vn 0.5474 -0.6485 0.5289 +vn -0.2228 -0.4655 0.8566 +vn 0.0623 -0.1764 0.9823 +vn 0.3162 -0.1547 0.9360 +vn 0.2120 -0.1651 0.9632 +vn 0.6325 0.1486 0.7602 +vn -0.5402 0.0414 0.8405 +vn -0.5631 0.2665 0.7822 +vn 0.8176 0.3550 0.4533 +vn 0.5123 0.5581 0.6528 +vn 0.7166 0.4412 0.5402 +vn 0.5006 0.5632 0.6574 +vn -0.5176 0.6659 0.5372 +vn 0.7876 0.5797 -0.2090 +vn -0.8625 0.5025 -0.0603 +vn -0.9539 0.2993 0.0219 +vn -0.9631 0.2675 -0.0303 +vn 0.6756 0.6958 0.2437 +vn 0.1744 0.6816 -0.7106 +vn 0.0972 0.8125 -0.5748 +vn 0.1461 0.7807 -0.6076 +vn 0.1080 0.6600 -0.7434 +vn 0.2691 0.4505 -0.8513 +vn 0.2765 -0.2467 -0.9288 +vn -0.2506 -0.5951 -0.7636 +vn -0.0312 -0.7075 -0.7061 +vn -0.2578 -0.5934 -0.7625 +vn -0.0311 -0.7291 -0.6837 +vn -0.0524 -0.7985 -0.5998 +vn 0.4536 -0.7210 0.5239 +vn 0.4625 -0.6725 0.5778 +vn 0.4399 -0.7146 0.5440 +vn 0.6117 -0.5203 0.5959 +vn 0.6446 -0.4838 0.5919 +vn -0.7258 -0.3320 0.6025 +vn 0.6296 -0.2503 0.7354 +vn 0.0354 -0.0743 0.9966 +vn -0.0121 -0.0702 0.9975 +vn -0.2092 -0.1646 0.9639 +vn -0.0083 0.1712 0.9852 +vn -0.0101 0.1802 0.9836 +vn -0.0196 0.3210 0.9469 +vn 0.8398 0.2294 0.4920 +vn -0.9945 0.0890 -0.0546 +vn 0.1800 0.7029 0.6882 +vn 0.0730 0.6186 0.7823 +vn 0.1694 0.6087 0.7751 +vn 0.2590 0.8377 -0.4808 +vn -0.8450 0.5335 -0.0350 +vn 0.7834 0.6006 0.1597 +vn -0.7895 0.5396 0.2925 +vn 0.1405 0.6615 0.7367 +vn 0.2038 0.7951 0.5712 +vn -0.0792 0.6155 -0.7841 +vn 0.1841 0.7541 -0.6304 +vn 0.3756 0.7421 -0.5551 +vn -0.0823 0.6927 -0.7165 +vn -0.1483 0.5115 -0.8464 +vn 0.6870 0.1408 -0.7129 +vn -0.5321 -0.1791 -0.8275 +vn 0.2715 -0.2508 -0.9292 +vn -0.2436 -0.5929 -0.7675 +vn 0.0054 -0.6929 -0.7210 +vn -0.2524 -0.5910 -0.7662 +vn -0.0223 -0.7430 -0.6689 +vn -0.0655 -0.7975 -0.5997 +vn 0.4167 -0.6886 0.5934 +vn 0.4115 -0.7353 0.5385 +vn 0.4314 -0.7408 0.5149 +vn 0.5626 -0.5402 0.6259 +vn 0.5998 -0.5008 0.6240 +vn 0.6505 -0.2416 0.7200 +vn 0.4167 -0.1485 0.8968 +vn 0.6215 -0.2341 0.7476 +vn 0.5017 -0.0522 0.8635 +vn 0.5303 -0.0313 0.8472 +vn -0.2764 0.1029 0.9555 +vn -0.1220 0.2570 0.9587 +vn -0.3421 0.0314 0.9391 +vn -0.0447 0.3277 0.9437 +vn 0.0409 0.6087 0.7923 +vn 0.0680 0.6182 0.7831 +vn 0.1625 0.6052 0.7793 +vn 0.3617 0.7325 -0.5767 +vn -0.7948 0.5315 -0.2929 +vn 0.7243 0.6605 -0.1980 +vn -0.7709 0.6368 -0.0129 +vn 0.6524 0.7513 0.0997 +vn -0.3915 0.8059 0.4441 +vn -0.1154 0.6948 0.7099 +vn -0.4147 0.7963 0.4403 +vn -0.0711 0.6517 0.7552 +vn -0.0361 0.6854 -0.7272 +vn 0.1870 0.7494 -0.6352 +vn 0.1339 0.7656 -0.6292 +vn -0.0734 0.6891 -0.7209 +vn -0.1449 0.5258 -0.8382 +vn -0.5547 -0.5201 -0.6494 +vn -0.4325 -0.6610 -0.6132 +vn -0.5880 -0.4852 -0.6471 +vn -0.4295 -0.7095 -0.5587 +vn -0.4525 -0.7205 -0.5255 +vn 0.4535 -0.7210 0.5239 +vn 0.6117 -0.5202 0.5959 +vn 0.6447 -0.4837 0.5919 +vn -0.7255 -0.3322 0.6027 +vn 0.6506 -0.2416 0.7199 +vn 0.4168 -0.1485 0.8968 +vn 0.6215 -0.2342 0.7476 +vn 0.0408 0.6087 0.7923 +vn -0.7391 0.5831 -0.3371 +vn 0.6705 0.7107 -0.2130 +vn -0.6362 0.7648 -0.1015 +vn 0.7292 0.6743 0.1163 +vn -0.2554 0.8385 0.4813 +vn -0.0682 0.6456 0.7607 +vn -0.1100 0.6873 0.7180 +vn -0.4885 0.8716 0.0405 +vn 0.2614 0.9222 -0.2850 +vn -0.2069 0.7796 -0.5910 +vn -0.0911 0.7501 -0.6550 +vn -0.0565 0.6905 -0.7212 +vn -0.0539 0.7258 -0.6858 +vn 0.7292 0.1349 -0.6708 +vn -0.6364 -0.0804 -0.7672 +vn 0.6704 -0.1934 -0.7163 +vn -0.7466 -0.3187 -0.5839 +vn 0.6878 -0.4567 -0.5642 +vn 0.4621 -0.6835 -0.5651 +vn 0.6547 -0.4944 -0.5718 +vn 0.4283 -0.7266 -0.5372 +vn 0.4416 -0.7361 -0.5129 +vn -0.0702 0.6491 0.7574 +vn -0.1103 0.6893 0.7161 +vn -0.2577 0.8434 0.4714 +vn 0.4313 0.8029 0.4114 +vn 0.1647 0.7109 -0.6837 +vn 0.1536 0.7829 -0.6029 +vn 0.1301 0.7877 -0.6022 +vn 0.1018 0.6561 -0.7478 +vn 0.2767 -0.2467 -0.9288 +vn -0.2430 -0.5930 -0.7676 +vn 0.0055 -0.6929 -0.7210 +vn -0.2519 -0.5911 -0.7663 +vn 0.5892 -0.2332 0.7736 +vn 0.2820 -0.2428 0.9282 +vn 0.2098 0.7682 -0.6048 +vn -0.7119 0.5982 -0.3679 +vn 0.7833 0.5955 -0.1785 +vn -0.8246 0.5653 -0.0218 +vn -0.3911 0.8061 0.4442 +vn -0.4143 0.7965 0.4403 +vn -0.0047 0.7917 -0.6108 +vn 0.4041 0.6399 -0.6537 +vn 0.3861 0.5871 -0.7114 +vn 0.5394 0.3992 -0.7414 +vn -0.8248 0.0211 -0.5650 +vn 0.6644 -0.1807 -0.7252 +vn -0.7499 -0.3053 -0.5869 +vn 0.3149 -0.5240 -0.7913 +vn 0.2789 -0.6480 -0.7087 +vn 0.1557 -0.6702 -0.7257 +vn 0.1047 -0.7809 -0.6158 +vn 0.0037 -0.7824 -0.6228 +vn 0.0256 -0.8295 -0.5580 +vn 0.3309 -0.7390 0.5868 +vn 0.4263 -0.6146 0.6637 +vn 0.6296 -0.2503 0.7355 +vn 0.0320 -0.2374 0.9709 +vn 0.2875 0.0191 0.9576 +vn -0.0077 0.1623 0.9867 +vn -0.0097 0.1736 0.9848 +vn -0.0186 0.3065 0.9517 +vn 0.4906 0.4975 0.7154 +vn 0.4187 0.6253 0.6585 +vn 0.3013 0.6449 0.7024 +vn 0.0552 0.7449 0.6649 +vn -0.2612 0.7332 -0.6278 +vn -0.1108 0.7284 -0.6761 +vn -0.0000 0.6486 -0.7611 +vn -0.2832 0.8170 -0.5024 +vn 0.3782 0.8058 -0.4556 +vn -0.0071 0.9948 -0.1014 +vn -0.4550 0.7694 0.4483 +vn -0.3488 0.6417 0.6830 +vn -0.2464 0.6750 0.6954 +vn -0.1326 0.5907 0.7959 +vn 0.0114 0.5369 -0.8436 +vn 0.0125 0.4264 -0.9044 +vn 0.0259 0.2366 -0.9713 +vn -0.0057 0.3603 -0.9328 +vn 0.0015 0.1767 -0.9843 +vn -0.0082 0.0446 -0.9990 +vn 0.0329 -0.1186 -0.9924 +vn 0.0005 -0.3130 -0.9498 +vn 0.0042 -0.3784 -0.9257 +vn 0.0138 -0.2359 -0.9717 +vn 0.0034 -0.5321 -0.8467 +vn -0.0025 -0.0027 1.0000 +vn -0.0150 -0.0023 0.9999 +vn 0.0004 -0.0020 1.0000 +vn -0.0130 0.2441 0.9697 +vn 0.0216 0.7620 -0.6472 +vn 0.0147 0.7695 -0.6384 +vn 0.0088 0.7760 -0.6307 +vn 0.0277 0.7552 -0.6550 +vn -0.9974 -0.0275 -0.0661 +vn -0.9884 -0.0405 -0.1466 +vn -0.9978 -0.0276 -0.0607 +vn -0.9582 0.2860 -0.0056 +vn -0.9906 0.1187 0.0674 +vn -0.9976 0.0607 0.0324 +vn -0.9989 -0.0206 -0.0427 +vn -0.9992 -0.0301 -0.0275 +vn -0.9891 0.1462 0.0155 +vn -0.9993 0.0319 0.0192 +vn -0.9996 -0.0203 -0.0187 +vn -0.9993 -0.0377 -0.0065 +vn -0.9998 0.0151 0.0138 +vn -0.9999 0.0081 0.0075 +vn -0.9972 -0.0608 -0.0430 +vn -0.9616 -0.2647 -0.0732 +vn -0.9869 -0.1412 -0.0779 +vn 0.0038 0.9881 0.1540 +vn -0.0973 0.9891 0.1104 +vn -0.0304 0.9898 0.1395 +vn -0.1264 0.9872 0.0975 +vn 0.1219 -0.0697 -0.9901 +vn 0.0251 -0.1054 -0.9941 +vn 0.0961 -0.0793 -0.9922 +vn -0.0031 -0.1156 -0.9933 +vn 0.1208 0.9719 0.2022 +vn 0.0495 0.9836 0.1732 +vn 0.1765 0.9584 0.2243 +vn -0.1366 0.8001 -0.5841 +vn -0.3112 0.7315 -0.6066 +vn 0.3156 -0.0239 -0.9486 +vn 0.0795 -0.1272 -0.9887 +vn 0.2609 -0.0488 -0.9641 +vn -0.0039 -0.1612 -0.9869 +vn -0.0931 0.9893 0.1123 +vn -0.0290 0.9897 0.1401 +vn -0.1212 0.9876 0.0998 +vn 0.1432 -0.1004 -0.9846 +vn 0.0436 -0.1420 -0.9889 +vn 0.1133 -0.1131 -0.9871 +vn 0.1018 -0.0250 -0.9945 +vn 0.0296 -0.0625 -0.9976 +vn 0.0816 -0.0355 -0.9960 +vn -0.0024 -0.0789 -0.9969 +vn 0.0443 0.9834 0.1759 +vn 0.2111 0.9735 0.0877 +vn -0.0599 0.9719 0.2275 +vn 0.2800 0.9587 0.0491 +vn -0.3130 0.7520 -0.5801 +vn 0.2327 0.6308 -0.7402 +vn 0.0016 -0.1184 -0.9930 +vn -0.0021 -0.1197 -0.9928 +vn 0.0003 -0.1189 -0.9929 +vn -0.0032 -0.1201 -0.9928 +vn -0.0273 0.9733 0.2278 +vn 0.3773 0.8920 -0.2489 +vn -0.0957 0.7881 -0.6080 +vn 0.1668 0.0172 -0.9858 +vn 0.0727 -0.0603 -0.9955 +vn 0.1043 -0.0345 -0.9939 +vn -0.0014 -0.1201 -0.9928 +vn 0.0028 -0.0976 0.9952 +vn 0.4143 0.6910 0.5924 +vn -0.4650 0.8520 -0.2406 +vn -0.1427 0.9798 -0.1398 +vn -0.3055 0.9326 -0.1923 +vn -0.0369 0.9939 -0.1041 +vn 0.0041 -0.1750 0.9846 +vn -0.0859 -0.1315 0.9876 +vn -0.0302 -0.1586 0.9869 +vn -0.1138 -0.1176 0.9865 +vn 0.1432 0.9882 -0.0542 +vn 0.0341 0.9951 -0.0933 +vn 0.1181 0.9910 -0.0634 +vn 0.0036 0.9946 -0.1040 +vn 0.0014 -0.1161 0.9932 +vn -0.0127 -0.1048 0.9944 +vn -0.0094 -0.1075 0.9942 +vn -0.0236 -0.0961 0.9951 +vn -0.3357 0.7050 0.6247 +vn -0.3060 0.7102 0.6341 +vn 0.0267 0.9909 -0.1317 +vn 0.0135 0.9895 -0.1440 +vn 0.0150 0.9897 -0.1425 +vn 0.0013 0.9879 -0.1552 +vn 0.0304 -0.0981 0.9947 +vn 0.0286 0.5122 0.8584 +vn 0.4189 -0.0577 0.9062 +vn -0.1909 0.5177 0.8340 +vn -0.1908 0.5176 0.8340 +vn -0.0084 -0.0953 0.9954 +vn 0.0326 0.5124 0.8581 +vn 0.0225 -0.1998 0.9796 +vn -0.2206 -0.1076 0.9694 +vn -0.0480 -0.1744 0.9835 +vn -0.2607 -0.0911 0.9611 +vn 0.3134 0.3910 0.8654 +vn 0.0664 0.4906 0.8688 +vn 0.2710 0.4108 0.8705 +vn -0.0074 0.5134 0.8581 +vn 0.0173 0.0366 -0.9992 +vn 0.0061 0.0270 -0.9996 +vn -0.0128 0.9997 -0.0207 +vn -0.0149 0.9996 -0.0230 +vn -0.0005 0.6056 0.7958 +vn -0.0038 0.6084 0.7937 +vn -0.0048 0.9979 0.0653 +vn 0.0094 0.9970 0.0771 +vn -0.0055 0.4929 0.8701 +vn -0.0248 0.6265 0.7790 +vn 0.0151 0.5122 0.8587 +vn 0.9992 -0.0347 0.0174 +vn 0.9990 -0.0325 0.0307 +vn 0.9993 -0.0354 0.0144 +vn 0.9990 -0.0322 0.0311 +vn 0.9992 -0.0388 -0.0056 +vn 0.9988 -0.0296 -0.0383 +vn 0.9992 -0.0334 -0.0239 +vn 0.9988 -0.0192 -0.0451 +vn 0.9984 -0.0200 -0.0529 +vn 0.9985 -0.0339 -0.0438 +vn -0.9737 -0.2265 -0.0259 +vn -1.0000 -0.0013 0.0054 +vn -1.0000 -0.0005 0.0063 +vn -0.9996 0.0167 0.0214 +vn -0.9365 -0.3497 0.0254 +vn -0.9729 -0.2244 0.0552 +vn -1.0000 0.0023 0.0073 +vn -0.9998 -0.0049 0.0198 +vn -0.9479 -0.2869 0.1388 +vn -0.9952 -0.0700 0.0677 +vn -0.9991 -0.0350 0.0230 +vn -0.9998 -0.0179 0.0042 +vn -0.9996 -0.0232 0.0179 +vn -0.9992 0.0029 0.0410 +vn -0.9970 0.0670 -0.0392 +vn -0.9991 -0.0386 -0.0158 +vn -0.9997 -0.0008 -0.0239 +vn -0.9508 0.3097 -0.0075 +vn -0.9990 0.0266 -0.0350 +vn -0.9978 0.0285 -0.0592 +vn -0.9998 0.0169 -0.0056 +vn -0.9979 0.0283 -0.0579 +vn -0.9937 0.0343 -0.1067 +vn -0.9771 -0.0007 -0.2129 +vn 0.9989 0.0239 0.0396 +vn 0.8540 0.0277 0.5195 +vn 0.9917 -0.0566 0.1151 +vn 0.9650 -0.0667 0.2536 +vn 0.9982 0.0599 0.0080 +vn -0.9997 -0.0095 0.0234 +vn -0.9811 -0.0779 0.1769 +vn -0.9754 -0.0880 0.2021 +vn -0.9872 -0.0542 0.1498 +vn -0.9884 -0.0490 0.1439 +vn 0.9883 -0.0558 0.1418 +vn 0.9999 -0.0048 0.0122 +vn 0.9834 -0.0665 0.1691 +vn -0.9999 -0.0046 0.0140 +vn -0.9877 -0.0487 0.1483 +vn -0.9843 -0.0561 0.1674 +vn -0.9842 -0.0563 0.1676 +vn 0.9856 -0.0714 0.1533 +vn 0.9920 -0.0562 0.1129 +vn 0.9814 -0.0760 0.1761 +vn -0.9806 -0.0761 0.1809 +vn -0.9752 -0.0861 0.2041 +vn -0.9848 -0.0577 0.1640 +vn -0.9858 -0.0534 0.1592 +vn 0.9834 -0.0666 0.1691 +vn -0.9878 -0.0487 0.1483 +vn -0.9999 -0.0046 0.0141 +vn -0.9877 -0.0488 0.1487 +vn 0.9999 -0.0157 -0.0025 +vn 0.9955 -0.0489 0.0812 +vn 0.9998 -0.0185 0.0046 +vn 0.9938 -0.0549 0.0963 +vn -0.0010 -0.5507 0.8347 +vn 0.0536 -0.5437 0.8375 +vn -0.0065 -0.5513 0.8343 +vn 0.0590 -0.5430 0.8377 +vn -0.0155 -0.6038 0.7970 +vn 0.2145 -0.4770 0.8523 +vn -0.3310 -0.5204 0.7871 +vn 0.5769 -0.4045 0.7096 +vn 0.9988 -0.0110 0.0479 +vn 0.9758 -0.2035 0.0799 +vn 0.9992 0.0048 0.0409 +vn 0.9812 -0.1693 -0.0924 +vn 0.9989 -0.0116 -0.0464 +vn 0.9992 0.0043 -0.0394 +vn 0.9838 -0.1706 -0.0552 +vn 0.9595 -0.2807 -0.0243 +vn 0.9859 -0.1652 0.0283 +vn 0.9815 -0.1625 0.1009 +vn -1.0000 0.0007 -0.0004 +vn -1.0000 0.0002 -0.0000 +vn -1.0000 0.0008 -0.0005 +vn 0.9758 -0.2035 0.0800 +vn 0.9992 -0.0032 -0.0403 +vn 0.9829 -0.1590 -0.0933 +vn 0.9988 -0.0164 -0.0462 +vn 0.9835 -0.1740 -0.0496 +vn 0.9599 -0.2792 -0.0243 +vn 0.9772 -0.2098 0.0324 +vn 0.9735 -0.2004 0.1105 +vn -0.9990 -0.0098 -0.0426 +vn -0.9765 -0.2018 -0.0757 +vn -0.9993 0.0042 -0.0365 +vn -0.9794 -0.1746 0.1019 +vn -0.9986 -0.0160 0.0501 +vn -0.9991 -0.0008 0.0434 +vn -0.9596 -0.2802 0.0244 +vn -0.9811 -0.1863 0.0518 +vn -0.9772 -0.2099 -0.0323 +vn -0.9781 -0.1819 -0.1012 +vn 0.9793 -0.1943 -0.0562 +vn 0.9735 -0.2003 0.1105 +vn -0.9984 -0.0153 -0.0540 +vn -0.9718 -0.2194 -0.0867 +vn -0.9989 0.0006 -0.0469 +vn -0.9595 -0.2805 0.0245 +vn -0.9763 -0.2140 -0.0314 +vn -0.9695 -0.2142 -0.1191 +vn 0.9829 -0.1589 -0.0933 +vn 0.9989 -0.0145 -0.0453 +vn 0.9992 -0.0008 -0.0392 +vn -0.9990 -0.0125 -0.0438 +vn -0.9768 -0.2003 -0.0755 +vn -0.9993 0.0005 -0.0381 +vn -0.9772 -0.2099 -0.0324 +vn 0.9992 -0.0090 0.0393 +vn 0.9797 -0.1876 0.0704 +vn 0.9994 0.0039 0.0337 +vn 0.9600 -0.2790 -0.0242 +vn 0.9779 -0.2064 0.0331 +vn 0.9805 -0.1719 0.0948 +vn -0.9985 -0.0120 -0.0525 +vn -0.9714 -0.2212 -0.0869 +vn -0.9990 0.0052 -0.0449 +vn -0.9989 -0.0036 0.0459 +vn -0.9789 -0.1794 0.0978 +vn -0.9985 -0.0187 0.0524 +vn -0.9591 -0.2818 0.0245 +vn -0.9772 -0.2042 0.0583 +vn 0.9991 -0.0091 0.0423 +vn 0.9802 -0.1841 0.0726 +vn 0.9993 0.0049 0.0360 +vn 1.0000 0.0004 0.0002 +vn 0.9997 -0.0186 -0.0159 +vn 0.9818 -0.1699 -0.0848 +vn 0.9524 -0.3018 -0.0434 +vn 0.9747 -0.2235 -0.0076 +vn 0.9739 -0.2245 0.0340 +vn 0.9778 -0.1840 0.1003 +vn 0.0310 -0.8075 -0.5891 +vn 0.2379 -0.8106 -0.5351 +vn -0.0065 -0.8030 -0.5960 +vn 0.2576 -0.8089 -0.5284 +vn -0.4393 -0.8523 -0.2841 +vn 0.5036 -0.8586 -0.0957 +vn -0.5036 -0.8586 0.0957 +vn 0.4393 -0.8523 0.2841 +vn -0.2379 -0.8106 0.5351 +vn -0.0311 -0.8075 0.5891 +vn -0.2576 -0.8089 0.5284 +vn 0.0063 -0.8030 0.5960 +vn -0.0139 -0.8029 -0.5959 +vn 0.5060 -0.7221 -0.4717 +vn -0.7324 -0.6459 -0.2153 +vn 0.7886 -0.6111 -0.0681 +vn -0.7886 -0.6111 0.0681 +vn 0.7325 -0.6459 0.2153 +vn -0.5056 -0.7223 0.4718 +vn 0.0142 -0.8029 0.5959 +vn -0.0142 -0.8029 -0.5959 +vn 0.7324 -0.6459 0.2153 +vn -0.5060 -0.7221 0.4717 +vn 0.5056 -0.7223 -0.4718 +vn -0.7325 -0.6459 -0.2153 +vn 0.0139 -0.8029 0.5959 +vn 0.0083 -0.9377 0.3473 +vn 0.0275 -0.9551 0.2949 +vn 0.0166 -0.9573 0.2885 +vn 0.0294 -0.9740 0.2245 +vn 0.0149 -0.9246 0.3808 +vn -0.0029 -0.7297 0.6838 +vn 0.0051 -0.7430 0.6693 +vn 0.0011 -0.7245 0.6892 +vn 0.0162 -0.8477 -0.5302 +vn 0.0249 -0.9065 -0.4215 +vn 0.0324 -0.9716 -0.2345 +vn -0.0076 -0.9547 -0.2975 +vn 0.0514 -0.9935 -0.1020 +vn -0.0186 -0.9974 0.0698 +vn -0.0129 -0.7659 -0.6428 +vn -0.0215 -0.7563 -0.6538 +vn -0.0291 -0.7477 -0.6634 +vn -0.0058 -0.7737 -0.6335 +vn -0.0048 0.0138 -0.9999 +vn 0.3096 0.1029 -0.9453 +vn 0.0911 0.0412 -0.9950 +vn 0.4692 0.1475 -0.8707 +vn -0.4204 -0.5847 -0.6938 +vn 0.5617 -0.8091 -0.1730 +vn -0.0146 -0.9997 0.0189 +vn -0.1007 -0.0137 -0.9948 +vn -0.0254 0.0079 -0.9996 +vn -0.1191 -0.0190 -0.9927 +vn 0.1277 -0.9699 -0.2074 +vn 0.0113 -0.9830 -0.1832 +vn 0.1103 -0.9727 -0.2040 +vn -0.0084 -0.9838 -0.1789 +vn 0.0031 0.1156 -0.9933 +vn -0.4691 -0.0696 -0.8804 +vn 0.3523 -0.6809 -0.6420 +vn -0.5477 -0.8279 -0.1211 +vn 0.0234 -0.9933 0.1128 +vn 0.2220 0.0783 -0.9719 +vn 0.0552 0.0309 -0.9980 +vn 0.3134 0.1040 -0.9439 +vn -0.4001 -0.7055 -0.5850 +vn 0.6420 -0.7497 -0.1603 +vn -0.0193 -0.9828 0.1838 +vn -0.0015 0.1168 -0.9932 +vn -0.0067 0.1126 -0.9936 +vn -0.0055 0.1136 -0.9935 +vn -0.0106 0.1095 -0.9939 +vn -0.0513 -0.7267 -0.6850 +vn -0.1387 -0.7247 -0.6750 +vn 0.0509 -0.9875 0.1492 +vn 0.0469 -0.9882 0.1459 +vn 0.0921 -0.9788 0.1830 +vn 0.0106 -0.9932 0.1159 +vn -0.0432 -0.9829 0.1788 +vn 0.8448 -0.5283 -0.0852 +vn -0.4232 -0.7018 0.5731 +vn 0.3511 -0.0179 0.9362 +vn 0.0865 0.0854 0.9926 +vn 0.3003 0.0027 0.9538 +vn 0.0033 0.1159 0.9933 +vn 0.0250 -0.9879 0.1532 +vn 0.7713 -0.6330 -0.0671 +vn -0.3488 -0.7144 0.6066 +vn 0.4684 -0.0693 0.8808 +vn -0.0031 0.1155 0.9933 +vn 0.0280 -0.9860 0.1645 +vn 0.7987 -0.5984 -0.0635 +vn -0.4051 -0.6970 0.5918 +vn 0.3506 -0.0179 0.9363 +vn 0.0863 0.0852 0.9926 +vn 0.2999 0.0026 0.9540 +vn 0.0034 0.1155 0.9933 +vn 0.0084 -0.9838 0.1790 +vn 0.8096 -0.5818 -0.0782 +vn -0.4051 -0.6970 0.5917 +vn 0.0172 -0.9913 -0.1301 +vn 0.0191 -0.9911 -0.1317 +vn 0.0188 -0.9911 -0.1315 +vn 0.0208 -0.9909 -0.1331 +vn 0.0092 -0.6706 0.7418 +vn -0.2843 -0.7056 0.6490 +vn -0.0720 0.1709 0.9826 +vn -0.0319 0.1396 0.9897 +vn -0.0377 0.1441 0.9888 +vn -0.0014 0.1155 0.9933 +vn 0.2356 -0.5974 0.7666 +vn -0.1017 -0.1841 0.9776 +vn 0.6163 0.0273 0.7871 +vn -0.3022 0.3013 0.9043 +vn 0.4456 -0.5050 0.7392 +vn -0.3438 -0.1581 0.9257 +vn 0.6160 0.1476 0.7738 +vn 0.6095 0.1453 0.7793 +vn 0.0238 -0.3725 0.9277 +vn 0.0736 -0.5985 0.7977 +vn 0.7903 0.0581 0.6100 +vn 0.0039 -0.5895 0.8077 +vn 0.0750 -0.3522 0.9329 +vn 0.0165 -0.5940 0.8043 +vn 0.1122 0.1752 0.9781 +vn -0.0102 0.2265 0.9740 +vn -0.0192 -0.0332 -0.9993 +vn -0.0109 -0.0252 -0.9996 +vn 0.0201 -0.9991 -0.0371 +vn 0.0108 -0.9995 -0.0283 +vn -0.0076 -0.6335 0.7737 +vn 0.0152 -0.6480 0.7615 +vn 0.0063 -0.9983 0.0583 +vn -0.0061 -0.9974 0.0717 +vn -0.0039 -0.5302 0.8479 +vn -0.0019 -0.5324 0.8465 +vn 0.9600 0.2563 -0.1130 +vn 0.7538 0.5274 -0.3920 +vn 0.7193 0.6681 -0.1905 +vn 0.9193 0.3799 -0.1023 +vn 0.9053 0.4189 -0.0699 +vn 0.9431 0.3300 -0.0414 +vn 0.9015 0.4326 0.0156 +vn 0.8849 0.4658 -0.0041 +vn 0.7124 0.7004 0.0424 +vn 0.9337 0.3440 0.0990 +vn 0.9385 0.3451 0.0145 +vn 0.7394 0.6325 0.2307 +vn 0.9416 0.2456 0.2306 +vn 0.7401 0.4536 0.4965 +vn 0.8880 0.3274 0.3230 +vn 0.8266 0.1999 0.5261 +vn 0.8973 0.1540 0.4137 +vn 0.7186 0.5524 0.4225 +vn 0.8392 0.1026 0.5341 +vn 0.6058 0.3250 0.7262 +vn 0.5604 0.1063 0.8213 +vn 0.7767 0.0977 0.6222 +vn 0.6654 0.2435 0.7056 +vn 0.8120 -0.0796 0.5783 +vn 0.4846 -0.0125 0.8747 +vn 0.6294 -0.0771 0.7733 +vn 0.7443 -0.4218 0.5177 +vn 0.7113 -0.6002 0.3659 +vn 0.8300 -0.4478 0.3326 +vn 0.9396 -0.1491 0.3080 +vn 0.9706 -0.2301 0.0701 +vn 0.7622 -0.4089 0.5019 +vn 0.9114 -0.4092 0.0435 +vn 0.7156 -0.6843 0.1399 +vn 0.7077 -0.7052 -0.0440 +vn 0.9498 -0.2894 0.1187 +vn 0.9464 -0.3224 0.0169 +vn 0.7257 -0.6470 -0.2340 +vn 0.9471 -0.2917 -0.1340 +vn 0.9425 -0.3287 -0.0614 +vn 0.8988 -0.4276 -0.0960 +vn 0.7703 -0.4754 -0.4250 +vn 0.7099 -0.4197 -0.5656 +vn 0.9473 -0.0961 -0.3056 +vn 0.7511 -0.5082 -0.4213 +vn 0.7292 -0.1704 -0.6627 +vn 0.7752 0.0117 -0.6316 +vn 0.9455 0.1225 -0.3018 +vn 0.9244 0.0741 -0.3741 +vn 0.7328 0.2882 -0.6163 +vn 0.7419 0.4723 -0.4759 +vn 0.8818 -0.0460 0.4694 +vn 0.8360 -0.0008 0.5487 +vn 0.6523 -0.3356 0.6796 +vn 0.9418 0.0705 0.3288 +vn 0.9780 0.0009 0.2084 +vn 0.8382 0.3944 -0.3767 +vn 0.9775 0.0735 -0.1975 +vn 0.9767 -0.1280 -0.1720 +vn 0.8981 -0.3205 -0.3010 +vn 0.9763 0.1299 0.1733 +vn 0.9826 -0.1133 0.1475 +vn 0.7170 -0.6056 0.3451 +vn 0.9743 0.2177 0.0585 +vn 0.9954 0.0591 -0.0748 +vn 0.9990 0.0263 0.0372 +vn 0.9865 -0.1627 -0.0195 +vn 0.3846 0.7395 0.5525 +vn -0.0189 0.8648 0.5018 +vn -0.0153 0.9912 0.1318 +vn 0.2564 0.8767 0.4070 +vn 0.2846 0.8805 0.3791 +vn 0.3162 0.9357 0.1567 +vn 0.3410 0.9364 -0.0824 +vn 0.2383 0.9232 -0.3017 +vn 0.2971 0.8010 -0.5197 +vn 0.2846 0.5820 -0.7617 +vn 0.2442 0.3951 -0.8856 +vn 0.2754 0.2097 -0.9382 +vn 0.2990 -0.0482 -0.9530 +vn 0.3086 -0.3232 -0.8946 +vn 0.2186 -0.5749 -0.7885 +vn 0.2652 -0.2399 0.9339 +vn 0.1752 0.2517 0.9518 +vn 0.2420 0.6205 0.7460 +vn 0.0034 -0.6068 0.7949 +vn 0.0285 -0.5518 0.8335 +vn -0.0369 -0.6885 0.7243 +vn -0.0697 -0.7489 0.6590 +vn 0.0683 -0.7154 -0.6954 +vn 0.0656 -0.7122 -0.6989 +vn 0.0609 -0.7069 -0.7047 +vn 0.0763 -0.7243 -0.6852 +vn 0.0778 0.8893 -0.4507 +vn 0.0273 0.8394 -0.5429 +vn -0.0100 0.7955 -0.6059 +vn -0.0830 0.6926 -0.7165 +vn -0.0068 0.5990 0.8007 +vn -0.0198 0.6290 0.7772 +vn -0.0438 0.6823 0.7298 +vn -0.0575 0.7112 0.7007 +vn -0.0357 -0.9078 -0.4180 +vn 0.0467 -0.5151 -0.8558 +vn -0.0287 0.1213 -0.9922 +vn 0.0242 0.9166 -0.3992 +vn 0.0246 0.9175 -0.3970 +vn 0.0268 0.9219 -0.3864 +vn 0.0271 0.9225 -0.3851 +vn -0.0331 0.6836 0.7291 +vn -0.0256 0.6453 0.7635 +vn 0.0303 0.3150 0.9486 +vn 0.0381 0.2632 0.9640 +vn -0.0321 -0.5712 0.8202 +vn -0.0257 -0.6100 0.7920 +vn 0.0250 -0.8575 0.5139 +vn 0.0328 -0.8862 0.4622 +vn -0.0072 0.7081 -0.7060 +vn 0.2632 0.5213 -0.8117 +vn 0.2897 0.8395 -0.4597 +vn 0.2928 0.9558 0.0285 +vn -0.0079 0.9992 -0.0397 +vn -0.0092 0.9791 -0.2031 +vn -0.0183 0.9926 0.1203 +vn 0.0062 0.7580 0.6522 +vn 0.0216 0.7039 0.7100 +vn 0.0076 0.7042 0.7100 +vn 0.0069 0.7620 0.6475 +vn 0.3473 0.5194 -0.7808 +vn 0.2684 0.8311 -0.4871 +vn -0.0146 0.3441 0.9388 +vn 0.2225 0.4672 0.8557 +vn 0.0037 0.2427 0.9701 +vn 0.5353 0.1599 -0.8294 +vn 0.5171 0.8526 -0.0754 +vn 0.4431 0.4395 0.7813 +vn 0.4197 0.4492 0.7887 +vn 0.0408 0.6978 0.7151 +vn 0.6063 0.7627 0.2251 +vn 0.7527 0.5291 0.3918 +vn 0.4315 0.8972 0.0943 +vn 0.4743 0.8220 0.3152 +vn 0.6953 0.6862 0.2138 +vn 0.7799 0.0704 0.6220 +vn 0.4706 0.6888 0.5514 +vn 0.4588 0.6983 0.5495 +vn 0.3614 -0.8754 0.3210 +vn 0.2938 -0.7072 0.6431 +vn 0.0011 -0.8263 0.5633 +vn 0.2465 -0.6787 0.6918 +vn 0.0062 -0.9613 0.2754 +vn 0.0007 -0.7865 -0.6176 +vn 0.2577 -0.8777 -0.4040 +vn 0.3533 -0.9192 -0.1741 +vn 0.3254 -0.9446 0.0430 +vn -0.0245 0.9007 0.4337 +vn 0.0354 0.4339 0.9003 +vn -0.0412 -0.1623 0.9859 +vn 0.0327 -0.7782 0.6272 +vn -0.0253 -0.9921 -0.1229 +vn -0.0212 -0.9872 -0.1579 +vn 0.0133 -0.9014 -0.4328 +vn 0.0181 -0.8829 -0.4693 +vn -0.0203 -0.2348 -0.9718 +vn -0.0162 -0.1987 -0.9799 +vn 0.0226 0.1458 -0.9891 +vn 0.0269 0.1843 -0.9825 +vn -0.0220 0.7358 -0.6769 +vn 0.0332 0.9831 -0.1803 +vn -0.0099 -0.6988 -0.7153 +vn 0.0009 -0.8612 -0.5082 +vn 0.2162 -0.5300 -0.8200 +vn 0.0061 -0.9570 0.2901 +vn -0.0144 -0.7030 0.7111 +vn -0.0080 -0.8359 0.5489 +vn 0.0012 -0.9522 0.3055 +vn 0.0077 -0.9649 0.2626 +vn 0.2896 -0.5268 -0.7992 +vn 0.2498 -0.8297 -0.4992 +vn -0.0089 -0.9707 -0.2402 +vn 0.0098 -0.9892 -0.1463 +vn 0.0029 -0.9551 -0.2963 +vn -0.0007 -0.5590 0.8292 +vn 0.2587 -0.4249 0.8675 +vn -0.0071 -0.3483 0.9373 +vn 0.0148 -0.2404 0.9706 +vn 0.4279 -0.7721 -0.4699 +vn 0.6585 -0.5319 -0.5325 +vn 0.6438 -0.6381 -0.4224 +vn 0.6145 -0.5388 0.5762 +vn 0.6251 -0.4765 0.6182 +vn 0.6372 -0.7182 0.2796 +vn -0.9759 -0.1144 -0.1857 +vn 0.6402 -0.7459 0.1840 +vn 0.5131 -0.7246 0.4601 +vn -0.7432 -0.5908 0.3139 +vn 0.8640 0.4905 0.1137 +vn 0.8113 0.5817 0.0586 +vn 0.9121 0.3507 0.2123 +vn 0.9908 -0.1162 0.0696 +vn 0.9865 -0.1245 0.1067 +vn 0.9717 -0.1892 0.1412 +vn 0.9946 -0.0896 0.0522 +vn 0.9783 0.1156 0.1717 +vn 0.9991 0.0274 0.0334 +vn 0.9303 0.0032 -0.3668 +vn 0.9655 0.0641 -0.2523 +vn 0.8455 -0.0885 -0.5266 +vn 0.9491 -0.2292 -0.2161 +vn 0.9206 -0.3676 -0.1318 +vn 0.9646 -0.2624 -0.0280 +vn 0.7861 -0.1360 -0.6030 +vn 0.9982 -0.0559 -0.0208 +vn 0.9996 -0.0205 0.0209 +vn 0.9730 -0.2237 0.0563 +vn 0.9562 -0.2789 0.0893 +vn 0.9995 -0.0286 0.0109 +vn -0.6372 -0.1645 -0.7530 +vn -0.9638 -0.2623 -0.0484 +vn -0.9619 -0.2681 -0.0543 +vn -0.9474 -0.3061 -0.0933 +vn -0.9795 0.1842 0.0819 +vn -0.9690 0.2469 0.0007 +vn -0.9904 0.0832 0.1108 +vn -0.9600 0.2507 -0.1249 +vn -0.9749 -0.2225 -0.0083 +vn -0.8083 -0.5578 -0.1886 +vn -0.8500 -0.5054 -0.1486 +vn -0.8391 -0.5201 -0.1596 +vn -0.9731 0.1630 -0.1625 +vn -0.8027 -0.3299 -0.4969 +vn -0.9999 0.0101 0.0101 +vn -0.9994 -0.0340 0.0055 +vn -0.9811 -0.1829 0.0631 +vn -0.9791 -0.1978 0.0472 +vn -0.9986 -0.0525 -0.0076 +vn -0.9991 -0.0371 -0.0182 +vn -0.8906 -0.0501 0.4520 +vn 0.7411 -0.5421 0.3961 +vn -0.0002 -0.8964 0.4433 +vn -0.4804 -0.8296 -0.2846 +vn 0.6340 -0.6401 -0.4339 +vn -0.5736 -0.2559 -0.7781 +vn 0.6603 0.0150 -0.7509 +vn -0.7798 0.4435 -0.4418 +vn 0.6277 0.7029 -0.3347 +vn -0.2125 0.8985 0.3841 +vn -0.4752 0.7908 0.3858 +vn -0.1158 0.9193 0.3762 +vn -0.4975 0.7777 0.3844 +vn 0.4211 0.3145 0.8507 +vn 0.4266 -0.6501 -0.6288 +vn -0.3023 -0.9464 -0.1139 +vn 0.1247 -0.8245 0.5519 +vn -0.1664 -0.0675 0.9837 +vn -0.3995 -0.0902 0.9123 +vn -0.1449 -0.0652 0.9873 +vn -0.4529 -0.0949 0.8865 +vn 0.5965 0.5092 0.6204 +vn -0.6961 0.6044 0.3875 +vn 0.5836 0.8097 0.0616 +vn -0.7038 0.6523 -0.2816 +vn 0.2275 0.7670 -0.6000 +vn -0.1157 0.7430 0.6592 +vn 0.7166 0.6372 -0.2835 +vn 0.0882 0.2742 -0.9576 +vn -0.6711 0.0049 -0.7414 +vn -0.8571 -0.4955 -0.1411 +vn -0.3737 -0.2284 0.8990 +vn 0.3700 -0.6579 0.6559 +vn -0.3009 -0.7581 -0.5786 +vn 0.2788 -0.3505 -0.8941 +vn -0.3284 0.8508 -0.4102 +vn 0.3715 0.9278 0.0346 +vn 0.4161 0.8614 0.2913 +vn -0.5313 -0.1948 0.8245 +vn 0.3888 -0.6972 0.6023 +vn -0.0396 -0.7295 -0.6828 +vn 0.4643 -0.2450 -0.8511 +vn -0.5644 0.6967 -0.4428 +vn 0.9994 -0.0015 0.0347 +vn 0.9988 0.0454 -0.0204 +vn 0.9986 0.0130 -0.0511 +vn 0.9989 0.0320 -0.0333 +vn 0.9987 0.0129 -0.0501 +vn 0.9972 0.0739 0.0083 +vn -0.9949 -0.0991 0.0177 +vn -0.9994 0.0320 -0.0152 +vn -0.9930 -0.1162 0.0220 +vn 0.0186 -0.6843 -0.7289 +vn -0.0245 -0.8098 -0.5862 +vn 0.0290 -0.6497 -0.7596 +vn -0.0716 0.5177 -0.8526 +vn -0.0571 0.5684 -0.8208 +vn -0.0060 0.7242 -0.6895 +vn 0.0086 0.7627 -0.6467 +vn -0.0609 0.8127 0.5794 +vn -0.0455 0.7760 0.6291 +vn 0.0078 0.6288 0.7776 +vn 0.0215 0.5858 0.8101 +vn -0.0486 -0.5809 0.8125 +vn -0.0377 -0.6153 0.7874 +vn 0.0060 -0.7396 0.6730 +vn 0.0180 -0.7697 0.6382 +vn -0.0383 -0.8441 -0.5349 +vn -0.9925 0.1198 0.0233 +vn -0.9917 -0.0134 0.1278 +vn -0.9936 0.1122 0.0137 +vn -0.9882 -0.1534 -0.0019 +vn -0.9902 -0.1119 0.0831 +vn -0.9904 -0.1172 -0.0731 +vn -0.9913 0.0201 0.1303 +vn -0.9924 0.0078 -0.1225 +vn -0.9921 0.0276 -0.1224 +vn -0.1125 -0.4176 -0.9016 +vn -0.0673 -0.3712 -0.9261 +vn -0.0648 -0.3686 -0.9273 +vn -0.0058 -0.3058 -0.9521 +vn 0.0637 0.5391 -0.8398 +vn -0.0919 0.6737 -0.7332 +vn -0.1111 0.6881 -0.7170 +vn -0.2299 0.7652 -0.6013 +vn 0.2170 0.9604 0.1750 +vn -0.1713 0.6528 0.7379 +vn -0.0445 0.5214 0.8521 +vn -0.0535 0.5315 0.8454 +vn 0.0955 0.3514 0.9313 +vn -0.1151 -0.4313 0.8948 +vn 0.0177 -0.5933 0.8048 +vn 0.0276 -0.6041 0.7964 +vn 0.1494 -0.7242 0.6732 +vn -0.1044 -0.9902 0.0924 +vn 0.0150 -0.9961 -0.0867 +vn 0.0276 -0.9941 -0.1053 +vn 0.1529 -0.9449 -0.2896 +vn 0.7997 -0.5674 0.1963 +vn 0.4873 -0.6950 -0.5287 +vn -0.0694 0.2535 -0.9648 +vn 0.8302 0.5362 0.1524 +vn 0.7620 0.5720 0.3036 +vn 0.7709 0.5687 0.2868 +vn 0.6690 0.5916 0.4500 +vn -0.2986 -0.4725 0.8292 +vn -0.9660 -0.2524 0.0563 +vn 0.9995 0.0062 -0.0311 +vn 0.9994 -0.0053 -0.0354 +vn 0.9997 0.0239 -0.0108 +vn 0.9998 -0.0190 -0.0039 +vn 0.9998 -0.0166 0.0106 +vn 0.9998 0.0051 0.0185 +vn 0.9996 0.0263 0.0144 +vn -0.9994 0.0213 0.0258 +vn -0.9964 0.0489 0.0699 +vn -0.9969 0.0419 -0.0661 +vn -0.9948 0.0278 -0.0983 +vn 0.0027 -0.5853 -0.8108 +vn -0.0099 -0.3635 -0.9315 +vn -0.0107 -0.3488 -0.9371 +vn 0.0033 -0.5952 -0.8036 +vn 0.0062 -0.9174 0.3980 +vn -0.0207 -0.9986 0.0486 +vn -0.0226 -0.9995 0.0219 +vn 0.0079 -0.9079 0.4192 +vn 0.0040 0.3518 0.9361 +vn -0.0233 -0.0198 0.9995 +vn -0.0249 -0.0430 0.9988 +vn 0.0057 0.3737 0.9276 +vn -0.0030 0.9985 0.0551 +vn -0.0124 0.9762 0.2166 +vn -0.0129 0.9742 0.2255 +vn -0.0025 0.9989 0.0469 +vn 0.0066 0.4449 -0.8956 +vn -0.0142 0.7409 -0.6715 +vn -0.0152 0.7524 -0.6585 +vn 0.0076 0.4299 -0.9028 +vn -0.9954 -0.0909 -0.0300 +vn -0.9956 -0.0468 -0.0815 +vn -0.9954 -0.0956 -0.0012 +vn -0.9943 -0.0039 -0.1067 +vn -0.9960 0.0544 -0.0708 +vn -0.9949 0.0927 -0.0389 +vn -0.9952 0.0946 0.0231 +vn -0.9953 0.0787 0.0564 +vn -0.9952 0.0327 0.0926 +vn -0.9923 -0.0429 0.1159 +vn -0.9946 -0.0796 0.0663 +vn 0.1674 -0.7381 -0.6536 +vn 0.0907 -0.7968 -0.5975 +vn 0.0937 -0.7947 -0.5998 +vn -0.0076 -0.8566 -0.5160 +vn -0.1104 -0.9297 0.3514 +vn 0.2599 -0.5865 0.7671 +vn 0.1116 -0.4539 0.8840 +vn 0.1314 -0.4727 0.8714 +vn -0.0690 -0.2685 0.9608 +vn 0.1093 0.8064 0.5812 +vn 0.1243 0.8139 0.5676 +vn -0.0128 0.7324 0.6807 +vn 0.2132 0.8510 0.4799 +vn -0.1811 0.9440 -0.2756 +vn 0.2071 0.5074 -0.8364 +vn -0.1532 0.0508 -0.9869 +vn -0.1238 0.1877 -0.9744 +vn -0.0016 0.0595 -0.9982 +vn 0.0017 0.0561 -0.9984 +vn 0.1239 -0.0740 -0.9895 +vn -0.1238 0.7500 0.6497 +vn -0.0017 0.8347 0.5506 +vn 0.0016 0.8366 0.5478 +vn 0.1238 0.8940 0.4307 +vn -0.9487 0.0761 -0.3070 +vn 0.9986 0.0179 -0.0490 +vn 0.9969 0.0606 -0.0504 +vn 0.9748 0.1862 -0.1228 +vn 0.9383 0.3459 -0.0013 +vn 0.7734 0.1345 -0.6195 +vn 0.8418 0.0774 -0.5343 +vn 0.9265 -0.0193 -0.3758 +vn 0.9636 -0.0883 -0.2524 +vn 0.4567 -0.8553 0.2448 +vn 0.9737 -0.1976 0.1135 +vn 0.9946 -0.0902 0.0518 +vn 0.9915 -0.1127 0.0647 +vn 0.4440 -0.6536 -0.6129 +vn 0.2249 -0.7266 -0.6492 +vn 0.4288 -0.6601 -0.6167 +vn 0.9922 -0.0790 0.0962 +vn 0.9993 -0.0347 0.0152 +vn 0.9796 -0.1815 0.0868 +vn 0.9812 -0.1708 0.0899 +vn 0.9977 -0.0678 0.0004 +vn 0.9997 0.0067 0.0240 +vn 0.9983 -0.0542 -0.0219 +vn 0.9876 0.1458 0.0579 +vn 0.9993 0.0340 0.0145 +vn 0.9870 0.1469 0.0656 +vn -0.9898 -0.0127 0.1418 +vn -0.9989 -0.0324 0.0350 +vn -0.9017 -0.3005 -0.3107 +vn -0.8994 0.0835 -0.4290 +vn -0.9313 0.0408 -0.3618 +vn -0.9524 0.0056 -0.3046 +vn -0.9721 -0.2285 -0.0526 +vn 0.1002 -0.8745 0.4746 +vn -0.8281 -0.3505 -0.4374 +vn -0.8805 0.1051 -0.4623 +vn -0.9997 0.0252 0.0063 +vn -0.9997 -0.0217 0.0093 +vn -0.9936 -0.1046 0.0433 +vn -0.9862 -0.1524 0.0647 +vn -0.9887 -0.1311 0.0726 +vn -0.9997 -0.0206 0.0133 +vn -0.9998 0.0208 -0.0047 +vn -0.9988 0.0283 -0.0407 +vn -0.9899 0.1208 0.0736 +vn -0.9813 0.1826 0.0613 +vn -0.5208 -0.6421 0.5626 +vn -0.6512 -0.4832 0.5852 +vn -0.4865 -0.6808 0.5476 +vn -0.6717 -0.4813 0.5631 +vn 0.6603 -0.6657 0.3477 +vn -0.7796 -0.6008 -0.1766 +vn 0.7949 -0.4605 -0.3951 +vn -0.6995 -0.0301 -0.7140 +vn 0.5989 0.2340 -0.7659 +vn -0.6340 0.6401 -0.4339 +vn 0.4804 0.8296 -0.2846 +vn -0.0273 0.8857 0.4634 +vn -0.0788 0.8798 0.4688 +vn -0.0161 0.8867 0.4621 +vn -0.0870 0.8786 0.4695 +vn -0.2731 0.3384 0.9005 +vn -0.8345 0.4320 0.3421 +vn -0.8105 0.5182 0.2730 +vn -0.8475 0.3428 0.4052 +vn 0.8385 0.4799 -0.2580 +vn -0.7645 0.6192 0.1790 +vn 0.7311 0.0471 -0.6807 +vn -0.1612 -0.2717 -0.9488 +vn 0.0670 -0.9624 -0.2634 +vn 0.1974 -0.7328 -0.6512 +vn -0.3740 -0.9255 0.0605 +vn -0.4641 -0.5886 0.6620 +vn 0.4418 -0.0633 0.8949 +vn -0.3145 0.0664 0.9469 +vn 0.1274 0.7095 0.6931 +vn -0.5596 0.8273 0.0486 +vn 0.6362 0.6588 -0.4016 +vn -0.1664 0.7243 -0.6692 +vn -0.8814 0.4666 -0.0735 +vn -0.4409 -0.8217 0.3613 +vn -0.5083 0.5902 0.6271 +vn 0.7158 -0.6421 0.2746 +vn -0.0710 -0.5477 0.8337 +vn 0.0632 -0.4135 -0.9083 +vn -0.4789 -0.0146 -0.8777 +vn 0.4574 0.8833 -0.1025 +vn -0.1328 0.3272 0.9356 +vn 0.3913 -0.0169 0.9201 +vn -0.4678 -0.8838 0.0033 +vn 0.3126 -0.7341 -0.6028 +vn -0.5632 0.4582 -0.6877 +vn 0.0914 0.8752 -0.4751 +vn 0.0108 0.0316 0.9994 +vn 0.0196 0.0224 0.9996 +vn 0.0336 0.0002 0.9994 +vn -0.0327 0.0026 0.9995 +vn -0.0493 0.0000 0.9988 +vn -0.0225 -0.0247 0.9994 +vn 0.0143 -0.0305 0.9994 +vn 0.0345 -0.0255 0.9991 +vn 0.0021 -0.0440 0.9990 +vn -0.0207 0.0252 0.9995 +vn 0.0195 -0.0101 -0.9998 +vn 0.0302 -0.0232 -0.9993 +vn 0.0242 -0.0494 -0.9985 +vn 0.0229 0.0049 -0.9997 +vn -0.0050 0.0489 -0.9988 +vn 0.2857 -0.9582 -0.0158 +vn 0.2693 -0.9630 -0.0117 +vn 0.2660 -0.9639 -0.0109 +vn 0.2890 -0.9572 -0.0166 +vn -0.8907 -0.4545 0.0074 +vn -0.8909 -0.4541 0.0073 +vn -0.8929 -0.4502 0.0064 +vn -0.8932 -0.4496 0.0063 +vn -0.9177 0.3956 -0.0375 +vn -0.4822 0.8756 0.0304 +vn -0.4441 0.8956 0.0238 +vn -0.1556 0.9875 -0.0233 +vn -0.0958 0.9949 -0.0325 +vn 0.9380 0.3467 -0.0019 +vn 0.9542 0.2990 0.0109 +vn 0.9576 0.2878 0.0139 +vn 0.9345 0.3561 -0.0045 +vn -0.0274 -0.0632 -0.9976 +vn 0.0776 -0.0506 -0.9957 +vn 0.0210 -0.0696 -0.9974 +vn 0.0763 -0.0042 -0.9971 +vn 0.0292 0.0834 -0.9961 +vn -0.0753 0.0197 -0.9970 +vn -0.0233 0.0700 -0.9973 +vn -0.0766 0.0444 -0.9961 +vn 0.0598 0.0547 -0.9967 +vn -0.0382 -0.0700 -0.9968 +vn -0.0665 -0.0278 -0.9974 +vn 0.9296 0.3621 -0.0682 +vn 0.8878 0.4601 0.0023 +vn 0.8769 0.4804 0.0175 +vn 0.8203 0.5656 0.0849 +vn 0.2400 0.9640 -0.1143 +vn 0.0415 0.9991 -0.0037 +vn -0.0217 0.9993 0.0313 +vn -0.2015 0.9708 0.1304 +vn -0.6427 0.7612 -0.0869 +vn -0.8964 0.4405 -0.0495 +vn -0.8437 0.5368 0.0078 +vn -0.9984 0.0353 0.0433 +vn -0.9442 -0.3268 -0.0403 +vn -0.8913 -0.4527 0.0245 +vn -0.7370 -0.6713 -0.0778 +vn -0.1925 -0.9813 -0.0025 +vn -0.2348 -0.9718 0.0200 +vn -0.3000 -0.9524 0.0551 +vn -0.1201 -0.9919 -0.0404 +vn 0.6648 -0.7452 -0.0518 +vn 0.7568 -0.6532 0.0223 +vn 0.4656 -0.8829 0.0609 +vn 0.8376 -0.5448 -0.0406 +vn 0.9437 -0.3210 0.0799 +vn 0.9868 -0.0555 0.1524 +vn 0.5636 0.7816 -0.2672 +vn 0.0237 0.9885 0.1495 +vn -0.9872 0.1001 -0.1238 +vn -0.9865 0.0780 -0.1440 +vn -0.9867 0.0815 -0.1408 +vn -0.9848 0.0554 -0.1644 +vn 0.3992 -0.8877 -0.2294 +vn -0.0239 -0.9942 0.1048 +vn -0.0422 -0.9991 -0.0068 +vn -0.0461 -0.9988 -0.0169 +vn -0.0391 -0.9989 -0.0263 +vn -0.0340 -0.9993 0.0158 +vn -0.0040 -0.9992 0.0402 +vn 0.0356 -0.9993 0.0137 +vn -0.0057 -0.9991 0.0420 +vn 0.0235 -0.9993 0.0300 +vn 0.0199 -0.9996 -0.0184 +vn 0.0323 -0.9994 -0.0101 +vn 0.0184 -0.9997 -0.0183 +vn 0.0189 0.9997 0.0140 +vn 0.0080 0.9994 0.0328 +vn -0.0158 0.9995 0.0269 +vn 0.0079 0.9999 0.0101 +vn 0.0779 0.9968 -0.0187 +vn -0.9612 0.0576 0.2697 +vn -0.4588 -0.0296 0.8881 +vn 0.5208 0.0005 0.8537 +vn 0.2105 0.0316 0.9771 +vn 0.1733 0.0349 0.9842 +vn 0.5587 -0.0038 0.8294 +vn 0.9977 -0.0119 -0.0660 +vn 0.9735 0.0268 0.2271 +vn 0.9630 0.0322 0.2676 +vn 0.9943 -0.0170 -0.1050 +vn 0.2088 -0.0108 -0.9779 +vn 0.4889 0.0296 -0.8718 +vn 0.5306 0.0360 -0.8469 +vn 0.1670 -0.0165 -0.9858 +vn -0.5574 0.0337 -0.8296 +vn -0.9286 -0.0262 -0.3702 +vn -0.0815 0.9962 0.0322 +vn -0.0317 0.9975 -0.0639 +vn -0.0727 0.9972 -0.0182 +vn -0.0563 0.9965 0.0625 +vn 0.0792 0.9954 -0.0541 +vn 0.0675 0.9977 0.0109 +vn 0.0260 0.9976 -0.0642 +vn 0.0624 0.9969 0.0476 +vn -0.0452 0.9971 -0.0616 +vn 0.0011 0.9978 0.0658 +vn 0.0106 0.9977 0.0675 +vn -0.8384 0.0623 -0.5414 +vn -0.7677 0.0116 -0.6408 +vn -0.7050 -0.0269 -0.7087 +vn -0.6164 -0.0749 -0.7838 +vn -0.1351 0.0947 -0.9863 +vn -0.0189 0.0305 -0.9994 +vn 0.0487 -0.0071 -0.9988 +vn 0.1864 -0.0839 -0.9789 +vn 0.7917 0.0089 -0.6108 +vn 0.8457 0.0883 -0.5263 +vn 0.8372 0.0744 -0.5419 +vn 0.8710 0.1345 -0.4725 +vn 0.9532 -0.1270 0.2743 +vn 0.6953 0.1505 0.7027 +vn 0.2791 -0.1090 0.9541 +vn -0.3540 0.0953 0.9304 +vn -0.4755 0.0214 0.8795 +vn -0.5169 -0.0056 0.8561 +vn -0.6257 -0.0818 0.7758 +vn -0.9581 0.0861 0.2733 +vn -0.9888 0.0239 0.1473 +vn -0.9975 -0.0145 0.0685 +vn -0.9952 -0.0769 -0.0611 +vn -0.4443 -0.1642 -0.8807 +vn -0.4227 -0.1408 -0.8953 +vn -0.4257 -0.1439 -0.8934 +vn -0.4070 -0.1238 -0.9050 +vn 0.8678 0.1496 -0.4738 +vn 0.9507 -0.2270 0.2113 +vn 0.9587 -0.2672 0.0973 +vn 0.9427 -0.2081 0.2608 +vn 0.9102 -0.1576 0.3831 +vn -0.8320 0.1135 0.5431 +vn -0.5477 -0.3509 0.7596 +vn -0.5235 0.8184 0.2369 +vn -0.8831 0.1416 -0.4474 +vn -0.9924 -0.0753 0.0971 +vn -0.1241 -0.9835 0.1318 +vn -0.1130 -0.9891 0.0943 +vn -0.1281 -0.9810 0.1455 +vn -0.1078 -0.9912 0.0766 +vn 0.8309 -0.4377 -0.3434 +vn 0.7817 0.0328 0.6229 +vn 0.5742 0.6784 -0.4584 +vn 0.6074 0.5873 -0.5349 +vn 0.5919 0.6340 -0.4977 +vn 0.7251 -0.4598 0.5127 +vn 0.6220 0.5323 -0.5743 +vn -0.5331 -0.8298 -0.1650 +vn -0.6257 -0.7721 0.1109 +vn -0.4974 -0.8329 -0.2426 +vn -0.6438 -0.7394 0.1972 +vn -0.9895 0.0014 -0.1448 +vn -0.9924 0.0087 -0.1229 +vn -0.9885 -0.0007 -0.1511 +vn -0.9935 0.0121 -0.1128 +vn -0.5295 0.8118 0.2464 +vn -0.3299 0.8710 -0.3640 +vn 0.4292 0.8511 0.3024 +vn 0.6550 0.6942 -0.2984 +vn 0.9243 0.0993 0.3685 +vn 0.9442 -0.1467 -0.2948 +vn 0.4835 -0.8744 0.0404 +vn -0.7474 0.1195 0.6536 +vn 0.0112 -0.4332 0.9012 +vn 0.0030 -0.1163 0.9932 +vn 0.0069 -0.2660 0.9640 +vn 0.0114 -0.2444 -0.9696 +vn 0.0033 -0.0699 -0.9976 +vn 0.0152 -0.3273 -0.9448 +vn -0.0076 -0.9093 0.4160 +vn -0.1260 -0.9431 0.3078 +vn 0.0757 -0.8711 0.4853 +vn 0.5363 -0.6772 -0.5038 +vn 0.8457 -0.3701 0.3844 +vn 0.7249 0.5843 -0.3647 +vn 0.6183 0.7669 0.1717 +vn -0.6610 0.7383 -0.1339 +vn -0.7380 0.6314 0.2381 +vn -0.6891 0.7232 -0.0461 +vn -0.7396 0.5967 0.3113 +vn -0.8883 -0.3910 -0.2409 +vn -0.6815 0.6532 -0.3300 +vn -0.7108 0.0947 -0.6970 +vn 0.8895 0.4108 0.2002 +vn 0.9167 0.1675 -0.3627 +vn 0.8573 -0.4415 0.2646 +vn 0.6349 -0.7041 -0.3181 +vn 0.2587 -0.9083 0.3287 +vn -0.2583 -0.9123 -0.3179 +vn -0.5992 -0.7334 0.3212 +vn -0.8534 -0.4409 -0.2779 +vn -0.9557 0.0903 0.2802 +vn -0.8870 0.3767 -0.2671 +vn -0.5510 0.7874 0.2765 +vn -0.1742 0.9039 -0.3908 +vn 0.2318 0.9376 0.2593 +vn 0.1986 -0.7922 0.5771 +vn 0.8139 0.0786 -0.5756 +vn -0.5177 -0.0858 -0.8513 +vn -0.9911 0.0620 0.1177 +vn -0.9837 -0.0689 0.1663 +vn -0.9890 0.1091 0.0996 +vn -0.9762 -0.1160 0.1831 +vn -0.0306 0.0684 0.9972 +vn 0.0184 -0.0621 0.9979 +vn -0.0482 0.1153 0.9922 +vn 0.0361 -0.1091 0.9934 +vn 0.9437 0.0884 0.3189 +vn 0.9476 0.0699 0.3116 +vn 0.9414 0.0982 0.3227 +vn 0.9501 0.0573 0.3066 +vn 0.7527 -0.1538 -0.6401 +vn 0.6745 0.1019 -0.7312 +vn 0.7343 -0.0735 -0.6748 +vn 0.6474 0.1626 -0.7446 +vn 0.7098 0.6543 0.2609 +vn 0.0267 -0.4708 0.8818 +vn -0.6908 0.3366 0.6399 +vn -0.8597 -0.3516 0.3705 +vn -0.9080 0.3853 -0.1647 +vn -0.6846 -0.3563 -0.6358 +vn -0.4970 0.1869 -0.8474 +vn 0.2000 -0.1827 -0.9626 +vn 0.2474 -0.0526 -0.9675 +vn 0.1864 -0.2176 -0.9581 +vn 0.2665 0.0039 -0.9638 +vn 0.9113 0.2025 -0.3585 +vn 0.9266 -0.3451 -0.1496 +vn 0.7702 0.3633 0.5242 +vn 0.6309 -0.2469 0.7356 +vn -0.7116 0.4147 0.5671 +vn -0.2016 0.9774 -0.0642 +vn -0.0420 0.9990 -0.0134 +vn -0.2528 0.9642 -0.0805 +vn -0.5181 -0.8076 -0.2816 +vn 0.0756 0.4000 0.9134 +vn -0.0782 0.3069 0.9485 +vn 0.1179 0.4234 0.8982 +vn 0.4031 -0.5988 0.6921 +vn 0.8133 0.5556 0.1731 +vn 0.6882 -0.4971 -0.5284 +vn 0.5108 0.1664 -0.8435 +vn -0.4880 -0.0561 -0.8710 +vn -0.4854 -0.0484 -0.8729 +vn -0.4896 -0.0609 -0.8698 +vn -0.4840 -0.0444 -0.8739 +vn -0.9957 0.0079 0.0921 +vn -0.9924 -0.0422 -0.1152 +vn -0.9961 -0.0014 0.0883 +vn -0.9948 -0.0451 -0.0913 +vn -0.9352 -0.0684 -0.3474 +vn 0.8720 0.1373 -0.4698 +vn 0.9059 -0.2255 0.3584 +vn 0.7855 0.3183 0.5307 +vn 0.2824 -0.2661 0.9216 +vn -0.1204 0.3946 0.9109 +vn -0.4476 -0.2781 0.8499 +vn -0.9798 0.1221 0.1584 +vn -0.9682 -0.1218 0.2187 +vn -0.9665 0.2210 0.1305 +vn -0.9454 -0.2207 0.2396 +vn -0.6651 0.3151 -0.6770 +vn -0.3676 -0.5206 -0.7706 +vn 0.2411 0.3049 -0.9214 +vn 0.2903 0.5092 0.8102 +vn 0.7030 -0.6612 -0.2619 +vn 0.0591 0.9960 -0.0670 +vn 0.2144 0.9461 -0.2429 +vn 0.2943 0.8956 -0.3335 +vn 0.2086 -0.9133 -0.3499 +vn 0.0510 -0.9950 -0.0855 +vn 0.1381 -0.9630 -0.2316 +vn 0.0037 0.2897 0.9571 +vn 0.0039 0.1453 0.9894 +vn -0.0007 0.2894 0.9572 +vn -0.0082 0.5626 0.8267 +vn 0.0043 0.4292 0.9032 +vn 0.0046 -0.9722 -0.2340 +vn -0.0011 -0.9561 -0.2929 +vn 0.0187 -0.9288 -0.3702 +vn -0.0057 -0.7950 -0.6066 +vn 0.0067 0.0135 0.9999 +vn 0.0586 0.2377 0.9696 +vn 0.0498 0.1030 0.9934 +vn -0.0079 0.1567 0.9876 +vn 0.0007 0.2794 0.9602 +vn -0.0007 0.1948 0.9808 +vn -0.3899 0.1940 0.9002 +vn -0.0021 0.2706 0.9627 +vn 0.0001 0.2702 0.9628 +vn 0.0087 0.2721 0.9622 +vn -0.0090 0.1655 0.9862 +vn -0.0011 0.2674 0.9636 +vn -0.0024 0.2653 0.9642 +vn 0.0008 0.2767 0.9610 +vn -0.1951 0.2595 0.9458 +vn 0.0137 0.0892 -0.9959 +vn -0.0301 0.1292 -0.9912 +vn -0.0241 0.1805 -0.9833 +vn -0.0230 0.0543 -0.9983 +vn 0.0194 0.3907 -0.9203 +vn 0.0269 0.4326 -0.9012 +vn -0.0046 0.5160 -0.8566 +vn -0.0066 0.5168 -0.8561 +vn 0.0070 -0.8702 0.4927 +vn -0.0427 -0.9504 0.3081 +vn -0.0061 -0.8724 0.4888 +vn -0.0032 -0.9024 0.4308 +vn 0.0308 -0.9954 0.0910 +vn -0.0477 -0.9961 -0.0736 +vn 0.0506 -0.9535 -0.2972 +vn -0.0009 -0.9029 -0.4299 +vn -0.0171 -0.8719 -0.4893 +vn -0.0048 -0.8740 -0.4859 +vn -0.0212 -0.9569 -0.2897 +vn -0.0040 -0.9762 -0.2167 +vn -0.0539 -0.9611 -0.2710 +vn -0.0012 -0.9720 -0.2351 +vn -0.0009 -0.9607 -0.2776 +vn 0.0006 -0.9920 -0.1263 +vn -0.0174 -0.9971 -0.0747 +vn -0.0073 -0.9648 -0.2628 +vn -0.0012 -0.9644 -0.2646 +vn -0.0028 -0.9914 -0.1311 +vn -0.0001 -0.9637 -0.2669 +vn -0.0004 -0.9639 -0.2663 +vn -0.0003 -0.9639 -0.2663 +vn -0.0002 -0.9603 -0.2790 +vn 0.0050 0.5024 0.8646 +vn -0.0229 0.3389 0.9406 +vn 0.0019 0.5014 0.8652 +vn -0.0226 0.3982 0.9170 +vn 0.0049 0.0740 0.9972 +vn -0.0149 -0.0517 0.9986 +vn 0.0184 -0.2947 0.9554 +vn -0.0134 -0.4047 0.9144 +vn -0.0183 -0.2222 0.9748 +vn -0.0180 -0.2972 0.9547 +vn 0.0022 -0.2490 -0.9685 +vn 0.0009 -0.1096 -0.9940 +vn 0.0005 -0.2552 -0.9669 +vn 0.0002 -0.1125 -0.9937 +vn -0.0001 0.1934 -0.9811 +vn 0.0002 0.1942 -0.9810 +vn 0.0001 0.4695 -0.8829 +vn -0.0011 0.4653 -0.8852 +vn 0.0011 0.6821 -0.7312 +vn -0.0006 0.6754 -0.7375 +vn 0.0009 0.8613 -0.5081 +vn -0.0010 0.8593 -0.5114 +vn -0.0054 0.9786 -0.2055 +vn 0.0011 0.9682 -0.2501 +vn 0.0059 1.0000 0.0066 +vn -0.0068 0.9932 0.1162 +vn 0.0038 0.9784 0.2065 +vn -0.0033 0.9654 0.2606 +vn -0.0008 0.9613 0.2754 +vn 0.0014 -0.0176 0.9998 +vn -0.0141 -0.1433 0.9896 +vn -0.2039 -0.2982 0.9325 +vn -0.0348 -0.4674 0.8834 +vn -0.0173 -0.5018 0.8648 +vn -0.0048 -0.6826 0.7308 +vn -0.0185 -0.7500 0.6612 +vn -0.0057 -0.8294 0.5587 +vn -0.0225 -0.9351 0.3536 +vn -0.0040 -0.9312 0.3645 +vn -0.0076 -0.9920 0.1256 +vn -0.0073 0.8614 -0.5079 +vn 0.0310 0.9121 -0.4087 +vn 0.0222 0.8679 -0.4962 +vn -0.0171 0.9550 -0.2962 +vn 0.0117 0.9971 -0.0752 +vn 0.0102 0.9998 -0.0150 +vn 0.0393 0.9967 0.0711 +vn 0.0552 0.9964 0.0646 +vn -0.9966 0.0314 -0.0760 +vn -0.9991 0.0246 -0.0358 +vn -0.9985 0.0124 -0.0536 +vn -0.9997 0.0140 -0.0211 +vn -0.9988 0.0059 -0.0494 +vn -0.9992 0.0326 -0.0214 +vn -0.9999 -0.0126 -0.0017 +vn -0.9984 0.0499 -0.0274 +vn -0.9994 0.0333 -0.0136 +vn -0.9988 0.0493 -0.0019 +vn -0.9990 0.0103 -0.0446 +vn -0.9989 0.0110 -0.0452 +vn -0.9985 0.0490 -0.0241 +vn -0.9982 0.0589 0.0114 +vn -0.9751 0.0260 -0.2202 +vn -0.9477 0.0334 -0.3175 +vn -0.9972 0.0704 -0.0265 +vn -0.9984 0.0220 -0.0516 +vn -0.9983 -0.0071 -0.0572 +vn 0.9989 0.0338 -0.0337 +vn 0.9999 0.0154 -0.0061 +vn 0.9997 0.0222 -0.0028 +vn -0.9978 -0.0656 0.0015 +vn -0.9986 -0.0499 0.0184 +vn -0.9988 -0.0477 0.0065 +vn -0.9989 -0.0395 0.0247 +vn -0.9989 -0.0007 0.0477 +vn -0.9990 -0.0186 0.0402 +vn -0.9997 -0.0091 0.0222 +vn -0.9964 0.0667 0.0514 +vn -0.9933 0.0814 0.0824 +vn -0.9859 0.1468 0.0801 +vn -0.9951 0.0103 0.0979 +vn -0.9366 0.0606 0.3453 +vn -0.9914 -0.1274 -0.0311 +vn -0.9885 -0.1472 -0.0336 +vn -0.9970 -0.0728 -0.0268 +vn -0.9968 -0.0285 0.0748 +vn -0.9940 -0.0839 -0.0709 +vn -0.9982 -0.0543 -0.0236 +vn -0.9995 -0.0198 0.0249 +vn -0.9994 -0.0043 0.0356 +vn -0.9993 -0.0348 0.0153 +vn -0.9140 -0.3991 -0.0732 +vn -0.9265 0.0585 0.3717 +vn -0.9987 0.0220 0.0461 +vn -0.9982 -0.0560 -0.0214 +vn -0.0012 -0.9998 0.0191 +vn 0.0018 -0.9998 0.0210 +vn -0.0122 -0.9997 0.0202 +vn -0.0005 0.0013 -1.0000 +vn -0.0005 0.0012 -1.0000 +vn -0.0006 0.0007 -1.0000 +vn -0.0006 0.0006 -1.0000 +vn 0.6966 -0.1765 -0.6954 +vn 0.6777 -0.1655 -0.7164 +vn 0.6714 -0.1017 -0.7341 +vn 0.6925 -0.0061 -0.7214 +vn 0.6753 0.1428 -0.7236 +vn 0.6701 0.2105 -0.7118 +vn 0.6796 0.3344 -0.6529 +vn 0.6653 0.4028 -0.6286 +vn 0.6196 0.5378 -0.5717 +vn 0.6881 0.6134 -0.3876 +vn 0.7055 0.6178 -0.3473 +vn 0.6696 0.7276 -0.1491 +vn 0.6619 0.7318 -0.1624 +vn 0.6809 0.7306 0.0499 +vn 0.6882 0.7205 0.0859 +vn 0.6909 0.7017 0.1740 +vn 0.7025 0.6884 0.1808 +vn -0.7194 -0.1770 -0.6717 +vn -0.7217 -0.0998 -0.6849 +vn -0.7095 -0.1701 -0.6839 +vn -0.7186 -0.0223 -0.6951 +vn -0.6715 0.1376 -0.7281 +vn -0.7081 0.2652 -0.6544 +vn -0.6843 0.3726 -0.6268 +vn -0.6985 0.4747 -0.5355 +vn -0.7003 0.4554 -0.5497 +vn -0.7041 0.5901 -0.3951 +vn -0.7098 0.6087 -0.3545 +vn -0.7024 0.6799 -0.2104 +vn -0.7009 0.6952 -0.1596 +vn -0.7135 0.7000 0.0293 +vn -0.7229 0.6909 -0.0111 +vn -0.7073 0.6906 0.1509 +vn -0.7023 0.6900 0.1750 +vn -0.7170 0.6692 0.1952 +vn -0.9067 -0.1835 0.3797 +vn -0.8613 0.1623 -0.4814 +vn -0.7601 -0.1482 -0.6327 +vn -0.8395 0.0585 -0.5403 +vn -0.7276 -0.2089 -0.6534 +vn 0.1047 0.2734 -0.9562 +vn 0.4786 -0.3512 -0.8047 +vn 0.8842 0.3300 -0.3307 +vn 0.8166 -0.5054 0.2789 +vn -0.5449 -0.1010 -0.8324 +vn -0.5609 -0.1933 -0.8050 +vn -0.5329 -0.0453 -0.8450 +vn -0.5682 -0.2504 -0.7839 +vn 0.1950 0.2554 -0.9470 +vn 0.7136 -0.3365 -0.6145 +vn 0.9070 0.1644 -0.3877 +vn 0.8651 -0.0100 0.5015 +vn -0.9402 0.0121 0.3403 +vn -0.0044 0.9997 -0.0233 +vn -0.0050 0.9997 -0.0254 +vn 0.0105 0.9992 -0.0397 +vn 0.0110 0.9991 -0.0415 +vn 0.0777 0.9947 -0.0666 +vn -0.0052 0.9997 -0.0235 +vn 0.0104 -0.9998 0.0165 +vn -0.0287 -0.9993 0.0245 +vn 0.0284 -0.9993 0.0253 +vn 0.0040 0.5815 -0.8135 +vn -0.0551 0.4935 -0.8680 +vn 0.0023 0.5650 -0.8251 +vn -0.0028 0.5046 -0.8634 +vn -0.6565 0.7543 0.0078 +vn -0.7914 0.6102 -0.0370 +vn -0.8151 0.5775 -0.0459 +vn -0.6323 0.7746 0.0149 +vn -0.6148 0.5458 -0.5693 +vn -0.6084 0.5715 -0.5506 +vn -0.6283 0.4775 -0.6142 +vn -0.6313 0.4577 -0.6261 +vn 0.2573 0.7014 -0.6648 +vn 0.2701 0.6774 -0.6842 +vn -0.0051 0.5067 -0.8621 +vn -0.0054 0.5004 -0.8658 +vn 0.6187 0.4961 -0.6092 +vn 0.6570 0.4285 -0.6203 +vn -0.0053 -0.0161 0.9999 +vn -0.0241 -0.0172 0.9996 +vn 0.0081 -0.0171 0.9998 +vn 0.0354 -0.0184 0.9992 +vn 0.0020 1.0000 0.0078 +vn 0.0017 1.0000 0.0016 +vn -0.0013 0.9838 0.1794 +vn -0.0013 0.9999 -0.0143 +vn 0.9360 -0.3143 0.1584 +vn 0.8613 0.4814 -0.1623 +vn 0.8387 0.5418 -0.0555 +vn 0.8545 0.5047 -0.1230 +vn 0.8282 0.5601 -0.0198 +vn -0.0264 0.9987 0.0443 +vn -0.0707 0.9968 -0.0383 +vn 0.0046 0.9948 0.1014 +vn -0.1032 0.9897 -0.0992 +vn -0.9275 0.3737 0.0049 +vn -0.9260 0.3773 -0.0145 +vn -0.9273 0.3744 0.0011 +vn -0.9252 0.3788 -0.0224 +vn -0.7922 -0.5747 0.2053 +vn -0.0489 -0.0331 0.9983 +vn -0.0009 -0.0132 0.9999 +vn -0.0001 0.0478 -0.9989 +vn -0.0054 0.0187 -0.9998 +vn -0.0037 0.0110 -0.9999 +vn -0.0015 0.0529 -0.9986 +vn 0.0332 0.0647 -0.9974 +vn 0.0029 -0.0115 0.9999 +vn 0.0447 -0.0183 0.9988 +vn -0.0263 0.0178 -0.9995 +vn -0.8291 0.4308 -0.3565 +vn -0.7914 -0.3508 0.5005 +vn 0.8973 -0.3983 0.1906 +vn 0.8892 0.4347 -0.1426 +vn 0.8287 0.5562 0.0624 +vn 0.8721 0.4852 -0.0638 +vn 0.8036 0.5835 0.1176 +vn 0.1838 0.9757 -0.1192 +vn -0.0033 0.9956 0.0934 +vn 0.0763 0.9971 0.0038 +vn -0.0915 0.9773 0.1910 +vn -0.5593 0.8095 -0.1786 +vn -0.9193 0.3293 0.2153 +vn -0.0002 0.8109 -0.5852 +vn 0.0023 0.7995 -0.6007 +vn -0.0623 0.8723 -0.4849 +vn 0.0011 -0.8347 -0.5507 +vn -0.0018 0.8922 0.4517 +vn -0.0440 0.8626 -0.5039 +vn -0.0999 0.8957 -0.4333 +vn -0.8902 -0.0113 -0.4554 +vn -0.8342 0.0120 -0.5514 +vn -0.6152 0.6249 -0.4807 +vn -0.6315 0.6275 -0.4554 +vn -0.6195 0.6256 -0.4742 +vn -0.6348 0.6280 -0.4501 +vn 0.0007 0.8905 -0.4550 +vn 0.0006 0.8897 -0.4566 +vn -0.0019 0.8655 -0.5009 +vn -0.0020 0.8645 -0.5026 +vn 0.6384 0.6613 -0.3939 +vn 0.6378 0.6564 -0.4028 +vn 0.6383 0.6603 -0.3957 +vn 0.6377 0.6554 -0.4047 +vn -0.0259 0.0181 0.9995 +vn 0.0149 0.0653 0.9978 +vn -0.0018 -0.7412 0.6713 +vn -0.0048 -0.7443 0.6679 +vn -0.0082 -0.7478 0.6639 +vn 0.0016 -0.7375 0.6753 +vn 0.0034 -0.9971 -0.0762 +vn -0.0052 -0.9978 -0.0660 +vn -0.0076 -0.9980 -0.0631 +vn -0.0161 -0.9985 -0.0530 +vn 0.9997 0.0225 -0.0113 +vn 1.0000 -0.0026 -0.0026 +vn 0.9992 -0.0160 0.0379 +vn 1.0000 -0.0069 0.0064 +vn 0.9986 -0.0106 0.0524 +vn 0.9992 -0.0351 0.0203 +vn 1.0000 -0.0078 0.0008 +vn 1.0000 -0.0007 0.0023 +vn 0.9996 0.0021 -0.0269 +vn 1.0000 -0.0068 0.0053 +vn 1.0000 0.0074 0.0032 +vn 0.9995 0.0043 -0.0314 +vn 0.9995 0.0234 0.0201 +vn 0.9874 0.1475 0.0572 +vn 0.9999 0.0130 -0.0034 +vn 1.0000 0.0089 0.0015 +vn 1.0000 -0.0024 -0.0034 +vn 1.0000 -0.0071 -0.0042 +vn 0.9997 -0.0191 -0.0130 +vn 0.9989 0.0232 0.0419 +vn 0.9992 0.0129 0.0371 +vn 0.9997 0.0129 0.0209 +vn 0.9995 -0.0276 0.0169 +vn 0.9997 -0.0216 -0.0109 +vn 0.9981 0.0211 0.0572 +vn 0.9998 -0.0169 0.0044 +vn -0.0207 -0.9959 0.0886 +vn -0.0100 -0.9970 0.0772 +vn -0.0075 -0.9972 0.0745 +vn 0.0014 -0.9979 0.0650 +vn -0.0241 -0.7059 -0.7079 +vn 0.0376 -0.7922 -0.6091 +vn 0.0917 -0.8548 -0.5108 +vn -0.0816 -0.6111 -0.7873 +vn 0.0068 0.0478 -0.9988 +vn 0.0123 -0.1468 -0.9891 +vn -0.0147 0.0093 -0.9998 +vn -0.0107 -0.0413 -0.9991 +vn -0.0068 -0.0372 -0.9993 +vn -0.0062 -0.0366 -0.9993 +vn -0.0026 -0.0327 -0.9995 +vn 0.0160 0.7196 -0.6942 +vn -0.0216 0.7659 -0.6426 +vn -0.0618 0.8103 -0.5827 +vn 0.0560 0.6652 -0.7446 +vn -0.0077 0.9977 0.0669 +vn -0.0038 0.9974 0.0714 +vn -0.0025 0.9973 0.0728 +vn 0.0017 0.9970 0.0777 +vn -0.0055 0.9827 0.1852 +vn -0.0457 0.9984 0.0340 +vn -0.0347 0.9993 0.0128 +vn 0.0377 0.6195 0.7841 +vn 0.0495 0.6362 0.7700 +vn 0.0580 0.6478 0.7596 +vn 0.0277 0.6051 0.7957 +vn -0.0046 -0.0862 0.9963 +vn -0.0151 -0.0735 0.9972 +vn -0.0176 -0.0705 0.9974 +vn -0.0276 -0.0582 0.9979 +vn 0.0332 0.0490 -0.9982 +vn 0.0542 0.0322 -0.9980 +vn -0.0587 0.1217 -0.9908 +vn 0.1282 -0.0273 -0.9914 +vn -0.1256 -0.9919 0.0188 +vn 0.3388 -0.6973 0.6317 +vn -0.1442 -0.2209 0.9646 +vn 0.0990 0.9453 0.3107 +vn 0.1102 0.9467 0.3027 +vn 0.0737 0.9416 0.3286 +vn 0.1393 0.9494 0.2815 +vn 0.0225 -0.1424 0.9895 +vn -0.0198 -0.2087 0.9778 +vn -0.0886 -0.3140 0.9453 +vn 0.0855 -0.0416 0.9955 +vn 0.0433 0.9730 -0.2268 +vn -0.0031 0.9877 -0.1561 +vn -0.1139 0.9933 0.0181 +vn 0.1567 0.9052 -0.3950 +vn -0.0509 -0.7444 -0.6657 +vn -0.0236 -0.7669 -0.6413 +vn 0.1164 -0.8592 -0.4982 +vn -0.1870 -0.6103 -0.7698 +vn -0.9355 -0.3293 -0.1278 +vn -0.8636 -0.4827 -0.1454 +vn -0.6648 -0.7207 -0.1963 +vn -0.6173 -0.7854 -0.0453 +vn -0.5879 -0.7794 -0.2166 +vn -0.5368 -0.1574 0.8289 +vn -0.5264 -0.0522 0.8486 +vn -0.6171 -0.5239 0.5871 +vn -0.5944 -0.7063 0.3845 +vn -0.6824 -0.5733 0.4536 +vn -0.7031 -0.7104 0.0303 +vn -0.8355 -0.2434 0.4927 +vn -0.8252 -0.2298 0.5160 +vn -0.7038 -0.6362 0.3163 +vn -0.8494 -0.1469 0.5068 +vn -0.8032 -0.5761 0.1517 +vn 0.3661 -0.1223 0.9225 +vn -0.8865 0.1183 0.4473 +vn -0.7471 0.2979 0.5942 +vn -0.5571 0.2284 0.7984 +vn -0.8530 0.1415 0.5023 +vn -0.0181 -0.2760 -0.9610 +vn 0.0422 -0.6763 -0.7354 +vn -0.0244 0.9484 0.3161 +vn 0.0134 0.7857 0.6185 +vn -0.7980 0.1682 0.5787 +vn -0.9450 0.2963 0.1384 +vn -0.0445 -0.9989 -0.0138 +vn -0.0306 -0.9995 -0.0075 +vn -0.0270 -0.9995 0.0184 +vn 0.0316 -0.9995 -0.0079 +vn 0.0223 -0.9994 -0.0261 +vn 0.0049 -0.9993 -0.0382 +vn -0.0145 -0.9994 -0.0311 +vn 0.0086 -0.9994 0.0344 +vn 0.0271 -0.9994 0.0210 +vn -0.0116 -0.9994 0.0332 +vn 0.0079 0.9995 0.0295 +vn -0.0253 0.9996 0.0087 +vn 0.0058 0.9996 0.0293 +vn 0.0211 0.9990 0.0384 +vn 0.0240 0.9990 0.0378 +vn 0.5696 0.0366 -0.8211 +vn -0.4609 -0.0229 -0.8872 +vn -0.3528 0.0003 -0.9357 +vn -0.3293 0.0052 -0.9442 +vn -0.4748 -0.0260 -0.8797 +vn -0.9977 0.0463 -0.0489 +vn -0.8254 -0.0383 0.5633 +vn -0.1985 0.0511 0.9788 +vn 0.4740 -0.0315 0.8799 +vn 0.9549 0.0463 0.2933 +vn 0.9245 -0.0362 -0.3795 +vn -0.0829 0.9965 -0.0102 +vn 0.0297 0.9969 -0.0727 +vn -0.0293 0.9974 -0.0661 +vn 0.0456 0.9952 -0.0869 +vn -0.0124 0.9957 0.0923 +vn -0.0471 0.9976 0.0506 +vn 0.0351 0.9974 0.0626 +vn 0.0824 0.9959 0.0364 +vn 0.0712 0.9974 -0.0105 +vn -0.0885 0.9956 -0.0316 +vn 0.7388 0.0119 -0.6738 +vn 0.7962 0.0759 -0.6003 +vn 0.7228 -0.0042 -0.6910 +vn 0.9751 -0.0848 0.2051 +vn 0.9393 0.0192 0.3426 +vn 0.9448 0.0075 0.3277 +vn 0.8863 0.1067 0.4507 +vn 0.3069 -0.1080 0.9456 +vn 0.0854 0.0361 0.9957 +vn 0.1162 0.0165 0.9931 +vn -0.0946 0.1484 0.9844 +vn -0.6269 -0.1112 0.7711 +vn -0.9668 0.0934 0.2378 +vn -0.9801 0.0594 0.1893 +vn -0.9845 0.0455 0.1693 +vn -0.9944 0.0012 0.1053 +vn -0.7732 -0.0165 -0.6339 +vn -0.7316 0.0217 -0.6814 +vn -0.7481 0.0070 -0.6636 +vn -0.7072 0.0424 -0.7058 +vn -0.1886 -0.0439 -0.9811 +vn -0.0533 0.0247 -0.9983 +vn -0.1124 -0.0051 -0.9936 +vn 0.0209 0.0619 -0.9979 +vn 0.6536 -0.0684 -0.7538 +vn 0.7018 0.1239 -0.7016 +vn 0.7152 0.1441 -0.6840 +vn 0.7131 0.1409 -0.6868 +vn 0.7282 0.1645 -0.6654 +vn 0.2517 0.2295 0.9402 +vn 0.6468 -0.1048 0.7554 +vn -0.7296 -0.1524 0.6667 +vn -0.9307 0.2672 -0.2496 +vn -0.6431 -0.1495 -0.7510 +vn 0.0120 -0.0257 0.9996 +vn -0.0157 -0.0309 0.9994 +vn 0.0195 -0.0291 0.9994 +vn -0.0326 0.0014 0.9995 +vn -0.0394 -0.0124 0.9991 +vn -0.0045 0.0325 0.9995 +vn -0.0277 0.0248 0.9993 +vn 0.0165 0.0309 0.9994 +vn 0.0281 0.0081 0.9996 +vn -0.0150 -0.0081 -0.9999 +vn -0.0200 -0.0119 -0.9997 +vn -0.0770 0.0177 -0.9969 +vn 0.0113 -0.0216 -0.9997 +vn 0.0276 -0.0183 -0.9995 +vn -0.7336 -0.6789 0.0307 +vn -0.9987 -0.0272 -0.0427 +vn -0.8552 0.5180 0.0159 +vn -0.0149 0.9999 0.0002 +vn -0.3481 0.9371 -0.0269 +vn -0.3832 0.9232 -0.0298 +vn 0.0205 0.9998 0.0031 +vn 0.8304 0.5571 0.0092 +vn 0.6167 0.7866 -0.0301 +vn 0.5835 0.8113 -0.0351 +vn 0.8533 0.5212 0.0145 +vn 0.7128 -0.7011 0.0185 +vn 0.8768 -0.4801 -0.0267 +vn 0.9010 -0.4324 -0.0353 +vn 0.6798 -0.7329 0.0260 +vn -0.2038 -0.9778 -0.0490 +vn -0.0785 -0.0016 -0.9969 +vn -0.0179 -0.0902 -0.9958 +vn -0.0599 -0.0379 -0.9975 +vn -0.0654 0.0344 -0.9973 +vn 0.0725 -0.0057 -0.9974 +vn 0.0532 0.0509 -0.9973 +vn 0.0749 -0.0184 -0.9970 +vn 0.0325 0.0662 -0.9973 +vn 0.0237 -0.0728 -0.9971 +vn -0.0383 0.0633 -0.9973 +vn -0.0097 0.0720 -0.9974 +vn -0.5533 -0.8316 -0.0475 +vn -0.3919 -0.9099 -0.1364 +vn -0.6097 -0.7925 -0.0127 +vn 0.0545 -0.9908 0.1241 +vn 0.7291 -0.6702 -0.1382 +vn 0.8640 -0.5035 0.0053 +vn 0.8710 -0.4910 0.0150 +vn 0.9422 -0.2991 0.1512 +vn 0.9465 0.3003 -0.1184 +vn 0.5800 0.8054 0.1224 +vn 0.4568 0.8892 0.0238 +vn 0.4808 0.8758 0.0422 +vn 0.3276 0.9422 -0.0696 +vn -0.4647 0.8840 0.0519 +vn -0.5408 0.8411 -0.0061 +vn -0.5212 0.8534 0.0093 +vn -0.5933 0.8035 -0.0490 +vn -0.9734 0.2223 0.0548 +vn -0.9965 0.0766 -0.0346 +vn -0.9930 0.1173 -0.0099 +vn -0.9955 -0.0206 -0.0929 +vn -0.7599 -0.6431 0.0946 +vn -0.8141 -0.5612 0.1495 +vn 0.4988 -0.8578 -0.1238 +vn 0.5162 -0.8443 -0.1439 +vn 0.5135 -0.8465 -0.1408 +vn 0.5335 -0.8297 -0.1643 +vn 0.4841 0.8444 -0.2295 +vn 0.8188 0.5645 0.1049 +vn -0.5345 0.8313 0.1525 +vn -0.9636 -0.0030 -0.2672 +vn 0.8208 0.5021 0.2724 +vn 0.8788 0.4369 0.1918 +vn 0.9842 0.1757 0.0237 +vn 0.9982 0.0553 0.0246 +vn 0.9988 0.0275 0.0403 +vn 0.9992 0.0324 0.0247 +vn 0.9992 0.0245 0.0323 +vn 0.9988 0.0363 -0.0316 +vn 0.9988 0.0350 -0.0341 +vn 0.9989 0.0283 -0.0371 +vn 0.9987 0.0409 -0.0302 +vn 0.9987 0.0387 -0.0341 +vn 0.6240 -0.1725 -0.7622 +vn 0.3022 -0.5516 0.7775 +vn 0.3732 -0.5167 0.7706 +vn -0.1529 -0.7120 -0.6854 +vn 0.5921 -0.6682 -0.4504 +vn -0.4493 -0.8013 -0.3950 +vn 0.7402 -0.6681 -0.0757 +vn 0.4523 -0.8814 -0.1361 +vn 0.7484 -0.6591 -0.0734 +vn -0.2084 -0.1893 0.9595 +vn -0.4242 -0.8987 0.1114 +vn 0.6635 -0.6705 0.3319 +vn 0.7719 -0.5750 0.2713 +vn 0.8156 -0.5261 0.2410 +vn 0.2663 0.2938 0.9180 +vn 0.1381 0.0436 0.9895 +vn 0.2222 0.1824 0.9578 +vn -0.1468 -0.5010 0.8529 +vn 0.6899 0.3411 0.6385 +vn 0.1864 0.7836 0.5926 +vn 0.2580 0.8056 0.5333 +vn 0.4244 0.8281 0.3662 +vn 0.4771 0.8250 0.3028 +vn 0.6968 0.7172 -0.0122 +vn 0.8344 0.4762 -0.2774 +vn -0.4707 0.6604 0.5851 +vn 0.6659 0.4343 -0.6067 +vn 0.6978 0.3384 0.6313 +vn -0.4063 -0.1077 -0.9074 +vn -0.2589 -0.4566 -0.8512 +vn 0.5250 -0.4626 -0.7144 +vn 0.5857 -0.2495 0.7712 +vn 0.6579 -0.6747 0.3346 +vn -0.4577 -0.6605 0.5952 +vn -0.1928 -0.7032 -0.6844 +vn 0.6730 0.0687 0.7364 +vn -0.4827 0.6570 0.5792 +vn -0.4569 0.8561 -0.2413 +vn -0.1615 0.7706 -0.6165 +vn 0.6945 0.1605 -0.7014 +vn 0.9319 0.0774 -0.3544 +vn 0.9268 0.1003 -0.3618 +vn 0.3279 -0.9320 -0.1544 +vn -0.9998 0.0163 -0.0077 +vn -0.9984 -0.0175 0.0538 +vn -1.0000 -0.0031 0.0022 +vn -1.0000 -0.0007 -0.0023 +vn -0.9992 -0.0376 0.0103 +vn -1.0000 -0.0005 0.0037 +vn -1.0000 0.0037 -0.0035 +vn -0.9999 0.0092 0.0118 +vn -0.9999 0.0132 0.0089 +vn -0.9997 -0.0122 -0.0233 +vn -0.9998 -0.0105 -0.0139 +vn -0.9998 -0.0215 -0.0048 +vn -1.0000 0.0062 -0.0030 +vn -0.9996 -0.0030 0.0276 +vn -0.9999 0.0047 -0.0088 +vn -1.0000 0.0029 -0.0063 +vn -1.0000 -0.0010 -0.0069 +vn -1.0000 -0.0023 -0.0080 +vn -0.9999 0.0145 0.0057 +vn -1.0000 0.0004 -0.0047 +vn -1.0000 0.0005 -0.0000 +vn 0.9988 -0.0336 -0.0370 +vn 0.9996 -0.0204 -0.0179 +vn 0.9985 0.0220 0.0508 +vn 0.9999 0.0168 0.0006 +vn 0.9985 -0.0225 -0.0499 +vn 0.9994 0.0298 0.0188 +vn 0.9947 -0.0150 -0.1013 +vn 0.9996 0.0057 0.0260 +vn 0.9948 -0.0919 -0.0439 +vn 0.9997 -0.0145 -0.0177 +vn 0.9999 0.0109 0.0096 +vn 0.9996 0.0024 -0.0271 +vn 0.9997 0.0021 -0.0245 +vn 0.9993 0.0053 -0.0364 +vn 0.9666 0.2535 0.0382 +vn 0.9959 0.0855 -0.0300 +vn 0.9999 0.0166 -0.0027 +vn 0.9997 0.0026 -0.0259 +vn 0.9999 -0.0125 0.0051 +vn 0.9998 -0.0208 0.0029 +vn 0.9460 0.1359 -0.2944 +vn 0.9969 0.0435 -0.0651 +vn 0.9995 0.0310 -0.0056 +vn 0.9990 0.0429 -0.0093 +vn 0.9995 0.0222 0.0246 +vn 0.9995 0.0073 -0.0300 +vn 0.9995 -0.0105 0.0293 +vn 0.9990 -0.0133 0.0418 +vn 0.9994 -0.0332 0.0096 +vn 0.9995 -0.0218 -0.0229 +vn 0.9991 -0.0350 -0.0243 +vn -1.0000 0.0080 -0.0041 +vn -0.9952 0.0978 0.0061 +vn -0.9936 0.1124 -0.0078 +vn -0.9994 -0.0285 0.0187 +vn 0.0038 0.3879 0.9217 +vn -0.0130 0.7102 0.7039 +vn -0.0120 0.6936 0.7202 +vn 0.0045 0.3728 0.9279 +vn 0.0004 -0.6741 0.7387 +vn -0.0223 -0.3250 0.9455 +vn -0.0212 -0.3451 0.9383 +vn 0.0017 -0.6904 0.7234 +vn 0.0002 -0.9210 -0.3895 +vn -0.0194 -0.9925 -0.1209 +vn -0.0184 -0.9906 -0.1355 +vn 0.0013 -0.9148 -0.4038 +vn -0.0066 -0.0177 -0.9998 +vn -0.0109 0.0291 -0.9995 +vn -0.0069 -0.0149 -0.9999 +vn -0.0112 0.0320 -0.9994 +vn 0.0112 0.9839 -0.1782 +vn -0.0090 0.9070 -0.4211 +vn -0.0078 0.9134 -0.4070 +vn 0.0121 0.9860 -0.1665 +vn -0.9885 -0.0117 0.1508 +vn -0.9970 -0.0597 0.0502 +vn -0.9955 0.0584 0.0740 +vn -0.9937 0.1058 0.0378 +vn -0.9958 0.0826 -0.0395 +vn -0.9946 0.0549 -0.0879 +vn -0.9952 -0.0015 -0.0975 +vn -0.9961 -0.0455 -0.0755 +vn -0.9955 -0.0732 -0.0609 +vn -0.9924 -0.1233 -0.0038 +vn -0.0694 0.9712 0.2280 +vn -0.1102 0.9764 0.1860 +vn -0.0663 0.9706 0.2312 +vn -0.0173 0.9598 0.2803 +vn 0.0376 0.1907 0.9809 +vn -0.0910 0.0467 0.9948 +vn -0.1021 0.0339 0.9942 +vn -0.2010 -0.0812 0.9762 +vn 0.1614 -0.6908 0.7048 +vn -0.0822 -0.9901 -0.1136 +vn -0.1354 -0.9894 -0.0532 +vn -0.0822 -0.9901 -0.1137 +vn -0.0150 -0.9820 -0.1882 +vn 0.0327 -0.3714 -0.9279 +vn 0.0415 -0.3797 -0.9242 +vn 0.0400 -0.3783 -0.9248 +vn 0.0502 -0.3879 -0.9203 +vn 0.0182 0.6176 -0.7862 +vn -0.1178 0.4665 -0.8767 +vn 0.0074 0.6067 -0.7949 +vn 0.1373 0.7255 -0.6744 +vn -0.1238 0.9744 -0.1874 +vn 0.0017 0.9984 -0.0557 +vn -0.0016 0.9982 -0.0592 +vn 0.1239 0.9895 0.0743 +vn -0.1239 -0.6496 -0.7501 +vn 0.0016 -0.5476 -0.8367 +vn -0.0017 -0.5505 -0.8348 +vn 0.1237 -0.4305 -0.8941 +vn -0.1237 -0.3248 0.9376 +vn 0.0018 -0.4508 0.8926 +vn -0.0015 -0.4477 0.8942 +vn 0.1240 -0.5590 0.8198 +vn -0.9546 0.2971 0.0214 +vn 0.9995 -0.0313 -0.0049 +vn 0.9996 -0.0131 -0.0233 +vn 0.9995 0.0240 -0.0211 +vn 0.9991 0.0258 -0.0343 +vn 0.9995 0.0302 0.0063 +vn 0.9995 -0.0043 0.0314 +vn 0.9996 0.0063 0.0278 +vn 0.9994 -0.0320 0.0135 +vn -0.9998 0.0086 -0.0155 +vn -0.9984 0.0496 0.0277 +vn -0.9998 0.0048 -0.0194 +vn -0.9973 -0.0373 -0.0637 +vn -0.0263 0.0385 -0.9989 +vn 0.0178 0.5826 -0.8126 +vn 0.0024 0.8588 0.5122 +vn -0.0310 0.9978 0.0590 +vn -0.0293 0.9960 0.0843 +vn 0.0047 0.8419 0.5397 +vn -0.0090 -0.1915 0.9814 +vn -0.0079 -0.1814 0.9834 +vn -0.0089 -0.1909 0.9816 +vn -0.0078 -0.1808 0.9835 +vn 0.0156 -0.9627 -0.2702 +vn -0.0145 -0.9994 0.0305 +vn -0.0121 -0.9999 0.0058 +vn 0.0174 -0.9573 -0.2884 +vn -0.9945 0.1032 -0.0192 +vn -0.9951 0.0961 0.0227 +vn -0.9956 0.0524 -0.0775 +vn -0.9715 -0.0502 -0.2317 +vn -0.9955 -0.0818 -0.0485 +vn -0.9938 -0.1016 0.0460 +vn -0.9953 -0.0591 0.0766 +vn -0.9960 0.0352 0.0822 +vn -0.9957 0.0365 0.0846 +vn -0.0741 -0.0730 -0.9946 +vn -0.0479 -0.0468 -0.9978 +vn 0.0877 0.0886 -0.9922 +vn -0.0307 0.9280 -0.3712 +vn -0.0192 0.9244 -0.3809 +vn -0.0187 0.9243 -0.3813 +vn -0.0077 0.9206 -0.3905 +vn 0.0694 0.6865 0.7238 +vn -0.0406 0.7770 0.6282 +vn 0.0676 0.6881 0.7225 +vn 0.1554 0.6000 0.7848 +vn -0.1646 -0.1078 0.9805 +vn 0.1793 -0.6176 0.7658 +vn -0.1989 -0.9722 0.1239 +vn 0.1692 -0.9357 -0.3094 +vn -0.1910 -0.1898 -0.9631 +vn -0.1237 -0.9376 -0.3248 +vn 0.0018 -0.8926 -0.4508 +vn -0.0015 -0.8942 -0.4477 +vn 0.1240 -0.8198 -0.5590 +vn -0.1238 0.1874 0.9744 +vn 0.0017 0.0557 0.9984 +vn -0.0016 0.0592 0.9982 +vn 0.1239 -0.0743 0.9895 +vn -0.1239 0.7501 -0.6496 +vn 0.0016 0.8367 -0.5476 +vn -0.0017 0.8348 -0.5505 +vn 0.1237 0.8941 -0.4305 +vn 0.9974 -0.0723 -0.0013 +vn 0.9963 0.0208 0.0832 +vn 0.9961 0.0437 -0.0761 +vn 0.9979 0.0378 -0.0526 +vn 0.9972 0.0405 -0.0632 +vn 0.9982 0.0364 -0.0468 +vn -0.9999 0.0090 -0.0087 +vn -0.9990 -0.0395 -0.0207 +vn -0.9999 0.0087 -0.0088 +vn -0.9986 0.0537 0.0024 +vn -0.0589 -0.9133 0.4029 +vn 0.0168 -0.9481 -0.3175 +vn -0.0510 -0.4449 -0.8941 +vn 0.0167 0.2949 -0.9554 +vn -0.0488 0.7672 -0.6396 +vn 0.0221 0.9467 0.3214 +vn -0.0667 0.5844 0.8087 +vn 0.0248 -0.3932 0.9191 +vn -0.9898 0.0104 0.1421 +vn -0.9952 0.0704 0.0676 +vn -0.9924 0.1103 -0.0545 +vn -0.9895 0.1338 -0.0538 +vn -0.9927 -0.1182 0.0244 +vn -0.9940 -0.0838 0.0701 +vn -0.9939 0.0214 -0.1080 +vn -0.9921 -0.0591 -0.1107 +vn -0.9926 -0.1047 -0.0621 +vn 0.1704 -0.8605 0.4802 +vn -0.1875 -0.9823 0.0003 +vn 0.1426 -0.8231 -0.5497 +vn 0.0016 -0.3352 -0.9422 +vn -0.0401 -0.3961 -0.9173 +vn -0.0089 -0.3507 -0.9364 +vn 0.0404 -0.2765 -0.9602 +vn -0.0168 0.6113 -0.7912 +vn -0.0317 0.5981 -0.8008 +vn -0.0181 0.6102 -0.7921 +vn -0.0024 0.6238 -0.7816 +vn -0.0563 0.9881 0.1428 +vn 0.0002 0.9817 0.1907 +vn -0.0459 0.9874 0.1517 +vn -0.1198 0.9889 0.0878 +vn 0.1838 0.7238 0.6651 +vn -0.1161 -0.1721 0.9782 +vn -0.2196 -0.0705 0.9730 +vn -0.1058 -0.1819 0.9776 +vn 0.0426 -0.3168 0.9475 +vn 0.0093 -0.6160 0.7877 +vn 0.0474 -0.6317 0.7738 +vn 0.0265 -0.6232 0.7816 +vn 0.0807 -0.6445 0.7603 +vn 0.2955 0.9540 0.0497 +vn 0.3853 0.9162 0.1104 +vn 0.3467 0.9342 0.0840 +vn 0.4551 0.8761 0.1590 +vn 0.3733 -0.2527 -0.8927 +vn 0.3217 -0.2908 -0.9011 +vn 0.3452 -0.2737 -0.8977 +vn 0.2736 -0.3245 -0.9054 +vn 0.0829 0.0886 -0.9926 +vn 0.1123 0.0795 -0.9905 +vn 0.2021 0.0509 -0.9781 +vn 0.2407 0.0382 -0.9698 +vn -0.3944 0.9140 0.0947 +vn 0.6006 0.6934 0.3980 +vn -0.5216 -0.2347 0.8202 +vn 0.3522 -0.6292 0.6929 +vn 0.4028 -0.5404 0.7387 +vn 0.4429 -0.4573 0.7712 +vn 0.4939 -0.3278 0.8054 +vn -0.1700 0.8782 -0.4470 +vn 0.0488 -0.1185 -0.9918 +vn 0.1280 -0.0948 -0.9872 +vn -0.2972 -0.2112 -0.9312 +vn -0.3550 -0.2249 -0.9074 +vn 0.4767 -0.8515 -0.2184 +vn -0.4111 -0.9097 0.0581 +vn 0.1657 -0.3902 0.9057 +vn 0.0997 -0.4098 0.9067 +vn -0.0469 -0.4459 0.8939 +vn -0.1062 -0.4576 0.8828 +vn 0.2866 0.4832 0.8272 +vn -0.3981 0.6637 0.6332 +vn 0.0422 -0.4647 -0.8845 +vn 0.7087 0.0514 -0.7036 +vn -0.9973 0.0719 -0.0122 +vn -0.9585 0.2811 -0.0477 +vn -0.9248 0.3751 -0.0636 +vn 0.9942 0.1071 0.0011 +vn 0.9635 0.2678 0.0028 +vn 0.9064 0.4224 0.0044 +vn -0.2941 -0.6192 0.7281 +vn 0.5747 -0.7874 0.2232 +vn -0.5089 -0.7358 -0.4468 +vn 0.4308 -0.0391 -0.9016 +vn 0.3564 0.0016 -0.9343 +vn 0.1387 0.1122 -0.9840 +vn 0.0045 0.1750 -0.9846 +vn -0.0001 0.9999 -0.0147 +vn -0.0487 0.9983 -0.0322 +vn 0.1270 0.9914 0.0312 +vn 0.1714 0.9841 0.0473 +vn 0.0780 0.8168 0.5716 +vn -0.6212 -0.5009 -0.6027 +vn 0.5129 -0.8385 -0.1841 +vn -0.4323 -0.7354 0.5219 +vn 0.1249 -0.6570 0.7435 +vn 0.0001 0.2126 0.9771 +vn -0.0667 0.2317 0.9705 +vn 0.1509 0.1654 0.9746 +vn 0.2384 0.1356 0.9617 +vn -0.3310 0.8151 0.4755 +vn 0.3920 0.9049 0.1658 +vn -0.3992 0.7557 -0.5192 +vn 0.1787 0.6560 -0.7333 +vn -0.5747 -0.8133 -0.0902 +vn -0.4455 -0.8585 -0.2541 +vn -0.4531 -0.8570 -0.2454 +vn -0.2847 -0.8634 -0.4166 +vn -0.9992 -0.0222 -0.0344 +vn -0.9607 -0.1506 -0.2334 +vn -0.9291 -0.2005 -0.3107 +vn 0.9917 0.0920 -0.0894 +vn 0.9813 0.1381 -0.1341 +vn 0.9402 0.2444 -0.2373 +vn 0.9997 -0.0099 0.0203 +vn 0.9994 -0.0342 0.0038 +vn 0.9996 -0.0184 -0.0219 +vn 0.9993 -0.0255 -0.0279 +vn 0.9996 -0.0121 0.0239 +vn 0.9994 0.0106 -0.0322 +vn 0.9998 0.0199 0.0024 +vn 0.9997 0.0211 -0.0138 +vn -0.9997 0.0163 0.0172 +vn -0.9997 0.0227 0.0105 +vn -0.9997 0.0161 0.0174 +vn -0.9996 0.0067 0.0271 +vn 0.0097 -0.3944 -0.9189 +vn -0.0141 -0.1790 -0.9837 +vn 0.0080 -0.3795 -0.9252 +vn -0.0162 -0.1594 -0.9871 +vn -0.0123 0.9977 -0.0661 +vn 0.0041 0.9980 0.0628 +vn 0.0027 0.9986 0.0521 +vn -0.0135 0.9970 -0.0758 +vn 0.0025 0.1277 0.9918 +vn -0.0178 -0.1648 0.9862 +vn 0.0013 0.1110 0.9938 +vn -0.0188 -0.1805 0.9834 +vn 0.0038 -0.8751 0.4840 +vn -0.0186 -0.9867 0.1617 +vn 0.0027 -0.8835 0.4685 +vn -0.0199 -0.9897 0.1415 +vn -0.9909 0.0697 -0.1150 +vn -0.9951 -0.0187 -0.0968 +vn -0.9952 -0.0946 -0.0236 +vn -0.9936 -0.1018 -0.0480 +vn -0.9952 -0.0830 0.0516 +vn -0.9958 -0.0483 0.0784 +vn -0.9962 -0.0017 0.0866 +vn -0.9932 0.0789 0.0860 +vn -0.9956 0.0891 0.0287 +vn -0.9927 0.1072 -0.0560 +vn 0.0355 -0.9874 -0.1541 +vn -0.0026 -0.9976 -0.0688 +vn 0.1053 -0.9454 -0.3083 +vn -0.1495 -0.6005 -0.7855 +vn 0.1462 -0.1583 -0.9765 +vn -0.1214 0.4524 -0.8835 +vn 0.1747 0.8555 -0.4874 +vn 0.0429 0.9428 -0.3306 +vn 0.0503 0.9392 -0.3398 +vn -0.1118 0.9853 -0.1292 +vn 0.0944 0.5357 0.8391 +vn 0.0331 0.5800 0.8139 +vn 0.1104 0.5235 0.8448 +vn 0.1585 0.4852 0.8599 +vn -0.0023 -0.6970 0.7170 +vn -0.1296 -0.5464 0.8275 +vn -0.0162 -0.6823 0.7309 +vn 0.1070 -0.7979 0.5933 +vn -0.0772 -0.9920 0.0999 +vn -0.0912 -0.3260 0.9410 +vn 0.4922 0.3316 0.8049 +vn -0.2678 0.9461 -0.1819 +vn 0.1108 -0.6506 -0.7513 +vn 0.2795 -0.4970 -0.8215 +vn 0.2714 -0.5054 -0.8191 +vn 0.4077 -0.3479 -0.8443 +vn 0.0586 0.9242 -0.3774 +vn 0.0295 0.9332 -0.3582 +vn -0.1218 0.9770 -0.1750 +vn -0.1695 0.9731 -0.1563 +vn 0.1234 0.2179 0.9681 +vn 0.0866 0.2049 0.9749 +vn -0.0148 0.1678 0.9857 +vn -0.0545 0.1526 0.9868 +vn 0.0476 -0.9135 0.4040 +vn 0.0106 -0.9216 0.3879 +vn -0.0517 -0.9318 0.3593 +vn -0.0863 -0.9355 0.3427 +vn 0.1161 -0.7557 -0.6445 +vn 0.0690 -0.7432 -0.6655 +vn -0.0215 -0.7135 -0.7003 +vn -0.0591 -0.6990 -0.7126 +vn -0.5205 -0.8438 0.1306 +vn 0.5452 0.0385 0.8374 +vn -0.4396 0.6348 0.6354 +vn 0.5048 0.8417 0.1915 +vn -0.6378 0.6669 -0.3853 +vn 0.5514 0.3830 -0.7411 +vn -0.3926 -0.4976 -0.7735 +vn -0.4895 -0.4952 -0.7178 +vn -0.1963 -0.4850 -0.8522 +vn -0.1432 -0.4781 -0.8666 +vn 0.1045 -0.9788 0.1762 +vn 0.1570 -0.9749 0.1577 +vn -0.0854 -0.9676 0.2376 +vn -0.1381 -0.9575 0.2531 +vn 0.0772 -0.4089 0.9093 +vn 0.0496 0.8497 -0.5249 +vn -0.9882 0.0662 0.1378 +vn -0.9924 0.0532 0.1108 +vn -0.9498 0.1355 0.2819 +vn 0.9867 0.0483 0.1551 +vn 0.9939 0.0327 0.1049 +vn 0.9504 0.0926 0.2970 +vn -0.4508 0.5488 0.7040 +vn -0.4795 0.4978 0.7227 +vn -0.3472 0.6983 0.6259 +vn 0.6306 0.1038 0.7691 +vn -0.6030 -0.5263 0.5995 +vn 0.5572 -0.8119 -0.1742 +vn -0.1758 -0.8138 -0.5539 +vn 0.1063 0.3245 -0.9399 +vn 0.0808 0.3160 -0.9453 +vn 0.1436 0.4278 -0.8924 +vn 0.1469 0.4695 -0.8706 +vn 0.1195 0.5731 -0.8107 +vn -0.1316 -0.9148 0.3820 +vn 0.0392 -0.2292 0.9726 +vn 0.0954 -0.2485 0.9639 +vn -0.1411 -0.1622 0.9766 +vn -0.1894 -0.1430 0.9714 +vn 0.2640 0.6199 0.7389 +vn -0.5527 0.7550 0.3528 +vn 0.5066 0.8565 -0.0989 +vn -0.4701 0.4046 -0.7844 +vn 0.0356 0.2959 -0.9546 +vn 0.0483 -0.6562 -0.7530 +vn 0.1318 -0.6287 -0.7664 +vn -0.1961 -0.7063 -0.6803 +vn -0.2586 -0.7116 -0.6533 +vn -0.5682 0.2972 0.7674 +vn 0.4821 -0.6042 0.6345 +vn -0.9822 -0.1867 -0.0209 +vn -0.9969 -0.0787 -0.0088 +vn -0.9516 -0.3054 -0.0342 +vn 0.9838 -0.1639 -0.0729 +vn 0.9920 -0.1156 -0.0514 +vn 0.9402 -0.3113 -0.1385 +vn 0.9963 -0.0550 0.0656 +vn 0.9981 -0.0298 -0.0542 +vn 0.9988 0.0422 0.0231 +vn -0.9999 0.0076 -0.0126 +vn -0.9949 -0.0668 -0.0757 +vn -0.9998 0.0175 -0.0042 +vn -0.9946 0.0874 0.0553 +vn 0.0448 -0.7473 -0.6630 +vn -0.0859 -0.9953 0.0451 +vn 0.0406 -0.6436 0.7643 +vn -0.0864 -0.0360 0.9956 +vn 0.0578 0.9031 0.4255 +vn -0.0776 0.9883 -0.1313 +vn 0.0099 0.4680 -0.8837 +vn -0.0005 0.4083 -0.9129 +vn -0.0488 0.1043 -0.9934 +vn -0.0591 0.0339 -0.9977 +vn -0.9887 0.1330 -0.0690 +vn -0.9902 0.0553 -0.1286 +vn -0.9864 -0.0283 -0.1617 +vn -0.9923 -0.0987 -0.0748 +vn -0.9823 0.0834 0.1678 +vn -0.9915 0.1295 0.0090 +vn -0.9868 0.0272 0.1599 +vn -0.9908 -0.0954 0.0958 +vn -0.9808 -0.1941 0.0196 +vn 0.1637 -0.8856 -0.4346 +vn -0.1410 -0.9840 0.1090 +vn -0.1068 -0.9826 0.1520 +vn -0.1108 -0.9829 0.1471 +vn -0.0586 -0.9757 0.2112 +vn 0.0982 -0.3753 0.9217 +vn -0.0052 -0.2592 0.9658 +vn -0.0049 -0.2595 0.9657 +vn -0.1018 -0.1443 0.9843 +vn 0.1035 0.6461 0.7562 +vn 0.0053 0.7341 0.6791 +vn 0.0094 0.7308 0.6826 +vn -0.0892 0.8025 0.5899 +vn -0.0138 0.9118 -0.4104 +vn 0.1164 0.9726 -0.2012 +vn 0.0350 0.8317 -0.5540 +vn -0.0399 0.7573 -0.6518 +vn 0.0866 0.5782 -0.8113 +vn -0.0775 -0.1769 -0.9812 +vn -0.0134 -0.1107 -0.9938 +vn -0.0764 -0.1757 -0.9815 +vn -0.1254 -0.2257 -0.9661 +vn 0.2787 -0.8841 -0.3750 +vn 0.7955 -0.3116 -0.5197 +vn 0.5043 -0.5078 0.6984 +vn 0.6157 0.4672 0.6345 +vn 0.6564 0.4169 0.6288 +vn 0.6433 0.4336 0.6310 +vn 0.6886 0.3729 0.6220 +vn 0.1448 0.6931 -0.7061 +vn 0.9706 0.1464 -0.1910 +vn 0.9960 -0.0085 -0.0893 +vn 0.9949 0.0140 -0.0996 +vn 0.9995 0.0200 -0.0234 +vn -1.0000 -0.0002 0.0004 +vn -1.0000 -0.0001 0.0002 +vn 0.9604 0.1185 -0.2521 +vn 0.9797 0.0483 -0.1947 +vn 0.9771 0.0572 -0.2051 +vn 0.9985 0.0447 -0.0330 +vn 0.9995 0.0299 0.0031 +vn 0.9497 0.1363 -0.2819 +vn -0.9967 0.0707 -0.0400 +vn -0.9169 0.1732 -0.3596 +vn -0.8802 0.1364 -0.4545 +vn -0.9572 0.0841 -0.2770 +vn -0.9986 0.0527 0.0029 +vn -0.9884 0.0594 -0.1398 +vn 0.9497 0.1362 -0.2818 +vn -0.9931 0.1062 -0.0498 +vn -0.8929 0.1800 -0.4126 +vn -0.8966 0.1661 -0.4105 +vn -0.9564 0.0858 -0.2793 +vn -0.9964 0.0842 0.0046 +vn -0.9887 0.0585 -0.1378 +vn -0.8929 0.1800 -0.4128 +vn -0.8966 0.1662 -0.4106 +vn -0.8965 0.1662 -0.4106 +vn 0.9801 0.0782 -0.1825 +vn 0.9865 0.0526 -0.1550 +vn 0.9855 0.0565 -0.1598 +vn 0.9996 0.0104 -0.0247 +vn 0.9752 0.0883 -0.2028 +vn 0.9805 0.0772 -0.1808 +vn 0.9866 0.0525 -0.1542 +vn 0.9857 0.0564 -0.1589 +vn 0.9996 0.0105 -0.0247 +vn 0.9757 0.0872 -0.2009 +vn -0.9982 -0.0582 -0.0164 +vn -0.9922 0.0487 -0.1145 +vn -0.9986 -0.0260 -0.0457 +vn -0.9898 0.0576 -0.1302 +vn -0.0614 0.5427 -0.8377 +vn -0.0673 0.5418 -0.8378 +vn -0.0001 0.5506 -0.8347 +vn 0.0062 0.5513 -0.8343 +vn 0.0134 0.6035 -0.7972 +vn 0.0134 0.6036 -0.7972 +vn 0.0112 0.6037 -0.7972 +vn 1.0000 0.0078 0.0040 +vn 0.9958 0.0862 0.0311 +vn 0.9621 0.2716 -0.0258 +vn 0.9995 0.0078 -0.0298 +vn 0.9891 0.1340 -0.0617 +vn 0.9896 0.1361 -0.0475 +vn 0.9997 -0.0025 -0.0255 +vn -1.0000 -0.0000 0.0003 +vn -0.9999 0.0100 -0.0048 +vn -0.9999 0.0129 0.0028 +vn -0.9762 0.2155 -0.0229 +vn -0.9714 0.2347 -0.0368 +vn 0.9868 0.0026 -0.1620 +vn 0.9879 0.0046 -0.1552 +vn 0.9881 0.0051 -0.1535 +vn 0.9856 0.0004 -0.1692 +vn 0.9743 0.2125 0.0742 +vn 0.9994 0.0078 0.0343 +vn 0.9996 -0.0036 0.0294 +vn 0.9841 0.1551 0.0866 +vn 0.9792 0.2011 0.0279 +vn 0.9467 0.3204 -0.0325 +vn 0.9995 0.0080 -0.0321 +vn 0.9859 0.1582 -0.0552 +vn 0.9911 0.1183 -0.0608 +vn 0.9996 -0.0033 -0.0273 +vn -0.9851 0.0021 -0.1720 +vn -0.9866 0.0048 -0.1629 +vn -0.9863 0.0043 -0.1648 +vn -0.9837 -0.0002 -0.1799 +vn -0.9985 -0.0517 0.0195 +vn -0.9995 0.0321 0.0080 +vn -0.9782 0.2072 0.0136 +vn -0.9728 0.2303 -0.0247 +vn -0.9620 0.2580 -0.0894 +vn -0.9875 0.1314 -0.0868 +vn -0.9997 0.0179 -0.0186 +vn 0.9998 0.0174 0.0079 +vn 0.9866 0.1496 0.0653 +vn 0.9832 0.1673 0.0730 +vn 0.9914 0.1296 0.0194 +vn 0.9908 0.1322 0.0280 +vn 1.0000 0.0001 -0.0023 +vn 0.9987 -0.0500 -0.0135 +vn -0.9862 -0.0030 -0.1657 +vn -0.9845 -0.0002 -0.1754 +vn -0.9874 -0.0052 -0.1582 +vn -0.9877 -0.0058 -0.1562 +vn -0.9830 0.1720 0.0647 +vn -0.9764 0.2047 0.0689 +vn -0.9710 0.2385 0.0143 +vn -0.9994 -0.0025 0.0355 +vn -0.9991 0.0113 0.0415 +vn -0.9712 0.2361 -0.0309 +vn -0.9658 0.2431 -0.0903 +vn -0.9825 0.1547 -0.1036 +vn -0.9995 0.0220 -0.0228 +vn 0.9887 0.1246 0.0833 +vn 0.9997 0.0171 0.0187 +vn 0.9655 0.2461 0.0852 +vn 0.9758 0.2173 0.0258 +vn 0.9459 0.3227 -0.0332 +vn 0.9911 0.1182 -0.0608 +vn -0.9997 0.0196 0.0132 +vn -0.9976 0.0475 0.0506 +vn -0.9971 0.0524 0.0559 +vn 0.0426 0.9988 -0.0221 +vn -0.9853 0.1578 0.0662 +vn -0.9877 0.1441 0.0605 +vn -0.9880 0.1481 0.0444 +vn -0.9843 0.1651 0.0628 +vn -0.9712 0.2378 0.0142 +vn -0.9996 -0.0019 0.0270 +vn -0.9995 0.0086 0.0315 +vn -0.9713 0.2361 -0.0309 +vn -0.9658 0.2432 -0.0903 +vn 0.9455 0.3240 -0.0332 +vn 0.9736 0.1806 -0.1393 +vn 0.9752 0.2135 -0.0577 +vn 0.9583 0.2449 -0.1474 +vn 0.9757 0.1718 -0.1357 +vn 0.9854 0.0036 -0.1701 +vn 0.9872 0.0068 -0.1591 +vn 0.9877 0.0076 -0.1564 +vn 0.9835 0.0004 -0.1809 +vn 0.9999 0.0007 0.0111 +vn 0.9974 0.0603 0.0399 +vn 0.9805 0.1923 0.0415 +vn 0.9741 0.2257 0.0124 +vn 0.9997 0.0052 -0.0221 +vn 0.9907 0.1265 -0.0507 +vn 0.9811 0.1919 -0.0246 +vn 0.9998 -0.0028 -0.0188 +vn -0.9883 0.1396 -0.0620 +vn -0.9799 0.1689 -0.1058 +vn -0.9782 0.1766 -0.1091 +vn -0.9726 0.2322 0.0103 +vn -0.9808 0.1924 -0.0304 +vn -0.9902 0.1210 -0.0700 +vn 0.0310 0.8075 -0.5891 +vn -0.0063 0.8030 -0.5959 +vn 0.2377 0.8107 -0.5351 +vn 0.2574 0.8090 -0.5285 +vn -0.4393 0.8522 -0.2841 +vn 0.5036 0.8586 -0.0957 +vn -0.5036 0.8586 0.0957 +vn 0.4393 0.8523 0.2841 +vn -0.2379 0.8106 0.5351 +vn -0.2576 0.8089 0.5284 +vn -0.0311 0.8075 0.5891 +vn 0.0063 0.8030 0.5960 +vn -0.0139 0.8029 -0.5959 +vn 0.5060 0.7221 -0.4717 +vn -0.7324 0.6459 -0.2153 +vn 0.7886 0.6111 -0.0681 +vn -0.7886 0.6111 0.0681 +vn 0.7324 0.6459 0.2153 +vn -0.5060 0.7221 0.4717 +vn 0.0139 0.8029 0.5959 +vn 0.5056 0.7223 -0.4718 +vn -0.7325 0.6459 -0.2153 +vn -0.0172 -0.0054 -0.9998 +vn -0.0308 -0.0106 -0.9995 +vn 0.0170 0.0074 -0.9998 +vn 0.0305 0.0125 -0.9995 +vn 0.0019 0.9418 -0.3360 +vn 0.0022 0.9375 -0.3480 +vn 0.0161 0.9736 -0.2277 +vn 0.0236 0.8350 -0.5497 +vn -0.0099 0.7613 -0.6483 +vn -0.0087 0.7577 -0.6525 +vn 0.0160 0.8736 -0.4864 +vn 0.0209 0.8730 -0.4873 +vn 0.9999 0.0107 0.0110 +vn 0.9972 0.0473 0.0583 +vn 0.9764 0.0597 0.2078 +vn 0.9957 -0.0112 0.0922 +vn 1.0000 -0.0013 0.0055 +vn -0.9747 0.0803 0.2086 +vn -0.9984 0.0516 0.0214 +vn -0.9989 0.0462 0.0095 +vn -1.0000 -0.0022 0.0067 +vn -0.9986 -0.0094 0.0530 +vn -0.9809 0.1037 0.1644 +vn -0.0060 0.5959 0.8030 +vn -0.0193 0.5982 0.8011 +vn 0.0123 0.4987 0.8667 +vn -0.0290 0.4079 0.9126 +vn 0.0276 0.1651 0.9859 +vn -0.0493 0.0161 0.9987 +vn 0.1476 -0.1393 0.9792 +vn 0.1619 -0.1404 0.9768 +vn -0.1271 -0.5437 0.8296 +vn -0.1368 -0.5418 0.8293 +vn -0.0059 -0.5630 0.8264 +vn 0.0077 -0.5647 0.8253 +vn 0.9998 -0.0081 0.0184 +vn 0.9769 -0.0767 0.1996 +vn 0.9986 -0.0130 0.0513 +vn 0.9767 0.1074 0.1859 +vn 0.8938 0.1348 0.4277 +vn 0.9315 0.0491 0.3603 +vn 0.8760 -0.0363 0.4809 +vn 0.9548 -0.0951 0.2816 +vn 0.9757 -0.0841 0.2024 +vn 0.9986 -0.0523 0.0122 +vn -0.9997 -0.0089 0.0208 +vn -0.9792 -0.0694 0.1906 +vn -0.9776 -0.0803 0.1947 +vn -0.9851 -0.0398 0.1675 +vn -0.9160 -0.0022 0.4012 +vn -0.9572 0.0017 0.2893 +vn -0.8794 0.1331 0.4571 +vn -0.9784 0.1112 0.1742 +vn -0.9988 -0.0038 0.0483 +vn -0.9986 -0.0529 0.0027 +vn -0.0420 0.5898 0.8065 +vn 0.0174 -0.5892 0.8078 +vn 0.7926 0.1319 0.5953 +vn 0.9317 0.1581 0.3272 +vn 0.7298 0.1347 0.6702 +vn 0.9805 0.0130 0.1960 +vn 0.9814 0.0596 0.1825 +vn 0.9814 0.0244 0.1905 +vn 0.9780 -0.0629 0.1988 +vn 0.9839 -0.0248 0.1770 +vn 0.9901 -0.0620 0.1258 +vn 0.9990 0.0224 0.0374 +vn 0.9987 0.0510 0.0095 +vn 0.9995 0.0324 -0.0033 +vn 0.9984 0.0470 0.0310 +vn -0.9998 -0.0078 0.0180 +vn -0.9808 -0.0707 0.1817 +vn -0.9776 -0.0775 0.1957 +vn -0.9731 -0.0684 0.2200 +vn -0.9261 -0.0303 0.3761 +vn -0.9415 0.0229 0.3362 +vn -0.8771 0.1397 0.4595 +vn -0.9766 0.1135 0.1826 +vn -0.9988 -0.0056 0.0494 +vn -0.9988 -0.0490 0.0076 +vn -0.0140 0.5891 0.8080 +vn 0.0160 -0.5892 0.8078 +vn 0.9981 -0.0507 0.0357 +vn 0.9992 -0.0385 0.0070 +vn 0.9474 -0.1260 0.2941 +vn 0.9228 0.1188 0.3665 +vn 0.9414 0.1430 0.3053 +vn 0.9399 0.0438 0.3387 +vn 0.9398 0.0461 0.3385 +vn 0.9266 -0.0635 0.3707 +vn 0.9296 -0.0876 0.3581 +vn 0.9414 -0.1421 0.3060 +vn 0.9995 0.0299 -0.0030 +vn 0.9986 0.0440 0.0304 +vn -0.9817 -0.0683 0.1775 +vn -0.9864 -0.0401 0.1597 +vn -0.9690 -0.0184 0.2464 +vn -0.9753 0.0121 0.2206 +vn -0.9090 0.1334 0.3950 +vn -0.9651 0.1410 0.2207 +vn -0.9986 -0.0025 0.0524 +vn 0.9795 -0.0702 0.1890 +vn 0.7836 0.1308 0.6073 +vn 0.9312 0.1580 0.3285 +vn 0.6886 0.1404 0.7114 +vn 0.9737 -0.0044 0.2278 +vn 0.9859 0.0521 0.1589 +vn 0.9832 0.0385 0.1785 +vn 0.9881 -0.0325 0.1501 +vn -0.9966 -0.0744 0.0363 +vn -0.9187 -0.1584 0.3618 +vn -0.9984 -0.0563 -0.0064 +vn -0.9092 -0.1811 0.3748 +vn -0.9255 -0.0805 0.3701 +vn -0.9243 -0.0579 0.3773 +vn -0.9217 0.0414 0.3857 +vn -0.9235 0.0356 0.3820 +vn -0.9097 0.1482 0.3880 +vn -0.9493 0.1685 0.2654 +vn -0.9982 0.0048 0.0594 +vn 0.0174 -0.5891 0.8078 +vn 0.9998 -0.0080 0.0181 +vn 0.9769 -0.0766 0.1993 +vn 0.9767 0.1075 0.1859 +vn 0.8938 0.1349 0.4278 +vn -0.9864 -0.0401 0.1596 +vn 0.9998 -0.0087 0.0198 +vn 0.9774 -0.0753 0.1975 +vn 0.8812 0.1037 0.4612 +vn 0.9747 0.0861 0.2062 +vn 0.9549 0.0622 0.2904 +vn 0.8970 -0.0223 0.4414 +vn 0.9634 -0.0831 0.2549 +vn 0.9762 -0.0829 0.2003 +vn 0.9997 0.0094 0.0219 +vn -0.9808 -0.0708 0.1817 +vn -0.8772 0.1397 0.4594 +vn -0.0140 0.5891 0.8079 +vn 0.0076 0.9962 -0.0869 +vn 0.0106 0.9942 -0.1066 +vn -0.0104 0.9917 0.1281 +vn 0.0097 0.9610 0.2763 +vn -0.0011 0.9178 0.3970 +vn 0.0075 0.9718 0.2359 +vn 0.0130 0.8370 0.5471 +vn -0.6863 0.3668 0.6280 +vn 0.7162 0.4321 0.5481 +vn 0.0442 0.7632 0.6446 +vn -0.4770 0.7003 0.5311 +vn -0.1698 0.7394 0.6515 +vn -0.4859 0.6981 0.5260 +vn 0.7375 0.1146 0.6655 +vn -0.6253 -0.1595 0.7640 +vn 0.5693 -0.4378 0.6959 +vn -0.2142 -0.6121 0.7612 +vn -0.1597 -0.5734 0.8035 +vn -0.2173 -0.5898 0.7778 +vn -0.3489 -0.6040 0.7166 +vn 0.3382 -0.8077 0.4830 +vn 0.6639 -0.5988 -0.4480 +vn 0.6002 -0.6284 -0.4948 +vn 0.6718 -0.5946 -0.4417 +vn 0.5474 -0.6485 -0.5289 +vn -0.2227 -0.4655 -0.8566 +vn 0.0623 -0.1764 -0.9823 +vn 0.2119 -0.1651 -0.9632 +vn 0.3162 -0.1547 -0.9360 +vn 0.6325 0.1486 -0.7602 +vn -0.5402 0.0414 -0.8405 +vn -0.5631 0.2665 -0.7822 +vn 0.8190 0.3533 -0.4520 +vn 0.7697 0.3979 -0.4992 +vn 0.5123 0.5581 -0.6528 +vn 0.5006 0.5632 -0.6574 +vn 0.8387 0.3299 -0.4333 +vn 0.6340 0.7159 0.2925 +vn -0.7135 0.6224 -0.3218 +vn 0.1744 0.6816 0.7106 +vn 0.1444 0.7782 0.6112 +vn 0.0940 0.8079 0.5818 +vn 0.1080 0.6600 0.7434 +vn 0.2691 0.4505 0.8513 +vn 0.2765 -0.2467 0.9288 +vn -0.2506 -0.5951 0.7636 +vn -0.2578 -0.5935 0.7625 +vn -0.0312 -0.7075 0.7061 +vn -0.0311 -0.7291 0.6837 +vn -0.0524 -0.7985 0.5998 +vn 0.4536 -0.7210 -0.5239 +vn 0.4399 -0.7146 -0.5440 +vn 0.4625 -0.6725 -0.5778 +vn 0.6117 -0.5203 -0.5959 +vn 0.6446 -0.4838 -0.5919 +vn -0.7258 -0.3320 -0.6025 +vn 0.6296 -0.2503 -0.7355 +vn 0.0354 -0.0743 -0.9966 +vn -0.2092 -0.1646 -0.9639 +vn -0.0121 -0.0702 -0.9975 +vn -0.0083 0.1712 -0.9852 +vn -0.0101 0.1802 -0.9836 +vn -0.0196 0.3210 -0.9469 +vn 0.8398 0.2294 -0.4920 +vn -0.7629 0.4279 -0.4846 +vn 0.1208 0.5696 -0.8130 +vn 0.3207 0.5850 -0.7449 +vn 0.1741 0.6301 -0.7568 +vn 0.2529 0.8303 0.4966 +vn -0.0792 0.6155 0.7841 +vn 0.3756 0.7421 0.5551 +vn 0.1951 0.7494 0.6328 +vn -0.0648 0.6809 0.7295 +vn -0.1483 0.5115 0.8464 +vn 0.6870 0.1408 0.7129 +vn -0.5321 -0.1791 0.8275 +vn 0.2715 -0.2508 0.9292 +vn -0.2436 -0.5929 0.7675 +vn -0.2524 -0.5910 0.7662 +vn 0.0055 -0.6929 0.7210 +vn -0.0223 -0.7430 0.6689 +vn -0.0655 -0.7975 0.5997 +vn 0.4167 -0.6886 -0.5934 +vn 0.4314 -0.7408 -0.5149 +vn 0.4115 -0.7353 -0.5385 +vn 0.5626 -0.5402 -0.6259 +vn 0.5998 -0.5008 -0.6240 +vn 0.6505 -0.2416 -0.7200 +vn 0.6214 -0.2341 -0.7477 +vn 0.4167 -0.1485 -0.8968 +vn 0.5017 -0.0522 -0.8635 +vn 0.5303 -0.0313 -0.8472 +vn -0.2764 0.1029 -0.9555 +vn -0.3421 0.0314 -0.9391 +vn -0.1220 0.2570 -0.9587 +vn -0.0447 0.3277 -0.9437 +vn 0.0615 0.6211 -0.7813 +vn 0.1625 0.6052 -0.7793 +vn 0.0680 0.6182 -0.7831 +vn 0.3617 0.7325 0.5767 +vn -0.7948 0.5315 0.2929 +vn 0.7243 0.6605 0.1980 +vn -0.7709 0.6368 0.0129 +vn 0.6524 0.7513 -0.0997 +vn -0.3915 0.8059 -0.4441 +vn -0.4147 0.7963 -0.4403 +vn -0.1023 0.6960 -0.7108 +vn -0.0711 0.6517 -0.7552 +vn -0.0451 0.6684 0.7424 +vn 0.0894 0.7713 0.6301 +vn 0.1000 0.7876 0.6081 +vn -0.0734 0.6891 0.7209 +vn -0.1449 0.5258 0.8382 +vn -0.5547 -0.5201 0.6494 +vn -0.5880 -0.4852 0.6471 +vn -0.4325 -0.6610 0.6132 +vn -0.4295 -0.7095 0.5587 +vn -0.4525 -0.7205 0.5255 +vn 0.4535 -0.7210 -0.5239 +vn 0.6117 -0.5202 -0.5959 +vn 0.6447 -0.4837 -0.5919 +vn -0.7255 -0.3322 -0.6027 +vn 0.6506 -0.2416 -0.7200 +vn 0.6215 -0.2342 -0.7476 +vn 0.4168 -0.1485 -0.8968 +vn 0.0408 0.6087 -0.7923 +vn -0.2517 0.8311 -0.4959 +vn -0.1080 0.6823 -0.7230 +vn -0.0670 0.6424 -0.7634 +vn -0.4885 0.8716 -0.0405 +vn 0.2614 0.9222 0.2850 +vn -0.2069 0.7796 0.5910 +vn -0.0429 0.7482 0.6621 +vn -0.0361 0.7120 0.7012 +vn -0.0565 0.6905 0.7212 +vn 0.7292 0.1349 0.6708 +vn -0.6364 -0.0804 0.7672 +vn 0.6704 -0.1934 0.7163 +vn -0.7466 -0.3187 0.5839 +vn 0.6878 -0.4567 0.5642 +vn 0.6547 -0.4944 0.5718 +vn 0.4621 -0.6835 0.5651 +vn 0.4283 -0.7266 0.5372 +vn 0.4416 -0.7361 0.5129 +vn -0.0702 0.6491 -0.7574 +vn -0.1103 0.6893 -0.7161 +vn -0.2577 0.8434 -0.4714 +vn 0.4313 0.8029 -0.4114 +vn 0.1554 0.6961 0.7009 +vn 0.0478 0.7906 0.6105 +vn 0.0175 0.8124 0.5828 +vn 0.1018 0.6561 0.7478 +vn 0.2767 -0.2467 0.9288 +vn -0.2431 -0.5930 0.7676 +vn -0.2519 -0.5911 0.7663 +vn 0.5892 -0.2332 -0.7736 +vn 0.2820 -0.2428 -0.9282 +vn 0.0560 0.8434 0.5343 +vn -0.0680 0.7899 0.6094 +vn 0.3641 0.5952 0.7164 +vn 0.4041 0.6399 0.6537 +vn 0.5394 0.3992 0.7414 +vn -0.8248 0.0211 0.5650 +vn 0.6644 -0.1807 0.7252 +vn -0.7499 -0.3053 0.5869 +vn 0.3149 -0.5240 0.7913 +vn 0.1557 -0.6702 0.7257 +vn 0.2789 -0.6480 0.7087 +vn 0.1047 -0.7809 0.6158 +vn 0.0286 -0.7681 0.6397 +vn 0.0256 -0.8295 0.5580 +vn 0.2955 -0.7495 -0.5924 +vn 0.4108 -0.6369 -0.6524 +vn 0.2875 0.0191 -0.9576 +vn 0.0320 -0.2374 -0.9709 +vn -0.0077 0.1623 -0.9867 +vn -0.0097 0.1736 -0.9848 +vn -0.0186 0.3065 -0.9517 +vn 0.4906 0.4975 -0.7154 +vn 0.3013 0.6449 -0.7024 +vn 0.4187 0.6254 -0.6585 +vn 0.0552 0.7449 -0.6649 +vn -0.2612 0.7332 0.6278 +vn 0.0000 0.6486 0.7611 +vn -0.1108 0.7284 0.6761 +vn -0.2832 0.8170 0.5024 +vn 0.3782 0.8058 0.4556 +vn -0.0071 0.9948 0.1014 +vn -0.4550 0.7694 -0.4483 +vn -0.2464 0.6750 -0.6954 +vn -0.3488 0.6417 -0.6830 +vn -0.1326 0.5907 -0.7959 +vn 0.0089 0.5324 0.8465 +vn 0.0247 0.2285 0.9732 +vn 0.0155 0.3242 0.9459 +vn 0.0049 0.3724 0.9281 +vn -0.0248 0.0563 0.9981 +vn 0.0052 -0.0666 0.9978 +vn -0.0060 -0.3093 0.9510 +vn -0.0026 -0.3665 0.9304 +vn 0.0132 -0.2359 0.9717 +vn 0.0034 -0.5321 0.8467 +vn -0.0025 -0.0027 -1.0000 +vn 0.0004 -0.0020 -1.0000 +vn -0.0098 -0.0005 -1.0000 +vn -0.0044 0.2446 -0.9696 +vn 0.0216 0.7620 0.6472 +vn 0.0088 0.7760 0.6307 +vn 0.0147 0.7695 0.6384 +vn 0.0277 0.7552 0.6550 +vn -0.9722 0.2339 -0.0105 +vn -0.9714 0.2058 -0.1181 +vn -0.9416 0.3252 -0.0870 +vn -0.9973 0.0649 -0.0357 +vn -0.9980 -0.0216 0.0599 +vn -0.9989 -0.0204 0.0422 +vn -0.9984 -0.0217 0.0514 +vn -0.9991 -0.0313 0.0299 +vn -0.9891 0.1462 -0.0155 +vn -0.9993 0.0319 -0.0192 +vn -0.9996 -0.0203 0.0187 +vn -0.9993 -0.0377 0.0065 +vn -0.9998 0.0151 -0.0138 +vn -0.9999 0.0081 -0.0075 +vn -0.9958 -0.0720 0.0563 +vn -0.9657 -0.2474 0.0789 +vn -0.9641 -0.2530 0.0808 +vn 0.0038 0.9881 -0.1540 +vn -0.0304 0.9898 -0.1395 +vn -0.0973 0.9891 -0.1104 +vn -0.1264 0.9872 -0.0975 +vn 0.1219 -0.0697 0.9901 +vn 0.0961 -0.0793 0.9922 +vn 0.0251 -0.1054 0.9941 +vn -0.0031 -0.1156 0.9933 +vn 0.0495 0.9836 -0.1732 +vn 0.1208 0.9719 -0.2022 +vn 0.1765 0.9584 -0.2243 +vn -0.1366 0.8001 0.5841 +vn -0.3112 0.7315 0.6066 +vn 0.3156 -0.0239 0.9486 +vn 0.2609 -0.0488 0.9641 +vn 0.0795 -0.1272 0.9887 +vn -0.0039 -0.1612 0.9869 +vn -0.0290 0.9897 -0.1401 +vn -0.0931 0.9893 -0.1123 +vn -0.1212 0.9876 -0.0998 +vn 0.2167 -0.0685 0.9738 +vn 0.1737 -0.0873 0.9809 +vn 0.0521 -0.1385 0.9890 +vn 0.1433 -0.1004 0.9846 +vn 0.1133 -0.1131 0.9871 +vn 0.0436 -0.1420 0.9889 +vn 0.0146 -0.0702 0.9974 +vn 0.0108 -0.0721 0.9973 +vn 0.0028 -0.0762 0.9971 +vn -0.0024 -0.0789 0.9969 +vn 0.0443 0.9834 -0.1759 +vn -0.0599 0.9719 -0.2275 +vn 0.2111 0.9735 -0.0877 +vn 0.2800 0.9587 -0.0491 +vn -0.3130 0.7520 0.5801 +vn 0.2327 0.6308 0.7402 +vn 0.0016 -0.1184 0.9930 +vn 0.0003 -0.1189 0.9929 +vn -0.0021 -0.1197 0.9928 +vn -0.0032 -0.1201 0.9928 +vn -0.0273 0.9733 -0.2278 +vn 0.3320 0.9238 0.1909 +vn -0.1856 0.7780 0.6002 +vn 0.1981 0.0434 0.9792 +vn 0.1295 -0.0138 0.9915 +vn 0.0870 -0.0486 0.9950 +vn -0.0014 -0.1201 0.9928 +vn 0.0031 -0.1188 -0.9929 +vn 0.0215 -0.1292 -0.9914 +vn 0.0418 -0.1407 -0.9892 +vn 0.0578 -0.1496 -0.9870 +vn -0.1431 0.5995 -0.7875 +vn 0.3617 0.7490 -0.5552 +vn -0.4650 0.8520 0.2406 +vn -0.3055 0.9326 0.1923 +vn -0.1427 0.9798 0.1398 +vn -0.0369 0.9939 0.1041 +vn 0.0041 -0.1750 -0.9846 +vn -0.0282 -0.1596 -0.9868 +vn -0.0633 -0.1426 -0.9878 +vn -0.0839 -0.1325 -0.9876 +vn 0.1432 0.9882 0.0542 +vn 0.1181 0.9910 0.0634 +vn 0.0341 0.9951 0.0933 +vn 0.0036 0.9946 0.1040 +vn -0.0302 -0.1586 -0.9869 +vn -0.0859 -0.1315 -0.9876 +vn -0.1138 -0.1176 -0.9865 +vn 0.0014 -0.1161 -0.9932 +vn -0.0094 -0.1075 -0.9942 +vn -0.0127 -0.1048 -0.9944 +vn -0.0236 -0.0961 -0.9951 +vn -0.3742 0.6986 -0.6099 +vn -0.3056 0.7103 -0.6341 +vn 0.0267 0.9909 0.1317 +vn 0.0150 0.9897 0.1425 +vn 0.0135 0.9895 0.1440 +vn 0.0013 0.9879 0.1552 +vn 0.0304 -0.0981 -0.9947 +vn 0.0286 0.5123 -0.8583 +vn 0.4189 -0.0577 -0.9062 +vn -0.1909 0.5176 -0.8340 +vn -0.0084 -0.0953 -0.9954 +vn 0.0327 0.5124 -0.8581 +vn 0.0225 -0.1998 -0.9796 +vn -0.0480 -0.1744 -0.9835 +vn -0.2206 -0.1076 -0.9694 +vn -0.2607 -0.0911 -0.9611 +vn 0.3134 0.3910 -0.8654 +vn 0.2710 0.4108 -0.8705 +vn 0.0664 0.4906 -0.8688 +vn -0.0074 0.5134 -0.8581 +vn 0.0173 0.0366 0.9992 +vn 0.0061 0.0270 0.9996 +vn -0.0128 0.9997 0.0207 +vn -0.0149 0.9996 0.0230 +vn -0.0005 0.6056 -0.7958 +vn -0.0038 0.6084 -0.7937 +vn -0.0048 0.9979 -0.0653 +vn 0.0094 0.9970 -0.0771 +vn -0.0055 0.4929 -0.8701 +vn -0.0142 0.4741 -0.8804 +vn 0.0151 0.5122 -0.8587 +vn 0.9992 -0.0347 -0.0174 +vn 0.9993 -0.0354 -0.0144 +vn 0.9990 -0.0325 -0.0307 +vn 0.9990 -0.0322 -0.0311 +vn 0.9992 -0.0388 0.0056 +vn 0.9988 -0.0296 0.0383 +vn 0.9988 -0.0192 0.0451 +vn 0.9992 -0.0334 0.0239 +vn 0.9984 -0.0200 0.0529 +vn 0.9985 -0.0339 0.0438 +vn -0.9726 -0.2320 -0.0181 +vn -0.9821 -0.1872 0.0201 +vn -1.0000 -0.0013 -0.0054 +vn -1.0000 -0.0005 -0.0063 +vn -0.9996 0.0167 -0.0214 +vn -1.0000 0.0023 -0.0073 +vn -0.9739 -0.2214 -0.0500 +vn -0.9998 -0.0048 -0.0197 +vn -0.9474 -0.2893 -0.1370 +vn -0.9991 -0.0347 -0.0224 +vn -0.9952 -0.0706 -0.0681 +vn -0.9998 -0.0182 -0.0038 +vn -0.9996 -0.0224 -0.0167 +vn -0.9992 0.0029 -0.0410 +vn -0.9979 0.0576 0.0309 +vn -0.9996 -0.0006 0.0281 +vn -0.9995 -0.0226 0.0231 +vn -0.9960 0.0888 0.0124 +vn -0.9989 0.0272 0.0378 +vn -0.9972 0.0376 0.0640 +vn -0.9893 0.1304 0.0651 +vn -0.9971 0.0319 0.0695 +vn -0.9587 0.2828 0.0290 +vn -0.9772 -0.0043 0.2122 +vn -0.9788 -0.0262 0.2032 +vn -1.0000 0.0001 0.0001 +vn 0.9989 0.0239 -0.0396 +vn 0.9917 -0.0566 -0.1151 +vn 0.8540 0.0277 -0.5195 +vn 0.9650 -0.0667 -0.2536 +vn 0.9982 0.0599 -0.0080 +vn -0.9997 -0.0095 -0.0234 +vn -0.9811 -0.0779 -0.1769 +vn -0.9872 -0.0542 -0.1498 +vn -0.9754 -0.0880 -0.2021 +vn -0.9884 -0.0490 -0.1439 +vn 0.9999 -0.0048 -0.0122 +vn 0.9883 -0.0558 -0.1418 +vn 0.9834 -0.0665 -0.1691 +vn -0.9999 -0.0046 -0.0140 +vn -0.9877 -0.0487 -0.1483 +vn -0.9843 -0.0561 -0.1674 +vn -0.9842 -0.0563 -0.1676 +vn 0.9920 -0.0562 -0.1129 +vn 0.9856 -0.0714 -0.1533 +vn 0.9814 -0.0760 -0.1761 +vn -0.9806 -0.0761 -0.1809 +vn -0.9848 -0.0577 -0.1640 +vn -0.9752 -0.0861 -0.2041 +vn -0.9858 -0.0534 -0.1592 +vn -0.9878 -0.0487 -0.1483 +vn -0.9999 -0.0046 -0.0141 +vn -0.9877 -0.0488 -0.1487 +vn 0.9999 -0.0157 0.0025 +vn 0.9998 -0.0185 -0.0046 +vn 0.9955 -0.0489 -0.0812 +vn 0.9938 -0.0549 -0.0963 +vn -0.0010 -0.5507 -0.8347 +vn -0.0065 -0.5513 -0.8343 +vn 0.0536 -0.5437 -0.8375 +vn 0.0590 -0.5430 -0.8377 +vn -0.0155 -0.6038 -0.7970 +vn 0.2144 -0.4770 -0.8524 +vn -0.3310 -0.5204 -0.7871 +vn 0.5769 -0.4045 -0.7096 +vn 0.9988 -0.0110 -0.0479 +vn 0.9992 0.0048 -0.0409 +vn 0.9758 -0.2035 -0.0799 +vn 0.9812 -0.1693 0.0924 +vn 0.9992 0.0043 0.0394 +vn 0.9989 -0.0116 0.0464 +vn 0.9838 -0.1706 0.0552 +vn 0.9595 -0.2807 0.0243 +vn 0.9859 -0.1652 -0.0283 +vn 0.9815 -0.1625 -0.1009 +vn -1.0000 0.0003 -0.0001 +vn -1.0000 0.0008 -0.0006 +vn 0.9758 -0.2035 -0.0800 +vn 0.9992 -0.0032 0.0403 +vn 0.9988 -0.0164 0.0462 +vn 0.9829 -0.1590 0.0933 +vn 0.9835 -0.1740 0.0496 +vn 0.9599 -0.2792 0.0243 +vn 0.9772 -0.2098 -0.0324 +vn 0.9735 -0.2004 -0.1105 +vn -0.9990 -0.0098 0.0426 +vn -0.9993 0.0042 0.0365 +vn -0.9765 -0.2018 0.0757 +vn -0.9794 -0.1746 -0.1019 +vn -0.9991 -0.0008 -0.0434 +vn -0.9986 -0.0160 -0.0501 +vn -0.9811 -0.1863 -0.0518 +vn -0.9596 -0.2802 -0.0244 +vn -0.9772 -0.2099 0.0323 +vn -0.9781 -0.1819 0.1012 +vn 0.9793 -0.1943 0.0562 +vn 0.9735 -0.2003 -0.1105 +vn -0.9984 -0.0153 0.0540 +vn -0.9989 0.0006 0.0469 +vn -0.9718 -0.2194 0.0867 +vn -0.9595 -0.2805 -0.0245 +vn -0.9763 -0.2140 0.0314 +vn -0.9695 -0.2142 0.1191 +vn 0.9829 -0.1589 0.0933 +vn 0.9992 -0.0008 0.0392 +vn 0.9989 -0.0145 0.0453 +vn 0.9772 -0.2098 -0.0323 +vn -0.9990 -0.0125 0.0438 +vn -0.9993 0.0005 0.0381 +vn -0.9768 -0.2003 0.0755 +vn 0.9992 -0.0090 -0.0393 +vn 0.9994 0.0039 -0.0337 +vn 0.9797 -0.1876 -0.0704 +vn 0.9600 -0.2790 0.0242 +vn 0.9779 -0.2064 -0.0331 +vn 0.9805 -0.1719 -0.0948 +vn -0.9985 -0.0120 0.0525 +vn -0.9990 0.0052 0.0449 +vn -0.9714 -0.2212 0.0869 +vn -0.9718 -0.2195 0.0867 +vn -0.9989 -0.0036 -0.0459 +vn -0.9985 -0.0187 -0.0524 +vn -0.9789 -0.1794 -0.0978 +vn -0.9772 -0.2042 -0.0583 +vn -0.9591 -0.2818 -0.0245 +vn 0.9991 -0.0091 -0.0423 +vn 0.9993 0.0049 -0.0360 +vn 0.9801 -0.1848 -0.0728 +vn 1.0000 0.0004 -0.0002 +vn 0.9832 -0.1662 0.0760 +vn 0.9998 -0.0170 0.0145 +vn 0.9850 -0.1615 0.0606 +vn 0.9519 -0.3058 0.0212 +vn 0.9700 -0.2393 -0.0431 +vn 0.9778 -0.1840 -0.1003 +vn 0.0310 -0.8075 0.5891 +vn -0.0065 -0.8030 0.5960 +vn 0.2379 -0.8106 0.5351 +vn 0.2576 -0.8089 0.5284 +vn -0.4393 -0.8523 0.2841 +vn 0.5036 -0.8586 0.0957 +vn -0.5036 -0.8586 -0.0957 +vn 0.4393 -0.8523 -0.2841 +vn -0.2379 -0.8106 -0.5351 +vn -0.2576 -0.8089 -0.5284 +vn -0.0311 -0.8075 -0.5891 +vn 0.0063 -0.8030 -0.5960 +vn -0.0138 -0.8029 0.5959 +vn 0.5060 -0.7221 0.4717 +vn -0.7324 -0.6459 0.2153 +vn 0.7886 -0.6111 0.0681 +vn -0.7886 -0.6111 -0.0681 +vn 0.7325 -0.6459 -0.2153 +vn -0.5056 -0.7223 -0.4718 +vn 0.0142 -0.8029 -0.5959 +vn -0.0142 -0.8029 0.5959 +vn 0.7324 -0.6459 -0.2153 +vn -0.5060 -0.7221 -0.4717 +vn 0.5056 -0.7223 0.4718 +vn -0.7325 -0.6459 0.2153 +vn 0.0139 -0.8029 -0.5959 +vn 0.0113 -0.9389 -0.3440 +vn 0.0210 -0.9534 -0.3011 +vn 0.0294 -0.9545 -0.2967 +vn 0.0298 -0.9737 -0.2260 +vn 0.0140 -0.9245 -0.3808 +vn -0.0012 -0.7371 -0.6758 +vn -0.0073 -0.7289 -0.6846 +vn 0.0011 -0.7245 -0.6893 +vn 0.0133 -0.8495 0.5274 +vn 0.0313 -0.9734 0.2272 +vn 0.0182 -0.9416 0.3362 +vn 0.0008 -0.9548 0.2971 +vn 0.0215 -0.9985 0.0500 +vn -0.0147 -0.9973 -0.0723 +vn -0.0129 -0.7659 0.6428 +vn -0.0291 -0.7477 0.6634 +vn -0.0215 -0.7563 0.6538 +vn -0.0058 -0.7737 0.6335 +vn -0.0048 0.0138 0.9999 +vn 0.0911 0.0412 0.9950 +vn 0.3096 0.1029 0.9453 +vn 0.4692 0.1475 0.8707 +vn -0.4204 -0.5847 0.6938 +vn 0.5617 -0.8091 0.1730 +vn -0.0146 -0.9997 -0.0189 +vn -0.0254 0.0079 0.9996 +vn -0.1007 -0.0137 0.9948 +vn -0.1191 -0.0190 0.9927 +vn 0.1277 -0.9699 0.2074 +vn 0.1103 -0.9727 0.2040 +vn 0.0113 -0.9830 0.1832 +vn -0.0084 -0.9838 0.1789 +vn 0.0031 0.1156 0.9933 +vn -0.4691 -0.0696 0.8804 +vn 0.3523 -0.6809 0.6420 +vn -0.5477 -0.8279 0.1211 +vn 0.0234 -0.9933 -0.1128 +vn 0.0551 0.0309 0.9980 +vn 0.2220 0.0783 0.9719 +vn 0.3134 0.1040 0.9439 +vn -0.4001 -0.7054 0.5850 +vn 0.6420 -0.7497 0.1603 +vn -0.0193 -0.9828 -0.1838 +vn -0.0010 0.1885 0.9821 +vn -0.0416 0.1497 0.9879 +vn -0.0478 0.1437 0.9885 +vn -0.0833 0.1091 0.9905 +vn 0.1037 -0.6645 0.7401 +vn -0.0178 -0.7339 0.6790 +vn 0.0509 -0.9875 -0.1492 +vn 0.0921 -0.9788 -0.1830 +vn 0.0469 -0.9882 -0.1459 +vn 0.0106 -0.9932 -0.1159 +vn -0.0432 -0.9829 -0.1788 +vn 0.8448 -0.5283 0.0852 +vn -0.4232 -0.7018 -0.5731 +vn 0.3511 -0.0179 -0.9362 +vn 0.3003 0.0027 -0.9538 +vn 0.0865 0.0854 -0.9926 +vn 0.0033 0.1159 -0.9933 +vn 0.0250 -0.9879 -0.1532 +vn 0.7713 -0.6330 0.0671 +vn -0.3488 -0.7144 -0.6066 +vn 0.4684 -0.0693 -0.8808 +vn -0.0031 0.1155 -0.9933 +vn 0.0280 -0.9860 -0.1645 +vn 0.7987 -0.5984 0.0635 +vn -0.4050 -0.6970 -0.5918 +vn 0.3506 -0.0179 -0.9363 +vn 0.2999 0.0026 -0.9540 +vn 0.0863 0.0852 -0.9926 +vn 0.0034 0.1155 -0.9933 +vn 0.0084 -0.9838 -0.1790 +vn 0.8096 -0.5818 0.0782 +vn 0.0172 -0.9913 0.1301 +vn 0.0188 -0.9911 0.1315 +vn 0.0191 -0.9911 0.1317 +vn 0.0208 -0.9909 0.1331 +vn -0.1871 -0.7398 -0.6463 +vn -0.1455 -0.7417 -0.6548 +vn 0.0859 0.0457 -0.9952 +vn 0.0511 0.0738 -0.9960 +vn 0.0363 0.0855 -0.9957 +vn -0.0014 0.1155 -0.9933 +vn 0.2356 -0.5974 -0.7666 +vn -0.1017 -0.1841 -0.9776 +vn 0.6163 0.0273 -0.7871 +vn -0.3022 0.3013 -0.9043 +vn 0.4456 -0.5050 -0.7392 +vn -0.3438 -0.1581 -0.9257 +vn 0.6160 0.1476 -0.7738 +vn 0.6095 0.1453 -0.7793 +vn 0.0238 -0.3725 -0.9277 +vn 0.0736 -0.5985 -0.7977 +vn 0.7903 0.0581 -0.6100 +vn 0.0039 -0.5895 -0.8077 +vn 0.0165 -0.5940 -0.8043 +vn 0.0750 -0.3522 -0.9329 +vn 0.1122 0.1752 -0.9781 +vn -0.0102 0.2265 -0.9740 +vn -0.0192 -0.0332 0.9993 +vn -0.0109 -0.0252 0.9996 +vn 0.0201 -0.9991 0.0371 +vn 0.0108 -0.9995 0.0283 +vn -0.0105 -0.6298 -0.7767 +vn 0.0180 -0.6481 -0.7614 +vn 0.0064 -0.9983 -0.0583 +vn -0.0061 -0.9974 -0.0717 +vn -0.0039 -0.5302 -0.8479 +vn -0.0061 -0.5348 -0.8449 +vn 0.9525 0.2765 0.1273 +vn 0.7173 0.6705 0.1894 +vn 0.7567 0.5292 0.3839 +vn 0.9184 0.3836 0.0967 +vn 0.9054 0.4188 0.0699 +vn 0.9484 0.3157 0.0299 +vn 0.9015 0.4325 -0.0156 +vn 0.7125 0.7004 -0.0421 +vn 0.8849 0.4657 0.0040 +vn 0.9346 0.3400 -0.1042 +vn 0.9399 0.3413 -0.0128 +vn 0.7158 0.6575 -0.2351 +vn 0.7058 0.5130 -0.4886 +vn 0.7163 0.3887 -0.5795 +vn 0.8852 0.2100 -0.4152 +vn 0.8953 0.0916 -0.4360 +vn 0.8029 0.0861 -0.5899 +vn 0.5785 0.3001 -0.7585 +vn 0.7693 0.1144 -0.6286 +vn 0.7862 0.1150 -0.6072 +vn 0.8394 -0.0970 -0.5348 +vn 0.7127 -0.1633 -0.6822 +vn 0.7792 -0.0976 -0.6192 +vn 0.7484 -0.1473 -0.6467 +vn 0.5729 -0.3717 -0.7305 +vn 0.9414 -0.2512 -0.2251 +vn 0.7584 -0.4518 -0.4698 +vn 0.9176 -0.2549 -0.3052 +vn 0.9353 -0.3539 -0.0069 +vn 0.9011 -0.4337 -0.0042 +vn 0.7017 -0.7100 -0.0597 +vn 0.7186 -0.6616 0.2143 +vn 0.8807 -0.4660 0.0844 +vn 0.9357 -0.3409 0.0910 +vn 0.7099 -0.4197 0.5656 +vn 0.7518 -0.5086 0.4197 +vn 0.9474 -0.0967 0.3052 +vn 0.7293 -0.1704 0.6627 +vn 0.7692 0.0238 0.6385 +vn 0.9450 0.1233 0.3030 +vn 0.7149 0.2185 0.6642 +vn 0.8523 0.0196 -0.5227 +vn 0.6440 -0.5039 -0.5756 +vn 0.7598 0.4533 0.4661 +vn 0.8927 -0.1144 -0.4359 +vn 0.7985 -0.4223 -0.4291 +vn 0.9068 0.2196 -0.3599 +vn 0.9356 0.1606 -0.3145 +vn 0.9389 -0.1272 -0.3199 +vn 0.9377 0.2587 -0.2317 +vn 0.9599 -0.0042 -0.2803 +vn 0.8975 0.2800 0.3407 +vn 0.9783 0.0724 0.1939 +vn 0.9753 -0.1317 0.1774 +vn 0.8869 -0.3453 0.3070 +vn 0.9747 0.1270 -0.1838 +vn 0.9793 -0.1656 -0.1165 +vn 0.7615 -0.5922 -0.2634 +vn 0.9931 -0.0354 -0.1120 +vn 0.9436 -0.3166 -0.0970 +vn 0.9689 0.2344 -0.0789 +vn 0.9847 0.1560 0.0773 +vn 0.9961 0.0834 -0.0285 +vn 0.9968 -0.0558 0.0568 +vn 0.9643 -0.2500 0.0873 +vn 0.7900 -0.4755 0.3871 +vn 0.2509 0.7385 -0.6259 +vn 0.2925 0.8717 -0.3932 +vn -0.0239 0.8832 -0.4684 +vn -0.0245 0.8831 -0.4686 +vn -0.0079 0.9918 -0.1276 +vn 0.2513 0.8657 -0.4330 +vn 0.3118 0.9373 -0.1559 +vn 0.3410 0.9365 0.0824 +vn 0.2381 0.9232 0.3017 +vn 0.2949 0.8008 0.5213 +vn 0.3211 0.5795 0.7490 +vn 0.2870 0.4128 0.8644 +vn 0.3083 0.1781 0.9345 +vn 0.3008 -0.0443 0.9527 +vn 0.3086 -0.3232 0.8946 +vn 0.2186 -0.5749 0.7885 +vn 0.0122 0.0099 -0.9999 +vn -0.0241 0.0340 -0.9991 +vn 0.0371 0.2706 -0.9620 +vn 0.3935 0.5140 -0.7623 +vn 0.0048 -0.6075 -0.7943 +vn -0.0360 -0.6908 -0.7222 +vn 0.0299 -0.5518 -0.8334 +vn -0.0694 -0.7526 -0.6549 +vn 0.0682 -0.7152 0.6956 +vn 0.0609 -0.7069 0.7047 +vn 0.0656 -0.7122 0.6989 +vn 0.0759 -0.7239 0.6857 +vn 0.0778 0.8893 0.4507 +vn -0.0026 0.8046 0.5937 +vn 0.0314 0.8438 0.5357 +vn -0.0700 0.7126 0.6980 +vn -0.0074 0.5990 -0.8007 +vn -0.0440 0.6815 -0.7305 +vn -0.0202 0.6287 -0.7774 +vn -0.0577 0.7103 -0.7015 +vn -0.0356 -0.9077 0.4182 +vn 0.0467 -0.5151 0.8558 +vn -0.0287 0.1213 0.9922 +vn 0.0242 0.9166 0.3992 +vn 0.0268 0.9219 0.3864 +vn 0.0246 0.9175 0.3970 +vn 0.0271 0.9225 0.3851 +vn -0.0331 0.6836 -0.7291 +vn 0.0303 0.3150 -0.9486 +vn -0.0256 0.6453 -0.7635 +vn 0.0381 0.2632 -0.9640 +vn -0.0321 -0.5710 -0.8203 +vn 0.0250 -0.8575 -0.5139 +vn -0.0257 -0.6099 -0.7921 +vn 0.0329 -0.8862 -0.4622 +vn -0.0074 0.7083 0.7059 +vn -0.0031 0.8726 0.4884 +vn 0.2098 0.4874 0.8476 +vn -0.0036 0.9874 0.1580 +vn 0.0041 0.9778 0.2094 +vn -0.0047 0.9941 0.1087 +vn 0.0098 0.7681 -0.6402 +vn -0.0027 0.8247 -0.5656 +vn -0.0042 0.8312 -0.5559 +vn 0.0110 0.7620 -0.6474 +vn 0.3574 0.5180 0.7772 +vn 0.2745 0.8424 0.4636 +vn 0.3364 0.9406 -0.0461 +vn 0.2389 0.4238 -0.8737 +vn -0.0140 0.3446 -0.9387 +vn 0.0010 0.2402 -0.9707 +vn 0.6123 0.7098 0.3482 +vn -0.5291 0.6494 0.5462 +vn 0.6121 0.6795 0.4046 +vn 0.5164 0.8530 0.0754 +vn 0.6599 0.5031 -0.5580 +vn 0.6644 0.4558 -0.5924 +vn 0.6028 0.6833 -0.4119 +vn 0.5954 0.7435 -0.3046 +vn 0.6241 0.7580 -0.1895 +vn 0.5305 0.7752 -0.3429 +vn 0.3847 0.0086 -0.9230 +vn -0.0013 -0.9343 -0.3566 +vn 0.0151 -0.8193 -0.5732 +vn 0.0132 -0.7856 -0.6186 +vn 0.1880 -0.7034 -0.6855 +vn 0.3364 -0.8572 -0.3899 +vn 0.0010 -0.7841 0.6206 +vn 0.2861 -0.8739 0.3931 +vn 0.3651 -0.9235 0.1175 +vn 0.2579 -0.9544 -0.1503 +vn 0.2503 -0.4305 -0.8672 +vn -0.0292 0.9691 -0.2448 +vn 0.0240 0.9976 0.0655 +vn -0.0374 0.9557 -0.2920 +vn -0.0260 -0.1436 -0.9893 +vn 0.0317 0.2076 -0.9777 +vn 0.0231 0.1554 -0.9876 +vn -0.0328 -0.1848 -0.9822 +vn 0.0292 -0.8787 -0.4765 +vn -0.0275 -0.9757 0.2175 +vn 0.0066 -0.8857 0.4642 +vn -0.0240 -0.9694 0.2443 +vn 0.0113 -0.8681 0.4962 +vn -0.0160 0.2232 0.9746 +vn -0.0239 0.1904 0.9814 +vn -0.0169 0.2195 0.9755 +vn -0.0253 0.1843 0.9825 +vn 0.0335 0.9921 0.1212 +vn -0.0099 -0.6988 0.7152 +vn 0.2178 -0.5348 0.8164 +vn 0.0001 -0.8700 0.4930 +vn -0.0088 -0.3663 -0.9305 +vn 0.3470 -0.7531 -0.5589 +vn 0.1834 -0.5095 -0.8407 +vn 0.0029 -0.9654 -0.2607 +vn 0.2492 -0.9476 -0.2001 +vn 0.0026 -0.9649 -0.2625 +vn 0.3037 -0.5230 0.7964 +vn 0.2512 -0.8303 0.4975 +vn 0.2163 -0.9755 0.0403 +vn -0.0146 -0.9704 0.2409 +vn -0.0017 -0.9531 0.3027 +vn 0.2746 -0.4831 -0.8314 +vn 0.0126 -0.5651 -0.8249 +vn 0.4191 -0.7763 0.4709 +vn 0.6269 -0.5560 0.5458 +vn 0.6312 -0.6503 0.4227 +vn 0.5166 -0.8493 0.1084 +vn 0.5945 -0.7615 -0.2584 +vn 0.6642 -0.5772 -0.4750 +vn 0.3957 -0.4960 -0.7729 +vn 0.5815 -0.6208 -0.5258 +vn -0.0931 -0.9957 -0.0021 +vn 0.4595 -0.8641 -0.2056 +vn 0.6811 -0.6967 -0.2250 +vn 0.8721 -0.3998 -0.2821 +vn -0.7432 -0.5908 -0.3139 +vn 0.8640 0.4905 -0.1137 +vn 0.9121 0.3507 -0.2123 +vn 0.8113 0.5817 -0.0586 +vn 0.9783 0.1156 -0.1717 +vn 0.9973 0.0448 -0.0590 +vn 0.9303 0.0032 0.3668 +vn 0.8455 -0.0885 0.5266 +vn 0.9655 0.0641 0.2523 +vn 0.9491 -0.2292 0.2161 +vn 0.9646 -0.2624 0.0280 +vn 0.9206 -0.3676 0.1318 +vn 0.7861 -0.1360 0.6030 +vn 0.9822 0.1042 -0.1565 +vn 0.9649 0.1472 -0.2174 +vn 0.6096 0.7639 0.2119 +vn 0.5842 0.7842 0.2092 +vn 0.7523 0.6197 0.2234 +vn 0.9744 -0.2137 -0.0695 +vn 0.9672 -0.2456 -0.0655 +vn 0.9663 -0.2467 -0.0734 +vn 0.9995 -0.0289 -0.0103 +vn -0.6980 -0.1525 0.6996 +vn -0.9622 -0.2692 0.0412 +vn -0.9393 -0.3279 0.1007 +vn -0.9593 -0.2779 0.0499 +vn -0.9793 0.1835 -0.0852 +vn -0.9906 0.0848 -0.1076 +vn -0.9636 0.2662 0.0235 +vn -0.9583 0.2458 0.1456 +vn -0.9761 -0.2172 -0.0103 +vn -0.9723 0.1311 0.1933 +vn -0.8027 -0.3299 0.4969 +vn -0.9994 0.0159 -0.0292 +vn -0.9967 0.0255 -0.0765 +vn -0.9977 0.0053 -0.0675 +vn -0.9960 -0.0883 -0.0095 +vn -0.9988 -0.0459 0.0161 +vn -0.9991 -0.0371 0.0182 +vn -0.4245 0.5802 -0.6951 +vn -0.6365 -0.4581 -0.6205 +vn 0.7681 -0.5171 -0.3778 +vn -0.7512 -0.6600 0.0133 +vn 0.7510 -0.5465 0.3705 +vn -0.7062 -0.2640 0.6570 +vn 0.6603 0.0150 0.7509 +vn -0.7145 0.4514 0.5346 +vn 0.7665 0.6018 0.2242 +vn -0.4776 0.7784 -0.4074 +vn 0.4211 0.3145 -0.8507 +vn 0.4266 -0.6501 0.6288 +vn -0.3023 -0.9464 0.1139 +vn 0.1247 -0.8245 -0.5519 +vn -0.1664 -0.0675 -0.9837 +vn -0.1449 -0.0652 -0.9873 +vn -0.3995 -0.0902 -0.9123 +vn -0.4529 -0.0949 -0.8865 +vn 0.5965 0.5092 -0.6205 +vn -0.6961 0.6043 -0.3875 +vn 0.5836 0.8097 -0.0616 +vn -0.7038 0.6523 0.2816 +vn 0.2275 0.7670 0.6000 +vn -0.1157 0.7430 -0.6592 +vn 0.7166 0.6372 0.2835 +vn 0.0882 0.2742 0.9576 +vn -0.6711 0.0049 0.7414 +vn 0.6142 -0.7785 -0.1288 +vn -0.8659 -0.4258 0.2627 +vn -0.2521 -0.2383 -0.9379 +vn 0.2777 -0.5393 -0.7950 +vn -0.2735 -0.7646 0.5836 +vn 0.3017 -0.4115 0.8601 +vn -0.3284 0.8508 0.4102 +vn 0.2627 0.9638 0.0455 +vn 0.4161 0.8614 -0.2913 +vn -0.5313 -0.1948 -0.8245 +vn 0.3888 -0.6972 -0.6023 +vn -0.0396 -0.7295 0.6828 +vn 0.4643 -0.2450 0.8511 +vn -0.5644 0.6967 0.4428 +vn 0.9987 0.0426 0.0265 +vn 0.9991 -0.0066 0.0414 +vn 0.9989 -0.0285 0.0378 +vn 0.9976 -0.0463 0.0515 +vn 0.9965 -0.0372 -0.0755 +vn 0.9971 0.0677 0.0342 +vn 0.9984 0.0527 -0.0205 +vn 0.9980 0.0609 -0.0140 +vn -0.9928 0.0124 0.1192 +vn -0.9992 0.0373 -0.0122 +vn -0.9917 0.0107 0.1278 +vn -0.0224 0.4501 0.8927 +vn 0.0473 0.2083 0.9769 +vn 0.0330 0.2601 0.9650 +vn -0.0385 0.5021 0.8639 +vn -0.0042 0.9496 -0.3134 +vn -0.0112 0.9418 -0.3360 +vn -0.0345 0.9116 -0.4096 +vn -0.0420 0.9004 -0.4330 +vn -0.0703 -0.6068 -0.7917 +vn 0.0043 -0.3328 -0.9430 +vn -0.0122 -0.3965 -0.9179 +vn -0.0844 -0.6545 -0.7514 +vn -0.0428 -0.8683 0.4941 +vn 0.0219 -0.9884 0.1501 +vn 0.0103 -0.9767 0.2143 +vn -0.0577 -0.8209 0.5682 +vn -0.9914 -0.1145 -0.0637 +vn -0.9903 -0.1123 -0.0817 +vn -0.9896 -0.1306 0.0595 +vn -0.9849 -0.0925 0.1464 +vn -0.9928 0.1190 -0.0165 +vn -0.9894 0.0011 -0.1455 +vn -0.9842 0.0895 -0.1528 +vn -0.9798 0.1604 0.1196 +vn -0.9913 0.0252 0.1291 +vn -0.0727 -0.4422 0.8939 +vn -0.0401 -0.4717 0.8809 +vn -0.0728 -0.4421 0.8940 +vn -0.0985 -0.4181 0.9030 +vn 0.0900 0.5062 0.8577 +vn -0.0838 0.6750 0.7331 +vn -0.0655 0.6593 0.7490 +vn -0.2101 0.7688 0.6040 +vn 0.1497 0.9859 0.0751 +vn -0.0673 0.6891 -0.7215 +vn -0.0910 0.6717 -0.7352 +vn -0.0899 0.6725 -0.7346 +vn -0.1075 0.6591 -0.7443 +vn 0.0940 -0.1211 -0.9882 +vn 0.0084 -0.2661 -0.9639 +vn -0.0174 -0.3081 -0.9512 +vn -0.0962 -0.4322 -0.8966 +vn 0.0997 -0.8132 -0.5734 +vn -0.1044 -0.9902 -0.0924 +vn -0.0014 -0.9981 0.0623 +vn -0.0179 -0.9991 0.0377 +vn 0.1017 -0.9714 0.2147 +vn 0.6958 -0.7143 0.0753 +vn 0.2633 -0.7678 0.5841 +vn 0.1858 0.4977 0.8472 +vn -0.2475 0.3098 -0.9180 +vn 0.6690 0.5916 -0.4500 +vn -0.9593 -0.0194 0.2817 +vn 0.9995 0.0050 0.0308 +vn 0.9994 0.0233 0.0240 +vn 0.9993 -0.0130 0.0362 +vn 0.9996 -0.0232 -0.0141 +vn 0.9997 -0.0259 0.0030 +vn 0.9994 -0.0093 -0.0326 +vn 0.9997 0.0164 -0.0168 +vn 0.9997 0.0223 -0.0135 +vn -0.9991 -0.0097 -0.0404 +vn -0.9948 -0.0653 -0.0779 +vn -0.9991 -0.0095 -0.0403 +vn -0.9992 0.0395 -0.0072 +vn 0.0077 -0.5952 0.8036 +vn 0.0092 -0.9198 -0.3922 +vn -0.0245 -0.9990 0.0386 +vn -0.0223 -0.9997 0.0095 +vn 0.0115 -0.9078 -0.4192 +vn 0.0046 0.3524 -0.9358 +vn -0.0211 -0.0958 -0.9952 +vn -0.0196 -0.0683 -0.9975 +vn 0.0059 0.3737 -0.9276 +vn 0.0007 0.9978 -0.0665 +vn -0.0205 0.9185 -0.3949 +vn -0.0195 0.9251 -0.3792 +vn 0.0019 0.9989 -0.0468 +vn -0.0323 0.4173 0.9082 +vn -0.0133 0.2494 0.9683 +vn -0.0144 0.2588 0.9658 +vn -0.0337 0.4295 0.9024 +vn -0.9949 -0.0946 0.0342 +vn -0.9952 -0.0982 0.0016 +vn -0.9964 -0.0293 0.0796 +vn -0.9957 0.0096 0.0924 +vn -0.9950 0.0735 0.0670 +vn -0.9948 0.0926 0.0424 +vn -0.9967 0.0678 -0.0452 +vn -0.9977 0.0581 -0.0347 +vn -0.9934 -0.0164 -0.1137 +vn -0.9947 -0.0546 -0.0868 +vn 0.0593 -0.7664 0.6396 +vn 0.0151 -0.7939 0.6078 +vn 0.0130 -0.7952 0.6062 +vn -0.0334 -0.8208 0.5703 +vn 0.0270 -0.8514 -0.5238 +vn -0.0655 -0.8946 -0.4421 +vn 0.0348 -0.8471 -0.5302 +vn 0.1185 -0.7941 -0.5962 +vn -0.0462 0.2603 -0.9644 +vn -0.0921 0.2198 -0.9712 +vn -0.0325 0.2722 -0.9617 +vn 0.0175 0.3147 -0.9490 +vn 0.0129 0.9930 0.1172 +vn -0.0197 0.9959 0.0883 +vn 0.0207 0.9921 0.1241 +vn 0.0521 0.9871 0.1515 +vn -0.0328 0.2307 0.9725 +vn -0.0695 0.2663 0.9614 +vn -0.0329 0.2308 0.9725 +vn 0.0076 0.1909 0.9816 +vn -0.1238 0.1877 0.9744 +vn 0.0017 0.0561 0.9984 +vn -0.0016 0.0595 0.9982 +vn 0.1239 -0.0740 0.9895 +vn -0.1239 0.7500 -0.6497 +vn 0.0016 0.8366 -0.5478 +vn -0.0017 0.8347 -0.5506 +vn 0.1238 0.8940 -0.4307 +vn 0.8887 0.4119 -0.2012 +vn 0.8104 0.5842 0.0445 +vn 0.9031 0.3452 -0.2555 +vn 0.9986 0.0179 0.0490 +vn 0.9613 0.1942 0.1953 +vn 0.9969 0.0606 0.0505 +vn 0.9467 0.2352 0.2202 +vn 0.9913 0.0571 0.1182 +vn 0.9737 -0.1976 -0.1135 +vn 0.9919 -0.1103 -0.0633 +vn 0.9944 -0.0914 -0.0525 +vn 0.4440 -0.6536 0.6129 +vn 0.4288 -0.6601 0.6167 +vn 0.2249 -0.7266 0.6492 +vn 0.9922 -0.0790 -0.0962 +vn 0.9993 -0.0347 -0.0152 +vn 0.9807 -0.1766 -0.0844 +vn 0.9812 -0.1708 -0.0899 +vn 0.9977 -0.0678 -0.0004 +vn 0.9997 0.0067 -0.0240 +vn 0.9983 -0.0542 0.0219 +vn 0.9876 0.1458 -0.0579 +vn 0.9993 0.0340 -0.0145 +vn 0.9870 0.1469 -0.0656 +vn -0.9898 -0.0127 -0.1418 +vn -0.9971 0.0718 -0.0232 +vn -0.9988 -0.0327 -0.0353 +vn -0.9018 -0.3005 0.3107 +vn -0.9886 -0.1327 0.0708 +vn -0.9799 0.1507 -0.1311 +vn -0.9864 0.1124 -0.1202 +vn -0.9828 0.1587 -0.0943 +vn -0.9721 -0.2285 0.0526 +vn -0.8870 -0.4074 0.2174 +vn -0.8281 -0.3505 0.4374 +vn -0.9104 0.3746 0.1756 +vn -0.9122 0.3672 0.1815 +vn -0.9305 0.2358 0.2804 +vn -0.9993 -0.0161 -0.0324 +vn -0.9996 -0.0125 -0.0252 +vn -0.9884 -0.1426 -0.0519 +vn -0.9891 -0.1309 -0.0669 +vn -0.9997 -0.0206 -0.0133 +vn -0.9998 0.0208 0.0047 +vn -0.9988 0.0283 0.0407 +vn -0.9899 0.1208 -0.0736 +vn -0.9997 0.0254 -0.0063 +vn -0.9813 0.1826 -0.0613 +vn 0.4009 -0.2299 -0.8868 +vn -0.6717 -0.4813 -0.5631 +vn 0.6603 -0.6657 -0.3477 +vn -0.7796 -0.6008 0.1766 +vn 0.7949 -0.4605 0.3951 +vn -0.6995 -0.0301 0.7140 +vn 0.5989 0.2340 0.7659 +vn -0.6340 0.6401 0.4339 +vn 0.7362 0.6597 0.1508 +vn -0.7782 0.5149 -0.3595 +vn 0.8625 0.2596 -0.4345 +vn 0.7697 0.6337 0.0772 +vn 0.7551 0.0606 0.6528 +vn -0.1612 -0.2717 0.9488 +vn 0.0670 -0.9624 0.2634 +vn 0.1974 -0.7328 0.6512 +vn -0.3740 -0.9255 -0.0605 +vn -0.4641 -0.5886 -0.6620 +vn 0.4418 -0.0633 -0.8949 +vn -0.3145 0.0664 -0.9469 +vn 0.1274 0.7095 -0.6931 +vn -0.5596 0.8273 -0.0486 +vn 0.6362 0.6588 0.4016 +vn -0.2383 0.7032 0.6699 +vn -0.8718 0.4829 0.0829 +vn -0.4067 0.1411 0.9026 +vn 0.7830 -0.5831 -0.2165 +vn -0.8682 -0.4377 0.2336 +vn -0.5522 0.5288 -0.6446 +vn 0.5621 -0.4166 -0.7145 +vn -0.4729 -0.8743 0.1097 +vn 0.4573 -0.4377 0.7742 +vn -0.1862 0.4742 0.8605 +vn 0.4574 0.8833 0.1025 +vn 0.3901 0.8608 -0.3269 +vn -0.5460 0.2766 -0.7908 +vn 0.1436 -0.6370 -0.7574 +vn -0.5332 -0.8460 -0.0032 +vn 0.5416 -0.2508 0.8024 +vn -0.5149 0.4753 0.7134 +vn -0.0293 0.0345 -0.9990 +vn -0.0191 0.0439 -0.9989 +vn -0.0064 0.0413 -0.9991 +vn 0.0116 -0.0438 -0.9990 +vn 0.0296 -0.0461 -0.9985 +vn 0.0290 -0.0487 -0.9984 +vn -0.0011 -0.0419 -0.9991 +vn -0.0154 -0.0252 -0.9996 +vn -0.0160 -0.0216 -0.9996 +vn 0.0110 0.0394 -0.9992 +vn 0.0171 0.0290 -0.9994 +vn 0.0172 0.0273 -0.9995 +vn -0.0104 -0.0499 0.9987 +vn 0.0254 -0.0024 0.9997 +vn -0.0369 -0.0559 0.9978 +vn 0.0058 0.0093 0.9999 +vn -0.0749 0.0989 0.9923 +vn 0.5730 -0.8189 -0.0334 +vn -0.0966 -0.9943 0.0456 +vn -0.8390 -0.5427 -0.0404 +vn -0.9349 -0.3549 -0.0046 +vn -0.8489 -0.5272 -0.0373 +vn -0.9463 -0.3234 0.0012 +vn -0.9234 0.3820 0.0369 +vn -0.4821 0.8755 -0.0322 +vn -0.2589 0.9659 0.0056 +vn -0.4628 0.8860 -0.0288 +vn -0.2190 0.9756 0.0121 +vn 0.8725 0.4881 -0.0244 +vn 0.5738 0.8183 0.0337 +vn 0.6249 0.7803 0.0256 +vn 0.8920 0.4511 -0.0297 +vn 0.9578 -0.2835 0.0476 +vn 0.0691 -0.0162 0.9975 +vn 0.0518 -0.0505 0.9974 +vn 0.0729 0.0090 0.9973 +vn -0.0097 -0.0741 0.9972 +vn -0.0176 -0.0867 0.9961 +vn 0.0287 0.0887 0.9956 +vn -0.0263 0.0672 0.9974 +vn -0.0712 0.0205 0.9973 +vn -0.0875 0.0228 0.9959 +vn 0.0591 0.0568 0.9966 +vn -0.0632 -0.0360 0.9974 +vn 0.9805 0.1863 -0.0633 +vn 0.9604 0.2780 -0.0185 +vn 0.9359 0.3519 0.0190 +vn 0.8988 0.4340 0.0620 +vn 0.5288 0.8469 -0.0566 +vn 0.2014 0.9791 -0.0265 +vn 0.3282 0.9437 0.0416 +vn 0.0858 0.9957 0.0347 +vn -0.1630 0.9837 -0.0763 +vn -0.7471 0.6612 0.0683 +vn -0.8128 0.5825 0.0005 +vn -0.7968 0.6039 0.0182 +vn -0.8557 0.5148 -0.0526 +vn -0.9876 -0.1531 0.0361 +vn -0.9576 -0.2864 -0.0307 +vn -0.9730 -0.2308 -0.0026 +vn -0.9331 -0.3535 -0.0654 +vn -0.6256 -0.7773 0.0662 +vn -0.4857 -0.8739 -0.0198 +vn -0.5443 -0.8387 0.0149 +vn -0.3877 -0.9188 -0.0740 +vn 0.3278 -0.9425 0.0652 +vn 0.3889 -0.9211 0.0210 +vn 0.3708 -0.9281 0.0342 +vn 0.4362 -0.8997 -0.0147 +vn 0.9417 -0.3361 0.0149 +vn 0.9326 -0.3609 0.0014 +vn 0.9375 -0.3480 0.0084 +vn 0.9452 -0.3259 0.0203 +vn 0.5103 -0.8513 -0.1218 +vn 0.3592 -0.9138 -0.1896 +vn 0.3021 -0.9293 -0.2125 +vn 0.4444 0.8894 0.1072 +vn 0.7116 0.5767 -0.4013 +vn -0.4059 0.7154 -0.5687 +vn -0.9266 0.3550 -0.1237 +vn -0.4773 -0.8572 0.1934 +vn 0.1512 -0.9517 -0.2671 +vn -0.1143 -0.2373 0.9647 +vn -0.0442 -0.9990 0.0062 +vn -0.0419 -0.9987 0.0275 +vn -0.0484 -0.9986 0.0205 +vn 0.0361 -0.9993 -0.0104 +vn 0.0403 -0.9992 0.0060 +vn 0.0213 -0.9996 0.0170 +vn -0.0351 -0.9993 -0.0113 +vn -0.0114 -0.9993 -0.0350 +vn -0.0183 -0.9993 -0.0326 +vn 0.0238 -0.9992 -0.0311 +vn 0.0171 -0.9997 0.0175 +vn 0.0189 0.9997 -0.0140 +vn -0.0158 0.9995 -0.0269 +vn 0.0080 0.9994 -0.0328 +vn 0.0079 0.9999 -0.0101 +vn 0.0779 0.9968 0.0187 +vn -0.9612 0.0576 -0.2697 +vn -0.4588 -0.0296 -0.8881 +vn 0.5208 0.0005 -0.8537 +vn 0.1733 0.0349 -0.9842 +vn 0.2105 0.0316 -0.9771 +vn 0.5587 -0.0038 -0.8294 +vn 0.9977 -0.0119 0.0660 +vn 0.9630 0.0322 -0.2676 +vn 0.9735 0.0268 -0.2271 +vn 0.9943 -0.0170 0.1050 +vn 0.2088 -0.0108 0.9779 +vn 0.5306 0.0360 0.8469 +vn 0.4890 0.0296 0.8718 +vn 0.1670 -0.0165 0.9858 +vn -0.5574 0.0337 0.8296 +vn -0.9286 -0.0262 0.3702 +vn -0.0771 0.9965 -0.0317 +vn -0.0974 0.9947 -0.0340 +vn -0.0610 0.9975 0.0354 +vn -0.0332 0.9973 0.0650 +vn -0.0229 0.9974 -0.0686 +vn 0.0601 0.9967 0.0544 +vn 0.0385 0.9968 0.0695 +vn 0.0667 0.9978 -0.0013 +vn 0.0648 0.9971 -0.0402 +vn -0.0085 0.9973 0.0734 +vn 0.0094 0.9974 -0.0721 +vn 0.0392 0.9971 -0.0653 +vn -0.5720 0.0074 0.8202 +vn -0.6030 -0.0191 0.7975 +vn -0.5828 -0.0017 0.8126 +vn -0.5522 0.0238 0.8334 +vn 0.1956 -0.0143 0.9806 +vn 0.2235 -0.0332 0.9741 +vn 0.2136 -0.0265 0.9766 +vn 0.2388 -0.0436 0.9701 +vn 0.8577 0.0540 0.5113 +vn 0.8779 0.0248 0.4782 +vn 0.8717 0.0342 0.4889 +vn 0.8930 0.0008 0.4501 +vn 0.9305 -0.0699 -0.3596 +vn 0.8971 -0.0023 -0.4418 +vn 0.8869 0.0147 -0.4617 +vn 0.8412 0.0802 -0.5347 +vn 0.1160 -0.0315 -0.9927 +vn 0.1148 -0.0325 -0.9929 +vn 0.1151 -0.0323 -0.9928 +vn 0.1140 -0.0332 -0.9929 +vn -0.7189 0.0236 -0.6947 +vn -0.7520 -0.0096 -0.6591 +vn -0.7424 0.0003 -0.6700 +vn -0.7729 -0.0320 -0.6337 +vn -0.9968 0.0451 0.0659 +vn -0.9921 0.0066 0.1251 +vn -0.9946 0.0217 0.1019 +vn -0.9862 -0.0193 0.1646 +vn -0.4443 -0.1642 0.8807 +vn -0.4256 -0.1439 0.8934 +vn -0.4227 -0.1408 0.8953 +vn -0.4070 -0.1238 0.9050 +vn 0.8678 0.1496 0.4738 +vn 0.9507 -0.2270 -0.2113 +vn 0.9427 -0.2081 -0.2608 +vn 0.9587 -0.2672 -0.0973 +vn 0.9102 -0.1576 -0.3831 +vn -0.8320 0.1135 -0.5431 +vn -0.5477 -0.3509 -0.7596 +vn -0.8307 0.4181 -0.3676 +vn -0.8248 0.4426 -0.3518 +vn -0.8346 0.3998 -0.3790 +vn -0.8648 -0.0777 0.4961 +vn -0.6474 -0.6385 -0.4161 +vn -0.0294 -0.9173 0.3970 +vn 0.4834 -0.8111 -0.3293 +vn 0.8302 -0.4895 0.2667 +vn 0.8926 0.1974 -0.4052 +vn 0.6817 0.5913 0.4309 +vn 0.7093 0.5101 0.4866 +vn 0.7206 0.4658 0.5135 +vn 0.9459 -0.3064 -0.1070 +vn 0.7386 0.3628 0.5681 +vn -0.7116 -0.7022 0.0211 +vn -0.7224 -0.6853 0.0923 +vn -0.7286 -0.5960 0.3375 +vn -0.7245 -0.5759 0.3788 +vn -0.8394 0.3209 -0.4387 +vn -0.5237 0.5839 0.6203 +vn -0.0258 0.8103 -0.5855 +vn 0.5282 0.6527 0.5432 +vn 0.8041 0.1776 -0.5674 +vn 0.9442 -0.1467 0.2948 +vn 0.4835 -0.8744 -0.0404 +vn -0.8189 0.4642 -0.3375 +vn -0.0666 -0.3161 -0.9464 +vn -0.0347 -0.1645 -0.9858 +vn -0.0267 -0.1266 -0.9916 +vn -0.0029 -0.1878 0.9822 +vn -0.0046 -0.2943 0.9557 +vn -0.0011 -0.0707 0.9975 +vn -0.1334 -0.9911 0.0020 +vn 0.9213 -0.3883 -0.0180 +vn 0.9148 -0.4003 -0.0543 +vn 0.9317 -0.3559 0.0724 +vn 0.9333 -0.3431 0.1058 +vn 0.6161 0.7843 -0.0721 +vn 0.6241 0.7742 -0.1055 +vn 0.5905 0.8068 0.0184 +vn 0.5787 0.8137 0.0547 +vn -0.7034 0.7107 -0.0081 +vn -0.7186 0.6909 -0.0789 +vn -0.7390 0.6210 -0.2612 +vn -0.7396 0.5967 -0.3113 +vn -0.8883 -0.3910 0.2409 +vn -0.6365 0.1856 0.7486 +vn 0.8785 0.4446 -0.1750 +vn 0.9218 -0.3710 0.1126 +vn 0.9229 -0.3463 0.1684 +vn 0.8992 -0.4346 -0.0509 +vn 0.8834 -0.4550 -0.1119 +vn 0.2528 -0.9606 0.1153 +vn 0.2493 -0.9630 0.1025 +vn 0.2640 -0.9517 0.1568 +vn 0.2696 -0.9464 0.1779 +vn -0.5506 -0.7813 -0.2938 +vn -0.7604 -0.5262 0.3807 +vn -0.9514 -0.1985 -0.2355 +vn -0.8800 0.3737 0.2932 +vn -0.6754 0.6393 -0.3676 +vn -0.1715 0.8900 0.4224 +vn 0.1961 0.9379 -0.2863 +vn 0.7493 -0.1673 0.6408 +vn 0.1108 -0.5462 -0.8303 +vn 0.0258 0.0668 -0.9974 +vn -0.0143 0.0905 -0.9958 +vn 0.3542 0.1559 -0.9221 +vn 0.2253 0.1586 -0.9613 +vn -0.0128 0.2768 0.9608 +vn -0.0053 0.1136 0.9935 +vn -0.0063 0.1369 0.9906 +vn 0.0241 -0.0474 0.9986 +vn 0.1670 -0.3288 0.9295 +vn 0.1373 -0.2704 0.9529 +vn -0.7962 0.4597 0.3933 +vn -0.8372 0.4869 0.2490 +vn -0.7752 0.3802 0.5045 +vn -0.8730 -0.4814 -0.0785 +vn -0.8750 0.1732 -0.4521 +vn 0.1009 -0.0339 -0.9943 +vn 0.1193 -0.0938 -0.9884 +vn 0.0570 0.1039 -0.9930 +vn 0.0358 0.1686 -0.9850 +vn 0.9181 -0.2634 -0.2963 +vn 0.8469 0.5099 0.1511 +vn 0.7280 -0.2946 0.6191 +vn 0.7047 -0.2712 0.6556 +vn 0.6942 -0.2609 0.6708 +vn 0.6429 0.7285 -0.2363 +vn 0.6669 -0.2351 0.7070 +vn -0.2422 -0.2430 -0.9393 +vn -0.6908 0.3366 -0.6399 +vn -0.8646 -0.1772 -0.4701 +vn -0.9684 0.1768 0.1757 +vn -0.9716 0.0830 0.2214 +vn -0.9264 -0.1757 0.3330 +vn -0.8950 -0.2579 0.3639 +vn -0.4852 0.2835 0.8272 +vn -0.1487 -0.3213 0.9352 +vn 0.2555 0.2833 0.9243 +vn 0.6575 -0.2902 0.6953 +vn 0.8957 0.2714 0.3523 +vn 0.9714 -0.2354 0.0307 +vn 0.7702 0.3633 -0.5242 +vn 0.6309 -0.2469 -0.7356 +vn -0.8479 0.5152 0.1256 +vn -0.8935 0.4475 0.0378 +vn -0.0003 0.4411 -0.8975 +vn 0.0747 0.5121 -0.8557 +vn -0.0765 0.3633 -0.9285 +vn 0.5472 -0.4951 -0.6749 +vn 0.8871 0.4212 -0.1888 +vn 0.9004 -0.3174 0.2975 +vn 0.3258 0.4533 0.8297 +vn -0.0821 -0.4768 0.8752 +vn -0.8665 0.4248 0.2622 +vn -0.9713 -0.2380 0.0047 +vn -0.1365 0.4485 0.8833 +vn -0.7813 -0.3866 0.4901 +vn 0.9865 -0.1473 0.0711 +vn 0.9700 -0.2230 0.0966 +vn 0.9850 0.1684 -0.0367 +vn 0.9682 0.2422 -0.0622 +vn 0.5595 -0.1815 -0.8087 +vn 0.5726 -0.2466 -0.7819 +vn 0.4955 0.0406 -0.8677 +vn 0.4632 0.1259 -0.8772 +vn -0.3430 0.0398 -0.9385 +vn -0.3565 -0.0020 -0.9343 +vn -0.3879 -0.1092 -0.9152 +vn -0.3969 -0.1432 -0.9066 +vn -0.9887 0.0188 -0.1487 +vn -0.9883 0.0737 -0.1334 +vn -0.9725 -0.1360 -0.1889 +vn -0.9576 -0.2026 -0.2049 +vn -0.6651 0.3151 0.6770 +vn -0.3676 -0.5206 0.7706 +vn 0.2411 0.3049 0.9214 +vn 0.1558 0.5825 -0.7978 +vn 0.7030 -0.6612 0.2619 +vn -0.0165 0.2787 -0.9602 +vn -0.0053 0.0906 -0.9959 +vn -0.0025 -0.0087 -1.0000 +vn -0.0062 0.5892 -0.8079 +vn 0.0006 0.3939 -0.9192 +vn 0.0046 -0.9722 0.2340 +vn 0.0187 -0.9288 0.3702 +vn -0.0011 -0.9561 0.2929 +vn -0.0057 -0.7950 0.6066 +vn 0.0182 0.0231 -0.9996 +vn 0.0988 0.1443 -0.9846 +vn 0.0639 0.2239 -0.9725 +vn -0.0079 0.1567 -0.9876 +vn 0.0022 0.2882 -0.9576 +vn 0.0009 0.2791 -0.9603 +vn -0.0008 0.2671 -0.9637 +vn -0.0025 0.2656 -0.9641 +vn -0.0120 0.0842 -0.9964 +vn -0.3875 0.1963 -0.9007 +vn 0.0013 0.2741 -0.9617 +vn -0.0006 0.2708 -0.9626 +vn -0.1927 0.2636 -0.9452 +vn 0.0143 0.0946 0.9954 +vn -0.0231 0.1808 0.9832 +vn -0.0301 0.1292 0.9912 +vn -0.0230 0.0543 0.9983 +vn 0.0194 0.3906 0.9204 +vn 0.0269 0.4324 0.9013 +vn -0.0050 0.5158 0.8567 +vn -0.0072 0.5167 0.8561 +vn -0.0084 -0.8605 -0.5094 +vn -0.0065 -0.8600 -0.5102 +vn 0.0085 -0.9214 -0.3884 +vn 0.0160 -0.9319 -0.3625 +vn -0.0453 -0.9990 -0.0029 +vn 0.0049 -0.9889 -0.1485 +vn 0.0581 -0.9653 0.2546 +vn -0.0381 -0.9122 0.4080 +vn -0.0308 -0.8712 0.4900 +vn 0.0024 -0.8642 0.5031 +vn -0.0212 -0.9569 0.2897 +vn -0.0539 -0.9611 0.2710 +vn -0.0040 -0.9762 0.2167 +vn -0.0012 -0.9720 0.2351 +vn 0.0006 -0.9920 0.1263 +vn -0.0009 -0.9607 0.2776 +vn -0.0171 -0.9977 0.0654 +vn -0.0017 -0.9642 0.2652 +vn -0.0073 -0.9648 0.2628 +vn 0.0014 -0.9818 0.1900 +vn -0.0012 -0.9632 0.2687 +vn 0.0000 -0.9632 0.2687 +vn -0.0023 -0.9633 0.2686 +vn -0.0002 -0.9603 0.2790 +vn -0.0056 0.5057 -0.8627 +vn 0.0400 0.4877 -0.8721 +vn 0.0784 0.4103 -0.9086 +vn -0.0425 0.2167 -0.9753 +vn 0.1046 -0.0017 -0.9945 +vn -0.0160 -0.2888 -0.9573 +vn -0.0471 -0.3266 -0.9440 +vn -0.0105 -0.2124 -0.9771 +vn -0.0207 -0.2799 -0.9598 +vn 0.0022 -0.2518 0.9678 +vn 0.0005 -0.2581 0.9661 +vn 0.0009 -0.1184 0.9930 +vn 0.0001 -0.1215 0.9926 +vn -0.0001 0.1583 0.9874 +vn 0.0002 0.1591 0.9873 +vn -0.0001 0.4442 0.8959 +vn 0.0003 0.4458 0.8951 +vn -0.0009 0.7014 0.7127 +vn 0.0005 0.7053 0.7089 +vn -0.0008 0.8795 0.4760 +vn -0.0011 0.8793 0.4763 +vn -0.0053 0.9801 0.1982 +vn 0.0015 0.9701 0.2426 +vn 0.0059 1.0000 -0.0066 +vn -0.0068 0.9932 -0.1162 +vn 0.0020 0.9807 -0.1957 +vn -0.0037 0.9661 -0.2582 +vn -0.0048 0.9678 -0.2516 +vn -0.0009 -0.0256 -0.9997 +vn -0.1994 -0.3118 -0.9290 +vn -0.0187 -0.2996 -0.9539 +vn -0.0174 -0.5320 -0.8465 +vn -0.0195 -0.6640 -0.7475 +vn 0.0003 -0.7617 -0.6479 +vn -0.0009 -0.8999 -0.4361 +vn -0.0219 -0.9236 -0.3826 +vn -0.0140 -0.9755 -0.2197 +vn -0.0105 -0.9996 -0.0252 +vn -0.0073 0.8614 0.5079 +vn 0.0222 0.8679 0.4962 +vn 0.0310 0.9121 0.4087 +vn -0.0171 0.9550 0.2962 +vn 0.0117 0.9971 0.0752 +vn 0.0102 0.9998 0.0150 +vn 0.0393 0.9967 -0.0711 +vn 0.0552 0.9964 -0.0646 +vn -0.9975 0.0696 -0.0148 +vn -0.9759 0.0276 0.2163 +vn -0.9508 0.0406 0.3070 +vn -0.9966 0.0315 0.0761 +vn -0.9984 0.0086 0.0556 +vn -0.9991 0.0237 0.0353 +vn -0.9996 0.0179 0.0208 +vn -0.9988 0.0059 0.0494 +vn -0.9998 0.0203 0.0065 +vn -0.9992 0.0351 0.0208 +vn -0.9982 0.0531 0.0267 +vn -0.9994 0.0333 0.0136 +vn -0.9987 0.0510 0.0014 +vn -0.9988 0.0189 0.0443 +vn -0.9977 0.0655 0.0184 +vn -0.9988 0.0180 0.0452 +vn -0.9979 0.0617 0.0202 +vn -0.9984 0.0219 0.0513 +vn -0.9983 -0.0068 0.0579 +vn -0.9987 -0.0492 -0.0151 +vn -0.9988 -0.0480 -0.0023 +vn -0.9969 -0.0727 -0.0317 +vn -0.9988 -0.0005 -0.0482 +vn -0.9997 -0.0091 -0.0222 +vn -0.9987 -0.0164 -0.0490 +vn -0.9964 0.0667 -0.0514 +vn -0.9859 0.1468 -0.0801 +vn -0.9933 0.0814 -0.0824 +vn -0.9951 0.0103 -0.0979 +vn -0.9366 0.0606 -0.3452 +vn -0.9919 -0.1238 0.0265 +vn -0.9968 -0.0744 0.0293 +vn -0.9889 -0.1454 0.0321 +vn -0.9968 -0.0266 -0.0759 +vn -0.9988 -0.0298 -0.0380 +vn -0.9927 -0.0885 0.0816 +vn -0.9970 -0.0634 0.0440 +vn -0.9995 -0.0235 -0.0227 +vn -0.9994 -0.0043 -0.0356 +vn -0.9993 -0.0348 -0.0153 +vn -0.9614 -0.2741 0.0230 +vn -0.9230 0.0580 -0.3804 +vn -0.9987 0.0220 -0.0461 +vn -0.9994 -0.0317 0.0133 +vn -0.0012 -0.9998 -0.0191 +vn -0.0122 -0.9997 -0.0202 +vn 0.0018 -0.9998 -0.0210 +vn -0.0005 0.0013 1.0000 +vn -0.0006 0.0007 1.0000 +vn -0.0005 0.0012 1.0000 +vn -0.0006 0.0006 1.0000 +vn 0.6960 -0.1762 0.6960 +vn 0.6694 -0.1046 0.7355 +vn 0.6772 -0.1652 0.7170 +vn 0.6871 -0.0086 0.7265 +vn 0.6775 0.1152 0.7264 +vn 0.6787 0.2000 0.7067 +vn 0.6742 0.3184 0.6663 +vn 0.6733 0.4052 0.6185 +vn 0.6197 0.5457 0.5641 +vn 0.6936 0.6084 0.3858 +vn 0.6968 0.6460 0.3117 +vn 0.6673 0.7298 0.1484 +vn 0.6619 0.7318 0.1624 +vn 0.6806 0.7308 -0.0519 +vn 0.6866 0.7217 -0.0884 +vn 0.6851 0.7066 -0.1770 +vn 0.6947 0.6957 -0.1828 +vn -0.7119 0.0760 0.6982 +vn -0.7800 0.3715 0.5036 +vn -0.7187 -0.0285 0.6948 +vn -0.6741 0.1228 0.7284 +vn -0.7061 0.2578 0.6595 +vn -0.7146 0.3247 0.6196 +vn -0.7059 -0.1211 0.6979 +vn -0.7068 0.4490 0.5466 +vn -0.7072 0.5028 0.4971 +vn -0.7056 0.5962 0.3829 +vn -0.6951 0.6435 0.3205 +vn -0.7106 0.6915 0.1298 +vn -0.7162 0.6707 0.1928 +vn -0.6901 0.7236 -0.0122 +vn -0.7131 0.6865 -0.1421 +vn -0.7015 0.7046 -0.1065 +vn -0.7059 0.6857 -0.1778 +vn -0.7084 0.6822 -0.1811 +vn -0.9067 -0.1835 -0.3797 +vn -0.8613 0.1623 0.4814 +vn -0.8395 0.0585 0.5403 +vn -0.7601 -0.1482 0.6327 +vn -0.7276 -0.2089 0.6534 +vn 0.1047 0.2734 0.9562 +vn 0.4786 -0.3512 0.8047 +vn 0.8842 0.3300 0.3307 +vn 0.8166 -0.5054 -0.2789 +vn -0.5450 -0.1010 0.8324 +vn -0.5329 -0.0453 0.8450 +vn -0.5609 -0.1933 0.8050 +vn -0.5682 -0.2504 0.7839 +vn 0.1950 0.2554 0.9470 +vn 0.7136 -0.3365 0.6145 +vn 0.9070 0.1644 0.3877 +vn 0.8651 -0.0100 -0.5015 +vn -0.9402 0.0121 -0.3403 +vn 0.0008 0.9995 0.0303 +vn 0.0096 0.9990 0.0426 +vn -0.0002 0.9995 0.0316 +vn 0.0734 0.9951 0.0665 +vn 0.0098 0.9990 0.0435 +vn 0.0256 0.9994 0.0250 +vn 0.0104 -0.9998 -0.0165 +vn -0.0287 -0.9993 -0.0245 +vn 0.0284 -0.9993 -0.0253 +vn 0.0045 0.5795 0.8150 +vn 0.0022 0.5562 0.8310 +vn -0.0566 0.4938 0.8677 +vn -0.0004 0.5305 0.8477 +vn -0.5820 0.8131 -0.0134 +vn -0.6941 0.6839 0.2246 +vn -0.5525 0.8333 -0.0209 +vn -0.6478 0.4197 0.6358 +vn 0.0055 0.6692 0.7430 +vn -0.0052 0.4653 0.8852 +vn 0.0051 0.6624 0.7491 +vn -0.0056 0.4575 0.8892 +vn 0.5317 0.6142 0.5832 +vn 0.5617 0.5746 0.5952 +vn 0.6244 0.4791 0.6169 +vn 0.6513 0.4314 0.6243 +vn -0.0053 -0.0161 -0.9999 +vn -0.0241 -0.0172 -0.9996 +vn -0.0069 -0.0178 -0.9998 +vn 0.0568 -0.0295 -0.9979 +vn 0.0078 -0.0194 -0.9998 +vn 0.0020 1.0000 -0.0078 +vn -0.0013 0.9838 -0.1794 +vn 0.0017 1.0000 -0.0016 +vn -0.0013 0.9999 0.0143 +vn 0.8788 -0.1072 0.4649 +vn 0.8050 0.5444 -0.2358 +vn 0.3031 0.9165 0.2611 +vn 0.0045 0.9783 -0.2071 +vn -0.8821 0.4083 0.2349 +vn -0.8888 0.4060 0.2126 +vn -0.9173 0.3893 0.0845 +vn -0.9252 0.3788 0.0224 +vn -0.7923 -0.5745 -0.2052 +vn -0.1322 -0.0894 -0.9872 +vn 0.0017 -0.0231 -0.9997 +vn 0.0042 0.0469 0.9989 +vn 0.0023 -0.0065 1.0000 +vn -0.0013 0.0050 1.0000 +vn 0.0020 0.0537 0.9986 +vn 0.0521 0.0706 0.9961 +vn 0.0028 -0.0115 -0.9999 +vn 0.0447 -0.0183 -0.9988 +vn -0.0196 0.0010 0.9998 +vn -0.8691 0.4516 -0.2019 +vn -0.9023 -0.2383 0.3593 +vn 0.8970 -0.3869 0.2137 +vn 0.7627 0.5539 -0.3339 +vn 0.5065 0.7910 0.3433 +vn -0.0900 0.9613 -0.2603 +vn -0.6269 0.7360 0.2556 +vn -0.0002 0.8109 0.5852 +vn -0.0623 0.8723 0.4849 +vn 0.0023 0.7995 0.6007 +vn -0.0379 0.9976 -0.0579 +vn 0.0021 0.2909 -0.9567 +vn 0.0011 -0.8346 0.5508 +vn -0.0018 0.8922 -0.4517 +vn -0.0440 0.8626 0.5039 +vn -0.0999 0.8957 0.4333 +vn -0.8857 -0.0132 0.4642 +vn -0.7983 0.0175 0.6020 +vn -0.5220 0.4856 0.7012 +vn -0.2576 0.5988 0.7583 +vn -0.5323 0.4893 0.6908 +vn -0.2507 0.5894 0.7679 +vn 0.0072 0.8876 0.4605 +vn 0.0068 0.8822 0.4708 +vn 0.6543 0.6577 0.3733 +vn 0.6654 0.6587 0.3512 +vn 0.6701 0.6590 0.3415 +vn 0.6492 0.6571 0.3831 +vn -0.0259 0.0181 -0.9995 +vn 0.0149 0.0653 -0.9978 +vn -0.0018 -0.7412 -0.6713 +vn -0.0082 -0.7478 -0.6639 +vn -0.0048 -0.7443 -0.6679 +vn 0.0016 -0.7375 -0.6753 +vn 0.0034 -0.9971 0.0762 +vn -0.0076 -0.9980 0.0631 +vn -0.0052 -0.9978 0.0660 +vn -0.0161 -0.9985 0.0530 +vn 0.9998 0.0190 0.0052 +vn 0.9990 0.0337 0.0297 +vn 1.0000 -0.0018 0.0032 +vn 0.9992 -0.0160 -0.0378 +vn 0.9985 -0.0108 -0.0530 +vn 0.9999 -0.0083 -0.0130 +vn 0.9995 -0.0262 -0.0182 +vn 0.9999 0.0143 0.0039 +vn 1.0000 -0.0065 0.0008 +vn 0.9999 -0.0110 -0.0007 +vn 1.0000 -0.0095 -0.0019 +vn 0.9999 -0.0034 -0.0096 +vn 0.9996 -0.0009 -0.0294 +vn 0.9998 0.0145 -0.0106 +vn 0.9999 0.0140 0.0035 +vn 0.9996 0.0266 -0.0024 +vn 1.0000 0.0005 0.0085 +vn 0.9999 -0.0123 0.0028 +vn 1.0000 -0.0084 0.0041 +vn 0.9997 -0.0191 0.0130 +vn 0.9989 0.0248 -0.0403 +vn 0.9997 -0.0134 0.0198 +vn 0.9995 -0.0265 -0.0168 +vn 0.9997 -0.0215 0.0107 +vn 0.9971 0.0190 -0.0730 +vn 0.9998 -0.0168 -0.0044 +vn 0.0099 -0.9972 -0.0737 +vn 0.0056 -0.9969 -0.0789 +vn 0.0066 -0.9969 -0.0778 +vn 0.0022 -0.9965 -0.0830 +vn -0.0035 -0.7411 0.6713 +vn -0.0111 -0.7332 0.6800 +vn -0.0071 -0.7374 0.6754 +vn 0.0006 -0.7454 0.6666 +vn -0.0250 0.0356 0.9991 +vn -0.0270 0.0312 0.9991 +vn 0.0023 -0.1445 0.9895 +vn -0.0013 -0.0577 0.9983 +vn 0.0057 -0.0494 0.9988 +vn 0.0046 -0.0506 0.9987 +vn 0.0118 -0.0420 0.9990 +vn 0.0127 0.7711 0.6366 +vn -0.0357 0.7119 0.7013 +vn -0.0113 0.7427 0.6695 +vn -0.0586 0.6811 0.7298 +vn -0.0077 0.9983 -0.0577 +vn -0.0030 0.9980 -0.0634 +vn -0.0039 0.9981 -0.0623 +vn 0.0007 0.9977 -0.0679 +vn -0.0043 0.9794 -0.2017 +vn -0.0356 0.9993 -0.0144 +vn -0.0457 0.9984 -0.0340 +vn 0.0377 0.6195 -0.7841 +vn 0.0580 0.6478 -0.7596 +vn 0.0495 0.6362 -0.7700 +vn 0.0277 0.6051 -0.7957 +vn -0.0053 -0.0853 -0.9963 +vn -0.0180 -0.0700 -0.9974 +vn -0.0155 -0.0729 -0.9972 +vn -0.0276 -0.0582 -0.9979 +vn 0.0332 0.0490 0.9982 +vn -0.0587 0.1217 0.9908 +vn 0.0542 0.0322 0.9980 +vn 0.1282 -0.0273 0.9914 +vn -0.1256 -0.9919 -0.0188 +vn 0.3388 -0.6973 -0.6317 +vn -0.1442 -0.2209 -0.9646 +vn 0.0990 0.9453 -0.3107 +vn 0.0737 0.9416 -0.3286 +vn 0.1102 0.9467 -0.3027 +vn 0.1393 0.9494 -0.2815 +vn 0.0225 -0.1424 -0.9895 +vn -0.0886 -0.3140 -0.9453 +vn -0.0198 -0.2087 -0.9778 +vn 0.0855 -0.0416 -0.9955 +vn 0.0433 0.9730 0.2268 +vn -0.1139 0.9933 -0.0181 +vn -0.0031 0.9877 0.1561 +vn 0.1567 0.9052 0.3950 +vn -0.0509 -0.7444 0.6657 +vn 0.1164 -0.8592 0.4982 +vn -0.0236 -0.7669 0.6413 +vn -0.1870 -0.6103 0.7698 +vn -0.9339 -0.3324 0.1317 +vn -0.8704 -0.4720 0.1400 +vn -0.6547 -0.7279 0.2038 +vn -0.7325 -0.6676 0.1331 +vn -0.5812 -0.7964 0.1672 +vn -0.5749 -0.7863 0.2264 +vn -0.5412 -0.1129 -0.8333 +vn -0.5262 -0.0522 -0.8488 +vn -0.6099 -0.6374 -0.4709 +vn -0.6959 -0.4936 -0.5216 +vn -0.6033 -0.7299 -0.3213 +vn -0.6137 -0.7076 -0.3502 +vn -0.6016 -0.7712 -0.2082 +vn -0.7993 -0.6006 -0.0219 +vn -0.5981 -0.4517 -0.6620 +vn -0.8873 -0.1167 -0.4461 +vn -0.5696 -0.4531 -0.6857 +vn -0.5471 -0.0659 -0.8345 +vn -0.8838 0.1192 -0.4524 +vn -0.7393 0.3010 -0.6024 +vn -0.8463 0.1424 -0.5134 +vn -0.5921 0.2238 -0.7742 +vn -0.0208 -0.2619 0.9649 +vn 0.0422 -0.6763 0.7354 +vn 0.0365 0.7222 -0.6907 +vn -0.0211 0.9550 -0.2958 +vn -0.7996 0.1643 -0.5776 +vn -0.9386 0.3387 -0.0656 +vn -0.9450 0.2963 -0.1384 +vn 0.0306 -0.9995 -0.0098 +vn 0.0399 -0.9990 0.0219 +vn 0.0230 -0.9994 0.0255 +vn 0.0147 -0.9989 -0.0441 +vn 0.0066 -0.9995 -0.0318 +vn -0.0185 -0.9994 -0.0305 +vn 0.0052 -0.9993 0.0383 +vn -0.0322 -0.9995 0.0041 +vn -0.0213 -0.9995 0.0223 +vn -0.0299 -0.9994 -0.0174 +vn 0.0149 0.9998 -0.0131 +vn -0.0073 0.9974 -0.0720 +vn 0.0186 0.9996 -0.0229 +vn 0.0287 0.9996 0.0007 +vn 0.0340 0.9992 -0.0195 +vn 0.4092 -0.0015 0.9125 +vn 0.4742 0.0112 0.8803 +vn 0.4650 0.0094 0.8853 +vn 0.4010 -0.0031 0.9161 +vn -0.7841 0.0114 0.6206 +vn -0.7460 0.0233 0.6656 +vn -0.7520 0.0215 0.6588 +vn -0.7897 0.0095 0.6134 +vn -0.7585 0.0120 -0.6516 +vn -0.7600 0.0125 -0.6498 +vn -0.7598 0.0124 -0.6500 +vn -0.7583 0.0120 -0.6519 +vn 0.2045 0.0028 -0.9789 +vn 0.2737 0.0135 -0.9617 +vn 0.2118 0.0039 -0.9773 +vn 0.2813 0.0147 -0.9595 +vn 0.9850 0.0052 -0.1725 +vn 0.9818 0.0085 -0.1895 +vn 0.9823 0.0080 -0.1871 +vn 0.9854 0.0047 -0.1703 +vn -0.0223 0.9973 0.0698 +vn 0.0124 0.9975 0.0696 +vn 0.0660 0.9965 0.0504 +vn 0.0704 0.9975 0.0102 +vn -0.0525 0.9973 0.0507 +vn 0.0615 0.9970 -0.0469 +vn 0.0345 0.9974 -0.0634 +vn -0.0142 0.9970 -0.0765 +vn -0.0418 0.9975 -0.0567 +vn -0.0795 0.9968 -0.0063 +vn -0.0935 0.9956 0.0040 +vn 0.6808 0.0981 0.7259 +vn 0.6511 0.0660 0.7561 +vn 0.6426 0.0571 0.7641 +vn 0.9872 -0.1077 0.1176 +vn 0.8945 0.1403 -0.4246 +vn 0.8113 0.0286 -0.5839 +vn 0.8317 0.0521 -0.5528 +vn 0.7001 -0.0776 -0.7099 +vn -0.0683 0.0630 -0.9957 +vn -0.0707 0.0611 -0.9956 +vn -0.0700 0.0617 -0.9956 +vn -0.0729 0.0593 -0.9956 +vn -0.8581 0.0338 -0.5124 +vn -0.7112 -0.0775 -0.6988 +vn -0.8075 -0.0096 -0.5897 +vn -0.9126 0.0924 -0.3984 +vn -0.9613 -0.0133 0.2752 +vn -0.9869 -0.0977 0.1282 +vn -0.9743 -0.0453 0.2205 +vn -0.9208 0.0541 0.3864 +vn -0.3564 0.0016 0.9343 +vn -0.3285 -0.0243 0.9442 +vn -0.3331 -0.0201 0.9427 +vn -0.3069 -0.0440 0.9507 +vn 0.6009 0.0155 0.7992 +vn 0.7018 0.1239 0.7016 +vn 0.7131 0.1409 0.6868 +vn 0.7152 0.1441 0.6840 +vn 0.7282 0.1645 0.6654 +vn 0.2517 0.2295 -0.9402 +vn 0.6468 -0.1048 -0.7554 +vn -0.7296 -0.1524 -0.6667 +vn -0.9307 0.2672 0.2496 +vn -0.6431 -0.1495 0.7510 +vn -0.0307 -0.0275 -0.9991 +vn -0.0220 -0.0424 -0.9989 +vn -0.0334 -0.0313 -0.9990 +vn 0.0328 0.0345 -0.9989 +vn 0.0288 -0.0001 -0.9996 +vn 0.0243 0.0310 -0.9992 +vn -0.0313 -0.0076 -0.9995 +vn 0.0113 0.0491 -0.9987 +vn 0.0145 0.0505 -0.9986 +vn -0.0282 -0.0033 -0.9996 +vn 0.0280 -0.0093 -0.9996 +vn 0.0345 -0.0139 -0.9993 +vn -0.0028 -0.0143 0.9999 +vn -0.0556 -0.0131 0.9984 +vn -0.0129 -0.0202 0.9997 +vn 0.0104 -0.0163 0.9998 +vn 0.0239 -0.0080 0.9997 +vn -0.9521 -0.3031 0.0392 +vn -0.8962 0.4437 0.0078 +vn -0.8009 0.5980 -0.0297 +vn -0.8171 0.5761 -0.0241 +vn -0.9037 0.4279 0.0114 +vn 0.0383 0.9986 0.0360 +vn 0.1681 0.9857 0.0101 +vn 0.1543 0.9879 0.0129 +vn 0.0205 0.9990 0.0395 +vn 0.8532 0.5212 -0.0190 +vn 0.9917 -0.1149 0.0570 +vn 0.7524 -0.6582 -0.0257 +vn -0.4427 -0.8966 -0.0138 +vn -0.1121 -0.9930 0.0378 +vn -0.1650 -0.9858 0.0300 +vn -0.4854 -0.8740 -0.0210 +vn -0.0787 -0.0249 0.9966 +vn -0.1003 -0.0143 0.9949 +vn -0.0366 -0.0620 0.9974 +vn 0.0142 -0.0675 0.9976 +vn -0.0553 0.0442 0.9975 +vn 0.0754 -0.0042 0.9971 +vn 0.0783 0.0196 0.9967 +vn 0.0441 0.0553 0.9975 +vn 0.0312 0.0609 0.9977 +vn 0.0564 -0.0430 0.9975 +vn 0.0115 -0.0791 0.9968 +vn -0.0314 0.0640 0.9975 +vn -0.0046 0.0756 0.9971 +vn -0.1817 -0.9830 -0.0263 +vn -0.1676 -0.9857 -0.0165 +vn -0.1759 -0.9841 -0.0223 +vn -0.1910 -0.9811 -0.0327 +vn 0.4964 -0.8679 0.0195 +vn 0.5031 -0.8641 0.0149 +vn 0.4998 -0.8660 0.0171 +vn 0.5071 -0.8618 0.0121 +vn 0.9754 -0.2203 0.0067 +vn 0.9579 -0.2848 -0.0351 +vn 0.9693 -0.2458 -0.0097 +vn 0.9831 -0.1805 0.0322 +vn 0.8628 0.5054 -0.0120 +vn 0.8772 0.4801 0.0079 +vn 0.8707 0.4919 -0.0013 +vn 0.8846 0.4659 0.0189 +vn 0.4130 0.9100 -0.0362 +vn 0.3623 0.9320 -0.0084 +vn 0.3129 0.9496 0.0180 +vn 0.2621 0.9640 0.0445 +vn -0.3935 0.9192 0.0119 +vn -0.3119 0.9497 -0.0284 +vn -0.3566 0.9342 -0.0066 +vn -0.4320 0.9013 0.0314 +vn -0.9412 0.3378 0.0026 +vn -0.8679 0.4875 -0.0955 +vn -0.9201 0.3905 -0.0310 +vn -0.9713 0.2274 0.0702 +vn -0.8595 -0.5111 -0.0103 +vn -0.8864 -0.4605 -0.0471 +vn -0.8692 -0.4939 -0.0230 +vn -0.8373 -0.5466 0.0166 +vn -0.8141 -0.5612 -0.1495 +vn -0.2604 -0.8123 -0.5219 +vn 0.5335 -0.8297 0.1643 +vn 0.9248 0.3804 0.0029 +vn 0.9688 0.2125 0.1280 +vn 0.9252 0.3795 0.0037 +vn 0.8141 0.5612 -0.1495 +vn 0.4990 0.5787 -0.6451 +vn -0.5335 0.8297 0.1643 +vn -0.9550 0.0402 0.2938 +vn 0.8208 0.5021 -0.2724 +vn 0.9842 0.1757 -0.0237 +vn 0.8788 0.4369 -0.1918 +vn 0.9988 0.0275 -0.0403 +vn 0.9982 0.0553 -0.0246 +vn 0.9992 0.0324 -0.0247 +vn 0.9992 0.0245 -0.0323 +vn 0.9988 0.0363 0.0316 +vn 0.9989 0.0283 0.0371 +vn 0.9988 0.0350 0.0341 +vn 0.9987 0.0387 0.0341 +vn 0.9987 0.0409 0.0302 +vn 0.6238 -0.1725 0.7623 +vn 0.3723 -0.5168 -0.7709 +vn -0.3677 -0.6491 0.6660 +vn -0.5734 -0.5476 0.6093 +vn -0.2150 -0.6977 0.6834 +vn 0.7250 -0.6177 0.3048 +vn 0.7249 -0.6177 0.3048 +vn 0.7238 -0.6188 0.3052 +vn 0.7233 -0.6194 0.3054 +vn -0.3088 -0.1709 -0.9356 +vn 0.7582 -0.6465 -0.0844 +vn 0.6536 -0.7522 -0.0841 +vn 0.7233 -0.6854 -0.0845 +vn -0.4814 -0.7931 -0.3731 +vn 0.2577 0.3109 -0.9148 +vn 0.1688 0.1671 -0.9714 +vn 0.0696 0.0440 -0.9966 +vn -0.1463 -0.5012 -0.8529 +vn 0.6900 0.3411 -0.6384 +vn 0.2396 0.7835 -0.5733 +vn 0.3193 0.8651 -0.3869 +vn 0.2886 0.8368 -0.4653 +vn 0.5928 0.7542 0.2825 +vn -0.1033 0.7707 0.6288 +vn 0.0148 0.7811 0.6242 +vn -0.1392 0.7653 0.6285 +vn -0.5061 0.6499 -0.5670 +vn 0.7010 0.4176 0.5781 +vn 0.6980 0.3383 -0.6312 +vn -0.4064 -0.1077 0.9073 +vn -0.2596 -0.4565 0.8510 +vn 0.5249 -0.4626 0.7144 +vn 0.5859 -0.2495 -0.7710 +vn 0.5783 -0.6727 -0.4615 +vn -0.1976 -0.7290 -0.6554 +vn -0.2291 -0.7282 -0.6459 +vn -0.1928 -0.7032 0.6844 +vn 0.8296 0.0751 -0.5532 +vn 0.6500 -0.7553 -0.0841 +vn -0.5383 0.6391 -0.5493 +vn 0.3582 0.8933 -0.2715 +vn 0.5347 0.8451 -0.0016 +vn -0.2930 0.9217 0.2543 +vn 0.0195 0.7813 0.6239 +vn 0.6945 0.1606 0.7014 +vn 0.9269 0.0995 0.3619 +vn 0.9319 0.0774 0.3544 +vn -0.5315 -0.8357 0.1382 +vn -0.9988 -0.0298 -0.0392 +vn -1.0000 0.0017 0.0005 +vn -0.9999 -0.0052 -0.0116 +vn -1.0000 0.0017 0.0018 +vn -1.0000 0.0033 0.0032 +vn -1.0000 0.0036 0.0026 +vn -0.9999 0.0092 -0.0118 +vn -0.9999 0.0132 -0.0089 +vn -0.9999 -0.0079 0.0141 +vn -0.9998 -0.0143 0.0155 +vn -0.9996 -0.0274 0.0047 +vn -1.0000 0.0048 0.0021 +vn -0.9996 -0.0030 -0.0276 +vn -1.0000 0.0085 -0.0010 +vn -1.0000 0.0029 0.0063 +vn -1.0000 -0.0010 0.0069 +vn -1.0000 -0.0023 0.0080 +vn -0.9999 0.0112 -0.0056 +vn -1.0000 -0.0011 0.0041 +vn -1.0000 0.0002 -0.0002 +vn 0.9988 -0.0335 0.0370 +vn 0.9996 -0.0194 0.0214 +vn 0.9984 0.0218 -0.0514 +vn 0.9999 0.0162 0.0042 +vn 0.9994 0.0293 -0.0167 +vn 0.9977 -0.0213 0.0644 +vn 0.9948 -0.0152 0.1010 +vn 0.9996 -0.0226 -0.0147 +vn 0.9948 -0.0919 0.0439 +vn 0.9997 -0.0145 0.0177 +vn 0.9999 0.0096 -0.0093 +vn 0.9996 0.0024 0.0271 +vn 0.9997 0.0021 0.0245 +vn 0.9993 0.0053 0.0364 +vn 0.9992 0.0395 -0.0004 +vn 0.9992 0.0395 -0.0038 +vn 0.9997 0.0026 0.0259 +vn 1.0000 -0.0038 0.0005 +vn 0.9998 -0.0208 -0.0029 +vn 0.9456 0.1346 0.2962 +vn 0.9974 0.0480 0.0537 +vn 0.9999 0.0086 0.0112 +vn 0.9989 0.0062 0.0470 +vn -0.3527 0.6806 0.6422 +vn -0.2146 0.5962 0.7736 +vn -0.2248 0.7912 0.5688 +vn 0.2764 -0.8975 0.3436 +vn 0.4785 -0.6744 0.5623 +vn 0.1711 -0.8016 0.5728 +vn -0.4286 -0.6664 0.6101 +vn -0.0373 -0.6652 0.7457 +vn -0.2043 -0.6543 0.7281 +vn -0.4600 0.5031 -0.7316 +vn -0.4528 0.2650 -0.8513 +vn -0.7747 0.1340 -0.6179 +vn -0.1304 -0.9828 0.1308 +vn -0.2701 -0.8226 0.5004 +vn -0.8385 -0.1491 0.5241 +vn -0.9481 0.0111 0.3179 +vn -0.9591 0.0236 0.2822 +vn 0.9137 0.0169 0.4059 +vn 0.6837 0.0698 0.7264 +vn 0.7386 0.0574 0.6717 +vn -0.7549 0.5386 -0.3742 +vn -0.6263 0.6795 -0.3820 +vn -0.6609 0.4896 -0.5688 +vn 0.0565 0.9972 0.0486 +vn 0.0281 0.9985 0.0466 +vn 0.0328 0.9769 0.2110 +vn 0.2101 0.9744 -0.0799 +vn 0.3214 0.9204 0.2227 +vn 0.4375 0.8846 -0.1615 +vn -0.6825 0.7299 0.0372 +vn -0.7006 0.6632 0.2631 +vn -0.6229 0.7707 0.1340 +vn 0.8854 0.1469 -0.4410 +vn 0.6604 0.3253 -0.6768 +vn 0.7626 0.2802 -0.5831 +vn 0.6883 0.5929 0.4180 +vn 0.7852 0.5827 0.2096 +vn 0.6613 0.6968 0.2778 +vn -0.4257 0.8197 -0.3833 +vn -0.3420 0.9156 -0.2113 +vn -0.0875 0.8949 -0.4377 +vn 0.4170 0.8448 -0.3352 +vn 0.2611 0.9579 -0.1192 +vn 0.6703 0.7097 -0.2166 +vn -0.1725 -0.8391 0.5159 +vn -0.0015 0.9833 0.1820 +vn 0.2159 0.9456 0.2434 +vn 0.3914 0.9123 0.1201 +vn -0.6353 0.7385 0.2261 +vn -0.4337 0.8841 0.1740 +vn -0.4457 0.8879 -0.1137 +vn 0.6613 0.6968 -0.2778 +vn 0.6773 0.5842 -0.4472 +vn 0.4500 0.7505 -0.4840 +vn 0.4318 0.6592 -0.6156 +vn 0.4401 0.7459 -0.5000 +vn 0.5204 0.7187 -0.4611 +vn 0.3987 0.8428 -0.3616 +vn 0.5684 0.7736 -0.2802 +vn -0.0117 0.3772 -0.9261 +vn 0.1969 0.3377 -0.9204 +vn 0.2097 0.1702 -0.9628 +vn -0.7341 0.4884 0.4718 +vn -0.4257 0.8197 0.3833 +vn -0.5496 0.8216 0.1515 +vn -0.1304 -0.9828 -0.1308 +vn -0.1303 -0.9828 -0.1308 +vn 0.4716 -0.0403 -0.8809 +vn 0.5393 -0.0670 -0.8395 +vn 0.4706 -0.0992 -0.8768 +vn -0.0580 -0.8284 0.5571 +vn 0.0983 0.9859 -0.1356 +vn 0.0466 0.9878 -0.1485 +vn 0.3126 0.9107 -0.2700 +vn 0.4502 0.8650 -0.2215 +vn 0.4905 0.7993 -0.3471 +vn -0.3527 0.6806 -0.6422 +vn -0.3991 0.4388 -0.8051 +vn -0.4803 0.6309 -0.6093 +vn 0.1730 0.9790 -0.1077 +vn 0.0897 0.9947 0.0494 +vn -0.7570 0.6465 -0.0949 +vn -0.7848 0.5980 -0.1628 +vn -0.8207 0.5701 0.0372 +vn 0.3528 0.4414 -0.8250 +vn 0.3444 0.5188 -0.7824 +vn 0.5616 0.4478 -0.6957 +vn 0.6176 -0.2154 0.7564 +vn 0.3719 -0.3443 0.8621 +vn 0.5732 -0.5191 0.6341 +vn -0.1725 -0.8391 -0.5159 +vn 0.0537 0.4112 -0.9100 +vn 0.2528 0.1703 -0.9524 +vn 0.0338 0.0528 -0.9980 +vn -0.9875 0.1577 -0.0042 +vn -0.9527 0.3006 -0.0437 +vn -0.9922 0.1180 -0.0389 +vn -0.5676 0.7301 0.3805 +vn -0.7128 0.6221 0.3239 +vn -0.7779 0.3136 0.5446 +vn 0.9912 -0.1050 -0.0806 +vn 0.9516 0.2899 0.1020 +vn 0.9871 -0.0818 0.1376 +vn 0.1755 -0.9842 0.0213 +vn 0.3852 -0.9197 -0.0759 +vn 0.4185 -0.9075 0.0370 +vn -0.9969 0.0662 0.0425 +vn -0.9855 0.1608 0.0534 +vn -0.1152 0.7926 -0.5987 +vn -0.4000 0.4668 -0.7887 +vn -0.3513 0.5398 -0.7650 +vn 0.6322 0.7633 -0.1331 +vn 0.5136 0.8068 0.2920 +vn 0.7165 0.6956 -0.0526 +vn -0.0753 -0.9886 0.1305 +vn 0.0503 0.1853 -0.9814 +vn -0.0092 0.2828 -0.9591 +vn 0.0539 0.2770 -0.9594 +vn 0.5616 0.4478 0.6957 +vn 0.5341 0.6213 0.5733 +vn 0.3910 0.6651 0.6362 +vn -0.9409 0.2323 -0.2465 +vn -0.7349 0.4222 -0.5307 +vn -0.7615 0.3976 -0.5119 +vn -0.4216 0.6295 -0.6526 +vn -0.2652 0.7669 -0.5844 +vn -0.0999 0.7450 -0.6596 +vn -0.6057 0.5469 0.5780 +vn -0.8202 0.5440 0.1768 +vn -0.8568 0.2790 0.4336 +vn -0.2701 -0.8226 0.5005 +vn -0.2460 -0.6205 -0.7446 +vn -0.2648 -0.5810 -0.7696 +vn 0.0153 -0.7165 -0.6975 +vn -0.2701 -0.8226 -0.5004 +vn 0.2630 -0.5440 -0.7968 +vn -0.2214 -0.1683 0.9606 +vn -0.4277 -0.1615 0.8894 +vn -0.6229 -0.0529 0.7805 +vn 0.0378 0.9913 -0.1263 +vn 0.1508 0.7965 -0.5856 +vn 0.1331 0.7443 -0.6545 +vn 0.1276 0.8220 -0.5550 +vn 0.9626 -0.0564 -0.2649 +vn 0.9893 -0.1416 0.0343 +vn 0.9309 -0.0761 -0.3573 +vn -0.7997 0.5954 -0.0778 +vn -0.5456 0.8354 -0.0665 +vn -0.5580 0.8113 -0.1744 +vn 0.8385 0.5315 -0.1199 +vn 0.8482 0.5241 -0.0769 +vn 0.8702 0.4885 -0.0647 +vn 0.9429 -0.2922 0.1601 +vn 0.9808 -0.1945 -0.0115 +vn -0.9293 -0.0116 0.3692 +vn 0.0378 0.9913 0.1263 +vn -0.2914 0.9559 0.0358 +vn -0.1943 0.9310 0.3089 +vn -0.6919 0.6956 -0.1933 +vn -0.7944 0.6067 0.0293 +vn -0.7287 0.6842 0.0295 +vn 0.2277 0.8115 -0.5381 +vn 0.2415 0.7805 -0.5766 +vn 0.2616 0.7893 -0.5556 +vn 0.3674 -0.1313 0.9207 +vn 0.5459 -0.1263 0.8283 +vn 0.2560 -0.1267 0.9583 +vn 0.6183 0.1149 -0.7775 +vn 0.6394 0.0378 -0.7680 +vn 0.5103 0.5211 -0.6842 +vn 0.7503 0.2437 -0.6145 +vn 0.5694 0.0487 -0.8206 +vn -0.9526 -0.1209 -0.2791 +vn -0.8535 -0.2483 -0.4582 +vn 0.9275 0.3648 -0.0816 +vn 0.9437 0.3289 -0.0355 +vn 0.8765 0.3487 -0.3320 +vn 0.2541 -0.1536 -0.9549 +vn 0.2797 -0.2149 -0.9357 +vn -0.0295 -0.2608 -0.9649 +vn 0.9064 -0.0647 -0.4174 +vn 0.9685 -0.0980 -0.2291 +vn -0.0899 0.9266 0.3651 +vn -0.2583 0.9661 0.0037 +vn -0.5945 0.0701 0.8011 +vn -0.3991 0.4388 0.8051 +vn -0.4803 0.6309 0.6093 +vn 0.8804 0.4672 0.0813 +vn 0.8840 0.4470 0.1370 +vn -0.6609 0.4896 0.5688 +vn -0.5271 0.6425 0.5563 +vn -0.6263 0.6795 0.3820 +vn -0.5809 0.7035 -0.4095 +vn -0.8057 0.5618 -0.1875 +vn -0.5722 0.7722 -0.2763 +vn 0.8358 0.0593 0.5459 +vn 0.9591 -0.2046 0.1958 +vn 0.9546 0.2164 0.2047 +vn 0.2468 0.8206 -0.5154 +vn -0.0634 0.6863 -0.7246 +vn -0.1122 0.7924 -0.5996 +vn 0.1136 0.7537 -0.6473 +vn 0.5027 -0.7665 0.3997 +vn 0.6075 -0.7925 0.0539 +vn 0.6078 -0.7917 0.0613 +vn -0.7285 0.4662 -0.5020 +vn -0.3800 0.5412 -0.7501 +vn -0.6151 0.5036 -0.6067 +vn -0.7170 -0.6678 0.1999 +vn -0.7061 -0.6773 0.2067 +vn -0.7195 -0.5553 0.4170 +vn 0.9736 0.0766 -0.2153 +vn 0.9743 -0.1687 0.1494 +vn 0.9736 0.0765 -0.2153 +vn 0.1778 0.9566 0.2308 +vn 0.1725 0.8391 0.5160 +vn 0.4462 0.8747 0.1889 +vn 0.4393 0.0585 -0.8964 +vn 0.2026 0.2216 -0.9539 +vn 0.4640 0.2483 -0.8503 +vn 0.9293 0.0116 0.3692 +vn 0.1125 -0.5538 0.8250 +vn -0.2933 -0.1691 -0.9409 +vn -0.0502 0.8795 -0.4733 +vn -0.0528 0.8696 -0.4909 +vn -0.1325 0.8667 -0.4810 +vn -0.7479 -0.6296 -0.2106 +vn -0.7189 -0.6674 -0.1942 +vn -0.6453 -0.7615 0.0616 +vn 0.7047 0.3612 0.6106 +vn 0.8924 0.2077 0.4006 +vn 0.7054 0.3722 0.6032 +vn 0.9022 0.3294 0.2783 +vn 0.7804 0.4054 0.4761 +vn 0.1420 -0.5594 -0.8166 +vn 0.4458 -0.5181 -0.7299 +vn 0.3761 -0.5377 -0.7546 +vn 0.2600 -0.5513 -0.7928 +vn -0.2974 0.7063 0.6425 +vn -0.3440 0.5544 0.7578 +vn -0.0485 0.6721 0.7389 +vn 0.2871 0.9523 -0.1031 +vn 0.0433 -0.3896 -0.9200 +vn -0.2214 -0.1683 -0.9606 +vn -0.1962 -0.1188 -0.9733 +vn 0.4145 0.9097 -0.0239 +vn 0.3270 0.9439 -0.0467 +vn 0.9437 0.0111 0.3307 +vn 0.7865 0.2739 0.5535 +vn 0.7310 0.1835 0.6573 +vn -0.9882 -0.0972 0.1180 +vn -0.9293 0.0822 0.3600 +vn -0.9394 0.0889 0.3312 +vn 0.6259 0.5950 -0.5041 +vn 0.2701 0.8226 -0.5005 +vn 0.2701 0.8226 -0.5004 +vn 0.1236 0.9829 0.1363 +vn 0.1107 0.9841 0.1392 +vn 0.1290 0.9566 0.2612 +vn -0.6357 0.7090 -0.3053 +vn -0.6207 0.7831 -0.0389 +vn -0.4680 0.8177 -0.3351 +vn -0.2403 0.9267 -0.2890 +vn -0.2098 0.9694 -0.1272 +vn -0.2701 -0.8226 -0.5005 +vn -0.9873 -0.0041 -0.1587 +vn -0.9929 0.0292 -0.1154 +vn -0.9844 0.0710 -0.1610 +vn 0.3518 0.7330 0.5822 +vn 0.4019 0.4884 0.7745 +vn 0.5103 0.5211 0.6842 +vn 0.9440 -0.1777 -0.2781 +vn 0.9538 -0.2860 -0.0921 +vn 0.9227 -0.3854 -0.0020 +vn -0.2583 0.9661 -0.0037 +vn -0.1330 0.9547 0.2661 +vn -0.0349 0.9994 0.0032 +vn 0.4340 0.8055 -0.4036 +vn 0.3934 0.9173 -0.0610 +vn 0.5838 0.8118 -0.0130 +vn -0.0378 -0.9913 -0.1263 +vn 0.5360 0.7342 0.4167 +vn 0.1514 0.8806 0.4489 +vn -0.0641 0.2501 -0.9661 +vn -0.0866 0.2221 -0.9712 +vn -0.1279 0.3080 -0.9428 +vn -0.2630 -0.6389 -0.7230 +vn -0.5603 -0.6221 -0.5469 +vn -0.3097 -0.6073 -0.7316 +vn -0.5811 0.7225 -0.3747 +vn -0.7779 0.3136 -0.5446 +vn -0.7128 0.6221 -0.3239 +vn -0.0141 0.8318 -0.5549 +vn 0.0122 0.8540 -0.5202 +vn 0.0330 0.8487 -0.5278 +vn -0.2006 0.8747 0.4412 +vn -0.3041 0.7718 0.5584 +vn -0.1607 0.7767 0.6091 +vn -0.9863 0.0082 -0.1649 +vn -0.9532 0.0437 -0.2993 +vn -0.9849 0.0073 -0.1729 +vn 0.0611 0.4471 -0.8924 +vn 0.1083 0.8779 -0.4665 +vn 0.1203 0.8585 -0.4986 +vn 0.1196 0.8699 -0.4786 +vn 0.6160 -0.1927 0.7638 +vn 0.3933 -0.1537 0.9065 +vn 0.3515 -0.2110 0.9121 +vn 0.4581 0.0753 -0.8857 +vn 0.4282 0.0537 -0.9021 +vn 0.1723 0.0967 -0.9803 +vn 0.7767 0.6073 0.1674 +vn 0.6019 0.7768 0.1855 +vn 0.5251 0.7195 0.4544 +vn 0.9137 0.0169 -0.4060 +vn 0.9137 0.0169 -0.4059 +vn 0.9762 -0.0096 -0.2167 +vn -0.3087 0.5905 -0.7456 +vn 0.0739 0.6689 -0.7397 +vn -0.6241 0.7738 0.1083 +vn -0.6883 0.7178 -0.1044 +vn -0.8316 0.5535 0.0462 +vn -0.1271 0.5192 0.8451 +vn 0.0537 0.4112 0.9100 +vn 0.2562 0.6365 0.7275 +vn -0.3405 -0.3216 0.8835 +vn -0.3826 -0.2240 0.8963 +vn -0.5140 -0.4179 0.7491 +vn 0.3147 -0.9433 -0.1059 +vn 0.1184 -0.8796 -0.4607 +vn 0.3831 -0.8543 -0.3513 +vn -0.3360 0.1653 -0.9272 +vn -0.5355 0.1598 -0.8293 +vn -0.2240 0.1788 -0.9580 +vn 0.4262 -0.8829 0.1973 +vn 0.3321 -0.8054 0.4910 +vn 0.2910 -0.8638 0.4112 +vn 0.7680 0.6236 0.1462 +vn 0.8711 0.4530 0.1898 +vn 0.8228 0.5605 -0.0945 +vn 0.1178 0.9031 0.4129 +vn 0.1210 0.9438 0.3076 +vn -0.0662 0.9708 0.2304 +vn 0.7214 0.1193 0.6822 +vn 0.4892 0.2865 0.8237 +vn 0.6177 0.1789 0.7658 +vn -0.9433 0.3180 -0.0954 +vn -0.8183 0.4995 -0.2844 +vn -0.9492 0.2753 -0.1523 +vn 0.7865 0.2739 -0.5535 +vn 0.7310 0.1835 -0.6573 +vn 0.6445 0.3160 -0.6962 +vn 0.5818 0.3178 0.7487 +vn 0.5968 0.0438 0.8012 +vn 0.8548 0.3013 0.4224 +vn -0.5780 0.7807 -0.2378 +vn -0.3812 0.8205 -0.4261 +vn -0.5886 0.7131 -0.3809 +vn -0.5322 0.8420 -0.0884 +vn -0.3564 0.9004 -0.2496 +vn 0.8939 0.2659 0.3608 +vn 0.8914 0.4446 0.0880 +vn 0.0851 0.4570 -0.8854 +vn 0.2284 0.5497 -0.8035 +vn 0.3399 0.1630 -0.9262 +vn 0.5031 -0.8453 -0.1798 +vn 0.4976 -0.7937 -0.3499 +vn -0.6799 0.3273 -0.6562 +vn -0.5332 0.3748 -0.7585 +vn 0.7783 -0.1881 0.5991 +vn 0.6069 -0.1839 0.7732 +vn 0.3614 -0.1746 0.9159 +vn -0.1303 -0.9828 0.1307 +vn 0.4946 0.8301 -0.2576 +vn 0.7165 0.6956 0.0526 +vn 0.7680 0.6236 -0.1462 +vn 0.0474 0.7198 -0.6926 +vn 0.0525 0.6126 -0.7886 +vn -0.0572 0.5611 -0.8258 +vn -0.3728 0.9033 0.2122 +vn -0.5436 0.8299 0.1257 +vn -0.1043 0.9136 0.3930 +vn 0.0075 0.8062 0.5916 +vn 0.1146 0.9125 0.3926 +vn -0.0264 0.9063 -0.4219 +vn 0.0635 0.9065 -0.4175 +vn 0.0183 0.8884 -0.4588 +vn 0.1250 0.8503 -0.5111 +vn 0.1419 0.8404 -0.5231 +vn -0.0823 -0.6562 -0.7501 +vn 0.9373 -0.1148 0.3290 +vn 0.7845 -0.1330 0.6057 +vn 0.8287 -0.1348 0.5432 +vn -0.6281 -0.7587 -0.1730 +vn -0.2664 -0.9403 -0.2120 +vn 0.0049 0.9846 -0.1749 +vn 0.3849 0.9156 -0.1166 +vn 0.2654 0.7844 -0.5606 +vn -0.0187 0.9987 0.0476 +vn 0.0697 0.9751 0.2106 +vn -0.4680 0.8177 0.3351 +vn 0.0643 0.9640 0.2582 +vn 0.0871 0.9856 0.1450 +vn 0.0744 0.9878 0.1371 +vn 0.6868 0.3470 -0.6387 +vn 0.4964 0.2614 -0.8278 +vn 0.6138 0.4142 -0.6721 +vn -0.0179 0.9901 -0.1390 +vn -0.1069 0.9920 0.0666 +vn -0.1900 0.8682 -0.4584 +vn -0.1607 0.7767 -0.6091 +vn -0.3041 0.7718 -0.5584 +vn 0.2867 -0.4343 -0.8540 +vn 0.1711 -0.8016 -0.5728 +vn 0.2721 -0.4439 -0.8538 +vn 0.5402 -0.4996 0.6772 +vn 0.5900 -0.4393 0.6774 +vn 0.4083 -0.4027 0.8192 +vn 0.2649 0.9141 0.3071 +vn -0.0378 -0.9913 0.1263 +vn 0.0102 0.9909 0.1341 +vn 0.0031 0.9915 0.1297 +vn 0.0146 0.9681 0.2500 +vn 0.7352 0.6343 -0.2389 +vn 0.6167 0.7457 -0.2522 +vn 0.6945 0.6908 -0.2009 +vn 0.6222 -0.2277 0.7490 +vn 0.4878 -0.2779 0.8275 +vn 0.7378 -0.2537 0.6255 +vn -0.5438 0.8344 -0.0891 +vn -0.5322 0.8420 0.0884 +vn -0.4462 0.8829 -0.1464 +vn -0.2811 0.9596 0.0136 +vn -0.0688 0.9270 -0.3687 +vn 0.0753 0.9886 -0.1305 +vn 0.0636 0.8823 -0.4664 +vn 0.2184 -0.2299 -0.9484 +vn 0.1591 -0.2728 -0.9488 +vn -0.0067 -0.2678 -0.9634 +vn -0.7460 -0.5424 0.3863 +vn -0.8176 -0.4694 0.3334 +vn -0.6799 -0.7027 0.2093 +vn 0.0284 0.8946 0.4460 +vn -0.9887 0.1182 -0.0926 +vn 0.7391 0.6735 -0.0118 +vn 0.7154 0.5764 -0.3950 +vn 0.6073 0.6945 -0.3859 +vn 0.2562 0.6365 -0.7275 +vn 0.2933 0.3331 -0.8961 +vn 0.2754 0.4163 -0.8665 +vn 0.2418 0.2544 -0.9364 +vn 0.1875 0.2845 -0.9402 +vn 0.3194 0.9412 0.1098 +vn 0.2746 0.8780 0.3920 +vn 0.4645 0.8359 0.2923 +vn 0.1212 0.8514 -0.5103 +vn 0.1220 0.8958 -0.4273 +vn 0.1063 0.8906 -0.4422 +vn 0.8953 0.2634 -0.3592 +vn 0.8210 0.1497 -0.5510 +vn 0.7997 0.2080 -0.5633 +vn -0.8387 -0.1503 -0.5234 +vn -0.5690 -0.3427 -0.7475 +vn -0.6298 -0.3150 -0.7100 +vn 0.6576 -0.1588 -0.7364 +vn 0.8501 -0.1083 -0.5153 +vn 0.6777 0.6113 -0.4088 +vn 0.9481 0.2339 -0.2155 +vn 0.7273 0.4434 -0.5239 +vn 0.7063 0.7075 0.0231 +vn 0.7852 0.5827 -0.2096 +vn -0.2133 0.9679 -0.1326 +vn 0.0015 0.9869 -0.1613 +vn -0.9255 0.1885 0.3286 +vn -0.7549 0.5386 0.3742 +vn -0.9644 0.2628 -0.0294 +vn -0.1060 0.9236 0.3685 +vn 0.0753 0.9886 0.1305 +vn 0.5492 0.7472 -0.3743 +vn 0.3131 0.7873 -0.5312 +vn -0.1042 -0.3781 0.9199 +vn 0.2229 -0.3266 0.9185 +vn -0.0164 -0.3812 0.9243 +vn 0.9831 0.0139 -0.1827 +vn 0.8168 0.5696 -0.0914 +vn 0.8341 0.5429 0.0978 +vn 0.1724 0.8391 -0.5159 +vn 0.2987 0.5895 -0.7505 +vn 0.1725 0.8391 -0.5159 +vn 0.8533 -0.3372 -0.3977 +vn 0.6176 -0.2154 -0.7564 +vn 0.8547 -0.3218 -0.4073 +vn -0.7728 -0.5995 -0.2083 +vn -0.6946 -0.6932 0.1924 +vn -0.7592 -0.6502 0.0295 +vn -0.2056 -0.9646 0.1653 +vn -0.4595 -0.8880 0.0182 +vn -0.6587 -0.7507 -0.0501 +vn 0.3195 0.9474 0.0210 +vn -0.0341 0.9687 0.2458 +vn -0.9854 0.1260 0.1143 +vn -0.9643 0.2451 0.1005 +vn 0.9408 0.1514 -0.3033 +vn 0.9485 0.1889 -0.2541 +vn 0.9680 0.1886 -0.1654 +vn 0.1464 0.1195 0.9820 +vn 0.9055 0.4210 0.0527 +vn 0.9103 0.4079 0.0709 +vn 0.9371 0.3484 0.0221 +vn 0.2523 -0.1341 0.9583 +vn 0.5450 -0.1497 0.8249 +vn 0.3671 0.6825 -0.6320 +vn 0.1747 0.7161 -0.6758 +vn 0.1959 0.8041 -0.5612 +vn -0.9571 0.2788 0.0786 +vn -0.4751 0.8710 0.1252 +vn -0.5905 0.7249 0.3547 +vn 0.8338 -0.3471 0.4293 +vn -0.7770 0.1832 0.6023 +vn -0.7770 0.1832 0.6022 +vn 0.2933 0.3331 0.8961 +vn -0.0326 0.8764 0.4804 +vn -0.2392 0.9608 0.1402 +vn -0.3368 0.8947 0.2933 +vn 0.5955 0.6397 0.4860 +vn 0.5601 0.7547 0.3416 +vn 0.2701 0.8226 0.5005 +vn 0.6259 0.5950 0.5041 +vn 0.2701 0.8226 0.5004 +vn 0.7770 -0.1832 0.6023 +vn 0.0329 0.9879 0.1517 +vn 0.0222 0.9893 0.1442 +vn 0.5251 0.7195 -0.4544 +vn 0.2788 0.6959 -0.6618 +vn 0.0580 0.8284 -0.5571 +vn 0.8629 -0.4213 -0.2791 +vn 0.4992 -0.5624 -0.6592 +vn 0.6958 -0.2893 -0.6573 +vn 0.4690 0.6890 0.5526 +vn 0.4359 0.7749 0.4577 +vn 0.9437 0.0111 -0.3307 +vn 0.8890 0.3106 -0.3365 +vn -0.8099 0.3754 0.4507 +vn -0.8614 0.0025 0.5080 +vn -0.7196 0.1587 0.6760 +vn 0.0433 -0.3896 0.9200 +vn 0.4701 0.7150 -0.5174 +vn 0.6418 0.5684 -0.5148 +vn -0.0777 0.7520 0.6546 +vn -0.4218 0.6351 0.6471 +vn -0.2261 0.6027 0.7653 +vn 0.6283 0.7756 0.0608 +vn 0.7804 0.6159 0.1079 +vn 0.7767 0.6073 -0.1674 +vn 0.1047 0.8031 -0.5865 +vn 0.5839 0.4283 -0.6896 +vn 0.1304 0.9828 0.1307 +vn 0.1304 0.9828 0.1308 +vn 0.3034 -0.7734 0.5565 +vn 0.5481 -0.7401 0.3897 +vn -0.4219 0.8170 0.3931 +vn 0.3066 0.2214 0.9257 +vn 0.3103 0.6259 0.7155 +vn 0.0121 0.5851 0.8109 +vn -0.5510 0.4087 -0.7276 +vn -0.5363 0.3123 -0.7841 +vn -0.8072 0.2121 -0.5508 +vn -0.0263 0.7629 -0.6460 +vn 0.0137 0.5879 -0.8088 +vn -0.2146 0.5962 -0.7736 +vn 0.3464 0.1694 0.9227 +vn 0.0657 0.1111 0.9916 +vn 0.1848 -0.1392 0.9729 +vn -0.5687 -0.5973 -0.5655 +vn -0.2061 -0.6337 -0.7456 +vn -0.0452 0.1975 -0.9793 +vn 0.1732 0.5937 -0.7858 +vn 0.3021 0.5692 -0.7647 +vn 0.9725 0.2316 0.0250 +vn 0.9666 0.2494 -0.0596 +vn 0.2587 0.1146 -0.9591 +vn 0.2696 0.0526 -0.9615 +vn 0.2153 0.0785 -0.9734 +vn 0.2243 -0.8898 0.3974 +vn 0.9016 -0.1287 -0.4130 +vn 0.8358 -0.0291 -0.5483 +vn -0.0753 -0.9886 -0.1305 +vn 0.3910 0.6651 -0.6362 +vn 0.5341 0.6213 -0.5733 +vn 0.5962 0.6804 0.4262 +vn 0.6888 0.6514 0.3183 +vn 0.3259 0.9343 0.1446 +vn 0.3194 0.0664 -0.9453 +vn 0.3210 0.2722 -0.9071 +vn 0.3625 0.1972 -0.9109 +vn 0.9765 0.1845 -0.1111 +vn -0.1978 -0.5366 0.8203 +vn -0.5504 -0.6417 0.5342 +vn -0.2724 -0.5922 0.7584 +vn -0.1304 -0.9828 -0.1307 +vn 0.2249 0.6206 -0.7512 +vn 0.4692 0.4441 -0.7633 +vn -0.2528 0.1971 -0.9472 +vn -0.5945 0.0701 -0.8011 +vn -0.2993 -0.5844 -0.7542 +vn -0.8316 -0.3417 -0.4378 +vn -0.5504 -0.6417 -0.5342 +vn 0.7440 0.6387 -0.1961 +vn 0.1099 0.8343 -0.5403 +vn 0.1173 0.8461 -0.5200 +vn -0.9776 0.1544 -0.1429 +vn 0.2097 0.1702 0.9628 +vn -0.0117 0.3772 0.9261 +vn -0.0452 0.1975 0.9793 +vn -0.3248 -0.7705 -0.5486 +vn -0.0131 -0.7899 -0.6131 +vn 0.0392 -0.8237 -0.5657 +vn 0.6507 -0.7573 -0.0558 +vn 0.3651 -0.9259 -0.0964 +vn 0.0284 0.8946 -0.4460 +vn 0.3518 0.7330 -0.5822 +vn 0.2170 0.6836 -0.6968 +vn 0.7770 -0.1832 -0.6023 +vn -0.9403 -0.0233 -0.3396 +vn -0.2564 0.5624 0.7861 +vn -0.1039 0.4550 -0.8844 +vn 0.0580 0.8284 0.5571 +vn 0.9373 -0.1148 -0.3290 +vn -0.0580 -0.8284 -0.5571 +vn -0.6070 0.7817 0.1430 +vn -0.6207 0.7831 0.0389 +vn -0.7620 0.6397 -0.1009 +vn -0.7570 0.6465 0.0949 +vn 0.1465 0.1195 0.9820 +vn -0.7664 0.4600 0.4484 +vn -0.8879 0.3695 0.2740 +vn -0.9456 0.3086 0.1030 +vn -0.2172 0.9218 -0.3211 +vn -0.1290 0.9320 -0.3387 +vn -0.3800 0.8342 -0.3996 +vn -0.7503 0.6208 0.2271 +vn -0.8202 0.5440 -0.1768 +vn -0.6695 -0.7185 -0.1886 +vn -0.7227 -0.6908 -0.0247 +vn -0.6884 -0.6909 -0.2208 +vn 0.8087 0.5432 -0.2258 +vn 0.7736 0.6037 -0.1925 +vn 0.7928 0.5810 -0.1841 +vn -0.6710 0.6674 0.3229 +vn -0.5751 0.7709 0.2737 +vn -0.6025 0.7702 0.2093 +vn 0.2140 0.5402 0.8139 +vn 0.4446 0.4788 0.7571 +vn 0.8914 0.4446 -0.0880 +vn -0.9017 0.1730 0.3962 +vn -0.7231 0.1975 0.6619 +vn -0.9741 0.1574 0.1623 +vn 0.9293 0.0116 -0.3692 +vn 0.0338 0.0528 0.9980 +vn -0.2296 -0.0826 0.9698 +vn 0.2684 -0.7800 0.5653 +vn 0.7507 0.2656 -0.6049 +vn 0.7473 0.4445 -0.4939 +vn 0.9022 0.3294 -0.2783 +vn 0.7767 0.4104 -0.4779 +vn -0.7323 0.1371 -0.6670 +vn -0.7814 0.1398 -0.6082 +vn -0.4761 0.1499 -0.8665 +vn -0.0043 0.4571 -0.8894 +vn -0.5200 0.6278 -0.5793 +vn -0.7229 0.2406 -0.6477 +vn 0.9319 -0.3540 -0.0788 +vn 0.4843 0.8151 -0.3181 +vn 0.6418 0.7649 -0.0550 +vn 0.6888 0.6514 -0.3183 +vn -0.2103 0.1364 -0.9681 +vn -0.4046 0.1313 -0.9050 +vn -0.4819 0.1379 -0.8653 +vn 0.3216 0.8950 0.3091 +vn 0.6039 0.7858 0.1337 +vn 0.3397 0.9343 0.1085 +vn -0.7085 -0.4227 0.5651 +vn -0.6735 -0.4710 0.5697 +vn -0.8130 0.0827 -0.5763 +vn 0.4348 0.1089 -0.8939 +vn 0.3646 0.1016 -0.9256 +vn 0.1458 0.1185 0.9822 +vn -0.2525 0.1455 0.9566 +vn 0.8260 0.3092 -0.4713 +vn 0.6941 0.2235 -0.6843 +vn -0.5438 0.8344 0.0891 +vn 0.3735 0.8785 -0.2980 +vn -0.5496 0.8216 -0.1515 +vn -0.7341 0.4884 -0.4718 +vn -0.6567 0.7382 -0.1541 +vn 0.8153 0.3683 0.4468 +vn 0.6192 0.3666 0.6944 +vn 0.5342 0.1166 0.8373 +vn 0.9432 0.3287 0.0475 +vn 0.9518 0.0530 -0.3020 +vn -0.2268 -0.9401 0.2546 +vn -0.4604 -0.8867 0.0438 +vn -0.2508 -0.9561 0.1515 +vn -0.4270 0.8860 0.1810 +vn -0.6281 0.7559 0.1848 +vn -0.5071 0.7063 0.4941 +vn 0.6958 -0.2893 0.6573 +vn 0.5000 0.2073 0.8409 +vn 0.4554 0.0751 0.8871 +vn -0.9762 0.0096 -0.2167 +vn -0.0724 0.9343 -0.3492 +vn -0.0511 0.9741 -0.2203 +vn 0.1178 0.9031 -0.4129 +vn 0.1755 0.5935 0.7854 +vn 0.4507 0.4839 -0.7501 +vn 0.3712 0.5005 -0.7821 +vn 0.2149 0.5387 -0.8146 +vn -0.1303 -0.9828 -0.1307 +vn -0.4726 0.7435 -0.4731 +vn -0.6224 0.6906 -0.3683 +vn -0.4337 0.8841 -0.1740 +vn -0.7410 0.2812 0.6097 +vn -0.6140 0.2281 0.7556 +vn -0.4295 0.1154 -0.8957 +vn -0.7075 -0.1199 -0.6964 +vn -0.9272 0.0213 -0.3740 +vn -0.4083 0.9119 0.0408 +vn -0.2703 0.8555 0.4416 +vn 0.8890 0.3106 0.3365 +vn 0.3957 0.6849 -0.6118 +vn 0.5416 0.5766 -0.6118 +vn 0.3422 0.6541 -0.6746 +vn 0.8530 0.1169 -0.5087 +vn 0.7675 0.5356 -0.3523 +vn 0.6880 0.5886 -0.4245 +vn 0.6824 0.6348 -0.3625 +vn 0.6497 0.0200 -0.7599 +vn -0.6563 -0.7541 0.0235 +vn -0.7170 -0.6942 0.0639 +vn -0.5972 -0.7713 -0.2203 +vn 0.7814 -0.1398 -0.6082 +vn 0.4977 0.4935 -0.7133 +vn 0.4349 0.3484 -0.8304 +vn 0.3157 0.8045 -0.5031 +vn 0.3764 0.7989 -0.4691 +vn 0.3243 0.7837 -0.5297 +vn 0.2170 0.6836 0.6968 +vn 0.9036 0.4219 -0.0744 +vn 0.8592 0.4880 -0.1535 +vn 0.8966 0.4428 -0.0003 +vn 0.8921 0.4514 -0.0200 +vn -0.6229 -0.0529 -0.7805 +vn -0.4277 -0.1615 -0.8894 +vn 0.1813 0.9642 -0.1937 +vn -0.1913 0.9744 -0.1185 +vn -0.2727 0.4685 -0.8403 +vn -0.2564 0.3508 -0.9007 +vn 0.9117 -0.0153 -0.4107 +vn 0.6532 0.0550 -0.7552 +vn -0.3077 0.9299 -0.2015 +vn 0.3146 0.8583 -0.4054 +vn 0.2224 0.9222 -0.3165 +vn -0.9485 0.0905 -0.3037 +vn -0.9762 0.1042 -0.1901 +vn 0.2148 0.8711 -0.4417 +vn 0.2243 0.8509 -0.4750 +vn 0.2244 0.8477 -0.4806 +vn -0.5070 0.7151 0.4812 +vn -0.6651 0.6707 0.3285 +vn -0.6524 0.5634 0.5069 +vn -0.9525 0.0564 -0.2994 +vn -0.8772 -0.2779 -0.3915 +vn -0.6619 -0.2580 -0.7038 +vn -0.3147 0.6844 -0.6577 +vn -0.5800 0.6435 -0.4995 +vn -0.3200 0.7575 -0.5690 +vn 0.9440 -0.1777 0.2781 +vn 0.9227 -0.3854 0.0020 +vn 0.9538 -0.2860 0.0921 +vn -0.7022 0.0032 0.7120 +vn -0.6764 -0.0083 0.7365 +vn -0.3405 -0.0827 0.9366 +vn 0.1831 0.1117 0.9767 +vn -0.0177 0.1943 0.9808 +vn -0.2528 0.1971 0.9472 +vn -0.3345 -0.1191 0.9349 +vn -0.1962 -0.1188 0.9733 +vn 0.7273 0.4434 0.5239 +vn 0.5866 0.3786 0.7159 +vn 0.3957 0.6849 0.6118 +vn 0.1006 0.9838 0.1484 +vn 0.9748 0.0796 0.2082 +vn -0.9219 0.0716 -0.3809 +vn -0.9272 0.0213 0.3740 +vn -0.7047 -0.3612 0.6106 +vn 0.3167 0.7661 -0.5593 +vn 0.2130 0.9741 0.0756 +vn 0.2142 0.9430 0.2548 +vn 0.2564 -0.5624 -0.7861 +vn 0.2528 0.1703 0.9524 +vn -0.8316 -0.3417 0.4378 +vn -0.7250 -0.4082 0.5548 +vn -0.9078 -0.2175 0.3587 +vn -0.3977 0.9173 -0.0180 +vn -0.1122 0.7924 0.5996 +vn -0.3826 0.5014 0.7761 +vn -0.2107 -0.1853 -0.9598 +vn -0.3877 -0.1980 -0.9003 +vn -0.1779 -0.1254 -0.9760 +vn -0.0875 0.8949 0.4377 +vn 0.1332 0.8853 0.4455 +vn -0.9450 0.1150 -0.3063 +vn 0.0583 0.9904 0.1251 +vn 0.0586 0.9897 0.1309 +vn 0.0572 0.9902 0.1273 +vn -0.9818 0.0507 -0.1828 +vn -0.9798 0.0977 0.1747 +vn -0.9798 0.0977 0.1746 +vn 0.3046 0.0414 -0.9516 +vn -0.9836 0.1741 0.0461 +vn -0.9617 0.2581 -0.0919 +vn -0.9429 0.2922 -0.1601 +vn -0.3048 -0.0970 -0.9475 +vn 0.0143 -0.1314 -0.9912 +vn -0.3022 -0.1021 -0.9478 +vn -0.1996 0.9798 -0.0110 +vn -0.2248 0.7912 -0.5688 +vn 0.0678 0.9886 0.1346 +vn 0.0612 0.9892 0.1330 +vn 0.7828 -0.1079 0.6128 +vn 0.0712 0.8927 -0.4450 +vn 0.1347 0.9314 -0.3383 +vn 0.1131 0.8916 -0.4384 +vn -0.5436 0.8299 -0.1257 +vn 0.2649 0.9141 -0.3071 +vn 0.2701 0.8225 0.5005 +vn 0.1019 0.9528 0.2860 +vn -0.6561 0.2562 -0.7098 +vn -0.8099 0.1403 -0.5695 +vn -0.4831 0.5122 -0.7101 +vn -0.2555 0.5571 -0.7902 +vn -0.1816 0.5575 -0.8101 +vn 0.3143 0.8117 -0.4923 +vn 0.3156 0.8158 -0.4846 +vn 0.1053 0.1174 0.9875 +vn -0.2463 0.1663 0.9548 +vn -0.1732 0.1524 0.9730 +vn 0.2452 0.8236 -0.5115 +vn -0.1330 0.9547 -0.2661 +vn 0.0461 0.9904 0.1303 +vn -0.9475 0.3196 0.0040 +vn -0.9615 0.2578 -0.0952 +vn -0.9093 0.3891 0.1477 +vn -0.1472 0.7702 -0.6206 +vn 0.2142 0.9430 -0.2548 +vn -0.7022 0.0032 -0.7120 +vn -0.8894 0.0582 -0.4534 +vn -0.4420 0.7685 -0.4627 +vn -0.4751 0.8710 -0.1252 +vn -0.3478 0.9060 -0.2412 +vn -0.4219 0.8170 -0.3931 +vn -0.2284 -0.1821 0.9564 +vn 0.7311 0.6305 -0.2608 +vn -0.5690 -0.3427 0.7475 +vn -0.1301 -0.4998 0.8563 +vn -0.6275 -0.3039 0.7169 +vn -0.1458 -0.1185 -0.9822 +vn -0.1369 0.7736 0.6187 +vn -0.4478 0.8890 0.0958 +vn -0.3024 0.8684 0.3929 +vn -0.8240 -0.0857 0.5601 +vn 0.9219 -0.0716 0.3809 +vn 0.0597 -0.7151 -0.6964 +vn 0.3187 -0.6471 -0.6925 +vn 0.1698 -0.8722 -0.4587 +vn 0.6604 0.3253 0.6768 +vn 0.5223 0.4119 0.7467 +vn 0.2180 0.5035 0.8360 +vn -0.3826 0.5014 -0.7761 +vn -0.4373 0.1490 -0.8869 +vn -0.6344 0.4405 -0.6353 +vn 0.3686 -0.0001 -0.9296 +vn 0.3286 -0.5634 -0.7580 +vn 0.2936 -0.5654 -0.7708 +vn -0.1262 -0.4896 -0.8628 +vn 0.2518 0.9421 -0.2215 +vn 0.0750 0.9941 0.0786 +vn 0.7161 -0.5154 -0.4707 +vn 0.5998 -0.5499 -0.5812 +vn 0.1398 -0.3001 0.9436 +vn -0.0883 -0.4220 0.9023 +vn 0.1115 -0.5387 0.8351 +vn -0.1842 -0.0213 0.9827 +vn 0.1021 0.1117 0.9885 +vn 0.0480 0.1270 0.9907 +vn 0.9647 -0.1900 -0.1821 +vn -0.1043 0.9136 -0.3930 +vn -0.1645 0.8274 -0.5369 +vn -0.0052 0.7528 -0.6583 +vn 0.0679 0.7986 -0.5980 +vn -0.9429 0.2922 0.1601 +vn -0.8047 0.4244 0.4151 +vn -0.9617 0.2581 0.0919 +vn 0.5917 0.7941 -0.1392 +vn 0.6208 0.7568 -0.2047 +vn 0.5369 0.8289 -0.1570 +vn 0.9018 0.3395 0.2673 +vn -0.2954 0.5863 -0.7543 +vn 0.2733 -0.2476 0.9295 +vn 0.1464 0.1195 -0.9820 +vn 0.1465 0.1195 -0.9820 +vn 0.0666 -0.9968 -0.0449 +vn 0.2003 -0.9793 0.0286 +vn 0.4324 -0.8953 0.1075 +vn -0.8171 0.3401 -0.4655 +vn 0.6669 0.0059 -0.7452 +vn 0.8350 -0.0868 -0.5434 +vn 0.8889 -0.4076 -0.2092 +vn 0.6941 0.2235 0.6843 +vn 0.8260 0.3092 0.4713 +vn 0.7002 -0.5319 0.4763 +vn 0.8644 -0.4777 0.1570 +vn -0.6229 0.7707 -0.1340 +vn -0.6825 0.7299 -0.0372 +vn -0.3478 0.9060 0.2412 +vn -0.9985 0.0533 -0.0105 +vn -0.9171 0.1310 0.3765 +vn -0.9462 0.1312 0.2956 +vn -0.7594 0.5048 -0.4105 +vn -0.9093 0.3891 -0.1477 +vn -0.9475 0.3196 -0.0040 +vn 0.3528 0.4414 0.8250 +vn -0.6151 0.4957 -0.6131 +vn -0.8456 0.3969 -0.3568 +vn -0.7288 0.4584 -0.5086 +vn 0.8299 0.3707 -0.4170 +vn 0.5382 0.6150 -0.5763 +vn 0.4167 0.8842 0.2110 +vn 0.6781 0.6099 0.4102 +vn 0.3136 0.8366 -0.4491 +vn 0.2760 0.8500 -0.4487 +vn 0.2549 -0.1556 -0.9544 +vn 0.0144 -0.1332 -0.9910 +vn -0.3027 -0.0814 -0.9496 +vn 0.3805 -0.9245 0.0228 +vn 0.4185 -0.9075 -0.0370 +vn 0.5102 -0.8541 0.1008 +vn 0.1086 0.9868 0.1201 +vn -0.1089 0.9744 0.1965 +vn 0.1085 0.9862 0.1251 +vn 0.2527 0.6989 -0.6691 +vn 0.3345 0.6893 -0.6426 +vn 0.6755 0.2085 0.7072 +vn 0.0987 0.5505 -0.8290 +vn 0.7828 -0.1079 -0.6128 +vn -0.1943 0.9310 -0.3089 +vn -0.2974 0.7063 -0.6425 +vn -0.4103 0.7416 -0.5307 +vn 0.2916 0.7059 0.6455 +vn 0.1491 0.6095 0.7786 +vn -0.9192 0.3119 -0.2404 +vn -0.8638 -0.0078 -0.5037 +vn 0.7626 0.2802 0.5831 +vn 0.3674 -0.1313 -0.9207 +vn 0.2560 -0.1267 -0.9583 +vn 0.7023 -0.1163 -0.7023 +vn -0.0091 0.9475 -0.3196 +vn 0.4700 -0.7183 0.5130 +vn 0.2128 -0.8725 0.4398 +vn 0.4644 -0.8172 0.3414 +vn -0.5638 0.4961 -0.6603 +vn 0.3887 0.7380 0.5516 +vn 0.2677 0.4314 0.8615 +vn 0.2144 0.3961 0.8928 +vn -0.3381 -0.0799 -0.9377 +vn -0.8176 -0.4694 -0.3334 +vn -0.7365 -0.4344 -0.5185 +vn -0.7632 -0.5136 -0.3922 +vn 0.3507 0.9351 0.0518 +vn 0.3817 -0.1638 0.9096 +vn -0.8223 0.4025 -0.4022 +vn -0.6504 0.5017 -0.5703 +vn -0.7832 0.4287 -0.4503 +vn 0.1725 0.8391 0.5159 +vn -0.5149 -0.2278 -0.8265 +vn -0.5019 -0.1799 -0.8460 +vn -0.2609 -0.1979 -0.9449 +vn -0.3945 -0.2708 0.8781 +vn -0.5767 -0.2446 0.7795 +vn -0.5350 -0.3207 0.7816 +vn 0.9749 -0.1648 -0.1495 +vn 0.9268 -0.2520 -0.2786 +vn 0.7872 -0.3759 -0.4888 +vn 0.1834 0.9535 0.2392 +vn -0.0790 0.9850 0.1533 +vn 0.7368 0.0330 -0.6753 +vn 0.5208 0.0731 -0.8505 +vn 0.1931 -0.8489 -0.4921 +vn 0.0032 -0.8353 -0.5498 +vn -0.0394 -0.7917 -0.6096 +vn 0.1557 0.4437 -0.8826 +vn 0.1209 0.9588 0.2570 +vn 0.9295 0.2177 -0.2976 +vn -0.2568 0.9444 0.2052 +vn -0.2597 0.9404 0.2196 +vn -0.1162 0.9387 0.3247 +vn -0.9825 0.1495 -0.1110 +vn 0.1544 0.8933 -0.4221 +vn 0.0450 0.9729 0.2270 +vn 0.0270 0.9722 0.2325 +vn -0.0274 0.9986 0.0461 +vn 0.2285 0.8374 -0.4965 +vn 0.2406 0.8298 -0.5035 +vn -0.3048 -0.0968 0.9475 +vn -0.4145 -0.0880 0.9058 +vn -0.1457 -0.1180 0.9823 +vn 0.1657 0.9848 0.0519 +vn 0.1639 0.9821 0.0927 +vn 0.1900 0.9788 0.0761 +vn -0.9086 0.4176 -0.0061 +vn -0.7905 0.6124 -0.0099 +vn 0.4699 0.7152 0.5174 +vn 0.4147 0.4175 0.8085 +vn 0.7087 0.3082 0.6346 +vn 0.2272 0.6770 -0.7000 +vn -0.5185 0.8533 -0.0550 +vn 0.5258 0.5887 -0.6140 +vn -0.9192 0.0592 -0.3894 +vn -0.7770 -0.1213 -0.6177 +vn -0.6208 -0.2585 -0.7401 +vn -0.5681 0.0691 -0.8200 +vn -0.4408 0.1305 -0.8881 +vn 0.2373 0.9423 0.2360 +vn 0.1714 0.9764 0.1318 +vn 0.1658 0.9762 0.1397 +vn 0.7653 0.6427 0.0357 +vn 0.7823 0.6229 -0.0016 +vn 0.1344 0.9656 0.2228 +vn 0.0764 0.9599 0.2699 +vn -0.5606 -0.6868 0.4626 +vn -0.7173 -0.6767 0.1657 +vn 0.3364 -0.5385 0.7725 +vn 0.6141 -0.5007 0.6101 +vn 0.7326 -0.4556 0.5057 +vn 0.5788 0.1990 -0.7908 +vn 0.6078 -0.7917 -0.0613 +vn 0.8228 0.5605 0.0945 +vn -0.4586 0.5446 0.7022 +vn -0.3264 0.4178 0.8479 +vn 0.5591 0.7839 0.2702 +vn -0.5070 0.7151 -0.4812 +vn -0.6651 0.6707 -0.3285 +vn -0.4780 0.8095 -0.3408 +vn -0.1015 -0.9818 -0.1605 +vn -0.1078 -0.9753 -0.1927 +vn 0.1755 -0.9842 -0.0213 +vn -0.1239 0.2982 0.9464 +vn -0.3784 0.4856 0.7880 +vn 0.8411 -0.0705 0.5363 +vn 0.3176 -0.2036 0.9261 +vn 0.1816 -0.5575 0.8101 +vn 0.3743 -0.5354 0.7572 +vn 0.4095 -0.5260 0.7454 +vn -0.2319 0.8763 -0.4222 +vn -0.3392 0.8880 -0.3105 +vn 0.1181 -0.9656 0.2315 +vn 0.3696 -0.8682 0.3312 +vn -0.6521 -0.0706 0.7549 +vn -0.3412 -0.1060 0.9340 +vn -0.3773 -0.0915 0.9216 +vn 0.9546 0.2164 -0.2047 +vn -0.9994 0.0251 -0.0240 +vn -0.1503 0.5643 -0.8118 +vn 0.0361 0.5420 -0.8396 +vn 0.8866 0.2304 -0.4011 +vn 0.5842 0.4309 0.6878 +vn 0.6244 0.3453 0.7006 +vn 0.7543 0.4022 0.5189 +vn -0.9245 -0.2400 0.2962 +vn -0.9938 0.0062 0.1108 +vn 0.1332 0.8853 -0.4455 +vn -0.2147 -0.2609 -0.9412 +vn -0.0360 -0.3411 -0.9393 +vn -0.4369 0.5679 -0.6976 +vn -0.7382 0.5106 -0.4408 +vn 0.9117 -0.0153 0.4107 +vn 0.9740 -0.0449 0.2219 +vn 0.0006 0.8582 0.5133 +vn 0.0095 0.7218 -0.6920 +vn 0.2253 0.8422 -0.4898 +vn 0.2207 0.8361 -0.5023 +vn -0.5870 0.5724 -0.5725 +vn -0.8442 0.4147 -0.3396 +vn 0.0578 0.9912 0.1192 +vn -0.0441 0.9749 0.2181 +vn -0.0941 0.9723 0.2141 +vn -0.9192 0.3119 0.2404 +vn -0.8638 -0.0078 0.5037 +vn 0.1405 0.8582 0.4938 +vn -0.0454 0.9296 0.3657 +vn -0.0548 0.7608 0.6467 +vn -0.5780 0.7807 0.2378 +vn -0.3564 0.9004 0.2496 +vn 0.4578 0.0544 -0.8874 +vn -0.4760 0.5490 0.6870 +vn -0.3346 0.4585 0.8233 +vn -0.4135 0.6258 0.6613 +vn 0.4015 0.5567 -0.7273 +vn 0.5842 0.4309 -0.6878 +vn 0.6244 0.3453 -0.7006 +vn 0.1364 0.9742 0.1797 +vn 0.1670 0.9634 0.2097 +vn -0.2630 0.5440 -0.7968 +vn 0.8272 0.1055 0.5519 +vn 0.9683 -0.1467 0.2021 +vn 0.9481 0.2340 0.2155 +vn 0.0393 0.8456 -0.5323 +vn 0.0423 0.8408 -0.5397 +vn -0.0590 0.9463 0.3179 +vn -0.0148 0.9534 0.3013 +vn 0.1901 0.8894 -0.4156 +vn -0.0242 0.8852 -0.4646 +vn 0.0230 -0.9728 -0.2304 +vn 0.1053 0.9689 0.2240 +vn -0.7828 -0.5873 -0.2056 +vn -0.6048 -0.5645 -0.5618 +vn 0.7543 0.4022 -0.5189 +vn -0.5515 -0.6043 -0.5750 +vn -0.2764 -0.5056 -0.8173 +vn -0.5656 -0.6283 -0.5342 +vn 0.8358 0.0593 -0.5459 +vn 0.9591 -0.2046 -0.1958 +vn 0.6529 0.7416 -0.1543 +vn 0.8341 0.5429 -0.0977 +vn 0.0477 0.7522 0.6572 +vn 0.8272 0.1055 -0.5519 +vn 0.4014 -0.9108 0.0962 +vn 0.5268 -0.7773 -0.3440 +vn 0.6787 -0.7327 0.0490 +vn -0.7387 -0.6740 0.0019 +vn -0.6865 -0.7090 -0.1614 +vn -0.6950 -0.7063 0.1349 +vn -0.5262 -0.3282 -0.7845 +vn -0.3945 -0.2708 -0.8781 +vn -0.1506 -0.2854 -0.9465 +vn 0.0992 -0.5521 0.8279 +vn -0.2388 -0.4749 0.8470 +vn -0.2341 -0.4824 0.8441 +vn 0.7168 0.6761 -0.1705 +vn 0.7300 0.6524 -0.2036 +vn -0.2268 -0.5953 0.7708 +vn -0.2061 -0.6337 0.7456 +vn 0.0597 -0.7151 0.6964 +vn 0.0529 -0.3836 -0.9220 +vn 0.7325 -0.0066 -0.6807 +vn -0.3203 0.8150 -0.4829 +vn -0.7770 0.1832 -0.6023 +vn -0.7770 0.1832 -0.6022 +vn 0.9219 -0.0716 -0.3809 +vn -0.6171 0.5743 -0.5380 +vn -0.7283 0.4936 -0.4753 +vn 0.9863 0.1633 -0.0253 +vn 0.9850 0.1635 -0.0553 +vn 0.1304 0.9828 -0.1308 +vn 0.1304 0.9828 -0.1307 +vn 0.6330 0.7540 -0.1755 +vn 0.1232 -0.3127 -0.9418 +vn -0.2310 -0.0578 -0.9712 +vn 0.6906 0.2705 -0.6708 +vn 0.1724 0.8391 0.5159 +vn 0.0879 0.6670 0.7399 +vn 0.4178 0.6158 0.6680 +vn 0.6066 0.2481 -0.7553 +vn -0.6286 -0.3229 -0.7075 +vn -0.5561 -0.2390 -0.7960 +vn -0.9150 0.0787 -0.3956 +vn -0.8758 0.3600 -0.3216 +vn -0.6524 0.5634 -0.5069 +vn -0.4103 0.7416 0.5307 +vn -0.5496 0.6278 0.5512 +vn -0.8833 0.4602 0.0892 +vn -0.7892 0.5954 0.1503 +vn 0.8859 0.4227 -0.1912 +vn 0.8293 0.4807 -0.2850 +vn 0.0471 0.9863 0.1579 +vn 0.0791 0.5683 -0.8190 +vn 0.9359 0.3129 -0.1620 +vn 0.8869 0.3798 -0.2629 +vn 0.7899 0.4754 -0.3875 +vn 0.7114 0.5099 -0.4835 +vn 0.1459 0.8342 -0.5317 +vn 0.1474 0.8219 -0.5503 +vn 0.1612 0.9060 -0.3914 +vn 0.3870 0.5010 -0.7741 +vn -0.9647 0.0391 0.2606 +vn -0.9798 0.0977 -0.1746 +vn -0.9798 0.0977 -0.1747 +vn -0.0129 0.9870 0.1602 +vn 0.1969 0.9732 0.1191 +vn 0.2047 0.7836 -0.5865 +vn 0.2226 0.7714 -0.5962 +vn 0.1909 0.7240 -0.6628 +vn 0.3010 -0.5436 -0.7835 +vn 0.3364 -0.5385 -0.7725 +vn 0.6141 -0.5007 -0.6101 +vn -0.2388 -0.4749 -0.8470 +vn -0.0634 0.6863 0.7246 +vn -0.9687 0.0061 -0.2482 +vn -0.8686 0.1217 -0.4804 +vn 0.6481 -0.4555 -0.6103 +vn 0.4326 0.4060 0.8050 +vn 0.2469 0.4702 0.8473 +vn -0.6101 0.7738 0.1703 +vn -0.8797 0.3542 0.3173 +vn 0.5946 0.6867 -0.4181 +vn 0.6056 0.5549 -0.5704 +vn -0.7468 0.0379 -0.6640 +vn -0.8556 0.0084 -0.5176 +vn -0.8629 0.0278 -0.5046 +vn -0.0022 0.9766 0.2151 +vn -0.0293 0.1789 -0.9834 +vn -0.0514 0.3185 -0.9465 +vn 0.7739 0.5599 -0.2959 +vn -0.5751 0.7709 -0.2737 +vn -0.4671 0.8342 -0.2933 +vn -0.4801 0.7177 -0.5044 +vn 0.5776 -0.7699 0.2712 +vn 0.6150 -0.7633 0.1979 +vn 0.6028 -0.6955 0.3911 +vn 0.1698 -0.8722 0.4587 +vn 0.4403 -0.7329 0.5187 +vn 0.3187 -0.6471 0.6925 +vn -0.2362 0.2275 -0.9447 +vn 0.4860 -0.8081 -0.3327 +vn -0.2547 0.2240 0.9407 +vn -0.4231 0.1147 0.8988 +vn 0.3200 0.8197 -0.4751 +vn 0.3324 0.8280 -0.4515 +vn -0.4612 0.5199 0.7190 +vn 0.5769 0.1405 0.8046 +vn 0.1941 0.2362 0.9521 +vn -0.1236 0.3682 0.9215 +vn -0.1823 0.2705 0.9453 +vn 0.1081 0.9842 0.1404 +vn -0.2687 0.6795 0.6828 +vn 0.8881 -0.1104 -0.4461 +vn 0.8735 0.2265 -0.4309 +vn 0.8927 0.1671 -0.4185 +vn 0.8252 0.0625 -0.5614 +vn 0.8115 0.5660 -0.1453 +vn 0.8280 0.5523 -0.0968 +vn -0.6755 -0.2085 0.7072 +vn -0.9997 -0.0039 0.0225 +vn -0.9995 0.0034 0.0300 +vn 0.1816 -0.6616 -0.7275 +vn 0.0694 0.9962 0.0533 +vn 0.1946 0.9548 0.2246 +vn 0.3017 0.9216 0.2441 +vn 0.2235 0.9466 0.2325 +vn -0.0329 0.9779 0.2065 +vn -0.3622 0.7739 -0.5195 +vn 0.2558 0.4480 0.8566 +vn 0.0142 0.4567 0.8895 +vn -0.1749 0.5376 0.8249 +vn 0.0436 0.9771 0.2082 +vn 0.2461 0.5280 0.8128 +vn -0.1047 0.3585 0.9276 +vn -0.1301 -0.4998 -0.8563 +vn -0.2600 0.5513 -0.7928 +vn 0.6066 0.2481 0.7553 +vn 0.4801 0.0809 -0.8735 +vn -0.9664 0.0471 -0.2528 +vn -0.4528 0.2650 0.8513 +vn -0.0209 0.8899 -0.4557 +vn -0.0497 0.8187 -0.5721 +vn 0.0728 0.9585 -0.2757 +vn -0.2103 -0.2868 0.9346 +vn -0.4800 -0.1783 0.8590 +vn -0.4817 -0.2405 0.8427 +vn -0.0349 0.9994 -0.0032 +vn 0.6906 0.2705 0.6708 +vn 0.6906 0.2705 0.6707 +vn 0.8889 -0.4076 0.2092 +vn 0.7256 -0.1572 0.6700 +vn 0.7503 0.2437 0.6145 +vn 0.5694 0.0487 0.8206 +vn 0.4554 0.0751 -0.8871 +vn 0.5031 0.2018 -0.8403 +vn -0.2473 0.9654 0.0831 +vn 0.0014 0.9867 0.1623 +vn 0.1085 0.9854 0.1309 +vn 0.1085 0.9855 0.1304 +vn -0.9933 -0.0329 -0.1104 +vn -0.9969 -0.0427 -0.0655 +vn 0.8775 0.1071 0.4675 +vn 0.8644 -0.4777 -0.1570 +vn -0.0093 0.9925 0.1220 +vn -0.0067 0.9927 0.1205 +vn 0.2284 0.5497 0.8035 +vn 0.0361 0.5420 0.8396 +vn -0.5788 0.5874 -0.5657 +vn -0.6710 0.6674 -0.3229 +vn -0.6054 0.6628 -0.4406 +vn -0.8201 -0.0758 0.5672 +vn -0.6181 -0.2504 0.7451 +vn 0.8888 -0.0109 0.4582 +vn 0.7530 0.0175 0.6577 +vn 0.8839 -0.0553 0.4643 +vn -0.7620 0.6397 0.1009 +vn -0.2391 0.9304 -0.2779 +vn -0.3376 0.9354 -0.1054 +vn -0.8568 0.2790 -0.4336 +vn -0.6057 0.5469 -0.5780 +vn 0.1876 -0.6238 -0.7587 +vn 0.3803 -0.7450 -0.5480 +vn 0.4664 0.8781 -0.1067 +vn 0.4397 0.8715 0.2170 +vn 0.9831 0.0139 0.1827 +vn 0.8168 0.5696 0.0914 +vn 0.3341 0.9201 0.2045 +vn 0.2699 0.9461 0.1790 +vn 0.9064 -0.0647 0.4174 +vn 0.7325 -0.0066 0.6807 +vn 0.6775 0.0046 0.7355 +vn 0.3067 0.7909 -0.5295 +vn -0.1178 0.9839 -0.1342 +vn -0.5458 0.1269 0.8282 +vn -0.2123 0.1395 0.9672 +vn -0.7323 0.1185 0.6706 +vn 0.9018 0.3395 -0.2673 +vn 0.5652 0.7123 -0.4162 +vn 0.7804 0.6159 -0.1079 +vn 0.2339 0.8653 -0.4433 +vn -0.2864 0.9572 -0.0407 +vn 0.1469 0.9792 0.1397 +vn 0.1342 0.9815 0.1363 +vn -0.1566 -0.0442 0.9867 +vn -0.2044 0.0003 0.9789 +vn -0.1554 -0.0453 0.9868 +vn -0.0571 -0.6657 0.7440 +vn 0.1104 -0.6993 0.7063 +vn 0.1703 -0.6415 0.7479 +vn 0.9886 0.0352 0.1463 +vn 0.8533 -0.3372 0.3977 +vn 0.7326 -0.4556 -0.5057 +vn 0.1222 0.9687 0.2160 +vn -0.6567 0.7382 0.1541 +vn -0.5725 -0.7608 0.3058 +vn -0.6263 -0.7093 0.3236 +vn 0.9518 0.0530 0.3020 +vn 0.8854 0.1469 0.4410 +vn 0.1647 0.1380 -0.9766 +vn 0.1089 0.1730 -0.9789 +vn 0.6192 0.3666 -0.6944 +vn 0.1491 0.6095 -0.7786 +vn 0.2916 0.7059 -0.6455 +vn -0.6062 0.1059 -0.7882 +vn -0.9293 -0.0116 -0.3692 +vn 0.4005 0.8557 -0.3275 +vn 0.6042 0.7922 -0.0862 +vn 0.0125 0.9783 0.2070 +vn -0.8042 -0.0822 -0.5886 +vn -0.9245 -0.2400 -0.2962 +vn -0.7380 0.2750 -0.6162 +vn 0.1086 0.9861 0.1255 +vn -0.2489 0.1389 -0.9585 +vn -0.4601 0.8773 0.1367 +vn -0.2588 0.9659 0.0000 +vn 0.0630 0.9745 0.2153 +vn -0.1304 -0.9828 0.1307 +vn 0.2234 0.8639 -0.4514 +vn -0.2161 0.9687 -0.1224 +vn -0.2509 0.9680 -0.0037 +vn 0.6218 0.7534 -0.2140 +vn 0.6276 0.7583 -0.1764 +vn -0.4163 -0.6106 0.6737 +vn 0.8580 0.0302 -0.5127 +vn 0.4434 -0.8340 0.3284 +vn 0.4572 -0.8245 0.3334 +vn 0.1500 -0.8588 0.4899 +vn 0.0034 -0.4172 -0.9088 +vn -0.1694 -0.2008 -0.9649 +vn -0.9078 -0.2175 -0.3587 +vn -0.7250 -0.4082 -0.5548 +vn -0.9644 0.2628 0.0294 +vn -0.7503 0.6208 -0.2271 +vn -0.3526 -0.3992 0.8464 +vn -0.0507 -0.5069 0.8605 +vn -0.5962 -0.0420 0.8017 +vn 0.0750 -0.0075 0.9972 +vn -0.4601 0.8773 -0.1367 +vn -0.3368 0.8947 -0.2933 +vn 0.9275 0.3648 0.0816 +vn 0.8765 0.3487 0.3320 +vn 0.9437 0.3289 0.0355 +vn -0.9898 -0.0884 -0.1120 +vn -0.9558 0.2865 0.0654 +vn -0.8792 0.4694 0.0818 +vn -0.0485 0.6721 -0.7389 +vn -0.9762 0.0103 0.2168 +vn -0.8583 -0.0325 0.5121 +vn -0.8577 -0.0194 0.5137 +vn -0.9628 -0.2652 0.0517 +vn -0.8446 -0.1822 0.5035 +vn -0.7723 0.1198 0.6239 +vn 0.0006 0.8582 -0.5133 +vn -0.5851 0.6712 -0.4552 +vn -0.2547 0.2240 -0.9407 +vn -0.2521 0.3969 -0.8826 +vn -0.4989 0.8240 -0.2685 +vn -0.7149 0.4411 -0.5426 +vn 0.6687 0.7309 0.1364 +vn -0.8474 0.5137 -0.1340 +vn 0.7739 0.5599 0.2959 +vn -0.5264 0.2156 -0.8224 +vn 0.0113 0.9711 0.2383 +vn 0.3010 -0.5436 0.7835 +vn 0.0407 0.8083 -0.5874 +vn 0.9432 0.3287 -0.0475 +vn 0.7212 0.5195 -0.4583 +vn -0.3254 0.8416 0.4310 +vn -0.1847 0.8966 0.4024 +vn -0.7913 0.3902 0.4708 +vn -0.9871 0.0559 -0.1498 +vn -0.5647 -0.8186 -0.1048 +vn -0.0725 -0.1969 0.9777 +vn -0.5626 0.8128 0.1511 +vn -0.0491 -0.0221 0.9985 +vn -0.4371 -0.3253 -0.8385 +vn -0.6604 -0.2146 -0.7196 +vn -0.0857 0.0925 0.9920 +vn -0.3481 0.4522 0.8212 +vn -0.4241 0.1101 0.8989 +vn 0.2764 -0.8975 -0.3436 +vn -0.1041 0.5421 -0.8338 +vn 0.1323 0.4878 -0.8629 +vn 0.2420 0.4451 -0.8622 +vn 0.3159 -0.9465 -0.0653 +vn 0.0527 -0.9965 -0.0653 +vn -0.0899 0.9266 -0.3651 +vn 0.6755 0.2085 -0.7072 +vn 0.3559 0.9320 -0.0679 +vn 0.6418 0.7649 0.0550 +vn 0.8804 0.4672 -0.0813 +vn -0.1319 0.4554 0.8805 +vn 0.8993 0.3202 -0.2978 +vn -0.5332 -0.8458 0.0160 +vn -0.9419 0.3348 0.0280 +vn -0.9625 -0.1017 -0.2515 +vn -0.7066 -0.0344 0.7068 +vn -0.9985 0.0533 0.0105 +vn -0.9904 0.1229 -0.0640 +vn -0.9462 0.1312 -0.2956 +vn 0.0121 0.9567 0.2910 +vn 0.1336 0.9677 0.2138 +vn -0.4975 -0.8648 -0.0685 +vn 0.3269 -0.2153 -0.9202 +vn 0.7491 -0.0729 0.6584 +vn 0.6419 0.3037 0.7041 +vn 0.5918 0.3091 0.7445 +vn -0.9360 0.3464 0.0624 +vn -0.9886 0.1465 -0.0334 +vn 0.7543 0.0375 -0.6555 +vn 0.1225 0.2719 -0.9545 +vn 0.3515 -0.2110 -0.9121 +vn -0.9886 -0.0514 -0.1413 +vn -0.1355 0.7124 -0.6885 +vn -0.6337 -0.7239 -0.2728 +vn -0.2512 0.1603 -0.9546 +vn 0.2209 0.1045 -0.9697 +vn 0.1842 0.1056 -0.9772 +vn 0.8621 -0.4331 0.2631 +vn 0.8881 -0.1104 0.4461 +vn 0.2936 -0.5654 0.7708 +vn 0.5998 -0.5499 0.5812 +vn 0.3286 -0.5634 0.7580 +vn -0.9765 0.1871 0.1067 +vn -0.9639 0.2534 0.0813 +vn -0.9628 -0.2652 -0.0517 +vn -0.1996 0.9798 0.0110 +vn 0.7823 0.6229 0.0016 +vn 0.2564 -0.5624 0.7861 +vn -0.6799 0.3273 0.6562 +vn 0.0992 -0.5521 -0.8279 +vn 0.1702 -0.5495 0.8180 +vn -0.5801 0.2288 -0.7818 +vn -0.0294 -0.9971 -0.0696 +vn 0.2367 -0.9700 -0.0556 +vn 0.0230 -0.9728 0.2304 +vn 0.1440 0.1134 0.9831 +vn -0.0782 -0.7891 -0.6093 +vn 0.1500 -0.8588 -0.4899 +vn -0.0298 -0.8273 -0.5610 +vn -0.6891 -0.6353 0.3486 +vn -0.9376 0.1066 0.3309 +vn 0.3526 -0.4129 -0.8397 +vn 0.0417 -0.3363 -0.9408 +vn 0.3663 -0.4021 -0.8391 +vn 0.9429 -0.2922 -0.1601 +vn 0.0417 0.9589 0.2807 +vn 0.9272 -0.0213 0.3740 +vn -0.2600 0.5513 0.7928 +vn 0.6781 0.5056 -0.5334 +vn -0.5905 0.7249 -0.3547 +vn -0.5867 0.6428 -0.4926 +vn 0.7256 -0.1572 -0.6700 +vn -0.3359 0.1389 0.9316 +vn -0.3900 0.2324 0.8910 +vn -0.5801 0.2288 0.7818 +vn 0.7505 0.5897 -0.2983 +vn 0.8363 0.5404 0.0927 +vn 0.5460 -0.6587 0.5177 +vn -0.2703 0.8555 -0.4416 +vn -0.4135 0.6258 -0.6613 +vn -0.5271 0.6425 -0.5563 +vn 0.5826 -0.1085 -0.8055 +vn 0.8550 -0.0464 -0.5166 +vn 0.9214 -0.3716 -0.1135 +vn 0.9587 -0.2780 0.0605 +vn 0.4015 0.5567 0.7273 +vn 0.5346 0.5960 0.5991 +vn 0.7023 0.2308 0.6734 +vn -0.2261 0.6027 -0.7653 +vn -0.1147 0.5216 -0.8455 +vn 0.3959 0.0231 -0.9180 +vn 0.3628 0.0884 -0.9277 +vn 0.8041 -0.4225 0.4183 +vn -0.4470 0.5400 0.7131 +vn -0.6445 0.4924 0.5849 +vn 0.9647 -0.1900 0.1821 +vn 0.5838 0.8118 0.0130 +vn 0.6288 0.7675 -0.1249 +vn 0.4700 0.8516 -0.2322 +vn -0.6430 0.7474 -0.1671 +vn 0.9014 0.4316 0.0330 +vn -0.7074 -0.0360 -0.7059 +vn -0.5224 -0.0689 -0.8499 +vn 0.1608 0.9764 0.1439 +vn 0.3034 0.1155 0.9458 +vn 0.0262 0.1256 0.9917 +vn 0.7106 0.6615 -0.2398 +vn 0.8840 0.4470 -0.1370 +vn 0.5732 -0.5191 -0.6341 +vn 0.2041 -0.5682 -0.7971 +vn 0.3719 -0.3443 -0.8621 +vn -0.6214 0.7675 0.1572 +vn -0.8074 0.5776 0.1202 +vn -0.7586 0.6346 0.1479 +vn -0.6919 0.6956 0.1933 +vn -0.5886 0.7131 0.3809 +vn -0.5901 0.7830 0.1969 +vn 0.9320 -0.1665 0.3219 +vn 0.8455 -0.1791 0.5030 +vn 0.3526 -0.4129 0.8397 +vn 0.3663 -0.4021 0.8391 +vn 0.0417 -0.3363 0.9408 +vn -0.9542 0.0386 -0.2965 +vn -0.8946 0.0097 -0.4468 +vn 0.3131 0.7873 0.5312 +vn -0.9965 -0.0312 0.0781 +vn -0.9968 -0.0297 0.0740 +vn -0.9992 -0.0017 0.0394 +vn -0.6764 -0.0083 -0.7365 +vn -0.4490 0.0587 -0.8916 +vn -0.2215 0.0304 -0.9747 +vn -0.1540 0.0362 -0.9874 +vn -0.4232 0.8822 0.2063 +vn 0.9319 -0.3540 0.0788 +vn 0.9886 0.0352 -0.1463 +vn 0.0384 0.9781 0.2045 +vn -0.8263 0.4083 0.3879 +vn -0.2706 0.5550 0.7866 +vn -0.5479 0.4819 0.6838 +vn 0.4064 0.8463 0.3443 +vn 0.1166 0.9081 -0.4022 +vn -0.9992 -0.0021 0.0407 +vn -0.9171 0.1310 -0.3765 +vn 0.1981 0.8131 0.5473 +vn 0.1236 0.3209 -0.9390 +vn 0.9137 0.0169 0.4060 +vn 0.9971 -0.0502 -0.0574 +vn 0.9989 -0.0408 -0.0213 +vn -0.3052 0.4973 0.8121 +vn -0.0753 -0.9886 0.1304 +vn -0.0180 -0.3222 0.9465 +vn 0.5431 0.8298 0.1279 +vn 0.4462 0.8747 -0.1889 +vn -0.4373 0.1490 0.8869 +vn -0.5201 -0.7835 -0.3401 +vn -0.3469 -0.7768 -0.5255 +vn 0.2130 0.9741 -0.0756 +vn 0.5605 -0.5159 0.6479 +vn 0.7322 -0.5269 0.4316 +vn 0.1341 0.5034 0.8536 +vn -0.1072 0.5371 0.8367 +vn 0.5450 -0.1504 -0.8248 +vn 0.3669 -0.1492 -0.9182 +vn 0.2559 -0.1406 -0.9564 +vn -0.5962 -0.0420 -0.8017 +vn 0.6406 0.6984 -0.3192 +vn 0.4434 -0.8340 -0.3284 +vn 0.4572 -0.8245 -0.3334 +vn -0.6171 0.5743 0.5380 +vn -0.7283 0.4936 0.4753 +vn -0.9979 -0.0303 -0.0580 +vn -0.9965 0.0394 -0.0743 +vn 0.5866 0.3786 -0.7159 +vn -0.4024 -0.3596 0.8419 +vn -0.6357 0.7090 0.3053 +vn -0.7229 0.5913 0.3575 +vn -0.1953 -0.9611 -0.1954 +vn -0.2087 -0.9475 -0.2421 +vn 0.0878 0.9724 0.2160 +vn -0.3180 -0.7712 -0.5514 +vn -0.3597 0.5377 -0.7626 +vn 0.3289 0.9429 0.0520 +vn 0.8041 -0.4225 -0.4183 +vn -0.7944 0.6067 -0.0293 +vn -0.7287 0.6842 -0.0295 +vn 0.2909 0.5734 -0.7659 +vn 0.2316 0.8341 -0.5007 +vn 0.2220 0.1157 -0.9682 +vn 0.0788 0.5735 0.8154 +vn -0.4586 0.5446 -0.7022 +vn 0.7100 0.0404 0.7030 +vn -0.7204 -0.6930 -0.0276 +vn 0.6595 0.7292 -0.1826 +vn -0.4390 -0.7907 0.4267 +vn 0.1449 0.1116 -0.9831 +vn 0.8939 0.2659 -0.3608 +vn 0.9358 -0.1009 -0.3379 +vn -0.9543 0.0383 0.2965 +vn -0.6025 0.7702 -0.2093 +vn 0.6259 -0.0541 -0.7781 +vn 0.7063 0.7075 -0.0231 +vn 0.7161 -0.5154 0.4707 +vn 0.1717 0.7901 -0.5884 +vn -0.3481 0.4522 -0.8212 +vn -0.4019 0.5686 0.7177 +vn 0.0120 0.5169 0.8560 +vn 0.1263 0.4896 0.8627 +vn -0.7204 0.5022 0.4784 +vn 0.4785 -0.6744 -0.5623 +vn -0.7372 -0.6412 0.2133 +vn -0.5634 -0.4470 -0.6949 +vn -0.7349 0.4222 0.5307 +vn -0.7615 0.3976 0.5119 +vn -0.4831 0.5122 0.7101 +vn -0.9485 0.0905 0.3037 +vn -0.8894 0.0582 0.4534 +vn 0.1165 0.9481 -0.2960 +vn 0.2959 0.8992 -0.3222 +vn -0.4726 0.7435 0.4731 +vn 0.9878 0.1553 0.0060 +vn -0.4746 0.1359 0.8696 +vn -0.4490 0.0587 0.8916 +vn -0.2215 0.0304 0.9747 +vn -0.2403 0.9267 0.2890 +vn 0.1854 0.1147 -0.9759 +vn -0.7066 -0.0347 -0.7068 +vn -0.9394 0.2262 -0.2576 +vn -0.9456 0.1725 -0.2758 +vn 0.5955 0.6397 -0.4860 +vn -0.2268 -0.5953 -0.7708 +vn 0.6965 0.6974 -0.1689 +vn 0.2234 0.9680 -0.1140 +vn -0.4612 0.5199 -0.7190 +vn -0.3052 0.4973 -0.8121 +vn 0.7154 0.5764 0.3950 +vn 0.0642 0.8896 -0.4522 +vn -0.9422 0.3230 -0.0890 +vn -0.8705 -0.1650 -0.4637 +vn -0.4083 0.9119 -0.0408 +vn -0.8124 -0.0145 0.5829 +vn -0.0283 0.9879 -0.1526 +vn 0.7106 0.6615 0.2398 +vn -0.8879 0.3695 -0.2740 +vn -0.9456 0.3086 -0.1030 +vn -0.9360 0.3464 -0.0624 +vn 0.2181 0.6806 0.6994 +vn 0.3444 0.5188 0.7824 +vn -0.6344 0.4405 0.6353 +vn -0.2486 -0.8084 -0.5336 +vn -0.3958 -0.7984 -0.4538 +vn -0.4215 -0.7504 -0.5092 +vn -0.7293 -0.6651 0.1607 +vn -0.1271 0.5192 -0.8451 +vn 0.6481 -0.4555 0.6103 +vn -0.4760 0.1506 0.8664 +vn 0.2510 -0.0090 0.9680 +vn 0.9886 -0.1252 -0.0832 +vn -0.6755 -0.2085 -0.7072 +vn -0.4801 0.7177 0.5044 +vn -0.4733 0.1783 0.8627 +vn -0.9886 0.1465 0.0334 +vn -0.9497 0.1105 0.2930 +vn -0.9319 0.3540 0.0788 +vn -0.9742 0.1515 -0.1673 +vn -0.9018 0.1723 -0.3963 +vn 0.3730 0.0704 0.9251 +vn 0.4146 0.0639 0.9077 +vn 0.8358 -0.0291 0.5483 +vn 0.8735 0.2265 0.4309 +vn 0.9683 -0.1467 -0.2021 +vn 0.2666 0.6879 0.6751 +vn 0.2019 0.9751 0.0919 +vn -0.0551 0.9647 -0.2576 +vn -0.4671 0.8342 0.2933 +vn -0.3490 0.7741 0.5282 +vn -0.1823 0.2705 -0.9453 +vn -0.1340 0.3644 -0.9216 +vn -0.6224 0.6906 0.3683 +vn -0.7006 0.6632 -0.2631 +vn -0.3900 0.2324 -0.8910 +vn 0.4403 -0.7329 -0.5187 +vn 0.4319 -0.8323 -0.3474 +vn -0.4730 0.8246 0.3105 +vn -0.3533 -0.3103 -0.8825 +vn -0.5140 -0.4179 -0.7491 +vn -0.3826 -0.2240 -0.8963 +vn -0.1803 -0.8216 0.5408 +vn -0.3513 -0.8043 0.4793 +vn -0.2521 0.3969 0.8826 +vn -0.3087 0.5905 0.7456 +vn -0.4600 0.5031 0.7316 +vn 0.0584 0.9911 0.1197 +vn -0.1072 0.5371 -0.8367 +vn -0.4119 0.5372 -0.7360 +vn 0.6591 0.7392 -0.1385 +vn 0.6532 0.7430 -0.1458 +vn -0.9293 0.0822 -0.3600 +vn -0.9394 0.0889 -0.3312 +vn -0.8500 0.1631 -0.5009 +vn -0.2630 0.5440 0.7968 +vn 0.1634 -0.2390 -0.9572 +vn 0.9087 -0.0872 -0.4082 +vn -0.5459 0.1263 -0.8283 +vn 0.1778 0.9566 -0.2308 +vn 0.1725 0.8391 -0.5160 +vn 0.9184 0.0181 0.3951 +vn -0.6101 0.7738 -0.1703 +vn -0.8943 0.4310 0.1201 +vn -0.3359 0.1389 -0.9316 +vn 0.0636 -0.8715 0.4862 +vn 0.6906 0.2705 -0.6707 +vn 0.4235 0.3653 -0.8290 +vn 0.4019 0.4884 -0.7745 +vn 0.6073 0.6945 0.3859 +vn 0.4314 0.3701 0.8228 +vn 0.3527 0.3996 0.8461 +vn 0.9392 -0.0784 0.3342 +vn -0.6054 0.6628 0.4406 +vn -0.5656 -0.6346 0.5266 +vn -0.3988 -0.6318 0.6647 +vn -0.4269 -0.5694 0.7025 +vn 0.6445 0.3160 0.6962 +vn -0.9825 0.1495 0.1110 +vn -0.9966 0.0809 0.0164 +vn -0.9409 0.2323 0.2465 +vn -0.1506 -0.2854 0.9465 +vn -0.4760 0.5490 -0.6870 +vn -0.3346 0.4585 -0.8233 +vn 0.1606 0.6809 0.7145 +vn 0.1136 0.7537 0.6473 +vn 0.7082 0.6921 0.1394 +vn 0.7282 0.5115 0.4561 +vn 0.5383 0.5335 0.6524 +vn 0.9882 0.0317 0.1500 +vn -0.9765 0.1871 -0.1067 +vn -0.9639 0.2534 -0.0813 +vn -0.0096 -0.6120 0.7908 +vn 0.4692 0.4441 0.7633 +vn -0.7229 0.2406 0.6477 +vn -0.6573 -0.2787 0.7002 +vn -0.1724 -0.8391 0.5159 +vn 0.0442 0.0756 -0.9962 +vn -0.0857 0.0925 -0.9920 +vn -0.1816 0.5575 0.8101 +vn -0.2555 0.5571 0.7902 +vn -0.9929 0.0578 -0.1043 +vn -0.1147 0.5216 0.8455 +vn 0.2510 -0.0090 -0.9680 +vn -0.0782 -0.7891 0.6093 +vn -0.0298 -0.8273 0.5610 +vn 0.5962 0.6804 -0.4262 +vn 0.1037 0.0990 0.9897 +vn -0.0918 0.1647 0.9821 +vn 0.1743 0.9766 0.1260 +vn -0.9880 0.0034 -0.1544 +vn -0.1448 -0.1116 0.9831 +vn -0.1449 -0.1116 0.9831 +vn 0.4319 -0.8323 0.3474 +vn 0.1123 0.4564 -0.8827 +vn 0.4878 -0.2779 -0.8275 +vn 0.7378 -0.2537 -0.6255 +vn -0.1324 -0.3310 -0.9343 +vn 0.9594 0.2815 0.0166 +vn 0.9605 0.2736 0.0509 +vn 0.5223 0.4119 -0.7467 +vn -0.9281 0.0840 -0.3628 +vn 0.4640 0.2483 0.8503 +vn -0.0424 0.9807 0.1910 +vn -0.5634 -0.4470 0.6949 +vn 0.2746 0.8780 -0.3920 +vn 0.2487 0.7496 -0.6134 +vn 0.5661 0.7087 0.4211 +vn 0.3836 0.8565 0.3453 +vn -0.5901 0.7830 -0.1969 +vn 0.0154 0.9903 0.1379 +vn 0.6784 -0.7335 -0.0416 +vn 0.5268 -0.7773 0.3440 +vn 0.5140 -0.7880 0.3389 +vn -0.9647 0.1901 0.1821 +vn -0.9647 0.1900 0.1821 +vn 0.0095 0.7218 0.6920 +vn 0.1747 0.7161 0.6758 +vn -0.8359 -0.3071 -0.4550 +vn -0.6678 -0.3434 -0.6603 +vn -0.8021 -0.3936 -0.4491 +vn -0.3812 0.8205 0.4261 +vn -0.1645 0.8274 0.5369 +vn 0.9601 0.2784 0.0252 +vn 0.9623 0.2703 0.0306 +vn -0.4456 -0.8006 0.4006 +vn -0.5804 -0.7805 0.2322 +vn 0.9157 0.3921 0.0881 +vn 0.9213 0.3752 0.1024 +vn -0.2243 0.0190 0.9743 +vn 0.9878 0.1553 -0.0060 +vn 0.9789 -0.0736 -0.1907 +vn -0.2098 0.9694 0.1272 +vn -0.3712 -0.5001 -0.7824 +vn -0.1783 -0.5404 -0.8223 +vn -0.1010 -0.5531 -0.8270 +vn 0.2220 -0.8389 0.4970 +vn -0.0130 -0.7899 0.6131 +vn 0.0238 -0.8403 0.5416 +vn 0.0568 0.7453 -0.6643 +vn -0.9453 0.1242 -0.3017 +vn -0.0724 0.9343 0.3492 +vn 0.0471 0.9863 -0.1579 +vn 0.1123 0.4564 0.8827 +vn -0.1303 0.8120 -0.5689 +vn 0.8833 0.4675 -0.0356 +vn -0.1303 -0.9828 0.1308 +vn -0.6448 -0.2680 0.7158 +vn 0.9242 0.3659 0.1091 +vn 0.9294 0.3502 0.1161 +vn 0.8153 0.3683 -0.4468 +vn 0.6019 0.7768 -0.1855 +vn 0.0798 0.9711 0.2250 +vn 0.2858 0.4608 0.8402 +vn -0.8473 0.3935 -0.3568 +vn 0.4801 0.0809 0.8735 +vn 0.9358 -0.1009 0.3379 +vn -0.9087 0.0867 0.4083 +vn -0.2313 -0.8515 0.4706 +vn -0.8319 -0.4703 -0.2946 +vn 0.2137 0.8138 -0.5404 +vn 0.1303 0.9828 0.1308 +vn 0.1303 0.9828 0.1307 +vn 0.1021 0.1117 -0.9885 +vn 0.0480 0.1270 -0.9907 +vn 0.7322 -0.5269 -0.4316 +vn 0.7002 -0.5319 -0.4763 +vn -0.6428 -0.3061 0.7022 +vn -0.5200 0.6278 0.5793 +vn 0.3706 0.8964 -0.2430 +vn -0.5542 -0.6486 -0.5217 +vn 0.0140 -0.1264 0.9919 +vn -0.2948 0.7764 0.5570 +vn 0.6660 0.7343 -0.1313 +vn -0.9916 -0.0140 0.1289 +vn 0.0449 0.9888 0.1426 +vn 0.0555 0.9894 0.1344 +vn 0.3678 -0.6413 0.6734 +vn -0.8556 0.0084 0.5176 +vn -0.8629 0.0278 0.5046 +vn -0.9625 -0.1017 0.2515 +vn -0.0294 -0.9971 0.0696 +vn 0.2367 -0.9700 0.0556 +vn -0.7594 0.5048 0.4105 +vn -0.4020 0.5686 0.7177 +vn 0.5346 0.5960 -0.5991 +vn -0.9938 -0.0686 0.0876 +vn 0.4393 0.0585 0.8964 +vn 0.1999 0.8781 0.4348 +vn -0.1815 -0.4132 -0.8924 +vn -0.3420 0.9156 0.2113 +vn -0.9255 0.1885 -0.3286 +vn -0.2701 -0.8225 -0.5005 +vn -0.6353 0.7385 -0.2261 +vn -0.4685 0.8165 0.3374 +vn 0.0075 0.8062 -0.5916 +vn 0.0613 0.9049 -0.4213 +vn -0.4034 0.5725 -0.7138 +vn 0.1999 0.8781 -0.4348 +vn 0.1084 0.9845 0.1381 +vn 0.9789 -0.0736 0.1907 +vn -0.9904 0.1229 0.0640 +vn -0.9996 -0.0234 -0.0174 +vn 0.1658 -0.6896 0.7050 +vn -0.7828 0.1079 -0.6128 +vn 0.2010 -0.5350 0.8206 +vn 0.4992 -0.5624 0.6592 +vn 0.4713 -0.5197 0.7126 +vn -0.5687 -0.5973 0.5655 +vn -0.8106 -0.3611 0.4610 +vn -0.6678 -0.3434 0.6603 +vn -0.9969 -0.0661 0.0417 +vn 0.4751 -0.3412 -0.8111 +vn 0.6495 -0.5338 -0.5415 +vn 0.6064 -0.5867 -0.5367 +vn -0.0119 -0.5169 -0.8560 +vn -0.5448 0.8039 0.2384 +vn -0.4255 0.9050 -0.0053 +vn -0.2391 0.9304 0.2779 +vn -0.3376 0.9354 0.1054 +vn 0.2336 0.3891 0.8911 +vn -0.9647 0.1901 -0.1821 +vn -0.9647 0.1900 -0.1821 +vn -0.9952 0.0544 0.0817 +vn -0.9870 0.0060 -0.1606 +vn -0.9876 0.0043 -0.1570 +vn 0.7421 -0.2091 -0.6368 +vn 0.6160 -0.1927 -0.7638 +vn -0.9069 0.1223 0.4032 +vn -0.1855 -0.7000 0.6896 +vn 0.3123 -0.1562 -0.9370 +vn -0.0754 -0.9886 -0.1305 +vn 0.3756 0.9245 0.0654 +vn -0.3717 0.4271 0.8243 +vn 0.2130 0.8262 -0.5215 +vn 0.2469 0.4702 -0.8473 +vn 0.4326 0.4060 -0.8050 +vn -0.1271 0.1854 -0.9744 +vn 0.9214 -0.3716 0.1135 +vn 0.7856 -0.4888 0.3794 +vn 0.7214 0.1193 -0.6822 +vn 0.6177 0.1789 -0.7658 +vn 0.4892 0.2865 -0.8237 +vn 0.9604 0.2775 0.0263 +vn 0.7082 0.6921 -0.1394 +vn -0.7828 0.1079 0.6128 +vn -0.9938 -0.0686 -0.0876 +vn 0.2684 -0.7800 -0.5653 +vn -0.4241 0.1101 -0.8989 +vn -0.7229 0.5913 -0.3575 +vn -0.5687 -0.8108 -0.1382 +vn -0.6906 -0.2705 -0.6708 +vn 0.9320 -0.1664 0.3219 +vn -0.5496 0.6278 -0.5512 +vn -0.3728 0.9033 -0.2122 +vn 0.8711 0.4530 -0.1898 +vn 0.3031 0.1091 0.9467 +vn 0.5561 0.0844 0.8268 +vn 0.9616 0.2723 0.0337 +vn -0.5328 -0.7643 -0.3633 +vn -0.3264 0.4178 -0.8479 +vn -0.2761 0.6646 -0.6943 +vn -0.7479 -0.6296 0.2106 +vn 0.5178 0.0455 -0.8543 +vn -0.6604 -0.2146 0.7196 +vn -0.6417 -0.2362 0.7297 +vn -0.0901 0.5834 -0.8072 +vn 0.0649 0.6428 -0.7633 +vn 0.3667 -0.9247 0.1024 +vn -0.1663 0.4655 -0.8693 +vn -0.0453 0.1696 -0.9845 +vn 0.4700 0.8516 0.2322 +vn 0.2134 -0.1438 0.9663 +vn -0.2564 0.5624 -0.7861 +vn -0.2795 -0.4309 -0.8580 +vn 0.6787 -0.7327 -0.0490 +vn 0.5761 -0.7190 -0.3888 +vn -0.4191 -0.4004 0.8149 +vn -0.1503 0.5643 0.8118 +vn 0.1458 0.1185 -0.9822 +vn -0.6906 -0.2705 0.6708 +vn 0.1181 -0.9656 -0.2315 +vn 0.4076 -0.9024 -0.1397 +vn 0.3159 -0.9465 0.0653 +vn -0.1464 -0.1195 0.9820 +vn 0.5918 0.3091 -0.7445 +vn 0.7491 -0.0729 -0.6584 +vn 0.2243 -0.8898 -0.3974 +vn 0.3046 0.0414 0.9516 +vn -0.8535 -0.2483 0.4582 +vn -0.9526 -0.1209 0.2791 +vn 0.8110 -0.3645 -0.4576 +vn -0.5867 0.6428 0.4926 +vn -0.1540 0.0362 0.9874 +vn -0.1449 -0.1116 -0.9831 +vn -0.7149 -0.6992 0.0055 +vn 0.0565 0.9972 -0.0486 +vn 0.0328 0.9769 -0.2110 +vn 0.0281 0.9985 -0.0466 +vn -0.0348 0.9270 -0.3734 +vn 0.6821 0.0668 -0.7282 +vn 0.2677 0.4314 -0.8615 +vn 0.2144 0.3961 -0.8928 +vn -0.1239 0.2982 -0.9464 +vn 0.4318 0.6592 0.6156 +vn 0.5204 0.7187 0.4611 +vn 0.4401 0.7459 0.5000 +vn 0.5276 0.8490 -0.0277 +vn 0.4716 -0.0403 0.8809 +vn 0.4706 -0.0992 0.8768 +vn 0.5393 -0.0670 0.8395 +vn 0.0983 0.9859 0.1356 +vn 0.0466 0.9878 0.1485 +vn 0.3126 0.9107 0.2700 +vn 0.4905 0.7993 0.3471 +vn 0.4502 0.8650 0.2215 +vn 0.1730 0.9790 0.1077 +vn 0.0897 0.9947 -0.0494 +vn 0.6419 0.3037 -0.7041 +vn 0.3515 0.2221 -0.9095 +vn 0.1449 0.1116 0.9831 +vn 0.1448 0.1116 0.9831 +vn 0.6521 0.7186 0.2417 +vn -0.9875 0.1577 0.0042 +vn -0.9922 0.1180 0.0389 +vn -0.9527 0.3006 0.0437 +vn 0.7814 -0.1398 0.6082 +vn -0.9969 0.0662 -0.0425 +vn -0.9855 0.1608 -0.0534 +vn 0.0503 0.1853 0.9814 +vn 0.0539 0.2770 0.9594 +vn -0.0092 0.2828 0.9591 +vn 0.1508 0.7965 0.5856 +vn 0.1276 0.8220 0.5550 +vn 0.1331 0.7443 0.6545 +vn 0.0499 -0.5323 -0.8451 +vn -0.7997 0.5954 0.0778 +vn -0.5580 0.8113 0.1744 +vn -0.5456 0.8354 0.0665 +vn 0.8385 0.5315 0.1199 +vn 0.8702 0.4885 0.0647 +vn 0.8482 0.5241 0.0769 +vn 0.2277 0.8115 0.5381 +vn 0.2616 0.7893 0.5556 +vn 0.2415 0.7805 0.5766 +vn 0.6394 0.0378 0.7680 +vn 0.6183 0.1149 0.7775 +vn -0.5809 0.7035 0.4095 +vn -0.5722 0.7722 0.2763 +vn -0.8057 0.5618 0.1875 +vn 0.2468 0.8206 0.5154 +vn 0.3031 0.1091 -0.9467 +vn 0.5140 -0.7880 -0.3389 +vn 0.2220 -0.8389 -0.4970 +vn -0.0502 0.8795 0.4733 +vn -0.1325 0.8667 0.4810 +vn -0.0528 0.8696 0.4909 +vn -0.4255 0.9050 0.0053 +vn -0.9824 -0.0535 0.1792 +vn 0.2871 0.9523 0.1031 +vn 0.4145 0.9097 0.0239 +vn 0.3270 0.9439 0.0467 +vn -0.2087 -0.9475 0.2421 +vn 0.9016 -0.1287 0.4130 +vn 0.6756 0.2085 -0.7072 +vn 0.1236 0.9829 -0.1363 +vn 0.1290 0.9566 -0.2612 +vn 0.1107 0.9841 -0.1392 +vn 0.2908 -0.1623 0.9429 +vn -0.9873 -0.0041 0.1587 +vn -0.9844 0.0710 0.1610 +vn -0.9929 0.0292 0.1154 +vn -0.6430 0.7474 0.1671 +vn -0.6414 -0.4523 -0.6197 +vn -0.0641 0.2501 0.9661 +vn -0.1279 0.3080 0.9428 +vn -0.0866 0.2221 0.9712 +vn -0.0141 0.8318 0.5549 +vn 0.0330 0.8487 0.5278 +vn 0.0122 0.8540 0.5202 +vn -0.9863 0.0082 0.1649 +vn -0.9849 0.0073 0.1729 +vn -0.9532 0.0437 0.2993 +vn 0.0611 0.4471 0.8924 +vn 0.1083 0.8779 0.4665 +vn 0.1196 0.8699 0.4786 +vn 0.1203 0.8585 0.4986 +vn -0.6241 0.7738 -0.1083 +vn -0.8316 0.5535 -0.0462 +vn -0.6883 0.7178 0.1044 +vn -0.3360 0.1653 0.9272 +vn -0.2240 0.1788 0.9580 +vn -0.5355 0.1598 0.8293 +vn -0.9433 0.3180 0.0954 +vn -0.9492 0.2753 0.1523 +vn -0.8183 0.4995 0.2844 +vn -0.5567 -0.2907 -0.7782 +vn 0.2600 -0.5513 0.7928 +vn 0.2701 0.8225 -0.5005 +vn 0.0474 0.7198 0.6926 +vn -0.0572 0.5611 0.8258 +vn 0.0525 0.6126 0.7886 +vn -0.0264 0.9063 0.4219 +vn 0.0183 0.8884 0.4588 +vn 0.0635 0.9065 0.4175 +vn 0.1419 0.8404 0.5231 +vn 0.1250 0.8503 0.5111 +vn 0.0697 0.9751 -0.2106 +vn -0.0187 0.9987 -0.0476 +vn 0.0643 0.9639 -0.2582 +vn 0.0744 0.9878 -0.1371 +vn 0.0871 0.9856 -0.1450 +vn 0.6868 0.3470 0.6387 +vn 0.6138 0.4142 0.6721 +vn 0.4964 0.2614 0.8278 +vn -0.0179 0.9901 0.1390 +vn -0.1069 0.9920 -0.0666 +vn -0.6435 -0.4380 0.6278 +vn 0.0102 0.9909 -0.1341 +vn 0.0146 0.9681 -0.2500 +vn 0.0031 0.9915 -0.1297 +vn 0.7352 0.6343 0.2389 +vn 0.6945 0.6908 0.2009 +vn 0.6167 0.7457 0.2522 +vn 0.3933 -0.1537 -0.9065 +vn -0.9887 0.1182 0.0926 +vn -0.3235 0.8489 -0.4180 +vn -0.4734 0.1776 -0.8627 +vn 0.2754 0.4163 0.8665 +vn 0.1875 0.2845 0.9402 +vn 0.2418 0.2544 0.9364 +vn 0.1212 0.8514 0.5103 +vn 0.1220 0.8958 0.4273 +vn 0.1063 0.8906 0.4422 +vn 0.8953 0.2634 0.3592 +vn 0.7997 0.2080 0.5633 +vn 0.8210 0.1497 0.5510 +vn 0.0442 0.0756 0.9962 +vn 0.2777 -0.6628 -0.6954 +vn 0.7421 -0.2091 0.6368 +vn -0.3027 0.3244 -0.8962 +vn -0.5362 0.4218 -0.7311 +vn 0.3211 -0.9344 0.1541 +vn -0.1480 0.0546 0.9875 +vn -0.9643 0.2451 -0.1005 +vn -0.9854 0.1260 -0.1143 +vn 0.9408 0.1514 0.3033 +vn 0.9680 0.1886 0.1654 +vn 0.9485 0.1889 0.2541 +vn 0.9055 0.4210 -0.0527 +vn 0.9371 0.3484 -0.0221 +vn 0.9103 0.4079 -0.0709 +vn 0.5342 0.1166 -0.8373 +vn -0.0663 -0.1216 0.9904 +vn -0.3754 -0.0731 0.9240 +vn -0.9571 0.2788 -0.0786 +vn 0.7884 -0.3777 0.4856 +vn 0.5420 -0.1811 -0.8207 +vn 0.3650 -0.1702 -0.9153 +vn 0.0329 0.9879 -0.1517 +vn 0.0222 0.9893 -0.1442 +vn 0.2858 0.4608 -0.8402 +vn 0.2558 0.4480 -0.8566 +vn 0.0142 0.4567 -0.8895 +vn 0.4917 0.3291 0.8062 +vn 0.1047 0.8031 0.5865 +vn -0.3513 0.5398 0.7650 +vn -0.5510 0.4087 0.7276 +vn -0.8072 0.2121 0.5508 +vn -0.5363 0.3123 0.7841 +vn -0.7382 0.5106 0.4408 +vn 0.7023 0.2308 -0.6734 +vn 0.4992 -0.7979 -0.3378 +vn 0.6507 -0.7573 0.0558 +vn 0.1732 0.5937 0.7858 +vn 0.3021 0.5692 0.7647 +vn 0.9725 0.2316 -0.0250 +vn 0.9666 0.2494 0.0596 +vn 0.2587 0.1146 0.9591 +vn 0.2153 0.0785 0.9734 +vn 0.2696 0.0526 0.9615 +vn -0.9216 0.0607 0.3833 +vn 0.3194 0.0664 0.9453 +vn 0.3625 0.1972 0.9109 +vn 0.3210 0.2722 0.9071 +vn 0.9765 0.1845 0.1111 +vn 0.8775 0.1071 -0.4675 +vn -0.8359 -0.3071 0.4550 +vn -0.8514 -0.4307 0.2995 +vn 0.7440 0.6387 0.1961 +vn 0.1173 0.8461 0.5200 +vn 0.1099 0.8343 0.5403 +vn 0.9587 -0.2780 -0.0605 +vn -0.9776 0.1544 0.1429 +vn -0.1039 0.4550 0.8844 +vn 0.1723 0.0967 0.9803 +vn 0.3560 0.0964 0.9295 +vn -0.2762 -0.9255 -0.2592 +vn -0.6070 0.7817 -0.1430 +vn 0.1448 0.1116 -0.9831 +vn -0.1601 -0.7816 0.6028 +vn 0.4499 0.0845 0.8891 +vn -0.2172 0.9218 0.3211 +vn -0.3800 0.8342 0.3996 +vn -0.1290 0.9320 0.3387 +vn 0.8087 0.5432 0.2258 +vn 0.7928 0.5810 0.1841 +vn 0.7736 0.6037 0.1925 +vn 0.0160 -0.1372 0.9904 +vn 0.1303 0.9828 -0.1307 +vn 0.1303 0.9828 -0.1308 +vn 0.7507 0.2656 0.6049 +vn 0.7473 0.4445 0.4939 +vn -0.0043 0.4571 0.8894 +vn 0.1166 0.9081 0.4022 +vn -0.8130 0.0827 0.5763 +vn 0.3646 0.1016 0.9256 +vn 0.4348 0.1089 0.8939 +vn 0.3211 -0.9344 -0.1541 +vn -0.4270 0.8860 -0.1810 +vn -0.5071 0.7063 -0.4941 +vn -0.6281 0.7559 -0.1848 +vn 0.5150 0.4532 -0.7276 +vn 0.3628 0.0884 0.9277 +vn 0.3443 0.0900 0.9345 +vn 0.2010 -0.5350 -0.8206 +vn -0.4619 -0.2969 0.8358 +vn -0.4289 -0.2521 0.8675 +vn -0.1015 -0.9818 0.1605 +vn -0.6735 -0.4710 -0.5697 +vn -0.7195 -0.5553 -0.4170 +vn -0.7085 -0.4227 -0.5651 +vn 0.8530 0.1169 0.5087 +vn 0.7675 0.5356 0.3523 +vn 0.6824 0.6348 0.3625 +vn 0.6880 0.5886 0.4245 +vn -0.7298 -0.5731 0.3727 +vn 0.0556 -0.2966 0.9534 +vn 0.4977 0.4935 0.7133 +vn 0.4349 0.3484 0.8304 +vn 0.3157 0.8045 0.5031 +vn 0.3243 0.7837 0.5297 +vn 0.3764 0.7989 0.4691 +vn -0.9818 0.0604 -0.1801 +vn 0.9036 0.4219 0.0744 +vn 0.8592 0.4880 0.1535 +vn 0.8966 0.4428 0.0003 +vn 0.8921 0.4514 0.0200 +vn -0.1913 0.9744 0.1185 +vn -0.2564 0.3508 0.9007 +vn -0.2727 0.4685 0.8403 +vn -0.3077 0.9299 0.2015 +vn 0.2224 0.9222 0.3165 +vn 0.3146 0.8583 0.4054 +vn -0.3469 -0.7768 0.5255 +vn 0.2148 0.8711 0.4417 +vn 0.2244 0.8477 0.4806 +vn 0.2243 0.8509 0.4750 +vn 0.3706 0.8964 0.2430 +vn -0.3147 0.6844 0.6577 +vn -0.3200 0.7575 0.5690 +vn -0.5800 0.6435 0.4995 +vn 0.1006 0.9838 -0.1484 +vn 0.3167 0.7661 0.5593 +vn -0.0603 0.9465 0.3171 +vn -0.3977 0.9173 0.0180 +vn -0.7047 -0.3612 -0.6106 +vn -0.9450 0.1150 0.3063 +vn 0.0583 0.9904 -0.1251 +vn 0.0572 0.9902 -0.1273 +vn 0.0586 0.9897 -0.1309 +vn -0.9219 0.0716 0.3809 +vn -0.1724 -0.8391 -0.5160 +vn 0.0678 0.9886 -0.1346 +vn 0.0612 0.9892 -0.1330 +vn 0.0712 0.8927 0.4450 +vn 0.1131 0.8916 0.4384 +vn 0.1347 0.9314 0.3383 +vn -0.8099 0.1403 0.5695 +vn -0.6561 0.2562 0.7098 +vn 0.3143 0.8117 0.4923 +vn 0.3156 0.8158 0.4846 +vn 0.1341 0.5034 -0.8536 +vn 0.2452 0.8236 0.5115 +vn 0.0461 0.9904 -0.1303 +vn -0.7483 -0.6278 -0.2141 +vn -0.7170 -0.6678 -0.1999 +vn -0.4975 -0.8648 0.0685 +vn 0.3686 -0.0001 0.9296 +vn -0.7235 -0.6524 -0.2254 +vn 0.0679 0.7986 0.5980 +vn -0.0052 0.7528 0.6583 +vn 0.5917 0.7941 0.1392 +vn 0.5369 0.8289 0.1570 +vn 0.6208 0.7568 0.2047 +vn -0.2954 0.5863 0.7543 +vn 0.0666 -0.9968 0.0449 +vn 0.4324 -0.8953 -0.1075 +vn 0.2003 -0.9793 -0.0286 +vn -0.8171 0.3401 0.4655 +vn 0.6669 0.0059 0.7452 +vn 0.8299 0.3707 0.4170 +vn 0.5382 0.6150 0.5763 +vn 0.2760 0.8500 0.4487 +vn 0.3136 0.8366 0.4491 +vn 0.1086 0.9868 -0.1201 +vn 0.1085 0.9862 -0.1251 +vn -0.1089 0.9744 -0.1965 +vn 0.2527 0.6989 0.6691 +vn 0.3345 0.6893 0.6426 +vn 0.3131 0.9426 -0.1160 +vn -0.4119 0.5372 0.7360 +vn -0.0091 0.9475 0.3196 +vn -0.5638 0.4961 0.6603 +vn -0.9966 0.0809 -0.0164 +vn 0.1834 0.9535 -0.2392 +vn -0.0790 0.9850 -0.1533 +vn -0.1078 -0.9753 0.1927 +vn 0.1557 0.4437 0.8826 +vn 0.1209 0.9588 -0.2570 +vn 0.9295 0.2177 0.2976 +vn -0.2568 0.9444 -0.2052 +vn -0.1162 0.9387 -0.3247 +vn -0.2597 0.9404 -0.2196 +vn 0.1544 0.8933 0.4221 +vn 0.0270 0.9722 -0.2325 +vn 0.0450 0.9729 -0.2270 +vn 0.2285 0.8374 0.4965 +vn 0.2406 0.8298 0.5035 +vn -0.3712 -0.5001 0.7824 +vn 0.1657 0.9848 -0.0519 +vn 0.1900 0.9788 -0.0761 +vn 0.1639 0.9821 -0.0927 +vn -0.9086 0.4176 0.0061 +vn -0.7905 0.6124 0.0099 +vn -0.5185 0.8533 0.0550 +vn -0.5681 0.0691 0.8200 +vn -0.4408 0.1305 0.8881 +vn 0.2373 0.9423 -0.2360 +vn 0.1658 0.9762 -0.1397 +vn 0.1714 0.9764 -0.1318 +vn 0.1344 0.9656 -0.2228 +vn 0.0764 0.9599 -0.2699 +vn 0.2991 0.5086 -0.8074 +vn 0.5788 0.1990 0.7908 +vn -0.2319 0.8763 0.4222 +vn -0.3392 0.8880 0.3105 +vn -0.9994 0.0251 0.0240 +vn 0.8866 0.2304 0.4011 +vn -0.7249 0.1845 0.6637 +vn 0.2253 0.8422 0.4898 +vn 0.2207 0.8361 0.5023 +vn -0.5870 0.5724 0.5725 +vn -0.8442 0.4147 0.3396 +vn 0.0578 0.9912 -0.1192 +vn -0.0941 0.9723 -0.2141 +vn -0.0441 0.9749 -0.2181 +vn 0.4578 0.0544 0.8874 +vn 0.1364 0.9742 -0.1797 +vn 0.1670 0.9634 -0.2097 +vn 0.0393 0.8456 0.5323 +vn 0.0423 0.8408 0.5397 +vn -0.9319 0.3540 -0.0788 +vn -0.6195 -0.0561 0.7830 +vn -0.0590 0.9463 -0.3179 +vn -0.0148 0.9534 -0.3013 +vn 0.1901 0.8894 0.4156 +vn -0.0242 0.8852 0.4646 +vn 0.1053 0.9689 -0.2240 +vn 0.7168 0.6761 0.1705 +vn 0.7300 0.6524 0.2036 +vn -0.3203 0.8150 0.4829 +vn 0.9850 0.1635 0.0553 +vn 0.9863 0.1633 0.0253 +vn 0.6330 0.7540 0.1755 +vn 0.5819 0.0275 0.8128 +vn -0.9762 0.1042 0.1901 +vn 0.7807 -0.1132 -0.6146 +vn -0.8833 0.4602 -0.0892 +vn -0.7892 0.5954 -0.1503 +vn 0.8859 0.4227 0.1912 +vn 0.8293 0.4807 0.2850 +vn 0.9359 0.3129 0.1620 +vn 0.8869 0.3798 0.2629 +vn 0.7114 0.5099 0.4835 +vn 0.7899 0.4754 0.3875 +vn 0.1474 0.8219 0.5503 +vn 0.1459 0.8342 0.5317 +vn 0.1612 0.9060 0.3914 +vn 0.3870 0.5010 0.7741 +vn 0.2047 0.7836 0.5865 +vn 0.2226 0.7714 0.5962 +vn 0.1909 0.7240 0.6628 +vn 0.3422 0.6541 0.6746 +vn -0.9687 0.0061 0.2482 +vn -0.8686 0.1217 0.4804 +vn 0.6056 0.5549 0.5704 +vn 0.5946 0.6867 0.4181 +vn -0.0944 0.1294 -0.9871 +vn -0.0022 0.9766 -0.2151 +vn -0.0293 0.1789 0.9834 +vn -0.0514 0.3185 0.9465 +vn -0.2362 0.2275 0.9447 +vn -0.7848 0.5980 0.1628 +vn 0.3324 0.8280 0.4515 +vn 0.3200 0.8197 0.4751 +vn -0.7235 -0.6524 0.2254 +vn 0.1081 0.9842 -0.1404 +vn 0.8927 0.1671 0.4185 +vn 0.8252 0.0625 0.5614 +vn 0.8115 0.5660 0.1453 +vn 0.8280 0.5523 0.0968 +vn 0.8547 -0.3218 0.4073 +vn -0.9997 -0.0039 -0.0225 +vn -0.9995 0.0034 -0.0300 +vn 0.0694 0.9962 -0.0533 +vn 0.1946 0.9548 -0.2246 +vn 0.3017 0.9216 -0.2441 +vn -0.0329 0.9779 -0.2065 +vn 0.2235 0.9466 -0.2325 +vn 0.9536 -0.2735 0.1260 +vn -0.9536 0.2735 -0.1260 +vn 0.0436 0.9771 -0.2082 +vn -0.9615 0.2578 0.0952 +vn -0.2473 0.9654 -0.0831 +vn 0.1085 0.9854 -0.1309 +vn 0.1085 0.9855 -0.1304 +vn -0.9933 -0.0329 0.1104 +vn -0.9969 -0.0427 0.0655 +vn 0.5629 -0.6270 0.5386 +vn -0.8415 -0.5345 0.0784 +vn -0.8333 -0.5460 0.0859 +vn -0.0093 0.9925 -0.1220 +vn -0.0067 0.9927 -0.1205 +vn -0.1741 0.1419 -0.9745 +vn 0.4664 0.8781 0.1067 +vn 0.4397 0.8715 -0.2170 +vn 0.3341 0.9201 -0.2045 +vn 0.2699 0.9461 -0.1790 +vn 0.3067 0.7909 0.5295 +vn -0.1178 0.9839 0.1342 +vn 0.9320 -0.1665 -0.3219 +vn 0.9320 -0.1664 -0.3219 +vn 0.2339 0.8653 0.4433 +vn -0.2864 0.9572 0.0407 +vn 0.1342 0.9815 -0.1363 +vn 0.1469 0.9792 -0.1397 +vn -0.1566 -0.0442 -0.9867 +vn -0.1554 -0.0453 -0.9868 +vn -0.2044 0.0003 -0.9789 +vn 0.1222 0.9687 -0.2160 +vn 0.1647 0.1380 0.9766 +vn 0.1089 0.1730 0.9789 +vn -0.6062 0.1059 0.7882 +vn 0.0125 0.9783 -0.2070 +vn 0.1086 0.9861 -0.1255 +vn -0.4878 -0.7514 0.4444 +vn 0.4803 -0.3443 -0.8067 +vn -0.3334 -0.7509 -0.5701 +vn 0.0630 0.9745 -0.2153 +vn 0.2234 0.8639 0.4514 +vn 0.8580 0.0302 0.5127 +vn 0.6218 0.7534 0.2140 +vn 0.6276 0.7583 0.1764 +vn -0.8016 0.4183 0.4271 +vn -0.7632 0.4419 0.4715 +vn -0.9898 -0.0884 0.1120 +vn -0.9558 0.2865 -0.0654 +vn -0.8792 0.4694 -0.0818 +vn -0.5851 0.6712 0.4552 +vn -0.7149 0.4411 0.5426 +vn -0.9859 0.1425 0.0881 +vn -0.8474 0.5137 0.1340 +vn -0.5264 0.2156 0.8224 +vn 0.0113 0.9711 -0.2383 +vn 0.0407 0.8083 0.5874 +vn 0.3515 0.2221 0.9095 +vn -0.3254 0.8416 -0.4310 +vn -0.1847 0.8966 -0.4024 +vn 0.5629 -0.6270 -0.5386 +vn -0.7913 0.3902 -0.4708 +vn -0.0725 -0.1969 -0.9777 +vn -0.5626 0.8128 -0.1511 +vn -0.0491 -0.0221 -0.9985 +vn 0.8924 0.2071 -0.4010 +vn -0.3784 0.4856 -0.7880 +vn -0.2706 0.5550 -0.7866 +vn 0.8993 0.3202 0.2978 +vn 0.4713 -0.5197 -0.7126 +vn -0.9419 0.3348 -0.0280 +vn 0.0121 0.9567 -0.2910 +vn 0.7856 -0.4888 -0.3794 +vn 0.1336 0.9677 -0.2138 +vn -0.6448 -0.2680 -0.7158 +vn -0.6428 -0.3061 -0.7022 +vn 0.7543 0.0375 0.6555 +vn 0.1225 0.2719 0.9545 +vn -0.9886 -0.0514 0.1413 +vn -0.1355 0.7124 0.6885 +vn -0.7468 0.0379 0.6640 +vn 0.9536 -0.2735 0.1261 +vn -0.9963 0.0406 0.0756 +vn -0.9882 -0.0972 -0.1180 +vn 0.9740 -0.0449 -0.2219 +vn -0.0581 -0.8284 0.5570 +vn 0.1606 0.6809 -0.7145 +vn -0.7809 -0.5836 -0.2225 +vn -0.7709 -0.6353 0.0472 +vn -0.5891 -0.0805 -0.8040 +vn -0.6572 -0.0797 -0.7495 +vn -0.7109 -0.0621 -0.7005 +vn 0.0599 0.4891 -0.8702 +vn 0.0417 0.9589 -0.2807 +vn -0.1842 -0.0213 -0.9827 +vn -0.1464 -0.1195 -0.9820 +vn -0.7061 -0.6773 -0.2067 +vn 0.6781 0.5056 0.5334 +vn -0.7814 0.1398 0.6082 +vn 0.7505 0.5897 0.2983 +vn 0.7047 0.3612 -0.6106 +vn -0.4122 -0.2300 -0.8816 +vn -0.6573 -0.2787 -0.7002 +vn 0.9808 -0.1945 0.0115 +vn -0.4130 -0.1046 -0.9047 +vn -0.9536 0.2735 0.1260 +vn 0.9014 0.4316 -0.0330 +vn 0.1608 0.9764 -0.1439 +vn -0.5201 -0.7835 0.3401 +vn 0.0527 -0.9965 0.0653 +vn -0.5332 0.3748 0.7585 +vn -0.6214 0.7675 -0.1572 +vn -0.7586 0.6346 -0.1479 +vn -0.8074 0.5776 -0.1202 +vn -0.6075 0.2148 -0.7647 +vn -0.9965 -0.0312 -0.0781 +vn -0.9992 -0.0017 -0.0394 +vn -0.9968 -0.0297 -0.0740 +vn 0.0384 0.9781 -0.2045 +vn 0.8870 -0.0135 -0.4616 +vn -0.9992 -0.0021 -0.0407 +vn -0.1941 -0.2128 0.9576 +vn 0.6406 0.6984 0.3192 +vn -0.8500 0.1631 0.5009 +vn -0.1724 -0.8391 -0.5159 +vn -0.5989 -0.6902 0.4061 +vn 0.3040 -0.4476 0.8410 +vn 0.4076 -0.9024 0.1397 +vn 0.0878 0.9724 -0.2160 +vn -0.7664 0.4600 -0.4484 +vn -0.5479 0.4819 -0.6838 +vn 0.6595 0.7292 0.1826 +vn 0.6259 -0.0541 0.7781 +vn 0.1717 0.7901 0.5884 +vn -0.1779 -0.1254 0.9760 +vn -0.9087 0.0867 -0.4083 +vn -0.1458 -0.1185 0.9822 +vn -0.9394 0.2262 0.2576 +vn -0.9456 0.1725 0.2758 +vn 0.6965 0.6974 0.1689 +vn 0.3696 -0.8682 -0.3312 +vn -0.3334 -0.7509 0.5701 +vn 0.0642 0.8896 0.4522 +vn 0.9272 -0.0213 -0.3740 +vn -0.0580 -0.8284 -0.5570 +vn -0.9916 -0.0140 -0.1289 +vn -0.3027 0.3244 0.8962 +vn -0.4746 0.1359 -0.8696 +vn -0.9836 0.1741 -0.0461 +vn -0.2674 -0.1071 -0.9576 +vn 0.0140 -0.1264 -0.9919 +vn 0.2630 -0.5440 0.7968 +vn 0.1386 0.5459 0.8263 +vn -0.2065 0.5462 -0.8118 +vn 0.0584 0.9911 -0.1197 +vn 0.6532 0.7430 0.1458 +vn 0.6591 0.7392 0.1385 +vn -0.8943 0.4310 -0.1201 +vn -0.6043 0.5205 0.6032 +vn -0.8072 0.1048 0.5809 +vn 0.5431 0.8298 -0.1279 +vn 0.6187 -0.6885 -0.3785 +vn 0.5223 0.0691 0.8499 +vn 0.7368 0.0330 0.6753 +vn 0.1743 0.9766 -0.1260 +vn -0.9880 0.0034 0.1544 +vn 0.9594 0.2815 -0.0166 +vn 0.9605 0.2736 -0.0509 +vn -0.0424 0.9807 -0.1910 +vn 0.0154 0.9903 -0.1379 +vn 0.9601 0.2784 -0.0252 +vn 0.9623 0.2703 -0.0306 +vn 0.9157 0.3921 -0.0881 +vn 0.9213 0.3752 -0.1024 +vn -0.2243 0.0190 -0.9743 +vn 0.5450 -0.1504 -0.8249 +vn -0.7204 0.5022 -0.4784 +vn -0.1303 0.8120 0.5689 +vn 0.8833 0.4675 0.0356 +vn 0.9242 0.3659 -0.1091 +vn 0.9294 0.3502 -0.1161 +vn 0.3090 -0.4514 0.8371 +vn -0.2527 0.1318 0.9585 +vn 0.0798 0.9711 -0.2250 +vn 0.6288 0.7675 0.1249 +vn -0.1480 0.0546 -0.9875 +vn 0.2137 0.8138 0.5404 +vn 0.9685 -0.0980 0.2291 +vn 0.6660 0.7343 0.1313 +vn 0.0449 0.9888 -0.1426 +vn 0.0555 0.9894 -0.1344 +vn -0.2700 -0.8225 0.5005 +vn 0.3957 -0.7553 -0.5225 +vn -0.7365 -0.4344 0.5185 +vn 0.1084 0.9845 -0.1381 +vn -0.9996 -0.0234 0.0174 +vn 0.9536 -0.2735 -0.1260 +vn 0.9536 -0.2735 -0.1261 +vn -0.9969 -0.0661 -0.0417 +vn -0.5448 0.8039 -0.2384 +vn 0.6222 -0.2277 -0.7490 +vn -0.9952 0.0544 -0.0817 +vn -0.9870 0.0060 0.1606 +vn -0.9876 0.0043 0.1570 +vn 0.3123 -0.1562 0.9370 +vn 0.2130 0.8262 0.5215 +vn -0.1271 0.1854 0.9744 +vn 0.9604 0.2775 -0.0263 +vn -0.1941 -0.2128 -0.9576 +vn 0.9616 0.2723 -0.0337 +vn 0.5605 -0.5159 -0.6479 +vn -0.0453 0.1696 0.9845 +vn -0.4734 0.1776 -0.8628 +vn -0.0565 -0.9972 -0.0486 +vn -0.0331 -0.9932 -0.1118 +vn -0.0281 -0.9985 -0.0466 +vn -0.4318 -0.6592 0.6156 +vn -0.5204 -0.7187 0.4611 +vn -0.4401 -0.7459 0.5000 +vn -0.4716 0.0403 0.8809 +vn -0.4706 0.0992 0.8768 +vn -0.5393 0.0670 0.8395 +vn -0.0983 -0.9859 0.1356 +vn -0.0466 -0.9878 0.1485 +vn -0.3126 -0.9107 0.2700 +vn -0.4905 -0.7993 0.3471 +vn -0.4502 -0.8650 0.2215 +vn -0.1730 -0.9790 0.1077 +vn -0.0897 -0.9947 -0.0494 +vn 0.9875 -0.1577 0.0042 +vn 0.9922 -0.1180 0.0389 +vn 0.9527 -0.3006 0.0437 +vn 0.9969 -0.0662 -0.0425 +vn 0.9855 -0.1608 -0.0534 +vn -0.0503 -0.1853 0.9814 +vn -0.0539 -0.2770 0.9594 +vn 0.0092 -0.2828 0.9591 +vn -0.1508 -0.7965 0.5856 +vn -0.1276 -0.8220 0.5550 +vn -0.1331 -0.7443 0.6545 +vn 0.7997 -0.5954 0.0778 +vn 0.5580 -0.8113 0.1744 +vn 0.5456 -0.8354 0.0665 +vn -0.8385 -0.5315 0.1199 +vn -0.8702 -0.4885 0.0647 +vn -0.8482 -0.5241 0.0769 +vn -0.2277 -0.8115 0.5381 +vn -0.2616 -0.7893 0.5556 +vn -0.2416 -0.7805 0.5766 +vn -0.6394 -0.0378 0.7680 +vn -0.6183 -0.1149 0.7775 +vn 0.5809 -0.7035 0.4095 +vn 0.5722 -0.7722 0.2763 +vn 0.8057 -0.5618 0.1875 +vn -0.2468 -0.8206 0.5154 +vn 0.0502 -0.8795 0.4733 +vn 0.1325 -0.8667 0.4810 +vn 0.0528 -0.8696 0.4909 +vn -0.2871 -0.9523 0.1031 +vn -0.4145 -0.9097 0.0239 +vn -0.3270 -0.9439 0.0467 +vn -0.0808 -0.9698 -0.2302 +vn -0.1311 -0.9809 -0.1439 +vn -0.0311 -0.9731 -0.2283 +vn 0.9873 0.0041 0.1587 +vn 0.9844 -0.0710 0.1610 +vn 0.9929 -0.0292 0.1154 +vn 0.0641 -0.2501 0.9661 +vn 0.1279 -0.3080 0.9428 +vn 0.0866 -0.2221 0.9712 +vn 0.0141 -0.8318 0.5549 +vn -0.0330 -0.8487 0.5278 +vn -0.0123 -0.8540 0.5202 +vn 0.9863 -0.0082 0.1649 +vn 0.9849 -0.0073 0.1729 +vn 0.9532 -0.0437 0.2993 +vn -0.0611 -0.4471 0.8924 +vn -0.1083 -0.8779 0.4665 +vn -0.1196 -0.8699 0.4786 +vn -0.1203 -0.8585 0.4986 +vn 0.6241 -0.7738 -0.1083 +vn 0.8316 -0.5535 -0.0462 +vn 0.6883 -0.7178 0.1044 +vn 0.3360 -0.1653 0.9272 +vn 0.2240 -0.1788 0.9580 +vn 0.5355 -0.1598 0.8293 +vn 0.9433 -0.3180 0.0954 +vn 0.9492 -0.2753 0.1523 +vn 0.8183 -0.4995 0.2844 +vn -0.0474 -0.7198 0.6926 +vn 0.0572 -0.5611 0.8258 +vn -0.0525 -0.6126 0.7886 +vn 0.0264 -0.9063 0.4219 +vn -0.0184 -0.8884 0.4588 +vn -0.0635 -0.9065 0.4175 +vn -0.1418 -0.8404 0.5231 +vn -0.1250 -0.8504 0.5111 +vn -0.0189 -0.9935 -0.1119 +vn 0.0187 -0.9987 -0.0476 +vn -0.0653 -0.9872 -0.1453 +vn -0.0314 -0.9725 -0.2309 +vn -0.0837 -0.9682 -0.2356 +vn -0.6868 -0.3470 0.6387 +vn -0.6138 -0.4142 0.6721 +vn -0.4964 -0.2614 0.8278 +vn 0.0179 -0.9901 0.1390 +vn 0.1069 -0.9920 -0.0666 +vn 0.1341 -0.9633 -0.2324 +vn -0.0072 -0.9909 -0.1345 +vn -0.0031 -0.9915 -0.1297 +vn -0.7352 -0.6343 0.2389 +vn -0.6945 -0.6908 0.2009 +vn -0.6167 -0.7457 0.2522 +vn 0.9887 -0.1182 0.0926 +vn -0.2754 -0.4163 0.8665 +vn -0.1875 -0.2845 0.9402 +vn -0.2418 -0.2544 0.9364 +vn -0.1212 -0.8514 0.5103 +vn -0.1220 -0.8959 0.4273 +vn -0.1063 -0.8906 0.4422 +vn -0.8953 -0.2634 0.3592 +vn -0.7996 -0.2080 0.5633 +vn -0.8210 -0.1497 0.5510 +vn 0.9643 -0.2451 -0.1005 +vn 0.9854 -0.1260 -0.1143 +vn -0.9408 -0.1514 0.3033 +vn -0.9680 -0.1886 0.1654 +vn -0.9485 -0.1889 0.2541 +vn -0.9055 -0.4210 -0.0527 +vn -0.9371 -0.3484 -0.0221 +vn -0.9103 -0.4079 -0.0709 +vn 0.9571 -0.2788 -0.0786 +vn -0.0326 -0.9706 -0.2386 +vn 0.0193 -0.9710 -0.2384 +vn -0.1047 -0.8031 0.5865 +vn 0.5510 -0.4087 0.7276 +vn 0.8072 -0.2121 0.5508 +vn 0.5363 -0.3123 0.7841 +vn -0.1732 -0.5937 0.7858 +vn -0.3021 -0.5692 0.7647 +vn -0.9725 -0.2316 -0.0250 +vn -0.9666 -0.2494 0.0596 +vn -0.2587 -0.1146 0.9591 +vn -0.2153 -0.0785 0.9734 +vn -0.2697 -0.0526 0.9615 +vn -0.3194 -0.0664 0.9453 +vn -0.3625 -0.1972 0.9109 +vn -0.3210 -0.2722 0.9071 +vn -0.9765 -0.1845 0.1111 +vn -0.7440 -0.6387 0.1961 +vn -0.1173 -0.8461 0.5200 +vn -0.1099 -0.8343 0.5403 +vn 0.9776 -0.1544 0.1429 +vn 0.1039 -0.4550 0.8844 +vn 0.6070 -0.7817 -0.1430 +vn 0.2172 -0.9218 0.3211 +vn 0.3800 -0.8342 0.3996 +vn 0.1290 -0.9320 0.3387 +vn -0.8087 -0.5432 0.2258 +vn -0.7928 -0.5810 0.1841 +vn -0.7736 -0.6037 0.1925 +vn -0.7507 -0.2656 0.6049 +vn -0.7473 -0.4445 0.4939 +vn 0.0043 -0.4571 0.8894 +vn 0.8130 -0.0827 0.5763 +vn -0.3646 -0.1016 0.9256 +vn -0.4348 -0.1089 0.8939 +vn 0.4270 -0.8860 -0.1810 +vn 0.5071 -0.7062 -0.4941 +vn 0.6281 -0.7559 -0.1848 +vn -0.8530 -0.1169 0.5087 +vn -0.7675 -0.5356 0.3523 +vn -0.6824 -0.6348 0.3625 +vn -0.6880 -0.5886 0.4245 +vn -0.4977 -0.4935 0.7133 +vn -0.4349 -0.3484 0.8304 +vn -0.3157 -0.8045 0.5031 +vn -0.3243 -0.7837 0.5297 +vn -0.3764 -0.7989 0.4691 +vn -0.9036 -0.4219 0.0744 +vn -0.8592 -0.4880 0.1535 +vn -0.8966 -0.4427 0.0003 +vn -0.8921 -0.4514 0.0200 +vn 0.1913 -0.9744 0.1185 +vn 0.2564 -0.3508 0.9007 +vn 0.2727 -0.4685 0.8403 +vn 0.3077 -0.9299 0.2015 +vn -0.2224 -0.9222 0.3165 +vn -0.3146 -0.8583 0.4054 +vn -0.2148 -0.8711 0.4417 +vn -0.2244 -0.8477 0.4806 +vn -0.2244 -0.8509 0.4750 +vn 0.3147 -0.6844 0.6577 +vn 0.3200 -0.7575 0.5690 +vn 0.5800 -0.6435 0.4995 +vn -0.1432 -0.9598 -0.2415 +vn -0.3167 -0.7661 0.5593 +vn 0.3977 -0.9173 0.0180 +vn 0.9450 -0.1150 0.3063 +vn -0.0583 -0.9904 -0.1251 +vn -0.0572 -0.9902 -0.1273 +vn -0.0586 -0.9897 -0.1309 +vn 0.0210 -0.9731 -0.2295 +vn 0.0756 -0.9720 -0.2226 +vn -0.0712 -0.8927 0.4450 +vn -0.1131 -0.8916 0.4384 +vn -0.1347 -0.9314 0.3383 +vn 0.8099 -0.1404 0.5695 +vn 0.6561 -0.2562 0.7098 +vn -0.3143 -0.8117 0.4923 +vn -0.3157 -0.8158 0.4846 +vn -0.2452 -0.8236 0.5115 +vn 0.1663 -0.9640 -0.2074 +vn -0.3686 0.0001 0.9296 +vn -0.0679 -0.7986 0.5980 +vn 0.0052 -0.7528 0.6583 +vn -0.5917 -0.7941 0.1392 +vn -0.5369 -0.8289 0.1570 +vn -0.6208 -0.7568 0.2047 +vn 0.2954 -0.5863 0.7543 +vn -0.0666 0.9968 0.0449 +vn 0.8171 -0.3401 0.4655 +vn -0.6669 -0.0059 0.7452 +vn -0.8299 -0.3707 0.4170 +vn -0.5382 -0.6150 0.5763 +vn -0.2761 -0.8500 0.4487 +vn -0.3136 -0.8366 0.4491 +vn -0.1086 -0.9868 -0.1201 +vn -0.1085 -0.9862 -0.1251 +vn -0.1086 -0.9869 -0.1196 +vn -0.2527 -0.6989 0.6691 +vn -0.3345 -0.6893 0.6426 +vn 0.0091 -0.9475 0.3196 +vn 0.5638 -0.4961 0.6603 +vn 0.0806 -0.9847 -0.1547 +vn 0.0790 -0.9850 -0.1533 +vn -0.1557 -0.4437 0.8826 +vn 0.0816 -0.9845 -0.1554 +vn -0.9295 -0.2177 0.2976 +vn 0.2568 -0.9443 -0.2057 +vn 0.1653 -0.9715 -0.1701 +vn 0.2597 -0.9403 -0.2200 +vn -0.1544 -0.8933 0.4221 +vn 0.0213 -0.9925 -0.1200 +vn 0.0443 -0.9923 -0.1158 +vn -0.2285 -0.8374 0.4965 +vn -0.2406 -0.8298 0.5036 +vn -0.1657 -0.9848 -0.0519 +vn -0.1900 -0.9788 -0.0761 +vn -0.2857 -0.9524 0.1063 +vn 0.9086 -0.4176 0.0061 +vn 0.7905 -0.6124 0.0099 +vn 0.5185 -0.8533 0.0550 +vn 0.5681 -0.0691 0.8200 +vn 0.4408 -0.1305 0.8881 +vn -0.2484 -0.9666 -0.0626 +vn -0.3530 -0.8960 -0.2693 +vn -0.1714 -0.9764 -0.1318 +vn 0.0700 -0.9873 -0.1428 +vn 0.0830 -0.9842 -0.1561 +vn -0.5788 -0.1990 0.7908 +vn 0.2319 -0.8764 0.4222 +vn 0.3392 -0.8880 0.3105 +vn 0.9994 -0.0251 0.0240 +vn -0.8866 -0.2304 0.4011 +vn -0.2253 -0.8422 0.4898 +vn -0.2207 -0.8361 0.5023 +vn 0.5870 -0.5724 0.5725 +vn 0.8442 -0.4147 0.3396 +vn -0.0578 -0.9912 -0.1192 +vn -0.0591 -0.9920 -0.1118 +vn -0.0542 -0.9922 -0.1121 +vn -0.4578 -0.0544 0.8874 +vn -0.1348 -0.9900 -0.0424 +vn -0.1151 -0.9899 -0.0825 +vn -0.0393 -0.8456 0.5323 +vn -0.0423 -0.8408 0.5397 +vn 0.1118 -0.9804 -0.1620 +vn 0.0899 -0.9832 -0.1586 +vn -0.1902 -0.8894 0.4156 +vn 0.0242 -0.8852 0.4646 +vn -0.1374 -0.9832 -0.1200 +vn -0.7168 -0.6761 0.1705 +vn -0.7300 -0.6524 0.2036 +vn 0.3203 -0.8150 0.4829 +vn -0.9850 -0.1635 0.0553 +vn -0.9863 -0.1633 0.0253 +vn -0.6330 -0.7540 0.1755 +vn 0.8833 -0.4602 -0.0892 +vn 0.7892 -0.5954 -0.1503 +vn -0.8859 -0.4227 0.1912 +vn -0.8293 -0.4807 0.2850 +vn -0.9359 -0.3129 0.1620 +vn -0.8869 -0.3798 0.2629 +vn -0.7114 -0.5099 0.4835 +vn -0.7899 -0.4754 0.3875 +vn -0.1474 -0.8219 0.5503 +vn -0.1459 -0.8342 0.5317 +vn -0.1612 -0.9060 0.3914 +vn -0.3870 -0.5010 0.7741 +vn -0.2047 -0.7836 0.5865 +vn -0.2226 -0.7714 0.5962 +vn -0.1909 -0.7240 0.6628 +vn 0.9687 -0.0061 0.2482 +vn 0.8686 -0.1218 0.4804 +vn -0.6056 -0.5549 0.5704 +vn -0.5946 -0.6867 0.4181 +vn -0.0454 -0.9927 -0.1117 +vn 0.0293 -0.1789 0.9834 +vn 0.0514 -0.3185 0.9465 +vn 0.2362 -0.2275 0.9447 +vn -0.3324 -0.8280 0.4515 +vn -0.3200 -0.8197 0.4751 +vn -0.2350 -0.9404 -0.2457 +vn -0.8927 -0.1671 0.4185 +vn -0.8252 -0.0625 0.5614 +vn -0.8115 -0.5660 0.1453 +vn -0.8280 -0.5523 0.0968 +vn 0.9997 0.0039 -0.0225 +vn 0.9995 -0.0034 -0.0300 +vn -0.0694 -0.9962 -0.0533 +vn -0.0588 -0.9915 -0.1161 +vn -0.1087 -0.9876 -0.1132 +vn -0.1086 -0.9877 -0.1126 +vn -0.1087 -0.9888 -0.1021 +vn -0.1065 -0.9897 -0.0957 +vn 0.2473 -0.9654 -0.0831 +vn 0.0836 -0.9764 -0.1991 +vn -0.1085 -0.9855 -0.1305 +vn 0.9933 0.0329 0.1104 +vn 0.9969 0.0427 0.0655 +vn 0.0093 -0.9925 -0.1220 +vn 0.0067 -0.9927 -0.1205 +vn -0.4664 -0.8781 0.1067 +vn -0.4584 -0.8885 0.0205 +vn -0.3050 -0.9520 0.0274 +vn -0.2589 -0.9639 0.0622 +vn -0.3066 -0.7910 0.5295 +vn 0.1178 -0.9839 0.1342 +vn -0.2339 -0.8653 0.4433 +vn 0.2864 -0.9572 0.0407 +vn -0.1305 -0.9637 -0.2329 +vn -0.1886 -0.9503 -0.2475 +vn 0.1566 0.0442 -0.9867 +vn 0.1554 0.0454 -0.9868 +vn 0.2043 -0.0003 -0.9789 +vn -0.0719 -0.9909 -0.1136 +vn -0.1647 -0.1380 0.9766 +vn -0.1089 -0.1730 0.9789 +vn 0.6062 -0.1058 0.7882 +vn -0.1087 -0.9889 -0.1009 +vn -0.1086 -0.9861 -0.1255 +vn -0.0932 -0.9902 -0.1038 +vn -0.2234 -0.8639 0.4514 +vn -0.6218 -0.7534 0.2140 +vn -0.6276 -0.7583 0.1764 +vn 0.9898 0.0884 0.1120 +vn 0.9558 -0.2865 -0.0654 +vn 0.8792 -0.4694 -0.0818 +vn 0.5851 -0.6712 0.4551 +vn 0.7149 -0.4411 0.5426 +vn 0.8474 -0.5137 0.1340 +vn 0.5264 -0.2156 0.8224 +vn 0.0093 -0.9925 -0.1221 +vn -0.0407 -0.8083 0.5874 +vn 0.4192 -0.8926 -0.1658 +vn 0.2478 -0.9401 -0.2342 +vn 0.7912 -0.3904 -0.4707 +vn 0.0725 0.1969 -0.9777 +vn 0.5626 -0.8128 -0.1511 +vn 0.0491 0.0221 -0.9985 +vn -0.8993 -0.3202 0.2978 +vn 0.9419 -0.3348 -0.0280 +vn 0.0872 -0.9836 -0.1578 +vn -0.0078 -0.9934 -0.1145 +vn -0.7543 -0.0375 0.6555 +vn -0.1225 -0.2719 0.9545 +vn 0.9886 0.0514 0.1413 +vn 0.1355 -0.7124 0.6885 +vn 0.0849 -0.9839 -0.1570 +vn -0.6781 -0.5056 0.5334 +vn -0.7505 -0.5897 0.2983 +vn -0.9014 -0.4316 -0.0330 +vn -0.2621 -0.9284 -0.2632 +vn 0.6214 -0.7675 -0.1572 +vn 0.7586 -0.6346 -0.1479 +vn 0.8074 -0.5776 -0.1202 +vn 0.9965 0.0312 -0.0781 +vn 0.9992 0.0017 -0.0394 +vn 0.9968 0.0297 -0.0739 +vn -0.1452 -0.9821 -0.1199 +vn 0.9992 0.0021 -0.0407 +vn -0.6406 -0.6984 0.3192 +vn -0.0833 -0.9905 -0.1096 +vn -0.6595 -0.7292 0.1826 +vn -0.6259 0.0541 0.7781 +vn -0.1717 -0.7901 0.5884 +vn 0.9394 -0.2262 0.2576 +vn 0.9456 -0.1725 0.2758 +vn -0.6965 -0.6974 0.1689 +vn -0.0642 -0.8896 0.4522 +vn -0.0584 -0.9911 -0.1197 +vn -0.6532 -0.7430 0.1458 +vn -0.6591 -0.7392 0.1385 +vn 0.8943 -0.4310 -0.1201 +vn -0.1743 -0.9766 -0.1260 +vn 0.9880 -0.0034 0.1544 +vn -0.9594 -0.2815 -0.0166 +vn -0.9605 -0.2736 -0.0509 +vn -0.1487 -0.9811 -0.1237 +vn 0.0733 -0.9686 -0.2377 +vn -0.9601 -0.2784 -0.0252 +vn -0.9623 -0.2703 -0.0306 +vn -0.9157 -0.3921 -0.0881 +vn -0.9213 -0.3752 -0.1024 +vn 0.2242 -0.0191 -0.9744 +vn 0.1303 -0.8120 0.5689 +vn -0.8833 -0.4675 0.0356 +vn -0.9242 -0.3659 -0.1091 +vn -0.9294 -0.3502 -0.1161 +vn 0.0550 -0.9909 -0.1229 +vn -0.2137 -0.8138 0.5404 +vn -0.6660 -0.7343 0.1314 +vn -0.0892 -0.9683 -0.2332 +vn -0.1720 -0.9576 -0.2309 +vn 0.0135 -0.9757 -0.2188 +vn 0.9996 0.0234 0.0174 +vn 0.9969 0.0661 -0.0417 +vn 0.5449 -0.8039 -0.2384 +vn 0.9952 -0.0544 -0.0817 +vn 0.9870 -0.0060 0.1606 +vn 0.9876 -0.0043 0.1570 +vn -0.6963 0.1741 -0.6963 +vn -0.2130 -0.8263 0.5215 +vn 0.1271 -0.1854 0.9744 +vn -0.9604 -0.2775 -0.0263 +vn -0.9616 -0.2723 -0.0337 +vn 0.0453 -0.1696 0.9845 +vn -0.0565 -0.9972 0.0486 +vn -0.0281 -0.9985 0.0466 +vn -0.0331 -0.9932 0.1118 +vn -0.4318 -0.6592 -0.6156 +vn -0.4401 -0.7459 -0.5000 +vn -0.5204 -0.7187 -0.4611 +vn -0.4716 0.0403 -0.8809 +vn -0.5393 0.0670 -0.8395 +vn -0.4706 0.0992 -0.8768 +vn -0.0983 -0.9859 -0.1356 +vn -0.0466 -0.9878 -0.1485 +vn -0.3126 -0.9107 -0.2700 +vn -0.4502 -0.8650 -0.2215 +vn -0.4905 -0.7993 -0.3471 +vn -0.1730 -0.9790 -0.1077 +vn -0.0897 -0.9947 0.0494 +vn 0.9875 -0.1577 -0.0042 +vn 0.9527 -0.3006 -0.0437 +vn 0.9922 -0.1180 -0.0389 +vn 0.9969 -0.0662 0.0425 +vn 0.9855 -0.1608 0.0534 +vn -0.0503 -0.1853 -0.9814 +vn 0.0092 -0.2828 -0.9591 +vn -0.0539 -0.2770 -0.9594 +vn -0.1508 -0.7965 -0.5856 +vn -0.1331 -0.7443 -0.6545 +vn -0.1276 -0.8220 -0.5550 +vn 0.7997 -0.5954 -0.0778 +vn 0.5456 -0.8354 -0.0665 +vn 0.5580 -0.8113 -0.1744 +vn -0.8385 -0.5315 -0.1199 +vn -0.8482 -0.5241 -0.0769 +vn -0.8702 -0.4885 -0.0647 +vn -0.2277 -0.8115 -0.5381 +vn -0.2416 -0.7805 -0.5766 +vn -0.2616 -0.7893 -0.5556 +vn -0.6183 -0.1149 -0.7775 +vn -0.6394 -0.0378 -0.7680 +vn 0.5809 -0.7035 -0.4095 +vn 0.8057 -0.5618 -0.1875 +vn 0.5722 -0.7722 -0.2763 +vn -0.2468 -0.8206 -0.5154 +vn 0.0502 -0.8795 -0.4733 +vn 0.0528 -0.8696 -0.4909 +vn 0.1325 -0.8667 -0.4810 +vn -0.2871 -0.9523 -0.1031 +vn -0.4145 -0.9097 -0.0239 +vn -0.3270 -0.9439 -0.0467 +vn -0.0808 -0.9698 0.2302 +vn -0.0311 -0.9731 0.2283 +vn -0.1311 -0.9809 0.1439 +vn 0.9873 0.0041 -0.1587 +vn 0.9929 -0.0292 -0.1154 +vn 0.9844 -0.0710 -0.1610 +vn 0.0641 -0.2501 -0.9661 +vn 0.0866 -0.2221 -0.9712 +vn 0.1279 -0.3080 -0.9428 +vn 0.0141 -0.8318 -0.5549 +vn -0.0122 -0.8540 -0.5202 +vn -0.0330 -0.8487 -0.5278 +vn 0.9863 -0.0082 -0.1649 +vn 0.9532 -0.0437 -0.2993 +vn 0.9849 -0.0073 -0.1729 +vn -0.0611 -0.4471 -0.8924 +vn -0.1083 -0.8779 -0.4665 +vn -0.1203 -0.8585 -0.4986 +vn -0.1196 -0.8699 -0.4786 +vn 0.6241 -0.7738 0.1083 +vn 0.6883 -0.7178 -0.1044 +vn 0.8316 -0.5535 0.0462 +vn 0.3360 -0.1653 -0.9272 +vn 0.5355 -0.1598 -0.8293 +vn 0.2240 -0.1788 -0.9580 +vn 0.9433 -0.3180 -0.0954 +vn 0.8183 -0.4995 -0.2844 +vn 0.9492 -0.2753 -0.1523 +vn -0.0474 -0.7198 -0.6926 +vn -0.0525 -0.6126 -0.7886 +vn 0.0572 -0.5611 -0.8258 +vn 0.0264 -0.9063 -0.4219 +vn -0.0635 -0.9065 -0.4175 +vn -0.0184 -0.8884 -0.4588 +vn -0.1250 -0.8504 -0.5111 +vn -0.1418 -0.8404 -0.5231 +vn 0.0187 -0.9987 0.0476 +vn -0.0189 -0.9935 0.1119 +vn -0.0653 -0.9872 0.1453 +vn -0.0837 -0.9682 0.2356 +vn -0.0314 -0.9725 0.2309 +vn -0.6868 -0.3470 -0.6387 +vn -0.4964 -0.2614 -0.8278 +vn -0.6138 -0.4142 -0.6721 +vn 0.0179 -0.9901 -0.1390 +vn 0.1069 -0.9920 0.0666 +vn 0.1341 -0.9633 0.2324 +vn -0.0031 -0.9915 0.1297 +vn -0.0072 -0.9909 0.1345 +vn -0.7352 -0.6343 -0.2389 +vn -0.6167 -0.7457 -0.2522 +vn -0.6945 -0.6908 -0.2009 +vn 0.9887 -0.1182 -0.0926 +vn -0.2754 -0.4163 -0.8665 +vn -0.2418 -0.2544 -0.9364 +vn -0.1875 -0.2845 -0.9402 +vn -0.1212 -0.8514 -0.5103 +vn -0.1220 -0.8959 -0.4273 +vn -0.1063 -0.8906 -0.4422 +vn -0.8953 -0.2634 -0.3592 +vn -0.8210 -0.1497 -0.5510 +vn -0.7996 -0.2080 -0.5633 +vn 0.9854 -0.1260 0.1143 +vn 0.9643 -0.2451 0.1005 +vn -0.9408 -0.1514 -0.3033 +vn -0.9485 -0.1889 -0.2541 +vn -0.9680 -0.1886 -0.1654 +vn -0.9055 -0.4210 0.0527 +vn -0.9103 -0.4079 0.0709 +vn -0.9371 -0.3484 0.0221 +vn 0.9571 -0.2788 0.0786 +vn -0.0326 -0.9706 0.2386 +vn 0.0193 -0.9710 0.2384 +vn -0.1047 -0.8031 -0.5865 +vn 0.5510 -0.4087 -0.7276 +vn 0.5363 -0.3123 -0.7841 +vn 0.8072 -0.2121 -0.5508 +vn -0.1732 -0.5937 -0.7858 +vn -0.3021 -0.5692 -0.7647 +vn -0.9725 -0.2316 0.0250 +vn -0.9666 -0.2494 -0.0596 +vn -0.2587 -0.1146 -0.9591 +vn -0.2697 -0.0526 -0.9615 +vn -0.2153 -0.0785 -0.9734 +vn -0.3194 -0.0664 -0.9453 +vn -0.3210 -0.2722 -0.9071 +vn -0.3625 -0.1972 -0.9109 +vn -0.9765 -0.1845 -0.1111 +vn -0.7440 -0.6387 -0.1961 +vn -0.1099 -0.8343 -0.5403 +vn -0.1173 -0.8461 -0.5200 +vn 0.9776 -0.1544 -0.1429 +vn 0.1039 -0.4550 -0.8844 +vn 0.6070 -0.7817 0.1430 +vn 0.2172 -0.9218 -0.3211 +vn 0.1290 -0.9320 -0.3387 +vn 0.3800 -0.8342 -0.3996 +vn -0.8087 -0.5432 -0.2258 +vn -0.7736 -0.6037 -0.1925 +vn -0.7928 -0.5810 -0.1841 +vn -0.7507 -0.2656 -0.6049 +vn -0.7473 -0.4445 -0.4939 +vn 0.0043 -0.4571 -0.8894 +vn 0.8130 -0.0827 -0.5763 +vn -0.4348 -0.1089 -0.8939 +vn -0.3646 -0.1016 -0.9256 +vn 0.4270 -0.8860 0.1810 +vn 0.6281 -0.7559 0.1848 +vn 0.5071 -0.7062 0.4941 +vn -0.8530 -0.1169 -0.5087 +vn -0.7675 -0.5356 -0.3523 +vn -0.6880 -0.5886 -0.4245 +vn -0.6824 -0.6348 -0.3625 +vn -0.4977 -0.4935 -0.7133 +vn -0.4349 -0.3484 -0.8304 +vn -0.3157 -0.8045 -0.5031 +vn -0.3764 -0.7989 -0.4691 +vn -0.3243 -0.7837 -0.5297 +vn -0.9036 -0.4219 -0.0744 +vn -0.8592 -0.4880 -0.1535 +vn -0.8966 -0.4427 -0.0003 +vn -0.8921 -0.4514 -0.0200 +vn 0.1913 -0.9744 -0.1185 +vn 0.2727 -0.4685 -0.8403 +vn 0.2564 -0.3508 -0.9007 +vn 0.3077 -0.9299 -0.2015 +vn -0.3146 -0.8583 -0.4054 +vn -0.2224 -0.9222 -0.3165 +vn -0.2148 -0.8711 -0.4417 +vn -0.2243 -0.8509 -0.4750 +vn -0.2244 -0.8477 -0.4806 +vn 0.3147 -0.6844 -0.6577 +vn 0.5800 -0.6435 -0.4995 +vn 0.3200 -0.7575 -0.5690 +vn -0.1432 -0.9598 0.2415 +vn -0.3167 -0.7661 -0.5593 +vn 0.3977 -0.9173 -0.0180 +vn 0.9450 -0.1150 -0.3063 +vn -0.0583 -0.9904 0.1252 +vn -0.0586 -0.9897 0.1309 +vn -0.0572 -0.9902 0.1273 +vn 0.0210 -0.9731 0.2295 +vn 0.0756 -0.9720 0.2226 +vn -0.0712 -0.8927 -0.4450 +vn -0.1347 -0.9314 -0.3383 +vn -0.1131 -0.8916 -0.4384 +vn 0.6561 -0.2562 -0.7098 +vn 0.8099 -0.1404 -0.5695 +vn -0.3143 -0.8117 -0.4923 +vn -0.3157 -0.8158 -0.4846 +vn -0.2452 -0.8236 -0.5115 +vn 0.1663 -0.9640 0.2074 +vn -0.3686 0.0001 -0.9296 +vn 0.0052 -0.7528 -0.6583 +vn -0.0679 -0.7986 -0.5980 +vn -0.5917 -0.7941 -0.1392 +vn -0.6208 -0.7568 -0.2047 +vn -0.5369 -0.8289 -0.1570 +vn 0.2954 -0.5863 -0.7543 +vn -0.0666 0.9968 -0.0449 +vn 0.8171 -0.3401 -0.4655 +vn -0.6669 -0.0059 -0.7452 +vn -0.8299 -0.3707 -0.4170 +vn -0.5382 -0.6150 -0.5763 +vn -0.3136 -0.8366 -0.4491 +vn -0.2761 -0.8500 -0.4487 +vn -0.1086 -0.9868 0.1201 +vn -0.1086 -0.9869 0.1196 +vn -0.1085 -0.9862 0.1251 +vn -0.2527 -0.6989 -0.6691 +vn -0.3345 -0.6893 -0.6426 +vn 0.0091 -0.9475 -0.3196 +vn 0.5638 -0.4961 -0.6603 +vn 0.0806 -0.9847 0.1547 +vn 0.0790 -0.9850 0.1533 +vn -0.1557 -0.4437 -0.8826 +vn 0.0816 -0.9845 0.1554 +vn -0.9295 -0.2177 -0.2976 +vn 0.2568 -0.9443 0.2056 +vn 0.2597 -0.9403 0.2199 +vn 0.1653 -0.9715 0.1701 +vn -0.1544 -0.8933 -0.4221 +vn 0.0443 -0.9923 0.1158 +vn 0.0213 -0.9925 0.1200 +vn -0.2285 -0.8374 -0.4965 +vn -0.2406 -0.8298 -0.5036 +vn -0.1657 -0.9848 0.0519 +vn -0.2861 -0.9523 -0.1064 +vn -0.1900 -0.9788 0.0761 +vn 0.9086 -0.4176 -0.0061 +vn 0.7905 -0.6124 -0.0099 +vn 0.5185 -0.8533 -0.0550 +vn 0.5681 -0.0691 -0.8200 +vn 0.4408 -0.1305 -0.8881 +vn -0.2484 -0.9666 0.0626 +vn -0.1714 -0.9764 0.1318 +vn -0.3530 -0.8960 0.2693 +vn 0.0700 -0.9873 0.1428 +vn 0.0830 -0.9842 0.1561 +vn -0.5788 -0.1990 -0.7908 +vn 0.2319 -0.8764 -0.4222 +vn 0.3392 -0.8880 -0.3105 +vn 0.9994 -0.0251 -0.0240 +vn -0.8866 -0.2304 -0.4011 +vn -0.2253 -0.8422 -0.4898 +vn -0.2207 -0.8361 -0.5023 +vn 0.5870 -0.5724 -0.5725 +vn 0.8442 -0.4147 -0.3396 +vn -0.0578 -0.9912 0.1192 +vn -0.0542 -0.9922 0.1121 +vn -0.0591 -0.9920 0.1119 +vn -0.4578 -0.0544 -0.8874 +vn -0.1348 -0.9900 0.0424 +vn -0.1151 -0.9899 0.0825 +vn -0.0393 -0.8456 -0.5323 +vn -0.0423 -0.8408 -0.5397 +vn 0.1118 -0.9804 0.1620 +vn 0.0899 -0.9832 0.1586 +vn -0.1902 -0.8894 -0.4156 +vn 0.0242 -0.8852 -0.4646 +vn -0.1374 -0.9832 0.1200 +vn -0.7168 -0.6761 -0.1705 +vn -0.7300 -0.6524 -0.2036 +vn 0.3203 -0.8150 -0.4829 +vn -0.9863 -0.1633 -0.0253 +vn -0.9850 -0.1635 -0.0553 +vn -0.6330 -0.7540 -0.1755 +vn 0.8833 -0.4602 0.0892 +vn 0.7892 -0.5954 0.1503 +vn -0.8859 -0.4227 -0.1912 +vn -0.8293 -0.4807 -0.2850 +vn -0.9359 -0.3129 -0.1620 +vn -0.8869 -0.3798 -0.2629 +vn -0.7899 -0.4754 -0.3875 +vn -0.7114 -0.5099 -0.4835 +vn -0.1459 -0.8342 -0.5317 +vn -0.1474 -0.8219 -0.5503 +vn -0.1612 -0.9060 -0.3914 +vn -0.3870 -0.5010 -0.7741 +vn -0.2047 -0.7836 -0.5865 +vn -0.2226 -0.7714 -0.5962 +vn -0.1909 -0.7240 -0.6628 +vn 0.9687 -0.0061 -0.2482 +vn 0.8686 -0.1218 -0.4804 +vn -0.5946 -0.6867 -0.4181 +vn -0.6056 -0.5549 -0.5704 +vn -0.0454 -0.9927 0.1117 +vn 0.0293 -0.1789 -0.9834 +vn 0.0514 -0.3185 -0.9465 +vn 0.2362 -0.2275 -0.9447 +vn -0.3200 -0.8197 -0.4751 +vn -0.3324 -0.8280 -0.4515 +vn -0.2350 -0.9404 0.2457 +vn -0.8927 -0.1671 -0.4185 +vn -0.8252 -0.0625 -0.5614 +vn -0.8115 -0.5660 -0.1453 +vn -0.8280 -0.5523 -0.0968 +vn 0.9997 0.0039 0.0225 +vn 0.9995 -0.0034 0.0300 +vn -0.0694 -0.9962 0.0533 +vn -0.0588 -0.9915 0.1161 +vn -0.1087 -0.9876 0.1132 +vn -0.1087 -0.9888 0.1021 +vn -0.1086 -0.9877 0.1126 +vn -0.1065 -0.9897 0.0957 +vn 0.2473 -0.9654 0.0831 +vn 0.0836 -0.9764 0.1991 +vn -0.1085 -0.9855 0.1305 +vn 0.9933 0.0329 -0.1104 +vn 0.9969 0.0427 -0.0655 +vn 0.0093 -0.9925 0.1220 +vn 0.0067 -0.9927 0.1205 +vn -0.4664 -0.8781 -0.1067 +vn -0.4584 -0.8885 -0.0205 +vn -0.3050 -0.9520 -0.0274 +vn -0.2589 -0.9639 -0.0622 +vn -0.3066 -0.7910 -0.5295 +vn 0.1178 -0.9839 -0.1342 +vn -0.2339 -0.8653 -0.4433 +vn 0.2864 -0.9572 -0.0407 +vn -0.1886 -0.9503 0.2475 +vn -0.1305 -0.9637 0.2329 +vn 0.1566 0.0442 0.9867 +vn 0.2043 -0.0003 0.9789 +vn 0.1554 0.0454 0.9868 +vn -0.0719 -0.9909 0.1136 +vn -0.1647 -0.1380 -0.9766 +vn -0.1089 -0.1730 -0.9789 +vn 0.6062 -0.1058 -0.7882 +vn -0.1087 -0.9889 0.1009 +vn -0.1086 -0.9861 0.1255 +vn -0.0932 -0.9902 0.1038 +vn -0.2234 -0.8639 -0.4514 +vn -0.6218 -0.7534 -0.2140 +vn -0.6276 -0.7583 -0.1764 +vn 0.9898 0.0884 -0.1120 +vn 0.9558 -0.2865 0.0654 +vn 0.8792 -0.4694 0.0818 +vn 0.5851 -0.6712 -0.4551 +vn 0.7149 -0.4411 -0.5426 +vn 0.8474 -0.5137 -0.1340 +vn 0.5264 -0.2156 -0.8224 +vn 0.0093 -0.9925 0.1221 +vn -0.0407 -0.8083 -0.5874 +vn 0.4192 -0.8926 0.1658 +vn 0.2478 -0.9401 0.2342 +vn 0.7912 -0.3904 0.4707 +vn 0.0725 0.1969 0.9777 +vn 0.5626 -0.8128 0.1511 +vn 0.0491 0.0221 0.9985 +vn -0.8993 -0.3202 -0.2978 +vn 0.9419 -0.3348 0.0280 +vn 0.0872 -0.9836 0.1578 +vn -0.0078 -0.9934 0.1145 +vn -0.7543 -0.0375 -0.6555 +vn -0.1225 -0.2719 -0.9545 +vn 0.9886 0.0514 -0.1413 +vn 0.1355 -0.7124 -0.6885 +vn 0.0849 -0.9839 0.1570 +vn -0.6781 -0.5056 -0.5334 +vn -0.7505 -0.5897 -0.2983 +vn -0.9014 -0.4316 0.0330 +vn -0.2621 -0.9285 0.2632 +vn 0.6214 -0.7675 0.1572 +vn 0.8074 -0.5776 0.1202 +vn 0.7586 -0.6346 0.1479 +vn 0.9965 0.0312 0.0781 +vn 0.9968 0.0297 0.0739 +vn 0.9992 0.0017 0.0394 +vn -0.1452 -0.9821 0.1199 +vn 0.9992 0.0021 0.0407 +vn -0.6406 -0.6984 -0.3192 +vn -0.0833 -0.9905 0.1096 +vn -0.6595 -0.7292 -0.1826 +vn -0.6259 0.0541 -0.7781 +vn -0.1717 -0.7901 -0.5884 +vn 0.9394 -0.2262 -0.2576 +vn 0.9456 -0.1725 -0.2758 +vn -0.6965 -0.6974 -0.1689 +vn -0.0642 -0.8896 -0.4522 +vn -0.0584 -0.9911 0.1197 +vn -0.6591 -0.7392 -0.1385 +vn -0.6532 -0.7430 -0.1458 +vn 0.8943 -0.4310 0.1201 +vn -0.1743 -0.9766 0.1260 +vn 0.9880 -0.0034 -0.1544 +vn -0.9594 -0.2815 0.0166 +vn -0.9605 -0.2736 0.0509 +vn -0.1487 -0.9811 0.1237 +vn 0.0733 -0.9686 0.2377 +vn -0.9601 -0.2784 0.0252 +vn -0.9623 -0.2703 0.0306 +vn -0.9157 -0.3921 0.0881 +vn -0.9213 -0.3752 0.1024 +vn 0.2242 -0.0191 0.9744 +vn 0.1303 -0.8120 -0.5689 +vn -0.8833 -0.4675 -0.0356 +vn -0.9242 -0.3659 0.1091 +vn -0.9294 -0.3502 0.1161 +vn 0.0550 -0.9909 0.1229 +vn -0.2137 -0.8138 -0.5404 +vn -0.6660 -0.7343 -0.1314 +vn -0.0892 -0.9683 0.2332 +vn -0.1720 -0.9576 0.2309 +vn 0.0135 -0.9757 0.2188 +vn 0.9996 0.0234 -0.0174 +vn 0.9969 0.0661 0.0417 +vn 0.5449 -0.8039 0.2384 +vn 0.9952 -0.0544 0.0817 +vn 0.9870 -0.0060 -0.1606 +vn 0.9876 -0.0043 -0.1570 +vn -0.6963 0.1741 0.6963 +vn -0.2130 -0.8263 -0.5215 +vn 0.1271 -0.1854 -0.9744 +vn -0.9604 -0.2775 0.0263 +vn -0.9616 -0.2723 0.0337 +vn 0.0453 -0.1696 -0.9845 +vn -0.6893 -0.7210 0.0699 +vn -0.6932 -0.7169 0.0747 +vn -0.7193 -0.6860 0.1096 +vn -0.7125 -0.6945 0.1002 +vn 0.8478 -0.4453 0.2881 +vn 0.8536 -0.4292 0.2954 +vn 0.7998 -0.5511 0.2380 +vn 0.7946 -0.5606 0.2332 +vn 0.7822 0.3869 -0.4884 +vn 0.8000 0.3391 -0.4950 +vn 0.8440 0.1794 -0.5055 +vn 0.8247 0.2598 -0.5023 +vn 0.5823 0.7784 -0.2347 +vn 0.4597 0.8416 -0.2837 +vn 0.3422 0.8818 -0.3246 +vn -0.2090 0.9198 -0.3322 +vn -0.0922 0.9352 -0.3418 +vn -0.6894 -0.7210 -0.0699 +vn -0.6932 -0.7169 -0.0747 +vn -0.6688 -0.7421 -0.0456 +vn -0.6650 -0.7457 -0.0414 +vn 0.2910 0.9463 0.1407 +vn 0.3092 0.9404 0.1413 +vn 0.1401 0.9811 0.1334 +vn 0.1424 0.9808 0.1335 +vn -0.4039 -0.8976 0.1769 +vn -0.4037 -0.8976 0.1770 +vn -0.3993 -0.8989 0.1801 +vn -0.3965 -0.8998 0.1819 +vn -0.6525 -0.7573 -0.0274 +vn -0.6309 -0.7759 -0.0053 +vn -0.6267 -0.7792 -0.0011 +vn 0.0915 -0.6852 0.7226 +vn -0.0106 -0.5789 0.8153 +vn -0.2326 -0.2798 0.9314 +vn -0.1532 -0.3983 0.9044 +vn 0.2936 0.9471 -0.1294 +vn 0.3306 0.9301 -0.1603 +vn 0.3800 0.9027 -0.2020 +vn 0.7040 0.5493 0.4501 +vn 0.7130 0.5334 0.4552 +vn 0.6753 0.5972 0.4329 +vn 0.6695 0.6062 0.4293 +vn -0.0053 -0.9887 -0.1497 +vn -0.0185 -0.9885 -0.1498 +vn 0.2359 -0.9611 -0.1439 +vn 0.3149 -0.9387 -0.1403 +vn 0.4399 0.8618 -0.2525 +vn 0.4631 0.8436 -0.2718 +vn 0.6263 -0.7786 -0.0396 +vn 0.7585 -0.6109 -0.2271 +vn 0.7960 -0.5254 -0.3007 +vn 0.2872 -0.8326 0.4736 +vn 0.2179 -0.7898 0.5734 +vn -0.0862 -0.9293 0.3592 +vn -0.2769 -0.8871 0.3692 +vn -0.4040 0.0551 -0.9131 +vn -0.4098 0.0786 -0.9088 +vn -0.3619 -0.0509 -0.9308 +vn -0.3299 -0.1129 -0.9372 +vn 0.4810 0.8173 -0.3172 +vn 0.5073 0.7893 -0.3459 +vn 0.4247 0.8675 -0.2591 +vn 0.3785 0.9006 -0.2136 +vn 0.4782 -0.8206 0.3131 +vn 0.4368 -0.8406 0.3204 +vn 0.7683 0.3681 0.5236 +vn 0.7422 0.4231 0.5197 +vn 0.8065 0.2688 0.5266 +vn 0.8354 0.1643 0.5245 +vn 0.2936 0.9471 0.1294 +vn 0.2127 0.9752 0.0607 +vn 0.2691 0.9570 0.1085 +vn 0.4390 0.8428 -0.3113 +vn 0.8203 0.5378 -0.1946 +vn 0.5341 0.7933 -0.2923 +vn -0.0348 -0.9841 0.1741 +vn -0.0390 -0.9838 0.1749 +vn 0.0570 -0.9867 0.1520 +vn 0.0730 -0.9863 0.1477 +vn -0.4641 0.8657 -0.1877 +vn -0.4219 0.8833 -0.2045 +vn 0.0520 -0.9370 0.3456 +vn 0.6068 0.6419 0.4688 +vn 0.6123 0.6308 0.4767 +vn 0.6433 0.5562 0.5261 +vn 0.6425 0.5586 0.5246 +vn 0.1905 0.9206 -0.3409 +vn 0.6969 0.5031 -0.5112 +vn 0.6770 0.5336 -0.5070 +vn 0.5995 0.6336 -0.4890 +vn 0.6177 0.6123 -0.4935 +vn 0.6263 -0.7786 0.0396 +vn 0.7585 -0.6109 0.2271 +vn 0.5774 -0.8163 -0.0169 +vn 0.5820 -0.8131 -0.0123 +vn -0.3865 -0.9052 0.1769 +vn -0.3846 -0.9058 0.1776 +vn 0.7908 -0.4663 0.3964 +vn 0.8420 -0.2937 0.4525 +vn 0.8003 -0.4432 0.4038 +vn 0.8594 -0.2019 0.4697 +vn 0.5208 0.7917 -0.3193 +vn 0.5105 0.8017 -0.3110 +vn 0.5606 0.7499 -0.3512 +vn 0.5646 0.7454 -0.3543 +vn 0.9434 0.2896 -0.1619 +vn 0.9848 0.0982 -0.1433 +vn 0.9481 -0.3060 -0.0865 +vn 0.9895 -0.0778 -0.1214 +vn -0.7936 0.5806 -0.1818 +vn -0.7509 0.6289 -0.2016 +vn -0.4637 0.8368 -0.2912 +vn 0.6499 -0.7581 0.0534 +vn 0.6106 -0.7918 0.0146 +vn 0.6926 -0.7147 0.0975 +vn 0.7185 -0.6841 0.1253 +vn -0.7125 -0.6945 -0.1002 +vn -0.7193 -0.6860 -0.1096 +vn 0.7945 -0.5607 -0.2332 +vn 0.7998 -0.5511 -0.2380 +vn 0.8536 -0.4292 -0.2954 +vn 0.8478 -0.4453 -0.2881 +vn 0.8247 0.2598 0.5023 +vn 0.8440 0.1794 0.5055 +vn 0.8000 0.3391 0.4950 +vn 0.7822 0.3869 0.4884 +vn 0.6016 0.7013 -0.3824 +vn 0.6018 0.7010 -0.3826 +vn 0.6683 0.4703 -0.5764 +vn 0.6667 0.4768 -0.5728 +vn 0.6433 0.5562 -0.5261 +vn 0.6425 0.5586 -0.5246 +vn 0.3422 0.8818 0.3246 +vn 0.4597 0.8416 0.2837 +vn 0.5823 0.7784 0.2347 +vn -0.0922 0.9352 0.3418 +vn -0.2090 0.9198 0.3322 +vn 0.0976 0.9277 -0.3604 +vn 0.1808 0.9198 -0.3483 +vn 0.4369 0.8156 -0.3794 +vn 0.7134 0.6017 -0.3592 +vn 0.3800 0.9027 0.2020 +vn 0.3306 0.9301 0.1603 +vn 0.0525 0.9035 0.4253 +vn 0.0949 0.9079 0.4083 +vn 0.4631 0.8436 0.2718 +vn 0.4399 0.8618 0.2525 +vn 0.0225 0.9298 -0.3673 +vn 0.0375 0.9298 -0.3662 +vn 0.8787 -0.4443 0.1744 +vn -0.2769 -0.8871 -0.3692 +vn -0.0862 -0.9293 -0.3592 +vn -0.3299 -0.1129 0.9372 +vn -0.3619 -0.0509 0.9308 +vn -0.4098 0.0786 0.9088 +vn -0.4040 0.0551 0.9131 +vn -0.2367 -0.9602 0.1484 +vn -0.2178 -0.9646 0.1488 +vn -0.3826 -0.9127 0.1439 +vn -0.4251 -0.8939 0.1419 +vn 0.1231 -0.9855 -0.1171 +vn 0.0527 -0.9904 -0.1279 +vn 0.3075 -0.9477 -0.0858 +vn 0.3963 -0.9155 -0.0691 +vn 0.4368 -0.8406 -0.3204 +vn 0.4782 -0.8206 -0.3131 +vn -0.7794 -0.5009 0.3763 +vn -0.8159 -0.4473 0.3664 +vn -0.0029 0.8931 0.4498 +vn 0.4897 -0.8471 0.2065 +vn 0.2333 -0.9286 0.2884 +vn -0.0885 0.8499 -0.5195 +vn -0.1668 0.7623 -0.6254 +vn 0.6387 0.6517 -0.4090 +vn 0.6359 0.6557 -0.4071 +vn 0.5341 0.7933 0.2923 +vn 0.8203 0.5378 0.1946 +vn 0.4390 0.8428 0.3113 +vn 0.4970 0.8510 -0.1696 +vn 0.5742 0.7999 -0.1744 +vn 0.6870 0.7043 -0.1789 +vn -0.4219 0.8833 0.2045 +vn -0.4641 0.8657 0.1877 +vn 0.0520 -0.9370 -0.3456 +vn -0.1821 0.9411 -0.2849 +vn 0.1231 -0.9855 0.1171 +vn 0.0527 -0.9904 0.1279 +vn -0.2252 -0.9602 0.1653 +vn -0.2215 -0.9611 0.1648 +vn -0.1766 0.9785 -0.1067 +vn -0.2272 0.9686 -0.1010 +vn -0.0348 0.9921 -0.1205 +vn -0.0106 0.9924 -0.1226 +vn -0.8546 0.5192 0.0145 +vn -0.7812 0.6242 -0.0059 +vn -0.6092 0.7918 -0.0436 +vn 0.1905 0.9206 0.3409 +vn 0.9538 -0.2965 0.0484 +vn 0.8723 -0.4833 0.0747 +vn 0.6972 -0.7089 0.1067 +vn 0.7845 -0.6131 0.0931 +vn 0.5820 -0.8131 0.0123 +vn 0.5774 -0.8163 0.0169 +vn -0.3857 0.8701 -0.3068 +vn 0.5646 0.7454 0.3543 +vn 0.5606 0.7499 0.3512 +vn 0.5105 0.8017 0.3110 +vn 0.5207 0.7917 0.3193 +vn -0.4637 0.8368 0.2912 +vn -0.7509 0.6289 0.2016 +vn -0.7936 0.5806 0.1818 +vn 0.9895 -0.0778 0.1214 +vn 0.9481 -0.3060 0.0865 +vn 0.9848 0.0982 0.1433 +vn 0.9434 0.2896 0.1619 +vn 0.7185 -0.6841 -0.1253 +vn 0.6926 -0.7147 -0.0975 +vn 0.6106 -0.7918 -0.0146 +vn 0.6499 -0.7581 -0.0534 +vn 0.6018 0.7010 0.3826 +vn 0.6016 0.7013 0.3824 +vn 0.6667 0.4768 0.5728 +vn 0.6683 0.4703 0.5764 +vn 0.5186 -0.8538 0.0453 +vn 0.4926 -0.8697 0.0307 +vn 0.3449 -0.9375 -0.0463 +vn 0.3688 -0.9289 -0.0345 +vn 0.3093 0.9393 -0.1486 +vn 0.2264 0.9712 -0.0741 +vn -0.1132 -0.9816 0.1535 +vn -0.1173 -0.9811 0.1538 +vn -0.2519 -0.9543 0.1610 +vn -0.2643 -0.9508 0.1615 +vn 0.7581 -0.6202 0.2014 +vn 0.7086 -0.6862 0.1646 +vn 0.7122 -0.6818 0.1671 +vn 0.1808 0.9198 0.3483 +vn 0.0976 0.9277 0.3604 +vn 0.7134 0.6017 0.3592 +vn 0.4369 0.8156 0.3794 +vn -0.8990 0.4365 -0.0353 +vn -0.7258 -0.6776 0.1184 +vn -0.7277 -0.6751 0.1213 +vn 0.6570 -0.7428 0.1289 +vn 0.8787 -0.4443 -0.1744 +vn -0.7325 0.6795 0.0416 +vn -0.8545 0.5130 0.0816 +vn -0.6120 0.7908 0.0086 +vn -0.4921 0.8703 -0.0203 +vn -0.4251 -0.8939 -0.1419 +vn -0.3826 -0.9127 -0.1439 +vn -0.2178 -0.9646 -0.1488 +vn -0.2367 -0.9602 -0.1484 +vn -0.9704 -0.2339 0.0601 +vn -0.9055 -0.4159 0.0841 +vn -0.9879 -0.1471 0.0483 +vn -0.8159 -0.4473 -0.3664 +vn -0.7794 -0.5009 -0.3762 +vn 0.2333 -0.9286 -0.2884 +vn 0.4897 -0.8471 -0.2065 +vn -0.1668 0.7623 0.6254 +vn -0.0885 0.8499 0.5195 +vn 0.6359 0.6557 0.4071 +vn 0.6388 0.6517 0.4090 +vn 0.2329 -0.9091 0.3454 +vn 0.1049 -0.9296 0.3534 +vn 0.1410 0.9094 0.3913 +vn 0.1939 0.9073 0.3732 +vn 0.7908 -0.4663 -0.3964 +vn 0.8420 -0.2937 -0.4525 +vn 0.8568 0.0339 -0.5145 +vn 0.8598 -0.1635 -0.4837 +vn -0.5871 -0.7847 -0.1988 +vn -0.5078 -0.8395 -0.1933 +vn -0.2252 -0.9602 -0.1653 +vn -0.2215 -0.9611 -0.1648 +vn -0.9305 -0.3278 0.1635 +vn -0.1821 0.9411 0.2849 +vn 0.1401 0.9811 -0.1334 +vn 0.1424 0.9808 -0.1335 +vn -0.9610 -0.2458 0.1267 +vn 0.2584 0.8996 -0.3521 +vn -0.2569 0.6230 -0.7388 +vn -0.2806 0.5772 -0.7669 +vn -0.3161 -0.9276 0.1991 +vn -0.3159 -0.9277 0.1991 +vn -0.2960 -0.9335 0.2022 +vn -0.2965 -0.9334 0.2021 +vn 0.8065 0.2688 -0.5266 +vn 0.8354 0.1643 -0.5245 +vn -0.0106 0.9924 0.1226 +vn -0.0348 0.9921 0.1205 +vn -0.2272 0.9686 0.1010 +vn -0.1766 0.9785 0.1067 +vn -0.6092 0.7919 0.0436 +vn -0.7812 0.6242 0.0059 +vn -0.8546 0.5192 -0.0145 +vn 0.7656 -0.6431 -0.0178 +vn 0.8808 -0.4702 -0.0560 +vn 0.7845 -0.6131 -0.0931 +vn 0.6972 -0.7089 -0.1067 +vn 0.8723 -0.4833 -0.0747 +vn 0.9538 -0.2965 -0.0484 +vn -0.2088 -0.9121 -0.3529 +vn -0.0326 -0.9337 -0.3565 +vn -0.3858 0.8701 0.3068 +vn 0.5608 0.7917 -0.2423 +vn 0.3295 -0.8950 0.3007 +vn 0.1719 -0.9284 0.3294 +vn 0.3688 -0.9289 0.0345 +vn 0.3449 -0.9375 0.0463 +vn 0.4926 -0.8697 -0.0307 +vn 0.5186 -0.8538 -0.0453 +vn -0.2643 -0.9508 -0.1615 +vn -0.2519 -0.9543 -0.1610 +vn -0.1173 -0.9811 -0.1538 +vn -0.1132 -0.9816 -0.1535 +vn -0.4826 0.8697 -0.1037 +vn -0.3458 0.9313 -0.1144 +vn -0.2441 0.9623 -0.1203 +vn 0.7122 -0.6818 -0.1671 +vn 0.7086 -0.6862 -0.1646 +vn 0.7581 -0.6202 -0.2014 +vn 0.8582 0.4829 -0.1738 +vn -0.0235 0.9454 -0.3251 +vn -0.8990 0.4365 0.0353 +vn -0.6166 0.7645 -0.1877 +vn -0.5719 0.7943 -0.2051 +vn -0.7277 -0.6751 -0.1213 +vn -0.7258 -0.6776 -0.1184 +vn -0.3298 0.4644 -0.8219 +vn -0.3430 0.4289 -0.8357 +vn 0.6570 -0.7428 -0.1289 +vn -0.1056 -0.9767 -0.1866 +vn -0.1095 -0.9762 -0.1872 +vn -0.2041 -0.9585 -0.1992 +vn -0.2020 -0.9590 -0.1990 +vn -0.4921 0.8703 0.0203 +vn -0.6120 0.7908 -0.0086 +vn -0.8545 0.5130 -0.0816 +vn -0.7325 0.6795 -0.0416 +vn 0.2026 -0.9735 -0.1061 +vn 0.2290 -0.9687 -0.0961 +vn -0.9879 -0.1471 -0.0483 +vn -0.9055 -0.4159 -0.0841 +vn -0.9704 -0.2339 -0.0601 +vn -0.6525 -0.7573 0.0274 +vn -0.6688 -0.7421 0.0456 +vn -0.6650 -0.7457 0.0414 +vn 0.8598 -0.1635 0.4837 +vn 0.8568 0.0339 0.5145 +vn 0.0620 0.9375 -0.3424 +vn -0.9836 -0.0540 0.1718 +vn -0.9490 -0.2513 0.1905 +vn -0.9810 0.1232 0.1497 +vn -0.9289 0.3525 0.1132 +vn 0.3093 0.9393 0.1486 +vn 0.2264 0.9712 0.0741 +vn -0.2846 0.9135 -0.2908 +vn 0.1489 0.9223 -0.3566 +vn 0.5555 -0.8303 0.0439 +vn 0.5498 -0.8336 0.0527 +vn 0.5155 -0.8489 0.1168 +vn 0.5324 -0.8422 0.0849 +vn 0.5592 0.7588 -0.3339 +vn 0.6180 0.7163 -0.3242 +vn -0.9305 -0.3278 -0.1635 +vn 0.6495 -0.7602 -0.0134 +vn 0.5322 -0.8456 -0.0409 +vn 0.7656 -0.6431 0.0178 +vn 0.8808 -0.4702 0.0560 +vn 0.5830 0.1151 -0.8042 +vn 0.6457 0.2848 -0.7085 +vn 0.6101 0.1810 -0.7714 +vn -0.0493 0.9413 -0.3340 +vn 0.0203 0.9393 -0.3424 +vn 0.2794 0.8854 -0.3715 +vn -0.2088 -0.9121 0.3529 +vn -0.4909 -0.8084 0.3249 +vn -0.9610 -0.2458 -0.1267 +vn 0.2584 0.8996 0.3521 +vn -0.5384 -0.8258 0.1677 +vn -0.4593 -0.8724 0.1673 +vn -0.6500 -0.7417 0.1657 +vn 0.8583 -0.4167 0.2995 +vn 0.8529 -0.4331 0.2915 +vn -0.2806 0.5772 0.7669 +vn -0.2569 0.6230 0.7388 +vn -0.2327 -0.2798 -0.9314 +vn -0.1533 -0.3983 -0.9044 +vn 0.6753 0.5972 -0.4329 +vn 0.6695 0.6062 -0.4293 +vn -0.2721 0.9600 -0.0662 +vn -0.3564 0.9330 -0.0496 +vn -0.0976 0.9905 -0.0973 +vn -0.0341 0.9936 -0.1077 +vn 0.4970 0.8510 0.1696 +vn 0.5742 0.7999 0.1744 +vn 0.2233 0.9642 0.1433 +vn 0.2263 0.9634 0.1436 +vn 0.4751 -0.8596 -0.1879 +vn 0.4356 -0.8642 -0.2520 +vn 0.5155 -0.8489 -0.1168 +vn 0.5324 -0.8422 -0.0849 +vn -0.3320 -0.9228 0.1956 +vn -0.3325 -0.9226 0.1955 +vn 0.5546 0.7294 -0.4006 +vn 0.5681 0.7093 -0.4173 +vn 0.8047 -0.5488 0.2264 +vn 0.7938 -0.5698 0.2127 +vn 0.8260 -0.5032 0.2541 +vn 0.8329 -0.4868 0.2634 +vn 0.5608 0.7917 0.2423 +vn -0.3320 -0.9228 -0.1956 +vn -0.3325 -0.9226 -0.1955 +vn -0.3865 -0.9052 -0.1769 +vn -0.3846 -0.9058 -0.1776 +vn 0.1719 -0.9284 -0.3294 +vn 0.3295 -0.8950 -0.3007 +vn 0.6266 -0.7716 0.1095 +vn 0.6192 -0.7782 0.1048 +vn -0.2441 0.9623 0.1203 +vn -0.3458 0.9313 0.1144 +vn -0.4826 0.8697 0.1037 +vn 0.8582 0.4829 0.1738 +vn 0.8682 -0.0660 -0.4918 +vn 0.8603 0.0777 -0.5039 +vn -0.6719 -0.7400 0.0306 +vn -0.6403 -0.7679 -0.0179 +vn -0.6059 -0.7924 -0.0707 +vn -0.6122 -0.7885 -0.0597 +vn -0.0235 0.9454 0.3251 +vn 0.6029 0.7851 -0.1423 +vn 0.6655 0.7332 -0.1398 +vn 0.9077 0.4043 -0.1123 +vn 0.7938 0.5941 -0.1300 +vn 0.0975 -0.9418 -0.3216 +vn -0.3829 0.2992 -0.8740 +vn -0.3890 0.2750 -0.8792 +vn -0.5719 0.7943 0.2051 +vn -0.6166 0.7645 0.1877 +vn -0.3430 0.4289 0.8357 +vn -0.3298 0.4644 0.8219 +vn -0.2020 -0.9590 0.1990 +vn -0.2041 -0.9585 0.1992 +vn -0.1095 -0.9762 0.1872 +vn -0.1056 -0.9767 0.1866 +vn 0.3032 0.8965 -0.3231 +vn 0.6563 -0.7259 0.2055 +vn 0.0521 0.9904 -0.1282 +vn 0.0582 0.9900 -0.1283 +vn -0.5564 -0.8201 0.1338 +vn -0.6237 -0.7710 0.1282 +vn -0.5813 -0.8049 -0.1192 +vn -0.5426 -0.8181 -0.1903 +vn -0.2847 -0.7892 -0.5443 +vn -0.4650 -0.8268 -0.3165 +vn 0.2290 -0.9687 0.0961 +vn 0.2026 -0.9735 0.1061 +vn 0.3713 0.9206 -0.1212 +vn 0.3190 0.9397 -0.1236 +vn 0.2233 0.9642 -0.1433 +vn 0.2263 0.9634 -0.1436 +vn -0.0070 -0.9392 -0.3433 +vn -0.2712 -0.9407 -0.2040 +vn -0.2704 -0.9409 -0.2040 +vn -0.2960 -0.9335 -0.2022 +vn -0.2965 -0.9334 -0.2021 +vn 0.6731 0.4001 -0.6220 +vn 0.6672 0.3688 -0.6472 +vn 0.0620 0.9375 0.3424 +vn -0.9289 0.3525 -0.1132 +vn -0.9810 0.1232 -0.1497 +vn -0.9490 -0.2513 -0.1905 +vn -0.9836 -0.0540 -0.1718 +vn 0.5201 -0.8501 -0.0830 +vn 0.4411 -0.8819 -0.1661 +vn -0.2846 0.9135 0.2908 +vn 0.1489 0.9223 0.3566 +vn 0.6179 0.7163 0.3242 +vn 0.5592 0.7588 0.3339 +vn 0.3875 -0.8632 -0.3236 +vn 0.3557 -0.8592 -0.3678 +vn 0.7156 0.6926 -0.0905 +vn 0.8013 0.5933 -0.0767 +vn 0.9604 0.2768 -0.0323 +vn 0.8894 0.4536 -0.0572 +vn 0.6101 0.1810 0.7714 +vn 0.6457 0.2848 0.7085 +vn 0.5830 0.1151 0.8043 +vn 0.0203 0.9393 0.3424 +vn -0.0493 0.9413 0.3340 +vn 0.2794 0.8854 0.3715 +vn -0.4909 -0.8084 -0.3249 +vn 0.2329 -0.9091 -0.3454 +vn -0.6500 -0.7417 -0.1656 +vn -0.4593 -0.8724 -0.1673 +vn -0.5384 -0.8258 -0.1677 +vn -0.4473 0.8915 -0.0714 +vn -0.3643 0.9275 -0.0836 +vn 0.8003 -0.4432 -0.4038 +vn 0.8594 -0.2019 -0.4697 +vn -0.4868 -0.8654 -0.1185 +vn -0.4889 -0.8645 -0.1169 +vn -0.5715 -0.8191 -0.0501 +vn -0.5677 -0.8215 -0.0535 +vn 0.6969 0.5031 0.5112 +vn 0.6770 0.5336 0.5070 +vn 0.7515 -0.6394 0.1624 +vn 0.7676 -0.6148 0.1811 +vn -0.8733 -0.4433 0.2020 +vn -0.7736 -0.5995 0.2052 +vn 0.4810 0.8173 0.3172 +vn 0.5073 0.7893 0.3459 +vn 0.5681 0.7093 0.4173 +vn 0.5546 0.7294 0.4006 +vn 0.8329 -0.4868 -0.2634 +vn 0.8259 -0.5032 -0.2541 +vn 0.7938 -0.5698 -0.2127 +vn 0.8047 -0.5488 -0.2264 +vn 0.4611 0.7602 -0.4576 +vn 0.4425 0.7737 -0.4534 +vn 0.3961 0.8048 -0.4420 +vn 0.6192 -0.7782 -0.1048 +vn 0.6266 -0.7716 -0.1095 +vn 0.8603 0.0777 0.5039 +vn 0.8682 -0.0660 0.4918 +vn 0.9946 0.1032 -0.0079 +vn 0.9922 -0.1221 0.0238 +vn -0.6122 -0.7885 0.0597 +vn -0.6059 -0.7924 0.0707 +vn -0.6403 -0.7679 0.0179 +vn -0.6719 -0.7400 -0.0306 +vn 0.7938 0.5941 0.1300 +vn 0.9077 0.4043 0.1123 +vn 0.6655 0.7332 0.1398 +vn 0.6029 0.7851 0.1423 +vn 0.8073 -0.5893 0.0312 +vn 0.6392 -0.7660 0.0677 +vn 0.3911 -0.9142 0.1059 +vn 0.4766 -0.8741 0.0942 +vn -0.3890 0.2750 0.8792 +vn -0.3829 0.2992 0.8740 +vn 0.0326 0.9377 -0.3458 +vn -0.6209 -0.7010 0.3507 +vn -0.6815 -0.6480 0.3401 +vn -0.0326 -0.9337 0.3565 +vn 0.3032 0.8965 0.3231 +vn 0.6563 -0.7259 -0.2055 +vn -0.0029 0.8931 -0.4498 +vn -0.0520 0.8782 -0.4755 +vn 0.0582 0.9900 0.1283 +vn 0.0521 0.9904 0.1282 +vn -0.8923 0.4462 0.0690 +vn -0.6237 -0.7710 -0.1282 +vn -0.5564 -0.8201 -0.1338 +vn 0.5555 -0.8303 -0.0439 +vn 0.5498 -0.8336 -0.0527 +vn -0.4650 -0.8268 0.3165 +vn -0.2847 -0.7892 0.5442 +vn -0.5426 -0.8181 0.1903 +vn -0.5813 -0.8049 0.1192 +vn 0.3190 0.9397 0.1236 +vn 0.3713 0.9206 0.1212 +vn -0.0976 0.9905 0.0973 +vn -0.0341 0.9936 0.1077 +vn 0.3785 0.9006 0.2136 +vn 0.4247 0.8675 0.2591 +vn 0.7040 0.5493 -0.4501 +vn 0.7130 0.5334 -0.4552 +vn 0.7544 0.4516 -0.4763 +vn 0.7411 0.4795 -0.4699 +vn -0.2704 -0.9409 0.2040 +vn -0.2712 -0.9407 0.2040 +vn -0.0348 -0.9841 -0.1741 +vn -0.0390 -0.9838 -0.1749 +vn -0.5871 -0.7847 0.1988 +vn -0.5078 -0.8395 0.1933 +vn -0.6309 -0.7758 0.0053 +vn -0.6267 -0.7792 0.0011 +vn -0.5498 -0.7739 0.3143 +vn -0.7379 -0.6650 0.1155 +vn -0.8219 -0.5603 0.1026 +vn -0.7024 -0.7073 0.0800 +vn -0.7136 -0.6937 0.0982 +vn 0.0570 -0.9867 -0.1520 +vn 0.0730 -0.9863 -0.1477 +vn 0.4751 -0.8596 0.1879 +vn 0.4356 -0.8642 0.2520 +vn 0.3557 -0.8592 0.3678 +vn 0.3875 -0.8632 0.3236 +vn 0.9797 0.1377 -0.1459 +vn 0.8583 -0.4167 -0.2995 +vn 0.8529 -0.4331 -0.2915 +vn 0.8894 0.4536 0.0572 +vn 0.9604 0.2768 0.0323 +vn 0.8013 0.5933 0.0767 +vn 0.7156 0.6926 0.0905 +vn 0.5386 0.6963 -0.4744 +vn 0.5302 0.7040 -0.4726 +vn 0.6731 0.4001 0.6220 +vn 0.6672 0.3688 0.6472 +vn 0.2854 -0.3493 -0.8925 +vn 0.1185 0.9195 -0.3749 +vn 0.0601 0.9276 -0.3687 +vn -0.3643 0.9275 0.0836 +vn -0.4473 0.8915 0.0714 +vn -0.5677 -0.8215 0.0535 +vn -0.5715 -0.8191 0.0501 +vn -0.4889 -0.8645 0.1169 +vn -0.4868 -0.8654 0.1185 +vn 0.7960 -0.5254 0.3007 +vn 0.1939 0.9073 -0.3732 +vn 0.1410 0.9094 -0.3913 +vn 0.0949 0.9079 -0.4083 +vn 0.7676 -0.6148 -0.1811 +vn 0.7515 -0.6394 -0.1624 +vn 0.6177 0.6123 0.4935 +vn 0.5995 0.6336 0.4891 +vn 0.3961 0.8048 0.4420 +vn 0.4425 0.7737 0.4534 +vn 0.4611 0.7602 0.4577 +vn 0.2651 0.8729 -0.4096 +vn 0.1979 0.8981 -0.3928 +vn 0.9922 -0.1221 -0.0238 +vn 0.9946 0.1032 0.0079 +vn 0.4427 0.8850 -0.1440 +vn 0.4826 0.8639 -0.1441 +vn 0.8772 -0.4800 0.0110 +vn 0.5345 0.8379 -0.1104 +vn 0.6007 0.7927 -0.1042 +vn 0.4766 -0.8741 -0.0942 +vn 0.3911 -0.9142 -0.1059 +vn 0.6392 -0.7660 -0.0677 +vn 0.8073 -0.5893 -0.0312 +vn 0.7604 0.6243 -0.1788 +vn 0.8619 0.4762 -0.1742 +vn -0.4737 -0.7846 0.4000 +vn 0.0326 0.9377 0.3458 +vn -0.6815 -0.6480 -0.3401 +vn -0.6209 -0.7010 -0.3507 +vn 0.1049 -0.9296 -0.3534 +vn 0.3191 0.8476 -0.4239 +vn 0.0375 0.9298 0.3662 +vn 0.0225 0.9298 0.3673 +vn -0.0520 0.8782 0.4755 +vn -0.2047 -0.7548 -0.6232 +vn -0.8923 0.4462 -0.0690 +vn 0.7411 0.4795 0.4699 +vn 0.7544 0.4516 0.4763 +vn -0.8733 -0.4433 -0.2020 +vn -0.7736 -0.5995 -0.2052 +vn -0.5498 -0.7739 -0.3143 +vn -0.8219 -0.5603 -0.1026 +vn -0.7379 -0.6650 -0.1155 +vn -0.7136 -0.6937 -0.0982 +vn -0.7024 -0.7073 -0.0800 +vn 0.7016 -0.6876 0.1868 +vn 0.9797 0.1377 0.1459 +vn 0.6870 0.7043 0.1788 +vn 0.6870 0.7043 0.1789 +vn 0.5302 0.7040 0.4726 +vn 0.5386 0.6963 0.4744 +vn 0.2872 -0.8326 -0.4736 +vn 0.2179 -0.7898 -0.5734 +vn 0.7521 0.5576 -0.3513 +vn 0.0464 -0.9888 0.1420 +vn 0.0204 -0.9894 0.1441 +vn 0.2854 -0.3493 0.8925 +vn 0.0525 0.9035 -0.4253 +vn 0.0601 0.9276 0.3687 +vn 0.1185 0.9195 0.3749 +vn 0.2910 0.9463 -0.1407 +vn 0.3092 0.9404 -0.1413 +vn 0.2563 0.8991 -0.3549 +vn 0.3963 -0.9155 0.0691 +vn 0.3075 -0.9477 0.0858 +vn -0.4131 0.1603 -0.8965 +vn -0.4123 0.1649 -0.8960 +vn 0.9532 0.2856 -0.0995 +vn 0.1979 0.8981 0.3928 +vn 0.2651 0.8729 0.4097 +vn 0.4826 0.8639 0.1441 +vn 0.4427 0.8850 0.1440 +vn 0.8772 -0.4800 -0.0110 +vn 0.6007 0.7927 0.1042 +vn 0.5345 0.8379 0.1104 +vn 0.6068 0.6419 -0.4688 +vn 0.6123 0.6308 -0.4767 +vn 0.8619 0.4762 0.1742 +vn 0.7604 0.6243 0.1788 +vn 0.5341 -0.8240 0.1891 +vn -0.4737 -0.7846 -0.4000 +vn 0.2492 -0.9606 0.1227 +vn 0.1957 -0.9722 0.1283 +vn 0.3191 0.8476 0.4239 +vn -0.2047 -0.7548 0.6232 +vn -0.2721 0.9600 0.0662 +vn -0.3564 0.9330 0.0496 +vn -0.1403 0.9370 -0.3200 +vn -0.0053 -0.9887 0.1497 +vn -0.0185 -0.9885 0.1498 +vn -0.4039 -0.8976 -0.1769 +vn -0.4037 -0.8976 -0.1770 +vn -0.2971 -0.8727 0.3874 +vn 0.7016 -0.6876 -0.1868 +vn 0.7521 0.5576 0.3513 +vn 0.0204 -0.9894 -0.1441 +vn 0.0464 -0.9888 -0.1420 +vn 0.2563 0.8991 0.3549 +vn -0.4123 0.1649 0.8960 +vn -0.4131 0.1603 0.8965 +vn -0.9901 0.0666 0.1234 +vn 0.9532 0.2856 0.0995 +vn 0.1010 0.9315 -0.3495 +vn 0.5341 -0.8240 -0.1891 +vn -0.3159 -0.9276 -0.1991 +vn -0.3161 -0.9276 -0.1991 +vn 0.1957 -0.9722 -0.1283 +vn 0.2492 -0.9606 -0.1227 +vn -0.1403 0.9370 0.3200 +vn -0.0070 -0.9392 0.3433 +vn -0.1394 -0.9200 0.3664 +vn -0.2971 -0.8727 -0.3875 +vn 0.5842 -0.8027 0.1202 +vn 0.4988 -0.8572 0.1281 +vn 0.2359 -0.9611 0.1439 +vn 0.3149 -0.9387 0.1403 +vn -0.9901 0.0667 -0.1234 +vn 0.2127 0.9752 -0.0607 +vn 0.2691 0.9570 -0.1085 +vn 0.5322 -0.8456 0.0409 +vn 0.6495 -0.7602 0.0134 +vn 0.1010 0.9315 0.3495 +vn -0.1394 -0.9200 -0.3664 +vn 0.9586 -0.2677 -0.0969 +vn 0.4411 -0.8819 0.1661 +vn 0.5201 -0.8501 0.0830 +vn -0.3965 -0.8998 -0.1819 +vn -0.3993 -0.8989 -0.1801 +vn 0.0975 -0.9418 0.3216 +vn -0.0106 -0.5789 -0.8153 +vn 0.0915 -0.6852 -0.7226 +vn 0.4988 -0.8572 -0.1281 +vn 0.5842 -0.8027 -0.1202 +vn 0.7422 0.4231 -0.5197 +vn 0.7683 0.3681 -0.5236 +vn 0.9586 -0.2677 0.0969 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/4 6/6/4 +f 4/4/5 7/7/6 8/8/7 +f 8/8/7 9/9/8 4/4/5 +f 5/5/9 4/4/5 9/9/8 +f 9/9/10 3/3/11 5/5/12 +f 5/5/12 3/3/11 6/6/13 +f 10/10/14 6/6/13 3/3/11 +f 3/3/11 2/2/15 10/10/14 +f 10/10/14 2/2/15 11/11/16 +f 12/12/17 11/11/18 2/2/19 +f 1/1/20 12/12/17 2/2/19 +f 12/12/17 1/1/20 13/13/21 +f 14/14/22 13/13/21 1/1/20 +f 15/15/23 13/13/21 14/14/22 +f 8/8/7 15/15/23 14/14/22 +f 7/7/6 15/15/23 8/8/7 +f 1/1/1 3/3/3 16/16/24 +f 14/14/25 1/1/25 17/17/25 +f 8/8/26 14/14/26 16/16/26 +f 16/16/27 14/14/27 17/17/27 +f 9/9/28 8/8/28 16/16/28 +f 3/3/29 9/9/29 16/16/29 +f 16/16/24 17/17/30 1/1/1 +f 18/18/31 19/19/31 20/20/31 +f 21/21/32 22/22/33 23/23/34 +f 23/23/34 22/22/33 24/24/35 +f 24/24/35 22/22/33 18/18/36 +f 19/19/37 18/18/36 22/22/33 +f 19/19/37 22/22/33 25/25/38 +f 26/26/39 19/19/37 25/25/38 +f 20/20/40 19/19/37 26/26/39 +f 20/20/40 26/26/39 27/27/41 +f 28/28/42 27/27/41 26/26/39 +f 26/26/39 29/29/43 28/28/42 +f 27/27/44 28/28/45 30/30/46 +f 28/28/45 29/29/47 30/30/46 +f 30/30/46 29/29/47 31/31/48 +f 31/31/48 29/29/47 32/32/49 +f 33/33/50 31/31/48 21/21/32 +f 21/21/32 31/31/48 32/32/49 +f 34/34/51 33/33/50 21/21/32 +f 23/23/34 34/34/51 21/21/32 +f 24/24/52 34/34/52 23/23/52 +f 29/29/53 26/26/53 35/35/53 +f 32/32/54 29/29/55 36/36/56 +f 36/36/56 29/29/55 35/35/57 +f 21/21/58 32/32/58 36/36/58 +f 22/22/59 21/21/59 36/36/59 +f 25/25/60 22/22/61 36/36/62 +f 26/26/63 25/25/60 35/35/64 +f 25/25/60 36/36/62 35/35/64 +f 37/37/65 38/38/65 39/39/65 +f 39/39/66 40/40/66 41/41/66 +f 41/41/67 42/42/67 43/43/67 +f 44/44/68 45/45/68 46/46/68 +f 40/40/69 46/46/70 41/41/71 +f 40/40/69 47/47/72 46/46/70 +f 40/40/69 39/39/73 47/47/72 +f 48/48/74 47/47/72 39/39/73 +f 38/38/75 48/48/74 39/39/73 +f 49/49/76 48/48/74 38/38/75 +f 50/50/77 49/49/78 38/38/79 +f 38/38/79 37/37/80 50/50/77 +f 43/43/81 50/50/77 37/37/80 +f 50/50/77 43/43/81 51/51/82 +f 52/52/83 51/51/84 43/43/85 +f 43/43/85 42/42/86 52/52/83 +f 44/44/87 52/52/83 42/42/86 +f 45/45/88 44/44/87 42/42/86 +f 45/45/88 42/42/86 41/41/71 +f 46/46/70 45/45/88 41/41/71 +f 37/37/89 39/39/89 53/53/89 +f 43/43/90 37/37/91 54/54/92 +f 54/54/92 37/37/91 53/53/93 +f 41/41/94 43/43/94 54/54/94 +f 55/55/95 41/41/95 54/54/95 +f 39/39/96 41/41/96 55/55/96 +f 53/53/97 39/39/97 55/55/97 +f 53/53/98 55/55/98 54/54/98 +f 56/56/99 57/57/100 58/58/101 +f 58/58/102 59/59/102 60/60/102 +f 51/51/103 52/52/104 50/50/105 +f 47/47/106 48/48/107 46/46/108 +f 50/50/105 52/52/104 44/44/109 +f 49/49/110 50/50/105 44/44/109 +f 49/49/110 44/44/109 46/46/108 +f 49/49/110 46/46/108 48/48/107 +f 34/34/111 24/24/112 31/31/113 +f 27/27/114 18/18/115 20/20/116 +f 24/24/112 30/30/117 31/31/113 +f 24/24/112 18/18/115 30/30/117 +f 27/27/114 30/30/117 18/18/115 +f 33/33/118 34/34/111 31/31/113 +f 12/12/119 13/13/120 15/15/121 +f 12/12/119 15/15/121 11/11/122 +f 15/15/121 7/7/123 11/11/122 +f 10/10/124 7/7/123 4/4/125 +f 61/61/126 62/62/126 63/63/126 +f 62/62/127 60/60/128 63/63/129 +f 59/59/130 63/63/129 60/60/128 +f 64/64/131 63/63/129 59/59/130 +f 58/58/132 64/64/131 59/59/130 +f 58/58/132 65/65/133 64/64/131 +f 66/66/134 65/65/133 58/58/132 +f 66/66/134 58/58/132 57/57/100 +f 66/66/134 57/57/100 67/67/135 +f 68/68/136 67/67/135 57/57/100 +f 57/57/100 56/56/99 68/68/136 +f 67/67/135 68/68/136 69/69/137 +f 70/70/138 69/69/139 68/68/140 +f 71/71/141 70/70/138 68/68/140 +f 71/71/141 68/68/140 56/56/142 +f 61/61/143 70/70/138 71/71/141 +f 62/62/127 61/61/143 71/71/141 +f 71/71/141 60/60/128 62/62/127 +f 56/56/144 58/58/144 72/72/144 +f 73/73/145 56/56/145 72/72/145 +f 71/71/146 56/56/146 73/73/146 +f 60/60/147 71/71/147 73/73/147 +f 58/58/148 60/60/149 72/72/150 +f 72/72/150 60/60/149 73/73/151 +f 11/11/122 7/7/123 10/10/124 +f 10/10/124 4/4/125 6/6/152 +f 70/70/153 67/67/154 69/69/155 +f 70/70/153 61/61/156 67/67/154 +f 63/63/157 64/64/158 65/65/159 +f 61/61/156 63/63/157 67/67/154 +f 66/66/160 67/67/154 63/63/157 +f 65/65/159 66/66/160 63/63/157 +f 74/74/161 75/75/162 76/76/163 +f 77/77/164 78/78/165 79/79/166 +f 80/80/167 81/81/168 79/79/166 +f 82/82/169 75/75/169 74/74/169 +f 80/80/167 79/79/166 78/78/165 +f 80/80/167 78/78/165 83/83/170 +f 74/74/161 76/76/163 83/83/170 +f 74/74/161 83/83/170 78/78/165 +f 78/78/165 77/77/164 84/84/171 +f 78/78/165 84/84/171 85/85/172 +f 85/85/172 84/84/171 86/86/173 +f 85/85/172 86/86/173 87/87/174 +f 85/85/172 87/87/174 88/88/175 +f 89/89/176 88/88/175 87/87/174 +f 90/90/177 89/89/176 87/87/174 +f 91/91/178 90/90/177 87/87/174 +f 92/92/179 93/93/180 94/94/181 +f 94/94/181 93/93/180 95/95/182 +f 95/95/182 93/93/180 96/96/183 +f 96/96/183 97/97/184 95/95/182 +f 95/95/182 97/97/184 98/98/185 +f 98/98/185 99/99/186 95/95/182 +f 95/95/182 99/99/186 100/100/187 +f 96/96/183 101/101/188 97/97/184 +f 102/102/189 103/103/190 104/104/191 +f 104/104/191 103/103/190 100/100/187 +f 95/95/182 100/100/187 105/105/192 +f 103/103/190 105/105/192 100/100/187 +f 106/106/193 107/107/194 108/108/195 +f 108/108/195 109/109/196 106/106/193 +f 110/110/197 111/111/198 112/112/199 +f 110/110/197 112/112/199 113/113/200 +f 113/113/200 112/112/199 114/114/201 +f 115/115/202 110/110/197 113/113/200 +f 115/115/202 113/113/200 116/116/203 +f 116/116/203 113/113/200 114/114/201 +f 116/116/203 114/114/201 117/117/204 +f 117/117/204 114/114/201 118/118/205 +f 119/119/206 115/115/202 120/120/207 +f 120/120/207 116/116/203 117/117/204 +f 120/120/207 117/117/204 121/121/208 +f 114/114/201 122/122/209 118/118/205 +f 117/117/204 118/118/205 123/123/210 +f 116/116/203 120/120/207 115/115/202 +f 123/123/210 121/121/208 117/117/204 +f 124/124/211 125/125/212 126/126/213 +f 126/126/213 125/125/212 118/118/205 +f 126/126/213 118/118/205 122/122/209 +f 125/125/212 123/123/210 118/118/205 +f 127/127/214 123/123/210 128/128/215 +f 123/123/210 125/125/212 128/128/215 +f 128/128/215 125/125/212 129/129/216 +f 129/129/216 125/125/212 124/124/211 +f 110/110/197 115/115/202 130/130/217 +f 131/131/218 130/130/217 106/106/193 +f 131/131/218 106/106/193 109/109/196 +f 130/130/217 131/131/218 111/111/198 +f 130/130/217 111/111/198 110/110/197 +f 132/132/219 127/127/214 128/128/215 +f 128/128/215 129/129/216 133/133/220 +f 128/128/215 133/133/220 134/134/221 +f 128/128/215 134/134/221 132/132/219 +f 135/135/222 136/136/223 137/137/224 +f 135/135/222 137/137/224 138/138/225 +f 138/138/225 137/137/224 139/139/226 +f 140/140/227 135/135/222 138/138/225 +f 138/138/225 141/141/228 142/142/229 +f 138/138/225 142/142/229 140/140/227 +f 135/135/222 140/140/227 143/143/230 +f 142/142/229 127/127/214 132/132/219 +f 140/140/227 142/142/229 132/132/219 +f 140/140/227 132/132/219 134/134/221 +f 140/140/227 134/134/221 143/143/230 +f 143/143/230 134/134/221 144/144/231 +f 145/145/232 139/139/226 137/137/224 +f 137/137/224 146/146/233 145/145/232 +f 145/145/232 146/146/233 147/147/234 +f 145/145/232 147/147/234 148/148/235 +f 146/146/233 137/137/224 136/136/223 +f 147/147/234 102/102/189 148/148/235 +f 89/89/176 90/90/177 149/149/236 +f 85/85/172 150/150/237 78/78/165 +f 151/151/238 152/152/239 153/153/240 +f 154/154/241 155/155/242 153/153/240 +f 156/156/243 94/94/181 157/157/244 +f 158/158/245 159/159/246 160/160/247 +f 160/160/247 159/159/246 149/149/236 +f 149/149/236 90/90/177 160/160/247 +f 161/161/248 88/88/175 89/89/176 +f 162/162/249 85/85/172 163/163/250 +f 163/163/250 85/85/172 88/88/175 +f 150/150/237 85/85/172 162/162/249 +f 164/164/251 165/165/252 166/166/253 +f 166/166/253 165/165/252 167/167/254 +f 166/166/253 167/167/254 168/168/255 +f 169/169/256 168/168/255 170/170/257 +f 169/169/256 170/170/257 171/171/258 +f 172/172/259 171/171/258 173/173/260 +f 166/166/253 168/168/255 169/169/256 +f 174/174/261 164/164/251 166/166/253 +f 175/175/262 166/166/253 169/169/256 +f 176/176/263 169/169/256 171/171/258 +f 176/176/263 171/171/258 172/172/259 +f 174/174/261 166/166/253 175/175/262 +f 176/176/263 175/175/262 169/169/256 +f 161/161/248 175/175/262 176/176/263 +f 177/177/264 174/174/261 161/161/248 +f 161/161/248 174/174/261 175/175/262 +f 163/163/250 161/161/248 176/176/263 +f 162/162/249 176/176/263 172/172/259 +f 162/162/249 163/163/250 176/176/263 +f 163/163/250 88/88/175 161/161/248 +f 161/161/248 89/89/176 177/177/264 +f 177/177/264 89/89/176 149/149/236 +f 168/168/255 167/167/254 170/170/257 +f 170/170/257 167/167/254 178/178/265 +f 179/179/266 173/173/260 171/171/258 +f 179/179/266 171/171/258 180/180/267 +f 180/180/267 171/171/258 170/170/257 +f 180/180/267 170/170/257 181/181/268 +f 181/181/268 170/170/257 178/178/265 +f 182/182/269 183/183/270 184/184/271 +f 167/167/254 165/165/252 185/185/272 +f 167/167/254 185/185/272 186/186/273 +f 186/186/273 185/185/272 184/184/271 +f 184/184/271 185/185/272 182/182/269 +f 184/184/271 183/183/270 187/187/274 +f 184/184/271 187/187/274 186/186/273 +f 186/186/273 187/187/274 188/188/275 +f 186/186/273 188/188/275 167/167/254 +f 167/167/254 188/188/275 178/178/265 +f 187/187/274 183/183/270 189/189/276 +f 182/182/269 190/190/277 183/183/270 +f 183/183/270 190/190/277 191/191/278 +f 183/183/270 191/191/278 189/189/276 +f 189/189/276 191/191/278 192/192/279 +f 193/193/280 74/74/161 194/194/281 +f 195/195/282 180/180/267 181/181/268 +f 122/122/209 179/179/266 195/195/282 +f 195/195/282 179/179/266 180/180/267 +f 196/196/283 195/195/282 181/181/268 +f 126/126/213 122/122/209 195/195/282 +f 126/126/213 195/195/282 124/124/211 +f 124/124/211 195/195/282 196/196/283 +f 197/197/284 189/189/276 198/198/285 +f 198/198/285 189/189/276 192/192/279 +f 198/198/285 192/192/279 199/199/286 +f 154/154/241 200/200/287 155/155/242 +f 200/200/287 154/154/241 156/156/243 +f 201/201/288 182/182/269 202/202/289 +f 190/190/277 182/182/269 201/201/288 +f 203/203/290 191/191/278 190/190/277 +f 191/191/278 204/204/291 192/192/279 +f 201/201/288 203/203/290 190/190/277 +f 205/205/292 204/204/291 191/191/278 +f 205/205/292 191/191/278 203/203/290 +f 205/205/292 206/206/293 204/204/291 +f 207/207/294 205/205/292 203/203/290 +f 207/207/294 203/203/290 208/208/295 +f 208/208/295 203/203/290 201/201/288 +f 208/208/295 201/201/288 209/209/296 +f 209/209/296 201/201/288 202/202/289 +f 210/210/297 206/206/293 205/205/292 +f 211/211/298 208/208/295 209/209/296 +f 200/200/287 210/210/297 205/205/292 +f 212/212/299 205/205/292 207/207/294 +f 213/213/300 207/207/294 208/208/295 +f 213/213/300 208/208/295 211/211/298 +f 200/200/287 205/205/292 212/212/299 +f 212/212/299 207/207/294 213/213/300 +f 151/151/238 213/213/300 211/211/298 +f 151/151/238 211/211/298 214/214/301 +f 157/157/244 210/210/297 156/156/243 +f 156/156/243 210/210/297 200/200/287 +f 155/155/242 200/200/287 212/212/299 +f 155/155/242 212/212/299 153/153/240 +f 153/153/240 212/212/299 213/213/300 +f 153/153/240 213/213/300 151/151/238 +f 215/215/302 133/133/220 129/129/216 +f 199/199/286 144/144/231 198/198/285 +f 197/197/284 198/198/285 215/215/302 +f 133/133/220 215/215/302 198/198/285 +f 133/133/220 198/198/285 134/134/221 +f 134/134/221 198/198/285 144/144/231 +f 105/105/192 103/103/190 216/216/303 +f 217/217/304 218/218/305 199/199/286 +f 219/219/306 151/151/238 214/214/301 +f 152/152/239 151/151/238 219/219/306 +f 220/220/307 177/177/264 149/149/236 +f 221/221/308 174/174/261 177/177/264 +f 164/164/251 222/222/309 165/165/252 +f 222/222/309 185/185/272 165/165/252 +f 202/202/289 182/182/269 222/222/309 +f 222/222/309 182/182/269 185/185/272 +f 220/220/307 214/214/301 211/211/298 +f 223/223/310 224/224/311 219/219/306 +f 202/202/289 222/222/309 209/209/296 +f 214/214/301 220/220/307 223/223/310 +f 214/214/301 223/223/310 219/219/306 +f 209/209/296 222/222/309 221/221/308 +f 209/209/296 221/221/308 211/211/298 +f 211/211/298 221/221/308 220/220/307 +f 224/224/311 223/223/310 158/158/245 +f 222/222/309 164/164/251 221/221/308 +f 223/223/310 159/159/246 158/158/245 +f 221/221/308 164/164/251 174/174/261 +f 220/220/307 221/221/308 177/177/264 +f 223/223/310 220/220/307 149/149/236 +f 223/223/310 149/149/236 159/159/246 +f 158/158/245 225/225/312 224/224/311 +f 123/123/210 127/127/214 121/121/208 +f 121/121/208 127/127/214 142/142/229 +f 121/121/208 142/142/229 141/141/228 +f 121/121/208 141/141/228 120/120/207 +f 139/139/226 119/119/206 138/138/225 +f 138/138/225 119/119/206 120/120/207 +f 138/138/225 120/120/207 141/141/228 +f 119/119/206 139/139/226 226/226/313 +f 119/119/206 226/226/313 227/227/314 +f 227/227/314 226/226/313 228/228/315 +f 95/95/182 105/105/192 94/94/181 +f 105/105/192 216/216/303 157/157/244 +f 94/94/181 105/105/192 157/157/244 +f 216/216/303 210/210/297 157/157/244 +f 216/216/303 229/229/316 210/210/297 +f 206/206/293 229/229/316 217/217/304 +f 229/229/316 206/206/293 210/210/297 +f 204/204/291 206/206/293 217/217/304 +f 204/204/291 217/217/304 199/199/286 +f 199/199/286 192/192/279 204/204/291 +f 78/78/165 150/150/237 74/74/161 +f 162/162/249 194/194/281 150/150/237 +f 150/150/237 194/194/281 74/74/161 +f 162/162/249 230/230/317 194/194/281 +f 162/162/249 172/172/259 230/230/317 +f 172/172/259 231/231/318 230/230/317 +f 231/231/318 172/172/259 173/173/260 +f 173/173/260 179/179/266 231/231/318 +f 216/216/303 146/146/233 229/229/316 +f 103/103/190 102/102/189 147/147/234 +f 103/103/190 147/147/234 216/216/303 +f 216/216/303 147/147/234 146/146/233 +f 229/229/316 146/146/233 136/136/223 +f 136/136/223 217/217/304 229/229/316 +f 218/218/305 217/217/304 135/135/222 +f 135/135/222 217/217/304 136/136/223 +f 143/143/230 218/218/305 135/135/222 +f 143/143/230 144/144/231 199/199/286 +f 218/218/305 143/143/230 199/199/286 +f 129/129/216 188/188/275 187/187/274 +f 187/187/274 215/215/302 129/129/216 +f 197/197/284 215/215/302 187/187/274 +f 197/197/284 187/187/274 189/189/276 +f 196/196/283 188/188/275 124/124/211 +f 124/124/211 188/188/275 129/129/216 +f 188/188/275 196/196/283 181/181/268 +f 188/188/275 181/181/268 178/178/265 +f 131/131/218 109/109/196 193/193/280 +f 131/131/218 193/193/280 194/194/281 +f 194/194/281 111/111/198 131/131/218 +f 231/231/318 112/112/199 230/230/317 +f 194/194/281 230/230/317 111/111/198 +f 230/230/317 112/112/199 111/111/198 +f 231/231/318 114/114/201 112/112/199 +f 179/179/266 122/122/209 114/114/201 +f 179/179/266 114/114/201 231/231/318 +f 104/104/191 148/148/235 102/102/189 +f 148/148/235 104/104/191 232/232/319 +f 232/232/319 145/145/232 148/148/235 +f 226/226/313 139/139/226 233/233/320 +f 233/233/320 139/139/226 145/145/232 +f 233/233/320 145/145/232 232/232/319 +f 233/233/320 228/228/315 226/226/313 +f 227/227/314 228/228/315 234/234/321 +f 115/115/202 119/119/206 234/234/321 +f 234/234/321 119/119/206 227/227/314 +f 115/115/202 234/234/321 107/107/194 +f 106/106/193 130/130/217 107/107/194 +f 107/107/194 130/130/217 115/115/202 +f 235/235/322 74/74/161 193/193/280 +f 82/82/323 74/74/161 235/235/322 +f 236/236/324 152/152/239 237/237/325 +f 152/152/239 236/236/324 153/153/240 +f 236/236/324 154/154/241 153/153/240 +f 238/238/326 156/156/243 236/236/324 +f 156/156/243 154/154/241 236/236/324 +f 238/238/326 239/239/327 156/156/243 +f 156/156/243 239/239/327 94/94/181 +f 94/94/181 239/239/327 92/92/179 +f 91/91/178 160/160/247 90/90/177 +f 158/158/245 160/160/247 240/240/328 +f 240/240/328 160/160/247 91/91/178 +f 240/240/328 225/225/312 158/158/245 +f 241/241/329 224/224/311 240/240/328 +f 240/240/328 224/224/311 225/225/312 +f 237/237/325 219/219/306 241/241/329 +f 241/241/329 219/219/306 224/224/311 +f 219/219/306 237/237/325 152/152/239 +f 109/109/196 108/108/195 193/193/280 +f 193/193/280 108/108/195 235/235/322 +f 242/242/330 243/243/330 244/244/330 +f 244/244/331 243/243/331 245/245/331 +f 244/244/332 245/245/333 246/246/334 +f 246/246/335 245/245/336 247/247/337 +f 247/247/337 245/245/336 248/248/338 +f 247/247/337 248/248/338 249/249/339 +f 250/250/340 251/251/341 249/249/339 +f 249/249/339 251/251/341 247/247/337 +f 96/96/342 250/250/340 249/249/339 +f 239/239/327 238/238/326 252/252/343 +f 252/252/343 253/253/344 239/239/327 +f 252/252/343 254/254/345 253/253/344 +f 254/254/345 252/252/343 243/243/346 +f 254/254/345 243/243/346 242/242/347 +f 255/255/348 256/256/348 257/257/348 +f 257/257/349 256/256/350 258/258/351 +f 257/257/349 258/258/351 259/259/352 +f 259/259/353 258/258/353 260/260/353 +f 261/261/354 260/260/355 262/262/356 +f 262/262/356 260/260/355 258/258/357 +f 263/263/358 101/101/359 264/264/360 +f 263/263/361 264/264/362 265/265/363 +f 264/264/362 266/266/364 265/265/363 +f 266/266/364 264/264/362 256/256/365 +f 266/266/364 256/256/365 255/255/366 +f 263/263/358 265/265/367 267/267/368 +f 267/267/369 265/265/369 266/266/369 +f 268/268/370 260/260/370 261/261/370 +f 269/269/371 244/244/332 246/246/334 +f 269/269/372 246/246/373 270/270/374 +f 242/242/375 244/244/376 269/269/377 +f 247/247/378 251/251/379 270/270/374 +f 247/247/378 270/270/374 246/246/373 +f 271/271/380 272/272/380 273/273/380 +f 273/273/381 272/272/382 274/274/383 +f 273/273/381 274/274/383 275/275/384 +f 275/275/385 274/274/386 276/276/387 +f 276/276/387 274/274/386 277/277/388 +f 86/86/173 84/84/171 277/277/388 +f 84/84/171 278/278/389 277/277/388 +f 277/277/388 278/278/389 276/276/387 +f 279/279/390 280/280/391 81/81/392 +f 281/281/393 282/282/394 279/279/395 +f 279/279/390 282/282/396 280/280/391 +f 281/281/393 279/279/395 272/272/397 +f 281/281/393 272/272/397 271/271/398 +f 283/283/399 284/284/400 82/82/401 +f 82/82/401 284/284/400 285/285/402 +f 284/284/403 283/283/404 286/286/405 +f 286/286/405 283/283/404 287/287/406 +f 287/287/407 283/283/408 288/288/409 +f 287/287/407 288/288/409 289/289/410 +f 289/289/411 288/288/412 290/290/413 +f 290/290/413 288/288/412 291/291/414 +f 291/291/414 288/288/412 292/292/415 +f 293/293/416 294/294/417 295/295/418 +f 295/295/418 294/294/417 292/292/415 +f 292/292/415 294/294/417 291/291/414 +f 80/80/419 293/293/416 295/295/418 +f 269/269/377 270/270/420 242/242/375 +f 270/270/420 251/251/421 253/253/422 +f 254/254/423 242/242/375 270/270/420 +f 254/254/423 270/270/420 253/253/422 +f 260/260/424 268/268/425 266/266/426 +f 255/255/427 259/259/428 260/260/424 +f 255/255/427 257/257/429 259/259/428 +f 255/255/427 260/260/424 266/266/426 +f 286/286/430 290/290/431 284/284/432 +f 268/268/425 267/267/433 266/266/426 +f 284/284/432 290/290/431 296/296/434 +f 297/297/435 284/284/432 296/296/434 +f 281/281/436 271/271/437 298/298/438 +f 298/298/438 276/276/439 281/281/436 +f 281/281/436 276/276/439 299/299/440 +f 297/297/435 296/296/434 294/294/441 +f 282/282/442 281/281/436 299/299/440 +f 291/291/443 294/294/444 296/296/445 +f 290/290/446 291/291/443 296/296/445 +f 287/287/447 289/289/448 290/290/431 +f 286/286/430 287/287/447 290/290/431 +f 284/284/449 297/297/449 285/285/449 +f 278/278/450 84/84/451 299/299/452 +f 276/276/453 278/278/450 299/299/452 +f 271/271/437 273/273/454 298/298/438 +f 298/298/455 273/273/381 275/275/384 +f 298/298/456 275/275/456 276/276/456 +f 99/99/457 261/261/458 262/262/459 +f 261/261/458 99/99/457 98/98/460 +f 261/261/461 98/98/462 268/268/463 +f 267/267/368 268/268/463 97/97/464 +f 97/97/464 268/268/463 98/98/462 +f 101/101/359 263/263/358 97/97/464 +f 263/263/358 267/267/368 97/97/464 +f 82/82/465 285/285/465 75/75/465 +f 297/297/466 76/76/467 285/285/468 +f 285/285/468 76/76/467 75/75/469 +f 83/83/470 76/76/471 294/294/472 +f 294/294/472 76/76/471 297/297/473 +f 293/293/474 80/80/474 83/83/474 +f 294/294/472 293/293/475 83/83/470 +f 79/79/476 81/81/392 280/280/391 +f 280/280/391 282/282/396 79/79/476 +f 77/77/477 79/79/476 299/299/452 +f 299/299/452 79/79/476 282/282/396 +f 84/84/451 77/77/477 299/299/452 +f 250/250/478 96/96/479 93/93/480 +f 250/250/478 93/93/480 251/251/481 +f 253/253/482 251/251/481 92/92/483 +f 92/92/483 251/251/481 93/93/480 +f 239/239/484 253/253/482 92/92/483 +f 300/300/485 301/301/486 302/302/487 +f 302/302/487 301/301/486 303/303/488 +f 304/304/489 305/305/490 306/306/491 +f 307/307/492 305/305/490 304/304/489 +f 308/308/493 307/307/492 304/304/489 +f 309/309/494 310/310/495 311/311/496 +f 311/311/496 310/310/495 312/312/497 +f 313/313/498 314/314/499 315/315/500 +f 316/316/501 317/317/501 318/318/501 +f 319/319/502 312/312/503 313/313/498 +f 315/315/500 319/319/502 313/313/498 +f 319/319/502 315/315/500 318/318/504 +f 318/318/504 315/315/500 320/320/505 +f 318/318/504 320/320/505 316/316/506 +f 316/316/506 320/320/505 321/321/507 +f 321/321/507 320/320/505 322/322/508 +f 313/313/498 312/312/503 310/310/509 +f 323/323/510 324/324/511 325/325/512 +f 326/326/513 327/327/514 328/328/515 +f 323/323/510 329/329/516 324/324/511 +f 324/324/511 329/329/516 330/330/517 +f 324/324/511 330/330/517 327/327/514 +f 327/327/514 330/330/517 331/331/518 +f 327/327/514 331/331/518 328/328/515 +f 311/311/519 326/326/513 309/309/520 +f 311/311/519 327/327/514 326/326/513 +f 332/332/521 333/333/522 334/334/523 +f 335/335/524 336/336/525 337/337/526 +f 336/336/525 335/335/524 338/338/527 +f 339/339/528 340/340/529 341/341/528 +f 332/332/521 342/342/528 333/333/522 +f 334/334/523 333/333/522 343/343/530 +f 337/337/526 336/336/525 344/344/528 +f 342/342/528 332/332/521 345/345/528 +f 346/346/531 340/340/529 347/347/532 +f 344/344/528 348/348/528 337/337/526 +f 349/349/533 347/347/532 340/340/529 +f 337/337/526 348/348/528 350/350/528 +f 350/350/528 348/348/528 351/351/528 +f 350/350/528 351/351/528 352/352/534 +f 352/352/534 351/351/528 353/353/528 +f 354/354/528 355/355/528 345/345/528 +f 354/354/528 345/345/528 332/332/521 +f 356/356/535 357/357/536 358/358/528 +f 358/358/528 357/357/536 359/359/528 +f 339/339/528 341/341/528 360/360/528 +f 339/339/528 360/360/528 344/344/528 +f 344/344/528 360/360/528 348/348/528 +f 342/342/528 345/345/528 361/361/528 +f 357/357/536 356/356/535 362/362/537 +f 358/358/528 359/359/528 361/361/528 +f 361/361/528 359/359/528 342/342/528 +f 357/357/536 362/362/537 363/363/538 +f 354/354/528 323/323/528 355/355/528 +f 355/355/528 323/323/528 364/364/528 +f 353/353/528 365/365/539 352/352/534 +f 363/363/538 366/366/540 357/357/536 +f 367/367/541 368/368/542 369/369/543 +f 370/370/544 371/371/545 368/368/542 +f 368/368/542 371/371/545 369/369/543 +f 371/371/545 370/370/544 372/372/546 +f 369/369/543 371/371/545 373/373/547 +f 374/374/548 373/373/547 375/375/549 +f 371/371/545 376/376/550 373/373/547 +f 373/373/547 376/376/550 375/375/549 +f 371/371/545 377/377/551 376/376/550 +f 378/378/552 379/379/553 380/380/554 +f 378/378/552 380/380/554 381/381/555 +f 381/381/555 380/380/554 382/382/556 +f 382/382/556 383/383/557 381/381/555 +f 379/379/558 378/378/558 384/384/558 +f 384/384/559 378/378/559 385/385/559 +f 384/384/560 385/385/560 386/386/560 +f 387/387/561 384/384/562 386/386/563 +f 384/384/562 387/387/561 388/388/564 +f 388/388/564 387/387/561 389/389/565 +f 389/389/565 390/390/566 388/388/564 +f 391/391/567 385/385/567 378/378/567 +f 391/391/568 378/378/569 392/392/570 +f 391/391/568 392/392/570 393/393/571 +f 393/393/572 392/392/573 383/383/557 +f 394/394/574 395/395/575 396/396/576 +f 396/396/576 397/397/577 394/394/574 +f 398/398/578 399/399/579 400/400/580 +f 400/400/580 401/401/581 398/398/578 +f 402/402/582 403/403/583 404/404/584 +f 403/403/583 402/402/582 393/393/585 +f 393/393/585 402/402/582 405/405/586 +f 406/406/587 407/407/588 408/408/589 +f 408/408/589 407/407/588 409/409/590 +f 408/408/589 409/409/590 410/410/591 +f 410/410/591 409/409/590 411/411/592 +f 410/410/591 411/411/592 412/412/593 +f 412/412/593 411/411/592 413/413/594 +f 412/412/593 413/413/594 414/414/595 +f 414/414/595 413/413/594 415/415/596 +f 414/414/595 415/415/596 416/416/597 +f 416/416/597 415/415/596 417/417/598 +f 416/416/597 417/417/598 418/418/599 +f 418/418/599 417/417/598 419/419/600 +f 418/418/599 419/419/600 420/420/601 +f 420/420/601 419/419/600 421/421/602 +f 422/422/603 423/423/603 424/424/603 +f 423/423/603 422/422/603 354/354/604 +f 425/425/605 426/426/606 427/427/607 +f 427/427/607 426/426/606 332/332/608 +f 425/425/605 424/424/603 426/426/606 +f 422/422/603 424/424/603 425/425/605 +f 332/332/608 426/426/606 428/428/603 +f 428/428/603 423/423/603 354/354/604 +f 332/332/608 428/428/603 354/354/604 +f 429/429/609 330/330/517 329/329/516 +f 430/430/610 431/431/611 432/432/612 +f 430/430/610 432/432/612 433/433/613 +f 433/433/613 434/434/614 425/425/605 +f 425/425/605 434/434/614 422/422/603 +f 422/422/603 434/434/614 431/431/611 +f 435/435/615 422/422/603 436/436/616 +f 437/437/603 438/438/615 439/439/603 +f 431/431/611 430/430/610 422/422/603 +f 422/422/603 430/430/610 436/436/616 +f 430/430/610 439/439/603 436/436/616 +f 435/435/615 438/438/615 437/437/603 +f 422/422/603 435/435/615 437/437/603 +f 440/440/617 441/441/618 442/442/619 +f 442/442/619 441/441/618 326/326/513 +f 442/442/619 326/326/513 443/443/620 +f 442/442/619 430/430/610 444/444/621 +f 440/440/617 445/445/622 433/433/613 +f 445/445/622 446/446/623 433/433/613 +f 445/445/622 440/440/617 444/444/621 +f 433/433/613 446/446/623 430/430/610 +f 442/442/619 444/444/621 440/440/617 +f 447/447/603 448/448/624 439/439/603 +f 430/430/610 442/442/619 447/447/603 +f 430/430/610 447/447/603 439/439/603 +f 443/443/620 449/449/625 442/442/619 +f 443/443/620 450/450/626 437/437/603 +f 443/443/620 437/437/603 439/439/603 +f 443/443/620 439/439/603 449/449/625 +f 449/449/625 439/439/603 448/448/624 +f 328/328/515 451/451/627 326/326/513 +f 326/326/513 451/451/627 443/443/620 +f 331/331/518 452/452/609 450/450/626 +f 331/331/518 450/450/626 328/328/515 +f 437/437/603 453/453/628 454/454/629 +f 455/455/630 453/453/628 354/354/604 +f 456/456/611 455/455/630 354/354/604 +f 422/422/603 454/454/629 456/456/611 +f 422/422/603 456/456/611 354/354/604 +f 437/437/603 454/454/629 422/422/603 +f 323/323/510 457/457/631 329/329/516 +f 429/429/609 458/458/632 354/354/604 +f 429/429/609 354/354/604 437/437/603 +f 437/437/603 354/354/604 453/453/628 +f 458/458/632 457/457/631 323/323/510 +f 429/429/609 459/459/633 458/458/632 +f 354/354/604 458/458/632 323/323/510 +f 329/329/516 459/459/633 429/429/609 +f 317/317/634 316/316/634 325/325/634 +f 325/325/635 316/316/635 323/323/635 +f 307/307/492 460/460/636 461/461/637 +f 307/307/492 461/461/637 462/462/638 +f 462/462/638 461/461/637 463/463/639 +f 464/464/640 465/465/641 466/466/642 +f 466/466/642 465/465/641 463/463/639 +f 466/466/642 463/463/639 467/467/643 +f 100/468/644 464/464/645 468/469/646 +f 465/465/641 469/470/647 402/402/648 +f 100/468/649 468/469/650 461/461/637 +f 461/461/637 468/469/650 467/467/643 +f 461/461/637 467/467/643 463/463/639 +f 100/468/651 470/471/652 464/464/640 +f 464/464/640 470/471/652 469/470/647 +f 464/464/640 469/470/647 465/465/641 +f 471/472/653 472/473/654 473/474/655 +f 471/472/653 473/474/655 474/475/656 +f 474/475/656 473/474/655 475/476/657 +f 474/475/656 475/476/657 391/391/658 +f 391/391/658 475/476/657 385/385/659 +f 472/473/654 476/477/660 477/478/661 +f 472/473/654 471/472/662 476/477/660 +f 476/477/663 478/479/664 477/478/661 +f 477/478/661 478/479/664 479/480/665 +f 479/480/665 478/479/664 480/481/666 +f 479/480/665 480/481/666 362/362/667 +f 356/356/668 481/482/669 482/483/670 +f 356/356/668 482/483/670 362/362/667 +f 362/362/667 482/483/670 479/480/665 +f 404/404/671 483/484/672 356/356/673 +f 356/356/673 483/484/672 481/482/674 +f 403/403/675 484/485/676 485/486/677 +f 403/403/675 485/486/677 404/404/678 +f 404/404/678 485/486/677 483/484/679 +f 383/383/557 403/403/675 393/393/572 +f 390/390/566 389/389/565 484/485/676 +f 484/485/676 389/389/565 486/487/680 +f 403/403/675 383/383/557 382/382/556 +f 403/403/675 382/382/556 484/485/676 +f 484/485/676 382/382/556 390/390/566 +f 487/488/681 488/489/682 489/490/683 +f 489/490/683 488/489/682 490/491/684 +f 490/491/684 488/489/682 491/492/685 +f 358/358/686 492/493/687 364/364/688 +f 364/364/688 492/493/687 493/494/689 +f 492/493/690 358/358/691 494/495/692 +f 494/495/692 358/358/691 361/361/693 +f 494/495/694 361/361/695 495/496/696 +f 495/496/696 361/361/695 345/345/697 +f 495/496/698 345/345/699 496/497/700 +f 496/497/700 345/345/699 355/355/701 +f 496/497/702 355/355/703 493/494/704 +f 493/494/704 355/355/703 364/364/705 +f 496/497/528 494/495/528 495/496/528 +f 496/497/528 493/494/528 494/495/528 +f 494/495/528 493/494/528 492/493/528 +f 342/342/706 497/498/707 333/333/708 +f 333/333/708 497/498/707 498/499/709 +f 333/333/710 498/499/711 499/500/712 +f 497/498/713 342/342/714 500/501/715 +f 500/501/715 342/342/714 359/359/716 +f 357/357/717 501/502/718 502/503/719 +f 357/357/717 502/503/719 359/359/720 +f 359/359/720 502/503/719 500/501/721 +f 501/502/722 503/504/723 504/505/724 +f 504/505/724 503/504/723 505/506/725 +f 501/502/722 366/366/726 503/504/723 +f 357/357/727 366/366/726 501/502/722 +f 506/507/728 507/508/729 504/505/730 +f 506/507/728 504/505/730 508/509/731 +f 504/505/724 505/506/725 508/509/732 +f 509/510/733 510/511/734 511/512/735 +f 511/512/735 510/511/734 512/513/736 +f 512/513/736 513/514/737 511/512/735 +f 511/512/735 513/514/737 506/507/738 +f 506/507/738 513/514/737 507/508/739 +f 343/343/740 514/515/741 509/510/742 +f 514/515/741 343/343/740 515/516/743 +f 333/333/710 516/517/744 343/343/745 +f 343/343/745 516/517/744 515/516/746 +f 510/511/734 517/518/747 518/519/748 +f 514/515/749 519/520/750 509/510/733 +f 509/510/733 519/520/750 510/511/734 +f 510/511/734 519/520/750 517/518/747 +f 517/518/751 519/520/752 520/521/753 +f 517/518/751 520/521/753 521/522/754 +f 520/521/755 522/523/756 521/522/757 +f 520/521/755 523/524/758 522/523/756 +f 519/520/759 514/515/760 524/525/761 +f 519/520/759 524/525/761 525/526/762 +f 516/517/744 523/524/758 525/526/763 +f 525/526/763 524/525/764 516/517/744 +f 522/523/756 523/524/758 499/500/712 +f 499/500/712 523/524/758 333/333/710 +f 523/524/758 516/517/744 333/333/710 +f 526/527/765 527/528/766 528/529/767 +f 527/528/766 529/530/768 528/529/767 +f 374/374/769 530/531/770 531/532/771 +f 532/533/772 531/532/771 530/531/770 +f 532/533/772 530/531/770 533/534/773 +f 531/532/771 532/533/772 534/535/774 +f 534/535/775 535/536/776 536/537/777 +f 534/535/774 536/537/778 537/538/779 +f 536/537/778 367/367/780 537/538/779 +f 534/535/774 537/538/779 531/532/771 +f 531/532/781 537/538/782 407/407/783 +f 531/532/781 407/407/783 406/406/784 +f 372/372/546 370/370/544 534/535/785 +f 534/535/785 370/370/544 535/536/786 +f 533/534/773 377/377/551 532/533/772 +f 376/376/550 377/377/551 533/534/773 +f 427/427/607 538/539/787 399/399/579 +f 440/440/617 399/399/579 395/395/575 +f 399/399/579 398/398/578 395/395/575 +f 440/440/617 395/395/575 394/394/574 +f 394/394/574 539/540/788 440/440/617 +f 427/427/607 399/399/579 440/440/617 +f 440/440/617 433/433/613 425/425/605 +f 440/440/617 425/425/605 427/427/607 +f 401/401/581 400/400/580 540/541/789 +f 540/541/789 400/400/580 541/542/790 +f 542/543/791 543/544/792 544/545/793 +f 543/544/792 540/541/789 545/546/794 +f 540/541/789 541/542/790 546/547/795 +f 540/541/789 546/547/795 545/546/794 +f 546/547/795 547/548/796 545/546/794 +f 540/541/789 543/544/792 548/549/797 +f 397/397/577 396/396/576 543/544/792 +f 543/544/792 396/396/576 548/549/797 +f 543/544/792 545/546/794 544/545/793 +f 544/545/798 545/546/799 420/420/601 +f 544/545/798 420/420/601 421/421/602 +f 369/369/543 373/373/547 469/470/800 +f 369/369/543 469/470/800 470/471/801 +f 490/491/684 491/492/685 549/550/802 +f 549/550/802 491/492/685 550/551/803 +f 549/550/802 550/551/803 479/480/665 +f 479/480/665 550/551/803 477/478/661 +f 481/482/804 490/491/805 482/483/806 +f 482/483/806 490/491/805 549/550/807 +f 482/483/670 549/550/808 479/480/665 +f 472/473/654 550/551/803 551/552/809 +f 477/478/661 550/551/803 472/473/654 +f 551/552/809 550/551/803 491/492/685 +f 489/490/683 490/491/805 552/553/810 +f 552/553/810 490/491/805 481/482/804 +f 552/553/810 481/482/804 483/484/811 +f 385/385/812 475/476/813 487/488/681 +f 487/488/681 475/476/813 488/489/682 +f 473/474/655 488/489/682 475/476/813 +f 473/474/655 472/473/654 551/552/809 +f 473/474/655 551/552/809 488/489/682 +f 488/489/682 551/552/809 491/492/685 +f 552/553/810 553/554/814 489/490/683 +f 484/485/676 553/554/814 485/486/677 +f 485/486/677 553/554/814 552/553/810 +f 485/486/677 552/553/810 483/484/679 +f 386/386/815 385/385/815 554/555/815 +f 555/556/816 554/555/817 385/385/812 +f 555/556/816 385/385/812 487/488/681 +f 487/488/681 489/490/683 553/554/814 +f 487/488/681 553/554/814 555/556/816 +f 555/556/818 553/554/814 554/555/819 +f 554/555/819 553/554/814 484/485/676 +f 554/555/819 484/485/676 486/487/680 +f 526/527/820 528/529/821 556/557/822 +f 556/557/822 528/529/821 501/502/722 +f 556/557/822 501/502/722 504/505/724 +f 507/508/823 526/527/820 556/557/822 +f 504/505/724 507/508/823 556/557/822 +f 500/501/824 502/503/825 557/558/826 +f 501/502/827 528/529/828 502/503/825 +f 557/558/826 502/503/825 528/529/828 +f 507/508/823 513/514/829 527/528/830 +f 507/508/823 527/528/830 526/527/820 +f 513/514/829 512/513/831 558/559/832 +f 513/514/829 558/559/832 527/528/830 +f 512/513/831 510/511/734 558/559/832 +f 558/559/832 510/511/734 559/560/833 +f 558/559/832 559/560/833 529/530/834 +f 558/559/832 529/530/834 527/528/830 +f 528/529/767 529/530/768 557/558/835 +f 557/558/835 529/530/768 560/561/836 +f 557/558/826 560/561/837 500/501/824 +f 500/501/824 560/561/837 497/498/838 +f 510/511/734 518/519/748 561/562/839 +f 562/563/840 561/562/841 499/500/712 +f 562/563/840 499/500/712 498/499/711 +f 562/563/840 529/530/842 561/562/841 +f 529/530/842 559/560/843 561/562/841 +f 559/560/833 510/511/734 561/562/839 +f 562/563/844 560/561/836 529/530/768 +f 497/498/845 560/561/836 562/563/844 +f 498/499/846 497/498/845 562/563/844 +f 469/470/847 373/373/848 402/402/849 +f 374/374/850 405/405/851 373/373/848 +f 373/373/848 405/405/851 402/402/849 +f 538/539/852 427/427/853 334/334/854 +f 334/334/854 427/427/853 332/332/855 +f 406/406/856 405/405/857 531/532/858 +f 531/532/859 405/405/851 374/374/850 +f 334/334/854 420/420/860 545/546/861 +f 334/334/854 545/546/861 547/548/862 +f 334/334/854 547/548/862 538/539/852 +f 414/414/863 471/472/864 412/412/865 +f 412/412/865 471/472/864 474/475/866 +f 412/412/865 474/475/866 410/410/867 +f 410/410/867 474/475/866 408/408/868 +f 408/408/868 474/475/866 391/391/869 +f 506/507/870 471/472/864 414/414/863 +f 343/343/871 509/510/872 418/418/873 +f 418/418/873 509/510/872 511/512/874 +f 418/418/873 511/512/874 416/416/875 +f 416/416/875 511/512/874 414/414/863 +f 414/414/863 511/512/874 506/507/870 +f 391/391/869 393/393/876 408/408/868 +f 408/408/868 393/393/876 405/405/857 +f 408/408/868 405/405/857 406/406/856 +f 420/420/860 334/334/854 418/418/873 +f 418/418/873 334/334/854 343/343/871 +f 563/564/877 470/471/878 564/565/879 +f 564/565/879 470/471/878 100/468/880 +f 369/369/881 470/471/878 565/566/882 +f 565/566/882 470/471/878 563/564/877 +f 566/567/883 367/367/884 369/369/881 +f 566/567/883 369/369/881 565/566/882 +f 566/567/883 407/407/885 537/538/886 +f 566/567/883 537/538/886 367/367/884 +f 407/407/885 566/567/883 409/409/887 +f 409/409/887 566/567/883 567/568/888 +f 409/409/887 567/568/888 411/411/889 +f 411/411/889 567/568/888 568/569/890 +f 411/411/889 568/569/890 413/413/891 +f 413/413/891 568/569/890 569/570/892 +f 413/413/891 569/570/892 415/415/893 +f 415/415/893 569/570/892 570/571/894 +f 415/415/893 570/571/894 417/417/895 +f 417/417/895 570/571/894 419/419/896 +f 419/419/896 570/571/894 571/572/897 +f 419/419/896 571/572/897 421/421/898 +f 421/421/898 571/572/897 572/573/899 +f 421/421/898 572/573/899 544/545/900 +f 544/545/900 572/573/899 542/543/901 +f 572/573/899 441/441/902 440/440/903 +f 572/573/899 440/440/903 539/540/904 +f 572/573/899 539/540/904 542/543/901 +f 508/509/905 471/472/864 506/507/870 +f 508/509/905 476/477/906 471/472/864 +f 570/571/907 569/570/907 568/569/907 +f 523/524/908 573/574/909 525/526/910 +f 525/526/910 573/574/909 574/575/911 +f 540/541/912 519/520/913 574/575/914 +f 574/575/914 519/520/913 525/526/915 +f 519/520/916 548/549/917 520/521/918 +f 575/576/919 520/521/918 548/549/917 +f 573/574/920 520/521/921 575/576/922 +f 573/574/920 523/524/923 520/521/921 +f 548/549/924 519/520/924 540/541/924 +f 548/549/925 396/396/925 575/576/925 +f 574/575/926 401/401/926 540/541/926 +f 573/574/927 395/395/927 398/398/927 +f 573/574/928 398/398/928 574/575/928 +f 575/576/929 395/395/930 573/574/931 +f 574/575/932 398/398/932 401/401/932 +f 575/576/929 396/396/933 395/395/930 +f 543/544/934 576/577/935 518/519/936 +f 518/519/936 576/577/935 561/562/937 +f 577/578/938 499/500/939 576/577/940 +f 576/577/940 499/500/939 561/562/941 +f 499/500/942 577/578/943 522/523/944 +f 522/523/944 577/578/943 578/579/945 +f 578/579/946 521/522/946 522/523/946 +f 579/580/947 521/522/947 578/579/947 +f 579/580/948 517/518/949 521/522/950 +f 543/544/951 517/518/949 579/580/948 +f 543/544/952 518/519/748 517/518/747 +f 543/544/953 542/543/953 576/577/953 +f 579/580/948 397/397/954 543/544/951 +f 397/397/955 579/580/956 578/579/957 +f 577/578/958 539/540/958 394/394/958 +f 577/578/959 394/394/959 578/579/959 +f 576/577/960 539/540/961 577/578/962 +f 578/579/957 394/394/963 397/397/955 +f 576/577/960 542/543/964 539/540/961 +f 580/581/965 515/516/966 516/517/967 +f 581/582/968 515/516/966 580/581/965 +f 546/547/969 515/516/970 581/582/971 +f 546/547/969 514/515/972 515/516/970 +f 514/515/973 541/542/973 524/525/973 +f 582/583/974 524/525/974 541/542/974 +f 516/517/975 524/525/975 582/583/975 +f 580/581/976 516/517/976 582/583/976 +f 541/542/977 514/515/977 546/547/977 +f 541/542/978 400/400/978 582/583/978 +f 581/582/979 547/548/980 546/547/981 +f 538/539/982 547/548/980 581/582/979 +f 582/583/983 399/399/983 580/581/983 +f 580/581/984 399/399/984 538/539/984 +f 580/581/985 538/539/982 581/582/979 +f 582/583/986 400/400/986 399/399/986 +f 382/382/987 583/584/988 390/390/989 +f 584/585/990 388/388/991 583/584/992 +f 583/584/992 388/388/991 390/390/993 +f 534/535/994 384/384/995 584/585/996 +f 584/585/996 384/384/995 388/388/997 +f 379/379/998 532/533/999 380/380/1000 +f 380/380/1000 532/533/999 585/586/1001 +f 585/586/1001 382/382/1002 380/380/1000 +f 585/586/1003 583/584/988 382/382/987 +f 534/535/1004 379/379/1005 384/384/1006 +f 532/533/1007 379/379/1005 534/535/1004 +f 532/533/1008 377/377/1008 585/586/1008 +f 584/585/996 372/372/1009 534/535/994 +f 585/586/1010 377/377/1010 371/371/1010 +f 585/586/1011 371/371/1011 583/584/1011 +f 583/584/1012 371/371/1012 372/372/1012 +f 583/584/1013 372/372/1013 584/585/1013 +f 586/587/1014 486/487/1015 389/389/1016 +f 587/588/1017 554/555/1018 586/587/1019 +f 586/587/1019 554/555/1018 486/487/1020 +f 536/537/1021 554/555/1022 587/588/1023 +f 536/537/1021 386/386/1024 554/555/1022 +f 588/589/1025 389/389/1026 589/590/1027 +f 589/590/1027 389/389/1026 387/387/1028 +f 588/589/1029 586/587/1014 389/389/1016 +f 386/386/1030 536/537/777 535/536/776 +f 589/590/1031 387/387/1032 386/386/1033 +f 589/590/1031 386/386/1033 535/536/1034 +f 589/590/1035 370/370/1035 588/589/1035 +f 589/590/1031 535/536/1034 370/370/1036 +f 587/588/1037 367/367/1037 536/537/1037 +f 588/589/1029 370/370/1038 586/587/1014 +f 586/587/1039 370/370/1039 368/368/1039 +f 586/587/1040 368/368/1041 367/367/1042 +f 586/587/1040 367/367/1042 587/588/1043 +f 590/591/1044 383/383/1045 591/592/1046 +f 590/591/1044 381/381/1047 383/383/1045 +f 533/534/1048 378/378/1049 590/591/1050 +f 590/591/1051 378/378/1051 381/381/1051 +f 378/378/1052 530/531/1053 392/392/1054 +f 392/392/1054 530/531/1053 592/593/1055 +f 383/383/1056 392/392/1057 592/593/1058 +f 591/592/1059 383/383/1056 592/593/1058 +f 530/531/1060 378/378/1060 533/534/1060 +f 592/593/1061 530/531/1061 374/374/1061 +f 533/534/1048 590/591/1050 376/376/1062 +f 592/593/1063 374/374/1063 375/375/1063 +f 592/593/1064 375/375/1064 591/592/1064 +f 591/592/1065 375/375/1065 376/376/1065 +f 591/592/1066 376/376/1066 590/591/1066 +f 503/504/1067 478/479/1068 505/506/1069 +f 480/481/1070 478/479/1068 503/504/1067 +f 476/477/1071 508/509/1072 505/506/1073 +f 476/477/1071 505/506/1073 478/479/1074 +f 480/481/1075 363/363/1076 362/362/1077 +f 503/504/1078 366/366/1079 363/363/1076 +f 363/363/1076 480/481/1075 503/504/1078 +f 593/594/1080 594/595/1080 595/596/1080 +f 595/596/1081 594/595/1081 596/597/1081 +f 596/597/1082 597/598/1082 595/596/1082 +f 597/598/1083 593/594/1083 595/596/1083 +f 593/594/1084 451/451/1085 594/595/1086 +f 594/595/1086 451/451/1085 328/328/1087 +f 594/595/1088 328/328/1089 596/597/1090 +f 596/597/1090 328/328/1089 450/450/1091 +f 596/597/1092 450/450/1093 597/598/1094 +f 597/598/1094 450/450/1093 443/443/1095 +f 597/598/1096 443/443/1097 451/451/1098 +f 597/598/1096 451/451/1098 593/594/1099 +f 598/599/1100 599/600/1100 600/601/1100 +f 598/599/1101 600/601/1101 601/602/1101 +f 598/599/1102 601/602/1102 602/603/1102 +f 598/599/1103 602/603/1103 599/600/1103 +f 600/601/1104 330/330/1104 429/429/1104 +f 600/601/1105 429/429/1105 601/602/1105 +f 601/602/1106 429/429/1106 452/452/1106 +f 601/602/1107 452/452/1107 602/603/1107 +f 602/603/1108 452/452/1108 331/331/1108 +f 602/603/1109 331/331/1109 599/600/1109 +f 599/600/1110 331/331/1110 330/330/1110 +f 599/600/1111 330/330/1111 600/601/1111 +f 603/604/1112 604/605/1112 605/606/1112 +f 604/605/1113 606/607/1113 605/606/1113 +f 606/607/1114 607/608/1114 605/606/1114 +f 607/608/1115 603/604/1115 605/606/1115 +f 603/604/1116 457/457/1117 604/605/1118 +f 604/605/1118 457/457/1117 458/458/1119 +f 604/605/1120 458/458/1120 606/607/1120 +f 606/607/1121 458/458/1122 459/459/1123 +f 606/607/1121 459/459/1123 607/608/1124 +f 607/608/1125 459/459/1125 329/329/1125 +f 607/608/1126 329/329/1126 603/604/1126 +f 603/604/1127 329/329/1127 457/457/1127 +f 608/609/1128 609/610/1128 610/611/1128 +f 610/611/1129 611/612/1129 608/609/1129 +f 611/612/1130 612/613/1130 608/609/1130 +f 608/609/1131 612/613/1131 609/610/1131 +f 609/610/1132 431/431/1133 610/611/1134 +f 610/611/1134 431/431/1133 434/434/1135 +f 610/611/1136 434/434/1137 611/612/1138 +f 611/612/1138 434/434/1137 433/433/1139 +f 611/612/1140 433/433/1141 432/432/1142 +f 611/612/1140 432/432/1142 612/613/1143 +f 612/613/1144 432/432/1145 431/431/1146 +f 612/613/1144 431/431/1146 609/610/1147 +f 613/614/1148 614/615/1148 615/616/1148 +f 614/615/1149 616/617/1149 615/616/1149 +f 616/617/1150 617/618/1150 615/616/1150 +f 615/616/1151 617/618/1151 613/614/1151 +f 613/614/1152 438/438/1153 614/615/1154 +f 614/615/1154 438/438/1153 435/435/1155 +f 614/615/1156 435/435/1157 616/617/1158 +f 616/617/1158 435/435/1157 436/436/1159 +f 616/617/1160 436/436/1161 617/618/1162 +f 617/618/1162 436/436/1161 439/439/1163 +f 617/618/1164 439/439/1164 613/614/1164 +f 613/614/1165 439/439/1165 438/438/1165 +f 618/619/1166 619/620/1166 620/621/1166 +f 619/620/1167 621/622/1167 620/621/1167 +f 621/622/1168 622/623/1168 620/621/1168 +f 622/623/1169 618/619/1169 620/621/1169 +f 618/619/1170 444/444/1171 430/430/1172 +f 618/619/1173 430/430/1173 619/620/1173 +f 619/620/1174 430/430/1174 446/446/1174 +f 619/620/1175 446/446/1176 621/622/1177 +f 621/622/1177 446/446/1176 445/445/1178 +f 621/622/1179 445/445/1180 444/444/1181 +f 621/622/1179 444/444/1181 622/623/1182 +f 622/623/1183 444/444/1171 618/619/1170 +f 623/624/1184 624/625/1184 625/626/1184 +f 624/625/1185 626/627/1185 625/626/1185 +f 625/626/1186 626/627/1186 627/628/1186 +f 627/628/1187 623/624/1187 625/626/1187 +f 623/624/1188 423/423/1188 428/428/1188 +f 623/624/1189 428/428/1189 624/625/1189 +f 624/625/1190 428/428/1190 426/426/1190 +f 624/625/1191 426/426/1191 626/627/1191 +f 626/627/1192 426/426/1192 424/424/1192 +f 626/627/1193 424/424/1193 627/628/1193 +f 627/628/1194 424/424/1194 423/423/1194 +f 627/628/1195 423/423/1195 623/624/1195 +f 628/629/1196 629/630/1196 630/631/1196 +f 629/630/1197 631/632/1197 630/631/1197 +f 631/632/1198 632/633/1198 630/631/1198 +f 632/633/1199 628/629/1199 630/631/1199 +f 628/629/1200 449/449/1201 629/630/1202 +f 629/630/1202 449/449/1201 448/448/1203 +f 629/630/1204 448/448/1205 447/447/1206 +f 629/630/1204 447/447/1206 631/632/1207 +f 631/632/1208 447/447/1209 632/633/1210 +f 632/633/1210 447/447/1209 442/442/1211 +f 632/633/1212 442/442/1212 628/629/1212 +f 628/629/1213 442/442/1213 449/449/1213 +f 633/634/1214 634/635/1214 635/636/1214 +f 635/636/1215 634/635/1215 636/637/1215 +f 636/637/1216 637/638/1216 635/636/1216 +f 637/638/1217 633/634/1217 635/636/1217 +f 633/634/1218 453/453/1219 455/455/1220 +f 633/634/1218 455/455/1220 634/635/1221 +f 634/635/1222 455/455/1223 636/637/1224 +f 636/637/1224 455/455/1223 456/456/1225 +f 636/637/1226 456/456/1227 454/454/1228 +f 636/637/1226 454/454/1228 637/638/1229 +f 637/638/1230 454/454/1231 633/634/1232 +f 633/634/1232 454/454/1231 453/453/1233 +f 300/300/485 638/639/1234 301/301/486 +f 301/301/486 638/639/1234 639/640/1235 +f 640/641/1236 301/301/486 639/640/1235 +f 640/641/1236 639/640/1235 641/642/1237 +f 641/642/1237 638/639/1234 642/643/1238 +f 642/643/1238 638/639/1234 300/300/485 +f 303/303/488 643/644/1239 640/641/1236 +f 640/641/1236 641/642/1237 642/643/1238 +f 303/303/488 301/301/486 643/644/1239 +f 644/645/1240 645/646/1241 642/643/1238 +f 642/643/1238 645/646/1241 303/303/488 +f 642/643/1238 303/303/488 640/641/1236 +f 642/643/1242 646/647/1243 647/648/1244 +f 647/648/1244 644/645/528 642/643/1242 +f 303/303/1245 645/646/98 648/649/98 +f 303/303/1245 648/649/98 649/650/1246 +f 650/651/1247 306/306/1247 305/305/1247 +f 651/652/1248 463/463/639 465/465/641 +f 651/652/1248 650/651/1249 463/463/639 +f 308/308/528 300/300/1250 652/653/528 +f 465/465/1251 304/304/528 651/652/528 +f 308/308/528 652/653/528 653/654/528 +f 651/652/1252 306/306/1253 650/651/1254 +f 304/304/1255 306/306/1253 651/652/1252 +f 305/305/1256 307/307/1257 462/462/1258 +f 463/463/1259 650/651/1260 462/462/1258 +f 462/462/1258 650/651/1260 305/305/1256 +f 654/655/1261 319/319/1262 655/656/1263 +f 655/656/1263 319/319/1262 318/318/1264 +f 312/312/1265 654/655/1266 656/657/1267 +f 656/657/1267 311/311/1268 312/312/1265 +f 657/658/1269 655/656/1270 317/317/1271 +f 657/658/1269 317/317/1271 325/325/1272 +f 657/658/1273 324/324/1274 658/659/1275 +f 658/659/1275 324/324/1274 327/327/1276 +f 317/317/1271 655/656/1270 318/318/1277 +f 319/319/1278 654/655/1278 312/312/1278 +f 324/324/1279 657/658/1269 325/325/1272 +f 311/311/1268 656/657/1267 327/327/1280 +f 658/659/1281 327/327/1280 656/657/1267 +f 659/660/1282 660/661/1283 661/662/1284 +f 661/662/1284 660/661/1283 662/663/1285 +f 467/467/643 661/662/1284 466/466/642 +f 466/466/642 661/662/1284 662/663/1285 +f 663/664/1286 664/665/1287 659/660/1282 +f 659/660/1282 664/665/1287 660/661/1283 +f 665/666/1288 464/464/645 666/667/1289 +f 464/464/645 665/666/1288 468/469/646 +f 666/667/1290 660/661/1291 667/668/1292 +f 659/660/1293 665/666/1293 668/669/1293 +f 663/664/1294 665/666/1288 664/665/1295 +f 666/667/1289 664/665/1295 665/666/1288 +f 464/464/1296 466/466/1297 662/663/1298 +f 464/464/1296 662/663/1298 666/667/1290 +f 660/661/1291 666/667/1290 662/663/1298 +f 665/666/1299 659/660/1300 468/469/650 +f 659/660/1300 661/662/1301 468/469/650 +f 468/469/650 661/662/1301 467/467/643 +f 667/668/1302 664/665/1302 666/667/1302 +f 667/668/1303 660/661/1303 664/665/1303 +f 663/664/1304 668/669/1304 665/666/1304 +f 663/664/1305 659/660/1305 668/669/1305 +f 669/670/1306 301/301/1306 670/671/1306 +f 669/670/1307 643/644/1307 301/301/1307 +f 643/644/1308 669/670/1308 671/672/1308 +f 643/644/1309 671/672/1309 640/641/1309 +f 640/641/1310 671/672/1310 670/671/1310 +f 670/671/1311 301/301/1311 640/641/1311 +f 639/640/1312 672/673/1312 641/642/1312 +f 641/642/1313 673/674/1313 638/639/1313 +f 674/675/1314 638/639/1314 673/674/1314 +f 638/639/1315 674/675/1315 639/640/1315 +f 300/300/1316 302/302/1317 652/653/1318 +f 652/653/1318 302/302/1317 675/676/1319 +f 676/677/1320 677/678/1321 678/679/1322 +f 652/653/1323 679/680/1324 680/681/1325 +f 679/680/1324 652/653/1323 675/676/1326 +f 653/654/1327 676/677/1320 678/679/1322 +f 678/679/1322 681/682/1328 675/676/1326 +f 675/676/1326 681/682/1328 682/683/1329 +f 675/676/1326 677/678/1321 679/680/1324 +f 676/677/1320 653/654/1327 683/684/1330 +f 676/677/1320 683/684/1330 684/685/1331 +f 680/681/1325 684/685/1331 685/686/1332 +f 686/687/1333 683/684/1330 653/654/1327 +f 680/681/1325 685/686/1332 652/653/1323 +f 685/686/1332 686/687/1333 652/653/1323 +f 684/685/1331 680/681/1325 676/677/1320 +f 682/683/1329 687/688/1334 677/678/1321 +f 687/688/1334 681/682/1328 677/678/1321 +f 677/678/1321 681/682/1328 678/679/1322 +f 652/653/1323 686/687/1333 653/654/1327 +f 675/676/1326 682/683/1329 677/678/1321 +f 653/654/1335 678/679/1336 308/308/1337 +f 308/308/1337 678/679/1336 460/460/1338 +f 308/308/493 460/460/636 307/307/492 +f 675/676/1339 460/460/98 678/679/98 +f 688/689/1340 689/690/1340 690/691/1340 +f 688/689/1341 690/691/1341 691/692/1341 +f 688/689/1342 691/692/1342 692/693/1342 +f 688/689/1343 692/693/1343 689/690/1343 +f 689/690/1344 683/684/1345 686/687/1346 +f 689/690/1344 686/687/1346 690/691/1347 +f 690/691/1348 686/687/1349 691/692/1350 +f 691/692/1350 686/687/1349 685/686/1351 +f 691/692/1352 685/686/1353 692/693/1354 +f 692/693/1354 685/686/1353 684/685/1355 +f 692/693/1356 684/685/1357 689/690/1358 +f 689/690/1358 684/685/1357 683/684/1359 +f 693/694/1360 694/695/1360 695/696/1360 +f 694/695/1361 696/697/1361 695/696/1361 +f 696/697/1362 697/698/1362 695/696/1362 +f 695/696/1363 697/698/1363 693/694/1363 +f 693/694/1364 681/682/1364 687/688/1364 +f 693/694/1365 687/688/1365 694/695/1365 +f 694/695/1366 687/688/1366 682/683/1366 +f 694/695/1367 682/683/1367 696/697/1367 +f 696/697/1368 682/683/1369 697/698/1370 +f 697/698/1370 682/683/1369 681/682/1371 +f 697/698/1372 681/682/1372 693/694/1372 +f 698/699/1373 699/700/1373 700/701/1373 +f 700/701/1374 699/700/1374 701/702/1374 +f 701/702/1375 702/703/1375 700/701/1375 +f 702/703/1376 698/699/1376 700/701/1376 +f 698/699/1377 676/677/1378 699/700/1379 +f 699/700/1379 676/677/1378 680/681/1380 +f 699/700/1381 680/681/1382 679/680/1383 +f 699/700/1381 679/680/1383 701/702/1384 +f 701/702/1385 679/680/1386 677/678/1387 +f 701/702/1385 677/678/1387 702/703/1388 +f 702/703/1389 677/678/1390 698/699/1391 +f 698/699/1391 677/678/1390 676/677/1392 +f 649/650/1393 703/704/1394 704/705/1395 +f 703/704/1394 646/647/1396 705/706/1397 +f 704/705/1395 703/704/1394 705/706/1397 +f 706/707/1398 707/708/1399 708/709/1400 +f 708/709/1400 707/708/1399 709/710/1401 +f 709/710/1401 710/711/1402 708/709/1400 +f 313/313/1403 711/712/1404 314/314/1405 +f 314/314/1405 711/712/1404 712/713/1406 +f 713/714/1407 714/715/1408 712/713/1409 +f 713/714/1407 712/713/1409 711/712/1410 +f 365/365/1411 715/716/1412 716/717/1413 +f 713/714/1407 717/718/1414 714/715/1408 +f 714/715/1408 717/718/1414 715/716/1412 +f 715/716/1412 717/718/1414 718/719/1415 +f 715/716/1412 718/719/1415 716/717/1413 +f 719/720/1416 715/716/1412 365/365/1411 +f 719/720/1416 365/365/1411 720/721/1417 +f 721/722/1418 722/723/1419 723/724/1420 +f 723/724/1420 724/725/1421 725/726/1422 +f 724/725/1421 726/727/1423 725/726/1422 +f 727/728/1424 725/726/1422 726/727/1423 +f 723/724/1420 728/729/1425 724/725/1421 +f 723/724/1420 722/723/1419 728/729/1425 +f 728/729/1425 722/723/1419 729/730/1426 +f 728/729/1425 729/730/1426 730/731/1427 +f 731/732/1428 732/733/1429 728/729/1425 +f 728/729/1425 732/733/1429 724/725/1421 +f 733/734/1430 734/735/1431 735/736/1432 +f 734/735/1431 736/737/1433 735/736/1432 +f 734/735/1431 737/738/1434 736/737/1433 +f 736/737/1433 737/738/1434 738/739/1435 +f 739/740/1436 740/741/1437 741/742/1438 +f 740/741/1437 739/740/1436 742/743/1439 +f 742/743/1439 739/740/1436 743/744/1440 +f 742/743/1441 743/744/1442 744/745/1443 +f 742/743/1441 744/745/1443 745/746/1444 +f 744/745/1443 746/747/1445 745/746/1444 +f 739/740/1446 741/742/1447 738/739/1448 +f 739/740/1446 738/739/1448 737/738/1449 +f 739/740/1450 737/738/1451 747/748/1452 +f 747/748/1452 737/738/1451 748/749/1453 +f 748/749/1453 737/738/1451 749/750/1454 +f 748/749/1453 749/750/1454 750/751/1455 +f 748/749/1453 750/751/1455 751/752/1456 +f 750/751/1455 744/745/1443 751/752/1456 +f 744/745/1443 750/751/1455 752/753/1457 +f 752/753/1457 733/734/1458 735/736/1459 +f 753/754/1460 754/755/1461 755/756/1462 +f 756/757/1463 757/758/1464 758/759/1465 +f 756/757/1463 758/759/1465 759/760/1466 +f 760/761/1467 761/762/1468 762/763/1469 +f 760/761/1467 763/764/1470 761/762/1468 +f 764/765/1471 765/766/1472 766/767/1473 +f 735/736/1474 767/768/1475 768/769/1476 +f 768/769/1476 767/768/1475 769/770/1477 +f 769/770/1477 770/771/528 768/769/1476 +f 771/772/1478 772/773/1479 773/774/1480 +f 773/774/1480 772/773/1479 774/775/1481 +f 773/774/1480 774/775/1481 775/776/1482 +f 775/776/1482 774/775/1481 776/777/1483 +f 775/776/1482 776/777/1483 777/778/1484 +f 777/778/1484 776/777/1483 778/779/1485 +f 777/778/1484 778/779/1485 779/780/1486 +f 779/780/1486 778/779/1485 780/781/1487 +f 779/780/1486 780/781/1487 781/782/1488 +f 781/782/1488 780/781/1487 782/783/1489 +f 781/782/1488 782/783/1489 736/737/1490 +f 736/737/1491 782/783/1491 783/784/1491 +f 783/784/1492 782/783/1493 784/785/1494 +f 783/784/1492 784/785/1494 785/786/1495 +f 785/786/1495 784/785/1494 786/787/1496 +f 754/755/1461 787/788/1497 788/789/1498 +f 337/337/1499 787/788/1497 754/755/1461 +f 788/789/1498 787/788/1497 789/790/1500 +f 790/791/1501 791/792/1500 350/350/1502 +f 337/337/1499 792/793/1503 787/788/1497 +f 789/790/1500 791/792/1500 790/791/1501 +f 350/350/1502 791/792/1500 792/793/1503 +f 788/789/1498 789/790/1500 790/791/1501 +f 350/350/1502 792/793/1503 337/337/1499 +f 793/794/1504 794/795/1505 795/796/1506 +f 795/796/1506 794/795/1505 796/797/1507 +f 797/798/1501 798/799/1508 799/800/1502 +f 795/796/1506 796/797/1507 797/798/1501 +f 795/796/1506 797/798/1501 799/800/1502 +f 716/717/1413 718/719/1415 800/801/1509 +f 790/791/1501 801/802/1501 802/803/1503 +f 798/799/1508 801/802/1501 790/791/1501 +f 788/789/1498 803/804/1510 794/795/1505 +f 794/795/1505 803/804/1510 804/805/1511 +f 798/799/1508 804/805/1511 801/802/1501 +f 788/789/1498 805/806/1512 803/804/1510 +f 790/791/1501 802/803/1503 788/789/1498 +f 788/789/1498 802/803/1503 805/806/1512 +f 806/807/1513 807/808/1514 808/809/1503 +f 809/810/1501 798/799/1508 810/811/1501 +f 790/791/1501 810/811/1501 798/799/1508 +f 798/799/1508 809/810/1501 807/808/1514 +f 807/808/1514 809/810/1501 808/809/1503 +f 790/791/1501 811/812/1515 810/811/1501 +f 806/807/1513 811/812/1515 790/791/1501 +f 812/813/1501 813/814/1502 352/352/1516 +f 350/350/1502 813/814/1502 814/815/1501 +f 350/350/1502 814/815/1501 790/791/1501 +f 790/791/1501 812/813/1501 806/807/1513 +f 352/352/1516 813/814/1502 350/350/1502 +f 352/352/1516 815/816/1501 800/801/1509 +f 352/352/1516 800/801/1509 807/808/1514 +f 352/352/1516 807/808/1514 806/807/1513 +f 352/352/1516 806/807/1513 812/813/1501 +f 365/365/1411 716/717/1413 816/817/1517 +f 352/352/1516 816/817/1517 815/816/1501 +f 365/365/1411 816/817/1517 352/352/1516 +f 800/801/1509 815/816/1501 817/818/1518 +f 800/801/1509 817/818/1518 716/717/1413 +f 818/819/1519 819/820/1503 807/808/1514 +f 798/799/1508 820/821/1502 799/800/1502 +f 799/800/1502 820/821/1502 821/822/1500 +f 807/808/1514 819/820/1503 820/821/1502 +f 794/795/1505 804/805/1511 798/799/1508 +f 798/799/1508 807/808/1514 820/821/1502 +f 799/800/1502 821/822/1500 822/823/1520 +f 822/823/1520 821/822/1500 818/819/1519 +f 807/808/1514 822/823/1520 818/819/1519 +f 807/808/1514 823/824/1521 822/823/1520 +f 822/823/1520 823/824/1521 824/825/1522 +f 713/714/1407 825/826/1523 717/718/1414 +f 824/825/1522 825/826/1523 713/714/1407 +f 717/718/1414 823/824/1521 807/808/1514 +f 825/826/1523 823/824/1521 717/718/1414 +f 822/823/1520 824/825/1522 713/714/1407 +f 321/321/507 322/322/508 720/721/1524 +f 720/721/1524 322/322/508 719/720/1525 +f 826/827/1526 827/828/1527 828/829/1528 +f 828/829/1528 827/828/1527 706/707/1398 +f 706/707/1398 827/828/1527 829/830/1529 +f 830/831/1530 831/832/1531 826/827/1526 +f 826/827/1526 831/832/1531 832/833/1532 +f 833/834/1533 235/835/1534 832/833/1532 +f 832/833/1532 235/835/1534 827/828/1527 +f 832/833/1532 827/828/1527 826/827/1526 +f 834/836/1535 835/837/1536 836/838/1537 +f 834/836/1535 836/838/1537 833/834/1533 +f 833/834/1533 836/838/1537 235/835/1534 +f 835/837/1536 830/831/1530 769/770/1538 +f 834/836/1535 831/832/1531 835/837/1536 +f 835/837/1536 831/832/1531 830/831/1530 +f 736/737/1433 738/739/1435 837/839/1539 +f 837/839/1539 738/739/1435 838/840/1540 +f 838/840/1540 839/841/1541 837/839/1539 +f 837/839/1539 839/841/1541 840/842/1542 +f 840/842/1542 839/841/1541 841/843/1543 +f 842/844/1544 764/765/1545 840/842/1546 +f 842/844/1544 840/842/1546 841/843/1547 +f 843/845/1548 844/846/1549 842/844/1544 +f 842/844/1544 844/846/1549 845/847/1550 +f 842/844/1544 845/847/1550 764/765/1545 +f 843/845/1548 347/347/1551 844/846/1549 +f 846/848/1552 347/347/1551 843/845/1548 +f 847/849/1553 346/346/1554 846/848/1552 +f 846/848/1552 346/346/1554 347/347/1551 +f 346/346/1555 847/849/1556 848/850/1557 +f 346/346/1555 848/850/1557 770/771/1558 +f 770/771/1558 848/850/1557 849/851/1559 +f 770/771/1560 849/851/1561 768/769/1562 +f 768/769/1562 849/851/1561 850/852/1563 +f 850/852/1564 746/747/1445 744/745/1443 +f 735/736/1459 768/769/1565 752/753/1457 +f 850/852/1564 744/745/1443 768/769/1565 +f 768/769/1565 744/745/1443 752/753/1457 +f 851/853/1566 852/854/1567 853/855/1568 +f 854/856/1569 851/853/1566 855/857/1570 +f 855/857/1570 851/853/1566 853/855/1568 +f 353/353/1571 856/858/1572 857/859/1573 +f 353/353/1571 857/859/1573 341/341/1574 +f 341/341/1575 857/859/1576 360/360/1577 +f 360/360/1577 857/859/1576 858/860/1578 +f 360/360/1579 858/860/1580 348/348/1581 +f 348/348/1581 858/860/1580 859/861/1582 +f 348/348/1583 859/861/1584 351/351/1585 +f 351/351/1585 859/861/1584 860/862/1586 +f 351/351/1587 860/862/1588 353/353/1589 +f 353/353/1589 860/862/1588 856/858/1590 +f 860/862/528 859/861/528 858/860/528 +f 858/860/528 857/859/528 860/862/528 +f 860/862/528 857/859/528 856/858/528 +f 336/336/1591 861/863/1592 862/864/1593 +f 336/336/1591 862/864/1593 344/344/1594 +f 344/344/1595 862/864/1596 339/339/1597 +f 339/339/1597 862/864/1596 863/865/1598 +f 339/339/1599 863/865/1600 864/866/1601 +f 339/339/1599 864/866/1601 340/340/1602 +f 340/340/1602 864/866/1601 865/867/1603 +f 866/868/1604 867/869/1605 868/870/1606 +f 866/868/1604 868/870/1606 865/867/1607 +f 865/867/1607 868/870/1606 340/340/1608 +f 340/340/1608 868/870/1606 349/349/1609 +f 867/869/1605 866/868/1604 766/767/1610 +f 866/868/1604 869/871/1611 766/767/1610 +f 869/871/1611 866/868/1604 870/872/1612 +f 869/871/1613 870/872/1614 871/873/1615 +f 869/871/1613 871/873/1615 872/874/1616 +f 872/874/1616 871/873/1615 873/875/1617 +f 872/874/1616 873/875/1617 874/876/1618 +f 872/874/1616 874/876/1618 875/877/1619 +f 876/878/1620 877/879/1621 878/880/1622 +f 876/878/1620 878/880/1622 879/881/1623 +f 876/878/1620 879/881/1623 880/882/1624 +f 880/882/1625 879/881/1626 881/883/1627 +f 881/883/1627 879/881/1626 882/884/1628 +f 881/883/1629 882/884/1629 875/877/1629 +f 881/883/1630 874/876/1618 883/885/1631 +f 881/883/1632 883/885/1633 884/886/1634 +f 884/886/1634 883/885/1633 885/887/1635 +f 885/887/1635 883/885/1633 886/888/1636 +f 885/887/1635 886/888/1636 887/889/1637 +f 888/890/1638 887/889/1637 886/888/1636 +f 888/890/1638 876/878/1620 887/889/1637 +f 874/876/1618 889/891/1639 883/885/1631 +f 875/877/1619 874/876/1618 881/883/1630 +f 875/877/1640 882/884/1641 338/338/1642 +f 338/338/1642 882/884/1641 890/892/1643 +f 890/892/1644 877/879/1621 338/338/1645 +f 338/338/1645 877/879/1621 336/336/1646 +f 336/336/1646 876/878/1620 861/863/1647 +f 876/878/1620 888/890/1638 861/863/1647 +f 336/336/1646 877/879/1621 876/878/1620 +f 891/893/1648 892/894/1649 893/895/1650 +f 892/894/1649 891/893/1648 894/896/1651 +f 730/731/1427 729/730/1426 895/897/1652 +f 730/731/1427 895/897/1652 896/898/1653 +f 897/899/1654 727/728/1655 898/900/1656 +f 898/900/1656 896/898/1653 899/901/1657 +f 896/898/1658 898/900/1659 900/902/1660 +f 896/898/1653 895/897/1652 901/903/1661 +f 896/898/1653 901/903/1661 899/901/1657 +f 901/903/1661 721/722/1662 899/901/1657 +f 900/902/1663 898/900/1664 732/733/1429 +f 900/902/1663 732/733/1429 731/732/1428 +f 785/786/1665 786/787/1666 897/899/1667 +f 785/786/1665 897/899/1667 899/901/1668 +f 899/901/1657 897/899/1654 898/900/1656 +f 793/794/1504 902/904/1669 759/760/1466 +f 754/755/1461 759/760/1466 762/763/1469 +f 762/763/1469 759/760/1466 758/759/1465 +f 754/755/1461 762/763/1469 761/762/1468 +f 761/762/1468 755/756/1462 754/755/1461 +f 793/794/1504 759/760/1466 754/755/1461 +f 754/755/1461 788/789/1498 793/794/1504 +f 793/794/1504 788/789/1498 794/795/1505 +f 772/773/1670 771/772/1671 903/905/1672 +f 772/773/1670 903/905/1672 904/906/1673 +f 903/905/1674 753/754/1675 905/907/1676 +f 906/908/1677 903/905/1674 905/907/1676 +f 907/909/1678 908/910/1679 904/906/1680 +f 906/908/1677 909/911/1681 903/905/1674 +f 909/911/1681 907/909/1678 903/905/1674 +f 903/905/1674 907/909/1678 904/906/1680 +f 907/909/1678 909/911/1681 757/758/1464 +f 907/909/1678 757/758/1464 756/757/1463 +f 763/764/1470 760/761/1467 906/908/1677 +f 763/764/1470 906/908/1677 905/907/1676 +f 723/724/1420 725/726/1422 835/837/1536 +f 835/837/1536 725/726/1422 836/838/1537 +f 843/845/1682 842/844/1683 910/912/1684 +f 843/845/1682 910/912/1684 911/913/1685 +f 911/913/1685 910/912/1684 854/856/1569 +f 911/913/1685 854/856/1569 855/857/1570 +f 847/849/1686 911/913/1687 855/857/1688 +f 843/845/1548 911/913/1687 846/848/1552 +f 847/849/1686 846/848/1552 911/913/1687 +f 841/843/1547 910/912/1689 842/844/1544 +f 848/850/1690 847/849/1686 855/857/1688 +f 848/850/1690 855/857/1688 853/855/1691 +f 841/843/1692 839/841/1693 910/912/1694 +f 910/912/1694 839/841/1693 851/853/1695 +f 910/912/1694 851/853/1695 854/856/1696 +f 839/841/1693 912/914/1697 851/853/1695 +f 839/841/1693 838/840/1698 912/914/1697 +f 838/840/1698 738/739/1699 912/914/1697 +f 912/914/1697 738/739/1699 852/854/1700 +f 912/914/1697 852/854/1700 851/853/1695 +f 849/851/1701 848/850/1702 853/855/1703 +f 850/852/1704 849/851/1701 853/855/1703 +f 738/739/1705 741/742/1705 913/915/1705 +f 852/854/1706 738/739/1707 913/915/1708 +f 746/747/1445 850/852/1564 913/915/1708 +f 913/915/1708 850/852/1564 852/854/1706 +f 852/854/1706 850/852/1564 853/855/1709 +f 866/868/1604 865/867/1607 914/916/1710 +f 914/916/1710 865/867/1607 915/917/1711 +f 914/916/1712 915/917/1713 893/895/1650 +f 893/895/1650 915/917/1713 891/893/1648 +f 866/868/1604 914/916/1714 870/872/1612 +f 870/872/1612 914/916/1714 893/895/1715 +f 915/917/1713 864/866/1716 891/893/1648 +f 863/865/1717 916/918/1718 864/866/1716 +f 891/893/1648 864/866/1716 916/918/1718 +f 915/917/1713 865/867/1719 864/866/1716 +f 874/876/1720 873/875/1721 892/894/1649 +f 874/876/1720 892/894/1649 917/919/1722 +f 894/896/1651 917/919/1722 892/894/1649 +f 873/875/1721 871/873/1723 892/894/1649 +f 871/873/1723 893/895/1715 892/894/1649 +f 871/873/1723 870/872/1612 893/895/1715 +f 863/865/1724 862/864/1725 916/918/1726 +f 916/918/1726 862/864/1725 918/920/1727 +f 916/918/1728 918/920/1729 891/893/1648 +f 891/893/1648 918/920/1729 894/896/1651 +f 889/891/1730 874/876/1720 919/921/1731 +f 861/863/1647 888/890/1638 919/921/1732 +f 920/922/1733 917/919/1722 921/923/1734 +f 921/923/1734 917/919/1722 894/896/1651 +f 920/922/1735 919/921/1731 874/876/1720 +f 920/922/1735 874/876/1720 917/919/1722 +f 861/863/1647 919/921/1732 920/922/1736 +f 921/923/1734 894/896/1651 918/920/1729 +f 862/864/1737 921/923/1734 918/920/1729 +f 861/863/1647 920/922/1736 921/923/1734 +f 861/863/1647 921/923/1734 862/864/1737 +f 723/724/1738 835/837/1739 769/770/1740 +f 767/768/1741 721/722/1742 769/770/1740 +f 769/770/1740 721/722/1742 723/724/1738 +f 335/335/1743 337/337/1744 754/755/1745 +f 335/335/1743 754/755/1745 753/754/1746 +f 767/768/1741 785/786/1747 899/901/1748 +f 767/768/1741 899/901/1748 721/722/1742 +f 771/772/1749 335/335/1743 903/905/1750 +f 903/905/1750 335/335/1743 753/754/1746 +f 773/774/1751 875/877/1752 338/338/1753 +f 779/780/1486 869/871/1754 777/778/1755 +f 777/778/1755 869/871/1754 872/874/1756 +f 777/778/1755 872/874/1756 775/776/1757 +f 775/776/1757 872/874/1756 773/774/1751 +f 773/774/1751 872/874/1756 875/877/1752 +f 840/842/1758 869/871/1754 779/780/1486 +f 783/784/1759 735/736/1760 736/737/1761 +f 736/737/1762 837/839/1762 781/782/1762 +f 781/782/1488 837/839/1763 779/780/1486 +f 779/780/1486 837/839/1763 840/842/1758 +f 335/335/1743 771/772/1749 773/774/1751 +f 335/335/1743 773/774/1751 338/338/1753 +f 785/786/1747 767/768/1741 783/784/1759 +f 783/784/1759 767/768/1741 735/736/1760 +f 836/838/1764 922/924/1765 923/925/1766 +f 923/925/1766 235/835/1767 836/838/1764 +f 922/924/1765 836/838/1764 725/726/1768 +f 922/924/1765 725/726/1768 924/926/1769 +f 727/728/1770 925/927/1771 725/726/1768 +f 725/726/1768 925/927/1771 924/926/1769 +f 786/787/1772 925/927/1771 897/899/1773 +f 897/899/1773 925/927/1771 727/728/1770 +f 925/927/1771 786/787/1772 784/785/1774 +f 925/927/1771 784/785/1774 926/928/1775 +f 926/928/1775 784/785/1774 782/783/1776 +f 926/928/1775 782/783/1776 927/929/1777 +f 927/929/1777 782/783/1776 780/781/1778 +f 927/929/1777 780/781/1778 928/930/1779 +f 928/930/1779 780/781/1778 778/779/1780 +f 928/930/1779 778/779/1780 929/931/1781 +f 929/931/1781 778/779/1780 776/777/1782 +f 929/931/1781 776/777/1782 930/932/1783 +f 930/932/1783 776/777/1782 774/775/1784 +f 930/932/1783 774/775/1784 931/933/1785 +f 931/933/1785 774/775/1784 772/773/1786 +f 931/933/1785 772/773/1786 904/906/1787 +f 931/933/1788 904/906/1789 908/910/1790 +f 931/933/1788 908/910/1790 902/904/1791 +f 902/904/1791 793/794/1792 931/933/1788 +f 931/933/1788 793/794/1792 795/796/1793 +f 764/765/1471 869/871/1754 840/842/1758 +f 764/765/1471 766/767/1473 869/871/1754 +f 926/928/1794 927/929/1794 928/930/1794 +f 928/930/1795 929/931/1795 930/932/1795 +f 881/883/1796 906/908/1797 932/934/1798 +f 881/883/1796 932/934/1798 880/882/1799 +f 933/935/1800 876/878/1801 932/934/1802 +f 932/934/1802 876/878/1801 880/882/1803 +f 933/935/1804 934/936/1805 876/878/1806 +f 934/936/1805 887/889/1807 876/878/1806 +f 887/889/1808 934/936/1809 935/937/1810 +f 887/889/1808 935/937/1810 885/887/1811 +f 909/911/1812 885/887/1813 935/937/1814 +f 909/911/1812 884/886/1815 885/887/1813 +f 906/908/1816 881/883/1817 909/911/1818 +f 909/911/1818 881/883/1817 884/886/1819 +f 932/934/1820 760/761/1821 933/935/1822 +f 932/934/1798 906/908/1797 760/761/1823 +f 935/937/1824 757/758/1824 909/911/1824 +f 933/935/1825 762/763/1826 934/936/1827 +f 934/936/1827 762/763/1826 758/759/1828 +f 934/936/1829 758/759/1830 935/937/1831 +f 935/937/1831 758/759/1830 757/758/1832 +f 933/935/1822 760/761/1821 762/763/1833 +f 936/938/1834 888/890/1834 937/939/1834 +f 936/938/1835 919/921/1836 888/890/1837 +f 938/940/1838 919/921/1836 936/938/1835 +f 939/941/1839 919/921/1840 938/940/1841 +f 939/941/1839 889/891/1842 919/921/1840 +f 883/885/1843 907/909/1844 940/942/1845 +f 883/885/1843 940/942/1845 886/888/1846 +f 937/939/1847 886/888/1847 940/942/1847 +f 888/890/1848 886/888/1848 937/939/1848 +f 939/941/1849 883/885/1631 889/891/1639 +f 907/909/1850 883/885/1631 939/941/1849 +f 940/942/1851 756/757/1852 937/939/1853 +f 939/941/1849 908/910/1854 907/909/1850 +f 940/942/1855 907/909/1855 756/757/1855 +f 938/940/1856 908/910/1857 939/941/1858 +f 902/904/1859 908/910/1857 938/940/1856 +f 937/939/1860 759/760/1860 936/938/1860 +f 936/938/1861 759/760/1861 902/904/1861 +f 936/938/1862 902/904/1859 938/940/1856 +f 937/939/1853 756/757/1852 759/760/1863 +f 882/884/1864 941/943/1865 942/944/1866 +f 882/884/1864 942/944/1866 890/892/1867 +f 943/945/1868 890/892/1869 942/944/1870 +f 943/945/1868 877/879/1871 890/892/1869 +f 943/945/1872 944/946/1873 877/879/1874 +f 944/946/1873 878/880/1875 877/879/1874 +f 878/880/1808 944/946/1809 945/947/1810 +f 878/880/1808 945/947/1810 879/881/1811 +f 905/907/1876 879/881/1877 945/947/1878 +f 905/907/1876 882/884/1879 879/881/1877 +f 882/884/1880 905/907/1881 941/943/1882 +f 942/944/1883 753/754/1884 943/945/1885 +f 941/943/1882 905/907/1881 753/754/1886 +f 941/943/1887 753/754/1887 942/944/1887 +f 945/947/1888 763/764/1888 905/907/1888 +f 943/945/1889 755/756/1890 761/762/1891 +f 943/945/1889 761/762/1891 944/946/1892 +f 944/946/1893 761/762/1894 945/947/1895 +f 945/947/1895 761/762/1894 763/764/1896 +f 943/945/1885 753/754/1884 755/756/1897 +f 739/740/1898 900/902/1899 946/948/1900 +f 739/740/1898 946/948/1900 743/744/1901 +f 946/948/1902 744/745/1903 743/744/1904 +f 946/948/1902 947/949/1905 744/745/1903 +f 948/950/1906 751/752/1907 947/949/1908 +f 947/949/1908 751/752/1907 744/745/1909 +f 751/752/1910 948/950/1910 748/749/1910 +f 896/898/1911 748/749/1912 948/950/1913 +f 896/898/1911 747/748/1914 748/749/1912 +f 747/748/1915 896/898/1658 900/902/1660 +f 900/902/1660 739/740/1916 747/748/1915 +f 946/948/1917 900/902/1917 731/732/1917 +f 948/950/1918 730/731/1918 896/898/1918 +f 946/948/1919 731/732/1920 728/729/1921 +f 946/948/1919 728/729/1921 947/949/1922 +f 947/949/1923 728/729/1924 948/950/1925 +f 948/950/1925 728/729/1924 730/731/1926 +f 741/742/1927 949/951/1928 913/915/1929 +f 949/951/1928 950/952/1930 913/915/1929 +f 950/952/1931 746/747/1932 913/915/1933 +f 951/953/1934 746/747/1932 950/952/1931 +f 951/953/1935 745/746/1935 746/747/1935 +f 745/746/1936 951/953/1937 952/954/1938 +f 745/746/1936 952/954/1938 742/743/1939 +f 898/900/1940 742/743/1941 952/954/1942 +f 898/900/1940 740/741/1943 742/743/1941 +f 740/741/1944 898/900/1945 949/951/1946 +f 949/951/1946 741/742/1947 740/741/1944 +f 949/951/1948 727/728/1948 950/952/1948 +f 949/951/1946 898/900/1945 727/728/1949 +f 952/954/1950 732/733/1950 898/900/1950 +f 950/952/1951 727/728/1951 726/727/1951 +f 950/952/1952 726/727/1952 951/953/1952 +f 951/953/1953 726/727/1953 724/725/1953 +f 951/953/1954 724/725/1955 952/954/1956 +f 952/954/1956 724/725/1955 732/733/1957 +f 737/738/1958 953/955/1959 954/956/1960 +f 737/738/1958 954/956/1960 749/750/1961 +f 954/956/1962 750/751/1962 749/750/1962 +f 955/957/1963 752/753/1964 954/956/1965 +f 954/956/1965 752/753/1964 750/751/1966 +f 955/957/1967 733/734/1968 752/753/1969 +f 733/734/1968 955/957/1967 956/958/1970 +f 901/903/1971 734/735/1972 956/958/1973 +f 956/958/1973 734/735/1972 733/734/1974 +f 734/735/1431 901/903/1975 953/955/1976 +f 953/955/1976 737/738/1434 734/735/1431 +f 954/956/1977 895/897/1977 729/730/1977 +f 953/955/1976 901/903/1975 895/897/1978 +f 953/955/1979 895/897/1979 954/956/1979 +f 956/958/1980 721/722/1980 901/903/1980 +f 954/956/1981 729/730/1982 722/723/1983 +f 954/956/1981 722/723/1983 955/957/1984 +f 955/957/1985 722/723/1986 956/958/1987 +f 956/958/1987 722/723/1986 721/722/1988 +f 845/847/1989 844/846/1990 867/869/1991 +f 868/870/1992 867/869/1991 844/846/1990 +f 764/765/1993 845/847/1993 765/766/1993 +f 867/869/1994 766/767/1995 765/766/1996 +f 765/766/1996 845/847/1997 867/869/1994 +f 347/347/1998 868/870/1999 844/846/2000 +f 868/870/1999 347/347/1998 349/349/2001 +f 957/959/2002 958/960/2002 959/961/2002 +f 957/959/2003 959/961/2003 960/962/2003 +f 960/962/2004 961/963/2004 957/959/2004 +f 961/963/2005 962/964/2005 957/959/2005 +f 957/959/2006 962/964/2006 958/960/2006 +f 958/960/2007 825/826/2007 959/961/2007 +f 959/961/2008 825/826/2008 824/825/2008 +f 959/961/2009 824/825/2009 960/962/2009 +f 960/962/2010 824/825/2011 823/824/2012 +f 960/962/2010 823/824/2012 961/963/2013 +f 961/963/2014 823/824/2014 962/964/2014 +f 962/964/2015 823/824/2016 825/826/2017 +f 962/964/2015 825/826/2017 958/960/2018 +f 963/965/2019 964/966/2019 965/967/2019 +f 965/967/2020 964/966/2020 966/968/2020 +f 965/967/2021 966/968/2021 967/969/2021 +f 967/969/2022 963/965/2022 965/967/2022 +f 967/969/2023 800/801/2023 718/719/2023 +f 967/969/2024 718/719/2024 963/965/2024 +f 963/965/2025 718/719/2026 717/718/2027 +f 963/965/2025 717/718/2027 964/966/2028 +f 964/966/2029 717/718/2030 807/808/2031 +f 964/966/2029 807/808/2031 966/968/2032 +f 966/968/2033 807/808/2034 800/801/2035 +f 966/968/2033 800/801/2035 967/969/2036 +f 968/970/2037 969/971/2037 970/972/2037 +f 969/971/2038 971/973/2038 970/972/2038 +f 971/973/2039 972/974/2039 970/972/2039 +f 970/972/2040 972/974/2040 968/970/2040 +f 968/970/2041 716/717/2042 817/818/2043 +f 968/970/2041 817/818/2043 969/971/2044 +f 969/971/2045 817/818/2046 815/816/2047 +f 969/971/2045 815/816/2047 971/973/2048 +f 971/973/2049 815/816/2050 816/817/2051 +f 971/973/2049 816/817/2051 972/974/2052 +f 972/974/2053 816/817/2054 716/717/2055 +f 972/974/2053 716/717/2055 968/970/2056 +f 973/975/2057 974/976/2057 975/977/2057 +f 975/977/2058 974/976/2058 976/978/2058 +f 975/977/2059 976/978/2059 977/979/2059 +f 977/979/2060 973/975/2060 975/977/2060 +f 977/979/2061 805/806/2062 802/803/2063 +f 977/979/2061 802/803/2063 973/975/2064 +f 973/975/2065 802/803/2065 801/802/2065 +f 973/975/2066 801/802/2067 974/976/2068 +f 974/976/2068 801/802/2067 804/805/2069 +f 974/976/2070 804/805/2071 976/978/2072 +f 976/978/2072 804/805/2071 803/804/2073 +f 976/978/2074 803/804/2075 977/979/2076 +f 977/979/2076 803/804/2075 805/806/2077 +f 978/980/2078 979/981/2078 980/982/2078 +f 979/981/2079 981/983/2079 980/982/2079 +f 980/982/2080 981/983/2080 982/984/2080 +f 982/984/2081 978/980/2081 980/982/2081 +f 982/984/2082 811/812/2083 978/980/2084 +f 978/980/2084 811/812/2083 806/807/2085 +f 978/980/2086 806/807/2087 808/809/2088 +f 978/980/2086 808/809/2088 979/981/2089 +f 979/981/2090 808/809/2090 809/810/2090 +f 979/981/2091 809/810/2091 981/983/2091 +f 981/983/2092 809/810/2092 810/811/2092 +f 981/983/2093 810/811/2094 982/984/2095 +f 982/984/2095 810/811/2094 811/812/2096 +f 983/985/2097 984/986/2097 985/987/2097 +f 984/986/2098 986/988/2098 985/987/2098 +f 986/988/2099 987/989/2099 985/987/2099 +f 987/989/2100 983/985/2100 985/987/2100 +f 983/985/2101 797/798/2101 984/986/2101 +f 984/986/2102 797/798/2102 796/797/2102 +f 984/986/2103 796/797/2103 986/988/2103 +f 986/988/2104 796/797/2104 794/795/2104 +f 986/988/2105 794/795/2106 798/799/2107 +f 986/988/2105 798/799/2107 987/989/2108 +f 987/989/2109 798/799/2110 983/985/2111 +f 983/985/2111 798/799/2110 797/798/2112 +f 988/990/2113 989/991/2113 990/992/2113 +f 989/991/2114 991/993/2114 990/992/2114 +f 991/993/2115 992/994/2115 990/992/2115 +f 992/994/2116 988/990/2116 990/992/2116 +f 988/990/2117 791/792/2117 989/991/2117 +f 989/991/2118 791/792/2118 789/790/2118 +f 989/991/2119 789/790/2120 991/993/2121 +f 991/993/2121 789/790/2120 787/788/2122 +f 991/993/2123 787/788/2124 992/994/2125 +f 992/994/2125 787/788/2124 792/793/2126 +f 992/994/2127 792/793/2128 988/990/2129 +f 988/990/2129 792/793/2128 791/792/2130 +f 993/995/2131 994/996/2131 995/997/2131 +f 995/997/2132 996/998/2132 993/995/2132 +f 996/998/2133 997/999/2133 993/995/2133 +f 997/999/2134 998/1000/2134 993/995/2134 +f 993/995/2135 998/1000/2135 994/996/2135 +f 994/996/2136 819/820/2136 818/819/2136 +f 994/996/2137 818/819/2137 995/997/2137 +f 995/997/2138 818/819/2139 821/822/2140 +f 995/997/2138 821/822/2140 996/998/2141 +f 996/998/2142 821/822/2143 820/821/2144 +f 996/998/2142 820/821/2144 997/999/2145 +f 997/999/2146 820/821/2147 998/1000/2148 +f 998/1000/2148 820/821/2147 819/820/2149 +f 998/1000/2150 819/820/2150 994/996/2150 +f 999/1001/2151 1000/1002/2151 1001/1003/2151 +f 1001/1003/2152 1000/1002/2152 1002/1004/2152 +f 1002/1004/2153 1003/1005/2153 1001/1003/2153 +f 1003/1005/2154 1004/1006/2154 1001/1003/2154 +f 1004/1006/2155 999/1001/2155 1001/1003/2155 +f 999/1001/2156 812/813/2156 1000/1002/2156 +f 1000/1002/2157 812/813/2158 1002/1004/2159 +f 1002/1004/2159 812/813/2158 790/791/2160 +f 1002/1004/2161 790/791/2162 1003/1005/2163 +f 1003/1005/2163 790/791/2162 814/815/2164 +f 1003/1005/2165 814/815/2166 1004/1006/2167 +f 1004/1006/2167 814/815/2166 813/814/2168 +f 1004/1006/2169 813/814/2169 999/1001/2169 +f 999/1001/2170 813/814/2170 812/813/2170 +f 1005/1007/2171 1006/1008/2172 1007/1009/2172 +f 1007/1009/2172 1008/1010/2172 1009/1011/2171 +f 1005/1007/2171 1007/1009/2172 1009/1011/2171 +f 657/658/2173 656/657/2173 655/656/2173 +f 656/657/2173 657/658/2173 658/659/2174 +f 656/657/2173 654/655/2173 655/656/2173 +f 437/437/603 452/452/609 429/429/609 +f 452/452/609 437/437/603 450/450/626 +f 1010/1012/2175 703/704/1394 649/650/1393 +f 646/647/1396 1011/1013/2176 1010/1012/2175 +f 646/647/1396 1010/1012/2175 647/648/2177 +f 1010/1012/2175 1011/1013/2176 1012/1014/2178 +f 1010/1012/2175 1012/1014/2178 1013/1015/2179 +f 1012/1014/2178 703/704/1394 1013/1015/2179 +f 703/704/1394 1012/1014/2178 1014/1016/2180 +f 703/704/1394 1014/1016/2180 646/647/1396 +f 646/647/1396 1014/1016/2180 1011/1013/2176 +f 647/648/2177 1010/1012/2175 649/650/1393 +f 647/648/2177 649/650/1393 648/649/2181 +f 708/709/2182 710/711/2183 1015/1017/2184 +f 830/831/2185 1015/1017/2186 1016/1018/2187 +f 826/827/2188 1015/1017/2186 830/831/2185 +f 707/708/528 830/831/528 709/710/528 +f 709/710/528 830/831/528 1016/1018/528 +f 705/706/528 707/708/528 1017/1019/528 +f 705/706/528 1017/1019/528 1018/1020/528 +f 705/706/528 1018/1020/528 1019/1021/528 +f 710/711/2189 709/710/2190 1015/1017/2191 +f 1015/1017/2191 709/710/2190 1016/1018/2192 +f 706/707/2193 708/709/2193 828/829/2193 +f 1015/1017/2184 826/827/2194 708/709/2182 +f 708/709/2195 826/827/1526 828/829/1528 +f 1006/1008/2196 320/320/2197 1007/1009/2198 +f 1007/1009/2198 320/320/2197 315/315/2199 +f 1007/1009/2200 314/314/2201 1008/1010/2202 +f 1008/1010/2202 314/314/2201 712/713/2203 +f 320/320/2204 1006/1008/2205 322/322/2206 +f 322/322/2206 1006/1008/2205 1005/1007/2207 +f 1005/1007/2207 719/720/2208 322/322/2206 +f 1008/1010/2209 714/715/2210 1009/1011/2211 +f 1009/1011/2211 714/715/2210 715/716/2212 +f 314/314/2213 1007/1009/2213 315/315/2213 +f 719/720/2214 1005/1007/2215 715/716/2216 +f 715/716/2216 1005/1007/2215 1009/1011/2217 +f 714/715/2218 1008/1010/2218 712/713/2218 +f 1020/1022/2219 1021/1023/2220 831/832/1531 +f 1021/1023/2220 832/833/1532 831/832/1531 +f 1022/1024/2221 1023/1025/2222 1020/1022/2219 +f 1020/1022/2219 1023/1025/2222 1021/1023/2220 +f 833/834/1533 1024/1026/2223 834/836/1535 +f 834/836/1535 1024/1026/2223 1025/1027/2224 +f 1026/1028/2225 1027/1029/2225 1025/1027/2225 +f 1024/1026/2226 1028/1030/2226 1029/1031/2226 +f 1024/1026/2223 1023/1025/2227 1025/1027/2224 +f 1025/1027/2224 1023/1025/2227 1022/1024/2228 +f 834/836/2229 1025/1027/2230 831/832/1531 +f 831/832/1531 1025/1027/2230 1027/1029/2231 +f 1028/1030/2232 1024/1026/2233 833/834/2234 +f 1028/1030/2232 833/834/2234 832/833/2235 +f 1022/1024/2236 1026/1028/2236 1025/1027/2236 +f 1020/1022/2237 1027/1029/2238 1022/1024/2239 +f 1022/1024/2239 1027/1029/2238 1026/1028/2240 +f 1020/1022/2219 831/832/1531 1027/1029/2231 +f 1029/1031/2241 1023/1025/2241 1024/1026/2241 +f 1028/1030/2242 1021/1023/2243 1029/1031/2244 +f 1029/1031/2244 1021/1023/2243 1023/1025/2245 +f 1021/1023/2246 1028/1030/2232 832/833/2235 +f 1030/1032/2247 1013/1015/2248 1031/1033/2249 +f 1031/1033/2249 1013/1015/2248 703/704/2250 +f 1013/1015/2251 1030/1032/2252 1010/1012/2253 +f 1010/1012/2253 1030/1032/2252 1032/1034/2254 +f 1010/1012/2255 1032/1034/2255 1033/1035/2255 +f 1033/1035/2256 703/704/2256 1010/1012/2256 +f 1033/1035/2257 1031/1033/2257 703/704/2257 +f 1012/1014/2258 1034/1036/2259 1035/1037/2260 +f 1035/1037/2260 1014/1016/2261 1012/1014/2258 +f 1035/1037/2262 1011/1013/2263 1014/1016/2264 +f 1036/1038/2265 1011/1013/2263 1035/1037/2262 +f 1034/1036/2266 1012/1014/2267 1011/1013/2268 +f 1019/1021/2269 1037/1039/2270 705/706/2271 +f 705/706/2271 1037/1039/2270 704/705/2272 +f 1038/1040/2273 1039/1041/2274 1040/1042/2275 +f 1041/1043/2276 1042/1044/2277 1018/1020/2278 +f 1018/1020/2278 1042/1044/2277 1043/1045/2279 +f 1040/1042/2275 1044/1046/2280 1038/1040/2273 +f 1045/1047/2281 1019/1021/2282 1044/1046/2280 +f 1044/1046/2280 1019/1021/2282 1038/1040/2273 +f 1019/1021/2282 1045/1047/2281 1037/1039/2283 +f 1045/1047/2281 1046/1048/2284 1037/1039/2283 +f 1043/1045/2279 1047/1049/2285 1018/1020/2278 +f 1019/1021/2282 1048/1050/2286 1049/1051/2287 +f 1038/1040/2273 1050/1052/2288 1043/1045/2279 +f 1018/1020/2278 1047/1049/2285 1048/1050/2286 +f 1018/1020/2278 1048/1050/2286 1019/1021/2282 +f 1038/1040/2273 1019/1021/2282 1049/1051/2287 +f 1038/1040/2273 1049/1051/2287 1050/1052/2288 +f 1037/1039/2283 1046/1048/2284 1041/1043/2276 +f 1041/1043/2276 1046/1048/2284 1040/1042/2275 +f 1043/1045/2279 1050/1052/2288 1047/1049/2285 +f 1039/1041/2274 1042/1044/2277 1040/1042/2275 +f 1040/1042/2275 1042/1044/2277 1041/1043/2276 +f 707/708/1399 706/707/1398 829/830/1529 +f 707/708/1399 829/830/1529 1017/1019/2289 +f 1017/1019/2290 829/830/2291 1018/1020/2292 +f 1018/1020/2292 829/830/2291 1041/1043/2293 +f 829/830/2294 704/705/2295 1037/1039/98 +f 829/830/2294 1037/1039/98 1041/1043/98 +f 1051/1053/2296 1052/1054/2296 1053/1055/2296 +f 1053/1055/2297 1054/1056/2297 1051/1053/2297 +f 1054/1056/2298 1055/1057/2298 1051/1053/2298 +f 1055/1057/2299 1056/1058/2299 1051/1053/2299 +f 1051/1053/2300 1056/1058/2300 1052/1054/2300 +f 1052/1054/2301 1047/1049/2302 1053/1055/2303 +f 1053/1055/2303 1047/1049/2302 1050/1052/2304 +f 1053/1055/2305 1050/1052/2305 1054/1056/2305 +f 1054/1056/2306 1050/1052/2307 1049/1051/2308 +f 1054/1056/2306 1049/1051/2308 1055/1057/2309 +f 1055/1057/2310 1049/1051/2311 1048/1050/2312 +f 1055/1057/2310 1048/1050/2312 1056/1058/2313 +f 1056/1058/2314 1048/1050/2315 1052/1054/2316 +f 1052/1054/2316 1048/1050/2315 1047/1049/2317 +f 1057/1059/2318 1058/1060/2318 1059/1061/2318 +f 1058/1060/2319 1060/1062/2319 1059/1061/2319 +f 1060/1062/2320 1061/1063/2320 1059/1061/2320 +f 1061/1063/2321 1057/1059/2321 1059/1061/2321 +f 1057/1059/2322 1040/1042/2322 1058/1060/2322 +f 1058/1060/2323 1040/1042/2323 1046/1048/2323 +f 1058/1060/2324 1046/1048/2325 1060/1062/2326 +f 1060/1062/2326 1046/1048/2325 1045/1047/2327 +f 1060/1062/2328 1045/1047/2329 1061/1063/2330 +f 1061/1063/2330 1045/1047/2329 1044/1046/2331 +f 1061/1063/2332 1044/1046/2332 1057/1059/2332 +f 1057/1059/2333 1044/1046/2333 1040/1042/2333 +f 1062/1064/2334 1063/1065/2334 1064/1066/2334 +f 1063/1065/2335 1065/1067/2335 1064/1066/2335 +f 1065/1067/2336 1066/1068/2336 1064/1066/2336 +f 1066/1068/2337 1062/1064/2337 1064/1066/2337 +f 1062/1064/2338 1042/1044/2338 1063/1065/2338 +f 1063/1065/2339 1042/1044/2339 1039/1041/2339 +f 1063/1065/2340 1039/1041/2340 1065/1067/2340 +f 1065/1067/2341 1039/1041/2341 1038/1040/2341 +f 1065/1067/2342 1038/1040/2343 1066/1068/2344 +f 1066/1068/2344 1038/1040/2343 1043/1045/2345 +f 1066/1068/2346 1043/1045/2346 1062/1064/2346 +f 1062/1064/2347 1043/1045/2347 1042/1044/2347 +f 1034/1036/2266 1011/1013/2268 1036/1038/2348 +f 647/648/2349 645/646/2350 644/645/2351 +f 1030/1032/2352 1031/1033/2352 1032/1034/2352 +f 647/648/2349 648/649/2353 645/646/2350 +f 1032/1034/2352 1031/1033/2352 1033/1035/2352 +f 1035/1037/2352 1034/1036/2352 1036/1038/2352 +f 673/674/2354 641/642/2354 672/673/2354 +f 672/673/2355 639/640/2355 674/675/2355 +f 673/674/2352 672/673/2352 674/675/2352 +f 671/672/2352 669/670/2352 670/671/2352 +f 1067/1069/2356 1068/1070/2357 1069/1071/2358 +f 1069/1071/2358 1068/1070/2357 1070/1072/2359 +f 1068/1070/2357 1067/1069/2356 1071/1073/2360 +f 1072/1074/2361 1069/1071/2358 1070/1072/2359 +f 1073/1075/2362 1072/1074/2361 1070/1072/2359 +f 1073/1075/2362 1070/1072/2359 1074/1076/2363 +f 1075/1077/2364 1073/1075/2362 1074/1076/2363 +f 1076/1078/2365 1077/1079/2366 1074/1076/2363 +f 1077/1079/2366 1075/1077/2364 1074/1076/2363 +f 1078/1080/2367 1079/1081/2368 1076/1078/2365 +f 1079/1081/2368 1077/1079/2366 1076/1078/2365 +f 1068/1070/2357 1071/1073/2360 1080/1082/2369 +f 1081/1083/2370 1082/1084/2371 1068/1070/2357 +f 1068/1070/2357 1082/1084/2371 1083/1085/2372 +f 1080/1082/2369 1084/1086/2373 1068/1070/2357 +f 1084/1086/2373 1081/1083/2370 1068/1070/2357 +f 1085/1087/2374 1086/1088/2375 1087/1089/2376 +f 1088/1090/2377 1089/1091/2378 1090/1092/2379 +f 1090/1092/2379 1091/1093/2380 1092/1094/2381 +f 1092/1094/2381 1091/1093/2380 1093/1095/2382 +f 1092/1094/2381 1093/1095/2382 1094/1096/2383 +f 1086/1088/2375 1095/1097/2384 1087/1089/2376 +f 1095/1097/2384 1096/1098/2385 1087/1089/2376 +f 1087/1089/2376 1096/1098/2385 1097/1099/2386 +f 1097/1099/2386 1096/1098/2385 1098/1100/2387 +f 1097/1099/2386 1098/1100/2387 1099/1101/2388 +f 1097/1099/2386 1099/1101/2388 1100/1102/2389 +f 1100/1102/2389 1099/1101/2388 1101/1103/2390 +f 1102/1104/2391 1097/1099/2386 1100/1102/2389 +f 1102/1104/2391 1100/1102/2389 1088/1090/2377 +f 1094/1096/2383 1103/1105/2392 1085/1087/2374 +f 1094/1096/2383 1085/1087/2374 1087/1089/2376 +f 1094/1096/2383 1087/1089/2376 1092/1094/2381 +f 1092/1094/2381 1102/1104/2391 1090/1092/2379 +f 1090/1092/2379 1102/1104/2391 1088/1090/2377 +f 1092/1094/2381 1087/1089/2376 1097/1099/2386 +f 1092/1094/2381 1097/1099/2386 1102/1104/2391 +f 1104/1106/2393 1105/1107/2394 1106/1108/2395 +f 1107/1109/2396 1106/1108/2395 1108/1110/2397 +f 1107/1109/2396 1109/1111/2398 1110/1112/2399 +f 1110/1112/2399 1109/1111/2398 1111/1113/2400 +f 1112/1114/2401 1113/1115/2402 1111/1113/2400 +f 1111/1113/2400 1113/1115/2402 1110/1112/2399 +f 1108/1110/2397 1093/1095/2382 1109/1111/2398 +f 1109/1111/2398 1093/1095/2382 1091/1093/2380 +f 1091/1093/2380 1089/1091/2378 1111/1113/2400 +f 1111/1113/2400 1089/1091/2378 1112/1114/2401 +f 1103/1105/2392 1094/1096/2383 1108/1110/2397 +f 1108/1110/2397 1094/1096/2383 1093/1095/2382 +f 1091/1093/2380 1090/1092/2379 1089/1091/2378 +f 1105/1107/2394 1108/1110/2397 1106/1108/2395 +f 1107/1109/2396 1108/1110/2397 1109/1111/2398 +f 1105/1107/2394 1103/1105/2392 1108/1110/2397 +f 1109/1111/2398 1091/1093/2380 1111/1113/2400 +f 1114/1116/2403 1115/1117/2404 1116/1118/2405 +f 1117/1119/2406 1118/1120/2407 1079/1081/2368 +f 1118/1120/2407 1117/1119/2406 1119/1121/2408 +f 1120/1122/2409 1121/1123/2410 1122/1124/2411 +f 1122/1124/2411 1121/1123/2410 1123/1125/2412 +f 1124/1126/2413 1123/1125/2412 1125/1127/2414 +f 1126/1128/2415 1127/1129/2416 1128/1130/2417 +f 1126/1128/2415 1128/1130/2417 1129/1131/2418 +f 1079/1081/2368 1130/1132/2419 1117/1119/2406 +f 1117/1119/2406 1131/1133/2420 1119/1121/2408 +f 1125/1127/2414 1123/1125/2412 1121/1123/2410 +f 1121/1123/2410 1120/1122/2409 1132/1134/2421 +f 1114/1116/2403 1116/1118/2405 1130/1132/2419 +f 1130/1132/2419 1116/1118/2405 1133/1135/2422 +f 1130/1132/2419 1133/1135/2422 1117/1119/2406 +f 1134/1136/2423 1124/1126/2413 1135/1137/2424 +f 1135/1137/2424 1124/1126/2413 1125/1127/2414 +f 1125/1127/2414 1121/1123/2410 1136/1138/2425 +f 1136/1138/2425 1121/1123/2410 1132/1134/2421 +f 1115/1117/2404 1128/1130/2417 1116/1118/2405 +f 1133/1135/2422 1137/1139/2426 1117/1119/2406 +f 1117/1119/2406 1137/1139/2426 1131/1133/2420 +f 1128/1130/2417 1127/1129/2416 1134/1136/2423 +f 1128/1130/2417 1134/1136/2423 1138/1140/2427 +f 1138/1140/2427 1134/1136/2423 1135/1137/2424 +f 1135/1137/2424 1125/1127/2414 1136/1138/2425 +f 1139/1141/2428 1136/1138/2425 1132/1134/2421 +f 1129/1131/2418 1128/1130/2417 1115/1117/2404 +f 1116/1118/2405 1128/1130/2417 1138/1140/2427 +f 1116/1118/2405 1138/1140/2427 1135/1137/2424 +f 1116/1118/2405 1135/1137/2424 1133/1135/2422 +f 1133/1135/2422 1135/1137/2424 1137/1139/2426 +f 1137/1139/2426 1139/1141/2428 1131/1133/2420 +f 1135/1137/2424 1136/1138/2425 1137/1139/2426 +f 1137/1139/2426 1136/1138/2425 1139/1141/2428 +f 1140/1142/2429 1141/1143/2430 1142/1144/2431 +f 1142/1144/2431 1141/1143/2430 1143/1145/2432 +f 1143/1145/2432 1144/1146/2433 1142/1144/2431 +f 1124/1126/2413 1145/1147/2434 1146/1148/2435 +f 1146/1148/2435 1145/1147/2434 1147/1149/2436 +f 1146/1148/2435 1147/1149/2436 1148/1150/2437 +f 1149/1151/2438 1147/1149/2436 1141/1143/2430 +f 1149/1151/2438 1141/1143/2430 1150/1152/2439 +f 1147/1149/2436 1149/1151/2438 1148/1150/2437 +f 1141/1143/2430 1140/1142/2429 1150/1152/2439 +f 1143/1145/2432 1151/1153/2440 1144/1146/2433 +f 1143/1145/2432 1152/1154/2441 1151/1153/2440 +f 1153/1155/2442 1154/1156/2443 1143/1145/2432 +f 1143/1145/2432 1154/1156/2443 1155/1157/2444 +f 1143/1145/2432 1155/1157/2444 1152/1154/2441 +f 1156/1158/2445 1157/1159/2446 1158/1160/2447 +f 1159/1161/2448 1160/1162/2449 1161/1163/2450 +f 1160/1162/2449 1162/1164/2451 1161/1163/2450 +f 1162/1164/2451 1160/1162/2449 1163/1165/2452 +f 1160/1162/2449 1159/1161/2448 1164/1166/2453 +f 1160/1162/2449 1164/1166/2453 1157/1159/2446 +f 1157/1159/2446 1164/1166/2453 1158/1160/2447 +f 1083/1085/2372 1082/1084/2371 1156/1158/2445 +f 1165/1167/2454 1166/1168/2455 1167/1169/2456 +f 1165/1167/2454 1167/1169/2456 1168/1170/2457 +f 1167/1169/2456 1169/1171/2458 1168/1170/2457 +f 1170/1172/2459 1169/1171/2458 1167/1169/2456 +f 1171/1173/2460 1170/1172/2459 1167/1169/2456 +f 1172/1174/2461 1170/1172/2459 1171/1173/2460 +f 1173/1175/2462 1164/1166/2453 1172/1174/2461 +f 1173/1175/2462 1172/1174/2461 1171/1173/2460 +f 1173/1175/2462 1158/1160/2447 1164/1166/2453 +f 1156/1158/2445 1158/1160/2447 1173/1175/2462 +f 1083/1085/2372 1156/1158/2445 1173/1175/2462 +f 1165/1167/2454 1154/1156/2443 1153/1155/2442 +f 1166/1168/2455 1165/1167/2454 1153/1155/2442 +f 1130/1132/2419 1079/1081/2368 1078/1080/2367 +f 1114/1116/2403 1078/1080/2367 1174/1176/2463 +f 1078/1080/2367 1114/1116/2403 1130/1132/2419 +f 1115/1117/2404 1174/1176/2463 1175/1177/2464 +f 1115/1117/2404 1175/1177/2464 1129/1131/2418 +f 1174/1176/2463 1115/1117/2404 1114/1116/2403 +f 1175/1177/2464 1126/1128/2415 1129/1131/2418 +f 1126/1128/2415 1175/1177/2464 1176/1178/2465 +f 1126/1128/2415 1176/1178/2465 1127/1129/2416 +f 1176/1178/2465 1134/1136/2423 1127/1129/2416 +f 1134/1136/2423 1176/1178/2465 1145/1147/2434 +f 1145/1147/2434 1124/1126/2413 1134/1136/2423 +f 1177/1179/2466 1178/1180/2467 1179/1181/2468 +f 1168/1170/2457 1180/1182/2469 1181/1183/2470 +f 1165/1167/2454 1168/1170/2457 1182/1184/2471 +f 1177/1179/2466 1179/1181/2468 1183/1185/2472 +f 1177/1179/2466 1183/1185/2472 1181/1183/2470 +f 1182/1184/2471 1168/1170/2457 1183/1185/2472 +f 1183/1185/2472 1168/1170/2457 1181/1183/2470 +f 1184/1186/2473 1185/1187/2474 1186/1188/2475 +f 1186/1188/2475 1187/1189/2476 1188/1190/2477 +f 1185/1187/2474 1169/1171/2458 1170/1172/2459 +f 1170/1172/2459 1172/1174/2461 1164/1166/2453 +f 1170/1172/2459 1164/1166/2453 1185/1187/2474 +f 1185/1187/2474 1164/1166/2453 1187/1189/2476 +f 1185/1187/2474 1187/1189/2476 1186/1188/2475 +f 1189/1191/2478 1190/1192/2479 1191/1193/2480 +f 1191/1193/2480 1192/1194/2481 1189/1191/2478 +f 1189/1191/2478 1192/1194/2481 1193/1195/2482 +f 1192/1194/2481 1194/1196/2483 1193/1195/2482 +f 1071/1073/2360 1194/1196/2483 1192/1194/2481 +f 1071/1073/2360 1069/1071/2358 1194/1196/2483 +f 1195/1197/2484 1196/1198/2485 1197/1199/2486 +f 1195/1197/2484 1197/1199/2486 1198/1200/2487 +f 1198/1200/2487 1199/1201/2488 1195/1197/2484 +f 1198/1200/2487 1200/1202/2489 1199/1201/2488 +f 1196/1198/2485 1150/1152/2439 1197/1199/2486 +f 1197/1199/2486 1150/1152/2439 1201/1203/2490 +f 1201/1203/2490 1150/1152/2439 1140/1142/2429 +f 1201/1203/2490 1140/1142/2429 1142/1144/2431 +f 1148/1150/2437 1202/1204/2491 1146/1148/2435 +f 1122/1124/2411 1123/1125/2412 1202/1204/2491 +f 1202/1204/2491 1123/1125/2412 1146/1148/2435 +f 1146/1148/2435 1123/1125/2412 1124/1126/2413 +f 1203/1205/2492 1148/1150/2437 1149/1151/2438 +f 1196/1198/2485 1203/1205/2492 1149/1151/2438 +f 1196/1198/2485 1149/1151/2438 1150/1152/2439 +f 1148/1150/2437 1203/1205/2492 1202/1204/2491 +f 1120/1122/2409 1122/1124/2411 1202/1204/2491 +f 1120/1122/2409 1202/1204/2491 1204/1206/2493 +f 1203/1205/2492 1196/1198/2485 1195/1197/2484 +f 1203/1205/2492 1204/1206/2493 1202/1204/2491 +f 1204/1206/2493 1203/1205/2492 1195/1197/2484 +f 1077/1079/2366 1205/1207/2494 1075/1077/2364 +f 1118/1120/2407 1205/1207/2494 1077/1079/2366 +f 1118/1120/2407 1077/1079/2366 1079/1081/2368 +f 1142/1144/2431 1144/1146/2433 1201/1203/2490 +f 1104/1106/2393 1195/1197/2484 1199/1201/2488 +f 1104/1106/2393 1199/1201/2488 1105/1107/2394 +f 1105/1107/2394 1199/1201/2488 1103/1105/2392 +f 1103/1105/2392 1199/1201/2488 1200/1202/2489 +f 1120/1122/2409 1204/1206/2493 1104/1106/2393 +f 1104/1106/2393 1204/1206/2493 1195/1197/2484 +f 1205/1207/2494 1206/1208/2495 1075/1077/2364 +f 1201/1203/2490 1144/1146/2433 1197/1199/2486 +f 1151/1153/2440 1197/1199/2486 1144/1146/2433 +f 1197/1199/2486 1151/1153/2440 1198/1200/2487 +f 1198/1200/2487 1207/1209/2496 1200/1202/2489 +f 1085/1087/2374 1103/1105/2392 1200/1202/2489 +f 1085/1087/2374 1200/1202/2489 1207/1209/2496 +f 1131/1133/2420 1139/1141/2428 1208/1210/2497 +f 1139/1141/2428 1132/1134/2421 1208/1210/2497 +f 1209/1211/2498 1119/1121/2408 1110/1112/2399 +f 1110/1112/2399 1119/1121/2408 1210/1212/2499 +f 1210/1212/2499 1208/1210/2497 1107/1109/2396 +f 1119/1121/2408 1131/1133/2420 1210/1212/2499 +f 1210/1212/2499 1131/1133/2420 1208/1210/2497 +f 1208/1210/2497 1132/1134/2421 1106/1108/2395 +f 1106/1108/2395 1132/1134/2421 1120/1122/2409 +f 1106/1108/2395 1120/1122/2409 1104/1106/2393 +f 1208/1210/2497 1106/1108/2395 1107/1109/2396 +f 1210/1212/2499 1107/1109/2396 1110/1112/2399 +f 1110/1112/2399 1113/1115/2402 1209/1211/2498 +f 1193/1195/2482 1206/1208/2495 1189/1191/2478 +f 1205/1207/2494 1118/1120/2407 1209/1211/2498 +f 1209/1211/2498 1189/1191/2478 1206/1208/2495 +f 1209/1211/2498 1206/1208/2495 1205/1207/2494 +f 1119/1121/2408 1209/1211/2498 1118/1120/2407 +f 1075/1077/2364 1206/1208/2495 1073/1075/2362 +f 1073/1075/2362 1206/1208/2495 1193/1195/2482 +f 1193/1195/2482 1194/1196/2483 1073/1075/2362 +f 1073/1075/2362 1194/1196/2483 1072/1074/2361 +f 1072/1074/2361 1194/1196/2483 1069/1071/2358 +f 1182/1184/2471 1154/1156/2443 1165/1167/2454 +f 1113/1115/2402 1189/1191/2478 1209/1211/2498 +f 1069/1071/2358 1071/1073/2360 1067/1069/2356 +f 1168/1170/2457 1169/1171/2458 1180/1182/2469 +f 1179/1181/2468 1178/1180/2467 1152/1154/2441 +f 1152/1154/2441 1155/1157/2444 1179/1181/2468 +f 1179/1181/2468 1155/1157/2444 1183/1185/2472 +f 1182/1184/2471 1183/1185/2472 1155/1157/2444 +f 1154/1156/2443 1182/1184/2471 1155/1157/2444 +f 1085/1087/2374 1207/1209/2496 1086/1088/2375 +f 1151/1153/2440 1152/1154/2441 1178/1180/2467 +f 1198/1200/2487 1211/1213/2500 1207/1209/2496 +f 1207/1209/2496 1211/1213/2500 1086/1088/2375 +f 1178/1180/2467 1211/1213/2500 1198/1200/2487 +f 1178/1180/2467 1198/1200/2487 1151/1153/2440 +f 1211/1213/2500 1178/1180/2467 1212/1214/2501 +f 1211/1213/2500 1212/1214/2501 1213/1215/2502 +f 1211/1213/2500 1213/1215/2502 1086/1088/2375 +f 1086/1088/2375 1213/1215/2502 1095/1097/2384 +f 1089/1091/2378 1214/1216/2503 1190/1192/2479 +f 1089/1091/2378 1190/1192/2479 1112/1114/2401 +f 1112/1114/2401 1190/1192/2479 1113/1115/2402 +f 1189/1191/2478 1113/1115/2402 1190/1192/2479 +f 1214/1216/2503 1088/1090/2377 1215/1217/2504 +f 1214/1216/2503 1215/1217/2504 1191/1193/2480 +f 1191/1193/2480 1190/1192/2479 1214/1216/2503 +f 1088/1090/2377 1214/1216/2503 1089/1091/2378 +f 1192/1194/2481 1080/1082/2369 1071/1073/2360 +f 1191/1193/2480 1080/1082/2369 1192/1194/2481 +f 1180/1182/2469 1169/1171/2458 1181/1183/2470 +f 1169/1171/2458 1185/1187/2474 1181/1183/2470 +f 1185/1187/2474 1184/1186/2473 1181/1183/2470 +f 1181/1183/2470 1184/1186/2473 1177/1179/2466 +f 1177/1179/2466 1212/1214/2501 1178/1180/2467 +f 1213/1215/2502 1216/1218/2505 1217/1219/2506 +f 1177/1179/2466 1184/1186/2473 1216/1218/2505 +f 1177/1179/2466 1216/1218/2505 1213/1215/2502 +f 1177/1179/2466 1213/1215/2502 1212/1214/2501 +f 1217/1219/2506 1095/1097/2384 1213/1215/2502 +f 1096/1098/2385 1095/1097/2384 1217/1219/2506 +f 1088/1090/2377 1100/1102/2389 1215/1217/2504 +f 1191/1193/2480 1215/1217/2504 1218/1220/2507 +f 1218/1220/2507 1215/1217/2504 1100/1102/2389 +f 1100/1102/2389 1101/1103/2390 1219/1221/2508 +f 1100/1102/2389 1219/1221/2508 1218/1220/2507 +f 1219/1221/2508 1163/1165/2452 1218/1220/2507 +f 1163/1165/2452 1084/1086/2373 1218/1220/2507 +f 1218/1220/2507 1084/1086/2373 1080/1082/2369 +f 1218/1220/2507 1080/1082/2369 1191/1193/2480 +f 1084/1086/2373 1163/1165/2452 1160/1162/2449 +f 1084/1086/2373 1160/1162/2449 1081/1083/2370 +f 1081/1083/2370 1160/1162/2449 1157/1159/2446 +f 1082/1084/2371 1157/1159/2446 1156/1158/2445 +f 1081/1083/2370 1157/1159/2446 1082/1084/2371 +f 1164/1166/2453 1159/1161/2448 1187/1189/2476 +f 1159/1161/2448 1161/1163/2450 1188/1190/2477 +f 1187/1189/2476 1159/1161/2448 1188/1190/2477 +f 1220/1222/2509 1099/1101/2388 1098/1100/2387 +f 1220/1222/2509 1098/1100/2387 1217/1219/2506 +f 1188/1190/2477 1220/1222/2509 1186/1188/2475 +f 1186/1188/2475 1220/1222/2509 1216/1218/2505 +f 1098/1100/2387 1096/1098/2385 1217/1219/2506 +f 1220/1222/2509 1217/1219/2506 1216/1218/2505 +f 1220/1222/2509 1188/1190/2477 1099/1101/2388 +f 1216/1218/2505 1184/1186/2473 1186/1188/2475 +f 1101/1103/2390 1162/1164/2451 1163/1165/2452 +f 1101/1103/2390 1163/1165/2452 1219/1221/2508 +f 1101/1103/2390 1099/1101/2388 1188/1190/2477 +f 1101/1103/2390 1188/1190/2477 1162/1164/2451 +f 1188/1190/2477 1161/1163/2450 1162/1164/2451 +f 1174/1176/2510 1068/1070/98 1175/1177/98 +f 1176/1178/1246 1175/1177/98 1143/1145/98 +f 1174/1176/2510 1070/1072/98 1068/1070/98 +f 1074/1076/2511 1070/1072/98 1076/1078/2512 +f 1176/1178/1246 1141/1143/98 1145/1147/98 +f 1070/1072/98 1078/1080/2510 1076/1078/2512 +f 1141/1143/98 1147/1149/2513 1145/1147/98 +f 1070/1072/98 1174/1176/2510 1078/1080/2510 +f 1141/1143/98 1176/1178/1246 1143/1145/98 +f 1175/1177/98 1068/1070/98 1143/1145/98 +f 1143/1145/98 1068/1070/98 1083/1085/2514 +f 1143/1145/98 1083/1085/2514 1153/1155/2294 +f 1173/1175/2515 1171/1173/2514 1083/1085/2514 +f 1171/1173/2514 1153/1155/2294 1083/1085/2514 +f 1167/1169/2516 1166/1168/2517 1153/1155/2294 +f 258/258/2518 256/256/2519 264/264/2520 +f 241/241/2521 249/249/2522 237/237/2523 +f 82/82/2524 295/295/2525 292/292/2526 +f 91/91/2527 86/86/2528 277/277/2529 +f 81/81/2530 91/91/2527 277/277/2529 +f 86/86/2528 91/91/2527 87/87/2531 +f 236/236/2532 237/237/2523 238/238/2533 +f 240/240/2534 249/249/2522 241/241/2521 +f 279/279/2535 81/81/2530 277/277/2529 +f 238/238/2533 237/237/2523 252/252/2536 +f 240/240/2534 91/91/2527 81/81/2530 +f 1167/1169/2516 1153/1155/2294 1171/1173/2514 +f 243/243/2518 252/252/2536 248/248/2537 +f 277/277/2529 274/274/2538 279/279/2535 +f 245/245/2539 243/243/2518 248/248/2537 +f 249/249/2522 248/248/2537 252/252/2536 +f 274/274/2538 272/272/2540 279/279/2535 +f 292/292/2526 288/288/2541 283/283/2542 +f 82/82/2524 292/292/2526 283/283/2542 +f 262/262/2543 264/264/2520 99/99/2544 +f 649/650/1246 704/705/2295 235/835/2545 +f 99/99/2544 295/295/2525 82/82/2524 +f 82/82/2524 100/100/2546 99/99/2544 +f 82/82/2524 228/228/2547 100/100/2546 +f 235/235/2548 228/228/2547 82/82/2524 +f 108/108/2549 234/234/2550 235/235/2548 +f 233/233/2551 104/104/2552 100/100/2546 +f 104/104/2552 233/233/2551 232/232/1243 +f 100/468/880 302/302/2553 303/303/1245 +f 234/234/2550 108/108/2549 107/107/528 +f 235/235/2548 234/234/2550 228/228/2547 +f 228/228/2547 233/233/2551 100/100/2546 +f 341/341/528 346/346/531 321/321/528 +f 358/358/528 323/323/528 316/316/528 +f 404/404/584 770/771/528 769/770/1477 +f 705/706/528 830/831/528 707/708/528 +f 720/721/528 365/365/539 353/353/528 +f 358/358/528 364/364/528 323/323/528 +f 720/721/528 353/353/528 341/341/528 +f 321/321/528 720/721/528 341/341/528 +f 646/647/1243 769/770/1477 830/831/528 +f 346/346/531 316/316/528 321/321/528 +f 341/341/528 340/340/529 346/346/531 +f 346/346/531 356/356/535 316/316/528 +f 404/404/584 356/356/535 770/771/528 +f 402/402/582 404/404/584 769/770/1477 +f 705/706/528 646/647/1243 830/831/528 +f 402/402/582 300/300/1250 465/465/1251 +f 465/465/1251 300/300/1250 308/308/528 +f 356/356/535 358/358/528 316/316/528 +f 356/356/535 346/346/531 770/771/528 +f 304/304/528 465/465/1251 308/308/528 +f 237/237/2523 249/249/2522 252/252/2536 +f 402/402/582 769/770/1477 642/643/1242 +f 769/770/1477 646/647/1243 642/643/1242 +f 300/300/1250 402/402/582 642/643/1242 +f 930/932/2554 795/796/2555 799/800/2556 +f 922/924/2557 926/928/2558 313/313/2559 +f 568/569/2560 563/564/2561 310/310/2562 +f 711/712/2563 313/313/2559 822/823/2564 +f 313/313/2559 926/928/2558 822/823/2564 +f 460/460/98 675/676/1339 461/461/2565 +f 310/310/2562 309/309/2566 326/326/2567 +f 713/714/2568 711/712/2563 822/823/2564 +f 565/566/2569 568/569/2560 567/568/2570 +f 568/569/2560 310/310/2562 326/326/2567 +f 572/573/2571 571/572/2572 441/441/2573 +f 326/326/2567 441/441/2573 571/572/2572 +f 326/326/2567 571/572/2572 570/571/2574 +f 931/933/2575 795/796/2555 930/932/2554 +f 326/326/2567 570/571/2574 568/569/2560 +f 930/932/2554 799/800/2556 928/930/2576 +f 799/800/2556 822/823/2564 928/930/2576 +f 822/823/2564 926/928/2558 928/930/2576 +f 565/566/2569 563/564/2561 568/569/2560 +f 563/564/2561 313/313/2559 310/310/2562 +f 924/926/2577 925/927/2578 926/928/2558 +f 565/566/2569 567/568/2570 566/567/2579 +f 922/924/2557 924/926/2577 926/928/2558 +f 922/924/2557 313/313/2559 563/564/2561 +f 563/564/2561 923/925/2580 922/924/2557 +f 563/564/2561 564/565/879 923/925/2580 +f 564/565/879 649/650/1246 923/925/2580 +f 564/565/879 100/468/880 303/303/1245 +f 923/925/2580 649/650/1246 235/835/2545 +f 461/461/2565 675/676/1339 100/468/880 +f 704/705/2295 829/830/2294 235/835/2545 +f 829/830/2294 827/828/2581 235/835/2545 +f 649/650/1246 564/565/879 303/303/1245 +f 249/249/2522 240/240/2534 81/81/2530 +f 81/81/2530 96/96/2582 249/249/2522 +f 81/81/2530 101/101/2583 96/96/2582 +f 81/81/2530 80/80/2584 101/101/2583 +f 80/80/2584 295/295/2525 101/101/2583 +f 295/295/2525 99/99/2544 101/101/2583 +f 101/101/2583 99/99/2544 264/264/2520 +f 262/262/2543 258/258/2518 264/264/2520 +f 675/676/1339 302/302/2553 100/468/880 +f 1221/1223/2585 1222/1224/2586 1223/1225/2585 +f 1224/1226/2587 1225/1227/2587 1226/1228/2588 +f 1226/1228/2588 1225/1227/2587 1227/1229/2588 +f 1228/1230/2589 1226/1228/2588 1227/1229/2588 +f 1229/1231/2590 1230/1232/2591 1223/1225/2592 +f 1228/1230/2588 1225/1227/2588 1231/1233/2585 +f 1222/1224/2586 1232/1234/2593 1223/1225/2585 +f 1222/1224/2586 1233/1235/2594 1232/1234/2593 +f 1234/1236/2595 1235/1237/2596 1231/1233/2585 +f 1236/1238/2597 1237/1239/2598 1238/1240/2599 +f 1233/1235/2594 1238/1240/2599 1232/1234/2593 +f 1233/1235/2594 1236/1238/2597 1238/1240/2599 +f 1225/1227/2588 1234/1236/2595 1231/1233/2585 +f 1236/1238/2597 1239/1241/2600 1237/1239/2598 +f 1239/1241/2600 1240/1242/2601 1237/1239/2598 +f 1237/1239/2598 1240/1242/2601 1241/1243/2602 +f 1240/1242/2601 1242/1244/2603 1241/1243/2602 +f 1240/1242/2601 1235/1237/2596 1242/1244/2603 +f 1235/1237/2596 1234/1236/2595 1242/1244/2603 +f 1243/1245/2604 1244/1246/2605 1245/1247/2606 +f 1246/1248/2607 1247/1249/2605 1248/1250/2608 +f 1249/1251/2609 1250/1252/2610 1251/1253/2611 +f 1252/1254/2612 1247/1249/2605 1246/1248/2607 +f 1245/1247/2606 1248/1250/2608 1243/1245/2604 +f 1250/1252/2610 1253/1255/2613 1251/1253/2611 +f 1253/1255/2613 1254/1256/2614 1251/1253/2611 +f 1255/1257/2615 1249/1251/2616 1256/1258/2617 +f 1247/1249/2605 1252/1254/2612 1244/1246/2605 +f 1256/1258/2617 1254/1256/2614 1255/1257/2615 +f 1254/1256/2614 1257/1259/2618 1255/1257/2615 +f 1248/1250/2608 1247/1249/2605 1243/1245/2604 +f 1244/1246/2605 1252/1254/2612 1258/1260/2619 +f 1254/1256/2614 1259/1261/2620 1257/1259/2618 +f 1244/1246/2605 1260/1262/2621 1245/1247/2606 +f 1244/1246/2605 1258/1260/2619 1260/1262/2621 +f 1239/1241/2622 1261/1263/2623 1262/1264/2624 +f 1258/1260/2619 1261/1263/2623 1260/1262/2621 +f 1258/1260/2619 1238/1240/2625 1261/1263/2623 +f 1238/1240/2625 1262/1264/2624 1261/1263/2623 +f 1263/1265/2626 1239/1241/2622 1264/1266/2627 +f 1239/1241/2622 1262/1264/2624 1264/1266/2627 +f 1265/1267/2628 1263/1265/2626 1266/1268/2629 +f 1263/1265/2626 1264/1266/2627 1266/1268/2629 +f 1253/1255/2613 1265/1267/2628 1259/1261/2620 +f 1254/1256/2614 1253/1255/2613 1259/1261/2620 +f 1265/1267/2628 1266/1268/2629 1259/1261/2620 +f 1228/1230/2630 1231/1233/2631 1250/1252/2632 +f 1231/1233/2631 1253/1255/2633 1250/1252/2632 +f 1231/1233/2634 1235/1237/2634 1253/1255/2634 +f 1235/1237/2635 1265/1267/2635 1253/1255/2635 +f 1235/1237/2636 1240/1242/2636 1265/1267/2636 +f 1240/1242/2637 1263/1265/2637 1265/1267/2637 +f 1240/1242/2638 1239/1241/2638 1263/1265/2638 +f 1236/1238/2639 1261/1263/2639 1239/1241/2639 +f 1236/1238/2640 1233/1235/2640 1261/1263/2640 +f 1233/1235/2641 1260/1262/2641 1261/1263/2641 +f 1233/1235/2642 1222/1224/2642 1260/1262/2642 +f 1222/1224/2643 1245/1247/2644 1260/1262/2645 +f 1222/1224/2643 1221/1223/2646 1245/1247/2644 +f 1230/1232/2647 1248/1250/2647 1221/1223/2647 +f 1248/1250/2648 1245/1247/2648 1221/1223/2648 +f 1230/1232/2649 1229/1231/2649 1248/1250/2649 +f 1229/1231/2650 1246/1248/2650 1248/1250/2650 +f 1223/1225/2592 1252/1254/2651 1229/1231/2590 +f 1252/1254/2652 1246/1248/2652 1229/1231/2652 +f 1223/1225/2653 1232/1234/2653 1252/1254/2653 +f 1232/1234/2654 1258/1260/2654 1252/1254/2654 +f 1232/1234/2655 1238/1240/2655 1258/1260/2655 +f 1238/1240/2656 1237/1239/2656 1262/1264/2656 +f 1237/1239/2657 1264/1266/2657 1262/1264/2657 +f 1237/1239/2658 1241/1243/2658 1264/1266/2658 +f 1241/1243/2659 1242/1244/2660 1264/1266/2661 +f 1242/1244/2660 1266/1268/2662 1264/1266/2661 +f 1242/1244/2663 1259/1261/2664 1266/1268/2665 +f 1242/1244/2663 1234/1236/2666 1259/1261/2664 +f 1234/1236/2667 1257/1259/2668 1259/1261/2669 +f 1234/1236/2667 1225/1227/2670 1257/1259/2668 +f 1224/1226/2671 1255/1257/2671 1225/1227/2671 +f 1255/1257/2672 1257/1259/2672 1225/1227/2672 +f 1224/1226/2673 1226/1228/2673 1255/1257/2673 +f 1226/1228/2674 1249/1251/2674 1255/1257/2674 +f 1228/1230/2630 1250/1252/2632 1226/1228/2675 +f 1250/1252/2676 1249/1251/2676 1226/1228/2676 +f 1223/1225/2677 1230/1232/2677 1247/1249/2677 +f 1230/1232/2678 1243/1245/2678 1247/1249/2678 +f 1230/1232/2679 1221/1223/2679 1243/1245/2679 +f 1221/1223/2680 1244/1246/2680 1243/1245/2680 +f 1221/1223/2681 1223/1225/2681 1244/1246/2681 +f 1223/1225/2682 1247/1249/2682 1244/1246/2682 +f 1227/1229/2683 1256/1258/2683 1249/1251/2683 +f 1227/1229/2684 1225/1227/2684 1256/1258/2684 +f 1225/1227/2685 1254/1256/2685 1256/1258/2685 +f 1225/1227/2686 1228/1230/2686 1254/1256/2686 +f 1228/1230/2687 1251/1253/2687 1254/1256/2687 +f 1228/1230/2688 1227/1229/2689 1251/1253/2690 +f 1227/1229/2689 1249/1251/2691 1251/1253/2690 +f 1267/1269/2692 1268/1270/2693 1269/1271/2694 +f 1267/1269/2695 1270/1272/2695 1271/1273/2695 +f 1272/1274/2696 1273/1275/2697 1274/1276/2698 +f 1273/1275/2697 1275/1277/2699 1276/1278/2700 +f 1270/1272/2701 1267/1269/2692 1269/1271/2694 +f 1277/1279/2702 1276/1278/2700 1275/1277/2699 +f 1274/1276/2698 1273/1275/2697 1276/1278/2700 +f 1278/1280/2703 1268/1270/2704 1271/1273/2705 +f 1279/1281/2706 1272/1274/2707 1274/1276/2708 +f 1269/1271/2694 1268/1270/2693 1280/1282/2709 +f 1281/1283/2710 1282/1284/2711 1283/1285/2711 +f 1269/1271/2694 1280/1282/2709 1281/1283/2710 +f 1281/1283/2710 1280/1282/2709 1282/1284/2711 +f 1274/1276/2712 1277/1279/2712 1284/1286/2713 +f 1274/1276/2712 1284/1286/2713 1279/1281/2714 +f 1282/1284/2711 1285/1287/2711 1283/1285/2711 +f 1283/1285/2711 1285/1287/2711 1286/1288/2711 +f 1283/1285/2711 1286/1288/2711 1287/1289/2711 +f 1287/1289/2711 1286/1288/2711 1284/1286/2713 +f 1284/1286/2713 1286/1288/2711 1279/1281/2714 +f 1288/1290/2715 1289/1291/2716 1290/1292/2717 +f 1291/1293/2718 1288/1290/2715 1290/1292/2717 +f 1270/1272/2719 1292/1294/2720 1293/1295/2721 +f 1270/1272/2719 1293/1295/2721 1289/1291/2716 +f 1290/1292/2717 1289/1291/2716 1293/1295/2721 +f 1294/1296/2722 1295/1297/2723 1296/1298/2724 +f 1296/1298/2724 1295/1297/2723 1297/1299/2725 +f 1291/1293/2718 1290/1292/2717 1292/1294/2726 +f 1297/1299/2727 1273/1275/2728 1272/1274/2729 +f 1295/1297/2723 1294/1296/2722 1298/1300/2730 +f 1273/1275/2728 1297/1299/2727 1298/1300/2731 +f 1292/1294/2726 1299/1301/2732 1291/1293/2718 +f 1297/1299/2733 1272/1274/2707 1300/1302/2734 +f 1299/1301/2732 1292/1294/2726 1301/1303/2735 +f 1302/1304/2736 1303/1305/2737 1304/1306/2738 +f 1299/1301/2732 1301/1303/2735 1304/1306/2738 +f 1304/1306/2738 1301/1303/2735 1302/1304/2736 +f 1305/1307/2739 1306/1308/2740 1302/1304/2736 +f 1302/1304/2736 1306/1308/2740 1303/1305/2737 +f 1305/1307/2739 1307/1309/2718 1306/1308/2740 +f 1297/1299/2725 1300/1302/2724 1296/1298/2724 +f 1296/1298/2724 1300/1302/2724 1308/1310/2741 +f 1308/1310/2741 1300/1302/2724 1307/1309/2718 +f 1308/1310/2741 1307/1309/2718 1305/1307/2739 +f 1277/1279/2742 1294/1296/2743 1296/1298/2744 +f 1277/1279/2745 1296/1298/2745 1284/1286/2745 +f 1284/1286/2746 1296/1298/2746 1308/1310/2746 +f 1284/1286/2747 1308/1310/2747 1287/1289/2747 +f 1287/1289/2748 1308/1310/2748 1305/1307/2748 +f 1287/1289/2749 1305/1307/2749 1283/1285/2749 +f 1283/1285/2750 1305/1307/2750 1302/1304/2750 +f 1283/1285/2751 1302/1304/2751 1281/1283/2751 +f 1281/1283/2752 1302/1304/2752 1301/1303/2752 +f 1281/1283/2753 1301/1303/2753 1269/1271/2753 +f 1269/1271/2754 1301/1303/2754 1292/1294/2754 +f 1269/1271/2755 1292/1294/2720 1270/1272/2719 +f 1271/1273/2756 1270/1272/2756 1289/1291/2756 +f 1271/1273/2757 1289/1291/2757 1278/1280/2757 +f 1278/1280/2758 1289/1291/2758 1288/1290/2758 +f 1268/1270/2704 1278/1280/2703 1291/1293/2759 +f 1291/1293/2760 1278/1280/2760 1288/1290/2760 +f 1268/1270/2761 1291/1293/2761 1280/1282/2761 +f 1280/1282/2762 1291/1293/2762 1299/1301/2762 +f 1280/1282/2763 1299/1301/2764 1304/1306/2765 +f 1280/1282/2763 1304/1306/2765 1282/1284/2766 +f 1282/1284/2767 1304/1306/2767 1303/1305/2767 +f 1282/1284/2768 1303/1305/2768 1285/1287/2768 +f 1285/1287/2769 1303/1305/2769 1306/1308/2769 +f 1285/1287/2770 1306/1308/2770 1286/1288/2770 +f 1286/1288/2771 1306/1308/2771 1307/1309/2771 +f 1286/1288/2772 1307/1309/2773 1300/1302/2774 +f 1286/1288/2772 1300/1302/2774 1279/1281/2775 +f 1279/1281/2706 1300/1302/2734 1272/1274/2707 +f 1273/1275/2776 1298/1300/2776 1275/1277/2776 +f 1277/1279/2742 1275/1277/2777 1294/1296/2743 +f 1294/1296/2722 1275/1277/2778 1298/1300/2730 +f 1268/1270/2779 1290/1292/2779 1271/1273/2779 +f 1271/1273/2780 1290/1292/2780 1293/1295/2780 +f 1271/1273/2781 1293/1295/2781 1267/1269/2781 +f 1267/1269/2782 1293/1295/2782 1292/1294/2782 +f 1267/1269/2783 1292/1294/2783 1268/1270/2783 +f 1268/1270/2784 1292/1294/2784 1290/1292/2784 +f 1276/1278/2785 1295/1297/2785 1298/1300/2785 +f 1276/1278/2786 1298/1300/2786 1274/1276/2786 +f 1274/1276/2787 1298/1300/2787 1297/1299/2787 +f 1274/1276/2788 1297/1299/2788 1277/1279/2788 +f 1277/1279/2789 1297/1299/2789 1295/1297/2789 +f 1277/1279/2790 1295/1297/2790 1276/1278/2790 +f 1309/1311/2791 1310/1312/2792 1311/1313/2793 +f 1312/1314/2794 1310/1312/2792 1309/1311/2791 +f 1313/1315/2795 1314/1316/2796 1315/1317/2797 +f 1315/1317/2797 1314/1316/2796 1316/1318/2798 +f 1317/1319/2799 1318/1320/2800 1319/1321/2801 +f 1319/1321/2801 1320/1322/2802 1317/1319/2799 +f 1321/1323/2803 1322/1324/2803 1323/1325/2803 +f 1324/1326/2804 1325/1327/2805 1322/1324/2806 +f 1324/1326/2804 1322/1324/2806 1326/1328/2807 +f 1325/1327/2805 1323/1325/2808 1322/1324/2806 +f 1325/1327/2805 1327/1329/2809 1323/1325/2808 +f 1323/1325/2808 1327/1329/2809 1328/1330/2810 +f 1328/1330/2810 1329/1331/2811 1323/1325/2808 +f 1330/1332/2812 1331/1333/2813 1332/1334/2814 +f 1333/1335/2815 1334/1336/2816 1335/1337/2817 +f 1336/1338/2818 1309/1311/2819 1311/1313/2820 +f 1336/1338/2818 1337/1339/2821 1309/1311/2819 +f 1338/1340/2820 1332/1334/2814 1331/1333/2813 +f 1339/1341/2822 1340/1342/2822 1341/1343/2822 +f 1342/1344/2823 1340/1342/2824 1339/1341/2825 +f 1342/1344/2823 1334/1336/2826 1340/1342/2824 +f 1343/1345/2827 1334/1336/2826 1342/1344/2823 +f 1343/1345/2827 1335/1337/2828 1334/1336/2826 +f 1344/1346/2829 1335/1337/2828 1343/1345/2827 +f 1345/1347/2830 1339/1341/2830 1341/1343/2830 +f 1346/1348/2831 1347/1349/2832 1348/1350/2833 +f 1349/1351/2834 1350/1352/2835 1351/1353/2836 +f 1347/1349/2832 1352/1354/2837 1348/1350/2833 +f 1350/1352/2838 1333/1335/2815 1335/1337/2817 +f 1350/1352/2838 1353/1355/2839 1333/1335/2815 +f 1344/1346/2840 1328/1330/2810 1354/1356/2841 +f 1343/1345/2842 1328/1330/2810 1344/1346/2840 +f 1343/1345/2842 1329/1331/2811 1328/1330/2810 +f 1342/1344/2843 1329/1331/2811 1343/1345/2842 +f 1342/1344/2843 1345/1347/2844 1329/1331/2811 +f 1339/1341/2845 1345/1347/2844 1342/1344/2843 +f 1350/1352/2835 1354/1356/2846 1351/1353/2836 +f 1334/1336/2816 1333/1335/2815 1355/1357/2816 +f 1353/1355/2847 1351/1353/2848 1333/1335/2849 +f 1349/1351/2850 1351/1353/2848 1353/1355/2847 +f 1350/1352/2851 1349/1351/2851 1353/1355/2851 +f 1335/1337/2852 1354/1356/2852 1350/1352/2852 +f 1354/1356/2853 1335/1337/2853 1344/1346/2853 +f 1333/1335/2854 1356/1358/2855 1355/1357/2856 +f 1351/1353/2857 1356/1358/2855 1333/1335/2854 +f 1356/1358/2858 1334/1336/2859 1355/1357/2860 +f 1328/1330/2861 1334/1336/2859 1356/1358/2858 +f 1327/1329/2862 1357/1359/2863 1358/1360/2864 +f 1327/1329/2862 1358/1360/2864 1328/1330/2865 +f 1358/1360/2866 1334/1336/2859 1328/1330/2861 +f 1327/1329/2867 1359/1361/2868 1357/1359/2869 +f 1325/1327/2870 1359/1361/2868 1327/1329/2867 +f 1360/1362/2871 1325/1327/2872 1324/1326/2873 +f 1359/1361/2874 1325/1327/2872 1360/1362/2871 +f 1359/1361/2875 1361/1363/2876 1321/1323/2877 +f 1360/1362/2878 1361/1363/2876 1359/1361/2875 +f 1360/1362/2878 1362/1364/2879 1361/1363/2876 +f 1321/1323/2877 1357/1359/2880 1359/1361/2875 +f 1358/1360/2881 1363/1365/2882 1340/1342/2883 +f 1357/1359/2880 1363/1365/2882 1358/1360/2881 +f 1357/1359/2880 1321/1323/2877 1363/1365/2882 +f 1340/1342/2883 1334/1336/2884 1358/1360/2881 +f 1326/1328/2885 1360/1362/2886 1324/1326/2887 +f 1362/1364/2888 1360/1362/2886 1326/1328/2885 +f 1362/1364/2889 1326/1328/2889 1361/1363/2889 +f 1361/1363/2890 1322/1324/2890 1321/1323/2890 +f 1361/1363/2891 1326/1328/2891 1322/1324/2891 +f 1323/1325/2892 1363/1365/2892 1321/1323/2892 +f 1329/1331/2893 1363/1365/2893 1323/1325/2893 +f 1329/1331/2894 1340/1342/2895 1363/1365/2896 +f 1345/1347/2897 1341/1343/2897 1364/1366/2897 +f 1365/1367/2898 1364/1366/2898 1366/1368/2898 +f 1367/1369/2899 1365/1367/2900 1366/1368/2901 +f 1368/1370/2902 1365/1367/2900 1367/1369/2899 +f 1369/1371/2903 1368/1370/2904 1367/1369/2905 +f 1370/1372/2906 1368/1370/2904 1369/1371/2903 +f 1340/1342/2895 1370/1372/2907 1369/1371/2908 +f 1329/1331/2894 1370/1372/2907 1340/1342/2895 +f 1371/1373/2909 1372/1374/2909 1373/1375/2909 +f 1374/1376/2909 1371/1373/2909 1373/1375/2909 +f 1372/1374/2910 1371/1373/2911 1375/1377/2912 +f 1376/1378/2913 1377/1379/2914 1374/1376/2915 +f 1376/1378/2913 1374/1376/2915 1373/1375/2916 +f 1378/1380/2917 1377/1379/2918 1379/1381/2919 +f 1378/1380/2917 1380/1382/2920 1377/1379/2918 +f 1378/1380/2921 1381/1383/2921 1380/1382/2921 +f 1381/1383/2922 1382/1384/2923 1379/1381/2924 +f 1383/1385/2925 1382/1384/2923 1381/1383/2922 +f 1377/1379/2926 1371/1373/2927 1374/1376/2928 +f 1380/1382/2929 1371/1373/2927 1377/1379/2926 +f 1371/1373/2911 1380/1382/2930 1375/1377/2912 +f 1376/1378/2931 1372/1374/2932 1375/1377/2933 +f 1376/1378/2931 1373/1375/2934 1372/1374/2932 +f 1378/1380/2935 1383/1385/2935 1381/1383/2935 +f 1382/1384/2936 1378/1380/2937 1379/1381/2938 +f 1383/1385/2939 1378/1380/2937 1382/1384/2936 +f 1384/1386/2940 1385/1387/2941 1386/1388/2942 +f 1387/1389/2943 1388/1390/2944 1389/1391/2943 +f 1390/1392/2945 1389/1391/2943 1388/1390/2944 +f 1391/1393/2946 1386/1388/2942 1392/1394/2947 +f 1386/1388/2942 1391/1393/2946 1384/1386/2940 +f 1389/1391/2948 1386/1388/2949 1385/1387/2950 +f 1390/1392/2951 1386/1388/2949 1389/1391/2948 +f 1385/1387/2952 1387/1389/2952 1389/1391/2952 +f 1384/1386/2953 1387/1389/2953 1385/1387/2953 +f 1390/1392/2945 1391/1393/2954 1392/1394/2955 +f 1388/1390/2944 1391/1393/2954 1390/1392/2945 +f 1384/1386/2956 1388/1390/2956 1387/1389/2956 +f 1391/1393/2957 1388/1390/2957 1384/1386/2957 +f 1393/1395/2958 1394/1396/2959 1395/1397/2960 +f 1395/1397/2960 1396/1398/2961 1393/1395/2958 +f 1397/1399/2962 1398/1400/2963 1395/1397/2964 +f 1395/1397/2964 1394/1396/2965 1397/1399/2962 +f 1386/1388/2966 1390/1392/2966 1392/1394/2966 +f 1399/1401/2967 1400/1402/2968 1401/1403/2969 +f 1402/1404/2970 1403/1405/2970 1404/1406/2970 +f 1402/1404/2971 1405/1407/2971 1403/1405/2971 +f 1406/1408/2972 1405/1407/2972 1402/1404/2972 +f 1405/1407/2973 1400/1402/2968 1403/1405/2974 +f 1402/1404/2975 1404/1406/2820 1399/1401/2976 +f 1400/1402/2968 1407/1409/2977 1403/1405/2974 +f 1406/1408/2978 1402/1404/2975 1399/1401/2976 +f 1405/1407/2973 1401/1403/2969 1400/1402/2968 +f 1404/1406/2979 1407/1409/2979 1399/1401/2979 +f 1404/1406/2980 1403/1405/2980 1407/1409/2980 +f 1400/1402/2981 1399/1401/2981 1407/1409/2981 +f 1337/1339/1501 1336/1338/1513 1346/1348/1515 +f 1408/1410/2982 1409/1411/1501 1346/1348/1515 +f 1336/1338/1513 1347/1349/1513 1346/1348/1515 +f 1410/1412/1501 1411/1413/2983 1346/1348/1515 +f 1409/1411/1501 1410/1412/1501 1346/1348/1515 +f 1411/1413/2983 1337/1339/1501 1346/1348/1515 +f 1412/1414/2984 1413/1415/2984 1414/1416/2984 +f 1415/1417/2985 1412/1414/2985 1414/1416/2985 +f 1416/1418/2986 1415/1417/2987 1414/1416/2988 +f 1413/1415/2989 1416/1418/2986 1414/1416/2988 +f 1417/1419/2990 1418/1420/2991 1419/1421/2992 +f 1420/1422/2993 1421/1423/2994 1422/1424/2995 +f 1421/1423/2994 1423/1425/2996 1424/1426/2997 +f 1424/1426/2997 1423/1425/2996 1425/1427/2998 +f 1420/1422/2993 1426/1428/2999 1421/1423/2994 +f 1421/1423/2994 1426/1428/2999 1423/1425/2996 +f 1427/1429/3000 1428/1430/3001 1429/1431/3002 +f 1425/1427/2998 1430/1432/3003 1424/1426/2997 +f 1430/1432/3003 1425/1427/2998 1429/1431/3002 +f 1429/1431/3002 1425/1427/2998 1427/1429/3000 +f 1431/1433/3002 1432/1434/3004 1433/1435/3001 +f 1431/1433/3002 1433/1435/3001 1428/1430/3001 +f 1428/1430/3001 1433/1435/3001 1429/1431/3002 +f 1420/1422/2993 1422/1424/2995 1431/1433/3002 +f 1431/1433/3002 1434/1436/3000 1424/1426/2997 +f 1424/1426/2997 1430/1432/3003 1432/1434/3004 +f 1422/1424/2995 1434/1436/3000 1431/1433/3002 +f 1424/1426/2997 1432/1434/3004 1431/1433/3002 +f 1428/1430/3005 1427/1429/3006 1435/1437/3007 +f 1435/1437/3007 1427/1429/3006 1436/1438/3008 +f 1437/1439/3009 1436/1438/3010 1438/1440/3011 +f 1439/1441/3012 1438/1440/3011 1440/1442/3013 +f 1439/1441/3012 1440/1442/3013 1441/1443/3014 +f 1440/1442/3013 1438/1440/3011 1436/1438/3010 +f 1442/1444/3015 1443/1445/3016 1439/1441/3012 +f 1439/1441/3012 1443/1445/3016 1438/1440/3011 +f 1435/1437/3015 1444/1446/3016 1442/1444/3015 +f 1436/1438/3010 1437/1439/3009 1445/1447/3017 +f 1435/1437/3015 1436/1438/3010 1445/1447/3017 +f 1443/1445/3016 1442/1444/3015 1446/1448/3018 +f 1445/1447/3017 1447/1449/3019 1435/1437/3015 +f 1444/1446/3016 1435/1437/3015 1447/1449/3019 +f 1444/1446/3016 1448/1450/3020 1442/1444/3015 +f 1442/1444/3015 1448/1450/3020 1446/1448/3018 +f 1448/1450/3020 1444/1446/3016 1438/1440/3011 +f 1438/1440/3011 1444/1446/3016 1437/1439/3009 +f 1425/1427/3021 1436/1438/3021 1427/1429/3021 +f 1436/1438/3022 1425/1427/3022 1440/1442/3022 +f 1440/1442/3023 1425/1427/3024 1423/1425/3025 +f 1449/1451/3026 1450/1452/3026 1451/1453/3026 +f 1449/1451/3026 1451/1453/3026 1423/1425/3025 +f 1423/1425/3025 1451/1453/3026 1440/1442/3023 +f 1452/1454/3027 1449/1451/3028 1426/1428/3029 +f 1426/1428/3029 1449/1451/3028 1423/1425/3030 +f 1453/1455/3031 1454/1456/3031 1452/1454/3031 +f 1452/1454/3031 1455/1457/3031 1453/1455/3031 +f 1420/1422/3032 1439/1441/3033 1426/1428/3034 +f 1426/1428/3034 1439/1441/3033 1441/1443/3035 +f 1426/1428/3034 1455/1457/3031 1452/1454/3031 +f 1426/1428/3034 1441/1443/3035 1455/1457/3031 +f 1439/1441/3033 1420/1422/3032 1442/1444/3036 +f 1442/1444/3036 1420/1422/3032 1431/1433/3037 +f 1441/1443/3038 1440/1442/3039 1455/1457/3040 +f 1455/1457/3040 1440/1442/3039 1451/1453/3041 +f 1455/1457/3042 1451/1453/3043 1450/1452/3044 +f 1455/1457/3042 1450/1452/3044 1453/1455/3045 +f 1453/1455/3046 1450/1452/3046 1454/1456/3046 +f 1450/1452/3047 1449/1451/3047 1454/1456/3047 +f 1454/1456/3048 1449/1451/3048 1452/1454/3048 +f 1442/1444/3049 1431/1433/3050 1435/1437/3051 +f 1435/1437/3051 1431/1433/3050 1428/1430/3052 +f 1433/1435/3053 1444/1446/3053 1447/1449/3053 +f 1433/1435/3054 1447/1449/3054 1429/1431/3054 +f 1429/1431/3055 1447/1449/3055 1445/1447/3055 +f 1429/1431/3056 1445/1447/3056 1430/1432/3056 +f 1430/1432/3057 1445/1447/3057 1437/1439/3057 +f 1430/1432/3058 1437/1439/3058 1432/1434/3058 +f 1432/1434/3059 1437/1439/3059 1444/1446/3059 +f 1432/1434/3060 1444/1446/3060 1433/1435/3060 +f 1424/1426/3061 1446/1448/3061 1448/1450/3061 +f 1424/1426/3062 1448/1450/3063 1438/1440/3064 +f 1424/1426/3062 1438/1440/3064 1421/1423/3065 +f 1421/1423/3066 1438/1440/3067 1443/1445/3068 +f 1421/1423/3066 1443/1445/3068 1422/1424/3069 +f 1422/1424/3070 1443/1445/3070 1434/1436/3070 +f 1434/1436/3071 1443/1445/3071 1446/1448/3071 +f 1434/1436/3072 1446/1448/3072 1424/1426/3072 +f 1456/1458/3073 1457/1459/3074 1458/1460/3075 +f 1459/1461/3076 1460/1462/3077 1461/1463/3078 +f 1457/1459/3079 1462/1464/3080 1459/1461/3076 +f 1457/1459/3079 1459/1461/3076 1463/1465/3081 +f 1459/1461/3076 1461/1463/3078 1463/1465/3081 +f 1464/1466/3082 1465/1467/3083 1466/1468/3084 +f 1467/1469/3026 1465/1467/3083 1464/1466/3082 +f 1468/1470/3085 1469/1471/3085 1470/1472/3085 +f 1471/1473/3086 1472/1474/3087 1468/1470/3088 +f 1468/1470/3088 1472/1474/3087 1469/1471/3089 +f 1471/1473/3086 1468/1470/3088 1473/1475/3090 +f 1471/1473/3086 1473/1475/3090 1474/1476/3091 +f 1475/1477/3092 1474/1476/3092 1473/1475/3092 +f 1476/1478/3093 1477/1479/3026 1475/1477/3094 +f 1475/1477/3094 1473/1475/3095 1476/1478/3093 +f 1458/1460/3075 1478/1480/3026 1456/1458/3073 +f 1461/1463/3096 1479/1481/3097 1458/1460/3075 +f 1479/1481/3097 1478/1480/3026 1458/1460/3075 +f 1458/1460/3075 1480/1482/3098 1461/1463/3096 +f 1481/1483/3099 1482/1484/3100 1483/1485/3101 +f 1483/1485/3101 1482/1484/3100 1484/1486/3102 +f 1485/1487/3103 1477/1479/3104 1486/1488/3105 +f 1486/1488/3105 1477/1479/3104 1476/1478/3106 +f 1486/1488/3105 1476/1478/3106 1487/1489/3107 +f 1487/1489/3107 1476/1478/3106 1488/1490/3108 +f 1487/1489/3107 1488/1490/3108 1483/1485/3109 +f 1483/1485/3109 1488/1490/3108 1481/1483/3110 +f 1484/1486/3111 1482/1484/3112 1489/1491/3113 +f 1489/1491/3113 1482/1484/3112 1490/1492/3114 +f 1489/1491/3115 1490/1492/3116 1470/1472/3117 +f 1489/1491/3115 1470/1472/3117 1491/1493/3118 +f 1492/1494/3119 1491/1493/3118 1493/1495/3120 +f 1493/1495/3120 1491/1493/3118 1470/1472/3117 +f 1469/1471/98 1472/1474/98 1492/1494/98 +f 1492/1494/98 1493/1495/98 1469/1471/98 +f 1494/1496/3121 1495/1497/3121 1496/1498/3121 +f 1495/1497/3122 1494/1496/3122 1497/1499/3122 +f 1495/1497/3123 1497/1499/3123 1498/1500/3123 +f 1495/1497/3124 1498/1500/3124 1496/1498/3124 +f 1499/1501/3125 1500/1502/3125 1501/1503/3125 +f 1499/1501/3126 1501/1503/3126 1502/1504/3126 +f 1499/1501/3127 1502/1504/3127 1500/1502/3127 +f 1503/1505/3128 1504/1506/3129 1505/1507/3130 +f 1503/1505/3128 1506/1508/3131 1504/1506/3129 +f 1496/1498/3132 1507/1509/3133 1508/1510/3134 +f 1507/1509/3133 1496/1498/3132 1498/1500/3135 +f 1498/1500/3136 1509/1511/3137 1507/1509/3138 +f 1509/1511/3137 1498/1500/3136 1497/1499/3139 +f 1509/1511/3140 1497/1499/3141 1494/1496/3142 +f 1494/1496/3142 1510/1512/3143 1509/1511/3140 +f 1510/1512/3144 1494/1496/3145 1496/1498/3146 +f 1496/1498/3146 1508/1510/3147 1510/1512/3144 +f 1502/1504/3148 1511/1513/3148 1512/1514/3148 +f 1511/1513/3149 1502/1504/3150 1501/1503/3151 +f 1501/1503/3151 1513/1515/3152 1511/1513/3149 +f 1501/1503/3153 1514/1516/3153 1513/1515/3153 +f 1514/1516/3154 1501/1503/3154 1500/1502/3154 +f 1500/1502/3155 1512/1514/3155 1514/1516/3155 +f 1512/1514/3156 1500/1502/3156 1502/1504/3156 +f 1506/1508/3157 1515/1517/3158 1516/1518/3159 +f 1515/1517/3160 1506/1508/3160 1503/1505/3160 +f 1503/1505/3161 1517/1519/3162 1515/1517/3163 +f 1517/1519/3164 1503/1505/3164 1505/1507/3164 +f 1505/1507/3165 1518/1520/3166 1517/1519/3167 +f 1518/1520/3168 1505/1507/3168 1504/1506/3168 +f 1504/1506/3169 1516/1518/3170 1518/1520/3171 +f 1516/1518/3172 1504/1506/3172 1506/1508/3172 +f 1519/1521/3173 1520/1522/3174 1521/1523/3175 +f 1521/1523/3176 1522/1524/3176 1519/1521/3176 +f 1522/1524/3177 1521/1523/3178 1523/1525/3179 +f 1523/1525/3180 1524/1526/3180 1522/1524/3180 +f 1524/1526/3181 1523/1525/3182 1525/1527/3183 +f 1525/1527/3184 1526/1528/3184 1524/1526/3184 +f 1526/1528/3185 1525/1527/3186 1520/1522/3187 +f 1520/1522/3187 1519/1521/3188 1526/1528/3185 +f 1520/1522/3187 1518/1520/3171 1516/1518/3170 +f 1518/1520/3171 1520/1522/3187 1525/1527/3186 +f 1525/1527/3183 1517/1519/3167 1518/1520/3166 +f 1517/1519/3167 1525/1527/3183 1523/1525/3182 +f 1521/1523/3178 1515/1517/3163 1517/1519/3162 +f 1517/1519/3162 1523/1525/3179 1521/1523/3178 +f 1521/1523/3175 1516/1518/3159 1515/1517/3158 +f 1516/1518/3159 1521/1523/3175 1520/1522/3174 +f 1527/1529/3189 1528/1530/3190 1529/1531/3191 +f 1530/1532/3192 1529/1531/3192 1528/1530/3192 +f 1528/1530/3193 1531/1533/3194 1530/1532/3195 +f 1531/1533/3196 1528/1530/3196 1527/1529/3196 +f 1527/1529/3197 1532/1534/3198 1531/1533/3199 +f 1532/1534/3200 1527/1529/3200 1533/1535/3200 +f 1533/1535/3201 1534/1536/3201 1532/1534/3201 +f 1534/1536/3202 1533/1535/3202 1529/1531/3202 +f 1529/1531/3203 1530/1532/3204 1534/1536/3205 +f 1535/1537/3206 1536/1538/3207 1537/1539/3208 +f 1536/1538/3209 1535/1537/3210 1538/1540/3211 +f 1536/1538/3212 1538/1540/3213 1539/1541/3214 +f 1539/1541/3214 1540/1542/3215 1536/1538/3212 +f 1540/1542/3216 1539/1541/3217 1541/1543/3218 +f 1540/1542/3219 1541/1543/3220 1542/1544/3221 +f 1542/1544/3221 1537/1539/3222 1540/1542/3219 +f 1537/1539/3223 1542/1544/3224 1535/1537/3225 +f 1534/1536/3226 1542/1544/3221 1541/1543/3220 +f 1541/1543/3218 1532/1534/3227 1534/1536/3228 +f 1532/1534/3227 1541/1543/3218 1539/1541/3217 +f 1539/1541/3214 1531/1533/3199 1532/1534/3198 +f 1531/1533/3199 1539/1541/3214 1538/1540/3213 +f 1535/1537/3210 1530/1532/3195 1531/1533/3194 +f 1531/1533/3194 1538/1540/3211 1535/1537/3210 +f 1542/1544/3224 1534/1536/3205 1530/1532/3204 +f 1530/1532/3204 1535/1537/3225 1542/1544/3224 +f 1470/1472/3085 1490/1492/3085 1473/1475/3085 +f 1469/1471/3085 1493/1495/3085 1470/1472/3085 +f 1476/1478/3085 1473/1475/3085 1490/1492/3085 +f 1473/1475/3085 1468/1470/3085 1470/1472/3085 +f 1488/1490/3085 1476/1478/3085 1490/1492/3085 +f 1543/1545/3229 1544/1546/3230 1545/1547/3231 +f 1544/1546/3230 1546/1548/3232 1547/1549/3233 +f 1547/1549/3233 1545/1547/3231 1544/1546/3230 +f 1547/1549/3234 1548/1550/3234 1549/1551/3234 +f 1550/1552/3235 1543/1545/3236 1545/1547/3237 +f 1545/1547/3237 1551/1553/3238 1550/1552/3235 +f 1548/1550/3239 1550/1552/3240 1551/1553/3241 +f 1551/1553/3241 1549/1551/3242 1548/1550/3239 +f 1549/1551/3243 1545/1547/3244 1547/1549/3245 +f 1545/1547/3244 1549/1551/3243 1551/1553/3246 +f 1552/1554/3247 1553/1555/3248 1554/1556/3249 +f 1553/1555/3250 1552/1554/3250 1555/1557/3250 +f 1556/1558/3251 1557/1559/3251 1558/1560/3251 +f 1559/1561/3252 1560/1562/3252 1561/1563/3252 +f 1556/1558/3253 1559/1561/3254 1561/1563/3255 +f 1561/1563/3255 1557/1559/3256 1556/1558/3253 +f 1524/1526/3257 1526/1528/3258 1522/1524/3259 +f 1526/1528/3258 1519/1521/3260 1522/1524/3259 +f 1514/1516/3261 1511/1513/3262 1513/1515/3263 +f 1511/1513/3262 1514/1516/3261 1512/1514/3264 +f 1507/1509/3265 1509/1511/3266 1508/1510/3267 +f 1508/1510/3267 1509/1511/3266 1510/1512/3268 +f 1489/1491/3269 1491/1493/2352 1471/1473/3270 +f 1489/1491/3269 1471/1473/3270 1474/1476/3271 +f 1492/1494/2352 1472/1474/2352 1491/1493/2352 +f 1472/1474/2352 1471/1473/3270 1491/1493/2352 +f 1486/1488/3272 1487/1489/2352 1489/1491/3269 +f 1474/1476/3271 1486/1488/3272 1489/1491/3269 +f 1562/1564/3273 1554/1556/3273 1563/1565/3273 +f 1564/1566/3274 1565/1567/3274 1563/1565/3274 +f 1564/1566/3275 1563/1565/3275 1554/1556/3275 +f 1566/1568/3276 1565/1567/3276 1564/1566/3276 +f 1555/1557/3277 1552/1554/3278 1562/1564/3279 +f 1553/1555/3248 1566/1568/3031 1554/1556/3249 +f 1554/1556/3249 1566/1568/3031 1564/1566/3031 +f 1562/1564/3279 1563/1565/3026 1565/1567/3026 +f 1555/1557/3277 1562/1564/3279 1565/1567/3026 +f 1553/1555/3280 1555/1557/3280 1566/1568/3280 +f 1566/1568/3281 1555/1557/3281 1565/1567/3281 +f 1554/1556/3282 1562/1564/3279 1552/1554/3278 +f 1567/1569/3283 1568/1570/3283 1569/1571/3283 +f 1559/1561/3284 1556/1558/3285 1558/1560/3286 +f 1558/1560/3286 1560/1562/3287 1559/1561/3284 +f 1561/1563/3288 1560/1562/3289 1558/1560/3290 +f 1558/1560/3290 1557/1559/3291 1561/1563/3288 +f 1570/1572/3292 1571/1573/3292 1569/1571/3292 +f 1571/1573/3293 1570/1572/3294 1572/1574/3295 +f 1571/1573/3293 1572/1574/3295 1573/1575/3296 +f 1573/1575/3297 1572/1574/3297 1574/1576/3297 +f 1568/1570/3298 1570/1572/3299 1569/1571/3300 +f 1573/1575/3301 1574/1576/3301 1575/1577/3301 +f 1575/1577/3302 1574/1576/3302 1576/1578/3302 +f 1568/1570/3303 1567/1569/3304 1576/1578/3305 +f 1576/1578/3305 1567/1569/3304 1575/1577/3306 +f 1571/1573/3307 1567/1569/3308 1569/1571/3309 +f 1571/1573/3307 1573/1575/3310 1567/1569/3308 +f 1568/1570/3298 1576/1578/3026 1572/1574/3026 +f 1574/1576/3026 1572/1574/3026 1576/1578/3026 +f 1573/1575/3310 1575/1577/3031 1567/1569/3308 +f 1572/1574/3026 1570/1572/3299 1568/1570/3298 +f 1577/1579/3311 1578/1580/3312 1579/1581/3313 +f 1579/1581/3313 1578/1580/3312 1546/1548/3314 +f 1578/1580/3031 1577/1579/3031 1544/1546/3031 +f 1548/1550/3315 1580/1582/3316 1581/1583/3317 +f 1548/1550/3315 1581/1583/3317 1550/1552/3318 +f 1582/1584/3319 1543/1545/3320 1550/1552/3321 +f 1543/1545/3322 1582/1584/3323 1547/1549/3324 +f 1547/1549/3324 1582/1584/3323 1583/1585/3325 +f 1577/1579/3326 1579/1581/3327 1544/1546/3328 +f 1544/1546/3328 1579/1581/3327 1546/1548/3329 +f 1578/1580/3330 1544/1546/3330 1543/1545/3330 +f 1578/1580/3331 1543/1545/3332 1547/1549/3333 +f 1578/1580/3331 1547/1549/3333 1546/1548/3334 +f 1548/1550/3335 1583/1585/3336 1580/1582/3337 +f 1548/1550/3335 1547/1549/3338 1583/1585/3336 +f 1581/1583/3339 1582/1584/3319 1550/1552/3321 +f 1583/1585/3340 1582/1584/3340 1580/1582/3340 +f 1582/1584/3340 1581/1583/3340 1580/1582/3340 +f 1461/1463/3341 1460/1462/3341 1479/1481/3341 +f 1460/1462/3342 1459/1461/3343 1479/1481/3344 +f 1479/1481/3344 1459/1461/3343 1478/1480/3345 +f 1459/1461/3346 1462/1464/3347 1478/1480/3348 +f 1478/1480/3348 1462/1464/3347 1456/1458/3349 +f 1462/1464/3350 1457/1459/3350 1456/1458/3350 +f 1463/1465/3351 1458/1460/3351 1457/1459/3351 +f 1461/1463/3096 1480/1482/3098 1584/1586/3352 +f 1584/1586/3353 1480/1482/3353 1585/1587/3353 +f 1586/1588/3354 1587/1589/3354 1588/1590/3354 +f 1586/1588/3355 1588/1590/3355 1585/1587/3355 +f 1589/1591/3356 1587/1589/3356 1586/1588/3356 +f 1589/1591/3357 1590/1592/3358 1587/1589/3359 +f 1587/1589/3359 1590/1592/3358 1591/1593/3360 +f 1591/1593/3361 1590/1592/3361 1592/1594/3361 +f 1480/1482/3362 1593/1595/3363 1594/1596/3364 +f 1595/1597/3365 1585/1587/3366 1480/1482/3362 +f 1595/1597/3365 1480/1482/3362 1594/1596/3364 +f 1592/1594/3367 1589/1591/3368 1586/1588/3369 +f 1592/1594/3367 1590/1592/3370 1589/1591/3368 +f 1592/1594/3367 1586/1588/3369 1595/1597/3365 +f 1595/1597/3365 1586/1588/3369 1585/1587/3366 +f 1595/1597/3371 1596/1598/3371 1592/1594/3371 +f 1592/1594/3372 1596/1598/3372 1591/1593/3372 +f 1593/1595/3373 1466/1468/3373 1594/1596/3373 +f 1594/1596/3374 1466/1468/3374 1597/1599/3374 +f 1596/1598/3375 1595/1597/3375 1597/1599/3375 +f 1597/1599/3376 1595/1597/3376 1594/1596/3376 +f 1464/1466/3377 1466/1468/3377 1598/1600/3377 +f 1467/1469/3378 1464/1466/3379 1599/1601/3380 +f 1599/1601/3380 1464/1466/3379 1598/1600/3381 +f 1465/1467/3382 1600/1602/3382 1601/1603/3382 +f 1600/1602/3383 1465/1467/3384 1602/1604/3385 +f 1600/1602/3383 1602/1604/3385 1603/1605/3386 +f 1602/1604/3385 1604/1606/3387 1603/1605/3386 +f 1603/1605/3386 1604/1606/3387 1605/1607/3388 +f 1604/1606/3389 1467/1469/3390 1605/1607/3347 +f 1605/1607/3347 1467/1469/3390 1599/1601/3391 +f 1466/1468/3392 1599/1601/3393 1598/1600/3394 +f 1606/1608/3395 1463/1465/3396 1607/1609/3397 +f 1607/1609/3397 1463/1465/3396 1461/1463/3398 +f 1607/1609/3397 1461/1463/3398 1608/1610/3399 +f 1608/1610/3399 1461/1463/3398 1466/1468/3400 +f 1608/1610/3399 1466/1468/3400 1601/1603/3401 +f 1601/1603/3401 1466/1468/3400 1465/1467/3402 +f 1599/1601/3393 1466/1468/3392 1593/1595/3403 +f 1603/1605/3031 1605/1607/3031 1599/1601/3393 +f 1487/1489/3404 1483/1485/3026 1484/1486/3405 +f 1604/1606/3026 1602/1604/3026 1467/1469/3026 +f 1489/1491/3406 1487/1489/3404 1484/1486/3405 +f 1599/1601/3393 1600/1602/3031 1603/1605/3031 +f 1602/1604/3026 1465/1467/3083 1467/1469/3026 +f 1463/1465/3407 1606/1608/3407 1458/1460/3407 +f 1601/1603/3408 1600/1602/3409 1608/1610/3410 +f 1608/1610/3410 1600/1602/3409 1593/1595/3363 +f 1608/1610/3410 1593/1595/3363 1607/1609/3411 +f 1607/1609/3411 1593/1595/3363 1480/1482/3362 +f 1607/1609/3411 1480/1482/3362 1606/1608/3412 +f 1606/1608/3413 1480/1482/3413 1458/1460/3413 +f 1481/1483/3031 1488/1490/3414 1482/1484/3415 +f 1485/1487/3416 1474/1476/3417 1609/1611/3418 +f 1486/1488/3419 1474/1476/3417 1485/1487/3416 +f 1599/1601/3393 1593/1595/3403 1600/1602/3031 +f 1490/1492/3420 1482/1484/3415 1488/1490/3414 +f 1597/1599/3421 1461/1463/3398 1584/1586/3422 +f 1461/1463/3398 1597/1599/3421 1466/1468/3400 +f 1584/1586/3422 1596/1598/3423 1597/1599/3421 +f 1596/1598/3423 1584/1586/3422 1588/1590/3424 +f 1591/1593/3425 1588/1590/3424 1587/1589/3426 +f 1418/1420/2991 1417/1419/2990 1610/1612/3427 +f 1611/1613/3428 1612/1614/3429 1613/1615/3430 +f 1614/1616/3431 1611/1613/3428 1613/1615/3430 +f 1591/1593/3425 1596/1598/3423 1588/1590/3424 +f 1585/1587/3432 1588/1590/3432 1584/1586/3432 +f 1533/1535/3433 1527/1529/3189 1529/1531/3191 +f 1615/1617/3434 1540/1542/3434 1537/1539/3434 +f 1536/1538/3435 1540/1542/3435 1615/1617/3435 +f 1537/1539/3208 1536/1538/3207 1615/1617/3436 +f 1475/1477/3437 1609/1611/3437 1474/1476/3437 +f 1475/1477/3438 1477/1479/3439 1609/1611/3440 +f 1609/1611/3440 1477/1479/3439 1485/1487/3441 +f 1398/1400/3442 1397/1399/3443 1393/1395/3444 +f 1393/1395/3444 1396/1398/3445 1398/1400/3442 +f 1397/1399/3446 1394/1396/3446 1393/1395/3446 +f 1398/1400/3447 1396/1398/3447 1395/1397/3447 +f 1406/1408/3448 1401/1403/3448 1405/1407/3448 +f 1401/1403/3449 1406/1408/2978 1399/1401/2976 +f 1616/1618/3450 1617/1619/3451 1618/1620/3452 +f 1617/1619/3451 1616/1618/3450 1377/1379/3453 +f 1376/1378/3454 1375/1377/3455 1618/1620/3456 +f 1618/1620/3456 1617/1619/3457 1376/1378/3454 +f 1375/1377/3458 1380/1382/3459 1616/1618/3460 +f 1616/1618/3460 1618/1620/3461 1375/1377/3458 +f 1377/1379/3462 1376/1378/3462 1617/1619/3462 +f 1381/1383/3463 1379/1381/3464 1377/1379/3465 +f 1377/1379/3465 1616/1618/3466 1381/1383/3463 +f 1380/1382/3467 1381/1383/3463 1616/1618/3466 +f 1619/1621/3468 1330/1332/3469 1620/1622/3470 +f 1332/1334/3471 1621/1623/3468 1330/1332/3469 +f 1621/1623/3468 1620/1622/3470 1330/1332/3469 +f 1622/1624/3468 1623/1625/3472 1624/1626/3468 +f 1624/1626/3468 1330/1332/3469 1619/1621/3468 +f 1625/1627/3473 1626/1628/3474 1627/1629/3475 +f 1625/1627/3476 1627/1629/3477 1628/1630/3478 +f 1628/1630/3479 1629/1631/3480 1625/1627/3481 +f 1628/1630/3482 1630/1632/3483 1629/1631/3484 +f 1630/1632/3483 1628/1630/3482 1631/1633/3485 +f 1630/1632/3486 1631/1633/3487 1626/1628/3488 +f 1626/1628/3488 1632/1634/3489 1630/1632/3486 +f 1626/1628/3474 1625/1627/3473 1632/1634/3490 +f 1316/1318/3491 1632/1634/3490 1625/1627/3473 +f 1632/1634/3492 1316/1318/3492 1314/1316/3492 +f 1314/1316/3493 1630/1632/3486 1632/1634/3489 +f 1630/1632/3494 1314/1316/3494 1313/1315/3494 +f 1313/1315/3495 1629/1631/3484 1630/1632/3483 +f 1629/1631/3496 1313/1315/3496 1315/1317/3496 +f 1315/1317/3497 1625/1627/3481 1629/1631/3480 +f 1625/1627/3481 1315/1317/3497 1316/1318/3498 +f 1317/1319/3499 1627/1629/3475 1626/1628/3474 +f 1626/1628/3500 1318/1320/3500 1317/1319/3500 +f 1318/1320/3501 1626/1628/3488 1631/1633/3487 +f 1631/1633/3502 1319/1321/3502 1318/1320/3502 +f 1319/1321/3503 1631/1633/3485 1628/1630/3482 +f 1628/1630/3504 1320/1322/3504 1319/1321/3504 +f 1320/1322/3505 1628/1630/3478 1627/1629/3477 +f 1627/1629/3506 1317/1319/3506 1320/1322/3506 +f 1633/1635/3507 1634/1636/3508 1635/1637/3509 +f 1634/1636/3510 1633/1635/3511 1636/1638/3512 +f 1634/1636/3513 1636/1638/3514 1637/1639/3515 +f 1637/1639/3515 1638/1640/3516 1634/1636/3513 +f 1637/1639/3517 1639/1641/3518 1638/1640/3519 +f 1639/1641/3520 1637/1639/3520 1633/1635/3520 +f 1633/1635/3521 1635/1637/3522 1639/1641/3523 +f 1611/1613/3524 1639/1641/3523 1635/1637/3522 +f 1635/1637/3522 1612/1614/3525 1611/1613/3524 +f 1614/1616/3526 1638/1640/3519 1639/1641/3518 +f 1639/1641/3518 1611/1613/3527 1614/1616/3526 +f 1613/1615/3528 1634/1636/3513 1638/1640/3516 +f 1638/1640/3516 1614/1616/3529 1613/1615/3528 +f 1612/1614/3530 1635/1637/3509 1634/1636/3508 +f 1634/1636/3508 1613/1615/3531 1612/1614/3530 +f 1637/1639/3532 1636/1638/3532 1640/1642/3532 +f 1633/1635/3511 1641/1643/3533 1642/1644/3534 +f 1642/1644/3534 1636/1638/3512 1633/1635/3511 +f 1641/1643/3535 1633/1635/3535 1637/1639/3535 +f 1637/1639/3536 1643/1645/3536 1641/1643/3536 +f 1643/1645/3537 1637/1639/3537 1640/1642/3537 +f 1640/1642/3538 1644/1646/3538 1643/1645/3538 +f 1644/1646/3539 1640/1642/3539 1636/1638/3539 +f 1636/1638/3540 1642/1644/3540 1644/1646/3540 +f 1645/1647/3541 1610/1612/3542 1417/1419/3543 +f 1417/1419/3543 1646/1648/3544 1645/1647/3541 +f 1646/1648/3545 1417/1419/3545 1419/1421/3545 +f 1419/1421/3546 1647/1649/3547 1646/1648/3548 +f 1647/1649/3547 1419/1421/3546 1418/1420/3549 +f 1610/1612/3550 1645/1647/3551 1647/1649/3552 +f 1647/1649/3552 1418/1420/3553 1610/1612/3550 +f 1413/1415/3554 1648/1650/3555 1649/1651/3556 +f 1649/1651/3556 1416/1418/3557 1413/1415/3554 +f 1413/1415/3558 1650/1652/3559 1648/1650/3560 +f 1650/1652/3559 1413/1415/3558 1412/1414/3561 +f 1415/1417/3562 1651/1653/3563 1650/1652/3564 +f 1650/1652/3564 1412/1414/3565 1415/1417/3562 +f 1416/1418/3566 1649/1651/3567 1651/1653/3568 +f 1651/1653/3568 1415/1417/3569 1416/1418/3566 +f 1642/1644/3570 1643/1645/3571 1644/1646/3572 +f 1642/1644/3570 1641/1643/3573 1643/1645/3571 +f 1652/1654/3574 1647/1649/3574 1645/1647/3574 +f 1652/1654/3575 1646/1648/3575 1647/1649/3575 +f 1646/1648/3576 1652/1654/3576 1645/1647/3576 +f 1653/1655/3577 1649/1651/3578 1648/1650/3579 +f 1649/1651/3578 1653/1655/3577 1651/1653/3580 +f 1653/1655/3581 1650/1652/3581 1651/1653/3581 +f 1650/1652/3582 1653/1655/3582 1648/1650/3582 +f 1622/1624/98 1410/1412/98 1409/1411/98 +f 1409/1411/98 1623/1625/98 1622/1624/98 +f 1623/1625/3583 1408/1410/3584 1624/1626/3585 +f 1409/1411/3586 1408/1410/3584 1623/1625/3583 +f 1346/1348/3587 1624/1626/3585 1408/1410/3584 +f 1346/1348/3588 1330/1332/3588 1624/1626/3588 +f 1346/1348/3589 1331/1333/3589 1330/1332/3589 +f 1348/1350/3590 1331/1333/3590 1346/1348/3590 +f 1352/1354/3591 1332/1334/3592 1338/1340/3593 +f 1347/1349/3594 1332/1334/3592 1352/1354/3591 +f 1347/1349/3594 1621/1623/3595 1332/1334/3592 +f 1336/1338/3596 1621/1623/3595 1347/1349/3594 +f 1336/1338/3596 1310/1312/3597 1621/1623/3595 +f 1311/1313/3598 1310/1312/3597 1336/1338/3596 +f 1352/1354/3599 1331/1333/3600 1348/1350/3601 +f 1338/1340/3602 1331/1333/3600 1352/1354/3599 +f 1369/1371/3603 1367/1369/3604 1341/1343/3605 +f 1340/1342/3606 1369/1371/3603 1341/1343/3605 +f 1341/1343/3605 1367/1369/3604 1366/1368/3607 +f 1312/1314/3608 1620/1622/3609 1621/1623/3610 +f 1621/1623/3610 1310/1312/2943 1312/1314/3608 +f 1620/1622/3611 1309/1311/3612 1337/1339/3613 +f 1312/1314/3614 1309/1311/3614 1620/1622/3614 +f 1337/1339/3613 1619/1621/3615 1620/1622/3611 +f 1411/1413/3616 1619/1621/3617 1337/1339/3618 +f 1619/1621/3617 1410/1412/3619 1622/1624/3620 +f 1411/1413/3616 1410/1412/3619 1619/1621/3617 +f 1619/1621/3468 1622/1624/3468 1624/1626/3468 +f 1351/1353/2836 1354/1356/2846 1356/1358/3621 +f 1356/1358/3621 1354/1356/2846 1328/1330/3622 +f 1368/1370/3623 1329/1331/3624 1345/1347/3625 +f 1364/1366/3626 1368/1370/3623 1345/1347/3625 +f 1364/1366/3626 1365/1367/3627 1368/1370/3623 +f 1368/1370/3623 1370/1372/3628 1329/1331/3624 +f 1366/1368/3607 1364/1366/3629 1341/1343/3605 +f 1654/1656/3630 1655/1657/3631 1656/1658/3632 +f 1657/1659/3633 1658/1660/3634 1659/1661/3635 +f 1659/1661/3635 1658/1660/3634 1655/1657/3631 +f 1659/1661/3635 1655/1657/3631 1654/1656/3630 +f 1656/1658/3632 1660/1662/3636 1661/1663/3637 +f 1662/1664/3638 1663/1665/3639 1654/1656/3630 +f 1656/1658/3632 1664/1666/3640 1654/1656/3630 +f 1654/1656/3630 1664/1666/3640 1662/1664/3638 +f 1661/1663/3637 1664/1666/3640 1656/1658/3632 +f 1665/1667/3639 1657/1659/3633 1659/1661/3635 +f 1666/1668/3641 1667/1669/3642 1660/1662/3636 +f 1660/1662/3636 1667/1669/3642 1661/1663/3637 +f 1657/1659/3633 1665/1667/3639 1666/1668/3641 +f 1666/1668/3641 1665/1667/3639 1663/1665/3639 +f 1662/1664/3638 1667/1669/3642 1663/1665/3639 +f 1663/1665/3639 1667/1669/3642 1666/1668/3641 +f 1660/1662/3643 1656/1658/3644 1668/1670/3645 +f 1668/1670/3645 1656/1658/3644 1669/1671/3646 +f 1670/1672/3647 1671/1673/3648 1672/1674/3649 +f 1672/1674/3649 1669/1671/3650 1670/1672/3647 +f 1673/1675/3651 1670/1672/3647 1674/1676/3652 +f 1673/1675/3651 1674/1676/3652 1675/1677/3653 +f 1674/1676/3652 1670/1672/3647 1669/1671/3650 +f 1676/1678/3654 1677/1679/3655 1673/1675/3651 +f 1673/1675/3651 1677/1679/3655 1670/1672/3647 +f 1668/1670/3656 1671/1673/3648 1676/1678/3654 +f 1677/1679/3655 1676/1678/3654 1678/1680/3657 +f 1668/1670/3656 1669/1671/3650 1679/1681/3656 +f 1671/1673/3648 1668/1670/3656 1679/1681/3656 +f 1669/1671/3650 1672/1674/3649 1679/1681/3656 +f 1671/1673/3648 1678/1680/3657 1676/1678/3654 +f 1671/1673/3648 1670/1672/3647 1678/1680/3657 +f 1680/1682/3658 1681/1683/2943 1682/1684/3659 +f 1669/1671/3646 1656/1658/3644 1674/1676/3660 +f 1674/1676/3660 1656/1658/3644 1655/1657/3661 +f 1682/1684/3659 1681/1683/2943 1683/1685/3662 +f 1682/1684/3659 1683/1685/3662 1655/1657/3661 +f 1655/1657/3661 1683/1685/3662 1674/1676/3660 +f 1684/1686/3663 1680/1682/3664 1682/1684/3665 +f 1684/1686/3666 1682/1684/3667 1658/1660/3668 +f 1658/1660/3668 1682/1684/3667 1655/1657/3669 +f 1685/1687/3670 1686/1688/3671 1684/1686/3672 +f 1657/1659/3673 1673/1675/3674 1658/1660/3675 +f 1658/1660/3675 1673/1675/3674 1675/1677/3676 +f 1658/1660/3675 1675/1677/3676 1684/1686/3672 +f 1684/1686/3672 1675/1677/3676 1685/1687/3670 +f 1673/1675/3674 1657/1659/3673 1676/1678/3677 +f 1676/1678/3677 1657/1659/3673 1666/1668/3678 +f 1675/1677/3679 1674/1676/3679 1683/1685/3679 +f 1675/1677/3680 1683/1685/3681 1685/1687/3682 +f 1685/1687/3682 1683/1685/3681 1681/1683/3683 +f 1681/1683/3684 1680/1682/3685 1685/1687/3686 +f 1685/1687/3686 1680/1682/3685 1686/1688/3687 +f 1686/1688/3688 1680/1682/3664 1684/1686/3663 +f 1676/1678/3689 1666/1668/3690 1668/1670/3691 +f 1668/1670/3691 1666/1668/3690 1660/1662/3692 +f 1667/1669/3693 1671/1673/3694 1661/1663/3695 +f 1661/1663/3695 1671/1673/3694 1679/1681/3696 +f 1661/1663/3697 1679/1681/3697 1664/1666/3697 +f 1664/1666/3698 1679/1681/3698 1672/1674/3698 +f 1664/1666/3699 1672/1674/3699 1662/1664/3699 +f 1662/1664/3700 1672/1674/3700 1671/1673/3700 +f 1662/1664/3701 1671/1673/3701 1667/1669/3701 +f 1663/1665/3702 1678/1680/3703 1670/1672/3704 +f 1663/1665/3702 1670/1672/3704 1654/1656/3705 +f 1654/1656/3706 1670/1672/3706 1659/1661/3706 +f 1659/1661/3707 1670/1672/3707 1677/1679/3707 +f 1659/1661/3708 1677/1679/3708 1665/1667/3708 +f 1665/1667/3709 1677/1679/3710 1663/1665/3711 +f 1663/1665/3711 1677/1679/3710 1678/1680/3712 +f 1687/1689/3713 1688/1690/3714 1689/1691/3715 +f 1690/1692/3716 1687/1689/3713 1689/1691/3715 +f 1691/1693/3717 1692/1694/3717 1693/1695/3717 +f 1692/1694/3718 1694/1696/3718 1693/1695/3718 +f 1694/1696/3719 1695/1697/3719 1693/1695/3719 +f 1695/1697/3720 1691/1693/3720 1693/1695/3720 +f 1696/1698/3721 1697/1699/3722 1698/1700/3723 +f 1697/1699/3722 1699/1701/3724 1698/1700/3723 +f 1700/1702/3725 1698/1700/3723 1699/1701/3724 +f 1700/1702/3726 1696/1698/3726 1698/1700/3726 +f 1701/1703/3727 1702/1704/3728 1703/1705/3729 +f 1704/1706/3730 1705/1707/3731 1706/1708/3732 +f 1706/1708/3732 1705/1707/3731 1702/1704/3728 +f 1706/1708/3732 1702/1704/3728 1701/1703/3727 +f 1703/1705/3729 1707/1709/3733 1708/1710/3734 +f 1709/1711/3735 1710/1712/3736 1701/1703/3727 +f 1703/1705/3729 1709/1711/3735 1701/1703/3727 +f 1709/1711/3735 1703/1705/3729 1708/1710/3734 +f 1711/1713/3737 1704/1706/3730 1706/1708/3732 +f 1712/1714/3738 1713/1715/3739 1707/1709/3733 +f 1713/1715/3739 1708/1710/3734 1707/1709/3733 +f 1704/1706/3730 1711/1713/3737 1712/1714/3738 +f 1711/1713/3737 1710/1712/3736 1712/1714/3738 +f 1710/1712/3736 1709/1711/3735 1713/1715/3739 +f 1710/1712/3736 1713/1715/3739 1712/1714/3738 +f 1707/1709/3740 1703/1705/3741 1714/1716/3742 +f 1714/1716/3742 1703/1705/3741 1715/1717/3743 +f 1716/1718/3744 1717/1719/3745 1718/1720/3746 +f 1719/1721/3747 1720/1722/3748 1721/1723/3749 +f 1719/1721/3747 1721/1723/3749 1722/1724/3750 +f 1721/1723/3749 1720/1722/3748 1717/1719/3745 +f 1717/1719/3745 1720/1722/3748 1718/1720/3746 +f 1723/1725/3751 1724/1726/3752 1719/1721/3747 +f 1714/1716/3753 1725/1727/3754 1723/1725/3751 +f 1717/1719/3745 1716/1718/3744 1726/1728/3755 +f 1724/1726/3752 1723/1725/3751 1727/1729/3756 +f 1714/1716/3753 1715/1717/3757 1726/1728/3755 +f 1720/1722/3748 1719/1721/3747 1724/1726/3752 +f 1726/1728/3755 1715/1717/3757 1717/1719/3745 +f 1714/1716/3753 1726/1728/3755 1725/1727/3754 +f 1725/1727/3754 1718/1720/3746 1723/1725/3751 +f 1718/1720/3746 1727/1729/3756 1723/1725/3751 +f 1725/1727/3754 1716/1718/3744 1718/1720/3746 +f 1703/1705/3758 1717/1719/3758 1715/1717/3758 +f 1717/1719/3759 1703/1705/3759 1721/1723/3759 +f 1721/1723/3760 1703/1705/3761 1702/1704/3762 +f 1702/1704/3762 1728/1730/3763 1721/1723/3760 +f 1729/1731/3764 1728/1730/3763 1702/1704/3762 +f 1730/1732/3765 1729/1731/3765 1702/1704/3765 +f 1730/1732/3766 1702/1704/3766 1705/1707/3766 +f 1731/1733/3767 1732/1734/3768 1730/1732/3769 +f 1704/1706/3770 1719/1721/3771 1705/1707/3772 +f 1705/1707/3772 1719/1721/3771 1722/1724/3773 +f 1705/1707/3772 1722/1724/3773 1730/1732/3769 +f 1730/1732/3769 1722/1724/3773 1731/1733/3767 +f 1719/1721/3771 1704/1706/3770 1723/1725/3774 +f 1723/1725/3774 1704/1706/3770 1712/1714/3775 +f 1722/1724/3776 1721/1723/3777 1728/1730/3778 +f 1722/1724/3776 1728/1730/3778 1731/1733/3779 +f 1728/1730/3780 1729/1731/3781 1731/1733/3782 +f 1731/1733/3782 1729/1731/3781 1732/1734/3783 +f 1732/1734/3784 1729/1731/3784 1730/1732/3784 +f 1723/1725/3785 1712/1714/3786 1714/1716/3787 +f 1714/1716/3787 1712/1714/3786 1707/1709/3788 +f 1708/1710/3789 1725/1727/3789 1726/1728/3789 +f 1708/1710/3790 1726/1728/3790 1709/1711/3790 +f 1709/1711/3791 1726/1728/3791 1716/1718/3791 +f 1709/1711/3792 1716/1718/3792 1713/1715/3792 +f 1713/1715/3793 1716/1718/3793 1725/1727/3793 +f 1713/1715/3794 1725/1727/3794 1708/1710/3794 +f 1710/1712/3795 1727/1729/3795 1718/1720/3795 +f 1710/1712/3796 1718/1720/3796 1701/1703/3796 +f 1701/1703/3797 1718/1720/3797 1720/1722/3797 +f 1701/1703/3798 1720/1722/3798 1706/1708/3798 +f 1706/1708/3799 1720/1722/3799 1724/1726/3799 +f 1706/1708/3800 1724/1726/3800 1711/1713/3800 +f 1711/1713/3801 1724/1726/3802 1727/1729/3803 +f 1711/1713/3801 1727/1729/3803 1710/1712/3804 +f 1733/1735/629 1734/1736/603 1735/1737/629 +f 1736/1738/603 1737/1739/629 1734/1736/603 +f 1737/1739/629 1735/1737/629 1734/1736/603 +f 1738/1740/629 1739/1741/3805 1734/1736/603 +f 1740/1742/3806 1736/1738/603 1734/1736/603 +f 1733/1735/629 1738/1740/629 1734/1736/603 +f 1741/1743/3807 1742/1744/3807 1743/1745/3807 +f 1744/1746/3808 1745/1747/3808 1743/1745/3808 +f 1744/1746/3809 1743/1745/3809 1742/1744/3809 +f 1746/1748/3810 1745/1747/3810 1744/1746/3810 +f 1741/1743/3811 1745/1747/3812 1747/1749/3813 +f 1747/1749/3813 1748/1750/3814 1741/1743/3811 +f 1742/1744/3815 1746/1748/3816 1744/1746/3817 +f 1742/1744/3815 1747/1749/3818 1746/1748/3816 +f 1741/1743/3811 1743/1745/3819 1745/1747/3812 +f 1746/1748/3820 1747/1749/3820 1745/1747/3820 +f 1742/1744/3821 1741/1743/3811 1748/1750/3814 +f 1749/1751/3822 1750/1752/3823 1751/1753/3824 +f 1752/1754/3825 1753/1755/3826 1754/1756/3827 +f 1754/1756/3827 1755/1757/3828 1752/1754/3825 +f 1756/1758/3829 1755/1757/3830 1754/1756/3831 +f 1754/1756/3831 1757/1759/3832 1756/1758/3829 +f 1758/1760/3833 1759/1761/3834 1760/1762/3835 +f 1758/1760/3833 1760/1762/3835 1761/1763/3836 +f 1758/1760/3833 1761/1763/3836 1762/1764/3837 +f 1760/1762/3838 1759/1761/3839 1750/1752/3840 +f 1750/1752/3840 1759/1761/3839 1751/1753/3841 +f 1762/1764/3842 1761/1763/3843 1763/1765/3844 +f 1763/1765/3844 1761/1763/3843 1764/1766/3845 +f 1750/1752/3823 1749/1751/3822 1764/1766/3846 +f 1764/1766/3846 1749/1751/3822 1763/1765/3847 +f 1759/1761/3848 1749/1751/3849 1751/1753/3850 +f 1749/1751/3849 1759/1761/3848 1758/1760/3851 +f 1758/1760/3851 1762/1764/3852 1763/1765/3852 +f 1764/1766/3853 1761/1763/3819 1760/1762/3838 +f 1750/1752/3840 1764/1766/3853 1760/1762/3838 +f 1758/1760/3851 1763/1765/3852 1749/1751/3849 +f 1765/1767/3854 1766/1768/3855 1767/1769/3856 +f 1767/1769/3856 1766/1768/3855 1768/1770/3857 +f 1766/1768/3858 1765/1767/3858 1769/1771/3858 +f 1770/1772/3859 1771/1773/3860 1772/1774/3861 +f 1770/1772/3859 1772/1774/3861 1773/1775/3862 +f 1774/1776/3863 1775/1777/3864 1773/1775/3865 +f 1775/1777/3866 1774/1776/3867 1776/1778/3867 +f 1776/1778/3867 1774/1776/3867 1777/1779/3868 +f 1765/1767/3869 1767/1769/3870 1769/1771/3871 +f 1769/1771/3871 1767/1769/3870 1768/1770/3872 +f 1766/1768/3873 1769/1771/3873 1775/1777/3873 +f 1766/1768/3874 1775/1777/3875 1776/1778/3876 +f 1766/1768/3874 1776/1778/3876 1768/1770/3877 +f 1770/1772/3878 1777/1779/3879 1771/1773/3880 +f 1770/1772/3878 1776/1778/3881 1777/1779/3879 +f 1772/1774/3882 1774/1776/3863 1773/1775/3865 +f 1777/1779/3883 1774/1776/3883 1771/1773/3883 +f 1774/1776/3883 1772/1774/3883 1771/1773/3883 +f 1778/1780/3884 1779/1781/3884 1780/1782/3884 +f 1779/1781/3885 1781/1783/3886 1780/1782/3887 +f 1780/1782/3887 1781/1783/3886 1782/1784/3888 +f 1781/1783/3889 1783/1785/3890 1782/1784/3891 +f 1782/1784/3891 1783/1785/3890 1784/1786/3892 +f 1783/1785/3893 1785/1787/3893 1784/1786/3893 +f 1786/1788/3894 1787/1789/3894 1785/1787/3894 +f 1778/1780/3895 1788/1790/3896 1789/1791/3897 +f 1778/1780/3895 1789/1791/3897 1790/1792/3898 +f 1791/1793/3899 1792/1794/3899 1793/1795/3899 +f 1791/1793/3900 1793/1795/3900 1794/1796/3900 +f 1795/1797/3901 1792/1794/3901 1791/1793/3901 +f 1795/1797/3902 1796/1798/3903 1792/1794/3904 +f 1792/1794/3904 1796/1798/3903 1797/1799/3905 +f 1788/1790/3906 1798/1800/3907 1799/1801/3908 +f 1800/1802/3909 1789/1791/3910 1799/1801/3908 +f 1799/1801/3908 1789/1791/3910 1788/1790/3906 +f 1789/1791/3910 1800/1802/3909 1801/1803/3911 +f 1801/1803/3911 1794/1796/3912 1789/1791/3910 +f 1796/1798/3913 1795/1797/3914 1791/1793/3915 +f 1796/1798/3913 1791/1793/3915 1801/1803/3911 +f 1801/1803/3911 1791/1793/3915 1794/1796/3912 +f 1801/1803/3916 1802/1804/3917 1796/1798/3918 +f 1796/1798/3918 1802/1804/3917 1797/1799/3919 +f 1802/1804/3920 1801/1803/3921 1800/1802/3922 +f 1798/1800/3923 1803/1805/3923 1799/1801/3923 +f 1799/1801/3924 1803/1805/3924 1804/1806/3924 +f 1802/1804/3920 1800/1802/3922 1804/1806/3925 +f 1804/1806/3926 1800/1802/3926 1799/1801/3926 +f 1805/1807/3927 1803/1805/3927 1806/1808/3927 +f 1807/1809/3928 1805/1807/3929 1808/1810/3930 +f 1808/1810/3930 1805/1807/3929 1806/1808/3931 +f 1809/1811/3932 1810/1812/3932 1811/1813/3932 +f 1810/1812/3933 1809/1811/3933 1812/1814/3933 +f 1812/1814/3934 1809/1811/3934 1813/1815/3934 +f 1813/1815/3935 1814/1816/3936 1812/1814/3937 +f 1812/1814/3937 1814/1816/3936 1815/1817/3938 +f 1814/1816/3939 1807/1809/3940 1815/1817/3941 +f 1815/1817/3941 1807/1809/3940 1808/1810/3942 +f 1803/1805/3943 1808/1810/3944 1806/1808/3945 +f 1813/1815/3853 1809/1811/3946 1807/1809/3853 +f 1816/1818/3947 1786/1788/3948 1817/1819/3949 +f 1817/1819/3949 1786/1788/3948 1778/1780/3950 +f 1817/1819/3949 1778/1780/3950 1818/1820/3951 +f 1818/1820/3951 1778/1780/3950 1803/1805/3952 +f 1818/1820/3951 1803/1805/3952 1811/1813/3953 +f 1811/1813/3953 1803/1805/3952 1809/1811/3954 +f 1808/1810/3944 1810/1812/3955 1812/1814/3956 +f 1808/1810/3944 1803/1805/3943 1798/1800/3957 +f 1812/1814/3956 1815/1817/3852 1808/1810/3944 +f 1739/1741/3958 1819/1821/3853 1820/1822/3959 +f 1814/1816/3960 1813/1815/3853 1807/1809/3853 +f 1734/1736/3961 1739/1741/3958 1820/1822/3959 +f 1786/1788/3962 1816/1818/3962 1787/1789/3962 +f 1811/1813/3963 1810/1812/3964 1818/1820/3965 +f 1818/1820/3965 1810/1812/3964 1798/1800/3907 +f 1818/1820/3965 1798/1800/3907 1817/1819/3966 +f 1817/1819/3966 1798/1800/3907 1788/1790/3906 +f 1817/1819/3966 1788/1790/3906 1816/1818/3967 +f 1816/1818/3968 1788/1790/3968 1787/1789/3968 +f 1821/1823/3955 1822/1824/3969 1823/1825/3970 +f 1738/1740/3971 1733/1735/3972 1824/1826/3973 +f 1738/1740/3971 1824/1826/3973 1825/1827/3974 +f 1808/1810/3944 1798/1800/3957 1810/1812/3955 +f 1826/1828/3975 1823/1825/3970 1822/1824/3969 +f 1804/1806/3976 1778/1780/3950 1790/1792/3977 +f 1778/1780/3950 1804/1806/3976 1803/1805/3952 +f 1790/1792/3977 1802/1804/3978 1804/1806/3976 +f 1802/1804/3978 1790/1792/3977 1793/1795/3979 +f 1797/1799/3980 1793/1795/3979 1792/1794/3981 +f 1797/1799/3980 1802/1804/3978 1793/1795/3979 +f 1794/1796/3982 1793/1795/3983 1790/1792/3984 +f 1794/1796/3982 1790/1792/3984 1789/1791/3985 +f 1827/1829/3986 1828/1830/3986 1829/1831/3986 +f 1827/1829/3987 1830/1832/3987 1828/1830/3987 +f 1831/1833/3988 1832/1834/3988 1833/1835/3988 +f 1834/1836/3989 1831/1833/3990 1833/1835/3991 +f 1835/1837/3992 1834/1836/3989 1833/1835/3991 +f 1835/1837/3993 1833/1835/3993 1832/1834/3993 +f 1836/1838/3994 1837/1839/3995 1824/1826/3996 +f 1824/1826/3996 1837/1839/3995 1825/1827/3997 +f 1784/1786/3998 1785/1787/3999 1787/1789/4000 +f 1781/1783/4001 1779/1781/4002 1778/1780/4003 +f 1785/1787/4004 1783/1785/4005 1781/1783/4001 +f 1785/1787/4004 1781/1783/4001 1786/1788/4006 +f 1781/1783/4001 1778/1780/4003 1786/1788/4006 +f 1805/1807/4007 1809/1811/3946 1803/1805/4008 +f 1807/1809/3853 1809/1811/3946 1805/1807/4007 +f 1838/1840/4009 1839/1841/4010 1840/1842/4011 +f 1735/1737/4012 1737/1739/4013 1838/1840/4014 +f 1838/1840/4014 1737/1739/4013 1839/1841/4015 +f 1735/1737/4012 1838/1840/4014 1733/1735/4016 +f 1733/1735/4017 1838/1840/4017 1841/1843/4017 +f 1836/1838/4018 1824/1826/4018 1841/1843/4018 +f 1841/1843/4019 1824/1826/4019 1733/1735/4019 +f 1842/1844/4020 1837/1839/4021 1836/1838/4022 +f 1836/1838/4022 1841/1843/4023 1842/1844/4020 +f 1787/1789/4000 1782/1784/4024 1784/1786/3998 +f 1778/1780/3895 1780/1782/4025 1787/1789/4000 +f 1780/1782/4025 1782/1784/4024 1787/1789/4000 +f 1787/1789/4000 1788/1790/3896 1778/1780/3895 +f 1821/1823/4026 1823/1825/4027 1819/1821/4028 +f 1819/1821/4028 1823/1825/4027 1820/1822/4029 +f 1825/1827/4030 1837/1839/4031 1738/1740/4032 +f 1738/1740/4032 1837/1839/4031 1842/1844/4033 +f 1738/1740/4032 1842/1844/4033 1739/1741/4034 +f 1739/1741/4034 1842/1844/4033 1822/1824/4035 +f 1739/1741/4034 1822/1824/4035 1819/1821/4036 +f 1819/1821/4036 1822/1824/4035 1821/1823/4037 +f 1820/1822/4038 1823/1825/4038 1734/1736/4038 +f 1734/1736/4039 1823/1825/4039 1826/1828/4039 +f 1734/1736/4040 1826/1828/4040 1840/1842/4040 +f 1734/1736/4041 1840/1842/4042 1740/1742/4043 +f 1736/1738/4044 1740/1742/4043 1843/1845/4045 +f 1843/1845/4045 1740/1742/4043 1840/1842/4042 +f 1839/1841/98 1737/1739/98 1736/1738/98 +f 1736/1738/98 1843/1845/98 1839/1841/98 +f 1844/1846/4046 1845/1847/4047 1846/1848/4048 +f 1847/1849/4049 1848/1850/4050 1845/1847/4047 +f 1847/1849/4049 1845/1847/4047 1844/1846/4046 +f 1847/1849/4049 1849/1851/4051 1848/1850/4050 +f 1847/1849/4049 1850/1852/4052 1849/1851/4051 +f 1844/1846/4046 1851/1853/4053 1847/1849/4049 +f 1847/1849/4049 1851/1853/4053 1850/1852/4052 +f 1844/1846/4046 1846/1848/4048 1851/1853/4053 +f 1852/1854/4054 1853/1855/4055 1854/1856/4056 +f 1855/1857/4057 1853/1855/4055 1852/1854/4054 +f 1856/1858/4058 1852/1854/4059 1854/1856/4060 +f 1856/1858/4058 1854/1856/4060 1857/1859/4061 +f 1857/1859/4062 1854/1856/4062 1853/1855/4062 +f 1857/1859/4063 1853/1855/4064 1858/1860/4065 +f 1858/1860/4065 1853/1855/4064 1859/1861/4066 +f 1858/1860/4067 1859/1861/4068 1860/1862/4069 +f 1860/1862/4069 1859/1861/4068 1855/1857/4070 +f 1860/1862/4071 1855/1857/4071 1852/1854/4071 +f 1860/1862/4072 1852/1854/4072 1856/1858/4072 +f 1848/1850/4073 1856/1858/4074 1857/1859/4075 +f 1848/1850/4073 1857/1859/4075 1845/1847/4076 +f 1845/1847/4077 1857/1859/4078 1846/1848/4079 +f 1846/1848/4079 1857/1859/4078 1858/1860/4080 +f 1846/1848/4081 1858/1860/4081 1851/1853/4081 +f 1851/1853/4082 1858/1860/4083 1860/1862/4084 +f 1851/1853/4082 1860/1862/4084 1850/1852/4085 +f 1850/1852/4086 1860/1862/4087 1849/1851/4088 +f 1849/1851/4088 1860/1862/4087 1856/1858/4089 +f 1849/1851/4090 1856/1858/4090 1848/1850/4090 +f 1859/1861/4091 1853/1855/4055 1855/1857/4057 +f 1861/1863/4092 1862/1864/4093 1863/1865/4094 +f 1864/1866/4095 1865/1867/4096 1863/1865/4094 +f 1863/1865/4094 1865/1867/4096 1861/1863/4092 +f 1864/1866/4095 1866/1868/4097 1865/1867/4096 +f 1863/1865/4094 1867/1869/4098 1864/1866/4095 +f 1864/1866/4095 1867/1869/4098 1868/1870/4099 +f 1863/1865/4094 1862/1864/4093 1867/1869/4098 +f 1864/1866/4095 1868/1870/4099 1866/1868/4097 +f 1869/1871/4100 1870/1872/4101 1871/1873/4102 +f 1869/1871/4100 1872/1874/4103 1870/1872/4101 +f 1873/1875/4104 1869/1871/4104 1874/1876/4104 +f 1874/1876/4105 1869/1871/4105 1871/1873/4105 +f 1874/1876/4106 1871/1873/4106 1875/1877/4106 +f 1875/1877/4107 1871/1873/4107 1870/1872/4107 +f 1875/1877/4108 1870/1872/4108 1876/1878/4108 +f 1876/1878/4109 1870/1872/4109 1872/1874/4109 +f 1876/1878/4110 1872/1874/4111 1869/1871/4112 +f 1876/1878/4110 1869/1871/4112 1873/1875/4113 +f 1866/1868/4114 1873/1875/4114 1865/1867/4114 +f 1865/1867/4115 1873/1875/4116 1874/1876/4117 +f 1865/1867/4115 1874/1876/4117 1861/1863/4118 +f 1861/1863/4119 1874/1876/4120 1875/1877/4121 +f 1861/1863/4119 1875/1877/4121 1862/1864/4122 +f 1862/1864/4123 1875/1877/4124 1867/1869/4125 +f 1867/1869/4125 1875/1877/4124 1876/1878/4126 +f 1867/1869/4127 1876/1878/4127 1868/1870/4127 +f 1868/1870/4128 1876/1878/4129 1866/1868/4130 +f 1866/1868/4130 1876/1878/4129 1873/1875/4131 +f 1877/1879/4132 1878/1880/4133 1879/1881/4134 +f 1880/1882/4135 1881/1883/4136 1882/1884/4137 +f 1882/1884/4137 1878/1880/4133 1877/1879/4132 +f 1882/1884/4137 1881/1883/4136 1878/1880/4133 +f 1877/1879/4132 1879/1881/4134 1883/1885/4138 +f 1877/1879/4132 1883/1885/4138 1882/1884/4137 +f 1882/1884/4137 1883/1885/4138 1880/1882/4135 +f 1884/1886/4139 1885/1887/4140 1886/1888/4141 +f 1886/1888/4141 1887/1889/4142 1884/1886/4139 +f 1888/1890/4143 1886/1888/4144 1885/1887/4145 +f 1888/1890/4143 1885/1887/4145 1889/1891/4146 +f 1889/1891/4147 1885/1887/4148 1890/1892/4149 +f 1890/1892/4149 1885/1887/4148 1884/1886/4150 +f 1890/1892/4151 1884/1886/4152 1887/1889/4153 +f 1890/1892/4151 1887/1889/4153 1891/1893/4154 +f 1891/1893/4155 1887/1889/4156 1888/1890/4157 +f 1888/1890/4157 1887/1889/4156 1886/1888/4158 +f 1880/1882/4159 1888/1890/4160 1881/1883/4161 +f 1881/1883/4161 1888/1890/4160 1889/1891/4162 +f 1881/1883/4161 1889/1891/4162 1878/1880/4163 +f 1878/1880/4164 1889/1891/4165 1890/1892/4166 +f 1878/1880/4164 1890/1892/4166 1879/1881/4167 +f 1879/1881/4168 1890/1892/4169 1883/1885/4170 +f 1883/1885/4170 1890/1892/4169 1891/1893/4171 +f 1883/1885/4172 1891/1893/4173 1880/1882/4174 +f 1880/1882/4174 1891/1893/4173 1888/1890/4175 +f 1892/1894/4176 1893/1895/4176 1894/1896/4176 +f 1892/1894/4177 1894/1896/4177 1895/1897/4177 +f 1895/1897/4178 1894/1896/4178 1896/1898/4178 +f 1895/1897/4179 1896/1898/4179 1897/1899/4179 +f 1897/1899/4180 1896/1898/4180 1898/1900/4180 +f 1897/1899/4181 1898/1900/4181 1899/1901/4181 +f 1899/1901/4182 1898/1900/4182 1900/1902/4182 +f 1899/1901/4183 1900/1902/4183 1901/1903/4183 +f 1901/1903/4184 1900/1902/4184 1893/1895/4184 +f 1901/1903/4185 1893/1895/4185 1892/1894/4185 +f 1902/1904/4186 1892/1894/4187 1903/1905/4188 +f 1904/1906/2171 1899/1901/4189 1901/1903/4190 +f 1904/1906/2171 1901/1903/4190 1902/1904/4186 +f 1905/1907/4191 1897/1899/4191 1904/1906/2171 +f 1904/1906/2171 1897/1899/4191 1899/1901/4189 +f 1902/1904/4186 1901/1903/4190 1892/1894/4187 +f 1903/1905/4188 1895/1897/4192 1905/1907/4191 +f 1905/1907/4191 1895/1897/4192 1897/1899/4191 +f 1903/1905/4188 1892/1894/4187 1895/1897/4192 +f 1902/1904/4193 1906/1908/4193 1907/1909/4193 +f 1902/1904/4194 1907/1909/4195 1908/1910/4196 +f 1908/1910/4196 1904/1906/4197 1902/1904/4194 +f 1909/1911/4198 1904/1906/4198 1908/1910/4198 +f 1904/1906/4199 1909/1911/4200 1910/1912/4201 +f 1904/1906/4199 1910/1912/4201 1905/1907/4202 +f 1905/1907/4203 1910/1912/4204 1911/1913/4205 +f 1905/1907/4206 1911/1913/4207 1912/1914/4208 +f 1912/1914/4208 1903/1905/4209 1905/1907/4206 +f 1913/1915/4210 1903/1905/4210 1912/1914/4210 +f 1903/1905/4211 1913/1915/4212 1902/1904/4213 +f 1902/1904/4213 1913/1915/4212 1906/1908/4214 +f 1910/1912/4204 1914/1916/4215 1911/1913/4205 +f 1909/1911/4216 1914/1916/4216 1910/1912/4216 +f 1906/1908/4217 1915/1917/4217 1907/1909/4217 +f 1909/1911/4218 1908/1910/4219 1914/1916/4215 +f 1907/1909/4220 1915/1917/4221 1908/1910/4219 +f 1911/1913/4205 1916/1918/4222 1912/1914/4223 +f 1912/1914/4223 1916/1918/4222 1913/1915/4224 +f 1913/1915/4224 1916/1918/4222 1906/1908/4225 +f 1908/1910/4219 1915/1917/4221 1914/1916/4215 +f 1911/1913/4205 1914/1916/4215 1916/1918/4222 +f 1906/1908/4225 1916/1918/4222 1915/1917/4226 +f 1914/1916/4215 1915/1917/4221 1916/1918/4222 +f 1917/1919/4227 1918/1920/4227 1919/1921/4227 +f 1917/1919/4228 1919/1921/4228 1920/1922/4228 +f 1920/1922/4229 1919/1921/4229 1921/1923/4229 +f 1920/1922/4230 1921/1923/4230 1922/1924/4230 +f 1922/1924/4231 1921/1923/4231 1923/1925/4231 +f 1922/1924/4232 1923/1925/4232 1924/1926/4232 +f 1924/1926/4233 1923/1925/4233 1925/1927/4233 +f 1924/1926/4234 1925/1927/4234 1926/1928/4234 +f 1926/1928/4235 1925/1927/4235 1918/1920/4235 +f 1926/1928/4236 1918/1920/4236 1917/1919/4236 +f 1927/1929/4237 1926/1928/4187 1917/1919/4238 +f 1927/1929/4237 1917/1919/4238 1928/1930/4239 +f 1929/1931/4240 1922/1924/4241 1924/1926/4242 +f 1929/1931/4240 1924/1926/4242 1930/1932/4243 +f 1924/1926/4242 1926/1928/4187 1930/1932/4243 +f 1930/1932/4243 1926/1928/4187 1927/1929/4237 +f 1929/1931/4240 1920/1922/4244 1922/1924/4241 +f 1928/1930/4239 1920/1922/4244 1929/1931/4240 +f 1928/1930/4239 1917/1919/4238 1920/1922/4244 +f 1927/1929/4245 1931/1933/4245 1932/1934/4245 +f 1927/1929/4246 1932/1934/4247 1930/1932/4248 +f 1933/1935/4249 1930/1932/4248 1932/1934/4247 +f 1934/1936/4250 1930/1932/4251 1933/1935/4252 +f 1930/1932/4253 1934/1936/4254 1929/1931/4255 +f 1934/1936/4254 1935/1937/4256 1929/1931/4255 +f 1929/1931/4257 1935/1937/4258 1936/1938/4259 +f 1937/1939/4260 1928/1930/4261 1929/1931/4262 +f 1937/1939/4260 1929/1931/4262 1936/1938/4263 +f 1928/1930/4264 1937/1939/4265 1931/1933/4266 +f 1928/1930/4264 1931/1933/4266 1927/1929/4267 +f 1936/1938/4259 1935/1937/4258 1938/1940/4268 +f 1936/1938/4269 1939/1941/4270 1937/1939/4271 +f 1933/1935/4252 1940/1942/4272 1934/1936/4250 +f 1934/1936/4250 1940/1942/4272 1935/1937/4273 +f 1933/1935/4252 1941/1943/4274 1940/1942/4272 +f 1936/1938/4269 1938/1940/4275 1939/1941/4270 +f 1937/1939/4276 1939/1941/4277 1931/1933/4278 +f 1931/1933/4278 1941/1943/4279 1932/1934/4280 +f 1932/1934/4281 1941/1943/4274 1933/1935/4252 +f 1940/1942/4282 1938/1940/4268 1935/1937/4258 +f 1931/1933/4278 1939/1941/4277 1941/1943/4279 +f 1939/1941/4277 1938/1940/4268 1941/1943/4279 +f 1940/1942/4282 1941/1943/4279 1938/1940/4268 +f 1942/1944/4283 1943/1945/4284 1944/1946/4285 +f 1945/1947/4286 1946/1948/4287 1947/1949/4288 +f 1948/1950/4289 1946/1948/4287 1945/1947/4286 +f 1948/1950/4289 1945/1947/4286 1949/1951/4290 +f 1950/1952/4291 1951/1953/4292 1952/1954/4293 +f 1953/1955/4294 1954/1956/4295 1955/1957/4296 +f 1953/1955/4294 1948/1950/4289 1949/1951/4290 +f 1949/1951/4290 1954/1956/4295 1953/1955/4294 +f 1949/1951/4290 1952/1954/4293 1951/1953/4292 +f 1954/1956/4295 1949/1951/4290 1951/1953/4292 +f 1956/1958/4297 1957/1959/4298 1954/1956/4295 +f 1956/1958/4297 1954/1956/4295 1958/1960/4299 +f 1958/1960/4299 1959/1961/4300 1956/1958/4297 +f 1954/1956/4295 1951/1953/4292 1958/1960/4299 +f 1960/1962/4301 1959/1961/4300 1958/1960/4299 +f 1961/1963/4302 1954/1956/4295 1957/1959/4298 +f 1962/1964/4303 1963/1965/4304 1964/1966/4305 +f 1962/1964/4303 1964/1966/4305 1965/1967/4306 +f 1959/1961/4300 1960/1962/4301 1966/1968/4307 +f 1962/1964/4303 1965/1967/4306 1967/1969/4308 +f 1918/1920/4303 1925/1927/4309 1923/1925/4306 +f 1918/1920/4303 1923/1925/4306 1921/1923/4306 +f 1919/1921/4303 1918/1920/4303 1921/1923/4306 +f 1894/1896/4310 1898/1900/4310 1896/1898/4311 +f 1898/1900/4310 1894/1896/4310 1893/1895/4303 +f 1900/1902/4303 1898/1900/4310 1893/1895/4303 +f 1968/1970/4303 1969/1971/4303 1970/1972/4303 +f 1969/1971/4303 1971/1973/4303 1970/1972/4303 +f 1969/1971/4303 1972/1974/4303 1971/1973/4303 +f 1972/1974/4303 1973/1975/4303 1971/1973/4303 +f 1974/1976/4312 1962/1964/4312 1967/1969/4312 +f 1974/1976/4313 1967/1969/4313 1975/1977/4313 +f 1975/1977/4314 1967/1969/4315 1976/1978/4316 +f 1976/1978/4316 1967/1969/4315 1965/1967/4317 +f 1976/1978/4318 1965/1967/4319 1964/1966/4320 +f 1976/1978/4318 1964/1966/4320 1977/1979/4321 +f 1977/1979/4322 1964/1966/4323 1963/1965/4324 +f 1977/1979/4322 1963/1965/4324 1978/1980/4325 +f 1978/1980/4326 1963/1965/4326 1979/1981/4326 +f 1979/1981/4327 1963/1965/4327 1962/1964/4327 +f 1979/1981/4328 1962/1964/4328 1974/1976/4328 +f 1980/1982/4329 1979/1981/4188 1974/1976/4330 +f 1980/1982/4329 1974/1976/4330 1981/1983/4331 +f 1982/1984/4332 1977/1979/4330 1978/1980/4244 +f 1983/1985/4333 1976/1978/4334 1977/1979/4330 +f 1983/1985/4333 1977/1979/4330 1982/1984/4332 +f 1978/1980/4188 1979/1981/4188 1980/1982/4329 +f 1975/1977/4334 1976/1978/4334 1983/1985/4333 +f 1981/1983/4331 1974/1976/4330 1975/1977/4335 +f 1980/1982/4336 1984/1986/4337 1978/1980/4338 +f 1985/1987/4339 1978/1980/4338 1984/1986/4337 +f 1985/1987/4340 1982/1984/4340 1978/1980/4340 +f 1982/1984/4341 1985/1987/4341 1986/1988/4341 +f 1987/1989/4342 1982/1984/4343 1986/1988/4344 +f 1982/1984/4343 1987/1989/4342 1983/1985/4345 +f 1983/1985/4346 1987/1989/4346 1988/1990/4346 +f 1983/1985/4347 1988/1990/4348 1975/1977/4349 +f 1989/1991/4350 1975/1977/4349 1988/1990/4348 +f 1989/1991/4351 1981/1983/4351 1975/1977/4351 +f 1990/1992/4352 1981/1983/4353 1989/1991/4354 +f 1981/1983/4355 1990/1992/4356 1980/1982/4357 +f 1980/1982/4357 1990/1992/4356 1984/1986/4358 +f 1989/1991/4359 1988/1990/4359 1991/1993/4359 +f 1989/1991/4354 1992/1994/4360 1990/1992/4352 +f 1990/1992/4356 1992/1994/4361 1984/1986/4358 +f 1989/1991/4354 1991/1993/4362 1992/1994/4360 +f 1984/1986/4358 1943/1945/4363 1985/1987/4364 +f 1986/1988/4365 1985/1987/4366 1993/1995/4367 +f 1986/1988/4344 1993/1995/4368 1987/1989/4342 +f 1992/1994/4361 1944/1946/4369 1984/1986/4358 +f 1984/1986/4358 1944/1946/4369 1943/1945/4363 +f 1987/1989/4370 1993/1995/4371 1988/1990/4372 +f 1988/1990/4372 1942/1944/4283 1991/1993/4373 +f 1985/1987/4366 1943/1945/4374 1993/1995/4367 +f 1993/1995/4371 1942/1944/4283 1988/1990/4372 +f 1992/1994/4375 1991/1993/4373 1944/1946/4285 +f 1991/1993/4373 1942/1944/4283 1944/1946/4285 +f 1943/1945/4284 1942/1944/4283 1993/1995/4376 +f 1994/1996/4377 1995/1997/4378 1969/1971/4379 +f 1969/1971/4379 1995/1997/4378 1972/1974/4380 +f 1971/1973/4381 1973/1975/4382 1996/1998/4383 +f 1996/1998/4383 1973/1975/4382 1997/1999/4384 +f 1973/1975/4385 1972/1974/4386 1997/1999/4387 +f 1997/1999/4387 1972/1974/4386 1995/1997/4388 +f 1998/2000/4389 1995/1997/4390 1999/2001/4391 +f 1999/2001/4391 1995/1997/4390 1994/1996/4392 +f 2000/2002/4329 1997/1999/4393 1998/2000/4389 +f 1998/2000/4389 1997/1999/4393 1995/1997/4390 +f 2000/2002/4329 2001/2003/4191 1996/1998/4393 +f 1996/1998/4393 2001/2003/4191 1994/1996/4392 +f 1994/1996/4392 2001/2003/4191 1999/2001/4391 +f 1996/1998/4393 1997/1999/4393 2000/2002/4329 +f 2001/2003/4394 2000/2002/4395 2002/2004/4396 +f 2001/2003/4394 2002/2004/4396 2003/2005/4397 +f 2004/2006/4398 2005/2007/4399 1998/2000/4400 +f 2004/2006/4398 1998/2000/4400 1999/2001/4401 +f 2003/2005/4402 2002/2004/4403 2006/2008/4404 +f 2006/2008/4404 2002/2004/4403 2007/2009/4405 +f 2006/2008/4404 2007/2009/4405 2005/2007/4406 +f 2006/2008/4404 2005/2007/4406 2004/2006/4407 +f 2003/2005/4408 2006/2008/4409 2001/2003/4408 +f 2001/2003/4408 2006/2008/4409 1999/2001/4410 +f 1999/2001/4410 2006/2008/4409 2004/2006/4411 +f 1998/2000/4412 2005/2007/4413 2007/2009/4414 +f 1998/2000/4412 2007/2009/4414 2000/2002/4412 +f 2000/2002/4412 2007/2009/4414 2002/2004/4412 +f 2008/2010/4415 1994/1996/4377 1968/1970/4416 +f 1968/1970/4416 1994/1996/4377 1969/1971/4379 +f 1968/1970/4417 1970/1972/4418 2008/2010/4419 +f 2008/2010/4419 1970/1972/4418 2009/2011/4420 +f 1970/1972/4421 1971/1973/4381 2009/2011/4422 +f 2009/2011/4422 1971/1973/4381 1996/1998/4383 +f 2010/2012/4423 1994/1996/4392 2011/2013/4424 +f 2011/2013/4424 1994/1996/4392 2008/2010/4425 +f 1996/1998/4393 2010/2012/4423 2012/2014/4426 +f 2013/2015/4191 2009/2011/2172 2012/2014/4426 +f 2012/2014/4426 2009/2011/2172 1996/1998/4393 +f 2011/2013/4424 2008/2010/4425 2013/2015/4191 +f 2013/2015/4191 2008/2010/4425 2009/2011/2172 +f 2010/2012/4423 1996/1998/4393 1994/1996/4392 +f 2013/2015/4427 2012/2014/4428 2014/2016/4429 +f 2013/2015/4427 2014/2016/4429 2015/2017/4430 +f 2016/2018/4431 2017/2019/4432 2010/2012/4433 +f 2016/2018/4431 2010/2012/4433 2011/2013/4434 +f 2015/2017/4435 2014/2016/4436 2018/2020/4437 +f 2018/2020/4437 2014/2016/4436 2019/2021/4438 +f 2018/2020/4437 2019/2021/4438 2016/2018/4439 +f 2016/2018/4439 2019/2021/4438 2017/2019/4440 +f 2013/2015/4408 2015/2017/4408 2018/2020/4410 +f 2013/2015/4408 2018/2020/4410 2011/2013/4410 +f 2018/2020/4410 2016/2018/4410 2011/2013/4410 +f 2010/2012/4414 2019/2021/4441 2012/2014/4412 +f 2012/2014/4412 2019/2021/4441 2014/2016/4412 +f 2010/2012/4414 2017/2019/4442 2019/2021/4441 +f 2020/2022/4443 2021/2023/4444 2022/2024/4445 +f 2023/2025/4446 2021/2023/4444 2024/2026/4447 +f 2024/2026/4447 2021/2023/4444 2020/2022/4443 +f 2024/2026/4447 2025/2027/4448 2023/2025/4446 +f 2024/2026/4447 2026/2028/4449 2025/2027/4448 +f 2022/2024/4445 2026/2028/4449 2020/2022/4443 +f 2020/2022/4443 2026/2028/4449 2024/2026/4447 +f 2027/2029/4450 2028/2030/4451 2029/2031/4452 +f 2027/2029/4450 2029/2031/4452 2030/2032/4453 +f 2031/2033/4454 2029/2031/4455 2032/2034/4456 +f 2032/2034/4456 2029/2031/4455 2028/2030/4457 +f 2032/2034/4458 2028/2030/4459 2033/2035/4460 +f 2033/2035/4460 2028/2030/4459 2027/2029/4461 +f 2033/2035/4462 2027/2029/4462 2034/2036/4462 +f 2034/2036/4463 2027/2029/4463 2030/2032/4463 +f 2034/2036/4464 2030/2032/4465 2031/2033/4466 +f 2031/2033/4466 2030/2032/4465 2029/2031/4467 +f 2023/2025/4468 2031/2033/4469 2032/2034/4470 +f 2023/2025/4468 2032/2034/4470 2021/2023/4471 +f 2021/2023/4472 2032/2034/4472 2033/2035/4472 +f 2021/2023/4473 2033/2035/4473 2022/2024/4473 +f 2022/2024/4474 2033/2035/4475 2034/2036/4476 +f 2022/2024/4474 2034/2036/4476 2026/2028/4477 +f 2026/2028/4478 2034/2036/4479 2025/2027/4480 +f 2025/2027/4480 2034/2036/4479 2031/2033/4481 +f 2025/2027/4482 2031/2033/4482 2023/2025/4482 +f 2035/2037/4483 2036/2038/4484 1959/1961/4485 +f 2035/2037/4483 1959/1961/4485 2037/2039/4486 +f 1966/1968/4487 2038/2040/4488 1959/1961/4489 +f 1959/1961/4489 2038/2040/4488 2037/2039/4490 +f 2039/2041/4491 1955/1957/4492 1954/1956/4493 +f 2039/2041/4491 1954/1956/4493 2040/2042/4494 +f 2040/2042/4494 1954/1956/4493 1961/1963/4495 +f 2040/2042/4494 1961/1963/4495 2035/2037/4496 +f 2041/2043/4497 1945/1947/4498 2042/2044/4499 +f 2042/2044/4499 1945/1947/4498 1947/1949/4500 +f 2043/2045/4501 2044/2046/4502 2041/2043/4503 +f 2041/2043/4503 2044/2046/4502 1945/1947/4504 +f 2045/2047/4505 2046/2048/4505 2047/2049/4505 +f 2047/2049/4506 2046/2048/4506 1951/1953/4506 +f 2047/2049/4507 1951/1953/4508 2048/2050/4509 +f 2048/2050/4509 1951/1953/4508 1950/1952/4510 +f 2049/2051/4511 2044/2046/4512 2050/2052/4513 +f 2050/2052/4514 2044/2046/4515 1950/1952/4516 +f 2050/2052/4514 1950/1952/4516 2051/2053/4517 +f 2051/2053/4518 1950/1952/4518 1952/1954/4518 +f 2051/2053/4519 1952/1954/4519 2052/2054/4519 +f 2052/2054/4520 1952/1954/4520 1949/1951/4520 +f 2052/2054/4521 1949/1951/4521 2053/2055/4521 +f 2053/2055/4522 1949/1951/4523 1945/1947/4524 +f 2053/2055/4522 1945/1947/4524 2049/2051/4525 +f 2049/2051/4511 1945/1947/4526 2044/2046/4512 +f 2054/2056/4527 1947/1949/4528 1946/1948/4529 +f 2054/2056/4527 1946/1948/4529 2055/2057/4530 +f 2055/2057/4531 1946/1948/4531 1948/1950/4531 +f 2055/2057/4532 1948/1950/4533 2056/2058/4534 +f 2056/2058/4534 1948/1950/4533 1953/1955/4535 +f 2056/2058/4536 1953/1955/4537 2057/2059/4538 +f 2057/2059/4538 1953/1955/4537 1955/1957/4539 +f 2057/2059/4540 1955/1957/4541 1947/1949/4542 +f 2057/2059/4540 1947/1949/4542 2054/2056/4543 +f 2058/2060/4544 2036/2038/4545 2059/2061/4546 +f 2060/2062/4547 1956/1958/4547 1959/1961/4547 +f 2060/2062/4548 1959/1961/4548 2058/2060/4548 +f 2058/2060/4544 1959/1961/4549 2036/2038/4545 +f 2061/2063/4550 1957/1959/4551 1956/1958/4552 +f 2061/2063/4550 1956/1958/4552 2060/2062/4553 +f 2059/2061/4546 2036/2038/4545 1961/1963/4554 +f 2059/2061/4555 1961/1963/4556 2061/2063/4557 +f 2061/2063/4557 1961/1963/4556 1957/1959/4558 +f 2062/2064/4559 1966/1968/4560 1960/1962/4561 +f 2062/2064/4559 1960/1962/4561 2063/2065/4562 +f 2064/2066/4563 1951/1953/4564 2046/2048/4565 +f 2064/2066/4563 2046/2048/4565 1966/1968/4566 +f 2064/2066/4563 1966/1968/4566 2062/2064/4567 +f 2065/2067/4568 1958/1960/4568 1951/1953/4568 +f 2065/2067/4569 1951/1953/4569 2064/2066/4569 +f 2063/2065/4570 1960/1962/4571 2066/2068/4572 +f 2066/2068/4572 1960/1962/4571 1958/1960/4573 +f 2066/2068/4574 1958/1960/4574 2065/2067/4574 +f 2046/2048/4575 2045/2047/4576 2038/2040/4577 +f 2046/2048/4575 2038/2040/4577 1966/1968/4578 +f 2044/2046/4579 2043/2045/4579 1950/1952/4579 +f 1950/1952/4580 2043/2045/4580 2048/2050/4580 +f 2036/2038/4581 2035/2037/4581 1961/1963/4581 +f 1955/1957/4582 2039/2041/4583 1947/1949/4584 +f 1947/1949/4584 2039/2041/4583 2042/2044/4585 +f 2067/2069/4586 2068/2070/4587 2069/2071/4588 +f 2069/2071/4588 2068/2070/4587 2070/2072/4589 +f 2069/2071/4590 2070/2072/4591 2071/2073/4592 +f 2071/2073/4592 2070/2072/4591 2072/2074/4593 +f 2071/2073/4594 2072/2074/4595 2067/2069/4596 +f 2067/2069/4596 2072/2074/4595 2068/2070/4597 +f 2073/2075/4598 2074/2076/4599 2072/2074/4600 +f 2072/2074/4600 2074/2076/4599 2068/2070/4601 +f 2068/2070/4601 2074/2076/4599 2075/2077/4602 +f 2072/2074/4600 2076/2078/4603 2073/2075/4598 +f 2070/2072/4604 2076/2078/4603 2072/2074/4600 +f 2070/2072/4604 2077/2079/4605 2076/2078/4603 +f 2070/2072/4604 2075/2077/4602 2077/2079/4605 +f 2068/2070/4601 2075/2077/4602 2070/2072/4604 +f 2078/2080/4606 2079/2081/4607 2080/2082/4608 +f 2081/2083/4609 2077/2079/4605 2082/2084/4610 +f 2073/2075/4611 2083/2085/4611 2074/2076/4611 +f 2084/2086/4612 2083/2085/4613 2073/2075/4614 +f 2073/2075/4614 2078/2080/4615 2084/2086/4612 +f 2084/2086/4612 2078/2080/4615 2080/2082/4616 +f 2073/2075/4598 2076/2078/4603 2078/2080/4606 +f 2076/2078/4603 2079/2081/4607 2078/2080/4606 +f 2076/2078/4603 2081/2083/4609 2079/2081/4607 +f 2076/2078/4603 2077/2079/4605 2081/2083/4609 +f 2085/2087/4617 2082/2084/4618 2077/2079/4619 +f 2086/2088/4620 2085/2087/4617 2077/2079/4619 +f 2077/2079/4605 2075/2077/4602 2086/2088/4621 +f 2086/2088/4621 2075/2077/4602 2087/2089/4622 +f 2087/2089/4622 2075/2077/4602 2088/2090/4623 +f 2074/2076/4624 2088/2090/4623 2075/2077/4602 +f 2089/2091/4625 2088/2090/4626 2074/2076/4627 +f 2083/2085/4628 2089/2091/4625 2074/2076/4627 +f 2090/2092/4629 2083/2085/4613 2084/2086/4612 +f 2079/2081/4630 2091/2093/4630 2080/2082/4630 +f 2081/2083/4609 2091/2093/4631 2079/2081/4607 +f 2082/2084/4632 2091/2093/4631 2081/2083/4609 +f 2091/2093/4633 2082/2084/4633 2085/2087/4633 +f 2085/2087/4634 2086/2088/4634 2092/2094/4634 +f 2092/2094/4635 2086/2088/4635 2087/2089/4635 +f 2088/2090/4623 2092/2094/4636 2087/2089/4622 +f 2088/2090/4637 2089/2091/4637 2092/2094/4637 +f 2090/2092/4638 2089/2091/4625 2083/2085/4628 +f 2093/2095/4639 2091/2093/4640 2094/2096/4641 +f 2084/2086/4642 2080/2082/4643 2093/2095/4639 +f 2093/2095/4639 2080/2082/4643 2091/2093/4640 +f 2095/2097/4644 2092/2094/4645 2089/2091/4646 +f 2096/2098/4647 2090/2092/4648 2084/2086/4642 +f 2096/2098/4647 2084/2086/4642 2093/2095/4639 +f 2096/2098/4647 2089/2091/4646 2090/2092/4648 +f 2095/2097/4644 2089/2091/4646 2096/2098/4647 +f 2095/2097/4644 2085/2087/4649 2092/2094/4645 +f 2094/2096/4641 2085/2087/4649 2095/2097/4644 +f 2094/2096/4641 2091/2093/4640 2085/2087/4649 +f 2096/2098/4650 2097/2099/4650 2095/2097/4650 +f 2095/2097/4651 2097/2099/4651 2098/2100/4651 +f 2095/2097/4652 2098/2100/4652 2094/2096/4652 +f 2094/2096/4653 2098/2100/4653 2099/2101/4653 +f 2094/2096/4654 2099/2101/4654 2093/2095/4654 +f 2093/2095/4655 2099/2101/4655 2100/2102/4655 +f 2093/2095/4656 2100/2102/4656 2096/2098/4656 +f 2096/2098/4657 2100/2102/4657 2097/2099/4657 +f 2101/2103/4658 2102/2104/4659 2071/2073/4660 +f 2067/2069/4661 2103/2105/4662 2071/2073/4660 +f 2071/2073/4660 2103/2105/4662 2101/2103/4658 +f 2067/2069/4661 2104/2106/4663 2103/2105/4662 +f 2069/2071/4664 2104/2106/4663 2067/2069/4661 +f 2105/2107/4665 2069/2071/4664 2071/2073/4660 +f 2071/2073/4660 2102/2104/4659 2105/2107/4665 +f 2104/2106/4663 2069/2071/4664 2105/2107/4665 +f 2103/2105/4666 2106/2108/4667 2107/2109/4668 +f 2106/2108/4667 2103/2105/4666 2108/2110/4669 +f 2108/2110/4669 2103/2105/4666 2104/2106/4670 +f 2109/2111/4671 2108/2110/4669 2104/2106/4670 +f 2110/2112/4672 2109/2111/4671 2104/2106/4670 +f 2109/2111/4671 2110/2112/4672 2111/2113/4673 +f 2104/2106/4663 2105/2107/4665 2110/2112/4674 +f 2110/2112/4672 2112/2114/4675 2111/2113/4673 +f 2105/2107/4665 2112/2114/4675 2110/2112/4674 +f 2112/2114/4675 2105/2107/4665 2113/2115/4676 +f 2112/2114/4675 2113/2115/4676 2114/2116/4677 +f 2115/2117/4678 2113/2115/4679 2105/2107/4665 +f 2102/2104/4659 2115/2117/4678 2105/2107/4665 +f 2102/2104/4680 2116/2118/4681 2115/2117/4682 +f 2117/2119/4683 2116/2118/4681 2118/2120/4684 +f 2118/2120/4684 2116/2118/4681 2102/2104/4680 +f 2118/2120/4685 2102/2104/4686 2101/2103/4658 +f 2119/2121/4687 2118/2120/4685 2101/2103/4658 +f 2103/2105/4662 2119/2121/4687 2101/2103/4658 +f 2103/2105/4662 2107/2109/4688 2119/2121/4687 +f 2106/2108/4689 2108/2110/4689 2109/2111/4689 +f 2112/2114/4675 2114/2116/4677 2111/2113/4673 +f 2113/2115/4676 2120/2122/4690 2114/2116/4677 +f 2113/2115/4691 2115/2117/4691 2120/2122/4691 +f 2120/2122/4692 2115/2117/4692 2116/2118/4692 +f 2119/2121/4693 2121/2123/4694 2118/2120/4695 +f 2118/2120/4695 2121/2123/4694 2117/2119/4696 +f 2121/2123/4694 2119/2121/4693 2107/2109/4697 +f 2121/2123/4698 2107/2109/4698 2106/2108/4698 +f 2097/2099/4699 2109/2111/4700 2098/2100/4701 +f 2097/2099/4699 2121/2123/4702 2106/2108/4703 +f 2100/2102/4704 2117/2119/4705 2121/2123/4702 +f 2100/2102/4704 2121/2123/4702 2097/2099/4699 +f 2099/2101/4706 2120/2122/4707 2116/2118/4708 +f 2109/2111/4700 2111/2113/4709 2098/2100/4701 +f 2098/2100/4701 2120/2122/4707 2099/2101/4706 +f 2098/2100/4701 2114/2116/4710 2120/2122/4707 +f 2099/2101/4706 2116/2118/4708 2100/2102/4704 +f 2100/2102/4704 2116/2118/4708 2117/2119/4705 +f 2098/2100/4701 2111/2113/4709 2114/2116/4710 +f 2097/2099/4699 2106/2108/4703 2109/2111/4700 +f 2122/2124/4711 2123/2125/4712 2124/2126/4713 +f 2125/2127/4714 2126/2128/4715 2127/2129/4716 +f 2128/2130/4717 2125/2127/4714 2127/2129/4716 +f 2129/2131/4718 2126/2128/4718 2125/2127/4718 +f 2129/2131/4719 2125/2127/4719 2130/2132/4719 +f 2130/2132/4720 2125/2127/4720 2128/2130/4720 +f 2130/2132/4721 2128/2130/4722 2131/2133/4723 +f 2131/2133/4723 2128/2130/4722 2127/2129/4724 +f 2131/2133/4725 2127/2129/4726 2126/2128/4727 +f 2131/2133/4725 2126/2128/4727 2129/2131/4728 +f 2129/2131/4729 2132/2134/4730 2131/2133/4731 +f 2129/2131/4729 2133/2135/4732 2132/2134/4730 +f 2131/2133/4731 2134/2136/4733 2135/2137/4734 +f 2132/2134/4730 2134/2136/4733 2131/2133/4731 +f 2130/2132/4735 2136/2138/4736 2129/2131/4729 +f 2129/2131/4729 2136/2138/4736 2133/2135/4732 +f 2131/2133/4731 2135/2137/4734 2137/2139/4737 +f 2131/2133/4731 2137/2139/4737 2130/2132/4735 +f 2130/2132/4735 2138/2140/4738 2136/2138/4736 +f 2130/2132/4735 2137/2139/4737 2138/2140/4738 +f 2124/2126/4739 2123/2125/4740 2137/2139/4741 +f 2138/2140/4742 2137/2139/4741 2123/2125/4740 +f 2123/2125/4743 2122/2124/4744 2138/2140/4745 +f 2122/2124/4744 2136/2138/4746 2138/2140/4745 +f 2133/2135/4747 2136/2138/4748 2122/2124/4711 +f 2122/2124/4711 2139/2141/4749 2133/2135/4747 +f 2132/2134/4750 2133/2135/4750 2139/2141/4750 +f 2122/2124/4711 2140/2142/4751 2139/2141/4749 +f 2139/2141/4749 2140/2142/4751 2134/2136/4752 +f 2139/2141/4749 2134/2136/4752 2132/2134/4753 +f 2134/2136/4752 2140/2142/4751 2141/2143/4754 +f 2135/2137/4755 2134/2136/4752 2141/2143/4754 +f 2141/2143/4754 2142/2144/4756 2135/2137/4755 +f 2137/2139/4741 2135/2137/4757 2142/2144/4758 +f 2124/2126/4739 2137/2139/4741 2142/2144/4758 +f 2142/2144/4759 2141/2143/4760 2124/2126/4713 +f 2124/2126/4713 2141/2143/4760 2140/2142/4751 +f 2124/2126/4713 2140/2142/4751 2122/2124/4711 +f 2143/2145/4761 2144/2146/4761 2145/2147/4762 +f 2146/2148/4763 2144/2146/4761 2143/2145/4761 +f 2147/2149/4764 2146/2148/4764 2148/2150/4764 +f 2148/2150/4765 2146/2148/4765 2143/2145/4765 +f 2148/2150/4766 2143/2145/4766 2149/2151/4766 +f 2149/2151/4767 2143/2145/4767 2145/2147/4767 +f 2149/2151/4768 2145/2147/4768 2150/2152/4768 +f 2150/2152/4769 2145/2147/4769 2144/2146/4769 +f 2150/2152/4770 2144/2146/4770 2147/2149/4770 +f 2147/2149/4771 2144/2146/4771 2146/2148/4771 +f 2150/2152/4772 2151/2153/4773 2149/2151/4774 +f 2148/2150/4775 2152/2154/4776 2147/2149/4777 +f 2147/2149/4777 2152/2154/4776 2153/2155/4778 +f 2147/2149/4777 2154/2156/4779 2150/2152/4772 +f 2147/2149/4777 2153/2155/4778 2154/2156/4779 +f 2148/2150/4775 2155/2157/4780 2152/2154/4776 +f 2150/2152/4772 2156/2158/4781 2151/2153/4773 +f 2150/2152/4772 2154/2156/4779 2156/2158/4781 +f 2149/2151/4774 2157/2159/4782 2158/2160/4783 +f 2149/2151/4774 2158/2160/4783 2155/2157/4780 +f 2149/2151/4774 2155/2157/4780 2148/2150/4775 +f 2149/2151/4774 2151/2153/4773 2157/2159/4782 +f 2159/2161/4784 2154/2156/4784 2153/2155/4784 +f 2155/2157/4785 2158/2160/4786 2160/2162/4787 +f 2161/2163/4788 2157/2159/4789 2162/2164/4790 +f 2161/2163/4788 2160/2162/4791 2157/2159/4789 +f 2158/2160/4792 2157/2159/4789 2160/2162/4791 +f 2163/2165/4793 2160/2162/4794 2161/2163/4795 +f 2163/2165/4796 2155/2157/4785 2160/2162/4787 +f 2155/2157/4785 2163/2165/4796 2152/2154/4797 +f 2163/2165/4796 2164/2166/4798 2152/2154/4797 +f 2152/2154/4797 2164/2166/4798 2153/2155/4799 +f 2164/2166/4798 2159/2161/4800 2153/2155/4799 +f 2164/2166/4798 2165/2167/4801 2159/2161/4800 +f 2165/2167/4801 2154/2156/4802 2159/2161/4800 +f 2162/2164/4790 2154/2156/4802 2165/2167/4801 +f 2162/2164/4790 2156/2158/4803 2154/2156/4802 +f 2151/2153/4804 2156/2158/4803 2162/2164/4790 +f 2157/2159/4789 2151/2153/4804 2162/2164/4790 +f 2164/2166/4805 2163/2165/4793 2165/2167/4806 +f 2162/2164/4807 2165/2167/4806 2161/2163/4795 +f 2161/2163/4795 2165/2167/4806 2163/2165/4793 +f 2166/2168/4808 2167/2169/4809 2168/2170/4810 +f 2166/2168/4808 2168/2170/4810 2169/2171/4811 +f 2170/2172/4812 2167/2169/4812 2171/2173/4812 +f 2171/2173/4813 2167/2169/4813 2166/2168/4813 +f 2171/2173/4814 2166/2168/4814 2172/2174/4814 +f 2172/2174/4815 2166/2168/4815 2169/2171/4815 +f 2172/2174/4816 2169/2171/4816 2173/2175/4816 +f 2173/2175/4817 2169/2171/4817 2168/2170/4817 +f 2173/2175/4818 2168/2170/4818 2170/2172/4818 +f 2170/2172/4819 2168/2170/4819 2167/2169/4819 +f 2170/2172/4820 2174/2176/4821 2173/2175/4822 +f 2170/2172/4820 2175/2177/4823 2174/2176/4821 +f 2173/2175/4822 2174/2176/4821 2176/2178/4824 +f 2170/2172/4820 2177/2179/4825 2175/2177/4823 +f 2172/2174/4826 2178/2180/4827 2179/2181/4828 +f 2173/2175/4822 2176/2178/4824 2178/2180/4827 +f 2173/2175/4822 2178/2180/4827 2172/2174/4826 +f 2172/2174/4826 2180/2182/4829 2171/2173/4830 +f 2171/2173/4830 2177/2179/4825 2170/2172/4820 +f 2171/2173/4830 2180/2182/4829 2177/2179/4825 +f 2172/2174/4826 2179/2181/4828 2180/2182/4829 +f 2181/2183/4831 2176/2178/4831 2174/2176/4831 +f 2177/2179/4832 2180/2182/4832 2182/2184/4832 +f 2179/2181/4833 2183/2185/4834 2180/2182/4835 +f 2183/2185/4834 2182/2184/4836 2180/2182/4835 +f 2184/2186/4837 2177/2179/4838 2182/2184/4839 +f 2175/2177/4840 2177/2179/4838 2184/2186/4837 +f 2175/2177/4841 2184/2186/4842 2185/2187/4843 +f 2174/2176/4844 2175/2177/4841 2185/2187/4843 +f 2181/2183/4845 2174/2176/4844 2185/2187/4843 +f 2186/2188/4846 2181/2183/4845 2185/2187/4843 +f 2176/2178/4847 2181/2183/4845 2186/2188/4846 +f 2176/2178/4847 2186/2188/4846 2178/2180/4848 +f 2186/2188/4846 2183/2185/4834 2178/2180/4848 +f 2179/2181/4833 2178/2180/4848 2183/2185/4834 +f 2185/2187/4849 2184/2186/4850 2186/2188/4851 +f 2183/2185/4852 2186/2188/4851 2182/2184/4853 +f 2182/2184/4853 2186/2188/4851 2184/2186/4850 +f 2187/2189/4854 2188/2190/4855 2189/2191/4854 +f 2189/2191/4854 2190/2192/4856 2187/2189/4854 +f 2191/2193/4857 2188/2190/4857 2187/2189/4857 +f 2191/2193/4858 2187/2189/4858 2192/2194/4858 +f 2192/2194/4859 2187/2189/4860 2190/2192/4861 +f 2192/2194/4859 2190/2192/4861 2193/2195/4862 +f 2193/2195/4863 2190/2192/4863 2189/2191/4863 +f 2193/2195/4864 2189/2191/4864 2194/2196/4864 +f 2194/2196/4865 2189/2191/4865 2188/2190/4865 +f 2194/2196/4866 2188/2190/4866 2191/2193/4866 +f 2193/2195/4867 2195/2197/4868 2192/2194/4869 +f 2191/2193/4870 2196/2198/4871 2197/2199/4872 +f 2191/2193/4870 2197/2199/4872 2194/2196/4873 +f 2194/2196/4873 2198/2200/4874 2193/2195/4867 +f 2194/2196/4873 2197/2199/4872 2198/2200/4874 +f 2191/2193/4870 2199/2201/4875 2196/2198/4871 +f 2193/2195/4867 2200/2202/4876 2195/2197/4868 +f 2193/2195/4867 2198/2200/4874 2200/2202/4876 +f 2192/2194/4869 2199/2201/4875 2191/2193/4870 +f 2192/2194/4869 2201/2203/4877 2199/2201/4875 +f 2192/2194/4869 2195/2197/4868 2201/2203/4877 +f 2202/2204/4878 2196/2198/4878 2199/2201/4878 +f 2203/2205/4879 2204/2206/4880 2195/2197/4881 +f 2201/2203/4882 2195/2197/4881 2204/2206/4880 +f 2204/2206/4883 2205/2207/4884 2199/2201/4885 +f 2204/2206/4883 2199/2201/4885 2201/2203/4886 +f 2202/2204/4887 2199/2201/4885 2205/2207/4884 +f 2202/2204/4888 2205/2207/4889 2196/2198/4890 +f 2206/2208/4891 2196/2198/4890 2205/2207/4889 +f 2197/2199/4892 2196/2198/4890 2206/2208/4891 +f 2207/2209/4893 2197/2199/4892 2206/2208/4891 +f 2198/2200/4894 2197/2199/4892 2207/2209/4893 +f 2208/2210/4895 2198/2200/4896 2207/2209/4897 +f 2200/2202/4898 2198/2200/4896 2208/2210/4895 +f 2195/2197/4881 2200/2202/4898 2208/2210/4895 +f 2195/2197/4881 2208/2210/4895 2203/2205/4879 +f 2208/2210/4899 2207/2209/4900 2206/2208/4901 +f 2203/2205/4902 2208/2210/4899 2204/2206/4903 +f 2208/2210/4899 2206/2208/4901 2204/2206/4903 +f 2204/2206/4903 2206/2208/4901 2205/2207/4904 +f 2209/2211/4905 2210/2212/4906 2211/2213/4907 +f 2211/2213/4907 2212/2214/4908 2209/2211/4905 +f 2211/2213/4907 2210/2212/4906 2213/2215/4909 +f 2211/2213/4907 2213/2215/4909 2214/2216/4910 +f 2214/2216/4910 2215/2217/4911 2212/2214/4908 +f 2213/2215/4909 2215/2217/4911 2214/2216/4910 +f 2214/2216/4910 2212/2214/4908 2211/2213/4907 +f 2216/2218/4912 2217/2219/4913 2218/2220/4914 +f 2219/2221/4915 2220/2222/4916 2218/2220/4917 +f 2219/2221/4915 2218/2220/4917 2221/2223/4918 +f 2221/2223/4919 2218/2220/4919 2217/2219/4919 +f 2221/2223/4920 2217/2219/4920 2222/2224/4920 +f 2222/2224/4921 2217/2219/4922 2223/2225/4923 +f 2223/2225/4923 2217/2219/4922 2216/2218/4924 +f 2223/2225/4925 2216/2218/4926 2219/2221/4927 +f 2219/2221/4927 2216/2218/4926 2220/2222/4928 +f 2209/2211/4929 2219/2221/4930 2210/2212/4931 +f 2210/2212/4932 2219/2221/4933 2213/2215/4934 +f 2213/2215/4934 2219/2221/4933 2221/2223/4935 +f 2213/2215/4936 2221/2223/4937 2215/2217/4938 +f 2215/2217/4938 2221/2223/4937 2222/2224/4939 +f 2215/2217/4940 2222/2224/4941 2212/2214/4942 +f 2212/2214/4942 2222/2224/4941 2223/2225/4943 +f 2212/2214/4944 2223/2225/4944 2209/2211/4944 +f 2209/2211/4929 2223/2225/4945 2219/2221/4930 +f 2220/2222/4946 2216/2218/4912 2218/2220/4914 +f 2224/2226/4947 2225/2227/4948 2226/2228/4949 +f 2224/2226/4947 2226/2228/4949 2227/2229/4950 +f 2224/2226/4947 2228/2230/4951 2225/2227/4948 +f 2224/2226/4947 2229/2231/4952 2228/2230/4951 +f 2227/2229/4950 2230/2232/4953 2229/2231/4952 +f 2227/2229/4950 2231/2233/4954 2230/2232/4953 +f 2227/2229/4950 2226/2228/4949 2231/2233/4954 +f 2227/2229/4950 2229/2231/4952 2224/2226/4947 +f 2232/2234/4955 2233/2235/4956 2234/2236/4957 +f 2235/2237/4958 2234/2236/4959 2236/2238/4960 +f 2235/2237/4958 2236/2238/4960 2237/2239/4961 +f 2237/2239/4962 2236/2238/4962 2233/2235/4962 +f 2237/2239/4963 2233/2235/4964 2238/2240/4965 +f 2238/2240/4965 2233/2235/4964 2239/2241/4966 +f 2238/2240/4967 2239/2241/4968 2232/2234/4969 +f 2238/2240/4967 2232/2234/4969 2240/2242/4970 +f 2240/2242/4971 2232/2234/4972 2234/2236/4973 +f 2240/2242/4971 2234/2236/4973 2235/2237/4974 +f 2228/2230/4975 2235/2237/4976 2225/2227/4977 +f 2225/2227/4977 2235/2237/4976 2237/2239/4978 +f 2225/2227/4979 2237/2239/4979 2226/2228/4979 +f 2226/2228/4980 2237/2239/4981 2238/2240/4982 +f 2226/2228/4980 2238/2240/4982 2231/2233/4983 +f 2231/2233/4984 2238/2240/4985 2230/2232/4986 +f 2230/2232/4986 2238/2240/4985 2240/2242/4987 +f 2230/2232/4986 2240/2242/4987 2229/2231/4988 +f 2229/2231/4989 2240/2242/4990 2235/2237/4991 +f 2229/2231/4989 2235/2237/4991 2228/2230/4992 +f 2236/2238/4993 2234/2236/4957 2233/2235/4956 +f 2239/2241/4994 2233/2235/4956 2232/2234/4955 +f 2241/2243/4995 2242/2244/4996 2243/2245/4997 +f 2244/2246/4998 2245/2247/4999 2241/2243/4995 +f 2241/2243/4995 2245/2247/4999 2242/2244/4996 +f 2246/2248/5000 2247/2249/5001 2244/2246/4998 +f 2244/2246/4998 2247/2249/5001 2245/2247/4999 +f 2248/2250/5002 2246/2248/5000 2244/2246/4998 +f 2241/2243/4995 2248/2250/5002 2244/2246/4998 +f 2241/2243/4995 2243/2245/4997 2248/2250/5002 +f 2249/2251/5003 2250/2252/5003 2251/2253/5003 +f 2252/2254/5004 2251/2253/5004 2253/2255/5004 +f 2253/2255/5005 2251/2253/5005 2250/2252/5005 +f 2253/2255/5006 2250/2252/5006 2254/2256/5006 +f 2254/2256/5007 2250/2252/5007 2249/2251/5007 +f 2254/2256/5008 2249/2251/5008 2255/2257/5008 +f 2255/2257/5009 2249/2251/5010 2252/2254/5011 +f 2252/2254/5011 2249/2251/5010 2251/2253/5012 +f 2247/2249/5013 2252/2254/5014 2245/2247/5015 +f 2245/2247/5015 2252/2254/5014 2253/2255/5016 +f 2245/2247/5017 2253/2255/5017 2242/2244/5017 +f 2242/2244/5018 2253/2255/5019 2254/2256/5020 +f 2242/2244/5018 2254/2256/5020 2243/2245/5021 +f 2243/2245/5022 2254/2256/5022 2248/2250/5022 +f 2248/2250/5023 2254/2256/5024 2255/2257/5025 +f 2248/2250/5023 2255/2257/5025 2246/2248/5026 +f 2246/2248/5027 2255/2257/5028 2252/2254/5029 +f 2246/2248/5027 2252/2254/5029 2247/2249/5030 +f 2256/2258/5031 2257/2259/5032 2258/2260/5033 +f 2259/2261/5034 2257/2259/5032 2256/2258/5031 +f 2260/2262/5035 2258/2260/5033 2261/2263/5036 +f 2256/2258/5031 2258/2260/5033 2260/2262/5035 +f 2256/2258/5031 2262/2264/5037 2259/2261/5034 +f 2260/2262/5035 2262/2264/5037 2256/2258/5031 +f 2260/2262/5035 2261/2263/5036 2262/2264/5037 +f 2263/2265/5038 2264/2266/5039 2265/2267/5040 +f 2266/2268/5041 2267/2269/5042 2268/2270/5043 +f 2268/2270/5044 2267/2269/5045 2269/2271/5046 +f 2269/2271/5046 2267/2269/5045 2264/2266/5047 +f 2269/2271/5048 2264/2266/5049 2270/2272/5050 +f 2270/2272/5050 2264/2266/5049 2263/2265/5051 +f 2270/2272/5052 2263/2265/5053 2271/2273/5054 +f 2270/2272/5052 2271/2273/5054 2266/2268/5055 +f 2266/2268/5056 2271/2273/5056 2265/2267/5056 +f 2266/2268/5041 2265/2267/5057 2267/2269/5042 +f 2257/2259/5058 2268/2270/5058 2258/2260/5058 +f 2258/2260/5059 2268/2270/5059 2269/2271/5059 +f 2258/2260/5060 2269/2271/5060 2261/2263/5060 +f 2261/2263/5061 2269/2271/5061 2270/2272/5061 +f 2261/2263/5062 2270/2272/5062 2262/2264/5062 +f 2262/2264/5063 2270/2272/5064 2266/2268/5065 +f 2262/2264/5063 2266/2268/5065 2259/2261/5066 +f 2259/2261/5067 2266/2268/5068 2257/2259/5069 +f 2257/2259/5069 2266/2268/5068 2268/2270/5070 +f 2267/2269/5071 2265/2267/5040 2264/2266/5039 +f 2271/2273/5072 2263/2265/5038 2265/2267/5040 +f 2272/2274/5073 2273/2275/5074 2274/2276/5075 +f 2274/2276/5075 2273/2275/5074 2275/2277/5076 +f 2276/2278/5077 2277/2279/5077 2278/2280/5077 +f 2278/2280/5078 2277/2279/5078 2279/2281/5078 +f 2280/2282/5079 2278/2280/5079 2279/2281/5079 +f 2281/2283/5080 2282/2284/5081 2283/2285/5082 +f 2283/2285/5082 2282/2284/5081 2284/2286/5083 +f 2285/2287/5084 2286/2288/5085 2287/2289/5086 +f 2285/2287/5084 2287/2289/5086 2288/2290/5087 +f 2289/2291/5088 2283/2285/5088 2287/2289/5088 +f 2289/2291/5089 2287/2289/5090 2290/2292/5091 +f 2290/2292/5092 2287/2289/5092 2291/2293/5092 +f 2290/2292/5093 2291/2293/5093 2292/2294/5093 +f 2292/2294/5094 2291/2293/5094 2293/2295/5094 +f 2293/2295/5095 2291/2293/5095 2294/2296/5095 +f 2293/2295/5096 2294/2296/5097 2283/2285/5098 +f 2293/2295/5096 2283/2285/5098 2289/2291/5099 +f 2295/2297/5100 2277/2279/5101 2281/2283/5102 +f 2295/2297/5100 2281/2283/5102 2296/2298/5103 +f 2296/2298/5104 2281/2283/5105 2297/2299/5106 +f 2296/2298/5104 2297/2299/5106 2298/2300/5107 +f 2298/2300/5108 2297/2299/5109 2299/2301/5110 +f 2298/2300/5108 2299/2301/5110 2300/2302/5111 +f 2300/2302/5112 2299/2301/5112 2279/2281/5112 +f 2300/2302/5113 2279/2281/5113 2295/2297/5113 +f 2295/2297/5100 2279/2281/5114 2277/2279/5101 +f 2301/2303/5115 2302/2304/5116 2303/2305/5117 +f 2303/2305/5118 2302/2304/5119 2304/2306/5120 +f 2302/2304/5119 2305/2307/5121 2304/2306/5120 +f 2304/2306/5122 2305/2307/5122 2306/2308/5122 +f 2306/2308/5123 2305/2307/5123 2273/2275/5123 +f 2306/2308/5124 2273/2275/5124 2307/2309/5124 +f 2307/2309/5125 2273/2275/5126 2301/2303/5127 +f 2301/2303/5127 2273/2275/5126 2280/2282/5128 +f 2301/2303/5115 2280/2282/5129 2302/2304/5116 +f 2308/2310/5130 2309/2311/5131 2286/2288/5132 +f 2308/2310/5130 2286/2288/5132 2310/2312/5133 +f 2310/2312/5134 2286/2288/5135 2311/2313/5136 +f 2311/2313/5136 2286/2288/5135 2275/2277/5137 +f 2312/2314/5138 2309/2311/5139 2308/2310/5140 +f 2312/2314/5138 2313/2315/5141 2309/2311/5139 +f 2311/2313/5142 2275/2277/5142 2313/2315/5142 +f 2311/2313/5143 2313/2315/5143 2312/2314/5143 +f 2286/2288/5144 2285/2287/5145 2275/2277/5146 +f 2275/2277/5146 2285/2287/5145 2274/2276/5147 +f 2283/2285/5148 2284/2286/5149 2287/2289/5150 +f 2287/2289/5150 2284/2286/5149 2288/2290/5151 +f 2273/2275/5152 2272/2274/5153 2280/2282/5154 +f 2280/2282/5154 2272/2274/5153 2278/2280/5155 +f 2277/2279/5156 2276/2278/5157 2281/2283/5158 +f 2281/2283/5158 2276/2278/5157 2282/2284/5159 +f 2314/2316/5160 2315/2317/5161 2316/2318/5162 +f 2316/2318/5162 2315/2317/5161 2317/2319/534 +f 2318/2320/5163 2319/2321/5164 2317/2319/5165 +f 2316/2318/5166 2317/2319/5165 2319/2321/5164 +f 2320/2322/5167 2321/2323/5168 2318/2320/5169 +f 2318/2320/5169 2321/2323/5168 2319/2321/5170 +f 2322/2324/5171 2323/2325/5172 2324/2326/5173 +f 2323/2325/5172 2322/2324/5171 2325/2327/5174 +f 2323/2325/5172 2325/2327/5174 2326/2328/5175 +f 2326/2328/5175 2325/2327/5174 2327/2329/5176 +f 2326/2328/5175 2327/2329/5176 2328/2330/5177 +f 2326/2328/5175 2328/2330/5177 2329/2331/5178 +f 2326/2328/5179 2329/2331/5180 2330/2332/5181 +f 2330/2332/5181 2329/2331/5180 2331/2333/5182 +f 2332/2334/5183 2333/2335/5184 2330/2332/5185 +f 2332/2334/5183 2330/2332/5185 2331/2333/5186 +f 2333/2335/5187 2332/2334/5188 2334/2336/5189 +f 2333/2335/5187 2334/2336/5189 2323/2325/5190 +f 2323/2325/5172 2334/2336/5191 2324/2326/5173 +f 2335/2337/5192 2336/2338/5193 2337/2339/5194 +f 2338/2340/5195 2339/2341/5196 2340/2342/5197 +f 2341/2343/5198 2342/2344/5199 2343/2345/5200 +f 2344/2346/5201 2345/2347/5202 2346/2348/5203 +f 2345/2347/5204 2344/2346/5204 2347/2349/5204 +f 2348/2350/5205 2349/2351/5206 2350/2352/5207 +f 2351/2353/5208 2352/2354/5209 2353/2355/5210 +f 2353/2355/5210 2352/2354/5209 2354/2356/5211 +f 2353/2355/5212 2354/2356/5212 2348/2350/5212 +f 2355/2357/5213 2348/2350/5213 2354/2356/5213 +f 2355/2357/5214 2349/2351/5206 2348/2350/5205 +f 2356/2358/5215 2352/2354/5216 2357/2359/5217 +f 2358/2360/5218 2359/2361/5218 2360/2362/5218 +f 2361/2363/5219 2360/2362/5220 2362/2364/5221 +f 2361/2363/5219 2362/2364/5221 2363/2365/5222 +f 2364/2366/5223 2355/2357/5224 2363/2365/5225 +f 2365/2367/5226 2363/2365/5226 2362/2364/5226 +f 2365/2367/5227 2364/2366/5223 2363/2365/5225 +f 2366/2368/5228 2359/2361/5229 2367/2369/5230 +f 2359/2361/5229 2366/2368/5228 2362/2364/5231 +f 2359/2361/5229 2362/2364/5231 2360/2362/5232 +f 2368/2370/5233 2365/2367/5234 2369/2371/5235 +f 2370/2372/5236 2337/2339/5236 2371/2373/5236 +f 2371/2373/5237 2337/2339/5237 2372/2374/5237 +f 2373/2375/5238 2372/2374/5239 2369/2371/5235 +f 2368/2370/5233 2369/2371/5235 2374/2376/5240 +f 2369/2371/5241 2372/2374/5242 2337/2339/5194 +f 2369/2371/5241 2337/2339/5194 2336/2338/5193 +f 2375/2377/5243 2376/2378/5243 2377/2379/5243 +f 2377/2379/5244 2374/2376/5245 2378/2380/5246 +f 2379/2381/5247 2377/2379/5248 2380/2382/5249 +f 2340/2342/5197 2339/2341/5196 2381/2383/5250 +f 2340/2342/5251 2381/2383/5251 2382/2384/5251 +f 2381/2383/5252 2383/2385/5252 2382/2384/5252 +f 2384/2386/5253 2381/2383/5253 2339/2341/5253 +f 2385/2387/5254 2383/2385/5254 2384/2386/5254 +f 2339/2341/5255 2386/2388/5255 2387/2389/5255 +f 2339/2341/5256 2338/2340/5256 2386/2388/5256 +f 2388/2390/5257 2389/2391/5258 2390/2392/5259 +f 2390/2392/5259 2389/2391/5258 2391/2393/5260 +f 2392/2394/5261 2391/2393/5260 2393/2395/5262 +f 2393/2395/5263 2394/2396/5263 2392/2394/5263 +f 2395/2397/5264 2394/2396/5264 2393/2395/5264 +f 2389/2391/5265 2393/2395/5266 2391/2393/5267 +f 2396/2398/5268 2397/2399/5269 2398/2400/5270 +f 2398/2400/5270 2397/2399/5269 2399/2401/5271 +f 2400/2402/5272 2398/2400/5273 2399/2401/5274 +f 2400/2402/5275 2401/2403/5275 2398/2400/5275 +f 2402/2404/5276 2400/2402/5272 2399/2401/5274 +f 2402/2404/5277 2403/2405/5278 2400/2402/5279 +f 2404/2406/5280 2397/2399/5281 2405/2407/5282 +f 2397/2399/5281 2404/2406/5280 2399/2401/5283 +f 2406/2408/5284 2402/2404/5285 2407/2409/5286 +f 2408/2410/5287 2341/2343/5288 2409/2411/5289 +f 2408/2410/5290 2409/2411/5290 2407/2409/5290 +f 2410/2412/5291 2407/2409/5292 2409/2411/5293 +f 2406/2408/5294 2407/2409/5292 2410/2412/5291 +f 2341/2343/5295 2411/2413/5295 2409/2411/5295 +f 2412/2414/5296 2385/2387/5296 2382/2384/5296 +f 2382/2384/5297 2385/2387/5297 2384/2386/5297 +f 2382/2384/5298 2384/2386/5298 2339/2341/5298 +f 2382/2384/5299 2339/2341/5299 2413/2415/5299 +f 2412/2414/5300 2382/2384/5300 2383/2385/5300 +f 2340/2342/5301 2413/2415/5301 2338/2340/5301 +f 2414/2416/5302 2402/2404/5303 2401/2403/5304 +f 2401/2403/5304 2402/2404/5303 2399/2401/5305 +f 2401/2403/5306 2399/2401/5306 2396/2398/5306 +f 2396/2398/5307 2399/2401/5308 2404/2406/5309 +f 2414/2416/5310 2401/2403/5311 2403/2405/5278 +f 2397/2399/5312 2396/2398/5313 2415/2417/5314 +f 2355/2357/5315 2365/2367/5315 2362/2364/5315 +f 2355/2357/5316 2362/2364/5316 2358/2360/5316 +f 2358/2360/5317 2362/2364/5317 2366/2368/5317 +f 2358/2360/5318 2360/2362/5220 2361/2363/5219 +f 2355/2357/5224 2361/2363/5319 2363/2365/5225 +f 2358/2360/5320 2416/2418/5321 2359/2361/5322 +f 2417/2419/5323 2395/2397/5323 2393/2395/5323 +f 2417/2419/5324 2393/2395/5324 2390/2392/5324 +f 2390/2392/5325 2393/2395/5326 2388/2390/5327 +f 2388/2390/5327 2393/2395/5326 2387/2389/5328 +f 2387/2389/5329 2393/2395/5266 2389/2391/5265 +f 2390/2392/5259 2391/2393/5260 2392/2394/5261 +f 2417/2419/5330 2392/2394/5331 2394/2396/5332 +f 2402/2404/5333 2410/2412/5333 2418/2420/5333 +f 2418/2420/5334 2410/2412/5334 2409/2411/5334 +f 2418/2420/5335 2409/2411/5335 2342/2344/5335 +f 2342/2344/5336 2409/2411/5336 2411/2413/5336 +f 2342/2344/5337 2341/2343/5288 2408/2410/5287 +f 2418/2420/5338 2408/2410/5339 2407/2409/5286 +f 2342/2344/5340 2419/2421/5340 2343/2345/5340 +f 2374/2376/5341 2412/2414/5341 2378/2380/5341 +f 2378/2380/5342 2412/2414/5342 2379/2381/5342 +f 2378/2380/5343 2379/2381/5344 2375/2377/5345 +f 2375/2377/5345 2379/2381/5344 2380/2382/5346 +f 2375/2377/5347 2377/2379/5347 2378/2380/5347 +f 2376/2378/5348 2375/2377/5348 2420/2422/5348 +f 2421/2423/5349 2352/2354/5349 2356/2358/5349 +f 2422/2424/5350 2355/2357/5350 2350/2352/5350 +f 2350/2352/5351 2355/2357/5351 2354/2356/5351 +f 2350/2352/5352 2354/2356/5352 2421/2423/5352 +f 2421/2423/5353 2354/2356/5353 2352/2354/5353 +f 2422/2424/5354 2350/2352/5207 2349/2351/5206 +f 2421/2423/5355 2351/2353/5356 2353/2355/5357 +f 2348/2350/5358 2350/2352/5358 2353/2355/5358 +f 2352/2354/5216 2351/2353/5359 2423/2425/5360 +f 2365/2367/5361 2374/2376/5361 2371/2373/5361 +f 2371/2373/5362 2374/2376/5362 2369/2371/5362 +f 2371/2373/5363 2369/2371/5364 2370/2372/5365 +f 2370/2372/5365 2369/2371/5364 2336/2338/5366 +f 2370/2372/5367 2336/2338/5367 2424/2426/5367 +f 2365/2367/5234 2373/2375/5238 2369/2371/5235 +f 2373/2375/5238 2371/2373/5368 2372/2374/5239 +f 2337/2339/5369 2370/2372/5370 2424/2426/5371 +f 2347/2349/5372 2344/2346/5372 2346/2348/5372 +f 2425/2427/5373 2426/2428/5374 2427/2429/5375 +f 2428/2430/5376 2429/2431/5377 2430/2432/5378 +f 2377/2379/5244 2379/2381/5379 2374/2376/5245 +f 2380/2382/5249 2377/2379/5248 2376/2378/5380 +f 2431/2433/5381 2374/2376/5245 2379/2381/5379 +f 2381/2383/5382 2384/2386/5382 2383/2385/5382 +f 2401/2403/5311 2400/2402/5279 2403/2405/5278 +f 2407/2409/5286 2402/2404/5285 2418/2420/5338 +f 2338/2340/5383 2413/2415/5383 2386/2388/5383 +f 2413/2415/5384 2339/2341/5384 2387/2389/5384 +f 2413/2415/5385 2340/2342/5385 2382/2384/5385 +f 2415/2417/5314 2405/2407/5386 2397/2399/5312 +f 2396/2398/5307 2404/2406/5309 2415/2417/5387 +f 2396/2398/5388 2398/2400/5388 2401/2403/5388 +f 2416/2418/5321 2367/2369/5389 2359/2361/5322 +f 2358/2360/5390 2366/2368/5390 2416/2418/5390 +f 2358/2360/5391 2361/2363/5391 2355/2357/5391 +f 2388/2390/5392 2387/2389/5392 2432/2434/5392 +f 2389/2391/5393 2388/2390/5393 2433/2435/5393 +f 2433/2435/5394 2388/2390/5394 2432/2434/5394 +f 2387/2389/5395 2389/2391/5395 2433/2435/5395 +f 2390/2392/5396 2392/2394/5396 2417/2419/5396 +f 2341/2343/5198 2343/2345/5200 2411/2413/5397 +f 2342/2344/5398 2411/2413/5398 2419/2421/5398 +f 2342/2344/5399 2408/2410/5399 2418/2420/5399 +f 2420/2422/5400 2375/2377/5400 2434/2436/5400 +f 2420/2422/5401 2380/2382/5249 2376/2378/5380 +f 2375/2377/5402 2380/2382/5402 2434/2436/5402 +f 2423/2425/5360 2357/2359/5217 2352/2354/5216 +f 2421/2423/5403 2356/2358/5403 2423/2425/5403 +f 2423/2425/5404 2351/2353/5356 2421/2423/5355 +f 2421/2423/5355 2353/2355/5357 2350/2352/5405 +f 2337/2339/5369 2424/2426/5371 2335/2337/5406 +f 2373/2375/5407 2365/2367/5407 2371/2373/5407 +f 2435/2437/5408 2436/2438/5409 2437/2439/5410 +f 2437/2439/5410 2436/2438/5409 2438/2440/5411 +f 2439/2441/5412 2440/2442/5413 2441/2443/5414 +f 2441/2443/5414 2440/2442/5413 2442/2444/5415 +f 2427/2429/5375 2443/2445/5416 2425/2427/5373 +f 2425/2427/5373 2443/2445/5416 2444/2446/5417 +f 2445/2447/5418 2446/2448/5418 2447/2449/5418 +f 2446/2448/5419 2429/2431/5420 2448/2450/5421 +f 2448/2450/5421 2429/2431/5420 2428/2430/5422 +f 2449/2451/5423 2430/2432/5378 2450/2452/5424 +f 2450/2452/5424 2430/2432/5378 2429/2431/5377 +f 2451/2453/5425 2406/2408/5426 2410/2412/5427 +f 2451/2453/5425 2410/2412/5427 2452/2454/5428 +f 2452/2454/5428 2411/2413/5429 2343/2345/5430 +f 2452/2454/5428 2343/2345/5430 2419/2421/5431 +f 2402/2404/5432 2419/2421/5433 2410/2412/5427 +f 2410/2412/5427 2419/2421/5433 2411/2413/5429 +f 2410/2412/5427 2411/2413/5429 2452/2454/5428 +f 2453/2455/5434 2402/2404/5435 2406/2408/5426 +f 2432/2434/5436 2405/2407/5437 2415/2417/5438 +f 2419/2421/5439 2405/2407/5437 2432/2434/5436 +f 2432/2434/5436 2415/2417/5438 2433/2435/5440 +f 2433/2435/5440 2415/2417/5438 2402/2404/5441 +f 2402/2404/5442 2415/2417/5442 2404/2406/5442 +f 2402/2404/5443 2404/2406/5443 2419/2421/5443 +f 2419/2421/5439 2404/2406/5444 2405/2407/5437 +f 2453/2455/5434 2414/2416/5445 2403/2405/5446 +f 2453/2455/5434 2403/2405/5446 2402/2404/5435 +f 2433/2435/5440 2402/2404/5441 2414/2416/5445 +f 2433/2435/5440 2414/2416/5445 2453/2455/5434 +f 2454/2456/5447 2417/2419/5330 2453/2455/5448 +f 2453/2455/5448 2417/2419/5330 2394/2396/5332 +f 2453/2455/5434 2394/2396/5449 2433/2435/5440 +f 2433/2435/5450 2394/2396/5450 2395/2397/5450 +f 2433/2435/5451 2395/2397/5452 2387/2389/5453 +f 2387/2389/5453 2395/2397/5452 2417/2419/5330 +f 2387/2389/5453 2417/2419/5330 2454/2456/5447 +f 2386/2388/5454 2413/2415/5455 2455/2457/5456 +f 2432/2434/5457 2386/2388/5454 2455/2457/5456 +f 2455/2457/5458 2413/2415/5458 2412/2414/5458 +f 2412/2414/5459 2413/2415/5460 2387/2389/5461 +f 2432/2434/5457 2387/2389/5462 2386/2388/5454 +f 2454/2456/5463 2412/2414/5463 2383/2385/5463 +f 2454/2456/5464 2383/2385/5464 2387/2389/5464 +f 2387/2389/5465 2383/2385/5465 2385/2387/5465 +f 2387/2389/5461 2385/2387/5466 2412/2414/5459 +f 2455/2457/5467 2420/2422/5467 2434/2436/5467 +f 2374/2376/5468 2434/2436/5468 2412/2414/5468 +f 2412/2414/5469 2434/2436/5469 2380/2382/5469 +f 2412/2414/5470 2380/2382/5470 2455/2457/5470 +f 2455/2457/5471 2380/2382/5471 2420/2422/5471 +f 2456/2458/5472 2374/2376/5245 2431/2433/5381 +f 2456/2458/5472 2431/2433/5381 2454/2456/5473 +f 2454/2456/5473 2431/2433/5381 2379/2381/5379 +f 2454/2456/5473 2379/2381/5379 2412/2414/5474 +f 2434/2436/5475 2335/2337/5406 2367/2369/5476 +f 2367/2369/5476 2335/2337/5406 2424/2426/5371 +f 2367/2369/5477 2424/2426/5478 2365/2367/5479 +f 2365/2367/5479 2424/2426/5478 2374/2376/5480 +f 2374/2376/5481 2424/2426/5481 2336/2338/5481 +f 2374/2376/5482 2336/2338/5482 2434/2436/5482 +f 2434/2436/5475 2336/2338/5483 2335/2337/5406 +f 2456/2458/5472 2365/2367/5484 2368/2370/5485 +f 2456/2458/5472 2368/2370/5485 2374/2376/5245 +f 2453/2455/5434 2406/2408/5426 2451/2453/5425 +f 2356/2358/5486 2367/2369/5389 2416/2418/5321 +f 2356/2358/5487 2416/2418/5488 2355/2357/5489 +f 2355/2357/5489 2416/2418/5488 2365/2367/5490 +f 2365/2367/5491 2416/2418/5491 2366/2368/5491 +f 2365/2367/5492 2366/2368/5228 2367/2369/5230 +f 2355/2357/5224 2364/2366/5223 2456/2458/5493 +f 2456/2458/5472 2364/2366/5494 2365/2367/5484 +f 2356/2358/5215 2357/2359/5217 2457/2459/5495 +f 2457/2459/5496 2357/2359/5497 2423/2425/5498 +f 2457/2459/5496 2423/2425/5498 2355/2357/5489 +f 2355/2357/5489 2423/2425/5498 2356/2358/5487 +f 2456/2458/5499 2422/2424/5499 2349/2351/5499 +f 2456/2458/5493 2349/2351/5500 2355/2357/5224 +f 2457/2459/5496 2355/2357/5489 2422/2424/5501 +f 2457/2459/5496 2422/2424/5501 2456/2458/5502 +f 2356/2358/5503 2457/2459/5503 2447/2449/5503 +f 2356/2358/5504 2447/2449/5505 2367/2369/5506 +f 2446/2448/5507 2452/2454/5507 2419/2421/5507 +f 2446/2448/5508 2419/2421/5508 2432/2434/5508 +f 2446/2448/5509 2432/2434/5509 2455/2457/5509 +f 2446/2448/5510 2455/2457/5510 2447/2449/5510 +f 2447/2449/5511 2455/2457/5511 2434/2436/5511 +f 2447/2449/5505 2434/2436/5512 2367/2369/5506 +f 2458/2460/5513 2426/2428/5514 2445/2447/5515 +f 2445/2447/5516 2426/2428/5516 2425/2427/5516 +f 2456/2458/5517 2454/2456/5518 2451/2453/5519 +f 2451/2453/5519 2454/2456/5518 2453/2455/5520 +f 2452/2454/5521 2446/2448/5521 2451/2453/5522 +f 2347/2349/5523 2448/2450/5524 2345/2347/5525 +f 2345/2347/5202 2448/2450/5526 2442/2444/5527 +f 2345/2347/5202 2442/2444/5527 2346/2348/5203 +f 2346/2348/5203 2442/2444/5527 2459/2461/5528 +f 2451/2453/5522 2446/2448/5521 2448/2450/5524 +f 2451/2453/5522 2448/2450/5524 2347/2349/5523 +f 2451/2453/5522 2347/2349/5523 2346/2348/5529 +f 2451/2453/5530 2346/2348/5203 2459/2461/5528 +f 2448/2450/5421 2428/2430/5422 2442/2444/5531 +f 2442/2444/5531 2428/2430/5422 2430/2432/5532 +f 2427/2429/5375 2435/2437/5533 2443/2445/5416 +f 2444/2446/5534 2450/2452/5534 2425/2427/5535 +f 2425/2427/5535 2450/2452/5534 2429/2431/5536 +f 2425/2427/5535 2429/2431/5536 2445/2447/5537 +f 2445/2447/5537 2429/2431/5536 2446/2448/5538 +f 2430/2432/5378 2449/2451/5423 2439/2441/5539 +f 2449/2451/5540 2460/2462/5540 2439/2441/5540 +f 2443/2445/5541 2435/2437/5542 2461/2463/5543 +f 2458/2460/5513 2438/2440/5544 2426/2428/5514 +f 2426/2428/5514 2438/2440/5544 2427/2429/5545 +f 2462/2464/5546 2457/2459/5547 2456/2458/5548 +f 2462/2464/5546 2456/2458/5548 2463/2465/5549 +f 2462/2464/5546 2463/2465/5549 2464/2466/5550 +f 2464/2466/5550 2463/2465/5549 2438/2440/5551 +f 2464/2466/5550 2438/2440/5551 2458/2460/5552 +f 2464/2466/5550 2458/2460/5552 2462/2464/5546 +f 2462/2464/5546 2458/2460/5552 2457/2459/5547 +f 2457/2459/5547 2458/2460/5552 2445/2447/5553 +f 2457/2459/5547 2445/2447/5553 2447/2449/5554 +f 2456/2458/5555 2451/2453/5556 2463/2465/5557 +f 2463/2465/5557 2451/2453/5556 2459/2461/5558 +f 2465/2467/5559 2437/2439/5410 2438/2440/5411 +f 2438/2440/5411 2463/2465/5560 2465/2467/5559 +f 2465/2467/5559 2463/2465/5560 2466/2468/5561 +f 2435/2437/5408 2437/2439/5410 2460/2462/5562 +f 2460/2462/5563 2437/2439/5563 2440/2442/5563 +f 2439/2441/5412 2460/2462/5564 2440/2442/5413 +f 2459/2461/5565 2442/2444/5415 2466/2468/5561 +f 2442/2444/5415 2440/2442/5413 2466/2468/5561 +f 2463/2465/5560 2459/2461/5565 2466/2468/5561 +f 2441/2443/5566 2442/2444/5531 2430/2432/5532 +f 2430/2432/5378 2439/2441/5539 2441/2443/5567 +f 2444/2446/5568 2443/2445/5541 2461/2463/5543 +f 2450/2452/5569 2444/2446/5570 2449/2451/5571 +f 2449/2451/5571 2444/2446/5570 2461/2463/5572 +f 2449/2451/5571 2461/2463/5572 2460/2462/5573 +f 2461/2463/5543 2435/2437/5542 2460/2462/5574 +f 2427/2429/5375 2436/2438/5575 2435/2437/5533 +f 2427/2429/5545 2438/2440/5544 2436/2438/5576 +f 2465/2467/5577 2467/2469/5577 2437/2439/5577 +f 2466/2468/5578 2440/2442/5578 2468/2470/5578 +f 2467/2469/5579 2468/2470/5580 2437/2439/5581 +f 2437/2439/5581 2468/2470/5580 2440/2442/5582 +f 2467/2469/5583 2465/2467/5584 2469/2471/5585 +f 2466/2468/5586 2468/2470/5587 2470/2472/5588 +f 2469/2471/5585 2471/2473/5589 2467/2469/5583 +f 2472/2474/5590 2469/2471/5591 2466/2468/5592 +f 2466/2468/5592 2469/2471/5591 2465/2467/5593 +f 2470/2472/5588 2472/2474/5594 2466/2468/5586 +f 2471/2473/5595 2470/2472/5596 2467/2469/5597 +f 2467/2469/5597 2470/2472/5596 2468/2470/5598 +f 2473/2475/5599 2474/2476/5600 2475/2477/5601 +f 2473/2475/5599 2476/2478/5602 2474/2476/5600 +f 2477/2479/5603 2478/2480/5604 2479/2481/5605 +f 2479/2481/5605 2478/2480/5604 2480/2482/5606 +f 2481/2483/5607 2480/2482/5606 2482/2484/5608 +f 2482/2484/5608 2480/2482/5606 2483/2485/5609 +f 2484/2486/5610 2483/2485/5609 2485/2487/5611 +f 2485/2487/5611 2483/2485/5609 2486/2488/5612 +f 2487/2489/5613 2486/2488/5612 2488/2490/5614 +f 2488/2490/5614 2486/2488/5612 2489/2491/5615 +f 2490/2492/5616 2491/2493/5617 2492/2494/5618 +f 2492/2494/5618 2491/2493/5617 2493/2495/5619 +f 2494/2496/5620 2476/2478/5621 2473/2475/5622 +f 2495/2497/5613 2496/2498/5623 2497/2499/5624 +f 2497/2499/5624 2496/2498/5623 2498/2500/5625 +f 2499/2501/5626 2500/2502/5627 2501/2503/5628 +f 2501/2503/5628 2500/2502/5627 2496/2498/5623 +f 2502/2504/5629 2503/2505/5630 2504/2506/5631 +f 2504/2506/5631 2503/2505/5630 2500/2502/5627 +f 2505/2507/5632 2506/2508/5633 2507/2509/5634 +f 2507/2509/5634 2506/2508/5633 2503/2505/5630 +f 2508/2510/5635 2509/2511/5636 2510/2512/5637 +f 2510/2512/5637 2509/2511/5636 2511/2513/5638 +f 2512/2514/5639 2513/2515/5640 2514/2516/5641 +f 2515/2517/5642 2516/2518/5643 2474/2476/5644 +f 2474/2476/5644 2516/2518/5643 2475/2477/5645 +f 2517/2519/5646 2518/2520/5646 2519/2521/5646 +f 2520/2522/5647 2521/2523/5648 2522/2524/5649 +f 2521/2523/5648 2520/2522/5647 2523/2525/5650 +f 2521/2523/5651 2524/2526/5652 2525/2527/5653 +f 2521/2523/5651 2525/2527/5653 2522/2524/5654 +f 2523/2525/5655 2526/2528/5655 2521/2523/5655 +f 2527/2529/5656 2518/2520/5657 2528/2530/5658 +f 2528/2530/5658 2518/2520/5657 2517/2519/5659 +f 2529/2531/5660 2517/2519/5661 2530/2532/5662 +f 2529/2531/5660 2530/2532/5662 2519/2521/5663 +f 2488/2490/5664 2491/2493/5664 2487/2489/5664 +f 2487/2489/5665 2491/2493/5665 2531/2533/5665 +f 2487/2489/5666 2531/2533/5666 2532/2534/5666 +f 2532/2534/5667 2491/2493/5668 2488/2490/5669 +f 2532/2534/5667 2488/2490/5669 2533/2535/5670 +f 2533/2535/5671 2488/2490/5671 2489/2491/5671 +f 2485/2487/5672 2534/2536/5673 2484/2486/5674 +f 2484/2486/5674 2534/2536/5673 2535/2537/5675 +f 2484/2486/5676 2535/2537/5677 2536/2538/5678 +f 2536/2538/5679 2534/2536/5680 2485/2487/5681 +f 2536/2538/5679 2485/2487/5681 2537/2539/5670 +f 2537/2539/5682 2485/2487/5682 2486/2488/5682 +f 2482/2484/5683 2535/2537/5683 2481/2483/5683 +f 2538/2540/5684 2539/2541/5685 2482/2484/5686 +f 2482/2484/5686 2539/2541/5685 2535/2537/5687 +f 2540/2542/5688 2482/2484/5689 2483/2485/5690 +f 2479/2481/5691 2539/2541/5691 2477/2479/5691 +f 2541/2543/5692 2539/2541/5693 2479/2481/5694 +f 2541/2543/5695 2479/2481/5695 2542/2544/5695 +f 2542/2544/5696 2479/2481/5696 2480/2482/5696 +f 2543/2545/5697 2478/2480/5697 2544/2546/5697 +f 2543/2545/5698 2544/2546/5699 2492/2494/5700 +f 2492/2494/5700 2544/2546/5699 2490/2492/5701 +f 2493/2495/5702 2491/2493/5703 2489/2491/5704 +f 2493/2495/5702 2489/2491/5704 2545/2547/5705 +f 2541/2543/5706 2542/2544/5707 2477/2479/5708 +f 2477/2479/5708 2542/2544/5707 2478/2480/5709 +f 2482/2484/5689 2540/2542/5688 2538/2540/5710 +f 2538/2540/5710 2540/2542/5688 2480/2482/5711 +f 2538/2540/5712 2480/2482/5712 2481/2483/5712 +f 2538/2540/5713 2481/2483/5713 2539/2541/5713 +f 2536/2538/5714 2537/2539/5715 2484/2486/5716 +f 2484/2486/5716 2537/2539/5715 2483/2485/5717 +f 2532/2534/5714 2533/2535/5718 2487/2489/5719 +f 2487/2489/5719 2533/2535/5718 2486/2488/5720 +f 2546/2548/5721 2547/2549/5722 2548/2550/5723 +f 2494/2496/5620 2549/2551/5724 2476/2478/5621 +f 2476/2478/5621 2549/2551/5724 2550/2552/5725 +f 2551/2553/5726 2552/2554/5727 2553/2555/5728 +f 2551/2553/5726 2553/2555/5728 2554/2556/5729 +f 2555/2557/5730 2556/2558/5730 2557/2559/5730 +f 2555/2557/5731 2557/2559/5731 2558/2560/5731 +f 2559/2561/5732 2560/2562/5732 2561/2563/5732 +f 2507/2509/5733 2562/2564/5734 2505/2507/5735 +f 2563/2565/5736 2564/2566/5737 2507/2509/5738 +f 2507/2509/5738 2564/2566/5737 2562/2564/5739 +f 2565/2567/5740 2507/2509/5741 2503/2505/5742 +f 2566/2568/5743 2502/2504/5743 2567/2569/5743 +f 2567/2569/5744 2504/2506/5744 2566/2568/5744 +f 2566/2568/5745 2504/2506/5745 2568/2570/5745 +f 2568/2570/5746 2504/2506/5746 2500/2502/5746 +f 2501/2503/5747 2569/2571/5747 2499/2501/5747 +f 2567/2569/5748 2569/2571/5748 2501/2503/5748 +f 2567/2569/5749 2501/2503/5749 2570/2572/5749 +f 2570/2572/5682 2501/2503/5682 2496/2498/5682 +f 2497/2499/5750 2509/2511/5751 2495/2497/5752 +f 2495/2497/5752 2509/2511/5751 2569/2571/5753 +f 2495/2497/5754 2569/2571/5754 2571/2573/5754 +f 2571/2573/5755 2509/2511/5756 2497/2499/5757 +f 2571/2573/5755 2497/2499/5757 2572/2574/5670 +f 2572/2574/5758 2497/2499/5758 2498/2500/5758 +f 2573/2575/5759 2506/2508/5760 2564/2566/5761 +f 2573/2575/5759 2564/2566/5761 2510/2512/5762 +f 2510/2512/5762 2564/2566/5761 2508/2510/5763 +f 2508/2510/5764 2562/2564/5734 2509/2511/5765 +f 2511/2513/5766 2509/2511/5767 2498/2500/5768 +f 2511/2513/5766 2498/2500/5768 2574/2576/5769 +f 2571/2573/5714 2572/2574/5718 2495/2497/5719 +f 2495/2497/5719 2572/2574/5718 2496/2498/5720 +f 2567/2569/5770 2570/2572/5771 2499/2501/5772 +f 2499/2501/5772 2570/2572/5771 2500/2502/5773 +f 2566/2568/5774 2568/2570/5775 2502/2504/5776 +f 2502/2504/5776 2568/2570/5775 2503/2505/5777 +f 2507/2509/5741 2565/2567/5740 2563/2565/5778 +f 2563/2565/5778 2565/2567/5740 2506/2508/5779 +f 2563/2565/5780 2506/2508/5780 2505/2507/5780 +f 2563/2565/5781 2505/2507/5782 2564/2566/5783 +f 2575/2577/5784 2576/2578/5785 2552/2554/5786 +f 2561/2563/5787 2560/2562/5787 2556/2558/5787 +f 2513/2515/5640 2512/2514/5639 2577/2579/5788 +f 2578/2580/5789 2579/2581/5790 2580/2582/5791 +f 2581/2583/5792 2582/2584/5793 2514/2516/5794 +f 2514/2516/5794 2582/2584/5793 2512/2514/5795 +f 2578/2580/5796 2583/2585/5797 2579/2581/5798 +f 2579/2581/5798 2583/2585/5797 2584/2586/5799 +f 2519/2521/5800 2518/2520/5801 2529/2531/5802 +f 2529/2531/5802 2518/2520/5801 2585/2587/5803 +f 2585/2587/5803 2518/2520/5801 2527/2529/5804 +f 2524/2526/5805 2523/2525/5806 2525/2527/5807 +f 2525/2527/5807 2523/2525/5806 2520/2522/5808 +f 2524/2526/5809 2521/2523/5809 2526/2528/5809 +f 2517/2519/5810 2529/2531/5811 2528/2530/5812 +f 2528/2530/5812 2529/2531/5811 2585/2587/5813 +f 2478/2480/5604 2489/2491/5615 2486/2488/5612 +f 2478/2480/5604 2486/2488/5612 2483/2485/5609 +f 2478/2480/5604 2483/2485/5609 2480/2482/5606 +f 2542/2544/5814 2480/2482/528 2539/2541/5815 +f 2542/2544/5814 2539/2541/5815 2478/2480/5816 +f 2478/2480/5816 2539/2541/5815 2544/2546/5817 +f 2540/2542/528 2483/2485/528 2535/2537/528 +f 2540/2542/528 2535/2537/528 2480/2482/528 +f 2480/2482/528 2535/2537/528 2539/2541/5815 +f 2537/2539/528 2486/2488/528 2531/2533/528 +f 2537/2539/528 2531/2533/528 2483/2485/528 +f 2483/2485/528 2531/2533/528 2535/2537/528 +f 2533/2535/5818 2489/2491/5819 2586/2588/5820 +f 2533/2535/5818 2586/2588/5820 2486/2488/528 +f 2486/2488/528 2586/2588/5820 2531/2533/528 +f 2539/2541/5821 2490/2492/5821 2477/2479/5821 +f 2477/2479/5822 2490/2492/5822 2544/2546/5822 +f 2477/2479/5823 2544/2546/5823 2541/2543/5823 +f 2541/2543/5692 2544/2546/5824 2539/2541/5693 +f 2490/2492/5825 2539/2541/5825 2481/2483/5825 +f 2490/2492/5826 2481/2483/5826 2491/2493/5826 +f 2491/2493/5827 2481/2483/5827 2535/2537/5827 +f 2536/2538/5678 2535/2537/5677 2531/2533/5828 +f 2536/2538/5829 2531/2533/5829 2534/2536/5829 +f 2534/2536/5830 2531/2533/5831 2491/2493/5832 +f 2534/2536/5830 2491/2493/5832 2535/2537/5833 +f 2532/2534/5834 2531/2533/5834 2586/2588/5834 +f 2532/2534/5835 2586/2588/5820 2491/2493/5836 +f 2586/2588/5820 2489/2491/5819 2491/2493/5836 +f 2493/2495/5837 2545/2547/5838 2492/2494/5839 +f 2492/2494/5839 2545/2547/5838 2543/2545/5840 +f 2587/2589/5841 2588/2590/5842 2589/2591/5843 +f 2587/2589/5841 2589/2591/5843 2590/2592/5844 +f 2591/2593/5845 2590/2592/5846 2589/2591/5847 +f 2547/2549/5722 2546/2548/5721 2592/2594/5848 +f 2593/2595/5849 2594/2596/5850 2548/2550/5851 +f 2548/2550/5851 2594/2596/5850 2546/2548/5852 +f 2595/2597/5853 2596/2598/5854 2597/2599/5855 +f 2595/2597/5856 2598/2600/5857 2596/2598/5858 +f 2596/2598/5858 2598/2600/5857 2599/2601/5859 +f 2556/2558/5860 2558/2560/5861 2600/2602/5862 +f 2560/2562/5863 2559/2561/5864 2555/2557/5865 +f 2560/2562/5863 2555/2557/5865 2558/2560/5866 +f 2556/2558/5867 2600/2602/5867 2557/2559/5867 +f 2601/2603/5868 2561/2563/5868 2556/2558/5868 +f 2602/2604/5869 2553/2555/5870 2576/2578/5871 +f 2551/2553/5872 2576/2578/5873 2575/2577/5874 +f 2602/2604/5875 2576/2578/5873 2554/2556/5876 +f 2554/2556/5876 2576/2578/5873 2551/2553/5872 +f 2575/2577/5877 2603/2605/5877 2551/2553/5877 +f 2551/2553/5878 2603/2605/5879 2552/2554/5880 +f 2559/2561/5881 2601/2603/5882 2555/2557/5883 +f 2555/2557/5883 2601/2603/5882 2556/2558/5884 +f 2604/2606/5885 2605/2607/5885 2506/2508/5885 +f 2606/2608/5886 2506/2508/5886 2607/2609/5886 +f 2607/2609/5887 2506/2508/5887 2605/2607/5887 +f 2604/2606/5888 2606/2608/5889 2605/2607/5890 +f 2605/2607/5890 2606/2608/5889 2607/2609/5891 +f 2498/2500/5625 2496/2498/5623 2500/2502/5627 +f 2498/2500/5625 2500/2502/5627 2503/2505/5630 +f 2498/2500/5625 2503/2505/5630 2506/2508/5633 +f 2506/2508/5892 2565/2567/5893 2564/2566/5894 +f 2568/2570/5895 2500/2502/5896 2567/2569/5897 +f 2568/2570/5895 2567/2569/5897 2503/2505/5898 +f 2503/2505/5898 2567/2569/5897 2565/2567/5899 +f 2570/2572/528 2496/2498/528 2569/2571/5900 +f 2570/2572/528 2569/2571/5900 2500/2502/5896 +f 2500/2502/5896 2569/2571/5900 2567/2569/5897 +f 2572/2574/5901 2498/2500/5902 2608/2610/5903 +f 2572/2574/5901 2608/2610/5903 2496/2498/528 +f 2496/2498/528 2608/2610/5903 2569/2571/5900 +f 2505/2507/5735 2562/2564/5734 2508/2510/5764 +f 2505/2507/5782 2508/2510/5904 2564/2566/5783 +f 2562/2564/5905 2564/2566/5894 2565/2567/5893 +f 2565/2567/5899 2567/2569/5897 2502/2504/5906 +f 2565/2567/5893 2502/2504/5629 2562/2564/5905 +f 2562/2564/5905 2502/2504/5629 2504/2506/5631 +f 2569/2571/5907 2509/2511/5907 2499/2501/5907 +f 2499/2501/5908 2509/2511/5765 2562/2564/5734 +f 2499/2501/5909 2562/2564/5909 2567/2569/5909 +f 2567/2569/5910 2562/2564/5910 2504/2506/5910 +f 2571/2573/5911 2569/2571/5911 2608/2610/5911 +f 2571/2573/5912 2608/2610/5903 2509/2511/5913 +f 2608/2610/5903 2498/2500/5902 2509/2511/5913 +f 2576/2578/5914 2553/2555/5915 2574/2576/5916 +f 2574/2576/5917 2553/2555/5728 2511/2513/5918 +f 2511/2513/5918 2553/2555/5728 2552/2554/5727 +f 2511/2513/5919 2552/2554/5919 2576/2578/5919 +f 2556/2558/5920 2560/2562/5921 2510/2512/5922 +f 2510/2512/5922 2560/2562/5921 2558/2560/5923 +f 2510/2512/5924 2558/2560/5924 2573/2575/5924 +f 2573/2575/5925 2558/2560/5926 2556/2558/5920 +f 2510/2512/5922 2511/2513/5927 2556/2558/5920 +f 2556/2558/5920 2511/2513/5927 2576/2578/5914 +f 2556/2558/5920 2576/2578/5914 2573/2575/5925 +f 2573/2575/5925 2576/2578/5914 2574/2576/5916 +f 2514/2516/5928 2513/2515/5928 2609/2611/5928 +f 2610/2612/5929 2514/2516/5930 2609/2611/5931 +f 2610/2612/5929 2609/2611/5931 2577/2579/5932 +f 2610/2612/5933 2577/2579/5934 2512/2514/5935 +f 2610/2612/5933 2512/2514/5935 2611/2613/5936 +f 2611/2613/5936 2512/2514/5935 2582/2584/5937 +f 2612/2614/5938 2578/2580/5939 2613/2615/5940 +f 2612/2614/5938 2613/2615/5940 2580/2582/5941 +f 2612/2614/5942 2580/2582/5943 2579/2581/5944 +f 2612/2614/5942 2579/2581/5944 2584/2586/5945 +f 2614/2616/5946 2583/2585/5946 2578/2580/5946 +f 2611/2613/5947 2581/2583/5948 2610/2612/5949 +f 2610/2612/5949 2581/2583/5948 2514/2516/5950 +f 2584/2586/5951 2614/2616/5952 2612/2614/5953 +f 2612/2614/5953 2614/2616/5952 2578/2580/5954 +f 2523/2525/5955 2585/2587/5956 2527/2529/5957 +f 2530/2532/5958 2517/2519/5958 2615/2617/5958 +f 2615/2617/5959 2517/2519/5960 2519/2521/5961 +f 2615/2617/5959 2519/2521/5961 2616/2618/5962 +f 2522/2524/5963 2524/2526/5964 2526/2528/5965 +f 2523/2525/5955 2524/2526/5966 2585/2587/5956 +f 2585/2587/5956 2524/2526/5966 2522/2524/5967 +f 2585/2587/5968 2522/2524/5969 2528/2530/5970 +f 2528/2530/5970 2522/2524/5969 2525/2527/5971 +f 2519/2521/5961 2520/2522/5972 2616/2618/5962 +f 2616/2618/5962 2520/2522/5972 2522/2524/5963 +f 2526/2528/5965 2515/2517/5973 2616/2618/5962 +f 2526/2528/5965 2616/2618/5962 2522/2524/5963 +f 2526/2528/5974 2523/2525/5974 2515/2517/5974 +f 2515/2517/5642 2523/2525/5975 2527/2529/5976 +f 2515/2517/5642 2527/2529/5976 2516/2518/5643 +f 2516/2518/5643 2527/2529/5976 2528/2530/5970 +f 2615/2617/5977 2516/2518/5643 2530/2532/5978 +f 2530/2532/5978 2516/2518/5643 2528/2530/5970 +f 2530/2532/5978 2528/2530/5970 2519/2521/5961 +f 2519/2521/5961 2528/2530/5970 2525/2527/5971 +f 2519/2521/5961 2525/2527/5971 2520/2522/5972 +f 2616/2618/5979 2617/2619/5980 2489/2491/5981 +f 2489/2491/5981 2617/2619/5980 2545/2547/5982 +f 2616/2618/5979 2489/2491/5981 2478/2480/5983 +f 2616/2618/5979 2478/2480/5983 2615/2617/5984 +f 2615/2617/5984 2478/2480/5983 2618/2620/5985 +f 2618/2620/5985 2478/2480/5983 2543/2545/5986 +f 2618/2620/5985 2543/2545/5986 2617/2619/5980 +f 2617/2619/5980 2543/2545/5986 2545/2547/5982 +f 2617/2619/5987 2619/2621/5988 2620/2622/5989 +f 2591/2593/5990 2589/2591/5990 2588/2590/5990 +f 2590/2592/5846 2591/2593/5845 2587/2589/5991 +f 2621/2623/5992 2592/2594/5993 2622/2624/5994 +f 2621/2623/5992 2622/2624/5994 2548/2550/5995 +f 2622/2624/5996 2592/2594/5997 2546/2548/5998 +f 2622/2624/5996 2546/2548/5998 2623/2625/5999 +f 2623/2625/5999 2546/2548/5998 2594/2596/6000 +f 2548/2550/6001 2547/2549/6001 2621/2623/6001 +f 2548/2550/6002 2622/2624/6003 2593/2595/6004 +f 2593/2595/6004 2622/2624/6003 2623/2625/6005 +f 2624/2626/6006 2598/2600/6006 2595/2597/6006 +f 2625/2627/6007 2597/2599/6008 2626/2628/6009 +f 2625/2627/6007 2626/2628/6009 2595/2597/6010 +f 2626/2628/6011 2597/2599/6012 2596/2598/6013 +f 2626/2628/6011 2596/2598/6013 2599/2601/6014 +f 2595/2597/6015 2626/2628/6016 2624/2626/6017 +f 2624/2626/6017 2626/2628/6016 2599/2601/6018 +f 2600/2602/5862 2558/2560/5861 2627/2629/6019 +f 2554/2556/6020 2561/2563/6021 2602/2604/5869 +f 2602/2604/5869 2561/2563/6021 2601/2603/6022 +f 2575/2577/5784 2552/2554/5786 2550/2552/5725 +f 2550/2552/6023 2552/2554/5880 2603/2605/5879 +f 2628/2630/6024 2553/2555/5870 2602/2604/5869 +f 2627/2629/6019 2628/2630/6024 2600/2602/5862 +f 2600/2602/5862 2628/2630/6024 2602/2604/5869 +f 2600/2602/5862 2602/2604/5869 2557/2559/6025 +f 2557/2559/6025 2602/2604/5869 2601/2603/6022 +f 2557/2559/6025 2601/2603/6022 2558/2560/6026 +f 2558/2560/6026 2601/2603/6022 2559/2561/6027 +f 2627/2629/6028 2558/2560/6026 2559/2561/6027 +f 2627/2629/6028 2559/2561/6027 2549/2551/5724 +f 2549/2551/5724 2559/2561/6027 2561/2563/6021 +f 2550/2552/5725 2549/2551/5724 2575/2577/5784 +f 2575/2577/5784 2549/2551/5724 2561/2563/6021 +f 2575/2577/5784 2561/2563/6021 2554/2556/6020 +f 2575/2577/5784 2554/2556/6020 2603/2605/6029 +f 2603/2605/6029 2554/2556/6020 2553/2555/5870 +f 2603/2605/6029 2553/2555/5870 2550/2552/6030 +f 2550/2552/6030 2553/2555/5870 2628/2630/6024 +f 2606/2608/6031 2498/2500/6032 2506/2508/6033 +f 2574/2576/6034 2498/2500/6032 2628/2630/6035 +f 2628/2630/6035 2498/2500/6032 2606/2608/6031 +f 2627/2629/6036 2573/2575/6037 2628/2630/6035 +f 2628/2630/6035 2573/2575/6037 2574/2576/6034 +f 2604/2606/6038 2506/2508/6039 2627/2629/6036 +f 2627/2629/6036 2506/2508/6039 2573/2575/6037 +f 2604/2606/6040 2629/2631/6041 2630/2632/6042 +f 2631/2633/6043 2516/2518/6044 2615/2617/6045 +f 2631/2633/6043 2615/2617/6045 2632/2634/6046 +f 2632/2634/6046 2615/2617/6045 2618/2620/6047 +f 2632/2634/6046 2618/2620/6047 2633/2635/6048 +f 2633/2635/6048 2634/2636/6049 2632/2634/6046 +f 2632/2634/6046 2634/2636/6049 2631/2633/6043 +f 2631/2633/6043 2634/2636/6049 2516/2518/6044 +f 2617/2619/6050 2578/2580/5789 2580/2582/5791 +f 2617/2619/6051 2620/2622/6052 2614/2616/6053 +f 2513/2515/6054 2577/2579/6055 2618/2620/6056 +f 2611/2613/6057 2582/2584/6058 2633/2635/6059 +f 2580/2582/5791 2609/2611/6060 2513/2515/6054 +f 2580/2582/5791 2513/2515/6054 2617/2619/6050 +f 2617/2619/6050 2513/2515/6054 2618/2620/6056 +f 2578/2580/6061 2617/2619/6061 2613/2615/6061 +f 2613/2615/6062 2617/2619/6051 2614/2616/6053 +f 2613/2615/6062 2614/2616/6053 2580/2582/5791 +f 2580/2582/5791 2614/2616/6053 2584/2586/5799 +f 2580/2582/5791 2584/2586/5799 2609/2611/6060 +f 2609/2611/6060 2584/2586/5799 2581/2583/5792 +f 2609/2611/6060 2581/2583/5792 2577/2579/6055 +f 2577/2579/6055 2581/2583/5792 2611/2613/6057 +f 2577/2579/6055 2611/2613/6057 2618/2620/6056 +f 2611/2613/6057 2633/2635/6059 2618/2620/6056 +f 2582/2584/5793 2581/2583/5792 2633/2635/6063 +f 2633/2635/6063 2581/2583/5792 2584/2586/5799 +f 2633/2635/6063 2584/2586/5799 2620/2622/6052 +f 2620/2622/6052 2584/2586/5799 2583/2585/5797 +f 2620/2622/6052 2583/2585/5797 2614/2616/6053 +f 2515/2517/6064 2635/2637/6065 2616/2618/6066 +f 2616/2618/6066 2635/2637/6065 2617/2619/6067 +f 2617/2619/6067 2635/2637/6065 2636/2638/6068 +f 2617/2619/6067 2636/2638/6068 2619/2621/6069 +f 2635/2637/6065 2515/2517/6064 2636/2638/6068 +f 2636/2638/6068 2515/2517/6064 2619/2621/6069 +f 2637/2639/6070 2587/2589/5841 2606/2608/6071 +f 2606/2608/6071 2587/2589/5841 2628/2630/6072 +f 2628/2630/6073 2587/2589/6073 2591/2593/6073 +f 2628/2630/6074 2591/2593/6074 2550/2552/6074 +f 2591/2593/6075 2588/2590/6075 2550/2552/6075 +f 2550/2552/6076 2588/2590/5842 2638/2640/6077 +f 2638/2640/6077 2588/2590/5842 2587/2589/5841 +f 2638/2640/6077 2587/2589/5841 2637/2639/6070 +f 2599/2601/5859 2593/2595/6078 2597/2599/5855 +f 2547/2549/6079 2592/2594/6080 2606/2608/6081 +f 2625/2627/6082 2595/2597/6082 2604/2606/6082 +f 2604/2606/6083 2595/2597/5853 2597/2599/5855 +f 2639/2641/6084 2637/2639/6085 2594/2596/6086 +f 2599/2601/5859 2597/2599/5855 2624/2626/6087 +f 2594/2596/6086 2637/2639/6085 2623/2625/6088 +f 2604/2606/6089 2630/2632/6090 2624/2626/6087 +f 2604/2606/6089 2624/2626/6087 2625/2627/6091 +f 2625/2627/6091 2624/2626/6087 2597/2599/5855 +f 2594/2596/6086 2593/2595/6078 2639/2641/6084 +f 2639/2641/6084 2593/2595/6078 2599/2601/5859 +f 2639/2641/6084 2599/2601/5859 2630/2632/6090 +f 2630/2632/6090 2599/2601/5859 2598/2600/5857 +f 2630/2632/6090 2598/2600/5857 2624/2626/6087 +f 2621/2623/6092 2593/2595/6078 2592/2594/6080 +f 2592/2594/6080 2593/2595/6078 2623/2625/6088 +f 2592/2594/6080 2623/2625/6088 2606/2608/6081 +f 2606/2608/6081 2623/2625/6088 2637/2639/6085 +f 2597/2599/5855 2593/2595/6078 2621/2623/6092 +f 2597/2599/5855 2621/2623/6092 2547/2549/6079 +f 2597/2599/5855 2547/2549/6079 2604/2606/6083 +f 2604/2606/6083 2547/2549/6079 2606/2608/6081 +f 2629/2631/6093 2604/2606/6094 2640/2642/6095 +f 2640/2642/6095 2604/2606/6094 2641/2643/6096 +f 2641/2643/6096 2604/2606/6094 2627/2629/6097 +f 2641/2643/6096 2627/2629/6097 2549/2551/6098 +f 2641/2643/6096 2549/2551/6098 2640/2642/6095 +f 2640/2642/6095 2549/2551/6098 2629/2631/6093 +f 2475/2477/6099 2516/2518/6044 2642/2644/6100 +f 2642/2644/6100 2516/2518/6044 2634/2636/6049 +f 2642/2644/6100 2634/2636/6049 2633/2635/6048 +f 2620/2622/6052 2643/2645/6101 2633/2635/6063 +f 2633/2635/6063 2643/2645/6101 2642/2644/6102 +f 2619/2621/5988 2643/2645/6103 2620/2622/5989 +f 2515/2517/6064 2474/2476/6104 2619/2621/6069 +f 2619/2621/6069 2474/2476/6104 2643/2645/6105 +f 2476/2478/6106 2550/2552/6076 2644/2646/6107 +f 2644/2646/6107 2550/2552/6076 2638/2640/6077 +f 2644/2646/6107 2638/2640/6077 2637/2639/6070 +f 2645/2647/6108 2644/2646/6109 2639/2641/6084 +f 2644/2646/6109 2637/2639/6085 2639/2641/6084 +f 2639/2641/6084 2630/2632/6090 2645/2647/6108 +f 2629/2631/6041 2645/2647/6110 2630/2632/6042 +f 2549/2551/6098 2494/2496/6111 2629/2631/6093 +f 2629/2631/6093 2494/2496/6111 2645/2647/6112 +f 2473/2475/6113 2645/2647/6113 2494/2496/6113 +f 2476/2478/5602 2644/2646/6114 2646/2648/6115 +f 2647/2649/6116 2643/2645/6117 2474/2476/5600 +f 2647/2649/6116 2474/2476/5600 2476/2478/5602 +f 2647/2649/6116 2476/2478/5602 2646/2648/6115 +f 2646/2648/6115 2644/2646/6114 2648/2650/6118 +f 2648/2650/6118 2644/2646/6114 2645/2647/6119 +f 2475/2477/6120 2642/2644/6121 2649/2651/6122 +f 2649/2651/6122 2642/2644/6121 2647/2649/6116 +f 2647/2649/6116 2642/2644/6121 2643/2645/6117 +f 2648/2650/6123 2475/2477/6120 2649/2651/6122 +f 2648/2650/6118 2645/2647/6119 2473/2475/6124 +f 2648/2650/6123 2473/2475/6125 2475/2477/6120 +f 2650/2652/6126 2648/2650/6127 2651/2653/6128 +f 2651/2653/6128 2648/2650/6127 2649/2651/6129 +f 2651/2653/6130 2649/2651/6131 2652/2654/6132 +f 2652/2654/6132 2649/2651/6131 2647/2649/6133 +f 2652/2654/6134 2647/2649/6135 2653/2655/6136 +f 2653/2655/6136 2647/2649/6135 2646/2648/6137 +f 2653/2655/6138 2646/2648/6139 2650/2652/6140 +f 2650/2652/6140 2646/2648/6139 2648/2650/6141 +f 2654/2656/6142 2331/2333/5182 2655/2657/6143 +f 2655/2657/6143 2331/2333/5182 2329/2331/5180 +f 2656/2658/6144 2332/2334/5183 2654/2656/6145 +f 2654/2656/6145 2332/2334/5183 2331/2333/5186 +f 2657/2659/6146 2334/2336/5189 2656/2658/6147 +f 2656/2658/6147 2334/2336/5189 2332/2334/5188 +f 2655/2657/6148 2329/2331/6149 2657/2659/6150 +f 2657/2659/6150 2329/2331/6149 2334/2336/6151 +f 2658/2660/2173 2659/2661/6152 2660/2662/6153 +f 2658/2660/2173 2661/2663/6154 2662/2664/6155 +f 2658/2660/2173 2660/2662/6153 2661/2663/6154 +f 2663/2665/6156 2660/2662/6157 2664/2666/6158 +f 2664/2666/6159 2660/2662/6160 2659/2661/6161 +f 2664/2666/6159 2659/2661/6161 2665/2667/6162 +f 2665/2667/6163 2659/2661/6164 2658/2660/6165 +f 2665/2667/6163 2658/2660/6165 2666/2668/6166 +f 2666/2668/6167 2658/2660/6168 2662/2664/6169 +f 2666/2668/6167 2662/2664/6169 2667/2669/6170 +f 2667/2669/6171 2662/2664/6172 2661/2663/6173 +f 2667/2669/6171 2661/2663/6173 2668/2670/6174 +f 2668/2670/6175 2661/2663/6176 2663/2665/6177 +f 2663/2665/6177 2661/2663/6176 2660/2662/6178 +f 2669/2671/6179 2670/2672/6180 2667/2669/6170 +f 2667/2669/6170 2670/2672/6180 2666/2668/6167 +f 2668/2670/6174 2669/2671/6181 2667/2669/6171 +f 2671/2673/6182 2669/2671/6182 2663/2665/6182 +f 2663/2665/6177 2669/2671/6183 2668/2670/6175 +f 2672/2674/6184 2671/2673/6185 2664/2666/6158 +f 2664/2666/6158 2671/2673/6185 2663/2665/6156 +f 2665/2667/6162 2672/2674/6186 2664/2666/6159 +f 2670/2672/6187 2672/2674/6187 2666/2668/6187 +f 2666/2668/6166 2672/2674/6188 2665/2667/6163 +f 2671/2673/6189 2672/2674/6190 2669/2671/6190 +f 2669/2671/6190 2672/2674/6190 2670/2672/6190 +f 2673/2675/5534 2674/2676/6191 2675/2677/5534 +f 2675/2677/5534 2676/2678/6192 2673/2675/5534 +f 2677/2679/6193 2676/2678/6194 2678/2680/6195 +f 2678/2680/6195 2676/2678/6194 2675/2677/6196 +f 2678/2680/6197 2675/2677/6198 2679/2681/6199 +f 2679/2681/6200 2675/2677/6201 2674/2676/6202 +f 2679/2681/6200 2674/2676/6202 2680/2682/6203 +f 2680/2682/6204 2674/2676/6205 2673/2675/6206 +f 2680/2682/6204 2673/2675/6206 2681/2683/6207 +f 2681/2683/6208 2673/2675/6209 2682/2684/6210 +f 2682/2684/6210 2673/2675/6209 2676/2678/6211 +f 2682/2684/6212 2676/2678/6213 2677/2679/6214 +f 2680/2682/6203 2683/2685/6215 2679/2681/6200 +f 2684/2686/6216 2683/2685/6217 2681/2683/6207 +f 2681/2683/6207 2683/2685/6217 2680/2682/6204 +f 2682/2684/6210 2684/2686/6218 2681/2683/6208 +f 2685/2687/6219 2684/2686/6220 2677/2679/6214 +f 2677/2679/6214 2684/2686/6220 2682/2684/6212 +f 2678/2680/6195 2685/2687/6221 2677/2679/6193 +f 2683/2685/6222 2685/2687/6223 2679/2681/6199 +f 2679/2681/6199 2685/2687/6223 2678/2680/6197 +f 2684/2686/6224 2685/2687/6224 2683/2685/6224 +f 2037/2039/6225 2047/2049/6226 2040/2042/6227 +f 2062/2064/6228 2063/2065/6229 2038/2040/6230 +f 2037/2039/6225 2063/2065/6229 2066/2068/6231 +f 2038/2040/6230 2045/2047/6232 2064/2066/6233 +f 2037/2039/6225 2066/2068/6231 2047/2049/6226 +f 2062/2064/6228 2038/2040/6230 2064/2066/6233 +f 2058/2060/6234 2037/2039/6225 2060/2062/6235 +f 2047/2049/6226 2048/2050/6236 2052/2054/6237 +f 2045/2047/6232 2065/2067/6238 2064/2066/6233 +f 2047/2049/6226 2065/2067/6238 2045/2047/6232 +f 2061/2063/6239 2040/2042/6227 2035/2037/6240 +f 2037/2039/6225 2058/2060/6234 2035/2037/6240 +f 2065/2067/6238 2047/2049/6226 2066/2068/6231 +f 2060/2062/6235 2037/2039/6225 2040/2042/6227 +f 2061/2063/6239 2060/2062/6235 2040/2042/6227 +f 2040/2042/6227 2053/2055/6241 2056/2058/6242 +f 2039/2041/6243 2040/2042/6227 2056/2058/6242 +f 2052/2054/6237 2048/2050/6236 2051/2053/6244 +f 2052/2054/6237 2053/2055/6241 2047/2049/6226 +f 2039/2041/6243 2056/2058/6242 2057/2059/6245 +f 2053/2055/6241 2040/2042/6227 2047/2049/6226 +f 2041/2043/6246 2055/2057/6247 2056/2058/6242 +f 2037/2039/6225 2038/2040/6230 2063/2065/6229 +f 2043/2045/6248 2041/2043/6246 2049/2051/6249 +f 2035/2037/6240 2059/2061/6250 2061/2063/6239 +f 2043/2045/6248 2051/2053/6244 2048/2050/6236 +f 2049/2051/6249 2041/2043/6246 2053/2055/6241 +f 2054/2056/6251 2039/2041/6243 2057/2059/6245 +f 2041/2043/6246 2042/2044/6252 2055/2057/6247 +f 2049/2051/6249 2050/2052/6253 2043/2045/6248 +f 2042/2044/6252 2039/2041/6243 2054/2056/6251 +f 2041/2043/6246 2056/2058/6242 2053/2055/6241 +f 2054/2056/6251 2055/2057/6247 2042/2044/6252 +f 2043/2045/6248 2050/2052/6253 2051/2053/6244 +f 2035/2037/6240 2058/2060/6234 2059/2061/6250 +f 2320/2322/6254 2315/2317/6255 2314/2316/6256 +f 2320/2322/6254 2314/2316/6256 2321/2323/6257 +f 2324/2326/6258 2334/2336/6259 2328/2330/6260 +f 2328/2330/6260 2334/2336/6259 2329/2331/6260 +f 2324/2326/6261 2328/2330/6262 2325/2327/3031 +f 2325/2327/3031 2328/2330/6262 2327/2329/3031 +f 2324/2326/6261 2325/2327/3031 2322/2324/3031 +f 2283/2285/6263 2297/2299/6264 2281/2283/6265 +f 2333/2335/6266 2279/2281/6267 2321/2323/6268 +f 2299/2301/6269 2297/2299/6264 2283/2285/6263 +f 2299/2301/6269 2319/2321/6270 2279/2281/6267 +f 2305/2307/6271 2302/2304/6272 2323/2325/6273 +f 2294/2296/6274 2291/2293/6275 2319/2321/6270 +f 2323/2325/6273 2302/2304/6272 2279/2281/6267 +f 2319/2321/6270 2299/2301/6269 2283/2285/6263 +f 2319/2321/6270 2291/2293/6275 2316/2318/6276 +f 2321/2323/6268 2279/2281/6267 2319/2321/6270 +f 2287/2289/6277 2314/2316/6278 2316/2318/6276 +f 2314/2316/6278 2330/2332/6279 2321/2323/6268 +f 2333/2335/6266 2323/2325/6273 2279/2281/6267 +f 2287/2289/6277 2326/2328/6280 2330/2332/6279 +f 2287/2289/6277 2309/2311/6281 2326/2328/6280 +f 2287/2289/6277 2330/2332/6279 2314/2316/6278 +f 2330/2332/6279 2333/2335/6266 2321/2323/6268 +f 2319/2321/6270 2283/2285/6263 2294/2296/6274 +f 2305/2307/6271 2323/2325/6273 2273/2275/6282 +f 2323/2325/6273 2326/2328/6280 2273/2275/6282 +f 2309/2311/6281 2313/2315/6283 2326/2328/6280 +f 2291/2293/6275 2287/2289/6277 2316/2318/6276 +f 2287/2289/6277 2286/2288/6284 2309/2311/6281 +f 2279/2281/6267 2302/2304/6272 2280/2282/6285 +f 2273/2275/6282 2326/2328/6280 2313/2315/6283 +f 2275/2277/6286 2273/2275/6282 2313/2315/6283 +f 2308/2310/6287 2310/2312/6288 2312/2314/6289 +f 2311/2313/6290 2312/2314/6289 2310/2312/6288 +f 2304/2306/6291 2301/2303/6292 2303/2305/6293 +f 2306/2308/6294 2301/2303/6292 2304/2306/6291 +f 2306/2308/6294 2307/2309/6295 2301/2303/6292 +f 2298/2300/6296 2295/2297/6296 2296/2298/6297 +f 2295/2297/6296 2298/2300/6296 2300/2302/6298 +f 2289/2291/5089 2290/2292/5091 2293/2295/6299 +f 2290/2292/5091 2292/2294/6300 2293/2295/6299 +f 2282/2284/6301 2288/2290/6301 2284/2286/6189 +f 2278/2280/6224 2282/2284/6301 2276/2278/6190 +f 2288/2290/6301 2282/2284/6301 2278/2280/6224 +f 2278/2280/6224 2274/2276/6301 2288/2290/6301 +f 2288/2290/6301 2274/2276/6301 2285/2287/6302 +f 2274/2276/6301 2278/2280/6224 2272/2274/6303 +f 2686/2688/6304 2687/2689/6305 2688/2690/6306 +f 2686/2688/6304 2689/2691/6307 2687/2689/6305 +f 2690/2692/6308 2688/2690/6308 2687/2689/6308 +f 2690/2692/6309 2687/2689/6310 2689/2691/6311 +f 2690/2692/6309 2689/2691/6311 2691/2693/6312 +f 2691/2693/6313 2689/2691/6314 2692/2694/6315 +f 2692/2694/6315 2689/2691/6314 2686/2688/6316 +f 2692/2694/6317 2686/2688/6317 2688/2690/6317 +f 2692/2694/6318 2688/2690/6318 2690/2692/6318 +f 2692/2694/6319 2693/2695/6320 2691/2693/6321 +f 2690/2692/6322 2694/2696/6323 2692/2694/6319 +f 2690/2692/6322 2695/2697/6324 2694/2696/6323 +f 2692/2694/6319 2694/2696/6323 2696/2698/6325 +f 2692/2694/6319 2697/2699/6326 2693/2695/6320 +f 2692/2694/6319 2696/2698/6325 2697/2699/6326 +f 2690/2692/6322 2698/2700/6327 2695/2697/6324 +f 2691/2693/6321 2698/2700/6327 2690/2692/6322 +f 2691/2693/6321 2693/2695/6320 2698/2700/6327 +f 2699/2701/6328 2694/2696/6328 2695/2697/6328 +f 2698/2700/6329 2700/2702/6329 2695/2697/6329 +f 2701/2703/6330 2698/2700/6331 2693/2695/6332 +f 2701/2703/6330 2702/2704/6333 2698/2700/6331 +f 2700/2702/6334 2698/2700/6331 2702/2704/6333 +f 2703/2705/6335 2700/2702/6334 2702/2704/6333 +f 2695/2697/6336 2700/2702/6334 2703/2705/6335 +f 2695/2697/6336 2703/2705/6335 2699/2701/6337 +f 2704/2706/6338 2694/2696/6339 2699/2701/6337 +f 2704/2706/6338 2699/2701/6337 2703/2705/6335 +f 2696/2698/6340 2694/2696/6341 2704/2706/6342 +f 2704/2706/6342 2705/2707/6343 2696/2698/6340 +f 2706/2708/6344 2696/2698/6345 2705/2707/6346 +f 2697/2699/6347 2696/2698/6345 2706/2708/6344 +f 2693/2695/6348 2697/2699/6347 2706/2708/6344 +f 2693/2695/6348 2706/2708/6344 2701/2703/6349 +f 2704/2706/6350 2703/2705/6351 2705/2707/6352 +f 2701/2703/6353 2706/2708/6354 2702/2704/6355 +f 2706/2708/6354 2705/2707/6352 2702/2704/6355 +f 2702/2704/6355 2705/2707/6352 2703/2705/6351 +f 2707/2709/6356 2708/2710/6357 2709/2711/6358 +f 2709/2711/6358 2710/2712/6359 2707/2709/6356 +f 2711/2713/6360 2708/2710/6361 2712/2714/6362 +f 2712/2714/6363 2708/2710/6363 2707/2709/6363 +f 2712/2714/6364 2707/2709/6364 2713/2715/6364 +f 2713/2715/6365 2707/2709/6365 2710/2712/6365 +f 2713/2715/6366 2710/2712/6366 2711/2713/6366 +f 2711/2713/6367 2710/2712/6367 2709/2711/6367 +f 2711/2713/6360 2709/2711/6368 2708/2710/6361 +f 2712/2714/6369 2714/2716/6370 2711/2713/6371 +f 2711/2713/6371 2714/2716/6370 2715/2717/6372 +f 2711/2713/6371 2715/2717/6372 2716/2718/6373 +f 2712/2714/6369 2717/2719/6374 2714/2716/6370 +f 2713/2715/6375 2718/2720/6376 2719/2721/6377 +f 2711/2713/6371 2716/2718/6373 2718/2720/6376 +f 2711/2713/6371 2718/2720/6376 2713/2715/6375 +f 2712/2714/6369 2720/2722/6378 2717/2719/6374 +f 2713/2715/6375 2720/2722/6378 2712/2714/6369 +f 2713/2715/6375 2719/2721/6377 2720/2722/6378 +f 2721/2723/6379 2719/2721/6377 2718/2720/6376 +f 2714/2716/6380 2722/2724/6380 2715/2717/6380 +f 2721/2723/6381 2723/2725/6382 2719/2721/6383 +f 2719/2721/6383 2723/2725/6382 2720/2722/6384 +f 2723/2725/6382 2724/2726/6385 2720/2722/6384 +f 2720/2722/6384 2724/2726/6385 2717/2719/6386 +f 2725/2727/6387 2717/2719/6386 2724/2726/6385 +f 2714/2716/6388 2717/2719/6386 2725/2727/6387 +f 2722/2724/6389 2714/2716/6388 2725/2727/6387 +f 2725/2727/6387 2726/2728/6390 2722/2724/6389 +f 2726/2728/6390 2715/2717/6391 2722/2724/6389 +f 2716/2718/6392 2715/2717/6391 2726/2728/6390 +f 2716/2718/6392 2726/2728/6390 2727/2729/6393 +f 2718/2720/6394 2716/2718/6395 2727/2729/6396 +f 2726/2728/6390 2728/2730/6397 2727/2729/6393 +f 2727/2729/6396 2728/2730/6398 2718/2720/6394 +f 2721/2723/6381 2718/2720/6394 2728/2730/6398 +f 2728/2730/6398 2723/2725/6382 2721/2723/6381 +f 2723/2725/6399 2728/2730/6397 2724/2726/6400 +f 2728/2730/6397 2726/2728/6390 2724/2726/6400 +f 2724/2726/6400 2726/2728/6390 2725/2727/6401 +f 2729/2731/6402 2730/2732/6403 2731/2733/6404 +f 2732/2734/6405 2733/2735/6405 2734/2736/6406 +f 2732/2734/6405 2735/2737/6407 2733/2735/6405 +f 2736/2738/6408 2735/2737/6408 2737/2739/6408 +f 2737/2739/6409 2735/2737/6409 2732/2734/6409 +f 2737/2739/6410 2732/2734/6411 2734/2736/6412 +f 2737/2739/6410 2734/2736/6412 2738/2740/6413 +f 2738/2740/6414 2734/2736/6415 2733/2735/6416 +f 2738/2740/6414 2733/2735/6416 2736/2738/6417 +f 2736/2738/6418 2733/2735/6418 2735/2737/6418 +f 2737/2739/6419 2739/2741/6420 2736/2738/6421 +f 2736/2738/6421 2739/2741/6420 2740/2742/6422 +f 2736/2738/6421 2740/2742/6422 2741/2743/6423 +f 2737/2739/6419 2742/2744/6424 2739/2741/6420 +f 2738/2740/6425 2743/2745/6426 2744/2746/6427 +f 2736/2738/6421 2741/2743/6423 2743/2745/6426 +f 2736/2738/6421 2743/2745/6426 2738/2740/6425 +f 2738/2740/6425 2745/2747/2810 2737/2739/6419 +f 2737/2739/6419 2746/2748/6428 2742/2744/6424 +f 2737/2739/6419 2745/2747/2810 2746/2748/6428 +f 2738/2740/6425 2744/2746/6427 2745/2747/2810 +f 2747/2749/6429 2745/2747/6430 2748/2750/6431 +f 2745/2747/6432 2747/2749/6433 2731/2733/6434 +f 2746/2748/6435 2745/2747/6432 2731/2733/6434 +f 2746/2748/6435 2731/2733/6434 2730/2732/6436 +f 2742/2744/6437 2746/2748/6435 2730/2732/6436 +f 2730/2732/6436 2729/2731/6438 2742/2744/6437 +f 2742/2744/6437 2729/2731/6438 2739/2741/6439 +f 2740/2742/6440 2739/2741/6441 2729/2731/6442 +f 2749/2751/6443 2740/2742/6440 2729/2731/6442 +f 2741/2743/6444 2740/2742/6445 2749/2751/6446 +f 2750/2752/6447 2749/2751/6443 2729/2731/6442 +f 2750/2752/6448 2741/2743/6444 2749/2751/6446 +f 2741/2743/6444 2750/2752/6448 2743/2745/6449 +f 2743/2745/6449 2750/2752/6448 2748/2750/6450 +f 2744/2746/6451 2743/2745/6449 2748/2750/6450 +f 2747/2749/6452 2748/2750/6453 2750/2752/6454 +f 2745/2747/6430 2744/2746/6455 2748/2750/6431 +f 2750/2752/6456 2729/2731/6456 2751/2753/6456 +f 2747/2749/6452 2750/2752/6454 2731/2733/6457 +f 2750/2752/6454 2751/2753/6458 2731/2733/6457 +f 2731/2733/6404 2751/2753/6459 2729/2731/6402 +f 2752/2754/6460 2753/2755/6461 2754/2756/6462 +f 2752/2754/6460 2755/2757/6463 2753/2755/6461 +f 2756/2758/6464 2752/2754/6465 2757/2759/6466 +f 2757/2759/6466 2752/2754/6465 2754/2756/6467 +f 2757/2759/6468 2754/2756/6469 2753/2755/6470 +f 2757/2759/6468 2753/2755/6470 2758/2760/6471 +f 2758/2760/6472 2753/2755/6472 2755/2757/6472 +f 2758/2760/6473 2755/2757/6473 2756/2758/6473 +f 2756/2758/6474 2755/2757/6474 2752/2754/6474 +f 2756/2758/6475 2759/2761/6476 2760/2762/6477 +f 2756/2758/6475 2761/2763/6478 2758/2760/6479 +f 2756/2758/6475 2760/2762/6477 2761/2763/6478 +f 2757/2759/6480 2759/2761/6476 2756/2758/6475 +f 2757/2759/6480 2762/2764/6481 2759/2761/6476 +f 2758/2760/6479 2763/2765/6482 2764/2766/6483 +f 2758/2760/6479 2761/2763/6478 2763/2765/6482 +f 2757/2759/6480 2765/2767/6484 2766/2768/6485 +f 2757/2759/6480 2766/2768/6485 2762/2764/6481 +f 2758/2760/6479 2764/2766/6483 2765/2767/6484 +f 2758/2760/6479 2765/2767/6484 2757/2759/6480 +f 2766/2768/6486 2765/2767/6487 2767/2769/6488 +f 2767/2769/6488 2768/2770/6489 2766/2768/6486 +f 2762/2764/6490 2766/2768/6486 2768/2770/6489 +f 2769/2771/6491 2762/2764/6490 2768/2770/6489 +f 2759/2761/6492 2762/2764/6490 2769/2771/6491 +f 2770/2772/6493 2769/2771/6491 2768/2770/6489 +f 2759/2761/6494 2769/2771/6491 2770/2772/6493 +f 2760/2762/6495 2759/2761/6494 2770/2772/6493 +f 2771/2773/6496 2760/2762/6495 2770/2772/6493 +f 2761/2763/6497 2760/2762/6495 2771/2773/6496 +f 2771/2773/6496 2763/2765/6498 2761/2763/6497 +f 2772/2774/6499 2763/2765/6498 2771/2773/6496 +f 2764/2766/6500 2763/2765/6501 2772/2774/6502 +f 2765/2767/6503 2764/2766/6500 2772/2774/6502 +f 2765/2767/6503 2772/2774/6502 2767/2769/6504 +f 2771/2773/6505 2770/2772/6493 2772/2774/6506 +f 2770/2772/6493 2768/2770/6489 2767/2769/6507 +f 2767/2769/6507 2772/2774/6506 2770/2772/6493 +f 2773/2775/6508 2774/2776/6509 2775/2777/6510 +f 2776/2778/6511 2773/2775/6508 2775/2777/6510 +f 2777/2779/6512 2774/2776/6513 2773/2775/6514 +f 2777/2779/6515 2773/2775/6515 2776/2778/6515 +f 2777/2779/6516 2776/2778/6516 2778/2780/6516 +f 2778/2780/6517 2776/2778/6517 2775/2777/6517 +f 2778/2780/6518 2775/2777/6519 2779/2781/6520 +f 2779/2781/6520 2775/2777/6519 2774/2776/6521 +f 2779/2781/6522 2774/2776/6513 2777/2779/6512 +f 2777/2779/6523 2780/2782/6524 2779/2781/6525 +f 2777/2779/6523 2781/2783/6526 2780/2782/6524 +f 2779/2781/6525 2782/2784/6527 2778/2780/6528 +f 2779/2781/6525 2783/2785/6529 2784/2786/6530 +f 2779/2781/6525 2784/2786/6530 2782/2784/6527 +f 2780/2782/6524 2783/2785/6529 2779/2781/6525 +f 2778/2780/6528 2782/2784/6527 2785/2787/6531 +f 2778/2780/6528 2786/2788/6532 2777/2779/6523 +f 2777/2779/6523 2786/2788/6532 2787/2789/6533 +f 2777/2779/6523 2787/2789/6533 2781/2783/6526 +f 2778/2780/6528 2785/2787/6531 2786/2788/6532 +f 2785/2787/6534 2788/2790/6535 2786/2788/6536 +f 2789/2791/6537 2786/2788/6536 2788/2790/6535 +f 2786/2788/6536 2789/2791/6537 2787/2789/6538 +f 2789/2791/6539 2790/2792/6540 2781/2783/6541 +f 2789/2791/6539 2781/2783/6541 2787/2789/6542 +f 2791/2793/6543 2781/2783/6544 2790/2792/6545 +f 2780/2782/6546 2781/2783/6544 2791/2793/6543 +f 2783/2785/6547 2780/2782/6548 2791/2793/6549 +f 2784/2786/6550 2783/2785/6547 2791/2793/6549 +f 2791/2793/6549 2792/2794/6551 2784/2786/6550 +f 2782/2784/6552 2784/2786/6553 2792/2794/6554 +f 2793/2795/6555 2782/2784/6552 2792/2794/6554 +f 2785/2787/6534 2782/2784/6552 2793/2795/6555 +f 2793/2795/6555 2788/2790/6535 2785/2787/6534 +f 2791/2793/6556 2790/2792/6557 2792/2794/6558 +f 2788/2790/6559 2793/2795/6560 2789/2791/6561 +f 2793/2795/6560 2792/2794/6558 2789/2791/6561 +f 2789/2791/6561 2792/2794/6558 2790/2792/6557 +f 2794/2796/6562 2795/2797/6563 2796/2798/6564 +f 2797/2799/6565 2798/2800/6566 2799/2801/6567 +f 2797/2799/6565 2800/2802/6568 2798/2800/6566 +f 2801/2803/6569 2799/2801/6569 2798/2800/6569 +f 2801/2803/6570 2798/2800/6570 2802/2804/6570 +f 2802/2804/6571 2798/2800/6571 2800/2802/6571 +f 2802/2804/6572 2800/2802/6573 2803/2805/6574 +f 2803/2805/6574 2800/2802/6573 2797/2799/6575 +f 2803/2805/6576 2797/2799/6577 2799/2801/6578 +f 2803/2805/6576 2799/2801/6578 2804/2806/6579 +f 2804/2806/6580 2799/2801/6580 2801/2803/6580 +f 2801/2803/6581 2805/2807/6582 2804/2806/6583 +f 2801/2803/6581 2806/2808/6584 2805/2807/6582 +f 2804/2806/6583 2807/2809/6585 2803/2805/6586 +f 2804/2806/6583 2805/2807/6582 2807/2809/6585 +f 2803/2805/6586 2807/2809/6585 2808/2810/6587 +f 2802/2804/6588 2809/2811/6589 2806/2808/6584 +f 2802/2804/6588 2806/2808/6584 2801/2803/6581 +f 2803/2805/6586 2808/2810/6587 2809/2811/6589 +f 2803/2805/6586 2809/2811/6589 2802/2804/6588 +f 2810/2812/6590 2805/2807/6582 2806/2808/6584 +f 2808/2810/6591 2811/2813/6591 2809/2811/6591 +f 2809/2811/6592 2812/2814/6592 2806/2808/6592 +f 2796/2798/6593 2811/2813/6594 2813/2815/6595 +f 2809/2811/6596 2811/2813/6594 2796/2798/6593 +f 2812/2814/6597 2809/2811/6596 2796/2798/6593 +f 2795/2797/6598 2812/2814/6597 2796/2798/6593 +f 2806/2808/6599 2812/2814/6597 2795/2797/6598 +f 2794/2796/6600 2806/2808/6599 2795/2797/6598 +f 2806/2808/6599 2794/2796/6600 2810/2812/6601 +f 2814/2816/6602 2810/2812/6601 2794/2796/6600 +f 2810/2812/6601 2814/2816/6602 2805/2807/6603 +f 2807/2809/6604 2805/2807/6605 2814/2816/6606 +f 2815/2817/6607 2807/2809/6604 2814/2816/6606 +f 2816/2818/6608 2807/2809/6609 2815/2817/6610 +f 2808/2810/6611 2807/2809/6609 2816/2818/6608 +f 2811/2813/6594 2808/2810/6611 2816/2818/6608 +f 2811/2813/6594 2816/2818/6608 2813/2815/6595 +f 2815/2817/6612 2814/2816/6613 2794/2796/6562 +f 2813/2815/6614 2816/2818/6615 2815/2817/6612 +f 2794/2796/6562 2796/2798/6564 2813/2815/6614 +f 2813/2815/6614 2815/2817/6612 2794/2796/6562 +f 2657/2659/5534 2656/2658/5534 2654/2656/5534 +f 2657/2659/5534 2654/2656/5534 2655/2657/5534 +f 2315/2317/5534 2318/2320/5534 2317/2319/5534 +f 2315/2317/5534 2320/2322/5534 2318/2320/5534 +f 2469/2471/6301 2472/2474/6616 2470/2472/6301 +f 2471/2473/6224 2469/2471/6301 2470/2472/6301 +f 2650/2652/6301 2652/2654/6301 2653/2655/6224 +f 2650/2652/6301 2651/2653/6301 2652/2654/6301 +f 2817/2819/6617 2818/2820/6618 2819/2821/6619 +f 2820/2822/6620 2817/2819/6617 2819/2821/6619 +f 2821/2823/6621 2822/2824/6621 2823/2825/6621 +f 2821/2823/6622 2823/2825/6622 2824/2826/6622 +f 2825/2827/6623 2821/2823/6624 2824/2826/6625 +f 2821/2823/6624 2825/2827/6623 2822/2824/6626 +f 2826/2828/6627 2827/2829/6628 2828/2830/6629 +f 2826/2828/6627 2828/2830/6629 2829/2831/6630 +f 1697/1699/6631 2817/2819/6632 2820/2822/6633 +f 2820/2822/6634 1699/1701/6634 1697/1699/6634 +f 1699/1701/6635 2820/2822/6635 2819/2821/6635 +f 2819/2821/6636 1700/1702/6636 1699/1701/6636 +f 1700/1702/6637 2819/2821/6637 2818/2820/6637 +f 2818/2820/6638 1696/1698/6638 1700/1702/6638 +f 1696/1698/6639 2818/2820/6640 2817/2819/6632 +f 2817/2819/6632 1697/1699/6631 1696/1698/6639 +f 1691/1693/6641 2822/2824/6642 2825/2827/6643 +f 2825/2827/6643 1692/1694/6644 1691/1693/6641 +f 1692/1694/6645 2825/2827/6645 2824/2826/6645 +f 2824/2826/6646 1694/1696/6646 1692/1694/6646 +f 1694/1696/6647 2824/2826/6648 2823/2825/6649 +f 2823/2825/6649 1695/1697/6650 1694/1696/6647 +f 1695/1697/6651 2823/2825/6652 2822/2824/6653 +f 2822/2824/6653 1691/1693/6654 1695/1697/6651 +f 2830/2832/6655 2826/2828/6655 2829/2831/6655 +f 2829/2831/6656 2831/2833/6657 2830/2832/6658 +f 2831/2833/6659 2829/2831/6659 2828/2830/6659 +f 2828/2830/6660 2832/2834/6660 2831/2833/6660 +f 2832/2834/6661 2828/2830/6661 2827/2829/6661 +f 2827/2829/6662 2833/2835/6662 2832/2834/6662 +f 2833/2835/6663 2827/2829/6663 2826/2828/6663 +f 2826/2828/6664 2830/2832/6665 2833/2835/6666 +f 1688/1690/6667 2834/2836/6667 2835/2837/6667 +f 2835/2837/6668 1689/1691/6668 1688/1690/6668 +f 1689/1691/6669 2835/2837/6670 2836/2838/6671 +f 2836/2838/6671 1690/1692/6672 1689/1691/6669 +f 1690/1692/6673 2836/2838/6674 2837/2839/6675 +f 2837/2839/6676 1687/1689/6676 1690/1692/6676 +f 1687/1689/6677 2837/2839/6678 2834/2836/6679 +f 2834/2836/6680 1688/1690/6680 1687/1689/6680 +f 2837/2839/6681 2833/2835/6666 2830/2832/6665 +f 2830/2832/6682 2834/2836/6679 2837/2839/6678 +f 2837/2839/6683 2832/2834/6683 2833/2835/6683 +f 2832/2834/6684 2837/2839/6675 2836/2838/6674 +f 2836/2838/6671 2831/2833/6685 2832/2834/6686 +f 2831/2833/6685 2836/2838/6671 2835/2837/6670 +f 2834/2836/6687 2830/2832/6658 2831/2833/6657 +f 2831/2833/6657 2835/2837/6688 2834/2836/6687 +f 2838/2840/6689 1827/1829/6690 1829/1831/6691 +f 1827/1829/6690 2838/2840/6689 1830/1832/6692 +f 2839/2841/6693 1830/1832/6694 2838/2840/6695 +f 2838/2840/6695 2840/2842/6696 2839/2841/6693 +f 2840/2842/6697 2838/2840/6698 1829/1831/6699 +f 1829/1831/6699 2841/2843/6700 2840/2842/6697 +f 1829/1831/6701 2842/2844/6702 2841/2843/6703 +f 2842/2844/6702 1829/1831/6701 1828/1830/6704 +f 1828/1830/6705 2839/2841/6706 2842/2844/6707 +f 2839/2841/6706 1828/1830/6705 1830/1832/6708 +f 1832/1834/6709 2843/2845/6710 2844/2846/6711 +f 2844/2846/6712 1835/1837/6712 1832/1834/6712 +f 1835/1837/6713 2844/2846/6714 2845/2847/6715 +f 2845/2847/6715 1834/1836/6716 1835/1837/6713 +f 2845/2847/6717 1831/1833/6717 1834/1836/6717 +f 1831/1833/6718 2845/2847/6719 2846/2848/6720 +f 2846/2848/6721 1832/1834/6721 1831/1833/6721 +f 1832/1834/6722 2846/2848/6723 2843/2845/6724 +f 2839/2841/6725 2843/2845/6724 2846/2848/6723 +f 2846/2848/6726 2842/2844/6707 2839/2841/6706 +f 2842/2844/6727 2846/2848/6720 2845/2847/6719 +f 2845/2847/6728 2841/2843/6703 2842/2844/6702 +f 2841/2843/6729 2845/2847/6715 2844/2846/6714 +f 2844/2846/6730 2840/2842/6697 2841/2843/6700 +f 2840/2842/6731 2844/2846/6711 2843/2845/6710 +f 2843/2845/6732 2839/2841/6693 2840/2842/6696 +f 1839/1841/4010 1843/1845/4010 1840/1842/4011 +f 1842/1844/4010 1841/1843/6733 1826/1828/4011 +f 1841/1843/6733 1838/1840/4009 1840/1842/4011 +f 1822/1824/6734 1842/1844/4010 1826/1828/4011 +f 1841/1843/6733 1840/1842/4011 1826/1828/4011 +f 1775/1777/6735 1769/1771/6736 2847/2849/6737 +f 1769/1771/6736 1768/1770/6738 1776/1778/6739 +f 1776/1778/6739 2847/2849/6737 1769/1771/6736 +f 1776/1778/6740 1770/1772/6740 2848/2850/6740 +f 1773/1775/6741 1775/1777/6742 2847/2849/6743 +f 2847/2849/6743 2849/2851/6744 1773/1775/6741 +f 1770/1772/6745 1773/1775/6746 2849/2851/6747 +f 2849/2851/6747 2848/2850/6748 1770/1772/6745 +f 2848/2850/6749 2847/2849/6750 1776/1778/6751 +f 2847/2849/6750 2848/2850/6749 2849/2851/6752 +f 1748/1750/6753 1747/1749/3818 1742/1744/3815 +f 1753/1755/6754 1757/1759/6754 1754/1756/6754 +f 1752/1754/6755 1755/1757/6755 1756/1758/6755 +f 1753/1755/6756 1752/1754/6757 1756/1758/6758 +f 1756/1758/6758 1757/1759/6759 1753/1755/6756 +f 2850/2852/6760 2851/2853/6761 2852/2854/6762 +f 2853/2855/6763 2854/2856/6764 2855/2857/6765 +f 2850/2852/6760 2855/2857/6765 2851/2853/6761 +f 2850/2852/6760 2853/2855/6763 2855/2857/6765 +f 2856/2858/6766 2850/2852/6760 2852/2854/6762 +f 2856/2858/6766 2852/2854/6762 2857/2859/6767 +f 2853/2855/6763 2856/2858/6766 2854/2856/6764 +f 2856/2858/6766 2857/2859/6767 2854/2856/6764 +f 2858/2860/6768 2859/2861/6769 2860/2862/6770 +f 2858/2860/6768 2861/2863/6771 2859/2861/6769 +f 2862/2864/6772 2860/2862/6772 2859/2861/6772 +f 2862/2864/6773 2863/2865/6774 2860/2862/6775 +f 2863/2865/6774 2864/2866/6776 2860/2862/6775 +f 2863/2865/6777 2865/2867/6777 2864/2866/6777 +f 2865/2867/6778 2858/2860/6778 2864/2866/6778 +f 2865/2867/6779 2866/2868/6780 2858/2860/6781 +f 2866/2868/6780 2861/2863/6782 2858/2860/6781 +f 2866/2868/6783 2867/2869/6784 2861/2863/6785 +f 2867/2869/6784 2859/2861/6786 2861/2863/6785 +f 2867/2869/6787 2862/2864/6787 2859/2861/6787 +f 2863/2865/6788 2862/2864/6789 2868/2870/6790 +f 2862/2864/6789 2869/2871/6791 2868/2870/6790 +f 2862/2864/6789 2867/2869/6792 2869/2871/6791 +f 2867/2869/6792 2870/2872/6793 2869/2871/6791 +f 2867/2869/6792 2871/2873/6794 2870/2872/6793 +f 2867/2869/6792 2866/2868/6795 2871/2873/6794 +f 2866/2868/6795 2872/2874/6796 2871/2873/6794 +f 2866/2868/6795 2865/2867/6797 2872/2874/6796 +f 2865/2867/6797 2868/2870/6790 2872/2874/6796 +f 2865/2867/6797 2863/2865/6788 2868/2870/6790 +f 2851/2853/6798 2855/2857/6798 2869/2871/6798 +f 2855/2857/6799 2868/2870/6799 2869/2871/6799 +f 2855/2857/6800 2854/2856/6800 2868/2870/6800 +f 2854/2856/6801 2872/2874/6801 2868/2870/6801 +f 2854/2856/6802 2857/2859/6802 2872/2874/6802 +f 2857/2859/6803 2871/2873/6804 2872/2874/6805 +f 2857/2859/6803 2852/2854/6806 2871/2873/6804 +f 2852/2854/6807 2870/2872/6807 2871/2873/6807 +f 2852/2854/6808 2851/2853/6809 2870/2872/6810 +f 2851/2853/6809 2869/2871/6811 2870/2872/6810 +f 2853/2855/6812 2873/2875/6813 2856/2858/6814 +f 2873/2875/6813 2874/2876/6815 2856/2858/6814 +f 2850/2852/6816 2875/2877/6817 2853/2855/6818 +f 2875/2877/6817 2873/2875/6819 2853/2855/6818 +f 2856/2858/6820 2874/2876/6821 2850/2852/6822 +f 2874/2876/6821 2875/2877/6823 2850/2852/6822 +f 2874/2876/528 2873/2875/528 2875/2877/528 +f 2864/2866/6824 2858/2860/6768 2860/2862/6770 +f 2876/2878/6825 2877/2879/6826 2878/2880/6827 +f 2877/2879/6826 2879/2881/6828 2880/2882/6829 +f 2877/2879/6826 2881/2883/6830 2879/2881/6828 +f 2877/2879/6826 2880/2882/6829 2878/2880/6827 +f 2881/2883/6830 2882/2884/6831 2883/2885/6832 +f 2881/2883/6830 2876/2878/6833 2882/2884/6831 +f 2879/2881/6828 2881/2883/6830 2883/2885/6832 +f 2884/2886/6834 2885/2887/6835 2886/2888/6836 +f 2884/2886/6834 2886/2888/6836 2887/2889/6837 +f 2888/2890/6838 2884/2886/6839 2887/2889/6840 +f 2888/2890/6838 2889/2891/6841 2884/2886/6839 +f 2889/2891/6842 2890/2892/6842 2884/2886/6842 +f 2889/2891/6843 2891/2893/6843 2890/2892/6843 +f 2891/2893/6844 2885/2887/6845 2890/2892/6846 +f 2891/2893/6844 2892/2894/6847 2885/2887/6845 +f 2892/2894/6848 2886/2888/6848 2885/2887/6848 +f 2892/2894/6849 2888/2890/6850 2886/2888/6851 +f 2888/2890/6850 2887/2889/6852 2886/2888/6851 +f 2889/2891/6853 2893/2895/6854 2894/2896/6855 +f 2889/2891/6853 2888/2890/6856 2893/2895/6854 +f 2888/2890/6856 2895/2897/6857 2893/2895/6854 +f 2888/2890/6856 2896/2898/6858 2895/2897/6857 +f 2888/2890/6856 2892/2894/6859 2896/2898/6858 +f 2892/2894/6859 2897/2899/6860 2896/2898/6858 +f 2892/2894/6859 2891/2893/6861 2897/2899/6860 +f 2891/2893/6861 2894/2896/6855 2897/2899/6860 +f 2891/2893/6861 2889/2891/6853 2894/2896/6855 +f 2878/2880/6862 2880/2882/6862 2893/2895/6862 +f 2880/2882/6863 2894/2896/6864 2893/2895/6865 +f 2880/2882/6863 2879/2881/6866 2894/2896/6864 +f 2879/2881/6867 2897/2899/6868 2894/2896/6869 +f 2879/2881/6867 2883/2885/6870 2897/2899/6868 +f 2883/2885/6871 2882/2884/6872 2897/2899/6873 +f 2882/2884/6872 2896/2898/6874 2897/2899/6873 +f 2882/2884/6875 2876/2878/6876 2896/2898/6877 +f 2876/2878/6876 2895/2897/6878 2896/2898/6877 +f 2876/2878/6876 2878/2880/6879 2895/2897/6878 +f 2878/2880/6880 2893/2895/6880 2895/2897/6880 +f 2877/2879/6881 2898/2900/6882 2881/2883/6883 +f 2898/2900/6882 2899/2901/6884 2881/2883/6883 +f 2876/2878/6885 2900/2902/6886 2877/2879/6887 +f 2900/2902/6886 2898/2900/6888 2877/2879/6887 +f 2881/2883/6889 2899/2901/6890 2876/2878/6891 +f 2899/2901/6890 2900/2902/6892 2876/2878/6891 +f 2899/2901/528 2898/2900/528 2900/2902/528 +f 2890/2892/6893 2885/2887/6835 2884/2886/6834 +f 2901/2903/6894 2902/2904/6894 2903/2905/6894 +f 2904/2906/6895 2902/2904/6896 2905/2907/6897 +f 2902/2904/6896 2906/2908/6898 2905/2907/6897 +f 2907/2909/6899 2908/2910/6900 2909/2911/6901 +f 2910/2912/6902 2907/2909/6903 2909/2911/6904 +f 2910/2912/6902 2911/2913/6905 2907/2909/6903 +f 2911/2913/6906 2912/2914/6906 2907/2909/6906 +f 2911/2913/6907 2913/2915/6907 2912/2914/6907 +f 2913/2915/6908 2908/2910/6908 2912/2914/6908 +f 2913/2915/6909 2914/2916/6910 2908/2910/6911 +f 2914/2916/6910 2915/2917/6912 2908/2910/6911 +f 2914/2916/6913 2909/2911/6914 2915/2917/6915 +f 2914/2916/6913 2910/2912/6916 2909/2911/6914 +f 2914/2916/6917 2913/2915/6918 2916/2918/6919 +f 2913/2915/6918 2917/2919/6920 2916/2918/6919 +f 2910/2912/6921 2918/2920/6922 2919/2921/6923 +f 2910/2912/6921 2914/2916/6917 2918/2920/6922 +f 2913/2915/6918 2920/2922/6924 2917/2919/6920 +f 2913/2915/6918 2911/2913/6925 2920/2922/6924 +f 2914/2916/6917 2916/2918/6919 2918/2920/6922 +f 2911/2913/6925 2910/2912/6921 2919/2921/6923 +f 2911/2913/6925 2919/2921/6923 2920/2922/6924 +f 2903/2905/6926 2919/2921/6926 2918/2920/6926 +f 2903/2905/6927 2902/2904/6928 2919/2921/6929 +f 2902/2904/6928 2920/2922/6930 2919/2921/6929 +f 2902/2904/6931 2904/2906/6931 2920/2922/6931 +f 2904/2906/6932 2917/2919/6933 2920/2922/6934 +f 2904/2906/6932 2905/2907/6935 2917/2919/6933 +f 2905/2907/6936 2916/2918/6937 2917/2919/6938 +f 2905/2907/6936 2906/2908/6939 2916/2918/6937 +f 2906/2908/6940 2901/2903/6940 2916/2918/6940 +f 2901/2903/6941 2918/2920/6941 2916/2918/6941 +f 2901/2903/6942 2903/2905/6942 2918/2920/6942 +f 2902/2904/6943 2921/2923/6944 2906/2908/6945 +f 2921/2923/6944 2922/2924/6946 2906/2908/6945 +f 2901/2903/6947 2923/2925/6947 2902/2904/6947 +f 2923/2925/6948 2921/2923/6948 2902/2904/6948 +f 2906/2908/6949 2922/2924/6950 2901/2903/6951 +f 2922/2924/6950 2923/2925/6952 2901/2903/6951 +f 2922/2924/528 2921/2923/528 2923/2925/528 +f 2912/2914/6953 2908/2910/6900 2907/2909/6899 +f 2915/2917/6954 2909/2911/6901 2908/2910/6900 +f 2924/2926/6955 2925/2927/6956 2926/2928/6957 +f 2924/2926/6958 2927/2929/6958 2925/2927/6958 +f 2927/2929/6959 2928/2930/6959 2925/2927/6959 +f 2927/2929/6960 2929/2931/6961 2928/2930/6962 +f 2929/2931/6961 2930/2932/6963 2928/2930/6962 +f 2929/2931/6964 2931/2933/6964 2930/2932/6964 +f 2929/2931/6965 2932/2934/6965 2931/2933/6965 +f 2933/2935/6966 2931/2933/6966 2932/2934/6966 +f 2933/2935/6967 2934/2936/6967 2931/2933/6967 +f 2933/2935/6968 2935/2937/6968 2934/2936/6968 +f 2935/2937/6969 2936/2938/6969 2934/2936/6969 +f 2935/2937/6970 2937/2939/6970 2936/2938/6970 +f 2937/2939/6971 2938/2940/6971 2936/2938/6971 +f 2937/2939/6972 2939/2941/6973 2938/2940/6974 +f 2939/2941/6973 2940/2942/6975 2938/2940/6974 +f 2939/2941/6976 2941/2943/6977 2940/2942/6978 +f 2939/2941/6976 2942/2944/6979 2941/2943/6977 +f 2924/2926/6955 2926/2928/6957 2942/2944/6980 +f 2926/2928/6981 2941/2943/6981 2942/2944/6981 +f 2929/2931/98 2927/2929/98 2935/2937/98 +f 2927/2929/98 2937/2939/98 2935/2937/98 +f 2924/2926/98 2942/2944/98 2939/2941/98 +f 2932/2934/98 2929/2931/98 2933/2935/98 +f 2929/2931/98 2935/2937/98 2933/2935/98 +f 2927/2929/98 2924/2926/98 2939/2941/98 +f 2927/2929/98 2939/2941/98 2937/2939/98 +f 2928/2930/528 2930/2932/528 2936/2938/528 +f 2930/2932/528 2934/2936/528 2936/2938/528 +f 2928/2930/528 2936/2938/528 2938/2940/528 +f 2925/2927/528 2928/2930/528 2938/2940/528 +f 2930/2932/528 2931/2933/528 2934/2936/528 +f 2925/2927/528 2938/2940/528 2940/2942/528 +f 2926/2928/528 2925/2927/528 2941/2943/528 +f 2925/2927/528 2940/2942/528 2941/2943/528 +f 2943/2945/6982 2944/2946/6982 2945/2947/6982 +f 2943/2945/6983 2946/2948/6983 2944/2946/6983 +f 2946/2948/6984 2947/2949/6984 2944/2946/6984 +f 2946/2948/6985 2948/2950/6985 2947/2949/6985 +f 2946/2948/6986 2949/2951/6986 2948/2950/6986 +f 2949/2951/6987 2950/2952/6987 2948/2950/6987 +f 2949/2951/6988 2951/2953/6988 2950/2952/6988 +f 2952/2954/6989 2950/2952/6990 2951/2953/6991 +f 2952/2954/6992 2953/2955/6992 2954/2956/6992 +f 2953/2955/6993 2955/2957/6993 2954/2956/6993 +f 2953/2955/6994 2956/2958/6995 2955/2957/6996 +f 2956/2958/6995 2957/2959/6997 2955/2957/6996 +f 2956/2958/6998 2958/2960/6999 2957/2959/7000 +f 2956/2958/6998 2959/2961/7001 2958/2960/6999 +f 2959/2961/7002 2960/2962/7002 2958/2960/7002 +f 2960/2962/7003 2961/2963/7003 2958/2960/7003 +f 2960/2962/7004 2962/2964/7004 2961/2963/7004 +f 2962/2964/7005 2963/2965/7005 2961/2963/7005 +f 2943/2945/7006 2945/2947/7006 2962/2964/7006 +f 2945/2947/7007 2963/2965/7007 2962/2964/7007 +f 2946/2948/98 2959/2961/98 2956/2958/98 +f 2949/2951/7008 2956/2958/98 2953/2955/7009 +f 2949/2951/7008 2946/2948/98 2956/2958/98 +f 2943/2945/98 2962/2964/98 2960/2962/98 +f 2949/2951/7008 2953/2955/7009 2952/2954/7010 +f 2951/2953/7011 2949/2951/7008 2952/2954/7010 +f 2946/2948/98 2943/2945/98 2960/2962/98 +f 2946/2948/98 2960/2962/98 2959/2961/98 +f 2948/2950/528 2955/2957/528 2957/2959/528 +f 2948/2950/528 2950/2952/6990 2955/2957/528 +f 2958/2960/528 2947/2949/528 2957/2959/528 +f 2947/2949/528 2948/2950/528 2957/2959/528 +f 2944/2946/528 2947/2949/528 2958/2960/528 +f 2950/2952/6990 2952/2954/6989 2954/2956/7012 +f 2955/2957/528 2950/2952/6990 2954/2956/7012 +f 2944/2946/528 2958/2960/528 2961/2963/528 +f 2945/2947/528 2944/2946/528 2963/2965/528 +f 2944/2946/528 2961/2963/528 2963/2965/528 +f 2964/2966/7013 2965/2967/7014 2966/2968/7015 +f 2964/2966/7013 2966/2968/7015 2967/2969/7016 +f 2968/2970/7017 2969/2971/7018 2970/2972/7019 +f 2965/2967/7014 2969/2971/7018 2968/2970/7017 +f 2965/2967/7014 2968/2970/7017 2966/2968/7015 +f 2969/2971/7018 2964/2966/7013 2970/2972/7019 +f 2964/2966/7013 2967/2969/7016 2970/2972/7019 +f 2971/2973/7020 2972/2974/7021 2973/2975/7022 +f 2972/2974/7021 2971/2973/7020 2974/2976/7023 +f 2975/2977/7024 2976/2978/7025 2972/2974/7026 +f 2975/2977/7024 2977/2979/7027 2976/2978/7025 +f 2977/2979/7028 2973/2975/7028 2976/2978/7028 +f 2977/2979/7029 2971/2973/7030 2973/2975/7031 +f 2977/2979/7029 2978/2980/7032 2971/2973/7030 +f 2978/2980/7033 2974/2976/7034 2971/2973/7035 +f 2978/2980/7033 2979/2981/7036 2974/2976/7034 +f 2979/2981/7037 2975/2977/7038 2974/2976/7039 +f 2975/2977/7038 2972/2974/7040 2974/2976/7039 +f 2977/2979/7041 2975/2977/7042 2980/2982/7043 +f 2975/2977/7042 2981/2983/7044 2980/2982/7043 +f 2975/2977/7042 2982/2984/7045 2981/2983/7044 +f 2975/2977/7042 2979/2981/7046 2982/2984/7045 +f 2979/2981/7046 2983/2985/7047 2982/2984/7045 +f 2979/2981/7046 2978/2980/7048 2983/2985/7047 +f 2978/2980/7048 2984/2986/7049 2983/2985/7047 +f 2978/2980/7048 2985/2987/7050 2984/2986/7049 +f 2978/2980/7048 2977/2979/7041 2985/2987/7050 +f 2977/2979/7041 2980/2982/7043 2985/2987/7050 +f 2966/2968/7051 2980/2982/7052 2981/2983/7053 +f 2966/2968/7051 2968/2970/7054 2980/2982/7052 +f 2968/2970/7055 2985/2987/7056 2980/2982/7057 +f 2968/2970/7055 2970/2972/7058 2985/2987/7056 +f 2970/2972/7059 2984/2986/7059 2985/2987/7059 +f 2970/2972/7060 2983/2985/7061 2984/2986/7062 +f 2970/2972/7060 2967/2969/7063 2983/2985/7061 +f 2967/2969/7064 2982/2984/7064 2983/2985/7064 +f 2967/2969/7065 2966/2968/7066 2982/2984/7067 +f 2966/2968/7066 2981/2983/7068 2982/2984/7067 +f 2965/2967/7069 2986/2988/7069 2969/2971/7069 +f 2987/2989/7070 2986/2988/7070 2965/2967/7070 +f 2964/2966/7071 2987/2989/7071 2965/2967/7071 +f 2969/2971/7072 2986/2988/7073 2964/2966/7074 +f 2986/2988/7073 2987/2989/7075 2964/2966/7074 +f 2976/2978/7076 2973/2975/7022 2972/2974/7021 +f 2988/2990/7077 2989/2991/7078 2990/2992/7079 +f 2989/2991/7078 2991/2993/7080 2990/2992/7079 +f 2989/2991/7081 2992/2994/7082 2991/2993/7083 +f 2992/2994/7082 2993/2995/7084 2991/2993/7083 +f 2992/2994/7085 2994/2996/7086 2993/2995/7087 +f 2994/2996/7086 2995/2997/7088 2993/2995/7087 +f 2994/2996/7089 2996/2998/7090 2995/2997/7091 +f 2996/2998/7090 2997/2999/7092 2995/2997/7091 +f 2998/3000/7093 2997/2999/7093 2996/2998/7093 +f 2998/3000/7094 2999/3001/7094 2997/2999/7094 +f 2998/3000/7095 3000/3002/7095 2999/3001/7095 +f 3000/3002/7096 3001/3003/7096 2999/3001/7096 +f 3000/3002/7097 3002/3004/7097 3001/3003/7097 +f 3002/3004/7098 3003/3005/7098 3001/3003/7098 +f 3002/3004/7099 3004/3006/7100 3003/3005/7101 +f 3002/3004/7099 3005/3007/7102 3004/3006/7100 +f 3005/3007/7103 3006/3008/7104 3004/3006/7105 +f 3005/3007/7103 3007/3009/7106 3006/3008/7104 +f 3007/3009/7107 3008/3010/7107 3006/3008/7107 +f 2988/2990/7077 2990/2992/7079 3008/3010/7108 +f 2989/2991/98 3005/3007/98 3002/3004/98 +f 2992/2994/98 2989/2991/98 3002/3004/98 +f 2994/2996/98 2992/2994/98 3000/3002/98 +f 2992/2994/98 3002/3004/98 3000/3002/98 +f 2988/2990/7109 3008/3010/7110 3007/3009/7111 +f 2989/2991/98 2988/2990/7109 3005/3007/98 +f 2988/2990/7109 3007/3009/7111 3005/3007/98 +f 2996/2998/98 3000/3002/98 2998/3000/98 +f 2996/2998/98 2994/2996/98 3000/3002/98 +f 2991/2993/528 2993/2995/528 3003/3005/528 +f 2993/2995/528 2995/2997/528 3001/3003/528 +f 2993/2995/528 3001/3003/528 3003/3005/528 +f 2991/2993/528 3003/3005/528 3004/3006/528 +f 2995/2997/528 2999/3001/528 3001/3003/528 +f 2995/2997/528 2997/2999/528 2999/3001/528 +f 2990/2992/7112 3004/3006/528 3006/3008/7113 +f 2990/2992/7112 2991/2993/528 3004/3006/528 +f 2990/2992/7112 3006/3008/7113 3008/3010/7114 +f 3009/3011/7115 3010/3012/7116 3011/3013/7117 +f 3009/3011/7118 3012/3014/7118 3010/3012/7118 +f 3012/3014/7119 3013/3015/7119 3010/3012/7119 +f 3013/3015/7120 3014/3016/7120 3010/3012/7120 +f 3013/3015/7121 3015/3017/7121 3014/3016/7121 +f 3013/3015/7122 3016/3018/7122 3015/3017/7122 +f 3016/3018/7123 3017/3019/7123 3015/3017/7123 +f 3016/3018/7124 3018/3020/7124 3017/3019/7124 +f 3019/3021/7125 3017/3019/7125 3018/3020/7125 +f 3019/3021/7126 3020/3022/7126 3021/3023/7126 +f 3020/3022/7127 3022/3024/7128 3021/3023/7129 +f 3020/3022/7127 3023/3025/7130 3022/3024/7128 +f 3023/3025/7131 3024/3026/7131 3022/3024/7131 +f 3023/3025/7132 3025/3027/7132 3024/3026/7132 +f 3025/3027/7133 3026/3028/7133 3024/3026/7133 +f 3025/3027/7134 3027/3029/7134 3026/3028/7134 +f 3027/3029/7135 3028/3030/7135 3026/3028/7135 +f 3027/3029/7136 3029/3031/7137 3028/3030/7138 +f 3027/3029/7136 3030/3032/7139 3029/3031/7137 +f 3009/3011/7115 3011/3013/7117 3030/3032/7140 +f 3011/3013/7141 3029/3031/7141 3030/3032/7141 +f 3013/3015/98 3012/3014/98 3025/3027/98 +f 3013/3015/98 3025/3027/98 3023/3025/98 +f 3016/3018/98 3013/3015/98 3023/3025/98 +f 3009/3011/98 3030/3032/98 3027/3029/98 +f 3012/3014/98 3009/3011/98 3027/3029/98 +f 3016/3018/98 3023/3025/98 3020/3022/7142 +f 3018/3020/7143 3020/3022/7142 3019/3021/7144 +f 3018/3020/7143 3016/3018/98 3020/3022/7142 +f 3012/3014/98 3027/3029/98 3025/3027/98 +f 3014/3016/528 3015/3017/528 3024/3026/528 +f 3015/3017/528 3017/3019/7145 3022/3024/528 +f 3024/3026/528 3015/3017/528 3022/3024/528 +f 3014/3016/528 3024/3026/528 3026/3028/528 +f 3010/3012/528 3014/3016/528 3026/3028/528 +f 3017/3019/7145 3019/3021/7146 3021/3023/7147 +f 3022/3024/528 3017/3019/7145 3021/3023/7147 +f 3010/3012/528 3026/3028/528 3028/3030/528 +f 3010/3012/528 3028/3030/528 3029/3031/528 +f 3011/3013/528 3010/3012/528 3029/3031/528 +f 3031/3033/7148 3032/3034/7148 3033/3035/7148 +f 3034/3036/7149 3031/3033/7149 3035/3037/7149 +f 3032/3034/7150 3034/3036/7150 3036/3038/7150 +f 3037/3039/7151 3038/3040/7152 3039/3041/7153 +f 3037/3039/7151 3039/3041/7153 3040/3042/7154 +f 3041/3043/7155 3038/3040/7155 3042/3044/7155 +f 3038/3040/7156 3037/3039/7156 3042/3044/7156 +f 3042/3044/7157 3037/3039/7157 3043/3045/7157 +f 3037/3039/7158 3040/3042/7158 3043/3045/7158 +f 3043/3045/7159 3040/3042/7159 3044/3046/7159 +f 3040/3042/7160 3039/3041/7161 3044/3046/7162 +f 3044/3046/7162 3039/3041/7161 3041/3043/7163 +f 3039/3041/7164 3038/3040/7164 3041/3043/7164 +f 3043/3045/7165 3044/3046/7166 3045/3047/7167 +f 3042/3044/7168 3046/3048/7169 3047/3049/7170 +f 3041/3043/7171 3047/3049/7170 3048/3050/7172 +f 3043/3045/7165 3045/3047/7167 3049/3051/7173 +f 3041/3043/7171 3042/3044/7168 3047/3049/7170 +f 3045/3047/7167 3044/3046/7166 3048/3050/7172 +f 3044/3046/7166 3041/3043/7171 3048/3050/7172 +f 3042/3044/7168 3043/3045/7165 3049/3051/7173 +f 3042/3044/7168 3049/3051/7173 3046/3048/7169 +f 3047/3049/7174 3046/3048/7174 3033/3035/7174 +f 3033/3035/7175 3046/3048/7176 3031/3033/7177 +f 3046/3048/7176 3049/3051/7178 3031/3033/7177 +f 3031/3033/7179 3049/3051/7179 3035/3037/7179 +f 3049/3051/7180 3045/3047/7180 3035/3037/7180 +f 3045/3047/7181 3034/3036/7181 3035/3037/7181 +f 3045/3047/7182 3048/3050/7183 3034/3036/7184 +f 3034/3036/7184 3048/3050/7183 3036/3038/7185 +f 3036/3038/7186 3048/3050/7187 3032/3034/7188 +f 3048/3050/7187 3047/3049/7189 3032/3034/7188 +f 3032/3034/7190 3047/3049/7190 3033/3035/7190 +f 3034/3036/7191 3050/3052/7192 3031/3033/7193 +f 3050/3052/7192 3051/3053/7194 3031/3033/7193 +f 3032/3034/7195 3050/3052/7195 3034/3036/7195 +f 3051/3053/7196 3050/3052/7196 3032/3034/7196 +f 3031/3033/7197 3051/3053/7197 3032/3034/7197 +f 3052/3054/7198 3053/3055/7199 3054/3056/7200 +f 3052/3054/7198 3055/3057/7201 3053/3055/7199 +f 3055/3057/7201 3056/3058/528 3053/3055/7199 +f 3057/3059/7202 3058/3060/7203 3059/3061/2513 +f 3058/3060/7203 3060/3062/2513 3059/3061/2513 +f 3061/3063/7204 3062/3064/7205 3063/3065/7206 +f 3061/3063/7204 3064/3066/7207 3065/3067/7208 +f 3061/3063/7204 3066/3068/7209 3062/3064/7205 +f 3061/3063/7204 3065/3067/7208 3066/3068/7209 +f 3067/3069/7210 3052/3054/7211 3066/3068/7212 +f 3052/3054/7211 3068/3070/7213 3066/3068/7212 +f 3052/3054/7211 3067/3069/7210 3069/3071/7214 +f 3066/3068/7212 3068/3070/7213 3062/3064/7215 +f 3070/3072/7216 3071/3073/7205 3072/3074/7206 +f 3070/3072/7216 3073/3075/7207 3074/3076/7208 +f 3070/3072/7216 3075/3077/7217 3071/3073/7205 +f 3070/3072/7216 3074/3076/7208 3075/3077/7217 +f 3076/3078/7218 3061/3063/7219 3075/3077/7220 +f 3061/3063/7219 3077/3079/7221 3075/3077/7220 +f 3061/3063/7219 3076/3078/7218 3078/3080/7222 +f 3075/3077/7220 3077/3079/7221 3071/3073/7223 +f 3079/3081/7204 3080/3082/7205 3081/3083/7206 +f 3079/3081/7204 3082/3084/7207 3083/3085/7208 +f 3079/3081/7204 3084/3086/7209 3080/3082/7205 +f 3079/3081/7204 3083/3085/7208 3084/3086/7209 +f 3085/3087/7218 3070/3072/7224 3084/3086/7225 +f 3070/3072/7224 3086/3088/7221 3084/3086/7225 +f 3070/3072/7224 3085/3087/7218 3087/3089/7222 +f 3084/3086/7225 3086/3088/7221 3080/3082/7223 +f 3088/3090/7204 3089/3091/7205 3090/3092/7206 +f 3088/3090/7204 3091/3093/7207 3092/3094/7208 +f 3088/3090/7204 3093/3095/7209 3089/3091/7205 +f 3088/3090/7204 3092/3094/7208 3093/3095/7209 +f 3094/3096/7218 3079/3081/7224 3093/3095/7225 +f 3079/3081/7224 3095/3097/7221 3093/3095/7225 +f 3079/3081/7224 3094/3096/7218 3096/3098/7222 +f 3093/3095/7225 3095/3097/7221 3089/3091/7223 +f 3097/3099/7226 3098/3100/7227 3099/3101/7228 +f 3097/3099/7226 3100/3102/528 3101/3103/7229 +f 3097/3099/7226 3102/3104/7230 3098/3100/7227 +f 3097/3099/7226 3101/3103/7229 3102/3104/7230 +f 3103/3105/7218 3088/3090/7224 3102/3104/7225 +f 3088/3090/7224 3104/3106/7221 3102/3104/7225 +f 3088/3090/7224 3103/3105/7218 3105/3107/7222 +f 3102/3104/7225 3104/3106/7221 3098/3100/7223 +f 3106/3108/7231 3107/3109/7232 3108/3110/7233 +f 3106/3108/7231 3109/3111/1243 3110/3112/7234 +f 3106/3108/7231 3111/3113/7235 3107/3109/7232 +f 3106/3108/7231 3110/3112/7234 3111/3113/7235 +f 3112/3114/7236 3113/3115/7237 3111/3113/7238 +f 3113/3115/7237 3114/3116/7239 3111/3113/7238 +f 3111/3113/7238 3114/3116/7239 3107/3109/7215 +f 3053/3055/7240 3057/3059/7241 3059/3061/7242 +f 3053/3055/7240 3056/3058/7243 3057/3059/7241 +f 3066/3068/7244 3065/3067/7244 3067/3069/7244 +f 3075/3077/7245 3074/3076/7245 3076/3078/7245 +f 3084/3086/7244 3083/3085/7244 3085/3087/7244 +f 3093/3095/7244 3092/3094/7244 3094/3096/7244 +f 3102/3104/7244 3101/3103/7244 3103/3105/7244 +f 3111/3113/7246 3110/3112/7246 3112/3114/7246 +f 3115/3117/528 3054/3056/528 3116/3118/528 +f 3117/3119/528 3115/3117/528 3116/3118/528 +f 3118/3120/7247 3119/3121/528 3120/3122/528 +f 3121/3123/528 3118/3120/7247 3120/3122/528 +f 3121/3123/528 3122/3124/7248 3118/3120/7247 +f 3122/3124/7248 3123/3125/7249 3118/3120/7247 +f 3124/3126/7250 3125/3127/7251 3126/3128/7252 +f 3125/3127/7251 3123/3125/7249 3126/3128/7252 +f 3123/3125/7249 3122/3124/7248 3126/3128/7252 +f 3127/3129/7253 3125/3127/7251 3124/3126/7250 +f 3128/3130/7254 3129/3131/7254 3060/3062/7254 +f 3128/3130/7254 3130/3132/7255 3129/3131/7254 +f 3131/3133/7256 3132/3134/98 3133/3135/98 +f 3134/3136/7257 3135/3137/7258 3136/3138/7259 +f 3137/3139/98 3134/3136/7257 3138/3140/98 +f 3134/3136/7257 3136/3138/7259 3138/3140/98 +f 3136/3138/7259 3135/3137/7258 3139/3141/7260 +f 3135/3137/7258 3140/3142/7261 3139/3141/7260 +f 3135/3137/7258 3131/3133/7256 3140/3142/7261 +f 3131/3133/7256 3133/3135/98 3140/3142/7261 +f 3141/3143/7262 3063/3065/7263 3142/3144/7264 +f 3143/3145/7265 3141/3143/7262 3142/3144/7264 +f 3144/3146/528 3145/3147/528 3146/3148/528 +f 3147/3149/528 3144/3146/528 3146/3148/528 +f 3147/3149/528 3148/3150/528 3144/3146/528 +f 3148/3150/528 3149/3151/528 3144/3146/528 +f 3150/3152/528 3149/3151/528 3151/3153/528 +f 3149/3151/528 3148/3150/528 3151/3153/528 +f 3152/3154/528 3149/3151/528 3150/3152/528 +f 3153/3155/7266 3142/3144/7267 3068/3070/7268 +f 3153/3155/7266 3143/3145/7269 3142/3144/7267 +f 3154/3156/7270 3123/3125/7271 3155/3157/7272 +f 3156/3158/98 3154/3156/7270 3157/3159/98 +f 3154/3156/7270 3155/3157/7272 3157/3159/98 +f 3155/3157/7272 3123/3125/7271 3158/3160/7273 +f 3123/3125/7271 3125/3127/7274 3158/3160/7273 +f 3125/3127/7274 3159/3161/7275 3158/3160/7273 +f 3125/3127/7274 3160/3162/7276 3159/3161/7275 +f 3160/3162/7276 3161/3163/98 3159/3161/7275 +f 3162/3164/7262 3072/3074/7263 3163/3165/7264 +f 3164/3166/7265 3162/3164/7262 3163/3165/7264 +f 3165/3167/7277 3166/3168/7278 3167/3169/7279 +f 3168/3170/528 3165/3167/7277 3167/3169/7279 +f 3168/3170/528 3169/3171/7280 3165/3167/7277 +f 3169/3171/7280 3170/3172/7281 3165/3167/7277 +f 3171/3173/528 3172/3174/7282 3173/3175/7283 +f 3172/3174/7282 3170/3172/7281 3173/3175/7283 +f 3170/3172/7281 3169/3171/7280 3173/3175/7283 +f 3174/3176/528 3172/3174/7282 3171/3173/528 +f 3077/3079/7284 3164/3166/7285 3163/3165/7286 +f 3077/3079/7284 3175/3177/7287 3164/3166/7285 +f 3176/3178/98 3177/3179/98 3178/3180/98 +f 3176/3178/98 3179/3181/98 3180/3182/98 +f 3176/3178/98 3178/3180/98 3179/3181/98 +f 3178/3180/98 3177/3179/98 3181/3183/98 +f 3177/3179/98 3182/3184/98 3181/3183/98 +f 3182/3184/98 3183/3185/98 3181/3183/98 +f 3182/3184/98 3184/3186/98 3183/3185/98 +f 3184/3186/98 3185/3187/98 3183/3185/98 +f 3186/3188/7262 3081/3083/7263 3187/3189/7264 +f 3188/3190/7265 3186/3188/7262 3187/3189/7264 +f 3189/3191/528 3190/3192/528 3191/3193/528 +f 3189/3191/528 3192/3194/528 3190/3192/528 +f 3189/3191/528 3193/3195/528 3192/3194/528 +f 3193/3195/528 3194/3196/7288 3192/3194/528 +f 3195/3197/7289 3196/3198/7290 3197/3199/7291 +f 3196/3198/7290 3194/3196/7288 3197/3199/7291 +f 3194/3196/7288 3193/3195/528 3197/3199/7291 +f 3198/3200/7292 3196/3198/7290 3195/3197/7289 +f 3086/3088/7284 3188/3190/7285 3187/3189/7286 +f 3086/3088/7284 3199/3201/7287 3188/3190/7285 +f 3200/3202/7293 3170/3172/7294 3201/3203/7295 +f 3170/3172/7296 3202/3204/7296 3201/3203/7296 +f 3200/3202/7293 3203/3205/7297 3166/3168/7298 +f 3200/3202/7293 3201/3203/7295 3203/3205/7297 +f 3201/3203/98 3202/3204/98 3204/3206/98 +f 3202/3204/98 3205/3207/98 3204/3206/98 +f 3202/3204/98 3206/3208/98 3205/3207/98 +f 3206/3208/98 3207/3209/98 3205/3207/98 +f 3208/3210/7262 3090/3092/7263 3209/3211/7264 +f 3210/3212/7265 3208/3210/7262 3209/3211/7264 +f 3211/3213/528 3212/3214/528 3213/3215/528 +f 3211/3213/528 3214/3216/528 3212/3214/528 +f 3211/3213/528 3215/3217/528 3214/3216/528 +f 3215/3217/528 3216/3218/528 3214/3216/528 +f 3217/3219/528 3216/3218/528 3218/3220/528 +f 3216/3218/528 3215/3217/528 3218/3220/528 +f 3219/3221/528 3216/3218/528 3217/3219/528 +f 3095/3097/7284 3210/3212/7285 3209/3211/7286 +f 3095/3097/7284 3220/3222/7287 3210/3212/7285 +f 3221/3223/98 3222/3224/7299 3223/3225/98 +f 3221/3223/98 3224/3226/98 3225/3227/98 +f 3221/3223/98 3223/3225/98 3224/3226/98 +f 3223/3225/98 3222/3224/7299 3226/3228/7300 +f 3222/3224/7299 3196/3198/7301 3226/3228/7300 +f 3196/3198/7301 3227/3229/7302 3226/3228/7300 +f 3196/3198/7301 3228/3230/7303 3227/3229/7302 +f 3228/3230/7303 3229/3231/98 3227/3229/7302 +f 3230/3232/7262 3099/3101/7263 3231/3233/7264 +f 3232/3234/7265 3230/3232/7262 3231/3233/7264 +f 3233/3235/7304 3234/3236/7305 3235/3237/528 +f 3233/3235/7304 3236/3238/7306 3234/3236/7305 +f 3233/3235/7304 3237/3239/7307 3236/3238/7306 +f 3237/3239/7307 3238/3240/7308 3236/3238/7306 +f 3239/3241/528 3238/3240/7308 3240/3242/528 +f 3238/3240/7308 3237/3239/7307 3240/3242/528 +f 3241/3243/528 3238/3240/7308 3239/3241/528 +f 3104/3106/7284 3232/3234/7285 3231/3233/7286 +f 3104/3106/7284 3242/3244/7287 3232/3234/7285 +f 3243/3245/98 3244/3246/98 3245/3247/98 +f 3243/3245/98 3246/3248/98 3247/3249/98 +f 3243/3245/98 3245/3247/98 3246/3248/98 +f 3245/3247/98 3244/3246/98 3248/3250/98 +f 3244/3246/98 3249/3251/98 3248/3250/98 +f 3249/3251/98 3250/3252/98 3248/3250/98 +f 3249/3251/98 3251/3253/98 3250/3252/98 +f 3251/3253/98 3252/3254/98 3250/3252/98 +f 3253/3255/7309 3108/3110/7310 3254/3256/7311 +f 3255/3257/7312 3253/3255/7309 3254/3256/7311 +f 3256/3258/7313 3109/3111/7314 3257/3259/7315 +f 3258/3260/7316 3259/3261/528 3260/3262/528 +f 3261/3263/528 3258/3260/7316 3260/3262/528 +f 3261/3263/528 3262/3264/7317 3258/3260/7316 +f 3262/3264/7317 3263/3265/7318 3258/3260/7316 +f 3264/3266/7319 3257/3259/7320 3265/3267/7321 +f 3257/3259/7320 3263/3265/7318 3265/3267/7321 +f 3263/3265/7318 3262/3264/7317 3265/3267/7321 +f 3257/3259/7320 3264/3266/7319 3256/3258/7322 +f 3266/3268/7266 3254/3256/7267 3114/3116/7268 +f 3266/3268/7266 3255/3257/7269 3254/3256/7267 +f 3267/3269/7323 3256/3258/7324 3268/3270/7325 +f 3236/3238/7326 3269/3271/7327 3270/3272/7328 +f 3271/3273/7329 3236/3238/7326 3272/3274/7330 +f 3236/3238/7326 3270/3272/7328 3272/3274/7330 +f 3270/3272/7328 3269/3271/7327 3273/3275/98 +f 3269/3271/7327 3267/3269/7323 3273/3275/98 +f 3267/3269/7323 3274/3276/98 3273/3275/98 +f 3267/3269/7323 3268/3270/7325 3274/3276/98 +f 3124/3126/7331 3140/3142/7332 3133/3135/7333 +f 3124/3126/7331 3126/3128/7334 3140/3142/7332 +f 3126/3128/7335 3139/3141/7335 3140/3142/7335 +f 3126/3128/7336 3122/3124/7336 3139/3141/7336 +f 3122/3124/7337 3136/3138/7337 3139/3141/7337 +f 3122/3124/7338 3121/3123/7338 3136/3138/7338 +f 3121/3123/7339 3138/3140/7340 3136/3138/7341 +f 3121/3123/7339 3120/3122/7342 3138/3140/7340 +f 3150/3152/7343 3159/3161/7343 3161/3163/7343 +f 3150/3152/7344 3151/3153/7344 3159/3161/7344 +f 3151/3153/7345 3158/3160/7273 3159/3161/7275 +f 3151/3153/7346 3148/3150/7346 3158/3160/7346 +f 3148/3150/7347 3155/3157/7272 3158/3160/7273 +f 3148/3150/7348 3147/3149/7348 3155/3157/7348 +f 3147/3149/7349 3157/3159/7349 3155/3157/7349 +f 3147/3149/7350 3146/3148/7350 3157/3159/7350 +f 3171/3173/7343 3183/3185/7343 3185/3187/7343 +f 3171/3173/7344 3173/3175/7344 3183/3185/7344 +f 3173/3175/7345 3181/3183/7345 3183/3185/7345 +f 3173/3175/7346 3169/3171/7346 3181/3183/7346 +f 3169/3171/7347 3178/3180/7347 3181/3183/7347 +f 3169/3171/7348 3168/3170/7348 3178/3180/7348 +f 3168/3170/7349 3179/3181/7349 3178/3180/7349 +f 3168/3170/7350 3167/3169/7350 3179/3181/7350 +f 3195/3197/7343 3205/3207/7343 3207/3209/7343 +f 3195/3197/7344 3197/3199/7344 3205/3207/7344 +f 3197/3199/7345 3204/3206/7345 3205/3207/7345 +f 3197/3199/7346 3193/3195/7346 3204/3206/7346 +f 3193/3195/7347 3201/3203/7347 3204/3206/7347 +f 3193/3195/7348 3189/3191/7348 3201/3203/7348 +f 3189/3191/7349 3203/3205/7349 3201/3203/7349 +f 3189/3191/7350 3191/3193/7350 3203/3205/7350 +f 3217/3219/7343 3227/3229/7343 3229/3231/7343 +f 3217/3219/7344 3218/3220/7344 3227/3229/7344 +f 3218/3220/7345 3226/3228/7300 3227/3229/7302 +f 3218/3220/7346 3215/3217/7346 3226/3228/7346 +f 3215/3217/7347 3223/3225/7347 3226/3228/7347 +f 3215/3217/7348 3211/3213/7348 3223/3225/7348 +f 3211/3213/7349 3224/3226/7349 3223/3225/7349 +f 3211/3213/7350 3213/3215/7350 3224/3226/7350 +f 3239/3241/7343 3250/3252/7343 3252/3254/7343 +f 3239/3241/7344 3240/3242/7344 3250/3252/7344 +f 3240/3242/7345 3248/3250/7345 3250/3252/7345 +f 3240/3242/7346 3237/3239/7346 3248/3250/7346 +f 3237/3239/7347 3245/3247/7347 3248/3250/7347 +f 3237/3239/7307 3233/3235/7304 3245/3247/7348 +f 3233/3235/7349 3246/3248/7349 3245/3247/7349 +f 3233/3235/7350 3235/3237/7350 3246/3248/7350 +f 3264/3266/7343 3274/3276/7343 3268/3270/7343 +f 3264/3266/7344 3265/3267/7344 3274/3276/7344 +f 3265/3267/7345 3273/3275/7345 3274/3276/7345 +f 3265/3267/7321 3262/3264/7317 3273/3275/7346 +f 3262/3264/7347 3270/3272/7347 3273/3275/7347 +f 3262/3264/7348 3261/3263/7348 3270/3272/7348 +f 3261/3263/7349 3272/3274/7349 3270/3272/7349 +f 3261/3263/7350 3260/3262/7350 3272/3274/7350 +f 3117/3119/7351 3129/3131/7352 3130/3132/7353 +f 3117/3119/7351 3116/3118/7354 3129/3131/7352 +f 3275/3277/7355 3276/3278/7356 3277/3279/7357 +f 3276/3278/7356 3278/3280/7358 3277/3279/7357 +f 3279/3281/7359 3280/3282/7360 3281/3283/7361 +f 3280/3282/7360 3282/3284/7362 3281/3283/7361 +f 3283/3285/7363 3284/3286/7364 3285/3287/7365 +f 3284/3286/7364 3286/3288/7366 3285/3287/7365 +f 3284/3286/7364 3287/3289/7367 3286/3288/7366 +f 3287/3289/7367 3288/3290/528 3286/3288/7366 +f 3287/3289/7367 3289/3291/528 3288/3290/528 +f 3289/3291/528 3290/3292/528 3288/3290/528 +f 3283/3285/7363 3285/3287/7365 3291/3293/528 +f 3292/3294/98 3293/3295/98 3294/3296/98 +f 3295/3297/7368 3137/3139/7369 3296/3298/7370 +f 3294/3296/98 3297/3299/7371 3298/3300/98 +f 3297/3299/7371 3299/3301/7372 3298/3300/98 +f 3297/3299/7371 3295/3297/7368 3299/3301/7372 +f 3295/3297/7368 3300/3302/7373 3299/3301/7372 +f 3295/3297/7368 3296/3298/7370 3300/3302/7373 +f 3294/3296/98 3298/3300/98 3292/3294/98 +f 3291/3293/7374 3300/3302/7375 3296/3298/7376 +f 3291/3293/7374 3285/3287/7377 3300/3302/7375 +f 3285/3287/7377 3299/3301/7378 3300/3302/7375 +f 3285/3287/7377 3286/3288/7379 3299/3301/7378 +f 3286/3288/7379 3298/3300/7380 3299/3301/7378 +f 3286/3288/7379 3288/3290/7381 3298/3300/7380 +f 3288/3290/7382 3292/3294/7383 3298/3300/7384 +f 3288/3290/7382 3290/3292/7385 3292/3294/7383 +f 3301/3303/7386 3302/3304/7387 3303/3305/528 +f 3304/3306/7388 3305/3307/7389 3306/3308/7390 +f 3305/3307/7389 3307/3309/7391 3306/3308/7390 +f 3305/3307/7389 3308/3310/7392 3307/3309/7391 +f 3308/3310/7392 3309/3311/7393 3307/3309/7391 +f 3308/3310/7392 3302/3304/7387 3309/3311/7393 +f 3302/3304/7387 3310/3312/7394 3309/3311/7393 +f 3302/3304/7387 3301/3303/7386 3310/3312/7394 +f 3304/3306/7388 3306/3308/7390 3311/3313/7395 +f 3312/3314/7396 3313/3315/98 3314/3316/7397 +f 3314/3316/7397 3309/3311/7398 3310/3312/7399 +f 3314/3316/7397 3315/3317/7400 3309/3311/7398 +f 3315/3317/7400 3307/3309/7401 3309/3311/7398 +f 3315/3317/7400 3284/3286/7402 3307/3309/7401 +f 3284/3286/7402 3306/3308/7403 3307/3309/7401 +f 3284/3286/7402 3316/3318/7404 3306/3308/7403 +f 3316/3318/7404 3317/3319/7405 3306/3308/7403 +f 3314/3316/7397 3310/3312/7399 3312/3314/7396 +f 3311/3313/7406 3306/3308/7406 3317/3319/7406 +f 3310/3312/7407 3301/3303/7407 3312/3314/7407 +f 3318/3320/7408 3319/3321/7409 3320/3322/7410 +f 3319/3321/7411 3321/3323/7412 3320/3322/7413 +f 3319/3321/7411 3322/3324/7414 3321/3323/7412 +f 3322/3324/7414 3323/3325/7415 3321/3323/7412 +f 3322/3324/7414 3324/3326/7416 3323/3325/7415 +f 3322/3324/7414 3325/3327/7417 3324/3326/7416 +f 3325/3327/7417 3326/3328/7418 3324/3326/7416 +f 3327/3329/7419 3318/3320/7408 3328/3330/7420 +f 3318/3320/7408 3320/3322/7410 3328/3330/7420 +f 3329/3331/7421 3330/3332/98 3331/3333/7422 +f 3331/3333/7422 3323/3325/7423 3324/3326/7424 +f 3331/3333/7422 3308/3310/7425 3323/3325/7423 +f 3308/3310/7425 3321/3323/7426 3323/3325/7423 +f 3308/3310/7425 3305/3307/7427 3321/3323/7426 +f 3305/3307/7427 3320/3322/7428 3321/3323/7426 +f 3305/3307/7427 3332/3334/7429 3320/3322/7428 +f 3332/3334/7429 3333/3335/7430 3320/3322/7428 +f 3331/3333/7422 3324/3326/7424 3329/3331/7421 +f 3328/3330/7431 3320/3322/7431 3333/3335/7431 +f 3324/3326/7432 3326/3328/7432 3329/3331/7432 +f 3334/3336/7433 3335/3337/7434 3336/3338/7435 +f 3337/3339/7436 3338/3340/7437 3339/3341/7438 +f 3338/3340/7437 3340/3342/7439 3339/3341/7438 +f 3338/3340/7437 3341/3343/7440 3340/3342/7439 +f 3341/3343/7440 3342/3344/7441 3340/3342/7439 +f 3341/3343/7440 3335/3337/7434 3342/3344/7441 +f 3335/3337/7434 3343/3345/7442 3342/3344/7441 +f 3335/3337/7434 3334/3336/7433 3343/3345/7442 +f 3344/3346/7443 3337/3339/7436 3345/3347/7444 +f 3337/3339/7436 3339/3341/7438 3345/3347/7444 +f 3346/3348/7421 3347/3349/98 3348/3350/7445 +f 3348/3350/7445 3342/3344/7446 3343/3345/7424 +f 3348/3350/7445 3349/3351/7447 3342/3344/7446 +f 3349/3351/7447 3340/3342/7448 3342/3344/7446 +f 3349/3351/7447 3318/3320/7449 3340/3342/7448 +f 3318/3320/7449 3339/3341/7450 3340/3342/7448 +f 3318/3320/7449 3350/3352/7451 3339/3341/7450 +f 3350/3352/7451 3351/3353/7430 3339/3341/7450 +f 3348/3350/7445 3343/3345/7424 3346/3348/7421 +f 3345/3347/7431 3339/3341/7431 3351/3353/7431 +f 3343/3345/7432 3334/3336/7432 3346/3348/7432 +f 3352/3354/7386 3353/3355/7452 3354/3356/528 +f 3355/3357/7453 3356/3358/7454 3357/3359/7455 +f 3356/3358/7456 3358/3360/7457 3357/3359/7458 +f 3356/3358/7456 3359/3361/7459 3358/3360/7457 +f 3356/3358/7456 3353/3355/7452 3359/3361/7459 +f 3353/3355/7452 3360/3362/7394 3359/3361/7459 +f 3353/3355/7452 3352/3354/7386 3360/3362/7394 +f 3361/3363/7419 3355/3357/7453 3362/3364/7420 +f 3355/3357/7453 3357/3359/7455 3362/3364/7420 +f 3363/3365/7460 3364/3366/7461 3335/3337/7462 +f 3335/3337/7462 3359/3361/7463 3360/3362/7464 +f 3335/3337/7462 3341/3343/7465 3359/3361/7463 +f 3341/3343/7465 3358/3360/7466 3359/3361/7463 +f 3341/3343/7465 3338/3340/7467 3358/3360/7466 +f 3338/3340/7467 3337/3339/7468 3358/3360/7466 +f 3337/3339/7468 3357/3359/7469 3358/3360/7466 +f 3337/3339/7468 3365/3367/7470 3357/3359/7469 +f 3365/3367/7470 3366/3368/7430 3357/3359/7469 +f 3335/3337/7462 3360/3362/7464 3363/3365/7460 +f 3362/3364/7431 3357/3359/7431 3366/3368/7431 +f 3360/3362/7471 3352/3354/7471 3363/3365/7471 +f 3367/3369/7472 3368/3370/7473 3369/3371/528 +f 3370/3372/7388 3371/3373/7474 3372/3374/7475 +f 3371/3373/7474 3373/3375/7391 3372/3374/7475 +f 3371/3373/7474 3374/3376/7392 3373/3375/7391 +f 3374/3376/7392 3375/3377/7393 3373/3375/7391 +f 3374/3376/7392 3368/3370/7473 3375/3377/7393 +f 3368/3370/7473 3376/3378/7394 3375/3377/7393 +f 3368/3370/7473 3367/3369/7472 3376/3378/7394 +f 3370/3372/7388 3372/3374/7475 3377/3379/7395 +f 3378/3380/7421 3379/3381/98 3380/3382/7445 +f 3380/3382/7445 3375/3377/7476 3376/3378/7424 +f 3380/3382/7445 3381/3383/7447 3375/3377/7476 +f 3381/3383/7447 3373/3375/7448 3375/3377/7476 +f 3381/3383/7447 3355/3357/7449 3373/3375/7448 +f 3355/3357/7449 3372/3374/7450 3373/3375/7448 +f 3355/3357/7449 3382/3384/7451 3372/3374/7450 +f 3382/3384/7451 3383/3385/7430 3372/3374/7450 +f 3380/3382/7445 3376/3378/7424 3378/3380/7421 +f 3377/3379/7431 3372/3374/7431 3383/3385/7431 +f 3376/3378/7432 3367/3369/7432 3378/3380/7432 +f 3384/3386/7477 3385/3387/7478 3386/3388/528 +f 3387/3389/7479 3388/3390/7480 3389/3391/7481 +f 3387/3389/7479 3390/3392/7482 3388/3390/7480 +f 3390/3392/7482 3391/3393/7483 3388/3390/7480 +f 3390/3392/7482 3385/3387/7478 3391/3393/7483 +f 3385/3387/7478 3392/3394/7484 3391/3393/7483 +f 3385/3387/7478 3384/3386/7477 3392/3394/7484 +f 3393/3395/528 3387/3389/7479 3394/3396/7485 +f 3387/3389/7479 3389/3391/7481 3394/3396/7485 +f 3395/3397/7421 3396/3398/98 3397/3399/7486 +f 3397/3399/7486 3391/3393/7423 3392/3394/7424 +f 3397/3399/7486 3374/3376/7425 3391/3393/7423 +f 3374/3376/7425 3388/3390/7426 3391/3393/7423 +f 3374/3376/7425 3371/3373/7487 3388/3390/7426 +f 3371/3373/7487 3389/3391/7428 3388/3390/7426 +f 3371/3373/7487 3398/3400/7429 3389/3391/7428 +f 3398/3400/7429 3399/3401/7430 3389/3391/7428 +f 3397/3399/7486 3392/3394/7424 3395/3397/7421 +f 3394/3396/7488 3389/3391/7488 3399/3401/7488 +f 3392/3394/7432 3384/3386/7432 3395/3397/7432 +f 3277/3279/7357 3400/3402/7489 3275/3277/7355 +f 3277/3279/7357 3401/3403/7490 3400/3402/7489 +f 3401/3403/7490 3402/3404/7491 3400/3402/7489 +f 3402/3404/7491 3403/3405/7492 3400/3402/7489 +f 3402/3404/7491 3404/3406/7493 3403/3405/7492 +f 3404/3406/7493 3405/3407/7494 3403/3405/7492 +f 3404/3406/7493 3406/3408/7495 3405/3407/7494 +f 3387/3389/7496 3393/3395/7496 3407/3409/7496 +f 3393/3395/7497 3408/3410/7497 3407/3409/7497 +f 3393/3395/7498 3259/3261/7499 3408/3410/7500 +f 3259/3261/7501 3258/3260/7501 3408/3410/7501 +f 3387/3389/7479 3407/3409/7502 3390/3392/7482 +f 3385/3387/7503 3390/3392/7503 3409/3411/7503 +f 3409/3411/7504 3410/3412/7504 3385/3387/7504 +f 3410/3412/7505 3386/3388/7506 3385/3387/7507 +f 3410/3412/7505 3411/3413/7508 3386/3388/7506 +f 3411/3413/7509 3410/3412/7509 3412/3414/7509 +f 3413/3415/7510 3414/3416/7511 3415/3417/7512 +f 3416/3418/7513 3413/3415/7510 3415/3417/7512 +f 3415/3417/7514 3417/3419/7514 3416/3418/7514 +f 3417/3419/7515 3418/3420/7516 3253/3255/7517 +f 3108/3110/7518 3418/3420/7518 3419/3421/7518 +f 3108/3110/7519 3253/3255/7519 3418/3420/7519 +f 3419/3421/7520 3106/3108/7520 3108/3110/7520 +f 3109/3111/7521 3106/3108/7522 3420/3422/7523 +f 3106/3108/7522 3419/3421/7524 3420/3422/7523 +f 3257/3259/7525 3109/3111/7525 3420/3422/7525 +f 3258/3260/7526 3421/3423/7526 3408/3410/7526 +f 3258/3260/7527 3263/3265/7528 3421/3423/7529 +f 3257/3259/7530 3420/3422/7530 3263/3265/7530 +f 3398/3400/7531 3234/3236/7532 3271/3273/7533 +f 3234/3236/7532 3398/3400/7531 3370/3372/7534 +f 3398/3400/7531 3371/3373/7535 3370/3372/7534 +f 3374/3376/7536 3397/3399/7536 3368/3370/7536 +f 3397/3399/7537 3369/3371/7538 3368/3370/7539 +f 3397/3399/7537 3396/3398/7540 3369/3371/7538 +f 3396/3398/7540 3422/3424/7541 3369/3371/7538 +f 3423/3425/7542 3424/3426/7543 3425/3427/7544 +f 3425/3427/7544 3424/3426/7543 3426/3428/7545 +f 3424/3426/7543 3427/3429/7546 3426/3428/7545 +f 3427/3429/7547 3428/3430/7547 3426/3428/7547 +f 3427/3429/7548 3266/3268/7548 3428/3430/7548 +f 3266/3268/7549 3230/3232/7550 3428/3430/7551 +f 3266/3268/7549 3099/3101/7552 3230/3232/7550 +f 3266/3268/7549 3114/3116/7553 3099/3101/7552 +f 3114/3116/7553 3097/3099/7554 3099/3101/7552 +f 3114/3116/7555 3113/3115/7555 3097/3099/7555 +f 3113/3115/7556 3256/3258/7556 3097/3099/7556 +f 3256/3258/7557 3100/3102/7558 3097/3099/7559 +f 3234/3236/7532 3236/3238/7560 3271/3273/7533 +f 3236/3238/7326 3238/3240/7561 3269/3271/7327 +f 3238/3240/7562 3267/3269/7562 3269/3271/7562 +f 3238/3240/7563 3241/3243/7563 3267/3269/7563 +f 3241/3243/7564 3256/3258/7557 3267/3269/7565 +f 3241/3243/7564 3100/3102/7558 3256/3258/7557 +f 3382/3384/7566 3212/3214/7567 3247/3249/7568 +f 3212/3214/7567 3382/3384/7566 3361/3363/7569 +f 3382/3384/7566 3355/3357/7570 3361/3363/7569 +f 3355/3357/7453 3381/3383/7571 3356/3358/7454 +f 3381/3383/7572 3353/3355/7572 3356/3358/7572 +f 3381/3383/7573 3380/3382/7573 3353/3355/7573 +f 3380/3382/7574 3354/3356/7575 3353/3355/7576 +f 3380/3382/7574 3379/3381/7577 3354/3356/7575 +f 3379/3381/7577 3429/3431/7578 3354/3356/7575 +f 3430/3432/7579 3431/3433/7580 3432/3434/7581 +f 3431/3433/7580 3430/3432/7579 3433/3435/7582 +f 3430/3432/7579 3434/3436/7583 3433/3435/7582 +f 3434/3436/7547 3435/3437/7547 3433/3435/7547 +f 3434/3436/7584 3242/3244/7585 3435/3437/7586 +f 3242/3244/7585 3208/3210/7587 3435/3437/7586 +f 3242/3244/7585 3104/3106/7588 3208/3210/7587 +f 3104/3106/7589 3090/3092/7590 3208/3210/7591 +f 3104/3106/7589 3088/3090/7592 3090/3092/7590 +f 3105/3107/7593 3091/3093/7594 3088/3090/7595 +f 3212/3214/7567 3243/3245/7596 3247/3249/7568 +f 3212/3214/7597 3214/3216/7597 3243/3245/7597 +f 3214/3216/7598 3244/3246/7598 3243/3245/7598 +f 3214/3216/7599 3216/3218/7599 3244/3246/7599 +f 3216/3218/7600 3249/3251/7600 3244/3246/7600 +f 3216/3218/7601 3251/3253/7602 3249/3251/7603 +f 3216/3218/7601 3219/3221/7604 3251/3253/7602 +f 3219/3221/7604 3105/3107/7593 3251/3253/7602 +f 3219/3221/7604 3091/3093/7594 3105/3107/7593 +f 3365/3367/7605 3190/3192/7606 3225/3227/7607 +f 3190/3192/7606 3365/3367/7605 3344/3346/7608 +f 3365/3367/7605 3337/3339/7609 3344/3346/7608 +f 3364/3366/7610 3336/3338/7611 3335/3337/7612 +f 3364/3366/7610 3436/3438/7613 3336/3338/7611 +f 3436/3438/7613 3437/3439/7614 3336/3338/7611 +f 3438/3440/7615 3439/3441/7543 3440/3442/7544 +f 3440/3442/7544 3439/3441/7543 3441/3443/7616 +f 3439/3441/7543 3442/3444/7617 3441/3443/7616 +f 3442/3444/7618 3443/3445/7618 3441/3443/7618 +f 3442/3444/7619 3220/3222/7620 3443/3445/7621 +f 3220/3222/7620 3186/3188/7587 3443/3445/7621 +f 3220/3222/7620 3095/3097/7588 3186/3188/7587 +f 3095/3097/7589 3081/3083/7590 3186/3188/7591 +f 3095/3097/7589 3079/3081/7592 3081/3083/7590 +f 3096/3098/7622 3082/3084/7594 3079/3081/7595 +f 3190/3192/7606 3221/3223/7596 3225/3227/7607 +f 3190/3192/7623 3192/3194/7623 3221/3223/7623 +f 3192/3194/7624 3222/3224/7624 3221/3223/7624 +f 3192/3194/7625 3194/3196/7625 3222/3224/7625 +f 3194/3196/7626 3196/3198/7626 3222/3224/7626 +f 3196/3198/7627 3198/3200/7628 3228/3230/7629 +f 3198/3200/7628 3096/3098/7622 3228/3230/7629 +f 3198/3200/7628 3082/3084/7594 3096/3098/7622 +f 3202/3204/7630 3170/3172/7630 3172/3174/7630 +f 3170/3172/7631 3200/3202/7631 3165/3167/7631 +f 3200/3202/7632 3166/3168/7632 3165/3167/7632 +f 3166/3168/7633 3350/3352/7634 3327/3329/7635 +f 3350/3352/7634 3318/3320/7570 3327/3329/7635 +f 3318/3320/7408 3349/3351/7636 3319/3321/7409 +f 3349/3351/7637 3322/3324/7637 3319/3321/7637 +f 3349/3351/7638 3348/3350/7638 3322/3324/7638 +f 3348/3350/7639 3325/3327/7639 3322/3324/7639 +f 3348/3350/7640 3347/3349/7641 3325/3327/7642 +f 3347/3349/7641 3444/3446/7643 3325/3327/7642 +f 3347/3349/7641 3445/3447/7644 3444/3446/7643 +f 3446/3448/7542 3447/3449/7543 3448/3450/7544 +f 3448/3450/7544 3447/3449/7543 3449/3451/7545 +f 3447/3449/7543 3450/3452/7546 3449/3451/7545 +f 3450/3452/7547 3451/3453/7547 3449/3451/7547 +f 3450/3452/7584 3199/3201/7585 3451/3453/7586 +f 3199/3201/7585 3162/3164/7587 3451/3453/7586 +f 3199/3201/7585 3086/3088/7588 3162/3164/7587 +f 3086/3088/7589 3072/3074/7590 3162/3164/7591 +f 3086/3088/7589 3070/3072/7592 3072/3074/7590 +f 3087/3089/7622 3073/3075/7594 3070/3072/7595 +f 3087/3089/7622 3174/3176/7645 3073/3075/7594 +f 3087/3089/7622 3206/3208/7646 3174/3176/7645 +f 3206/3208/7646 3172/3174/7647 3174/3176/7645 +f 3206/3208/7648 3202/3204/7648 3172/3174/7648 +f 3332/3334/7649 3145/3147/7650 3180/3182/7651 +f 3145/3147/7650 3332/3334/7649 3304/3306/7652 +f 3332/3334/7649 3305/3307/7535 3304/3306/7652 +f 3308/3310/7653 3331/3333/7653 3302/3304/7653 +f 3331/3333/7654 3303/3305/7655 3302/3304/7656 +f 3331/3333/7654 3330/3332/7577 3303/3305/7655 +f 3330/3332/7577 3452/3454/7578 3303/3305/7655 +f 3453/3455/7542 3454/3456/7543 3455/3457/7544 +f 3455/3457/7544 3454/3456/7543 3456/3458/7545 +f 3454/3456/7543 3457/3459/7546 3456/3458/7545 +f 3457/3459/7547 3458/3460/7547 3456/3458/7547 +f 3457/3459/7584 3175/3177/7585 3458/3460/7657 +f 3175/3177/7585 3141/3143/7658 3458/3460/7657 +f 3175/3177/7585 3077/3079/7588 3141/3143/7658 +f 3077/3079/7589 3063/3065/7590 3141/3143/7591 +f 3077/3079/7589 3061/3063/7592 3063/3065/7590 +f 3078/3080/7622 3064/3066/7594 3061/3063/7595 +f 3145/3147/7650 3176/3178/7659 3180/3182/7651 +f 3145/3147/7660 3144/3146/7660 3176/3178/7660 +f 3144/3146/7661 3177/3179/7661 3176/3178/7661 +f 3144/3146/7662 3149/3151/7662 3177/3179/7662 +f 3149/3151/7600 3182/3184/7600 3177/3179/7600 +f 3149/3151/7663 3184/3186/7602 3182/3184/7664 +f 3149/3151/7663 3152/3154/7604 3184/3186/7602 +f 3152/3154/7604 3078/3080/7622 3184/3186/7602 +f 3152/3154/7604 3064/3066/7594 3078/3080/7622 +f 3119/3121/7665 3316/3318/7666 3283/3285/7667 +f 3316/3318/7666 3284/3286/7668 3283/3285/7667 +f 3315/3317/7400 3287/3289/7669 3284/3286/7402 +f 3315/3317/7670 3314/3316/7670 3287/3289/7670 +f 3314/3316/7671 3289/3291/7671 3287/3289/7671 +f 3314/3316/7672 3313/3315/7673 3289/3291/7674 +f 3313/3315/7673 3459/3461/7675 3289/3291/7674 +f 3459/3461/7675 3460/3462/7676 3289/3291/7674 +f 3459/3461/7675 3461/3463/7677 3460/3462/7676 +f 3462/3464/7615 3463/3465/7543 3464/3466/7678 +f 3464/3466/7678 3463/3465/7543 3465/3467/7679 +f 3463/3465/7543 3466/3468/7546 3465/3467/7679 +f 3466/3468/7547 3467/3469/7547 3465/3467/7547 +f 3466/3468/7680 3153/3155/7680 3467/3469/7680 +f 3153/3155/7549 3115/3117/7681 3467/3469/7682 +f 3153/3155/7549 3054/3056/7683 3115/3117/7681 +f 3153/3155/7549 3068/3070/7684 3054/3056/7683 +f 3068/3070/7684 3052/3054/7685 3054/3056/7683 +f 3052/3054/7686 3069/3071/7687 3055/3057/7688 +f 3069/3071/7687 3127/3129/7689 3055/3057/7688 +f 3119/3121/7690 3156/3158/7691 3316/3318/7692 +f 3119/3121/7690 3118/3120/7693 3156/3158/7691 +f 3118/3120/7694 3154/3156/7694 3156/3158/7694 +f 3118/3120/7695 3123/3125/7695 3154/3156/7695 +f 3125/3127/7696 3127/3129/7697 3160/3162/7698 +f 3127/3129/7697 3069/3071/7699 3160/3162/7698 +f 3468/3470/7700 3469/3471/7701 3470/3472/7702 +f 3468/3470/7700 3471/3473/7703 3469/3471/7701 +f 3471/3473/7703 3472/3474/7704 3469/3471/7701 +f 3471/3473/7703 3473/3475/7705 3472/3474/7704 +f 3473/3475/7705 3474/3476/7706 3472/3474/7704 +f 3473/3475/7705 3475/3477/7707 3474/3476/7706 +f 3475/3477/7707 3476/3478/7708 3474/3476/7706 +f 3475/3477/7707 3477/3479/7709 3476/3478/7708 +f 3475/3477/7707 3478/3480/7710 3477/3479/7709 +f 3479/3481/7711 3480/3482/7712 3481/3483/7713 +f 3480/3482/7712 3482/3484/7714 3481/3483/7713 +f 3483/3485/7715 3484/3486/7716 3485/3487/7717 +f 3483/3485/7715 3486/3488/7718 3484/3486/7716 +f 3409/3411/7719 3474/3476/7720 3476/3478/7721 +f 3400/3402/7722 3263/3265/7528 3275/3277/7723 +f 3275/3277/7723 3263/3265/7528 3420/3422/7724 +f 3409/3411/7719 3476/3478/7721 3477/3479/7725 +f 3409/3411/7719 3477/3479/7725 3410/3412/7726 +f 3275/3277/7723 3420/3422/7724 3276/3278/7727 +f 3487/3489/7728 3276/3278/7727 3420/3422/7724 +f 3410/3412/7726 3477/3479/7725 3488/3490/7729 +f 3410/3412/7726 3488/3490/7729 3489/3491/7730 +f 3487/3489/7728 3420/3422/7724 3279/3281/7731 +f 3420/3422/7724 3419/3421/7732 3279/3281/7731 +f 3410/3412/7726 3489/3491/7730 3490/3492/7733 +f 3410/3412/7726 3490/3492/7733 3412/3414/7734 +f 3412/3414/7734 3490/3492/7733 3491/3493/7735 +f 3399/3401/7736 3398/3400/7737 3394/3396/7738 +f 3398/3400/7737 3393/3395/7739 3394/3396/7738 +f 3398/3400/7531 3271/3273/7533 3393/3395/7498 +f 3271/3273/7533 3259/3261/7499 3393/3395/7498 +f 3271/3273/7740 3272/3274/7741 3259/3261/7742 +f 3272/3274/7741 3260/3262/7743 3259/3261/7742 +f 3383/3385/7736 3382/3384/7744 3377/3379/7745 +f 3382/3384/7744 3370/3372/7746 3377/3379/7745 +f 3382/3384/7747 3247/3249/7748 3370/3372/7534 +f 3247/3249/7748 3234/3236/7532 3370/3372/7534 +f 3247/3249/7749 3246/3248/7750 3234/3236/7751 +f 3246/3248/7750 3235/3237/7752 3234/3236/7751 +f 3366/3368/7736 3365/3367/7753 3362/3364/7754 +f 3365/3367/7753 3361/3363/7755 3362/3364/7754 +f 3365/3367/7605 3225/3227/7607 3361/3363/7569 +f 3225/3227/7607 3212/3214/7567 3361/3363/7569 +f 3225/3227/7749 3224/3226/7750 3212/3214/7751 +f 3224/3226/7750 3213/3215/7752 3212/3214/7751 +f 3351/3353/7736 3350/3352/7753 3345/3347/7754 +f 3350/3352/7753 3344/3346/7755 3345/3347/7754 +f 3350/3352/7634 3166/3168/7633 3344/3346/7608 +f 3166/3168/7633 3190/3192/7606 3344/3346/7608 +f 3166/3168/7756 3203/3205/7757 3190/3192/7758 +f 3203/3205/7757 3191/3193/7752 3190/3192/7758 +f 3333/3335/7736 3332/3334/7753 3328/3330/7754 +f 3332/3334/7753 3327/3329/7755 3328/3330/7754 +f 3332/3334/7649 3180/3182/7651 3327/3329/7635 +f 3180/3182/7651 3166/3168/7633 3327/3329/7635 +f 3180/3182/7759 3179/3181/7760 3166/3168/7761 +f 3179/3181/7760 3167/3169/7762 3166/3168/7761 +f 3317/3319/7763 3304/3306/7764 3311/3313/7765 +f 3317/3319/7763 3316/3318/7766 3304/3306/7764 +f 3316/3318/7767 3145/3147/7650 3304/3306/7652 +f 3316/3318/7692 3156/3158/7691 3145/3147/7768 +f 3156/3158/7769 3157/3159/7770 3145/3147/7771 +f 3157/3159/7770 3146/3148/7772 3145/3147/7771 +f 3296/3298/7773 3283/3285/7773 3291/3293/7773 +f 3296/3298/7774 3137/3139/7774 3283/3285/7774 +f 3137/3139/7775 3119/3121/7665 3283/3285/7667 +f 3137/3139/7776 3138/3140/7777 3119/3121/7778 +f 3138/3140/7777 3120/3122/7779 3119/3121/7778 +f 3268/3270/7780 3256/3258/7780 3264/3266/7780 +f 3256/3258/7313 3113/3115/7781 3109/3111/7314 +f 3113/3115/7782 3112/3114/7783 3109/3111/7784 +f 3112/3114/7783 3110/3112/7785 3109/3111/7784 +f 3252/3254/7786 3251/3253/7787 3239/3241/7788 +f 3251/3253/7787 3241/3243/7789 3239/3241/7788 +f 3251/3253/7602 3105/3107/7593 3241/3243/7564 +f 3105/3107/7593 3100/3102/7558 3241/3243/7564 +f 3105/3107/7790 3103/3105/7791 3100/3102/7792 +f 3103/3105/7791 3101/3103/7793 3100/3102/7792 +f 3229/3231/7786 3228/3230/7787 3217/3219/7788 +f 3228/3230/7787 3219/3221/7789 3217/3219/7788 +f 3228/3230/7629 3096/3098/7622 3219/3221/7604 +f 3096/3098/7622 3091/3093/7594 3219/3221/7604 +f 3096/3098/7790 3094/3096/7791 3091/3093/7792 +f 3094/3096/7791 3092/3094/7793 3091/3093/7792 +f 3207/3209/7786 3206/3208/7787 3195/3197/7788 +f 3206/3208/7787 3198/3200/7789 3195/3197/7788 +f 3206/3208/7646 3087/3089/7622 3198/3200/7628 +f 3087/3089/7622 3082/3084/7594 3198/3200/7628 +f 3087/3089/7790 3085/3087/7791 3082/3084/7792 +f 3085/3087/7791 3083/3085/7793 3082/3084/7792 +f 3185/3187/7786 3184/3186/7787 3171/3173/7788 +f 3184/3186/7787 3174/3176/7789 3171/3173/7788 +f 3184/3186/7602 3078/3080/7622 3174/3176/7645 +f 3078/3080/7622 3073/3075/7594 3174/3176/7645 +f 3078/3080/7790 3076/3078/7791 3073/3075/7792 +f 3076/3078/7791 3074/3076/7793 3073/3075/7792 +f 3161/3163/7786 3160/3162/7787 3150/3152/7788 +f 3160/3162/7787 3152/3154/7789 3150/3152/7788 +f 3160/3162/7698 3069/3071/7699 3152/3154/7604 +f 3069/3071/7699 3064/3066/7594 3152/3154/7604 +f 3069/3071/7790 3067/3069/7791 3064/3066/7792 +f 3067/3069/7791 3065/3067/7793 3064/3066/7792 +f 3133/3135/7794 3132/3134/7795 3124/3126/7796 +f 3132/3134/7795 3127/3129/7797 3124/3126/7796 +f 3132/3134/7798 3058/3060/7799 3127/3129/7689 +f 3058/3060/7799 3055/3057/7688 3127/3129/7689 +f 3058/3060/7800 3057/3059/7801 3055/3057/7802 +f 3057/3059/7801 3056/3058/7803 3055/3057/7802 +f 3114/3116/7804 3108/3110/7804 3107/3109/7804 +f 3114/3116/7805 3254/3256/7805 3108/3110/7805 +f 3104/3106/7806 3099/3101/7806 3098/3100/7806 +f 3104/3106/7807 3231/3233/7807 3099/3101/7807 +f 3095/3097/7806 3090/3092/7806 3089/3091/7806 +f 3095/3097/7808 3209/3211/7808 3090/3092/7808 +f 3086/3088/7806 3081/3083/7806 3080/3082/7806 +f 3086/3088/7808 3187/3189/7808 3081/3083/7808 +f 3077/3079/7806 3072/3074/7806 3071/3073/7806 +f 3077/3079/7808 3163/3165/7808 3072/3074/7808 +f 3068/3070/7809 3063/3065/7809 3062/3064/7809 +f 3068/3070/7810 3142/3144/7810 3063/3065/7810 +f 3059/3061/7811 3060/3062/7812 3053/3055/7813 +f 3060/3062/7812 3054/3056/7814 3053/3055/7813 +f 3060/3062/7815 3129/3131/7816 3054/3056/7817 +f 3129/3131/7816 3116/3118/7818 3054/3056/7817 +f 3485/3487/7819 3468/3470/7700 3483/3485/7820 +f 3468/3470/7700 3470/3472/7702 3483/3485/7820 +f 3406/3408/7495 3484/3486/7821 3405/3407/7494 +f 3484/3486/7821 3486/3488/7822 3405/3407/7494 +f 3487/3489/7823 3279/3281/7359 3492/3494/7824 +f 3279/3281/7359 3281/3283/7361 3492/3494/7824 +f 3276/3278/7356 3487/3489/7825 3278/3280/7358 +f 3487/3489/7825 3492/3494/7826 3278/3280/7358 +f 3280/3282/7827 3482/3484/7714 3282/3284/7828 +f 3280/3282/7827 3481/3483/7829 3482/3484/7714 +f 3493/3495/7830 3494/3496/7831 3495/3497/7832 +f 3496/3498/7833 3494/3496/7831 3493/3495/7830 +f 3495/3497/7832 3497/3499/7834 3493/3495/7830 +f 3498/3500/7835 3499/3501/7836 3500/3502/7837 +f 3501/3503/7838 3478/3480/7839 3498/3500/7835 +f 3501/3503/7838 3498/3500/7835 3500/3502/7837 +f 3412/3414/7734 3491/3493/7735 3502/3504/7840 +f 3280/3282/7841 3419/3421/7732 3481/3483/7842 +f 3481/3483/7842 3419/3421/7732 3418/3420/7843 +f 3412/3414/7734 3502/3504/7840 3503/3505/7844 +f 3503/3505/7844 3502/3504/7840 3504/3506/7845 +f 3481/3483/7842 3418/3420/7843 3479/3481/7846 +f 3479/3481/7846 3418/3420/7843 3505/3507/7847 +f 3503/3505/7844 3504/3506/7845 3414/3416/7848 +f 3419/3421/7732 3280/3282/7841 3279/3281/7731 +f 3414/3416/7848 3506/3508/7849 3415/3417/7850 +f 3506/3508/7849 3507/3509/7851 3415/3417/7850 +f 3415/3417/7850 3507/3509/7851 3508/3510/7852 +f 3505/3507/7847 3417/3419/7853 3415/3417/7850 +f 3415/3417/7850 3508/3510/7852 3505/3507/7847 +f 3505/3507/7847 3418/3420/7843 3417/3419/7853 +f 3408/3410/7854 3486/3488/7855 3483/3485/7856 +f 3405/3407/7857 3486/3488/7855 3408/3410/7854 +f 3408/3410/7854 3483/3485/7856 3470/3472/7858 +f 3408/3410/7854 3470/3472/7858 3407/3409/7859 +f 3405/3407/7857 3408/3410/7854 3403/3405/7860 +f 3407/3409/7859 3470/3472/7858 3469/3471/7861 +f 3407/3409/7859 3469/3471/7861 3472/3474/7862 +f 3504/3506/7845 3506/3508/7849 3414/3416/7848 +f 3408/3410/7854 3421/3423/7529 3403/3405/7860 +f 3407/3409/7859 3472/3474/7862 3390/3392/7863 +f 3390/3392/7863 3472/3474/7862 3474/3476/7720 +f 3403/3405/7860 3421/3423/7529 3400/3402/7722 +f 3400/3402/7722 3421/3423/7529 3263/3265/7528 +f 3390/3392/7863 3474/3476/7720 3409/3411/7719 +f 3465/3467/528 3467/3469/528 3509/3511/528 +f 3465/3467/528 3509/3511/528 3510/3512/528 +f 3511/3513/98 3512/3514/98 3513/3515/1245 +f 3511/3513/98 3513/3515/1245 3128/3130/1245 +f 3513/3515/1245 3512/3514/98 3514/3516/98 +f 3456/3458/7864 3458/3460/7865 3515/3517/7866 +f 3458/3460/7865 3516/3518/7867 3515/3517/7866 +f 3456/3458/7864 3515/3517/7866 3517/3519/7868 +f 3518/3520/7869 3466/3468/7870 3463/3465/98 +f 3466/3468/7870 3515/3517/7871 3516/3518/7872 +f 3466/3468/7870 3516/3518/7872 3153/3155/7873 +f 3515/3517/7871 3466/3468/7870 3518/3520/7869 +f 3449/3451/528 3451/3453/7874 3519/3521/7875 +f 3451/3453/7874 3520/3522/7876 3519/3521/7875 +f 3521/3523/7877 3457/3459/7878 3454/3456/98 +f 3457/3459/7878 3521/3523/7877 3520/3522/7879 +f 3457/3459/7878 3520/3522/7879 3175/3177/7880 +f 3441/3443/7864 3443/3445/7881 3522/3524/7882 +f 3443/3445/7881 3523/3525/7883 3522/3524/7882 +f 3441/3443/7864 3522/3524/7882 3524/3526/7868 +f 3525/3527/7869 3450/3452/7884 3447/3449/98 +f 3450/3452/7884 3522/3524/7885 3523/3525/7886 +f 3450/3452/7884 3523/3525/7886 3199/3201/7887 +f 3522/3524/7885 3450/3452/7884 3525/3527/7869 +f 3433/3435/528 3435/3437/7874 3526/3528/7875 +f 3435/3437/7874 3527/3529/7888 3526/3528/7875 +f 3528/3530/7877 3442/3444/7889 3439/3441/98 +f 3442/3444/7889 3528/3530/7877 3527/3529/7879 +f 3442/3444/7889 3527/3529/7879 3220/3222/7880 +f 3426/3428/528 3428/3430/7874 3529/3531/7875 +f 3428/3430/7874 3530/3532/7876 3529/3531/7875 +f 3531/3533/7890 3434/3436/7891 3430/3432/98 +f 3434/3436/7891 3531/3533/7890 3530/3532/7879 +f 3434/3436/7891 3530/3532/7879 3242/3244/7880 +f 3416/3418/7892 3417/3419/7893 3532/3534/7894 +f 3417/3419/7893 3533/3535/7895 3532/3534/7894 +f 3534/3536/98 3427/3429/98 3424/3426/98 +f 3427/3429/98 3535/3537/98 3266/3268/98 +f 3535/3537/98 3427/3429/98 3534/3536/98 +f 3510/3512/7896 3513/3515/7897 3514/3516/7898 +f 3510/3512/7896 3509/3511/7899 3513/3515/7897 +f 3517/3519/7900 3515/3517/7900 3518/3520/7900 +f 3519/3521/7901 3520/3522/7901 3521/3523/7901 +f 3524/3526/7900 3522/3524/7900 3525/3527/7900 +f 3526/3528/7901 3527/3529/7901 3528/3530/7901 +f 3529/3531/7901 3530/3532/7901 3531/3533/7901 +f 3532/3534/7902 3535/3537/7902 3534/3536/7902 +f 3532/3534/7903 3533/3535/7903 3535/3537/7903 +f 3536/3538/7904 3462/3464/7905 3464/3466/7906 +f 3461/3463/7907 3537/3539/7908 3460/3462/7909 +f 3537/3539/7908 3461/3463/7907 3538/3540/7910 +f 3461/3463/7907 3539/3541/7911 3538/3540/7910 +f 3539/3541/7911 3540/3542/7912 3538/3540/7910 +f 3539/3541/7911 3462/3464/7905 3540/3542/7912 +f 3462/3464/7905 3541/3543/7913 3540/3542/7912 +f 3462/3464/7905 3536/3538/7904 3541/3543/7913 +f 3542/3544/98 3543/3545/98 3544/3546/98 +f 3545/3547/7914 3546/3548/98 3547/3549/7915 +f 3546/3548/98 3548/3550/98 3547/3549/7915 +f 3546/3548/98 3543/3545/98 3548/3550/98 +f 3543/3545/98 3549/3551/98 3548/3550/98 +f 3543/3545/98 3542/3544/98 3549/3551/98 +f 3545/3547/7914 3547/3549/7915 3550/3552/7916 +f 3551/3553/7904 3453/3455/7917 3455/3457/7906 +f 3303/3305/7918 3452/3454/7919 3552/3554/7920 +f 3552/3554/7920 3452/3454/7919 3553/3555/7921 +f 3452/3454/7919 3554/3556/7922 3553/3555/7921 +f 3554/3556/7922 3555/3557/7923 3553/3555/7921 +f 3554/3556/7922 3453/3455/7917 3555/3557/7923 +f 3453/3455/7917 3556/3558/7924 3555/3557/7923 +f 3453/3455/7917 3551/3553/7904 3556/3558/7924 +f 3557/3559/7925 3461/3463/7926 3459/3461/7927 +f 3462/3464/7928 3558/3560/7929 3463/3465/7930 +f 3462/3464/7928 3539/3541/7931 3559/3561/7932 +f 3539/3541/7931 3560/3562/7933 3559/3561/7932 +f 3539/3541/7931 3461/3463/7926 3560/3562/7933 +f 3461/3463/7926 3561/3563/7934 3560/3562/7933 +f 3461/3463/7926 3557/3559/7925 3561/3563/7934 +f 3462/3464/7928 3559/3561/7932 3558/3560/7929 +f 3562/3564/7904 3446/3448/7905 3448/3450/7906 +f 3445/3447/7907 3563/3565/7908 3444/3446/7909 +f 3563/3565/7908 3445/3447/7907 3564/3566/7935 +f 3445/3447/7907 3565/3567/7911 3564/3566/7935 +f 3565/3567/7911 3566/3568/7923 3564/3566/7935 +f 3565/3567/7911 3446/3448/7905 3566/3568/7923 +f 3446/3448/7905 3567/3569/7936 3566/3568/7923 +f 3446/3448/7905 3562/3564/7904 3567/3569/7936 +f 3568/3570/7937 3452/3454/7938 3330/3332/7939 +f 3453/3455/7928 3569/3571/7929 3454/3456/7930 +f 3453/3455/7928 3554/3556/7940 3570/3572/7932 +f 3554/3556/7940 3571/3573/7941 3570/3572/7932 +f 3554/3556/7940 3452/3454/7938 3571/3573/7941 +f 3452/3454/7938 3572/3574/7942 3571/3573/7941 +f 3452/3454/7938 3568/3570/7937 3572/3574/7942 +f 3453/3455/7928 3570/3572/7932 3569/3571/7929 +f 3573/3575/7904 3438/3440/7905 3440/3442/7906 +f 3437/3439/7943 3574/3576/7944 3336/3338/7945 +f 3574/3576/7944 3437/3439/7943 3575/3577/7921 +f 3437/3439/7943 3576/3578/7922 3575/3577/7921 +f 3576/3578/7922 3577/3579/7923 3575/3577/7921 +f 3576/3578/7922 3438/3440/7905 3577/3579/7923 +f 3438/3440/7905 3578/3580/7936 3577/3579/7923 +f 3438/3440/7905 3573/3575/7904 3578/3580/7936 +f 3579/3581/7946 3445/3447/7947 3347/3349/7948 +f 3446/3448/7928 3580/3582/7929 3447/3449/7930 +f 3446/3448/7928 3565/3567/7931 3581/3583/7932 +f 3565/3567/7931 3582/3584/7949 3581/3583/7932 +f 3565/3567/7931 3445/3447/7947 3582/3584/7949 +f 3445/3447/7947 3583/3585/7934 3582/3584/7949 +f 3445/3447/7947 3579/3581/7946 3583/3585/7934 +f 3446/3448/7928 3581/3583/7932 3580/3582/7929 +f 3584/3586/7950 3432/3434/7951 3431/3433/7952 +f 3354/3356/7918 3429/3431/7919 3585/3587/7920 +f 3585/3587/7920 3429/3431/7919 3586/3588/7921 +f 3429/3431/7919 3587/3589/7953 3586/3588/7921 +f 3587/3589/7953 3588/3590/7954 3586/3588/7921 +f 3587/3589/7953 3432/3434/7951 3588/3590/7954 +f 3432/3434/7951 3589/3591/7955 3588/3590/7954 +f 3432/3434/7951 3584/3586/7950 3589/3591/7955 +f 3590/3592/7956 3437/3439/7957 3436/3438/7958 +f 3438/3440/7928 3591/3593/7929 3439/3441/7930 +f 3438/3440/7928 3576/3578/7940 3592/3594/7932 +f 3576/3578/7940 3593/3595/7941 3592/3594/7932 +f 3576/3578/7940 3437/3439/7957 3593/3595/7941 +f 3437/3439/7957 3594/3596/7942 3593/3595/7941 +f 3437/3439/7957 3590/3592/7956 3594/3596/7942 +f 3438/3440/7928 3592/3594/7932 3591/3593/7929 +f 3595/3597/7904 3423/3425/7905 3425/3427/7906 +f 3422/3424/7943 3596/3598/7944 3369/3371/7945 +f 3596/3598/7944 3422/3424/7943 3597/3599/7921 +f 3422/3424/7943 3598/3600/7922 3597/3599/7921 +f 3598/3600/7922 3599/3601/7923 3597/3599/7921 +f 3598/3600/7922 3423/3425/7905 3599/3601/7923 +f 3423/3425/7905 3600/3602/7936 3599/3601/7923 +f 3423/3425/7905 3595/3597/7904 3600/3602/7936 +f 3601/3603/7937 3429/3431/7938 3379/3381/7939 +f 3430/3432/7959 3432/3434/7960 3602/3604/7961 +f 3432/3434/7960 3587/3589/7962 3603/3605/7963 +f 3587/3589/7962 3604/3606/7941 3603/3605/7963 +f 3587/3589/7962 3429/3431/7938 3604/3606/7941 +f 3429/3431/7938 3605/3607/7942 3604/3606/7941 +f 3429/3431/7938 3601/3603/7937 3605/3607/7942 +f 3432/3434/7960 3603/3605/7963 3602/3604/7961 +f 3606/3608/7964 3414/3416/7965 3413/3415/7966 +f 3607/3609/7967 3411/3413/7968 3608/3610/7969 +f 3411/3413/7968 3412/3414/7970 3608/3610/7969 +f 3412/3414/7970 3503/3505/7971 3608/3610/7969 +f 3503/3505/7971 3609/3611/7972 3608/3610/7969 +f 3503/3505/7971 3414/3416/7965 3609/3611/7972 +f 3414/3416/7965 3610/3612/7973 3609/3611/7972 +f 3414/3416/7965 3606/3608/7964 3610/3612/7973 +f 3611/3613/7937 3422/3424/7938 3396/3398/7939 +f 3423/3425/7928 3612/3614/7929 3424/3426/7930 +f 3423/3425/7928 3598/3600/7940 3613/3615/7932 +f 3598/3600/7940 3614/3616/7941 3613/3615/7932 +f 3598/3600/7940 3422/3424/7938 3614/3616/7941 +f 3422/3424/7938 3615/3617/7942 3614/3616/7941 +f 3422/3424/7938 3611/3613/7937 3615/3617/7942 +f 3423/3425/7928 3613/3615/7932 3612/3614/7929 +f 3537/3539/7974 3549/3551/7975 3542/3544/7976 +f 3537/3539/7974 3538/3540/7977 3549/3551/7975 +f 3538/3540/7978 3548/3550/7978 3549/3551/7978 +f 3538/3540/7979 3540/3542/7979 3548/3550/7979 +f 3540/3542/7980 3547/3549/7980 3548/3550/7980 +f 3540/3542/7981 3541/3543/7981 3547/3549/7981 +f 3541/3543/7982 3550/3552/7983 3547/3549/7984 +f 3541/3543/7982 3536/3538/7985 3550/3552/7983 +f 3552/3554/7986 3561/3563/7986 3557/3559/7986 +f 3552/3554/7987 3553/3555/7987 3561/3563/7987 +f 3553/3555/7988 3560/3562/7933 3561/3563/7934 +f 3553/3555/7921 3555/3557/7923 3560/3562/7989 +f 3555/3557/7990 3559/3561/7932 3560/3562/7933 +f 3555/3557/7923 3556/3558/7924 3559/3561/7991 +f 3556/3558/7992 3558/3560/7992 3559/3561/7992 +f 3556/3558/7993 3551/3553/7993 3558/3560/7993 +f 3563/3565/7994 3572/3574/7994 3568/3570/7994 +f 3563/3565/7987 3564/3566/7987 3572/3574/7987 +f 3564/3566/7988 3571/3573/7941 3572/3574/7942 +f 3564/3566/7935 3566/3568/7923 3571/3573/7989 +f 3566/3568/7990 3570/3572/7932 3571/3573/7941 +f 3566/3568/7923 3567/3569/7936 3570/3572/7995 +f 3567/3569/7996 3569/3571/7996 3570/3572/7996 +f 3567/3569/7993 3562/3564/7993 3569/3571/7993 +f 3574/3576/7994 3583/3585/7994 3579/3581/7994 +f 3574/3576/7997 3575/3577/7997 3583/3585/7997 +f 3575/3577/7998 3582/3584/7949 3583/3585/7934 +f 3575/3577/7921 3577/3579/7923 3582/3584/7989 +f 3577/3579/7990 3581/3583/7932 3582/3584/7949 +f 3577/3579/7923 3578/3580/7936 3581/3583/7995 +f 3578/3580/7996 3580/3582/7996 3581/3583/7996 +f 3578/3580/7993 3573/3575/7993 3580/3582/7993 +f 3585/3587/7986 3594/3596/7986 3590/3592/7986 +f 3585/3587/7987 3586/3588/7987 3594/3596/7987 +f 3586/3588/7988 3593/3595/7941 3594/3596/7942 +f 3586/3588/7921 3588/3590/7954 3593/3595/7989 +f 3588/3590/7990 3592/3594/7932 3593/3595/7941 +f 3588/3590/7954 3589/3591/7955 3592/3594/7995 +f 3589/3591/7996 3591/3593/7996 3592/3594/7996 +f 3589/3591/7993 3584/3586/7993 3591/3593/7993 +f 3596/3598/7994 3605/3607/7994 3601/3603/7994 +f 3596/3598/7997 3597/3599/7997 3605/3607/7997 +f 3597/3599/7998 3604/3606/7941 3605/3607/7942 +f 3597/3599/7921 3599/3601/7923 3604/3606/7989 +f 3599/3601/7990 3603/3605/7963 3604/3606/7941 +f 3599/3601/7923 3600/3602/7936 3603/3605/7995 +f 3600/3602/7996 3602/3604/7996 3603/3605/7996 +f 3600/3602/7999 3595/3597/7999 3602/3604/7999 +f 3607/3609/7994 3615/3617/7994 3611/3613/7994 +f 3607/3609/7987 3608/3610/7987 3615/3617/7987 +f 3608/3610/7988 3614/3616/7941 3615/3617/7942 +f 3608/3610/7969 3609/3611/7972 3614/3616/7989 +f 3609/3611/7990 3613/3615/7932 3614/3616/7941 +f 3609/3611/7972 3610/3612/7973 3613/3615/7991 +f 3610/3612/7992 3612/3614/7992 3613/3615/7992 +f 3610/3612/7993 3606/3608/7993 3612/3614/7993 +f 3616/3618/8000 3496/3498/8001 3504/3506/8002 +f 3496/3498/8001 3506/3508/8003 3504/3506/8002 +f 3497/3499/8004 3617/3619/8005 3508/3510/8006 +f 3617/3619/8005 3505/3507/8007 3508/3510/8006 +f 3499/3501/8008 3491/3493/8009 3490/3492/8010 +f 3499/3501/8008 3618/3620/8011 3491/3493/8009 +f 3618/3620/8011 3502/3504/8012 3491/3493/8009 +f 3618/3620/8011 3619/3621/8013 3502/3504/8012 +f 3619/3621/8013 3504/3506/8002 3502/3504/8012 +f 3619/3621/8013 3616/3618/8000 3504/3506/8002 +f 3489/3491/8014 3501/3503/8015 3500/3502/8016 +f 3489/3491/8014 3488/3490/8017 3501/3503/8015 +f 3611/3613/8018 3396/3398/8019 3607/3609/8020 +f 3396/3398/8019 3411/3413/8021 3607/3609/8020 +f 3396/3398/8022 3386/3388/7506 3411/3413/7508 +f 3396/3398/8023 3395/3397/8023 3386/3388/8023 +f 3395/3397/8024 3384/3386/8024 3386/3388/8024 +f 3601/3603/8018 3379/3381/8025 3596/3598/8026 +f 3379/3381/8025 3369/3371/8027 3596/3598/8026 +f 3379/3381/8028 3378/3380/8029 3369/3371/8030 +f 3378/3380/8029 3367/3369/8031 3369/3371/8030 +f 3590/3592/8032 3436/3438/8032 3585/3587/8032 +f 3436/3438/8033 3354/3356/8033 3585/3587/8033 +f 3436/3438/8034 3364/3366/8034 3354/3356/8034 +f 3364/3366/8035 3352/3354/8035 3354/3356/8035 +f 3364/3366/8036 3363/3365/8036 3352/3354/8036 +f 3579/3581/8018 3347/3349/8025 3574/3576/8026 +f 3347/3349/8025 3336/3338/8027 3574/3576/8026 +f 3347/3349/8028 3346/3348/8029 3336/3338/8030 +f 3346/3348/8029 3334/3336/8031 3336/3338/8030 +f 3568/3570/8018 3330/3332/8037 3563/3565/8038 +f 3330/3332/8037 3444/3446/8039 3563/3565/8038 +f 3330/3332/8040 3325/3327/8040 3444/3446/8040 +f 3330/3332/8041 3329/3331/8041 3325/3327/8041 +f 3329/3331/8042 3326/3328/8042 3325/3327/8042 +f 3557/3559/8032 3459/3461/8032 3552/3554/8032 +f 3459/3461/8033 3303/3305/8033 3552/3554/8033 +f 3459/3461/7675 3313/3315/7673 3303/3305/8034 +f 3313/3315/8035 3301/3303/8035 3303/3305/8035 +f 3313/3315/8036 3312/3314/8036 3301/3303/8036 +f 3542/3544/8043 3544/3546/8044 3537/3539/8045 +f 3544/3546/8044 3460/3462/8046 3537/3539/8045 +f 3544/3546/8047 3293/3295/8048 3460/3462/7676 +f 3293/3295/8048 3289/3291/7674 3460/3462/7676 +f 3293/3295/8049 3290/3292/8050 3289/3291/8051 +f 3293/3295/8049 3292/3294/8052 3290/3292/8050 +f 3534/3536/8053 3424/3426/8053 3532/3534/8053 +f 3424/3426/8054 3416/3418/8054 3532/3534/8054 +f 3424/3426/8055 3413/3415/8055 3416/3418/8055 +f 3424/3426/8056 3612/3614/8057 3413/3415/8058 +f 3612/3614/8057 3606/3608/8059 3413/3415/8058 +f 3531/3533/8060 3430/3432/8060 3529/3531/8060 +f 3430/3432/8061 3426/3428/8061 3529/3531/8061 +f 3430/3432/8062 3425/3427/8062 3426/3428/8062 +f 3430/3432/8063 3602/3604/8063 3425/3427/8063 +f 3602/3604/8064 3595/3597/8064 3425/3427/8064 +f 3528/3530/8065 3439/3441/8065 3526/3528/8065 +f 3439/3441/8066 3433/3435/8066 3526/3528/8066 +f 3439/3441/8067 3431/3433/8067 3433/3435/8067 +f 3439/3441/8068 3591/3593/8069 3431/3433/8070 +f 3591/3593/8069 3584/3586/8071 3431/3433/8070 +f 3525/3527/8072 3447/3449/8072 3524/3526/8072 +f 3447/3449/8073 3441/3443/8073 3524/3526/8073 +f 3447/3449/8074 3440/3442/8074 3441/3443/8074 +f 3447/3449/8068 3580/3582/8069 3440/3442/8070 +f 3580/3582/8069 3573/3575/8071 3440/3442/8070 +f 3521/3523/8065 3454/3456/8065 3519/3521/8065 +f 3454/3456/8066 3449/3451/8066 3519/3521/8066 +f 3454/3456/8067 3448/3450/8067 3449/3451/8067 +f 3454/3456/8068 3569/3571/8069 3448/3450/8070 +f 3569/3571/8069 3562/3564/8071 3448/3450/8070 +f 3518/3520/8072 3463/3465/8072 3517/3519/8072 +f 3463/3465/8073 3456/3458/8073 3517/3519/8073 +f 3463/3465/8074 3455/3457/8074 3456/3458/8074 +f 3463/3465/8068 3558/3560/8069 3455/3457/8070 +f 3558/3560/8069 3551/3553/8071 3455/3457/8070 +f 3514/3516/8075 3512/3514/8076 3510/3512/8077 +f 3512/3514/8076 3465/3467/8078 3510/3512/8077 +f 3512/3514/8079 3545/3547/8080 3465/3467/7679 +f 3545/3547/8080 3464/3466/7678 3465/3467/7679 +f 3545/3547/8081 3550/3552/8082 3464/3466/8083 +f 3550/3552/8082 3536/3538/8084 3464/3466/8083 +f 3266/3268/8085 3253/3255/8085 3255/3257/8085 +f 3266/3268/8086 3417/3419/7515 3253/3255/7517 +f 3266/3268/8087 3535/3537/8087 3417/3419/8087 +f 3535/3537/8088 3533/3535/8088 3417/3419/8088 +f 3242/3244/8089 3230/3232/8089 3232/3234/8089 +f 3242/3244/8090 3428/3430/7551 3230/3232/7550 +f 3242/3244/8091 3530/3532/8091 3428/3430/8091 +f 3220/3222/8089 3208/3210/8089 3210/3212/8089 +f 3220/3222/8090 3435/3437/8090 3208/3210/8090 +f 3220/3222/8091 3527/3529/8091 3435/3437/8091 +f 3199/3201/8089 3186/3188/8089 3188/3190/8089 +f 3199/3201/8090 3443/3445/8090 3186/3188/8090 +f 3199/3201/8092 3523/3525/8092 3443/3445/8092 +f 3175/3177/8089 3162/3164/8089 3164/3166/8089 +f 3175/3177/8090 3451/3453/8090 3162/3164/8090 +f 3175/3177/8091 3520/3522/8091 3451/3453/8091 +f 3153/3155/8093 3141/3143/7658 3143/3145/8094 +f 3153/3155/8093 3458/3460/7657 3141/3143/7658 +f 3153/3155/8095 3516/3518/7867 3458/3460/7865 +f 3130/3132/8096 3128/3130/8097 3117/3119/8098 +f 3128/3130/8097 3115/3117/7681 3117/3119/8098 +f 3128/3130/8097 3467/3469/7682 3115/3117/7681 +f 3128/3130/8097 3513/3515/8099 3467/3469/7682 +f 3513/3515/8099 3509/3511/8100 3467/3469/7682 +f 3478/3480/7710 3501/3503/8101 3477/3479/7709 +f 3501/3503/8101 3488/3490/8102 3477/3479/7709 +f 3500/3502/8103 3499/3501/8008 3489/3491/8104 +f 3499/3501/8008 3490/3492/8010 3489/3491/8104 +f 3508/3510/8006 3507/3509/8105 3497/3499/8004 +f 3507/3509/8105 3493/3495/8106 3497/3499/8004 +f 3507/3509/8107 3506/3508/8003 3493/3495/8108 +f 3506/3508/8003 3496/3498/8001 3493/3495/8108 +f 3479/3481/8109 3617/3619/8005 3480/3482/8110 +f 3479/3481/8109 3505/3507/8007 3617/3619/8005 +f 3620/3622/8111 3621/3623/8112 3622/3624/8113 +f 3623/3625/8114 3622/3624/8113 3624/3626/8115 +f 3620/3622/8111 3622/3624/8113 3623/3625/8114 +f 3620/3622/8111 3623/3625/8114 3625/3627/8116 +f 3626/3628/8117 3624/3626/8118 3627/3629/8119 +f 3628/3630/8120 3629/3631/8121 3626/3628/8117 +f 3627/3629/8119 3628/3630/8120 3626/3628/8117 +f 3628/3630/8120 3627/3629/8119 3630/3632/8122 +f 3631/3633/8123 3632/3634/8124 3633/3635/8125 +f 3634/3636/8126 3635/3637/8127 3636/3638/8128 +f 3637/3639/8129 3638/3640/8130 3639/3641/8131 +f 3639/3641/8131 3640/3642/8132 3637/3639/8129 +f 3640/3642/8132 3641/3643/8133 3637/3639/8129 +f 3642/3644/8134 3640/3642/8135 3643/3645/8136 +f 3644/3646/8137 3645/3647/8138 3646/3648/8139 +f 3647/3649/8140 3648/3650/8141 3649/3651/8142 +f 3647/3649/8140 3646/3648/8139 3648/3650/8141 +f 3650/3652/8143 3651/3653/8144 3652/3654/8145 +f 3653/3655/8146 3650/3652/8143 3654/3656/8147 +f 3655/3657/8148 3656/3658/8149 3657/3659/8150 +f 3655/3657/8148 3657/3659/8150 3658/3660/8151 +f 3659/3661/8152 3656/3658/8149 3655/3657/8148 +f 3660/3662/8153 3661/3663/8154 3662/3664/8155 +f 3661/3663/8154 3660/3662/8153 3663/3665/8156 +f 3661/3663/8154 3663/3665/8156 3664/3666/8157 +f 3664/3666/8157 3665/3667/8158 3661/3663/8154 +f 3664/3666/8157 3666/3668/8159 3665/3667/8158 +f 3665/3667/8158 3667/3669/8160 3668/3670/8161 +f 3642/3644/8134 3669/3671/8162 3670/3672/8163 +f 3637/3639/8129 3641/3643/8133 3670/3672/8163 +f 3638/3640/8130 3637/3639/8129 3634/3636/8126 +f 3642/3644/8134 3643/3645/8136 3669/3671/8162 +f 3643/3645/8136 3671/3673/8164 3669/3671/8162 +f 3665/3667/8158 3666/3668/8159 3667/3669/8160 +f 3670/3672/8163 3669/3671/8162 3637/3639/8129 +f 3671/3673/8164 3644/3646/8137 3669/3671/8162 +f 3634/3636/8126 3637/3639/8129 3635/3637/8127 +f 3637/3639/8129 3669/3671/8162 3635/3637/8127 +f 3636/3638/8128 3635/3637/8127 3633/3635/8125 +f 3669/3671/8162 3672/3674/8165 3635/3637/8127 +f 3669/3671/8162 3647/3649/8140 3672/3674/8165 +f 3669/3671/8162 3644/3646/8137 3647/3649/8140 +f 3635/3637/8127 3672/3674/8165 3633/3635/8125 +f 3644/3646/8137 3646/3648/8139 3647/3649/8140 +f 3633/3635/8125 3672/3674/8165 3631/3633/8123 +f 3672/3674/8165 3647/3649/8140 3673/3675/8166 +f 3620/3622/8111 3665/3667/8158 3674/3676/8167 +f 3620/3622/8111 3675/3677/8168 3665/3667/8158 +f 3675/3677/8168 3661/3663/8154 3665/3667/8158 +f 3675/3677/8168 3676/3678/8169 3661/3663/8154 +f 3676/3678/8169 3677/3679/8170 3661/3663/8154 +f 3674/3676/8167 3665/3667/8158 3668/3670/8161 +f 3677/3679/8170 3662/3664/8155 3661/3663/8154 +f 3672/3674/8165 3678/3680/8171 3631/3633/8123 +f 3672/3674/8165 3673/3675/8166 3678/3680/8171 +f 3647/3649/8140 3679/3681/8172 3673/3675/8166 +f 3647/3649/8140 3649/3651/8142 3653/3655/8146 +f 3632/3634/8124 3628/3630/8120 3630/3632/8122 +f 3632/3634/8124 3631/3633/8123 3628/3630/8120 +f 3647/3649/8140 3653/3655/8146 3679/3681/8172 +f 3649/3651/8142 3680/3682/8173 3653/3655/8146 +f 3628/3630/8120 3681/3683/8174 3629/3631/8121 +f 3681/3683/8174 3620/3622/8111 3629/3631/8121 +f 3681/3683/8174 3682/3684/8175 3620/3622/8111 +f 3681/3683/8174 3683/3685/8176 3682/3684/8175 +f 3653/3655/8146 3657/3659/8150 3684/3686/8177 +f 3653/3655/8146 3654/3656/8147 3657/3659/8150 +f 3629/3631/8121 3620/3622/8111 3625/3627/8116 +f 3683/3685/8176 3684/3686/8177 3682/3684/8175 +f 3684/3686/8177 3656/3658/8149 3676/3678/8169 +f 3684/3686/8177 3657/3659/8150 3656/3658/8149 +f 3620/3622/8111 3674/3676/8167 3621/3623/8112 +f 3656/3658/8149 3677/3679/8170 3676/3678/8169 +f 3656/3658/8149 3659/3661/8152 3677/3679/8170 +f 3631/3633/8123 3681/3683/8174 3628/3630/8120 +f 3631/3633/8123 3678/3680/8171 3681/3683/8174 +f 3680/3682/8173 3651/3653/8144 3653/3655/8146 +f 3678/3680/8171 3683/3685/8176 3681/3683/8174 +f 3678/3680/8171 3673/3675/8166 3683/3685/8176 +f 3673/3675/8166 3679/3681/8172 3683/3685/8176 +f 3679/3681/8172 3653/3655/8146 3684/3686/8177 +f 3679/3681/8172 3684/3686/8177 3683/3685/8176 +f 3651/3653/8144 3650/3652/8143 3653/3655/8146 +f 3620/3622/8111 3682/3684/8175 3675/3677/8168 +f 3682/3684/8175 3676/3678/8169 3675/3677/8168 +f 3682/3684/8175 3684/3686/8177 3676/3678/8169 +f 3685/3687/8178 3277/3279/7357 3278/3280/7358 +f 3686/3688/8179 3687/3689/8180 3282/3284/7828 +f 3687/3689/8180 3686/3688/8179 3688/3690/8181 +f 3277/3279/7357 3685/3687/8178 3689/3691/8182 +f 3277/3279/7357 3689/3691/8182 3690/3692/8183 +f 3401/3403/7490 3277/3279/7357 3690/3692/8183 +f 3402/3404/7491 3690/3692/8183 3691/3693/8184 +f 3402/3404/7491 3401/3403/7490 3690/3692/8183 +f 3402/3404/7491 3691/3693/8184 3692/3694/8185 +f 3692/3694/8185 3404/3406/7493 3402/3404/7491 +f 3404/3406/7493 3692/3694/8185 3693/3695/8186 +f 3693/3695/8186 3406/3408/7495 3404/3406/7493 +f 3694/3696/8187 3471/3473/7703 3468/3470/7700 +f 3694/3696/8187 3695/3697/8188 3471/3473/7703 +f 3471/3473/7703 3695/3697/8188 3696/3698/8189 +f 3473/3475/7705 3471/3473/7703 3696/3698/8189 +f 3696/3698/8189 3697/3699/8190 3473/3475/7705 +f 3697/3699/8190 3475/3477/7707 3473/3475/7705 +f 3697/3699/8190 3698/3700/8191 3475/3477/7707 +f 3478/3480/7710 3475/3477/7707 3699/3701/8192 +f 3475/3477/7707 3698/3700/8191 3699/3701/8192 +f 3700/3702/8193 3482/3484/7714 3480/3482/7712 +f 3482/3484/7714 3700/3702/8193 3701/3703/8194 +f 3282/3284/7828 3482/3484/7714 3701/3703/8194 +f 3282/3284/7828 3701/3703/8194 3702/3704/8195 +f 3282/3284/7828 3702/3704/8195 3686/3688/8179 +f 3703/3705/8196 3704/3706/8197 3670/3672/8198 +f 3703/3705/8196 3670/3672/8198 3641/3643/8199 +f 3641/3643/8200 3705/3707/8201 3703/3705/8202 +f 3641/3643/8200 3640/3642/8203 3705/3707/8201 +f 3706/3708/8204 3705/3707/8205 3642/3644/8206 +f 3705/3707/8205 3640/3642/8207 3642/3644/8206 +f 3704/3706/8208 3706/3708/8209 3670/3672/8210 +f 3706/3708/8209 3642/3644/8211 3670/3672/8210 +f 3707/3709/8212 3624/3626/8212 3626/3628/8212 +f 3707/3709/8213 3626/3628/8213 3708/3710/8213 +f 3626/3628/8214 3629/3631/8214 3708/3710/8214 +f 3629/3631/8215 3625/3627/8216 3708/3710/8217 +f 3625/3627/8216 3709/3711/8218 3708/3710/8217 +f 3625/3627/8219 3623/3625/8220 3709/3711/8221 +f 3623/3625/8220 3710/3712/8222 3709/3711/8221 +f 3623/3625/8223 3624/3626/8224 3710/3712/8225 +f 3707/3709/8226 3710/3712/8225 3624/3626/8224 +f 3711/3713/8227 3712/3714/8228 3713/3715/8229 +f 3714/3716/8230 3715/3717/8231 3716/3718/8232 +f 3716/3718/8232 3715/3717/8231 3717/3719/8233 +f 3718/3720/8234 3717/3719/8235 3719/3721/8236 +f 3718/3720/8234 3716/3718/8237 3717/3719/8235 +f 3406/3408/7495 3693/3695/8186 3720/3722/8238 +f 3720/3722/8238 3711/3713/8227 3406/3408/7495 +f 3720/3722/8238 3712/3714/8228 3711/3713/8227 +f 3468/3470/7700 3711/3713/8227 3721/3723/8239 +f 3711/3713/8227 3713/3715/8229 3721/3723/8239 +f 3468/3470/7700 3721/3723/8239 3694/3696/8187 +f 3714/3716/8230 3687/3689/8180 3688/3690/8181 +f 3714/3716/8230 3716/3718/8232 3687/3689/8180 +f 3278/3280/7358 3718/3720/8240 3722/3724/8241 +f 3718/3720/8240 3719/3721/8242 3722/3724/8241 +f 3278/3280/7358 3722/3724/8241 3685/3687/8178 +f 3697/3699/8190 3666/3668/8243 3664/3666/8157 +f 3697/3699/8190 3696/3698/8189 3666/3668/8243 +f 3696/3698/8189 3667/3669/8160 3666/3668/8243 +f 3664/3666/8157 3663/3665/8156 3697/3699/8190 +f 3663/3665/8156 3660/3662/8153 3698/3700/8191 +f 3667/3669/8160 3694/3696/8187 3668/3670/8161 +f 3694/3696/8187 3667/3669/8160 3695/3697/8188 +f 3695/3697/8188 3667/3669/8160 3696/3698/8189 +f 3697/3699/8190 3663/3665/8156 3698/3700/8191 +f 3698/3700/8191 3660/3662/8153 3699/3701/8192 +f 3668/3670/8161 3694/3696/8187 3721/3723/8239 +f 3721/3723/8239 3674/3676/8167 3668/3670/8161 +f 3721/3723/8239 3713/3715/8229 3674/3676/8167 +f 3712/3714/8228 3674/3676/8167 3713/3715/8229 +f 3720/3722/8238 3621/3623/8112 3674/3676/8167 +f 3720/3722/8238 3693/3695/8186 3621/3623/8112 +f 3674/3676/8167 3712/3714/8228 3720/3722/8238 +f 3627/3629/8119 3624/3626/8244 3622/3624/8113 +f 3685/3687/8178 3630/3632/8122 3689/3691/8182 +f 3630/3632/8122 3690/3692/8183 3689/3691/8182 +f 3627/3629/8119 3691/3693/8184 3690/3692/8183 +f 3627/3629/8119 3622/3624/8113 3691/3693/8184 +f 3691/3693/8184 3622/3624/8113 3692/3694/8185 +f 3622/3624/8113 3621/3623/8112 3693/3695/8186 +f 3693/3695/8186 3692/3694/8185 3622/3624/8113 +f 3627/3629/8119 3690/3692/8183 3630/3632/8122 +f 3630/3632/8122 3685/3687/8178 3632/3634/8124 +f 3719/3721/8245 3632/3634/8124 3722/3724/8241 +f 3632/3634/8124 3685/3687/8178 3722/3724/8241 +f 3633/3635/8246 3632/3634/8124 3719/3721/8245 +f 3723/3725/8247 3719/3721/8236 3717/3719/8235 +f 3723/3725/8248 3633/3635/8125 3719/3721/8249 +f 3715/3717/8250 3723/3725/8248 3717/3719/8251 +f 3715/3717/8250 3724/3726/8252 3723/3725/8248 +f 3724/3726/8252 3633/3635/8125 3723/3725/8248 +f 3724/3726/8252 3636/3638/8128 3633/3635/8125 +f 3714/3716/8230 3688/3690/8181 3636/3638/8128 +f 3724/3726/8252 3714/3716/8230 3636/3638/8128 +f 3724/3726/8252 3715/3717/8250 3714/3716/8230 +f 3634/3636/8126 3686/3688/8253 3702/3704/8195 +f 3688/3690/8181 3686/3688/8254 3636/3638/8128 +f 3636/3638/8128 3686/3688/8254 3634/3636/8255 +f 3701/3703/8194 3638/3640/8130 3702/3704/8195 +f 3639/3641/8131 3638/3640/8130 3701/3703/8194 +f 3638/3640/8130 3634/3636/8126 3702/3704/8195 +f 3700/3702/8193 3639/3641/8131 3701/3703/8194 +f 3643/3645/8136 3640/3642/8135 3700/3702/8193 +f 3639/3641/8131 3700/3702/8193 3640/3642/8135 +f 3725/3727/8256 3726/3728/8257 3727/3729/8258 +f 3617/3619/8005 3497/3499/8004 3728/3730/8259 +f 3497/3499/8004 3729/3731/8260 3728/3730/8259 +f 3730/3732/8261 3731/3733/8262 3499/3501/8008 +f 3731/3733/8262 3618/3620/8011 3499/3501/8008 +f 3618/3620/8011 3731/3733/8262 3732/3734/8263 +f 3619/3621/8013 3618/3620/8011 3733/3735/8264 +f 3618/3620/8011 3732/3734/8263 3733/3735/8264 +f 3733/3735/8264 3725/3727/8256 3619/3621/8013 +f 3725/3727/8256 3616/3618/8000 3619/3621/8013 +f 3725/3727/8256 3727/3729/8258 3616/3618/8000 +f 3728/3730/8259 3480/3482/8110 3617/3619/8005 +f 3480/3482/8110 3728/3730/8259 3700/3702/8193 +f 3652/3654/8265 3658/3660/8265 3734/3736/8265 +f 3658/3660/8266 3735/3737/8266 3734/3736/8266 +f 3658/3660/8267 3657/3659/8267 3735/3737/8267 +f 3657/3659/8268 3736/3738/8268 3735/3737/8268 +f 3657/3659/8269 3654/3656/8270 3736/3738/8271 +f 3654/3656/8270 3737/3739/8272 3736/3738/8271 +f 3654/3656/8273 3650/3652/8274 3737/3739/8275 +f 3650/3652/8274 3738/3740/8276 3737/3739/8275 +f 3650/3652/8277 3652/3654/8277 3738/3740/8277 +f 3734/3736/8278 3738/3740/8278 3652/3654/8278 +f 3498/3500/8279 3739/3741/8280 3740/3742/8281 +f 3494/3496/8282 3741/3743/8283 3742/3744/8284 +f 3494/3496/8282 3742/3744/8284 3743/3745/8285 +f 3495/3497/8286 3494/3496/8282 3743/3745/8285 +f 3499/3501/8008 3498/3500/8279 3744/3746/8287 +f 3498/3500/8279 3740/3742/8281 3744/3746/8287 +f 3499/3501/8008 3744/3746/8287 3730/3732/8261 +f 3478/3480/7710 3699/3701/8192 3745/3747/8288 +f 3498/3500/8279 3478/3480/7710 3745/3747/8288 +f 3745/3747/8288 3739/3741/8280 3498/3500/8279 +f 3497/3499/8004 3495/3497/8289 3746/3748/8290 +f 3495/3497/8289 3743/3745/8291 3746/3748/8290 +f 3729/3731/8260 3497/3499/8004 3746/3748/8290 +f 3496/3498/8292 3727/3729/8258 3726/3728/8257 +f 3496/3498/8292 3726/3728/8257 3747/3749/8293 +f 3747/3749/8293 3494/3496/8294 3496/3498/8292 +f 3747/3749/8293 3741/3743/8295 3494/3496/8294 +f 3745/3747/8288 3662/3664/8155 3739/3741/8296 +f 3745/3747/8288 3660/3662/8153 3662/3664/8155 +f 3745/3747/8288 3699/3701/8192 3660/3662/8153 +f 3748/3750/8297 3662/3664/8155 3677/3679/8170 +f 3748/3750/8297 3739/3741/8296 3662/3664/8155 +f 3739/3741/8296 3748/3750/8297 3740/3742/8281 +f 3659/3661/8152 3748/3750/8297 3677/3679/8170 +f 3744/3746/8287 3659/3661/8152 3730/3732/8298 +f 3740/3742/8281 3748/3750/8297 3744/3746/8287 +f 3748/3750/8297 3659/3661/8152 3744/3746/8287 +f 3655/3657/8148 3658/3660/8151 3652/3654/8145 +f 3725/3727/8256 3733/3735/8264 3651/3653/8144 +f 3733/3735/8264 3652/3654/8145 3651/3653/8144 +f 3733/3735/8264 3732/3734/8263 3652/3654/8145 +f 3731/3733/8262 3655/3657/8148 3732/3734/8263 +f 3655/3657/8148 3730/3732/8298 3659/3661/8152 +f 3655/3657/8148 3652/3654/8145 3732/3734/8263 +f 3651/3653/8144 3680/3682/8173 3725/3727/8256 +f 3730/3732/8298 3655/3657/8148 3731/3733/8262 +f 3680/3682/8173 3726/3728/8257 3725/3727/8256 +f 3648/3650/8299 3747/3749/8293 3649/3651/8142 +f 3726/3728/8257 3649/3651/8142 3747/3749/8293 +f 3680/3682/8173 3649/3651/8142 3726/3728/8257 +f 3741/3743/8300 3747/3749/8293 3648/3650/8299 +f 3648/3650/8299 3743/3745/8301 3741/3743/8300 +f 3743/3745/8302 3742/3744/8302 3741/3743/8302 +f 3648/3650/8299 3646/3648/8139 3743/3745/8301 +f 3746/3748/8303 3743/3745/8301 3646/3648/8139 +f 3746/3748/8303 3645/3647/8138 3729/3731/8304 +f 3646/3648/8139 3645/3647/8138 3746/3748/8303 +f 3644/3646/8137 3671/3673/8164 3728/3730/8259 +f 3645/3647/8138 3644/3646/8137 3729/3731/8304 +f 3644/3646/8137 3728/3730/8259 3729/3731/8304 +f 3671/3673/8164 3643/3645/8136 3700/3702/8193 +f 3728/3730/8259 3671/3673/8164 3700/3702/8193 +f 3727/3729/8305 3496/3498/8305 3616/3618/8305 +f 3749/3751/8306 3750/3752/8307 3751/3753/8308 +f 3752/3754/8309 3753/3755/8310 3754/3756/8311 +f 3755/3757/528 3756/3758/528 3757/3759/8312 +f 3749/3751/8306 3751/3753/8308 3758/3760/8313 +f 3751/3753/8308 3759/3761/8314 3758/3760/8313 +f 3750/3752/8315 3749/3751/8316 3760/3762/8317 +f 3757/3759/8312 3756/3758/528 3752/3754/8309 +f 3754/3756/8311 3757/3759/8312 3752/3754/8309 +f 3761/3763/8318 3762/3764/8319 3760/3762/8320 +f 3760/3762/8320 3758/3760/8313 3761/3763/8318 +f 3762/3764/8321 3750/3752/8315 3760/3762/8317 +f 3758/3760/8313 3763/3765/8322 3761/3763/8318 +f 3764/3766/528 3753/3755/8310 3756/3758/528 +f 3753/3755/8310 3765/3767/8323 3754/3756/8311 +f 3759/3761/8314 3763/3765/8322 3758/3760/8313 +f 3759/3761/8314 3766/3768/8324 3763/3765/8322 +f 3766/3768/8324 3767/3769/8325 3763/3765/8322 +f 3766/3768/8324 3768/3770/8326 3767/3769/8325 +f 3765/3767/8323 3753/3755/8310 3764/3766/528 +f 3764/3766/528 3769/3771/528 3765/3767/8323 +f 3770/3772/528 3771/3773/528 3772/3774/528 +f 3766/3768/8324 3770/3772/528 3768/3770/8326 +f 3770/3772/528 3772/3774/528 3768/3770/8326 +f 3771/3773/528 3773/3775/528 3772/3774/528 +f 3771/3773/528 3769/3771/528 3773/3775/528 +f 3764/3766/528 3773/3775/528 3769/3771/528 +f 3762/3764/8327 3774/3776/8327 3750/3752/8327 +f 3761/3763/8328 3774/3776/8329 3762/3764/8330 +f 3751/3753/8331 3775/3777/8332 3776/3778/8333 +f 3751/3753/8331 3750/3752/8334 3775/3777/8332 +f 3761/3763/8328 3776/3778/8335 3774/3776/8329 +f 3777/3779/98 3778/3780/98 3779/3781/98 +f 3780/3782/8336 3781/3783/8337 3754/3756/8338 +f 3775/3777/8332 3750/3752/8334 3774/3776/8339 +f 3776/3778/8340 3761/3763/8340 3782/3784/8340 +f 3779/3781/98 3781/3783/98 3777/3779/98 +f 3777/3779/98 3783/3785/98 3778/3780/98 +f 3776/3778/8333 3784/3786/8341 3751/3753/8331 +f 3782/3784/8342 3767/3769/8343 3785/3787/8344 +f 3776/3778/8333 3782/3784/8342 3784/3786/8341 +f 3784/3786/8341 3782/3784/8342 3785/3787/8344 +f 3767/3769/8343 3786/3788/8345 3785/3787/8344 +f 3767/3769/8343 3787/3789/8346 3786/3788/8345 +f 3787/3789/8346 3788/3790/98 3786/3788/8345 +f 3788/3790/98 3789/3791/98 3786/3788/8345 +f 3783/3785/98 3780/3782/98 3790/3792/98 +f 3777/3779/98 3780/3782/98 3783/3785/98 +f 3788/3790/98 3790/3792/98 3789/3791/98 +f 3788/3790/98 3783/3785/98 3790/3792/98 +f 3765/3767/8347 3780/3782/8347 3754/3756/8347 +f 3765/3767/8348 3790/3792/8348 3780/3782/8348 +f 3765/3767/8349 3769/3771/8349 3790/3792/8349 +f 3769/3771/8350 3771/3773/8350 3790/3792/8350 +f 3771/3773/8351 3789/3791/8351 3790/3792/8351 +f 3771/3773/8352 3770/3772/8352 3789/3791/8352 +f 3770/3772/8353 3786/3788/8353 3789/3791/8353 +f 3770/3772/8354 3766/3768/8354 3786/3788/8354 +f 3766/3768/8355 3785/3787/8355 3786/3788/8355 +f 3766/3768/8356 3784/3786/8357 3785/3787/8358 +f 3766/3768/8356 3759/3761/8359 3784/3786/8357 +f 3759/3761/8360 3751/3753/8360 3784/3786/8360 +f 3761/3763/8361 3763/3765/8361 3782/3784/8361 +f 3763/3765/8362 3767/3769/8362 3782/3784/8362 +f 3767/3769/8363 3768/3770/8363 3787/3789/8363 +f 3768/3770/8364 3788/3790/8365 3787/3789/8366 +f 3768/3770/8364 3772/3774/8367 3788/3790/8365 +f 3772/3774/8368 3773/3775/8368 3788/3790/8368 +f 3773/3775/8369 3783/3785/8369 3788/3790/8369 +f 3773/3775/8370 3764/3766/8370 3783/3785/8370 +f 3764/3766/8371 3778/3780/8371 3783/3785/8371 +f 3764/3766/8372 3756/3758/8372 3778/3780/8372 +f 3755/3757/8373 3779/3781/8373 3756/3758/8373 +f 3779/3781/8374 3778/3780/8374 3756/3758/8374 +f 3755/3757/8375 3757/3759/8375 3779/3781/8375 +f 3757/3759/8376 3781/3783/8376 3779/3781/8376 +f 3754/3756/8338 3781/3783/8337 3757/3759/8377 +f 3760/3762/8378 3749/3751/8378 3774/3776/8378 +f 3749/3751/8379 3775/3777/8379 3774/3776/8379 +f 3749/3751/8380 3758/3760/8380 3775/3777/8380 +f 3758/3760/8381 3776/3778/8381 3775/3777/8381 +f 3758/3760/8382 3760/3762/8382 3776/3778/8382 +f 3760/3762/8383 3774/3776/8383 3776/3778/8383 +f 3752/3754/8384 3781/3783/8384 3780/3782/8384 +f 3752/3754/8385 3756/3758/8385 3781/3783/8385 +f 3756/3758/8386 3777/3779/8386 3781/3783/8386 +f 3756/3758/8387 3753/3755/8387 3777/3779/8387 +f 3753/3755/8388 3780/3782/8388 3777/3779/8388 +f 3753/3755/8389 3752/3754/8389 3780/3782/8389 +f 3791/3793/8390 3792/3794/8390 3793/3795/8390 +f 3794/3796/8391 3795/3797/8392 3796/3798/8393 +f 3796/3798/8393 3795/3797/8392 3797/3799/8394 +f 3794/3796/8391 3796/3798/8393 3793/3795/8395 +f 3798/3800/8396 3799/3801/8397 3800/3802/8398 +f 3801/3803/8399 3800/3802/8400 3802/3804/8401 +f 3800/3802/8402 3799/3801/8403 3802/3804/8404 +f 3799/3801/8403 3803/3805/8405 3802/3804/8404 +f 3799/3801/8406 3798/3800/8407 3803/3805/8408 +f 3798/3800/8407 3804/3806/8409 3803/3805/8408 +f 3798/3800/8410 3805/3807/8411 3804/3806/8412 +f 3805/3807/8411 3801/3803/8413 3804/3806/8412 +f 3805/3807/8414 3800/3802/8400 3801/3803/8399 +f 3803/3805/8415 3804/3806/8416 3806/3808/8417 +f 3804/3806/8416 3801/3803/8418 3807/3809/8419 +f 3801/3803/8418 3808/3810/8420 3807/3809/8419 +f 3806/3808/8417 3804/3806/8416 3809/3811/8421 +f 3801/3803/8418 3802/3804/8422 3808/3810/8420 +f 3802/3804/8422 3810/3812/8423 3808/3810/8420 +f 3804/3806/8416 3807/3809/8419 3809/3811/8421 +f 3802/3804/8422 3803/3805/8415 3806/3808/8417 +f 3802/3804/8422 3806/3808/8417 3810/3812/8423 +f 3808/3810/8424 3810/3812/8425 3795/3797/8426 +f 3795/3797/8426 3810/3812/8425 3797/3799/8427 +f 3797/3799/8428 3810/3812/8429 3796/3798/8430 +f 3810/3812/8429 3806/3808/8431 3796/3798/8430 +f 3806/3808/8432 3793/3795/8432 3796/3798/8432 +f 3806/3808/8433 3809/3811/8434 3793/3795/8435 +f 3793/3795/8435 3809/3811/8434 3791/3793/8436 +f 3809/3811/8437 3807/3809/8438 3791/3793/8439 +f 3807/3809/8438 3792/3794/8440 3791/3793/8439 +f 3807/3809/8441 3808/3810/8442 3792/3794/8443 +f 3808/3810/8442 3795/3797/8444 3792/3794/8443 +f 3793/3795/8445 3811/3813/8445 3794/3796/8445 +f 3811/3813/8446 3812/3814/8446 3794/3796/8446 +f 3792/3794/8447 3811/3813/8447 3793/3795/8447 +f 3795/3797/8448 3812/3814/8449 3792/3794/8450 +f 3812/3814/8449 3811/3813/8451 3792/3794/8450 +f 3794/3796/8452 3812/3814/8452 3795/3797/8452 +f 3805/3807/8453 3798/3800/8396 3800/3802/8398 +f 3813/3815/8454 3814/3816/8455 3815/3817/8456 +f 3816/3818/8457 3817/3819/8458 3818/3820/8459 +f 3813/3815/8454 3816/3818/8457 3814/3816/8455 +f 3813/3815/8454 3817/3819/8458 3816/3818/8457 +f 3819/3821/8460 3813/3815/8454 3815/3817/8456 +f 3819/3821/8460 3815/3817/8456 3818/3820/8459 +f 3817/3819/8458 3819/3821/8460 3818/3820/8459 +f 3820/3822/8461 3821/3823/8462 3822/3824/8463 +f 3823/3825/8464 3820/3822/8461 3822/3824/8463 +f 3824/3826/8465 3823/3825/8466 3825/3827/8467 +f 3824/3826/8465 3826/3828/8468 3823/3825/8466 +f 3826/3828/8469 3820/3822/8470 3823/3825/8471 +f 3826/3828/8469 3827/3829/8472 3820/3822/8470 +f 3827/3829/8473 3821/3823/8474 3820/3822/8475 +f 3827/3829/8473 3828/3830/8476 3821/3823/8474 +f 3828/3830/8477 3822/3824/8478 3821/3823/8479 +f 3828/3830/8477 3829/3831/8480 3822/3824/8478 +f 3829/3831/8481 3825/3827/8482 3822/3824/8483 +f 3829/3831/8481 3824/3826/8484 3825/3827/8482 +f 3826/3828/8485 3830/3832/8486 3831/3833/8487 +f 3826/3828/8485 3824/3826/8488 3830/3832/8486 +f 3824/3826/8488 3832/3834/8489 3830/3832/8486 +f 3824/3826/8488 3829/3831/8490 3832/3834/8489 +f 3829/3831/8490 3833/3835/8491 3832/3834/8489 +f 3829/3831/8490 3828/3830/8492 3833/3835/8491 +f 3828/3830/8492 3834/3836/8493 3833/3835/8491 +f 3828/3830/8492 3827/3829/8494 3834/3836/8493 +f 3827/3829/8494 3835/3837/8495 3834/3836/8493 +f 3827/3829/8494 3831/3833/8487 3835/3837/8495 +f 3827/3829/8494 3826/3828/8485 3831/3833/8487 +f 3814/3816/8496 3816/3818/8497 3830/3832/8498 +f 3816/3818/8497 3831/3833/8499 3830/3832/8498 +f 3816/3818/8500 3835/3837/8500 3831/3833/8500 +f 3816/3818/8501 3818/3820/8502 3835/3837/8503 +f 3818/3820/8502 3834/3836/8504 3835/3837/8503 +f 3818/3820/8505 3833/3835/8506 3834/3836/8507 +f 3818/3820/8505 3815/3817/8508 3833/3835/8506 +f 3815/3817/8509 3832/3834/8509 3833/3835/8509 +f 3815/3817/8510 3814/3816/8510 3832/3834/8510 +f 3814/3816/8511 3830/3832/8511 3832/3834/8511 +f 3817/3819/8512 3836/3838/8513 3819/3821/8514 +f 3836/3838/8513 3837/3839/8515 3819/3821/8514 +f 3813/3815/8516 3838/3840/8517 3817/3819/8518 +f 3838/3840/8517 3836/3838/8519 3817/3819/8518 +f 3819/3821/6881 3837/3839/6882 3813/3815/6883 +f 3837/3839/6882 3838/3840/6884 3813/3815/6883 +f 3837/3839/528 3836/3838/528 3838/3840/528 +f 3825/3827/8520 3823/3825/8464 3822/3824/8463 +f 3839/3841/528 3840/3842/528 3841/3843/528 +f 3842/3844/8521 3843/3845/8522 3844/3846/8523 +f 3844/3846/8523 3843/3845/8522 3845/3847/8524 +f 3844/3846/8525 3845/3847/8526 3846/3848/8527 +f 3841/3843/528 3847/3849/528 3839/3841/528 +f 3848/3850/8528 3846/3848/8527 3845/3847/8526 +f 3839/3841/528 3847/3849/528 3849/3851/528 +f 3850/3852/528 3848/3850/528 3843/3845/8522 +f 3850/3852/8529 3846/3848/8529 3848/3850/8529 +f 3851/3853/8530 3852/3854/8531 3849/3851/8532 +f 3852/3854/8531 3840/3842/528 3849/3851/8532 +f 3849/3851/8533 3853/3855/8534 3851/3853/8535 +f 3842/3844/8521 3854/3856/8536 3843/3845/8522 +f 3847/3849/528 3853/3855/8537 3849/3851/528 +f 3847/3849/528 3855/3857/8538 3853/3855/8537 +f 3855/3857/8538 3856/3858/8539 3853/3855/8537 +f 3855/3857/8538 3857/3859/8540 3856/3858/8539 +f 3858/3860/8541 3843/3845/8522 3854/3856/8536 +f 3858/3860/8541 3850/3852/528 3843/3845/8522 +f 3856/3858/8539 3857/3859/8540 3859/3861/8542 +f 3857/3859/8540 3860/3862/8543 3859/3861/8542 +f 3860/3862/8543 3861/3863/8544 3859/3861/8542 +f 3860/3862/8543 3862/3864/8545 3861/3863/8544 +f 3860/3862/8543 3858/3860/8541 3862/3864/8545 +f 3858/3860/8541 3854/3856/8536 3862/3864/8545 +f 3863/3865/8546 3864/3866/8547 3865/3867/98 +f 3851/3853/8548 3864/3866/8547 3863/3865/8546 +f 3866/3868/98 3867/3869/98 3868/3870/98 +f 3869/3871/8549 3846/3848/8550 3870/3872/8551 +f 3851/3853/8548 3868/3870/8552 3864/3866/8547 +f 3870/3872/8553 3846/3848/8553 3871/3873/8553 +f 3865/3867/98 3864/3866/8547 3867/3869/98 +f 3868/3870/8552 3851/3853/8548 3872/3874/8554 +f 3844/3846/8555 3846/3848/8550 3869/3871/8549 +f 3871/3873/98 3873/3875/8556 3869/3871/98 +f 3872/3874/8557 3874/3876/8558 3866/3868/98 +f 3872/3874/8557 3856/3858/8559 3874/3876/8558 +f 3868/3870/98 3872/3874/8557 3866/3868/98 +f 3856/3858/8559 3875/3877/8560 3874/3876/8558 +f 3856/3858/8559 3876/3878/8561 3875/3877/8560 +f 3876/3878/8561 3877/3879/8562 3875/3877/8560 +f 3876/3878/8561 3878/3880/8563 3877/3879/8562 +f 3878/3880/8563 3862/3864/8564 3877/3879/8562 +f 3873/3875/8556 3879/3881/2514 3880/3882/8565 +f 3871/3873/98 3879/3881/2514 3873/3875/8556 +f 3862/3864/8564 3880/3882/8565 3877/3879/8562 +f 3862/3864/8564 3873/3875/8556 3880/3882/8565 +f 3850/3852/8566 3879/3881/8567 3871/3873/8568 +f 3850/3852/8566 3858/3860/8569 3879/3881/8567 +f 3858/3860/8570 3880/3882/8570 3879/3881/8570 +f 3858/3860/8571 3860/3862/8571 3880/3882/8571 +f 3860/3862/8572 3877/3879/8572 3880/3882/8572 +f 3860/3862/8573 3857/3859/8573 3877/3879/8573 +f 3857/3859/8574 3875/3877/8574 3877/3879/8574 +f 3857/3859/8575 3855/3857/8575 3875/3877/8575 +f 3855/3857/8576 3874/3876/8576 3875/3877/8576 +f 3855/3857/8577 3866/3868/8578 3874/3876/8579 +f 3855/3857/8577 3847/3849/8580 3866/3868/8578 +f 3847/3849/8581 3841/3843/8581 3866/3868/8581 +f 3841/3843/8582 3867/3869/8583 3866/3868/8584 +f 3840/3842/8585 3865/3867/8585 3841/3843/8585 +f 3865/3867/8586 3867/3869/8583 3841/3843/8582 +f 3840/3842/8587 3852/3854/8587 3865/3867/8587 +f 3852/3854/8588 3863/3865/8588 3865/3867/8588 +f 3851/3853/8589 3863/3865/8589 3852/3854/8589 +f 3851/3853/8535 3853/3855/8534 3872/3874/8590 +f 3853/3855/8591 3856/3858/8591 3872/3874/8591 +f 3859/3861/8592 3876/3878/8592 3856/3858/8592 +f 3859/3861/8593 3861/3863/8593 3876/3878/8593 +f 3861/3863/8594 3878/3880/8594 3876/3878/8594 +f 3861/3863/8595 3862/3864/8595 3878/3880/8595 +f 3854/3856/8596 3873/3875/8596 3862/3864/8596 +f 3854/3856/8597 3842/3844/8597 3873/3875/8597 +f 3842/3844/8598 3869/3871/8598 3873/3875/8598 +f 3844/3846/8599 3869/3871/8599 3842/3844/8599 +f 3850/3852/8566 3871/3873/8568 3846/3848/8600 +f 3849/3851/8601 3840/3842/8601 3864/3866/8601 +f 3840/3842/8602 3839/3841/8602 3864/3866/8602 +f 3839/3841/8603 3867/3869/8603 3864/3866/8603 +f 3839/3841/8604 3868/3870/8604 3867/3869/8604 +f 3839/3841/8605 3849/3851/8605 3868/3870/8605 +f 3849/3851/8606 3864/3866/8606 3868/3870/8606 +f 3848/3850/8607 3845/3847/8607 3870/3872/8607 +f 3845/3847/8608 3869/3871/8608 3870/3872/8608 +f 3845/3847/8609 3843/3845/8609 3869/3871/8609 +f 3843/3845/8610 3871/3873/8610 3869/3871/8610 +f 3843/3845/8611 3848/3850/8611 3871/3873/8611 +f 3848/3850/8612 3870/3872/8612 3871/3873/8612 +f 3881/3883/8613 3882/3884/8614 3883/3885/8615 +f 3884/3886/8616 3885/3887/8617 3886/3888/8618 +f 3882/3884/8614 3887/3889/8619 3883/3885/8615 +f 3887/3889/8619 3888/3890/8620 3883/3885/8615 +f 3887/3889/8619 3886/3888/8618 3889/3891/8621 +f 3887/3889/8619 3884/3886/8616 3886/3888/8618 +f 3888/3890/8620 3887/3889/8619 3889/3891/8621 +f 3884/3886/8616 3882/3884/8614 3890/3892/8622 +f 3882/3884/8614 3881/3883/8613 3890/3892/8622 +f 3884/3886/8616 3890/3892/8622 3885/3887/8617 +f 3891/3893/8623 3892/3894/8624 3893/3895/8625 +f 3894/3896/8626 3891/3893/8623 3895/3897/8627 +f 3892/3894/8624 3891/3893/8623 3894/3896/8626 +f 3896/3898/8628 3893/3895/8629 3892/3894/8630 +f 3896/3898/8628 3897/3899/8631 3893/3895/8629 +f 3897/3899/8632 3898/3900/8633 3893/3895/8634 +f 3898/3900/8633 3891/3893/8635 3893/3895/8634 +f 3898/3900/8636 3895/3897/8636 3891/3893/8636 +f 3898/3900/8637 3899/3901/8638 3895/3897/8639 +f 3899/3901/8638 3894/3896/8640 3895/3897/8639 +f 3899/3901/8641 3892/3894/8642 3894/3896/8643 +f 3899/3901/8641 3896/3898/8644 3892/3894/8642 +f 3897/3899/8645 3896/3898/8646 3900/3902/8647 +f 3896/3898/8646 3901/3903/8648 3900/3902/8647 +f 3899/3901/8649 3898/3900/8650 3902/3904/8651 +f 3898/3900/8650 3903/3905/8652 3902/3904/8651 +f 3899/3901/8649 3902/3904/8651 3904/3906/8653 +f 3896/3898/8646 3899/3901/8649 3901/3903/8648 +f 3899/3901/8649 3904/3906/8653 3901/3903/8648 +f 3897/3899/8645 3905/3907/8654 3906/3908/8655 +f 3897/3899/8645 3900/3902/8647 3905/3907/8654 +f 3898/3900/8650 3906/3908/8655 3903/3905/8652 +f 3898/3900/8650 3897/3899/8645 3906/3908/8655 +f 3901/3903/8656 3904/3906/8657 3883/3885/8658 +f 3904/3906/8657 3881/3883/8659 3883/3885/8658 +f 3904/3906/8660 3902/3904/8661 3881/3883/8662 +f 3902/3904/8661 3890/3892/8663 3881/3883/8662 +f 3902/3904/8664 3903/3905/8665 3890/3892/8666 +f 3890/3892/8666 3903/3905/8665 3885/3887/8667 +f 3903/3905/8665 3906/3908/8668 3885/3887/8667 +f 3885/3887/8667 3906/3908/8668 3886/3888/8669 +f 3906/3908/8668 3905/3907/8670 3886/3888/8669 +f 3905/3907/8671 3889/3891/8672 3886/3888/8673 +f 3905/3907/8671 3900/3902/8674 3889/3891/8672 +f 3900/3902/8675 3888/3890/8676 3889/3891/8677 +f 3900/3902/8675 3901/3903/8678 3888/3890/8676 +f 3901/3903/8678 3883/3885/8679 3888/3890/8676 +f 3907/3909/8680 3908/3910/8680 3884/3886/8680 +f 3887/3889/8681 3907/3909/8681 3884/3886/8681 +f 3909/3911/8682 3907/3909/8682 3887/3889/8682 +f 3882/3884/8683 3910/3912/8684 3887/3889/8685 +f 3910/3912/8684 3909/3911/8686 3887/3889/8685 +f 3884/3886/8687 3908/3910/8687 3882/3884/8687 +f 3908/3910/8688 3910/3912/8688 3882/3884/8688 +f 3910/3912/3031 3907/3909/3031 3909/3911/3031 +f 3910/3912/3031 3908/3910/3031 3907/3909/3031 +f 3911/3913/8689 3912/3914/8690 3913/3915/8691 +f 3911/3913/8689 3914/3916/8692 3912/3914/8690 +f 3915/3917/8693 3916/3918/8694 3917/3919/8695 +f 3916/3918/8694 3918/3920/8696 3917/3919/8695 +f 3911/3913/8689 3915/3917/8693 3914/3916/8692 +f 3915/3917/8693 3917/3919/8695 3914/3916/8692 +f 3916/3918/8694 3919/3921/8697 3920/3922/8698 +f 3916/3918/8694 3913/3915/8699 3919/3921/8697 +f 3916/3918/8694 3920/3922/8698 3918/3920/8696 +f 3921/3923/8700 3922/3924/8701 3923/3925/8702 +f 3924/3926/8703 3921/3923/8700 3923/3925/8702 +f 3921/3923/8700 3924/3926/8703 3925/3927/8704 +f 3926/3928/8705 3923/3925/8705 3922/3924/8705 +f 3926/3928/8706 3927/3929/8706 3923/3925/8706 +f 3927/3929/8707 3924/3926/8708 3923/3925/8709 +f 3927/3929/8707 3928/3930/8710 3924/3926/8708 +f 3928/3930/8711 3925/3927/8712 3924/3926/8713 +f 3928/3930/8711 3929/3931/8714 3925/3927/8712 +f 3929/3931/8715 3921/3923/8716 3925/3927/8717 +f 3929/3931/8715 3930/3932/8718 3921/3923/8716 +f 3930/3932/8719 3922/3924/8719 3921/3923/8719 +f 3930/3932/8720 3926/3928/8720 3922/3924/8720 +f 3926/3928/8721 3930/3932/8722 3931/3933/8723 +f 3926/3928/8721 3931/3933/8723 3932/3934/8724 +f 3929/3931/8725 3933/3935/8726 3934/3936/8727 +f 3929/3931/8725 3928/3930/8728 3933/3935/8726 +f 3930/3932/8722 3929/3931/8725 3934/3936/8727 +f 3930/3932/8722 3935/3937/8729 3931/3933/8723 +f 3930/3932/8722 3934/3936/8727 3935/3937/8729 +f 3927/3929/8730 3926/3928/8721 3936/3938/8731 +f 3926/3928/8721 3932/3934/8724 3936/3938/8731 +f 3928/3930/8728 3936/3938/8731 3933/3935/8726 +f 3928/3930/8728 3927/3929/8730 3936/3938/8731 +f 3931/3933/8732 3935/3937/8733 3912/3914/8734 +f 3935/3937/8733 3913/3915/8735 3912/3914/8734 +f 3935/3937/8736 3934/3936/8737 3913/3915/8738 +f 3934/3936/8737 3919/3921/8739 3913/3915/8738 +f 3919/3921/8740 3934/3936/8741 3920/3922/8742 +f 3934/3936/8741 3933/3935/8743 3920/3922/8742 +f 3920/3922/8744 3933/3935/8744 3918/3920/8744 +f 3933/3935/8745 3936/3938/8745 3918/3920/8745 +f 3918/3920/8746 3936/3938/8746 3917/3919/8746 +f 3936/3938/8747 3932/3934/8748 3917/3919/8749 +f 3932/3934/8748 3914/3916/8750 3917/3919/8749 +f 3932/3934/8751 3931/3933/8752 3914/3916/8753 +f 3931/3933/8752 3912/3914/8754 3914/3916/8753 +f 3915/3917/8755 3937/3939/8756 3916/3918/8757 +f 3937/3939/8756 3938/3940/8758 3916/3918/8757 +f 3911/3913/8759 3937/3939/8759 3915/3917/8759 +f 3939/3941/8760 3937/3939/8761 3911/3913/8762 +f 3913/3915/8763 3939/3941/8760 3911/3913/8762 +f 3916/3918/8764 3938/3940/8764 3913/3915/8764 +f 3938/3940/8765 3939/3941/8765 3913/3915/8765 +f 3939/3941/2352 3938/3940/2352 3937/3939/2352 +f 3940/3942/8766 3941/3943/8766 3942/3944/8766 +f 3940/3942/8767 3943/3945/8767 3941/3943/8767 +f 3943/3945/8768 3944/3946/8768 3941/3943/8768 +f 3943/3945/8769 3945/3947/8770 3944/3946/8771 +f 3943/3945/8769 3946/3948/8772 3945/3947/8770 +f 3946/3948/8773 3947/3949/8773 3945/3947/8773 +f 3947/3949/8774 3948/3950/8774 3945/3947/8774 +f 3947/3949/8775 3949/3951/8776 3948/3950/8777 +f 3950/3952/8778 3951/3953/8778 3949/3951/8778 +f 3951/3953/8779 3948/3950/8777 3949/3951/8776 +f 3950/3952/8780 3952/3954/8781 3951/3953/8782 +f 3950/3952/8780 3953/3955/8783 3952/3954/8781 +f 3953/3955/8784 3954/3956/8785 3952/3954/8786 +f 3953/3955/8784 3955/3957/8787 3954/3956/8785 +f 3955/3957/8788 3956/3958/8788 3954/3956/8788 +f 3956/3958/8789 3957/3959/8789 3954/3956/8789 +f 3956/3958/8790 3958/3960/8790 3957/3959/8790 +f 3958/3960/8791 3959/3961/8791 3957/3959/8791 +f 3958/3960/8792 3960/3962/8792 3959/3961/8792 +f 3960/3962/8793 3961/3963/8793 3959/3961/8793 +f 3960/3962/8794 3962/3964/8794 3961/3963/8794 +f 3940/3942/8795 3942/3944/8795 3962/3964/8795 +f 3962/3964/8796 3960/3962/8797 3940/3942/8798 +f 3947/3949/3031 3955/3957/3031 3953/3955/3031 +f 3947/3949/3031 3953/3955/3031 3950/3952/3031 +f 3949/3951/3031 3947/3949/3031 3950/3952/3031 +f 3946/3948/3031 3956/3958/3031 3955/3957/3031 +f 3947/3949/3031 3946/3948/3031 3955/3957/3031 +f 3943/3945/3031 3940/3942/8798 3960/3962/8797 +f 3943/3945/3031 3960/3962/8797 3958/3960/3031 +f 3943/3945/3031 3958/3960/3031 3956/3958/3031 +f 3946/3948/3031 3943/3945/3031 3956/3958/3031 +f 3945/3947/3026 3948/3950/3026 3954/3956/3026 +f 3948/3950/3026 3952/3954/3026 3954/3956/3026 +f 3948/3950/3026 3951/3953/3026 3952/3954/3026 +f 3945/3947/3026 3954/3956/3026 3957/3959/3026 +f 3944/3946/3026 3945/3947/3026 3957/3959/3026 +f 3944/3946/3026 3957/3959/3026 3959/3961/3026 +f 3942/3944/8799 3961/3963/8800 3962/3964/8801 +f 3942/3944/8799 3941/3943/3026 3961/3963/8800 +f 3941/3943/3026 3944/3946/3026 3959/3961/3026 +f 3941/3943/3026 3959/3961/3026 3961/3963/8800 +f 3963/3965/8802 3964/3966/8803 3965/3967/8804 +f 3963/3965/8805 3966/3968/8805 3964/3966/8805 +f 3966/3968/8806 3967/3969/8806 3964/3966/8806 +f 3966/3968/8807 3968/3970/8807 3967/3969/8807 +f 3968/3970/8808 3969/3971/8808 3967/3969/8808 +f 3968/3970/8809 3970/3972/8810 3969/3971/8811 +f 3970/3972/8810 3971/3973/8812 3969/3971/8811 +f 3970/3972/8813 3972/3974/8813 3971/3973/8813 +f 3973/3975/8814 3974/3976/8814 3972/3974/8814 +f 3974/3976/8815 3971/3973/8815 3972/3974/8815 +f 3973/3975/8816 3975/3977/8816 3974/3976/8816 +f 3975/3977/8817 3976/3978/8817 3974/3976/8817 +f 3975/3977/8818 3977/3979/8818 3976/3978/8818 +f 3977/3979/8819 3978/3980/8819 3976/3978/8819 +f 3977/3979/8820 3979/3981/8820 3978/3980/8820 +f 3979/3981/8821 3980/3982/8821 3978/3980/8821 +f 3979/3981/8822 3981/3983/8822 3980/3982/8822 +f 3981/3983/8823 3982/3984/8823 3980/3982/8823 +f 3981/3983/8824 3983/3985/8824 3982/3984/8824 +f 3983/3985/8825 3984/3986/8825 3982/3984/8825 +f 3983/3985/8826 3985/3987/8826 3984/3986/8826 +f 3985/3987/8827 3986/3988/8827 3984/3986/8827 +f 3985/3987/8828 3987/3989/8828 3986/3988/8828 +f 3963/3965/8802 3965/3967/8804 3987/3989/8829 +f 3965/3967/8830 3986/3988/8830 3987/3989/8830 +f 3970/3972/3031 3977/3979/3031 3975/3977/3031 +f 3970/3972/3031 3968/3970/3031 3977/3979/3031 +f 3972/3974/3031 3970/3972/3031 3973/3975/3031 +f 3970/3972/3031 3975/3977/3031 3973/3975/3031 +f 3966/3968/3031 3983/3985/3031 3981/3983/3031 +f 3968/3970/3031 3979/3981/3031 3977/3979/3031 +f 3963/3965/3031 3987/3989/3031 3985/3987/3031 +f 3966/3968/3031 3963/3965/3031 3983/3985/3031 +f 3963/3965/3031 3985/3987/3031 3983/3985/3031 +f 3968/3970/3031 3966/3968/3031 3981/3983/3031 +f 3968/3970/3031 3981/3983/3031 3979/3981/3031 +f 3969/3971/3026 3976/3978/3026 3978/3980/3026 +f 3969/3971/3026 3971/3973/3026 3976/3978/3026 +f 3971/3973/3026 3974/3976/3026 3976/3978/3026 +f 3969/3971/3026 3978/3980/3026 3980/3982/3026 +f 3967/3969/3026 3969/3971/3026 3980/3982/3026 +f 3967/3969/3026 3980/3982/3026 3982/3984/3026 +f 3964/3966/3026 3967/3969/3026 3982/3984/3026 +f 3965/3967/3026 3964/3966/3026 3986/3988/3026 +f 3964/3966/3026 3982/3984/3026 3984/3986/3026 +f 3964/3966/3026 3984/3986/3026 3986/3988/3026 +f 3988/3990/8831 3989/3991/8831 3990/3992/8831 +f 3989/3991/8832 3991/3993/8833 3990/3992/8834 +f 3989/3991/8832 3992/3994/8835 3991/3993/8833 +f 3992/3994/8836 3993/3995/8837 3991/3993/8838 +f 3992/3994/8836 3994/3996/8839 3993/3995/8837 +f 3994/3996/8840 3995/3997/8841 3993/3995/8842 +f 3994/3996/8840 3996/3998/8843 3995/3997/8841 +f 3996/3998/8844 3997/3999/8845 3995/3997/8846 +f 3997/3999/8845 3998/4000/8847 3995/3997/8846 +f 3999/4001/8848 3998/4000/8848 3997/3999/8848 +f 3999/4001/8849 4000/4002/8849 3998/4000/8849 +f 3999/4001/8850 4001/4003/8850 4000/4002/8850 +f 4001/4003/8851 4002/4004/8851 4000/4002/8851 +f 4001/4003/8852 4003/4005/8852 4002/4004/8852 +f 4003/4005/8853 4004/4006/8853 4002/4004/8853 +f 4003/4005/8854 4005/4007/8854 4004/4006/8854 +f 4005/4007/8855 4006/4008/8856 4004/4006/8857 +f 4005/4007/8855 4007/4009/8858 4006/4008/8856 +f 4007/4009/8859 4008/4010/8859 4006/4008/8859 +f 4008/4010/8860 4009/4011/8860 4006/4008/8860 +f 4008/4010/8861 4010/4012/8861 4009/4011/8861 +f 4010/4012/8862 4011/4013/8862 4009/4011/8862 +f 3988/3990/8863 4011/4013/8863 4010/4012/8863 +f 4010/4012/8864 3989/3991/8865 3988/3990/8866 +f 3997/3999/3085 4001/4003/3085 3999/4001/3085 +f 3997/3999/3085 3996/3998/3085 4001/4003/3085 +f 3996/3998/3085 4003/4005/3085 4001/4003/3085 +f 3996/3998/3085 3994/3996/3085 4003/4005/3085 +f 3989/3991/8865 4010/4012/8864 4008/4010/3085 +f 3992/3994/3085 4008/4010/3085 4007/4009/3085 +f 3992/3994/3085 3989/3991/8865 4008/4010/3085 +f 3992/3994/3085 4007/4009/3085 4005/4007/3085 +f 4003/4005/3085 3994/3996/3085 4005/4007/3085 +f 3994/3996/3085 3992/3994/3085 4005/4007/3085 +f 3995/3997/2352 4000/4002/2352 4002/4004/2352 +f 3995/3997/2352 3998/4000/2352 4000/4002/2352 +f 3993/3995/2352 3995/3997/2352 4002/4004/2352 +f 3993/3995/2352 4002/4004/2352 4004/4006/2352 +f 3991/3993/2352 4004/4006/2352 4006/4008/2352 +f 3991/3993/2352 3993/3995/2352 4004/4006/2352 +f 3988/3990/8867 3990/3992/8867 4011/4013/8867 +f 3990/3992/2352 4009/4011/2352 4011/4013/2352 +f 3990/3992/2352 3991/3993/2352 4009/4011/2352 +f 3991/3993/2352 4006/4008/2352 4009/4011/2352 +f 4012/4014/8868 4013/4015/8869 4014/4016/8870 +f 4012/4014/8871 4015/4017/8871 4013/4015/8871 +f 4015/4017/8872 4016/4018/8872 4013/4015/8872 +f 4015/4017/8873 4017/4019/8873 4016/4018/8873 +f 4017/4019/8874 4018/4020/8874 4016/4018/8874 +f 4017/4019/8875 4019/4021/8876 4018/4020/8877 +f 4017/4019/8875 4020/4022/8878 4019/4021/8876 +f 4020/4022/8879 4021/4023/8880 4019/4021/8881 +f 4021/4023/8880 4022/4024/8882 4019/4021/8881 +f 4023/4025/8883 4022/4024/8882 4021/4023/8880 +f 4023/4025/8884 4024/4026/8884 4025/4027/8884 +f 4024/4026/8885 4026/4028/8885 4025/4027/8885 +f 4024/4026/8886 4027/4029/8886 4026/4028/8886 +f 4027/4029/8887 4028/4030/8887 4026/4028/8887 +f 4027/4029/8888 4029/4031/8888 4028/4030/8888 +f 4029/4031/8889 4030/4032/8889 4028/4030/8889 +f 4029/4031/8890 4031/4033/8891 4030/4032/8892 +f 4029/4031/8890 4032/4034/8893 4031/4033/8891 +f 4032/4034/8894 4033/4035/8894 4031/4033/8894 +f 4033/4035/8895 4034/4036/8895 4031/4033/8895 +f 4033/4035/8896 4035/4037/8896 4034/4036/8896 +f 4012/4014/8868 4014/4016/8870 4035/4037/8897 +f 4014/4016/8898 4034/4036/8898 4035/4037/8898 +f 4035/4037/3085 4033/4035/3085 4012/4014/3085 +f 4020/4022/3085 4027/4029/3085 4024/4026/8899 +f 4021/4023/8900 4020/4022/3085 4024/4026/8899 +f 4021/4023/8900 4024/4026/8899 4023/4025/8901 +f 4017/4019/3085 4029/4031/3085 4027/4029/3085 +f 4020/4022/3085 4017/4019/3085 4027/4029/3085 +f 4015/4017/3085 4012/4014/3085 4033/4035/3085 +f 4015/4017/3085 4033/4035/3085 4032/4034/3085 +f 4015/4017/3085 4032/4034/3085 4029/4031/3085 +f 4017/4019/3085 4015/4017/3085 4029/4031/3085 +f 4023/4025/8902 4025/4027/8903 4022/4024/8904 +f 4019/4021/2352 4025/4027/8903 4026/4028/2352 +f 4019/4021/2352 4022/4024/8904 4025/4027/8903 +f 4018/4020/2352 4026/4028/2352 4028/4030/2352 +f 4018/4020/2352 4019/4021/2352 4026/4028/2352 +f 4016/4018/2352 4018/4020/2352 4030/4032/2352 +f 4018/4020/2352 4028/4030/2352 4030/4032/2352 +f 4016/4018/2352 4030/4032/2352 4031/4033/2352 +f 4013/4015/2352 4016/4018/2352 4031/4033/2352 +f 4014/4016/2352 4013/4015/2352 4034/4036/2352 +f 4013/4015/2352 4031/4033/2352 4034/4036/2352 +f 4036/4038/8905 4037/4039/8906 4038/4040/8907 +f 4039/4041/8908 4038/4040/8907 4040/4042/8909 +f 4039/4041/8908 4036/4038/8905 4038/4040/8907 +f 4041/4043/8910 4042/4044/8911 4043/4045/8912 +f 4042/4044/8911 4044/4046/8913 4043/4045/8912 +f 4045/4047/8914 4046/4048/8915 4047/4049/8916 +f 4048/4050/8917 4049/4051/8918 4050/4052/8919 +f 4051/4053/8920 4052/4054/8921 4053/4055/8922 +f 4046/4048/8915 4054/4056/8923 4047/4049/8916 +f 4055/4057/8924 4056/4058/8925 4057/4059/8926 +f 4055/4057/8924 4051/4053/8920 4056/4058/8925 +f 4046/4048/8915 4055/4057/8924 4054/4056/8923 +f 4055/4057/8924 4057/4059/8926 4054/4056/8923 +f 4053/4055/8922 4058/4060/8927 4056/4058/8925 +f 4058/4060/8927 4049/4051/8918 4056/4058/8925 +f 4052/4054/8921 4051/4053/8920 4040/4042/8928 +f 4056/4058/8925 4051/4053/8920 4053/4055/8922 +f 4049/4051/8918 4058/4060/8927 4050/4052/8919 +f 4059/4061/8929 4060/4062/8930 4061/4063/8931 +f 4059/4061/8929 4062/4064/8932 4060/4062/8930 +f 4062/4064/8932 4063/4065/8933 4060/4062/8930 +f 4063/4065/8933 4064/4066/8934 4060/4062/8930 +f 4063/4065/8933 4065/4067/8935 4064/4066/8934 +f 4063/4065/8933 4066/4068/8936 4065/4067/8935 +f 4067/4069/8937 4068/4070/8938 4069/4071/8939 +f 4067/4069/8937 4070/4072/8940 4068/4070/8938 +f 4070/4072/8940 4071/4073/8941 4068/4070/8938 +f 4071/4073/8941 4072/4074/8942 4068/4070/8938 +f 4071/4073/8941 4073/4075/8943 4072/4074/8942 +f 4073/4075/8943 4074/4076/8944 4072/4074/8942 +f 4073/4075/8943 4075/4077/8945 4074/4076/8944 +f 4073/4075/8943 4076/4078/8946 4075/4077/8945 +f 4077/4079/8947 4078/4080/8948 4079/4081/8949 +f 4080/4082/8950 4081/4083/8951 4082/4084/8952 +f 4083/4085/8953 4084/4086/8954 4085/4087/8955 +f 4086/4088/8956 4087/4089/8957 4088/4090/8958 +f 4086/4088/8956 4083/4085/8953 4085/4087/8955 +f 4084/4086/8954 4083/4085/8953 4079/4081/8949 +f 4083/4085/8953 4077/4079/8947 4079/4081/8949 +f 4086/4088/8956 4088/4090/8958 4043/4045/8959 +f 4082/4084/8952 4081/4083/8951 4089/4091/8960 +f 4086/4088/8956 4085/4087/8955 4087/4089/8957 +f 4081/4083/8951 4087/4089/8957 4089/4091/8960 +f 4087/4089/8957 4085/4087/8955 4089/4091/8960 +f 4090/4092/8961 4091/4093/8962 4092/4094/8963 +f 4090/4092/8961 4093/4095/8964 4091/4093/8962 +f 4093/4095/8964 4094/4096/8965 4091/4093/8962 +f 4094/4096/8965 4095/4097/8966 4091/4093/8962 +f 4094/4096/8965 4096/4098/8967 4095/4097/8966 +f 4096/4098/8967 4097/4099/8968 4095/4097/8966 +f 4096/4098/8967 4098/4100/8969 4097/4099/8968 +f 4098/4100/8969 4099/4101/8970 4097/4099/8968 +f 4100/4102/8971 4101/4103/8972 4102/4104/8973 +f 4101/4103/8972 4103/4105/8974 4102/4104/8973 +f 4101/4103/8972 4104/4106/8975 4103/4105/8974 +f 4104/4106/8975 4105/4107/8976 4103/4105/8974 +f 4104/4106/8975 4106/4108/8977 4105/4107/8976 +f 4106/4108/8977 4107/4109/8978 4105/4107/8976 +f 4106/4108/8977 4108/4110/8979 4107/4109/8978 +f 4108/4110/8979 4109/4111/8980 4107/4109/8978 +f 4108/4110/8979 4110/4112/8981 4109/4111/8980 +f 4110/4112/8981 4111/4113/8982 4109/4111/8980 +f 4110/4112/8981 4112/4114/8983 4111/4113/8982 +f 4112/4114/8983 4113/4115/8984 4111/4113/8982 +f 4112/4114/8983 4114/4116/8985 4113/4115/8984 +f 4112/4114/8983 4115/4117/8986 4114/4116/8985 +f 4115/4117/8986 4116/4118/8987 4114/4116/8985 +f 4115/4117/8986 4117/4119/8988 4116/4118/8987 +f 4117/4119/8988 4118/4120/8989 4116/4118/8987 +f 4119/4121/8990 4055/4057/8924 4120/4122/8991 +f 4119/4121/8990 4051/4053/8920 4055/4057/8924 +f 4121/4123/8992 4119/4121/8990 4120/4122/8991 +f 4122/4124/8993 4121/4123/8992 4123/4125/8994 +f 4121/4123/8992 4120/4122/8991 4123/4125/8994 +f 4123/4125/8994 4124/4126/8995 4122/4124/8993 +f 4123/4125/8994 4125/4127/8996 4124/4126/8995 +f 4126/4128/8997 4125/4127/8996 4127/4129/8998 +f 4126/4128/8997 4124/4126/8995 4125/4127/8996 +f 4127/4129/8998 4128/4130/8999 4126/4128/8997 +f 4127/4129/8998 4129/4131/9000 4128/4130/8999 +f 4086/4088/8956 4129/4131/9000 4083/4085/8953 +f 4129/4131/9000 4127/4129/8998 4083/4085/8953 +f 4130/4132/9001 4131/4133/9002 4132/4134/9003 +f 4131/4133/9002 4133/4135/9004 4132/4134/9003 +f 4131/4133/9002 4134/4136/9005 4133/4135/9004 +f 4134/4136/9005 4135/4137/9006 4133/4135/9004 +f 4134/4136/9005 4136/4138/9007 4135/4137/9006 +f 4134/4136/9005 4137/4139/9008 4136/4138/9007 +f 4138/4140/9009 4139/4141/9010 4066/4068/9011 +f 4139/4141/9010 4140/4142/9012 4066/4068/9011 +f 4062/4064/9013 4138/4140/9009 4066/4068/9011 +f 4140/4142/9012 4130/4132/9014 4141/4143/9015 +f 4130/4132/9014 4140/4142/9012 4139/4141/9010 +f 4139/4141/9010 4142/4144/9016 4130/4132/9014 +f 4131/4133/9017 4130/4132/9014 4134/4136/9018 +f 4143/4145/9019 4059/4061/9020 4144/4146/9021 +f 4145/4147/9022 4137/4139/9023 4134/4136/9018 +f 4145/4147/9022 4146/4148/9024 4137/4139/9023 +f 4134/4136/9018 4147/4149/9025 4145/4147/9022 +f 4130/4132/9014 4142/4144/9016 4147/4149/9025 +f 4130/4132/9014 4147/4149/9025 4134/4136/9018 +f 4062/4064/9013 4066/4068/9011 4063/4065/9026 +f 4143/4145/9019 4148/4150/9027 4059/4061/9020 +f 4148/4150/9027 4062/4064/9013 4059/4061/9020 +f 4148/4150/9027 4138/4140/9009 4062/4064/9013 +f 4149/4151/9028 4150/4152/9029 4151/4153/9030 +f 4152/4154/98 4153/4155/98 4154/4156/98 +f 4067/4069/9031 4155/4157/9032 4071/4073/9033 +f 4155/4157/9032 4067/4069/9031 4156/4158/9034 +f 4094/4096/9035 4098/4100/9036 4096/4098/9037 +f 4157/4159/9038 4158/4160/9039 4159/4161/9040 +f 4157/4159/9038 4160/4162/9041 4158/4160/9039 +f 4160/4162/9041 4090/4092/9042 4158/4160/9039 +f 4076/4078/9043 4161/4163/9044 4162/4164/9045 +f 4163/4165/9046 4156/4158/9034 4098/4100/9036 +f 4094/4096/9035 4163/4165/9046 4098/4100/9036 +f 4161/4163/9044 4164/4166/9047 4162/4164/9045 +f 4164/4166/9047 4165/4167/9048 4162/4164/9045 +f 4166/4168/9049 4156/4158/9034 4067/4069/9031 +f 4098/4100/9036 4166/4168/9049 4167/4169/9050 +f 4067/4069/9031 4071/4073/9033 4070/4072/9051 +f 4076/4078/9043 4168/4170/9052 4161/4163/9044 +f 4094/4096/9035 4169/4171/9053 4163/4165/9046 +f 4160/4162/9041 4169/4171/9053 4090/4092/9042 +f 4169/4171/9053 4093/4095/9054 4090/4092/9042 +f 4073/4075/9055 4168/4170/9052 4076/4078/9043 +f 4156/4158/9034 4166/4168/9049 4098/4100/9036 +f 4155/4157/9032 4168/4170/9052 4071/4073/9033 +f 4168/4170/9052 4073/4075/9055 4071/4073/9033 +f 4169/4171/9053 4094/4096/9035 4093/4095/9054 +f 4080/4082/8950 4041/4043/8910 4170/4172/9056 +f 4078/4080/8948 4171/4173/9057 4172/4174/9058 +f 4173/4175/9059 4042/4044/9060 4174/4176/9061 +f 4042/4044/9060 4077/4079/9062 4174/4176/9061 +f 4100/4102/9063 4175/4177/9064 4101/4103/9065 +f 4175/4177/9064 4176/4178/9066 4101/4103/9065 +f 4176/4178/9066 4104/4106/9067 4101/4103/9065 +f 4176/4178/9066 4177/4179/9068 4104/4106/9067 +f 4177/4179/9068 4106/4108/9069 4104/4106/9067 +f 4177/4179/9068 4178/4180/9070 4106/4108/9069 +f 4178/4180/9070 4108/4110/9071 4106/4108/9069 +f 4178/4180/9070 4179/4181/9072 4108/4110/9071 +f 4108/4110/9071 4179/4181/9072 4110/4112/9073 +f 4110/4112/9073 4179/4181/9072 4112/4114/9074 +f 4179/4181/9072 4180/4182/9075 4112/4114/9074 +f 4180/4182/9075 4181/4183/9076 4112/4114/9074 +f 4181/4183/9076 4115/4117/9077 4112/4114/9074 +f 4181/4183/9076 4182/4184/9078 4115/4117/9077 +f 4182/4184/9078 4117/4119/9079 4115/4117/9077 +f 4102/4104/9080 4103/4105/9081 4143/4145/9082 +f 4103/4105/9081 4148/4150/9083 4143/4145/9082 +f 4103/4105/9081 4105/4107/9084 4148/4150/9083 +f 4105/4107/9084 4138/4140/9085 4148/4150/9083 +f 4105/4107/9084 4107/4109/9086 4138/4140/9085 +f 4107/4109/9086 4109/4111/9087 4138/4140/9085 +f 4109/4111/9087 4139/4141/9088 4138/4140/9085 +f 4109/4111/9087 4142/4144/9089 4139/4141/9088 +f 4109/4111/9087 4111/4113/9090 4142/4144/9089 +f 4111/4113/9090 4147/4149/9091 4142/4144/9089 +f 4111/4113/9090 4113/4115/9092 4147/4149/9091 +f 4113/4115/9092 4145/4147/9093 4147/4149/9091 +f 4113/4115/9092 4114/4116/9094 4145/4147/9093 +f 4116/4118/9095 4146/4148/9096 4145/4147/9093 +f 4116/4118/9095 4118/4120/9097 4146/4148/9096 +f 4114/4116/9094 4116/4118/9095 4145/4147/9093 +f 4089/4091/9098 4183/4185/9098 4082/4084/9098 +f 4089/4091/9099 4085/4087/9100 4183/4185/9101 +f 4085/4087/9100 4171/4173/9102 4183/4185/9101 +f 4085/4087/9103 4084/4086/9103 4171/4173/9103 +f 4084/4086/9104 4172/4174/9104 4171/4173/9104 +f 4084/4086/9105 4079/4081/9105 4172/4174/9105 +f 4079/4081/9106 4078/4080/9106 4172/4174/9106 +f 4043/4045/9107 4170/4172/9108 4184/4186/9109 +f 4043/4045/9107 4088/4090/9110 4170/4172/9108 +f 4088/4090/9111 4087/4089/9111 4170/4172/9111 +f 4087/4089/9112 4185/4187/9112 4170/4172/9112 +f 4087/4089/9113 4081/4083/9113 4185/4187/9113 +f 4081/4083/9114 4080/4082/9114 4185/4187/9114 +f 4184/4186/9115 4041/4043/9115 4043/4045/9115 +f 4078/4080/8948 4082/4084/8952 4171/4173/9057 +f 4186/4188/9116 4187/4189/9117 4188/4190/9118 +f 4188/4190/9118 4174/4176/9119 4189/4191/9120 +f 4190/4192/9121 4187/4189/9117 4186/4188/9116 +f 4170/4172/9056 4041/4043/8910 4184/4186/9122 +f 4185/4187/9123 4080/4082/8950 4170/4172/9056 +f 4082/4084/8952 4183/4185/9124 4171/4173/9057 +f 4188/4190/9118 4187/4189/9117 4174/4176/9119 +f 4187/4189/9125 4173/4175/9126 4174/4176/9127 +f 4041/4043/8910 4078/4080/8948 4077/4079/8947 +f 4041/4043/8910 4080/4082/8950 4078/4080/8948 +f 4078/4080/8948 4080/4082/8950 4082/4084/8952 +f 4041/4043/8910 4077/4079/8947 4042/4044/8911 +f 4144/4146/9128 4061/4063/8931 4173/4175/9126 +f 4144/4146/9128 4059/4061/8929 4061/4063/8931 +f 4144/4146/9128 4173/4175/9126 4187/4189/9125 +f 4144/4146/9129 4190/4192/9130 4143/4145/9131 +f 4144/4146/9129 4187/4189/9132 4190/4192/9130 +f 4143/4145/9133 4190/4192/9134 4186/4188/9135 +f 4143/4145/9133 4186/4188/9135 4102/4104/9136 +f 4188/4190/9137 4100/4102/9138 4186/4188/9139 +f 4100/4102/9138 4102/4104/9140 4186/4188/9139 +f 4188/4190/9137 4189/4191/9141 4100/4102/9138 +f 4189/4191/9141 4175/4177/9142 4100/4102/9138 +f 4191/4193/9143 4050/4052/8919 4192/4194/9144 +f 4037/4039/8906 4193/4195/9145 4194/4196/9146 +f 4036/4038/9147 4195/4197/9148 4196/4198/9149 +f 4195/4197/9148 4197/4199/9150 4196/4198/9149 +f 4054/4056/9151 4198/4200/9151 4047/4049/9151 +f 4054/4056/9152 4057/4059/9153 4198/4200/9154 +f 4057/4059/9153 4199/4201/9155 4198/4200/9154 +f 4057/4059/9156 4200/4202/9157 4199/4201/9158 +f 4057/4059/9156 4056/4058/9159 4200/4202/9157 +f 4056/4058/9160 4049/4051/9161 4200/4202/9162 +f 4049/4051/9161 4201/4203/9163 4200/4202/9162 +f 4049/4051/9164 4048/4050/9164 4201/4203/9164 +f 4198/4200/9165 4199/4201/9166 4047/4049/8916 +f 4199/4201/9166 4045/4047/8914 4047/4049/8916 +f 4202/4204/9167 4203/4205/9168 4204/4206/9169 +f 4197/4199/9170 4202/4204/9167 4205/4207/9171 +f 4050/4052/8919 4193/4195/9145 4037/4039/8906 +f 4050/4052/8919 4191/4193/9143 4193/4195/9145 +f 4199/4201/9166 4200/4202/9172 4045/4047/8914 +f 4200/4202/9172 4048/4050/8917 4045/4047/8914 +f 4200/4202/9172 4201/4203/9173 4048/4050/8917 +f 4206/4208/9174 4204/4206/9169 4203/4205/9168 +f 4197/4199/9170 4203/4205/9168 4202/4204/9167 +f 4193/4195/9175 4038/4040/9175 4194/4196/9175 +f 4038/4040/9176 4037/4039/9176 4194/4196/9176 +f 4058/4060/9177 4192/4194/9177 4050/4052/9177 +f 4058/4060/9178 4053/4055/9179 4192/4194/9180 +f 4053/4055/9179 4191/4193/9181 4192/4194/9180 +f 4053/4055/9182 4052/4054/9183 4191/4193/9184 +f 4052/4054/9183 4193/4195/9185 4191/4193/9184 +f 4052/4054/9186 4040/4042/9186 4193/4195/9186 +f 4038/4040/9187 4193/4195/9187 4040/4042/9187 +f 4203/4205/9188 4197/4199/9189 4195/4197/9190 +f 4036/4038/8905 4050/4052/8919 4037/4039/8906 +f 4050/4052/8919 4045/4047/8914 4048/4050/8917 +f 4050/4052/8919 4036/4038/8905 4045/4047/8914 +f 4045/4047/9191 4036/4038/9191 4046/4048/9191 +f 4036/4038/9147 4196/4198/9149 4046/4048/9192 +f 4137/4139/9193 4195/4197/9190 4136/4138/9194 +f 4203/4205/9188 4195/4197/9190 4137/4139/9193 +f 4146/4148/9024 4203/4205/9195 4137/4139/9023 +f 4146/4148/9024 4206/4208/9196 4203/4205/9195 +f 4204/4206/9197 4206/4208/9198 4118/4120/9199 +f 4206/4208/9198 4146/4148/9200 4118/4120/9199 +f 4117/4119/9201 4202/4204/9202 4118/4120/9203 +f 4202/4204/9202 4204/4206/9204 4118/4120/9203 +f 4117/4119/9205 4182/4184/9206 4202/4204/9207 +f 4182/4184/9206 4205/4207/9208 4202/4204/9207 +f 4207/4209/9209 4098/4100/8969 4167/4169/9210 +f 4207/4209/9209 4099/4101/8970 4098/4100/8969 +f 4208/4210/9211 4167/4169/9212 4166/4168/9213 +f 4208/4210/9211 4207/4209/9214 4167/4169/9212 +f 4069/4071/9215 4208/4210/9216 4067/4069/9217 +f 4208/4210/9216 4166/4168/9218 4067/4069/9217 +f 4132/4134/9219 4209/4211/9220 4149/4151/9028 +f 4210/4212/9221 4211/4213/9222 4099/4101/9223 +f 4212/4214/9224 4068/4070/9225 4213/4215/9226 +f 4095/4097/9227 4097/4099/9228 4211/4213/9222 +f 4213/4215/9226 4068/4070/9225 4214/4216/9229 +f 4211/4213/9222 4215/4217/9230 4095/4097/9227 +f 4216/4218/9231 4136/4138/9232 4195/4197/9233 +f 4072/4074/9234 4217/4219/9235 4214/4216/9229 +f 4074/4076/9236 4218/4220/9237 4217/4219/9235 +f 4219/4221/9238 4091/4093/9239 4220/4222/9240 +f 4220/4222/9240 4095/4097/9227 4215/4217/9230 +f 4074/4076/9236 4217/4219/9235 4072/4074/9234 +f 4068/4070/9225 4212/4214/9224 4069/4071/9241 +f 4220/4222/9240 4091/4093/9239 4095/4097/9227 +f 4075/4077/9242 4218/4220/9237 4074/4076/9236 +f 4219/4221/9238 4092/4094/9243 4091/4093/9239 +f 4210/4212/9221 4069/4071/9241 4212/4214/9224 +f 4099/4101/9223 4207/4209/9244 4210/4212/9221 +f 4221/4223/9245 4075/4077/9246 4162/4164/9247 +f 4075/4077/9246 4076/4078/9248 4162/4164/9247 +f 4162/4164/9249 4222/4224/9250 4221/4223/9251 +f 4162/4164/9249 4165/4167/9252 4222/4224/9250 +f 4165/4167/9253 4223/4225/9254 4222/4224/9255 +f 4150/4152/9256 4065/4067/9257 4140/4142/9258 +f 4065/4067/9257 4066/4068/9259 4140/4142/9258 +f 4151/4153/9260 4140/4142/9261 4141/4143/9262 +f 4151/4153/9260 4150/4152/9263 4140/4142/9261 +f 4132/4134/9264 4151/4153/9265 4130/4132/9266 +f 4151/4153/9265 4141/4143/9267 4130/4132/9266 +f 4159/4161/9268 4224/4226/9269 4225/4227/9270 +f 4224/4226/9271 4226/4228/9272 4225/4227/9273 +f 4224/4226/9271 4158/4160/9274 4226/4228/9272 +f 4092/4094/9275 4226/4228/9276 4090/4092/9277 +f 4226/4228/9276 4158/4160/9278 4090/4092/9277 +f 4161/4163/9279 4227/4229/9280 4228/4230/9281 +f 4161/4163/9279 4229/4231/9282 4227/4229/9280 +f 4229/4231/9283 4230/4232/9283 4227/4229/9283 +f 4229/4231/9284 4164/4166/9284 4230/4232/9284 +f 4231/4233/9285 4230/4232/9285 4164/4166/9285 +f 4228/4230/9286 4164/4166/9287 4161/4163/9288 +f 4228/4230/9286 4231/4233/9289 4164/4166/9287 +f 4157/4159/9290 4152/4154/9291 4154/4156/9292 +f 4157/4159/9290 4232/4234/9293 4152/4154/9291 +f 4232/4234/9294 4153/4155/9295 4152/4154/9296 +f 4153/4155/9295 4232/4234/9294 4160/4162/9297 +f 4154/4156/9298 4160/4162/9299 4157/4159/9300 +f 4154/4156/9298 4153/4155/9301 4160/4162/9299 +f 4223/4225/9302 4165/4167/9048 4164/4166/9047 +f 4223/4225/9302 4164/4166/9047 4229/4231/9303 +f 4229/4231/9303 4233/4235/9304 4223/4225/9302 +f 4168/4170/9052 4229/4231/9303 4161/4163/9044 +f 4086/4088/9305 4043/4045/9306 4233/4235/9304 +f 4168/4170/9052 4233/4235/9304 4229/4231/9303 +f 4168/4170/9052 4086/4088/9305 4233/4235/9304 +f 4121/4123/8992 4122/4124/8993 4234/4236/9307 +f 4119/4121/9308 4234/4236/9307 4169/4171/9053 +f 4119/4121/9308 4121/4123/8992 4234/4236/9307 +f 4124/4126/9309 4126/4128/9310 4156/4158/9311 +f 4086/4088/9305 4168/4170/9052 4129/4131/9312 +f 4051/4053/8920 4119/4121/9308 4169/4171/9053 +f 4122/4124/9313 4124/4126/9309 4163/4165/9314 +f 4124/4126/9309 4156/4158/9311 4163/4165/9314 +f 4126/4128/9310 4128/4130/9315 4156/4158/9311 +f 4122/4124/9313 4163/4165/9314 4234/4236/9316 +f 4128/4130/9315 4129/4131/9312 4155/4157/9317 +f 4129/4131/9312 4168/4170/9052 4155/4157/9317 +f 4234/4236/9318 4163/4165/9318 4169/4171/9318 +f 4128/4130/9315 4155/4157/9317 4156/4158/9311 +f 4160/4162/9041 4232/4234/9319 4169/4171/9053 +f 4159/4161/9320 4235/4237/9321 4157/4159/9322 +f 4235/4237/9321 4232/4234/9319 4157/4159/9322 +f 4235/4237/9321 4169/4171/9053 4232/4234/9319 +f 4235/4237/9321 4051/4053/8920 4169/4171/9053 +f 4040/4042/8928 4051/4053/8920 4235/4237/9321 +f 4223/4225/9254 4236/4238/9323 4222/4224/9255 +f 4236/4238/9323 4223/4225/9254 4233/4235/9324 +f 4233/4235/9324 4044/4046/8913 4236/4238/9323 +f 4233/4235/9324 4043/4045/8912 4044/4046/8913 +f 4237/4239/9325 4039/4041/8908 4235/4237/9326 +f 4039/4041/8908 4040/4042/8909 4235/4237/9326 +f 4237/4239/9325 4235/4237/9326 4159/4161/9268 +f 4159/4161/9268 4225/4227/9270 4237/4239/9325 +f 4196/4198/9327 4055/4057/9327 4046/4048/9327 +f 4159/4161/9040 4158/4160/9039 4224/4226/9328 +f 4238/4240/9329 4239/4241/9330 4240/4242/9331 +f 4241/4243/9332 4242/4244/9333 4243/4245/9334 +f 4244/4246/9335 4239/4241/9330 4238/4240/9329 +f 4243/4245/9334 4242/4244/9333 4244/4246/9335 +f 4242/4244/9333 4239/4241/9330 4244/4246/9335 +f 4245/4247/9336 4246/4248/9337 4247/4249/9338 +f 4239/4241/9330 4247/4249/9338 4240/4242/9331 +f 4239/4241/9330 4245/4247/9336 4247/4249/9338 +f 4245/4247/9336 4241/4243/9332 4246/4248/9337 +f 4245/4247/9336 4242/4244/9333 4241/4243/9332 +f 4248/4250/9339 4249/4251/9340 4250/4252/9341 +f 4251/4253/9342 4248/4250/9339 4250/4252/9341 +f 4248/4250/9339 4251/4253/9342 4252/4254/9343 +f 4253/4255/9344 4248/4250/9344 4252/4254/9344 +f 4253/4255/9345 4249/4251/9346 4248/4250/9347 +f 4253/4255/9345 4254/4256/9348 4249/4251/9346 +f 4254/4256/9349 4250/4252/9349 4249/4251/9349 +f 4254/4256/9350 4255/4257/9350 4250/4252/9350 +f 4255/4257/9351 4251/4253/9351 4250/4252/9351 +f 4255/4257/9352 4256/4258/9352 4251/4253/9352 +f 4256/4258/9353 4252/4254/9353 4251/4253/9353 +f 4256/4258/9354 4253/4255/9354 4252/4254/9354 +f 4254/4256/9355 4253/4255/9356 4257/4259/9357 +f 4253/4255/9356 4258/4260/9358 4257/4259/9357 +f 4255/4257/9359 4259/4261/9360 4260/4262/9361 +f 4256/4258/9362 4260/4262/9361 4261/4263/9363 +f 4256/4258/9362 4255/4257/9359 4260/4262/9361 +f 4258/4260/9358 4253/4255/9356 4261/4263/9363 +f 4253/4255/9356 4256/4258/9362 4261/4263/9363 +f 4254/4256/9355 4257/4259/9357 4262/4264/9364 +f 4255/4257/9359 4254/4256/9355 4259/4261/9360 +f 4254/4256/9355 4262/4264/9364 4259/4261/9360 +f 4258/4260/9365 4261/4263/9366 4241/4243/9367 +f 4241/4243/9368 4261/4263/9369 4246/4248/9370 +f 4261/4263/9369 4260/4262/9371 4246/4248/9370 +f 4246/4248/9372 4260/4262/9373 4247/4249/9374 +f 4260/4262/9373 4259/4261/9375 4247/4249/9374 +f 4259/4261/9376 4240/4242/9376 4247/4249/9376 +f 4259/4261/9377 4262/4264/9378 4240/4242/9379 +f 4240/4242/9379 4262/4264/9378 4238/4240/9380 +f 4238/4240/9381 4262/4264/9382 4244/4246/9383 +f 4262/4264/9382 4257/4259/9384 4244/4246/9383 +f 4244/4246/9385 4257/4259/9386 4243/4245/9387 +f 4257/4259/9386 4258/4260/9388 4243/4245/9387 +f 4258/4260/9365 4241/4243/9367 4243/4245/9389 +f 4239/4241/9390 4263/4265/9391 4245/4247/9392 +f 4263/4265/9391 4264/4266/9393 4245/4247/9392 +f 4242/4244/9394 4265/4267/9394 4239/4241/9394 +f 4265/4267/9395 4263/4265/9395 4239/4241/9395 +f 4266/4268/9396 4265/4267/9396 4242/4244/9396 +f 4245/4247/9397 4266/4268/9397 4242/4244/9397 +f 4264/4266/9398 4266/4268/9398 4245/4247/9398 +f 4266/4268/2352 4263/4265/2352 4265/4267/2352 +f 4266/4268/2352 4264/4266/2352 4263/4265/2352 +f 4267/4269/9399 4268/4270/9400 4269/4271/9401 +f 4267/4269/9399 4270/4272/9402 4268/4270/9400 +f 4270/4272/9402 4271/4273/9403 4268/4270/9400 +f 4270/4272/9402 4272/4274/9404 4273/4275/9405 +f 4270/4272/9402 4274/4276/9406 4272/4274/9404 +f 4270/4272/9402 4273/4275/9405 4271/4273/9403 +f 4274/4276/9406 4267/4269/9399 4275/4277/9407 +f 4267/4269/9399 4269/4271/9401 4275/4277/9407 +f 4274/4276/9406 4275/4277/9407 4272/4274/9404 +f 4276/4278/9408 4277/4279/9409 4278/4280/9410 +f 4279/4281/9411 4276/4278/9408 4280/4282/9412 +f 4276/4278/9408 4279/4281/9411 4277/4279/9409 +f 4281/4283/9413 4282/4284/9413 4277/4279/9413 +f 4282/4284/9414 4278/4280/9414 4277/4279/9414 +f 4282/4284/9415 4283/4285/9415 4278/4280/9415 +f 4283/4285/9416 4276/4278/9417 4278/4280/9418 +f 4283/4285/9416 4284/4286/9419 4276/4278/9417 +f 4284/4286/9420 4280/4282/9421 4276/4278/9422 +f 4284/4286/9420 4285/4287/9423 4280/4282/9421 +f 4285/4287/9424 4279/4281/9425 4280/4282/9426 +f 4285/4287/9424 4281/4283/9427 4279/4281/9425 +f 4281/4283/9428 4277/4279/9428 4279/4281/9428 +f 4282/4284/9429 4281/4283/9430 4286/4288/9431 +f 4282/4284/9429 4286/4288/9431 4287/4289/9432 +f 4285/4287/9433 4288/4290/9434 4289/4291/9435 +f 4285/4287/9433 4284/4286/9436 4288/4290/9434 +f 4281/4283/9430 4285/4287/9433 4290/4292/9437 +f 4285/4287/9433 4289/4291/9435 4290/4292/9437 +f 4286/4288/9431 4281/4283/9430 4290/4292/9437 +f 4283/4285/9438 4287/4289/9432 4291/4293/9439 +f 4283/4285/9438 4282/4284/9429 4287/4289/9432 +f 4284/4286/9436 4291/4293/9439 4288/4290/9434 +f 4284/4286/9436 4283/4285/9438 4291/4293/9439 +f 4286/4288/9440 4290/4292/9441 4268/4270/9442 +f 4290/4292/9443 4269/4271/9443 4268/4270/9443 +f 4290/4292/9444 4289/4291/9445 4269/4271/9446 +f 4289/4291/9445 4275/4277/9447 4269/4271/9446 +f 4289/4291/9448 4288/4290/9448 4275/4277/9448 +f 4275/4277/9449 4288/4290/9450 4272/4274/9451 +f 4288/4290/9450 4291/4293/9452 4272/4274/9451 +f 4272/4274/9453 4291/4293/9454 4273/4275/9455 +f 4291/4293/9454 4287/4289/9456 4273/4275/9455 +f 4273/4275/9457 4287/4289/9458 4271/4273/9459 +f 4287/4289/9458 4286/4288/9460 4271/4273/9459 +f 4271/4273/9461 4286/4288/9440 4268/4270/9442 +f 4292/4294/9462 4293/4295/9462 4274/4276/9462 +f 4270/4272/9463 4294/4296/9464 4274/4276/9465 +f 4294/4296/9464 4292/4294/9466 4274/4276/9465 +f 4267/4269/9467 4295/4297/9467 4270/4272/9467 +f 4295/4297/9468 4294/4296/9468 4270/4272/9468 +f 4293/4295/9469 4295/4297/9469 4267/4269/9469 +f 4274/4276/9470 4293/4295/9470 4267/4269/9470 +f 4295/4297/3031 4293/4295/3031 4294/4296/3031 +f 4293/4295/3031 4292/4294/3031 4294/4296/3031 +f 3282/3284/9471 3687/3689/9472 3281/3283/9473 +f 3281/3283/9473 3716/3718/9474 3492/3494/9475 +f 3718/3720/9476 3492/3494/9475 3716/3718/9474 +f 3492/3494/9475 3718/3720/9476 3278/3280/9477 +f 3281/3283/9473 3687/3689/9472 3716/3718/9474 +f 3485/3487/9478 3711/3713/9479 3468/3470/9480 +f 3711/3713/9479 3484/3486/9481 3406/3408/9482 +f 3485/3487/9478 3484/3486/9481 3711/3713/9479 +f 3707/3709/528 3708/3710/528 3709/3711/528 +f 3710/3712/528 3707/3709/528 3709/3711/528 +f 3706/3708/528 3703/3705/528 3705/3707/528 +f 3703/3705/528 3706/3708/528 3704/3706/528 +f 3737/3739/528 3738/3740/528 3734/3736/528 +f 3735/3737/528 3737/3739/528 3734/3736/528 +f 3737/3739/528 3735/3737/528 3736/3738/528 +f 3294/3296/9483 4296/4298/9483 3297/3299/9483 +f 4210/4212/9484 3512/3514/8079 3511/3513/9485 +f 4218/4220/9486 3293/3295/8048 3544/3546/8047 +f 4218/4220/9487 3544/3546/9487 3543/3545/9487 +f 4218/4220/9488 3543/3545/9488 4217/4219/9488 +f 4214/4216/9489 3543/3545/9490 3546/3548/9491 +f 4211/4213/9492 3128/3130/9492 4215/4217/9492 +f 4214/4216/9493 3546/3548/9493 4213/4215/9493 +f 4213/4215/9494 3545/3547/9495 4212/4214/9496 +f 4220/4222/9497 3128/3130/9498 3060/3062/9499 +f 4210/4212/9500 3511/3513/9500 4211/4213/9500 +f 4220/4222/9497 3060/3062/9499 4219/4221/9501 +f 3132/3134/9502 3131/3133/9503 4216/4218/9504 +f 3131/3133/9503 3135/3137/9505 4216/4218/9504 +f 4297/4299/9506 3135/3137/9506 3134/3136/9506 +f 4209/4211/9507 3134/3136/9507 3137/3139/9507 +f 4219/4221/9508 3058/3060/7799 3132/3134/7798 +f 3295/3297/9509 4149/4151/9509 3137/3139/9509 +f 4219/4221/9501 3060/3062/9499 3058/3060/9510 +f 4296/4298/9511 4298/4300/9511 3297/3299/9511 +f 4299/4301/9512 4296/4298/9512 3294/3296/9512 +f 3293/3295/9513 4299/4301/9513 3294/3296/9513 +f 4211/4213/9514 3511/3513/9514 3128/3130/9514 +f 4213/4215/9494 3546/3548/9515 3545/3547/9495 +f 4212/4214/9516 3545/3547/8080 4210/4212/9484 +f 4299/4301/9517 3293/3295/8048 4218/4220/9486 +f 3512/3514/8079 4210/4212/9484 3545/3547/8080 +f 4215/4217/9518 3128/3130/9518 4220/4222/9518 +f 3132/3134/7798 4216/4218/9519 4219/4221/9508 +f 4297/4299/9520 3134/3136/9520 4209/4211/9520 +f 4209/4211/9521 3137/3139/9521 4149/4151/9521 +f 3297/3299/9522 4298/4300/9523 3295/3297/9524 +f 4217/4219/9525 3543/3545/9490 4214/4216/9489 +f 4123/4125/9526 4120/4122/9527 4125/4127/9528 +f 4125/4127/9528 4083/4085/9529 4127/4129/9530 +f 4120/4122/9527 4055/4057/9531 4125/4127/9528 +f 4055/4057/9531 4083/4085/9529 4125/4127/9528 +f 4055/4057/9531 4178/4180/9532 4083/4085/9529 +f 4077/4079/9533 4083/4085/9529 4189/4191/9534 +f 4205/4207/9535 4055/4057/9531 4196/4198/9536 +f 4197/4199/9537 4205/4207/9535 4196/4198/9536 +f 4055/4057/9531 4179/4181/9538 4178/4180/9532 +f 4189/4191/9534 4174/4176/9539 4077/4079/9533 +f 4182/4184/9540 4055/4057/9531 4205/4207/9535 +f 4083/4085/9529 4175/4177/9541 4189/4191/9534 +f 4083/4085/9529 4178/4180/9532 4177/4179/9542 +f 4083/4085/9529 4176/4178/9543 4175/4177/9541 +f 4182/4184/9540 4181/4183/9544 4055/4057/9531 +f 4083/4085/9529 4177/4179/9542 4176/4178/9543 +f 4181/4183/9544 4180/4182/9545 4055/4057/9531 +f 4180/4182/9545 4179/4181/9538 4055/4057/9531 +f 4231/4233/2568 4228/4230/5591 4227/4229/2568 +f 4231/4233/2568 4227/4229/2568 4230/4232/9546 +f 4299/4301/9547 4218/4220/9237 4075/4077/9242 +f 4221/4223/9548 4299/4301/9547 4075/4077/9242 +f 4219/4221/9238 4226/4228/9549 4092/4094/9243 +f 4219/4221/9238 4225/4227/9550 4226/4228/9549 +f 4222/4224/9551 4299/4301/9547 4221/4223/9548 +f 4219/4221/9238 4237/4239/9552 4225/4227/9550 +f 4222/4224/9551 4236/4238/9553 4299/4301/9547 +f 4216/4218/9231 4237/4239/9552 4219/4221/9238 +f 4216/4218/9231 4039/4041/9554 4237/4239/9552 +f 4044/4046/9555 4299/4301/9547 4236/4238/9553 +f 4042/4044/9556 4299/4301/9547 4044/4046/9555 +f 4216/4218/9231 4036/4038/9557 4039/4041/9554 +f 4042/4044/9556 4296/4298/9558 4299/4301/9547 +f 4216/4218/9231 4195/4197/9233 4036/4038/9557 +f 4042/4044/9556 4173/4175/9559 4296/4298/9558 +f 4173/4175/9559 4061/4063/9560 4296/4298/9558 +f 3135/3137/9561 4136/4138/9232 4216/4218/9231 +f 4214/4216/9229 4068/4070/9225 4072/4074/9234 +f 4099/4101/9223 4211/4213/9222 4097/4099/9228 +f 3135/3137/9561 4135/4137/9562 4136/4138/9232 +f 4061/4063/9560 4298/4300/9523 4296/4298/9558 +f 4297/4299/9563 4135/4137/9562 3135/3137/9561 +f 4060/4062/9564 4298/4300/9523 4061/4063/9560 +f 4297/4299/9563 4133/4135/9565 4135/4137/9562 +f 4210/4212/9221 4208/4210/9566 4069/4071/9241 +f 3295/3297/9524 4298/4300/9523 4064/4066/9567 +f 4064/4066/9567 4298/4300/9523 4060/4062/9564 +f 4133/4135/9565 4209/4211/9220 4132/4134/9219 +f 4149/4151/9028 3295/3297/9524 4065/4067/9568 +f 4210/4212/9221 4207/4209/9244 4208/4210/9566 +f 4065/4067/9568 3295/3297/9524 4064/4066/9567 +f 4065/4067/9568 4150/4152/9029 4149/4151/9028 +f 4149/4151/9028 4151/4153/9030 4132/4134/9219 +f 4133/4135/9565 4297/4299/9563 4209/4211/9220 +f 4300/4302/9569 4301/4303/9570 4302/4304/9571 +f 4300/4302/9569 4303/4305/9572 4301/4303/9570 +f 4304/4306/9573 4302/4304/9571 4305/4307/9574 +f 4304/4306/9573 4305/4307/9574 4306/4308/9575 +f 4300/4302/9569 4302/4304/9571 4304/4306/9573 +f 4307/4309/9576 4303/4305/9572 4300/4302/9569 +f 4307/4309/9576 4308/4310/9577 4303/4305/9572 +f 4304/4306/9573 4306/4308/9575 4307/4309/9576 +f 4307/4309/9576 4306/4308/9575 4308/4310/9577 +f 4309/4311/9578 4310/4312/9579 4311/4313/9580 +f 4309/4311/9578 4312/4314/9581 4310/4312/9579 +f 4313/4315/9582 4314/4316/9583 4310/4312/9584 +f 4313/4315/9582 4310/4312/9584 4315/4317/9585 +f 4315/4317/9586 4310/4312/9587 4312/4314/9588 +f 4315/4317/9586 4312/4314/9588 4316/4318/9589 +f 4316/4318/9590 4312/4314/9591 4309/4311/9592 +f 4316/4318/9590 4309/4311/9592 4317/4319/9593 +f 4317/4319/9594 4309/4311/9595 4318/4320/9596 +f 4318/4320/9596 4309/4311/9595 4311/4313/9597 +f 4318/4320/9598 4311/4313/9599 4314/4316/9600 +f 4318/4320/9598 4314/4316/9600 4313/4315/9601 +f 4315/4317/9602 4319/4321/9603 4320/4322/9604 +f 4315/4317/9602 4320/4322/9604 4313/4315/9605 +f 4313/4315/9605 4320/4322/9604 4321/4323/9606 +f 4313/4315/9605 4321/4323/9606 4318/4320/9607 +f 4318/4320/9607 4321/4323/9606 4322/4324/9608 +f 4318/4320/9607 4322/4324/9608 4317/4319/9609 +f 4317/4319/9609 4322/4324/9608 4323/4325/9610 +f 4317/4319/9609 4323/4325/9610 4316/4318/9611 +f 4316/4318/9611 4323/4325/9610 4319/4321/9603 +f 4316/4318/9611 4319/4321/9603 4315/4317/9602 +f 4301/4303/9612 4321/4323/9613 4320/4322/9614 +f 4301/4303/9612 4320/4322/9614 4302/4304/9615 +f 4302/4304/9616 4320/4322/9617 4305/4307/9618 +f 4305/4307/9618 4320/4322/9617 4319/4321/9619 +f 4305/4307/9620 4319/4321/9620 4306/4308/9620 +f 4306/4308/9621 4319/4321/9622 4323/4325/9623 +f 4306/4308/9621 4323/4325/9623 4308/4310/9624 +f 4308/4310/9625 4323/4325/9626 4303/4305/9627 +f 4303/4305/9627 4323/4325/9626 4322/4324/9628 +f 4303/4305/9629 4322/4324/9630 4321/4323/9631 +f 4303/4305/9629 4321/4323/9631 4301/4303/9632 +f 4304/4306/9633 4307/4309/9634 4324/4326/9635 +f 4324/4326/9635 4307/4309/9634 4325/4327/9636 +f 4300/4302/9637 4304/4306/9638 4326/4328/9639 +f 4326/4328/9639 4304/4306/9638 4324/4326/9640 +f 4307/4309/9641 4300/4302/9642 4325/4327/9643 +f 4325/4327/9643 4300/4302/9642 4326/4328/9644 +f 4325/4327/528 4326/4328/528 4324/4326/528 +f 4314/4316/9645 4311/4313/9580 4310/4312/9579 +f 4327/4329/9646 4328/4330/9647 4329/4331/9648 +f 4329/4331/9648 4328/4330/9647 4330/4332/9649 +f 4331/4333/9650 4332/4334/9651 4333/4335/9652 +f 4329/4331/9648 4331/4333/9650 4333/4335/9652 +f 4329/4331/9648 4330/4332/9649 4331/4333/9650 +f 4327/4329/9646 4334/4336/9653 4328/4330/9647 +f 4333/4335/9652 4332/4334/9651 4334/4336/9653 +f 4333/4335/9652 4334/4336/9653 4327/4329/9646 +f 4335/4337/9654 4336/4338/9655 4337/4339/9656 +f 4337/4339/9656 4338/4340/9657 4335/4337/9654 +f 4339/4341/9658 4338/4340/9658 4337/4339/9658 +f 4339/4341/9659 4337/4339/9659 4340/4342/9659 +f 4340/4342/9660 4337/4339/9661 4336/4338/9662 +f 4340/4342/9660 4336/4338/9662 4341/4343/9663 +f 4341/4343/9664 4336/4338/9665 4342/4344/9666 +f 4342/4344/9666 4336/4338/9665 4335/4337/9667 +f 4342/4344/9668 4335/4337/9669 4338/4340/9670 +f 4342/4344/9668 4338/4340/9670 4339/4341/9671 +f 4340/4342/9672 4343/4345/9673 4344/4346/9674 +f 4340/4342/9672 4344/4346/9674 4339/4341/9675 +f 4339/4341/9675 4344/4346/9674 4345/4347/9676 +f 4339/4341/9675 4345/4347/9676 4342/4344/9677 +f 4342/4344/9677 4345/4347/9676 4346/4348/9678 +f 4342/4344/9677 4346/4348/9678 4341/4343/9679 +f 4341/4343/9679 4346/4348/9678 4347/4349/9680 +f 4341/4343/9679 4347/4349/9680 4343/4345/9673 +f 4341/4343/9679 4343/4345/9673 4340/4342/9672 +f 4328/4330/9681 4344/4346/9682 4330/4332/9683 +f 4330/4332/9684 4344/4346/9685 4331/4333/9686 +f 4331/4333/9686 4344/4346/9685 4343/4345/9687 +f 4331/4333/9688 4343/4345/9689 4347/4349/9690 +f 4331/4333/9688 4347/4349/9690 4332/4334/9691 +f 4332/4334/9692 4347/4349/9692 4346/4348/9692 +f 4332/4334/9693 4346/4348/9693 4334/4336/9693 +f 4334/4336/9694 4346/4348/9694 4345/4347/9694 +f 4334/4336/9695 4345/4347/9695 4328/4330/9695 +f 4328/4330/9681 4345/4347/9696 4344/4346/9682 +f 4329/4331/9697 4333/4335/9698 4348/4350/9699 +f 4348/4350/9699 4333/4335/9698 4349/4351/9700 +f 4327/4329/9701 4329/4331/9702 4350/4352/9703 +f 4350/4352/9703 4329/4331/9702 4348/4350/9704 +f 4333/4335/9705 4327/4329/9706 4349/4351/9707 +f 4349/4351/9707 4327/4329/9706 4350/4352/9708 +f 4349/4351/528 4350/4352/528 4348/4350/528 +f 4351/4353/9709 4352/4354/9709 4353/4355/9709 +f 4354/4356/9710 4351/4353/9710 4355/4357/9710 +f 4356/4358/9711 4357/4359/9712 4353/4355/9713 +f 4353/4355/9713 4357/4359/9712 4355/4357/9714 +f 4358/4360/9715 4359/4361/9716 4360/4362/9717 +f 4360/4362/9717 4361/4363/9718 4358/4360/9715 +f 4362/4364/9719 4360/4362/9719 4359/4361/9719 +f 4362/4364/9720 4359/4361/9720 4363/4365/9720 +f 4363/4365/9721 4359/4361/9721 4358/4360/9721 +f 4363/4365/9722 4358/4360/9722 4364/4366/9722 +f 4364/4366/9723 4358/4360/9723 4361/4363/9723 +f 4364/4366/9724 4361/4363/9724 4365/4367/9724 +f 4365/4367/9725 4361/4363/9725 4360/4362/9725 +f 4365/4367/9726 4360/4362/9726 4362/4364/9726 +f 4365/4367/9727 4366/4368/9728 4364/4366/9729 +f 4364/4366/9729 4366/4368/9728 4367/4369/9730 +f 4362/4364/9731 4368/4370/9732 4365/4367/9727 +f 4364/4366/9729 4367/4369/9730 4369/4371/9733 +f 4364/4366/9729 4369/4371/9733 4363/4365/9734 +f 4365/4367/9727 4368/4370/9732 4366/4368/9728 +f 4363/4365/9734 4370/4372/9735 4362/4364/9731 +f 4362/4364/9731 4370/4372/9735 4368/4370/9732 +f 4363/4365/9734 4369/4371/9733 4370/4372/9735 +f 4351/4353/9736 4368/4370/9736 4352/4354/9736 +f 4352/4354/9737 4368/4370/9737 4370/4372/9737 +f 4352/4354/9738 4370/4372/9738 4353/4355/9738 +f 4353/4355/9739 4370/4372/9740 4369/4371/9741 +f 4353/4355/9739 4369/4371/9741 4356/4358/9742 +f 4356/4358/9743 4369/4371/9744 4367/4369/9745 +f 4356/4358/9743 4367/4369/9745 4357/4359/9746 +f 4357/4359/9747 4367/4369/9748 4366/4368/9749 +f 4357/4359/9747 4366/4368/9749 4355/4357/9750 +f 4355/4357/9751 4366/4368/9751 4354/4356/9751 +f 4354/4356/9752 4366/4368/9753 4368/4370/9754 +f 4354/4356/9752 4368/4370/9754 4351/4353/9755 +f 4353/4355/9756 4355/4357/9757 4371/4373/9758 +f 4371/4373/9758 4355/4357/9757 4372/4374/9759 +f 4351/4353/9760 4353/4355/9761 4373/4375/9762 +f 4373/4375/9762 4353/4355/9761 4371/4373/9763 +f 4355/4357/9764 4351/4353/9765 4372/4374/9766 +f 4372/4374/9766 4351/4353/9765 4373/4375/9767 +f 4372/4374/528 4373/4375/528 4371/4373/528 +f 4374/4376/9768 4375/4377/9769 4376/4378/9770 +f 4376/4378/9770 4375/4377/9769 4377/4379/9771 +f 4376/4378/9772 4377/4379/9772 4378/4380/9772 +f 4376/4378/9773 4378/4380/9773 4379/4381/9773 +f 4379/4381/9774 4378/4380/9774 4380/4382/9774 +f 4379/4381/9775 4380/4382/9776 4381/4383/9777 +f 4382/4384/9778 4381/4383/9777 4380/4382/9776 +f 4382/4384/9779 4383/4385/9779 4384/4386/9779 +f 4384/4386/9780 4383/4385/9781 4385/4387/9782 +f 4384/4386/9780 4385/4387/9782 4386/4388/9783 +f 4386/4388/9784 4385/4387/9784 4387/4389/9784 +f 4386/4388/9785 4387/4389/9785 4388/4390/9785 +f 4388/4390/9786 4387/4389/9787 4389/4391/9788 +f 4389/4391/9788 4387/4389/9787 4390/4392/9789 +f 4389/4391/9790 4390/4392/9790 4391/4393/9790 +f 4389/4391/9791 4391/4393/9791 4392/4394/9791 +f 4374/4376/9792 4392/4394/9792 4375/4377/9792 +f 4375/4377/9793 4392/4394/9793 4391/4393/9793 +f 4376/4378/98 4386/4388/98 4388/4390/98 +f 4379/4381/98 4386/4388/98 4376/4378/98 +f 4379/4381/98 4384/4386/9794 4386/4388/98 +f 4374/4376/98 4389/4391/98 4392/4394/98 +f 4381/4383/9795 4384/4386/9794 4379/4381/98 +f 4381/4383/9795 4382/4384/9796 4384/4386/9794 +f 4376/4378/98 4389/4391/98 4374/4376/98 +f 4376/4378/98 4388/4390/98 4389/4391/98 +f 4378/4380/528 4385/4387/528 4383/4385/9797 +f 4377/4379/528 4387/4389/528 4378/4380/528 +f 4378/4380/528 4387/4389/528 4385/4387/528 +f 4380/4382/9798 4383/4385/9797 4382/4384/9799 +f 4378/4380/528 4383/4385/9797 4380/4382/9798 +f 4375/4377/528 4390/4392/528 4377/4379/528 +f 4377/4379/528 4390/4392/528 4387/4389/528 +f 4375/4377/528 4391/4393/528 4390/4392/528 +f 4393/4395/9800 4394/4396/9800 4395/4397/9800 +f 4393/4395/9801 4395/4397/9801 4396/4398/9801 +f 4396/4398/9802 4395/4397/9802 4397/4399/9802 +f 4396/4398/9803 4397/4399/9804 4398/4400/9805 +f 4398/4400/9805 4397/4399/9804 4399/4401/9806 +f 4398/4400/9807 4399/4401/9808 4400/4402/9809 +f 4398/4400/9807 4400/4402/9809 4401/4403/9810 +f 4402/4404/9811 4401/4403/9811 4400/4402/9811 +f 4402/4404/9812 4403/4405/9812 4404/4406/9812 +f 4404/4406/9813 4403/4405/9813 4405/4407/9813 +f 4404/4406/9814 4405/4407/9814 4406/4408/9814 +f 4406/4408/9815 4405/4407/9815 4407/4409/9815 +f 4406/4408/9816 4407/4409/9817 4408/4410/9818 +f 4406/4408/9816 4408/4410/9818 4409/4411/9819 +f 4409/4411/9820 4408/4410/9820 4410/4412/9820 +f 4410/4412/9821 4408/4410/9821 4411/4413/9821 +f 4410/4412/9822 4411/4413/9822 4412/4414/9822 +f 4412/4414/9823 4411/4413/9823 4413/4415/9823 +f 4393/4395/9824 4412/4414/9825 4394/4396/9826 +f 4394/4396/9826 4412/4414/9825 4413/4415/9827 +f 4396/4398/98 4406/4408/98 4409/4411/98 +f 4398/4400/98 4406/4408/98 4396/4398/98 +f 4398/4400/98 4404/4406/9828 4406/4408/98 +f 4401/4403/9829 4404/4406/9828 4398/4400/98 +f 4396/4398/98 4410/4412/98 4393/4395/98 +f 4393/4395/98 4410/4412/98 4412/4414/98 +f 4401/4403/9829 4402/4404/9830 4404/4406/9828 +f 4396/4398/98 4409/4411/98 4410/4412/98 +f 4399/4401/528 4407/4409/528 4405/4407/528 +f 4399/4401/528 4405/4407/528 4400/4402/9831 +f 4408/4410/528 4407/4409/528 4397/4399/528 +f 4397/4399/528 4407/4409/528 4399/4401/528 +f 4395/4397/528 4408/4410/528 4397/4399/528 +f 4400/4402/9831 4403/4405/9832 4402/4404/9833 +f 4405/4407/528 4403/4405/9832 4400/4402/9831 +f 4395/4397/528 4411/4413/528 4408/4410/528 +f 4394/4396/528 4413/4415/528 4395/4397/528 +f 4395/4397/528 4413/4415/528 4411/4413/528 +f 4414/4416/9834 4415/4417/9835 4416/4418/9836 +f 4416/4418/9836 4415/4417/9835 4417/4419/9837 +f 4414/4416/9834 4418/4420/9838 4415/4417/9835 +f 4419/4421/9839 4420/4422/9840 4421/4423/9841 +f 4416/4418/9836 4417/4419/9837 4419/4421/9839 +f 4416/4418/9836 4419/4421/9839 4421/4423/9841 +f 4421/4423/9841 4420/4422/9840 4414/4416/9834 +f 4414/4416/9834 4420/4422/9840 4418/4420/9838 +f 4422/4424/9842 4423/4425/9843 4424/4426/9844 +f 4424/4426/9844 4425/4427/9845 4422/4424/9842 +f 4426/4428/9846 4424/4426/9847 4427/4429/9848 +f 4427/4429/9848 4424/4426/9847 4423/4425/9849 +f 4427/4429/9850 4423/4425/9851 4422/4424/9852 +f 4427/4429/9850 4422/4424/9852 4428/4430/9853 +f 4428/4430/9854 4422/4424/9855 4429/4431/9856 +f 4429/4431/9856 4422/4424/9855 4425/4427/9857 +f 4429/4431/9858 4425/4427/9859 4426/4428/9860 +f 4426/4428/9860 4425/4427/9859 4424/4426/9861 +f 4427/4429/9862 4430/4432/9863 4426/4428/9864 +f 4426/4428/9864 4430/4432/9863 4431/4433/9865 +f 4426/4428/9864 4431/4433/9865 4432/4434/9866 +f 4426/4428/9864 4432/4434/9866 4429/4431/9867 +f 4429/4431/9867 4432/4434/9866 4433/4435/9868 +f 4429/4431/9867 4433/4435/9868 4428/4430/9869 +f 4428/4430/9869 4433/4435/9868 4434/4436/9870 +f 4428/4430/9869 4434/4436/9870 4427/4429/9862 +f 4427/4429/9862 4434/4436/9870 4435/4437/9871 +f 4427/4429/9862 4435/4437/9871 4430/4432/9863 +f 4415/4417/9872 4431/4433/9873 4417/4419/9874 +f 4417/4419/9875 4431/4433/9875 4430/4432/9875 +f 4417/4419/9876 4430/4432/9876 4419/4421/9876 +f 4419/4421/9877 4430/4432/9877 4435/4437/9877 +f 4419/4421/9878 4435/4437/9879 4420/4422/9880 +f 4420/4422/9880 4435/4437/9879 4434/4436/9881 +f 4420/4422/9882 4434/4436/9883 4433/4435/9884 +f 4420/4422/9882 4433/4435/9884 4418/4420/9885 +f 4418/4420/9886 4433/4435/9887 4432/4434/9888 +f 4418/4420/9886 4432/4434/9888 4415/4417/9889 +f 4415/4417/9872 4432/4434/9890 4431/4433/9873 +f 4416/4418/9891 4421/4423/9891 4436/4438/9891 +f 4437/4439/9892 4416/4418/9892 4436/4438/9892 +f 4414/4416/9893 4416/4418/9893 4437/4439/9893 +f 4421/4423/9894 4414/4416/9895 4436/4438/9896 +f 4436/4438/9896 4414/4416/9895 4437/4439/9897 +f 4438/4440/9898 4439/4441/9899 4440/4442/9900 +f 4440/4442/9900 4439/4441/9899 4441/4443/9901 +f 4440/4442/9902 4441/4443/9903 4442/4444/9904 +f 4442/4444/9904 4441/4443/9903 4443/4445/9905 +f 4442/4444/9906 4443/4445/9907 4444/4446/9908 +f 4444/4446/9908 4443/4445/9907 4445/4447/9909 +f 4444/4446/9910 4445/4447/9911 4446/4448/9912 +f 4446/4448/9912 4445/4447/9911 4447/4449/9913 +f 4448/4450/9914 4446/4448/9914 4447/4449/9914 +f 4448/4450/9915 4447/4449/9915 4449/4451/9915 +f 4448/4450/9916 4449/4451/9916 4450/4452/9916 +f 4450/4452/9917 4449/4451/9917 4451/4453/9917 +f 4450/4452/9918 4451/4453/9918 4452/4454/9918 +f 4452/4454/9919 4451/4453/9919 4453/4455/9919 +f 4452/4454/9920 4453/4455/9921 4454/4456/9922 +f 4452/4454/9920 4454/4456/9922 4455/4457/9923 +f 4455/4457/9924 4454/4456/9925 4456/4458/9926 +f 4455/4457/9924 4456/4458/9926 4457/4459/9927 +f 4457/4459/9928 4456/4458/9928 4458/4460/9928 +f 4438/4440/9898 4458/4460/9929 4439/4441/9899 +f 4440/4442/98 4452/4454/98 4455/4457/98 +f 4442/4444/98 4452/4454/98 4440/4442/98 +f 4444/4446/98 4450/4452/98 4442/4444/98 +f 4442/4444/98 4450/4452/98 4452/4454/98 +f 4438/4440/9930 4457/4459/9931 4458/4460/9932 +f 4440/4442/98 4455/4457/98 4438/4440/9930 +f 4438/4440/9930 4455/4457/98 4457/4459/9931 +f 4446/4448/98 4448/4450/98 4450/4452/98 +f 4446/4448/98 4450/4452/98 4444/4446/98 +f 4441/4443/528 4453/4455/528 4443/4445/528 +f 4443/4445/528 4451/4453/528 4445/4447/528 +f 4443/4445/528 4453/4455/528 4451/4453/528 +f 4441/4443/528 4454/4456/528 4453/4455/528 +f 4445/4447/528 4451/4453/528 4449/4451/528 +f 4445/4447/528 4449/4451/528 4447/4449/528 +f 4439/4441/9933 4456/4458/9934 4454/4456/528 +f 4439/4441/9933 4454/4456/528 4441/4443/528 +f 4439/4441/9933 4458/4460/9935 4456/4458/9934 +f 4459/4461/9936 4460/4462/9937 4461/4463/9938 +f 4459/4461/9939 4461/4463/9939 4462/4464/9939 +f 4462/4464/9940 4461/4463/9940 4463/4465/9940 +f 4462/4464/9941 4463/4465/9941 4464/4466/9941 +f 4464/4466/9942 4463/4465/9942 4465/4467/9942 +f 4464/4466/9943 4465/4467/9944 4466/4468/9945 +f 4464/4466/9943 4466/4468/9945 4467/4469/9946 +f 4468/4470/9947 4467/4469/9946 4466/4468/9945 +f 4468/4470/9948 4469/4471/9948 4470/4472/9948 +f 4470/4472/9949 4469/4471/9950 4471/4473/9951 +f 4470/4472/9949 4471/4473/9951 4472/4474/9952 +f 4472/4474/9953 4471/4473/9953 4473/4475/9953 +f 4472/4474/9954 4473/4475/9954 4474/4476/9954 +f 4474/4476/9955 4473/4475/9955 4475/4477/9955 +f 4474/4476/9956 4475/4477/9956 4476/4478/9956 +f 4476/4478/9957 4475/4477/9957 4477/4479/9957 +f 4476/4478/9958 4477/4479/9959 4478/4480/9960 +f 4476/4478/9958 4478/4480/9960 4479/4481/9961 +f 4459/4461/9936 4479/4481/9962 4460/4462/9937 +f 4460/4462/9963 4479/4481/9963 4478/4480/9963 +f 4464/4466/98 4474/4476/98 4462/4464/98 +f 4464/4466/98 4472/4474/98 4474/4476/98 +f 4459/4461/98 4476/4478/98 4479/4481/98 +f 4462/4464/98 4476/4478/98 4459/4461/98 +f 4467/4469/9964 4470/4472/9965 4464/4466/98 +f 4464/4466/98 4470/4472/9965 4472/4474/98 +f 4467/4469/9964 4468/4470/9966 4470/4472/9965 +f 4462/4464/98 4474/4476/98 4476/4478/98 +f 4463/4465/528 4473/4475/528 4465/4467/528 +f 4465/4467/528 4471/4473/528 4466/4468/9967 +f 4473/4475/528 4471/4473/528 4465/4467/528 +f 4463/4465/528 4475/4477/528 4473/4475/528 +f 4461/4463/528 4475/4477/528 4463/4465/528 +f 4466/4468/9967 4469/4471/9968 4468/4470/9969 +f 4471/4473/528 4469/4471/9968 4466/4468/9967 +f 4461/4463/528 4477/4479/528 4475/4477/528 +f 4461/4463/528 4478/4480/528 4477/4479/528 +f 4460/4462/528 4478/4480/528 4461/4463/528 +f 4480/4482/9970 4481/4483/9970 4482/4484/9970 +f 4482/4484/9971 4483/4485/9971 4484/4486/9971 +f 4485/4487/9972 4486/4488/9972 4480/4482/9972 +f 4487/4489/9973 4488/4490/9974 4489/4491/9975 +f 4490/4492/9976 4487/4489/9973 4489/4491/9975 +f 4491/4493/9977 4492/4494/9977 4488/4490/9977 +f 4488/4490/9978 4492/4494/9978 4489/4491/9978 +f 4492/4494/9979 4493/4495/9979 4489/4491/9979 +f 4489/4491/9980 4493/4495/9980 4490/4492/9980 +f 4490/4492/9981 4493/4495/9981 4494/4496/9981 +f 4490/4492/9982 4494/4496/9982 4487/4489/9982 +f 4494/4496/9983 4491/4493/9984 4487/4489/9985 +f 4487/4489/9985 4491/4493/9984 4488/4490/9986 +f 4494/4496/9987 4495/4497/9988 4491/4493/9989 +f 4491/4493/9989 4495/4497/9988 4496/4498/9990 +f 4497/4499/9991 4498/4500/9992 4493/4495/9993 +f 4493/4495/9993 4498/4500/9992 4494/4496/9987 +f 4493/4495/9993 4499/4501/9994 4497/4499/9991 +f 4491/4493/9989 4496/4498/9990 4492/4494/9995 +f 4494/4496/9987 4498/4500/9992 4495/4497/9988 +f 4492/4494/9995 4499/4501/9994 4493/4495/9993 +f 4492/4494/9995 4496/4498/9990 4499/4501/9994 +f 4483/4485/9996 4482/4484/9996 4496/4498/9996 +f 4496/4498/9997 4482/4484/9998 4499/4501/9999 +f 4482/4484/9998 4481/4483/10000 4499/4501/9999 +f 4481/4483/10001 4480/4482/10002 4499/4501/10003 +f 4499/4501/10003 4480/4482/10002 4497/4499/10004 +f 4480/4482/10005 4486/4488/10006 4497/4499/10007 +f 4497/4499/10007 4486/4488/10006 4498/4500/10008 +f 4498/4500/10009 4486/4488/10010 4485/4487/10011 +f 4498/4500/10009 4485/4487/10011 4495/4497/10012 +f 4485/4487/10011 4484/4486/10013 4495/4497/10012 +f 4495/4497/10014 4484/4486/10015 4483/4485/10016 +f 4495/4497/10014 4483/4485/10016 4496/4498/10017 +f 4485/4487/10018 4480/4482/10018 4500/4502/10018 +f 4500/4502/10019 4480/4482/10019 4501/4503/10019 +f 4484/4486/10020 4485/4487/10020 4500/4502/10020 +f 4482/4484/10021 4484/4486/10022 4501/4503/10023 +f 4501/4503/10023 4484/4486/10022 4500/4502/10024 +f 4480/4482/10025 4482/4484/10025 4501/4503/10025 +f 4502/4504/10026 4503/4505/10027 4504/4506/10028 +f 4502/4504/10026 4504/4506/10028 4505/4507/10029 +f 4505/4507/10029 4504/4506/10028 4506/4508/528 +f 4507/4509/10030 4508/4510/10031 4509/4511/2511 +f 4509/4511/2511 4508/4510/10031 4510/4512/10031 +f 4511/4513/10032 4512/4514/10033 4513/4515/10034 +f 4511/4513/10032 4514/4516/10035 4515/4517/10036 +f 4511/4513/10032 4513/4515/10034 4516/4518/10037 +f 4511/4513/10032 4516/4518/10037 4514/4516/10035 +f 4517/4519/10038 4516/4518/10039 4502/4504/10040 +f 4502/4504/10040 4516/4518/10039 4518/4520/10041 +f 4502/4504/10040 4519/4521/10042 4517/4519/10038 +f 4516/4518/10039 4513/4515/10043 4518/4520/10041 +f 4520/4522/10032 4521/4523/10033 4522/4524/10034 +f 4520/4522/10032 4523/4525/10035 4524/4526/10036 +f 4520/4522/10032 4522/4524/10034 4525/4527/10044 +f 4520/4522/10032 4525/4527/10044 4523/4525/10035 +f 4526/4528/10045 4525/4527/10046 4511/4513/10047 +f 4511/4513/10047 4525/4527/10046 4527/4529/10048 +f 4511/4513/10047 4528/4530/10049 4526/4528/10045 +f 4525/4527/10046 4522/4524/10050 4527/4529/10048 +f 4529/4531/10032 4530/4532/10033 4531/4533/10034 +f 4529/4531/10032 4532/4534/10035 4533/4535/10036 +f 4529/4531/10032 4531/4533/10034 4534/4536/10037 +f 4529/4531/10032 4534/4536/10037 4532/4534/10035 +f 4535/4537/10045 4534/4536/10051 4520/4522/10052 +f 4520/4522/10052 4534/4536/10051 4536/4538/10048 +f 4520/4522/10052 4537/4539/10049 4535/4537/10045 +f 4534/4536/10051 4531/4533/10050 4536/4538/10048 +f 4538/4540/10032 4539/4541/10033 4540/4542/10034 +f 4538/4540/10032 4541/4543/10035 4542/4544/10036 +f 4538/4540/10032 4540/4542/10034 4543/4545/10037 +f 4538/4540/10032 4543/4545/10037 4541/4543/10035 +f 4544/4546/10045 4543/4545/10051 4529/4531/10053 +f 4529/4531/10053 4543/4545/10051 4545/4547/10048 +f 4529/4531/10053 4546/4548/10049 4544/4546/10045 +f 4543/4545/10051 4540/4542/10050 4545/4547/10048 +f 4547/4549/10054 4548/4550/10055 4549/4551/10056 +f 4547/4549/10054 4550/4552/10057 4551/4553/528 +f 4547/4549/10054 4549/4551/10056 4552/4554/10058 +f 4547/4549/10054 4552/4554/10058 4550/4552/10057 +f 4553/4555/10045 4552/4554/10051 4538/4540/10053 +f 4538/4540/10053 4552/4554/10051 4554/4556/10048 +f 4538/4540/10053 4555/4557/10049 4553/4555/10045 +f 4552/4554/10051 4549/4551/10050 4554/4556/10048 +f 4556/4558/10059 4557/4559/10060 4558/4560/10061 +f 4556/4558/10059 4559/4561/10062 4560/4562/1243 +f 4556/4558/10059 4558/4560/10061 4561/4563/10063 +f 4556/4558/10059 4561/4563/10063 4559/4561/10062 +f 4562/4564/10064 4561/4563/10065 4563/4565/10066 +f 4563/4565/10066 4561/4563/10065 4564/4566/10067 +f 4561/4563/10065 4558/4560/10043 4564/4566/10067 +f 4504/4506/10068 4508/4510/10069 4507/4509/10070 +f 4504/4506/10068 4507/4509/10070 4506/4508/10071 +f 4516/4518/10072 4517/4519/10072 4514/4516/10072 +f 4525/4527/10073 4526/4528/10073 4523/4525/10073 +f 4534/4536/10072 4535/4537/10072 4532/4534/10072 +f 4543/4545/10072 4544/4546/10072 4541/4543/10072 +f 4552/4554/10072 4553/4555/10072 4550/4552/10072 +f 4561/4563/10074 4562/4564/10074 4559/4561/10074 +f 4565/4567/528 4566/4568/528 4503/4505/528 +f 4567/4569/528 4566/4568/528 4565/4567/528 +f 4568/4570/10075 4569/4571/528 4570/4572/528 +f 4571/4573/528 4569/4571/528 4568/4570/10075 +f 4571/4573/528 4568/4570/10075 4572/4574/10076 +f 4572/4574/10076 4568/4570/10075 4573/4575/10077 +f 4574/4576/10078 4575/4577/10079 4576/4578/10080 +f 4576/4578/10080 4575/4577/10079 4573/4575/10077 +f 4573/4575/10077 4575/4577/10079 4572/4574/10076 +f 4577/4579/10081 4574/4576/10078 4576/4578/10080 +f 4578/4580/10082 4510/4512/10082 4579/4581/10082 +f 4578/4580/10082 4579/4581/10082 4580/4582/5591 +f 4581/4583/10083 4582/4584/98 4583/4585/98 +f 4584/4586/98 4585/4587/98 4586/4588/10084 +f 4584/4586/98 4587/4589/98 4588/4590/98 +f 4584/4586/98 4588/4590/98 4585/4587/98 +f 4585/4587/98 4589/4591/10085 4586/4588/10084 +f 4586/4588/10084 4589/4591/10085 4590/4592/10086 +f 4590/4592/10086 4589/4591/10085 4581/4583/10083 +f 4581/4583/10083 4589/4591/10085 4591/4593/98 +f 4581/4583/10083 4591/4593/98 4582/4584/98 +f 4592/4594/10087 4593/4595/10088 4512/4514/10089 +f 4594/4596/10090 4593/4595/10088 4592/4594/10087 +f 4595/4597/10091 4596/4598/10092 4597/4599/10093 +f 4598/4600/10094 4596/4598/10092 4595/4597/10091 +f 4598/4600/10094 4595/4597/10091 4599/4601/10095 +f 4599/4601/10095 4595/4597/10091 4600/4602/10096 +f 4601/4603/10097 4602/4604/10098 4603/4605/10099 +f 4603/4605/10099 4602/4604/10098 4600/4602/10096 +f 4600/4602/10096 4602/4604/10098 4599/4601/10095 +f 4604/4606/10100 4601/4603/10097 4603/4605/10099 +f 4605/4607/10101 4518/4520/10102 4593/4595/10103 +f 4605/4607/10101 4593/4595/10103 4594/4596/10104 +f 4606/4608/10105 4607/4609/10106 4573/4575/10107 +f 4608/4610/98 4609/4611/98 4606/4608/10105 +f 4606/4608/10105 4609/4611/98 4607/4609/10106 +f 4607/4609/10106 4610/4612/10108 4573/4575/10107 +f 4573/4575/10107 4610/4612/10108 4576/4578/10109 +f 4576/4578/10109 4610/4612/10108 4611/4613/10110 +f 4576/4578/10109 4611/4613/10110 4612/4614/10111 +f 4612/4614/10111 4611/4613/10110 4613/4615/98 +f 4614/4616/10087 4615/4617/10088 4521/4523/10089 +f 4616/4618/10090 4615/4617/10088 4614/4616/10087 +f 4617/4619/10112 4618/4620/10113 4619/4621/10114 +f 4620/4622/528 4618/4620/10113 4617/4619/10112 +f 4620/4622/528 4617/4619/10112 4621/4623/10115 +f 4621/4623/10115 4617/4619/10112 4622/4624/10116 +f 4623/4625/528 4624/4626/10117 4625/4627/10118 +f 4625/4627/10118 4624/4626/10117 4622/4624/10116 +f 4622/4624/10116 4624/4626/10117 4621/4623/10115 +f 4626/4628/528 4623/4625/528 4625/4627/10118 +f 4527/4529/10119 4615/4617/10120 4616/4618/10121 +f 4527/4529/10119 4616/4618/10121 4627/4629/10122 +f 4595/4597/10123 4628/4630/10124 4600/4602/10125 +f 4629/4631/10126 4630/4632/10127 4595/4597/10123 +f 4595/4597/10123 4630/4632/10127 4628/4630/10124 +f 4628/4630/10124 4631/4633/10128 4600/4602/10125 +f 4600/4602/10125 4631/4633/10128 4603/4605/10129 +f 4603/4605/10129 4631/4633/10128 4632/4634/10130 +f 4603/4605/10129 4632/4634/10130 4633/4635/10131 +f 4633/4635/10131 4632/4634/10130 4634/4636/98 +f 4635/4637/10087 4636/4638/10088 4530/4532/10089 +f 4637/4639/10090 4636/4638/10088 4635/4637/10087 +f 4638/4640/10132 4639/4641/528 4640/4642/10133 +f 4638/4640/10132 4640/4642/10133 4641/4643/10134 +f 4638/4640/10132 4641/4643/10134 4642/4644/10135 +f 4642/4644/10135 4641/4643/10134 4643/4645/10136 +f 4644/4646/10097 4645/4647/10098 4646/4648/10137 +f 4646/4648/10137 4645/4647/10098 4643/4645/10136 +f 4643/4645/10136 4645/4647/10098 4642/4644/10135 +f 4647/4649/10100 4644/4646/10097 4646/4648/10137 +f 4536/4538/10119 4636/4638/10120 4637/4639/10121 +f 4536/4538/10119 4637/4639/10121 4648/4650/10122 +f 4649/4651/10138 4650/4652/10139 4622/4624/10140 +f 4622/4624/10141 4650/4652/10141 4651/4653/10141 +f 4649/4651/10138 4619/4621/10142 4652/4654/10143 +f 4649/4651/10138 4652/4654/10143 4650/4652/10139 +f 4650/4652/98 4653/4655/98 4651/4653/98 +f 4651/4653/98 4653/4655/98 4654/4656/98 +f 4651/4653/98 4654/4656/98 4655/4657/98 +f 4655/4657/98 4654/4656/98 4656/4658/98 +f 4657/4659/10087 4658/4660/10088 4539/4541/10089 +f 4659/4661/10090 4658/4660/10088 4657/4659/10087 +f 4660/4662/528 4661/4663/528 4662/4664/528 +f 4660/4662/528 4662/4664/528 4663/4665/528 +f 4660/4662/528 4663/4665/528 4664/4666/528 +f 4664/4666/528 4663/4665/528 4665/4667/528 +f 4666/4668/528 4667/4669/528 4665/4667/528 +f 4665/4667/528 4667/4669/528 4664/4666/528 +f 4668/4670/528 4666/4668/528 4665/4667/528 +f 4545/4547/10119 4658/4660/10120 4659/4661/10121 +f 4545/4547/10119 4659/4661/10121 4669/4671/10122 +f 4641/4643/10144 4670/4672/10145 4643/4645/10146 +f 4671/4673/10147 4672/4674/10148 4641/4643/10144 +f 4641/4643/10144 4672/4674/10148 4670/4672/10145 +f 4670/4672/10145 4673/4675/10149 4643/4645/10146 +f 4643/4645/10146 4673/4675/10149 4646/4648/10150 +f 4646/4648/10150 4673/4675/10149 4674/4676/10130 +f 4646/4648/10150 4674/4676/10130 4675/4677/10131 +f 4675/4677/10131 4674/4676/10130 4676/4678/98 +f 4677/4679/10087 4678/4680/10088 4548/4550/10089 +f 4679/4681/10090 4678/4680/10088 4677/4679/10087 +f 4680/4682/10132 4681/4683/528 4682/4684/10133 +f 4680/4682/10132 4682/4684/10133 4683/4685/10134 +f 4680/4682/10132 4683/4685/10134 4684/4686/10135 +f 4684/4686/10135 4683/4685/10134 4685/4687/10151 +f 4686/4688/10152 4687/4689/10153 4688/4690/10154 +f 4688/4690/10154 4687/4689/10153 4685/4687/10151 +f 4685/4687/10151 4687/4689/10153 4684/4686/10135 +f 4689/4691/10155 4686/4688/10152 4688/4690/10154 +f 4554/4556/10119 4678/4680/10120 4679/4681/10121 +f 4554/4556/10119 4679/4681/10121 4690/4692/10122 +f 4691/4693/98 4692/4694/98 4693/4695/98 +f 4691/4693/98 4694/4696/98 4695/4697/98 +f 4691/4693/98 4695/4697/98 4692/4694/98 +f 4692/4694/98 4696/4698/98 4693/4695/98 +f 4693/4695/98 4696/4698/98 4697/4699/98 +f 4697/4699/98 4696/4698/98 4698/4700/98 +f 4697/4699/98 4698/4700/98 4699/4701/98 +f 4699/4701/98 4698/4700/98 4700/4702/98 +f 4701/4703/10156 4702/4704/10157 4557/4559/10158 +f 4703/4705/10159 4702/4704/10157 4701/4703/10156 +f 4704/4706/10160 4705/4707/528 4706/4708/528 +f 4707/4709/10161 4705/4707/528 4704/4706/10160 +f 4707/4709/10161 4704/4706/10160 4708/4710/10162 +f 4707/4709/10161 4708/4710/10162 4709/4711/10163 +f 4710/4712/10164 4711/4713/10165 4712/4714/10166 +f 4712/4714/10166 4711/4713/10165 4708/4710/10162 +f 4708/4710/10162 4711/4713/10165 4709/4711/10163 +f 4713/4715/10167 4710/4712/10164 4712/4714/10166 +f 4714/4716/10101 4564/4566/10102 4702/4704/10103 +f 4714/4716/10101 4702/4704/10103 4703/4705/10104 +f 4688/4690/10168 4715/4717/10169 4689/4691/10170 +f 4683/4685/10144 4716/4718/10145 4685/4687/10171 +f 4717/4719/10147 4718/4720/10148 4683/4685/10144 +f 4683/4685/10144 4718/4720/10148 4716/4718/10145 +f 4716/4718/10145 4719/4721/10172 4685/4687/10171 +f 4685/4687/10171 4719/4721/10172 4688/4690/10168 +f 4688/4690/10168 4719/4721/10172 4720/4722/10173 +f 4688/4690/10168 4720/4722/10173 4715/4717/10169 +f 4574/4576/10174 4582/4584/10175 4591/4593/10176 +f 4574/4576/10174 4591/4593/10176 4575/4577/10177 +f 4575/4577/10178 4591/4593/10178 4589/4591/10178 +f 4575/4577/10179 4589/4591/10179 4572/4574/10179 +f 4572/4574/10180 4589/4591/10180 4585/4587/10180 +f 4572/4574/10181 4585/4587/10181 4571/4573/10181 +f 4571/4573/10182 4585/4587/10183 4588/4590/10184 +f 4571/4573/10182 4588/4590/10184 4569/4571/10185 +f 4601/4603/10186 4613/4615/10186 4611/4613/10186 +f 4601/4603/10187 4611/4613/10187 4602/4604/10187 +f 4602/4604/10188 4611/4613/10110 4610/4612/10108 +f 4602/4604/10098 4610/4612/10189 4599/4601/10095 +f 4599/4601/10190 4610/4612/10108 4607/4609/10106 +f 4599/4601/10095 4607/4609/10191 4598/4600/10094 +f 4598/4600/10192 4607/4609/10192 4609/4611/10192 +f 4598/4600/10193 4609/4611/10193 4596/4598/10193 +f 4623/4625/10186 4634/4636/10186 4632/4634/10186 +f 4623/4625/10187 4632/4634/10187 4624/4626/10187 +f 4624/4626/10188 4632/4634/10130 4631/4633/10128 +f 4624/4626/10189 4631/4633/10189 4621/4623/10189 +f 4621/4623/10190 4631/4633/10128 4628/4630/10124 +f 4621/4623/10191 4628/4630/10191 4620/4622/10191 +f 4620/4622/10192 4628/4630/10192 4630/4632/10192 +f 4620/4622/10193 4630/4632/10193 4618/4620/10193 +f 4644/4646/10186 4656/4658/10186 4654/4656/10186 +f 4644/4646/10187 4654/4656/10187 4645/4647/10187 +f 4645/4647/10188 4654/4656/10188 4653/4655/10188 +f 4645/4647/10098 4653/4655/10189 4642/4644/10135 +f 4642/4644/10190 4653/4655/10190 4650/4652/10190 +f 4642/4644/10135 4650/4652/10191 4638/4640/10132 +f 4638/4640/10192 4650/4652/10192 4652/4654/10192 +f 4638/4640/10193 4652/4654/10193 4639/4641/10193 +f 4666/4668/10186 4676/4678/10186 4674/4676/10186 +f 4666/4668/10194 4674/4676/10194 4667/4669/10194 +f 4667/4669/10195 4674/4676/10130 4673/4675/10149 +f 4667/4669/10189 4673/4675/10189 4664/4666/10189 +f 4664/4666/10190 4673/4675/10149 4670/4672/10145 +f 4664/4666/10191 4670/4672/10191 4660/4662/10191 +f 4660/4662/10192 4670/4672/10192 4672/4674/10192 +f 4660/4662/10193 4672/4674/10193 4661/4663/10193 +f 4686/4688/10186 4700/4702/10186 4698/4700/10186 +f 4686/4688/10187 4698/4700/10187 4687/4689/10187 +f 4687/4689/10188 4698/4700/10188 4696/4698/10188 +f 4687/4689/10153 4696/4698/10189 4684/4686/10135 +f 4684/4686/10190 4696/4698/10190 4692/4694/10190 +f 4684/4686/10135 4692/4694/10191 4680/4682/10132 +f 4680/4682/10192 4692/4694/10192 4695/4697/10192 +f 4680/4682/10193 4695/4697/10193 4681/4683/10193 +f 4710/4712/10186 4715/4717/10186 4720/4722/10186 +f 4710/4712/10187 4720/4722/10187 4711/4713/10187 +f 4711/4713/10188 4720/4722/10188 4719/4721/10188 +f 4711/4713/10165 4719/4721/10189 4709/4711/10163 +f 4709/4711/10190 4719/4721/10172 4716/4718/10145 +f 4709/4711/10163 4716/4718/10191 4707/4709/10161 +f 4707/4709/10192 4716/4718/10192 4718/4720/10192 +f 4707/4709/10193 4718/4720/10193 4705/4707/10193 +f 4567/4569/10196 4580/4582/10197 4579/4581/10198 +f 4567/4569/10196 4579/4581/10198 4566/4568/10199 +f 4721/4723/10200 4722/4724/10201 4723/4725/10202 +f 4723/4725/10202 4722/4724/10201 4724/4726/10203 +f 4725/4727/10204 4726/4728/10205 4727/4729/10206 +f 4727/4729/10206 4726/4728/10205 4728/4730/10207 +f 4729/4731/10208 4730/4732/10209 4731/4733/10210 +f 4731/4733/10210 4730/4732/10209 4732/4734/10211 +f 4731/4733/10210 4732/4734/10211 4733/4735/10212 +f 4733/4735/10212 4732/4734/10211 4734/4736/528 +f 4733/4735/10212 4734/4736/528 4735/4737/528 +f 4735/4737/528 4734/4736/528 4736/4738/528 +f 4729/4731/10208 4737/4739/528 4730/4732/10209 +f 4738/4740/98 4739/4741/98 4740/4742/98 +f 4741/4743/10213 4742/4744/10214 4587/4589/10215 +f 4739/4741/98 4743/4745/98 4744/4746/10216 +f 4744/4746/10216 4743/4745/98 4745/4747/10217 +f 4744/4746/10216 4745/4747/10217 4741/4743/10213 +f 4741/4743/10213 4745/4747/10217 4746/4748/10218 +f 4741/4743/10213 4746/4748/10218 4742/4744/10214 +f 4739/4741/98 4738/4740/98 4743/4745/98 +f 4737/4739/10219 4742/4744/10220 4746/4748/10221 +f 4737/4739/10219 4746/4748/10221 4730/4732/10222 +f 4730/4732/10222 4746/4748/10221 4745/4747/10223 +f 4730/4732/10222 4745/4747/10223 4732/4734/10224 +f 4732/4734/10224 4745/4747/10223 4743/4745/10225 +f 4732/4734/10224 4743/4745/10225 4734/4736/10226 +f 4734/4736/10227 4743/4745/10228 4738/4740/10229 +f 4734/4736/10227 4738/4740/10229 4736/4738/10230 +f 4747/4749/10231 4748/4750/528 4749/4751/10232 +f 4750/4752/10233 4751/4753/10234 4752/4754/10235 +f 4752/4754/10235 4751/4753/10234 4753/4755/10236 +f 4752/4754/10235 4753/4755/10236 4754/4756/10237 +f 4754/4756/10237 4753/4755/10236 4755/4757/10238 +f 4754/4756/10237 4755/4757/10238 4749/4751/10232 +f 4749/4751/10232 4755/4757/10238 4756/4758/10239 +f 4749/4751/10232 4756/4758/10239 4747/4749/10231 +f 4750/4752/10233 4757/4759/10240 4751/4753/10234 +f 4758/4760/10241 4759/4761/10242 4760/4762/98 +f 4759/4761/10242 4756/4758/10243 4755/4757/10244 +f 4759/4761/10242 4755/4757/10244 4761/4763/10245 +f 4761/4763/10245 4755/4757/10244 4753/4755/10246 +f 4761/4763/10245 4753/4755/10246 4731/4733/10247 +f 4731/4733/10247 4753/4755/10246 4751/4753/10248 +f 4731/4733/10247 4751/4753/10248 4762/4764/10249 +f 4762/4764/10249 4751/4753/10248 4763/4765/10250 +f 4759/4761/10242 4758/4760/10241 4756/4758/10243 +f 4757/4759/10251 4763/4765/10251 4751/4753/10251 +f 4756/4758/10252 4758/4760/10252 4747/4749/10252 +f 4764/4766/10253 4765/4767/10254 4766/4768/10255 +f 4766/4768/10256 4765/4767/10257 4767/4769/10258 +f 4766/4768/10256 4767/4769/10258 4768/4770/10259 +f 4768/4770/10259 4767/4769/10258 4769/4771/10260 +f 4768/4770/10259 4769/4771/10260 4770/4772/10261 +f 4768/4770/10259 4770/4772/10261 4771/4773/10262 +f 4771/4773/10262 4770/4772/10261 4772/4774/10263 +f 4773/4775/10264 4774/4776/10265 4764/4766/10253 +f 4764/4766/10253 4774/4776/10265 4765/4767/10254 +f 4775/4777/10266 4776/4778/10267 4777/4779/98 +f 4776/4778/10267 4770/4772/10268 4769/4771/10269 +f 4776/4778/10267 4769/4771/10269 4754/4756/10270 +f 4754/4756/10270 4769/4771/10269 4767/4769/10271 +f 4754/4756/10270 4767/4769/10271 4752/4754/10272 +f 4752/4754/10272 4767/4769/10271 4765/4767/10273 +f 4752/4754/10272 4765/4767/10273 4778/4780/10274 +f 4778/4780/10274 4765/4767/10273 4779/4781/10275 +f 4776/4778/10267 4775/4777/10266 4770/4772/10268 +f 4774/4776/10276 4779/4781/10276 4765/4767/10276 +f 4770/4772/10277 4775/4777/10277 4772/4774/10277 +f 4780/4782/10278 4781/4783/10279 4782/4784/10280 +f 4783/4785/10281 4784/4786/10282 4785/4787/10283 +f 4785/4787/10283 4784/4786/10282 4786/4788/10284 +f 4785/4787/10283 4786/4788/10284 4787/4789/10285 +f 4787/4789/10285 4786/4788/10284 4788/4790/10286 +f 4787/4789/10285 4788/4790/10286 4782/4784/10280 +f 4782/4784/10280 4788/4790/10286 4789/4791/10287 +f 4782/4784/10280 4789/4791/10287 4780/4782/10278 +f 4790/4792/10288 4791/4793/10289 4783/4785/10281 +f 4783/4785/10281 4791/4793/10289 4784/4786/10282 +f 4792/4794/10266 4793/4795/10290 4794/4796/98 +f 4793/4795/10290 4789/4791/10268 4788/4790/10291 +f 4793/4795/10290 4788/4790/10291 4795/4797/10292 +f 4795/4797/10292 4788/4790/10291 4786/4788/10293 +f 4795/4797/10292 4786/4788/10293 4764/4766/10294 +f 4764/4766/10294 4786/4788/10293 4784/4786/10295 +f 4764/4766/10294 4784/4786/10295 4796/4798/10296 +f 4796/4798/10296 4784/4786/10295 4797/4799/10275 +f 4793/4795/10290 4792/4794/10266 4789/4791/10268 +f 4791/4793/10276 4797/4799/10276 4784/4786/10276 +f 4789/4791/10277 4792/4794/10277 4780/4782/10277 +f 4798/4800/10231 4799/4801/528 4800/4802/10297 +f 4801/4803/10298 4802/4804/10299 4803/4805/10300 +f 4803/4805/10301 4802/4804/10302 4804/4806/10303 +f 4803/4805/10301 4804/4806/10303 4805/4807/10304 +f 4803/4805/10301 4805/4807/10304 4800/4802/10297 +f 4800/4802/10297 4805/4807/10304 4806/4808/10239 +f 4800/4802/10297 4806/4808/10239 4798/4800/10231 +f 4807/4809/10264 4808/4810/10265 4801/4803/10298 +f 4801/4803/10298 4808/4810/10265 4802/4804/10299 +f 4809/4811/10305 4782/4784/10306 4810/4812/10307 +f 4782/4784/10306 4806/4808/10308 4805/4807/10309 +f 4782/4784/10306 4805/4807/10309 4787/4789/10310 +f 4787/4789/10310 4805/4807/10309 4804/4806/10311 +f 4787/4789/10310 4804/4806/10311 4785/4787/10312 +f 4785/4787/10312 4804/4806/10311 4783/4785/10313 +f 4783/4785/10313 4804/4806/10311 4802/4804/10314 +f 4783/4785/10313 4802/4804/10314 4811/4813/10315 +f 4811/4813/10315 4802/4804/10314 4812/4814/10275 +f 4782/4784/10306 4809/4811/10305 4806/4808/10308 +f 4808/4810/10276 4812/4814/10276 4802/4804/10276 +f 4806/4808/10316 4809/4811/10316 4798/4800/10316 +f 4813/4815/10317 4814/4816/528 4815/4817/10318 +f 4816/4818/10233 4817/4819/10319 4818/4820/10320 +f 4818/4820/10320 4817/4819/10319 4819/4821/10236 +f 4818/4820/10320 4819/4821/10236 4820/4822/10237 +f 4820/4822/10237 4819/4821/10236 4821/4823/10238 +f 4820/4822/10237 4821/4823/10238 4815/4817/10318 +f 4815/4817/10318 4821/4823/10238 4822/4824/10239 +f 4815/4817/10318 4822/4824/10239 4813/4815/10317 +f 4816/4818/10233 4823/4825/10240 4817/4819/10319 +f 4824/4826/10266 4825/4827/10290 4826/4828/98 +f 4825/4827/10290 4822/4824/10268 4821/4823/10321 +f 4825/4827/10290 4821/4823/10321 4827/4829/10292 +f 4827/4829/10292 4821/4823/10321 4819/4821/10293 +f 4827/4829/10292 4819/4821/10293 4801/4803/10294 +f 4801/4803/10294 4819/4821/10293 4817/4819/10295 +f 4801/4803/10294 4817/4819/10295 4828/4830/10296 +f 4828/4830/10296 4817/4819/10295 4829/4831/10275 +f 4825/4827/10290 4824/4826/10266 4822/4824/10268 +f 4823/4825/10276 4829/4831/10276 4817/4819/10276 +f 4822/4824/10277 4824/4826/10277 4813/4815/10277 +f 4830/4832/10322 4831/4833/528 4832/4834/10323 +f 4833/4835/10324 4834/4836/10325 4835/4837/10326 +f 4833/4835/10324 4835/4837/10326 4836/4838/10327 +f 4836/4838/10327 4835/4837/10326 4837/4839/10328 +f 4836/4838/10327 4837/4839/10328 4832/4834/10323 +f 4832/4834/10323 4837/4839/10328 4838/4840/10329 +f 4832/4834/10323 4838/4840/10329 4830/4832/10322 +f 4839/4841/528 4840/4842/10330 4833/4835/10324 +f 4833/4835/10324 4840/4842/10330 4834/4836/10325 +f 4841/4843/10266 4842/4844/10331 4843/4845/98 +f 4842/4844/10331 4838/4840/10268 4837/4839/10269 +f 4842/4844/10331 4837/4839/10269 4820/4822/10270 +f 4820/4822/10270 4837/4839/10269 4835/4837/10271 +f 4820/4822/10270 4835/4837/10271 4818/4820/10332 +f 4818/4820/10332 4835/4837/10271 4834/4836/10273 +f 4818/4820/10332 4834/4836/10273 4844/4846/10274 +f 4844/4846/10274 4834/4836/10273 4845/4847/10275 +f 4842/4844/10331 4841/4843/10266 4838/4840/10268 +f 4840/4842/10333 4845/4847/10333 4834/4836/10333 +f 4838/4840/10277 4841/4843/10277 4830/4832/10277 +f 4722/4724/10201 4721/4723/10200 4846/4848/10334 +f 4722/4724/10201 4846/4848/10334 4847/4849/10335 +f 4847/4849/10335 4846/4848/10334 4848/4850/10336 +f 4848/4850/10336 4846/4848/10334 4849/4851/10337 +f 4848/4850/10336 4849/4851/10337 4850/4852/10338 +f 4850/4852/10338 4849/4851/10337 4851/4853/10339 +f 4850/4852/10338 4851/4853/10339 4852/4854/10340 +f 4833/4835/10341 4853/4855/10341 4839/4841/10341 +f 4839/4841/10342 4853/4855/10342 4854/4856/10342 +f 4839/4841/10343 4854/4856/10344 4706/4708/10345 +f 4706/4708/10345 4854/4856/10344 4704/4706/10346 +f 4833/4835/10324 4836/4838/10327 4853/4855/10347 +f 4832/4834/10348 4855/4857/10348 4836/4838/10348 +f 4855/4857/10349 4832/4834/10349 4856/4858/10349 +f 4856/4858/10350 4832/4834/10351 4831/4833/10352 +f 4856/4858/10350 4831/4833/10352 4857/4859/10353 +f 4857/4859/10354 4858/4860/10354 4856/4858/10354 +f 4859/4861/10355 4860/4862/10356 4861/4863/10357 +f 4862/4864/10358 4860/4862/10356 4859/4861/10355 +f 4860/4862/10359 4862/4864/10359 4863/4865/10359 +f 4863/4865/10360 4701/4703/10361 4864/4866/10362 +f 4557/4559/10363 4865/4867/10363 4864/4866/10363 +f 4557/4559/10364 4864/4866/10364 4701/4703/10364 +f 4865/4867/10365 4557/4559/10365 4556/4558/10365 +f 4560/4562/10366 4866/4868/10367 4556/4558/10368 +f 4556/4558/10368 4866/4868/10367 4865/4867/10369 +f 4713/4715/10370 4866/4868/10367 4560/4562/10366 +f 4704/4706/10371 4854/4856/10371 4708/4710/10371 +f 4712/4714/10372 4866/4868/10372 4713/4715/10372 +f 4844/4846/10373 4717/4719/10374 4682/4684/10375 +f 4682/4684/10375 4816/4818/10376 4844/4846/10373 +f 4844/4846/10373 4816/4818/10376 4818/4820/10377 +f 4820/4822/10378 4815/4817/10378 4842/4844/10378 +f 4842/4844/10379 4815/4817/10380 4814/4816/10381 +f 4842/4844/10379 4814/4816/10381 4843/4845/10382 +f 4843/4845/10382 4814/4816/10381 4867/4869/10383 +f 4868/4870/10384 4869/4871/10385 4870/4872/10386 +f 4869/4871/10385 4871/4873/10387 4870/4872/10386 +f 4870/4872/10386 4871/4873/10387 4872/4874/10388 +f 4872/4874/10389 4871/4873/10389 4873/4875/10389 +f 4872/4874/10390 4873/4875/10390 4714/4716/10390 +f 4714/4716/10391 4873/4875/10392 4677/4679/10393 +f 4714/4716/10391 4677/4679/10393 4548/4550/10394 +f 4714/4716/10391 4548/4550/10394 4564/4566/10395 +f 4564/4566/10395 4548/4550/10394 4547/4549/10396 +f 4564/4566/10397 4547/4549/10397 4563/4565/10397 +f 4563/4565/10398 4547/4549/10398 4689/4691/10398 +f 4689/4691/10399 4547/4549/10400 4551/4553/10401 +f 4682/4684/10375 4717/4719/10374 4683/4685/10402 +f 4828/4830/10403 4694/4696/10404 4662/4664/10405 +f 4662/4664/10405 4807/4809/10406 4828/4830/10403 +f 4828/4830/10403 4807/4809/10406 4801/4803/10407 +f 4801/4803/10298 4803/4805/10300 4827/4829/10408 +f 4827/4829/10409 4803/4805/10409 4800/4802/10409 +f 4827/4829/10410 4800/4802/10410 4825/4827/10410 +f 4825/4827/10411 4800/4802/10412 4799/4801/10413 +f 4825/4827/10411 4799/4801/10413 4826/4828/10414 +f 4826/4828/10414 4799/4801/10413 4874/4876/10415 +f 4875/4877/10416 4876/4878/10417 4877/4879/10418 +f 4877/4879/10418 4878/4880/10419 4875/4877/10416 +f 4875/4877/10416 4878/4880/10419 4879/4881/10420 +f 4879/4881/10389 4878/4880/10389 4880/4882/10389 +f 4879/4881/10421 4880/4882/10422 4690/4692/10423 +f 4690/4692/10423 4880/4882/10422 4657/4659/10424 +f 4690/4692/10423 4657/4659/10424 4554/4556/10425 +f 4554/4556/10426 4657/4659/10427 4539/4541/10428 +f 4554/4556/10426 4539/4541/10428 4538/4540/10429 +f 4555/4557/10430 4538/4540/10431 4542/4544/10432 +f 4662/4664/10405 4694/4696/10404 4691/4693/10433 +f 4662/4664/10434 4691/4693/10434 4663/4665/10434 +f 4663/4665/10435 4691/4693/10435 4693/4695/10435 +f 4663/4665/10436 4693/4695/10436 4665/4667/10436 +f 4665/4667/10437 4693/4695/10437 4697/4699/10437 +f 4665/4667/10438 4697/4699/10439 4699/4701/10440 +f 4665/4667/10438 4699/4701/10440 4668/4670/10441 +f 4668/4670/10441 4699/4701/10440 4555/4557/10430 +f 4668/4670/10441 4555/4557/10430 4542/4544/10432 +f 4811/4813/10442 4671/4673/10443 4640/4642/10444 +f 4640/4642/10444 4790/4792/10445 4811/4813/10442 +f 4811/4813/10442 4790/4792/10445 4783/4785/10446 +f 4810/4812/10447 4782/4784/10448 4781/4783/10449 +f 4810/4812/10447 4781/4783/10449 4881/4883/10450 +f 4881/4883/10450 4781/4783/10449 4882/4884/10451 +f 4883/4885/10452 4884/4886/10385 4885/4887/10386 +f 4884/4886/10385 4886/4888/10453 4885/4887/10386 +f 4885/4887/10386 4886/4888/10453 4887/4889/10454 +f 4887/4889/10455 4886/4888/10455 4888/4890/10455 +f 4887/4889/10456 4888/4890/10457 4669/4671/10458 +f 4669/4671/10458 4888/4890/10457 4635/4637/10424 +f 4669/4671/10458 4635/4637/10424 4545/4547/10425 +f 4545/4547/10426 4635/4637/10427 4530/4532/10428 +f 4545/4547/10426 4530/4532/10428 4529/4531/10429 +f 4546/4548/10459 4529/4531/10431 4533/4535/10432 +f 4640/4642/10444 4671/4673/10443 4641/4643/10402 +f 4646/4648/10460 4675/4677/10461 4647/4649/10462 +f 4647/4649/10462 4675/4677/10461 4546/4548/10459 +f 4647/4649/10462 4546/4548/10459 4533/4535/10432 +f 4651/4653/10463 4625/4627/10463 4622/4624/10463 +f 4622/4624/10464 4617/4619/10464 4649/4651/10464 +f 4649/4651/10465 4617/4619/10465 4619/4621/10465 +f 4619/4621/10466 4773/4775/10467 4796/4798/10468 +f 4796/4798/10468 4773/4775/10467 4764/4766/10407 +f 4764/4766/10253 4766/4768/10255 4795/4797/10469 +f 4795/4797/10470 4766/4768/10470 4768/4770/10470 +f 4795/4797/10471 4768/4770/10471 4793/4795/10471 +f 4793/4795/10472 4768/4770/10472 4771/4773/10472 +f 4793/4795/10473 4771/4773/10474 4794/4796/10475 +f 4794/4796/10475 4771/4773/10474 4889/4891/10476 +f 4794/4796/10475 4889/4891/10476 4890/4892/10477 +f 4891/4893/10384 4892/4894/10385 4893/4895/10386 +f 4892/4894/10385 4894/4896/10387 4893/4895/10386 +f 4893/4895/10386 4894/4896/10387 4895/4897/10388 +f 4895/4897/10389 4894/4896/10389 4896/4898/10389 +f 4895/4897/10421 4896/4898/10422 4648/4650/10423 +f 4648/4650/10423 4896/4898/10422 4614/4616/10424 +f 4648/4650/10423 4614/4616/10424 4536/4538/10425 +f 4536/4538/10426 4614/4616/10427 4521/4523/10428 +f 4536/4538/10426 4521/4523/10428 4520/4522/10429 +f 4537/4539/10459 4520/4522/10431 4524/4526/10432 +f 4537/4539/10459 4524/4526/10432 4626/4628/10478 +f 4537/4539/10459 4626/4628/10478 4655/4657/10479 +f 4655/4657/10479 4626/4628/10478 4625/4627/10480 +f 4655/4657/10481 4625/4627/10481 4651/4653/10481 +f 4778/4780/10482 4629/4631/10483 4597/4599/10484 +f 4597/4599/10484 4750/4752/10485 4778/4780/10482 +f 4778/4780/10482 4750/4752/10485 4752/4754/10377 +f 4754/4756/10486 4749/4751/10486 4776/4778/10486 +f 4776/4778/10487 4749/4751/10488 4748/4750/10413 +f 4776/4778/10487 4748/4750/10413 4777/4779/10414 +f 4777/4779/10414 4748/4750/10413 4897/4899/10415 +f 4898/4900/10384 4899/4901/10385 4900/4902/10386 +f 4899/4901/10385 4901/4903/10387 4900/4902/10386 +f 4900/4902/10386 4901/4903/10387 4902/4904/10388 +f 4902/4904/10389 4901/4903/10389 4903/4905/10389 +f 4902/4904/10421 4903/4905/10489 4627/4629/10423 +f 4627/4629/10423 4903/4905/10489 4592/4594/10490 +f 4627/4629/10423 4592/4594/10490 4527/4529/10425 +f 4527/4529/10426 4592/4594/10427 4512/4514/10428 +f 4527/4529/10426 4512/4514/10428 4511/4513/10429 +f 4528/4530/10459 4511/4513/10431 4515/4517/10432 +f 4597/4599/10484 4629/4631/10483 4595/4597/10491 +f 4603/4605/10460 4633/4635/10461 4604/4606/10462 +f 4604/4606/10462 4633/4635/10461 4528/4530/10459 +f 4604/4606/10462 4528/4530/10459 4515/4517/10432 +f 4570/4572/10492 4729/4731/10493 4762/4764/10494 +f 4762/4764/10494 4729/4731/10493 4731/4733/10495 +f 4761/4763/10245 4731/4733/10247 4733/4735/10496 +f 4761/4763/10497 4733/4735/10497 4759/4761/10497 +f 4759/4761/10498 4733/4735/10498 4735/4737/10498 +f 4759/4761/10499 4735/4737/10500 4760/4762/10501 +f 4760/4762/10501 4735/4737/10500 4904/4906/10502 +f 4904/4906/10502 4735/4737/10500 4905/4907/10503 +f 4904/4906/10502 4905/4907/10503 4906/4908/10504 +f 4907/4909/10452 4908/4910/10505 4909/4911/10386 +f 4908/4910/10505 4910/4912/10506 4909/4911/10386 +f 4909/4911/10386 4910/4912/10506 4911/4913/10388 +f 4911/4913/10389 4910/4912/10389 4912/4914/10389 +f 4911/4913/10390 4912/4914/10390 4605/4607/10390 +f 4605/4607/10391 4912/4914/10507 4565/4567/10508 +f 4605/4607/10391 4565/4567/10508 4503/4505/10509 +f 4605/4607/10391 4503/4505/10509 4518/4520/10510 +f 4518/4520/10510 4503/4505/10509 4502/4504/10511 +f 4502/4504/10512 4505/4507/10513 4519/4521/10514 +f 4519/4521/10514 4505/4507/10513 4577/4579/10515 +f 4570/4572/10516 4762/4764/10517 4608/4610/10518 +f 4570/4572/10516 4608/4610/10518 4568/4570/10519 +f 4568/4570/10520 4608/4610/10520 4606/4608/10520 +f 4568/4570/10521 4606/4608/10521 4573/4575/10521 +f 4576/4578/10522 4612/4614/10523 4577/4579/10524 +f 4577/4579/10524 4612/4614/10523 4519/4521/10525 +f 4913/4915/10526 4914/4916/10527 4915/4917/10528 +f 4913/4915/10526 4915/4917/10528 4916/4918/10529 +f 4916/4918/10529 4915/4917/10528 4917/4919/10530 +f 4917/4919/10530 4915/4917/10528 4918/4920/10531 +f 4917/4919/10530 4918/4920/10531 4919/4921/10532 +f 4919/4921/10532 4918/4920/10531 4920/4922/10533 +f 4919/4921/10532 4920/4922/10533 4921/4923/10534 +f 4919/4921/10532 4921/4923/10534 4922/4924/10535 +f 4923/4925/10536 4924/4926/10537 4925/4927/10538 +f 4925/4927/10538 4924/4926/10537 4926/4928/10539 +f 4927/4929/10540 4928/4930/10541 4929/4931/10542 +f 4927/4929/10540 4929/4931/10542 4930/4932/10543 +f 4846/4848/10544 4721/4723/10545 4712/4714/10546 +f 4721/4723/10545 4866/4868/10547 4712/4714/10546 +f 4855/4857/10548 4921/4923/10549 4920/4922/10550 +f 4855/4857/10548 4856/4858/10551 4921/4923/10549 +f 4721/4723/10545 4723/4725/10552 4866/4868/10547 +f 4931/4933/10553 4866/4868/10547 4723/4725/10552 +f 4856/4858/10551 4932/4934/10554 4921/4923/10549 +f 4856/4858/10551 4933/4935/10555 4932/4934/10554 +f 4931/4933/10553 4725/4727/10556 4866/4868/10547 +f 4866/4868/10547 4725/4727/10556 4865/4867/10557 +f 4856/4858/10551 4934/4936/10558 4933/4935/10555 +f 4856/4858/10551 4858/4860/10559 4934/4936/10558 +f 4858/4860/10559 4935/4937/10560 4934/4936/10558 +f 4845/4847/10561 4840/4842/10562 4844/4846/10563 +f 4844/4846/10563 4840/4842/10562 4839/4841/10564 +f 4844/4846/10373 4839/4841/10343 4717/4719/10374 +f 4717/4719/10374 4839/4841/10343 4706/4708/10345 +f 4717/4719/10565 4706/4708/10566 4718/4720/10567 +f 4718/4720/10567 4706/4708/10566 4705/4707/10568 +f 4829/4831/10561 4823/4825/10569 4828/4830/10570 +f 4828/4830/10570 4823/4825/10569 4816/4818/10571 +f 4828/4830/10572 4816/4818/10376 4694/4696/10573 +f 4694/4696/10573 4816/4818/10376 4682/4684/10375 +f 4694/4696/10574 4682/4684/10575 4695/4697/10576 +f 4695/4697/10576 4682/4684/10575 4681/4683/10577 +f 4812/4814/10561 4808/4810/10578 4811/4813/10579 +f 4811/4813/10579 4808/4810/10578 4807/4809/10580 +f 4811/4813/10442 4807/4809/10406 4671/4673/10443 +f 4671/4673/10443 4807/4809/10406 4662/4664/10405 +f 4671/4673/10581 4662/4664/10582 4672/4674/10583 +f 4672/4674/10583 4662/4664/10582 4661/4663/10577 +f 4797/4799/10561 4791/4793/10578 4796/4798/10579 +f 4796/4798/10579 4791/4793/10578 4790/4792/10580 +f 4796/4798/10468 4790/4792/10445 4619/4621/10466 +f 4619/4621/10466 4790/4792/10445 4640/4642/10444 +f 4619/4621/10584 4640/4642/10585 4652/4654/10586 +f 4652/4654/10586 4640/4642/10585 4639/4641/10577 +f 4779/4781/10561 4774/4776/10578 4778/4780/10579 +f 4778/4780/10579 4774/4776/10578 4773/4775/10580 +f 4778/4780/10482 4773/4775/10467 4629/4631/10483 +f 4629/4631/10483 4773/4775/10467 4619/4621/10466 +f 4629/4631/10587 4619/4621/10588 4630/4632/10589 +f 4630/4632/10589 4619/4621/10588 4618/4620/10590 +f 4763/4765/10591 4757/4759/10592 4750/4752/10593 +f 4763/4765/10591 4750/4752/10593 4762/4764/10594 +f 4762/4764/10595 4750/4752/10485 4597/4599/10484 +f 4762/4764/10517 4597/4599/10596 4608/4610/10518 +f 4608/4610/10597 4597/4599/10598 4609/4611/10599 +f 4609/4611/10599 4597/4599/10598 4596/4598/10600 +f 4742/4744/10601 4737/4739/10601 4729/4731/10601 +f 4742/4744/10602 4729/4731/10602 4587/4589/10602 +f 4587/4589/10603 4729/4731/10493 4570/4572/10492 +f 4587/4589/10604 4570/4572/10605 4588/4590/10606 +f 4588/4590/10606 4570/4572/10605 4569/4571/10607 +f 4715/4717/10608 4710/4712/10609 4689/4691/10610 +f 4689/4691/10610 4710/4712/10609 4713/4715/10611 +f 4689/4691/10612 4713/4715/10612 4560/4562/10612 +f 4689/4691/10613 4560/4562/10613 4563/4565/10613 +f 4563/4565/10614 4560/4562/10615 4562/4564/10616 +f 4562/4564/10616 4560/4562/10615 4559/4561/10617 +f 4700/4702/10618 4686/4688/10619 4699/4701/10620 +f 4699/4701/10620 4686/4688/10619 4689/4691/10621 +f 4699/4701/10440 4689/4691/10399 4555/4557/10430 +f 4555/4557/10430 4689/4691/10399 4551/4553/10401 +f 4555/4557/10622 4551/4553/10623 4553/4555/10624 +f 4553/4555/10624 4551/4553/10623 4550/4552/10625 +f 4676/4678/10618 4666/4668/10626 4675/4677/10627 +f 4675/4677/10627 4666/4668/10626 4668/4670/10628 +f 4675/4677/10461 4668/4670/10441 4546/4548/10459 +f 4546/4548/10459 4668/4670/10441 4542/4544/10432 +f 4546/4548/10622 4542/4544/10623 4544/4546/10624 +f 4544/4546/10624 4542/4544/10623 4541/4543/10625 +f 4656/4658/10618 4644/4646/10626 4655/4657/10627 +f 4655/4657/10627 4644/4646/10626 4647/4649/10628 +f 4655/4657/10479 4647/4649/10462 4537/4539/10459 +f 4537/4539/10459 4647/4649/10462 4533/4535/10432 +f 4537/4539/10622 4533/4535/10623 4535/4537/10624 +f 4535/4537/10624 4533/4535/10623 4532/4534/10625 +f 4634/4636/10618 4623/4625/10626 4633/4635/10627 +f 4633/4635/10627 4623/4625/10626 4626/4628/10628 +f 4633/4635/10461 4626/4628/10478 4528/4530/10459 +f 4528/4530/10459 4626/4628/10478 4524/4526/10432 +f 4528/4530/10622 4524/4526/10623 4526/4528/10624 +f 4526/4528/10624 4524/4526/10623 4523/4525/10625 +f 4613/4615/10618 4601/4603/10626 4612/4614/10627 +f 4612/4614/10627 4601/4603/10626 4604/4606/10628 +f 4612/4614/10523 4604/4606/10462 4519/4521/10525 +f 4519/4521/10525 4604/4606/10462 4515/4517/10432 +f 4519/4521/10622 4515/4517/10623 4517/4519/10624 +f 4517/4519/10624 4515/4517/10623 4514/4516/10625 +f 4582/4584/10629 4574/4576/10630 4583/4585/10631 +f 4583/4585/10631 4574/4576/10630 4577/4579/10632 +f 4583/4585/10633 4577/4579/10515 4509/4511/10634 +f 4509/4511/10634 4577/4579/10515 4505/4507/10513 +f 4509/4511/10635 4505/4507/10636 4507/4509/10637 +f 4507/4509/10637 4505/4507/10636 4506/4508/10638 +f 4564/4566/10639 4558/4560/10639 4557/4559/10639 +f 4564/4566/10640 4557/4559/10640 4702/4704/10640 +f 4554/4556/10641 4549/4551/10641 4548/4550/10641 +f 4554/4556/10642 4548/4550/10642 4678/4680/10642 +f 4545/4547/10641 4540/4542/10641 4539/4541/10641 +f 4545/4547/10642 4539/4541/10642 4658/4660/10642 +f 4536/4538/10641 4531/4533/10641 4530/4532/10641 +f 4536/4538/10642 4530/4532/10642 4636/4638/10642 +f 4527/4529/10641 4522/4524/10641 4521/4523/10641 +f 4527/4529/10642 4521/4523/10642 4615/4617/10642 +f 4518/4520/10643 4513/4515/10643 4512/4514/10643 +f 4518/4520/10644 4512/4514/10644 4593/4595/10644 +f 4508/4510/10645 4504/4506/10646 4510/4512/10647 +f 4510/4512/10647 4504/4506/10646 4503/4505/10648 +f 4510/4512/10649 4503/4505/10650 4579/4581/10651 +f 4579/4581/10651 4503/4505/10650 4566/4568/10652 +f 4928/4930/10653 4927/4929/10654 4913/4915/10526 +f 4913/4915/10526 4927/4929/10654 4914/4916/10527 +f 4852/4854/10340 4851/4853/10339 4929/4931/10655 +f 4929/4931/10655 4851/4853/10339 4930/4932/10656 +f 4931/4933/10657 4936/4938/10658 4725/4727/10204 +f 4725/4727/10204 4936/4938/10658 4726/4728/10205 +f 4723/4725/10202 4724/4726/10203 4931/4933/10659 +f 4931/4933/10659 4724/4726/10203 4936/4938/10660 +f 4727/4729/10661 4728/4730/10662 4926/4928/10539 +f 4727/4729/10661 4926/4928/10539 4924/4926/10663 +f 4937/4939/10664 4938/4940/10665 4939/4941/10666 +f 4940/4942/10667 4937/4939/10664 4939/4941/10666 +f 4938/4940/10665 4937/4939/10664 4941/4943/10668 +f 4942/4944/10669 4943/4945/10670 4944/4946/10671 +f 4945/4947/10672 4942/4944/10669 4922/4924/10673 +f 4945/4947/10672 4943/4945/10670 4942/4944/10669 +f 4858/4860/10559 4946/4948/10674 4935/4937/10560 +f 4946/4948/10674 4947/4949/10675 4935/4937/10560 +f 4727/4729/10676 4924/4926/10677 4865/4867/10557 +f 4924/4926/10677 4864/4866/10678 4865/4867/10557 +f 4924/4926/10677 4923/4925/10679 4864/4866/10678 +f 4946/4948/10674 4948/4950/10680 4947/4949/10675 +f 4923/4925/10679 4949/4951/10681 4864/4866/10678 +f 4946/4948/10674 4861/4863/10682 4948/4950/10680 +f 4865/4867/10557 4725/4727/10556 4727/4729/10676 +f 4861/4863/10682 4860/4862/10683 4950/4952/10684 +f 4950/4952/10684 4860/4862/10683 4951/4953/10685 +f 4860/4862/10683 4952/4954/10686 4951/4953/10685 +f 4949/4951/10681 4860/4862/10683 4863/4865/10687 +f 4860/4862/10683 4949/4951/10681 4952/4954/10686 +f 4949/4951/10681 4863/4865/10687 4864/4866/10678 +f 4854/4856/10688 4927/4929/10689 4930/4932/10690 +f 4851/4853/10691 4854/4856/10688 4930/4932/10690 +f 4854/4856/10688 4914/4916/10692 4927/4929/10689 +f 4854/4856/10688 4853/4855/10693 4914/4916/10692 +f 4851/4853/10691 4849/4851/10694 4854/4856/10688 +f 4853/4855/10693 4915/4917/10695 4914/4916/10692 +f 4854/4856/10688 4849/4851/10694 4708/4710/10696 +f 4948/4950/10680 4861/4863/10682 4950/4952/10684 +f 4853/4855/10693 4836/4838/10697 4915/4917/10695 +f 4836/4838/10697 4918/4920/10698 4915/4917/10695 +f 4849/4851/10694 4846/4848/10544 4708/4710/10696 +f 4846/4848/10544 4712/4714/10546 4708/4710/10696 +f 4836/4838/10697 4855/4857/10548 4918/4920/10698 +f 4855/4857/10548 4920/4922/10550 4918/4920/10698 +f 4910/4912/528 4953/4955/528 4912/4914/528 +f 4910/4912/528 4954/4956/528 4953/4955/528 +f 4955/4957/98 4956/4958/10699 4957/4959/98 +f 4955/4957/98 4578/4580/10699 4956/4958/10699 +f 4956/4958/10699 4958/4960/98 4957/4959/98 +f 4901/4903/10700 4959/4961/10701 4903/4905/10702 +f 4903/4905/10702 4959/4961/10701 4960/4962/10703 +f 4901/4903/10700 4961/4963/10704 4959/4961/10701 +f 4962/4964/10705 4909/4911/98 4911/4913/10706 +f 4911/4913/10706 4960/4962/10707 4959/4961/10708 +f 4911/4913/10706 4605/4607/10709 4960/4962/10707 +f 4959/4961/10708 4962/4964/10705 4911/4913/10706 +f 4894/4896/528 4963/4965/10710 4896/4898/10711 +f 4896/4898/10711 4963/4965/10710 4964/4966/10712 +f 4965/4967/10713 4900/4902/98 4902/4904/10714 +f 4902/4904/10714 4964/4966/10715 4965/4967/10713 +f 4902/4904/10714 4627/4629/10716 4964/4966/10715 +f 4886/4888/10700 4966/4968/10717 4888/4890/10718 +f 4888/4890/10718 4966/4968/10717 4967/4969/10719 +f 4886/4888/10700 4968/4970/10704 4966/4968/10717 +f 4969/4971/10705 4893/4895/98 4895/4897/10720 +f 4895/4897/10720 4967/4969/10721 4966/4968/10722 +f 4895/4897/10720 4648/4650/10723 4967/4969/10721 +f 4966/4968/10722 4969/4971/10705 4895/4897/10720 +f 4878/4880/528 4970/4972/10710 4880/4882/10711 +f 4880/4882/10711 4970/4972/10710 4971/4973/10712 +f 4972/4974/10713 4885/4887/98 4887/4889/10724 +f 4887/4889/10724 4971/4973/10715 4972/4974/10713 +f 4887/4889/10724 4669/4671/10716 4971/4973/10715 +f 4871/4873/528 4973/4975/10710 4873/4875/10711 +f 4873/4875/10711 4973/4975/10710 4974/4976/10712 +f 4975/4977/10725 4875/4877/98 4879/4881/10726 +f 4879/4881/10726 4974/4976/10715 4975/4977/10725 +f 4879/4881/10726 4690/4692/10716 4974/4976/10715 +f 4862/4864/10727 4976/4978/10728 4863/4865/10729 +f 4863/4865/10729 4976/4978/10728 4977/4979/10730 +f 4978/4980/98 4870/4872/98 4872/4874/98 +f 4872/4874/98 4714/4716/98 4979/4981/98 +f 4979/4981/98 4978/4980/98 4872/4874/98 +f 4954/4956/10731 4958/4960/10732 4956/4958/10733 +f 4954/4956/10731 4956/4958/10733 4953/4955/10734 +f 4961/4963/10735 4962/4964/10735 4959/4961/10735 +f 4963/4965/10736 4965/4967/10736 4964/4966/10736 +f 4968/4970/10735 4969/4971/10735 4966/4968/10735 +f 4970/4972/10736 4972/4974/10736 4971/4973/10736 +f 4973/4975/10736 4975/4977/10736 4974/4976/10736 +f 4976/4978/10737 4978/4980/10737 4979/4981/10737 +f 4976/4978/10738 4979/4981/10738 4977/4979/10738 +f 4980/4982/10739 4908/4910/10740 4907/4909/10741 +f 4906/4908/10742 4905/4907/10743 4981/4983/10744 +f 4981/4983/10744 4982/4984/10745 4906/4908/10742 +f 4906/4908/10742 4982/4984/10745 4983/4985/10746 +f 4983/4985/10746 4982/4984/10745 4984/4986/10747 +f 4983/4985/10746 4984/4986/10747 4907/4909/10741 +f 4907/4909/10741 4984/4986/10747 4985/4987/10748 +f 4907/4909/10741 4985/4987/10748 4980/4982/10739 +f 4986/4988/98 4987/4989/98 4988/4990/98 +f 4986/4988/98 4989/4991/98 4990/4992/98 +f 4990/4992/98 4989/4991/98 4991/4993/98 +f 4990/4992/98 4991/4993/98 4992/4994/10749 +f 4990/4992/98 4992/4994/10749 4993/4995/7914 +f 4993/4995/7914 4992/4994/10749 4994/4996/10750 +f 4986/4988/98 4988/4990/98 4989/4991/98 +f 4995/4997/10739 4899/4901/10740 4898/4900/10751 +f 4748/4750/10752 4996/4998/10753 4897/4899/10754 +f 4996/4998/10753 4997/4999/10755 4897/4899/10754 +f 4897/4899/10754 4997/4999/10755 4998/5000/10756 +f 4998/5000/10756 4997/4999/10755 4999/5001/10757 +f 4998/5000/10756 4999/5001/10757 4898/4900/10751 +f 4898/4900/10751 4999/5001/10757 5000/5002/10758 +f 4898/4900/10751 5000/5002/10758 4995/4997/10739 +f 5001/5003/10759 4904/4906/10760 4906/4908/10761 +f 4907/4909/10762 4909/4911/10763 5002/5004/10764 +f 4907/4909/10762 5003/5005/10765 4983/4985/10766 +f 4983/4985/10766 5003/5005/10765 5004/5006/10767 +f 4983/4985/10766 5004/5006/10767 4906/4908/10761 +f 4906/4908/10761 5004/5006/10767 5005/5007/10768 +f 4906/4908/10761 5005/5007/10768 5001/5003/10759 +f 4907/4909/10762 5002/5004/10764 5003/5005/10765 +f 5006/5008/10739 4892/4894/10740 4891/4893/10741 +f 4890/4892/10742 4889/4891/10743 5007/5009/10744 +f 5007/5009/10744 5008/5010/10769 4890/4892/10742 +f 4890/4892/10742 5008/5010/10769 5009/5011/10746 +f 5009/5011/10746 5008/5010/10769 5010/5012/10757 +f 5009/5011/10746 5010/5012/10757 4891/4893/10741 +f 4891/4893/10741 5010/5012/10757 5011/5013/10770 +f 4891/4893/10741 5011/5013/10770 5006/5008/10739 +f 5012/5014/10771 4777/4779/10772 4897/4899/10773 +f 4898/4900/10762 4900/4902/10763 5013/5015/10764 +f 4898/4900/10762 5014/5016/10765 4998/5000/10774 +f 4998/5000/10774 5014/5016/10765 5015/5017/10775 +f 4998/5000/10774 5015/5017/10775 4897/4899/10773 +f 4897/4899/10773 5015/5017/10775 5016/5018/10776 +f 4897/4899/10773 5016/5018/10776 5012/5014/10771 +f 4898/4900/10762 5013/5015/10764 5014/5016/10765 +f 5017/5019/10739 4884/4886/10740 4883/4885/10741 +f 4882/4884/10777 4781/4783/10778 5018/5020/10779 +f 5018/5020/10779 5019/5021/10755 4882/4884/10777 +f 4882/4884/10777 5019/5021/10755 5020/5022/10756 +f 5020/5022/10756 5019/5021/10755 5021/5023/10780 +f 5020/5022/10756 5021/5023/10780 4883/4885/10741 +f 4883/4885/10741 5021/5023/10780 5022/5024/10770 +f 4883/4885/10741 5022/5024/10770 5017/5019/10739 +f 5023/5025/10781 4794/4796/10782 4890/4892/10783 +f 4891/4893/10762 4893/4895/10763 5024/5026/10764 +f 4891/4893/10762 5025/5027/10765 5009/5011/10766 +f 5009/5011/10766 5025/5027/10765 5026/5028/10767 +f 5009/5011/10766 5026/5028/10767 4890/4892/10783 +f 4890/4892/10783 5026/5028/10767 5027/5029/10768 +f 4890/4892/10783 5027/5029/10768 5023/5025/10781 +f 4891/4893/10762 5024/5026/10764 5025/5027/10765 +f 5028/5030/10784 4877/4879/10785 4876/4878/10786 +f 4799/4801/10752 5029/5031/10753 4874/4876/10754 +f 5029/5031/10753 5030/5032/10755 4874/4876/10754 +f 4874/4876/10754 5030/5032/10755 5031/5033/10787 +f 5031/5033/10787 5030/5032/10755 5032/5034/10788 +f 5031/5033/10787 5032/5034/10788 4876/4878/10786 +f 4876/4878/10786 5032/5034/10788 5033/5035/10789 +f 4876/4878/10786 5033/5035/10789 5028/5030/10784 +f 5034/5036/10790 4881/4883/10791 4882/4884/10792 +f 4883/4885/10762 4885/4887/10763 5035/5037/10764 +f 4883/4885/10762 5036/5038/10765 5020/5022/10774 +f 5020/5022/10774 5036/5038/10765 5037/5039/10775 +f 5020/5022/10774 5037/5039/10775 4882/4884/10792 +f 4882/4884/10792 5037/5039/10775 5038/5040/10776 +f 4882/4884/10792 5038/5040/10776 5034/5036/10790 +f 4883/4885/10762 5035/5037/10764 5036/5038/10765 +f 5039/5041/10739 4869/4871/10740 4868/4870/10741 +f 4867/4869/10777 4814/4816/10778 5040/5042/10779 +f 5040/5042/10779 5041/5043/10755 4867/4869/10777 +f 4867/4869/10777 5041/5043/10755 5042/5044/10756 +f 5042/5044/10756 5041/5043/10755 5043/5045/10780 +f 5042/5044/10756 5043/5045/10780 4868/4870/10741 +f 4868/4870/10741 5043/5045/10780 5044/5046/10770 +f 4868/4870/10741 5044/5046/10770 5039/5041/10739 +f 5045/5047/10771 4826/4828/10772 4874/4876/10793 +f 4875/4877/10794 5046/5048/10795 4876/4878/10796 +f 4876/4878/10796 5047/5049/10797 5031/5033/10798 +f 5031/5033/10798 5047/5049/10797 5048/5050/10775 +f 5031/5033/10798 5048/5050/10775 4874/4876/10793 +f 4874/4876/10793 5048/5050/10775 5049/5051/10776 +f 4874/4876/10793 5049/5051/10776 5045/5047/10771 +f 4876/4878/10796 5046/5048/10795 5047/5049/10797 +f 5050/5052/10799 4859/4861/10800 4861/4863/10801 +f 5051/5053/10802 5052/5054/10803 4857/4859/10804 +f 4857/4859/10804 5052/5054/10803 4858/4860/10805 +f 4858/4860/10805 5052/5054/10803 4946/4948/10806 +f 4946/4948/10806 5052/5054/10803 5053/5055/10807 +f 4946/4948/10806 5053/5055/10807 4861/4863/10801 +f 4861/4863/10801 5053/5055/10807 5054/5056/10808 +f 4861/4863/10801 5054/5056/10808 5050/5052/10799 +f 5055/5057/10771 4843/4845/10772 4867/4869/10773 +f 4868/4870/10762 4870/4872/10763 5056/5058/10764 +f 4868/4870/10762 5057/5059/10765 5042/5044/10774 +f 5042/5044/10774 5057/5059/10765 5058/5060/10775 +f 5042/5044/10774 5058/5060/10775 4867/4869/10773 +f 4867/4869/10773 5058/5060/10775 5059/5061/10776 +f 4867/4869/10773 5059/5061/10776 5055/5057/10771 +f 4868/4870/10762 5056/5058/10764 5057/5059/10765 +f 4981/4983/10809 4994/4996/10810 4992/4994/10811 +f 4981/4983/10809 4992/4994/10811 4982/4984/10812 +f 4982/4984/10813 4992/4994/10813 4991/4993/10813 +f 4982/4984/10814 4991/4993/10814 4984/4986/10814 +f 4984/4986/10815 4991/4993/10815 4989/4991/10815 +f 4984/4986/10816 4989/4991/10816 4985/4987/10816 +f 4985/4987/10817 4989/4991/10818 4988/4990/10819 +f 4985/4987/10817 4988/4990/10819 4980/4982/10820 +f 4996/4998/10821 5001/5003/10821 5005/5007/10821 +f 4996/4998/10822 5005/5007/10822 4997/4999/10822 +f 4997/4999/10823 5005/5007/10768 5004/5006/10767 +f 4997/4999/10755 5004/5006/10824 4999/5001/10757 +f 4999/5001/10825 5004/5006/10767 5003/5005/10765 +f 4999/5001/10757 5003/5005/10826 5000/5002/10758 +f 5000/5002/10827 5003/5005/10827 5002/5004/10827 +f 5000/5002/10828 5002/5004/10828 4995/4997/10828 +f 5007/5009/10829 5012/5014/10829 5016/5018/10829 +f 5007/5009/10822 5016/5018/10822 5008/5010/10822 +f 5008/5010/10823 5016/5018/10776 5015/5017/10775 +f 5008/5010/10769 5015/5017/10824 5010/5012/10757 +f 5010/5012/10825 5015/5017/10775 5014/5016/10765 +f 5010/5012/10757 5014/5016/10830 5011/5013/10770 +f 5011/5013/10831 5014/5016/10831 5013/5015/10831 +f 5011/5013/10828 5013/5015/10828 5006/5008/10828 +f 5018/5020/10829 5023/5025/10829 5027/5029/10829 +f 5018/5020/10822 5027/5029/10822 5019/5021/10822 +f 5019/5021/10823 5027/5029/10768 5026/5028/10767 +f 5019/5021/10755 5026/5028/10824 5021/5023/10780 +f 5021/5023/10825 5026/5028/10767 5025/5027/10765 +f 5021/5023/10780 5025/5027/10830 5022/5024/10770 +f 5022/5024/10831 5025/5027/10831 5024/5026/10831 +f 5022/5024/10828 5024/5026/10828 5017/5019/10828 +f 5029/5031/10821 5034/5036/10821 5038/5040/10821 +f 5029/5031/10822 5038/5040/10822 5030/5032/10822 +f 5030/5032/10823 5038/5040/10776 5037/5039/10775 +f 5030/5032/10755 5037/5039/10824 5032/5034/10788 +f 5032/5034/10825 5037/5039/10775 5036/5038/10765 +f 5032/5034/10788 5036/5038/10830 5033/5035/10789 +f 5033/5035/10831 5036/5038/10831 5035/5037/10831 +f 5033/5035/10828 5035/5037/10828 5028/5030/10828 +f 5040/5042/10829 5045/5047/10829 5049/5051/10829 +f 5040/5042/10832 5049/5051/10832 5041/5043/10832 +f 5041/5043/10833 5049/5051/10776 5048/5050/10775 +f 5041/5043/10755 5048/5050/10824 5043/5045/10780 +f 5043/5045/10825 5048/5050/10775 5047/5049/10797 +f 5043/5045/10780 5047/5049/10830 5044/5046/10770 +f 5044/5046/10831 5047/5049/10831 5046/5048/10831 +f 5044/5046/10834 5046/5048/10834 5039/5041/10834 +f 5051/5053/10829 5055/5057/10829 5059/5061/10829 +f 5051/5053/10822 5059/5061/10822 5052/5054/10822 +f 5052/5054/10823 5059/5061/10776 5058/5060/10775 +f 5052/5054/10803 5058/5060/10824 5053/5055/10807 +f 5053/5055/10825 5058/5060/10775 5057/5059/10765 +f 5053/5055/10807 5057/5059/10826 5054/5056/10808 +f 5054/5056/10827 5057/5059/10827 5056/5058/10827 +f 5054/5056/10828 5056/5058/10828 5050/5052/10828 +f 5060/5062/10835 4948/4950/10836 4940/4942/10837 +f 4940/4942/10837 4948/4950/10836 4950/4952/10838 +f 4941/4943/10839 4952/4954/10840 5061/5063/10841 +f 5061/5063/10841 4952/4954/10840 4949/4951/10842 +f 4944/4946/10843 4934/4936/10844 4935/4937/10845 +f 4944/4946/10843 4935/4937/10845 5062/5064/10846 +f 5062/5064/10846 4935/4937/10845 4947/4949/10847 +f 5062/5064/10846 4947/4949/10847 5063/5065/10848 +f 5063/5065/10848 4947/4949/10847 4948/4950/10836 +f 5063/5065/10848 4948/4950/10836 5060/5062/10835 +f 4933/4935/10849 4943/4945/10850 4945/4947/10851 +f 4933/4935/10849 4945/4947/10851 4932/4934/10852 +f 5055/5057/10853 5051/5053/10854 4843/4845/10855 +f 4843/4845/10855 5051/5053/10854 4857/4859/10856 +f 4843/4845/10857 4857/4859/10353 4831/4833/10352 +f 4843/4845/10858 4831/4833/10858 4841/4843/10858 +f 4841/4843/10859 4831/4833/10859 4830/4832/10859 +f 5045/5047/10853 5040/5042/10860 4826/4828/10861 +f 4826/4828/10861 5040/5042/10860 4814/4816/10862 +f 4826/4828/10863 4814/4816/10864 4824/4826/10865 +f 4824/4826/10865 4814/4816/10864 4813/4815/10866 +f 5034/5036/10867 5029/5031/10867 4881/4883/10867 +f 4881/4883/10868 5029/5031/10868 4799/4801/10868 +f 4881/4883/10869 4799/4801/10869 4810/4812/10869 +f 4810/4812/10870 4799/4801/10870 4798/4800/10870 +f 4810/4812/10871 4798/4800/10871 4809/4811/10871 +f 5023/5025/10853 5018/5020/10860 4794/4796/10861 +f 4794/4796/10861 5018/5020/10860 4781/4783/10862 +f 4794/4796/10863 4781/4783/10864 4792/4794/10865 +f 4792/4794/10865 4781/4783/10864 4780/4782/10866 +f 5012/5014/10853 5007/5009/10872 4777/4779/10873 +f 4777/4779/10873 5007/5009/10872 4889/4891/10874 +f 4777/4779/10875 4889/4891/10875 4771/4773/10875 +f 4777/4779/10876 4771/4773/10876 4775/4777/10876 +f 4775/4777/10877 4771/4773/10877 4772/4774/10877 +f 5001/5003/10867 4996/4998/10867 4904/4906/10867 +f 4904/4906/10868 4996/4998/10868 4748/4750/10868 +f 4904/4906/10502 4748/4750/10869 4760/4762/10501 +f 4760/4762/10870 4748/4750/10870 4747/4749/10870 +f 4760/4762/10871 4747/4749/10871 4758/4760/10871 +f 4994/4996/10878 4981/4983/10879 4993/4995/10880 +f 4993/4995/10880 4981/4983/10879 4905/4907/10881 +f 4993/4995/10882 4905/4907/10503 4740/4742/10883 +f 4740/4742/10883 4905/4907/10503 4735/4737/10500 +f 4740/4742/10884 4735/4737/10885 4736/4738/10886 +f 4740/4742/10884 4736/4738/10886 4738/4740/10887 +f 4978/4980/10888 4976/4978/10888 4870/4872/10888 +f 4870/4872/10889 4976/4978/10889 4862/4864/10889 +f 4870/4872/10890 4862/4864/10890 4859/4861/10890 +f 4870/4872/10891 4859/4861/10892 5056/5058/10893 +f 5056/5058/10893 4859/4861/10892 5050/5052/10894 +f 4975/4977/10895 4973/4975/10895 4875/4877/10895 +f 4875/4877/10896 4973/4975/10896 4871/4873/10896 +f 4875/4877/10897 4871/4873/10897 4869/4871/10897 +f 4875/4877/10898 4869/4871/10898 5046/5048/10898 +f 5046/5048/10899 4869/4871/10899 5039/5041/10899 +f 4972/4974/10900 4970/4972/10900 4885/4887/10900 +f 4885/4887/10901 4970/4972/10901 4878/4880/10901 +f 4885/4887/10902 4878/4880/10902 4877/4879/10902 +f 4885/4887/10903 4877/4879/10904 5035/5037/10905 +f 5035/5037/10905 4877/4879/10904 5028/5030/10906 +f 4969/4971/10907 4968/4970/10907 4893/4895/10907 +f 4893/4895/10908 4968/4970/10908 4886/4888/10908 +f 4893/4895/10902 4886/4888/10902 4884/4886/10902 +f 4893/4895/10903 4884/4886/10904 5024/5026/10905 +f 5024/5026/10905 4884/4886/10904 5017/5019/10906 +f 4965/4967/10900 4963/4965/10900 4900/4902/10900 +f 4900/4902/10901 4963/4965/10901 4894/4896/10901 +f 4900/4902/10902 4894/4896/10902 4892/4894/10902 +f 4900/4902/10903 4892/4894/10904 5013/5015/10905 +f 5013/5015/10905 4892/4894/10904 5006/5008/10906 +f 4962/4964/10907 4961/4963/10907 4909/4911/10907 +f 4909/4911/10908 4961/4963/10908 4901/4903/10908 +f 4909/4911/10902 4901/4903/10902 4899/4901/10902 +f 4909/4911/10903 4899/4901/10904 5002/5004/10905 +f 5002/5004/10905 4899/4901/10904 4995/4997/10906 +f 4958/4960/10909 4954/4956/10910 4957/4959/10911 +f 4957/4959/10911 4954/4956/10910 4910/4912/10912 +f 4957/4959/10913 4910/4912/10506 4987/4989/10914 +f 4987/4989/10914 4910/4912/10506 4908/4910/10505 +f 4987/4989/10915 4908/4910/10916 4988/4990/10917 +f 4988/4990/10917 4908/4910/10916 4980/4982/10918 +f 4714/4716/10919 4703/4705/10919 4701/4703/10919 +f 4714/4716/10920 4701/4703/10361 4863/4865/10360 +f 4714/4716/10921 4863/4865/10921 4979/4981/10921 +f 4979/4981/10922 4863/4865/10922 4977/4979/10922 +f 4690/4692/10923 4679/4681/10923 4677/4679/10923 +f 4690/4692/10924 4677/4679/10393 4873/4875/10392 +f 4690/4692/10925 4873/4875/10925 4974/4976/10925 +f 4669/4671/10923 4659/4661/10923 4657/4659/10923 +f 4669/4671/10924 4657/4659/10924 4880/4882/10924 +f 4669/4671/10925 4880/4882/10925 4971/4973/10925 +f 4648/4650/10923 4637/4639/10923 4635/4637/10923 +f 4648/4650/10924 4635/4637/10924 4888/4890/10924 +f 4648/4650/10926 4888/4890/10926 4967/4969/10926 +f 4627/4629/10923 4616/4618/10923 4614/4616/10923 +f 4627/4629/10924 4614/4616/10924 4896/4898/10924 +f 4627/4629/10925 4896/4898/10925 4964/4966/10925 +f 4605/4607/10927 4594/4596/10928 4592/4594/10490 +f 4605/4607/10927 4592/4594/10490 4903/4905/10489 +f 4605/4607/10929 4903/4905/10702 4960/4962/10703 +f 4580/4582/10930 4567/4569/10931 4578/4580/10932 +f 4578/4580/10932 4567/4569/10931 4565/4567/10508 +f 4578/4580/10932 4565/4567/10508 4912/4914/10507 +f 4578/4580/10932 4912/4914/10507 4956/4958/10933 +f 4956/4958/10933 4912/4914/10507 4953/4955/10934 +f 4922/4924/10535 4921/4923/10534 4945/4947/10935 +f 4945/4947/10935 4921/4923/10534 4932/4934/10936 +f 4943/4945/10937 4933/4935/10938 4944/4946/10843 +f 4944/4946/10843 4933/4935/10938 4934/4936/10844 +f 4952/4954/10840 4941/4943/10839 4951/4953/10939 +f 4951/4953/10939 4941/4943/10839 4937/4939/10940 +f 4951/4953/10941 4937/4939/10942 4950/4952/10838 +f 4950/4952/10838 4937/4939/10942 4940/4942/10837 +f 4923/4925/10943 4925/4927/10944 5061/5063/10841 +f 4923/4925/10943 5061/5063/10841 4949/4951/10842 +f 5064/5066/10945 5065/5067/10946 5066/5068/10947 +f 5067/5069/10948 5068/5070/10949 5065/5067/10946 +f 5064/5066/10945 5067/5069/10948 5065/5067/10946 +f 5064/5066/10945 5069/5071/10950 5067/5069/10948 +f 5070/5072/10951 5071/5073/10952 5068/5070/10953 +f 5072/5074/10954 5070/5072/10951 5073/5075/10955 +f 5071/5073/10952 5070/5072/10951 5072/5074/10954 +f 5072/5074/10954 5074/5076/10956 5071/5073/10952 +f 5072/5074/10954 5075/5077/10957 5074/5076/10956 +f 5076/5078/10958 5077/5079/10959 5078/5080/10960 +f 5076/5078/10958 5079/5081/10961 5080/5082/10962 +f 5079/5081/10961 5076/5078/10958 5081/5083/10963 +f 5081/5083/10963 5076/5078/10958 5082/5084/10964 +f 5083/5085/10965 5084/5086/10966 5081/5083/10967 +f 5083/5085/10965 5081/5083/10967 5085/5087/10968 +f 5086/5088/10969 5084/5086/10966 5083/5085/10965 +f 5087/5089/10970 5088/5090/10971 5089/5091/10972 +f 5090/5092/10973 5091/5093/10974 5092/5094/10975 +f 5093/5095/10976 5094/5096/10977 5095/5097/10978 +f 5096/5098/10979 5097/5099/10980 5098/5100/10981 +f 5098/5100/10981 5099/5101/10982 5096/5098/10979 +f 5098/5100/10981 5100/5102/10983 5099/5101/10982 +f 5100/5102/10983 5098/5100/10981 5101/5103/10984 +f 5100/5102/10983 5101/5103/10984 5102/5104/10985 +f 5085/5087/10968 5103/5105/10986 5083/5085/10965 +f 5082/5084/10964 5076/5078/10958 5103/5105/10986 +f 5086/5088/10969 5083/5085/10965 5104/5106/10987 +f 5105/5107/10988 5102/5104/10985 5101/5103/10984 +f 5076/5078/10958 5078/5080/10960 5103/5105/10986 +f 5103/5105/10986 5078/5080/10960 5083/5085/10965 +f 5083/5085/10965 5078/5080/10960 5106/5108/10989 +f 5083/5085/10965 5106/5108/10989 5104/5106/10987 +f 5104/5106/10987 5106/5108/10989 5107/5109/10990 +f 5077/5079/10959 5108/5110/10991 5078/5080/10960 +f 5078/5080/10960 5108/5110/10991 5109/5111/10992 +f 5106/5108/10989 5078/5080/10960 5110/5112/10993 +f 5106/5108/10989 5110/5112/10993 5107/5109/10990 +f 5108/5110/10991 5111/5113/10994 5109/5111/10992 +f 5078/5080/10960 5109/5111/10992 5112/5114/10995 +f 5078/5080/10960 5112/5114/10995 5110/5112/10993 +f 5107/5109/10990 5110/5112/10993 5089/5091/10972 +f 5110/5112/10993 5087/5089/10970 5089/5091/10972 +f 5064/5066/10945 5113/5115/10996 5101/5103/10984 +f 5064/5066/10945 5101/5103/10984 5114/5116/10997 +f 5114/5116/10997 5101/5103/10984 5098/5100/10981 +f 5114/5116/10997 5098/5100/10981 5115/5117/10998 +f 5115/5117/10998 5098/5100/10981 5116/5118/10999 +f 5113/5115/10996 5105/5107/10988 5101/5103/10984 +f 5116/5118/10999 5098/5100/10981 5097/5099/10980 +f 5109/5111/10992 5111/5113/10994 5117/5119/11000 +f 5109/5111/10992 5117/5119/11000 5112/5114/10995 +f 5110/5112/10993 5112/5114/10995 5118/5120/11001 +f 5110/5112/10993 5118/5120/11001 5087/5089/10970 +f 5088/5090/10971 5087/5089/10970 5119/5121/11002 +f 5075/5077/10957 5072/5074/10954 5111/5113/10994 +f 5112/5114/10995 5117/5119/11000 5120/5122/11003 +f 5112/5114/10995 5120/5122/11003 5118/5120/11001 +f 5119/5121/11002 5087/5089/10970 5121/5123/11004 +f 5072/5074/10954 5073/5075/10955 5122/5124/11005 +f 5122/5124/11005 5073/5075/10955 5064/5066/10945 +f 5122/5124/11005 5064/5066/10945 5123/5125/11006 +f 5122/5124/11005 5123/5125/11006 5124/5126/11007 +f 5124/5126/11007 5125/5127/11008 5120/5122/11003 +f 5120/5122/11003 5125/5127/11008 5118/5120/11001 +f 5118/5120/11001 5125/5127/11008 5126/5128/11009 +f 5118/5120/11001 5126/5128/11009 5121/5123/11004 +f 5121/5123/11004 5126/5128/11009 5090/5092/10973 +f 5073/5075/10955 5069/5071/10950 5064/5066/10945 +f 5124/5126/11007 5123/5125/11006 5125/5127/11008 +f 5125/5127/11008 5115/5117/10998 5126/5128/11009 +f 5090/5092/10973 5126/5128/11009 5095/5097/10978 +f 5095/5097/10978 5126/5128/11009 5093/5095/10976 +f 5064/5066/10945 5066/5068/10947 5113/5115/10996 +f 5126/5128/11009 5115/5117/10998 5116/5118/10999 +f 5126/5128/11009 5116/5118/10999 5093/5095/10976 +f 5093/5095/10976 5116/5118/10999 5127/5129/11010 +f 5111/5113/10994 5072/5074/10954 5122/5124/11005 +f 5111/5113/10994 5122/5124/11005 5117/5119/11000 +f 5087/5089/10970 5118/5120/11001 5121/5123/11004 +f 5119/5121/11002 5121/5123/11004 5092/5094/10975 +f 5117/5119/11000 5122/5124/11005 5124/5126/11007 +f 5117/5119/11000 5124/5126/11007 5120/5122/11003 +f 5121/5123/11004 5090/5092/10973 5092/5094/10975 +f 5123/5125/11006 5064/5066/10945 5114/5116/10997 +f 5123/5125/11006 5114/5116/10997 5125/5127/11008 +f 5125/5127/11008 5114/5116/10997 5115/5117/10998 +f 5128/5130/11011 4724/4726/10203 4722/4724/10201 +f 5128/5130/11011 4722/4724/10201 5129/5131/11012 +f 5130/5132/11013 4728/4730/11014 5131/5133/11015 +f 5130/5132/11013 5131/5133/11015 5132/5134/11016 +f 4722/4724/10201 5133/5135/11017 5129/5131/11012 +f 4847/4849/10335 5133/5135/11017 4722/4724/10201 +f 4848/4850/10336 5134/5136/11018 5133/5135/11017 +f 4848/4850/10336 5133/5135/11017 4847/4849/10335 +f 4848/4850/10336 5135/5137/11019 5134/5136/11018 +f 5135/5137/11019 4848/4850/10336 4850/4852/10338 +f 4850/4852/10338 5136/5138/11020 5135/5137/11019 +f 5136/5138/11020 4850/4852/10338 4852/4854/10340 +f 5137/5139/11021 4913/4915/10526 4916/4918/10529 +f 5137/5139/11021 4916/4918/10529 5138/5140/11022 +f 4916/4918/10529 5139/5141/11023 5138/5140/11022 +f 4917/4919/10530 5139/5141/11023 4916/4918/10529 +f 5139/5141/11023 4917/4919/10530 5140/5142/11024 +f 5140/5142/11024 4917/4919/10530 4919/4921/10532 +f 5140/5142/11024 4919/4921/10532 5141/5143/11025 +f 4922/4924/10535 5142/5144/11026 4919/4921/10532 +f 4919/4921/10532 5142/5144/11026 5141/5143/11025 +f 4925/4927/10538 5084/5086/11027 5143/5145/11028 +f 5084/5086/11027 4925/4927/10538 4926/4928/10539 +f 4926/4928/10539 5079/5081/11029 5084/5086/11027 +f 4728/4730/10662 5079/5081/11029 4926/4928/10539 +f 4728/4730/10662 5130/5132/11030 5079/5081/11029 +f 5144/5146/11031 5103/5105/11032 5145/5147/11033 +f 5144/5146/11031 5082/5084/11034 5103/5105/11032 +f 5082/5084/11035 5144/5146/11036 5146/5148/11037 +f 5082/5084/11035 5146/5148/11037 5081/5083/11038 +f 5147/5149/11039 5085/5087/11040 5146/5148/11041 +f 5146/5148/11041 5085/5087/11040 5081/5083/11042 +f 5145/5147/11043 5103/5105/11044 5147/5149/11045 +f 5147/5149/11045 5103/5105/11044 5085/5087/11046 +f 5148/5150/11047 5070/5072/11047 5068/5070/11047 +f 5148/5150/11048 5149/5151/11048 5070/5072/11048 +f 5070/5072/11049 5149/5151/11049 5073/5075/11049 +f 5073/5075/11050 5149/5151/11051 5069/5071/11052 +f 5069/5071/11052 5149/5151/11051 5150/5152/11053 +f 5069/5071/11054 5150/5152/11055 5067/5069/11056 +f 5067/5069/11056 5150/5152/11055 5151/5153/11057 +f 5067/5069/11058 5151/5153/11059 5068/5070/11060 +f 5148/5150/11061 5068/5070/11060 5151/5153/11059 +f 5152/5154/11062 5153/5155/11063 5154/5156/11064 +f 5155/5157/11065 5156/5158/11066 5157/5159/11067 +f 5156/5158/11068 5158/5160/11069 5157/5159/11070 +f 5159/5161/11071 5158/5160/11069 5156/5158/11068 +f 4852/4854/10340 5160/5162/11072 5136/5138/11020 +f 5160/5162/11072 4852/4854/10340 5152/5154/11062 +f 5160/5162/11072 5152/5154/11062 5154/5156/11064 +f 4913/4915/10526 5161/5163/11073 5152/5154/11062 +f 5152/5154/11062 5161/5163/11073 5153/5155/11063 +f 4913/4915/10526 5137/5139/11021 5161/5163/11073 +f 5162/5164/11074 5132/5134/11016 5131/5133/11015 +f 5162/5164/11074 5131/5133/11015 5155/5157/11065 +f 5155/5157/11065 5131/5133/11015 5156/5158/11066 +f 4724/4726/10203 5163/5165/11075 5159/5161/11076 +f 5159/5161/11076 5163/5165/11075 5158/5160/11077 +f 4724/4726/10203 5128/5130/11011 5163/5165/11075 +f 5140/5142/11024 5100/5102/10983 5102/5104/10985 +f 5140/5142/11024 5102/5104/10985 5139/5141/11023 +f 5102/5104/10985 5105/5107/10988 5137/5139/11021 +f 5100/5102/10983 5140/5142/11024 5099/5101/10982 +f 5099/5101/10982 5141/5143/11025 5096/5098/10979 +f 5137/5139/11021 5138/5140/11022 5102/5104/10985 +f 5138/5140/11022 5139/5141/11023 5102/5104/10985 +f 5140/5142/11024 5141/5143/11025 5099/5101/10982 +f 5141/5143/11025 5142/5144/11026 5096/5098/10979 +f 5137/5139/11021 5105/5107/10988 5161/5163/11073 +f 5161/5163/11073 5105/5107/10988 5153/5155/11078 +f 5154/5156/11079 5153/5155/11079 5105/5107/11079 +f 5154/5156/11080 5105/5107/11080 5113/5115/11080 +f 5154/5156/11064 5113/5115/10996 5160/5162/11072 +f 5160/5162/11072 5113/5115/10996 5066/5068/10947 +f 5160/5162/11072 5066/5068/10947 5136/5138/11020 +f 5071/5073/10952 5065/5067/10946 5068/5070/11081 +f 5075/5077/10957 5129/5131/11012 5074/5076/10956 +f 5074/5076/10956 5129/5131/11012 5133/5135/11017 +f 5071/5073/10952 5133/5135/11017 5134/5136/11018 +f 5071/5073/10952 5134/5136/11018 5065/5067/10946 +f 5134/5136/11018 5135/5137/11019 5065/5067/10946 +f 5065/5067/10946 5136/5138/11020 5066/5068/10947 +f 5136/5138/11020 5065/5067/10946 5135/5137/11019 +f 5071/5073/10952 5074/5076/10956 5133/5135/11017 +f 5129/5131/11012 5075/5077/10957 5128/5130/11011 +f 5075/5077/10957 5111/5113/11082 5158/5160/11083 +f 5158/5160/11083 5163/5165/11075 5075/5077/10957 +f 5075/5077/10957 5163/5165/11075 5128/5130/11011 +f 5157/5159/11084 5158/5160/11083 5111/5113/11082 +f 5108/5110/11085 5157/5159/11084 5111/5113/11082 +f 5155/5157/11086 5157/5159/11084 5108/5110/11085 +f 5155/5157/11086 5108/5110/11085 5077/5079/11087 +f 5162/5164/11074 5077/5079/11087 5132/5134/11016 +f 5155/5157/11086 5077/5079/11087 5162/5164/11074 +f 5080/5082/10962 5130/5132/11030 5076/5078/10958 +f 5132/5134/11016 5077/5079/11087 5076/5078/10958 +f 5132/5134/11016 5076/5078/10958 5130/5132/11030 +f 5079/5081/11029 5130/5132/11030 5080/5082/10962 +f 5079/5081/11029 5081/5083/11088 5084/5086/11027 +f 5164/5166/11089 5165/5167/11090 5166/5168/11091 +f 5061/5063/10841 5167/5169/11092 4941/4943/10839 +f 4941/4943/10839 5167/5169/11092 5168/5170/11093 +f 5169/5171/11094 4944/4946/10843 5170/5172/11095 +f 5170/5172/11095 4944/4946/10843 5062/5064/10846 +f 5062/5064/10846 5171/5173/11096 5170/5172/11095 +f 5063/5065/10848 5171/5173/11096 5062/5064/10846 +f 5063/5065/10848 5172/5174/11097 5171/5173/11096 +f 5172/5174/11097 5063/5065/10848 5164/5166/11089 +f 5164/5166/11089 5063/5065/10848 5060/5062/10835 +f 5164/5166/11089 5060/5062/10835 5165/5167/11090 +f 5167/5169/11092 5061/5063/10841 4925/4927/10944 +f 4925/4927/10944 5143/5145/11098 5167/5169/11092 +f 5091/5093/11099 5173/5175/11100 5094/5096/11101 +f 5094/5096/11102 5173/5175/11103 5174/5176/11104 +f 5094/5096/11102 5174/5176/11104 5095/5097/11105 +f 5095/5097/11106 5174/5176/11106 5175/5177/11106 +f 5095/5097/11107 5175/5177/11108 5090/5092/11109 +f 5090/5092/11109 5175/5177/11108 5176/5178/11110 +f 5090/5092/11111 5176/5178/11112 5091/5093/11113 +f 5091/5093/11113 5176/5178/11112 5177/5179/11114 +f 5173/5175/11100 5091/5093/11099 5177/5179/11115 +f 4942/4944/11116 5178/5180/11117 5179/5181/11118 +f 4939/4941/11119 5180/5182/11120 5181/5183/11121 +f 4939/4941/11122 5182/5184/11123 5180/5182/11120 +f 4938/4940/11124 5182/5184/11123 4939/4941/11122 +f 4944/4946/10843 5183/5185/11125 4942/4944/11116 +f 4942/4944/11116 5183/5185/11125 5178/5180/11117 +f 4944/4946/10843 5169/5171/11094 5183/5185/11125 +f 4922/4924/10535 5184/5186/11126 5142/5144/11026 +f 4942/4944/11116 5184/5186/11126 4922/4924/10535 +f 5184/5186/11126 4942/4944/11116 5179/5181/11118 +f 4941/4943/10839 5185/5187/11127 4938/4940/11128 +f 4938/4940/11128 5185/5187/11127 5182/5184/11129 +f 5168/5170/11093 5185/5187/11127 4941/4943/10839 +f 5166/5168/11091 5165/5167/11090 5186/5188/11130 +f 4940/4942/11131 5186/5188/11130 5165/5167/11090 +f 5186/5188/11130 4940/4942/11131 4939/4941/11119 +f 5186/5188/11130 4939/4941/11119 5181/5183/11121 +f 5184/5186/11126 5179/5181/11132 5097/5099/10980 +f 5184/5186/11126 5097/5099/10980 5096/5098/10979 +f 5184/5186/11126 5096/5098/10979 5142/5144/11026 +f 5187/5189/11133 5116/5118/10999 5097/5099/10980 +f 5187/5189/11133 5097/5099/10980 5179/5181/11132 +f 5187/5189/11133 5179/5181/11132 5178/5180/11117 +f 5127/5129/11010 5116/5118/10999 5187/5189/11133 +f 5183/5185/11125 5187/5189/11133 5178/5180/11117 +f 5183/5185/11125 5169/5171/11134 5127/5129/11010 +f 5127/5129/11010 5187/5189/11133 5183/5185/11125 +f 5092/5094/10975 5091/5093/11135 5093/5095/10976 +f 5093/5095/10976 5091/5093/11135 5094/5096/10977 +f 5119/5121/11002 5092/5094/10975 5164/5166/11136 +f 5164/5166/11136 5092/5094/10975 5172/5174/11097 +f 5172/5174/11097 5092/5094/10975 5171/5173/11096 +f 5170/5172/11095 5093/5095/10976 5169/5171/11134 +f 5127/5129/11010 5169/5171/11134 5093/5095/10976 +f 5093/5095/10976 5171/5173/11096 5092/5094/10975 +f 5170/5172/11095 5171/5173/11096 5093/5095/10976 +f 5164/5166/11136 5166/5168/11137 5119/5121/11002 +f 5119/5121/11002 5166/5168/11137 5088/5090/10971 +f 5188/5190/11138 5186/5188/11130 5181/5183/11121 +f 5166/5168/11137 5186/5188/11130 5188/5190/11138 +f 5166/5168/11137 5188/5190/11138 5088/5090/10971 +f 5089/5091/11139 5088/5090/10971 5188/5190/11138 +f 5089/5091/11139 5188/5190/11138 5180/5182/11120 +f 5180/5182/11120 5188/5190/11138 5181/5183/11121 +f 5089/5091/11140 5189/5191/11140 5107/5109/11140 +f 5180/5182/11120 5182/5184/11123 5189/5191/11141 +f 5180/5182/11120 5189/5191/11141 5089/5091/11139 +f 5190/5192/11142 5107/5109/10990 5189/5191/11143 +f 5185/5187/11127 5168/5170/11093 5190/5192/11142 +f 5190/5192/11142 5168/5170/11093 5107/5109/10990 +f 5182/5184/11123 5185/5187/11127 5189/5191/11141 +f 5189/5191/11141 5185/5187/11127 5190/5192/11142 +f 5167/5169/11092 5104/5106/10987 5168/5170/11093 +f 5104/5106/10987 5107/5109/10990 5168/5170/11093 +f 5104/5106/10987 5167/5169/11092 5086/5088/10969 +f 5167/5169/11092 5143/5145/11098 5086/5088/10969 +f 5086/5088/10969 5143/5145/11098 5084/5086/10966 +f 5165/5167/11144 5060/5062/11144 4940/4942/11144 +f 5191/5193/11145 5192/5194/11146 5193/5195/11147 +f 5194/5196/528 5195/5197/528 5196/5198/528 +f 5197/5199/528 5198/5200/528 5199/5201/528 +f 5191/5193/11145 5200/5202/11148 5192/5194/11146 +f 5192/5194/11146 5200/5202/11148 5201/5203/11149 +f 5193/5195/11150 5202/5204/11151 5191/5193/11152 +f 5198/5200/528 5194/5196/528 5199/5201/528 +f 5195/5197/528 5194/5196/528 5198/5200/528 +f 5203/5205/11153 5202/5204/11154 5204/5206/11155 +f 5202/5204/11154 5203/5205/11153 5200/5202/11148 +f 5204/5206/11156 5202/5204/11151 5193/5195/11150 +f 5200/5202/11148 5203/5205/11153 5205/5207/11157 +f 5206/5208/528 5199/5201/528 5196/5198/528 +f 5201/5203/11149 5200/5202/11148 5205/5207/11157 +f 5201/5203/11149 5205/5207/11157 5207/5209/11158 +f 5207/5209/11159 5205/5207/11160 5208/5210/11161 +f 5208/5210/11162 5205/5207/11163 5209/5211/11164 +f 5208/5210/11162 5209/5211/11164 5210/5212/11165 +f 5211/5213/528 5206/5208/528 5196/5198/528 +f 5211/5213/528 5196/5198/528 5195/5197/528 +f 5212/5214/528 5213/5215/528 5214/5216/528 +f 5208/5210/11162 5210/5212/11165 5212/5214/528 +f 5212/5214/528 5210/5212/11165 5213/5215/528 +f 5214/5216/528 5213/5215/528 5215/5217/528 +f 5206/5208/528 5211/5213/528 5214/5216/528 +f 5206/5208/528 5214/5216/528 5215/5217/528 +f 5204/5206/11166 5193/5195/11166 5216/5218/11166 +f 5203/5205/11167 5204/5206/11168 5216/5218/11169 +f 5192/5194/11170 5217/5219/11171 5218/5220/11172 +f 5192/5194/11170 5218/5220/11172 5193/5195/11173 +f 5203/5205/11167 5216/5218/11169 5217/5219/11174 +f 5219/5221/98 5220/5222/98 5221/5223/98 +f 5222/5224/98 5223/5225/98 5224/5226/98 +f 5193/5195/11173 5218/5220/11172 5216/5218/11175 +f 5217/5219/11176 5225/5227/11176 5203/5205/11176 +f 5220/5222/98 5219/5221/98 5224/5226/98 +f 5219/5221/98 5221/5223/98 5226/5228/98 +f 5217/5219/11171 5192/5194/11170 5227/5229/11177 +f 5225/5227/11178 5207/5209/11179 5209/5211/11180 +f 5217/5219/11171 5227/5229/11177 5225/5227/11178 +f 5227/5229/11177 5207/5209/11179 5225/5227/11178 +f 5209/5211/11180 5207/5209/11179 5228/5230/11181 +f 5209/5211/11180 5228/5230/11181 5229/5231/11182 +f 5229/5231/11182 5228/5230/11181 5230/5232/98 +f 5230/5232/98 5228/5230/11181 5231/5233/98 +f 5226/5228/98 5232/5234/98 5222/5224/98 +f 5219/5221/98 5226/5228/98 5222/5224/98 +f 5230/5232/98 5231/5233/98 5232/5234/98 +f 5230/5232/98 5232/5234/98 5226/5228/98 +f 5195/5197/11183 5223/5225/11183 5222/5224/11183 +f 5195/5197/11184 5222/5224/11184 5211/5213/11184 +f 5211/5213/11185 5222/5224/11185 5232/5234/11185 +f 5211/5213/11186 5232/5234/11186 5214/5216/11186 +f 5214/5216/11187 5232/5234/11187 5231/5233/11187 +f 5214/5216/11188 5231/5233/11188 5212/5214/11188 +f 5212/5214/11189 5231/5233/11189 5228/5230/11189 +f 5212/5214/11190 5228/5230/11190 5208/5210/11190 +f 5208/5210/11161 5228/5230/11191 5207/5209/11159 +f 5207/5209/11192 5227/5229/11192 5201/5203/11192 +f 5201/5203/11193 5227/5229/11193 5192/5194/11193 +f 5203/5205/11194 5225/5227/11194 5205/5207/11194 +f 5205/5207/11195 5225/5227/11195 5209/5211/11195 +f 5209/5211/11196 5229/5231/11196 5210/5212/11196 +f 5210/5212/11197 5229/5231/11198 5230/5232/11199 +f 5210/5212/11197 5230/5232/11199 5213/5215/11200 +f 5213/5215/11201 5230/5232/11201 5215/5217/11201 +f 5215/5217/11202 5230/5232/11202 5226/5228/11202 +f 5215/5217/11203 5226/5228/11203 5206/5208/11203 +f 5206/5208/11204 5226/5228/11204 5221/5223/11204 +f 5206/5208/11205 5221/5223/11205 5199/5201/11205 +f 5197/5199/11206 5199/5201/11206 5220/5222/11206 +f 5220/5222/11207 5199/5201/11207 5221/5223/11207 +f 5197/5199/11208 5220/5222/11208 5198/5200/11208 +f 5198/5200/11209 5220/5222/11209 5224/5226/11209 +f 5195/5197/11210 5198/5200/11210 5223/5225/11210 +f 5223/5225/11211 5198/5200/11211 5224/5226/11211 +f 5202/5204/11212 5216/5218/11212 5191/5193/11212 +f 5191/5193/11213 5216/5218/11213 5218/5220/11213 +f 5191/5193/11214 5218/5220/11214 5200/5202/11214 +f 5200/5202/11215 5218/5220/11215 5217/5219/11215 +f 5200/5202/11216 5217/5219/11216 5202/5204/11216 +f 5202/5204/11217 5217/5219/11217 5216/5218/11217 +f 5194/5196/11218 5222/5224/11218 5224/5226/11218 +f 5194/5196/11219 5224/5226/11219 5199/5201/11219 +f 5199/5201/11220 5224/5226/11220 5219/5221/11220 +f 5199/5201/11221 5219/5221/11221 5196/5198/11221 +f 5196/5198/11222 5219/5221/11222 5222/5224/11222 +f 5196/5198/11223 5222/5224/11223 5194/5196/11223 +f 5233/5235/11224 5234/5236/11225 5235/5237/11226 +f 5235/5237/11226 5234/5236/11225 5236/5238/11227 +f 5237/5239/11228 5235/5237/11228 5238/5240/11228 +f 5239/5241/11229 5234/5236/11225 5233/5235/11224 +f 5233/5235/11224 5237/5239/11230 5240/5242/11231 +f 5233/5235/11224 5240/5242/11231 5239/5241/11229 +f 5241/5243/11232 5242/5244/11233 5243/5245/11234 +f 5244/5246/11235 5245/5247/11236 5246/5248/11237 +f 5244/5246/11235 5246/5248/11237 5241/5243/11238 +f 5246/5248/11239 5247/5249/11240 5241/5243/11241 +f 5241/5243/11241 5247/5249/11240 5242/5244/11242 +f 5242/5244/11243 5247/5249/11244 5248/5250/11245 +f 5242/5244/11243 5248/5250/11245 5243/5245/11246 +f 5243/5245/11247 5248/5250/11248 5245/5247/11249 +f 5243/5245/11247 5245/5247/11249 5244/5246/11250 +f 5248/5250/11251 5249/5251/11252 5250/5252/11253 +f 5248/5250/11251 5250/5252/11253 5245/5247/11254 +f 5251/5253/11255 5252/5254/11256 5247/5249/11257 +f 5246/5248/11258 5251/5253/11255 5247/5249/11257 +f 5245/5247/11254 5250/5252/11253 5253/5255/11259 +f 5247/5249/11257 5252/5254/11256 5248/5250/11251 +f 5248/5250/11251 5252/5254/11256 5249/5251/11252 +f 5245/5247/11254 5253/5255/11259 5246/5248/11258 +f 5246/5248/11258 5253/5255/11259 5251/5253/11255 +f 5250/5252/11260 5236/5238/11261 5234/5236/11262 +f 5250/5252/11260 5234/5236/11262 5253/5255/11263 +f 5234/5236/11264 5239/5241/11265 5253/5255/11266 +f 5253/5255/11266 5239/5241/11265 5251/5253/11267 +f 5239/5241/11268 5240/5242/11268 5251/5253/11268 +f 5240/5242/11269 5237/5239/11270 5251/5253/11271 +f 5251/5253/11271 5237/5239/11270 5252/5254/11272 +f 5237/5239/11273 5238/5240/11274 5252/5254/11275 +f 5252/5254/11275 5238/5240/11274 5249/5251/11276 +f 5249/5251/11277 5238/5240/11277 5235/5237/11277 +f 5249/5251/11278 5235/5237/11279 5250/5252/11280 +f 5250/5252/11280 5235/5237/11279 5236/5238/11281 +f 5237/5239/11282 5233/5235/11282 5254/5256/11282 +f 5254/5256/11283 5233/5235/11283 5255/5257/11283 +f 5235/5237/11284 5237/5239/11284 5254/5256/11284 +f 5233/5235/11285 5235/5237/11285 5255/5257/11285 +f 5255/5257/11286 5235/5237/11286 5254/5256/11286 +f 5244/5246/11287 5241/5243/11232 5243/5245/11234 +f 5256/5258/11288 5257/5259/11289 5258/5260/11290 +f 5259/5261/11291 5260/5262/11292 5261/5263/11293 +f 5256/5258/11288 5258/5260/11290 5260/5262/11292 +f 5256/5258/11288 5260/5262/11292 5259/5261/11291 +f 5262/5264/11294 5263/5265/11295 5257/5259/11289 +f 5262/5264/11294 5257/5259/11289 5256/5258/11288 +f 5259/5261/11291 5261/5263/11293 5262/5264/11294 +f 5262/5264/11294 5261/5263/11293 5263/5265/11295 +f 5264/5266/11296 5265/5267/11297 5266/5268/11298 +f 5266/5268/11298 5267/5269/11299 5264/5266/11296 +f 5268/5270/11300 5266/5268/11300 5269/5271/11300 +f 5269/5271/11301 5266/5268/11302 5265/5267/11303 +f 5269/5271/11301 5265/5267/11303 5270/5272/11304 +f 5270/5272/11305 5265/5267/11306 5264/5266/11307 +f 5270/5272/11305 5264/5266/11307 5271/5273/11308 +f 5271/5273/11309 5264/5266/11310 5267/5269/11311 +f 5271/5273/11309 5267/5269/11311 5272/5274/11312 +f 5272/5274/11313 5267/5269/11314 5266/5268/11315 +f 5272/5274/11313 5266/5268/11315 5268/5270/11316 +f 5269/5271/11317 5273/5275/11318 5274/5276/11319 +f 5269/5271/11317 5274/5276/11319 5268/5270/11320 +f 5268/5270/11320 5274/5276/11319 5275/5277/11321 +f 5268/5270/11320 5275/5277/11321 5272/5274/11322 +f 5272/5274/11322 5275/5277/11321 5276/5278/11323 +f 5272/5274/11322 5276/5278/11323 5271/5273/11324 +f 5271/5273/11324 5276/5278/11323 5270/5272/11325 +f 5270/5272/11325 5276/5278/11323 5277/5279/11326 +f 5270/5272/11325 5277/5279/11326 5273/5275/11318 +f 5270/5272/11325 5273/5275/11318 5269/5271/11317 +f 5258/5260/11327 5274/5276/11328 5260/5262/11329 +f 5260/5262/11329 5274/5276/11328 5273/5275/11330 +f 5260/5262/11331 5273/5275/11332 5277/5279/11333 +f 5260/5262/11331 5277/5279/11333 5261/5263/11334 +f 5261/5263/11335 5277/5279/11336 5276/5278/11337 +f 5261/5263/11335 5276/5278/11337 5263/5265/11338 +f 5263/5265/11339 5276/5278/11340 5275/5277/11341 +f 5263/5265/11339 5275/5277/11341 5257/5259/11342 +f 5257/5259/11343 5275/5277/11344 5274/5276/11345 +f 5257/5259/11343 5274/5276/11345 5258/5260/11346 +f 5259/5261/11347 5262/5264/11348 5278/5280/11349 +f 5278/5280/11349 5262/5264/11348 5279/5281/11350 +f 5256/5258/11351 5259/5261/11352 5280/5282/11353 +f 5280/5282/11353 5259/5261/11352 5278/5280/11354 +f 5262/5264/9697 5256/5258/9698 5279/5281/9699 +f 5279/5281/9699 5256/5258/9698 5280/5282/9700 +f 5279/5281/528 5280/5282/528 5278/5280/528 +f 5281/5283/11355 5282/5284/11356 5283/5285/11357 +f 5284/5286/11358 5285/5287/11359 5286/5288/11360 +f 5285/5287/11359 5287/5289/11361 5286/5288/11360 +f 5285/5287/11359 5288/5290/11362 5287/5289/11361 +f 5289/5291/528 5287/5289/11361 5288/5290/11362 +f 5290/5292/528 5286/5288/11360 5289/5291/528 +f 5290/5292/528 5289/5291/528 5288/5290/11362 +f 5291/5293/11363 5292/5294/11364 5293/5295/11365 +f 5293/5295/11365 5292/5294/11364 5282/5284/528 +f 5292/5294/11366 5291/5293/11367 5294/5296/11368 +f 5284/5286/11358 5286/5288/11360 5295/5297/11369 +f 5283/5285/528 5292/5294/528 5294/5296/11370 +f 5283/5285/528 5294/5296/11370 5296/5298/11371 +f 5296/5298/11371 5294/5296/11370 5297/5299/11372 +f 5296/5298/11371 5297/5299/11372 5298/5300/11373 +f 5299/5301/11374 5295/5297/11369 5286/5288/11360 +f 5299/5301/11374 5286/5288/11360 5290/5292/528 +f 5297/5299/11372 5300/5302/11375 5298/5300/11373 +f 5298/5300/11373 5300/5302/11375 5301/5303/11376 +f 5301/5303/11376 5300/5302/11375 5302/5304/11377 +f 5301/5303/11376 5302/5304/11377 5303/5305/11378 +f 5301/5303/11376 5303/5305/11378 5299/5301/11374 +f 5299/5301/11374 5303/5305/11378 5295/5297/11369 +f 5304/5306/11379 5305/5307/11380 5306/5308/11381 +f 5291/5293/11382 5304/5306/11379 5306/5308/11381 +f 5307/5309/11383 5308/5310/98 5309/5311/98 +f 5281/5283/11384 5310/5312/11385 5311/5313/11386 +f 5281/5283/11384 5311/5313/11386 5305/5307/11380 +f 5309/5311/98 5308/5310/98 5312/5314/98 +f 5291/5293/11382 5306/5308/11381 5310/5312/11387 +f 5308/5310/98 5307/5309/11383 5313/5315/11388 +f 5305/5307/11380 5311/5313/11386 5306/5308/11381 +f 5310/5312/11387 5314/5316/11389 5291/5293/11382 +f 5285/5287/11390 5312/5314/11391 5313/5315/11392 +f 5310/5312/11385 5281/5283/11384 5315/5317/11393 +f 5314/5316/11394 5315/5317/11393 5297/5299/11395 +f 5310/5312/11385 5315/5317/11393 5314/5316/11394 +f 5297/5299/11395 5315/5317/11393 5316/5318/11396 +f 5297/5299/11395 5316/5318/11396 5317/5319/11397 +f 5317/5319/11397 5316/5318/11396 5318/5320/11398 +f 5317/5319/11397 5318/5320/11398 5319/5321/11399 +f 5319/5321/11399 5318/5320/11398 5303/5305/11400 +f 5320/5322/11401 5321/5323/11402 5309/5311/98 +f 5312/5314/98 5320/5322/11401 5309/5311/98 +f 5303/5305/11400 5318/5320/11398 5321/5323/11402 +f 5303/5305/11400 5321/5323/11402 5320/5322/11401 +f 5290/5292/11403 5307/5309/11403 5309/5311/11403 +f 5290/5292/11404 5309/5311/11404 5299/5301/11404 +f 5299/5301/11405 5309/5311/11405 5321/5323/11405 +f 5299/5301/11406 5321/5323/11406 5301/5303/11406 +f 5301/5303/11407 5321/5323/11407 5318/5320/11407 +f 5301/5303/11408 5318/5320/11408 5298/5300/11408 +f 5298/5300/11409 5318/5320/11409 5316/5318/11409 +f 5298/5300/11410 5316/5318/11410 5296/5298/11410 +f 5296/5298/11411 5316/5318/11411 5315/5317/11411 +f 5296/5298/11412 5315/5317/11412 5283/5285/11412 +f 5283/5285/11357 5315/5317/11413 5281/5283/11355 +f 5282/5284/11356 5281/5283/11355 5305/5307/11414 +f 5282/5284/11415 5305/5307/11415 5293/5295/11415 +f 5293/5295/11416 5305/5307/11416 5304/5306/11416 +f 5291/5293/11417 5293/5295/11417 5304/5306/11417 +f 5291/5293/11367 5314/5316/11418 5294/5296/11368 +f 5294/5296/11419 5314/5316/11419 5297/5299/11419 +f 5300/5302/11420 5297/5299/11420 5317/5319/11420 +f 5300/5302/11421 5317/5319/11421 5302/5304/11421 +f 5302/5304/11422 5317/5319/11422 5319/5321/11422 +f 5302/5304/11423 5319/5321/11423 5303/5305/11423 +f 5295/5297/11424 5303/5305/11424 5320/5322/11424 +f 5295/5297/11425 5320/5322/11425 5284/5286/11425 +f 5284/5286/11426 5320/5322/11426 5312/5314/11426 +f 5285/5287/11390 5284/5286/11427 5312/5314/11391 +f 5285/5287/11428 5313/5315/11428 5288/5290/11428 +f 5290/5292/11429 5288/5290/11429 5307/5309/11429 +f 5307/5309/11383 5288/5290/11430 5313/5315/11388 +f 5292/5294/11431 5306/5308/11431 5282/5284/11431 +f 5282/5284/11432 5306/5308/11432 5311/5313/11432 +f 5282/5284/11433 5311/5313/11433 5283/5285/11433 +f 5283/5285/11434 5311/5313/11434 5310/5312/11434 +f 5283/5285/11435 5310/5312/11435 5292/5294/11435 +f 5292/5294/11436 5310/5312/11436 5306/5308/11436 +f 5289/5291/11437 5308/5310/11437 5313/5315/11437 +f 5289/5291/11438 5313/5315/11438 5287/5289/11438 +f 5287/5289/11439 5313/5315/11439 5312/5314/11439 +f 5287/5289/11440 5312/5314/11440 5286/5288/11440 +f 5286/5288/11441 5312/5314/11441 5308/5310/11441 +f 5286/5288/11442 5308/5310/11442 5289/5291/11442 +f 5322/5324/11443 5323/5325/11444 5324/5326/11445 +f 5325/5327/11446 5326/5328/11447 5327/5329/11448 +f 5328/5330/11449 5329/5331/11450 5325/5327/11446 +f 5325/5327/11446 5329/5331/11450 5322/5324/11451 +f 5327/5329/11448 5328/5330/11449 5325/5327/11446 +f 5324/5326/11445 5323/5325/11444 5330/5332/11452 +f 5330/5332/11452 5331/5333/11453 5324/5326/11445 +f 5324/5326/11445 5331/5333/11453 5326/5328/11454 +f 5332/5334/11455 5333/5335/11456 5334/5336/11457 +f 5335/5337/11458 5336/5338/11459 5334/5336/11457 +f 5333/5335/11456 5335/5337/11458 5334/5336/11457 +f 5337/5339/11460 5332/5334/11460 5338/5340/11460 +f 5338/5340/11461 5332/5334/11461 5339/5341/11461 +f 5338/5340/11462 5339/5341/11463 5340/5342/11464 +f 5340/5342/11464 5339/5341/11463 5334/5336/11465 +f 5340/5342/11466 5334/5336/11466 5336/5338/11466 +f 5340/5342/11467 5336/5338/11468 5341/5343/11469 +f 5341/5343/11469 5336/5338/11468 5335/5337/11470 +f 5341/5343/11471 5335/5337/11472 5333/5335/11473 +f 5341/5343/11471 5333/5335/11473 5337/5339/11474 +f 5337/5339/11475 5333/5335/11475 5332/5334/11475 +f 5337/5339/11476 5342/5344/11477 5343/5345/11478 +f 5338/5340/11479 5344/5346/11480 5342/5344/11477 +f 5338/5340/11479 5342/5344/11477 5337/5339/11476 +f 5341/5343/11481 5345/5347/11482 5340/5342/11483 +f 5340/5342/11483 5345/5347/11482 5346/5348/11484 +f 5341/5343/11481 5347/5349/11485 5345/5347/11482 +f 5337/5339/11476 5343/5345/11478 5341/5343/11481 +f 5341/5343/11481 5343/5345/11478 5347/5349/11485 +f 5338/5340/11479 5348/5350/11486 5344/5346/11480 +f 5340/5342/11483 5346/5348/11484 5348/5350/11486 +f 5340/5342/11483 5348/5350/11486 5338/5340/11479 +f 5326/5328/11487 5331/5333/11488 5343/5345/11489 +f 5343/5345/11489 5331/5333/11488 5347/5349/11490 +f 5331/5333/11491 5330/5332/11492 5347/5349/11493 +f 5347/5349/11493 5330/5332/11492 5345/5347/11494 +f 5345/5347/11494 5330/5332/11492 5323/5325/11495 +f 5345/5347/11496 5323/5325/11497 5346/5348/11498 +f 5346/5348/11498 5323/5325/11497 5322/5324/11499 +f 5346/5348/11500 5322/5324/11501 5348/5350/11502 +f 5348/5350/11502 5322/5324/11501 5329/5331/11503 +f 5348/5350/11504 5329/5331/11505 5344/5346/11506 +f 5329/5331/11505 5328/5330/11507 5344/5346/11506 +f 5344/5346/11508 5328/5330/11509 5342/5344/11510 +f 5342/5344/11510 5328/5330/11509 5327/5329/11511 +f 5342/5344/11512 5327/5329/11513 5326/5328/11514 +f 5342/5344/11512 5326/5328/11514 5343/5345/11515 +f 5322/5324/11516 5324/5326/11517 5349/5351/11518 +f 5325/5327/11519 5322/5324/11519 5350/5352/11519 +f 5350/5352/11520 5322/5324/11520 5349/5351/11520 +f 5326/5328/11521 5325/5327/11521 5351/5353/11521 +f 5351/5353/11522 5325/5327/11522 5350/5352/11522 +f 5324/5326/11523 5326/5328/11523 5351/5353/11523 +f 5349/5351/11518 5324/5326/11517 5351/5353/11524 +f 5351/5353/3026 5350/5352/3026 5349/5351/3026 +f 5339/5341/11525 5332/5334/11455 5334/5336/11457 +f 5352/5354/11526 5353/5355/11527 5354/5356/11528 +f 5355/5357/11529 5356/5358/11530 5357/5359/11531 +f 5354/5356/11528 5358/5360/11532 5352/5354/11526 +f 5359/5361/11533 5360/5362/11534 5361/5363/11535 +f 5359/5361/11533 5361/5363/11535 5355/5357/11529 +f 5358/5360/11532 5360/5362/11534 5352/5354/11526 +f 5352/5354/11526 5360/5362/11534 5359/5361/11533 +f 5355/5357/11529 5357/5359/11531 5353/5355/11536 +f 5355/5357/11529 5361/5363/11535 5356/5358/11530 +f 5362/5364/11537 5363/5365/11538 5364/5366/11539 +f 5365/5367/11540 5363/5365/11538 5362/5364/11537 +f 5362/5364/11537 5366/5368/11541 5365/5367/11540 +f 5367/5369/11542 5364/5366/11542 5363/5365/11542 +f 5367/5369/11543 5363/5365/11543 5368/5370/11543 +f 5368/5370/11544 5363/5365/11545 5365/5367/11546 +f 5368/5370/11544 5365/5367/11546 5369/5371/11547 +f 5369/5371/11548 5365/5367/11549 5366/5368/11550 +f 5369/5371/11548 5366/5368/11550 5370/5372/11551 +f 5370/5372/11552 5366/5368/11553 5362/5364/11554 +f 5370/5372/11552 5362/5364/11554 5371/5373/11555 +f 5371/5373/11556 5362/5364/11556 5364/5366/11556 +f 5371/5373/11557 5364/5366/11557 5367/5369/11557 +f 5367/5369/11558 5372/5374/11559 5373/5375/11560 +f 5367/5369/11558 5373/5375/11560 5371/5373/11561 +f 5367/5369/11558 5374/5376/11562 5372/5374/11559 +f 5370/5372/11563 5375/5377/11564 5376/5378/11565 +f 5370/5372/11563 5376/5378/11565 5369/5371/11566 +f 5371/5373/11561 5377/5379/11567 5370/5372/11563 +f 5370/5372/11563 5377/5379/11567 5375/5377/11564 +f 5371/5373/11561 5373/5375/11560 5377/5379/11567 +f 5368/5370/11568 5378/5380/11569 5374/5376/11562 +f 5368/5370/11568 5374/5376/11562 5367/5369/11558 +f 5369/5371/11566 5376/5378/11565 5378/5380/11569 +f 5369/5371/11566 5378/5380/11569 5368/5370/11568 +f 5373/5375/11570 5354/5356/11571 5353/5355/11572 +f 5373/5375/11570 5353/5355/11572 5377/5379/11573 +f 5377/5379/11574 5353/5355/11575 5375/5377/11576 +f 5375/5377/11576 5353/5355/11575 5357/5359/11577 +f 5375/5377/11578 5357/5359/11579 5376/5378/11580 +f 5357/5359/11579 5356/5358/11581 5376/5378/11580 +f 5356/5358/11582 5361/5363/11583 5376/5378/11584 +f 5376/5378/11584 5361/5363/11583 5378/5380/11585 +f 5378/5380/11586 5361/5363/11587 5374/5376/11588 +f 5374/5376/11588 5361/5363/11587 5360/5362/11589 +f 5374/5376/11590 5360/5362/11591 5372/5374/11592 +f 5360/5362/11591 5358/5360/11593 5372/5374/11592 +f 5372/5374/11594 5358/5360/11595 5373/5375/11596 +f 5373/5375/11596 5358/5360/11595 5354/5356/11597 +f 5359/5361/11598 5355/5357/11599 5379/5381/11600 +f 5379/5381/11600 5355/5357/11599 5380/5382/11601 +f 5352/5354/11602 5359/5361/11602 5379/5381/11602 +f 5381/5383/11603 5352/5354/11604 5379/5381/11605 +f 5353/5355/11606 5352/5354/11604 5381/5383/11603 +f 5355/5357/11607 5353/5355/11607 5380/5382/11607 +f 5380/5382/11608 5353/5355/11608 5381/5383/11608 +f 5381/5383/2352 5379/5381/2352 5380/5382/2352 +f 5382/5384/11609 5383/5385/11610 5384/5386/11611 +f 5382/5384/11612 5384/5386/11612 5385/5387/11612 +f 5385/5387/11613 5384/5386/11613 5386/5388/11613 +f 5385/5387/11614 5386/5388/11614 5387/5389/11614 +f 5387/5389/11615 5386/5388/11615 5388/5390/11615 +f 5387/5389/11616 5388/5390/11616 5389/5391/11616 +f 5389/5391/11617 5388/5390/11617 5390/5392/11617 +f 5389/5391/11618 5390/5392/11619 5391/5393/11620 +f 5392/5394/11621 5391/5393/11621 5393/5395/11621 +f 5393/5395/11622 5391/5393/11620 5390/5392/11619 +f 5392/5394/11623 5393/5395/11624 5394/5396/11625 +f 5394/5396/11625 5393/5395/11624 5395/5397/11626 +f 5394/5396/11627 5395/5397/11627 5396/5398/11627 +f 5396/5398/11628 5395/5397/11628 5397/5399/11628 +f 5396/5398/11629 5397/5399/11629 5398/5400/11629 +f 5398/5400/11630 5397/5399/11630 5399/5401/11630 +f 5398/5400/11631 5399/5401/11631 5400/5402/11631 +f 5400/5402/11632 5399/5401/11632 5401/5403/11632 +f 5400/5402/11633 5401/5403/11633 5402/5404/11633 +f 5382/5384/11609 5402/5404/11634 5383/5385/11610 +f 5402/5404/11635 5382/5384/11636 5400/5402/11637 +f 5391/5393/3026 5392/5394/3026 5394/5396/3026 +f 5391/5393/3026 5394/5396/3026 5389/5391/3026 +f 5389/5391/3026 5394/5396/3026 5396/5398/3026 +f 5389/5391/3026 5396/5398/3026 5387/5389/3026 +f 5385/5387/3026 5398/5400/3026 5400/5402/11637 +f 5385/5387/3026 5400/5402/11637 5382/5384/11636 +f 5387/5389/3026 5396/5398/3026 5385/5387/3026 +f 5385/5387/3026 5396/5398/3026 5398/5400/3026 +f 5388/5390/3031 5395/5397/3031 5390/5392/3031 +f 5395/5397/3031 5393/5395/3031 5390/5392/3031 +f 5386/5388/3031 5397/5399/3031 5388/5390/3031 +f 5388/5390/3031 5397/5399/3031 5395/5397/3031 +f 5384/5386/3031 5399/5401/3031 5386/5388/3031 +f 5386/5388/3031 5399/5401/3031 5397/5399/3031 +f 5383/5385/11638 5402/5404/11639 5401/5403/11640 +f 5383/5385/11638 5401/5403/11640 5384/5386/3031 +f 5384/5386/3031 5401/5403/11640 5399/5401/3031 +f 5403/5405/11641 5404/5406/11641 5405/5407/11641 +f 5403/5405/11642 5405/5407/11643 5406/5408/11644 +f 5403/5405/11642 5406/5408/11644 5407/5409/11645 +f 5407/5409/11646 5406/5408/11647 5408/5410/11648 +f 5407/5409/11646 5408/5410/11648 5409/5411/11649 +f 5409/5411/11650 5408/5410/11651 5410/5412/11652 +f 5410/5412/11652 5408/5410/11651 5411/5413/11653 +f 5410/5412/11654 5411/5413/11654 5412/5414/11654 +f 5413/5415/11655 5412/5414/11655 5411/5413/11655 +f 5413/5415/11656 5414/5416/11656 5415/5417/11656 +f 5415/5417/11657 5414/5416/11658 5416/5418/11659 +f 5415/5417/11657 5416/5418/11659 5417/5419/11660 +f 5417/5419/11661 5416/5418/11662 5418/5420/11663 +f 5417/5419/11661 5418/5420/11663 5419/5421/11664 +f 5419/5421/11665 5418/5420/11665 5420/5422/11665 +f 5420/5422/11666 5418/5420/11666 5421/5423/11666 +f 5420/5422/11667 5421/5423/11667 5422/5424/11667 +f 5422/5424/11668 5421/5423/11668 5423/5425/11668 +f 5422/5424/11669 5423/5425/11669 5424/5426/11669 +f 5424/5426/11670 5423/5425/11670 5425/5427/11670 +f 5424/5426/11671 5425/5427/11671 5426/5428/11671 +f 5404/5406/11672 5426/5428/11672 5425/5427/11672 +f 5426/5428/11673 5404/5406/11673 5403/5405/11673 +f 5410/5412/11674 5415/5417/11675 5417/5419/3026 +f 5410/5412/11674 5417/5419/3026 5409/5411/3026 +f 5412/5414/11676 5413/5415/11677 5410/5412/11674 +f 5410/5412/11674 5413/5415/11677 5415/5417/11675 +f 5407/5409/3026 5422/5424/3026 5403/5405/3026 +f 5409/5411/3026 5417/5419/3026 5419/5421/3026 +f 5403/5405/3026 5424/5426/3026 5426/5428/3026 +f 5403/5405/3026 5422/5424/3026 5424/5426/3026 +f 5407/5409/3026 5420/5422/3026 5422/5424/3026 +f 5409/5411/3026 5419/5421/3026 5407/5409/3026 +f 5407/5409/3026 5419/5421/3026 5420/5422/3026 +f 5413/5415/11678 5411/5413/11679 5414/5416/11680 +f 5411/5413/11679 5416/5418/3031 5414/5416/11680 +f 5408/5410/3031 5416/5418/3031 5411/5413/11679 +f 5408/5410/3031 5418/5420/3031 5416/5418/3031 +f 5406/5408/3031 5418/5420/3031 5408/5410/3031 +f 5406/5408/3031 5421/5423/3031 5418/5420/3031 +f 5405/5407/11681 5421/5423/3031 5406/5408/3031 +f 5404/5406/11682 5425/5427/11683 5405/5407/11681 +f 5405/5407/11681 5423/5425/3031 5421/5423/3031 +f 5405/5407/11681 5425/5427/11683 5423/5425/3031 +f 5427/5429/11684 5428/5430/11685 5429/5431/11686 +f 5427/5429/11687 5429/5431/11687 5430/5432/11687 +f 5430/5432/11688 5429/5431/11688 5431/5433/11688 +f 5430/5432/11689 5431/5433/11690 5432/5434/11691 +f 5430/5432/11689 5432/5434/11691 5433/5435/11692 +f 5433/5435/11693 5432/5434/11693 5434/5436/11693 +f 5434/5436/11694 5432/5434/11694 5435/5437/11694 +f 5434/5436/11695 5435/5437/11696 5436/5438/11697 +f 5437/5439/11698 5436/5438/11698 5438/5440/11698 +f 5438/5440/11699 5436/5438/11697 5435/5437/11696 +f 5437/5439/11700 5438/5440/11700 5439/5441/11700 +f 5437/5439/11701 5439/5441/11701 5440/5442/11701 +f 5440/5442/11702 5439/5441/11702 5441/5443/11702 +f 5440/5442/11703 5441/5443/11704 5442/5444/11705 +f 5442/5444/11705 5441/5443/11704 5443/5445/11706 +f 5442/5444/11707 5443/5445/11707 5444/5446/11707 +f 5444/5446/11708 5443/5445/11708 5445/5447/11708 +f 5444/5446/11709 5445/5447/11709 5446/5448/11709 +f 5446/5448/11710 5445/5447/11710 5447/5449/11710 +f 5446/5448/11711 5447/5449/11711 5448/5450/11711 +f 5448/5450/11712 5447/5449/11712 5449/5451/11712 +f 5448/5450/11713 5449/5451/11713 5450/5452/11713 +f 5450/5452/11714 5449/5451/11714 5451/5453/11714 +f 5427/5429/11684 5450/5452/11715 5428/5430/11685 +f 5428/5430/11685 5450/5452/11715 5451/5453/11716 +f 5436/5438/3085 5437/5439/3085 5440/5442/3085 +f 5436/5438/3085 5440/5442/3085 5434/5436/3085 +f 5434/5436/3085 5440/5442/3085 5442/5444/3085 +f 5434/5436/3085 5442/5444/3085 5433/5435/3085 +f 5427/5429/3085 5448/5450/3085 5450/5452/3085 +f 5430/5432/3085 5446/5448/3085 5448/5450/3085 +f 5430/5432/3085 5448/5450/3085 5427/5429/3085 +f 5430/5432/3085 5444/5446/3085 5446/5448/3085 +f 5442/5444/3085 5444/5446/3085 5433/5435/3085 +f 5433/5435/3085 5444/5446/3085 5430/5432/3085 +f 5438/5440/2352 5435/5437/2352 5439/5441/2352 +f 5435/5437/2352 5441/5443/2352 5439/5441/2352 +f 5432/5434/2352 5441/5443/2352 5435/5437/2352 +f 5432/5434/2352 5443/5445/2352 5441/5443/2352 +f 5431/5433/2352 5445/5447/2352 5432/5434/2352 +f 5432/5434/2352 5445/5447/2352 5443/5445/2352 +f 5429/5431/2352 5447/5449/2352 5431/5433/2352 +f 5431/5433/2352 5447/5449/2352 5445/5447/2352 +f 5428/5430/2352 5451/5453/2352 5449/5451/2352 +f 5429/5431/2352 5449/5451/2352 5447/5449/2352 +f 5428/5430/2352 5449/5451/2352 5429/5431/2352 +f 5452/5454/11717 5453/5455/11718 5454/5456/11719 +f 5452/5454/11720 5454/5456/11720 5455/5457/11720 +f 5455/5457/11721 5454/5456/11721 5456/5458/11721 +f 5455/5457/11722 5456/5458/11722 5457/5459/11722 +f 5457/5459/11723 5456/5458/11723 5458/5460/11723 +f 5457/5459/11724 5458/5460/11724 5459/5461/11724 +f 5459/5461/11725 5458/5460/11725 5460/5462/11725 +f 5459/5461/11726 5460/5462/11726 5461/5463/11726 +f 5462/5464/11727 5461/5463/11727 5463/5465/11727 +f 5463/5465/11728 5461/5463/11728 5460/5462/11728 +f 5462/5464/11729 5463/5465/11730 5464/5466/11731 +f 5462/5464/11729 5464/5466/11731 5465/5467/11732 +f 5465/5467/11733 5464/5466/11734 5466/5468/11735 +f 5465/5467/11733 5466/5468/11735 5467/5469/11736 +f 5467/5469/11737 5466/5468/11738 5468/5470/11739 +f 5468/5470/11739 5466/5468/11738 5469/5471/11740 +f 5468/5470/11741 5469/5471/11742 5470/5472/11743 +f 5468/5470/11741 5470/5472/11743 5471/5473/11744 +f 5471/5473/11745 5470/5472/11745 5472/5474/11745 +f 5472/5474/11746 5470/5472/11746 5473/5475/11746 +f 5472/5474/11747 5473/5475/11747 5474/5476/11747 +f 5452/5454/11717 5474/5476/11748 5453/5455/11718 +f 5453/5455/11749 5474/5476/11749 5473/5475/11749 +f 5474/5476/3085 5452/5454/3085 5472/5474/3085 +f 5461/5463/3085 5462/5464/3085 5459/5461/3085 +f 5459/5461/3085 5462/5464/3085 5465/5467/3085 +f 5459/5461/3085 5467/5469/3085 5457/5459/3085 +f 5459/5461/3085 5465/5467/3085 5467/5469/3085 +f 5455/5457/3085 5471/5473/3085 5452/5454/3085 +f 5452/5454/3085 5471/5473/3085 5472/5474/3085 +f 5457/5459/3085 5468/5470/3085 5455/5457/3085 +f 5455/5457/3085 5468/5470/3085 5471/5473/3085 +f 5467/5469/3085 5468/5470/3085 5457/5459/3085 +f 5458/5460/2352 5464/5466/2352 5460/5462/2352 +f 5458/5460/2352 5466/5468/2352 5464/5466/2352 +f 5460/5462/2352 5464/5466/2352 5463/5465/2352 +f 5456/5458/2352 5469/5471/2352 5458/5460/2352 +f 5458/5460/2352 5469/5471/2352 5466/5468/2352 +f 5456/5458/2352 5470/5472/2352 5469/5471/2352 +f 5454/5456/2352 5470/5472/2352 5456/5458/2352 +f 5453/5455/2352 5473/5475/2352 5454/5456/2352 +f 5454/5456/2352 5473/5475/2352 5470/5472/2352 +f 5475/5477/11750 5476/5478/11751 5477/5479/11752 +f 5478/5480/11753 5479/5481/11754 5475/5477/11750 +f 5475/5477/11750 5479/5481/11754 5476/5478/11751 +f 5480/5482/11755 5481/5483/11756 5482/5484/11757 +f 5482/5484/11757 5481/5483/11756 5483/5485/11758 +f 5484/5486/11759 5485/5487/11760 5486/5488/11761 +f 5487/5489/11762 5488/5490/11763 5489/5491/11764 +f 5490/5492/11765 5491/5493/11766 5492/5494/11767 +f 5492/5494/11767 5491/5493/11766 5493/5495/11768 +f 5486/5488/11761 5485/5487/11760 5490/5492/11765 +f 5486/5488/11761 5490/5492/11765 5492/5494/11767 +f 5494/5496/11769 5495/5497/11770 5493/5495/11768 +f 5494/5496/11769 5491/5493/11766 5489/5491/11764 +f 5493/5495/11768 5495/5497/11770 5479/5481/11771 +f 5491/5493/11766 5494/5496/11769 5493/5495/11768 +f 5489/5491/11764 5488/5490/11763 5494/5496/11769 +f 5496/5498/11772 5497/5499/11773 5498/5500/11774 +f 5496/5498/11772 5498/5500/11774 5499/5501/11775 +f 5499/5501/11775 5498/5500/11774 5500/5502/11776 +f 5500/5502/11776 5498/5500/11774 5501/5503/11777 +f 5500/5502/11776 5501/5503/11777 5502/5504/11778 +f 5500/5502/11776 5502/5504/11778 5503/5505/11779 +f 5504/5506/11780 5505/5507/11781 5506/5508/11782 +f 5504/5506/11780 5506/5508/11782 5507/5509/11783 +f 5507/5509/11783 5506/5508/11782 5508/5510/11784 +f 5507/5509/11783 5508/5510/11784 5509/5511/11785 +f 5509/5511/11785 5508/5510/11784 5510/5512/11786 +f 5510/5512/11786 5508/5510/11784 5511/5513/11787 +f 5510/5512/11786 5511/5513/11787 5512/5514/11788 +f 5512/5514/11788 5511/5513/11787 5513/5515/11789 +f 5514/5516/11790 5515/5517/11791 5516/5518/11792 +f 5517/5519/11793 5518/5520/11794 5519/5521/11795 +f 5520/5522/11796 5521/5523/11797 5522/5524/11798 +f 5523/5525/11799 5524/5526/11800 5525/5527/11801 +f 5523/5525/11799 5521/5523/11797 5520/5522/11796 +f 5522/5524/11798 5515/5517/11791 5520/5522/11796 +f 5520/5522/11796 5515/5517/11791 5514/5516/11790 +f 5523/5525/11799 5481/5483/11802 5524/5526/11800 +f 5518/5520/11794 5526/5528/11803 5519/5521/11795 +f 5523/5525/11799 5525/5527/11801 5521/5523/11797 +f 5519/5521/11795 5526/5528/11803 5525/5527/11801 +f 5525/5527/11801 5526/5528/11803 5521/5523/11797 +f 5527/5529/11804 5528/5530/11805 5529/5531/11806 +f 5529/5531/11806 5528/5530/11805 5530/5532/11807 +f 5529/5531/11806 5530/5532/11807 5531/5533/11808 +f 5531/5533/11808 5530/5532/11807 5532/5534/11809 +f 5531/5533/11808 5532/5534/11809 5533/5535/11810 +f 5533/5535/11810 5532/5534/11809 5534/5536/11811 +f 5534/5536/11811 5532/5534/11809 5535/5537/11812 +f 5536/5538/11813 5537/5539/11814 5538/5540/11815 +f 5538/5540/11815 5537/5539/11814 5539/5541/11816 +f 5538/5540/11815 5539/5541/11816 5540/5542/11817 +f 5540/5542/11817 5539/5541/11816 5541/5543/11818 +f 5540/5542/11817 5541/5543/11818 5542/5544/11819 +f 5542/5544/11819 5541/5543/11818 5543/5545/11820 +f 5542/5544/11819 5543/5545/11820 5544/5546/11821 +f 5544/5546/11821 5543/5545/11820 5545/5547/11822 +f 5544/5546/11821 5545/5547/11822 5546/5548/11823 +f 5546/5548/11823 5545/5547/11822 5547/5549/11824 +f 5546/5548/11823 5547/5549/11824 5548/5550/11825 +f 5548/5550/11825 5547/5549/11824 5549/5551/11826 +f 5548/5550/11825 5549/5551/11826 5550/5552/11827 +f 5548/5550/11825 5550/5552/11827 5551/5553/11828 +f 5551/5553/11828 5550/5552/11827 5552/5554/11829 +f 5551/5553/11828 5552/5554/11829 5553/5555/11830 +f 5553/5555/11830 5552/5554/11829 5554/5556/11831 +f 5555/5557/11832 5492/5494/11767 5493/5495/11768 +f 5556/5558/11833 5557/5559/11834 5555/5557/11832 +f 5555/5557/11832 5557/5559/11834 5492/5494/11767 +f 5558/5560/11835 5557/5559/11834 5556/5558/11833 +f 5557/5559/11834 5558/5560/11835 5559/5561/11836 +f 5558/5560/11835 5560/5562/11837 5559/5561/11836 +f 5561/5563/11838 5562/5564/11839 5560/5562/11837 +f 5560/5562/11837 5562/5564/11839 5559/5561/11836 +f 5562/5564/11839 5561/5563/11838 5563/5565/11840 +f 5564/5566/11841 5520/5522/11796 5563/5565/11840 +f 5563/5565/11840 5520/5522/11796 5562/5564/11839 +f 5523/5525/11799 5520/5522/11796 5564/5566/11841 +f 5565/5567/11842 5566/5568/11843 5567/5569/11844 +f 5567/5569/11844 5566/5568/11843 5568/5570/11845 +f 5567/5569/11844 5568/5570/11845 5569/5571/11846 +f 5569/5571/11846 5568/5570/11845 5570/5572/11847 +f 5569/5571/11846 5570/5572/11847 5571/5573/11848 +f 5569/5571/11846 5571/5573/11848 5572/5574/11849 +f 5573/5575/11850 5572/5574/11851 5574/5576/11852 +f 5575/5577/11853 5503/5505/11854 5576/5578/11855 +f 5576/5578/11855 5503/5505/11854 5577/5579/11856 +f 5499/5501/11857 5503/5505/11854 5575/5577/11853 +f 5577/5579/11856 5578/5580/11858 5565/5567/11859 +f 5565/5567/11859 5576/5578/11855 5577/5579/11856 +f 5576/5578/11855 5565/5567/11859 5579/5581/11860 +f 5567/5569/11861 5569/5571/11862 5565/5567/11859 +f 5580/5582/11863 5581/5583/11864 5496/5498/11865 +f 5582/5584/11866 5569/5571/11862 5573/5575/11850 +f 5573/5575/11850 5569/5571/11862 5572/5574/11851 +f 5565/5567/11859 5582/5584/11866 5579/5581/11860 +f 5565/5567/11859 5569/5571/11862 5582/5584/11866 +f 5499/5501/11857 5500/5502/11867 5503/5505/11854 +f 5580/5582/11863 5496/5498/11865 5583/5585/11868 +f 5583/5585/11868 5496/5498/11865 5499/5501/11857 +f 5583/5585/11868 5499/5501/11857 5575/5577/11853 +f 5584/5586/98 5585/5587/98 5586/5588/98 +f 5504/5506/11869 5509/5511/11870 5587/5589/11871 +f 5531/5533/11872 5533/5535/11873 5534/5536/11874 +f 5588/5590/11875 5589/5591/11876 5590/5592/11877 +f 5588/5590/11875 5590/5592/11877 5591/5593/11878 +f 5591/5593/11878 5590/5592/11877 5527/5529/11879 +f 5512/5514/11880 5592/5594/11881 5593/5595/11882 +f 5594/5596/11883 5534/5536/11874 5595/5597/11884 +f 5531/5533/11872 5534/5536/11874 5594/5596/11883 +f 5593/5595/11882 5592/5594/11881 5596/5598/11885 +f 5596/5598/11885 5592/5594/11881 5597/5599/11886 +f 5598/5600/11887 5504/5506/11869 5595/5597/11884 +f 5534/5536/11874 5599/5601/11888 5598/5600/11887 +f 5504/5506/11869 5507/5509/11889 5509/5511/11870 +f 5512/5514/11880 5593/5595/11882 5600/5602/11890 +f 5531/5533/11872 5594/5596/11883 5601/5603/11891 +f 5509/5511/11870 5600/5602/11890 5587/5589/11871 +f 5591/5593/11878 5527/5529/11879 5601/5603/11891 +f 5601/5603/11891 5527/5529/11879 5529/5531/11892 +f 5510/5512/11893 5512/5514/11880 5600/5602/11890 +f 5595/5597/11884 5534/5536/11874 5598/5600/11887 +f 5600/5602/11890 5509/5511/11870 5510/5512/11893 +f 5601/5603/11891 5529/5531/11892 5531/5533/11872 +f 5517/5519/11793 5602/5604/11894 5480/5482/11755 +f 5516/5518/11792 5603/5605/11895 5604/5606/11896 +f 5605/5607/11897 5606/5608/11898 5482/5484/11899 +f 5482/5484/11899 5606/5608/11898 5514/5516/11900 +f 5536/5538/11901 5538/5540/11902 5607/5609/11903 +f 5607/5609/11903 5538/5540/11902 5608/5610/11904 +f 5608/5610/11904 5538/5540/11902 5540/5542/11905 +f 5608/5610/11904 5540/5542/11905 5609/5611/11906 +f 5540/5542/11905 5542/5544/11907 5609/5611/11906 +f 5609/5611/11906 5542/5544/11907 5610/5612/11908 +f 5610/5612/11908 5542/5544/11907 5544/5546/11909 +f 5610/5612/11908 5544/5546/11909 5611/5613/11910 +f 5611/5613/11910 5544/5546/11909 5546/5548/11911 +f 5546/5548/11911 5548/5550/11912 5611/5613/11910 +f 5611/5613/11910 5548/5550/11912 5612/5614/11913 +f 5612/5614/11913 5548/5550/11912 5613/5615/11914 +f 5613/5615/11914 5548/5550/11912 5551/5553/11915 +f 5613/5615/11914 5551/5553/11915 5614/5616/11916 +f 5614/5616/11916 5551/5553/11915 5553/5555/11917 +f 5537/5539/11918 5580/5582/11919 5583/5585/11920 +f 5541/5543/11921 5575/5577/11922 5543/5545/11923 +f 5539/5541/11924 5537/5539/11918 5583/5585/11920 +f 5539/5541/11924 5583/5585/11920 5541/5543/11921 +f 5541/5543/11921 5583/5585/11920 5575/5577/11922 +f 5543/5545/11923 5575/5577/11922 5576/5578/11925 +f 5543/5545/11923 5576/5578/11925 5545/5547/11926 +f 5545/5547/11926 5576/5578/11925 5579/5581/11927 +f 5545/5547/11926 5579/5581/11927 5547/5549/11928 +f 5547/5549/11928 5579/5581/11927 5582/5584/11929 +f 5547/5549/11928 5582/5584/11929 5549/5551/11930 +f 5549/5551/11930 5582/5584/11929 5550/5552/11931 +f 5552/5554/11932 5573/5575/11933 5574/5576/11934 +f 5552/5554/11932 5574/5576/11934 5554/5556/11935 +f 5550/5552/11931 5582/5584/11929 5573/5575/11933 +f 5550/5552/11931 5573/5575/11933 5552/5554/11932 +f 5526/5528/11936 5518/5520/11936 5615/5617/11936 +f 5526/5528/11937 5615/5617/11938 5521/5523/11939 +f 5521/5523/11939 5615/5617/11938 5604/5606/11940 +f 5521/5523/11941 5604/5606/11941 5522/5524/11941 +f 5522/5524/11942 5604/5606/11942 5603/5605/11942 +f 5522/5524/11943 5603/5605/11943 5515/5517/11943 +f 5515/5517/11944 5603/5605/11944 5516/5518/11944 +f 5481/5483/11945 5616/5618/11946 5602/5604/11947 +f 5481/5483/11945 5602/5604/11947 5524/5526/11948 +f 5524/5526/11949 5602/5604/11949 5525/5527/11949 +f 5525/5527/11950 5602/5604/11950 5617/5619/11950 +f 5525/5527/11951 5617/5619/11951 5519/5521/11951 +f 5519/5521/11952 5617/5619/11952 5517/5519/11952 +f 5616/5618/11953 5481/5483/11953 5480/5482/11953 +f 5516/5518/11792 5604/5606/11896 5518/5520/11794 +f 5618/5620/11954 5619/5621/11955 5620/5622/11956 +f 5619/5621/11955 5621/5623/11957 5606/5608/11958 +f 5620/5622/11956 5622/5624/11959 5618/5620/11954 +f 5602/5604/11894 5616/5618/11960 5480/5482/11755 +f 5617/5619/11961 5602/5604/11894 5517/5519/11793 +f 5518/5520/11794 5604/5606/11896 5615/5617/11962 +f 5619/5621/11955 5606/5608/11958 5620/5622/11956 +f 5620/5622/11963 5606/5608/11964 5605/5607/11965 +f 5480/5482/11755 5514/5516/11790 5516/5518/11792 +f 5480/5482/11755 5516/5518/11792 5517/5519/11793 +f 5516/5518/11792 5518/5520/11794 5517/5519/11793 +f 5480/5482/11755 5482/5484/11757 5514/5516/11790 +f 5581/5583/11966 5605/5607/11965 5497/5499/11773 +f 5581/5583/11966 5497/5499/11773 5496/5498/11772 +f 5605/5607/11965 5581/5583/11966 5620/5622/11963 +f 5581/5583/11967 5580/5582/11919 5622/5624/11968 +f 5622/5624/11968 5620/5622/11969 5581/5583/11967 +f 5618/5620/11970 5580/5582/11919 5537/5539/11918 +f 5580/5582/11919 5618/5620/11970 5622/5624/11968 +f 5619/5621/11971 5618/5620/11972 5536/5538/11973 +f 5536/5538/11973 5618/5620/11972 5537/5539/11974 +f 5619/5621/11975 5536/5538/11976 5621/5623/11977 +f 5621/5623/11977 5536/5538/11976 5607/5609/11978 +f 5623/5625/11979 5624/5626/11980 5488/5490/11981 +f 5476/5478/11751 5625/5627/11982 5626/5628/11983 +f 5475/5477/11984 5627/5629/11985 5628/5630/11986 +f 5628/5630/11986 5627/5629/11985 5629/5631/11987 +f 5485/5487/11988 5630/5632/11988 5490/5492/11988 +f 5490/5492/11989 5630/5632/11989 5631/5633/11989 +f 5490/5492/11990 5631/5633/11990 5491/5493/11990 +f 5491/5493/11991 5631/5633/11991 5632/5634/11991 +f 5491/5493/11992 5632/5634/11993 5489/5491/11994 +f 5489/5491/11994 5632/5634/11993 5633/5635/11995 +f 5489/5491/11996 5633/5635/11996 5487/5489/11996 +f 5630/5632/11997 5485/5487/11760 5631/5633/11998 +f 5631/5633/11998 5485/5487/11760 5484/5486/11759 +f 5634/5636/11999 5635/5637/12000 5636/5638/12001 +f 5629/5631/12002 5637/5639/12003 5634/5636/11999 +f 5488/5490/11981 5477/5479/11752 5626/5628/11983 +f 5488/5490/11981 5626/5628/11983 5623/5625/11979 +f 5477/5479/11752 5476/5478/11751 5626/5628/11983 +f 5631/5633/11998 5484/5486/11759 5632/5634/12004 +f 5632/5634/12004 5484/5486/11759 5487/5489/11762 +f 5632/5634/12004 5487/5489/11762 5633/5635/12005 +f 5638/5640/12006 5636/5638/12001 5635/5637/12000 +f 5629/5631/12002 5634/5636/11999 5636/5638/12001 +f 5626/5628/12007 5625/5627/12007 5479/5481/12007 +f 5479/5481/12008 5625/5627/12008 5476/5478/12008 +f 5494/5496/12009 5488/5490/12009 5624/5626/12009 +f 5494/5496/12010 5624/5626/12010 5623/5625/12010 +f 5494/5496/12011 5623/5625/12011 5495/5497/12011 +f 5495/5497/12012 5623/5625/12012 5626/5628/12012 +f 5626/5628/12013 5479/5481/12013 5495/5497/12013 +f 5636/5638/12014 5628/5630/12015 5629/5631/12016 +f 5475/5477/12017 5477/5479/12017 5488/5490/12017 +f 5488/5490/11763 5487/5489/11762 5484/5486/11759 +f 5488/5490/11763 5484/5486/11759 5475/5477/12018 +f 5484/5486/12019 5486/5488/12019 5475/5477/12019 +f 5475/5477/11984 5486/5488/12020 5627/5629/11985 +f 5572/5574/12021 5571/5573/12022 5628/5630/12015 +f 5636/5638/12014 5572/5574/12021 5628/5630/12015 +f 5574/5576/11852 5572/5574/11851 5636/5638/12023 +f 5574/5576/11852 5636/5638/12023 5638/5640/12024 +f 5638/5640/12025 5554/5556/12026 5574/5576/12027 +f 5635/5637/12028 5554/5556/12026 5638/5640/12025 +f 5553/5555/12029 5554/5556/12026 5634/5636/12030 +f 5634/5636/12030 5554/5556/12026 5635/5637/12028 +f 5553/5555/12031 5637/5639/12032 5614/5616/12033 +f 5553/5555/12031 5634/5636/12034 5637/5639/12032 +f 5639/5641/12035 5599/5601/12036 5534/5536/11811 +f 5639/5641/12035 5534/5536/11811 5535/5537/11812 +f 5640/5642/12037 5598/5600/12038 5599/5601/12039 +f 5640/5642/12037 5599/5601/12039 5639/5641/12040 +f 5505/5507/12041 5504/5506/12042 5640/5642/12043 +f 5640/5642/12043 5504/5506/12042 5598/5600/12044 +f 5587/5589/11871 5595/5597/11884 5504/5506/11869 +f 5566/5568/12045 5641/5643/12046 5642/5644/12047 +f 5643/5645/12048 5535/5537/12049 5644/5646/12050 +f 5645/5647/12051 5646/5648/12052 5506/5508/12053 +f 5646/5648/12052 5647/5649/12054 5508/5510/12055 +f 5644/5646/12050 5532/5534/12056 5648/5650/12057 +f 5649/5651/12058 5628/5630/12059 5571/5573/12060 +f 5530/5532/12061 5648/5650/12057 5532/5534/12056 +f 5508/5510/12055 5647/5649/12054 5650/5652/12062 +f 5511/5513/12063 5650/5652/12062 5651/5653/12064 +f 5652/5654/12065 5653/5655/12066 5530/5532/12061 +f 5511/5513/12063 5508/5510/12055 5650/5652/12062 +f 5506/5508/12053 5505/5507/12067 5645/5647/12051 +f 5653/5655/12066 5648/5650/12057 5530/5532/12061 +f 5513/5515/12068 5511/5513/12063 5651/5653/12064 +f 5652/5654/12065 5530/5532/12061 5528/5530/12069 +f 5643/5645/12048 5645/5647/12051 5505/5507/12067 +f 5535/5537/12049 5643/5645/12048 5639/5641/12070 +f 5654/5656/12071 5592/5594/12072 5513/5515/12073 +f 5513/5515/12073 5592/5594/12072 5512/5514/12074 +f 5592/5594/12075 5654/5656/12076 5655/5657/12077 +f 5592/5594/12075 5655/5657/12077 5597/5599/12078 +f 5597/5599/12079 5655/5657/12080 5656/5658/12081 +f 5657/5659/12082 5577/5579/12083 5502/5504/12084 +f 5502/5504/12084 5577/5579/12083 5503/5505/12085 +f 5658/5660/12086 5578/5580/12087 5657/5659/12088 +f 5657/5659/12088 5578/5580/12087 5577/5579/12089 +f 5566/5568/12090 5565/5567/12091 5658/5660/12092 +f 5658/5660/12092 5565/5567/12091 5578/5580/12093 +f 5589/5591/12094 5659/5661/12095 5660/5662/12096 +f 5660/5662/12097 5659/5661/12098 5661/5663/12099 +f 5660/5662/12097 5661/5663/12099 5590/5592/12100 +f 5528/5530/12101 5527/5529/12102 5661/5663/12103 +f 5661/5663/12103 5527/5529/12102 5590/5592/12104 +f 5593/5595/12105 5662/5664/12106 5663/5665/12107 +f 5593/5595/12105 5663/5665/12107 5664/5666/12108 +f 5664/5666/12109 5663/5665/12109 5665/5667/12109 +f 5664/5666/12110 5665/5667/12110 5596/5598/12110 +f 5666/5668/12111 5596/5598/12111 5665/5667/12111 +f 5662/5664/12112 5593/5595/12113 5596/5598/12114 +f 5662/5664/12112 5596/5598/12114 5666/5668/12115 +f 5588/5590/12116 5585/5587/12117 5584/5586/12118 +f 5588/5590/12116 5584/5586/12118 5667/5669/12119 +f 5667/5669/12120 5584/5586/12121 5586/5588/12122 +f 5586/5588/12122 5591/5593/12123 5667/5669/12120 +f 5585/5587/12124 5588/5590/12125 5591/5593/12126 +f 5585/5587/12124 5591/5593/12126 5586/5588/12127 +f 5656/5658/12128 5596/5598/11885 5597/5599/11886 +f 5656/5658/12128 5664/5666/12129 5596/5598/11885 +f 5664/5666/12129 5656/5658/12128 5668/5670/12130 +f 5600/5602/11890 5664/5666/12129 5669/5671/12131 +f 5600/5602/11890 5593/5595/11882 5664/5666/12129 +f 5669/5671/12131 5668/5670/12130 5523/5525/12132 +f 5523/5525/12132 5668/5670/12130 5481/5483/12133 +f 5669/5671/12131 5664/5666/12129 5668/5670/12130 +f 5556/5558/11833 5670/5672/12134 5558/5560/11835 +f 5555/5557/12135 5601/5603/11891 5670/5672/12134 +f 5555/5557/12135 5670/5672/12134 5556/5558/11833 +f 5560/5562/12136 5595/5597/12137 5561/5563/12138 +f 5561/5563/12138 5587/5589/12139 5563/5565/12140 +f 5564/5566/12141 5669/5671/12131 5523/5525/12132 +f 5493/5495/11768 5601/5603/11891 5555/5557/12135 +f 5558/5560/12142 5595/5597/12137 5560/5562/12136 +f 5561/5563/12138 5595/5597/12137 5587/5589/12139 +f 5558/5560/12143 5670/5672/12143 5594/5596/12143 +f 5558/5560/12142 5594/5596/12144 5595/5597/12137 +f 5563/5565/12140 5587/5589/12139 5600/5602/11890 +f 5563/5565/12140 5600/5602/11890 5564/5566/12141 +f 5564/5566/12141 5600/5602/11890 5669/5671/12131 +f 5670/5672/12134 5601/5603/11891 5594/5596/12145 +f 5591/5593/11878 5601/5603/11891 5667/5669/12146 +f 5589/5591/12147 5588/5590/12148 5671/5673/12149 +f 5671/5673/12149 5588/5590/12148 5667/5669/12146 +f 5671/5673/12149 5667/5669/12146 5601/5603/11891 +f 5671/5673/12149 5601/5603/11891 5493/5495/11768 +f 5671/5673/12149 5493/5495/11768 5479/5481/11771 +f 5656/5658/12081 5655/5657/12080 5672/5674/12150 +f 5672/5674/12150 5668/5670/12151 5656/5658/12081 +f 5668/5670/12151 5672/5674/12150 5483/5485/11758 +f 5668/5670/12151 5483/5485/11758 5481/5483/11756 +f 5479/5481/11754 5478/5480/11753 5671/5673/12152 +f 5673/5675/12153 5671/5673/12152 5478/5480/11753 +f 5673/5675/12153 5589/5591/12094 5671/5673/12152 +f 5589/5591/12094 5673/5675/12153 5659/5661/12095 +f 5627/5629/12154 5486/5488/12154 5492/5494/12154 +f 4590/4592/12155 5649/5651/12155 5674/5676/12155 +f 5589/5591/11876 5660/5662/12156 5590/5592/11877 +f 5675/5677/12157 5676/5678/12158 5677/5679/12159 +f 5678/5680/12160 5675/5677/12157 5679/5681/12161 +f 5679/5681/12161 5680/5682/12162 5678/5680/12160 +f 5676/5678/12158 5681/5683/12163 5677/5679/12159 +f 5682/5684/12164 5683/5685/12165 5684/5686/12166 +f 5681/5683/12163 5683/5685/12165 5677/5679/12159 +f 5677/5679/12159 5683/5685/12165 5682/5684/12164 +f 5682/5684/12164 5684/5686/12166 5680/5682/12162 +f 5682/5684/12164 5680/5682/12162 5679/5681/12161 +f 5679/5681/12161 5675/5677/12157 5677/5679/12159 +f 5685/5687/12167 5686/5688/12168 5687/5689/12169 +f 5687/5689/12169 5688/5690/12170 5685/5687/12167 +f 5689/5691/12171 5688/5690/12170 5687/5689/12169 +f 5690/5692/12172 5688/5690/12173 5689/5691/12174 +f 5690/5692/12172 5689/5691/12174 5691/5693/12175 +f 5691/5693/12176 5689/5691/12177 5687/5689/12178 +f 5691/5693/12176 5687/5689/12178 5692/5694/12179 +f 5692/5694/12180 5687/5689/12181 5686/5688/12182 +f 5692/5694/12180 5686/5688/12182 5693/5695/12183 +f 5693/5695/12184 5686/5688/12185 5694/5696/12186 +f 5694/5696/12186 5686/5688/12185 5685/5687/12187 +f 5694/5696/12188 5685/5687/12189 5688/5690/12190 +f 5694/5696/12188 5688/5690/12190 5690/5692/12191 +f 5691/5693/12192 5695/5697/12193 5690/5692/12194 +f 5690/5692/12194 5695/5697/12193 5696/5698/12195 +f 5691/5693/12192 5697/5699/12196 5695/5697/12193 +f 5694/5696/12197 5698/5700/12198 5693/5695/12199 +f 5693/5695/12199 5698/5700/12198 5699/5701/12200 +f 5694/5696/12197 5696/5698/12195 5698/5700/12198 +f 5690/5692/12194 5696/5698/12195 5694/5696/12197 +f 5692/5694/12201 5700/5702/12202 5697/5699/12196 +f 5692/5694/12201 5697/5699/12196 5691/5693/12192 +f 5693/5695/12199 5699/5701/12200 5692/5694/12201 +f 5692/5694/12201 5699/5701/12200 5700/5702/12202 +f 5696/5698/12203 5695/5697/12204 5676/5678/12205 +f 5696/5698/12206 5676/5678/12206 5675/5677/12206 +f 5696/5698/12207 5675/5677/12208 5698/5700/12209 +f 5675/5677/12208 5678/5680/12210 5698/5700/12209 +f 5698/5700/12211 5678/5680/12212 5699/5701/12213 +f 5678/5680/12212 5680/5682/12214 5699/5701/12213 +f 5699/5701/12215 5680/5682/12216 5684/5686/12217 +f 5699/5701/12215 5684/5686/12217 5700/5702/12218 +f 5700/5702/12219 5684/5686/12220 5683/5685/12221 +f 5700/5702/12219 5683/5685/12221 5697/5699/12222 +f 5697/5699/12223 5683/5685/12224 5695/5697/12225 +f 5683/5685/12224 5681/5683/12226 5695/5697/12225 +f 5695/5697/12204 5681/5683/12227 5676/5678/12205 +f 5682/5684/12228 5679/5681/12229 5701/5703/12230 +f 5701/5703/12230 5679/5681/12229 5702/5704/12231 +f 5677/5679/12232 5682/5684/12232 5703/5705/12232 +f 5703/5705/12233 5682/5684/12233 5701/5703/12233 +f 5704/5706/12234 5677/5679/12234 5703/5705/12234 +f 5679/5681/12235 5677/5679/12235 5704/5706/12235 +f 5702/5704/12236 5679/5681/12236 5704/5706/12236 +f 5704/5706/2352 5703/5705/2352 5701/5703/2352 +f 5704/5706/2352 5701/5703/2352 5702/5704/2352 +f 5705/5707/12237 5706/5708/12238 5707/5709/12239 +f 5708/5710/12240 5709/5711/12241 5710/5712/12242 +f 5707/5709/12239 5711/5713/12243 5705/5707/12237 +f 5710/5712/12242 5712/5714/12244 5713/5715/12245 +f 5705/5707/12237 5711/5713/12243 5712/5714/12246 +f 5710/5712/12242 5709/5711/12241 5706/5708/12247 +f 5706/5708/12247 5709/5711/12241 5714/5716/12248 +f 5713/5715/12245 5708/5710/12240 5710/5712/12242 +f 5715/5717/12249 5716/5718/12250 5717/5719/12251 +f 5718/5720/12252 5719/5721/12253 5715/5717/12249 +f 5717/5719/12251 5718/5720/12252 5715/5717/12249 +f 5720/5722/12254 5717/5719/12254 5716/5718/12254 +f 5720/5722/12255 5716/5718/12256 5715/5717/12257 +f 5720/5722/12255 5715/5717/12257 5721/5723/12258 +f 5721/5723/12259 5715/5717/12260 5719/5721/12261 +f 5721/5723/12259 5719/5721/12261 5722/5724/12262 +f 5722/5724/12263 5719/5721/12263 5723/5725/12263 +f 5723/5725/12264 5719/5721/12264 5718/5720/12264 +f 5723/5725/12265 5718/5720/12265 5724/5726/12265 +f 5724/5726/12266 5718/5720/12267 5717/5719/12268 +f 5724/5726/12266 5717/5719/12268 5720/5722/12269 +f 5720/5722/12270 5725/5727/12271 5726/5728/12272 +f 5720/5722/12270 5726/5728/12272 5724/5726/12273 +f 5720/5722/12270 5727/5729/12274 5725/5727/12271 +f 5723/5725/12275 5728/5730/12276 5729/5731/12277 +f 5723/5725/12275 5729/5731/12277 5722/5724/12278 +f 5724/5726/12273 5730/5732/12279 5723/5725/12275 +f 5723/5725/12275 5730/5732/12279 5728/5730/12276 +f 5724/5726/12273 5726/5728/12272 5731/5733/12280 +f 5724/5726/12273 5731/5733/12280 5730/5732/12279 +f 5721/5723/12281 5732/5734/12282 5727/5729/12274 +f 5721/5723/12281 5727/5729/12274 5720/5722/12270 +f 5722/5724/12278 5729/5731/12277 5732/5734/12282 +f 5722/5724/12278 5732/5734/12282 5721/5723/12281 +f 5726/5728/12283 5707/5709/12284 5706/5708/12285 +f 5726/5728/12283 5706/5708/12285 5731/5733/12286 +f 5731/5733/12287 5706/5708/12288 5730/5732/12289 +f 5706/5708/12288 5714/5716/12290 5730/5732/12289 +f 5730/5732/12291 5714/5716/12292 5709/5711/12293 +f 5730/5732/12291 5709/5711/12293 5728/5730/12294 +f 5728/5730/12295 5709/5711/12296 5729/5731/12297 +f 5709/5711/12296 5708/5710/12298 5729/5731/12297 +f 5708/5710/12299 5713/5715/12300 5729/5731/12301 +f 5729/5731/12301 5713/5715/12300 5732/5734/12302 +f 5732/5734/12303 5713/5715/12304 5712/5714/12305 +f 5732/5734/12303 5712/5714/12305 5727/5729/12306 +f 5727/5729/12307 5712/5714/12308 5711/5713/12309 +f 5727/5729/12307 5711/5713/12309 5725/5727/12310 +f 5725/5727/12311 5711/5713/12312 5707/5709/12313 +f 5725/5727/12311 5707/5709/12313 5726/5728/12314 +f 5733/5735/12315 5710/5712/12315 5734/5736/12315 +f 5712/5714/12316 5710/5712/12316 5735/5737/12316 +f 5735/5737/12317 5710/5712/12317 5733/5735/12317 +f 5705/5707/12318 5712/5714/12319 5735/5737/12320 +f 5736/5738/12321 5705/5707/12318 5735/5737/12320 +f 5706/5708/12322 5705/5707/12322 5734/5736/12322 +f 5734/5736/12323 5705/5707/12323 5736/5738/12323 +f 5710/5712/12324 5706/5708/12324 5734/5736/12324 +f 5736/5738/3026 5735/5737/3026 5734/5736/3026 +f 5734/5736/3026 5735/5737/3026 5733/5735/3026 +f 4728/4730/12325 4726/4728/12326 5131/5133/12327 +f 4726/4728/12326 4936/4938/12328 5156/5158/12329 +f 5159/5161/12330 5156/5158/12329 4936/4938/12328 +f 4936/4938/12328 4724/4726/12331 5159/5161/12330 +f 4726/4728/12326 5156/5158/12329 5131/5133/12327 +f 4928/4930/12332 4913/4915/12333 5152/5154/12334 +f 5152/5154/12334 4852/4854/12335 4929/4931/12336 +f 4928/4930/12332 5152/5154/12334 4929/4931/12336 +f 5148/5150/528 5150/5152/528 5149/5151/528 +f 5151/5153/528 5150/5152/528 5148/5150/528 +f 5147/5149/528 5146/5148/528 5144/5146/528 +f 5144/5146/528 5145/5147/528 5147/5149/528 +f 5176/5178/528 5173/5175/528 5177/5179/528 +f 5173/5175/528 5176/5178/528 5174/5176/528 +f 5176/5178/528 5175/5177/528 5174/5176/528 +f 4739/4741/12337 4744/4746/12337 5737/5739/12337 +f 5643/5645/12338 4955/4957/12338 4957/4959/12338 +f 5651/5653/12339 4993/4995/12340 4740/4742/12341 +f 4993/4995/12342 5651/5653/12343 4990/4992/12344 +f 5651/5653/12343 5650/5652/12345 4990/4992/12344 +f 5644/5646/12346 5648/5650/12346 4578/4580/12346 +f 5647/5649/12347 5646/5648/12348 4990/4992/12349 +f 5646/5648/12350 5645/5647/12350 4986/4988/12350 +f 5653/5655/12351 4510/4512/12352 4578/4580/12353 +f 5643/5645/12354 5644/5646/12354 4955/4957/12354 +f 5653/5655/12351 5652/5654/12355 4510/4512/12352 +f 4583/4585/12356 5649/5651/12357 4581/4583/12358 +f 5642/5644/12359 4584/4586/12359 4586/4588/12359 +f 5642/5644/12360 4587/4589/12361 4584/4586/12362 +f 5652/5654/12363 4583/4585/10633 4509/4511/10634 +f 4741/4743/12364 4587/4589/12364 5641/5643/12364 +f 5652/5654/12355 4509/4511/12365 4510/4512/12352 +f 5737/5739/12366 4744/4746/12366 5738/5740/12366 +f 5739/5741/12367 4739/4741/12367 5737/5739/12367 +f 4740/4742/12368 4739/4741/12368 5739/5741/12368 +f 5644/5646/12369 4578/4580/12369 4955/4957/12369 +f 5645/5647/12370 4987/4989/12370 4986/4988/12370 +f 5645/5647/12371 5643/5645/12372 4987/4989/10914 +f 5739/5741/12373 5651/5653/12339 4740/4742/12341 +f 4957/4959/10913 4987/4989/10914 5643/5645/12372 +f 5648/5650/12374 5653/5655/12374 4578/4580/12374 +f 5646/5648/12348 4986/4988/12375 4990/4992/12349 +f 4583/4585/10633 5652/5654/12363 5649/5651/12376 +f 4581/4583/12358 5649/5651/12357 4590/4592/12377 +f 4590/4592/12378 5674/5676/12378 4586/4588/12378 +f 5674/5676/12379 5642/5644/12379 4586/4588/12379 +f 5642/5644/12360 5641/5643/12380 4587/4589/12361 +f 4744/4746/12381 4741/4743/12382 5738/5740/12383 +f 5650/5652/12384 5647/5649/12384 4990/4992/12384 +f 5559/5561/12385 5562/5564/12386 5557/5559/12387 +f 5557/5559/12387 5562/5564/12386 5492/5494/12388 +f 5492/5494/12388 5562/5564/12386 5520/5522/12389 +f 5492/5494/12388 5520/5522/12389 5610/5612/12390 +f 5514/5516/12391 5621/5623/12392 5520/5522/12389 +f 5637/5639/12393 5627/5629/12394 5492/5494/12388 +f 5629/5631/12395 5627/5629/12394 5637/5639/12393 +f 5492/5494/12388 5610/5612/12390 5611/5613/12396 +f 5621/5623/12392 5514/5516/12391 5606/5608/12397 +f 5614/5616/12398 5637/5639/12393 5492/5494/12388 +f 5520/5522/12389 5621/5623/12392 5607/5609/12399 +f 5520/5522/12389 5609/5611/12400 5610/5612/12390 +f 5520/5522/12389 5607/5609/12399 5608/5610/12401 +f 5614/5616/12398 5492/5494/12388 5613/5615/12402 +f 5520/5522/12389 5608/5610/12401 5609/5611/12400 +f 5613/5615/12402 5492/5494/12388 5612/5614/12403 +f 5612/5614/12403 5492/5494/12388 5611/5613/12396 +f 5666/5668/12404 5663/5665/12404 5662/5664/7255 +f 5666/5668/12404 5665/5667/9546 5663/5665/12404 +f 5739/5741/12405 5513/5515/12068 5651/5653/12064 +f 5654/5656/12406 5513/5515/12068 5739/5741/12405 +f 5652/5654/12065 5528/5530/12069 5661/5663/12407 +f 5652/5654/12065 5661/5663/12407 5659/5661/12408 +f 5652/5654/12065 5659/5661/12408 5673/5675/12409 +f 5655/5657/12410 5739/5741/12405 5672/5674/12411 +f 5655/5657/12410 5654/5656/12406 5739/5741/12405 +f 5649/5651/12058 5652/5654/12065 5673/5675/12409 +f 5649/5651/12058 5673/5675/12409 5478/5480/12412 +f 5483/5485/12413 5672/5674/12411 5739/5741/12405 +f 5482/5484/12414 5483/5485/12413 5739/5741/12405 +f 5649/5651/12058 5478/5480/12412 5475/5477/12415 +f 5482/5484/12414 5739/5741/12405 5737/5739/12416 +f 5649/5651/12058 5475/5477/12415 5628/5630/12059 +f 5482/5484/12414 5737/5739/12416 5605/5607/12417 +f 5605/5607/12417 5737/5739/12416 5497/5499/12418 +f 5535/5537/12049 5532/5534/12056 5644/5646/12050 +f 5674/5676/12419 5649/5651/12058 5571/5573/12060 +f 5674/5676/12419 5571/5573/12060 5570/5572/12420 +f 5497/5499/12418 5737/5739/12416 5738/5740/12383 +f 5498/5500/12421 5497/5499/12418 5738/5740/12383 +f 5674/5676/12419 5570/5572/12420 5568/5570/12422 +f 5643/5645/12048 5505/5507/12067 5640/5642/12423 +f 4741/4743/12382 5501/5503/12424 5738/5740/12383 +f 5646/5648/12052 5508/5510/12055 5506/5508/12053 +f 5501/5503/12424 5498/5500/12421 5738/5740/12383 +f 5568/5570/12422 5566/5568/12045 5642/5644/12047 +f 5641/5643/12046 5502/5504/12425 4741/4743/12382 +f 5643/5645/12048 5640/5642/12423 5639/5641/12070 +f 5502/5504/12425 5501/5503/12424 4741/4743/12382 +f 5641/5643/12046 5566/5568/12045 5658/5660/12426 +f 5502/5504/12425 5641/5643/12046 5657/5659/12427 +f 5568/5570/12422 5642/5644/12047 5674/5676/12419 +f 5657/5659/12427 5641/5643/12046 5658/5660/12426 +f 5836/5742/12428 5833/5743/12429 5835/5744/12430 +f 6555/5745/12431 6553/5746/12432 6539/5747/12433 +f 7562/5748/12434 7561/5749/12435 7585/5750/12436 +f 6740/5751/12437 6741/5752/12438 6711/5753/12439 +f 6893/5754/12440 6898/5755/12440 6892/5756/12440 +f 6558/5757/12441 6561/5758/12441 6580/5759/12441 +f 7837/5760/12442 7839/5761/12443 7838/5762/12444 +f 7578/5763/12445 7580/5764/12446 7579/5765/12447 +f 6858/5766/12448 6857/5767/12449 6859/5768/12450 +f 6909/5769/12440 6944/5770/12440 6911/5771/12440 +f 6099/5772/12451 6097/5773/12452 6098/5774/12453 +f 7760/5775/12454 7671/5776/12455 7758/5777/12456 +f 5808/5778/12457 5807/5779/12458 5841/5780/12459 +f 7977/5781/12460 7962/5782/12461 7978/5783/12462 +f 7874/5784/12463 7875/5785/12464 7876/5786/12465 +f 5843/5787/12466 5743/5788/12467 5845/5789/12468 +f 5850/5790/12469 5749/5791/12470 5755/5792/12471 +f 6704/5793/12472 6705/5794/12472 6674/5795/12472 +f 6850/5796/12473 6838/5797/12474 6849/5798/12475 +f 7854/5799/12476 7882/5800/12477 7870/5801/12478 +f 6731/5802/12479 6729/5803/12480 6655/5804/12481 +f 5923/5805/12482 5987/5806/12483 5988/5807/12484 +f 7744/5808/12485 7758/5777/12456 7743/5809/12486 +f 6744/5810/12487 6745/5811/12488 6714/5812/12489 +f 6948/5813/12490 6981/5814/12491 6980/5815/12492 +f 5769/5816/12493 5804/5817/12493 5800/5818/12494 +f 6184/5819/12495 6017/5820/12496 6018/5821/12497 +f 6817/5822/12498 6818/5823/12498 6799/5824/12498 +f 6236/5825/12499 6237/5826/12500 6099/5772/12451 +f 5913/5827/12501 5912/5828/12502 5984/5829/12503 +f 6974/5830/12504 6965/5831/12505 6975/5832/12506 +f 6235/5833/12507 6236/5825/12499 6129/5834/12508 +f 7642/5835/12509 7605/5836/12510 7606/5837/12511 +f 6582/5838/12441 6579/5839/12441 6549/5840/12441 +f 7493/5841/12512 7510/5842/12513 7500/5843/12514 +f 7973/5844/12515 7972/5845/12516 7958/5846/12517 +f 7852/5847/12518 7823/5848/12518 7850/5849/12518 +f 6633/5850/12519 6636/5851/12520 6634/5852/12521 +f 6179/5853/12522 6174/5854/12523 6180/5855/12524 +f 6376/5856/12525 6375/5857/12526 6357/5858/12527 +f 6718/5859/12528 6719/5860/12529 6707/5861/12530 +f 7940/5862/12531 7919/5863/12532 7939/5864/12533 +f 6167/5865/12534 6166/5866/12535 6179/5853/12522 +f 7981/5867/12536 7956/5868/12537 7982/5869/12538 +f 7757/5870/12539 7674/5871/12540 7756/5872/12541 +f 7467/5873/12542 7463/5874/12542 7466/5875/12542 +f 6020/5876/12543 6195/5877/12544 6196/5878/12545 +f 6359/5879/12546 6366/5880/12547 6367/5881/12548 +f 7950/5882/12549 7924/5883/12550 7923/5884/12551 +f 7515/5885/12552 7513/5886/12553 7512/5887/12554 +f 6841/5888/12555 6842/5889/12556 6812/5890/12557 +f 6579/5839/12441 6547/5891/12558 6549/5840/12441 +f 5762/5892/12559 5785/5893/12560 5783/5894/12561 +f 7717/5895/12562 7705/5896/12562 7703/5897/12562 +f 6749/5898/12563 6652/5899/12563 6753/5900/12563 +f 6332/5901/12564 6355/5902/12565 6331/5903/12566 +f 7658/5904/12567 7655/5905/12567 7657/5906/12567 +f 5980/5907/12568 5918/5908/12569 5891/5909/12570 +f 7864/5910/12571 7863/5911/12572 7853/5912/12573 +f 6262/5913/12574 6261/5914/12575 6254/5915/12576 +f 5946/5916/12577 5947/5917/12578 5943/5918/12579 +f 7826/5919/12580 7824/5920/12581 7825/5921/12581 +f 6518/5922/12582 6411/5923/12582 6403/5924/12582 +f 6400/5925/12583 6406/5926/12584 6402/5927/12585 +f 6340/5928/12586 6339/5929/12587 6380/5930/12588 +f 5879/5931/12589 5886/5932/12590 5887/5933/12591 +f 6429/5934/12592 6432/5935/12593 6430/5936/12594 +f 6184/5819/12495 6222/5937/12595 6225/5938/12596 +f 7625/5939/12597 7616/5940/12598 7617/5941/12599 +f 6805/5942/12600 6804/5943/12601 6803/5944/12601 +f 6609/5945/12602 6597/5946/12603 6596/5947/12604 +f 6960/5948/12605 6942/5949/12606 6961/5950/12607 +f 5778/5951/12608 5777/5952/12609 5776/5953/12609 +f 7790/5954/12610 7881/5955/12611 7882/5800/12477 +f 5825/5956/12612 5827/5957/12613 5837/5958/12614 +f 6609/5945/12602 6610/5959/12615 6598/5960/12616 +f 8001/5961/12617 8002/5962/12618 7999/5963/12619 +f 6250/5964/12620 6248/5965/12621 6249/5966/12622 +f 5819/5967/12623 5806/5968/12624 5818/5969/12625 +f 5879/5931/12589 5883/5970/12626 5886/5932/12590 +f 5812/5971/12627 5844/5972/12628 5847/5973/12629 +f 6894/5974/12440 6898/5755/12440 6893/5754/12440 +f 6897/5975/12630 6896/5976/12631 6910/5977/12632 +f 7813/5978/12633 7818/5979/12634 7815/5980/12635 +f 6805/5942/12636 6778/5981/12637 6807/5982/12638 +f 7934/5983/12639 7935/5984/12640 7933/5985/12641 +f 7795/5986/12642 7796/5987/12643 7800/5988/12644 +f 6844/5989/12645 6867/5990/12646 6868/5991/12647 +f 7655/5905/12648 7542/5992/12648 7541/5993/12648 +f 7958/5846/12517 7972/5845/12516 7957/5994/12649 +f 6942/5949/12606 6938/5995/12650 6961/5950/12607 +f 5905/5996/12651 5899/5997/12652 6163/5998/12653 +f 6322/5999/12654 6296/6000/12655 6324/6001/12656 +f 6787/6002/12657 6789/6003/12658 6788/6004/12659 +f 7872/6005/12660 7875/5785/12464 7873/6006/12661 +f 7845/6007/12518 7836/6008/12518 7844/6009/12518 +f 6800/6010/12662 6799/5824/12663 6798/6011/12664 +f 6873/6012/12665 6757/6013/12665 6761/6014/12665 +f 6496/6015/12666 6480/6016/12667 6495/6017/12668 +f 6234/6018/12669 5913/5827/12501 6235/5833/12507 +f 7494/6019/12670 7471/6020/12671 7495/6021/12672 +f 6232/6022/12673 5912/5828/12502 6233/6023/12674 +f 7975/6024/12675 7985/6025/12676 7974/6026/12677 +f 7480/6027/12678 7469/6028/12679 7481/6029/12680 +f 6534/6030/12681 6525/6031/12682 6532/6032/12683 +f 6113/6033/12684 6114/6034/12685 6075/6035/12686 +f 7641/6036/12687 7644/6037/12688 7640/6038/12689 +f 7982/5869/12690 7993/6039/12691 7981/5867/12536 +f 7716/6040/12562 7713/6041/12562 7715/6042/12562 +f 7728/6043/12692 7692/6044/12562 7726/6045/12692 +f 6042/6046/12693 6182/6047/12694 6177/6048/12695 +f 6491/6049/12696 6483/6050/12697 6484/6051/12698 +f 7740/6052/12699 7739/6053/12700 7727/6054/12701 +f 6736/6055/12702 6734/6056/12703 6735/6057/12704 +f 6769/6058/12705 6765/6059/12706 6848/6060/12707 +f 6459/6061/12708 6462/6062/12708 6432/5935/12708 +f 6287/6063/12709 6283/6064/12710 6367/5881/12548 +f 6027/6065/12711 6026/6066/12712 6198/6067/12713 +f 6421/6068/12714 6444/6069/12715 6443/6070/12716 +f 7517/6071/12717 7498/6072/12718 7516/6073/12719 +f 5901/6074/12720 5900/6075/12721 5902/6076/12722 +f 7649/6077/12723 7609/6078/12724 7610/6079/12725 +f 6041/6080/12726 6168/6081/12727 6037/6082/12728 +f 6210/6083/12729 6196/5878/12545 6195/5877/12544 +f 6519/6084/12583 6518/5922/12583 6514/6085/12583 +f 5975/6086/12730 5893/6087/12731 5894/6088/12732 +f 7515/5885/12552 7498/6072/12718 7517/6071/12717 +f 6351/6089/12733 6352/6090/12734 6335/6091/12735 +f 6345/6092/12736 6334/6093/12737 6344/6094/12738 +f 6489/6095/12739 6488/6096/12740 6490/6097/12741 +f 6435/6098/12742 6436/6099/12743 6434/6100/12744 +f 6647/6101/12745 6653/6102/12746 6744/5810/12487 +f 6258/6103/12747 6257/6104/12748 6263/6105/12749 +f 6180/5855/12524 6167/5865/12534 6179/5853/12522 +f 7776/6106/12750 7777/6107/12751 7670/6108/12752 +f 6771/6109/12753 6781/6110/12754 6779/6111/12755 +f 5760/6112/12756 5761/6113/12757 5778/5951/12758 +f 6031/6114/12759 6239/6115/12760 6025/6116/12761 +f 6306/6117/12762 6305/6118/12763 6291/6119/12764 +f 7755/6120/12765 7751/6121/12766 7754/6122/12767 +f 6602/6123/12768 6617/6124/12769 6619/6125/12770 +f 6599/6126/12771 6600/6127/12772 6583/6128/12773 +f 6175/6129/12774 6251/6130/12775 6173/6131/12776 +f 6843/6132/12777 6832/6133/12778 6870/6134/12779 +f 6953/6135/12780 6939/6136/12781 6954/6137/12782 +f 6382/6138/12783 6385/6139/12784 6384/6140/12785 +f 6381/6141/12786 6383/6142/12787 6382/6138/12783 +f 6474/6143/12788 6485/6144/12789 6489/6095/12739 +f 7619/6145/12790 7633/6146/12791 7618/6147/12792 +f 7937/6148/12793 7919/5863/12532 7935/5984/12794 +f 6571/6149/12441 6573/6150/12441 6569/6151/12441 +f 6825/6152/12795 6859/5768/12450 6862/6153/12796 +f 5774/6154/12797 5773/6155/12798 5771/6156/12799 +f 6939/6136/12440 6917/6157/12440 6916/6158/12800 +f 6533/6159/12801 6613/6160/12802 6612/6161/12803 +f 5919/6162/12804 6209/6163/12805 6204/6164/12806 +f 6841/5888/12555 6852/6165/12807 6853/6166/12808 +f 7754/6122/12767 7756/5872/12541 7755/6120/12765 +f 7528/6167/12809 7530/6168/12810 7529/6169/12811 +f 5864/6170/12812 5865/6171/12813 5898/6172/12814 +f 5891/5909/12570 5976/6173/12815 5977/6174/12816 +f 6438/6175/12708 6440/6176/12708 6457/6177/12708 +f 7449/6178/12542 7473/6179/12542 7451/6180/12542 +f 6443/6070/12716 6441/6181/12817 6421/6068/12714 +f 6308/6182/12818 6307/6183/12819 6306/6117/12820 +f 6565/6184/12821 6541/6185/12822 6542/6186/12821 +f 7992/6187/12823 7991/6188/12824 7980/6189/12825 +f 6097/5773/12452 6082/6190/12826 6096/6191/12827 +f 6402/5927/12585 6406/5926/12584 6499/6192/12828 +f 6076/6193/12829 6106/6194/12830 6107/6195/12831 +f 6220/6196/12832 6219/6197/12833 6218/6198/12834 +f 6442/6199/12708 6445/6200/12708 6453/6201/12708 +f 6231/6202/12835 6081/6203/12836 6082/6190/12826 +f 6508/6204/12837 6469/6205/12838 6468/6206/12839 +f 7691/6207/12840 7680/6208/12841 7679/6209/12842 +f 6773/6210/12843 6789/6003/12844 6787/6002/12845 +f 6491/6049/12696 6490/6097/12741 6413/6211/12846 +f 7600/6212/12847 7586/6213/12847 7583/6214/12847 +f 6088/6215/12848 6089/6216/12849 6068/6217/12850 +f 6424/6218/12708 6427/6219/12708 6455/6220/12708 +f 5959/6221/12851 5985/6222/12852 5956/6223/12853 +f 5820/6224/12854 5821/6225/12855 5805/6226/12856 +f 7520/6227/12857 7522/6228/12858 7413/6229/12859 +f 7541/5993/12567 7546/6230/12860 7545/6231/12567 +f 7417/6232/12861 7412/6233/12862 7420/6234/12863 +f 7930/6235/12864 7916/6236/12865 7928/6237/12866 +f 6658/6238/12867 6693/6239/12868 6691/6240/12869 +f 6413/6211/12846 6407/6241/12870 6491/6049/12696 +f 6182/6047/12694 6178/6242/12871 6177/6048/12695 +f 6889/6243/12872 6968/6244/12873 6891/6245/12874 +f 7597/6246/12847 7566/6247/12847 7594/6248/12847 +f 7843/6249/12518 7839/5761/12518 7845/6007/12518 +f 6531/6250/12875 6635/6251/12876 6633/5850/12519 +f 6213/6252/12877 6183/6253/12878 6193/6254/12879 +f 6886/6255/12880 6987/6256/12881 6988/6257/12882 +f 5975/6086/12730 5892/6258/12883 5893/6087/12731 +f 5895/6259/12884 5896/6260/12885 5975/6086/12730 +f 5861/6261/12886 6207/6262/12887 6223/6263/12888 +f 6690/6264/12889 6689/6265/12890 6688/6266/12891 +f 6334/6093/12737 6346/6267/12892 6326/6268/12893 +f 7506/6269/12894 7490/6270/12895 7501/6271/12896 +f 6720/6272/12897 6719/5860/12529 6730/6273/12898 +f 6405/6274/12899 6410/6275/12900 6508/6204/12837 +f 7966/6276/12901 8000/6277/12902 7965/6278/12903 +f 6278/6279/12904 6281/6280/12905 6274/6281/12905 +f 7850/5849/12518 7823/5848/12518 7821/6282/12518 +f 5853/6283/12906 5848/6284/12907 5850/5790/12469 +f 5836/5742/12428 5837/5958/12614 5827/5957/12613 +f 6782/6285/12908 6772/6286/12909 6784/6287/12910 +f 6348/6288/12911 6362/6289/12912 6361/6290/12913 +f 6648/6291/12914 6656/6292/12915 6649/6293/12916 +f 6700/6294/12472 6668/6295/12472 6671/6296/12472 +f 6810/6297/12917 6831/6298/12918 6832/6133/12919 +f 5764/6299/12920 5756/6300/12921 5791/6301/12922 +f 7808/6302/12923 7835/6303/12924 7809/6304/12925 +f 7909/6305/12926 7992/6187/12823 7910/6306/12927 +f 6166/5866/12535 6151/6307/12928 6052/6308/12929 +f 6011/6309/12930 5860/6310/12931 5933/6311/12932 +f 7656/6312/12933 7548/6313/12933 7542/5992/12933 +f 5942/6314/12934 5935/6315/12935 6000/6316/12936 +f 6655/5804/12481 6648/6291/12914 6649/6293/12916 +f 6307/6183/12819 6304/6317/12937 6305/6118/12938 +f 6345/6092/12939 6344/6094/12940 6390/6318/12941 +f 6052/6308/12929 6152/6319/12942 6166/5866/12535 +f 5840/6320/12943 5841/5780/12459 5839/6321/12944 +f 7937/6148/12945 7935/5984/12640 7936/6322/12640 +f 6890/6323/12946 6997/6324/12946 6996/6325/12947 +f 7670/6108/12752 7777/6107/12751 7779/6326/12948 +f 7663/6327/12949 7766/6328/12950 7767/6329/12951 +f 6990/6330/12952 6954/6137/12782 6991/6331/12953 +f 7665/6332/12954 7675/6333/12955 7673/6334/12956 +f 6447/6335/12708 6451/6336/12708 6454/6337/12708 +f 6306/6117/12820 6307/6183/12819 6305/6118/12938 +f 5856/6338/12957 5746/6339/12957 5740/6340/12957 +f 6168/6081/12727 6041/6080/12726 6177/6048/12695 +f 6085/6341/12958 6086/6342/12959 6068/6217/12850 +f 7631/6343/12960 7616/5940/12598 7625/5939/12597 +f 6769/6058/12705 6758/6344/12961 6767/6345/12962 +f 6695/6346/12963 6703/6347/12964 6716/6348/12965 +f 7801/6349/12966 7874/5784/12463 7799/6350/12967 +f 7853/5912/12518 7823/5848/12518 7852/5847/12518 +f 6833/6351/12968 6843/6132/12777 6846/6352/12969 +f 7731/6353/12970 7720/6354/12971 7732/6355/12972 +f 6352/6090/12734 6353/6356/12973 6335/6091/12735 +f 6391/6357/12974 6346/6267/12975 6345/6092/12939 +f 6371/6358/12976 6374/6359/12977 6373/6360/12978 +f 7628/6361/12979 7627/6362/12980 7630/6363/12981 +f 5909/6364/12982 5891/5909/12570 5918/5908/12569 +f 6648/6291/12983 6655/5804/12481 6729/5803/12480 +f 5751/6365/12984 5754/6366/12985 5748/6367/12984 +f 6914/6368/12986 6897/5975/12630 6912/6369/12987 +f 5838/6370/12988 5840/6320/12943 5839/6321/12944 +f 5822/6371/12989 5751/6365/12990 5832/6372/12991 +f 6245/6373/12992 6246/6374/12993 6247/6375/12994 +f 6972/6376/12995 6970/6377/12996 6971/6378/12997 +f 6477/6379/12998 6478/6380/12999 6461/6381/13000 +f 6320/6382/13001 6294/6383/13002 6295/6384/13001 +f 6714/5812/12489 6713/6385/13003 6744/5810/12487 +f 6211/6386/13004 6214/6387/13005 6213/6252/12877 +f 6009/6388/13006 6001/6389/13007 6000/6316/12936 +f 6185/6390/13008 6022/6391/13009 6021/6392/13010 +f 7723/6393/13011 7736/6394/13011 7724/6395/13011 +f 7728/6043/13012 7741/6396/13013 7740/6052/12699 +f 6331/5903/13014 6328/6397/13014 6299/6398/13014 +f 7500/5843/12514 7508/6399/13015 7507/6400/13016 +f 7533/6401/13017 7534/6402/13018 7415/6403/13019 +f 6187/6404/13020 6192/6405/13021 6191/6406/13022 +f 6001/6389/13007 5932/6407/13023 5860/6310/12931 +f 7970/6408/13024 7969/6409/13025 7954/6410/13026 +f 5773/6155/13027 5805/6226/12494 5803/6411/12493 +f 6868/5991/12647 6763/6412/13028 6869/6413/13029 +f 6965/5831/12505 6962/6414/13030 6963/6415/13031 +f 6813/6416/13032 6814/6417/13033 6827/6418/13034 +f 5949/6419/13035 5959/6221/12851 5956/6223/12853 +f 5891/5909/12570 5889/6420/13036 5890/6421/13037 +f 6173/6131/12776 6172/6422/13038 6178/6242/12871 +f 7859/6423/13039 7889/6424/13040 7858/6425/13041 +f 7556/6426/13042 7569/6427/13043 7557/6428/13044 +f 6308/6182/13045 6306/6117/12762 6292/6429/13046 +f 7547/6430/13047 7632/6431/13048 7634/6432/13049 +f 6992/6433/13050 6884/6434/13050 6994/6435/13050 +f 6691/6240/13051 6690/6264/12889 6688/6266/12891 +f 6639/6436/13052 6525/6031/13052 6527/6437/13052 +f 6195/5877/12544 6198/6067/12713 6203/6438/13053 +f 7909/6305/13054 7906/6439/13054 7911/6440/13054 +f 7446/6441/13055 7445/6442/13055 7447/6443/13055 +f 7921/6444/13056 7918/6445/13056 7920/6446/13056 +f 6268/6447/13057 6258/6103/12747 6263/6105/12749 +f 6503/6448/13058 6502/6449/13059 6501/6450/13060 +f 6299/6398/13014 6301/6451/13014 6331/5903/13014 +f 7656/6312/12933 7660/6452/13061 7548/6313/12933 +f 6578/6453/13062 6606/6454/13063 6574/6455/13064 +f 6154/6456/13065 6153/6457/13066 6156/6458/13067 +f 7965/6278/12903 7998/6459/13068 7984/6460/13069 +f 7427/6461/13070 7462/6462/13071 7464/6463/13072 +f 5786/6464/12493 5801/6465/12493 5784/6466/12493 +f 6278/6279/12904 6283/6064/12710 6281/6280/12905 +f 5993/6467/13073 5950/6468/13074 5951/6469/13075 +f 7959/6470/13056 7932/6471/13056 7929/6472/13056 +f 7730/6473/13076 7768/6474/13077 7729/6475/13078 +f 6788/6004/12659 6785/6476/13079 6786/6477/13080 +f 7630/6363/12981 7627/6362/12980 7626/6478/13081 +f 6926/6479/13082 6925/6480/13083 6928/6481/13084 +f 6514/6085/13085 6401/6482/13085 6515/6483/13085 +f 7778/6484/13086 7777/6107/12751 7734/6485/13087 +f 6665/6486/12472 6664/6487/12472 6662/6488/13088 +f 6224/6489/13089 6220/6196/12832 5929/6490/13090 +f 6727/6491/13091 6728/6492/13092 6730/6273/12898 +f 6320/6382/13093 6321/6493/13094 6319/6494/13095 +f 6205/6495/13096 6210/6083/12729 6195/5877/12544 +f 6935/6496/12440 6925/6480/12440 6922/6497/12440 +f 6358/6498/13097 6341/6499/13098 6384/6140/12785 +f 6521/6500/13099 6637/6501/13099 6520/6502/13099 +f 6276/6503/13100 6363/6504/13101 6393/6505/13102 +f 6442/6199/13103 6443/6070/13104 6445/6200/13105 +f 6615/6506/13106 6614/6507/13107 6616/6508/13108 +f 6809/6509/13109 6770/6510/13110 6779/6111/12755 +f 6238/6511/13111 6247/6375/12994 6239/6115/12760 +f 6191/6406/13022 6190/6512/13112 6189/6513/13113 +f 6335/6091/13014 6332/5901/13014 6304/6317/13014 +f 7455/6514/13114 7457/6515/13115 7456/6516/13115 +f 7953/6517/13056 7949/6518/13056 7952/6519/13056 +f 6534/6030/12681 6595/6520/13116 6594/6521/13117 +f 6380/5930/12588 6379/6522/13118 6381/6141/12786 +f 7424/6523/12862 7426/6524/13119 7421/6525/12862 +f 6870/6134/12779 6831/6298/12918 6868/5991/12647 +f 5842/6526/13120 5810/6527/13121 5809/6528/13122 +f 7592/6529/13123 7612/6530/13124 7599/6531/13125 +f 7976/6532/13126 7964/6533/13127 7977/5781/12460 +f 7702/6534/13128 7704/6535/13129 7682/6536/13130 +f 6264/6537/13131 6269/6538/13132 6272/6539/13133 +f 7861/6540/13134 7891/6541/13135 7860/6542/13136 +f 7564/6543/13137 7590/6544/13137 7591/6545/13137 +f 7746/6546/13138 7762/6547/13139 7745/6548/13140 +f 7908/6549/13141 7905/6550/13054 7907/6551/13054 +f 7932/6471/13142 7930/6235/13143 7929/6472/13144 +f 5760/6112/12756 5759/6552/13145 5758/6553/13145 +f 7589/6554/12847 7596/6555/12847 7591/6545/12847 +f 6645/6556/13146 6738/6557/13147 6737/6558/13148 +f 6480/6016/12667 6481/6559/13149 6455/6220/13150 +f 7475/6560/12542 7453/6561/12542 7472/6562/12542 +f 6711/5753/12439 6712/6563/13151 6699/6564/13152 +f 7416/6565/13153 7424/6523/13153 7539/6566/13153 +f 7910/6306/12927 7996/6567/13154 7901/6568/13155 +f 7975/6024/12675 7988/6569/13156 7985/6025/12676 +f 6614/6507/13107 6533/6159/12801 6616/6508/13108 +f 5851/6570/13157 5815/6571/13158 5814/6572/13159 +f 6208/6573/13160 6207/6262/12887 5861/6261/12886 +f 5992/6574/13161 5926/6575/13162 5990/6576/13163 +f 5778/5951/12608 5781/6577/13164 5779/6578/12608 +f 6414/6579/13165 6448/6580/13166 6446/6581/13167 +f 7418/6582/13168 7537/6583/13168 7535/6584/13168 +f 6805/5942/12600 6806/6585/12600 6804/5943/12601 +f 6216/6586/13169 6219/6197/12833 6217/6587/13170 +f 5866/6588/13171 5867/6589/13172 5884/6590/13173 +f 6483/6050/12697 6491/6049/12696 6493/6591/13174 +f 6707/5861/12472 6678/6592/12472 6680/6593/12472 +f 5998/6594/13175 5995/6595/13176 5946/5916/12577 +f 5940/6596/13177 6000/6316/12936 5939/6597/13178 +f 7471/6020/12671 7470/6598/13179 7496/6599/13180 +f 5946/5916/12577 5995/6595/13176 5993/6467/13073 +f 6279/6600/12905 6277/6601/12905 6286/6602/13181 +f 6153/6457/13066 6154/6456/13065 6229/6603/13182 +f 6246/6374/12993 6202/6604/13183 6201/6605/13184 +f 6310/6606/13185 6313/6607/13186 6311/6608/13185 +f 6229/6603/13182 6154/6456/13065 6228/6609/13187 +f 5913/5827/12501 5870/6610/13188 5914/6611/13189 +f 6928/6481/13084 6930/6612/13190 6929/6613/13191 +f 5969/6614/13192 5877/6615/13193 5968/6616/13194 +f 7648/6617/13195 7646/6618/13196 7608/6619/13197 +f 6573/6150/13198 6589/6620/13199 6576/6621/13200 +f 6160/6622/13201 6252/6623/13202 6159/6624/13203 +f 6991/6331/12953 6889/6243/12872 6988/6257/12882 +f 6597/5946/13204 6584/6625/13205 6596/5947/13206 +f 5766/6626/13207 5765/6627/13208 5767/6628/13209 +f 7455/6514/13114 7456/6516/13115 7454/6629/13210 +f 5823/6630/13211 5824/6631/13212 5800/5818/13213 +f 6353/6356/12973 6354/6632/13214 6332/5901/12564 +f 6360/6633/13215 6359/5879/12546 6351/6089/13216 +f 6962/6414/13030 6971/6378/12997 6970/6377/12996 +f 6953/6135/12780 6990/6330/12952 6989/6634/13217 +f 6114/6034/12685 6132/6635/13218 6075/6035/12686 +f 6325/6636/13014 6327/6637/13014 6323/6638/13014 +f 6788/6004/12659 6789/6003/12658 6791/6639/13219 +f 6882/6640/13220 6890/6323/13220 6996/6325/13220 +f 6277/6601/13221 6398/6641/13221 6284/6642/13221 +f 7466/5875/12542 7461/6643/12542 7469/6028/12542 +f 7911/6440/13222 7906/6439/13222 8019/6644/13222 +f 5923/5805/12482 5885/6645/13223 5987/5806/12483 +f 6584/6625/12441 6585/6646/12441 6554/6647/12441 +f 6733/6648/13224 6734/6056/12703 6732/6649/13225 +f 6529/6650/13226 6642/6651/13226 6638/6652/13226 +f 7780/6653/13227 7779/6326/12948 7777/6107/12751 +f 7955/6654/13228 7968/6655/13229 7967/6656/13230 +f 6255/6657/13231 6258/6103/12747 6268/6447/13057 +f 7644/6037/12688 7641/6036/12687 7642/5835/12509 +f 6982/6658/13232 6981/5814/12491 6949/6659/13233 +f 7598/6660/13234 7621/6661/13235 7620/6662/13236 +f 6983/6663/13237 6982/6658/13232 6984/6664/13238 +f 6169/6665/13239 6247/6375/12994 6238/6511/13111 +f 6811/6666/12498 6806/6585/12498 6808/6667/12498 +f 6105/6668/13240 6092/6669/13241 6111/6670/13242 +f 7462/6462/13243 7460/6671/13244 7461/6643/13245 +f 6867/5990/12646 6844/5989/12645 6845/6672/13246 +f 7840/6673/13247 7810/6674/13248 7841/6675/13249 +f 6411/5923/12583 6408/6676/12583 6413/6211/12846 +f 7440/6677/13250 7441/6678/13251 7439/6679/13252 +f 6280/6680/13253 6275/6681/12905 6273/6682/12905 +f 7905/6550/13054 7908/6549/13141 7904/6683/13054 +f 6192/6405/13021 6183/6253/12878 6213/6252/12877 +f 6974/5830/12504 6973/6684/13254 6971/6378/12997 +f 6108/6685/13255 6109/6686/13256 6076/6193/12829 +f 6516/6687/13257 6404/6688/13257 6400/5925/13257 +f 5974/6689/13258 5915/6690/13259 5973/6691/13260 +f 7984/6460/13069 7996/6567/13154 7995/6692/13261 +f 7632/6431/13048 7554/6693/13262 7631/6343/12960 +f 7659/6694/12567 7655/5905/12567 7658/5904/12567 +f 7668/6695/13263 7666/6696/13264 7662/6697/12956 +f 6238/6511/13111 6036/6698/13265 6035/6699/13266 +f 7925/6700/13267 7927/6701/13268 7926/6702/13269 +f 5871/6703/13270 5872/6704/13271 5867/6589/13172 +f 6383/6142/12787 6381/6141/12786 6280/6680/13253 +f 7951/6705/13056 7936/6322/13056 7963/6706/13056 +f 6919/6707/13272 6922/6497/13273 6921/6708/13274 +f 5882/6709/13275 5883/5970/12626 5879/5931/12589 +f 7881/5955/12611 7879/6710/13276 7870/5801/12478 +f 6109/6686/13256 6112/6711/13277 6076/6193/12829 +f 6571/6149/13278 6570/6712/13279 6572/6713/13280 +f 6573/6150/12441 6576/6621/12441 6567/6714/12441 +f 7869/6715/13281 7879/6710/13276 7877/6716/13282 +f 6930/6612/13190 6902/6717/13283 6931/6718/13284 +f 7515/5885/12552 7414/6719/13285 7513/5886/12553 +f 6978/6720/13286 6880/6721/13287 6976/6722/13288 +f 6461/6381/13000 6478/6380/12999 6456/6723/13289 +f 5853/6283/12906 5755/5792/12471 5816/6724/13290 +f 7835/6303/13291 7834/6725/13292 7836/6008/13293 +f 6700/6294/12472 6696/6726/12472 6668/6295/12472 +f 7537/6583/13294 7416/6565/13294 7538/6727/13294 +f 6724/6728/13295 6725/6729/13296 6701/6730/13297 +f 6481/6559/13149 6452/6731/13298 6455/6220/13150 +f 6992/6433/13299 6993/6732/13299 6879/6733/13299 +f 6315/6734/13300 6314/6735/13301 6293/6736/13302 +f 6820/6737/13303 6837/6738/13304 6819/6739/13305 +f 5811/6740/13306 5797/6741/13307 5798/6742/13308 +f 7537/6583/13294 7418/6582/13294 7416/6565/13294 +f 6019/6743/13309 6189/6513/13113 6190/6512/13112 +f 6561/5758/13310 6560/6744/13311 6562/6745/13312 +f 6528/6746/13313 6618/6747/13314 6616/6508/13108 +f 6561/5758/13310 6558/5757/13315 6559/6748/13316 +f 7735/6749/13317 7717/5895/13318 7724/6395/13319 +f 6950/6750/13320 6940/6751/13321 6951/6752/13322 +f 6873/6012/13323 6755/6753/13323 6757/6013/13323 +f 6383/6142/12787 6387/6754/13324 6386/6755/13325 +f 5918/5908/12569 5917/6756/13326 5908/6757/13327 +f 6694/6758/13328 6668/6295/13329 6666/6759/13330 +f 7958/5846/13056 7941/6760/13056 7938/6761/13056 +f 5910/6762/13331 5961/6763/13332 5911/6764/13333 +f 7613/6765/13334 7612/6530/13124 7592/6529/13123 +f 6203/6438/13053 6202/6604/13183 6200/6766/13335 +f 6333/6767/13014 6334/6093/13014 6316/6768/13014 +f 6787/6002/12845 6786/6477/13336 6772/6286/12909 +f 6515/6483/13337 6408/6676/13337 6519/6084/13338 +f 6043/6769/13339 6044/6770/13340 6045/6771/13341 +f 7445/6442/12542 7478/6772/12542 7447/6443/12542 +f 6169/6665/13239 6244/6773/13342 6247/6375/12994 +f 6206/6774/13343 6225/5938/12596 6207/6262/12887 +f 5794/6775/13344 5817/6776/13345 5806/5968/12624 +f 7675/6333/12955 7737/6777/13346 7738/6778/13347 +f 7723/6393/13348 7727/6054/12701 7738/6778/13349 +f 6980/5815/12492 6979/6779/13350 6946/6780/13351 +f 5840/6320/12943 5838/6370/12988 5742/6781/13352 +f 6933/6782/13353 6937/6783/13354 6947/6784/13355 +f 7685/6785/13356 7714/6786/13357 7713/6041/13358 +f 6678/6592/12472 6707/5861/12472 6708/6787/12472 +f 6988/6257/12882 6889/6243/12872 6886/6255/12880 +f 6352/6090/13359 6351/6089/13216 6359/5879/12546 +f 7816/6788/13360 7811/6789/13361 7814/6790/13362 +f 6223/6263/12888 6224/6489/13089 5930/6791/13363 +f 5914/6611/13189 5870/6610/13188 5915/6690/13259 +f 5923/5805/12482 5988/5807/12484 5925/6792/13364 +f 6288/6793/13365 6287/6063/12709 6365/6794/13366 +f 5870/6610/13188 5873/6795/13367 5874/6796/13368 +f 6907/6797/13369 6905/6798/13370 6904/6799/13371 +f 6775/6800/13372 6797/6801/13373 6795/6802/13374 +f 6118/6803/13375 6122/6804/13376 6124/6805/13377 +f 5836/5742/12428 5835/5744/12430 5838/6370/12988 +f 6316/6768/13014 6318/6806/13014 6333/6767/13014 +f 5920/6807/13378 5922/6808/13379 6214/6387/13005 +f 6527/6437/13380 6637/6501/13380 6639/6436/13380 +f 7928/6237/13381 7927/6701/13268 7929/6472/13144 +f 7655/5905/13382 7541/5993/13382 7545/6231/13382 +f 7435/6809/12542 7433/6810/12542 7434/6811/12542 +f 7543/6812/13383 7637/6813/13384 7638/6814/13385 +f 6907/6797/12440 6942/5949/12440 6909/5769/12440 +f 7612/6530/13124 7651/6815/13386 7611/6816/13387 +f 7479/6817/13388 7498/6072/12718 7467/5873/13389 +f 6836/6818/13390 6837/6738/13304 6820/6737/13303 +f 7570/6819/13391 7571/6820/13392 7573/6821/13393 +f 5916/6822/13394 6231/6202/12835 6237/5826/12500 +f 7579/5765/13395 7560/6823/13396 7577/6824/13397 +f 5930/6791/13363 5861/6261/12886 6223/6263/12888 +f 6243/6825/13398 6160/6622/13201 6200/6766/13335 +f 7913/6826/13399 7911/6440/13054 7904/6683/13054 +f 6600/6127/12772 6601/6827/13400 6582/5838/13401 +f 6904/6799/13371 6905/6798/13370 6903/6828/13402 +f 6671/6296/12472 6674/5795/12472 6705/5794/12472 +f 7840/6673/13403 7841/6675/13404 7802/6829/13405 +f 6277/6601/12905 6284/6642/12905 6285/6830/13406 +f 6461/6381/13000 6460/6831/13407 6477/6379/12998 +f 6581/6832/12441 6580/5759/12441 6561/5758/12441 +f 6275/6681/12905 6278/6279/12904 6274/6281/12905 +f 7870/5801/13408 7846/6833/13409 7847/6834/13410 +f 7800/5988/12644 7798/6835/13411 7799/6350/12967 +f 7677/6836/13412 7686/6837/13413 7688/6838/13414 +f 6670/6839/13415 6669/6840/13416 6659/6841/13417 +f 6793/6842/13418 6794/6843/13419 6796/6844/13420 +f 6061/6845/13421 6060/6846/13422 6081/6203/12836 +f 6777/6847/12498 6776/6848/12498 6775/6800/12498 +f 6313/6607/13186 6312/6849/13423 6314/6735/13424 +f 7442/6850/13425 7429/6851/13426 7441/6678/13427 +f 6209/6163/12805 6211/6386/13004 6212/6852/13428 +f 6062/6853/13429 6061/6845/13421 6081/6203/12836 +f 5861/6261/12886 5931/6854/13430 6208/6573/13160 +f 6084/6855/13431 6083/6856/13432 6059/6857/13433 +f 7924/5883/12550 7950/5882/12549 7949/6518/13434 +f 5973/6691/13260 5915/6690/13259 5972/6858/13435 +f 6082/6190/12826 6071/6859/13436 6070/6860/13437 +f 7760/5775/12454 7762/6547/13139 7763/6861/13438 +f 5880/6862/13439 5881/6863/13440 5879/5931/12589 +f 6301/6451/13441 6300/6864/13442 6302/6865/13443 +f 6136/6866/13444 6138/6867/13445 6139/6868/13446 +f 6259/6869/13447 6263/6105/12749 6260/6870/13448 +f 7532/6871/13449 7486/6872/13450 7487/6873/13451 +f 7508/6399/13015 7510/5842/12513 7509/6874/13452 +f 6261/5914/12575 6260/6870/13448 6256/6875/13453 +f 7701/6876/12562 7724/6395/12562 7703/5897/12562 +f 6758/6344/12961 6769/6058/12705 6871/6877/13454 +f 6568/6878/13455 6567/6714/13456 6565/6184/13457 +f 6240/6879/13458 6239/6115/12760 6030/6880/13459 +f 6074/6881/13460 6143/6882/13461 6144/6883/13462 +f 5752/6884/13463 5817/6776/13464 5816/6724/13290 +f 6060/6846/13422 6073/6885/13465 6081/6203/12836 +f 6937/6783/13354 6948/5813/12490 6947/6784/13355 +f 6063/6886/13466 6062/6853/13429 6081/6203/12836 +f 7562/5748/12434 7588/6887/13467 7563/6888/13468 +f 6791/6639/12498 6822/6889/12498 6788/6004/12498 +f 7832/6890/13469 7830/6891/13470 7829/6892/13471 +f 6222/5937/12595 6221/6893/13472 6224/6489/13089 +f 5778/5951/12758 5776/5953/13473 5760/6112/12756 +f 6611/6894/13474 6612/6161/12803 6613/6160/12802 +f 7774/6895/13475 7732/6355/12972 7775/6896/13476 +f 6224/6489/13089 5929/6490/13090 5930/6791/13363 +f 6600/6127/13477 6614/6507/13107 6615/6506/13106 +f 6507/6897/13478 6505/6898/13479 6506/6899/13480 +f 6776/6848/13481 6801/6900/13482 6798/6011/13483 +f 6582/5838/13401 6602/6123/13484 6579/5839/13485 +f 6954/6137/12782 6939/6136/12781 6932/6901/13486 +f 5803/6411/13487 5805/6226/12856 5821/6225/12855 +f 6518/5922/12583 6517/6902/12583 6514/6085/12583 +f 6211/6386/13004 6209/6163/12805 5918/5908/12569 +f 7943/6903/13488 7940/5862/13489 7941/6760/13490 +f 6154/6456/13065 6156/6458/13067 6157/6904/13491 +f 6154/6456/13065 6157/6904/13491 6158/6905/13492 +f 6663/6906/13493 6679/6907/13494 6662/6488/13088 +f 7734/6485/13087 7717/5895/13318 7735/6749/13317 +f 6425/6908/13495 6426/6909/13496 6427/6219/13497 +f 6889/6243/12872 6956/6910/13498 6968/6244/12873 +f 6167/5865/12534 6180/5855/12524 6181/6911/13499 +f 7620/6662/13500 7635/6912/13501 7619/6145/12790 +f 5860/6310/12931 6011/6309/12930 6012/6913/13502 +f 5828/6914/13503 5820/6224/13504 5829/6915/13505 +f 6482/6916/13506 6450/6917/13507 6452/6731/13298 +f 5908/6757/13327 5917/6756/13326 5901/6074/12720 +f 6506/6899/13480 6405/6274/12899 6508/6204/12837 +f 5846/6918/13508 5848/6284/12907 5847/5973/12629 +f 7679/6209/12842 7678/6919/13509 7689/6920/13510 +f 7685/6785/13356 7686/6837/13511 7684/6921/13512 +f 7448/6922/13513 7446/6441/13514 7447/6443/13514 +f 7610/6079/12725 7650/6923/13515 7649/6077/12723 +f 6390/6318/12941 6344/6094/12940 6343/6924/13516 +f 5817/6776/13345 5818/5969/12625 5806/5968/12624 +f 5877/6615/13193 5878/6925/13517 5968/6616/13194 +f 5878/6925/13517 5880/6862/13439 5967/6926/13518 +f 6650/6927/12916 6649/6293/12916 6656/6292/12915 +f 6374/6359/12977 6376/5856/12525 6357/5858/12527 +f 5792/6928/12493 5795/6929/12493 5790/6930/12493 +f 6242/6931/13519 6244/6773/13342 6253/6932/13520 +f 6110/6933/13521 6102/6934/13522 6103/6935/13523 +f 6338/6936/13524 6328/6397/13525 6357/5858/12527 +f 5747/6937/13526 5745/6938/13527 5834/6939/13528 +f 7522/6228/12858 7523/6940/13529 7524/6941/13530 +f 5975/6086/12730 5915/6690/13259 5974/6689/13258 +f 6221/6893/13472 6188/6942/13531 6190/6512/13112 +f 8003/6943/13532 8006/6944/13533 7899/6945/13534 +f 6959/6946/13535 6966/6947/13536 6958/6948/13537 +f 6082/6190/12826 6081/6203/12836 6071/6859/13436 +f 6174/5854/12523 6260/6870/13448 6262/5913/12574 +f 6135/6949/13538 6129/5834/12508 6134/6950/13539 +f 7611/6816/13387 7650/6923/13515 7610/6079/12725 +f 6458/6951/12708 6457/6177/12708 6440/6176/12708 +f 7895/6952/13540 7794/6953/13540 7793/6954/13540 +f 6350/6955/13541 6337/6956/13542 6349/6957/13543 +f 5903/6958/13544 5906/6959/13545 5901/6074/12720 +f 7440/6677/12542 7471/6020/12542 7443/6960/12542 +f 6820/6737/12498 6819/6739/12498 6788/6004/12498 +f 5755/5792/12985 5749/5791/12470 5744/6961/12985 +f 6066/6962/13546 6067/6963/13547 6081/6203/12836 +f 5870/6610/13188 5969/6614/13192 5970/6964/13548 +f 7698/6965/12562 7723/6393/12562 7701/6876/12562 +f 7791/6966/13411 7787/6967/13411 7789/6968/13411 +f 5904/6969/13549 5905/5996/12651 5864/6170/12812 +f 6382/6138/12783 6384/6140/12785 6340/5928/12586 +f 6435/6098/12742 6434/6100/12744 6433/6970/12744 +f 7666/6696/13264 7760/5775/12454 7763/6861/13438 +f 7681/6971/13550 7677/6836/12692 7680/6208/12841 +f 6137/6972/13551 6138/6867/13445 6136/6866/13444 +f 5789/6973/13552 5763/6974/13553 5764/6299/12920 +f 6967/6975/13554 6968/6244/12873 6956/6910/13498 +f 6712/6563/13555 6697/6976/13556 6699/6564/13557 +f 6957/6977/13558 6956/6910/13498 6944/5770/13559 +f 7490/6270/12895 7505/6978/13560 7502/6979/13561 +f 7664/6980/13562 7661/6981/12956 7663/6327/12949 +f 7491/6982/13563 7501/6271/12896 7490/6270/12895 +f 7559/6983/13564 7572/6984/13565 7575/6985/13566 +f 6929/6613/13567 6892/5756/13568 6927/6986/13569 +f 7803/6987/13570 7817/6988/13571 7804/6989/13572 +f 7859/6423/13573 7858/6425/13574 7844/6009/13575 +f 5789/6973/13552 5787/6990/13553 5763/6974/13553 +f 6449/6991/12708 6463/6992/12708 6436/6099/12708 +f 5958/6993/13576 5960/6994/13577 5956/6223/12853 +f 7826/5919/12580 7827/6995/12580 7829/6892/13471 +f 7456/6516/13578 7433/6810/13579 7454/6629/13580 +f 7619/6145/13581 7598/6660/13234 7620/6662/13236 +f 5778/5951/12608 5780/6996/13582 5781/6577/13164 +f 6250/5964/12620 6155/6997/13583 6159/6624/13203 +f 5753/6998/13584 5858/6999/13585 5859/7000/13584 +f 6204/6164/12806 6209/6163/12805 6205/6495/13096 +f 5854/7001/13586 5741/7002/13586 5855/7003/13586 +f 6738/6557/13147 6739/7004/13587 6710/7005/13588 +f 6001/6389/13007 6010/7006/13589 5934/7007/13590 +f 6890/6323/13591 6891/6245/13591 6885/7008/13592 +f 5985/6222/12852 5911/6764/13333 5954/7009/13593 +f 6592/7010/13594 6591/7011/13595 6634/5852/12521 +f 7895/6952/13596 7893/7012/13596 7787/6967/13596 +f 7793/6954/13597 7797/7013/13598 7792/7014/13599 +f 6531/6250/12875 6530/7015/13600 6635/6251/12876 +f 7803/6987/13570 7813/5978/13601 7815/5980/13602 +f 6454/6337/13603 6466/7016/13604 6467/7017/13605 +f 6496/6015/12666 6497/7018/13606 6498/7019/13607 +f 6266/7020/13608 6267/7021/13609 6268/6447/13057 +f 5996/7022/13610 5994/7023/13611 5993/6467/13073 +f 6887/7024/13612 6882/6640/13591 6884/6434/13591 +f 7511/7025/13613 7509/6874/13452 7510/5842/12513 +f 5999/7026/13614 5997/7027/13615 5996/7022/13610 +f 5926/6575/13162 5928/7028/13616 5863/7029/13617 +f 5891/5909/12570 5978/7030/13618 5979/7031/13619 +f 5970/6964/13548 5971/7032/13620 5870/6610/13188 +f 6215/7033/13621 5922/6808/13379 5923/5805/12482 +f 6324/6001/13622 6323/6638/13623 6322/5999/13624 +f 7544/7034/12567 7550/7035/13625 7549/7036/13626 +f 6245/6373/12992 6200/6766/13335 6202/6604/13183 +f 5982/7037/13627 5983/7038/13628 5879/5931/12589 +f 5921/7039/13629 5918/5908/12569 5982/7037/13627 +f 6684/7040/13630 6685/7041/13631 6683/7042/13632 +f 6712/6563/13555 6713/6385/13633 6697/6976/13556 +f 6982/6658/13232 6949/6659/13233 6950/6750/13634 +f 6033/7043/13635 6168/6081/12727 6034/7044/13636 +f 6799/5824/12663 6796/6844/13420 6797/6801/13637 +f 6676/7045/13638 6673/7046/13639 6675/7047/13638 +f 7645/7048/13640 7607/7049/13641 7646/6618/13196 +f 5925/6792/13364 5989/7050/13642 5924/7051/13643 +f 5745/6938/13527 5835/5744/12430 5834/6939/13528 +f 5909/6364/12982 5889/6420/13036 5891/5909/12570 +f 6963/6415/13644 6934/7052/13645 6964/7053/13646 +f 5745/6938/13527 5742/6781/13352 5838/6370/12988 +f 6098/5774/12453 6100/7054/13647 6099/5772/12451 +f 6199/7055/13648 6029/7056/13649 6027/6065/12711 +f 6738/6557/13147 6645/6556/13146 6739/7004/13587 +f 6583/6128/12773 6600/6127/12772 6582/5838/13401 +f 5879/5931/12589 5921/7039/13629 5982/7037/13627 +f 6189/6513/13113 6019/6743/13309 6187/6404/13020 +f 6362/6289/12912 6348/6288/12911 6347/7057/13650 +f 6624/7058/13651 6625/7059/13652 6627/7060/13653 +f 6774/7061/13654 6794/6843/13655 6792/7062/13656 +f 7432/7063/13657 7450/7064/13658 7452/7065/13659 +f 6197/7066/13660 6201/6605/13184 6198/6067/12713 +f 6273/6682/12905 6279/6600/12905 6280/6680/13253 +f 7430/7067/13661 7429/6851/13426 7442/6850/13425 +f 7858/6425/13041 7888/7068/13662 7857/7069/13663 +f 5867/6589/13172 5868/7070/13664 5869/7071/13665 +f 6357/5858/12527 6356/7072/13666 6374/6359/12977 +f 7486/6872/13450 7472/6562/13667 7487/6873/13451 +f 8009/7073/13668 8007/7074/13669 8008/7075/13670 +f 6114/6034/12685 6115/7076/13671 6132/6635/13218 +f 7664/6980/13562 7773/7077/13672 7776/6106/12750 +f 6718/5859/12528 6717/7078/13673 6726/7079/13674 +f 6323/6638/13623 6321/6493/13094 6320/6382/13093 +f 6013/7080/13675 6014/7081/13676 6208/6573/13160 +f 6195/5877/12544 6020/5876/12543 6199/7055/13648 +f 5944/7082/13677 5945/7083/13678 5946/5916/12577 +f 7673/6334/13679 7668/6695/13679 7786/7084/13679 +f 6046/7085/13680 6050/7086/13681 6167/5865/12534 +f 6421/6068/12714 6441/6181/12817 6420/7087/13682 +f 7598/6660/12847 7568/7088/12847 7597/6246/12847 +f 6101/7089/13683 6110/6933/13521 6131/7090/13684 +f 6126/7091/13685 6133/7092/13686 6121/7093/13687 +f 7928/6237/13381 7926/6702/13269 7927/6701/13268 +f 6626/7094/13688 6627/7060/13653 6625/7059/13652 +f 6704/5793/13689 6723/7095/13690 6705/5794/13691 +f 6133/7092/13686 6134/6950/13539 6119/7096/13692 +f 6838/5797/13693 6839/7097/13694 6819/6739/13305 +f 6688/6266/12891 6689/6265/12890 6687/7098/13695 +f 7904/6683/13696 8017/7099/13696 8016/7100/13696 +f 7954/6410/13026 7969/6409/13025 7955/6654/13228 +f 7670/6108/12752 7779/6326/12948 7669/7101/13697 +f 6530/7015/13600 6593/7102/13698 6636/5851/12520 +f 6692/7103/13699 6690/6264/12889 6691/6240/13051 +f 6254/5915/12576 6228/6609/13187 6158/6905/13492 +f 7886/7104/13700 7857/7069/13663 7888/7068/13662 +f 6523/7105/13701 6522/7106/13702 6626/7094/13688 +f 5855/7003/12985 5859/7000/12984 5858/6999/12985 +f 6523/7105/13701 6526/7107/13703 6521/6500/12683 +f 6154/6456/13065 6158/6905/13492 6228/6609/13187 +f 6548/7108/13704 6546/7109/13705 6536/7110/13706 +f 7723/6393/12562 7698/6965/12562 7696/7111/12562 +f 5833/5743/12429 5827/5957/12613 5824/6631/13212 +f 6059/6857/13433 6066/6962/13546 6081/6203/12836 +f 7795/5986/12642 7880/7112/13707 7790/5954/12610 +f 7559/6983/13564 7556/6426/12847 7558/7113/12847 +f 6750/7114/13708 6650/6927/13709 6643/7115/13708 +f 6955/7116/13710 6944/5770/13559 6956/6910/13498 +f 6462/6062/13711 6475/7117/13712 6476/7118/13713 +f 6716/6348/12965 6715/7119/13714 6746/7120/13715 +f 6226/7121/13716 6084/6855/13431 6059/6857/13433 +f 6422/7122/12708 6421/6068/12708 6415/7123/12708 +f 7422/7124/13717 7524/6941/13530 7528/6167/12809 +f 6215/7033/13621 6214/6387/13005 5922/6808/13379 +f 6117/7125/13718 6125/7126/13719 6115/7076/13671 +f 6292/6429/13046 6291/6119/13014 6295/6384/13014 +f 6250/5964/12620 6159/6624/13203 6252/6623/13202 +f 6164/7127/13720 6045/6771/13721 6181/6911/13499 +f 6534/6030/12681 6533/6159/12801 6612/6161/12803 +f 6676/7045/13722 6675/7047/13722 6677/7128/13722 +f 6136/6866/13444 6129/5834/12508 6135/6949/13538 +f 6595/6520/13723 6596/5947/13206 6584/6625/13205 +f 5972/6858/13435 5870/6610/13188 5971/7032/13620 +f 6090/7129/13724 6091/7130/13725 6070/6860/13437 +f 6225/5938/12596 6206/6774/13343 6017/5820/12496 +f 6492/7131/13726 6494/7132/13727 6478/6380/12999 +f 6588/7133/13728 6587/7134/13729 6628/7135/13730 +f 5800/5818/12494 5796/7136/12493 5766/6626/12493 +f 7709/7137/13731 7708/7138/13731 7707/7139/13732 +f 7488/7140/13733 7473/6179/13734 7465/7141/13735 +f 7606/5837/12511 7643/7142/13736 7642/5835/12509 +f 7747/7143/13737 7764/7144/13738 7762/6547/13139 +f 7953/6517/13739 7983/7145/13740 7956/5868/12537 +f 6420/7087/13682 6439/7146/13741 6437/7147/13742 +f 6079/7148/13743 5911/6764/13333 6080/7149/13744 +f 7489/7150/13745 7502/6979/13561 7503/7151/13746 +f 6078/7152/13747 6232/6022/12673 6077/7153/13748 +f 6912/6369/13749 6915/7154/13750 6914/6368/13751 +f 6080/7149/13744 5911/6764/13333 6232/6022/12673 +f 5887/5933/12591 5888/7155/13752 5885/6645/13223 +f 6081/6203/12836 6230/7156/13753 6229/6603/13182 +f 7587/7157/13754 7586/6213/13755 7589/6554/13756 +f 6472/7158/13757 6513/7159/13758 6486/7160/13759 +f 5870/6610/13188 5874/6796/13368 5875/7161/13760 +f 6954/6137/12782 6932/6901/13486 6955/7116/13710 +f 5993/6467/13073 5951/6469/13075 5946/5916/12577 +f 6227/7162/13761 6261/5914/12575 6256/6875/13453 +f 6075/6035/12686 6146/7163/13762 6147/7164/13763 +f 6269/6538/13764 6271/7165/13765 6272/6539/13766 +f 6919/6707/13767 6898/5755/13768 6918/7166/13769 +f 6287/6063/12905 6288/6793/13365 6284/6642/12905 +f 7913/6826/13399 7912/7167/13054 7911/6440/13054 +f 7963/6706/13770 7975/6024/12675 7951/6705/13771 +f 6281/6280/12905 6287/6063/12905 6284/6642/12905 +f 6685/7041/13631 6682/7168/13772 6683/7042/13632 +f 6798/6011/13483 6797/6801/13373 6775/6800/13372 +f 7839/5761/12443 7837/5760/12442 7836/6008/13293 +f 6101/7089/13683 6131/7090/13684 6130/7169/13773 +f 6980/5815/12492 6947/6784/13774 6948/5813/12490 +f 6289/7170/13775 6297/7171/13776 6324/6001/12656 +f 6214/6387/13005 6215/7033/13621 6213/6252/12877 +f 6556/7172/12441 6584/6625/12441 6554/6647/12441 +f 5747/6937/13526 5751/6365/12984 5748/6367/12984 +f 5879/5931/12589 5920/6807/13378 5921/7039/13629 +f 6822/6889/13777 6835/7173/13778 6820/6737/13303 +f 6186/7174/13779 6023/7175/13780 6020/5876/12543 +f 6471/7176/13781 6470/7177/13782 6510/7178/13783 +f 6240/6879/13458 6032/7179/13784 6238/6511/13111 +f 6238/6511/13111 6032/7179/13784 6036/6698/13265 +f 6264/6537/13131 6083/6856/13432 6084/6855/13431 +f 7659/6694/13785 7658/5904/13785 7544/7034/13785 +f 6512/7180/13786 6487/7181/13787 6513/7159/13758 +f 6119/7096/13692 6120/7182/13788 6133/7092/13686 +f 7666/6696/13264 7766/6328/12950 7663/6327/12949 +f 7594/6248/13789 7623/7183/13790 7622/7184/13791 +f 6168/6081/12727 6035/6699/13266 6034/7044/13636 +f 7876/5786/12465 7875/5785/12464 7800/5988/12644 +f 6123/7185/13792 6124/6805/13377 6125/7126/13719 +f 6292/6429/13046 6306/6117/12762 6291/6119/12764 +f 6780/7186/12498 6783/7187/12498 6815/7188/12498 +f 5881/6863/13440 5882/6709/13275 5879/5931/12589 +f 6211/6386/13004 6213/6252/12877 6212/6852/13428 +f 6317/7189/13793 6320/6382/13093 6319/6494/13095 +f 6268/6447/13057 6269/6538/13132 6264/6537/13131 +f 7749/7190/13794 7766/6328/12950 7765/7191/13795 +f 6119/7096/13692 6129/5834/12508 6127/7192/13796 +f 6615/6506/13106 6617/6124/12769 6602/6123/12768 +f 6936/7193/13797 6925/6480/12440 6935/6496/12440 +f 5875/7161/13760 5876/7194/13798 5969/6614/13192 +f 6622/7195/13799 6621/7196/13800 6618/6747/13314 +f 5962/7197/13801 5963/7198/13802 5911/6764/13333 +f 6934/7052/12440 6902/6717/12440 6930/6612/12440 +f 7587/7157/13803 7588/6887/13467 7562/5748/12434 +f 7693/7199/13804 7691/6207/13804 7692/6044/13804 +f 5759/6552/13805 5774/6154/13806 5771/6156/13807 +f 6134/6950/13539 6129/5834/12508 6119/7096/13692 +f 6210/6083/12729 6209/6163/12805 6212/6852/13428 +f 6816/7200/13808 6813/6416/13032 6828/7201/13809 +f 6814/6417/13033 6825/6152/13810 6826/7202/13811 +f 5923/5805/12482 6216/6586/13169 6215/7033/13621 +f 6823/7203/13812 6842/5889/12556 6856/7204/13813 +f 7705/5896/13814 7702/6534/13815 7703/5897/13815 +f 6357/5858/12527 6331/5903/12566 6356/7072/13816 +f 5823/6630/13211 5804/5817/13817 5822/6371/12989 +f 6606/6454/13818 6622/7195/13799 6623/7205/13819 +f 7752/7206/13820 7739/6053/13821 7740/6052/13822 +f 6043/6769/13823 6045/6771/13721 6164/7127/13720 +f 6165/7207/13824 6265/7208/13825 6266/7020/13608 +f 7635/6912/13501 7636/7209/13826 7634/6432/13049 +f 6448/6580/13827 6423/7210/13828 6424/6218/13829 +f 7855/7211/13830 7845/6007/13831 7856/7212/13832 +f 6470/7177/13782 6469/6205/12838 6509/7213/13833 +f 6257/6104/12748 6258/6103/13834 6256/6875/13453 +f 6097/5773/12452 6096/6191/12827 6098/5774/12453 +f 5918/5908/12569 5919/6162/12804 5917/6756/13326 +f 6255/6657/13231 6226/7121/13716 6256/6875/13453 +f 6233/6023/12674 6074/6881/13460 6232/6022/12673 +f 6261/5914/12575 6228/6609/13187 6254/5915/12576 +f 6743/7214/13835 6741/5752/12438 6742/7215/13836 +f 6215/7033/13621 6216/6586/13169 6217/6587/13170 +f 5972/6858/13435 5915/6690/13259 5870/6610/13188 +f 6257/6104/12748 6256/6875/13453 6260/6870/13448 +f 7895/6952/13540 7793/6954/13540 7896/7216/13540 +f 7414/6719/13285 7517/6071/12717 7518/7217/13837 +f 6259/6869/13838 6260/6870/13838 6174/5854/13838 +f 6081/6203/12836 6226/7121/13716 6059/6857/13433 +f 6091/7130/13725 6082/6190/12826 6070/6860/13437 +f 6364/7218/13839 6285/6830/13406 6288/6793/13365 +f 7975/6024/12675 7963/6706/13770 7976/6532/13126 +f 6432/5935/12708 6460/6831/12708 6430/5936/12708 +f 6152/6319/12942 6270/7219/13840 6165/7207/13824 +f 6165/7207/13824 6270/7219/13840 6265/7208/13825 +f 7503/7151/13746 7488/7140/13841 7489/7150/13745 +f 6241/7220/13842 6246/6374/12993 6201/6605/13184 +f 6068/6217/12850 6090/7129/13724 6069/7221/13843 +f 5995/6595/13176 5996/7022/13610 5993/6467/13073 +f 6117/7125/13718 6123/7185/13792 6125/7126/13719 +f 6814/6417/12498 6813/6416/12498 6804/5943/12498 +f 7833/7222/13292 7831/7223/13844 7832/6890/13469 +f 5906/6959/13545 5907/7224/13845 5901/6074/12720 +f 6834/7225/13846 6847/7226/13847 6769/6058/12705 +f 6362/6289/12912 6393/6505/13102 6363/6504/13101 +f 6133/7092/13686 6120/7182/13788 6121/7093/13687 +f 6057/7227/13848 6058/7228/13849 6083/6856/13432 +f 6634/5852/12521 6591/7011/13595 6633/5850/12519 +f 6267/7021/13850 6270/7219/13850 6271/7165/13850 +f 6466/7016/13604 6454/6337/13603 6451/6336/13851 +f 6665/6486/13852 6658/6238/12867 6691/6240/12869 +f 6152/6319/13853 6271/7165/13853 6270/7219/13853 +f 6216/6586/13169 5925/6792/13364 5924/7051/13643 +f 6272/6539/13854 6057/7227/13848 6083/6856/13432 +f 6272/6539/13855 6083/6856/13855 6264/6537/13855 +f 5876/7194/13798 5877/6615/13193 5969/6614/13192 +f 6798/6011/13483 6775/6800/13372 6776/6848/13481 +f 6758/6344/12961 6763/6412/13028 6759/7229/12962 +f 6577/7230/13856 6576/6621/13200 6590/7231/13857 +f 7484/7232/13858 7483/7233/13859 7468/7234/13860 +f 8000/6277/12902 8001/5961/12617 7999/5963/12619 +f 5925/6792/13364 5988/5807/12484 5989/7050/13642 +f 6391/6357/12974 6393/6505/13102 6346/6267/12975 +f 7681/6971/13550 7680/6208/12841 7695/7235/13861 +f 6313/6607/13014 6316/6768/13014 6334/6093/13014 +f 7688/6838/13862 7690/7236/13863 7689/6920/13864 +f 6876/7237/12962 6875/7238/12962 6872/7239/12962 +f 6683/7042/13865 6663/6906/13493 6684/7040/13866 +f 6646/7240/13867 6645/6556/13146 6737/6558/13148 +f 6429/5934/12592 6431/7241/12593 6432/5935/12593 +f 7661/6981/13868 7783/7242/13868 7781/7243/13868 +f 7505/6978/13560 7425/7244/13869 7504/7245/13870 +f 7753/7246/13871 7754/6122/12767 7751/6121/12766 +f 6223/6263/12888 6225/5938/12596 6222/5937/12595 +f 6244/6773/13342 6243/6825/13398 6245/6373/12992 +f 7907/6551/13872 8009/7073/13668 7908/6549/13141 +f 5997/7027/13615 5862/7247/13873 5930/6791/13363 +f 7706/7248/13874 7682/6536/13130 7704/6535/13129 +f 6165/7207/13824 6176/7249/13875 6166/5866/12535 +f 6427/6219/12708 6430/5936/12708 6456/6723/12708 +f 6933/6782/13353 6945/7250/13876 6934/7052/13645 +f 6299/6398/13877 6300/6864/13442 6301/6451/13441 +f 7963/6706/13056 7934/5983/13056 7964/6533/13056 +f 5795/6929/13878 5808/5778/13879 5809/6528/13880 +f 6067/6963/13547 6065/7251/13881 6081/6203/12836 +f 7964/6533/13056 7932/6471/13056 7962/5782/13056 +f 6082/6190/12826 6091/7130/13725 6095/7252/13882 +f 6456/6723/12708 6455/6220/12708 6427/6219/12708 +f 5987/5806/12483 5885/6645/13223 5867/6589/13172 +f 6803/5944/13883 6801/6900/13482 6776/6848/13481 +f 7538/6727/12862 7535/6584/12862 7537/6583/12862 +f 7602/7253/13884 7598/6660/13234 7619/6145/13581 +f 6720/6272/13885 6721/7254/13886 6706/7255/13887 +f 6574/6455/13064 6586/7256/13888 6587/7134/13889 +f 6208/6573/13160 6014/7081/13676 6015/7257/13890 +f 5928/7028/13616 5929/6490/13090 5863/7029/13617 +f 7573/6821/12847 7571/6820/12847 7602/7253/12847 +f 7835/6303/13291 7833/7222/13292 7834/6725/13292 +f 6193/6254/12879 6194/7258/13891 6212/6852/13428 +f 7847/6834/12518 7812/7259/12518 7843/6249/12518 +f 6750/7114/13708 6643/7115/13708 6748/7260/13708 +f 7476/7261/13892 7471/6020/12671 7494/6019/12670 +f 6042/6046/12693 6047/7262/13893 6164/7127/13720 +f 6160/6622/13201 6159/6624/13203 6161/7263/13894 +f 6626/7094/13688 6623/7205/13819 6523/7105/13701 +f 6194/7258/13891 6193/6254/12879 6186/7174/13779 +f 7546/6230/12860 7644/6037/12688 7645/7048/13640 +f 7563/6888/13468 7564/6543/13895 7555/7264/13895 +f 7900/7265/13054 7907/6551/13054 7905/6550/13054 +f 6772/6286/12498 6771/6109/12498 6777/6847/12498 +f 5785/5893/13896 5784/6466/13897 5783/5894/13898 +f 7725/7266/12562 7690/7236/12562 7722/7267/12562 +f 5885/6645/13223 5879/5931/12589 5887/5933/12591 +f 5819/5967/12623 5805/6226/12856 5806/5968/12624 +f 7842/7268/13899 7863/5911/12572 7862/7269/13900 +f 5930/6791/13363 5929/6490/13090 5928/7028/13616 +f 6510/7178/13783 6470/7177/13782 6509/7213/13833 +f 7700/7270/13901 7699/7271/13902 7701/6876/13903 +f 6112/6711/13277 6111/6670/13242 6076/6193/12829 +f 5752/6884/12985 5755/5792/12985 5753/6998/12985 +f 6696/6726/13904 6709/7272/13905 6710/7005/13906 +f 7962/5782/13056 7932/6471/13056 7959/6470/13056 +f 7419/7273/13907 7411/7274/12862 7413/6229/12862 +f 6955/7116/13908 6956/6910/13498 6889/6243/12872 +f 5768/7275/12494 5769/5816/12493 5800/5818/12494 +f 7443/6960/12542 7476/7261/12542 7445/6442/12542 +f 5864/6170/12812 5898/6172/12814 5904/6969/13549 +f 6248/5965/12621 6262/5913/12574 6254/5915/12576 +f 6239/6115/12760 6247/6375/12994 6241/7220/13842 +f 7662/6697/13909 7786/7084/13909 7668/6695/13909 +f 7967/6656/13910 8001/5961/12617 7966/6276/12901 +f 7667/7276/12956 7670/6108/12752 7665/6332/12954 +f 6714/5812/13911 6697/6976/13556 6713/6385/13633 +f 6723/7095/13690 6724/6728/13295 6705/5794/13691 +f 6711/5753/12439 6710/7005/13588 6739/7004/13587 +f 5800/5818/12494 5766/6626/12493 5768/7275/12494 +f 6365/6794/13366 6360/6633/13215 6349/6957/13543 +f 6218/6198/12834 6216/6586/13169 5924/7051/13643 +f 6775/6800/12498 6774/7061/12498 6777/6847/12498 +f 6220/6196/12832 6218/6198/12834 5863/7029/13617 +f 5869/7071/13665 5873/6795/13367 5870/6610/13188 +f 6233/6023/12674 6234/6018/12669 6139/6868/13446 +f 7957/5994/12649 7971/7277/13912 7970/6408/13024 +f 6245/6373/12992 6243/6825/13398 6200/6766/13335 +f 6774/7061/12498 6772/6286/12498 6777/6847/12498 +f 7715/6042/12562 7711/7278/12562 7720/6354/12562 +f 6172/6422/13038 6177/6048/12695 6178/6242/12871 +f 8019/6644/13054 8014/7279/13054 8018/7280/13054 +f 6826/7202/13913 6825/6152/12795 6862/6153/12796 +f 6560/6744/13914 6559/6748/13915 6540/7281/13916 +f 5794/6775/12493 5779/6578/12493 5781/6577/12493 +f 6247/6375/12994 6246/6374/12993 6241/7220/13842 +f 6919/6707/13272 6920/7282/13917 6922/6497/13273 +f 6905/6798/13918 6906/7283/13919 6894/5974/13920 +f 6900/7284/13921 6927/6986/13569 6892/5756/13568 +f 7424/6523/12862 7416/6565/12862 7425/7244/13869 +f 6153/6457/13066 5916/6822/13394 5864/6170/12812 +f 7711/7278/13922 7708/7138/13731 7709/7137/13731 +f 7790/5954/12610 7880/7112/13707 7881/5955/12611 +f 7805/7285/13923 7820/7286/13924 7822/7287/13925 +f 6679/6907/13926 6682/7168/13772 6680/6593/13926 +f 6761/6014/12962 6764/7288/12962 6765/6059/12962 +f 6168/6081/12727 6169/6665/13239 6238/6511/13111 +f 7505/6978/13560 7490/6270/12895 7506/6269/12894 +f 6065/7251/13881 6064/7289/13927 6081/6203/12836 +f 6800/6010/12498 6816/7200/12498 6817/5822/12498 +f 7412/6233/13928 7535/6584/13928 7536/7290/13928 +f 7465/7141/12542 7447/6443/12542 7478/6772/12542 +f 7594/6248/12847 7565/7291/12847 7593/7292/12847 +f 6420/7087/12708 6419/7293/12708 6415/7123/12708 +f 6520/6502/12683 6522/7106/13702 6523/7105/13701 +f 6759/7229/13929 6874/7294/13929 6875/7238/13929 +f 5924/7051/13643 5927/7295/13930 6218/6198/12834 +f 6380/5930/12588 6339/5929/12587 6338/6936/13524 +f 7609/6078/12724 7648/6617/13195 7608/6619/13197 +f 6977/7296/13931 6975/5832/12506 6964/7053/13932 +f 7603/7297/13933 7617/5941/12599 7616/5940/12598 +f 7969/6409/13934 8005/7298/13935 7968/6655/13936 +f 7797/7013/13598 7794/6953/13411 7791/6966/13411 +f 5991/7299/13937 5992/6574/13161 5990/6576/13163 +f 6834/7225/13846 6846/6352/12969 6847/7226/13847 +f 7864/5910/13938 7875/5785/12464 7872/6005/12660 +f 5786/6464/12493 5788/7300/12493 5797/6741/12493 +f 6773/6210/12843 6774/7061/13654 6790/7301/13939 +f 6756/7302/13940 6754/7303/13941 6860/7304/13942 +f 5815/6571/13943 5816/6724/13944 5794/6775/13344 +f 7953/6517/13739 7965/6278/12903 7984/6460/13069 +f 6555/5745/13945 6554/6647/13946 6553/5746/13946 +f 6812/5890/12498 6811/6666/12498 6808/6667/12498 +f 5821/6225/13947 5828/6914/13503 5831/7305/13948 +f 7862/7269/13900 7873/6006/12661 7892/7306/13949 +f 7575/6985/13566 7577/6824/13397 7559/6983/13564 +f 7514/7307/13950 7511/7025/13613 7495/6021/13951 +f 5802/7308/13952 5814/6572/13953 5815/6571/13943 +f 7829/6892/13471 7830/6891/13470 7828/7309/13954 +f 6806/6585/12498 6814/6417/12498 6804/5943/12498 +f 6671/6296/13955 6668/6295/13329 6669/6840/13956 +f 6212/6852/13428 6213/6252/12877 6193/6254/12879 +f 7902/7310/13957 8014/7279/13957 8015/7311/13957 +f 7990/7312/13958 7978/5783/13959 7979/7313/13960 +f 7516/6073/12719 7519/7314/13961 7517/6071/12717 +f 6780/7186/12498 6812/5890/12498 6808/6667/12498 +f 7992/6187/12823 7980/6189/12825 7981/5867/12536 +f 5747/6937/13526 5748/6367/12984 5741/7002/12984 +f 5941/7315/13962 5942/6314/12934 6000/6316/12936 +f 7436/7316/13963 7440/6677/13250 7438/7317/13964 +f 6146/7163/13762 6075/6035/12686 6145/7318/13965 +f 5800/5818/13213 5804/5817/13817 5823/6630/13211 +f 7583/6214/13966 7586/6213/13755 7584/7319/13967 +f 6019/6743/13309 6022/6391/13009 6187/6404/13020 +f 5848/6284/12907 5853/6283/12906 5851/6570/13157 +f 7964/6533/13127 7962/5782/12461 7977/5781/12460 +f 7742/7320/13968 7754/6122/12767 7741/6396/13969 +f 6818/5823/13970 6817/5822/13971 6830/7321/13972 +f 6056/7322/13973 6271/7165/13974 6055/7323/13975 +f 7523/6940/13529 7481/6029/13976 7525/7324/13977 +f 6457/6177/12708 6449/6991/12708 6438/6175/12708 +f 5913/5827/12501 5984/5829/12503 5870/6610/13188 +f 7901/6568/13155 7996/6567/13154 7997/7325/13978 +f 5776/5953/13979 5775/7326/13980 5774/6154/12797 +f 6661/7327/13981 6675/7047/13982 6673/7046/13983 +f 7462/6462/13243 7463/5874/13984 7464/6463/13985 +f 6744/5810/12487 6742/7215/13836 6647/6101/12745 +f 6987/6256/12881 6984/6664/13238 6986/7328/13986 +f 6099/5772/12451 6101/7089/13683 6236/5825/12499 +f 6986/7328/13986 6988/6257/12882 6987/6256/12881 +f 6149/7329/13987 6150/7330/13988 6051/7331/13989 +f 6413/6211/12846 6490/6097/12741 6488/6096/12740 +f 6901/7332/13990 6902/6717/13283 6904/6799/13371 +f 6453/6201/13991 6469/6205/13992 6458/6951/13993 +f 6252/6623/13202 6253/6932/13520 6251/6130/12775 +f 6364/7218/13839 6288/6793/13365 6365/6794/13366 +f 6275/6681/13994 6280/6680/13253 6381/6141/12786 +f 7662/6697/13995 7661/6981/13995 7781/7243/13995 +f 6232/6022/12673 5911/6764/13333 5912/5828/12502 +f 6020/5876/12543 6194/7258/13891 6186/7174/13779 +f 6831/6298/12918 6830/7321/13972 6844/5989/12645 +f 6833/6351/12968 6834/7225/13846 6821/7333/13996 +f 6460/6831/12708 6461/6381/12708 6430/5936/12708 +f 6139/6868/13446 6138/6867/13445 6140/7334/13997 +f 6668/6295/13329 6667/7335/13998 6669/6840/13956 +f 6603/7336/13999 6604/7337/14000 6579/5839/13485 +f 6602/6123/12768 6601/6827/14001 6615/6506/13106 +f 7904/6683/13696 8016/7100/13696 7905/6550/13696 +f 7869/6715/13281 7877/6716/13282 7868/7338/14002 +f 6148/7339/14003 6051/7331/13989 6167/5865/12534 +f 6697/6976/12472 6702/7340/12472 6687/7098/12472 +f 5795/6929/13878 5809/6528/13880 5799/7341/14004 +f 7415/6403/13019 7531/7342/14005 7532/6871/13449 +f 6772/6286/12909 6773/6210/12843 6787/6002/12845 +f 6768/7343/14006 6763/6412/13028 6867/5990/12646 +f 7577/6824/14007 7575/6985/14008 7576/7344/14009 +f 6355/5902/14010 6373/6360/12978 6374/6359/12977 +f 6163/5998/12653 6155/6997/13583 6156/6458/13067 +f 7429/6851/12542 7427/6461/12542 7428/7345/14011 +f 6537/7346/14012 6548/7108/13704 6536/7110/13706 +f 6721/7254/14013 6720/6272/12897 6657/7347/14014 +f 6949/6659/13233 6935/6496/14015 6950/6750/13320 +f 6901/7332/14016 6893/5754/14017 6892/5756/13568 +f 7878/7348/14018 7879/6710/13276 7880/7112/13707 +f 7736/6394/14019 7723/6393/13348 7737/6777/14020 +f 6674/5795/14021 6671/6296/13955 6672/7349/14022 +f 7445/6442/14023 7442/6850/14024 7443/6960/14025 +f 7496/6599/13180 7470/6598/13179 7497/7350/14026 +f 5990/6576/13163 5986/7351/14027 5959/6221/12851 +f 6872/7239/12962 6873/6012/12962 6877/7352/12962 +f 5870/6610/13188 5984/5829/12503 5867/6589/13172 +f 6895/7353/14028 6906/7283/13919 6908/7354/14029 +f 7674/5871/12540 7672/7355/13263 7668/6695/13263 +f 7968/6655/13229 7955/6654/13228 7969/6409/13025 +f 7899/6945/13534 8006/6944/13533 7907/6551/13872 +f 7856/7212/13832 7884/7356/14030 7855/7211/14031 +f 6976/6722/13288 6977/7296/13931 6978/6720/13286 +f 6896/5976/12440 6894/5974/12440 6895/7353/12800 +f 7623/7183/13790 7593/7292/14032 7605/5836/14033 +f 5817/6776/13464 5752/6884/13463 5818/5969/12625 +f 7547/6430/13047 7637/6813/13384 7543/6812/13383 +f 6768/7343/12962 6762/7357/12962 6760/7358/12962 +f 7492/7359/14034 7501/6271/12896 7491/6982/13563 +f 6527/6437/12683 6525/6031/12682 6531/6250/12875 +f 7719/7360/14035 7717/5895/13318 7734/6485/13087 +f 5819/5967/12623 5818/5969/12625 5829/6915/13505 +f 6514/6085/12583 6515/6483/12583 6519/6084/12583 +f 6157/6904/13491 6156/6458/13067 6249/5966/12622 +f 7414/6719/13285 7515/5885/12552 7517/6071/12717 +f 6498/7019/13607 6500/7361/14036 6482/6916/14037 +f 5832/6372/12991 5823/6630/13211 5822/6371/12989 +f 6664/6487/14038 6686/7362/14039 6684/7040/13866 +f 7740/6052/12699 7727/6054/12701 7728/6043/13012 +f 7423/7363/12862 7421/6525/12862 7426/6524/13119 +f 6130/7169/13773 6128/7364/14040 6129/5834/12508 +f 7564/6543/13895 7567/7365/14041 7556/6426/13042 +f 6580/5759/12441 6584/6625/12441 6556/7172/12441 +f 7637/6813/13384 7636/7209/13826 7621/6661/14042 +f 6089/6216/12849 6090/7129/13724 6068/6217/12850 +f 7599/6531/12847 7580/5764/12847 7592/6529/12847 +f 7618/6147/12792 7602/7253/13884 7619/6145/13581 +f 6412/7366/14043 6413/6211/12846 6488/6096/12740 +f 6679/6907/13926 6681/7367/14044 6682/7168/13772 +f 7480/6027/14045 7521/7368/14046 7479/6817/13388 +f 6960/5948/14047 6970/6377/12996 6888/7369/14048 +f 6938/5995/12440 6902/6717/12440 6934/7052/12440 +f 6316/6768/14049 6313/6607/13186 6314/6735/13424 +f 5931/6854/13430 5861/6261/12886 5862/7247/13873 +f 6283/6064/12710 6371/6358/12976 6370/7370/14050 +f 6627/7060/13653 6630/7371/14051 6588/7133/13728 +f 5994/7023/13611 5930/6791/13363 5928/7028/13616 +f 5884/6590/13173 5867/6589/13172 5888/7155/13752 +f 6555/5745/13945 6556/7172/13945 6554/6647/13946 +f 7448/6922/13513 7449/6178/13513 7451/6180/14052 +f 7682/6536/13130 7706/7248/13874 7683/7372/14053 +f 5955/7373/14054 5956/6223/12853 5985/6222/12852 +f 6889/6243/12872 6954/6137/12782 6955/7116/13908 +f 6298/7374/14055 6297/7171/13776 6289/7170/13775 +f 5748/6367/14056 5859/7000/14056 5855/7003/14056 +f 7616/5940/12598 7615/7375/14057 7601/7376/14058 +f 7893/7012/13411 7898/7377/13411 7894/7378/13411 +f 6324/6001/13622 6325/6636/14059 6323/6638/13623 +f 6586/7256/14060 6606/6454/13818 6624/7058/13651 +f 6257/6104/12748 6260/6870/13448 6263/6105/12749 +f 6015/7257/13890 6016/7379/14061 6206/6774/13343 +f 7800/5988/12644 7875/5785/12464 7865/7380/14062 +f 6224/6489/13089 6223/6263/12888 6222/5937/12595 +f 6675/7047/13982 6661/7327/13981 6662/6488/13088 +f 7701/6876/13903 7699/7271/13902 7698/6965/14063 +f 5982/7037/13627 5918/5908/12569 5981/7381/14064 +f 6358/6498/13097 6385/6139/12784 6342/7382/14065 +f 6606/6454/13063 6586/7256/13888 6574/6455/13064 +f 6547/5891/14066 6548/7108/14067 6549/5840/14068 +f 7630/6363/12981 7615/7375/14057 7631/6343/12960 +f 6605/7383/14069 6606/6454/13063 6578/6453/13062 +f 7691/6207/12840 7693/7199/14070 7680/6208/12841 +f 7907/6551/13054 7900/7265/13054 7899/6945/13054 +f 7435/6809/14071 7462/6462/13071 7427/6461/13070 +f 6934/7052/14072 6963/6415/13031 6938/5995/12650 +f 6415/7123/12708 6414/6579/12708 6422/7122/12708 +f 6780/7186/14073 6779/6111/14074 6781/6110/14075 +f 5915/6690/13259 5975/6086/12730 5865/6171/12813 +f 5792/6928/14076 5793/7384/14077 5766/6626/13207 +f 6284/6642/12905 6288/6793/13365 6285/6830/13406 +f 6175/6129/12774 6173/6131/12776 6178/6242/12871 +f 7761/7385/14078 7760/5775/12454 7759/7386/14079 +f 7790/5954/12610 7882/5800/12477 7789/6968/14080 +f 6222/5937/12595 6184/5819/12495 6188/6942/13531 +f 7627/6362/12980 7613/6765/13334 7614/7387/14081 +f 7609/6078/14082 7595/7388/14083 7610/6079/14084 +f 6334/6093/13014 6326/6268/13014 6313/6607/13014 +f 6186/7174/13779 6021/6392/13010 6023/7175/13780 +f 7415/6403/13019 7532/6871/13449 7533/6401/13017 +f 6254/5915/12576 6249/5966/12622 6248/5965/12621 +f 7512/5887/12554 7511/7025/13613 7514/7307/13950 +f 6852/6165/12807 6841/5888/12555 6840/7389/14085 +f 6375/5857/12526 6380/5930/12588 6338/6936/13524 +f 6231/6202/12835 6230/7156/13753 6081/6203/12836 +f 6315/6734/14086 6316/6768/14049 6314/6735/13424 +f 6204/6164/12806 6205/6495/13096 6195/5877/12544 +f 7464/6463/13985 7437/7390/14087 7436/7316/13963 +f 6171/7391/14088 6170/7392/14089 6177/6048/12695 +f 5853/6283/12906 5852/7393/14090 5851/6570/13157 +f 7707/7139/13732 7708/7138/13731 7706/7248/13732 +f 6317/7189/14091 6315/6734/13300 6294/6383/13002 +f 5956/6223/12853 5957/7394/14092 5958/6993/13576 +f 7991/6188/12824 7992/6187/12823 7909/6305/12926 +f 6847/7226/13847 6846/6352/12969 6843/6132/12777 +f 5915/6690/13259 5916/6822/13394 6237/5826/12500 +f 7671/5776/12455 7760/5775/12454 7666/6696/13264 +f 6409/7395/14093 6412/7366/14043 6487/7181/13787 +f 6961/5950/12607 6938/5995/12650 6962/6414/13030 +f 7497/7350/14094 7515/5885/12552 7496/6599/14095 +f 6713/6385/13003 6712/6563/13151 6743/7214/13835 +f 7956/5868/12537 7983/7145/13740 7982/5869/12538 +f 6203/6438/13053 6198/6067/12713 6202/6604/13183 +f 5752/6884/13463 5830/7396/14096 5818/5969/12625 +f 7794/6953/13411 7797/7013/13598 7793/6954/13597 +f 5897/7397/14097 5898/6172/12814 5865/6171/12813 +f 6654/7398/12916 6657/7347/14014 6655/5804/12481 +f 6465/7399/14098 6466/7016/13604 6451/6336/13851 +f 6710/7005/13906 6711/5753/12439 6698/7400/14099 +f 6854/7401/14100 6853/6166/12808 6852/6165/12807 +f 6325/6636/14059 6297/7171/14101 6299/6398/13877 +f 6286/6602/13181 6282/7402/14102 6279/6600/12905 +f 7732/6355/12972 7774/6895/13475 7731/6353/12970 +f 6870/6134/12779 6847/7226/13847 6843/6132/12777 +f 6001/6389/13007 5998/6594/13175 6000/6316/12936 +f 6219/6197/12833 6221/6893/13472 6190/6512/13112 +f 5821/6225/12855 5822/6371/12989 5803/6411/13487 +f 6613/6160/12802 6614/6507/13107 6599/6126/14103 +f 7749/7190/14104 7716/6040/14105 7729/6475/14106 +f 6126/7091/13685 6121/7093/13687 6122/6804/13376 +f 7842/7268/12518 7825/5921/12518 7853/5912/12518 +f 6367/5881/12548 6368/7403/14107 6369/7404/14108 +f 5899/5997/12652 5901/6074/12720 6163/5998/12653 +f 6695/6346/12472 6680/6593/12472 6682/7168/12472 +f 6819/6739/12498 6815/7188/12498 6783/7187/12498 +f 6216/6586/13169 6218/6198/12834 6219/6197/12833 +f 7446/6441/13055 7444/7405/13055 7445/6442/13055 +f 6936/7193/14109 6948/5813/12490 6937/6783/13354 +f 6243/6825/13398 6242/6931/13519 6160/6622/13201 +f 7439/6679/14110 7428/7345/14111 7438/7317/14112 +f 7563/6888/13468 7588/6887/13467 7590/6544/14113 +f 6175/6129/12774 6178/6242/12871 6180/5855/12524 +f 6213/6252/12877 6217/6587/13170 6192/6405/13021 +f 5985/6222/12852 5984/5829/12503 5912/5828/12502 +f 6633/5850/12519 6591/7011/13595 6632/7406/14114 +f 7940/5862/13489 7939/5864/14115 7941/6760/13490 +f 6084/6855/13431 6226/7121/13716 6255/6657/13231 +f 7458/7407/14116 7457/6515/13115 7459/7408/14116 +f 7750/7409/14117 7780/6653/13227 7778/6484/13086 +f 6792/7062/14118 6794/6843/13419 6793/6842/13418 +f 6101/7089/13683 6129/5834/12508 6236/5825/12499 +f 6532/6032/14119 6641/7410/14119 6642/6651/14119 +f 6877/7352/12962 6876/7237/12962 6872/7239/12962 +f 6197/7066/13660 6025/6116/12761 6239/6115/12760 +f 7916/6236/13056 7918/6445/13056 7915/7411/13056 +f 7771/7412/14120 7731/6353/12970 7774/6895/13475 +f 6047/7262/13893 6043/6769/13823 6164/7127/13720 +f 6921/6708/13274 6922/6497/13273 6923/7413/14121 +f 7731/6353/12970 7730/6473/14122 7715/6042/14123 +f 6643/7115/12916 6645/6556/12916 6644/7414/12914 +f 6221/6893/13472 6220/6196/12832 6224/6489/13089 +f 6640/7415/14124 6532/6032/14124 6525/6031/14124 +f 5789/6973/14125 5790/6930/14125 5788/7300/14126 +f 6920/7282/13917 6918/7166/14127 6917/6157/14128 +f 6598/5960/14129 6599/6126/12771 6583/6128/12773 +f 6525/6031/12682 6534/6030/12681 6530/7015/12682 +f 7863/5911/12572 7871/7416/14130 7862/7269/13900 +f 6050/7086/13681 6148/7339/14003 6167/5865/12534 +f 7651/6815/13386 7650/6923/13515 7611/6816/13387 +f 6129/5834/12508 6101/7089/13683 6130/7169/13773 +f 7478/6772/14131 7489/7150/13745 7465/7141/13735 +f 5967/6926/13518 5880/6862/13439 5879/5931/12589 +f 7904/6683/13054 7903/7417/14132 7913/6826/13399 +f 6191/6406/13022 6217/6587/13170 6219/6197/12833 +f 6418/7418/12708 6417/7419/12708 6415/7123/12708 +f 6764/7288/14133 6766/7420/14134 6850/5796/12473 +f 7716/6040/14105 7730/6473/14122 7729/6475/14106 +f 6227/7162/13761 6229/6603/13182 6228/6609/13187 +f 5867/6589/13172 5885/6645/13223 5888/7155/13752 +f 7710/7421/13922 7711/7278/13922 7713/6041/13358 +f 7767/6329/12951 7769/7422/14135 7770/7423/14136 +f 6866/7424/14137 6865/7425/14138 6867/5990/12646 +f 7883/7426/14139 7882/5800/12477 7854/5799/12476 +f 6351/6089/13216 6350/6955/13541 6360/6633/13215 +f 7474/7427/12542 7455/6514/12542 7475/6560/12542 +f 6946/6780/13351 6979/6779/13350 6945/7250/14140 +f 6826/7202/13913 6862/6153/12796 6863/7428/14141 +f 6312/6849/14142 6310/6606/14143 6293/6736/13302 +f 6278/6279/12904 6275/6681/13994 6377/7429/14144 +f 7915/7411/14145 7923/5884/14146 7925/6700/14147 +f 6579/5839/13485 6604/7337/14000 6578/6453/13062 +f 6731/5802/12479 6657/7347/14014 6730/6273/12898 +f 6176/7249/13875 6165/7207/13824 6266/7020/13608 +f 6289/7170/13775 6290/7430/14148 6300/6864/14149 +f 6640/7415/14124 6641/7410/14124 6532/6032/14124 +f 7677/6836/13412 7688/6838/13414 7678/6919/13509 +f 7865/7380/14062 7875/5785/12464 7864/5910/13938 +f 6891/6245/13591 6890/6323/13591 6889/6243/13591 +f 7853/5912/12573 7863/5911/12572 7842/7268/13899 +f 7887/7431/14150 7791/6966/14151 7885/7432/14152 +f 7513/5886/12553 7414/6719/13285 7417/6232/12861 +f 6110/6933/13521 6104/7433/14153 6105/6668/13240 +f 7818/5979/12634 7819/7434/14154 7817/6988/14155 +f 5963/7198/13802 5964/7435/14156 5953/7436/14157 +f 6330/7437/14158 6340/5928/14159 6341/6499/14160 +f 6750/7114/14161 6751/7438/14161 6649/6293/14161 +f 5999/7026/13614 5931/6854/13430 5862/7247/13873 +f 6829/7439/14162 6828/7201/13809 6867/5990/12646 +f 7547/6430/13047 7548/6313/12567 7554/6693/13262 +f 6194/7258/13891 6210/6083/12729 6212/6852/13428 +f 6589/6620/13199 6590/7231/13857 6576/6621/13200 +f 7575/6985/14008 7574/7440/14163 7576/7344/14009 +f 6443/6070/13104 6444/6069/14164 6445/6200/13105 +f 6651/7441/14165 6652/5899/14166 6644/7414/12914 +f 5853/6283/12906 5850/5790/12469 5755/5792/12471 +f 8008/7075/13670 8007/7074/13669 8006/6944/13533 +f 6101/7089/13683 6100/7054/13647 6102/6934/13522 +f 6762/7357/12962 6754/7303/12962 6755/6753/12962 +f 6560/6744/13311 6561/5758/13310 6559/6748/13316 +f 6000/6316/12936 5998/6594/13175 5939/6597/13178 +f 6252/6623/13202 6251/6130/12775 6250/5964/12620 +f 7663/6327/12949 7662/6697/12956 7666/6696/13264 +f 6726/7079/13674 6727/6491/13091 6718/5859/12528 +f 6719/5860/12529 6708/6787/14167 6707/5861/12530 +f 7506/6269/12894 7501/6271/12896 7507/6400/13016 +f 6504/7442/14168 6506/6899/13480 6505/6898/13479 +f 6213/6252/12877 6215/7033/13621 6217/6587/13170 +f 7661/6981/12956 7662/6697/12956 7663/6327/12949 +f 6054/7443/14169 6271/7165/13974 6152/6319/12942 +f 7721/7444/12562 7685/6785/12562 7716/6040/12562 +f 6827/6418/14170 6863/7428/14141 6866/7424/14137 +f 6782/6285/12908 6781/6110/12754 6771/6109/12753 +f 6303/7445/14171 6290/7430/14148 6291/6119/12764 +f 7895/6952/13596 7787/6967/13596 7794/6953/14172 +f 7689/6920/13864 7692/6044/14173 7691/6207/14173 +f 7618/6147/12792 7624/7446/14174 7617/5941/12599 +f 6128/7364/14040 6127/7192/13796 6129/5834/12508 +f 6249/5966/12622 6158/6905/13492 6157/6904/13491 +f 6463/6992/12708 6434/6100/12708 6436/6099/12708 +f 5752/6884/13463 5754/6366/14175 5830/7396/14096 +f 6867/5990/12646 6845/6672/13246 6829/7439/14162 +f 6186/7174/13779 6183/6253/12878 6185/6390/13008 +f 6552/7447/14176 6549/5840/14068 6550/7448/14177 +f 6682/7168/13772 6681/7367/14044 6683/7042/13632 +f 6433/6970/14178 6434/6100/14178 6432/5935/14178 +f 7772/7449/14179 7771/7412/14120 7768/6474/13077 +f 6924/7450/14180 6899/7451/14181 6923/7413/14182 +f 5821/6225/13947 5820/6224/13504 5828/6914/13503 +f 6244/6773/13342 6170/7392/14089 6171/7391/14088 +f 6500/7361/14036 6499/6192/12828 6503/6448/13058 +f 6253/6932/13520 6244/6773/13342 6171/7391/14088 +f 7985/6025/12676 8012/7452/14183 7974/6026/12677 +f 6808/6667/14184 6807/5982/14185 6809/6509/14186 +f 6659/6841/13417 6660/7453/14187 6670/6839/13415 +f 6861/7454/14188 6754/7303/13941 6864/7455/14189 +f 6502/6449/13059 6503/6448/13058 6504/7442/14168 +f 6951/6752/14190 6985/7456/14191 6950/6750/13634 +f 6111/6670/13242 6110/6933/13521 6105/6668/13240 +f 5860/6310/12931 5931/6854/13430 6001/6389/13007 +f 7978/5783/13959 7990/7312/13958 7977/5781/14192 +f 6186/7174/13779 6193/6254/12879 6183/6253/12878 +f 7545/6231/12567 7546/6230/12860 7550/7035/13625 +f 7989/7457/14193 7913/6826/13399 8013/7458/14194 +f 6137/6972/13551 6136/6866/13444 6135/6949/13538 +f 5988/5807/12484 5987/5806/12483 5867/6589/13172 +f 5912/5828/12502 5913/5827/12501 6234/6018/12669 +f 6831/6298/12918 6818/5823/13970 6830/7321/13972 +f 6789/6003/12658 6790/7301/14195 6791/6639/13219 +f 7952/6519/13056 7947/7459/13056 7955/6654/13056 +f 6267/7021/13609 6269/6538/13132 6268/6447/13057 +f 7870/5801/13408 7843/6249/14196 7854/5799/14197 +f 5819/5967/12623 5820/6224/12854 5805/6226/12856 +f 7585/5750/12436 7561/5749/12435 7584/7319/14198 +f 6170/7392/14089 6169/6665/13239 6177/6048/12695 +f 6169/6665/13239 6170/7392/14089 6244/6773/13342 +f 6248/5965/12621 6175/6129/12774 6262/5913/12574 +f 5959/6221/12851 5986/7351/14027 5985/6222/12852 +f 6359/5879/12546 6360/6633/13215 6366/5880/12547 +f 8011/7460/14199 8012/7452/14183 8013/7458/14194 +f 6337/6956/13014 6336/7461/13014 6307/6183/13014 +f 5916/6822/13394 6153/6457/13066 6230/7156/13753 +f 6986/7328/13986 6989/6634/13217 6991/6331/12953 +f 7482/7462/14200 7469/6028/14201 7468/7234/13860 +f 6714/5812/12489 6745/5811/12488 6746/7120/13715 +f 6662/6488/13088 6661/7327/14202 6660/7453/12472 +f 6490/6097/12741 6484/6051/12698 6475/7117/13712 +f 6333/6767/14203 6343/6924/14204 6344/6094/12738 +f 7490/6270/12895 7502/6979/13561 7489/7150/13745 +f 5997/7027/13615 5999/7026/13614 5862/7247/13873 +f 5908/6757/13327 5909/6364/12982 5918/5908/12569 +f 6782/6285/14205 6785/6476/13079 6783/7187/14206 +f 6424/6218/13829 6447/6335/14207 6448/6580/13827 +f 6373/6360/12978 6354/6632/14208 6370/7370/14050 +f 7478/6772/12542 7445/6442/12542 7477/7463/12542 +f 6175/6129/12774 6248/5965/12621 6251/6130/12775 +f 6607/7464/14209 6634/5852/12521 6636/5851/12520 +f 5770/7465/14210 5758/6553/14211 5771/6156/13807 +f 6392/7466/14212 6276/6503/13100 6393/6505/13102 +f 7971/7277/14213 8009/7073/13668 7970/6408/14214 +f 6074/6881/13460 6142/7467/14215 6143/6882/13461 +f 6181/6911/13499 6046/7085/13680 6167/5865/12534 +f 6727/6491/13091 6726/7079/13674 6728/6492/13092 +f 6563/7468/12441 6564/7469/12441 6575/7470/12558 +f 7414/6719/12862 7411/7274/12862 7412/6233/12862 +f 6082/6190/12826 6095/7252/13882 6096/6191/12827 +f 5779/6578/12493 5794/6775/12493 5777/5952/12493 +f 6038/7471/14216 6042/6046/12693 6177/6048/12695 +f 6190/6512/13112 6191/6406/13022 6219/6197/12833 +f 6030/6880/13459 6239/6115/12760 6031/6114/12759 +f 5744/6961/14217 5856/6338/14218 5857/7472/14217 +f 7450/7064/13658 7432/7063/13657 7448/6922/14219 +f 7494/6019/14220 7510/5842/12513 7493/5841/12512 +f 6276/6503/13100 6392/7466/14212 6391/6357/12974 +f 6237/5826/12500 6097/5773/12452 6099/5772/12451 +f 6763/6412/13028 6758/6344/12961 6869/6413/13029 +f 6056/7322/13973 6272/6539/13854 6271/7165/13974 +f 6942/5949/12606 6959/6946/14221 6943/7473/14222 +f 7915/7411/14145 7926/6702/14223 7916/6236/12865 +f 6204/6164/12806 6203/6438/13053 6161/7263/13894 +f 7451/6180/12542 7473/6179/12542 7472/6562/12542 +f 6005/7474/14224 6009/6388/13006 6003/7475/14225 +f 7978/5783/12462 7962/5782/12461 7979/7313/14226 +f 6543/7476/12441 6542/6186/12441 6539/5747/12433 +f 6227/7162/13761 6256/6875/13453 6226/7121/13716 +f 6200/6766/13335 6160/6622/13201 6161/7263/13894 +f 7918/6445/13056 7916/6236/13056 7917/7477/13056 +f 6441/6181/12817 6439/7146/13741 6420/7087/13682 +f 6569/6151/14227 6568/6878/13455 6570/6712/13279 +f 8012/7452/14183 8010/7478/14228 7973/5844/12515 +f 6139/6868/13446 6140/7334/13997 6141/7479/14229 +f 5796/7136/14230 5800/5818/13213 5825/5956/12612 +f 6178/6242/12871 6181/6911/13499 6180/5855/12524 +f 5849/7480/14231 5848/6284/12907 5846/6918/13508 +f 6793/6842/12498 6821/7333/12498 6791/6639/12498 +f 5968/6616/13194 5878/6925/13517 5967/6926/13518 +f 7479/6817/13388 7516/6073/12719 7498/6072/12718 +f 7437/7390/12542 7463/5874/12542 7467/5873/12542 +f 7425/7244/13869 7505/6978/13560 7426/6524/13119 +f 6064/7289/13927 6063/6886/13466 6081/6203/12836 +f 6042/6046/12693 6164/7127/13720 6182/6047/12694 +f 7703/5897/13815 7702/6534/13815 7701/6876/13903 +f 7510/5842/12513 7494/6019/14220 7511/7025/13613 +f 6267/7021/13609 6266/7020/13608 6265/7208/13825 +f 5757/7481/12493 5756/6300/12493 5764/6299/12493 +f 7508/6399/13015 7509/6874/13452 7423/7363/14232 +f 6408/6676/12583 6401/6482/12583 6407/6241/12870 +f 6342/7382/14065 6341/6499/13098 6358/6498/13097 +f 7654/7482/14233 7653/7483/14234 7651/6815/13386 +f 6855/7484/14235 6856/7204/13813 6842/5889/12556 +f 6086/6342/12959 6087/7485/14236 6068/6217/12850 +f 6418/7418/14237 6431/7241/14238 6417/7419/14239 +f 7718/7486/12692 7707/7139/12562 7719/7360/12562 +f 6759/7229/14240 6876/7237/14241 6767/6345/14241 +f 6430/5936/12708 6461/6381/12708 6456/6723/12708 +f 7531/7342/14005 7484/7232/14242 7485/7487/14243 +f 7714/6786/14244 7684/6921/14245 7676/7488/14246 +f 6742/7215/13836 6740/5751/12437 6647/6101/12745 +f 6937/6783/12440 6925/6480/12440 6936/7193/13797 +f 8010/7478/14228 8011/7460/14199 7908/6549/13141 +f 7526/7489/14247 7527/7490/14248 7524/6941/13530 +f 6503/6448/13058 6501/6450/13060 6500/7361/14036 +f 6156/6458/13067 6155/6997/13583 6250/5964/12620 +f 6188/6942/13531 6184/5819/12495 6019/6743/13309 +f 7662/6697/13995 7781/7243/13995 7782/7491/13995 +f 5795/6929/12493 5799/7341/12493 5790/6930/12493 +f 6007/7492/14249 6004/7493/14250 6005/7474/14224 +f 5870/6610/13188 5875/7161/13760 5969/6614/13192 +f 6847/7226/13847 6870/6134/12779 6871/6877/13454 +f 5916/6822/13394 5915/6690/13259 5865/6171/12813 +f 6517/6902/12583 6516/6687/12583 6514/6085/12583 +f 6239/6115/12760 6240/6879/13458 6238/6511/13111 +f 5924/7051/13643 5989/7050/13642 5926/6575/13162 +f 6414/6579/13165 6415/7123/14251 6423/7210/14252 +f 5940/6596/13177 5941/7315/13962 6000/6316/12936 +f 7627/6362/12980 7654/7482/14233 7613/6765/13334 +f 5936/7494/14253 5938/7495/14254 6000/6316/12936 +f 6269/6538/13764 6267/7021/14255 6271/7165/13765 +f 6250/5964/12620 6249/5966/12622 6156/6458/13067 +f 7536/7290/13114 7540/7496/13114 7421/6525/13114 +f 6472/7158/13757 6473/7497/14256 6463/6992/14257 +f 6854/7401/14100 6851/7498/14258 6766/7420/14134 +f 6699/6564/12472 6697/6976/12472 6689/6265/12472 +f 6803/5944/14259 6802/7499/14260 6801/6900/14261 +f 6263/6105/12749 6266/7020/13608 6268/6447/13057 +f 7554/6693/13262 7632/6431/13048 7547/6430/13047 +f 7769/7422/14135 7749/7190/13794 7768/6474/13077 +f 7915/7411/13056 7922/7500/13056 7914/7501/13056 +f 6429/5934/14262 6428/7502/14263 6416/7503/14264 +f 6598/5960/12616 6610/5959/12615 6611/6894/13474 +f 5758/6553/13145 5757/7481/12493 5760/6112/12756 +f 7861/6540/13134 7892/7306/13949 7891/6541/13135 +f 5926/6575/13162 5863/7029/13617 5927/7295/13930 +f 7928/6237/12866 7916/6236/12865 7926/6702/14223 +f 6875/7238/12962 6874/7294/12962 6872/7239/12962 +f 7800/5988/12644 7877/6716/13282 7878/7348/14018 +f 6118/6803/13375 6126/7091/13685 6122/6804/13376 +f 6217/6587/13170 6191/6406/13022 6192/6405/13021 +f 6834/7225/13846 6833/6351/12968 6846/6352/12969 +f 5891/5909/12570 5977/6174/12816 5978/7030/13618 +f 6733/6648/13224 6735/6057/12704 6734/6056/12703 +f 5975/6086/12730 5976/6173/12815 5892/6258/12883 +f 5896/6260/12885 5865/6171/12813 5975/6086/12730 +f 6527/6437/12683 6524/7504/14265 6520/6502/12683 +f 6588/7133/14266 6589/6620/13199 6573/6150/13198 +f 5892/6258/12883 5976/6173/12815 5890/6421/13037 +f 5865/6171/12813 5864/6170/12812 5916/6822/13394 +f 5896/6260/12885 5897/7397/14097 5865/6171/12813 +f 5976/6173/12815 5891/5909/12570 5890/6421/13037 +f 6163/5998/12653 5864/6170/12812 5905/5996/12651 +f 6603/7336/14267 6602/6123/12768 6619/6125/12770 +f 5846/6918/13508 5845/5789/12468 5750/7505/14268 +f 6857/5767/12449 6855/7484/14235 6756/7302/13940 +f 7675/6333/12955 7739/6053/13821 7751/6121/12766 +f 6918/7166/13769 6898/5755/13768 6914/6368/12986 +f 7929/6472/13144 7930/6235/13143 7928/6237/13381 +f 6369/7404/14108 6370/7370/14050 6353/6356/14269 +f 6159/6624/13203 6155/6997/13583 6162/7506/14270 +f 7790/5954/12610 7788/7507/13597 7795/5986/12642 +f 5915/6690/13259 6236/5825/12499 6235/5833/12507 +f 5948/7508/14271 5939/6597/13178 5998/6594/13175 +f 6940/6751/12440 6920/7282/14272 6941/7509/12440 +f 7608/6619/14273 7595/7388/14083 7609/6078/14082 +f 5920/6807/13378 5879/5931/12589 5885/6645/13223 +f 7735/6749/13317 7778/6484/13086 7734/6485/13087 +f 5937/7510/14274 6002/7511/14275 6000/6316/12936 +f 6472/7158/13757 6449/6991/14276 6471/7176/13781 +f 6083/6856/13432 6058/7228/13849 6059/6857/13433 +f 5772/7512/12493 5773/6155/13027 5803/6411/12493 +f 6801/6900/14261 6800/6010/12662 6798/6011/12664 +f 7689/6920/13510 7678/6919/13509 7688/6838/13414 +f 5922/6808/13379 5920/6807/13378 5885/6645/13223 +f 7775/6896/13476 7776/6106/12750 7773/7077/13672 +f 7630/6363/12981 7631/6343/12960 7629/7513/14277 +f 5827/5957/12613 5825/5956/12612 5824/6631/13212 +f 7547/6430/13047 7542/5992/12567 7548/6313/12567 +f 6069/7221/13843 6090/7129/13724 6070/6860/13437 +f 6071/6859/13436 6081/6203/12836 6072/7514/14278 +f 7649/6077/12723 7648/6617/13195 7609/6078/12724 +f 5991/7299/13937 5994/7023/13611 5992/6574/13161 +f 6960/5948/14047 6888/7369/14048 6959/6946/13535 +f 6214/6387/13005 6211/6386/13004 5920/6807/13378 +f 7604/7515/12847 7578/5763/12847 7576/7344/12847 +f 6706/7255/13887 6721/7254/13886 6722/7516/14279 +f 5928/7028/13616 5992/6574/13161 5994/7023/13611 +f 6074/6881/13460 6077/7153/13748 6232/6022/12673 +f 6340/5928/12586 6380/5930/12588 6382/6138/12783 +f 6641/7410/12682 6640/7415/12683 6637/6501/12683 +f 6191/6406/13022 6189/6513/13113 6187/6404/13020 +f 6177/6048/12695 6172/6422/13038 6171/7391/14088 +f 6242/6931/13519 6243/6825/13398 6244/6773/13342 +f 7814/6790/13362 7811/6789/13361 7812/7259/14280 +f 6123/7185/13792 6118/6803/13375 6124/6805/13377 +f 7848/7517/12518 7832/6890/12518 7849/7518/12518 +f 5917/6756/13326 5919/6162/12804 6161/7263/13894 +f 7527/7490/14248 7526/7489/14247 7483/7233/13859 +f 6706/7255/12472 6704/5793/12472 6676/7045/12472 +f 6657/7347/14014 6733/6648/13224 6732/6649/13225 +f 7706/7248/13732 7705/5896/13814 7707/7139/13732 +f 7543/6812/13383 7542/5992/12567 7547/6430/13047 +f 6628/7135/13730 6624/7058/13651 6627/7060/13653 +f 7669/7101/13697 7780/6653/13227 7736/6394/14281 +f 7694/7519/12562 7692/6044/12562 7728/6043/12692 +f 6473/7497/14256 6474/6143/12788 6459/6061/14282 +f 7590/6544/14283 7589/6554/13756 7591/6545/14283 +f 5963/7198/13802 5954/7009/13593 5911/6764/13333 +f 7448/6922/13513 7447/6443/13514 7449/6178/13513 +f 6415/7123/14251 6416/7503/14264 6426/6909/14284 +f 7714/6786/14244 7676/7488/14246 7712/7520/14285 +f 6857/5767/12449 6756/7302/13940 6860/7304/13942 +f 5983/7038/13628 5965/7521/14286 5879/5931/12589 +f 7674/5871/12540 7755/6120/12765 7756/5872/12541 +f 6194/7258/13891 6196/5878/12545 6210/6083/12729 +f 5742/6781/14287 5741/7002/12984 5740/6340/14288 +f 5985/6222/12852 5912/5828/12502 5911/6764/13333 +f 7426/6524/13119 7424/6523/12862 7425/7244/13869 +f 7756/5872/12541 7742/7320/13968 7757/5870/12539 +f 7874/5784/12463 7873/6006/12661 7875/5785/12464 +f 5814/6572/13953 5801/6465/14289 5813/7522/14290 +f 6594/6521/14291 6595/6520/13723 6580/5759/14292 +f 6752/7523/12916 6751/7438/12916 6748/7260/12916 +f 6835/7173/13778 6836/6818/13390 6820/6737/13303 +f 7608/6619/14273 7596/6555/14293 7595/7388/14083 +f 7499/7524/14294 7526/7489/14247 7525/7324/13977 +f 5960/6994/13577 5949/6419/13035 5956/6223/12853 +f 6144/6883/13462 6145/7318/13965 6074/6881/13460 +f 7465/7141/12542 7449/6178/12542 7447/6443/12542 +f 7867/7525/14295 7877/6716/13282 7800/5988/12644 +f 6444/6069/12715 6422/7122/14296 6446/6581/13167 +f 6155/6997/13583 6163/5998/12653 6162/7506/14270 +f 6428/7502/14297 6429/5934/12592 6430/5936/12594 +f 6234/6018/12669 6233/6023/12674 5912/5828/12502 +f 7617/5941/12599 7624/7446/14174 7625/5939/12597 +f 5927/7295/13930 5924/7051/13643 5926/6575/13162 +f 6372/7526/14298 6376/5856/12525 6374/6359/12977 +f 7516/6073/12719 7479/6817/13388 7521/7368/14046 +f 6054/7443/14169 6152/6319/12942 6052/6308/12929 +f 5964/7435/14156 5952/7527/14299 5953/7436/14157 +f 6174/5854/12523 6175/6129/12774 6180/5855/12524 +f 6767/6345/12962 6761/6014/12962 6765/6059/12962 +f 6338/6936/13524 6327/6637/14300 6328/6397/13525 +f 5856/6338/12985 5854/7001/12985 5858/6999/12985 +f 5992/6574/13161 5928/7028/13616 5926/6575/13162 +f 6094/7528/14301 6076/6193/12829 6093/7529/14302 +f 6161/7263/13894 6162/7506/14270 5917/6756/13326 +f 6521/6500/12683 6520/6502/12683 6523/7105/13701 +f 7560/6823/13396 7579/5765/13395 7581/7530/14303 +f 5796/7136/14304 5826/7531/14305 5807/5779/14306 +f 5932/6407/13023 5933/6311/12932 5860/6310/12931 +f 5923/5805/12482 5925/6792/13364 6216/6586/13169 +f 6744/5810/12487 6743/7214/13835 6742/7215/13836 +f 7700/7270/14307 7681/6971/13550 7699/7271/14308 +f 6295/6384/13014 6294/6383/13014 6293/6736/13302 +f 5993/6467/13073 5994/7023/13611 5991/7299/13937 +f 6220/6196/12832 6221/6893/13472 6219/6197/12833 +f 6110/6933/13521 6101/7089/13683 6102/6934/13522 +f 6869/6413/13029 6871/6877/13454 6870/6134/12779 +f 7752/7206/13820 7740/6052/13822 7741/6396/13969 +f 6512/7180/13786 6409/7395/14093 6487/7181/13787 +f 6545/7532/14309 6546/7109/14310 6547/5891/14066 +f 6968/6244/12873 6969/7533/14311 6891/6245/12874 +f 5840/6320/12943 5742/6781/13352 5743/5788/12467 +f 6153/6457/13066 6163/5998/12653 6156/6458/13067 +f 7503/7151/13746 7504/7245/13870 7534/6402/13018 +f 6263/6105/12749 6259/6869/13447 6174/5854/12523 +f 6237/5826/12500 6236/5825/12499 5915/6690/13259 +f 7858/6425/13041 7889/6424/13040 7888/7068/13662 +f 5744/6961/14217 5746/6339/14218 5856/6338/14218 +f 7790/5954/12610 7789/6968/13411 7788/7507/13597 +f 6001/6389/13007 5999/7026/13614 5998/6594/13175 +f 7416/6565/13153 7539/6566/13153 7538/6727/13153 +f 7952/6519/14312 7955/6654/13228 7967/6656/13230 +f 6427/6219/13497 6426/6909/13496 6428/7502/14297 +f 7973/5844/12515 7986/7534/14313 7972/5845/12516 +f 6211/6386/13004 5921/7039/13629 5920/6807/13378 +f 7650/6923/13515 7651/6815/13386 7652/7535/14314 +f 5742/6781/14287 5745/6938/13527 5741/7002/12984 +f 6796/6844/12498 6810/6297/12498 6793/6842/12498 +f 6591/7011/13595 6592/7010/13594 6575/7470/14315 +f 5824/6631/13212 5823/6630/13211 5832/6372/12991 +f 6477/6379/12998 6476/7118/13713 6483/6050/12697 +f 6813/6416/12498 6816/7200/12498 6802/7499/12498 +f 6972/6376/12995 6888/7369/14048 6970/6377/12996 +f 7684/6921/13512 7714/6786/13357 7685/6785/13356 +f 6660/7453/14187 6661/7327/13981 6673/7046/13983 +f 6310/6606/14143 6308/6182/13045 6292/6429/13046 +f 6978/6720/13286 6881/7536/14316 6880/6721/13287 +f 6825/6152/12795 6824/7537/14317 6859/5768/12450 +f 5802/7308/12493 5781/6577/12493 5784/6466/12493 +f 7901/6568/13155 8002/5962/12618 7899/6945/13534 +f 5754/6366/12985 5753/6998/12985 5748/6367/12984 +f 7680/6208/12841 7677/6836/12692 7679/6209/14318 +f 6001/6389/13007 6009/6388/13006 6010/7006/13589 +f 6710/7005/13588 6709/7272/14319 6738/6557/13147 +f 7775/6896/13476 7773/7077/13672 7774/6895/13475 +f 6536/7110/12558 6535/7538/12558 6543/7476/12441 +f 7817/6988/13571 7803/6987/13570 7815/5980/13602 +f 7974/6026/12677 8012/7452/14183 7973/5844/12515 +f 7648/6617/13195 7649/6077/12723 7647/7539/14320 +f 6390/6318/12941 6389/7540/14321 6388/7541/14322 +f 7690/7236/13863 7688/6838/13862 7687/7542/14323 +f 5753/6998/13584 5859/7000/13584 5748/6367/13584 +f 6136/6866/13444 6235/5833/12507 6129/5834/12508 +f 7571/6820/12847 7568/7088/12847 7598/6660/12847 +f 7559/6983/13564 7577/6824/13397 7560/6823/13396 +f 7638/6814/13385 7640/6038/12689 7543/6812/13383 +f 6409/7395/14093 6512/7180/13786 6511/7543/14324 +f 6116/7544/14325 6117/7125/13718 6115/7076/13671 +f 7604/7515/14326 7613/6765/13334 7592/6529/13123 +f 6945/7250/13876 6933/6782/13353 6946/6780/14327 +f 6045/6771/13721 6048/7545/14328 6181/6911/13499 +f 6210/6083/12729 6205/6495/13096 6209/6163/12805 +f 6829/7439/14162 6817/5822/13971 6816/7200/13808 +f 5891/5909/12570 5979/7031/13619 5980/5907/12568 +f 7561/5749/12435 7582/7546/14329 7584/7319/14198 +f 6411/5923/14330 6518/5922/14330 6519/6084/14330 +f 5989/7050/13642 5988/5807/12484 5986/7351/14027 +f 6268/6447/13057 6264/6537/13131 6255/6657/13231 +f 5961/6763/13332 5962/7197/13801 5911/6764/13333 +f 6575/7470/12558 6581/6832/12441 6563/7468/12441 +f 6518/5922/12582 6403/5924/12582 6517/6902/12582 +f 7901/6568/13155 7902/7310/13054 7910/6306/12927 +f 5950/6468/13074 5993/6467/13073 5959/6221/12851 +f 7848/7517/14331 7849/7518/14332 7860/6542/14333 +f 7458/7407/14334 7434/6811/14334 7433/6810/13579 +f 6266/7020/13608 6263/6105/12749 6176/7249/13875 +f 6169/6665/13239 6168/6081/12727 6177/6048/12695 +f 5984/5829/12503 5985/6222/12852 5986/7351/14027 +f 6646/7240/13867 6737/6558/13148 6736/6055/12702 +f 6535/7538/14335 6536/7110/13706 6544/7547/14336 +f 6018/5821/12497 6019/6743/13309 6184/5819/12495 +f 6255/6657/13231 6264/6537/13131 6084/6855/13431 +f 6046/7085/13680 6049/7548/14337 6050/7086/13681 +f 7931/7549/14338 7933/5985/14339 7918/6445/14340 +f 5996/7022/13610 5997/7027/13615 5994/7023/13611 +f 6198/6067/12713 6195/5877/12544 6027/6065/12711 +f 6364/7218/13839 6361/6290/12913 6363/6504/13101 +f 6561/5758/13310 6562/6745/13312 6563/7468/14341 +f 6258/6103/12747 6255/6657/13231 6256/6875/14342 +f 6323/6638/13623 6320/6382/13093 6322/5999/13624 +f 6600/6127/13477 6599/6126/14103 6614/6507/13107 +f 6605/7383/14343 6604/7337/14344 6620/7550/14345 +f 6003/7475/14225 6009/6388/13006 6000/6316/12936 +f 6905/6798/13918 6894/5974/13920 6893/5754/14017 +f 6756/7302/13940 6757/6013/12962 6755/6753/12962 +f 7530/6168/12810 7484/7232/14242 7531/7342/14005 +f 6617/6124/12769 6615/6506/13106 6616/6508/13108 +f 5743/5788/12467 5750/7505/14268 5845/5789/12468 +f 5923/5805/12482 5922/6808/13379 5885/6645/13223 +f 5848/6284/12907 5851/6570/13157 5847/5973/12629 +f 6232/6022/12673 6078/7152/13747 6080/7149/13744 +f 7859/6423/13039 7891/6541/13135 7890/7551/14346 +f 6649/6293/12916 6654/7398/12916 6655/5804/12481 +f 6161/7263/13894 6203/6438/13053 6200/6766/13335 +f 5901/6074/12720 5899/5997/12652 5900/6075/12721 +f 7731/6353/12970 7772/7449/14179 7730/6473/13076 +f 7904/6683/14347 7911/6440/14348 8018/7280/14348 +f 6388/7541/14322 6286/6602/13181 6390/6318/12941 +f 6805/5942/12600 6807/5982/14185 6808/6667/14184 +f 7484/7232/14242 7527/7490/14248 7483/7233/13859 +f 7454/6629/13580 7432/7063/13657 7452/7065/13659 +f 6151/6307/12928 6053/7552/14349 6052/6308/12929 +f 6040/7553/14350 6039/7554/14351 6177/6048/12695 +f 6791/6639/13219 6790/7301/14195 6792/7062/14118 +f 7491/6982/13563 7477/7463/14352 7492/7359/14353 +f 7644/6037/12688 7642/5835/12509 7643/7142/13736 +f 7929/6472/13056 7927/6701/13056 7961/7555/13056 +f 6015/7257/13890 6206/6774/13343 6207/6262/12887 +f 5806/5968/12493 5775/7326/13027 5777/5952/12493 +f 5989/7050/13642 5990/6576/13163 5926/6575/13162 +f 7414/6719/13285 7518/7217/13837 7413/6229/12859 +f 6516/6687/13257 6400/5925/13257 6514/6085/13257 +f 7498/6072/12718 7497/7350/14026 7470/6598/13179 +f 5943/5918/12579 5948/7508/14271 5998/6594/13175 +f 6950/6750/13634 6985/7456/14191 6982/6658/13232 +f 6398/6641/12905 6397/7556/12905 6394/7557/12905 +f 5945/7083/13678 5947/5917/12578 5946/5916/12577 +f 6593/7102/13698 6592/7010/13594 6607/7464/14209 +f 5956/6223/12853 5955/7373/14054 5957/7394/14092 +f 7799/6350/12967 7798/6835/13411 7801/6349/12966 +f 5915/6690/13259 6235/5833/12507 5914/6611/13189 +f 6075/6035/12686 6132/6635/13218 6076/6193/12829 +f 7459/7408/14354 7461/6643/13245 7460/6671/13244 +f 6765/6059/12962 6769/6058/12705 6767/6345/12962 +f 6899/7451/14181 6921/6708/14355 6923/7413/14182 +f 7430/7067/12542 7433/6810/12542 7429/6851/12542 +f 7540/7496/12862 7535/6584/12862 7539/6566/12862 +f 7999/5963/12619 8002/5962/12618 7901/6568/13155 +f 6337/6956/13014 6307/6183/13014 6309/7558/13014 +f 6254/5915/12576 6158/6905/13492 6249/5966/12622 +f 5863/7029/13617 5929/6490/13090 6220/6196/12832 +f 6267/7021/14356 6265/7208/14356 6270/7219/14356 +f 6017/5820/12496 6184/5819/12495 6225/5938/12596 +f 6289/7170/13014 6296/6000/14357 6295/6384/13014 +f 7553/7559/14358 7551/7560/12567 7544/7034/12567 +f 6812/5890/12557 6815/7188/14359 6841/5888/12555 +f 5998/6594/13175 5999/7026/13614 5996/7022/13610 +f 6162/7506/14270 6161/7263/13894 6159/6624/13203 +f 6209/6163/12805 5919/6162/12804 5918/5908/12569 +f 5993/6467/13073 5991/7299/13937 5959/6221/12851 +f 5966/7561/14360 5967/6926/13518 5879/5931/12589 +f 6253/6932/13520 6252/6623/13202 6242/6931/13519 +f 7820/7286/14361 7823/5848/14362 7822/7287/14362 +f 6234/6018/12669 6235/5833/12507 6136/6866/13444 +f 6300/6864/14149 6298/7374/14055 6289/7170/13775 +f 5934/7007/13590 5932/6407/13023 6001/6389/13007 +f 6915/7154/12440 6913/7562/12440 6932/6901/12440 +f 6024/7563/14363 6197/7066/13660 6198/6067/12713 +f 5804/5817/13817 5803/6411/13487 5822/6371/12989 +f 5913/5827/12501 5914/6611/13189 6235/5833/12507 +f 7695/7235/14364 7698/6965/14063 7697/7564/14365 +f 6692/7103/12472 6666/6759/12472 6696/6726/12472 +f 6580/5759/14292 6595/6520/13723 6584/6625/13205 +f 6094/7528/14301 6085/6341/12958 6076/6193/12829 +f 7742/7320/14366 7726/6045/14367 7743/5809/14368 +f 5834/6939/13528 5833/5743/12429 5832/6372/12991 +f 6008/7565/14369 6007/7492/14249 6005/7474/14224 +f 6621/7196/13800 6620/7550/14345 6619/6125/12770 +f 6176/7249/13875 6263/6105/12749 6174/5854/12523 +f 6835/7173/14370 6769/6058/12705 6848/6060/12707 +f 7521/7368/14046 7520/6227/12857 7519/7314/13961 +f 6687/7098/12472 6702/7340/12472 6685/7041/12472 +f 7551/7560/14371 7548/6313/14371 7660/6452/14371 +f 6225/5938/12596 6223/6263/12888 6207/6262/12887 +f 6240/6879/13458 6030/6880/13459 6032/7179/13784 +f 6811/6666/14372 6824/7537/14317 6825/6152/13810 +f 6261/5914/12575 6262/5913/12574 6260/6870/13448 +f 6073/6885/13465 6072/7514/14278 6081/6203/12836 +f 6847/7226/13847 6871/6877/13454 6769/6058/12705 +f 7809/6304/12518 7806/7566/14373 7808/6302/12518 +f 6882/6640/13220 6996/6325/13220 6995/7567/13220 +f 6343/6924/14204 6333/6767/14203 6329/7568/14374 +f 7514/7307/13950 7495/6021/13951 7496/6599/14095 +f 5872/6704/13271 5868/7070/13664 5867/6589/13172 +f 7605/5836/12510 7641/6036/12687 7623/7183/14375 +f 6489/6095/12739 6490/6097/12741 6474/6143/12788 +f 6068/6217/12850 6076/6193/12829 6085/6341/12958 +f 6971/6378/12997 6965/5831/12505 6974/5830/12504 +f 6198/6067/12713 6201/6605/13184 6202/6604/13183 +f 6688/6266/14376 6665/6486/13852 6691/6240/12869 +f 6881/7536/14316 6983/6663/13237 6887/7024/13612 +f 5951/6469/13075 5944/7082/13677 5946/5916/12577 +f 6188/6942/13531 6019/6743/13309 6190/6512/13112 +f 6654/7398/14377 6753/5900/14377 6652/5899/14377 +f 7958/5846/13056 7938/6761/13056 7951/6705/13056 +f 6944/5770/12440 6909/5769/12440 6943/7473/14272 +f 6971/6378/12997 6962/6414/13030 6965/5831/12505 +f 7556/6426/13042 7567/7365/14041 7569/6427/13043 +f 5901/6074/12720 6162/7506/14270 6163/5998/12653 +f 5776/5953/13979 5777/5952/14378 5775/7326/13980 +f 6246/6374/12993 6245/6373/12992 6202/6604/13183 +f 6642/6651/12682 6641/7410/12682 6637/6501/12683 +f 6074/6881/13460 6139/6868/13446 6142/7467/14215 +f 6203/6438/13053 6204/6164/12806 6195/5877/12544 +f 6229/6603/13182 6227/7162/13761 6226/7121/13716 +f 6487/7181/13787 6488/6096/12740 6489/6095/12739 +f 6148/7339/14003 6149/7329/13987 6051/7331/13989 +f 5954/7009/13593 5955/7373/14054 5985/6222/12852 +f 7623/7183/14375 7639/7569/14379 7622/7184/13791 +f 6082/6190/12826 6097/5773/12452 6231/6202/12835 +f 6310/6606/13185 6312/6849/13423 6313/6607/13186 +f 7986/7534/14313 8010/7478/14228 8009/7073/13668 +f 6250/5964/12620 6251/6130/12775 6248/5965/12621 +f 7996/6567/13154 7994/7570/14380 7995/6692/13261 +f 6608/7571/14381 6534/6030/12681 6612/6161/12803 +f 6192/6405/13021 6187/6404/13020 6185/6390/13008 +f 6770/6510/13110 6771/6109/12753 6779/6111/12755 +f 7582/7546/14382 7581/7530/14383 7583/6214/13966 +f 5998/6594/13175 5946/5916/12577 5943/5918/12579 +f 6006/7572/14384 6008/7565/14369 6005/7474/14224 +f 6013/7080/13675 6208/6573/13160 5931/6854/13430 +f 5981/7381/14064 5918/5908/12569 5980/5907/12568 +f 7441/6678/13427 7429/6851/13426 7439/6679/14110 +f 6035/6699/13266 6168/6081/12727 6238/6511/13111 +f 6261/5914/12575 6227/7162/13761 6228/6609/13187 +f 7464/6463/13072 7436/7316/14385 7427/6461/13070 +f 6412/7366/14043 6411/5923/12583 6413/6211/12846 +f 5879/5931/12589 5965/7521/14286 5966/7561/14360 +f 6229/6603/13182 6230/7156/13753 6153/6457/13066 +f 6933/6782/12440 6930/6612/12440 6928/6481/12440 +f 6631/7573/14386 6629/7574/14387 6632/7406/14114 +f 5816/6724/13290 5815/6571/13158 5852/7393/14090 +f 6114/6034/12685 6116/7544/14325 6115/7076/13671 +f 5959/6221/12851 5991/7299/13937 5990/6576/13163 +f 7591/6545/12847 7593/7292/12847 7565/7291/12847 +f 6977/7296/13931 6964/7053/13932 6945/7250/14140 +f 6663/6906/13493 6664/6487/14038 6684/7040/13866 +f 6477/6379/12998 6483/6050/12697 6492/7131/13726 +f 6552/7447/12441 6554/6647/12441 6585/6646/12441 +f 7951/6705/13771 7973/5844/12515 7958/5846/12517 +f 5761/6113/12757 5762/5892/12559 5783/5894/12561 +f 6272/6539/13854 6056/7322/13973 6057/7227/13848 +f 7543/6812/13383 7640/6038/12689 7546/6230/12860 +f 6726/7079/13674 6717/7078/13673 6728/6492/13092 +f 6976/6722/13288 6975/5832/12506 6977/7296/13931 +f 5954/7009/13593 5963/7198/13802 5953/7436/14157 +f 7434/6811/14334 7460/6671/14388 7435/6809/14071 +f 6021/6392/13010 6186/7174/13779 6185/6390/13008 +f 6495/6017/12668 6407/6241/12870 6496/6015/12666 +f 6466/7016/13604 6502/6449/13059 6504/7442/14168 +f 6218/6198/12834 5927/7295/13930 5863/7029/13617 +f 6862/6153/12796 6861/7454/14188 6864/7455/14189 +f 6831/6298/12918 6844/5989/12645 6868/5991/12647 +f 5931/6854/13430 5999/7026/13614 6001/6389/13007 +f 6173/6131/12776 6171/7391/14088 6172/6422/13038 +f 6821/7333/13996 6810/6297/12917 6833/6351/12968 +f 6160/6622/13201 6242/6931/13519 6252/6623/13202 +f 6712/6563/13151 6711/5753/12439 6741/5752/12438 +f 7924/5883/13056 7956/5868/13056 7927/6701/13056 +f 6474/6143/12788 6473/7497/14256 6485/6144/12789 +f 5785/5893/13896 5786/6464/13896 5784/6466/13897 +f 5784/6466/13897 5781/6577/13164 5782/7575/14389 +f 7719/7360/14035 7733/7576/14390 7718/7486/14391 +f 6176/7249/13875 6179/5853/12522 6166/5866/12535 +f 6162/7506/14270 5901/6074/12720 5917/6756/13326 +f 6645/6556/12916 6646/7240/13867 6644/7414/12914 +f 6139/6868/13446 6074/6881/13460 6233/6023/12674 +f 6055/7323/13975 6271/7165/13974 6054/7443/14169 +f 6247/6375/12994 6244/6773/13342 6245/6373/12992 +f 6587/7134/13729 6586/7256/14060 6624/7058/13651 +f 6173/6131/12776 6251/6130/12775 6253/6932/13520 +f 7487/6873/13451 7473/6179/13734 7488/7140/13733 +f 6097/5773/12452 6237/5826/12500 6231/6202/12835 +f 6087/7485/14236 6088/6215/12848 6068/6217/12850 +f 7961/7555/14392 7981/5867/12536 7960/7577/14393 +f 6181/6911/13499 6182/6047/12694 6164/7127/13720 +f 6849/5798/12475 6764/7288/14133 6850/5796/12473 +f 6577/7230/13856 6590/7231/13857 6591/7011/13595 +f 5911/6764/13333 6079/7148/13743 5910/6762/13331 +f 6166/5866/12535 6167/5865/12534 6151/6307/12928 +f 7431/7578/14394 7448/6922/14219 7432/7063/13657 +f 6828/7201/13809 6866/7424/14137 6867/5990/12646 +f 6136/6866/13444 6139/6868/13446 6234/6018/12669 +f 6754/7303/13941 6762/7357/14395 6864/7455/14189 +f 6239/6115/12760 6241/7220/13842 6197/7066/13660 +f 6178/6242/12871 6182/6047/12694 6181/6911/13499 +f 6152/6319/12942 6165/7207/13824 6166/5866/12535 +f 5931/6854/13430 5860/6310/12931 6013/7080/13675 +f 6241/7220/13842 6201/6605/13184 6197/7066/13660 +f 6028/7579/14396 6029/7056/13649 6199/7055/13648 +f 7659/6694/13785 7544/7034/13785 7551/7560/13785 +f 6291/6119/12764 6305/6118/12763 6303/7445/14171 +f 6837/6738/14397 6848/6060/12707 6849/5798/12475 +f 6107/6195/12831 6108/6685/13255 6076/6193/12829 +f 7521/7368/14046 7522/6228/12858 7520/6227/12857 +f 5921/7039/13629 6211/6386/13004 5918/5908/12569 +f 7843/6249/14196 7855/7211/13830 7854/5799/14197 +f 6026/6066/12712 6024/7563/14363 6198/6067/12713 +f 5990/6576/13163 5989/7050/13642 5986/7351/14027 +f 6302/6865/13443 6303/7445/14398 6304/6317/12937 +f 6778/5981/12637 6770/6510/13110 6807/5982/12638 +f 7553/7559/14358 7654/7482/14233 7628/6361/12979 +f 7770/7423/14136 7663/6327/12949 7767/6329/12951 +f 6724/6728/13295 6732/6649/13225 6734/6056/12703 +f 6933/6782/13353 6947/6784/13355 6946/6780/14327 +f 6332/5901/13014 6331/5903/13014 6301/6451/13014 +f 6207/6262/12887 6208/6573/13160 6015/7257/13890 +f 5852/7393/14090 5853/6283/12906 5816/6724/13290 +f 6467/7017/13605 6466/7016/13604 6505/6898/13479 +f 7783/7242/14399 7667/7276/14399 7665/6332/14399 +f 6016/7379/14061 6017/5820/12496 6206/6774/13343 +f 6620/7550/14345 6621/7196/13800 6605/7383/14343 +f 7507/6400/13016 7426/6524/13119 7506/6269/12894 +f 5842/6526/13120 5808/5778/12457 5841/5780/12459 +f 6562/6745/13312 6565/6184/13457 6564/7469/14400 +f 5867/6589/13172 5866/6588/13171 5871/6703/13270 +f 7775/6896/13476 7734/6485/13087 7776/6106/12750 +f 6433/6970/14401 6418/7418/14237 6419/7293/14402 +f 6132/6635/13218 6106/6194/12830 6076/6193/12829 +f 6370/7370/14050 6369/7404/14108 6368/7403/14107 +f 6147/7164/13763 6113/6033/12684 6075/6035/12686 +f 6979/6779/13350 6980/5815/12492 6978/6720/13286 +f 6024/7563/14363 6025/6116/12761 6197/7066/13660 +f 6625/7059/13652 6624/7058/13651 6606/6454/13818 +f 7628/6361/12979 7654/7482/14233 7627/6362/12980 +f 6524/7504/14265 6632/7406/14114 6629/7574/14387 +f 7890/7551/14346 7891/6541/13135 7792/7014/13599 +f 6168/6081/12727 6033/7043/13635 6037/6082/12728 +f 7857/7069/14403 7844/6009/13575 7858/6425/13574 +f 6226/7121/13716 6081/6203/12836 6229/6603/13182 +f 7666/6696/13264 7668/6695/13263 7671/5776/12455 +f 6533/6159/12801 6528/6746/13313 6616/6508/13108 +f 6020/5876/12543 6028/7579/14396 6199/7055/13648 +f 6039/7554/14351 6038/7471/14216 6177/6048/12695 +f 6163/5998/12653 6153/6457/13066 5864/6170/12812 +f 5949/6419/13035 5950/6468/13074 5959/6221/12851 +f 6387/6754/13324 6389/7540/14321 6386/6755/13325 +f 7776/6106/12750 7670/6108/12752 7664/6980/13562 +f 6175/6129/12774 6174/5854/12523 6262/5913/12574 +f 7615/7375/14057 7626/6478/13081 7614/7387/14081 +f 6453/6201/12708 6458/6951/12708 6442/6199/12708 +f 5795/6929/13878 5796/7136/14304 5807/5779/14306 +f 7884/7356/14030 7856/7212/13832 7885/7432/14152 +f 7889/6424/13040 7887/7431/14150 7888/7068/13662 +f 6051/7331/13989 6053/7552/14349 6167/5865/12534 +f 5830/7396/14096 5754/6366/14175 5831/7305/13948 +f 6479/7580/14404 6494/7132/13727 6495/6017/12668 +f 6395/7581/14405 6274/6281/14405 6281/6280/14405 +f 5870/6610/13188 5867/6589/13172 5869/7071/13665 +f 7798/6835/14406 7898/7377/14406 7897/7582/14406 +f 6041/6080/12726 6040/7553/14350 6177/6048/12695 +f 5916/6822/13394 6230/7156/13753 6231/6202/12835 +f 6183/6253/12878 6192/6405/13021 6185/6390/13008 +f 7807/7583/14407 7828/7309/14408 7830/6891/14409 +f 6171/7391/14088 6173/6131/12776 6253/6932/13520 +f 6783/7187/12498 6785/6476/12498 6819/6739/12498 +f 7980/6189/12825 7960/7577/14393 7981/5867/12536 +f 6403/5924/14410 6516/6687/14410 6517/6902/14410 +f 6222/5937/12595 6188/6942/13531 6221/6893/13472 +f 6161/7263/13894 5919/6162/12804 6204/6164/12806 +f 6698/7400/14202 6699/6564/12472 6690/6264/12472 +f 7418/6582/13168 7535/6584/13168 7411/7274/13168 +f 7834/6725/12518 7844/6009/12518 7836/6008/12518 +f 7663/6327/12949 7773/7077/13672 7664/6980/13562 +f 6013/7080/13675 5860/6310/12931 6012/6913/13502 +f 7852/5847/14411 7865/7380/14412 7853/5912/12573 +f 6101/7089/13683 6099/5772/12451 6100/7054/13647 +f 5988/5807/12484 5984/5829/12503 5986/7351/14027 +f 6092/6669/13241 6093/7529/14302 6111/6670/13242 +f 7847/6834/12518 7846/6833/12518 7816/6788/12518 +f 6465/7399/14098 6501/6450/13060 6502/6449/13059 +f 5938/7495/14254 5937/7510/14274 6000/6316/12936 +f 5995/6595/13176 5998/6594/13175 5996/7022/13610 +f 5930/6791/13363 5994/7023/13611 5997/7027/13615 +f 6110/6933/13521 6103/6935/13523 6104/7433/14153 +f 6580/5759/14413 6581/6832/14413 6593/7102/14413 +f 6179/5853/12522 6176/7249/13875 6174/5854/12523 +f 7752/7206/13820 7741/6396/13969 7753/7246/13871 +f 6794/6843/13655 6774/7061/13654 6795/6802/13374 +f 8009/7073/13668 7971/7277/14213 7987/7584/14414 +f 8007/7074/13669 8009/7073/13668 7907/6551/13872 +f 6000/6316/12936 5935/6315/12935 5936/7494/14253 +f 7677/6836/12692 7681/6971/13550 7683/7372/12562 +f 6139/6868/13446 6141/7479/14229 6142/7467/14215 +f 6076/6193/12829 6111/6670/13242 6093/7529/14302 +f 7554/6693/13262 7629/7513/14277 7631/6343/12960 +f 6196/5878/12545 6194/7258/13891 6020/5876/12543 +f 6397/7556/12905 6396/7585/12905 6394/7557/12905 +f 6824/7537/14317 6823/7203/13812 6858/5766/12448 +f 5746/6339/12985 5750/7505/14268 5743/5788/14288 +f 6295/6384/13001 6296/6000/12655 6322/5999/12654 +f 6282/7402/14102 6280/6680/13253 6279/6600/12905 +f 6938/5995/12650 6963/6415/13031 6962/6414/13030 +f 7899/6945/13534 8002/5962/12618 8003/6943/13532 +f 7872/6005/12660 7873/6006/12661 7871/7416/14130 +f 6851/7498/14258 6854/7401/14100 6852/6165/12807 +f 7944/7586/14415 7947/7459/14416 7946/7587/14416 +f 6974/5830/12504 6976/6722/13288 6973/6684/13254 +f 6612/6161/12803 6611/6894/13474 6608/7571/14381 +f 6796/6844/13420 6795/6802/14417 6797/6801/13637 +f 6003/7475/14225 6006/7572/14384 6005/7474/14224 +f 7789/6968/14080 7884/7356/14030 7885/7432/14152 +f 5907/7224/13845 5908/6757/13327 5901/6074/12720 +f 6530/7015/13600 6534/6030/12681 6594/6521/13117 +f 5862/7247/13873 5861/6261/12886 5930/6791/13363 +f 5975/6086/12730 5894/6088/12732 5895/6259/12884 +f 5839/6321/12944 5807/5779/12458 5826/7531/14418 +f 6971/6378/12997 6973/6684/13254 6972/6376/12995 +f 6181/6911/13499 6048/7545/14328 6046/7085/13680 +f 7669/7101/13697 7737/6777/13346 7675/6333/12955 +f 5984/5829/12503 5988/5807/12484 5867/6589/13172 +f 6668/6295/12472 6696/6726/12472 6666/6759/12472 +f 6521/6500/13099 6638/6652/13099 6637/6501/13099 +f 7841/6675/13249 7812/7259/14280 7811/6789/13361 +f 6623/7205/13819 6626/7094/13688 6625/7059/13652 +f 7660/6452/12567 7655/5905/12567 7659/6694/12567 +f 6688/6266/14376 6686/7362/14039 6664/6487/14038 +f 6424/6218/13829 6425/6908/13495 6427/6219/13497 +f 6053/7552/14349 6151/6307/12928 6167/5865/12534 +f 7693/7199/13804 7692/6044/13804 7694/7519/13804 +f 6199/7055/13648 6027/6065/12711 6195/5877/12544 +f 6075/6035/12686 6074/6881/13460 6145/7318/13965 +f 6478/6380/12999 6477/6379/12998 6492/7131/13726 +f 5798/6742/13308 5799/7341/14004 5810/6527/13121 +f 5901/6074/12720 5902/6076/12722 5903/6958/13544 +f 6022/6391/13009 6185/6390/13008 6187/6404/13020 +f 6687/7098/12472 6689/6265/12472 6697/6976/12472 +f 6002/7511/14275 6003/7475/14225 6000/6316/12936 +f 6595/6520/13116 6534/6030/12681 6596/5947/12604 +f 6698/7400/14202 6690/6264/12472 6692/7103/12472 +f 7431/7578/14394 7433/6810/12542 7430/7067/12542 +f 7595/7388/14083 7600/6212/14419 7610/6079/14084 +f 6884/6434/14420 6995/7567/14420 6994/6435/14420 +f 6898/5755/12440 6894/5974/12440 6897/5975/12440 +f 7809/6304/12925 7835/6303/12924 7837/5760/14421 +f 7909/6305/13054 7911/6440/13054 7912/7167/13054 +f 7524/6941/13530 7527/7490/14248 7528/6167/12809 +f 7885/7432/14152 7856/7212/13832 7886/7104/13700 +f 6304/6317/12937 6301/6451/13441 6302/6865/13443 +f 7577/6824/14007 7576/7344/14009 7578/5763/12445 +f 7685/6785/13356 7687/7542/14323 7686/6837/13511 +f 6805/5942/12636 6777/6847/13883 6778/5981/12637 +f 6789/6003/12844 6773/6210/12843 6790/7301/13939 +f 7511/7025/13613 7420/6234/12863 7509/6874/13452 +f 7237/7588/14422 7236/7589/14423 7235/7590/14424 +f 7763/6861/13438 7765/7191/13795 7766/6328/12950 +f 6632/7406/14114 6524/7504/14265 6531/6250/12875 +f 7726/6045/14367 7741/6396/13013 7728/6043/13012 +f 6973/6684/13254 6976/6722/13288 6883/7591/14425 +f 7489/7150/13745 7478/6772/14131 7490/6270/12895 +f 5797/6741/12493 5801/6465/12493 5786/6464/12493 +f 6830/7321/13972 6829/7439/14162 6845/6672/13246 +f 6328/6397/13014 6327/6637/13014 6325/6636/13014 +f 7558/7113/12847 7556/6426/12847 7557/6428/12847 +f 7613/6765/13334 7654/7482/14233 7612/6530/13124 +f 6437/7147/14426 6438/6175/14426 6436/6099/12743 +f 7744/5808/14427 7725/7266/14428 7745/6548/14429 +f 6466/7016/13604 6465/7399/14098 6502/6449/13059 +f 7061/7592/14430 7126/7593/14431 7125/7594/14432 +f 7672/7355/14433 7758/5777/12456 7671/5776/12455 +f 5789/6973/13552 5764/6299/12920 5791/6301/12922 +f 7550/7035/13625 7652/7535/14314 7549/7036/13626 +f 7322/7595/14434 7156/7596/14435 7155/7597/14436 +f 7374/7598/14437 7237/7588/14422 7375/7599/14438 +f 7051/7600/14439 7122/7601/14440 7050/7602/14441 +f 7373/7603/14442 7267/7604/14443 7374/7598/14437 +f 6811/6666/14372 6825/6152/13810 6814/6417/13033 +f 7865/7380/14412 7852/5847/14411 7866/7605/14444 +f 6631/7573/14386 6630/7371/14051 6629/7574/14387 +f 7499/7524/14294 7525/7324/13977 7482/7462/14200 +f 6458/6951/14445 6470/7177/13782 6471/7176/13781 +f 6606/6454/13818 6621/7196/13800 6622/7195/13799 +f 6885/7008/14446 6879/6733/14447 6993/6732/14446 +f 7912/7167/14448 7989/7457/14193 7976/6532/13126 +f 6791/6639/13219 6792/7062/14118 6793/6842/13418 +f 7317/7606/14449 7318/7607/14450 7312/7608/14451 +f 6400/5925/12583 6404/6688/12583 6405/6274/12899 +f 6832/6133/12778 6831/6298/12918 6870/6134/12779 +f 6279/6600/14452 6273/6682/14452 6394/7557/14452 +f 8012/7452/14183 7985/6025/12676 7989/7457/14193 +f 7305/7609/14453 7317/7606/14449 7304/7610/14454 +f 6437/7147/14426 6436/6099/12743 6435/6098/12742 +f 7743/5809/12486 7758/5777/12456 7757/5870/12539 +f 7158/7611/14455 7334/7612/14456 7333/7613/14457 +f 6382/6138/12783 6380/5930/12588 6381/6141/12786 +f 7706/7248/13732 7704/6535/13814 7705/5896/13814 +f 7787/6967/13411 7791/6966/13411 7794/6953/13411 +f 7118/7614/14458 7029/7615/14459 7056/7616/14460 +f 6656/6292/12915 6653/6102/12746 6650/6927/12916 +f 6592/7010/13594 6581/6832/14461 6575/7470/14315 +f 7400/7617/14462 7392/7618/14463 7399/7619/14464 +f 7084/7620/14465 7081/7621/14466 7085/7622/14467 +f 6353/6356/14269 6352/6090/13359 6369/7404/14108 +f 7580/5764/12847 7578/5763/12847 7592/6529/12847 +f 7549/7036/13626 7652/7535/14314 7653/7483/14234 +f 7849/7518/14332 7861/6540/13134 7860/6542/14333 +f 6276/6503/13100 6285/6830/13406 6363/6504/13101 +f 6463/6992/14257 6473/7497/14256 6459/6061/14282 +f 7017/7623/14468 7025/7624/14469 7024/7625/14470 +f 6834/7225/13846 6835/7173/13778 6822/6889/13777 +f 7322/7595/14434 7363/7626/14471 7360/7627/14472 +f 7582/7546/14329 7560/6823/13396 7581/7530/14303 +f 6770/6510/12498 6778/5981/12498 6777/6847/12498 +f 5764/6299/12493 5763/6974/13027 5762/5892/12493 +f 7849/7518/12518 7829/6892/12518 7842/7268/12518 +f 7388/7628/14473 7387/7629/14474 7386/7630/14475 +f 7017/7623/14468 7024/7625/14470 7021/7631/14476 +f 7859/6423/13573 7844/6009/13575 7848/7517/14331 +f 6900/7284/12440 6898/5755/12440 6899/7451/12440 +f 7929/6472/13056 7961/7555/13056 7960/7577/13056 +f 6579/5839/12441 6578/6453/12441 6547/5891/12558 +f 7926/6702/14223 7915/7411/14145 7925/6700/14147 +f 7545/6231/12567 7550/7035/13625 7544/7034/12567 +f 6922/6497/12440 6920/7282/14272 6940/6751/12440 +f 6440/6176/14477 6438/6175/14426 6437/7147/14426 +f 6812/5890/12557 6842/5889/12556 6823/7203/13812 +f 7476/7261/12542 7443/6960/12542 7471/6020/12542 +f 7524/6941/13530 7419/7273/13907 7522/6228/12858 +f 6622/7195/13799 6523/7105/13701 6623/7205/13819 +f 6685/7041/12472 6703/6347/12472 6682/7168/12472 +f 7572/6984/13565 7558/7113/14478 7570/6819/14479 +f 7043/7632/14480 7301/7633/14481 7037/7634/14482 +f 6824/7537/14317 6858/5766/12448 6859/5768/12450 +f 7765/7191/13795 7748/7635/14483 7749/7190/13794 +f 6406/5926/12584 6503/6448/13058 6499/6192/12828 +f 7499/7524/14294 7483/7233/13859 7526/7489/14247 +f 6739/7004/13587 6740/5751/12437 6711/5753/12439 +f 7558/7113/14478 7557/6428/13044 7570/6819/14479 +f 7593/7292/14032 7606/5837/14484 7605/5836/14033 +f 7372/7636/14485 7373/7603/14442 7051/7600/14439 +f 7370/7637/14486 7371/7638/14487 7050/7602/14441 +f 5775/7326/13980 5773/6155/12798 5774/6154/12797 +f 7833/7222/14488 7835/6303/12924 7808/6302/12923 +f 6585/6646/14489 6597/5946/13204 6598/5960/14129 +f 6475/7117/13712 6462/6062/13711 6459/6061/14282 +f 6417/7419/14239 6429/5934/14262 6416/7503/14264 +f 5764/6299/12493 5762/5892/12493 5760/6112/12756 +f 7661/6981/13868 7667/7276/14490 7783/7242/13868 +f 7251/7639/14491 7213/7640/14492 7252/7641/14493 +f 5773/6155/12798 5772/7512/14494 5771/6156/12799 +f 6935/6496/12440 6922/6497/12440 6940/6751/12440 +f 6792/7062/13656 6790/7301/13939 6774/7061/13654 +f 7180/7642/14495 7315/7643/14496 7320/7644/14497 +f 6380/5930/12588 6378/7645/14498 6379/6522/13118 +f 6852/6165/12807 6840/7389/14085 6851/7498/14258 +f 7429/6851/13426 7428/7345/14111 7439/6679/14110 +f 6947/6784/13774 6980/5815/12492 6946/6780/13351 +f 6735/6057/12704 6733/6648/13224 6651/7441/14165 +f 7720/6354/12971 7718/7486/14391 7732/6355/12972 +f 7841/6675/13404 7811/6789/14499 7802/6829/13405 +f 7165/7646/14500 7336/7647/14501 7164/7648/14502 +f 6283/6064/12710 6287/6063/12905 6281/6280/12905 +f 6367/5881/12548 6366/5880/12547 6287/6063/12709 +f 7039/7649/14503 7040/7650/14504 7038/7651/14505 +f 7582/7546/14382 7583/6214/13966 7584/7319/13967 +f 6766/7420/14134 6764/7288/12962 6761/6014/12962 +f 7179/7652/14506 7175/7653/14507 7306/7654/14508 +f 7348/7655/14509 7333/7613/14457 7334/7612/14456 +f 7903/7417/14132 7904/6683/13054 7908/6549/13141 +f 7113/7656/14510 7032/7657/14511 7031/7658/14512 +f 7655/5905/12567 7660/6452/12567 7656/6312/12567 +f 7440/6677/13250 7436/7316/13963 7437/7390/14087 +f 7396/7659/14513 7401/7660/14514 7395/7661/14515 +f 7318/7607/14450 7317/7606/14449 7305/7609/14453 +f 6498/7019/13607 6480/6016/12667 6496/6015/12666 +f 6393/6505/13102 6391/6357/12974 6392/7466/14212 +f 7169/7662/14516 7163/7663/14517 7377/7664/14518 +f 7774/6895/13475 7770/7423/14136 7771/7412/14120 +f 7785/7665/12956 7783/7242/12956 7784/7666/12956 +f 7595/7388/12847 7589/6554/12847 7586/6213/12847 +f 7313/7667/14519 7311/7668/14520 7389/7669/14521 +f 6565/6184/13457 6566/7670/14522 6564/7469/14400 +f 7751/6121/12766 7755/6120/12765 7675/6333/12955 +f 8015/7311/14523 7906/6439/14523 7902/7310/14523 +f 7871/7416/14130 7873/6006/12661 7862/7269/13900 +f 7793/6954/13597 7792/7014/13599 7801/6349/12966 +f 6428/7502/14297 6430/5936/12594 6427/6219/13497 +f 6966/6947/13536 6967/6975/13554 6958/6948/13537 +f 6528/6746/13313 6529/6650/14524 6521/6500/12683 +f 6983/6663/13237 6981/5814/12491 6982/6658/13232 +f 6365/6794/13366 6366/5880/12547 6360/6633/13215 +f 7057/7671/14525 7342/7672/14526 7347/7673/14527 +f 7789/6968/14080 7882/5800/12477 7883/7426/14139 +f 7741/6396/13969 7754/6122/12767 7753/7246/13871 +f 7002/7674/14528 7036/7675/14529 7003/7676/14530 +f 7029/7615/14459 7115/7677/14531 7114/7678/14532 +f 7505/6978/13560 7504/7245/13870 7502/6979/13561 +f 5793/7384/14077 5765/6627/13208 5766/6626/13207 +f 7235/7590/14424 7234/7679/14533 7220/7680/14534 +f 7214/7681/14535 7245/7682/14536 7244/7683/14537 +f 6837/6738/13304 6838/5797/13693 6819/6739/13305 +f 6377/7429/14144 6378/7645/14498 6376/5856/12525 +f 7358/7684/14538 7356/7685/14539 7357/7686/14540 +f 7470/6598/12542 7437/7390/12542 7467/5873/12542 +f 6767/6345/12962 6758/6344/12961 6759/7229/12962 +f 7369/7687/14541 7220/7680/14534 7219/7688/14542 +f 7624/7446/14174 7633/6146/12791 7634/6432/13049 +f 7969/6409/13934 8008/7075/13670 8005/7298/13935 +f 6659/6841/13417 6669/6840/13416 6667/7335/14543 +f 7226/7689/14544 7206/7690/14545 7227/7691/14546 +f 7512/5887/12554 7514/7307/13950 7515/5885/12552 +f 7451/6180/12542 7472/6562/12542 7453/6561/12542 +f 7097/7692/14547 7094/7693/14548 7123/7694/14549 +f 7492/7359/14353 7476/7261/13892 7493/5841/14550 +f 5745/6938/13527 5747/6937/13526 5741/7002/12984 +f 6886/6255/12880 6889/6243/13591 6882/6640/13591 +f 6284/6642/13094 6398/6641/13094 6399/7695/13094 +f 6285/6830/13406 6276/6503/12905 6277/6601/12905 +f 6371/6358/12976 6373/6360/12978 6370/7370/14050 +f 7320/7644/14497 7315/7643/14496 7316/7696/14551 +f 7869/6715/13281 7846/6833/14552 7870/5801/12478 +f 6968/6244/12873 6967/6975/13554 6969/7533/14311 +f 5787/6990/14553 5786/6464/13896 5785/5893/13896 +f 7351/7697/14554 7331/7698/14555 7321/7699/14556 +f 6286/6602/13181 6276/6503/13100 6391/6357/12974 +f 6545/7532/14309 6571/6149/13278 6572/6713/13280 +f 7518/7217/13837 7517/6071/12717 7519/7314/13961 +f 7113/7656/14510 7031/7658/14512 7030/7700/14557 +f 7033/7701/14558 7113/7656/14510 7034/7702/14559 +f 6999/7703/14560 7361/7704/14561 7345/7705/14562 +f 7547/6430/13047 7634/6432/13049 7636/7209/13826 +f 7832/6890/12518 7829/6892/12518 7849/7518/12518 +f 7484/7232/13858 7468/7234/13860 7474/7427/14563 +f 7685/6785/12562 7713/6041/12562 7716/6040/12562 +f 7434/6811/14334 7458/7407/14334 7460/6671/14388 +f 5783/5894/12561 5782/7575/14564 5761/6113/12757 +f 6354/6632/13214 6355/5902/12565 6332/5901/12564 +f 6418/7418/14237 6433/6970/14401 6431/7241/14238 +f 6452/6731/13298 6481/6559/13149 6482/6916/13506 +f 5743/5788/14288 5742/6781/14287 5740/6340/14288 +f 7751/6121/12766 7739/6053/13821 7752/7206/13820 +f 7438/7317/13964 7440/6677/13250 7439/6679/13252 +f 6963/6415/13031 6975/5832/12506 6965/5831/12505 +f 6278/6279/12904 6372/7526/14298 6371/6358/12976 +f 6336/7461/14565 6351/6089/12733 6335/6091/12735 +f 6590/7231/14566 6589/6620/14567 6631/7573/14386 +f 6540/7281/13916 6559/6748/13915 6557/7706/14568 +f 7890/7551/14346 7797/7013/13598 7889/6424/13040 +f 7610/6079/14084 7600/6212/14419 7611/6816/14569 +f 6356/7072/13666 6355/5902/14010 6374/6359/12977 +f 7677/6836/13412 7684/6921/14245 7686/6837/13413 +f 7304/7610/14454 7190/7707/14570 7289/7708/14571 +f 7149/7709/14572 7071/7710/14573 6998/7711/14574 +f 7080/7712/14575 7138/7713/14576 7073/7714/14577 +f 6458/6951/14445 6471/7176/13781 6457/6177/14578 +f 5769/5816/14579 5768/7275/14580 5767/6628/13209 +f 7519/7314/13961 7520/6227/12857 7518/7217/13837 +f 7190/7707/14570 7304/7610/14454 7290/7715/14581 +f 8010/7478/14228 8012/7452/14183 8011/7460/14199 +f 6442/6199/13103 6440/6176/14477 6439/7146/14477 +f 5858/6999/12985 5857/7472/12985 5856/6338/12985 +f 7937/6148/12945 7936/6322/12640 7938/6761/14582 +f 6883/7591/14425 6885/7008/13592 6888/7369/14048 +f 6909/5769/14583 6906/7283/14584 6907/6797/13369 +f 6959/6946/13535 6969/7533/14311 6966/6947/13536 +f 6593/7102/13698 6607/7464/14209 6636/5851/12520 +f 6350/6955/13541 6349/6957/13543 6360/6633/13215 +f 6799/5824/12498 6800/6010/12498 6817/5822/12498 +f 7997/7325/13978 7996/6567/13154 7984/6460/13069 +f 7801/6349/12966 7873/6006/12661 7874/5784/12463 +f 7306/7654/14508 7315/7643/14496 7179/7652/14506 +f 6320/6382/13001 6317/7189/14091 6294/6383/13002 +f 7223/7716/14585 7206/7690/14545 7224/7717/14586 +f 7867/7525/14587 7850/5849/14588 7868/7338/14589 +f 6708/6787/12472 6706/7255/12472 6676/7045/12472 +f 6957/6977/13558 6967/6975/13554 6956/6910/13498 +f 7703/5897/12562 7724/6395/12562 7717/5895/12562 +f 6550/7448/14177 6551/7718/14590 6552/7447/14176 +f 7587/7157/13803 7562/5748/12434 7585/5750/12436 +f 7047/7719/14591 7056/7616/14460 7029/7615/14459 +f 6601/6827/14001 6600/6127/13477 6615/6506/13106 +f 6815/7188/14359 6840/7389/14592 6841/5888/12555 +f 7647/7539/14320 7649/6077/12723 7546/6230/12860 +f 6280/6680/13253 6282/7402/14102 6383/6142/12787 +f 6357/5858/12527 6328/6397/13525 6331/5903/12566 +f 7383/7720/14593 7385/7721/14594 7384/7722/14595 +f 6545/7532/14309 6544/7547/14596 6546/7109/14310 +f 7526/7489/14247 7524/6941/13530 7523/6940/13529 +f 7602/7253/12847 7571/6820/12847 7598/6660/12847 +f 6747/7723/14597 6648/6291/12983 6728/6492/13092 +f 7743/5809/14368 7725/7266/14428 7744/5808/14427 +f 7444/7405/14598 7446/6441/14599 7431/7578/14394 +f 6803/5944/14259 6804/5943/14259 6802/7499/14260 +f 7564/6543/13895 7556/6426/13042 7555/7264/13895 +f 7349/7724/14600 7351/7697/14554 7352/7725/14601 +f 6555/5745/13945 6558/5757/13315 6556/7172/13945 +f 7604/7515/12847 7576/7344/12847 7601/7376/12847 +f 7147/7726/14602 7138/7713/14576 7139/7727/14603 +f 7841/6675/13249 7810/6674/13248 7812/7259/14280 +f 7323/7728/14604 7159/7729/14605 7160/7730/14606 +f 7596/6555/14607 7606/5837/14484 7593/7292/14032 +f 7556/6426/12847 7563/6888/12847 7555/7264/12847 +f 7987/7584/14414 7971/7277/14213 7972/5845/12516 +f 6901/7332/13990 6904/6799/13371 6903/6828/13402 +f 6540/7281/13916 6555/5745/12431 6539/5747/12433 +f 7766/6328/12950 7666/6696/13264 7763/6861/13438 +f 7503/7151/13746 7534/6402/13018 7488/7140/13841 +f 7325/7731/14608 7329/7732/14609 7330/7733/14610 +f 7139/7727/14603 6998/7711/14574 7070/7734/14611 +f 6657/7347/14014 6654/7398/12916 6652/5899/14166 +f 7823/5848/14612 7824/5920/14612 7822/7287/14612 +f 7941/6760/13490 7939/5864/14115 7938/6761/14582 +f 6572/6713/14613 6570/6712/14614 6535/7538/14335 +f 7689/6920/13864 7690/7236/13863 7692/6044/14173 +f 7963/6706/13056 7936/6322/13056 7934/5983/13056 +f 7813/5978/13601 7803/6987/13570 7811/6789/14499 +f 7087/7735/14615 7094/7693/14548 7097/7692/14547 +f 6394/7557/12905 6395/7581/12905 6399/7695/12905 +f 7826/5919/12580 7825/5921/12581 7827/6995/12580 +f 7029/7615/14459 7028/7736/14616 7027/7737/14617 +f 7695/7235/14364 7694/7519/14618 7696/7111/14364 +f 7311/7668/14520 7316/7696/14551 7310/7738/14619 +f 6534/6030/12681 6608/7571/14381 6596/5947/12604 +f 6375/5857/12526 6376/5856/12525 6378/7645/14498 +f 5781/6577/13164 5780/6996/13582 5782/7575/14389 +f 5815/6571/13158 5851/6570/13157 5852/7393/14090 +f 6722/7516/14279 6723/7095/13690 6704/5793/13689 +f 7788/7507/13597 7789/6968/13411 7787/6967/13411 +f 7839/5761/12443 7810/6674/13248 7840/6673/13247 +f 6750/7114/14161 6649/6293/14161 6650/6927/14161 +f 7910/6306/12927 7906/6439/13054 7909/6305/13054 +f 5787/6990/13553 5762/5892/12559 5763/6974/13553 +f 7333/7613/14457 7341/7739/14620 7336/7647/14501 +f 7486/6872/13450 7485/7487/14621 7475/6560/14622 +f 6565/6184/12821 6562/6745/14623 6541/6185/12822 +f 7406/7740/14624 7401/7660/14514 7396/7659/14513 +f 8017/7099/13054 8014/7279/13054 8016/7100/13054 +f 5748/6367/14056 5855/7003/14056 5741/7002/14625 +f 6374/6359/12977 6371/6358/12976 6372/7526/14298 +f 7842/7268/13899 7861/6540/13134 7849/7518/14332 +f 6290/7430/14148 6302/6865/14626 6300/6864/14149 +f 7698/6965/14063 7699/7271/13902 7697/7564/14365 +f 7454/6629/13210 7453/6561/14627 7455/6514/13114 +f 7292/7741/14628 7294/7742/14629 7291/7743/14630 +f 5792/6928/12493 5766/6626/12493 5796/7136/12493 +f 7943/6903/13488 7942/7744/13488 7940/5862/13489 +f 5774/6154/13806 5759/6552/13805 5760/6112/12756 +f 7500/5843/12514 7507/6400/13016 7501/6271/12896 +f 6771/6109/12753 6772/6286/12909 6782/6285/12908 +f 7131/7745/14631 7089/7746/14632 7088/7747/14633 +f 7845/6007/13831 7857/7069/13663 7856/7212/13832 +f 5749/5791/12470 5750/7505/14268 5744/6961/12985 +f 5770/7465/14634 5772/7512/14494 5769/5816/14579 +f 7574/7440/12847 7603/7297/12847 7601/7376/12847 +f 6341/6499/13098 6340/5928/12586 6384/6140/12785 +f 6881/7536/14635 6878/7748/14635 6880/6721/14636 +f 7792/7014/13599 7873/6006/12661 7801/6349/12966 +f 7639/7569/14379 7637/6813/13384 7621/6661/14042 +f 7422/7124/13717 7418/6582/12862 7419/7273/13907 +f 7615/7375/14057 7630/6363/12981 7626/6478/13081 +f 6480/6016/12667 6479/7580/14404 6495/6017/12668 +f 7901/6568/13155 7900/7265/13054 7902/7310/13054 +f 7362/7749/14637 7067/7750/14638 7358/7684/14538 +f 6749/5898/12563 6644/7414/12563 6652/5899/12563 +f 7599/6531/12847 7583/6214/12847 7580/5764/12847 +f 6655/5804/12481 6657/7347/14014 6731/5802/12479 +f 5794/6775/13344 5802/7308/13952 5815/6571/13943 +f 7343/7751/14639 7333/7613/14457 7348/7655/14509 +f 6724/6728/13295 6723/7095/14640 6732/6649/13225 +f 6759/7229/14240 6875/7238/14240 6876/7237/14241 +f 6810/6297/12917 6818/5823/13970 6831/6298/12918 +f 6490/6097/12741 6491/6049/12696 6484/6051/12698 +f 6561/5758/12441 6563/7468/12441 6581/6832/12441 +f 7842/7268/12518 7829/6892/12518 7827/6995/12518 +f 6582/5838/12441 6549/5840/12441 6552/7447/12441 +f 6695/6346/12963 6717/7078/13673 6718/5859/12528 +f 7376/7752/14641 7377/7664/14518 7385/7721/14594 +f 7329/7732/14609 7327/7753/14642 7328/7754/14643 +f 6631/7573/14386 6632/7406/14114 6591/7011/13595 +f 7596/6555/12847 7589/6554/12847 7595/7388/12847 +f 5755/5792/12471 5752/6884/13463 5816/6724/13290 +f 7682/6536/13130 7681/6971/13550 7700/7270/14307 +f 7613/6765/13334 7604/7515/14326 7614/7387/14081 +f 6754/7303/13941 6861/7454/14188 6860/7304/13942 +f 6943/7473/14272 6909/5769/12440 6942/5949/12440 +f 6606/6454/13818 6623/7205/13819 6625/7059/13652 +f 7822/7287/13925 7806/7566/14373 7805/7285/13923 +f 6890/6323/12946 6885/7008/12946 6997/6324/12946 +f 7795/5986/12642 7788/7507/13597 7796/5987/12643 +f 7681/6971/13550 7697/7564/14644 7699/7271/14308 +f 6888/7369/14048 6972/6376/12995 6883/7591/14425 +f 7402/7755/14645 7410/7756/14646 7407/7757/14647 +f 7931/7549/14648 7930/6235/13143 7932/6471/13142 +f 7412/6233/12862 7417/6232/12861 7414/6719/12862 +f 6717/7078/13673 6747/7723/14597 6728/6492/13092 +f 6952/7758/14649 6940/6751/13321 6941/7509/14650 +f 7607/7049/13641 7645/7048/13640 7643/7142/13736 +f 6714/5812/13911 6702/7340/14651 6697/6976/13556 +f 6455/6220/14652 6456/6723/13289 6480/6016/14653 +f 6766/7420/14134 6851/7498/14258 6850/5796/12473 +f 7983/7145/13740 7995/6692/13261 7994/7570/14380 +f 6604/7337/14344 6619/6125/12770 6620/7550/14345 +f 7940/5862/12531 7920/6446/14654 7919/5863/12532 +f 7679/6209/14318 7677/6836/12692 7678/6919/12562 +f 7914/7501/14655 7948/7759/14656 7950/5882/14657 +f 7346/7760/14658 6999/7703/14560 7345/7705/14562 +f 7130/7761/14659 7128/7762/14660 7064/7763/14661 +f 8000/6277/12902 7999/5963/12619 7998/6459/13068 +f 6926/6479/14662 6927/6986/13569 6900/7284/13921 +f 6550/7448/14663 6548/7108/13704 6537/7346/14012 +f 6513/7159/13758 6510/7178/13783 6512/7180/13786 +f 7642/5835/12509 7641/6036/12687 7605/5836/12510 +f 7354/7764/14664 7355/7765/14665 7357/7686/14540 +f 7004/7766/14666 7022/7767/14667 7005/7768/14668 +f 6447/6335/14207 6446/6581/14669 6448/6580/13827 +f 6907/6797/12440 6904/6799/12440 6938/5995/12440 +f 7720/6354/12971 7731/6353/12970 7715/6042/14123 +f 6419/7293/14402 6420/7087/13682 6437/7147/13742 +f 7136/7769/14670 7084/7620/14465 7133/7770/14671 +f 7078/7771/14672 7077/7772/14673 7138/7713/14576 +f 7759/7386/14079 7745/6548/13140 7761/7385/14078 +f 7084/7620/14465 7131/7745/14631 7133/7770/14671 +f 6401/6482/12583 6402/5927/12585 6407/6241/12870 +f 7976/6532/13126 7989/7457/14193 7988/6569/13156 +f 7291/7743/14630 7367/7773/14674 7292/7741/14628 +f 7729/6475/13078 7768/6474/13077 7749/7190/13794 +f 7384/7722/14595 7339/7774/14675 7340/7775/14676 +f 7719/7360/12562 7705/5896/12562 7717/5895/12562 +f 7412/6233/13928 7411/7274/13928 7535/6584/13928 +f 7367/7773/14674 7366/7776/14677 7292/7741/14628 +f 7051/7600/14439 7052/7777/14678 7008/7778/14679 +f 6707/5861/12530 6695/6346/12963 6718/5859/12528 +f 5770/7465/14210 5757/7481/14680 5758/6553/14211 +f 7107/7779/14681 7106/7780/14682 7015/7781/14683 +f 6723/7095/14640 6722/7516/14684 6732/6649/13225 +f 6819/6739/13305 6839/7097/13694 6815/7188/14359 +f 6408/6676/12583 6407/6241/12870 6413/6211/12846 +f 7298/7782/14685 7297/7783/14686 7390/7784/14687 +f 7651/6815/13386 7612/6530/13124 7654/7482/14233 +f 7673/6334/13679 7786/7084/13679 7785/7665/13679 +f 7474/7427/14563 7485/7487/14621 7484/7232/13858 +f 7495/6021/13951 7511/7025/13613 7494/6019/14220 +f 7983/7145/13740 7953/6517/13739 7984/6460/13069 +f 6954/6137/12782 6990/6330/12952 6953/6135/12780 +f 7252/7641/14493 7213/7640/14492 7270/7785/14688 +f 7427/6461/13070 7436/7316/14385 7428/7345/14111 +f 6922/6497/13273 6925/6480/13083 6923/7413/14121 +f 7653/7483/14234 7654/7482/14233 7553/7559/14358 +f 6533/6159/12801 6534/6030/12681 6532/6032/12683 +f 7061/7592/14430 7125/7594/14432 7023/7786/14689 +f 7719/7360/14035 7734/6485/13087 7733/7576/14390 +f 6839/7097/14690 6850/5796/12473 6851/7498/14258 +f 7770/7423/14136 7769/7422/14135 7771/7412/14120 +f 6993/6732/13591 6996/6325/13591 6997/6324/13592 +f 7393/7787/14691 7406/7740/14624 7396/7659/14513 +f 7883/7426/14139 7884/7356/14030 7789/6968/14080 +f 6949/6659/13233 6981/5814/12491 6948/5813/12490 +f 7792/7014/13599 7891/6541/13135 7892/7306/13949 +f 6767/6345/14692 6876/7237/14692 6877/7352/14692 +f 7677/6836/12692 7683/7372/12562 7676/7488/12692 +f 7473/6179/13734 7487/6873/13451 7472/6562/13667 +f 7949/6518/13056 7947/7459/13056 7952/6519/13056 +f 7307/7788/14693 7376/7752/14641 7385/7721/14594 +f 7462/6462/13243 7461/6643/13245 7463/5874/13984 +f 7243/7789/14694 7249/7790/14695 7230/7791/14696 +f 6401/6482/12583 6400/5925/12583 6402/5927/12585 +f 7857/7069/13663 7886/7104/13700 7856/7212/13832 +f 6407/6241/12870 6402/5927/12585 6496/6015/12666 +f 6762/7357/14395 6865/7425/14138 6864/7455/14189 +f 6803/5944/13883 6776/6848/13481 6777/6847/13883 +f 7475/6560/14622 7485/7487/14621 7474/7427/14563 +f 5744/6961/14697 5857/7472/14697 5858/6999/14697 +f 7847/6834/12518 7816/6788/12518 7814/6790/14698 +f 7330/7733/14610 7351/7697/14554 7321/7699/14556 +f 7246/7792/14699 7214/7681/14535 7247/7793/14700 +f 6399/7695/12905 6398/6641/12905 6394/7557/12905 +f 7112/7794/14701 7111/7795/14702 7053/7796/14703 +f 7952/6519/14312 7965/6278/12903 7953/6517/13739 +f 7861/6540/13134 7842/7268/13899 7862/7269/13900 +f 7376/7752/14641 7173/7797/14704 7174/7798/14705 +f 6941/7509/12440 6920/7282/14272 6917/6157/12440 +f 7009/7799/14706 7005/7768/14668 7010/7800/14707 +f 7984/6460/13069 7995/6692/13261 7983/7145/13740 +f 7821/6282/14708 7819/7434/14154 7818/5979/12634 +f 6508/6204/12837 6468/6206/12839 6507/6897/13478 +f 7020/7801/14709 7017/7623/14468 7021/7631/14476 +f 7468/7234/12542 7457/6515/12542 7474/7427/12542 +f 7247/7793/14700 7214/7681/14535 7250/7802/14710 +f 6567/6714/12441 6569/6151/12441 6573/6150/12441 +f 7881/5955/12611 7880/7112/13707 7879/6710/13276 +f 6434/6100/12708 6459/6061/12708 6432/5935/12708 +f 6900/7284/13921 6899/7451/14181 6924/7450/14180 +f 7722/7267/12562 7687/7542/12692 7721/7444/12562 +f 6855/7484/14235 6857/5767/12449 6856/7204/13813 +f 7996/6567/13154 7910/6306/12927 7993/6039/12691 +f 7938/6761/14582 7939/5864/14115 7937/6148/12945 +f 6617/6124/12769 6616/6508/13108 6618/6747/13314 +f 7471/6020/12542 7440/6677/12542 7470/6598/12542 +f 7838/5762/14711 7809/6304/12925 7837/5760/14421 +f 5783/5894/13898 5784/6466/13897 5782/7575/14389 +f 6706/7255/13887 6722/7516/14279 6704/5793/13689 +f 7946/7587/14712 7921/6444/14713 7944/7586/14713 +f 7157/7803/14714 7328/7754/14643 7327/7753/14642 +f 6934/7052/13645 6945/7250/13876 6964/7053/13646 +f 5757/7481/12493 5764/6299/12493 5760/6112/12756 +f 6410/6275/12900 6404/6688/12583 6403/5924/12583 +f 7415/6403/13019 7534/6402/13018 7504/7245/13870 +f 7687/7542/14323 7688/6838/13862 7686/6837/13511 +f 6892/5756/13568 6929/6613/13567 6931/6718/14715 +f 6273/6682/12905 6275/6681/12905 6274/6281/12905 +f 6364/7218/13839 6363/6504/13101 6285/6830/13406 +f 7056/7616/14460 7046/7804/14716 7055/7805/14717 +f 7048/7806/14718 7049/7807/14719 7099/7808/14720 +f 7341/7739/14620 7338/7809/14721 7340/7775/14676 +f 6760/7358/12657 6872/7239/12657 6874/7294/12657 +f 6588/7133/14266 6573/6150/13198 6587/7134/13889 +f 7691/6207/12840 7679/6209/12842 7689/6920/13510 +f 7876/5786/12465 7799/6350/12967 7874/5784/12463 +f 6805/5942/12636 6803/5944/13883 6777/6847/13883 +f 7181/7810/14722 7183/7811/14723 7182/7812/14724 +f 7307/7788/14693 7385/7721/14594 7382/7813/14725 +f 6293/6736/13302 6292/6429/13046 6295/6384/13014 +f 7344/7814/14726 7345/7705/14562 7363/7626/14471 +f 6932/6901/13486 6944/5770/13559 6955/7116/13710 +f 7749/7190/13794 7767/6329/12951 7766/6328/12950 +f 6509/7213/13833 6410/6275/12900 6511/7543/14324 +f 6945/7250/14140 6979/6779/13350 6977/7296/13931 +f 6918/7166/14127 6920/7282/13917 6919/6707/13272 +f 5796/7136/12493 5795/6929/12493 5792/6928/12493 +f 7765/7191/13795 7762/6547/13139 7764/7144/13738 +f 6887/7024/13612 6884/6434/13591 6881/7536/14635 +f 6991/6331/12953 6989/6634/13217 6990/6330/12952 +f 7361/7704/14561 7068/7815/14727 7362/7749/14637 +f 7052/7777/14678 7053/7796/14703 7008/7778/14679 +f 7061/7592/14430 7063/7816/14728 7126/7593/14431 +f 7617/5941/12599 7603/7297/13933 7602/7253/13884 +f 7008/7778/14679 7012/7817/14729 7011/7818/14730 +f 7256/7819/14731 7262/7820/14732 7260/7821/14733 +f 6759/7229/13929 6760/7358/13929 6874/7294/13929 +f 7956/5868/13056 7924/5883/13056 7953/6517/13056 +f 7058/7822/14734 7352/7725/14601 7060/7823/14735 +f 6830/7321/13972 6845/6672/13246 6844/5989/12645 +f 6811/6666/12498 6814/6417/12498 6806/6585/12498 +f 7552/7824/14736 7629/7513/14277 7554/6693/13262 +f 6669/6840/13956 6670/6839/14737 6671/6296/13955 +f 5814/6572/13953 5802/7308/13952 5801/6465/14289 +f 7054/7825/14738 7375/7599/14438 7369/7687/14541 +f 7068/7815/14727 7361/7704/14561 6999/7703/14560 +f 7381/7826/14739 7338/7809/14721 7298/7782/14685 +f 5824/6631/13212 5832/6372/12991 5833/5743/12429 +f 6636/5851/12520 6633/5850/12519 6635/6251/12876 +f 7989/7457/14193 8013/7458/14194 8012/7452/14183 +f 6610/5959/12615 6608/7571/14381 6611/6894/13474 +f 7945/7827/13056 7943/6903/13056 7954/6410/13056 +f 6942/5949/12440 6907/6797/12440 6938/5995/12440 +f 6380/5930/12588 6375/5857/12526 6378/7645/14498 +f 6324/6001/13622 6297/7171/14101 6325/6636/14059 +f 6694/6758/13328 6667/7335/13998 6668/6295/13329 +f 7949/6518/13434 7950/5882/12549 7948/7759/14740 +f 7674/5871/12540 7668/6695/13263 7673/6334/12956 +f 7596/6555/14607 7608/6619/13197 7607/7049/13641 +f 7199/7828/14741 7219/7688/14542 7198/7829/14742 +f 7603/7297/12847 7573/6821/12847 7602/7253/12847 +f 7944/7586/14713 7920/6446/14654 7942/7744/14743 +f 7347/7673/14527 7350/7830/14744 7349/7724/14600 +f 6770/6510/13110 6809/6509/13109 6807/5982/12638 +f 7200/7831/14745 7219/7688/14542 7199/7828/14741 +f 6484/6051/12698 6476/7118/13713 6475/7117/13712 +f 6999/7703/14560 7346/7760/14658 7069/7832/14746 +f 6410/6275/12900 6509/7213/13833 6508/6204/12837 +f 7222/7833/14747 7197/7834/14748 7221/7835/14749 +f 6948/5813/12490 6936/7193/14109 6949/6659/13233 +f 5844/5972/12628 5811/6740/13306 5843/5787/12466 +f 7111/7795/14702 7110/7836/14750 7053/7796/14703 +f 7220/7680/14534 7208/7837/14751 7209/7838/14752 +f 7870/5801/13408 7847/6834/13410 7843/6249/14196 +f 7018/7839/14753 7017/7623/14468 7019/7840/14754 +f 7783/7242/12956 7782/7491/12954 7781/7243/12956 +f 7944/7586/14755 7942/7744/14755 7943/6903/14755 +f 7274/7841/14756 7277/7842/14757 7276/7843/14758 +f 7397/7844/14759 7398/7845/14760 7401/7660/14514 +f 7950/5882/14657 7923/5884/14146 7914/7501/14655 +f 7399/7619/14464 7394/7846/14761 7398/7845/14760 +f 6705/5794/12472 6701/6730/12472 6671/6296/12472 +f 7378/7847/14762 7168/7848/14763 7377/7664/14518 +f 7212/7849/14764 7282/7850/14765 7281/7851/14766 +f 7484/7232/14242 7530/6168/12810 7527/7490/14248 +f 6476/7118/13713 6460/6831/13407 6462/6062/13711 +f 7198/7829/14742 7219/7688/14542 7211/7852/14767 +f 7762/6547/13139 7746/6546/13138 7747/7143/13737 +f 7201/7853/14768 7219/7688/14542 7200/7831/14745 +f 7477/7463/12542 7445/6442/12542 7476/7261/12542 +f 7979/7313/14226 7959/6470/14769 7980/6189/12825 +f 7977/5781/14192 7990/7312/13958 7912/7167/14448 +f 7360/7627/14472 7362/7749/14637 7359/7854/14770 +f 6409/7395/14093 6403/5924/12583 6412/7366/14043 +f 7823/5848/14612 7825/5921/14612 7824/5920/14612 +f 6329/7568/13014 6319/6494/13014 6321/6493/13014 +f 7362/7749/14637 7068/7815/14727 7067/7750/14638 +f 7777/6107/12751 7776/6106/12750 7734/6485/13087 +f 6703/6347/12472 6695/6346/12472 6682/7168/12472 +f 6869/6413/13029 6758/6344/12961 6871/6877/13454 +f 7989/7457/14193 7985/6025/12676 7988/6569/13156 +f 6361/6290/12913 6362/6289/12912 6363/6504/13101 +f 7962/5782/12461 7959/6470/14769 7979/7313/14226 +f 6423/7210/13828 6425/6908/13495 6424/6218/13829 +f 7349/7724/14600 7056/7616/14460 7347/7673/14527 +f 7420/6234/12863 7511/7025/13613 7512/5887/12554 +f 7292/7741/14628 7295/7855/14771 7294/7742/14629 +f 7292/7741/14628 7296/7856/14772 7295/7855/14771 +f 6452/6731/12708 6450/6917/12708 6424/6218/12708 +f 7493/5841/12512 7500/5843/12514 7492/7359/14034 +f 6275/6681/13994 6379/6522/13118 6377/7429/14144 +f 7724/6395/12562 7701/6876/12562 7723/6393/12562 +f 7305/7609/14453 7319/7857/14773 7318/7607/14450 +f 7973/5844/12515 8010/7478/14228 7986/7534/14313 +f 6998/7711/14574 7150/7858/14774 7149/7709/14572 +f 6923/7413/14121 6925/6480/13083 6924/7450/14775 +f 6934/7052/12440 6930/6612/12440 6933/6782/12440 +f 7046/7804/14716 7039/7649/14503 7055/7805/14717 +f 7474/7427/12542 7457/6515/12542 7455/6514/12542 +f 5750/7505/14268 5749/5791/12470 5849/7480/14231 +f 7633/6146/12791 7619/6145/12790 7635/6912/13501 +f 6290/7430/13014 6289/7170/13014 6295/6384/13014 +f 6604/7337/14000 6605/7383/14069 6578/6453/13062 +f 7738/6778/13347 7739/6053/13821 7675/6333/12955 +f 5755/5792/12985 5744/6961/12985 5753/6998/12985 +f 6886/6255/12880 6882/6640/13591 6887/7024/13612 +f 7015/7781/14683 7106/7780/14682 7016/7859/14776 +f 7016/7859/14776 7105/7860/14777 7018/7839/14753 +f 6583/6128/12558 6582/5838/12441 6552/7447/12441 +f 7667/7276/12956 7664/6980/13562 7670/6108/12752 +f 6787/6002/12657 6788/6004/12659 6786/6477/13080 +f 7647/7539/14320 7546/6230/12860 7645/7048/13640 +f 7380/7861/14778 7391/7862/14779 7382/7813/14725 +f 7248/7863/14780 7241/7864/14781 7240/7865/14782 +f 7113/7656/14510 7112/7794/14701 7053/7796/14703 +f 7359/7854/14770 7328/7754/14643 7326/7866/14783 +f 6514/6085/13085 6400/5925/13085 6401/6482/13085 +f 6308/6182/12818 6309/7558/12818 6307/6183/12819 +f 6815/7188/12498 6812/5890/12498 6780/7186/12498 +f 6337/6956/13542 6326/6268/12893 6348/6288/12911 +f 7220/7680/14534 7209/7838/14752 7219/7688/14542 +f 7312/7608/14451 7400/7617/14462 7398/7845/14760 +f 7273/7867/14784 7272/7868/14785 7267/7604/14443 +f 7645/7048/13640 7646/6618/13196 7647/7539/14320 +f 6506/6899/13480 6406/5926/12584 6405/6274/12899 +f 6279/6600/14452 6394/7557/14452 6396/7585/14452 +f 7041/7869/14786 7039/7649/14503 7044/7870/14787 +f 7665/6332/14788 7785/7665/14788 7784/7666/14788 +f 6299/6398/13877 6298/7374/14789 6300/6864/13442 +f 7204/7871/14790 7219/7688/14542 7205/7872/14791 +f 7008/7778/14679 7108/7873/14792 7107/7779/14681 +f 6653/6102/12746 6647/6101/12916 6650/6927/12916 +f 7042/7874/14793 7002/7674/14528 7043/7632/14480 +f 7459/7408/14354 7460/6671/13244 7458/7407/14354 +f 6510/7178/13783 6511/7543/14324 6512/7180/13786 +f 6549/5840/14068 6548/7108/14067 6550/7448/14177 +f 7275/7875/14794 7274/7841/14756 7276/7843/14758 +f 6658/6238/12472 6665/6486/12472 6662/6488/13088 +f 6882/6640/13591 6889/6243/13591 6890/6323/13591 +f 7617/5941/12599 7602/7253/13884 7618/6147/12792 +f 5794/6775/12493 5806/5968/12493 5777/5952/12493 +f 6589/6620/14567 6588/7133/13728 6630/7371/14051 +f 7852/5847/14411 7850/5849/14588 7867/7525/14587 +f 6583/6128/12773 6585/6646/14489 6598/5960/14129 +f 7096/7876/14795 7094/7693/14548 7098/7877/14796 +f 6619/6125/12770 6604/7337/14344 6603/7336/14267 +f 7812/7259/12518 7847/6834/12518 7814/6790/14698 +f 6483/6050/12697 6493/6591/13174 6492/7131/13726 +f 6497/7018/13606 6499/6192/12828 6498/7019/13607 +f 7388/7628/14473 7297/7783/14686 7293/7878/14797 +f 6883/7591/14425 6972/6376/12995 6973/6684/13254 +f 7648/6617/13195 7647/7539/14320 7646/6618/13196 +f 7342/7672/14526 7343/7751/14639 7347/7673/14527 +f 6557/7706/14568 6555/5745/12431 6540/7281/13916 +f 7139/7727/14603 7072/7879/14798 7148/7880/14799 +f 5844/5972/12628 5812/5971/12627 5811/6740/13306 +f 7123/7694/14549 7092/7881/14800 7049/7807/14719 +f 6916/6158/14801 6914/6368/13751 6915/7154/13750 +f 7927/6701/13268 7925/6700/13267 7924/5883/12550 +f 5790/6930/14125 5791/6301/14802 5792/6928/14076 +f 7695/7235/13861 7680/6208/12841 7693/7199/14070 +f 7695/7235/14364 7693/7199/14618 7694/7519/14618 +f 6452/6731/12708 6424/6218/12708 6455/6220/12708 +f 7572/6984/14803 7574/7440/14163 7575/6985/14008 +f 6754/7303/12962 6756/7302/13940 6755/6753/12962 +f 7404/7882/14804 7406/7740/14624 7405/7883/14805 +f 7134/7884/14806 7131/7745/14631 7132/7885/14807 +f 6856/7204/13813 6858/5766/12448 6823/7203/13812 +f 7137/7886/14808 7134/7884/14806 7135/7887/14809 +f 7064/7763/14661 7001/7888/14810 7066/7889/14811 +f 7029/7615/14459 7117/7890/14812 7116/7891/14813 +f 7108/7873/14792 7008/7778/14679 7109/7892/14814 +f 7353/7893/14815 7061/7592/14430 7060/7823/14735 +f 7463/5874/13984 7437/7390/14087 7464/6463/13985 +f 7383/7720/14593 7340/7775/14676 7338/7809/14721 +f 7120/7894/14816 7017/7623/14468 7121/7895/14817 +f 7960/7577/14393 7980/6189/12825 7959/6470/14769 +f 7059/7896/14818 7120/7894/14816 7056/7616/14460 +f 6952/7758/14819 6985/7456/14191 6951/6752/14190 +f 7604/7515/14326 7601/7376/14058 7614/7387/14081 +f 7171/7897/14820 7172/7898/14821 7306/7654/14508 +f 6696/6726/12472 6698/7400/14202 6692/7103/12472 +f 6939/6136/12440 6941/7509/12440 6917/6157/12440 +f 7063/7816/14728 7062/7899/14822 7127/7900/14823 +f 6442/6199/13103 6439/7146/14477 6441/6181/14824 +f 6989/6634/13217 6985/7456/14191 6952/7758/14819 +f 7909/6305/12926 7990/7312/13958 7991/6188/12824 +f 7047/7719/14591 7029/7615/14459 7027/7737/14617 +f 6566/7670/12441 6567/6714/12441 6576/6621/12441 +f 6964/7053/13932 6975/5832/12506 6963/6415/13031 +f 7562/5748/12847 7563/6888/12847 7561/5749/12847 +f 7236/7589/14423 7237/7588/14422 7238/7901/14825 +f 7337/7902/14826 7165/7646/14500 7167/7903/14827 +f 7428/7345/14111 7436/7316/14385 7438/7317/14112 +f 7017/7623/14468 7120/7894/14816 7059/7896/14818 +f 7327/7753/14642 7325/7731/14608 7157/7803/14714 +f 7441/6678/13251 7440/6677/13250 7443/6960/14025 +f 7335/7904/14828 7336/7647/14501 7339/7774/14675 +f 5839/6321/12944 5826/7531/14418 5837/5958/12614 +f 6501/6450/13060 6464/7905/14829 6500/7361/14036 +f 7820/7286/14361 7819/7434/14154 7821/6282/14708 +f 6833/6351/12968 6832/6133/12778 6843/6132/12777 +f 7469/6028/12542 7459/7408/12542 7468/7234/12542 +f 7419/7273/13907 7524/6941/13530 7422/7124/13717 +f 7005/7768/14668 7007/7906/14830 7006/7907/14831 +f 5756/6300/12921 5793/7384/14832 5791/6301/12922 +f 7491/6982/13563 7490/6270/12895 7478/6772/14131 +f 7252/7641/14493 7270/7785/14688 7253/7908/14833 +f 6805/5942/12600 6808/6667/14184 6806/6585/12600 +f 5833/5743/12429 5836/5742/12428 5827/5957/12613 +f 6343/6924/14204 6329/7568/14374 6342/7382/14065 +f 7151/7909/14834 7346/7760/14658 7152/7910/14835 +f 6766/7420/14134 6756/7302/13940 6854/7401/14100 +f 6286/6602/13181 6391/6357/12974 6390/6318/12941 +f 7333/7613/14457 7337/7902/14826 7158/7611/14455 +f 7082/7911/14836 7084/7620/14465 7083/7912/14837 +f 7951/6705/13771 7975/6024/12675 7974/6026/14838 +f 7184/7913/14839 7305/7609/14453 7188/7914/14840 +f 7702/6534/13128 7682/6536/13130 7700/7270/14307 +f 7643/7142/13736 7645/7048/13640 7644/6037/12688 +f 7239/7915/14841 7269/7916/14842 7248/7863/14780 +f 7264/7917/14843 7259/7918/14844 7271/7919/14845 +f 6609/5945/12602 6598/5960/12616 6597/5946/12603 +f 7893/7012/14846 7788/7507/14846 7787/6967/14846 +f 7651/6815/13386 7653/7483/14234 7652/7535/14314 +f 7897/7582/14847 7896/7216/14847 7793/6954/14847 +f 7415/6403/13019 7416/6565/12862 7422/7124/13717 +f 7554/6693/13262 7548/6313/12567 7551/7560/12567 +f 6345/6092/12736 6346/6267/12892 6334/6093/12737 +f 6386/6755/13325 6342/7382/14065 6385/6139/12784 +f 7271/7919/14845 7257/7920/14848 7272/7868/14785 +f 5833/5743/12429 5834/6939/13528 5835/5744/12430 +f 7889/6424/13040 7791/6966/14151 7887/7431/14150 +f 6524/7504/14265 6522/7106/13702 6520/6502/12683 +f 7683/7372/12562 7681/6971/13550 7682/6536/12562 +f 7392/7618/14463 7296/7856/14772 7366/7776/14677 +f 5854/7001/13586 5740/6340/13586 5741/7002/13586 +f 6630/7371/14051 6631/7573/14386 6589/6620/14567 +f 7292/7741/14628 7366/7776/14677 7296/7856/14772 +f 6891/6245/12874 6969/7533/14311 6888/7369/14048 +f 7491/6982/13563 7478/6772/14131 7477/7463/14352 +f 7197/7834/14748 7219/7688/14542 7204/7871/14790 +f 6448/6580/13166 6414/6579/13165 6423/7210/14252 +f 7710/7421/13922 7713/6041/13358 7712/7520/14849 +f 7768/6474/13077 7771/7412/14120 7769/7422/14135 +f 6745/5811/12488 6653/6102/12746 6656/6292/12915 +f 7364/7921/14850 7197/7834/14748 7222/7833/14747 +f 6419/7293/12708 6418/7418/12708 6415/7123/12708 +f 6283/6064/12710 6278/6279/12904 6371/6358/12976 +f 5841/5780/12459 5840/6320/12943 5842/6526/13120 +f 6326/6268/13014 6309/7558/13014 6311/6608/13014 +f 7353/7893/14815 7060/7823/14735 7352/7725/14601 +f 7255/7922/14851 7253/7908/14833 7263/7923/14852 +f 7798/6835/14406 7796/5987/14406 7898/7377/14406 +f 7388/7628/14473 7390/7784/14687 7297/7783/14686 +f 6501/6450/13060 6465/7399/14098 6464/7905/14829 +f 7302/7924/14853 7319/7857/14773 7183/7811/14854 +f 6679/6907/13494 6677/7128/14855 6662/6488/13088 +f 6568/6878/14856 6542/6186/12821 6543/7476/14857 +f 7966/6276/12901 8001/5961/12617 8000/6277/12902 +f 7655/5905/13382 7545/6231/13382 7657/5906/13382 +f 7274/7841/14756 7273/7867/14784 7267/7604/14443 +f 7770/7423/14136 7773/7077/13672 7663/6327/12949 +f 7110/7836/14750 7109/7892/14814 7008/7778/14679 +f 7228/7925/14858 7208/7837/14751 7229/7926/14859 +f 6878/7748/14635 6879/6733/13592 6880/6721/14636 +f 7363/7626/14471 7155/7597/14436 7344/7814/14726 +f 6614/6507/13107 6613/6160/12802 6533/6159/12801 +f 6349/6957/13543 6348/6288/12911 6361/6290/12913 +f 7614/7387/14081 7626/6478/13081 7627/6362/12980 +f 6316/6768/14049 6317/7189/13793 6318/6806/14860 +f 6698/7400/14099 6696/6726/13904 6710/7005/13906 +f 7217/7927/14861 7218/7928/14862 7049/7807/14719 +f 7216/7929/14863 7215/7930/14864 7370/7637/14486 +f 7218/7928/14862 7370/7637/14486 7049/7807/14719 +f 7025/7624/14469 7023/7786/14689 7026/7931/14865 +f 7446/6441/14599 7448/6922/14219 7431/7578/14394 +f 7219/7688/14542 7367/7773/14674 7368/7932/14866 +f 6910/5977/14867 6908/7354/14867 6909/5769/14868 +f 7964/6533/13127 7976/6532/13126 7963/6706/13770 +f 7008/7778/14679 7013/7933/14869 7012/7817/14729 +f 7131/7745/14631 7084/7620/14465 7089/7746/14632 +f 7365/7934/14870 7394/7846/14761 7399/7619/14464 +f 7213/7640/14492 7285/7935/14871 7284/7936/14872 +f 7407/7757/14873 7410/7756/14874 7409/7937/14875 +f 6781/6110/14075 6782/6285/14205 6783/7187/14206 +f 7466/5875/12542 7463/5874/12542 7461/6643/12542 +f 7836/6008/12518 7845/6007/12518 7839/5761/12518 +f 6676/7045/13722 6677/7128/13722 6678/6592/13722 +f 6526/7107/13703 6622/7195/13799 6618/6747/13314 +f 7956/5868/12537 7981/5867/12536 7961/7555/14392 +f 6719/5860/12529 6718/5859/12528 6727/6491/13091 +f 7239/7915/14841 7268/7938/14876 7269/7916/14842 +f 6811/6666/14372 6812/5890/12557 6823/7203/13812 +f 7352/7725/14601 7351/7697/14554 7353/7893/14815 +f 7641/6036/12687 7640/6038/12689 7639/7569/14379 +f 7017/7623/14468 7059/7896/14818 7058/7822/14734 +f 6422/7122/14296 6414/6579/13165 6446/6581/13167 +f 7324/7939/14877 7158/7611/14455 7161/7940/14878 +f 7542/5992/12567 7543/6812/13383 7541/5993/12567 +f 7378/7847/14762 7376/7752/14641 7170/7941/14879 +f 7376/7752/14641 7174/7798/14705 7170/7941/14879 +f 7402/7755/14645 7222/7833/14747 7221/7835/14749 +f 6385/6139/12784 6382/6138/12783 6383/6142/12787 +f 7257/7920/14848 7271/7919/14845 7258/7942/14880 +f 7878/7348/14018 7877/6716/13282 7879/6710/13276 +f 7583/6214/13966 7581/7530/14383 7580/5764/12446 +f 7306/7654/14508 7172/7898/14821 7173/7797/14704 +f 6657/7347/14014 6720/6272/12897 6730/6273/12898 +f 7261/7943/14881 7263/7923/14852 7262/7820/14732 +f 6415/7123/14251 6425/6908/14882 6423/7210/14252 +f 7019/7840/14754 7017/7623/14468 7020/7801/14709 +f 7349/7724/14600 7350/7830/14744 7351/7697/14554 +f 7930/6235/12864 7917/7477/14883 7916/6236/12865 +f 6866/7424/14137 6864/7455/14189 6865/7425/14138 +f 7406/7740/14624 7402/7755/14645 7407/7757/14647 +f 6893/5754/14017 6901/7332/14016 6903/6828/14884 +f 7257/7920/14848 7265/7944/14885 7267/7604/14443 +f 6984/6664/13238 6987/6256/12881 6887/7024/13612 +f 6469/6205/12838 6508/6204/12837 6509/7213/13833 +f 7013/7933/14869 7107/7779/14681 7014/7945/14886 +f 6553/5746/14887 6554/6647/14887 6552/7447/14887 +f 6507/6897/13478 6506/6899/13480 6508/6204/12837 +f 7100/7946/14888 7049/7807/14719 7101/7947/14889 +f 7676/7488/14246 7684/6921/14245 7677/6836/13412 +f 6725/6729/14890 6696/6726/13904 6700/6294/14891 +f 6898/5755/13768 6897/5975/12630 6914/6368/12986 +f 6828/7201/13809 6827/6418/14170 6866/7424/14137 +f 6500/7361/14036 6498/7019/13607 6499/6192/12828 +f 7272/7868/14785 7257/7920/14848 7267/7604/14443 +f 7348/7655/14509 7350/7830/14744 7347/7673/14527 +f 7061/7592/14430 7353/7893/14815 7354/7764/14664 +f 8015/7311/14523 8019/6644/14523 7906/6439/14523 +f 6842/5889/12556 6853/6166/12808 6854/7401/14100 +f 6542/6186/12441 6541/6185/12441 6539/5747/12433 +f 7595/7388/12847 7586/6213/12847 7600/6212/12847 +f 6634/5852/12521 6607/7464/14209 6592/7010/13594 +f 5790/6930/14125 5789/6973/14125 5791/6301/14802 +f 7933/5985/14339 7935/5984/12794 7918/6445/14340 +f 7181/7810/14892 7302/7924/14853 7183/7811/14854 +f 7303/7948/14893 7404/7882/14804 7403/7949/14894 +f 7965/6278/12903 7952/6519/14312 7966/6276/12901 +f 7912/7167/14448 7976/6532/13126 7977/5781/14192 +f 6888/7369/14048 6969/7533/14311 6959/6946/13535 +f 6348/6288/12911 6349/6957/13543 6337/6956/13542 +f 7395/7661/14515 7394/7846/14761 7396/7659/14895 +f 7235/7590/14424 7236/7589/14423 7234/7679/14533 +f 7056/7616/14460 7055/7805/14717 7057/7671/14525 +f 7393/7787/14691 7394/7846/14761 7364/7921/14850 +f 7371/7638/14487 7370/7637/14486 7212/7849/14764 +f 7399/7619/14464 7392/7618/14463 7366/7776/14677 +f 7353/7893/14815 7355/7765/14665 7354/7764/14664 +f 7110/7836/14750 7008/7778/14679 7053/7796/14703 +f 7395/7661/14515 7398/7845/14760 7394/7846/14761 +f 6472/7158/13757 6471/7176/13781 6513/7159/13758 +f 7871/7416/14130 7863/5911/12572 7872/6005/12660 +f 7632/6431/13048 7625/5939/12597 7624/7446/14174 +f 6578/6453/12441 6574/6455/12441 6545/7532/12441 +f 7397/7844/14896 7312/7608/14896 7398/7845/14896 +f 6928/6481/13084 6929/6613/13191 6927/6986/14897 +f 7219/7688/14542 7197/7834/14748 7364/7921/14850 +f 7229/7926/14859 7208/7837/14751 7220/7680/14534 +f 6326/6268/13014 6311/6608/13014 6313/6607/13014 +f 6361/6290/12913 6364/7218/13839 6365/6794/13366 +f 7290/7715/14581 7303/7948/14893 7408/7950/14898 +f 7303/7948/14893 7403/7949/14894 7408/7950/14898 +f 7550/7035/13625 7649/6077/12723 7650/6923/13515 +f 7379/7951/14899 7339/7774/14675 7384/7722/14595 +f 7206/7690/14545 7207/7952/14900 7228/7925/14858 +f 7133/7770/14671 7131/7745/14631 7134/7884/14806 +f 7255/7922/14851 7263/7923/14852 7261/7943/14881 +f 6547/5891/12558 6578/6453/12441 6545/7532/12441 +f 7723/6393/12562 7696/7111/12562 7727/6054/12562 +f 7044/7870/14787 7039/7649/14503 7045/7953/14901 +f 7600/6212/14902 7599/6531/13125 7612/6530/13124 +f 7271/7919/14845 7259/7918/14844 7258/7942/14880 +f 7195/7954/14903 7221/7835/14749 7196/7955/14904 +f 7822/7287/13925 7824/5920/14905 7806/7566/14373 +f 8018/7280/13054 8014/7279/13054 8017/7099/13054 +f 7405/7883/14906 7409/7937/14906 7408/7950/14906 +f 7458/7407/14334 7433/6810/13579 7456/6516/13578 +f 7290/7715/14907 7408/7950/14907 7409/7937/14907 +f 7354/7764/14664 7062/7899/14822 7063/7816/14728 +f 7573/6821/13393 7574/7440/14163 7572/6984/14803 +f 7628/6361/12979 7630/6363/12981 7629/7513/14277 +f 7410/7756/14908 7221/7835/14749 7195/7954/14903 +f 7410/7756/14909 7402/7755/14909 7221/7835/14909 +f 7014/7945/14886 7107/7779/14681 7015/7781/14683 +f 5740/6340/14288 5746/6339/12985 5743/5788/14288 +f 7570/6819/14479 7557/6428/13044 7569/6427/13043 +f 6921/6708/14355 6898/5755/13768 6919/6707/13767 +f 7951/6705/13056 7938/6761/13056 7936/6322/13056 +f 7063/7816/14728 7127/7900/14823 7126/7593/14431 +f 7933/5985/12641 7932/6471/14910 7934/5983/12639 +f 7536/7290/13114 7421/6525/13114 7412/6233/13114 +f 7852/5847/14411 7867/7525/14587 7866/7605/14444 +f 7458/7407/14116 7456/6516/13115 7457/6515/13115 +f 7745/6548/14429 7722/7267/14911 7746/6546/14912 +f 7904/6683/14347 8018/7280/14348 8017/7099/14347 +f 7802/6829/13405 7838/5762/14711 7840/6673/13403 +f 7600/6212/12847 7583/6214/12847 7599/6531/12847 +f 7910/6306/12927 7902/7310/13054 7906/6439/13054 +f 7933/5985/12641 7931/7549/14910 7932/6471/14910 +f 5744/6961/14697 5858/6999/14697 5753/6998/14697 +f 6621/7196/13800 6619/6125/12770 6618/6747/13314 +f 7361/7704/14561 7360/7627/14472 7363/7626/14471 +f 7382/7813/14725 7383/7720/14593 7381/7826/14739 +f 6618/6747/13314 6528/6746/13313 6526/7107/13703 +f 7135/7887/14809 7068/7815/14727 7000/7956/14913 +f 6702/7340/14651 6715/7119/14914 6703/6347/12964 +f 7303/7948/14893 7304/7610/14454 7314/7957/14915 +f 5754/6366/12985 5752/6884/12985 5753/6998/12985 +f 6897/5975/12630 6910/5977/12632 6912/6369/12987 +f 7205/7872/14791 7219/7688/14542 7203/7958/14916 +f 6859/5768/12450 6857/5767/12449 6860/7304/13942 +f 6558/5757/13315 6557/7706/14917 6559/6748/13316 +f 7934/5983/12639 7936/6322/12640 7935/5984/12640 +f 7220/7680/14534 7233/7959/14918 7229/7926/14859 +f 6536/7110/13706 6546/7109/13705 6544/7547/14336 +f 7608/6619/13197 7646/6618/13196 7607/7049/13641 +f 7125/7594/14432 7005/7768/14668 7023/7786/14689 +f 6467/7017/14919 6453/6201/13991 6454/6337/14920 +f 6421/6068/12714 6422/7122/14296 6444/6069/12715 +f 5806/5968/12493 5805/6226/12494 5775/7326/13027 +f 6411/5923/14330 6519/6084/14330 6408/6676/14330 +f 7758/5777/12456 7759/7386/14079 7760/5775/12454 +f 7346/7760/14658 7153/7960/14921 7152/7910/14835 +f 7066/7889/14811 7001/7888/14810 7067/7750/14638 +f 7951/6705/13771 7974/6026/14838 7973/5844/12515 +f 6369/7404/14108 6359/5879/12546 6367/5881/12548 +f 7331/7698/14555 7350/7830/14744 7332/7961/14922 +f 6304/6317/12937 6303/7445/14398 6305/6118/12938 +f 6555/5745/13945 6557/7706/14917 6558/5757/13315 +f 7924/5883/12550 7925/6700/13267 7923/5884/12551 +f 7725/7266/14428 7722/7267/14911 7745/6548/14429 +f 7180/7642/14495 7302/7924/14853 7185/7962/14923 +f 7298/7782/14685 7299/7963/14924 7297/7783/14686 +f 7912/7167/14448 7990/7312/13958 7909/6305/12926 +f 5835/5744/12430 5745/6938/13527 5838/6370/12988 +f 5825/5956/14925 5826/7531/14305 5796/7136/14304 +f 7332/7961/14922 7324/7939/14877 7331/7698/14555 +f 7748/7635/14483 7764/7144/13738 7747/7143/13737 +f 6475/7117/13712 6474/6143/12788 6490/6097/12741 +f 6640/7415/12683 6639/6436/12683 6637/6501/12683 +f 7806/7566/14373 7802/6829/12518 7804/6989/12518 +f 6361/6290/12913 6365/6794/13366 6349/6957/13543 +f 7810/6674/12518 7843/6249/12518 7812/7259/12518 +f 7893/7012/14846 7894/7378/14926 7788/7507/14846 +f 5809/6528/13122 5808/5778/12457 5842/6526/13120 +f 7023/7786/14689 7025/7624/14469 7017/7623/14468 +f 7622/7184/13791 7639/7569/14379 7621/6661/14042 +f 6688/6266/14376 6664/6487/14038 6665/6486/13852 +f 5807/5779/14306 5808/5778/13879 5795/6929/13878 +f 7068/7815/14727 7066/7889/14811 7067/7750/14638 +f 7880/7112/13707 7795/5986/12642 7878/7348/14018 +f 6686/7362/13695 6685/7041/13631 6684/7040/13630 +f 6708/6787/14167 6719/5860/12529 6720/6272/13885 +f 7629/7513/14277 7552/7824/14736 7628/6361/12979 +f 7250/7802/14710 7214/7681/14535 7249/7790/14695 +f 6482/6916/13506 6464/7905/14927 6450/6917/13507 +f 6296/6000/12655 6289/7170/13775 6324/6001/12656 +f 7957/5994/13056 7941/6760/13056 7958/5846/13056 +f 6756/7302/13940 6766/7420/14134 6757/6013/12962 +f 5803/6411/12493 5804/5817/12493 5772/7512/12493 +f 7523/6940/13529 7522/6228/12858 7521/7368/14046 +f 6802/7499/14260 6800/6010/12662 6801/6900/14261 +f 7815/5980/12635 7818/5979/12634 7817/6988/14155 +f 7002/7674/14528 7042/7874/14793 7036/7675/14529 +f 7386/7630/14475 7392/7618/14463 7400/7617/14462 +f 7377/7664/14518 7379/7951/14899 7385/7721/14594 +f 6327/6637/14300 6338/6936/13524 6339/5929/14928 +f 7831/7223/13844 7830/6891/13470 7832/6890/13469 +f 6981/5814/12491 6983/6663/13237 6881/7536/14316 +f 7952/6519/14312 7967/6656/13230 7966/6276/12901 +f 6451/6336/13851 6450/6917/13507 6464/7905/14927 +f 7650/6923/13515 7652/7535/14314 7550/7035/13625 +f 5788/7300/12493 5790/6930/12493 5799/7341/12493 +f 6535/7538/14335 6570/6712/14614 6543/7476/14857 +f 6310/6606/13185 6309/7558/14929 6308/6182/14929 +f 7356/7685/14539 7062/7899/14822 7354/7764/14664 +f 6774/7061/12498 6773/6210/14930 6772/6286/12498 +f 7358/7684/14538 7001/7888/14810 7356/7685/14539 +f 7007/7906/14830 7008/7778/14679 7011/7818/14730 +f 7371/7638/14487 7277/7842/14757 7372/7636/14485 +f 6689/6265/12472 6690/6264/12472 6699/6564/12472 +f 7477/7463/14352 7476/7261/13892 7492/7359/14353 +f 7910/6306/12927 7992/6187/12823 7993/6039/12691 +f 7383/7720/14593 7338/7809/14721 7381/7826/14739 +f 6329/7568/13014 6333/6767/13014 6318/6806/13014 +f 5814/6572/13159 5813/7522/14931 5847/5973/12629 +f 7310/7738/14619 7316/7696/14551 7315/7643/14496 +f 7710/7421/14932 7683/7372/14053 7708/7138/14933 +f 7385/7721/14594 7379/7951/14899 7384/7722/14595 +f 6810/6297/12498 6821/7333/12498 6793/6842/12498 +f 7853/5912/12518 7825/5921/12518 7823/5848/12518 +f 7291/7743/14630 7002/7674/14528 7054/7825/14738 +f 8006/6944/13533 8005/7298/13935 8008/7075/13670 +f 7566/6247/14934 7564/6543/14935 7565/7291/14936 +f 6755/6753/12962 6760/7358/12962 6762/7357/12962 +f 6375/5857/12526 6338/6936/13524 6357/5858/12527 +f 6962/6414/13030 6970/6377/12996 6961/5950/14937 +f 7306/7654/14508 7376/7752/14641 7307/7788/14693 +f 7203/7958/14916 7219/7688/14542 7202/7964/14938 +f 6818/5823/12498 6810/6297/12498 6796/6844/12498 +f 6984/6664/13238 6982/6658/13232 6985/7456/14191 +f 7722/7267/12562 7690/7236/12562 7687/7542/12692 +f 6574/6455/12441 6573/6150/12441 6571/6149/12441 +f 5797/6741/13307 5812/5971/14939 5801/6465/14289 +f 7544/7034/14940 7657/5906/14940 7545/6231/14940 +f 7922/7500/14941 7948/7759/14656 7914/7501/14655 +f 6933/6782/12440 6928/6481/12440 6937/6783/12440 +f 5842/6526/13120 5840/6320/12943 5743/5788/12467 +f 7062/7899/14822 7356/7685/14539 7065/7965/14942 +f 6905/6798/13370 6907/6797/13369 6906/7283/14584 +f 7946/7587/14416 7947/7459/14416 7949/6518/13434 +f 6660/7453/12472 6659/6841/12472 6658/6238/12472 +f 7424/6523/14943 7540/7496/14943 7539/6566/14943 +f 7811/6789/13361 7816/6788/13360 7813/5978/12633 +f 7888/7068/13662 7887/7431/14150 7886/7104/13700 +f 6284/6642/13094 6399/7695/13094 6281/6280/13094 +f 7802/6829/13405 7811/6789/14499 7803/6987/13570 +f 7544/7034/14940 7658/5904/14940 7657/5906/14940 +f 6991/6331/12953 6988/6257/12882 6986/7328/13986 +f 6729/5803/12480 6730/6273/12898 6728/6492/13092 +f 5845/5789/12468 5844/5972/12628 5843/5787/12466 +f 6482/6916/14037 6481/6559/13149 6498/7019/13607 +f 6486/7160/13759 6513/7159/13758 6487/7181/13787 +f 7129/7966/14944 7128/7762/14660 7130/7761/14659 +f 7544/7034/12567 7549/7036/13626 7553/7559/14358 +f 6741/5752/12438 6743/7214/13835 6712/6563/13151 +f 6783/7187/14206 6780/7186/14073 6781/6110/14075 +f 7905/6550/14945 8014/7279/14945 7900/7265/14945 +f 7546/6230/12860 7649/6077/12723 7550/7035/13625 +f 7426/6524/13119 7505/6978/13560 7506/6269/12894 +f 5751/6365/12990 5747/6937/13526 5832/6372/12991 +f 7696/7111/12562 7694/7519/12562 7727/6054/12562 +f 7597/6246/14946 7621/6661/13235 7598/6660/13234 +f 7836/6008/13293 7837/5760/12442 7835/6303/13291 +f 6341/6499/13098 6329/7568/14374 6330/7437/14947 +f 7607/7049/13641 7643/7142/13736 7606/5837/12511 +f 6978/6720/13286 6977/7296/13931 6979/6779/13350 +f 6679/6907/13926 6678/6592/14948 6677/7128/14948 +f 6570/6712/14614 6568/6878/14856 6543/7476/14857 +f 7695/7235/14364 7696/7111/14364 7698/6965/14063 +f 7350/7830/14744 7331/7698/14555 7351/7697/14554 +f 6378/7645/14498 6377/7429/14144 6379/6522/13118 +f 7541/5993/12567 7543/6812/13383 7546/6230/12860 +f 6880/6721/14636 6879/6733/13592 6883/7591/14425 +f 6445/6200/12708 6447/6335/12708 6454/6337/12708 +f 6822/6889/12498 6820/6737/12498 6788/6004/12498 +f 7564/6543/14935 7566/6247/14934 7567/7365/14949 +f 6752/7523/14950 6654/7398/14950 6649/6293/14950 +f 7079/7967/14951 7138/7713/14576 7080/7712/14575 +f 7284/7936/14872 7283/7968/14952 7213/7640/14492 +f 7957/5994/12649 7972/5845/12516 7971/7277/13912 +f 5765/6627/14953 5756/6300/12921 5757/7481/14680 +f 6941/7509/14650 6953/6135/12780 6952/7758/14649 +f 7157/7803/14714 7325/7731/14608 7160/7730/14606 +f 6838/5797/12474 6837/6738/14397 6849/5798/12475 +f 7732/6355/12972 7718/7486/14391 7733/7576/14390 +f 6939/6136/12440 6915/7154/12440 6932/6901/12440 +f 7905/6550/14945 8016/7100/14945 8014/7279/14945 +f 6701/6730/13297 6705/5794/13691 6724/6728/13295 +f 6367/5881/12548 6283/6064/12710 6368/7403/14107 +f 6410/6275/12900 6405/6274/12899 6404/6688/12583 +f 7551/7560/14371 7660/6452/14371 7659/6694/14371 +f 7808/6302/12923 7831/7223/14954 7833/7222/14488 +f 7968/6655/13936 8004/7969/14955 7967/6656/13910 +f 7194/7970/14956 7193/7971/14957 7409/7937/14958 +f 7051/7600/14439 7008/7778/14679 7122/7601/14440 +f 6416/7503/14264 6428/7502/14263 6426/6909/14284 +f 6622/7195/13799 6526/7107/13703 6523/7105/13701 +f 7624/7446/14174 7634/6432/13049 7632/6431/13048 +f 5754/6366/14175 5751/6365/12990 5831/7305/13948 +f 7842/7268/12518 7827/6995/12518 7825/5921/12518 +f 7621/6661/14042 7597/6246/14959 7622/7184/13791 +f 6599/6126/14103 6598/5960/12616 6611/6894/13474 +f 7237/7588/14422 7374/7598/14437 7239/7915/14841 +f 6937/6783/12440 6928/6481/12440 6925/6480/12440 +f 7287/7972/14960 7189/7973/14961 7288/7974/14962 +f 7465/7141/13735 7489/7150/13745 7488/7140/13733 +f 6506/6899/13480 6504/7442/14168 6406/5926/12584 +f 6868/5991/12647 6869/6413/13029 6870/6134/12779 +f 7801/6349/12966 7798/6835/13411 7793/6954/13597 +f 6935/6496/14015 6940/6751/13321 6950/6750/13320 +f 6725/6729/13296 6736/6055/12702 6737/6558/13148 +f 7390/7784/14687 7389/7669/14521 7391/7862/14779 +f 7799/6350/12967 7876/5786/12465 7800/5988/12644 +f 7968/6655/13936 8005/7298/13935 8004/7969/14955 +f 6785/6476/12498 6788/6004/12498 6819/6739/12498 +f 7370/7637/14486 7050/7602/14441 7049/7807/14719 +f 7158/7611/14455 7324/7939/14877 7332/7961/14922 +f 7592/6529/12847 7578/5763/12847 7604/7515/12847 +f 7578/5763/12445 7579/5765/12447 7577/6824/14007 +f 6431/7241/14238 6429/5934/14262 6417/7419/14239 +f 7277/7842/14757 7278/7975/14963 7276/7843/14758 +f 7521/7368/14046 7519/7314/13961 7516/6073/12719 +f 5802/7308/12493 5794/6775/12493 5781/6577/12493 +f 7673/6334/12956 7675/6333/12955 7674/5871/12540 +f 7870/5801/12478 7879/6710/13276 7869/6715/13281 +f 6346/6267/12892 6347/7057/14964 6326/6268/12893 +f 7566/6247/12847 7565/7291/12847 7594/6248/12847 +f 7286/7976/14965 7305/7609/14453 7189/7973/14961 +f 7707/7139/12562 7705/5896/12562 7719/7360/12562 +f 6695/6346/12472 6707/5861/12472 6680/6593/12472 +f 7606/5837/14484 7596/6555/14607 7607/7049/13641 +f 7532/6871/13449 7487/6873/13451 7534/6402/13018 +f 6984/6664/13238 6985/7456/14191 6986/7328/13986 +f 7715/6042/12562 7713/6041/12562 7711/7278/12562 +f 6454/6337/12708 6453/6201/12708 6445/6200/12708 +f 7301/7633/14481 7294/7742/14629 7293/7878/14797 +f 7427/6461/12542 7429/6851/12542 7435/6809/12542 +f 6673/7046/13983 6672/7349/14966 6660/7453/14187 +f 7914/7501/14655 7923/5884/14146 7915/7411/14145 +f 7833/7222/13292 7832/6890/13469 7834/6725/13292 +f 6702/7340/14651 6714/5812/13911 6715/7119/14914 +f 7433/6810/13579 7432/7063/13657 7454/6629/13580 +f 6304/6317/13014 6332/5901/13014 6301/6451/13014 +f 6341/6499/13098 6342/7382/14065 6329/7568/14374 +f 7791/6966/14151 7889/6424/13040 7797/7013/13598 +f 7997/7325/13978 7984/6460/13069 7998/6459/13068 +f 6463/6992/12708 6459/6061/12708 6434/6100/12708 +f 6996/6325/13591 6994/6435/13591 6995/7567/13591 +f 7128/7762/14660 7097/7692/14547 7124/7977/14967 +f 7008/7778/14679 7005/7768/14668 7122/7601/14440 +f 6780/7186/14073 6808/6667/14184 6809/6509/14186 +f 7636/7209/13826 7637/6813/13384 7547/6430/13047 +f 7469/6028/12679 7482/7462/14968 7481/6029/12680 +f 7745/6548/13140 7762/6547/13139 7761/7385/14078 +f 7806/7566/14373 7804/6989/12518 7805/7285/14969 +f 7857/7069/14970 7845/6007/14970 7844/6009/14970 +f 6816/7200/12498 6800/6010/12498 6802/7499/12498 +f 6531/6250/12875 6524/7504/14265 6527/6437/12683 +f 7687/7542/12692 7685/6785/12562 7721/7444/12562 +f 6855/7484/14235 6842/5889/12556 6854/7401/14100 +f 7941/6760/13056 7957/5994/13056 7943/6903/13056 +f 6551/7718/14971 6539/5747/12433 6553/5746/12432 +f 7665/6332/14788 7673/6334/14788 7785/7665/14788 +f 7295/7855/14771 7387/7629/14474 7294/7742/14629 +f 6885/7008/14446 6993/6732/14446 6997/6324/14446 +f 6663/6906/13493 6683/7042/13865 6681/7367/14972 +f 6957/6977/13558 6944/5770/13559 6943/7473/14222 +f 6925/6480/13083 6926/6479/13082 6924/7450/14775 +f 7419/7273/13907 7418/6582/12862 7411/7274/12862 +f 6991/6331/12953 6954/6137/12782 6889/6243/12872 +f 7268/7938/14876 7267/7604/14443 7266/7978/14973 +f 7444/7405/14598 7431/7578/14394 7430/7067/13661 +f 7621/6661/14042 7636/7209/13826 7620/6662/13500 +f 7227/7691/14546 7206/7690/14545 7228/7925/14858 +f 5800/5818/13213 5824/6631/13212 5825/5956/12612 +f 7846/6833/12518 7818/5979/12518 7816/6788/12518 +f 6377/7429/14144 6376/5856/12525 6372/7526/14298 +f 7720/6354/12562 7711/7278/12562 7709/7137/12562 +f 6328/6397/13014 6325/6636/13014 6299/6398/13014 +f 7722/7267/14911 7721/7444/14974 7747/7143/14975 +f 7848/7517/14331 7860/6542/14333 7859/6423/13573 +f 7069/7832/14746 7000/7956/14913 6999/7703/14560 +f 7420/6234/12863 7421/6525/12862 7423/7363/12862 +f 6629/7574/14387 6630/7371/14051 6626/7094/13688 +f 7132/7885/14807 7066/7889/14811 7068/7815/14727 +f 7022/7767/14667 7026/7931/14865 7005/7768/14668 +f 7804/6989/12518 7802/6829/12518 7803/6987/12518 +f 7664/6980/13562 7667/7276/12956 7661/6981/12956 +f 7093/7979/14976 7123/7694/14549 7094/7693/14548 +f 7994/7570/14380 7993/6039/12691 7982/5869/12690 +f 5770/7465/14634 5771/6156/12799 5772/7512/14494 +f 7736/6394/14281 7750/7409/14117 7735/6749/13317 +f 7908/6549/13141 8011/7460/14199 7903/7417/14132 +f 6334/6093/12737 6333/6767/14203 6344/6094/12738 +f 7395/7661/14515 7401/7660/14514 7398/7845/14760 +f 7153/7960/14921 7344/7814/14726 7154/7980/14977 +f 7362/7749/14637 7360/7627/14472 7361/7704/14561 +f 7486/6872/13450 7532/6871/13449 7531/7342/14005 +f 6748/7260/12916 6749/5898/12916 6753/5900/12916 +f 7535/6584/12862 7540/7496/12862 7536/7290/12862 +f 7120/7894/14816 7119/7981/14978 7056/7616/14460 +f 6840/7389/14085 6839/7097/14690 6851/7498/14258 +f 6664/6487/12472 6663/6906/13493 6662/6488/13088 +f 6355/5902/12565 6356/7072/13816 6331/5903/12566 +f 7473/6179/12542 7449/6178/12542 7465/7141/12542 +f 6917/6157/14128 6918/7166/14127 6916/6158/14801 +f 6597/5946/13204 6585/6646/14489 6584/6625/13205 +f 8009/7073/13668 7987/7584/14414 7986/7534/14313 +f 6529/6650/13226 6638/6652/13226 6521/6500/13226 +f 7564/6543/13137 7591/6545/13137 7565/7291/13137 +f 7053/7796/14703 7003/7676/14530 7113/7656/14510 +f 6391/6357/12974 6345/6092/12939 6390/6318/12941 +f 7313/7667/14519 7316/7696/14551 7311/7668/14520 +f 6883/7591/14425 6976/6722/13288 6880/6721/13287 +f 7980/6189/12825 7991/6188/12824 7979/7313/13960 +f 7360/7627/14472 7326/7866/14783 7322/7595/14434 +f 6456/6723/13289 6479/7580/14979 6480/6016/14653 +f 7324/7939/14877 7161/7940/14878 7159/7729/14605 +f 7639/7569/14379 7623/7183/14375 7641/6036/12687 +f 6446/6581/14669 6445/6200/14980 6444/6069/14980 +f 6709/7272/14319 6725/6729/13296 6737/6558/13148 +f 7422/7124/13717 7529/6169/12811 7415/6403/13019 +f 7392/7618/14463 7386/7630/14475 7387/7629/14474 +f 7600/6212/14902 7612/6530/13124 7611/6816/13387 +f 6763/6412/13028 6868/5991/12647 6867/5990/12646 +f 7369/7687/14541 7219/7688/14542 7368/7932/14866 +f 7967/6656/13910 8004/7969/14955 8001/5961/12617 +f 7342/7672/14526 7333/7613/14457 7343/7751/14639 +f 6396/7585/14981 6277/6601/14981 6279/6600/14981 +f 7309/7982/14982 7315/7643/14496 7308/7983/14983 +f 7094/7693/14548 7096/7876/14795 7095/7984/14984 +f 6647/6101/12916 6645/6556/12916 6643/7115/12916 +f 6887/7024/13612 6987/6256/12881 6886/6255/12880 +f 7444/7405/14598 7430/7067/13661 7442/6850/13425 +f 7053/7796/14703 7375/7599/14438 7054/7825/14738 +f 7683/7372/14053 7706/7248/13874 7708/7138/14933 +f 7424/6523/14943 7421/6525/14943 7540/7496/14943 +f 7860/6542/13136 7891/6541/13135 7859/6423/13039 +f 7802/6829/12518 7806/7566/14373 7809/6304/12518 +f 6580/5759/12441 6556/7172/12441 6558/5757/12441 +f 5804/5817/12493 5769/5816/12493 5772/7512/12493 +f 7806/7566/14373 7826/5919/14985 7807/7583/14407 +f 7413/6229/12862 7411/7274/12862 7414/6719/12862 +f 6343/6924/13516 6342/7382/14065 6386/6755/13325 +f 6729/5803/12480 6731/5802/12479 6730/6273/12898 +f 7341/7739/14620 7340/7775/14676 7336/7647/14501 +f 5757/7481/14680 5767/6628/14986 5765/6627/14953 +f 6395/7581/14405 6281/6280/14405 6399/7695/14405 +f 7035/7985/14987 7003/7676/14530 7036/7675/14529 +f 5747/6937/13526 5834/6939/13528 5832/6372/12991 +f 5746/6339/12985 5744/6961/12985 5750/7505/14268 +f 6564/7469/14400 6563/7468/14341 6562/6745/13312 +f 6686/7362/13695 6687/7098/13695 6685/7041/13631 +f 6751/7438/12916 6750/7114/12916 6748/7260/12916 +f 6763/6412/13028 6768/7343/12962 6759/7229/12962 +f 7139/7727/14603 7138/7713/14576 7136/7769/14670 +f 7357/7686/14540 7328/7754/14643 7359/7854/14770 +f 7601/7376/12847 7576/7344/12847 7574/7440/12847 +f 7899/6945/13054 7900/7265/13054 7901/6568/13155 +f 7264/7917/14843 7260/7821/14733 7259/7918/14844 +f 6767/6345/14692 6877/7352/14692 6761/6014/14692 +f 6858/5766/12448 6856/7204/13813 6857/5767/12449 +f 7037/7634/14482 7301/7633/14481 7039/7649/14503 +f 6611/6894/13474 6613/6160/12802 6599/6126/14103 +f 6798/6011/12664 6799/5824/12663 6797/6801/13637 +f 7354/7764/14664 7357/7686/14540 7356/7685/14539 +f 7381/7826/14739 7298/7782/14685 7380/7861/14778 +f 6932/6901/12440 6911/5771/12440 6944/5770/12440 +f 7313/7667/14519 7318/7607/14450 7316/7696/14551 +f 7351/7697/14554 7330/7733/14610 7355/7765/14665 +f 7123/7694/14549 7050/7602/14441 7122/7601/14440 +f 6574/6455/12441 6571/6149/12441 6545/7532/12441 +f 6476/7118/13713 6484/6051/12698 6483/6050/12697 +f 7222/7833/14747 7393/7787/14691 7364/7921/14850 +f 6400/5925/12583 6405/6274/12899 6406/5926/12584 +f 6274/6281/14988 6394/7557/14988 6273/6682/14988 +f 7757/5870/12539 7672/7355/14433 7674/5871/12540 +f 7957/5994/12649 7970/6408/13024 7954/6410/13026 +f 6826/7202/13811 6827/6418/13034 6814/6417/13033 +f 7239/7915/14841 7374/7598/14437 7267/7604/14443 +f 7335/7904/14828 7377/7664/14518 7163/7663/14517 +f 6297/7171/14101 6298/7374/14789 6299/6398/13877 +f 7185/7962/14923 7302/7924/14853 7181/7810/14892 +f 7773/7077/13672 7770/7423/14136 7774/6895/13475 +f 7715/6042/14123 7730/6473/14122 7716/6040/14105 +f 7741/6396/13013 7726/6045/14367 7742/7320/14366 +f 7359/7854/14770 7362/7749/14637 7358/7684/14538 +f 7736/6394/14281 7780/6653/13227 7750/7409/14117 +f 7920/6446/13056 7918/6445/13056 7919/5863/14989 +f 7479/6817/13388 7467/5873/13389 7466/5875/14990 +f 7534/6402/13018 7533/6401/13017 7532/6871/13449 +f 7188/7914/14840 7305/7609/14453 7286/7976/14965 +f 7502/6979/13561 7504/7245/13870 7503/7151/13746 +f 7267/7604/14443 7268/7938/14876 7239/7915/14841 +f 7889/6424/13040 7859/6423/13039 7890/7551/14346 +f 6330/7437/13014 6329/7568/13014 6321/6493/13014 +f 7734/6485/13087 7775/6896/13476 7733/7576/14991 +f 6467/7017/14919 6468/6206/14992 6453/6201/13991 +f 7105/7860/14777 7017/7623/14468 7018/7839/14753 +f 6691/6240/13051 6693/6239/14993 6692/7103/13699 +f 7329/7732/14609 7357/7686/14540 7355/7765/14665 +f 6892/5756/12440 6898/5755/12440 6900/7284/12440 +f 7469/6028/12679 7480/6027/12678 7466/5875/14990 +f 7466/5875/14990 7480/6027/12678 7479/6817/13388 +f 7365/7934/14870 7366/7776/14677 7367/7773/14674 +f 7005/7768/14668 7026/7931/14865 7023/7786/14689 +f 7721/7444/14974 7716/6040/14105 7749/7190/14104 +f 7568/7088/14994 7569/6427/14995 7567/7365/14949 +f 7894/7378/14996 7898/7377/14996 7796/5987/14996 +f 7764/7144/13738 7748/7635/14483 7765/7191/13795 +f 7783/7242/14399 7665/6332/14399 7784/7666/14399 +f 6765/6059/12706 6849/5798/12475 6848/6060/12707 +f 6515/6483/13337 6401/6482/13337 6408/6676/13337 +f 6330/7437/14158 6327/6637/14300 6339/5929/14928 +f 6464/7905/14927 6465/7399/14098 6451/6336/13851 +f 6864/7455/14189 6866/7424/14137 6863/7428/14141 +f 6347/7057/13650 6346/6267/12975 6393/6505/13102 +f 6785/6476/13079 6784/6287/14997 6786/6477/13080 +f 6406/5926/12584 6504/7442/14168 6503/6448/13058 +f 5743/5788/12467 5843/5787/12466 5842/6526/13120 +f 7422/7124/13717 7416/6565/12862 7418/6582/12862 +f 6692/7103/13699 6693/6239/14993 6666/6759/13330 +f 6276/6503/12905 6286/6602/13181 6277/6601/12905 +f 7423/7363/14232 7509/6874/13452 7420/6234/12863 +f 7314/7957/14915 7404/7882/14804 7303/7948/14893 +f 7846/6833/14552 7869/6715/13281 7851/7986/14998 +f 6438/6175/12708 6449/6991/12708 6436/6099/12708 +f 6912/6369/13749 6913/7562/13749 6915/7154/13750 +f 5791/6301/14802 5793/7384/14077 5792/6928/14076 +f 6617/6124/12769 6618/6747/13314 6619/6125/12770 +f 6645/6556/13146 6740/5751/12437 6739/7004/13587 +f 7498/6072/12718 7515/5885/12552 7497/7350/14094 +f 7248/7863/14780 7243/7789/14694 7242/7987/14999 +f 5845/5789/12468 5846/6918/13508 5844/5972/12628 +f 7101/7947/14889 7091/7988/15000 7102/7989/15001 +f 7137/7886/14808 7000/7956/14913 7069/7832/14746 +f 7332/7961/14922 7350/7830/14744 7348/7655/14509 +f 6753/5900/12916 6752/7523/12916 6748/7260/12916 +f 6839/7097/13694 6840/7389/14592 6815/7188/14359 +f 7922/7500/13056 7918/6445/13056 7921/6444/13056 +f 7483/7233/13859 7499/7524/14294 7482/7462/14200 +f 7239/7915/14841 7240/7865/14782 7238/7901/14825 +f 6897/5975/12440 6894/5974/12440 6896/5976/12440 +f 7920/6446/14654 7940/5862/12531 7942/7744/14743 +f 7501/6271/12896 7492/7359/14034 7500/5843/12514 +f 7138/7713/14576 7077/7772/14673 7136/7769/14670 +f 7390/7784/14687 7388/7628/14473 7389/7669/14521 +f 6992/6433/13299 6879/6733/13299 6878/7748/13299 +f 6479/7580/14404 6478/6380/12999 6494/7132/13727 +f 6497/7018/13606 6402/5927/12585 6499/6192/12828 +f 6713/6385/13003 6743/7214/13835 6744/5810/12487 +f 6507/6897/13478 6467/7017/13605 6505/6898/13479 +f 7351/7697/14554 7355/7765/14665 7353/7893/14815 +f 6756/7302/13940 6855/7484/14235 6854/7401/14100 +f 7192/7990/15002 7290/7715/14581 7409/7937/14958 +f 7481/6029/13976 7523/6940/13529 7521/7368/14046 +f 6725/6729/14890 6700/6294/14891 6701/6730/15003 +f 6527/6437/13380 6520/6502/13380 6637/6501/13380 +f 6526/7107/13703 6528/6746/13313 6521/6500/12683 +f 7582/7546/14329 7561/5749/12435 7560/6823/13396 +f 7528/6167/12809 7527/7490/14248 7530/6168/12810 +f 7559/6983/13564 7558/7113/14478 7572/6984/13565 +f 7266/7978/14973 7267/7604/14443 7265/7944/14885 +f 7387/7629/14474 7295/7855/14771 7296/7856/14772 +f 7754/6122/12767 7742/7320/13968 7756/5872/12541 +f 7529/6169/12811 7422/7124/13717 7528/6167/12809 +f 5810/6527/13121 5842/6526/13120 5843/5787/12466 +f 7733/7576/14991 7775/6896/13476 7732/6355/12972 +f 7724/6395/13319 7736/6394/14281 7735/6749/13317 +f 7944/7586/14713 7921/6444/14713 7920/6446/14654 +f 7324/7939/14877 7323/7728/14604 7321/7699/14556 +f 6446/6581/14669 6447/6335/14207 6445/6200/14980 +f 6704/5793/12472 6674/5795/12472 6676/7045/12472 +f 7495/6021/12672 7471/6020/12671 7496/6599/13180 +f 7622/7184/13791 7597/6246/14959 7594/6248/13789 +f 7382/7813/14725 7309/7982/14982 7308/7983/14983 +f 7970/6408/14214 8009/7073/13668 8008/7075/13670 +f 7391/7862/14779 7309/7982/14982 7382/7813/14725 +f 5762/5892/12493 5761/6113/12757 5760/6112/12756 +f 6637/6501/12683 6638/6652/12683 6642/6651/12682 +f 6567/6714/13456 6566/7670/14522 6565/6184/13457 +f 6660/7453/14187 6672/7349/14966 6670/6839/13415 +f 6588/7133/13728 6628/7135/13730 6627/7060/13653 +f 7249/7790/14695 7243/7789/14694 7248/7863/14780 +f 6939/6136/12781 6953/6135/12780 6941/7509/14650 +f 6998/7711/14574 7139/7727/14603 7069/7832/14746 +f 7324/7939/14877 7321/7699/14556 7331/7698/14555 +f 6873/6012/13323 6872/7239/13323 6755/6753/13323 +f 6725/6729/14890 6709/7272/13905 6696/6726/13904 +f 6901/7332/14016 6892/5756/13568 6931/6718/14715 +f 7587/7157/13754 7589/6554/13756 7588/6887/15004 +f 7275/7875/14794 7273/7867/14784 7274/7841/14756 +f 7126/7593/14431 7005/7768/14668 7125/7594/14432 +f 7050/7602/14441 7372/7636/14485 7051/7600/14439 +f 7597/6246/12847 7568/7088/12847 7566/6247/12847 +f 6494/7132/13727 6493/6591/13174 6495/6017/12668 +f 6581/6832/14461 6592/7010/13594 6593/7102/13698 +f 5810/6527/13121 5811/6740/13306 5798/6742/13308 +f 7713/6041/13358 7714/6786/13357 7712/7520/14849 +f 6959/6946/14221 6942/5949/12606 6960/5948/12605 +f 6327/6637/13014 6330/7437/13014 6323/6638/13014 +f 6745/5811/12488 6744/5810/12487 6653/6102/12746 +f 7405/7883/14805 7406/7740/14624 7407/7757/14647 +f 7946/7587/14416 7949/6518/13434 7948/7759/14740 +f 7308/7983/14983 7315/7643/14496 7307/7788/14693 +f 7307/7788/14693 7382/7813/14725 7308/7983/14983 +f 7955/6654/13056 7945/7827/13056 7954/6410/13056 +f 7386/7630/14475 7400/7617/14462 7313/7667/14519 +f 6307/6183/13014 6336/7461/13014 6335/6091/13014 +f 7097/7692/14547 7123/7694/14549 7124/7977/14967 +f 5770/7465/14210 5767/6628/14986 5757/7481/14680 +f 6489/6095/12739 6485/6144/12789 6486/7160/13759 +f 7697/7564/14644 7681/6971/13550 7695/7235/13861 +f 7931/7549/14338 7918/6445/14340 7917/7477/14883 +f 7054/7825/14738 7368/7932/14866 7291/7743/14630 +f 6525/6031/12682 6530/7015/12682 6531/6250/12875 +f 7867/7525/14295 7800/5988/12644 7866/7605/15005 +f 7570/6819/13391 7573/6821/13393 7572/6984/14803 +f 6715/7119/13714 6714/5812/12489 6746/7120/13715 +f 7976/6532/13126 7988/6569/13156 7975/6024/12675 +f 6435/6098/15006 6419/7293/14402 6437/7147/13742 +f 7135/7887/14809 7000/7956/14913 7137/7886/14808 +f 7046/7804/14716 7056/7616/14460 7047/7719/14591 +f 7997/7325/13978 7998/6459/13068 7999/5963/12619 +f 7567/7365/14949 7566/6247/14934 7568/7088/14994 +f 6688/6266/12891 6687/7098/13695 6686/7362/13695 +f 7553/7559/14358 7628/6361/12979 7552/7824/14736 +f 6809/6509/14186 6779/6111/14074 6780/7186/14073 +f 7313/7667/14519 7389/7669/14521 7386/7630/14475 +f 7820/7286/14361 7821/6282/14708 7823/5848/14362 +f 7451/6180/14052 7452/7065/15007 7450/7064/15008 +f 7743/5809/12486 7757/5870/12539 7742/7320/13968 +f 6864/7455/14189 6863/7428/14141 6862/6153/12796 +f 7212/7849/14764 7281/7851/14766 7280/7991/15009 +f 7319/7857/14773 7305/7609/14453 7184/7913/14839 +f 6719/5860/12529 6727/6491/13091 6730/6273/12898 +f 6645/6556/13146 6647/6101/12745 6740/5751/12437 +f 6509/7213/13833 6511/7543/14324 6510/7178/13783 +f 7220/7680/14534 7234/7679/14533 7233/7959/14918 +f 6318/6806/14860 6317/7189/13793 6319/6494/13095 +f 7176/7992/15010 7315/7643/14496 7180/7642/14495 +f 7328/7754/14643 7357/7686/14540 7329/7732/14609 +f 7168/7848/14763 7169/7662/14516 7377/7664/14518 +f 5848/6284/12907 5849/7480/14231 5850/5790/12469 +f 7453/6561/14627 7452/7065/15007 7451/6180/14052 +f 7563/6888/13468 7590/6544/14113 7564/6543/13895 +f 7375/7599/14438 7237/7588/14422 7235/7590/14424 +f 6303/7445/14171 6302/6865/14626 6290/7430/14148 +f 7194/7970/14956 7409/7937/14958 7410/7756/14908 +f 5811/6740/13306 5812/5971/14939 5797/6741/13307 +f 7726/6045/14367 7725/7266/14428 7743/5809/14368 +f 7707/7139/12562 7718/7486/12692 7709/7137/12562 +f 6566/7670/12441 6577/7230/12558 6564/7469/12441 +f 7342/7672/14526 7299/7963/14924 7341/7739/14620 +f 7143/7993/15011 7141/7994/15012 7147/7726/14602 +f 7635/6912/13501 7634/6432/13049 7633/6146/12791 +f 6433/6970/14401 6419/7293/14402 6435/6098/15006 +f 6541/6185/12441 6540/7281/13916 6539/5747/12433 +f 7365/7934/14870 7364/7921/14850 7394/7846/14761 +f 7338/7809/14721 7299/7963/14924 7298/7782/14685 +f 7902/7310/13957 7900/7265/13957 8014/7279/13957 +f 6722/7516/14684 6657/7347/14014 6732/6649/13225 +f 6387/6754/13324 6388/7541/14322 6389/7540/14321 +f 6671/6296/13955 6670/6839/14737 6672/7349/14022 +f 6884/6434/14420 6882/6640/14420 6995/7567/14420 +f 6562/6745/14623 6560/6744/13914 6541/6185/12822 +f 6304/6317/13014 6307/6183/13014 6335/6091/13014 +f 6572/6713/14613 6535/7538/14335 6544/7547/14336 +f 7277/7842/14757 7279/7995/15013 7278/7975/14963 +f 6339/5929/14928 6340/5928/14159 6330/7437/14158 +f 7316/7696/14551 7318/7607/14450 7319/7857/14773 +f 5851/6570/13157 5814/6572/13159 5847/5973/12629 +f 7662/6697/13909 7782/7491/13909 7786/7084/13909 +f 7106/7780/14682 7105/7860/14777 7016/7859/14776 +f 6547/5891/14066 6546/7109/14310 6548/7108/14067 +f 7655/5905/12648 7656/6312/12648 7542/5992/12648 +f 7789/6968/14080 7885/7432/14152 7791/6966/14151 +f 6621/7196/13800 6606/6454/13818 6605/7383/14343 +f 7907/6551/13872 8006/6944/13533 8007/7074/13669 +f 6823/7203/13812 6824/7537/14317 6811/6666/14372 +f 7202/7964/14938 7219/7688/14542 7201/7853/14768 +f 7180/7642/14495 7320/7644/14497 7302/7924/14853 +f 6537/7346/12558 6536/7110/12558 6539/5747/12433 +f 8004/7969/14955 8006/6944/13533 8003/6943/13532 +f 7405/7883/14805 7403/7949/14894 7404/7882/14804 +f 5854/7001/12985 5855/7003/12985 5858/6999/12985 +f 6980/5815/12492 6881/7536/14316 6978/6720/13286 +f 7702/6534/13815 7705/5896/13814 7704/6535/13814 +f 7898/7377/13411 7893/7012/13411 7897/7582/13411 +f 6536/7110/12558 6543/7476/12441 6539/5747/12433 +f 5829/6915/13505 5818/5969/12625 5830/7396/14096 +f 7224/7717/14586 7206/7690/14545 7225/7996/15014 +f 7440/6677/12542 7437/7390/12542 7470/6598/12542 +f 7620/6662/13500 7636/7209/13826 7635/6912/13501 +f 7944/7586/14755 7943/6903/14755 7945/7827/14755 +f 7757/5870/12539 7758/5777/12456 7672/7355/14433 +f 7433/6810/12542 7431/7578/14394 7432/7063/13657 +f 6488/6096/12740 6487/7181/13787 6412/7366/14043 +f 6926/6479/13082 6928/6481/13084 6927/6986/14897 +f 6601/6827/13400 6602/6123/13484 6582/5838/13401 +f 7294/7742/14629 7388/7628/14473 7293/7878/14797 +f 7326/7866/14783 7157/7803/14714 7322/7595/14434 +f 5798/6742/13027 5797/6741/12493 5788/7300/12493 +f 7145/7997/15015 7143/7993/15011 7142/7998/15016 +f 7008/7778/14679 7107/7779/14681 7013/7933/14869 +f 7054/7825/14738 7003/7676/14530 7053/7796/14703 +f 6771/6109/12498 6770/6510/12498 6777/6847/12498 +f 7377/7664/14518 7376/7752/14641 7378/7847/14762 +f 5787/6990/13553 5785/5893/12560 5762/5892/12559 +f 7062/7899/14822 7064/7763/14661 7127/7900/14823 +f 6528/6746/13313 6533/6159/12801 6529/6650/14524 +f 7078/7771/14672 7138/7713/14576 7079/7967/14951 +f 6403/5924/14410 6404/6688/14410 6516/6687/14410 +f 7074/7999/15017 7138/7713/14576 7076/8000/15018 +f 7407/7757/14873 7409/7937/14875 7405/7883/15019 +f 7388/7628/14473 7294/7742/14629 7387/7629/14474 +f 7523/6940/13529 7525/7324/13977 7526/7489/14247 +f 7669/7101/12954 7665/6332/12954 7670/6108/12752 +f 6702/7340/12472 6703/6347/12472 6685/7041/12472 +f 6396/7585/14981 6397/7556/14981 6277/6601/14981 +f 6873/6012/12665 6761/6014/12665 6877/7352/12665 +f 6701/6730/12472 6700/6294/12472 6671/6296/12472 +f 7930/6235/12864 7931/7549/14338 7917/7477/14883 +f 7709/7137/12562 7718/7486/12692 7720/6354/12562 +f 7401/7660/14514 7406/7740/14624 7404/7882/14804 +f 6451/6336/12708 6447/6335/12708 6450/6917/12708 +f 5766/6626/13207 5767/6628/13209 5768/7275/14580 +f 5799/7341/14004 5809/6528/13880 5810/6527/13121 +f 7945/7827/13056 7955/6654/13056 7947/7459/13056 +f 7850/5849/12518 7821/6282/12518 7851/7986/12518 +f 6585/6646/12441 6583/6128/12558 6552/7447/12441 +f 6389/7540/14321 6390/6318/12941 6343/6924/13516 +f 7590/6544/14283 7588/6887/15004 7589/6554/13756 +f 7064/7763/14661 7065/7965/14942 7001/7888/14810 +f 7864/5910/13938 7872/6005/12660 7863/5911/12572 +f 7946/7587/14712 7922/7500/14941 7921/6444/14713 +f 7868/7338/14589 7851/7986/14998 7869/6715/13281 +f 7445/6442/14023 7444/7405/15020 7442/6850/14024 +f 7256/7819/14731 7260/7821/14733 7264/7917/14843 +f 7355/7765/14665 7330/7733/14610 7329/7732/14609 +f 7850/5849/14588 7851/7986/14998 7868/7338/14589 +f 7029/7615/14459 7116/7891/14813 7115/7677/14531 +f 7113/7656/14510 7030/7700/14557 7114/7678/14532 +f 7034/7702/14559 7113/7656/14510 7003/7676/14530 +f 6464/7905/14829 6482/6916/14037 6500/7361/14036 +f 7772/7449/14179 7768/6474/13077 7730/6473/13076 +f 7030/7700/14557 7028/7736/14616 7114/7678/14532 +f 7003/7676/14530 7054/7825/14738 7002/7674/14528 +f 7034/7702/14559 7003/7676/14530 7035/7985/14987 +f 7763/6861/13438 7762/6547/13139 7765/7191/13795 +f 6993/6732/13591 6994/6435/13591 6996/6325/13591 +f 7114/7678/14532 7028/7736/14616 7029/7615/14459 +f 7301/7633/14481 7043/7632/14480 7002/7674/14528 +f 6703/6347/12964 6715/7119/14914 6716/6348/12965 +f 7747/7143/14975 7721/7444/14974 7748/7635/15021 +f 7908/6549/13141 8009/7073/13668 8010/7478/14228 +f 6569/6151/14227 6570/6712/13279 6571/6149/13278 +f 6632/7406/14114 6531/6250/12875 6633/5850/12519 +f 7297/7783/14686 7300/8001/15022 7293/7878/14797 +f 7053/7796/14703 7373/7603/14442 7374/7598/14437 +f 7890/7551/14346 7792/7014/13599 7797/7013/13598 +f 7086/8002/15023 7136/7769/14670 7077/7772/14673 +f 7573/6821/12847 7603/7297/12847 7574/7440/12847 +f 7058/7822/14734 7023/7786/14689 7017/7623/14468 +f 6842/5889/12556 6841/5888/12555 6853/6166/12808 +f 6277/6601/13221 6397/7556/13221 6398/6641/13221 +f 7075/8003/15024 7138/7713/14576 7140/8004/15025 +f 5751/6365/12990 5821/6225/13947 5831/7305/13948 +f 7221/7835/14749 7197/7834/14748 7196/7955/14904 +f 7897/7582/14847 7793/6954/14847 7798/6835/14847 +f 6538/8005/15026 6550/7448/14663 6537/7346/14012 +f 7060/7823/14735 7023/7786/14689 7058/7822/14734 +f 6681/7367/14972 6679/6907/13494 6663/6906/13493 +f 6310/6606/13185 6311/6608/13185 6309/7558/14929 +f 7553/7559/14358 7552/7824/14736 7551/7560/12567 +f 7586/6213/13755 7587/7157/13754 7585/5750/15027 +f 6335/6091/12735 6353/6356/12973 6332/5901/12564 +f 7207/7952/14900 7208/7837/14751 7228/7925/14858 +f 7209/7838/14752 7210/8006/15028 7219/7688/14542 +f 7415/6403/13019 7504/7245/13870 7425/7244/13869 +f 7510/5842/12513 7508/6399/13015 7500/5843/12514 +f 6698/7400/14099 6711/5753/12439 6699/6564/13152 +f 7129/7966/14944 7130/7761/14659 7132/7885/14807 +f 7746/6546/14912 7722/7267/14911 7747/7143/14975 +f 5799/7341/12493 5798/6742/13027 5788/7300/12493 +f 7352/7725/14601 7058/7822/14734 7349/7724/14600 +f 6421/6068/12708 6420/7087/12708 6415/7123/12708 +f 6409/7395/14093 6410/6275/12900 6403/5924/12583 +f 6760/7358/12657 6755/6753/12657 6872/7239/12657 +f 7066/7889/14811 7132/7885/14807 7130/7761/14659 +f 7212/7849/14764 7370/7637/14486 7215/7930/14864 +f 7838/5762/12444 7839/5761/12443 7840/6673/13247 +f 7329/7732/14609 7325/7731/14608 7327/7753/14642 +f 7999/5963/12619 7901/6568/13155 7997/7325/13978 +f 7315/7643/14496 7309/7982/14982 7310/7738/14619 +f 7380/7861/14778 7382/7813/14725 7381/7826/14739 +f 6468/6206/12839 6467/7017/13605 6507/6897/13478 +f 7261/7943/14881 7262/7820/14732 7256/7819/14731 +f 7894/7378/14996 7796/5987/14996 7788/7507/14996 +f 6836/6818/15029 6835/7173/14370 6848/6060/12707 +f 7055/7805/14717 7299/7963/14924 7057/7671/14525 +f 7496/6599/14095 7515/5885/12552 7514/7307/13950 +f 6646/7240/13867 6736/6055/12702 6735/6057/12704 +f 5774/6154/13806 5760/6112/12756 5776/5953/13473 +f 6468/6206/14992 6469/6205/13992 6453/6201/13991 +f 6656/6292/12915 6648/6291/12983 6746/7120/13715 +f 7546/6230/12860 7640/6038/12689 7644/6037/12688 +f 7954/6410/13056 7943/6903/13056 7957/5994/13056 +f 7472/6562/13667 7486/6872/13450 7475/6560/14622 +f 7712/7520/14285 7676/7488/14246 7710/7421/14932 +f 7883/7426/14139 7855/7211/14031 7884/7356/14030 +f 6716/6348/12965 6717/7078/13673 6695/6346/12963 +f 6402/5927/12585 6497/7018/13606 6496/6015/12666 +f 6314/6735/13301 6312/6849/14142 6293/6736/13302 +f 6463/6992/14257 6449/6991/14276 6472/7158/13757 +f 7101/7947/14889 7049/7807/14719 7092/7881/14800 +f 6469/6205/13992 6470/7177/15030 6458/6951/13993 +f 6986/7328/13986 6985/7456/14191 6989/6634/13217 +f 7964/6533/13056 7934/5983/13056 7932/6471/13056 +f 6879/6733/13592 6885/7008/13592 6883/7591/14425 +f 6693/6239/14993 6694/6758/13328 6666/6759/13330 +f 6385/6139/12784 6383/6142/12787 6386/6755/13325 +f 7482/7462/14200 7525/7324/13977 7481/6029/13976 +f 7121/7895/14817 7017/7623/14468 7103/8007/15031 +f 6274/6281/14988 6395/7581/14988 6394/7557/14988 +f 7786/7084/12954 7783/7242/12956 7785/7665/12956 +f 7539/6566/12862 7535/6584/12862 7538/6727/12862 +f 7332/7961/14922 7348/7655/14509 7334/7612/14456 +f 6473/7497/14256 6486/7160/13759 6485/6144/12789 +f 7862/7269/13900 7892/7306/13949 7861/6540/13134 +f 6330/7437/13014 6321/6493/13014 6323/6638/13014 +f 7123/7694/14549 7049/7807/14719 7050/7602/14441 +f 5807/5779/12458 5839/6321/12944 5841/5780/12459 +f 7831/7223/14954 7807/7583/14407 7830/6891/14409 +f 6926/6479/14662 6900/7284/13921 6924/7450/14180 +f 6551/7718/14971 6538/8005/15026 6539/5747/12433 +f 6577/7230/13856 6591/7011/13595 6575/7470/14315 +f 6909/5769/14583 6908/7354/14583 6906/7283/14584 +f 6478/6380/12999 6479/7580/14979 6456/6723/13289 +f 7098/7877/14796 7094/7693/14548 7087/7735/14615 +f 7282/7850/14765 7212/7849/14764 7283/7968/14952 +f 6504/7442/14168 6505/6898/13479 6466/7016/13604 +f 6295/6384/13001 6322/5999/12654 6320/6382/13001 +f 7293/7878/14797 7300/8001/15022 7301/7633/14481 +f 7727/6054/12562 7694/7519/12562 7728/6043/12692 +f 7372/7636/14485 7050/7602/14441 7371/7638/14487 +f 7065/7965/14942 7064/7763/14661 7062/7899/14822 +f 7498/6072/12718 7470/6598/13179 7467/5873/13389 +f 7959/6470/13056 7929/6472/13056 7960/7577/13056 +f 6912/6369/13749 6911/5771/15032 6913/7562/13749 +f 5856/6338/12957 5740/6340/12957 5854/7001/12957 +f 5830/7396/14096 5831/7305/13948 5829/6915/13505 +f 7782/7491/12954 7783/7242/12956 7786/7084/12954 +f 7192/7990/15002 7190/7707/14570 7290/7715/14581 +f 6745/5811/12488 6656/6292/12915 6746/7120/13715 +f 7102/7989/15001 7091/7988/15000 7090/8008/15033 +f 7312/7608/14451 7318/7607/14450 7313/7667/14519 +f 6676/7045/12472 6678/6592/12472 6708/6787/12472 +f 7972/5845/12516 7986/7534/14313 7987/7584/14414 +f 7493/5841/14550 7476/7261/13892 7494/6019/12670 +f 7614/7387/14081 7601/7376/14058 7615/7375/14057 +f 6706/7255/13887 6708/6787/14167 6720/6272/13885 +f 7130/7761/14659 7064/7763/14661 7066/7889/14811 +f 6352/6090/13359 6359/5879/12546 6369/7404/14108 +f 7232/8009/15034 7231/8010/15035 7214/7681/14535 +f 7299/7963/14924 7055/7805/14717 7300/8001/15022 +f 7809/6304/12925 7838/5762/14711 7802/6829/13405 +f 6539/5747/12433 6538/8005/15036 6537/7346/12558 +f 7851/7986/12518 7818/5979/12518 7846/6833/12518 +f 6894/5974/13920 6906/7283/13919 6895/7353/14028 +f 7070/7734/14611 6998/7711/14574 7071/7710/14573 +f 7061/7592/14430 7354/7764/14664 7063/7816/14728 +f 6913/7562/12440 6911/5771/12440 6932/6901/12440 +f 6522/7106/13702 6629/7574/14387 6626/7094/13688 +f 6817/5822/13971 6829/7439/14162 6830/7321/13972 +f 7946/7587/14712 7948/7759/14656 7922/7500/14941 +f 6292/6429/13046 6293/6736/13302 6310/6606/14143 +f 7708/7138/13731 7711/7278/13922 7710/7421/13922 +f 6865/7425/14138 6762/7357/14395 6768/7343/14006 +f 7131/7745/14631 7129/7966/14944 7132/7885/14807 +f 7358/7684/14538 7357/7686/14540 7359/7854/14770 +f 7248/7863/14780 7240/7865/14782 7239/7915/14841 +f 6813/6416/12498 6802/7499/12498 6804/5943/12498 +f 5846/6918/13508 5847/5973/12629 5844/5972/12628 +f 6573/6150/13198 6574/6455/13064 6587/7134/13889 +f 6648/6291/12983 6729/5803/12480 6728/6492/13092 +f 6568/6878/14856 6565/6184/12821 6542/6186/12821 +f 6426/6909/14284 6425/6908/14882 6415/7123/14251 +f 7486/6872/13450 7531/7342/14005 7485/7487/14243 +f 7291/7743/14630 7294/7742/14629 7301/7633/14481 +f 6486/7160/13759 6473/7497/14256 6472/7158/13757 +f 7401/7660/14514 7312/7608/14451 7397/7844/14759 +f 7375/7599/14438 7053/7796/14703 7374/7598/14437 +f 7731/6353/12970 7771/7412/14120 7772/7449/14179 +f 7139/7727/14603 7136/7769/14670 7137/7886/14808 +f 6915/7154/12440 6939/6136/12440 6916/6158/12800 +f 6905/6798/13918 6893/5754/14017 6903/6828/14884 +f 6576/6621/12441 6577/7230/12558 6566/7670/12441 +f 7349/7724/14600 7058/7822/14734 7059/7896/14818 +f 6975/5832/12506 6976/6722/13288 6974/5830/12504 +f 6717/7078/13673 6716/6348/12965 6747/7723/14597 +f 6654/7398/14377 6752/7523/14377 6753/5900/14377 +f 7683/7372/14053 7710/7421/14932 7676/7488/14246 +f 7460/6671/14388 7462/6462/13071 7435/6809/14071 +f 7637/6813/13384 7639/7569/14379 7638/6814/13385 +f 6794/6843/13419 6795/6802/14417 6796/6844/13420 +f 6646/7240/13867 6651/7441/14165 6644/7414/12914 +f 6326/6268/12893 6347/7057/14964 6348/6288/12911 +f 5782/7575/14564 5780/6996/15037 5761/6113/12757 +f 6403/5924/12583 6411/5923/12583 6412/7366/14043 +f 7944/7586/14415 7945/7827/14415 7947/7459/14416 +f 6541/6185/12822 6560/6744/13914 6540/7281/13916 +f 7139/7727/14603 7148/7880/14799 7147/7726/14602 +f 6294/6383/13002 6315/6734/13300 6293/6736/13302 +f 6533/6159/12801 6532/6032/12683 6529/6650/14524 +f 7701/6876/13903 7702/6534/13815 7700/7270/13901 +f 6350/6955/13541 6336/7461/14565 6337/6956/13542 +f 7927/6701/13056 7956/5868/13056 7961/7555/13056 +f 6577/7230/12558 6575/7470/12558 6564/7469/12441 +f 6667/7335/14543 6694/6758/15038 6658/6238/12867 +f 7580/5764/12446 7581/7530/14383 7579/5765/12447 +f 6362/6289/12912 6347/7057/13650 6393/6505/13102 +f 7796/5987/12643 7798/6835/13411 7800/5988/12644 +f 7274/7841/14756 7267/7604/14443 7373/7603/14442 +f 6772/6286/12909 6786/6477/13336 6784/6287/12910 +f 7913/6826/13399 7989/7457/14193 7912/7167/14448 +f 5801/6465/12493 5802/7308/12493 5784/6466/12493 +f 7254/8011/15039 7253/7908/14833 7255/7922/14851 +f 7623/7183/13790 7594/6248/13789 7593/7292/14032 +f 7183/7811/14854 7319/7857/14773 7186/8012/15040 +f 7348/7655/14509 7347/7673/14527 7343/7751/14639 +f 7029/7615/14459 7118/7614/14458 7117/7890/14812 +f 6433/6970/14178 6432/5935/14178 6431/7241/14178 +f 7753/7246/13871 7751/6121/12766 7752/7206/13820 +f 7127/7900/14823 7124/7977/14967 7126/7593/14431 +f 7821/6282/12518 7818/5979/12518 7851/7986/12518 +f 7406/7740/14624 7393/7787/14691 7402/7755/14645 +f 6318/6806/13014 6319/6494/13014 6329/7568/13014 +f 7099/7808/14720 7049/7807/14719 7100/7946/14888 +f 6379/6522/13118 6275/6681/13994 6381/6141/12786 +f 7818/5979/12634 7813/5978/12633 7816/6788/13360 +f 6748/7260/15041 6643/7115/15041 6644/7414/15041 +f 7413/6229/12859 7522/6228/12858 7419/7273/13907 +f 5780/6996/15037 5778/5951/12758 5761/6113/12757 +f 6368/7403/14107 6283/6064/12710 6370/7370/14050 +f 7088/7747/14633 7097/7692/14547 7131/7745/14631 +f 6952/7758/14649 6951/6752/13322 6940/6751/13321 +f 5820/6224/13504 5819/5967/12623 5829/6915/13505 +f 7404/7882/14804 7314/7957/14915 7401/7660/14514 +f 7307/7788/14693 7315/7643/14496 7306/7654/14508 +f 7122/7601/14440 7124/7977/14967 7123/7694/14549 +f 6748/7260/15041 6644/7414/15041 6749/5898/15042 +f 6958/6948/13537 6967/6975/13554 6957/6977/13558 +f 6462/6062/12708 6460/6831/12708 6432/5935/12708 +f 7156/7596/14435 7322/7595/14434 7157/7803/14714 +f 7393/7787/14691 7222/7833/14747 7402/7755/14645 +f 7184/7913/14839 7188/7914/14840 7187/8013/15043 +f 6752/7523/14950 6649/6293/14950 6751/7438/14950 +f 7134/7884/14806 7132/7885/14807 7135/7887/14809 +f 7336/7647/14501 7165/7646/14500 7333/7613/14457 +f 7868/7338/14002 7877/6716/13282 7867/7525/14295 +f 7396/7659/14513 7394/7846/15044 7393/7787/14691 +f 8006/6944/13533 8004/7969/14955 8005/7298/13935 +f 6822/6889/13777 6821/7333/13996 6834/7225/13846 +f 7413/6229/12859 7518/7217/13837 7520/6227/12857 +f 7141/7994/15012 7138/7713/14576 7147/7726/14602 +f 5826/7531/14418 5825/5956/12612 5837/5958/12614 +f 6957/6977/13558 6943/7473/14222 6958/6948/15045 +f 6366/5880/12547 6365/6794/13366 6287/6063/12709 +f 7531/7342/14005 7529/6169/12811 7530/6168/12810 +f 6476/7118/13713 6477/6379/12998 6460/6831/13407 +f 6291/6119/13014 6290/7430/13014 6295/6384/13014 +f 7508/6399/13015 7426/6524/13119 7507/6400/13016 +f 7061/7592/14430 7023/7786/14689 7060/7823/14735 +f 7529/6169/12811 7531/7342/14005 7415/6403/13019 +f 6949/6659/13233 6936/7193/14109 6935/6496/14015 +f 7726/6045/12692 7692/6044/12562 7725/7266/12562 +f 7370/7637/14486 7218/7928/14862 7216/7929/14863 +f 7981/5867/12536 7993/6039/12691 7992/6187/12823 +f 7299/7963/14924 7338/7809/14721 7341/7739/14620 +f 7039/7649/14503 7038/7651/14505 7037/7634/14482 +f 7919/5863/12532 7937/6148/12793 7939/5864/12533 +f 6898/5755/13768 6921/6708/14355 6899/7451/14181 +f 7289/7708/14571 7190/7707/14570 7191/8014/15046 +f 7178/8015/15047 7315/7643/14496 7177/8016/15048 +f 6593/7102/13698 6530/7015/13600 6594/6521/13117 +f 5812/5971/14939 5813/7522/14290 5801/6465/14289 +f 6796/6844/12498 6799/5824/12498 6818/5823/12498 +f 7593/7292/12847 7591/6545/12847 7596/6555/12847 +f 7153/7960/14921 7345/7705/14562 7344/7814/14726 +f 7998/6459/13068 7965/6278/12903 8000/6277/12902 +f 7488/7140/13841 7534/6402/13018 7487/6873/13451 +f 8014/7279/13054 8019/6644/13054 8015/7311/13054 +f 7127/7900/14823 7064/7763/14661 7128/7762/14660 +f 6908/7354/14029 6896/5976/12631 6895/7353/14028 +f 7631/6343/12960 7625/5939/12597 7632/6431/13048 +f 7748/7635/15021 7721/7444/14974 7749/7190/14104 +f 7897/7582/13411 7893/7012/13411 7896/7216/13411 +f 7081/7621/14466 7136/7769/14670 7086/8002/15023 +f 6553/5746/14887 6552/7447/14887 6551/7718/14887 +f 7083/7912/14837 7084/7620/14465 7085/7622/14467 +f 5778/5951/12608 5779/6578/12608 5777/5952/12609 +f 7584/7319/13967 7586/6213/13755 7585/5750/15027 +f 7094/7693/14548 7095/7984/14984 7093/7979/14976 +f 7053/7796/14703 7052/7777/14678 7373/7603/14442 +f 7213/7640/14492 7214/7681/14535 7270/7785/14688 +f 7561/5749/12847 7563/6888/12847 7560/6823/13396 +f 7461/6643/12542 7459/7408/12542 7469/6028/12542 +f 5765/6627/14953 5793/7384/14832 5756/6300/12921 +f 5813/7522/14931 5812/5971/12627 5847/5973/12629 +f 7915/7411/13056 7918/6445/13056 7922/7500/13056 +f 5846/6918/13508 5750/7505/14268 5849/7480/14231 +f 7824/5920/14905 7826/5919/14985 7806/7566/14373 +f 7392/7618/14463 7387/7629/14474 7296/7856/14772 +f 7001/7888/14810 7358/7684/14538 7067/7750/14638 +f 7405/7883/15049 7408/7950/15049 7403/7949/15049 +f 7155/7597/14436 7363/7626/14471 7322/7595/14434 +f 7435/6809/12542 7429/6851/12542 7433/6810/12542 +f 6736/6055/12702 6725/6729/13296 6734/6056/12703 +f 7136/7769/14670 7134/7884/14806 7137/7886/14808 +f 7300/8001/15022 7297/7783/14686 7299/7963/14924 +f 7347/7673/14527 7056/7616/14460 7057/7671/14525 +f 7131/7745/14631 7097/7692/14547 7129/7966/14944 +f 7104/8017/15050 7017/7623/14468 7105/7860/14777 +f 7391/7862/14779 7380/7861/14778 7390/7784/14687 +f 6859/5768/12450 6860/7304/13942 6861/7454/14188 +f 7372/7636/14485 7274/7841/14756 7373/7603/14442 +f 6910/5977/14867 6909/5769/14868 6911/5771/14868 +f 7072/7879/14798 7139/7727/14603 7070/7734/14611 +f 7162/8018/15051 7336/7647/14501 7335/7904/14828 +f 6774/7061/13654 6775/6800/13372 6795/6802/13374 +f 7779/6326/12948 7780/6653/13227 7669/7101/13697 +f 7853/5912/12573 7865/7380/14412 7864/5910/12571 +f 7051/7600/14439 7373/7603/14442 7052/7777/14678 +f 6326/6268/13014 6337/6956/13014 6309/7558/13014 +f 7452/7065/15007 7453/6561/14627 7454/6629/13210 +f 6961/5950/14937 6970/6377/12996 6960/5948/14047 +f 7232/8009/15034 7214/7681/14535 7223/7716/14585 +f 6510/7178/13783 6513/7159/13758 6471/7176/13781 +f 7468/7234/12542 7459/7408/12542 7457/6515/12542 +f 7146/8019/15052 7143/7993/15011 7145/7997/15015 +f 7314/7957/14915 7312/7608/14451 7401/7660/14514 +f 6544/7547/14596 6545/7532/14309 6572/6713/13280 +f 6591/7011/13595 6590/7231/14566 6631/7573/14386 +f 7363/7626/14471 7345/7705/14562 7361/7704/14561 +f 7378/7847/14762 7170/7941/14879 7168/7848/14763 +f 6675/7047/13982 6662/6488/13088 6677/7128/14855 +f 7399/7619/14464 7398/7845/14760 7400/7617/14462 +f 7211/7852/14767 7219/7688/14542 7210/8006/15028 +f 7675/6333/12955 7755/6120/12765 7674/5871/12540 +f 6657/7347/14014 6651/7441/14165 6733/6648/13224 +f 7979/7313/13960 7991/6188/12824 7990/7312/13958 +f 7778/6484/13086 7735/6749/13317 7750/7409/14117 +f 6651/7441/14165 6657/7347/14014 6652/5899/14166 +f 7010/7800/14707 7005/7768/14668 7006/7907/14831 +f 7759/7386/14079 7758/5777/12456 7744/5808/12485 +f 7206/7690/14545 7223/7716/14585 7214/7681/14535 +f 7448/6922/13513 7451/6180/14052 7450/7064/15008 +f 6769/6058/12705 6835/7173/14370 6834/7225/13846 +f 7336/7647/14501 7340/7775/14676 7339/7774/14675 +f 7804/6989/13572 7820/7286/13924 7805/7285/13923 +f 7441/6678/13251 7443/6960/14025 7442/6850/14024 +f 7737/6777/14020 7723/6393/13348 7738/6778/13349 +f 7804/6989/13572 7817/6988/13571 7819/7434/15053 +f 7089/7746/14632 7084/7620/14465 7082/7911/14836 +f 7326/7866/14783 7328/7754/14643 7157/7803/14714 +f 6407/6241/12870 6495/6017/12668 6493/6591/13174 +f 7896/7216/13411 7893/7012/13411 7895/6952/13411 +f 7903/7417/14132 8013/7458/14194 7913/6826/13399 +f 6888/7369/14048 6885/7008/13592 6891/6245/13591 +f 7475/6560/12542 7455/6514/12542 7453/6561/12542 +f 6610/5959/12615 6609/5945/12602 6608/7571/14381 +f 7039/7649/14503 7301/7633/14481 7300/8001/15022 +f 6316/6768/14049 6315/6734/14086 6317/7189/13793 +f 7384/7722/14595 7340/7775/14676 7383/7720/14593 +f 7212/7849/14764 7280/7991/15009 7277/7842/14757 +f 7341/7739/14620 7333/7613/14457 7342/7672/14526 +f 7367/7773/14674 7364/7921/14850 7365/7934/14870 +f 5816/6724/13944 5817/6776/13345 5794/6775/13344 +f 6865/7425/14138 6768/7343/14006 6867/5990/12646 +f 6417/7419/12708 6416/7503/12708 6415/7123/12708 +f 7286/7976/14965 7189/7973/14961 7287/7972/14960 +f 7092/7881/14800 7123/7694/14549 7093/7979/14976 +f 7220/7680/14534 7369/7687/14541 7235/7590/14424 +f 7675/6333/12955 7665/6332/12954 7669/7101/12954 +f 7388/7628/14473 7386/7630/14475 7389/7669/14521 +f 7808/6302/12518 7806/7566/14373 7807/7583/14407 +f 6602/6123/13484 6603/7336/13999 6579/5839/13485 +f 7330/7733/14610 7323/7728/14604 7325/7731/14608 +f 6693/6239/12868 6658/6238/12867 6694/6758/15038 +f 6658/6238/12867 6659/6841/13417 6667/7335/14543 +f 7136/7769/14670 7081/7621/14466 7084/7620/14465 +f 7144/8020/15054 7143/7993/15011 7146/8019/15052 +f 7918/6445/14340 7935/5984/12794 7919/5863/12532 +f 7820/7286/13924 7804/6989/13572 7819/7434/15053 +f 7151/7909/14834 7069/7832/14746 7346/7760/14658 +f 7119/7981/14978 7118/7614/14458 7056/7616/14460 +f 7426/6524/13119 7508/6399/13015 7423/7363/14232 +f 6372/7526/14298 6278/6279/12904 6377/7429/14144 +f 7173/7797/14704 7376/7752/14641 7306/7654/14508 +f 7399/7619/14464 7366/7776/14677 7365/7934/14870 +f 6358/6498/13097 6384/6140/12785 6385/6139/12784 +f 7017/7623/14468 7104/8017/15050 7103/8007/15031 +f 7367/7773/14674 7291/7743/14630 7368/7932/14866 +f 7970/6408/14214 8008/7075/13670 7969/6409/13934 +f 6538/8005/15026 6551/7718/14971 6550/7448/14663 +f 7252/7641/14493 7253/7908/14833 7254/8011/15039 +f 7097/7692/14547 7128/7762/14660 7129/7966/14944 +f 7885/7432/14152 7886/7104/13700 7887/7431/14150 +f 6343/6924/13516 6386/6755/13325 6389/7540/14321 +f 7810/6674/12518 7839/5761/12518 7843/6249/12518 +f 6958/6948/15045 6943/7473/14222 6959/6946/14221 +f 6282/7402/14102 6387/6754/13324 6383/6142/12787 +f 7410/7756/14908 7195/7954/14903 7194/7970/14956 +f 6410/6275/12900 6409/7395/14093 6511/7543/14324 +f 6716/6348/12965 6746/7120/13715 6747/7723/14597 +f 5838/6370/12988 5839/6321/12944 5837/5958/12614 +f 7092/7881/14800 7091/7988/15000 7101/7947/14889 +f 7159/7729/14605 7323/7728/14604 7324/7939/14877 +f 6532/6032/14119 6642/6651/14119 6529/6650/14119 +f 7616/5940/12598 7631/6343/12960 7615/7375/14057 +f 6738/6557/13147 6709/7272/14319 6737/6558/13148 +f 6850/5796/12473 6839/7097/14690 6838/5797/12474 +f 7356/7685/14539 7001/7888/14810 7065/7965/14942 +f 6862/6153/12796 6859/5768/12450 6861/7454/14188 +f 8011/7460/14199 8013/7458/14194 7903/7417/14132 +f 7069/7832/14746 7139/7727/14603 7137/7886/14808 +f 7311/7668/14520 7310/7738/14619 7309/7982/14982 +f 7298/7782/14685 7390/7784/14687 7380/7861/14778 +f 6848/6060/12707 6837/6738/14397 6836/6818/15029 +f 6635/6251/12876 6530/7015/13600 6636/5851/12520 +f 6679/6907/13926 6680/6593/13926 6678/6592/14948 +f 6828/7201/13809 6829/7439/14162 6816/7200/13808 +f 7314/7957/14915 7304/7610/14454 7317/7606/14449 +f 7481/6029/13976 7521/7368/14046 7480/6027/14045 +f 7844/6009/12518 7834/6725/12518 7848/7517/12518 +f 6908/7354/14029 6910/5977/12632 6896/5976/12631 +f 7300/8001/15022 7055/7805/14717 7039/7649/14503 +f 7277/7842/14757 7371/7638/14487 7212/7849/14764 +f 7193/7971/14957 7192/7990/15002 7409/7937/14958 +f 5789/6973/14125 5788/7300/14126 5787/6990/14126 +f 7385/7721/14594 7383/7720/14593 7382/7813/14725 +f 7311/7668/14520 7391/7862/14779 7389/7669/14521 +f 6440/6176/14477 6437/7147/14426 6439/7146/14477 +f 7235/7590/14424 7369/7687/14541 7375/7599/14438 +f 7225/7996/15014 7206/7690/14545 7226/7689/14544 +f 6387/6754/13324 6282/7402/14102 6388/7541/14322 +f 6487/7181/13787 6489/6095/12739 6486/7160/13759 +f 6989/6634/13217 6952/7758/14819 6953/6135/12780 +f 7319/7857/14773 7302/7924/14853 7320/7644/14497 +f 5749/5791/12470 5850/5790/12469 5849/7480/14231 +f 7049/7807/14719 7048/7806/14718 7217/7927/14861 +f 7304/7610/14454 7289/7708/14571 7305/7609/14453 +f 5805/6226/12494 5773/6155/13027 5775/7326/13027 +f 7671/5776/12455 7668/6695/13263 7672/7355/13263 +f 6628/7135/13730 6587/7134/13729 6624/7058/13651 +f 7274/7841/14756 7372/7636/14485 7277/7842/14757 +f 6827/6418/14170 6826/7202/13913 6863/7428/14141 +f 7377/7664/14518 7335/7904/14828 7379/7951/14899 +f 7316/7696/14551 7319/7857/14773 7320/7644/14497 +f 6593/7102/15055 6594/6521/14291 6580/5759/14292 +f 7290/7715/14581 7304/7610/14454 7303/7948/14893 +f 6407/6241/12870 6493/6591/13174 6491/6049/12696 +f 7866/7605/15005 7800/5988/12644 7865/7380/14062 +f 7069/7832/14746 7151/7909/14834 6998/7711/14574 +f 7379/7951/14899 7335/7904/14828 7339/7774/14675 +f 6740/5751/12437 6742/7215/13836 6741/5752/12438 +f 7166/8021/15056 7337/7902/14826 7167/7903/14827 +f 7245/7682/14536 7214/7681/14535 7246/7792/14699 +f 5811/6740/13306 5810/6527/13121 5843/5787/12466 +f 7059/7896/14818 7056/7616/14460 7349/7724/14600 +f 6608/7571/14381 6609/5945/12602 6596/5947/12604 +f 6639/6436/13052 6640/7415/13052 6525/6031/13052 +f 7164/7648/14502 7336/7647/14501 7162/8018/15051 +f 7128/7762/14660 7124/7977/14967 7127/7900/14823 +f 6966/6947/13536 6969/7533/14311 6967/6975/13554 +f 6350/6955/13541 6351/6089/12733 6336/7461/14565 +f 5758/6553/14211 5759/6552/13805 5771/6156/13807 +f 6821/7333/12498 6822/6889/12498 6791/6639/12498 +f 6282/7402/14102 6286/6602/13181 6388/7541/14322 +f 6648/6291/12983 6747/7723/14597 6746/7120/13715 +f 6725/6729/13296 6724/6728/13295 6734/6056/12703 +f 7738/6778/13349 7727/6054/12701 7739/6053/12700 +f 6916/6158/14801 6918/7166/14127 6914/6368/13751 +f 7345/7705/14562 7153/7960/14921 7346/7760/14658 +f 7911/6440/13222 8019/6644/13222 8018/7280/13222 +f 8004/7969/14955 8003/6943/13532 8001/5961/12617 +f 6449/6991/14276 6457/6177/14578 6471/7176/13781 +f 7828/7309/14408 7807/7583/14407 7826/5919/14985 +f 7154/7980/14977 7344/7814/14726 7155/7597/14436 +f 7870/5801/12478 7882/5800/12477 7881/5955/12611 +f 7571/6820/13392 7569/6427/14995 7568/7088/14994 +f 6810/6297/12917 6832/6133/12919 6833/6351/12968 +f 6759/7229/12962 6768/7343/12962 6760/7358/12962 +f 5787/6990/14553 5788/7300/15057 5786/6464/13896 +f 7005/7768/14668 7009/7799/14706 7004/7766/14666 +f 6929/6613/13191 6930/6612/13190 6931/6718/13284 +f 6673/7046/13639 6674/5795/14021 6672/7349/14022 +f 7270/7785/14688 7214/7681/14535 7244/7683/14537 +f 7420/6234/12863 7412/6233/12862 7421/6525/12862 +f 7285/7935/14871 7213/7640/14492 7251/7639/14491 +f 6569/6151/14227 6567/6714/13456 6568/6878/13455 +f 6881/7536/14316 6980/5815/12492 6981/5814/12491 +f 7162/8018/15051 7335/7904/14828 7163/7663/14517 +f 7616/5940/12598 7601/7376/14058 7603/7297/13933 +f 6849/5798/12475 6765/6059/12706 6764/7288/14133 +f 6458/6951/12708 6440/6176/12708 6442/6199/12708 +f 6522/7106/13702 6524/7504/14265 6629/7574/14387 +f 7425/7244/13869 7416/6565/12862 7415/6403/13019 +f 7306/7654/14508 7175/7653/14507 7171/7897/14820 +f 7892/7306/13949 7873/6006/12661 7792/7014/13599 +f 7364/7921/14850 7367/7773/14674 7219/7688/14542 +f 7653/7483/14234 7553/7559/14358 7549/7036/13626 +f 6676/7045/13638 6674/5795/14021 6673/7046/13639 +f 6662/6488/13088 6660/7453/12472 6658/6238/12472 +f 7158/7611/14455 7337/7902/14826 7166/8021/15056 +f 7177/8016/15048 7315/7643/14496 7176/7992/15010 +f 7301/7633/14481 7002/7674/14528 7291/7743/14630 +f 7087/7735/14615 7097/7692/14547 7088/7747/14633 +f 7767/6329/12951 7749/7190/13794 7769/7422/14135 +f 7560/6823/13396 7556/6426/12847 7559/6983/13564 +f 5769/5816/14579 5767/6628/13209 5770/7465/14634 +f 6481/6559/13149 6480/6016/12667 6498/7019/13607 +f 7313/7667/14519 7400/7617/14462 7312/7608/14451 +f 6931/6718/13284 6902/6717/13283 6901/7332/13990 +f 8001/5961/12617 8003/6943/13532 8002/5962/12618 +f 6766/7420/14134 6761/6014/12962 6757/6013/12962 +f 7554/6693/13262 7551/7560/12567 7552/7824/14736 +f 7189/7973/14961 7305/7609/14453 7191/8014/15046 +f 5828/6914/13503 5829/6915/13505 5831/7305/13948 +f 7807/7583/14407 7831/7223/14954 7808/6302/12923 +f 7420/6234/12863 7512/5887/12554 7417/6232/12861 +f 7008/7778/14679 7007/7906/14830 7005/7768/14668 +f 6881/7536/14635 6884/6434/13591 6878/7748/14635 +f 7417/6232/12861 7512/5887/12554 7513/5886/12553 +f 7179/7652/14506 7315/7643/14496 7178/8015/15047 +f 7054/7825/14738 7369/7687/14541 7368/7932/14866 +f 5837/5958/12614 5836/5742/12428 5838/6370/12988 +f 7321/7699/14556 7323/7728/14604 7330/7733/14610 +f 7309/7982/14982 7391/7862/14779 7311/7668/14520 +f 7618/6147/12792 7633/6146/12791 7624/7446/14174 +f 6494/7132/13727 6492/7131/13726 6493/6591/13174 +f 6354/6632/14208 6353/6356/14269 6370/7370/14050 +f 7832/6890/12518 7848/7517/12518 7834/6725/12518 +f 7360/7627/14472 7359/7854/14770 7326/7866/14783 +f 7299/7963/14924 7342/7672/14526 7057/7671/14525 +f 7151/7909/14834 7150/7858/14774 6998/7711/14574 +f 6904/6799/12440 6902/6717/12440 6938/5995/12440 +f 7239/7915/14841 7238/7901/14825 7237/7588/14422 +f 7126/7593/14431 7124/7977/14967 7122/7601/14440 +f 5822/6371/12989 5821/6225/13947 5751/6365/12990 +f 7230/7791/14696 7249/7790/14695 7231/8010/15035 +f 6630/7371/14051 6627/7060/13653 6626/7094/13688 +f 7076/8000/15018 7138/7713/14576 7075/8003/15024 +f 7133/7770/14671 7134/7884/14806 7136/7769/14670 +f 7068/7815/14727 7135/7887/14809 7132/7885/14807 +f 7745/6548/13140 7759/7386/14079 7744/5808/12485 +f 7248/7863/14780 7242/7987/14999 7241/7864/14781 +f 7317/7606/14449 7312/7608/14451 7314/7957/14915 +f 6475/7117/13712 6459/6061/14282 6474/6143/12788 +f 7138/7713/14576 7074/7999/15017 7073/7714/14577 +f 7777/6107/12751 7778/6484/13086 7780/6653/13227 +f 7277/7842/14757 7280/7991/15009 7279/7995/15013 +f 7214/7681/14535 7231/8010/15035 7249/7790/14695 +f 7845/6007/13831 7855/7211/13830 7843/6249/14196 +f 7855/7211/14031 7883/7426/14139 7854/5799/12476 +f 6447/6335/12708 6424/6218/12708 6450/6917/12708 +f 7334/7612/14456 7158/7611/14455 7332/7961/14922 +f 7560/6823/13396 7563/6888/12847 7556/6426/12847 +f 7826/5919/12580 7829/6892/13471 7828/7309/13954 +f 7994/7570/14380 7982/5869/12690 7983/7145/13740 +f 7761/7385/14078 7762/6547/13139 7760/5775/12454 +f 6782/6285/14205 6784/6287/14997 6785/6476/13079 +f 6651/7441/14165 6646/7240/13867 6735/6057/12704 +f 7141/7994/15012 7143/7993/15011 7144/8020/15054 +f 7045/7953/14901 7039/7649/14503 7046/7804/14716 +f 7000/7956/14913 7068/7815/14727 6999/7703/14560 +f 7113/7656/14510 7033/7701/14558 7032/7657/14511 +f 7800/5988/12644 7878/7348/14018 7795/5986/12642 +f 7319/7857/14773 7184/7913/14839 7186/8012/15040 +f 7736/6394/14281 7737/6777/13346 7669/7101/13697 +f 7122/7601/14440 7005/7768/14668 7126/7593/14431 +f 7993/6039/12691 7994/7570/14380 7996/6567/13154 +f 7569/6427/14995 7571/6820/13392 7570/6819/13391 +f 6643/7115/12916 6650/6927/12916 6647/6101/12916 +f 6722/7516/14684 6721/7254/14013 6657/7347/14014 +f 7482/7462/14200 7468/7234/13860 7483/7233/13859 +f 6373/6360/12978 6355/5902/14010 6354/6632/14208 +f 6912/6369/13749 6910/5977/15032 6911/5771/15032 +f 7191/8014/15046 7305/7609/14453 7289/7708/14571 +f 6984/6664/13238 6887/7024/13612 6983/6663/13237 +f 7337/7902/14826 7333/7613/14457 7165/7646/14500 +f 7213/7640/14492 7283/7968/14952 7212/7849/14764 +f 6994/6435/13591 6993/6732/13591 6992/6433/13591 +f 7039/7649/14503 7041/7869/14786 7040/7650/14504 +f 7949/6518/13056 7953/6517/13056 7924/5883/13056 +f 7725/7266/12562 7692/6044/12562 7690/7236/12562 +f 7160/7730/14606 7325/7731/14608 7323/7728/14604 +f 6441/6181/14824 6443/6070/13104 6442/6199/13103 +f 6992/6433/13050 6878/7748/13050 6884/6434/13050 +f 7140/8004/15025 7138/7713/14576 7141/7994/15012 +f 7638/6814/13385 7639/7569/14379 7640/6038/12689 +f 6828/7201/13809 6813/6416/13032 6827/6418/13034 +f 8057/8022/15058 8424/8023/15059 8207/8024/15060 +f 8270/8025/15061 8158/8026/15062 8402/8027/15063 +f 8066/8028/15064 8096/8029/15065 8279/8030/15066 +f 8056/8031/15067 8057/8022/15058 8058/8032/15068 +f 8167/8033/15069 8048/8034/15070 8064/8035/15071 +f 8054/8036/15072 8055/8037/15073 8056/8031/15067 +f 8030/8038/15074 8031/8039/15075 8029/8040/15076 +f 8037/8041/15077 8030/8038/15074 8290/8042/15078 +f 8392/8043/15079 8368/8044/15080 8021/8045/15081 +f 8151/8046/15082 8148/8047/15083 8142/8048/15084 +f 8026/8049/15085 8024/8050/15086 8214/8051/15087 +f 8271/8052/15088 8298/8053/15089 8292/8054/15090 +f 8140/8055/15091 8320/8056/15092 8388/8057/15093 +f 8066/8028/15064 8067/8058/15094 8387/8059/15095 +f 8078/8060/15096 8075/8061/15097 8025/8062/15098 +f 8140/8055/15091 8388/8057/15093 8379/8063/15099 +f 8411/8064/15100 8383/8065/15101 8410/8066/15102 +f 8050/8067/15103 8054/8036/15072 8167/8033/15069 +f 8325/8068/15104 8278/8069/15105 8064/8035/15071 +f 8359/8070/15106 8358/8071/15107 8357/8072/15108 +f 8068/8073/15109 8023/8074/15110 8418/8075/15111 +f 8242/8076/15112 8039/8077/15113 8366/8078/15114 +f 8045/8079/15115 8362/8080/15116 8117/8081/15117 +f 8355/8082/15118 8356/8083/15119 8046/8084/15120 +f 8069/8085/15121 8021/8045/15081 8368/8044/15080 +f 8423/8086/15122 8331/8087/15123 8334/8088/15124 +f 8169/8089/15125 8175/8090/15126 8170/8091/15127 +f 8031/8039/15075 8030/8038/15074 8037/8041/15077 +f 8061/8092/15128 8063/8093/15129 8060/8094/15130 +f 8032/8095/15131 8034/8096/15132 8070/8097/15133 +f 8089/8098/15134 8087/8099/15135 8137/8100/15136 +f 8323/8101/15137 8315/8102/15138 8405/8103/15139 +f 8148/8047/15083 8149/8104/15140 8422/8105/15141 +f 8207/8024/15060 8395/8106/15142 8260/8107/15143 +f 8040/8108/15144 8319/8109/15145 8318/8110/15146 +f 8301/8111/15147 8311/8112/15148 8276/8113/15149 +f 8348/8114/15150 8260/8107/15143 8243/8115/15151 +f 8108/8116/15152 8107/8117/15153 8428/8118/15154 +f 8221/8119/15155 8128/8120/15156 8110/8121/15157 +f 8418/8075/15111 8023/8074/15110 8033/8122/15158 +f 8073/8123/15159 8090/8124/15160 8079/8125/15161 +f 8423/8086/15122 8334/8088/15124 8353/8126/15162 +f 8332/8127/15163 8423/8086/15122 8339/8128/15164 +f 8328/8129/15165 8374/8130/15166 8241/8131/15167 +f 8290/8042/15078 8161/8132/15168 8162/8133/15169 +f 8172/8134/15170 8287/8135/15171 8322/8136/15172 +f 8373/8137/15173 8103/8138/15174 8399/8139/15175 +f 8161/8132/15168 8290/8042/15078 8125/8140/15176 +f 8046/8084/15120 8023/8074/15110 8355/8082/15118 +f 8041/8141/15177 8107/8117/15153 8401/8142/15178 +f 8147/8143/15179 8142/8048/15084 8148/8047/15083 +f 8385/8144/15180 8305/8145/15181 8386/8146/15182 +f 8135/8147/15183 8073/8123/15159 8133/8148/15184 +f 8102/8149/15185 8103/8138/15174 8028/8150/15186 +f 8080/8151/15187 8082/8152/15188 8384/8153/15189 +f 8413/8154/15190 8182/8155/15191 8081/8156/15192 +f 8028/8150/15186 8322/8136/15172 8412/8157/15193 +f 8163/8158/15194 8128/8120/15156 8221/8119/15155 +f 8148/8047/15083 8352/8159/15195 8351/8160/15196 +f 8034/8096/15132 8033/8122/15158 8035/8161/15197 +f 8021/8045/15081 8020/8162/15198 8039/8077/15113 +f 8153/8163/15199 8175/8090/15126 8169/8089/15125 +f 8307/8164/15200 8077/8165/15201 8306/8166/15202 +f 8273/8167/15203 8275/8168/15204 8427/8169/15205 +f 8382/8170/15206 8300/8171/15207 8301/8111/15147 +f 8138/8172/15208 8021/8045/15081 8069/8085/15121 +f 8065/8173/15209 8060/8094/15130 8305/8145/15181 +f 8182/8155/15191 8347/8174/15210 8098/8175/15211 +f 8154/8176/15212 8183/8177/15213 8160/8178/15214 +f 8094/8179/15215 8328/8129/15165 8241/8131/15167 +f 8122/8180/15216 8179/8181/15217 8113/8182/15218 +f 8269/8183/15219 8074/8184/15220 8276/8113/15149 +f 8409/8185/15221 8389/8186/15222 8049/8187/15223 +f 8027/8188/15224 8271/8052/15088 8274/8189/15225 +f 8365/8190/15226 8350/8191/15227 8103/8138/15174 +f 8271/8052/15088 8273/8167/15203 8274/8189/15225 +f 8306/8166/15202 8286/8192/15228 8307/8164/15200 +f 8386/8146/15182 8171/8193/15229 8038/8194/15230 +f 8286/8192/15228 8308/8195/15231 8307/8164/15200 +f 8167/8033/15069 8168/8196/15232 8086/8197/15233 +f 8203/8198/15234 8211/8199/15235 8208/8200/15236 +f 8312/8201/15237 8191/8202/15238 8071/8203/15239 +f 8357/8072/15108 8358/8071/15107 8310/8204/15240 +f 8270/8025/15061 8402/8027/15063 8321/8205/15241 +f 8111/8206/15242 8153/8163/15199 8169/8089/15125 +f 8224/8207/15243 8065/8173/15209 8305/8145/15181 +f 8289/8208/15244 8294/8209/15245 8430/8210/15246 +f 8081/8156/15192 8073/8123/15159 8079/8125/15161 +f 8326/8211/15247 8040/8108/15144 8327/8212/15248 +f 8199/8213/15249 8202/8214/15250 8181/8215/15251 +f 8065/8173/15209 8195/8216/15252 8293/8217/15253 +f 8419/8218/15254 8049/8187/15223 8303/8219/15255 +f 8217/8220/15256 8140/8055/15091 8379/8063/15099 +f 8327/8212/15248 8040/8108/15144 8330/8221/15257 +f 8097/8222/15258 8098/8175/15211 8347/8174/15210 +f 8142/8048/15084 8145/8223/15259 8141/8224/15260 +f 8280/8225/15261 8156/8226/15262 8155/8227/15263 +f 8020/8162/15198 8375/8228/15264 8038/8194/15230 +f 8343/8229/15265 8344/8230/15265 8391/8231/15265 +f 8224/8207/15243 8305/8145/15181 8084/8232/15266 +f 8201/8233/15267 8241/8131/15167 8067/8058/15094 +f 8374/8130/15166 8121/8234/15268 8382/8170/15206 +f 8168/8196/15232 8181/8215/15251 8086/8197/15233 +f 8270/8025/15061 8302/8235/15269 8158/8026/15062 +f 8086/8197/15233 8197/8236/15270 8380/8237/15271 +f 8336/8238/15272 8267/8239/15273 8266/8240/15274 +f 8134/8241/15275 8133/8148/15184 8268/8242/15276 +f 8228/8243/15277 8058/8032/15068 8348/8114/15150 +f 8121/8234/15268 8374/8130/15166 8328/8129/15165 +f 8376/8244/15278 8375/8228/15264 8312/8201/15237 +f 8251/8245/15279 8243/8115/15151 8252/8246/15280 +f 8137/8100/15136 8091/8247/15281 8135/8147/15183 +f 8250/8248/15282 8243/8115/15151 8251/8245/15279 +f 8328/8129/15165 8094/8179/15215 8095/8249/15283 +f 8112/8250/15284 8244/8251/15285 8254/8252/15286 +f 8202/8214/15250 8204/8253/15287 8181/8215/15251 +f 8260/8107/15143 8258/8254/15288 8261/8255/15289 +f 8215/8256/15290 8140/8055/15091 8216/8257/15291 +f 8051/8258/15292 8184/8259/15293 8190/8260/15294 +f 8174/8261/15295 8178/8262/15296 8175/8090/15126 +f 8214/8051/15087 8092/8263/15297 8178/8262/15296 +f 8177/8264/15298 8189/8265/15299 8060/8094/15130 +f 8130/8266/15300 8239/8267/15301 8238/8268/15302 +f 8252/8246/15280 8243/8115/15151 8253/8269/15303 +f 8249/8270/15304 8243/8115/15151 8250/8248/15282 +f 8387/8059/15095 8382/8170/15206 8378/8271/15305 +f 8382/8170/15206 8121/8234/15268 8300/8171/15207 +f 8135/8147/15183 8142/8048/15084 8137/8100/15136 +f 8307/8164/15200 8076/8272/15306 8077/8165/15201 +f 8307/8164/15200 8188/8273/15307 8076/8272/15306 +f 8037/8041/15077 8036/8274/15308 8031/8039/15075 +f 8322/8136/15172 8173/8275/15309 8172/8134/15170 +f 8145/8223/15259 8045/8079/15115 8141/8224/15260 +f 8208/8200/15236 8211/8199/15235 8212/8276/15310 +f 8212/8276/15310 8213/8277/15311 8215/8256/15290 +f 8313/8278/15312 8085/8279/15313 8084/8232/15266 +f 8335/8280/15314 8291/8281/15315 8408/8282/15316 +f 8423/8086/15122 8199/8213/15249 8181/8215/15251 +f 8378/8271/15305 8098/8175/15211 8099/8283/15317 +f 8260/8107/15143 8261/8255/15289 8243/8115/15151 +f 8029/8040/15076 8026/8049/15085 8178/8262/15296 +f 8185/8284/15318 8187/8285/15319 8055/8037/15073 +f 8044/8286/15320 8045/8079/15115 8417/8287/15321 +f 8245/8288/15322 8243/8115/15151 8246/8289/15323 +f 8086/8197/15233 8205/8290/15324 8203/8198/15234 +f 8333/8291/15325 8323/8101/15137 8411/8064/15100 +f 8186/8292/15326 8051/8258/15292 8190/8260/15294 +f 8127/8293/15327 8128/8120/15156 8164/8294/15328 +f 8078/8060/15096 8191/8202/15238 8196/8295/15329 +f 8087/8099/15135 8138/8172/15208 8137/8100/15136 +f 8028/8150/15186 8416/8296/15330 8432/8297/15331 +f 8110/8121/15157 8193/8298/15332 8156/8226/15262 +f 8282/8299/15333 8153/8163/15199 8043/8300/15334 +f 8124/8301/15335 8273/8167/15203 8118/8302/15336 +f 8123/8303/15337 8124/8301/15335 8367/8304/15338 +f 8113/8182/15218 8324/8305/15339 8120/8306/15340 +f 8148/8047/15083 8152/8307/15341 8150/8308/15342 +f 8205/8290/15324 8086/8197/15233 8210/8309/15343 +f 8072/8310/15344 8270/8025/15061 8268/8242/15276 +f 8385/8144/15180 8038/8194/15230 8375/8228/15264 +f 8143/8311/15345 8140/8055/15091 8144/8312/15346 +f 8139/8313/15347 8143/8311/15345 8142/8048/15084 +f 8230/8314/15348 8194/8315/15349 8046/8084/15120 +f 8302/8235/15269 8115/8316/15350 8116/8317/15351 +f 8147/8143/15179 8148/8047/15083 8351/8160/15196 +f 8424/8023/15059 8057/8022/15058 8420/8318/15352 +f 8381/8319/15353 8242/8076/15112 8296/8320/15354 +f 8140/8055/15091 8143/8311/15345 8139/8313/15347 +f 8347/8174/15210 8413/8154/15190 8097/8222/15258 +f 8062/8321/15355 8039/8077/15113 8171/8193/15229 +f 8049/8187/15223 8393/8322/15356 8390/8323/15357 +f 8357/8072/15108 8310/8204/15240 8309/8324/15358 +f 8225/8325/15359 8094/8179/15215 8226/8326/15360 +f 8021/8045/15081 8381/8319/15353 8392/8043/15079 +f 8277/8327/15361 8271/8052/15088 8272/8328/15362 +f 8369/8329/15363 8037/8041/15077 8404/8330/15364 +f 8059/8331/15365 8354/8332/15366 8335/8280/15314 +f 8236/8333/15367 8220/8334/15368 8237/8335/15369 +f 8237/8335/15369 8223/8336/15370 8187/8285/15319 +f 8024/8050/15086 8188/8273/15307 8308/8195/15231 +f 8307/8164/15200 8308/8195/15231 8188/8273/15307 +f 8244/8251/15285 8243/8115/15151 8245/8288/15322 +f 8255/8337/15371 8244/8251/15285 8112/8250/15284 +f 8072/8310/15344 8268/8242/15276 8133/8148/15184 +f 8337/8338/15372 8309/8324/15358 8281/8339/15373 +f 8078/8060/15096 8071/8203/15239 8191/8202/15238 +f 8342/8340/15374 8036/8274/15308 8344/8230/15375 +f 8051/8258/15292 8185/8284/15318 8055/8037/15073 +f 8204/8253/15287 8210/8309/15343 8086/8197/15233 +f 8262/8341/15376 8258/8254/15288 8259/8342/15377 +f 8067/8058/15094 8279/8030/15066 8201/8233/15267 +f 8299/8343/15378 8285/8344/15379 8156/8226/15262 +f 8284/8345/15380 8403/8346/15381 8325/8068/15104 +f 8285/8344/15379 8325/8068/15104 8156/8226/15262 +f 8320/8056/15092 8321/8205/15241 8231/8347/15382 +f 8243/8115/15151 8286/8192/15228 8400/8348/15383 +f 8086/8197/15233 8198/8349/15384 8197/8236/15270 +f 8273/8167/15203 8271/8052/15088 8275/8168/15204 +f 8093/8350/15385 8092/8263/15297 8214/8051/15087 +f 8358/8071/15107 8360/8351/15386 8361/8352/15387 +f 8160/8178/15388 8183/8177/15389 8159/8353/15390 +f 8059/8331/15365 8222/8354/15391 8354/8332/15366 +f 8133/8148/15184 8073/8123/15159 8072/8310/15344 +f 8140/8055/15091 8139/8313/15347 8134/8241/15275 +f 8052/8355/15392 8392/8043/15079 8396/8356/15393 +f 8177/8264/15298 8065/8173/15209 8176/8357/15394 +f 8065/8173/15209 8293/8217/15253 8176/8357/15394 +f 8154/8176/15212 8112/8250/15284 8254/8252/15286 +f 8223/8336/15370 8237/8335/15369 8219/8358/15395 +f 8046/8084/15120 8194/8315/15349 8195/8216/15252 +f 8338/8359/15396 8281/8339/15373 8267/8239/15273 +f 8216/8257/15291 8140/8055/15091 8217/8220/15256 +f 8135/8147/15183 8091/8247/15281 8073/8123/15159 +f 8153/8163/15199 8154/8176/15212 8160/8178/15214 +f 8223/8336/15370 8165/8360/15397 8055/8037/15073 +f 8198/8349/15384 8203/8198/15234 8206/8361/15398 +f 8371/8362/15399 8156/8226/15262 8363/8363/15400 +f 8187/8285/15319 8223/8336/15370 8055/8037/15073 +f 8069/8085/15121 8091/8247/15281 8137/8100/15136 +f 8270/8025/15061 8072/8310/15344 8269/8183/15219 +f 8343/8229/15401 8342/8340/15374 8344/8230/15375 +f 8180/8364/15402 8282/8299/15333 8329/8365/15403 +f 8170/8091/15127 8092/8263/15297 8169/8089/15404 +f 8207/8024/15060 8424/8023/15059 8395/8106/15142 +f 8142/8048/15084 8141/8224/15260 8089/8098/15134 +f 8111/8206/15242 8092/8263/15297 8255/8337/15371 +f 8278/8069/15105 8325/8068/15104 8130/8266/15300 +f 8214/8051/15087 8024/8050/15086 8308/8195/15231 +f 8072/8310/15344 8074/8184/15220 8269/8183/15219 +f 8204/8253/15287 8086/8197/15233 8181/8215/15251 +f 8170/8091/15127 8178/8262/15296 8092/8263/15297 +f 8174/8261/15405 8029/8040/15405 8178/8262/15405 +f 8243/8115/15151 8244/8251/15285 8255/8337/15371 +f 8259/8342/15377 8258/8254/15288 8260/8107/15143 +f 8125/8140/15176 8180/8364/15402 8042/8366/15406 +f 8180/8364/15402 8329/8365/15403 8042/8366/15406 +f 8304/8367/15407 8171/8193/15229 8386/8146/15182 +f 8107/8117/15153 8263/8368/15408 8262/8341/15376 +f 8274/8189/15225 8273/8167/15203 8124/8301/15335 +f 8337/8338/15372 8281/8339/15373 8338/8359/15396 +f 8417/8287/15321 8045/8079/15115 8426/8369/15409 +f 8237/8335/15369 8220/8334/15368 8219/8358/15395 +f 8257/8370/15410 8254/8252/15286 8283/8371/15411 +f 8043/8300/15412 8159/8353/15412 8042/8366/15412 +f 8125/8140/15413 8042/8366/15413 8159/8353/15413 +f 8269/8183/15219 8115/8316/15350 8302/8235/15269 +f 8183/8177/15414 8254/8252/15286 8257/8370/15410 +f 8183/8177/15415 8154/8176/15415 8254/8252/15415 +f 8206/8361/15398 8203/8198/15234 8208/8200/15236 +f 8302/8235/15269 8116/8317/15351 8158/8026/15062 +f 8374/8130/15166 8387/8059/15095 8067/8058/15094 +f 8084/8232/15266 8385/8144/15180 8376/8244/15278 +f 8367/8304/15338 8121/8234/15268 8209/8372/15416 +f 8180/8364/15402 8290/8042/15078 8340/8373/15417 +f 8246/8289/15323 8243/8115/15151 8247/8374/15418 +f 8260/8107/15143 8421/8375/15419 8259/8342/15377 +f 8402/8027/15063 8049/8187/15223 8321/8205/15241 +f 8094/8179/15215 8240/8376/15420 8226/8326/15360 +f 8120/8306/15340 8324/8305/15339 8300/8171/15207 +f 8090/8124/15160 8091/8247/15281 8053/8377/15421 +f 8068/8073/15109 8342/8340/15374 8341/8378/15422 +f 8312/8201/15237 8088/8379/15423 8191/8202/15238 +f 8053/8377/15421 8052/8355/15392 8090/8124/15160 +f 8321/8205/15241 8320/8056/15092 8140/8055/15091 +f 8121/8234/15268 8120/8306/15340 8300/8171/15207 +f 8330/8221/15257 8040/8108/15144 8294/8209/15245 +f 8323/8101/15137 8333/8291/15325 8315/8102/15138 +f 8025/8062/15098 8024/8050/15086 8026/8049/15085 +f 8060/8094/15130 8304/8367/15407 8305/8145/15181 +f 8311/8112/15148 8115/8316/15350 8269/8183/15219 +f 8301/8111/15147 8324/8305/15339 8311/8112/15148 +f 8393/8322/15356 8086/8197/15233 8380/8237/15271 +f 8278/8069/15105 8184/8259/15293 8050/8067/15103 +f 8385/8144/15180 8375/8228/15264 8376/8244/15278 +f 8035/8161/15197 8033/8122/15158 8023/8074/15110 +f 8305/8145/15181 8304/8367/15407 8386/8146/15182 +f 8306/8166/15202 8323/8101/15137 8228/8243/15277 +f 8046/8084/15120 8065/8173/15209 8224/8207/15243 +f 8247/8374/15418 8243/8115/15151 8248/8380/15424 +f 8115/8316/15350 8311/8112/15148 8114/8381/15425 +f 8119/8382/15426 8179/8181/15217 8122/8180/15216 +f 8091/8247/15281 8090/8124/15160 8073/8123/15159 +f 8370/8383/15427 8103/8138/15174 8373/8137/15173 +f 8361/8352/15387 8131/8384/15428 8358/8071/15107 +f 8097/8222/15258 8413/8154/15190 8384/8153/15189 +f 8256/8385/15429 8372/8386/15430 8159/8353/15431 +f 8167/8033/15069 8086/8197/15233 8048/8034/15070 +f 8057/8022/15058 8056/8031/15067 8059/8331/15365 +f 8317/8387/15432 8132/8388/15433 8345/8389/15434 +f 8071/8203/15239 8070/8097/15133 8085/8279/15313 +f 8325/8068/15104 8064/8035/15071 8156/8226/15262 +f 8392/8043/15079 8052/8355/15392 8053/8377/15421 +f 8184/8259/15293 8265/8390/15435 8190/8260/15294 +f 8316/8391/15436 8037/8041/15077 8132/8388/15433 +f 8383/8065/15101 8077/8165/15201 8196/8295/15329 +f 8179/8181/15217 8221/8119/15155 8157/8392/15437 +f 8086/8197/15233 8049/8187/15223 8048/8034/15070 +f 8076/8272/15306 8075/8061/15097 8077/8165/15201 +f 8222/8354/15391 8055/8037/15073 8166/8393/15438 +f 8428/8118/15154 8107/8117/15153 8262/8341/15376 +f 8095/8249/15283 8209/8372/15416 8328/8129/15165 +f 8118/8302/15336 8120/8306/15340 8121/8234/15268 +f 8389/8186/15222 8231/8347/15382 8049/8187/15223 +f 8109/8394/15439 8110/8121/15157 8128/8120/15156 +f 8170/8091/15127 8175/8090/15126 8178/8262/15296 +f 8240/8376/15420 8201/8233/15267 8200/8395/15440 +f 8382/8170/15206 8387/8059/15095 8374/8130/15166 +f 8143/8311/15345 8146/8396/15441 8142/8048/15084 +f 8181/8215/15251 8405/8103/15139 8423/8086/15122 +f 8032/8095/15131 8033/8122/15158 8034/8096/15132 +f 8387/8059/15095 8099/8283/15317 8066/8028/15064 +f 8052/8355/15392 8396/8356/15393 8082/8152/15188 +f 8024/8050/15086 8025/8062/15098 8075/8061/15097 +f 8348/8114/15150 8243/8115/15151 8400/8348/15383 +f 8087/8099/15135 8021/8045/15081 8138/8172/15208 +f 8083/8397/15442 8023/8074/15110 8022/8398/15443 +f 8128/8120/15156 8127/8293/15327 8129/8399/15444 +f 8181/8215/15251 8058/8032/15068 8228/8243/15277 +f 8020/8162/15198 8038/8194/15230 8039/8077/15113 +f 8314/8400/15445 8405/8103/15139 8315/8102/15138 +f 8028/8150/15186 8103/8138/15174 8027/8188/15224 +f 8276/8113/15149 8098/8175/15211 8378/8271/15305 +f 8236/8333/15367 8266/8240/15274 8220/8334/15368 +f 8410/8066/15102 8383/8065/15101 8045/8079/15115 +f 8269/8183/15219 8276/8113/15149 8311/8112/15148 +f 8376/8244/15278 8312/8201/15237 8313/8278/15312 +f 8032/8095/15131 8031/8039/15075 8033/8122/15158 +f 8073/8123/15159 8081/8156/15192 8074/8184/15220 +f 8110/8121/15157 8064/8035/15071 8048/8034/15070 +f 8112/8250/15284 8111/8206/15242 8255/8337/15371 +f 8059/8331/15365 8056/8031/15067 8055/8037/15073 +f 8062/8321/15355 8060/8094/15130 8063/8093/15129 +f 8341/8378/15422 8342/8340/15374 8343/8229/15401 +f 8378/8271/15305 8382/8170/15206 8301/8111/15147 +f 8404/8330/15364 8037/8041/15077 8316/8391/15436 +f 8055/8037/15073 8222/8354/15391 8059/8331/15365 +f 8213/8277/15311 8140/8055/15091 8215/8256/15290 +f 8182/8155/15191 8276/8113/15149 8074/8184/15220 +f 8093/8350/15385 8308/8195/15231 8286/8192/15228 +f 8049/8187/15223 8231/8347/15382 8321/8205/15241 +f 8340/8373/15417 8282/8299/15333 8180/8364/15402 +f 8335/8280/15314 8289/8208/15244 8288/8401/15446 +f 8363/8363/15400 8229/8402/15447 8364/8403/15448 +f 8123/8303/15337 8209/8372/15416 8095/8249/15283 +f 8053/8377/15421 8091/8247/15281 8069/8085/15121 +f 8059/8331/15365 8408/8282/15316 8420/8318/15352 +f 8103/8138/15174 8350/8191/15227 8027/8188/15224 +f 8071/8203/15239 8078/8060/15096 8070/8097/15133 +f 8073/8123/15159 8074/8184/15220 8072/8310/15344 +f 8126/8404/15449 8125/8140/15176 8159/8353/15431 +f 8166/8393/15438 8055/8037/15073 8165/8360/15397 +f 8075/8061/15097 8076/8272/15306 8188/8273/15307 +f 8052/8355/15392 8080/8151/15187 8079/8125/15161 +f 8084/8232/15266 8083/8397/15442 8022/8398/15443 +f 8085/8279/15313 8083/8397/15442 8084/8232/15266 +f 8294/8209/15245 8289/8208/15244 8335/8280/15314 +f 8322/8136/15172 8028/8150/15186 8095/8249/15283 +f 8052/8355/15392 8079/8125/15161 8090/8124/15160 +f 8186/8292/15326 8185/8284/15318 8051/8258/15292 +f 8158/8026/15062 8049/8187/15223 8402/8027/15063 +f 8064/8035/15071 8050/8067/15103 8167/8033/15069 +f 8043/8300/15334 8153/8163/15199 8160/8178/15214 +f 8022/8398/15443 8023/8074/15110 8224/8207/15243 +f 8224/8207/15243 8084/8232/15266 8022/8398/15443 +f 8025/8062/15098 8026/8049/15085 8032/8095/15131 +f 8221/8119/15155 8110/8121/15157 8157/8392/15437 +f 8228/8243/15277 8400/8348/15383 8306/8166/15202 +f 8367/8304/15338 8209/8372/15416 8123/8303/15337 +f 8145/8223/15259 8142/8048/15084 8147/8143/15179 +f 8032/8095/15131 8070/8097/15133 8025/8062/15098 +f 8130/8266/15300 8238/8268/15302 8233/8405/15450 +f 8036/8274/15308 8037/8041/15077 8369/8329/15363 +f 8260/8107/15143 8395/8106/15142 8421/8375/15419 +f 8047/8406/15451 8023/8074/15110 8068/8073/15109 +f 8098/8175/15211 8276/8113/15149 8182/8155/15191 +f 8189/8265/15299 8061/8092/15128 8060/8094/15130 +f 8058/8032/15068 8057/8022/15058 8207/8024/15060 +f 8256/8385/15429 8159/8353/15431 8183/8177/15414 +f 8087/8099/15135 8088/8379/15423 8020/8162/15198 +f 8101/8407/15452 8100/8408/15453 8102/8149/15185 +f 8093/8350/15385 8255/8337/15371 8092/8263/15297 +f 8375/8228/15264 8088/8379/15423 8312/8201/15237 +f 8184/8259/15293 8232/8409/15454 8265/8390/15435 +f 8033/8122/15158 8031/8039/15075 8036/8274/15308 +f 8211/8199/15235 8213/8277/15311 8212/8276/15310 +f 8248/8380/15424 8243/8115/15151 8249/8270/15304 +f 8068/8073/15109 8418/8075/15111 8342/8340/15374 +f 8043/8300/15334 8329/8365/15403 8282/8299/15333 +f 8401/8142/15178 8107/8117/15153 8398/8410/15455 +f 8077/8165/15201 8078/8060/15096 8196/8295/15329 +f 8099/8283/15317 8097/8222/15258 8066/8028/15064 +f 8106/8411/15456 8101/8407/15452 8406/8412/15457 +f 8086/8197/15233 8203/8198/15234 8198/8349/15384 +f 8228/8243/15277 8405/8103/15139 8181/8215/15251 +f 8060/8094/15130 8065/8173/15209 8177/8264/15298 +f 8115/8316/15350 8113/8182/15218 8116/8317/15351 +f 8365/8190/15226 8103/8138/15174 8370/8383/15427 +f 8407/8413/15458 8103/8138/15174 8346/8414/15459 +f 8160/8178/15388 8159/8353/15390 8043/8300/15460 +f 8078/8060/15096 8077/8165/15201 8075/8061/15097 +f 8175/8090/15126 8153/8163/15199 8282/8299/15333 +f 8113/8182/15218 8114/8381/15425 8324/8305/15339 +f 8336/8238/15272 8266/8240/15274 8236/8333/15367 +f 8074/8184/15220 8081/8156/15192 8182/8155/15191 +f 8148/8047/15083 8150/8308/15342 8149/8104/15140 +f 8423/8086/15122 8353/8126/15162 8422/8105/15141 +f 8339/8128/15164 8423/8086/15122 8405/8103/15139 +f 8353/8126/15162 8352/8159/15195 8422/8105/15141 +f 8405/8103/15139 8228/8243/15277 8323/8101/15137 +f 8339/8128/15164 8405/8103/15139 8314/8400/15445 +f 8422/8105/15141 8352/8159/15195 8148/8047/15083 +f 8383/8065/15101 8411/8064/15100 8323/8101/15137 +f 8191/8202/15238 8192/8415/15461 8196/8295/15329 +f 8181/8215/15251 8054/8036/15072 8056/8031/15067 +f 8297/8416/15462 8027/8188/15224 8350/8191/15227 +f 8134/8241/15275 8321/8205/15241 8140/8055/15091 +f 8234/8417/15463 8103/8138/15174 8235/8418/15464 +f 8254/8252/15286 8244/8251/15285 8283/8371/15411 +f 8268/8242/15276 8321/8205/15241 8134/8241/15275 +f 8263/8368/15408 8258/8254/15288 8262/8341/15376 +f 8261/8255/15289 8264/8419/15465 8243/8115/15151 +f 8119/8382/15426 8122/8180/15216 8118/8302/15336 +f 8133/8148/15184 8134/8241/15275 8135/8147/15183 +f 8120/8306/15340 8118/8302/15336 8122/8180/15216 +f 8130/8266/15300 8325/8068/15104 8403/8346/15381 +f 8182/8155/15191 8413/8154/15190 8347/8174/15210 +f 8023/8074/15110 8083/8397/15442 8035/8161/15197 +f 8313/8278/15312 8084/8232/15266 8376/8244/15278 +f 8338/8359/15396 8267/8239/15273 8336/8238/15272 +f 8141/8224/15260 8088/8379/15423 8089/8098/15134 +f 8363/8363/15400 8156/8226/15262 8193/8298/15332 +f 8144/8312/15346 8140/8055/15091 8227/8420/15466 +f 8053/8377/15421 8069/8085/15121 8368/8044/15080 +f 8110/8121/15157 8156/8226/15262 8064/8035/15071 +f 8164/8294/15328 8128/8120/15156 8163/8158/15194 +f 8239/8267/15301 8130/8266/15300 8131/8384/15428 +f 8196/8295/15329 8192/8415/15461 8383/8065/15101 +f 8050/8067/15103 8064/8035/15071 8278/8069/15105 +f 8114/8381/15425 8113/8182/15218 8115/8316/15350 +f 8126/8404/15449 8161/8132/15168 8125/8140/15176 +f 8364/8403/15448 8229/8402/15447 8429/8421/15467 +f 8029/8040/15076 8031/8039/15075 8032/8095/15131 +f 8122/8180/15216 8113/8182/15218 8120/8306/15340 +f 8397/8422/15468 8431/8423/15469 8040/8108/15144 +f 8088/8379/15423 8141/8224/15260 8192/8415/15461 +f 8412/8157/15193 8322/8136/15172 8287/8135/15171 +f 8270/8025/15061 8269/8183/15219 8302/8235/15269 +f 8273/8167/15203 8119/8382/15426 8118/8302/15336 +f 8301/8111/15147 8276/8113/15149 8378/8271/15305 +f 8335/8280/15314 8408/8282/15316 8059/8331/15365 +f 8306/8166/15202 8077/8165/15201 8383/8065/15101 +f 8175/8090/15126 8029/8040/15076 8174/8261/15295 +f 8058/8032/15068 8181/8215/15251 8056/8031/15067 +f 8028/8150/15186 8027/8188/15224 8123/8303/15337 +f 8135/8147/15183 8134/8241/15275 8139/8313/15347 +f 8028/8150/15186 8432/8297/15331 8102/8149/15185 +f 8051/8258/15292 8055/8037/15073 8054/8036/15072 +f 8349/8424/15470 8309/8324/15358 8337/8338/15372 +f 8344/8230/15375 8036/8274/15308 8394/8425/15471 +f 8069/8085/15121 8137/8100/15136 8138/8172/15208 +f 8148/8047/15083 8151/8046/15082 8152/8307/15341 +f 8116/8317/15351 8157/8392/15437 8158/8026/15062 +f 8153/8163/15199 8111/8206/15242 8154/8176/15212 +f 8155/8227/15263 8156/8226/15262 8371/8362/15399 +f 8427/8169/15205 8221/8119/15155 8273/8167/15203 +f 8282/8299/15333 8340/8373/15417 8175/8090/15126 +f 8224/8207/15243 8023/8074/15110 8046/8084/15120 +f 8048/8034/15070 8157/8392/15437 8110/8121/15157 +f 8096/8029/15065 8066/8028/15064 8097/8222/15258 +f 8111/8206/15242 8112/8250/15284 8154/8176/15212 +f 8369/8329/15363 8404/8330/15364 8377/8426/15472 +f 8124/8301/15335 8118/8302/15336 8367/8304/15338 +f 8039/8077/15113 8242/8076/15112 8021/8045/15081 +f 8169/8089/15125 8092/8263/15473 8111/8206/15242 +f 8100/8408/15453 8103/8138/15174 8102/8149/15185 +f 8270/8025/15061 8321/8205/15241 8268/8242/15276 +f 8325/8068/15104 8285/8344/15379 8284/8345/15380 +f 8088/8379/15423 8375/8228/15264 8020/8162/15198 +f 8045/8079/15115 8117/8081/15117 8410/8066/15102 +f 8162/8133/15169 8161/8132/15168 8136/8427/15474 +f 8425/8428/15475 8023/8074/15110 8415/8429/15476 +f 8240/8376/15420 8241/8131/15167 8201/8233/15267 +f 8116/8317/15351 8113/8182/15218 8179/8181/15217 +f 8298/8053/15089 8027/8188/15224 8297/8416/15462 +f 8272/8328/15362 8271/8052/15088 8292/8054/15090 +f 8128/8120/15156 8129/8399/15444 8109/8394/15439 +f 8181/8215/15251 8168/8196/15232 8054/8036/15072 +f 8358/8071/15107 8040/8108/15144 8310/8204/15240 +f 8024/8050/15086 8075/8061/15097 8188/8273/15307 +f 8324/8305/15339 8301/8111/15147 8300/8171/15207 +f 8043/8300/15477 8042/8366/15477 8329/8365/15477 +f 8279/8030/15066 8067/8058/15094 8066/8028/15064 +f 8027/8188/15224 8124/8301/15335 8123/8303/15337 +f 8192/8415/15461 8191/8202/15238 8088/8379/15423 +f 8137/8100/15136 8142/8048/15084 8089/8098/15134 +f 8273/8167/15203 8221/8119/15155 8119/8382/15426 +f 8218/8430/15478 8140/8055/15091 8213/8277/15311 +f 8085/8279/15313 8313/8278/15312 8071/8203/15239 +f 8050/8067/15103 8051/8258/15292 8054/8036/15072 +f 8416/8296/15330 8028/8150/15186 8412/8157/15193 +f 8414/8431/15479 8039/8077/15113 8062/8321/15355 +f 8167/8033/15069 8054/8036/15072 8168/8196/15232 +f 8397/8422/15468 8040/8108/15144 8041/8141/15177 +f 8105/8432/15480 8101/8407/15452 8106/8411/15456 +f 8340/8373/15417 8029/8040/15076 8175/8090/15126 +f 8067/8058/15094 8241/8131/15167 8374/8130/15166 +f 8177/8264/15298 8176/8357/15394 8189/8265/15299 +f 8214/8051/15087 8178/8262/15296 8026/8049/15085 +f 8253/8269/15303 8243/8115/15151 8264/8419/15465 +f 8303/8219/15255 8049/8187/15223 8390/8323/15357 +f 8107/8117/15153 8041/8141/15177 8040/8108/15144 +f 8039/8077/15113 8038/8194/15230 8171/8193/15229 +f 8275/8168/15204 8271/8052/15088 8277/8327/15361 +f 8099/8283/15317 8098/8175/15211 8097/8222/15258 +f 8045/8079/15115 8383/8065/15101 8192/8415/15461 +f 8386/8146/15182 8038/8194/15230 8385/8144/15180 +f 8130/8266/15300 8233/8405/15450 8184/8259/15293 +f 8020/8162/15198 8021/8045/15081 8087/8099/15135 +f 8286/8192/15228 8255/8337/15371 8093/8350/15385 +f 8316/8391/15436 8132/8388/15433 8317/8387/15432 +f 8193/8298/15332 8110/8121/15157 8109/8394/15439 +f 8260/8107/15143 8348/8114/15150 8207/8024/15060 +f 8078/8060/15096 8025/8062/15098 8070/8097/15133 +f 8081/8156/15192 8080/8151/15187 8413/8154/15190 +f 8027/8188/15224 8298/8053/15089 8271/8052/15088 +f 8104/8433/15481 8101/8407/15452 8105/8432/15480 +f 8225/8325/15359 8095/8249/15283 8094/8179/15215 +f 8146/8396/15441 8151/8046/15082 8142/8048/15084 +f 8195/8216/15252 8065/8173/15209 8046/8084/15120 +f 8214/8051/15087 8308/8195/15231 8093/8350/15385 +f 8140/8055/15091 8218/8430/15478 8227/8420/15466 +f 8286/8192/15228 8306/8166/15202 8400/8348/15383 +f 8357/8072/15108 8309/8324/15358 8349/8424/15470 +f 8221/8119/15155 8179/8181/15217 8119/8382/15426 +f 8183/8177/15414 8257/8370/15410 8256/8385/15429 +f 8193/8298/15332 8229/8402/15447 8363/8363/15400 +f 8082/8152/15188 8080/8151/15187 8052/8355/15392 +f 8311/8112/15148 8324/8305/15339 8114/8381/15425 +f 8095/8249/15283 8028/8150/15186 8123/8303/15337 +f 8034/8096/15132 8035/8161/15197 8083/8397/15442 +f 8312/8201/15237 8071/8203/15239 8313/8278/15312 +f 8340/8373/15417 8290/8042/15078 8030/8038/15074 +f 8192/8415/15461 8141/8224/15260 8045/8079/15115 +f 8184/8259/15293 8278/8069/15105 8130/8266/15300 +f 8372/8386/15430 8126/8404/15449 8159/8353/15431 +f 8305/8145/15181 8385/8144/15180 8084/8232/15266 +f 8034/8096/15132 8085/8279/15313 8070/8097/15133 +f 8207/8024/15060 8348/8114/15150 8058/8032/15068 +f 8398/8410/15455 8107/8117/15153 8108/8116/15152 +f 8036/8274/15308 8342/8340/15374 8418/8075/15111 +f 8156/8226/15262 8280/8225/15261 8299/8343/15378 +f 8290/8042/15078 8162/8133/15169 8037/8041/15077 +f 8051/8258/15292 8050/8067/15103 8184/8259/15293 +f 8060/8094/15130 8062/8321/15355 8304/8367/15407 +f 8033/8122/15158 8036/8274/15308 8418/8075/15111 +f 8125/8140/15176 8290/8042/15078 8180/8364/15402 +f 8095/8249/15283 8225/8325/15359 8322/8136/15172 +f 8304/8367/15407 8062/8321/15355 8171/8193/15229 +f 8295/8434/15482 8381/8319/15353 8296/8320/15354 +f 8319/8109/15145 8040/8108/15144 8326/8211/15247 +f 8139/8313/15347 8142/8048/15084 8135/8147/15183 +f 8366/8078/15114 8039/8077/15113 8414/8431/15479 +f 8179/8181/15217 8157/8392/15437 8116/8317/15351 +f 8241/8131/15167 8240/8376/15420 8094/8179/15215 +f 8200/8395/15440 8201/8233/15267 8279/8030/15066 +f 8049/8187/15223 8419/8218/15254 8409/8185/15221 +f 8310/8204/15240 8040/8108/15144 8318/8110/15146 +f 8360/8351/15386 8358/8071/15107 8359/8070/15106 +f 8414/8431/15479 8062/8321/15355 8063/8093/15129 +f 8046/8084/15120 8356/8083/15119 8230/8314/15348 +f 8255/8337/15371 8286/8192/15228 8243/8115/15151 +f 8392/8043/15079 8381/8319/15353 8295/8434/15482 +f 8415/8429/15476 8023/8074/15110 8047/8406/15451 +f 8383/8065/15101 8323/8101/15137 8306/8166/15202 +f 8163/8158/15194 8221/8119/15155 8427/8169/15205 +f 8032/8095/15131 8026/8049/15085 8029/8040/15076 +f 8132/8388/15433 8037/8041/15077 8136/8427/15474 +f 8086/8197/15233 8393/8322/15356 8049/8187/15223 +f 8355/8082/15118 8023/8074/15110 8425/8428/15475 +f 8228/8243/15277 8348/8114/15150 8400/8348/15383 +f 8079/8125/15161 8080/8151/15187 8081/8156/15192 +f 8083/8397/15442 8085/8279/15313 8034/8096/15132 +f 8387/8059/15095 8378/8271/15305 8099/8283/15317 +f 8088/8379/15423 8087/8099/15135 8089/8098/15134 +f 8225/8325/15359 8173/8275/15309 8322/8136/15172 +f 8059/8331/15365 8420/8318/15352 8057/8022/15058 +f 8158/8026/15062 8157/8392/15437 8048/8034/15070 +f 8430/8210/15246 8294/8209/15245 8431/8423/15469 +f 8346/8414/15459 8103/8138/15174 8234/8417/15463 +f 8274/8189/15225 8124/8301/15335 8027/8188/15224 +f 8121/8234/15268 8367/8304/15338 8118/8302/15336 +f 8335/8280/15314 8288/8401/15446 8291/8281/15315 +f 8030/8038/15074 8029/8040/15076 8340/8373/15417 +f 8103/8138/15174 8407/8413/15458 8399/8139/15175 +f 8184/8259/15293 8233/8405/15450 8232/8409/15454 +f 8040/8108/15144 8431/8423/15469 8294/8209/15245 +f 8368/8044/15080 8392/8043/15079 8053/8377/15421 +f 8100/8408/15453 8101/8407/15452 8104/8433/15481 +f 8426/8369/15409 8045/8079/15115 8145/8223/15259 +f 8209/8372/15416 8121/8234/15268 8328/8129/15165 +f 8423/8086/15122 8332/8127/15163 8331/8087/15123 +f 8036/8274/15308 8369/8329/15363 8394/8425/15471 +f 8048/8034/15070 8049/8187/15223 8158/8026/15062 +f 8136/8427/15474 8037/8041/15077 8162/8133/15169 +f 8381/8319/15353 8021/8045/15081 8242/8076/15112 +f 8358/8071/15107 8131/8384/15428 8130/8266/15300 +f 8045/8079/15115 8044/8286/15320 8362/8080/15116 +f 8384/8153/15189 8413/8154/15190 8080/8151/15187 +f 8235/8418/15464 8103/8138/15174 8100/8408/15453 +f 8470/8435/15483 8620/8436/15484 8837/8437/15485 +f 8683/8438/15486 8815/8439/15487 8571/8440/15488 +f 8479/8441/15489 8692/8442/15490 8509/8443/15491 +f 8469/8444/15492 8471/8445/15493 8470/8435/15483 +f 8580/8446/15494 8477/8447/15495 8461/8448/15496 +f 8467/8449/15497 8469/8444/15492 8468/8450/15498 +f 8443/8451/15499 8442/8452/15500 8444/8453/15501 +f 8450/8454/15502 8703/8455/15503 8443/8451/15499 +f 8805/8456/15504 8434/8457/15505 8781/8458/15506 +f 8564/8459/15507 8555/8460/15508 8561/8461/15509 +f 8439/8462/15510 8627/8463/15511 8437/8464/15512 +f 8684/8465/15513 8705/8466/15514 8711/8467/15515 +f 8553/8468/15516 8801/8469/15517 8733/8470/15518 +f 8479/8441/15489 8800/8471/15519 8480/8472/15520 +f 8491/8473/15521 8438/8474/15522 8488/8475/15523 +f 8553/8468/15516 8792/8476/15524 8801/8469/15517 +f 8824/8477/15525 8823/8478/15526 8796/8479/15527 +f 8463/8480/15528 8580/8446/15494 8467/8449/15497 +f 8738/8481/15529 8477/8447/15495 8691/8482/15530 +f 8772/8483/15531 8770/8484/15532 8771/8485/15533 +f 8481/8486/15534 8831/8487/15535 8436/8488/15536 +f 8655/8489/15537 8779/8490/15538 8452/8491/15539 +f 8458/8492/15540 8530/8493/15541 8775/8494/15542 +f 8768/8495/15543 8459/8496/15544 8769/8497/15545 +f 8482/8498/15546 8781/8458/15506 8434/8457/15505 +f 8836/8499/15547 8747/8500/15548 8744/8501/15549 +f 8582/8502/15550 8583/8503/15551 8588/8504/15552 +f 8444/8453/15501 8450/8454/15502 8443/8451/15499 +f 8474/8505/15553 8473/8506/15554 8476/8507/15555 +f 8445/8508/15556 8483/8509/15557 8447/8510/15558 +f 8502/8511/15559 8550/8512/15560 8500/8513/15561 +f 8736/8514/15562 8818/8515/15563 8728/8516/15564 +f 8561/8461/15509 8835/8517/15565 8562/8518/15566 +f 8620/8436/15484 8673/8519/15567 8808/8520/15568 +f 8453/8521/15569 8731/8522/15570 8732/8523/15571 +f 8714/8524/15572 8689/8525/15573 8724/8526/15574 +f 8761/8527/15575 8656/8528/15576 8673/8519/15567 +f 8521/8529/15577 8841/8530/15578 8520/8531/15579 +f 8634/8532/15580 8523/8533/15581 8541/8534/15582 +f 8831/8487/15535 8446/8535/15583 8436/8488/15536 +f 8486/8536/15584 8492/8537/15585 8503/8538/15586 +f 8836/8499/15547 8766/8539/15587 8747/8500/15548 +f 8745/8540/15588 8752/8541/15589 8836/8499/15547 +f 8741/8542/15590 8654/8543/15591 8787/8544/15592 +f 8703/8455/15503 8575/8545/15593 8574/8546/15594 +f 8585/8547/15595 8735/8548/15596 8700/8549/15597 +f 8786/8550/15598 8812/8551/15599 8516/8552/15600 +f 8574/8546/15594 8538/8553/15601 8703/8455/15503 +f 8459/8496/15544 8768/8495/15543 8436/8488/15536 +f 8454/8554/15602 8814/8555/15603 8520/8531/15579 +f 8560/8556/15604 8561/8461/15509 8555/8460/15508 +f 8798/8557/15605 8799/8558/15606 8718/8559/15607 +f 8548/8560/15608 8546/8561/15609 8486/8536/15584 +f 8515/8562/15610 8441/8563/15611 8516/8552/15600 +f 8493/8564/15612 8797/8565/15613 8495/8566/15614 +f 8826/8567/15615 8494/8568/15616 8595/8569/15617 +f 8441/8563/15611 8825/8570/15618 8735/8548/15596 +f 8576/8571/15619 8634/8532/15580 8541/8534/15582 +f 8561/8461/15509 8764/8572/15620 8765/8573/15621 +f 8447/8510/15558 8448/8574/15622 8446/8535/15583 +f 8434/8457/15505 8452/8491/15539 8433/8575/15623 +f 8566/8576/15624 8582/8502/15550 8588/8504/15552 +f 8720/8577/15625 8719/8578/15626 8490/8579/15627 +f 8686/8580/15628 8840/8581/15629 8688/8582/15630 +f 8795/8583/15631 8714/8524/15572 8713/8584/15632 +f 8551/8585/15633 8482/8498/15546 8434/8457/15505 +f 8478/8586/15634 8718/8559/15607 8473/8506/15554 +f 8595/8569/15617 8511/8587/15635 8760/8588/15636 +f 8567/8589/15637 8573/8590/15638 8596/8591/15639 +f 8507/8592/15640 8654/8543/15591 8741/8542/15590 +f 8535/8593/15641 8526/8594/15642 8592/8595/15643 +f 8682/8596/15644 8689/8525/15573 8487/8597/15645 +f 8822/8598/15646 8462/8599/15647 8802/8600/15648 +f 8440/8601/15649 8687/8602/15650 8684/8465/15513 +f 8778/8603/15651 8516/8552/15600 8763/8604/15652 +f 8684/8465/15513 8687/8602/15650 8686/8580/15628 +f 8719/8578/15626 8720/8577/15625 8699/8605/15653 +f 8799/8558/15606 8451/8606/15654 8584/8607/15655 +f 8699/8605/15653 8720/8577/15625 8721/8608/15656 +f 8580/8446/15494 8499/8609/15657 8581/8610/15658 +f 8616/8611/15659 8621/8612/15660 8624/8613/15661 +f 8725/8614/15662 8484/8615/15663 8604/8616/15664 +f 8770/8484/15532 8723/8617/15665 8771/8485/15533 +f 8683/8438/15486 8734/8618/15666 8815/8439/15487 +f 8524/8619/15667 8582/8502/15550 8566/8576/15624 +f 8637/8620/15668 8718/8559/15607 8478/8586/15634 +f 8702/8621/15669 8843/8622/15670 8707/8623/15671 +f 8494/8568/15616 8492/8537/15585 8486/8536/15584 +f 8739/8624/15672 8740/8625/15673 8453/8521/15569 +f 8612/8626/15674 8594/8627/15675 8615/8628/15676 +f 8478/8586/15634 8706/8629/15677 8608/8630/15678 +f 8832/8631/15679 8716/8632/15680 8462/8599/15647 +f 8630/8633/15681 8792/8476/15524 8553/8468/15516 +f 8740/8625/15673 8743/8634/15682 8453/8521/15569 +f 8510/8635/15683 8760/8588/15636 8511/8587/15635 +f 8555/8460/15508 8554/8636/15684 8558/8637/15685 +f 8693/8638/15686 8568/8639/15687 8569/8640/15688 +f 8433/8575/15623 8451/8606/15654 8788/8641/15689 +f 8756/8642/15690 8804/8643/15690 8757/8644/15690 +f 8637/8620/15668 8497/8645/15691 8718/8559/15607 +f 8614/8646/15692 8480/8472/15520 8654/8543/15591 +f 8787/8544/15592 8795/8583/15631 8534/8647/15693 +f 8581/8610/15658 8499/8609/15657 8594/8627/15675 +f 8683/8438/15486 8571/8440/15488 8715/8648/15694 +f 8499/8609/15657 8793/8649/15695 8610/8650/15696 +f 8749/8651/15697 8679/8652/15698 8680/8653/15699 +f 8547/8654/15700 8681/8655/15701 8546/8561/15609 +f 8641/8656/15702 8761/8527/15575 8471/8445/15493 +f 8534/8647/15693 8741/8542/15590 8787/8544/15592 +f 8789/8657/15703 8725/8614/15662 8788/8641/15689 +f 8664/8658/15704 8665/8659/15705 8656/8528/15576 +f 8550/8512/15560 8548/8560/15608 8504/8660/15706 +f 8663/8661/15707 8664/8658/15704 8656/8528/15576 +f 8741/8542/15590 8508/8662/15708 8507/8592/15640 +f 8525/8663/15709 8667/8664/15710 8657/8665/15711 +f 8615/8628/15676 8594/8627/15675 8617/8666/15712 +f 8673/8519/15567 8674/8667/15713 8671/8668/15714 +f 8628/8669/15715 8629/8670/15716 8553/8468/15516 +f 8464/8671/15717 8603/8672/15718 8597/8673/15719 +f 8587/8674/15720 8588/8504/15552 8591/8675/15721 +f 8627/8463/15511 8591/8675/15721 8505/8676/15722 +f 8590/8677/15723 8473/8506/15554 8602/8678/15724 +f 8543/8679/15725 8651/8680/15726 8652/8681/15727 +f 8665/8659/15705 8666/8682/15728 8656/8528/15576 +f 8662/8683/15729 8663/8661/15707 8656/8528/15576 +f 8800/8471/15519 8791/8684/15730 8795/8583/15631 +f 8795/8583/15631 8713/8584/15632 8534/8647/15693 +f 8548/8560/15608 8550/8512/15560 8555/8460/15508 +f 8720/8577/15625 8490/8579/15627 8489/8685/15731 +f 8720/8577/15625 8489/8685/15731 8601/8686/15732 +f 8450/8454/15502 8444/8453/15501 8449/8687/15733 +f 8735/8548/15596 8585/8547/15595 8586/8688/15734 +f 8558/8637/15685 8554/8636/15684 8458/8492/15540 +f 8621/8612/15660 8625/8689/15735 8624/8613/15661 +f 8625/8689/15735 8628/8669/15715 8626/8690/15736 +f 8726/8691/15737 8497/8645/15691 8498/8692/15738 +f 8748/8693/15739 8821/8694/15740 8704/8695/15741 +f 8836/8499/15547 8594/8627/15675 8612/8626/15674 +f 8791/8684/15730 8512/8696/15742 8511/8587/15635 +f 8673/8519/15567 8656/8528/15576 8674/8667/15713 +f 8442/8452/15500 8591/8675/15721 8439/8462/15510 +f 8598/8697/15743 8468/8450/15498 8600/8698/15744 +f 8457/8699/15745 8830/8700/15746 8458/8492/15540 +f 8658/8701/15747 8659/8702/15748 8656/8528/15576 +f 8499/8609/15657 8616/8611/15659 8618/8703/15749 +f 8746/8704/15750 8824/8477/15525 8736/8514/15562 +f 8599/8705/15751 8603/8672/15718 8464/8671/15717 +f 8540/8706/15752 8577/8707/15753 8541/8534/15582 +f 8491/8473/15521 8609/8708/15754 8604/8616/15664 +f 8500/8513/15561 8550/8512/15560 8551/8585/15633 +f 8441/8563/15611 8845/8709/15755 8829/8710/15756 +f 8523/8533/15581 8569/8640/15688 8606/8711/15757 +f 8695/8712/15758 8456/8713/15759 8566/8576/15624 +f 8537/8714/15760 8531/8715/15761 8686/8580/15628 +f 8536/8716/15762 8780/8717/15763 8537/8714/15760 +f 8526/8594/15642 8533/8718/15764 8737/8719/15765 +f 8561/8461/15509 8563/8720/15766 8565/8721/15767 +f 8618/8703/15749 8623/8722/15768 8499/8609/15657 +f 8485/8723/15769 8681/8655/15701 8683/8438/15486 +f 8798/8557/15605 8788/8641/15689 8451/8606/15654 +f 8556/8724/15770 8557/8725/15771 8553/8468/15516 +f 8552/8726/15772 8555/8460/15508 8556/8724/15770 +f 8643/8727/15773 8459/8496/15544 8607/8728/15774 +f 8715/8648/15694 8529/8729/15775 8528/8730/15776 +f 8560/8556/15604 8764/8572/15620 8561/8461/15509 +f 8837/8437/15485 8833/8731/15777 8470/8435/15483 +f 8794/8732/15778 8709/8733/15779 8655/8489/15537 +f 8553/8468/15516 8552/8726/15772 8556/8724/15770 +f 8760/8588/15636 8510/8635/15683 8826/8567/15615 +f 8475/8734/15780 8584/8607/15655 8452/8491/15539 +f 8462/8599/15647 8803/8735/15781 8806/8736/15782 +f 8770/8484/15532 8722/8737/15783 8723/8617/15665 +f 8638/8738/15784 8639/8739/15785 8507/8592/15640 +f 8434/8457/15505 8805/8456/15504 8794/8732/15778 +f 8690/8740/15786 8685/8741/15787 8684/8465/15513 +f 8782/8742/15788 8817/8743/15789 8450/8454/15502 +f 8472/8744/15790 8748/8693/15739 8767/8745/15791 +f 8649/8746/15792 8650/8747/15793 8633/8748/15794 +f 8650/8747/15793 8600/8698/15744 8636/8749/15795 +f 8437/8464/15512 8721/8608/15656 8601/8686/15732 +f 8720/8577/15625 8601/8686/15732 8721/8608/15656 +f 8657/8665/15711 8658/8701/15747 8656/8528/15576 +f 8668/8750/15796 8525/8663/15709 8657/8665/15711 +f 8485/8723/15769 8546/8561/15609 8681/8655/15701 +f 8750/8751/15797 8694/8752/15798 8722/8737/15783 +f 8491/8473/15521 8604/8616/15664 8484/8615/15663 +f 8755/8753/15799 8757/8644/15800 8449/8687/15733 +f 8464/8671/15717 8468/8450/15498 8598/8697/15743 +f 8617/8666/15712 8499/8609/15657 8623/8722/15768 +f 8675/8754/15801 8672/8755/15802 8671/8668/15714 +f 8480/8472/15520 8614/8646/15692 8692/8442/15490 +f 8712/8756/15803 8569/8640/15688 8698/8757/15804 +f 8697/8758/15805 8738/8481/15529 8816/8759/15806 +f 8698/8757/15804 8569/8640/15688 8738/8481/15529 +f 8733/8470/15518 8644/8760/15807 8734/8618/15666 +f 8656/8528/15576 8813/8761/15808 8699/8605/15653 +f 8499/8609/15657 8610/8650/15696 8611/8762/15809 +f 8686/8580/15628 8688/8582/15630 8684/8465/15513 +f 8506/8763/15810 8627/8463/15511 8505/8676/15722 +f 8771/8485/15533 8774/8764/15811 8773/8765/15812 +f 8573/8590/15813 8572/8766/15814 8596/8591/15815 +f 8472/8744/15790 8767/8745/15791 8635/8767/15816 +f 8546/8561/15609 8485/8723/15769 8486/8536/15584 +f 8553/8468/15516 8547/8654/15700 8552/8726/15772 +f 8465/8768/15817 8809/8769/15818 8805/8456/15504 +f 8590/8677/15723 8589/8770/15819 8478/8586/15634 +f 8478/8586/15634 8589/8770/15819 8706/8629/15677 +f 8567/8589/15637 8667/8664/15710 8525/8663/15709 +f 8636/8749/15795 8632/8771/15820 8650/8747/15793 +f 8459/8496/15544 8608/8630/15678 8607/8728/15774 +f 8751/8772/15821 8680/8653/15699 8694/8752/15798 +f 8629/8670/15716 8630/8633/15681 8553/8468/15516 +f 8548/8560/15608 8486/8536/15584 8504/8660/15706 +f 8566/8576/15624 8573/8590/15638 8567/8589/15637 +f 8636/8749/15795 8468/8450/15498 8578/8773/15822 +f 8611/8762/15809 8619/8774/15823 8616/8611/15659 +f 8784/8775/15824 8776/8776/15825 8569/8640/15688 +f 8600/8698/15744 8468/8450/15498 8636/8749/15795 +f 8482/8498/15546 8550/8512/15560 8504/8660/15706 +f 8683/8438/15486 8682/8596/15644 8485/8723/15769 +f 8756/8642/15826 8757/8644/15800 8755/8753/15799 +f 8593/8777/15827 8742/8778/15828 8695/8712/15758 +f 8583/8503/15551 8582/8502/15829 8505/8676/15722 +f 8620/8436/15484 8808/8520/15568 8837/8437/15485 +f 8555/8460/15508 8502/8511/15559 8554/8636/15684 +f 8524/8619/15667 8668/8750/15796 8505/8676/15722 +f 8691/8482/15530 8543/8679/15725 8738/8481/15529 +f 8627/8463/15511 8721/8608/15656 8437/8464/15512 +f 8485/8723/15769 8682/8596/15644 8487/8597/15645 +f 8617/8666/15712 8594/8627/15675 8499/8609/15657 +f 8583/8503/15551 8505/8676/15722 8591/8675/15721 +f 8587/8674/15830 8591/8675/15830 8442/8452/15830 +f 8656/8528/15576 8668/8750/15796 8657/8665/15711 +f 8672/8755/15802 8673/8519/15567 8671/8668/15714 +f 8538/8553/15601 8455/8779/15831 8593/8777/15827 +f 8593/8777/15827 8455/8779/15831 8742/8778/15828 +f 8717/8780/15832 8799/8558/15606 8584/8607/15655 +f 8520/8531/15579 8675/8754/15801 8676/8781/15833 +f 8687/8602/15650 8537/8714/15760 8686/8580/15628 +f 8750/8751/15797 8751/8772/15821 8694/8752/15798 +f 8830/8700/15746 8839/8782/15834 8458/8492/15540 +f 8650/8747/15793 8632/8771/15820 8633/8748/15794 +f 8670/8783/15835 8696/8784/15836 8667/8664/15710 +f 8456/8713/15837 8455/8779/15837 8572/8766/15837 +f 8538/8553/15838 8572/8766/15838 8455/8779/15838 +f 8682/8596/15644 8715/8648/15694 8528/8730/15776 +f 8596/8591/15839 8670/8783/15835 8667/8664/15710 +f 8596/8591/15840 8667/8664/15840 8567/8589/15840 +f 8619/8774/15823 8621/8612/15660 8616/8611/15659 +f 8715/8648/15694 8571/8440/15488 8529/8729/15775 +f 8787/8544/15592 8480/8472/15520 8800/8471/15519 +f 8497/8645/15691 8789/8657/15703 8798/8557/15605 +f 8780/8717/15763 8622/8785/15841 8534/8647/15693 +f 8593/8777/15827 8753/8786/15842 8703/8455/15503 +f 8659/8702/15748 8660/8787/15843 8656/8528/15576 +f 8673/8519/15567 8672/8755/15802 8834/8788/15844 +f 8815/8439/15487 8734/8618/15666 8462/8599/15647 +f 8507/8592/15640 8639/8739/15785 8653/8789/15845 +f 8533/8718/15764 8713/8584/15632 8737/8719/15765 +f 8503/8538/15586 8466/8790/15846 8504/8660/15706 +f 8481/8486/15534 8754/8791/15847 8755/8753/15799 +f 8725/8614/15662 8604/8616/15664 8501/8792/15848 +f 8466/8790/15846 8503/8538/15586 8465/8768/15817 +f 8734/8618/15666 8553/8468/15516 8733/8470/15518 +f 8534/8647/15693 8713/8584/15632 8533/8718/15764 +f 8743/8634/15682 8707/8623/15671 8453/8521/15569 +f 8736/8514/15562 8728/8516/15564 8746/8704/15750 +f 8438/8474/15522 8439/8462/15510 8437/8464/15512 +f 8473/8506/15554 8718/8559/15607 8717/8780/15832 +f 8724/8526/15574 8682/8596/15644 8528/8730/15776 +f 8714/8524/15572 8724/8526/15574 8737/8719/15765 +f 8806/8736/15782 8793/8649/15695 8499/8609/15657 +f 8691/8482/15530 8463/8480/15528 8597/8673/15719 +f 8798/8557/15605 8789/8657/15703 8788/8641/15689 +f 8448/8574/15622 8436/8488/15536 8446/8535/15583 +f 8718/8559/15607 8799/8558/15606 8717/8780/15832 +f 8719/8578/15626 8641/8656/15702 8736/8514/15562 +f 8459/8496/15544 8637/8620/15668 8478/8586/15634 +f 8660/8787/15843 8661/8793/15849 8656/8528/15576 +f 8528/8730/15776 8527/8794/15850 8724/8526/15574 +f 8532/8795/15851 8535/8593/15641 8592/8595/15643 +f 8504/8660/15706 8486/8536/15584 8503/8538/15586 +f 8783/8796/15852 8786/8550/15598 8516/8552/15600 +f 8774/8764/15811 8771/8485/15533 8544/8797/15853 +f 8510/8635/15683 8797/8565/15613 8826/8567/15615 +f 8669/8798/15854 8572/8766/15855 8785/8799/15856 +f 8580/8446/15494 8461/8448/15496 8499/8609/15657 +f 8470/8435/15483 8472/8744/15790 8469/8444/15492 +f 8730/8800/15857 8758/8801/15858 8545/8802/15859 +f 8484/8615/15663 8498/8692/15738 8483/8509/15557 +f 8738/8481/15529 8569/8640/15688 8477/8447/15495 +f 8805/8456/15504 8466/8790/15846 8465/8768/15817 +f 8597/8673/15719 8603/8672/15718 8678/8803/15860 +f 8729/8804/15861 8545/8802/15859 8450/8454/15502 +f 8796/8479/15527 8609/8708/15754 8490/8579/15627 +f 8592/8595/15643 8570/8805/15862 8634/8532/15580 +f 8499/8609/15657 8461/8448/15496 8462/8599/15647 +f 8489/8685/15731 8490/8579/15627 8488/8475/15523 +f 8635/8767/15816 8579/8806/15863 8468/8450/15498 +f 8841/8530/15578 8675/8754/15801 8520/8531/15579 +f 8508/8662/15708 8741/8542/15590 8622/8785/15841 +f 8531/8715/15761 8534/8647/15693 8533/8718/15764 +f 8802/8600/15648 8462/8599/15647 8644/8760/15807 +f 8522/8807/15864 8541/8534/15582 8523/8533/15581 +f 8583/8503/15551 8591/8675/15721 8588/8504/15552 +f 8653/8789/15845 8613/8808/15865 8614/8646/15692 +f 8795/8583/15631 8787/8544/15592 8800/8471/15519 +f 8556/8724/15770 8555/8460/15508 8559/8809/15866 +f 8594/8627/15675 8836/8499/15547 8818/8515/15563 +f 8445/8508/15556 8447/8510/15558 8446/8535/15583 +f 8800/8471/15519 8479/8441/15489 8512/8696/15742 +f 8465/8768/15817 8495/8566/15614 8809/8769/15818 +f 8437/8464/15512 8488/8475/15523 8438/8474/15522 +f 8761/8527/15575 8813/8761/15808 8656/8528/15576 +f 8500/8513/15561 8551/8585/15633 8434/8457/15505 +f 8496/8810/15867 8435/8811/15868 8436/8488/15536 +f 8541/8534/15582 8542/8812/15869 8540/8706/15752 +f 8594/8627/15675 8641/8656/15702 8471/8445/15493 +f 8433/8575/15623 8452/8491/15539 8451/8606/15654 +f 8727/8813/15870 8728/8516/15564 8818/8515/15563 +f 8441/8563/15611 8440/8601/15649 8516/8552/15600 +f 8689/8525/15573 8791/8684/15730 8511/8587/15635 +f 8649/8746/15792 8633/8748/15794 8679/8652/15698 +f 8823/8478/15526 8458/8492/15540 8796/8479/15527 +f 8682/8596/15644 8724/8526/15574 8689/8525/15573 +f 8789/8657/15703 8726/8691/15737 8725/8614/15662 +f 8445/8508/15556 8446/8535/15583 8444/8453/15501 +f 8486/8536/15584 8487/8597/15645 8494/8568/15616 +f 8523/8533/15581 8461/8448/15496 8477/8447/15495 +f 8525/8663/15709 8668/8750/15796 8524/8619/15667 +f 8472/8744/15790 8468/8450/15498 8469/8444/15492 +f 8475/8734/15780 8476/8507/15555 8473/8506/15554 +f 8754/8791/15847 8756/8642/15826 8755/8753/15799 +f 8791/8684/15730 8714/8524/15572 8795/8583/15631 +f 8817/8743/15789 8729/8804/15861 8450/8454/15502 +f 8468/8450/15498 8472/8744/15790 8635/8767/15816 +f 8626/8690/15736 8628/8669/15715 8553/8468/15516 +f 8595/8569/15617 8487/8597/15645 8689/8525/15573 +f 8506/8763/15810 8699/8605/15653 8721/8608/15656 +f 8462/8599/15647 8734/8618/15666 8644/8760/15807 +f 8753/8786/15842 8593/8777/15827 8695/8712/15758 +f 8748/8693/15739 8701/8814/15871 8702/8621/15669 +f 8776/8776/15825 8777/8815/15872 8642/8816/15873 +f 8536/8716/15762 8508/8662/15708 8622/8785/15841 +f 8466/8790/15846 8482/8498/15546 8504/8660/15706 +f 8472/8744/15790 8833/8731/15777 8821/8694/15740 +f 8516/8552/15600 8440/8601/15649 8763/8604/15652 +f 8484/8615/15663 8483/8509/15557 8491/8473/15521 +f 8486/8536/15584 8485/8723/15769 8487/8597/15645 +f 8539/8817/15874 8572/8766/15855 8538/8553/15601 +f 8579/8806/15863 8578/8773/15822 8468/8450/15498 +f 8488/8475/15523 8601/8686/15732 8489/8685/15731 +f 8465/8768/15817 8492/8537/15585 8493/8564/15612 +f 8497/8645/15691 8435/8811/15868 8496/8810/15867 +f 8498/8692/15738 8497/8645/15691 8496/8810/15867 +f 8707/8623/15671 8748/8693/15739 8702/8621/15669 +f 8735/8548/15596 8508/8662/15708 8441/8563/15611 +f 8465/8768/15817 8503/8538/15586 8492/8537/15585 +f 8599/8705/15751 8464/8671/15717 8598/8697/15743 +f 8571/8440/15488 8815/8439/15487 8462/8599/15647 +f 8477/8447/15495 8580/8446/15494 8463/8480/15528 +f 8456/8713/15759 8573/8590/15638 8566/8576/15624 +f 8435/8811/15868 8637/8620/15668 8436/8488/15536 +f 8637/8620/15668 8435/8811/15868 8497/8645/15691 +f 8438/8474/15522 8445/8508/15556 8439/8462/15510 +f 8634/8532/15580 8570/8805/15862 8523/8533/15581 +f 8641/8656/15702 8719/8578/15626 8813/8761/15808 +f 8780/8717/15763 8536/8716/15762 8622/8785/15841 +f 8558/8637/15685 8560/8556/15604 8555/8460/15508 +f 8445/8508/15556 8438/8474/15522 8483/8509/15557 +f 8543/8679/15725 8646/8818/15875 8651/8680/15726 +f 8449/8687/15733 8782/8742/15788 8450/8454/15502 +f 8673/8519/15567 8834/8788/15844 8808/8520/15568 +f 8460/8819/15876 8481/8486/15534 8436/8488/15536 +f 8511/8587/15635 8595/8569/15617 8689/8525/15573 +f 8602/8678/15724 8473/8506/15554 8474/8505/15553 +f 8471/8445/15493 8620/8436/15484 8470/8435/15483 +f 8669/8798/15854 8596/8591/15839 8572/8766/15855 +f 8500/8513/15561 8433/8575/15623 8501/8792/15848 +f 8514/8820/15877 8515/8562/15610 8513/8821/15878 +f 8506/8763/15810 8505/8676/15722 8668/8750/15796 +f 8788/8641/15689 8725/8614/15662 8501/8792/15848 +f 8597/8673/15719 8678/8803/15860 8645/8822/15879 +f 8446/8535/15583 8449/8687/15733 8444/8453/15501 +f 8624/8613/15661 8625/8689/15735 8626/8690/15736 +f 8661/8793/15849 8662/8683/15729 8656/8528/15576 +f 8481/8486/15534 8755/8753/15799 8831/8487/15535 +f 8456/8713/15759 8695/8712/15758 8742/8778/15828 +f 8814/8555/15603 8811/8823/15880 8520/8531/15579 +f 8490/8579/15627 8609/8708/15754 8491/8473/15521 +f 8512/8696/15742 8479/8441/15489 8510/8635/15683 +f 8519/8824/15881 8819/8825/15882 8514/8820/15877 +f 8499/8609/15657 8611/8762/15809 8616/8611/15659 +f 8641/8656/15702 8594/8627/15675 8818/8515/15563 +f 8473/8506/15554 8590/8677/15723 8478/8586/15634 +f 8528/8730/15776 8529/8729/15775 8526/8594/15642 +f 8778/8603/15651 8783/8796/15852 8516/8552/15600 +f 8820/8826/15883 8759/8827/15884 8516/8552/15600 +f 8573/8590/15813 8456/8713/15885 8572/8766/15814 +f 8491/8473/15521 8488/8475/15523 8490/8579/15627 +f 8588/8504/15552 8695/8712/15758 8566/8576/15624 +f 8526/8594/15642 8737/8719/15765 8527/8794/15850 +f 8749/8651/15697 8649/8746/15792 8679/8652/15698 +f 8487/8597/15645 8595/8569/15617 8494/8568/15616 +f 8561/8461/15509 8562/8518/15566 8563/8720/15766 +f 8836/8499/15547 8835/8517/15565 8766/8539/15587 +f 8752/8541/15589 8818/8515/15563 8836/8499/15547 +f 8766/8539/15587 8835/8517/15565 8765/8573/15621 +f 8818/8515/15563 8736/8514/15562 8641/8656/15702 +f 8752/8541/15589 8727/8813/15870 8818/8515/15563 +f 8835/8517/15565 8561/8461/15509 8765/8573/15621 +f 8796/8479/15527 8736/8514/15562 8824/8477/15525 +f 8604/8616/15664 8609/8708/15754 8605/8828/15886 +f 8594/8627/15675 8469/8444/15492 8467/8449/15497 +f 8710/8829/15887 8763/8604/15652 8440/8601/15649 +f 8547/8654/15700 8553/8468/15516 8734/8618/15666 +f 8647/8830/15888 8648/8831/15889 8516/8552/15600 +f 8667/8664/15710 8696/8784/15836 8657/8665/15711 +f 8681/8655/15701 8547/8654/15700 8734/8618/15666 +f 8676/8781/15833 8675/8754/15801 8671/8668/15714 +f 8674/8667/15713 8656/8528/15576 8677/8832/15890 +f 8532/8795/15851 8531/8715/15761 8535/8593/15641 +f 8546/8561/15609 8548/8560/15608 8547/8654/15700 +f 8533/8718/15764 8535/8593/15641 8531/8715/15761 +f 8543/8679/15725 8816/8759/15806 8738/8481/15529 +f 8595/8569/15617 8760/8588/15636 8826/8567/15615 +f 8436/8488/15536 8448/8574/15622 8496/8810/15867 +f 8726/8691/15737 8789/8657/15703 8497/8645/15691 +f 8751/8772/15821 8749/8651/15697 8680/8653/15699 +f 8554/8636/15684 8502/8511/15559 8501/8792/15848 +f 8776/8776/15825 8606/8711/15757 8569/8640/15688 +f 8557/8725/15771 8640/8833/15891 8553/8468/15516 +f 8466/8790/15846 8781/8458/15506 8482/8498/15546 +f 8523/8533/15581 8477/8447/15495 8569/8640/15688 +f 8577/8707/15753 8576/8571/15619 8541/8534/15582 +f 8652/8681/15727 8544/8797/15853 8543/8679/15725 +f 8609/8708/15754 8796/8479/15527 8605/8828/15886 +f 8463/8480/15528 8691/8482/15530 8477/8447/15495 +f 8527/8794/15850 8528/8730/15776 8526/8594/15642 +f 8539/8817/15874 8538/8553/15601 8574/8546/15594 +f 8777/8815/15872 8842/8834/15892 8642/8816/15873 +f 8442/8452/15500 8445/8508/15556 8444/8453/15501 +f 8535/8593/15641 8533/8718/15764 8526/8594/15642 +f 8810/8835/15893 8453/8521/15569 8844/8836/15894 +f 8501/8792/15848 8605/8828/15886 8554/8636/15684 +f 8825/8570/15618 8700/8549/15597 8735/8548/15596 +f 8683/8438/15486 8715/8648/15694 8682/8596/15644 +f 8686/8580/15628 8531/8715/15761 8532/8795/15851 +f 8714/8524/15572 8791/8684/15730 8689/8525/15573 +f 8748/8693/15739 8472/8744/15790 8821/8694/15740 +f 8719/8578/15626 8796/8479/15527 8490/8579/15627 +f 8588/8504/15552 8587/8674/15720 8442/8452/15500 +f 8471/8445/15493 8469/8444/15492 8594/8627/15675 +f 8441/8563/15611 8536/8716/15762 8440/8601/15649 +f 8548/8560/15608 8552/8726/15772 8547/8654/15700 +f 8441/8563/15611 8515/8562/15610 8845/8709/15755 +f 8464/8671/15717 8467/8449/15497 8468/8450/15498 +f 8762/8837/15895 8750/8751/15797 8722/8737/15783 +f 8757/8644/15800 8807/8838/15896 8449/8687/15733 +f 8482/8498/15546 8551/8585/15633 8550/8512/15560 +f 8561/8461/15509 8565/8721/15767 8564/8459/15507 +f 8529/8729/15775 8571/8440/15488 8570/8805/15862 +f 8566/8576/15624 8567/8589/15637 8524/8619/15667 +f 8568/8639/15687 8784/8775/15824 8569/8640/15688 +f 8840/8581/15629 8686/8580/15628 8634/8532/15580 +f 8695/8712/15758 8588/8504/15552 8753/8786/15842 +f 8637/8620/15668 8459/8496/15544 8436/8488/15536 +f 8461/8448/15496 8523/8533/15581 8570/8805/15862 +f 8509/8443/15491 8510/8635/15683 8479/8441/15489 +f 8524/8619/15667 8567/8589/15637 8525/8663/15709 +f 8782/8742/15788 8790/8839/15897 8817/8743/15789 +f 8537/8714/15760 8780/8717/15763 8531/8715/15761 +f 8452/8491/15539 8434/8457/15505 8655/8489/15537 +f 8582/8502/15550 8524/8619/15667 8505/8676/15898 +f 8513/8821/15878 8515/8562/15610 8516/8552/15600 +f 8683/8438/15486 8681/8655/15701 8734/8618/15666 +f 8738/8481/15529 8697/8758/15805 8698/8757/15804 +f 8501/8792/15848 8433/8575/15623 8788/8641/15689 +f 8458/8492/15540 8823/8478/15526 8530/8493/15541 +f 8575/8545/15593 8549/8840/15899 8574/8546/15594 +f 8838/8841/15900 8828/8842/15901 8436/8488/15536 +f 8653/8789/15845 8614/8646/15692 8654/8543/15591 +f 8529/8729/15775 8592/8595/15643 8526/8594/15642 +f 8711/8467/15515 8710/8829/15887 8440/8601/15649 +f 8685/8741/15787 8705/8466/15514 8684/8465/15513 +f 8541/8534/15582 8522/8807/15864 8542/8812/15869 +f 8594/8627/15675 8467/8449/15497 8581/8610/15658 +f 8771/8485/15533 8723/8617/15665 8453/8521/15569 +f 8437/8464/15512 8601/8686/15732 8488/8475/15523 +f 8737/8719/15765 8713/8584/15632 8714/8524/15572 +f 8456/8713/15902 8742/8778/15902 8455/8779/15902 +f 8692/8442/15490 8479/8441/15489 8480/8472/15520 +f 8440/8601/15649 8536/8716/15762 8537/8714/15760 +f 8605/8828/15886 8501/8792/15848 8604/8616/15664 +f 8550/8512/15560 8502/8511/15559 8555/8460/15508 +f 8686/8580/15628 8532/8795/15851 8634/8532/15580 +f 8631/8843/15903 8626/8690/15736 8553/8468/15516 +f 8498/8692/15738 8484/8615/15663 8726/8691/15737 +f 8463/8480/15528 8467/8449/15497 8464/8671/15717 +f 8829/8710/15756 8825/8570/15618 8441/8563/15611 +f 8827/8844/15904 8475/8734/15780 8452/8491/15539 +f 8580/8446/15494 8581/8610/15658 8467/8449/15497 +f 8810/8835/15893 8454/8554/15602 8453/8521/15569 +f 8518/8845/15905 8519/8824/15881 8514/8820/15877 +f 8753/8786/15842 8588/8504/15552 8442/8452/15500 +f 8480/8472/15520 8787/8544/15592 8654/8543/15591 +f 8590/8677/15723 8602/8678/15724 8589/8770/15819 +f 8627/8463/15511 8439/8462/15510 8591/8675/15721 +f 8666/8682/15728 8677/8832/15890 8656/8528/15576 +f 8716/8632/15680 8803/8735/15781 8462/8599/15647 +f 8520/8531/15579 8453/8521/15569 8454/8554/15602 +f 8452/8491/15539 8584/8607/15655 8451/8606/15654 +f 8688/8582/15630 8690/8740/15786 8684/8465/15513 +f 8512/8696/15742 8510/8635/15683 8511/8587/15635 +f 8458/8492/15540 8605/8828/15886 8796/8479/15527 +f 8799/8558/15606 8798/8557/15605 8451/8606/15654 +f 8543/8679/15725 8597/8673/15719 8646/8818/15875 +f 8433/8575/15623 8500/8513/15561 8434/8457/15505 +f 8699/8605/15653 8506/8763/15810 8668/8750/15796 +f 8729/8804/15861 8730/8800/15857 8545/8802/15859 +f 8606/8711/15757 8522/8807/15864 8523/8533/15581 +f 8673/8519/15567 8620/8436/15484 8761/8527/15575 +f 8491/8473/15521 8483/8509/15557 8438/8474/15522 +f 8494/8568/15616 8826/8567/15615 8493/8564/15612 +f 8440/8601/15649 8684/8465/15513 8711/8467/15515 +f 8517/8846/15906 8518/8845/15905 8514/8820/15877 +f 8638/8738/15784 8507/8592/15640 8508/8662/15708 +f 8559/8809/15866 8555/8460/15508 8564/8459/15507 +f 8608/8630/15678 8459/8496/15544 8478/8586/15634 +f 8627/8463/15511 8506/8763/15810 8721/8608/15656 +f 8553/8468/15516 8640/8833/15891 8631/8843/15903 +f 8699/8605/15653 8813/8761/15808 8719/8578/15626 +f 8770/8484/15532 8762/8837/15895 8722/8737/15783 +f 8634/8532/15580 8532/8795/15851 8592/8595/15643 +f 8596/8591/15839 8669/8798/15854 8670/8783/15835 +f 8606/8711/15757 8776/8776/15825 8642/8816/15873 +f 8495/8566/15614 8465/8768/15817 8493/8564/15612 +f 8724/8526/15574 8527/8794/15850 8737/8719/15765 +f 8508/8662/15708 8536/8716/15762 8441/8563/15611 +f 8447/8510/15558 8496/8810/15867 8448/8574/15622 +f 8725/8614/15662 8726/8691/15737 8484/8615/15663 +f 8753/8786/15842 8443/8451/15499 8703/8455/15503 +f 8605/8828/15886 8458/8492/15540 8554/8636/15684 +f 8597/8673/15719 8543/8679/15725 8691/8482/15530 +f 8785/8799/15856 8572/8766/15855 8539/8817/15874 +f 8718/8559/15607 8497/8645/15691 8798/8557/15605 +f 8447/8510/15558 8483/8509/15557 8498/8692/15738 +f 8620/8436/15484 8471/8445/15493 8761/8527/15575 +f 8811/8823/15880 8521/8529/15577 8520/8531/15579 +f 8449/8687/15733 8831/8487/15535 8755/8753/15799 +f 8569/8640/15688 8712/8756/15803 8693/8638/15686 +f 8703/8455/15503 8450/8454/15502 8575/8545/15593 +f 8464/8671/15717 8597/8673/15719 8463/8480/15528 +f 8473/8506/15554 8717/8780/15832 8475/8734/15780 +f 8446/8535/15583 8831/8487/15535 8449/8687/15733 +f 8538/8553/15601 8593/8777/15827 8703/8455/15503 +f 8508/8662/15708 8735/8548/15596 8638/8738/15784 +f 8717/8780/15832 8584/8607/15655 8475/8734/15780 +f 8708/8847/15907 8709/8733/15779 8794/8732/15778 +f 8732/8523/15571 8739/8624/15672 8453/8521/15569 +f 8552/8726/15772 8548/8560/15608 8555/8460/15508 +f 8779/8490/15538 8827/8844/15904 8452/8491/15539 +f 8592/8595/15643 8529/8729/15775 8570/8805/15862 +f 8654/8543/15591 8507/8592/15640 8653/8789/15845 +f 8613/8808/15865 8692/8442/15490 8614/8646/15692 +f 8462/8599/15647 8822/8598/15646 8832/8631/15679 +f 8723/8617/15665 8731/8522/15570 8453/8521/15569 +f 8773/8765/15812 8772/8483/15531 8771/8485/15533 +f 8827/8844/15904 8476/8507/15555 8475/8734/15780 +f 8459/8496/15544 8643/8727/15773 8769/8497/15545 +f 8668/8750/15796 8656/8528/15576 8699/8605/15653 +f 8805/8456/15504 8708/8847/15907 8794/8732/15778 +f 8828/8842/15901 8460/8819/15876 8436/8488/15536 +f 8796/8479/15527 8719/8578/15626 8736/8514/15562 +f 8576/8571/15619 8840/8581/15629 8634/8532/15580 +f 8445/8508/15556 8442/8452/15500 8439/8462/15510 +f 8545/8802/15859 8549/8840/15899 8450/8454/15502 +f 8499/8609/15657 8462/8599/15647 8806/8736/15782 +f 8768/8495/15543 8838/8841/15900 8436/8488/15536 +f 8641/8656/15702 8813/8761/15808 8761/8527/15575 +f 8492/8537/15585 8494/8568/15616 8493/8564/15612 +f 8496/8810/15867 8447/8510/15558 8498/8692/15738 +f 8800/8471/15519 8512/8696/15742 8791/8684/15730 +f 8501/8792/15848 8502/8511/15559 8500/8513/15561 +f 8638/8738/15784 8735/8548/15596 8586/8688/15734 +f 8472/8744/15790 8470/8435/15483 8833/8731/15777 +f 8571/8440/15488 8461/8448/15496 8570/8805/15862 +f 8843/8622/15670 8844/8836/15894 8707/8623/15671 +f 8759/8827/15884 8647/8830/15888 8516/8552/15600 +f 8687/8602/15650 8440/8601/15649 8537/8714/15760 +f 8534/8647/15693 8531/8715/15761 8780/8717/15763 +f 8748/8693/15739 8704/8695/15741 8701/8814/15871 +f 8443/8451/15499 8753/8786/15842 8442/8452/15500 +f 8516/8552/15600 8812/8551/15599 8820/8826/15883 +f 8597/8673/15719 8645/8822/15879 8646/8818/15875 +f 8453/8521/15569 8707/8623/15671 8844/8836/15894 +f 8781/8458/15506 8466/8790/15846 8805/8456/15504 +f 8513/8821/15878 8517/8846/15906 8514/8820/15877 +f 8839/8782/15834 8558/8637/15685 8458/8492/15540 +f 8622/8785/15841 8741/8542/15590 8534/8647/15693 +f 8836/8499/15547 8744/8501/15549 8745/8540/15588 +f 8449/8687/15733 8807/8838/15896 8782/8742/15788 +f 8461/8448/15496 8571/8440/15488 8462/8599/15647 +f 8549/8840/15899 8575/8545/15593 8450/8454/15502 +f 8794/8732/15778 8655/8489/15537 8434/8457/15505 +f 8771/8485/15533 8543/8679/15725 8544/8797/15853 +f 8458/8492/15540 8775/8494/15542 8457/8699/15745 +f 8797/8565/15613 8493/8564/15612 8826/8567/15615 +f 8648/8831/15889 8513/8821/15878 8516/8552/15600 +f 7149/7709/15908 8585/8547/15909 8700/8549/15910 7071/7710/15911 +f 7171/7897/15912 8643/8727/15913 8607/8728/15914 7172/7898/15915 +f 7096/7876/15916 8540/8706/15917 8542/8812/15918 7095/7984/15919 +f 7198/7829/15920 8665/8659/15921 8664/8658/15922 7199/7828/14741 +f 7240/7865/14782 8821/8694/15923 8833/8731/15924 7238/7901/14825 +f 6011/6309/15925 8172/8134/15926 8173/8275/15927 6012/6913/15928 +f 5980/5907/15929 8151/8046/15930 8146/8396/15931 5981/7381/15932 +f 6017/5820/15933 8279/8030/15934 8096/8029/15935 6018/5821/15936 +f 6013/7080/15937 8225/8325/15937 8226/8326/15938 6014/7081/15939 +f 6149/7329/15940 8317/8387/15941 8345/8389/15942 6150/7330/15943 +f 7077/7772/15944 8763/8604/15944 8710/8829/15945 7086/8002/15946 +f 5949/6419/15947 8163/8158/15948 8427/8169/15949 5950/6468/15950 +f 5897/7397/15951 8314/8400/15952 8315/8102/15953 5898/6172/15954 +f 7086/8002/15946 8710/8829/15945 8711/8467/15955 7081/7621/15956 +f 6043/6769/15957 8343/8229/15958 8391/8231/15959 6044/6770/15959 +f 6148/7339/15960 8316/8391/15961 8317/8387/15941 6149/7329/15940 +f 7244/7683/15962 8731/8522/15570 8723/8617/15665 7270/7785/15963 +f 7191/8014/15964 8549/8840/15965 8545/8802/15966 7189/7973/15967 +f 7073/7714/15968 8812/8551/15969 8786/8550/15970 7080/7712/15971 +f 7227/7691/15972 8841/8530/15972 8521/8529/15577 7226/7689/15973 +f 5963/7198/15974 8363/8363/15975 8364/8403/15976 5964/7435/15977 +f 5939/6597/15978 8350/8191/15978 8365/8190/15979 5940/6596/15980 +f 7233/7959/14918 8834/8788/15981 8672/8755/15982 7229/7926/15983 +f 6027/6065/15984 8242/8076/15985 8366/8078/15986 6026/6066/15987 +f 7280/7991/15988 8646/8818/15988 8645/8822/15989 7279/7995/15013 +f 7245/7682/15990 8732/8523/15571 8731/8522/15570 7244/7683/15962 +f 5938/7495/15991 8346/8414/15992 8234/8417/15993 5937/7510/15994 +f 7234/7679/14533 8808/8520/15995 8834/8788/15981 7233/7959/14918 +f 7100/7946/15996 8784/8775/15997 8568/8639/15998 7099/7808/15999 +f 7181/7810/16000 8756/8642/16001 8754/8791/16002 7185/7962/16003 +f 6018/5821/15936 8096/8029/15935 8097/8222/16004 6019/6743/16005 +f 5953/7436/16006 8229/8402/16007 8193/8298/16008 5954/7009/16009 +f 7085/7622/16010 8705/8466/16011 8685/8741/16012 7083/7912/16013 +f 7019/7840/16014 8629/8670/16015 8628/8669/16016 7018/7839/16017 +f 7243/7789/16018 8702/8621/16018 8701/8814/16019 7242/7987/16020 +f 7180/7642/16021 8481/8486/16022 8460/8819/16023 7176/7992/16024 +f 5933/6311/16025 8287/8135/16026 8172/8134/15926 6011/6309/15925 +f 6034/7044/16027 8194/8315/16028 8230/8314/16029 6033/7043/16030 +f 5957/7394/16031 8129/8399/16032 8127/8293/16033 5958/6993/16034 +f 7083/7912/16013 8685/8741/16012 8690/8740/16035 7082/7911/16036 +f 7140/8004/16037 8648/8831/16038 8647/8830/16039 7075/8003/16040 +f 6061/6845/13421 8251/8245/16041 8252/8246/16042 6060/6846/16043 +f 6100/7054/13647 8420/8318/16044 8408/8282/16045 6102/6934/13522 +f 7208/7837/14751 8671/8668/16046 8674/8667/16047 7209/7838/14752 +f 7271/7919/14845 8650/8747/16048 8649/8746/16049 7264/7917/14843 +f 5948/7508/16050 8297/8416/16051 8350/8191/15978 5939/6597/15978 +f 6067/6963/13547 8246/8289/16052 8247/8374/16053 6065/7251/13881 +f 5943/5918/16054 8298/8053/16055 8297/8416/16051 5948/7508/16050 +f 7206/7690/14545 8520/8531/16056 8676/8781/16057 7207/7952/14900 +f 7228/7925/16058 8675/8754/16058 8841/8530/16058 7227/7691/16058 +f 6132/6635/16059 8310/8204/15240 8318/8110/15146 6106/6194/16060 +f 6051/7331/16061 8132/8388/16062 8136/8427/16063 6053/7552/16064 +f 7034/7702/16065 8752/8541/16066 8745/8540/16067 7033/7701/16068 +f 5875/7161/16069 8198/8349/16070 8206/8361/16071 5876/7194/16072 +f 6088/6215/16073 8108/8116/15152 8428/8118/16074 6089/6216/16074 +f 7282/7850/16075 8652/8681/15727 8651/8680/16076 7281/7851/16076 +f 6066/6962/13546 8245/8288/16077 8246/8289/16052 6067/6963/13547 +f 7255/7922/16078 8750/8751/15797 8762/8837/15895 7254/8011/16079 +f 7196/7955/14904 8696/8784/16080 8670/8783/16081 7195/7954/14903 +f 7082/7911/16036 8690/8740/16035 8688/8582/16082 7089/7746/16083 +f 6091/7130/16084 8259/8342/16085 8421/8375/16086 6095/7252/13882 +f 7024/7625/16087 8801/8469/16088 8792/8476/16089 7021/7631/16089 +f 6141/7479/14229 8232/8409/16090 8233/8405/16091 6142/7467/16091 +f 6106/6194/16060 8318/8110/15146 8319/8109/15145 6107/6195/16092 +f 7279/7995/15013 8645/8822/15989 8678/8803/16093 7278/7975/14963 +f 7013/7933/16094 8611/8762/16095 8610/8650/16096 7012/7817/16097 +f 7121/7895/16098 8557/8725/16099 8556/8724/16100 7120/7894/16101 +f 7105/7860/16102 8626/8690/16102 8631/8843/16103 7104/8017/16104 +f 6095/7252/13882 8421/8375/16086 8395/8106/16105 6096/6191/12827 +f 7037/7634/16106 8823/8478/16107 8824/8477/16108 7043/7632/16109 +f 6047/7262/16110 8341/8378/16111 8343/8229/15958 6043/6769/15957 +f 7242/7987/16020 8701/8814/16019 8704/8695/16112 7241/7864/14781 +f 5945/7083/16113 8272/8328/16114 8292/8054/16115 5947/5917/16116 +f 6104/7433/16117 8288/8401/16118 8289/8208/16119 6105/6668/16119 +f 5880/6862/16120 8215/8256/16121 8216/8257/16122 5881/6863/16123 +f 6038/7471/16124 8047/8406/16125 8068/8073/16126 6042/6046/16127 +f 5944/7082/16128 8277/8327/16129 8272/8328/16114 5945/7083/16113 +f 5937/7510/15994 8234/8417/15993 8235/8418/16130 6002/7511/16131 +f 7169/7662/16132 8474/8505/16133 8476/8507/16134 7163/7663/16135 +f 7080/7712/15971 8786/8550/15970 8783/8796/16136 7079/7967/16137 +f 7109/7892/16138 8623/8722/16139 8618/8703/16140 7108/7873/16141 +f 7173/7797/16142 8608/8630/16142 8706/8629/16143 7174/7798/16144 +f 6071/6859/13436 8261/8255/16145 8258/8254/16146 6070/6860/13437 +f 6126/7091/13685 8236/8333/16147 8237/8335/16148 6133/7092/13686 +f 7028/7736/16149 8765/8573/16149 8764/8572/16149 7027/7737/16149 +f 7071/7710/15911 8700/8549/15910 8825/8570/16150 7070/7734/16151 +f 7174/7798/16144 8706/8629/16143 8589/8770/16152 7170/7941/16152 +f 6089/6216/16153 8428/8118/16153 8262/8341/16153 6090/7129/16153 +f 7009/7799/16154 8832/8631/16155 8822/8598/16156 7004/7766/16157 +f 5895/6259/16158 8332/8127/16159 8339/8128/16160 5896/6260/16161 +f 7030/7700/16162 8766/8539/16163 8765/8573/16164 7028/7736/16164 +f 6143/6882/16165 8238/8268/16165 8239/8267/15301 6144/6883/16166 +f 6116/7544/16167 8349/8424/15470 8337/8338/15372 6117/7125/16168 +f 6057/7227/13848 8257/8370/16169 8283/8371/16170 6058/7228/13849 +f 5951/6469/16171 8275/8168/16172 8277/8327/16129 5944/7082/16128 +f 7225/7996/16173 8811/8823/15880 8814/8555/15603 7224/7717/16174 +f 6064/7289/13927 8248/8380/16175 8249/8270/16176 6063/6886/13466 +f 7091/7988/16177 8642/8816/16178 8842/8834/16179 7090/8008/16180 +f 5873/6795/16181 8380/8237/16182 8197/8236/16183 5874/6796/16184 +f 7230/7791/16185 8843/8622/16185 8702/8621/16185 7243/7789/16185 +f 6140/7334/13997 8265/8390/16186 8232/8409/16090 6141/7479/14229 +f 7120/7894/16101 8556/8724/16100 8559/8809/16187 7119/7981/16188 +f 7106/7780/16189 8624/8613/16189 8626/8690/16189 7105/7860/16189 +f 7199/7828/14741 8664/8658/15922 8663/8661/16190 7200/7831/14745 +f 7195/7954/14903 8670/8783/16081 8669/8798/16191 7194/7970/16192 +f 6021/6392/16193 8082/8152/16194 8396/8356/16195 6023/7175/16196 +f 7090/8008/16180 8842/8834/16179 8777/8815/16197 7102/7989/16198 +f 5982/7037/16199 8143/8311/16200 8144/8312/16201 5983/7038/16202 +f 5966/7561/16203 8218/8430/16204 8213/8277/16205 5967/6926/16205 +f 7018/7839/16017 8628/8669/16016 8625/8689/16206 7016/7859/16207 +f 5905/5996/16208 8411/8064/16209 8410/8066/16210 5899/5997/16211 +f 6094/7528/16212 8397/8422/15468 8041/8141/15177 6085/6341/16213 +f 6103/6935/13523 8291/8281/16214 8288/8401/16118 6104/7433/16117 +f 7211/7852/14767 8666/8682/16215 8665/8659/15921 7198/7829/15920 +f 7247/7793/16216 8740/8625/15673 8739/8624/15672 7246/7792/16217 +f 6025/6116/16218 8063/8093/16219 8061/8092/16220 6031/6114/16221 +f 5970/6964/16222 8205/8290/16223 8210/8309/16224 5971/7032/16225 +f 7027/7737/16226 8764/8572/16226 8560/8556/16227 7047/7719/16228 +f 6036/6698/16229 8293/8217/16230 8195/8216/16231 6035/6699/16231 +f 7229/7926/15983 8672/8755/15982 8675/8754/16232 7228/7925/16232 +f 7278/7975/14963 8678/8803/16093 8603/8672/16233 7276/7843/14758 +f 5889/6420/16234 8351/8160/16234 8352/8159/16234 5890/6421/16234 +f 7262/7820/16235 8680/8653/16235 8679/8652/16236 7260/7821/14733 +f 5932/6407/16237 8412/8157/16238 8287/8135/16026 5933/6311/16025 +f 7194/7970/16192 8669/8798/16191 8785/8799/16239 7193/7971/16240 +f 6032/7179/16241 8176/8357/16241 8293/8217/16230 6036/6698/16229 +f 7167/7903/16242 8709/8733/16243 8708/8847/16244 7166/8021/16245 +f 5866/6588/16246 8409/8185/16247 8419/8218/16248 5871/6703/16249 +f 7163/7663/16135 8476/8507/16134 8827/8844/16250 7162/8018/16251 +f 5890/6421/16252 8352/8159/16252 8353/8126/16253 5892/6258/16254 +f 7151/7909/16255 8638/8738/16255 8586/8688/16256 7150/7858/16257 +f 5952/7527/16258 8429/8421/16259 8229/8402/16007 5953/7436/16006 +f 7276/7843/14758 8603/8672/16233 8599/8705/16260 7275/7875/14794 +f 7006/7907/16261 8803/8735/16262 8716/8632/16263 7010/7800/16264 +f 7185/7962/16003 8754/8791/16002 8481/8486/16022 7180/7642/16021 +f 5940/6596/15980 8365/8190/15979 8370/8383/16265 5941/7315/16266 +f 7260/7821/14733 8679/8652/16236 8633/8748/16267 7259/7918/14844 +f 7275/7875/14794 8599/8705/16260 8598/8697/16268 7273/7867/14784 +f 6048/7545/16269 8394/8425/16270 8369/8329/16271 6046/7085/16272 +f 7269/7916/14842 8767/8745/16273 8748/8693/16274 7248/7863/16274 +f 6105/6668/16275 8289/8208/16275 8430/8210/16275 6092/6669/16275 +f 5877/6615/16276 8208/8200/16277 8212/8276/16278 5878/6925/16279 +f 7146/8019/16280 8518/8845/16280 8517/8846/16281 7144/8020/16282 +f 5981/7381/15932 8146/8396/15931 8143/8311/16200 5982/7037/16199 +f 7257/7920/14848 8636/8749/16283 8578/8773/16284 7265/7944/14885 +f 7273/7867/14784 8598/8697/16268 8600/8698/16285 7272/7868/14785 +f 7232/8009/16286 8810/8835/15893 8844/8836/15894 7231/8010/16287 +f 5967/6926/16288 8213/8277/16288 8211/8199/16288 5968/6616/16288 +f 6062/6853/13429 8250/8248/16289 8251/8245/16041 6061/6845/13421 +f 7107/7779/16290 8616/8611/16291 8624/8613/16292 7106/7780/16292 +f 7175/7653/16293 8769/8497/16294 8643/8727/15913 7171/7897/15912 +f 6056/7322/16295 8256/8385/16296 8257/8370/16169 6057/7227/13848 +f 7189/7973/15967 8545/8802/15966 8758/8801/16297 7288/7974/16298 +f 5964/7435/15977 8364/8403/15976 8429/8421/16259 5952/7527/16258 +f 7089/7746/16083 8688/8582/16082 8840/8581/16299 7088/7747/16300 +f 7022/7767/16301 8802/8600/16302 8644/8760/16303 7026/7931/16304 +f 5886/5932/16305 8388/8057/16306 8320/8056/16307 5887/5933/16308 +f 7187/8013/16309 8790/8839/16310 8782/8742/16311 7184/7913/16312 +f 6022/6391/16313 8384/8153/16314 8082/8152/16194 6021/6392/16193 +f 7074/7999/16315 8820/8826/16316 8812/8551/15969 7073/7714/15968 +f 7178/8015/16317 8838/8841/16318 8768/8495/16319 7179/7652/16320 +f 6060/6846/16043 8252/8246/16042 8253/8269/16321 6073/6885/13465 +f 7160/7730/16322 8797/8565/16323 8510/8635/16324 7157/7803/16325 +f 6108/6685/16326 8326/8211/15247 8327/8212/15248 6109/6686/16327 +f 7168/7848/16328 8602/8678/16329 8474/8505/16133 7169/7662/16132 +f 5909/6364/16330 8147/8143/16331 8351/8160/16332 5889/6420/16332 +f 6090/7129/16333 8262/8341/16333 8259/8342/16085 6091/7130/16084 +f 7095/7984/15919 8542/8812/15918 8522/8807/16334 7093/7979/16335 +f 7148/7880/16336 8845/8709/16337 8515/8562/16338 7147/7726/16339 +f 6138/6867/13445 8190/8260/16340 8265/8390/16186 6140/7334/13997 +f 7116/7891/16341 8563/8720/16342 8562/8518/16343 7115/7677/16344 +f 6114/6034/16345 8357/8072/15108 8349/8424/15470 6116/7544/16167 +f 7193/7971/16240 8785/8799/16239 8539/8817/16346 7192/7990/16347 +f 6122/6804/13376 8266/8240/16348 8267/8239/16349 6124/6805/16349 +f 6055/7323/16350 8372/8386/16351 8256/8385/16296 6056/7322/16295 +f 6028/7579/16352 8295/8434/16353 8296/8320/16354 6029/7056/16355 +f 7209/7838/14752 8674/8667/16047 8677/8832/16356 7210/8006/15028 +f 7250/7802/16357 8743/8634/15682 8740/8625/15673 7247/7793/16216 +f 7047/7719/16228 8560/8556/16227 8558/8637/16358 7046/7804/16359 +f 7033/7701/16068 8745/8540/16067 8744/8501/16360 7032/7657/16361 +f 7143/7993/16362 8514/8820/16363 8819/8825/16364 7142/7998/16365 +f 6024/7563/16366 8414/8431/16367 8063/8093/16219 6025/6116/16218 +f 7046/7804/16359 8558/8637/16358 8839/8782/16368 7045/7953/16369 +f 7026/7931/16304 8644/8760/16303 8733/8470/16370 7025/7624/16371 +f 6113/6033/16372 8359/8070/15106 8357/8072/15108 6114/6034/16345 +f 7158/7611/16373 8805/8456/16374 8809/8769/16375 7161/7940/16376 +f 6012/6913/15928 8173/8275/15927 8225/8325/15937 6013/7080/15937 +f 7144/8020/16282 8517/8846/16281 8513/8821/16377 7141/7994/16378 +f 7246/7792/16217 8739/8624/15672 8732/8523/15571 7245/7682/15990 +f 6137/6972/13551 8186/8292/16379 8190/8260/16340 6138/6867/13445 +f 5872/6704/16380 8303/8219/16381 8390/8323/16382 5868/7070/16383 +f 6042/6046/16127 8068/8073/16126 8341/8378/16111 6047/7262/16110 +f 7183/7811/14723 8757/8644/16384 8804/8643/16385 7182/7812/14724 +f 6121/7093/13687 8220/8334/16386 8266/8240/16348 6122/6804/13376 +f 6135/6949/13538 8185/8284/16387 8186/8292/16379 6137/6972/13551 +f 6110/6933/16388 8335/8280/16388 8354/8332/16389 6131/7090/13684 +f 7188/7914/16390 8817/8743/16391 8790/8839/16310 7187/8013/16309 +f 7166/8021/16245 8708/8847/16244 8805/8456/16374 7158/7611/16373 +f 7179/7652/16320 8768/8495/16319 8769/8497/16294 7175/7653/16293 +f 7041/7869/16392 8457/8699/16393 8775/8494/16394 7040/7650/16395 +f 6006/7572/16396 8104/8433/16397 8105/8432/16398 6008/7565/16398 +f 6127/7192/13796 8165/8360/16399 8223/8336/16400 6119/7096/13692 +f 6134/6950/13539 8187/8285/16401 8185/8284/16387 6135/6949/13538 +f 6093/7529/16402 8431/8423/15469 8397/8422/15468 6094/7528/16212 +f 6087/7485/16403 8398/8410/15455 8108/8116/15152 6088/6215/16073 +f 7141/7994/16378 8513/8821/16377 8648/8831/16038 7140/8004/16037 +f 5968/6616/16404 8211/8199/16404 8203/8198/16405 5969/6614/16406 +f 6150/7330/15943 8345/8389/15942 8132/8388/16062 6051/7331/16061 +f 5950/6468/15950 8427/8169/15949 8275/8168/16172 5951/6469/16171 +f 7104/8017/16104 8631/8843/16103 8640/8833/16407 7103/8007/16408 +f 7093/7979/16335 8522/8807/16334 8606/8711/16409 7092/7881/16410 +f 7154/7980/16411 8613/8808/16412 8653/8789/16413 7153/7960/16414 +f 5962/7197/16415 8371/8362/16416 8363/8363/15975 5963/7198/15974 +f 7172/7898/15915 8607/8728/15914 8608/8630/16142 7173/7797/16142 +f 5876/7194/16072 8206/8361/16071 8208/8200/16277 5877/6615/16276 +f 7176/7992/16024 8460/8819/16023 8828/8842/16417 7177/8016/16418 +f 7007/7906/16419 8806/8736/16420 8803/8735/16262 7006/7907/16261 +f 5935/6315/16421 8399/8139/16422 8407/8413/16423 5936/7494/16424 +f 6041/6080/16425 8355/8082/16426 8425/8428/16427 6040/7553/16428 +f 7217/7927/16429 8712/8756/16430 8698/8757/16431 7218/7928/14862 +f 6019/6743/16005 8097/8222/16004 8384/8153/16314 6022/6391/16313 +f 6031/6114/16221 8061/8092/16220 8189/8265/16432 6030/6880/16433 +f 5955/7373/16434 8109/8394/16435 8129/8399/16032 5957/7394/16031 +f 7038/7651/16436 8530/8493/16437 8823/8478/16107 7037/7634/16106 +f 6009/6388/16438 8102/8149/16439 8432/8297/16440 6010/7006/16441 +f 5977/6174/16442 8149/8104/16443 8150/8308/16444 5978/7030/16445 +f 7113/7656/16446 8836/8499/16447 8612/8626/16448 7112/7794/16449 +f 6054/7443/16450 8126/8404/16451 8372/8386/16351 6055/7323/16350 +f 7236/7589/14423 8837/8437/16452 8808/8520/15995 7234/7679/14533 +f 7253/7908/16453 8722/8737/15783 8694/8752/16454 7263/7923/16454 +f 7108/7873/16141 8618/8703/16140 8616/8611/16291 7107/7779/16290 +f 7224/7717/16174 8814/8555/15603 8454/8554/15602 7223/7716/16455 +f 6072/7514/14278 8264/8419/16456 8261/8255/16145 6071/6859/13436 +f 6109/6686/16327 8327/8212/15248 8330/8221/15257 6112/6711/16457 +f 7204/7871/14790 8658/8701/16458 8657/8665/16459 7197/7834/14748 +f 5908/6757/16460 8145/8223/16461 8147/8143/16331 5909/6364/16330 +f 7281/7851/16462 8651/8680/16462 8646/8818/16462 7280/7991/16462 +f 5894/6088/16463 8331/8087/16464 8332/8127/16159 5895/6259/16158 +f 7186/8012/16465 8807/8838/16466 8757/8644/16384 7183/7811/14723 +f 6004/7493/16467 8406/8412/16468 8101/8407/16469 6005/7474/16470 +f 7272/7868/14785 8600/8698/16285 8650/8747/16048 7271/7919/14845 +f 7147/7726/16339 8515/8562/16338 8514/8820/16363 7143/7993/16362 +f 5907/7224/16471 8426/8369/16472 8145/8223/16461 5908/6757/16460 +f 5887/5933/16308 8320/8056/16307 8231/8347/16473 5888/7155/16474 +f 5942/6314/16475 8373/8137/16476 8399/8139/16422 5935/6315/16421 +f 7087/7735/16477 8576/8571/16478 8577/8707/16479 7098/7877/16480 +f 6023/7175/16196 8396/8356/16195 8392/8043/16481 6020/5876/16482 +f 7165/7646/16483 8655/8489/16484 8709/8733/16243 7167/7903/16242 +f 6107/6195/16092 8319/8109/15145 8326/8211/15247 6108/6685/16326 +f 7011/7818/16485 8793/8649/16486 8806/8736/16420 7007/7906/16419 +f 7153/7960/16414 8653/8789/16413 8639/8739/16487 7152/7910/16488 +f 7231/8010/16287 8844/8836/15894 8843/8622/16489 7230/7791/16489 +f 7032/7657/16361 8744/8501/16360 8747/8500/16490 7031/7658/16491 +f 7070/7734/16151 8825/8570/16150 8829/8710/16492 7072/7879/16493 +f 7162/8018/16251 8827/8844/16250 8779/8490/16494 7164/7648/16495 +f 6049/7548/16496 8377/8426/16497 8404/8330/16498 6050/7086/16499 +f 7248/7863/16500 8748/8693/16500 8707/8623/16500 7249/7790/16500 +f 6037/6082/16501 8356/8083/16502 8355/8082/16426 6041/6080/16425 +f 5902/6076/16503 8362/8080/16504 8044/8286/16505 5903/6958/16506 +f 7048/7806/16507 8693/8638/16508 8712/8756/16430 7217/7927/16429 +f 6002/7511/16131 8235/8418/16130 8100/8408/16509 6003/7475/16510 +f 7145/7997/16511 8519/8824/16511 8518/8845/16511 7146/8019/16511 +f 7213/7640/14492 8771/8485/16512 8453/8521/16513 7214/7681/14535 +f 5965/7521/16514 8227/8420/16515 8218/8430/16204 5966/7561/16203 +f 5954/7009/16009 8193/8298/16008 8109/8394/16435 5955/7373/16434 +f 6015/7257/16516 8240/8376/16517 8200/8395/16518 6016/7379/16519 +f 7182/7812/16520 8804/8643/16520 8756/8642/16001 7181/7810/16000 +f 7200/7831/14745 8663/8661/16190 8662/8683/16521 7201/7853/14768 +f 6035/6699/16231 8195/8216/16231 8194/8315/16028 6034/7044/16027 +f 7202/7964/14938 8661/8793/16522 8660/8787/16523 7203/7958/14916 +f 6039/7554/16524 8415/8429/16525 8047/8406/16125 6038/7471/16124 +f 5961/6763/16526 8155/8227/16527 8371/8362/16416 5962/7197/16415 +f 6080/7149/13744 8285/8344/16528 8299/8343/16529 6079/7148/16530 +f 7010/7800/16264 8716/8632/16263 8832/8631/16155 7009/7799/16154 +f 7215/7930/14864 8816/8759/16531 8543/8679/16532 7212/7849/14764 +f 5899/5997/16211 8410/8066/16210 8117/8081/16533 5900/6075/16534 +f 7117/7890/16535 8565/8721/16536 8563/8720/16342 7116/7891/16341 +f 7114/7678/16537 8835/8517/16537 8836/8499/16447 7113/7656/16446 +f 7044/7870/16538 8830/8700/16539 8457/8699/16393 7041/7869/16392 +f 5974/6689/16540 8199/8213/16541 8423/8086/16542 5975/6086/16543 +f 7020/7801/16544 8630/8633/16545 8629/8670/16015 7019/7840/16014 +f 7283/7968/16546 8544/8797/15853 8652/8681/15727 7282/7850/16075 +f 6096/6191/12827 8395/8106/16105 8424/8023/16547 6098/5774/12453 +f 6125/7126/16548 8281/8339/16548 8309/8324/15358 6115/7076/16549 +f 5969/6614/16406 8203/8198/16405 8205/8290/16223 5970/6964/16222 +f 7072/7879/16493 8829/8710/16492 8845/8709/16337 7148/7880/16336 +f 6085/6341/16213 8041/8141/15177 8401/8142/15178 6086/6342/16550 +f 7216/7929/14863 8697/8758/16551 8816/8759/16531 7215/7930/14864 +f 7081/7621/15956 8711/8467/15955 8705/8466/16011 7085/7622/16010 +f 6069/7221/13843 8263/8368/16552 8107/8117/16553 6068/6217/12850 +f 6059/6857/13433 8244/8251/16554 8245/8288/16077 6066/6962/13546 +f 7142/7998/16365 8819/8825/16364 8519/8824/16555 7145/7997/16555 +f 7004/7766/16157 8822/8598/16156 8802/8600/16302 7022/7767/16301 +f 6142/7467/16556 8233/8405/16556 8238/8268/16556 6143/6882/16556 +f 6133/7092/13686 8237/8335/16148 8187/8285/16401 6134/6950/13539 +f 6005/7474/16470 8101/8407/16469 8102/8149/16439 6009/6388/16438 +f 5960/6994/16557 8164/8294/16558 8163/8158/15948 5949/6419/15947 +f 6029/7056/16355 8296/8320/16354 8242/8076/15985 6027/6065/15984 +f 5869/7071/16559 8393/8322/16560 8380/8237/16182 5873/6795/16181 +f 6014/7081/15939 8226/8326/15938 8240/8376/16517 6015/7257/16516 +f 7031/7658/16491 8747/8500/16490 8766/8539/16163 7030/7700/16162 +f 6092/6669/16561 8430/8210/16561 8431/8423/15469 6093/7529/16402 +f 5893/6087/16562 8334/8088/16563 8331/8087/16464 5894/6088/16463 +f 5934/7007/16564 8416/8296/16565 8412/8157/16238 5932/6407/16237 +f 7249/7790/16566 8707/8623/16566 8743/8634/15682 7250/7802/16357 +f 6026/6066/15987 8366/8078/15986 8414/8431/16367 6024/7563/16366 +f 6111/6670/16567 8294/8209/16567 8335/8280/16567 6110/6933/16567 +f 5883/5970/16568 8379/8063/16569 8388/8057/16306 5886/5932/16305 +f 6079/7148/16530 8299/8343/16529 8280/8225/16570 5910/6762/16571 +f 7286/7976/16572 8729/8804/16573 8817/8743/16391 7188/7914/16390 +f 7264/7917/14843 8649/8746/16049 8749/8651/16574 7256/7819/16574 +f 7110/7836/16575 8617/8666/16576 8623/8722/16139 7109/7892/16138 +f 6008/7565/16577 8105/8432/16577 8106/8411/16577 6007/7492/16577 +f 7203/7958/14916 8660/8787/16523 8659/8702/16578 7205/7872/14791 +f 6076/6193/12829 8040/8108/16579 8358/8071/16580 6075/6035/12686 +f 7118/7614/16581 8564/8459/16582 8565/8721/16536 7117/7890/16535 +f 5874/6796/16184 8197/8236/16183 8198/8349/16070 5875/7161/16069 +f 6063/6886/13466 8249/8270/16176 8250/8248/16289 6062/6853/13429 +f 6065/7251/13881 8247/8374/16053 8248/8380/16175 6064/7289/13927 +f 7268/7938/14876 8635/8767/16583 8767/8745/16273 7269/7916/14842 +f 7014/7945/16584 8619/8774/16585 8611/8762/16095 7013/7933/16094 +f 7190/7707/16586 8574/8546/16587 8549/8840/15965 7191/8014/15964 +f 7205/7872/14791 8659/8702/16578 8658/8701/16458 7204/7871/14790 +f 7214/7681/14535 8453/8521/16513 8520/8531/16056 7206/7690/14545 +f 7115/7677/16344 8562/8518/16343 8835/8517/16588 7114/7678/16588 +f 5871/6703/16249 8419/8218/16248 8303/8219/16381 5872/6704/16380 +f 7177/8016/16418 8828/8842/16417 8838/8841/16318 7178/8015/16317 +f 5941/7315/16266 8370/8383/16265 8373/8137/16476 5942/6314/16475 +f 6074/6881/13460 8130/8266/16589 8403/8346/16590 6077/7153/13748 +f 5978/7030/16445 8150/8308/16444 8152/8307/16591 5979/7031/16592 +f 5975/6086/16543 8423/8086/16542 8422/8105/16593 5976/6173/16593 +f 5903/6958/16506 8044/8286/16505 8417/8287/16594 5906/6959/16595 +f 7076/8000/16596 8759/8827/16597 8820/8826/16316 7074/7999/16315 +f 5881/6863/16123 8216/8257/16122 8217/8220/16598 5882/6709/16599 +f 7261/7943/16600 8751/8772/16600 8750/8751/15797 7255/7922/16078 +f 6144/6883/16166 8239/8267/15301 8131/8384/15428 6145/7318/16601 +f 7238/7901/14825 8833/8731/15924 8837/8437/16452 7236/7589/14423 +f 7270/7785/15963 8723/8617/15665 8722/8737/15783 7253/7908/16453 +f 6010/7006/16441 8432/8297/16440 8416/8296/16565 5934/7007/16564 +f 7111/7795/16602 8615/8628/16603 8617/8666/16576 7110/7836/16575 +f 5947/5917/16116 8292/8054/16115 8298/8053/16055 5943/5918/16054 +f 6077/7153/13748 8403/8346/16590 8284/8345/16604 6078/7152/13747 +f 6007/7492/16605 8106/8411/16605 8406/8412/16468 6004/7493/16467 +f 5884/6590/16606 8389/8186/16607 8409/8185/16247 5866/6588/16246 +f 7259/7918/14844 8633/8748/16267 8632/8771/16608 7258/7942/14880 +f 7035/7985/16609 8727/8813/16610 8752/8541/16066 7034/7702/16065 +f 7155/7597/16611 8692/8442/16612 8613/8808/16412 7154/7980/16411 +f 7192/7990/16347 8539/8817/16346 8574/8546/16587 7190/7707/16586 +f 5892/6258/16254 8353/8126/16253 8334/8088/16563 5893/6087/16562 +f 6086/6342/16550 8401/8142/15178 8398/8410/15455 6087/7485/16403 +f 7284/7936/16613 8774/8764/15811 8544/8797/15853 7283/7968/16546 +f 6112/6711/16457 8330/8221/15257 8294/8209/16614 6111/6670/16614 +f 6050/7086/16499 8404/8330/16498 8316/8391/15961 6148/7339/15960 +f 6118/6803/16615 8336/8238/16615 8236/8333/16147 6126/7091/13685 +f 5971/7032/16225 8210/8309/16224 8204/8253/16616 5972/6858/16617 +f 5979/7031/16592 8152/8307/16591 8151/8046/15930 5980/5907/15929 +f 7112/7794/16449 8612/8626/16448 8615/8628/16603 7111/7795/16602 +f 6131/7090/13684 8354/8332/16389 8222/8354/16618 6130/7169/13773 +f 7207/7952/14900 8676/8781/16057 8671/8668/16046 7208/7837/14751 +f 5878/6925/16279 8212/8276/16278 8215/8256/16121 5880/6862/16120 +f 7099/7808/15999 8568/8639/15998 8693/8638/16508 7048/7806/16507 +f 6053/7552/16064 8136/8427/16063 8161/8132/16619 6052/6308/16620 +f 7263/7923/16621 8694/8752/16621 8680/8653/16621 7262/7820/16621 +f 6068/6217/12850 8107/8117/16553 8040/8108/16579 6076/6193/12829 +f 5976/6173/16622 8422/8105/16622 8149/8104/16443 5977/6174/16442 +f 7201/7853/14768 8662/8683/16521 8661/8793/16522 7202/7964/14938 +f 6040/7553/16428 8425/8428/16427 8415/8429/16525 6039/7554/16524 +f 7012/7817/16097 8610/8650/16096 8793/8649/16486 7011/7818/16485 +f 7266/7978/14973 8579/8806/16623 8635/8767/16583 7268/7938/14876 +f 5936/7494/16424 8407/8413/16423 8346/8414/15992 5938/7495/15991 +f 6117/7125/16168 8337/8338/15372 8338/8359/16624 6123/7185/16624 +f 7045/7953/16369 8839/8782/16368 8830/8700/16539 7044/7870/16538 +f 6098/5774/12453 8424/8023/16547 8420/8318/16044 6100/7054/13647 +f 7161/7940/16376 8809/8769/16375 8495/8566/16625 7159/7729/16626 +f 6115/7076/16549 8309/8324/15358 8310/8204/15240 6132/6635/16059 +f 5972/6858/16617 8204/8253/16616 8202/8214/16627 5973/6691/16628 +f 7241/7864/14781 8704/8695/16112 8821/8694/15923 7240/7865/14782 +f 6120/7182/13788 8219/8358/16629 8220/8334/16386 6121/7093/13687 +f 5896/6260/16161 8339/8128/16160 8314/8400/15952 5897/7397/15951 +f 6016/7379/16519 8200/8395/16518 8279/8030/15934 6017/5820/15933 +f 7223/7716/16455 8454/8554/15602 8810/8835/15893 7232/8009/16286 +f 7258/7942/14880 8632/8771/16608 8636/8749/16283 7257/7920/14848 +f 6052/6308/16620 8161/8132/16619 8126/8404/16451 6054/7443/16450 +f 7098/7877/16480 8577/8707/16479 8540/8706/15917 7096/7876/15916 +f 7251/7639/16630 8772/8483/15531 8773/8765/15812 7285/7935/16631 +f 6145/7318/16601 8131/8384/15428 8361/8352/15387 6146/7163/16632 +f 7285/7935/16631 8773/8765/15812 8774/8764/15811 7284/7936/16613 +f 7103/8007/16408 8640/8833/16407 8557/8725/16099 7121/7895/16098 +f 5958/6993/16034 8127/8293/16033 8164/8294/16558 5960/6994/16557 +f 7170/7941/16152 8589/8770/16152 8602/8678/16329 7168/7848/16328 +f 7210/8006/15028 8677/8832/16356 8666/8682/16215 7211/7852/14767 +f 6033/7043/16030 8230/8314/16029 8356/8083/16502 6037/6082/16501 +f 5973/6691/16628 8202/8214/16627 8199/8213/16541 5974/6689/16540 +f 7265/7944/14885 8578/8773/16284 8579/8806/16623 7266/7978/14973 +f 5888/7155/16474 8231/8347/16473 8389/8186/16607 5884/6590/16606 +f 6046/7085/16272 8369/8329/16271 8377/8426/16497 6049/7548/16496 +f 6070/6860/13437 8258/8254/16146 8263/8368/16552 6069/7221/13843 +f 5910/6762/16571 8280/8225/16570 8155/8227/16527 5961/6763/16526 +f 7042/7874/16633 8746/8704/16634 8728/8516/16635 7036/7675/16636 +f 6124/6805/16637 8267/8239/16637 8281/8339/16637 6125/7126/16637 +f 7212/7849/14764 8543/8679/16532 8771/8485/16512 7213/7640/14492 +f 7040/7650/16395 8775/8494/16394 8530/8493/16437 7038/7651/16436 +f 7079/7967/16137 8783/8796/16136 8778/8603/16638 7078/7771/16639 +f 7184/7913/16312 8782/8742/16311 8807/8838/16466 7186/8012/16465 +f 7016/7859/16207 8625/8689/16206 8621/8612/16640 7015/7781/16641 +f 6130/7169/13773 8222/8354/16618 8166/8393/16642 6128/7364/14040 +f 7197/7834/14748 8657/8665/16459 8696/8784/16080 7196/7955/14904 +f 7021/7631/16089 8792/8476/16089 8630/8633/16545 7020/7801/16544 +f 7218/7928/14862 8698/8757/16431 8697/8758/16551 7216/7929/14863 +f 5906/6959/16595 8417/8287/16594 8426/8369/16472 5907/7224/16471 +f 6102/6934/13522 8408/8282/16045 8291/8281/16214 6103/6935/13523 +f 7025/7624/16371 8733/8470/16370 8801/8469/16088 7024/7625/16087 +f 7159/7729/16626 8495/8566/16625 8797/8565/16323 7160/7730/16322 +f 6119/7096/13692 8223/8336/16400 8219/8358/16629 6120/7182/13788 +f 6003/7475/16510 8100/8408/16509 8104/8433/16397 6006/7572/16396 +f 6147/7164/16643 8360/8351/15386 8359/8070/15106 6113/6033/16372 +f 7043/7632/16109 8824/8477/16108 8746/8704/16634 7042/7874/16633 +f 7256/7819/16644 8749/8651/16644 8751/8772/16644 7261/7943/16644 +f 6044/6770/13340 8391/8231/16645 8344/8230/16646 6045/6771/13341 +f 6020/5876/16482 8392/8043/16481 8295/8434/16353 6028/7579/16352 +f 6146/7163/16632 8361/8352/15387 8360/8351/15386 6147/7164/16643 +f 5983/7038/16202 8144/8312/16201 8227/8420/16515 5965/7521/16514 +f 7150/7858/16257 8586/8688/16256 8585/8547/15909 7149/7709/15908 +f 6030/6880/16433 8189/8265/16432 8176/8357/16241 6032/7179/16241 +f 7119/7981/16188 8559/8809/16187 8564/8459/16582 7118/7614/16581 +f 7156/7596/16647 8509/8443/16648 8692/8442/16612 7155/7597/16611 +f 7152/7910/16488 8639/8739/16487 8638/8738/16255 7151/7909/16255 +f 7254/8011/16079 8762/8837/15895 8770/8484/15532 7252/7641/16649 +f 7288/7974/16298 8758/8801/16297 8730/8800/16650 7287/7972/16651 +f 6073/6885/13465 8253/8269/16321 8264/8419/16456 6072/7514/14278 +f 7088/7747/16300 8840/8581/16299 8576/8571/16478 7087/7735/16477 +f 7036/7675/16636 8728/8516/16635 8727/8813/16610 7035/7985/16609 +f 6128/7364/14040 8166/8393/16642 8165/8360/16399 6127/7192/13796 +f 7287/7972/16651 8730/8800/16650 8729/8804/16573 7286/7976/16572 +f 5898/6172/15954 8315/8102/15953 8333/8291/16652 5904/6969/16653 +f 5868/7070/16383 8390/8323/16382 8393/8322/16560 5869/7071/16559 +f 7252/7641/16649 8770/8484/15532 8772/8483/15531 7251/7639/16630 +f 6075/6035/12686 8358/8071/16580 8130/8266/16589 6074/6881/13460 +f 7102/7989/16198 8777/8815/16197 8776/8776/16654 7101/7947/16655 +f 5900/6075/16534 8117/8081/16533 8362/8080/16504 5902/6076/16503 +f 7078/7771/16639 8778/8603/16638 8763/8604/15944 7077/7772/15944 +f 7164/7648/16495 8779/8490/16494 8655/8489/16484 7165/7646/16483 +f 6058/7228/13849 8283/8371/16170 8244/8251/16554 6059/6857/13433 +f 5882/6709/16599 8217/8220/16598 8379/8063/16569 5883/5970/16568 +f 6078/7152/13747 8284/8345/16604 8285/8344/16528 6080/7149/13744 +f 7075/8003/16040 8647/8830/16039 8759/8827/16597 7076/8000/16596 +f 7226/7689/15973 8521/8529/15577 8811/8823/15880 7225/7996/16173 +f 7101/7947/16655 8776/8776/16654 8784/8775/15997 7100/7946/15996 +f 7015/7781/16641 8621/8612/16640 8619/8774/16585 7014/7945/16584 +f 6045/6771/13341 8344/8230/16646 8394/8425/16270 6048/7545/16269 +f 7157/7803/16325 8510/8635/16324 8509/8443/16648 7156/7596/16647 +f 7092/7881/16410 8606/8711/16409 8642/8816/16178 7091/7988/16177 +f 5904/6969/16653 8333/8291/16652 8411/8064/16209 5905/5996/16208 +f 6123/7185/16656 8338/8359/16656 8336/8238/16656 6118/6803/16656 diff --git a/examples/Cassie/urdf/meshes/agility/plantar-rod.obj b/examples/Cassie/urdf/meshes/agility/plantar-rod.obj new file mode 100644 index 0000000000..c6e49adeec --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/plantar-rod.obj @@ -0,0 +1,5035 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o plantar-rod +v 0.006152 0.001747 -0.007140 +v 0.006727 0.003569 -0.005703 +v 0.007781 0.001608 -0.005473 +v 0.011444 -0.003567 -0.000590 +v 0.010047 -0.003567 -0.002128 +v 0.011789 -0.002975 -0.001900 +v 0.013041 -0.003173 0.000671 +v 0.010843 -0.003572 0.001406 +v 0.011444 0.003567 0.000590 +v 0.010047 0.003567 0.002128 +v 0.011789 0.002975 0.001900 +v 0.012468 0.003269 -0.000785 +v 0.010843 0.003572 -0.001406 +v 0.013508 0.003209 0.000093 +v 0.013456 -0.003177 -0.000509 +v 0.010300 -0.000185 0.004008 +v 0.011773 -0.001464 0.003216 +v 0.013072 0.000244 0.003229 +v 0.013459 -0.000891 0.003085 +v 0.013430 0.002925 0.001357 +v 0.011807 0.002912 -0.001973 +v 0.013477 -0.002811 -0.001542 +v 0.012151 -0.002727 0.002080 +v 0.013756 0.002934 -0.001301 +v 0.010324 0.002454 0.003214 +v 0.013437 0.002172 0.002362 +v 0.010423 0.002494 -0.003134 +v 0.008921 0.003571 -0.003186 +v 0.010018 -0.000988 -0.004051 +v 0.011059 0.000002 -0.003753 +v 0.011773 -0.001771 -0.003058 +v 0.013072 -0.000244 -0.003229 +v 0.010324 -0.002454 -0.003214 +v 0.013437 -0.002172 -0.002362 +v 0.010423 -0.002494 0.003134 +v 0.008311 -0.003562 0.003811 +v 0.009656 0.001026 0.004203 +v 0.011773 0.001771 0.003058 +v 0.008531 0.003570 0.003562 +v 0.013433 -0.001269 -0.002957 +v 0.008516 -0.003570 -0.003576 +v 0.007675 0.001878 0.005491 +v 0.009063 0.002360 0.004085 +v 0.013433 0.001269 0.002957 +v 0.009041 -0.002232 -0.004183 +v 0.007838 -0.001968 -0.005285 +v 0.008017 -0.000379 0.005441 +v 0.007970 -0.001925 0.005141 +v 0.009970 -0.001831 0.003779 +v 0.013635 -0.002130 0.002418 +v 0.006258 0.003569 0.006267 +v 0.008815 0.002444 -0.004212 +v 0.012787 0.002510 -0.002131 +v 0.009474 0.000724 -0.004395 +v 0.007783 -0.000712 -0.005640 +v 0.011669 0.001315 -0.003298 +v 0.013440 0.001901 -0.002593 +v 0.013459 0.000891 -0.003085 +v 0.006363 -0.003571 -0.006160 +v 0.013882 -0.002949 0.001223 +v -0.009486 -0.000631 -0.000946 +v -0.009449 -0.001249 0.000659 +v -0.009522 0.000723 0.000006 +v 0.006048 -0.001903 -0.007155 +v 0.006105 -0.000453 -0.007339 +v 0.005831 0.000113 0.007602 +v -0.000982 -0.002304 0.009227 +v -0.001647 -0.003570 0.008686 +v 0.000823 -0.003570 0.008818 +v -0.009197 -0.002484 -0.000649 +v -0.008796 -0.003571 -0.000922 +v -0.008784 -0.003567 0.001188 +v -0.008219 -0.003572 -0.003341 +v -0.008917 -0.002023 -0.002834 +v -0.004828 -0.003570 -0.007452 +v -0.006859 -0.003571 -0.005586 +v -0.006014 -0.001960 -0.007203 +v 0.003630 0.003575 -0.008065 +v 0.003064 0.001998 -0.008832 +v 0.000970 0.003571 -0.008816 +v -0.002414 0.003572 -0.008566 +v -0.004444 0.002433 -0.008098 +v -0.005061 0.003572 -0.007262 +v -0.006439 0.003571 -0.006067 +v -0.007389 0.002615 -0.005463 +v -0.007791 0.003571 -0.004210 +v -0.007916 0.003570 0.003955 +v -0.008747 0.003568 0.001514 +v -0.008875 0.001896 0.003018 +v 0.005779 -0.003566 0.006758 +v 0.005396 0.003571 -0.007027 +v 0.006118 -0.001908 0.007097 +v 0.004499 0.001945 -0.008208 +v 0.004441 -0.003566 -0.007697 +v 0.005776 0.001643 0.007454 +v 0.004944 0.003564 0.007366 +v 0.003199 0.002195 0.008752 +v 0.003607 0.003572 0.008089 +v 0.000586 0.003573 0.008860 +v 0.004535 -0.002033 0.008149 +v 0.003049 -0.003571 0.008343 +v 0.002413 -0.002119 0.009018 +v 0.000852 0.001949 -0.009337 +v -0.001716 0.001114 -0.009375 +v -0.003081 0.001552 -0.008910 +v 0.002326 0.000274 -0.009284 +v -0.005133 0.000512 -0.008047 +v 0.004480 -0.000649 -0.008420 +v -0.000169 0.000000 -0.009550 +v -0.003703 -0.000420 -0.008801 +v 0.002405 -0.001783 -0.009099 +v -0.000541 -0.001844 -0.009385 +v -0.003351 -0.001827 -0.008782 +v 0.001338 -0.003571 -0.008798 +v -0.002072 -0.003570 -0.008624 +v 0.000669 -0.001001 0.009491 +v 0.002410 0.000356 0.009250 +v 0.000942 0.001468 0.009390 +v -0.001023 0.000632 0.009508 +v -0.006116 -0.001296 0.007254 +v -0.004508 0.000570 0.008407 +v -0.005721 0.001521 0.007510 +v 0.003813 -0.000345 0.008762 +v -0.002728 0.000712 0.009124 +v -0.003446 0.002301 0.008625 +v -0.001712 0.003562 0.008709 +v -0.004226 0.003572 0.007811 +v -0.006599 0.003564 0.005969 +v -0.005993 0.001708 -0.007242 +v -0.006902 0.001137 0.006528 +v -0.006861 0.000458 -0.006667 +v -0.007826 -0.002294 -0.004985 +v -0.007796 -0.000710 -0.005484 +v -0.008195 0.001962 0.004495 +v -0.008203 0.000315 0.004903 +v -0.008199 0.001417 -0.004710 +v -0.008828 0.002454 -0.002702 +v -0.008656 0.003572 -0.001860 +v -0.008680 -0.000472 -0.003935 +v -0.008882 0.001007 -0.003372 +v -0.007156 -0.003569 0.005233 +v -0.008225 -0.001863 0.004529 +v -0.008252 -0.003570 0.003214 +v -0.005677 -0.003569 0.006800 +v -0.007020 -0.001420 0.006325 +v -0.003087 -0.001743 0.008896 +v -0.003730 -0.003571 0.008030 +v -0.004776 -0.001589 0.008126 +v -0.008964 -0.000593 0.003265 +v -0.009134 -0.001840 0.002109 +v -0.009314 -0.000571 -0.002080 +v -0.009328 0.001648 -0.001318 +v -0.008855 0.003567 -0.000241 +v -0.009329 0.001776 0.001151 +v -0.009379 0.000443 0.001756 +v -0.002263 -0.003572 0.006279 +v 0.006359 -0.003572 -0.002027 +v 0.006452 -0.003572 0.001866 +v -0.004773 -0.003572 0.004619 +v -0.003604 -0.003572 -0.005618 +v -0.005697 -0.003572 -0.003415 +v 0.000758 -0.003572 0.006598 +v 0.003983 -0.003572 0.005408 +v 0.002263 -0.003572 -0.006279 +v 0.004773 -0.003572 -0.004619 +v -0.006359 -0.003572 0.002027 +v -0.000758 -0.003572 -0.006598 +v -0.006570 -0.003572 -0.000975 +v -0.003604 0.003572 0.005618 +v -0.000758 0.003572 0.006598 +v -0.005930 0.003572 0.003063 +v -0.006641 0.003572 0.000109 +v 0.006359 0.003572 0.002027 +v 0.006452 0.003572 -0.001866 +v -0.004773 0.003572 -0.004619 +v -0.006177 0.003572 -0.002440 +v 0.004773 0.003572 0.004619 +v 0.002263 0.003572 0.006279 +v -0.002263 0.003572 -0.006279 +v 0.000758 0.003572 -0.006598 +v 0.003983 0.003572 -0.005408 +v -0.006500 -0.000543 -0.000692 +v -0.006526 0.000076 0.000676 +v -0.006531 0.000646 -0.000088 +v -0.002224 0.004763 -0.003934 +v -0.003387 0.004195 -0.003733 +v -0.003772 0.004764 -0.002504 +v -0.004896 0.004115 -0.001467 +v -0.004495 0.004761 -0.000394 +v 0.004039 0.004761 0.002003 +v 0.002844 0.004761 0.003530 +v 0.004114 0.004136 0.003002 +v 0.006494 0.000820 -0.000422 +v 0.006541 -0.000383 -0.000234 +v 0.006343 0.000575 -0.001616 +v 0.006399 -0.001389 -0.000531 +v 0.006385 -0.000806 0.001331 +v 0.006519 0.000184 0.000661 +v 0.006116 -0.002374 0.000277 +v 0.006324 -0.000603 -0.001630 +v 0.005781 0.000151 -0.003104 +v 0.005817 -0.001167 -0.002823 +v 0.006022 0.002275 0.001269 +v 0.006145 0.002283 -0.000337 +v 0.005542 0.003457 0.000749 +v 0.006399 0.001324 0.000548 +v 0.005724 0.002419 -0.002152 +v 0.006102 0.001645 -0.001772 +v 0.005576 0.001480 -0.003130 +v 0.005886 -0.002658 0.001258 +v 0.005397 -0.003746 -0.000030 +v 0.004495 -0.004761 -0.000394 +v 0.004227 -0.004756 -0.001628 +v 0.005242 -0.003656 -0.001469 +v 0.005938 -0.002442 -0.001442 +v 0.004454 -0.004753 0.000830 +v 0.004966 -0.003810 0.001993 +v 0.005979 -0.001361 0.002336 +v 0.003701 -0.004763 0.002630 +v 0.005255 -0.002726 0.002852 +v 0.004519 0.004756 0.000334 +v 0.004928 0.003902 0.001927 +v 0.005494 0.003507 -0.000832 +v 0.004334 0.004757 -0.001332 +v 0.005136 0.003520 -0.002096 +v 0.003851 0.004756 -0.002382 +v 0.004064 0.003979 -0.003271 +v 0.004114 -0.004088 0.003066 +v 0.005504 -0.001374 0.003334 +v 0.003210 -0.004738 -0.003271 +v 0.004737 -0.003577 -0.002824 +v 0.005633 0.002445 0.002313 +v 0.005590 -0.002494 -0.002362 +v 0.003946 -0.003247 0.004139 +v 0.002166 -0.004761 0.003968 +v 0.002682 -0.003789 0.004664 +v 0.004061 -0.002253 0.004660 +v 0.006096 0.000076 0.002443 +v 0.006152 0.001074 0.002069 +v 0.002826 0.004758 -0.003519 +v 0.004829 -0.000960 0.004353 +v 0.003321 0.003759 0.004236 +v 0.005189 0.002391 0.003258 +v 0.003283 0.003706 -0.004316 +v 0.005426 0.000433 0.003670 +v 0.002799 -0.002487 0.005389 +v 0.004422 0.002756 0.004020 +v 0.000658 -0.004748 0.004527 +v 0.003769 -0.000635 0.005352 +v 0.001285 -0.002854 0.005794 +v 0.000258 -0.004763 -0.004510 +v 0.001837 -0.003898 -0.004969 +v 0.002224 -0.004763 -0.003934 +v 0.003871 -0.003225 -0.004232 +v 0.001236 0.003951 -0.005121 +v -0.000149 0.004763 -0.004524 +v 0.001770 0.004761 -0.004156 +v 0.004706 0.002752 -0.003663 +v -0.001604 -0.000541 -0.006349 +v -0.000665 0.000764 -0.006490 +v 0.000470 -0.000978 -0.006494 +v 0.001420 0.000544 -0.006403 +v 0.002039 -0.001307 -0.006116 +v 0.002656 -0.000049 -0.006004 +v 0.004865 -0.000728 -0.004356 +v 0.003932 0.000082 -0.005263 +v 0.004809 0.001000 -0.004376 +v 0.003438 -0.001129 -0.005473 +v -0.000791 -0.001698 -0.006293 +v 0.003630 -0.002126 -0.005050 +v 0.000009 -0.002727 -0.005976 +v 0.001107 -0.002976 -0.005758 +v 0.005051 -0.001904 -0.003748 +v 0.002489 -0.003068 -0.005242 +v -0.000010 -0.004057 -0.005162 +v -0.001725 -0.003447 -0.005333 +v -0.001537 -0.004761 -0.004269 +v -0.001789 -0.002138 -0.005946 +v -0.001704 -0.003765 0.005133 +v -0.001877 -0.004763 0.004146 +v -0.000049 -0.003326 0.005679 +v -0.001468 -0.002516 0.005880 +v -0.000894 -0.001541 0.006316 +v 0.000677 -0.001410 0.006385 +v 0.002111 -0.000830 0.006189 +v -0.002112 -0.000828 0.006189 +v 0.000018 -0.000130 0.006575 +v 0.002516 0.000868 0.006019 +v -0.001074 0.001043 0.006402 +v 0.001319 0.000983 0.006355 +v 0.004854 0.000863 0.004339 +v 0.003797 0.001400 0.005193 +v 0.000195 0.001817 0.006312 +v -0.001405 0.002486 0.005911 +v -0.002649 0.002045 0.005677 +v 0.001165 0.002780 0.005848 +v 0.002982 0.002519 0.005286 +v -0.000518 0.003411 0.005590 +v 0.002309 0.003588 0.004982 +v -0.002061 0.003708 0.005026 +v 0.000966 0.003933 0.005182 +v 0.001391 0.004761 0.004299 +v -0.000411 0.004761 0.004505 +v -0.002166 0.004761 0.003968 +v -0.003017 0.000177 0.005836 +v -0.003133 -0.002434 0.005248 +v -0.002826 -0.004758 -0.003519 +v -0.003338 -0.003488 -0.004468 +v -0.003123 -0.002103 -0.005380 +v -0.003248 -0.000899 -0.005643 +v -0.002213 0.000517 -0.006166 +v -0.003317 0.003692 0.004310 +v -0.003321 -0.003759 0.004236 +v -0.003733 0.000338 -0.005394 +v -0.003325 0.004762 0.003035 +v -0.004061 0.002254 0.004660 +v -0.003795 0.001000 0.005260 +v -0.003560 -0.001397 0.005333 +v -0.003758 -0.004757 0.002580 +v -0.003851 -0.004756 -0.002382 +v -0.004061 -0.003979 -0.003265 +v -0.004113 0.004093 0.003067 +v -0.001048 0.003952 -0.005157 +v -0.002729 0.003552 -0.004808 +v -0.004019 0.003079 -0.004182 +v -0.001735 0.002993 -0.005575 +v 0.000541 0.003178 -0.005716 +v 0.002762 0.002629 -0.005359 +v 0.003928 0.002304 -0.004743 +v -0.002821 0.001854 -0.005660 +v -0.000799 0.002328 -0.006099 +v 0.001759 0.002153 -0.005952 +v 0.000437 0.001641 -0.006346 +v 0.003288 0.001140 -0.005566 +v -0.004086 0.001691 -0.004854 +v -0.004175 0.004748 0.001804 +v -0.004387 -0.000378 0.004867 +v -0.004317 -0.002032 0.004532 +v -0.004368 -0.003406 0.003520 +v -0.004509 -0.001888 -0.004392 +v -0.004733 0.003208 0.003238 +v -0.004618 -0.002875 -0.003679 +v -0.004560 -0.000696 -0.004666 +v -0.004691 0.003559 -0.002935 +v -0.004803 0.001010 0.004369 +v -0.004995 0.000684 -0.004213 +v -0.005106 0.001961 -0.003630 +v -0.005328 -0.002214 0.003159 +v -0.005258 -0.003496 0.001833 +v -0.004401 -0.004755 0.001087 +v -0.004427 -0.004759 -0.001051 +v -0.005134 -0.003522 -0.002094 +v -0.005484 0.003609 -0.000326 +v -0.004454 0.004753 0.000830 +v -0.005512 0.003337 0.001348 +v -0.005553 0.001344 0.003257 +v -0.005378 -0.000373 0.003776 +v -0.005473 -0.003621 0.000353 +v -0.005256 -0.003863 -0.000639 +v -0.005370 -0.000902 -0.003677 +v -0.005584 0.002143 -0.002700 +v -0.005607 0.002969 -0.001673 +v -0.005686 0.002165 0.002468 +v -0.005694 -0.002227 -0.002435 +v -0.005704 0.000496 -0.003227 +v -0.005862 -0.002245 0.001961 +v -0.005844 -0.002813 -0.001009 +v -0.005954 0.002338 0.001448 +v -0.006061 0.002285 -0.001139 +v -0.006032 -0.000441 0.002559 +v -0.006122 -0.002331 0.000410 +v -0.006169 -0.000786 -0.002121 +v -0.006140 0.000698 -0.002218 +v -0.006247 0.001974 0.000426 +v -0.006245 0.001012 0.001747 +v -0.006344 -0.001044 0.001304 +v -0.006287 -0.001719 -0.000754 +v -0.006389 0.000741 -0.001344 +v -0.006375 0.000025 0.001525 +v -0.006458 -0.001106 0.000126 +v -0.002764 -0.004762 -0.002205 +v -0.001347 -0.004762 -0.003252 +v -0.003224 -0.004762 0.001553 +v -0.001409 -0.004762 0.003258 +v -0.003460 -0.004762 -0.000631 +v 0.003224 -0.004762 0.001553 +v 0.001191 -0.004762 0.003373 +v 0.003460 -0.004762 -0.000631 +v 0.002522 -0.004762 -0.002536 +v 0.000396 -0.004762 -0.003514 +v -0.003308 0.004761 -0.001426 +v -0.003224 0.004762 0.001553 +v -0.001361 0.004762 0.003285 +v 0.001247 0.004762 0.003344 +v -0.001534 0.004762 -0.003186 +v 0.002522 0.004762 -0.002536 +v 0.000396 0.004762 -0.003514 +v 0.003460 0.004762 -0.000631 +v 0.003224 0.004762 0.001553 +v 0.000497 -0.004446 0.003155 +v 0.000026 0.004448 0.003254 +v 0.001845 -0.004443 0.002621 +v 0.001951 0.004445 0.002554 +v 0.003025 -0.004444 0.001144 +v 0.003066 0.004444 0.001005 +v 0.003130 -0.004445 -0.000600 +v 0.003094 0.004446 -0.000814 +v 0.002584 -0.004444 -0.001911 +v 0.002204 0.004440 -0.002337 +v 0.001163 -0.004444 -0.002994 +v 0.000962 0.004445 -0.003037 +v -0.000388 0.004446 -0.003182 +v -0.000432 -0.004444 -0.003168 +v -0.002078 -0.004438 -0.002473 +v -0.002101 0.004444 -0.002456 +v -0.003094 -0.004446 -0.000814 +v -0.003101 0.004441 -0.000784 +v -0.003144 -0.004446 0.000540 +v -0.003050 0.004442 0.001046 +v -0.002578 -0.004444 0.001916 +v -0.001916 0.004444 0.002578 +v -0.001150 -0.004440 0.003000 +v 0.344296 0.002059 0.007332 +v 0.344197 0.003566 0.006640 +v 0.341616 0.002856 0.004201 +v 0.338676 0.003567 -0.000590 +v 0.340140 0.003568 -0.002188 +v 0.338327 0.002976 -0.001896 +v 0.338676 -0.003567 0.000590 +v 0.340140 -0.003568 0.002188 +v 0.338418 -0.003140 0.001622 +v 0.337704 -0.003335 -0.000487 +v 0.338951 -0.003570 -0.000986 +v 0.336575 -0.002965 0.001258 +v 0.336329 -0.003206 -0.000259 +v 0.338028 0.000001 0.003430 +v 0.337008 0.001420 0.002912 +v 0.336223 0.000402 0.003190 +v 0.336636 0.003128 -0.000732 +v 0.336637 0.003190 0.000302 +v 0.338734 0.003561 0.000673 +v 0.338744 -0.002976 -0.002092 +v 0.338314 0.002910 0.001973 +v 0.339824 0.003572 0.001888 +v 0.339764 -0.000952 0.003906 +v 0.340100 0.000314 0.004145 +v 0.338364 -0.002511 0.002466 +v 0.336615 -0.002289 0.002263 +v 0.336950 -0.002998 -0.001249 +v 0.339482 0.000749 -0.003826 +v 0.337013 0.000120 -0.003240 +v 0.337649 0.001297 -0.003073 +v 0.337043 0.002559 -0.002024 +v 0.336625 0.002962 0.001226 +v 0.336371 -0.001291 0.002950 +v 0.339797 -0.002452 0.003221 +v 0.340695 -0.003568 -0.002710 +v 0.339590 0.002379 -0.003136 +v 0.339695 0.002497 0.003136 +v 0.341778 0.003569 0.003757 +v 0.338018 -0.001325 0.003164 +v 0.341702 -0.003568 0.003694 +v 0.342068 0.001790 -0.005130 +v 0.341063 0.000655 -0.004673 +v 0.336342 0.001938 -0.002568 +v 0.341763 0.003562 -0.003774 +v 0.340087 -0.002332 -0.003422 +v 0.342225 -0.003557 -0.004289 +v 0.341060 -0.001681 0.004425 +v 0.342200 -0.000916 0.005480 +v 0.343702 0.000426 0.007074 +v 0.342603 0.000866 0.005877 +v 0.341163 0.001171 0.004607 +v 0.338927 0.001676 0.003307 +v 0.336922 0.002375 0.002171 +v 0.342358 -0.002544 0.005123 +v 0.343860 -0.003569 0.006265 +v 0.341992 -0.001399 -0.005153 +v 0.343452 -0.003572 -0.005796 +v 0.337120 -0.002478 -0.002099 +v 0.339689 -0.000883 -0.003873 +v 0.337612 -0.001301 -0.003095 +v 0.343998 0.001813 -0.007120 +v 0.342323 0.000004 -0.005661 +v 0.336270 -0.001329 -0.002935 +v 0.343895 0.003569 -0.006334 +v 0.359572 -0.000916 -0.001017 +v 0.359591 0.001035 -0.000539 +v 0.359644 0.000385 0.000346 +v 0.359590 -0.000980 0.000601 +v 0.343803 -0.001724 -0.006958 +v 0.344293 -0.001608 0.007428 +v 0.351102 0.002304 0.009227 +v 0.352669 0.003571 0.008516 +v 0.349297 0.003570 0.008818 +v 0.359322 0.002495 0.000696 +v 0.358931 0.003568 -0.000891 +v 0.358817 0.003571 0.001790 +v 0.358454 0.003572 -0.002986 +v 0.359250 0.002140 -0.001870 +v 0.352540 -0.003572 -0.008564 +v 0.353911 -0.002030 -0.008546 +v 0.355181 -0.003572 -0.007260 +v 0.356617 -0.003572 -0.005997 +v 0.357332 -0.002210 -0.005821 +v 0.357879 -0.003573 -0.004258 +v 0.358964 -0.003572 0.000486 +v 0.359304 -0.002491 -0.000684 +v 0.359233 -0.002649 0.001094 +v 0.358580 -0.003558 0.002713 +v 0.344724 -0.003571 -0.007026 +v 0.345299 -0.002118 -0.007931 +v 0.346818 -0.003575 -0.008229 +v 0.345555 0.003561 -0.007597 +v 0.345178 -0.003565 0.007368 +v 0.346994 -0.002318 0.008739 +v 0.346513 -0.003572 0.008089 +v 0.349204 -0.003575 0.008808 +v 0.346983 0.003573 0.008301 +v 0.347011 0.002457 0.008713 +v 0.346660 -0.001544 -0.008772 +v 0.349150 -0.003571 -0.008816 +v 0.349177 -0.001839 -0.009354 +v 0.351766 -0.001813 -0.009244 +v 0.344300 -0.000165 -0.007606 +v 0.347006 -0.000006 -0.009046 +v 0.349918 0.000000 -0.009566 +v 0.353212 0.000378 -0.009074 +v 0.355454 -0.000646 -0.007915 +v 0.344930 0.001134 -0.007942 +v 0.346658 0.001709 -0.008746 +v 0.349177 0.001836 -0.009355 +v 0.351766 0.001817 -0.009243 +v 0.353809 0.001817 -0.008633 +v 0.347739 0.003570 -0.008549 +v 0.349954 0.003571 -0.008837 +v 0.352192 0.003570 -0.008624 +v 0.354289 0.003570 -0.007800 +v 0.356078 0.003570 -0.006564 +v 0.355957 0.002274 -0.007211 +v 0.355847 0.000604 -0.007630 +v 0.356153 -0.002145 -0.007108 +v 0.346932 0.000802 0.008993 +v 0.345586 -0.000210 0.008435 +v 0.348075 -0.000711 0.009308 +v 0.349695 0.001190 0.009491 +v 0.350399 -0.000632 0.009527 +v 0.352567 0.000631 0.009219 +v 0.352496 -0.001791 0.009104 +v 0.354484 -0.001412 0.008422 +v 0.350025 -0.002140 0.009338 +v 0.355985 -0.000309 0.007579 +v 0.355970 -0.003558 0.006687 +v 0.351977 -0.003565 0.008655 +v 0.354346 -0.003572 0.007811 +v 0.357014 -0.003566 0.005570 +v 0.357474 -0.001587 0.005899 +v 0.357397 -0.000088 0.006197 +v 0.357143 0.001776 -0.006227 +v 0.357431 -0.000021 -0.006151 +v 0.357725 0.003567 -0.004565 +v 0.358037 -0.003570 0.003951 +v 0.358366 -0.001877 0.004445 +v 0.358299 0.001513 -0.004701 +v 0.358328 -0.000693 -0.004841 +v 0.358531 -0.002171 -0.004029 +v 0.358845 -0.000136 0.003943 +v 0.359011 0.001715 -0.003057 +v 0.358739 -0.003571 -0.002080 +v 0.357832 0.003571 0.004356 +v 0.358943 0.001776 0.003256 +v 0.356634 0.003570 0.005979 +v 0.357853 0.001809 0.005328 +v 0.355164 0.003573 0.007279 +v 0.356509 0.001934 0.006837 +v 0.353199 0.002419 0.008707 +v 0.354590 0.001607 0.008309 +v 0.358960 0.000011 -0.003599 +v 0.359258 -0.001404 0.002394 +v 0.359427 0.000050 -0.002158 +v 0.359309 -0.001623 -0.002016 +v 0.359481 0.000026 0.001831 +v 0.359496 0.001307 0.001253 +v 0.343599 0.003572 0.001424 +v 0.343865 0.003572 -0.002447 +v 0.351544 0.003572 0.006521 +v 0.354614 0.003572 0.004935 +v 0.355599 0.003572 -0.003811 +v 0.348904 0.003572 0.006506 +v 0.344660 0.003572 0.003740 +v 0.346516 0.003572 0.005618 +v 0.353734 0.003572 -0.005546 +v 0.348753 0.003572 -0.006476 +v 0.346309 0.003572 -0.005480 +v 0.351300 0.003572 -0.006569 +v 0.356771 0.003572 -0.000560 +v 0.356297 0.003572 0.002440 +v 0.349559 -0.003572 0.006651 +v 0.352960 -0.003572 0.006040 +v 0.355599 -0.003572 0.003811 +v 0.356771 -0.003572 0.000561 +v 0.346704 -0.003572 0.005696 +v 0.344502 -0.003572 0.003604 +v 0.354614 -0.003572 -0.004935 +v 0.356297 -0.003572 -0.002440 +v 0.343453 -0.003572 0.000312 +v 0.344026 -0.003572 -0.002641 +v 0.352320 -0.003572 -0.006243 +v 0.349808 -0.003572 -0.006667 +v 0.346137 -0.003572 -0.005409 +v 0.356620 0.000451 0.000813 +v 0.356623 -0.000814 0.000097 +v 0.356662 0.000008 -0.000356 +v 0.350650 0.004757 0.004507 +v 0.352409 0.004208 0.004477 +v 0.352646 0.004756 0.003764 +v 0.352180 -0.004758 -0.004053 +v 0.353373 -0.004086 -0.004019 +v 0.353886 -0.004760 -0.002537 +v 0.354898 -0.004103 -0.001866 +v 0.354632 -0.004758 -0.000277 +v 0.351621 -0.003690 0.005254 +v 0.349930 -0.004758 0.004546 +v 0.352261 -0.004760 0.003987 +v 0.347981 -0.003940 0.004825 +v 0.347767 -0.004761 0.003852 +v 0.343659 -0.000393 -0.001045 +v 0.343596 -0.000629 0.000143 +v 0.343619 0.000570 -0.000660 +v 0.343685 0.001268 0.000112 +v 0.343584 0.000201 0.000352 +v 0.343749 0.001095 0.001125 +v 0.343891 0.000571 -0.002018 +v 0.344088 0.002567 0.000221 +v 0.344306 -0.000390 -0.003037 +v 0.344609 0.001055 -0.003436 +v 0.344191 -0.002438 -0.001340 +v 0.343868 -0.001305 -0.001538 +v 0.344519 -0.001916 -0.002875 +v 0.344707 0.003681 -0.000596 +v 0.344523 0.003218 0.001326 +v 0.345058 0.004002 0.001205 +v 0.343912 -0.001702 0.001291 +v 0.343785 -0.001746 -0.000057 +v 0.344187 -0.002750 0.000543 +v 0.344744 -0.003571 0.001251 +v 0.343871 0.001789 -0.000882 +v 0.344749 -0.003490 -0.001432 +v 0.344995 -0.003185 -0.002580 +v 0.345618 0.004760 -0.000349 +v 0.345943 0.004761 -0.001673 +v 0.345203 0.003855 -0.002107 +v 0.344317 0.002697 -0.001485 +v 0.344159 0.002064 0.001878 +v 0.345863 0.004761 0.001575 +v 0.345781 0.003822 0.003147 +v 0.345617 -0.004756 0.000473 +v 0.345913 -0.004756 0.001712 +v 0.344758 -0.003748 -0.000765 +v 0.345777 -0.004763 -0.001212 +v 0.345060 0.003075 0.002886 +v 0.343667 -0.000155 0.001136 +v 0.344235 0.001045 0.002741 +v 0.345686 -0.004055 -0.002596 +v 0.346646 -0.004759 -0.002915 +v 0.346609 0.004760 -0.002852 +v 0.346753 0.004751 0.003054 +v 0.345033 0.002127 0.003546 +v 0.346564 -0.004754 0.002816 +v 0.345359 -0.003504 0.002888 +v 0.344450 -0.002337 0.002363 +v 0.345741 0.002798 0.004029 +v 0.344059 -0.000399 0.002529 +v 0.345312 0.003361 -0.003006 +v 0.347440 0.004746 0.003684 +v 0.347136 0.003517 0.004649 +v 0.347600 0.004758 -0.003794 +v 0.346234 0.003389 -0.004098 +v 0.344348 0.001963 -0.002471 +v 0.344867 0.000117 0.003961 +v 0.345688 0.001361 0.004639 +v 0.346197 -0.003540 0.003887 +v 0.346904 0.002367 0.005222 +v 0.346829 -0.003511 -0.004446 +v 0.345862 -0.002991 -0.004018 +v 0.348616 0.004752 0.004292 +v 0.348858 0.002863 0.005799 +v 0.346965 0.001112 0.005647 +v 0.349807 0.004763 -0.004511 +v 0.349154 0.003860 -0.005228 +v 0.347759 0.004029 -0.004570 +v 0.348316 -0.004759 -0.004191 +v 0.346073 0.001002 -0.005075 +v 0.347527 0.000246 -0.006039 +v 0.346066 -0.000508 -0.005135 +v 0.345166 0.000252 -0.004291 +v 0.351079 0.001753 -0.006277 +v 0.352028 0.000580 -0.006283 +v 0.349599 0.000078 -0.006565 +v 0.349121 0.001263 -0.006365 +v 0.347474 0.001489 -0.005828 +v 0.345304 0.001988 -0.004008 +v 0.349264 0.002441 -0.006032 +v 0.350863 0.002970 -0.005824 +v 0.347944 0.002789 -0.005525 +v 0.346805 0.002917 -0.004863 +v 0.350644 0.003984 -0.005186 +v 0.351793 0.004763 -0.004227 +v 0.352071 0.004111 -0.004715 +v 0.352526 0.002588 -0.005530 +v 0.352299 0.003335 0.005229 +v 0.350799 0.003292 0.005637 +v 0.349718 0.003944 0.005236 +v 0.352140 0.002099 0.005887 +v 0.350641 0.002201 0.006164 +v 0.348400 0.001667 0.006117 +v 0.349835 0.000688 0.006542 +v 0.352571 0.000448 0.006088 +v 0.350961 0.000848 0.006464 +v 0.348293 0.000232 0.006306 +v 0.347149 -0.000663 0.005822 +v 0.346157 0.000345 0.005227 +v 0.351747 -0.001126 0.006291 +v 0.348255 -0.000918 0.006242 +v 0.349885 -0.000906 0.006493 +v 0.346107 -0.000844 0.005115 +v 0.350859 -0.001831 0.006275 +v 0.345424 -0.001721 0.004280 +v 0.349169 -0.002242 0.006100 +v 0.344765 -0.001741 0.003366 +v 0.347585 -0.002523 0.005524 +v 0.346361 -0.002551 0.004760 +v 0.350652 -0.003267 0.005671 +v 0.344177 -0.001398 0.002413 +v 0.349170 -0.003437 0.005507 +v 0.352697 -0.003740 0.004735 +v 0.353256 0.003638 -0.004488 +v 0.353128 -0.002383 0.005338 +v 0.353373 0.004757 -0.003154 +v 0.353557 0.001984 -0.005217 +v 0.353693 0.000322 -0.005513 +v 0.352643 -0.000823 -0.006010 +v 0.353498 -0.001228 0.005506 +v 0.353354 0.002069 0.005324 +v 0.353848 -0.004745 0.002663 +v 0.354043 -0.003580 0.003887 +v 0.354012 0.000420 0.005285 +v 0.353681 0.003185 0.004543 +v 0.353755 0.004736 0.002802 +v 0.350632 -0.003823 -0.005313 +v 0.350433 -0.004763 -0.004511 +v 0.349105 -0.003271 -0.005638 +v 0.347813 -0.003457 -0.005071 +v 0.353135 -0.003214 -0.004884 +v 0.351496 -0.003035 -0.005673 +v 0.349929 -0.002624 -0.006022 +v 0.352554 -0.001850 -0.005827 +v 0.346666 -0.001688 -0.005347 +v 0.345153 -0.001270 -0.004124 +v 0.354236 -0.002287 -0.004556 +v 0.347728 -0.001484 -0.005944 +v 0.354196 -0.001192 -0.005014 +v 0.350882 -0.001128 -0.006431 +v 0.349121 -0.001385 -0.006340 +v 0.354632 -0.002034 0.004341 +v 0.354607 -0.000713 0.004751 +v 0.354563 0.001549 0.004594 +v 0.354277 0.003174 0.003916 +v 0.354026 0.003397 0.003995 +v 0.354175 0.003703 0.003546 +v 0.354644 0.003788 -0.002922 +v 0.354469 0.002705 -0.004035 +v 0.354600 0.000237 -0.004807 +v 0.354533 -0.003158 -0.003710 +v 0.354226 0.004762 -0.001861 +v 0.354806 0.001510 -0.004342 +v 0.354774 0.003044 0.003534 +v 0.354608 0.003080 0.003623 +v 0.354608 0.003484 0.003237 +v 0.355343 -0.001492 -0.003710 +v 0.355266 -0.003023 -0.002802 +v 0.355211 -0.003944 0.001328 +v 0.354382 -0.004764 0.001527 +v 0.355309 -0.002896 0.002798 +v 0.355428 0.000440 0.003844 +v 0.355485 0.002825 0.002552 +v 0.355267 0.003807 0.001471 +v 0.354230 0.004755 0.001937 +v 0.354592 0.004754 -0.000728 +v 0.355164 0.003792 -0.001900 +v 0.355625 -0.000201 -0.003575 +v 0.355431 -0.003830 -0.000500 +v 0.355345 -0.002262 0.003321 +v 0.355782 0.001375 0.003046 +v 0.354604 0.004756 0.000576 +v 0.355543 0.003674 -0.000494 +v 0.355390 0.002811 -0.002744 +v 0.355534 0.001262 -0.003493 +v 0.355797 -0.001092 0.003122 +v 0.356014 -0.002800 -0.000805 +v 0.355877 -0.003109 0.000513 +v 0.355831 -0.002674 0.001825 +v 0.355896 0.003056 0.000671 +v 0.356024 0.002699 -0.001048 +v 0.355999 -0.001126 -0.002646 +v 0.356066 -0.002047 -0.001898 +v 0.356159 -0.001730 0.001941 +v 0.356196 -0.000073 0.002507 +v 0.356061 0.001993 -0.001949 +v 0.355921 0.001298 -0.002828 +v 0.356251 0.001522 0.001802 +v 0.356318 0.000563 -0.002108 +v 0.356407 -0.001852 0.000416 +v 0.356369 0.001974 0.000395 +v 0.356478 -0.000605 -0.001511 +v 0.356478 -0.001434 -0.000734 +v 0.356506 -0.000747 0.001288 +v 0.356560 0.001183 -0.000416 +v 0.356561 0.000670 -0.001060 +v 0.352744 0.004762 0.002344 +v 0.353562 0.004762 0.000803 +v 0.351167 0.004762 0.003390 +v 0.351288 0.004762 -0.003337 +v 0.353279 0.004761 -0.001746 +v 0.348740 0.004761 -0.003331 +v 0.346656 0.004761 0.001000 +v 0.346934 0.004762 -0.001539 +v 0.348567 0.004762 0.003224 +v 0.353513 -0.004762 -0.000921 +v 0.353562 -0.004762 0.000803 +v 0.351288 -0.004762 0.003337 +v 0.348675 -0.004761 0.003291 +v 0.352745 -0.004762 0.002345 +v 0.346687 -0.004762 -0.000829 +v 0.347534 -0.004762 -0.002382 +v 0.352620 -0.004762 -0.002501 +v 0.346835 -0.004762 0.001361 +v 0.350907 -0.004762 -0.003447 +v 0.348952 -0.004762 -0.003337 +v 0.350070 0.004448 0.003194 +v 0.348970 -0.004440 0.003000 +v 0.348756 0.004446 0.002901 +v 0.347476 -0.004446 0.001841 +v 0.347630 0.004444 0.001998 +v 0.347015 0.004446 0.000782 +v 0.346965 -0.004446 0.000450 +v 0.347089 0.004444 -0.001129 +v 0.347026 -0.004446 -0.000815 +v 0.348041 -0.004438 -0.002472 +v 0.348319 0.004444 -0.002661 +v 0.349687 -0.004444 -0.003168 +v 0.349581 0.004445 -0.003136 +v 0.350901 0.004445 -0.003118 +v 0.351207 -0.004446 -0.003016 +v 0.352224 0.004446 -0.002400 +v 0.352582 -0.004445 -0.002063 +v 0.353159 0.004442 -0.001075 +v 0.353239 -0.004444 -0.000685 +v 0.353253 0.004445 0.000635 +v 0.353243 -0.004444 0.000672 +v 0.352692 0.004446 0.001902 +v 0.352766 -0.004446 0.001776 +v 0.351885 -0.004444 0.002667 +v 0.351453 0.004445 0.002924 +v 0.350617 -0.004446 0.003155 +v 0.329256 0.004637 -0.001573 +v 0.329257 0.004737 0.001397 +v 0.329256 0.003064 0.003820 +v 0.329256 0.003495 -0.003387 +v 0.329257 0.001397 -0.004737 +v 0.329256 0.001186 0.004720 +v 0.329257 -0.001397 0.004737 +v 0.329256 -0.001186 -0.004720 +v 0.329256 -0.003064 -0.003819 +v 0.329256 -0.003495 0.003387 +v 0.329256 -0.004637 0.001573 +v 0.329257 -0.004737 -0.001397 +v 0.327060 -0.000552 0.003405 +v 0.327060 0.001139 -0.003183 +v 0.327060 -0.000851 -0.003302 +v 0.327060 0.003105 0.001427 +v 0.327060 0.003331 -0.000589 +v 0.327060 0.002580 -0.002194 +v 0.327060 0.001736 0.002906 +v 0.327060 -0.002580 -0.002194 +v 0.327060 -0.002580 0.002194 +v 0.327060 -0.003443 -0.000000 +v 0.021756 -0.001186 0.004720 +v 0.021756 -0.001776 -0.004563 +v 0.021756 -0.003820 -0.003064 +v 0.021756 0.004854 0.000349 +v 0.021756 0.002731 -0.004115 +v 0.021756 0.004115 0.002731 +v 0.021756 0.004563 -0.001776 +v 0.021756 0.001397 0.004737 +v 0.021756 0.000349 -0.004854 +v 0.021756 -0.004720 -0.001186 +v 0.021755 -0.004737 0.001397 +v 0.021756 -0.003064 0.003820 +v 0.024000 0.002793 -0.001971 +v 0.024000 0.003392 0.000314 +v 0.024000 0.002580 0.002194 +v 0.024000 0.000851 0.003302 +v 0.024000 0.001139 -0.003183 +v 0.024000 -0.000851 -0.003302 +v 0.024000 -0.001763 0.002972 +v 0.024000 -0.002580 -0.002194 +v 0.024000 -0.003049 0.001417 +v 0.024000 -0.003399 -0.000285 +v 0.320754 -0.006349 0.000553 +v 0.030258 -0.006157 -0.001647 +v 0.320754 -0.006156 -0.001652 +v 0.030258 -0.005222 -0.003654 +v 0.320754 -0.005220 -0.003657 +v 0.030258 -0.003657 -0.005220 +v 0.320754 -0.003654 -0.005222 +v 0.030258 -0.001652 -0.006156 +v 0.320754 -0.001648 -0.006157 +v 0.030258 0.000553 -0.006349 +v 0.320765 0.001117 -0.006314 +v 0.030247 0.003203 -0.005555 +v 0.320754 0.003657 -0.005220 +v 0.030258 0.005220 -0.003657 +v 0.320765 0.005555 -0.003203 +v 0.030247 0.006314 -0.001117 +v 0.320754 0.006349 -0.000553 +v 0.030258 0.006157 0.001647 +v 0.320754 0.006156 0.001652 +v 0.030258 0.005222 0.003654 +v 0.320754 0.005220 0.003657 +v 0.030258 0.003657 0.005220 +v 0.320765 0.003203 0.005555 +v 0.030247 0.001117 0.006314 +v 0.320754 0.000553 0.006349 +v 0.030258 -0.001647 0.006157 +v 0.320754 -0.001652 0.006156 +v 0.030258 -0.003654 0.005222 +v 0.320754 -0.003657 0.005220 +v 0.030258 -0.005220 0.003657 +v 0.320765 -0.005555 0.003203 +v 0.030247 -0.006314 0.001117 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vn 0.6385 0.1744 -0.7496 +vn 0.6752 0.3227 -0.6633 +vn 0.6595 0.1875 -0.7280 +vn 0.1535 -0.9820 -0.1102 +vn 0.2226 -0.9302 -0.2919 +vn 0.2564 -0.8102 -0.5271 +vn 0.1115 -0.9736 0.1990 +vn 0.1833 -0.9517 0.2463 +vn 0.1499 0.9826 0.1093 +vn 0.2226 0.9302 0.2919 +vn 0.2547 0.8087 0.5302 +vn 0.1911 0.9510 -0.2429 +vn 0.1866 0.9514 -0.2452 +vn 0.0925 0.9956 0.0172 +vn 0.0789 -0.9846 -0.1560 +vn 0.4281 -0.0311 0.9032 +vn 0.2749 -0.3932 0.8774 +vn 0.1095 0.0654 0.9918 +vn 0.0707 -0.2693 0.9605 +vn 0.0976 0.9026 0.4192 +vn 0.2636 0.8235 -0.5023 +vn 0.0886 -0.8748 -0.4763 +vn 0.2219 -0.7700 0.5982 +vn 0.0489 0.9072 -0.4178 +vn 0.4114 0.5543 0.7235 +vn 0.0911 0.6804 0.7271 +vn 0.4012 0.5693 -0.7176 +vn 0.5356 0.5776 -0.6160 +vn 0.4506 -0.1995 -0.8702 +vn 0.3508 -0.0272 -0.9360 +vn 0.2667 -0.4703 -0.8413 +vn 0.1047 -0.0705 -0.9920 +vn 0.4170 -0.5530 -0.7213 +vn 0.0902 -0.6737 -0.7335 +vn 0.4134 -0.5958 0.6886 +vn 0.5742 -0.4761 0.6661 +vn 0.5077 0.2084 0.8360 +vn 0.2650 0.4684 0.8428 +vn 0.5568 0.5158 0.6511 +vn 0.0688 -0.3907 -0.9179 +vn 0.5603 -0.5118 -0.6512 +vn 0.6673 0.2331 0.7074 +vn 0.5302 0.4298 0.7309 +vn 0.0688 0.3907 0.9179 +vn 0.5272 -0.4403 -0.7267 +vn 0.6638 -0.2682 -0.6982 +vn 0.6327 -0.0385 0.7734 +vn 0.6420 -0.2839 0.7122 +vn 0.4567 -0.3567 0.8150 +vn 0.0765 -0.6608 0.7467 +vn 0.6709 0.2895 0.6827 +vn 0.5940 0.3938 -0.7015 +vn 0.1950 0.7540 -0.6272 +vn 0.5038 0.1386 -0.8526 +vn 0.6821 -0.0782 -0.7270 +vn 0.2848 0.3512 -0.8919 +vn 0.0794 0.6140 -0.7853 +vn 0.0699 0.2659 -0.9615 +vn 0.6661 -0.3083 -0.6792 +vn 0.0234 -0.8864 0.4624 +vn -0.9932 -0.0680 -0.0945 +vn -0.9884 -0.1338 0.0725 +vn -0.9974 0.0719 -0.0015 +vn 0.6180 -0.2114 -0.7572 +vn 0.6328 -0.0266 -0.7738 +vn 0.6025 0.0110 0.7981 +vn -0.0996 -0.2313 0.9678 +vn -0.1828 -0.3278 0.9269 +vn 0.0793 -0.2978 0.9513 +vn -0.9638 -0.2578 -0.0675 +vn -0.9370 -0.3306 -0.1130 +vn -0.9470 -0.2951 0.1268 +vn -0.8783 -0.3171 -0.3579 +vn -0.9306 -0.2174 -0.2944 +vn -0.5093 -0.3017 -0.8060 +vn -0.7290 -0.3166 -0.6069 +vn -0.6267 -0.1993 -0.7533 +vn 0.3772 0.3249 -0.8673 +vn 0.3166 0.2095 -0.9251 +vn 0.0883 0.3138 -0.9454 +vn -0.2366 0.2987 -0.9246 +vn -0.4596 0.2597 -0.8493 +vn -0.5435 0.3190 -0.7764 +vn -0.6847 0.3093 -0.6599 +vn -0.7683 0.2709 -0.5799 +vn -0.8412 0.3149 -0.4397 +vn -0.8498 0.3152 0.4226 +vn -0.9375 0.3014 0.1738 +vn -0.9267 0.1982 0.3192 +vn 0.6109 -0.3091 0.7289 +vn 0.5813 0.3094 -0.7526 +vn 0.6366 -0.1930 0.7467 +vn 0.4750 0.1851 -0.8603 +vn 0.4668 -0.2745 -0.8407 +vn 0.5947 0.1758 0.7845 +vn 0.5305 0.2727 0.8026 +vn 0.3369 0.2296 0.9131 +vn 0.3759 0.3092 0.8736 +vn 0.0609 0.2739 0.9598 +vn 0.4755 -0.2191 0.8520 +vn 0.3422 -0.3117 0.8865 +vn 0.2477 -0.2146 0.9448 +vn 0.0718 0.2105 -0.9749 +vn -0.1682 0.1133 -0.9792 +vn -0.3396 0.1611 -0.9267 +vn 0.2432 0.0218 -0.9697 +vn -0.5332 0.0365 -0.8452 +vn 0.4651 -0.0680 -0.8826 +vn -0.0075 -0.0116 -0.9999 +vn -0.3850 -0.0455 -0.9218 +vn 0.2545 -0.1903 -0.9482 +vn -0.0605 -0.1940 -0.9791 +vn -0.3469 -0.1928 -0.9179 +vn 0.1400 -0.3011 -0.9433 +vn -0.2165 -0.3099 -0.9258 +vn 0.0650 -0.1066 0.9922 +vn 0.2466 0.0361 0.9684 +vn 0.0887 0.1660 0.9821 +vn -0.1097 0.0732 0.9913 +vn -0.6386 -0.1343 0.7577 +vn -0.4746 0.0491 0.8788 +vn -0.5933 0.1654 0.7878 +vn 0.4119 -0.0270 0.9108 +vn -0.2793 0.0703 0.9576 +vn -0.3496 0.2385 0.9060 +vn -0.1697 0.2624 0.9499 +vn -0.4719 0.3014 0.8285 +vn -0.7098 0.2775 0.6474 +vn -0.6304 0.1950 -0.7514 +vn -0.7283 0.1147 0.6755 +vn -0.7192 0.0428 -0.6934 +vn -0.8158 -0.2440 -0.5244 +vn -0.8145 -0.0725 -0.5756 +vn -0.8494 0.2094 0.4844 +vn -0.8550 0.0305 0.5177 +vn -0.8586 0.1378 -0.4938 +vn -0.9178 0.2644 -0.2961 +vn -0.9264 0.3191 -0.1999 +vn -0.9031 -0.0400 -0.4275 +vn -0.9302 0.0985 -0.3537 +vn -0.7650 -0.2880 0.5761 +vn -0.8579 -0.1985 0.4739 +vn -0.8907 -0.2952 0.3458 +vn -0.6191 -0.2806 0.7335 +vn -0.7398 -0.1600 0.6535 +vn -0.3130 -0.1729 0.9339 +vn -0.4065 -0.3042 0.8615 +vn -0.4977 -0.1694 0.8506 +vn -0.9382 -0.0552 0.3416 +vn -0.9535 -0.1997 0.2256 +vn -0.9737 -0.0530 -0.2217 +vn -0.9758 0.1728 -0.1338 +vn -0.9595 0.2803 -0.0276 +vn -0.9740 0.1973 0.1112 +vn -0.9811 0.0325 0.1910 +vn -0.0001 -1.0000 0.0006 +vn 0.0000 -1.0000 0.0008 +vn -0.0004 -1.0000 0.0006 +vn 0.0011 -1.0000 -0.0000 +vn 0.0016 -1.0000 0.0016 +vn -0.0010 -1.0000 0.0007 +vn -0.0013 -1.0000 0.0008 +vn -0.0002 -1.0000 -0.0005 +vn -0.0003 -1.0000 -0.0007 +vn -0.0001 -1.0000 -0.0002 +vn -0.0001 -1.0000 0.0007 +vn 0.0011 -1.0000 0.0002 +vn -0.0001 -1.0000 -0.0001 +vn -0.0001 -1.0000 0.0009 +vn 0.0018 -1.0000 0.0032 +vn 0.0021 -1.0000 0.0011 +vn 0.0026 -1.0000 0.0010 +vn -0.0003 -1.0000 -0.0009 +vn 0.0006 -1.0000 0.0007 +vn 0.0012 -1.0000 -0.0012 +vn 0.0009 -1.0000 -0.0017 +vn 0.0002 -1.0000 -0.0011 +vn -0.0015 -1.0000 0.0001 +vn -0.0009 -1.0000 0.0008 +vn -0.0011 -1.0000 -0.0000 +vn -0.0003 -1.0000 -0.0010 +vn -0.0003 -1.0000 -0.0008 +vn -0.0002 -1.0000 -0.0007 +vn -0.0007 -1.0000 0.0005 +vn -0.0004 -1.0000 0.0012 +vn -0.0015 -1.0000 0.0002 +vn 0.0006 -1.0000 -0.0007 +vn -0.0015 1.0000 0.0003 +vn -0.0007 1.0000 0.0010 +vn -0.0009 1.0000 0.0018 +vn -0.0010 1.0000 0.0043 +vn -0.0013 1.0000 0.0013 +vn -0.0005 1.0000 0.0012 +vn -0.0017 1.0000 0.0015 +vn -0.0017 1.0000 -0.0001 +vn -0.0015 1.0000 0.0005 +vn 0.0011 1.0000 0.0002 +vn 0.0005 1.0000 -0.0001 +vn -0.0025 1.0000 0.0013 +vn -0.0003 1.0000 -0.0001 +vn -0.0005 1.0000 -0.0001 +vn -0.0002 1.0000 -0.0002 +vn -0.0003 1.0000 -0.0003 +vn 0.0009 1.0000 -0.0000 +vn 0.0012 1.0000 0.0012 +vn -0.0003 1.0000 0.0019 +vn 0.0046 1.0000 0.0026 +vn -0.0016 1.0000 0.0006 +vn 0.0001 1.0000 -0.0002 +vn -0.0009 1.0000 0.0007 +vn -0.0002 1.0000 0.0000 +vn 0.0000 1.0000 -0.0007 +vn 0.0020 1.0000 0.0006 +vn 0.0001 1.0000 -0.0001 +vn -0.0000 1.0000 0.0000 +vn -0.0004 1.0000 -0.0000 +vn -0.0005 1.0000 -0.0005 +vn 0.0008 1.0000 0.0004 +vn 0.0014 1.0000 0.0006 +vn 0.0000 1.0000 0.0006 +vn 0.0008 1.0000 -0.0004 +vn 0.1117 -0.0185 -0.9936 +vn -0.1211 0.0206 -0.9924 +vn 0.3367 0.0181 -0.9414 +vn 0.5494 -0.0202 -0.8353 +vn 0.7198 0.0179 -0.6939 +vn 0.8836 -0.0195 -0.4678 +vn 0.9528 0.0168 -0.3033 +vn 0.9995 -0.0156 -0.0261 +vn 0.9904 0.0151 0.1374 +vn 0.9300 -0.0137 0.3673 +vn 0.8523 0.0158 0.5228 +vn 0.7132 -0.0163 0.7008 +vn 0.5417 0.0181 0.8404 +vn 0.3367 -0.0181 0.9414 +vn 0.1117 0.0185 0.9936 +vn -0.1211 -0.0206 0.9924 +vn -0.3354 0.0184 0.9419 +vn -0.6118 -0.0222 0.7907 +vn -0.7267 0.0090 0.6869 +vn -0.8289 -0.0206 0.5591 +vn -0.8530 -0.0007 0.5219 +vn -1.0000 -0.0046 -0.0088 +vn -0.9996 0.0125 0.0239 +vn -1.0000 0.0046 0.0088 +vn -0.9996 -0.0125 -0.0239 +vn -0.8530 0.0007 -0.5219 +vn -0.8289 0.0206 -0.5591 +vn -0.7267 -0.0090 -0.6869 +vn -0.6118 0.0222 -0.7907 +vn -0.3354 -0.0184 -0.9419 +vn -0.9904 -0.0773 -0.1142 +vn -0.9949 0.0201 0.0990 +vn -0.9932 0.1156 -0.0096 +vn -0.3479 0.6845 -0.6407 +vn -0.5148 0.6477 -0.5617 +vn -0.6098 0.6858 -0.3973 +vn -0.7342 0.6392 -0.2290 +vn -0.7314 0.6782 -0.0710 +vn 0.6447 0.6966 0.3148 +vn 0.4587 0.6713 0.5821 +vn 0.6299 0.6231 0.4637 +vn 0.9889 0.1300 -0.0717 +vn 0.9975 -0.0604 -0.0355 +vn 0.9636 0.0839 -0.2538 +vn 0.9741 -0.2131 -0.0755 +vn 0.9729 -0.1280 0.1928 +vn 0.9929 0.0301 0.1149 +vn 0.9339 -0.3559 0.0334 +vn 0.9619 -0.0996 -0.2545 +vn 0.8793 0.0235 -0.4757 +vn 0.8873 -0.1748 -0.4268 +vn 0.9173 0.3521 0.1861 +vn 0.9350 0.3502 -0.0558 +vn 0.8420 0.5282 0.1099 +vn 0.9746 0.2052 0.0895 +vn 0.8664 0.3760 -0.3285 +vn 0.9339 0.2439 -0.2613 +vn 0.8478 0.2242 -0.4806 +vn 0.8916 -0.4065 0.1995 +vn 0.8237 -0.5670 0.0007 +vn 0.7494 -0.6580 -0.0740 +vn 0.7002 -0.6564 -0.2808 +vn 0.7971 -0.5626 -0.2191 +vn 0.9058 -0.3683 -0.2096 +vn 0.7400 -0.6556 0.1504 +vn 0.7574 -0.5845 0.2913 +vn 0.9125 -0.2159 0.3475 +vn 0.5921 -0.6758 0.4391 +vn 0.7935 -0.4149 0.4453 +vn 0.7522 0.6569 0.0510 +vn 0.7536 0.5867 0.2962 +vn 0.8335 0.5395 -0.1190 +vn 0.7317 0.6488 -0.2088 +vn 0.7729 0.5427 -0.3287 +vn 0.6398 0.6588 -0.3958 +vn 0.6254 0.6011 -0.4975 +vn 0.6217 -0.6121 0.4887 +vn 0.8306 -0.2106 0.5155 +vn 0.5436 -0.6272 -0.5577 +vn 0.7152 -0.5467 -0.4354 +vn 0.8562 0.3801 0.3499 +vn 0.8447 -0.3809 -0.3760 +vn 0.6038 -0.5018 0.6194 +vn 0.3742 -0.6630 0.6484 +vn 0.4000 -0.5824 0.7077 +vn 0.6221 -0.3350 0.7076 +vn 0.9270 0.0056 0.3750 +vn 0.9330 0.1647 0.3201 +vn 0.4650 0.6674 -0.5818 +vn 0.7334 -0.1400 0.6653 +vn 0.5058 0.5700 0.6475 +vn 0.7926 0.3567 0.4945 +vn 0.4891 0.5651 -0.6643 +vn 0.8338 0.0695 0.5477 +vn 0.4250 -0.3645 0.8286 +vn 0.6672 0.4188 0.6160 +vn 0.0989 -0.6366 0.7648 +vn 0.5674 -0.0910 0.8184 +vn 0.2017 -0.4383 0.8759 +vn 0.0543 -0.6860 -0.7256 +vn 0.2832 -0.6085 -0.7413 +vn 0.3792 -0.6353 -0.6727 +vn 0.5841 -0.5007 -0.6389 +vn 0.1948 0.5994 -0.7764 +vn -0.0222 0.6749 -0.7376 +vn 0.2964 0.6622 -0.6882 +vn 0.7205 0.4182 -0.5532 +vn -0.2389 -0.0886 -0.9670 +vn -0.0999 0.1071 -0.9892 +vn 0.0695 -0.1426 -0.9873 +vn 0.2140 0.0810 -0.9735 +vn 0.3052 -0.2134 -0.9281 +vn 0.4010 0.0012 -0.9161 +vn 0.7401 -0.1103 -0.6634 +vn 0.6036 0.0114 -0.7972 +vn 0.7326 0.1521 -0.6635 +vn 0.5258 -0.1752 -0.8323 +vn -0.1157 -0.2554 -0.9599 +vn 0.5539 -0.3186 -0.7692 +vn -0.0087 -0.4132 -0.9106 +vn 0.1738 -0.4395 -0.8813 +vn 0.7612 -0.3003 -0.5748 +vn 0.3912 -0.4554 -0.7997 +vn -0.0102 -0.6114 -0.7912 +vn -0.2609 -0.5279 -0.8082 +vn -0.2607 -0.6482 -0.7154 +vn -0.2777 -0.3258 -0.9037 +vn -0.2488 -0.5767 0.7781 +vn -0.3002 -0.6777 0.6712 +vn -0.0106 -0.5108 0.8596 +vn -0.2286 -0.3798 0.8964 +vn -0.1216 -0.2357 0.9642 +vn 0.1002 -0.2224 0.9698 +vn 0.3232 -0.1295 0.9374 +vn -0.3147 -0.1213 0.9414 +vn 0.0015 -0.0150 0.9999 +vn 0.3854 0.1372 0.9125 +vn -0.1771 0.1463 0.9733 +vn 0.1978 0.1470 0.9692 +vn 0.7319 0.1343 0.6680 +vn 0.5823 0.2035 0.7871 +vn 0.0250 0.2770 0.9606 +vn -0.2054 0.3771 0.9031 +vn -0.4029 0.3072 0.8622 +vn 0.1868 0.4098 0.8928 +vn 0.4456 0.3808 0.8102 +vn -0.0761 0.5227 0.8491 +vn 0.3500 0.5533 0.7559 +vn -0.3081 0.5644 0.7659 +vn 0.1381 0.6032 0.7856 +vn 0.2378 0.6741 0.6993 +vn -0.0769 0.6619 0.7456 +vn -0.3488 0.6719 0.6533 +vn -0.4510 0.0331 0.8919 +vn -0.4612 -0.3813 0.8012 +vn -0.4632 -0.6585 -0.5932 +vn -0.4992 -0.5309 -0.6848 +vn -0.4787 -0.3285 -0.8142 +vn -0.4893 -0.1385 -0.8610 +vn -0.3366 0.0904 -0.9373 +vn -0.5083 0.5550 0.6585 +vn -0.5026 -0.5787 0.6423 +vn -0.5688 0.0545 -0.8207 +vn -0.5285 0.6818 0.5058 +vn -0.6217 0.3544 0.6985 +vn -0.5767 0.1475 0.8035 +vn -0.5351 -0.1930 0.8224 +vn -0.6229 -0.6483 0.4379 +vn -0.6417 -0.6594 -0.3917 +vn -0.6220 -0.6059 -0.4959 +vn -0.6382 0.6193 0.4574 +vn -0.1531 0.6069 -0.7799 +vn -0.4181 0.5349 -0.7342 +vn -0.6108 0.4592 -0.6450 +vn -0.2702 0.4484 -0.8520 +vn 0.0730 0.4836 -0.8722 +vn 0.4102 0.4105 -0.8144 +vn 0.6029 0.3464 -0.7187 +vn -0.4230 0.2858 -0.8599 +vn -0.1294 0.3498 -0.9278 +vn 0.2697 0.3246 -0.9066 +vn 0.0682 0.2485 -0.9662 +vn 0.4921 0.1797 -0.8518 +vn -0.6210 0.2660 -0.7373 +vn -0.7098 0.6317 0.3116 +vn -0.6658 -0.0601 0.7437 +vn -0.6670 -0.3107 0.6772 +vn -0.6693 -0.5218 0.5289 +vn -0.6829 -0.2938 -0.6689 +vn -0.7281 0.4794 0.4899 +vn -0.7120 -0.4315 -0.5539 +vn -0.6875 -0.1002 -0.7192 +vn -0.7152 0.5383 -0.4457 +vn -0.7336 0.1602 0.6604 +vn -0.7536 0.1013 -0.6495 +vn -0.7718 0.3040 -0.5586 +vn -0.8087 -0.3301 0.4869 +vn -0.7933 -0.5378 0.2853 +vn -0.7328 -0.6591 0.1689 +vn -0.7353 -0.6581 -0.1623 +vn -0.7749 -0.5423 -0.3248 +vn -0.8372 0.5458 -0.0356 +vn -0.7607 0.6362 0.1286 +vn -0.8278 0.5212 0.2075 +vn -0.8415 0.2046 0.5000 +vn -0.8175 -0.0664 0.5721 +vn -0.8284 -0.5570 0.0594 +vn -0.7945 -0.5998 -0.0948 +vn -0.8221 -0.1480 -0.5498 +vn -0.8556 0.3230 -0.4045 +vn -0.8458 0.4628 -0.2653 +vn -0.8589 0.3402 0.3827 +vn -0.8631 -0.3325 -0.3801 +vn -0.8690 0.0733 -0.4893 +vn -0.8950 -0.3362 0.2931 +vn -0.8904 -0.4285 -0.1536 +vn -0.9124 0.3483 0.2150 +vn -0.9279 0.3348 -0.1643 +vn -0.9154 -0.0693 0.3966 +vn -0.9297 -0.3613 0.0713 +vn -0.9376 -0.1229 -0.3251 +vn -0.9325 0.1164 -0.3418 +vn -0.9522 0.3003 0.0554 +vn -0.9509 0.1556 0.2675 +vn -0.9643 -0.1705 0.2026 +vn -0.9559 -0.2640 -0.1290 +vn -0.9731 0.1192 -0.1973 +vn -0.9700 0.0052 0.2429 +vn -0.9852 -0.1691 0.0290 +vn -0.0039 -1.0000 -0.0029 +vn -0.0031 -1.0000 -0.0023 +vn -0.0017 -1.0000 -0.0009 +vn -0.0040 -1.0000 0.0019 +vn -0.0053 -1.0000 0.0019 +vn 0.0012 -1.0000 0.0020 +vn 0.0019 -1.0000 -0.0001 +vn -0.0049 -1.0000 -0.0038 +vn -0.0037 -1.0000 0.0004 +vn -0.0036 -1.0000 -0.0005 +vn 0.0036 -1.0000 -0.0008 +vn 0.0100 -0.9999 0.0046 +vn 0.0013 -1.0000 -0.0011 +vn -0.0059 -1.0000 0.0011 +vn -0.0021 -1.0000 0.0075 +vn -0.0009 -1.0000 0.0097 +vn 0.0024 -1.0000 -0.0020 +vn 0.0056 -1.0000 -0.0063 +vn 0.0033 -1.0000 -0.0004 +vn 0.0128 -0.9999 -0.0083 +vn -0.0018 -1.0000 -0.0006 +vn -0.0003 -1.0000 0.0007 +vn -0.0001 -1.0000 0.0010 +vn 0.0076 -1.0000 -0.0009 +vn -0.0016 -1.0000 0.0043 +vn 0.0218 -0.9997 -0.0123 +vn 0.0013 1.0000 0.0014 +vn -0.0021 1.0000 0.0015 +vn -0.0086 1.0000 0.0022 +vn -0.0117 0.9999 0.0074 +vn -0.0135 0.9999 0.0045 +vn -0.0002 1.0000 0.0009 +vn -0.0001 1.0000 0.0009 +vn 0.0003 1.0000 0.0009 +vn -0.0002 1.0000 0.0012 +vn 0.0022 1.0000 0.0019 +vn -0.0036 1.0000 0.0000 +vn 0.0003 1.0000 0.0010 +vn 0.0007 1.0000 0.0011 +vn 0.0038 1.0000 -0.0023 +vn 0.0014 1.0000 -0.0009 +vn 0.0005 1.0000 0.0003 +vn 0.0050 1.0000 -0.0006 +vn 0.0048 1.0000 -0.0015 +vn 0.0049 1.0000 -0.0030 +vn 0.0048 1.0000 -0.0001 +vn 0.0021 1.0000 -0.0003 +vn 0.0006 1.0000 0.0007 +vn 0.0017 1.0000 -0.0008 +vn 0.0004 1.0000 0.0008 +vn 0.0046 1.0000 -0.0026 +vn -0.0420 -0.2095 -0.9769 +vn -0.0112 -0.0089 -0.9999 +vn -0.3645 -0.0083 -0.9312 +vn -0.3417 -0.0030 -0.9398 +vn -0.7813 0.0046 -0.6242 +vn -0.8077 -0.0041 -0.5896 +vn -0.7854 0.0033 -0.6189 +vn -0.8116 -0.0054 -0.5842 +vn -0.9982 0.0037 -0.0601 +vn -0.9998 -0.0034 -0.0209 +vn -0.9861 0.0042 0.1659 +vn -0.9679 -0.0080 0.2512 +vn -0.7931 0.0078 0.6090 +vn -0.7002 -0.0088 0.7139 +vn -0.3679 0.0065 0.9298 +vn -0.3021 -0.0022 0.9533 +vn 0.1454 0.0009 0.9894 +vn 0.1455 0.0008 0.9894 +vn 0.3891 -0.0005 0.9212 +vn 0.3902 -0.0008 0.9207 +vn 0.8528 0.0012 0.5223 +vn 0.8575 -0.0007 0.5145 +vn 0.9575 0.0008 0.2885 +vn 0.9668 -0.0048 0.2553 +vn 0.9851 0.0056 -0.1721 +vn 0.9458 -0.0114 -0.3246 +vn 0.7931 0.0115 -0.6090 +vn 0.5926 -0.0147 -0.8054 +vn 0.2959 -0.3935 -0.8704 +vn -0.0857 0.7227 0.6858 +vn 0.1199 0.6265 0.7701 +vn -0.2989 0.6075 0.7360 +vn -0.4918 0.7288 0.4764 +vn -0.4490 0.7467 0.4907 +vn -0.6883 0.6892 0.2265 +vn -0.6963 0.7105 0.1017 +vn -0.7290 0.6664 -0.1564 +vn -0.5746 0.7689 -0.2805 +vn -0.4691 0.8158 -0.3382 +vn -0.6325 0.3353 -0.6982 +vn -0.1808 0.8465 -0.5008 +vn 0.0222 0.1948 -0.9806 +vn 0.1781 0.8376 -0.5165 +vn 0.6232 0.4027 -0.6704 +vn 0.4709 0.8100 -0.3496 +vn 0.8615 0.5072 -0.0245 +vn 0.8615 0.5073 -0.0245 +vn 0.8611 0.5079 -0.0243 +vn 0.8609 0.5082 -0.0243 +vn 0.4566 0.8462 0.2746 +vn 0.6595 0.3506 0.6650 +vn 0.2237 0.8179 0.5300 +vn 0.2151 0.7876 0.5775 +vn -0.2080 -0.8223 -0.5297 +vn -0.6216 -0.3625 -0.6944 +vn -0.4786 -0.7906 -0.3818 +vn -0.6961 -0.6930 -0.1874 +vn -0.5965 -0.7479 -0.2913 +vn -0.7015 -0.7033 0.1153 +vn -0.6817 -0.7215 0.1213 +vn -0.6423 -0.6613 0.3875 +vn -0.4488 -0.7777 0.4402 +vn -0.3449 -0.8223 0.4526 +vn -0.3771 -0.4309 0.8198 +vn -0.0317 -0.7725 0.6342 +vn -0.0641 -0.8065 0.5878 +vn 0.1102 -0.6593 0.7438 +vn 0.2525 -0.7462 0.6160 +vn 0.4824 -0.6322 0.6063 +vn 0.5345 -0.7551 0.3797 +vn 0.6769 -0.7033 0.2171 +vn 0.7072 -0.6987 0.1082 +vn 0.7936 -0.6001 -0.1006 +vn 0.5879 -0.7842 -0.1982 +vn 0.5260 -0.8229 -0.2151 +vn 0.5977 -0.4879 -0.6362 +vn 0.5814 -0.5162 -0.6288 +vn 0.2814 -0.7067 -0.6491 +vn 0.0654 -0.5146 -0.8549 +vn -0.5882 0.2151 0.7796 +vn -0.6168 0.3117 0.7227 +vn -0.5912 0.4161 0.6909 +vn -0.1429 0.9817 -0.1256 +vn -0.2297 0.9284 -0.2922 +vn -0.2492 0.8392 -0.4833 +vn -0.1568 -0.9821 0.1049 +vn -0.2241 -0.9299 0.2917 +vn -0.2547 -0.8597 0.4428 +vn -0.1889 -0.9735 -0.1288 +vn -0.1877 -0.9653 -0.1817 +vn -0.0818 -0.9288 0.3613 +vn -0.0422 -0.9969 0.0665 +vn -0.2414 0.0182 0.9702 +vn -0.1069 0.4336 0.8947 +vn -0.0332 0.0865 0.9957 +vn -0.0873 0.9657 -0.2445 +vn -0.0946 0.9915 0.0893 +vn -0.1434 0.9798 0.1393 +vn -0.2947 -0.8077 -0.5107 +vn -0.2524 0.7931 0.5543 +vn -0.2124 0.9390 0.2705 +vn -0.3823 -0.2147 0.8987 +vn -0.4399 0.0499 0.8966 +vn -0.2743 -0.6753 0.6847 +vn -0.0794 -0.7040 0.7058 +vn -0.3605 -0.8225 -0.4399 +vn -0.3530 0.2007 -0.9138 +vn -0.1446 0.0568 -0.9879 +vn -0.2473 0.3925 -0.8859 +vn -0.1202 0.7767 -0.6183 +vn -0.0819 0.9156 0.3937 +vn -0.0558 -0.3801 0.9233 +vn -0.4133 -0.5461 0.7287 +vn -0.4851 -0.6513 -0.5835 +vn -0.3954 0.5389 -0.7438 +vn -0.4270 0.5770 0.6963 +vn -0.5683 0.5558 0.6068 +vn -0.2386 -0.3767 0.8951 +vn -0.5807 -0.4929 0.6480 +vn -0.6436 0.2556 -0.7214 +vn -0.5427 0.1037 -0.8335 +vn -0.0080 0.5288 -0.8487 +vn -0.5741 0.4829 -0.6612 +vn -0.4545 -0.4894 -0.7442 +vn -0.6333 -0.3987 -0.6633 +vn -0.5508 -0.3040 0.7773 +vn -0.6491 -0.1169 0.7517 +vn -0.6599 0.0371 0.7504 +vn -0.6987 0.1146 0.7061 +vn -0.5340 0.2250 0.8150 +vn -0.3377 0.4186 0.8431 +vn -0.1059 0.7253 0.6803 +vn -0.6686 -0.3202 0.6712 +vn -0.6719 -0.2816 0.6850 +vn -0.6340 -0.2129 -0.7434 +vn -0.7006 -0.3004 -0.6472 +vn -0.1925 -0.6778 -0.7096 +vn -0.5918 -0.6295 -0.5035 +vn -0.4013 -0.2127 -0.8909 +vn -0.1860 -0.4254 -0.8857 +vn -0.6375 0.1936 -0.7457 +vn -0.6772 -0.0026 -0.7358 +vn -0.0208 -0.4127 -0.9106 +vn -0.6570 0.2967 -0.6931 +vn 0.9914 -0.0915 -0.0939 +vn 0.9912 0.1153 -0.0643 +vn 0.9989 0.0321 0.0332 +vn 0.9919 -0.1104 0.0630 +vn -0.6543 -0.1914 -0.7316 +vn -0.6036 -0.1756 0.7777 +vn 0.1016 0.2532 0.9621 +vn 0.2697 0.3231 0.9071 +vn -0.0876 0.2993 0.9501 +vn 0.9611 0.2683 0.0656 +vn 0.9447 0.3154 -0.0902 +vn 0.9291 0.3075 0.2055 +vn 0.8965 0.2991 -0.3268 +vn 0.9564 0.2281 -0.1823 +vn 0.2408 -0.3064 -0.9209 +vn 0.4025 -0.2124 -0.8904 +vn 0.5270 -0.3146 -0.7895 +vn 0.7029 -0.3205 -0.6349 +vn 0.7621 -0.2255 -0.6070 +vn 0.8249 -0.3227 -0.4641 +vn 0.9399 -0.3394 0.0380 +vn 0.9610 -0.2677 -0.0700 +vn 0.9561 -0.2674 0.1198 +vn 0.9144 -0.2780 0.2942 +vn -0.5778 -0.2981 -0.7598 +vn -0.5037 -0.2184 -0.8358 +vn -0.3487 -0.2865 -0.8924 +vn -0.4873 0.2831 -0.8260 +vn -0.5287 -0.2687 0.8051 +vn -0.3249 -0.2396 0.9149 +vn -0.3848 -0.3041 0.8715 +vn -0.1095 -0.3166 0.9422 +vn -0.3542 0.3236 0.8774 +vn -0.3275 0.2461 0.9122 +vn -0.3619 -0.1663 -0.9173 +vn -0.0862 -0.2943 -0.9518 +vn -0.0972 -0.1986 -0.9752 +vn 0.1512 -0.1920 -0.9697 +vn -0.5986 -0.0258 -0.8006 +vn -0.3201 -0.0014 -0.9474 +vn -0.0136 -0.0002 -0.9999 +vn 0.3166 0.0234 -0.9483 +vn 0.5540 -0.0694 -0.8296 +vn -0.5200 0.1247 -0.8450 +vn -0.3617 0.1859 -0.9136 +vn -0.1008 0.1897 -0.9767 +vn 0.1559 0.1850 -0.9703 +vn 0.4018 0.2010 -0.8934 +vn -0.2587 0.2927 -0.9205 +vn -0.0068 0.3051 -0.9523 +vn 0.2211 0.3008 -0.9277 +vn 0.4502 0.3007 -0.8408 +vn 0.6461 0.3170 -0.6943 +vn 0.5965 0.2360 -0.7671 +vn 0.5963 0.0691 -0.7998 +vn 0.6325 -0.2163 -0.7437 +vn -0.3313 0.0903 0.9392 +vn -0.4741 -0.0218 0.8802 +vn -0.2098 -0.0789 0.9746 +vn -0.0535 0.1260 0.9906 +vn 0.0387 -0.0508 0.9980 +vn 0.2557 0.0564 0.9651 +vn 0.2470 -0.1843 0.9513 +vn 0.4585 -0.1441 0.8769 +vn -0.0143 -0.2334 0.9723 +vn 0.6113 -0.0411 0.7903 +vn 0.6315 -0.2404 0.7372 +vn 0.1960 -0.3174 0.9278 +vn 0.4529 -0.2787 0.8469 +vn 0.7533 -0.2824 0.5940 +vn 0.7619 -0.1726 0.6243 +vn 0.7687 -0.0003 0.6396 +vn 0.7395 0.1919 -0.6452 +vn 0.7596 -0.0103 -0.6503 +vn 0.8180 0.2838 -0.5004 +vn 0.8480 -0.2935 0.4412 +vn 0.8638 -0.1989 0.4629 +vn 0.8538 0.1631 -0.4945 +vn 0.8546 -0.0699 -0.5146 +vn 0.8806 -0.2273 -0.4157 +vn 0.9077 -0.0115 0.4194 +vn 0.9248 0.1827 -0.3337 +vn 0.9239 -0.3084 -0.2267 +vn 0.8337 0.3048 0.4605 +vn 0.9204 0.1932 0.3399 +vn 0.7037 0.3075 0.6405 +vn 0.8108 0.1862 0.5549 +vn 0.5354 0.2987 0.7901 +vn 0.6645 0.2012 0.7197 +vn 0.3317 0.2476 0.9103 +vn 0.4703 0.1625 0.8674 +vn 0.9260 -0.0060 -0.3774 +vn 0.9539 -0.1536 0.2580 +vn 0.9738 0.0076 -0.2273 +vn 0.9564 -0.1782 -0.2313 +vn 0.9790 0.0044 0.2036 +vn 0.9793 0.1418 0.1442 +vn -0.0009 1.0000 0.0001 +vn -0.0020 1.0000 -0.0013 +vn -0.0002 1.0000 0.0004 +vn 0.0003 1.0000 0.0001 +vn -0.0001 1.0000 -0.0004 +vn 0.0011 1.0000 -0.0006 +vn 0.0010 1.0000 -0.0009 +vn 0.0016 1.0000 -0.0022 +vn 0.0004 1.0000 0.0007 +vn 0.0009 1.0000 0.0003 +vn 0.0004 1.0000 0.0004 +vn -0.0012 1.0000 0.0014 +vn -0.0005 1.0000 0.0013 +vn -0.0018 1.0000 0.0012 +vn -0.0027 1.0000 -0.0033 +vn 0.0004 1.0000 -0.0008 +vn 0.0005 1.0000 -0.0007 +vn -0.0003 1.0000 0.0001 +vn -0.0003 1.0000 -0.0007 +vn -0.0017 1.0000 -0.0014 +vn -0.0014 1.0000 -0.0024 +vn 0.0003 1.0000 -0.0007 +vn 0.0010 1.0000 0.0000 +vn 0.0019 1.0000 0.0002 +vn 0.0009 1.0000 -0.0007 +vn 0.0004 1.0000 0.0002 +vn -0.0012 1.0000 -0.0024 +vn -0.0028 1.0000 -0.0042 +vn -0.0000 1.0000 -0.0006 +vn 0.0008 1.0000 -0.0002 +vn 0.0010 -1.0000 0.0001 +vn 0.0015 -1.0000 0.0016 +vn 0.0005 -1.0000 0.0016 +vn 0.0022 -1.0000 -0.0017 +vn -0.0010 -1.0000 0.0042 +vn 0.0011 -1.0000 0.0027 +vn 0.0038 -1.0000 0.0001 +vn 0.0015 -1.0000 0.0011 +vn 0.0001 -1.0000 0.0028 +vn 0.0089 -1.0000 -0.0010 +vn -0.0012 -1.0000 0.0009 +vn -0.0009 -1.0000 0.0018 +vn -0.0013 -1.0000 0.0007 +vn 0.0025 -1.0000 0.0022 +vn 0.0000 -1.0000 -0.0000 +vn -0.0002 -1.0000 -0.0000 +vn 0.0001 -1.0000 0.0002 +vn -0.0003 -1.0000 0.0003 +vn -0.0010 -1.0000 0.0002 +vn -0.0006 -1.0000 -0.0027 +vn -0.0025 -1.0000 -0.0014 +vn -0.0012 -1.0000 0.0007 +vn -0.0024 -1.0000 0.0020 +vn -0.0022 -1.0000 -0.0005 +vn 0.0013 -1.0000 -0.0012 +vn 0.0003 -1.0000 0.0002 +vn -0.0056 -1.0000 -0.0030 +vn 0.0003 -1.0000 -0.0001 +vn 0.0007 -1.0000 -0.0007 +vn -0.0003 -1.0000 0.0004 +vn -0.0007 -1.0000 -0.0000 +vn 0.0001 -1.0000 0.0005 +vn -0.0028 -1.0000 0.0003 +vn 0.0824 0.0116 -0.9965 +vn -0.2297 -0.0175 -0.9731 +vn -0.4256 0.0225 -0.9046 +vn -0.6656 -0.0202 -0.7461 +vn -0.8215 0.0224 -0.5697 +vn -0.9306 -0.0179 -0.3656 +vn -0.9954 0.0195 -0.0941 +vn -0.9954 -0.0195 0.0940 +vn -0.9306 0.0179 0.3656 +vn -0.8333 -0.0178 0.5525 +vn -0.6770 0.0154 0.7358 +vn -0.5404 -0.0140 0.8413 +vn -0.3384 0.0140 0.9409 +vn -0.1821 -0.0132 0.9832 +vn 0.0808 0.0175 0.9966 +vn 0.2171 -0.0059 0.9761 +vn 0.5903 0.0074 0.8072 +vn 0.5938 -0.0063 0.8046 +vn 0.9289 -0.0144 0.3700 +vn 0.9104 0.0093 0.4137 +vn 0.9984 0.0142 -0.0544 +vn 0.9825 -0.0151 -0.1857 +vn 0.8444 0.0137 -0.5355 +vn 0.8210 -0.0073 -0.5709 +vn 0.5390 0.0050 -0.8423 +vn 0.5119 0.0041 -0.8590 +vn 0.1901 -0.0025 -0.9818 +vn 0.9885 0.0720 0.1328 +vn 0.9930 -0.1169 0.0161 +vn 0.9986 -0.0050 -0.0529 +vn 0.1026 0.6633 0.7413 +vn 0.3299 0.6458 0.6886 +vn 0.4208 0.6634 0.6187 +vn 0.3211 -0.6549 -0.6841 +vn 0.4951 -0.6292 -0.5991 +vn 0.6154 -0.6719 -0.4121 +vn 0.7234 -0.6307 -0.2810 +vn 0.7264 -0.6858 -0.0448 +vn 0.2245 -0.5566 0.7999 +vn -0.0270 -0.6656 0.7458 +vn 0.3469 -0.6788 0.6472 +vn -0.3269 -0.6040 0.7269 +vn -0.3913 -0.6723 0.6284 +vn -0.9845 -0.0639 -0.1634 +vn -0.9945 -0.1029 0.0214 +vn -0.9905 0.0867 -0.1064 +vn -0.9786 0.2046 0.0232 +vn -0.9981 0.0357 0.0496 +vn -0.9691 0.1661 0.1826 +vn -0.9482 0.0836 -0.3063 +vn -0.9204 0.3898 0.0308 +vn -0.8867 -0.0621 -0.4581 +vn -0.8374 0.1554 -0.5240 +vn -0.9026 -0.3809 -0.2004 +vn -0.9505 -0.1952 -0.2418 +vn -0.8492 -0.2990 -0.4352 +vn -0.8213 0.5650 -0.0791 +vn -0.8485 0.4919 0.1950 +vn -0.7626 0.6225 0.1756 +vn -0.9466 -0.2568 0.1952 +vn -0.9615 -0.2743 -0.0190 +vn -0.9019 -0.4254 0.0753 +vn -0.8169 -0.5447 0.1898 +vn -0.9516 0.2732 -0.1408 +vn -0.8066 -0.5362 -0.2488 +vn -0.7841 -0.4788 -0.3949 +vn -0.7430 0.6675 -0.0492 +vn -0.6820 0.6827 -0.2625 +vn -0.7448 0.5920 -0.3078 +vn -0.8832 0.4131 -0.2220 +vn -0.9070 0.3093 0.2860 +vn -0.7003 0.6649 0.2599 +vn -0.6449 0.5955 0.4790 +vn -0.7543 -0.6533 0.0653 +vn -0.7097 -0.6426 0.2888 +vn -0.8136 -0.5724 -0.1019 +vn -0.7128 -0.6694 -0.2093 +vn -0.7780 0.4652 0.4223 +vn -0.9806 -0.0290 0.1936 +vn -0.8926 0.1583 0.4221 +vn -0.6742 -0.6227 -0.3970 +vn -0.5688 -0.6542 -0.4985 +vn -0.5899 0.6510 -0.4778 +vn -0.5684 0.6402 0.5167 +vn -0.7882 0.2923 0.5417 +vn -0.5852 -0.6487 0.4865 +vn -0.7253 -0.5275 0.4424 +vn -0.8570 -0.3759 0.3525 +vn -0.6480 0.4265 0.6310 +vn -0.9221 -0.0534 0.3833 +vn -0.7293 0.5030 -0.4638 +vn -0.4620 0.6156 0.6385 +vn -0.4406 0.5477 0.7112 +vn -0.4052 0.6544 -0.6384 +vn -0.5852 0.5212 -0.6212 +vn -0.8762 0.3018 -0.3758 +vn -0.7956 0.0164 0.6056 +vn -0.6804 0.2109 0.7018 +vn -0.5893 -0.5433 0.5979 +vn -0.4822 0.3665 0.7957 +vn -0.5002 -0.5433 -0.6742 +vn -0.6490 -0.4544 -0.6102 +vn -0.2523 0.6283 0.7360 +vn -0.1965 0.4406 0.8760 +vn -0.4730 0.1676 0.8650 +vn -0.0644 0.6873 -0.7235 +vn -0.1587 0.5879 -0.7932 +vn -0.3478 0.6100 -0.7120 +vn -0.2967 -0.6504 -0.6993 +vn -0.6098 0.1635 -0.7755 +vn -0.3891 0.0225 -0.9209 +vn -0.6099 -0.0708 -0.7893 +vn -0.7537 0.0373 -0.6562 +vn 0.1403 0.2529 -0.9573 +vn 0.2856 0.0918 -0.9539 +vn -0.0737 0.0117 -0.9972 +vn -0.1560 0.1967 -0.9680 +vn -0.4016 0.2368 -0.8846 +vn -0.7233 0.3038 -0.6202 +vn -0.1320 0.3725 -0.9186 +vn 0.1141 0.4593 -0.8809 +vn -0.3248 0.4270 -0.8439 +vn -0.5028 0.4291 -0.7504 +vn 0.0864 0.6088 -0.7886 +vn 0.2739 0.6746 -0.6855 +vn 0.2992 0.5997 -0.7422 +vn 0.3624 0.3902 -0.8464 +vn 0.3149 0.5135 0.7982 +vn 0.1096 0.5092 0.8536 +vn -0.0735 0.6033 0.7941 +vn 0.3034 0.3123 0.9002 +vn 0.0639 0.3348 0.9401 +vn -0.2553 0.2554 0.9325 +vn -0.0488 0.1004 0.9937 +vn 0.3740 0.0677 0.9250 +vn 0.1407 0.1091 0.9840 +vn -0.2728 0.0410 0.9612 +vn -0.4605 -0.1087 0.8810 +vn -0.6090 0.0497 0.7916 +vn 0.2527 -0.1710 0.9523 +vn -0.2707 -0.1500 0.9509 +vn -0.0321 -0.1203 0.9922 +vn -0.6138 -0.1400 0.7770 +vn 0.1186 -0.2995 0.9467 +vn -0.7175 -0.2613 0.6457 +vn -0.1424 -0.3416 0.9290 +vn -0.8115 -0.2644 0.5211 +vn -0.3875 -0.3750 0.8421 +vn -0.5655 -0.3893 0.7271 +vn 0.0702 -0.4927 0.8674 +vn -0.9080 -0.2029 0.3666 +vn -0.1393 -0.5295 0.8368 +vn 0.4127 -0.5667 0.7131 +vn 0.4890 0.5478 -0.6788 +vn 0.4420 -0.3730 0.8158 +vn 0.5320 0.6594 -0.5312 +vn 0.5271 0.2965 -0.7964 +vn 0.5323 0.0635 -0.8442 +vn 0.3849 -0.1173 -0.9155 +vn 0.5055 -0.1777 0.8443 +vn 0.4909 0.3012 0.8175 +vn 0.6301 -0.6283 0.4563 +vn 0.5956 -0.5460 0.5892 +vn 0.5875 0.0668 0.8065 +vn 0.5436 0.4868 0.6837 +vn 0.6256 0.6134 0.4820 +vn 0.0841 -0.5954 -0.7990 +vn 0.0391 -0.6626 -0.7479 +vn -0.1681 -0.5037 -0.8474 +vn -0.3597 -0.5127 -0.7796 +vn 0.4465 -0.4818 -0.7540 +vn 0.2174 -0.4637 -0.8589 +vn -0.0129 -0.3806 -0.9246 +vn 0.3724 -0.2903 -0.8815 +vn -0.5260 -0.2691 -0.8068 +vn -0.7490 -0.2017 -0.6311 +vn 0.6199 -0.3469 -0.7038 +vn -0.3531 -0.2288 -0.9072 +vn 0.6161 -0.1858 -0.7654 +vn 0.1197 -0.1690 -0.9783 +vn -0.1596 -0.2070 -0.9652 +vn 0.6809 -0.3138 0.6618 +vn 0.6953 -0.1023 0.7114 +vn 0.6829 0.2386 0.6905 +vn 0.6465 0.4578 0.6103 +vn 0.6075 0.5403 0.5823 +vn 0.5995 0.5859 0.5453 +vn 0.6680 0.5750 -0.4724 +vn 0.6645 0.4152 -0.6213 +vn 0.6913 0.0378 -0.7216 +vn 0.6671 -0.4871 -0.5636 +vn 0.6602 0.6832 -0.3120 +vn 0.7073 0.2465 -0.6625 +vn 0.7223 0.3471 0.5982 +vn 0.1111 0.9759 -0.1878 +vn 0.1537 0.9819 -0.1106 +vn 0.1164 0.9771 -0.1783 +vn 0.6787 0.5073 0.5310 +vn 0.6995 0.5547 0.4506 +vn 0.7903 -0.2286 -0.5684 +vn 0.7821 -0.4635 -0.4166 +vn 0.7705 -0.6022 0.2089 +vn 0.7108 -0.6587 0.2466 +vn 0.7769 -0.4654 0.4240 +vn 0.8021 0.0571 0.5944 +vn 0.1562 0.9820 -0.1060 +vn 0.8178 0.4322 0.3801 +vn 0.7790 0.5818 0.2340 +vn 0.7132 0.6145 0.3372 +vn 0.7411 0.6621 -0.1113 +vn 0.7698 0.5758 -0.2754 +vn 0.8370 -0.0270 -0.5466 +vn 0.8038 -0.5898 -0.0779 +vn 0.7972 -0.3543 0.4888 +vn 0.8555 0.2151 0.4710 +vn 0.7541 0.6508 0.0887 +vn 0.8207 0.5684 -0.0581 +vn 0.8002 0.4116 -0.4363 +vn 0.8072 0.2008 -0.5551 +vn 0.8572 -0.1635 0.4883 +vn 0.8936 -0.4287 -0.1334 +vn 0.8774 -0.4726 0.0822 +vn 0.8690 -0.4145 0.2702 +vn 0.8786 0.4648 0.1099 +vn 0.9038 0.3985 -0.1560 +vn 0.8997 -0.1654 -0.4039 +vn 0.9017 -0.3134 -0.2977 +vn 0.9181 -0.2602 0.2989 +vn 0.9269 -0.0040 0.3754 +vn 0.9115 0.3024 -0.2789 +vn 0.8809 0.1956 -0.4309 +vn 0.9340 0.2359 0.2682 +vn 0.9424 0.0720 -0.3265 +vn 0.9547 -0.2894 0.0694 +vn 0.9512 0.3017 0.0641 +vn 0.9666 -0.0942 -0.2382 +vn 0.9687 -0.2192 -0.1161 +vn 0.9741 -0.1078 0.1989 +vn 0.9781 0.1961 -0.0699 +vn 0.9790 0.1141 -0.1692 +vn 0.0121 0.9999 0.0092 +vn 0.0169 0.9997 0.0195 +vn 0.0077 0.9999 0.0100 +vn 0.0059 1.0000 0.0011 +vn 0.0018 1.0000 0.0050 +vn 0.0086 1.0000 0.0051 +vn 0.0016 1.0000 -0.0018 +vn 0.0009 1.0000 0.0009 +vn 0.0014 1.0000 -0.0005 +vn -0.0009 1.0000 -0.0017 +vn -0.0016 1.0000 -0.0007 +vn -0.0015 1.0000 -0.0027 +vn -0.0006 1.0000 0.0019 +vn -0.0011 1.0000 0.0002 +vn 0.0019 1.0000 0.0027 +vn -0.0010 1.0000 -0.0006 +vn -0.0007 1.0000 0.0009 +vn -0.0007 1.0000 0.0032 +vn 0.0047 1.0000 0.0005 +vn 0.0057 1.0000 -0.0000 +vn 0.0000 1.0000 0.0056 +vn -0.0060 0.9999 0.0096 +vn -0.0063 0.9999 0.0089 +vn -0.0010 1.0000 -0.0003 +vn 0.0011 1.0000 0.0018 +vn -0.0051 1.0000 0.0076 +vn -0.0084 0.9999 0.0143 +vn 0.0029 -1.0000 -0.0009 +vn 0.0004 -1.0000 -0.0017 +vn 0.0017 -1.0000 0.0035 +vn 0.0002 -1.0000 0.0026 +vn -0.0001 -1.0000 0.0026 +vn -0.0008 -1.0000 0.0012 +vn 0.0035 -1.0000 0.0029 +vn 0.0079 -0.9999 0.0068 +vn -0.0011 -1.0000 0.0008 +vn -0.0014 -1.0000 -0.0019 +vn -0.0021 -1.0000 -0.0021 +vn 0.0020 -1.0000 -0.0014 +vn 0.0016 -1.0000 -0.0024 +vn 0.0110 -0.9998 0.0154 +vn 0.0020 -1.0000 -0.0023 +vn 0.0006 -1.0000 0.0011 +vn -0.0044 -1.0000 0.0014 +vn -0.0051 -1.0000 0.0028 +vn -0.0041 -1.0000 0.0032 +vn -0.0054 -1.0000 0.0030 +vn -0.0014 -1.0000 -0.0022 +vn 0.0017 -1.0000 -0.0006 +vn -0.0016 -1.0000 -0.0016 +vn 0.0006 -1.0000 -0.0000 +vn -0.0019 -1.0000 -0.0021 +vn 0.0139 -0.0057 -0.9999 +vn 0.3691 0.0076 -0.9293 +vn 0.4351 -0.0011 -0.9004 +vn 0.8070 0.0061 -0.5906 +vn 0.7745 -0.0022 -0.6326 +vn 0.9770 -0.0067 -0.2130 +vn 0.9891 0.0009 -0.1473 +vn 0.9372 -0.0078 0.3488 +vn 0.9574 0.0034 0.2887 +vn 0.6512 0.0087 0.7589 +vn 0.5837 -0.0047 0.8120 +vn 0.1494 0.0070 0.9887 +vn 0.1737 -0.0015 0.9848 +vn -0.2519 -0.0045 0.9677 +vn -0.3456 0.0076 0.9384 +vn -0.6632 -0.0079 0.7484 +vn -0.7611 0.0085 0.6485 +vn -0.9449 -0.0080 0.3272 +vn -0.9757 0.0055 0.2191 +vn -0.9833 -0.0033 -0.1820 +vn -0.9794 -0.0004 -0.2022 +vn -0.7982 -0.0043 -0.6024 +vn -0.8299 0.0010 -0.5579 +vn -0.5488 0.0061 -0.8359 +vn -0.4266 -0.0074 -0.9044 +vn -0.1367 0.0092 -0.9906 +vn 0.0729 -0.6442 0.7614 +vn 0.2256 -0.7500 0.6217 +vn -0.1360 -0.7237 0.6766 +vn 0.4787 -0.6505 0.5896 +vn 0.5422 -0.7359 0.4055 +vn 0.6797 -0.7118 0.1769 +vn 0.6590 -0.7169 0.2274 +vn 0.7968 -0.5996 -0.0744 +vn 0.6114 -0.7706 -0.1801 +vn 0.5507 -0.8098 -0.2023 +vn 0.6673 -0.3875 -0.6360 +vn 0.6468 -0.4318 -0.6286 +vn 0.2842 -0.7356 -0.6150 +vn 0.1974 -0.7518 -0.6292 +vn -0.0327 -0.5713 -0.8201 +vn -0.2196 -0.7186 -0.6599 +vn -0.4268 -0.6444 -0.6345 +vn -0.5189 -0.7153 -0.4681 +vn -0.6309 -0.6759 -0.3810 +vn -0.6822 -0.7141 -0.1569 +vn -0.6744 -0.7278 -0.1244 +vn -0.6979 -0.7047 0.1280 +vn -0.6788 -0.7069 0.1988 +vn -0.5817 -0.6898 0.4310 +vn -0.4723 -0.7194 0.5093 +vn -0.3005 -0.6736 0.6752 +vn 0.0689 0.4166 -0.9065 +vn 0.2728 0.7626 -0.5865 +vn 0.2674 0.7366 -0.6212 +vn 0.4053 0.7606 -0.5071 +vn 0.7306 0.2682 -0.6279 +vn 0.5370 0.7991 -0.2703 +vn 0.6203 0.7777 -0.1023 +vn 0.6216 0.7722 -0.1320 +vn 0.7453 0.6378 0.1942 +vn 0.6275 0.6995 0.3419 +vn 0.6061 0.5218 0.6003 +vn 0.6135 0.4915 0.6181 +vn 0.1937 0.8342 0.5164 +vn -0.0118 0.5022 0.8647 +vn -0.1012 0.6427 0.7594 +vn -0.0061 0.5299 0.8480 +vn -0.2496 0.6954 0.6739 +vn -0.5392 0.4717 0.6977 +vn -0.5652 0.4240 0.7076 +vn -0.4467 0.8363 0.3178 +vn -0.8502 0.5180 0.0942 +vn -0.8412 0.5333 0.0896 +vn -0.6900 0.7079 -0.1510 +vn -0.6864 0.7207 -0.0974 +vn -0.6005 0.6899 -0.4044 +vn -0.5053 0.7154 -0.4825 +vn -0.3602 0.6699 -0.6492 +vn -0.2118 0.7427 -0.6352 +vn -0.1167 0.7864 -0.6066 +vn 0.0592 0.3717 -0.9265 +vn 1.0000 -0.0001 -0.0000 +vn 1.0000 -0.0011 -0.0003 +vn 1.0000 0.0003 0.0000 +vn 1.0000 -0.0000 -0.0000 +vn 1.0000 0.0003 0.0001 +vn 1.0000 -0.0002 -0.0001 +vn 1.0000 0.0001 -0.0000 +vn 1.0000 -0.0004 -0.0000 +vn 1.0000 0.0011 0.0003 +vn -1.0000 0.0000 0.0000 +vn -1.0000 0.0001 0.0000 +vn -1.0000 0.0011 -0.0004 +vn 0.0833 -0.9915 0.0996 +vn -0.0872 -0.9658 -0.2441 +vn 0.0828 -0.9627 -0.2574 +vn -0.0857 -0.8174 -0.5696 +vn 0.0837 -0.8159 -0.5721 +vn -0.0832 -0.5722 -0.8159 +vn 0.0858 -0.5697 -0.8174 +vn -0.0842 -0.2567 -0.9628 +vn 0.0872 -0.2442 -0.9658 +vn -0.0874 0.1019 -0.9910 +vn 0.0838 0.1713 -0.9816 +vn -0.0858 0.4956 -0.8643 +vn 0.0812 0.5725 -0.8159 +vn -0.0819 0.8159 -0.5724 +vn 0.0820 0.8631 -0.4983 +vn -0.0820 0.9815 -0.1730 +vn 0.0833 0.9915 -0.0996 +vn -0.0824 0.9664 0.2436 +vn 0.0828 0.9627 0.2574 +vn -0.0828 0.8161 0.5719 +vn 0.0825 0.8079 0.5835 +vn -0.0837 0.5611 0.8235 +vn 0.0823 0.4976 0.8635 +vn -0.0838 0.1713 0.9816 +vn 0.0836 0.1001 0.9915 +vn -0.0872 -0.2441 0.9658 +vn 0.0828 -0.2574 0.9627 +vn -0.0857 -0.5696 0.8174 +vn 0.0824 -0.5837 0.8078 +vn -0.0824 -0.8239 0.5608 +vn 0.0820 -0.8631 0.4983 +vn -0.0838 -0.9816 0.1713 +vn -0.0045 -0.9948 -0.1016 +vn -0.0057 -0.9012 0.4334 +vn -0.0047 -0.4837 0.8752 +vn -0.0038 0.9972 0.0750 +vn -0.0053 0.7608 0.6489 +vn -0.0044 0.8269 -0.5623 +vn -0.0043 0.2227 0.9749 +vn -0.0039 0.3389 -0.9408 +vn -0.0061 -0.2536 -0.9673 +vn -0.0066 -0.7622 -0.6473 +vn 0.0080 0.7632 -0.6461 +vn 0.0051 0.3263 -0.9453 +vn 0.0051 0.9094 0.4158 +vn 0.0029 0.4970 0.8678 +vn 0.0077 0.9865 -0.1638 +vn 0.0044 -0.2539 -0.9672 +vn 0.0034 -0.1612 0.9869 +vn 0.0012 -0.7619 0.6477 +vn 0.0063 -0.5437 -0.8392 +vn 0.0015 -0.9385 0.3452 +vn 0.0137 -0.9318 -0.3628 +vn 0.0130 -0.9307 -0.3656 +vn 0.0135 -0.9315 -0.3634 +vn 0.1942 0.9375 -0.2888 +vn 0.1902 0.6972 -0.6912 +vn 0.1894 0.2722 -0.9434 +vn 0.1808 -0.2243 -0.9576 +vn 0.1875 -0.6327 -0.7514 +vn 0.1977 -0.9407 -0.2758 +vn 0.1942 -0.9375 0.2888 +vn 0.1902 -0.6972 0.6912 +vn 0.1911 -0.2735 0.9427 +vn 0.1891 0.2208 0.9568 +vn 0.1933 0.6356 0.7474 +vn 0.1977 0.9407 0.2757 +vn -0.1808 -0.9577 -0.2241 +vn -0.1849 -0.7598 -0.6233 +vn -0.1883 -0.3656 -0.9115 +vn -0.1798 0.0836 -0.9801 +vn -0.1880 0.5518 -0.8125 +vn -0.1943 0.9038 -0.3812 +vn -0.1902 0.9784 0.0814 +vn -0.1976 0.8012 0.5648 +vn -0.1961 0.2983 0.9341 +vn -0.1808 -0.2241 0.9577 +vn -0.1875 -0.6326 0.7515 +vn -0.1928 -0.9388 0.2855 +vn 0.0129 -0.9305 -0.3660 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 4/4/4 5/5/5 6/6/6 +f 4/4/4 7/7/7 8/8/8 +f 9/9/9 10/10/10 11/11/11 +f 9/9/9 12/12/12 13/13/13 +f 9/9/9 14/14/14 12/12/12 +f 4/4/4 15/15/15 7/7/7 +f 16/16/16 17/17/17 18/18/18 +f 18/18/18 17/17/17 19/19/19 +f 9/9/9 11/11/11 20/20/20 +f 9/9/9 20/20/20 14/14/14 +f 13/13/13 12/12/12 21/21/21 +f 4/4/4 6/6/6 22/22/22 +f 4/4/4 22/22/22 15/15/15 +f 8/8/8 7/7/7 23/23/23 +f 14/14/14 24/24/24 12/12/12 +f 10/10/10 25/25/25 11/11/11 +f 11/11/11 26/26/26 20/20/20 +f 27/27/27 28/28/28 13/13/13 +f 29/29/29 30/30/30 31/31/31 +f 31/31/31 30/30/30 32/32/32 +f 5/5/5 33/33/33 6/6/6 +f 6/6/6 34/34/34 22/22/22 +f 35/35/35 36/36/36 8/8/8 +f 37/37/37 16/16/16 38/38/38 +f 38/38/38 16/16/16 18/18/18 +f 39/39/39 25/25/25 10/10/10 +f 11/11/11 38/38/38 26/26/26 +f 31/31/31 32/32/32 40/40/40 +f 41/41/41 33/33/33 5/5/5 +f 6/6/6 31/31/31 34/34/34 +f 42/42/42 37/37/37 43/43/43 +f 38/38/38 18/18/18 44/44/44 +f 39/39/39 43/43/43 25/25/25 +f 25/25/25 38/38/38 11/11/11 +f 45/45/45 29/29/29 33/33/33 +f 33/33/33 29/29/29 31/31/31 +f 41/41/41 45/45/45 33/33/33 +f 33/33/33 31/31/31 6/6/6 +f 43/43/43 37/37/37 25/25/25 +f 25/25/25 37/37/37 38/38/38 +f 39/39/39 42/42/42 43/43/43 +f 38/38/38 44/44/44 26/26/26 +f 41/41/41 46/46/46 45/45/45 +f 31/31/31 40/40/40 34/34/34 +f 47/47/47 48/48/48 16/16/16 +f 16/16/16 48/48/48 49/49/49 +f 49/49/49 35/35/35 17/17/17 +f 17/17/17 23/23/23 50/50/50 +f 37/37/37 42/42/42 47/47/47 +f 37/37/37 47/47/47 16/16/16 +f 16/16/16 49/49/49 17/17/17 +f 19/19/19 17/17/17 50/50/50 +f 42/42/42 39/39/39 51/51/51 +f 3/3/3 2/2/2 52/52/52 +f 52/52/52 2/2/2 28/28/28 +f 52/52/52 28/28/28 27/27/27 +f 27/27/27 13/13/13 21/21/21 +f 12/12/12 24/24/24 53/53/53 +f 12/12/12 53/53/53 21/21/21 +f 54/54/54 3/3/3 52/52/52 +f 53/53/53 27/27/27 21/21/21 +f 54/54/54 52/52/52 27/27/27 +f 55/55/55 3/3/3 54/54/54 +f 54/54/54 27/27/27 56/56/56 +f 56/56/56 27/27/27 53/53/53 +f 56/56/56 53/53/53 57/57/57 +f 57/57/57 53/53/53 24/24/24 +f 46/46/46 55/55/55 54/54/54 +f 30/30/30 54/54/54 56/56/56 +f 29/29/29 46/46/46 54/54/54 +f 58/58/58 56/56/56 57/57/57 +f 29/29/29 54/54/54 30/30/30 +f 59/59/59 46/46/46 41/41/41 +f 45/45/45 46/46/46 29/29/29 +f 32/32/32 30/30/30 56/56/56 +f 32/32/32 56/56/56 58/58/58 +f 49/49/49 36/36/36 35/35/35 +f 35/35/35 8/8/8 23/23/23 +f 48/48/48 36/36/36 49/49/49 +f 23/23/23 7/7/7 60/60/60 +f 17/17/17 35/35/35 23/23/23 +f 50/50/50 23/23/23 60/60/60 +f 61/61/61 62/62/62 63/63/63 +f 55/55/55 46/46/46 64/64/64 +f 3/3/3 55/55/55 65/65/65 +f 47/47/47 42/42/42 66/66/66 +f 67/67/67 68/68/68 69/69/69 +f 70/70/70 71/71/71 72/72/72 +f 73/73/73 71/71/71 74/74/74 +f 75/75/75 76/76/76 77/77/77 +f 78/78/78 79/79/79 80/80/80 +f 81/81/81 82/82/82 83/83/83 +f 84/84/84 85/85/85 86/86/86 +f 87/87/87 88/88/88 89/89/89 +f 90/90/90 36/36/36 48/48/48 +f 2/2/2 1/1/1 91/91/91 +f 90/90/90 48/48/48 92/92/92 +f 91/91/91 93/93/93 78/78/78 +f 64/64/64 46/46/46 59/59/59 +f 64/64/64 59/59/59 94/94/94 +f 95/95/95 42/42/42 51/51/51 +f 95/95/95 51/51/51 96/96/96 +f 97/97/97 96/96/96 98/98/98 +f 97/97/97 98/98/98 99/99/99 +f 90/90/90 100/100/100 101/101/101 +f 101/101/101 100/100/100 102/102/102 +f 91/91/91 1/1/1 93/93/93 +f 78/78/78 93/93/93 79/79/79 +f 80/80/80 79/79/79 103/103/103 +f 80/80/80 103/103/103 81/81/81 +f 81/81/81 103/103/103 104/104/104 +f 81/81/81 105/105/105 82/82/82 +f 81/81/81 104/104/104 105/105/105 +f 103/103/103 79/79/79 106/106/106 +f 82/82/82 105/105/105 107/107/107 +f 1/1/1 3/3/3 65/65/65 +f 93/93/93 1/1/1 108/108/108 +f 93/93/93 108/108/108 79/79/79 +f 79/79/79 108/108/108 106/106/106 +f 103/103/103 106/106/106 109/109/109 +f 103/103/103 109/109/109 104/104/104 +f 105/105/105 104/104/104 110/110/110 +f 105/105/105 110/110/110 107/107/107 +f 1/1/1 65/65/65 108/108/108 +f 106/106/106 108/108/108 111/111/111 +f 106/106/106 111/111/111 109/109/109 +f 109/109/109 111/111/111 112/112/112 +f 109/109/109 112/112/112 104/104/104 +f 104/104/104 112/112/112 113/113/113 +f 104/104/104 113/113/113 110/110/110 +f 65/65/65 55/55/55 64/64/64 +f 65/65/65 64/64/64 108/108/108 +f 108/108/108 64/64/64 94/94/94 +f 108/108/108 94/94/94 111/111/111 +f 111/111/111 94/94/94 114/114/114 +f 111/111/111 114/114/114 112/112/112 +f 112/112/112 114/114/114 115/115/115 +f 112/112/112 115/115/115 113/113/113 +f 113/113/113 115/115/115 75/75/75 +f 75/75/75 77/77/77 113/113/113 +f 113/113/113 77/77/77 110/110/110 +f 110/110/110 77/77/77 107/107/107 +f 116/116/116 117/117/117 118/118/118 +f 116/116/116 118/118/118 119/119/119 +f 120/120/120 121/121/121 122/122/122 +f 66/66/66 95/95/95 123/123/123 +f 123/123/123 95/95/95 97/97/97 +f 123/123/123 97/97/97 117/117/117 +f 121/121/121 124/124/124 125/125/125 +f 66/66/66 42/42/42 95/95/95 +f 117/117/117 97/97/97 118/118/118 +f 119/119/119 118/118/118 99/99/99 +f 119/119/119 126/126/126 124/124/124 +f 124/124/124 126/126/126 125/125/125 +f 121/121/121 125/125/125 122/122/122 +f 95/95/95 96/96/96 97/97/97 +f 118/118/118 97/97/97 99/99/99 +f 119/119/119 99/99/99 126/126/126 +f 125/125/125 126/126/126 127/127/127 +f 125/125/125 127/127/127 122/122/122 +f 122/122/122 127/127/127 128/128/128 +f 107/107/107 129/129/129 82/82/82 +f 82/82/82 129/129/129 83/83/83 +f 128/128/128 130/130/130 122/122/122 +f 77/77/77 131/131/131 107/107/107 +f 107/107/107 131/131/131 129/129/129 +f 129/129/129 84/84/84 83/83/83 +f 122/122/122 130/130/130 120/120/120 +f 129/129/129 131/131/131 85/85/85 +f 129/129/129 85/85/85 84/84/84 +f 76/76/76 132/132/132 77/77/77 +f 77/77/77 132/132/132 133/133/133 +f 77/77/77 133/133/133 131/131/131 +f 128/128/128 87/87/87 134/134/134 +f 128/128/128 134/134/134 130/130/130 +f 130/130/130 134/134/134 135/135/135 +f 73/73/73 132/132/132 76/76/76 +f 131/131/131 133/133/133 136/136/136 +f 131/131/131 136/136/136 85/85/85 +f 85/85/85 136/136/136 86/86/86 +f 87/87/87 89/89/89 134/134/134 +f 137/137/137 138/138/138 86/86/86 +f 73/73/73 74/74/74 132/132/132 +f 132/132/132 74/74/74 139/139/139 +f 132/132/132 139/139/139 133/133/133 +f 133/133/133 139/139/139 140/140/140 +f 133/133/133 140/140/140 136/136/136 +f 136/136/136 137/137/137 86/86/86 +f 141/141/141 142/142/142 143/143/143 +f 144/144/144 120/120/120 141/141/141 +f 141/141/141 120/120/120 145/145/145 +f 68/68/68 67/67/67 146/146/146 +f 68/68/68 146/146/146 147/147/147 +f 147/147/147 146/146/146 148/148/148 +f 147/147/147 148/148/148 144/144/144 +f 144/144/144 148/148/148 120/120/120 +f 141/141/141 145/145/145 142/142/142 +f 90/90/90 92/92/92 100/100/100 +f 101/101/101 102/102/102 69/69/69 +f 69/69/69 102/102/102 116/116/116 +f 69/69/69 116/116/116 67/67/67 +f 48/48/48 47/47/47 92/92/92 +f 100/100/100 123/123/123 102/102/102 +f 92/92/92 47/47/47 66/66/66 +f 92/92/92 66/66/66 100/100/100 +f 100/100/100 66/66/66 123/123/123 +f 102/102/102 123/123/123 117/117/117 +f 102/102/102 117/117/117 116/116/116 +f 67/67/67 116/116/116 119/119/119 +f 67/67/67 119/119/119 146/146/146 +f 142/142/142 145/145/145 135/135/135 +f 146/146/146 119/119/119 124/124/124 +f 146/146/146 124/124/124 121/121/121 +f 146/146/146 121/121/121 148/148/148 +f 148/148/148 121/121/121 120/120/120 +f 145/145/145 120/120/120 130/130/130 +f 145/145/145 130/130/130 135/135/135 +f 136/136/136 140/140/140 137/137/137 +f 134/134/134 89/89/89 135/135/135 +f 135/135/135 89/89/89 149/149/149 +f 135/135/135 149/149/149 142/142/142 +f 142/142/142 149/149/149 150/150/150 +f 142/142/142 150/150/150 143/143/143 +f 143/143/143 150/150/150 72/72/72 +f 71/71/71 70/70/70 74/74/74 +f 139/139/139 74/74/74 151/151/151 +f 139/139/139 151/151/151 140/140/140 +f 137/137/137 152/152/152 138/138/138 +f 138/138/138 152/152/152 153/153/153 +f 88/88/88 154/154/154 89/89/89 +f 149/149/149 155/155/155 150/150/150 +f 150/150/150 62/62/62 72/72/72 +f 72/72/72 62/62/62 70/70/70 +f 74/74/74 70/70/70 151/151/151 +f 140/140/140 151/151/151 152/152/152 +f 140/140/140 152/152/152 137/137/137 +f 153/153/153 152/152/152 154/154/154 +f 153/153/153 154/154/154 88/88/88 +f 154/154/154 155/155/155 89/89/89 +f 89/89/89 155/155/155 149/149/149 +f 155/155/155 62/62/62 150/150/150 +f 70/70/70 62/62/62 61/61/61 +f 70/70/70 61/61/61 151/151/151 +f 151/151/151 61/61/61 152/152/152 +f 152/152/152 63/63/63 154/154/154 +f 152/152/152 61/61/61 63/63/63 +f 154/154/154 63/63/63 155/155/155 +f 155/155/155 63/63/63 62/62/62 +f 156/156/156 68/68/157 147/147/158 +f 157/157/159 5/5/5 158/158/160 +f 158/158/160 5/5/5 4/4/4 +f 156/156/156 147/147/158 159/159/161 +f 159/159/161 147/147/158 144/144/162 +f 76/76/163 160/160/164 161/161/165 +f 162/162/166 68/68/157 156/156/156 +f 41/41/167 5/5/5 157/157/159 +f 161/161/165 73/73/168 76/76/163 +f 162/162/166 69/69/169 68/68/157 +f 158/158/160 36/36/170 163/163/171 +f 163/163/171 36/36/170 90/90/172 +f 8/8/8 36/36/170 158/158/160 +f 76/76/163 75/75/173 160/160/164 +f 162/162/166 101/101/174 69/69/169 +f 163/163/171 101/101/174 162/162/166 +f 163/163/171 90/90/172 101/101/174 +f 158/158/160 4/4/4 8/8/8 +f 164/164/175 94/94/176 165/165/177 +f 166/166/178 141/141/179 143/143/180 +f 159/159/161 141/141/179 166/166/178 +f 165/165/177 59/59/181 157/157/159 +f 157/157/159 59/59/181 41/41/167 +f 165/165/177 94/94/176 59/59/181 +f 75/75/173 115/115/182 160/160/164 +f 160/160/164 115/115/182 167/167/183 +f 168/168/184 73/73/168 161/161/165 +f 168/168/184 71/71/185 73/73/168 +f 168/168/184 72/72/186 71/71/185 +f 143/143/180 72/72/186 166/166/178 +f 159/159/161 144/144/162 141/141/179 +f 114/114/187 94/94/176 164/164/175 +f 167/167/183 115/115/182 114/114/187 +f 167/167/183 114/114/187 164/164/175 +f 166/166/178 72/72/186 168/168/184 +f 169/169/188 127/127/189 170/170/190 +f 170/170/190 127/127/189 126/126/191 +f 171/171/192 87/87/193 128/128/194 +f 88/88/195 171/171/192 172/172/196 +f 173/173/197 10/10/10 174/174/198 +f 174/174/198 10/10/10 9/9/9 +f 169/169/188 128/128/194 127/127/189 +f 172/172/196 153/153/199 88/88/195 +f 175/175/200 84/84/201 176/176/202 +f 176/176/202 84/84/201 86/86/203 +f 39/39/204 10/10/10 173/173/197 +f 177/177/205 51/51/206 173/173/197 +f 173/173/197 51/51/206 39/39/204 +f 177/177/205 96/96/207 51/51/206 +f 170/170/190 126/126/191 99/99/208 +f 170/170/190 99/99/208 178/178/209 +f 171/171/192 128/128/194 169/169/188 +f 171/171/192 88/88/195 87/87/193 +f 176/176/202 86/86/203 138/138/210 +f 84/84/201 175/175/200 83/83/211 +f 174/174/198 13/13/13 28/28/212 +f 174/174/198 9/9/9 13/13/13 +f 96/96/207 177/177/205 98/98/213 +f 98/98/213 177/177/205 178/178/209 +f 178/178/209 99/99/208 98/98/213 +f 172/172/196 138/138/210 153/153/199 +f 81/81/214 83/83/211 179/179/215 +f 179/179/215 83/83/211 175/175/200 +f 176/176/202 138/138/210 172/172/196 +f 180/180/216 80/80/217 81/81/214 +f 180/180/216 81/81/214 179/179/215 +f 181/181/218 91/91/219 78/78/220 +f 181/181/218 78/78/220 180/180/216 +f 180/180/216 78/78/220 80/80/217 +f 181/181/218 2/2/221 91/91/219 +f 174/174/198 28/28/212 2/2/221 +f 174/174/198 2/2/221 181/181/218 +f 170/170/222 162/162/223 156/156/224 +f 170/170/222 156/156/224 169/169/225 +f 169/169/225 156/156/224 159/159/226 +f 169/169/225 159/159/226 171/171/227 +f 171/171/227 159/159/226 166/166/228 +f 171/171/227 166/166/228 172/172/229 +f 172/172/229 166/166/228 168/168/230 +f 172/172/229 168/168/230 176/176/231 +f 176/176/231 168/168/230 161/161/232 +f 176/176/231 161/161/232 175/175/233 +f 175/175/233 161/161/232 160/160/234 +f 175/175/233 160/160/234 179/179/235 +f 179/179/235 160/160/234 167/167/236 +f 179/179/235 167/167/236 180/180/237 +f 180/180/237 167/167/236 164/164/238 +f 180/180/237 164/164/238 181/181/239 +f 181/181/239 164/164/238 165/165/240 +f 181/181/239 165/165/240 174/174/241 +f 174/174/241 165/165/240 157/157/242 +f 174/174/243 157/157/244 158/158/245 +f 174/174/243 158/158/245 173/173/246 +f 173/173/247 158/158/248 177/177/249 +f 177/177/249 158/158/248 163/163/250 +f 177/177/249 163/163/250 178/178/251 +f 178/178/251 163/163/250 162/162/223 +f 178/178/251 162/162/223 170/170/222 +f 182/182/252 183/183/253 184/184/254 +f 185/185/255 186/186/256 187/187/257 +f 187/187/257 188/188/258 189/189/259 +f 190/190/260 191/191/261 192/192/262 +f 193/193/263 194/194/264 195/195/265 +f 196/196/266 194/194/264 197/197/267 +f 198/198/268 194/194/264 193/193/263 +f 196/196/266 197/197/267 199/199/269 +f 195/195/265 194/194/264 200/200/270 +f 201/201/271 200/200/270 202/202/272 +f 203/203/273 204/204/274 205/205/275 +f 195/195/265 200/200/270 201/201/271 +f 203/203/273 206/206/276 204/204/274 +f 207/207/277 208/208/278 209/209/279 +f 199/199/269 210/210/280 211/211/281 +f 198/198/268 193/193/263 206/206/276 +f 193/193/263 195/195/265 208/208/278 +f 212/212/282 213/213/283 214/214/284 +f 211/211/281 214/214/284 215/215/285 +f 196/196/266 199/199/269 215/215/285 +f 215/215/285 199/199/269 211/211/281 +f 214/214/284 211/211/281 212/212/282 +f 199/199/269 197/197/267 210/210/280 +f 211/211/281 216/216/286 212/212/282 +f 194/194/264 198/198/268 197/197/267 +f 210/210/280 217/217/287 211/211/281 +f 211/211/281 217/217/287 216/216/286 +f 197/197/267 218/218/288 210/210/280 +f 216/216/286 217/217/287 219/219/289 +f 217/217/287 210/210/280 220/220/290 +f 221/221/291 222/222/292 205/205/275 +f 223/223/293 221/221/291 205/205/275 +f 223/223/293 205/205/275 204/204/274 +f 224/224/294 221/221/291 223/223/293 +f 225/225/295 224/224/294 223/223/293 +f 226/226/296 225/225/295 227/227/297 +f 210/210/280 218/218/288 220/220/290 +f 217/217/287 228/228/298 219/219/289 +f 229/229/299 220/220/290 218/218/288 +f 221/221/291 190/190/260 222/222/292 +f 207/207/277 223/223/293 204/204/274 +f 204/204/274 206/206/276 193/193/263 +f 204/204/274 208/208/278 207/207/277 +f 213/213/283 230/230/300 231/231/301 +f 213/213/283 231/231/301 214/214/284 +f 217/217/287 220/220/290 228/228/298 +f 190/190/260 192/192/262 222/222/292 +f 205/205/275 222/222/292 232/232/302 +f 205/205/275 232/232/302 203/203/273 +f 226/226/296 224/224/294 225/225/295 +f 207/207/277 225/225/295 223/223/293 +f 208/208/278 204/204/274 193/193/263 +f 214/214/284 233/233/303 215/215/285 +f 220/220/290 234/234/304 228/228/298 +f 214/214/284 231/231/301 233/233/303 +f 235/235/305 219/219/289 236/236/306 +f 236/236/306 219/219/289 228/228/298 +f 236/236/306 228/228/298 234/234/304 +f 234/234/304 220/220/290 237/237/307 +f 237/237/307 220/220/290 229/229/299 +f 229/229/299 218/218/288 238/238/308 +f 238/238/308 218/218/288 197/197/267 +f 206/206/276 203/203/273 239/239/309 +f 227/227/297 240/240/310 226/226/296 +f 229/229/299 241/241/311 237/237/307 +f 191/191/261 242/242/312 192/192/262 +f 222/222/292 192/192/262 243/243/313 +f 222/222/292 243/243/313 232/232/302 +f 238/238/308 197/197/267 239/239/309 +f 239/239/309 197/197/267 198/198/268 +f 244/244/314 240/240/310 227/227/297 +f 238/238/308 245/245/315 229/229/299 +f 246/246/316 236/236/306 234/234/304 +f 246/246/316 234/234/304 237/237/307 +f 241/241/311 229/229/299 245/245/315 +f 192/192/262 242/242/312 247/247/317 +f 192/192/262 247/247/317 243/243/313 +f 248/248/318 235/235/305 236/236/306 +f 249/249/319 237/237/307 241/241/311 +f 248/248/318 236/236/306 250/250/320 +f 251/251/321 252/252/322 253/253/323 +f 253/253/323 252/252/322 230/230/300 +f 230/230/300 254/254/324 231/231/301 +f 255/255/325 256/256/326 257/257/327 +f 244/244/314 257/257/327 240/240/310 +f 244/244/314 227/227/297 258/258/328 +f 259/259/329 260/260/330 261/261/331 +f 261/261/331 262/262/332 263/263/333 +f 263/263/333 262/262/332 264/264/334 +f 265/265/335 266/266/336 267/267/337 +f 268/268/338 264/264/334 266/266/336 +f 269/269/339 259/259/329 261/261/331 +f 263/263/333 264/264/334 268/268/338 +f 265/265/335 268/268/338 266/266/336 +f 202/202/272 265/265/335 201/201/271 +f 270/270/340 268/268/338 265/265/335 +f 271/271/341 269/269/339 261/261/331 +f 271/271/341 261/261/331 272/272/342 +f 272/272/342 261/261/331 263/263/333 +f 270/270/340 263/263/333 268/268/338 +f 273/273/343 270/270/340 265/265/335 +f 273/273/343 265/265/335 202/202/272 +f 272/272/342 263/263/333 274/274/344 +f 274/274/344 263/263/333 270/270/340 +f 252/252/322 272/272/342 274/274/344 +f 254/254/324 270/270/340 273/273/343 +f 275/275/345 276/276/346 271/271/341 +f 275/275/345 271/271/341 272/272/342 +f 254/254/324 274/274/344 270/270/340 +f 196/196/266 200/200/270 194/194/264 +f 275/275/345 272/272/342 252/252/322 +f 233/233/303 273/273/343 202/202/272 +f 215/215/285 202/202/272 200/200/270 +f 200/200/270 196/196/266 215/215/285 +f 273/273/343 233/233/303 231/231/301 +f 273/273/343 231/231/301 254/254/324 +f 274/274/344 254/254/324 252/252/322 +f 277/277/347 275/275/345 251/251/321 +f 251/251/321 275/275/345 252/252/322 +f 230/230/300 252/252/322 254/254/324 +f 233/233/303 202/202/272 215/215/285 +f 275/275/345 277/277/347 276/276/346 +f 271/271/341 276/276/346 278/278/348 +f 271/271/341 278/278/348 269/269/339 +f 269/269/339 278/278/348 259/259/329 +f 279/279/349 280/280/350 248/248/318 +f 281/281/351 279/279/349 248/248/318 +f 250/250/320 281/281/351 248/248/318 +f 282/282/352 279/279/349 281/281/351 +f 246/246/316 250/250/320 236/236/306 +f 283/283/353 282/282/352 281/281/351 +f 283/283/353 281/281/351 284/284/354 +f 284/284/354 281/281/351 250/250/320 +f 285/285/355 250/250/320 246/246/316 +f 286/286/356 282/282/352 283/283/353 +f 284/284/354 250/250/320 285/285/355 +f 285/285/355 246/246/316 249/249/319 +f 249/249/319 246/246/316 237/237/307 +f 287/287/357 283/283/353 284/284/354 +f 286/286/356 283/283/353 287/287/357 +f 287/287/357 284/284/354 285/285/355 +f 288/288/358 285/285/355 249/249/319 +f 289/289/359 286/286/356 287/287/357 +f 290/290/360 287/287/357 285/285/355 +f 291/291/361 249/249/319 241/241/311 +f 291/291/361 241/241/311 245/245/315 +f 290/290/360 285/285/355 288/288/358 +f 292/292/362 288/288/358 249/249/319 +f 292/292/362 249/249/319 291/291/361 +f 293/293/363 289/289/359 287/287/357 +f 293/293/363 287/287/357 290/290/360 +f 294/294/364 295/295/365 289/289/359 +f 294/294/364 289/289/359 293/293/363 +f 296/296/366 293/293/363 290/290/360 +f 296/296/366 290/290/360 288/288/358 +f 297/297/367 288/288/358 292/292/362 +f 239/239/309 245/245/315 238/238/308 +f 297/297/367 296/296/366 288/288/358 +f 247/247/317 292/292/362 291/291/361 +f 243/243/313 291/291/361 245/245/315 +f 243/243/313 245/245/315 239/239/309 +f 298/298/368 294/294/364 293/293/363 +f 298/298/368 293/293/363 296/296/366 +f 243/243/313 247/247/317 291/291/361 +f 299/299/369 296/296/366 297/297/367 +f 300/300/370 294/294/364 298/298/368 +f 301/301/371 296/296/366 299/299/369 +f 247/247/317 297/297/367 292/292/362 +f 232/232/302 243/243/313 239/239/309 +f 301/301/371 298/298/368 296/296/366 +f 242/242/312 299/299/369 297/297/367 +f 242/242/312 297/297/367 247/247/317 +f 206/206/276 239/239/309 198/198/268 +f 301/301/371 299/299/369 302/302/372 +f 301/301/371 303/303/373 298/298/368 +f 298/298/368 303/303/373 300/300/370 +f 304/304/374 300/300/370 303/303/373 +f 303/303/373 301/301/371 302/302/372 +f 191/191/261 302/302/372 299/299/369 +f 191/191/261 299/299/369 242/242/312 +f 203/203/273 232/232/302 239/239/309 +f 294/294/364 300/300/370 295/295/365 +f 289/289/359 295/295/365 305/305/375 +f 289/289/359 305/305/375 286/286/356 +f 282/282/352 286/286/356 306/306/376 +f 282/282/352 306/306/376 279/279/349 +f 277/277/347 307/307/377 308/308/378 +f 277/277/347 308/308/378 276/276/346 +f 276/276/346 309/309/379 278/278/348 +f 278/278/348 309/309/379 310/310/380 +f 278/278/348 310/310/380 259/259/329 +f 259/259/329 310/310/380 311/311/381 +f 304/304/374 312/312/382 300/300/370 +f 276/276/346 308/308/378 309/309/379 +f 279/279/349 306/306/376 313/313/383 +f 279/279/349 313/313/383 280/280/350 +f 310/310/380 314/314/384 311/311/381 +f 304/304/374 315/315/385 312/312/382 +f 300/300/370 312/312/382 295/295/365 +f 295/295/365 316/316/386 317/317/387 +f 295/295/365 317/317/387 305/305/375 +f 286/286/356 305/305/375 318/318/388 +f 286/286/356 318/318/388 306/306/376 +f 280/280/350 313/313/383 319/319/389 +f 307/307/377 320/320/390 321/321/391 +f 307/307/377 321/321/391 308/308/378 +f 315/315/385 322/322/392 312/312/382 +f 312/312/382 316/316/386 295/295/365 +f 256/256/326 323/323/393 185/185/255 +f 185/185/255 323/323/393 324/324/394 +f 185/185/255 324/324/394 186/186/256 +f 324/324/394 325/325/395 186/186/256 +f 323/323/393 256/256/326 255/255/325 +f 255/255/325 257/257/327 244/244/314 +f 326/326/396 324/324/394 323/323/393 +f 327/327/397 323/323/393 255/255/325 +f 328/328/398 255/255/325 244/244/314 +f 328/328/398 244/244/314 329/329/399 +f 329/329/399 244/244/314 258/258/328 +f 209/209/279 258/258/328 207/207/277 +f 330/330/400 325/325/395 324/324/394 +f 330/330/400 324/324/394 326/326/396 +f 331/331/401 326/326/396 323/323/393 +f 331/331/401 323/323/393 327/327/397 +f 332/332/402 327/327/397 255/255/325 +f 332/332/402 255/255/325 328/328/398 +f 267/267/337 329/329/399 258/258/328 +f 267/267/337 258/258/328 209/209/279 +f 195/195/265 209/209/279 208/208/278 +f 330/330/400 326/326/396 331/331/401 +f 333/333/403 331/331/401 327/327/397 +f 333/333/403 327/327/397 332/332/402 +f 334/334/404 328/328/398 329/329/399 +f 260/260/330 331/331/401 333/333/403 +f 334/334/404 332/332/402 328/328/398 +f 334/334/404 329/329/399 267/267/337 +f 201/201/271 209/209/279 195/195/265 +f 314/314/384 335/335/405 330/330/400 +f 311/311/381 330/330/400 331/331/401 +f 311/311/381 331/331/401 260/260/330 +f 262/262/332 333/333/403 332/332/402 +f 262/262/332 332/332/402 334/334/404 +f 266/266/336 334/334/404 267/267/337 +f 201/201/271 267/267/337 209/209/279 +f 260/260/330 333/333/403 262/262/332 +f 264/264/334 262/262/332 334/334/404 +f 334/334/404 266/266/336 264/264/334 +f 330/330/400 311/311/381 314/314/384 +f 259/259/329 311/311/381 260/260/330 +f 261/261/331 260/260/330 262/262/332 +f 265/265/335 267/267/337 201/201/271 +f 315/315/385 336/336/406 322/322/392 +f 305/305/375 317/317/387 337/337/407 +f 305/305/375 337/337/407 318/318/388 +f 318/318/388 338/338/408 306/306/376 +f 306/306/376 338/338/408 313/313/383 +f 313/313/383 338/338/408 339/339/409 +f 313/313/383 339/339/409 319/319/389 +f 308/308/378 340/340/410 309/309/379 +f 309/309/379 340/340/410 310/310/380 +f 330/330/400 335/335/405 325/325/395 +f 322/322/392 341/341/411 312/312/382 +f 312/312/382 341/341/411 316/316/386 +f 318/318/388 337/337/407 338/338/408 +f 321/321/391 342/342/412 308/308/378 +f 308/308/378 342/342/412 340/340/410 +f 340/340/410 343/343/413 310/310/380 +f 310/310/380 343/343/413 314/314/384 +f 325/325/395 344/344/414 186/186/256 +f 186/186/256 344/344/414 187/187/257 +f 316/316/386 345/345/415 317/317/387 +f 317/317/387 345/345/415 337/337/407 +f 314/314/384 343/343/413 346/346/416 +f 314/314/384 346/346/416 335/335/405 +f 344/344/414 188/188/258 187/187/257 +f 227/227/297 225/225/295 258/258/328 +f 258/258/328 225/225/295 207/207/277 +f 346/346/416 347/347/417 335/335/405 +f 335/335/405 347/347/417 325/325/395 +f 325/325/395 347/347/417 344/344/414 +f 322/322/392 336/336/406 341/341/411 +f 338/338/408 348/348/418 339/339/409 +f 339/339/409 349/349/419 319/319/389 +f 319/319/389 349/349/419 350/350/420 +f 351/351/421 352/352/422 320/320/390 +f 320/320/390 352/352/422 321/321/391 +f 321/321/391 352/352/422 342/342/412 +f 189/189/259 188/188/258 353/353/423 +f 189/189/259 353/353/423 354/354/424 +f 354/354/424 355/355/425 336/336/406 +f 336/336/406 355/355/425 341/341/411 +f 341/341/411 356/356/426 316/316/386 +f 316/316/386 356/356/426 345/345/415 +f 345/345/415 357/357/427 337/337/407 +f 337/337/407 357/357/427 338/338/408 +f 338/338/408 357/357/427 348/348/418 +f 339/339/409 348/348/418 349/349/419 +f 350/350/420 349/349/419 358/358/428 +f 350/350/420 358/358/428 351/351/421 +f 351/351/421 358/358/428 359/359/429 +f 351/351/421 359/359/429 352/352/422 +f 340/340/410 360/360/430 343/343/413 +f 343/343/413 360/360/430 346/346/416 +f 347/347/417 361/361/431 344/344/414 +f 344/344/414 362/362/432 188/188/258 +f 353/353/423 355/355/425 354/354/424 +f 341/341/411 355/355/425 363/363/433 +f 341/341/411 363/363/433 356/356/426 +f 352/352/422 364/364/434 342/342/412 +f 342/342/412 364/364/434 340/340/410 +f 340/340/410 364/364/434 360/360/430 +f 346/346/416 365/365/435 347/347/417 +f 361/361/431 362/362/432 344/344/414 +f 188/188/258 362/362/432 353/353/423 +f 345/345/415 356/356/426 357/357/427 +f 348/348/418 366/366/436 349/349/419 +f 359/359/429 367/367/437 352/352/422 +f 360/360/430 365/365/435 346/346/416 +f 347/347/417 365/365/435 361/361/431 +f 355/355/425 368/368/438 363/363/433 +f 359/359/429 358/358/428 367/367/437 +f 352/352/422 367/367/437 364/364/434 +f 361/361/431 369/369/439 362/362/432 +f 353/353/423 362/362/432 369/369/439 +f 357/357/427 356/356/426 370/370/440 +f 357/357/427 370/370/440 348/348/418 +f 348/348/418 370/370/440 366/366/436 +f 366/366/436 371/371/441 349/349/419 +f 349/349/419 371/371/441 358/358/428 +f 364/364/434 372/372/442 360/360/430 +f 360/360/430 372/372/442 365/365/435 +f 365/365/435 373/373/443 361/361/431 +f 361/361/431 373/373/443 369/369/439 +f 369/369/439 374/374/444 353/353/423 +f 353/353/423 374/374/444 355/355/425 +f 355/355/425 374/374/444 368/368/438 +f 363/363/433 375/375/445 356/356/426 +f 356/356/426 375/375/445 370/370/440 +f 358/358/428 371/371/441 367/367/437 +f 372/372/442 373/373/443 365/365/435 +f 368/368/438 375/375/445 363/363/433 +f 370/370/440 376/376/446 366/366/436 +f 371/371/441 377/377/447 367/367/437 +f 367/367/437 377/377/447 364/364/434 +f 364/364/434 377/377/447 372/372/442 +f 373/373/443 378/378/448 369/369/439 +f 368/368/438 374/374/444 375/375/445 +f 375/375/445 379/379/449 370/370/440 +f 370/370/440 379/379/449 376/376/446 +f 366/366/436 376/376/446 371/371/441 +f 372/372/442 378/378/448 373/373/443 +f 369/369/439 378/378/448 184/184/254 +f 369/369/439 184/184/254 374/374/444 +f 376/376/446 380/380/450 371/371/441 +f 371/371/441 380/380/450 377/377/447 +f 377/377/447 182/182/252 372/372/442 +f 374/374/444 184/184/254 183/183/253 +f 374/374/444 183/183/253 375/375/445 +f 375/375/445 183/183/253 379/379/449 +f 379/379/449 183/183/253 376/376/446 +f 377/377/447 380/380/450 182/182/252 +f 372/372/442 182/182/252 378/378/448 +f 378/378/448 182/182/252 184/184/254 +f 376/376/446 183/183/253 380/380/450 +f 380/380/450 183/183/253 182/182/252 +f 381/381/451 307/307/452 382/382/453 +f 319/319/454 383/383/455 384/384/456 +f 384/384/456 280/280/457 319/319/454 +f 381/381/451 320/320/458 307/307/452 +f 385/385/459 351/351/460 381/381/451 +f 381/381/451 351/351/460 320/320/458 +f 386/386/461 216/216/462 219/219/463 +f 351/351/460 385/385/459 350/350/464 +f 350/350/464 385/385/459 383/383/455 +f 319/319/454 350/350/464 383/383/455 +f 387/387/465 248/248/466 384/384/456 +f 384/384/456 248/248/466 280/280/457 +f 388/388/467 213/213/468 212/212/469 +f 389/389/470 213/213/468 388/388/467 +f 382/382/453 277/277/471 251/251/472 +f 382/382/453 251/251/472 390/390/473 +f 388/388/467 212/212/469 386/386/461 +f 386/386/461 212/212/469 216/216/462 +f 307/307/452 277/277/471 382/382/453 +f 219/219/463 387/387/465 386/386/461 +f 390/390/473 253/253/474 389/389/470 +f 387/387/465 235/235/475 248/248/466 +f 219/219/463 235/235/475 387/387/465 +f 389/389/470 230/230/476 213/213/468 +f 251/251/472 253/253/474 390/390/473 +f 389/389/470 253/253/474 230/230/476 +f 391/391/477 189/189/478 392/392/479 +f 392/392/479 189/189/478 354/354/480 +f 392/392/479 354/354/480 336/336/481 +f 393/393/482 303/303/483 394/394/484 +f 304/304/485 303/303/483 393/393/482 +f 189/189/478 391/391/477 187/187/486 +f 392/392/479 315/315/487 393/393/482 +f 393/393/482 315/315/487 304/304/485 +f 392/392/479 336/336/481 315/315/487 +f 395/395/488 185/185/489 391/391/477 +f 391/391/477 185/185/489 187/187/486 +f 396/396/490 257/257/491 397/397/492 +f 398/398/493 224/224/494 396/396/490 +f 396/396/490 224/224/494 226/226/495 +f 224/224/494 398/398/493 221/221/496 +f 399/399/497 221/221/496 398/398/493 +f 191/191/498 190/190/499 399/399/497 +f 394/394/484 303/303/483 302/302/488 +f 397/397/492 257/257/491 256/256/500 +f 190/190/499 221/221/496 399/399/497 +f 397/397/492 256/256/500 395/395/488 +f 395/395/488 256/256/500 185/185/489 +f 394/394/484 191/191/498 399/399/497 +f 394/394/484 302/302/488 191/191/498 +f 240/240/501 257/257/491 396/396/490 +f 226/226/495 240/240/501 396/396/490 +f 400/400/502 401/401/503 402/402/504 +f 402/402/504 401/401/503 403/403/505 +f 402/402/506 403/403/507 404/404/508 +f 404/404/508 403/403/507 405/405/509 +f 404/404/510 405/405/511 406/406/512 +f 406/406/512 405/405/511 407/407/513 +f 406/406/512 407/407/513 408/408/514 +f 408/408/514 407/407/513 409/409/515 +f 408/408/514 409/409/515 410/410/516 +f 410/410/516 409/409/515 411/411/517 +f 410/410/516 411/411/517 412/412/518 +f 410/410/516 412/412/518 413/413/519 +f 413/413/519 412/412/518 414/414/520 +f 414/414/520 412/412/518 415/415/521 +f 414/414/522 415/415/523 416/416/524 +f 416/416/524 415/415/523 417/417/525 +f 416/416/524 417/417/525 418/418/526 +f 418/418/526 417/417/525 419/419/527 +f 418/418/526 419/419/527 420/420/528 +f 420/420/528 419/419/527 421/421/529 +f 420/420/528 421/421/529 422/422/530 +f 422/422/530 421/421/529 401/401/503 +f 422/422/530 401/401/503 400/400/502 +f 397/397/531 412/412/532 411/411/533 +f 397/397/531 411/411/533 396/396/534 +f 396/396/534 411/411/533 409/409/535 +f 409/409/535 407/407/536 396/396/534 +f 396/396/534 407/407/536 398/398/537 +f 407/407/536 405/405/538 398/398/537 +f 398/398/537 405/405/538 399/399/539 +f 405/405/538 403/403/540 399/399/539 +f 399/399/541 403/403/541 394/394/541 +f 403/403/542 401/401/542 394/394/542 +f 394/394/543 401/401/543 393/393/543 +f 393/393/544 401/401/544 421/421/544 +f 393/393/545 421/421/545 392/392/545 +f 392/392/546 421/421/546 419/419/546 +f 392/392/547 419/419/548 391/391/549 +f 391/391/549 419/419/548 417/417/550 +f 417/417/551 415/415/551 391/391/551 +f 391/391/552 415/415/552 395/395/552 +f 415/415/553 412/412/532 395/395/554 +f 395/395/554 412/412/532 397/397/531 +f 387/387/555 400/400/555 402/402/555 +f 387/387/556 402/402/556 386/386/556 +f 402/402/557 404/404/558 386/386/559 +f 386/386/559 404/404/558 388/388/560 +f 388/388/560 404/404/558 406/406/561 +f 388/388/560 406/406/561 408/408/562 +f 388/388/560 408/408/562 389/389/563 +f 389/389/563 408/408/562 410/410/564 +f 389/389/565 410/410/565 390/390/565 +f 390/390/566 410/410/567 413/413/568 +f 390/390/566 413/413/568 382/382/569 +f 382/382/569 413/413/568 414/414/570 +f 382/382/569 414/414/570 381/381/571 +f 414/414/570 416/416/572 381/381/571 +f 381/381/571 416/416/572 385/385/573 +f 416/416/572 418/418/574 385/385/573 +f 385/385/573 418/418/574 383/383/575 +f 383/383/575 418/418/574 420/420/576 +f 383/383/577 420/420/578 384/384/579 +f 384/384/579 420/420/578 422/422/530 +f 384/384/579 422/422/530 387/387/580 +f 387/387/580 422/422/530 400/400/502 +f 423/423/581 424/424/582 425/425/583 +f 426/426/584 427/427/585 428/428/586 +f 429/429/587 430/430/588 431/431/589 +f 429/429/587 432/432/590 433/433/591 +f 434/434/592 435/435/593 432/432/590 +f 436/436/594 437/437/595 438/438/596 +f 429/429/587 434/434/592 432/432/590 +f 426/426/584 439/439/597 440/440/598 +f 426/426/584 440/440/598 441/441/599 +f 429/429/587 431/431/589 434/434/592 +f 433/433/591 432/432/590 442/442/600 +f 426/426/584 428/428/586 439/439/597 +f 441/441/599 443/443/601 444/444/602 +f 445/445/603 446/446/604 436/436/594 +f 430/430/588 447/447/605 431/431/589 +f 431/431/589 448/448/606 434/434/592 +f 435/435/593 449/449/607 432/432/590 +f 432/432/590 449/449/607 442/442/600 +f 450/450/608 451/451/609 452/452/610 +f 428/428/586 453/453/611 439/439/597 +f 440/440/598 454/454/612 441/441/599 +f 441/441/599 454/454/612 443/443/601 +f 436/436/594 438/438/596 455/455/613 +f 430/430/588 456/456/614 447/447/605 +f 431/431/589 447/447/605 448/448/606 +f 442/442/600 457/457/615 433/433/591 +f 427/427/585 458/458/616 428/428/586 +f 459/459/617 460/460/618 444/444/602 +f 445/445/603 436/436/594 461/461/619 +f 461/461/619 436/436/594 455/455/613 +f 430/430/588 462/462/620 456/456/614 +f 463/463/621 464/464/622 458/458/616 +f 458/458/616 464/464/622 450/450/608 +f 452/452/610 451/451/609 465/465/623 +f 427/427/585 466/466/624 458/458/616 +f 460/460/618 459/459/617 425/425/583 +f 467/467/625 468/468/626 457/457/615 +f 458/458/616 450/450/608 452/452/610 +f 428/428/586 458/458/616 453/453/611 +f 469/469/627 445/445/603 456/456/614 +f 456/456/614 445/445/603 461/461/619 +f 456/456/614 461/461/619 447/447/605 +f 447/447/605 461/461/619 448/448/606 +f 466/466/624 463/463/621 458/458/616 +f 458/458/616 452/452/610 453/453/611 +f 453/453/611 452/452/610 465/465/623 +f 470/470/628 471/471/629 472/472/630 +f 470/470/628 472/472/630 473/473/631 +f 474/474/632 473/473/631 459/459/617 +f 437/437/595 474/474/632 475/475/633 +f 470/470/628 473/473/631 446/446/604 +f 446/446/604 473/473/631 474/474/632 +f 469/469/627 470/470/628 446/446/604 +f 436/436/594 446/446/604 474/474/632 +f 436/436/594 474/474/632 437/437/595 +f 476/476/634 470/470/628 469/469/627 +f 469/469/627 446/446/604 445/445/603 +f 455/455/613 448/448/606 461/461/619 +f 456/456/614 462/462/620 469/469/627 +f 476/476/634 469/469/627 462/462/620 +f 476/476/634 462/462/620 477/477/635 +f 457/457/615 442/442/600 467/467/625 +f 468/468/626 478/478/636 479/479/637 +f 478/478/636 468/468/626 467/467/625 +f 480/480/638 442/442/600 449/449/607 +f 480/480/638 449/449/607 435/435/639 +f 481/481/640 478/478/636 467/467/625 +f 480/480/638 467/467/625 442/442/600 +f 481/481/640 467/467/625 480/480/638 +f 481/481/640 480/480/638 482/482/641 +f 483/483/642 484/484/643 463/463/621 +f 464/464/622 484/484/643 478/478/636 +f 482/482/641 480/480/638 485/485/644 +f 486/486/645 483/483/642 463/463/621 +f 463/463/621 484/484/643 464/464/622 +f 464/464/622 478/478/636 481/481/640 +f 450/450/608 464/464/622 481/481/640 +f 466/466/624 486/486/645 463/463/621 +f 450/450/608 481/481/640 451/451/609 +f 451/451/609 481/481/640 482/482/641 +f 451/451/609 482/482/641 485/485/644 +f 460/460/618 425/425/583 424/424/582 +f 459/459/617 444/444/602 443/443/601 +f 472/472/630 423/423/581 425/425/583 +f 472/472/630 425/425/583 473/473/631 +f 475/475/633 443/443/601 454/454/612 +f 473/473/631 425/425/583 459/459/617 +f 474/474/632 459/459/617 443/443/601 +f 474/474/632 443/443/601 475/475/633 +f 487/487/646 488/488/647 489/489/648 +f 490/490/649 487/487/646 489/489/648 +f 478/478/636 484/484/643 491/491/650 +f 471/471/629 470/470/628 492/492/651 +f 493/493/652 494/494/653 495/495/654 +f 496/496/655 497/497/656 498/498/657 +f 499/499/658 497/497/656 500/500/659 +f 501/501/660 502/502/661 503/503/662 +f 504/504/663 505/505/664 506/506/665 +f 507/507/666 508/508/667 509/509/668 +f 507/507/666 509/509/668 510/510/669 +f 476/476/634 477/477/635 470/470/628 +f 479/479/637 478/478/636 491/491/650 +f 479/479/637 491/491/650 511/511/670 +f 511/511/670 512/512/671 513/513/672 +f 483/483/642 486/486/645 514/514/673 +f 492/492/651 470/470/628 477/477/635 +f 492/492/651 477/477/635 515/515/674 +f 516/516/675 515/515/674 517/517/676 +f 516/516/675 517/517/676 518/518/677 +f 424/424/582 423/423/581 519/519/678 +f 519/519/678 423/423/581 520/520/679 +f 519/519/678 520/520/679 495/495/654 +f 511/511/670 491/491/650 512/512/671 +f 513/513/672 512/512/671 521/521/680 +f 522/522/681 513/513/672 523/523/682 +f 522/522/681 523/523/682 501/501/660 +f 501/501/660 523/523/682 524/524/683 +f 501/501/660 524/524/683 502/502/661 +f 513/513/672 521/521/680 523/523/682 +f 512/512/671 491/491/650 525/525/684 +f 512/512/671 525/525/684 521/521/680 +f 491/491/650 484/484/643 525/525/684 +f 521/521/680 525/525/684 526/526/685 +f 521/521/680 526/526/685 523/523/682 +f 523/523/682 526/526/685 527/527/686 +f 523/523/682 527/527/686 524/524/683 +f 524/524/683 527/527/686 528/528/687 +f 524/524/683 528/528/687 502/502/661 +f 502/502/661 528/528/687 529/529/688 +f 525/525/684 530/530/689 526/526/685 +f 525/525/684 483/483/642 530/530/689 +f 526/526/685 530/530/689 531/531/690 +f 526/526/685 531/531/690 532/532/691 +f 526/526/685 532/532/691 527/527/686 +f 527/527/686 532/532/691 533/533/692 +f 527/527/686 533/533/692 528/528/687 +f 528/528/687 533/533/692 534/534/693 +f 525/525/684 484/484/643 483/483/642 +f 530/530/689 514/514/673 531/531/690 +f 530/530/689 483/483/642 514/514/673 +f 531/531/690 514/514/673 535/535/694 +f 531/531/690 535/535/694 532/532/691 +f 532/532/691 535/535/694 536/536/695 +f 532/532/691 536/536/695 533/533/692 +f 533/533/692 536/536/695 537/537/696 +f 533/533/692 537/537/696 534/534/693 +f 534/534/693 537/537/696 538/538/697 +f 538/538/697 539/539/698 540/540/699 +f 538/538/697 540/540/699 534/534/693 +f 534/534/693 540/540/699 541/541/700 +f 534/534/693 541/541/700 528/528/687 +f 528/528/687 541/541/700 529/529/688 +f 502/502/661 529/529/688 542/542/701 +f 502/502/661 542/542/701 503/503/662 +f 543/543/702 544/544/703 545/545/704 +f 546/546/705 545/545/704 547/547/706 +f 548/548/707 547/547/706 549/549/708 +f 548/548/707 549/549/708 550/550/709 +f 471/471/629 492/492/651 544/544/703 +f 544/544/703 516/516/675 545/545/704 +f 545/545/704 551/551/710 547/547/706 +f 547/547/706 551/551/710 549/549/708 +f 544/544/703 492/492/651 516/516/675 +f 545/545/704 516/516/675 551/551/710 +f 492/492/651 515/515/674 516/516/675 +f 551/551/710 516/516/675 518/518/677 +f 552/552/711 550/550/709 553/553/712 +f 518/518/677 554/554/713 551/551/710 +f 551/551/710 554/554/713 549/549/708 +f 549/549/708 554/554/713 555/555/714 +f 549/549/708 555/555/714 550/550/709 +f 550/550/709 555/555/714 553/553/712 +f 503/503/662 542/542/701 504/504/663 +f 553/553/712 556/556/715 557/557/716 +f 553/553/712 557/557/716 552/552/711 +f 552/552/711 557/557/716 558/558/717 +f 539/539/698 559/559/718 540/540/699 +f 540/540/699 559/559/718 541/541/700 +f 541/541/700 559/559/718 560/560/719 +f 541/541/700 560/560/719 529/529/688 +f 529/529/688 560/560/719 542/542/701 +f 542/542/701 505/505/664 504/504/663 +f 539/539/698 561/561/720 559/559/718 +f 560/560/719 505/505/664 542/542/701 +f 556/556/715 562/562/721 563/563/722 +f 556/556/715 563/563/722 557/557/716 +f 561/561/720 564/564/723 559/559/718 +f 559/559/718 564/564/723 560/560/719 +f 560/560/719 565/565/724 505/505/664 +f 505/505/664 565/565/724 566/566/725 +f 505/505/664 566/566/725 506/506/665 +f 557/557/716 563/563/722 567/567/726 +f 557/557/716 567/567/726 558/558/717 +f 560/560/719 564/564/723 565/565/724 +f 562/562/721 510/510/669 563/563/722 +f 499/499/658 568/568/727 561/561/720 +f 561/561/720 568/568/727 564/564/723 +f 566/566/725 569/569/728 506/506/665 +f 498/498/657 570/570/729 571/571/730 +f 570/570/729 572/572/731 573/573/732 +f 570/570/729 573/573/732 571/571/730 +f 572/572/731 574/574/733 575/575/734 +f 572/572/731 575/575/734 573/573/732 +f 494/494/653 493/493/652 576/576/735 +f 494/494/653 576/576/735 574/574/733 +f 574/574/733 576/576/735 577/577/736 +f 574/574/733 577/577/736 575/575/734 +f 495/495/654 520/520/679 546/546/705 +f 495/495/654 546/546/705 493/493/652 +f 571/571/730 573/573/732 567/567/726 +f 423/423/581 472/472/630 471/471/629 +f 520/520/679 423/423/581 543/543/702 +f 520/520/679 543/543/702 546/546/705 +f 576/576/735 493/493/652 548/548/707 +f 576/576/735 548/548/707 577/577/736 +f 575/575/734 577/577/736 552/552/711 +f 573/573/732 575/575/734 558/558/717 +f 423/423/581 471/471/629 544/544/703 +f 423/423/581 544/544/703 543/543/702 +f 493/493/652 546/546/705 548/548/707 +f 575/575/734 552/552/711 558/558/717 +f 573/573/732 558/558/717 567/567/726 +f 543/543/702 545/545/704 546/546/705 +f 546/546/705 547/547/706 548/548/707 +f 577/577/736 548/548/707 550/550/709 +f 577/577/736 550/550/709 552/552/711 +f 499/499/658 500/500/659 568/568/727 +f 564/564/723 568/568/727 578/578/737 +f 564/564/723 578/578/737 565/565/724 +f 565/565/724 578/578/737 566/566/725 +f 510/510/669 579/579/738 563/563/722 +f 563/563/722 579/579/738 567/567/726 +f 578/578/737 568/568/727 580/580/739 +f 578/578/737 580/580/739 581/581/740 +f 578/578/737 581/581/740 566/566/725 +f 566/566/725 581/581/740 569/569/728 +f 569/569/728 581/581/740 508/508/667 +f 569/569/728 508/508/667 507/507/666 +f 509/509/668 579/579/738 510/510/669 +f 571/571/730 496/496/655 498/498/657 +f 567/567/726 582/582/741 571/571/730 +f 571/571/730 582/582/741 583/583/742 +f 571/571/730 583/583/742 496/496/655 +f 497/497/656 496/496/655 500/500/659 +f 568/568/727 500/500/659 580/580/739 +f 581/581/740 580/580/739 487/487/646 +f 567/567/726 579/579/738 582/582/741 +f 496/496/655 583/583/742 488/488/647 +f 496/496/655 488/488/647 500/500/659 +f 500/500/659 488/488/647 580/580/739 +f 581/581/740 487/487/646 508/508/667 +f 508/508/667 487/487/646 490/490/649 +f 508/508/667 490/490/649 509/509/668 +f 509/509/668 490/490/649 579/579/738 +f 579/579/738 490/490/649 582/582/741 +f 582/582/741 489/489/648 583/583/742 +f 583/583/742 489/489/648 488/488/647 +f 580/580/739 488/488/647 487/487/646 +f 582/582/741 490/490/649 489/489/648 +f 584/584/743 585/585/744 427/427/585 +f 586/586/220 494/494/745 587/587/746 +f 494/494/745 574/574/747 587/587/746 +f 427/427/585 426/426/584 584/584/743 +f 584/584/743 441/441/599 444/444/602 +f 539/539/748 588/588/749 561/561/750 +f 586/586/220 495/495/751 494/494/745 +f 587/587/746 572/572/752 570/570/753 +f 589/589/753 495/495/751 586/586/220 +f 590/590/754 460/460/755 424/424/756 +f 590/590/754 424/424/756 591/591/196 +f 584/584/743 460/460/755 590/590/754 +f 444/444/602 460/460/755 584/584/743 +f 585/585/744 466/466/757 427/427/585 +f 538/538/758 592/592/759 539/539/748 +f 588/588/749 539/539/748 592/592/759 +f 495/495/751 589/589/753 519/519/760 +f 591/591/196 519/519/760 589/589/753 +f 591/591/196 424/424/756 519/519/760 +f 593/593/761 535/535/762 594/594/763 +f 538/538/758 595/595/764 592/592/759 +f 596/596/765 497/497/766 499/499/767 +f 587/587/746 570/570/753 597/597/768 +f 587/587/746 574/574/747 572/572/752 +f 584/584/743 426/426/584 441/441/599 +f 585/585/744 486/486/769 466/466/757 +f 594/594/763 486/486/769 585/585/744 +f 594/594/763 514/514/770 486/486/769 +f 594/594/763 535/535/762 514/514/770 +f 536/536/771 535/535/762 593/593/761 +f 538/538/758 537/537/758 595/595/764 +f 596/596/765 499/499/767 588/588/749 +f 597/597/768 498/498/772 596/596/765 +f 570/570/753 498/498/772 597/597/768 +f 588/588/749 499/499/767 561/561/750 +f 498/498/772 497/497/766 596/596/765 +f 595/595/764 537/537/758 536/536/771 +f 595/595/764 536/536/771 593/593/761 +f 598/598/773 599/599/774 554/554/775 +f 599/599/774 555/555/776 554/554/775 +f 556/556/777 600/600/778 562/562/779 +f 562/562/779 600/600/778 601/601/780 +f 601/601/780 507/507/781 510/510/782 +f 602/602/783 477/477/784 603/603/785 +f 556/556/777 553/553/786 600/600/778 +f 600/600/778 553/553/786 599/599/774 +f 599/599/774 553/553/786 555/555/776 +f 601/601/780 510/510/782 562/562/779 +f 604/604/787 504/504/788 605/605/789 +f 605/605/789 504/504/788 506/506/790 +f 606/606/791 457/457/792 607/607/793 +f 430/430/588 429/429/587 606/606/791 +f 603/603/785 462/462/794 606/606/791 +f 606/606/791 462/462/794 430/430/588 +f 603/603/785 477/477/784 462/462/794 +f 602/602/783 515/515/795 477/477/784 +f 598/598/773 517/517/796 602/602/783 +f 598/598/773 554/554/775 518/518/797 +f 601/601/780 569/569/798 507/507/781 +f 605/605/789 506/506/790 569/569/798 +f 504/504/788 604/604/787 503/503/787 +f 608/608/787 501/501/168 604/604/787 +f 606/606/791 433/433/591 457/457/792 +f 606/606/791 429/429/587 433/433/591 +f 515/515/795 602/602/783 517/517/796 +f 598/598/773 518/518/797 517/517/796 +f 501/501/168 503/503/787 604/604/787 +f 607/607/793 457/457/792 468/468/799 +f 605/605/789 569/569/798 601/601/780 +f 609/609/800 522/522/801 501/501/168 +f 609/609/800 501/501/168 608/608/787 +f 610/610/802 511/511/803 513/513/804 +f 610/610/802 513/513/804 609/609/800 +f 609/609/800 513/513/804 522/522/801 +f 479/479/805 610/610/802 607/607/793 +f 610/610/802 479/479/805 511/511/803 +f 607/607/793 468/468/799 479/479/805 +f 598/598/806 586/586/807 599/599/808 +f 599/599/808 586/586/807 587/587/809 +f 599/599/808 587/587/809 600/600/810 +f 600/600/810 587/587/809 597/597/811 +f 600/600/810 597/597/811 601/601/812 +f 601/601/812 597/597/811 596/596/813 +f 601/601/812 596/596/813 605/605/814 +f 605/605/814 596/596/813 588/588/815 +f 605/605/814 588/588/815 604/604/816 +f 604/604/816 588/588/815 592/592/817 +f 604/604/816 592/592/817 608/608/818 +f 608/608/818 592/592/817 595/595/819 +f 608/608/818 595/595/819 609/609/820 +f 609/609/820 595/595/819 593/593/821 +f 609/609/820 593/593/821 610/610/822 +f 610/610/822 593/593/821 594/594/823 +f 610/610/822 594/594/823 585/585/824 +f 610/610/822 585/585/824 607/607/825 +f 607/607/825 585/585/824 606/606/826 +f 606/606/826 585/585/824 584/584/827 +f 606/606/826 584/584/827 603/603/828 +f 603/603/828 584/584/827 590/590/829 +f 603/603/828 590/590/829 591/591/830 +f 603/603/828 591/591/830 602/602/831 +f 602/602/831 591/591/830 598/598/806 +f 598/598/806 591/591/830 589/589/832 +f 598/598/806 589/589/832 586/586/807 +f 611/611/833 612/612/834 613/613/835 +f 614/614/836 615/615/837 616/616/838 +f 617/617/839 618/618/840 619/619/841 +f 619/619/841 620/620/842 621/621/843 +f 622/622/844 623/623/845 624/624/846 +f 623/623/845 625/625/847 626/626/848 +f 627/627/849 628/628/850 629/629/851 +f 630/630/852 631/631/853 632/632/854 +f 627/627/849 629/629/851 633/633/855 +f 630/630/852 632/632/854 634/634/856 +f 635/635/857 633/633/855 636/636/858 +f 629/629/851 631/631/853 630/630/852 +f 637/637/859 638/638/860 639/639/861 +f 640/640/862 634/634/856 641/641/863 +f 640/640/862 641/641/863 642/642/864 +f 643/643/865 644/644/866 645/645/867 +f 643/643/865 645/645/867 646/646/868 +f 647/647/869 630/630/852 634/634/856 +f 637/637/859 639/639/861 648/648/870 +f 648/648/870 639/639/861 649/649/871 +f 650/650/872 651/651/873 652/652/874 +f 653/653/875 647/647/869 634/634/856 +f 653/653/875 634/634/856 640/640/862 +f 652/652/874 640/640/862 650/650/872 +f 634/634/856 654/654/876 641/641/863 +f 642/642/864 655/655/877 650/650/872 +f 655/655/877 642/642/864 656/656/878 +f 657/657/879 658/658/880 646/646/868 +f 659/659/881 657/657/879 646/646/868 +f 659/659/881 646/646/868 645/645/867 +f 660/660/882 657/657/879 659/659/881 +f 659/659/881 645/645/867 644/644/866 +f 637/637/859 659/659/881 644/644/866 +f 644/644/866 627/627/849 638/638/860 +f 653/653/875 640/640/862 652/652/874 +f 630/630/852 647/647/869 629/629/851 +f 641/641/863 661/661/883 642/642/864 +f 642/642/864 661/661/883 656/656/878 +f 631/631/853 662/662/884 632/632/854 +f 654/654/876 661/661/883 641/641/863 +f 663/663/885 654/654/876 632/632/854 +f 659/659/881 637/637/859 648/648/870 +f 659/659/881 648/648/870 664/664/886 +f 659/659/881 664/664/886 660/660/882 +f 665/665/887 660/660/882 664/664/886 +f 638/638/860 637/637/859 644/644/866 +f 628/628/850 627/627/849 644/644/866 +f 651/651/873 666/666/888 652/652/874 +f 655/655/877 656/656/878 667/667/889 +f 661/661/883 654/654/876 668/668/890 +f 668/668/890 654/654/876 663/663/885 +f 658/658/880 669/669/891 670/670/892 +f 658/658/880 670/670/892 646/646/868 +f 646/646/868 671/671/893 643/643/865 +f 649/649/871 664/664/886 648/648/870 +f 668/668/890 672/672/894 661/661/883 +f 661/661/883 672/672/894 656/656/878 +f 663/663/885 632/632/854 673/673/895 +f 673/673/895 632/632/854 662/662/884 +f 644/644/866 643/643/865 628/628/850 +f 652/652/874 666/666/888 674/674/896 +f 675/675/897 667/667/889 676/676/898 +f 676/676/898 667/667/889 656/656/878 +f 646/646/868 670/670/892 671/671/893 +f 666/666/888 677/677/899 678/678/900 +f 666/666/888 678/678/900 674/674/896 +f 653/653/875 679/679/901 647/647/869 +f 663/663/885 680/680/902 668/668/890 +f 656/656/878 672/672/894 676/676/898 +f 681/681/903 672/672/894 668/668/890 +f 669/669/891 626/626/848 682/682/904 +f 669/669/891 682/682/904 670/670/892 +f 652/652/874 674/674/896 653/653/875 +f 683/683/905 676/676/898 672/672/894 +f 681/681/903 668/668/890 680/680/902 +f 680/680/902 663/663/885 673/673/895 +f 684/684/906 665/665/887 685/685/907 +f 685/685/907 665/665/887 664/664/886 +f 675/675/897 676/676/898 686/686/908 +f 683/683/905 672/672/894 681/681/903 +f 626/626/848 625/625/847 682/682/904 +f 687/687/909 686/686/908 676/676/898 +f 688/688/910 683/683/905 681/681/903 +f 650/650/872 640/640/862 642/642/864 +f 654/654/876 634/634/856 632/632/854 +f 677/677/899 689/689/911 690/690/912 +f 677/677/899 690/690/912 691/691/913 +f 677/677/899 691/691/913 678/678/900 +f 653/653/875 674/674/896 679/679/901 +f 647/647/869 633/633/855 629/629/851 +f 684/684/906 692/692/914 665/665/887 +f 685/685/907 664/664/886 649/649/871 +f 693/693/915 694/694/916 695/695/917 +f 693/693/915 695/695/917 696/696/918 +f 697/697/919 698/698/920 699/699/921 +f 700/700/922 699/699/921 694/694/916 +f 697/697/919 699/699/921 700/700/922 +f 701/701/923 700/700/922 694/694/916 +f 701/701/923 694/694/916 693/693/915 +f 702/702/924 693/693/915 696/696/918 +f 703/703/925 697/697/919 700/700/922 +f 702/702/924 696/696/918 636/636/858 +f 704/704/926 697/697/919 703/703/925 +f 703/703/925 700/700/922 705/705/927 +f 705/705/927 700/700/922 701/701/923 +f 705/705/927 701/701/923 706/706/928 +f 706/706/928 701/701/923 693/693/915 +f 706/706/928 693/693/915 702/702/924 +f 679/679/901 636/636/858 633/633/855 +f 690/690/912 704/704/926 703/703/925 +f 690/690/912 703/703/925 705/705/927 +f 678/678/900 706/706/928 702/702/924 +f 707/707/929 704/704/926 690/690/912 +f 702/702/924 636/636/858 679/679/901 +f 691/691/913 690/690/912 705/705/927 +f 691/691/913 705/705/927 706/706/928 +f 702/702/924 679/679/901 674/674/896 +f 702/702/924 674/674/896 678/678/900 +f 706/706/928 678/678/900 691/691/913 +f 708/708/930 707/707/929 689/689/911 +f 689/689/911 707/707/929 690/690/912 +f 647/647/869 679/679/901 633/633/855 +f 636/636/858 696/696/918 635/635/857 +f 708/708/930 709/709/931 707/707/929 +f 707/707/929 709/709/931 704/704/926 +f 704/704/926 709/709/931 710/710/932 +f 704/704/926 710/710/932 697/697/919 +f 711/711/933 615/615/837 614/614/836 +f 712/712/934 711/711/933 614/614/836 +f 712/712/934 614/614/836 713/713/935 +f 687/687/909 712/712/934 713/713/935 +f 714/714/936 711/711/933 712/712/934 +f 715/715/937 712/712/934 687/687/909 +f 715/715/937 714/714/936 712/712/934 +f 716/716/938 687/687/909 683/683/905 +f 717/717/939 715/715/937 687/687/909 +f 717/717/939 687/687/909 716/716/938 +f 688/688/910 716/716/938 683/683/905 +f 718/718/940 714/714/936 719/719/941 +f 719/719/941 714/714/936 715/715/937 +f 719/719/941 715/715/937 717/717/939 +f 720/720/942 716/716/938 688/688/910 +f 720/720/942 717/717/939 716/716/938 +f 721/721/943 720/720/942 688/688/910 +f 721/721/943 688/688/910 722/722/944 +f 723/723/945 718/718/940 719/719/941 +f 723/723/945 719/719/941 717/717/939 +f 724/724/946 717/717/939 720/720/942 +f 725/725/947 723/723/945 717/717/939 +f 725/725/947 717/717/939 724/724/946 +f 726/726/948 721/721/943 722/722/944 +f 726/726/948 722/722/944 680/680/902 +f 727/727/949 723/723/945 725/725/947 +f 724/724/946 720/720/942 721/721/943 +f 728/728/950 726/726/948 680/680/902 +f 729/729/951 727/727/949 725/725/947 +f 729/729/951 725/725/947 724/724/946 +f 730/730/952 680/680/902 673/673/895 +f 731/731/953 729/729/951 724/724/946 +f 731/731/953 724/724/946 721/721/943 +f 731/731/953 721/721/943 732/732/954 +f 732/732/954 721/721/943 726/726/948 +f 732/732/954 726/726/948 728/728/950 +f 730/730/952 728/728/950 680/680/902 +f 622/622/844 723/723/945 727/727/949 +f 622/622/844 727/727/949 733/733/955 +f 733/733/955 727/727/949 729/729/951 +f 734/734/956 730/730/952 673/673/895 +f 735/735/957 733/733/955 729/729/951 +f 735/735/957 729/729/951 731/731/953 +f 625/625/847 731/731/953 732/732/954 +f 734/734/956 673/673/895 643/643/865 +f 643/643/865 673/673/895 662/662/884 +f 625/625/847 735/735/957 731/731/953 +f 682/682/904 732/732/954 728/728/950 +f 670/670/892 728/728/950 730/730/952 +f 670/670/892 730/730/952 671/671/893 +f 622/622/844 733/733/955 623/623/845 +f 623/623/845 733/733/955 735/735/957 +f 623/623/845 735/735/957 625/625/847 +f 682/682/904 625/625/847 732/732/954 +f 670/670/892 682/682/904 728/728/950 +f 628/628/850 643/643/865 662/662/884 +f 734/734/956 671/671/893 730/730/952 +f 736/736/958 622/622/844 624/624/846 +f 643/643/865 671/671/893 734/734/956 +f 614/614/836 686/686/908 713/713/935 +f 713/713/935 686/686/908 687/687/909 +f 687/687/909 676/676/898 683/683/905 +f 688/688/910 681/681/903 722/722/944 +f 722/722/944 681/681/903 680/680/902 +f 662/662/884 631/631/853 628/628/850 +f 709/709/931 737/737/959 710/710/932 +f 697/697/919 710/710/932 698/698/920 +f 622/622/844 738/738/960 723/723/945 +f 709/709/931 708/708/930 737/737/959 +f 736/736/958 738/738/960 622/622/844 +f 708/708/930 739/739/961 737/737/959 +f 710/710/932 740/740/962 698/698/920 +f 698/698/920 741/741/963 742/742/964 +f 738/738/960 743/743/965 723/723/945 +f 723/723/945 743/743/965 718/718/940 +f 718/718/940 744/744/966 714/714/936 +f 714/714/936 744/744/966 711/711/933 +f 710/710/932 737/737/959 740/740/962 +f 740/740/962 741/741/963 698/698/920 +f 624/624/846 745/745/967 746/746/968 +f 624/624/846 746/746/968 736/736/958 +f 743/743/965 747/747/969 718/718/940 +f 718/718/940 747/747/969 744/744/966 +f 744/744/966 748/748/970 711/711/933 +f 711/711/933 748/748/970 615/615/837 +f 615/615/837 748/748/970 616/616/838 +f 736/736/958 746/746/968 738/738/960 +f 748/748/970 749/749/971 616/616/838 +f 750/750/972 617/617/839 751/751/973 +f 750/750/972 751/751/973 752/752/974 +f 752/752/974 751/751/973 692/692/914 +f 753/753/975 692/692/914 684/684/906 +f 754/754/976 618/618/840 617/617/839 +f 754/754/976 617/617/839 755/755/977 +f 755/755/977 617/617/839 750/750/972 +f 752/752/974 692/692/914 753/753/975 +f 639/639/861 685/685/907 649/649/871 +f 756/756/978 750/750/972 752/752/974 +f 757/757/979 754/754/976 755/755/977 +f 755/755/977 750/750/972 756/756/978 +f 758/758/980 753/753/975 684/684/906 +f 758/758/980 684/684/906 685/685/907 +f 759/759/981 685/685/907 639/639/861 +f 760/760/982 754/754/976 757/757/979 +f 761/761/983 752/752/974 753/753/975 +f 761/761/983 753/753/975 758/758/980 +f 758/758/980 685/685/907 759/759/981 +f 762/762/984 760/760/982 757/757/979 +f 762/762/984 757/757/979 742/742/964 +f 757/757/979 755/755/977 763/763/985 +f 763/763/985 755/755/977 756/756/978 +f 764/764/986 756/756/978 752/752/974 +f 764/764/986 752/752/974 761/761/983 +f 763/763/985 756/756/978 764/764/986 +f 695/695/917 758/758/980 759/759/981 +f 633/633/855 635/635/857 638/638/860 +f 635/635/857 759/759/981 639/639/861 +f 633/633/855 638/638/860 627/627/849 +f 741/741/963 762/762/984 742/742/964 +f 742/742/964 757/757/979 763/763/985 +f 699/699/921 763/763/985 764/764/986 +f 759/759/981 635/635/857 696/696/918 +f 759/759/981 696/696/918 695/695/917 +f 758/758/980 695/695/917 694/694/916 +f 758/758/980 694/694/916 761/761/983 +f 761/761/983 694/694/916 764/764/986 +f 764/764/986 694/694/916 699/699/921 +f 763/763/985 698/698/920 742/742/964 +f 698/698/920 763/763/985 699/699/921 +f 738/738/960 746/746/968 765/765/987 +f 738/738/960 765/765/987 743/743/965 +f 743/743/965 765/765/987 766/766/988 +f 743/743/965 766/766/988 747/747/969 +f 747/747/969 767/767/989 744/744/966 +f 744/744/966 767/767/989 748/748/970 +f 748/748/970 768/768/990 769/769/991 +f 748/748/970 769/769/991 770/770/992 +f 748/748/970 770/770/992 749/749/971 +f 739/739/961 771/771/993 737/737/959 +f 737/737/959 772/772/994 740/740/962 +f 741/741/963 773/773/995 762/762/984 +f 754/754/976 760/760/982 774/774/996 +f 754/754/976 774/774/996 618/618/840 +f 748/748/970 767/767/989 768/768/990 +f 769/769/991 768/768/990 770/770/992 +f 739/739/961 775/775/997 771/771/993 +f 737/737/959 771/771/993 772/772/994 +f 740/740/962 772/772/994 776/776/998 +f 740/740/962 776/776/998 773/773/995 +f 740/740/962 773/773/995 741/741/963 +f 618/618/840 774/774/996 619/619/841 +f 767/767/989 777/777/999 768/768/990 +f 768/768/1000 777/777/1001 778/778/1002 +f 768/768/990 778/778/1003 779/779/1004 +f 768/768/990 779/779/1004 770/770/992 +f 770/770/992 779/779/1004 749/749/971 +f 619/619/841 774/774/996 620/620/842 +f 639/639/861 638/638/860 635/635/857 +f 629/629/851 628/628/850 631/631/853 +f 762/762/984 780/780/1005 760/760/982 +f 760/760/982 780/780/1005 774/774/996 +f 774/774/996 781/781/1006 620/620/842 +f 621/621/843 782/782/1007 783/783/1008 +f 783/783/1008 782/782/1007 745/745/967 +f 745/745/967 782/782/1007 784/784/1009 +f 745/745/967 784/784/1009 746/746/968 +f 746/746/968 784/784/1009 765/765/987 +f 747/747/969 766/766/988 785/785/1010 +f 747/747/969 785/785/1010 767/767/989 +f 778/778/1002 777/777/1001 786/786/1011 +f 778/778/1003 786/786/1012 779/779/1004 +f 779/779/1004 786/786/1012 749/749/971 +f 749/749/971 786/786/1012 787/787/1013 +f 749/749/971 787/787/1013 788/788/1014 +f 775/775/997 789/789/1015 790/790/1016 +f 775/775/997 790/790/1016 771/771/993 +f 773/773/995 791/791/1017 780/780/1005 +f 773/773/995 780/780/1005 762/762/984 +f 774/774/996 780/780/1005 781/781/1006 +f 620/620/842 792/792/1018 621/621/843 +f 784/784/1009 793/793/1019 765/765/987 +f 767/767/989 794/794/1020 777/777/999 +f 777/777/999 794/794/1020 786/786/1012 +f 788/788/1014 787/787/1013 795/795/1021 +f 795/795/1021 796/796/1022 789/789/1015 +f 790/790/1016 797/797/1023 771/771/993 +f 771/771/993 797/797/1023 772/772/994 +f 772/772/994 797/797/1023 798/798/1024 +f 772/772/994 798/798/1024 776/776/998 +f 621/621/843 792/792/1018 782/782/1007 +f 793/793/1019 784/784/1009 799/799/1025 +f 793/793/1019 799/799/1025 765/765/987 +f 765/765/987 799/799/1025 766/766/988 +f 766/766/988 799/799/1025 785/785/1010 +f 767/767/989 785/785/1010 794/794/1020 +f 795/795/1021 787/787/1013 796/796/1022 +f 789/789/1015 796/796/1022 790/790/1016 +f 776/776/998 798/798/1024 773/773/995 +f 773/773/995 798/798/1024 791/791/1017 +f 620/620/842 781/781/1006 800/800/1026 +f 620/620/842 800/800/1026 792/792/1018 +f 792/792/1018 801/801/1027 782/782/1007 +f 782/782/1007 802/802/1028 784/784/1009 +f 787/787/1013 803/803/1029 796/796/1022 +f 790/790/1016 796/796/1022 804/804/1030 +f 790/790/1016 804/804/1030 797/797/1023 +f 780/780/1005 791/791/1017 805/805/1031 +f 780/780/1005 805/805/1031 806/806/1032 +f 780/780/1005 806/806/1032 781/781/1006 +f 781/781/1006 806/806/1032 800/800/1026 +f 792/792/1018 800/800/1026 801/801/1027 +f 782/782/1007 801/801/1027 802/802/1028 +f 784/784/1009 802/802/1028 807/807/1033 +f 784/784/1009 807/807/1033 799/799/1025 +f 799/799/1025 808/808/1034 785/785/1010 +f 786/786/1012 803/803/1029 787/787/1013 +f 804/804/1030 809/809/1035 797/797/1023 +f 797/797/1023 810/810/1036 798/798/1024 +f 798/798/1024 810/810/1036 791/791/1017 +f 808/808/1034 794/794/1020 785/785/1010 +f 786/786/1012 794/794/1020 811/811/1037 +f 803/803/1029 804/804/1030 796/796/1022 +f 797/797/1023 809/809/1035 810/810/1036 +f 791/791/1017 812/812/1038 805/805/1031 +f 801/801/1027 800/800/1026 813/813/1039 +f 801/801/1027 813/813/1039 802/802/1028 +f 802/802/1028 813/813/1039 807/807/1033 +f 786/786/1012 811/811/1037 803/803/1029 +f 803/803/1029 814/814/1040 804/804/1030 +f 810/810/1036 809/809/1035 812/812/1038 +f 810/810/1036 812/812/1038 791/791/1017 +f 812/812/1038 815/815/1041 805/805/1031 +f 805/805/1031 815/815/1041 806/806/1032 +f 799/799/1025 807/807/1033 808/808/1034 +f 794/794/1020 808/808/1034 811/811/1037 +f 811/811/1037 814/814/1040 803/803/1029 +f 815/815/1041 816/816/1042 806/806/1032 +f 806/806/1032 816/816/1042 800/800/1026 +f 800/800/1026 816/816/1042 813/813/1039 +f 807/807/1033 813/813/1039 817/817/1043 +f 807/807/1033 817/817/1043 808/808/1034 +f 804/804/1030 814/814/1040 818/818/1044 +f 804/804/1030 818/818/1044 819/819/1045 +f 804/804/1030 819/819/1045 809/809/1035 +f 809/809/1035 819/819/1045 812/812/1038 +f 808/808/1034 817/817/1043 611/611/833 +f 808/808/1034 611/611/833 811/811/1037 +f 811/811/1037 611/611/833 814/814/1040 +f 812/812/1038 819/819/1045 815/815/1041 +f 816/816/1042 612/612/834 813/813/1039 +f 813/813/1039 612/612/834 817/817/1043 +f 814/814/1040 611/611/833 818/818/1044 +f 815/815/1041 819/819/1045 613/613/835 +f 815/815/1041 613/613/835 816/816/1042 +f 816/816/1042 613/613/835 612/612/834 +f 817/817/1043 612/612/834 611/611/833 +f 611/611/833 613/613/835 818/818/1044 +f 818/818/1044 613/613/835 819/819/1045 +f 820/820/1046 749/749/1047 788/788/1048 +f 820/820/1046 788/788/1048 821/821/1049 +f 822/822/1050 616/616/1051 820/820/1046 +f 820/820/1046 616/616/1051 749/749/1047 +f 739/739/1052 823/823/1053 824/824/1054 +f 666/666/1055 825/825/1056 677/677/1057 +f 826/826/1058 650/650/1059 655/655/1060 +f 825/825/1056 666/666/1055 827/827/1061 +f 825/825/1056 689/689/1062 677/677/1057 +f 825/825/1056 823/823/1053 689/689/1062 +f 824/824/1054 775/775/1063 739/739/1052 +f 824/824/1054 789/789/1064 775/775/1063 +f 821/821/1049 789/789/1064 824/824/1054 +f 789/789/1064 821/821/1049 795/795/1065 +f 788/788/1048 795/795/1065 821/821/1049 +f 822/822/1050 614/614/1066 616/616/1051 +f 686/686/1067 614/614/1066 828/828/1068 +f 828/828/1068 614/614/1066 822/822/1050 +f 827/827/1061 651/651/1069 650/650/1059 +f 827/827/1061 650/650/1059 826/826/1058 +f 823/823/1053 708/708/1070 689/689/1062 +f 667/667/1071 828/828/1068 826/826/1058 +f 827/827/1061 666/666/1055 651/651/1069 +f 739/739/1052 708/708/1070 823/823/1053 +f 686/686/1067 828/828/1068 675/675/1072 +f 667/667/1071 675/675/1072 828/828/1068 +f 826/826/1058 655/655/1060 667/667/1071 +f 829/829/469 621/621/1073 830/830/1074 +f 830/830/1074 621/621/1073 783/783/1075 +f 831/831/1076 623/623/1077 832/832/1078 +f 624/624/1079 831/831/1076 833/833/1080 +f 830/830/1074 783/783/1075 833/833/1080 +f 834/834/1081 665/665/1082 835/835/1083 +f 624/624/1079 623/623/1077 831/831/1076 +f 621/621/1073 829/829/469 619/619/1084 +f 836/836/1085 619/619/1084 829/829/469 +f 833/833/1080 745/745/1086 624/624/1079 +f 833/833/1080 783/783/1075 745/745/1086 +f 836/836/1085 617/617/1087 619/619/1084 +f 834/834/1081 660/660/1088 665/665/1082 +f 660/660/1088 834/834/1081 657/657/1089 +f 837/837/1090 657/657/1089 834/834/1081 +f 669/669/1091 658/658/1092 837/837/1090 +f 832/832/1078 623/623/1077 626/626/1093 +f 617/617/1087 836/836/1085 838/838/1094 +f 838/838/1094 839/839/1095 751/751/1096 +f 839/839/1095 692/692/1097 751/751/1096 +f 658/658/1092 657/657/1089 837/837/1090 +f 832/832/1078 669/669/1091 837/837/1090 +f 838/838/1094 751/751/1096 617/617/1087 +f 835/835/1083 665/665/1082 839/839/1095 +f 832/832/1078 626/626/1093 669/669/1091 +f 665/665/1082 692/692/1097 839/839/1095 +f 840/840/1098 841/841/1099 842/842/1100 +f 842/842/1100 841/841/1099 843/843/1101 +f 842/842/1100 843/843/1101 844/844/1102 +f 844/844/1102 843/843/1101 845/845/1103 +f 845/845/1103 843/843/1101 846/846/1104 +f 845/845/1103 846/846/1104 847/847/1105 +f 847/847/1105 846/846/1104 848/848/1106 +f 847/847/1105 848/848/1106 849/849/1107 +f 847/847/1105 849/849/1107 850/850/1108 +f 850/850/1108 849/849/1107 851/851/1109 +f 850/850/1108 851/851/1109 852/852/1110 +f 852/852/1110 851/851/1109 853/853/1111 +f 853/853/1111 851/851/1109 854/854/1112 +f 853/853/1111 854/854/1112 855/855/1113 +f 855/855/1113 854/854/1112 856/856/1114 +f 855/855/1113 856/856/1114 857/857/1115 +f 857/857/1115 856/856/1114 858/858/1116 +f 857/857/1115 858/858/1116 859/859/1117 +f 859/859/1117 858/858/1116 860/860/1118 +f 859/859/1117 860/860/1118 861/861/1119 +f 861/861/1119 860/860/1118 862/862/1120 +f 861/861/1119 862/862/1120 863/863/1121 +f 861/861/1119 863/863/1121 864/864/1122 +f 864/864/1122 863/863/1121 865/865/1123 +f 864/864/1122 865/865/1123 840/840/1098 +f 840/840/1098 865/865/1123 841/841/1099 +f 851/851/1124 839/839/1125 838/838/1126 +f 839/839/1125 851/851/1124 849/849/1127 +f 839/839/1125 849/849/1127 835/835/1128 +f 835/835/1128 849/849/1127 834/834/1129 +f 849/849/1127 848/848/1130 834/834/1129 +f 848/848/1130 846/846/1131 834/834/1129 +f 834/834/1129 846/846/1131 837/837/1132 +f 846/846/1131 843/843/1133 837/837/1132 +f 837/837/1134 843/843/1135 832/832/1136 +f 832/832/1136 843/843/1135 841/841/1137 +f 832/832/1136 841/841/1137 865/865/1138 +f 832/832/1136 865/865/1138 831/831/1139 +f 831/831/1139 865/865/1138 863/863/1140 +f 831/831/1139 863/863/1140 833/833/1141 +f 833/833/1141 863/863/1140 862/862/1142 +f 833/833/1141 862/862/1142 830/830/1143 +f 830/830/1143 862/862/1142 860/860/1144 +f 830/830/1143 860/860/1144 858/858/1145 +f 830/830/1143 858/858/1145 829/829/1146 +f 829/829/1146 858/858/1145 856/856/1147 +f 829/829/1146 856/856/1147 836/836/1148 +f 856/856/1147 854/854/1149 836/836/1148 +f 836/836/1148 854/854/1149 838/838/1126 +f 838/838/1126 854/854/1149 851/851/1124 +f 840/840/1150 842/842/1151 828/828/1152 +f 828/828/1152 842/842/1151 844/844/1153 +f 828/828/1154 844/844/1154 826/826/1154 +f 844/844/1155 845/845/1156 826/826/1157 +f 826/826/1157 845/845/1156 847/847/1158 +f 826/826/1157 847/847/1158 827/827/1159 +f 827/827/1159 847/847/1158 850/850/1160 +f 827/827/1159 850/850/1160 825/825/1161 +f 825/825/1162 850/850/1162 852/852/1162 +f 852/852/1163 853/853/1164 825/825/1165 +f 825/825/1165 853/853/1164 823/823/1166 +f 853/853/1164 855/855/1167 823/823/1166 +f 823/823/1166 855/855/1167 824/824/1168 +f 824/824/1169 855/855/1169 857/857/1169 +f 824/824/1170 857/857/1171 821/821/1172 +f 857/857/1171 859/859/1173 821/821/1172 +f 859/859/1173 861/861/1174 821/821/1172 +f 821/821/1172 861/861/1174 820/820/1175 +f 861/861/1174 864/864/1176 820/820/1175 +f 820/820/1175 864/864/1176 822/822/1177 +f 822/822/1177 864/864/1176 840/840/1178 +f 822/822/1179 840/840/1150 828/828/1152 +f 866/866/1180 867/867/1181 868/868/1180 +f 869/869/1182 866/866/1180 868/868/1180 +f 868/868/1180 870/870/1183 869/869/1182 +f 871/871/1184 870/870/1183 868/868/1180 +f 871/871/1184 872/872/1183 870/870/1183 +f 872/872/1183 873/873/1185 870/870/1183 +f 872/872/1183 874/874/1186 873/873/1185 +f 872/872/1183 875/875/1187 874/874/1186 +f 875/875/1187 876/876/1186 874/874/1186 +f 876/876/1186 877/877/1188 874/874/1186 +f 878/878/1189 879/879/1189 880/880/1189 +f 881/881/1189 882/882/1190 883/883/1189 +f 884/884/1189 881/881/1189 879/879/1189 +f 884/884/1189 879/879/1189 878/878/1189 +f 881/881/1189 883/883/1189 879/879/1189 +f 878/878/1189 880/880/1189 885/885/1189 +f 886/886/1189 878/878/1189 885/885/1189 +f 886/886/1189 885/885/1189 887/887/1189 +f 888/888/1189 889/889/1189 890/890/1189 +f 891/891/1189 892/892/1189 893/893/1189 +f 891/891/1189 894/894/1189 892/892/1189 +f 895/895/1189 893/893/1189 892/892/1189 +f 895/895/1189 892/892/1189 896/896/1189 +f 897/897/1190 898/898/1191 899/899/1190 +f 895/895/1189 896/896/1189 889/889/1189 +f 895/895/1189 889/889/1189 888/888/1189 +f 899/899/1190 888/888/1189 890/890/1189 +f 897/897/1190 899/899/1190 890/890/1189 +f 900/900/1183 901/901/1183 902/902/1183 +f 900/900/1183 903/903/1183 904/904/1183 +f 900/900/1183 902/902/1183 903/903/1183 +f 905/905/1183 904/904/1183 903/903/1183 +f 905/905/1183 903/903/1183 906/906/1183 +f 907/907/1183 905/905/1183 906/906/1183 +f 907/907/1183 906/906/1183 908/908/1183 +f 907/907/1183 908/908/1183 909/909/1183 +f 910/910/1192 911/911/1193 912/912/1194 +f 912/912/1194 911/911/1193 913/913/1195 +f 912/912/1194 913/913/1195 914/914/1196 +f 914/914/1196 913/913/1195 915/915/1197 +f 914/914/1196 915/915/1197 916/916/1198 +f 916/916/1198 915/915/1197 917/917/1199 +f 916/916/1198 917/917/1199 918/918/1200 +f 918/918/1200 917/917/1199 919/919/1201 +f 918/918/1200 919/919/1201 920/920/1202 +f 920/920/1202 919/919/1201 921/921/1203 +f 920/920/1202 921/921/1203 922/922/1204 +f 922/922/1204 921/921/1203 923/923/1205 +f 922/922/1204 923/923/1205 924/924/1206 +f 924/924/1206 923/923/1205 925/925/1207 +f 924/924/1206 925/925/1207 926/926/1208 +f 926/926/1208 925/925/1207 927/927/1209 +f 926/926/1208 927/927/1209 928/928/1210 +f 928/928/1210 927/927/1209 929/929/1211 +f 928/928/1210 929/929/1211 930/930/1212 +f 930/930/1212 929/929/1211 931/931/1213 +f 930/930/1212 931/931/1213 932/932/1214 +f 932/932/1214 931/931/1213 933/933/1215 +f 932/932/1214 933/933/1215 934/934/1216 +f 934/934/1216 933/933/1215 935/935/1217 +f 934/934/1216 935/935/1217 936/936/1218 +f 936/936/1218 935/935/1217 937/937/1219 +f 936/936/1218 937/937/1219 938/938/1220 +f 938/938/1220 937/937/1219 939/939/1221 +f 938/938/1220 939/939/1221 940/940/1222 +f 940/940/1222 939/939/1221 941/941/1223 +f 940/940/1222 941/941/1223 910/910/1192 +f 910/910/1192 941/941/1223 911/911/1193 +f 909/909/1224 7/7/7 15/15/15 +f 908/908/1225 906/906/1226 50/50/50 +f 14/14/14 901/901/1227 24/24/24 +f 909/909/1224 15/15/15 22/22/22 +f 902/902/1228 901/901/1227 20/20/20 +f 20/20/20 26/26/26 902/902/1228 +f 900/900/1229 57/57/57 24/24/24 +f 26/26/26 903/903/1230 902/902/1228 +f 900/900/1229 904/904/1231 57/57/57 +f 26/26/26 44/44/44 903/903/1230 +f 904/904/1231 58/58/58 57/57/57 +f 34/34/34 905/905/1232 907/907/1233 +f 44/44/44 18/18/18 903/903/1230 +f 904/904/1231 32/32/32 58/58/58 +f 904/904/1231 905/905/1232 32/32/32 +f 18/18/18 906/906/1226 903/903/1230 +f 18/18/18 19/19/19 906/906/1226 +f 905/905/1232 40/40/40 32/32/32 +f 19/19/19 50/50/50 906/906/1226 +f 905/905/1232 34/34/34 40/40/40 +f 907/907/1233 22/22/22 34/34/34 +f 60/60/60 908/908/1225 50/50/50 +f 907/907/1233 909/909/1224 22/22/22 +f 60/60/60 7/7/7 908/908/1225 +f 901/901/1227 14/14/14 20/20/20 +f 909/909/1224 908/908/1225 7/7/7 +f 901/901/1227 900/900/1229 24/24/24 +f 883/883/1234 465/465/623 879/879/1235 +f 475/475/633 881/881/1236 884/884/1237 +f 437/437/595 884/884/1237 438/438/596 +f 879/879/1235 465/465/623 451/451/609 +f 882/882/1238 881/881/1236 440/440/598 +f 879/879/1235 451/451/609 880/880/1239 +f 438/438/596 878/878/1240 455/455/613 +f 880/880/1239 451/451/609 485/485/644 +f 455/455/613 878/878/1240 886/886/1241 +f 880/880/1239 485/485/644 885/885/1242 +f 455/455/613 886/886/1241 448/448/606 +f 885/885/1242 485/485/644 480/480/638 +f 448/448/606 886/886/1241 434/434/592 +f 887/887/1243 435/435/593 434/434/592 +f 886/886/1241 887/887/1243 434/434/592 +f 435/435/1244 887/887/1245 480/480/1246 +f 882/882/1238 439/439/597 453/453/611 +f 438/438/596 884/884/1237 878/878/1240 +f 926/926/1208 866/866/1247 924/924/1206 +f 924/924/1206 866/866/1247 869/869/1248 +f 924/924/1206 869/869/1248 922/922/1204 +f 922/922/1204 869/869/1248 870/870/1249 +f 922/922/1204 870/870/1249 920/920/1202 +f 920/920/1202 870/870/1249 873/873/1250 +f 920/920/1202 873/873/1250 918/918/1200 +f 918/918/1200 873/873/1250 874/874/1251 +f 918/918/1200 874/874/1251 916/916/1198 +f 916/916/1198 874/874/1251 914/914/1196 +f 914/914/1196 874/874/1251 877/877/1252 +f 914/914/1196 877/877/1252 912/912/1194 +f 912/912/1194 877/877/1252 910/910/1192 +f 910/910/1192 877/877/1252 876/876/1253 +f 910/910/1192 876/876/1253 940/940/1222 +f 940/940/1222 876/876/1253 875/875/1254 +f 940/940/1222 875/875/1254 938/938/1220 +f 938/938/1220 875/875/1254 872/872/1255 +f 938/938/1220 872/872/1255 936/936/1218 +f 936/936/1218 872/872/1255 934/934/1216 +f 934/934/1216 872/872/1255 871/871/1256 +f 934/934/1216 871/871/1256 932/932/1214 +f 932/932/1214 871/871/1256 868/868/1257 +f 932/932/1214 868/868/1257 930/930/1212 +f 930/930/1212 868/868/1257 867/867/1258 +f 930/930/1212 867/867/1258 928/928/1210 +f 928/928/1210 867/867/1258 926/926/1208 +f 926/926/1208 867/867/1258 866/866/1247 +f 941/941/1223 897/897/1259 911/911/1193 +f 911/911/1193 897/897/1259 890/890/1260 +f 911/911/1193 890/890/1260 913/913/1195 +f 913/913/1195 890/890/1260 915/915/1197 +f 915/915/1197 890/890/1260 889/889/1261 +f 915/915/1197 889/889/1261 917/917/1199 +f 917/917/1199 889/889/1261 896/896/1262 +f 917/917/1199 896/896/1262 919/919/1201 +f 919/919/1201 896/896/1262 892/892/1263 +f 919/919/1201 892/892/1263 921/921/1203 +f 921/921/1203 892/892/1263 923/923/1205 +f 923/923/1205 892/892/1263 894/894/1264 +f 923/923/1205 894/894/1264 925/925/1207 +f 925/925/1207 894/894/1264 891/891/1265 +f 925/925/1207 891/891/1265 927/927/1209 +f 927/927/1209 891/891/1265 893/893/1266 +f 927/927/1209 893/893/1266 929/929/1211 +f 929/929/1211 893/893/1266 931/931/1213 +f 931/931/1213 893/893/1266 895/895/1267 +f 931/931/1213 895/895/1267 933/933/1215 +f 933/933/1215 895/895/1267 888/888/1268 +f 933/933/1215 888/888/1268 935/935/1217 +f 935/935/1217 888/888/1268 899/899/1269 +f 935/935/1217 899/899/1269 937/937/1219 +f 937/937/1219 899/899/1269 939/939/1221 +f 939/939/1221 899/899/1269 898/898/1270 +f 939/939/1221 898/898/1270 941/941/1223 +f 941/941/1223 898/898/1270 897/897/1259 +f 882/882/1238 440/440/598 439/439/597 +f 440/440/598 881/881/1236 454/454/612 +f 887/887/1245 885/885/1271 480/480/1246 +f 883/883/1234 882/882/1238 453/453/611 +f 454/454/612 881/881/1236 475/475/633 +f 883/883/1234 453/453/611 465/465/623 +f 475/475/633 884/884/1237 437/437/595 diff --git a/examples/Cassie/urdf/meshes/agility/shin.obj b/examples/Cassie/urdf/meshes/agility/shin.obj new file mode 100644 index 0000000000..5a875e909c --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/shin.obj @@ -0,0 +1,22185 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o shin +v 0.129744 -0.024499 0.011348 +v 0.133890 -0.024473 0.010425 +v 0.131182 -0.024498 0.009842 +v 0.133744 -0.024492 0.013621 +v 0.130696 -0.024480 0.014080 +v 0.131838 -0.034500 0.015083 +v 0.131123 -0.025240 0.015033 +v 0.129400 -0.034500 0.013751 +v 0.129244 -0.025253 0.013293 +v 0.129031 -0.025242 0.011141 +v 0.129085 -0.034500 0.010991 +v 0.130422 -0.025250 0.009398 +v 0.131345 -0.034500 0.008884 +v 0.132630 -0.025251 0.008975 +v 0.134381 -0.034500 0.010015 +v 0.134425 -0.025247 0.010182 +v 0.135085 -0.025241 0.012480 +v 0.135032 -0.034500 0.012403 +v 0.134019 -0.034500 0.014305 +v 0.133704 -0.025250 0.014526 +v 0.133005 -0.034500 0.018792 +v 0.136215 -0.034500 0.017442 +v 0.129316 -0.034500 0.018367 +v 0.125721 -0.034500 0.015076 +v 0.125328 -0.034500 0.010214 +v 0.138886 -0.034500 0.013355 +v 0.137262 -0.034500 0.007308 +v 0.132392 -0.034500 0.005110 +v 0.127922 -0.034500 0.006365 +v 0.137710 -0.035325 0.015841 +v 0.136994 -0.035329 0.013194 +v 0.138962 -0.035325 0.011126 +v 0.137073 -0.035331 0.011036 +v 0.136060 -0.035328 0.008828 +v 0.136072 -0.035325 0.006365 +v 0.134092 -0.035326 0.007308 +v 0.132303 -0.035325 0.005165 +v 0.131723 -0.035329 0.006868 +v 0.127671 -0.035325 0.017577 +v 0.132222 -0.035330 0.017195 +v 0.133815 -0.035325 0.018785 +v 0.128888 -0.035325 0.005839 +v 0.129458 -0.035328 0.007480 +v 0.126172 -0.035325 0.008375 +v 0.127056 -0.035329 0.010261 +v 0.125051 -0.035325 0.012402 +v 0.128668 -0.035326 0.015971 +v 0.135758 -0.035332 0.015650 +v 0.127012 -0.035376 0.013451 +v 0.132021 -0.037768 0.014384 +v 0.133970 -0.037778 0.014488 +v 0.132118 -0.037797 0.015065 +v 0.130081 -0.037806 0.014456 +v 0.133897 -0.037710 0.013305 +v 0.133902 -0.037720 0.010712 +v 0.132141 -0.037780 0.009663 +v 0.133582 -0.037787 0.009300 +v 0.130114 -0.037719 0.010654 +v 0.131114 -0.037795 0.008964 +v 0.134109 -0.037686 0.011890 +v 0.135095 -0.037804 0.011661 +v 0.128866 -0.037811 0.011794 +v 0.129907 -0.037728 0.013095 +v 0.135526 -0.036808 0.014413 +v 0.128698 -0.036908 0.009439 +v 0.135801 -0.036953 0.010356 +v 0.128265 -0.037158 0.013196 +v 0.127840 -0.036816 0.011212 +v 0.136268 -0.036720 0.012489 +v 0.132432 -0.036706 0.016298 +v 0.130466 -0.036678 0.016089 +v 0.128898 -0.036706 0.015005 +v 0.131475 -0.036556 0.007609 +v 0.133172 -0.036620 0.007773 +v 0.134933 -0.036391 0.008513 +v 0.134152 -0.036443 0.015973 +v 0.129284 -0.036356 0.008307 +v 0.133997 -0.035490 0.013159 +v 0.131997 -0.035490 0.014313 +v 0.133997 -0.035490 0.010849 +v 0.129997 -0.035490 0.013159 +v 0.131997 -0.035490 0.009695 +v 0.129997 -0.035490 0.010849 +v 0.139480 -0.030000 0.010165 +v 0.139612 -0.029000 0.011687 +v 0.138920 -0.030000 0.015083 +v 0.138557 -0.029000 0.015795 +v 0.135836 -0.030000 0.018650 +v 0.135725 -0.029000 0.018625 +v 0.132072 -0.029000 0.019562 +v 0.131208 -0.030000 0.019540 +v 0.128404 -0.029000 0.018699 +v 0.126862 -0.030000 0.017709 +v 0.125242 -0.029000 0.015533 +v 0.124349 -0.030000 0.012648 +v 0.124514 -0.029000 0.010165 +v 0.126385 -0.030000 0.006624 +v 0.128614 -0.029000 0.005005 +v 0.132075 -0.030000 0.004357 +v 0.134739 -0.029000 0.004866 +v 0.136525 -0.030000 0.005903 +v 0.138220 -0.029000 0.007682 +v 0.129189 -0.029000 0.008831 +v 0.127940 -0.029000 0.012411 +v 0.133073 -0.029000 0.008050 +v 0.129478 -0.029000 0.015298 +v 0.133736 -0.029000 0.015868 +v 0.136047 -0.029000 0.012645 +v 0.135422 -0.029000 0.009793 +v 0.136127 -0.034000 0.012414 +v 0.134475 -0.034000 0.015242 +v 0.131497 -0.034000 0.016095 +v 0.129070 -0.034000 0.014793 +v 0.127887 -0.034000 0.012301 +v 0.129204 -0.034000 0.008939 +v 0.132316 -0.034000 0.007940 +v 0.134965 -0.034000 0.009179 +v 0.134053 -0.033920 0.007515 +v 0.136604 -0.034002 0.010415 +v 0.131435 -0.033865 0.007080 +v 0.135966 -0.033956 0.014958 +v 0.127130 -0.033958 0.011120 +v 0.128723 -0.033902 0.008249 +v 0.128417 -0.033931 0.015393 +v 0.131051 -0.033868 0.016908 +v 0.133627 -0.033928 0.016659 +v 0.137120 -0.030101 0.012537 +v 0.137081 -0.033514 0.012767 +v 0.136820 -0.030284 0.010490 +v 0.136255 -0.033501 0.009240 +v 0.135970 -0.030293 0.008891 +v 0.134555 -0.030264 0.007625 +v 0.132372 -0.030243 0.006931 +v 0.130122 -0.030299 0.007304 +v 0.128464 -0.030108 0.008294 +v 0.127381 -0.030295 0.009901 +v 0.126931 -0.030102 0.010810 +v 0.127044 -0.033510 0.013191 +v 0.127101 -0.030267 0.013287 +v 0.127850 -0.030113 0.014985 +v 0.129147 -0.030322 0.016176 +v 0.131098 -0.030128 0.017053 +v 0.133211 -0.030290 0.016925 +v 0.135197 -0.030344 0.015922 +v 0.136618 -0.030396 0.014045 +v 0.136612 -0.030047 0.009418 +v 0.134161 -0.030025 0.006993 +v 0.130433 -0.030038 0.006884 +v 0.126689 -0.030024 0.013091 +v 0.129705 -0.030032 0.016831 +v 0.134460 -0.030031 0.016749 +v 0.136419 -0.030039 0.014935 +v 0.126510 -0.004194 0.025529 +v 0.137526 -0.002086 0.025883 +v 0.126473 0.002805 0.025771 +v 0.137488 0.004881 0.025380 +v 0.137516 0.028720 0.018770 +v 0.126478 0.028702 0.018793 +v 0.125994 -0.019449 0.013859 +v 0.137991 -0.018947 0.014577 +v 0.138238 -0.023171 0.006579 +v 0.125769 -0.023119 0.006683 +v 0.138390 0.028464 0.000354 +v 0.125643 0.028634 0.000354 +v 0.138320 -0.028647 0.000354 +v 0.137516 -0.028702 0.018793 +v 0.126478 -0.028720 0.018770 +v 0.138291 0.022027 0.009665 +v 0.138298 0.018322 0.015538 +v 0.125995 0.021446 0.010577 +v 0.138230 0.023267 0.005940 +v 0.125598 0.015556 0.018798 +v 0.125570 0.024313 0.000376 +v 0.138100 0.023951 0.000376 +v 0.125995 0.023525 0.004063 +v 0.125995 0.014722 0.018846 +v 0.138198 0.013336 0.019943 +v 0.126005 0.006915 0.022965 +v 0.137989 0.004938 0.023496 +v 0.126004 -0.003421 0.023764 +v 0.137991 -0.003908 0.023573 +v 0.138284 -0.009244 0.022179 +v 0.125773 -0.010991 0.021314 +v 0.138209 -0.014689 0.018958 +v 0.125751 -0.015934 0.017932 +v 0.125891 -0.024038 0.000434 +v 0.138073 -0.024024 0.000414 +v 0.138499 -0.027843 0.018140 +v 0.138496 -0.020962 0.012610 +v 0.138499 0.027868 0.018108 +v 0.138577 0.005101 0.024114 +v 0.138582 -0.002424 0.024551 +v 0.125499 0.021830 0.011292 +v 0.125421 0.003757 0.024494 +v 0.125425 -0.004151 0.024239 +v 0.125497 -0.021503 0.011657 +v 0.125494 0.027843 0.018140 +v 0.125604 -0.028464 0.000354 +v 0.125494 -0.027868 0.018108 +v 0.126588 0.009916 -0.024159 +v 0.127563 0.023517 -0.015538 +v 0.130346 0.023353 -0.015643 +v 0.137439 0.010670 -0.023760 +v 0.134476 0.023045 -0.015843 +v 0.137421 0.024394 -0.014992 +v 0.126235 0.025254 -0.014223 +v 0.131948 0.025902 -0.014039 +v 0.137503 -0.001415 -0.026053 +v 0.126493 -0.002317 -0.025928 +v 0.137455 -0.011625 -0.023175 +v 0.126527 -0.011749 -0.023111 +v 0.125924 -0.023991 -0.000392 +v 0.138366 -0.028478 -0.000346 +v 0.138266 -0.023928 -0.000346 +v 0.138275 0.028667 -0.000346 +v 0.125728 0.023928 -0.000346 +v 0.138309 0.024000 -0.000346 +v 0.125627 0.028478 -0.000346 +v 0.125673 -0.028647 -0.000346 +v 0.133426 0.028478 -0.006811 +v 0.136172 0.028659 -0.006811 +v 0.137717 0.026854 -0.006811 +v 0.132105 0.026052 -0.006811 +v 0.137434 0.024371 -0.006811 +v 0.133945 0.023110 -0.006811 +v 0.137538 0.027505 -0.012800 +v 0.135663 0.028799 -0.010373 +v 0.133316 0.028327 -0.011595 +v 0.127261 0.028463 -0.006811 +v 0.130036 0.028661 -0.006811 +v 0.131649 0.027125 -0.006811 +v 0.126144 0.025535 -0.006811 +v 0.131319 0.024135 -0.006811 +v 0.127982 0.023211 -0.006811 +v 0.130926 0.028268 -0.011858 +v 0.127877 0.028682 -0.010851 +v 0.126483 0.027287 -0.012932 +v 0.126465 0.028729 -0.010858 +v 0.137492 0.028953 -0.009655 +v 0.125452 0.012090 -0.021608 +v 0.125414 0.002753 -0.024529 +v 0.125423 -0.004735 -0.024179 +v 0.125419 -0.010374 -0.022439 +v 0.125491 0.027508 -0.011438 +v 0.138503 0.027547 -0.011416 +v 0.138550 0.009979 -0.022692 +v 0.138497 -0.009693 -0.023030 +v 0.138581 -0.000544 -0.024723 +v 0.137997 0.023254 -0.005851 +v 0.138496 0.023678 -0.006427 +v 0.138250 0.019219 -0.014464 +v 0.137999 0.015969 -0.017775 +v 0.137999 0.010064 -0.021671 +v 0.137989 0.002187 -0.023852 +v 0.137992 -0.005980 -0.023130 +v 0.138495 -0.012860 -0.020962 +v 0.137992 -0.011879 -0.020692 +v 0.137992 -0.016938 -0.016850 +v 0.138270 -0.020425 -0.012652 +v 0.138265 -0.023482 -0.005184 +v 0.138503 -0.027508 -0.011438 +v 0.125497 0.023727 -0.006029 +v 0.126002 0.023232 -0.005925 +v 0.125995 -0.022337 -0.008491 +v 0.125499 -0.023535 -0.007140 +v 0.125733 -0.018318 -0.015599 +v 0.125996 -0.014340 -0.019161 +v 0.125993 -0.005756 -0.023301 +v 0.126005 0.002480 -0.023730 +v 0.126002 0.008020 -0.022472 +v 0.126003 0.014860 -0.018814 +v 0.125770 0.019966 -0.013273 +v 0.134634 -0.023051 -0.015838 +v 0.129626 -0.023044 -0.015843 +v 0.126572 -0.024393 -0.014993 +v 0.137316 -0.024290 -0.015064 +v 0.131983 -0.025621 -0.014219 +v 0.133261 -0.028416 -0.006811 +v 0.132139 -0.025569 -0.006811 +v 0.136476 -0.028563 -0.006811 +v 0.134463 -0.022972 -0.006811 +v 0.137965 -0.025329 -0.006811 +v 0.132806 -0.027805 -0.012371 +v 0.137750 -0.026759 -0.013250 +v 0.134433 -0.028808 -0.010326 +v 0.137174 -0.028074 -0.012097 +v 0.128997 -0.022925 -0.006811 +v 0.131822 -0.025248 -0.006811 +v 0.126136 -0.025335 -0.006811 +v 0.127034 -0.028153 -0.006811 +v 0.130529 -0.028658 -0.006811 +v 0.126385 -0.027207 -0.013013 +v 0.128383 -0.028854 -0.010271 +v 0.131006 -0.028038 -0.012061 +v 0.137489 -0.028968 -0.009585 +v 0.126479 -0.028844 -0.010300 +v 0.125490 -0.027546 -0.011416 +v 0.124917 -0.034000 0.009261 +v 0.124555 -0.030000 0.009999 +v 0.128953 -0.034000 0.002329 +v 0.129053 -0.030000 0.002016 +v 0.129125 -0.034000 -0.019810 +v 0.129287 -0.030000 -0.018512 +v 0.124783 -0.030000 -0.027660 +v 0.124712 -0.034000 -0.027641 +v 0.128141 -0.030000 -0.036554 +v 0.125208 -0.034000 -0.033758 +v 0.124858 -0.030000 -0.032765 +v 0.130474 -0.034000 -0.037563 +v 0.133448 -0.030000 -0.037564 +v 0.135489 -0.034000 -0.036721 +v 0.138786 -0.030000 -0.033758 +v 0.138586 -0.034000 -0.033811 +v 0.139543 -0.034000 -0.028305 +v 0.139282 -0.030000 -0.027641 +v 0.134920 -0.034000 -0.020092 +v 0.134889 -0.030000 -0.019912 +v 0.135021 -0.030000 0.002329 +v 0.134932 -0.034000 0.002021 +v 0.139282 -0.034000 0.009649 +v 0.139398 -0.030000 0.009951 +v 0.138786 -0.034000 0.015767 +v 0.139060 -0.030000 0.014751 +v 0.136211 -0.030000 0.018397 +v 0.134196 -0.034000 0.019294 +v 0.130506 -0.030000 0.019572 +v 0.128820 -0.034000 0.019009 +v 0.125457 -0.030000 0.016081 +v 0.124678 -0.034000 0.014416 +v 0.130831 0.024498 0.009945 +v 0.133441 0.024497 0.013828 +v 0.130932 0.024489 0.014161 +v 0.134322 0.024497 0.011944 +v 0.133254 0.024496 0.010027 +v 0.129672 0.024497 0.011944 +v 0.132643 0.034500 0.015095 +v 0.132788 0.025240 0.015014 +v 0.134603 0.025253 0.013569 +v 0.134930 0.034500 0.013024 +v 0.135026 0.025240 0.011289 +v 0.134701 0.034500 0.010564 +v 0.132884 0.025239 0.008979 +v 0.132788 0.034500 0.009001 +v 0.130210 0.034500 0.009491 +v 0.130227 0.025253 0.009514 +v 0.128872 0.025233 0.011761 +v 0.128874 0.034500 0.011922 +v 0.130077 0.025251 0.014430 +v 0.129975 0.034500 0.014305 +v 0.132157 0.034500 0.018932 +v 0.128159 0.034500 0.017718 +v 0.138793 0.034500 0.013496 +v 0.136295 0.034500 0.017408 +v 0.129526 0.034500 0.005530 +v 0.125124 0.034500 0.013597 +v 0.126137 0.034500 0.008352 +v 0.137882 0.034500 0.008237 +v 0.133933 0.034500 0.005376 +v 0.130528 0.035325 0.005300 +v 0.132278 0.035330 0.006829 +v 0.134467 0.035325 0.005530 +v 0.125579 0.035325 0.014618 +v 0.126978 0.035334 0.010579 +v 0.125263 0.035325 0.010681 +v 0.127262 0.035334 0.014101 +v 0.127043 0.035325 0.007159 +v 0.129028 0.035327 0.007757 +v 0.131836 0.035325 0.018990 +v 0.134497 0.035353 0.016532 +v 0.132765 0.035359 0.017115 +v 0.134714 0.035336 0.007597 +v 0.137857 0.035325 0.008352 +v 0.136432 0.035373 0.009338 +v 0.138896 0.035325 0.013114 +v 0.136413 0.035325 0.017312 +v 0.129530 0.035332 0.016631 +v 0.127919 0.035325 0.017502 +v 0.136327 0.035328 0.014801 +v 0.137178 0.035329 0.012149 +v 0.130910 0.037803 0.014973 +v 0.132215 0.037732 0.014306 +v 0.131106 0.037678 0.013921 +v 0.129926 0.037721 0.013025 +v 0.133466 0.037798 0.014725 +v 0.129897 0.037780 0.010958 +v 0.128888 0.037748 0.012794 +v 0.129041 0.037802 0.011007 +v 0.131883 0.037718 0.009642 +v 0.130469 0.037792 0.009283 +v 0.134007 0.037778 0.010818 +v 0.132805 0.037800 0.009038 +v 0.134767 0.037799 0.010550 +v 0.134078 0.037745 0.013049 +v 0.135109 0.037764 0.012659 +v 0.135391 0.037000 0.014239 +v 0.131468 0.036756 0.007727 +v 0.129032 0.036785 0.015086 +v 0.132028 0.036872 0.016173 +v 0.134659 0.036781 0.008686 +v 0.133270 0.036911 0.008082 +v 0.127820 0.036752 0.011007 +v 0.130380 0.036760 0.015977 +v 0.134496 0.036651 0.015638 +v 0.136109 0.036807 0.010912 +v 0.129841 0.036541 0.008099 +v 0.128589 0.036658 0.009305 +v 0.127590 0.036332 0.013326 +v 0.136466 0.036330 0.012982 +v 0.129997 0.035490 0.013159 +v 0.131997 0.035490 0.014313 +v 0.129997 0.035490 0.010849 +v 0.133997 0.035490 0.013159 +v 0.131997 0.035490 0.009695 +v 0.133997 0.035490 0.010849 +v 0.124514 0.030000 0.010165 +v 0.124629 0.029000 0.009525 +v 0.125351 0.029000 0.015843 +v 0.125534 0.030000 0.016200 +v 0.129128 0.029000 0.019040 +v 0.129945 0.030000 0.019344 +v 0.134784 0.029000 0.019261 +v 0.134885 0.030000 0.019085 +v 0.138453 0.030000 0.016010 +v 0.139191 0.029000 0.014678 +v 0.139632 0.030000 0.010959 +v 0.138848 0.029000 0.008330 +v 0.137142 0.030000 0.006413 +v 0.134418 0.029000 0.004802 +v 0.132401 0.030000 0.004309 +v 0.129234 0.029000 0.004810 +v 0.127469 0.030000 0.005903 +v 0.133525 0.029000 0.008177 +v 0.136048 0.029000 0.010995 +v 0.129589 0.029000 0.008557 +v 0.134713 0.029000 0.015256 +v 0.130811 0.029000 0.015926 +v 0.127843 0.029000 0.013028 +v 0.127916 0.034000 0.012408 +v 0.129369 0.034000 0.015148 +v 0.131965 0.034000 0.016063 +v 0.135021 0.034000 0.014881 +v 0.136047 0.034000 0.011241 +v 0.134464 0.034000 0.008781 +v 0.131312 0.034000 0.007886 +v 0.128622 0.034000 0.009750 +v 0.129595 0.033899 0.007644 +v 0.127742 0.033893 0.009539 +v 0.132594 0.033876 0.007082 +v 0.127034 0.033934 0.012063 +v 0.136523 0.033946 0.010090 +v 0.134898 0.033922 0.008004 +v 0.128986 0.033938 0.015875 +v 0.134978 0.033927 0.015947 +v 0.136495 0.033928 0.013985 +v 0.131093 0.033938 0.016849 +v 0.127115 0.030431 0.010702 +v 0.128030 0.030263 0.008879 +v 0.129668 0.030265 0.007461 +v 0.132159 0.030318 0.006963 +v 0.134339 0.030299 0.007478 +v 0.136351 0.030109 0.009287 +v 0.136952 0.030307 0.010937 +v 0.137064 0.033514 0.011865 +v 0.136922 0.030259 0.013201 +v 0.135807 0.030363 0.015335 +v 0.133878 0.030266 0.016714 +v 0.132954 0.033502 0.016940 +v 0.132191 0.030102 0.017125 +v 0.130302 0.030279 0.016778 +v 0.128617 0.030298 0.015762 +v 0.127638 0.033499 0.014573 +v 0.127568 0.030284 0.014424 +v 0.127042 0.030105 0.013409 +v 0.126848 0.030056 0.010697 +v 0.129155 0.030018 0.007373 +v 0.132611 0.030024 0.006617 +v 0.135186 0.030031 0.007762 +v 0.137356 0.030025 0.012323 +v 0.129084 0.030030 0.016573 +v 0.136340 0.030040 0.015039 +v 0.134497 0.030017 0.016801 +v 0.139227 0.034000 0.009577 +v 0.138943 0.030000 0.008985 +v 0.134941 0.030000 0.002016 +v 0.134827 0.034000 0.001180 +v 0.134869 0.034000 -0.019810 +v 0.134707 0.030000 -0.018512 +v 0.139211 0.030000 -0.027660 +v 0.139722 0.034000 -0.028722 +v 0.136852 0.030000 -0.035914 +v 0.138013 0.034000 -0.034664 +v 0.139305 0.030000 -0.032002 +v 0.133155 0.034000 -0.037689 +v 0.131332 0.030000 -0.037673 +v 0.126815 0.034000 -0.035700 +v 0.125911 0.030000 -0.034723 +v 0.124354 0.034000 -0.030464 +v 0.124408 0.030000 -0.028351 +v 0.125264 0.034000 -0.026618 +v 0.129073 0.034000 -0.020092 +v 0.129104 0.030000 -0.019912 +v 0.128973 0.030000 0.002329 +v 0.129156 0.034000 0.001467 +v 0.124880 0.034000 0.009313 +v 0.124917 0.030000 0.009261 +v 0.124678 0.030000 0.014416 +v 0.124681 0.034000 0.014265 +v 0.127994 0.034000 0.018531 +v 0.128141 0.030000 0.018570 +v 0.133490 0.030000 0.019572 +v 0.134088 0.034000 0.019476 +v 0.137740 0.030000 0.016949 +v 0.139029 0.034000 0.015156 +v 0.139531 0.030000 0.013104 +v 0.128882 -0.024514 -0.009811 +v 0.126988 -0.024066 -0.009702 +v 0.128904 -0.023231 -0.009679 +v 0.126221 -0.026142 -0.009694 +v 0.127556 -0.025920 -0.009811 +v 0.128293 -0.028684 -0.009682 +v 0.126801 -0.027622 -0.009736 +v 0.129112 -0.027486 -0.009811 +v 0.131550 -0.025006 -0.009712 +v 0.131601 -0.027021 -0.009700 +v 0.130438 -0.026080 -0.009811 +v 0.130414 -0.023651 -0.009736 +v 0.130022 -0.028549 -0.009733 +v 0.127871 -0.025926 0.005194 +v 0.130015 -0.026960 0.005015 +v 0.129509 -0.024982 0.005213 +v 0.129024 -0.027415 0.005013 +v 0.128282 -0.024498 0.004724 +v 0.127349 -0.025866 -0.006721 +v 0.127526 -0.026643 0.004703 +v 0.127949 -0.027208 -0.006734 +v 0.129497 -0.027563 -0.006703 +v 0.130416 -0.026862 -0.006746 +v 0.130539 -0.025435 0.004716 +v 0.130263 -0.024900 -0.006721 +v 0.128459 -0.024475 -0.006727 +v 0.130698 -0.028117 -0.006877 +v 0.131723 -0.026599 -0.006900 +v 0.127556 -0.023590 -0.006870 +v 0.126185 -0.025903 -0.006910 +v 0.128852 -0.028804 -0.006890 +v 0.126927 -0.027774 -0.006859 +v 0.131375 -0.024666 -0.006878 +v 0.130019 -0.023423 -0.006893 +v 0.130438 -0.026080 -0.007811 +v 0.128719 -0.027464 -0.007811 +v 0.129275 -0.024536 -0.007811 +v 0.127556 -0.025920 -0.007811 +v 0.132529 -0.027153 -0.009709 +v 0.132264 -0.025450 -0.009698 +v 0.133868 -0.026973 -0.009811 +v 0.133663 -0.028444 -0.009714 +v 0.137300 -0.027523 -0.009715 +v 0.135757 -0.028652 -0.009702 +v 0.136404 -0.026491 -0.009811 +v 0.136710 -0.023836 -0.009699 +v 0.134719 -0.024536 -0.009811 +v 0.134891 -0.023239 -0.009707 +v 0.133284 -0.023863 -0.009703 +v 0.137722 -0.025513 -0.009713 +v 0.133875 -0.026120 0.005194 +v 0.135615 -0.026968 0.005220 +v 0.135397 -0.024923 0.005220 +v 0.133339 -0.025712 -0.006716 +v 0.134113 -0.027328 -0.006735 +v 0.134360 -0.027473 0.004703 +v 0.135416 -0.027563 -0.006726 +v 0.136311 -0.026938 0.004695 +v 0.136458 -0.026674 -0.006729 +v 0.136518 -0.025410 -0.006714 +v 0.136304 -0.025149 0.004690 +v 0.134992 -0.024345 -0.006724 +v 0.134941 -0.024437 0.004703 +v 0.133428 -0.025578 0.004707 +v 0.132578 -0.027387 -0.006884 +v 0.134980 -0.028850 -0.006881 +v 0.137413 -0.027389 -0.006878 +v 0.137459 -0.024568 -0.006888 +v 0.132409 -0.024960 -0.006892 +v 0.134607 -0.023177 -0.006874 +v 0.135112 -0.024514 -0.007811 +v 0.136226 -0.026843 -0.007811 +v 0.133653 -0.026643 -0.007811 +v 0.137289 0.024598 -0.009756 +v 0.136196 0.023514 -0.009699 +v 0.135112 0.024514 -0.009811 +v 0.133918 0.023402 -0.009718 +v 0.134882 0.027486 -0.009811 +v 0.133572 0.028356 -0.009712 +v 0.135938 0.028664 -0.009722 +v 0.132292 0.025336 -0.009705 +v 0.132657 0.027307 -0.009764 +v 0.137737 0.026594 -0.009718 +v 0.135958 0.026590 0.005194 +v 0.134069 0.026662 0.005213 +v 0.135028 0.024845 0.005228 +v 0.135491 0.024459 0.004713 +v 0.136589 0.025774 -0.006730 +v 0.136570 0.026472 0.004716 +v 0.136223 0.027024 -0.006729 +v 0.135021 0.027646 -0.006746 +v 0.134988 0.027554 0.004696 +v 0.134140 0.027365 -0.006705 +v 0.133631 0.026785 0.004692 +v 0.133380 0.025998 -0.006721 +v 0.133693 0.025122 0.004696 +v 0.134264 0.024519 -0.006723 +v 0.135810 0.024631 -0.006729 +v 0.137174 0.024282 -0.006893 +v 0.137733 0.026161 -0.006885 +v 0.135538 0.028699 -0.006878 +v 0.133002 0.028036 -0.006873 +v 0.137105 0.027759 -0.006896 +v 0.135490 0.023305 -0.006877 +v 0.132295 0.025211 -0.006913 +v 0.133666 0.023604 -0.006865 +v 0.133556 0.026080 -0.007811 +v 0.135275 0.027464 -0.007811 +v 0.134719 0.024536 -0.007811 +v 0.136438 0.025920 -0.007811 +v 0.131319 0.027481 -0.009718 +v 0.131738 0.025512 -0.009688 +v 0.130438 0.026080 -0.009811 +v 0.128719 0.027464 -0.009811 +v 0.129600 0.028720 -0.009705 +v 0.128965 0.023239 -0.009715 +v 0.127026 0.024039 -0.009699 +v 0.129275 0.024536 -0.009811 +v 0.130712 0.023851 -0.009708 +v 0.127556 0.025920 -0.009811 +v 0.126203 0.026478 -0.009720 +v 0.127613 0.028377 -0.009703 +v 0.128263 0.027133 0.005127 +v 0.129879 0.025353 0.005197 +v 0.130290 0.026542 0.005001 +v 0.128048 0.025352 0.005220 +v 0.130276 0.027105 -0.006729 +v 0.129406 0.027510 0.004702 +v 0.128690 0.027575 -0.006729 +v 0.127561 0.026727 -0.006724 +v 0.127415 0.025859 0.004699 +v 0.127659 0.025014 -0.006722 +v 0.128424 0.024555 0.004696 +v 0.129282 0.024416 -0.006729 +v 0.130214 0.024918 0.004704 +v 0.130614 0.025637 -0.006693 +v 0.126682 0.027468 -0.006884 +v 0.126274 0.025400 -0.006872 +v 0.131745 0.026477 -0.006891 +v 0.130181 0.028546 -0.006877 +v 0.127999 0.028561 -0.006902 +v 0.127718 0.023541 -0.006882 +v 0.129886 0.023371 -0.006902 +v 0.131311 0.024562 -0.006871 +v 0.128882 0.024514 -0.007811 +v 0.127556 0.025920 -0.007811 +v 0.130438 0.026080 -0.007811 +v 0.129112 0.027486 -0.007811 +v 0.131068 -0.034000 0.007967 +v 0.128780 -0.034000 0.005184 +v 0.125562 -0.034000 0.007833 +v 0.127855 -0.034000 0.010987 +v 0.124487 -0.034000 0.013974 +v 0.132625 -0.034000 0.004389 +v 0.134690 -0.034000 0.008857 +v 0.137815 -0.034000 0.006916 +v 0.129080 -0.034000 0.014878 +v 0.128437 -0.034000 0.018796 +v 0.134777 -0.034000 0.015076 +v 0.133707 -0.034000 0.019452 +v 0.137660 -0.034000 0.017064 +v 0.131707 -0.034000 0.016069 +v 0.136092 -0.034000 0.011948 +v 0.139639 -0.034000 0.012635 +v 0.127849 -0.034500 0.012656 +v 0.129961 -0.034500 0.015534 +v 0.133331 -0.034500 0.015955 +v 0.136125 -0.034500 0.012771 +v 0.134661 -0.034500 0.008797 +v 0.131363 -0.034500 0.007979 +v 0.128975 -0.034500 0.009270 +v 0.131838 -0.034500 0.004364 +v 0.136781 -0.034500 0.018075 +v 0.139511 -0.034500 0.013248 +v 0.136460 -0.034500 0.005832 +v 0.131452 -0.034500 0.019601 +v 0.139001 -0.034500 0.009121 +v 0.127282 -0.034500 0.006023 +v 0.124878 -0.034500 0.009417 +v 0.126583 -0.034500 0.017476 +v 0.124501 -0.034500 0.013092 +v 0.133767 0.034000 0.008229 +v 0.133471 0.034000 0.004532 +v 0.137154 0.034000 0.006457 +v 0.135974 0.034000 0.011027 +v 0.139343 0.034000 0.009993 +v 0.130369 0.034000 0.008268 +v 0.128216 0.034000 0.005299 +v 0.128289 0.034000 0.010266 +v 0.124380 0.034000 0.010500 +v 0.131396 0.034000 0.016226 +v 0.125581 0.034179 0.016063 +v 0.128155 0.034000 0.013486 +v 0.128544 0.034000 0.018768 +v 0.135397 0.034000 0.014371 +v 0.139210 0.034000 0.014378 +v 0.136364 0.034000 0.018307 +v 0.132156 0.034000 0.019559 +v 0.136060 0.034500 0.011069 +v 0.135388 0.034500 0.014231 +v 0.132926 0.034500 0.016041 +v 0.129303 0.034500 0.015152 +v 0.127902 0.034500 0.012060 +v 0.129002 0.034500 0.009211 +v 0.132837 0.034500 0.007823 +v 0.124431 0.034500 0.013257 +v 0.128695 0.034500 0.005015 +v 0.125184 0.034500 0.008695 +v 0.128883 0.034500 0.018955 +v 0.133772 0.034500 0.004641 +v 0.137229 0.034500 0.006500 +v 0.139626 0.034500 0.010981 +v 0.134415 0.034500 0.019346 +v 0.138493 0.034500 0.015937 +v 0.026444 0.028161 0.023596 +v 0.038156 0.018793 0.026061 +v 0.041396 0.019765 0.024258 +v 0.045665 0.016718 0.023543 +v 0.043418 0.014397 0.026274 +v 0.046283 0.010557 0.026390 +v 0.028604 0.022920 0.025681 +v 0.014151 0.031794 0.022886 +v -0.004741 0.032043 0.021774 +v -0.004307 0.033385 0.020289 +v 0.012660 0.033443 0.020837 +v 0.043757 0.026703 0.014052 +v 0.049029 0.024817 0.009600 +v 0.035005 0.033353 0.013994 +v 0.038056 0.033182 0.008095 +v 0.048980 0.026367 0.002997 +v 0.038818 0.033439 0.003215 +v 0.048975 0.026345 -0.003629 +v 0.038671 0.033394 -0.004522 +v 0.049026 0.023971 -0.011446 +v 0.036177 0.033352 -0.011869 +v 0.035043 0.033343 -0.013992 +v 0.045462 0.025193 -0.014402 +v 0.048983 0.020394 -0.016995 +v 0.048240 0.019125 -0.019215 +v 0.049038 0.014385 -0.022388 +v 0.045873 0.016610 -0.023440 +v 0.045109 0.012447 -0.026334 +v 0.048795 0.005070 -0.026372 +v 0.048982 0.010918 0.024292 +v 0.049092 0.000444 0.026610 +v 0.048193 0.019171 0.019074 +v 0.047374 0.017038 0.021760 +v 0.048982 0.020887 0.016438 +v 0.046617 0.023603 0.015437 +v 0.091774 0.026587 0.000978 +v 0.091767 0.025272 0.008028 +v 0.091802 0.022105 0.014911 +v 0.091708 0.015934 0.021285 +v 0.091747 0.008469 0.025243 +v 0.091782 -0.000403 0.026601 +v 0.091763 -0.009373 0.024909 +v 0.049026 -0.008524 0.025161 +v 0.049015 -0.013744 0.022696 +v 0.091750 -0.017390 0.020160 +v 0.049010 -0.018278 0.019295 +v 0.049002 -0.023754 0.012164 +v 0.091750 -0.023172 0.013108 +v 0.091756 -0.026492 0.003318 +v 0.048997 -0.026766 0.000369 +v 0.091751 -0.025727 -0.006834 +v 0.048951 -0.023867 -0.011818 +v 0.091749 -0.021909 -0.015120 +v 0.049027 -0.020323 -0.017225 +v 0.091782 -0.015669 -0.021491 +v 0.049003 -0.014721 -0.022144 +v 0.091729 -0.006322 -0.025943 +v 0.049009 -0.008296 -0.025215 +v 0.049051 -0.000468 -0.026573 +v 0.091737 0.004067 -0.026312 +v 0.091774 0.012542 -0.023459 +v 0.091726 0.019691 -0.017928 +v 0.091728 0.025138 -0.009016 +v 0.046150 -0.010842 -0.026381 +v 0.044392 -0.012597 -0.026276 +v 0.021395 -0.012500 -0.025377 +v 0.020629 0.012500 -0.025265 +v -0.004518 0.012500 -0.024162 +v -0.004403 0.023585 -0.024211 +v 0.029590 0.022683 -0.025713 +v 0.039118 0.018148 -0.026096 +v -0.006185 0.023668 0.023961 +v 0.020549 0.012500 0.025331 +v 0.021542 -0.012498 0.025390 +v -0.004761 -0.012500 0.024142 +v -0.003765 -0.019577 0.024293 +v 0.045354 -0.012123 0.026120 +v 0.033127 -0.018992 0.025868 +v 0.046356 -0.010439 0.026395 +v 0.046407 -0.016090 -0.023274 +v -0.004795 0.012500 0.024135 +v -0.014444 0.012500 0.020129 +v -0.017315 0.023493 0.017715 +v -0.021457 0.012500 0.012070 +v -0.023851 0.023491 0.006684 +v -0.024516 0.012500 0.002911 +v -0.023996 0.023490 -0.006137 +v -0.023694 0.012500 -0.006674 +v -0.019970 0.012500 -0.014389 +v -0.019617 0.023471 -0.014777 +v -0.013429 0.023510 -0.020708 +v -0.012946 0.012500 -0.021015 +v 0.019083 -0.012500 -0.023325 +v 0.025364 -0.012500 -0.004085 +v 0.019093 0.012500 -0.022399 +v 0.025306 0.012500 -0.004181 +v 0.019124 0.012500 0.022280 +v 0.025097 0.012500 0.005132 +v 0.019068 -0.012500 0.023462 +v 0.025047 -0.012500 0.005215 +v 0.093998 -0.025218 0.002906 +v 0.093997 -0.021686 0.013196 +v 0.093998 -0.014205 0.021040 +v 0.093997 -0.005174 0.024783 +v 0.093997 0.003492 0.025076 +v 0.093998 0.012722 0.021968 +v 0.093998 0.021402 0.013808 +v 0.093997 0.025061 0.003569 +v 0.093997 0.024794 -0.005098 +v 0.093998 0.021098 -0.014108 +v 0.093999 0.011477 -0.022844 +v 0.093998 -0.002396 -0.025351 +v 0.093997 -0.012704 -0.021891 +v 0.093998 -0.020788 -0.014708 +v 0.093997 -0.024617 -0.005655 +v -0.004181 0.032013 -0.021839 +v 0.014328 0.031651 -0.022930 +v -0.011265 0.031998 -0.019237 +v -0.017048 0.031995 -0.014321 +v -0.020250 0.032509 -0.008536 +v -0.022029 0.031966 -0.002975 +v -0.021856 0.032019 0.004370 +v -0.019351 0.032023 0.010923 +v -0.015544 0.032254 0.015744 +v -0.011384 0.031933 0.019124 +v 0.033939 0.024647 -0.023890 +v 0.042641 0.018596 -0.024262 +v 0.023548 0.029107 -0.023467 +v -0.004194 0.033380 -0.020354 +v 0.012904 0.033178 -0.021474 +v 0.012619 0.033562 -0.019090 +v -0.008588 0.032970 -0.019554 +v -0.020768 0.033377 0.000013 +v -0.017344 0.033379 0.011454 +v -0.009174 0.033381 0.018771 +v -0.014821 0.032991 -0.015464 +v -0.020550 0.033083 0.005325 +v -0.012689 0.033433 -0.016041 +v -0.019059 0.033445 -0.007369 +v 0.044770 0.001000 -0.014231 +v 0.026528 0.001000 -0.014059 +v 0.025386 0.014500 -0.014092 +v 0.017724 0.014500 -0.014174 +v 0.017745 0.033500 -0.014147 +v 0.023386 0.001000 -0.015993 +v 0.022679 0.014500 -0.018170 +v 0.022885 0.001000 -0.020510 +v 0.023381 0.014500 -0.021405 +v 0.025894 0.001000 -0.023515 +v 0.026147 0.014500 -0.023546 +v 0.043935 0.001000 -0.024158 +v 0.047346 0.001000 -0.022140 +v 0.047716 0.001000 -0.017063 +v 0.014624 0.014500 -0.023064 +v 0.012948 0.014500 -0.018613 +v 0.012741 0.014500 -0.021240 +v 0.026583 0.014500 0.023587 +v 0.026491 0.001000 0.023580 +v 0.023733 0.014500 0.021989 +v 0.023573 0.001000 0.021787 +v 0.022732 0.014500 0.017133 +v 0.022702 0.001000 0.017744 +v 0.025378 0.001000 0.014324 +v 0.026350 0.014500 0.014025 +v 0.044449 0.001000 0.014157 +v 0.017714 0.033500 0.014185 +v 0.017788 0.014500 0.014151 +v 0.044530 0.001000 0.024089 +v 0.047665 0.001000 0.016829 +v 0.047566 0.001000 0.021492 +v 0.014615 0.014500 0.023076 +v 0.012691 0.014500 0.021126 +v 0.012983 0.014500 0.018596 +v 0.012948 0.033500 0.018621 +v -0.005050 -0.029470 0.019698 +v 0.022332 -0.029500 0.014399 +v 0.020247 -0.029500 0.018106 +v 0.020565 -0.029440 0.021128 +v 0.030758 -0.029500 0.016692 +v 0.034084 -0.029491 0.014679 +v 0.032469 -0.029321 0.019790 +v 0.027755 -0.029500 0.013756 +v 0.029427 -0.029500 -0.014663 +v 0.033783 -0.029496 -0.014918 +v 0.026875 -0.029337 -0.010800 +v 0.024945 -0.029500 -0.013523 +v 0.024064 -0.029384 -0.008080 +v 0.031236 -0.029418 -0.019828 +v 0.032478 -0.029466 -0.018961 +v 0.026122 -0.029454 0.011097 +v 0.031186 -0.029393 0.019893 +v 0.040325 -0.029334 0.013937 +v 0.043751 -0.027626 0.012139 +v 0.041198 -0.028521 0.014504 +v 0.043509 -0.024541 0.017871 +v 0.040615 -0.015658 -0.026159 +v -0.005605 -0.012500 -0.024245 +v 0.033216 -0.018986 -0.025858 +v -0.004493 -0.019684 -0.024184 +v 0.040987 -0.015375 0.026180 +v -0.012293 -0.019502 0.021413 +v -0.013443 -0.012500 0.020713 +v -0.019589 -0.019500 0.014935 +v -0.020413 -0.012500 0.013787 +v -0.023005 -0.019497 0.008558 +v -0.023722 -0.012500 0.006451 +v -0.024678 -0.019502 0.000729 +v -0.024584 -0.012500 -0.001520 +v -0.022974 -0.019499 -0.008877 +v -0.022098 -0.012500 -0.011009 +v -0.019327 -0.019497 -0.015125 +v -0.016005 -0.012500 -0.018717 +v -0.013530 -0.019502 -0.020646 +v 0.041295 -0.028397 -0.014582 +v 0.043463 -0.024663 -0.017737 +v 0.040300 -0.029343 -0.013935 +v 0.043838 -0.027569 -0.012110 +v 0.021761 -0.028136 -0.022932 +v -0.003578 -0.027963 -0.021948 +v 0.023374 -0.024532 -0.024114 +v 0.026904 -0.023524 -0.024491 +v -0.007269 -0.027792 0.021067 +v -0.002785 -0.027921 0.022051 +v -0.012122 -0.028091 0.018592 +v -0.016637 -0.027974 0.014761 +v -0.019944 -0.027919 0.009901 +v -0.021718 -0.027936 0.004743 +v -0.021942 -0.028498 0.000233 +v -0.021977 -0.027919 -0.003425 +v -0.020104 -0.028252 -0.009299 +v -0.016835 -0.028025 -0.014468 +v -0.012622 -0.027939 -0.018354 +v -0.008062 -0.028070 -0.020631 +v 0.021704 -0.028250 0.022895 +v 0.024431 -0.023305 0.024498 +v 0.036187 -0.021239 0.024394 +v 0.040159 -0.019579 0.024207 +v 0.028377 -0.024645 0.024007 +v 0.033400 -0.026086 0.022207 +v 0.030676 -0.028356 0.021509 +v 0.045494 -0.016106 0.023863 +v 0.042978 -0.021250 0.021692 +v 0.035918 -0.021539 -0.024281 +v 0.032653 -0.028421 -0.020854 +v 0.030101 -0.027112 -0.022521 +v 0.040294 -0.019493 -0.024223 +v 0.043075 -0.021472 -0.021396 +v 0.033332 -0.017500 0.022121 +v 0.032400 -0.017500 0.018617 +v 0.035964 -0.017500 0.024249 +v 0.039109 -0.017501 0.024502 +v 0.042291 -0.017500 0.022707 +v 0.043600 -0.017500 0.018678 +v 0.042115 -0.017500 0.015301 +v 0.038545 -0.017500 0.013354 +v 0.035917 -0.029295 0.013806 +v 0.034280 -0.017500 0.014899 +v 0.042158 -0.017500 -0.015143 +v 0.043530 -0.017500 -0.018876 +v 0.042889 -0.017500 -0.021728 +v 0.040180 -0.017500 -0.024206 +v 0.035787 -0.017500 -0.024291 +v 0.032876 -0.017500 -0.021247 +v 0.032653 -0.017500 -0.016627 +v 0.037359 -0.017500 -0.013391 +v 0.035483 -0.029324 -0.013971 +v 0.020503 -0.017500 0.021160 +v 0.022888 -0.017500 0.023874 +v 0.025994 -0.017500 0.024603 +v 0.028975 -0.017500 0.023579 +v 0.031257 -0.017500 0.020094 +v 0.021118 -0.017500 0.015460 +v 0.026654 -0.017500 0.013453 +v 0.030197 -0.017500 0.015749 +v 0.030943 -0.017500 -0.020962 +v 0.031094 -0.017500 -0.017563 +v 0.028856 -0.017500 -0.023634 +v 0.025940 -0.017500 -0.024599 +v 0.022470 -0.017500 -0.023657 +v 0.020473 -0.017500 -0.020883 +v 0.020977 -0.029117 -0.021887 +v 0.020102 -0.029590 -0.019694 +v 0.029184 -0.017500 -0.014688 +v 0.025621 -0.017500 -0.013424 +v 0.020770 -0.017500 -0.015947 +v 0.021563 -0.029500 -0.015243 +v -0.005014 -0.029024 0.020807 +v -0.016292 -0.029450 -0.012255 +v -0.019937 -0.029352 -0.005792 +v -0.020206 -0.029444 0.002974 +v -0.019808 -0.029382 0.006335 +v -0.017434 -0.028982 0.012476 +v -0.012779 -0.029405 0.016264 +v -0.007358 -0.029388 -0.019400 +v -0.003185 -0.029374 -0.020496 +v -0.014645 -0.028950 -0.015761 +v 0.048997 -0.017500 0.012004 +v 0.031891 -0.017500 0.011718 +v 0.033072 -0.027242 0.011920 +v 0.048997 -0.017500 -0.011996 +v 0.031836 -0.017500 -0.011684 +v 0.033886 -0.027336 -0.012008 +v 0.028333 -0.027538 0.009850 +v 0.025888 -0.017500 0.007405 +v 0.025648 -0.027369 0.007042 +v 0.024173 -0.027205 0.004214 +v 0.023661 -0.017500 0.002396 +v 0.023358 -0.027165 0.000104 +v 0.023661 -0.017500 -0.002391 +v 0.024172 -0.027206 -0.004204 +v 0.025916 -0.017500 -0.007426 +v 0.026540 -0.027200 -0.008238 +v 0.030541 -0.027321 -0.011032 +v 0.032622 -0.028639 -0.012692 +v 0.022938 -0.028262 -0.000750 +v 0.026522 -0.028265 -0.008892 +v 0.033768 -0.028684 0.012843 +v 0.030226 -0.028523 0.011624 +v 0.023693 -0.028892 0.005808 +v 0.023025 -0.028633 0.003251 +v 0.023607 -0.028556 -0.004818 +v 0.026414 -0.028968 0.009773 +v 0.021520 -0.029371 -0.001854 +v 0.022009 -0.029450 0.005109 +v 0.039107 -0.023500 0.021722 +v 0.042061 -0.023402 0.021997 +v 0.039534 -0.023374 0.023893 +v 0.033509 -0.023397 0.021235 +v 0.032968 -0.023383 0.018618 +v 0.035134 -0.023500 0.018687 +v 0.039749 -0.023500 0.016764 +v 0.041056 -0.023394 0.015094 +v 0.042731 -0.023390 0.017339 +v 0.040860 -0.023500 0.019428 +v 0.038369 -0.023398 0.014026 +v 0.036886 -0.023500 0.016393 +v 0.034671 -0.023418 0.015180 +v 0.042917 -0.023400 0.019827 +v 0.036245 -0.023500 0.021352 +v 0.035637 -0.023409 0.023574 +v 0.039943 -0.001498 0.020845 +v 0.035309 -0.001613 0.017920 +v 0.036775 -0.001488 0.021452 +v 0.038390 -0.001488 0.016399 +v 0.040731 -0.001677 0.018121 +v 0.039555 -0.001990 0.021719 +v 0.039871 -0.017416 0.021595 +v 0.040939 -0.001996 0.019855 +v 0.041011 -0.017415 0.019727 +v 0.040875 -0.017418 0.017863 +v 0.039738 -0.001996 0.016532 +v 0.039734 -0.017412 0.016518 +v 0.037735 -0.017415 0.015912 +v 0.037240 -0.001983 0.016049 +v 0.035616 -0.017418 0.017046 +v 0.034844 -0.017414 0.019432 +v 0.034951 -0.001993 0.019562 +v 0.036652 -0.001987 0.021891 +v 0.036111 -0.017419 0.021526 +v 0.037766 -0.017408 0.022133 +v 0.043046 -0.017571 0.019894 +v 0.036572 -0.017584 0.014200 +v 0.034045 -0.017566 0.016002 +v 0.041933 -0.017565 0.015875 +v 0.041062 -0.017573 0.023029 +v 0.033963 -0.017579 0.022047 +v 0.036211 -0.017564 0.023748 +v 0.038799 -0.017574 0.023975 +v 0.039451 -0.017576 0.014293 +v 0.032937 -0.017584 0.018911 +v 0.035134 -0.018500 0.018687 +v 0.036886 -0.018500 0.016393 +v 0.036245 -0.018500 0.021352 +v 0.039107 -0.018500 0.021722 +v 0.040860 -0.018500 0.019428 +v 0.039749 -0.018500 0.016764 +v 0.040466 -0.023500 -0.017554 +v 0.042956 -0.023393 -0.019781 +v 0.042566 -0.023386 -0.016926 +v 0.035467 -0.023500 -0.017659 +v 0.034731 -0.023398 -0.015172 +v 0.033047 -0.023379 -0.018106 +v 0.040244 -0.023414 -0.014522 +v 0.037936 -0.023500 -0.016163 +v 0.040527 -0.023500 -0.020440 +v 0.041571 -0.023411 -0.022630 +v 0.036624 -0.023399 -0.023875 +v 0.039039 -0.023365 -0.023949 +v 0.038058 -0.023500 -0.021936 +v 0.037464 -0.023394 -0.014087 +v 0.035528 -0.023500 -0.020545 +v 0.033684 -0.023418 -0.021787 +v 0.035812 -0.001484 -0.020660 +v 0.035542 -0.001641 -0.017536 +v 0.040166 -0.001499 -0.017624 +v 0.039231 -0.001687 -0.021728 +v 0.040607 -0.001679 -0.020294 +v 0.036997 -0.001661 -0.016228 +v 0.035587 -0.017417 -0.017072 +v 0.037389 -0.017424 -0.016013 +v 0.039462 -0.001987 -0.016276 +v 0.039228 -0.017408 -0.016182 +v 0.040708 -0.017421 -0.017553 +v 0.041017 -0.001996 -0.018517 +v 0.041089 -0.017412 -0.019480 +v 0.040318 -0.017421 -0.021081 +v 0.038736 -0.017418 -0.022067 +v 0.036693 -0.001990 -0.021874 +v 0.036381 -0.017411 -0.021759 +v 0.034989 -0.001994 -0.019748 +v 0.034865 -0.017415 -0.019441 +v 0.035145 -0.017564 -0.014834 +v 0.038611 -0.017583 -0.014069 +v 0.040657 -0.017572 -0.023327 +v 0.033322 -0.017574 -0.017326 +v 0.034779 -0.017561 -0.022996 +v 0.042672 -0.017564 -0.020874 +v 0.041584 -0.017565 -0.015478 +v 0.033041 -0.017575 -0.019833 +v 0.042951 -0.017594 -0.018325 +v 0.037810 -0.017580 -0.024050 +v 0.038058 -0.018500 -0.021936 +v 0.040527 -0.018500 -0.020440 +v 0.035528 -0.018500 -0.020545 +v 0.035467 -0.018500 -0.017659 +v 0.037936 -0.018500 -0.016163 +v 0.040466 -0.018500 -0.017554 +v 0.022825 -0.023500 -0.019232 +v 0.021299 -0.023378 -0.016487 +v 0.020750 -0.023414 -0.019734 +v 0.026989 -0.023500 -0.016463 +v 0.027869 -0.023372 -0.014448 +v 0.024289 -0.023417 -0.014209 +v 0.024108 -0.023500 -0.016646 +v 0.029869 -0.023418 -0.016339 +v 0.028587 -0.023500 -0.018867 +v 0.030164 -0.023408 -0.021283 +v 0.030746 -0.023373 -0.018714 +v 0.028588 -0.023386 -0.023158 +v 0.027304 -0.023500 -0.021453 +v 0.025241 -0.023421 -0.024125 +v 0.024423 -0.023500 -0.021636 +v 0.021944 -0.023377 -0.022417 +v 0.023441 -0.001564 -0.020821 +v 0.028660 -0.001710 -0.019249 +v 0.027223 -0.001631 -0.021568 +v 0.027862 -0.001706 -0.017043 +v 0.024188 -0.001638 -0.016526 +v 0.022777 -0.001711 -0.018714 +v 0.022795 -0.017418 -0.017845 +v 0.024500 -0.017415 -0.016171 +v 0.025790 -0.001993 -0.015963 +v 0.026741 -0.017415 -0.016105 +v 0.028321 -0.017411 -0.017392 +v 0.028794 -0.017412 -0.019872 +v 0.026967 -0.017416 -0.021912 +v 0.025455 -0.001991 -0.022150 +v 0.024718 -0.017415 -0.022004 +v 0.022894 -0.017415 -0.020470 +v 0.021596 -0.017582 -0.016096 +v 0.025125 -0.017564 -0.013963 +v 0.028737 -0.017574 -0.015053 +v 0.020728 -0.017559 -0.018943 +v 0.030353 -0.017585 -0.017201 +v 0.030626 -0.017573 -0.020243 +v 0.021229 -0.017579 -0.021321 +v 0.023801 -0.017572 -0.023769 +v 0.028145 -0.017571 -0.023550 +v 0.027304 -0.018500 -0.021453 +v 0.028587 -0.018500 -0.018867 +v 0.024423 -0.018500 -0.021636 +v 0.022825 -0.018500 -0.019232 +v 0.024108 -0.018500 -0.016646 +v 0.026989 -0.018500 -0.016463 +v 0.024930 -0.023500 0.021838 +v 0.025695 -0.023381 0.024095 +v 0.022766 -0.023390 0.023147 +v 0.020663 -0.023401 0.018527 +v 0.021942 -0.023399 0.015767 +v 0.023686 -0.023500 0.016996 +v 0.030192 -0.023396 0.021342 +v 0.028294 -0.023420 0.023328 +v 0.027726 -0.023500 0.021120 +v 0.026950 -0.023373 0.014208 +v 0.029412 -0.023417 0.015636 +v 0.026482 -0.023500 0.016277 +v 0.028502 -0.023500 0.018339 +v 0.024251 -0.023413 0.014242 +v 0.022910 -0.023500 0.019776 +v 0.021203 -0.023391 0.021198 +v 0.030700 -0.023372 0.018442 +v 0.027845 -0.001499 0.020459 +v 0.027949 -0.001479 0.017482 +v 0.025986 -0.001566 0.021921 +v 0.024501 -0.001630 0.016448 +v 0.023077 -0.001479 0.019835 +v 0.028400 -0.017416 0.020613 +v 0.028766 -0.017415 0.018439 +v 0.028403 -0.001996 0.020678 +v 0.028503 -0.001993 0.017750 +v 0.027735 -0.017417 0.016714 +v 0.026550 -0.001994 0.016087 +v 0.025946 -0.017416 0.015957 +v 0.024186 -0.017408 0.016374 +v 0.022724 -0.002012 0.018005 +v 0.022769 -0.017417 0.017917 +v 0.022806 -0.017418 0.020181 +v 0.023430 -0.001987 0.021215 +v 0.024178 -0.017411 0.021771 +v 0.026546 -0.017415 0.022092 +v 0.028919 -0.017562 0.015072 +v 0.025488 -0.017594 0.014055 +v 0.030119 -0.017573 0.021404 +v 0.030723 -0.017574 0.018589 +v 0.028016 -0.017564 0.023538 +v 0.024145 -0.017577 0.023933 +v 0.022853 -0.017564 0.014902 +v 0.020721 -0.017572 0.018036 +v 0.021338 -0.017573 0.021524 +v 0.022910 -0.018500 0.019776 +v 0.023686 -0.018500 0.016996 +v 0.024930 -0.018500 0.021838 +v 0.027726 -0.018500 0.021120 +v 0.028502 -0.018500 0.018339 +v 0.026482 -0.018500 0.016277 +v 0.034103 -0.018500 0.004910 +v 0.036500 -0.018500 0.006512 +v 0.035018 -0.018500 0.007063 +v 0.032354 -0.018500 0.002115 +v 0.032156 -0.018500 0.005310 +v 0.032323 -0.018500 -0.002350 +v 0.031607 -0.018500 0.003683 +v 0.037181 -0.018500 0.008263 +v 0.034536 -0.018500 0.009563 +v 0.034319 -0.018500 0.008343 +v 0.033913 -0.018500 0.004727 +v 0.031244 -0.018500 0.007175 +v 0.029293 -0.018500 0.004008 +v 0.030415 -0.018500 0.004737 +v 0.033620 -0.018500 0.006644 +v 0.033287 -0.018500 0.007774 +v 0.031553 -0.018500 0.007445 +v 0.030599 -0.018500 0.001437 +v 0.031594 -0.018500 -0.004640 +v 0.042176 -0.018500 0.008084 +v 0.039944 -0.018500 0.006910 +v 0.043366 -0.018500 0.005464 +v 0.041662 -0.018500 -0.006588 +v 0.044674 -0.018500 -0.007284 +v 0.045618 -0.018500 -0.002493 +v 0.047778 -0.018500 -0.002735 +v 0.047260 -0.018500 0.003857 +v 0.045631 -0.018500 0.002213 +v 0.035972 -0.018500 -0.006393 +v 0.035669 -0.018500 -0.008344 +v 0.040307 -0.018500 -0.008983 +v 0.034094 -0.017500 0.004914 +v 0.033384 -0.017500 0.006828 +v 0.034556 -0.017500 0.006660 +v 0.030677 -0.017500 0.001521 +v 0.029283 -0.017500 0.004118 +v 0.031223 -0.017500 0.003676 +v 0.030498 -0.017500 0.004779 +v 0.031551 -0.017500 0.007494 +v 0.034645 -0.017500 0.009558 +v 0.033652 -0.017500 0.008260 +v 0.033565 -0.017500 0.004502 +v 0.032350 -0.017500 0.004601 +v 0.031293 -0.017500 0.007175 +v 0.031408 -0.017500 0.005526 +v 0.037838 -0.017500 0.007019 +v 0.035017 -0.017500 0.007747 +v 0.037186 -0.017500 0.008273 +v 0.031197 -0.017500 -0.004006 +v 0.031982 -0.017500 -0.000196 +v 0.042621 -0.017500 0.007950 +v 0.033257 -0.017500 -0.003951 +v 0.036500 -0.017500 -0.008813 +v 0.036761 -0.017500 -0.006710 +v 0.045935 -0.017500 -0.000415 +v 0.048127 -0.017500 -0.000150 +v 0.044791 -0.017500 -0.003955 +v 0.046343 -0.017500 -0.005651 +v 0.041467 -0.017500 -0.006538 +v 0.042292 -0.017500 -0.008511 +v 0.042219 -0.017500 0.006163 +v 0.045133 -0.017500 0.003466 +v 0.046619 -0.017500 0.004574 +v 0.396697 0.023665 0.003755 +v 0.051997 0.023782 0.002921 +v 0.051997 0.019770 0.013775 +v 0.396697 0.020093 0.013056 +v 0.396697 0.014458 0.018991 +v 0.051997 0.010880 0.021351 +v 0.396697 0.007002 0.022918 +v 0.051997 0.002789 0.023706 +v 0.396697 -0.004655 0.023644 +v 0.051997 -0.006988 0.023062 +v 0.396697 -0.015081 0.018622 +v 0.051997 -0.018145 0.015855 +v 0.396697 -0.022201 0.009364 +v 0.051997 -0.022857 0.006866 +v 0.051997 -0.023927 -0.001247 +v 0.396697 -0.023863 -0.000292 +v 0.396697 -0.022368 -0.008585 +v 0.051997 -0.021921 -0.009432 +v 0.051997 -0.016475 -0.017577 +v 0.396697 -0.016940 -0.016940 +v 0.396697 -0.010195 -0.021574 +v 0.051997 -0.004655 -0.023636 +v 0.396697 -0.002085 -0.023865 +v 0.051997 0.005486 -0.023222 +v 0.396697 0.006060 -0.023079 +v 0.051997 0.013047 -0.020092 +v 0.396697 0.013745 -0.019621 +v 0.051997 0.020093 -0.013048 +v 0.396697 0.020539 -0.012334 +v 0.051997 0.023280 -0.005247 +v 0.396697 0.023403 -0.004668 +v 0.415846 0.006277 -0.031859 +v 0.418454 0.002430 -0.035591 +v 0.416094 -0.002123 -0.032817 +v 0.417360 0.010399 -0.032601 +v 0.420666 0.010397 -0.037513 +v 0.418387 -0.003922 -0.035446 +v 0.406653 0.010399 -0.024914 +v 0.403758 0.006809 -0.025732 +v 0.397488 0.010567 -0.024286 +v 0.419163 -0.010398 -0.035448 +v 0.415541 -0.010399 -0.030407 +v 0.413826 -0.006359 -0.030019 +v 0.409237 -0.010400 -0.025867 +v 0.413097 -0.001457 -0.030127 +v 0.409788 -0.006770 -0.027474 +v 0.406020 -0.005188 -0.026525 +v 0.413109 0.005011 -0.029799 +v 0.408508 -0.000643 -0.027738 +v 0.403280 -0.005231 -0.026158 +v 0.400297 -0.010402 -0.024196 +v 0.403693 0.001664 -0.026562 +v 0.408882 0.005545 -0.027346 +v 0.413511 0.010399 -0.028544 +v 0.421271 -0.010398 -0.037988 +v 0.428220 -0.010399 -0.041760 +v 0.428146 0.010399 -0.041691 +v 0.439297 0.010400 -0.042305 +v 0.437846 -0.010400 -0.042397 +v 0.448362 -0.010400 -0.038373 +v 0.448539 0.010400 -0.037923 +v 0.455652 0.010400 -0.029280 +v 0.456609 -0.010400 -0.026724 +v 0.457188 0.010400 -0.016108 +v 0.456762 -0.010400 -0.014501 +v 0.451293 0.010400 -0.004186 +v 0.451184 -0.010400 -0.004159 +v 0.437926 -0.010400 -0.037395 +v 0.443779 -0.010400 -0.035019 +v 0.448623 -0.010400 -0.030971 +v 0.451739 -0.010400 -0.024469 +v 0.429833 -0.010400 -0.036910 +v 0.417163 -0.010400 -0.019094 +v 0.410133 -0.010464 -0.014126 +v 0.423373 -0.010400 -0.006351 +v 0.413822 -0.010471 -0.006939 +v 0.418663 -0.010400 -0.012962 +v 0.452231 -0.010400 -0.017275 +v 0.419793 -0.010501 0.000064 +v 0.424214 -0.010400 -0.034043 +v 0.437018 -0.010400 -0.002526 +v 0.428803 -0.010474 0.009421 +v 0.448624 -0.010400 -0.009021 +v 0.443010 -0.010400 -0.004494 +v 0.430722 -0.010400 -0.002904 +v 0.428566 -0.010436 0.004706 +v 0.418861 -0.010400 -0.027940 +v 0.397869 -0.011584 -0.022407 +v 0.396953 -0.020502 -0.016973 +v 0.394172 -0.011850 -0.023818 +v 0.402533 -0.011422 -0.019505 +v 0.405920 -0.011669 -0.016006 +v 0.401296 -0.024773 -0.009725 +v 0.409061 -0.011400 -0.012125 +v 0.404833 -0.026615 -0.000927 +v 0.417210 0.010400 -0.016627 +v 0.407440 0.010479 -0.017695 +v 0.441163 0.010400 -0.003515 +v 0.428824 0.010469 0.009409 +v 0.431291 0.010400 -0.002570 +v 0.418368 0.010400 -0.026450 +v 0.430081 0.010400 -0.036977 +v 0.422948 0.010400 -0.033158 +v 0.447752 0.010400 -0.032255 +v 0.438195 0.010400 -0.037340 +v 0.452026 0.010400 -0.023429 +v 0.448449 0.010400 -0.008809 +v 0.451995 0.010400 -0.016309 +v 0.422545 0.010400 -0.007207 +v 0.419433 0.010516 -0.000221 +v 0.428527 0.010433 0.004391 +v 0.413754 0.010462 -0.007103 +v 0.404028 0.026433 -0.002612 +v 0.412869 0.011557 -0.004675 +v 0.401039 0.024557 -0.010243 +v 0.408519 0.011421 -0.012976 +v 0.402951 0.011462 -0.019172 +v 0.395639 0.018995 -0.018780 +v 0.394831 0.011818 -0.023690 +v 0.353698 -0.025855 0.006543 +v 0.353655 -0.026118 -0.005682 +v 0.419627 0.023660 0.011948 +v 0.418257 0.024527 0.010066 +v 0.353684 0.025172 0.008587 +v 0.419584 0.022331 0.014301 +v 0.353808 0.020421 0.017266 +v 0.412336 0.018674 0.018926 +v 0.353719 0.011958 0.023776 +v 0.402201 0.010161 0.024781 +v 0.353686 0.002519 0.026546 +v 0.399009 -0.000947 0.026623 +v 0.353725 -0.008363 0.025345 +v 0.402308 -0.009894 0.024719 +v 0.353728 -0.016143 0.021098 +v 0.410820 -0.017834 0.019805 +v 0.353717 -0.021955 0.015041 +v 0.419132 -0.021957 0.014853 +v 0.419800 -0.023468 0.012340 +v 0.418277 -0.024533 0.010052 +v 0.411189 -0.025874 0.005893 +v 0.353733 -0.021390 -0.015838 +v 0.353664 -0.015045 -0.021907 +v 0.353855 -0.006806 -0.025898 +v 0.398081 -0.010514 -0.024322 +v 0.353719 0.003904 -0.026320 +v 0.353638 0.014483 -0.022450 +v 0.353675 0.023487 -0.012784 +v 0.353692 0.026645 -0.001062 +v 0.409884 0.026131 0.004991 +v 0.425410 0.011783 0.005191 +v 0.421309 0.011582 0.003018 +v 0.417394 0.011546 0.000145 +v 0.412356 -0.011414 -0.005763 +v 0.415288 -0.011687 -0.001669 +v 0.420413 -0.011571 0.002518 +v 0.425372 -0.011718 0.005141 +v 0.351756 -0.025459 -0.000760 +v 0.351756 -0.023792 -0.009089 +v 0.351754 -0.018160 -0.018064 +v 0.351756 -0.009161 -0.023762 +v 0.351755 0.000213 -0.025532 +v 0.351754 0.012560 -0.022433 +v 0.351755 0.021675 -0.013499 +v 0.351755 0.025293 -0.003515 +v 0.351756 0.024744 0.006044 +v 0.351754 0.020281 0.015654 +v 0.351755 0.011164 0.022972 +v 0.351756 0.001901 0.025404 +v 0.351755 -0.008617 0.024130 +v 0.351755 -0.018394 0.017718 +v 0.351755 -0.024009 0.008706 +v 0.417195 -0.021000 -0.019129 +v 0.418749 -0.021000 -0.012648 +v 0.422388 -0.021000 -0.007535 +v 0.428930 -0.021000 -0.003249 +v 0.437595 -0.021000 -0.002614 +v 0.445387 -0.021000 -0.005829 +v 0.450931 -0.021000 -0.012927 +v 0.452312 -0.021000 -0.019704 +v 0.451259 -0.021000 -0.026218 +v 0.447354 -0.021000 -0.032273 +v 0.441400 -0.021000 -0.036333 +v 0.432479 -0.021000 -0.037580 +v 0.422945 -0.021000 -0.033268 +v 0.418079 -0.021000 -0.025658 +v 0.452274 0.021000 -0.017577 +v 0.448789 0.021000 -0.009239 +v 0.441670 0.021000 -0.003722 +v 0.432758 0.021000 -0.002427 +v 0.425911 0.021000 -0.004826 +v 0.420505 0.021000 -0.009529 +v 0.417616 0.021000 -0.016182 +v 0.417394 0.021000 -0.023344 +v 0.420313 0.021000 -0.029984 +v 0.425419 0.021000 -0.035012 +v 0.433140 0.021000 -0.037535 +v 0.441163 0.021000 -0.036477 +v 0.448449 0.021000 -0.031184 +v 0.451677 0.021000 -0.024687 +v 0.426425 0.011278 0.005497 +v 0.426708 0.011936 0.008061 +v 0.425767 0.012445 0.010350 +v 0.424033 0.013147 0.012154 +v 0.425961 -0.012409 0.009954 +v 0.424276 -0.012959 0.012015 +v 0.426848 -0.011746 0.007921 +v 0.426201 -0.011871 0.006253 +v 0.427339 0.011013 0.010201 +v 0.427718 0.010807 0.006188 +v 0.426561 -0.011352 0.010706 +v 0.426394 -0.010787 0.004326 +v 0.427849 -0.010941 0.007649 +v 0.434518 0.009812 0.015265 +v 0.435020 0.007043 0.018223 +v 0.438764 0.009583 0.013078 +v 0.441150 0.006742 0.014989 +v 0.423344 -0.007737 0.024110 +v 0.423508 -0.009724 0.021724 +v 0.429103 -0.007437 0.020897 +v 0.427665 -0.009664 0.019392 +v 0.440561 -0.007747 0.014166 +v 0.435380 -0.008563 0.005624 +v 0.435495 0.008112 0.005558 +v 0.432744 0.009858 0.012030 +v 0.434012 0.009870 0.006415 +v 0.425485 0.009820 0.016222 +v 0.420291 0.009957 0.014336 +v 0.426738 0.009964 0.019582 +v 0.423282 0.009560 0.022043 +v 0.423751 0.006742 0.025034 +v 0.418360 -0.007903 0.015451 +v 0.418531 0.008570 0.015352 +v 0.425155 -0.009930 0.016412 +v 0.419752 -0.009827 0.014648 +v 0.432771 -0.009865 0.012015 +v 0.433616 -0.009957 0.006643 +v 0.434434 -0.009773 0.015359 +v 0.438329 -0.009742 0.013146 +v 0.425664 -0.008666 0.011234 +v 0.426120 0.005833 0.010971 +v 0.428475 -0.006992 0.009611 +v 0.426299 -0.005692 0.010868 +v 0.427834 0.008988 0.009981 +v 0.425717 0.008739 0.011204 +v 0.427769 -0.009036 0.010019 +v 0.428431 0.006762 0.009637 +v 0.434681 -0.007824 0.017489 +v 0.429678 0.006756 0.021597 +v 0.428467 0.008934 0.019773 +v 0.430554 -0.008296 0.013295 +v 0.428457 -0.009187 0.014506 +v 0.431881 -0.008472 0.012529 +v 0.431681 -0.005859 0.012644 +v 0.429790 -0.005872 0.013736 +v 0.429016 -0.004119 0.014183 +v 0.427556 -0.006690 0.015026 +v 0.426234 -0.008690 0.015789 +v 0.426473 -0.005868 0.015651 +v 0.430714 -0.004528 0.020113 +v 0.432900 -0.004335 0.018866 +v 0.434564 -0.005899 0.017779 +v 0.428175 0.006078 0.014669 +v 0.429281 0.004155 0.014030 +v 0.429742 0.005874 0.013764 +v 0.431673 0.005880 0.012649 +v 0.430588 0.007408 0.013276 +v 0.429790 0.009128 0.013735 +v 0.427556 0.008310 0.015026 +v 0.431872 0.008421 0.012535 +v 0.426294 0.007266 0.015754 +v 0.427213 0.004980 0.015224 +v 0.430436 0.005023 0.021044 +v 0.433630 0.004292 0.019141 +v 0.432293 -0.009443 0.015623 +v 0.432887 -0.007077 0.015283 +v 0.431653 -0.008308 0.016125 +v 0.429484 -0.006692 0.017377 +v 0.428195 -0.008228 0.018001 +v 0.430541 -0.010207 0.016709 +v 0.429101 -0.009699 0.017470 +v 0.428342 -0.006402 0.017911 +v 0.429395 -0.005044 0.017314 +v 0.431102 -0.006195 0.016443 +v 0.431661 -0.004989 0.016013 +v 0.424188 -0.007068 0.007722 +v 0.425963 -0.006453 0.006872 +v 0.425996 -0.007638 0.006687 +v 0.424858 -0.008596 0.007329 +v 0.424627 -0.008873 0.008047 +v 0.427652 -0.007731 0.014876 +v 0.423970 -0.007418 0.008428 +v 0.428213 -0.006101 0.014542 +v 0.424943 -0.005917 0.007853 +v 0.429734 -0.006127 0.013671 +v 0.430464 -0.007678 0.013244 +v 0.426622 -0.007905 0.006892 +v 0.425879 -0.008888 0.007339 +v 0.429256 -0.009122 0.013941 +v 0.428227 -0.008788 0.014561 +v 0.427692 -0.009720 0.015043 +v 0.426799 -0.008162 0.015543 +v 0.431083 -0.005924 0.013083 +v 0.429086 -0.004660 0.014216 +v 0.427032 -0.006078 0.015414 +v 0.431445 -0.008099 0.012860 +v 0.430438 -0.009797 0.013463 +v 0.429042 -0.010218 0.014246 +v 0.430798 -0.007952 0.014309 +v 0.430102 -0.006195 0.014711 +v 0.429035 -0.008805 0.015327 +v 0.428339 -0.007048 0.015729 +v 0.428274 0.008394 0.017967 +v 0.428338 0.006209 0.017902 +v 0.429471 0.008285 0.017384 +v 0.429450 0.010016 0.017275 +v 0.430082 0.004771 0.016929 +v 0.431640 0.005085 0.015980 +v 0.430528 0.006010 0.016774 +v 0.432611 0.006180 0.015462 +v 0.432816 0.008453 0.015342 +v 0.431706 0.008205 0.016094 +v 0.431360 0.010081 0.016173 +v 0.425623 0.006629 0.006903 +v 0.424486 0.006684 0.007558 +v 0.423997 0.007933 0.008009 +v 0.425725 0.008339 0.006818 +v 0.427598 0.007586 0.014766 +v 0.425017 0.009100 0.007806 +v 0.427860 0.008480 0.014771 +v 0.428933 0.009119 0.014142 +v 0.429997 0.008614 0.013519 +v 0.426529 0.008200 0.006948 +v 0.430415 0.007469 0.013271 +v 0.426246 0.006271 0.007100 +v 0.429585 0.005958 0.013748 +v 0.424404 0.006288 0.008176 +v 0.427954 0.006435 0.014707 +v 0.427030 0.008814 0.015417 +v 0.428050 0.009958 0.014821 +v 0.426754 0.006972 0.015589 +v 0.431506 0.007929 0.012837 +v 0.430975 0.005813 0.013132 +v 0.429194 0.004681 0.014156 +v 0.430060 0.010095 0.013665 +v 0.427537 0.005465 0.015121 +v 0.430805 0.007074 0.014305 +v 0.428631 0.006476 0.015560 +v 0.429269 0.008950 0.015192 +v 0.092815 0.047249 0.010440 +v 0.093696 0.047597 0.009490 +v 0.093738 0.047373 0.010291 +v 0.090727 0.047564 0.008672 +v 0.091074 0.047523 0.008926 +v 0.091504 0.047212 0.010158 +v 0.092481 0.047093 0.010884 +v 0.093913 0.047911 0.008447 +v 0.093266 0.047907 0.008258 +v 0.091634 0.047070 0.010702 +v 0.093445 0.048023 0.007905 +v 0.091955 0.047871 0.007976 +v 0.091405 0.047871 0.007801 +v 0.090766 0.047255 0.009775 +v 0.092507 0.048044 0.007538 +v 0.094100 0.038801 0.007937 +v 0.094605 0.039064 0.007168 +v 0.094602 0.039261 0.006472 +v 0.094088 0.039438 0.005685 +v 0.093195 0.039456 0.005343 +v 0.092490 0.039357 0.005469 +v 0.091656 0.038981 0.006533 +v 0.091814 0.038737 0.007445 +v 0.092294 0.038630 0.007974 +v 0.093211 0.038634 0.008247 +v 0.094595 0.039132 0.007780 +v 0.094021 0.045592 0.009610 +v 0.094811 0.039290 0.007289 +v 0.094237 0.045750 0.009119 +v 0.094806 0.039517 0.006486 +v 0.094232 0.045977 0.008316 +v 0.094416 0.039686 0.005768 +v 0.093842 0.046146 0.007599 +v 0.094214 0.039722 0.005578 +v 0.093461 0.039756 0.005220 +v 0.092887 0.046216 0.007050 +v 0.093183 0.039742 0.005182 +v 0.092631 0.039678 0.005237 +v 0.092057 0.046137 0.007068 +v 0.092370 0.039629 0.005328 +v 0.091796 0.046088 0.007159 +v 0.092129 0.039570 0.005459 +v 0.091554 0.046030 0.007289 +v 0.091473 0.039275 0.006296 +v 0.090899 0.045735 0.008126 +v 0.091407 0.039195 0.006557 +v 0.091386 0.039117 0.006825 +v 0.090812 0.045577 0.008656 +v 0.091589 0.038913 0.007608 +v 0.091015 0.045373 0.009438 +v 0.091166 0.045321 0.009669 +v 0.092144 0.038790 0.008219 +v 0.091570 0.045249 0.010049 +v 0.092648 0.038767 0.008459 +v 0.092074 0.045226 0.010289 +v 0.093202 0.038794 0.008534 +v 0.093747 0.038871 0.008436 +v 0.093173 0.045330 0.010266 +v 0.094228 0.038987 0.008176 +v 0.094449 0.045141 0.011335 +v 0.095269 0.045436 0.010552 +v 0.090448 0.044853 0.011095 +v 0.090162 0.044903 0.010831 +v 0.093008 0.044866 0.011853 +v 0.092228 0.044797 0.011850 +v 0.095821 0.045877 0.009167 +v 0.095762 0.046191 0.008040 +v 0.089306 0.045623 0.008022 +v 0.089297 0.045303 0.009149 +v 0.094796 0.046568 0.006407 +v 0.093445 0.046665 0.005642 +v 0.090201 0.046163 0.006394 +v 0.090811 0.046347 0.005939 +v 0.091518 0.046495 0.005637 +v 0.094904 0.045663 0.011045 +v 0.094490 0.045529 0.011389 +v 0.092146 0.045162 0.011948 +v 0.091873 0.045151 0.011901 +v 0.090394 0.045224 0.011181 +v 0.089681 0.045395 0.010355 +v 0.089284 0.045643 0.009355 +v 0.089294 0.046019 0.008030 +v 0.090225 0.046551 0.006445 +v 0.091389 0.046846 0.005771 +v 0.091653 0.046890 0.005696 +v 0.093293 0.047031 0.005713 +v 0.094742 0.046939 0.006492 +v 0.095277 0.046811 0.007113 +v 0.095717 0.046571 0.008097 +v 0.095801 0.046278 0.009158 +v 0.095705 0.046121 0.009681 +v 0.095250 0.045809 0.010638 +v 0.091880 0.045421 0.011832 +v 0.090121 0.046693 0.006791 +v 0.090304 0.046760 0.006611 +v 0.091164 0.047676 0.007340 +v 0.091719 0.047428 0.006329 +v 0.091950 0.047461 0.006284 +v 0.093061 0.047687 0.006577 +v 0.093867 0.047659 0.006930 +v 0.094820 0.047360 0.007541 +v 0.094353 0.047727 0.008161 +v 0.095044 0.047265 0.007947 +v 0.094434 0.047688 0.008323 +v 0.095186 0.046770 0.009738 +v 0.094489 0.047248 0.009893 +v 0.095116 0.046702 0.009954 +v 0.094130 0.047043 0.010505 +v 0.093875 0.046948 0.010758 +v 0.092559 0.046464 0.011424 +v 0.092142 0.045431 0.011877 +v 0.091928 0.046188 0.011511 +v 0.091714 0.046185 0.011456 +v 0.090033 0.046149 0.010314 +v 0.089921 0.046196 0.010110 +v 0.089702 0.046683 0.008325 +v 0.089762 0.046750 0.008106 +v 0.092879 0.046525 0.010235 +v 0.093761 0.046873 0.009285 +v 0.091568 0.046488 0.009953 +v 0.091138 0.046799 0.008721 +v 0.092019 0.047147 0.007771 +v 0.093330 0.047184 0.008053 +v 0.352455 -0.024903 -0.000390 +v 0.353457 -0.023815 -0.000363 +v 0.353457 -0.023902 -0.000363 +v 0.319029 -0.027256 -0.001127 +v 0.257186 -0.034199 -0.001244 +v 0.259242 -0.033975 -0.001333 +v 0.277621 -0.031854 -0.001589 +v 0.289016 -0.030540 -0.001748 +v 0.288454 -0.030605 -0.001740 +v 0.198555 -0.040224 0.001039 +v 0.225092 -0.037698 0.000135 +v 0.187790 -0.041217 0.001090 +v 0.177024 -0.042209 0.001141 +v 0.172794 -0.042609 0.001010 +v 0.163052 -0.042435 0.000695 +v 0.163579 -0.043480 0.000724 +v 0.155247 -0.044371 0.000013 +v 0.152217 -0.044695 -0.000245 +v 0.117685 -0.047685 -0.003615 +v 0.109314 -0.047616 -0.003326 +v 0.109122 -0.046520 -0.003311 +v 0.109020 -0.047603 -0.003288 +v 0.107831 -0.047550 -0.003131 +v 0.101656 -0.046179 -0.002301 +v 0.127581 -0.047315 -0.003349 +v 0.132062 -0.045881 -0.003039 +v 0.135992 -0.046574 -0.002589 +v 0.137322 -0.046457 -0.002469 +v 0.101927 -0.047291 -0.002352 +v 0.100976 -0.047212 -0.002134 +v 0.093923 -0.046626 -0.000516 +v 0.050792 -0.040055 0.007288 +v 0.051124 -0.039006 0.007211 +v -0.026544 0.035661 0.013517 +v -0.026559 0.034603 0.013529 +v -0.011081 0.034178 0.001114 +v 0.002113 0.034104 -0.003233 +v 0.002917 0.035181 -0.003308 +v -0.011184 0.035244 0.001180 +v -0.008881 0.034140 -0.000164 +v -0.008449 0.034135 -0.000344 +v -0.007098 0.035183 -0.001025 +v -0.004577 0.034094 -0.001957 +v -0.005324 0.035171 -0.001607 +v -0.001917 0.034092 -0.002534 +v -0.002781 0.035155 -0.002442 +v -0.000667 0.034092 -0.002806 +v 0.014029 0.034385 -0.003377 +v 0.009917 0.034257 -0.003521 +v 0.011826 0.035380 -0.003492 +v 0.008315 0.034208 -0.003577 +v 0.009921 0.035328 -0.003525 +v 0.011091 0.035352 -0.003561 +v 0.015910 0.034461 -0.003146 +v 0.016450 0.035552 -0.003061 +v 0.020604 0.034694 -0.002056 +v 0.020993 0.035777 -0.001925 +v 0.024901 0.034961 -0.000206 +v 0.025421 0.036052 0.000074 +v 0.036450 0.036356 0.006531 +v 0.036380 0.037396 0.006499 +v 0.039824 0.036943 0.007769 +v 0.039946 0.038029 0.007801 +v 0.042880 0.037489 0.008236 +v 0.043559 0.038689 0.008257 +v 0.047318 0.038298 0.007968 +v 0.057786 0.041342 0.005577 +v 0.060280 0.041780 0.005158 +v 0.048143 0.039540 0.007833 +v 0.067152 0.042987 0.004002 +v 0.088824 0.046098 0.000697 +v 0.079657 0.044911 0.002473 +v 0.076883 0.044484 0.002812 +v 0.107834 0.046453 -0.003111 +v 0.099971 0.047145 -0.001963 +v 0.101695 0.046182 -0.002308 +v 0.099574 0.047108 -0.001868 +v 0.118817 0.046583 -0.003609 +v 0.107544 0.047541 -0.003167 +v 0.107823 0.047546 -0.003182 +v 0.109720 0.046537 -0.003357 +v 0.111006 0.047603 -0.003357 +v 0.115397 0.047681 -0.003599 +v 0.127959 0.046201 -0.003328 +v 0.161200 0.042618 0.000583 +v 0.159130 0.043934 0.000352 +v 0.162634 0.042482 0.000637 +v 0.318032 0.026263 -0.001155 +v 0.300198 0.029292 -0.001531 +v 0.302521 0.027916 -0.001598 +v 0.290138 0.030393 -0.001745 +v 0.352474 0.024884 -0.000389 +v 0.353457 0.023815 -0.000363 +v 0.353457 0.023902 -0.000363 +v 0.082735 -0.036006 0.023680 +v 0.082438 -0.038247 0.021093 +v 0.080645 -0.040822 0.017285 +v 0.072894 -0.042327 0.013190 +v 0.076944 -0.042246 0.014193 +v 0.080223 -0.041117 0.016755 +v 0.082652 -0.025507 0.030212 +v 0.082656 -0.025901 0.030068 +v 0.082678 -0.028528 0.028979 +v 0.082700 -0.031149 0.027538 +v 0.082728 -0.035032 0.024454 +v 0.049601 -0.017126 0.028319 +v 0.044253 -0.016877 0.028439 +v 0.040704 -0.016711 0.028518 +v 0.033701 -0.015935 0.029208 +v 0.028513 -0.014867 0.030205 +v 0.023496 -0.013239 0.031269 +v 0.020583 -0.011591 0.031917 +v 0.018721 -0.009891 0.032746 +v 0.018268 -0.009478 0.032948 +v 0.016408 -0.006657 0.034292 +v 0.015426 -0.003900 0.035227 +v 0.015280 -0.002816 0.035385 +v 0.015000 -0.000727 0.035688 +v 0.014986 -0.000000 0.035704 +v 0.082235 -0.023369 0.030785 +v 0.081374 -0.022100 0.030934 +v 0.081062 -0.021640 0.030988 +v 0.078968 -0.020163 0.030907 +v 0.075865 -0.019000 0.030581 +v 0.073653 -0.018582 0.030307 +v 0.070381 -0.017964 0.029903 +v 0.059358 -0.017331 0.028818 +v 0.053777 -0.017214 0.028533 +v 0.353457 -0.018679 0.014411 +v 0.353457 0.002335 0.023337 +v 0.353457 0.009943 0.021278 +v 0.353457 0.016289 0.017004 +v 0.353457 0.016228 0.017067 +v 0.353457 0.014659 0.018119 +v 0.353457 0.018103 0.015111 +v 0.353457 0.022229 0.008183 +v 0.353457 0.023786 0.000809 +v 0.353457 -0.022491 0.007467 +v 0.353457 -0.007197 0.022098 +v 0.353457 -0.012890 0.019663 +v 0.353457 -0.005584 0.022788 +v 0.059114 -0.041003 0.012791 +v 0.073631 -0.018339 0.030315 +v 0.091951 -0.015850 0.033628 +v 0.157142 -0.033295 0.039873 +v 0.157003 -0.035768 0.036591 +v 0.166463 -0.035823 0.036248 +v 0.188636 -0.037846 0.028339 +v 0.214800 -0.034535 0.031659 +v 0.268658 0.016242 0.036173 +v 0.021917 -0.000014 0.031856 +v 0.275441 0.032088 0.006896 +v 0.118368 0.048055 0.000883 +v -0.006751 0.035699 -0.000617 +v 0.000557 0.034184 0.030490 +v 0.007842 0.033816 0.030703 +v 0.011256 0.030226 0.034565 +v 0.011433 0.029968 0.034625 +v 0.014168 0.030682 0.031912 +v 0.057966 -0.040919 0.012593 +v 0.111692 -0.048168 -0.002979 +v 0.268877 -0.033362 -0.000978 +v 0.338164 -0.026032 0.000815 +v 0.351946 -0.025349 0.000647 +v 0.344045 -0.025692 -0.000080 +v 0.351946 -0.025408 0.000106 +v 0.328340 -0.026866 -0.000396 +v 0.277290 -0.032393 -0.001192 +v 0.277681 -0.032348 -0.001191 +v 0.318200 -0.027818 0.000241 +v 0.298116 -0.030016 -0.001122 +v 0.301958 -0.029578 -0.001109 +v 0.272283 -0.032970 -0.001064 +v 0.275554 -0.032075 0.006887 +v 0.249950 -0.035542 -0.000495 +v 0.213330 -0.039348 0.001132 +v 0.241842 -0.036385 -0.000135 +v 0.167715 -0.043582 0.001411 +v 0.186499 -0.041834 0.001679 +v 0.198505 -0.040722 0.001434 +v 0.163304 -0.044030 0.001118 +v 0.141943 -0.046420 -0.001297 +v 0.121430 -0.048105 -0.003069 +v 0.121488 -0.048102 -0.003066 +v 0.131610 -0.047512 -0.002577 +v 0.104182 -0.047912 -0.002235 +v 0.096402 -0.047378 -0.000642 +v 0.099850 -0.047064 0.005077 +v 0.083259 -0.045643 0.005147 +v 0.084444 -0.046068 0.002186 +v 0.056349 -0.040800 0.012314 +v 0.055876 -0.040780 0.012149 +v 0.053474 -0.040709 0.010826 +v 0.053025 -0.040694 0.010463 +v 0.051241 -0.040595 0.008402 +v 0.050875 -0.040558 0.007779 +v 0.079997 -0.043190 0.012768 +v 0.094889 -0.039020 0.021781 +v 0.093470 -0.032194 0.028341 +v 0.092440 -0.021755 0.032914 +v 0.057408 -0.016569 0.028621 +v 0.057191 -0.011607 0.028647 +v 0.018763 -0.000013 0.032899 +v 0.015192 0.015083 0.034867 +v 0.014009 0.021124 0.035429 +v 0.015068 0.021695 0.034289 +v 0.014842 0.027105 0.033572 +v 0.012936 0.027777 0.035132 +v 0.013188 0.032931 0.029551 +v 0.009336 0.032031 0.033884 +v 0.010438 0.031418 0.034288 +v 0.006672 0.033513 0.032908 +v -0.001484 0.034408 0.029683 +v -0.013215 0.035390 0.023543 +v -0.026145 0.036177 0.013863 +v -0.010907 0.035762 0.001614 +v -0.002510 0.035672 -0.001980 +v 0.010467 0.035852 -0.003065 +v 0.021165 0.036315 -0.001313 +v 0.016226 0.036064 -0.002577 +v 0.039734 0.038539 0.008296 +v 0.038892 0.038216 0.013036 +v 0.036165 0.037921 0.006997 +v 0.043515 0.039208 0.008777 +v 0.050633 0.039955 0.012715 +v 0.064382 0.041684 0.012556 +v 0.066146 0.042800 0.009269 +v 0.062710 0.042736 0.005158 +v 0.084382 0.046053 0.002195 +v 0.083253 0.045640 0.005167 +v 0.084021 0.046012 0.002279 +v 0.083342 0.045916 0.002379 +v 0.074894 0.044733 0.003623 +v 0.068928 0.043755 0.004375 +v 0.102690 0.047831 -0.001976 +v 0.118619 0.048172 -0.003099 +v 0.111020 0.048143 -0.002908 +v 0.110352 0.048141 -0.002892 +v 0.136476 0.046430 0.007719 +v 0.140079 0.046621 -0.001533 +v 0.136727 0.047017 -0.002039 +v 0.161381 0.044197 0.001102 +v 0.213891 0.039177 0.005920 +v 0.197548 0.040819 0.001570 +v 0.273228 0.032865 -0.001019 +v 0.318200 0.027818 0.000251 +v 0.288630 0.031087 -0.001237 +v 0.351946 0.024821 0.005087 +v 0.351946 0.025408 0.000116 +v 0.351947 0.023574 0.009128 +v 0.338147 0.025188 0.006324 +v 0.338133 0.023244 0.011648 +v 0.346461 0.022586 0.011689 +v 0.351955 0.019446 0.015885 +v 0.351951 0.021287 0.013521 +v 0.351960 0.017282 0.018146 +v 0.346453 0.019502 0.016319 +v 0.351957 0.018648 0.016909 +v 0.351963 0.015313 0.019929 +v 0.346437 0.010911 0.022950 +v 0.351964 0.011074 0.022520 +v 0.351960 0.005495 0.024352 +v 0.346443 0.005612 0.024717 +v 0.351960 0.006971 0.024082 +v 0.346444 -0.000005 0.025324 +v 0.351958 0.002127 0.024967 +v 0.351960 -0.007360 0.023968 +v 0.346443 -0.005623 0.024715 +v 0.351960 -0.005498 0.024339 +v 0.351958 -0.002550 0.024928 +v 0.346437 -0.010920 0.022946 +v 0.351963 -0.010752 0.022589 +v 0.351957 -0.018816 0.016725 +v 0.346453 -0.019508 0.016311 +v 0.351963 -0.015517 0.019768 +v 0.346437 -0.015596 0.020113 +v 0.351963 -0.015485 0.019798 +v 0.351964 -0.011726 0.022193 +v 0.351947 -0.023606 0.009048 +v 0.346461 -0.022591 0.011679 +v 0.351950 -0.021546 0.013115 +v 0.351955 -0.019449 0.015889 +v 0.351946 -0.024919 0.004618 +v 0.092464 -0.045679 0.008711 +v 0.092464 0.045669 0.008744 +v 0.094311 0.047188 -0.000121 +v 0.318108 -0.025553 0.011599 +v 0.318108 0.025549 0.011610 +v 0.268761 0.032217 0.012423 +v 0.061196 0.038229 0.018994 +v 0.075825 0.035170 0.023784 +v 0.017684 0.031363 0.029585 +v 0.018250 0.027875 0.031242 +v 0.021503 0.028384 0.030285 +v 0.016946 0.033488 0.027269 +v 0.057734 0.021328 0.028597 +v 0.044607 0.024346 0.028115 +v 0.045083 0.028401 0.027171 +v 0.034921 0.030504 0.027299 +v 0.035334 0.033512 0.025285 +v 0.027923 0.034153 0.025787 +v 0.027982 0.035716 0.022929 +v 0.015941 0.031050 0.030520 +v 0.016578 0.027519 0.032175 +v 0.018499 0.022414 0.031890 +v 0.011939 0.034287 0.026587 +v 0.034576 0.026862 0.028508 +v 0.027879 0.031799 0.027944 +v 0.020690 0.033909 0.026364 +v 0.016039 0.034735 0.024400 +v 0.028196 0.036286 0.019503 +v 0.036648 0.037043 0.018964 +v 0.035846 0.035859 0.022371 +v 0.046502 0.035710 0.022178 +v 0.045710 0.032366 0.025221 +v 0.059004 0.031022 0.025866 +v 0.058274 0.025951 0.027857 +v 0.074523 0.026602 0.028833 +v 0.073629 0.018320 0.030315 +v 0.338090 0.018492 0.018702 +v 0.338110 0.020301 0.016518 +v 0.317959 0.012718 0.026883 +v 0.317984 0.019100 0.022876 +v 0.318053 0.023040 0.017332 +v 0.294531 0.026673 0.018728 +v 0.091949 0.015830 0.033629 +v 0.157517 0.022607 0.047743 +v 0.167315 0.019495 0.049105 +v 0.148973 0.029710 0.042720 +v 0.141689 0.025490 0.044327 +v 0.149023 0.025940 0.045297 +v 0.141674 0.021603 0.046100 +v 0.149075 0.022079 0.047194 +v 0.141669 0.014697 0.047838 +v 0.149181 0.015120 0.049116 +v 0.112911 0.024579 0.036662 +v 0.166465 0.035808 0.036273 +v 0.157143 0.033274 0.039898 +v 0.157274 0.030098 0.043043 +v 0.157399 0.026423 0.045730 +v 0.135239 0.029018 0.040639 +v 0.113734 0.035012 0.029816 +v 0.074177 0.023587 0.029671 +v 0.092438 0.021730 0.032919 +v 0.102339 0.021123 0.035174 +v 0.093088 0.028807 0.030388 +v 0.092744 0.025195 0.031943 +v 0.059921 0.035441 0.022559 +v 0.047652 0.037689 0.018752 +v 0.141713 0.029334 0.041875 +v 0.135448 0.035331 0.034817 +v 0.135666 0.039135 0.029154 +v 0.188638 0.037839 0.028361 +v 0.189660 0.023972 0.046098 +v 0.215106 0.024201 0.042946 +v 0.189516 0.027541 0.043881 +v 0.215039 0.027504 0.040735 +v 0.214965 0.030457 0.037953 +v 0.189193 0.033534 0.037803 +v 0.214885 0.032822 0.034845 +v 0.189016 0.035547 0.034484 +v 0.148922 0.033013 0.039668 +v 0.157004 0.035752 0.036616 +v 0.148869 0.035627 0.036465 +v 0.148737 0.039009 0.030453 +v 0.165090 0.042038 0.018466 +v 0.136081 0.043939 0.018371 +v 0.136283 0.045445 0.013030 +v 0.117564 0.047448 0.005896 +v 0.338110 -0.020307 0.016510 +v 0.317984 -0.019110 0.022866 +v 0.338067 -0.011330 0.023806 +v 0.338065 -0.013970 0.022441 +v 0.294418 -0.014533 0.031213 +v 0.241884 -0.028970 0.034059 +v 0.268658 -0.016260 0.036168 +v 0.268640 -0.007790 0.037515 +v 0.189358 -0.030847 0.041012 +v 0.167006 -0.026913 0.045566 +v 0.189659 -0.023999 0.046084 +v 0.214965 -0.030477 0.037931 +v 0.215039 -0.027528 0.040716 +v 0.215106 -0.024226 0.042932 +v 0.215165 -0.020860 0.044482 +v 0.189910 -0.017119 0.048518 +v 0.268640 0.007776 0.037517 +v 0.190352 -0.000008 0.049900 +v 0.190236 -0.007763 0.049615 +v 0.167449 -0.016168 0.049926 +v 0.167314 -0.019521 0.049097 +v 0.177959 -0.023631 0.047109 +v 0.136082 -0.043945 0.018351 +v 0.136283 -0.045449 0.013010 +v 0.115935 -0.044573 0.015502 +v 0.115151 -0.042228 0.020188 +v 0.117567 -0.047451 0.005876 +v 0.136477 -0.046433 0.007699 +v 0.155039 -0.044870 0.000568 +v 0.189191 -0.033552 0.037778 +v 0.166836 -0.030471 0.042789 +v 0.157398 -0.026452 0.045712 +v 0.157516 -0.022636 0.047730 +v 0.149075 -0.022108 0.047182 +v 0.157273 -0.030124 0.043021 +v 0.149023 -0.025969 0.045280 +v 0.141674 -0.021631 0.046089 +v 0.148973 -0.029737 0.042698 +v 0.141689 -0.025519 0.044311 +v 0.190236 0.007748 0.049616 +v 0.167832 -0.007208 0.050904 +v 0.158030 -0.006920 0.050707 +v 0.157732 -0.015642 0.049833 +v 0.149181 -0.015143 0.049112 +v 0.141669 -0.014720 0.047835 +v 0.149336 -0.006659 0.049855 +v 0.167832 0.007194 0.050905 +v 0.215166 0.020835 0.044491 +v 0.141681 -0.006451 0.048432 +v 0.167450 0.016144 0.049931 +v 0.135875 -0.041869 0.023723 +v 0.102611 -0.024794 0.034075 +v 0.124001 -0.032210 0.035005 +v 0.135449 -0.035350 0.034795 +v 0.135667 -0.039146 0.029133 +v 0.102341 -0.021149 0.035168 +v 0.135151 -0.025153 0.042949 +v 0.135240 -0.029046 0.040619 +v 0.141713 -0.029361 0.041854 +v 0.141743 -0.032765 0.038910 +v 0.353457 -0.021061 0.010944 +v 0.353457 -0.022701 0.007119 +v 0.353457 -0.023724 0.002546 +v 0.353457 -0.015211 0.018085 +v 0.353457 -0.018331 0.014951 +v 0.353457 -0.018491 0.014790 +v 0.353457 -0.007579 0.022314 +v 0.353457 -0.011562 0.020568 +v 0.353457 -0.005169 0.022872 +v 0.353457 -0.003171 0.023335 +v 0.353457 0.005955 0.022793 +v 0.353457 0.001417 0.023504 +v 0.353457 0.010336 0.021200 +v 0.353457 0.016289 0.017000 +v 0.353457 0.014242 0.018844 +v 0.353457 0.017602 0.015816 +v 0.353457 0.020256 0.012331 +v 0.353457 0.022121 0.008694 +v 0.353457 0.023262 0.005046 +v 0.353457 0.023680 0.002888 +v 0.100108 -0.046078 -0.001991 +v 0.077904 -0.043599 0.002716 +v 0.058459 -0.041450 0.005607 +v 0.051124 -0.039006 0.007211 +v 0.050797 -0.040038 0.007287 +v 0.067172 -0.041914 0.003999 +v 0.063302 -0.042342 0.004545 +v 0.063087 -0.042303 0.004592 +v 0.059525 -0.040558 0.005271 +v 0.091236 -0.046389 0.000112 +v 0.080468 -0.045070 0.002352 +v 0.083525 -0.045444 0.001716 +v 0.087757 -0.044905 0.000946 +v 0.101422 -0.047233 -0.002233 +v 0.101982 -0.047279 -0.002362 +v 0.108486 -0.046500 -0.003257 +v 0.110361 -0.047639 -0.003402 +v 0.112838 -0.047636 -0.003445 +v 0.116859 -0.046607 -0.003613 +v 0.120787 -0.047627 -0.003584 +v 0.118181 -0.046593 -0.003613 +v 0.131434 -0.047024 -0.003091 +v 0.139526 -0.045097 -0.002142 +v 0.139982 -0.045052 -0.002093 +v 0.145834 -0.045444 -0.001253 +v 0.151427 -0.043678 -0.000345 +v 0.157515 -0.044087 0.000285 +v 0.281863 -0.031360 -0.001640 +v 0.281862 -0.030271 -0.001701 +v 0.279752 -0.030510 -0.001717 +v 0.262052 -0.033652 -0.001414 +v 0.249928 -0.033948 -0.000999 +v 0.157971 -0.044034 0.000345 +v 0.163052 -0.042435 0.000695 +v 0.185216 -0.041453 0.001065 +v 0.194983 -0.040553 0.001073 +v 0.196553 -0.040408 0.001074 +v 0.210643 -0.038008 0.000723 +v 0.223109 -0.037876 0.000174 +v 0.289491 -0.030478 -0.001727 +v 0.290865 -0.030319 -0.001743 +v 0.305702 -0.027566 -0.001520 +v 0.321180 -0.027031 -0.001069 +v 0.353457 -0.023902 -0.000363 +v 0.353457 -0.023815 -0.000363 +v 0.352458 -0.024901 -0.000389 +v 0.353457 0.023815 -0.000363 +v 0.353457 0.023902 -0.000363 +v 0.352448 0.024910 -0.000390 +v 0.171408 0.042737 0.001031 +v 0.162590 0.043594 0.000581 +v 0.157522 0.043028 0.000196 +v 0.157994 0.044041 0.000347 +v 0.157515 0.044097 0.000285 +v 0.129560 0.046050 -0.003169 +v 0.132097 0.046975 -0.003036 +v 0.139149 0.045149 -0.002215 +v 0.143593 0.045710 -0.001529 +v 0.152276 0.043580 -0.000238 +v 0.127959 0.046201 -0.003328 +v 0.111030 0.047663 -0.003443 +v 0.110566 0.046558 -0.003415 +v 0.076707 0.044482 0.002795 +v 0.089412 0.046167 0.000482 +v 0.081523 0.045221 0.002186 +v 0.047762 0.038380 0.007898 +v 0.048229 0.039573 0.007818 +v 0.066806 0.042962 0.004047 +v 0.061795 0.040976 0.004791 +v 0.063064 0.042290 0.004713 +v 0.058448 0.040359 0.005548 +v 0.058441 0.041459 0.005537 +v 0.053997 0.039538 0.006554 +v 0.056383 0.041089 0.005904 +v 0.048640 0.039650 0.007721 +v 0.043469 0.038714 0.008256 +v 0.042880 0.037489 0.008236 +v 0.042407 0.038528 0.008105 +v 0.040946 0.038273 0.007897 +v 0.040176 0.037006 0.007857 +v 0.039572 0.038033 0.007702 +v 0.039208 0.037971 0.007558 +v 0.036450 0.036356 0.006531 +v 0.036163 0.037451 0.006359 +v 0.035759 0.037382 0.006200 +v 0.025781 0.035025 0.000273 +v 0.024750 0.034958 -0.000202 +v 0.023650 0.035988 -0.000835 +v 0.021063 0.034719 -0.001901 +v 0.018827 0.035702 -0.002567 +v 0.016297 0.034481 -0.003053 +v 0.015181 0.034430 -0.003248 +v 0.013605 0.035466 -0.003416 +v 0.008944 0.034223 -0.003585 +v 0.007775 0.035304 -0.003486 +v 0.006066 0.034173 -0.003436 +v 0.006040 0.035256 -0.003506 +v 0.002113 0.034104 -0.003233 +v -0.000168 0.035194 -0.002872 +v 0.001320 0.034098 -0.003146 +v -0.002071 0.034094 -0.002489 +v -0.001261 0.035183 -0.002760 +v -0.003675 0.034092 -0.002178 +v -0.003651 0.035194 -0.002102 +v -0.004127 0.034091 -0.002091 +v -0.006152 0.035204 -0.001413 +v -0.008881 0.034140 -0.000164 +v -0.007357 0.035223 -0.000798 +v -0.010995 0.035278 0.001060 +v -0.010121 0.034161 0.000529 +v -0.011685 0.035296 0.001568 +v -0.017227 0.035434 0.005641 +v -0.026543 0.035709 0.013516 +v -0.026559 0.034603 0.013529 +v -0.110968 0.031561 0.037538 +v -0.112644 0.030981 0.039382 +v -0.114457 0.029571 0.041399 +v -0.115757 0.027496 0.042859 +v -0.115855 0.027109 0.042970 +v -0.116379 0.025041 0.043562 +v -0.117571 0.003752 0.045260 +v -0.117404 -0.010068 0.045022 +v -0.117390 -0.010780 0.044917 +v -0.117827 -0.017839 0.038785 +v -0.117804 -0.019458 0.034419 +v -0.117446 -0.013559 0.043862 +v -0.117612 -0.015678 0.042085 +v -0.117166 -0.020653 0.028713 +v -0.112922 -0.021697 0.016142 +v -0.115532 -0.021365 0.022287 +v -0.097765 0.032925 0.019278 +v -0.107643 0.031561 0.020245 +v -0.110238 0.031561 0.027899 +v -0.117026 0.025041 0.039115 +v -0.117010 0.025041 0.036043 +v -0.116226 0.027902 0.036027 +v -0.116986 0.025041 0.031208 +v -0.115318 0.027902 0.026803 +v -0.112343 0.027902 0.018025 +v -0.113098 0.025041 0.017661 +v -0.115451 0.025041 0.023452 +v -0.108608 0.027604 0.011400 +v -0.108864 0.026590 0.011214 +v -0.112475 0.025041 0.016127 +v -0.107189 0.029827 0.012431 +v -0.105377 0.031176 0.013747 +v -0.110177 0.030437 0.019048 +v -0.112977 0.030437 0.027308 +v -0.113831 0.030437 0.035988 +v -0.113666 0.009350 0.015505 +v -0.118439 -0.006398 0.031062 +v -0.118324 0.009350 0.031074 +v -0.116739 0.009350 0.023067 +v -0.091155 -0.025254 -0.014163 +v -0.091211 -0.025060 -0.014134 +v -0.091561 -0.024376 -0.013794 +v -0.092964 -0.023263 -0.012066 +v -0.095301 -0.022524 -0.008948 +v -0.059695 -0.033784 -0.020588 +v -0.065454 -0.033207 -0.020354 +v -0.079581 -0.031687 -0.017649 +v -0.080717 -0.031425 -0.017337 +v -0.084124 -0.030640 -0.016401 +v -0.086204 -0.030161 -0.015830 +v -0.088207 -0.028726 -0.015178 +v -0.089889 -0.027521 -0.014630 +v -0.030013 -0.035675 -0.013728 +v -0.043475 -0.035092 -0.018601 +v -0.044959 -0.034998 -0.018949 +v -0.092107 0.033045 0.012829 +v -0.084052 0.033470 0.006700 +v -0.073641 0.034210 0.002045 +v -0.063436 0.034977 0.000100 +v -0.052018 0.035727 0.000594 +v -0.043129 0.036137 0.002971 +v -0.042759 0.036144 0.003154 +v -0.038021 0.036238 0.005488 +v -0.034682 0.036305 0.007133 +v 0.033293 -0.037189 -0.007579 +v 0.047710 -0.039445 -0.006297 +v 0.049554 -0.040052 -0.001700 +v 0.044274 -0.038662 -0.009255 +v 0.039674 -0.037877 -0.010365 +v 0.035116 -0.037333 -0.009209 +v -0.013802 -0.034430 -0.003080 +v -0.010756 -0.034169 -0.001666 +v -0.010071 -0.034159 -0.001600 +v 0.353457 -0.003068 -0.023979 +v 0.353457 -0.011332 -0.021309 +v 0.353457 -0.005790 -0.023099 +v 0.353457 -0.018080 -0.015863 +v 0.353457 -0.022537 -0.008059 +v 0.353457 0.022215 -0.008944 +v 0.353457 0.017659 -0.016341 +v 0.353457 0.020396 -0.011897 +v 0.353457 0.012219 -0.020512 +v 0.353457 0.013714 -0.019832 +v 0.353457 0.005647 -0.023498 +v 0.133322 0.032898 -0.053648 +v 0.133355 0.028627 -0.054027 +v 0.345827 0.015818 -0.020580 +v 0.336741 0.016622 -0.020931 +v 0.336730 0.019205 -0.018251 +v 0.133292 -0.035731 -0.052776 +v 0.148895 -0.027978 -0.051783 +v 0.314877 -0.018617 -0.023085 +v 0.230683 -0.020059 -0.039047 +v 0.197344 -0.022789 -0.044467 +v -0.051871 -0.027101 -0.060317 +v -0.051742 -0.028345 -0.058900 +v -0.057618 -0.028482 -0.054338 +v 0.008440 -0.012104 -0.062825 +v 0.037112 -0.027880 -0.058208 +v 0.036820 -0.030582 -0.055185 +v 0.037066 0.028411 -0.057795 +v 0.013989 0.035971 -0.003866 +v 0.019774 0.036237 -0.002808 +v 0.024524 0.036526 -0.000921 +v 0.111716 0.048134 -0.007549 +v 0.083385 -0.045958 0.001292 +v 0.074782 -0.044734 0.002542 +v 0.082460 -0.045702 -0.001117 +v -0.011615 -0.035770 -0.001965 +v -0.080006 -0.031498 -0.018817 +v -0.033408 0.036162 -0.000038 +v -0.026889 0.036202 0.013189 +v -0.082940 -0.025856 -0.025389 +v -0.082423 -0.028789 -0.023517 +v -0.008319 -0.035720 -0.001331 +v 0.000283 -0.035679 -0.003012 +v 0.013158 -0.035941 -0.003453 +v 0.022915 -0.036419 -0.001689 +v 0.020340 -0.036269 -0.002140 +v 0.019063 -0.036201 -0.002507 +v 0.029226 -0.036876 -0.003613 +v 0.026233 -0.036644 -0.002111 +v 0.078699 -0.045095 -0.005832 +v 0.072700 -0.044438 0.002844 +v 0.060904 -0.042436 0.004428 +v 0.049882 -0.040391 0.005057 +v 0.050433 -0.040500 0.006843 +v 0.098938 -0.047586 -0.002264 +v 0.092480 -0.046933 -0.000738 +v 0.084709 -0.046147 0.001099 +v 0.098135 -0.047272 -0.010505 +v 0.116159 -0.048199 -0.004109 +v 0.127169 -0.047844 -0.003872 +v 0.107364 -0.048048 -0.003656 +v 0.172944 -0.043092 0.000497 +v 0.168439 -0.043511 0.000431 +v 0.185294 -0.041945 0.000677 +v 0.251883 -0.035322 -0.001578 +v 0.230893 -0.037552 -0.003932 +v 0.209062 -0.039749 0.000272 +v 0.309875 -0.028701 -0.001918 +v 0.260514 -0.034306 -0.003300 +v 0.280704 -0.031993 -0.002232 +v 0.260498 -0.034327 -0.001773 +v 0.332244 -0.026580 -0.001358 +v 0.336762 -0.026159 -0.001289 +v 0.336358 -0.026191 -0.001255 +v 0.336762 -0.026170 -0.001246 +v 0.351947 -0.025201 -0.003633 +v 0.351947 -0.024440 -0.006836 +v 0.351946 -0.025406 -0.000915 +v 0.351946 -0.025394 -0.001074 +v 0.336756 -0.022650 -0.013508 +v 0.351947 -0.023976 -0.008785 +v 0.351946 -0.018680 -0.017591 +v 0.351946 -0.021817 -0.013394 +v 0.351950 -0.012719 -0.022366 +v 0.351952 -0.014765 -0.021049 +v 0.345829 -0.015360 -0.020935 +v 0.351950 -0.012450 -0.022484 +v 0.336760 -0.012793 -0.023441 +v 0.336782 -0.006418 -0.025817 +v 0.351947 -0.007693 -0.024583 +v 0.336789 0.000294 -0.026582 +v 0.351946 -0.002308 -0.025670 +v 0.336781 0.006984 -0.025673 +v 0.351946 0.002650 -0.025636 +v 0.351947 0.007532 -0.024634 +v 0.336757 0.013350 -0.023151 +v 0.351951 0.012927 -0.022209 +v 0.351950 0.011982 -0.022775 +v 0.351950 0.015483 -0.020400 +v 0.351947 0.017567 -0.018725 +v 0.351946 0.022479 -0.011973 +v 0.345848 0.022177 -0.013159 +v 0.351945 0.020947 -0.014749 +v 0.351946 0.019406 -0.016563 +v 0.351946 0.025407 -0.000896 +v 0.351947 0.024791 -0.005947 +v 0.336774 0.025319 -0.007106 +v 0.289005 0.030252 -0.008578 +v 0.260583 0.033971 -0.008128 +v 0.094280 0.047050 -0.007517 +v 0.094949 0.047187 -0.001257 +v 0.100460 0.047691 -0.002568 +v 0.109025 0.048104 -0.003791 +v 0.078305 0.045279 0.002182 +v 0.080333 0.045543 0.001805 +v 0.075827 0.044913 -0.000319 +v 0.088234 0.046573 0.000339 +v 0.089260 0.046667 0.000095 +v 0.092453 0.046959 -0.000664 +v 0.062879 0.042788 0.004115 +v 0.045509 0.039585 0.007694 +v 0.043761 0.039267 0.007655 +v 0.051508 0.040701 0.006608 +v 0.062864 0.042786 0.004117 +v 0.037876 0.038208 0.006648 +v 0.041300 0.038819 0.007601 +v 0.042347 0.039009 0.007624 +v 0.033045 0.037420 0.004187 +v 0.024576 0.036529 -0.000900 +v 0.033081 0.037254 -0.005237 +v 0.032391 0.037307 0.001415 +v -0.005466 0.035688 -0.002174 +v -0.002234 0.035681 -0.002947 +v -0.000267 0.035677 -0.003417 +v 0.005915 0.035757 -0.003918 +v 0.007431 0.035776 -0.004040 +v -0.014804 0.035852 0.003157 +v -0.010067 0.035748 -0.000056 +v -0.007545 0.035715 -0.001217 +v -0.015920 0.035883 0.004040 +v -0.015110 0.035859 0.003364 +v 0.285500 -0.030333 -0.010345 +v 0.289083 -0.029044 -0.013081 +v 0.265438 -0.033043 -0.010249 +v 0.260670 -0.033103 -0.013671 +v 0.314753 -0.028183 -0.001838 +v 0.078589 0.045076 -0.005850 +v 0.089922 0.031362 -0.057456 +v 0.037317 0.024795 -0.059688 +v 0.008959 0.027356 -0.059462 +v -0.034217 0.030711 -0.056333 +v 0.036529 0.031862 -0.051223 +v 0.036760 0.030970 -0.054405 +v -0.018380 0.024488 -0.064088 +v -0.035097 0.029961 -0.059409 +v -0.038038 0.036267 0.005156 +v -0.035565 0.028070 -0.062894 +v -0.051117 0.030480 -0.054667 +v -0.045740 0.030309 -0.057362 +v -0.046246 0.028528 -0.061030 +v -0.040938 0.028306 -0.062385 +v -0.041121 0.025597 -0.065032 +v -0.035755 0.025299 -0.065395 +v -0.035783 0.022876 -0.066286 +v -0.035867 0.000551 -0.068838 +v -0.035815 0.014126 -0.067914 +v -0.056894 0.030635 -0.050153 +v -0.051689 0.028712 -0.058372 +v -0.046456 0.025861 -0.063785 +v -0.041140 0.023160 -0.066013 +v 0.057415 -0.019689 -0.059260 +v 0.008566 -0.018044 -0.062315 +v 0.036618 -0.031605 -0.052413 +v -0.035823 -0.012986 -0.068058 +v -0.035774 -0.024593 -0.065753 +v 0.037355 -0.023964 -0.059882 +v 0.008724 -0.023319 -0.061624 +v -0.018152 -0.027037 -0.062413 +v -0.029650 -0.029507 -0.060196 +v -0.041097 0.014323 -0.067822 +v -0.041111 0.000558 -0.068846 +v -0.041099 -0.013169 -0.067981 +v -0.041139 -0.024893 -0.065423 +v -0.046484 0.023414 -0.064825 +v -0.046379 0.014504 -0.066788 +v -0.046362 0.000564 -0.067899 +v -0.046377 -0.013336 -0.066960 +v -0.046482 -0.025158 -0.064195 +v -0.064296 0.028966 -0.046734 +v -0.064605 0.026305 -0.049314 +v -0.064602 0.023922 -0.050268 +v -0.064346 0.000577 -0.053449 +v -0.064629 -0.025624 -0.049682 +v -0.057557 0.028852 -0.053817 +v -0.057835 0.026189 -0.056540 +v -0.057845 0.023775 -0.057551 +v -0.057583 0.000573 -0.060826 +v -0.057635 -0.013588 -0.059824 +v -0.057863 -0.025498 -0.056932 +v -0.046292 -0.028159 -0.061550 +v -0.040980 -0.027929 -0.062887 +v -0.035610 -0.027681 -0.063375 +v -0.030053 -0.027439 -0.063332 +v -0.051942 0.026055 -0.061155 +v -0.051972 0.023615 -0.062200 +v -0.051814 0.014652 -0.064261 +v -0.051772 0.000569 -0.065429 +v -0.051808 -0.013474 -0.064442 +v -0.051974 -0.025355 -0.061564 +v -0.057763 -0.027233 -0.055728 +v -0.064368 -0.028593 -0.047231 +v -0.045184 -0.030798 -0.055463 +v -0.045883 -0.030039 -0.058110 +v -0.051278 -0.030211 -0.055421 +v -0.056180 -0.031124 -0.048282 +v -0.057079 -0.030364 -0.050899 +v -0.081366 -0.030713 -0.020917 +v 0.314938 -0.006677 -0.028165 +v 0.260793 -0.017545 -0.034140 +v 0.336743 -0.016088 -0.021372 +v 0.336730 -0.018829 -0.018685 +v 0.314871 -0.020694 -0.020902 +v 0.140106 -0.043906 -0.041177 +v 0.260711 -0.032481 -0.016597 +v 0.289160 -0.026578 -0.019418 +v 0.133330 -0.031369 -0.053896 +v 0.148276 0.000609 -0.053311 +v 0.148425 -0.013216 -0.052991 +v 0.119521 -0.032495 -0.055480 +v 0.119296 -0.036389 -0.054760 +v 0.126174 -0.039935 -0.051878 +v 0.125915 -0.042630 -0.049194 +v 0.125596 -0.044344 -0.046177 +v 0.132793 -0.044370 -0.043847 +v 0.117855 -0.044811 -0.044761 +v 0.139974 -0.045024 -0.034334 +v 0.118305 -0.043887 -0.048118 +v 0.119017 -0.039740 -0.053089 +v 0.314813 -0.027368 -0.007702 +v 0.314842 -0.025340 -0.013175 +v 0.132522 -0.045212 -0.040273 +v 0.104390 -0.038233 -0.054904 +v 0.103992 -0.040371 -0.053192 +v 0.103523 -0.041961 -0.050971 +v 0.102974 -0.042956 -0.047775 +v 0.336758 0.022924 -0.013028 +v 0.351946 0.023341 -0.010411 +v 0.165175 0.042834 -0.021613 +v 0.289076 0.029197 -0.012635 +v 0.260663 0.033194 -0.013206 +v 0.314841 0.025560 -0.012716 +v 0.289155 0.026931 -0.018593 +v 0.314862 0.022520 -0.018148 +v 0.289180 0.023127 -0.024775 +v 0.260745 0.031637 -0.020057 +v 0.260794 0.012994 -0.035149 +v 0.148779 0.025236 -0.052135 +v 0.148452 0.014410 -0.052931 +v 0.148966 0.029591 -0.051395 +v 0.099600 0.045966 -0.022551 +v 0.314884 0.017044 -0.024281 +v 0.289205 0.016440 -0.029290 +v 0.140149 0.031558 -0.052635 +v 0.133266 0.037157 -0.052103 +v 0.133140 0.040808 -0.049398 +v 0.126090 0.040998 -0.050989 +v 0.125813 0.043303 -0.048225 +v 0.125473 0.044750 -0.045000 +v 0.124779 0.045804 -0.038371 +v 0.102108 0.043728 -0.043207 +v 0.117245 0.045458 -0.040341 +v 0.103348 0.042394 -0.049949 +v 0.103842 0.040941 -0.052566 +v 0.104254 0.039078 -0.054326 +v 0.118909 0.040724 -0.052326 +v 0.119206 0.037600 -0.054297 +v 0.119449 0.033910 -0.055337 +v 0.119831 0.025850 -0.055388 +v 0.351952 0.014126 -0.021491 +v 0.353457 0.021446 -0.010917 +v 0.353457 0.022410 -0.008676 +v 0.353457 0.023610 -0.004092 +v 0.353457 0.016985 -0.016989 +v 0.353457 0.019065 -0.014779 +v 0.353457 0.015850 -0.018195 +v 0.353457 0.015534 -0.018531 +v 0.353457 0.014538 -0.019212 +v 0.353457 0.006741 -0.023295 +v 0.353457 0.011296 -0.021429 +v 0.353457 0.005177 -0.023575 +v 0.353457 0.001624 -0.024210 +v 0.353457 -0.012456 -0.020618 +v 0.353457 -0.003430 -0.024018 +v 0.353457 -0.009499 -0.022298 +v 0.353457 -0.008075 -0.022860 +v 0.353457 -0.017786 -0.016330 +v 0.353457 -0.013989 -0.019747 +v 0.353457 -0.020813 -0.012115 +v 0.353457 -0.023367 -0.005392 +v 0.353457 -0.022095 -0.009479 +v 0.028507 -0.036748 -0.003123 +v 0.024541 -0.036365 -0.001746 +v 0.078833 0.047137 -0.004466 +v 0.079759 0.047229 -0.005432 +v 0.079044 0.047183 -0.004115 +v 0.080064 0.047288 -0.005094 +v 0.077185 0.046825 -0.006074 +v 0.080196 0.047276 -0.005806 +v 0.077546 0.046935 -0.004787 +v 0.077405 0.046932 -0.004379 +v 0.079398 0.047119 -0.006720 +v 0.076748 0.046775 -0.005773 +v 0.079595 0.047132 -0.007082 +v 0.079234 0.047069 -0.007320 +v 0.078111 0.046917 -0.007041 +v 0.078539 0.046960 -0.007494 +v 0.077341 0.046804 -0.007060 +v 0.077053 0.046777 -0.006733 +v 0.080978 0.038457 -0.004506 +v 0.081247 0.038456 -0.005424 +v 0.081052 0.038397 -0.006118 +v 0.080348 0.038266 -0.006752 +v 0.079176 0.038095 -0.006752 +v 0.078291 0.038014 -0.005665 +v 0.078399 0.038072 -0.004717 +v 0.079271 0.038234 -0.003932 +v 0.080217 0.038372 -0.003932 +v 0.081132 0.038720 -0.004384 +v 0.080161 0.045382 -0.004680 +v 0.080401 0.045395 -0.005185 +v 0.081443 0.038719 -0.005444 +v 0.080472 0.045380 -0.005739 +v 0.081219 0.038650 -0.006244 +v 0.081063 0.038617 -0.006475 +v 0.080091 0.045279 -0.006770 +v 0.080406 0.038499 -0.006975 +v 0.080143 0.038457 -0.007064 +v 0.079172 0.045119 -0.007360 +v 0.079054 0.038302 -0.006975 +v 0.078083 0.044964 -0.007271 +v 0.078391 0.038228 -0.006475 +v 0.077420 0.044889 -0.006771 +v 0.078032 0.038209 -0.005722 +v 0.077997 0.038216 -0.005444 +v 0.077026 0.044878 -0.005740 +v 0.077089 0.044911 -0.005185 +v 0.078157 0.038276 -0.004627 +v 0.077185 0.044937 -0.004923 +v 0.078675 0.038380 -0.003982 +v 0.077703 0.045041 -0.004278 +v 0.079163 0.038462 -0.003722 +v 0.078191 0.045124 -0.004018 +v 0.080255 0.038622 -0.003722 +v 0.079284 0.045283 -0.004018 +v 0.081567 0.045617 -0.004002 +v 0.080810 0.045546 -0.003111 +v 0.076534 0.044918 -0.003217 +v 0.079419 0.045373 -0.002436 +v 0.078261 0.045206 -0.002395 +v 0.081881 0.045631 -0.004720 +v 0.081974 0.045576 -0.006271 +v 0.075564 0.044634 -0.006430 +v 0.075562 0.044703 -0.004876 +v 0.075494 0.044676 -0.005261 +v 0.081102 0.045372 -0.007986 +v 0.079801 0.045146 -0.008808 +v 0.076539 0.044702 -0.008098 +v 0.077888 0.044865 -0.008856 +v 0.080736 0.045923 -0.003113 +v 0.079250 0.045737 -0.002430 +v 0.078977 0.045699 -0.002393 +v 0.078157 0.045578 -0.002419 +v 0.076457 0.045293 -0.003253 +v 0.075453 0.045061 -0.005172 +v 0.075433 0.045022 -0.006001 +v 0.075534 0.045012 -0.006545 +v 0.076544 0.045087 -0.008170 +v 0.076987 0.045137 -0.008499 +v 0.077736 0.045231 -0.008844 +v 0.078545 0.045343 -0.008990 +v 0.079630 0.045507 -0.008862 +v 0.080611 0.045671 -0.008381 +v 0.081027 0.045748 -0.008023 +v 0.081525 0.045849 -0.007367 +v 0.081910 0.045951 -0.006337 +v 0.081812 0.046010 -0.004694 +v 0.081465 0.045993 -0.003940 +v 0.081309 0.045980 -0.003711 +v 0.075577 0.045273 -0.006260 +v 0.076719 0.045575 -0.003197 +v 0.078668 0.045889 -0.002531 +v 0.077256 0.045417 -0.008518 +v 0.077026 0.045389 -0.008388 +v 0.077204 0.046637 -0.007236 +v 0.077332 0.046652 -0.007340 +v 0.077116 0.046275 -0.007687 +v 0.077461 0.046315 -0.007901 +v 0.078469 0.046041 -0.008542 +v 0.078937 0.046110 -0.008527 +v 0.080706 0.047055 -0.005808 +v 0.079338 0.046787 -0.003444 +v 0.079131 0.046177 -0.002748 +v 0.078948 0.046735 -0.003339 +v 0.078931 0.045927 -0.002545 +v 0.076861 0.046031 -0.003482 +v 0.076683 0.045998 -0.003635 +v 0.075953 0.046002 -0.005755 +v 0.075664 0.045527 -0.005992 +v 0.075997 0.045989 -0.006194 +v 0.078942 0.046390 -0.004433 +v 0.079868 0.046482 -0.005399 +v 0.077655 0.046188 -0.004754 +v 0.077294 0.046079 -0.006041 +v 0.078220 0.046171 -0.007008 +v 0.079507 0.046373 -0.006687 +v 0.098335 0.049302 -0.009346 +v 0.099249 0.049322 -0.010328 +v 0.099264 0.049367 -0.009497 +v 0.099611 0.049361 -0.010133 +v 0.099647 0.049356 -0.010275 +v 0.096305 0.049048 -0.011190 +v 0.096644 0.049089 -0.010925 +v 0.097032 0.049185 -0.009645 +v 0.097986 0.049298 -0.008887 +v 0.099501 0.049286 -0.011409 +v 0.098860 0.049226 -0.011609 +v 0.098684 0.049181 -0.012206 +v 0.097558 0.049109 -0.011907 +v 0.097013 0.049057 -0.012091 +v 0.096307 0.049108 -0.010045 +v 0.097547 0.049087 -0.012319 +v 0.099736 0.040495 -0.009143 +v 0.100108 0.040454 -0.010496 +v 0.099209 0.040329 -0.011567 +v 0.098028 0.040238 -0.011547 +v 0.097323 0.040216 -0.010901 +v 0.097195 0.040267 -0.009725 +v 0.098178 0.040395 -0.008731 +v 0.099131 0.040468 -0.008747 +v 0.100061 0.040750 -0.009217 +v 0.099538 0.047459 -0.009564 +v 0.100353 0.040718 -0.010281 +v 0.099830 0.047427 -0.010628 +v 0.100316 0.040700 -0.010558 +v 0.099950 0.040633 -0.011305 +v 0.099427 0.047343 -0.011652 +v 0.099279 0.040556 -0.011794 +v 0.099012 0.040531 -0.011878 +v 0.098489 0.047240 -0.012225 +v 0.098181 0.040467 -0.011864 +v 0.097658 0.047176 -0.012211 +v 0.097917 0.040451 -0.011771 +v 0.097671 0.040439 -0.011636 +v 0.097148 0.047148 -0.011983 +v 0.096735 0.047135 -0.011606 +v 0.097102 0.040426 -0.011026 +v 0.096986 0.040430 -0.010771 +v 0.096463 0.047139 -0.011118 +v 0.096881 0.040450 -0.010222 +v 0.096358 0.047159 -0.010569 +v 0.096956 0.040484 -0.009669 +v 0.097058 0.040506 -0.009409 +v 0.096535 0.047215 -0.009756 +v 0.097592 0.040580 -0.008773 +v 0.097069 0.047290 -0.009119 +v 0.098089 0.040632 -0.008521 +v 0.097566 0.047341 -0.008868 +v 0.099190 0.040717 -0.008540 +v 0.098667 0.047426 -0.008887 +v 0.099887 0.040748 -0.008997 +v 0.095556 0.046990 -0.012631 +v 0.099569 0.047564 -0.007575 +v 0.100505 0.047601 -0.008278 +v 0.095912 0.047255 -0.008039 +v 0.096911 0.047364 -0.007437 +v 0.097667 0.047433 -0.007248 +v 0.101140 0.047600 -0.009263 +v 0.101333 0.047515 -0.011185 +v 0.094873 0.047009 -0.011233 +v 0.094825 0.047066 -0.010064 +v 0.100422 0.047356 -0.012884 +v 0.099095 0.047212 -0.013684 +v 0.095823 0.046996 -0.012918 +v 0.097167 0.047061 -0.013698 +v 0.099476 0.047943 -0.007564 +v 0.097589 0.047811 -0.007274 +v 0.095861 0.047634 -0.008078 +v 0.095175 0.047536 -0.008939 +v 0.094811 0.047454 -0.009978 +v 0.094867 0.047388 -0.011352 +v 0.095313 0.047370 -0.012362 +v 0.095853 0.047380 -0.012993 +v 0.097040 0.047436 -0.013687 +v 0.097306 0.047453 -0.013763 +v 0.098948 0.047582 -0.013738 +v 0.100371 0.047735 -0.012923 +v 0.100886 0.047809 -0.012277 +v 0.101293 0.047894 -0.011254 +v 0.101364 0.047928 -0.010705 +v 0.101137 0.047980 -0.009348 +v 0.100892 0.047987 -0.008851 +v 0.097363 0.048164 -0.013333 +v 0.097596 0.048180 -0.013379 +v 0.098380 0.048834 -0.012788 +v 0.098486 0.048462 -0.013187 +v 0.098701 0.048481 -0.013137 +v 0.098736 0.048867 -0.012690 +v 0.099857 0.049002 -0.011769 +v 0.099946 0.049017 -0.011607 +v 0.100061 0.048971 -0.009355 +v 0.099823 0.048969 -0.009025 +v 0.099020 0.048938 -0.008409 +v 0.098240 0.048889 -0.008186 +v 0.098037 0.048874 -0.008172 +v 0.098076 0.048508 -0.007755 +v 0.097605 0.048470 -0.007782 +v 0.095806 0.048463 -0.009122 +v 0.096311 0.048998 -0.009514 +v 0.095403 0.048014 -0.009110 +v 0.095291 0.047993 -0.009334 +v 0.095594 0.048427 -0.009507 +v 0.096090 0.048957 -0.009957 +v 0.095689 0.048525 -0.011390 +v 0.095399 0.047864 -0.012005 +v 0.095853 0.048518 -0.011762 +v 0.095528 0.047863 -0.012220 +v 0.098394 0.048550 -0.009308 +v 0.099308 0.048571 -0.010289 +v 0.097091 0.048433 -0.009606 +v 0.096702 0.048337 -0.010887 +v 0.097616 0.048357 -0.011868 +v 0.098919 0.048474 -0.011570 +v 0.092815 -0.047185 0.010440 +v 0.093696 -0.047532 0.009490 +v 0.093046 -0.047111 0.010774 +v 0.094095 -0.047554 0.009540 +v 0.090727 -0.047500 0.008672 +v 0.091074 -0.047459 0.008926 +v 0.094116 -0.047674 0.009121 +v 0.091504 -0.047148 0.010158 +v 0.093266 -0.047843 0.008258 +v 0.091634 -0.047006 0.010702 +v 0.090661 -0.047298 0.009365 +v 0.090973 -0.047103 0.010150 +v 0.091658 -0.047867 0.007668 +v 0.091955 -0.047807 0.007976 +v 0.091180 -0.047739 0.007973 +v 0.092934 -0.047992 0.007630 +v 0.094100 -0.038737 0.007937 +v 0.094605 -0.039000 0.007168 +v 0.094602 -0.039196 0.006472 +v 0.094088 -0.039374 0.005685 +v 0.093195 -0.039392 0.005343 +v 0.092094 -0.039185 0.005727 +v 0.091656 -0.038917 0.006533 +v 0.092106 -0.038592 0.007823 +v 0.093211 -0.038570 0.008247 +v 0.094595 -0.039068 0.007780 +v 0.094021 -0.045527 0.009610 +v 0.094811 -0.039226 0.007289 +v 0.094237 -0.045686 0.009119 +v 0.094280 -0.045765 0.008854 +v 0.094806 -0.039453 0.006486 +v 0.094232 -0.045913 0.008316 +v 0.094416 -0.039622 0.005768 +v 0.093842 -0.046081 0.007599 +v 0.094214 -0.039658 0.005578 +v 0.093461 -0.039692 0.005220 +v 0.092887 -0.046152 0.007050 +v 0.093183 -0.039678 0.005182 +v 0.092631 -0.039614 0.005237 +v 0.092057 -0.046073 0.007068 +v 0.092129 -0.039506 0.005459 +v 0.091554 -0.045966 0.007289 +v 0.091913 -0.039440 0.005625 +v 0.091473 -0.039211 0.006296 +v 0.090899 -0.045670 0.008126 +v 0.091407 -0.039131 0.006557 +v 0.091386 -0.039053 0.006825 +v 0.090812 -0.045513 0.008656 +v 0.091589 -0.038849 0.007608 +v 0.091015 -0.045309 0.009438 +v 0.091926 -0.038756 0.008044 +v 0.092144 -0.038725 0.008219 +v 0.091570 -0.045185 0.010049 +v 0.092648 -0.038702 0.008459 +v 0.092074 -0.045162 0.010289 +v 0.093202 -0.038730 0.008534 +v 0.093747 -0.038806 0.008436 +v 0.093173 -0.045266 0.010266 +v 0.094228 -0.038923 0.008176 +v 0.094117 -0.044993 0.011526 +v 0.095029 -0.045267 0.010845 +v 0.090448 -0.044789 0.011095 +v 0.092228 -0.044733 0.011850 +v 0.095847 -0.045922 0.008791 +v 0.095749 -0.045702 0.009536 +v 0.089306 -0.045559 0.008022 +v 0.089297 -0.045238 0.009149 +v 0.094796 -0.046504 0.006407 +v 0.095496 -0.046306 0.007325 +v 0.093445 -0.046601 0.005642 +v 0.090201 -0.046099 0.006394 +v 0.091518 -0.046431 0.005637 +v 0.094022 -0.045346 0.011661 +v 0.093511 -0.045247 0.011852 +v 0.092146 -0.045098 0.011948 +v 0.090612 -0.045132 0.011349 +v 0.090394 -0.045160 0.011181 +v 0.089832 -0.045280 0.010582 +v 0.089284 -0.045579 0.009355 +v 0.089294 -0.045955 0.008030 +v 0.090225 -0.046487 0.006445 +v 0.090653 -0.046618 0.006118 +v 0.091389 -0.046781 0.005771 +v 0.093293 -0.046967 0.005713 +v 0.094742 -0.046875 0.006492 +v 0.095277 -0.046747 0.007113 +v 0.095419 -0.046693 0.007345 +v 0.095805 -0.046365 0.008625 +v 0.095705 -0.046057 0.009681 +v 0.095395 -0.045822 0.010414 +v 0.095086 -0.045671 0.010849 +v 0.089783 -0.045590 0.010352 +v 0.090938 -0.046878 0.006168 +v 0.090713 -0.046821 0.006298 +v 0.093061 -0.047623 0.006577 +v 0.093022 -0.047929 0.007374 +v 0.093867 -0.047595 0.006930 +v 0.093607 -0.047822 0.007365 +v 0.094820 -0.047296 0.007541 +v 0.094643 -0.047447 0.007693 +v 0.095044 -0.047200 0.007947 +v 0.094852 -0.047359 0.008072 +v 0.094316 -0.047653 0.008754 +v 0.094994 -0.047256 0.008478 +v 0.095196 -0.047091 0.008383 +v 0.095272 -0.046969 0.008835 +v 0.094368 -0.047568 0.009071 +v 0.093532 -0.046552 0.011192 +v 0.093157 -0.046479 0.011332 +v 0.091375 -0.046367 0.011170 +v 0.091025 -0.046394 0.010963 +v 0.089927 -0.045541 0.010569 +v 0.090033 -0.046084 0.010314 +v 0.089921 -0.046132 0.010110 +v 0.090075 -0.046362 0.010088 +v 0.089916 -0.046462 0.009688 +v 0.089833 -0.046753 0.008633 +v 0.089702 -0.046619 0.008325 +v 0.089762 -0.046686 0.008106 +v 0.092879 -0.046461 0.010235 +v 0.093761 -0.046808 0.009285 +v 0.091568 -0.046424 0.009953 +v 0.091138 -0.046735 0.008721 +v 0.092019 -0.047083 0.007771 +v 0.093330 -0.047119 0.008053 +v 0.078833 -0.047073 -0.004466 +v 0.079759 -0.047165 -0.005432 +v 0.079757 -0.047201 -0.004601 +v 0.079044 -0.047119 -0.004115 +v 0.080064 -0.047224 -0.005094 +v 0.080152 -0.047225 -0.005372 +v 0.076854 -0.046701 -0.006345 +v 0.077185 -0.046761 -0.006074 +v 0.077546 -0.046871 -0.004787 +v 0.077405 -0.046868 -0.004379 +v 0.079398 -0.047055 -0.006720 +v 0.077019 -0.046793 -0.004806 +v 0.079595 -0.047068 -0.007082 +v 0.078111 -0.046853 -0.007041 +v 0.077574 -0.046766 -0.007234 +v 0.078683 -0.046917 -0.007483 +v 0.080978 -0.038393 -0.004506 +v 0.081247 -0.038392 -0.005424 +v 0.081052 -0.038332 -0.006118 +v 0.080348 -0.038202 -0.006752 +v 0.079176 -0.038031 -0.006752 +v 0.078291 -0.037950 -0.005665 +v 0.078399 -0.038008 -0.004717 +v 0.079271 -0.038170 -0.003932 +v 0.080217 -0.038308 -0.003932 +v 0.081132 -0.038656 -0.004384 +v 0.080161 -0.045318 -0.004680 +v 0.080459 -0.045327 -0.005459 +v 0.081443 -0.038654 -0.005444 +v 0.080472 -0.045316 -0.005739 +v 0.081219 -0.038586 -0.006244 +v 0.081063 -0.038553 -0.006475 +v 0.080091 -0.045215 -0.006770 +v 0.080406 -0.038435 -0.006975 +v 0.080143 -0.038393 -0.007064 +v 0.079172 -0.045055 -0.007360 +v 0.079054 -0.038238 -0.006975 +v 0.078083 -0.044900 -0.007271 +v 0.078391 -0.038164 -0.006475 +v 0.077420 -0.044825 -0.006771 +v 0.078032 -0.038145 -0.005722 +v 0.077997 -0.038152 -0.005444 +v 0.077026 -0.044813 -0.005740 +v 0.078157 -0.038211 -0.004627 +v 0.077185 -0.044873 -0.004923 +v 0.078675 -0.038316 -0.003982 +v 0.077703 -0.044977 -0.004278 +v 0.079163 -0.038398 -0.003722 +v 0.078191 -0.045060 -0.004018 +v 0.080255 -0.038558 -0.003722 +v 0.079284 -0.045219 -0.004018 +v 0.080810 -0.045482 -0.003111 +v 0.076534 -0.044854 -0.003217 +v 0.079419 -0.045309 -0.002436 +v 0.078261 -0.045142 -0.002395 +v 0.082019 -0.045553 -0.005490 +v 0.081881 -0.045567 -0.004720 +v 0.082019 -0.045535 -0.005882 +v 0.075564 -0.044570 -0.006430 +v 0.075494 -0.044611 -0.005261 +v 0.081102 -0.045308 -0.007986 +v 0.081748 -0.045445 -0.007019 +v 0.079801 -0.045082 -0.008808 +v 0.076539 -0.044638 -0.008098 +v 0.077888 -0.044801 -0.008856 +v 0.080736 -0.045859 -0.003113 +v 0.080035 -0.045776 -0.002677 +v 0.079250 -0.045672 -0.002430 +v 0.078157 -0.045514 -0.002419 +v 0.076888 -0.045307 -0.002913 +v 0.076457 -0.045229 -0.003253 +v 0.075676 -0.045065 -0.004375 +v 0.075453 -0.044997 -0.005172 +v 0.075433 -0.044958 -0.006001 +v 0.075534 -0.044948 -0.006545 +v 0.076544 -0.045023 -0.008170 +v 0.077477 -0.045134 -0.008750 +v 0.077736 -0.045167 -0.008844 +v 0.078545 -0.045279 -0.008990 +v 0.079630 -0.045443 -0.008862 +v 0.080826 -0.045646 -0.008211 +v 0.081027 -0.045683 -0.008023 +v 0.081653 -0.045815 -0.007123 +v 0.081969 -0.045920 -0.005787 +v 0.081812 -0.045946 -0.004694 +v 0.081309 -0.045916 -0.003711 +v 0.075577 -0.045208 -0.006260 +v 0.080995 -0.046117 -0.003601 +v 0.081162 -0.046132 -0.003807 +v 0.077341 -0.045826 -0.008238 +v 0.077555 -0.045853 -0.008337 +v 0.078469 -0.045977 -0.008542 +v 0.078937 -0.046046 -0.008527 +v 0.078782 -0.046616 -0.007939 +v 0.078963 -0.046643 -0.007910 +v 0.080419 -0.046291 -0.007876 +v 0.079770 -0.046946 -0.007261 +v 0.080749 -0.046354 -0.007540 +v 0.080001 -0.046990 -0.007026 +v 0.081174 -0.046707 -0.005584 +v 0.081112 -0.046717 -0.005147 +v 0.080776 -0.046704 -0.004333 +v 0.080153 -0.047116 -0.004701 +v 0.080513 -0.046681 -0.003978 +v 0.079955 -0.047099 -0.004435 +v 0.079845 -0.046207 -0.002973 +v 0.079242 -0.046873 -0.003657 +v 0.079614 -0.046177 -0.002878 +v 0.079066 -0.046850 -0.003602 +v 0.077551 -0.046767 -0.004001 +v 0.077277 -0.046719 -0.004182 +v 0.076666 -0.046458 -0.004537 +v 0.076495 -0.046419 -0.004863 +v 0.075664 -0.045463 -0.005992 +v 0.075965 -0.045694 -0.006677 +v 0.078942 -0.046326 -0.004433 +v 0.079868 -0.046418 -0.005399 +v 0.077655 -0.046124 -0.004754 +v 0.077294 -0.046014 -0.006041 +v 0.078220 -0.046107 -0.007008 +v 0.079507 -0.046308 -0.006687 +v 0.098335 -0.049238 -0.009346 +v 0.099249 -0.049258 -0.010328 +v 0.099434 -0.049303 -0.009734 +v 0.096305 -0.048984 -0.011190 +v 0.096644 -0.049024 -0.010925 +v 0.099682 -0.049272 -0.010709 +v 0.097032 -0.049121 -0.009645 +v 0.096898 -0.049132 -0.009235 +v 0.097986 -0.049234 -0.008887 +v 0.099501 -0.049222 -0.011409 +v 0.098860 -0.049162 -0.011609 +v 0.098684 -0.049117 -0.012206 +v 0.097558 -0.049045 -0.011907 +v 0.097547 -0.049023 -0.012319 +v 0.096678 -0.048981 -0.011811 +v 0.099736 -0.040431 -0.009143 +v 0.100108 -0.040390 -0.010496 +v 0.099209 -0.040264 -0.011567 +v 0.098028 -0.040173 -0.011547 +v 0.097323 -0.040152 -0.010901 +v 0.097195 -0.040203 -0.009725 +v 0.098178 -0.040331 -0.008731 +v 0.099131 -0.040404 -0.008747 +v 0.100061 -0.040686 -0.009217 +v 0.099538 -0.047395 -0.009564 +v 0.100353 -0.040654 -0.010281 +v 0.099830 -0.047363 -0.010628 +v 0.100316 -0.040636 -0.010558 +v 0.099950 -0.040569 -0.011305 +v 0.099427 -0.047278 -0.011652 +v 0.099005 -0.047227 -0.012015 +v 0.099279 -0.040492 -0.011794 +v 0.099012 -0.040466 -0.011878 +v 0.098489 -0.047176 -0.012225 +v 0.098213 -0.047152 -0.012265 +v 0.098181 -0.040402 -0.011864 +v 0.097658 -0.047112 -0.012211 +v 0.097917 -0.040387 -0.011771 +v 0.097671 -0.040374 -0.011636 +v 0.097148 -0.047084 -0.011983 +v 0.097102 -0.040362 -0.011026 +v 0.096986 -0.040366 -0.010771 +v 0.096463 -0.047075 -0.011118 +v 0.096881 -0.040386 -0.010222 +v 0.096358 -0.047095 -0.010569 +v 0.096956 -0.040420 -0.009669 +v 0.097058 -0.040442 -0.009409 +v 0.096535 -0.047151 -0.009756 +v 0.097592 -0.040516 -0.008773 +v 0.097069 -0.047226 -0.009119 +v 0.098089 -0.040568 -0.008521 +v 0.097566 -0.047277 -0.008868 +v 0.099190 -0.040653 -0.008540 +v 0.098667 -0.047362 -0.008887 +v 0.099887 -0.040684 -0.008997 +v 0.099569 -0.047500 -0.007575 +v 0.100505 -0.047537 -0.008278 +v 0.095912 -0.047191 -0.008039 +v 0.097667 -0.047369 -0.007248 +v 0.101140 -0.047535 -0.009263 +v 0.101333 -0.047451 -0.011185 +v 0.094873 -0.046945 -0.011233 +v 0.094825 -0.047002 -0.010064 +v 0.098328 -0.047080 -0.013828 +v 0.100422 -0.047292 -0.012884 +v 0.099095 -0.047148 -0.013684 +v 0.100128 -0.047256 -0.013142 +v 0.095823 -0.046932 -0.012918 +v 0.097167 -0.046997 -0.013698 +v 0.099476 -0.047879 -0.007564 +v 0.097589 -0.047746 -0.007274 +v 0.097050 -0.047698 -0.007397 +v 0.096074 -0.047596 -0.007903 +v 0.095861 -0.047570 -0.008078 +v 0.094950 -0.047429 -0.009443 +v 0.094811 -0.047390 -0.009978 +v 0.094867 -0.047324 -0.011352 +v 0.095313 -0.047306 -0.012362 +v 0.095853 -0.047316 -0.012993 +v 0.097040 -0.047372 -0.013687 +v 0.097306 -0.047389 -0.013763 +v 0.098948 -0.047518 -0.013738 +v 0.100371 -0.047671 -0.012923 +v 0.100886 -0.047745 -0.012277 +v 0.101293 -0.047830 -0.011254 +v 0.101364 -0.047863 -0.010705 +v 0.101137 -0.047916 -0.009348 +v 0.100892 -0.047922 -0.008851 +v 0.097343 -0.048859 -0.012501 +v 0.097136 -0.048086 -0.013268 +v 0.097363 -0.048100 -0.013333 +v 0.097502 -0.048870 -0.012547 +v 0.098380 -0.048770 -0.012788 +v 0.098486 -0.048398 -0.013187 +v 0.098701 -0.048417 -0.013137 +v 0.098736 -0.048803 -0.012690 +v 0.100247 -0.048598 -0.011972 +v 0.099946 -0.048953 -0.011607 +v 0.100443 -0.048634 -0.011578 +v 0.100022 -0.048968 -0.011438 +v 0.099020 -0.048874 -0.008409 +v 0.098240 -0.048825 -0.008186 +v 0.097632 -0.048777 -0.008195 +v 0.096309 -0.048277 -0.008320 +v 0.096081 -0.048438 -0.008777 +v 0.095957 -0.048233 -0.008635 +v 0.095588 -0.048473 -0.010995 +v 0.095689 -0.048460 -0.011390 +v 0.095399 -0.047800 -0.012004 +v 0.095853 -0.048454 -0.011762 +v 0.095528 -0.047799 -0.012220 +v 0.098394 -0.048486 -0.009308 +v 0.099308 -0.048506 -0.010289 +v 0.097091 -0.048369 -0.009606 +v 0.096702 -0.048272 -0.010887 +v 0.097616 -0.048293 -0.011868 +v 0.098919 -0.048410 -0.011570 +v 0.275776 0.033806 0.008424 +v 0.276895 0.033760 0.007686 +v 0.276326 0.033708 0.008703 +v 0.274260 0.034254 0.006169 +v 0.274524 0.034183 0.006504 +v 0.277405 0.033731 0.007417 +v 0.274591 0.034018 0.007834 +v 0.275328 0.033817 0.008788 +v 0.276828 0.033925 0.006356 +v 0.274006 0.034136 0.007421 +v 0.277101 0.033929 0.006046 +v 0.277438 0.033778 0.006984 +v 0.275643 0.034137 0.005765 +v 0.275731 0.034174 0.005364 +v 0.274541 0.034260 0.005835 +v 0.276433 0.034072 0.005513 +v 0.275264 0.024973 0.007424 +v 0.275969 0.024966 0.006778 +v 0.276162 0.025025 0.006083 +v 0.275889 0.025164 0.005177 +v 0.275124 0.025321 0.004625 +v 0.274408 0.025411 0.004584 +v 0.273571 0.025457 0.005046 +v 0.273172 0.025402 0.005913 +v 0.273511 0.025229 0.007035 +v 0.274318 0.025075 0.007523 +v 0.276835 0.031794 0.007934 +v 0.276197 0.025158 0.006915 +v 0.276991 0.031803 0.007701 +v 0.276420 0.025226 0.006114 +v 0.276406 0.025260 0.005836 +v 0.277200 0.031906 0.006622 +v 0.276105 0.025387 0.005069 +v 0.275926 0.025433 0.004857 +v 0.276720 0.032079 0.005643 +v 0.275479 0.025525 0.004534 +v 0.276273 0.032170 0.005320 +v 0.275222 0.025568 0.004431 +v 0.274673 0.025642 0.004355 +v 0.275467 0.032288 0.005141 +v 0.274396 0.025672 0.004384 +v 0.274126 0.025696 0.004458 +v 0.274919 0.032341 0.005243 +v 0.273430 0.025724 0.004917 +v 0.274224 0.032370 0.005702 +v 0.273119 0.025707 0.005381 +v 0.273913 0.032352 0.006167 +v 0.272970 0.025661 0.005918 +v 0.272998 0.025592 0.006472 +v 0.273792 0.032237 0.007258 +v 0.273361 0.025461 0.007212 +v 0.274154 0.032107 0.007998 +v 0.274293 0.025283 0.007776 +v 0.275086 0.031929 0.008561 +v 0.275384 0.025167 0.007662 +v 0.276178 0.031812 0.008447 +v 0.276195 0.031618 0.010072 +v 0.276930 0.031562 0.009805 +v 0.273016 0.032115 0.009079 +v 0.274651 0.031803 0.010064 +v 0.278119 0.031538 0.008802 +v 0.278726 0.031635 0.007373 +v 0.272543 0.032601 0.005442 +v 0.272296 0.032361 0.007722 +v 0.272196 0.032464 0.006952 +v 0.278297 0.031951 0.005130 +v 0.277209 0.032209 0.004048 +v 0.273866 0.032610 0.004031 +v 0.275351 0.032485 0.003588 +v 0.276172 0.032002 0.010132 +v 0.274805 0.032165 0.010134 +v 0.274539 0.032205 0.010065 +v 0.272969 0.032517 0.009016 +v 0.272433 0.032693 0.008066 +v 0.272351 0.032734 0.007804 +v 0.272415 0.032951 0.005904 +v 0.272634 0.032984 0.005396 +v 0.273113 0.033007 0.004719 +v 0.273981 0.032984 0.004036 +v 0.275022 0.032903 0.003674 +v 0.275295 0.032874 0.003639 +v 0.277149 0.032607 0.004032 +v 0.278000 0.032425 0.004712 +v 0.278327 0.032334 0.005150 +v 0.278813 0.032092 0.006705 +v 0.278751 0.032002 0.007528 +v 0.278205 0.031918 0.008789 +v 0.277428 0.031918 0.009574 +v 0.274610 0.032452 0.009958 +v 0.278675 0.032377 0.006480 +v 0.277922 0.032661 0.004835 +v 0.277740 0.032705 0.004647 +v 0.274877 0.033345 0.004077 +v 0.275155 0.033998 0.004930 +v 0.275123 0.033322 0.004025 +v 0.275519 0.033961 0.004868 +v 0.277201 0.033691 0.005455 +v 0.277444 0.033630 0.005728 +v 0.278397 0.032847 0.006581 +v 0.278699 0.032343 0.006742 +v 0.277874 0.033416 0.007104 +v 0.278420 0.032789 0.007051 +v 0.278024 0.033178 0.007491 +v 0.277831 0.033378 0.007470 +v 0.278233 0.032702 0.007973 +v 0.277910 0.033146 0.007881 +v 0.277898 0.032669 0.008598 +v 0.277234 0.032669 0.009269 +v 0.276828 0.032688 0.009513 +v 0.276769 0.032917 0.009367 +v 0.276547 0.033526 0.008843 +v 0.276396 0.033536 0.008910 +v 0.276567 0.032930 0.009456 +v 0.275122 0.033298 0.009407 +v 0.274362 0.032491 0.009871 +v 0.274737 0.033358 0.009290 +v 0.273164 0.033517 0.007936 +v 0.273051 0.033580 0.007514 +v 0.275687 0.033062 0.008336 +v 0.276806 0.033015 0.007598 +v 0.274502 0.033273 0.007746 +v 0.274435 0.033438 0.006416 +v 0.275554 0.033392 0.005677 +v 0.276739 0.033181 0.006268 +v 0.265800 0.035143 -0.009302 +v 0.266908 0.034875 -0.010010 +v 0.265933 0.035190 -0.008915 +v 0.264526 0.034987 -0.011239 +v 0.264125 0.035026 -0.011326 +v 0.267336 0.034821 -0.009989 +v 0.264609 0.035199 -0.009917 +v 0.264948 0.035291 -0.009102 +v 0.267426 0.034666 -0.010837 +v 0.266825 0.034663 -0.011332 +v 0.267001 0.034569 -0.011745 +v 0.265634 0.034719 -0.011946 +v 0.263999 0.035185 -0.010483 +v 0.265718 0.034641 -0.012343 +v 0.266420 0.034574 -0.012179 +v 0.265169 0.026391 -0.007787 +v 0.265865 0.026192 -0.008413 +v 0.265980 0.025981 -0.009572 +v 0.265424 0.025924 -0.010349 +v 0.264279 0.026031 -0.010628 +v 0.263185 0.026318 -0.009796 +v 0.263091 0.026489 -0.008860 +v 0.263780 0.026559 -0.007899 +v 0.265756 0.026529 -0.007910 +v 0.266640 0.033116 -0.009022 +v 0.266097 0.026412 -0.008337 +v 0.266282 0.026300 -0.008853 +v 0.267166 0.032887 -0.009964 +v 0.266292 0.026205 -0.009404 +v 0.267176 0.032793 -0.010515 +v 0.266230 0.026168 -0.009675 +v 0.265801 0.026105 -0.010387 +v 0.266685 0.032692 -0.011499 +v 0.265589 0.026103 -0.010570 +v 0.265351 0.026110 -0.010718 +v 0.266234 0.032697 -0.011830 +v 0.264544 0.026185 -0.010915 +v 0.265427 0.032772 -0.012027 +v 0.264267 0.026226 -0.010893 +v 0.263514 0.026381 -0.010570 +v 0.264397 0.032968 -0.011682 +v 0.263005 0.026557 -0.009933 +v 0.262912 0.026613 -0.009674 +v 0.263796 0.033200 -0.010786 +v 0.262897 0.026754 -0.008852 +v 0.263781 0.033341 -0.009964 +v 0.263268 0.026829 -0.008109 +v 0.264152 0.033417 -0.009221 +v 0.264349 0.033424 -0.009021 +v 0.263691 0.026834 -0.007743 +v 0.264575 0.033422 -0.008855 +v 0.265090 0.033389 -0.008639 +v 0.264759 0.026735 -0.007483 +v 0.265643 0.033322 -0.008595 +v 0.265294 0.026641 -0.007615 +v 0.266588 0.033428 -0.007215 +v 0.262786 0.033725 -0.008481 +v 0.263614 0.033753 -0.007653 +v 0.265056 0.033657 -0.007078 +v 0.264302 0.033724 -0.007281 +v 0.268120 0.033035 -0.008329 +v 0.268709 0.032719 -0.009733 +v 0.262512 0.033202 -0.011797 +v 0.262198 0.033431 -0.010692 +v 0.268253 0.032402 -0.011971 +v 0.267154 0.032364 -0.013071 +v 0.263815 0.032796 -0.013167 +v 0.265293 0.032529 -0.013572 +v 0.266723 0.033787 -0.007309 +v 0.264307 0.034102 -0.007363 +v 0.264055 0.034116 -0.007480 +v 0.262820 0.034098 -0.008568 +v 0.262545 0.034054 -0.009048 +v 0.262240 0.033824 -0.010650 +v 0.262394 0.033668 -0.011450 +v 0.262608 0.033556 -0.011949 +v 0.263936 0.033155 -0.013268 +v 0.264970 0.032960 -0.013603 +v 0.265242 0.032918 -0.013631 +v 0.266065 0.032817 -0.013578 +v 0.267098 0.032742 -0.013197 +v 0.267956 0.032745 -0.012501 +v 0.268288 0.032775 -0.012059 +v 0.268712 0.032889 -0.011045 +v 0.268740 0.033115 -0.009687 +v 0.268592 0.033223 -0.009164 +v 0.268211 0.033395 -0.008448 +v 0.262652 0.033838 -0.011686 +v 0.264767 0.033256 -0.013454 +v 0.265057 0.034163 -0.012887 +v 0.265025 0.033213 -0.013503 +v 0.265455 0.034100 -0.012945 +v 0.266494 0.033768 -0.012957 +v 0.266697 0.033755 -0.012872 +v 0.267160 0.033503 -0.012775 +v 0.267081 0.033740 -0.012653 +v 0.267578 0.033747 -0.012216 +v 0.268383 0.033667 -0.010830 +v 0.268044 0.034107 -0.010845 +v 0.268408 0.033703 -0.010596 +v 0.268070 0.034172 -0.010444 +v 0.268372 0.033698 -0.009352 +v 0.268160 0.033801 -0.008907 +v 0.266674 0.034210 -0.007665 +v 0.266438 0.034255 -0.007589 +v 0.266416 0.034443 -0.007792 +v 0.265953 0.034975 -0.008402 +v 0.265956 0.034520 -0.007705 +v 0.265770 0.035002 -0.008391 +v 0.264974 0.035198 -0.008798 +v 0.264679 0.035212 -0.008951 +v 0.263064 0.034630 -0.009352 +v 0.262973 0.034605 -0.009569 +v 0.263620 0.035042 -0.009861 +v 0.263521 0.034996 -0.010215 +v 0.262741 0.034103 -0.011428 +v 0.262828 0.034052 -0.011659 +v 0.265701 0.034405 -0.009178 +v 0.266809 0.034137 -0.009885 +v 0.264510 0.034461 -0.009793 +v 0.264427 0.034249 -0.011115 +v 0.265535 0.033981 -0.011822 +v 0.266726 0.033925 -0.011207 +v 0.285798 0.032402 -0.009453 +v 0.286885 0.032096 -0.010177 +v 0.286357 0.032387 -0.009177 +v 0.284471 0.032163 -0.011346 +v 0.284591 0.032435 -0.010038 +v 0.284952 0.032563 -0.009238 +v 0.287380 0.031847 -0.011007 +v 0.286766 0.031824 -0.011485 +v 0.284021 0.032235 -0.011290 +v 0.284075 0.032475 -0.010170 +v 0.287026 0.031722 -0.011788 +v 0.285559 0.031857 -0.012069 +v 0.285066 0.031857 -0.012370 +v 0.285631 0.031760 -0.012464 +v 0.284462 0.032019 -0.012004 +v 0.285570 0.023622 -0.007780 +v 0.286020 0.023329 -0.008835 +v 0.285550 0.023155 -0.009908 +v 0.284209 0.023246 -0.010315 +v 0.283392 0.023455 -0.009864 +v 0.283029 0.023692 -0.009011 +v 0.283150 0.023830 -0.008312 +v 0.284237 0.023879 -0.007424 +v 0.285761 0.023862 -0.007663 +v 0.285944 0.023793 -0.007865 +v 0.286820 0.030318 -0.009303 +v 0.286261 0.023587 -0.008608 +v 0.287137 0.030111 -0.010046 +v 0.286281 0.023524 -0.008881 +v 0.286256 0.023467 -0.009154 +v 0.287132 0.029992 -0.010592 +v 0.285738 0.023324 -0.010118 +v 0.286614 0.029848 -0.011557 +v 0.285279 0.023315 -0.010437 +v 0.286155 0.029840 -0.011876 +v 0.284467 0.023385 -0.010616 +v 0.285343 0.029909 -0.012054 +v 0.284191 0.023428 -0.010588 +v 0.283448 0.023602 -0.010253 +v 0.284324 0.030126 -0.011691 +v 0.283249 0.023669 -0.010067 +v 0.283960 0.030264 -0.011290 +v 0.282871 0.023878 -0.009353 +v 0.283747 0.030402 -0.010791 +v 0.282829 0.023943 -0.009083 +v 0.282969 0.024102 -0.008277 +v 0.283846 0.030626 -0.009715 +v 0.283703 0.024184 -0.007456 +v 0.284579 0.030709 -0.008894 +v 0.284223 0.024159 -0.007252 +v 0.285375 0.030655 -0.008652 +v 0.284777 0.024092 -0.007220 +v 0.285653 0.030617 -0.008658 +v 0.285308 0.023989 -0.007362 +v 0.286184 0.030514 -0.008800 +v 0.286988 0.030701 -0.007462 +v 0.282802 0.031037 -0.008487 +v 0.285497 0.030977 -0.007117 +v 0.285108 0.031024 -0.007143 +v 0.284350 0.031085 -0.007329 +v 0.288336 0.030232 -0.008768 +v 0.288692 0.029777 -0.010613 +v 0.282436 0.030363 -0.011767 +v 0.282837 0.030167 -0.012410 +v 0.282280 0.030879 -0.009524 +v 0.282154 0.030644 -0.010665 +v 0.288363 0.029578 -0.011720 +v 0.287367 0.029450 -0.012907 +v 0.283701 0.029888 -0.013150 +v 0.285167 0.029596 -0.013583 +v 0.287017 0.031077 -0.007534 +v 0.286248 0.031239 -0.007269 +v 0.285430 0.031364 -0.007202 +v 0.284883 0.031422 -0.007271 +v 0.284353 0.031458 -0.007428 +v 0.283007 0.031430 -0.008376 +v 0.282834 0.031406 -0.008592 +v 0.282198 0.031039 -0.010642 +v 0.282330 0.030846 -0.011439 +v 0.282529 0.030709 -0.011937 +v 0.283589 0.030304 -0.013131 +v 0.283820 0.030242 -0.013271 +v 0.285116 0.029982 -0.013658 +v 0.285939 0.029880 -0.013622 +v 0.287448 0.029822 -0.012966 +v 0.287661 0.029832 -0.012788 +v 0.288346 0.029930 -0.011928 +v 0.288470 0.029967 -0.011682 +v 0.288749 0.030162 -0.010632 +v 0.288365 0.030614 -0.008812 +v 0.287598 0.030099 -0.012738 +v 0.283951 0.031013 -0.012887 +v 0.285257 0.030738 -0.013337 +v 0.285961 0.030650 -0.013307 +v 0.287394 0.030088 -0.012907 +v 0.287979 0.030960 -0.011618 +v 0.287804 0.031487 -0.011012 +v 0.287837 0.031562 -0.010650 +v 0.288212 0.031161 -0.010564 +v 0.288362 0.030944 -0.009504 +v 0.287903 0.031557 -0.009829 +v 0.287719 0.031734 -0.009941 +v 0.288162 0.031069 -0.009060 +v 0.287244 0.031860 -0.008859 +v 0.286829 0.032096 -0.008845 +v 0.286478 0.031591 -0.007718 +v 0.286451 0.031770 -0.007929 +v 0.286238 0.031636 -0.007657 +v 0.286225 0.031813 -0.007872 +v 0.285058 0.031969 -0.007874 +v 0.284604 0.032000 -0.008008 +v 0.283453 0.031976 -0.008819 +v 0.283768 0.032336 -0.009620 +v 0.283174 0.031930 -0.009200 +v 0.283603 0.032286 -0.009948 +v 0.283430 0.031182 -0.012434 +v 0.283781 0.031576 -0.012257 +v 0.283918 0.031526 -0.012399 +v 0.285699 0.031671 -0.009292 +v 0.286787 0.031365 -0.010015 +v 0.284492 0.031704 -0.009877 +v 0.284373 0.031431 -0.011185 +v 0.285461 0.031126 -0.011908 +v 0.286668 0.031093 -0.011323 +v 0.275776 -0.033731 0.008424 +v 0.276895 -0.033684 0.007686 +v 0.276326 -0.033632 0.008703 +v 0.274524 -0.034107 0.006504 +v 0.274123 -0.034164 0.006426 +v 0.277405 -0.033655 0.007417 +v 0.274591 -0.033942 0.007834 +v 0.275328 -0.033741 0.008788 +v 0.276828 -0.033849 0.006356 +v 0.274006 -0.034061 0.007421 +v 0.277101 -0.033853 0.006046 +v 0.275643 -0.034061 0.005765 +v 0.275731 -0.034098 0.005364 +v 0.274895 -0.034172 0.005579 +v 0.274541 -0.034184 0.005835 +v 0.275264 -0.024898 0.007424 +v 0.275969 -0.024890 0.006778 +v 0.276162 -0.024949 0.006083 +v 0.275889 -0.025089 0.005177 +v 0.275124 -0.025245 0.004625 +v 0.274408 -0.025336 0.004584 +v 0.273571 -0.025381 0.005046 +v 0.273172 -0.025326 0.005913 +v 0.273511 -0.025153 0.007035 +v 0.274318 -0.024999 0.007523 +v 0.276197 -0.025082 0.006915 +v 0.276991 -0.031727 0.007701 +v 0.276420 -0.025150 0.006114 +v 0.276406 -0.025185 0.005836 +v 0.277200 -0.031830 0.006622 +v 0.276105 -0.025311 0.005069 +v 0.275926 -0.025358 0.004857 +v 0.276720 -0.032003 0.005643 +v 0.275479 -0.025449 0.004534 +v 0.276273 -0.032094 0.005320 +v 0.275222 -0.025492 0.004431 +v 0.274673 -0.025566 0.004355 +v 0.275467 -0.032212 0.005141 +v 0.274396 -0.025596 0.004384 +v 0.274126 -0.025620 0.004458 +v 0.274919 -0.032265 0.005243 +v 0.273430 -0.025649 0.004917 +v 0.274224 -0.032294 0.005702 +v 0.273119 -0.025631 0.005381 +v 0.273913 -0.032276 0.006167 +v 0.272970 -0.025585 0.005918 +v 0.272998 -0.025516 0.006472 +v 0.273792 -0.032162 0.007258 +v 0.273361 -0.025386 0.007212 +v 0.274154 -0.032031 0.007998 +v 0.274349 -0.031984 0.008194 +v 0.273780 -0.025293 0.007570 +v 0.274573 -0.031939 0.008356 +v 0.274293 -0.025208 0.007776 +v 0.274847 -0.025138 0.007807 +v 0.275640 -0.031783 0.008593 +v 0.275384 -0.025091 0.007662 +v 0.276178 -0.031736 0.008447 +v 0.276195 -0.031542 0.010072 +v 0.273290 -0.031974 0.009352 +v 0.273016 -0.032039 0.009079 +v 0.274651 -0.031727 0.010064 +v 0.278119 -0.031462 0.008802 +v 0.278726 -0.031559 0.007373 +v 0.272543 -0.032525 0.005442 +v 0.272296 -0.032285 0.007722 +v 0.272196 -0.032388 0.006952 +v 0.278297 -0.031875 0.005130 +v 0.278714 -0.031698 0.006210 +v 0.277209 -0.032133 0.004048 +v 0.273866 -0.032534 0.004031 +v 0.275351 -0.032409 0.003588 +v 0.276172 -0.031926 0.010132 +v 0.274805 -0.032090 0.010134 +v 0.274539 -0.032129 0.010065 +v 0.272969 -0.032441 0.009016 +v 0.272433 -0.032617 0.008066 +v 0.272351 -0.032658 0.007804 +v 0.272634 -0.032909 0.005396 +v 0.273113 -0.032932 0.004719 +v 0.273981 -0.032909 0.004036 +v 0.275022 -0.032827 0.003674 +v 0.275295 -0.032799 0.003639 +v 0.277149 -0.032531 0.004032 +v 0.278000 -0.032349 0.004712 +v 0.278327 -0.032258 0.005150 +v 0.278794 -0.031953 0.007255 +v 0.278751 -0.031926 0.007528 +v 0.278205 -0.031842 0.008789 +v 0.277428 -0.031842 0.009574 +v 0.274610 -0.032376 0.009958 +v 0.277922 -0.032586 0.004835 +v 0.277740 -0.032630 0.004647 +v 0.274877 -0.033270 0.004077 +v 0.275155 -0.033922 0.004930 +v 0.275123 -0.033246 0.004025 +v 0.275519 -0.033886 0.004868 +v 0.277201 -0.033615 0.005455 +v 0.277444 -0.033554 0.005728 +v 0.277234 -0.032593 0.009269 +v 0.276828 -0.032612 0.009513 +v 0.276769 -0.032841 0.009367 +v 0.276547 -0.033450 0.008843 +v 0.276396 -0.033460 0.008910 +v 0.276567 -0.032855 0.009456 +v 0.275122 -0.033223 0.009407 +v 0.274362 -0.032416 0.009871 +v 0.274737 -0.033282 0.009290 +v 0.273164 -0.033441 0.007936 +v 0.273051 -0.033504 0.007514 +v 0.273247 -0.033696 0.007297 +v 0.275687 -0.032986 0.008336 +v 0.276806 -0.032940 0.007598 +v 0.274502 -0.033197 0.007746 +v 0.274435 -0.033362 0.006416 +v 0.275554 -0.033316 0.005677 +v 0.276739 -0.033105 0.006268 +v 0.265800 -0.035067 -0.009302 +v 0.266908 -0.034799 -0.010010 +v 0.265933 -0.035115 -0.008915 +v 0.264526 -0.034911 -0.011239 +v 0.267336 -0.034745 -0.009989 +v 0.264609 -0.035123 -0.009917 +v 0.264948 -0.035215 -0.009102 +v 0.267426 -0.034590 -0.010837 +v 0.266825 -0.034587 -0.011332 +v 0.267249 -0.034521 -0.011386 +v 0.265634 -0.034643 -0.011946 +v 0.265150 -0.034655 -0.012260 +v 0.263999 -0.035109 -0.010483 +v 0.264535 -0.034798 -0.011904 +v 0.266420 -0.034498 -0.012179 +v 0.265169 -0.026315 -0.007787 +v 0.265865 -0.026116 -0.008413 +v 0.266049 -0.025976 -0.009098 +v 0.265765 -0.025861 -0.010004 +v 0.264994 -0.025869 -0.010571 +v 0.264279 -0.025955 -0.010628 +v 0.263185 -0.026242 -0.009796 +v 0.263091 -0.026413 -0.008860 +v 0.263780 -0.026483 -0.007899 +v 0.265756 -0.026454 -0.007910 +v 0.266640 -0.033041 -0.009022 +v 0.266097 -0.026336 -0.008337 +v 0.266282 -0.026224 -0.008853 +v 0.267166 -0.032811 -0.009964 +v 0.266309 -0.026174 -0.009127 +v 0.266292 -0.026130 -0.009404 +v 0.267176 -0.032717 -0.010515 +v 0.265982 -0.026041 -0.010173 +v 0.265801 -0.026029 -0.010387 +v 0.266685 -0.032617 -0.011499 +v 0.265351 -0.026034 -0.010718 +v 0.266234 -0.032621 -0.011830 +v 0.265093 -0.026050 -0.010827 +v 0.264544 -0.026109 -0.010915 +v 0.265427 -0.032696 -0.012027 +v 0.264267 -0.026150 -0.010893 +v 0.263514 -0.026305 -0.010570 +v 0.264397 -0.032892 -0.011682 +v 0.263005 -0.026481 -0.009933 +v 0.262912 -0.026537 -0.009674 +v 0.263796 -0.033124 -0.010786 +v 0.262897 -0.026678 -0.008852 +v 0.263781 -0.033265 -0.009964 +v 0.263268 -0.026754 -0.008109 +v 0.264152 -0.033341 -0.009221 +v 0.263691 -0.026759 -0.007743 +v 0.264575 -0.033346 -0.008855 +v 0.264759 -0.026659 -0.007483 +v 0.265643 -0.033247 -0.008595 +v 0.265294 -0.026565 -0.007615 +v 0.266178 -0.033152 -0.008727 +v 0.266588 -0.033353 -0.007215 +v 0.267592 -0.033124 -0.007774 +v 0.262786 -0.033649 -0.008481 +v 0.265444 -0.033535 -0.007044 +v 0.264302 -0.033648 -0.007281 +v 0.268499 -0.032796 -0.008994 +v 0.268746 -0.032573 -0.010117 +v 0.262512 -0.033126 -0.011797 +v 0.262294 -0.033537 -0.009538 +v 0.262198 -0.033355 -0.010692 +v 0.268253 -0.032326 -0.011971 +v 0.267154 -0.032288 -0.013071 +v 0.263815 -0.032720 -0.013167 +v 0.265293 -0.032453 -0.013572 +v 0.266723 -0.033711 -0.007309 +v 0.264307 -0.034026 -0.007363 +v 0.264055 -0.034040 -0.007480 +v 0.263170 -0.034047 -0.008139 +v 0.262820 -0.034022 -0.008568 +v 0.262234 -0.033795 -0.010376 +v 0.262240 -0.033748 -0.010650 +v 0.262608 -0.033480 -0.011949 +v 0.263270 -0.033247 -0.012802 +v 0.263936 -0.033079 -0.013268 +v 0.265242 -0.032842 -0.013631 +v 0.266065 -0.032741 -0.013578 +v 0.267098 -0.032667 -0.013197 +v 0.268288 -0.032699 -0.012059 +v 0.268638 -0.032778 -0.011310 +v 0.268798 -0.032940 -0.010230 +v 0.268592 -0.033147 -0.009164 +v 0.267660 -0.033494 -0.007852 +v 0.264052 -0.033832 -0.012845 +v 0.266075 -0.033496 -0.013227 +v 0.266530 -0.033456 -0.013101 +v 0.267843 -0.033695 -0.011863 +v 0.268327 -0.033259 -0.011536 +v 0.268046 -0.033734 -0.011472 +v 0.268414 -0.033287 -0.011302 +v 0.268372 -0.033622 -0.009352 +v 0.268160 -0.033725 -0.008907 +v 0.266674 -0.034134 -0.007665 +v 0.266438 -0.034179 -0.007589 +v 0.266416 -0.034368 -0.007792 +v 0.265953 -0.034900 -0.008402 +v 0.265956 -0.034444 -0.007705 +v 0.265770 -0.034926 -0.008391 +v 0.264390 -0.034230 -0.007532 +v 0.264767 -0.034895 -0.008336 +v 0.264974 -0.035122 -0.008798 +v 0.264679 -0.035136 -0.008951 +v 0.263521 -0.034920 -0.010215 +v 0.263483 -0.034864 -0.010580 +v 0.263684 -0.033929 -0.012563 +v 0.265701 -0.034329 -0.009178 +v 0.266809 -0.034061 -0.009885 +v 0.264510 -0.034385 -0.009793 +v 0.264427 -0.034173 -0.011115 +v 0.265535 -0.033905 -0.011822 +v 0.266726 -0.033849 -0.011207 +v 0.285798 -0.032326 -0.009453 +v 0.286885 -0.032020 -0.010177 +v 0.286357 -0.032312 -0.009177 +v 0.284471 -0.032087 -0.011346 +v 0.284591 -0.032359 -0.010038 +v 0.284952 -0.032487 -0.009238 +v 0.287380 -0.031771 -0.011007 +v 0.286766 -0.031748 -0.011485 +v 0.284021 -0.032160 -0.011290 +v 0.284075 -0.032399 -0.010170 +v 0.285559 -0.031781 -0.012069 +v 0.285066 -0.031781 -0.012370 +v 0.286595 -0.031618 -0.012178 +v 0.285570 -0.023546 -0.007780 +v 0.286020 -0.023253 -0.008835 +v 0.285550 -0.023080 -0.009908 +v 0.284209 -0.023170 -0.010315 +v 0.283139 -0.023500 -0.009469 +v 0.283150 -0.023754 -0.008312 +v 0.284237 -0.023804 -0.007424 +v 0.285761 -0.023786 -0.007663 +v 0.285944 -0.023717 -0.007865 +v 0.286820 -0.030242 -0.009303 +v 0.286261 -0.023511 -0.008608 +v 0.287137 -0.030035 -0.010046 +v 0.286281 -0.023448 -0.008881 +v 0.286256 -0.023391 -0.009154 +v 0.287132 -0.029916 -0.010592 +v 0.285738 -0.023248 -0.010118 +v 0.286614 -0.029773 -0.011557 +v 0.285279 -0.023239 -0.010437 +v 0.286155 -0.029764 -0.011876 +v 0.284467 -0.023309 -0.010616 +v 0.285343 -0.029834 -0.012054 +v 0.284191 -0.023352 -0.010588 +v 0.283448 -0.023526 -0.010253 +v 0.284324 -0.030051 -0.011691 +v 0.282957 -0.023733 -0.009611 +v 0.282871 -0.023802 -0.009353 +v 0.283747 -0.030326 -0.010791 +v 0.282969 -0.024026 -0.008277 +v 0.283846 -0.030550 -0.009715 +v 0.283703 -0.024108 -0.007456 +v 0.284579 -0.030633 -0.008894 +v 0.284223 -0.024083 -0.007252 +v 0.284777 -0.024016 -0.007220 +v 0.285653 -0.030541 -0.008658 +v 0.285308 -0.023914 -0.007362 +v 0.286184 -0.030438 -0.008800 +v 0.285884 -0.030845 -0.007137 +v 0.286988 -0.030625 -0.007462 +v 0.282802 -0.030961 -0.008487 +v 0.285497 -0.030901 -0.007117 +v 0.284350 -0.031009 -0.007329 +v 0.288336 -0.030156 -0.008768 +v 0.288692 -0.029702 -0.010613 +v 0.282436 -0.030287 -0.011767 +v 0.282154 -0.030568 -0.010665 +v 0.288363 -0.029502 -0.011720 +v 0.286690 -0.029378 -0.013302 +v 0.287367 -0.029374 -0.012907 +v 0.283701 -0.029812 -0.013150 +v 0.285167 -0.029520 -0.013583 +v 0.287017 -0.031001 -0.007534 +v 0.286248 -0.031163 -0.007269 +v 0.285430 -0.031288 -0.007202 +v 0.284883 -0.031346 -0.007271 +v 0.284353 -0.031382 -0.007428 +v 0.283007 -0.031354 -0.008376 +v 0.282834 -0.031330 -0.008592 +v 0.282342 -0.031181 -0.009569 +v 0.282198 -0.030963 -0.010642 +v 0.282330 -0.030770 -0.011439 +v 0.282529 -0.030633 -0.011937 +v 0.283820 -0.030166 -0.013271 +v 0.284844 -0.029951 -0.013624 +v 0.285116 -0.029907 -0.013658 +v 0.285939 -0.029804 -0.013622 +v 0.287448 -0.029746 -0.012966 +v 0.287661 -0.029757 -0.012788 +v 0.288346 -0.029854 -0.011928 +v 0.288470 -0.029892 -0.011682 +v 0.288749 -0.030086 -0.010632 +v 0.288365 -0.030539 -0.008812 +v 0.287598 -0.030023 -0.012738 +v 0.284647 -0.030254 -0.013484 +v 0.284356 -0.030833 -0.013109 +v 0.284720 -0.030502 -0.013381 +v 0.284796 -0.030741 -0.013261 +v 0.284963 -0.030459 -0.013432 +v 0.285961 -0.030574 -0.013307 +v 0.286479 -0.031222 -0.012675 +v 0.286640 -0.030528 -0.013105 +v 0.286806 -0.031217 -0.012500 +v 0.287394 -0.030013 -0.012907 +v 0.287434 -0.030534 -0.012593 +v 0.287979 -0.030884 -0.011618 +v 0.287804 -0.031411 -0.011012 +v 0.287837 -0.031487 -0.010650 +v 0.288212 -0.031085 -0.010564 +v 0.288362 -0.030868 -0.009504 +v 0.287903 -0.031482 -0.009829 +v 0.287719 -0.031659 -0.009941 +v 0.288162 -0.030993 -0.009060 +v 0.286829 -0.032020 -0.008845 +v 0.286478 -0.031515 -0.007718 +v 0.286451 -0.031694 -0.007929 +v 0.286238 -0.031560 -0.007657 +v 0.286225 -0.031737 -0.007872 +v 0.285058 -0.031893 -0.007874 +v 0.284604 -0.031925 -0.008008 +v 0.283768 -0.032260 -0.009620 +v 0.283174 -0.031854 -0.009200 +v 0.282773 -0.031617 -0.009514 +v 0.283603 -0.032210 -0.009948 +v 0.282884 -0.031752 -0.009840 +v 0.285699 -0.031595 -0.009292 +v 0.286787 -0.031289 -0.010015 +v 0.284492 -0.031628 -0.009877 +v 0.284373 -0.031356 -0.011185 +v 0.285461 -0.031050 -0.011908 +v 0.286668 -0.031017 -0.011323 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vn -0.0031 1.0000 -0.0027 +vn -0.0057 1.0000 0.0026 +vn -0.0078 0.9999 -0.0068 +vn -0.0021 1.0000 0.0006 +vn 0.0027 1.0000 -0.0079 +vn -0.4792 -0.0323 0.8771 +vn -0.6479 0.1609 0.7445 +vn -0.5152 -0.0227 0.8567 +vn -0.6736 0.1369 0.7263 +vn -0.9951 -0.0119 0.0984 +vn -0.9948 -0.0111 0.1012 +vn -0.9938 -0.0083 0.1112 +vn -0.9935 -0.0076 0.1134 +vn -0.6976 -0.0225 -0.7161 +vn -0.7816 0.0055 -0.6238 +vn -0.7634 -0.0009 -0.6460 +vn -0.6817 -0.0274 -0.7312 +vn -0.1880 0.0358 -0.9815 +vn 0.3488 -0.0392 -0.9364 +vn 0.5179 0.0018 -0.8555 +vn 0.3805 -0.0319 -0.9242 +vn 0.5579 0.0123 -0.8298 +vn 0.9642 -0.0027 -0.2651 +vn 0.9611 0.0004 -0.2760 +vn 0.9618 -0.0002 -0.2739 +vn 0.9648 -0.0033 -0.2630 +vn 0.8826 -0.0090 0.4701 +vn 0.8372 0.0114 0.5468 +vn 0.8745 -0.0051 0.4850 +vn 0.8287 0.0149 0.5594 +vn 0.3360 -0.0111 0.9418 +vn 0.2150 0.0154 0.9765 +vn 0.3120 -0.0057 0.9501 +vn 0.1928 0.0202 0.9810 +vn -0.2196 0.7393 -0.6365 +vn 0.1232 0.7584 -0.6400 +vn -0.3867 0.7077 -0.5913 +vn -0.5465 0.7001 -0.4596 +vn -0.5730 0.6781 -0.4604 +vn -0.7299 0.6793 0.0757 +vn -0.5854 0.7952 0.1578 +vn -0.6701 0.7337 0.1122 +vn -0.5369 0.8239 0.1814 +vn -0.6009 0.4716 0.6454 +vn 0.0928 0.7983 0.5951 +vn 0.1007 0.7896 0.6053 +vn 0.1181 0.7700 0.6271 +vn 0.1287 0.7574 0.6401 +vn 0.7013 0.5309 0.4757 +vn 0.5056 0.8623 0.0282 +vn 0.5668 0.8235 -0.0218 +vn 0.6955 0.7046 -0.1411 +vn 0.7681 0.6006 -0.2222 +vn 0.4679 0.5425 -0.6977 +vn 0.3562 0.6585 -0.6629 +vn 0.0000 1.0000 0.0000 +vn 0.0033 -1.0000 0.0017 +vn 0.0030 -1.0000 0.0008 +vn 0.0029 -1.0000 -0.0004 +vn 0.0032 -1.0000 -0.0012 +vn 0.0016 -1.0000 -0.0014 +vn 0.0005 -1.0000 -0.0010 +vn 0.0004 -1.0000 -0.0010 +vn 0.0005 -1.0000 -0.0018 +vn 0.0003 -1.0000 -0.0021 +vn -0.0007 -1.0000 0.0062 +vn -0.0004 -1.0000 0.0031 +vn 0.0006 -1.0000 0.0032 +vn -0.0010 -1.0000 -0.0017 +vn -0.0011 -1.0000 -0.0015 +vn -0.0017 -1.0000 -0.0013 +vn -0.0053 -1.0000 -0.0037 +vn -0.0194 -0.9998 -0.0037 +vn 0.0074 -1.0000 0.0052 +vn 0.0029 -1.0000 0.0028 +vn -0.0247 -0.9997 0.0075 +vn -0.8740 0.4808 0.0706 +vn -0.7173 -0.5946 0.3632 +vn -0.5687 0.5391 0.6212 +vn -0.1657 -0.4622 0.8712 +vn -0.1687 -0.4852 0.8580 +vn -0.1293 -0.2144 0.9682 +vn -0.1136 -0.1199 0.9863 +vn 0.3632 0.3493 0.8637 +vn 0.5487 -0.4145 0.7260 +vn 0.7618 0.4144 0.4979 +vn 0.8272 -0.5172 0.2196 +vn 0.7579 0.6198 -0.2035 +vn 0.7200 -0.5390 -0.4371 +vn 0.3754 0.4092 -0.8317 +vn 0.0491 -0.0449 -0.9978 +vn 0.3020 -0.0958 -0.9485 +vn 0.0399 -0.0708 -0.9967 +vn -0.2543 0.2558 -0.9327 +vn -0.2591 0.2850 -0.9228 +vn -0.6475 -0.3160 -0.6935 +vn -0.7706 0.3693 -0.5194 +vn -0.8982 -0.3616 -0.2500 +vn 0.0083 -0.9988 -0.0478 +vn -0.0301 -0.9981 -0.0531 +vn 0.0064 -0.9990 -0.0435 +vn 0.0388 -0.9974 -0.0601 +vn -0.1028 -0.9935 -0.0492 +vn -0.0987 -0.9930 0.0651 +vn -0.0014 -0.9995 0.0300 +vn -0.0155 -0.9988 0.0465 +vn 0.1756 -0.9756 0.1320 +vn 0.0082 -0.9990 0.0444 +vn -0.1187 -0.9929 0.0007 +vn -0.1217 -0.9925 0.0139 +vn 0.1019 -0.9948 0.0075 +vn 0.1253 -0.9903 -0.0602 +vn 0.5974 -0.8007 -0.0438 +vn 0.6325 -0.6643 0.3983 +vn 0.3985 -0.7751 0.4903 +vn -0.5763 -0.8148 -0.0628 +vn -0.5741 -0.6852 -0.4483 +vn -0.1909 -0.7798 -0.5962 +vn 0.3244 -0.7758 -0.5411 +vn 0.6698 -0.6783 -0.3022 +vn -0.3799 -0.7897 0.4817 +vn -0.6632 -0.7137 0.2254 +vn -0.7577 -0.6401 -0.1271 +vn 0.7583 -0.6451 0.0944 +vn 0.0849 -0.6479 0.7570 +vn 0.0208 -0.7721 0.6352 +vn -0.2722 -0.5949 0.7563 +vn -0.5775 -0.6258 0.5243 +vn -0.1067 -0.6182 -0.7787 +vn 0.1994 -0.6275 -0.7526 +vn 0.5216 -0.5848 -0.6213 +vn 0.3751 -0.5526 0.7443 +vn -0.5018 -0.5627 -0.6569 +vn -0.8068 -0.5425 0.2339 +vn 0.0312 -0.4652 0.8846 +vn -0.4350 -0.4923 -0.7539 +vn -0.0398 -0.4855 -0.8733 +vn 0.3536 -0.4735 -0.8067 +vn 0.6949 -0.4912 -0.5252 +vn 0.8369 -0.5224 -0.1634 +vn 0.8367 -0.5039 0.2145 +vn 0.6166 -0.4946 0.6125 +vn -0.5542 -0.4807 0.6796 +vn -0.8073 -0.5115 -0.2944 +vn -0.0000 -1.0000 -0.0000 +vn -0.9999 0.0076 0.0133 +vn -0.9984 -0.0199 -0.0537 +vn -0.9982 -0.0254 0.0539 +vn -0.9846 0.0314 0.1721 +vn -0.9884 0.0348 -0.1475 +vn -0.4995 -0.0344 -0.8656 +vn -0.4985 -0.0334 -0.8662 +vn -0.4976 -0.0323 -0.8668 +vn 0.5107 -0.0091 -0.8597 +vn 0.5100 -0.0081 -0.8601 +vn 0.4998 0.0047 -0.8661 +vn 0.5202 -0.0211 -0.8538 +vn 0.9992 -0.0402 0.0000 +vn 0.9991 0.0014 0.0414 +vn 0.9990 0.0047 0.0448 +vn 0.9954 0.0449 0.0846 +vn 0.4992 -0.0495 0.8651 +vn 0.4700 -0.0173 0.8825 +vn 0.4697 -0.0171 0.8826 +vn 0.4395 0.0151 0.8981 +vn -0.5046 -0.0377 0.8625 +vn -0.5048 -0.0380 0.8624 +vn -0.4995 -0.0319 0.8657 +vn -0.5102 -0.0441 0.8589 +vn 0.9508 -0.2903 0.1083 +vn 0.9625 -0.2409 0.1252 +vn 0.9666 0.1126 0.2301 +vn 0.9542 0.1719 0.2450 +vn 0.7430 -0.1877 0.6424 +vn 0.7418 -0.1565 0.6521 +vn 0.7137 0.0522 0.6985 +vn 0.7036 0.0957 0.7041 +vn 0.2382 0.0111 0.9711 +vn 0.2481 0.0517 0.9673 +vn 0.1933 -0.1560 0.9687 +vn 0.1857 -0.1817 0.9657 +vn -0.2516 0.1036 0.9623 +vn -0.2255 0.1738 0.9586 +vn -0.3569 -0.2419 0.9023 +vn -0.3705 -0.2993 0.8793 +vn -0.6589 0.3645 0.6580 +vn -0.8064 -0.4351 0.4004 +vn -0.8873 0.4452 0.1203 +vn -0.7984 -0.5383 -0.2698 +vn -0.6300 0.5938 -0.5006 +vn -0.3062 -0.5618 -0.7686 +vn -0.0197 0.4947 -0.8688 +vn 0.3054 -0.3661 -0.8790 +vn 0.5995 0.3022 -0.7411 +vn 0.7684 -0.3546 -0.5327 +vn 0.8844 0.3511 -0.3074 +vn -0.8126 0.0139 -0.5827 +vn -0.8422 -0.0310 -0.5382 +vn -0.8323 -0.0152 -0.5541 +vn -0.8617 -0.0643 -0.5034 +vn -0.0052 -0.0430 -0.9991 +vn -0.2745 0.0794 -0.9583 +vn 0.1151 0.0226 -0.9931 +vn 0.2411 -0.0571 -0.9688 +vn 0.4721 0.0504 -0.8801 +vn 0.8895 -0.0092 -0.4568 +vn 0.9030 -0.0304 -0.4287 +vn 0.8957 -0.0188 -0.4442 +vn 0.8826 0.0010 -0.4702 +vn 0.9440 -0.0173 0.3294 +vn 0.9367 -0.0008 0.3502 +vn 0.9391 -0.0061 0.3436 +vn 0.9311 0.0107 0.3647 +vn 0.2374 -0.0246 0.9711 +vn 0.3056 0.0215 0.9519 +vn 0.2606 -0.0091 0.9654 +vn 0.1969 -0.0513 0.9791 +vn -0.5422 -0.0155 0.8401 +vn -0.4233 0.0442 0.9049 +vn -0.4818 0.0155 0.8762 +vn -0.5953 -0.0441 0.8023 +vn -0.9654 0.0006 0.2609 +vn -0.9402 0.0445 0.3377 +vn -0.9546 0.0212 0.2971 +vn -0.9765 -0.0255 0.2140 +vn 0.0457 -0.9968 -0.0659 +vn 0.0288 -0.9962 -0.0821 +vn 0.0801 -0.9968 0.0066 +vn -0.0018 -0.9912 -0.1320 +vn -0.0269 -0.9914 -0.1281 +vn 0.0721 -0.9972 0.0194 +vn 0.1028 -0.9940 0.0376 +vn -0.0980 -0.9948 0.0290 +vn -0.1200 -0.9927 0.0118 +vn -0.0633 -0.9942 -0.0871 +vn -0.0640 -0.9932 -0.0968 +vn 0.0366 -0.9974 0.0613 +vn -0.0530 -0.9965 0.0642 +vn -0.1059 -0.9916 0.0750 +vn -0.0279 -0.9911 0.1304 +vn -0.0392 -0.9905 0.1321 +vn 0.0181 -0.9969 0.0767 +vn 0.9969 -0.0126 0.0777 +vn 0.9920 -0.0363 0.1211 +vn 0.9716 0.0587 -0.2290 +vn 0.8538 -0.0298 -0.5197 +vn 0.7769 0.0005 -0.6296 +vn 0.4979 -0.0279 -0.8668 +vn 0.4003 -0.0615 -0.9143 +vn 0.0784 -0.0227 -0.9967 +vn -0.1192 -0.0704 -0.9904 +vn -0.3569 -0.0301 -0.9337 +vn -0.6670 -0.0801 -0.7408 +vn -0.6987 -0.0220 -0.7151 +vn -0.8539 0.1547 -0.4969 +vn -0.9611 -0.0786 -0.2648 +vn -0.9777 -0.0471 -0.2046 +vn -0.9686 -0.0405 0.2454 +vn -0.9697 0.0098 0.2441 +vn -0.8057 -0.0375 0.5911 +vn -0.6911 -0.0724 0.7191 +vn -0.6117 -0.1403 0.7785 +vn -0.2033 -0.0639 0.9770 +vn -0.1670 -0.0248 0.9856 +vn 0.1680 0.1140 0.9792 +vn 0.3483 -0.0652 0.9351 +vn 0.6318 -0.0241 0.7748 +vn 0.7619 -0.0556 0.6453 +vn 0.9199 -0.0780 0.3843 +vn 0.0080 -0.9999 -0.0134 +vn 0.0174 -0.9997 -0.0159 +vn 0.0043 -0.9999 -0.0131 +vn 0.0286 -0.9995 -0.0115 +vn 0.0010 -0.9999 -0.0146 +vn 0.0327 -0.9995 0.0047 +vn -0.0044 -0.9997 -0.0249 +vn -0.0256 -0.9992 -0.0295 +vn -0.0203 -0.9990 -0.0393 +vn -0.0653 -0.9978 -0.0071 +vn -0.0239 -0.9997 0.0086 +vn -0.2354 -0.9710 0.0413 +vn -0.0175 -0.9996 0.0228 +vn -0.0681 -0.9738 0.2171 +vn -0.0103 -0.9990 0.0424 +vn -0.0426 -0.9955 0.0846 +vn 0.0146 -0.9998 0.0161 +vn 0.0187 -0.9998 0.0028 +vn 0.0241 -0.9996 0.0167 +vn 0.0130 -0.9997 0.0188 +vn -0.0594 -0.9980 0.0199 +vn 0.0290 0.0457 -0.9985 +vn -0.3806 -0.6323 -0.6748 +vn -0.1587 -0.7816 -0.6032 +vn -0.0732 -0.8219 -0.5649 +vn 0.4137 -0.7358 -0.5361 +vn 0.1928 -0.8693 -0.4552 +vn 0.6661 -0.3097 -0.6786 +vn 0.5352 -0.7969 -0.2800 +vn 0.9442 -0.1729 0.2805 +vn 0.2431 -0.8155 0.5253 +vn -0.1383 -0.8566 0.4971 +vn -0.6756 -0.2591 0.6903 +vn -0.5907 -0.7374 0.3275 +vn -0.5704 -0.7924 0.2165 +vn -0.7741 0.4212 -0.4726 +vn -0.4752 -0.5451 -0.6907 +vn 0.1242 -0.9000 -0.4178 +vn 0.6712 -0.2927 -0.6810 +vn 0.9763 0.1493 -0.1564 +vn 0.5216 -0.7452 0.4155 +vn 0.6421 -0.3240 0.6948 +vn 0.0789 0.2713 0.9593 +vn -0.5157 -0.8416 0.1606 +vn 0.4969 -0.8642 0.0785 +vn 0.9637 0.1432 -0.2252 +vn 0.5006 -0.7327 -0.4611 +vn -0.0036 -0.1615 0.9869 +vn 0.0112 -0.0946 0.9954 +vn -0.0117 0.1169 0.9931 +vn 0.0036 0.1790 0.9838 +vn 0.0016 0.2672 0.9636 +vn -0.0028 0.2653 0.9642 +vn -0.0862 0.7920 -0.6045 +vn 0.0538 0.7649 -0.6419 +vn -0.0029 0.9525 -0.3046 +vn 0.0014 0.9524 -0.3049 +vn 0.0041 1.0000 -0.0073 +vn 0.0133 0.9998 -0.0133 +vn 0.0082 0.9999 -0.0099 +vn -0.0089 -0.9999 -0.0097 +vn 0.0016 -1.0000 -0.0029 +vn -0.0045 -1.0000 -0.0068 +vn 0.0115 -0.9063 -0.4225 +vn 0.0116 -0.8330 -0.5532 +vn 0.0224 -0.8928 -0.4499 +vn 0.0118 -0.9734 -0.2287 +vn 0.0279 -0.8132 -0.5813 +vn -0.0178 -0.9782 -0.2070 +vn -0.0071 -0.9904 -0.1379 +vn 0.0518 -0.9719 -0.2294 +vn -0.2133 -0.1570 -0.9643 +vn 0.0174 -0.5217 -0.8529 +vn -0.0078 -0.6620 -0.7495 +vn -0.0056 -0.5372 -0.8434 +vn 0.0180 -0.2804 -0.9597 +vn -0.0079 -0.2003 -0.9797 +vn 0.0140 0.1205 -0.9926 +vn -0.0106 0.1286 -0.9916 +vn -0.0026 0.3839 -0.9234 +vn 0.0131 0.4453 -0.8953 +vn -0.0066 0.6185 -0.7857 +vn 0.0014 0.6686 -0.7436 +vn 0.0017 0.9897 -0.1430 +vn -0.0014 0.9906 -0.1370 +vn 0.9988 0.0422 -0.0239 +vn 0.9980 0.0538 -0.0341 +vn 0.9989 0.0373 -0.0274 +vn 0.9998 0.0113 -0.0148 +vn 0.9808 0.1755 -0.0854 +vn 0.9890 -0.0385 -0.1427 +vn 0.9998 -0.0197 -0.0051 +vn 0.9995 -0.0234 -0.0214 +vn 0.9974 -0.0642 -0.0312 +vn 0.9984 -0.0523 -0.0201 +vn 0.9992 -0.0373 -0.0143 +vn 0.9998 -0.0114 -0.0167 +vn 0.9985 0.0250 -0.0477 +vn 0.9228 0.0940 -0.3736 +vn 0.9841 -0.0422 -0.1727 +vn 0.8358 0.0273 -0.5483 +vn 0.8941 0.4069 -0.1873 +vn 0.1214 0.7088 -0.6949 +vn 0.6942 0.1824 -0.6963 +vn 0.7425 -0.1565 -0.6513 +vn 0.7359 -0.1599 -0.6580 +vn 0.7312 -0.2812 -0.6215 +vn 0.1094 -0.9694 -0.2198 +vn -0.7618 -0.6172 -0.1970 +vn -0.7922 -0.5563 -0.2508 +vn -0.8171 -0.4900 -0.3037 +vn -0.8336 -0.4292 -0.3478 +vn -0.6586 -0.3518 -0.6652 +vn -0.0075 -0.4346 -0.9006 +vn -0.9100 -0.0319 -0.4134 +vn -0.7093 0.0787 -0.7005 +vn -0.9030 -0.0297 -0.4287 +vn -0.7561 0.1592 -0.6348 +vn -0.9644 0.0677 -0.2556 +vn -0.1808 0.7392 -0.6488 +vn -0.8928 0.4118 -0.1826 +vn -0.9986 0.0465 -0.0268 +vn -0.9809 0.1727 -0.0891 +vn 0.7425 0.1260 0.6579 +vn 0.7447 0.1057 0.6590 +vn 0.7732 -0.0445 0.6326 +vn 0.7712 -0.0798 0.6316 +vn 0.6582 0.1941 0.7274 +vn 0.6626 0.1935 0.7236 +vn 0.6629 0.7484 0.0211 +vn -0.7616 -0.1013 0.6401 +vn -0.7646 -0.0930 0.6378 +vn -0.7193 0.1206 0.6842 +vn -0.7572 0.0372 0.6522 +vn -0.6555 0.1966 0.7292 +vn -0.6563 0.1964 0.7285 +vn -0.6677 0.7439 0.0275 +vn -0.0012 0.0170 -0.9999 +vn -0.0017 0.0182 -0.9998 +vn -0.0002 0.0141 -0.9999 +vn 0.0002 0.0130 -0.9999 +vn -0.0001 -0.0049 -1.0000 +vn -0.0001 -0.0050 -1.0000 +vn -0.0001 -0.0051 -1.0000 +vn -0.0016 -0.2657 0.9641 +vn 0.0036 -0.2635 0.9646 +vn -0.0144 -0.9998 -0.0132 +vn 0.6551 -0.1947 0.7300 +vn 0.6581 -0.1939 0.7275 +vn 0.6678 -0.7438 0.0269 +vn -0.6562 -0.1906 0.7301 +vn -0.6625 -0.1897 0.7246 +vn -0.6625 -0.7488 0.0210 +vn -0.4263 0.3119 -0.8491 +vn -0.0762 0.5377 -0.8397 +vn -0.0016 0.5358 -0.8444 +vn 0.0085 0.3767 -0.9263 +vn -0.0017 0.5376 -0.8432 +vn -0.0031 0.5384 -0.8427 +vn -0.1229 0.5376 -0.8342 +vn -0.0012 0.5331 -0.8460 +vn 0.0045 -0.0441 -0.9990 +vn -0.4242 -0.0714 -0.9028 +vn 0.0027 -0.4120 -0.9112 +vn -0.0005 -0.4183 -0.9083 +vn -0.0009 0.0077 1.0000 +vn -0.0029 0.0022 1.0000 +vn -0.0037 -0.0001 1.0000 +vn -0.0000 -0.0000 1.0000 +vn -0.0001 0.0099 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.6418 -0.7669 0.0014 +vn -0.7082 -0.7055 -0.0256 +vn -0.5297 -0.8471 0.0424 +vn -0.7588 -0.6495 -0.0479 +vn 0.1097 -0.9938 -0.0207 +vn 0.1460 -0.9893 0.0025 +vn 0.0657 -0.9967 -0.0486 +vn 0.1837 -0.9826 0.0268 +vn 0.8782 -0.4782 -0.0092 +vn 0.8753 -0.4836 -0.0066 +vn 0.8770 -0.4804 -0.0081 +vn 0.8730 -0.4877 -0.0047 +vn 0.7818 0.6231 0.0247 +vn 0.8475 0.5300 -0.0294 +vn 0.8237 0.5670 -0.0085 +vn 0.7607 0.6478 0.0401 +vn -0.3951 0.9186 -0.0055 +vn -0.3398 0.9401 -0.0267 +vn -0.3570 0.9339 -0.0202 +vn -0.4172 0.9088 0.0032 +vn -0.9927 0.1131 0.0420 +vn -0.9987 0.0503 0.0090 +vn -0.9955 0.0898 0.0297 +vn -0.9993 0.0364 0.0017 +vn -0.7519 -0.6580 -0.0413 +vn -0.8766 -0.4809 0.0167 +vn -0.9057 -0.4226 0.0340 +vn -0.6881 -0.7226 -0.0651 +vn -0.0004 -1.0000 -0.0050 +vn -0.0573 -0.9980 0.0254 +vn -0.1159 -0.9916 0.0568 +vn 0.0711 -0.9965 -0.0432 +vn 0.6599 -0.7490 0.0600 +vn 0.8930 -0.4492 -0.0272 +vn 0.9549 -0.2966 0.0140 +vn 0.9490 -0.3130 -0.0370 +vn 0.9911 -0.1318 0.0172 +vn 0.7876 0.6160 -0.0159 +vn 0.7843 0.6203 -0.0139 +vn 0.7851 0.6193 -0.0143 +vn 0.7883 0.6150 -0.0163 +vn 0.0600 0.9977 0.0321 +vn -0.2060 0.9778 -0.0394 +vn -0.0160 0.9998 0.0118 +vn -0.2664 0.9622 -0.0558 +vn -0.9787 0.2020 -0.0358 +vn -0.8967 0.4417 0.0299 +vn -0.8594 0.5089 0.0496 +vn -0.9922 0.1095 -0.0596 +vn 0.0072 0.9559 -0.2936 +vn 0.0299 0.8804 -0.4733 +vn 0.0301 0.8208 -0.5704 +vn 0.0572 0.7282 -0.6829 +vn 0.0208 0.9186 -0.3947 +vn 0.0332 0.8677 -0.4959 +vn -0.2055 0.9229 0.3256 +vn -0.0193 0.9998 -0.0111 +vn 0.0157 0.9406 -0.3392 +vn 0.0622 0.6909 -0.7203 +vn 0.3121 0.8647 -0.3935 +vn 0.0869 0.9054 -0.4156 +vn 0.5780 0.7879 -0.2124 +vn -0.7093 0.3513 -0.6111 +vn -0.5834 0.1156 -0.8039 +vn -0.7065 -0.1820 -0.6839 +vn -0.7149 -0.2602 -0.6490 +vn -0.7428 -0.3080 -0.5945 +vn -0.8051 0.3345 -0.4898 +vn -0.7021 0.6094 -0.3683 +vn 0.7662 0.3487 -0.5397 +vn 0.7623 0.3534 -0.5422 +vn 0.7639 0.3516 -0.5412 +vn 0.7479 0.2570 -0.6120 +vn 0.7461 0.2356 -0.6227 +vn 0.6132 -0.2579 -0.7466 +vn 0.7149 -0.3397 -0.6112 +vn 0.7750 -0.0360 -0.6309 +vn 0.7623 0.0430 -0.6458 +vn 0.5727 0.7687 -0.2849 +vn -0.6861 0.4990 -0.5294 +vn -0.7259 0.6641 -0.1790 +vn 0.7824 0.6211 -0.0467 +vn 0.6854 -0.7257 0.0595 +vn 0.7288 -0.6708 0.1375 +vn 0.7638 -0.6092 0.2132 +vn 0.7885 -0.5478 0.2798 +vn -0.6508 -0.5166 0.5564 +vn 0.8253 -0.3110 0.4713 +vn 0.8442 -0.2463 0.4761 +vn 0.8566 -0.1936 0.4784 +vn 0.8674 -0.1338 0.4793 +vn 0.5007 -0.1626 0.8502 +vn 0.8823 0.0418 0.4688 +vn -0.1155 0.2908 0.9498 +vn 0.7787 0.2397 0.5799 +vn 0.8026 0.2644 0.5347 +vn 0.8341 0.3003 0.4627 +vn 0.8490 0.3195 0.4208 +vn -0.5385 0.6303 0.5592 +vn 0.9994 0.0325 0.0125 +vn 0.9998 0.0220 0.0018 +vn 0.9996 0.0283 0.0084 +vn 0.9995 0.0073 0.0304 +vn 1.0000 0.0044 0.0089 +vn 0.9996 0.0131 0.0256 +vn 0.9999 -0.0134 0.0083 +vn 0.9055 0.2329 0.3547 +vn 0.9978 0.0418 0.0522 +vn 0.9990 0.0370 0.0249 +vn 0.9938 -0.0635 0.0909 +vn 0.9902 -0.0735 0.1187 +vn 0.9998 -0.0126 -0.0183 +vn 0.8930 0.2471 0.3762 +vn -0.7701 0.6363 -0.0462 +vn -0.7072 -0.6837 0.1801 +vn -0.7070 -0.6820 0.1872 +vn -0.7046 -0.7076 0.0537 +vn -0.9936 0.0895 0.0686 +vn -0.8820 0.4631 0.0868 +vn -0.9797 0.1957 0.0432 +vn -0.5644 0.7095 0.4220 +vn 0.0163 0.7713 0.6363 +vn 0.1204 0.6057 0.7865 +vn 0.2381 0.6391 0.7313 +vn -0.9057 0.1839 0.3819 +vn -0.7415 0.1730 0.6483 +vn -0.8962 0.1865 0.4025 +vn -0.8026 0.0622 0.5933 +vn -0.8153 -0.0800 0.5735 +vn -0.8117 -0.0551 0.5815 +vn -0.8191 -0.1682 0.5484 +vn 0.0060 -0.0900 0.9959 +vn -0.0488 -0.2843 0.9575 +vn -0.1066 -0.2202 0.9696 +vn -0.9031 -0.2024 0.3788 +vn 0.2089 -0.7148 0.6674 +vn 0.1068 -0.6693 0.7353 +vn 0.0015 -0.8383 0.5452 +vn -0.6974 -0.6465 0.3094 +vn 0.0272 0.9843 0.1745 +vn -0.0054 0.9958 0.0918 +vn -0.0009 0.9721 0.2346 +vn 0.0245 0.9352 0.3532 +vn -0.0084 0.8593 0.5115 +vn -0.0188 0.6925 0.7212 +vn -0.0055 0.4924 0.8703 +vn 0.0091 0.2437 0.9698 +vn -0.0094 0.2398 0.9708 +vn -0.0079 -0.0885 0.9960 +vn -0.0120 -0.4138 0.9103 +vn 0.0008 -0.6482 0.7615 +vn 0.0098 -0.8175 0.5759 +vn -0.0044 -0.9624 0.2716 +vn 0.0018 -0.9603 0.2791 +vn 0.0023 -0.9919 0.1267 +vn 0.0057 -0.9910 0.1340 +vn -0.0195 0.9994 0.0278 +vn -0.0149 0.9996 0.0227 +vn -0.0023 -0.5387 -0.8425 +vn 0.0018 -0.5392 -0.8422 +vn 0.0044 -0.5403 -0.8415 +vn -0.0061 -0.5393 -0.8421 +vn 0.0001 -0.5331 -0.8461 +vn 0.9462 0.3209 -0.0422 +vn 0.9395 0.3408 -0.0335 +vn 0.9332 0.3583 -0.0258 +vn -0.9898 -0.1287 0.0616 +vn -0.4554 -0.8901 -0.0153 +vn -0.5573 -0.8281 -0.0604 +vn -0.5282 -0.8478 -0.0472 +vn -0.4194 -0.9078 -0.0000 +vn 0.7020 -0.7119 0.0195 +vn 0.7329 -0.6804 -0.0021 +vn 0.7119 -0.7022 0.0128 +vn 0.7451 -0.6668 -0.0110 +vn 0.9301 0.3666 -0.0222 +vn 0.1627 0.9851 -0.0556 +vn 0.1524 0.9878 0.0320 +vn 0.4697 0.8809 0.0584 +vn -0.0596 0.9976 -0.0349 +vn -0.2213 0.9733 0.0608 +vn -0.9395 0.3295 -0.0936 +vn -0.9114 0.4061 -0.0665 +vn -0.9247 0.3725 -0.0786 +vn -0.9066 0.4174 -0.0624 +vn 0.9739 0.2249 -0.0288 +vn 0.9990 0.0350 0.0295 +vn 0.9983 -0.0315 0.0496 +vn 0.9514 0.3032 -0.0533 +vn 0.2167 0.9757 0.0334 +vn 0.5821 0.8107 0.0627 +vn 0.2957 0.9521 -0.0776 +vn -0.0074 0.9986 -0.0520 +vn -0.2376 0.9669 0.0926 +vn -0.9396 0.3394 -0.0453 +vn -0.9354 0.3513 -0.0396 +vn -0.9370 0.3469 -0.0417 +vn -0.9344 0.3543 -0.0381 +vn -0.6348 -0.7720 -0.0340 +vn -0.7097 -0.7045 0.0006 +vn -0.6619 -0.7493 -0.0219 +vn -0.7433 -0.6688 0.0175 +vn 0.5929 -0.8046 -0.0314 +vn 0.4695 -0.8827 0.0192 +vn 0.4132 -0.9097 0.0408 +vn 0.6433 -0.7637 -0.0536 +vn -0.0010 -0.9691 -0.2468 +vn 0.0129 -0.9557 -0.2939 +vn 0.4004 -0.9073 -0.1285 +vn 0.3891 -0.8223 -0.4153 +vn -0.0045 -0.8495 -0.5275 +vn 0.0006 -0.8010 -0.5987 +vn -0.0451 -0.6551 -0.7542 +vn -0.2743 -0.8275 -0.4898 +vn -0.3645 -0.9046 -0.2210 +vn -0.7690 -0.3459 -0.5376 +vn -0.8004 -0.3085 -0.5140 +vn -0.7871 -0.3248 -0.5244 +vn 0.5404 -0.4363 -0.7194 +vn 0.7575 -0.4127 -0.5058 +vn 0.6532 -0.6608 -0.3697 +vn -0.5970 -0.7337 -0.3243 +vn 0.7940 -0.6063 -0.0432 +vn -0.7732 -0.6322 -0.0501 +vn -0.0010 -0.9994 0.0335 +vn 0.0133 -0.9986 0.0517 +vn -0.9497 -0.0284 -0.3119 +vn -0.9781 0.0069 -0.2078 +vn -0.9623 0.0073 -0.2719 +vn -0.9695 0.0063 -0.2451 +vn -0.9614 -0.0312 0.2732 +vn -0.9844 -0.0170 0.1754 +vn -0.8783 -0.0154 0.4779 +vn -0.8711 0.0178 0.4909 +vn -0.5163 0.0114 -0.8563 +vn -0.6866 -0.0048 -0.7270 +vn -0.7523 0.0960 -0.6518 +vn -0.9977 -0.0362 -0.0567 +vn -0.9945 -0.0670 -0.0806 +vn -0.9989 -0.0182 -0.0427 +vn -0.9997 0.0177 -0.0147 +vn -0.2212 -0.0311 -0.9747 +vn 0.2135 0.0427 -0.9760 +vn 0.4764 0.0043 -0.8792 +vn 0.6353 0.0474 -0.7708 +vn 0.6846 -0.0246 -0.7285 +vn 0.9841 -0.0469 -0.1711 +vn 0.9908 0.0026 -0.1356 +vn 0.9930 0.0327 -0.1138 +vn 0.9937 0.0782 -0.0806 +vn 0.8712 -0.0246 0.4904 +vn 0.8707 -0.0223 0.4913 +vn 0.9651 -0.0056 0.2619 +vn 0.9688 -0.0054 0.2478 +vn 0.9623 -0.0014 -0.2720 +vn 0.9692 -0.0008 -0.2463 +vn 0.8675 0.0141 -0.4972 +vn 0.8671 0.0124 -0.4979 +vn 0.9961 -0.0350 0.0808 +vn 0.9962 -0.0406 0.0769 +vn 0.9962 -0.0434 0.0750 +vn 0.9963 -0.0504 0.0702 +vn 0.7112 -0.0043 0.7030 +vn 0.7839 0.1019 0.6125 +vn 0.5375 0.0183 0.8430 +vn 0.2856 -0.0307 0.9578 +vn 0.0549 -0.0188 0.9983 +vn -0.0526 -0.1174 0.9917 +vn -0.6376 0.0275 0.7699 +vn -0.5644 0.1230 0.8163 +vn -0.6816 -0.0381 0.7308 +vn -0.7360 -0.1330 0.6638 +vn -0.9959 0.0517 0.0746 +vn -0.9807 0.1305 0.1454 +vn -0.0002 -1.0000 -0.0009 +vn 0.0014 -1.0000 -0.0012 +vn 0.0015 -1.0000 -0.0022 +vn -0.0004 -1.0000 0.0002 +vn -0.0009 -1.0000 0.0010 +vn -0.0027 -1.0000 -0.0021 +vn 0.6637 0.0173 0.7478 +vn 0.6228 0.0029 0.7823 +vn 0.6327 0.0063 0.7744 +vn 0.6711 0.0199 0.7411 +vn 0.9829 -0.0240 0.1825 +vn 0.9902 -0.0158 0.1390 +vn 0.9985 0.0199 -0.0512 +vn 0.9953 0.0277 -0.0927 +vn 0.6541 0.0011 -0.7564 +vn 0.7069 -0.4207 -0.5686 +vn 0.7106 -0.1774 -0.6809 +vn 0.6327 0.0084 -0.7744 +vn -0.1867 0.0004 -0.9824 +vn -0.1955 -0.0022 -0.9807 +vn -0.1887 -0.0002 -0.9820 +vn -0.1974 -0.0028 -0.9803 +vn -0.8563 -0.0029 -0.5164 +vn -0.8601 -0.0007 -0.5100 +vn -0.8729 0.0065 -0.4878 +vn -0.8763 0.0086 -0.4816 +vn -0.9085 -0.0048 0.4179 +vn -0.9114 -0.0070 0.4115 +vn -0.9107 -0.0065 0.4129 +vn -0.9078 -0.0043 0.4194 +vn -0.2839 0.0098 0.9588 +vn -0.2168 -0.1856 0.9584 +vn -0.2705 0.0058 0.9627 +vn 0.0096 -0.5024 0.8646 +vn -0.0236 -0.7684 -0.6396 +vn 0.0190 -0.8124 -0.5827 +vn -0.1188 -0.6497 -0.7508 +vn 0.6208 -0.5753 -0.5325 +vn 0.5441 -0.7825 -0.3027 +vn 0.7798 -0.6083 0.1481 +vn 0.6134 -0.7077 0.3507 +vn 0.7228 -0.6659 0.1848 +vn 0.4293 -0.7235 0.5407 +vn -0.1197 -0.6014 0.7899 +vn -0.6098 -0.7354 0.2955 +vn -0.5911 -0.7593 0.2720 +vn -0.6475 -0.6794 0.3452 +vn -0.6719 -0.6360 0.3796 +vn -0.5921 -0.7290 -0.3436 +vn -0.5970 -0.7207 -0.3524 +vn -0.6048 -0.7072 -0.3661 +vn -0.6087 -0.7001 -0.3733 +vn -0.1631 -0.5843 -0.7950 +vn -0.0008 1.0000 -0.0020 +vn -0.0005 1.0000 -0.0034 +vn 0.0012 1.0000 -0.0050 +vn -0.0045 1.0000 0.0020 +vn -0.0045 1.0000 -0.0014 +vn -0.0053 1.0000 -0.0008 +vn -0.0046 1.0000 0.0025 +vn -0.0013 1.0000 -0.0022 +vn -0.0007 1.0000 -0.0018 +vn -0.0027 0.9999 0.0141 +vn 0.0098 0.9999 0.0136 +vn 0.0039 0.9998 0.0201 +vn 0.0041 0.9999 -0.0097 +vn 0.0187 0.9997 -0.0151 +vn 0.0175 0.9997 -0.0167 +vn 0.0041 1.0000 0.0032 +vn 0.0092 0.9999 0.0063 +vn -0.0038 1.0000 0.0055 +vn -0.0026 1.0000 0.0032 +vn 0.0048 1.0000 0.0010 +vn -0.0041 0.9999 0.0115 +vn 0.8539 0.1106 0.5086 +vn 0.8537 0.1272 0.5050 +vn 0.8441 -0.0385 0.5348 +vn 0.8414 -0.0578 0.5373 +vn 0.3437 0.0608 0.9371 +vn 0.3436 0.0599 0.9372 +vn 0.3446 0.0671 0.9363 +vn 0.3448 0.0683 0.9362 +vn -0.2859 -0.1775 0.9417 +vn -0.2948 -0.1430 0.9448 +vn -0.3462 0.1055 0.9322 +vn -0.3516 0.1401 0.9256 +vn -0.7776 -0.0989 0.6209 +vn -0.7751 -0.0608 0.6289 +vn -0.7750 -0.2610 0.5755 +vn -0.7734 -0.2784 0.5696 +vn -0.9087 0.4109 0.0729 +vn -0.8765 -0.4507 -0.1693 +vn -0.8481 0.3115 -0.4286 +vn -0.5924 -0.3782 -0.7114 +vn -0.4475 0.3096 -0.8390 +vn -0.0340 -0.2299 -0.9726 +vn -0.0251 -0.1940 -0.9807 +vn 0.0476 0.1050 -0.9933 +vn 0.0577 0.1470 -0.9875 +vn 0.5719 -0.2228 -0.7894 +vn 0.5805 -0.1928 -0.7911 +vn 0.6315 0.0853 -0.7707 +vn 0.6347 0.1255 -0.7625 +vn 0.9776 0.0295 -0.2083 +vn 0.9753 0.0592 -0.2128 +vn 0.9691 -0.1771 -0.1716 +vn 0.9658 -0.1981 -0.1673 +vn 0.0327 0.9937 -0.1068 +vn -0.0157 0.9942 -0.1063 +vn 0.0619 0.9924 -0.1064 +vn 0.0411 0.9985 -0.0363 +vn -0.0323 0.9977 -0.0597 +vn 0.0251 0.9997 0.0057 +vn 0.0264 0.9996 0.0054 +vn 0.0300 0.9992 0.0259 +vn 0.0007 0.9948 0.1017 +vn 0.0397 0.9980 0.0495 +vn -0.0245 0.9994 0.0236 +vn -0.0371 0.9970 0.0676 +vn -0.0188 0.9996 0.0200 +vn -0.0292 0.9992 -0.0260 +vn -0.0170 0.9998 0.0038 +vn 0.2792 0.7894 0.5467 +vn 0.6042 0.6935 0.3925 +vn 0.6289 0.7663 0.1315 +vn 0.1614 0.7988 -0.5795 +vn -0.1056 0.6299 -0.7694 +vn -0.3099 0.7788 -0.5454 +vn -0.6347 0.7502 0.1853 +vn -0.5556 0.6458 0.5238 +vn -0.2126 0.7962 0.5664 +vn 0.0211 0.6546 0.7557 +vn 0.5561 0.7662 -0.3221 +vn 0.4901 0.6591 -0.5704 +vn 0.2293 0.6608 -0.7147 +vn -0.6002 0.7668 -0.2276 +vn -0.7520 0.6406 -0.1554 +vn -0.2638 0.6252 0.7345 +vn 0.4339 0.6243 0.6496 +vn 0.7392 0.6426 -0.2014 +vn -0.3696 0.5927 -0.7156 +vn -0.6261 0.6093 -0.4866 +vn -0.7986 0.5663 0.2040 +vn 0.8007 0.5698 0.1848 +vn 0.0971 0.5473 0.8313 +vn 0.7213 0.5437 -0.4290 +vn -0.8004 0.4754 0.3653 +vn 0.4173 0.5157 0.7483 +vn 0.4382 0.5203 -0.7330 +vn -0.8377 0.4934 -0.2342 +vn -0.4004 0.5057 0.7642 +vn 0.7296 0.5001 0.4664 +vn 0.0350 0.5036 -0.8632 +vn -0.5057 0.4672 -0.7253 +vn 0.8676 0.4971 0.0142 +vn 0.9993 0.0380 -0.0064 +vn 0.9995 0.0318 0.0000 +vn 0.9993 0.0377 -0.0061 +vn 0.9989 0.0442 -0.0128 +vn 0.5398 0.0195 -0.8416 +vn 0.4744 -0.0080 -0.8803 +vn 0.4493 0.0230 -0.8931 +vn 0.6038 -0.0286 -0.7966 +vn 0.3293 -0.0350 -0.9436 +vn -0.4993 0.0458 -0.8652 +vn -0.5294 0.0132 -0.8483 +vn -0.5298 0.0128 -0.8480 +vn -0.5591 -0.0203 -0.8289 +vn -0.9994 0.0359 0.0000 +vn -0.9997 0.0204 0.0159 +vn -0.9997 0.0205 0.0158 +vn -0.9995 0.0048 0.0319 +vn -0.4918 0.0050 0.8707 +vn -0.4923 0.0045 0.8704 +vn -0.4998 -0.0050 0.8661 +vn -0.4846 0.0140 0.8746 +vn 0.4992 0.0461 0.8652 +vn 0.5259 0.0155 0.8504 +vn 0.5272 0.0140 0.8496 +vn 0.5520 -0.0156 0.8337 +vn -0.9803 -0.1594 0.1164 +vn -0.9766 -0.1837 0.1116 +vn -0.9825 0.0929 0.1612 +vn -0.9789 0.1201 0.1654 +vn -0.6349 -0.1105 0.7646 +vn -0.6385 -0.1525 0.7544 +vn -0.5767 0.1862 0.7954 +vn -0.5661 0.2210 0.7942 +vn -0.0297 -0.2245 0.9740 +vn -0.0377 -0.2623 0.9642 +vn 0.0408 0.1153 0.9925 +vn 0.0516 0.1680 0.9844 +vn 0.6514 0.0672 0.7558 +vn 0.6631 0.0004 0.7485 +vn 0.6746 -0.3320 0.6593 +vn 0.6713 -0.3644 0.6455 +vn 0.8992 0.3840 0.2099 +vn 0.8407 -0.5397 -0.0454 +vn 0.7602 0.4987 -0.4164 +vn 0.5709 -0.4003 -0.7168 +vn 0.3807 0.3450 -0.8579 +vn -0.0014 -0.4444 -0.8958 +vn -0.2754 0.4452 -0.8520 +vn -0.6401 -0.4465 -0.6252 +vn -0.7934 0.2608 -0.5501 +vn 0.7704 0.0348 -0.6366 +vn 0.8812 -0.0708 -0.4673 +vn 0.6494 -0.0242 -0.7600 +vn 0.2900 0.0613 -0.9551 +vn -0.0188 -0.0236 -0.9995 +vn -0.2399 0.0248 -0.9705 +vn -0.3603 -0.0477 -0.9316 +vn -0.9536 0.0363 -0.2988 +vn -0.9585 0.0239 -0.2840 +vn -0.9574 0.0268 -0.2875 +vn -0.9624 0.0132 -0.2713 +vn -0.7789 0.0306 0.6264 +vn -0.8406 -0.0268 0.5409 +vn -0.8053 0.0074 0.5929 +vn -0.7437 0.0592 0.6659 +vn -0.0338 0.0432 0.9985 +vn -0.2726 -0.0648 0.9600 +vn -0.1304 -0.0000 0.9915 +vn 0.0956 0.1000 0.9904 +vn 0.5675 -0.0856 0.8189 +vn 0.9275 0.0930 0.3622 +vn 0.9502 0.0533 0.3070 +vn 0.9419 0.0688 0.3288 +vn 0.9663 0.0177 0.2567 +vn -0.0016 1.0000 -0.0036 +vn -0.0218 0.9876 -0.1553 +vn -0.0530 0.9945 -0.0902 +vn -0.0922 0.9934 -0.0687 +vn -0.1051 0.9923 -0.0649 +vn 0.0172 0.9919 -0.1256 +vn -0.0806 0.9967 -0.0020 +vn -0.0841 0.9962 0.0244 +vn 0.0988 0.9951 -0.0015 +vn 0.0602 0.9978 -0.0280 +vn 0.0443 0.9966 -0.0700 +vn 0.0433 0.9959 -0.0794 +vn -0.0593 0.9969 0.0523 +vn -0.0514 0.9970 0.0579 +vn 0.0673 0.9959 0.0609 +vn 0.0435 0.9964 0.0731 +vn 0.0684 0.9974 0.0240 +vn 0.0147 0.9957 0.0915 +vn -0.0117 0.9975 0.0692 +vn -0.8626 0.0664 -0.5015 +vn -0.9685 0.0176 -0.2485 +vn -0.9977 0.0626 -0.0266 +vn -0.7819 0.0295 -0.6227 +vn -0.6940 0.0549 -0.7178 +vn -0.6543 0.0249 -0.7558 +vn -0.1909 0.0518 -0.9802 +vn -0.1837 0.0458 -0.9819 +vn 0.0900 0.0532 -0.9945 +vn -0.0004 0.0335 -0.9994 +vn 0.4683 0.0201 -0.8834 +vn 0.5980 0.0693 -0.7985 +vn 0.8362 0.0246 -0.5479 +vn 0.8885 0.0673 -0.4540 +vn 0.9631 -0.0952 -0.2516 +vn 0.9991 0.0371 -0.0227 +vn 0.9670 -0.0008 0.2549 +vn 0.8938 0.0561 0.4450 +vn 0.7568 0.0165 0.6535 +vn 0.6332 0.0556 0.7720 +vn 0.4084 0.0102 0.9127 +vn 0.2014 0.0534 0.9780 +vn 0.0151 0.0199 0.9997 +vn -0.2426 0.0609 0.9682 +vn -0.2685 0.0412 0.9624 +vn -0.5637 0.0552 0.8241 +vn -0.7008 0.2216 0.6781 +vn -0.8586 0.0515 0.5101 +vn -0.8240 -0.2190 0.5225 +vn -0.9700 -0.0176 0.2426 +vn -0.0273 0.9996 -0.0101 +vn -0.0179 0.9997 -0.0151 +vn -0.0053 0.9999 -0.0111 +vn -0.0020 0.9999 -0.0103 +vn 0.0001 0.9999 -0.0102 +vn 0.0009 0.9999 -0.0112 +vn 0.0126 0.9996 -0.0251 +vn 0.1591 0.9746 -0.1577 +vn 0.0467 0.9982 -0.0383 +vn 0.0253 0.9997 0.0031 +vn 0.0173 0.9998 0.0087 +vn -0.0356 0.9993 0.0114 +vn -0.0136 0.9996 0.0264 +vn 0.0022 0.9996 0.0298 +vn -0.0149 0.9997 0.0192 +vn -0.0229 0.9995 0.0212 +vn 0.0122 0.9999 0.0079 +vn 0.0131 0.9998 0.0126 +vn 0.0194 0.9998 0.0066 +vn 0.0145 0.9998 0.0164 +vn 0.8464 0.4265 0.3188 +vn 0.6350 0.6820 0.3628 +vn 0.8606 0.3965 0.3197 +vn 0.1327 0.6043 0.7856 +vn 0.2562 0.8173 0.5161 +vn 0.1725 0.6783 0.7142 +vn 0.0596 0.7974 -0.6004 +vn -0.3087 0.8155 -0.4895 +vn -0.2202 0.7002 -0.6792 +vn 0.9268 -0.2084 -0.3125 +vn 0.1336 0.8345 -0.5346 +vn -0.0821 0.7040 -0.7055 +vn -0.3427 0.8525 -0.3947 +vn -0.7909 -0.2770 -0.5457 +vn -0.7371 0.5304 -0.4188 +vn -0.8029 0.5738 -0.1617 +vn -0.7947 0.5687 -0.2123 +vn 0.6226 0.4255 0.6568 +vn 0.6326 0.5092 0.5835 +vn 0.3851 0.8587 -0.3381 +vn 0.3871 0.2989 -0.8723 +vn -0.8140 0.5789 0.0478 +vn -0.7451 -0.4735 0.4696 +vn -0.7111 0.4342 0.5530 +vn -0.2498 0.8674 0.4305 +vn -0.1758 0.0508 0.9831 +vn 0.2784 0.8490 0.4491 +vn 0.5131 0.8580 0.0250 +vn 0.1481 0.7634 0.6287 +vn -0.5210 0.8111 0.2659 +vn 0.6078 0.7941 0.0080 +vn 0.9666 0.0094 -0.2562 +vn 0.9389 -0.0158 -0.3438 +vn 0.9614 -0.0211 -0.2742 +vn 0.9782 -0.0154 -0.2071 +vn 0.9616 0.0389 0.2718 +vn 0.9844 0.0170 0.1754 +vn 0.9557 -0.0301 0.2929 +vn 0.9911 0.0056 0.1330 +vn 0.6169 -0.0242 -0.7867 +vn 0.7974 0.0561 -0.6009 +vn 0.9614 -0.0060 -0.2752 +vn 0.3953 -0.0419 -0.9176 +vn 0.3006 -0.1408 -0.9433 +vn -0.2967 0.1315 -0.9459 +vn -0.3626 0.0496 -0.9306 +vn -0.4143 -0.0190 -0.9099 +vn -0.4753 -0.1059 -0.8734 +vn -0.9005 0.1001 -0.4232 +vn -0.9362 0.0095 -0.3512 +vn -0.9930 0.0056 -0.1183 +vn -0.9845 -0.0225 0.1742 +vn -0.9119 0.0175 0.4101 +vn -0.9649 -0.0022 0.2625 +vn -0.9694 0.0067 0.2455 +vn -0.9581 -0.0076 -0.2864 +vn -0.9763 -0.0053 -0.2164 +vn -0.9610 -0.0128 -0.2762 +vn -0.9582 -0.0051 -0.2861 +vn -0.9991 -0.0042 -0.0428 +vn -0.9992 -0.0008 -0.0402 +vn -0.7896 0.0237 0.6132 +vn -0.7811 0.0052 0.6244 +vn -0.7770 -0.0035 0.6295 +vn -0.7679 -0.0220 0.6402 +vn -0.1716 0.0206 0.9850 +vn -0.1841 0.0028 0.9829 +vn -0.1644 0.0307 0.9859 +vn -0.1531 0.0466 0.9871 +vn 0.5842 0.0209 0.8113 +vn 0.5243 -0.0580 0.8495 +vn 0.7323 0.0038 0.6810 +vn 0.9040 0.0514 0.4244 +vn 0.9920 -0.0088 0.1260 +vn -0.0101 0.0698 -0.9975 +vn -0.0558 0.0566 -0.9968 +vn -0.0201 0.1027 -0.9945 +vn -0.0890 0.0101 -0.9960 +vn -0.0650 0.0103 -0.9978 +vn -0.0253 -0.0899 -0.9956 +vn -0.0470 -0.0382 -0.9982 +vn 0.0015 -0.0613 -0.9981 +vn 0.0596 0.0205 -0.9980 +vn 0.0673 -0.0280 -0.9973 +vn 0.0629 -0.0038 -0.9980 +vn 0.0248 0.0427 -0.9988 +vn 0.0224 -0.0541 -0.9983 +vn 0.0398 -0.0897 0.9952 +vn 0.1508 -0.0605 0.9867 +vn 0.2125 -0.0433 0.9762 +vn 0.0395 -0.0904 0.9951 +vn -0.9325 0.3566 0.0573 +vn -0.8061 0.5918 -0.0050 +vn -0.9407 0.3308 0.0747 +vn -0.9129 -0.4080 -0.0136 +vn -0.4623 -0.8863 0.0267 +vn -0.2458 -0.9693 0.0054 +vn -0.4411 -0.8971 0.0246 +vn -0.2236 -0.9747 0.0033 +vn 0.4170 -0.9084 0.0283 +vn 0.5968 -0.8022 0.0149 +vn 0.4293 -0.9028 0.0275 +vn 0.6068 -0.7947 0.0141 +vn 0.9471 -0.3196 0.0296 +vn 0.9989 0.0430 -0.0161 +vn 0.9585 -0.2839 0.0251 +vn 0.9967 0.0780 -0.0204 +vn 0.3834 0.9234 0.0167 +vn 0.2499 0.9682 0.0092 +vn 0.3709 0.9285 0.0163 +vn 0.2293 0.9733 0.0055 +vn -0.7816 0.6237 -0.0108 +vn 0.1122 -0.0667 0.9914 +vn 0.0625 -0.0897 0.9940 +vn 0.1266 -0.0229 0.9917 +vn -0.0296 0.1174 0.9926 +vn -0.0690 0.1076 0.9918 +vn -0.1405 0.0226 0.9898 +vn -0.1607 0.0159 0.9869 +vn 0.1529 -0.2245 0.9624 +vn -0.0037 -0.1323 0.9912 +vn -0.0679 -0.0952 0.9931 +vn -0.0925 -0.0783 0.9926 +vn 0.0954 0.0809 0.9921 +vn 0.1273 0.0593 0.9901 +vn 0.0437 0.1324 0.9902 +vn -0.9049 0.4252 0.0195 +vn -0.8963 0.4422 0.0332 +vn -0.8576 0.5069 0.0868 +vn -0.9373 0.3461 -0.0418 +vn -0.9299 -0.3672 0.0206 +vn -0.9307 -0.3653 0.0193 +vn -0.9302 -0.3664 0.0201 +vn -0.9296 -0.3681 0.0213 +vn -0.5794 -0.8149 -0.0177 +vn -0.5371 -0.8434 0.0120 +vn -0.5114 -0.8589 0.0294 +vn -0.4703 -0.8807 0.0563 +vn 0.0760 -0.9954 -0.0580 +vn 0.4114 -0.9108 -0.0338 +vn 0.2602 -0.9653 0.0205 +vn 0.6217 -0.7827 0.0295 +vn 0.7465 -0.6651 -0.0194 +vn 0.8281 -0.5585 0.0481 +vn 0.9986 0.0250 -0.0473 +vn 0.9964 0.0830 -0.0143 +vn 0.9929 0.1188 0.0062 +vn 0.9835 0.1766 0.0395 +vn 0.7083 0.7058 0.0125 +vn 0.7662 0.6419 -0.0297 +vn 0.5467 0.8370 -0.0226 +vn 0.3470 0.9366 0.0482 +vn -0.0583 0.9981 -0.0178 +vn -0.1981 0.9797 0.0302 +vn -0.3977 0.9145 -0.0740 +vn -0.7275 0.6861 0.0000 +vn -0.6745 0.7350 -0.0695 +vn -0.6762 0.7336 -0.0674 +vn -0.6217 0.7722 -0.1307 +vn -0.7033 -0.6988 0.1305 +vn -0.7531 -0.6545 0.0673 +vn -0.7515 -0.6560 0.0694 +vn -0.7988 -0.6017 0.0000 +vn 0.7275 -0.6861 0.0000 +vn 0.6745 -0.7350 -0.0695 +vn 0.6762 -0.7336 -0.0674 +vn 0.6217 -0.7722 -0.1307 +vn 0.7033 0.6988 0.1305 +vn 0.7531 0.6545 0.0673 +vn 0.7515 0.6560 0.0694 +vn 0.7988 0.6017 0.0000 +vn -0.2187 0.3613 0.9064 +vn 0.3828 0.9226 -0.0475 +vn 0.4428 0.0236 0.8963 +vn -0.3763 -0.3934 0.8388 +vn -0.9288 0.3256 0.1771 +vn -0.0726 -0.0247 -0.9971 +vn -0.0605 0.0163 -0.9980 +vn -0.0398 -0.0325 -0.9987 +vn -0.0251 -0.0623 -0.9977 +vn 0.0557 -0.0444 -0.9975 +vn 0.0144 -0.0587 -0.9982 +vn 0.0481 -0.0156 -0.9987 +vn 0.0400 0.0460 -0.9981 +vn -0.0100 0.0532 -0.9985 +vn 0.0012 0.0798 -0.9968 +vn -0.0513 0.0508 -0.9974 +vn 0.0575 0.0207 -0.9981 +vn -0.1001 -0.1754 0.9794 +vn -0.1083 -0.1923 0.9754 +vn -0.0158 -0.0017 0.9999 +vn -0.9012 -0.4331 0.0138 +vn -0.9017 -0.4321 0.0140 +vn -0.8956 -0.4397 0.0679 +vn -0.1774 -0.9841 -0.0086 +vn 0.2601 -0.9656 -0.0073 +vn 0.2393 -0.9677 0.0797 +vn 0.2851 -0.9526 0.1059 +vn 0.6490 -0.7607 -0.0092 +vn 0.9988 -0.0476 0.0118 +vn 0.9990 -0.0426 0.0124 +vn 0.9998 0.0003 0.0182 +vn 0.9998 0.0039 0.0187 +vn 0.4698 0.8763 0.1067 +vn 0.5723 0.8200 -0.0080 +vn 0.5633 0.8262 -0.0066 +vn 0.4599 0.8780 0.1326 +vn -0.6021 0.7984 0.0037 +vn -0.6337 0.7736 -0.0033 +vn -0.6063 0.7952 0.0028 +vn -0.6373 0.7706 -0.0041 +vn -0.8926 -0.4392 0.1017 +vn -0.0777 -0.1129 0.9906 +vn -0.1163 -0.0703 0.9907 +vn -0.0030 -0.1327 0.9912 +vn -0.1348 0.0278 0.9905 +vn 0.1275 -0.0448 0.9908 +vn 0.1166 -0.0639 0.9911 +vn 0.1188 0.0724 0.9903 +vn 0.1470 0.0400 0.9883 +vn 0.0467 -0.1269 0.9908 +vn -0.1346 0.0650 0.9888 +vn 0.0097 0.1266 0.9919 +vn -0.0198 0.1242 0.9921 +vn -0.7507 -0.6593 -0.0416 +vn -0.4722 -0.8814 -0.0151 +vn -0.6041 -0.7942 0.0650 +vn -0.3668 -0.9295 0.0373 +vn -0.0978 -0.9905 -0.0965 +vn 0.5130 -0.8545 0.0813 +vn 0.5536 -0.8314 0.0472 +vn 0.5433 -0.8377 0.0561 +vn 0.5905 -0.8069 0.0146 +vn 0.9783 -0.2054 -0.0293 +vn 0.9928 -0.1153 0.0319 +vn 0.9947 -0.0915 0.0479 +vn 0.9951 -0.0159 0.0980 +vn 0.8521 0.5150 -0.0929 +vn 0.4359 0.8925 0.1163 +vn 0.3778 0.9235 0.0658 +vn 0.3900 0.9176 0.0763 +vn 0.3118 0.9501 0.0105 +vn -0.3615 0.9306 -0.0566 +vn -0.6334 0.7738 -0.0066 +vn -0.5437 0.8377 0.0511 +vn -0.7140 0.6983 0.0503 +vn -0.8402 0.5399 -0.0509 +vn -0.9956 -0.0691 0.0635 +vn -0.9927 -0.1163 0.0307 +vn -0.9942 -0.0991 0.0427 +vn -0.9881 -0.1538 0.0044 +vn -0.7484 -0.6451 0.1542 +vn -0.8481 -0.5293 -0.0246 +vn -0.8254 -0.5641 0.0244 +vn -0.8913 -0.4263 -0.1544 +vn 0.9328 -0.3257 0.1540 +vn 0.8825 -0.4697 -0.0245 +vn 0.9012 -0.4327 0.0245 +vn 0.8150 -0.5586 -0.1540 +vn -0.1845 0.9706 0.1544 +vn -0.0343 0.9991 -0.0245 +vn -0.0758 0.9968 0.0246 +vn 0.0766 0.9851 -0.1543 +vn -0.8515 -0.4194 0.3147 +vn -0.3631 0.4546 0.8133 +vn -0.3608 0.4409 0.8218 +vn -0.3670 0.4783 0.7978 +vn -0.3691 0.4923 0.7883 +vn 0.4297 0.8155 0.3876 +vn 0.5366 0.0423 0.8427 +vn 0.5139 0.0548 0.8561 +vn 0.5740 0.0211 0.8186 +vn 0.6021 0.0046 0.7984 +vn 0.2546 -0.9242 0.2847 +vn -0.2076 -0.3986 0.8933 +vn 0.0283 -0.0809 -0.9963 +vn 0.0233 -0.0863 -0.9960 +vn -0.0074 -0.0670 -0.9977 +vn -0.0281 -0.0533 -0.9982 +vn 0.0062 0.0609 -0.9981 +vn -0.0236 0.0778 -0.9967 +vn 0.0241 0.0538 -0.9983 +vn -0.0447 -0.0247 -0.9987 +vn -0.0439 -0.0218 -0.9988 +vn 0.0379 0.0173 -0.9991 +vn 0.0360 0.0110 -0.9993 +vn -0.0269 0.0729 -0.9970 +vn 0.0181 0.2162 0.9762 +vn -0.3631 0.0653 0.9295 +vn -0.1950 -0.0948 0.9762 +vn 0.8771 -0.4795 0.0291 +vn 0.8335 -0.5523 0.0165 +vn 0.8809 -0.4722 0.0303 +vn 0.9596 0.2810 -0.0155 +vn 0.5502 0.8188 0.1639 +vn 0.4591 0.8879 0.0289 +vn 0.4706 0.8819 0.0267 +vn 0.5610 0.8221 0.0971 +vn -0.4837 0.8749 0.0215 +vn -0.3036 0.9528 0.0068 +vn -0.3195 0.9475 0.0081 +vn -0.4930 0.8698 0.0222 +vn -0.8738 0.4860 -0.0143 +vn -0.9990 -0.0372 0.0245 +vn -0.8796 -0.4755 -0.0124 +vn -0.9964 -0.0817 0.0211 +vn -0.8583 -0.5130 -0.0158 +vn -0.3450 -0.9332 0.1008 +vn 0.0297 -0.9995 -0.0084 +vn -0.3212 -0.9365 0.1405 +vn 0.0722 -0.9973 -0.0130 +vn 0.8262 -0.5631 0.0146 +vn 0.1281 -0.0217 0.9915 +vn 0.1101 -0.0835 0.9904 +vn 0.1374 0.0096 0.9905 +vn 0.0674 -0.1067 0.9920 +vn 0.0250 0.1233 0.9921 +vn -0.1004 0.0946 0.9904 +vn -0.0027 0.1354 0.9908 +vn -0.0601 0.1453 0.9876 +vn 0.1002 0.0834 0.9915 +vn 0.1111 0.0915 0.9896 +vn 0.0291 -0.1268 0.9915 +vn -0.1581 -0.0003 0.9874 +vn -0.1468 -0.0387 0.9884 +vn -0.0722 -0.1067 0.9917 +vn -0.0611 -0.1043 0.9927 +vn 0.7947 -0.6067 0.0189 +vn 0.8785 -0.4765 -0.0337 +vn 0.9657 -0.2595 -0.0081 +vn 0.9754 -0.2183 -0.0320 +vn 0.9291 0.3655 0.0572 +vn 0.8235 0.5652 -0.0489 +vn 0.7635 0.6457 0.0140 +vn 0.6766 0.7351 -0.0440 +vn 0.5140 0.8556 0.0618 +vn -0.2527 0.9664 -0.0474 +vn -0.1878 0.9819 0.0229 +vn -0.1987 0.9800 0.0113 +vn -0.1283 0.9880 0.0856 +vn -0.9319 0.3621 0.0199 +vn -0.7495 0.6576 -0.0764 +vn -0.9122 0.4096 -0.0132 +vn -0.9750 0.2189 0.0371 +vn -0.9832 0.1824 0.0092 +vn -0.7626 -0.6465 -0.0243 +vn -0.7652 -0.6432 -0.0280 +vn -0.7632 -0.6457 -0.0252 +vn -0.7603 -0.6493 -0.0212 +vn -0.1612 -0.9854 0.0555 +vn -0.0269 -0.9995 -0.0192 +vn 0.1750 -0.9841 0.0316 +vn 0.4100 -0.9115 -0.0336 +vn 0.0555 -0.8337 -0.5494 +vn 0.7449 0.6524 0.1392 +vn 0.7699 0.6325 0.0846 +vn 0.7630 0.6386 0.1004 +vn 0.7987 0.6016 0.0103 +vn -0.0174 0.8234 -0.5673 +vn -0.7617 -0.6321 0.1427 +vn -0.7776 -0.6195 0.1076 +vn -0.7731 -0.6233 0.1179 +vn -0.7974 -0.6006 0.0593 +vn -0.3255 -0.8735 0.3620 +vn -0.4925 -0.1665 0.8542 +vn -0.7683 -0.0271 0.6395 +vn -0.4200 0.7385 0.5275 +vn 0.0271 0.4802 0.8767 +vn 0.4984 0.7372 0.4562 +vn 0.5624 -0.2892 0.7747 +vn 0.5564 -0.2813 0.7818 +vn 0.5745 -0.3055 0.7594 +vn 0.5788 -0.3114 0.7537 +vn 0.0551 0.0357 -0.9978 +vn 0.0856 -0.0197 -0.9961 +vn 0.0663 0.0007 -0.9978 +vn -0.0118 0.0644 -0.9979 +vn 0.0175 0.0719 -0.9973 +vn -0.0071 -0.0721 -0.9974 +vn -0.0493 -0.0498 -0.9975 +vn 0.0089 -0.0594 -0.9982 +vn 0.0533 -0.0521 -0.9972 +vn -0.0593 -0.0101 -0.9982 +vn -0.0645 0.0122 -0.9978 +vn -0.0420 0.0671 -0.9969 +vn 0.0911 0.1976 0.9760 +vn 0.0611 0.0946 0.9936 +vn 0.1244 0.2205 0.9674 +vn 0.0125 0.0506 0.9986 +vn 0.9420 0.3340 0.0332 +vn 0.9659 0.2588 0.0113 +vn 0.7331 0.6793 0.0317 +vn 0.2841 0.9587 -0.0123 +vn -0.3049 0.9521 0.0245 +vn -0.5836 0.8120 0.0093 +vn -0.6112 0.7910 0.0284 +vn -0.6223 0.7828 0.0100 +vn -0.8368 0.5466 0.0308 +vn -0.9982 -0.0571 -0.0171 +vn -0.7849 -0.6076 0.1210 +vn -0.7905 -0.6118 0.0284 +vn -0.7854 -0.6080 0.1164 +vn -0.3458 -0.9382 -0.0146 +vn 0.1986 -0.9797 0.0268 +vn 0.6759 -0.7367 -0.0228 +vn 0.9981 -0.0525 0.0317 +vn 0.9794 0.2017 0.0115 +vn -0.1126 0.0624 0.9917 +vn -0.1120 0.0810 0.9904 +vn -0.1278 -0.0251 0.9915 +vn 0.1212 0.0866 0.9888 +vn 0.1162 0.0156 0.9931 +vn 0.0531 0.1226 0.9910 +vn -0.1017 -0.0806 0.9915 +vn -0.0300 0.1331 0.9906 +vn -0.0543 0.1355 0.9893 +vn -0.0554 -0.1248 0.9906 +vn 0.0241 -0.1336 0.9907 +vn 0.0443 -0.1382 0.9894 +vn 0.1123 -0.0721 0.9911 +vn 0.3045 0.0398 0.9517 +vn 0.8351 0.5494 -0.0282 +vn 0.7212 0.6921 0.0294 +vn 0.9775 0.2041 0.0532 +vn 0.5829 0.8095 -0.0700 +vn 0.0062 0.9982 0.0601 +vn -0.0988 0.9951 0.0000 +vn -0.0619 0.9979 0.0212 +vn -0.1700 0.9846 -0.0412 +vn -0.6379 0.7692 0.0374 +vn -0.7519 0.6583 -0.0361 +vn -0.8498 0.5260 0.0347 +vn -0.8889 0.4580 -0.0098 +vn -0.9763 0.1932 0.0975 +vn -0.8710 -0.4913 0.0048 +vn -0.9428 -0.3190 -0.0972 +vn -0.8933 -0.4490 -0.0215 +vn -0.7867 -0.6115 0.0851 +vn -0.1960 -0.9804 0.0182 +vn -0.3810 -0.9220 -0.0694 +vn -0.0263 -0.9990 -0.0360 +vn 0.3090 -0.9501 0.0413 +vn 0.6291 -0.7766 -0.0347 +vn 0.8502 -0.5247 0.0429 +vn 0.9833 -0.1786 -0.0345 +vn 0.6217 0.7722 0.1307 +vn 0.6762 0.7336 0.0674 +vn 0.6745 0.7350 0.0695 +vn 0.7275 0.6861 0.0000 +vn -0.7988 0.6017 0.0000 +vn -0.7515 0.6560 -0.0694 +vn -0.7531 0.6545 -0.0673 +vn -0.7033 0.6988 -0.1305 +vn -0.6217 -0.7722 0.1307 +vn -0.6762 -0.7336 0.0674 +vn -0.6745 -0.7350 0.0695 +vn -0.7275 -0.6861 0.0000 +vn 0.7988 -0.6017 0.0000 +vn 0.7515 -0.6560 -0.0694 +vn 0.7531 -0.6545 -0.0673 +vn 0.7033 -0.6988 -0.1305 +vn 0.7495 -0.1529 0.6442 +vn 0.0426 -0.6692 0.7418 +vn 0.0088 -0.7468 0.6649 +vn 0.0787 -0.5753 0.8141 +vn 0.1003 -0.5132 0.8524 +vn -0.7427 -0.5755 0.3424 +vn -0.5766 0.1119 0.8094 +vn 0.1826 0.4385 0.8800 +vn 0.6698 -0.7120 -0.2109 +vn 0.6777 0.5416 -0.4973 +vn 0.3741 -0.4234 -0.8251 +vn 0.1049 0.5324 -0.8400 +vn -0.2424 -0.6163 -0.7493 +vn -0.5277 0.7121 -0.4631 +vn -0.7557 -0.5727 -0.3177 +vn -0.8369 0.4523 0.3083 +vn -0.8461 0.4291 0.3162 +vn -0.9124 0.0535 0.4059 +vn -0.9107 0.0032 0.4131 +vn -0.2375 -0.1034 0.9659 +vn -0.2374 -0.1022 0.9660 +vn -0.2388 -0.1159 0.9641 +vn -0.2391 -0.1179 0.9638 +vn 0.4553 0.2888 0.8422 +vn 0.4921 -0.6955 0.5235 +vn 0.6570 0.7215 0.2185 +vn -0.7115 -0.6160 0.3379 +vn -0.4963 0.7670 0.4066 +vn -0.2920 -0.6835 0.6690 +vn -0.0940 0.6489 0.7551 +vn 0.1991 -0.6907 0.6952 +vn 0.3995 0.6349 0.6613 +vn 0.7676 -0.4716 0.4341 +vn 0.8822 0.2575 0.3942 +vn 0.9201 -0.3749 -0.1137 +vn 0.7012 0.6770 -0.2236 +vn 0.6122 -0.6337 -0.4730 +vn 0.3480 0.6065 -0.7148 +vn 0.2782 -0.3941 -0.8759 +vn -0.1900 0.3451 -0.9191 +vn -0.2996 -0.4830 -0.8228 +vn -0.5429 0.5199 -0.6595 +vn -0.6639 -0.5815 -0.4702 +vn -0.7687 0.6253 -0.1346 +vn -0.9835 0.1504 -0.1009 +vn -0.0092 -0.9999 0.0117 +vn -0.0103 -0.9999 0.0000 +vn -0.0308 -0.9994 0.0180 +vn -0.0240 -0.9993 0.0293 +vn -0.0191 -0.9996 -0.0214 +vn -0.9725 0.1579 -0.1714 +vn -0.9692 0.1808 -0.1672 +vn -0.9780 -0.0464 -0.2034 +vn -0.9754 -0.0756 -0.2073 +vn -0.5765 -0.2299 -0.7841 +vn -0.3047 0.6893 -0.6573 +vn 0.1612 -0.7364 -0.6570 +vn 0.4425 0.7281 -0.5235 +vn 0.7405 -0.5823 -0.3355 +vn 0.8476 0.5294 0.0353 +vn 0.8104 -0.4954 0.3129 +vn 0.6111 0.4709 0.6362 +vn 0.2602 -0.6445 0.7189 +vn 0.0088 0.6402 0.7682 +vn -0.5683 -0.5989 0.5643 +vn -0.7825 0.0827 0.6172 +vn -0.0165 0.9990 0.0425 +vn -0.0347 0.9992 0.0176 +vn -0.0654 0.9944 0.0831 +vn -0.0341 0.9994 -0.0038 +vn 0.8474 -0.5304 0.0257 +vn 0.7975 0.5752 0.1823 +vn 0.6735 -0.5553 0.4879 +vn 0.4754 0.6713 0.5687 +vn 0.2141 -0.6607 0.7195 +vn -0.0566 0.5966 0.8005 +vn -0.2089 -0.2151 0.9540 +vn -0.6584 0.1724 0.7326 +vn -0.5957 -0.7883 0.1540 +vn -0.6981 0.7066 -0.1152 +vn -0.6136 -0.6471 -0.4526 +vn -0.6928 0.2883 -0.6610 +vn -0.1330 -0.3901 -0.9111 +vn -0.0711 0.2531 -0.9648 +vn 0.4708 -0.0812 -0.8785 +vn 0.4716 -0.0927 -0.8769 +vn 0.4641 -0.0016 -0.8858 +vn 0.4632 0.0067 -0.8862 +vn 0.8474 -0.0820 -0.5246 +vn 0.8517 -0.0456 -0.5220 +vn 0.8153 0.3771 -0.4394 +vn 0.8092 0.3973 -0.4329 +vn 0.0919 0.4078 0.9084 +vn 0.1411 0.2869 0.9475 +vn 0.3457 0.4782 0.8073 +vn 0.5304 0.4335 0.7286 +vn 0.4623 0.4273 0.7770 +vn 0.5543 0.3078 0.7733 +vn 0.0380 0.2204 0.9747 +vn -0.0341 0.2551 0.9663 +vn -0.1710 0.5199 0.8369 +vn -0.0239 0.7679 0.6401 +vn -0.1082 0.7542 0.6477 +vn -0.0232 0.7705 0.6370 +vn 0.5708 0.7360 0.3641 +vn 0.5849 0.7575 0.2898 +vn 0.2314 0.9653 0.1214 +vn 0.4197 0.8937 0.1586 +vn 0.5768 0.8122 0.0871 +vn 0.3203 0.9466 0.0375 +vn 0.5755 0.8093 -0.1172 +vn 0.5676 0.8148 -0.1176 +vn 0.5843 0.7389 -0.3356 +vn 0.5695 0.7766 -0.2693 +vn 0.5672 0.7600 -0.3173 +vn 0.5696 0.7140 -0.4072 +vn 0.5568 0.6458 -0.5224 +vn 0.6639 0.5146 -0.5426 +vn 0.5822 0.4238 -0.6938 +vn 0.5220 0.4584 -0.7193 +vn 0.5314 0.3715 -0.7613 +vn 0.5972 0.3022 -0.7430 +vn 0.5816 0.3182 0.7487 +vn 0.5885 0.1806 0.7881 +vn 0.7216 0.4179 0.5519 +vn 0.6839 0.4250 0.5929 +vn 0.2704 0.7896 0.5509 +vn 0.5889 0.6909 0.4195 +vn 0.1046 0.7039 0.7025 +vn -0.0062 0.9891 -0.1470 +vn -0.0033 0.9935 0.1142 +vn 0.2689 0.9630 0.0157 +vn 0.2881 0.9106 0.2964 +vn -0.0038 0.9307 0.3658 +vn 0.2469 0.7939 0.5556 +vn 0.2778 0.5941 0.7549 +vn -0.0055 0.3871 0.9220 +vn 0.2803 0.3019 0.9112 +vn 0.0383 0.0117 0.9992 +vn 0.2701 -0.0199 0.9626 +vn 0.2769 -0.3419 0.8980 +vn 0.2809 -0.2732 0.9200 +vn -0.0027 -0.5161 0.8565 +vn 0.2747 -0.6411 0.7166 +vn 0.0003 -0.7049 0.7093 +vn -0.0028 -0.8974 0.4413 +vn 0.2498 -0.8524 0.4593 +vn 0.2586 -0.9575 0.1277 +vn -0.0115 -0.9999 0.0093 +vn 0.2652 -0.9315 -0.2491 +vn -0.0085 -0.9171 -0.3986 +vn 0.2339 -0.8036 -0.5472 +vn -0.0029 -0.7550 -0.6557 +vn 0.2770 -0.5717 -0.7723 +vn 0.0008 -0.5486 -0.8361 +vn 0.2797 -0.2442 -0.9285 +vn 0.2789 -0.2782 -0.9191 +vn -0.0008 -0.0300 -0.9995 +vn 0.3196 0.1447 -0.9364 +vn -0.0199 0.1182 -0.9928 +vn 0.2198 0.4713 -0.8542 +vn -0.0049 0.5373 -0.8434 +vn 0.2942 0.6978 -0.6530 +vn -0.0016 0.7625 -0.6470 +vn -0.0033 0.9058 -0.4236 +vn 0.2797 0.9011 -0.3314 +vn -0.0398 -0.0109 -0.9991 +vn -0.0391 -0.0206 -0.9990 +vn -0.0424 -0.0002 -0.9991 +vn -0.0488 -0.0009 -0.9988 +vn -0.2003 -0.0023 -0.9797 +vn -0.2000 0.1319 -0.9709 +vn 0.0533 0.2394 -0.9695 +vn 0.1674 0.2813 -0.9449 +vn -0.0356 -0.0045 -0.9994 +vn -0.2618 0.1323 0.9560 +vn -0.0445 0.0016 0.9990 +vn -0.0383 0.0022 0.9993 +vn -0.2091 0.0064 0.9779 +vn -0.1711 -0.1306 0.9766 +vn -0.0412 -0.0006 0.9992 +vn -0.0745 -0.0293 0.9968 +vn 0.0401 -0.2144 0.9759 +vn -0.0406 0.0071 0.9992 +vn -0.0454 -0.0014 0.9990 +vn -0.0928 -0.0583 0.9940 +vn 0.6054 -0.4011 0.6874 +vn 0.5447 -0.4302 0.7199 +vn 0.4945 -0.4154 0.7635 +vn 0.5437 -0.3604 -0.7580 +vn 0.4926 -0.4836 -0.7235 +vn 0.5452 -0.4503 -0.7071 +vn -0.2052 -0.0103 0.9787 +vn -0.5763 -0.0104 0.8172 +vn -0.6947 0.1317 0.7072 +vn -0.8678 -0.0139 0.4967 +vn -0.9551 0.1353 0.2636 +vn -0.9943 -0.0086 0.1064 +vn -0.9635 0.1330 -0.2326 +vn -0.9626 -0.0132 -0.2705 +vn -0.8083 -0.0014 -0.5888 +vn -0.7959 0.1271 -0.5919 +vn -0.5354 0.1288 -0.8347 +vn -0.5255 -0.0026 -0.8508 +vn -0.9506 -0.0111 0.3103 +vn -0.9896 -0.0030 0.1438 +vn -0.9483 -0.0053 0.3174 +vn -0.9882 -0.0017 0.1530 +vn -0.9443 -0.0134 -0.3289 +vn -0.9846 -0.0045 -0.1750 +vn -0.9479 -0.0049 -0.3184 +vn -0.9846 0.0014 -0.1748 +vn 0.5040 -0.8580 0.0988 +vn 0.4954 -0.7399 0.4551 +vn 0.4572 -0.4844 0.7459 +vn 0.4611 -0.1769 0.8695 +vn 0.4654 0.1295 0.8756 +vn 0.4668 0.4423 0.7658 +vn 0.5059 0.7251 0.4672 +vn 0.4984 0.8557 0.1390 +vn 0.4572 0.8754 -0.1568 +vn 0.4387 0.7514 -0.4929 +vn 0.4722 0.3876 -0.7917 +vn 0.4328 -0.0566 -0.8997 +vn 0.4697 -0.4195 -0.7768 +vn 0.4806 -0.7138 -0.5094 +vn 0.5068 -0.8452 -0.1697 +vn -0.1596 0.5041 -0.8488 +vn -0.0307 0.2568 -0.9660 +vn -0.4367 0.5076 -0.7427 +vn -0.6729 0.5048 -0.5408 +vn -0.8777 0.2799 -0.3891 +vn -0.8505 0.5164 -0.1002 +vn -0.8585 0.4919 0.1447 +vn -0.7559 0.5034 0.4186 +vn -0.5622 0.5973 0.5720 +vn -0.4470 0.4850 0.7517 +vn -0.9058 0.0220 0.4231 +vn -0.6443 -0.0190 0.7646 +vn -0.8902 0.0187 0.4552 +vn -0.6145 -0.0225 0.7886 +vn -0.6845 -0.0142 -0.7289 +vn -0.8813 0.0178 -0.4723 +vn -0.8683 0.0152 -0.4958 +vn -0.6637 -0.0170 -0.7478 +vn 0.1895 0.4559 -0.8696 +vn 0.3882 0.4603 -0.7984 +vn 0.0650 0.3833 -0.9213 +vn -0.0689 0.9177 -0.3912 +vn -0.0389 0.6774 -0.7346 +vn -0.0407 0.6694 -0.7418 +vn 0.0013 0.9873 -0.1589 +vn -0.0072 0.9988 -0.0477 +vn -0.2379 0.7884 -0.5673 +vn -0.4218 0.9067 -0.0011 +vn -0.3296 0.9175 0.2226 +vn -0.1899 0.8993 0.3940 +vn -0.4354 0.7789 -0.4513 +vn -0.4843 0.8479 -0.2157 +vn -0.5047 0.8493 0.1547 +vn -0.1646 0.9581 -0.2345 +vn -0.2813 0.9544 -0.1000 +vn -0.0094 -0.0068 -0.9999 +vn -0.0113 -0.0053 -0.9999 +vn -0.0184 0.0069 -0.9998 +vn -0.0047 0.0013 -1.0000 +vn -0.0100 0.0104 -0.9999 +vn 0.0107 0.0014 -0.9999 +vn 0.0094 0.0009 -1.0000 +vn 0.7921 -0.0315 -0.6096 +vn 0.5237 0.0422 -0.8508 +vn 0.8456 0.0315 -0.5329 +vn 0.9837 -0.0285 -0.1776 +vn 0.9977 0.0261 -0.0629 +vn 0.9770 -0.0218 0.2120 +vn 0.6307 -0.0039 0.7760 +vn 0.7065 0.0209 0.7074 +vn 0.6921 0.0161 0.7216 +vn 0.6121 -0.0097 0.7907 +vn -0.5940 -0.0247 0.8041 +vn -0.0480 -0.0012 0.9988 +vn -0.2421 0.0146 0.9701 +vn -0.8475 0.0270 0.5301 +vn -0.9101 -0.0219 0.4139 +vn -0.9967 0.0374 0.0726 +vn -0.8818 -0.0304 -0.4706 +vn -0.7265 0.0079 -0.6871 +vn -0.8478 -0.0207 -0.5298 +vn -0.6929 0.0147 -0.7208 +vn 0.0391 0.0050 0.9992 +vn 0.0479 -0.0018 0.9988 +vn 0.0470 -0.0011 0.9989 +vn 0.0419 0.0017 0.9991 +vn 0.0424 0.0015 0.9991 +vn 0.0563 -0.0068 0.9984 +vn 0.7148 0.0028 0.6993 +vn 0.7162 0.0025 0.6979 +vn 0.6973 0.0061 0.7167 +vn 0.9979 0.0135 -0.0629 +vn 0.9928 -0.0072 0.1198 +vn 0.9949 -0.0050 0.1010 +vn 0.6958 0.0064 0.7183 +vn 0.9968 0.0152 -0.0785 +vn 0.6808 -0.0066 -0.7325 +vn 0.6913 -0.0012 -0.7225 +vn 0.6838 -0.0050 -0.7296 +vn 0.6941 0.0003 -0.7198 +vn 0.1582 -0.0002 -0.9874 +vn 0.2872 0.0068 -0.9579 +vn 0.4945 -0.0014 -0.8692 +vn 0.5235 0.0065 -0.8520 +vn 0.9794 -0.0086 -0.2019 +vn 0.9779 -0.0110 -0.2086 +vn 0.9790 -0.0092 -0.2036 +vn 0.9775 -0.0117 -0.2106 +vn 0.6801 -0.0192 0.7328 +vn 0.7873 0.0261 0.6160 +vn 0.7613 0.0143 0.6483 +vn 0.6513 -0.0301 0.7582 +vn 0.0064 0.0038 1.0000 +vn 0.0088 0.0215 0.9997 +vn -0.3351 0.0142 0.9421 +vn -0.1187 0.0006 0.9929 +vn 0.0034 0.0007 1.0000 +vn 0.0110 -0.0017 0.9999 +vn 0.0130 -0.0035 0.9999 +vn -0.0184 -0.0014 -0.9998 +vn -0.0023 0.0086 -1.0000 +vn 0.0482 -0.0031 -0.9988 +vn 0.0483 -0.0038 -0.9988 +vn 0.0549 -0.0095 -0.9984 +vn -0.5826 -0.0096 0.8127 +vn -0.9076 0.0240 0.4191 +vn -0.9805 -0.0132 0.1962 +vn -0.8847 -0.0028 -0.4661 +vn -0.9020 0.0255 -0.4310 +vn -0.6499 0.0205 -0.7598 +vn -0.7124 0.0054 -0.7018 +vn -0.1798 -0.0212 -0.9835 +vn 0.7994 -0.0063 -0.6008 +vn 0.7118 0.0114 -0.7023 +vn 0.7210 0.0096 -0.6929 +vn 0.8056 -0.0077 -0.5924 +vn 0.9934 0.0017 0.1147 +vn 0.9918 0.0034 0.1277 +vn 0.9933 0.0018 0.1157 +vn 0.9916 0.0036 0.1290 +vn 0.6795 0.0005 0.7336 +vn 0.6813 0.0013 0.7320 +vn 0.6808 0.0011 0.7324 +vn 0.6791 0.0003 0.7341 +vn -0.0063 1.0000 0.0036 +vn -0.0035 1.0000 0.0073 +vn -0.0042 0.9997 0.0252 +vn -0.0006 1.0000 0.0009 +vn -0.0006 1.0000 0.0013 +vn 0.0082 0.9999 -0.0068 +vn 0.0091 0.9999 -0.0089 +vn 0.0092 0.9999 -0.0091 +vn -0.0619 -0.9755 0.2113 +vn 0.0001 -1.0000 -0.0060 +vn -0.0007 -1.0000 0.0081 +vn -0.0128 -0.9328 0.3600 +vn 0.0184 -0.9996 0.0195 +vn 0.0134 -0.9998 0.0140 +vn 0.0457 -0.9984 0.0325 +vn 0.0022 -0.9999 -0.0160 +vn 0.0042 -0.9996 0.0284 +vn 0.0072 -0.9793 0.2024 +vn 0.2295 -0.9269 0.2968 +vn 0.0080 -0.9995 0.0311 +vn 0.0192 -0.9997 0.0145 +vn -0.0161 -0.9998 -0.0075 +vn -0.0432 -0.9990 0.0065 +vn 0.1246 -0.9821 -0.1415 +vn 0.0581 -0.9980 0.0256 +vn 0.5589 -0.7772 0.2891 +vn 0.5567 -0.7572 0.3415 +vn 0.5816 -0.6771 0.4508 +vn 0.5618 -0.7635 0.3183 +vn 0.5665 -0.6552 0.4998 +vn 0.5575 -0.5721 0.6015 +vn 0.1420 -0.2437 -0.9594 +vn -0.2467 -0.0105 -0.9690 +vn -0.0406 0.0119 -0.9991 +vn 0.0392 -0.2193 -0.9749 +vn -0.1930 -0.1482 -0.9699 +vn 0.1508 -0.2234 0.9630 +vn -0.4962 -0.1297 0.8585 +vn -0.5518 0.0103 0.8339 +vn -0.7775 -0.1291 0.6155 +vn -0.8239 0.0158 0.5666 +vn -0.9300 -0.1297 0.3439 +vn -0.9643 0.0139 0.2643 +vn -0.9911 -0.1310 0.0220 +vn -0.9966 0.0145 -0.0810 +vn -0.9305 -0.1317 -0.3419 +vn -0.8948 0.0209 -0.4461 +vn -0.7779 -0.1313 -0.6145 +vn -0.6472 0.0309 -0.7617 +vn -0.5347 -0.1246 -0.8358 +vn 0.5580 -0.6231 -0.5480 +vn 0.5674 -0.7558 -0.3268 +vn 0.5656 -0.6680 -0.4836 +vn 0.5615 -0.7712 -0.2999 +vn 0.5690 -0.7017 -0.4288 +vn 0.5602 -0.7452 -0.3617 +vn -0.0469 -0.2874 -0.9567 +vn -0.1334 -0.5073 -0.8514 +vn -0.0413 -0.2514 -0.9670 +vn 0.0103 -0.3007 -0.9537 +vn -0.3071 -0.4633 0.8313 +vn -0.0944 -0.4896 0.8668 +vn -0.4559 -0.5433 0.7050 +vn -0.6343 -0.4916 0.5967 +vn -0.7797 -0.4984 0.3790 +vn -0.8468 -0.4983 0.1861 +vn -0.9561 -0.2920 0.0225 +vn -0.8543 -0.4983 -0.1480 +vn -0.7371 -0.5759 -0.3535 +vn -0.6708 -0.5029 -0.5450 +vn -0.4765 -0.5138 -0.7134 +vn -0.3171 -0.5124 -0.7980 +vn -0.0435 -0.2821 0.9584 +vn -0.0311 -0.2625 0.9644 +vn 0.1588 -0.4239 0.8917 +vn 0.2995 -0.4700 0.8303 +vn 0.0874 -0.3946 0.9147 +vn 0.2055 -0.5118 0.8341 +vn 0.2354 -0.7219 0.6507 +vn 0.2378 -0.6017 0.7625 +vn 0.4613 -0.4780 0.7475 +vn 0.4825 -0.5580 0.6752 +vn 0.1610 -0.4301 -0.8883 +vn 0.1792 -0.7029 -0.6884 +vn 0.1621 -0.5223 -0.8372 +vn 0.3883 -0.4553 -0.8012 +vn 0.3096 -0.4731 -0.8248 +vn 0.4922 -0.5613 -0.6653 +vn 0.9315 0.0037 -0.3638 +vn 0.9466 -0.0056 -0.3223 +vn 0.9622 -0.0166 -0.2720 +vn 0.9662 -0.0199 -0.2570 +vn 0.6287 0.0073 -0.7776 +vn 0.6229 0.0000 -0.7823 +vn 0.6247 0.0023 -0.7809 +vn 0.6205 -0.0029 -0.7842 +vn 0.0801 -0.0339 -0.9962 +vn -0.1857 -0.0190 -0.9824 +vn 0.0107 0.0205 -0.9997 +vn -0.3905 0.0205 -0.9204 +vn -0.5847 0.0144 -0.8111 +vn -0.6318 0.0926 -0.7696 +vn -0.9754 -0.0151 -0.2201 +vn -0.9472 -0.0902 -0.3077 +vn -0.9700 -0.0328 -0.2410 +vn -0.9859 0.0316 -0.1642 +vn -0.7347 -0.0199 0.6780 +vn -0.8579 0.0176 0.5135 +vn -0.9149 -0.0343 0.4023 +vn -0.5998 -0.0198 0.7999 +vn -0.4817 -0.0245 0.8760 +vn -0.5204 -0.0362 0.8532 +vn 0.2645 -0.0220 0.9641 +vn 0.2338 0.0033 0.9723 +vn -0.0293 0.0448 0.9986 +vn 0.3504 -0.0381 0.9358 +vn 0.9108 -0.0077 0.4129 +vn 0.9533 0.0353 0.3000 +vn 0.9424 0.0227 0.3338 +vn 0.8922 -0.0229 0.4511 +vn 0.4319 -0.0236 0.9016 +vn -0.7059 -0.0328 -0.7076 +vn -0.6254 0.0094 -0.7802 +vn -0.2204 0.0191 -0.9752 +vn -0.9284 0.0241 -0.3708 +vn -0.9981 -0.0233 -0.0577 +vn -0.9876 0.0141 0.1561 +vn -0.9753 -0.0273 0.2192 +vn -0.6950 0.0047 0.7190 +vn -0.6743 -0.0449 0.7371 +vn -0.6884 -0.0115 0.7252 +vn -0.7033 0.0264 0.7104 +vn -0.0171 -0.0045 0.9998 +vn -0.0156 -0.0011 0.9999 +vn -0.0142 0.0020 0.9999 +vn -0.0193 -0.0096 0.9998 +vn 0.7143 0.0152 0.6997 +vn 0.6988 0.0244 0.7149 +vn 0.7164 0.0139 0.6975 +vn 0.7227 0.0101 0.6911 +vn 0.9998 -0.0067 -0.0211 +vn 0.9918 0.0103 -0.1273 +vn 0.9971 -0.0273 0.0706 +vn 0.9987 -0.0187 0.0482 +vn 0.5659 -0.0494 -0.8230 +vn 0.5109 -0.0702 -0.8568 +vn 0.5578 -0.0525 -0.8283 +vn 0.0077 0.0478 -0.9988 +vn -0.2646 -0.0214 -0.9641 +vn 0.4911 -0.0773 -0.8676 +vn 0.9508 0.0459 -0.3065 +vn 0.9577 0.0057 -0.2877 +vn 0.9504 -0.0320 -0.3095 +vn 0.7809 0.0061 -0.6246 +vn 0.5195 -0.0256 -0.8541 +vn 0.2367 0.0279 -0.9712 +vn -0.0550 -0.0219 -0.9982 +vn -0.5463 0.0213 -0.8373 +vn -0.6146 -0.0242 -0.7885 +vn -0.9853 -0.0242 -0.1692 +vn -0.9107 0.0074 -0.4130 +vn -0.9993 0.0066 -0.0369 +vn 0.9813 0.0150 0.1920 +vn 0.9816 -0.0297 0.1886 +vn 0.8707 0.0448 0.4897 +vn 0.3404 -0.0486 0.9390 +vn 0.1812 0.0123 0.9834 +vn 0.2831 -0.0264 0.9587 +vn 0.1177 0.0359 0.9924 +vn -0.5436 -0.0287 0.8388 +vn -0.6689 0.0127 0.7432 +vn -0.5778 -0.0179 0.8160 +vn -0.6989 0.0235 0.7148 +vn -0.9712 -0.0268 0.2369 +vn -0.9877 -0.0032 0.1561 +vn -0.9390 -0.0228 0.3433 +vn -0.9979 0.0336 -0.0545 +vn -0.9632 -0.0095 -0.2687 +vn -0.8411 0.0151 0.5407 +vn -0.5758 -0.0217 0.8173 +vn -0.2440 0.0282 0.9694 +vn -0.0252 -0.0216 0.9994 +vn 0.4239 0.0166 0.9055 +vn 0.5733 -0.0196 0.8191 +vn 0.7764 -0.0106 0.6302 +vn 0.9582 -0.0247 0.2849 +vn 0.8888 -0.0010 0.4583 +vn 0.9996 0.0185 0.0212 +vn -0.9277 0.0391 -0.3713 +vn -0.8328 -0.0180 -0.5533 +vn -0.3343 -0.0087 -0.9424 +vn -0.2638 0.0159 -0.9644 +vn -0.3143 -0.0017 -0.9493 +vn -0.2464 0.0219 -0.9689 +vn 0.4613 -0.0187 -0.8870 +vn 0.4554 -0.0213 -0.8900 +vn 0.4597 -0.0194 -0.8879 +vn 0.4532 -0.0223 -0.8911 +vn 0.9928 -0.0181 -0.1187 +vn 0.9489 0.0444 -0.3124 +vn -0.1473 -0.7765 0.6126 +vn -0.0213 -0.8176 0.5753 +vn -0.2728 -0.9434 -0.1887 +vn -0.3885 -0.9157 -0.1032 +vn -0.5174 -0.8557 -0.0090 +vn -0.2987 -0.9538 0.0319 +vn -0.4044 -0.9041 0.1383 +vn -0.4889 -0.8029 0.3411 +vn -0.2460 -0.9199 0.3055 +vn -0.1417 -0.9201 -0.3651 +vn -0.0988 -0.7268 -0.6797 +vn -0.4145 -0.7845 -0.4612 +vn -0.0324 -0.7168 -0.6965 +vn -0.0325 -0.7164 -0.6969 +vn 0.0001 -1.0000 -0.0057 +vn -0.0018 -0.9774 -0.2115 +vn -0.0060 -0.9955 -0.0942 +vn 0.0911 -0.8248 0.5580 +vn 0.2774 -0.8517 -0.4445 +vn 0.1750 -0.8159 -0.5511 +vn 0.0167 -0.0256 -0.9995 +vn 0.0177 -0.0228 -0.9996 +vn 0.3052 -0.0269 -0.9519 +vn 0.0192 -0.0190 -0.9996 +vn 0.2003 0.0040 -0.9797 +vn -0.0775 0.0284 0.9966 +vn -0.0104 -0.0060 0.9999 +vn 0.0046 -0.1635 0.9865 +vn 0.3134 -0.0215 0.9494 +vn 0.1005 -0.2746 0.9563 +vn 0.5782 0.0012 -0.8159 +vn 0.7805 -0.0332 -0.6242 +vn 0.8126 0.0017 -0.5828 +vn 0.9402 0.0000 -0.3405 +vn 0.9777 -0.0240 -0.2086 +vn 0.9782 -0.2078 -0.0033 +vn 0.9775 -0.0236 0.2097 +vn 0.9094 -0.2519 0.3310 +vn 0.7755 -0.0239 0.6309 +vn 0.7170 -0.2178 0.6621 +vn 0.4088 -0.3027 0.8609 +vn 0.1755 -0.7496 0.6381 +vn -0.0273 -0.9053 0.4238 +vn 0.0343 -0.7637 0.6446 +vn 0.7826 -0.6204 0.0506 +vn 0.5530 -0.6194 0.5573 +vn 0.1928 -0.4962 -0.8465 +vn 0.0676 -0.7546 -0.6527 +vn 0.3516 -0.5677 -0.7444 +vn 0.4408 -0.5830 -0.6825 +vn 0.6731 -0.5599 -0.4832 +vn 0.5757 -0.7471 -0.3322 +vn 0.7949 -0.5379 -0.2806 +vn 0.8437 -0.5028 -0.1882 +vn 0.7116 -0.6370 0.2965 +vn 0.4280 -0.8039 -0.4130 +vn 0.5887 -0.8039 0.0849 +vn 0.5030 -0.8008 0.3252 +vn 0.5376 -0.8387 -0.0865 +vn 0.1858 -0.9791 -0.0825 +vn 0.2347 -0.8202 -0.5218 +vn 0.0176 -0.9051 -0.4248 +vn -0.0157 -0.8598 -0.5105 +vn 0.0324 -0.7617 -0.6471 +vn 0.0252 -0.7077 -0.7061 +vn -0.0005 -1.0000 -0.0003 +vn -0.0063 -0.9999 0.0153 +vn 0.0167 -0.9988 0.0450 +vn 0.0347 -0.9990 0.0297 +vn 0.0154 -0.9984 0.0549 +vn -0.0432 -0.9989 0.0173 +vn -0.0538 -0.9985 -0.0044 +vn -0.0450 -0.9990 -0.0041 +vn 0.0273 -0.9991 -0.0339 +vn 0.0316 -0.9988 -0.0387 +vn 0.0439 -0.9989 -0.0177 +vn 0.0413 -0.9991 0.0036 +vn 0.0053 -0.9990 -0.0448 +vn -0.0113 -0.9993 -0.0368 +vn -0.0275 -0.9992 -0.0291 +vn 0.0476 -0.9989 0.0050 +vn -0.0249 -0.9992 0.0302 +vn -0.0171 -0.9991 0.0398 +vn 0.1315 0.9913 0.0062 +vn -0.1462 0.9888 -0.0289 +vn -0.0751 0.9972 -0.0041 +vn 0.0090 0.9844 -0.1757 +vn 0.2194 0.9730 -0.0716 +vn 0.7983 0.1087 0.5924 +vn 0.8491 0.0008 0.5282 +vn 0.8042 0.0833 0.5886 +vn 0.8536 -0.0003 0.5209 +vn 0.9934 0.0106 -0.1140 +vn 0.9973 0.0053 -0.0728 +vn 0.9262 0.0038 -0.3769 +vn 0.9432 0.0141 -0.3319 +vn 0.8415 0.0154 -0.5401 +vn 0.7626 0.0004 -0.6469 +vn 0.1969 0.0569 -0.9788 +vn 0.2901 0.0008 -0.9570 +vn 0.2800 0.0022 -0.9600 +vn 0.1898 0.0630 -0.9798 +vn -0.6754 0.0235 -0.7371 +vn -0.4718 -0.0073 -0.8817 +vn -0.7684 -0.0028 -0.6399 +vn -0.8718 0.0176 -0.4896 +vn -0.9535 -0.0008 -0.3014 +vn -0.9774 0.0086 -0.2111 +vn -0.8076 0.0006 0.5898 +vn -0.8501 0.0157 0.5264 +vn -0.8127 0.0024 0.5826 +vn -0.8554 0.0177 0.5176 +vn 0.0308 0.0179 0.9994 +vn -0.3443 -0.0101 0.9388 +vn -0.0485 -0.0051 0.9988 +vn 0.0758 0.0180 0.9970 +vn 0.2476 -0.0027 0.9689 +vn 0.0507 0.9967 0.0635 +vn 0.0791 0.9968 0.0139 +vn 0.0747 0.9970 0.0210 +vn -0.0089 0.9966 -0.0825 +vn -0.0259 0.9963 -0.0822 +vn -0.0588 0.9970 -0.0508 +vn -0.0630 0.9968 -0.0482 +vn 0.0782 0.9966 -0.0270 +vn 0.0644 0.9967 -0.0501 +vn 0.0418 0.9969 -0.0673 +vn 0.0537 0.9965 0.0645 +vn -0.0517 0.9969 0.0585 +vn -0.0703 0.9964 0.0477 +vn -0.0309 0.9966 0.0758 +vn -0.0028 0.9969 0.0788 +vn 0.0161 0.9964 0.0836 +vn 0.0234 0.9962 -0.0840 +vn -0.0830 0.9965 0.0100 +vn -0.0880 0.9961 -0.0029 +vn 0.9878 0.0402 0.1504 +vn 0.6413 0.0305 0.7667 +vn 0.7985 -0.0166 0.6017 +vn 0.9885 -0.0236 0.1491 +vn 0.9391 -0.0108 -0.3436 +vn 0.7977 0.0369 -0.6020 +vn 0.6042 -0.0240 -0.7965 +vn 0.2984 0.0274 -0.9541 +vn 0.0486 -0.0327 -0.9983 +vn -0.2862 0.0247 -0.9578 +vn -0.6549 -0.0333 -0.7550 +vn -0.7993 0.0221 -0.6005 +vn -0.9087 -0.0192 -0.4169 +vn -0.9345 0.0130 -0.3558 +vn -0.9593 0.0183 0.2818 +vn -0.9792 -0.0155 0.2023 +vn -0.8939 -0.0173 0.4479 +vn -0.8139 0.0223 0.5805 +vn -0.7040 -0.0162 0.7100 +vn -0.6032 0.0355 0.7968 +vn -0.0852 -0.0239 0.9961 +vn -0.0814 -0.0217 0.9964 +vn 0.2726 -0.0229 0.9619 +vn 0.1342 0.0030 0.9910 +vn 0.7947 0.0000 0.6070 +vn 0.9230 0.0000 -0.3848 +vn 0.1282 0.0000 -0.9917 +vn -0.7946 0.0000 -0.6072 +vn -0.9230 0.0000 0.3849 +vn -0.1285 0.0000 0.9917 +vn 0.0965 0.8281 0.5522 +vn 0.1027 0.8466 0.5222 +vn 0.0559 0.6923 0.7194 +vn 0.0454 0.6535 0.7556 +vn -0.6570 0.5827 0.4783 +vn -0.3852 0.9140 0.1275 +vn -0.2454 0.8710 -0.4255 +vn 0.1854 0.2426 -0.9522 +vn 0.3579 0.8467 -0.3937 +vn 0.5185 0.8499 0.0942 +vn 0.7399 0.3902 0.5481 +vn 0.0394 -0.9990 0.0197 +vn 0.0475 -0.9989 -0.0028 +vn 0.0485 -0.9986 0.0191 +vn -0.0424 -0.9989 0.0192 +vn -0.0310 -0.9989 0.0349 +vn -0.0505 -0.9987 0.0090 +vn 0.0194 -0.9991 0.0368 +vn -0.0040 -0.9991 0.0411 +vn 0.0367 -0.9992 -0.0165 +vn 0.0282 -0.9990 -0.0343 +vn -0.0078 -0.9989 -0.0462 +vn 0.0129 -0.9981 -0.0607 +vn 0.0026 -0.9989 -0.0474 +vn -0.0090 -0.9988 0.0490 +vn -0.0340 -0.9993 -0.0171 +vn -0.0327 -0.9993 -0.0176 +vn -0.0189 0.9933 -0.1144 +vn -0.0297 0.9984 0.0479 +vn 0.1356 0.9871 0.0845 +vn 0.0247 0.9925 -0.1195 +vn 0.1381 0.9894 -0.0439 +vn -0.0016 0.9937 0.1117 +vn -0.5200 0.0008 0.8542 +vn -0.5067 -0.0008 0.8621 +vn -0.6560 0.0183 0.7545 +vn 0.0213 0.0142 0.9997 +vn 0.0845 0.0056 0.9964 +vn 0.0263 0.0135 0.9996 +vn 0.0915 0.0047 0.9958 +vn 0.8107 0.0780 0.5802 +vn 0.6795 -0.0058 0.7336 +vn 0.8728 -0.0055 0.4880 +vn 0.9749 0.0605 0.2143 +vn 0.9914 -0.0005 -0.1305 +vn 0.8731 0.0201 -0.4871 +vn 0.7449 0.0043 -0.6671 +vn 0.4312 0.0213 -0.9020 +vn 0.2145 -0.0004 -0.9767 +vn 0.0386 0.0176 -0.9991 +vn -0.1297 -0.0048 -0.9915 +vn -0.7799 0.0338 -0.6250 +vn -0.8310 -0.0025 -0.5562 +vn -0.7852 0.0355 -0.6182 +vn -0.8369 -0.0042 -0.5473 +vn -0.9705 0.0126 0.2406 +vn -0.9579 0.0065 0.2869 +vn -0.9692 0.0119 0.2462 +vn -0.9565 0.0058 0.2915 +vn -0.6683 0.0200 0.7437 +vn -0.0151 0.9967 0.0797 +vn -0.0412 0.9970 0.0655 +vn 0.0080 0.9960 0.0888 +vn 0.0570 0.9970 -0.0525 +vn 0.0420 0.9967 -0.0696 +vn 0.0170 0.9968 -0.0777 +vn -0.0599 0.9972 0.0451 +vn -0.0777 0.9966 0.0278 +vn -0.0366 0.9971 -0.0661 +vn -0.0507 0.9969 -0.0597 +vn -0.0779 0.9969 -0.0109 +vn 0.0814 0.9967 -0.0053 +vn 0.0766 0.9966 -0.0288 +vn 0.0298 0.9966 0.0773 +vn 0.0604 0.9966 0.0558 +vn 0.0753 0.9966 0.0340 +vn -0.0842 0.9963 -0.0150 +vn 0.0897 0.9958 0.0175 +vn -0.0023 0.9963 -0.0854 +vn -0.3688 -0.0277 0.9291 +vn -0.1134 -0.0183 0.9934 +vn -0.2608 0.0199 0.9652 +vn 0.1095 0.0343 0.9934 +vn 0.4557 -0.0275 0.8897 +vn 0.7059 0.0310 0.7076 +vn 0.9014 -0.0287 0.4320 +vn 0.9862 0.0265 0.1631 +vn 0.9873 -0.0279 -0.1566 +vn 0.9229 0.0245 -0.3841 +vn 0.7168 -0.0231 -0.6969 +vn 0.5334 0.0304 -0.8453 +vn 0.2203 -0.0191 -0.9753 +vn -0.0422 0.0301 -0.9987 +vn -0.3096 -0.0286 -0.9504 +vn -0.6386 0.0323 -0.7688 +vn -0.8469 -0.0351 -0.5306 +vn -0.9823 0.0295 -0.1848 +vn -0.9830 -0.0301 0.1810 +vn -0.9301 0.0191 0.3667 +vn -0.8501 -0.0109 0.5266 +vn -0.8069 0.0231 0.5902 +vn -0.5182 0.0000 0.8553 +vn 0.4818 0.0000 0.8763 +vn 0.9998 0.0000 0.0211 +vn 0.5182 0.0000 -0.8553 +vn -0.4818 0.0000 -0.8763 +vn -0.9998 0.0000 -0.0211 +vn -0.5292 0.8485 -0.0031 +vn -0.7727 0.1399 -0.6191 +vn -0.0822 0.8973 -0.4336 +vn 0.5272 0.8492 0.0298 +vn 0.7673 0.3597 0.5309 +vn 0.1280 0.9093 0.3960 +vn -0.0411 -0.9992 -0.0023 +vn -0.0430 -0.9988 0.0251 +vn -0.0397 -0.9992 -0.0072 +vn 0.0184 -0.9990 0.0418 +vn 0.0212 -0.9983 0.0541 +vn -0.0110 -0.9991 0.0410 +vn -0.0282 -0.9991 0.0316 +vn 0.0367 -0.9990 0.0236 +vn 0.0445 -0.9990 0.0013 +vn 0.0413 -0.9990 -0.0188 +vn 0.0586 -0.9983 0.0015 +vn 0.0298 -0.9986 -0.0444 +vn 0.0244 -0.9991 -0.0351 +vn -0.0044 -0.9992 -0.0397 +vn -0.0255 -0.9991 -0.0346 +vn -0.0375 -0.9988 -0.0329 +vn -0.0166 0.9986 -0.0495 +vn 0.0244 0.9996 0.0117 +vn 0.0037 0.9975 -0.0710 +vn 0.0310 0.9973 0.0668 +vn 0.0104 0.9956 0.0927 +vn -0.1067 0.9936 0.0357 +vn -0.8405 0.0290 0.5411 +vn -0.7165 0.0049 0.6976 +vn -0.6310 0.0222 0.7755 +vn -0.3960 -0.0039 0.9182 +vn 0.0596 0.0176 0.9981 +vn 0.3247 -0.0040 0.9458 +vn 0.4757 0.0186 0.8794 +vn 0.6316 0.0012 0.7753 +vn 0.9402 0.0199 0.3401 +vn 0.9794 0.0027 0.2018 +vn 0.9454 0.0181 0.3253 +vn 0.9823 0.0009 0.1873 +vn 0.8501 0.0281 -0.5258 +vn 0.7574 0.0052 -0.6529 +vn 0.8399 0.0253 -0.5422 +vn 0.7449 0.0025 -0.6671 +vn 0.3098 0.0157 -0.9507 +vn 0.0613 -0.0094 -0.9981 +vn 0.2889 0.0136 -0.9573 +vn 0.0409 -0.0114 -0.9991 +vn -0.5480 0.0183 -0.8363 +vn -0.6350 0.0065 -0.7725 +vn -0.5583 0.0169 -0.8294 +vn -0.6436 0.0053 -0.7653 +vn -0.9540 0.0263 -0.2988 +vn -0.9982 -0.0007 -0.0607 +vn -0.9614 0.0235 -0.2740 +vn -0.9993 -0.0032 -0.0377 +vn -0.0702 0.9970 0.0316 +vn -0.0670 0.9963 0.0539 +vn -0.0380 0.9967 0.0722 +vn 0.0276 0.9967 0.0768 +vn -0.0104 0.9968 0.0795 +vn 0.0528 0.9962 0.0689 +vn -0.0779 0.9970 0.0022 +vn -0.0689 0.9969 -0.0393 +vn 0.0724 0.9965 0.0416 +vn 0.0838 0.9960 0.0303 +vn 0.0791 0.9966 -0.0224 +vn 0.0835 0.9963 -0.0200 +vn -0.0750 0.9962 -0.0452 +vn -0.0217 0.9968 -0.0774 +vn -0.0298 0.9967 -0.0756 +vn 0.0283 0.9969 -0.0739 +vn 0.0379 0.9968 -0.0706 +vn -0.6061 -0.0226 0.7951 +vn -0.5729 0.0007 0.8197 +vn -0.5499 0.0163 0.8351 +vn -0.5170 0.0379 0.8551 +vn 0.0672 -0.0515 0.9964 +vn 0.4062 -0.0205 0.9136 +vn 0.2145 0.0198 0.9765 +vn 0.5807 0.0318 0.8135 +vn 0.8342 -0.0201 0.5511 +vn 0.9306 0.0257 0.3651 +vn 0.9974 -0.0206 0.0693 +vn 0.9612 0.0343 -0.2737 +vn 0.8878 -0.0022 -0.4602 +vn 0.7908 0.0362 -0.6110 +vn 0.7655 0.0150 -0.6433 +vn 0.2777 -0.0435 -0.9597 +vn 0.1904 0.0020 -0.9817 +vn 0.1274 0.0342 -0.9913 +vn 0.0502 0.0730 -0.9961 +vn -0.4598 -0.0593 -0.8860 +vn -0.7319 -0.0298 -0.6808 +vn -0.6173 0.0143 -0.7866 +vn -0.8775 0.0278 -0.4787 +vn -0.9922 -0.0245 -0.1225 +vn -0.9989 0.0179 0.0434 +vn -0.9789 -0.0100 0.2040 +vn -0.9561 0.0293 0.2917 +vn -0.8958 0.0000 0.4444 +vn -0.0634 0.0000 0.9980 +vn 0.8328 0.0000 0.5536 +vn 0.8958 0.0000 -0.4444 +vn 0.0634 0.0000 -0.9980 +vn -0.8328 0.0000 -0.5536 +vn -0.0601 0.9202 -0.3867 +vn 0.0706 0.9221 0.3805 +vn -0.0138 -0.9989 0.0445 +vn -0.0054 -0.9985 0.0545 +vn -0.0282 -0.9988 0.0401 +vn -0.0442 -0.9990 -0.0048 +vn -0.0376 -0.9989 -0.0287 +vn -0.0296 -0.9992 -0.0269 +vn 0.0452 -0.9989 0.0140 +vn 0.0185 -0.9992 0.0358 +vn 0.0286 -0.9993 0.0242 +vn 0.0148 -0.9982 -0.0579 +vn 0.0316 -0.9991 -0.0295 +vn 0.0114 -0.9990 -0.0436 +vn 0.0459 -0.9989 -0.0068 +vn -0.0088 -0.9991 -0.0420 +vn -0.0408 -0.9991 0.0130 +vn -0.0436 -0.9988 0.0242 +vn 0.0583 -0.9983 -0.0036 +vn -0.0316 0.9995 0.0056 +vn -0.0127 0.9954 -0.0953 +vn -0.0069 0.9999 -0.0075 +vn -0.0573 0.9905 -0.1252 +vn -0.0607 0.9957 -0.0699 +vn 0.9861 -0.0009 0.1660 +vn 0.9886 0.0014 0.1507 +vn 0.9988 0.0168 0.0461 +vn 0.9992 0.0186 0.0341 +vn 0.8583 -0.0083 -0.5130 +vn 0.6563 -0.0068 -0.7545 +vn 0.6584 0.1027 -0.7456 +vn 0.6317 0.0558 -0.7732 +vn 0.3897 -0.0075 -0.9209 +vn -0.1709 0.0150 -0.9852 +vn -0.2256 0.0096 -0.9742 +vn -0.4328 0.0162 -0.9013 +vn -0.5037 0.0064 -0.8638 +vn -0.6671 0.0155 -0.7448 +vn -0.7365 0.0017 -0.6764 +vn -0.9999 -0.0030 0.0163 +vn -0.9357 -0.0063 0.3528 +vn -0.9799 0.0057 0.1994 +vn -0.9690 0.0015 0.2469 +vn -0.7570 -0.0132 0.6533 +vn -0.2695 0.0216 0.9628 +vn -0.1484 0.0076 0.9889 +vn -0.2557 0.0200 0.9665 +vn -0.1343 0.0059 0.9909 +vn 0.4608 0.0259 0.8871 +vn 0.6070 -0.0002 0.7947 +vn 0.4759 0.0233 0.8792 +vn 0.6236 -0.0034 0.7817 +vn 0.0483 0.9974 -0.0532 +vn 0.0481 0.9969 -0.0621 +vn 0.0061 0.9960 -0.0888 +vn -0.0020 0.9957 -0.0927 +vn 0.0688 0.9969 0.0381 +vn 0.0739 0.9966 0.0371 +vn 0.0824 0.9966 -0.0074 +vn 0.0795 0.9967 -0.0167 +vn 0.0178 0.9968 0.0776 +vn 0.0364 0.9968 0.0713 +vn -0.0424 0.9966 0.0704 +vn -0.0257 0.9964 0.0807 +vn -0.0366 0.9967 -0.0725 +vn -0.0447 0.9966 -0.0686 +vn -0.0740 0.9968 -0.0301 +vn -0.0803 0.9967 -0.0149 +vn -0.0756 0.9968 0.0263 +vn -0.0736 0.9964 0.0421 +vn 0.9800 0.0046 0.1988 +vn 0.9777 0.0100 0.2098 +vn 0.9830 -0.0029 0.1834 +vn 0.9850 -0.0083 0.1725 +vn 0.8956 0.0235 -0.4442 +vn 0.9088 0.0070 -0.4173 +vn 0.9018 0.0159 -0.4319 +vn 0.8894 0.0310 -0.4561 +vn 0.3467 0.0219 -0.9377 +vn 0.5008 -0.0411 -0.8646 +vn 0.2507 -0.0204 -0.9679 +vn -0.0153 0.0314 -0.9994 +vn -0.2921 -0.0242 -0.9561 +vn -0.5963 0.0300 -0.8022 +vn -0.7606 -0.0176 -0.6489 +vn -0.8531 0.0242 -0.5211 +vn -0.9070 -0.0264 -0.4203 +vn -0.9844 0.0245 0.1741 +vn -0.9817 0.0160 0.1899 +vn -0.8724 0.0294 0.4880 +vn -0.9097 -0.0022 0.4153 +vn -0.5782 -0.0203 0.8156 +vn -0.2996 0.0380 0.9533 +vn -0.0005 -0.0208 0.9998 +vn 0.4464 0.0206 0.8946 +vn 0.5291 -0.0053 0.8485 +vn 0.7197 0.0071 0.6943 +vn 0.7123 0.0015 0.7019 +vn 0.9632 0.0000 0.2689 +vn 0.7143 0.0000 -0.6998 +vn -0.2487 0.0000 -0.9686 +vn -0.9632 0.0000 -0.2688 +vn -0.7143 0.0000 0.6998 +vn 0.2490 0.0000 0.9685 +vn 0.4162 0.7149 0.5619 +vn -0.2537 0.8849 0.3906 +vn -0.9723 -0.0928 0.2146 +vn -0.3660 0.9101 -0.1945 +vn 0.0864 0.9033 -0.4202 +vn 0.6206 0.2888 -0.7290 +vn 0.6737 0.7386 0.0238 +vn 0.6710 0.7411 0.0246 +vn 0.6614 0.7495 0.0273 +vn 0.6587 0.7519 0.0281 +vn 0.5556 0.0083 -0.8314 +vn 0.5415 -0.0390 -0.8398 +vn 0.4909 -0.1807 -0.8522 +vn 0.4793 -0.2091 -0.8524 +vn 0.1084 0.3304 -0.9376 +vn -0.1838 -0.2846 -0.9409 +vn -0.3819 0.1937 -0.9037 +vn -0.6564 -0.2572 -0.7092 +vn -0.7842 0.2941 -0.5464 +vn -0.9535 -0.2280 -0.1970 +vn -0.9548 0.2972 0.0026 +vn -0.9016 -0.3197 0.2914 +vn -0.6629 0.3880 0.6404 +vn -0.6060 -0.1572 0.7798 +vn -0.0262 -0.0064 0.9996 +vn -0.0365 -0.0570 0.9977 +vn 0.0267 0.2491 0.9681 +vn 0.0329 0.2783 0.9599 +vn 0.6017 -0.2325 0.7642 +vn 0.6941 0.3547 0.6265 +vn 0.8882 -0.3467 0.3016 +vn 0.9421 0.3353 -0.0065 +vn 0.8843 -0.3596 -0.2979 +vn 0.8446 0.1805 -0.5041 +vn 0.6756 -0.0331 0.7366 +vn 0.7096 0.3094 0.6330 +vn 0.6907 0.0422 0.7219 +vn 0.7048 0.3800 0.5990 +vn -0.8381 0.0229 0.5451 +vn -0.8349 0.0409 0.5489 +vn -0.8479 -0.0488 0.5279 +vn -0.8495 -0.0661 0.5234 +vn -0.9586 0.0758 -0.2744 +vn -0.8819 0.0562 -0.4682 +vn -0.9539 0.0912 -0.2859 +vn -0.8803 0.0432 -0.4725 +vn -0.9568 -0.2486 -0.1508 +vn -0.9480 -0.2779 -0.1552 +vn -0.6582 0.1996 -0.7259 +vn -0.6582 0.1990 -0.7261 +vn -0.6580 0.2057 -0.7243 +vn -0.6580 0.2073 -0.7239 +vn -0.1288 -0.3314 -0.9347 +vn 0.0489 0.3454 -0.9372 +vn 0.3492 -0.2695 -0.8975 +vn 0.5407 0.3482 -0.7658 +vn 0.7509 -0.4166 -0.5124 +vn 0.8624 0.4220 -0.2797 +vn 0.8734 -0.4822 0.0686 +vn 0.8868 0.3654 0.2831 +vn 0.6375 -0.1422 0.7572 +vn 0.6394 -0.1331 0.7572 +vn 0.6300 -0.1748 0.7567 +vn 0.6290 -0.1785 0.7566 +vn 0.0567 0.0952 0.9938 +vn 0.0590 0.1068 0.9925 +vn 0.2505 -0.0034 0.9681 +vn 0.2484 -0.0145 0.9685 +vn 0.4407 -0.0435 0.8966 +vn 0.4429 -0.0370 0.8958 +vn -0.5582 0.0474 0.8283 +vn -0.5538 0.0645 0.8302 +vn -0.5748 -0.0233 0.8180 +vn -0.5784 -0.0411 0.8147 +vn -0.7050 -0.0035 -0.7092 +vn -0.7107 0.0268 -0.7030 +vn -0.7063 0.0028 -0.7080 +vn -0.7118 0.0330 -0.7016 +vn 0.7691 0.0543 0.6368 +vn 0.7248 0.1319 0.6763 +vn 0.8321 -0.0920 0.5469 +vn 0.6344 -0.0202 -0.7728 +vn 0.2863 0.4020 -0.8698 +vn -0.6571 -0.3470 -0.6692 +vn -0.8765 0.3798 0.2958 +vn -0.6172 -0.2317 0.7519 +vn 0.6412 0.2513 0.7251 +vn 0.9450 0.1718 0.2785 +vn 0.9491 -0.2601 -0.1776 +vn 0.4685 0.2420 -0.8497 +vn -0.3358 -0.2981 -0.8935 +vn -0.8342 0.3108 -0.4556 +vn -0.8893 -0.2588 0.3771 +vn -0.2783 0.2456 0.9286 +vn 0.1404 -0.1470 0.9791 +vn 0.0001 0.9859 0.1672 +vn -0.0004 0.9893 0.1457 +vn -0.0010 0.8201 0.5722 +vn 0.0003 0.8458 0.5336 +vn 0.0010 0.6037 0.7972 +vn -0.0014 0.4745 0.8802 +vn 0.0014 0.2702 0.9628 +vn -0.0012 0.1085 0.9941 +vn 0.0015 -0.1922 0.9814 +vn -0.0016 -0.3140 0.9494 +vn 0.0018 -0.6302 0.7764 +vn -0.0018 -0.7385 0.6743 +vn 0.0009 -0.9162 0.4007 +vn -0.0004 -0.9535 0.3014 +vn 0.0001 -0.9985 -0.0541 +vn 0.0002 -1.0000 -0.0036 +vn 0.0003 -0.9296 -0.3686 +vn -0.0002 -0.9151 -0.4033 +vn -0.0009 -0.6656 -0.7463 +vn 0.0003 -0.7164 -0.6977 +vn 0.0010 -0.4249 -0.9052 +vn -0.0015 -0.2144 -0.9767 +vn 0.0008 -0.0891 -0.9960 +vn -0.0006 0.2152 -0.9766 +vn 0.0003 0.2566 -0.9665 +vn -0.0004 0.5554 -0.8316 +vn 0.0004 0.5823 -0.8130 +vn -0.0004 0.8328 -0.5536 +vn 0.0004 0.8505 -0.5260 +vn -0.0003 0.9749 -0.2227 +vn 0.0003 0.9812 -0.1931 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.7234 0.1231 -0.6794 +vn -0.7299 0.0230 -0.6832 +vn -0.7290 -0.0409 -0.6833 +vn -0.7789 0.1778 -0.6014 +vn -0.6416 0.0504 -0.7654 +vn -0.7339 -0.0436 -0.6779 +vn -0.2451 0.2922 -0.9244 +vn -0.1092 0.2482 -0.9625 +vn -0.0151 0.3447 -0.9386 +vn -0.7830 -0.1002 -0.6139 +vn -0.6878 -0.1504 -0.7102 +vn -0.5816 -0.1600 -0.7976 +vn -0.3661 -0.2639 -0.8924 +vn -0.5774 -0.0386 -0.8156 +vn -0.4284 -0.2286 -0.8742 +vn -0.2111 -0.1504 -0.9658 +vn -0.5610 0.1354 -0.8166 +vn -0.3605 -0.0318 -0.9322 +vn -0.0864 -0.1673 -0.9821 +vn -0.0563 -0.3256 -0.9438 +vn -0.1212 0.0451 -0.9916 +vn -0.3740 0.1836 -0.9091 +vn -0.5745 0.2052 -0.7924 +vn -0.6120 -0.0285 -0.7903 +vn -0.2772 0.0062 -0.9608 +vn -0.2790 0.0022 -0.9603 +vn 0.1896 0.0048 -0.9819 +vn 0.1398 -0.0054 -0.9902 +vn 0.6102 -0.0159 -0.7921 +vn 0.6172 0.0118 -0.7867 +vn 0.9166 0.0105 -0.3996 +vn 0.9524 -0.0176 -0.3043 +vn 0.9846 0.0154 0.1744 +vn 0.9696 -0.0088 0.2446 +vn 0.8912 0.0094 0.4536 +vn 0.8801 -0.0040 0.4747 +vn -0.0001 -1.0000 -0.0002 +vn -0.0001 -1.0000 -0.0001 +vn -0.0001 -1.0000 0.0000 +vn 0.0033 -1.0000 -0.0029 +vn 0.1825 -0.9758 -0.1206 +vn 0.0015 -1.0000 -0.0047 +vn 0.0079 -0.9999 -0.0079 +vn 0.2085 -0.9679 -0.1405 +vn 0.0079 -1.0000 -0.0042 +vn 0.2029 -0.9469 -0.2493 +vn -0.0003 -1.0000 -0.0003 +vn -0.0004 -1.0000 -0.0061 +vn -0.0001 -1.0000 -0.0011 +vn 0.2716 -0.9623 0.0112 +vn 0.0001 -1.0000 -0.0002 +vn 0.0008 -1.0000 -0.0051 +vn 0.0768 -0.9954 -0.0575 +vn -0.0001 -1.0000 -0.0003 +vn 0.3450 -0.7091 -0.6149 +vn 0.2540 -0.6888 -0.6790 +vn 0.0896 -0.5209 -0.8489 +vn 0.4066 -0.7608 -0.5059 +vn 0.6352 -0.5119 -0.5784 +vn 0.6946 -0.5142 -0.5032 +vn 0.7327 -0.5036 -0.4578 +vn 0.7137 -0.5042 -0.4863 +vn 0.0064 1.0000 -0.0037 +vn 0.0139 0.9998 -0.0140 +vn 0.0081 1.0000 0.0001 +vn -0.0001 1.0000 -0.0011 +vn -0.0004 1.0000 -0.0049 +vn 0.2226 0.9748 -0.0142 +vn 0.0004 1.0000 -0.0050 +vn -0.0001 1.0000 -0.0001 +vn -0.0002 1.0000 -0.0002 +vn -0.0001 1.0000 -0.0002 +vn -0.0003 1.0000 -0.0005 +vn -0.0002 1.0000 -0.0004 +vn -0.0002 1.0000 -0.0001 +vn 0.0114 0.9998 -0.0146 +vn 0.0079 0.9999 -0.0084 +vn 0.1925 0.9501 -0.2456 +vn 0.1010 0.9927 -0.0657 +vn 0.2185 0.9656 -0.1409 +vn 0.7295 0.4985 -0.4684 +vn 0.5649 0.7161 -0.4101 +vn 0.6859 0.5172 -0.5118 +vn 0.5816 0.7174 -0.3834 +vn 0.4430 0.6926 -0.5693 +vn 0.2219 0.6621 -0.7158 +vn 0.1315 0.5431 -0.8293 +vn 0.0029 -1.0000 0.0022 +vn -0.2736 -0.9389 0.2087 +vn -0.2882 -0.9370 -0.1973 +vn -0.0022 0.8855 0.4647 +vn 0.0001 0.9186 0.3951 +vn -0.2782 0.9040 0.3246 +vn -0.0007 0.8478 0.5303 +vn -0.2502 0.7216 0.6456 +vn 0.0025 0.7323 0.6809 +vn -0.2437 0.4497 0.8593 +vn -0.0004 0.4395 0.8983 +vn -0.2668 0.0884 0.9597 +vn 0.0073 -0.0278 0.9996 +vn -0.2473 -0.2798 0.9277 +vn 0.0042 -0.4195 0.9077 +vn -0.2935 -0.5675 0.7693 +vn 0.0020 -0.7132 0.7009 +vn -0.2926 -0.7953 0.5309 +vn 0.0016 -0.8347 0.5506 +vn -0.0007 -0.8801 0.4747 +vn -0.0022 -0.9159 0.4014 +vn 0.0026 -0.9668 0.2554 +vn 0.0067 -0.9465 -0.3227 +vn -0.2795 -0.7869 -0.5501 +vn -0.2981 -0.5356 -0.7901 +vn -0.2782 -0.2272 -0.9333 +vn 0.0030 -0.3606 -0.9327 +vn 0.0482 0.1558 -0.9866 +vn -0.2954 0.1640 -0.9412 +vn -0.2639 0.5525 -0.7906 +vn -0.2735 0.8491 -0.4519 +vn 0.0011 0.9366 -0.3504 +vn -0.2734 0.9613 -0.0347 +vn 0.0023 0.9980 -0.0634 +vn 0.0028 0.9730 0.2309 +vn 0.4379 0.4546 -0.7756 +vn 0.3643 0.7053 -0.6082 +vn 0.6162 0.5458 -0.5677 +vn 0.6168 0.5004 -0.6076 +vn 0.4806 0.6926 -0.5379 +vn 0.7283 -0.5071 -0.4609 +vn 0.5182 -0.7021 -0.4883 +vn 0.5945 -0.4978 -0.6315 +vn 0.3926 -0.6916 -0.6063 +vn 0.6216 -0.5442 -0.5634 +vn 0.4261 -0.6982 -0.5753 +vn -0.3718 -0.9283 0.0063 +vn -0.4213 -0.8304 -0.3646 +vn -0.4185 -0.6384 -0.6460 +vn -0.4877 -0.3409 -0.8037 +vn -0.4145 -0.0092 -0.9100 +vn -0.4485 0.3965 -0.8011 +vn -0.4868 0.7033 -0.5181 +vn -0.4233 0.8877 -0.1810 +vn -0.4696 0.8638 0.1824 +vn -0.4805 0.7063 0.5198 +vn -0.4896 0.3819 0.7839 +vn -0.5166 0.0320 0.8557 +vn -0.4906 -0.2976 0.8190 +vn -0.4483 -0.6413 0.6227 +vn -0.4635 -0.8215 0.3322 +vn -0.9994 0.0091 0.0345 +vn -0.9987 -0.0032 0.0500 +vn -0.9083 0.0042 0.4182 +vn -0.9107 0.0049 0.4131 +vn -0.6463 0.0099 0.7630 +vn -0.7054 -0.0136 0.7087 +vn -0.3144 -0.0118 0.9492 +vn -0.2269 0.0067 0.9739 +vn 0.1189 -0.0050 0.9929 +vn 0.1536 -0.0153 0.9880 +vn 0.4677 0.0140 0.8838 +vn 0.5994 -0.0254 0.8001 +vn 0.7930 0.0215 0.6089 +vn 0.9100 -0.0220 0.4140 +vn 0.9863 0.0222 0.1632 +vn 0.9997 -0.0186 0.0135 +vn 0.9676 0.0189 -0.2518 +vn 0.9348 -0.0141 -0.3550 +vn 0.7878 0.0118 -0.6159 +vn 0.7133 -0.0213 -0.7005 +vn 0.5187 0.0145 -0.8549 +vn 0.3686 -0.0264 -0.9292 +vn 0.1662 0.0155 -0.9860 +vn -0.1433 -0.0277 -0.9893 +vn -0.2816 0.0045 -0.9595 +vn -0.6534 -0.0240 -0.7567 +vn -0.6009 0.0135 -0.7992 +vn -0.8984 0.0142 -0.4390 +vn -0.9444 -0.0164 -0.3284 +vn 0.9739 -0.0104 0.2269 +vn 0.9879 0.0131 0.1545 +vn 0.7929 0.0103 0.6093 +vn 0.7693 -0.0065 0.6389 +vn 0.3922 0.0069 0.9199 +vn 0.3565 -0.0110 0.9342 +vn -0.0878 0.0121 0.9961 +vn -0.1896 -0.0232 0.9816 +vn -0.5000 0.0126 0.8659 +vn -0.6941 -0.0366 0.7189 +vn -0.8120 0.0043 0.5836 +vn -0.9800 -0.0265 0.1970 +vn -0.9741 0.0279 0.2242 +vn -0.9819 0.0103 -0.1891 +vn -0.9337 -0.0308 -0.3567 +vn -0.8240 0.0197 -0.5663 +vn -0.6700 -0.0246 -0.7419 +vn -0.5191 0.0205 -0.8545 +vn -0.2645 -0.0234 -0.9641 +vn -0.0925 0.0233 -0.9954 +vn 0.2131 -0.0294 -0.9766 +vn 0.3743 0.0140 -0.9272 +vn 0.7258 -0.0170 -0.6877 +vn 0.7752 0.0128 -0.6316 +vn 0.9598 0.0010 -0.2807 +vn 0.9751 -0.0147 -0.2213 +vn 0.4468 0.8208 -0.3560 +vn 0.8423 0.5358 -0.0590 +vn 0.7741 0.6323 -0.0323 +vn 0.7514 0.2629 0.6053 +vn 0.7598 0.5655 0.3209 +vn 0.6083 0.0891 0.7887 +vn 0.8054 -0.5110 0.3004 +vn 0.6411 -0.1535 0.7520 +vn 0.6926 -0.1913 0.6955 +vn 0.8279 -0.3704 0.4212 +vn 0.7393 -0.6715 -0.0498 +vn 0.7825 -0.5670 -0.2573 +vn 0.7047 -0.6151 -0.3536 +vn 0.6467 0.6725 0.3599 +vn 0.7027 0.6967 0.1443 +vn 0.4264 0.9012 -0.0774 +vn 0.3361 0.9417 -0.0166 +vn 0.3171 0.9045 -0.2852 +vn 0.2966 0.8353 -0.4630 +vn 0.6642 -0.7154 0.2169 +vn 0.2935 -0.8791 -0.3756 +vn 0.4899 -0.8698 -0.0583 +vn 0.3707 -0.8923 -0.2578 +vn 0.3849 -0.8976 -0.2146 +vn 0.2108 -0.8941 -0.3951 +vn 0.1086 -0.9586 -0.2634 +vn 0.3998 -0.8349 -0.3783 +vn -0.9999 0.0140 -0.0045 +vn -1.0000 0.0026 -0.0019 +vn -1.0000 -0.0018 -0.0061 +vn -0.9991 -0.0106 -0.0406 +vn -0.9984 -0.0114 -0.0546 +vn -0.9999 0.0169 -0.0027 +vn -0.9998 0.0145 -0.0141 +vn -0.9997 0.0213 -0.0129 +vn -0.9974 0.0652 -0.0291 +vn -0.9983 0.0540 -0.0196 +vn -1.0000 -0.0065 0.0069 +vn -0.9996 -0.0073 0.0289 +vn -0.9997 -0.0219 0.0067 +vn -0.9989 -0.0222 0.0414 +vn -0.9964 -0.0528 0.0656 +vn -0.9937 -0.0597 0.0943 +vn -0.9880 0.0845 0.1290 +vn -0.9825 0.0978 0.1587 +vn -0.9999 0.0118 0.0074 +vn -0.9985 0.0289 0.0474 +vn -1.0000 -0.0002 0.0001 +vn -1.0000 -0.0004 -0.0004 +vn -1.0000 -0.0002 0.0003 +vn -1.0000 0.0000 0.0005 +vn -1.0000 -0.0001 -0.0001 +vn -1.0000 0.0001 -0.0001 +vn -1.0000 0.0006 0.0006 +vn -1.0000 -0.0003 -0.0001 +vn 0.5057 0.0134 0.8626 +vn 0.5007 -0.0004 0.8656 +vn 0.5006 0.0004 0.8657 +vn 0.5005 0.0001 0.8657 +vn 0.4953 0.0011 0.8687 +vn 0.5058 0.0009 0.8627 +vn 0.4922 0.0000 0.8705 +vn 0.5183 -0.0009 0.8552 +vn 0.5187 -0.0016 0.8549 +vn 0.5019 -0.0034 0.8649 +vn 0.4975 0.0009 0.8675 +vn 0.3513 0.7125 0.6074 +vn 0.3534 0.7108 0.6081 +vn 0.3545 0.7100 0.6085 +vn 0.3561 0.7087 0.6090 +vn 0.3757 -0.6993 0.6082 +vn 0.3742 -0.6924 0.6169 +vn 0.3719 -0.6820 0.6297 +vn 0.3696 -0.6722 0.6415 +vn 0.8587 0.1153 -0.4993 +vn 0.8552 -0.0053 -0.5182 +vn 0.8560 -0.0064 -0.5169 +vn 0.7932 0.3651 -0.4874 +vn 0.0477 0.9988 -0.0120 +vn 0.0454 0.9990 0.0011 +vn 0.0208 0.9998 0.0021 +vn 0.0243 0.9996 0.0106 +vn 0.0318 0.9993 -0.0213 +vn -0.2410 0.9623 0.1260 +vn -0.0305 0.9989 0.0361 +vn -0.1483 0.9830 0.1082 +vn -0.8666 -0.0075 0.4989 +vn -0.8612 0.1169 0.4947 +vn -0.8719 0.0006 0.4896 +vn -0.8707 0.0819 0.4849 +vn 0.0437 -0.9977 0.0522 +vn 0.0068 -0.9991 0.0409 +vn -0.0047 -1.0000 0.0060 +vn -0.0166 -0.9998 0.0079 +vn 0.0080 -0.9999 0.0152 +vn 0.0087 -0.9998 0.0182 +vn 0.0182 -0.9996 0.0194 +vn 0.0189 -0.9996 0.0193 +vn -0.5000 -0.0004 -0.8660 +vn -0.5000 -0.0003 -0.8660 +vn -0.5000 -0.0001 -0.8660 +vn -0.5000 0.0000 -0.8661 +vn -0.5001 -0.0000 -0.8660 +vn -0.5001 0.0002 -0.8660 +vn -0.4999 0.0002 -0.8661 +vn -0.4999 -0.0001 -0.8661 +vn -0.5000 -0.0007 -0.8660 +vn -0.4999 -0.0000 -0.8661 +vn -0.5001 -0.0002 -0.8660 +vn -0.5000 -0.0000 -0.8660 +vn -0.5001 0.0001 -0.8660 +vn -0.5001 -0.0001 -0.8660 +vn 0.3533 -0.7097 0.6095 +vn 0.3532 -0.7079 0.6117 +vn 0.3533 -0.7088 0.6106 +vn 0.3534 -0.7102 0.6089 +vn 0.3530 0.7080 0.6117 +vn 0.3531 0.7081 0.6114 +vn 0.3531 0.7079 0.6117 +vn 0.3532 0.7079 0.6116 +vn 0.3535 0.7070 0.6125 +vn 0.5000 -0.0001 0.8660 +vn 0.5000 0.0001 0.8660 +vn 0.5000 -0.0002 0.8660 +vn 0.4999 -0.0000 0.8661 +vn 0.5001 -0.0000 0.8660 +vn 0.5000 0.0000 0.8660 +vn 0.4999 0.0001 0.8661 +vn 0.7878 -0.3820 -0.4832 +vn 0.8775 -0.1440 -0.4575 +vn 0.7500 -0.5264 -0.4006 +vn 0.4140 -0.8613 -0.2945 +vn 0.3809 -0.9085 -0.1717 +vn 0.0419 -0.9959 -0.0807 +vn -0.4964 -0.8157 0.2970 +vn -0.3994 -0.8693 0.2912 +vn -0.4369 -0.8502 0.2938 +vn -0.5428 -0.7850 0.2986 +vn -0.8655 -0.1256 0.4849 +vn -0.8632 -0.0959 0.4956 +vn -0.8443 -0.2098 0.4932 +vn -0.8165 -0.3444 0.4633 +vn -0.8655 -0.3398 0.3681 +vn -0.3275 -0.8802 0.3434 +vn 0.1825 -0.9421 -0.2813 +vn 0.9131 -0.2359 -0.3326 +vn 0.7321 0.3817 -0.5642 +vn 0.1765 0.9843 0.0061 +vn -0.3478 0.9337 0.0847 +vn -0.7477 0.3685 0.5524 +vn 0.4998 -0.0001 0.8661 +vn 0.5001 -0.0002 0.8660 +vn 0.5000 -0.0003 0.8660 +vn 0.4998 0.0000 0.8661 +vn 0.5000 -0.0004 0.8660 +vn 0.4998 0.0007 0.8662 +vn 0.4997 0.0007 0.8662 +vn 0.4998 -0.0001 0.8662 +vn -0.7964 0.4279 0.4275 +vn -0.8085 0.3413 0.4794 +vn -0.7368 0.5033 0.4515 +vn 0.7958 0.3501 -0.4941 +vn 0.7830 0.4609 -0.4176 +vn 0.7922 0.4209 -0.4418 +vn 0.2827 0.9452 -0.1635 +vn 0.1725 0.9737 -0.1489 +vn 0.2377 0.9584 -0.1578 +vn 0.1384 0.9798 -0.1441 +vn -0.4176 0.8455 0.3327 +vn -0.6942 0.6224 0.3615 +vn 0.8225 0.3536 -0.4455 +vn 0.8490 0.1287 -0.5125 +vn -0.7980 -0.2952 0.5254 +vn -0.7854 -0.4191 0.4555 +vn -0.7950 -0.3445 0.4993 +vn -0.7746 -0.4718 0.4212 +vn 0.1063 -0.9942 -0.0183 +vn 0.1862 -0.9709 -0.1504 +vn 0.1492 -0.9848 -0.0887 +vn 0.2241 -0.9507 -0.2145 +vn 0.8967 0.1575 -0.4138 +vn 0.8548 0.2495 -0.4551 +vn 0.8761 0.2059 -0.4360 +vn 0.8238 0.3049 -0.4780 +vn -0.1497 0.9722 0.1799 +vn 0.0690 0.9922 -0.1041 +vn -0.0330 0.9991 0.0282 +vn -0.2200 0.9370 0.2715 +vn -0.7647 0.5357 0.3582 +vn -0.7454 0.4464 0.4951 +vn -0.7144 0.5741 0.4000 +vn 0.7599 0.3420 -0.5528 +vn 0.5168 0.8252 -0.2281 +vn 0.5709 -0.7067 -0.4178 +vn 0.8653 -0.2761 -0.4183 +vn -0.7530 -0.4652 0.4654 +vn -0.7141 -0.5933 0.3715 +vn 0.7921 0.4339 -0.4292 +vn 0.5975 0.6972 -0.3961 +vn 0.6808 -0.6343 -0.3663 +vn 0.4705 -0.8247 -0.3137 +vn 0.5153 -0.7925 -0.3262 +vn 0.7073 -0.6014 -0.3716 +vn -0.5111 0.8251 0.2409 +vn -0.7760 0.3938 0.4927 +vn -0.6814 -0.6273 0.3771 +vn -0.6741 -0.6409 0.3671 +vn -0.7068 -0.5740 0.4134 +vn -0.7114 -0.5633 0.4202 +vn 0.5009 -0.0565 0.8636 +vn 0.4987 -0.0677 0.8641 +vn 0.4989 -0.0669 0.8641 +vn 0.4937 -0.0441 0.8685 +vn 0.4681 0.0578 0.8818 +vn 0.4944 -0.0478 0.8679 +vn 0.4971 -0.0641 0.8654 +vn 0.4989 -0.0698 0.8639 +vn 0.4965 -0.0789 0.8644 +vn 0.4966 -0.0621 0.8658 +vn 0.4883 -0.0354 0.8719 +vn 0.4976 -0.0747 0.8642 +vn 0.4905 -0.1006 0.8656 +vn 0.5611 -0.0491 0.8263 +vn 0.5555 0.0119 0.8314 +vn 0.5635 -0.0230 0.8258 +vn 0.4557 0.0304 0.8896 +vn 0.4523 -0.0198 0.8916 +vn 0.4606 -0.0331 0.8870 +vn 0.4557 -0.0403 0.8892 +vn 0.4298 0.0306 0.9024 +vn 0.4762 0.0593 0.8773 +vn 0.5258 0.0588 0.8486 +vn 0.5248 0.0492 0.8498 +vn 0.5453 -0.0622 0.8359 +vn -0.5002 0.1921 -0.8443 +vn -0.4840 0.2298 -0.8444 +vn -0.4778 0.0739 -0.8754 +vn -0.4953 0.0062 -0.8687 +vn -0.7755 -0.4696 0.4220 +vn -0.7463 -0.5185 0.4173 +vn -0.7794 -0.4626 0.4226 +vn -0.7982 0.3719 0.4739 +vn -0.7886 0.4089 0.4592 +vn -0.7739 0.5723 0.2712 +vn -0.7471 0.5966 0.2932 +vn 0.0256 0.9996 0.0150 +vn 0.0586 0.9982 -0.0122 +vn 0.2603 0.9486 -0.1801 +vn 0.2919 0.9338 -0.2067 +vn 0.7898 0.3745 -0.4859 +vn 0.7578 0.4787 -0.4433 +vn 0.7633 0.4636 -0.4500 +vn 0.7946 0.3538 -0.4933 +vn 0.6520 -0.6614 -0.3707 +vn 0.6327 -0.6910 -0.3497 +vn 0.6485 -0.6669 -0.3669 +vn 0.6302 -0.6946 -0.3470 +vn -0.0878 -0.9870 -0.1344 +vn -0.2056 -0.9712 0.1204 +vn -0.1173 -0.9818 -0.1492 +vn -0.2289 -0.9635 0.1391 +vn -0.7409 -0.5271 0.4163 +vn -0.5640 -0.1017 -0.8195 +vn -0.5632 -0.1008 -0.8201 +vn -0.6041 -0.0356 -0.7961 +vn -0.6028 -0.0186 -0.7976 +vn -0.4321 0.1127 -0.8948 +vn -0.3959 0.0805 -0.9148 +vn -0.3857 -0.0145 -0.9225 +vn -0.4937 0.1319 -0.8596 +vn -0.5661 0.1199 -0.8156 +vn -0.5994 0.0684 -0.7975 +vn -0.3775 -0.0356 -0.9253 +vn -0.4732 -0.1249 -0.8721 +vn -0.4215 -0.1103 -0.9001 +vn -0.5036 -0.1378 -0.8529 +vn -0.7135 -0.5692 0.4085 +vn -0.7330 -0.5490 0.4016 +vn -0.7218 -0.5607 0.4056 +vn -0.8611 0.1267 0.4924 +vn -0.8704 0.1073 0.4805 +vn -0.8670 0.1146 0.4850 +vn -0.8766 0.0938 0.4721 +vn -0.6228 0.6645 0.4130 +vn -0.5744 0.7616 0.2999 +vn -0.5497 0.7971 0.2498 +vn -0.4982 0.8530 0.1554 +vn 0.0440 0.9920 0.1186 +vn 0.3531 0.8689 -0.3469 +vn 0.6035 0.7174 -0.3480 +vn 0.6777 0.5785 -0.4539 +vn 0.8810 0.1576 -0.4461 +vn 0.8265 -0.2061 -0.5238 +vn 0.8064 -0.3953 -0.4398 +vn 0.6684 -0.5673 -0.4811 +vn 0.3283 -0.9358 -0.1286 +vn 0.2919 -0.9477 -0.1290 +vn 0.2634 -0.9560 -0.1291 +vn 0.2192 -0.9671 -0.1291 +vn -0.2568 -0.9530 0.1605 +vn -0.2552 -0.9540 0.1575 +vn -0.2560 -0.9535 0.1590 +vn -0.2543 -0.9545 0.1559 +vn -0.7017 -0.5810 0.4124 +vn -0.8874 -0.2858 0.3618 +vn -0.8426 -0.3507 0.4088 +vn -0.8441 -0.3486 0.4073 +vn -0.7875 -0.4160 0.4547 +vn -0.3375 0.4516 0.8259 +vn -0.2665 0.9144 0.3047 +vn 0.7389 0.3335 -0.5854 +vn 0.7652 0.3699 -0.5270 +vn 0.7579 0.3595 -0.5443 +vn 0.7940 0.4159 -0.4433 +vn 0.2226 -0.9664 -0.1285 +vn 0.3165 -0.9431 -0.1024 +vn 0.3137 -0.9439 -0.1033 +vn 0.3972 -0.9144 -0.0784 +vn -0.2462 -0.8750 -0.4168 +vn -0.0637 -0.4568 -0.8873 +vn -0.1201 -0.4502 -0.8848 +vn 0.0104 -0.4632 -0.8862 +vn 0.0888 -0.4672 -0.8797 +vn 0.3660 0.1535 -0.9179 +vn -0.5061 0.4178 -0.7545 +vn -0.8368 0.5474 0.0130 +vn -0.8711 -0.2811 -0.4026 +vn -0.8707 -0.2773 -0.4063 +vn -0.8719 -0.2870 -0.3969 +vn -0.8723 -0.2910 -0.3929 +vn 0.4390 0.0161 0.8983 +vn 0.4504 -0.0296 0.8923 +vn 0.4618 0.0278 0.8866 +vn 0.4825 0.0594 0.8739 +vn 0.4885 -0.0670 0.8700 +vn 0.5343 -0.0800 0.8415 +vn 0.4994 -0.0541 0.8647 +vn 0.5418 -0.0359 0.8398 +vn 0.5570 0.0243 0.8302 +vn 0.5369 0.0281 0.8432 +vn 0.5116 0.0582 0.8573 +vn -0.5422 0.0359 -0.8395 +vn -0.4913 0.1192 -0.8628 +vn -0.5637 0.1706 -0.8082 +vn -0.5846 0.1475 -0.7978 +vn -0.6606 0.6444 0.3852 +vn -0.8682 0.3081 0.3890 +vn -0.6823 0.6198 0.3878 +vn -0.8863 0.2577 0.3847 +vn -0.3900 0.8894 0.2384 +vn 0.3475 0.8882 -0.3005 +vn 0.3213 0.9253 -0.2014 +vn 0.3312 0.9198 -0.2104 +vn 0.3350 0.8811 -0.3339 +vn 0.8037 0.3906 -0.4488 +vn 0.8319 -0.1638 -0.5302 +vn 0.7667 -0.4818 -0.4244 +vn 0.8276 -0.2203 -0.5163 +vn 0.7446 -0.5350 -0.3992 +vn -0.0284 -0.9991 -0.0328 +vn -0.1752 -0.9789 0.1050 +vn -0.0570 -0.9984 -0.0061 +vn -0.2052 -0.9696 0.1333 +vn -0.8707 -0.1803 0.4575 +vn -0.8399 -0.2835 0.4629 +vn -0.8449 -0.2688 0.4625 +vn -0.8733 -0.1697 0.4567 +vn -0.5848 0.0596 -0.8090 +vn -0.5997 0.0540 -0.7984 +vn -0.5447 0.1183 -0.8303 +vn -0.5041 0.1293 -0.8539 +vn -0.5761 -0.0728 -0.8141 +vn -0.6025 -0.0176 -0.7979 +vn -0.3807 -0.0077 -0.9247 +vn -0.3707 0.0280 -0.9283 +vn -0.3971 -0.0820 -0.9141 +vn -0.4506 -0.1187 -0.8848 +vn -0.4021 0.0968 -0.9105 +vn -0.4979 -0.1269 -0.8579 +vn -0.4470 0.1227 -0.8861 +vn -0.5726 -0.1011 -0.8136 +vn -0.6410 0.6433 0.4187 +vn -0.6321 0.6695 0.3902 +vn -0.6244 0.6894 0.3672 +vn -0.6116 0.7182 0.3319 +vn -0.0614 0.9980 0.0115 +vn -0.0403 0.9991 0.0151 +vn -0.0455 0.9989 0.0142 +vn -0.0237 0.9996 0.0179 +vn 0.6205 0.7170 -0.3176 +vn 0.6348 0.6669 -0.3902 +vn 0.6366 0.6583 -0.4016 +vn 0.6445 0.6077 -0.4641 +vn 0.8462 -0.2041 -0.4922 +vn 0.8901 -0.1037 -0.4438 +vn 0.7908 -0.4350 -0.4305 +vn 0.6546 -0.6164 -0.4377 +vn 0.4147 -0.8829 -0.2201 +vn 0.3124 -0.9256 -0.2139 +vn 0.1820 -0.9829 -0.0264 +vn -0.3538 -0.9243 0.1433 +vn -0.4290 -0.8609 0.2735 +vn -0.5719 -0.7657 0.2945 +vn -0.7403 -0.4728 0.4780 +vn -0.8690 -0.1722 0.4638 +vn -0.8519 0.0371 0.5223 +vn -0.8736 0.1733 0.4547 +vn -0.8592 0.4977 0.1181 +vn -0.0258 0.9191 0.3932 +vn 0.5575 0.4467 -0.6997 +vn 0.9480 -0.2696 -0.1692 +vn -0.1891 -0.9444 -0.2691 +vn -0.4305 -0.6491 0.6272 +vn 0.0756 -0.0277 0.9968 +vn -0.9226 -0.2574 -0.2874 +vn -0.3329 -0.7812 -0.5281 +vn -0.3472 -0.7680 -0.5382 +vn -0.3107 -0.8008 -0.5121 +vn -0.3035 -0.8069 -0.5067 +vn 0.2264 -0.0754 -0.9711 +vn 0.2674 -0.0637 -0.9615 +vn 0.1696 -0.0911 -0.9813 +vn 0.1422 -0.0985 -0.9849 +vn 0.2247 0.8432 -0.4884 +vn -0.5833 0.3854 -0.7149 +vn -1.0000 -0.0008 0.0006 +vn -1.0000 -0.0005 0.0004 +vn -1.0000 0.0010 0.0010 +vn -1.0000 0.0043 0.0032 +vn -1.0000 0.0074 0.0055 +vn -0.0000 -1.0000 -0.0001 +vn -0.0002 -1.0000 -0.0010 +vn 1.0000 0.0001 0.0000 +vn 1.0000 0.0005 -0.0001 +vn -0.0348 -0.5573 -0.8296 +vn 1.0000 -0.0001 -0.0000 +vn 1.0000 0.0002 -0.0000 +vn 1.0000 0.0000 0.0001 +vn 1.0000 0.0004 0.0003 +vn -0.0000 1.0000 -0.0006 +vn -0.0000 1.0000 -0.0010 +vn -0.1300 -0.9683 0.2135 +vn -0.1178 -0.9862 -0.1166 +vn 0.0917 0.9587 0.2694 +vn 0.0759 0.9028 0.4233 +vn 0.1480 0.9125 0.3815 +vn 0.4917 0.0032 -0.8708 +vn 0.4225 0.3758 -0.8248 +vn 0.7356 0.1674 -0.6564 +vn -0.1312 0.9775 0.1650 +vn -0.1311 0.9775 0.1650 +vn -0.4011 0.2156 0.8903 +vn -0.6590 0.1455 0.7380 +vn -0.7901 0.1741 0.5877 +vn 0.8948 0.0287 0.4455 +vn 0.6753 -0.3577 0.6450 +vn 0.9277 -0.1973 0.3169 +vn 0.0852 0.9586 -0.2716 +vn 0.0130 -0.7269 0.6866 +vn 0.0067 -0.7092 0.7049 +vn 0.0080 -0.7105 0.7036 +vn 0.5751 -0.0325 0.8174 +vn 0.4370 -0.0182 0.8993 +vn 0.4502 0.0116 0.8929 +vn 0.0976 -0.0902 -0.9911 +vn 0.0931 -0.0553 -0.9941 +vn 0.1236 0.1589 -0.9795 +vn -0.0869 -0.0968 0.9915 +vn -0.0621 -0.1192 0.9909 +vn -0.0921 -0.1051 0.9902 +vn -0.7092 0.1341 -0.6922 +vn -0.2844 0.3265 0.9014 +vn -0.1598 0.6210 0.7673 +vn -0.4520 0.6677 0.5915 +vn 0.1178 -0.9862 0.1166 +vn 0.2222 -0.9002 0.3744 +vn 0.1178 -0.9862 0.1165 +vn 0.8686 0.4828 0.1114 +vn 0.7281 0.6058 0.3206 +vn 0.8949 0.3168 0.3142 +vn -0.1595 -0.2301 -0.9600 +vn 0.0198 -0.1189 -0.9927 +vn 0.2373 -0.3011 -0.9236 +vn -0.8213 0.4995 0.2757 +vn -0.8676 -0.0417 0.4954 +vn -0.7390 0.5374 0.4062 +vn 0.6056 -0.7758 0.1770 +vn 0.2823 -0.9461 0.1584 +vn 0.5894 -0.8076 0.0169 +vn -0.5437 -0.0855 -0.8349 +vn -0.6058 -0.0881 -0.7907 +vn -0.7798 -0.0914 -0.6194 +vn 0.5893 0.1214 0.7987 +vn 0.7624 0.1392 0.6319 +vn 0.5893 0.1214 0.7988 +vn 0.6701 0.2885 -0.6839 +vn 0.5308 0.0140 -0.8474 +vn 0.4855 0.4107 -0.7718 +vn 0.1397 0.6196 0.7723 +vn 0.0584 0.6674 0.7424 +vn 0.1430 0.4895 0.8602 +vn 0.2111 0.4571 -0.8640 +vn 0.0738 0.4424 -0.8938 +vn -0.0086 0.4632 -0.8862 +vn -0.4258 0.7803 0.4580 +vn -0.2445 0.7592 0.6032 +vn -0.2392 0.7974 0.5540 +vn 0.1808 0.1832 0.9663 +vn 0.5977 0.0676 0.7988 +vn 0.3892 0.4834 0.7841 +vn -0.1867 -0.0134 -0.9823 +vn -0.2096 -0.1935 -0.9585 +vn -0.1810 -0.0193 -0.9833 +vn -0.6322 -0.1636 -0.7573 +vn -0.9200 -0.0355 -0.3902 +vn -0.7493 -0.1186 -0.6515 +vn 0.8934 -0.1144 -0.4345 +vn 0.7432 -0.0829 -0.6639 +vn 0.7220 -0.0300 -0.6913 +vn 0.7356 -0.1674 -0.6564 +vn 0.8783 -0.2980 -0.3737 +vn 0.6914 -0.5867 -0.4216 +vn -0.0776 -0.9957 -0.0515 +vn -0.0776 -0.9957 -0.0514 +vn -0.1856 0.4538 -0.8716 +vn -0.1947 0.0554 -0.9793 +vn -0.4580 0.2668 -0.8480 +vn 0.7123 -0.5182 0.4735 +vn 0.7130 -0.4505 0.5372 +vn 0.6951 -0.4877 0.5283 +vn -0.2526 0.9663 -0.0500 +vn -0.3104 0.9503 -0.0233 +vn -0.1424 0.9857 -0.0898 +vn 0.0057 -0.6630 0.7486 +vn -0.0634 -0.8101 0.5828 +vn 0.2295 -0.7357 0.6373 +vn 0.4176 -0.8279 -0.3745 +vn 0.0922 -0.9389 -0.3316 +vn 0.2343 -0.7780 -0.5829 +vn 0.7533 -0.2003 -0.6265 +vn 0.7538 -0.2064 -0.6238 +vn 0.5778 -0.2105 -0.7885 +vn 0.5279 0.0846 0.8451 +vn 0.2196 0.0184 0.9754 +vn 0.0689 0.1777 0.9817 +vn -0.3459 -0.1588 0.9247 +vn -0.6841 -0.3520 0.6388 +vn -0.3706 -0.4686 0.8019 +vn 0.1446 -0.7119 0.6872 +vn 0.3309 -0.6031 0.7258 +vn 0.0587 -0.5426 0.8380 +vn 0.1075 -0.0003 0.9942 +vn 0.1039 -0.0001 0.9946 +vn 0.1637 -0.0884 0.9825 +vn -0.0724 0.7488 0.6589 +vn -0.0004 0.8417 0.5399 +vn -0.2155 0.8403 0.4975 +vn -0.3988 0.6364 -0.6603 +vn 0.0779 0.5562 -0.8274 +vn -0.1219 0.6306 -0.7665 +vn -0.4929 0.8068 0.3258 +vn -0.2683 0.9613 -0.0626 +vn -0.5479 0.8338 0.0681 +vn -0.9584 -0.1429 0.2471 +vn -0.9488 -0.2525 -0.1897 +vn -0.8167 -0.5755 0.0426 +vn 0.1786 -0.1432 0.9734 +vn -0.1216 -0.1352 0.9833 +vn 0.6626 -0.0301 0.7484 +vn 0.3847 -0.1010 0.9175 +vn 0.9918 0.1109 -0.0636 +vn 0.9918 0.1108 -0.0636 +vn 0.9918 0.1109 -0.0637 +vn -0.2217 0.0202 0.9749 +vn -0.2796 -0.0194 0.9599 +vn -0.3418 -0.0374 0.9390 +vn 0.1229 0.0611 -0.9905 +vn 0.0948 0.1576 -0.9829 +vn 0.1597 0.2195 -0.9625 +vn -0.4379 -0.0096 0.8990 +vn -0.7225 0.1863 0.6658 +vn 0.6706 0.0909 0.7362 +vn 0.8887 0.0925 0.4491 +vn 0.8291 0.0982 0.5504 +vn -0.5801 -0.7422 0.3356 +vn -0.4433 -0.8279 0.3435 +vn -0.4447 -0.6734 0.5906 +vn -0.0602 0.0839 0.9947 +vn 0.0275 0.1212 0.9922 +vn -0.0579 -0.0034 0.9983 +vn -0.9894 0.1395 0.0398 +vn -0.9894 0.1394 0.0399 +vn -0.9894 0.1394 0.0398 +vn 0.0751 -0.9866 -0.1446 +vn 0.1079 -0.9894 -0.0976 +vn 0.0666 -0.9961 -0.0584 +vn -0.6182 -0.7845 -0.0476 +vn -0.7270 -0.6821 0.0790 +vn -0.6301 -0.7459 -0.2160 +vn 0.8705 -0.1195 -0.4775 +vn 0.0904 -0.4107 0.9073 +vn 0.0550 -0.3611 0.9309 +vn 0.1072 -0.2177 0.9701 +vn -0.6823 0.7303 0.0346 +vn -0.4459 0.8685 -0.2163 +vn -0.7500 0.6110 -0.2532 +vn -0.6536 0.0074 0.7568 +vn -0.5477 -0.0778 0.8330 +vn -0.3482 -0.1525 0.9249 +vn 0.1372 0.5304 0.8366 +vn 0.1967 0.6196 0.7599 +vn 0.1868 0.2525 0.9494 +vn 0.4152 0.7458 0.5210 +vn 0.4107 0.6301 0.6590 +vn 0.5397 0.5428 0.6436 +vn 0.1442 -0.9886 0.0439 +vn -0.3197 -0.8939 -0.3141 +vn -0.5651 -0.8168 -0.1165 +vn -0.5833 -0.6970 -0.4171 +vn 0.4960 0.7796 -0.3823 +vn 0.3995 0.7609 -0.5114 +vn 0.3736 0.7834 -0.4967 +vn -0.9079 0.0870 -0.4102 +vn -0.9972 0.0737 0.0146 +vn -0.9966 0.0789 -0.0233 +vn -0.1442 0.9886 -0.0439 +vn -0.1441 0.9886 -0.0439 +vn 0.1926 -0.8290 0.5250 +vn 0.2101 -0.7299 0.6505 +vn -0.0004 -0.8417 0.5399 +vn 0.8904 0.4526 0.0479 +vn 0.8944 0.4172 -0.1615 +vn 0.7853 0.6109 -0.1004 +vn -0.6041 0.2540 -0.7554 +vn -0.6343 -0.1019 -0.7663 +vn -0.7913 -0.0995 -0.6033 +vn -0.0852 0.9586 0.2716 +vn 0.3741 -0.7803 0.5012 +vn 0.1022 -0.7076 0.6992 +vn 0.2985 -0.8560 0.4221 +vn 0.5748 0.5390 -0.6157 +vn 0.6631 0.2028 -0.7206 +vn 0.4648 0.3378 -0.8185 +vn -0.4271 0.7651 -0.4819 +vn -0.2002 0.9512 -0.2347 +vn -0.1367 0.9606 -0.2418 +vn -0.2487 -0.7287 0.6381 +vn 0.2111 0.7242 0.6565 +vn 0.3334 0.6300 0.7014 +vn 0.1719 0.7080 0.6850 +vn -0.0663 -0.8056 0.5887 +vn 0.0884 -0.6880 0.7203 +vn 0.0617 -0.3769 0.9242 +vn 0.0431 -0.1046 0.9936 +vn 0.0118 -0.1725 0.9849 +vn -0.0296 0.3126 0.9494 +vn 0.7113 -0.2271 0.6651 +vn 0.7139 -0.2721 0.6453 +vn 0.7120 -0.3405 0.6141 +vn -0.7421 0.5810 -0.3343 +vn -0.5573 0.7030 -0.4419 +vn -0.7064 0.3726 -0.6018 +vn -0.2431 0.0076 0.9700 +vn -0.6308 -0.0577 0.7738 +vn 0.0781 0.7927 0.6046 +vn 0.0361 0.8001 0.5988 +vn 0.0624 0.8573 0.5110 +vn 0.3403 -0.8517 -0.3985 +vn 0.2652 -0.9451 -0.1910 +vn 0.0315 -0.8717 -0.4891 +vn 0.0810 -0.9366 -0.3409 +vn 0.4258 -0.8530 -0.3017 +vn 0.3636 -0.8924 -0.2673 +vn -0.1300 0.9683 0.2135 +vn -0.2107 0.9558 -0.2048 +vn -0.6233 0.3316 0.7082 +vn -0.6611 -0.0682 0.7472 +vn -0.4119 0.2605 0.8732 +vn 0.8378 -0.4952 -0.2301 +vn 0.9933 -0.0246 -0.1127 +vn 0.7979 -0.1950 0.5703 +vn 0.9565 0.1333 0.2593 +vn 0.8309 -0.1715 0.5293 +vn 0.4621 0.0888 0.8824 +vn 0.6270 0.1103 0.7712 +vn 0.5966 0.0439 0.8013 +vn 0.0852 -0.9586 -0.2716 +vn -0.3211 -0.7671 -0.5554 +vn -0.1495 -0.7819 -0.6052 +vn -0.1270 -0.9366 -0.3267 +vn 0.1552 0.1095 -0.9818 +vn 0.1549 0.1943 -0.9686 +vn 0.1316 0.0418 -0.9904 +vn 0.1300 0.9683 -0.2134 +vn 0.1300 0.9683 -0.2135 +vn 0.5204 0.7247 -0.4516 +vn 0.3339 0.7406 -0.5831 +vn 0.4640 0.7564 -0.4611 +vn 0.6707 0.2101 -0.7114 +vn 0.8474 0.1964 -0.4932 +vn 0.7524 0.2017 -0.6271 +vn 1.0000 -0.0006 0.0000 +vn -0.1334 -0.0050 -0.9911 +vn -0.1682 0.0044 -0.9857 +vn 0.5893 -0.1214 0.7987 +vn 0.5893 -0.1214 0.7988 +vn 0.7360 -0.2385 -0.6335 +vn 0.3802 -0.2475 -0.8912 +vn 0.7361 -0.2385 -0.6335 +vn -0.0863 -0.1307 -0.9877 +vn 0.0258 -0.1348 -0.9905 +vn 0.0250 -0.1409 -0.9897 +vn 0.2556 -0.6530 0.7129 +vn 0.5325 -0.6390 0.5551 +vn 0.2627 -0.6527 0.7106 +vn -0.9632 0.0450 0.2652 +vn -0.8856 0.4097 0.2189 +vn -0.9162 0.3985 0.0409 +vn 0.1941 -0.2834 -0.9392 +vn 0.1312 0.9775 -0.1650 +vn 0.1311 0.9775 -0.1650 +vn 0.0180 0.9998 -0.0080 +vn 0.0177 0.9998 -0.0065 +vn 0.0010 0.9982 -0.0597 +vn 0.6790 0.6717 -0.2963 +vn 0.8148 0.5633 -0.1368 +vn 0.7122 0.5387 -0.4501 +vn 0.5140 -0.8576 -0.0148 +vn -0.1476 -0.9879 -0.0482 +vn -0.1476 -0.9879 -0.0483 +vn -0.1304 -0.9906 -0.0419 +vn 0.5853 -0.6897 -0.4263 +vn 0.6257 -0.5580 -0.5451 +vn 0.7396 -0.6096 -0.2852 +vn 0.1302 -0.9768 -0.1699 +vn 0.1475 -0.9509 -0.2721 +vn 0.0923 -0.3183 -0.9435 +vn 0.0799 -0.1046 -0.9913 +vn 0.1464 -0.1526 -0.9774 +vn -0.3641 0.1450 0.9200 +vn -0.1189 0.5215 0.8449 +vn -0.3706 0.4687 0.8019 +vn -0.2800 -0.9079 -0.3119 +vn -0.4065 -0.8730 -0.2695 +vn -0.5427 -0.7096 -0.4493 +vn 0.1638 0.0878 0.9826 +vn 0.1628 0.3560 0.9202 +vn 0.1855 0.3989 0.8980 +vn -0.2846 -0.1693 -0.9436 +vn -0.5716 -0.0963 -0.8148 +vn -0.0852 -0.1986 -0.9764 +vn 0.1063 0.2088 0.9722 +vn 0.0965 0.3235 0.9413 +vn -0.2261 0.0327 0.9736 +vn -0.9518 0.2261 0.2071 +vn -0.6738 0.6156 0.4087 +vn -0.7635 -0.2311 0.6030 +vn -0.9821 -0.1431 0.1226 +vn 0.9912 0.1262 0.0395 +vn 0.9676 0.0900 0.2360 +vn 0.9599 0.0749 0.2700 +vn 0.9540 -0.0592 -0.2940 +vn 0.7107 0.6480 -0.2740 +vn 0.8173 0.5076 -0.2729 +vn 0.6385 0.5605 -0.5275 +vn 0.1867 0.7028 -0.6864 +vn 0.1815 0.7290 -0.6601 +vn 0.1784 0.4598 -0.8699 +vn 0.0897 -0.1275 0.9878 +vn -0.7887 -0.0199 0.6144 +vn -0.8116 -0.0279 0.5836 +vn -0.6511 0.0121 0.7589 +vn 0.4304 0.8975 -0.0962 +vn 0.6533 0.7566 -0.0263 +vn 0.5434 0.8071 -0.2308 +vn 0.4726 0.5947 -0.6503 +vn 0.5493 0.6823 -0.4824 +vn -0.2957 0.5625 -0.7721 +vn -0.5387 0.5966 -0.5949 +vn -0.2943 0.6970 -0.6539 +vn 0.5979 0.6497 0.4696 +vn 0.5603 0.7963 0.2278 +vn 0.4347 0.7836 0.4439 +vn 0.4674 -0.1332 0.8739 +vn 0.1286 -0.1970 0.9719 +vn 0.0542 -0.2144 0.9752 +vn -0.1325 -0.1727 0.9760 +vn -0.0586 -0.1884 0.9803 +vn -0.0627 -0.0350 0.9974 +vn 0.8417 -0.1262 0.5250 +vn 0.8511 -0.0748 0.5196 +vn 0.7200 -0.2142 0.6601 +vn -0.0776 0.9957 -0.0515 +vn 0.4447 -0.7910 -0.4201 +vn 0.6669 -0.7185 -0.1974 +vn 0.3782 -0.9236 -0.0627 +vn 0.5370 -0.1005 0.8376 +vn 0.7005 -0.0350 0.7128 +vn 0.7005 -0.0289 0.7131 +vn 0.6808 0.0053 -0.7325 +vn 0.4879 0.0448 -0.8718 +vn 0.4190 0.0604 -0.9060 +vn -0.2277 -0.7002 -0.6766 +vn -0.2377 -0.6696 -0.7037 +vn -0.2283 -0.7234 -0.6516 +vn -0.4966 0.8678 0.0186 +vn -0.4633 0.8490 -0.2542 +vn -0.0493 -0.2489 -0.9673 +vn -0.5545 -0.0718 -0.8290 +vn -0.1556 -0.6122 -0.7752 +vn -0.3653 -0.6157 -0.6982 +vn 0.1786 -0.8955 -0.4076 +vn 0.1565 -0.9403 -0.3022 +vn 0.1467 -0.3048 -0.9410 +vn 0.0427 0.8720 0.4876 +vn 0.2341 0.9597 0.1556 +vn -0.0843 0.8995 0.4287 +vn 0.5131 0.8532 0.0938 +vn -0.1136 0.2067 0.9718 +vn -0.1310 0.0659 0.9892 +vn -0.1781 0.2069 0.9620 +vn 0.0989 0.7692 -0.6313 +vn 0.1149 0.8942 -0.4326 +vn 0.0743 0.8716 -0.4846 +vn 0.7931 0.5063 0.3388 +vn 0.6563 0.5502 0.5163 +vn 0.7361 0.4185 0.5320 +vn 0.0813 0.9406 -0.3296 +vn 0.2343 0.7758 -0.5859 +vn -0.0098 0.7895 -0.6136 +vn 0.2367 -0.9650 0.1126 +vn 0.1306 0.9732 -0.1894 +vn 0.1054 0.9910 -0.0819 +vn 0.1086 0.9882 -0.1077 +vn -0.7279 -0.0918 -0.6795 +vn -0.7279 -0.0919 -0.6795 +vn -0.0754 0.6935 0.7165 +vn 0.3192 0.6376 0.7011 +vn -0.0765 0.7288 0.6805 +vn 0.0950 0.9952 0.0221 +vn 0.1404 0.9746 -0.1744 +vn 0.0711 0.9897 0.1241 +vn 0.7031 -0.7032 0.1055 +vn 0.5795 -0.8139 0.0419 +vn 0.6751 -0.7256 -0.1335 +vn -0.2487 0.7287 0.6381 +vn 0.0057 0.6630 0.7486 +vn -0.0634 0.8102 0.5828 +vn -0.7361 0.2385 0.6335 +vn -0.7360 0.2385 0.6335 +vn -0.5557 0.2495 0.7931 +vn 0.7264 -0.3472 -0.5931 +vn 0.7095 -0.4128 -0.5712 +vn 0.7145 -0.4136 -0.5642 +vn -0.6826 0.0152 -0.7306 +vn -0.6646 0.2058 -0.7183 +vn -0.5358 0.1231 -0.8353 +vn -0.8360 0.1585 0.5254 +vn -0.6129 0.3810 0.6922 +vn -0.9781 0.1578 0.1359 +vn 0.0776 0.9957 0.0515 +vn -0.8433 -0.0038 -0.5375 +vn -0.7973 -0.0291 -0.6029 +vn -0.8273 -0.5303 -0.1851 +vn -0.7664 -0.5321 -0.3599 +vn -0.6886 -0.6830 -0.2435 +vn -0.1845 -0.8517 0.4905 +vn 0.0768 -0.8793 0.4701 +vn -0.0812 0.9285 -0.3623 +vn -0.1169 0.9785 -0.1699 +vn -0.0475 0.9865 -0.1566 +vn 0.2057 0.2081 0.9562 +vn 0.5091 -0.1876 0.8400 +vn 0.4617 0.1583 0.8728 +vn -0.0852 -0.9586 0.2716 +vn 0.3615 0.3809 0.8510 +vn 0.6510 0.0140 -0.7589 +vn 0.8614 -0.2195 -0.4580 +vn 0.6871 -0.0421 -0.7254 +vn 0.2261 -0.0327 -0.9736 +vn -0.1123 -0.5165 -0.8489 +vn 0.1709 -0.5955 -0.7850 +vn 0.0509 -0.6373 -0.7689 +vn -0.4968 -0.1695 -0.8512 +vn -0.7284 0.1249 -0.6736 +vn -0.5696 0.1879 -0.8001 +vn 0.0776 -0.9957 0.0515 +vn 0.6752 0.5976 0.4324 +vn 0.9400 0.0280 0.3400 +vn 0.9549 0.0726 0.2880 +vn 0.8561 -0.0012 0.5168 +vn 0.1442 0.9886 0.0439 +vn -0.9934 -0.0905 -0.0710 +vn -0.8850 -0.4251 -0.1898 +vn -0.8332 -0.5510 -0.0468 +vn 0.1178 0.9862 0.1166 +vn 0.2537 0.9346 -0.2493 +vn -0.2898 -0.8046 -0.5182 +vn -0.0485 -0.8900 -0.4534 +vn -0.2306 -0.8588 -0.4574 +vn 0.4519 -0.0104 -0.8920 +vn 0.1472 -0.0396 -0.9883 +vn 0.2616 -0.0244 -0.9649 +vn -0.7157 0.6791 0.1630 +vn -0.7091 0.6847 -0.1684 +vn -0.8127 0.5808 0.0471 +vn 0.5975 -0.6830 0.4201 +vn 0.4991 -0.6669 0.5533 +vn 0.3788 -0.7985 0.4679 +vn 0.9845 0.1664 0.0547 +vn -0.6647 0.1484 -0.7323 +vn -0.9024 0.0413 -0.4289 +vn -0.9187 0.0300 -0.3938 +vn 0.5278 0.8459 -0.0770 +vn 0.5708 0.1030 0.8146 +vn 0.5708 0.1029 0.8146 +vn -0.7789 0.3442 -0.5243 +vn 0.7504 -0.4061 -0.5215 +vn 0.8169 -0.4290 -0.3855 +vn 0.7158 -0.5511 -0.4289 +vn 0.0269 0.7798 -0.6254 +vn 0.0313 0.5136 -0.8575 +vn -0.0999 0.5398 -0.8358 +vn -0.1941 -0.2834 0.9392 +vn 0.7691 0.0942 -0.6322 +vn 0.9828 0.1429 -0.1173 +vn 0.8967 0.1123 -0.4282 +vn -0.4971 -0.7662 -0.4074 +vn -0.0827 -0.8816 0.4646 +vn -0.0167 -0.9165 0.3998 +vn -0.0580 -0.8619 0.5037 +vn 0.5254 -0.1214 -0.8422 +vn 0.5980 -0.3643 -0.7139 +vn 0.0707 -0.6632 0.7451 +vn 0.1152 -0.8125 0.5714 +vn 0.1308 -0.6151 0.7775 +vn 0.0939 -0.8966 0.4327 +vn -0.1095 -0.9175 0.3824 +vn -0.3318 -0.8838 0.3300 +vn -0.2742 0.7770 -0.5666 +vn -0.1103 0.6718 -0.7325 +vn 0.5708 -0.1030 0.8146 +vn 0.7196 0.6651 0.1996 +vn 0.6695 0.6805 0.2978 +vn 0.1456 -0.8269 -0.5432 +vn -0.1399 -0.8640 -0.4836 +vn 0.0596 -0.7228 -0.6884 +vn -0.7860 -0.1365 -0.6030 +vn -0.7624 -0.1392 -0.6319 +vn -0.9487 -0.1502 -0.2781 +vn 0.0766 -0.2339 -0.9692 +vn 0.0625 -0.3010 -0.9516 +vn 0.0957 -0.4428 -0.8915 +vn 0.0356 -0.7635 0.6449 +vn 0.2809 -0.8022 0.5268 +vn 0.3563 -0.3924 0.8480 +vn -0.1045 -0.6393 -0.7618 +vn 0.1408 -0.6764 -0.7229 +vn 0.0826 -0.1088 -0.9906 +vn 0.0574 -0.0411 -0.9975 +vn 0.0381 -0.2533 -0.9666 +vn 1.0000 0.0010 0.0000 +vn -0.0075 0.6029 0.7977 +vn 0.0205 0.2656 0.9639 +vn 0.2063 0.3537 0.9123 +vn -0.3528 0.8038 -0.4790 +vn -0.5334 0.7690 -0.3524 +vn -0.5054 0.8131 -0.2890 +vn 0.6751 0.7256 -0.1335 +vn 0.7145 0.6943 0.0863 +vn 0.1517 -0.9861 0.0672 +vn 0.1987 -0.9798 -0.0221 +vn 0.5790 -0.8031 0.1407 +vn -0.7636 -0.0904 -0.6393 +vn -0.2343 -0.2373 -0.9428 +vn -0.5542 -0.3441 -0.7580 +vn -0.1311 -0.9775 0.1650 +vn -0.0077 0.9070 0.4212 +vn -0.0537 0.9178 0.3934 +vn -0.1294 0.7628 0.6336 +vn -0.6665 -0.7281 0.1600 +vn -0.4973 -0.8233 0.2735 +vn -0.5983 -0.7365 0.3156 +vn 0.7279 0.0919 0.6795 +vn 0.2251 0.0735 0.9715 +vn 0.2169 0.0101 0.9762 +vn 0.2349 0.0797 0.9687 +vn -0.1679 0.6900 -0.7041 +vn -0.1178 0.9862 -0.1166 +vn -0.5708 -0.1029 -0.8146 +vn -0.1297 0.9858 0.1064 +vn -0.1199 0.9671 0.2245 +vn -0.1561 0.9852 0.0702 +vn -0.9918 -0.1108 0.0636 +vn -0.4175 0.8495 0.3227 +vn -0.5617 0.7048 0.4334 +vn -0.2659 0.6956 0.6674 +vn 0.0703 -0.6986 -0.7121 +vn 0.0261 -0.5908 -0.8064 +vn 0.0714 -0.7635 -0.6418 +vn 0.3801 -0.2475 -0.8912 +vn 0.0307 -0.2191 -0.9752 +vn -0.1442 -0.9886 -0.0439 +vn 0.0550 -0.9857 0.1593 +vn -0.0564 -0.9651 0.2556 +vn 0.0938 -0.9906 0.0998 +vn 0.1010 -0.9842 0.1457 +vn 0.0532 -0.9737 0.2216 +vn -0.1472 -0.1982 0.9691 +vn -0.1850 -0.1902 0.9642 +vn -0.2144 -0.0767 0.9737 +vn -0.5904 0.7318 -0.3405 +vn 0.6627 -0.7412 -0.1070 +vn 0.5628 -0.7872 -0.2520 +vn 0.8404 -0.4604 -0.2861 +vn -0.7683 0.4725 0.4318 +vn -0.7231 0.0806 0.6860 +vn -0.6717 0.1771 0.7193 +vn -0.7351 -0.5938 0.3272 +vn -0.5347 -0.6641 0.5225 +vn -0.6356 -0.5982 0.4880 +vn -0.3081 0.8966 -0.3180 +vn -0.5710 0.8047 -0.1623 +vn 0.3682 -0.2026 -0.9074 +vn 0.4043 -0.2031 -0.8918 +vn 0.3444 0.8116 0.4718 +vn 0.5122 0.6218 0.5924 +vn 0.5031 0.6351 0.5861 +vn 0.4714 -0.6287 -0.6184 +vn 0.2568 -0.6500 -0.7153 +vn 0.3784 -0.4248 -0.8224 +vn 0.8814 -0.1561 -0.4458 +vn 0.9755 0.1369 -0.1723 +vn 0.9831 0.1070 -0.1485 +vn -0.7442 -0.6568 0.1218 +vn -0.0037 -0.7874 -0.6164 +vn -0.0170 0.9972 0.0728 +vn -0.5224 -0.0383 0.8519 +vn -0.7482 -0.4482 -0.4893 +vn -0.6379 -0.5675 -0.5206 +vn -0.6271 0.5001 0.5972 +vn -0.5933 0.0795 0.8011 +vn -0.3391 0.4960 0.7994 +vn 0.9498 0.1835 -0.2535 +vn 0.7361 0.2385 -0.6335 +vn 0.7360 0.2385 -0.6335 +vn -0.9238 -0.1052 -0.3681 +vn -0.6937 -0.1930 -0.6939 +vn -0.7485 -0.5732 -0.3334 +vn 0.0579 -0.6152 -0.7863 +vn 0.0603 -0.6210 -0.7815 +vn 0.0678 -0.6244 -0.7781 +vn -0.0851 -0.9586 0.2716 +vn 0.4623 -0.8724 -0.1589 +vn 0.5424 -0.8390 -0.0440 +vn 0.3940 -0.6071 -0.6900 +vn 0.3337 -0.6996 -0.6318 +vn -0.1892 -0.2363 0.9531 +vn -0.5557 -0.2495 0.7931 +vn -0.4906 -0.2564 0.8328 +vn 0.2132 -0.0303 0.9766 +vn -0.1657 0.0131 0.9861 +vn -0.2320 -0.6935 0.6821 +vn -0.2721 -0.7808 -0.5624 +vn -0.2037 -0.9453 -0.2546 +vn -0.4523 -0.8379 -0.3055 +vn 0.7258 0.1363 0.6743 +vn 0.8817 0.2200 0.4175 +vn 0.9652 0.0185 0.2610 +vn -0.2683 -0.9613 -0.0626 +vn -0.3081 -0.8966 -0.3180 +vn -0.0263 -0.9306 -0.3652 +vn -0.5940 -0.7893 -0.1556 +vn -0.5491 -0.7591 -0.3497 +vn -0.5534 -0.8270 0.0988 +vn -0.1199 -0.3291 0.9366 +vn -0.0885 -0.2768 0.9568 +vn -0.3192 -0.0936 0.9431 +vn 0.0930 0.8192 -0.5659 +vn 0.0918 0.9829 -0.1595 +vn 0.1567 0.6899 -0.7068 +vn 0.9873 -0.1559 -0.0294 +vn 0.8710 -0.2658 -0.4131 +vn 0.9268 -0.2142 -0.3084 +vn -0.2294 -0.0206 0.9731 +vn -0.2221 0.1316 0.9661 +vn -0.2125 0.0746 0.9743 +vn 0.5171 -0.8533 -0.0664 +vn 0.4807 -0.8468 0.2279 +vn 0.4700 -0.7663 0.4381 +vn 0.8624 -0.3532 0.3627 +vn 0.5323 -0.6619 0.5277 +vn 0.2832 -0.8701 0.4035 +vn -0.7128 0.1407 -0.6871 +vn -0.0839 0.9771 -0.1955 +vn -0.1503 0.9851 -0.0836 +vn 0.0469 0.6831 -0.7288 +vn 0.0776 0.4275 -0.9007 +vn 0.3401 0.0293 -0.9399 +vn 0.2694 0.0147 -0.9629 +vn 0.0434 0.2909 -0.9558 +vn 0.1145 -0.0260 0.9931 +vn 0.0633 -0.0059 0.9980 +vn 0.1825 -0.1645 0.9693 +vn -0.0661 -0.5763 -0.8146 +vn -0.1702 -0.4478 -0.8778 +vn -0.0139 -0.4472 -0.8943 +vn 0.2312 -0.6828 -0.6931 +vn 0.7314 0.6609 -0.1683 +vn 0.4927 0.8097 -0.3188 +vn 0.4772 0.8778 -0.0423 +vn 0.1349 -0.9640 -0.2292 +vn 0.1204 -0.9828 -0.1403 +vn -0.6130 0.0508 -0.7884 +vn -0.6117 0.0414 -0.7900 +vn -0.8693 -0.0339 -0.4931 +vn 0.4525 0.7514 0.4802 +vn 0.5057 0.7860 0.3556 +vn 0.5246 0.8326 0.1776 +vn 0.5132 -0.8214 0.2490 +vn 0.6775 -0.6970 0.2348 +vn 0.5616 0.2719 -0.7815 +vn 0.2721 0.2846 -0.9192 +vn 0.2316 0.2920 -0.9279 +vn -0.2602 0.5470 -0.7956 +vn -0.3018 0.2886 -0.9086 +vn -0.5030 0.2661 -0.8223 +vn -0.1131 0.9377 0.3284 +vn -0.0650 0.8516 0.5202 +vn 0.0338 0.2628 -0.9643 +vn 0.0546 0.1186 -0.9914 +vn -0.1009 0.1343 -0.9858 +vn 0.2401 0.7978 0.5531 +vn -0.4930 0.1464 -0.8577 +vn -0.4228 0.1115 -0.8993 +vn -0.7226 0.2713 -0.6358 +vn -0.9973 -0.0596 -0.0433 +vn -0.9989 -0.0178 0.0431 +vn -0.9958 -0.0173 -0.0894 +vn 0.1410 -0.5564 -0.8189 +vn -0.0536 -0.6869 -0.7248 +vn -0.2447 -0.6087 -0.7547 +vn 0.9632 -0.0537 -0.2633 +vn 0.8614 0.2195 -0.4580 +vn 0.9785 0.0379 -0.2030 +vn 0.4650 0.7757 -0.4268 +vn -0.0738 0.0331 0.9967 +vn -0.1460 -0.0613 0.9874 +vn -0.1692 -0.0474 0.9844 +vn -0.6744 -0.3631 0.6429 +vn -0.8118 -0.3164 0.4908 +vn -0.6521 -0.4781 0.5884 +vn 0.3155 -0.1262 0.9405 +vn 0.1746 -0.1862 0.9669 +vn -0.2261 -0.0327 0.9736 +vn -0.6205 0.0078 0.7841 +vn -0.6205 0.0078 0.7842 +vn -0.9790 0.0970 -0.1795 +vn -0.9444 0.0519 -0.3247 +vn -0.9914 0.1294 -0.0191 +vn -0.0134 0.9785 0.2060 +vn 0.0431 0.9720 0.2309 +vn 0.5190 0.6540 0.5504 +vn 0.5602 0.7630 0.3225 +vn -0.0007 -0.7576 0.6527 +vn -0.0040 -0.6445 0.7646 +vn -0.0095 -0.6703 0.7420 +vn 0.7428 -0.3096 -0.5937 +vn 0.7272 -0.3015 -0.6167 +vn -0.4089 0.5061 -0.7594 +vn -0.5326 0.3001 -0.7914 +vn -0.3956 -0.6077 0.6886 +vn -0.5825 -0.6513 0.4863 +vn -0.7451 -0.6138 0.2609 +vn 0.7057 0.6566 0.2661 +vn 0.7093 0.5893 0.3868 +vn 0.7063 0.6018 0.3728 +vn -0.5512 -0.2813 0.7855 +vn -0.1993 0.7533 -0.6268 +vn -0.2342 0.6390 -0.7327 +vn -0.1576 0.6268 -0.7630 +vn -0.5228 0.8068 0.2752 +vn -0.6918 0.6959 0.1928 +vn -0.6746 0.5267 0.5172 +vn -0.4079 0.4893 -0.7708 +vn -0.1658 0.6334 -0.7558 +vn -0.3206 0.2153 -0.9224 +vn 0.7068 0.3394 -0.6207 +vn 0.5504 -0.0266 -0.8344 +vn 0.5905 0.2853 -0.7549 +vn 0.0484 -0.7449 -0.6655 +vn 0.0473 -0.7410 -0.6699 +vn 0.0394 -0.6585 -0.7515 +vn -0.4519 -0.6719 -0.5868 +vn -0.4985 -0.5340 -0.6829 +vn 0.0757 0.3874 0.9188 +vn -0.0392 0.3695 0.9284 +vn 0.0163 0.3348 0.9421 +vn 0.0600 0.9869 -0.1498 +vn 0.0871 0.9449 -0.3157 +vn 0.1254 0.9444 -0.3040 +vn -0.9120 0.1435 -0.3843 +vn -0.9934 0.0905 -0.0710 +vn -0.8685 0.4430 -0.2226 +vn -0.0553 0.8232 0.5651 +vn -0.0033 0.8428 0.5382 +vn 0.0243 0.0023 -0.9997 +vn 0.0269 0.0000 -0.9996 +vn 0.0218 0.0047 -0.9998 +vn 0.1236 0.7907 0.5995 +vn 0.0667 0.6834 0.7270 +vn -0.7668 -0.4628 0.4448 +vn 0.1311 -0.9775 -0.1650 +vn 0.1312 -0.9775 -0.1650 +vn -0.0256 -0.7556 0.6545 +vn -0.0379 -0.6475 0.7611 +vn -0.0874 -0.6302 0.7715 +vn -0.4170 0.8300 0.3704 +vn -0.4812 0.7547 0.4459 +vn -0.2633 0.7591 0.5953 +vn -0.4683 0.7907 0.3942 +vn -0.3108 0.8272 0.4681 +vn -0.5310 0.8145 0.2337 +vn -0.0823 0.9899 0.1152 +vn -0.1534 0.9875 0.0368 +vn -0.0894 0.9949 0.0462 +vn -0.0852 -0.9586 0.2717 +vn -0.5280 -0.7408 -0.4153 +vn -0.7263 -0.6702 -0.1527 +vn -0.7369 -0.4370 -0.5158 +vn 0.1300 -0.9683 -0.2134 +vn 0.3041 -0.8403 -0.4488 +vn 0.4223 -0.8681 -0.2609 +vn -0.4307 0.2358 0.8711 +vn -0.4527 0.0512 0.8902 +vn -0.2026 0.5669 0.7985 +vn -0.1841 0.3824 0.9055 +vn -0.2366 0.3488 0.9069 +vn 0.0794 -0.9964 0.0310 +vn 0.0424 -0.9939 0.1021 +vn 0.0689 -0.9797 0.1884 +vn -0.0675 -0.4623 -0.8842 +vn -0.1661 -0.1247 -0.9782 +vn -0.1311 -0.2555 -0.9579 +vn -0.7727 -0.2746 -0.5723 +vn -0.7310 -0.3101 -0.6079 +vn -0.0067 -0.5068 0.8620 +vn -0.1189 -0.5215 0.8449 +vn 0.1199 -0.9182 0.3776 +vn 0.1439 -0.8578 0.4934 +vn 0.0837 -0.9601 0.2668 +vn 0.1423 0.5560 -0.8189 +vn 0.7079 -0.0595 -0.7038 +vn 0.7087 0.0826 -0.7007 +vn 0.7097 0.0439 -0.7031 +vn 0.0982 0.8522 0.5140 +vn -0.0314 0.9777 0.2078 +vn 0.0634 0.9768 0.2043 +vn -0.9886 -0.1457 0.0381 +vn -0.9826 -0.1435 -0.1176 +vn 0.4167 -0.2488 -0.8743 +vn 0.4167 -0.2487 -0.8743 +vn -0.2628 0.9110 0.3179 +vn -0.5321 0.7781 0.3338 +vn -0.4202 0.5501 0.7217 +vn -0.5901 0.3387 0.7329 +vn -0.5760 0.6273 -0.5242 +vn -0.3490 0.6849 -0.6396 +vn -0.5325 0.4928 -0.6882 +vn 0.1257 0.0257 -0.9917 +vn 0.4655 -0.0292 -0.8846 +vn 0.2393 0.0030 -0.9709 +vn -0.1787 -0.9827 -0.0488 +vn -0.1827 -0.9832 -0.0038 +vn -0.1837 -0.9827 -0.0236 +vn 0.0296 0.1187 -0.9925 +vn 0.2668 0.0819 -0.9603 +vn -0.1570 0.9492 -0.2725 +vn -0.1396 0.9863 -0.0879 +vn -0.0959 0.9814 0.1660 +vn -0.6758 0.3372 0.6554 +vn -0.5172 0.7539 0.4053 +vn -0.1105 0.9939 0.0041 +vn -0.1149 0.9705 -0.2118 +vn -0.1126 0.9910 -0.0717 +vn 0.0852 -0.9586 -0.2717 +vn 0.4345 0.6617 0.6111 +vn 0.3956 0.7581 0.5184 +vn -0.2441 0.9637 -0.1085 +vn -0.2856 0.9368 -0.2018 +vn -0.5237 0.8202 -0.2304 +vn 0.7314 -0.6609 -0.1683 +vn 0.4772 -0.8778 -0.0423 +vn 0.4927 -0.8097 -0.3188 +vn -0.0064 0.0434 0.9990 +vn -0.0065 0.0434 0.9990 +vn 0.7005 0.0351 0.7128 +vn 0.5301 0.1185 0.8396 +vn 0.0799 -0.0191 -0.9966 +vn 0.2287 -0.0061 -0.9735 +vn -0.0141 0.0144 -0.9998 +vn 0.0642 -0.9949 0.0773 +vn 0.1044 -0.9926 0.0621 +vn 0.0914 -0.9866 0.1355 +vn -0.4396 0.5235 -0.7299 +vn 0.9967 0.0589 0.0561 +vn 0.9470 -0.1285 0.2945 +vn 0.9916 -0.0086 0.1288 +vn 0.0265 0.1317 -0.9909 +vn 0.8949 -0.3168 0.3142 +vn 0.7136 -0.6215 0.3233 +vn 0.8686 -0.4828 0.1114 +vn 0.9958 -0.0721 0.0568 +vn 0.9659 -0.1435 -0.2156 +vn 0.9771 -0.0235 0.2113 +vn -0.2452 -0.5293 -0.8123 +vn -0.0993 -0.5373 -0.8376 +vn -0.2537 -0.6111 -0.7498 +vn -0.6293 0.5720 -0.5261 +vn -0.3084 0.6321 -0.7108 +vn 0.2025 -0.1296 0.9707 +vn 0.2356 -0.1640 0.9579 +vn 0.1170 0.0762 0.9902 +vn -0.1485 -0.0150 0.9888 +vn -0.1383 -0.0812 0.9871 +vn -0.1122 0.1200 0.9864 +vn 0.2165 -0.3974 -0.8917 +vn 0.3858 -0.5206 -0.7617 +vn 0.3741 0.7803 0.5012 +vn 0.4784 0.6827 0.5524 +vn 0.6837 0.6497 0.3323 +vn -0.0263 0.9306 -0.3652 +vn 0.0385 -0.0027 0.9993 +vn 0.1111 0.0506 0.9925 +vn 0.0353 -0.0689 0.9970 +vn -0.5190 0.8489 -0.1000 +vn -0.6345 0.7157 -0.2919 +vn -0.6950 0.7082 -0.1238 +vn -0.4632 0.0443 -0.8851 +vn -0.5605 -0.0035 -0.8282 +vn -0.5676 0.0048 -0.8233 +vn -0.3834 -0.1023 -0.9179 +vn -0.3905 -0.0496 -0.9193 +vn -0.2491 0.1225 -0.9607 +vn -0.2908 0.0831 -0.9532 +vn -0.2308 -0.0790 -0.9698 +vn -0.2730 -0.1277 -0.9535 +vn -0.1597 0.0212 -0.9869 +vn 0.6081 0.7828 0.1321 +vn 0.7510 0.6590 -0.0412 +vn 0.7276 0.6849 -0.0395 +vn -0.0819 -0.0002 -0.9966 +vn 0.1038 0.1160 -0.9878 +vn 0.0225 -0.0179 -0.9996 +vn 0.0556 -0.0349 -0.9978 +vn -0.0216 0.0682 -0.9974 +vn -0.0111 0.0151 -0.9998 +vn -0.2075 0.3259 0.9224 +vn -0.2353 0.2440 0.9408 +vn 0.0677 -0.1084 -0.9918 +vn 0.1401 0.0186 -0.9900 +vn 0.1832 -0.0078 -0.9830 +vn 0.9523 -0.1266 -0.2778 +vn 0.0850 -0.6328 -0.7696 +vn 0.0863 -0.8136 -0.5750 +vn 0.0865 -0.6486 -0.7562 +vn -0.0235 0.9966 -0.0791 +vn -0.0203 0.9965 -0.0808 +vn -0.0101 0.9864 -0.1641 +vn 0.1134 -0.9916 0.0628 +vn 0.1134 -0.9928 -0.0372 +vn 0.1129 -0.9920 -0.0562 +vn 0.0148 0.1126 0.9935 +vn 0.0897 0.1275 0.9878 +vn -0.2280 0.0867 0.9698 +vn 0.4301 -0.0000 -0.9028 +vn 0.4755 -0.0006 -0.8797 +vn 0.4238 -0.0003 -0.9058 +vn 0.1477 0.8576 0.4927 +vn 0.1195 0.9253 0.3600 +vn 0.8116 0.0202 0.5839 +vn 0.6052 -0.0129 0.7960 +vn -0.2804 0.7039 -0.6527 +vn -0.3822 0.7059 -0.5963 +vn -0.2657 0.7026 -0.6601 +vn -0.6117 -0.0414 -0.7900 +vn -0.6130 -0.0508 -0.7884 +vn -0.8693 0.0339 -0.4931 +vn 0.6342 -0.1574 0.7570 +vn 0.8449 -0.0750 0.5296 +vn 0.8017 -0.0895 0.5910 +vn -0.9755 -0.0976 -0.1972 +vn -0.9473 -0.0799 -0.3101 +vn -0.9667 -0.1630 0.1974 +vn 0.0595 -0.4622 0.8848 +vn 0.0968 -0.6054 0.7900 +vn -0.7744 0.0078 -0.6327 +vn -0.6854 -0.1054 -0.7205 +vn -0.4283 -0.7618 -0.4859 +vn 0.0752 -0.8644 -0.4972 +vn 0.0724 -0.2155 -0.9738 +vn -0.0028 -0.5745 -0.8185 +vn 0.1825 -0.6442 0.7428 +vn 0.0824 -0.7744 0.6274 +vn 0.1161 0.6392 -0.7602 +vn 0.2656 0.0125 0.9640 +vn 0.7039 0.5565 -0.4414 +vn 0.7184 0.5152 -0.4674 +vn 0.6993 0.5355 -0.4735 +vn -0.0701 0.9968 -0.0386 +vn -0.0074 0.9999 -0.0152 +vn 0.0343 0.9994 -0.0028 +vn 0.0852 0.9586 -0.2717 +vn -0.1310 -0.0683 -0.9890 +vn -0.2113 -0.0355 -0.9768 +vn -0.1097 -0.0802 -0.9907 +vn -0.1062 -0.7721 0.6266 +vn -0.1658 -0.6632 0.7298 +vn -0.1620 -0.5715 0.8045 +vn 0.0434 -0.2909 -0.9558 +vn -0.2364 -0.1609 -0.9583 +vn 0.0279 0.1012 -0.9945 +vn -0.0351 0.0323 -0.9989 +vn -0.0461 -0.1338 -0.9899 +vn 0.5262 -0.3162 -0.7894 +vn 0.7068 -0.3394 -0.6207 +vn -0.2585 0.1264 -0.9577 +vn 0.0179 0.1687 -0.9855 +vn -0.0597 0.1500 -0.9869 +vn 0.0375 -0.1158 -0.9926 +vn 0.0974 -0.0277 -0.9949 +vn -0.0395 -0.2832 -0.9582 +vn 0.8291 -0.0982 0.5504 +vn 0.9953 -0.0799 -0.0542 +vn 0.9947 -0.0808 0.0635 +vn -0.1144 -0.0681 0.9911 +vn 0.4655 0.0292 -0.8846 +vn 0.2393 -0.0030 -0.9709 +vn 0.4912 0.8120 0.3153 +vn 0.5895 0.7895 0.1710 +vn 0.4449 0.8483 0.2872 +vn -0.9875 -0.1457 0.0598 +vn -0.9875 -0.1458 0.0598 +vn -0.1312 -0.9775 0.1650 +vn -0.2748 0.8203 0.5016 +vn 0.0647 0.9571 -0.2825 +vn 0.0971 0.8556 -0.5085 +vn 0.7157 0.0744 -0.6944 +vn 0.7320 -0.0178 -0.6811 +vn 0.5568 -0.1066 -0.8238 +vn 0.1441 0.9886 0.0439 +vn -0.9624 0.2672 0.0478 +vn -0.9998 0.0192 -0.0024 +vn 0.0805 -0.8510 -0.5190 +vn 0.0509 -0.8559 -0.5147 +vn 0.0504 -0.9453 -0.3223 +vn 0.2563 -0.8854 -0.3877 +vn 0.3158 -0.8402 -0.4408 +vn 0.4075 -0.8680 -0.2838 +vn 0.0222 -0.0041 -0.9997 +vn 0.0245 -0.0022 -0.9997 +vn -0.4319 0.2102 -0.8771 +vn 0.2038 0.9669 0.1538 +vn 0.0829 -0.4246 0.9016 +vn 0.0359 -0.1022 0.9941 +vn 0.0325 0.0710 0.9969 +vn -0.5707 -0.1029 -0.8146 +vn 0.0045 0.9431 0.3324 +vn 0.0254 0.8343 0.5508 +vn 0.0659 -0.8417 0.5358 +vn 0.0365 -0.8665 0.4979 +vn -0.0547 -0.9614 0.2698 +vn 0.1532 0.8855 0.4386 +vn 0.0497 -0.9976 -0.0472 +vn 0.0332 -0.9936 0.1076 +vn 0.8731 0.2678 -0.4075 +vn -0.1123 0.5165 -0.8489 +vn 0.0628 0.6701 -0.7396 +vn 0.4666 0.5365 -0.7032 +vn 0.4609 0.4850 -0.7432 +vn 0.2525 0.5284 -0.8106 +vn -0.2317 0.1676 -0.9582 +vn -0.2628 0.0776 -0.9617 +vn -0.4232 0.2230 -0.8782 +vn 0.5841 -0.5840 -0.5638 +vn -0.7905 -0.5091 -0.3404 +vn -0.4179 -0.8219 -0.3871 +vn -0.5101 -0.8398 -0.1856 +vn -0.0790 -0.9900 0.1172 +vn -0.0326 -0.9949 0.0952 +vn -0.0568 -0.9808 0.1863 +vn 0.7462 0.4105 -0.5240 +vn 0.6265 0.4151 -0.6597 +vn -0.6329 0.0749 -0.7706 +vn -0.9649 -0.0797 -0.2502 +vn -0.8821 -0.0152 -0.4708 +vn -0.1027 0.9923 -0.0697 +vn -0.1198 0.9921 -0.0385 +vn -0.1099 0.9501 0.2921 +vn -0.1385 0.8091 0.5711 +vn -0.1964 0.6754 -0.7108 +vn -0.2193 0.2911 -0.9312 +vn -0.1517 0.0988 -0.9835 +vn 0.0441 -0.5743 -0.8175 +vn 0.0486 -0.6268 -0.7777 +vn 0.0476 -0.6021 -0.7970 +vn 0.0805 0.0087 -0.9967 +vn 0.0131 0.3123 -0.9499 +vn 0.0062 0.2331 0.9724 +vn -0.1156 0.2203 0.9685 +vn -0.6262 -0.0006 -0.7796 +vn -0.6262 -0.0002 -0.7796 +vn 0.2433 0.6053 0.7579 +vn -0.0949 -0.8214 0.5625 +vn -0.0917 -0.6405 0.7624 +vn -0.0539 -0.6788 0.7324 +vn 0.2540 -0.0225 -0.9669 +vn 0.3255 -0.0522 -0.9441 +vn -0.6158 0.7715 0.1597 +vn -0.7740 0.4996 0.3889 +vn 0.1079 0.8076 0.5798 +vn 0.0851 0.9039 0.4193 +vn -0.3690 0.9071 0.2025 +vn -0.1159 0.9390 0.3237 +vn 0.0039 -0.0646 0.9979 +vn 0.0184 -0.0843 0.9963 +vn 0.9352 -0.3538 -0.0109 +vn 0.9954 -0.0920 0.0263 +vn -0.0381 -0.9796 -0.1974 +vn -0.0926 -0.9246 -0.3696 +vn 0.0210 -0.9075 -0.4195 +vn -0.0456 0.9889 0.1414 +vn -0.0534 0.9860 0.1578 +vn -0.0649 0.9518 0.2998 +vn -0.6273 -0.7475 0.2184 +vn -0.5315 -0.8471 0.0045 +vn -0.5310 -0.8145 0.2337 +vn 0.3754 -0.0299 0.9264 +vn 0.3324 -0.7271 0.6007 +vn 0.1963 -0.6217 0.7583 +vn 0.1436 -0.6859 0.7134 +vn 0.6959 0.1003 0.7111 +vn -0.1178 -0.9862 -0.1165 +vn 0.5968 0.2854 0.7499 +vn 0.5625 0.4998 0.6586 +vn 0.6619 0.4133 0.6253 +vn -0.2161 0.9081 -0.3586 +vn -0.1918 0.9723 -0.1337 +vn 0.2540 0.8450 0.4705 +vn 0.2933 0.8689 0.3986 +vn 0.4824 0.7136 0.5080 +vn -0.9967 0.0623 -0.0522 +vn -0.8163 0.1315 0.5625 +vn -0.9428 -0.1149 0.3130 +vn -0.5337 -0.5681 -0.6264 +vn -0.3595 -0.5077 -0.7830 +vn 0.4333 -0.1382 0.8906 +vn 0.6644 -0.0750 0.7436 +vn 0.1301 -0.9682 -0.2137 +vn -0.6442 0.7591 -0.0936 +vn 0.6381 0.7336 -0.2336 +vn -0.9372 -0.0888 -0.3374 +vn -0.8287 -0.0963 -0.5514 +vn -0.1762 0.8110 -0.5579 +vn -0.9629 -0.0947 -0.2526 +vn -0.9847 -0.1087 0.1360 +vn -0.9801 -0.0747 0.1839 +vn 0.6845 0.7278 0.0418 +vn 0.6416 0.7334 0.2245 +vn 0.7415 0.6410 0.1985 +vn 0.9434 -0.1653 -0.2875 +vn -0.0734 0.2234 -0.9720 +vn -0.1521 0.1656 -0.9744 +vn -0.3181 -0.8001 0.5085 +vn -0.4619 -0.6511 0.6023 +vn -0.4962 -0.7472 0.4420 +vn 0.5789 0.8150 0.0240 +vn 0.4196 0.8772 -0.2332 +vn -0.5556 0.7754 -0.3001 +vn -0.4513 0.8920 -0.0254 +vn 0.0764 0.7300 -0.6791 +vn 0.0765 0.7311 -0.6780 +vn 0.0699 0.5842 -0.8086 +vn 0.1427 0.1145 0.9831 +vn -0.0752 0.7250 0.6846 +vn -0.0086 0.7484 0.6632 +vn 0.1300 -0.9683 -0.2135 +vn 0.3227 0.2970 0.8987 +vn 0.3466 0.6103 0.7123 +vn 0.1113 0.9920 0.0591 +vn 0.0868 0.9368 0.3390 +vn 0.1133 0.9907 -0.0750 +vn 0.9759 -0.1637 -0.1444 +vn 0.9757 -0.1966 0.0967 +vn 0.9803 -0.1881 -0.0606 +vn -0.5603 0.8194 -0.1209 +vn -0.7950 0.4899 -0.3578 +vn -0.8421 0.5070 -0.1841 +vn -0.8089 0.3439 -0.4768 +vn -0.9629 0.0947 -0.2526 +vn -0.9737 0.1076 -0.2009 +vn 0.0095 0.8290 0.5591 +vn -0.4967 -0.5717 0.6530 +vn -0.6445 -0.5390 0.5423 +vn 0.0388 0.7254 0.6873 +vn -0.3139 -0.7804 -0.5408 +vn -0.1844 -0.7416 -0.6450 +vn -0.1642 -0.9856 -0.0406 +vn -0.1484 -0.9858 -0.0788 +vn 0.6843 0.6548 -0.3209 +vn 0.7046 0.5867 -0.3991 +vn 0.6931 0.6388 -0.3340 +vn 0.0226 0.1083 0.9939 +vn 0.0502 0.1611 0.9857 +vn -0.7800 0.2029 0.5920 +vn -0.4450 0.1987 0.8732 +vn -0.6408 0.2105 0.7383 +vn 0.6091 0.7759 0.1643 +vn 0.5140 0.8576 -0.0148 +vn 0.0725 -0.8470 0.5267 +vn 0.0171 -0.8386 0.5445 +vn 0.0384 -0.8064 0.5901 +vn 0.7095 -0.6903 0.1417 +vn 0.7070 -0.6736 0.2156 +vn 0.7053 -0.6578 0.2643 +vn 0.7229 -0.1661 0.6707 +vn 0.6044 -0.1643 0.7795 +vn 0.6601 -0.1745 0.7306 +vn -0.1133 -0.7301 0.6739 +vn -0.1541 -0.5888 0.7935 +vn -0.1952 -0.5768 0.7932 +vn -0.9954 0.0930 0.0221 +vn -0.9927 0.1050 0.0594 +vn -0.9843 0.0386 -0.1722 +vn -0.3540 0.9204 0.1663 +vn -0.5171 0.8546 -0.0475 +vn -0.1357 -0.9771 -0.1637 +vn 0.0922 0.8724 -0.4801 +vn -0.1835 -0.8141 -0.5509 +vn -0.2298 -0.7596 -0.6085 +vn -0.0179 -0.8066 -0.5909 +vn -0.3480 0.9368 0.0358 +vn -0.6239 0.7771 0.0828 +vn -0.4168 -0.2487 0.8743 +vn -0.0215 -0.0050 0.9998 +vn -0.0269 -0.0000 0.9996 +vn -0.0243 -0.0009 0.9997 +vn 0.5920 -0.4849 -0.6437 +vn 0.6611 -0.3432 -0.6672 +vn 0.0749 -0.6154 -0.7846 +vn 0.0111 -0.4311 -0.9022 +vn 0.0129 -0.0526 0.9985 +vn -0.7091 -0.7042 -0.0357 +vn -0.7673 -0.6330 0.1025 +vn -0.7938 -0.5934 0.1336 +vn -0.7204 -0.6905 -0.0653 +vn 0.7211 -0.6908 -0.0535 +vn 0.7082 -0.7057 -0.0205 +vn 0.7172 -0.6953 -0.0474 +vn 0.5565 0.7960 -0.2380 +vn 0.3952 0.8826 -0.2547 +vn 0.6315 0.7736 0.0526 +vn 0.0303 0.9991 0.0312 +vn -0.0030 0.9996 0.0292 +vn 0.0145 0.9968 0.0788 +vn -0.2620 0.6011 -0.7550 +vn 0.7108 0.5184 0.4754 +vn 0.7096 0.5160 0.4798 +vn 0.7111 0.4722 0.5209 +vn -0.2191 0.6169 0.7559 +vn -0.7047 0.5807 0.4077 +vn -0.4388 0.6448 0.6259 +vn -0.2480 0.1896 -0.9500 +vn -0.4119 0.7123 0.5683 +vn -0.4011 0.7167 0.5705 +vn -0.3735 0.6239 0.6864 +vn -0.0141 -0.9958 0.0900 +vn -0.0040 -0.9789 0.2042 +vn 0.1681 0.6194 -0.7668 +vn 0.1062 0.8604 -0.4984 +vn 0.0888 0.8283 -0.5532 +vn -0.0804 0.8327 -0.5479 +vn -0.4767 -0.5366 0.6963 +vn -0.0046 0.9382 0.3461 +vn 0.8551 0.0405 -0.5169 +vn 0.9710 0.0897 -0.2218 +vn 0.9857 0.0909 -0.1420 +vn 0.9498 -0.1835 -0.2535 +vn -0.2956 -0.8732 -0.3875 +vn -0.2819 -0.5537 -0.7835 +vn -0.0053 -0.2724 -0.9622 +vn 0.2721 -0.2846 -0.9192 +vn 0.2316 -0.2920 -0.9279 +vn 0.5790 0.0411 -0.8143 +vn 0.2433 -0.6053 0.7579 +vn -0.7580 0.1644 -0.6313 +vn -0.8752 0.0298 -0.4829 +vn -0.8675 0.0814 -0.4907 +vn 0.2984 0.0021 -0.9544 +vn -0.3113 -0.5997 -0.7372 +vn -0.5083 -0.6872 -0.5190 +vn 0.3892 -0.4834 0.7841 +vn 0.1919 -0.1748 0.9657 +vn -0.6322 -0.6859 0.3604 +vn -0.4004 -0.9115 0.0941 +vn -0.6950 0.1657 -0.6997 +vn -0.9014 0.1554 -0.4042 +vn -0.9297 0.1570 -0.3331 +vn -0.4125 0.0031 0.9109 +vn 0.1624 -0.1880 -0.9686 +vn 0.1701 -0.1463 -0.9745 +vn 0.1224 0.0007 -0.9925 +vn 0.1381 -0.0407 -0.9896 +vn 0.3636 0.8924 -0.2673 +vn 0.0810 0.9366 -0.3409 +vn -0.4806 -0.3715 -0.7944 +vn -0.6321 -0.3295 -0.7013 +vn 0.0796 0.7792 0.6217 +vn 0.0871 0.6700 0.7372 +vn -0.0401 0.7876 -0.6149 +vn -0.0593 0.8895 -0.4530 +vn 0.5467 0.5787 0.6051 +vn 0.4493 0.6046 0.6577 +vn 0.9758 0.1901 0.1077 +vn 0.9795 -0.1263 0.1568 +vn 0.8849 0.3908 -0.2533 +vn 0.6777 -0.7261 0.1162 +vn 0.6306 -0.7210 0.2873 +vn 0.0024 -0.0719 0.9974 +vn 0.0253 -0.0338 0.9991 +vn 0.0301 0.0470 0.9984 +vn -0.6239 -0.7815 0.0006 +vn -0.3808 0.7056 -0.5975 +vn -0.4303 0.7083 -0.5596 +vn 0.1224 0.1774 0.9765 +vn 0.8748 -0.3779 -0.3033 +vn 0.8346 -0.5007 -0.2296 +vn 0.7950 -0.4337 -0.4242 +vn 0.0532 -0.9940 0.0956 +vn -0.5036 0.7608 -0.4094 +vn 0.9558 0.1629 0.2446 +vn 0.4932 0.3060 0.8144 +vn -0.1177 0.9862 -0.1166 +vn -0.1177 0.9862 -0.1165 +vn 0.0359 -0.9955 0.0882 +vn -0.7248 0.1080 -0.6805 +vn -0.9136 -0.1343 -0.3838 +vn 0.1518 0.9562 0.2501 +vn -0.7775 -0.0013 0.6289 +vn -0.9632 -0.0450 0.2652 +vn -0.9077 0.0465 0.4169 +vn 0.7092 0.1341 0.6922 +vn 0.7092 0.1342 0.6922 +vn 0.9947 0.0808 0.0635 +vn 0.9539 0.0597 -0.2941 +vn 0.9953 0.0799 -0.0542 +vn -0.2588 -0.5034 -0.8244 +vn 0.4666 -0.5365 -0.7032 +vn 0.0956 -0.5298 -0.8427 +vn 0.2525 -0.5284 -0.8106 +vn 0.5745 -0.5584 0.5985 +vn 0.4107 -0.6301 0.6590 +vn 0.4319 -0.7401 0.5154 +vn -0.8098 -0.0366 -0.5856 +vn -0.8043 -0.1099 -0.5840 +vn 0.1439 -0.0027 0.9896 +vn 0.0474 -0.0051 0.9989 +vn 0.3799 -0.2901 0.8784 +vn 0.1241 0.4318 0.8934 +vn 0.0218 -0.7302 0.6829 +vn 0.0219 -0.7309 0.6822 +vn 0.0233 -0.7406 0.6715 +vn -0.0648 -0.9978 0.0140 +vn -0.0643 -0.9976 0.0264 +vn -0.0633 -0.9976 0.0293 +vn -0.0903 -0.9926 -0.0814 +vn -0.0905 -0.9954 -0.0324 +vn 0.1197 -0.6252 -0.7712 +vn 0.1255 -0.6229 -0.7722 +vn 0.1266 -0.7573 -0.6407 +vn -0.0151 -0.9933 -0.1150 +vn -0.0485 -0.9927 -0.1107 +vn 0.7167 0.3220 -0.6186 +vn 0.7094 0.2093 -0.6730 +vn 0.7078 0.3181 -0.6307 +vn 0.6544 0.7555 -0.0319 +vn 0.6580 0.7251 -0.2029 +vn -0.7493 0.1181 -0.6516 +vn -0.0342 -0.8445 -0.5344 +vn 0.1300 -0.9682 -0.2135 +vn 0.0950 -0.0375 -0.9948 +vn 0.0320 0.2605 -0.9649 +vn -0.5738 -0.8166 0.0626 +vn -0.1077 0.7330 0.6716 +vn 0.1301 -0.9683 -0.2135 +vn -0.0206 -0.9913 0.1299 +vn -0.1674 -0.9797 -0.1105 +vn 0.0076 -0.9978 -0.0656 +vn 0.0100 -0.9996 0.0269 +vn 0.0065 -0.9999 -0.0132 +vn 0.4482 -0.0784 0.8905 +vn 0.4504 -0.1157 0.8853 +vn 0.5621 0.0403 0.8261 +vn -0.6273 0.7475 0.2184 +vn 0.0406 0.0963 -0.9945 +vn -0.5040 0.1012 -0.8578 +vn -0.2485 0.0216 -0.9684 +vn 0.3609 -0.9036 0.2310 +vn -0.6358 -0.7052 -0.3138 +vn 0.0273 0.0497 -0.9984 +vn -0.2510 0.0694 -0.9655 +vn -0.1744 0.0676 -0.9823 +vn 0.5201 -0.8343 0.1828 +vn 0.6945 -0.5638 0.4470 +vn -0.1073 -0.7001 0.7059 +vn -0.0328 -0.9830 -0.1809 +vn 0.0059 -0.8914 -0.4532 +vn 0.0750 -0.9359 -0.3441 +vn -0.4765 0.2081 0.8542 +vn -0.0461 0.9445 -0.3252 +vn 0.2558 0.9420 -0.2171 +vn 0.0929 0.8830 -0.4601 +vn 0.1585 0.0136 0.9873 +vn 0.0988 -0.0963 0.9904 +vn 0.0230 0.0493 0.9985 +vn 0.1300 0.9682 -0.2135 +vn 0.1084 -0.9720 0.2084 +vn -0.9765 -0.0888 -0.1963 +vn -0.1498 0.6091 0.7788 +vn -0.0909 0.6191 0.7801 +vn 0.6484 -0.2395 -0.7227 +vn 0.9141 -0.1633 -0.3712 +vn 0.8120 -0.1552 -0.5626 +vn -0.4096 -0.5437 0.7325 +vn -0.7361 -0.2385 0.6335 +vn -0.6070 0.0834 -0.7903 +vn -0.8278 0.0926 -0.5534 +vn 0.7042 0.7078 -0.0551 +vn 0.7070 0.7071 -0.0078 +vn 0.7133 0.6992 -0.0481 +vn -0.9869 0.1299 -0.0961 +vn -0.1186 -0.9899 -0.0780 +vn 0.1325 -0.7514 -0.6464 +vn 0.1787 -0.6315 -0.7545 +vn 0.1774 0.1471 0.9731 +vn 0.0254 0.1566 0.9873 +vn 0.4089 0.0990 0.9072 +vn 0.6418 -0.6263 -0.4426 +vn 0.5048 -0.7203 -0.4757 +vn -0.9077 -0.0466 0.4169 +vn -0.0423 -0.2686 -0.9623 +vn 0.0373 0.1033 -0.9939 +vn 0.2531 0.6747 -0.6933 +vn -0.1332 0.8407 -0.5248 +vn -0.0041 -0.2005 0.9797 +vn -0.3919 -0.1991 0.8982 +vn -0.1785 -0.1493 0.9726 +vn 0.9680 0.1565 -0.1963 +vn -0.0040 -0.7639 -0.6453 +vn -0.0570 -0.7927 -0.6069 +vn -0.1092 -0.4333 -0.8946 +vn 0.0278 -0.3789 -0.9250 +vn 0.2414 -0.3010 -0.9226 +vn 0.1642 -0.4995 -0.8506 +vn 0.9857 -0.0908 -0.1420 +vn 0.9167 -0.1486 0.3709 +vn 0.9870 -0.1287 0.0962 +vn -0.9511 0.2473 -0.1850 +vn -0.7780 0.1211 -0.6165 +vn -0.9751 -0.0256 -0.2204 +vn -0.1154 0.2853 -0.9515 +vn -0.4802 -0.8761 -0.0435 +vn -0.3565 -0.9147 0.1904 +vn -0.2765 -0.4356 -0.8566 +vn -0.1820 -0.7754 -0.6046 +vn 0.5866 0.8074 -0.0624 +vn 0.5542 0.7962 -0.2427 +vn 0.1326 0.8791 -0.4579 +vn 0.3802 0.2475 -0.8912 +vn 0.0307 0.2191 -0.9752 +vn 0.3801 0.2475 -0.8912 +vn -0.9918 0.1108 0.0636 +vn -0.9918 0.1108 0.0637 +vn 0.1577 -0.8590 0.4870 +vn -0.5647 -0.3965 0.7238 +vn -0.0957 0.7873 -0.6091 +vn -0.3532 0.2200 0.9093 +vn -0.6793 0.1151 0.7247 +vn -0.5096 0.0848 0.8562 +vn -0.1662 0.3404 0.9255 +vn -0.5302 0.6812 -0.5048 +vn 0.9831 0.1800 -0.0320 +vn 0.9669 0.1865 0.1744 +vn 0.9865 0.1584 0.0424 +vn -0.1166 0.9930 -0.0183 +vn -0.1427 0.9897 -0.0066 +vn -0.1684 0.9857 -0.0096 +vn -0.1319 0.9886 -0.0722 +vn -0.8810 0.1968 0.4302 +vn -0.5929 0.2647 0.7605 +vn -0.7149 0.2485 0.6536 +vn -0.4882 0.8716 -0.0436 +vn -0.2231 0.9422 -0.2500 +vn -0.4523 0.8379 -0.3055 +vn 0.8215 0.5585 0.1152 +vn -0.3091 0.7957 -0.5209 +vn -0.0782 0.9555 -0.2846 +vn 0.0924 -0.8678 0.4883 +vn 0.2955 -0.8791 0.3740 +vn 0.9903 -0.1392 -0.0028 +vn 0.9482 -0.1416 0.2845 +vn 0.9683 -0.1496 0.2000 +vn -0.3701 0.7899 -0.4889 +vn -0.1274 0.9100 -0.3944 +vn 0.3417 -0.6692 -0.6598 +vn 0.1006 -0.9902 0.0973 +vn 0.7107 -0.7019 0.0472 +vn 0.7059 -0.7070 0.0430 +vn 0.7068 -0.7050 0.0582 +vn 0.0962 -0.9951 0.0248 +vn 0.0901 -0.9951 -0.0397 +vn 0.0697 -0.9243 0.3752 +vn -0.0776 0.9957 -0.0514 +vn 0.0520 -0.7351 -0.6759 +vn -0.0852 0.1986 -0.9764 +vn 0.5116 -0.3295 -0.7936 +vn 0.1496 -0.7496 -0.6447 +vn 0.1665 -0.7077 -0.6866 +vn 0.0997 -0.7478 -0.6564 +vn 0.2647 -0.0254 0.9640 +vn 0.2031 -0.0192 0.9790 +vn 0.4394 0.6709 0.5973 +vn 0.2948 0.6288 0.7196 +vn 0.4860 0.5352 0.6909 +vn 0.1038 -0.9852 -0.1368 +vn 0.1067 -0.9922 -0.0642 +vn -0.1071 0.7917 0.6014 +vn 0.0584 -0.5915 0.8042 +vn 0.1015 -0.7698 0.6302 +vn 0.0729 -0.7962 0.6006 +vn -0.1108 0.5010 0.8583 +vn -0.1830 0.4649 0.8663 +vn 0.4219 0.8133 0.4006 +vn 0.2122 0.8108 0.5455 +vn 0.4674 0.1332 0.8739 +vn 0.6644 0.0750 0.7436 +vn 0.7998 0.0282 0.5996 +vn 0.2679 -0.4139 0.8700 +vn 0.5301 -0.1185 0.8396 +vn 0.4572 0.3896 -0.7995 +vn 0.2750 0.5525 -0.7868 +vn 0.3767 0.5551 -0.7415 +vn -0.8968 0.1118 0.4282 +vn -0.6308 0.0577 0.7738 +vn 0.7493 -0.1181 0.6516 +vn 0.7493 -0.1180 0.6517 +vn 0.1242 -0.6854 -0.7175 +vn 0.1068 -0.6394 -0.7614 +vn 0.2514 -0.7237 -0.6427 +vn -0.9245 0.0139 0.3809 +vn -0.8493 -0.1229 0.5133 +vn -0.6360 -0.7179 0.2830 +vn -0.7328 -0.6434 0.2215 +vn -0.7735 -0.6289 0.0787 +vn -0.1207 0.3503 0.9288 +vn 0.1257 -0.0257 -0.9917 +vn -0.6717 0.5100 -0.5373 +vn -0.1780 0.9840 -0.0049 +vn -0.1790 0.9838 -0.0054 +vn -0.6685 0.1562 -0.7271 +vn -0.6183 0.1046 -0.7789 +vn 0.0912 -0.7194 0.6886 +vn 0.0076 -0.7033 0.7109 +vn -0.2191 -0.6169 0.7559 +vn 0.2222 0.9002 0.3744 +vn 0.3962 0.8920 0.2178 +vn 0.5057 -0.7860 0.3557 +vn 0.4525 -0.7514 0.4802 +vn 0.3287 -0.7156 0.6164 +vn 0.0839 0.7150 0.6941 +vn -0.1029 0.7628 0.6384 +vn 0.9523 0.1266 -0.2778 +vn 0.9523 0.1265 -0.2778 +vn 0.2318 -0.6656 -0.7094 +vn 0.0663 -0.0198 -0.9976 +vn 0.0407 -0.5202 -0.8530 +vn -0.9521 0.2892 0.0993 +vn -0.9211 0.3799 0.0858 +vn -0.8711 0.4910 0.0048 +vn -0.0404 0.2641 0.9636 +vn 0.9862 -0.1496 -0.0713 +vn 0.8148 -0.5633 -0.1368 +vn 0.1984 0.1416 0.9698 +vn -0.1216 0.1352 0.9833 +vn 0.0468 -0.6860 0.7261 +vn 0.0555 -0.9302 0.3629 +vn 0.0476 -0.6923 0.7201 +vn -0.0334 0.0566 0.9978 +vn 0.4166 0.0753 0.9060 +vn -0.4312 0.8753 0.2190 +vn -0.8032 0.2024 0.5603 +vn -0.9667 0.1630 0.1973 +vn -0.1028 -0.9787 0.1776 +vn -0.0893 -0.9898 0.1107 +vn -0.1258 -0.9829 0.1345 +vn -0.6374 0.7693 0.0423 +vn -0.7302 0.6736 -0.1141 +vn -0.7774 0.6208 0.1014 +vn -0.0134 -0.8527 0.5223 +vn -0.9755 0.0976 -0.1972 +vn -0.9473 0.0799 -0.3101 +vn 0.5616 -0.2719 -0.7815 +vn 0.0943 -0.9909 0.0960 +vn 0.7099 0.0427 0.7030 +vn 0.7087 -0.0666 0.7023 +vn 0.7099 -0.1008 0.6971 +vn -0.9523 -0.1265 0.2778 +vn -0.9187 -0.0299 -0.3938 +vn 0.0947 0.2531 -0.9628 +vn 0.0841 0.0068 -0.9964 +vn -0.1079 0.2310 0.9670 +vn -0.5235 0.2531 0.8136 +vn -0.1905 0.2343 0.9533 +vn -0.3473 -0.7791 -0.5219 +vn -0.5259 -0.8206 -0.2236 +vn 0.9862 0.1496 -0.0713 +vn -0.1441 -0.9886 -0.0439 +vn -0.2950 -0.9376 0.1839 +vn -0.1502 0.0566 0.9870 +vn -0.1498 0.0591 0.9870 +vn -0.0816 0.0240 0.9964 +vn 0.4567 -0.6993 0.5499 +vn 0.7034 -0.6175 0.3521 +vn 0.1581 0.9164 -0.3676 +vn 0.1562 0.9327 -0.3250 +vn -0.1988 -0.2773 0.9400 +vn 0.0454 -0.2679 0.9624 +vn 0.3571 -0.2122 0.9097 +vn 0.0772 0.7446 0.6630 +vn 0.2570 0.6709 0.6956 +vn 0.2101 0.7299 0.6505 +vn -0.6503 0.7571 0.0616 +vn -0.0101 0.7253 0.6884 +vn 0.0132 0.5984 0.8011 +vn 0.0089 0.7674 0.6412 +vn 0.5517 -0.6884 0.4708 +vn 0.1567 -0.8946 -0.4184 +vn 0.1257 -0.7940 -0.5948 +vn 0.6706 -0.0909 0.7362 +vn 0.6034 -0.0972 0.7915 +vn 0.0495 -0.7392 0.6717 +vn -0.8569 0.0402 0.5139 +vn -0.8945 0.0434 0.4450 +vn 0.0270 -0.6931 0.7203 +vn -0.6358 0.7052 -0.3138 +vn -0.5626 0.8147 -0.1405 +vn -0.0742 -0.8850 -0.4597 +vn -0.0278 -0.7243 -0.6889 +vn 0.0806 -0.7826 -0.6173 +vn -0.2510 0.1434 0.9573 +vn -0.5482 -0.1737 0.8181 +vn -0.0938 0.9955 -0.0118 +vn -0.4027 -0.1088 -0.9088 +vn -0.2635 -0.1392 -0.9546 +vn -0.8047 -0.0083 -0.5936 +vn 0.0118 -0.9477 0.3191 +vn 0.3192 -0.6376 0.7011 +vn -0.0754 -0.6935 0.7165 +vn 0.0562 0.2716 0.9608 +vn 0.0621 0.3551 0.9328 +vn 0.6752 -0.5977 0.4324 +vn 0.6752 -0.5976 0.4324 +vn -0.1096 0.9886 -0.1029 +vn -0.0790 0.9922 -0.0960 +vn 0.0674 0.5798 0.8119 +vn 0.1182 0.2086 0.9708 +vn 0.4063 0.3535 0.8426 +vn 0.1101 -0.9644 -0.2407 +vn 0.5748 -0.5390 -0.6157 +vn -0.1553 -0.1487 0.9766 +vn -0.1416 -0.1778 0.9738 +vn -0.5671 -0.8133 -0.1304 +vn -0.5334 -0.7690 -0.3524 +vn -0.5054 -0.8131 -0.2890 +vn -0.5728 0.7950 -0.1997 +vn -0.4245 0.7122 -0.5590 +vn -0.5743 0.7003 -0.4240 +vn 0.9870 0.1287 0.0962 +vn -0.0937 0.6332 0.7683 +vn -0.0336 0.7103 0.7031 +vn -0.0293 0.4969 0.8673 +vn -0.0170 -0.9972 0.0728 +vn 0.2341 -0.9597 0.1556 +vn 0.7546 0.4600 -0.4679 +vn -0.1319 0.9912 -0.0143 +vn -0.1245 0.9832 -0.1334 +vn -0.1587 0.9869 -0.0279 +vn -0.1069 0.2776 0.9547 +vn -0.7231 -0.1575 -0.6726 +vn -0.7085 -0.1197 -0.6955 +vn 0.7279 -0.0919 0.6795 +vn 0.7279 -0.0918 0.6795 +vn 0.8429 -0.0054 0.5380 +vn 0.7998 -0.0282 0.5996 +vn 0.9733 0.0836 0.2139 +vn 0.0048 0.9302 -0.3671 +vn -0.4883 -0.8716 -0.0436 +vn 0.1408 0.6764 -0.7229 +vn 0.0596 0.7228 -0.6884 +vn -0.5663 0.8240 -0.0198 +vn 0.6745 -0.7078 0.2101 +vn 0.7888 -0.2632 0.5554 +vn -0.2187 -0.2410 0.9456 +vn -0.1512 -0.3504 0.9243 +vn -0.1691 -0.3531 0.9202 +vn 0.5483 0.0672 0.8336 +vn 0.0518 -0.1241 -0.9909 +vn -0.4039 -0.8257 -0.3939 +vn -0.0053 0.3165 0.9486 +vn -0.1688 0.5228 0.8356 +vn -0.2895 0.3060 0.9069 +vn -0.3009 -0.1371 -0.9437 +vn -0.0990 -0.1345 -0.9860 +vn -0.0471 0.9978 0.0457 +vn 0.0492 0.9949 0.0883 +vn 0.0258 -0.4018 -0.9153 +vn 0.0378 0.8616 0.5062 +vn 0.0674 0.7434 0.6654 +vn 0.1116 0.9746 0.1944 +vn 0.8472 -0.0479 -0.5291 +vn 0.5855 0.5396 0.6050 +vn 0.7401 0.5423 0.3977 +vn 0.6258 0.5991 0.4995 +vn 0.8169 0.4290 -0.3855 +vn 0.0427 -0.9649 -0.2593 +vn 0.2154 -0.8379 -0.5015 +vn 0.3446 -0.8891 -0.3012 +vn -0.1674 0.9797 -0.1105 +vn -0.5223 0.7927 -0.3143 +vn 0.1402 0.6608 -0.7374 +vn 0.1442 -0.9886 0.0438 +vn -0.8914 -0.4527 0.0236 +vn -0.6415 -0.7297 -0.2367 +vn -0.5873 0.4767 -0.6541 +vn 0.6914 0.5867 -0.4216 +vn 0.5600 0.7780 0.2849 +vn 0.6082 0.7805 0.1446 +vn 0.5554 0.8207 0.1344 +vn 0.0623 0.6474 0.7596 +vn 0.0494 0.6608 0.7489 +vn -0.0177 0.7362 0.6765 +vn -0.2445 -0.7592 0.6032 +vn 0.1983 -0.8066 0.5569 +vn -0.9851 -0.1521 0.0807 +vn 0.6104 -0.7231 -0.3233 +vn 0.6903 -0.7187 -0.0830 +vn 0.5848 -0.8078 -0.0733 +vn -0.0591 0.0505 0.9970 +vn -0.0944 0.0075 0.9955 +vn 0.4631 -0.8254 0.3230 +vn 0.5229 -0.6674 0.5302 +vn 0.3677 0.9281 -0.0578 +vn 0.6301 0.7375 -0.2432 +vn 0.9540 0.0592 -0.2940 +vn -0.5197 0.0052 -0.8543 +vn -0.3329 0.1917 0.9233 +vn -0.1300 -0.9683 0.2134 +vn 0.0483 -0.1732 0.9837 +vn 0.0120 -0.1285 0.9916 +vn -0.5174 0.0598 -0.8536 +vn 0.7933 0.2302 -0.5636 +vn 0.7167 0.2531 -0.6499 +vn 0.1158 -0.9912 0.0639 +vn 0.9999 0.0129 0.0000 +vn -1.0000 0.0002 0.0000 +vn -0.3840 -0.7654 -0.5165 +vn 0.5004 0.4638 0.7311 +vn 0.2357 0.4621 0.8550 +vn 0.4938 0.2387 0.8362 +vn -0.1031 0.3212 0.9414 +vn -0.4199 0.0505 0.9062 +vn -0.5216 0.0401 0.8522 +vn -0.8474 0.1309 -0.5145 +vn -0.8176 0.5502 -0.1698 +vn -0.7664 0.5321 -0.3599 +vn 0.5744 0.8093 0.1233 +vn -0.1104 0.6804 0.7245 +vn -0.1195 0.7275 0.6756 +vn -0.1708 0.9847 -0.0342 +vn -0.0435 -0.9331 0.3570 +vn 0.6777 0.7261 0.1162 +vn 0.1030 -0.8808 -0.4621 +vn 0.7098 0.6823 0.1752 +vn 0.7069 0.6535 0.2706 +vn 0.8835 -0.2238 0.4116 +vn 0.7699 0.2956 0.5656 +vn 0.7522 -0.0080 0.6589 +vn 0.7615 0.0093 -0.6481 +vn -0.0581 -0.1535 -0.9864 +vn 0.9585 -0.0044 0.2851 +vn -0.0624 -0.9973 0.0398 +vn -0.0411 -0.9991 -0.0098 +vn 0.0974 -0.4018 0.9105 +vn 0.0811 -0.5421 0.8364 +vn 0.0872 -0.4933 0.8655 +vn 0.5087 0.7896 0.3431 +vn 0.4834 0.8235 0.2969 +vn -0.1814 -0.9748 -0.1295 +vn 0.5325 0.6390 0.5551 +vn 0.2556 0.6530 0.7129 +vn 0.2626 0.6527 0.7106 +vn -0.7161 0.5678 0.4059 +vn -0.7751 0.4917 0.3968 +vn 0.7153 -0.3111 0.6257 +vn 0.7102 -0.4255 0.5608 +vn -0.4146 -0.8298 0.3735 +vn -0.1826 -0.7415 0.6457 +vn -0.3459 -0.7587 0.5520 +vn 0.7011 -0.5455 0.4592 +vn 0.7086 -0.5101 0.4875 +vn 0.6930 -0.5736 0.4368 +vn 0.8017 0.0895 0.5910 +vn 0.8449 0.0750 0.5296 +vn 0.6342 0.1574 0.7570 +vn 0.1295 0.1952 0.9722 +vn 0.4333 0.1381 0.8906 +vn 0.9785 -0.0379 -0.2030 +vn 0.1482 -0.5896 -0.7940 +vn -0.5483 0.0672 -0.8336 +vn -0.0876 -0.9905 -0.1062 +vn 0.0776 0.9957 0.0514 +vn 0.0016 0.4916 -0.8708 +vn 0.0977 0.4066 -0.9084 +vn -0.1178 0.9862 -0.1165 +vn -0.0542 0.6148 -0.7868 +vn -0.1040 0.7597 -0.6419 +vn -0.0504 0.6365 -0.7696 +vn -0.1463 0.3406 0.9288 +vn -0.9618 0.0840 0.2606 +vn -0.8929 0.0538 0.4470 +vn -0.9770 0.1012 0.1876 +vn -0.0164 0.9916 0.1279 +vn 0.1301 0.9682 -0.2135 +vn 0.2367 0.9650 0.1126 +vn 0.4108 0.8598 0.3034 +vn 0.0850 0.6226 -0.7779 +vn -0.1231 -0.3532 0.9274 +vn -0.2017 -0.3221 0.9250 +vn -0.1107 -0.5020 0.8578 +vn -0.7437 0.0322 0.6677 +vn -0.1334 -0.6402 -0.7565 +vn -0.1857 -0.7433 -0.6427 +vn -0.1890 -0.7945 -0.5771 +vn 0.7027 -0.7059 0.0893 +vn -0.9966 -0.0789 -0.0233 +vn -0.9497 -0.0895 -0.3002 +vn 0.0428 0.5280 0.8482 +vn -0.0458 0.8145 0.5784 +vn -0.0145 0.7467 -0.6651 +vn -0.0359 0.6467 -0.7619 +vn 0.0726 0.4364 -0.8968 +vn -0.2243 -0.0098 -0.9745 +vn 0.3227 0.6891 0.6489 +vn 0.3325 0.6748 0.6588 +vn -0.2037 0.7963 -0.5695 +vn -0.1140 -0.9675 -0.2256 +vn -0.1836 0.9316 -0.3137 +vn 0.6466 -0.7476 0.1519 +vn 0.6613 0.4090 -0.6288 +vn 0.5517 0.6884 0.4708 +vn 0.5437 0.0855 0.8349 +vn 0.6034 0.0972 0.7915 +vn -0.9853 -0.1022 -0.1366 +vn -0.9875 -0.1458 0.0597 +vn -0.4784 0.7719 0.4188 +vn -0.1045 0.6393 -0.7618 +vn -0.3139 0.7804 -0.5408 +vn -0.1844 0.7416 -0.6450 +vn -0.2830 -0.9215 0.2662 +vn 0.1851 -0.9575 0.2213 +vn 0.0106 -0.9999 -0.0107 +vn 0.3838 -0.9214 0.0611 +vn -0.0437 -0.8530 -0.5201 +vn -0.1788 -0.2097 -0.9613 +vn -0.4158 -0.1659 -0.8942 +vn 0.2955 0.8791 0.3740 +vn 0.5221 -0.7147 0.4654 +vn -0.1510 -0.0239 0.9882 +vn 0.1425 0.9420 -0.3037 +vn -0.3242 0.6403 0.6963 +vn -0.8041 -0.1172 0.5828 +vn -0.6590 -0.1455 0.7380 +vn 0.5355 -0.3725 0.7579 +vn -0.5671 0.8133 -0.1304 +vn -0.2239 -0.6254 -0.7475 +vn -0.0949 -0.7366 -0.6696 +vn -0.0374 -0.6501 -0.7589 +vn -0.1097 -0.8232 -0.5571 +vn -0.1031 -0.8085 -0.5793 +vn 0.0011 -0.7800 -0.6258 +vn 0.0471 -0.6237 -0.7802 +vn 0.0771 -0.7835 -0.6166 +vn 0.1236 -0.6118 -0.7813 +vn 0.1557 -0.7503 -0.6425 +vn -0.2721 0.2846 0.9192 +vn -0.1988 0.2773 0.9400 +vn 0.0454 0.2679 0.9624 +vn 0.0666 -0.5161 -0.8539 +vn -0.1597 0.9676 0.1953 +vn -0.1547 0.9774 0.1442 +vn 0.1647 0.7481 0.6428 +vn 0.1142 0.6059 0.7873 +vn 0.0133 0.1804 0.9835 +vn 0.0918 -0.7385 -0.6679 +vn 0.0910 -0.7472 -0.6583 +vn 0.0678 -0.6368 -0.7681 +vn 0.0871 -0.7485 -0.6574 +vn 0.0881 -0.7533 -0.6518 +vn 0.9875 -0.1458 -0.0597 +vn -0.3145 0.6327 0.7077 +vn -0.3836 0.7256 0.5713 +vn 0.0301 0.1138 -0.9930 +vn -0.8954 -0.1149 0.4302 +vn -0.8602 -0.1033 0.4994 +vn 0.4503 0.0143 -0.8928 +vn 0.7657 -0.0232 -0.6428 +vn 0.5228 0.0019 -0.8525 +vn -0.7240 -0.5376 0.4322 +vn -0.6984 -0.5624 0.4426 +vn 0.0129 0.0526 0.9985 +vn 0.0869 0.9948 0.0530 +vn -0.9487 0.1502 -0.2781 +vn -0.7624 0.1392 -0.6319 +vn -0.7860 0.1365 -0.6030 +vn -0.2258 -0.5181 0.8250 +vn -0.9647 -0.0015 -0.2632 +vn -0.9114 -0.0034 -0.4115 +vn -0.9926 0.0883 -0.0835 +vn -0.9352 0.2040 -0.2895 +vn 0.9336 -0.1571 0.3220 +vn -0.9751 0.0256 -0.2204 +vn 0.0300 -0.4317 -0.9015 +vn -0.0539 0.9158 0.3981 +vn 0.0026 0.7830 0.6220 +vn -0.4683 -0.7907 0.3942 +vn 0.6940 0.7143 0.0902 +vn 0.7055 0.7071 0.0483 +vn 0.7144 0.6984 0.0425 +vn 0.7089 0.7034 0.0520 +vn 0.7012 0.6957 0.1558 +vn 0.1496 0.0427 -0.9878 +vn 0.1606 -0.2286 0.9602 +vn 0.1352 0.0336 0.9903 +vn 0.1586 -0.0783 0.9842 +vn 0.1526 0.9726 0.1752 +vn 0.1215 -0.0368 0.9919 +vn 0.2067 0.1218 0.9708 +vn 0.1295 -0.3318 0.9344 +vn 0.1935 -0.0843 0.9775 +vn 0.1611 -0.4486 0.8791 +vn 0.2155 0.0323 0.9760 +vn 0.1573 -0.0491 0.9863 +vn 0.3117 -0.5982 0.7382 +vn -0.1200 -0.6508 0.7497 +vn -0.1188 -0.9865 -0.1130 +vn -0.1301 0.0670 0.9892 +vn -0.1425 -0.0475 0.9886 +vn -0.1265 0.1937 0.9729 +vn -0.1132 -0.1324 0.9847 +vn -0.1020 0.0793 0.9916 +vn -0.1645 0.9859 -0.0301 +vn -0.0144 -0.1638 0.9864 +vn -0.1477 0.2580 0.9548 +vn 0.1178 0.9862 0.1165 +vn 0.7168 -0.4008 -0.5706 +vn 0.0114 -0.3218 0.9467 +vn -0.0482 -0.3816 0.9231 +vn 0.0590 -0.4235 0.9040 +vn 0.9742 -0.0590 0.2178 +vn 0.1619 -0.1736 -0.9714 +vn 0.1725 -0.3702 -0.9128 +vn 0.0318 -0.2717 0.9619 +vn -0.0039 0.0503 0.9987 +vn 0.0032 -0.0912 0.9958 +vn -0.0315 0.0894 0.9955 +vn 0.0531 -0.5307 -0.8459 +vn 0.0161 -0.0557 0.9983 +vn 0.1054 -0.0792 0.9913 +vn -0.6947 0.0095 0.7192 +vn -0.0775 -0.9957 -0.0515 +vn 0.2039 -0.0021 0.9790 +vn 0.5895 -0.8040 0.0781 +vn -0.0268 -0.5229 -0.8520 +vn 0.0679 0.7538 0.6536 +vn 0.1181 0.6294 0.7680 +vn 0.0125 0.6549 0.7556 +vn 0.0012 0.9992 0.0399 +vn 0.0119 0.9998 -0.0178 +vn 0.9894 -0.1395 -0.0398 +vn 0.9894 -0.1394 -0.0398 +vn -0.9452 -0.0350 -0.3247 +vn -0.9811 -0.0571 -0.1848 +vn 0.1115 -0.9908 -0.0766 +vn -0.0873 0.0683 0.9938 +vn -0.0890 0.1012 0.9909 +vn -0.1238 0.0230 -0.9920 +vn -0.4277 0.8611 -0.2749 +vn -0.3016 0.8268 -0.4748 +vn 0.6659 0.1655 0.7275 +vn 0.4702 0.1588 0.8682 +vn 0.4702 0.1588 0.8681 +vn -0.6185 0.7774 0.1146 +vn 0.0644 0.6903 -0.7206 +vn -0.1998 0.6844 -0.7011 +vn -0.1116 -0.0028 0.9937 +vn 0.6754 0.0472 0.7359 +vn 0.6737 0.0342 0.7382 +vn 0.8694 -0.0327 0.4930 +vn -0.4190 0.8186 -0.3928 +vn -0.5208 0.8172 -0.2468 +vn -0.5019 0.8362 -0.2210 +vn 0.1177 -0.9862 0.1166 +vn 0.0170 -0.1758 0.9843 +vn 0.0920 -0.2824 0.9549 +vn 0.7493 0.1181 0.6516 +vn 0.2102 0.0752 0.9748 +vn 0.1880 0.0247 0.9819 +vn 0.1473 0.1814 0.9723 +vn 0.9894 0.1394 -0.0398 +vn 0.9894 0.1395 -0.0398 +vn -0.1532 0.9701 -0.1884 +vn 0.9918 -0.1109 -0.0636 +vn 0.1219 0.9137 0.3877 +vn 0.1321 0.7377 0.6621 +vn -0.4048 -0.0752 -0.9113 +vn -0.2120 -0.0668 -0.9750 +vn 0.5919 0.3239 0.7381 +vn 0.6456 -0.0003 0.7637 +vn 0.6444 0.0204 0.7645 +vn -0.4217 0.1028 0.9009 +vn -0.4238 0.0478 0.9045 +vn -0.3295 -0.0574 0.9424 +vn -0.2429 0.0560 0.9684 +vn -0.1401 0.8721 -0.4688 +vn -0.7183 0.6722 -0.1794 +vn 0.1399 -0.2112 -0.9674 +vn 0.1255 -0.0770 0.9891 +vn 0.1780 0.0966 0.9793 +vn 0.1357 0.1282 0.9824 +vn 0.2176 -0.0492 0.9748 +vn 0.2549 -0.0842 0.9633 +vn 0.1882 -0.0255 0.9818 +vn -0.1381 -0.0248 0.9901 +vn 0.2541 -0.0582 0.9654 +vn 0.3682 0.0601 0.9278 +vn 0.6260 0.7620 -0.1657 +vn -0.1446 -0.4092 0.9009 +vn -0.4479 -0.3776 0.8104 +vn -0.2810 -0.5119 0.8118 +vn 0.2373 -0.9116 -0.3356 +vn 0.4224 -0.3760 -0.8247 +vn 0.0406 -0.0963 -0.9945 +vn 0.4917 -0.0032 -0.8708 +vn -0.0432 -0.5287 0.8477 +vn -0.9763 0.1636 0.1419 +vn -0.9820 0.1885 0.0125 +vn -0.0909 -0.9887 0.1190 +vn -0.0720 -0.9615 0.2653 +vn -0.0327 0.1096 0.9934 +vn -0.9713 0.2172 -0.0973 +vn -0.8987 0.2126 -0.3835 +vn -0.9232 0.2420 -0.2987 +vn -0.0369 -0.8662 0.4983 +vn -0.0763 -0.9229 0.3773 +vn -0.8127 0.1829 -0.5532 +vn -0.6664 0.6947 -0.2707 +vn -0.1108 0.9925 0.0509 +vn -0.1107 0.9796 0.1679 +vn -0.1107 0.9796 0.1678 +vn -0.6205 -0.0078 0.7842 +vn -0.6205 -0.0078 0.7841 +vn -0.2227 -0.1543 0.9626 +vn -0.4167 0.2487 0.8743 +vn -0.4168 0.2487 0.8743 +vn 0.3571 0.2122 0.9097 +vn 0.3583 0.2249 0.9061 +vn -0.5517 0.7470 -0.3711 +vn 0.2660 -0.0016 -0.9640 +vn -0.1595 -0.2509 0.9548 +vn 0.8710 0.2658 -0.4131 +vn -0.2376 0.6875 -0.6863 +vn 0.1868 -0.3923 0.9007 +vn -0.0871 0.0136 -0.9961 +vn -0.4388 -0.6448 0.6259 +vn 0.6337 0.7736 -0.0023 +vn -0.9560 0.0348 -0.2912 +vn -0.9145 -0.1834 0.3605 +vn -0.9931 -0.1014 0.0582 +vn -0.8805 -0.2031 0.4284 +vn 0.0294 -0.1358 -0.9903 +vn 0.6955 -0.6547 -0.2961 +vn 0.3694 -0.7339 -0.5700 +vn 0.5784 -0.6917 -0.4324 +vn 0.7181 -0.0740 -0.6920 +vn 0.8967 -0.1123 -0.4282 +vn 0.7691 -0.0942 -0.6322 +vn 0.3713 -0.8719 -0.3193 +vn 0.6161 0.7874 -0.0179 +vn 0.5119 0.8112 0.2826 +vn 0.5012 -0.2648 -0.8238 +vn 0.4469 -0.2232 -0.8663 +vn 0.6779 -0.3528 -0.6450 +vn -0.0775 0.9957 -0.0516 +vn 0.9190 -0.1818 -0.3498 +vn 0.0972 -0.7678 0.6332 +vn 0.0884 -0.6204 0.7793 +vn 0.9632 0.0537 -0.2633 +vn 0.6966 -0.6642 -0.2713 +vn 0.7053 -0.6038 -0.3715 +vn 0.7063 -0.6135 -0.3533 +vn -0.0551 0.0017 0.9985 +vn 0.7094 0.1662 0.6849 +vn 0.7022 0.1198 0.7018 +vn -0.1802 -0.9792 -0.0933 +vn -0.2739 -0.9545 -0.1184 +vn -0.2387 -0.9624 -0.1294 +vn -0.1503 0.2878 0.9458 +vn -0.4455 0.3765 0.8123 +vn 0.0776 -0.9957 0.0514 +vn 0.0220 -0.1635 0.9863 +vn 0.4087 -0.0983 0.9074 +vn 0.5952 0.5660 -0.5704 +vn 0.0372 -0.8675 0.4961 +vn 0.0305 -0.8359 0.5480 +vn -0.3011 0.9169 -0.2620 +vn 0.3351 0.6862 -0.6456 +vn 0.0578 -0.1737 -0.9831 +vn -0.1202 0.1491 0.9815 +vn -0.1908 0.2197 0.9567 +vn -0.0067 0.5068 0.8620 +vn -0.3952 -0.6299 -0.6686 +vn -0.2028 -0.3555 -0.9124 +vn 0.3235 0.8694 -0.3736 +vn -0.9983 0.0368 -0.0460 +vn 0.0320 0.6519 -0.7576 +vn 0.1880 0.5613 -0.8060 +vn -0.1098 0.6162 -0.7799 +vn -0.8744 -0.0288 -0.4843 +vn -0.9819 -0.1199 -0.1469 +vn -0.9815 -0.1028 -0.1618 +vn -0.5430 -0.5807 -0.6065 +vn 0.8150 0.2649 -0.5153 +vn 0.2731 0.0850 0.9582 +vn 0.7457 0.0273 -0.6657 +vn 0.9539 -0.0597 -0.2941 +vn -0.8167 -0.1379 0.5603 +vn -0.5708 0.1029 -0.8146 +vn -0.5708 0.1030 -0.8146 +vn 0.0292 -0.5007 0.8651 +vn -0.1690 -0.1357 -0.9762 +vn 0.0301 -0.1138 -0.9930 +vn 0.0296 -0.1187 -0.9925 +vn -0.0504 -0.2568 0.9651 +vn -0.0063 0.0066 1.0000 +vn -0.0352 -0.0583 0.9977 +vn -0.3602 -0.6350 -0.6835 +vn -0.2028 -0.6015 -0.7727 +vn -0.2156 -0.6503 -0.7284 +vn 0.4392 0.0146 -0.8983 +vn 0.3416 -0.0036 -0.9398 +vn -0.1448 -0.7641 -0.6286 +vn 0.0484 -0.7479 0.6620 +vn 0.0283 -0.6744 0.7378 +vn -0.5178 -0.7513 0.4091 +vn -0.6704 -0.7290 0.1381 +vn -0.8373 -0.2175 0.5017 +vn 0.8456 -0.1661 0.5073 +vn -0.4220 -0.4753 -0.7720 +vn -0.4961 -0.5979 -0.6296 +vn 0.0886 -0.9894 -0.1153 +vn 0.0699 -0.9821 -0.1749 +vn 0.0886 -0.9869 0.1352 +vn 0.0372 -0.9861 -0.1616 +vn 0.0256 -0.9726 -0.2313 +vn 0.0517 -0.9958 -0.0750 +vn 0.0531 -0.9666 -0.2507 +vn 0.0515 -0.9958 -0.0752 +vn 0.8150 -0.2648 -0.5153 +vn -0.0124 -0.4537 -0.8910 +vn 0.0434 -0.5993 -0.7994 +vn 0.0623 -0.6117 -0.7886 +vn 0.9657 0.0714 0.2495 +vn 0.9605 0.1764 -0.2154 +vn 0.0593 -0.0954 -0.9937 +vn 0.0580 0.1048 -0.9928 +vn 0.0546 0.2975 -0.9532 +vn 0.0237 0.2546 0.9668 +vn 0.0558 0.8353 -0.5469 +vn 0.0111 0.8111 -0.5848 +vn -0.0152 0.7618 -0.6476 +vn -0.1887 -0.9261 -0.3267 +vn -0.1921 0.6952 -0.6927 +vn 0.7137 0.0706 0.6969 +vn 0.1671 0.6484 -0.7427 +vn -0.0288 0.5173 -0.8553 +vn -0.3090 -0.7941 -0.5234 +vn -0.3766 0.6035 0.7029 +vn -0.6254 0.6636 0.4104 +vn -0.0618 0.0380 -0.9974 +vn -0.0792 -0.0443 -0.9959 +vn -0.7248 -0.1080 -0.6805 +vn -0.4487 0.1503 -0.8809 +vn -0.1690 0.1357 -0.9762 +vn -0.8995 -0.0255 -0.4362 +vn -0.0690 0.8113 -0.5806 +vn -0.5519 0.7237 -0.4144 +vn -0.5370 -0.1855 -0.8230 +vn -0.5040 -0.1012 -0.8578 +vn -0.2485 -0.0216 -0.9684 +vn -0.2983 0.0056 -0.9545 +vn -0.0898 0.0054 -0.9959 +vn 0.0653 -0.7044 -0.7068 +vn 0.0170 -0.6452 -0.7638 +vn 0.1847 -0.6798 -0.7098 +vn 0.0799 -0.8370 0.5414 +vn 0.1478 -0.4818 0.8637 +vn 0.1584 -0.4235 0.8919 +vn 0.1765 -0.3479 0.9208 +vn 0.6150 -0.7350 -0.2857 +vn 0.0516 -0.6182 0.7843 +vn 0.0457 -0.6154 0.7869 +vn 0.1301 0.9682 -0.2138 +vn -0.4581 -0.0227 0.8886 +vn -0.4835 -0.0646 0.8729 +vn 0.1681 0.1906 0.9672 +vn -0.1820 0.9833 -0.0024 +vn 0.3384 -0.4573 0.8224 +vn 0.1348 -0.4176 0.8986 +vn 0.7953 0.5869 0.1519 +vn 0.8519 0.5165 -0.0866 +vn 0.9400 -0.0280 0.3400 +vn 0.9909 0.1193 0.0622 +vn 0.9919 0.1252 0.0203 +vn -0.9875 0.1457 0.0598 +vn -0.9875 0.1458 0.0598 +vn -0.5610 0.6183 -0.5504 +vn -0.5765 0.5799 -0.5757 +vn -0.6693 0.6559 -0.3490 +vn 0.7633 0.0359 -0.6451 +vn -0.7100 0.6658 -0.2294 +vn 0.6393 -0.0414 0.7678 +vn 0.5372 -0.4160 0.7338 +vn 0.6438 0.7194 -0.2606 +vn -0.9645 0.2189 0.1480 +vn -0.9845 0.1208 0.1268 +vn -0.8254 0.3568 0.4374 +vn 0.6093 0.3736 0.6994 +vn -0.7363 -0.5489 0.3957 +vn -0.5035 -0.8609 0.0734 +vn 0.4939 0.0558 -0.8677 +vn -0.3432 0.2031 0.9170 +vn -0.5342 -0.8060 -0.2550 +vn 0.0110 -0.7545 0.6562 +vn 0.0260 -0.7037 0.7100 +vn 0.0250 -0.7075 0.7063 +vn 0.7167 -0.2531 -0.6499 +vn -0.3023 0.1367 -0.9434 +vn -0.7713 0.6323 0.0732 +vn 0.1217 -0.8835 -0.4522 +vn 0.2391 0.7752 -0.5848 +vn 0.2185 0.7083 -0.6712 +vn 0.1997 0.7185 -0.6663 +vn 0.8887 -0.0925 0.4491 +vn 0.8865 0.4198 -0.1947 +vn 0.8187 0.2559 -0.5140 +vn -0.6266 -0.6333 -0.4542 +vn 0.5402 0.2256 -0.8107 +vn 0.4778 0.2139 -0.8520 +vn 0.1766 0.4308 -0.8850 +vn 0.7090 -0.5268 -0.4689 +vn 0.7064 -0.5180 -0.4824 +vn 0.4486 0.8621 -0.2357 +vn 0.2340 0.8782 -0.4172 +vn 0.7016 0.7043 -0.1081 +vn 0.0555 -0.6769 0.7340 +vn 0.0177 0.9986 0.0490 +vn 0.0803 -0.4508 0.8890 +vn 0.5119 -0.8112 0.2826 +vn 0.5866 -0.8075 -0.0624 +vn 0.6161 -0.7875 -0.0179 +vn -0.2898 0.8046 -0.5183 +vn 0.6306 0.7210 0.2873 +vn -0.9731 -0.1453 0.1790 +vn -0.1943 0.7514 -0.6306 +vn -0.2026 0.7544 -0.6243 +vn -0.2343 0.6133 -0.7543 +vn 0.0156 0.8761 0.4819 +vn 0.0309 0.5665 0.8235 +vn 0.9775 -0.1403 -0.1572 +vn -0.2077 -0.0165 0.9780 +vn 0.2159 -0.4149 0.8839 +vn 0.1974 -0.2675 0.9431 +vn 0.4750 0.8004 0.3657 +vn 0.0871 0.8986 0.4300 +vn 0.0446 -0.7389 -0.6723 +vn 0.0727 -0.9225 -0.3791 +vn 0.0198 -0.2551 0.9667 +vn -0.1926 0.6637 0.7228 +vn -0.2580 0.7368 0.6250 +vn -0.1088 0.7023 0.7035 +vn -0.9623 -0.1300 0.2390 +vn -0.6547 -0.7028 -0.2783 +vn -0.4689 -0.7948 -0.3853 +vn -0.6077 -0.7472 -0.2690 +vn -0.2142 -0.0237 -0.9765 +vn -0.4225 0.2302 0.8766 +vn -0.1965 -0.0091 0.9805 +vn -0.0202 -0.9988 -0.0449 +vn -0.0468 0.3977 -0.9163 +vn -0.2678 0.4564 -0.8485 +vn -0.4411 0.2066 0.8733 +vn -0.4411 0.2066 0.8734 +vn 0.1660 -0.9614 -0.2195 +vn 0.1179 0.9874 0.1051 +vn -0.1006 -0.6499 0.7533 +vn -0.1926 -0.7653 0.6142 +vn 0.0834 0.0145 -0.9964 +vn 0.2431 -0.0076 -0.9700 +vn -0.0815 0.2008 -0.9762 +vn -0.0830 0.2750 -0.9578 +vn 0.1028 0.4075 -0.9074 +vn -0.6650 -0.6032 0.4404 +vn 0.0924 0.8678 0.4883 +vn -0.7791 -0.2045 0.5926 +vn -0.9667 -0.1630 0.1973 +vn -0.0414 -0.5681 0.8219 +vn -0.0706 -0.9786 -0.1935 +vn 0.2665 -0.7107 0.6511 +vn -0.1777 -0.9826 -0.0543 +vn -0.1601 -0.9799 -0.1192 +vn 0.1179 0.9862 0.1165 +vn -0.5893 -0.1214 -0.7988 +vn -0.5893 -0.1214 -0.7987 +vn -0.2731 -0.1499 0.9502 +vn 0.1418 -0.4895 0.8604 +vn 0.0912 0.7194 0.6886 +vn 0.0076 0.7033 0.7108 +vn 0.0331 0.1020 -0.9942 +vn 0.5910 0.1005 0.8004 +vn -0.1681 0.6685 0.7245 +vn -0.1966 0.5780 0.7920 +vn -0.1918 0.6979 0.6900 +vn 0.4166 -0.0753 0.9060 +vn -0.9434 -0.1653 0.2875 +vn -0.0732 0.0549 -0.9958 +vn -0.5893 0.1214 -0.7988 +vn 0.9710 -0.0897 -0.2218 +vn 0.8551 -0.0405 -0.5169 +vn -0.6076 0.7263 0.3214 +vn 0.5841 0.5840 -0.5638 +vn -0.5616 -0.2714 0.7816 +vn -0.7684 -0.2370 0.5945 +vn -0.5924 -0.2710 0.7587 +vn 0.4411 -0.2066 -0.8733 +vn 0.3694 0.7339 -0.5700 +vn 0.6955 0.6547 -0.2961 +vn 0.5784 0.6917 -0.4324 +vn 0.0337 -0.6193 -0.7845 +vn 0.9657 -0.0714 0.2495 +vn 0.9919 -0.1252 0.0203 +vn 0.9605 -0.1764 -0.2154 +vn 0.0186 -0.1887 -0.9819 +vn -0.1492 -0.2079 -0.9667 +vn 0.1766 -0.4308 -0.8850 +vn -0.1193 -0.7666 -0.6309 +vn 0.1132 0.1619 0.9803 +vn -0.5255 -0.7545 -0.3931 +vn -0.6225 -0.6229 -0.4738 +vn 0.0574 -0.6098 0.7905 +vn 0.0651 -0.7537 -0.6540 +vn 0.1926 0.8290 0.5250 +vn 0.3714 0.7799 0.5039 +vn -0.6567 -0.6445 0.3916 +vn -0.7466 -0.6489 0.1467 +vn 0.4161 0.0266 -0.9089 +vn -0.2157 0.6990 -0.6818 +vn -0.1531 0.7098 -0.6876 +vn 0.4527 0.0512 -0.8902 +vn 0.2552 0.4990 -0.8282 +vn 0.0309 0.6566 0.7536 +vn 0.5253 -0.8321 -0.1779 +vn -0.7399 0.4620 -0.4890 +vn -0.7451 0.6138 0.2609 +vn -0.7468 0.6650 0.0010 +vn 0.4437 -0.0799 0.8926 +vn 0.0422 -0.7213 -0.6913 +vn 0.4411 0.2066 -0.8733 +vn -0.6175 -0.6111 0.4953 +vn -0.4926 -0.1878 -0.8497 +vn -0.5769 0.1075 -0.8097 +vn -0.1651 -0.6254 -0.7627 +vn 0.3819 -0.6956 0.6085 +vn 0.8194 0.1705 0.5473 +vn 0.8309 0.1715 0.5293 +vn 0.9430 0.1792 0.2804 +vn 0.7434 0.5745 -0.3425 +vn 0.7313 0.5859 -0.3492 +vn 0.2546 0.1938 -0.9474 +vn 0.2316 0.6422 0.7307 +vn -0.9434 0.1653 0.2875 +vn -0.3680 0.9096 -0.1931 +vn 0.0456 0.7069 -0.7059 +vn -0.1101 0.6976 -0.7080 +vn 0.0456 0.7053 -0.7075 +vn 0.7037 -0.1096 -0.7020 +vn 0.3946 0.9109 -0.1206 +vn 0.3339 -0.7406 -0.5831 +vn 0.4640 -0.7564 -0.4611 +vn 0.1045 0.5997 0.7933 +vn 0.7103 0.1956 0.6762 +vn 0.7131 0.3038 0.6318 +vn 0.7102 0.3099 0.6321 +vn 0.2373 0.9116 -0.3356 +vn -0.1195 -0.7275 0.6756 +vn -0.9667 0.1630 0.1974 +vn 0.7115 0.4164 0.5661 +vn 0.9708 0.1032 -0.2164 +vn 0.1390 0.8251 -0.5476 +vn 0.1203 0.9721 -0.2016 +vn -0.0724 -0.7488 0.6589 +vn -0.2633 -0.7591 0.5953 +vn -0.2252 -0.8423 0.4897 +vn -0.7279 0.0919 -0.6795 +vn -0.7279 0.0918 -0.6795 +vn 0.7093 0.5587 0.4299 +vn 0.7092 -0.1341 0.6922 +vn 0.7092 -0.1341 0.6921 +vn 0.7092 -0.1342 0.6922 +vn 0.0597 0.6144 -0.7867 +vn 0.1048 0.4698 -0.8765 +vn -0.1922 0.6861 -0.7016 +vn -0.1140 0.6981 -0.7069 +vn 0.8556 0.1236 0.5026 +vn 0.9632 0.1593 0.2166 +vn 0.1175 -0.9423 -0.3136 +vn 0.1361 -0.9377 -0.3196 +vn -0.4027 0.1088 -0.9088 +vn -0.0009 0.0827 0.9966 +vn -0.0029 0.0620 0.9981 +vn -0.9653 -0.0882 0.2457 +vn -0.1818 0.9833 -0.0034 +vn 0.9410 -0.1134 0.3187 +vn -0.6064 -0.6909 0.3936 +vn -0.5951 -0.7129 0.3710 +vn -0.2159 0.1899 0.9578 +vn -0.4847 -0.8577 -0.1713 +vn -0.7063 -0.6935 0.1424 +vn -0.1726 -0.0643 -0.9829 +vn -0.6929 0.4223 -0.5844 +vn -0.9649 -0.0618 0.2553 +vn -0.8945 -0.0434 0.4450 +vn -0.9972 -0.0737 0.0146 +vn -0.3928 -0.8795 0.2687 +vn -0.0623 0.6471 -0.7598 +vn -0.2028 0.6015 -0.7727 +vn -0.2156 0.6503 -0.7284 +vn 0.1097 -0.6158 -0.7802 +vn -0.3221 -0.9069 -0.2715 +vn 0.1732 0.2174 -0.9606 +vn 0.1806 0.2326 -0.9557 +vn -0.9523 0.1265 0.2778 +vn 0.0009 -0.9970 -0.0778 +vn 0.0810 0.9755 0.2046 +vn 0.6645 -0.7473 -0.0031 +vn 0.0354 0.3302 0.9433 +vn 0.6027 0.7780 0.1775 +vn 0.2985 0.8560 0.4221 +vn 0.0898 0.6767 0.7308 +vn -0.1661 0.7547 0.6347 +vn -0.1860 0.7542 0.6297 +vn -0.0456 0.6319 0.7737 +vn 0.0505 0.8744 -0.4826 +vn -0.2721 -0.2846 0.9192 +vn 0.9873 0.1559 -0.0294 +vn 0.9268 0.2142 -0.3084 +vn 0.2635 -0.8925 0.3661 +vn -0.0485 0.8900 -0.4534 +vn 0.0441 0.4582 -0.8878 +vn -0.0545 -0.1557 -0.9863 +vn 0.6713 -0.6739 -0.3085 +vn 0.6416 -0.7357 -0.2170 +vn -0.2860 -0.5109 -0.8107 +vn 0.5862 -0.0099 0.8101 +vn -0.0758 0.6975 0.7126 +vn -0.0287 0.7526 0.6578 +vn 0.4527 -0.0512 -0.8902 +vn 0.5051 -0.7422 -0.4405 +vn 0.2431 0.0076 -0.9700 +vn 0.0294 0.1358 -0.9903 +vn 0.0727 0.7340 0.6752 +vn 0.0523 0.7487 0.6608 +vn -0.0023 0.0577 0.9983 +vn -0.8911 -0.3988 0.2165 +vn -0.0175 0.7002 -0.7137 +vn -0.0588 0.8284 -0.5571 +vn -0.3809 0.5906 0.7114 +vn 0.1179 -0.9862 0.1165 +vn -0.0053 0.2724 -0.9622 +vn 0.0179 0.0815 0.9965 +vn -0.3280 -0.6208 -0.7121 +vn 0.4912 0.1881 0.8505 +vn 0.7564 0.1118 0.6445 +vn 0.2638 0.0276 -0.9642 +vn 0.6737 -0.0342 0.7382 +vn 0.4088 -0.0983 0.9073 +vn 0.0728 0.9634 0.2580 +vn 0.4648 -0.3378 -0.8185 +vn -0.8945 0.3062 -0.3258 +vn 0.2285 0.0564 0.9719 +vn 0.7074 -0.6238 0.3325 +vn -0.7982 0.5547 0.2348 +vn -0.1794 0.9837 0.0141 +vn -0.0261 0.9989 0.0395 +vn 0.0025 0.9992 0.0398 +vn 0.0622 0.9966 0.0547 +vn 0.4834 -0.8235 0.2969 +vn 0.4413 0.7813 -0.4414 +vn -0.9618 -0.0841 0.2606 +vn 0.0117 -0.3804 0.9248 +vn -0.7468 -0.6650 0.0010 +vn -0.7092 -0.1341 -0.6922 +vn 0.0317 0.5603 -0.8277 +vn 0.0144 0.5138 -0.8578 +vn -0.0314 -0.1948 0.9803 +vn -0.2431 -0.0076 0.9700 +vn -0.0065 -0.0434 0.9990 +vn -0.0064 -0.0434 0.9990 +vn 0.6808 -0.0053 -0.7325 +vn 0.4190 -0.0604 -0.9060 +vn -0.5618 -0.8195 0.1128 +vn -0.3583 -0.8672 0.3457 +vn -0.9857 0.1560 0.0639 +vn 0.5095 0.6280 -0.5883 +vn 0.8508 0.4738 0.2271 +vn 0.7173 0.4913 -0.4940 +vn -0.4929 -0.8068 0.3258 +vn -0.5322 -0.7781 0.3338 +vn -0.5479 -0.8338 0.0681 +vn 0.1245 0.6305 0.7661 +vn -0.0322 -0.8682 -0.4951 +vn -0.4800 -0.7132 -0.5109 +vn -0.3745 -0.6656 -0.6455 +vn 0.7005 0.0289 0.7131 +vn 0.0355 0.1202 -0.9921 +vn 0.1070 -0.9898 0.0937 +vn -0.4527 -0.0512 0.8902 +vn 1.0000 -0.0003 0.0000 +vn -0.3621 0.1536 -0.9194 +vn -1.0000 -0.0001 0.0000 +vn 0.5413 0.8407 -0.0159 +vn 0.5055 0.8300 -0.2359 +vn -1.0000 -0.0009 0.0000 +vn 0.3791 -0.6319 0.6760 +vn -0.1666 0.5029 -0.8482 +vn 0.5391 -0.1621 0.8265 +vn -0.1104 -0.6804 0.7245 +vn 0.7493 0.1180 0.6517 +vn -0.9890 0.1424 0.0401 +vn 0.0579 0.4849 -0.8727 +vn -0.7944 -0.2098 -0.5701 +vn -0.8033 -0.1306 -0.5811 +vn 0.7019 -0.2078 -0.6813 +vn 0.2316 -0.6422 0.7307 +vn 0.4781 0.6913 0.5417 +vn 0.4768 0.6937 0.5398 +vn 0.7077 0.1340 -0.6937 +vn -0.5281 0.2746 0.8036 +vn -0.4553 -0.7138 -0.5321 +vn 0.7106 0.4244 0.5612 +vn 0.7121 0.4706 0.5210 +vn 0.7228 0.6256 -0.2935 +vn 0.6999 0.6717 -0.2428 +vn 0.0455 0.8518 0.5218 +vn 0.1487 -0.2322 0.9612 +vn 0.0915 -0.9919 0.0882 +vn 0.3715 0.7111 -0.5970 +vn 0.1607 -0.1998 0.9666 +vn 0.7047 0.4415 -0.5554 +vn 0.6632 0.5091 -0.5486 +vn 0.7182 0.4026 -0.5675 +vn 0.6980 0.4972 -0.5153 +vn 0.0042 0.9817 -0.1904 +vn 0.4822 -0.6026 0.6358 +vn 0.8033 0.2001 -0.5609 +vn -0.3159 -0.2048 0.9264 +vn 0.5274 -0.6239 -0.5767 +vn 0.5708 -0.1029 0.8146 +vn -0.5707 0.1029 -0.8147 +vn 0.0520 0.7529 0.6561 +vn -0.1115 -0.9809 0.1595 +vn 0.2120 0.7168 -0.6642 +vn -0.1787 -0.2107 0.9611 +vn -0.4307 -0.2358 0.8711 +vn -0.2486 -0.6533 0.7151 +vn -0.0241 0.5296 0.8479 +vn 0.0058 0.6347 0.7728 +vn 0.0904 0.4878 0.8683 +vn -0.0296 0.7589 0.6506 +vn -0.0228 0.7649 0.6437 +vn -0.0228 0.7648 0.6439 +vn 0.6978 -0.6983 -0.1599 +vn 0.7167 -0.6912 -0.0931 +vn 0.6970 -0.6920 -0.1880 +vn 0.0668 0.5930 0.8024 +vn -0.0162 0.7546 0.6560 +vn -0.0229 0.8130 0.5818 +vn -0.2399 -0.2596 0.9354 +vn -0.1598 0.5670 0.8081 +vn -0.3232 0.7789 0.5375 +vn -0.3173 0.7133 0.6249 +vn 0.0501 0.9761 -0.2116 +vn 0.0530 0.9155 -0.3988 +vn 0.0416 -0.6573 0.7525 +vn -0.0194 -0.7883 0.6150 +vn -0.6885 0.5742 -0.4430 +vn 0.7081 0.6881 -0.1583 +vn 0.4639 0.6073 0.6449 +vn 0.2925 0.7713 0.5653 +vn -0.0273 -0.8019 0.5968 +vn 0.0912 -0.5735 0.8141 +vn 0.2318 0.6656 -0.7094 +vn 0.0941 -0.7267 0.6805 +vn 0.0883 -0.6594 0.7466 +vn 0.0954 -0.7299 0.6768 +vn -0.3956 0.6077 0.6886 +vn -0.5825 0.6513 0.4863 +vn 0.1606 0.3333 -0.9290 +vn 0.1051 -0.7088 0.6975 +vn 0.0806 -0.6081 0.7898 +vn 0.0829 -0.5835 0.8078 +vn 0.0171 -0.5386 0.8424 +vn -0.2459 -0.2471 -0.9373 +vn 0.7280 -0.0246 0.6851 +vn -0.9926 0.1137 -0.0420 +vn 0.7697 0.0670 0.6348 +vn -0.1531 0.9092 -0.3872 +vn -0.3035 -0.6440 0.7022 +vn 0.0579 -0.4848 -0.8727 +vn -0.0068 0.1828 -0.9831 +vn -0.1179 0.1900 -0.9747 +vn 0.1963 0.6217 0.7583 +vn 0.3324 0.7271 0.6007 +vn 0.1436 0.6859 0.7134 +vn 0.5221 0.7147 0.4654 +vn 0.4834 0.7437 0.4618 +vn -0.8697 0.4877 -0.0758 +vn -0.5161 -0.1263 -0.8472 +vn 0.5086 -0.8021 0.3130 +vn 0.3583 -0.2249 0.9061 +vn 0.2518 -0.1002 -0.9626 +vn 0.1794 0.7127 -0.6781 +vn -0.6616 0.7387 -0.1289 +vn -0.2721 0.7808 -0.5624 +vn 0.0790 0.7499 0.6569 +vn -0.1422 0.9828 -0.1178 +vn -0.1615 0.9765 -0.1428 +vn -0.2846 0.1693 -0.9436 +vn -0.4679 0.5923 -0.6559 +vn 0.5966 0.6857 -0.4170 +vn 0.5448 -0.8326 0.1001 +vn 0.5483 -0.0672 0.8336 +vn 0.4609 -0.4850 -0.7432 +vn -0.6077 0.0850 -0.7896 +vn -0.1709 0.7040 -0.6893 +vn -0.8908 0.0615 -0.4503 +vn -0.8571 0.1463 -0.4939 +vn -0.9869 -0.1299 -0.0961 +vn -0.9297 -0.1570 -0.3331 +vn -0.9770 -0.1012 0.1876 +vn -0.9894 -0.1395 0.0398 +vn -0.9894 -0.1394 0.0398 +vn -0.3528 -0.8038 -0.4790 +vn -0.8187 0.5460 0.1777 +vn 0.7933 -0.2302 -0.5636 +vn 0.2265 0.8266 0.5153 +vn -0.0326 0.8376 0.5453 +vn 0.0038 -0.9954 -0.0954 +vn 0.1916 0.7534 -0.6290 +vn 0.0975 -0.4009 0.9109 +vn 0.4258 0.8530 -0.3017 +vn 0.5165 0.4453 -0.7314 +vn -0.0563 -0.0578 0.9967 +vn 0.3819 0.6956 0.6086 +vn -0.5757 -0.7381 -0.3517 +vn 0.9667 0.1630 -0.1974 +vn 0.7353 -0.6192 -0.2756 +vn 0.8019 -0.5968 0.0281 +vn 0.8020 -0.5963 0.0355 +vn 0.1441 -0.9886 0.0439 +vn -0.1941 0.2834 0.9392 +vn 0.1205 0.4524 -0.8836 +vn -0.0190 -0.2029 -0.9790 +vn -0.2338 0.5947 -0.7692 +vn -0.2721 0.8008 -0.5336 +vn 0.9488 0.1500 0.2781 +vn 0.9905 0.1376 -0.0038 +vn -0.7402 0.6668 0.0864 +vn -0.7343 0.5415 0.4093 +vn 0.4167 0.2487 -0.8743 +vn 0.2451 0.8086 0.5349 +vn 0.9918 -0.1108 -0.0637 +vn 0.5952 -0.5660 -0.5704 +vn 0.7434 -0.5745 -0.3425 +vn 0.7313 -0.5859 -0.3492 +vn 0.7276 -0.6849 -0.0395 +vn 0.7510 -0.6590 -0.0412 +vn 0.6081 -0.7828 0.1321 +vn -0.1975 0.7445 -0.6378 +vn 0.8561 0.0012 0.5168 +vn 0.9549 -0.0726 0.2880 +vn 0.2178 -0.0092 0.9759 +vn 0.1279 0.0105 0.9917 +vn 0.8088 -0.5867 0.0401 +vn 0.9359 -0.3018 -0.1818 +vn -0.9352 -0.2040 -0.2895 +vn 0.8092 0.1366 0.5714 +vn -0.1301 -0.9683 0.2135 +vn 0.1131 -0.9912 -0.0684 +vn -0.8569 -0.0402 0.5139 +vn 0.3552 -0.0043 -0.9348 +vn -0.0460 0.6328 -0.7730 +vn -0.4487 -0.1503 -0.8809 +vn 0.0414 -0.9565 -0.2888 +vn 0.5542 -0.7962 -0.2428 +vn -0.4515 0.7389 -0.5001 +vn 0.6905 -0.3004 -0.6580 +vn -0.6772 -0.7322 0.0727 +vn -0.0110 0.9997 -0.0218 +vn 0.5170 0.0070 0.8560 +vn 0.0026 0.2630 -0.9648 +vn -0.4909 0.8706 0.0324 +vn 0.9680 -0.1577 -0.1950 +vn 0.9861 -0.1457 -0.0794 +vn 0.1311 0.9775 -0.1651 +vn 0.0323 -0.3062 0.9514 +vn -0.5893 0.1214 -0.7987 +vn -0.2436 0.2443 -0.9386 +vn -0.4319 0.2101 -0.8771 +vn 0.0943 0.7049 -0.7031 +vn 0.0335 0.7197 -0.6935 +vn 0.0840 0.7052 -0.7040 +vn 0.1407 -0.8398 0.5243 +vn 1.0000 -0.0002 0.0000 +vn 0.9434 0.1653 -0.2875 +vn 0.0573 0.9980 0.0270 +vn 0.0279 0.9991 0.0326 +vn 0.0415 0.5321 -0.8457 +vn 0.0418 0.5342 -0.8443 +vn 0.0889 0.7056 -0.7030 +vn 0.7038 0.1371 0.6971 +vn 0.2978 0.7286 -0.6169 +vn -0.0171 0.6821 0.7311 +vn -0.0322 0.7591 0.6502 +vn 0.9565 0.1442 0.2535 +vn 0.9747 0.1287 0.1826 +vn 0.0971 -0.9946 -0.0362 +vn -0.1715 -0.4736 0.8639 +vn -0.8979 0.1920 0.3961 +vn 0.9909 -0.1193 0.0622 +vn -0.5423 0.6950 -0.4721 +vn 0.9600 -0.0767 0.2693 +vn 0.9755 -0.0976 0.1972 +vn -0.3602 0.6350 -0.6834 +vn 0.5246 -0.8326 0.1776 +vn -0.7364 0.2877 -0.6123 +vn -0.8680 -0.0226 -0.4961 +vn -0.2748 -0.8203 0.5015 +vn -0.5483 0.0671 -0.8336 +vn -0.0216 0.6398 -0.7683 +vn -0.1015 0.9888 -0.1093 +vn 0.0631 0.8919 0.4478 +vn -0.9734 0.1449 0.1772 +vn -0.9250 0.2096 0.3169 +vn 0.0113 0.0351 0.9993 +vn -0.0081 0.0173 0.9998 +vn 0.0107 0.0346 0.9993 +vn 0.7068 -0.2276 -0.6698 +vn -0.0771 -0.9682 -0.2379 +vn -0.7321 0.6662 -0.1419 +vn -0.6772 0.7322 0.0727 +vn 0.5437 -0.0855 0.8349 +vn 0.7100 -0.5952 0.3763 +vn -0.1423 -0.9804 -0.1359 +vn -0.9918 -0.1108 0.0637 +vn 0.7181 0.0740 -0.6920 +vn -0.2559 0.9083 0.3308 +vn 0.0465 0.9881 0.1464 +vn 0.1784 -0.7704 -0.6121 +vn -0.6950 -0.1657 -0.6997 +vn -0.0463 0.9654 0.2565 +vn -0.2585 -0.1264 -0.9577 +vn 0.8429 0.0054 0.5380 +vn 0.9733 -0.0836 0.2139 +vn -0.9540 0.0592 0.2941 +vn -0.9540 0.0592 0.2940 +vn 0.1859 -0.0070 0.9825 +vn 0.4283 0.6783 -0.5971 +vn 0.0828 0.9702 0.2276 +vn 0.0827 0.9701 0.2281 +vn -0.6392 0.6824 0.3547 +vn -0.6749 0.2596 0.6907 +vn 0.0983 -0.8568 0.5063 +vn -0.0953 -0.9933 0.0659 +vn 0.7082 -0.7060 -0.0037 +vn 0.6657 0.7244 0.1790 +vn 0.0532 0.9243 0.3779 +vn 0.0639 0.8003 0.5962 +vn 0.8559 0.0796 -0.5110 +vn 0.6351 0.6806 0.3654 +vn -0.9953 -0.0943 0.0206 +vn -0.7482 0.6595 0.0722 +vn -0.0136 -0.1858 -0.9825 +vn -0.8361 -0.5357 0.1182 +vn -0.0623 -0.6471 -0.7598 +vn 0.0677 -0.6492 0.7576 +vn -0.1172 -0.0187 -0.9929 +vn 0.0422 0.7079 -0.7051 +vn -0.6342 0.0843 -0.7686 +vn -0.4302 0.7084 -0.5595 +vn 0.9555 -0.1558 -0.2503 +vn -0.3065 0.1216 -0.9441 +vn 0.7641 0.0262 -0.6446 +vn -0.5610 -0.6183 -0.5504 +vn -0.5764 -0.5799 -0.5757 +vn 0.4527 -0.0511 -0.8902 +vn -0.0416 -0.9400 0.3387 +vn 0.3837 -0.7779 0.4976 +vn -0.0060 0.1888 -0.9820 +vn 0.8694 0.0327 0.4930 +vn -0.0765 -0.7288 0.6805 +vn -0.6567 0.6445 0.3916 +vn -0.9868 0.1422 -0.0776 +vn -0.0712 0.9971 0.0268 +vn -0.0781 0.9969 0.0132 +vn 0.2514 0.7237 -0.6427 +vn 0.1068 0.6394 -0.7614 +vn 0.1242 0.6854 -0.7175 +vn -0.7736 -0.5623 0.2921 +vn -0.3983 0.1544 -0.9042 +vn -0.9772 0.1617 0.1380 +vn 0.1784 0.7704 -0.6121 +vn 0.8518 0.1502 0.5019 +vn 0.8560 -0.1935 -0.4793 +vn 0.8322 -0.2411 -0.4993 +vn 0.8008 -0.5896 0.1056 +vn -0.1835 0.8141 -0.5509 +vn -0.2298 0.7596 -0.6085 +vn 0.0100 -0.0133 0.9999 +vn -0.4411 0.2065 0.8734 +vn -0.4475 -0.7918 0.4156 +vn 0.5391 0.1621 0.8265 +vn 0.0570 0.6254 -0.7782 +vn -0.1807 0.9829 0.0350 +vn -0.3621 -0.1536 -0.9194 +vn -0.3983 -0.1544 -0.9042 +vn -0.0151 0.6485 0.7611 +vn -0.7764 -0.5759 0.2562 +vn -0.1301 0.9683 0.2134 +vn -0.3954 0.9108 0.1190 +vn -0.2068 0.2528 -0.9452 +vn 0.3287 0.7156 0.6164 +vn -0.0574 0.9946 -0.0861 +vn 0.6093 -0.3736 0.6994 +vn -0.3731 0.0481 0.9265 +vn 0.0230 0.0111 -0.9997 +vn 0.3715 -0.7111 -0.5970 +vn 0.0402 -0.8809 0.4716 +vn -0.1104 -0.9651 0.2377 +vn 0.1653 -0.5942 0.7872 +vn -0.1803 -0.0154 -0.9835 +vn -0.3108 -0.8272 0.4681 +vn 0.1117 -0.9930 0.0391 +vn 0.1117 -0.9930 0.0378 +vn 0.7615 -0.0093 -0.6481 +vn 0.4283 -0.6783 -0.5971 +vn 0.1941 0.2834 -0.9392 +vn 0.0774 -0.6076 -0.7904 +vn 0.5595 -0.8189 -0.1277 +vn -0.7763 0.5759 0.2562 +vn -0.4444 0.8538 0.2712 +vn -0.8811 0.0414 -0.4711 +vn -0.9647 0.0015 -0.2632 +vn -0.9979 -0.0438 -0.0488 +vn 0.7128 -0.6697 -0.2083 +vn -0.0776 0.9956 -0.0515 +vn 0.4074 0.2016 -0.8907 +vn 0.2668 -0.0819 -0.9603 +vn 0.4879 -0.0448 -0.8718 +vn -0.9977 0.0017 0.0675 +vn -0.9958 -0.0151 0.0904 +vn 0.1151 0.8999 -0.4207 +vn 0.0936 -0.9907 0.0988 +vn 0.9638 0.1461 -0.2232 +vn 0.0700 0.0105 -0.9975 +vn -0.8733 -0.0309 -0.4862 +vn 0.3171 0.8790 -0.3560 +vn 0.7523 -0.6026 0.2664 +vn -0.1812 -0.9741 -0.1355 +vn -0.1107 -0.9884 -0.1045 +vn 0.7309 0.6816 -0.0347 +vn 0.4167 0.2488 -0.8743 +vn -0.0432 0.0138 0.9990 +vn -0.7100 -0.6658 -0.2294 +vn 0.5156 -0.8111 0.2762 +vn 0.9742 0.0590 0.2178 +vn -0.8324 -0.5519 -0.0502 +vn 0.9661 0.1461 -0.2127 +vn 0.5391 -0.1620 0.8265 +vn -0.5710 -0.8048 -0.1623 +vn 0.0441 0.9784 0.2020 +vn -0.4096 0.5438 0.7325 +vn 1.0000 -0.0009 0.0000 +vn -0.4411 -0.2066 0.8734 +vn 0.5538 -0.7145 0.4275 +vn 0.0217 0.0047 -0.9998 +vn 0.5156 0.8111 0.2762 +vn -0.7493 -0.1181 -0.6516 +vn -0.0310 -0.9970 -0.0712 +vn 0.0166 0.7145 -0.6995 +vn -0.0369 0.6801 -0.7322 +vn 0.1214 0.7958 -0.5932 +vn -0.0179 0.8066 -0.5909 +vn 0.9773 0.0273 0.2102 +vn 0.7123 -0.1534 0.6849 +vn 0.7047 -0.1438 0.6947 +vn -0.2258 0.5181 0.8250 +vn -0.9649 0.0617 0.2553 +vn 0.7051 0.1891 -0.6835 +vn -0.9936 -0.1123 -0.0141 +vn 0.9523 -0.1265 -0.2778 +vn 0.8399 0.0379 0.5414 +vn -0.7267 -0.4297 -0.5359 +vn 0.7092 0.1341 0.6921 +vn -0.4167 -0.2487 0.8743 +vn 0.1616 -0.1449 -0.9762 +vn -0.7812 -0.6059 -0.1504 +vn -0.7321 -0.6662 -0.1419 +vn -0.2307 -0.4281 0.8738 +vn 0.6091 -0.7759 0.1643 +vn 0.0617 0.9924 -0.1061 +vn -0.9721 -0.0539 -0.2281 +vn -0.9632 0.0031 -0.2688 +vn -0.9888 0.0641 0.1348 +vn 1.0000 0.0004 0.0000 +vn 0.1301 0.9683 -0.2135 +vn 0.5054 -0.4284 -0.7490 +vn 0.8320 -0.5495 -0.0765 +vn 0.9638 -0.1559 0.2162 +vn -0.8348 0.0367 -0.5494 +vn 0.5483 -0.0671 0.8336 +vn -0.9849 -0.0360 -0.1693 +vn 0.9152 -0.1274 -0.3824 +vn -0.4048 0.0752 -0.9113 +vn 0.4411 0.2066 -0.8734 +vn -0.0264 0.9954 0.0922 +vn 0.2261 0.0327 -0.9736 +vn -0.0628 -0.9975 0.0327 +vn -0.0540 -0.9975 0.0444 +vn 0.0505 -0.6125 -0.7888 +vn 0.7317 -0.0009 0.6817 +vn -0.0827 -0.7826 0.6169 +vn 0.1906 -0.6253 -0.7567 +vn -0.9945 0.1040 0.0148 +vn 0.1767 -0.8566 0.4848 +vn 0.4472 0.6691 -0.5935 +vn -0.9013 -0.1554 -0.4042 +vn -0.2823 -0.2382 -0.9293 +vn -0.6693 -0.6559 -0.3490 +vn 0.8109 -0.0378 -0.5839 +vn 0.7127 0.7003 0.0409 +vn -0.0010 -0.7678 0.6406 +vn 0.0961 -0.7682 0.6329 +vn -0.0412 0.9947 -0.0939 +vn -0.0221 0.9978 -0.0630 +vn -0.1257 -0.5215 0.8439 +vn 0.9540 -0.0591 -0.2940 +vn -0.1073 0.7001 0.7059 +vn 0.9156 -0.1718 -0.3636 +vn -0.0914 -0.8317 -0.5476 +vn 0.1144 -0.9933 -0.0128 +vn 1.0000 -0.0008 0.0000 +vn -0.1369 -0.3182 0.9381 +vn -0.4411 -0.2066 0.8733 +vn 0.1062 0.9899 0.0938 +vn -0.9540 -0.0592 0.2941 +vn -0.9540 -0.0592 0.2940 +vn 0.0714 0.6834 -0.7265 +vn -0.1772 -0.9827 -0.0541 +vn -0.5778 -0.6949 -0.4281 +vn 0.1177 0.9862 0.1166 +vn 0.3791 0.6319 0.6760 +vn 0.2295 0.7357 0.6373 +vn -0.9832 -0.1135 0.1432 +vn -0.5285 0.4456 0.7226 +vn 0.0307 0.9993 0.0202 +vn -0.9910 -0.0314 0.1303 +vn -0.9850 -0.0436 0.1670 +vn -0.7766 -0.4293 0.4611 +vn -0.2732 0.8080 -0.5220 +vn 0.7353 0.6192 -0.2756 +vn 0.8020 0.5963 0.0355 +vn 0.8019 0.5968 0.0281 +vn -0.7092 -0.1341 -0.6921 +vn -0.1448 0.7641 -0.6286 +vn 0.5087 -0.7896 0.3431 +vn 0.0611 -0.7978 0.5998 +vn -0.0272 0.9947 -0.0992 +vn 0.6701 -0.2885 -0.6839 +vn -0.7812 0.6059 -0.1504 +vn 0.9230 -0.1503 0.3544 +vn -0.5315 0.8471 0.0045 +vn 0.1133 -0.9910 -0.0714 +vn -0.1527 -0.0576 0.9866 +vn -0.0597 -0.6316 0.7730 +vn 0.7938 -0.6033 -0.0764 +vn -0.1328 0.9832 0.1255 +vn -0.0187 0.9965 -0.0815 +vn -0.0160 0.9960 -0.0881 +vn -0.0984 -0.9511 0.2927 +vn -0.0759 -0.8985 0.4324 +vn -0.9497 0.0895 -0.3002 +vn 0.2029 0.9498 0.2383 +vn -0.5391 -0.1621 -0.8265 +vn -0.2277 -0.6995 -0.6773 +vn 0.0602 -0.3004 -0.9519 +vn 0.0204 0.9997 -0.0131 +vn 0.9875 0.1458 -0.0597 +vn 0.0531 0.6526 0.7559 +vn 0.4900 0.0674 -0.8691 +vn 0.0446 0.9988 0.0216 +vn 0.1079 -0.9933 -0.0412 +vn 0.1927 0.6640 0.7225 +vn 0.1628 0.6644 0.7294 +vn 0.9894 0.1393 -0.0398 +vn -0.0776 -0.9956 -0.0515 +vn 0.1079 -0.9900 0.0908 +vn -0.5483 -0.0672 -0.8336 +vn -0.2267 -0.0569 -0.9723 +vn 0.7093 -0.1966 0.6769 +vn 0.0549 0.9928 -0.1066 +vn 0.0983 0.9917 0.0833 +vn 0.4765 0.2081 -0.8542 +vn 0.0484 -0.6729 0.7382 +vn 0.1214 -0.7958 -0.5932 +vn 0.5916 0.0812 0.8021 +vn 0.4527 0.0511 -0.8902 +vn -0.0225 0.9951 -0.0964 +vn 0.7232 0.3945 -0.5668 +vn 0.1363 0.5402 0.8304 +vn -0.1396 0.9902 -0.0065 +vn -0.5391 0.1621 -0.8265 +vn -0.0446 -0.9948 -0.0919 +vn 0.0792 0.4064 -0.9102 +vn 0.0936 -0.9951 -0.0317 +vn 0.0929 -0.9951 -0.0328 +vn -0.1273 -0.9895 -0.0691 +vn 0.0960 0.9899 0.1043 +vn 0.1849 -0.9199 0.3457 +vn -0.1300 0.9683 0.2134 +vn -0.5483 -0.0671 -0.8336 +vn 0.2149 0.0040 0.9766 +vn -0.0766 0.0005 -0.9971 +vn -0.1312 -0.0091 -0.9913 +vn 0.6067 -0.0455 0.7936 +vn -0.0975 0.9923 -0.0767 +vn 0.7285 -0.6831 -0.0514 +vn 0.7245 -0.6578 -0.2059 +vn -0.0176 0.9965 -0.0822 +vn -0.5390 -0.1621 -0.8265 +vn 0.0560 -0.6141 0.7873 +vn 0.0518 -0.0015 -0.9987 +vn 0.0127 -0.7299 0.6834 +vn 0.7333 -0.6642 -0.1456 +vn 0.0188 0.9997 -0.0123 +vn -0.1150 -0.5487 0.8280 +vn 0.0049 0.0563 0.9984 +vn 0.0191 -0.8875 0.4603 +vn -0.1528 -0.1630 0.9747 +vn 0.5391 0.1620 0.8265 +vn -0.0016 0.9974 -0.0723 +vn -0.9875 -0.1456 0.0598 +vn 0.0847 -0.9960 -0.0275 +vn 0.0402 -0.8809 0.4717 +vn 0.9910 0.1307 0.0298 +vn -0.0732 -0.0549 -0.9958 +vn 0.7071 0.3628 -0.6070 +vn 0.1113 0.0904 0.9897 +vn 0.1317 -0.2179 0.9671 +vn -0.3694 0.5337 -0.7607 +vn 0.5483 0.0671 0.8336 +vn -0.2071 0.1327 -0.9693 +vn -0.4411 -0.2065 0.8734 +vn -0.1981 0.0255 -0.9798 +vn 0.0321 -0.0114 -0.9994 +vn 0.7369 -0.6720 0.0729 +vn -0.2367 0.0522 -0.9702 +vn 0.0917 -0.9953 -0.0312 +vn 0.5204 -0.7247 -0.4516 +vn -0.1475 0.9831 0.1081 +vn -0.2371 0.2087 0.9488 +vn -0.5390 0.1621 -0.8265 +vn 0.8399 -0.0379 0.5414 +vn -0.9904 0.1059 0.0884 +vn 0.1180 0.0107 -0.9930 +vn 0.0602 0.8099 0.5835 +vn 0.4204 0.6068 0.6746 +vn -0.1679 -0.1174 -0.9788 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 1/1/1 4/4/4 2/2/2 +f 1/1/1 5/5/5 4/4/4 +f 6/6/6 7/7/7 8/8/8 +f 8/8/8 7/7/7 9/9/9 +f 9/9/10 10/10/11 8/8/12 +f 8/8/12 10/10/11 11/11/13 +f 11/11/14 10/10/15 12/12/16 +f 11/11/14 12/12/16 13/13/17 +f 13/13/18 12/12/18 14/14/18 +f 13/13/19 14/14/20 15/15/21 +f 14/14/20 16/16/22 15/15/21 +f 15/15/23 16/16/24 17/17/25 +f 15/15/23 17/17/25 18/18/26 +f 18/18/27 17/17/28 19/19/29 +f 19/19/29 17/17/28 20/20/30 +f 19/19/31 20/20/32 6/6/33 +f 6/6/33 20/20/32 7/7/34 +f 3/3/35 14/14/36 12/12/37 +f 3/3/35 12/12/37 1/1/38 +f 1/1/38 12/12/37 10/10/39 +f 10/10/40 9/9/41 1/1/42 +f 1/1/42 9/9/41 5/5/43 +f 5/5/44 9/9/9 7/7/7 +f 5/5/45 7/7/46 4/4/47 +f 4/4/47 7/7/46 20/20/48 +f 4/4/49 20/20/49 17/17/49 +f 4/4/50 17/17/51 2/2/52 +f 2/2/52 17/17/51 16/16/53 +f 16/16/54 14/14/36 2/2/55 +f 2/2/55 14/14/36 3/3/35 +f 6/6/56 21/21/56 19/19/56 +f 19/19/56 21/21/56 22/22/56 +f 8/8/56 23/23/56 6/6/56 +f 8/8/56 24/24/56 23/23/56 +f 11/11/56 25/25/56 24/24/56 +f 11/11/56 24/24/56 8/8/56 +f 19/19/56 26/26/56 18/18/56 +f 19/19/56 22/22/56 26/26/56 +f 6/6/56 23/23/56 21/21/56 +f 15/15/56 27/27/56 13/13/56 +f 13/13/56 27/27/56 28/28/56 +f 13/13/56 29/29/56 11/11/56 +f 11/11/56 29/29/56 25/25/56 +f 13/13/56 28/28/56 29/29/56 +f 18/18/56 26/26/56 15/15/56 +f 15/15/56 26/26/56 27/27/56 +f 30/30/57 31/31/58 32/32/59 +f 32/32/59 31/31/58 33/33/60 +f 32/32/59 33/33/60 34/34/61 +f 35/35/62 34/34/61 36/36/63 +f 35/35/62 36/36/63 37/37/64 +f 37/37/64 36/36/63 38/38/65 +f 39/39/66 40/40/67 41/41/68 +f 32/32/59 34/34/61 35/35/62 +f 37/37/64 38/38/65 42/42/69 +f 42/42/69 38/38/65 43/43/70 +f 44/44/71 45/45/72 46/46/73 +f 39/39/66 47/47/74 40/40/67 +f 41/41/68 40/40/67 48/48/75 +f 30/30/57 48/48/75 31/31/58 +f 46/46/73 49/49/76 39/39/66 +f 39/39/66 49/49/76 47/47/74 +f 41/41/68 48/48/75 30/30/57 +f 46/46/73 45/45/72 49/49/76 +f 42/42/69 43/43/70 44/44/71 +f 44/44/71 43/43/70 45/45/72 +f 25/25/77 46/46/77 24/24/77 +f 24/24/78 46/46/78 39/39/78 +f 24/24/79 39/39/79 23/23/79 +f 23/23/80 39/39/81 41/41/82 +f 23/23/80 41/41/82 21/21/83 +f 21/21/84 41/41/84 22/22/84 +f 22/22/85 41/41/85 30/30/85 +f 22/22/86 30/30/86 26/26/86 +f 26/26/87 30/30/87 32/32/87 +f 26/26/88 32/32/88 27/27/88 +f 27/27/89 32/32/89 35/35/89 +f 27/27/90 35/35/90 28/28/90 +f 28/28/91 35/35/92 37/37/93 +f 28/28/91 37/37/93 42/42/94 +f 28/28/91 42/42/94 29/29/95 +f 29/29/96 42/42/96 44/44/96 +f 29/29/97 44/44/97 25/25/97 +f 25/25/98 44/44/98 46/46/98 +f 50/50/99 51/51/100 52/52/101 +f 50/50/99 52/52/101 53/53/102 +f 54/54/103 51/51/100 50/50/99 +f 55/55/104 56/56/105 57/57/106 +f 56/56/105 58/58/107 59/59/108 +f 54/54/103 60/60/109 61/61/110 +f 55/55/104 61/61/110 60/60/109 +f 58/58/107 62/62/111 59/59/108 +f 63/63/112 62/62/111 58/58/107 +f 56/56/105 59/59/108 57/57/106 +f 61/61/110 51/51/100 54/54/103 +f 55/55/104 57/57/106 61/61/110 +f 50/50/99 53/53/102 63/63/112 +f 63/63/112 53/53/102 62/62/111 +f 61/61/113 64/64/114 51/51/115 +f 62/62/116 65/65/117 59/59/118 +f 57/57/119 66/66/120 61/61/113 +f 53/53/121 67/67/122 62/62/116 +f 62/62/116 68/68/123 65/65/117 +f 61/61/113 69/69/124 64/64/114 +f 51/51/115 70/70/125 52/52/126 +f 52/52/126 70/70/125 71/71/127 +f 52/52/126 71/71/127 53/53/121 +f 71/71/127 72/72/128 53/53/121 +f 53/53/121 72/72/128 67/67/122 +f 67/67/122 68/68/123 62/62/116 +f 59/59/118 73/73/129 74/74/130 +f 59/59/118 74/74/130 57/57/119 +f 61/61/113 66/66/120 69/69/124 +f 74/74/130 75/75/131 57/57/119 +f 57/57/119 75/75/131 66/66/120 +f 64/64/114 76/76/132 51/51/115 +f 51/51/115 76/76/132 70/70/125 +f 65/65/117 77/77/133 59/59/118 +f 59/59/118 77/77/133 73/73/129 +f 67/67/122 49/49/134 68/68/123 +f 70/70/125 40/40/135 71/71/127 +f 72/72/128 49/49/134 67/67/122 +f 77/77/133 43/43/136 73/73/129 +f 73/73/129 38/38/137 74/74/130 +f 74/74/130 36/36/138 75/75/131 +f 75/75/131 34/34/139 66/66/120 +f 66/66/120 34/34/139 33/33/140 +f 66/66/120 33/33/140 69/69/124 +f 69/69/124 33/33/140 31/31/141 +f 69/69/124 31/31/141 64/64/114 +f 64/64/114 31/31/141 48/48/142 +f 64/64/114 48/48/142 76/76/132 +f 71/71/127 47/47/143 72/72/128 +f 49/49/134 45/45/144 68/68/123 +f 68/68/123 45/45/144 65/65/117 +f 65/65/117 45/45/144 77/77/133 +f 73/73/129 43/43/136 38/38/137 +f 76/76/132 40/40/135 70/70/125 +f 72/72/128 47/47/143 49/49/134 +f 77/77/133 45/45/144 43/43/136 +f 74/74/130 38/38/137 36/36/138 +f 36/36/138 34/34/139 75/75/131 +f 76/76/132 48/48/142 40/40/135 +f 71/71/127 40/40/135 47/47/143 +f 78/78/145 79/79/145 80/80/145 +f 80/80/145 79/79/145 81/81/145 +f 80/80/145 81/81/145 82/82/145 +f 82/82/145 81/81/145 83/83/145 +f 60/60/146 78/78/147 80/80/148 +f 80/80/148 55/55/149 60/60/146 +f 60/60/146 54/54/150 78/78/147 +f 78/78/151 54/54/152 79/79/152 +f 79/79/152 54/54/152 50/50/153 +f 79/79/154 63/63/155 81/81/156 +f 79/79/154 50/50/157 63/63/155 +f 81/81/158 63/63/159 83/83/160 +f 63/63/159 58/58/161 83/83/160 +f 83/83/162 58/58/163 82/82/164 +f 82/82/164 58/58/163 56/56/165 +f 82/82/166 55/55/167 80/80/168 +f 82/82/166 56/56/169 55/55/167 +f 84/84/170 85/85/171 86/86/172 +f 86/86/172 85/85/171 87/87/173 +f 86/86/174 87/87/175 88/88/176 +f 88/88/176 87/87/175 89/89/177 +f 88/88/178 89/89/179 90/90/180 +f 88/88/178 90/90/180 91/91/181 +f 91/91/182 90/90/183 92/92/184 +f 91/91/182 92/92/184 93/93/185 +f 93/93/186 92/92/186 94/94/186 +f 93/93/187 94/94/187 95/95/187 +f 95/95/188 94/94/188 96/96/188 +f 95/95/189 96/96/189 97/97/189 +f 97/97/190 96/96/190 98/98/190 +f 97/97/191 98/98/191 99/99/191 +f 99/99/192 98/98/192 100/100/192 +f 99/99/193 100/100/193 101/101/193 +f 101/101/194 100/100/194 102/102/194 +f 101/101/195 102/102/195 84/84/195 +f 84/84/196 102/102/196 85/85/196 +f 103/103/56 96/96/56 104/104/56 +f 103/103/56 98/98/56 96/96/56 +f 105/105/56 100/100/56 98/98/56 +f 105/105/56 98/98/56 103/103/56 +f 104/104/56 94/94/56 106/106/56 +f 106/106/56 90/90/56 107/107/56 +f 96/96/56 94/94/56 104/104/56 +f 108/108/56 87/87/56 85/85/56 +f 107/107/56 89/89/56 87/87/56 +f 106/106/56 92/92/56 90/90/56 +f 106/106/56 94/94/56 92/92/56 +f 109/109/56 102/102/56 100/100/56 +f 109/109/56 100/100/56 105/105/56 +f 107/107/56 87/87/56 108/108/56 +f 107/107/56 90/90/56 89/89/56 +f 108/108/56 85/85/56 109/109/56 +f 109/109/56 85/85/56 102/102/56 +f 108/108/197 110/110/198 107/107/199 +f 107/107/199 110/110/198 111/111/200 +f 107/107/201 111/111/202 112/112/203 +f 107/107/201 112/112/203 106/106/204 +f 106/106/204 112/112/203 113/113/205 +f 106/106/206 113/113/207 114/114/208 +f 106/106/206 114/114/208 104/104/209 +f 104/104/210 114/114/211 103/103/212 +f 103/103/212 114/114/211 115/115/213 +f 103/103/214 115/115/215 116/116/216 +f 103/103/214 116/116/216 105/105/217 +f 105/105/218 116/116/219 117/117/220 +f 105/105/218 117/117/220 109/109/221 +f 109/109/222 117/117/223 110/110/224 +f 109/109/222 110/110/224 108/108/225 +f 117/117/226 118/118/227 119/119/228 +f 116/116/229 120/120/230 118/118/227 +f 116/116/229 118/118/227 117/117/226 +f 117/117/226 119/119/228 110/110/231 +f 110/110/231 119/119/228 121/121/232 +f 114/114/233 122/122/234 115/115/235 +f 122/122/234 123/123/236 115/115/235 +f 115/115/235 123/123/236 116/116/229 +f 116/116/229 123/123/236 120/120/230 +f 110/110/231 121/121/232 111/111/237 +f 113/113/238 124/124/239 114/114/233 +f 114/114/233 124/124/239 122/122/234 +f 112/112/240 125/125/241 113/113/238 +f 113/113/238 125/125/241 124/124/239 +f 111/111/237 121/121/232 126/126/242 +f 111/111/237 126/126/242 112/112/240 +f 112/112/240 126/126/242 125/125/241 +f 127/127/243 128/128/244 129/129/245 +f 130/130/246 129/129/245 128/128/244 +f 129/129/245 130/130/246 131/131/247 +f 131/131/247 130/130/246 132/132/248 +f 118/118/249 132/132/248 130/130/246 +f 118/118/249 133/133/250 132/132/248 +f 133/133/250 118/118/249 120/120/251 +f 133/133/250 120/120/251 134/134/252 +f 134/134/252 120/120/251 123/123/253 +f 123/123/253 135/135/254 134/134/252 +f 123/123/253 136/136/255 135/135/254 +f 136/136/255 123/123/253 122/122/256 +f 137/137/257 136/136/255 122/122/256 +f 137/137/257 122/122/256 138/138/258 +f 137/137/257 138/138/258 139/139/259 +f 139/139/259 138/138/258 140/140/260 +f 124/124/261 140/140/260 138/138/258 +f 140/140/260 124/124/261 141/141/262 +f 141/141/262 124/124/261 125/125/263 +f 125/125/263 142/142/264 141/141/262 +f 125/125/263 143/143/265 142/142/264 +f 143/143/265 125/125/263 126/126/266 +f 143/143/265 126/126/266 144/144/267 +f 121/121/268 144/144/267 126/126/266 +f 121/121/268 145/145/269 144/144/267 +f 145/145/269 121/121/268 128/128/244 +f 128/128/244 127/127/243 145/145/269 +f 101/101/270 146/146/271 147/147/272 +f 84/84/273 146/146/271 101/101/270 +f 101/101/270 147/147/272 99/99/274 +f 84/84/273 127/127/275 146/146/271 +f 99/99/274 148/148/276 97/97/277 +f 97/97/277 148/148/276 135/135/278 +f 147/147/272 148/148/276 99/99/274 +f 97/97/277 135/135/278 137/137/279 +f 97/97/277 137/137/279 95/95/280 +f 95/95/280 137/137/279 149/149/281 +f 93/93/282 150/150/283 91/91/284 +f 91/91/284 142/142/285 88/88/286 +f 88/88/286 142/142/285 151/151/287 +f 86/86/288 152/152/289 127/127/275 +f 86/86/288 127/127/275 84/84/273 +f 93/93/282 140/140/290 150/150/283 +f 88/88/286 151/151/287 152/152/289 +f 95/95/280 149/149/281 93/93/282 +f 93/93/282 149/149/281 140/140/290 +f 91/91/284 150/150/283 142/142/285 +f 88/88/286 152/152/289 86/86/288 +f 148/148/291 147/147/291 133/133/291 +f 134/134/292 148/148/293 133/133/294 +f 132/132/295 147/147/296 131/131/297 +f 131/131/298 146/146/298 129/129/298 +f 127/127/243 152/152/299 145/145/269 +f 151/151/300 143/143/300 144/144/300 +f 142/142/285 150/150/283 141/141/301 +f 150/150/302 140/140/260 141/141/262 +f 140/140/303 149/149/281 139/139/304 +f 135/135/254 136/136/255 137/137/305 +f 135/135/306 148/148/293 134/134/292 +f 133/133/307 147/147/296 132/132/295 +f 147/147/296 146/146/308 131/131/297 +f 127/127/243 129/129/245 146/146/309 +f 145/145/310 152/152/310 144/144/310 +f 152/152/311 151/151/311 144/144/311 +f 151/151/312 142/142/264 143/143/265 +f 149/149/281 137/137/279 139/139/304 +f 138/138/313 122/122/234 124/124/239 +f 128/128/314 121/121/232 119/119/228 +f 128/128/244 119/119/315 130/130/246 +f 130/130/316 119/119/316 118/118/316 +f 153/153/317 154/154/318 155/155/319 +f 155/155/319 154/154/318 156/156/320 +f 157/157/321 158/158/322 156/156/320 +f 156/156/320 158/158/322 155/155/319 +f 159/159/323 160/160/324 161/161/325 +f 161/161/325 162/162/326 159/159/323 +f 157/157/327 163/163/328 164/164/329 +f 165/165/330 166/166/331 167/167/332 +f 168/168/333 169/169/334 170/170/335 +f 170/170/335 171/171/336 168/168/333 +f 172/172/337 170/170/335 169/169/334 +f 173/173/338 174/174/339 175/175/340 +f 175/175/340 174/174/339 171/171/336 +f 175/175/340 171/171/336 170/170/335 +f 172/172/341 169/169/341 176/176/341 +f 176/176/342 169/169/343 177/177/344 +f 176/176/342 177/177/344 178/178/345 +f 178/178/345 177/177/344 179/179/346 +f 178/178/345 179/179/346 180/180/347 +f 180/180/347 179/179/346 181/181/348 +f 180/180/347 181/181/348 182/182/349 +f 180/180/347 182/182/349 183/183/350 +f 183/183/350 182/182/349 184/184/351 +f 183/183/350 184/184/351 185/185/352 +f 185/185/352 184/184/351 160/160/324 +f 185/185/352 160/160/324 159/159/323 +f 162/162/326 161/161/325 186/186/353 +f 186/186/353 161/161/325 187/187/354 +f 165/165/355 187/187/356 161/161/357 +f 165/165/355 161/161/357 188/188/358 +f 188/188/358 161/161/357 189/189/359 +f 177/177/360 169/169/361 190/190/362 +f 174/174/363 163/163/364 171/171/365 +f 168/168/366 190/190/362 169/169/361 +f 190/190/362 168/168/366 171/171/365 +f 190/190/362 171/171/365 163/163/364 +f 189/189/359 184/184/367 188/188/358 +f 188/188/358 184/184/367 182/182/368 +f 190/190/362 191/191/369 177/177/360 +f 188/188/358 182/182/368 192/192/370 +f 161/161/357 160/160/371 189/189/359 +f 189/189/372 160/160/324 184/184/351 +f 182/182/368 181/181/373 192/192/370 +f 181/181/373 179/179/374 192/192/370 +f 192/192/370 179/179/374 191/191/375 +f 191/191/375 179/179/374 177/177/376 +f 173/173/338 175/175/340 193/193/377 +f 175/175/378 170/170/379 193/193/380 +f 170/170/379 172/172/381 193/193/380 +f 176/176/382 178/178/382 172/172/382 +f 172/172/383 178/178/383 194/194/383 +f 178/178/384 180/180/385 194/194/386 +f 194/194/386 180/180/385 195/195/387 +f 195/195/387 180/180/385 183/183/388 +f 185/185/352 159/159/323 196/196/389 +f 159/159/390 162/162/391 196/196/392 +f 191/191/393 156/156/394 154/154/395 +f 191/191/393 154/154/395 192/192/396 +f 190/190/397 157/157/398 191/191/393 +f 191/191/393 157/157/398 156/156/394 +f 157/157/399 190/190/399 163/163/399 +f 195/195/400 153/153/401 194/194/402 +f 194/194/402 153/153/401 155/155/403 +f 158/158/404 197/197/405 155/155/403 +f 155/155/403 197/197/405 194/194/402 +f 197/197/406 158/158/406 164/164/406 +f 198/198/407 186/186/408 187/187/409 +f 165/165/410 198/198/407 187/187/409 +f 163/163/411 173/173/412 164/164/413 +f 173/173/412 163/163/411 174/174/411 +f 167/167/414 166/166/415 153/153/317 +f 153/153/317 166/166/415 154/154/318 +f 165/165/330 167/167/332 198/198/416 +f 166/166/417 188/188/418 154/154/395 +f 154/154/395 188/188/418 192/192/396 +f 188/188/419 166/166/419 165/165/419 +f 199/199/420 167/167/421 195/195/400 +f 195/195/400 167/167/421 153/153/401 +f 167/167/422 199/199/422 198/198/422 +f 200/200/423 201/201/424 202/202/425 +f 200/200/423 202/202/425 203/203/426 +f 203/203/426 204/204/427 205/205/428 +f 200/200/423 206/206/429 201/201/424 +f 202/202/425 204/204/427 203/203/426 +f 204/204/427 202/202/425 207/207/430 +f 200/200/423 203/203/426 208/208/431 +f 200/200/423 208/208/431 209/209/432 +f 209/209/432 208/208/431 210/210/433 +f 209/209/432 210/210/433 211/211/434 +f 212/212/435 213/213/436 214/214/437 +f 215/215/438 216/216/438 217/217/438 +f 216/216/438 215/215/438 218/218/438 +f 213/213/436 212/212/435 219/219/439 +f 220/220/440 221/221/440 222/222/440 +f 220/220/440 222/222/440 223/223/440 +f 223/223/440 222/222/440 224/224/440 +f 223/223/440 224/224/440 225/225/440 +f 226/226/441 221/221/442 227/227/443 +f 221/221/442 226/226/441 222/222/444 +f 220/220/445 227/227/446 221/221/447 +f 220/220/445 228/228/448 227/227/446 +f 223/223/449 207/207/450 220/220/451 +f 220/220/451 207/207/450 228/228/452 +f 207/207/453 223/223/454 225/225/455 +f 207/207/453 225/225/455 204/204/456 +f 204/204/457 225/225/458 224/224/459 +f 204/204/457 224/224/459 205/205/460 +f 222/222/461 226/226/462 224/224/463 +f 224/224/463 226/226/462 205/205/464 +f 229/229/440 230/230/440 231/231/440 +f 229/229/440 231/231/440 232/232/440 +f 232/232/440 231/231/440 233/233/440 +f 232/232/440 233/233/440 234/234/440 +f 231/231/465 235/235/466 207/207/467 +f 235/235/466 231/231/465 230/230/468 +f 230/230/469 236/236/470 235/235/471 +f 229/229/472 236/236/470 230/230/469 +f 236/236/473 229/229/474 237/237/475 +f 237/237/475 229/229/474 232/232/476 +f 232/232/476 206/206/477 237/237/475 +f 206/206/478 232/232/479 234/234/480 +f 206/206/478 234/234/480 201/201/481 +f 201/201/482 234/234/483 202/202/484 +f 202/202/484 234/234/483 233/233/485 +f 233/233/486 207/207/487 202/202/488 +f 231/231/489 207/207/487 233/233/486 +f 238/238/490 236/236/491 237/237/492 +f 235/235/493 227/227/494 228/228/495 +f 227/227/496 235/235/496 239/239/496 +f 239/239/497 235/235/498 236/236/491 +f 235/235/493 228/228/495 207/207/499 +f 226/226/500 227/227/501 239/239/502 +f 236/236/491 238/238/490 239/239/497 +f 240/240/503 200/200/423 241/241/504 +f 241/241/504 200/200/423 209/209/432 +f 241/241/504 209/209/432 242/242/505 +f 242/242/505 209/209/432 243/243/506 +f 243/243/506 209/209/432 211/211/507 +f 206/206/508 200/200/423 240/240/503 +f 206/206/508 240/240/503 244/244/509 +f 205/205/510 226/226/511 245/245/512 +f 203/203/513 205/205/510 246/246/514 +f 246/246/514 205/205/510 245/245/512 +f 247/247/515 210/210/516 208/208/517 +f 247/247/515 208/208/517 248/248/518 +f 248/248/518 208/208/517 203/203/513 +f 248/248/518 203/203/513 246/246/514 +f 245/245/519 226/226/500 239/239/502 +f 244/244/509 237/237/520 206/206/508 +f 237/237/520 244/244/509 238/238/521 +f 215/215/522 245/245/519 239/239/502 +f 217/217/523 249/249/524 250/250/525 +f 249/249/524 251/251/526 250/250/525 +f 251/251/527 252/252/527 246/246/527 +f 252/252/528 253/253/529 246/246/530 +f 253/253/529 254/254/531 246/246/530 +f 246/246/532 254/254/532 248/248/532 +f 254/254/533 255/255/533 248/248/533 +f 248/248/534 255/255/534 256/256/534 +f 255/255/535 257/257/536 256/256/537 +f 257/257/536 258/258/538 256/256/537 +f 256/256/539 258/258/539 259/259/539 +f 260/260/540 214/214/541 213/213/542 +f 217/217/543 250/250/544 215/215/545 +f 215/215/545 250/250/544 245/245/546 +f 256/256/547 259/259/548 261/261/549 +f 261/261/549 260/260/540 213/213/542 +f 250/250/544 251/251/550 245/245/546 +f 260/260/540 261/261/549 259/259/548 +f 245/245/546 251/251/550 246/246/551 +f 256/256/552 247/247/552 248/248/552 +f 247/247/553 256/256/547 261/261/549 +f 218/218/554 238/238/521 244/244/509 +f 262/262/555 263/263/556 216/216/557 +f 212/212/558 264/264/559 265/265/560 +f 264/264/561 266/266/561 265/265/561 +f 266/266/562 267/267/563 243/243/564 +f 267/267/565 268/268/566 243/243/567 +f 243/243/567 268/268/566 242/242/568 +f 242/242/568 268/268/566 241/241/569 +f 241/241/569 268/268/566 269/269/570 +f 241/241/569 269/269/570 240/240/571 +f 269/269/572 270/270/573 240/240/574 +f 270/270/575 271/271/575 240/240/575 +f 240/240/576 271/271/577 272/272/578 +f 272/272/579 263/263/556 262/262/555 +f 212/212/580 214/214/581 260/260/582 +f 212/212/580 260/260/582 264/264/583 +f 264/264/583 260/260/582 259/259/584 +f 264/264/583 259/259/584 266/266/562 +f 266/266/562 259/259/584 258/258/585 +f 266/266/562 258/258/585 267/267/563 +f 267/267/563 258/258/585 257/257/586 +f 267/267/563 257/257/586 268/268/587 +f 268/268/587 257/257/586 255/255/588 +f 268/268/587 255/255/588 254/254/589 +f 268/268/587 254/254/589 269/269/572 +f 269/269/572 254/254/589 270/270/573 +f 270/270/573 254/254/589 253/253/590 +f 270/270/573 253/253/590 271/271/577 +f 271/271/577 253/253/590 252/252/591 +f 271/271/577 252/252/591 272/272/578 +f 272/272/578 252/252/591 251/251/592 +f 272/272/578 251/251/592 263/263/593 +f 263/263/593 251/251/592 249/249/594 +f 263/263/593 249/249/594 216/216/595 +f 216/216/595 249/249/594 217/217/596 +f 239/239/497 238/238/490 215/215/597 +f 215/215/597 238/238/490 218/218/598 +f 210/210/433 273/273/599 211/211/434 +f 211/211/434 274/274/600 275/275/601 +f 210/210/433 276/276/602 273/273/599 +f 211/211/434 273/273/599 274/274/600 +f 274/274/600 273/273/599 277/277/603 +f 278/278/440 279/279/440 280/280/440 +f 279/279/440 281/281/440 282/282/440 +f 279/279/440 282/282/440 280/280/440 +f 283/283/604 277/277/605 278/278/606 +f 284/284/607 282/282/607 276/276/607 +f 276/276/608 282/282/609 281/281/610 +f 276/276/608 281/281/610 273/273/611 +f 273/273/612 281/281/613 277/277/614 +f 277/277/614 281/281/613 279/279/615 +f 278/278/606 277/277/605 279/279/616 +f 278/278/617 285/285/618 283/283/619 +f 280/280/620 285/285/618 278/278/617 +f 280/280/620 286/286/621 285/285/618 +f 286/286/622 280/280/623 284/284/624 +f 282/282/625 284/284/624 280/280/623 +f 287/287/440 288/288/440 289/289/440 +f 289/289/440 288/288/440 290/290/440 +f 288/288/440 291/291/440 290/290/440 +f 289/289/626 292/292/627 275/275/628 +f 292/292/627 289/289/626 290/290/629 +f 293/293/630 292/292/631 290/290/632 +f 291/291/633 293/293/630 290/290/632 +f 291/291/633 294/294/634 293/293/630 +f 294/294/635 291/291/636 277/277/637 +f 288/288/638 277/277/637 291/291/636 +f 287/287/639 274/274/640 288/288/641 +f 288/288/641 274/274/640 277/277/642 +f 287/287/643 275/275/644 274/274/645 +f 289/289/646 275/275/644 287/287/643 +f 293/293/647 285/285/648 295/295/649 +f 295/295/649 285/285/648 286/286/650 +f 293/293/647 294/294/651 285/285/648 +f 285/285/648 294/294/651 283/283/652 +f 277/277/653 283/283/652 294/294/651 +f 292/292/654 293/293/647 296/296/655 +f 293/293/647 295/295/649 296/296/655 +f 275/275/656 292/292/657 297/297/658 +f 211/211/507 275/275/656 243/243/506 +f 243/243/506 275/275/656 297/297/658 +f 276/276/659 210/210/516 247/247/515 +f 276/276/659 247/247/515 284/284/660 +f 284/284/660 247/247/515 261/261/661 +f 284/284/660 261/261/661 286/286/650 +f 286/286/650 261/261/661 295/295/649 +f 297/297/662 292/292/654 296/296/655 +f 261/261/661 213/213/663 295/295/649 +f 296/296/655 219/219/664 297/297/662 +f 296/296/655 295/295/649 219/219/665 +f 219/219/665 295/295/649 213/213/666 +f 298/298/667 299/299/668 300/300/669 +f 300/300/669 299/299/668 301/301/670 +f 300/300/669 301/301/670 302/302/671 +f 302/302/671 301/301/670 303/303/672 +f 304/304/673 305/305/674 302/302/671 +f 304/304/673 302/302/671 303/303/672 +f 306/306/675 307/307/676 308/308/677 +f 308/308/678 307/307/679 305/305/680 +f 308/308/678 305/305/680 304/304/681 +f 306/306/675 309/309/682 307/307/676 +f 309/309/682 306/306/675 310/310/683 +f 309/309/682 310/310/683 311/311/684 +f 311/311/684 310/310/683 312/312/685 +f 311/311/684 312/312/685 313/313/686 +f 313/313/687 312/312/688 314/314/689 +f 314/314/689 312/312/688 315/315/690 +f 314/314/691 315/315/692 316/316/693 +f 316/316/693 315/315/692 317/317/694 +f 318/318/695 319/319/696 317/317/694 +f 317/317/694 319/319/696 316/316/693 +f 319/319/696 318/318/695 320/320/697 +f 320/320/697 318/318/695 321/321/698 +f 320/320/699 321/321/700 322/322/701 +f 322/322/701 321/321/700 323/323/702 +f 322/322/703 323/323/704 324/324/705 +f 322/322/703 324/324/705 325/325/706 +f 325/325/706 324/324/705 326/326/707 +f 325/325/706 326/326/707 327/327/708 +f 327/327/709 326/326/710 328/328/711 +f 327/327/709 328/328/711 329/329/712 +f 329/329/713 328/328/714 299/299/668 +f 329/329/713 299/299/668 298/298/667 +f 330/330/715 331/331/716 332/332/717 +f 330/330/715 333/333/718 331/331/716 +f 330/330/715 334/334/719 333/333/718 +f 330/330/715 332/332/717 335/335/720 +f 336/336/721 337/337/722 338/338/723 +f 336/336/721 338/338/723 339/339/724 +f 338/338/725 340/340/726 339/339/727 +f 339/339/727 340/340/726 341/341/728 +f 341/341/729 340/340/730 342/342/731 +f 341/341/729 342/342/731 343/343/732 +f 343/343/733 342/342/734 344/344/735 +f 344/344/735 342/342/734 345/345/736 +f 345/345/737 346/346/738 344/344/739 +f 344/344/739 346/346/738 347/347/740 +f 347/347/741 346/346/742 348/348/743 +f 347/347/741 348/348/743 349/349/744 +f 349/349/745 348/348/746 336/336/747 +f 348/348/746 337/337/748 336/336/747 +f 342/342/749 334/334/750 330/330/751 +f 334/334/752 342/342/731 340/340/730 +f 334/334/752 340/340/730 333/333/753 +f 340/340/754 338/338/755 333/333/756 +f 333/333/756 338/338/755 331/331/757 +f 331/331/757 338/338/755 337/337/748 +f 331/331/757 337/337/748 332/332/758 +f 337/337/748 348/348/746 332/332/758 +f 332/332/759 348/348/760 346/346/761 +f 332/332/759 346/346/761 335/335/762 +f 335/335/763 346/346/764 330/330/765 +f 346/346/764 345/345/766 330/330/765 +f 330/330/751 345/345/767 342/342/749 +f 336/336/145 350/350/145 351/351/145 +f 336/336/145 351/351/145 349/349/145 +f 341/341/145 352/352/145 339/339/145 +f 339/339/145 353/353/145 336/336/145 +f 344/344/145 354/354/145 343/343/145 +f 349/349/145 355/355/145 347/347/145 +f 349/349/145 351/351/145 355/355/145 +f 353/353/145 350/350/145 336/336/145 +f 339/339/145 352/352/145 353/353/145 +f 347/347/145 356/356/145 344/344/145 +f 343/343/145 357/357/145 341/341/145 +f 343/343/145 354/354/145 358/358/145 +f 341/341/145 357/357/145 352/352/145 +f 343/343/145 358/358/145 357/357/145 +f 344/344/145 356/356/145 354/354/145 +f 347/347/145 355/355/145 356/356/145 +f 359/359/768 360/360/769 361/361/770 +f 362/362/771 363/363/772 364/364/773 +f 362/362/771 365/365/774 363/363/772 +f 364/364/773 363/363/772 366/366/775 +f 366/366/775 367/367/776 359/359/768 +f 359/359/768 367/367/776 360/360/769 +f 368/368/777 369/369/778 370/370/779 +f 366/366/775 363/363/772 367/367/776 +f 361/361/770 360/360/769 371/371/780 +f 372/372/781 373/373/782 374/374/783 +f 375/375/784 369/369/778 368/368/777 +f 368/368/777 376/376/785 377/377/786 +f 374/374/783 378/378/787 375/375/784 +f 375/375/784 378/378/787 369/369/778 +f 377/377/786 376/376/785 362/362/771 +f 362/362/771 376/376/785 365/365/774 +f 361/361/770 371/371/780 372/372/781 +f 373/373/782 379/379/788 374/374/783 +f 374/374/783 379/379/788 378/378/787 +f 372/372/781 371/371/780 373/373/782 +f 368/368/777 370/370/779 376/376/785 +f 352/352/789 374/374/790 375/375/791 +f 352/352/789 375/375/791 353/353/792 +f 353/353/793 375/375/794 368/368/795 +f 353/353/793 368/368/795 350/350/796 +f 350/350/797 368/368/798 351/351/799 +f 351/351/799 368/368/798 377/377/800 +f 351/351/801 377/377/802 362/362/803 +f 351/351/801 362/362/803 355/355/804 +f 355/355/805 362/362/805 364/364/805 +f 355/355/806 364/364/806 356/356/806 +f 356/356/807 364/364/807 366/366/807 +f 356/356/808 366/366/808 354/354/808 +f 354/354/809 366/366/809 359/359/809 +f 354/354/810 359/359/811 358/358/812 +f 358/358/812 359/359/811 361/361/813 +f 358/358/814 361/361/815 357/357/816 +f 357/357/816 361/361/815 372/372/817 +f 357/357/818 372/372/819 374/374/820 +f 357/357/818 374/374/820 352/352/821 +f 380/380/822 381/381/823 382/382/824 +f 383/383/825 380/380/822 382/382/824 +f 381/381/823 380/380/822 384/384/826 +f 385/385/827 386/386/828 383/383/825 +f 385/385/827 387/387/829 386/386/828 +f 388/388/830 389/389/831 387/387/829 +f 388/388/830 387/387/829 385/385/827 +f 390/390/832 391/391/833 388/388/830 +f 390/390/832 392/392/834 391/391/833 +f 393/393/835 392/392/834 390/390/832 +f 393/393/835 394/394/836 392/392/834 +f 383/383/825 386/386/828 380/380/822 +f 388/388/830 391/391/833 389/389/831 +f 381/381/823 384/384/826 393/393/835 +f 393/393/835 384/384/826 394/394/836 +f 384/384/837 395/395/838 394/394/839 +f 391/391/840 396/396/841 389/389/842 +f 386/386/843 397/397/844 380/380/845 +f 380/380/845 398/398/846 384/384/837 +f 392/392/847 399/399/848 391/391/840 +f 391/391/840 399/399/848 400/400/849 +f 387/387/850 401/401/851 386/386/843 +f 380/380/845 397/397/844 402/402/852 +f 384/384/837 403/403/853 395/395/838 +f 392/392/847 394/394/839 404/404/854 +f 391/391/840 400/400/849 396/396/841 +f 396/396/841 405/405/855 389/389/842 +f 389/389/842 406/406/856 387/387/850 +f 387/387/850 406/406/856 401/401/851 +f 402/402/852 398/398/846 380/380/845 +f 398/398/846 403/403/853 384/384/837 +f 389/389/842 405/405/855 406/406/856 +f 386/386/843 407/407/857 397/397/844 +f 404/404/854 399/399/848 392/392/847 +f 395/395/838 408/408/858 394/394/839 +f 394/394/839 408/408/858 404/404/854 +f 401/401/851 407/407/857 386/386/843 +f 398/398/846 370/370/859 403/403/853 +f 404/404/854 373/373/860 399/399/848 +f 407/407/857 365/365/861 397/397/844 +f 403/403/853 370/370/859 369/369/862 +f 400/400/849 399/399/848 371/371/863 +f 406/406/856 363/363/864 401/401/851 +f 401/401/851 363/363/864 407/407/857 +f 397/397/844 376/376/865 402/402/852 +f 403/403/853 378/378/866 395/395/838 +f 400/400/849 371/371/863 360/360/867 +f 400/400/849 360/360/867 396/396/841 +f 396/396/841 367/367/868 405/405/855 +f 402/402/852 376/376/865 398/398/846 +f 398/398/846 376/376/865 370/370/859 +f 395/395/838 378/378/866 408/408/858 +f 408/408/858 379/379/869 404/404/854 +f 373/373/860 371/371/863 399/399/848 +f 405/405/855 367/367/868 406/406/856 +f 406/406/856 367/367/868 363/363/864 +f 397/397/844 365/365/861 376/376/865 +f 378/378/866 379/379/869 408/408/858 +f 379/379/869 373/373/860 404/404/854 +f 396/396/841 360/360/867 367/367/868 +f 363/363/864 365/365/861 407/407/857 +f 369/369/862 378/378/866 403/403/853 +f 409/409/56 410/410/56 411/411/56 +f 411/411/56 410/410/56 412/412/56 +f 411/411/56 412/412/56 413/413/56 +f 413/413/56 412/412/56 414/414/56 +f 383/383/870 409/409/871 411/411/872 +f 411/411/872 385/385/873 383/383/870 +f 409/409/874 382/382/875 410/410/876 +f 409/409/874 383/383/877 382/382/875 +f 410/410/876 382/382/875 381/381/878 +f 410/410/879 381/381/880 412/412/881 +f 381/381/880 393/393/882 412/412/881 +f 412/412/883 393/393/884 414/414/885 +f 414/414/885 393/393/884 390/390/886 +f 414/414/887 388/388/888 413/413/889 +f 414/414/887 390/390/890 388/388/888 +f 413/413/891 388/388/892 411/411/893 +f 411/411/893 388/388/892 385/385/894 +f 415/415/895 416/416/896 417/417/897 +f 415/415/895 417/417/897 418/418/898 +f 418/418/899 417/417/900 419/419/901 +f 418/418/899 419/419/901 420/420/902 +f 420/420/903 419/419/904 421/421/905 +f 420/420/903 421/421/905 422/422/906 +f 422/422/907 421/421/908 423/423/909 +f 423/423/909 421/421/908 424/424/910 +f 423/423/911 424/424/911 425/425/911 +f 425/425/912 424/424/912 426/426/912 +f 425/425/913 426/426/913 427/427/913 +f 427/427/914 426/426/914 428/428/914 +f 427/427/915 428/428/915 429/429/915 +f 429/429/916 428/428/916 430/430/916 +f 429/429/917 430/430/917 431/431/917 +f 431/431/918 430/430/918 416/416/918 +f 431/431/919 416/416/919 415/415/919 +f 432/432/145 428/428/145 426/426/145 +f 432/432/145 426/426/145 433/433/145 +f 434/434/145 430/430/145 432/432/145 +f 432/432/145 430/430/145 428/428/145 +f 433/433/145 426/426/145 424/424/145 +f 435/435/145 421/421/145 436/436/145 +f 433/433/145 424/424/145 435/435/145 +f 437/437/145 417/417/145 416/416/145 +f 435/435/145 424/424/145 421/421/145 +f 434/434/145 416/416/145 430/430/145 +f 436/436/145 419/419/145 437/437/145 +f 437/437/145 419/419/145 417/417/145 +f 437/437/145 416/416/145 434/434/145 +f 436/436/145 421/421/145 419/419/145 +f 437/437/920 438/438/921 439/439/922 +f 437/437/920 439/439/922 436/436/923 +f 436/436/923 439/439/922 440/440/924 +f 436/436/923 440/440/924 435/435/925 +f 435/435/925 440/440/924 441/441/926 +f 435/435/927 441/441/928 433/433/929 +f 433/433/929 441/441/928 442/442/930 +f 433/433/931 442/442/932 443/443/933 +f 433/433/931 443/443/933 432/432/934 +f 432/432/935 443/443/936 444/444/937 +f 432/432/935 444/444/937 434/434/938 +f 434/434/939 444/444/939 445/445/939 +f 434/434/940 445/445/941 437/437/942 +f 437/437/942 445/445/941 438/438/943 +f 157/157/327 164/164/329 158/158/944 +f 444/444/945 446/446/946 445/445/947 +f 445/445/947 446/446/946 447/447/948 +f 444/444/945 448/448/949 446/446/946 +f 445/445/947 447/447/948 449/449/950 +f 445/445/947 449/449/950 438/438/951 +f 442/442/952 450/450/953 443/443/954 +f 443/443/954 450/450/953 451/451/955 +f 443/443/954 451/451/955 444/444/945 +f 444/444/945 451/451/955 448/448/949 +f 438/438/951 449/449/950 439/439/956 +f 439/439/956 449/449/950 452/452/957 +f 441/441/958 453/453/959 454/454/960 +f 441/441/958 454/454/960 442/442/952 +f 442/442/952 454/454/960 450/450/953 +f 440/440/961 455/455/962 453/453/959 +f 440/440/961 453/453/959 441/441/958 +f 439/439/956 452/452/957 455/455/962 +f 439/439/956 455/455/962 440/440/961 +f 447/447/963 456/456/964 449/449/965 +f 456/456/964 447/447/963 457/457/966 +f 457/457/966 447/447/963 446/446/967 +f 457/457/966 446/446/967 458/458/968 +f 458/458/969 446/446/970 448/448/971 +f 458/458/969 448/448/971 459/459/972 +f 459/459/972 448/448/971 460/460/973 +f 460/460/973 448/448/971 451/451/974 +f 460/460/973 451/451/974 461/461/975 +f 450/450/976 461/461/975 451/451/974 +f 450/450/976 462/462/977 461/461/975 +f 463/463/978 462/462/977 450/450/976 +f 462/462/977 463/463/978 464/464/979 +f 454/454/980 464/464/979 463/463/978 +f 464/464/979 454/454/980 465/465/981 +f 453/453/982 465/465/981 454/454/980 +f 453/453/982 466/466/983 465/465/981 +f 467/467/984 466/466/983 453/453/982 +f 466/466/983 467/467/984 468/468/985 +f 455/455/986 468/468/985 467/467/984 +f 468/468/985 455/455/986 469/469/987 +f 469/469/987 455/455/986 452/452/988 +f 452/452/988 470/470/989 469/469/987 +f 470/470/989 452/452/988 471/471/990 +f 471/471/990 472/472/991 470/470/989 +f 449/449/965 473/473/992 471/471/990 +f 471/471/990 473/473/992 472/472/991 +f 456/456/964 473/473/992 449/449/965 +f 415/415/993 474/474/994 431/431/995 +f 431/431/995 474/474/994 475/475/996 +f 431/431/995 475/475/996 429/429/997 +f 429/429/997 475/475/996 476/476/998 +f 429/429/997 476/476/998 427/427/999 +f 427/427/999 476/476/998 477/477/1000 +f 427/427/999 477/477/1000 461/461/1001 +f 427/427/999 461/461/1001 425/425/1002 +f 425/425/1002 461/461/1001 478/478/1003 +f 415/415/993 473/473/1004 474/474/994 +f 420/420/1005 468/468/1006 479/479/1007 +f 418/418/1008 473/473/1004 415/415/993 +f 425/425/1002 478/478/1003 423/423/1009 +f 423/423/1009 478/478/1003 480/480/1010 +f 423/423/1009 480/480/1010 481/481/1011 +f 423/423/1009 481/481/1011 422/422/1012 +f 420/420/1005 479/479/1007 418/418/1008 +f 422/422/1012 481/481/1011 468/468/1006 +f 422/422/1012 468/468/1006 420/420/1005 +f 418/418/1008 479/479/1007 473/473/1004 +f 464/464/1013 480/480/1014 478/478/1015 +f 468/468/1016 481/481/1017 466/466/1018 +f 476/476/1019 475/475/1020 458/458/1021 +f 462/462/977 478/478/1022 461/461/975 +f 460/460/1023 476/476/1019 459/459/1024 +f 458/458/1021 475/475/1020 457/457/1025 +f 475/475/1026 474/474/1026 457/457/1026 +f 457/457/1027 474/474/1028 456/456/1029 +f 481/481/1030 480/480/1014 465/465/1031 +f 465/465/1031 480/480/1014 464/464/1013 +f 461/461/1001 477/477/1000 460/460/1032 +f 476/476/1033 460/460/1033 477/477/1033 +f 458/458/1021 459/459/1024 476/476/1019 +f 456/456/1029 474/474/1028 473/473/1034 +f 473/473/992 479/479/1035 472/472/991 +f 472/472/991 479/479/1036 470/470/989 +f 469/469/1037 470/470/1037 479/479/1037 +f 479/479/1038 468/468/985 469/469/987 +f 465/465/1039 466/466/1018 481/481/1017 +f 464/464/1040 478/478/1040 462/462/1040 +f 467/467/1041 453/453/1041 455/455/1041 +f 471/471/1042 452/452/1042 449/449/1042 +f 463/463/1043 450/450/1043 454/454/1043 +f 482/482/1044 483/483/1045 484/484/1046 +f 482/482/1044 484/484/1046 485/485/1047 +f 485/485/1047 484/484/1046 486/486/1048 +f 486/486/1048 484/484/1046 487/487/1049 +f 488/488/1050 489/489/1051 486/486/1048 +f 488/488/1050 486/486/1048 487/487/1049 +f 490/490/1052 491/491/1053 492/492/1054 +f 492/492/1054 491/491/1053 489/489/1051 +f 492/492/1054 489/489/1051 488/488/1050 +f 490/490/1052 493/493/1055 491/491/1053 +f 493/493/1055 490/490/1052 494/494/1056 +f 493/493/1057 494/494/1058 495/495/1059 +f 495/495/1059 494/494/1058 496/496/1060 +f 495/495/1061 496/496/1062 497/497/1063 +f 497/497/1063 496/496/1062 498/498/1064 +f 497/497/1063 498/498/1064 499/499/1065 +f 499/499/1065 498/498/1064 500/500/1066 +f 500/500/1066 498/498/1064 501/501/1067 +f 502/502/1068 503/503/1069 501/501/1067 +f 501/501/1067 503/503/1069 500/500/1066 +f 503/503/1069 502/502/1068 504/504/1070 +f 504/504/1070 502/502/1068 505/505/1071 +f 504/504/1070 505/505/1071 506/506/1072 +f 504/504/1070 506/506/1072 507/507/1073 +f 507/507/1074 506/506/1075 508/508/1076 +f 508/508/1076 506/506/1075 509/509/1077 +f 508/508/1078 509/509/1079 510/510/1080 +f 508/508/1078 510/510/1080 511/511/1081 +f 511/511/1082 510/510/1083 512/512/1084 +f 511/511/1082 512/512/1084 513/513/1085 +f 513/513/1085 512/512/1084 514/514/1086 +f 513/513/1085 514/514/1086 482/482/1044 +f 482/482/1044 514/514/1086 483/483/1045 +f 326/326/56 324/324/56 328/328/56 +f 324/324/56 323/323/56 328/328/56 +f 328/328/56 323/323/56 299/299/56 +f 323/323/56 321/321/56 299/299/56 +f 304/304/56 317/317/56 315/315/56 +f 321/321/56 301/301/56 299/299/56 +f 321/321/56 318/318/56 301/301/56 +f 318/318/56 303/303/56 301/301/56 +f 318/318/56 317/317/56 303/303/56 +f 317/317/56 304/304/56 303/303/56 +f 312/312/56 310/310/56 306/306/56 +f 315/315/56 308/308/56 304/304/56 +f 315/315/56 312/312/56 308/308/56 +f 312/312/56 306/306/56 308/308/56 +f 510/510/145 509/509/145 512/512/145 +f 512/512/145 509/509/145 506/506/145 +f 514/514/145 512/512/145 506/506/145 +f 514/514/145 506/506/145 505/505/145 +f 514/514/145 505/505/145 483/483/145 +f 483/483/145 505/505/145 502/502/145 +f 483/483/145 502/502/145 484/484/145 +f 484/484/145 502/502/145 501/501/145 +f 484/484/145 501/501/145 487/487/145 +f 487/487/145 501/501/145 488/488/145 +f 488/488/145 501/501/145 498/498/145 +f 488/488/145 498/498/145 492/492/145 +f 490/490/145 492/492/145 496/496/145 +f 490/490/145 496/496/145 494/494/145 +f 498/498/145 496/496/145 492/492/145 +f 515/515/1087 516/516/1088 517/517/1089 +f 518/518/1090 516/516/1088 519/519/1091 +f 519/519/1091 516/516/1088 515/515/1087 +f 520/520/1092 521/521/1093 522/522/1094 +f 523/523/1095 524/524/1096 525/525/1097 +f 517/517/1089 526/526/1098 515/515/1087 +f 522/522/1094 527/527/1099 520/520/1092 +f 515/515/1087 526/526/1098 523/523/1095 +f 515/515/1087 523/523/1095 525/525/1097 +f 522/522/1094 521/521/1093 519/519/1091 +f 519/519/1091 521/521/1093 518/518/1090 +f 525/525/1097 524/524/1096 522/522/1094 +f 522/522/1094 524/524/1096 527/527/1099 +f 528/528/1100 529/529/1101 530/530/1102 +f 528/528/1100 531/531/1103 529/529/1101 +f 532/532/1104 533/533/1105 534/534/1106 +f 534/534/1107 533/533/1107 535/535/1107 +f 534/534/1108 535/535/1109 531/531/1110 +f 535/535/1109 536/536/1111 531/531/1110 +f 531/531/1112 536/536/1113 529/529/1114 +f 529/529/1114 536/536/1113 537/537/1115 +f 529/529/1116 537/537/1117 538/538/1118 +f 538/538/1118 537/537/1117 539/539/1119 +f 538/538/1120 539/539/1121 532/532/1122 +f 532/532/1122 539/539/1121 540/540/1123 +f 532/532/1104 540/540/1124 533/533/1105 +f 537/537/1125 541/541/1126 542/542/1127 +f 540/540/1128 543/543/1129 533/533/1130 +f 533/533/1130 543/543/1129 544/544/1131 +f 536/536/1132 545/545/1133 537/537/1125 +f 537/537/1125 545/545/1133 541/541/1126 +f 535/535/1134 546/546/1135 545/545/1133 +f 535/535/1134 545/545/1133 536/536/1132 +f 533/533/1130 544/544/1131 546/546/1135 +f 533/533/1130 546/546/1135 535/535/1134 +f 537/537/1125 542/542/1127 539/539/1136 +f 539/539/1136 547/547/1137 548/548/1138 +f 539/539/1136 548/548/1138 540/540/1128 +f 540/540/1128 548/548/1138 543/543/1129 +f 539/539/1136 542/542/1127 547/547/1137 +f 516/516/1139 544/544/1140 543/543/1141 +f 516/516/1139 518/518/1142 544/544/1140 +f 544/544/1143 518/518/1144 521/521/1145 +f 544/544/1143 521/521/1145 546/546/1146 +f 521/521/1147 520/520/1148 546/546/1149 +f 546/546/1149 520/520/1148 545/545/1150 +f 520/520/1151 527/527/1152 545/545/1153 +f 545/545/1153 527/527/1152 541/541/1154 +f 527/527/1152 524/524/1155 541/541/1154 +f 541/541/1154 524/524/1155 542/542/1156 +f 524/524/1157 523/523/1158 542/542/1159 +f 542/542/1159 523/523/1158 547/547/1160 +f 547/547/1161 523/523/1162 526/526/1163 +f 547/547/1161 526/526/1163 548/548/1164 +f 526/526/1163 517/517/1165 548/548/1164 +f 548/548/1164 517/517/1165 543/543/1166 +f 543/543/1166 517/517/1165 516/516/1167 +f 525/525/1168 522/522/1169 549/549/1170 +f 549/549/1170 522/522/1169 550/550/1171 +f 515/515/1172 525/525/1173 551/551/1174 +f 551/551/1174 525/525/1173 549/549/1175 +f 519/519/1176 515/515/1177 552/552/1178 +f 552/552/1178 515/515/1177 551/551/1179 +f 522/522/1180 519/519/1181 550/550/1182 +f 550/550/1182 519/519/1181 552/552/1183 +f 550/550/440 552/552/440 551/551/440 +f 550/550/440 551/551/440 549/549/440 +f 532/532/1184 528/528/1184 530/530/1184 +f 532/532/1122 530/530/1185 538/538/1120 +f 538/538/1186 530/530/1102 529/529/1101 +f 534/534/1187 531/531/1187 528/528/1187 +f 534/534/1106 528/528/1188 532/532/1104 +f 553/553/1189 554/554/1190 555/555/1191 +f 555/555/1191 556/556/1192 553/553/1189 +f 557/557/1193 558/558/1194 559/559/1195 +f 560/560/1196 561/561/1197 562/562/1198 +f 555/555/1191 554/554/1190 561/561/1197 +f 561/561/1197 554/554/1190 563/563/1199 +f 559/559/1195 564/564/1200 557/557/1193 +f 563/563/1199 562/562/1198 561/561/1197 +f 559/559/1195 558/558/1194 555/555/1191 +f 558/558/1194 556/556/1192 555/555/1191 +f 560/560/1196 564/564/1200 561/561/1197 +f 561/561/1197 564/564/1200 559/559/1195 +f 565/565/1201 566/566/1202 567/567/1203 +f 568/568/1204 569/569/1205 570/570/1206 +f 569/569/1207 571/571/1208 570/570/1209 +f 570/570/1209 571/571/1208 572/572/1210 +f 571/571/1208 573/573/1211 572/572/1210 +f 573/573/1212 574/574/1213 572/572/1214 +f 572/572/1214 574/574/1213 575/575/1215 +f 575/575/1216 574/574/1217 576/576/1218 +f 575/575/1216 576/576/1218 577/577/1219 +f 577/577/1220 576/576/1221 578/578/1222 +f 576/576/1221 568/568/1223 578/578/1222 +f 578/578/1224 568/568/1204 570/570/1206 +f 569/569/1225 579/579/1226 580/580/1227 +f 568/568/1228 579/579/1226 569/569/1225 +f 573/573/1229 581/581/1230 582/582/1231 +f 573/573/1229 582/582/1231 574/574/1232 +f 571/571/1233 581/581/1230 573/573/1229 +f 571/571/1233 580/580/1227 581/581/1230 +f 569/569/1225 580/580/1227 571/571/1233 +f 568/568/1228 583/583/1234 579/579/1226 +f 574/574/1232 582/582/1231 576/576/1235 +f 576/576/1235 582/582/1231 584/584/1236 +f 576/576/1235 584/584/1236 568/568/1228 +f 568/568/1228 584/584/1236 583/583/1234 +f 553/553/1237 556/556/1238 579/579/1239 +f 579/579/1239 556/556/1238 580/580/1240 +f 580/580/1240 556/556/1238 558/558/1241 +f 580/580/1242 558/558/1243 581/581/1244 +f 558/558/1243 557/557/1245 581/581/1244 +f 557/557/1246 564/564/1247 581/581/1248 +f 581/581/1248 564/564/1247 582/582/1249 +f 582/582/1250 564/564/1250 560/560/1250 +f 582/582/1251 560/560/1252 584/584/1253 +f 560/560/1252 562/562/1254 584/584/1253 +f 562/562/1255 563/563/1256 584/584/1257 +f 584/584/1257 563/563/1256 583/583/1258 +f 563/563/1256 554/554/1259 583/583/1258 +f 583/583/1260 554/554/1261 579/579/1262 +f 579/579/1262 554/554/1261 553/553/1263 +f 561/561/1264 559/559/1265 585/585/1266 +f 585/585/1266 559/559/1265 586/586/1267 +f 555/555/1268 561/561/1269 587/587/1270 +f 587/587/1270 561/561/1269 585/585/1271 +f 559/559/1272 555/555/1273 586/586/1274 +f 586/586/1274 555/555/1273 587/587/1275 +f 586/586/440 587/587/440 585/585/440 +f 570/570/1206 565/565/1276 578/578/1224 +f 578/578/1277 565/565/1278 567/567/1279 +f 578/578/1277 567/567/1279 577/577/1280 +f 577/577/1219 567/567/1281 575/575/1216 +f 575/575/1282 567/567/1283 566/566/1284 +f 575/575/1282 566/566/1284 572/572/1285 +f 572/572/1210 566/566/1286 570/570/1209 +f 570/570/1287 566/566/1202 565/565/1201 +f 588/588/1288 589/589/1289 590/590/1290 +f 590/590/1290 589/589/1289 591/591/1291 +f 592/592/1292 593/593/1293 594/594/1294 +f 590/590/1290 591/591/1291 595/595/1295 +f 590/590/1290 595/595/1295 596/596/1296 +f 592/592/1292 594/594/1294 597/597/1297 +f 592/592/1292 597/597/1297 588/588/1298 +f 596/596/1299 593/593/1293 592/592/1292 +f 598/598/1300 599/599/1301 600/600/1302 +f 601/601/1303 602/602/1304 603/603/1305 +f 602/602/1306 604/604/1306 603/603/1306 +f 603/603/1307 604/604/1308 605/605/1309 +f 603/603/1307 605/605/1309 606/606/1310 +f 606/606/1311 605/605/1312 607/607/1313 +f 606/606/1311 607/607/1313 608/608/1314 +f 608/608/1315 607/607/1315 609/609/1315 +f 608/608/1316 609/609/1317 610/610/1318 +f 610/610/1318 609/609/1317 611/611/1319 +f 610/610/1320 611/611/1321 601/601/1322 +f 601/601/1322 611/611/1321 612/612/1323 +f 601/601/1303 612/612/1324 602/602/1304 +f 602/602/1325 613/613/1326 614/614/1327 +f 612/612/1328 613/613/1326 602/602/1325 +f 615/615/1329 616/616/1330 605/605/1331 +f 605/605/1331 616/616/1330 607/607/1332 +f 604/604/1333 615/615/1329 605/605/1331 +f 604/604/1333 617/617/1334 615/615/1329 +f 602/602/1325 614/614/1327 604/604/1333 +f 604/604/1333 614/614/1327 617/617/1334 +f 612/612/1328 618/618/1335 613/613/1326 +f 607/607/1332 616/616/1330 609/609/1336 +f 609/609/1336 616/616/1330 619/619/1337 +f 609/609/1336 620/620/1338 611/611/1339 +f 611/611/1339 620/620/1338 618/618/1335 +f 611/611/1339 618/618/1335 612/612/1328 +f 609/609/1336 619/619/1337 620/620/1338 +f 613/613/1340 588/588/1341 614/614/1342 +f 588/588/1341 597/597/1343 614/614/1342 +f 614/614/1344 597/597/1345 617/617/1346 +f 617/617/1346 597/597/1345 594/594/1347 +f 617/617/1346 594/594/1347 615/615/1348 +f 615/615/1349 594/594/1350 616/616/1351 +f 594/594/1350 593/593/1352 616/616/1351 +f 616/616/1353 593/593/1354 596/596/1355 +f 616/616/1353 596/596/1355 619/619/1356 +f 596/596/1355 595/595/1357 619/619/1356 +f 619/619/1358 595/595/1359 591/591/1360 +f 619/619/1358 591/591/1360 620/620/1361 +f 620/620/1362 591/591/1363 618/618/1364 +f 618/618/1364 591/591/1363 589/589/1365 +f 618/618/1364 589/589/1365 613/613/1340 +f 589/589/1365 588/588/1341 613/613/1340 +f 596/596/1366 592/592/1366 621/621/1366 +f 621/621/1179 592/592/1179 622/622/1179 +f 590/590/1367 596/596/1368 623/623/1369 +f 623/623/1369 596/596/1368 621/621/1370 +f 588/588/1371 590/590/1371 624/624/1371 +f 624/624/1171 590/590/1171 623/623/1171 +f 592/592/1372 588/588/1373 622/622/1374 +f 622/622/1374 588/588/1373 624/624/1375 +f 622/622/440 624/624/440 623/623/440 +f 622/622/440 623/623/440 621/621/440 +f 601/601/1322 600/600/1376 610/610/1320 +f 610/610/1377 600/600/1302 599/599/1301 +f 610/610/1377 599/599/1301 608/608/1378 +f 608/608/1379 599/599/1379 606/606/1379 +f 606/606/1380 599/599/1301 598/598/1300 +f 606/606/1310 598/598/1381 603/603/1307 +f 603/603/1382 598/598/1383 600/600/1384 +f 603/603/1382 600/600/1384 601/601/1385 +f 625/625/1386 626/626/1387 627/627/1388 +f 628/628/1389 625/625/1386 627/627/1388 +f 628/628/1389 629/629/1390 625/625/1386 +f 630/630/1391 631/631/1392 632/632/1393 +f 627/627/1388 626/626/1387 633/633/1394 +f 627/627/1388 633/633/1394 632/632/1393 +f 634/634/1395 635/635/1396 628/628/1389 +f 635/635/1396 636/636/1397 628/628/1389 +f 633/633/1394 630/630/1391 632/632/1393 +f 628/628/1389 636/636/1397 629/629/1390 +f 632/632/1393 631/631/1392 634/634/1395 +f 634/634/1395 631/631/1392 635/635/1396 +f 637/637/1398 638/638/1399 639/639/1400 +f 640/640/1401 638/638/1399 637/637/1398 +f 639/639/1402 641/641/1403 642/642/1404 +f 642/642/1405 641/641/1405 643/643/1405 +f 642/642/1406 643/643/1407 637/637/1408 +f 637/637/1408 643/643/1407 644/644/1409 +f 637/637/1408 644/644/1409 645/645/1410 +f 645/645/1411 644/644/1411 646/646/1411 +f 645/645/1412 646/646/1413 647/647/1414 +f 647/647/1415 646/646/1415 648/648/1415 +f 647/647/1416 648/648/1416 649/649/1416 +f 649/649/1417 648/648/1417 650/650/1417 +f 649/649/1418 650/650/1419 639/639/1402 +f 639/639/1402 650/650/1419 641/641/1403 +f 644/644/1420 651/651/1421 652/652/1422 +f 641/641/1423 653/653/1424 654/654/1425 +f 644/644/1420 652/652/1422 646/646/1426 +f 643/643/1427 655/655/1428 644/644/1420 +f 644/644/1420 655/655/1428 651/651/1421 +f 643/643/1427 654/654/1425 655/655/1428 +f 641/641/1423 654/654/1425 643/643/1427 +f 646/646/1426 652/652/1422 656/656/1429 +f 648/648/1430 657/657/1431 658/658/1432 +f 648/648/1430 658/658/1432 650/650/1433 +f 650/650/1433 658/658/1432 641/641/1423 +f 641/641/1423 658/658/1432 653/653/1424 +f 646/646/1426 656/656/1429 648/648/1430 +f 648/648/1430 656/656/1429 657/657/1431 +f 625/625/1434 654/654/1435 653/653/1436 +f 625/625/1434 629/629/1437 654/654/1435 +f 654/654/1438 629/629/1439 655/655/1440 +f 655/655/1440 629/629/1439 636/636/1441 +f 655/655/1442 636/636/1443 651/651/1444 +f 651/651/1444 636/636/1443 635/635/1445 +f 651/651/1444 635/635/1445 652/652/1446 +f 652/652/1447 635/635/1448 631/631/1449 +f 652/652/1447 631/631/1449 656/656/1450 +f 656/656/1451 631/631/1452 630/630/1453 +f 656/656/1451 630/630/1453 657/657/1454 +f 657/657/1454 630/630/1453 633/633/1455 +f 657/657/1454 633/633/1455 658/658/1456 +f 658/658/1456 633/633/1455 626/626/1457 +f 658/658/1456 626/626/1457 653/653/1436 +f 653/653/1436 626/626/1457 625/625/1434 +f 632/632/1458 634/634/1459 659/659/1460 +f 659/659/1460 634/634/1459 660/660/1461 +f 627/627/1462 632/632/1463 661/661/1464 +f 661/661/1464 632/632/1463 659/659/1465 +f 628/628/1466 627/627/1467 662/662/1468 +f 662/662/1468 627/627/1467 661/661/1469 +f 634/634/1470 628/628/1471 660/660/1472 +f 660/660/1472 628/628/1471 662/662/1473 +f 660/660/440 662/662/440 661/661/440 +f 660/660/440 661/661/440 659/659/440 +f 639/639/1474 638/638/1474 649/649/1474 +f 649/649/1475 638/638/1476 640/640/1477 +f 649/649/1475 640/640/1477 647/647/1478 +f 647/647/1414 640/640/1479 645/645/1412 +f 645/645/1480 640/640/1480 637/637/1480 +f 642/642/1481 637/637/1398 639/639/1400 +f 663/663/56 664/664/56 665/665/56 +f 663/663/56 665/665/56 666/666/56 +f 666/666/56 665/665/56 667/667/56 +f 668/668/56 664/664/56 663/663/56 +f 669/669/56 668/668/56 663/663/56 +f 669/669/56 670/670/56 668/668/56 +f 671/671/56 667/667/56 672/672/56 +f 673/673/56 674/674/56 675/675/56 +f 676/676/56 674/674/56 673/673/56 +f 666/666/56 667/667/56 671/671/56 +f 677/677/56 670/670/56 669/669/56 +f 673/673/56 675/675/56 678/678/56 +f 673/673/56 678/678/56 677/677/56 +f 671/671/56 672/672/56 676/676/56 +f 677/677/56 678/678/56 670/670/56 +f 676/676/56 672/672/56 674/674/56 +f 679/679/1482 666/666/1482 671/671/1482 +f 679/679/1483 671/671/1483 680/680/1483 +f 680/680/1484 671/671/1484 676/676/1484 +f 680/680/1485 676/676/1485 681/681/1485 +f 681/681/1486 676/676/1486 673/673/1486 +f 681/681/1487 673/673/1487 682/682/1487 +f 682/682/1488 673/673/1488 677/677/1488 +f 682/682/1489 677/677/1490 683/683/1491 +f 683/683/1491 677/677/1490 669/669/1492 +f 683/683/1493 669/669/1494 663/663/1495 +f 683/683/1493 663/663/1495 684/684/1496 +f 684/684/1497 663/663/1497 685/685/1497 +f 685/685/1498 663/663/1498 666/666/1498 +f 685/685/1499 666/666/1499 679/679/1499 +f 684/684/145 686/686/145 683/683/145 +f 682/682/145 687/687/145 681/681/145 +f 682/682/145 688/688/145 687/687/145 +f 683/683/145 686/686/145 689/689/145 +f 681/681/145 687/687/145 690/690/145 +f 689/689/145 691/691/145 683/683/145 +f 683/683/145 691/691/145 682/682/145 +f 685/685/145 692/692/145 684/684/145 +f 684/684/145 692/692/145 686/686/145 +f 685/685/145 693/693/145 692/692/145 +f 682/682/145 691/691/145 688/688/145 +f 679/679/145 693/693/145 685/685/145 +f 681/681/145 690/690/145 680/680/145 +f 680/680/145 694/694/145 679/679/145 +f 680/680/145 690/690/145 694/694/145 +f 679/679/145 695/695/145 693/693/145 +f 679/679/145 694/694/145 695/695/145 +f 667/667/1500 695/695/1500 694/694/1500 +f 667/667/1501 694/694/1501 672/672/1501 +f 672/672/1502 694/694/1502 690/690/1502 +f 672/672/1503 690/690/1503 674/674/1503 +f 674/674/1504 690/690/1504 687/687/1504 +f 674/674/1505 687/687/1505 675/675/1505 +f 675/675/1506 687/687/1506 688/688/1506 +f 675/675/1507 688/688/1507 678/678/1507 +f 678/678/1508 688/688/1508 691/691/1508 +f 678/678/1509 691/691/1509 670/670/1509 +f 670/670/1510 691/691/1510 689/689/1510 +f 670/670/1511 689/689/1511 668/668/1511 +f 668/668/1512 689/689/1512 686/686/1512 +f 668/668/1513 686/686/1513 664/664/1513 +f 664/664/1514 686/686/1514 692/692/1514 +f 664/664/1515 692/692/1515 665/665/1515 +f 665/665/1516 692/692/1516 693/693/1516 +f 665/665/1517 693/693/1517 667/667/1517 +f 667/667/1518 693/693/1518 695/695/1518 +f 696/696/145 697/697/145 698/698/145 +f 696/696/145 698/698/145 699/699/145 +f 699/699/145 698/698/145 700/700/145 +f 701/701/145 702/702/145 697/697/145 +f 701/701/145 697/697/145 696/696/145 +f 703/703/145 704/704/1519 702/702/145 +f 705/705/1520 706/706/1521 707/707/1522 +f 705/705/1520 708/708/1523 706/706/1521 +f 703/703/145 702/702/145 701/701/145 +f 709/709/145 710/710/145 711/711/145 +f 705/705/1520 712/712/145 708/708/1523 +f 705/705/1520 711/711/145 712/712/145 +f 709/709/145 711/711/145 705/705/1520 +f 700/700/145 710/710/145 699/699/145 +f 699/699/145 710/710/145 709/709/145 +f 707/707/1522 704/704/1519 703/703/145 +f 707/707/1522 706/706/1521 704/704/1519 +f 713/713/1524 699/699/1525 709/709/1526 +f 713/713/1524 709/709/1526 714/714/1527 +f 714/714/1528 709/709/1528 715/715/1528 +f 715/715/1529 709/709/1529 705/705/1529 +f 715/715/1530 705/705/1530 716/716/1530 +f 716/716/1531 705/705/1531 707/707/1531 +f 716/716/1532 707/707/1532 717/717/1532 +f 717/717/1533 707/707/1533 703/703/1533 +f 717/717/1534 703/703/1534 718/718/1534 +f 718/718/1535 703/703/1535 701/701/1535 +f 718/718/1536 701/701/1536 719/719/1536 +f 719/719/1537 701/701/1537 696/696/1537 +f 719/719/1538 696/696/1538 713/713/1538 +f 713/713/1539 696/696/1539 699/699/1539 +f 717/717/56 720/720/1540 716/716/1541 +f 716/716/1541 720/720/1540 706/706/1542 +f 718/718/56 721/721/56 722/722/56 +f 719/719/56 721/721/56 718/718/56 +f 716/716/1541 723/723/1543 715/715/56 +f 718/718/56 722/722/56 717/717/56 +f 719/719/56 724/724/56 721/721/56 +f 719/719/56 725/725/56 724/724/56 +f 716/716/1541 706/706/1542 723/723/1543 +f 713/713/56 725/725/56 719/719/56 +f 717/717/56 722/722/56 720/720/1540 +f 713/713/56 726/726/56 725/725/56 +f 715/715/56 727/727/56 714/714/56 +f 714/714/56 727/727/56 728/728/56 +f 715/715/56 723/723/1543 727/727/56 +f 714/714/56 728/728/56 713/713/56 +f 713/713/56 728/728/56 726/726/56 +f 700/700/1544 726/726/1544 710/710/1544 +f 710/710/1545 726/726/1545 728/728/1545 +f 710/710/1546 728/728/1546 711/711/1546 +f 711/711/1547 728/728/1547 727/727/1547 +f 711/711/1548 727/727/1548 712/712/1548 +f 712/712/1549 727/727/1549 723/723/1549 +f 712/712/1550 723/723/1550 708/708/1550 +f 708/708/1551 723/723/1551 706/706/1551 +f 706/706/1552 720/720/1552 704/704/1552 +f 704/704/1553 720/720/1553 722/722/1553 +f 704/704/1554 722/722/1554 702/702/1554 +f 702/702/1555 722/722/1555 721/721/1555 +f 702/702/1556 721/721/1556 697/697/1556 +f 697/697/1557 721/721/1557 724/724/1557 +f 697/697/1558 724/724/1559 725/725/1560 +f 697/697/1558 725/725/1560 698/698/1561 +f 698/698/1562 725/725/1563 700/700/1564 +f 700/700/1564 725/725/1563 726/726/1565 +f 729/729/1566 730/730/1567 731/731/1568 +f 732/732/1569 733/733/1570 734/734/1571 +f 732/732/1569 731/731/1568 733/733/1570 +f 731/731/1568 730/730/1567 733/733/1570 +f 729/729/1566 735/735/1572 730/730/1567 +f 729/729/1566 736/736/1573 735/735/1572 +f 737/737/1574 736/736/1575 738/738/1576 +f 738/738/1576 736/736/1575 739/739/1577 +f 740/740/1578 741/741/1579 742/742/1580 +f 743/743/1581 742/742/1580 741/741/1579 +f 741/741/1579 744/744/1582 743/743/1581 +f 744/744/1582 745/745/1583 743/743/1581 +f 746/746/1584 745/745/1583 744/744/1582 +f 746/746/1584 747/747/1585 745/745/1583 +f 748/748/1586 749/749/1587 746/746/1584 +f 746/746/1584 749/749/1587 747/747/1585 +f 748/748/1586 750/750/1588 749/749/1587 +f 748/748/1586 751/751/1589 750/750/1588 +f 752/752/1590 751/751/1589 748/748/1586 +f 752/752/1590 753/753/1591 751/751/1589 +f 753/753/1591 752/752/1590 754/754/1592 +f 754/754/1592 755/755/1593 753/753/1591 +f 754/754/1592 756/756/1594 755/755/1593 +f 756/756/1594 754/754/1592 757/757/1595 +f 758/758/1596 734/734/1571 759/759/1597 +f 732/732/1569 734/734/1571 758/758/1596 +f 760/760/1598 761/761/1599 758/758/1596 +f 758/758/1596 761/761/1599 732/732/1569 +f 762/762/1600 763/763/1601 760/760/1602 +f 740/740/1578 763/763/1601 741/741/1579 +f 763/763/1601 762/762/1600 741/741/1579 +f 746/746/1603 744/744/1604 764/764/1605 +f 764/764/1605 744/744/1604 765/765/1606 +f 765/765/1606 744/744/1604 741/741/1607 +f 765/765/1606 741/741/1607 766/766/1608 +f 766/766/1608 741/741/1607 762/762/1600 +f 766/766/1608 762/762/1600 767/767/1609 +f 767/767/1609 762/762/1600 760/760/1602 +f 767/767/1609 760/760/1602 758/758/1610 +f 767/767/1609 758/758/1610 768/768/1611 +f 768/768/1611 758/758/1610 759/759/1612 +f 768/768/1611 759/759/1612 769/769/1613 +f 769/769/1613 759/759/1612 770/770/1614 +f 759/759/1612 771/771/1615 770/770/1614 +f 770/770/1614 771/771/1615 772/772/1616 +f 770/770/1614 772/772/1616 773/773/1617 +f 773/773/1617 772/772/1616 774/774/1618 +f 773/773/1617 774/774/1618 775/775/1619 +f 773/773/1617 775/775/1619 776/776/1620 +f 776/776/1620 775/775/1619 777/777/1621 +f 777/777/1621 775/775/1619 778/778/1622 +f 777/777/1621 778/778/1622 779/779/1623 +f 779/779/1623 778/778/1622 780/780/1624 +f 779/779/1623 780/780/1624 781/781/1625 +f 781/781/1625 780/780/1624 782/782/1626 +f 781/781/1625 782/782/1626 783/783/1627 +f 783/783/1627 782/782/1626 784/784/1628 +f 783/783/1627 784/784/1628 785/785/1629 +f 785/785/1629 784/784/1628 786/786/1630 +f 785/785/1629 786/786/1630 787/787/1631 +f 785/785/1629 787/787/1631 788/788/1632 +f 757/757/1633 788/788/1632 787/787/1631 +f 788/788/1632 757/757/1633 789/789/1634 +f 789/789/1634 757/757/1633 754/754/1635 +f 754/754/1635 790/790/1636 789/789/1634 +f 790/790/1636 754/754/1635 752/752/1637 +f 790/790/1636 752/752/1637 748/748/1638 +f 790/790/1636 748/748/1638 791/791/1639 +f 791/791/1639 748/748/1638 746/746/1603 +f 746/746/1603 764/764/1605 791/791/1639 +f 792/792/1640 793/793/1641 794/794/1642 +f 795/795/1643 796/796/1644 797/797/1645 +f 795/795/1643 798/798/1646 794/794/1642 +f 797/797/1645 798/798/1646 795/795/1643 +f 798/798/1646 799/799/1647 794/794/1642 +f 756/756/1648 794/794/1642 799/799/1647 +f 794/794/1642 756/756/1648 757/757/1633 +f 787/787/1631 792/792/1640 794/794/1642 +f 757/757/1633 787/787/1631 794/794/1642 +f 800/800/1649 801/801/1650 735/735/1572 +f 802/802/1651 803/803/1652 804/804/1653 +f 801/801/1650 730/730/1567 735/735/1572 +f 801/801/1650 733/733/1654 730/730/1567 +f 802/802/1651 805/805/1655 801/801/1650 +f 806/806/1656 802/802/1651 804/804/1653 +f 733/733/1654 801/801/1650 734/734/1657 +f 734/734/1657 801/801/1650 759/759/1658 +f 759/759/1658 801/801/1650 807/807/1659 +f 801/801/1650 805/805/1655 807/807/1659 +f 807/807/1660 771/771/1615 759/759/1612 +f 772/772/1661 771/771/1615 805/805/1662 +f 786/786/1630 792/792/1663 787/787/1631 +f 792/792/1663 786/786/1630 808/808/1664 +f 808/808/1664 786/786/1630 784/784/1665 +f 771/771/1615 807/807/1660 805/805/1662 +f 809/809/1666 800/800/1649 810/810/1667 +f 810/810/1667 800/800/1649 811/811/1668 +f 810/810/1667 811/811/1668 812/812/1669 +f 812/812/1669 811/811/1668 813/813/1670 +f 812/812/1669 813/813/1670 814/814/1671 +f 814/814/1671 813/813/1670 815/815/1672 +f 814/814/1671 815/815/1672 816/816/1673 +f 816/816/1673 815/815/1672 817/817/1674 +f 817/817/1674 815/815/1672 818/818/1675 +f 817/817/1674 818/818/1675 819/819/1676 +f 817/817/1674 819/819/1676 820/820/1677 +f 820/820/1677 819/819/1676 797/797/1645 +f 820/820/1677 797/797/1645 796/796/1644 +f 821/821/1678 822/822/1679 823/823/1680 +f 823/823/1680 822/822/1679 824/824/1681 +f 825/825/1682 826/826/1683 827/827/1684 +f 827/827/1684 826/826/1683 828/828/1685 +f 800/800/1649 809/809/1666 801/801/1650 +f 796/796/145 809/809/145 817/817/145 +f 801/801/145 809/809/145 825/825/145 +f 796/796/145 817/817/145 820/820/145 +f 825/825/145 809/809/145 826/826/145 +f 816/816/145 810/810/145 814/814/145 +f 826/826/145 809/809/145 824/824/145 +f 809/809/145 796/796/145 824/824/145 +f 816/816/145 809/809/145 810/810/145 +f 809/809/145 816/816/145 817/817/145 +f 796/796/145 823/823/145 824/824/145 +f 810/810/145 812/812/145 814/814/145 +f 796/796/145 795/795/145 823/823/145 +f 824/824/1681 822/822/1679 826/826/1683 +f 826/826/1683 822/822/1679 828/828/1685 +f 777/777/1621 829/829/1686 830/830/1687 +f 777/777/1621 830/830/1687 776/776/1620 +f 776/776/1620 830/830/1687 773/773/1617 +f 773/773/1617 830/830/1687 831/831/1688 +f 773/773/1617 831/831/1688 770/770/1614 +f 770/770/1614 831/831/1688 832/832/1689 +f 770/770/1614 832/832/1689 769/769/1613 +f 769/769/1613 832/832/1689 833/833/1690 +f 769/769/1613 833/833/1690 768/768/1611 +f 768/768/1611 833/833/1690 834/834/1691 +f 768/768/1611 834/834/1691 767/767/1609 +f 767/767/1609 834/834/1691 835/835/1692 +f 767/767/1609 835/835/1692 766/766/1608 +f 766/766/1608 835/835/1692 765/765/1606 +f 765/765/1606 835/835/1692 836/836/1693 +f 765/765/1606 836/836/1693 764/764/1605 +f 764/764/1605 836/836/1693 837/837/1694 +f 764/764/1605 837/837/1694 791/791/1639 +f 791/791/1639 837/837/1694 838/838/1695 +f 791/791/1639 838/838/1695 790/790/1636 +f 790/790/1636 838/838/1695 839/839/1696 +f 790/790/1636 839/839/1696 789/789/1634 +f 789/789/1634 839/839/1696 788/788/1632 +f 788/788/1632 839/839/1696 840/840/1697 +f 788/788/1632 840/840/1697 785/785/1629 +f 785/785/1629 840/840/1697 841/841/1698 +f 785/785/1629 841/841/1698 783/783/1627 +f 783/783/1627 841/841/1698 842/842/1699 +f 783/783/1627 842/842/1699 781/781/1625 +f 781/781/1625 842/842/1699 779/779/1623 +f 779/779/1623 842/842/1699 843/843/1700 +f 779/779/1623 843/843/1700 829/829/1686 +f 779/779/1623 829/829/1686 777/777/1621 +f 797/797/1645 844/844/1701 845/845/1702 +f 797/797/1645 845/845/1702 798/798/1646 +f 844/844/1701 797/797/1645 846/846/1703 +f 846/846/1703 797/797/1645 819/819/1676 +f 818/818/1675 847/847/1704 819/819/1676 +f 819/819/1676 847/847/1704 846/846/1703 +f 815/815/1672 848/848/1705 818/818/1675 +f 848/848/1705 847/847/1704 818/818/1675 +f 849/849/1706 848/848/1705 815/815/1672 +f 813/813/1670 850/850/1707 815/815/1672 +f 850/850/1707 849/849/1706 815/815/1672 +f 850/850/1707 813/813/1670 851/851/1708 +f 851/851/1708 813/813/1670 811/811/1668 +f 851/851/1708 811/811/1668 852/852/1709 +f 852/852/1709 811/811/1668 853/853/1710 +f 853/853/1710 811/811/1668 800/800/1649 +f 853/853/1710 800/800/1649 737/737/1574 +f 736/736/1573 737/737/1574 800/800/1649 +f 735/735/1572 736/736/1573 800/800/1649 +f 825/825/1711 827/827/1712 801/801/1713 +f 801/801/1713 827/827/1712 802/802/1714 +f 821/821/1715 823/823/1716 795/795/1717 +f 821/821/1715 795/795/1717 794/794/1718 +f 854/854/1719 799/799/1647 798/798/1646 +f 799/799/1647 854/854/1719 855/855/1720 +f 855/855/1720 755/755/1593 756/756/1594 +f 799/799/1647 855/855/1720 756/756/1594 +f 856/856/1721 854/854/1719 798/798/1646 +f 845/845/1702 856/856/1721 798/798/1646 +f 742/742/1580 743/743/1581 745/745/1583 +f 844/844/1701 857/857/1722 845/845/1723 +f 857/857/1722 858/858/1724 845/845/1723 +f 858/858/1725 857/857/1722 859/859/1726 +f 844/844/1701 846/846/1703 860/860/1727 +f 861/861/1728 849/849/1706 850/850/1707 +f 851/851/1708 852/852/1709 862/862/1729 +f 863/863/1730 853/853/1710 737/737/1574 +f 863/863/1730 737/737/1574 738/738/1576 +f 857/857/1722 844/844/1701 860/860/1727 +f 860/860/1727 846/846/1703 864/864/1731 +f 864/864/1731 846/846/1703 847/847/1704 +f 864/864/1731 847/847/1704 848/848/1732 +f 848/848/1732 849/849/1706 861/861/1728 +f 861/861/1728 850/850/1707 865/865/1733 +f 865/865/1733 850/850/1707 851/851/1708 +f 865/865/1733 851/851/1708 862/862/1729 +f 852/852/1709 853/853/1710 863/863/1730 +f 857/857/1722 860/860/1727 866/866/1734 +f 866/866/1734 860/860/1727 864/864/1731 +f 867/867/1735 848/848/1732 861/861/1728 +f 862/862/1729 852/852/1709 863/863/1730 +f 867/867/1735 864/864/1731 848/848/1732 +f 861/861/1728 865/865/1733 862/862/1729 +f 866/866/1734 864/864/1731 867/867/1735 +f 868/868/1736 869/869/1737 751/751/1738 +f 751/751/1738 869/869/1737 870/870/1739 +f 751/751/1738 870/870/1739 750/750/1740 +f 871/871/1741 872/872/1742 870/870/1739 +f 870/870/1739 872/872/1742 750/750/1740 +f 870/870/1743 869/869/1744 873/873/1745 +f 870/870/1743 873/873/1745 874/874/1746 +f 874/874/1746 873/873/1745 875/875/1747 +f 874/874/1746 875/875/1747 876/876/1748 +f 876/876/1749 875/875/1750 877/877/1751 +f 876/876/1749 877/877/1751 878/878/1752 +f 755/755/1753 855/855/1754 879/879/1755 +f 880/880/1756 755/755/1753 879/879/1755 +f 880/880/1756 753/753/1757 755/755/1753 +f 753/753/1757 880/880/1756 881/881/1758 +f 753/753/1759 881/881/1760 751/751/1761 +f 868/868/1762 751/751/1761 881/881/1760 +f 879/879/1755 855/855/1754 877/877/1763 +f 856/856/1764 882/882/1765 878/878/1766 +f 878/878/1766 854/854/1767 856/856/1764 +f 877/877/1763 854/854/1767 878/878/1766 +f 856/856/1764 845/845/1768 882/882/1765 +f 855/855/1754 854/854/1767 877/877/1763 +f 882/882/56 876/876/56 878/878/56 +f 883/883/56 871/871/56 874/874/56 +f 871/871/56 870/870/56 874/874/56 +f 884/884/56 883/883/56 874/874/56 +f 882/882/56 884/884/56 874/874/56 +f 876/876/56 882/882/56 874/874/56 +f 845/845/1769 858/858/1770 884/884/1771 +f 884/884/1772 858/858/1773 859/859/1774 +f 882/882/1775 845/845/1769 884/884/1771 +f 884/884/1772 859/859/1774 883/883/1776 +f 883/883/1777 859/859/1778 871/871/1779 +f 871/871/1779 859/859/1778 872/872/1780 +f 885/885/1781 886/886/1782 887/887/1783 +f 887/887/1783 886/886/1782 888/888/1784 +f 887/887/1785 888/888/1786 889/889/1787 +f 889/889/1787 888/888/1786 890/890/1788 +f 889/889/1789 890/890/1790 891/891/1791 +f 889/889/1789 891/891/1791 892/892/1792 +f 892/892/1793 891/891/1794 893/893/1795 +f 893/893/1795 740/740/1796 892/892/1793 +f 892/892/1793 740/740/1796 742/742/1797 +f 894/894/1798 895/895/1799 742/742/1797 +f 742/742/1797 895/895/1799 892/892/1793 +f 881/881/56 879/879/56 868/868/56 +f 886/886/56 896/896/56 893/893/56 +f 873/873/56 869/869/56 877/877/56 +f 877/877/56 875/875/56 873/873/56 +f 880/880/56 879/879/56 881/881/56 +f 879/879/56 877/877/56 868/868/56 +f 869/869/56 868/868/56 877/877/56 +f 896/896/56 897/897/56 893/893/56 +f 888/888/56 886/886/56 890/890/56 +f 896/896/56 898/898/56 897/897/56 +f 890/890/56 886/886/56 891/891/56 +f 893/893/56 891/891/56 886/886/56 +f 731/731/1800 896/896/1801 886/886/1782 +f 729/729/1802 885/885/1781 899/899/1803 +f 729/729/1802 731/731/1800 885/885/1781 +f 885/885/1781 731/731/1800 886/886/1782 +f 899/899/1803 736/736/1804 729/729/1802 +f 893/893/1795 763/763/1805 740/740/1796 +f 897/897/1806 763/763/1805 893/893/1795 +f 897/897/1806 760/760/1807 763/763/1805 +f 761/761/1808 760/760/1807 898/898/1809 +f 898/898/1809 760/760/1807 897/897/1806 +f 898/898/1809 896/896/1810 732/732/1811 +f 732/732/1811 761/761/1808 898/898/1809 +f 731/731/1800 732/732/1812 896/896/1801 +f 736/736/1813 899/899/1814 900/900/1815 +f 900/900/1815 739/739/1816 736/736/1813 +f 901/901/1817 902/902/1818 900/900/1819 +f 900/900/1819 902/902/1818 739/739/1820 +f 895/895/1821 894/894/1822 902/902/1823 +f 895/895/1821 902/902/1823 901/901/1824 +f 895/895/56 889/889/56 892/892/56 +f 899/899/56 885/885/56 887/887/56 +f 901/901/56 889/889/56 895/895/56 +f 901/901/56 900/900/56 889/889/56 +f 889/889/56 900/900/56 899/899/56 +f 899/899/56 887/887/56 889/889/56 +f 902/902/1825 738/738/1826 739/739/1827 +f 738/738/1826 902/902/1825 894/894/1828 +f 863/863/1730 738/738/1826 894/894/1828 +f 872/872/1829 867/867/1735 861/861/1728 +f 894/894/1828 742/742/1580 745/745/1583 +f 862/862/1729 894/894/1828 861/861/1728 +f 872/872/1829 866/866/1734 867/867/1735 +f 872/872/1829 894/894/1828 745/745/1583 +f 747/747/1830 872/872/1829 745/745/1583 +f 749/749/1831 872/872/1829 747/747/1830 +f 861/861/1728 894/894/1828 872/872/1829 +f 750/750/1832 872/872/1829 749/749/1831 +f 863/863/1730 894/894/1828 862/862/1729 +f 857/857/1722 866/866/1734 872/872/1829 +f 859/859/1726 857/857/1722 872/872/1829 +f 903/903/1833 904/904/1834 905/905/1835 +f 903/903/1833 905/905/1835 906/906/1836 +f 907/907/1837 908/908/1838 909/909/1839 +f 908/908/1838 907/907/1837 910/910/1840 +f 911/911/1841 912/912/1842 913/913/1843 +f 911/911/1841 913/913/1843 914/914/1844 +f 914/914/1844 913/913/1843 915/915/1845 +f 916/916/1846 917/917/1847 912/912/1842 +f 916/916/1846 912/912/1842 911/911/1841 +f 908/908/1838 910/910/1840 918/918/1848 +f 918/918/1848 910/910/1840 904/904/1834 +f 907/907/1837 909/909/1839 919/919/1849 +f 920/920/1850 921/921/1851 775/775/1852 +f 920/920/1850 775/775/1852 922/922/1853 +f 923/923/1854 922/922/1853 775/775/1852 +f 775/775/1852 774/774/1855 923/923/1854 +f 924/924/1856 925/925/1857 793/793/1858 +f 925/925/1857 924/924/1856 926/926/1859 +f 925/925/1857 926/926/1859 927/927/1860 +f 805/805/1655 802/802/1651 928/928/1861 +f 928/928/1861 802/802/1651 806/806/1656 +f 804/804/1653 803/803/1652 929/929/1862 +f 929/929/1862 803/803/1652 930/930/1863 +f 929/929/1862 930/930/1863 931/931/1864 +f 931/931/1864 930/930/1863 932/932/1865 +f 931/931/1864 932/932/1865 933/933/1866 +f 933/933/1866 932/932/1865 934/934/1867 +f 933/933/1866 934/934/1867 935/935/1868 +f 935/935/1868 934/934/1867 936/936/1869 +f 935/935/1868 936/936/1869 937/937/1870 +f 937/937/1870 936/936/1869 938/938/1871 +f 937/937/1870 938/938/1871 939/939/1872 +f 939/939/1872 938/938/1871 940/940/1873 +f 939/939/1872 940/940/1873 941/941/1874 +f 941/941/1874 940/940/1873 925/925/1857 +f 941/941/1874 925/925/1857 927/927/1860 +f 782/782/1875 808/808/1664 784/784/1665 +f 942/942/1876 943/943/1877 782/782/1875 +f 944/944/1878 942/942/1876 780/780/1879 +f 780/780/1879 942/942/1876 782/782/1875 +f 944/944/1878 780/780/1879 945/945/1880 +f 946/946/1881 947/947/1882 927/927/1860 +f 946/946/1881 927/927/1860 948/948/1883 +f 949/949/1884 948/948/1883 927/927/1860 +f 926/926/1859 949/949/1884 927/927/1860 +f 950/950/1885 951/951/1886 804/804/1653 +f 950/950/1885 804/804/1653 929/929/1862 +f 952/952/1887 950/950/1885 929/929/1862 +f 952/952/1887 929/929/1862 953/953/1888 +f 953/953/1888 929/929/1862 931/931/1864 +f 931/931/1864 954/954/1889 953/953/1888 +f 954/954/1889 931/931/1864 933/933/1866 +f 955/955/1890 954/954/1889 933/933/1866 +f 955/955/1890 933/933/1866 935/935/1868 +f 956/956/1891 955/955/1890 935/935/1868 +f 935/935/1868 957/957/1892 956/956/1891 +f 957/957/1892 935/935/1868 937/937/1870 +f 937/937/1870 958/958/1893 957/957/1892 +f 958/958/1893 937/937/1870 939/939/1872 +f 939/939/1872 959/959/1894 958/958/1893 +f 959/959/1894 939/939/1872 941/941/1874 +f 941/941/1874 960/960/1895 959/959/1894 +f 960/960/1895 941/941/1874 961/961/1896 +f 961/961/1896 941/941/1874 927/927/1860 +f 927/927/1860 947/947/1882 961/961/1896 +f 804/804/1653 951/951/1886 962/962/1897 +f 804/804/1653 962/962/1897 963/963/1898 +f 804/804/1653 963/963/1898 806/806/1656 +f 928/928/1861 806/806/1656 964/964/1899 +f 965/965/1900 928/928/1861 964/964/1899 +f 966/966/1901 967/967/1902 964/964/1899 +f 909/909/1903 967/967/1902 968/968/1904 +f 963/963/1898 966/966/1901 806/806/1656 +f 772/772/1661 805/805/1662 969/969/1905 +f 969/969/1905 805/805/1662 928/928/1861 +f 774/774/1855 772/772/1661 969/969/1905 +f 970/970/1906 774/774/1855 969/969/1905 +f 965/965/1900 969/969/1905 928/928/1861 +f 970/970/1906 969/969/1905 965/965/1900 +f 923/923/1854 774/774/1855 970/970/1906 +f 964/964/1899 806/806/1656 966/966/1901 +f 966/966/1901 968/968/1904 967/967/1902 +f 971/971/1907 972/972/1908 973/973/1909 +f 792/792/1663 808/808/1664 793/793/1910 +f 793/793/1910 808/808/1664 974/974/1911 +f 793/793/1910 974/974/1911 924/924/1856 +f 808/808/1664 975/975/1912 974/974/1911 +f 924/924/1856 974/974/1911 971/971/1907 +f 943/943/1877 975/975/1912 782/782/1875 +f 782/782/1875 975/975/1912 808/808/1664 +f 924/924/1856 971/971/1907 926/926/1859 +f 971/971/1907 973/973/1909 926/926/1859 +f 926/926/1859 973/973/1909 949/949/1884 +f 967/967/1913 909/909/1914 976/976/1915 +f 976/976/1915 909/909/1914 977/977/1916 +f 978/978/1917 964/964/1918 976/976/1919 +f 976/976/1919 964/964/1918 967/967/1920 +f 978/978/1921 979/979/1922 964/964/1923 +f 979/979/1922 965/965/1924 964/964/1923 +f 980/980/1925 965/965/1924 979/979/1922 +f 970/970/1926 965/965/1924 980/980/1925 +f 970/970/1927 980/980/1928 981/981/1929 +f 981/981/1929 923/923/1930 970/970/1927 +f 982/982/1931 923/923/1932 981/981/1933 +f 922/922/1934 923/923/1932 982/982/1931 +f 983/983/1935 920/920/1936 922/922/1934 +f 983/983/1935 922/922/1934 982/982/1931 +f 983/983/1937 984/984/1938 920/920/1939 +f 985/985/1940 984/984/1938 983/983/1937 +f 977/977/1941 909/909/1942 908/908/1943 +f 977/977/1941 908/908/1943 985/985/1944 +f 985/985/1940 908/908/1945 984/984/1938 +f 986/986/1946 942/942/1947 944/944/1948 +f 986/986/1946 943/943/1949 942/942/1947 +f 987/987/1950 943/943/1949 986/986/1946 +f 987/987/1950 975/975/1951 943/943/1949 +f 988/988/1952 975/975/1951 987/987/1950 +f 988/988/1953 989/989/1954 974/974/1955 +f 988/988/1953 974/974/1955 975/975/1956 +f 974/974/1957 990/990/1958 971/971/1959 +f 990/990/1958 974/974/1957 989/989/1960 +f 972/972/1961 971/971/1962 990/990/1963 +f 991/991/1964 972/972/1961 990/990/1963 +f 992/992/1965 917/917/1966 972/972/1967 +f 992/992/1965 972/972/1967 991/991/1968 +f 993/993/1969 994/994/1970 992/992/1971 +f 994/994/1972 993/993/1973 944/944/1948 +f 986/986/1946 944/944/1948 993/993/1973 +f 992/992/1971 994/994/1970 912/912/1974 +f 992/992/1965 912/912/1975 917/917/1966 +f 906/906/1976 995/995/1977 962/962/1978 +f 996/996/1979 962/962/1978 995/995/1977 +f 963/963/1980 962/962/1978 996/996/1979 +f 997/997/1981 963/963/1980 996/996/1979 +f 966/966/1982 963/963/1980 997/997/1981 +f 998/998/1983 966/966/1982 997/997/1981 +f 999/999/1984 968/968/1985 998/998/1983 +f 998/998/1983 968/968/1985 966/966/1982 +f 919/919/1986 968/968/1985 999/999/1984 +f 995/995/1977 906/906/1976 905/905/1987 +f 995/995/1977 905/905/1987 1000/1000/1988 +f 1000/1000/1988 905/905/1987 904/904/1989 +f 1000/1000/1990 904/904/1991 1001/1001/1992 +f 1001/1001/1992 904/904/1991 910/910/1993 +f 1001/1001/1994 910/910/1995 1002/1002/1996 +f 1002/1002/1996 910/910/1995 907/907/1997 +f 1002/1002/1998 907/907/1999 999/999/1984 +f 999/999/1984 907/907/1999 919/919/1986 +f 1003/1003/2000 916/916/2001 1004/1004/2002 +f 1003/1003/2000 973/973/2003 916/916/2001 +f 1005/1005/2004 973/973/2003 1003/1003/2000 +f 1005/1005/2004 949/949/2005 973/973/2003 +f 1006/1006/2006 949/949/2005 1005/1005/2004 +f 948/948/2007 949/949/2005 1006/1006/2006 +f 1007/1007/2008 948/948/2007 1006/1006/2006 +f 1007/1007/2008 946/946/2009 948/948/2007 +f 1008/1008/2010 1009/1009/2011 946/946/2009 +f 1008/1008/2010 946/946/2009 1007/1007/2008 +f 1008/1008/2010 1010/1010/2012 1009/1009/2011 +f 1004/1004/2002 916/916/2001 911/911/2013 +f 1004/1004/2002 911/911/2013 1011/1011/2014 +f 1011/1011/2015 911/911/2016 1012/1012/2017 +f 1012/1012/2017 911/911/2016 914/914/2018 +f 1012/1012/2019 914/914/2020 1013/1013/2021 +f 1013/1013/2021 914/914/2020 1014/1014/2022 +f 1013/1013/2023 1014/1014/2024 1010/1010/2012 +f 1013/1013/2023 1010/1010/2012 1008/1008/2010 +f 951/951/1886 1015/1015/2025 962/962/2026 +f 962/962/2026 1015/1015/2025 906/906/1836 +f 906/906/1836 1015/1015/2025 903/903/1833 +f 1016/1016/2027 1017/1017/2028 958/958/1893 +f 956/956/2029 1018/1018/2030 1019/1019/2031 +f 956/956/2029 1019/1019/2031 955/955/1890 +f 1019/1019/2031 1020/1020/2032 954/954/1889 +f 1019/1019/2031 1021/1021/2033 1020/1020/2032 +f 1020/1020/2032 953/953/1888 954/954/1889 +f 961/961/1896 947/947/1882 1022/1022/2034 +f 1022/1022/2034 947/947/1882 1023/1023/2035 +f 961/961/1896 1022/1022/2034 960/960/1895 +f 1024/1024/2036 960/960/1895 1022/1022/2034 +f 1022/1022/2034 1016/1016/2027 1024/1024/2036 +f 959/959/1894 960/960/1895 1024/1024/2036 +f 958/958/1893 959/959/1894 1024/1024/2036 +f 958/958/1893 1024/1024/2036 1016/1016/2027 +f 957/957/1892 958/958/1893 1017/1017/2028 +f 956/956/2029 957/957/1892 1017/1017/2028 +f 1017/1017/2028 1018/1018/2030 956/956/2029 +f 1019/1019/2031 954/954/1889 955/955/1890 +f 952/952/1887 953/953/1888 1021/1021/2033 +f 1021/1021/2033 953/953/1888 1020/1020/2032 +f 1021/1021/2033 903/903/1833 1015/1015/2025 +f 1021/1021/2033 1015/1015/2025 952/952/1887 +f 952/952/1887 1015/1015/2025 950/950/1885 +f 950/950/1885 1015/1015/2025 951/951/1886 +f 947/947/1882 946/946/2037 1023/1023/2035 +f 1023/1023/2035 946/946/2037 1009/1009/2038 +f 1023/1023/2039 1009/1009/2040 1010/1010/2041 +f 909/909/1903 968/968/1904 919/919/2042 +f 917/917/2043 916/916/2044 972/972/1908 +f 916/916/2044 973/973/1909 972/972/1908 +f 1025/1025/2045 775/775/2046 1026/1026/2047 +f 1026/1026/2047 775/775/2046 921/921/2048 +f 1026/1026/2047 921/921/2048 1027/1027/2049 +f 780/780/2050 1028/1028/2051 945/945/2052 +f 945/945/2052 1028/1028/2051 1029/1029/2053 +f 945/945/2052 1029/1029/2053 1030/1030/2054 +f 1031/1031/2055 1026/1026/2047 1027/1027/2049 +f 1031/1031/2055 1032/1032/2056 1026/1026/2047 +f 1032/1032/2056 1031/1031/2055 1033/1033/2057 +f 1032/1032/2056 1033/1033/2057 1034/1034/2058 +f 1034/1034/2058 1035/1035/2059 1032/1032/2056 +f 1036/1036/2060 1035/1035/2059 1034/1034/2058 +f 1036/1036/2060 1037/1037/2061 1035/1035/2059 +f 1038/1038/2062 1037/1037/2061 1036/1036/2060 +f 1037/1037/2061 1038/1038/2062 1039/1039/2063 +f 1039/1039/2063 1038/1038/2062 1040/1040/2064 +f 1039/1039/2063 1040/1040/2064 1029/1029/2053 +f 1041/1041/2065 1029/1029/2053 1040/1040/2064 +f 1030/1030/2054 1029/1029/2053 1041/1041/2065 +f 1042/1042/2066 994/994/2067 944/944/2068 +f 1042/1042/2066 944/944/2068 945/945/2052 +f 1042/1042/2066 945/945/2052 1030/1030/2054 +f 1036/1036/2060 1043/1043/2069 1038/1038/2062 +f 1040/1040/2064 1044/1044/2070 1041/1041/2065 +f 1027/1027/2071 1045/1045/2072 1046/1046/2073 +f 1027/1027/2071 1046/1046/2073 1031/1031/2074 +f 1033/1033/2075 1047/1047/2076 1034/1034/2077 +f 1034/1034/2077 1047/1047/2076 1048/1048/2078 +f 1034/1034/2077 1048/1048/2078 1036/1036/2060 +f 1036/1036/2060 1048/1048/2078 1043/1043/2069 +f 1043/1043/2069 1049/1049/2079 1038/1038/2062 +f 1038/1038/2062 1049/1049/2079 1040/1040/2064 +f 1040/1040/2064 1049/1049/2079 1044/1044/2070 +f 1041/1041/2065 1042/1042/2066 1030/1030/2054 +f 1042/1042/2066 1041/1041/2065 913/913/1843 +f 913/913/1843 1041/1041/2065 1044/1044/2070 +f 1047/1047/2076 1033/1033/2075 1050/1050/2080 +f 1050/1050/2080 1033/1033/2075 1031/1031/2074 +f 1046/1046/2073 1050/1050/2080 1031/1031/2074 +f 1043/1043/2069 1051/1051/2081 1049/1049/2079 +f 1049/1049/2079 915/915/2082 1044/1044/2070 +f 912/912/1842 1042/1042/2066 913/913/1843 +f 913/913/1843 1044/1044/2070 915/915/2082 +f 1051/1051/2081 1043/1043/2069 1048/1048/2083 +f 994/994/2067 1042/1042/2066 912/912/1842 +f 915/915/2082 1049/1049/2079 1051/1051/2081 +f 1051/1051/2081 1048/1048/2083 1052/1052/2084 +f 1052/1052/2084 1048/1048/2083 1047/1047/2076 +f 1052/1052/2084 1047/1047/2076 1050/1050/2080 +f 1050/1050/2080 1046/1046/2085 918/918/1848 +f 918/918/1848 1046/1046/2085 908/908/2086 +f 908/908/2086 1046/1046/2085 1045/1045/2072 +f 908/908/2086 1045/1045/2072 984/984/2087 +f 1052/1052/2084 1050/1050/2080 918/918/1848 +f 920/920/2088 984/984/2087 1045/1045/2072 +f 920/920/2088 1045/1045/2072 921/921/2089 +f 921/921/2089 1045/1045/2072 1027/1027/2071 +f 903/903/1833 1021/1021/2033 1019/1019/2031 +f 903/903/1833 1019/1019/2031 1018/1018/2030 +f 904/904/1834 903/903/1833 1052/1052/2084 +f 1052/1052/2084 903/903/1833 1051/1051/2090 +f 1016/1016/2027 1022/1022/2034 903/903/1833 +f 1018/1018/2030 1017/1017/2028 903/903/1833 +f 1017/1017/2028 1016/1016/2027 903/903/1833 +f 1022/1022/2034 1023/1023/2039 903/903/1833 +f 1023/1023/2039 1051/1051/2090 903/903/1833 +f 914/914/1844 915/915/1845 1014/1014/2091 +f 915/915/1845 1051/1051/2090 1014/1014/2091 +f 1052/1052/2084 918/918/1848 904/904/1834 +f 1051/1051/2090 1023/1023/2039 1014/1014/2091 +f 1010/1010/2041 1014/1014/2091 1023/1023/2039 +f 1035/1035/145 1037/1037/145 1029/1029/145 +f 1026/1026/145 1032/1032/145 1029/1029/145 +f 1037/1037/145 1039/1039/145 1029/1029/145 +f 1025/1025/145 1026/1026/145 1029/1029/145 +f 1029/1029/145 1028/1028/145 1025/1025/145 +f 1029/1029/145 1032/1032/145 1035/1035/145 +f 1053/1053/2092 1054/1054/2093 1055/1055/2094 +f 1056/1056/2095 1057/1057/2096 1058/1058/2097 +f 1059/1059/2098 1060/1060/2099 1061/1061/2100 +f 1059/1059/2098 1061/1061/2100 1062/1062/2101 +f 1063/1063/2102 1059/1059/2098 1064/1064/2103 +f 1058/1058/2097 1057/1057/2096 1065/1065/2104 +f 1062/1062/2101 1066/1066/2105 1054/1054/2093 +f 1065/1065/2104 1063/1063/2102 1064/1064/2103 +f 1058/1058/2097 1065/1065/2104 1064/1064/2103 +f 1067/1067/2106 1068/1068/2107 1056/1056/2095 +f 1062/1062/2101 1054/1054/2093 1053/1053/2092 +f 1061/1061/2100 1066/1066/2105 1062/1062/2101 +f 1059/1059/2098 1063/1063/2102 1060/1060/2099 +f 1067/1067/2106 1056/1056/2095 1058/1058/2097 +f 1055/1055/2094 1068/1068/2107 1053/1053/2092 +f 1053/1053/2092 1068/1068/2107 1067/1067/2106 +f 1069/1069/2108 1070/1070/2109 1071/1071/2110 +f 1072/1072/2111 1070/1070/2109 1069/1069/2108 +f 1069/1069/2108 1073/1073/2112 1072/1072/2111 +f 1074/1074/2113 1075/1075/2114 1076/1076/2115 +f 1076/1076/2115 1075/1075/2114 1077/1077/2116 +f 1076/1076/2117 1077/1077/2118 1078/1078/2119 +f 1076/1076/2117 1078/1078/2119 1073/1073/2120 +f 1073/1073/2120 1078/1078/2119 1079/1079/2121 +f 1078/1078/2119 1080/1080/2122 1079/1079/2121 +f 1079/1079/2123 1080/1080/2124 1081/1081/2125 +f 1079/1079/2123 1081/1081/2125 1082/1082/2126 +f 1082/1082/2127 1081/1081/2128 1083/1083/2129 +f 1082/1082/2127 1083/1083/2129 1070/1070/2130 +f 1070/1070/2130 1083/1083/2129 1084/1084/2131 +f 1070/1070/2130 1084/1084/2131 1085/1085/2132 +f 1085/1085/2133 1084/1084/2134 1086/1086/2135 +f 1084/1084/2134 1087/1087/2136 1086/1086/2135 +f 1086/1086/2137 1087/1087/2138 1088/1088/2139 +f 1086/1086/2137 1088/1088/2139 1074/1074/2140 +f 1074/1074/2140 1088/1088/2139 1075/1075/2141 +f 1075/1075/2142 1089/1089/2143 1077/1077/2144 +f 1081/1081/2145 1090/1090/2146 1083/1083/2147 +f 1083/1083/2147 1090/1090/2146 1091/1091/2148 +f 1078/1078/2149 1092/1092/2150 1080/1080/2151 +f 1075/1075/2142 1093/1093/2152 1089/1089/2143 +f 1087/1087/2153 1094/1094/2154 1095/1095/2155 +f 1088/1088/2156 1096/1096/2157 1075/1075/2142 +f 1075/1075/2142 1096/1096/2157 1093/1093/2152 +f 1087/1087/2153 1095/1095/2155 1088/1088/2156 +f 1088/1088/2156 1095/1095/2155 1096/1096/2157 +f 1092/1092/2150 1097/1097/2158 1080/1080/2151 +f 1080/1080/2151 1097/1097/2158 1081/1081/2145 +f 1081/1081/2145 1097/1097/2158 1090/1090/2146 +f 1077/1077/2144 1089/1089/2143 1078/1078/2149 +f 1078/1078/2149 1089/1089/2143 1092/1092/2150 +f 1084/1084/2159 1098/1098/2160 1094/1094/2154 +f 1084/1084/2159 1094/1094/2154 1087/1087/2153 +f 1083/1083/2147 1091/1091/2148 1084/1084/2159 +f 1084/1084/2159 1091/1091/2148 1098/1098/2160 +f 1089/1089/2161 1093/1093/2162 1054/1054/2163 +f 1054/1054/2163 1066/1066/2164 1089/1089/2161 +f 1089/1089/2161 1066/1066/2164 1061/1061/2165 +f 1089/1089/2161 1061/1061/2165 1092/1092/2166 +f 1061/1061/2165 1060/1060/2167 1092/1092/2166 +f 1092/1092/2166 1060/1060/2167 1097/1097/2168 +f 1060/1060/2167 1063/1063/2169 1097/1097/2168 +f 1097/1097/2168 1063/1063/2169 1090/1090/2170 +f 1063/1063/2169 1065/1065/2171 1090/1090/2170 +f 1090/1090/2170 1065/1065/2171 1091/1091/2172 +f 1091/1091/2172 1065/1065/2171 1057/1057/2173 +f 1091/1091/2172 1057/1057/2173 1098/1098/2174 +f 1098/1098/2175 1057/1057/2176 1056/1056/2177 +f 1098/1098/2175 1056/1056/2177 1094/1094/2178 +f 1094/1094/2178 1056/1056/2177 1068/1068/2179 +f 1094/1094/2178 1068/1068/2179 1095/1095/2180 +f 1095/1095/2181 1068/1068/2182 1055/1055/2183 +f 1095/1095/2181 1055/1055/2183 1096/1096/2184 +f 1096/1096/2184 1055/1055/2183 1093/1093/2162 +f 1093/1093/2162 1055/1055/2183 1054/1054/2163 +f 1058/1058/2185 1064/1064/2185 1099/1099/2185 +f 1099/1099/2185 1064/1064/2185 1100/1100/2185 +f 1067/1067/2186 1058/1058/2186 1101/1101/2186 +f 1101/1101/2186 1058/1058/2186 1099/1099/2186 +f 1053/1053/2187 1067/1067/2187 1102/1102/2187 +f 1102/1102/2187 1067/1067/2187 1101/1101/2187 +f 1062/1062/2188 1053/1053/2188 1103/1103/2188 +f 1103/1103/2188 1053/1053/2188 1102/1102/2188 +f 1059/1059/2189 1062/1062/2189 1104/1104/2189 +f 1104/1104/2189 1062/1062/2189 1103/1103/2189 +f 1064/1064/2190 1059/1059/2190 1100/1100/2190 +f 1100/1100/2190 1059/1059/2190 1104/1104/2190 +f 1103/1103/145 1102/1102/145 1104/1104/145 +f 1104/1104/145 1102/1102/145 1101/1101/145 +f 1104/1104/145 1101/1101/145 1100/1100/145 +f 1100/1100/145 1101/1101/145 1099/1099/145 +f 1074/1074/2191 1069/1069/2192 1071/1071/2193 +f 1074/1074/2191 1071/1071/2193 1086/1086/2194 +f 1086/1086/2195 1071/1071/2195 1085/1085/2195 +f 1085/1085/2196 1071/1071/2110 1070/1070/2109 +f 1082/1082/2197 1070/1070/2109 1072/1072/2111 +f 1082/1082/2126 1072/1072/2198 1079/1079/2123 +f 1079/1079/2199 1072/1072/2111 1073/1073/2112 +f 1076/1076/2200 1073/1073/2112 1069/1069/2108 +f 1076/1076/2115 1069/1069/2201 1074/1074/2113 +f 1105/1105/2202 1106/1106/2203 1107/1107/2204 +f 1108/1108/2205 1109/1109/2206 1110/1110/2207 +f 1107/1107/2204 1111/1111/2208 1105/1105/2202 +f 1105/1105/2202 1111/1111/2208 1112/1112/2209 +f 1113/1113/2210 1114/1114/2211 1106/1106/2203 +f 1106/1106/2203 1105/1105/2202 1113/1113/2210 +f 1115/1115/2212 1116/1116/2213 1117/1117/2214 +f 1116/1116/2213 1114/1114/2211 1117/1117/2214 +f 1117/1117/2214 1114/1114/2211 1113/1113/2210 +f 1118/1118/2215 1109/1109/2206 1112/1112/2209 +f 1112/1112/2209 1109/1109/2206 1108/1108/2205 +f 1112/1112/2209 1111/1111/2208 1118/1118/2215 +f 1119/1119/2216 1120/1120/2217 1117/1117/2214 +f 1117/1117/2214 1120/1120/2217 1115/1115/2212 +f 1108/1108/2205 1110/1110/2207 1119/1119/2216 +f 1119/1119/2216 1110/1110/2207 1120/1120/2217 +f 1121/1121/2218 1122/1122/2219 1123/1123/2220 +f 1123/1123/2220 1124/1124/2221 1121/1121/2218 +f 1125/1125/2222 1124/1124/2221 1123/1123/2220 +f 1122/1122/2219 1126/1126/2223 1123/1123/2220 +f 1127/1127/2224 1128/1128/2225 1126/1126/2226 +f 1126/1126/2227 1128/1128/2228 1129/1129/2229 +f 1128/1128/2228 1130/1130/2230 1129/1129/2229 +f 1129/1129/2231 1130/1130/2232 1131/1131/2233 +f 1129/1129/2231 1131/1131/2233 1132/1132/2234 +f 1132/1132/2234 1131/1131/2233 1133/1133/2235 +f 1132/1132/2234 1133/1133/2235 1125/1125/2236 +f 1125/1125/2236 1133/1133/2235 1134/1134/2237 +f 1125/1125/2236 1134/1134/2237 1124/1124/2238 +f 1134/1134/2237 1135/1135/2239 1124/1124/2238 +f 1124/1124/2238 1135/1135/2239 1136/1136/2240 +f 1135/1135/2239 1137/1137/2241 1136/1136/2240 +f 1136/1136/2242 1137/1137/2243 1138/1138/2244 +f 1138/1138/2244 1137/1137/2243 1139/1139/2245 +f 1138/1138/2246 1139/1139/2247 1122/1122/2248 +f 1122/1122/2248 1139/1139/2247 1127/1127/2249 +f 1122/1122/2250 1127/1127/2224 1126/1126/2226 +f 1128/1128/2251 1140/1140/2252 1141/1141/2253 +f 1134/1134/2254 1142/1142/2255 1135/1135/2256 +f 1127/1127/2257 1140/1140/2252 1128/1128/2251 +f 1127/1127/2257 1143/1143/2258 1140/1140/2252 +f 1137/1137/2259 1144/1144/2260 1139/1139/2261 +f 1133/1133/2262 1145/1145/2263 1134/1134/2254 +f 1134/1134/2254 1145/1145/2263 1142/1142/2255 +f 1130/1130/2264 1146/1146/2265 1131/1131/2266 +f 1139/1139/2261 1147/1147/2267 1143/1143/2258 +f 1139/1139/2261 1143/1143/2258 1127/1127/2257 +f 1144/1144/2260 1147/1147/2267 1139/1139/2261 +f 1146/1146/2265 1148/1148/2268 1131/1131/2266 +f 1131/1131/2266 1148/1148/2268 1133/1133/2262 +f 1133/1133/2262 1148/1148/2268 1145/1145/2263 +f 1128/1128/2251 1141/1141/2253 1130/1130/2264 +f 1130/1130/2264 1141/1141/2253 1146/1146/2265 +f 1135/1135/2256 1142/1142/2255 1149/1149/2269 +f 1135/1135/2256 1149/1149/2269 1137/1137/2259 +f 1137/1137/2259 1149/1149/2269 1144/1144/2260 +f 1109/1109/2270 1118/1118/2271 1140/1140/2272 +f 1140/1140/2272 1118/1118/2271 1141/1141/2273 +f 1118/1118/2271 1111/1111/2274 1141/1141/2273 +f 1141/1141/2273 1111/1111/2274 1146/1146/2275 +f 1146/1146/2275 1111/1111/2274 1107/1107/2276 +f 1146/1146/2275 1107/1107/2276 1148/1148/2277 +f 1107/1107/2276 1106/1106/2278 1148/1148/2277 +f 1148/1148/2277 1106/1106/2278 1145/1145/2279 +f 1145/1145/2279 1106/1106/2278 1114/1114/2280 +f 1145/1145/2279 1114/1114/2280 1142/1142/2281 +f 1114/1114/2280 1116/1116/2282 1142/1142/2281 +f 1142/1142/2281 1116/1116/2282 1149/1149/2283 +f 1149/1149/2283 1116/1116/2282 1115/1115/2284 +f 1149/1149/2283 1115/1115/2284 1144/1144/2285 +f 1115/1115/2284 1120/1120/2286 1144/1144/2285 +f 1144/1144/2285 1120/1120/2286 1147/1147/2287 +f 1147/1147/2287 1120/1120/2286 1110/1110/2288 +f 1147/1147/2287 1110/1110/2288 1143/1143/2289 +f 1110/1110/2288 1109/1109/2290 1143/1143/2289 +f 1143/1143/2289 1109/1109/2290 1140/1140/2291 +f 1117/1117/2292 1113/1113/2292 1150/1150/2292 +f 1150/1150/2292 1113/1113/2292 1151/1151/2292 +f 1119/1119/2293 1117/1117/2293 1152/1152/2293 +f 1152/1152/2293 1117/1117/2293 1150/1150/2293 +f 1108/1108/2294 1119/1119/2294 1153/1153/2294 +f 1153/1153/2294 1119/1119/2294 1152/1152/2294 +f 1112/1112/2295 1108/1108/2295 1154/1154/2295 +f 1154/1154/2295 1108/1108/2295 1153/1153/2295 +f 1105/1105/2296 1112/1112/2296 1155/1155/2296 +f 1155/1155/2296 1112/1112/2296 1154/1154/2296 +f 1113/1113/2297 1105/1105/2297 1151/1151/2297 +f 1151/1151/2297 1105/1105/2297 1155/1155/2297 +f 1154/1154/145 1153/1153/145 1155/1155/145 +f 1155/1155/145 1153/1153/145 1152/1152/145 +f 1155/1155/145 1152/1152/145 1151/1151/145 +f 1151/1151/145 1152/1152/145 1150/1150/145 +f 1138/1138/2298 1122/1122/2298 1121/1121/2298 +f 1138/1138/2244 1121/1121/2299 1136/1136/2242 +f 1136/1136/2300 1121/1121/2218 1124/1124/2221 +f 1132/1132/2301 1125/1125/2222 1123/1123/2220 +f 1132/1132/2234 1123/1123/2302 1129/1129/2231 +f 1129/1129/2303 1123/1123/2220 1126/1126/2223 +f 1156/1156/2304 1157/1157/2305 1158/1158/2306 +f 1159/1159/2307 1160/1160/2308 1161/1161/2309 +f 1159/1159/2307 1161/1161/2309 1162/1162/2310 +f 1163/1163/2311 1159/1159/2307 1164/1164/2312 +f 1165/1165/2313 1166/1166/2314 1164/1164/2312 +f 1161/1161/2309 1157/1157/2305 1162/1162/2310 +f 1164/1164/2312 1166/1166/2314 1163/1163/2311 +f 1167/1167/2315 1165/1165/2313 1168/1168/2316 +f 1168/1168/2316 1165/1165/2313 1164/1164/2312 +f 1169/1169/2317 1167/1167/2315 1168/1168/2316 +f 1170/1170/2318 1171/1171/2319 1169/1169/2317 +f 1162/1162/2310 1157/1157/2305 1156/1156/2304 +f 1159/1159/2307 1163/1163/2311 1160/1160/2308 +f 1170/1170/2318 1169/1169/2317 1168/1168/2316 +f 1158/1158/2306 1171/1171/2319 1156/1156/2304 +f 1156/1156/2304 1171/1171/2319 1170/1170/2318 +f 1172/1172/2320 1173/1173/2321 1174/1174/2322 +f 1172/1172/2320 1175/1175/2323 1173/1173/2321 +f 1172/1172/2320 1176/1176/2324 1175/1175/2323 +f 1177/1177/2325 1176/1176/2324 1172/1172/2320 +f 1177/1177/2326 1178/1178/2327 1176/1176/2328 +f 1178/1178/2327 1179/1179/2329 1176/1176/2328 +f 1176/1176/2328 1179/1179/2329 1180/1180/2330 +f 1179/1179/2329 1181/1181/2331 1180/1180/2330 +f 1180/1180/2330 1181/1181/2331 1175/1175/2332 +f 1181/1181/2331 1182/1182/2333 1175/1175/2332 +f 1175/1175/2334 1182/1182/2335 1173/1173/2336 +f 1173/1173/2336 1182/1182/2335 1183/1183/2337 +f 1173/1173/2338 1183/1183/2339 1174/1174/2340 +f 1183/1183/2339 1184/1184/2341 1174/1174/2340 +f 1174/1174/2342 1184/1184/2343 1185/1185/2344 +f 1184/1184/2343 1186/1186/2345 1185/1185/2344 +f 1185/1185/2346 1186/1186/2347 1172/1172/2348 +f 1172/1172/2348 1186/1186/2347 1187/1187/2349 +f 1172/1172/2350 1187/1187/2351 1177/1177/2352 +f 1177/1177/2352 1187/1187/2351 1178/1178/2353 +f 1178/1178/2354 1188/1188/2355 1179/1179/2356 +f 1181/1181/2357 1189/1189/2358 1190/1190/2359 +f 1178/1178/2354 1191/1191/2360 1188/1188/2355 +f 1187/1187/2361 1191/1191/2360 1178/1178/2354 +f 1182/1182/2362 1192/1192/2363 1183/1183/2364 +f 1183/1183/2364 1192/1192/2363 1193/1193/2365 +f 1179/1179/2356 1189/1189/2358 1181/1181/2357 +f 1187/1187/2361 1194/1194/2366 1191/1191/2360 +f 1186/1186/2367 1195/1195/2368 1187/1187/2361 +f 1187/1187/2361 1195/1195/2368 1194/1194/2366 +f 1181/1181/2357 1190/1190/2359 1182/1182/2362 +f 1182/1182/2362 1190/1190/2359 1192/1192/2363 +f 1188/1188/2355 1189/1189/2358 1179/1179/2356 +f 1184/1184/2369 1196/1196/2370 1195/1195/2368 +f 1184/1184/2369 1195/1195/2368 1186/1186/2367 +f 1183/1183/2364 1193/1193/2365 1196/1196/2370 +f 1183/1183/2364 1196/1196/2370 1184/1184/2369 +f 1157/1157/2371 1161/1161/2372 1188/1188/2373 +f 1188/1188/2373 1161/1161/2372 1189/1189/2374 +f 1161/1161/2375 1160/1160/2376 1189/1189/2377 +f 1189/1189/2377 1160/1160/2376 1190/1190/2378 +f 1190/1190/2378 1160/1160/2376 1163/1163/2379 +f 1190/1190/2378 1163/1163/2379 1192/1192/2380 +f 1192/1192/2380 1163/1163/2379 1166/1166/2381 +f 1192/1192/2380 1166/1166/2381 1193/1193/2382 +f 1193/1193/2382 1166/1166/2381 1165/1165/2383 +f 1193/1193/2382 1165/1165/2383 1196/1196/2384 +f 1196/1196/2384 1165/1165/2383 1167/1167/2385 +f 1167/1167/2386 1169/1169/2387 1196/1196/2388 +f 1196/1196/2388 1169/1169/2387 1195/1195/2389 +f 1169/1169/2390 1171/1171/2391 1195/1195/2392 +f 1195/1195/2392 1171/1171/2391 1194/1194/2393 +f 1171/1171/2391 1158/1158/2394 1194/1194/2393 +f 1194/1194/2393 1158/1158/2394 1191/1191/2395 +f 1158/1158/2394 1157/1157/2396 1191/1191/2395 +f 1191/1191/2395 1157/1157/2396 1188/1188/2397 +f 1168/1168/2398 1164/1164/2398 1197/1197/2398 +f 1197/1197/2398 1164/1164/2398 1198/1198/2398 +f 1170/1170/2399 1168/1168/2399 1199/1199/2399 +f 1199/1199/2399 1168/1168/2399 1197/1197/2399 +f 1156/1156/2400 1170/1170/2400 1200/1200/2400 +f 1200/1200/2400 1170/1170/2400 1199/1199/2400 +f 1162/1162/2401 1156/1156/2401 1201/1201/2401 +f 1201/1201/2401 1156/1156/2401 1200/1200/2401 +f 1159/1159/2402 1162/1162/2402 1202/1202/2402 +f 1202/1202/2402 1162/1162/2402 1201/1201/2402 +f 1164/1164/2403 1159/1159/2403 1198/1198/2403 +f 1198/1198/2403 1159/1159/2403 1202/1202/2403 +f 1201/1201/145 1200/1200/145 1202/1202/145 +f 1202/1202/145 1200/1200/145 1199/1199/145 +f 1202/1202/145 1199/1199/145 1198/1198/145 +f 1198/1198/145 1199/1199/145 1197/1197/145 +f 1185/1185/2404 1172/1172/2320 1174/1174/2322 +f 1180/1180/2405 1175/1175/2323 1176/1176/2324 +f 1203/1203/2406 1204/1204/2407 1205/1205/2408 +f 1206/1206/2409 1207/1207/2410 1208/1208/2411 +f 1209/1209/2412 1210/1210/2413 1211/1211/2414 +f 1212/1212/2415 1213/1213/2416 1214/1214/2417 +f 1214/1214/2417 1213/1213/2416 1215/1215/2418 +f 1208/1208/2411 1207/1207/2410 1216/1216/2419 +f 1216/1216/2419 1214/1214/2417 1208/1208/2411 +f 1217/1217/2420 1206/1206/2409 1208/1208/2411 +f 1217/1217/2420 1218/1218/2421 1206/1206/2409 +f 1219/1219/2422 1209/1209/2412 1215/1215/2418 +f 1215/1215/2418 1209/1209/2412 1211/1211/2414 +f 1215/1215/2418 1213/1213/2416 1219/1219/2422 +f 1214/1214/2417 1216/1216/2419 1212/1212/2415 +f 1203/1203/2406 1205/1205/2408 1217/1217/2420 +f 1217/1217/2420 1205/1205/2408 1218/1218/2421 +f 1211/1211/2414 1210/1210/2413 1203/1203/2406 +f 1203/1203/2406 1210/1210/2413 1204/1204/2407 +f 1220/1220/2423 1221/1221/2424 1222/1222/2425 +f 1222/1222/2425 1223/1223/2426 1224/1224/2427 +f 1222/1222/2425 1221/1221/2424 1223/1223/2426 +f 1225/1225/2428 1226/1226/2429 1227/1227/2430 +f 1227/1227/2430 1226/1226/2429 1228/1228/2431 +f 1226/1226/2432 1229/1229/2433 1228/1228/2434 +f 1228/1228/2434 1229/1229/2433 1230/1230/2435 +f 1230/1230/2435 1229/1229/2433 1231/1231/2436 +f 1230/1230/2437 1231/1231/2438 1223/1223/2439 +f 1223/1223/2439 1231/1231/2438 1232/1232/2440 +f 1223/1223/2439 1232/1232/2440 1233/1233/2441 +f 1233/1233/2441 1232/1232/2440 1234/1234/2442 +f 1234/1234/2443 1235/1235/2444 1233/1233/2445 +f 1233/1233/2445 1235/1235/2444 1236/1236/2446 +f 1235/1235/2444 1237/1237/2447 1236/1236/2446 +f 1236/1236/2448 1237/1237/2449 1222/1222/2450 +f 1237/1237/2449 1238/1238/2451 1222/1222/2450 +f 1222/1222/2452 1238/1238/2453 1227/1227/2454 +f 1227/1227/2454 1238/1238/2453 1225/1225/2455 +f 1229/1229/2456 1239/1239/2457 1231/1231/2458 +f 1231/1231/2458 1239/1239/2457 1240/1240/2459 +f 1225/1225/2460 1241/1241/2461 1242/1242/2462 +f 1225/1225/2460 1242/1242/2462 1226/1226/2463 +f 1238/1238/2464 1243/1243/2465 1225/1225/2460 +f 1225/1225/2460 1243/1243/2465 1241/1241/2461 +f 1237/1237/2466 1244/1244/2467 1238/1238/2464 +f 1232/1232/2468 1245/1245/2469 1234/1234/2470 +f 1234/1234/2470 1245/1245/2469 1246/1246/2471 +f 1238/1238/2464 1244/1244/2467 1243/1243/2465 +f 1231/1231/2458 1240/1240/2459 1245/1245/2469 +f 1231/1231/2458 1245/1245/2469 1232/1232/2468 +f 1226/1226/2463 1242/1242/2462 1239/1239/2457 +f 1226/1226/2463 1239/1239/2457 1229/1229/2456 +f 1235/1235/2472 1247/1247/2473 1237/1237/2466 +f 1237/1237/2466 1247/1247/2473 1244/1244/2467 +f 1234/1234/2470 1246/1246/2471 1235/1235/2472 +f 1235/1235/2472 1246/1246/2471 1247/1247/2473 +f 1242/1242/2474 1241/1241/2475 1209/1209/2476 +f 1242/1242/2474 1209/1209/2476 1219/1219/2477 +f 1242/1242/2478 1219/1219/2479 1213/1213/2480 +f 1242/1242/2478 1213/1213/2480 1239/1239/2481 +f 1239/1239/2482 1213/1213/2483 1212/1212/2484 +f 1239/1239/2482 1212/1212/2484 1240/1240/2485 +f 1212/1212/2484 1216/1216/2486 1240/1240/2485 +f 1240/1240/2485 1216/1216/2486 1245/1245/2487 +f 1245/1245/2487 1216/1216/2486 1207/1207/2488 +f 1245/1245/2487 1207/1207/2488 1246/1246/2489 +f 1207/1207/2488 1206/1206/2490 1246/1246/2489 +f 1246/1246/2491 1206/1206/2492 1247/1247/2493 +f 1206/1206/2492 1218/1218/2494 1247/1247/2493 +f 1247/1247/2493 1218/1218/2494 1205/1205/2495 +f 1247/1247/2493 1205/1205/2495 1244/1244/2496 +f 1205/1205/2495 1204/1204/2497 1244/1244/2496 +f 1244/1244/2496 1204/1204/2497 1243/1243/2498 +f 1243/1243/2498 1204/1204/2497 1210/1210/2499 +f 1210/1210/2499 1209/1209/2500 1243/1243/2498 +f 1243/1243/2498 1209/1209/2500 1241/1241/2501 +f 1217/1217/2502 1208/1208/2502 1248/1248/2502 +f 1248/1248/2502 1208/1208/2502 1249/1249/2502 +f 1203/1203/2503 1217/1217/2503 1250/1250/2503 +f 1250/1250/2503 1217/1217/2503 1248/1248/2503 +f 1211/1211/2504 1203/1203/2504 1251/1251/2504 +f 1251/1251/2504 1203/1203/2504 1250/1250/2504 +f 1215/1215/2505 1211/1211/2505 1252/1252/2505 +f 1252/1252/2505 1211/1211/2505 1251/1251/2505 +f 1214/1214/2506 1215/1215/2506 1253/1253/2506 +f 1253/1253/2506 1215/1215/2506 1252/1252/2506 +f 1208/1208/2507 1214/1214/2507 1249/1249/2507 +f 1249/1249/2507 1214/1214/2507 1253/1253/2507 +f 1252/1252/145 1251/1251/145 1253/1253/145 +f 1253/1253/145 1251/1251/145 1250/1250/145 +f 1253/1253/145 1250/1250/145 1249/1249/145 +f 1249/1249/145 1250/1250/145 1248/1248/145 +f 1227/1227/2508 1220/1220/2508 1222/1222/2508 +f 1236/1236/2509 1222/1222/2509 1224/1224/2509 +f 1236/1236/2446 1224/1224/2510 1233/1233/2445 +f 1233/1233/2511 1224/1224/2427 1223/1223/2426 +f 1230/1230/2512 1223/1223/2426 1221/1221/2424 +f 1230/1230/2435 1221/1221/2513 1228/1228/2434 +f 1228/1228/2514 1221/1221/2515 1227/1227/2516 +f 1227/1227/2516 1221/1221/2515 1220/1220/2517 +f 1254/1254/145 1255/1255/145 1256/1256/145 +f 1257/1257/145 1258/1258/145 1259/1259/145 +f 1259/1259/145 1258/1258/145 1260/1260/145 +f 1261/1261/145 1262/1262/145 1263/1263/145 +f 1264/1264/145 1265/1265/145 1258/1258/145 +f 1265/1265/145 1266/1266/145 1267/1267/145 +f 1265/1265/145 1267/1267/145 1258/1258/145 +f 1268/1268/145 1269/1269/145 1270/1270/145 +f 1270/1270/145 1269/1269/145 1262/1262/145 +f 1262/1262/145 1269/1269/145 1263/1263/145 +f 1264/1264/145 1258/1258/145 1257/1257/145 +f 1254/1254/145 1256/1256/145 1268/1268/145 +f 1254/1254/145 1268/1268/145 1270/1270/145 +f 1271/1271/145 1260/1260/145 1266/1266/145 +f 1267/1267/145 1266/1266/145 1260/1260/145 +f 1261/1261/145 1263/1263/145 1256/1256/145 +f 1260/1260/145 1271/1271/145 1272/1272/145 +f 1256/1256/145 1273/1273/145 1261/1261/145 +f 1260/1260/145 1272/1272/145 1259/1259/145 +f 1256/1256/145 1255/1255/145 1274/1274/145 +f 1273/1273/145 1274/1274/145 1275/1275/145 +f 1256/1256/145 1274/1274/145 1273/1273/145 +f 1276/1276/145 1277/1277/145 1278/1278/145 +f 1278/1278/145 1277/1277/145 1279/1279/145 +f 1278/1278/145 1279/1279/145 1280/1280/145 +f 1278/1278/145 1280/1280/145 1281/1281/145 +f 1282/1282/145 1283/1283/145 1276/1276/145 +f 1276/1276/145 1283/1283/145 1284/1284/145 +f 1259/1259/145 1272/1272/145 1282/1282/145 +f 1282/1282/145 1272/1272/145 1283/1283/145 +f 1273/1273/145 1275/1275/145 1280/1280/145 +f 1280/1280/145 1275/1275/145 1281/1281/145 +f 1284/1284/145 1277/1277/145 1276/1276/145 +f 1285/1285/56 1286/1286/56 1287/1287/56 +f 1288/1288/56 1289/1289/56 1290/1290/56 +f 1289/1289/56 1291/1291/56 1290/1290/56 +f 1292/1292/56 1293/1293/56 1294/1294/56 +f 1295/1295/56 1296/1296/56 1297/1297/56 +f 1296/1296/56 1298/1298/56 1297/1297/56 +f 1285/1285/56 1287/1287/56 1299/1299/56 +f 1299/1299/56 1287/1287/56 1300/1300/56 +f 1292/1292/56 1294/1294/56 1286/1286/56 +f 1300/1300/56 1293/1293/56 1301/1301/56 +f 1297/1297/56 1298/1298/56 1289/1289/56 +f 1289/1289/56 1298/1298/56 1291/1291/56 +f 1296/1296/56 1295/1295/56 1290/1290/56 +f 1294/1294/56 1293/1293/56 1300/1300/56 +f 1285/1285/56 1292/1292/56 1286/1286/56 +f 1290/1290/56 1302/1302/56 1288/1288/56 +f 1295/1295/56 1303/1303/56 1290/1290/56 +f 1304/1304/56 1300/1300/56 1301/1301/56 +f 1303/1303/56 1305/1305/56 1302/1302/56 +f 1290/1290/56 1303/1303/56 1302/1302/56 +f 1302/1302/56 1305/1305/56 1306/1306/56 +f 1306/1306/56 1305/1305/56 1307/1307/56 +f 1308/1308/56 1309/1309/56 1310/1310/56 +f 1310/1310/56 1309/1309/56 1311/1311/56 +f 1312/1312/56 1313/1313/56 1306/1306/56 +f 1312/1312/56 1306/1306/56 1307/1307/56 +f 1314/1314/56 1299/1299/56 1304/1304/56 +f 1310/1310/56 1311/1311/56 1312/1312/56 +f 1312/1312/56 1311/1311/56 1313/1313/56 +f 1300/1300/56 1304/1304/56 1299/1299/56 +f 1315/1315/56 1316/1316/56 1309/1309/56 +f 1315/1315/56 1309/1309/56 1308/1308/56 +f 1314/1314/56 1304/1304/56 1315/1315/56 +f 1315/1315/56 1304/1304/56 1316/1316/56 +f 1254/1254/2518 1285/1285/2519 1255/1255/2520 +f 1255/1255/2520 1285/1285/2519 1299/1299/2521 +f 1255/1255/2522 1299/1299/2522 1274/1274/2522 +f 1274/1274/2523 1299/1299/2523 1314/1314/2523 +f 1274/1274/2524 1314/1314/2524 1275/1275/2524 +f 1275/1275/2525 1314/1314/2525 1315/1315/2525 +f 1275/1275/2526 1315/1315/2526 1281/1281/2526 +f 1281/1281/2527 1315/1315/2527 1308/1308/2527 +f 1281/1281/2528 1308/1308/2528 1278/1278/2528 +f 1278/1278/2529 1308/1308/2529 1310/1310/2529 +f 1278/1278/2530 1310/1310/2530 1276/1276/2530 +f 1276/1276/2531 1310/1310/2531 1312/1312/2531 +f 1276/1276/2532 1312/1312/2533 1307/1307/2534 +f 1276/1276/2532 1307/1307/2534 1282/1282/2535 +f 1282/1282/2536 1307/1307/2536 1305/1305/2536 +f 1282/1282/2537 1305/1305/2537 1259/1259/2537 +f 1259/1259/2538 1305/1305/2538 1303/1303/2538 +f 1259/1259/2539 1303/1303/2539 1257/1257/2539 +f 1257/1257/2540 1303/1303/2540 1295/1295/2540 +f 1257/1257/2541 1295/1295/2541 1264/1264/2541 +f 1265/1265/2542 1264/1264/2543 1297/1297/2544 +f 1297/1297/2544 1264/1264/2543 1295/1295/2545 +f 1265/1265/2546 1297/1297/2547 1289/1289/2548 +f 1265/1265/2546 1289/1289/2548 1266/1266/2549 +f 1271/1271/2550 1266/1266/2551 1288/1288/2552 +f 1288/1288/2552 1266/1266/2551 1289/1289/2553 +f 1271/1271/2550 1288/1288/2552 1302/1302/2554 +f 1271/1271/2550 1302/1302/2554 1272/1272/2555 +f 1272/1272/2556 1302/1302/2557 1306/1306/2558 +f 1272/1272/2556 1306/1306/2558 1283/1283/2559 +f 1283/1283/2560 1306/1306/2560 1284/1284/2560 +f 1284/1284/2561 1306/1306/2561 1313/1313/2561 +f 1284/1284/2562 1313/1313/2562 1277/1277/2562 +f 1277/1277/2563 1313/1313/2563 1311/1311/2563 +f 1277/1277/2564 1311/1311/2564 1279/1279/2564 +f 1279/1279/2565 1311/1311/2565 1309/1309/2565 +f 1279/1279/2566 1309/1309/2566 1280/1280/2566 +f 1280/1280/2567 1309/1309/2567 1316/1316/2567 +f 1280/1280/2568 1316/1316/2569 1304/1304/2570 +f 1280/1280/2568 1304/1304/2570 1273/1273/2571 +f 1273/1273/2572 1304/1304/2573 1301/1301/2574 +f 1273/1273/2572 1301/1301/2574 1261/1261/2575 +f 1262/1262/2576 1261/1261/2575 1293/1293/2577 +f 1293/1293/2577 1261/1261/2575 1301/1301/2574 +f 1262/1262/2578 1293/1293/2579 1292/1292/2580 +f 1262/1262/2578 1292/1292/2580 1270/1270/2581 +f 1254/1254/2582 1270/1270/2583 1285/1285/2584 +f 1285/1285/2584 1270/1270/2583 1292/1292/2585 +f 1267/1267/2586 1290/1290/2587 1291/1291/2588 +f 1267/1267/2589 1291/1291/2589 1298/1298/2589 +f 1267/1267/2590 1298/1298/2590 1258/1258/2590 +f 1258/1258/2591 1298/1298/2591 1296/1296/2591 +f 1258/1258/2592 1296/1296/2592 1260/1260/2592 +f 1260/1260/2593 1296/1296/2593 1290/1290/2593 +f 1260/1260/2594 1290/1290/2587 1267/1267/2586 +f 1268/1268/2595 1286/1286/2595 1269/1269/2595 +f 1269/1269/2596 1286/1286/2596 1294/1294/2596 +f 1269/1269/2597 1294/1294/2597 1263/1263/2597 +f 1263/1263/2598 1294/1294/2598 1300/1300/2598 +f 1263/1263/2599 1300/1300/2599 1256/1256/2599 +f 1256/1256/2600 1300/1300/2600 1287/1287/2600 +f 1256/1256/2601 1287/1287/2601 1268/1268/2601 +f 1268/1268/2602 1287/1287/2602 1286/1286/2602 +f 1317/1317/2603 1318/1318/2604 1319/1319/2605 +f 1317/1317/2603 1319/1319/2605 1320/1320/2606 +f 1320/1320/2606 1319/1319/2605 1321/1321/2607 +f 1321/1321/2607 1319/1319/2605 1322/1322/2608 +f 1321/1321/2607 1322/1322/2608 1323/1323/2609 +f 1323/1323/2609 1322/1322/2608 1324/1324/2610 +f 1323/1323/2609 1324/1324/2610 1325/1325/2611 +f 1325/1325/2611 1324/1324/2610 1326/1326/2612 +f 1325/1325/2611 1326/1326/2612 1327/1327/2613 +f 1327/1327/2613 1326/1326/2612 1328/1328/2614 +f 1327/1327/2613 1328/1328/2614 1329/1329/2615 +f 1329/1329/2615 1328/1328/2614 1330/1330/2616 +f 1329/1329/2615 1330/1330/2616 1331/1331/2617 +f 1329/1329/2615 1331/1331/2617 1332/1332/2618 +f 1332/1332/2618 1331/1331/2617 1333/1333/2619 +f 1333/1333/2619 1331/1331/2617 1334/1334/2620 +f 1333/1333/2619 1334/1334/2620 1335/1335/2621 +f 1333/1333/2619 1335/1335/2621 1336/1336/2622 +f 1336/1336/2622 1335/1335/2621 1337/1337/2623 +f 1337/1337/2623 1335/1335/2621 1338/1338/2624 +f 1337/1337/2623 1338/1338/2624 1339/1339/2625 +f 1339/1339/2625 1338/1338/2624 1340/1340/2626 +f 1339/1339/2625 1340/1340/2626 1341/1341/2627 +f 1341/1341/2627 1340/1340/2626 1342/1342/2628 +f 1341/1341/2627 1342/1342/2628 1343/1343/2629 +f 1343/1343/2629 1342/1342/2628 1344/1344/2630 +f 1343/1343/2629 1344/1344/2630 1345/1345/2631 +f 1345/1345/2631 1344/1344/2630 1346/1346/2632 +f 1345/1345/2631 1346/1346/2632 1347/1347/2633 +f 1347/1347/2633 1346/1346/2632 1318/1318/2604 +f 1347/1347/2633 1318/1318/2604 1317/1317/2603 +f 1331/1331/2634 1330/1330/2634 1334/1334/2634 +f 1342/1342/2634 1340/1340/2634 1344/1344/2634 +f 1322/1322/2634 1319/1319/2634 1340/1340/2634 +f 1322/1322/2634 1326/1326/2634 1324/1324/2634 +f 1340/1340/2634 1319/1319/2634 1344/1344/2634 +f 1319/1319/2634 1318/1318/2634 1344/1344/2634 +f 1335/1335/2634 1326/1326/2634 1338/1338/2634 +f 1344/1344/2634 1318/1318/2634 1346/1346/2634 +f 1340/1340/2634 1326/1326/2634 1322/1322/2634 +f 1326/1326/2634 1335/1335/2634 1328/1328/2634 +f 1328/1328/2634 1335/1335/2634 1334/1334/2634 +f 1328/1328/2634 1334/1334/2634 1330/1330/2634 +f 1340/1340/2634 1338/1338/2634 1326/1326/2634 +f 1327/1327/2635 1336/1336/2635 1339/1339/2635 +f 1347/1347/2635 1317/1317/2635 1345/1345/2635 +f 1321/1321/2635 1323/1323/2635 1320/1320/2635 +f 1339/1339/2635 1341/1341/2635 1345/1345/2635 +f 1323/1323/2635 1345/1345/2635 1320/1320/2635 +f 1343/1343/2635 1345/1345/2635 1341/1341/2635 +f 1323/1323/2635 1325/1325/2635 1327/1327/2635 +f 1336/1336/2635 1329/1329/2635 1333/1333/2635 +f 1317/1317/2635 1320/1320/2635 1345/1345/2635 +f 1339/1339/2635 1323/1323/2635 1327/1327/2635 +f 1339/1339/2635 1336/1336/2635 1337/1337/2635 +f 1329/1329/2635 1336/1336/2635 1327/1327/2635 +f 1339/1339/2635 1345/1345/2635 1323/1323/2635 +f 1333/1333/2635 1329/1329/2635 1332/1332/2635 +f 1348/1348/2636 1349/1349/2637 1350/1350/2638 +f 1351/1351/2639 1352/1352/2640 1348/1348/2636 +f 1349/1349/2637 1353/1353/2641 1350/1350/2638 +f 1354/1354/2642 1355/1355/2643 1356/1356/2644 +f 1353/1353/2641 1357/1357/2645 1350/1350/2638 +f 1350/1350/2638 1357/1357/2645 1358/1358/2646 +f 1359/1359/2647 1350/1350/2638 1358/1358/2646 +f 1359/1359/2647 1358/1358/2646 1360/1360/2648 +f 1361/1361/2649 1350/1350/2638 1359/1359/2647 +f 1359/1359/2647 1360/1360/2648 1362/1362/2650 +f 1361/1361/2649 1359/1359/2647 1362/1362/2650 +f 1363/1363/2651 1362/1362/2650 1360/1360/2648 +f 1348/1348/2636 1350/1350/2638 1364/1364/2652 +f 1364/1364/2652 1350/1350/2638 1361/1361/2649 +f 1365/1365/2653 1361/1361/2649 1362/1362/2650 +f 1366/1366/2654 1363/1363/2651 1360/1360/2648 +f 1366/1366/2654 1360/1360/2648 1367/1367/2655 +f 1365/1365/2653 1362/1362/2650 1363/1363/2651 +f 1368/1368/2656 1355/1355/2643 1369/1369/2657 +f 1369/1369/2657 1354/1354/2642 1370/1370/2658 +f 1365/1365/2653 1368/1368/2656 1369/1369/2657 +f 1364/1364/2652 1369/1369/2657 1370/1370/2658 +f 1363/1363/2651 1366/1366/2654 1368/1368/2656 +f 1365/1365/2653 1369/1369/2657 1364/1364/2652 +f 1348/1348/2636 1370/1370/2658 1351/1351/2639 +f 1364/1364/2652 1361/1361/2649 1365/1365/2653 +f 1354/1354/2642 1369/1369/2657 1355/1355/2643 +f 1370/1370/2658 1348/1348/2636 1364/1364/2652 +f 1368/1368/2656 1365/1365/2653 1363/1363/2651 +f 1353/1353/2641 1349/1349/2637 1371/1371/2659 +f 1371/1371/2659 1349/1349/2637 1352/1352/2640 +f 1371/1371/2659 1352/1352/2640 1372/1372/2660 +f 1352/1352/2640 1373/1373/2661 1372/1372/2660 +f 1372/1372/2660 1373/1373/2661 1374/1374/2662 +f 1372/1372/2660 1374/1374/2662 1375/1375/2663 +f 1375/1375/2663 1374/1374/2662 1376/1376/2664 +f 1376/1376/2664 1374/1374/2662 1377/1377/2665 +f 1376/1376/2664 1377/1377/2665 1378/1378/2666 +f 1376/1376/2664 1378/1378/2666 1379/1379/2667 +f 1379/1379/2667 1378/1378/2666 1380/1380/2668 +f 1379/1379/2667 1380/1380/2668 1381/1381/2669 +f 1381/1381/2669 1380/1380/2668 1382/1382/2670 +f 1381/1381/2669 1382/1382/2670 1383/1383/2671 +f 1384/1384/145 1376/1376/145 1385/1385/145 +f 1385/1385/145 1376/1376/145 1386/1386/145 +f 1386/1386/145 1376/1376/145 1379/1379/145 +f 1386/1386/145 1379/1379/145 1387/1387/145 +f 1388/1388/2672 1372/1372/2673 1384/1384/145 +f 1384/1384/145 1372/1372/2673 1375/1375/2674 +f 1384/1384/145 1375/1375/2674 1376/1376/145 +f 1389/1389/2675 1390/1390/2676 1367/1367/2677 +f 1391/1391/2678 1392/1392/2679 1393/1393/2680 +f 1393/1393/2680 1392/1392/2679 1390/1390/2676 +f 1387/1387/145 1379/1379/145 1394/1394/145 +f 1394/1394/145 1379/1379/145 1381/1381/145 +f 1391/1391/2678 1395/1395/2681 1392/1392/2679 +f 1396/1396/2682 1371/1371/2682 1388/1388/2672 +f 1388/1388/2672 1371/1371/2682 1372/1372/2673 +f 1393/1393/2680 1390/1390/2676 1389/1389/2675 +f 1397/1397/2683 1383/1383/2684 1398/1398/2685 +f 1394/1394/145 1381/1381/145 1399/1399/145 +f 1399/1399/145 1381/1381/145 1383/1383/2684 +f 1399/1399/145 1383/1383/2684 1400/1400/145 +f 1400/1400/145 1383/1383/2684 1397/1397/2683 +f 1389/1389/2675 1367/1367/2677 1360/1360/2686 +f 1401/1401/2687 1402/1402/2688 1391/1391/2678 +f 1391/1391/2678 1402/1402/2688 1395/1395/2681 +f 1396/1396/2682 1357/1357/2682 1371/1371/2682 +f 1403/1403/2672 1357/1357/2682 1396/1396/2682 +f 1403/1403/2672 1358/1358/2689 1357/1357/2682 +f 1360/1360/2686 1358/1358/2689 1403/1403/2672 +f 1398/1398/2685 1402/1402/2688 1401/1401/2687 +f 1397/1397/2683 1398/1398/2685 1401/1401/2687 +f 1389/1389/2675 1360/1360/2686 1403/1403/2672 +f 1404/1404/2690 1405/1405/2691 1406/1406/2692 +f 1407/1407/2693 1405/1405/2691 1404/1404/2690 +f 1405/1405/2691 1407/1407/2693 1408/1408/2694 +f 1408/1408/2694 1409/1409/2695 1405/1405/2691 +f 1409/1409/2695 1408/1408/2694 1410/1410/2696 +f 1409/1409/2695 1410/1410/2696 1411/1411/2697 +f 1412/1412/2698 1356/1356/2699 1413/1413/2700 +f 1382/1382/2701 1414/1414/2702 1415/1415/2703 +f 1415/1415/2703 1414/1414/2702 1416/1416/2704 +f 1417/1417/2705 1351/1351/2706 1370/1370/2707 +f 1418/1418/2706 1352/1352/2708 1419/1419/2709 +f 1418/1418/2706 1373/1373/2710 1352/1352/2708 +f 1419/1419/2709 1351/1351/2706 1417/1417/2705 +f 1420/1420/56 1374/1374/56 1421/1421/56 +f 1421/1421/56 1374/1374/56 1418/1418/2706 +f 1418/1418/2706 1374/1374/56 1373/1373/2710 +f 1417/1417/2705 1354/1354/2711 1412/1412/2698 +f 1419/1419/2709 1352/1352/2708 1351/1351/2706 +f 1422/1422/56 1378/1378/56 1420/1420/56 +f 1420/1420/56 1378/1378/56 1377/1377/56 +f 1420/1420/56 1377/1377/56 1374/1374/56 +f 1370/1370/2707 1354/1354/2711 1417/1417/2705 +f 1423/1423/56 1380/1380/56 1424/1424/56 +f 1424/1424/56 1380/1380/56 1422/1422/56 +f 1422/1422/56 1380/1380/56 1378/1378/56 +f 1412/1412/2698 1354/1354/2711 1356/1356/2699 +f 1414/1414/2702 1382/1382/2701 1423/1423/56 +f 1423/1423/56 1382/1382/2701 1380/1380/56 +f 1425/1425/2712 1426/1426/2713 1427/1427/2714 +f 1425/1425/2712 1427/1427/2714 1416/1416/2704 +f 1425/1425/2712 1428/1428/2715 1426/1426/2713 +f 1412/1412/2698 1428/1428/2715 1425/1425/2712 +f 1416/1416/2704 1427/1427/2714 1415/1415/2703 +f 1412/1412/2698 1413/1413/2700 1428/1428/2715 +f 1429/1429/2716 1430/1430/2717 1431/1431/2718 +f 1431/1431/2718 1430/1430/2717 1432/1432/2719 +f 1431/1431/2718 1432/1432/2719 1433/1433/2720 +f 1431/1431/2718 1433/1433/2720 1434/1434/2721 +f 1434/1434/2721 1433/1433/2720 1435/1435/2722 +f 1411/1411/2723 1436/1436/2724 1437/1437/2725 +f 1438/1438/2726 1439/1439/2727 1440/1440/2728 +f 1441/1441/2729 1438/1438/2726 1442/1442/2730 +f 1442/1442/2730 1438/1438/2726 1440/1440/2728 +f 1442/1442/2730 1443/1443/2731 1441/1441/2729 +f 1442/1442/2730 1444/1444/2732 1445/1445/2733 +f 1445/1445/2733 1443/1443/2731 1442/1442/2730 +f 1444/1444/2732 1446/1446/2734 1445/1445/2733 +f 1447/1447/2735 1445/1445/2733 1446/1446/2734 +f 1448/1448/2736 1447/1447/2735 1446/1446/2734 +f 1448/1448/2736 1449/1449/2737 1447/1447/2735 +f 1450/1450/2738 1449/1449/2737 1448/1448/2736 +f 1450/1450/2738 1451/1451/2739 1449/1449/2737 +f 1452/1452/2740 1451/1451/2739 1450/1450/2738 +f 1452/1452/2740 1453/1453/2741 1451/1451/2739 +f 1452/1452/2740 1454/1454/2742 1453/1453/2741 +f 1436/1436/2724 1455/1455/2743 1452/1452/2740 +f 1452/1452/2740 1455/1455/2743 1454/1454/2742 +f 1456/1456/2744 1455/1455/2743 1436/1436/2724 +f 1411/1411/2723 1456/1456/2744 1436/1436/2724 +f 1409/1409/2745 1411/1411/2723 1437/1437/2725 +f 1409/1409/2745 1437/1437/2725 1457/1457/2746 +f 1457/1457/2746 1405/1405/2691 1409/1409/2745 +f 1458/1458/2747 1405/1405/2691 1457/1457/2746 +f 1458/1458/2747 1406/1406/2692 1405/1405/2691 +f 1459/1459/2748 1460/1460/2749 1406/1406/2692 +f 1459/1459/2748 1406/1406/2692 1458/1458/2747 +f 1367/1367/2750 1460/1460/2750 1459/1459/2750 +f 1367/1367/2655 1459/1459/2748 1366/1366/2654 +f 1461/1461/2751 1366/1366/2654 1459/1459/2748 +f 1461/1461/2751 1368/1368/2656 1366/1366/2654 +f 1368/1368/2656 1461/1461/2751 1355/1355/2643 +f 1355/1355/2643 1461/1461/2751 1462/1462/2752 +f 1355/1355/2643 1462/1462/2752 1356/1356/2644 +f 1462/1462/2752 1435/1435/2722 1356/1356/2644 +f 1434/1434/2721 1435/1435/2722 1462/1462/2752 +f 1434/1434/2721 1462/1462/2752 1463/1463/2753 +f 1434/1434/2721 1463/1463/2753 1431/1431/2754 +f 1431/1431/2754 1463/1463/2753 1464/1464/2755 +f 1431/1431/2754 1464/1464/2755 1429/1429/2756 +f 1464/1464/2755 1465/1465/2757 1429/1429/2756 +f 1440/1440/2728 1465/1465/2757 1464/1464/2755 +f 1440/1440/2728 1439/1439/2727 1465/1465/2757 +f 1466/1466/2758 1467/1467/2759 1439/1439/2760 +f 1439/1439/2760 1467/1467/2759 1465/1465/2761 +f 1465/1465/2761 1467/1467/2759 1468/1468/2762 +f 1465/1465/2761 1468/1468/2762 1430/1430/2717 +f 1465/1465/2761 1430/1430/2717 1429/1429/2716 +f 1411/1411/2697 1410/1410/2696 1469/1469/2763 +f 1470/1470/2764 1456/1456/2765 1411/1411/2697 +f 1470/1470/2764 1411/1411/2697 1469/1469/2763 +f 1456/1456/2765 1470/1470/2764 1471/1471/2766 +f 1471/1471/2766 1455/1455/2767 1456/1456/2765 +f 1455/1455/2767 1471/1471/2766 1472/1472/2768 +f 1437/1437/2725 1473/1473/2769 1474/1474/2770 +f 1437/1437/2725 1474/1474/2770 1457/1457/2746 +f 1457/1457/2746 1474/1474/2770 1475/1475/2771 +f 1457/1457/2746 1475/1475/2771 1458/1458/2747 +f 1458/1458/2747 1475/1475/2771 1476/1476/2772 +f 1458/1458/2747 1476/1476/2772 1459/1459/2748 +f 1459/1459/2748 1476/1476/2772 1477/1477/2773 +f 1459/1459/2748 1477/1477/2773 1461/1461/2751 +f 1461/1461/2751 1477/1477/2773 1478/1478/2774 +f 1461/1461/2751 1478/1478/2774 1462/1462/2752 +f 1462/1462/2752 1478/1478/2774 1479/1479/2775 +f 1462/1462/2752 1479/1479/2775 1463/1463/2753 +f 1463/1463/2753 1479/1479/2775 1480/1480/2776 +f 1463/1463/2753 1480/1480/2776 1464/1464/2755 +f 1464/1464/2755 1480/1480/2776 1481/1481/2777 +f 1464/1464/2755 1481/1481/2777 1440/1440/2728 +f 1440/1440/2728 1481/1481/2777 1482/1482/2778 +f 1440/1440/2728 1482/1482/2778 1442/1442/2730 +f 1442/1442/2730 1482/1482/2778 1483/1483/2779 +f 1442/1442/2730 1483/1483/2779 1444/1444/2732 +f 1444/1444/2732 1483/1483/2779 1446/1446/2734 +f 1446/1446/2734 1483/1483/2779 1484/1484/2780 +f 1446/1446/2734 1484/1484/2780 1485/1485/2781 +f 1446/1446/2734 1485/1485/2781 1448/1448/2736 +f 1448/1448/2736 1485/1485/2781 1450/1450/2738 +f 1450/1450/2738 1485/1485/2781 1486/1486/2782 +f 1450/1450/2738 1486/1486/2782 1452/1452/2740 +f 1452/1452/2740 1486/1486/2782 1487/1487/2783 +f 1452/1452/2740 1487/1487/2783 1436/1436/2724 +f 1436/1436/2724 1487/1487/2783 1473/1473/2769 +f 1436/1436/2724 1473/1473/2769 1437/1437/2725 +f 1389/1389/2784 1488/1488/2785 1489/1489/2786 +f 1389/1389/2784 1489/1489/2786 1393/1393/2787 +f 1393/1393/2787 1489/1489/2786 1391/1391/2788 +f 1391/1391/2788 1489/1489/2786 1490/1490/2789 +f 1391/1391/2788 1490/1490/2789 1491/1491/2790 +f 1391/1391/2788 1491/1491/2790 1401/1401/2791 +f 1401/1401/2791 1491/1491/2790 1397/1397/2792 +f 1491/1491/2790 1492/1492/2793 1397/1397/2792 +f 1397/1397/2792 1492/1492/2793 1400/1400/2794 +f 1492/1492/2793 1493/1493/2795 1400/1400/2794 +f 1400/1400/2794 1493/1493/2795 1399/1399/2796 +f 1399/1399/2796 1493/1493/2795 1494/1494/2797 +f 1399/1399/2796 1494/1494/2797 1394/1394/2798 +f 1494/1494/2797 1495/1495/2799 1394/1394/2798 +f 1394/1394/2798 1495/1495/2799 1387/1387/2800 +f 1495/1495/2799 1496/1496/2801 1387/1387/2800 +f 1387/1387/2800 1496/1496/2801 1386/1386/2802 +f 1386/1386/2802 1496/1496/2801 1497/1497/2803 +f 1386/1386/2802 1497/1497/2803 1385/1385/2804 +f 1497/1497/2803 1498/1498/2805 1385/1385/2804 +f 1385/1385/2804 1498/1498/2805 1384/1384/2806 +f 1384/1384/2806 1498/1498/2805 1499/1499/2807 +f 1384/1384/2806 1499/1499/2807 1388/1388/2808 +f 1499/1499/2807 1500/1500/2809 1388/1388/2808 +f 1388/1388/2808 1500/1500/2809 1396/1396/2810 +f 1396/1396/2810 1500/1500/2809 1403/1403/2811 +f 1500/1500/2809 1501/1501/2812 1403/1403/2811 +f 1403/1403/2811 1501/1501/2812 1389/1389/2784 +f 1501/1501/2812 1488/1488/2785 1389/1389/2784 +f 1424/1424/2813 1502/1502/2814 1503/1503/2815 +f 1424/1424/2813 1503/1503/2815 1423/1423/2816 +f 1423/1423/2816 1503/1503/2815 1504/1504/2817 +f 1423/1423/2816 1504/1504/2817 1414/1414/2818 +f 1414/1414/2818 1504/1504/2817 1505/1505/2819 +f 1414/1414/2818 1505/1505/2819 1416/1416/2820 +f 1416/1416/2820 1505/1505/2819 1506/1506/2821 +f 1416/1416/2820 1506/1506/2821 1425/1425/2822 +f 1425/1425/2822 1506/1506/2821 1507/1507/2823 +f 1425/1425/2822 1507/1507/2823 1412/1412/2824 +f 1412/1412/2824 1507/1507/2823 1508/1508/2825 +f 1412/1412/2824 1508/1508/2825 1509/1509/2826 +f 1412/1412/2824 1509/1509/2826 1417/1417/2827 +f 1417/1417/2827 1509/1509/2826 1510/1510/2828 +f 1417/1417/2827 1510/1510/2828 1419/1419/2829 +f 1419/1419/2829 1510/1510/2828 1511/1511/2830 +f 1419/1419/2829 1511/1511/2830 1418/1418/2831 +f 1418/1418/2831 1511/1511/2830 1512/1512/2832 +f 1418/1418/2831 1512/1512/2832 1421/1421/2833 +f 1421/1421/2833 1512/1512/2832 1513/1513/2834 +f 1421/1421/2833 1513/1513/2834 1420/1420/2835 +f 1420/1420/2835 1513/1513/2834 1514/1514/2836 +f 1420/1420/2835 1514/1514/2836 1515/1515/2837 +f 1420/1420/2835 1515/1515/2837 1422/1422/2838 +f 1422/1422/2838 1515/1515/2837 1502/1502/2814 +f 1422/1422/2838 1502/1502/2814 1424/1424/2813 +f 1466/1466/2758 1439/1439/2760 1516/1516/2839 +f 1516/1516/2839 1439/1439/2760 1438/1438/2840 +f 1516/1516/2839 1438/1438/2840 1517/1517/2841 +f 1517/1517/2841 1438/1438/2840 1441/1441/2842 +f 1517/1517/2841 1441/1441/2842 1518/1518/2843 +f 1518/1518/2843 1441/1441/2842 1519/1519/2844 +f 1520/1520/2845 1521/1521/2846 1453/1453/2847 +f 1520/1520/2845 1454/1454/2848 1522/1522/2849 +f 1522/1522/2849 1454/1454/2850 1523/1523/2851 +f 1520/1520/2845 1453/1453/2847 1454/1454/2848 +f 1523/1523/2851 1454/1454/2850 1455/1455/2767 +f 1523/1523/2851 1455/1455/2767 1472/1472/2768 +f 1518/1518/2843 1519/1519/2852 1524/1524/2853 +f 1427/1427/2714 1516/1516/2839 1525/1525/2854 +f 1427/1427/2714 1525/1525/2854 1415/1415/2703 +f 1525/1525/2854 1524/1524/2855 1415/1415/2703 +f 1427/1427/2714 1467/1467/2759 1516/1516/2839 +f 1467/1467/2759 1466/1466/2758 1516/1516/2839 +f 1516/1516/2839 1517/1517/2841 1525/1525/2854 +f 1525/1525/2854 1517/1517/2841 1524/1524/2853 +f 1524/1524/2853 1517/1517/2841 1518/1518/2843 +f 1430/1430/2717 1468/1468/2762 1426/1426/2713 +f 1468/1468/2762 1467/1467/2759 1426/1426/2713 +f 1426/1426/2713 1467/1467/2759 1427/1427/2714 +f 1426/1426/2713 1428/1428/2715 1430/1430/2717 +f 1428/1428/2715 1432/1432/2719 1430/1430/2717 +f 1433/1433/2720 1432/1432/2719 1413/1413/2856 +f 1433/1433/2720 1413/1413/2856 1356/1356/2857 +f 1433/1433/2720 1356/1356/2857 1435/1435/2722 +f 1432/1432/2719 1428/1428/2715 1413/1413/2856 +f 1520/1520/2845 1526/1526/2858 1521/1521/2846 +f 1472/1472/2768 1527/1527/2859 1523/1523/2851 +f 1523/1523/2851 1527/1527/2859 1522/1522/2849 +f 1520/1520/2845 1522/1522/2849 1526/1526/2858 +f 1522/1522/2849 1528/1528/2860 1526/1526/2858 +f 1527/1527/2859 1528/1528/2860 1522/1522/2849 +f 1526/1526/2858 1528/1528/2860 1398/1398/2685 +f 1528/1528/2860 1527/1527/2859 1402/1402/2688 +f 1528/1528/2860 1402/1402/2688 1398/1398/2685 +f 1527/1527/2859 1395/1395/2681 1402/1402/2688 +f 1472/1472/2768 1471/1471/2766 1527/1527/2859 +f 1527/1527/2859 1471/1471/2766 1395/1395/2681 +f 1471/1471/2766 1470/1470/2764 1395/1395/2681 +f 1392/1392/2679 1469/1469/2861 1410/1410/2862 +f 1392/1392/2679 1410/1410/2862 1390/1390/2676 +f 1395/1395/2681 1470/1470/2764 1469/1469/2861 +f 1395/1395/2681 1469/1469/2861 1392/1392/2679 +f 1404/1404/2690 1406/1406/2692 1460/1460/2863 +f 1404/1404/2690 1460/1460/2863 1407/1407/2693 +f 1407/1407/2693 1460/1460/2863 1367/1367/2864 +f 1407/1407/2693 1367/1367/2864 1408/1408/2865 +f 1408/1408/2865 1367/1367/2864 1390/1390/2676 +f 1408/1408/2865 1390/1390/2676 1410/1410/2862 +f 1371/1371/2659 1357/1357/2645 1353/1353/2641 +f 1349/1349/2637 1348/1348/2636 1352/1352/2640 +f 325/325/145 327/327/145 322/322/145 +f 322/322/145 329/329/145 320/320/145 +f 320/320/145 329/329/145 298/298/145 +f 320/320/145 298/298/145 319/319/145 +f 319/319/145 300/300/145 316/316/145 +f 316/316/145 300/300/145 302/302/145 +f 316/316/145 302/302/145 314/314/145 +f 314/314/145 305/305/145 307/307/145 +f 327/327/145 329/329/145 322/322/145 +f 314/314/145 307/307/145 313/313/145 +f 298/298/145 300/300/145 319/319/145 +f 302/302/145 305/305/145 314/314/145 +f 313/313/145 307/307/145 311/311/145 +f 311/311/145 307/307/145 309/309/145 +f 508/508/56 513/513/56 507/507/56 +f 482/482/56 504/504/56 507/507/56 +f 508/508/56 511/511/56 513/513/56 +f 482/482/56 503/503/56 504/504/56 +f 485/485/56 486/486/56 503/503/56 +f 486/486/56 500/500/56 503/503/56 +f 503/503/56 482/482/56 485/485/56 +f 486/486/56 499/499/56 500/500/56 +f 486/486/56 489/489/56 499/499/56 +f 497/497/56 499/499/56 489/489/56 +f 489/489/56 491/491/56 497/497/56 +f 491/491/56 495/495/56 497/497/56 +f 491/491/56 493/493/56 495/495/56 +f 507/507/56 513/513/56 482/482/56 +f 164/164/2866 193/193/2867 197/197/2868 +f 193/193/2867 172/172/2869 197/197/2868 +f 172/172/2869 194/194/2870 197/197/2868 +f 164/164/2866 173/173/2871 193/193/2867 +f 195/195/387 183/183/388 199/199/2872 +f 185/185/2873 199/199/2872 183/183/388 +f 196/196/392 199/199/2872 185/185/2873 +f 162/162/391 186/186/2874 198/198/2875 +f 162/162/391 199/199/2872 196/196/392 +f 262/262/2876 218/218/2877 244/244/2878 +f 216/216/2879 218/218/2877 262/262/2876 +f 262/262/2876 244/244/2878 272/272/2880 +f 272/272/2880 244/244/2878 240/240/2881 +f 266/266/2882 243/243/2883 297/297/2884 +f 265/265/560 266/266/2882 297/297/2884 +f 199/199/2872 162/162/391 198/198/2875 +f 265/265/560 297/297/2884 219/219/2885 +f 1479/1479/2634 1481/1481/2634 1480/1480/2886 +f 1479/1479/2634 1485/1485/2634 1481/1481/2634 +f 1482/1482/2887 1481/1481/2634 1483/1483/2634 +f 1483/1483/2634 1481/1481/2634 1485/1485/2634 +f 1479/1479/2634 1478/1478/2888 1477/1477/2634 +f 1485/1485/2634 1484/1484/2889 1483/1483/2634 +f 1476/1476/2890 1474/1474/2634 1477/1477/2634 +f 1486/1486/2634 1485/1485/2634 1477/1477/2634 +f 212/212/558 265/265/560 219/219/2885 +f 1485/1485/2634 1479/1479/2634 1477/1477/2634 +f 1474/1474/2634 1486/1486/2634 1477/1477/2634 +f 1486/1486/2634 1474/1474/2634 1487/1487/2891 +f 1475/1475/2892 1474/1474/2634 1476/1476/2890 +f 1487/1487/2891 1474/1474/2634 1473/1473/2893 +f 1492/1492/145 1491/1491/145 1493/1493/145 +f 1493/1493/145 1491/1491/145 1490/1490/145 +f 1493/1493/145 1490/1490/145 1489/1489/145 +f 1494/1494/145 1493/1493/145 1489/1489/145 +f 1494/1494/145 1489/1489/145 1488/1488/145 +f 1494/1494/145 1488/1488/145 1495/1495/145 +f 1488/1488/145 1496/1496/145 1495/1495/145 +f 1488/1488/145 1501/1501/145 1496/1496/145 +f 1501/1501/145 1500/1500/145 1496/1496/145 +f 1500/1500/145 1497/1497/145 1496/1496/145 +f 1500/1500/145 1498/1498/145 1497/1497/145 +f 1500/1500/145 1499/1499/145 1498/1498/145 +f 1505/1505/56 1504/1504/56 1503/1503/56 +f 1503/1503/56 1511/1511/56 1505/1505/56 +f 1507/1507/56 1506/1506/56 1505/1505/56 +f 1511/1511/56 1510/1510/56 1509/1509/56 +f 1502/1502/56 1515/1515/56 1503/1503/56 +f 1507/1507/56 1511/1511/56 1508/1508/56 +f 1514/1514/56 1513/1513/56 1515/1515/56 +f 1511/1511/56 1509/1509/56 1508/1508/56 +f 1511/1511/56 1507/1507/56 1505/1505/56 +f 1513/1513/56 1503/1503/56 1515/1515/56 +f 1511/1511/56 1513/1513/56 1512/1512/56 +f 1511/1511/56 1503/1503/56 1513/1513/56 +f 1443/1443/2894 1519/1519/2844 1441/1441/2842 +f 1443/1443/2894 1445/1445/2895 1519/1519/2844 +f 1449/1449/2896 1521/1521/2846 1519/1519/2844 +f 1445/1445/2895 1447/1447/2897 1519/1519/2844 +f 1524/1524/2898 1398/1398/2899 1415/1415/2900 +f 1382/1382/2901 1398/1398/2899 1383/1383/2902 +f 1447/1447/2897 1449/1449/2896 1519/1519/2844 +f 1398/1398/2899 1382/1382/2901 1415/1415/2900 +f 1449/1449/2896 1451/1451/2903 1521/1521/2846 +f 1398/1398/2899 1524/1524/2898 1526/1526/2904 +f 1524/1524/2898 1519/1519/2844 1526/1526/2904 +f 1519/1519/2844 1521/1521/2846 1526/1526/2904 +f 1453/1453/2847 1521/1521/2846 1451/1451/2903 +f 1529/1529/2905 1530/1530/2906 1531/1531/2907 +f 1530/1530/2906 1532/1532/2908 1531/1531/2907 +f 1533/1533/2909 1534/1534/2910 1535/1535/2911 +f 1535/1535/2911 1534/1534/2910 1536/1536/2912 +f 1532/1532/2913 1537/1537/2914 1538/1538/2915 +f 1532/1532/2913 1538/1538/2915 1539/1539/2916 +f 1529/1529/2917 1531/1531/2918 1540/1540/2919 +f 1540/1540/2919 1531/1531/2918 1541/1541/2920 +f 1540/1540/2919 1541/1541/2920 1542/1542/2921 +f 1542/1542/2921 1541/1541/2920 1543/1543/2922 +f 1542/1542/2921 1543/1543/2922 1544/1544/2923 +f 1544/1544/2923 1543/1543/2922 1545/1545/2924 +f 1533/1533/2925 1546/1546/2926 1547/1547/2927 +f 1547/1547/2927 1546/1546/2926 1548/1548/2928 +f 1536/1536/2929 1534/1534/2930 1549/1549/2931 +f 1549/1549/2931 1534/1534/2930 1550/1550/2932 +f 1549/1549/2931 1550/1550/2932 1551/1551/2933 +f 1551/1551/2933 1550/1550/2932 1552/1552/2934 +f 1551/1551/2933 1552/1552/2934 1553/1553/2935 +f 1553/1553/2935 1552/1552/2934 1554/1554/2936 +f 1555/1555/2937 1550/1550/2938 1547/1547/2939 +f 1556/1556/2940 1557/1557/2941 1558/1558/2941 +f 1541/1541/2942 1559/1559/2943 1543/1543/2944 +f 1543/1543/2944 1559/1559/2943 1560/1560/2945 +f 1560/1560/2945 1548/1548/2946 1543/1543/2944 +f 1547/1547/2939 1558/1558/2941 1555/1555/2937 +f 1550/1550/2938 1555/1555/2937 1561/1561/2939 +f 1550/1550/2938 1561/1561/2939 1552/1552/2947 +f 1562/1562/2948 1539/1539/2949 1538/1538/2950 +f 1560/1560/2945 1556/1556/2940 1548/1548/2946 +f 1548/1548/2946 1556/1556/2940 1547/1547/2939 +f 1556/1556/2940 1558/1558/2941 1547/1547/2939 +f 1552/1552/2947 1561/1561/2939 1557/1557/2941 +f 1538/1538/2950 1552/1552/2947 1557/1557/2941 +f 1562/1562/2948 1559/1559/2943 1541/1541/2942 +f 1556/1556/2940 1562/1562/2948 1557/1557/2941 +f 1557/1557/2941 1562/1562/2948 1538/1538/2950 +f 1562/1562/2948 1541/1541/2942 1539/1539/2949 +f 1553/1553/2951 1554/1554/2952 1537/1537/2953 +f 1537/1537/2953 1563/1563/2954 1553/1553/2951 +f 1546/1546/2955 1564/1564/2956 1545/1545/2957 +f 1545/1545/2957 1564/1564/2956 1565/1565/2958 +f 1545/1545/2957 1565/1565/2958 1544/1544/2959 +f 1551/1551/2960 1566/1566/2961 1567/1567/2962 +f 1566/1566/2961 1568/1568/2963 1569/1569/2961 +f 1570/1570/2964 1569/1569/2961 1571/1571/2965 +f 1566/1566/2961 1551/1551/2960 1568/1568/2963 +f 1570/1570/2964 1571/1571/2965 1572/1572/2963 +f 1566/1566/2961 1569/1569/2961 1570/1570/2964 +f 1549/1549/2963 1551/1551/2960 1567/1567/2962 +f 1567/1567/2962 1573/1573/2966 1549/1549/2963 +f 1572/1572/2963 1573/1573/2966 1567/1567/2962 +f 1571/1571/2965 1574/1574/2966 1572/1572/2963 +f 1572/1572/2963 1574/1574/2966 1573/1573/2966 +f 1535/1535/2967 1573/1573/2968 1574/1574/2969 +f 1535/1535/2967 1574/1574/2969 1575/1575/2970 +f 1575/1575/2970 1574/1574/2969 1571/1571/2971 +f 1575/1575/2970 1571/1571/2971 1576/1576/2972 +f 1576/1576/2973 1571/1571/2974 1569/1569/2975 +f 1576/1576/2973 1569/1569/2975 1577/1577/2976 +f 1577/1577/2977 1569/1569/2978 1563/1563/2979 +f 1568/1568/2980 1563/1563/2979 1569/1569/2978 +f 1557/1557/2981 1566/1566/2981 1570/1570/2981 +f 1557/1557/2982 1570/1570/2982 1558/1558/2982 +f 1558/1558/2983 1570/1570/2983 1572/1572/2983 +f 1558/1558/2984 1572/1572/2984 1555/1555/2984 +f 1555/1555/2985 1572/1572/2985 1567/1567/2985 +f 1555/1555/2986 1567/1567/2986 1561/1561/2986 +f 1561/1561/2987 1567/1567/2987 1566/1566/2987 +f 1561/1561/2988 1566/1566/2988 1557/1557/2988 +f 1578/1578/2989 1579/1579/2962 1580/1580/2990 +f 1580/1580/2990 1581/1581/2991 1582/1582/2992 +f 1583/1583/2993 1542/1542/2962 1584/1584/2961 +f 1540/1540/2994 1542/1542/2962 1583/1583/2993 +f 1582/1582/2992 1581/1581/2991 1585/1585/2995 +f 1580/1580/2990 1579/1579/2962 1581/1581/2991 +f 1584/1584/2961 1586/1586/2996 1578/1578/2989 +f 1578/1578/2989 1586/1586/2996 1587/1587/2989 +f 1582/1582/2992 1585/1585/2995 1583/1583/2993 +f 1583/1583/2993 1585/1585/2995 1540/1540/2994 +f 1578/1578/2989 1587/1587/2989 1579/1579/2962 +f 1584/1584/2961 1542/1542/2962 1586/1586/2996 +f 1530/1530/2997 1585/1585/2998 1581/1581/2999 +f 1586/1586/3000 1588/1588/3001 1587/1587/3002 +f 1587/1587/3003 1588/1588/3004 1579/1579/3005 +f 1579/1579/3005 1588/1588/3004 1589/1589/3006 +f 1579/1579/3007 1589/1589/3008 1581/1581/2999 +f 1581/1581/2999 1589/1589/3008 1530/1530/2997 +f 1586/1586/3000 1564/1564/3009 1588/1588/3001 +f 1565/1565/3010 1564/1564/3009 1586/1586/3000 +f 1562/1562/3011 1582/1582/3012 1559/1559/3013 +f 1559/1559/3013 1582/1582/3012 1583/1583/3014 +f 1559/1559/3015 1583/1583/3016 1560/1560/3017 +f 1560/1560/3017 1583/1583/3016 1584/1584/3018 +f 1560/1560/3019 1584/1584/3020 1556/1556/3021 +f 1556/1556/3021 1584/1584/3020 1578/1578/3022 +f 1556/1556/3023 1578/1578/3024 1580/1580/3025 +f 1556/1556/3023 1580/1580/3025 1562/1562/3026 +f 1562/1562/3027 1580/1580/3027 1582/1582/3027 +f 1529/1529/3028 1540/1540/3029 1585/1585/2998 +f 1529/1529/3028 1585/1585/2998 1530/1530/2997 +f 1586/1586/3000 1542/1542/3030 1565/1565/3010 +f 1542/1542/3031 1544/1544/3031 1565/1565/3031 +f 1536/1536/3032 1549/1549/3032 1573/1573/3032 +f 1536/1536/3033 1573/1573/2968 1535/1535/2967 +f 1568/1568/2980 1553/1553/3034 1563/1563/2979 +f 1551/1551/3035 1553/1553/3034 1568/1568/2980 +f 1539/1539/2916 1531/1531/3036 1532/1532/2913 +f 1541/1541/3037 1531/1531/3036 1539/1539/2916 +f 1554/1554/3038 1552/1552/3039 1538/1538/3040 +f 1554/1554/3038 1538/1538/3040 1537/1537/3041 +f 1545/1545/2924 1543/1543/2922 1548/1548/3042 +f 1545/1545/3043 1548/1548/2928 1546/1546/2926 +f 1547/1547/3044 1550/1550/3045 1534/1534/3046 +f 1547/1547/3044 1534/1534/3046 1533/1533/3047 +f 1564/1564/3048 1546/1546/3049 1588/1588/3050 +f 1532/1532/3051 1530/1530/3052 1589/1589/3053 +f 1589/1589/3053 1588/1588/3050 1575/1575/3054 +f 1576/1576/3055 1577/1577/3056 1589/1589/3053 +f 1588/1588/3050 1546/1546/3049 1575/1575/3054 +f 1533/1533/3057 1535/1535/3058 1575/1575/3054 +f 1532/1532/3051 1589/1589/3053 1577/1577/3056 +f 1546/1546/3049 1533/1533/3057 1575/1575/3054 +f 1537/1537/3059 1532/1532/3051 1577/1577/3056 +f 1575/1575/3054 1576/1576/3055 1589/1589/3053 +f 1577/1577/3056 1563/1563/3060 1537/1537/3059 +f 1590/1590/3061 1591/1591/3062 1592/1592/3063 +f 1593/1593/3064 1594/1594/3065 1595/1595/3066 +f 1595/1595/3066 1594/1594/3065 1596/1596/3067 +f 1593/1593/3064 1597/1597/3068 1594/1594/3065 +f 1598/1598/3069 1597/1597/3068 1593/1593/3064 +f 1599/1599/3070 1600/1600/3071 1593/1593/3064 +f 1593/1593/3064 1600/1600/3071 1598/1598/3069 +f 1591/1591/3062 1600/1600/3071 1592/1592/3063 +f 1592/1592/3063 1600/1600/3071 1599/1599/3070 +f 1592/1592/3063 1595/1595/3072 1590/1590/3061 +f 1601/1601/3073 1602/1602/3074 1603/1603/3075 +f 1604/1604/3076 1601/1601/3073 1603/1603/3075 +f 1605/1605/3077 1606/1606/3078 1607/1607/3079 +f 1606/1606/3080 1608/1608/3081 1607/1607/3082 +f 1607/1607/3082 1608/1608/3081 1609/1609/3083 +f 1608/1608/3084 1610/1610/3085 1609/1609/3086 +f 1609/1609/3086 1610/1610/3085 1602/1602/3087 +f 1602/1602/3088 1610/1610/3089 1611/1611/3090 +f 1602/1602/3088 1611/1611/3090 1612/1612/3091 +f 1612/1612/3092 1611/1611/3093 1613/1613/3094 +f 1613/1613/3094 1611/1611/3093 1614/1614/3095 +f 1613/1613/3096 1614/1614/3097 1605/1605/3098 +f 1614/1614/3097 1615/1615/3099 1605/1605/3098 +f 1605/1605/3077 1615/1615/3100 1606/1606/3078 +f 1615/1615/3101 1616/1616/3102 1617/1617/3103 +f 1615/1615/3101 1617/1617/3103 1606/1606/3104 +f 1610/1610/3105 1618/1618/3106 1611/1611/3107 +f 1610/1610/3105 1619/1619/3108 1618/1618/3106 +f 1608/1608/3109 1619/1619/3108 1610/1610/3105 +f 1606/1606/3104 1617/1617/3103 1620/1620/3110 +f 1611/1611/3107 1618/1618/3106 1621/1621/3111 +f 1608/1608/3109 1620/1620/3110 1619/1619/3108 +f 1606/1606/3104 1620/1620/3110 1608/1608/3109 +f 1614/1614/3112 1622/1622/3113 1623/1623/3114 +f 1614/1614/3112 1623/1623/3114 1615/1615/3101 +f 1615/1615/3101 1623/1623/3114 1616/1616/3102 +f 1611/1611/3107 1621/1621/3111 1622/1622/3113 +f 1611/1611/3107 1622/1622/3113 1614/1614/3112 +f 1594/1594/3115 1617/1617/3116 1616/1616/3117 +f 1617/1617/3118 1594/1594/3119 1620/1620/3120 +f 1620/1620/3120 1594/1594/3119 1597/1597/3121 +f 1597/1597/3122 1598/1598/3123 1620/1620/3124 +f 1620/1620/3124 1598/1598/3123 1619/1619/3125 +f 1598/1598/3126 1600/1600/3126 1619/1619/3126 +f 1619/1619/3127 1600/1600/3128 1618/1618/3129 +f 1618/1618/3129 1600/1600/3128 1591/1591/3130 +f 1618/1618/3129 1591/1591/3130 1621/1621/3131 +f 1591/1591/3130 1590/1590/3132 1621/1621/3131 +f 1621/1621/3131 1590/1590/3132 1622/1622/3133 +f 1590/1590/3134 1595/1595/3135 1622/1622/3136 +f 1622/1622/3136 1595/1595/3135 1623/1623/3137 +f 1623/1623/3138 1595/1595/3139 1616/1616/3140 +f 1595/1595/3139 1596/1596/3141 1616/1616/3140 +f 1616/1616/3117 1596/1596/3142 1594/1594/3115 +f 1592/1592/3143 1599/1599/3144 1624/1624/3145 +f 1624/1624/3145 1599/1599/3144 1625/1625/3146 +f 1595/1595/3147 1592/1592/3147 1626/1626/3147 +f 1626/1626/3148 1592/1592/3148 1624/1624/3148 +f 1593/1593/3149 1595/1595/3150 1627/1627/3151 +f 1627/1627/3151 1595/1595/3150 1626/1626/3152 +f 1599/1599/3153 1593/1593/3154 1625/1625/3155 +f 1625/1625/3155 1593/1593/3154 1627/1627/3156 +f 1625/1625/2964 1627/1627/2964 1626/1626/2964 +f 1625/1625/2964 1626/1626/2964 1624/1624/2964 +f 1605/1605/3098 1604/1604/3157 1613/1613/3096 +f 1613/1613/3158 1604/1604/3159 1603/1603/3160 +f 1613/1613/3158 1603/1603/3160 1612/1612/3161 +f 1612/1612/3162 1603/1603/3162 1602/1602/3162 +f 1609/1609/3163 1602/1602/3074 1601/1601/3073 +f 1609/1609/3083 1601/1601/3164 1607/1607/3082 +f 1607/1607/3165 1601/1601/3166 1604/1604/3167 +f 1607/1607/3165 1604/1604/3167 1605/1605/3168 +f 1628/1628/3169 1629/1629/3170 1630/1630/3171 +f 1630/1630/3171 1631/1631/3172 1628/1628/3169 +f 1632/1632/3173 1633/1633/3174 1634/1634/3175 +f 1635/1635/3176 1636/1636/3177 1637/1637/3178 +f 1634/1634/3175 1633/1633/3174 1635/1635/3176 +f 1637/1637/3178 1638/1638/3179 1631/1631/3172 +f 1637/1637/3178 1631/1631/3172 1630/1630/3171 +f 1636/1636/3177 1638/1638/3179 1637/1637/3178 +f 1634/1634/3175 1635/1635/3176 1637/1637/3178 +f 1630/1630/3171 1629/1629/3170 1634/1634/3175 +f 1634/1634/3175 1629/1629/3170 1632/1632/3173 +f 1639/1639/3180 1640/1640/3181 1641/1641/3182 +f 1641/1641/3182 1642/1642/3183 1639/1639/3180 +f 1641/1641/3184 1643/1643/3185 1644/1644/3186 +f 1643/1643/3185 1645/1645/3187 1644/1644/3186 +f 1645/1645/3188 1646/1646/3188 1644/1644/3188 +f 1644/1644/3189 1646/1646/3190 1647/1647/3191 +f 1644/1644/3189 1647/1647/3191 1648/1648/3192 +f 1647/1647/3193 1649/1649/3193 1648/1648/3193 +f 1648/1648/3194 1649/1649/3195 1650/1650/3196 +f 1650/1650/3196 1649/1649/3195 1651/1651/3197 +f 1650/1650/3198 1651/1651/3199 1652/1652/3200 +f 1652/1652/3200 1651/1651/3199 1653/1653/3201 +f 1652/1652/3202 1653/1653/3203 1643/1643/3204 +f 1652/1652/3202 1643/1643/3204 1641/1641/3205 +f 1645/1645/3206 1654/1654/3207 1655/1655/3208 +f 1645/1645/3206 1655/1655/3208 1646/1646/3209 +f 1653/1653/3210 1656/1656/3211 1645/1645/3206 +f 1645/1645/3206 1656/1656/3211 1654/1654/3207 +f 1649/1649/3212 1657/1657/3213 1658/1658/3214 +f 1649/1649/3212 1658/1658/3214 1651/1651/3215 +f 1647/1647/3216 1657/1657/3213 1649/1649/3212 +f 1651/1651/3215 1658/1658/3214 1659/1659/3217 +f 1647/1647/3216 1660/1660/3218 1657/1657/3213 +f 1646/1646/3209 1660/1660/3218 1647/1647/3216 +f 1646/1646/3209 1655/1655/3208 1660/1660/3218 +f 1653/1653/3210 1661/1661/3219 1656/1656/3211 +f 1651/1651/3215 1659/1659/3217 1653/1653/3210 +f 1653/1653/3210 1659/1659/3217 1661/1661/3219 +f 1628/1628/3220 1631/1631/3221 1654/1654/3222 +f 1654/1654/3222 1631/1631/3221 1655/1655/3223 +f 1655/1655/3224 1631/1631/3225 1660/1660/3226 +f 1660/1660/3226 1631/1631/3225 1638/1638/3227 +f 1638/1638/3228 1636/1636/3229 1660/1660/3230 +f 1660/1660/3230 1636/1636/3229 1657/1657/3231 +f 1657/1657/3232 1636/1636/3233 1635/1635/3234 +f 1657/1657/3232 1635/1635/3234 1658/1658/3235 +f 1658/1658/3235 1635/1635/3234 1633/1633/3236 +f 1658/1658/3235 1633/1633/3236 1659/1659/3237 +f 1633/1633/3236 1632/1632/3238 1659/1659/3237 +f 1659/1659/3239 1632/1632/3240 1661/1661/3241 +f 1632/1632/3240 1629/1629/3242 1661/1661/3241 +f 1661/1661/3241 1629/1629/3242 1656/1656/3243 +f 1656/1656/3243 1629/1629/3242 1628/1628/3244 +f 1656/1656/3243 1628/1628/3244 1654/1654/3245 +f 1634/1634/3246 1637/1637/3246 1662/1662/3246 +f 1663/1663/3247 1634/1634/3247 1662/1662/3247 +f 1630/1630/3248 1634/1634/3248 1663/1663/3248 +f 1664/1664/3249 1630/1630/3249 1663/1663/3249 +f 1637/1637/3250 1630/1630/3250 1664/1664/3250 +f 1662/1662/3251 1637/1637/3251 1664/1664/3251 +f 1662/1662/2960 1664/1664/2960 1663/1663/2960 +f 1645/1645/3252 1643/1643/3252 1653/1653/3252 +f 1652/1652/3253 1641/1641/3253 1640/1640/3253 +f 1652/1652/3254 1640/1640/3255 1639/1639/3256 +f 1652/1652/3254 1639/1639/3256 1650/1650/3257 +f 1650/1650/3258 1639/1639/3259 1642/1642/3260 +f 1650/1650/3258 1642/1642/3260 1648/1648/3261 +f 1648/1648/3192 1642/1642/3262 1644/1644/3189 +f 1644/1644/3263 1642/1642/3183 1641/1641/3182 +f 775/775/3264 1025/1025/3265 778/778/3266 +f 778/778/3266 1025/1025/3265 1028/1028/3267 +f 780/780/3268 778/778/3266 1028/1028/3267 +f 993/993/145 992/992/145 986/986/145 +f 988/988/145 990/990/145 989/989/145 +f 991/991/145 990/990/145 988/988/145 +f 988/988/145 987/987/145 991/991/145 +f 987/987/145 992/992/145 991/991/145 +f 986/986/145 992/992/145 987/987/145 +f 1004/1004/145 1011/1011/145 1013/1013/145 +f 1005/1005/145 1003/1003/145 1007/1007/145 +f 1008/1008/145 1007/1007/145 1003/1003/145 +f 1013/1013/145 1003/1003/145 1004/1004/145 +f 1013/1013/145 1008/1008/145 1003/1003/145 +f 1011/1011/145 1012/1012/145 1013/1013/145 +f 1005/1005/145 1007/1007/145 1006/1006/145 +f 982/982/145 985/985/145 983/983/145 +f 982/982/145 977/977/145 985/985/145 +f 981/981/145 977/977/145 982/982/145 +f 981/981/145 976/976/145 977/977/145 +f 981/981/145 980/980/3269 976/976/145 +f 980/980/3269 978/978/3269 976/976/145 +f 979/979/3270 978/978/3269 980/980/3269 +f 1002/1002/145 1000/1000/145 1001/1001/145 +f 999/999/145 1000/1000/145 1002/1002/145 +f 999/999/145 995/995/145 1000/1000/145 +f 999/999/145 998/998/145 995/995/145 +f 998/998/145 996/996/145 995/995/145 +f 998/998/145 997/997/145 996/996/145 +f 843/843/3271 830/830/2635 829/829/3272 +f 794/794/3273 793/793/3273 925/925/3273 +f 830/830/2635 843/843/3271 841/841/3274 +f 830/830/2635 841/841/3274 831/831/2635 +f 840/840/3274 831/831/2635 841/841/3274 +f 840/840/3274 832/832/2635 831/831/2635 +f 840/840/3274 833/833/2635 832/832/2635 +f 839/839/2635 833/833/2635 840/840/3274 +f 839/839/2635 834/834/3274 833/833/2635 +f 834/834/3274 839/839/2635 835/835/3271 +f 839/839/2635 837/837/3271 836/836/3275 +f 839/839/2635 838/838/3276 837/837/3271 +f 841/841/3274 843/843/3271 842/842/3277 +f 835/835/3271 839/839/2635 836/836/3275 +f 821/821/56 794/794/56 925/925/56 +f 803/803/56 827/827/3278 828/828/56 +f 925/925/56 940/940/56 938/938/56 +f 936/936/56 925/925/56 938/938/56 +f 936/936/56 934/934/56 925/925/56 +f 925/925/56 803/803/56 822/822/56 +f 803/803/56 828/828/56 822/822/56 +f 934/934/56 930/930/56 925/925/56 +f 925/925/56 930/930/56 803/803/56 +f 930/930/56 934/934/56 932/932/56 +f 827/827/3278 803/803/56 802/802/3279 +f 821/821/56 925/925/56 822/822/56 +f 3600/1665/3280 3633/1666/3280 3598/1667/3280 +f 3338/1668/3281 3337/1669/3281 3336/1670/3281 +f 2140/1671/3282 2148/1672/3283 2112/1673/3284 +f 3385/1674/3285 3400/1675/3286 3401/1676/3287 +f 3860/1677/3288 3858/1678/3289 3867/1679/3289 +f 3625/1680/3290 3641/1681/3291 3622/1682/3292 +f 3868/1683/3293 3894/1684/3294 3893/1685/3295 +f 2973/1686/3296 2974/1687/3296 2976/1688/3296 +f 2482/1689/3297 2483/1690/3298 2256/1691/3299 +f 1902/1692/3300 1901/1693/3301 1990/1694/3302 +f 1814/1695/3303 1813/1696/3304 1815/1697/3305 +f 2288/1698/3306 2287/1699/3307 2289/1700/3308 +f 3081/1701/3309 3197/1702/3309 3082/1703/3309 +f 2795/1704/3310 2814/1705/3311 2828/1706/3312 +f 3691/1707/3313 3692/1708/3314 3690/1709/3315 +f 3665/1710/3316 3668/1711/3317 3655/1712/3318 +f 3282/1713/3319 3265/1714/3320 3283/1715/3321 +f 3876/1716/3289 3875/1717/3289 3846/1718/3289 +f 1745/1719/3322 1744/1720/3323 1779/1721/3324 +f 3288/1722/3325 3204/1723/3326 3207/1724/3327 +f 2877/1725/3328 2876/1726/3329 2878/1727/3330 +f 2776/1728/3331 2752/1729/3332 2777/1730/3333 +f 3651/1731/3334 3650/1732/3335 3660/1733/3336 +f 2144/1734/3337 2143/1735/3338 2142/1736/3339 +f 3612/1737/3280 3614/1738/3280 3622/1682/3280 +f 3522/1739/3340 3521/1740/3341 3533/1741/3342 +f 3741/1742/3343 3743/1743/3344 3714/1744/3345 +f 3388/1745/3346 3406/1746/3347 3427/1747/3348 +f 1811/1748/3349 1818/1749/3350 1820/1750/3351 +f 2997/1751/3352 3000/1752/3353 2998/1753/3354 +f 3163/1754/3355 3162/1755/3356 3141/1756/3357 +f 3774/1757/3358 3775/1758/3359 3781/1759/3360 +f 3211/1760/3361 3207/1724/3362 3203/1761/3362 +f 3531/1762/3363 3520/1763/3364 3519/1764/3365 +f 2060/1765/3366 2220/1766/3367 2062/1767/3368 +f 2369/1768/3369 2351/1769/3370 2367/1770/3371 +f 3795/1771/3372 3697/1772/3373 3793/1773/3374 +f 3299/1774/3375 3213/1775/3376 3297/1776/3377 +f 3475/1777/3378 3474/1778/3379 3476/1779/3380 +f 3621/1780/3381 3637/1781/3382 3623/1782/3383 +f 3764/1783/3384 3765/1784/3385 3796/1785/3386 +f 3340/1786/3281 3338/1668/3281 3336/1670/3281 +f 2958/1787/3387 3063/1788/3388 3064/1789/3389 +f 2052/1790/3390 2174/1791/3391 2164/1792/3392 +f 3639/1793/3393 3675/1794/3394 3676/1795/3395 +f 3027/1796/3296 3026/1797/3296 2997/1751/3296 +f 2977/1798/3396 2976/1688/3397 2994/1799/3398 +f 3103/1800/3399 3102/1801/3400 3122/1802/3401 +f 3034/1803/3402 3035/1804/3403 3073/1805/3404 +f 3375/1806/3405 3388/1745/3346 3389/1807/3406 +f 3864/1808/3407 3877/1809/3408 3894/1684/3294 +f 3803/1810/3409 3696/1811/3410 3693/1812/3411 +f 3350/1813/3281 3380/1814/3281 3347/1815/3281 +f 2316/1816/3412 2317/1817/3413 2318/1818/3414 +f 2436/1819/3415 2700/1820/3416 2435/1821/3417 +f 2780/1822/3418 2795/1704/3310 2796/1823/3419 +f 2893/1824/3420 2863/1825/3421 2864/1826/3422 +f 3306/1827/3423 3209/1828/3424 3305/1829/3425 +f 2083/1830/3426 2084/1831/3427 1989/1832/3428 +f 3565/1833/3429 3561/1834/3430 3444/1835/3431 +f 2664/1836/3432 2659/1837/3433 2483/1690/3434 +f 4038/1838/3435 3993/1839/3436 3994/1840/3437 +f 3401/1676/3287 3384/1841/3438 3385/1674/3285 +f 2058/1842/3439 2059/1843/3440 2055/1844/3441 +f 2735/1845/3442 2741/1846/3443 2832/1847/3444 +f 3880/1848/3445 3879/1849/3446 3867/1679/3447 +f 2095/1850/3448 2079/1851/3449 2081/1852/3450 +f 3429/1853/3451 3428/1854/3452 3426/1855/3453 +f 2784/1856/3454 2783/1857/3454 2755/1858/3454 +f 3216/1859/3455 3205/1860/3456 3311/1861/3457 +f 2807/1862/3458 2806/1863/3459 2736/1864/3460 +f 3244/1865/3461 3246/1866/3462 3245/1867/3463 +f 2735/1845/3464 2733/1868/3465 2732/1869/3465 +f 4031/1870/3466 4030/1871/3467 4032/1872/3468 +f 3418/1873/3469 3408/1874/3470 3417/1875/3471 +f 2915/1876/3472 2906/1877/3473 2894/1878/3474 +f 1673/1879/3475 1679/1880/3475 1676/1881/3475 +f 3906/1882/3476 3908/1883/3477 3907/1884/3478 +f 1751/1885/3479 1734/1886/3480 1735/1887/3481 +f 2617/1888/3482 2590/1889/3483 2581/1890/3484 +f 3697/1772/3373 3795/1771/3372 3797/1891/3485 +f 2555/1892/3486 2342/1893/3487 2340/1894/3488 +f 3189/1895/3489 3188/1896/3490 3148/1897/3491 +f 2274/1898/3492 2271/1899/3493 2272/1900/3494 +f 2223/1901/3495 2059/1843/3496 2224/1902/3497 +f 1758/1903/3498 1759/1904/3499 1747/1905/3500 +f 2774/1906/3501 2773/1907/3502 2772/1908/3502 +f 2044/1909/3503 2041/1910/3504 2040/1911/3505 +f 3052/1912/3506 3053/1913/3507 3050/1914/3508 +f 3599/1915/3509 3597/1916/3510 3583/1917/3511 +f 3941/1918/3512 3942/1919/3512 3939/1920/3513 +f 2910/1921/3514 2897/1922/3515 2898/1923/3516 +f 3380/1814/3517 3384/1841/3438 3403/1924/3518 +f 3379/1925/3519 3404/1926/3520 3405/1927/3521 +f 2092/1928/3522 1993/1929/3523 1991/1930/3524 +f 1680/1931/3525 1689/1932/3525 1684/1933/3525 +f 3975/1934/3512 3972/1935/3512 3969/1936/3512 +f 3290/1937/3526 3293/1938/3527 3215/1939/3528 +f 2680/1940/3529 2679/1941/3530 2681/1942/3531 +f 3685/1943/3532 3689/1944/3533 3686/1945/3533 +f 3720/1946/3534 3721/1947/3535 3708/1948/3536 +f 3840/1949/3537 3839/1950/3538 3841/1951/3539 +f 2427/1952/3540 2428/1953/2635 2721/1954/2635 +f 1810/1955/3541 1816/1956/3542 1811/1748/3349 +f 3130/1957/3543 3107/1958/3544 3106/1959/3543 +f 3597/1916/3545 3600/1665/3546 3598/1667/3547 +f 2917/1960/3548 2918/1961/3549 2905/1962/3550 +f 2862/1963/3551 2893/1824/3552 2891/1964/3553 +f 3382/1965/3554 3393/1966/3555 3383/1967/3556 +f 3075/1968/3557 2963/1969/3557 3077/1970/3557 +f 3448/1971/3558 3451/1972/3559 3444/1835/3558 +f 2564/1973/3560 2560/1974/3561 2461/1975/3562 +f 3662/1976/3563 3664/1977/3564 3661/1978/3565 +f 3583/1917/3511 3597/1916/3510 3595/1979/3566 +f 2456/1980/3567 2457/1981/3568 2458/1982/3569 +f 3816/1983/3570 3898/1984/3571 3900/1985/3572 +f 2568/1986/3573 2659/1837/3433 2647/1987/3574 +f 2653/1988/3575 2652/1989/3576 2649/1990/3577 +f 3390/1991/3578 3407/1992/3579 3433/1993/3580 +f 2639/1994/3581 2640/1995/3582 2634/1996/3583 +f 2173/1997/3584 2109/1998/3585 1937/1999/3586 +f 3603/2000/3587 3605/2001/3588 3602/2002/3589 +f 2050/2003/3590 2047/2004/3591 2109/1998/3585 +f 2987/2005/3296 2985/2006/3296 3019/2007/3296 +f 2851/2008/3592 2955/2009/3592 2849/2010/3592 +f 2797/2011/3593 2796/1823/3419 2829/2012/3594 +f 1727/2013/3595 1744/1720/3323 1733/2014/3596 +f 3836/2015/3597 3834/2016/3598 3835/2017/3599 +f 3208/2018/3600 3316/2019/3600 3315/2020/3600 +f 3541/2021/3601 3540/2022/3602 3539/2023/3603 +f 2688/2024/3604 2677/2025/3605 2687/2026/3606 +f 3374/2027/3607 3372/2028/3607 3371/2029/3607 +f 3738/2030/3608 3739/2031/3609 3740/2032/3610 +f 1766/2033/3611 1767/2034/3612 1765/2035/3613 +f 3539/2023/3603 3538/2036/3614 3453/2037/3615 +f 3657/2038/3616 3681/2039/3617 3683/2040/3618 +f 2924/2041/3619 2933/2042/3620 2934/2043/3621 +f 3971/2044/3622 3968/2045/3623 3969/1936/3624 +f 3404/1926/3520 3403/1924/3518 3418/1873/3469 +f 2200/2046/3625 2199/2047/3626 2198/2048/3627 +f 1725/2049/3628 1756/2050/3629 1739/2051/3630 +f 2954/2052/3631 2953/2053/3631 2950/2054/3631 +f 3787/2055/3632 3788/2056/3633 3700/2057/3634 +f 3973/2058/3635 4006/2059/3636 3977/2060/3637 +f 3352/2061/3638 3354/2062/3639 3355/2063/3640 +f 1819/2064/3641 1818/1749/3642 1977/2065/3643 +f 3940/2066/3644 3939/1920/3513 3958/2067/3645 +f 3520/1763/3364 3510/2068/3646 3509/2069/3647 +f 3282/1713/3319 3292/2070/3648 3291/2071/3649 +f 2664/1836/3432 2657/2072/3650 2646/2073/3651 +f 1805/2074/3652 1815/1697/3305 1813/1696/3304 +f 3551/2075/3653 3445/2076/3654 3552/2077/3655 +f 1766/2033/3611 1768/2078/3656 1767/2034/3612 +f 2130/2079/3657 2106/2080/3658 2131/2081/3659 +f 2439/2082/3660 2674/2083/3661 2669/2084/3662 +f 3423/2085/3663 3425/2086/3664 3405/1927/3665 +f 2850/2087/3666 2930/2088/3667 2927/2089/3668 +f 3925/2090/3669 4031/1870/3466 4032/1872/3468 +f 2673/2091/3670 2671/2092/3671 2532/2093/3672 +f 2951/2094/3673 2839/2095/3673 2840/2096/3674 +f 3128/2097/3675 3105/2098/3676 3104/2099/3677 +f 3426/1855/3453 3406/1746/3347 3425/2086/3664 +f 2029/2100/3678 2027/2101/3679 2026/2102/3680 +f 4024/2103/3681 4025/2104/3682 4021/2105/3683 +f 3434/2106/3684 3432/2107/3685 3326/2108/3686 +f 3612/1737/3687 3611/2109/3688 3613/2110/3689 +f 2715/2111/3690 2720/2112/3691 2508/2113/3692 +f 2620/2114/3693 2619/2115/3694 2629/2116/3695 +f 3033/2117/3696 3017/2118/3697 3022/2119/3698 +f 3258/2120/3699 3261/2121/3699 3226/2122/3699 +f 3607/2123/3700 3605/2001/3588 3606/2124/3701 +f 3278/2125/3702 3310/2126/3703 3309/2127/3704 +f 3908/1883/3477 3911/2128/3705 3909/2129/3706 +f 2695/2130/3707 2693/2131/3708 2694/2132/3709 +f 1728/2133/3710 1724/2134/3711 1740/2135/3712 +f 2965/2136/3713 2963/1969/3713 2956/2137/3713 +f 2908/2138/3714 2924/2041/3619 2934/2043/3621 +f 3591/2139/3280 3621/1780/3280 3620/2140/3280 +f 2919/2141/3715 2920/2142/3716 2904/2143/3717 +f 2846/2144/3718 2839/2095/3718 2950/2054/3718 +f 1732/2145/3525 1736/2146/3525 1709/2147/3525 +f 3159/2148/3719 3160/2149/3720 3173/2150/3721 +f 3634/2151/3722 3629/2152/3723 3646/2153/3724 +f 2905/1962/3725 2904/2143/3725 2872/2154/3725 +f 3105/2098/3676 3106/1959/3726 3097/2155/3726 +f 2900/2156/3727 2923/2157/3728 2924/2041/3729 +f 3103/1800/3730 3104/2099/3730 3105/2098/3730 +f 3154/2158/3731 3167/2159/3732 3194/2160/3733 +f 3331/2161/3734 3327/2162/3734 3334/2163/3735 +f 3603/2000/3736 3601/2164/3737 3584/2165/3738 +f 2870/2166/3739 2871/2167/3740 2872/2154/3741 +f 2944/2168/3742 2946/2169/3743 2912/2170/3744 +f 3169/2171/3745 3168/2172/3746 3184/2173/3747 +f 3869/2174/3748 3868/1683/3293 3893/1685/3295 +f 1706/2175/3749 1708/2176/3750 1709/2147/3751 +f 3120/2177/3730 3118/2178/3730 3144/2179/3730 +f 2823/2180/3752 2807/1862/3458 2736/1864/3460 +f 3687/2181/3753 3688/2182/3754 3577/2183/3754 +f 3645/2184/3755 3646/2153/3724 3629/2152/3723 +f 4003/2185/3756 4004/2186/3757 4019/2187/3758 +f 2580/2188/3759 2586/2189/3760 2585/2190/3761 +f 1787/2191/3762 1676/1881/3762 1786/2192/3762 +f 2758/2193/3763 2755/1858/3764 2756/2194/3765 +f 3994/1840/3437 3931/2195/3766 4038/1838/3435 +f 2774/1906/3501 2775/2196/3501 2773/1907/3502 +f 3386/2197/3281 3387/2198/3281 3361/2199/3281 +f 2182/2200/3767 2207/2201/3768 2211/2202/3769 +f 3268/2203/3770 3284/2204/3771 3283/1715/3321 +f 2165/2205/3772 2168/2206/3773 2169/2207/3774 +f 1689/1932/3775 1718/2208/3776 1688/2209/3777 +f 3683/2040/3618 3580/2210/3778 3578/2211/3779 +f 4042/2212/3780 3926/2213/3780 3933/2214/3780 +f 1754/2215/3781 1767/2034/3612 1769/2216/3782 +f 3786/2217/3783 3784/2218/3784 3785/2219/3785 +f 2765/2220/3786 2764/2221/3787 2766/2222/3788 +f 2512/2223/3789 2513/2224/3790 2511/2225/3791 +f 3303/2226/3792 3302/2227/3793 3271/2228/3794 +f 3785/2219/3785 3771/2229/3795 3772/2230/3796 +f 2595/2231/3797 2594/2232/3798 2599/2233/3799 +f 2234/2234/2635 2233/2235/3271 1923/2236/3800 +f 2827/2237/3801 2794/2238/3802 2793/2239/3803 +f 3240/2240/3804 3242/2241/3805 3221/2242/3806 +f 3664/1977/3564 3663/2243/3807 3666/2244/3808 +f 3085/2245/3809 3086/2246/3810 3181/2247/3811 +f 3026/1797/3812 3027/1796/3813 3037/2248/3814 +f 3460/2249/3815 3459/2250/3815 3464/2251/3815 +f 2152/2252/3816 2139/2253/3817 2138/2254/3818 +f 4036/2255/3819 4035/2256/3820 3992/2257/3821 +f 2851/2008/3822 2845/2258/3822 2953/2053/3822 +f 2245/2259/3823 2240/2260/3824 2239/2261/3825 +f 3532/2262/3826 3531/1762/3363 3519/1764/3365 +f 3753/2263/3827 3758/2264/3827 3719/2265/3827 +f 3566/2266/3828 3567/2267/3828 3685/1943/3828 +f 2009/2268/3829 2012/2269/3830 2011/2270/3831 +f 3691/1707/3832 3806/2271/3832 3698/2272/3832 +f 2941/2273/3833 2940/2274/3834 2939/2275/3835 +f 1949/2276/3836 1962/2277/3837 1793/2278/3838 +f 3602/2002/3589 3599/1915/3839 3601/2164/3840 +f 3081/1701/3841 3083/2279/3842 3084/2280/3843 +f 3136/2281/3730 3110/2282/3730 3108/2283/3730 +f 1967/2284/3844 1963/2285/3845 2180/2286/3846 +f 1908/2287/3847 1987/2288/3848 1931/2289/3849 +f 3645/2184/3755 3644/2290/3850 3681/2039/3617 +f 3760/2291/3827 3754/2292/3827 3732/2293/3827 +f 3056/2294/3851 3054/2295/3852 3042/2296/3853 +f 3152/2297/3854 3151/2298/3855 3133/2299/3856 +f 3071/2300/3857 2967/2301/3858 3070/2302/3859 +f 3119/2303/3860 3121/2304/3861 3102/1801/3400 +f 1725/2049/3525 1724/2134/3525 1691/2305/3525 +f 3476/1779/3380 3477/2306/3862 3478/2307/3863 +f 2564/1973/3864 2563/2308/3865 2348/2309/3866 +f 3866/2310/3288 3860/1677/3288 3867/1679/3289 +f 4016/2311/3867 4014/2312/3868 4015/2313/3869 +f 2807/1862/3870 2808/2314/3871 2784/1856/3872 +f 3034/1803/3402 3073/1805/3404 3072/2315/3873 +f 3294/2316/3874 3297/1776/3377 3213/1775/3376 +f 3445/2076/3654 3443/2317/3559 3450/2318/3875 +f 3215/1939/3528 3213/1775/3376 3214/2319/3361 +f 3371/2029/3876 3372/2028/3876 3370/2320/3876 +f 3279/2321/3877 3312/2322/3878 3310/2126/3703 +f 1778/2323/3879 1743/2324/3880 1777/2325/3881 +f 3949/2326/3882 3952/2327/3883 3951/2328/3884 +f 3213/1775/3376 3215/1939/3528 3294/2316/3874 +f 3155/2329/3885 3156/2330/3886 3195/2331/3887 +f 1955/2332/3888 1794/2333/3889 1956/2334/3890 +f 2965/2136/3713 2967/2301/3891 2963/1969/3713 +f 3055/2335/3892 3056/2294/3851 3057/2336/3893 +f 3666/2244/3808 3665/1710/3316 3664/1977/3564 +f 3160/2149/3720 3161/2337/3894 3176/2338/3895 +f 3967/2339/3896 3965/2340/3897 3966/2341/3898 +f 3148/1897/3491 3134/2342/3899 3135/2343/3900 +f 3148/1897/3491 3149/2344/3901 3189/1895/3489 +f 3481/2345/3902 3462/2346/3903 3482/2347/3904 +f 3016/2348/3905 3045/2349/3906 3020/2350/3907 +f 2747/2351/3908 2764/2221/3909 2746/2352/3910 +f 1711/2353/3911 1686/2354/3912 1687/2355/3913 +f 1729/2356/3914 1741/2357/3915 1742/2358/3916 +f 2029/2100/3917 2031/2359/3918 1873/2360/3919 +f 3627/2361/3920 3632/2362/3921 3653/2363/3922 +f 2205/2364/3923 2121/2365/3924 2113/2366/3925 +f 3460/2249/3926 3469/2367/3927 3459/2250/3928 +f 3044/2368/3929 3045/2349/3930 2959/2369/3931 +f 3144/2179/3932 3156/2330/3886 3155/2329/3885 +f 2693/2131/3708 2575/2370/3933 2570/2371/3934 +f 2580/2188/3759 2573/2372/3935 2577/2373/3936 +f 3143/2374/3937 3160/2149/3938 3159/2148/3939 +f 2298/2375/3940 2297/2376/3941 2300/2377/3942 +f 4011/2378/3943 4010/2379/3944 4012/2380/3945 +f 3052/1912/3506 3050/1914/3508 3039/2381/3946 +f 3229/2382/3947 3230/2383/3948 3218/2384/3949 +f 2565/2385/3950 2567/2386/3951 2647/1987/3574 +f 3848/2387/3952 3849/2388/3953 3850/2389/3954 +f 3944/2390/3955 3946/2391/3956 3937/2392/3957 +f 2959/2369/3931 3062/2393/3958 3061/2394/3959 +f 1698/2395/3960 1699/2396/3961 1700/2397/3962 +f 3692/1708/3314 3697/1772/3315 3690/1709/3315 +f 2592/2398/3963 2607/2399/3964 2628/2400/3965 +f 2013/2401/3966 2012/2269/3830 2077/2402/3967 +f 2587/2403/3968 2589/2404/3969 2603/2405/3970 +f 2935/2406/3971 2908/2138/3714 2934/2043/3621 +f 3875/1717/3972 3886/2407/3973 3885/2408/3974 +f 2361/2409/3975 2360/2410/3976 2387/2411/3977 +f 3896/2412/3978 3818/2413/3979 3895/2414/3980 +f 3286/2415/3981 3285/2416/3982 3262/2417/3983 +f 3415/2418/3984 3400/1675/3286 3334/2163/3735 +f 2329/2419/3985 2328/2420/3986 2327/2421/3987 +f 3095/2422/3841 3096/2423/3841 3094/2424/3841 +f 3067/2425/3988 3047/2426/3989 3068/2427/3990 +f 3877/1809/3408 3863/2428/3991 3866/2310/3992 +f 3252/2429/3993 3250/2430/3994 3251/2431/3995 +f 3609/2432/3996 3608/2433/3997 3610/2434/3998 +f 2026/2102/3680 2156/2435/3999 2155/2436/4000 +f 3636/2437/4001 3668/1711/3317 3669/2438/4002 +f 2475/2439/4003 2474/2440/4004 2243/2441/4005 +f 2507/2442/4006 2510/2443/4007 2715/2111/3690 +f 1747/1905/3500 1748/2444/4008 1737/2445/4009 +f 3465/2446/4010 3489/2447/4011 3464/2251/4012 +f 2037/2448/4013 2042/2449/4014 2233/2235/4015 +f 3722/2450/3827 3759/2451/3827 3724/2452/3827 +f 3698/2272/3313 3701/2453/3313 3700/2057/3634 +f 1726/2454/4016 1729/2356/3914 1742/2358/3916 +f 1864/2455/4017 2073/2456/4018 2022/2457/4019 +f 3554/2458/4020 3515/2459/4021 3514/2460/4022 +f 2815/2461/4023 2821/2462/4024 2802/2463/4025 +f 4002/2464/4026 4001/2465/4027 3983/2466/4028 +f 1963/2285/4029 1798/2467/4030 1964/2468/4031 +f 3895/2414/3980 3916/2469/4032 3885/2408/4033 +f 2141/2470/4034 2114/2471/4035 2115/2472/4036 +f 2528/2473/4037 2530/2474/4038 2531/2475/4039 +f 2799/2476/4040 2798/2477/4041 2812/2478/4042 +f 3026/1797/3296 3000/1752/3296 2997/1751/3296 +f 2152/2252/3816 2151/2479/4043 2150/2480/4044 +f 1789/2481/4045 1790/2482/4046 1788/2483/4047 +f 2107/2484/4048 2043/2485/4049 2044/1909/3503 +f 3071/2300/3857 3070/2302/3859 3069/2486/4050 +f 3815/2487/4051 3817/2488/4052 3821/2489/4051 +f 1932/2490/4053 2191/2491/4054 2194/2492/4055 +f 1703/2493/3525 1705/2494/3525 1738/2495/3525 +f 3677/2496/4056 3641/1681/4057 3640/2497/4058 +f 3248/2498/4059 3250/2430/4060 3222/2499/4061 +f 2098/2500/4062 2010/2501/4063 2006/2502/4064 +f 3079/2503/3713 3080/2504/4065 3076/2505/3713 +f 3049/2506/4066 3074/2507/4067 3036/2508/4068 +f 3930/2509/4069 3935/2510/4070 3929/2511/4071 +f 3640/2497/4072 3641/1681/3291 3625/1680/3290 +f 3102/1801/3400 3121/2304/3861 3122/1802/3401 +f 3805/2512/4073 3701/2453/4073 3698/2272/4073 +f 1730/2513/3525 1725/2049/3525 1693/2514/3525 +f 2128/2515/4074 2133/2516/4075 2123/2517/4076 +f 1950/2518/4077 1951/2519/4078 2070/2520/4079 +f 1855/2521/4080 1857/2522/4081 1853/2523/4082 +f 2463/2524/4083 2616/2525/4084 2634/1996/3583 +f 3763/2526/4085 3780/2527/4086 3795/1771/3372 +f 2074/2528/4087 1936/2529/4088 1935/2530/4089 +f 2687/2026/3606 2677/2025/3605 2684/2531/4090 +f 2515/2532/4091 2517/2533/4092 2714/2534/4093 +f 2082/2535/4094 2097/2536/4095 2093/2537/4096 +f 2766/2222/3788 2767/2538/4097 2768/2539/4098 +f 3570/2540/4099 3684/2541/4100 3686/1945/4099 +f 3450/2318/3875 3553/2542/4101 3552/2077/3655 +f 3124/2543/4102 3103/1800/3399 3122/1802/3401 +f 3513/2544/4103 3514/2460/4022 3500/2545/4104 +f 2819/2546/4105 2820/2547/4106 2816/2548/4107 +f 3115/2549/4108 3114/2550/4109 3116/2551/4110 +f 2475/2439/4111 2477/2552/4112 2476/2553/4113 +f 3358/2554/4114 3355/2063/3640 3356/2555/4115 +f 2016/2556/4116 2018/2557/4117 2017/2558/4118 +f 3391/2559/4119 3434/2106/3684 3435/2560/4120 +f 2143/1735/3338 2141/2470/4034 2142/1736/3339 +f 1794/2333/4121 1792/2561/4122 1798/2467/4123 +f 1726/2454/4124 1717/2562/3525 1719/2563/3525 +f 3872/2564/3289 3871/2565/3288 3854/2566/3289 +f 2347/2567/4125 2560/1974/4126 2348/2309/3866 +f 2368/2568/4127 2382/2569/4128 2383/2570/4129 +f 2867/2571/4130 2856/2572/4131 2868/2573/4132 +f 2775/2196/3501 2776/1728/4133 2777/1730/4134 +f 3621/1780/3381 3655/1712/4135 3636/2437/4136 +f 1851/2574/4137 1850/2575/4138 1852/2576/4139 +f 1972/2577/4140 1969/2578/4141 2184/2579/4142 +f 2592/2398/3963 2628/2400/3965 2627/2580/4143 +f 1754/2215/4144 1755/2581/4145 1730/2513/4146 +f 1812/2582/4147 1813/1696/3304 1814/1695/3303 +f 4006/2059/4148 4026/2583/4149 4023/2584/4150 +f 2985/2006/4151 2986/2585/4152 2983/2586/4153 +f 1704/2587/4154 1702/2588/4155 1685/2589/4156 +f 3034/1803/3402 3072/2315/3873 3071/2300/3857 +f 2174/1791/3391 2052/1790/3390 2173/1997/3584 +f 2949/2590/4157 2925/2591/4158 2915/1876/3472 +f 2306/2592/4159 2305/2593/4160 2304/2594/4161 +f 2294/2595/4162 2293/2596/4163 2295/2597/4164 +f 3896/2412/3978 3888/2598/4165 3897/2599/4166 +f 3548/2600/4167 3546/2601/4168 3545/2602/4169 +f 2507/2442/4006 2715/2111/3690 2508/2113/3692 +f 3105/2098/3730 3097/2155/3730 3101/2603/4170 +f 2254/2604/4171 2252/2605/4172 2253/2606/4173 +f 3557/2607/4174 3558/2608/4175 3516/2609/4176 +f 1827/2610/4177 1823/2611/4178 1826/2612/4179 +f 1828/2613/4180 1829/2614/4181 1830/2615/4182 +f 1830/2615/4182 1829/2614/4181 1831/2616/4183 +f 1830/2615/4182 1831/2616/4183 1832/2617/4184 +f 1832/2617/4184 1831/2616/4183 1833/2618/4185 +f 1832/2617/4184 1833/2618/4185 1834/2619/4186 +f 2981/2620/4187 2983/2586/4188 2973/1686/4189 +f 1825/2621/4190 1834/2619/4186 1833/2618/4185 +f 1835/2622/4191 1836/2623/4192 1837/2624/4193 +f 1838/2625/4194 1825/2621/4190 1839/2626/4195 +f 2119/2627/4196 2123/2517/4076 2132/2628/4197 +f 1836/2623/4192 1840/2629/4198 1837/2624/4193 +f 1835/2622/4191 1837/2624/4193 1841/2630/4199 +f 1841/2630/4199 1837/2624/4193 1842/2631/4200 +f 3199/2632/4201 3198/2633/4201 3089/2634/4201 +f 1959/2635/4202 1795/2636/4203 1791/2637/4204 +f 2562/2638/4205 2555/1892/4206 2574/2639/4207 +f 1960/2640/4208 1955/2332/4209 1956/2334/4210 +f 3745/2641/4211 3744/2642/4212 3743/1743/4213 +f 1847/2643/4214 1846/2644/4215 1848/2645/4216 +f 3693/1812/3313 3694/2646/3313 3704/2647/3313 +f 2112/1673/3284 2111/2648/4217 2075/2649/4218 +f 1906/2650/4219 1904/2651/4220 1991/1930/3524 +f 1829/2614/4221 2003/2652/4222 1941/2653/4223 +f 3483/2654/4224 3482/2347/4225 3484/2655/4226 +f 1723/2656/4227 1690/2657/4228 1691/2305/4229 +f 3851/2658/4230 3852/2659/4231 3854/2566/4232 +f 2065/2660/4233 2058/1842/3439 2063/2661/4234 +f 2616/2525/4084 2615/2662/4235 2621/2663/4236 +f 1695/2664/3525 1730/2513/3525 1693/2514/3525 +f 2634/1996/3583 2447/2665/4237 2639/1994/3581 +f 1791/2637/4204 1954/2666/4238 1959/2635/4202 +f 2600/2667/4239 2599/2233/3799 2449/2668/4240 +f 2063/2661/4234 2158/2669/4241 2061/2670/4242 +f 2439/2082/3660 2438/2671/4243 2677/2025/3605 +f 1938/2672/4244 2081/1852/3450 2092/1928/3522 +f 2707/2673/4245 2706/2674/4246 2527/2675/4247 +f 2535/2676/4248 2536/2677/4249 2455/2678/4250 +f 2794/2238/3802 2827/2237/3801 2814/1705/3311 +f 3020/2350/3296 2985/2006/3296 2984/2679/4251 +f 1861/2680/4252 1862/2681/4253 1866/2682/4254 +f 2687/2026/3606 2435/1821/3417 2700/1820/3416 +f 2210/2683/4255 2209/2684/4256 1986/2685/4257 +f 2802/2463/4025 2803/2686/4258 2791/2687/4259 +f 1865/2688/4260 1869/2689/4261 1870/2690/4262 +f 1677/2691/3475 1668/2692/3475 1669/2693/3475 +f 3636/2437/4001 3655/1712/3318 3668/1711/3317 +f 3632/2362/3921 3633/1666/4263 3651/1731/4264 +f 3847/2694/4265 3845/2695/4266 3846/1718/4267 +f 1872/2696/4268 1873/2360/4269 1874/2697/4270 +f 3226/2122/4271 3228/2698/4272 3227/2699/4273 +f 2289/1700/3308 2290/2700/4274 2288/1698/3306 +f 2758/2193/3763 2759/2701/4275 2761/2702/4276 +f 2810/2703/4277 2809/2704/4278 2729/2705/4279 +f 4044/2706/4280 3930/2509/4281 3924/2707/4280 +f 3493/2708/3815 3494/2709/4282 3502/2710/3815 +f 3126/2711/4283 3128/2097/3675 3104/2099/3677 +f 2695/2130/3707 2691/2712/4284 2690/2713/4285 +f 3036/2508/4068 3037/2248/3814 3049/2506/4066 +f 2806/1863/4286 2788/2714/4287 2805/2715/4288 +f 3135/2343/3730 3134/2342/4289 3131/2716/3730 +f 2370/2717/4290 2360/2410/3976 2357/2718/4291 +f 2503/2719/4292 2506/2720/4293 2504/2721/4294 +f 3461/2722/4295 3476/1779/4296 3474/1778/4297 +f 1879/2723/4298 1881/2724/4046 1880/2725/4299 +f 1706/2175/3749 1707/2726/3749 1705/2494/4300 +f 1672/2727/4301 1673/1879/3475 1666/2728/3475 +f 2275/2729/4302 2267/2730/4303 2268/2731/4304 +f 3566/2266/3828 3685/1943/3828 3684/2541/4305 +f 2089/2732/4306 2097/2536/4095 2096/2733/4307 +f 2186/2734/4308 1932/2490/4053 1934/2735/4309 +f 3302/2227/3793 3303/2226/3792 3210/2736/4310 +f 1667/2737/4311 1672/2727/4301 1666/2728/3475 +f 1951/2519/4078 1950/2518/4077 1952/2738/4312 +f 1951/2519/4078 1952/2738/4312 1953/2739/4313 +f 3384/1841/3438 3402/2740/4314 3403/1924/3518 +f 2803/2686/4315 2821/2462/4024 2822/2741/4316 +f 2975/2742/4317 2990/2743/4318 2991/2744/4319 +f 3145/2745/4320 3158/2746/4321 3157/2747/4322 +f 3774/1757/3358 3781/1759/3360 3782/2748/4323 +f 3768/2749/4324 3769/2750/4325 3694/2646/4326 +f 1785/2751/3475 1784/2752/3475 1782/2753/3475 +f 1974/2754/4327 1973/2755/4328 1975/2756/4329 +f 3652/2757/4330 3651/1731/3334 3656/2758/4331 +f 3959/2759/4332 3962/2760/4333 3960/2761/4334 +f 2533/2762/4335 2570/2371/3934 2541/2763/4336 +f 2847/2764/4337 2939/2275/3835 2937/2765/4338 +f 1859/2766/4339 1858/2767/4340 1863/2768/4341 +f 1797/2769/4342 1967/2284/4343 1799/2770/4344 +f 3506/2771/3815 3505/2772/3815 3486/2773/3815 +f 2701/2774/4345 2652/1989/3576 2571/2775/4346 +f 3623/1782/3383 3638/2776/4347 3624/2777/4348 +f 1826/2612/4179 1822/2778/4349 1821/2779/4350 +f 3427/1747/3348 3431/2780/4351 3388/1745/3346 +f 1985/2781/4352 1892/2782/4353 1882/2783/4354 +f 2803/2686/4258 2804/2784/4355 2789/2785/4356 +f 2852/2786/3631 2844/2787/3631 2845/2258/3631 +f 3679/2788/4357 3642/2789/4358 3677/2496/4056 +f 3445/2076/3654 3448/1971/3558 3444/1835/3558 +f 2108/2790/4359 2044/1909/3503 2040/1911/3505 +f 2980/2791/4360 2979/2792/4361 3009/2793/4362 +f 1893/2794/4363 1989/1832/3428 1894/2795/4364 +f 3044/2368/3929 3043/2796/4365 3019/2007/4366 +f 2780/1822/3454 2771/2797/3454 2773/1907/3454 +f 2635/2798/4367 2636/2799/4368 2602/2800/4369 +f 3099/2801/3730 3100/2802/3730 3101/2603/4170 +f 2022/2457/4370 2073/2456/4371 2072/2803/4372 +f 2884/2804/4373 2882/2805/4374 2860/2806/4375 +f 1990/1694/3302 1901/1693/3301 1900/2807/4376 +f 3466/2808/4377 3497/2809/4378 3458/2810/4379 +f 1906/2650/4219 1991/1930/3524 1992/2811/4380 +f 3336/1670/3281 3335/2812/4381 3344/2813/3281 +f 1994/2814/4382 1945/2815/4383 1995/2816/4384 +f 3446/2817/3558 3447/2818/4385 3455/2819/4386 +f 1996/2820/4387 1997/2821/4388 1998/2822/4389 +f 3506/2771/4390 3499/2823/4391 3515/2459/4392 +f 3280/2824/4393 3281/2825/4394 3291/2071/3649 +f 3970/2826/4395 3971/2044/3622 3943/2827/4396 +f 3924/2707/4397 3929/2511/4071 3925/2090/3669 +f 2700/1820/3416 2436/1819/3415 2701/2774/4345 +f 3393/1966/3555 3394/2828/4398 3383/1967/3556 +f 3453/2037/3615 3451/1972/4399 3541/2021/3601 +f 2881/2829/4400 2878/1727/3330 2879/2830/4401 +f 2627/2580/4143 2583/2831/4402 2592/2398/3963 +f 2913/2832/4403 2903/2833/4404 2912/2170/4405 +f 3419/2834/4406 3422/2835/4407 3421/2836/4408 +f 2963/1969/4409 2961/2837/4409 3078/2838/4409 +f 3875/1717/3972 3876/1716/4410 3887/2839/4411 +f 3190/2840/4412 3150/2841/4413 3191/2842/4414 +f 3667/2843/4415 3663/2243/3807 3572/2844/4416 +f 2979/2792/4361 2978/2845/4417 3004/2846/4418 +f 2036/2847/4419 1879/2723/4420 1876/2848/4421 +f 2142/1736/3339 2204/2849/4422 1937/1999/3586 +f 2149/2850/4423 2125/2851/4424 2150/2480/4044 +f 4040/2852/4425 4039/2853/4425 4041/2854/4425 +f 3553/2542/4101 3450/2318/3875 3455/2819/4386 +f 2080/2855/4426 2079/1851/3449 2090/2856/4427 +f 2032/2857/4428 2033/2858/4429 2034/2859/4430 +f 3138/2860/4431 3136/2281/4432 3164/2861/4433 +f 2384/2862/4434 2375/2863/4435 2374/2864/4436 +f 3279/2321/4437 3278/2125/4438 3263/2865/4439 +f 3699/2866/3313 3694/2646/3313 3693/1812/3313 +f 1829/2614/4181 1828/2613/4180 1827/2610/4177 +f 2041/1910/3504 2042/2449/4440 2040/1911/3505 +f 3305/1829/3425 3274/2867/4441 3275/2868/4442 +f 2044/1909/3503 2043/2485/4049 2045/2869/4443 +f 3770/2870/4444 3771/2229/3795 3783/2871/4445 +f 2474/2440/4446 2475/2439/4111 2473/2872/4447 +f 3015/2873/3296 3016/2348/3296 3013/2874/3296 +f 2703/2875/4448 2526/2876/4449 2524/2877/4450 +f 2052/1790/3390 2053/2878/4451 2049/2879/4452 +f 3489/2447/4453 3492/2880/4454 3491/2881/4455 +f 3948/2882/4456 3949/2326/4457 3937/2392/3957 +f 3796/1785/3386 3765/1784/3385 3797/1891/3485 +f 2058/1842/3439 2065/2660/4233 2059/1843/3440 +f 2067/2883/4458 2068/2884/4459 2069/2885/4460 +f 2070/2520/4461 2218/2886/4462 2066/2887/4463 +f 1724/2134/3711 1725/2049/3628 1739/2051/3630 +f 3345/2888/4464 3374/2027/4465 3373/2889/4466 +f 2216/2890/4467 2215/2891/4468 2214/2892/4469 +f 3003/2893/4470 3002/2894/4471 3001/2895/4472 +f 3679/2788/4357 3678/2896/4473 3680/2897/4474 +f 2640/1995/3582 2639/1994/3581 2638/2898/4475 +f 3454/2899/3558 3456/2900/4476 3447/2818/4385 +f 3864/1808/3289 3868/1683/3289 3832/2901/3288 +f 2858/2902/4477 2875/2903/4478 2873/2904/4479 +f 3133/2299/3730 3135/2343/3730 3129/2905/3730 +f 3074/2507/4067 3035/1804/3403 3036/2508/4068 +f 2940/2274/3834 2941/2273/3833 2944/2168/3742 +f 2853/2906/4480 2945/2907/4481 2941/2273/3833 +f 2428/1953/2635 2281/2908/2635 2722/2909/2635 +f 4043/2910/4482 3933/2214/4482 3930/2509/4482 +f 2940/2274/3834 2910/1921/3514 2939/2275/3835 +f 2282/2911/4483 2280/2912/4484 2281/2908/4485 +f 4018/2913/4486 4007/2914/4487 4003/2185/3756 +f 2653/1988/3575 2661/2915/4488 2665/2916/4489 +f 3254/2917/4490 3252/2429/3993 3253/2918/3993 +f 3205/1860/3456 3209/1828/3424 3308/2919/4491 +f 3586/2920/4492 3610/2434/4493 3608/2433/4494 +f 2280/2912/4495 2282/2911/4496 2502/2921/4497 +f 2932/2922/4498 2848/2923/4499 2843/2924/4500 +f 2023/2925/4501 2024/2926/4502 1940/2927/4503 +f 2994/1799/3398 2996/2928/4504 2977/1798/3396 +f 2232/2929/4505 2045/2869/4506 2043/2485/4507 +f 3942/1919/4508 3941/1918/4509 3965/2340/4510 +f 1748/2444/4008 1738/2495/4511 1737/2445/4009 +f 2551/2930/4512 2321/2931/4513 2548/2932/4514 +f 1973/2755/4328 1948/2933/4515 2183/2934/4516 +f 3862/2935/3288 3863/2428/3289 3864/1808/3289 +f 2804/2784/4517 2803/2686/4315 2822/2741/4316 +f 3826/2936/4518 3844/2937/4519 3845/2695/4520 +f 3066/2938/4521 3068/2427/3990 3070/2302/3859 +f 2152/2252/3816 2140/1671/3282 2154/2939/4522 +f 2599/2233/3799 2653/1988/3575 2665/2916/4489 +f 3720/1946/4523 3718/2940/4524 3719/2265/4525 +f 3454/2899/3558 3457/2941/3558 3456/2900/4476 +f 3595/1979/4526 3597/1916/3545 3598/1667/3547 +f 3050/1914/3508 2968/2942/4527 3038/2943/4528 +f 2993/2944/4529 2991/2744/4530 2992/2945/4531 +f 3160/2149/3938 3143/2374/3937 3161/2337/4532 +f 3795/1771/3372 3793/1773/3374 3794/2946/4533 +f 2614/2947/4534 2386/2948/4535 2380/2949/4536 +f 3609/2432/3280 3612/1737/3280 3631/2950/3280 +f 1842/2631/4200 1843/2951/4537 1841/2630/4199 +f 4009/2952/4538 3931/2195/3766 3996/2953/4539 +f 3790/2954/4540 3762/2955/4541 3794/2946/4533 +f 3192/2956/4542 3092/2957/4543 3191/2842/4414 +f 3362/2958/4544 3364/2959/4545 3365/2960/4546 +f 2319/2961/4547 2316/1816/3412 2318/1818/3414 +f 2443/2962/4548 2444/2963/4549 2650/2964/4550 +f 2649/1990/3577 2652/1989/3576 2651/2965/4551 +f 3939/1920/3513 3938/2966/4552 3953/2967/4553 +f 2632/2968/4554 2622/2969/4555 2621/2663/4236 +f 2088/2970/4556 2087/2971/4557 2089/2732/4306 +f 2696/2972/4558 2576/2973/4559 2695/2130/3707 +f 1998/2822/4389 1944/2974/4560 1996/2820/4387 +f 1996/2820/4387 1944/2974/4560 1946/2975/4561 +f 3527/2976/4562 3504/2977/4563 3526/2978/4564 +f 2865/2979/4565 2863/1825/4566 2856/2572/4131 +f 2330/2980/4567 2331/2981/4568 2332/2982/4569 +f 2960/2983/4570 3072/2315/3873 3074/2507/4067 +f 1826/2612/4571 2002/2984/4572 2003/2652/4222 +f 2094/2985/4573 2081/1852/3450 1938/2672/4244 +f 3607/2123/3280 3629/2152/3280 3605/2001/3280 +f 3891/2986/4574 3901/2987/4575 3899/2988/4576 +f 1971/2989/4577 1972/2577/4140 2183/2934/4516 +f 2382/2569/4128 2590/1889/3483 2612/2990/4578 +f 2784/1856/3872 2808/2314/3871 2809/2704/4579 +f 2080/2855/4426 2091/2991/4580 2092/1928/3522 +f 3750/2992/3827 3749/2993/4581 3740/2032/4582 +f 2183/2934/4516 1970/2994/4583 1971/2989/4577 +f 3769/2750/4584 3768/2749/4324 3754/2292/4585 +f 1943/2995/4586 1997/2821/4388 1996/2820/4387 +f 3750/2992/4587 3755/2996/4588 3766/2997/4589 +f 2079/1851/3449 2080/2855/4426 2081/1852/3450 +f 2836/2998/4590 2837/2999/4591 2738/3000/4591 +f 2865/2979/4592 2867/2571/4593 2866/3001/4594 +f 3885/2408/4033 3886/2407/4595 3895/2414/3980 +f 1683/3002/4596 1684/1933/4597 1699/2396/4598 +f 3789/3003/4599 3791/3004/4600 3792/3005/4601 +f 2393/3006/4602 2463/2524/4083 2392/3007/4603 +f 2084/1831/3427 1896/3008/4604 1895/3009/4605 +f 3134/2342/3899 3148/1897/3491 3147/3010/4606 +f 2095/1850/3448 2086/3011/4607 2088/2970/4556 +f 2095/1850/3448 2088/2970/4556 2096/2733/4307 +f 2498/3012/4608 2501/3013/4609 2282/2911/4610 +f 2471/3014/4611 2472/3015/4612 2468/3016/4613 +f 3133/2299/3730 3129/2905/3730 3127/3017/3730 +f 2473/2872/4447 2481/3018/4614 2478/3019/4615 +f 2784/1856/3454 2755/1858/3454 2758/2193/3454 +f 1803/3020/4616 1968/3021/4617 1804/3022/4618 +f 2404/3023/4619 2405/3024/4620 2635/2798/4367 +f 2712/3025/4621 2518/3026/4622 2521/3027/4623 +f 2922/3028/4624 2921/3029/4625 2932/2922/4498 +f 1783/3030/4626 1665/3031/4626 1666/2728/4626 +f 3934/3032/4627 3933/2214/4628 3926/2213/4425 +f 2855/3033/3725 2862/1963/3725 2859/3034/3725 +f 2096/2733/4307 2079/1851/3449 2095/1850/3448 +f 2571/2775/4346 2448/3035/4629 2572/3036/4630 +f 3694/2646/4326 3800/3037/4631 3768/2749/4324 +f 3969/1936/3624 3967/2339/3896 3966/2341/3898 +f 2129/3038/4632 2139/2253/3817 2077/2402/3967 +f 3927/3039/4633 3928/3040/4634 3932/3041/4635 +f 2466/3042/4636 2465/3043/4637 2459/3044/4638 +f 2343/3045/4639 2344/3046/4640 2345/3047/4641 +f 3247/3048/4642 3248/2498/4059 3222/2499/4061 +f 3387/2198/4643 3386/2197/4644 3398/3049/4645 +f 3183/3050/4646 3085/2245/3809 3181/2247/3811 +f 1711/2353/3911 1710/3051/4647 1686/2354/3912 +f 3681/2039/3617 3657/2038/3616 3646/2153/3724 +f 3236/3052/4648 3238/3053/4649 3237/3054/4650 +f 3695/3055/4651 3778/3056/4652 3789/3003/4599 +f 3465/2446/4010 3458/2810/4379 3495/3057/4653 +f 2658/3058/4654 2660/3059/4655 2656/3060/4656 +f 3492/2880/4454 3493/2708/4657 3491/2881/4455 +f 3982/3061/3512 3985/3062/3512 3956/3063/3512 +f 3070/2302/3859 2967/2301/3858 3066/2938/4521 +f 1679/1880/4658 1675/3064/4659 1763/3065/4660 +f 2335/3066/4661 2334/3067/4662 2333/3068/4663 +f 3579/3069/3533 3578/2211/4664 3577/2183/3533 +f 2070/2520/4079 2074/2528/4087 1961/3070/4665 +f 2913/2832/4403 2902/3071/4666 2903/2833/4404 +f 2137/3072/4667 2116/3073/4668 2149/2850/4423 +f 3023/3074/4669 3024/3075/4670 3041/3076/4671 +f 3492/2880/4672 3489/2447/4011 3465/2446/4010 +f 3963/3077/4673 3964/3078/4673 3966/2341/3898 +f 3241/3079/4674 3244/1865/3461 3242/2241/4675 +f 2528/2473/4676 2285/3080/4677 2284/3081/4678 +f 1948/2933/4515 1970/2994/4583 2183/2934/4516 +f 3364/2959/4545 3366/3082/4679 3365/2960/4546 +f 2479/3083/4680 2458/1982/3569 2478/3019/4615 +f 2652/1989/3576 2594/2232/3798 2571/2775/4346 +f 2185/3084/4681 1805/2074/4682 1804/3022/4618 +f 3496/3085/4683 3495/3057/4684 3497/2809/4685 +f 3284/2204/3771 3285/2416/4686 3298/3086/4687 +f 3128/2097/3675 3130/1957/3676 3105/2098/3676 +f 3393/1966/3555 3382/1965/3554 3392/3087/4688 +f 1874/2697/4270 1878/3088/4689 1877/3089/4690 +f 1763/3065/4660 1750/3090/4691 1762/3091/4692 +f 3975/1934/4693 3976/3092/4694 3989/3093/4695 +f 3841/1951/3539 3839/1950/3538 3838/3094/4696 +f 2625/3095/4697 2624/3096/4698 2606/3097/4699 +f 3455/2819/4386 3450/2318/3875 3449/3098/3558 +f 2970/3099/3713 2961/2837/3713 2960/2983/3713 +f 3999/3100/4700 4000/3101/4701 4013/3102/4702 +f 3350/1813/4703 3347/1815/4704 3348/3103/4705 +f 1746/3104/4706 1736/2146/4707 1732/2145/4708 +f 2607/2399/3964 2585/2190/3761 2593/3105/4709 +f 4037/3106/4710 4034/3107/4711 4035/2256/3820 +f 2611/3108/4712 2624/3096/4698 2623/3109/4713 +f 3708/1948/3536 3707/3110/4714 3718/2940/4715 +f 2096/2733/4307 2082/2535/4094 2079/1851/3449 +f 3207/1724/3362 3204/1723/3326 3203/1761/3362 +f 2676/3111/4716 2677/2025/3605 2690/2713/4285 +f 3954/3112/4717 3955/3113/4718 3953/2967/4719 +f 3442/3114/4720 3438/3115/4721 3320/3116/4720 +f 2169/2207/3774 2162/3117/4722 2158/2669/4241 +f 3032/3118/4723 3033/2117/3696 3067/2425/3988 +f 1797/2769/4724 1791/2637/4724 1798/2467/4724 +f 3273/3119/4725 3259/3120/4726 3274/2867/4727 +f 2132/2628/4197 2123/2517/4076 2134/3121/4728 +f 3103/1800/3399 3124/2543/4102 3126/2711/4283 +f 3447/2818/4385 3559/3122/4729 3558/2608/4175 +f 2741/1846/3443 2735/1845/3464 2730/3123/3464 +f 3758/2264/4730 3753/2263/4731 3776/3124/4732 +f 2554/3125/4733 2551/2930/4734 2548/2932/4735 +f 2553/3126/4736 2554/3125/4733 2548/2932/4735 +f 3005/3127/4737 3008/3128/4738 3006/3129/4739 +f 3828/3130/4740 3827/3131/4741 3848/2387/4742 +f 3423/2085/3663 3404/1926/3520 3420/3132/4743 +f 2837/2999/3501 2734/3133/3501 2738/3000/3501 +f 2591/3134/4744 2581/1890/3484 2582/3135/4745 +f 1720/3136/4746 1689/1932/3775 1721/3137/4747 +f 3109/3138/4748 3106/1959/4749 3108/2283/4750 +f 2820/2547/4106 2818/3139/4751 2739/3140/4752 +f 3821/2489/4753 3818/2413/3979 3896/2412/3978 +f 3417/1875/3471 3408/1874/3470 3402/2740/4314 +f 2185/3084/4754 2180/2286/3846 2184/2579/4142 +f 1788/2483/4755 1790/2482/4756 1951/2519/4757 +f 1957/3141/4758 1954/2666/4759 1950/2518/4077 +f 2084/1831/3427 1895/3009/4605 1989/1832/3428 +f 2575/2370/3933 2695/2130/3707 2576/2973/4559 +f 2067/2883/4458 2074/2528/4087 2066/2887/4760 +f 2849/2010/4761 2850/2087/3666 2851/2008/3631 +f 2505/3142/4762 2506/2720/4293 2503/2719/4292 +f 3954/3112/4717 3956/3063/4763 3955/3113/4718 +f 3063/1788/3388 2958/1787/3387 2959/2369/3931 +f 4018/2913/4486 4017/3143/4764 4007/2914/4487 +f 2806/1863/4286 2807/1862/3870 2788/2714/4287 +f 2645/3144/4765 2442/3145/4766 2644/3146/4767 +f 1938/2672/4244 1899/3147/4768 1898/3148/4769 +f 1772/3149/4770 1773/3150/4771 1739/2051/4772 +f 2567/2386/3951 2569/3151/4773 2492/3152/4774 +f 2814/1705/3311 2826/3153/4775 2828/1706/3312 +f 2277/3154/4776 2493/3155/4777 2491/3156/4778 +f 2119/2627/4196 2118/3157/4779 2117/3158/4780 +f 2811/3159/4781 2729/2705/4279 2824/3160/4782 +f 3620/2140/4783 3589/3161/4784 3591/2139/4785 +f 3987/3162/4786 3986/3163/4787 3973/2058/3635 +f 3523/3164/4788 3535/3165/4789 3536/3166/4790 +f 2426/3167/2635 2715/2111/2635 2717/3168/2635 +f 3124/2543/4791 3127/3017/4792 3126/2711/4792 +f 2128/2515/4074 2137/3072/4667 2138/2254/3818 +f 1785/2751/4793 1786/2192/4794 1676/1881/4793 +f 3339/3169/4795 3356/2555/4796 3354/2062/4797 +f 2786/3170/4798 2780/1822/4799 2796/1823/3419 +f 3931/2195/3766 3932/3041/4635 4037/3106/4710 +f 3072/2315/3873 2966/3171/4800 3071/2300/3857 +f 3495/3057/4653 3492/2880/4672 3465/2446/4010 +f 3276/3172/4801 3277/3173/4802 3308/2919/4491 +f 2119/2627/4196 2120/3174/4803 2118/3157/4779 +f 2759/2701/4275 2760/3175/4804 2761/2702/4276 +f 2819/2546/4105 2816/2548/4107 2800/3176/4805 +f 2550/3177/4806 2545/3178/4807 2553/3126/4736 +f 3625/1680/3280 3622/1682/3280 3614/1738/3280 +f 3269/3179/4808 3280/2824/4809 3279/2321/4437 +f 3619/3180/4810 3617/3181/4811 3588/3182/4812 +f 3321/3183/4813 3324/3184/4814 3320/3116/3734 +f 3592/3185/4815 3590/3186/4816 3581/3187/4817 +f 3550/3188/4818 3551/2075/3653 3512/3189/4819 +f 2732/1869/4820 2835/3190/4820 2836/2998/4821 +f 3959/2759/3512 3979/3191/3512 3962/2760/3512 +f 3531/1762/3363 3532/2262/3826 3533/1741/3342 +f 3022/2119/3698 3035/1804/3403 3034/1803/3402 +f 3283/1715/3321 3284/2204/3771 3296/3192/4822 +f 1802/3193/4823 1791/2637/4824 1797/2769/4342 +f 2355/3194/4825 2354/3195/4826 2372/3196/4827 +f 2130/2079/3657 2104/3197/4828 2083/1830/3426 +f 4005/3198/4829 4023/2584/4150 4022/3199/4830 +f 3927/3039/4633 3932/3041/4635 3926/2213/4425 +f 3748/3200/4831 3763/2526/4832 3762/2955/4541 +f 2495/3201/4833 2497/3202/4834 2279/3203/4835 +f 2899/3204/4836 2895/3205/4837 2908/2138/3714 +f 3434/2106/3684 3326/2108/3686 3328/3206/4838 +f 3490/3207/4839 3487/3208/4840 3489/2447/4453 +f 1978/3209/4841 1979/3210/4842 1947/3211/4843 +f 1668/2692/4844 1781/3212/4845 1780/3213/4846 +f 1679/1880/3475 1677/2691/3475 1676/1881/3475 +f 1933/3214/4847 2211/2202/3769 2207/2201/3768 +f 2106/2080/3658 2083/1830/3426 1989/1832/3428 +f 3484/2655/4226 3485/3215/4848 3486/2773/4849 +f 2991/2744/4530 2990/2743/4850 2992/2945/4531 +f 2185/3084/4754 1968/3021/4851 2180/2286/3846 +f 2228/3216/4852 2057/3217/4853 2226/3218/4854 +f 1730/2513/4146 1755/2581/4145 1725/2049/3628 +f 2838/3219/4855 2727/3220/4855 2734/3133/4855 +f 3000/1752/3353 2999/3221/4856 2998/1753/3354 +f 3849/2388/3953 3848/2387/3952 3847/2694/4265 +f 2679/1941/3530 2516/3222/4857 2514/3223/4858 +f 3616/3224/4859 3614/1738/4860 3615/3225/4861 +f 3916/2469/4032 3820/3226/4862 3915/3227/4863 +f 3665/1710/3316 3654/3228/4864 3664/1977/3564 +f 3089/2634/4865 3081/1701/3841 3090/3229/4866 +f 2314/3230/4867 2315/3231/4868 2313/3232/4869 +f 3904/3233/4870 3906/1882/3476 3903/3234/4871 +f 4022/3199/4830 4019/2187/3758 4005/3198/4829 +f 2675/3235/4872 2690/2713/4285 2678/3236/4873 +f 1719/2563/4874 1720/3136/4875 1722/3237/4876 +f 3638/2776/4877 3637/1781/4878 3673/3238/4879 +f 3555/3239/4880 3557/2607/4174 3516/2609/4176 +f 2538/3240/4881 2299/3241/4882 2301/3242/4883 +f 2862/1963/3551 2855/3033/4884 2893/1824/3552 +f 2845/2258/3631 2844/2787/3631 2853/2906/4480 +f 2648/3243/4885 2646/2073/3651 2655/3244/4886 +f 3226/2122/4271 3256/3245/4887 3255/3246/4888 +f 2069/2885/4460 2060/1765/4889 2061/2670/4242 +f 3251/2431/3995 3248/2498/4890 3249/3247/4891 +f 2186/2734/4308 2165/2205/3772 2187/3248/4892 +f 2978/2845/4417 3001/2895/4893 3002/2894/4894 +f 2676/3111/4716 2674/2083/3661 2439/2082/3660 +f 2660/3059/4655 2667/3249/4895 2666/3250/4896 +f 3490/3207/3815 3499/2823/3815 3488/3251/3815 +f 3175/3252/4897 3173/2150/3721 3176/2338/3895 +f 3342/3253/3281 3341/3254/3281 3340/1786/3281 +f 3579/3069/3533 3577/2183/3533 3573/3255/3533 +f 3751/3256/4898 3749/2993/4899 3764/1783/3384 +f 1743/2324/3880 1744/1720/3323 1727/2013/3595 +f 2541/2763/4336 2534/3257/4900 2533/2762/4335 +f 2916/3258/4901 2907/3259/4902 2906/1877/3473 +f 1736/2146/4707 1747/1905/3500 1737/2445/4009 +f 2386/2948/4535 2393/3006/4602 2394/3260/4903 +f 2207/2201/3768 2182/2200/3767 2179/3261/4904 +f 2750/3262/4905 2776/1728/4905 2774/1906/4906 +f 2047/2004/3591 2051/3263/4907 2048/3264/4908 +f 2742/3265/4909 2751/3266/4910 2776/1728/4905 +f 2591/3134/4744 2582/3135/4745 2583/2831/4402 +f 3918/3267/4051 3917/3268/4051 3919/3269/4051 +f 3697/1772/3373 3692/1708/3314 3793/1773/3374 +f 2590/1889/3483 2382/2569/4128 2368/2568/4127 +f 2408/3270/4911 2409/3271/4912 2590/1889/3483 +f 2623/3109/4713 2624/3096/4698 2636/2799/4368 +f 3501/3272/4913 3498/3273/4914 3511/3274/4915 +f 2662/3275/4916 2503/2719/4292 2504/2721/4294 +f 3040/3276/4917 3054/2295/3852 3052/1912/3506 +f 1910/3277/4918 1909/3278/4919 1931/2289/3849 +f 2880/3279/4920 2879/2830/4921 2859/3034/4922 +f 2844/2787/4923 2852/2786/4924 2948/3280/4925 +f 3719/2265/4525 3718/2940/4524 3717/3281/4926 +f 2078/3282/4927 2135/3283/4928 2103/3284/4929 +f 3190/2840/4412 3191/2842/4414 3090/3229/4866 +f 3928/3040/4634 3927/3039/4633 3923/3285/4425 +f 3813/3286/4930 3807/3287/4051 3809/3288/4931 +f 3526/2978/4564 3525/3289/4932 3540/2022/3602 +f 3796/1785/3386 3797/1891/3485 3780/2527/4086 +f 1778/2323/3879 1744/1720/3323 1743/2324/3880 +f 2538/3240/4933 2540/3290/4934 2539/3291/4935 +f 2105/3292/4936 2104/3197/4828 2130/2079/3657 +f 2790/3293/4937 2799/2476/4040 2800/3176/4938 +f 3317/3294/4939 3316/2019/4940 3206/3295/4939 +f 1729/2356/3525 1726/2454/4124 1719/2563/3525 +f 3944/2390/4941 3945/3296/4942 3947/3297/4943 +f 2573/2372/3935 2580/2188/3759 2578/3298/4944 +f 2092/1928/3522 2091/2991/4580 1994/2814/4382 +f 3462/2346/3903 3463/3299/4945 3482/2347/3904 +f 3400/1675/3286 3399/3300/4946 3413/3301/4947 +f 3371/2029/3876 3370/2320/3876 3369/3302/3876 +f 2369/1768/3369 2384/2862/4434 2385/3303/4948 +f 3165/3304/4949 3166/3305/4950 3169/2171/3745 +f 2589/2404/3969 2587/2403/3968 2577/2373/3936 +f 2208/3306/4951 1889/3307/4952 1890/3308/4953 +f 3454/2899/4954 3563/3309/4954 3564/3310/4954 +f 3075/1968/3713 3077/1970/3713 3079/2503/3713 +f 2597/3311/4955 2448/3035/4629 2595/2231/3797 +f 3980/3312/3512 3974/3313/3512 3964/3078/3512 +f 3704/2647/4956 3769/2750/4325 3784/2218/3784 +f 3259/3120/3699 3253/2918/3699 3251/2431/3699 +f 1775/3314/4957 1776/3315/4958 1757/3316/4959 +f 2606/3097/4699 2610/3317/4960 2605/3318/4961 +f 3254/2917/4490 3253/2918/3993 3255/3246/4490 +f 2007/3319/4962 1942/3320/4963 2093/2537/4096 +f 2598/3321/4964 2606/3097/4699 2605/3318/4961 +f 2124/3322/4965 2146/3323/4966 2148/1672/3283 +f 2959/2369/3931 2958/1787/3713 2957/3324/3713 +f 2903/2833/3725 2902/3071/3725 2883/3325/3725 +f 2112/1673/3284 2075/2649/4218 2076/3326/4967 +f 2079/1851/3449 2082/2535/4094 2090/2856/4427 +f 1751/1885/3479 1752/3327/4968 1734/1886/3480 +f 1756/2050/4969 1755/2581/4970 1771/3328/4971 +f 3654/3228/4864 3653/2363/4972 3661/1978/3565 +f 3507/3329/4282 3504/2977/4282 3472/3330/4282 +f 3093/3331/4973 3177/3332/4974 3179/3333/4975 +f 3680/2897/4474 3575/3334/4976 3574/3335/4977 +f 3093/3331/4973 3086/2246/3810 3091/3336/3841 +f 2689/3337/4978 2688/2024/3604 2687/2026/3606 +f 2787/3338/4979 2785/3339/3454 2768/2539/4979 +f 3971/2044/3622 3970/2826/4395 3968/2045/3623 +f 3915/3227/4863 3882/3340/4980 3883/3341/4981 +f 2627/2580/4143 2619/2115/3694 2618/3342/4982 +f 3402/2740/4314 3401/1676/3287 3409/3343/4983 +f 3834/2016/4984 3836/2015/4985 3824/3344/4986 +f 2116/3073/4668 2125/2851/4424 2149/2850/4423 +f 2558/3345/4987 2333/3068/4988 2559/3346/4989 +f 3371/2029/4990 3335/2812/4991 3373/2889/4991 +f 3188/1896/3490 3147/3010/4606 3148/1897/3491 +f 2787/3338/4992 2797/2011/3593 2798/2477/4041 +f 2729/2705/3464 2731/3347/3464 2727/3220/3464 +f 1975/2756/4329 1973/2755/4328 2183/2934/4516 +f 3163/1754/4993 3164/2861/4994 3180/3348/4995 +f 1988/3349/4996 1914/3350/4997 1989/1832/3428 +f 4027/3351/4998 4026/2583/4149 3986/3163/4999 +f 3329/3352/5000 3416/3353/5001 3415/2418/3984 +f 2184/2579/4142 2183/2934/4516 1972/2577/4140 +f 2953/2053/5002 2845/2258/5002 2846/2144/5002 +f 2945/2907/4481 2844/2787/4923 2946/2169/3743 +f 1935/2530/4089 2179/3261/4904 2180/2286/3846 +f 2629/2116/3695 2630/3354/5003 2620/2114/3693 +f 2129/3038/4632 2078/3282/4927 2128/2515/4074 +f 3500/2545/4104 3502/2710/5004 3513/2544/4103 +f 3588/3182/3280 3587/3355/5005 3586/2920/3280 +f 2052/1790/3390 2056/3356/5006 2057/3217/5007 +f 2802/2463/4025 2801/3357/5008 2815/2461/4023 +f 3803/1810/3409 3693/1812/3411 3804/3358/3411 +f 1996/2820/4387 1946/2975/4561 2090/2856/4427 +f 3404/1926/3520 3418/1873/3469 3420/3132/4743 +f 1696/3359/5009 1698/2395/3960 1697/3360/5010 +f 1949/2276/5011 1960/2640/4208 1961/3070/4665 +f 1927/3361/5012 2224/1902/2635 2220/1766/2635 +f 1926/3362/5013 1928/3363/5013 2225/3364/5013 +f 3086/2246/3810 3085/2245/3809 3082/1703/3841 +f 2749/3365/3454 2748/3366/3454 2742/3265/3454 +f 3048/3367/5014 3037/2248/3814 3038/2943/4528 +f 1918/3368/2635 2229/3369/2635 2227/3370/2635 +f 3792/3005/4601 3695/3055/4651 3789/3003/4599 +f 2792/3371/5015 2811/3159/4781 2824/3160/4782 +f 3029/3372/5016 3015/2873/5017 3018/3373/5018 +f 3602/2002/3280 3605/2001/3280 3634/2151/3280 +f 3742/3374/5019 3741/1742/5020 3740/2032/3610 +f 2914/3375/5021 2913/2832/5022 2947/3376/5023 +f 2055/1844/3441 2056/3356/5006 2052/1790/3390 +f 2922/3028/4624 2842/3377/5024 2933/2042/3620 +f 3033/2117/3696 3034/1803/3402 3047/2426/3989 +f 1923/2236/3800 1924/3378/2635 2235/3379/2635 +f 3250/2430/4060 3252/2429/5025 3223/3380/5026 +f 2570/2371/3934 2553/3126/4736 2547/3381/5027 +f 3911/2128/3705 3912/3382/5028 3909/2129/3706 +f 3940/2066/3644 3941/1918/3512 3939/1920/3513 +f 3227/2699/5029 3229/2382/3947 3218/2384/3949 +f 3477/2306/5030 3476/1779/4296 3461/2722/4295 +f 3311/1861/3457 3312/2322/3878 3291/2071/3649 +f 4022/3199/4830 4024/2103/3681 4021/2105/3683 +f 2235/3379/5031 2037/2448/4013 2234/2234/5032 +f 3528/3383/5033 3529/3384/5034 3503/3385/5035 +f 3205/1860/3456 3309/2127/3704 3311/1861/3457 +f 3719/2265/4525 3722/2450/5036 3720/1946/4523 +f 2548/2932/4735 2550/3177/4806 2553/3126/4736 +f 3477/2306/3862 3480/3386/5037 3478/2307/3863 +f 3023/3074/3296 3025/3387/3296 2992/2945/3296 +f 3602/2002/3589 3600/1665/3546 3599/1915/3839 +f 2947/3376/5023 2949/2590/4157 2914/3375/5021 +f 2983/2586/4153 2984/2679/5038 2985/2006/4151 +f 1980/3388/5039 1981/3389/5040 1947/3211/4843 +f 2109/1998/5041 2047/2004/5042 2048/3264/5043 +f 3014/3390/5044 2981/2620/4187 2972/3391/5045 +f 3820/3226/4862 3819/3392/5046 3915/3227/4863 +f 3256/3245/5047 3224/3393/5048 3254/2917/5049 +f 2942/3394/5050 2911/3395/5051 2910/1921/3514 +f 2224/1902/3497 2065/2660/5052 2064/3396/5053 +f 3880/1848/5054 3910/3397/5055 3879/1849/5056 +f 2222/3398/5057 2221/3399/5058 2069/2885/5059 +f 1946/2975/4561 1944/2974/4560 1945/2815/4383 +f 2728/3400/3464 2729/2705/3464 2726/3401/3464 +f 2982/3402/5060 2981/2620/5061 3014/3390/5062 +f 3617/3181/5063 3619/3180/5064 3620/2140/4783 +f 2904/2143/3717 2920/2142/3716 2901/3403/5065 +f 2654/3404/5066 2661/2915/4488 2653/1988/3575 +f 3918/3267/5067 3808/3405/5067 3807/3287/5067 +f 2395/3406/5068 2638/2898/4475 2405/3024/4620 +f 3266/3407/3699 3268/2203/5069 3231/3408/3699 +f 1896/3008/4604 2094/2985/4573 1938/2672/4244 +f 3509/2069/3815 3510/2068/3815 3480/3386/3815 +f 2572/3036/4630 2697/3409/5070 2699/3410/5071 +f 3635/3411/3280 3600/1665/3280 3602/2002/3280 +f 3710/3412/3827 3711/3413/3827 3707/3110/5072 +f 1867/3414/5073 1866/2682/5074 2025/3415/5075 +f 3605/2001/3588 3604/3416/3828 3606/2124/3701 +f 2909/3417/5076 2910/1921/3514 2898/1923/3516 +f 3868/1683/3289 3869/2174/3288 3835/2017/3289 +f 3367/3418/5077 3370/2320/5078 3368/3419/5079 +f 3575/3334/4976 3571/3420/5080 3570/2540/5081 +f 3568/3421/5082 3670/3422/5083 3667/2843/4415 +f 2384/2862/4434 2383/2570/4129 2375/2863/4435 +f 3456/2900/4476 3534/3423/5084 3532/2262/3826 +f 2190/3424/5085 2193/3425/5086 2192/3426/5087 +f 3259/3120/4726 3275/2868/5088 3274/2867/4727 +f 3873/3427/3288 3874/3428/3288 3841/1951/3288 +f 1973/2755/5089 1817/3429/5090 1816/1956/5091 +f 1790/2482/4756 2219/3430/5092 1951/2519/4757 +f 3330/3431/3734 3329/3352/5000 3327/2162/3734 +f 2882/2805/5093 2881/2829/4400 2880/3279/5094 +f 1774/3432/5095 1671/3433/5096 1777/2325/3881 +f 3629/2152/3280 3634/2151/3280 3605/2001/3280 +f 2624/3096/4698 2625/3095/4697 2636/2799/4368 +f 1870/2690/5097 2024/2926/5098 2023/2925/5099 +f 1816/1956/3542 1817/3429/5100 1811/1748/3349 +f 2191/2491/4054 1932/2490/4053 2187/3248/4892 +f 2562/2638/5101 2344/3046/5102 2555/1892/3486 +f 2025/3415/5075 1866/2682/5074 2022/2457/4019 +f 2022/2457/4019 1866/2682/5074 1862/2681/5103 +f 3709/3434/5072 3710/3412/3827 3707/3110/5072 +f 2211/2202/3769 1933/3214/4847 2216/2890/4467 +f 3698/2272/3313 3700/2057/3634 3695/3055/4651 +f 1864/2455/4017 2022/2457/4019 1862/2681/5103 +f 2660/3059/4655 2658/3058/4654 2668/3435/5104 +f 2019/3436/5105 2018/2557/4117 2016/2556/4116 +f 3907/1884/3478 3809/3288/4931 3811/3437/5106 +f 3525/3289/4932 3524/3438/5107 3539/2023/3603 +f 3637/1781/3382 3638/2776/4347 3623/1782/3383 +f 3387/2198/3281 3385/1674/3281 3355/2063/3281 +f 3256/3245/5047 3217/3439/5108 3224/3393/5048 +f 4027/3351/4998 4024/2103/3681 4026/2583/4149 +f 2891/1964/5109 2893/1824/3420 2892/3440/5110 +f 3961/3441/5111 3964/3078/5112 3963/3077/5112 +f 2497/3202/4834 2498/3012/4608 2282/2911/4610 +f 3511/3274/4915 3503/3385/5035 3529/3384/5034 +f 3459/2250/3815 3458/2810/3815 3464/2251/3815 +f 3515/2459/4021 3554/2458/4020 3555/3239/4880 +f 1746/3104/4706 1732/2145/4708 1733/2014/3596 +f 2733/1868/5113 2735/1845/3442 2829/2012/3594 +f 3398/3049/5114 3397/3442/5115 3411/3443/5116 +f 3801/3444/3313 3803/1810/3313 3805/2512/3313 +f 1746/3104/4706 1780/3213/4846 1781/3212/4845 +f 3912/3382/5028 3913/3445/5117 3813/3286/4930 +f 2688/2024/3604 2689/3337/4978 2690/2713/4285 +f 3017/2118/3296 3018/3373/3296 3010/3446/3296 +f 3935/2510/4070 3934/3032/4627 4014/2312/3868 +f 2966/3171/3713 2961/2837/3713 2963/1969/3713 +f 3143/2374/3937 3141/1756/3357 3161/2337/4532 +f 3678/2896/4473 3677/2496/4056 3571/3420/5080 +f 2962/3447/5118 2971/3448/5119 3058/3449/5120 +f 2666/3250/4896 2450/3450/5121 2449/2668/4240 +f 3648/3451/5122 3634/2151/3722 3647/3452/5123 +f 2796/1823/3419 2797/2011/3593 2786/3170/4798 +f 2972/3391/5045 2980/2791/4360 3012/3453/5124 +f 3420/3132/4743 3419/2834/4406 3421/2836/4408 +f 3018/3373/3296 3013/2874/3296 3010/3446/3296 +f 3469/2367/3927 3468/3454/5125 3459/2250/3928 +f 2832/1847/3444 2800/3176/4805 2799/2476/4040 +f 2113/2366/3925 2106/2080/3658 1930/3455/5126 +f 3675/1794/3394 3638/2776/4877 3673/3238/4879 +f 2672/3456/5127 2676/3111/4716 2675/3235/4872 +f 2676/3111/4716 2690/2713/4285 2675/3235/4872 +f 3270/3457/3699 3269/3179/3699 3241/3079/3699 +f 2324/3458/5128 2321/2931/4513 2551/2930/4512 +f 3499/2823/4391 3514/2460/4022 3515/2459/4392 +f 3976/3092/4694 3974/3313/5129 3991/3459/5130 +f 3779/3460/5131 3762/2955/4541 3790/2954/4540 +f 3259/3120/3699 3251/2431/3699 3249/3247/5069 +f 3221/2242/3806 3242/2241/3805 3243/3461/5132 +f 1818/1749/3642 1974/2754/5133 1977/2065/3643 +f 1974/2754/5133 1818/1749/3642 1817/3429/5090 +f 1973/2755/5089 1816/1956/5091 1810/1955/5134 +f 3531/1762/3363 3533/1741/3342 3520/1763/3364 +f 1948/2933/5135 1809/3462/5136 1807/3463/5137 +f 1948/2933/5135 1807/3463/5137 1806/3464/5138 +f 1971/2989/5139 1812/2582/5140 1972/2577/5141 +f 1972/2577/5141 1812/2582/5140 1814/1695/5142 +f 3009/2793/5143 3010/3446/5144 3011/3465/5145 +f 1806/3464/5138 1971/2989/5139 1970/2994/5146 +f 2014/3466/5147 2015/3467/5148 2013/2401/3966 +f 2107/2484/4048 2110/3468/5149 2046/3469/5150 +f 2115/2472/4036 2114/2471/4035 2206/3470/5151 +f 1965/3471/5152 1803/3020/4616 1801/3472/5153 +f 2601/3473/5154 2449/2668/4240 2450/3450/5121 +f 3763/2526/4085 3764/1783/3384 3780/2527/4086 +f 1956/2334/3890 1796/3474/5155 1958/3475/5156 +f 3687/2181/5157 3570/2540/5157 3686/1945/5157 +f 2454/3476/5158 2324/3458/5128 2552/3477/5159 +f 3356/2555/4115 3357/3478/5160 3358/2554/4114 +f 2770/3479/5161 2773/1907/3502 2771/2797/5162 +f 2976/1688/3296 2977/1798/4251 2978/2845/3296 +f 3446/2817/3558 3454/2899/3558 3447/2818/4385 +f 2815/2461/4023 2820/2547/4106 2821/2462/4024 +f 1795/2636/4203 1958/3475/5156 1796/3474/5155 +f 1755/2581/4970 1769/2216/3782 1771/3328/4971 +f 3233/3480/5163 3230/2383/5164 3232/3481/5165 +f 2983/2586/4153 2981/2620/5061 2982/3402/5060 +f 3581/3187/3280 3588/3182/3280 3584/2165/3280 +f 3611/2109/5166 3586/2920/4492 3587/3355/5167 +f 2889/3482/3592 2892/3440/5168 2890/3483/3592 +f 2028/3484/5169 2027/2101/3679 1873/2360/3919 +f 3121/2304/5170 3119/2303/5171 3120/2177/5172 +f 3458/2810/4379 3497/2809/4378 3495/3057/4653 +f 3617/3181/4811 3615/3225/5173 3588/3182/4812 +f 3644/2290/5174 3628/3485/5175 3631/2950/5176 +f 3144/2179/3932 3155/2329/3885 3139/3486/5177 +f 3164/2861/4433 3136/2281/4432 3165/3304/5178 +f 3035/1804/3403 3021/3487/5179 3026/1797/3812 +f 2862/1963/3725 2861/3488/3725 2859/3034/3725 +f 2513/2224/3790 2510/2443/5180 2511/2225/3791 +f 2136/3489/5181 2101/3490/5182 2135/3283/4928 +f 2097/2536/4095 2089/2732/4306 2098/2500/4062 +f 2851/2008/3592 2954/2052/3592 2955/2009/3592 +f 3817/2488/4052 3818/2413/4052 3821/2489/4051 +f 2884/2804/4373 2860/2806/4375 2885/3491/5183 +f 2236/3492/5184 1881/2724/5185 1879/2723/5186 +f 2036/2847/5187 2035/3493/5188 2236/3492/5184 +f 3008/3128/4738 3010/3446/5144 3009/2793/5143 +f 2872/2154/3725 2874/3494/3725 2907/3259/3725 +f 3954/3112/3512 3952/2327/3512 3983/2466/3512 +f 3237/3054/4650 3234/3495/5189 3236/3052/4648 +f 2243/2441/5190 2242/3496/5191 2244/3497/5192 +f 2244/3497/5192 2242/3496/5191 2245/2259/3823 +f 3762/2955/4541 3763/2526/4085 3795/1771/3372 +f 2841/3498/5193 2847/2764/4337 2935/2406/3971 +f 2238/3499/5194 2247/3500/5195 2248/3501/5196 +f 2238/3499/5194 2248/3501/5196 2249/3502/5197 +f 2249/3502/5197 2248/3501/5196 2246/3503/5198 +f 2237/3504/5199 2251/3505/5200 2252/2605/4172 +f 2252/2605/4172 2251/3505/5200 2253/2606/4173 +f 3877/1809/5201 3878/3506/5202 3908/1883/3477 +f 3510/2068/3815 3508/3507/4282 3478/2307/4282 +f 2078/3282/4927 2077/2402/3967 2135/3283/4928 +f 3434/2106/3684 3433/1993/3580 3407/1992/3579 +f 2396/3508/5203 2638/2898/4475 2395/3406/5068 +f 2259/3509/5204 2261/3510/5205 2260/3511/5206 +f 2260/3511/5206 2261/3510/5205 2262/3512/5207 +f 2262/3512/5207 2261/3510/5205 2263/3513/5208 +f 2316/1816/3412 2313/3232/4869 2315/3231/4868 +f 2543/3514/5209 2539/3291/4935 2570/2371/3934 +f 2270/3515/5210 2263/3513/5208 2269/3516/5211 +f 3319/3517/5212 3321/3183/4813 3320/3116/3734 +f 3890/3518/5213 3891/2986/4574 3899/2988/4576 +f 2177/3519/5214 2189/3520/5215 2178/3521/5216 +f 3899/2988/4576 3900/1985/3572 3898/1984/3571 +f 3654/3228/4864 3626/3522/5217 3627/2361/3920 +f 2642/3523/5218 2511/2225/3791 2440/3524/5219 +f 1992/2811/4380 1991/1930/3524 1993/1929/3523 +f 2274/1898/3492 2273/3525/5220 2275/2729/4302 +f 3513/2544/4103 3552/2077/3655 3553/2542/4101 +f 2265/3526/5221 2277/3154/5222 2278/3527/5223 +f 1800/3528/5224 1965/3471/5152 1801/3472/5153 +f 2197/3529/5225 2175/3530/5226 2174/1791/3391 +f 3072/2315/3873 2960/2983/4570 2966/3171/4800 +f 3382/1965/3554 3377/3531/5227 3392/3087/4688 +f 3210/2736/4310 3209/1828/3361 3208/2018/5228 +f 2306/2592/4159 2307/3532/5229 2305/2593/4160 +f 3048/3367/5014 2968/2942/4527 3049/2506/4066 +f 2173/1997/3584 2052/1790/3390 2050/2003/3590 +f 3787/2055/3632 3782/2748/4323 3781/1759/3360 +f 3059/3533/5230 3057/2336/3893 3056/2294/3851 +f 3088/3534/4865 3089/2634/4865 3092/2957/4543 +f 3714/1744/3827 3705/3535/3827 3711/3413/3827 +f 3886/2407/4595 3887/2839/5231 3895/2414/3980 +f 2534/3257/5232 2300/2377/5233 2297/2376/5234 +f 2878/1727/3725 2894/1878/3725 2906/1877/3725 +f 3732/2293/3827 3754/2292/3827 3734/3536/3827 +f 2461/1975/3562 2413/3537/5235 2414/3538/5236 +f 3563/3309/5237 3449/3098/5238 3562/3539/5238 +f 2653/1988/3575 2599/2233/3799 2652/1989/3576 +f 2286/3540/3307 2287/1699/3307 2288/1698/3306 +f 2366/3541/5239 2364/3542/5240 2387/2411/3977 +f 2488/3543/5241 2567/2386/3951 2492/3152/4774 +f 2292/3544/5242 2291/3545/5243 2293/2596/4163 +f 2133/2516/4075 2128/2515/4074 2078/3282/4927 +f 1825/2621/4190 1824/3546/5244 1834/2619/4186 +f 1760/3547/5245 1762/3091/4692 1761/3548/5246 +f 2294/2595/4162 2295/2597/4164 2290/2700/4274 +f 3931/2195/3766 4037/3106/4710 4038/1838/3435 +f 3716/3549/5247 3746/3550/5248 3747/3551/5249 +f 3436/3552/5250 3393/1966/3555 3435/2560/4120 +f 2696/2972/4558 2690/2713/4285 2698/3553/5251 +f 2020/3554/5252 2019/3436/5105 1859/2766/4339 +f 1913/3555/5253 1930/3455/5126 2106/2080/3658 +f 3391/2559/4119 3390/1991/3578 3433/1993/3580 +f 3467/3556/5254 3466/2808/5255 3468/3454/5256 +f 3375/1806/3281 3378/3557/3281 3372/2028/3281 +f 3396/3558/5257 3395/3559/5258 3322/3560/5259 +f 3805/2512/3313 3806/2271/5260 3802/3561/3313 +f 3601/2164/3737 3599/1915/3509 3584/2165/3738 +f 2176/3562/5261 2172/3563/5262 2175/3530/5226 +f 3078/2838/5263 2961/2837/5263 2969/3564/5263 +f 2309/3565/5264 2308/3566/5265 2310/3567/5266 +f 3812/3568/5267 3810/3569/5268 3920/3570/5268 +f 3322/3560/5259 3333/3571/5269 3396/3558/5257 +f 3660/1733/3336 3656/2758/4331 3651/1731/3334 +f 3325/3572/5270 3440/3573/5270 3323/3574/5270 +f 2617/1888/3482 2581/1890/3484 2591/3134/4744 +f 2147/3575/5271 2145/3576/5272 2110/3468/5149 +f 3633/1666/4263 3650/1732/3335 3651/1731/4264 +f 3476/1779/3380 3478/2307/3863 3475/1777/3378 +f 1839/2626/4195 1840/2629/4198 1836/2623/4192 +f 2875/2903/5273 2876/1726/3329 2874/3494/5274 +f 2348/2309/5275 2349/3577/5276 2350/3578/5277 +f 2323/3579/5278 2324/3458/5279 2325/3580/5280 +f 2325/3580/5280 2324/3458/5279 2326/3581/5281 +f 2325/3580/5280 2326/3581/5281 2327/2421/3987 +f 2329/2419/3985 2327/2421/3987 2326/3581/5281 +f 2904/2143/3725 2901/3403/3725 2869/3582/3725 +f 2134/3121/4728 2105/3292/4936 2130/2079/3657 +f 2328/2420/3986 2329/2419/3985 2330/2980/4567 +f 3397/3442/5115 3396/3558/5257 3412/3583/5282 +f 3958/2067/3645 3960/2761/5283 3940/2066/3644 +f 2641/3584/5284 2642/3523/5218 2443/2962/4548 +f 3210/2736/4310 3204/1723/3326 3302/2227/3793 +f 2336/3585/5285 2335/3066/4661 2337/3586/5286 +f 2337/3586/5286 2335/3066/4661 2338/3587/5287 +f 2337/3586/5286 2338/3587/5287 2339/3588/5288 +f 2339/3588/5288 2338/3587/5287 2340/1894/5289 +f 1897/3589/5290 1896/3008/4604 1938/2672/4244 +f 2202/3590/5291 2121/2365/3924 2205/2364/3923 +f 2341/3591/5292 2342/1893/5293 2343/3045/4639 +f 3824/3344/3288 3825/3592/3289 3826/2936/3289 +f 2953/2053/3631 2952/3593/3631 2950/2054/3631 +f 3190/2840/4412 3189/1895/3489 3149/2344/3901 +f 2808/2314/5294 2823/2180/3752 2809/2704/4278 +f 1728/2133/3525 1729/2356/3525 1719/2563/3525 +f 3675/1794/3394 3639/1793/3393 3638/2776/4877 +f 3030/3594/5295 3031/3595/5296 3065/3596/5297 +f 2856/2572/4131 2857/3597/5298 2868/2573/4132 +f 2731/3347/3464 2736/1864/3465 2734/3133/3464 +f 3773/3598/5299 3761/3599/5300 3759/2451/5301 +f 2188/3600/5302 2192/3426/5087 2191/2491/4054 +f 3368/3419/3281 3370/2320/3281 3382/1965/3281 +f 2356/3601/5303 2355/3194/4825 2370/2717/4290 +f 2370/2717/4290 2355/3194/4825 2371/3602/5304 +f 1977/2065/5305 1974/2754/4327 2071/3603/5306 +f 2278/3527/5223 2277/3154/5222 2279/3203/5307 +f 2373/3604/5308 2372/3196/4827 2374/2864/4436 +f 2375/2863/4435 2376/3605/5309 2374/2864/4436 +f 2374/2864/4436 2376/3605/5309 2377/3606/5310 +f 1985/2781/4352 1884/3607/5311 1984/3608/5312 +f 2376/3605/5309 2379/3609/5313 2380/2949/5314 +f 1791/2637/5315 1795/2636/5316 1796/3474/5317 +f 3418/1873/3469 3417/1875/3471 3420/3132/4743 +f 2889/3482/3592 2888/3610/5318 2887/3611/5319 +f 2193/3425/5086 2200/2046/3625 2201/3612/5320 +f 2168/2206/3773 2165/2205/3772 2186/2734/4308 +f 2247/3500/5195 2242/3496/5191 2243/2441/5190 +f 3090/3229/4866 3092/2957/4543 3089/2634/4865 +f 3573/3255/5321 3577/2183/5322 3688/2182/5322 +f 3013/2874/5323 3012/3453/5324 3011/3465/5145 +f 2874/3494/3725 2877/1725/3725 2907/3259/3725 +f 2381/3613/5325 2375/2863/4435 2383/2570/4129 +f 2797/2011/3593 2787/3338/4992 2786/3170/4798 +f 3565/1833/3429 3444/1835/3431 3452/3614/3429 +f 1848/2645/4216 1849/3615/5326 1847/2643/4214 +f 1987/2288/3848 1908/2287/3847 1907/3616/5327 +f 3981/3617/5328 4002/2464/4026 3983/2466/4028 +f 2646/2073/3651 2648/3243/4885 2647/1987/3574 +f 1858/2767/5329 2073/2456/4018 1864/2455/4017 +f 2175/3530/5226 2172/3563/5262 2163/3618/5330 +f 2014/3466/5147 2072/2803/4372 2017/2558/4118 +f 3661/1978/3565 3652/2757/4330 3656/2758/4331 +f 1811/1748/3349 1808/3619/5331 1810/1955/3541 +f 3588/3182/4812 3615/3225/5173 3613/2110/5332 +f 3416/3353/5001 3330/3431/5333 3419/2834/4406 +f 3312/2322/3878 3279/2321/3877 3280/2824/4393 +f 2366/3541/5239 2389/3620/5334 2386/2948/4535 +f 3058/3449/5120 3062/2393/3958 2962/3447/5118 +f 1714/3621/5335 1711/2353/5336 1713/3622/5337 +f 3773/3598/5299 3772/2230/5338 3761/3599/5300 +f 2744/3623/5339 2745/3624/5340 2757/3625/5341 +f 3112/3626/5342 3111/3627/5343 3113/3628/5344 +f 2838/3219/3464 2837/2999/3464 2833/3629/3464 +f 2376/3605/5309 2386/2948/4535 2389/3620/5334 +f 3299/1774/3375 3211/1760/5345 3213/1775/3376 +f 3782/2748/4323 3787/2055/3632 3773/3598/5299 +f 2576/2973/4559 2574/2639/4207 2575/2370/3933 +f 3717/3281/5346 3707/3110/4714 3706/3630/5347 +f 3508/3507/5348 3523/3164/5349 3524/3438/5350 +f 2846/2144/5351 2845/2258/3631 2853/2906/4480 +f 2717/3168/2635 2718/3631/2635 2426/3167/2635 +f 3473/3632/5352 3474/1778/3379 3475/1777/3378 +f 4013/3102/4702 4015/2313/3869 4014/2312/3868 +f 2493/3155/4777 2264/3633/5353 2494/3634/5354 +f 2920/2142/3716 2921/3029/5355 2901/3403/5065 +f 2723/3635/5356 2506/2720/5357 2721/1954/5358 +f 3260/3636/5359 3259/3120/4726 3273/3119/4725 +f 2228/3216/4852 2227/3370/5360 2049/2879/5361 +f 2397/3637/5362 2398/3638/5363 2460/3639/5364 +f 3030/3594/5365 3018/3373/5018 3031/3595/5366 +f 2883/3325/3725 2886/3640/5367 2903/2833/3725 +f 3859/3641/5368 3860/1677/5368 3862/2935/5369 +f 2763/3642/3454 2791/2687/3454 2761/2702/3454 +f 2990/2743/4318 2975/2742/4317 2988/3643/5370 +f 3720/1946/3534 3708/1948/3536 3718/2940/4715 +f 2483/1690/3298 2486/3644/5371 2261/3510/5372 +f 2738/3000/3464 2740/3645/5373 2730/3123/3464 +f 3937/2392/3512 3938/2966/3512 3939/1920/3513 +f 3538/2036/3614 3536/3166/4790 3457/2941/5374 +f 3010/3446/5144 3013/2874/5323 3011/3465/5145 +f 1985/2781/4352 2211/2202/3769 2210/2683/4255 +f 3477/2306/3862 3479/3646/5375 3480/3386/5037 +f 2114/2471/4035 2120/3174/4803 2122/3647/5376 +f 3638/2776/4347 3639/1793/5377 3624/2777/4348 +f 3432/2107/3685 3407/1992/3579 3389/1807/5378 +f 2622/2969/4555 2632/2968/4554 2445/3648/5379 +f 4009/2952/4538 4008/3649/5380 4010/2379/3944 +f 1774/3432/5095 1777/2325/3881 1776/3315/4958 +f 3508/3507/4282 3507/3329/4282 3475/1777/4282 +f 1750/3090/4691 1763/3065/4660 1764/3650/5381 +f 3329/3352/5000 3334/2163/3735 3327/2162/3734 +f 3935/2510/4070 4016/2311/3867 4019/2187/3758 +f 2387/2411/3977 2388/3651/5382 2389/3620/5334 +f 2928/3652/5383 2918/1961/5384 2926/3653/5385 +f 2049/2879/4452 2051/3263/4907 2050/2003/3590 +f 2678/3236/4873 2691/2712/4284 2671/2092/3671 +f 3019/2007/3296 3024/3075/3296 2987/2005/3296 +f 3884/3654/5386 3883/3341/5387 3872/2564/5388 +f 2622/2969/4555 2445/3648/5379 2633/3655/5389 +f 4003/2185/5390 4002/2464/4026 3981/3617/5328 +f 4035/2256/3820 4036/2255/3819 4038/1838/3435 +f 3559/3122/4729 3532/2262/3826 3519/1764/3365 +f 2781/3656/5391 2793/2239/3803 2794/2238/3802 +f 3262/2417/3983 3285/2416/3982 3266/3407/5392 +f 3449/3098/3558 3446/2817/3558 3455/2819/4386 +f 3227/2699/4273 3228/2698/4272 3229/2382/5393 +f 3867/1679/3447 3865/3657/5394 3880/1848/3445 +f 3923/3285/5395 4040/2852/5395 3924/2707/5396 +f 3989/3093/4695 3988/3658/5397 3975/1934/4693 +f 3728/3659/5398 3726/3660/5399 3727/3661/5400 +f 2258/3662/5401 2257/3663/5402 2256/1691/5403 +f 3360/3664/5404 3359/3665/5405 3340/1786/5406 +f 1845/3666/5407 1844/3667/5408 1846/2644/4215 +f 2764/2221/3909 2762/3668/5409 2746/2352/3910 +f 2484/3669/5410 2482/1689/3297 2253/2606/5411 +f 3362/2958/4544 3365/2960/4546 3363/3670/4544 +f 3798/3671/5412 3799/3672/5413 3800/3037/4631 +f 3974/3313/5129 3992/2257/5414 3991/3459/5130 +f 3347/1815/4704 3346/3673/5415 3348/3103/4705 +f 3259/3120/3699 3260/3636/3699 3253/2918/3699 +f 1791/2637/5315 1794/2333/4121 1798/2467/4123 +f 3156/2330/3886 3157/2747/5416 3170/3674/5417 +f 2495/3201/5418 2496/3675/5419 2497/3202/5420 +f 2607/2399/3964 2629/2116/3695 2628/2400/3965 +f 2499/3676/5421 2496/3675/5419 2500/3677/5422 +f 2575/2370/3933 2693/2131/3708 2695/2130/3707 +f 2501/3013/5423 2498/3012/5424 2502/2921/5425 +f 3929/2511/4071 3935/2510/4070 4019/2187/3758 +f 3651/1731/4264 3652/2757/5426 3632/2362/3921 +f 2507/2442/5427 2508/2113/5428 2509/3678/5429 +f 2507/2442/5427 2509/3678/5429 2510/2443/5180 +f 3946/2391/5430 3947/3297/4943 3950/3679/5431 +f 1751/1885/3479 1735/1887/3481 1750/3090/4691 +f 2615/2662/4235 2619/2115/3694 2620/2114/3693 +f 2512/2223/3789 2515/2532/5432 2513/2224/3790 +f 2517/2533/5433 2516/3222/4857 2518/3026/5434 +f 1741/2357/5435 1740/2135/3712 1775/3314/4957 +f 2781/3656/3454 2782/3680/3454 2777/1730/3454 +f 3418/1873/3469 3403/1924/3518 3408/1874/3470 +f 2791/2687/4259 2803/2686/4258 2789/2785/4356 +f 2525/3681/5436 2526/2876/5437 2527/2675/5438 +f 2639/1994/3581 2637/3682/5439 2638/2898/4475 +f 3580/2210/3533 3574/3335/3533 3569/3683/3533 +f 1860/3684/5440 1859/2766/4339 1863/2768/4341 +f 2049/2879/5361 2053/2878/5441 2228/3216/4852 +f 3124/2543/4791 3125/3685/4791 3127/3017/4792 +f 3781/1759/3360 3775/1758/3359 3788/2056/3633 +f 3578/2211/3779 3579/3069/5442 3658/3686/5443 +f 2901/3403/3725 2900/2156/3725 2866/3001/3725 +f 2539/3291/4935 2540/3290/4934 2541/2763/4336 +f 2636/2799/4368 2637/3682/5439 2446/3687/5444 +f 2097/2536/4095 2082/2535/4094 2096/2733/4307 +f 1674/3688/5445 1678/3689/5446 1778/2323/3879 +f 1869/2689/4261 1868/3690/5447 1867/3414/5448 +f 3053/1913/3507 3052/1912/3506 3055/2335/3892 +f 3926/2213/4425 3931/2195/4425 3934/3032/4627 +f 2720/2112/2635 2715/2111/2635 2427/1952/3540 +f 1773/3150/4771 1774/3432/5095 1740/2135/3712 +f 3396/3558/5449 3397/3442/5450 3386/2197/4644 +f 1738/2495/3525 1735/1887/3525 1700/2397/3525 +f 3358/2554/4114 3357/3478/5160 3359/3665/5451 +f 3316/2019/3361 3317/3294/3361 3313/3691/3361 +f 3885/2408/3974 3884/3654/5386 3870/3692/5452 +f 2580/2188/3759 2585/2190/3761 2584/3693/5453 +f 2741/1846/3443 2740/3645/5373 2817/3694/5454 +f 2998/1753/3354 2996/2928/5455 2997/1751/3352 +f 2863/1825/4566 2893/1824/3552 2855/3033/4884 +f 2140/1671/3282 2152/2252/3816 2124/3322/4965 +f 3036/2508/4068 3026/1797/3812 3037/2248/3814 +f 3760/2291/5456 3761/3599/5300 3771/2229/5457 +f 2609/3695/5458 2603/2405/3970 2604/3696/5459 +f 2801/3357/5008 2816/2548/4107 2815/2461/4023 +f 2598/3321/4964 2601/3473/5154 2626/3697/5460 +f 3294/2316/3874 3295/3698/5461 3296/3192/4822 +f 1805/2074/4682 2185/3084/4681 1969/2578/5462 +f 3846/1718/4267 3849/2388/3953 3847/2694/4265 +f 1748/2444/4008 1759/1904/3499 1761/3548/5246 +f 3993/1839/3436 4038/1838/3435 4036/2255/3819 +f 2492/3152/5463 2569/3151/5463 2491/3156/5463 +f 2160/3699/5464 2159/3700/5465 2161/3701/5466 +f 2509/3678/5429 2508/2113/5428 2505/3142/4762 +f 2086/3011/4607 2095/1850/3448 2094/2985/4573 +f 3040/3276/4917 3041/3076/5467 3054/2295/3852 +f 2487/3702/5468 2271/1899/3493 2485/3703/5469 +f 3572/2844/4416 3573/3255/3533 3567/2267/5470 +f 2319/2961/4547 2321/2931/5471 2322/3704/5472 +f 3617/3181/5063 3618/3705/5473 3616/3224/4859 +f 2545/3178/4807 2544/3706/5474 2553/3126/4736 +f 1674/3688/3475 1671/3433/5096 1665/3031/3475 +f 3028/3707/5475 3029/3372/5476 3063/1788/3388 +f 3544/3708/5477 3527/2976/4562 3542/3709/5478 +f 3261/2121/5479 3287/3710/5480 3262/2417/3983 +f 3212/3711/3362 3211/1760/3361 3203/1761/3362 +f 3948/2882/5481 3946/2391/5430 3950/3679/5431 +f 3893/1685/3295 3894/1684/3294 3903/3234/4871 +f 3689/1944/5482 3567/2267/5482 3573/3255/5483 +f 3523/3164/4788 3522/1739/3340 3535/3165/4789 +f 3711/3413/5484 3731/3712/5485 3733/3713/5486 +f 2866/3001/4594 2867/2571/4593 2869/3582/5487 +f 3683/2040/3618 3578/2211/3779 3657/2038/3616 +f 3848/2387/4742 3850/2389/5488 3828/3130/4740 +f 3132/3714/5489 3146/3715/5490 3166/3305/4950 +f 1765/2035/3613 1752/3327/5491 1751/1885/3479 +f 2915/1876/3472 2914/3375/5021 2949/2590/4157 +f 3864/1808/3407 3863/2428/3991 3877/1809/3408 +f 3140/3716/5492 3139/3486/5177 3154/2158/3731 +f 3762/2955/4541 3779/3460/5131 3748/3200/4831 +f 3231/3408/3699 3228/2698/3699 3262/2417/3699 +f 3264/3717/5493 3276/3172/5494 3259/3120/4726 +f 2676/3111/4716 2672/3456/5127 2674/2083/3661 +f 2817/3694/5454 2818/3139/4751 2819/2546/4105 +f 2908/2138/3714 2895/3205/4837 2896/3718/5495 +f 3277/3173/4802 3278/2125/3702 3308/2919/4491 +f 2385/3303/4948 2384/2862/4434 2372/3196/4827 +f 1697/3360/3525 1700/2397/3525 1734/1886/3525 +f 3881/3719/5496 3882/3340/4980 3914/3720/5497 +f 3029/3372/5476 3064/1789/3389 3063/1788/3388 +f 3486/2773/3815 3488/3251/3815 3506/2771/3815 +f 2919/2141/3715 2904/2143/3717 2905/1962/5498 +f 3502/2710/5004 3512/3189/5499 3513/2544/4103 +f 2958/1787/3713 2965/2136/3713 2956/2137/3713 +f 2970/3099/5500 2960/2983/4570 3074/2507/4067 +f 2871/2167/3740 2874/3494/5274 2872/2154/3741 +f 2239/2261/5501 2241/3721/5502 2477/2552/5503 +f 2992/2945/4531 2990/2743/4850 2989/3722/5504 +f 2630/3354/5003 2608/3723/5505 2609/3695/5458 +f 2782/3680/3454 2780/1822/3454 2775/2196/3454 +f 2735/1845/3442 2830/3724/5506 2829/2012/3594 +f 1787/2191/3475 1786/2192/3475 1782/2753/3475 +f 1805/2074/4682 1969/2578/5462 1815/1697/5507 +f 2531/2475/4039 2674/2083/3661 2672/3456/5127 +f 1846/2644/5508 2006/2502/5509 2010/2501/5510 +f 2780/1822/3454 2786/3170/4979 2771/2797/3454 +f 2610/3317/4960 2630/3354/5003 2609/3695/5458 +f 3570/2540/4099 3566/2266/4100 3684/2541/4100 +f 3225/3725/5511 3256/3245/4887 3226/2122/4271 +f 3563/3309/3559 3562/3539/3559 3565/1833/3559 +f 3869/2174/3748 3891/2986/5512 3873/3427/5513 +f 2634/1996/3583 2464/3726/5514 2463/2524/4083 +f 3874/3428/5515 3889/3727/5516 3888/2598/5517 +f 2963/1969/4409 3078/2838/4409 3077/1970/4409 +f 1945/2815/4383 1994/2814/4382 1946/2975/4561 +f 3586/2920/3280 3585/3728/5005 3584/2165/3280 +f 2768/2539/4979 2769/3729/3454 2787/3338/4979 +f 3511/3274/4915 3529/3384/5034 3546/2601/4168 +f 2719/3730/5518 2506/2720/5357 2505/3142/5519 +f 3443/2317/3559 3449/3098/3558 3450/2318/3875 +f 3826/2936/4518 3825/3592/5520 3842/3731/5521 +f 2284/3081/4678 2705/3732/5522 2528/2473/4676 +f 3105/2098/3676 3130/1957/3676 3106/1959/3726 +f 3195/2331/3887 3167/2159/3732 3155/2329/3885 +f 2062/1767/5523 2063/2661/4234 2060/1765/4889 +f 2461/1975/3562 2579/3733/5524 2413/3537/5235 +f 2949/2590/4157 2948/3280/4925 2852/2786/4924 +f 2899/3204/3725 2898/1923/3725 2890/3483/3725 +f 2178/3521/5216 2167/3734/5525 2177/3519/5214 +f 3336/1670/5526 3337/1669/5527 3348/3103/5528 +f 3939/1920/3513 3957/3735/5529 3958/2067/3645 +f 3218/2384/3949 3217/3439/5108 3225/3725/5530 +f 1746/3104/4706 1733/2014/3596 1745/1719/5531 +f 2021/3736/5532 1857/2522/5533 2015/3467/5534 +f 2100/3737/5535 2087/2971/4557 2102/3738/5536 +f 2593/3105/4709 2585/2190/3761 2586/2189/3760 +f 3264/3717/5493 3263/2865/4439 3278/2125/4438 +f 3309/2127/3704 3308/2919/4491 3278/2125/3702 +f 3113/3628/5344 3111/3627/5343 3110/2282/5537 +f 3574/3335/3533 3575/3334/4976 3569/3683/3533 +f 2780/1822/3418 2782/3680/5538 2795/1704/3310 +f 3261/2121/3699 3228/2698/3699 3226/2122/3699 +f 2600/2667/4239 2598/3321/4964 2595/2231/3797 +f 3937/2392/3957 3949/2326/4457 3938/2966/4552 +f 2300/2377/3942 2299/3241/5539 2305/2593/5540 +f 1727/2013/4124 1733/2014/3525 1714/3621/3525 +f 3366/3082/4679 3367/3418/5077 3368/3419/5079 +f 2869/3582/3725 2901/3403/3725 2866/3001/3725 +f 2638/2898/4475 2637/3682/5439 2635/2798/4367 +f 2158/2669/4241 2063/2661/4234 2160/3699/5464 +f 1768/2078/3656 1672/2727/4301 1770/3739/5541 +f 2040/1911/3505 2039/3740/5542 2108/2790/4359 +f 1791/2637/4204 1788/2483/5543 1952/2738/5544 +f 1741/2357/3915 1729/2356/3914 1728/2133/5545 +f 3081/1701/3841 3084/2280/3843 3090/3229/4866 +f 1914/3350/4997 1913/3555/5253 1989/1832/3428 +f 2326/3581/5546 2453/3741/5547 2452/3742/5548 +f 2770/3479/5161 2771/2797/5162 2769/3729/5549 +f 3373/2889/4991 3335/2812/4991 3336/1670/5526 +f 3606/2124/5550 3604/3416/5551 3585/3728/5552 +f 4008/3649/5380 3998/3743/5553 4012/2380/3945 +f 1918/3368/2635 1921/3744/2635 2229/3369/2635 +f 2584/3693/5453 2583/2831/4402 2582/3135/4745 +f 3150/2841/5554 3149/2344/5555 3135/2343/3900 +f 1981/3389/5040 1982/3745/5556 1947/3211/4843 +f 3648/3451/5557 3647/3452/5558 3658/3686/5443 +f 3452/3614/5559 3564/3310/5560 3565/1833/5559 +f 3700/2057/3634 3702/3746/5561 3787/2055/3632 +f 2140/1671/3282 2076/3326/4967 1939/3747/5562 +f 3396/3558/5257 3333/3571/5269 3412/3583/5282 +f 2216/2890/4467 1932/2490/4053 2194/2492/4055 +f 3447/2818/4385 3558/2608/4175 3557/2607/4174 +f 3303/2226/3792 3272/3748/5563 3304/3749/5564 +f 1739/2051/4772 1756/2050/4969 1772/3149/4770 +f 1802/3193/4823 1804/3022/5565 1805/2074/3652 +f 2105/3292/4936 2134/3121/4728 2133/2516/4075 +f 2732/1869/5566 2833/3629/5566 2835/3190/5566 +f 2505/3142/4762 2644/3146/4767 2509/3678/5429 +f 2842/3377/5024 2841/3498/5193 2933/2042/3620 +f 2050/2003/3590 2109/1998/3585 2173/1997/3584 +f 3999/3100/5567 3985/3062/5568 4000/3101/5569 +f 3055/2335/3892 3054/2295/3852 3056/2294/3851 +f 2637/3682/5439 2447/2665/4237 2446/3687/5444 +f 3307/3750/5570 3305/1829/3425 3275/2868/4442 +f 2980/2791/4360 3011/3465/5571 3012/3453/5124 +f 3856/3751/5572 3853/3752/5573 3854/2566/4232 +f 2483/1690/3298 2258/3662/5574 2256/1691/3299 +f 3703/3753/5575 3704/2647/4956 3784/2218/3784 +f 3146/3715/5490 3147/3010/4606 3186/3754/5576 +f 3111/3627/5343 3109/3138/4748 3110/2282/5537 +f 2970/3099/3713 2968/2942/3713 2969/3564/3713 +f 3027/1796/3813 3038/2943/4528 3037/2248/3814 +f 2617/1888/3482 2612/2990/4578 2590/1889/3483 +f 2964/3755/3713 2962/3447/5118 2957/3324/3713 +f 1714/3621/3525 1715/3756/3525 1727/2013/4124 +f 2416/3757/5577 2418/3758/5578 2473/2872/4447 +f 3326/2108/5212 3319/3517/5212 3325/3572/5579 +f 2763/3642/5580 2762/3668/5581 2764/2221/3787 +f 3378/3557/5582 3389/1807/3406 3390/1991/3578 +f 3292/2070/3648 3295/3698/5461 3294/2316/3874 +f 3176/2338/3895 3177/3332/4974 3175/3252/4897 +f 3910/3397/5055 3911/2128/3705 3908/1883/3477 +f 3057/2336/3893 3059/3533/5230 3058/3449/5120 +f 3209/1828/3424 3304/3749/5564 3305/1829/3425 +f 3935/2510/4070 3930/2509/4069 3933/2214/4628 +f 2169/2207/3774 2170/3759/5583 2167/3734/5525 +f 3970/2826/5584 3942/1919/4508 3968/2045/5585 +f 1877/3089/4690 1878/3088/4689 1876/2848/5586 +f 3644/2290/5174 3645/2184/3755 3628/3485/5175 +f 2792/3371/5015 2781/3656/5391 2779/3760/5587 +f 2550/3177/5588 2315/3231/5589 2314/3230/5590 +f 3271/2228/3794 3257/3761/5591 3260/3636/5359 +f 1787/2191/5592 1666/2728/5592 1673/1879/5592 +f 3118/2178/5593 3117/3762/5593 3115/2549/4108 +f 3119/2303/5171 3118/2178/5594 3120/2177/5172 +f 3137/3763/3730 3108/2283/3730 3107/1958/3730 +f 3350/1813/4703 3349/3764/5595 3351/3765/5596 +f 3703/3753/5575 3702/3746/5561 3701/2453/3313 +f 3813/3286/4930 3809/3288/4931 3912/3382/5028 +f 1756/2050/4969 1771/3328/4971 1772/3149/4770 +f 3387/2198/3281 3355/2063/3281 3358/2554/3281 +f 3714/1744/3345 3713/3766/5597 3741/1742/3343 +f 2739/3140/4752 2821/2462/4024 2820/2547/4106 +f 3401/1676/3287 3400/1675/3286 3410/3767/5598 +f 3925/2090/3669 3923/3285/4425 3924/2707/4397 +f 1717/2562/5599 1715/3756/5600 1716/3768/5601 +f 3443/2317/5602 3562/3539/5602 3449/3098/5602 +f 1839/2626/4195 1836/2623/4192 1838/2625/4194 +f 3100/2802/5603 3099/2801/5604 3112/3626/5605 +f 2446/3687/5444 2445/3648/5379 2623/3109/4713 +f 2623/3109/4713 2445/3648/5379 2611/3108/4712 +f 1948/2933/5135 1810/1955/5134 1809/3462/5136 +f 3139/3486/5177 3155/2329/3885 3154/2158/3731 +f 1964/2468/4031 1792/2561/5606 1962/2277/3837 +f 2333/3068/4663 2334/3067/4662 2332/2982/4569 +f 3074/2507/4067 3073/1805/3404 3035/1804/3403 +f 3592/3185/5607 3594/3769/5608 3596/3770/5609 +f 2122/3647/5376 2119/2627/4196 2121/2365/3924 +f 3648/3451/5122 3649/3771/5610 3635/3411/5611 +f 3522/1739/5612 3523/3164/5349 3508/3507/5348 +f 3173/2150/3721 3175/3252/4897 3174/3772/5613 +f 2173/1997/3584 1937/1999/3586 2196/3773/5614 +f 3894/1684/3294 3877/1809/5201 3904/3233/4870 +f 2632/2968/4554 2611/3108/4712 2445/3648/5379 +f 3583/1917/3511 3584/2165/3738 3599/1915/3509 +f 2633/3655/5389 2447/2665/4237 2634/1996/3583 +f 2400/3774/5615 2401/3775/5616 2464/3726/5514 +f 2064/3396/5617 2063/2661/4234 2062/1767/5523 +f 1799/2770/4344 1966/3776/5618 1800/3528/5224 +f 3670/3422/5083 3674/3777/5619 3672/3778/5620 +f 2107/2484/4048 2108/2790/4359 2111/2648/4217 +f 3798/3671/5412 3766/2997/5621 3767/3779/5622 +f 3982/3061/5623 4001/2465/4027 4000/3101/4701 +f 1831/2616/5624 1941/2653/4223 2004/3780/5625 +f 2200/2046/3625 2190/3424/5085 2199/2047/3626 +f 3827/3131/4741 3826/2936/4518 3845/2695/4520 +f 3325/3572/5626 3437/3781/5626 3439/3782/5626 +f 3659/3783/5627 3658/3686/5443 3579/3069/5442 +f 3035/1804/3403 3026/1797/3812 3036/2508/4068 +f 2909/3417/5076 2908/2138/3714 2938/3784/5628 +f 2640/1995/3582 2638/2898/4475 2460/3639/5364 +f 4043/2910/4425 4044/2706/4425 4041/2854/4425 +f 3211/1760/5345 3299/1774/3375 3301/3785/5629 +f 2898/1923/3516 2899/3204/4836 2909/3417/5076 +f 4044/2706/4425 4040/2852/4425 4041/2854/4425 +f 4001/2465/4027 4017/3143/4764 4015/2313/3869 +f 2732/1869/4820 2836/2998/4821 2730/3123/4821 +f 2968/2942/3713 2971/3448/5119 2969/3564/3713 +f 2379/3609/5313 2375/2863/4435 2378/3786/5630 +f 3829/3787/5631 3828/3130/4740 3851/2658/5632 +f 3164/2861/4994 3165/3304/4949 3181/2247/3811 +f 3388/1745/3346 3375/1806/3405 3376/3788/5633 +f 1788/2483/5543 1953/2739/5634 1952/2738/5544 +f 3919/3269/5635 3917/3268/5635 3807/3287/5635 +f 2196/3773/5614 2174/1791/3391 2173/1997/3584 +f 3151/2298/5636 3192/2956/4542 3191/2842/4414 +f 1962/2277/3837 1792/2561/5606 1793/2278/3838 +f 3997/3789/5637 3984/3790/5638 3998/3743/5553 +f 3363/3670/3281 3386/2197/3281 3361/2199/3281 +f 3375/1806/3405 3389/1807/3406 3378/3557/5582 +f 3172/3791/5639 3173/2150/3721 3174/3772/5613 +f 3826/2936/3289 3827/3131/4741 3828/3130/4740 +f 3987/3162/4786 4030/1871/3467 4028/3792/5640 +f 2645/3144/4765 2655/3244/4886 2654/3404/5066 +f 3389/1807/5378 3388/1745/3346 3432/2107/3685 +f 2027/2101/3679 2029/2100/3917 1873/2360/3919 +f 2621/2663/4236 2622/2969/4555 2616/2525/4084 +f 2821/2462/4024 2803/2686/4315 2802/2463/4025 +f 2739/3140/4752 2740/3645/5373 2738/3000/3464 +f 3281/2825/4394 3282/1713/3319 3291/2071/3649 +f 3276/3172/4801 3306/1827/3423 3307/3750/5570 +f 3752/3793/5641 3778/3056/5642 3777/3794/5643 +f 3769/2750/4325 3770/2870/4444 3784/2218/3784 +f 3504/2977/4282 3503/3385/3815 3470/3795/3815 +f 2986/2585/5644 2974/1687/5645 2973/1686/4189 +f 2742/3265/4909 2776/1728/4905 2750/3262/4905 +f 3846/1718/4267 3845/2695/4266 3844/2937/5646 +f 3548/2600/4167 3547/3796/5647 3546/2601/4168 +f 3080/2504/5648 2964/3755/5648 2957/3324/5648 +f 3576/3797/3533 3579/3069/3533 3573/3255/3533 +f 3223/3380/5026 3222/2499/4061 3250/2430/4060 +f 1668/2692/4844 1677/2691/5649 1760/3547/5245 +f 2858/2902/3725 2857/3597/5298 2855/3033/3725 +f 3201/3798/3841 3197/1702/4865 3196/3799/3841 +f 2118/3157/4779 2120/3174/4803 2114/2471/4035 +f 3014/3390/5062 3012/3453/5324 3013/2874/5323 +f 2008/3800/5650 1852/2576/5651 1850/2575/5652 +f 2515/2532/4091 2714/2534/4093 2716/3801/5653 +f 1678/3689/5446 1779/1721/3324 1778/2323/3879 +f 2478/3019/4615 2458/1982/3569 2473/2872/4447 +f 2736/1864/3460 2731/3347/5654 2823/2180/3752 +f 3692/1708/3314 3695/3055/4651 3792/3005/4601 +f 2110/3468/5149 2144/1734/3337 2142/1736/3339 +f 2577/2373/3936 2587/2403/3968 2586/2189/3760 +f 3354/2062/4797 3352/2061/5655 3338/1668/5656 +f 3769/2750/4325 3704/2647/4956 3694/2646/4326 +f 2540/3290/5657 2301/3242/4883 2300/2377/5233 +f 2051/3263/5658 2229/3369/5659 2048/3264/5660 +f 3012/3453/5124 3014/3390/5044 2972/3391/5045 +f 1735/1887/3525 1734/1886/3525 1700/2397/3525 +f 3327/2162/3734 3320/3116/3734 3330/3431/3734 +f 3770/2870/4444 3783/2871/4445 3784/2218/3784 +f 3223/3380/3699 3224/3393/3699 3219/3802/5661 +f 2169/2207/3774 2158/2669/4241 2170/3759/5583 +f 2861/3488/5662 2862/1963/3551 2891/1964/3553 +f 2111/2648/4217 2147/3575/5271 2110/3468/5149 +f 3849/2388/3953 3852/2659/4231 3850/2389/3954 +f 2729/2705/3464 2727/3220/3464 2726/3401/3464 +f 3485/3215/4848 3487/3208/4840 3488/3251/5663 +f 2231/3803/5664 2048/3264/5660 2229/3369/5659 +f 1734/1886/3480 1752/3327/4968 1731/3804/5665 +f 3611/2109/5166 3610/2434/4493 3586/2920/4492 +f 2638/2898/4475 2635/2798/4367 2405/3024/4620 +f 3280/2824/4393 3291/2071/3649 3312/2322/3878 +f 2614/2947/4534 2380/2949/4536 2379/3609/5313 +f 3414/3805/5666 3332/3806/5667 3334/2163/3735 +f 3989/3093/5668 3990/3807/5669 4033/3808/5670 +f 3202/3809/5671 3314/3810/5672 3203/1761/5672 +f 2233/2235/4015 2042/2449/4014 2041/1910/5673 +f 3199/2632/5674 3088/3534/5675 3094/2424/5676 +f 3984/3790/5638 3985/3062/5568 3998/3743/5553 +f 3284/2204/3771 3298/3086/4687 3297/1776/3377 +f 2437/3811/5677 2519/3812/5678 2438/2671/4243 +f 1856/3813/5679 1852/2576/5651 2011/2270/5680 +f 3813/3286/4930 3819/3392/5046 3812/3568/4052 +f 1814/1695/5142 1969/2578/5462 1972/2577/5141 +f 2778/3814/5681 2783/1857/5682 2809/2704/4579 +f 3501/3272/4282 3494/2709/4282 3496/3085/4282 +f 3976/3092/3512 3975/1934/3512 3969/1936/3512 +f 2648/3243/4885 2663/3815/5683 2566/3816/5684 +f 3328/3206/4838 3322/3560/5259 3436/3552/5250 +f 3269/3179/4808 3281/2825/5685 3280/2824/4809 +f 3043/2796/4365 3042/2296/3853 3024/3075/4670 +f 2266/3817/5686 2267/2730/4303 2264/3633/5687 +f 3031/3595/5296 3066/2938/4521 3065/3596/5297 +f 3755/2996/4588 3767/3779/5688 3766/2997/4589 +f 2544/3706/5474 2546/3818/5689 2553/3126/4736 +f 2914/3375/5021 2915/1876/3472 2894/1878/3474 +f 2859/3034/4922 2860/2806/4375 2882/2805/4374 +f 3165/3304/5178 3137/3763/5690 3166/3305/4950 +f 3344/2813/4990 3369/3302/5691 3343/3819/5692 +f 3493/2708/4657 3492/2880/4454 3494/2709/5693 +f 3087/3820/5694 3092/2957/4543 3193/3821/5695 +f 2668/3435/5104 2658/3058/4654 2481/3018/4614 +f 3500/2545/3815 3491/2881/3815 3493/2708/3815 +f 2190/3424/5085 2189/3520/5215 2199/2047/3626 +f 2871/2167/3740 2873/2904/5696 2874/3494/5274 +f 3077/1970/3713 3078/2838/3713 3079/2503/3713 +f 2613/3822/5697 2617/1888/3482 2618/3342/4982 +f 3532/2262/3826 3534/3423/5084 3533/1741/3342 +f 1747/1905/3500 1746/3104/4706 1758/1903/3498 +f 3084/2280/3843 3189/1895/3489 3190/2840/4412 +f 2884/2804/5698 2886/3640/5699 2883/3325/5700 +f 3798/3671/5412 3800/3037/4631 3699/2866/5701 +f 3372/2028/3281 3374/2027/3281 3375/1806/3281 +f 2082/2535/4094 2093/2537/4096 1996/2820/4387 +f 3726/3660/5702 3728/3659/5703 3710/3412/5704 +f 3181/2247/3811 3180/3348/4995 3164/2861/4994 +f 1667/2737/4311 1671/3433/5096 1773/3150/4771 +f 2442/3145/4766 2643/3823/5705 2644/3146/4767 +f 2464/3726/5514 2640/1995/3582 2399/3824/5706 +f 2939/2275/3835 2938/3784/5628 2937/2765/4338 +f 2682/3825/5707 2686/3826/5708 2687/2026/3606 +f 2102/3738/5536 2101/3490/5182 2100/3737/5535 +f 3082/1703/5709 3201/3798/5709 3091/3336/5709 +f 2658/3058/4654 2482/1689/5710 2481/3018/4614 +f 2026/2102/3680 2155/2436/4000 2153/3827/5711 +f 3207/1724/3327 3287/3710/5712 3288/1722/3325 +f 3132/3714/3730 3137/3763/3730 3107/1958/3730 +f 2086/3011/4607 2094/2985/4573 2084/1831/3427 +f 3268/2203/3770 3266/3407/5392 3284/2204/3771 +f 3749/2993/4581 3751/3256/3827 3742/3374/5072 +f 3784/2218/3784 3783/2871/4445 3785/2219/3785 +f 2102/3738/5536 2087/2971/4557 2085/3828/5713 +f 3545/2602/4169 3448/1971/5714 3548/2600/4167 +f 3448/1971/5714 3549/3829/5715 3548/2600/4167 +f 2825/3830/5716 2792/3371/5015 2824/3160/4782 +f 3828/3130/4740 3829/3787/3289 3826/2936/3289 +f 3639/1793/5377 3625/1680/3290 3624/2777/4348 +f 2846/2144/3718 2950/2054/3718 2952/3593/3718 +f 3322/3560/5259 3394/2828/4398 3436/3552/5250 +f 2545/3178/5717 2312/3831/5718 2544/3706/5719 +f 2729/2705/4279 2811/3159/4781 2810/2703/4277 +f 2524/2877/5720 2526/2876/5437 2525/3681/5436 +f 1717/2562/5599 1718/2208/5721 1719/2563/4874 +f 3414/3805/5666 3334/2163/3735 3400/1675/3286 +f 3981/3617/5328 3978/3832/5722 4004/2186/5723 +f 3136/2281/4432 3137/3763/5690 3165/3304/5178 +f 3183/3050/4646 3185/3833/5724 3083/2279/3842 +f 3955/3113/5725 3957/3735/5529 3939/1920/3513 +f 2516/3222/4857 2521/3027/5726 2518/3026/5434 +f 2535/2676/4248 2455/2678/4250 2533/2762/4335 +f 3572/2844/4416 3568/3421/5082 3667/2843/4415 +f 3520/1763/3364 3521/1740/5727 3510/2068/3646 +f 3220/3834/3699 3221/2242/3699 3223/3380/3699 +f 2955/2009/3631 2954/2052/3631 2950/2054/3631 +f 3431/2780/4351 3432/2107/3685 3388/1745/3346 +f 2085/3828/5713 2086/3011/4607 2084/1831/3427 +f 2539/3291/4935 2541/2763/4336 2570/2371/3934 +f 4022/3199/4830 4021/2105/3683 4020/3835/5728 +f 3792/3005/4601 3793/1773/3374 3692/1708/3314 +f 3300/3836/5729 3298/3086/4687 3285/2416/4686 +f 3158/2746/5730 3159/2148/3719 3172/3791/5639 +f 3832/2901/3288 3862/2935/3288 3864/1808/3289 +f 3981/3617/3512 3983/2466/3512 3952/2327/3512 +f 3511/3274/4915 3498/3273/5731 3503/3385/5035 +f 2329/2419/5732 2559/3346/4989 2331/2981/5733 +f 3696/1811/5734 3803/1810/5734 3801/3444/5734 +f 3178/3837/5735 3180/3348/4995 3179/3333/4975 +f 3788/2056/3633 3787/2055/3632 3781/1759/3360 +f 3641/1681/3291 3642/2789/4358 3622/1682/3292 +f 2074/2528/4087 2180/2286/3846 1961/3070/4665 +f 2975/2742/4317 2974/1687/5645 2988/3643/5370 +f 2368/2568/4127 2369/1768/3369 2367/1770/3371 +f 3196/3799/5736 3081/1701/5736 3089/2634/5736 +f 3400/1675/3286 3387/2198/4643 3399/3300/5737 +f 3604/3416/5551 3603/2000/3736 3584/2165/3738 +f 2557/3838/5738 2335/3066/5739 2558/3345/4987 +f 3022/2119/3698 3034/1803/3402 3033/2117/3696 +f 2698/3553/5251 2697/3409/5070 2696/2972/4558 +f 2206/3470/5151 2203/3839/5740 2196/3773/5614 +f 3898/1984/3571 3890/3518/5213 3899/2988/4576 +f 2498/3012/5424 2497/3202/5420 2496/3675/5419 +f 2356/3601/5303 2370/2717/4290 2357/2718/4291 +f 2964/3755/3713 2969/3564/3713 2971/3448/5119 +f 3882/3340/4980 3881/3719/5496 3871/2565/5741 +f 3010/3446/3296 3008/3128/3296 3017/2118/3296 +f 3985/3062/5568 3999/3100/5567 3998/3743/5553 +f 2591/3134/4744 2618/3342/4982 2617/1888/3482 +f 2004/3780/5625 2005/3840/5742 1825/2621/5743 +f 2321/2931/4513 2320/3841/5744 2548/2932/4514 +f 3699/2866/3313 3693/1812/3313 3696/1811/5745 +f 1700/2397/3962 1699/2396/3961 1701/3842/5746 +f 2605/3318/4961 2609/3695/5458 2604/3696/5459 +f 2254/2604/4171 2255/3843/5747 2252/2605/4172 +f 3880/1848/5054 3881/3719/5496 3913/3445/5117 +f 3157/2747/5416 3171/3844/5748 3170/3674/5417 +f 3016/2348/3905 3028/3707/5749 3046/3845/5750 +f 3563/3309/5237 3446/2817/5237 3449/3098/5238 +f 2720/2112/3691 2505/3142/5519 2508/2113/3692 +f 3232/3481/5165 3235/3846/5751 3233/3480/5163 +f 3831/3847/5752 3861/3848/5753 3862/2935/5369 +f 2039/3740/5542 2038/3849/5754 2075/2649/4218 +f 3025/3387/5755 3040/3276/4917 3039/2381/3946 +f 2546/3818/5689 2547/3381/5027 2553/3126/4736 +f 3608/2433/4494 3606/2124/5550 3585/3728/5552 +f 2836/2998/3464 2835/3190/3464 2833/3629/3464 +f 3406/1746/3347 3426/1855/3453 3427/1747/3348 +f 3558/2608/4175 3517/3850/5756 3516/2609/4176 +f 2250/3851/5757 2251/3505/5200 2237/3504/5199 +f 2217/3852/5758 2066/2887/4463 2218/2886/4462 +f 2801/3357/5008 2791/2687/4259 2790/3293/4937 +f 3868/1683/3293 3864/1808/3407 3894/1684/3294 +f 1766/2033/3611 1765/2035/3613 1764/3650/5381 +f 2911/3395/5051 2942/3394/5050 2943/3853/5759 +f 2192/3426/5087 2188/3600/5302 2189/3520/5215 +f 2548/2932/4735 2549/3854/5760 2550/3177/4806 +f 2681/1942/3531 2701/2774/4345 2436/1819/3415 +f 2111/2648/4217 2039/3740/5542 2075/2649/4218 +f 2005/3840/5761 2004/3780/5762 2000/3855/5763 +f 2219/3430/5092 2070/2520/4461 1951/2519/4757 +f 3218/2384/3949 3230/2383/3948 3219/3802/5661 +f 2895/3205/3725 2899/3204/3725 2892/3440/3725 +f 3914/3720/5497 3819/3392/5046 3913/3445/5117 +f 1689/1932/3775 1680/1931/5764 1721/3137/4747 +f 2930/2088/3667 2850/2087/3666 2931/3856/5765 +f 3736/3857/5766 3739/2031/3609 3738/2030/3608 +f 2486/3644/5767 2485/3703/5469 2271/1899/3493 +f 1785/2751/4793 1676/1881/4793 1669/2693/4793 +f 1898/3148/4769 1897/3589/5290 1938/2672/4244 +f 1775/3314/4957 1757/3316/4959 1742/2358/3916 +f 1703/2493/3525 1738/2495/3525 1700/2397/3525 +f 3527/2976/4562 3528/3383/5033 3504/2977/4563 +f 3485/3215/5768 3463/3299/4945 3464/2251/4012 +f 2834/3858/5769 2833/3629/5769 2726/3401/5769 +f 2850/2087/3666 2848/2923/4499 2931/3856/5765 +f 3628/3485/5175 3645/2184/3755 3629/2152/3723 +f 3628/3485/3280 3629/2152/3280 3607/2123/3280 +f 2592/2398/3963 2584/3693/5453 2585/2190/3761 +f 1726/2454/4124 1727/2013/4124 1717/2562/3525 +f 2437/3811/5677 2702/3859/5770 2520/3860/5771 +f 1799/2770/4344 1800/3528/5224 1802/3193/4823 +f 2297/2376/3941 2298/2375/3940 2296/3861/5772 +f 4027/3351/4998 3925/2090/3669 4025/2104/3682 +f 3413/3301/4947 3411/3443/5116 3412/3583/5282 +f 3129/2905/5773 3131/2716/5774 3130/1957/5775 +f 2124/3322/4965 2152/2252/3816 2150/2480/4044 +f 3721/1947/5776 3722/2450/5036 3724/2452/5777 +f 3131/2716/3730 3132/3714/3730 3107/1958/3730 +f 1713/3622/5778 1688/2209/3777 1716/3768/5779 +f 3695/3055/4651 3700/2057/3634 3788/2056/3633 +f 2899/3204/4836 2908/2138/3714 2909/3417/5076 +f 3610/2434/3998 3612/1737/5780 3609/2432/3996 +f 3661/1978/3565 3656/2758/4331 3576/3797/5781 +f 3544/3708/5477 3528/3383/5782 3527/2976/4562 +f 2706/2674/4246 2523/3862/5783 2527/2675/4247 +f 2748/3366/5784 2770/3479/5785 2767/2538/5786 +f 2534/3257/5232 2542/3863/5787 2300/2377/5233 +f 1746/3104/4706 1747/1905/3500 1736/2146/4707 +f 3461/2722/4295 3462/2346/3903 3479/3646/5788 +f 2145/3576/5272 2144/1734/3337 2110/3468/5149 +f 3171/3844/5748 3172/3791/5639 3174/3772/5613 +f 3118/2178/5593 3115/2549/4108 3116/2551/4110 +f 1731/3804/3525 1730/2513/3525 1695/2664/3525 +f 1708/2176/5789 1706/2175/5790 1685/2589/4156 +f 4032/1872/3468 3989/3093/5668 4033/3808/5670 +f 3621/1780/3381 3626/3522/5791 3655/1712/4135 +f 1871/3864/5792 1865/2688/4260 1870/2690/4262 +f 1963/2285/3845 1964/2468/5793 1961/3070/4665 +f 3327/2162/5794 3331/2161/5794 3441/3865/5794 +f 2703/2875/2635 2704/3866/2635 2429/3867/5795 +f 2203/3839/5740 2122/3647/5376 2198/2048/3627 +f 2706/2674/2634 2431/3868/2634 2430/3869/2634 +f 3503/3385/3815 3467/3556/4282 3470/3795/3815 +f 3361/2199/5796 3358/2554/4114 3359/3665/5451 +f 2710/3870/5797 2433/3871/5797 2432/3872/5797 +f 2432/3872/2635 2711/3873/2635 2712/3025/2635 +f 3837/3874/5798 3839/1950/5799 3825/3592/5520 +f 2711/3873/5800 2434/3875/5800 2713/3876/5800 +f 3589/3161/5801 3581/3187/4817 3590/3186/4816 +f 2715/2111/2634 2426/3167/2634 2425/3877/2634 +f 2917/1960/5802 2925/2591/4158 2926/3653/5385 +f 3331/2161/5803 3323/3574/5803 3440/3573/5803 +f 2861/3488/5662 2891/1964/3553 2889/3482/5804 +f 3078/2838/5263 2969/3564/5263 3079/2503/5805 +f 3125/3685/4791 3124/2543/4791 3122/1802/5806 +f 2993/2944/5807 2994/1799/3398 2976/1688/3397 +f 2463/2524/4083 2390/3878/5808 2391/3879/5809 +f 2970/3099/5500 3074/2507/4067 3049/2506/4066 +f 2716/3801/5653 2513/2224/5810 2515/2532/4091 +f 2449/2668/4240 2599/2233/3799 2665/2916/4489 +f 3908/1883/3477 3906/1882/3476 3905/3880/5811 +f 2768/2539/4098 2767/2538/4097 2769/3729/5549 +f 2348/2309/3866 2462/3881/5812 2349/3577/5813 +f 2713/3876/5814 2714/2534/4093 2517/2533/4092 +f 3008/3128/4738 3009/2793/5143 3007/3882/5815 +f 2578/3298/4944 2580/2188/3759 2584/3693/5453 +f 3174/3772/5613 3095/2422/5816 3171/3844/5748 +f 2043/2485/4507 2046/3469/5817 2230/3883/5818 +f 2670/3884/5819 2704/3866/5820 2524/2877/4450 +f 2524/2877/4450 2704/3866/5820 2703/2875/4448 +f 2535/2676/5821 2534/3257/5232 2297/2376/5234 +f 3297/1776/3377 3294/2316/3874 3296/3192/4822 +f 2172/3563/5262 2177/3519/5214 2171/3885/5822 +f 1968/3021/4851 1965/3471/5823 2180/2286/3846 +f 3573/3255/5321 3688/2182/5322 3689/1944/5321 +f 3230/2383/3948 3233/3480/5824 3219/3802/5661 +f 3571/3420/5080 3575/3334/4976 3678/2896/4473 +f 3988/3658/5397 3987/3162/4786 3972/1935/5825 +f 2522/3886/5826 2709/3887/5827 2710/3870/5828 +f 2709/3887/5827 2522/3886/5826 2708/3888/5829 +f 2708/3888/5829 2522/3886/5826 2523/3862/5783 +f 2119/2627/4196 2117/3158/4780 2123/2517/4076 +f 2216/2890/4467 2209/2684/4256 2210/2683/4255 +f 2189/3520/5215 2190/3424/5085 2192/3426/5087 +f 2666/3250/4896 2449/2668/4240 2665/2916/4489 +f 2687/2026/3606 2700/1820/3416 2699/3410/5071 +f 2785/3339/3454 2790/3293/3454 2765/2220/3454 +f 2372/3196/4827 2371/3602/5304 2355/3194/4825 +f 2421/3889/5830 2422/3890/5830 2423/3891/5830 +f 3046/3845/5831 3028/3707/5475 3063/1788/3388 +f 3874/3428/5515 3873/3427/5513 3890/3518/5832 +f 3048/3367/5014 3049/2506/4066 3037/2248/3814 +f 3954/3112/4717 3951/2328/3884 3952/2327/3883 +f 3403/1924/3518 3402/2740/4314 3408/1874/3470 +f 3879/1849/3446 3878/3506/5833 3867/1679/3447 +f 3090/3229/4866 3084/2280/3843 3190/2840/4412 +f 3176/2338/3895 3161/2337/3894 3162/1755/5834 +f 1943/2995/4586 1996/2820/4387 2093/2537/4096 +f 3953/2967/4553 3955/3113/5725 3939/1920/3513 +f 4042/2212/3780 3933/2214/3780 4043/2910/5835 +f 3923/3285/5395 4039/2853/5836 4040/2852/5395 +f 2536/2677/5837 2535/2676/5821 2297/2376/5234 +f 3159/2148/3939 3158/2746/4321 3145/2745/4320 +f 3627/2361/3280 3593/3892/5005 3596/3770/5005 +f 1976/3893/5838 1947/3211/4843 1977/2065/5305 +f 2598/3321/4964 2597/3311/4955 2595/2231/3797 +f 3474/1778/4297 3460/2249/3926 3461/2722/4295 +f 1742/2358/3916 1743/2324/3880 1726/2454/4016 +f 2974/1687/5645 2986/2585/5644 2988/3643/5370 +f 2010/2501/5510 1850/2575/5652 1848/2645/5839 +f 3866/2310/5840 3867/1679/3447 3878/3506/5833 +f 3990/3807/5841 3976/3092/4694 3991/3459/5130 +f 2888/3610/3725 2890/3483/3725 2898/1923/3725 +f 3065/3596/5297 2965/2136/5842 3064/1789/3389 +f 2114/2471/4035 2141/2470/4034 2127/3894/5843 +f 3874/3428/5515 3890/3518/5832 3889/3727/5516 +f 2536/2677/5837 2297/2376/5234 2292/3544/5844 +f 3707/3110/5072 3708/1948/4581 3709/3434/5072 +f 3200/3895/5773 3094/2424/5773 3091/3336/5773 +f 2538/3240/4881 2537/3896/5845 2299/3241/4882 +f 3385/1674/3281 3353/3897/3281 3355/2063/3281 +f 3972/1935/5825 3975/1934/4693 3988/3658/5397 +f 2547/3381/5846 2308/3566/5847 2306/2592/5848 +f 2722/2909/5849 2499/3676/5850 2500/3677/5851 +f 2310/3567/5852 2308/3566/5847 2547/3381/5846 +f 2311/3898/5853 2544/3706/5719 2303/3899/5854 +f 2303/3899/5854 2544/3706/5719 2312/3831/5718 +f 1931/2289/3849 1987/2288/3848 2212/3900/5855 +f 2010/2501/5510 2008/3800/5650 1850/2575/5652 +f 2615/2662/4235 2616/2525/4084 2463/2524/4083 +f 2315/3231/5589 2550/3177/5588 2549/3854/5856 +f 2315/3231/5589 2549/3854/5856 2317/1817/5857 +f 2549/3854/5856 2318/1818/5858 2317/1817/5857 +f 2174/1791/3391 2175/3530/5226 2164/1792/3392 +f 2318/1818/5858 2548/2932/4514 2320/3841/5744 +f 2530/2474/4038 2529/3901/5859 2670/3884/5860 +f 3908/1883/3477 3909/2129/3706 3907/1884/3478 +f 2456/1980/5861 2248/3501/5196 2247/3500/5862 +f 3558/2608/4175 3530/3902/5863 3517/3850/5756 +f 1979/3210/4842 1980/3388/5039 1947/3211/4843 +f 3822/3903/3289 3823/3904/3288 3824/3344/3288 +f 2326/3581/5546 2454/3476/5158 2453/3741/5547 +f 2529/3901/5864 2704/3866/5820 2670/3884/5819 +f 2514/3223/4858 2650/2964/4550 2679/1941/3530 +f 2138/2254/3818 2129/3038/4632 2128/2515/4074 +f 2503/2719/4292 2648/3243/4885 2645/3144/4765 +f 2824/3160/4782 2826/3153/4775 2825/3830/5716 +f 2511/2225/3791 2510/2443/5180 2509/3678/5429 +f 2342/1893/3487 2555/1892/3486 2344/3046/5102 +f 3025/3387/3296 3027/1796/3296 2992/2945/3296 +f 2345/3047/5865 2561/3905/5866 2347/2567/4125 +f 2347/2567/4125 2561/3905/5866 2560/1974/4126 +f 2107/2484/4048 2044/1909/3503 2108/2790/4359 +f 2239/2261/5501 2477/2552/5503 2475/2439/4003 +f 3961/3441/5111 3962/2760/4333 3964/3078/5112 +f 3985/3062/3512 3984/3790/3512 3956/3063/3512 +f 2592/2398/3963 2583/2831/4402 2584/3693/5453 +f 3377/3531/5227 3391/2559/4119 3392/3087/4688 +f 2666/3250/4896 2655/3244/4886 2660/3059/4655 +f 4004/2186/3757 4005/3198/4829 4019/2187/3758 +f 2243/2441/4005 2474/2440/4004 2247/3500/5862 +f 3123/3906/3730 3120/2177/3730 3139/3486/3730 +f 2247/3500/5862 2457/1981/5867 2456/1980/5861 +f 2248/3501/5196 2480/3907/5868 2246/3503/5198 +f 2789/2785/4356 2804/2784/4355 2805/2715/4288 +f 1794/2333/4121 1793/2278/4122 1792/2561/4122 +f 3895/2414/3980 3820/3226/4862 3916/2469/4032 +f 1751/1885/3479 1750/3090/4691 1764/3650/5381 +f 2929/3908/5869 2927/2089/3668 2930/2088/3667 +f 2087/2971/4557 2086/3011/4607 2085/3828/5713 +f 1991/1930/3524 1904/2651/4220 1990/1694/3302 +f 2478/3019/5870 2251/3505/5871 2250/3851/5872 +f 3830/3909/5873 3829/3787/5631 3855/3910/5874 +f 3407/1992/3579 3390/1991/3578 3389/1807/5378 +f 2037/2448/4013 2233/2235/4015 2234/2234/5032 +f 2872/2154/3741 2869/3582/5487 2870/2166/3739 +f 2516/3222/4857 2685/3911/5875 2519/3812/5678 +f 1975/2756/4329 2071/3603/5306 1974/2754/4327 +f 3391/2559/4119 3433/1993/3580 3434/2106/3684 +f 2275/2729/4302 2488/3543/5876 2267/2730/5877 +f 2490/3912/5878 2275/2729/4302 2273/3525/5220 +f 2189/3520/5215 2188/3600/5302 2166/3913/5879 +f 3024/3075/3296 3023/3074/3296 2989/3722/3296 +f 2995/3914/5880 2997/1751/3352 2996/2928/5455 +f 1671/3433/5096 1667/2737/4311 1665/3031/3475 +f 3207/1724/3327 3211/1760/5345 3301/3785/5629 +f 2277/3154/4776 2491/3156/4778 2279/3203/4835 +f 3813/3286/4930 3812/3568/4052 3807/3287/4051 +f 3862/2935/5369 3832/2901/5881 3831/3847/5752 +f 3340/1786/3281 3339/3169/4381 3338/1668/3281 +f 3849/2388/3289 3870/3692/3289 3852/2659/3289 +f 3370/2320/3281 3372/2028/3281 3378/3557/3281 +f 2039/3740/5542 2111/2648/4217 2108/2790/4359 +f 3095/2422/5816 3170/3674/5417 3171/3844/5748 +f 3654/3228/4864 3655/1712/3318 3626/3522/5217 +f 3631/2950/5176 3643/3915/5882 3644/2290/5174 +f 2811/3159/5883 2792/3371/5015 2779/3760/5587 +f 2926/3653/5385 2854/3916/5884 2927/2089/3668 +f 1675/3064/3475 1679/1880/3475 1673/1879/3475 +f 1709/2147/3525 1736/2146/3525 1707/2726/3525 +f 3416/3353/5001 3329/3352/5000 3330/3431/5333 +f 3311/1861/3457 3310/2126/3703 3312/2322/3878 +f 2979/2792/3296 2972/3391/3296 2976/1688/3296 +f 3016/2348/3296 3020/2350/3296 2982/3402/3296 +f 3614/1738/3280 3616/3224/3280 3625/1680/3280 +f 3273/3119/5885 3274/2867/4441 3305/1829/3425 +f 1684/1933/4597 1701/3842/5886 1699/2396/4598 +f 1735/1887/5887 1738/2495/4511 1749/3917/5888 +f 3535/3165/4789 3522/1739/3340 3534/3423/5084 +f 3861/3848/5889 3831/3847/5890 3822/3903/5891 +f 3505/2772/3815 3509/2069/3815 3483/2654/3815 +f 3075/1968/3557 2956/2137/3557 2963/1969/3557 +f 2483/1690/3298 2261/3510/5372 2258/3662/5574 +f 3831/3847/5890 3833/3918/5892 3823/3904/5893 +f 3810/3569/4052 3820/3226/4052 3817/2488/4052 +f 2475/2439/4111 2416/3757/5577 2473/2872/4447 +f 2830/3724/5506 2831/3919/5894 2797/2011/3593 +f 2620/2114/3693 2631/3920/5895 2621/2663/4236 +f 3585/3728/5552 3604/3416/5551 3584/2165/3738 +f 1718/2208/5721 1720/3136/4875 1719/2563/4874 +f 3181/2247/3811 3182/3921/5896 3183/3050/4646 +f 1722/3237/4876 1721/3137/5897 1723/2656/4227 +f 2607/2399/3964 2592/2398/3963 2585/2190/3761 +f 2450/3450/5121 2667/3249/4895 2668/3435/5104 +f 3658/3686/5443 3659/3783/5627 3649/3771/5898 +f 3854/2566/3289 3865/3657/3289 3856/3751/3289 +f 3092/2957/4543 3087/3820/5694 3088/3534/4865 +f 3838/3094/3288 3835/2017/3289 3869/2174/3288 +f 3402/2740/4314 3416/3353/5001 3417/1875/3471 +f 3580/2210/3533 3577/2183/3533 3578/2211/4664 +f 2463/2524/4083 2391/3879/5809 2392/3007/4603 +f 4005/3198/4829 4006/2059/4148 4023/2584/4150 +f 1846/2644/5508 1844/3667/5899 2006/2502/5509 +f 3574/3335/4977 3644/2290/3850 3643/3915/5900 +f 3554/2458/4020 3514/2460/4022 3553/2542/4101 +f 2012/2269/3830 2013/2401/3966 2015/3467/5148 +f 2015/3467/5148 2011/2270/3831 2012/2269/3830 +f 3827/3131/4741 3847/2694/5901 3848/2387/4742 +f 3167/2159/3732 3154/2158/3731 3155/2329/3885 +f 3722/2450/5036 3721/1947/5776 3720/1946/4523 +f 2285/3080/5902 2528/2473/5902 2286/3540/5902 +f 2407/3922/5903 2368/2568/4127 2406/3923/5904 +f 3444/1835/3558 3451/1972/3559 3452/3614/3559 +f 3358/2554/3281 3361/2199/3281 3387/2198/3281 +f 3426/1855/3453 3425/2086/3664 3429/1853/3451 +f 3697/1772/3315 3699/2866/3313 3696/1811/5745 +f 2204/2849/4422 2141/2470/4034 2115/2472/4036 +f 2886/3640/5367 2888/3610/3725 2897/1922/3725 +f 3944/2390/4941 3947/3297/4943 3946/2391/5430 +f 3957/3735/5905 3955/3113/4718 3956/3063/4763 +f 2455/2678/4250 2536/2677/4249 2671/2092/3671 +f 2837/2999/3501 2838/3219/3501 2734/3133/3501 +f 3549/3829/5715 3551/2075/3653 3550/3188/4818 +f 1727/2013/4124 1715/3756/3525 1717/2562/3525 +f 2996/2928/4504 2998/1753/5906 2977/1798/3396 +f 3539/2023/3603 3453/2037/3615 3541/2021/3601 +f 2921/3029/4625 2920/2142/5907 2932/2922/4498 +f 2139/2253/3817 2129/3038/4632 2138/2254/3818 +f 3621/1780/3280 3618/3705/3280 3620/2140/3280 +f 3471/3924/5908 3469/2367/3927 3460/2249/3926 +f 3648/3451/5122 3635/3411/5611 3634/2151/3722 +f 4021/2105/3683 4025/2104/3682 3929/2511/4071 +f 1825/2621/4190 1838/2625/4194 1824/3546/5244 +f 2873/2904/5696 2875/2903/5273 2874/3494/5274 +f 1687/2355/3525 1686/2354/3525 1684/1933/3525 +f 3920/3570/5909 3817/2488/5909 3921/3925/5909 +f 1699/2396/4598 1698/2395/5910 1683/3002/4596 +f 2614/2947/4534 2615/2662/4235 2386/2948/4535 +f 3508/3507/4282 3475/1777/4282 3478/2307/4282 +f 3238/3053/4649 3241/3079/4674 3240/2240/5911 +f 1825/2621/5743 1833/2618/5912 2004/3780/5625 +f 3381/3926/5913 3395/3559/5914 3396/3558/5449 +f 3735/3927/5915 3734/3536/5916 3737/3928/5917 +f 3702/3746/5561 3700/2057/3634 3701/2453/3313 +f 3254/2917/5049 3223/3380/5026 3252/2429/5025 +f 3815/2487/5918 3808/3405/5919 3918/3267/5919 +f 2876/1726/5920 2875/2903/4478 2858/2902/4477 +f 3678/2896/4473 3679/2788/4357 3677/2496/4056 +f 3091/3336/3841 3086/2246/3810 3082/1703/3841 +f 3642/2789/4358 3643/3915/5900 3630/3929/5921 +f 2990/2743/4850 2988/3643/5922 2989/3722/5504 +f 1678/3689/5446 1668/2692/4844 1780/3213/4846 +f 3871/2565/5741 3872/2564/5388 3882/3340/4980 +f 3443/2317/5602 3560/3930/5602 3562/3539/5602 +f 3705/3535/5923 3714/1744/3345 3744/2642/5924 +f 2466/3042/4636 2459/3044/4638 2403/3931/5925 +f 2686/3826/5708 2680/1940/3529 2436/1819/3415 +f 2705/3732/5522 2529/3901/5864 2528/2473/4676 +f 2816/2548/4107 2801/3357/5008 2800/3176/4805 +f 3932/3041/4635 3931/2195/4425 3926/2213/4425 +f 2189/3520/5215 2166/3913/5879 2178/3521/5216 +f 3215/1939/3528 3293/1938/3527 3294/2316/3874 +f 3635/3411/3280 3633/1666/3280 3600/1665/3280 +f 3045/2349/3930 3046/3845/5831 3063/1788/3388 +f 2657/2072/3650 2656/3060/4656 2655/3244/4886 +f 1940/2927/4503 2026/2102/3680 2028/3484/5169 +f 2650/2964/4550 2651/2965/4551 2652/1989/3576 +f 2822/2741/4316 2739/3140/4752 2737/3932/5926 +f 2048/3264/5043 2142/1736/5927 2109/1998/5041 +f 2715/2111/2635 2425/3877/2635 2427/1952/3540 +f 1779/1721/3324 1678/3689/5446 1780/3213/4846 +f 3938/2966/4552 3951/2328/5928 3953/2967/4553 +f 3536/3166/4790 3538/2036/3614 3537/3933/5929 +f 2673/2091/3670 2672/3456/5127 2675/3235/4872 +f 2560/1974/4126 2564/1973/3864 2348/2309/3866 +f 3945/3296/4942 3944/2390/4941 3943/2827/4396 +f 2837/2999/3464 2836/2998/3464 2833/3629/3464 +f 3318/3934/3993 3214/2319/3993 3212/3711/3993 +f 3273/3119/4725 3272/3748/5930 3260/3636/5359 +f 2494/3634/5354 2267/2730/5877 2488/3543/5876 +f 3980/3312/3512 3964/3078/3512 3962/2760/3512 +f 3637/1781/4878 3636/2437/4001 3671/3935/5931 +f 3994/1840/3437 3995/3936/5932 3931/2195/3766 +f 3839/1950/3538 3837/3874/5933 3838/3094/4696 +f 1940/2927/4503 2156/2435/3999 2026/2102/3680 +f 2756/2194/5934 2754/3937/5935 2743/3938/5936 +f 2744/3623/3454 2743/3938/5937 2742/3265/3454 +f 3838/3094/4696 3837/3874/5933 3836/2015/3597 +f 3400/1675/3286 3413/3301/4947 3414/3805/5666 +f 2663/3815/5683 2503/2719/4292 2662/3275/4916 +f 3740/2032/4582 3749/2993/4581 3742/3374/5072 +f 3018/3373/5018 3017/2118/3697 3031/3595/5366 +f 2999/3221/4856 3000/1752/3353 3001/2895/4472 +f 2969/3564/5938 2964/3755/5938 3080/2504/5938 +f 3985/3062/5568 3982/3061/5939 4000/3101/5569 +f 3860/1677/3288 3866/2310/3288 3863/2428/3289 +f 3317/3294/4939 3206/3295/4939 3214/2319/4939 +f 2918/1961/5384 2917/1960/5802 2926/3653/5385 +f 2841/3498/5193 2842/3377/4761 2840/2096/3631 +f 2609/3695/5458 2608/3723/5505 2603/2405/3970 +f 3803/1810/3313 3804/3358/3313 3805/2512/3313 +f 3039/2381/5940 3038/2943/4528 3027/1796/3813 +f 3140/3716/3730 3125/3685/3730 3123/3906/3730 +f 2015/3467/5534 1855/2521/5941 1854/3939/5942 +f 2876/1726/3329 2877/1725/3328 2874/3494/5274 +f 3458/2810/4379 3459/2250/3928 3466/2808/4377 +f 3118/2178/3730 3116/2551/3730 3145/2745/3730 +f 2755/1858/3764 2753/3940/5943 2754/3937/5944 +f 2770/3479/5161 2772/1908/3502 2773/1907/3502 +f 3794/2946/4533 3791/3004/4600 3790/2954/4540 +f 3815/2487/5918 3918/3267/5919 3922/3941/5918 +f 3961/3441/5945 3963/3077/5946 3941/1918/4509 +f 4039/2853/5947 3927/3039/5947 4041/2854/5947 +f 2258/3662/5401 2259/3509/5204 2257/3663/5402 +f 1671/3433/5096 1774/3432/5095 1773/3150/4771 +f 3703/3753/5575 3693/1812/3313 3704/2647/3313 +f 3114/2550/4109 3112/3626/5342 3113/3628/5344 +f 2202/3590/5291 2205/2364/3923 2201/3612/5320 +f 1697/3360/5010 1698/2395/3960 1700/2397/3962 +f 2833/3629/3464 2834/3858/3465 2838/3219/3464 +f 3706/3630/5347 3705/3535/5923 3746/3550/5948 +f 3325/3572/5270 3439/3782/5949 3440/3573/5270 +f 1675/3064/4659 1672/2727/4301 1766/2033/3611 +f 2605/3318/4961 2610/3317/4960 2609/3695/5458 +f 1696/3359/5950 1694/3942/5951 1682/3943/5952 +f 3528/3383/5782 3544/3708/5477 3545/2602/4169 +f 3822/3903/5891 3831/3847/5890 3823/3904/5893 +f 3148/1897/3491 3135/2343/3900 3149/2344/5555 +f 3882/3340/4980 3915/3227/4863 3914/3720/5497 +f 1681/3944/5953 1692/3945/5954 1690/2657/5955 +f 2590/1889/3483 2461/1975/3562 2574/2639/4207 +f 1761/3548/5246 1749/3917/5956 1748/2444/4008 +f 3289/3946/5957 3288/1722/5958 3261/2121/5479 +f 2311/3898/5959 2302/3947/5960 2309/3565/5264 +f 3566/2266/3533 3570/2540/5081 3571/3420/5080 +f 2081/1852/3450 2080/2855/4426 2092/1928/3522 +f 3776/3124/5961 3775/1758/3359 3758/2264/5962 +f 3761/3599/3827 3760/2291/3827 3730/3948/3827 +f 3881/3719/5496 3880/1848/3445 3865/3657/5394 +f 3003/2893/3296 3022/2119/3296 3005/3127/3296 +f 3689/1944/3533 3688/2182/3533 3686/1945/3533 +f 2798/2477/4041 2785/3339/5963 2787/3338/4992 +f 1745/1719/3322 1779/1721/3324 1780/3213/4846 +f 1842/2631/4200 1844/3667/5408 1843/2951/4537 +f 2753/3940/5943 2752/1729/3332 2751/3266/5964 +f 4009/2952/4538 3934/3032/4627 3931/2195/3766 +f 3621/1780/3280 3623/1782/5965 3618/3705/3280 +f 2525/3681/5436 2669/2084/3662 2670/3884/5860 +f 3146/3715/5490 3132/3714/5489 3147/3010/4606 +f 1681/3944/5953 1694/3942/5951 1692/3945/5954 +f 3011/3465/5571 2980/2791/4360 3009/2793/4362 +f 3374/2027/3281 3376/3788/3281 3375/1806/3281 +f 2995/3914/3296 2992/2945/3296 3027/1796/3296 +f 1954/2666/4759 1957/3141/4758 1959/2635/5966 +f 3585/3728/5552 3586/2920/4492 3608/2433/4494 +f 2885/3491/5967 2887/3611/5319 2888/3610/5318 +f 3529/3384/5034 3528/3383/5782 3545/2602/4169 +f 3265/1714/3320 3267/3949/5968 3283/1715/3321 +f 1869/2689/5969 1867/3414/5073 2025/3415/5075 +f 3798/3671/5412 3699/2866/5701 3797/1891/3485 +f 2894/1878/3725 2881/2829/3725 2902/3071/3725 +f 3770/2870/5970 3760/2291/5456 3771/2229/5457 +f 2052/1790/3390 2049/2879/4452 2050/2003/3590 +f 3642/2789/4358 3641/1681/4057 3677/2496/4056 +f 2670/3884/5860 2669/2084/3662 2530/2474/4038 +f 2647/1987/3574 2659/1837/3433 2646/2073/3651 +f 1782/2753/3475 1783/3030/3475 1787/2191/3475 +f 2885/3491/5967 2888/3610/5318 2886/3640/5699 +f 2859/3034/4922 2879/2830/4921 2876/1726/5920 +f 3908/1883/3477 3905/3880/5811 3877/1809/5201 +f 3615/3225/4861 3617/3181/5063 3616/3224/4859 +f 2616/2525/4084 2622/2969/4555 2633/3655/5389 +f 3395/3559/5258 3394/2828/4398 3322/3560/5259 +f 3051/3950/5971 2968/2942/4527 3050/1914/3508 +f 3744/2642/5924 3746/3550/5948 3705/3535/5923 +f 3337/1669/5527 3338/1668/5656 3349/3764/5972 +f 3681/2039/3617 3682/3951/5973 3683/2040/3618 +f 3022/2119/3698 3021/3487/5179 3035/1804/3403 +f 2510/2443/4007 2513/2224/5810 2717/3168/5974 +f 2965/2136/5842 3065/3596/5297 3066/2938/4521 +f 3369/3302/5691 3367/3418/5975 3343/3819/5692 +f 3752/3793/3827 3753/2263/3827 3716/3549/3827 +f 2412/3952/5976 2579/3733/5524 2461/1975/3562 +f 2345/3047/4641 2346/3953/5977 2343/3045/4639 +f 1812/2582/4147 1806/3464/5978 1813/1696/3304 +f 2259/3509/5204 2258/3662/5401 2261/3510/5205 +f 2352/3954/5979 2351/1769/3370 2385/3303/4948 +f 3472/3330/5980 3471/3924/5981 3473/3632/5352 +f 3324/3184/4814 3422/2835/4407 3419/2834/4406 +f 3565/1833/3559 3564/3310/5982 3563/3309/3559 +f 2056/3356/5006 2055/1844/3441 2054/3955/5983 +f 2250/3851/5872 2246/3503/5198 2478/3019/5870 +f 2934/2043/3621 2841/3498/5193 2935/2406/3971 +f 2230/3883/2634 1921/3744/2634 1920/3956/2634 +f 2814/1705/3311 2825/3830/5716 2826/3153/4775 +f 1780/3213/4846 1746/3104/4706 1745/1719/3322 +f 2864/1826/3725 2896/3718/3725 2892/3440/3725 +f 1776/3315/4958 1777/2325/3881 1757/3316/4959 +f 3745/2641/3827 3742/3374/5072 3751/3256/3827 +f 3095/2422/3841 3094/2424/3841 3088/3534/4865 +f 2713/3876/3271 2434/3875/3271 2424/3957/2635 +f 3119/2303/5171 3117/3762/5984 3118/2178/5594 +f 1705/2494/4300 1702/2588/5985 1704/2587/5986 +f 2201/3612/5320 1931/2289/3849 2212/3900/5855 +f 3858/1678/3289 3856/3751/3289 3865/3657/3289 +f 3914/3720/5497 3913/3445/5117 3881/3719/5496 +f 3760/2291/5456 3770/2870/5970 3769/2750/4584 +f 3127/3017/4792 3129/2905/5773 3128/2097/5773 +f 3823/3904/5893 3834/2016/4984 3824/3344/4986 +f 1842/2631/5987 1837/2624/5988 2007/3319/5989 +f 2703/2875/4448 2707/2673/4245 2526/2876/4449 +f 3186/3754/5576 3187/3958/5990 3184/2173/3747 +f 1917/3959/5991 1918/3368/2635 2227/3370/2635 +f 1785/2751/5992 1669/2693/5992 1670/3960/5992 +f 2001/3961/5993 2000/3855/5763 1941/2653/5994 +f 1931/2289/3849 2113/2366/3925 1930/3455/5126 +f 1873/2360/5995 2032/2857/5996 1878/3088/5997 +f 3779/3460/5998 3778/3056/5642 3752/3793/5641 +f 3143/2374/3730 3145/2745/3730 3116/2551/3730 +f 2806/1863/3459 2805/2715/5999 2736/1864/3460 +f 2304/2594/6000 2543/3514/6001 2306/2592/5848 +f 3715/3962/6002 3716/3549/6003 3717/3281/4926 +f 3495/3057/4684 3496/3085/4683 3494/2709/5693 +f 3695/3055/4651 3692/1708/3314 3691/1707/3313 +f 2483/1690/3434 2659/1837/3433 2486/3644/6004 +f 2194/2492/4055 2192/3426/5087 2195/3963/6005 +f 3006/3129/4739 3004/2846/6006 3005/3127/4737 +f 1742/2358/3916 1741/2357/5435 1775/3314/4957 +f 2922/3028/6007 2923/2157/3728 2900/2156/3727 +f 2200/2046/3625 2198/2048/3627 2202/3590/5291 +f 2999/3221/6008 3001/2895/4893 2978/2845/4417 +f 3451/1972/3559 3453/2037/3559 3452/3614/3559 +f 2944/2168/3742 2912/2170/3744 2943/3853/5759 +f 2898/1923/3725 2897/1922/3725 2888/3610/3725 +f 2641/3584/5284 2443/2962/4548 2650/2964/4550 +f 2672/3456/5127 2673/2091/3670 2531/2475/4039 +f 3471/3924/5981 3470/3795/6009 3469/2367/6010 +f 3728/3659/5703 3729/3964/6011 3710/3412/5704 +f 2166/3913/5879 2188/3600/5302 2191/2491/4054 +f 3083/2279/3842 3081/1701/3841 3082/1703/3841 +f 3196/3799/3841 3198/2633/3841 3201/3798/3841 +f 3582/3965/6012 3583/1917/3511 3595/1979/3566 +f 2256/1691/5403 2257/3663/5402 2255/3843/5747 +f 3236/3052/3699 3265/1714/3699 3238/3053/3699 +f 3517/3850/5756 3518/3966/6013 3505/2772/6014 +f 3064/1789/3389 3029/3372/5476 3030/3594/5295 +f 2091/2991/4580 2090/2856/4427 1946/2975/4561 +f 3576/3797/5781 3662/1976/3563 3661/1978/3565 +f 2772/1908/6015 2770/3479/5785 2748/3366/5784 +f 3421/2836/4408 3423/2085/3663 3420/3132/4743 +f 1704/2587/5986 1706/2175/3749 1705/2494/4300 +f 2972/3391/5045 2981/2620/4187 2973/1686/4189 +f 3918/3267/5067 3807/3287/5067 3917/3268/6016 +f 2573/2372/3935 2451/3967/6017 2572/3036/4630 +f 2693/2131/3708 2570/2371/3934 2683/3968/6018 +f 3571/3420/5080 3568/3421/5082 3566/2266/3533 +f 3746/3550/5248 3744/2642/4212 3745/2641/4211 +f 3497/2809/4685 3467/3556/5254 3496/3085/4683 +f 2826/3153/4775 2824/3160/4782 2728/3400/6019 +f 2197/3529/5225 2198/2048/3627 2199/2047/3626 +f 1773/3150/4771 1772/3149/4770 1667/2737/4311 +f 2577/2373/3936 2573/2372/3935 2572/3036/4630 +f 3377/3531/5227 3378/3557/5582 3390/1991/3578 +f 2203/3839/5740 2206/3470/5151 2122/3647/5376 +f 2679/1941/3530 2680/1940/3529 2682/3825/5707 +f 2892/3440/5110 2893/1824/3420 2864/1826/3422 +f 3377/3531/3281 3382/1965/3281 3370/2320/3281 +f 1794/2333/3889 1949/2276/3836 1793/2278/3838 +f 2827/2237/3801 2793/2239/3803 2825/3830/5716 +f 2087/2971/4557 2088/2970/4556 2086/3011/4607 +f 4025/2104/3682 4024/2103/3681 4027/3351/4998 +f 4024/2103/3681 4023/2584/4150 4026/2583/4149 +f 3140/3716/5492 3153/3969/6020 3152/2297/3854 +f 3711/3413/3827 3712/3970/3827 3713/3766/3827 +f 3666/2244/3808 3669/2438/4002 3668/1711/3317 +f 3993/1839/6021 3992/2257/5414 3974/3313/5129 +f 3457/2941/3558 3452/3614/3559 3453/2037/3559 +f 3509/2069/3815 3480/3386/3815 3483/2654/3815 +f 2286/3540/6022 2283/3971/6023 2285/3080/6024 +f 2513/2224/5810 2718/3631/6025 2717/3168/5974 +f 3829/3787/3289 3822/3903/3289 3826/2936/3289 +f 2751/3266/4910 2743/3938/5936 2754/3937/5935 +f 2612/2990/4578 2378/3786/5630 2381/3613/5325 +f 2473/2872/4447 2418/3758/5578 2596/3972/6026 +f 3836/2015/3597 3835/2017/3599 3838/3094/4696 +f 3713/3766/5597 3712/3970/6027 3736/3857/6028 +f 3291/2071/3649 3290/1937/3526 3216/1859/3455 +f 3581/3187/4817 3582/3965/6012 3592/3185/4815 +f 3300/3836/5729 3301/3785/5629 3299/1774/3375 +f 3405/1927/3665 3404/1926/3520 3423/2085/3663 +f 3256/3245/4887 3254/2917/6029 3255/3246/4888 +f 2068/2884/6030 2217/3852/5758 2222/3398/5057 +f 1934/2735/4309 1933/3214/4847 2207/2201/3768 +f 3913/3445/5117 3912/3382/5028 3911/2128/3705 +f 3002/2894/4894 3004/2846/4418 2978/2845/4417 +f 2370/2717/4290 2371/3602/5304 2388/3651/5382 +f 2418/3758/5578 2419/3973/6031 2596/3972/6026 +f 3691/1707/3832 3802/3561/6032 3806/2271/3832 +f 2383/2570/4129 2384/2862/4434 2369/1768/3369 +f 2757/3625/6033 2759/2701/4275 2758/2193/3763 +f 2593/3105/4709 2608/3723/5505 2607/2399/3964 +f 3007/3882/6034 3009/2793/4362 2979/2792/4361 +f 2036/2847/6035 2033/2858/4429 2038/3849/5754 +f 3925/2090/3669 4027/3351/4998 4031/1870/3466 +f 2745/3624/5340 2746/2352/3910 2760/3175/6036 +f 3381/3926/3281 3386/2197/3281 3363/3670/3281 +f 3344/2813/3281 3343/3819/3281 3340/1786/3281 +f 2788/2714/3454 2784/1856/3454 2758/2193/3454 +f 2139/2253/3817 2152/2252/3816 2013/2401/3966 +f 1681/3944/3525 1680/1931/3525 1684/1933/3525 +f 2103/3284/4929 2102/3738/5536 2085/3828/5713 +f 3734/3536/5916 3731/3712/6037 3732/2293/6037 +f 2100/3737/5535 2099/3974/6038 2098/2500/4062 +f 2059/1843/3496 2065/2660/5052 2224/1902/3497 +f 2832/1847/3444 2830/3724/5506 2735/1845/3442 +f 3482/2347/4225 3483/2654/4224 3481/2345/6039 +f 3589/3161/4784 3590/3186/6040 3591/2139/4785 +f 3640/2497/4058 3639/1793/3393 3676/1795/3395 +f 2432/3872/2635 2434/3875/2635 2711/3873/2635 +f 2805/2715/5999 2737/3932/5926 2736/1864/3460 +f 1787/2191/3762 1673/1879/3762 1676/1881/3762 +f 3596/3770/5609 3593/3892/6041 3592/3185/5607 +f 2966/3171/4800 2967/2301/3858 3071/2300/3857 +f 1933/3214/4847 1932/2490/4053 2216/2890/4467 +f 3318/3934/6042 3203/1761/6042 3314/3810/6043 +f 2756/2194/3765 2757/3625/6033 2758/2193/3763 +f 3445/2076/3654 3450/2318/3875 3552/2077/3655 +f 2311/3898/5959 2303/3899/6044 2302/3947/5960 +f 2710/3870/3275 2708/3888/2635 2706/2674/2635 +f 3112/3626/5605 3114/2550/6045 3100/2802/5603 +f 2290/2700/6046 2289/1700/6047 2287/1699/6046 +f 3736/3857/6028 3738/2030/6048 3713/3766/5597 +f 3017/2118/3697 3032/3118/6049 3031/3595/5366 +f 1767/2034/3612 1768/2078/3656 1769/2216/3782 +f 2082/2535/4094 1996/2820/4387 2090/2856/4427 +f 2157/3975/6050 2074/2528/4087 2067/2883/4458 +f 1982/3745/5556 1983/3976/6051 1947/3211/4843 +f 2083/1830/3426 2106/2080/3658 2130/2079/3657 +f 3464/2251/3815 3463/3299/4945 3462/2346/3903 +f 2614/2947/4534 2618/3342/4982 2619/2115/3694 +f 2782/3680/3454 2775/2196/3454 2777/1730/3454 +f 1769/2216/3782 1755/2581/4970 1754/2215/3781 +f 3195/2331/3887 3194/2160/3733 3167/2159/3732 +f 3033/2117/3696 3032/3118/6049 3017/2118/3697 +f 3988/3658/5397 3989/3093/5668 4032/1872/3468 +f 1697/3360/3525 1731/3804/3525 1695/2664/3525 +f 3059/3533/5230 3060/3977/6052 3061/2394/3959 +f 2933/2042/3620 2924/2041/3619 2923/2157/6053 +f 3992/2257/3821 3993/1839/3436 4036/2255/3819 +f 2668/3435/5104 2596/3972/6026 2450/3450/5121 +f 2037/2448/6054 2038/3849/5754 2039/3740/5542 +f 2937/2765/4338 2936/3978/6055 2847/2764/4337 +f 2652/1989/3576 2599/2233/3799 2594/2232/3798 +f 2723/3635/5356 2722/2909/5849 2500/3677/5851 +f 3759/2451/5301 3757/3979/6056 3774/1757/3358 +f 3422/2835/4407 3324/3184/4814 3424/3980/6057 +f 1744/1720/3323 1778/2323/3879 1779/1721/3324 +f 1714/3621/5335 1712/3981/6058 1711/2353/5336 +f 3385/1674/3281 3384/1841/3281 3353/3897/3281 +f 1754/2215/4144 1730/2513/4146 1731/3804/5665 +f 2353/3982/6059 2385/3303/4948 2372/3196/4827 +f 3039/2381/5940 3027/1796/3813 3025/3387/6060 +f 3448/1971/5714 3445/2076/3654 3549/3829/5715 +f 3193/3821/5695 3153/3969/6061 3194/2160/3733 +f 2594/2232/3798 2448/3035/4629 2571/2775/4346 +f 2882/2805/5093 2883/3325/5700 2881/2829/4400 +f 3453/2037/3615 3538/2036/3614 3457/2941/5374 +f 3588/3182/3280 3586/2920/3280 3584/2165/3280 +f 3647/3452/5558 3646/2153/3724 3657/2038/3616 +f 3579/3069/5442 3576/3797/5781 3659/3783/5627 +f 3356/2555/4796 3339/3169/4795 3357/3478/6062 +f 3866/2310/6063 3878/3506/5202 3877/1809/5201 +f 3616/3224/3280 3624/2777/5965 3625/1680/3280 +f 1853/2523/6064 1851/2574/4137 1852/2576/4139 +f 2439/2082/3660 2525/3681/5436 2523/3862/6065 +f 2747/2351/3908 2748/3366/5784 2767/2538/5786 +f 3799/3672/5413 3798/3671/5412 3767/3779/5622 +f 2654/3404/5066 2653/1988/3575 2440/3524/5219 +f 3805/2512/4073 3698/2272/4073 3806/2271/4073 +f 3928/3040/4634 3925/2090/3669 4032/1872/3468 +f 3959/2759/4332 3958/2067/6066 3957/3735/5905 +f 1826/2612/4571 1821/2779/6067 2002/2984/4572 +f 2635/2798/4367 2596/3972/6026 2403/3931/5925 +f 3752/3793/5641 3777/3794/5643 3753/2263/4731 +f 3019/2007/4366 3043/2796/4365 3024/3075/4670 +f 2858/2902/4477 2859/3034/4922 2876/1726/5920 +f 3405/1927/3521 3406/1746/3347 3379/1925/3519 +f 4017/3143/4764 4018/2913/4486 4015/2313/3869 +f 2428/1953/2635 2723/3635/2635 2721/1954/2635 +f 2135/3283/4928 2101/3490/5182 2103/3284/4929 +f 3701/2453/3313 3693/1812/3313 3703/3753/5575 +f 2568/1986/3573 2647/1987/3574 2567/2386/3951 +f 3809/3288/4931 3909/2129/3706 3912/3382/5028 +f 3559/3122/4729 3447/2818/4385 3532/2262/3826 +f 2900/2156/3725 2896/3718/3725 2864/1826/3725 +f 3344/2813/4990 3371/2029/4990 3369/3302/5691 +f 3164/2861/4433 3163/1754/3355 3138/2860/4431 +f 2681/1942/3531 2436/1819/3415 2680/1940/3529 +f 2985/2006/4151 2987/2005/6068 2986/2585/4152 +f 3282/1713/3319 3281/2825/5685 3270/3457/6069 +f 2496/3675/5419 2499/3676/5421 2502/2921/5425 +f 3547/3796/5647 3548/2600/4167 3550/3188/4818 +f 2130/2079/3657 2131/2081/3659 2134/3121/4728 +f 3677/2496/4056 3640/2497/4058 3676/1795/3395 +f 2867/2571/4593 2868/2573/6070 2869/3582/5487 +f 2491/3156/4778 2495/3201/4833 2279/3203/4835 +f 3931/2195/3766 3995/3936/5932 3996/2953/4539 +f 1924/3378/2635 1880/2725/5991 1881/2724/5991 +f 3966/2341/3512 3976/3092/3512 3969/1936/3512 +f 3789/3003/4599 3790/2954/4540 3791/3004/4600 +f 2940/2274/3834 2942/3394/5050 2910/1921/3514 +f 3178/3837/5735 3176/2338/3895 3162/1755/5834 +f 3341/3254/6071 3362/2958/6072 3360/3664/5404 +f 2643/3823/5705 2442/3145/4766 2511/2225/3791 +f 1860/3684/5440 2021/3736/5532 2020/3554/5252 +f 3696/1811/5734 3801/3444/5734 3690/1709/6073 +f 2232/2929/4505 2233/2235/4015 2041/1910/5673 +f 1984/3608/5312 2181/3983/6074 1985/2781/4352 +f 3597/1916/3545 3599/1915/3839 3600/1665/3546 +f 3098/3984/3730 3099/2801/3730 3101/2603/4170 +f 4029/3985/6075 4031/1870/3466 4027/3351/4998 +f 3086/2246/3810 3093/3331/4973 3179/3333/4975 +f 3568/3421/5082 3572/2844/4416 3567/2267/5470 +f 2192/3426/5087 2194/2492/4055 2191/2491/4054 +f 2977/1798/3396 2999/3221/6008 2978/2845/4417 +f 2897/1922/3725 2903/2833/3725 2886/3640/5367 +f 2551/2930/4512 2552/3477/5159 2324/3458/5128 +f 3509/2069/3647 3518/3966/6013 3519/1764/3365 +f 1749/3917/5888 1750/3090/6076 1735/1887/5887 +f 3181/2247/3811 3165/3304/4949 3182/3921/5896 +f 2541/2763/5787 2540/3290/5657 2300/2377/5233 +f 1817/3429/5100 1818/1749/3350 1811/1748/3349 +f 3835/2017/3599 3834/2016/3598 3833/3918/6077 +f 1740/2135/3712 1739/2051/4772 1773/3150/4771 +f 3626/3522/3280 3591/2139/3280 3593/3892/5005 +f 2791/2687/3454 2789/2785/3454 2761/2702/3454 +f 1713/3622/5778 1687/2355/3913 1688/2209/3777 +f 2774/1906/4906 2772/1908/6015 2749/3365/6078 +f 2180/2286/3846 2074/2528/4087 1935/2530/4089 +f 3656/2758/4331 3660/1733/3336 3576/3797/5781 +f 2950/2054/3631 2951/2094/3631 2955/2009/3631 +f 2637/3682/5439 2636/2799/4368 2635/2798/4367 +f 2389/3620/5334 2377/3606/5310 2376/3605/5309 +f 2776/1728/3331 2751/3266/5964 2752/1729/3332 +f 3393/1966/3555 3392/3087/6079 3435/2560/4120 +f 2067/2883/4458 2069/2885/4460 2061/2670/4242 +f 2799/2476/4040 2812/2478/4042 2832/1847/3444 +f 2946/2169/3743 2948/3280/4925 2947/3376/5023 +f 2861/3488/3725 2860/2806/3725 2859/3034/3725 +f 2902/3071/4666 2913/2832/4403 2914/3375/5021 +f 3761/3599/3827 3730/3948/3827 3727/3661/3827 +f 2373/3604/5308 2377/3606/5310 2389/3620/5334 +f 3002/2894/4471 3003/2893/4470 3005/3127/4737 +f 3326/2108/5212 3321/3183/4813 3319/3517/5212 +f 2025/3415/5075 2024/2926/5098 1869/2689/5969 +f 3123/3906/6080 3121/2304/5170 3120/2177/5172 +f 3824/3344/4986 3837/3874/5798 3825/3592/5520 +f 3290/1937/3526 3291/2071/3649 3292/2070/3648 +f 3925/2090/3669 3928/3040/4634 3923/3285/4425 +f 3816/1983/4051 3814/3986/4051 3815/2487/4051 +f 3906/1882/3476 3907/1884/3478 3811/3437/5106 +f 3461/2722/3815 3460/2249/3815 3464/2251/3815 +f 3379/1925/3281 3345/2888/3281 3347/1815/3281 +f 2454/3476/6081 2552/3477/6082 2553/3126/4736 +f 3723/3987/6083 3725/3988/6084 3709/3434/6085 +f 3649/3771/5898 3648/3451/5557 3658/3686/5443 +f 3271/2228/3794 3272/3748/5563 3303/2226/3792 +f 2706/2674/3274 2707/2673/3274 2431/3868/2635 +f 2012/2269/3830 2009/2268/3829 2136/3489/5181 +f 2706/2674/4246 2708/3888/5829 2523/3862/5783 +f 2746/2352/3910 2762/3668/5409 2760/3175/6036 +f 1736/2146/3525 1737/2445/3525 1707/2726/3525 +f 3193/3821/5695 3152/2297/6086 3153/3969/6061 +f 3363/3670/4544 3360/3664/6087 3362/2958/4544 +f 3610/2434/3998 3611/2109/6088 3612/1737/5780 +f 4031/1870/3466 4029/3985/6075 4028/3792/5640 +f 2576/2973/4559 2578/3298/4944 2574/2639/4207 +f 3884/3654/5386 3872/2564/5388 3870/3692/5452 +f 2376/3605/5309 2380/2949/4536 2386/2948/4535 +f 2790/3293/4937 2800/3176/4938 2801/3357/5008 +f 1848/2645/4216 1850/2575/4138 1849/3615/5326 +f 2929/3908/5869 2928/3652/5383 2927/2089/3668 +f 4033/3808/5670 3928/3040/4634 4032/1872/3468 +f 2988/3643/5922 2986/2585/4152 2987/2005/6068 +f 3838/3094/3288 3873/3427/3288 3841/1951/3288 +f 3100/2802/5603 3115/2549/6089 3101/2603/4170 +f 3956/3063/3512 3954/3112/3512 3982/3061/3512 +f 2810/2703/6090 2811/3159/5883 2778/3814/5681 +f 2913/2832/5022 2912/2170/3744 2946/2169/3743 +f 3872/2564/3289 3854/2566/3289 3852/2659/3289 +f 3525/3289/6091 3507/3329/6092 3524/3438/5350 +f 3900/1985/3572 3901/2987/4575 3902/3989/6093 +f 3714/1744/3345 3743/1743/3344 3744/2642/5924 +f 2907/3259/3725 2905/1962/3725 2872/2154/3725 +f 3220/3834/6094 3239/3990/6095 3240/2240/3804 +f 1961/3070/4665 2180/2286/3846 1963/2285/3845 +f 4031/1870/3466 4028/3792/5640 4030/1871/3467 +f 3276/3172/5494 3275/2868/5088 3259/3120/4726 +f 2312/3831/6096 2302/3947/5960 2303/3899/6044 +f 3452/3614/5559 3454/2899/6097 3564/3310/5560 +f 2429/3867/5795 2431/3868/2635 2703/2875/2635 +f 2843/2924/4500 2842/3377/5024 2922/3028/4624 +f 3480/3386/5037 3479/3646/5375 3481/2345/6039 +f 3225/3725/5530 3227/2699/5029 3218/2384/3949 +f 2121/2365/3924 2119/2627/4196 2132/2628/4197 +f 3990/3807/5669 3991/3459/6098 4033/3808/5670 +f 3701/2453/6099 3804/3358/6099 3693/1812/6099 +f 3922/3941/4051 3918/3267/4051 3919/3269/4051 +f 2633/3655/5389 2445/3648/5379 2446/3687/5444 +f 2522/3886/6100 2702/3859/5770 2437/3811/5677 +f 3064/1789/3389 3030/3594/5295 3065/3596/5297 +f 3323/3574/3734 3331/2161/3734 3333/3571/5269 +f 2180/2286/3846 2071/3603/5306 2183/2934/4516 +f 2009/2268/3829 2011/2270/3831 2008/3800/6101 +f 3730/3948/6102 3729/3964/6103 3728/3659/5398 +f 2126/3991/6104 2145/3576/5272 2146/3323/4966 +f 3489/2447/4011 3487/3208/6105 3464/2251/4012 +f 3146/3715/5490 3186/3754/5576 3184/2173/3747 +f 3978/3832/3512 3981/3617/3512 3950/3679/6106 +f 3017/2118/3296 3008/3128/3296 3005/3127/3296 +f 3429/1853/3451 3431/2780/4351 3428/1854/3452 +f 2559/3346/4989 2333/3068/4988 2331/2981/5733 +f 3898/1984/3571 3821/2489/4753 3897/2599/4166 +f 3555/3239/4880 3556/3992/6107 3557/2607/4174 +f 3646/2153/3724 3645/2184/3755 3681/2039/3617 +f 3125/3685/4791 3122/1802/5806 3123/3906/6080 +f 3665/1710/3316 3666/2244/3808 3668/1711/3317 +f 2979/2792/3296 2980/2791/3296 2972/3391/3296 +f 1705/2494/4300 1703/2493/6108 1702/2588/5985 +f 3936/3993/6109 3942/1919/4508 3970/2826/5584 +f 2553/3126/4736 2575/2370/3933 2453/3741/6110 +f 3258/2120/6111 3257/3761/5591 3271/2228/3794 +f 3797/1891/3485 3795/1771/3372 3780/2527/4086 +f 3968/2045/3623 3967/2339/3896 3969/1936/3624 +f 2132/2628/4197 2131/2081/3659 2113/2366/3925 +f 3934/3032/4627 4009/2952/4538 4011/2378/3943 +f 2321/2931/5471 2319/2961/4547 2320/3841/6112 +f 3101/2603/4170 3103/1800/3730 3105/2098/3730 +f 3183/3050/4646 3182/3921/5896 3184/2173/3747 +f 1762/3091/4692 1760/3547/5245 1679/1880/4658 +f 3066/2938/4521 3032/3118/4723 3067/2425/3988 +f 3911/2128/3705 3880/1848/5054 3913/3445/5117 +f 2209/2684/4256 2216/2890/4467 2214/2892/4469 +f 1875/3994/6113 1876/2848/5586 1879/2723/4298 +f 3445/2076/3654 3444/1835/3558 3443/2317/3559 +f 3038/2943/4528 3039/2381/3946 3050/1914/3508 +f 1723/2656/4227 1691/2305/4229 1722/3237/4876 +f 3494/2709/4282 3501/3272/4282 3502/2710/3815 +f 3021/3487/3296 3022/2119/3296 3003/2893/3296 +f 3757/3979/6056 3775/1758/3359 3774/1757/3358 +f 3570/2540/5081 3569/3683/3533 3575/3334/4976 +f 2857/3597/5298 2870/2166/6114 2868/2573/4132 +f 1765/2035/3613 1751/1885/3479 1764/3650/5381 +f 2245/2259/3823 2239/2261/3825 2244/3497/5192 +f 2730/3123/3464 2735/1845/3464 2732/1869/3465 +f 2486/3644/5371 2263/3513/6115 2261/3510/5372 +f 2552/3477/6082 2551/2930/4734 2554/3125/4733 +f 3595/1979/4526 3598/1667/3547 3596/3770/5609 +f 3503/3385/3815 3498/3273/4282 3467/3556/4282 +f 1890/3308/4953 2214/2892/4469 2208/3306/4951 +f 1733/2014/3525 1712/3981/3525 1714/3621/3525 +f 2071/3603/5306 1929/3995/6116 1976/3893/5838 +f 1936/2529/4088 2157/3975/6117 2186/2734/4308 +f 3954/3112/4717 3953/2967/4719 3951/2328/3884 +f 3734/3536/3827 3756/3996/3827 3737/3928/3827 +f 1818/1749/3350 1819/2064/6118 1820/1750/3351 +f 3852/2659/4231 3851/2658/4230 3850/2389/3954 +f 2151/2479/4043 2152/2252/3816 2138/2254/3818 +f 2752/1729/3454 2753/3940/3454 2778/3814/3454 +f 2860/2806/4375 2861/3488/5662 2887/3611/6119 +f 3694/2646/4326 3699/2866/5701 3800/3037/4631 +f 2492/3152/4774 2491/3156/6120 2493/3155/6121 +f 3353/3897/6122 3350/1813/4703 3351/3765/5596 +f 3306/1827/3423 3276/3172/4801 3308/2919/4491 +f 2745/3624/5340 2759/2701/6123 2757/3625/5341 +f 2659/1837/3433 2664/1836/3432 2646/2073/3651 +f 1782/2753/6124 1784/2752/6124 1670/3960/6124 +f 2398/3638/5363 2399/3824/5706 2640/1995/3582 +f 2350/3578/5277 2346/3953/5977 2348/2309/5275 +f 4013/3102/4702 4000/3101/4701 4015/2313/3869 +f 2569/3151/6125 2495/3201/6125 2491/3156/6125 +f 3460/2249/3926 3473/3632/6126 3471/3924/5908 +f 4016/2311/3867 4018/2913/4486 4019/2187/3758 +f 1957/3141/4758 1960/2640/4208 1956/2334/4210 +f 2596/3972/6026 2635/2798/4367 2602/2800/4369 +f 3647/3452/5558 3657/2038/3616 3658/3686/5443 +f 3441/3865/3734 3440/3573/3734 3439/3782/3734 +f 2231/3803/2635 2229/3369/2635 1921/3744/2635 +f 3851/2658/5632 3853/3752/6127 3829/3787/5631 +f 3006/3129/6128 2979/2792/4361 3004/2846/4418 +f 3507/3329/4282 3472/3330/4282 3475/1777/4282 +f 3802/3561/3313 3801/3444/3313 3805/2512/3313 +f 3401/1676/3287 3402/2740/4314 3384/1841/3438 +f 2669/2084/3662 2525/3681/5436 2439/2082/3660 +f 3979/3191/6129 3995/3936/6130 3980/3312/6131 +f 2779/3760/3454 2777/1730/3454 2752/1729/3454 +f 2021/3736/5532 1860/3684/5440 1857/2522/5533 +f 3875/1717/3289 3870/3692/3289 3849/2388/3289 +f 3285/2416/4686 3286/2415/6132 3300/3836/5729 +f 3673/3238/4879 3671/3935/5931 3674/3777/5619 +f 2945/2907/4481 2946/2169/3743 2944/2168/3742 +f 2839/2095/6133 2841/3498/5193 2840/2096/3631 +f 3844/2937/5646 3843/3997/6134 3846/1718/4267 +f 3725/3988/6135 3723/3987/6136 3724/2452/5777 +f 2793/2239/3803 2792/3371/5015 2825/3830/5716 +f 3462/2346/3903 3481/2345/3902 3479/3646/5788 +f 2403/3931/5925 2404/3023/4619 2635/2798/4367 +f 1941/2653/5994 2000/3855/5763 2004/3780/5762 +f 2127/3894/5843 2118/3157/4779 2114/2471/4035 +f 2182/2200/3767 2211/2202/3769 1985/2781/4352 +f 3505/2772/3815 3483/2654/3815 3486/2773/3815 +f 2360/2410/3976 2363/3998/6137 2358/3999/6138 +f 3014/3390/5062 3013/2874/5323 2982/3402/5060 +f 1870/2690/6139 1873/2360/6139 1871/3864/6139 +f 1965/3471/5823 1966/3776/6140 2180/2286/3846 +f 3541/2021/3601 3542/3709/5478 3540/2022/3602 +f 4008/3649/5380 4012/2380/3945 4010/2379/3944 +f 3578/2211/3779 3658/3686/5443 3657/2038/3616 +f 1752/3327/4968 1753/4000/6141 1731/3804/5665 +f 3456/2900/4476 3457/2941/5374 3535/3165/4789 +f 3687/2181/3753 3577/2183/3754 3569/3683/3753 +f 2218/2886/2635 2219/3430/3271 1925/4001/3274 +f 2785/3339/3454 2765/2220/3454 2768/2539/4979 +f 3680/2897/4474 3574/3335/4977 3643/3915/5900 +f 3029/3372/5016 3028/3707/5749 3015/2873/5017 +f 2645/3144/4765 2648/3243/4885 2655/3244/4886 +f 2159/3700/5465 2058/1842/3439 2055/1844/3441 +f 2589/2404/3969 2448/3035/4629 2588/4002/6142 +f 2751/3266/4910 2742/3265/4909 2743/3938/5936 +f 3116/2551/3730 3113/3628/3730 3141/1756/3730 +f 3551/2075/3653 3549/3829/5715 3445/2076/3654 +f 1675/3064/4659 1764/3650/5381 1763/3065/4660 +f 1686/2354/3525 1685/2589/4124 1684/1933/3525 +f 3043/2796/4365 3044/2368/3929 3061/2394/3959 +f 2366/3541/5239 2386/2948/4535 2365/4003/6143 +f 3207/1724/3327 3301/3785/5629 3300/3836/5729 +f 3716/3549/5247 3715/3962/5247 3746/3550/5248 +f 3104/2099/3677 3103/1800/3399 3126/2711/4283 +f 3594/3769/5608 3595/1979/4526 3596/3770/5609 +f 3761/3599/5300 3772/2230/5338 3771/2229/5457 +f 3082/1703/5709 3197/1702/5709 3201/3798/5709 +f 2979/2792/4361 3006/3129/6128 3007/3882/6034 +f 2448/3035/4629 2597/3311/4955 2588/4002/6142 +f 3936/3993/3512 3937/2392/3512 3939/1920/3513 +f 3325/3572/5579 3323/3574/3734 3328/3206/3734 +f 2268/2731/4304 2267/2730/4303 2266/3817/5686 +f 3842/3731/5521 3825/3592/5520 3840/1949/6144 +f 3406/1746/3347 3388/1745/3346 3376/3788/5633 +f 2971/3448/5119 2962/3447/5118 2964/3755/3713 +f 3649/3771/5898 3650/1732/3335 3633/1666/4263 +f 3490/3207/4839 3488/3251/5663 3487/3208/4840 +f 2719/3730/2635 2720/2112/2635 2427/1952/3540 +f 3875/1717/3972 3887/2839/4411 3886/2407/3973 +f 1969/2578/4141 2185/3084/4754 2184/2579/4142 +f 3096/2423/3841 3091/3336/3841 3094/2424/3841 +f 2923/2157/6053 2922/3028/4624 2933/2042/3620 +f 3260/3636/3699 3255/3246/3699 3253/2918/3699 +f 2662/3275/4916 2504/2721/4294 2495/3201/5418 +f 2076/3326/4967 2075/2649/4218 1939/3747/5562 +f 2175/3530/5226 2163/3618/5330 2164/1792/3392 +f 3173/2150/3721 3172/3791/5639 3159/2148/3719 +f 3221/2242/3806 3220/3834/6094 3240/2240/3804 +f 2247/3500/5195 2238/3499/5194 2242/3496/5191 +f 2789/2785/3454 2788/2714/3454 2761/2702/3454 +f 3235/3846/5751 3234/3495/5189 3233/3480/5163 +f 2159/3700/5465 2055/1844/3441 2161/3701/5466 +f 2166/3913/5879 2169/2207/3774 2167/3734/5525 +f 3888/2598/5517 3887/2839/4411 3876/1716/4410 +f 2986/2585/5644 2973/1686/4189 2983/2586/4188 +f 1959/2635/4202 1958/3475/5156 1795/2636/4203 +f 1760/3547/5245 1677/2691/5649 1679/1880/4658 +f 3251/2431/3995 3250/2430/3994 3248/2498/4890 +f 3695/3055/4651 3776/3124/5961 3777/3794/6145 +f 3952/2327/3512 3950/3679/6106 3981/3617/3512 +f 2420/4004/6146 2415/4005/6147 2596/3972/6026 +f 2851/2008/3822 2953/2053/3822 2954/2052/3822 +f 2517/2533/4092 2518/3026/4622 2713/3876/5814 +f 3265/1714/3699 3236/3052/3699 3235/3846/3699 +f 2944/2168/3742 2943/3853/5759 2942/3394/5050 +f 2073/2456/4371 2016/2556/4116 2072/2803/4372 +f 3291/2071/3649 3216/1859/3455 3311/1861/3457 +f 3710/3412/5704 3709/3434/6085 3726/3660/5702 +f 2988/3643/5922 2987/2005/6068 2989/3722/5504 +f 2117/3158/4780 2118/3157/4779 2116/3073/4668 +f 3283/1715/3321 3296/3192/4822 3295/3698/5461 +f 3464/2251/4012 3487/3208/6105 3485/3215/5768 +f 3598/1667/3280 3632/2362/3280 3596/3770/5005 +f 3517/3850/5756 3505/2772/6014 3506/2771/4390 +f 3543/4006/6148 3448/1971/5714 3544/3708/5477 +f 2176/3562/5261 2197/3529/5225 2199/2047/3626 +f 3669/2438/4002 3670/3422/5083 3672/3778/5620 +f 2661/2915/4488 2654/3404/5066 2655/3244/4886 +f 2075/2649/4218 2038/3849/5754 1939/3747/5562 +f 2235/3379/2635 2234/2234/2635 1923/2236/3800 +f 2393/3006/4602 2615/2662/4235 2463/2524/4083 +f 3743/1743/4213 3741/1742/5020 3742/3374/5019 +f 2444/2963/4549 2443/2962/4548 2440/3524/5219 +f 1759/1904/3499 1758/1903/3498 1760/3547/5245 +f 3334/2163/3735 3329/3352/5000 3415/2418/3984 +f 1983/3976/6051 1977/2065/5305 1947/3211/4843 +f 2848/2923/3631 2850/2087/3666 2849/2010/4761 +f 2123/2517/4076 2117/3158/4780 2128/2515/4074 +f 4039/2853/5947 3923/3285/6149 3927/3039/5947 +f 2092/1928/3522 1990/1694/3302 1938/2672/4244 +f 2429/3867/5795 2705/3732/3274 2283/3971/3271 +f 1706/2175/3749 1709/2147/3751 1707/2726/3749 +f 1915/4007/6150 1988/3349/4996 1989/1832/3428 +f 3170/3674/5417 3095/2422/5816 3195/2331/3887 +f 3626/3522/3280 3621/1780/3280 3591/2139/3280 +f 2512/2223/3789 2514/3223/4858 2515/2532/5432 +f 4014/2312/3868 4016/2311/3867 3935/2510/4070 +f 3411/3443/5116 3397/3442/5115 3412/3583/5282 +f 3670/3422/5083 3669/2438/4002 3667/2843/4415 +f 3463/3299/4945 3484/2655/6151 3482/2347/3904 +f 1739/2051/3630 1740/2135/3712 1724/2134/3711 +f 3283/1715/3321 3267/3949/5968 3268/2203/3770 +f 1750/3090/4691 1749/3917/5956 1762/3091/4692 +f 3021/3487/3296 3003/2893/3296 3000/1752/3296 +f 2378/3786/5630 2375/2863/4435 2381/3613/5325 +f 2437/3811/5677 2439/2082/3660 2523/3862/6065 +f 2705/3732/3274 2284/3081/3271 2283/3971/3271 +f 3712/3970/6027 3711/3413/5484 3733/3713/5486 +f 3373/2889/4991 3336/1670/5526 3346/3673/6152 +f 4005/3198/4829 3978/3832/5722 3977/2060/6153 +f 1725/2049/3525 1691/2305/3525 1693/2514/3525 +f 3768/2749/4324 3767/3779/5622 3756/3996/6154 +f 3976/3092/4694 3990/3807/5841 3989/3093/4695 +f 1695/2664/6155 1694/3942/6155 1696/3359/5009 +f 3972/1935/5825 3987/3162/4786 3973/2058/3635 +f 2566/3816/5684 2662/3275/4916 2565/2385/3950 +f 3504/2977/4563 3528/3383/5033 3503/3385/5035 +f 3275/2868/4442 3276/3172/4801 3307/3750/5570 +f 1866/2682/4254 1867/3414/5448 1861/2680/4252 +f 2972/3391/3296 2973/1686/3296 2976/1688/3296 +f 3560/3930/3559 3561/1834/3558 3565/1833/3559 +f 3331/2161/5803 3440/3573/5803 3441/3865/6156 +f 2767/2538/5786 2766/2222/6157 2747/2351/3908 +f 4019/2187/3758 4022/3199/4830 4020/3835/5728 +f 2946/2169/3743 2844/2787/4923 2948/3280/4925 +f 1720/3136/4875 1721/3137/5897 1722/3237/4876 +f 2038/3849/5754 2035/3493/6158 2036/2847/6035 +f 2396/3508/5203 2397/3637/5362 2460/3639/5364 +f 3754/2292/3827 3756/3996/3827 3734/3536/3827 +f 3855/3910/5874 3857/4008/6159 3830/3909/5873 +f 2233/2235/3271 2232/2929/2635 1922/4009/6160 +f 3857/4008/6161 3855/3910/5572 3856/3751/5572 +f 3318/3934/3993 3317/3294/3993 3214/2319/3993 +f 3290/1937/3526 3215/1939/3528 3216/1859/3455 +f 2562/2638/5101 2561/3905/5866 2345/3047/5865 +f 3204/1723/3326 3289/3946/6162 3302/2227/3793 +f 2230/3883/5818 2232/2929/4505 2043/2485/4507 +f 1831/2616/5624 1829/2614/4221 1941/2653/4223 +f 3743/1743/4213 3742/3374/5019 3745/2641/4211 +f 2072/2803/4372 2156/2435/3999 2022/2457/4370 +f 2805/2715/5999 2804/2784/4517 2822/2741/4316 +f 1718/2208/3776 1716/3768/5779 1688/2209/3777 +f 1791/2637/6163 1789/2481/4045 1788/2483/4047 +f 3623/1782/5965 3624/2777/5965 3616/3224/3280 +f 3603/2000/3587 3604/3416/3828 3605/2001/3588 +f 3706/3630/5347 3746/3550/5948 3715/3962/6164 +f 3076/2505/6165 2957/3324/6165 2956/2137/6165 +f 3110/2282/5537 3109/3138/4748 3108/2283/4750 +f 3343/3819/3281 3342/3253/3281 3340/1786/3281 +f 2482/1689/5710 2484/3669/6166 2481/3018/4614 +f 4020/3835/5728 3929/2511/4071 4019/2187/3758 +f 3381/3926/3281 3363/3670/3281 3365/2960/3281 +f 2005/3840/5742 1840/2629/6167 1839/2626/6168 +f 3234/3495/6169 3237/3054/6170 3219/3802/5661 +f 2547/3381/5027 2543/3514/5209 2570/2371/3934 +f 1695/2664/6155 1692/3945/6171 1694/3942/6155 +f 2225/3364/6172 2226/3218/4854 2056/3356/6173 +f 3630/3929/3280 3631/2950/3280 3612/1737/3280 +f 3965/2340/4510 3967/2339/6174 3942/1919/4508 +f 2292/3544/5242 2297/2376/3941 2296/3861/5772 +f 3872/2564/5388 3883/3341/5387 3882/3340/4980 +f 3137/3763/5690 3132/3714/5489 3166/3305/4950 +f 3246/1866/3462 3249/3247/4891 3247/3048/6175 +f 1683/3002/4596 1696/3359/5950 1682/3943/5952 +f 3129/2905/5773 3130/1957/5775 3128/2097/5773 +f 4016/2311/3867 4015/2313/3869 4018/2913/4486 +f 1743/2324/3880 1757/3316/4959 1777/2325/3881 +f 3539/2023/3603 3524/3438/5107 3537/3933/5929 +f 2712/3025/4621 2711/3873/6176 2518/3026/4622 +f 3363/3670/4544 3361/2199/5796 3360/3664/6087 +f 3716/3549/6003 3719/2265/4525 3717/3281/4926 +f 2838/3219/4855 2834/3858/4855 2727/3220/4855 +f 3002/2894/4471 3005/3127/4737 3004/2846/6006 +f 3224/3393/3699 3217/3439/3699 3219/3802/5661 +f 3133/2299/3730 3127/3017/3730 3125/3685/3730 +f 2881/2829/3725 2883/3325/3725 2902/3071/3725 +f 3654/3228/4864 3627/2361/3920 3653/2363/3922 +f 3196/3799/5736 3089/2634/5736 3198/2633/5736 +f 2969/3564/3713 2961/2837/3713 2970/3099/3713 +f 3324/3184/4814 3429/1853/3451 3424/3980/6057 +f 3995/3936/6130 3994/1840/6177 3980/3312/6131 +f 2215/2891/4468 2194/2492/4055 2195/3963/6005 +f 3750/2992/3827 3740/2032/4582 3739/2031/3827 +f 3199/2632/4201 3089/2634/4201 3088/3534/6178 +f 3261/2121/5479 3258/2120/6179 3289/3946/5957 +f 2769/3729/3454 2786/3170/4979 2787/3338/4979 +f 2401/3775/5616 2402/4010/6180 2463/2524/4083 +f 3437/3781/3734 3438/3115/3734 3441/3865/3734 +f 2836/2998/4590 2738/3000/4591 2730/3123/6181 +f 4043/2910/4482 3930/2509/4482 4044/2706/6182 +f 1755/2581/4145 1756/2050/3629 1725/2049/3628 +f 3691/1707/3313 3698/2272/3313 3695/3055/4651 +f 2851/2008/3631 2852/2786/3631 2845/2258/3631 +f 3819/3392/5046 3914/3720/5497 3915/3227/4863 +f 3470/3795/6009 3467/3556/5254 3468/3454/5256 +f 3737/3928/5917 3736/3857/5766 3735/3927/5915 +f 2441/4011/6183 2649/1990/3577 2651/2965/4551 +f 3367/3418/5975 3366/3082/6184 3342/3253/6185 +f 2215/2891/4468 2213/4012/6186 2214/2892/4469 +f 3974/3313/3512 3976/3092/3512 3966/2341/3512 +f 1942/3320/4963 2007/3319/4962 2005/3840/5761 +f 3956/3063/3512 3984/3790/3512 3959/2759/3512 +f 2790/3293/3454 2791/2687/3454 2763/3642/3454 +f 3594/3769/6187 3582/3965/6012 3595/1979/3566 +f 2710/3870/3275 2709/3887/5991 2708/3888/2635 +f 2916/3258/4901 2906/1877/3473 2915/1876/3472 +f 3497/2809/4685 3466/2808/5255 3467/3556/5254 +f 1704/2587/4154 1685/2589/4156 1706/2175/5790 +f 2122/3647/5376 2120/3174/4803 2119/2627/4196 +f 3490/3207/3815 3491/2881/3815 3499/2823/3815 +f 3754/2292/4585 3760/2291/5456 3769/2750/4584 +f 3713/3766/5597 3738/2030/6048 3741/1742/3343 +f 2317/1817/3413 2316/1816/3412 2315/3231/4868 +f 1686/2354/3912 1710/3051/4647 1708/2176/5789 +f 2536/2677/4249 2292/3544/6188 2671/2092/3671 +f 3145/2745/4320 3143/2374/3937 3159/2148/3939 +f 3421/2836/4408 3424/3980/6057 3423/2085/3663 +f 2532/2093/3672 2528/2473/4037 2531/2475/4039 +f 3367/3418/5077 3369/3302/5078 3370/2320/5078 +f 3962/2760/4333 3961/3441/5111 3960/2761/4334 +f 2921/3029/5355 2922/3028/6007 2901/3403/5065 +f 3759/2451/3827 3761/3599/3827 3724/2452/3827 +f 3262/2417/3699 3266/3407/3699 3231/3408/3699 +f 3876/1716/3289 3846/1718/3289 3843/3997/3288 +f 2098/2500/4062 2099/3974/6038 2009/2268/3829 +f 3381/3926/5913 3383/1967/6189 3394/2828/6190 +f 3277/3173/6191 3276/3172/5494 3264/3717/5493 +f 3390/1991/3578 3391/2559/4119 3377/3531/5227 +f 2070/2520/4079 2066/2887/4760 2074/2528/4087 +f 3502/2710/3815 3500/2545/3815 3493/2708/3815 +f 1924/3378/2635 1881/2724/5991 2236/3492/6192 +f 3949/2326/3882 3948/2882/5481 3950/3679/5431 +f 3457/2941/3558 3454/2899/3558 3452/3614/3559 +f 2207/2201/3768 1935/2530/4089 1934/2735/4309 +f 2225/3364/2635 1928/3363/2635 1917/3959/5991 +f 3133/2299/3856 3140/3716/5492 3152/2297/3854 +f 3304/3749/5564 3273/3119/5885 3305/1829/3425 +f 1705/2494/3525 1737/2445/3525 1738/2495/3525 +f 3394/2828/6190 3395/3559/5914 3381/3926/5913 +f 2683/3968/6018 2570/2371/3934 2533/2762/4335 +f 3546/2601/4168 3529/3384/5034 3545/2602/4169 +f 3878/3506/5202 3910/3397/5055 3908/1883/3477 +f 3891/2986/5512 3890/3518/5832 3873/3427/5513 +f 2887/3611/6119 2885/3491/5183 2860/2806/4375 +f 1685/2589/4156 1686/2354/3912 1708/2176/5789 +f 1782/2753/6124 1670/3960/6124 1665/3031/6124 +f 2756/2194/5934 2743/3938/5936 2744/3623/5339 +f 3924/2707/4397 3930/2509/4069 3929/2511/4071 +f 3688/2182/3533 3687/2181/6193 3686/1945/3533 +f 3897/2599/4166 3889/3727/6194 3898/1984/3571 +f 3613/2110/5332 3587/3355/5167 3588/3182/4812 +f 3984/3790/3512 3979/3191/3512 3959/2759/3512 +f 3627/2361/3280 3626/3522/3280 3593/3892/5005 +f 3892/4013/6195 3902/3989/6093 3901/2987/4575 +f 3404/1926/3520 3380/1814/6196 3403/1924/3518 +f 3996/2953/6197 3984/3790/5638 3997/3789/5637 +f 3671/3935/5931 3672/3778/5620 3674/3777/5619 +f 3265/1714/3699 3270/3457/3699 3238/3053/3699 +f 3133/2299/3856 3150/2841/5554 3135/2343/3900 +f 1734/1886/3525 1731/3804/3525 1697/3360/3525 +f 3920/3570/5909 3810/3569/6198 3817/2488/5909 +f 3144/2179/3932 3145/2745/4320 3157/2747/4322 +f 1733/2014/3525 1732/2145/3525 1712/3981/3525 +f 3282/1713/3319 3283/1715/3321 3292/2070/3648 +f 2978/2845/3296 2979/2792/3296 2976/1688/3296 +f 3822/3903/3289 3824/3344/3288 3826/2936/3289 +f 2597/3311/4955 2605/3318/4961 2604/3696/5459 +f 3383/1967/3281 3365/2960/3281 3368/3419/3281 +f 2974/1687/3296 2975/2742/4251 2976/1688/3296 +f 2993/2944/4529 2992/2945/4531 2995/3914/5880 +f 2440/3524/5219 2511/2225/3791 2442/3145/4766 +f 3194/2160/3733 3087/3820/5694 3193/3821/5695 +f 3795/1771/3372 3794/2946/4533 3762/2955/4541 +f 2649/1990/3577 2441/4011/6183 2440/3524/5219 +f 3485/3215/4848 3488/3251/5663 3486/2773/4849 +f 3871/2565/3288 3865/3657/3289 3854/2566/3289 +f 3895/2414/3980 3887/2839/5231 3896/2412/3978 +f 1708/2176/3750 1710/3051/6199 1709/2147/3751 +f 2823/2180/3752 2731/3347/5654 2729/2705/4279 +f 3442/3114/4720 3320/3116/4720 3327/2162/4720 +f 3163/1754/3355 3142/4014/6200 3138/2860/4431 +f 3240/2240/5911 3239/3990/6201 3238/3053/4649 +f 2739/3140/4752 2822/2741/4316 2821/2462/4024 +f 2037/2448/6054 2039/3740/5542 2040/1911/3505 +f 2597/3311/4955 2604/3696/5459 2588/4002/6142 +f 3946/2391/3956 3948/2882/4456 3937/2392/3957 +f 3919/3269/5635 3807/3287/5635 3812/3568/6202 +f 3025/3387/5755 3023/3074/4669 3040/3276/4917 +f 2024/2926/4502 2025/3415/6203 1940/2927/4503 +f 3829/3787/5631 3853/3752/6127 3855/3910/5874 +f 2126/3991/6104 2146/3323/4966 2125/2851/4424 +f 3313/3691/6204 3208/2018/6204 3315/2020/6204 +f 3982/3061/3512 3954/3112/3512 3983/2466/3512 +f 3663/2243/3807 3667/2843/4415 3666/2244/3808 +f 3721/1947/5776 3724/2452/5777 3723/3987/6136 +f 2788/2714/4287 2789/2785/4356 2805/2715/4288 +f 3655/1712/3318 3654/3228/4864 3665/1710/3316 +f 1717/2562/5599 1716/3768/5601 1718/2208/5721 +f 2469/4015/6205 2470/4016/6206 2471/3014/4611 +f 2206/3470/5151 2114/2471/4035 2122/3647/5376 +f 3840/1949/3537 3841/1951/3539 3843/3997/6134 +f 2000/3855/5763 1942/3320/4963 2005/3840/5761 +f 2304/2594/6000 2537/3896/5845 2543/3514/6001 +f 3346/3673/5415 3347/1815/4704 3345/2888/4464 +f 2231/3803/5664 2046/3469/5817 2048/3264/5660 +f 3643/3915/5900 3642/2789/4358 3679/2788/4357 +f 2759/2701/6123 2745/3624/5340 2760/3175/6036 +f 1949/2276/3836 1794/2333/3889 1960/2640/6207 +f 2647/1987/3574 2648/3243/4885 2566/3816/5684 +f 2235/3379/5031 2035/3493/5188 2037/2448/4013 +f 2737/3932/3465 2739/3140/4752 2734/3133/3464 +f 3360/3664/6087 3361/2199/5796 3359/3665/5451 +f 1906/2650/4219 1905/4017/6208 1904/2651/4220 +f 1859/2766/4339 2019/3436/5105 2016/2556/4116 +f 1702/2588/4155 1701/3842/5886 1684/1933/4597 +f 2104/3197/4828 2085/3828/5713 2083/1830/3426 +f 3904/3233/4870 3905/3880/5811 3906/1882/3476 +f 3269/3179/3699 3263/2865/3699 3244/1865/3699 +f 2526/2876/4449 2707/2673/4245 2527/2675/4247 +f 3974/3313/5129 3980/3312/6131 3993/1839/6021 +f 1985/2781/4352 1882/2783/4354 1883/4018/6209 +f 2840/2096/3631 2843/2924/4761 2848/2923/3631 +f 3101/2603/4170 3102/1801/3400 3103/1800/3730 +f 1879/2723/5186 2036/2847/5187 2236/3492/5184 +f 3710/3412/5704 3729/3964/6011 3711/3413/5484 +f 3166/3305/4950 3146/3715/5490 3168/2172/3746 +f 2227/3370/2635 2228/3216/2635 1917/3959/5991 +f 2647/1987/3574 2566/3816/5684 2565/2385/3950 +f 2819/2546/4105 2800/3176/4805 2832/1847/3444 +f 2842/3377/4761 2843/2924/4761 2840/2096/3631 +f 1702/2588/5985 1703/2493/6108 1701/3842/5746 +f 2165/2205/3772 2169/2207/3774 2166/3913/5879 +f 3635/3411/6210 3649/3771/5898 3633/1666/4263 +f 2906/1877/3725 2907/3259/3725 2877/1725/3725 +f 3516/2609/6211 3506/2771/4390 3515/2459/4392 +f 3963/3077/4673 3966/2341/3898 3965/2340/3897 +f 2724/4019/6212 2472/3015/6212 2471/3014/6212 +f 3252/2429/3993 3251/2431/3995 3253/2918/3993 +f 2919/2141/6213 2918/1961/5384 2929/3908/5869 +f 2593/3105/4709 2603/2405/3970 2608/3723/5505 +f 1764/3650/5381 1675/3064/4659 1766/2033/3611 +f 2809/2704/4579 2810/2703/6090 2778/3814/5681 +f 1845/3666/5407 1843/2951/4537 1844/3667/5408 +f 2281/2908/4485 2278/3527/5223 2279/3203/5307 +f 2313/3232/4869 2312/3831/6096 2314/3230/4867 +f 3376/3788/5633 3379/1925/3519 3406/1746/3347 +f 1931/2289/3849 2201/3612/5320 2205/2364/3923 +f 2517/2533/5433 2514/3223/4858 2516/3222/4857 +f 3233/3480/5824 3234/3495/6169 3219/3802/5661 +f 1963/2285/4029 1797/2769/4342 1798/2467/4030 +f 3526/2978/4564 3540/2022/3602 3542/3709/5478 +f 3200/3895/5773 3091/3336/5773 3201/3798/5773 +f 2005/3840/5742 2007/3319/5989 1837/2624/5988 +f 3080/2504/5648 2957/3324/5648 3076/2505/5648 +f 3024/3075/3296 2989/3722/3296 2987/2005/3296 +f 2304/2594/6000 2299/3241/4882 2537/3896/5845 +f 2718/3631/2635 2716/3801/2635 2426/3167/2635 +f 3674/3777/5619 3568/3421/5082 3675/1794/3394 +f 2967/2301/3891 2966/3171/3713 2963/1969/3713 +f 3888/2598/4165 3889/3727/6194 3897/2599/4166 +f 3542/3709/5478 3543/4006/6148 3544/3708/5477 +f 2078/3282/4927 2129/3038/4632 2077/2402/3967 +f 3734/3536/5916 3733/3713/6214 3731/3712/6037 +f 3199/2632/5674 3094/2424/5676 3200/3895/5676 +f 2995/3914/5880 2996/2928/5455 2994/1799/6215 +f 2883/3325/5700 2882/2805/5093 2884/2804/5698 +f 3514/2460/4022 3513/2544/4103 3553/2542/4101 +f 3171/3844/5748 3157/2747/5416 3158/2746/5730 +f 3775/1758/3359 3757/3979/6056 3758/2264/5962 +f 3754/2292/4585 3768/2749/4324 3756/3996/6154 +f 3341/3254/6071 3342/3253/6185 3364/2959/6216 +f 2828/1706/3312 2733/1868/5113 2829/2012/3594 +f 2093/2537/4096 2097/2536/4095 2007/3319/4962 +f 2655/3244/4886 2666/3250/4896 2661/2915/4488 +f 3231/3408/6217 3230/2383/5164 3229/2382/5393 +f 1759/1904/3499 1760/3547/5245 1761/3548/5246 +f 2602/2800/4369 2625/3095/4697 2626/3697/5460 +f 2516/3222/4857 2679/1941/3530 2685/3911/5875 +f 2070/2520/4079 1957/3141/4758 1950/2518/4077 +f 1754/2215/3781 1753/4000/6218 1767/2034/3612 +f 3736/3857/5766 3737/3928/5917 3739/2031/3609 +f 2045/2869/4506 2232/2929/4505 2041/1910/5673 +f 3058/3449/5120 3053/1913/3507 3055/2335/3892 +f 2475/2439/4003 2244/3497/6219 2239/2261/5501 +f 2061/2670/4242 2060/1765/4889 2063/2661/4234 +f 2543/3514/6001 2547/3381/5846 2306/2592/5848 +f 3709/3434/6085 3708/1948/3536 3723/3987/6083 +f 2193/3425/5086 2201/3612/5320 2212/3900/5855 +f 2817/3694/5454 2819/2546/4105 2832/1847/3444 +f 2695/2130/3707 2690/2713/4285 2696/2972/4558 +f 2611/3108/4712 2631/3920/5895 2610/3317/4960 +f 2162/3117/4722 2157/3975/6050 2158/2669/4241 +f 2270/3515/5210 2262/3512/5207 2263/3513/5208 +f 2493/3155/4777 2276/4020/6220 2264/3633/5353 +f 3511/3274/4915 3546/2601/4168 3547/3796/5647 +f 2092/1928/3522 1994/2814/4382 1993/1929/3523 +f 3283/1715/3321 3295/3698/5461 3292/2070/3648 +f 1919/4021/2634 2232/2929/2634 2230/3883/2634 +f 2070/2520/4461 2219/3430/5092 2218/2886/4462 +f 3242/2241/4675 3240/2240/5911 3241/3079/4674 +f 3867/1679/3289 3858/1678/3289 3865/3657/3289 +f 3122/1802/5806 3121/2304/5170 3123/3906/6080 +f 2368/2568/4127 2367/1770/3371 2406/3923/5904 +f 2615/2662/4235 2620/2114/3693 2621/2663/4236 +f 2410/4022/6221 2411/4023/6222 2461/1975/3562 +f 2995/3914/5880 2994/1799/6215 2993/2944/4529 +f 1803/3020/4616 1965/3471/5152 1968/3021/4617 +f 3622/1682/3280 3630/3929/3280 3612/1737/3280 +f 2449/2668/4240 2601/3473/5154 2600/2667/4239 +f 3066/2938/4521 3067/2425/3988 3068/2427/3990 +f 3042/2296/3853 3043/2796/4365 3060/3977/6052 +f 2272/1900/3494 2273/3525/5220 2274/1898/3492 +f 3156/2330/3886 3144/2179/3932 3157/2747/4322 +f 2687/2026/3606 2684/2531/4090 2685/3911/5875 +f 3246/1866/3699 3264/3717/3699 3249/3247/5069 +f 2726/3401/3464 2732/1869/3465 2733/1868/3465 +f 3568/3421/5082 3567/2267/5470 3566/2266/3533 +f 3521/1740/3341 3520/1763/3364 3533/1741/3342 +f 2265/3526/5221 2266/3817/5686 2264/3633/5687 +f 2195/3963/6005 2213/4012/6186 2215/2891/4468 +f 2223/1901/2635 2224/1902/2635 1926/3362/2635 +f 2574/2639/4207 2578/3298/4944 2582/3135/4745 +f 1895/3009/4605 1894/2795/4364 1989/1832/3428 +f 1927/3361/5012 1926/3362/2635 2224/1902/2635 +f 2209/2684/4256 1890/3308/6223 1986/2685/4257 +f 3271/2228/3794 3260/3636/5359 3272/3748/5930 +f 1692/3945/6171 1693/2514/6171 1691/2305/4229 +f 3706/3630/3827 3707/3110/5072 3711/3413/3827 +f 2857/3597/5298 2858/2902/4477 2873/2904/4479 +f 3383/1967/3281 3381/3926/3281 3365/2960/3281 +f 3208/2018/3600 3206/3295/6224 3316/2019/3600 +f 1938/2672/4244 1900/2807/4376 1899/3147/4768 +f 2788/2714/4287 2807/1862/3870 2784/1856/3872 +f 3308/2919/4491 3309/2127/3704 3205/1860/3456 +f 2750/3262/4905 2774/1906/4906 2749/3365/6078 +f 3417/1875/3471 3416/3353/5001 3419/2834/4406 +f 2088/2970/4556 2089/2732/4306 2096/2733/4307 +f 3318/3934/3361 3314/3810/3361 3313/3691/3361 +f 3843/3997/3288 3841/1951/3288 3874/3428/3288 +f 3859/3641/6225 3861/3848/5889 3822/3903/5891 +f 3766/2997/4589 3765/1784/3385 3750/2992/4587 +f 3507/3329/6092 3525/3289/6091 3526/2978/6226 +f 2387/2411/3977 2364/3542/5240 2361/2409/3975 +f 3815/2487/4051 3814/3986/4051 3808/3405/4052 +f 3054/2295/3852 3041/3076/5467 3042/2296/3853 +f 3096/2423/6227 3174/3772/5613 3175/3252/4897 +f 3507/3329/6092 3508/3507/5348 3524/3438/5350 +f 1671/3433/5096 1674/3688/5445 1777/2325/3881 +f 2794/2238/3802 2795/1704/3310 2782/3680/5538 +f 3974/3313/3512 3966/2341/3512 3964/3078/3512 +f 2102/3738/5536 2103/3284/4929 2101/3490/5182 +f 3216/1859/3455 3215/1939/3528 3214/2319/3361 +f 3424/3980/6057 3421/2836/4408 3422/2835/4407 +f 2374/2864/4436 2377/3606/5310 2373/3604/5308 +f 2493/3155/6121 2494/3634/6228 2492/3152/4774 +f 3814/3986/4051 3811/3437/4052 3808/3405/4052 +f 3071/2300/3857 3069/2486/4050 3034/1803/3402 +f 3934/3032/4627 3935/2510/4070 3933/2214/4628 +f 3821/2489/4051 3816/1983/4051 3815/2487/4051 +f 3905/3880/5811 3904/3233/4870 3877/1809/5201 +f 1916/4024/6229 1927/3361/5012 2220/1766/2635 +f 3588/3182/4812 3581/3187/4817 3619/3180/4810 +f 1858/2767/5329 1859/2766/4339 2016/2556/4116 +f 2159/3700/5465 2160/3699/5464 2058/1842/3439 +f 1932/2490/4053 2186/2734/4308 2187/3248/4892 +f 2225/3364/2635 2223/1901/2635 1926/3362/2635 +f 2279/3203/5307 2282/2911/4483 2281/2908/4485 +f 3352/2061/3638 3355/2063/3640 3353/3897/6122 +f 3807/3287/4051 3808/3405/4052 3809/3288/4931 +f 1888/4025/6230 1889/3307/4952 1987/2288/3848 +f 3898/1984/3571 3816/1983/3570 3821/2489/4753 +f 2847/2764/4337 2839/2095/6133 2846/2144/5351 +f 3921/3925/6161 3815/2487/6231 3922/3941/6231 +f 3169/2171/3745 3184/2173/3747 3182/3921/5896 +f 3516/2609/4176 3515/2459/4021 3555/3239/4880 +f 2183/2934/4516 2184/2579/4142 2180/2286/3846 +f 2032/2857/4428 2031/2359/3918 2030/4026/6232 +f 2920/2142/5907 2931/3856/5765 2932/2922/4498 +f 3343/3819/5692 3367/3418/5975 3342/3253/6185 +f 3820/3226/4052 3818/2413/4052 3817/2488/4052 +f 3263/2865/3699 3264/3717/3699 3246/1866/3699 +f 3661/1978/3565 3653/2363/4972 3652/2757/4330 +f 2717/3168/5974 2715/2111/3690 2510/2443/4007 +f 2342/1893/5293 2341/3591/5292 2340/1894/5289 +f 3212/3711/3362 3214/2319/3361 3213/1775/3376 +f 3687/2181/5157 3569/3683/5157 3570/2540/5157 +f 1716/3768/5601 1715/3756/5600 1713/3622/5337 +f 3499/2823/3815 3506/2771/3815 3488/3251/3815 +f 3857/4008/6161 3856/3751/5572 3858/1678/6231 +f 2706/2674/2635 2433/3871/3275 2710/3870/3275 +f 2920/2142/5907 2919/2141/6213 2931/3856/5765 +f 3187/3958/5990 3084/2280/3843 3185/3833/5724 +f 3614/1738/4860 3613/2110/3689 3615/3225/4861 +f 3241/3079/3699 3269/3179/3699 3244/1865/3699 +f 3139/3486/3730 3140/3716/3730 3123/3906/3730 +f 3020/2350/3296 3019/2007/3296 2985/2006/3296 +f 3735/3927/5915 3733/3713/6214 3734/3536/5916 +f 3524/3438/5107 3523/3164/4788 3537/3933/5929 +f 2831/3919/5894 2798/2477/4041 2797/2011/3593 +f 3509/2069/3647 3519/1764/3365 3520/1763/3364 +f 2951/2094/6233 2849/2010/6234 2955/2009/6234 +f 2733/1868/5113 2828/1706/3312 2826/3153/4775 +f 2830/3724/5506 2832/1847/3444 2831/3919/5894 +f 3999/3100/4700 4013/3102/4702 4012/2380/3945 +f 3214/2319/3361 3206/3295/3361 3216/1859/3455 +f 3774/1757/3358 3773/3598/5299 3759/2451/5301 +f 3340/1786/3281 3336/1670/3281 3344/2813/3281 +f 3462/2346/3903 3461/2722/3815 3464/2251/3815 +f 3860/1677/3288 3863/2428/3289 3862/2935/3288 +f 3650/1732/3335 3649/3771/5898 3660/1733/3336 +f 3732/2293/6037 3731/3712/6037 3729/3964/6103 +f 4029/3985/6075 4027/3351/4998 3986/3163/4999 +f 3490/3207/4839 3489/2447/4453 3491/2881/4455 +f 3491/2881/3815 3500/2545/3815 3499/2823/3815 +f 2528/2473/4037 2529/3901/5859 2530/2474/4038 +f 2172/3563/5262 2176/3562/5261 2177/3519/5214 +f 2032/2857/5996 2034/2859/6235 1878/3088/5997 +f 2055/1844/3441 2164/1792/3392 2161/3701/5466 +f 3410/3767/5598 3409/3343/4983 3401/1676/3287 +f 1672/2727/4301 1667/2737/4311 1770/3739/5541 +f 3110/2282/3730 3138/2860/3730 3142/4014/3730 +f 3778/3056/4652 3695/3055/4651 3777/3794/6145 +f 3177/3332/4974 3093/3331/4973 3175/3252/4897 +f 2831/3919/5894 2812/2478/4042 2798/2477/4041 +f 3486/2773/4849 3483/2654/4224 3484/2655/4226 +f 3785/2219/3785 3772/2230/3796 3773/3598/5299 +f 3512/3189/4819 3511/3274/4915 3550/3188/4818 +f 3137/3763/3730 3136/2281/3730 3108/2283/3730 +f 1791/2637/5315 1796/3474/5317 1794/2333/4121 +f 1935/2530/4089 2207/2201/3768 2179/3261/4904 +f 3870/3692/3289 3872/2564/3289 3852/2659/3289 +f 1692/3945/6171 1691/2305/4229 1690/2657/4228 +f 1720/3136/4746 1718/2208/3776 1689/1932/3775 +f 3892/4013/6195 3893/1685/3295 3902/3989/6093 +f 2475/2439/4111 2476/2553/4113 2417/4027/6236 +f 2976/1688/3397 2975/2742/4317 2991/2744/4319 +f 3932/3041/4635 3928/3040/4634 4034/3107/4711 +f 2571/2775/4346 2700/1820/3416 2701/2774/4345 +f 2697/3409/5070 2451/3967/6017 2696/2972/4558 +f 3979/3191/3512 3980/3312/3512 3962/2760/3512 +f 3884/3654/6237 3885/2408/4033 3916/2469/4032 +f 2655/3244/4886 2656/3060/4656 2660/3059/4655 +f 3413/3301/4947 3412/3583/5282 3414/3805/5666 +f 2435/1821/3417 2686/3826/5708 2436/1819/3415 +f 3386/2197/4644 3397/3442/5450 3398/3049/4645 +f 2281/2908/2635 2280/2912/2635 2722/2909/2635 +f 1672/2727/4301 1675/3064/3475 1673/1879/3475 +f 2415/4005/6147 2471/3014/4611 2470/4016/6206 +f 3709/3434/6085 3725/3988/6084 3726/3660/5702 +f 2782/3680/5538 2781/3656/5391 2794/2238/3802 +f 3732/2293/6037 3729/3964/6103 3730/3948/6102 +f 3020/2350/3296 2984/2679/4251 2982/3402/3296 +f 3757/3979/3827 3759/2451/3827 3722/2450/3827 +f 2650/2964/4550 2514/3223/4858 2641/3584/5284 +f 2333/3068/4663 2332/2982/4569 2331/2981/4568 +f 3870/3692/5452 3875/1717/3972 3885/2408/3974 +f 2203/3839/5740 2197/3529/5225 2174/1791/3391 +f 1939/3747/5562 2153/3827/5711 2140/1671/3282 +f 2808/2314/5294 2807/1862/3458 2823/2180/3752 +f 2149/2850/4423 2138/2254/3818 2137/3072/4667 +f 3069/2486/4050 3068/2427/3990 3047/2426/3989 +f 3176/2338/3895 3178/3837/5735 3179/3333/4975 +f 3322/3560/6238 3328/3206/3734 3323/3574/3734 +f 2673/2091/3670 2678/3236/4873 2671/2092/3671 +f 2889/3482/3592 2890/3483/3592 2888/3610/5318 +f 1993/1929/3523 1994/2814/4382 1995/2816/4384 +f 1844/3667/5899 1842/2631/5987 2007/3319/5989 +f 2662/3275/4916 2566/3816/5684 2663/3815/5683 +f 2494/3634/5354 2264/3633/5353 2267/2730/5877 +f 2691/2712/4284 2695/2130/3707 2694/2132/3709 +f 2580/2188/3759 2577/2373/3936 2586/2189/3760 +f 3260/3636/3699 3257/3761/3699 3255/3246/3699 +f 2379/3609/5313 2376/3605/5309 2375/2863/4435 +f 3047/2426/3989 3067/2425/3988 3033/2117/3696 +f 3447/2818/4385 3456/2900/4476 3532/2262/3826 +f 2798/2477/4041 2799/2476/4040 2785/3339/5963 +f 2167/3734/5525 2170/3759/5583 2171/3885/5822 +f 3970/2826/5584 3943/2827/6239 3936/3993/6109 +f 3076/2505/3713 3075/1968/3713 3079/2503/3713 +f 3630/3929/5921 3622/1682/3292 3642/2789/4358 +f 2098/2500/4062 2009/2268/3829 2010/2501/4063 +f 2820/2547/4106 2819/2546/4105 2818/3139/4751 +f 2729/2705/4279 2728/3400/6019 2824/3160/4782 +f 1813/1696/3304 1806/3464/5978 1808/3619/5331 +f 3784/2218/3784 3786/2217/3783 3702/3746/5561 +f 3270/3457/3699 3241/3079/3699 3238/3053/3699 +f 2228/3216/2635 2226/3218/2635 1917/3959/5991 +f 4011/2378/3943 4012/2380/3945 4013/3102/4702 +f 3455/2819/4386 3447/2818/4385 3557/2607/4174 +f 3255/3246/3699 3258/2120/3699 3226/2122/3699 +f 3836/2015/4985 3837/3874/5798 3824/3344/4986 +f 1853/2523/4082 1854/3939/4080 1855/2521/4080 +f 3293/1938/3527 3290/1937/3526 3292/2070/3648 +f 3431/2780/4351 3430/4028/6240 3432/2107/3685 +f 3767/3779/5688 3755/2996/4588 3756/3996/6241 +f 2699/3410/5071 2700/1820/3416 2571/2775/4346 +f 2478/3019/5870 2484/3669/5410 2251/3505/5871 +f 2927/2089/3668 2928/3652/5383 2926/3653/5385 +f 3713/3766/3827 3714/1744/3827 3711/3413/3827 +f 3971/2044/3622 3945/3296/4942 3943/2827/4396 +f 2912/2170/3744 2911/3395/5051 2943/3853/5759 +f 3833/3918/6077 3831/3847/5752 3832/2901/5881 +f 2143/1735/3338 2145/3576/5272 2126/3991/6104 +f 3727/3661/5400 3725/3988/6135 3724/2452/5777 +f 2828/1706/3312 2829/2012/3594 2813/4029/6242 +f 2852/2786/4924 2854/3916/5884 2925/2591/4158 +f 1941/2653/5994 2003/2652/6243 2001/3961/5993 +f 2828/1706/3312 2813/4029/6242 2795/1704/3310 +f 3634/2151/3280 3635/3411/3280 3602/2002/3280 +f 3609/2432/3996 3607/2123/3700 3608/2433/3997 +f 3856/3751/5572 3855/3910/5572 3853/3752/5573 +f 2666/3250/4896 2665/2916/4489 2661/2915/4488 +f 2362/4030/6244 2359/4031/6245 2358/3999/6138 +f 2848/2923/4499 2932/2922/4498 2931/3856/5765 +f 2275/2729/4302 2490/3912/5878 2488/3543/5876 +f 2884/2804/5698 2885/3491/5967 2886/3640/5699 +f 2565/2385/3950 2662/3275/4916 2569/3151/4773 +f 3263/2865/4439 3269/3179/4808 3279/2321/4437 +f 3289/3946/6162 3258/2120/6111 3271/2228/3794 +f 2569/3151/4773 2567/2386/3951 2565/2385/3950 +f 2911/3395/6246 2912/2170/4405 2903/2833/4404 +f 3180/3348/4995 3086/2246/3810 3179/3333/4975 +f 1856/3813/6247 2015/3467/5534 1854/3939/5942 +f 2454/3476/5158 2326/3581/5546 2324/3458/5128 +f 3247/3048/6175 3245/1867/3463 3246/1866/3462 +f 3066/2938/4521 3031/3595/5296 3032/3118/4723 +f 3318/3934/6042 3212/3711/6042 3203/1761/6042 +f 1753/4000/6218 1752/3327/5491 1767/2034/3612 +f 4041/2854/4425 4042/2212/4633 4043/2910/4425 +f 2294/2595/4162 2292/3544/5242 2293/2596/4163 +f 2503/2719/4292 2663/3815/5683 2648/3243/4885 +f 3226/2122/4271 3227/2699/4273 3225/3725/5511 +f 3111/3627/6248 3098/3984/6249 3109/3138/6250 +f 2205/2364/3923 2113/2366/3925 1931/2289/3849 +f 3880/1848/5054 3911/2128/3705 3910/3397/5055 +f 3903/3234/4871 3902/3989/6093 3893/1685/3295 +f 2834/3858/5769 2726/3401/5769 2727/3220/6251 +f 3115/2549/6089 3117/3762/6252 3101/2603/4170 +f 3058/3449/5120 3055/2335/3892 3057/2336/3893 +f 2889/3482/3592 2891/1964/5168 2892/3440/5168 +f 2677/2025/3605 2438/2671/4243 2684/2531/4090 +f 1738/2495/4511 1748/2444/4008 1749/3917/5888 +f 2363/3998/6137 2362/4030/6244 2358/3999/6138 +f 3936/3993/6109 3943/2827/6239 3944/2390/3955 +f 2437/3811/5677 2520/3860/5771 2521/3027/5726 +f 3111/3627/6248 3099/2801/5604 3098/3984/6249 +f 3093/3331/4973 3096/2423/6227 3175/3252/4897 +f 3819/3392/5046 3810/3569/4052 3812/3568/4052 +f 1690/2657/5955 1723/2656/6253 1680/1931/5764 +f 2825/3830/5716 2814/1705/3311 2827/2237/3801 +f 2479/3083/6254 2478/3019/5870 2246/3503/5198 +f 2160/3699/5464 2063/2661/4234 2058/1842/3439 +f 2499/3676/5850 2722/2909/5849 2280/2912/4495 +f 3149/2344/3901 3150/2841/4413 3190/2840/4412 +f 2152/2252/3816 2154/2939/4522 2072/2803/4372 +f 1794/2333/3889 1796/3474/5155 1956/2334/3890 +f 2924/2041/3619 2908/2138/3714 2896/3718/5495 +f 2455/2678/4250 2694/2132/3709 2683/3968/6018 +f 3765/1784/3385 3766/2997/5621 3798/3671/5412 +f 3888/2598/5517 3876/1716/4410 3874/3428/5515 +f 2587/2403/3968 2603/2405/3970 2593/3105/4709 +f 3471/3924/5981 3472/3330/5980 3470/3795/6009 +f 3978/3832/5722 4005/3198/4829 4004/2186/5723 +f 3384/1841/3281 3350/1813/3281 3353/3897/3281 +f 3399/3300/5737 3387/2198/4643 3398/3049/4645 +f 3576/3797/5781 3572/2844/4416 3662/1976/3563 +f 3457/2941/5374 3536/3166/4790 3535/3165/4789 +f 3254/2917/5049 3224/3393/5048 3223/3380/5026 +f 2452/3742/5548 2559/3346/4989 2329/2419/5732 +f 2453/3741/6110 2575/2370/3933 2452/3742/6255 +f 3758/2264/3827 3757/3979/3827 3719/2265/3827 +f 1800/3528/5224 1966/3776/5618 1965/3471/5152 +f 4007/2914/4487 4002/2464/6256 4003/2185/3756 +f 3891/2986/4574 3892/4013/6195 3901/2987/4575 +f 3217/3439/3699 3218/2384/3949 3219/3802/5661 +f 2133/2516/4075 2134/3121/4728 2123/2517/4076 +f 3712/3970/6027 3735/3927/6257 3736/3857/6028 +f 1990/1694/3302 1900/2807/4376 1938/2672/4244 +f 2183/2934/4516 2071/3603/5306 1975/2756/4329 +f 3511/3274/4915 3512/3189/4819 3501/3272/4913 +f 3106/1959/4749 3107/1958/6258 3108/2283/4750 +f 2453/3741/6110 2454/3476/6081 2553/3126/4736 +f 3127/3017/4792 3128/2097/5773 3126/2711/4792 +f 3243/3461/5132 3245/1867/6259 3221/2242/3806 +f 2330/2980/4567 2329/2419/3985 2331/2981/4568 +f 3317/3294/3361 3318/3934/3361 3313/3691/3361 +f 3632/2362/3280 3627/2361/3280 3596/3770/5005 +f 3045/2349/3906 3044/2368/3929 3020/2350/3907 +f 2882/2805/4374 2880/3279/4920 2859/3034/4922 +f 3663/2243/3807 3662/1976/3563 3572/2844/4416 +f 3980/3312/6131 3994/1840/6177 3993/1839/6021 +f 3432/2107/3685 3434/2106/3684 3407/1992/3579 +f 1956/2334/4210 1958/3475/6260 1957/3141/4758 +f 1930/3455/5126 1913/3555/5253 1912/4032/6261 +f 2763/3642/5580 2764/2221/3787 2765/2220/3786 +f 2795/1704/3310 2794/2238/3802 2814/1705/3311 +f 3865/3657/5394 3871/2565/5741 3881/3719/5496 +f 3786/2217/3783 3785/2219/3785 3773/3598/5299 +f 2936/3978/6055 2937/2765/4338 2938/3784/5628 +f 2288/1698/6262 2283/3971/6262 2286/3540/6262 +f 3272/3748/5563 3273/3119/5885 3304/3749/5564 +f 3504/2977/6263 3507/3329/6263 3526/2978/6263 +f 3925/2090/3669 3929/2511/4071 4025/2104/3682 +f 3022/2119/3296 3017/2118/3296 3005/3127/3296 +f 3868/1683/3289 3835/2017/3289 3832/2901/3288 +f 2482/1689/5710 2658/3058/4654 2664/1836/3432 +f 3509/2069/3647 3505/2772/6014 3518/3966/6013 +f 2991/2744/4319 2993/2944/5807 2976/1688/3397 +f 2020/3554/6264 2014/3466/5147 2017/2558/4118 +f 2045/2869/4443 2041/1910/3504 2044/1909/3503 +f 2155/2436/4000 2154/2939/4522 2153/3827/5711 +f 2557/3838/6265 2558/3345/6266 2574/2639/4207 +f 2790/3293/3454 2763/3642/3454 2765/2220/3454 +f 2059/1843/3440 2054/3955/5983 2055/1844/3441 +f 1712/3981/3525 1732/2145/3525 1709/2147/3525 +f 3313/3691/3361 3315/2020/3361 3316/2019/3361 +f 3402/2740/4314 3409/3343/4983 3416/3353/5001 +f 3842/3731/5521 3844/2937/4519 3826/2936/4518 +f 1919/4021/2634 2230/3883/2634 1920/3956/2634 +f 1743/2324/3880 1742/2358/3916 1757/3316/4959 +f 2596/3972/6026 2668/3435/5104 2473/2872/4447 +f 2829/2012/3594 2830/3724/5506 2797/2011/3593 +f 3475/1777/3378 3472/3330/5980 3473/3632/5352 +f 1806/3464/5138 1970/2994/5146 1948/2933/5135 +f 3439/3782/3734 3437/3781/3734 3441/3865/3734 +f 2792/3371/5015 2793/2239/3803 2781/3656/5391 +f 2852/2786/4924 2925/2591/4158 2949/2590/4157 +f 3425/2086/3664 3423/2085/3663 3424/3980/6057 +f 1885/4033/6267 1984/3608/5312 1886/4034/6268 +f 2146/3323/4966 2147/3575/5271 2148/1672/3283 +f 1695/2664/6155 1696/3359/5009 1697/3360/5010 +f 2321/2931/5471 2324/3458/5279 2322/3704/5472 +f 2439/2082/3660 2677/2025/3605 2676/3111/4716 +f 2157/3975/6050 2061/2670/4242 2158/2669/4241 +f 3244/1865/3461 3243/3461/6269 3242/2241/4675 +f 1740/2135/3712 1741/2357/5435 1728/2133/3710 +f 3334/2163/3735 3332/3806/5667 3331/2161/3734 +f 2812/2478/4042 2831/3919/5894 2832/1847/3444 +f 2667/3249/4895 2660/3059/4655 2668/3435/5104 +f 1943/2995/4586 1999/4035/6270 1997/2821/4388 +f 1869/2689/4261 1865/2688/4260 1868/3690/5447 +f 3000/1752/3353 3003/2893/4470 3001/2895/4472 +f 3690/1709/6271 3802/3561/6271 3691/1707/6271 +f 2894/1878/3474 2902/3071/4666 2914/3375/5021 +f 3151/2298/5636 3152/2297/6086 3192/2956/4542 +f 3957/3735/5905 3956/3063/4763 3959/2759/4332 +f 3221/2242/3699 3222/2499/3699 3223/3380/3699 +f 3543/4006/6148 3451/1972/4399 3448/1971/5714 +f 1977/2065/3643 1983/3976/6272 1819/2064/3641 +f 4028/3792/5640 4029/3985/6075 3986/3163/4999 +f 3379/1925/3519 3380/1814/6196 3404/1926/3520 +f 3764/1783/3384 3763/2526/4832 3751/3256/4898 +f 2962/3447/5118 2959/2369/3931 2957/3324/3713 +f 2460/3639/5364 2638/2898/4475 2396/3508/5203 +f 2857/3597/5298 2856/2572/4131 2855/3033/3725 +f 2869/3582/5487 2868/2573/6070 2870/2166/3739 +f 3310/2126/3703 3311/1861/3457 3309/2127/3704 +f 2650/2964/4550 2681/1942/3531 2679/1941/3530 +f 1955/2332/3888 1960/2640/6207 1794/2333/3889 +f 2716/3801/2635 2714/2534/2635 2424/3957/2635 +f 3997/3789/5637 3998/3743/5553 4008/3649/5380 +f 3176/2338/3895 3179/3333/4975 3177/3332/4974 +f 1873/2360/6273 1870/2690/6273 2028/3484/6273 +f 2783/1857/5682 2784/1856/3872 2809/2704/4579 +f 3748/3200/4831 3751/3256/4898 3763/2526/4832 +f 3960/2761/4334 3958/2067/6066 3959/2759/4332 +f 1889/3307/4952 2208/3306/4951 1987/2288/3848 +f 2147/3575/5271 2111/2648/4217 2112/1673/3284 +f 3026/1797/3296 3021/3487/3296 3000/1752/3296 +f 3180/3348/4995 3181/2247/3811 3086/2246/3810 +f 2731/3347/3464 2734/3133/3464 2727/3220/3464 +f 2138/2254/3818 2149/2850/4423 2151/2479/4043 +f 3791/3004/4600 3794/2946/4533 3792/3005/4601 +f 1785/2751/5992 1670/3960/5992 1784/2752/5992 +f 2820/2547/4106 2815/2461/4023 2816/2548/4107 +f 3163/1754/4993 3180/3348/4995 3178/3837/5735 +f 2940/2274/3834 2944/2168/3742 2942/3394/5050 +f 2080/2855/4426 2090/2856/4427 2091/2991/4580 +f 3534/3423/5084 3456/2900/4476 3535/3165/4789 +f 2060/1765/3366 2221/3399/5058 2220/1766/3367 +f 1932/2490/4053 1933/3214/4847 1934/2735/4309 +f 3793/1773/3374 3792/3005/4601 3794/2946/4533 +f 2461/1975/3562 2414/3538/5236 2462/3881/6274 +f 2779/3760/3454 2781/3656/3454 2777/1730/3454 +f 3083/2279/3842 3082/1703/3841 3085/2245/3809 +f 3751/3256/3827 3748/3200/3827 3745/2641/3827 +f 1752/3327/5491 1765/2035/3613 1767/2034/3612 +f 2854/3916/5884 2850/2087/3666 2927/2089/3668 +f 2721/1954/2635 2719/3730/2635 2427/1952/3540 +f 3340/1786/5406 3359/3665/5405 3357/3478/6062 +f 3410/3767/5598 3400/1675/3286 3415/2418/3984 +f 3549/3829/5715 3550/3188/4818 3548/2600/4167 +f 4042/2212/6275 4041/2854/6275 3927/3039/6275 +f 2748/3366/3454 2746/2352/3910 2742/3265/3454 +f 3130/1957/3543 3131/2716/3544 3107/1958/3544 +f 2071/3603/5306 2180/2286/3846 2181/3983/6074 +f 2547/3381/5846 2546/3818/6276 2310/3567/5852 +f 3790/2954/4540 3789/3003/4599 3779/3460/5131 +f 2627/2580/4143 2628/2400/3965 2619/2115/3694 +f 2519/3812/5678 2684/2531/4090 2438/2671/4243 +f 2919/2141/3715 2905/1962/5498 2918/1961/6277 +f 2154/2939/4522 2156/2435/3999 2072/2803/4372 +f 1925/4001/3274 2219/3430/3271 1789/2481/3274 +f 2574/2639/4207 2582/3135/4745 2581/1890/3484 +f 2003/2652/6243 2002/2984/6278 2001/3961/5993 +f 3287/3710/5480 3286/2415/3981 3262/2417/3983 +f 2712/3025/2635 2710/3870/2635 2432/3872/2635 +f 3504/2977/4282 3470/3795/3815 3472/3330/4282 +f 2697/3409/5070 2698/3553/5251 2699/3410/5071 +f 3474/1778/4297 3473/3632/6126 3460/2249/3926 +f 2214/2892/4469 2213/4012/6186 2208/3306/4951 +f 3748/3200/3827 3747/3551/3827 3745/2641/3827 +f 1857/2522/5533 1860/3684/5440 1863/2768/4341 +f 2202/3590/5291 2201/3612/5320 2200/2046/3625 +f 2659/1837/3433 2568/1986/3573 2489/4036/6279 +f 2089/2732/4306 2100/3737/5535 2098/2500/4062 +f 3606/2124/3701 3608/2433/3997 3607/2123/3700 +f 3616/3224/3280 3618/3705/3280 3623/1782/5965 +f 2556/4037/6280 2338/3587/6281 2557/3838/5738 +f 2619/2115/3694 2628/2400/3965 2629/2116/3695 +f 2033/2858/4429 2032/2857/4428 1939/3747/5562 +f 2012/2269/3830 2136/3489/5181 2077/2402/3967 +f 3721/1947/3535 3723/3987/6083 3708/1948/3536 +f 2249/3502/5197 2246/3503/5198 2237/3504/5199 +f 3106/1959/3726 3109/3138/6250 3098/3984/6249 +f 3649/3771/5898 3659/3783/5627 3660/1733/3336 +f 2371/3602/5304 2373/3604/5308 2388/3651/5382 +f 1954/2666/4759 1952/2738/4312 1950/2518/4077 +f 2308/3566/5265 2307/3532/5229 2306/2592/4159 +f 2971/3448/5119 3051/3950/5971 3053/1913/3507 +f 3113/3628/3730 3110/2282/3730 3142/4014/3730 +f 1669/2693/3475 1676/1881/3475 1677/2691/3475 +f 2511/2225/3791 2641/3584/5284 2512/2223/3789 +f 2221/3399/2635 1916/4024/6229 2220/1766/2635 +f 2444/2963/4549 2441/4011/6183 2651/2965/4551 +f 3400/1675/3286 3385/1674/3285 3387/2198/4643 +f 2529/3901/5864 2705/3732/5522 2704/3866/5820 +f 2683/3968/6018 2533/2762/4335 2455/2678/4250 +f 2198/2048/3627 2197/3529/5225 2203/3839/5740 +f 3210/2736/4310 3303/2226/3792 3304/3749/5564 +f 2006/2502/4064 2007/3319/4962 2097/2536/4095 +f 2253/2606/5411 2251/3505/5871 2484/3669/5410 +f 3755/2996/3827 3739/2031/3827 3737/3928/3827 +f 2919/2141/6213 2929/3908/5869 2930/2088/3667 +f 2379/3609/5313 2378/3786/5630 2613/3822/5697 +f 2094/2985/4573 2095/1850/3448 2081/1852/3450 +f 2610/3317/4960 2631/3920/5895 2630/3354/5003 +f 2271/1899/3493 2269/3516/5211 2486/3644/5767 +f 3887/2839/5231 3888/2598/4165 3896/2412/3978 +f 3919/3269/4051 3920/3570/4052 3921/3925/4051 +f 3132/3714/5489 3134/2342/3899 3147/3010/4606 +f 3217/3439/5108 3256/3245/5047 3225/3725/5530 +f 4035/2256/3820 3991/3459/6098 3992/2257/3821 +f 3427/1747/3348 3428/1854/3452 3431/2780/4351 +f 2673/2091/3670 2675/3235/4872 2678/3236/4873 +f 2685/3911/5875 2682/3825/5707 2687/2026/3606 +f 3521/1740/5727 3522/1739/5612 3510/2068/3646 +f 2217/3852/5758 2068/2884/6030 2066/2887/4463 +f 3639/1793/5377 3640/2497/4072 3625/1680/3290 +f 2127/3894/5843 2126/3991/6104 2118/3157/4779 +f 2177/3519/5214 2167/3734/5525 2171/3885/5822 +f 3812/3568/5267 3920/3570/5268 3919/3269/6282 +f 3081/1701/3309 3196/3799/3309 3197/1702/3309 +f 2850/2087/3666 2854/3916/5884 2851/2008/3631 +f 3321/3183/4813 3430/4028/6240 3429/1853/3451 +f 3767/3779/5622 3768/2749/4324 3799/3672/5413 +f 2855/3033/4884 2856/2572/4131 2863/1825/4566 +f 2590/1889/3483 2368/2568/4127 2407/3922/5903 +f 3210/2736/4310 3208/2018/5228 3202/3809/6283 +f 1964/2468/5793 1962/2277/6284 1961/3070/4665 +f 3444/1835/6285 3561/1834/6285 3560/3930/6285 +f 2206/3470/5151 2204/2849/4422 2115/2472/4036 +f 1862/2681/4253 1863/2768/4341 1864/2455/6286 +f 3973/2058/3635 3986/3163/4787 4006/2059/3636 +f 2116/3073/4668 2137/3072/4667 2117/3158/4780 +f 2696/2972/4558 2451/3967/6017 2576/2973/4559 +f 3278/2125/3702 3279/2321/3877 3310/2126/3703 +f 2256/1691/5403 2255/3843/5747 2254/2604/4171 +f 3697/1772/3315 3696/1811/5745 3690/1709/3315 +f 3613/2110/5332 3611/2109/5166 3587/3355/5167 +f 1715/3756/5600 1714/3621/5335 1713/3622/5337 +f 3073/1805/3404 3074/2507/4067 3072/2315/3873 +f 3523/3164/4788 3536/3166/4790 3537/3933/5929 +f 3568/3421/5082 3571/3420/5080 3675/1794/3394 +f 3576/3797/5781 3660/1733/3336 3659/3783/5627 +f 3239/3990/6201 3237/3054/4650 3238/3053/4649 +f 2849/2010/4761 2840/2096/3631 2848/2923/3631 +f 2579/3733/5524 2412/3952/5976 2413/3537/5235 +f 3209/1828/3424 3306/1827/3423 3308/2919/4491 +f 3219/3802/5661 3220/3834/3699 3223/3380/3699 +f 1684/1933/3525 1683/3002/4124 1682/3943/3525 +f 2133/2516/4075 2103/3284/4929 2105/3292/4936 +f 2959/2369/3931 2962/3447/5118 3062/2393/3958 +f 3971/2044/3512 3969/1936/3512 3972/1935/3512 +f 2054/3955/6287 2059/1843/3496 2223/1901/3495 +f 2720/2112/3691 2719/3730/5518 2505/3142/5519 +f 2634/1996/3583 2616/2525/4084 2633/3655/5389 +f 3267/3949/3699 3265/1714/3699 3235/3846/3699 +f 3525/3289/4932 3539/2023/3603 3540/2022/3602 +f 2372/3196/4827 2373/3604/5308 2371/3602/5304 +f 3384/1841/3281 3380/1814/3281 3350/1813/3281 +f 3819/3392/5046 3820/3226/4052 3810/3569/4052 +f 1912/4032/6261 1931/2289/3849 1930/3455/5126 +f 3374/2027/3607 3371/2029/3607 3373/2889/3607 +f 2859/3034/3725 2858/2902/3725 2855/3033/3725 +f 1994/2814/4382 2091/2991/4580 1946/2975/4561 +f 3485/3215/5768 3484/2655/6151 3463/3299/4945 +f 3052/1912/3506 3054/2295/3852 3055/2335/3892 +f 2140/1671/3282 2124/3322/4965 2148/1672/3283 +f 2637/3682/5439 2639/1994/3581 2447/2665/4237 +f 1936/2529/4088 2074/2528/4087 2157/3975/6050 +f 1754/2215/4144 1731/3804/5665 1753/4000/6141 +f 3949/2326/4457 3951/2328/5928 3938/2966/4552 +f 2202/3590/5291 2198/2048/3627 2122/3647/5376 +f 3582/3965/6012 3594/3769/6187 3592/3185/4815 +f 3833/3918/5892 3834/2016/4984 3823/3904/5893 +f 2929/3908/5869 2918/1961/5384 2928/3652/5383 +f 2692/4038/6288 2694/2132/3709 2455/2678/4250 +f 1678/3689/3475 1674/3688/3475 1670/3960/3475 +f 2170/3759/5583 2160/3699/5464 2161/3701/5466 +f 2294/2595/6289 2290/2700/6046 2287/1699/6046 +f 3160/2149/3720 3176/2338/3895 3173/2150/3721 +f 3844/2937/5646 3842/3731/6290 3843/3997/6134 +f 2666/3250/4896 2667/3249/4895 2450/3450/5121 +f 3631/2950/3280 3628/3485/3280 3609/2432/3280 +f 3043/2796/4365 3061/2394/3959 3060/3977/6052 +f 3371/2029/4990 3344/2813/4990 3335/2812/4991 +f 2671/2092/3671 2692/4038/6288 2455/2678/4250 +f 3264/3717/3699 3259/3120/3699 3249/3247/5069 +f 1813/1696/3304 1802/3193/4823 1805/2074/3652 +f 1665/3031/3475 1670/3960/3475 1674/3688/3475 +f 2699/3410/5071 2698/3553/5251 2689/3337/4978 +f 2687/2026/3606 2699/3410/5071 2689/3337/4978 +f 2725/4039/6291 2468/3016/6291 2472/3015/6291 +f 3707/3110/4714 3717/3281/5346 3718/2940/4715 +f 2126/3991/6104 2127/3894/5843 2143/1735/3338 +f 2871/2167/6292 2870/2166/6114 2857/3597/5298 +f 2346/3953/5977 2345/3047/4641 2347/2567/6293 +f 4000/3101/4701 4001/2465/4027 4015/2313/3869 +f 3828/3130/4740 3850/2389/5488 3851/2658/5632 +f 3819/3392/5046 3813/3286/4930 3913/3445/5117 +f 1768/2078/3656 1766/2033/3611 1672/2727/4301 +f 2164/1792/3392 2055/1844/3441 2052/1790/3390 +f 2214/2892/4469 1890/3308/6223 2209/2684/4256 +f 3292/2070/3648 3294/2316/3874 3293/1938/3527 +f 2971/3448/5119 3053/1913/3507 3058/3449/5120 +f 3188/1896/3490 3186/3754/5576 3147/3010/4606 +f 3796/1785/3386 3780/2527/4086 3764/1783/3384 +f 4035/2256/3820 4034/3107/4711 4033/3808/5670 +f 1984/3608/5312 1885/4033/6267 2071/3603/5306 +f 2668/3435/5104 2481/3018/4614 2473/2872/4447 +f 2024/2926/5098 1870/2690/5097 1869/2689/5969 +f 1962/2277/6284 1949/2276/5011 1961/3070/4665 +f 3325/3572/5626 3319/3517/6294 3437/3781/5626 +f 3942/1919/4508 3967/2339/6174 3968/2045/5585 +f 3845/2695/4520 3847/2694/5901 3827/3131/4741 +f 2452/3742/6255 2575/2370/3933 2559/3346/6295 +f 3232/3481/3699 3268/2203/5069 3267/3949/3699 +f 1678/3689/3475 1670/3960/3475 1669/2693/3475 +f 2576/2973/4559 2451/3967/6017 2573/2372/3935 +f 3617/3181/5063 3620/2140/4783 3618/3705/5473 +f 1783/3030/4626 1782/2753/4626 1665/3031/4626 +f 1666/2728/3475 1665/3031/3475 1667/2737/4311 +f 3324/3184/4814 3321/3183/4813 3429/1853/3451 +f 3644/2290/3850 3574/3335/4977 3682/3951/5973 +f 1685/2589/4156 1702/2588/4155 1684/1933/4597 +f 2385/3303/4948 2353/3982/6059 2352/3954/5979 +f 3106/1959/3726 3098/3984/6249 3097/2155/3726 +f 1987/2288/3848 1907/3616/5327 1888/4025/6230 +f 3669/2438/4002 3672/3778/5620 3636/2437/4001 +f 2702/3859/6296 2522/3886/5826 2710/3870/5828 +f 3411/3443/5116 3413/3301/4947 3398/3049/5114 +f 2707/2673/3274 2703/2875/2635 2431/3868/2635 +f 2233/2235/3271 1922/4009/6160 1923/2236/3800 +f 2246/3503/5198 2480/3907/5868 2479/3083/6254 +f 2212/3900/5855 2208/3306/4951 2213/4012/6186 +f 1814/1695/5142 1815/1697/5507 1969/2578/5462 +f 2864/1826/3422 2865/2979/4592 2866/3001/4594 +f 1682/3943/3525 1681/3944/3525 1684/1933/3525 +f 3829/3787/3289 3830/3909/3289 3822/3903/3289 +f 3332/3806/5667 3333/3571/5269 3331/2161/3734 +f 2213/4012/6186 2195/3963/6005 2193/3425/5086 +f 1877/3089/4690 1876/2848/5586 1875/3994/6113 +f 2498/3012/5424 2496/3675/5419 2502/2921/5425 +f 2741/1846/3443 2817/3694/5454 2832/1847/3444 +f 2754/3937/5944 2753/3940/5943 2751/3266/5964 +f 2732/1869/5566 2726/3401/5566 2833/3629/5566 +f 2442/3145/4766 2654/3404/5066 2440/3524/5219 +f 3136/2281/3730 3138/2860/3730 3110/2282/3730 +f 3756/3996/3827 3755/2996/3827 3737/3928/3827 +f 1826/2612/4179 1829/2614/4181 1827/2610/4177 +f 2142/1736/3339 2048/3264/6297 2110/3468/5149 +f 3394/2828/4398 3393/1966/3555 3436/3552/5250 +f 1744/1720/3323 1745/1719/5531 1733/2014/3596 +f 2543/3514/5209 2537/3896/6298 2539/3291/4935 +f 3996/2953/4539 3997/3789/5637 4009/2952/4538 +f 1770/3739/5541 1769/2216/3782 1768/2078/3656 +f 3319/3517/6299 3320/3116/6299 3438/3115/6299 +f 3264/3717/5493 3278/2125/4438 3277/3173/6191 +f 2411/4023/6222 2412/3952/5976 2461/1975/3562 +f 2677/2025/3605 2688/2024/3604 2690/2713/4285 +f 2604/3696/5459 2603/2405/3970 2589/2404/3969 +f 1939/3747/5562 2038/3849/5754 2033/2858/4429 +f 2596/3972/6026 2467/4040/6300 2466/3042/4636 +f 2227/3370/5360 2051/3263/5658 2049/2879/5361 +f 2085/3828/5713 2084/1831/3427 2083/1830/3426 +f 3305/1829/3425 3307/3750/5570 3306/1827/3423 +f 2181/3983/6074 2179/3261/4904 2182/2200/3767 +f 3498/3273/4282 3496/3085/4282 3467/3556/4282 +f 2822/2741/4316 2737/3932/5926 2805/2715/5999 +f 3746/3550/5248 3745/2641/4211 3747/3551/5249 +f 2308/3566/5265 2309/3565/5264 2307/3532/5229 +f 1870/2690/5097 2023/2925/5099 2028/3484/6301 +f 2394/3260/4903 2365/4003/6143 2386/2948/4535 +f 2620/2114/3693 2630/3354/5003 2631/3920/5895 +f 2415/4005/6147 2470/4016/6206 2467/4040/6300 +f 3632/2362/3921 3652/2757/5426 3653/2363/3922 +f 2818/3139/4751 2817/3694/5454 2740/3645/5373 +f 1867/3414/5448 1868/3690/5447 1861/2680/4252 +f 3818/2413/3979 3820/3226/4862 3895/2414/3980 +f 3593/3892/6041 3590/3186/6040 3592/3185/5607 +f 2897/1922/3515 2911/3395/6246 2903/2833/4404 +f 3633/1666/3280 3632/2362/3280 3598/1667/3280 +f 3183/3050/4646 3083/2279/3842 3085/2245/3809 +f 3679/2788/4357 3680/2897/4474 3643/3915/5900 +f 3869/2174/3288 3873/3427/3288 3838/3094/3288 +f 2112/1673/3284 2148/1672/3283 2147/3575/5271 +f 3510/2068/3646 3522/1739/5612 3508/3507/5348 +f 3808/3405/4052 3811/3437/4052 3809/3288/4931 +f 2153/3827/5711 2030/4026/6232 2026/2102/3680 +f 2107/2484/4048 2046/3469/5150 2043/2485/4049 +f 3220/3834/6094 3219/3802/5661 3237/3054/6170 +f 2601/3473/5154 2602/2800/4369 2626/3697/5460 +f 3761/3599/3827 3727/3661/3827 3724/2452/3827 +f 3832/2901/5881 3835/2017/3599 3833/3918/6077 +f 3195/2331/3887 3087/3820/5694 3194/2160/3733 +f 2193/3425/5086 2195/3963/6005 2192/3426/5087 +f 3097/2155/3730 3098/3984/3730 3101/2603/4170 +f 2400/3774/5615 2464/3726/5514 2399/3824/5706 +f 1711/2353/5336 1712/3981/6058 1709/2147/3751 +f 2409/3271/4912 2410/4022/6221 2590/1889/3483 +f 3672/3778/5620 3671/3935/5931 3636/2437/4001 +f 2998/1753/5906 2999/3221/6008 2977/1798/3396 +f 2656/3060/4656 2657/2072/3650 2664/1836/3432 +f 2348/2309/5275 2346/3953/5977 2347/2567/6293 +f 2599/2233/3799 2600/2667/4239 2595/2231/3797 +f 2659/1837/3433 2489/4036/6279 2490/3912/6302 +f 3076/2505/6165 2956/2137/6165 3075/1968/6165 +f 2485/3703/6303 2486/3644/6004 2659/1837/3433 +f 3787/2055/3632 3786/2217/3783 3773/3598/5299 +f 1695/2664/6155 1693/2514/6171 1692/3945/6171 +f 3673/3238/4879 3637/1781/4878 3671/3935/5931 +f 2480/3907/6304 2456/1980/3567 2458/1982/3569 +f 2691/2712/4284 2692/4038/6288 2671/2092/3671 +f 2031/2359/3918 2032/2857/4428 1873/2360/3919 +f 2320/3841/6112 2319/2961/4547 2318/1818/3414 +f 2669/2084/3662 2674/2083/3661 2530/2474/4038 +f 2369/1768/3369 2368/2568/4127 2383/2570/4129 +f 3087/3820/5694 3095/2422/3841 3088/3534/4865 +f 2292/3544/6188 2532/2093/3672 2671/2092/3671 +f 2084/1831/3427 2094/2985/4573 1896/3008/4604 +f 3430/4028/6240 3321/3183/4813 3326/2108/3686 +f 2788/2714/3454 2758/2193/3454 2761/2702/3454 +f 3830/3909/5873 3857/4008/6159 3859/3641/6225 +f 2287/1699/6046 2286/3540/6305 2294/2595/6289 +f 3184/2173/3747 3168/2172/3746 3146/3715/5490 +f 2951/2094/6233 2840/2096/6233 2849/2010/6234 +f 2598/3321/4964 2626/3697/5460 2625/3095/4697 +f 3244/1865/3461 3245/1867/3463 3243/3461/6269 +f 2584/3693/5453 2582/3135/4745 2578/3298/4944 +f 3894/1684/3294 3904/3233/4870 3903/3234/4871 +f 2300/2377/6306 2301/3242/6306 2299/3241/6306 +f 3062/2393/3958 3058/3449/5120 3059/3533/5230 +f 2615/2662/4235 2614/2947/4534 2619/2115/3694 +f 3551/2075/3653 3552/2077/3655 3512/3189/4819 +f 3095/2422/5816 3087/3820/5694 3195/2331/3887 +f 2131/2081/3659 2132/2628/4197 2134/3121/4728 +f 3947/3297/6307 3978/3832/3512 3950/3679/6106 +f 1687/2355/3913 1713/3622/5778 1711/2353/3911 +f 2644/3146/4767 2505/3142/4762 2503/2719/4292 +f 3702/3746/5561 3786/2217/3783 3787/2055/3632 +f 2567/2386/3951 2489/4036/6279 2568/1986/3573 +f 3151/2298/3855 3150/2841/5554 3133/2299/3856 +f 3900/1985/3572 3899/2988/4576 3901/2987/4575 +f 3444/1835/6285 3560/3930/6285 3443/2317/6308 +f 3041/3076/4671 3040/3276/4917 3023/3074/4669 +f 2217/3852/2635 1925/4001/3274 1916/4024/6229 +f 3338/1668/5656 3339/3169/4795 3354/2062/4797 +f 2896/3718/3725 2895/3205/3725 2892/3440/3725 +f 2706/2674/2635 2430/3869/2635 2433/3871/3275 +f 2241/3721/6309 2239/2261/3825 2240/2260/3824 +f 3883/3341/4981 3884/3654/6237 3915/3227/4863 +f 3438/3115/3734 3442/3114/6238 3441/3865/3734 +f 3479/3646/5788 3477/2306/5030 3461/2722/4295 +f 3771/2229/3795 3785/2219/3785 3783/2871/4445 +f 2275/2729/4302 2268/2731/4304 2274/1898/3492 +f 3053/1913/3507 3051/3950/5971 3050/1914/3508 +f 1808/3619/5331 1807/3463/6310 1809/3462/6311 +f 1893/2794/4363 1915/4007/6150 1989/1832/3428 +f 2864/1826/3422 2863/1825/3421 2865/2979/4592 +f 1903/4041/6312 1902/1692/3300 1990/1694/3302 +f 2625/3095/4697 2602/2800/4369 2636/2799/4368 +f 2651/2965/4551 2650/2964/4550 2444/2963/4549 +f 3646/2153/3724 3647/3452/5123 3634/2151/3722 +f 2140/1671/3282 2112/1673/3284 2076/3326/4967 +f 3171/3844/5748 3158/2746/5730 3172/3791/5639 +f 2550/3177/5588 2314/3230/5590 2545/3178/5717 +f 4037/3106/4710 4035/2256/3820 4038/1838/3435 +f 2351/1769/3370 2369/1768/3369 2385/3303/4948 +f 1940/2927/4503 2025/3415/6203 2156/2435/3999 +f 2680/1940/3529 2686/3826/5708 2682/3825/5707 +f 1762/3091/4692 1679/1880/4658 1763/3065/4660 +f 3669/2438/4002 3666/2244/3808 3667/2843/4415 +f 3019/2007/4366 3020/2350/3907 3044/2368/3929 +f 2100/3737/5535 2089/2732/4306 2087/2971/4557 +f 2057/3217/5007 2053/2878/4451 2052/1790/3390 +f 1746/3104/4706 1781/3212/4845 1758/1903/3498 +f 1802/3193/6313 1789/2481/6313 1791/2637/6313 +f 3145/2745/3730 3144/2179/3730 3118/2178/3730 +f 2282/2911/4496 2501/3013/6314 2502/2921/4497 +f 2460/3639/5364 2398/3638/5363 2640/1995/3582 +f 2723/3635/5356 2504/2721/6315 2506/2720/5357 +f 2968/2942/4527 2970/3099/5500 3049/2506/4066 +f 3468/3454/5256 3469/2367/6010 3470/3795/6009 +f 3878/3506/5202 3879/1849/5056 3910/3397/5055 +f 3593/3892/6041 3591/2139/4785 3590/3186/6040 +f 1874/2697/4270 1873/2360/4269 1878/3088/4689 +f 2953/2053/5002 2846/2144/5002 2952/3593/5002 +f 2969/3564/5938 3080/2504/5938 3079/2503/5938 +f 2193/3425/5086 2190/3424/5085 2200/2046/3625 +f 3580/2210/3778 3683/2040/3618 3682/3951/5973 +f 2037/2448/6054 2035/3493/6158 2038/3849/5754 +f 3530/3902/5863 3558/2608/4175 3559/3122/4729 +f 2946/2169/3743 2947/3376/5023 2913/2832/5022 +f 3024/3075/4670 3042/2296/3853 3041/3076/4671 +f 3750/2992/4587 3765/1784/3385 3749/2993/4899 +f 3996/2953/6197 3979/3191/6129 3984/3790/5638 +f 3185/3833/5724 3183/3050/4646 3184/2173/3747 +f 3287/3710/5712 3207/1724/3327 3300/3836/5729 +f 2171/3885/5822 2163/3618/5330 2172/3563/5262 +f 2494/3634/6228 2488/3543/5241 2492/3152/4774 +f 3096/2423/3841 3093/3331/4973 3091/3336/3841 +f 2892/3440/3725 2899/3204/3725 2890/3483/3725 +f 3492/2880/4454 3495/3057/4684 3494/2709/5693 +f 3141/1756/3730 3143/2374/3730 3116/2551/3730 +f 2311/3898/5853 2546/3818/6276 2544/3706/5719 +f 2704/3866/2635 2705/3732/3274 2429/3867/5795 +f 2673/2091/3670 2532/2093/3672 2531/2475/4039 +f 1737/2445/3525 1705/2494/3525 1707/2726/3525 +f 2968/2942/4527 3048/3367/5014 3038/2943/4528 +f 3553/2542/4101 3455/2819/4386 3556/3992/6107 +f 3345/2888/3281 3379/1925/3281 3376/3788/3281 +f 2373/3604/5308 2389/3620/5334 2388/3651/5382 +f 2060/1765/3366 2069/2885/5059 2221/3399/5058 +f 3582/3965/3280 3581/3187/3280 3584/2165/3280 +f 2740/3645/5373 2741/1846/3443 2730/3123/3464 +f 2343/3045/4639 2342/1893/5293 2344/3046/4640 +f 2116/3073/4668 2126/3991/6104 2125/2851/4424 +f 2483/1690/3434 2482/1689/5710 2664/1836/3432 +f 2556/4037/6316 2557/3838/6265 2574/2639/4207 +f 1703/2493/6108 1700/2397/3962 1701/3842/5746 +f 2163/3618/5330 2171/3885/5822 2170/3759/5583 +f 2282/2911/4610 2279/3203/4835 2497/3202/4834 +f 3949/2326/3882 3950/3679/5431 3952/2327/3883 +f 3288/1722/5958 3287/3710/5480 3261/2121/5479 +f 2542/3863/5787 2541/2763/5787 2300/2377/5233 +f 1880/2725/4299 1875/3994/6113 1879/2723/4298 +f 3602/2002/3589 3601/2164/3840 3603/2000/3587 +f 2217/3852/2635 2218/2886/2635 1925/4001/3274 +f 3857/4008/6161 3860/1677/5368 3859/3641/5368 +f 3747/3551/3827 3752/3793/3827 3716/3549/3827 +f 3840/1949/3537 3843/3997/6134 3842/3731/6290 +f 3857/4008/6161 3858/1678/6231 3860/1677/5368 +f 2598/3321/4964 2605/3318/4961 2597/3311/4955 +f 3972/1935/3512 3973/2058/3512 3971/2044/3512 +f 2175/3530/5226 2197/3529/5225 2176/3562/5261 +f 2907/3259/4902 2916/3258/4901 2917/1960/3548 +f 1985/2781/4352 1883/4018/6209 1884/3607/5311 +f 4023/2584/4150 4024/2103/3681 4022/3199/4830 +f 2901/3403/5065 2922/3028/6007 2900/2156/3727 +f 3690/1709/6271 3801/3444/6317 3802/3561/6271 +f 3539/2023/3603 3537/3933/5929 3538/2036/3614 +f 3234/3495/5189 3235/3846/5751 3236/3052/4648 +f 3825/3592/5520 3839/1950/5799 3840/1949/6144 +f 2185/3084/4681 1804/3022/4618 1968/3021/4617 +f 3518/3966/6013 3517/3850/5756 3530/3902/5863 +f 2594/2232/3798 2595/2231/3797 2448/3035/4629 +f 3522/1739/3340 3533/1741/3342 3534/3423/5084 +f 2636/2799/4368 2446/3687/5444 2623/3109/4713 +f 2710/3870/5828 2712/3025/4621 2702/3859/6296 +f 3729/3964/6011 3731/3712/5485 3711/3413/5484 +f 2048/3264/6297 2046/3469/5150 2110/3468/5149 +f 2189/3520/5215 2177/3519/5214 2199/2047/3626 +f 2643/3823/5705 2511/2225/3791 2509/3678/5429 +f 2664/1836/3432 2658/3058/4654 2656/3060/4656 +f 3498/3273/4282 3501/3272/4282 3496/3085/4282 +f 3556/3992/6107 3555/3239/4880 3554/2458/4020 +f 2690/2713/4285 2691/2712/4284 2678/3236/4873 +f 3997/3789/5637 4008/3649/5380 4009/2952/4538 +f 3114/2550/6045 3115/2549/6089 3100/2802/5603 +f 3061/2394/3959 3044/2368/3929 2959/2369/3931 +f 1936/2529/4088 2186/2734/4308 1934/2735/4309 +f 3571/3420/5080 3676/1795/3395 3675/1794/3394 +f 2534/3257/4900 2535/2676/4248 2533/2762/4335 +f 3204/1723/3326 3202/3809/6283 3203/1761/3362 +f 2215/2891/4468 2216/2890/4467 2194/2492/4055 +f 2796/1823/3419 2813/4029/6242 2829/2012/3594 +f 3748/3200/3827 3752/3793/3827 3747/3551/3827 +f 2484/3669/6166 2478/3019/4615 2481/3018/4614 +f 2644/3146/4767 2643/3823/5705 2509/3678/5429 +f 3722/2450/3827 3719/2265/3827 3757/3979/3827 +f 2728/3400/3464 2726/3401/3464 2733/1868/3465 +f 3705/3535/3827 3706/3630/3827 3711/3413/3827 +f 2133/2516/4075 2078/3282/4927 2103/3284/4929 +f 1770/3739/5541 1771/3328/4971 1769/2216/3782 +f 3023/3074/3296 2992/2945/3296 2989/3722/3296 +f 3945/3296/3512 3977/2060/3512 3947/3297/6307 +f 3084/2280/3843 3187/3958/5990 3189/1895/3489 +f 3455/2819/4386 3557/2607/4174 3556/3992/6107 +f 3286/2415/6132 3287/3710/5712 3300/3836/5729 +f 2753/3940/3454 2783/1857/3454 2778/3814/3454 +f 2273/3525/5220 2272/1900/6318 2487/3702/5468 +f 3755/2996/3827 3750/2992/3827 3739/2031/3827 +f 2546/3818/6276 2311/3898/5853 2310/3567/5852 +f 2894/1878/3725 2878/1727/3725 2881/2829/3725 +f 1929/3995/6116 1947/3211/4843 1976/3893/5838 +f 2475/2439/4111 2417/4027/6236 2416/3757/5577 +f 1942/3320/4963 1999/4035/6270 1943/2995/4586 +f 2790/3293/4937 2785/3339/5963 2799/2476/4040 +f 2949/2590/4157 2947/3376/5023 2948/3280/4925 +f 3163/1754/3355 3141/1756/3357 3142/4014/6200 +f 2125/2851/4424 2146/3323/4966 2124/3322/4965 +f 2813/4029/6242 2796/1823/3419 2795/1704/3310 +f 2538/3240/4881 2301/3242/4883 2540/3290/5657 +f 3247/3048/4642 3222/2499/4061 3245/1867/6259 +f 3776/3124/5961 3695/3055/4651 3788/2056/3633 +f 3222/2499/4061 3221/2242/3806 3245/1867/6259 +f 1698/2395/5910 1696/3359/5950 1683/3002/4596 +f 2221/3399/2635 2222/3398/2635 1916/4024/6229 +f 2309/3565/5264 2310/3567/5266 2311/3898/5959 +f 4005/3198/4829 3977/2060/6153 4006/2059/4148 +f 1802/3193/4823 1803/3020/6319 1804/3022/5565 +f 2458/1982/3569 2474/2440/4446 2473/2872/4447 +f 2613/3822/5697 2614/2947/4534 2379/3609/5313 +f 2219/3430/3271 1790/2482/3274 1789/2481/3274 +f 2007/3319/5989 2006/2502/5509 1844/3667/5899 +f 2574/2639/4207 2558/3345/6266 2575/2370/3933 +f 2768/2539/4098 2765/2220/3786 2766/2222/3788 +f 1913/3555/5253 2106/2080/3658 1989/1832/3428 +f 2746/2352/3910 2745/3624/3454 2744/3623/3454 +f 2699/3410/5071 2571/2775/4346 2572/3036/4630 +f 3934/3032/4627 4011/2378/3943 4013/3102/4702 +f 3514/2460/4022 3499/2823/4391 3500/2545/4104 +f 2496/3675/5419 2495/3201/5418 2504/2721/4294 +f 2686/3826/5708 2435/1821/3417 2687/2026/3606 +f 2254/2604/6320 2253/2606/5411 2482/1689/3297 +f 3144/2179/3730 3139/3486/3730 3120/2177/3730 +f 3206/3295/3361 3209/1828/3361 3205/1860/3361 +f 2177/3519/5214 2176/3562/5261 2199/2047/3626 +f 1861/2680/4252 1863/2768/4341 1862/2681/4253 +f 3552/2077/3655 3513/2544/4103 3512/3189/4819 +f 3352/2061/3638 3353/3897/6122 3351/3765/5596 +f 1995/2816/4384 1992/2811/4380 1993/1929/3523 +f 3187/3958/5990 3185/3833/5724 3184/2173/3747 +f 3902/3989/6093 3814/3986/6321 3900/1985/3572 +f 3941/1918/4509 3963/3077/5946 3965/2340/4510 +f 2069/2885/5059 2068/2884/6030 2222/3398/5057 +f 3448/1971/5714 3545/2602/4169 3544/3708/5477 +f 2077/2402/3967 2136/3489/5181 2135/3283/4928 +f 2910/1921/3514 2909/3417/5076 2939/2275/3835 +f 1760/3547/5245 1758/1903/3498 1781/3212/4845 +f 3986/3163/4999 3987/3162/4786 4028/3792/5640 +f 3699/2866/5701 3697/1772/3373 3797/1891/3485 +f 3903/3234/4871 3906/1882/3476 3811/3437/5106 +f 3355/2063/3640 3354/2062/3639 3356/2555/4115 +f 2778/3814/3454 2779/3760/3454 2752/1729/3454 +f 3162/1755/5834 3163/1754/4993 3178/3837/5735 +f 3716/3549/3827 3753/2263/3827 3719/2265/3827 +f 1797/2769/4342 1799/2770/4344 1802/3193/4823 +f 4014/2312/3868 3934/3032/4627 4013/3102/4702 +f 2542/3863/2635 2534/3257/2635 2541/2763/2635 +f 2766/2222/6157 2764/2221/3909 2747/2351/3908 +f 2254/2604/6320 2482/1689/3297 2256/1691/3299 +f 2462/3881/6274 2563/2308/6322 2461/1975/3562 +f 3459/2250/3928 3468/3454/5125 3466/2808/4377 +f 2017/2558/4118 2072/2803/4372 2016/2556/4116 +f 3982/3061/5623 3983/2466/4028 4001/2465/4027 +f 2861/3488/5662 2889/3482/5804 2887/3611/6119 +f 2645/3144/4765 2654/3404/5066 2442/3145/4766 +f 3581/3187/4817 3589/3161/5801 3619/3180/4810 +f 2525/3681/5436 2527/2675/5438 2523/3862/6065 +f 3674/3777/5619 3670/3422/5083 3568/3421/5082 +f 2965/2136/5842 2958/1787/3387 3064/1789/3389 +f 2117/3158/4780 2137/3072/4667 2128/2515/4074 +f 2029/2100/3678 2026/2102/3680 2030/4026/6232 +f 1890/3308/6223 1891/4042/6323 1986/2685/4257 +f 3333/3571/5269 3332/3806/5667 3412/3583/5282 +f 2523/3862/6065 2522/3886/6100 2437/3811/5677 +f 2360/2410/3976 2388/3651/5382 2387/2411/3977 +f 2305/2593/5540 2298/2375/3940 2300/2377/3942 +f 3345/2888/3281 3376/3788/3281 3374/2027/3281 +f 3213/1775/3376 3211/1760/3361 3212/3711/3362 +f 3884/3654/6237 3916/2469/4032 3915/3227/4863 +f 2047/2004/3591 2050/2003/3590 2051/3263/4907 +f 2124/3322/4965 2150/2480/4044 2125/2851/4424 +f 3434/2106/3684 3328/3206/4838 3435/2560/4120 +f 4026/2583/4149 4006/2059/4148 3986/3163/4999 +f 2518/3026/4622 2711/3873/6176 2713/3876/5814 +f 2010/2501/5510 1848/2645/5839 1846/2644/5508 +f 2694/2132/3709 2692/4038/6288 2691/2712/4284 +f 2030/4026/6232 1939/3747/5562 2032/2857/4428 +f 3940/2066/3644 3960/2761/5283 3961/3441/5945 +f 2867/2571/4130 2865/2979/4565 2856/2572/4131 +f 3760/2291/3827 3732/2293/3827 3730/3948/3827 +f 3735/3927/6257 3712/3970/6027 3733/3713/5486 +f 2161/3701/5466 2163/3618/5330 2170/3759/5583 +f 1722/3237/3525 1728/2133/3525 1719/2563/3525 +f 2632/2968/4554 2621/2663/4236 2631/3920/5895 +f 2106/2080/3658 2113/2366/3925 2131/2081/3659 +f 3237/3054/6170 3239/3990/6095 3220/3834/6094 +f 3018/3373/5018 3030/3594/5365 3029/3372/5016 +f 3152/2297/6086 3193/3821/5695 3192/2956/4542 +f 3339/3169/4795 3340/1786/5406 3357/3478/6062 +f 2558/3345/6266 2559/3346/6295 2575/2370/3933 +f 2381/3613/5325 2383/2570/4129 2382/2569/4128 +f 2602/2800/4369 2450/3450/5121 2596/3972/6026 +f 3945/3296/3512 3971/2044/3512 3973/2058/3512 +f 3332/3806/5667 3414/3805/5666 3412/3583/5282 +f 3409/3343/4983 3410/3767/5598 3415/2418/3984 +f 2869/3582/3725 2872/2154/3725 2904/2143/3725 +f 3686/1945/3533 3684/2541/3533 3685/1943/3532 +f 2384/2862/4434 2374/2864/4436 2372/3196/4827 +f 2196/3773/5614 2203/3839/5740 2174/1791/3391 +f 2581/1890/3484 2590/1889/3483 2574/2639/4207 +f 3204/1723/3326 3210/2736/4310 3202/3809/6283 +f 2136/3489/5181 2099/3974/6038 2101/3490/5182 +f 3198/2633/3841 3199/2632/3841 3201/3798/3841 +f 1964/2468/4031 1798/2467/4030 1792/2561/5606 +f 4018/2913/4486 4003/2185/3756 4019/2187/3758 +f 3060/3977/6052 3056/2294/3851 3042/2296/3853 +f 1851/2574/4137 1849/3615/5326 1850/2575/4138 +f 3142/4014/3730 3141/1756/3730 3113/3628/3730 +f 2276/4020/6324 2277/3154/5222 2265/3526/5221 +f 2578/3298/4944 2576/2973/4559 2573/2372/3935 +f 3851/2658/4230 3854/2566/4232 3853/3752/5573 +f 2596/3972/6026 2415/4005/6147 2467/4040/6300 +f 3296/3192/4822 3284/2204/3771 3297/1776/3377 +f 1952/2738/5544 1954/2666/4238 1791/2637/4204 +f 1681/3944/5953 1682/3943/5952 1694/3942/5951 +f 3889/3727/6194 3890/3518/5213 3898/1984/3571 +f 1774/3432/5095 1776/3315/4958 1775/3314/4957 +f 1886/4034/6268 1984/3608/5312 1887/4043/6325 +f 3328/3206/4838 3436/3552/5250 3435/2560/4120 +f 3612/1737/3687 3613/2110/3689 3614/1738/4860 +f 3046/3845/5750 3045/2349/3906 3016/2348/3905 +f 3480/3386/3815 3510/2068/3815 3478/2307/4282 +f 3728/3659/5398 3727/3661/5400 3730/3948/6102 +f 3153/3969/6061 3154/2158/3731 3194/2160/3733 +f 2873/2904/4479 2871/2167/6292 2857/3597/5298 +f 2424/3957/2635 2426/3167/2635 2716/3801/2635 +f 1931/2289/3849 1911/4044/6326 1910/3277/4918 +f 3425/2086/3664 3424/3980/6057 3429/1853/3451 +f 2210/2683/4255 2211/2202/3769 2216/2890/4467 +f 2591/3134/4744 2627/2580/4143 2618/3342/4982 +f 2783/1857/3454 2753/3940/3454 2755/1858/3454 +f 2841/3498/5193 2934/2043/3621 2933/2042/3620 +f 3701/2453/6099 3805/2512/6327 3804/3358/6099 +f 2714/2534/2635 2713/3876/3271 2424/3957/2635 +f 2633/3655/5389 2446/3687/5444 2447/2665/4237 +f 3249/3247/4891 3248/2498/4890 3247/3048/6175 +f 3382/1965/3281 3383/1967/3281 3368/3419/3281 +f 3399/3300/4946 3398/3049/5114 3413/3301/4947 +f 3270/3457/6069 3265/1714/3320 3282/1713/3319 +f 2514/3223/4858 2512/2223/3789 2641/3584/5284 +f 3897/2599/4166 3821/2489/4753 3896/2412/3978 +f 3018/3373/3296 3015/2873/3296 3013/2874/3296 +f 4020/3835/5728 4021/2105/3683 3929/2511/4071 +f 3246/1866/3699 3244/1865/3699 3263/2865/3699 +f 3165/3304/4949 3169/2171/3745 3182/3921/5896 +f 3349/3764/5972 3348/3103/5528 3337/1669/5527 +f 3435/2560/4120 3392/3087/6079 3391/2559/4119 +f 3753/2263/4731 3777/3794/5643 3776/3124/4732 +f 2596/3972/6026 2466/3042/4636 2403/3931/5925 +f 2358/3999/6138 2357/2718/4291 2360/2410/3976 +f 3140/3716/3730 3133/2299/3730 3125/3685/3730 +f 3092/2957/4543 3192/2956/4542 3193/3821/5695 +f 2264/3633/5687 2276/4020/6324 2265/3526/5221 +f 2500/3677/5422 2496/3675/5419 2504/2721/4294 +f 2292/3544/6188 2294/2595/6289 2286/3540/6305 +f 3726/3660/5399 3725/3988/6135 3727/3661/5400 +f 2296/3861/5772 2291/3545/5243 2292/3544/5242 +f 3814/3986/6321 3816/1983/3570 3900/1985/3572 +f 2961/2837/3713 2966/3171/3713 2960/2983/3713 +f 2051/3263/5658 2227/3370/5360 2229/3369/5659 +f 3068/2427/3990 3069/2486/4050 3070/2302/3859 +f 2066/2887/4760 2068/2884/4459 2067/2883/4458 +f 2690/2713/4285 2689/3337/4978 2698/3553/5251 +f 3961/3441/5945 3941/1918/4509 3940/2066/3644 +f 2694/2132/3709 2693/2131/3708 2683/3968/6018 +f 4030/1871/3467 3987/3162/4786 3988/3658/5397 +f 2103/3284/4929 2085/3828/5713 2104/3197/4828 +f 2390/3878/5808 2463/2524/4083 2402/4010/6180 +f 2464/3726/5514 2401/3775/5616 2463/2524/4083 +f 1724/2134/3525 1722/3237/3525 1691/2305/3525 +f 3419/2834/4406 3420/3132/4743 3417/1875/3471 +f 2326/3581/5546 2452/3742/5548 2329/2419/5732 +f 2560/1974/3561 2561/3905/6328 2461/1975/3562 +f 2243/2441/4005 2244/3497/6219 2475/2439/4003 +f 1799/2770/4344 1967/2284/4343 1966/3776/5618 +f 3556/3992/6107 3554/2458/4020 3553/2542/4101 +f 4030/1871/3467 3988/3658/5397 4032/1872/3468 +f 2755/1858/3764 2754/3937/5944 2756/2194/3765 +f 4044/2706/4280 3924/2707/4280 4040/2852/6329 +f 2843/2924/4500 2922/3028/4624 2932/2922/4498 +f 2208/3306/4951 2212/3900/5855 1987/2288/3848 +f 2186/2734/4308 2157/3975/6330 2162/3117/4722 +f 2025/3415/6203 2022/2457/4370 2156/2435/3999 +f 3373/2889/4466 3346/3673/5415 3345/2888/4464 +f 2312/3831/6096 2313/3232/4869 2302/3947/5960 +f 3998/3743/5553 3999/3100/4700 4012/2380/3945 +f 2109/1998/3585 2142/1736/3339 1937/1999/3586 +f 2644/3146/4767 2503/2719/4292 2645/3144/4765 +f 2191/2491/4054 2187/3248/4892 2166/3913/5879 +f 2126/3991/6104 2116/3073/4668 2118/3157/4779 +f 2627/2580/4143 2591/3134/4744 2583/2831/4402 +f 3202/3809/5671 3313/3691/5671 3314/3810/5672 +f 2222/3398/2635 2217/3852/2635 1916/4024/6229 +f 2719/3730/5518 2721/1954/5358 2506/2720/5357 +f 4034/3107/4711 4037/3106/4710 3932/3041/4635 +f 2479/3083/4680 2480/3907/6304 2458/1982/3569 +f 2646/2073/3651 2657/2072/3650 2655/3244/4886 +f 2853/2906/4480 2847/2764/4337 2846/2144/5351 +f 2983/2586/4153 2982/3402/5060 2984/2679/5038 +f 3937/2392/3957 3936/3993/6109 3944/2390/3955 +f 2908/2138/3714 2935/2406/3971 2938/3784/5628 +f 2598/3321/4964 2600/2667/4239 2601/3473/5154 +f 2269/3516/6331 2263/3513/6115 2486/3644/5371 +f 2495/3201/5418 2569/3151/4773 2662/3275/4916 +f 3892/4013/6332 3891/2986/5512 3869/2174/3748 +f 2945/2907/4481 2853/2906/4480 2844/2787/4923 +f 2786/3170/4979 2769/3729/3454 2771/2797/3454 +f 2763/3642/6333 2760/3175/4804 2762/3668/6333 +f 2154/2939/4522 2140/1671/3282 2153/3827/5711 +f 3636/2437/4136 3637/1781/3382 3621/1780/3381 +f 2590/1889/3483 2407/3922/5903 2408/3270/4911 +f 1806/3464/5138 1812/2582/5140 1971/2989/5139 +f 2162/3117/4722 2168/2206/3773 2186/2734/4308 +f 2728/3400/6019 2733/1868/5113 2826/3153/4775 +f 2879/2830/4401 2880/3279/5094 2881/2829/4400 +f 2854/3916/5884 2852/2786/3631 2851/2008/3631 +f 2563/2308/6322 2564/1973/3560 2461/1975/3562 +f 2071/3603/5306 1976/3893/5838 1977/2065/5305 +f 2034/2859/6235 2036/2847/4419 1876/2848/4421 +f 3519/1764/3365 3518/3966/6013 3559/3122/4729 +f 1797/2769/4342 1963/2285/4029 1967/2284/4343 +f 2712/3025/4621 2521/3027/4623 2520/3860/6334 +f 3257/3761/3699 3258/2120/3699 3255/3246/3699 +f 3206/3295/3361 3208/2018/5228 3209/1828/3361 +f 2386/2948/4535 2615/2662/4235 2393/3006/4602 +f 3047/2426/3989 3034/1803/3402 3069/2486/4050 +f 2450/3450/5121 2602/2800/4369 2601/3473/5154 +f 3574/3335/4977 3580/2210/3778 3682/3951/5973 +f 3765/1784/3385 3764/1783/3384 3749/2993/4899 +f 1748/2444/4008 1747/1905/3500 1759/1904/3499 +f 4042/2212/6275 3927/3039/6275 3926/2213/6275 +f 1674/3688/5445 1778/2323/3879 1777/2325/3881 +f 1958/3475/6260 1959/2635/5966 1957/3141/4758 +f 3327/2162/5794 3441/3865/5794 3442/3114/5794 +f 3340/1786/5406 3341/3254/6071 3360/3664/5404 +f 1885/4033/6267 1929/3995/6116 2071/3603/5306 +f 1667/2737/4311 1772/3149/4770 1770/3739/5541 +f 2457/1981/3568 2474/2440/4446 2458/1982/3569 +f 2854/3916/5884 2926/3653/5385 2925/2591/4158 +f 3542/3709/5478 3541/2021/3601 3543/4006/6148 +f 2348/2309/3866 2563/2308/3865 2462/3881/5812 +f 2099/3974/6038 2136/3489/5181 2009/2268/3829 +f 2931/3856/5765 2919/2141/6213 2930/2088/3667 +f 2910/1921/3514 2911/3395/6246 2897/1922/3515 +f 2682/3825/5707 2685/3911/5875 2679/1941/3530 +f 3209/1828/3424 3210/2736/4310 3304/3749/5564 +f 3431/2780/4351 3429/1853/3451 3430/4028/6240 +f 2606/3097/4699 2598/3321/4964 2625/3095/4697 +f 2299/3241/6335 2304/2594/4161 2305/2593/4160 +f 2206/3470/5151 1937/1999/6336 2204/2849/4422 +f 2556/4037/6280 2340/1894/3488 2338/3587/6281 +f 1749/3917/5956 1761/3548/5246 1762/3091/4692 +f 2847/2764/4337 2841/3498/5193 2839/2095/6133 +f 3378/3557/3281 3377/3531/3281 3370/2320/3281 +f 1724/2134/3525 1728/2133/3525 1722/3237/3525 +f 2324/3458/5279 2323/3579/5278 2322/3704/5472 +f 2925/2591/4158 2917/1960/5802 2916/3258/6337 +f 2181/3983/6074 1984/3608/5312 2071/3603/5306 +f 3454/2899/4954 3446/2817/6338 3563/3309/4954 +f 3717/3281/5346 3706/3630/5347 3715/3962/6164 +f 2504/2721/6315 2723/3635/5356 2500/3677/5851 +f 2030/4026/6232 2153/3827/5711 1939/3747/5562 +f 3365/2960/4546 3366/3082/4679 3368/3419/5079 +f 3313/3691/6204 3202/3809/6204 3208/2018/6204 +f 2441/4011/6183 2444/2963/4549 2440/3524/5219 +f 2767/2538/4097 2770/3479/5161 2769/3729/5549 +f 2011/2270/6339 2015/3467/6339 1856/3813/6339 +f 2801/3357/5008 2802/2463/4025 2791/2687/4259 +f 2014/3466/5147 2013/2401/3966 2072/2803/4372 +f 3336/1670/5526 3348/3103/5528 3346/3673/6152 +f 3609/2432/3280 3628/3485/3280 3607/2123/3280 +f 2226/3218/2635 2225/3364/2635 1917/3959/5991 +f 3921/3925/6161 3817/2488/6340 3815/2487/6231 +f 2353/3982/6059 2372/3196/4827 2354/3195/4826 +f 3289/3946/6162 3271/2228/3794 3302/2227/3793 +f 2151/2479/4043 2149/2850/4423 2150/2480/4044 +f 2750/3262/3454 2749/3365/3454 2742/3265/3454 +f 2521/3027/5726 2519/3812/5678 2437/3811/5677 +f 2031/2359/3918 2029/2100/3678 2030/4026/6232 +f 1853/2523/6064 1852/2576/4139 1856/3813/6341 +f 1876/2848/4421 1878/3088/5997 2034/2859/6235 +f 3084/2280/3843 3083/2279/3842 3185/3833/5724 +f 1801/3472/6342 1803/3020/6319 1802/3193/4823 +f 2958/1787/3713 2956/2137/3713 2957/3324/3713 +f 2489/4036/6279 2567/2386/3951 2488/3543/5241 +f 2143/1735/3338 2144/1734/3337 2145/3576/5272 +f 2746/2352/3910 2744/3623/3454 2742/3265/3454 +f 2193/3425/5086 2212/3900/5855 2213/4012/6186 +f 3364/2959/6216 3362/2958/6072 3341/3254/6071 +f 2028/3484/5169 2023/2925/4501 1940/2927/4503 +f 2561/3905/6328 2562/2638/4205 2574/2639/4207 +f 3008/3128/4738 3007/3882/5815 3006/3129/4739 +f 3619/3180/5064 3589/3161/4784 3620/2140/4783 +f 1710/3051/6199 1711/2353/5336 1709/2147/3751 +f 2110/3468/5149 2107/2484/4048 2111/2648/4217 +f 2959/2369/3931 3045/2349/3930 3063/1788/3388 +f 3288/1722/3325 3289/3946/6162 3204/1723/3326 +f 3991/3459/6098 4035/2256/3820 4033/3808/5670 +f 2274/1898/3492 2270/3515/5210 2271/1899/3493 +f 2141/2470/4034 2143/1735/3338 2127/3894/5843 +f 2537/3896/6298 2538/3240/4933 2539/3291/4935 +f 3016/2348/3905 3015/2873/5017 3028/3707/5749 +f 2611/3108/4712 2606/3097/4699 2624/3096/4698 +f 3775/1758/3359 3776/3124/5961 3788/2056/3633 +f 3269/3179/4808 3270/3457/6069 3281/2825/5685 +f 3451/1972/4399 3543/4006/6148 3541/2021/3601 +f 1986/2685/4257 1891/4042/6323 1892/2782/4353 +f 2428/1953/2635 2722/2909/2635 2723/3635/2635 +f 3869/2174/3748 3893/1685/3295 3892/4013/6332 +f 3765/1784/3385 3798/3671/5412 3797/1891/3485 +f 3188/1896/3490 3189/1895/3489 3187/3958/5990 +f 1951/2519/4757 1953/2739/6343 1788/2483/4755 +f 1689/1932/3525 1688/2209/3525 1684/1933/3525 +f 1909/3278/4919 1908/2287/3847 1931/2289/3849 +f 2549/3854/5856 2548/2932/4514 2318/1818/5858 +f 2010/2501/4063 2009/2268/3829 2008/3800/6101 +f 2775/2196/3501 2774/1906/3501 2776/1728/4133 +f 1825/2621/5743 2005/3840/5742 1839/2626/6168 +f 2640/1995/3582 2464/3726/5514 2634/1996/3583 +f 3928/3040/4634 4033/3808/5670 4034/3107/4711 +f 2606/3097/4699 2611/3108/4712 2610/3317/4960 +f 2562/2638/5101 2345/3047/5865 2344/3046/5102 +f 3235/3846/3699 3232/3481/3699 3267/3949/3699 +f 1853/2523/6064 1856/3813/6341 1854/3939/6344 +f 1680/1931/5764 1723/2656/6253 1721/3137/4747 +f 1915/4007/6150 1914/3350/4997 1988/3349/4996 +f 2064/3396/5053 2062/1767/3368 2220/1766/3367 +f 2876/1726/3329 2879/2830/4401 2878/1727/3330 +f 3205/1860/3361 3216/1859/3455 3206/3295/3361 +f 3741/1742/5020 3738/2030/3608 3740/2032/3610 +f 3170/3674/5417 3195/2331/3887 3156/2330/3886 +f 2142/1736/3339 2141/2470/4034 2204/2849/4422 +f 3562/3539/3559 3560/3930/3559 3565/1833/3559 +f 2641/3584/5284 2511/2225/3791 2642/3523/5218 +f 3458/2810/3815 3465/2446/3815 3464/2251/3815 +f 3135/2343/3730 3131/2716/3730 3129/2905/3730 +f 2614/2947/4534 2613/3822/5697 2618/3342/4982 +f 3330/3431/5333 3324/3184/4814 3419/2834/4406 +f 1948/2933/5135 1973/2755/5089 1810/1955/5134 +f 1857/2522/5533 1855/2521/5941 2015/3467/5534 +f 2179/3261/4904 2181/3983/6074 2180/2286/3846 +f 3174/3772/5613 3096/2423/6227 3095/2422/5816 +f 3511/3274/4915 3547/3796/5647 3550/3188/4818 +f 3328/3206/3734 3326/2108/5212 3325/3572/5579 +f 2410/4022/6221 2461/1975/3562 2590/1889/3483 +f 1840/2629/6167 2005/3840/5742 1837/2624/5988 +f 2054/3955/6287 2223/1901/3495 2225/3364/6172 +f 2485/3703/6303 2659/1837/3433 2487/3702/6345 +f 3338/1668/5656 3351/3765/6346 3349/3764/5972 +f 2554/3125/4733 2553/3126/4736 2552/3477/6082 +f 1937/1999/3586 2206/3470/5151 2196/3773/5614 +f 2020/3554/6264 2021/3736/6347 2014/3466/5147 +f 3674/3777/5619 3675/1794/3394 3673/3238/4879 +f 2557/3838/5738 2338/3587/6281 2335/3066/5739 +f 1960/2640/4208 1957/3141/4758 1961/3070/4665 +f 2461/1975/3562 2561/3905/6328 2574/2639/4207 +f 2575/2370/3933 2553/3126/4736 2570/2371/3934 +f 2613/3822/5697 2612/2990/4578 2617/1888/3482 +f 2277/3154/4776 2276/4020/6220 2493/3155/4777 +f 2335/3066/4661 2336/3585/5285 2334/3067/4662 +f 3261/2121/3699 3262/2417/3699 3228/2698/3699 +f 2555/1892/4206 2556/4037/6316 2574/2639/4207 +f 3380/1814/3281 3379/1925/3281 3347/1815/3281 +f 3662/1976/3563 3663/2243/3807 3664/1977/3564 +f 3846/1718/3289 3875/1717/3289 3849/2388/3289 +f 1787/2191/5592 1783/3030/5592 1666/2728/5592 +f 1781/3212/4845 1668/2692/4844 1760/3547/5245 +f 2008/3800/5650 2011/2270/5680 1852/2576/5651 +f 3228/2698/4272 3231/3408/6217 3229/2382/5393 +f 3689/1944/5482 3685/1943/5482 3567/2267/5482 +f 2749/3365/6078 2772/1908/6015 2748/3366/5784 +f 3572/2844/4416 3576/3797/3533 3573/3255/3533 +f 2295/2597/4164 2288/1698/3306 2290/2700/4274 +f 3199/2632/3841 3200/3895/3841 3201/3798/3841 +f 2360/2410/3976 2370/2717/4290 2388/3651/5382 +f 3773/3598/5299 3774/1757/3358 3782/2748/4323 +f 2684/2531/4090 2519/3812/5678 2685/3911/5875 +f 3051/3950/5971 2971/3448/5119 2968/2942/4527 +f 2847/2764/4337 2941/2273/3833 2939/2275/3835 +f 1826/2612/4179 1823/2611/4178 1822/2778/4349 +f 3150/2841/4413 3151/2298/5636 3191/2842/4414 +f 3512/3189/5499 3502/2710/5004 3501/3272/6348 +f 3298/3086/4687 3300/3836/5729 3299/1774/3375 +f 2738/3000/3464 2734/3133/3464 2739/3140/4752 +f 2612/2990/4578 2381/3613/5325 2382/2569/4128 +f 3676/1795/3395 3571/3420/5080 3677/2496/4056 +f 3902/3989/6093 3811/3437/5106 3814/3986/6321 +f 1806/3464/5978 1807/3463/6310 1808/3619/5331 +f 2516/3222/4857 2519/3812/5678 2521/3027/5726 +f 3809/3288/4931 3907/1884/3478 3909/2129/3706 +f 1809/3462/6311 1810/1955/3541 1808/3619/5331 +f 3428/1854/3452 3427/1747/3348 3426/1855/3453 +f 1904/2651/4220 1903/4041/6312 1990/1694/3302 +f 3778/3056/4652 3779/3460/5131 3789/3003/4599 +f 2270/3515/5210 2269/3516/5211 2271/1899/3493 +f 1858/2767/5329 2016/2556/4116 2073/2456/4018 +f 2607/2399/3964 2608/3723/5505 2629/2116/3695 +f 3060/3977/6052 3059/3533/5230 3056/2294/3851 +f 3013/2874/3296 3016/2348/3296 2982/3402/3296 +f 2228/3216/4852 2053/2878/5441 2057/3217/4853 +f 2967/2301/3858 2965/2136/5842 3066/2938/4521 +f 2230/3883/2635 2231/3803/2635 1921/3744/2635 +f 2716/3801/5653 2718/3631/6025 2513/2224/5810 +f 2004/3780/5625 1833/2618/5912 1831/2616/5624 +f 4002/2464/6256 4007/2914/4487 4017/3143/4764 +f 3996/2953/6197 3995/3936/6130 3979/3191/6129 +f 2558/3345/4987 2335/3066/5739 2333/3068/4988 +f 3169/2171/3745 3166/3305/4950 3168/2172/3746 +f 3348/3103/4705 3349/3764/5595 3350/1813/4703 +f 2220/1766/3367 2224/1902/3497 2064/3396/5053 +f 2018/2557/4117 2019/3436/5105 2017/2558/4118 +f 2604/3696/5459 2589/2404/3969 2588/4002/6142 +f 2273/3525/5220 2487/3702/5468 2490/3912/5878 +f 3921/3925/4051 3922/3941/4051 3919/3269/4051 +f 2611/3108/4712 2632/2968/4554 2631/3920/5895 +f 2021/3736/6347 2015/3467/5148 2014/3466/5147 +f 2474/2440/4004 2457/1981/5867 2247/3500/5862 +f 2163/3618/5330 2161/3701/5466 2164/1792/3392 +f 3333/3571/5269 3322/3560/6238 3323/3574/3734 +f 3324/3184/4814 3330/3431/3734 3320/3116/3734 +f 2167/3734/5525 2178/3521/5216 2166/3913/5879 +f 1887/4043/6325 1984/3608/5312 1884/3607/5311 +f 3575/3334/4976 3680/2897/4474 3678/2896/4473 +f 1774/3432/5095 1775/3314/4957 1740/2135/3712 +f 2019/3436/5105 2020/3554/6264 2017/2558/4118 +f 2517/2533/5433 2515/2532/5432 2514/3223/4858 +f 2997/1751/3296 2995/3914/3296 3027/1796/3296 +f 1966/3776/6140 1967/2284/3844 2180/2286/3846 +f 2210/2683/4255 1892/2782/4353 1985/2781/4352 +f 2939/2275/3835 2909/3417/5076 2938/3784/5628 +f 2589/2404/3969 2577/2373/3936 2572/3036/4630 +f 3584/2165/3280 3583/1917/3280 3582/3965/3280 +f 2555/1892/3486 2340/1894/3488 2556/4037/6280 +f 2292/3544/6188 2286/3540/6305 2528/2473/4037 +f 2451/3967/6017 2697/3409/5070 2572/3036/4630 +f 3800/3037/4631 3799/3672/5413 3768/2749/4324 +f 3661/1978/3565 3664/1977/3564 3654/3228/4864 +f 2702/3859/6296 2712/3025/4621 2520/3860/6334 +f 2468/3016/4613 2469/4015/6205 2471/3014/4611 +f 2925/2591/4158 2916/3258/6337 2915/1876/3472 +f 3973/2058/3512 3977/2060/3512 3945/3296/3512 +f 2026/2102/3680 2027/2101/3679 2028/3484/5169 +f 3099/2801/5604 3111/3627/6248 3112/3626/5605 +f 2650/2964/4550 2652/1989/3576 2701/2774/4345 +f 2456/1980/5861 2480/3907/5868 2248/3501/5196 +f 2935/2406/3971 2936/3978/6055 2938/3784/5628 +f 3116/2551/4110 3114/2550/4109 3113/3628/5344 +f 2780/1822/3454 2773/1907/3454 2775/2196/3454 +f 2701/2774/4345 2681/1942/3531 2650/2964/4550 +f 4001/2465/4027 4002/2464/6256 4017/3143/4764 +f 3298/3086/4687 3299/1774/3375 3297/1776/3377 +f 3784/2218/3784 3702/3746/5561 3703/3753/5575 +f 3141/1756/3357 3162/1755/3356 3161/2337/4532 +f 3319/3517/6299 3438/3115/6299 3437/3781/6349 +f 2649/1990/3577 2440/3524/5219 2653/1988/3575 +f 2896/3718/6350 2900/2156/3727 2924/2041/3729 +f 3134/2342/4289 3132/3714/3730 3131/2716/3730 +f 2040/1911/3505 2042/2449/4440 2037/2448/6054 +f 1990/1694/3302 2092/1928/3522 1991/1930/3524 +f 2674/2083/3661 2531/2475/4039 2530/2474/4038 +f 3406/1746/3347 3405/1927/3665 3425/2086/3664 +f 2593/3105/4709 2586/2189/3760 2587/2403/3968 +f 3643/3915/5882 3631/2950/5176 3630/3929/6351 +f 2070/2520/4079 1961/3070/4665 1957/3141/4758 +f 3039/2381/3946 3040/3276/4917 3052/1912/3506 +f 3285/2416/3982 3284/2204/3771 3266/3407/5392 +f 1873/2360/4269 1872/2696/4268 1871/3864/6352 +f 2170/3759/5583 2158/2669/4241 2160/3699/5464 +f 1931/2289/3849 1912/4032/6261 1911/4044/6326 +f 2236/3492/6192 2235/3379/2635 1924/3378/2635 +f 2063/2661/4234 2064/3396/5617 2065/2660/4233 +f 1688/2209/3525 1687/2355/3525 1684/1933/3525 +f 2103/3284/4929 2104/3197/4828 2105/3292/4936 +f 2487/3702/5468 2272/1900/6318 2271/1899/3493 +f 3822/3903/5891 3830/3909/5873 3859/3641/6225 +f 2613/3822/5697 2378/3786/5630 2612/2990/4578 +f 2246/3503/5198 2250/3851/5757 2237/3504/5199 +f 3527/2976/4562 3526/2978/4564 3542/3709/5478 +f 1786/2192/3475 1785/2751/3475 1782/2753/3475 +f 2900/2156/3725 2864/1826/3725 2866/3001/3725 +f 3409/3343/4983 3415/2418/3984 3416/3353/5001 +f 3102/1801/3400 3101/2603/4170 3119/2303/3860 +f 3101/2603/4170 3117/3762/6252 3119/2303/3860 +f 2736/1864/3465 2737/3932/3465 2734/3133/3464 +f 2905/1962/3550 2907/3259/4902 2917/1960/3548 +f 2809/2704/4278 2823/2180/3752 2729/2705/4279 +f 3861/3848/5753 3859/3641/5368 3862/2935/5369 +f 1829/2614/4221 1826/2612/4571 2003/2652/4222 +f 2154/2939/4522 2155/2436/4000 2156/2435/3999 +f 2341/3591/5292 2339/3588/5288 2340/1894/5289 +f 2439/2082/3660 2437/3811/5677 2438/2671/4243 +f 2670/3884/5860 2524/2877/5720 2525/3681/5436 +f 1680/1931/5764 1681/3944/5953 1690/2657/5955 +f 2097/2536/4095 2098/2500/4062 2006/2502/4064 +f 1942/3320/4963 1943/2995/4586 2093/2537/4096 +f 3430/4028/6240 3326/2108/3686 3432/2107/3685 +f 2046/3469/5817 2231/3803/5664 2230/3883/5818 +f 2443/2962/4548 2642/3523/5218 2440/3524/5219 +f 3530/3902/5863 3559/3122/4729 3518/3966/6013 +f 2630/3354/5003 2629/2116/3695 2608/3723/5505 +f 3352/2061/5655 3351/3765/6346 3338/1668/5656 +f 2166/3913/5879 2187/3248/4892 2165/2205/3772 +f 3506/2771/4390 3516/2609/6211 3517/3850/5756 +f 2100/3737/5535 2101/3490/5182 2099/3974/6038 +f 2389/3620/5334 2366/3541/5239 2387/2411/3977 +f 2169/2207/3774 2168/2206/3773 2162/3117/4722 +f 2061/2670/4242 2157/3975/6050 2067/2883/4458 +f 2740/3645/5373 2739/3140/4752 2818/3139/4751 +f 2951/2094/3673 2950/2054/3673 2839/2095/3673 +f 2181/3983/6074 2182/2200/3767 1985/2781/4352 +f 2132/2628/4197 2113/2366/3925 2121/2365/3924 +f 2056/3356/6173 2054/3955/6287 2225/3364/6172 +f 1864/2455/6286 1863/2768/4341 1858/2767/4340 +f 2748/3366/3454 2747/2351/3908 2746/2352/3910 +f 3342/3253/6185 3366/3082/6184 3364/2959/6216 +f 2013/2401/3966 2077/2402/3967 2139/2253/3817 +f 3153/3969/6020 3140/3716/5492 3154/2158/3731 +f 3681/2039/3617 3644/2290/3850 3682/3951/5973 +f 3231/3408/6217 3232/3481/5165 3230/2383/5164 +f 2778/3814/5681 2811/3159/5883 2779/3760/5587 +f 2488/3543/5241 2490/3912/6302 2489/4036/6279 +f 4010/2379/3944 4011/2378/3943 4009/2952/4538 +f 3062/2393/3958 3059/3533/5230 3061/2394/3959 +f 2036/2847/6035 2034/2859/6353 2033/2858/4429 +f 2877/1725/3725 2878/1727/3725 2906/1877/3725 +f 2013/2401/3966 2152/2252/3816 2072/2803/4372 +f 4003/2185/5390 3981/3617/5328 4004/2186/5723 +f 2941/2273/3833 2945/2907/4481 2944/2168/3742 +f 3902/3989/6093 3903/3234/4871 3811/3437/5106 +f 3748/3200/6354 3779/3460/6354 3752/3793/6354 +f 2756/2194/5934 2744/3623/5339 2757/3625/5341 +f 2232/2929/2635 1919/4021/2635 1922/4009/6160 +f 2763/3642/6333 2761/2702/4276 2760/3175/4804 +f 2226/3218/4854 2057/3217/4853 2056/3356/6173 +f 2490/3912/6302 2487/3702/6345 2659/1837/3433 +f 1892/2782/4353 2210/2683/4255 1986/2685/4257 +f 2545/3178/5717 2314/3230/5590 2312/3831/5718 +f 2283/3971/6023 2284/3081/4484 2285/3080/6024 +f 1973/2755/5089 1974/2754/5133 1817/3429/5090 +f 1727/2013/3595 1726/2454/4016 1743/2324/3880 +f 3874/3428/3288 3876/1716/3289 3843/3997/3288 +f 2847/2764/4337 2936/3978/6055 2935/2406/3971 +f 1936/2529/4088 1934/2735/4309 1935/2530/4089 +f 3483/2654/4224 3480/3386/5037 3481/2345/6039 +f 3977/2060/3512 3978/3832/3512 3947/3297/6307 +f 3396/3558/5449 3386/2197/4644 3381/3926/5913 +f 3942/1919/3512 3936/3993/3512 3939/1920/3513 +f 3186/3754/5576 3188/1896/3490 3187/3958/5990 +f 2502/2921/4497 2499/3676/5850 2280/2912/4495 +f 2147/3575/5271 2146/3323/4966 2145/3576/5272 +f 1847/2643/4214 1845/3666/5407 1846/2644/4215 +f 1859/2766/4339 1860/3684/5440 2020/3554/5252 +f 1668/2692/3475 1678/3689/3475 1669/2693/3475 +f 2202/3590/5291 2122/3647/5376 2121/2365/3924 +f 1771/3328/4971 1770/3739/5541 1772/3149/4770 +f 1863/2768/6355 1853/2523/4082 1857/2522/4081 +f 2419/3973/6031 2420/4004/6146 2596/3972/6026 +f 1800/3528/5224 1801/3472/6342 1802/3193/4823 +f 3268/2203/5069 3232/3481/3699 3231/3408/3699 +f 2035/3493/5188 2235/3379/5031 2236/3492/5184 +f 2847/2764/4337 2853/2906/4480 2941/2273/3833 +f 3580/2210/3533 3569/3683/3533 3577/2183/3533 +f 2448/3035/4629 2589/2404/3969 2572/3036/4630 +f 2292/3544/6188 2528/2473/4037 2532/2093/3672 +f 3092/2957/4543 3090/3229/4866 3191/2842/4414 diff --git a/examples/Cassie/urdf/meshes/agility/tarsus.obj b/examples/Cassie/urdf/meshes/agility/tarsus.obj new file mode 100644 index 0000000000..fcfebf9df9 --- /dev/null +++ b/examples/Cassie/urdf/meshes/agility/tarsus.obj @@ -0,0 +1,24843 @@ +# Blender v3.0.1 OBJ File: 'cassie-meshes.blend' +# www.blender.org +o tarsus +v 0.382000 0.017317 0.035177 +v 0.087000 0.016810 0.037235 +v 0.382000 0.014667 0.041572 +v 0.087000 0.012452 0.044447 +v 0.382000 0.008512 0.047560 +v 0.087000 0.006444 0.048285 +v 0.087000 -0.000351 0.049603 +v 0.382000 0.000454 0.049508 +v 0.382000 -0.007970 0.047845 +v 0.087000 -0.007281 0.047929 +v 0.087000 -0.013930 0.042978 +v 0.382000 -0.015069 0.041106 +v 0.087000 -0.017517 0.033773 +v 0.382000 -0.017732 0.031592 +v 0.087000 -0.015890 0.024121 +v 0.382000 -0.014686 0.022290 +v 0.087000 -0.010155 0.017731 +v 0.382000 -0.007233 0.015805 +v 0.087000 -0.002542 0.014447 +v 0.382000 0.000956 0.014512 +v 0.087000 0.007223 0.015944 +v 0.382000 0.009219 0.016848 +v 0.087000 0.013857 0.021139 +v 0.382000 0.016473 0.025425 +v 0.087000 0.017317 0.028823 +v 0.410640 -0.020505 0.032202 +v 0.379339 -0.020484 0.032902 +v 0.412232 -0.020295 0.028540 +v 0.344052 -0.020591 0.030889 +v 0.380329 0.020484 0.033577 +v 0.344020 0.020659 0.032049 +v 0.381097 0.020121 0.036653 +v 0.343995 0.019086 0.039723 +v 0.380534 0.019280 0.039206 +v 0.343982 0.015382 0.045673 +v 0.380978 0.017085 0.043550 +v 0.380521 0.013628 0.047458 +v 0.343981 0.010005 0.049985 +v 0.380553 0.009772 0.050099 +v 0.343999 0.001809 0.052638 +v 0.380734 0.005885 0.051743 +v 0.380262 0.000946 0.052546 +v 0.380314 -0.004127 0.052177 +v 0.344036 -0.007164 0.051327 +v 0.380770 -0.009303 0.050385 +v 0.343974 -0.013077 0.047886 +v 0.380355 -0.014347 0.046839 +v 0.344005 -0.017555 0.042769 +v 0.381715 -0.018312 0.041676 +v 0.380892 -0.019233 0.039377 +v 0.343994 -0.019881 0.037186 +v 0.380746 -0.020074 0.036640 +v 0.343979 -0.018993 0.024078 +v 0.407728 -0.018229 0.022710 +v 0.344013 -0.015285 0.018193 +v 0.405288 -0.016234 0.019543 +v 0.402527 -0.012620 0.016016 +v 0.343977 -0.009827 0.013920 +v 0.400716 -0.009284 0.013840 +v 0.398887 -0.005175 0.012126 +v 0.343998 -0.004148 0.011877 +v 0.343990 0.002904 0.011564 +v 0.398691 0.000227 0.011577 +v 0.398713 0.005049 0.012076 +v 0.343982 0.010144 0.014093 +v 0.401108 0.010264 0.014335 +v 0.344013 0.015486 0.018416 +v 0.403543 0.014820 0.017831 +v 0.407559 0.018344 0.022725 +v 0.343984 0.019139 0.024429 +v 0.413101 0.020276 0.029179 +v 0.408855 0.020499 0.031781 +v 0.410591 -0.012100 0.051828 +v 0.404900 -0.016592 0.052194 +v 0.410063 -0.019218 0.051792 +v 0.396871 -0.015367 0.052646 +v 0.395053 -0.014463 0.052748 +v 0.394885 -0.017999 0.052823 +v 0.403411 -0.013289 0.052277 +v 0.397694 -0.018444 0.052623 +v 0.397627 -0.012204 0.052603 +v 0.399583 -0.012735 0.052493 +v 0.403158 -0.019230 0.052204 +v 0.399801 -0.019882 0.051976 +v 0.397078 -0.020308 0.051757 +v 0.411444 -0.020425 0.050361 +v 0.401130 0.012100 0.044308 +v 0.406079 0.012100 0.048059 +v 0.397741 0.012189 0.052597 +v 0.410576 0.012100 0.051831 +v 0.395180 0.012207 0.047173 +v 0.397815 0.012064 0.034654 +v 0.403379 0.012100 0.033217 +v 0.400075 0.012100 0.038134 +v 0.385608 0.011977 0.051174 +v 0.400676 0.012100 0.043574 +v 0.412429 0.012100 0.046832 +v 0.414038 0.012100 0.034328 +v 0.418215 0.012100 0.033499 +v 0.416138 0.012100 0.041553 +v 0.403766 0.012045 0.017130 +v 0.408607 0.012100 0.031939 +v 0.419210 0.012100 0.044668 +v 0.415547 0.012100 0.049457 +v 0.420027 0.012100 0.038682 +v 0.383207 0.013598 0.048394 +v 0.383557 0.010070 0.050934 +v 0.389667 0.017989 0.049137 +v 0.383365 0.017144 0.044787 +v 0.383369 -0.015378 0.046974 +v 0.389436 -0.017760 0.049245 +v 0.385583 -0.011968 0.051187 +v 0.383721 -0.010351 0.050873 +v 0.399975 0.020500 0.038996 +v 0.394158 0.020353 0.046898 +v 0.400729 0.020500 0.043620 +v 0.402259 0.020500 0.034135 +v 0.400267 -0.020500 0.037027 +v 0.400659 -0.020500 0.043513 +v 0.394598 -0.020420 0.046674 +v 0.404855 -0.020500 0.032490 +v 0.384303 0.019204 0.042191 +v 0.382277 0.003806 0.052666 +v 0.382322 -0.004434 0.052601 +v 0.401180 0.020500 0.044182 +v 0.403010 0.020500 0.046365 +v 0.409216 0.020500 0.048285 +v 0.414937 0.020500 0.044262 +v 0.416076 0.020500 0.039563 +v 0.414426 0.020500 0.035000 +v 0.397077 0.020309 0.051754 +v 0.411851 0.020400 0.050212 +v 0.395269 0.020395 0.047129 +v 0.417224 0.020363 0.034088 +v 0.418670 0.020471 0.039032 +v 0.417044 0.020427 0.046019 +v 0.401130 -0.020500 0.044308 +v 0.406079 -0.020500 0.048059 +v 0.394250 -0.020062 0.047636 +v 0.412429 -0.020500 0.046832 +v 0.415200 -0.020500 0.036198 +v 0.418107 -0.020390 0.035595 +v 0.415941 -0.020500 0.042075 +v 0.417498 -0.020299 0.045955 +v 0.418701 -0.020426 0.041849 +v 0.400729 -0.012100 0.043619 +v 0.399975 -0.012100 0.038996 +v 0.402259 -0.012100 0.034135 +v 0.408843 -0.012100 0.031770 +v 0.414426 -0.012100 0.035000 +v 0.416076 -0.012100 0.039563 +v 0.414118 -0.012100 0.045717 +v 0.407531 -0.012100 0.048128 +v 0.403010 -0.012100 0.046365 +v 0.401180 -0.012100 0.044182 +v 0.395664 -0.009655 0.033564 +v 0.395695 0.009914 0.033594 +v 0.402414 -0.010469 0.015625 +v 0.402347 0.010204 0.015562 +v 0.397610 -0.012030 0.034621 +v 0.403937 -0.012068 0.017312 +v 0.418211 -0.012100 0.033495 +v 0.394997 -0.012231 0.047264 +v 0.420027 -0.012100 0.038685 +v 0.415544 -0.012100 0.049458 +v 0.419213 -0.012100 0.044659 +v 0.413521 -0.019529 0.050513 +v 0.415940 -0.019086 0.048991 +v 0.418229 -0.019264 0.046205 +v 0.419912 -0.019158 0.041743 +v 0.419722 -0.019232 0.037686 +v 0.418292 -0.019329 0.033784 +v 0.411468 0.018739 0.025971 +v 0.417549 0.019209 0.032824 +v 0.408994 -0.017627 0.023054 +v 0.405307 0.015267 0.018971 +v 0.395173 0.014253 0.052741 +v 0.397868 0.013553 0.052589 +v 0.394801 0.017872 0.052833 +v 0.397367 0.018382 0.052696 +v 0.409930 0.019537 0.051731 +v 0.404852 0.015370 0.052196 +v 0.403319 0.019295 0.052206 +v 0.402137 0.012735 0.052349 +v 0.414360 0.019108 0.050226 +v 0.416685 0.019607 0.048097 +v 0.419069 0.019420 0.044416 +v 0.420033 0.019193 0.040182 +v 0.419108 0.019559 0.035783 +v 0.395382 0.017834 0.048860 +v 0.397213 0.019733 0.047947 +v 0.399918 0.019813 0.051985 +v 0.399736 0.019573 0.046690 +v 0.401595 0.017244 0.045763 +v 0.400607 0.013395 0.046255 +v 0.397578 0.012686 0.047765 +v 0.395309 0.014654 0.048896 +v 0.397426 -0.019840 0.047841 +v 0.401128 -0.018633 0.045995 +v 0.394887 -0.016620 0.049106 +v 0.401099 -0.014082 0.046010 +v 0.397374 -0.012531 0.047867 +v 0.393180 0.018804 0.048169 +v 0.392573 0.014825 0.048472 +v 0.413811 -0.019672 0.028980 +v 0.419408 0.020032 0.040294 +v 0.392373 -0.015511 0.048572 +v 0.396326 -0.011202 0.033943 +v 0.396639 0.011538 0.034132 +v 0.342000 -0.019242 0.028953 +v 0.342000 -0.016668 0.022013 +v 0.341998 -0.010510 0.015433 +v 0.342000 -0.001075 0.012548 +v 0.341998 0.008597 0.014364 +v 0.342000 0.015481 0.020258 +v 0.341998 0.019291 0.028425 +v 0.341998 0.017985 0.039840 +v 0.341999 0.011784 0.047514 +v 0.342000 0.004347 0.050991 +v 0.342000 -0.003861 0.051096 +v 0.341999 -0.011384 0.047810 +v 0.341998 -0.018183 0.039596 +v 0.392202 -0.019680 0.047876 +v 0.412264 0.020500 0.045916 +v 0.410031 0.020350 0.047804 +v 0.414087 0.020476 0.045125 +v 0.415116 0.020500 0.040608 +v 0.415900 0.020445 0.039390 +v 0.402452 0.020500 0.044436 +v 0.402370 0.020404 0.045764 +v 0.406321 0.020500 0.046942 +v 0.406042 0.020426 0.047647 +v 0.413202 0.020500 0.034889 +v 0.414931 0.020390 0.036097 +v 0.412607 0.020419 0.033558 +v 0.403289 0.020500 0.034684 +v 0.402559 0.020445 0.034240 +v 0.400790 0.020500 0.039386 +v 0.400746 0.020412 0.036800 +v 0.400020 0.020393 0.040766 +v 0.408633 0.020453 0.031991 +v 0.407524 0.020500 0.032874 +v 0.401152 -0.020500 0.038111 +v 0.404273 -0.020500 0.033797 +v 0.410263 -0.020500 0.033179 +v 0.413631 -0.020500 0.035770 +v 0.415116 -0.020500 0.039392 +v 0.413202 -0.020500 0.045111 +v 0.408612 -0.020500 0.047017 +v 0.404072 -0.020500 0.046078 +v 0.401222 -0.020500 0.042013 +v 0.407535 -0.020426 0.032088 +v 0.411855 -0.020349 0.032944 +v 0.403024 -0.020436 0.046239 +v 0.400452 -0.020427 0.042495 +v 0.413456 -0.020428 0.045722 +v 0.408673 -0.020439 0.047874 +v 0.415122 -0.020425 0.036495 +v 0.415528 -0.020434 0.042526 +v 0.400110 -0.020396 0.039152 +v 0.402629 -0.020502 0.034228 +v 0.405047 -0.020001 0.047542 +v 0.411472 -0.019989 0.047271 +v 0.415522 0.020002 0.043009 +v 0.416097 -0.020001 0.039795 +v 0.405967 0.020005 0.032119 +v 0.403882 -0.020002 0.033040 +v 0.400982 -0.020002 0.035996 +v -0.017117 0.011250 0.019513 +v 0.008636 0.011250 0.022155 +v 0.000946 0.011250 0.026406 +v -0.025352 0.011250 0.003332 +v -0.014536 0.011250 -0.020039 +v -0.002324 0.011250 -0.024667 +v 0.009146 0.011250 -0.022925 +v -0.024096 0.011250 -0.005920 +v -0.021344 0.011250 -0.012224 +v 0.018325 0.011250 -0.016587 +v 0.127003 0.015579 0.020821 +v 0.127006 0.019285 0.032572 +v 0.127001 0.015499 0.043121 +v 0.127002 0.007730 0.049548 +v 0.127001 0.007690 0.014542 +v 0.127001 -0.001130 0.012957 +v 0.127001 -0.002204 0.050953 +v 0.127003 -0.010712 0.016096 +v 0.127001 -0.010657 0.047823 +v 0.127001 -0.017223 0.023796 +v 0.127001 -0.016067 0.042143 +v 0.127004 -0.019098 0.033703 +v 0.397105 0.015088 0.052377 +v 0.399001 0.014985 0.051525 +v 0.397148 0.017354 0.052358 +v 0.399717 0.017977 0.051168 +v 0.398355 0.019203 0.051757 +v 0.399312 0.012732 0.051285 +v 0.402234 0.013644 0.049815 +v 0.401679 0.015788 0.050190 +v 0.403295 0.016522 0.049305 +v 0.401393 0.019575 0.050248 +v 0.395988 0.017538 0.039686 +v 0.394931 0.014294 0.040374 +v 0.393286 0.016224 0.040947 +v 0.396181 0.015091 0.039707 +v 0.394843 0.018182 0.040413 +v 0.393230 0.015383 0.041530 +v 0.396703 0.017371 0.048110 +v 0.393625 0.017618 0.041350 +v 0.398290 0.018441 0.047308 +v 0.399962 0.017280 0.046485 +v 0.396840 0.016324 0.039747 +v 0.399998 0.015157 0.046459 +v 0.398168 0.014129 0.047377 +v 0.396610 0.015224 0.048148 +v 0.396182 0.013654 0.048534 +v 0.395262 0.016190 0.048989 +v 0.399910 0.019341 0.046686 +v 0.401286 0.017486 0.045985 +v 0.401352 0.015058 0.045959 +v 0.395848 0.018330 0.048718 +v 0.397628 0.019644 0.047809 +v 0.399255 0.012792 0.047002 +v 0.397999 0.014698 0.048672 +v 0.400395 0.016257 0.047478 +v 0.397989 0.017795 0.048677 +v 0.398644 -0.015594 0.051703 +v 0.397377 -0.014319 0.052248 +v 0.397150 -0.017563 0.052346 +v 0.399879 -0.012739 0.051014 +v 0.401621 -0.016906 0.050219 +v 0.401736 -0.019275 0.050063 +v 0.403151 -0.017114 0.049367 +v 0.399759 -0.017931 0.051147 +v 0.399076 -0.019618 0.051407 +v 0.402592 -0.013930 0.049644 +v 0.400506 -0.014569 0.050775 +v 0.393986 -0.017584 0.040615 +v 0.395867 -0.015194 0.039671 +v 0.396191 -0.017407 0.039672 +v 0.393591 -0.015158 0.040776 +v 0.393294 -0.015325 0.041517 +v 0.396683 -0.015154 0.048122 +v 0.397767 -0.014234 0.047566 +v 0.395211 -0.014142 0.040539 +v 0.399255 -0.014424 0.046831 +v 0.396773 -0.015596 0.039789 +v 0.400180 -0.015884 0.046369 +v 0.399720 -0.017684 0.046598 +v 0.395449 -0.018238 0.040448 +v 0.398391 -0.018352 0.047272 +v 0.393655 -0.017763 0.041320 +v 0.396664 -0.017452 0.048120 +v 0.395761 -0.018139 0.048755 +v 0.395258 -0.015265 0.048990 +v 0.400328 -0.013483 0.046488 +v 0.401592 -0.016227 0.045827 +v 0.397729 -0.012748 0.047747 +v 0.400298 -0.019032 0.046486 +v 0.397710 -0.019743 0.047774 +v 0.398421 -0.017931 0.048462 +v 0.400385 -0.016448 0.047483 +v 0.397204 -0.016052 0.049069 +v 0.399168 -0.014569 0.048090 +v 0.402107 0.008772 0.015842 +v 0.395411 0.008805 0.034239 +v 0.402842 0.008805 0.016145 +v 0.396146 0.008772 0.034541 +v 0.395400 -0.008772 0.034270 +v 0.396157 -0.008805 0.034510 +v 0.402096 -0.008805 0.015874 +v 0.402853 -0.008772 0.016114 +v 0.394655 0.008772 0.035000 +v 0.383426 0.008805 0.051036 +v 0.395286 0.008805 0.035482 +v 0.384057 0.008772 0.051519 +v 0.383407 -0.008772 0.051063 +v 0.384076 -0.008805 0.051491 +v 0.394636 -0.008805 0.035027 +v 0.395305 -0.008772 0.035455 +v 0.045953 0.025809 0.011372 +v 0.039076 0.025852 0.010497 +v 0.037961 0.026122 0.016960 +v 0.055626 0.025998 0.008066 +v 0.046027 0.025904 0.007082 +v 0.037301 0.025886 0.007367 +v 0.039795 0.025830 0.005109 +v 0.034185 0.025889 0.020655 +v 0.034665 0.025829 0.023462 +v 0.066104 0.025999 0.009176 +v 0.068407 0.026021 0.007977 +v 0.073409 0.025978 0.010677 +v 0.078651 0.026001 0.014897 +v 0.075709 0.026000 0.014867 +v 0.082491 0.025999 0.024837 +v 0.084060 0.025997 0.023593 +v 0.083529 0.025894 0.036907 +v 0.086074 0.025966 0.033466 +v 0.080420 0.025999 0.047449 +v 0.084372 0.025999 0.043988 +v 0.081696 0.025958 0.049036 +v 0.075963 0.026000 0.055554 +v 0.070839 0.025999 0.056798 +v 0.070700 0.026005 0.058975 +v 0.029271 0.026008 0.061940 +v 0.047126 0.025996 0.057830 +v 0.038973 0.025800 0.051157 +v 0.033304 0.025767 0.052550 +v 0.059195 0.025999 0.060022 +v 0.061208 0.026000 0.061977 +v 0.032694 0.025789 0.038414 +v 0.030479 0.025804 0.035917 +v 0.028056 0.025852 0.038977 +v 0.035191 0.025772 0.045514 +v 0.024074 0.025790 0.039971 +v -0.016105 0.025951 0.028849 +v 0.008057 0.025784 0.032837 +v 0.005807 0.025922 0.029225 +v -0.024066 0.025871 0.008721 +v -0.022535 0.025894 0.019582 +v -0.022328 0.025962 -0.006696 +v -0.010300 0.025899 -0.021190 +v -0.018878 0.025849 -0.014055 +v -0.002392 0.025912 -0.023281 +v 0.024429 0.025916 0.005167 +v 0.030258 0.025802 0.003716 +v 0.030456 0.025948 0.000734 +v 0.022972 0.025961 -0.006544 +v 0.005838 0.025922 -0.022530 +v 0.013764 0.025892 -0.019069 +v 0.032918 0.025830 0.028779 +v 0.031303 0.025823 0.028048 +v 0.007408 0.025822 0.023747 +v 0.020565 0.025789 0.013446 +v 0.014366 0.025789 0.019838 +v 0.060967 -0.026000 0.061981 +v 0.057518 -0.020676 0.061892 +v 0.055440 -0.023246 0.061977 +v 0.034747 -0.024043 0.061154 +v 0.037140 -0.026000 0.062000 +v 0.046660 -0.023696 0.061858 +v 0.036983 -0.025780 0.050264 +v 0.028829 -0.026000 0.058154 +v 0.032963 -0.025705 0.048653 +v -0.018592 -0.025946 0.022519 +v -0.017061 -0.025972 0.021260 +v -0.015057 -0.025865 0.026262 +v 0.032539 -0.025882 0.041706 +v 0.047659 -0.025734 0.058395 +v 0.084212 -0.025999 0.040544 +v 0.086359 -0.025994 0.033709 +v 0.084119 -0.026000 0.044319 +v 0.082383 -0.026033 0.020176 +v 0.084339 -0.025859 0.030529 +v 0.082180 -0.025879 0.023336 +v 0.074473 -0.025949 0.054859 +v 0.070589 -0.026007 0.059027 +v 0.064635 -0.025847 0.059752 +v 0.080064 -0.025865 0.048770 +v 0.079625 -0.025991 0.051859 +v 0.055979 -0.025778 0.060372 +v 0.075421 -0.026000 0.055923 +v 0.037159 0.011250 0.014501 +v 0.037026 -0.011250 0.014427 +v 0.033233 0.011250 0.020822 +v 0.030885 -0.011250 0.026179 +v 0.030097 0.011250 0.027299 +v -0.023592 0.011250 0.019476 +v -0.020404 0.011250 0.022827 +v -0.020660 0.011247 0.024719 +v 0.025266 0.011250 0.028619 +v 0.037947 0.011250 0.006410 +v 0.034592 0.011250 0.001986 +v 0.046916 0.011250 0.005968 +v 0.036315 0.011250 0.009822 +v 0.004841 0.011250 0.025585 +v 0.024820 0.011250 -0.006674 +v 0.047551 0.024863 0.006105 +v 0.041675 0.024434 0.004806 +v 0.033836 0.024890 0.001357 +v 0.027039 0.024411 -0.004140 +v 0.023330 0.025021 -0.008459 +v 0.069059 0.008679 0.008162 +v 0.062140 0.025084 0.006185 +v 0.065123 -0.016114 0.006849 +v 0.056822 -0.011420 0.005965 +v 0.125085 -0.020048 0.030128 +v 0.112956 -0.019594 0.037014 +v 0.113735 -0.020077 0.031881 +v 0.125150 -0.019353 0.036720 +v 0.125146 -0.003174 0.012245 +v 0.098751 -0.006932 0.013076 +v 0.092179 -0.003966 0.012247 +v 0.103726 -0.009466 0.014109 +v 0.125162 -0.009947 0.014486 +v 0.106357 -0.012259 0.015681 +v 0.110659 -0.013697 0.017039 +v 0.110978 -0.015733 0.019043 +v 0.115611 -0.016097 0.019944 +v 0.125209 -0.017040 0.021214 +v 0.115394 -0.018259 0.023520 +v 0.111656 -0.019450 0.026615 +v 0.115797 -0.011227 0.048745 +v 0.125204 -0.014175 0.046202 +v 0.125142 -0.007058 0.050820 +v 0.107896 -0.008628 0.050330 +v 0.104299 -0.004551 0.051580 +v 0.125098 0.000035 0.052071 +v 0.099546 -0.000890 0.052106 +v 0.100811 0.004303 0.051725 +v 0.125143 0.006006 0.051111 +v 0.108059 0.006968 0.050926 +v 0.113410 0.011556 0.048669 +v 0.115499 0.013606 0.047069 +v 0.125258 0.012267 0.047843 +v 0.125144 0.018229 0.040672 +v 0.116884 0.016691 0.043441 +v 0.117246 0.019085 0.038317 +v 0.111719 0.020084 0.033468 +v 0.125095 0.020019 0.032893 +v 0.113663 0.019832 0.028562 +v 0.125145 0.019193 0.025855 +v 0.111938 0.018825 0.024634 +v 0.125188 0.014777 0.018400 +v 0.115027 0.016608 0.020577 +v 0.114226 0.013944 0.017542 +v 0.110877 0.011285 0.015353 +v 0.125156 0.008671 0.013912 +v 0.101205 0.007920 0.013453 +v 0.092592 0.004123 0.012296 +v 0.125099 0.001959 0.012035 +v 0.089986 0.000256 0.011925 +v 0.125148 -0.017764 0.041173 +v -0.023280 0.024800 -0.007717 +v -0.019166 0.024498 0.027619 +v -0.020207 -0.024321 0.022748 +v -0.021610 0.025105 0.024047 +v -0.023635 0.024597 0.019410 +v 0.031541 -0.011079 0.035037 +v 0.032804 -0.011027 0.041999 +v 0.030214 -0.011250 0.039431 +v 0.008513 -0.011250 0.022199 +v 0.026473 -0.011250 0.028849 +v 0.002198 -0.011250 0.026660 +v -0.016158 -0.024786 0.026767 +v -0.014922 0.024859 0.031102 +v -0.024241 0.025200 -0.002507 +v -0.025063 0.024482 0.003943 +v -0.024787 0.024725 0.012321 +v 0.057569 0.021114 0.061887 +v 0.071590 -0.000795 0.058625 +v 0.019377 0.025180 -0.014715 +v 0.015756 0.024685 -0.018722 +v 0.010166 0.024847 -0.022255 +v 0.005212 0.024744 -0.023871 +v 0.000061 0.024812 -0.024490 +v -0.007286 0.024573 -0.023413 +v -0.014076 0.024860 -0.020028 +v -0.019807 0.024786 -0.014499 +v 0.030127 -0.025010 0.039371 +v -0.014917 -0.024487 0.019789 +v 0.055278 0.023508 0.061862 +v 0.032046 0.020738 0.062138 +v 0.034693 0.023765 0.062000 +v 0.045845 0.023974 0.061844 +v 0.031786 -0.021969 0.059893 +v 0.044338 -0.011114 0.011287 +v 0.036299 -0.011250 0.009759 +v 0.037991 -0.011250 0.006425 +v -0.019178 -0.024450 0.020994 +v -0.017172 -0.024372 0.019839 +v 0.100486 0.021511 0.030743 +v 0.109199 0.020201 0.029351 +v 0.081266 0.023259 0.053223 +v 0.075098 0.023890 0.056718 +v 0.096880 0.014373 0.050305 +v 0.096219 0.016653 0.049525 +v 0.089087 0.017996 0.051597 +v 0.087430 0.016618 0.052418 +v 0.097409 0.011306 0.050871 +v 0.098842 0.017808 0.047624 +v 0.091161 0.020958 0.048267 +v 0.088858 0.019849 0.050829 +v 0.085059 0.022863 0.050607 +v 0.081889 0.021667 0.053629 +v 0.080292 0.020645 0.054542 +v 0.089461 0.022991 0.045889 +v 0.088938 0.024253 0.041816 +v 0.102764 0.020789 0.038026 +v 0.111090 0.019261 0.039205 +v 0.104437 0.019009 0.042981 +v 0.108039 0.017013 0.045054 +v 0.105183 0.011027 0.049871 +v 0.105339 0.014441 0.048192 +v 0.090687 0.024003 0.028391 +v 0.086637 0.024175 0.020924 +v 0.083781 0.023769 0.016672 +v 0.082569 0.022035 0.013951 +v 0.108667 0.016079 0.019028 +v 0.106155 0.014137 0.016809 +v 0.101339 0.011794 0.014809 +v 0.093237 0.013490 0.014083 +v 0.105372 0.017533 0.020038 +v 0.101418 0.020688 0.025596 +v 0.100451 0.019244 0.020964 +v 0.096158 0.016394 0.016130 +v 0.096674 0.018428 0.017979 +v 0.085090 0.015840 0.012976 +v 0.087034 0.017957 0.013981 +v 0.096732 0.022398 0.035105 +v 0.096199 0.021792 0.041501 +v 0.096967 0.020090 0.045522 +v 0.089579 0.019675 0.015848 +v 0.090417 0.021029 0.017796 +v 0.093141 0.022281 0.022979 +v 0.076540 0.021785 0.011182 +v 0.082705 -0.019560 0.012987 +v 0.075616 -0.022170 0.010793 +v 0.075258 -0.016521 0.010373 +v 0.078250 -0.008717 0.010730 +v 0.074720 0.008540 0.009855 +v 0.087467 -0.016011 0.013525 +v 0.081465 0.002200 0.011129 +v 0.083794 0.008650 0.011878 +v 0.083745 -0.004551 0.011471 +v 0.095087 -0.012598 0.014145 +v 0.077282 -0.022853 0.055685 +v 0.077944 0.007167 0.056068 +v 0.078099 -0.009548 0.055978 +v 0.085619 0.009226 0.053657 +v 0.084374 0.000346 0.054300 +v 0.085631 -0.009327 0.053660 +v 0.084113 -0.019036 0.053218 +v 0.092174 -0.016140 0.051134 +v 0.092854 -0.006879 0.052349 +v 0.091251 0.000268 0.052935 +v 0.092846 0.006820 0.052342 +v 0.098717 -0.011547 0.050695 +v 0.085199 -0.021996 0.015530 +v 0.080336 -0.024897 0.015068 +v 0.077672 -0.023355 0.011991 +v 0.087310 -0.024236 0.022180 +v 0.091196 -0.023924 0.029270 +v 0.099731 -0.021776 0.033860 +v 0.093693 -0.022392 0.024085 +v 0.095208 -0.020581 0.020427 +v 0.088624 -0.022342 0.018644 +v 0.092113 -0.019230 0.016727 +v 0.086220 -0.019992 0.014600 +v 0.088701 -0.023849 0.044369 +v 0.116260 -0.017373 0.042447 +v 0.085618 -0.023532 0.049106 +v 0.083817 -0.022385 0.052212 +v 0.116222 -0.014808 0.045879 +v 0.078955 -0.024126 0.054375 +v 0.107508 -0.012054 0.049119 +v 0.109700 -0.018115 0.022282 +v 0.106408 -0.020513 0.030033 +v 0.108080 -0.016901 0.045104 +v 0.106601 -0.015143 0.047350 +v 0.103318 -0.015646 0.017420 +v 0.106931 -0.020460 0.035201 +v 0.108231 -0.018392 0.042547 +v 0.099362 -0.014692 0.049544 +v 0.101912 -0.018684 0.020575 +v 0.101805 -0.019950 0.023376 +v 0.101813 -0.020923 0.027392 +v 0.102962 -0.020486 0.039286 +v 0.100016 -0.018609 0.046126 +v 0.097917 -0.017310 0.048468 +v 0.092711 -0.016790 0.015270 +v 0.097084 -0.018690 0.018389 +v 0.100760 -0.020000 0.042895 +v 0.090377 -0.020112 0.049810 +v 0.087253 -0.019564 0.051767 +v 0.094759 -0.022207 0.041458 +v 0.092889 -0.021091 0.046703 +v 0.092785 -0.023516 0.036274 +v 0.046733 -0.008300 0.010178 +v 0.050606 -0.011013 0.008620 +v 0.056304 -0.008300 0.007686 +v 0.056523 -0.011227 0.007525 +v 0.037889 -0.008300 0.016723 +v 0.037093 -0.011075 0.017566 +v 0.034104 -0.010756 0.022939 +v 0.032442 -0.008300 0.027323 +v 0.032034 -0.011069 0.028695 +v 0.031875 -0.008300 0.037904 +v 0.034470 -0.008300 0.045726 +v 0.078250 -0.023691 0.017130 +v 0.082878 -0.008300 0.024791 +v 0.076865 -0.008300 0.015614 +v 0.070902 -0.019449 0.010930 +v 0.067994 -0.008300 0.009427 +v 0.062062 -0.014345 0.007972 +v 0.039152 -0.008300 0.052516 +v 0.041659 -0.025505 0.054653 +v 0.046882 -0.008300 0.057880 +v 0.055971 -0.008300 0.060344 +v 0.067942 -0.008300 0.058591 +v 0.068742 -0.025497 0.058046 +v 0.076796 -0.008300 0.052455 +v 0.082148 -0.008300 0.044722 +v 0.083627 -0.025497 0.040075 +v 0.084296 -0.008300 0.035542 +v 0.032609 0.024707 0.031404 +v 0.033447 0.024710 0.041072 +v 0.038339 0.024710 0.050320 +v 0.046527 0.024710 0.056831 +v 0.045450 0.025501 0.056168 +v 0.054160 0.024980 0.059084 +v 0.067027 0.024980 0.057717 +v 0.072702 0.025483 0.054804 +v 0.075584 0.024923 0.052351 +v 0.080544 0.024710 0.046029 +v 0.081048 0.025481 0.044850 +v 0.083593 0.024703 0.035397 +v 0.035473 0.024972 0.022220 +v 0.037749 0.024701 0.018542 +v 0.041021 0.025503 0.014998 +v 0.044435 0.024700 0.012341 +v 0.052800 0.024986 0.009184 +v 0.061772 0.025508 0.008722 +v 0.063410 0.024700 0.008917 +v 0.070373 0.025498 0.011728 +v 0.075065 0.024699 0.014835 +v 0.077516 0.025496 0.017502 +v 0.081748 0.024697 0.024541 +v 0.082919 0.025494 0.027926 +v 0.084729 0.024101 0.033597 +v 0.081781 0.024101 0.046030 +v 0.073331 0.024101 0.055861 +v 0.059191 0.024103 0.060800 +v 0.060722 0.024994 0.059167 +v 0.042206 0.024105 0.055866 +v 0.032951 0.024101 0.043107 +v 0.031685 0.024103 0.028383 +v 0.038575 0.024101 0.015831 +v 0.047038 0.024101 0.009806 +v 0.056926 0.024101 0.007413 +v 0.066822 0.024100 0.008950 +v 0.075663 0.024101 0.014114 +v 0.081904 0.024100 0.022419 +v -0.019767 -0.025303 0.022735 +v -0.018339 -0.025264 0.020702 +v -0.015475 -0.025602 0.020352 +v 0.028241 0.025432 -0.002266 +v 0.038276 0.024224 0.056722 +v 0.036403 0.023385 0.055889 +v 0.035453 0.021414 0.055131 +v 0.036777 -0.023446 0.055294 +v 0.034398 -0.020310 0.053804 +v 0.035028 -0.022151 0.054338 +v 0.039105 0.021772 0.054652 +v 0.037865 -0.020504 0.053381 +v 0.042648 -0.021396 0.057510 +v 0.045776 0.022023 0.059367 +v 0.048106 -0.021461 0.060273 +v 0.049939 0.022627 0.060935 +v 0.053254 -0.022578 0.061588 +v 0.045562 0.023301 0.060321 +v 0.047440 -0.022882 0.060754 +v 0.039040 0.023272 0.055499 +v 0.042045 -0.023042 0.058221 +v 0.037826 -0.022263 0.054070 +v 0.037539 0.022773 0.054889 +v 0.037053 0.020842 0.054218 +v 0.036206 -0.020504 0.053108 +v 0.008064 0.013250 0.032655 +v 0.025037 0.013250 0.040001 +v 0.007079 0.013250 0.024325 +v 0.006333 0.025485 0.026126 +v 0.006108 0.013250 0.029370 +v 0.024204 0.013250 0.005903 +v 0.019639 0.013250 0.015166 +v 0.029152 0.013250 0.003581 +v 0.026782 0.025494 0.004135 +v 0.036978 0.013250 0.007441 +v 0.039237 0.013250 0.012690 +v 0.038690 0.025525 0.014053 +v 0.030188 0.013250 0.036476 +v 0.031281 0.013250 0.027360 +v 0.034632 0.013250 0.019560 +v 0.050718 -0.026000 0.008155 +v 0.046554 -0.026000 0.007574 +v 0.045283 -0.022000 0.007610 +v 0.021626 -0.026009 -0.011499 +v 0.024740 -0.011250 -0.006048 +v 0.025708 -0.026000 -0.004790 +v 0.032822 -0.011250 0.001830 +v 0.033555 -0.026000 0.002259 +v 0.037405 -0.022000 0.004608 +v 0.043109 -0.011250 0.007018 +v 0.052641 -0.011250 0.008326 +v 0.062452 -0.026000 0.008038 +v -0.020471 -0.011250 0.013568 +v -0.016525 -0.026000 0.018712 +v -0.014805 -0.011250 0.019695 +v -0.024390 -0.011250 0.004279 +v -0.024576 -0.026000 0.001237 +v -0.022836 -0.026000 0.009059 +v -0.023427 -0.011250 -0.007760 +v -0.022701 -0.026000 -0.009971 +v -0.017103 -0.011250 -0.018073 +v -0.015788 -0.026000 -0.018889 +v -0.006648 -0.026000 -0.023743 +v -0.006166 -0.011250 -0.023820 +v 0.002821 -0.011250 -0.024454 +v 0.005899 -0.026018 -0.023942 +v 0.012459 -0.011250 -0.021288 +v 0.013938 -0.025999 -0.020225 +v 0.019309 -0.011250 -0.015181 +v 0.017996 -0.026000 -0.016625 +v 0.019460 -0.026000 -0.014885 +v 0.020446 -0.026000 -0.013463 +v 0.013095 -0.026000 0.031800 +v 0.021693 -0.026000 0.035493 +v 0.012772 -0.022000 0.031637 +v 0.022024 -0.022000 0.035579 +v 0.003472 -0.022000 0.027607 +v 0.004165 -0.026000 0.027664 +v 0.016859 -0.011250 0.033446 +v 0.030889 -0.022000 0.039531 +v 0.032705 -0.011250 0.040796 +v 0.031252 -0.026000 0.039796 +v 0.032277 -0.026000 0.040651 +v 0.032920 -0.026022 0.041480 +v 0.032260 -0.004233 0.037409 +v 0.031771 -0.011250 0.031462 +v 0.035475 -0.004293 0.047179 +v 0.032316 -0.004179 0.031067 +v 0.033729 -0.004187 0.024944 +v 0.036970 -0.004206 0.018846 +v 0.035953 -0.011250 0.019901 +v 0.050580 -0.004160 0.009124 +v 0.042913 -0.011250 0.012668 +v 0.043404 -0.004182 0.012488 +v 0.055537 -0.004537 0.007996 +v 0.041361 -0.022000 0.013857 +v 0.037705 -0.022000 0.013027 +v 0.044122 -0.022000 0.010098 +v 0.035961 -0.022000 0.009732 +v 0.037615 -0.022000 0.006517 +v 0.083165 -0.026000 0.041312 +v 0.031641 -0.026000 0.035648 +v 0.031808 -0.026014 0.035123 +v 0.031926 -0.026007 0.033662 +v 0.031282 -0.026019 0.031875 +v 0.041194 -0.026000 0.013671 +v 0.042427 -0.026000 0.013113 +v 0.041834 -0.026000 0.013444 +v 0.030589 -0.026000 0.039029 +v 0.030465 -0.026000 0.038711 +v 0.008514 -0.026000 0.022311 +v 0.062438 -0.004183 0.008522 +v 0.074709 -0.004168 0.014281 +v 0.074564 -0.026000 0.013727 +v 0.069057 -0.004242 0.010488 +v 0.079052 -0.004219 0.018851 +v 0.081749 -0.026000 0.022956 +v 0.083087 -0.004249 0.026959 +v 0.079000 -0.004229 0.049203 +v 0.081961 -0.004149 0.043633 +v 0.083777 -0.004244 0.037245 +v 0.083983 -0.026000 0.032029 +v 0.078197 -0.026000 0.050570 +v 0.073448 -0.004545 0.055073 +v 0.071114 -0.026000 0.056598 +v 0.069158 -0.004134 0.057434 +v 0.061215 -0.026000 0.060014 +v 0.062115 -0.004206 0.059581 +v 0.037582 -0.011250 0.014202 +v 0.036433 -0.011250 0.010455 +v 0.015042 -0.011250 0.024026 +v 0.032218 -0.011250 0.022811 +v 0.026080 -0.011250 0.002938 +v 0.030244 -0.011250 0.002435 +v 0.053306 -0.004181 0.059536 +v 0.050708 -0.026000 0.059067 +v 0.036114 -0.011250 0.006400 +v 0.043344 -0.004221 0.055563 +v 0.041411 -0.026000 0.054281 +v 0.035445 -0.026000 0.047050 +v 0.013404 -0.026000 0.024943 +v 0.012354 -0.026013 0.023219 +v 0.026257 -0.026000 0.030481 +v 0.037416 -0.026000 0.012687 +v 0.037944 -0.026000 0.013114 +v 0.028939 -0.026000 0.030229 +v 0.012153 -0.026003 0.029610 +v 0.012620 -0.026000 0.028779 +v 0.024692 -0.026000 0.031785 +v 0.030989 -0.026000 0.039580 +v 0.030765 -0.026000 0.039322 +v 0.036276 -0.026000 0.008954 +v 0.036189 -0.026000 0.009627 +v 0.030397 -0.026000 0.038377 +v 0.030387 -0.026000 0.038036 +v 0.030435 -0.026000 0.037698 +v 0.030540 -0.026000 0.037373 +v 0.031435 -0.026006 0.036067 +v 0.044260 -0.026000 0.008978 +v 0.044377 -0.026000 0.008672 +v 0.022523 -0.026000 0.035410 +v 0.022842 -0.026000 0.035290 +v 0.023135 -0.026000 0.035118 +v 0.023396 -0.026000 0.034899 +v 0.023616 -0.026000 0.034638 +v 0.023893 -0.026000 0.034109 +v 0.023971 -0.026000 0.033691 +v 0.026901 -0.026000 0.030245 +v 0.024101 -0.026000 0.033018 +v 0.024343 -0.026000 0.032376 +v 0.012771 -0.026000 0.031552 +v 0.012542 -0.026000 0.031299 +v 0.012298 -0.026000 0.030906 +v 0.030150 -0.026010 0.030769 +v 0.038791 -0.026000 0.013563 +v 0.039847 -0.026000 0.013786 +v 0.036438 -0.026000 0.011238 +v 0.036968 -0.026000 0.012177 +v 0.027576 -0.026000 0.030123 +v 0.013020 -0.026000 0.028228 +v 0.013321 -0.026000 0.027617 +v 0.013514 -0.026000 0.026963 +v 0.013593 -0.026000 0.026287 +v 0.025136 -0.026000 0.031263 +v 0.025118 -0.026000 0.031283 +v 0.013556 -0.026000 0.025607 +v 0.025663 -0.026000 0.030824 +v 0.028262 -0.026000 0.030117 +v 0.040525 -0.026000 0.013786 +v 0.027384 -0.026000 0.030158 +v 0.005483 -0.026039 0.026294 +v 0.006328 -0.026000 0.023854 +v 0.044542 -0.026000 0.008389 +v 0.044752 -0.026000 0.008138 +v 0.010538 -0.026000 0.022275 +v 0.006767 -0.026000 0.023333 +v 0.007288 -0.026000 0.022894 +v 0.007876 -0.026000 0.022550 +v 0.036217 -0.026000 0.010305 +v 0.042955 -0.026000 0.012686 +v 0.043403 -0.026000 0.012176 +v 0.044011 -0.026000 0.010968 +v 0.043758 -0.026000 0.011598 +v 0.044153 -0.026000 0.010304 +v 0.044181 -0.026000 0.009626 +v 0.044194 -0.026000 0.009299 +v 0.036475 -0.026000 0.008305 +v 0.045000 -0.026000 0.007924 +v 0.045279 -0.026000 0.007753 +v 0.009864 -0.026000 0.022171 +v 0.036781 -0.026000 0.007699 +v 0.045582 -0.026000 0.007630 +v 0.045902 -0.026000 0.007558 +v 0.046229 -0.026000 0.007539 +v 0.009183 -0.026000 0.022184 +v 0.037186 -0.026000 0.007154 +v 0.037381 -0.026000 0.006891 +v 0.037585 -0.026000 0.006476 +v 0.037681 -0.026000 0.005965 +v 0.037677 -0.026000 0.005637 +v 0.037618 -0.026000 0.005315 +v 0.037508 -0.026000 0.005007 +v 0.037350 -0.026000 0.004720 +v 0.037146 -0.026000 0.004464 +v 0.036903 -0.026000 0.004244 +v 0.023731 -0.022000 0.034585 +v 0.024537 -0.022000 0.031820 +v 0.027122 -0.022000 0.030126 +v 0.030466 -0.022000 0.030790 +v 0.032091 -0.022000 0.034569 +v 0.030308 -0.022000 0.037762 +v 0.005305 -0.022000 0.026797 +v 0.006176 -0.022000 0.023876 +v 0.010129 -0.022000 0.021901 +v 0.013876 -0.022000 0.025812 +v 0.012049 -0.022000 0.029754 +v 0.020757 -0.020000 0.027027 +v 0.020747 -0.011250 0.027039 +v 0.022557 -0.011250 0.029572 +v 0.024131 -0.020000 0.030900 +v 0.025163 -0.011250 0.030867 +v 0.029906 -0.020000 0.029412 +v 0.029914 -0.011250 0.029354 +v 0.032833 -0.020000 0.021322 +v 0.037538 -0.020000 0.014208 +v 0.036498 -0.020000 0.010393 +v 0.035732 -0.020000 0.006067 +v 0.029033 -0.020000 0.002016 +v 0.025450 -0.020000 0.004003 +v 0.022557 -0.011250 0.012739 +v 0.022171 -0.020000 0.013409 +v 0.015562 -0.011250 0.020456 +v 0.014842 -0.020000 0.021609 +v 0.016442 -0.020000 0.025920 +v 0.017441 -0.011250 0.026385 +v 0.012344 -0.026705 0.029287 +v 0.013421 -0.026737 0.027680 +v 0.013582 -0.026228 0.026089 +v 0.013114 -0.026700 0.023944 +v 0.010884 -0.026293 0.022340 +v 0.008868 -0.026445 0.022160 +v 0.006815 -0.026547 0.023191 +v 0.006026 -0.026013 0.024380 +v 0.012828 -0.026562 0.031634 +v 0.012532 -0.026000 0.031283 +v 0.023788 -0.026000 0.034345 +v 0.023649 -0.026745 0.034502 +v 0.022259 -0.026712 0.035501 +v 0.021733 -0.026016 0.035518 +v 0.028236 -0.026286 0.030029 +v 0.025935 -0.026175 0.030657 +v 0.025026 -0.026940 0.031100 +v 0.024147 -0.026781 0.032506 +v 0.030774 -0.026875 0.039167 +v 0.030365 -0.026021 0.038229 +v 0.030524 -0.026204 0.037246 +v 0.032178 -0.026917 0.040322 +v 0.062504 -0.026054 0.008313 +v 0.060178 -0.026920 0.008170 +v 0.054774 -0.026212 0.008105 +v 0.080291 -0.026014 0.020376 +v 0.078502 -0.026768 0.018116 +v 0.076352 -0.026035 0.015500 +v 0.083448 -0.026029 0.028272 +v 0.081986 -0.026978 0.024338 +v 0.082735 -0.026190 0.042252 +v 0.083655 -0.026822 0.037554 +v 0.084069 -0.026085 0.034777 +v 0.077240 -0.026580 0.051544 +v 0.080550 -0.026054 0.047155 +v 0.075651 -0.026004 0.053200 +v 0.073095 -0.026752 0.055106 +v 0.068570 -0.026471 0.057835 +v 0.050178 -0.026006 0.058901 +v 0.053399 -0.026653 0.059515 +v 0.057586 -0.026601 0.059984 +v 0.061773 -0.026004 0.059907 +v 0.045935 -0.026850 0.056991 +v 0.040816 -0.026039 0.053739 +v 0.034473 -0.026607 0.044962 +v 0.035983 -0.026109 0.048014 +v 0.045897 -0.026656 0.007592 +v 0.050552 -0.026004 0.008126 +v 0.044161 -0.026074 0.009278 +v 0.044685 -0.027146 0.008495 +v 0.045008 -0.026076 0.007874 +v 0.037560 -0.026124 0.006675 +v 0.036690 -0.026025 0.007864 +v 0.036074 -0.026664 0.009616 +v 0.036543 -0.026307 0.011495 +v 0.038177 -0.026740 0.013479 +v 0.039067 -0.026029 0.013659 +v 0.041272 -0.026777 0.013817 +v 0.042988 -0.026478 0.012832 +v 0.044123 -0.026313 0.010532 +v 0.037049 -0.026821 0.004487 +v 0.033436 -0.026005 0.002148 +v 0.037714 -0.026222 0.005476 +v 0.032063 -0.026754 0.001325 +v 0.026868 -0.026005 -0.003498 +v -0.014325 -0.026837 0.019737 +v -0.014236 -0.026006 0.019985 +v -0.018060 -0.026228 0.016661 +v -0.021316 -0.026016 -0.012338 +v -0.023316 -0.026901 -0.007356 +v -0.024555 -0.026130 -0.001899 +v -0.018054 -0.026643 -0.016524 +v -0.015192 -0.026001 -0.019286 +v -0.009448 -0.026073 -0.022680 +v -0.013161 -0.026977 -0.020512 +v 0.015223 -0.026292 -0.019294 +v 0.011635 -0.026031 -0.021604 +v 0.018441 -0.026928 -0.015991 +v 0.004278 -0.026028 0.027582 +v 0.003400 -0.026670 0.027497 +v 0.002872 -0.026072 0.024282 +v 0.002436 -0.026080 0.025451 +v 0.019564 -0.026000 0.016859 +v 0.002046 -0.026069 0.022993 +v -0.000011 -0.026130 0.024520 +v 0.000573 -0.026083 0.023216 +v 0.000978 -0.026121 0.025816 +v -0.021275 -0.026043 0.012382 +v -0.017863 -0.026107 0.010283 +v -0.017343 -0.026105 0.012215 +v -0.023411 -0.026035 0.007471 +v -0.020152 -0.026123 0.011168 +v -0.019184 -0.026079 0.010139 +v -0.019928 -0.026100 0.012360 +v -0.018702 -0.026111 0.013003 +v -0.024407 -0.026009 0.002731 +v -0.000793 -0.026091 -0.022401 +v -0.004022 -0.026058 -0.024271 +v -0.000477 -0.026071 -0.021027 +v 0.020875 -0.026028 -0.007100 +v 0.002197 -0.026012 -0.024505 +v 0.023356 -0.026114 -0.005567 +v 0.022182 -0.026081 -0.004663 +v 0.020868 -0.026112 -0.005196 +v 0.023353 -0.026110 -0.006793 +v 0.022230 -0.026159 -0.007628 +v 0.053854 -0.026000 0.024190 +v 0.046801 -0.026111 0.011349 +v 0.045691 -0.026116 0.010608 +v 0.045674 -0.026091 0.009274 +v 0.046929 -0.026099 0.008430 +v 0.048351 -0.026067 0.009364 +v 0.072350 -0.026637 0.012281 +v 0.067332 -0.026027 0.009649 +v 0.074984 -0.026107 0.018668 +v 0.075637 -0.026121 0.017467 +v 0.077360 -0.026099 0.017443 +v 0.077897 -0.026119 0.018942 +v 0.077152 -0.026092 0.019971 +v 0.075902 -0.026119 0.020077 +v 0.055021 -0.026084 0.056617 +v 0.055417 -0.026121 0.058092 +v 0.052506 -0.026125 0.058084 +v 0.053163 -0.026099 0.056320 +v 0.053862 -0.026093 0.059140 +v 0.034204 -0.026089 0.038110 +v 0.033668 -0.026093 0.039283 +v 0.032317 -0.026112 0.039599 +v 0.033051 -0.026112 0.036692 +v 0.031488 -0.026584 0.032124 +v 0.031333 -0.026103 0.038533 +v 0.032049 -0.026677 0.034336 +v 0.030994 -0.026009 0.031516 +v 0.031558 -0.026119 0.037319 +v 0.012105 -0.026103 0.030395 +v -0.000065 -0.026168 -0.023295 +v 0.001479 -0.026128 -0.023220 +v 0.002114 -0.026102 -0.021556 +v 0.000768 -0.026107 -0.020537 +v 0.048109 -0.026064 0.010873 +v 0.075874 -0.027444 0.015987 +v 0.056277 -0.027535 0.059201 +v 0.033400 -0.027465 0.040809 +v 0.036262 -0.027538 0.046746 +v 0.051500 -0.027387 0.058568 +v 0.039210 -0.027238 0.051362 +v 0.045332 -0.027556 0.055737 +v 0.068424 -0.027540 0.056955 +v 0.062329 -0.026977 0.059460 +v 0.075743 -0.027536 0.051759 +v 0.082341 -0.027531 0.040788 +v 0.083292 -0.027446 0.031403 +v 0.067182 -0.027492 0.010325 +v 0.079962 -0.027496 0.046671 +v 0.078874 -0.027589 0.020097 +v 0.059196 -0.027562 0.009109 +v 0.045355 -0.027184 0.008066 +v 0.047854 -0.026869 0.008021 +v 0.049982 -0.027654 0.009464 +v 0.030631 -0.026935 0.037663 +v 0.032414 -0.027432 0.035509 +v 0.029704 -0.026983 0.030141 +v 0.027701 -0.027482 0.029237 +v 0.022604 -0.027532 0.034540 +v 0.032299 -0.027548 0.031018 +v 0.024484 -0.027575 0.030268 +v 0.037174 -0.027176 0.006368 +v 0.043071 -0.027515 0.013958 +v 0.044767 -0.027505 0.011493 +v 0.034984 -0.027550 0.010615 +v 0.038146 -0.027555 0.014617 +v 0.036755 -0.027555 0.005515 +v 0.012882 -0.027521 0.030370 +v 0.023701 -0.026805 -0.007542 +v 0.027414 -0.026820 -0.002785 +v 0.024554 -0.027514 -0.005133 +v 0.029934 -0.027504 0.000738 +v 0.019907 -0.027509 -0.013054 +v 0.021878 -0.027559 -0.008883 +v -0.018055 -0.027630 0.014378 +v -0.015744 -0.027522 0.017847 +v -0.020506 -0.026969 0.012994 +v -0.000282 -0.027111 -0.024163 +v -0.005921 -0.027457 -0.023185 +v -0.014681 -0.027562 -0.018377 +v -0.022821 -0.027505 0.006902 +v 0.011329 -0.027482 -0.021045 +v 0.005525 -0.027113 -0.023566 +v 0.002770 -0.027461 -0.023687 +v -0.001927 -0.027603 -0.023129 +v -0.019365 -0.027461 -0.013975 +v -0.023015 -0.027565 -0.005204 +v -0.024259 -0.027061 0.001270 +v -0.021106 -0.027619 0.009761 +v 0.005998 -0.027468 0.022925 +v 0.014371 -0.027449 0.025900 +v 0.010614 -0.027495 0.021364 +v 0.004921 -0.027193 0.026622 +v 0.008626 -0.027389 0.021551 +v 0.013998 -0.027561 0.023393 +v 0.004189 -0.027614 0.025800 +v 0.003195 -0.027535 0.026621 +v -0.001280 -0.027537 0.024567 +v 0.000252 -0.026823 0.026067 +v 0.047226 -0.027594 0.012832 +v 0.076368 -0.027588 0.021668 +v 0.073513 -0.027593 0.018841 +v 0.052094 -0.027589 0.055296 +v 0.056439 -0.027587 0.055904 +v 0.035007 -0.027594 0.036377 +v 0.035288 -0.027596 0.039457 +v 0.000020 -0.027584 0.021751 +v 0.003527 -0.027597 0.022421 +v -0.017203 -0.027598 0.009064 +v -0.015882 -0.027597 0.011871 +v 0.002560 -0.027570 -0.019555 +v -0.001647 -0.027597 -0.020184 +v 0.022708 -0.027597 -0.003365 +v 0.019578 -0.027590 -0.004528 +v 0.019740 -0.027597 -0.007859 +v 0.022262 -0.027554 -0.005279 +v 0.024723 -0.027538 -0.006118 +v 0.023736 -0.027531 -0.004211 +v 0.021822 -0.027554 -0.007024 +v 0.021393 -0.027467 -0.008697 +v 0.023504 -0.027535 -0.008306 +v 0.022882 -0.027592 -0.006363 +v 0.019672 -0.027535 -0.007316 +v 0.021202 -0.027591 -0.005940 +v 0.019732 -0.027522 -0.004888 +v 0.021874 -0.027515 -0.003497 +v 0.022487 -0.022617 -0.006862 +v 0.021183 -0.022562 -0.006035 +v 0.022772 -0.022755 -0.005313 +v 0.022210 -0.026107 -0.007572 +v 0.022330 -0.023098 -0.007499 +v 0.023345 -0.023117 -0.006179 +v 0.023353 -0.026117 -0.006144 +v 0.022275 -0.026110 -0.004759 +v 0.021247 -0.023103 -0.005043 +v 0.020658 -0.026117 -0.006078 +v 0.020828 -0.023115 -0.006652 +v 0.031178 -0.025910 0.035595 +v 0.029726 -0.026000 0.034319 +v 0.031318 -0.025888 0.033124 +v 0.026877 -0.026000 0.035536 +v 0.027581 -0.025883 0.037622 +v 0.025241 -0.025904 0.036384 +v 0.029547 -0.025909 0.037190 +v 0.030221 -0.025883 0.031435 +v 0.024438 -0.025873 0.034153 +v 0.027961 -0.025908 0.030551 +v 0.027247 -0.026000 0.032461 +v 0.025225 -0.025911 0.031822 +v 0.026168 -0.002068 0.034661 +v 0.029355 -0.002138 0.035325 +v 0.029106 -0.001973 0.032871 +v 0.027018 -0.002163 0.035735 +v 0.026268 -0.002153 0.033180 +v 0.029912 -0.021919 0.034944 +v 0.029771 -0.021912 0.032994 +v 0.030009 -0.002502 0.033655 +v 0.027861 -0.002449 0.031913 +v 0.027695 -0.021910 0.031930 +v 0.026167 -0.021916 0.033040 +v 0.025893 -0.021913 0.034669 +v 0.027171 -0.021917 0.036077 +v 0.028322 -0.002487 0.036138 +v 0.028653 -0.021906 0.036072 +v 0.031467 -0.022076 0.033868 +v 0.024689 -0.022063 0.032639 +v 0.030491 -0.022082 0.036622 +v 0.026722 -0.022085 0.030821 +v 0.029835 -0.022069 0.030996 +v 0.027952 -0.022064 0.037608 +v 0.025062 -0.022069 0.036315 +v 0.026540 -0.023000 0.035205 +v 0.027702 -0.023000 0.032334 +v 0.029608 -0.023000 0.034776 +v 0.041756 -0.026000 0.010654 +v 0.043389 -0.025894 0.011258 +v 0.041574 -0.025887 0.013065 +v 0.043591 -0.025902 0.008901 +v 0.038660 -0.026000 0.010734 +v 0.038357 -0.025901 0.012914 +v 0.036604 -0.025911 0.009858 +v 0.040139 -0.026000 0.008012 +v 0.041813 -0.025913 0.006609 +v 0.038251 -0.025886 0.006735 +v 0.041825 -0.001995 0.009534 +v 0.038792 -0.002141 0.011126 +v 0.040741 -0.002218 0.011683 +v 0.039618 -0.002107 0.007950 +v 0.042155 -0.002507 0.010419 +v 0.041859 -0.021924 0.011094 +v 0.042262 -0.021913 0.009249 +v 0.041796 -0.002489 0.008461 +v 0.040369 -0.021906 0.007603 +v 0.038079 -0.002498 0.009288 +v 0.038424 -0.021915 0.008562 +v 0.038363 -0.021909 0.011034 +v 0.040448 -0.021913 0.011897 +v 0.042945 -0.022083 0.012034 +v 0.043670 -0.022076 0.009769 +v 0.038767 -0.022081 0.006546 +v 0.036895 -0.022083 0.008531 +v 0.039979 -0.022060 0.013400 +v 0.041143 -0.022058 0.006452 +v 0.037009 -0.022063 0.011443 +v 0.043006 -0.022083 0.007684 +v 0.038469 -0.023000 0.010302 +v 0.040608 -0.023000 0.008062 +v 0.041478 -0.023000 0.011035 +v 0.008070 -0.026000 0.027096 +v 0.007991 -0.025883 0.029339 +v 0.006159 -0.025898 0.027076 +v 0.012349 -0.025886 0.023852 +v 0.013074 -0.025890 0.026859 +v 0.011120 -0.026000 0.025228 +v 0.011213 -0.025921 0.029370 +v 0.010297 -0.026000 0.027746 +v 0.006883 -0.025898 0.023748 +v 0.008893 -0.026000 0.024579 +v 0.009783 -0.025919 0.022659 +v 0.011050 -0.002086 0.024919 +v 0.010298 -0.002218 0.028029 +v 0.011475 -0.002207 0.026491 +v 0.008346 -0.002183 0.027627 +v 0.008450 -0.001980 0.024944 +v 0.010595 -0.021911 0.028088 +v 0.011741 -0.021903 0.025754 +v 0.010586 -0.021922 0.024278 +v 0.009288 -0.002485 0.024121 +v 0.008439 -0.021912 0.024334 +v 0.007489 -0.002498 0.025650 +v 0.007469 -0.021914 0.026249 +v 0.008408 -0.021914 0.027929 +v 0.012390 -0.022071 0.028438 +v 0.012979 -0.022073 0.025009 +v 0.006739 -0.022085 0.024055 +v 0.009904 -0.022076 0.029634 +v 0.009091 -0.022082 0.022672 +v 0.011219 -0.022064 0.023081 +v 0.007382 -0.022063 0.028971 +v 0.006110 -0.022073 0.026528 +v 0.007878 -0.023000 0.026665 +v 0.008893 -0.023000 0.024579 +v 0.010297 -0.023000 0.027746 +v 0.011311 -0.023000 0.025660 +v -0.018008 -0.027304 0.012082 +v -0.016421 -0.027304 0.012791 +v -0.017955 -0.027251 0.014031 +v -0.016222 -0.027289 0.010930 +v -0.019247 -0.027342 0.012237 +v -0.021279 -0.027233 0.012132 +v -0.019449 -0.027304 0.011004 +v -0.018210 -0.027341 0.010850 +v -0.017202 -0.027202 0.009410 +v -0.019305 -0.027297 0.008973 +v -0.020971 -0.027293 0.010257 +v -0.020021 -0.027284 0.013800 +v -0.018251 -0.022366 0.010844 +v -0.019599 -0.022334 0.011537 +v -0.018225 -0.022357 0.012224 +v -0.017803 -0.025869 0.012497 +v -0.017663 -0.022848 0.012417 +v -0.019515 -0.025861 0.012681 +v -0.019431 -0.022863 0.012667 +v -0.020018 -0.022868 0.011453 +v -0.019885 -0.025865 0.010823 +v -0.019325 -0.022865 0.010373 +v -0.018599 -0.025868 0.010261 +v -0.017802 -0.022860 0.010578 +v -0.017514 -0.025863 0.010973 +v -0.000088 -0.027304 -0.022530 +v -0.001794 -0.027273 -0.021174 +v -0.001816 -0.027239 -0.022872 +v 0.001151 -0.027341 -0.022685 +v 0.001281 -0.027298 -0.024535 +v 0.002863 -0.027272 -0.023286 +v 0.001353 -0.027304 -0.021452 +v 0.003124 -0.027288 -0.021002 +v 0.001167 -0.027241 -0.019438 +v 0.000114 -0.027342 -0.021297 +v -0.000831 -0.027283 -0.019842 +v -0.000501 -0.027266 -0.024374 +v 0.000950 -0.022368 -0.022757 +v -0.000235 -0.022340 -0.021952 +v 0.001248 -0.022345 -0.021383 +v 0.001572 -0.025864 -0.021081 +v 0.001752 -0.022841 -0.021165 +v 0.000045 -0.025867 -0.020751 +v -0.000197 -0.022857 -0.020925 +v -0.000665 -0.025868 -0.022291 +v -0.000476 -0.022848 -0.022809 +v 0.000619 -0.025863 -0.023357 +v 0.001406 -0.022857 -0.023098 +v 0.001900 -0.025867 -0.022362 +v -0.001130 -0.027251 0.024883 +v -0.000979 -0.027285 0.023442 +v 0.000725 -0.027304 0.023852 +v 0.002167 -0.027304 0.024930 +v 0.003733 -0.027256 0.025611 +v 0.002100 -0.027270 0.026938 +v 0.003936 -0.027257 0.023664 +v 0.000927 -0.027342 0.025084 +v 0.000012 -0.027269 0.026551 +v 0.000516 -0.027294 0.021880 +v 0.002892 -0.027284 0.022242 +v 0.001964 -0.027341 0.023697 +v 0.000600 -0.022363 0.024208 +v 0.001740 -0.022495 0.025441 +v 0.002183 -0.022320 0.023928 +v 0.002236 -0.025865 0.025485 +v 0.002774 -0.022860 0.024552 +v 0.000616 -0.022857 0.025456 +v 0.000257 -0.025860 0.025179 +v 0.000406 -0.022833 0.023444 +v 0.000715 -0.025868 0.023263 +v 0.002131 -0.022868 0.023295 +v 0.002596 -0.025860 0.023572 +v 0.030519 -0.027257 0.039502 +v 0.030165 -0.027260 0.037832 +v 0.032005 -0.027304 0.037637 +v 0.033447 -0.027304 0.038715 +v 0.035295 -0.027253 0.038922 +v 0.033711 -0.027293 0.040554 +v 0.033244 -0.027341 0.037483 +v 0.033222 -0.027310 0.035647 +v 0.034661 -0.027260 0.036423 +v 0.032207 -0.027342 0.038870 +v 0.031248 -0.027263 0.035993 +v 0.031914 -0.027273 0.040667 +v 0.031882 -0.022303 0.038347 +v 0.033669 -0.022559 0.038879 +v 0.033204 -0.022366 0.037477 +v 0.033265 -0.025857 0.039501 +v 0.032200 -0.022860 0.039406 +v 0.031348 -0.025861 0.038405 +v 0.031409 -0.022857 0.037876 +v 0.032361 -0.025866 0.036892 +v 0.032716 -0.022863 0.036851 +v 0.033933 -0.025869 0.037531 +v 0.033862 -0.022868 0.037560 +v 0.054673 -0.027304 0.058195 +v 0.055967 -0.027264 0.059315 +v 0.054599 -0.027296 0.060144 +v 0.051624 -0.027208 0.058869 +v 0.051505 -0.027271 0.056719 +v 0.053232 -0.027304 0.057117 +v 0.056567 -0.027280 0.057634 +v 0.053434 -0.027342 0.058350 +v 0.054471 -0.027341 0.056963 +v 0.054113 -0.027299 0.055046 +v 0.055889 -0.027306 0.055924 +v 0.053189 -0.027276 0.060159 +v 0.052838 -0.027262 0.055282 +v 0.053669 -0.022366 0.058454 +v 0.054250 -0.022497 0.056562 +v 0.053137 -0.022516 0.056842 +v 0.054714 -0.022367 0.057905 +v 0.054375 -0.025866 0.058923 +v 0.055310 -0.022841 0.057965 +v 0.053828 -0.022865 0.058964 +v 0.052822 -0.025869 0.058404 +v 0.052626 -0.022857 0.057909 +v 0.052807 -0.025866 0.057070 +v 0.054110 -0.025863 0.056272 +v 0.055290 -0.025865 0.057659 +v 0.077184 -0.027304 0.019206 +v 0.078294 -0.027287 0.020507 +v 0.076942 -0.027260 0.021203 +v 0.074823 -0.027278 0.016671 +v 0.076096 -0.027292 0.016080 +v 0.075742 -0.027304 0.018128 +v 0.075945 -0.027342 0.019360 +v 0.073961 -0.027292 0.019245 +v 0.079075 -0.027314 0.018672 +v 0.076982 -0.027341 0.017973 +v 0.078631 -0.027274 0.017179 +v 0.074017 -0.027284 0.017771 +v 0.074945 -0.027268 0.020811 +v 0.076830 -0.022293 0.017897 +v 0.075382 -0.022483 0.018660 +v 0.076995 -0.022435 0.019606 +v 0.076925 -0.025866 0.019919 +v 0.075571 -0.022853 0.019698 +v 0.075419 -0.025865 0.019503 +v 0.075293 -0.025867 0.018077 +v 0.075982 -0.022860 0.017419 +v 0.076724 -0.025863 0.017312 +v 0.077748 -0.022841 0.018132 +v 0.077795 -0.025868 0.018666 +v 0.077388 -0.027097 0.016262 +v 0.047689 -0.027304 0.010444 +v 0.048928 -0.027277 0.011607 +v 0.047278 -0.027268 0.012506 +v 0.045053 -0.027279 0.011726 +v 0.044382 -0.027265 0.009906 +v 0.046248 -0.027304 0.009366 +v 0.049602 -0.027290 0.009769 +v 0.046450 -0.027342 0.010599 +v 0.045302 -0.027239 0.007827 +v 0.048134 -0.027281 0.007501 +v 0.047487 -0.027341 0.009212 +v 0.046381 -0.022515 0.010843 +v 0.048089 -0.022524 0.010077 +v 0.046218 -0.022363 0.009474 +v 0.047673 -0.022539 0.009047 +v 0.048220 -0.025869 0.010424 +v 0.047445 -0.022863 0.011142 +v 0.046734 -0.025861 0.011230 +v 0.045752 -0.025866 0.010333 +v 0.045653 -0.022863 0.009745 +v 0.046071 -0.025870 0.008816 +v 0.046624 -0.022865 0.008638 +v 0.047844 -0.025864 0.008922 +v -0.016548 0.025359 0.039065 +v -0.009487 0.020226 0.041848 +v -0.012722 0.019130 0.040307 +v -0.001529 0.024751 0.045776 +v 0.007843 0.019524 0.049604 +v 0.004602 0.018424 0.048061 +v -0.007285 0.017599 0.042641 +v -0.009933 -0.002884 0.039898 +v -0.007513 -0.000857 0.041142 +v -0.009119 -0.013791 0.039439 +v 0.016713 0.024013 0.053941 +v 0.010045 0.016897 0.050398 +v 0.025173 0.018822 0.057361 +v 0.029543 0.023062 0.059651 +v 0.027375 0.016195 0.058154 +v -0.012581 0.015155 0.040070 +v 0.021932 0.017723 0.055817 +v 0.022095 0.013739 0.055589 +v -0.007479 -0.017480 0.039899 +v 0.004415 -0.015472 0.045411 +v 0.004578 -0.019455 0.045183 +v -0.008966 0.014044 0.041615 +v 0.004765 0.014441 0.047833 +v -0.008799 0.002815 0.040840 +v 0.021962 0.001786 0.054625 +v 0.025695 0.012640 0.057128 +v 0.029801 -0.001447 0.057913 +v 0.008212 -0.014493 0.047196 +v 0.018694 -0.003699 0.052736 +v 0.021745 -0.016174 0.053168 +v 0.018757 0.001693 0.053173 +v 0.008364 0.013342 0.049371 +v -0.012908 -0.014767 0.037649 +v -0.015758 0.008825 0.038159 +v -0.012344 0.002602 0.039227 +v 0.017408 -0.000863 0.052372 +v 0.024110 -0.000738 0.055401 +v -0.012803 -0.001494 0.038710 +v 0.022364 -0.003933 0.054373 +v 0.025542 -0.015195 0.054952 +v 0.009851 -0.018182 0.047656 +v 0.027182 -0.018884 0.055412 +v -0.001804 -0.025096 0.041880 +v 0.029276 -0.026015 0.055816 +v 0.021908 -0.020157 0.052940 +v -0.009710 -0.019928 0.038709 +v 0.007621 -0.020630 0.046465 +v 0.024951 -0.021332 0.054222 +v -0.017457 -0.024465 0.034921 +v -0.012768 -0.018741 0.037420 +v 0.018175 0.001904 0.058424 +v 0.020817 -0.004120 0.059159 +v 0.021788 -0.000383 0.059879 +v -0.014195 -0.002575 0.043498 +v -0.015165 0.000402 0.043286 +v -0.011364 -0.003072 0.044736 +v -0.009609 -0.001003 0.045684 +v -0.010129 0.001553 0.045643 +v -0.012969 0.003074 0.044478 +v -0.022226 -0.024615 0.037083 +v -0.021051 0.025392 0.038956 +v -0.021483 -0.024470 0.035258 +v -0.021944 0.025240 0.041000 +v -0.021565 -0.023750 0.038545 +v -0.018762 -0.003864 0.041343 +v -0.021279 0.024155 0.042301 +v 0.027249 0.023147 0.063038 +v -0.006093 0.023512 0.049124 +v 0.013461 0.022720 0.057875 +v 0.026767 0.021960 0.063821 +v 0.028257 0.021741 0.063381 +v 0.026840 -0.001754 0.062052 +v 0.026865 -0.015043 0.060994 +v 0.027812 0.013962 0.062976 +v 0.026678 -0.022670 0.060411 +v 0.028013 -0.025013 0.059734 +v 0.027653 -0.018968 0.060359 +v 0.026517 -0.025439 0.060120 +v 0.026914 0.019301 0.063691 +v 0.027149 -0.026471 0.059230 +v -0.006356 -0.024154 0.045398 +v 0.013198 -0.024946 0.054149 +v 0.013072 0.007115 0.056519 +v 0.010145 0.019367 0.056109 +v 0.016786 0.013496 0.058667 +v -0.000706 0.017919 0.051116 +v 0.003986 0.022582 0.053576 +v 0.004415 0.009622 0.052794 +v -0.006256 0.008413 0.047907 +v 0.000312 0.012594 0.051182 +v 0.009988 0.012299 0.055509 +v 0.021079 0.009082 0.060264 +v -0.007723 0.006445 0.047097 +v -0.012139 0.010383 0.045404 +v 0.013037 -0.009471 0.055248 +v 0.015310 -0.000824 0.056927 +v 0.016681 -0.004039 0.057301 +v -0.007719 -0.007520 0.046042 +v -0.009725 -0.011515 0.044833 +v -0.014443 -0.011049 0.042741 +v 0.010882 -0.017942 0.053617 +v 0.016437 -0.016679 0.056223 +v -0.006055 -0.009315 0.046656 +v -0.000933 -0.016716 0.048399 +v 0.002003 -0.012015 0.050069 +v 0.001035 -0.022745 0.048815 +v 0.007620 -0.012224 0.052591 +v 0.007426 -0.023765 0.051626 +v -0.012712 -0.023553 0.042571 +v -0.017340 -0.020569 0.040712 +v -0.007527 -0.020890 0.045106 +v -0.018012 -0.014620 0.040858 +v -0.006916 -0.015541 0.045795 +v -0.007340 0.013006 0.047756 +v -0.015728 0.011846 0.043898 +v -0.017939 0.015322 0.043161 +v -0.016502 0.021653 0.044265 +v -0.009850 0.022631 0.047354 +v -0.006729 0.018355 0.048444 +v 0.025439 0.009938 0.062304 +v 0.021316 0.021880 0.061333 +v 0.017174 0.018337 0.059215 +v 0.023965 -0.012486 0.059940 +v 0.023600 -0.024702 0.058853 +v 0.018365 -0.023447 0.056571 +v 0.019685 -0.012726 0.057995 +v 0.014174 -0.009365 0.052470 +v -0.006404 -0.007702 0.043322 +v -0.004485 -0.009163 0.044077 +v 0.014727 0.006289 0.053904 +v -0.005920 0.008221 0.044746 +v 0.012957 0.007963 0.053233 +v 0.026153 -0.016900 0.057108 +v 0.022897 -0.015054 0.055787 +v 0.020670 -0.017345 0.054622 +v 0.021516 -0.020744 0.054728 +v 0.024419 -0.021308 0.056018 +v 0.025951 -0.020018 0.056806 +v 0.009193 -0.017720 0.049405 +v 0.007322 -0.014703 0.048806 +v 0.005002 -0.014683 0.047769 +v 0.003360 -0.016504 0.046883 +v 0.004084 -0.019903 0.046943 +v 0.007251 -0.020610 0.048326 +v -0.008255 -0.017016 0.041628 +v -0.009664 -0.014136 0.041181 +v -0.013211 -0.014389 0.039578 +v -0.013983 -0.017716 0.038973 +v -0.011598 -0.020136 0.039847 +v -0.009068 -0.019083 0.041093 +v 0.008839 0.014455 0.051690 +v 0.008621 0.018381 0.051882 +v 0.005594 0.019417 0.050609 +v 0.003685 0.017664 0.049623 +v 0.003598 0.015376 0.049406 +v 0.005673 0.013124 0.050159 +v -0.008410 0.018484 0.044212 +v -0.008452 0.015376 0.043977 +v -0.011478 0.020282 0.042957 +v -0.013716 0.018145 0.041810 +v -0.013537 0.015468 0.041694 +v -0.010820 0.013728 0.042773 +v 0.026430 0.016322 0.059763 +v 0.025030 0.018392 0.059292 +v 0.021730 0.018200 0.057772 +v 0.020848 0.014869 0.057140 +v 0.022428 0.012770 0.057698 +v 0.024691 0.012607 0.058702 +v 0.026247 0.014083 0.059524 +v -0.008265 -0.021399 0.044693 +v -0.006825 -0.017060 0.045682 +v -0.010751 -0.018585 0.043915 +v -0.014495 -0.018007 0.042272 +v -0.017998 -0.017050 0.040601 +v -0.017143 -0.020336 0.040803 +v -0.017598 -0.014545 0.041027 +v -0.014387 -0.022850 0.041855 +v -0.011757 -0.023207 0.042926 +v -0.012265 -0.014763 0.043522 +v -0.008388 -0.012992 0.045278 +v -0.011385 -0.011164 0.044051 +v -0.015157 -0.011571 0.042342 +v -0.002913 -0.017411 0.027811 +v -0.007814 -0.015905 0.025845 +v -0.007182 -0.013883 0.026256 +v -0.005974 -0.018403 0.026271 +v -0.003414 -0.013914 0.027758 +v -0.014088 -0.016521 0.038926 +v -0.007330 -0.018023 0.026253 +v -0.012447 -0.019624 0.039442 +v -0.004857 -0.018999 0.027290 +v -0.010010 -0.019740 0.040529 +v -0.008325 -0.017611 0.041449 +v -0.002735 -0.014645 0.028572 +v -0.009185 -0.014730 0.041281 +v -0.005319 -0.012773 0.027549 +v -0.011823 -0.013805 0.040161 +v -0.013254 -0.018395 0.040273 +v -0.009532 -0.017885 0.041989 +v -0.011897 -0.014599 0.041172 +v -0.007519 -0.001495 0.028897 +v -0.014397 -0.001557 0.042515 +v -0.008583 0.000964 0.028632 +v -0.014807 0.000247 0.042591 +v -0.013049 -0.002926 0.043018 +v -0.004826 -0.001989 0.030085 +v -0.010497 -0.002775 0.044192 +v -0.003111 -0.000534 0.029796 +v -0.009333 -0.000820 0.044901 +v -0.003027 0.001545 0.031180 +v -0.009578 0.001310 0.044925 +v -0.004306 0.003625 0.029568 +v -0.011397 0.002862 0.044202 +v -0.006353 0.003982 0.029849 +v -0.013686 0.002435 0.043147 +v -0.007532 0.002688 0.028071 +v -0.002839 0.000584 0.029914 +v -0.004490 -0.001520 0.028923 +v -0.006330 -0.001406 0.028109 +v -0.007782 0.000485 0.027677 +v -0.006661 0.003259 0.028265 +v -0.003163 0.002291 0.029875 +v -0.003675 0.000597 0.028922 +v -0.004705 0.002239 0.028443 +v -0.006184 0.000885 0.027689 +v -0.004722 0.000625 0.028195 +v -0.011780 -0.001030 0.044656 +v -0.012626 0.000314 0.044436 +v -0.012974 -0.001591 0.043930 +v -0.012687 0.001436 0.044291 +v -0.010851 0.000755 0.044959 +v 0.023208 -0.002079 0.041547 +v 0.016303 -0.003183 0.056220 +v 0.021983 0.000064 0.042338 +v 0.015789 -0.000620 0.056193 +v 0.023893 -0.003223 0.042928 +v 0.018117 -0.004311 0.056944 +v 0.026304 -0.002909 0.044056 +v 0.019855 -0.004094 0.057748 +v 0.027466 -0.001111 0.044728 +v 0.020938 -0.002877 0.058353 +v 0.021325 -0.001099 0.058641 +v 0.027705 0.000515 0.043772 +v 0.026890 0.001905 0.043506 +v 0.020348 0.000908 0.058367 +v 0.024514 0.002784 0.043668 +v 0.018825 0.001648 0.057728 +v 0.017084 0.001325 0.056906 +v 0.023192 0.001668 0.041815 +v 0.027139 -0.002014 0.043085 +v 0.025561 -0.002936 0.042434 +v 0.022730 -0.000486 0.041354 +v 0.024858 0.002470 0.042419 +v 0.026925 -0.000059 0.042665 +v 0.024763 -0.001535 0.041557 +v 0.024317 0.000213 0.041413 +v 0.025993 0.001047 0.042235 +v 0.025629 -0.000643 0.041788 +v 0.017393 -0.003200 0.057283 +v 0.016848 -0.000930 0.057448 +v 0.018073 -0.001893 0.058099 +v 0.018227 0.000162 0.058130 +v 0.020011 -0.000551 0.058684 +v 0.019395 -0.001525 0.058612 +v 0.018959 -0.003127 0.058067 +v 0.020353 0.014486 0.060435 +v 0.016801 0.016679 0.058869 +v 0.017778 0.012067 0.058936 +v 0.021250 0.017379 0.061058 +v 0.021779 0.021566 0.061495 +v 0.018623 0.019969 0.059955 +v 0.020404 0.009730 0.059948 +v 0.022872 0.009240 0.061131 +v 0.023438 0.013369 0.061741 +v 0.025177 0.020570 0.062883 +v 0.024336 0.016262 0.062364 +v 0.027285 0.012328 0.063270 +v 0.027992 0.015736 0.063824 +v 0.025362 0.010113 0.062185 +v 0.026875 0.018774 0.063607 +v 0.029321 0.019417 0.045106 +v 0.027929 0.014472 0.044250 +v 0.027339 0.018092 0.044197 +v 0.030636 0.014081 0.045233 +v 0.032182 0.017440 0.046300 +v 0.022262 0.018414 0.057960 +v 0.020883 0.015807 0.057139 +v 0.026753 0.016166 0.044202 +v 0.021767 0.013404 0.057358 +v 0.030487 0.013522 0.045661 +v 0.023623 0.012569 0.058132 +v 0.025481 0.013145 0.059015 +v 0.032281 0.015965 0.046678 +v 0.026573 0.015850 0.059703 +v 0.025017 0.018272 0.059191 +v 0.030597 0.019371 0.046176 +v 0.024381 0.013527 0.059649 +v 0.024980 0.016967 0.060179 +v 0.021594 0.014097 0.058436 +v 0.022193 0.017537 0.058966 +v -0.016297 0.012632 0.043682 +v -0.012677 0.010643 0.045117 +v -0.014308 0.015889 0.044921 +v -0.010564 0.015311 0.046565 +v -0.006698 0.016480 0.048201 +v -0.007201 0.019116 0.048309 +v -0.017717 0.015484 0.043170 +v -0.017047 0.020281 0.043876 +v -0.009688 0.011335 0.046593 +v -0.012078 0.019133 0.046172 +v -0.014124 0.022592 0.045396 +v -0.008771 0.021486 0.047671 +v -0.011630 0.022786 0.046526 +v -0.007579 0.013221 0.047616 +v -0.002929 0.016524 0.030306 +v -0.007188 0.016951 0.028400 +v -0.007513 0.019182 0.028626 +v -0.005179 0.015152 0.029379 +v -0.005810 0.020872 0.029497 +v -0.002355 0.018436 0.030876 +v -0.013667 0.018284 0.041755 +v -0.007389 0.016108 0.028802 +v -0.013341 0.015510 0.041695 +v -0.011774 0.014067 0.042294 +v -0.008833 0.014724 0.043669 +v -0.003248 0.015593 0.030633 +v -0.008306 0.018007 0.044152 +v -0.003605 0.020586 0.030846 +v -0.010692 0.020192 0.043245 +v -0.013067 0.015501 0.042923 +v -0.009345 0.016011 0.044638 +v -0.011710 0.019297 0.043821 +v 0.005252 0.018431 0.053928 +v 0.008766 0.020463 0.055581 +v 0.006509 0.021924 0.054651 +v 0.006767 0.014609 0.054322 +v 0.010454 0.014156 0.055790 +v 0.010290 0.018098 0.056018 +v 0.003022 0.015187 0.052678 +v -0.000454 0.015473 0.050985 +v 0.000389 0.012945 0.051249 +v -0.000113 0.018490 0.051390 +v 0.003781 0.022066 0.053360 +v 0.001293 0.020671 0.052198 +v 0.002152 0.010944 0.051806 +v 0.005834 0.009979 0.053437 +v 0.008778 0.011411 0.054878 +v 0.013532 0.014640 0.037738 +v 0.009868 0.016333 0.036174 +v 0.011281 0.019939 0.037020 +v 0.015027 0.017009 0.038596 +v 0.013216 0.019743 0.037821 +v 0.003593 0.017011 0.049442 +v 0.009737 0.018852 0.036737 +v 0.004368 0.014103 0.049569 +v 0.011236 0.014352 0.037062 +v 0.007030 0.013272 0.050708 +v 0.008639 0.014480 0.051524 +v 0.009142 0.017291 0.051959 +v 0.013726 0.019884 0.038603 +v 0.006676 0.019370 0.051009 +v 0.004736 0.018821 0.050092 +v 0.004263 0.014799 0.050679 +v 0.007985 0.015309 0.052395 +v 0.005621 0.018595 0.051578 +v 0.021919 -0.020877 0.058464 +v 0.024121 -0.024323 0.059048 +v 0.026423 -0.022597 0.060254 +v 0.020404 -0.017055 0.058071 +v 0.016604 -0.018622 0.056092 +v 0.017730 -0.021978 0.056368 +v 0.017406 -0.015257 0.056758 +v 0.020353 -0.024275 0.057385 +v 0.019840 -0.012799 0.058038 +v 0.024149 -0.017634 0.059714 +v 0.024696 -0.013119 0.060188 +v 0.027829 -0.019286 0.061143 +v 0.027049 -0.015633 0.061039 +v 0.030449 -0.019815 0.042584 +v 0.027012 -0.018265 0.041281 +v 0.028440 -0.014662 0.042127 +v 0.032117 -0.017284 0.043755 +v 0.030628 -0.014935 0.043038 +v 0.021604 -0.015978 0.055063 +v 0.026944 -0.015588 0.041882 +v 0.020643 -0.018761 0.054413 +v 0.028379 -0.020246 0.042169 +v 0.022659 -0.021223 0.055137 +v 0.025355 -0.020768 0.056391 +v 0.031225 -0.019707 0.043497 +v 0.026291 -0.018499 0.056981 +v 0.025689 -0.016403 0.056873 +v 0.030869 -0.014714 0.043710 +v 0.023643 -0.015222 0.056034 +v 0.021893 -0.012421 0.058737 +v 0.025129 -0.019289 0.057502 +v 0.022088 -0.020349 0.056051 +v 0.021071 -0.017438 0.055813 +v 0.024112 -0.016378 0.057264 +v 0.009542 -0.021274 0.052731 +v 0.010410 -0.018591 0.053319 +v 0.006818 -0.016932 0.051958 +v 0.003074 -0.016353 0.050314 +v -0.000696 -0.016938 0.048441 +v -0.000242 -0.020004 0.048423 +v 0.000635 -0.013690 0.049293 +v 0.009774 -0.014935 0.053326 +v 0.004588 -0.020175 0.050707 +v 0.001753 -0.022839 0.049082 +v 0.005106 -0.023894 0.050534 +v 0.007634 -0.023183 0.051720 +v 0.003807 -0.011706 0.050859 +v 0.007158 -0.012326 0.052346 +v 0.014266 -0.017939 0.035447 +v 0.009955 -0.017647 0.033507 +v 0.010905 -0.013954 0.034397 +v 0.012059 -0.019447 0.034510 +v 0.014070 -0.014879 0.035576 +v 0.003240 -0.017592 0.046659 +v 0.009309 -0.015669 0.033931 +v 0.009754 -0.018490 0.033909 +v 0.005189 -0.020489 0.047320 +v 0.007774 -0.020205 0.048509 +v 0.013895 -0.019005 0.035740 +v 0.009001 -0.017950 0.049233 +v 0.014800 -0.016545 0.036340 +v 0.008410 -0.015859 0.049125 +v 0.013539 -0.014012 0.035953 +v 0.006765 -0.014585 0.048480 +v 0.004647 -0.014986 0.047493 +v 0.007798 -0.018587 0.049745 +v 0.004758 -0.019647 0.048295 +v 0.003740 -0.016736 0.048057 +v 0.006781 -0.015676 0.049507 +v 0.018993 0.023920 0.054962 +v 0.022109 0.024443 0.048049 +v -0.012552 0.025847 0.032536 +v -0.015667 0.025324 0.039449 +v 0.021833 -0.025404 0.044153 +v 0.018718 -0.025927 0.051065 +v -0.012827 -0.024000 0.028640 +v -0.015942 -0.024523 0.035552 +v 0.033036 0.020794 0.052698 +v 0.029921 0.020271 0.059610 +v 0.029682 -0.023165 0.056215 +v 0.032797 -0.022642 0.049302 +v 0.007232 0.040296 0.013336 +v 0.007574 0.040297 0.013190 +v 0.008704 0.040309 0.013429 +v 0.007737 0.040303 0.013702 +v 0.008841 0.040313 0.013747 +v 0.006964 0.040289 0.012914 +v 0.007910 0.040277 0.010896 +v 0.007987 0.040281 0.011234 +v 0.007792 0.040277 0.010938 +v 0.007216 0.040283 0.012093 +v 0.009613 0.040313 0.013134 +v 0.009475 0.040307 0.012570 +v 0.006900 0.040279 0.011930 +v 0.009837 0.040306 0.012173 +v 0.009226 0.040290 0.011117 +v 0.009117 0.040293 0.011472 +v 0.008347 0.032658 0.013704 +v 0.009303 0.032662 0.013350 +v 0.009709 0.032656 0.012415 +v 0.009453 0.032647 0.011632 +v 0.008574 0.032634 0.011117 +v 0.007593 0.032629 0.011393 +v 0.007112 0.032636 0.012502 +v 0.007580 0.032648 0.013407 +v 0.008336 0.032860 0.013902 +v 0.008289 0.038659 0.013846 +v 0.009041 0.032864 0.013763 +v 0.008993 0.038664 0.013707 +v 0.009439 0.032865 0.013493 +v 0.009730 0.032863 0.013110 +v 0.009682 0.038663 0.013054 +v 0.009907 0.032858 0.012414 +v 0.009859 0.038658 0.012358 +v 0.009692 0.038649 0.011659 +v 0.009612 0.032847 0.011511 +v 0.009564 0.038646 0.011455 +v 0.009268 0.032841 0.011175 +v 0.009220 0.038640 0.011119 +v 0.008598 0.032833 0.010916 +v 0.008550 0.038632 0.010860 +v 0.007885 0.032828 0.010998 +v 0.007837 0.038627 0.010941 +v 0.007466 0.032826 0.011236 +v 0.007291 0.032827 0.011402 +v 0.007243 0.038626 0.011345 +v 0.007031 0.032828 0.011807 +v 0.006983 0.038628 0.011750 +v 0.006911 0.032834 0.012515 +v 0.006863 0.038634 0.012458 +v 0.007023 0.032840 0.012983 +v 0.006975 0.038639 0.012926 +v 0.007450 0.032849 0.013559 +v 0.007403 0.038648 0.013503 +v 0.007444 0.038664 0.015047 +v 0.005555 0.038617 0.011841 +v 0.006313 0.038647 0.014331 +v 0.005750 0.038635 0.013494 +v 0.009108 0.038678 0.015097 +v 0.010019 0.038681 0.014664 +v 0.007136 0.038610 0.009774 +v 0.008108 0.038615 0.009509 +v 0.006316 0.038609 0.010361 +v 0.011129 0.038674 0.013019 +v 0.010722 0.038680 0.013941 +v 0.011032 0.038657 0.011357 +v 0.009432 0.038628 0.009707 +v 0.010284 0.038640 0.010246 +v 0.007422 0.038994 0.015037 +v 0.007200 0.038991 0.014949 +v 0.006241 0.038976 0.014254 +v 0.005731 0.038964 0.013452 +v 0.005556 0.038947 0.011814 +v 0.005776 0.038942 0.011134 +v 0.006158 0.038939 0.010530 +v 0.006492 0.038939 0.010189 +v 0.007086 0.038940 0.009793 +v 0.008234 0.038946 0.009497 +v 0.008472 0.038948 0.009497 +v 0.009177 0.038955 0.009615 +v 0.009402 0.038958 0.009693 +v 0.010216 0.038969 0.010185 +v 0.010550 0.038975 0.010525 +v 0.011100 0.038990 0.011574 +v 0.011132 0.039004 0.012992 +v 0.010985 0.039007 0.013445 +v 0.010765 0.039010 0.013868 +v 0.009068 0.039008 0.015104 +v 0.006749 0.039146 0.010138 +v 0.006570 0.039146 0.010280 +v 0.011033 0.039198 0.011828 +v 0.010981 0.039195 0.011606 +v 0.009432 0.039888 0.010541 +v 0.010024 0.040187 0.012010 +v 0.010045 0.040189 0.012152 +v 0.007504 0.039393 0.014787 +v 0.007574 0.040054 0.014077 +v 0.007303 0.039391 0.014707 +v 0.007431 0.040052 0.014006 +v 0.006431 0.039377 0.014075 +v 0.007079 0.040177 0.013477 +v 0.006987 0.040176 0.013367 +v 0.006168 0.039372 0.013731 +v 0.006003 0.039536 0.011686 +v 0.006239 0.039532 0.011122 +v 0.007225 0.040019 0.010792 +v 0.007644 0.040020 0.010562 +v 0.007794 0.040021 0.010509 +v 0.007579 0.039647 0.013197 +v 0.008709 0.039659 0.013435 +v 0.007221 0.039633 0.012099 +v 0.007993 0.039631 0.011240 +v 0.009123 0.039643 0.011479 +v 0.009481 0.039657 0.012576 +v -0.018737 0.037668 0.002562 +v -0.018301 0.036149 0.002861 +v -0.019399 0.037391 0.002271 +v -0.019460 0.037365 0.002244 +v -0.020939 0.036745 0.001592 +v -0.020282 0.035303 0.001810 +v -0.022033 0.036110 0.001301 +v -0.021184 0.034775 0.001521 +v -0.023755 0.034688 0.000888 +v -0.024550 0.034032 0.000697 +v -0.023438 0.032903 0.000969 +v -0.025301 0.033174 0.000508 +v -0.025613 0.029684 0.000428 +v -0.023955 0.032319 0.000844 +v -0.027488 0.016000 -0.000065 +v -0.029077 0.016000 -0.000500 +v -0.026649 0.025922 0.000158 +v -0.028241 0.026028 -0.000270 +v -0.025933 0.028923 0.000346 +v -0.027508 0.029238 -0.000071 +v -0.027050 0.030354 0.000052 +v -0.016947 0.038135 0.004203 +v -0.016651 0.036588 0.004549 +v -0.016858 0.038158 0.004285 +v -0.013985 0.036913 0.008413 +v -0.013986 0.038501 0.008411 +v -0.011046 0.036957 0.011450 +v -0.011047 0.038545 0.011448 +v -0.008537 0.036963 0.013364 +v -0.008496 0.038550 0.013392 +v -0.002947 0.036983 0.016672 +v -0.002878 0.038571 0.016709 +v 0.013746 0.037130 0.023734 +v 0.013938 0.038720 0.023795 +v 0.037574 0.039025 0.029285 +v 0.046338 0.037530 0.030907 +v 0.046465 0.039118 0.030931 +v 0.078986 0.037510 0.037079 +v 0.079048 0.039097 0.037089 +v 0.096579 0.037115 0.039068 +v 0.096638 0.038702 0.039071 +v 0.113295 0.036422 0.038596 +v 0.113353 0.038009 0.038589 +v 0.120528 0.036042 0.037401 +v 0.120556 0.037630 0.037395 +v 0.155914 0.035312 0.029873 +v 0.187091 0.030794 0.030373 +v 0.183969 0.032730 0.030376 +v 0.155980 0.033714 0.029874 +v 0.155924 0.033719 0.029871 +v 0.155859 0.035316 0.029870 +v 0.142154 0.034686 0.031014 +v 0.142131 0.036278 0.031020 +v 0.147699 0.034310 0.030040 +v 0.147670 0.035903 0.030043 +v 0.225461 0.026148 0.030231 +v 0.226038 0.027675 0.030248 +v 0.237984 0.024594 0.030694 +v 0.237672 0.026231 0.030681 +v 0.262513 0.023467 0.031675 +v 0.325210 0.019364 0.031994 +v 0.320644 0.019558 0.032025 +v 0.276893 0.022134 0.032058 +v 0.277321 0.020504 0.032065 +v 0.275634 0.022250 0.032024 +v 0.342000 0.018095 0.032025 +v 0.342000 0.017507 0.032025 +v 0.340997 0.019099 0.032016 +v 0.155924 -0.033719 0.029871 +v 0.155859 -0.035316 0.029870 +v 0.155914 -0.035312 0.029873 +v 0.152808 -0.035542 0.029841 +v 0.147080 -0.035943 0.030101 +v 0.121219 -0.037593 0.037253 +v 0.037043 -0.039019 0.029186 +v 0.103669 -0.038447 0.039212 +v 0.089106 -0.038912 0.038468 +v 0.076720 -0.039126 0.036700 +v 0.017810 -0.038768 0.024954 +v 0.007407 -0.038648 0.021460 +v 0.001483 -0.038597 0.018893 +v -0.011002 -0.038545 0.011488 +v -0.008361 -0.038551 0.013484 +v -0.013985 -0.036913 0.008413 +v -0.013986 -0.038501 0.008411 +v -0.017089 -0.036490 0.004007 +v -0.017307 -0.038061 0.003764 +v -0.019104 -0.037543 0.002345 +v -0.019394 -0.037408 0.002236 +v -0.019105 -0.035852 0.002344 +v -0.029077 -0.016000 -0.000500 +v -0.027488 -0.016000 -0.000065 +v -0.028241 -0.026028 -0.000270 +v -0.026649 -0.025923 0.000158 +v -0.027443 -0.029416 -0.000053 +v -0.026143 -0.028323 0.000291 +v -0.025091 -0.033428 0.000561 +v -0.024269 -0.031923 0.000767 +v -0.024210 -0.034376 0.000782 +v -0.021350 -0.034666 0.001475 +v -0.021568 -0.036396 0.001417 +v 0.226038 -0.027675 0.030248 +v 0.226537 -0.027616 0.030268 +v 0.278739 -0.021978 0.032088 +v 0.342000 -0.017507 0.032025 +v 0.342000 -0.018095 0.032025 +v 0.340997 -0.019099 0.032016 +v 0.310340 -0.019916 0.032095 +v 0.220317 -0.028387 0.030555 +v 0.204312 0.005308 0.067616 +v 0.209123 0.006348 0.066516 +v 0.213293 0.007250 0.065563 +v 0.216972 0.009027 0.064573 +v 0.217689 0.009876 0.064290 +v 0.217876 0.010397 0.064162 +v 0.217734 0.009929 0.064273 +v 0.217796 0.011065 0.064055 +v 0.217214 0.011939 0.064000 +v 0.215794 0.013006 0.064063 +v 0.211755 0.014766 0.064493 +v 0.186195 0.004009 0.071613 +v 0.078985 0.010410 0.098840 +v 0.082525 0.007973 0.097913 +v 0.084556 0.007379 0.097350 +v 0.091609 0.005317 0.095398 +v 0.093575 0.005155 0.094857 +v 0.100385 0.004595 0.092986 +v 0.107613 0.004000 0.091000 +v 0.078108 0.012890 0.098950 +v 0.078206 0.011729 0.098995 +v 0.078675 0.014210 0.098689 +v 0.100740 0.019984 0.091507 +v 0.097899 0.019683 0.092389 +v 0.087903 0.018622 0.095489 +v 0.087862 0.018607 0.095503 +v 0.083016 0.016905 0.097140 +v 0.081084 0.016226 0.097792 +v 0.177540 0.019930 0.070938 +v 0.239543 -0.006254 0.062251 +v 0.311781 -0.002259 0.052586 +v 0.311782 0.000000 0.052636 +v 0.294463 0.000000 0.054376 +v 0.005390 0.031066 0.077232 +v -0.012727 0.024500 0.048000 +v -0.012922 0.016858 0.049017 +v -0.028968 0.016000 0.002378 +v -0.028309 0.016335 0.006454 +v -0.027708 0.026632 0.004793 +v -0.025891 0.019268 0.014737 +v -0.027179 0.017397 0.010617 +v -0.025087 0.020741 0.017026 +v -0.023730 0.023718 0.020443 +v -0.022745 0.026268 0.022576 +v -0.022397 0.027006 0.023351 +v -0.022045 0.028696 0.023750 +v -0.022025 0.027418 0.024302 +v -0.021776 0.027500 0.025000 +v -0.017208 0.029918 0.036358 +v -0.013791 0.027500 0.045000 +v -0.011444 0.030908 0.049036 +v -0.013329 0.027311 0.046048 +v -0.012954 0.026742 0.046993 +v -0.012740 0.025913 0.047646 +v -0.012693 0.024995 0.047959 +v -0.011380 0.030919 0.049176 +v -0.005080 0.031386 0.061067 +v 0.002479 0.031225 0.073179 +v 0.001081 0.031302 0.071233 +v 0.010919 0.030652 0.083332 +v 0.016838 0.030281 0.088462 +v 0.029299 0.029770 0.096008 +v 0.036495 0.029611 0.098846 +v 0.043932 0.029529 0.100814 +v 0.059457 0.029570 0.102094 +v 0.051693 0.029518 0.101916 +v 0.062966 0.029617 0.101760 +v 0.067244 0.029675 0.101354 +v 0.079016 0.029904 0.098360 +v 0.074759 0.029821 0.099746 +v 0.069942 0.029727 0.100776 +v 0.080760 0.015865 0.099587 +v 0.083422 0.017226 0.098654 +v 0.083893 0.017467 0.098489 +v 0.088906 0.018914 0.096822 +v 0.095928 0.019924 0.094601 +v 0.102910 0.020223 0.092509 +v 0.165725 0.020519 0.075407 +v 0.169415 0.020394 0.074546 +v 0.173514 0.020405 0.073490 +v 0.182393 0.020144 0.071392 +v 0.154267 0.020355 0.078448 +v 0.079544 0.010416 0.100331 +v 0.069009 -0.000000 0.102905 +v 0.078615 0.011936 0.100520 +v 0.078567 0.013079 0.100461 +v 0.079213 0.014429 0.100173 +v 0.098249 0.004508 0.095207 +v 0.079615 -0.000000 0.100594 +v 0.094005 0.005136 0.096382 +v 0.090795 0.005612 0.097270 +v 0.085314 0.007090 0.098791 +v 0.081712 0.008699 0.099775 +v 0.080399 0.009698 0.100115 +v 0.079622 0.010289 0.100316 +v 0.103509 0.004260 0.093768 +v 0.132913 0.000000 0.086054 +v 0.150581 0.004069 0.081554 +v 0.202343 0.005180 0.069668 +v 0.200830 0.004943 0.070005 +v 0.189692 0.004166 0.072460 +v 0.239543 0.006254 0.062251 +v 0.210041 0.006494 0.067942 +v 0.239590 -0.000000 0.062601 +v 0.209163 0.006249 0.068149 +v 0.217453 0.012329 0.065524 +v 0.218097 0.011384 0.065581 +v 0.218192 0.010731 0.065683 +v 0.217993 0.010132 0.065827 +v 0.217960 0.010031 0.065851 +v 0.216933 0.008994 0.066223 +v 0.214266 0.007671 0.066945 +v 0.212076 0.015143 0.066002 +v 0.215676 0.013595 0.065615 +v 0.273621 0.006094 0.056689 +v 0.247266 0.009623 0.060371 +v 0.274318 0.006018 0.056607 +v 0.296318 0.003611 0.054020 +v 0.341004 -0.000000 0.051114 +v 0.341005 0.000223 0.051114 +v 0.335040 0.000590 0.051243 +v 0.328313 -0.000000 0.051517 +v 0.316992 0.001848 0.052180 +v 0.331440 -0.000819 0.051369 +v 0.341004 -0.000222 0.051114 +v 0.312341 -0.002208 0.052532 +v 0.316456 -0.001909 0.052282 +v 0.291330 -0.004102 0.054557 +v 0.274733 -0.006019 0.056608 +v 0.241181 -0.010532 0.061287 +v 0.267086 -0.006903 0.057553 +v 0.182909 -0.020044 0.071381 +v 0.174438 -0.021469 0.072962 +v 0.165725 -0.020519 0.075407 +v 0.067240 -0.029671 0.101355 +v 0.074076 -0.029802 0.099930 +v 0.059857 -0.029574 0.102078 +v 0.044155 -0.029528 0.100859 +v 0.048037 -0.029523 0.101396 +v 0.051954 -0.029519 0.101937 +v 0.055872 -0.029546 0.102007 +v 0.029481 -0.029766 0.096093 +v 0.036581 -0.029610 0.098874 +v 0.023500 -0.029969 0.092961 +v 0.011072 -0.030641 0.083481 +v 0.005829 -0.031036 0.077774 +v 0.016984 -0.030274 0.088573 +v 0.001438 -0.031298 0.071780 +v -0.004609 -0.031392 0.061892 +v -0.011422 -0.030889 0.049025 +v -0.010972 -0.030963 0.050002 +v -0.012727 -0.024500 0.048000 +v -0.012695 -0.025405 0.047860 +v -0.012795 -0.026222 0.047457 +v -0.013013 -0.026873 0.046835 +v -0.013343 -0.027323 0.046016 +v -0.013791 -0.027500 0.045000 +v -0.016637 -0.030034 0.037714 +v -0.021776 -0.027500 0.025000 +v -0.021951 -0.028721 0.024019 +v -0.022158 -0.027310 0.023950 +v -0.022276 -0.027139 0.023662 +v -0.022534 -0.026763 0.023031 +v -0.024093 -0.022860 0.019581 +v -0.026491 -0.018317 0.012888 +v -0.025171 -0.020577 0.016797 +v -0.027681 -0.016850 0.008843 +v -0.027734 -0.026617 0.004652 +v -0.028618 -0.016136 0.004987 +v -0.028968 -0.016000 0.002378 +v -0.013781 0.010820 0.048000 +v -0.013542 0.000000 0.049005 +v -0.014016 -0.002930 0.048000 +v 0.132634 -0.014495 0.085116 +v 0.132843 -0.007265 0.085819 +v -0.002955 -0.000000 0.067844 +v 0.205472 0.016484 0.065375 +v 0.201925 0.017134 0.065984 +v 0.195442 0.018321 0.067097 +v 0.342000 0.000401 0.049511 +v 0.342000 0.016498 0.037857 +v 0.342000 0.005802 0.048525 +v 0.342000 0.004161 0.049013 +v 0.342000 0.009226 0.046884 +v 0.342000 0.014849 0.041277 +v 0.342000 0.013630 0.042990 +v 0.342000 0.010942 0.045671 +v 0.342000 0.017082 0.035835 +v 0.342000 -0.012301 0.044461 +v 0.342000 -0.015732 0.039684 +v 0.342000 -0.003895 0.049076 +v 0.342000 -0.001820 0.049421 +v 0.342000 -0.016539 0.037741 +v 0.342000 -0.017387 0.034040 +v 0.342000 -0.013706 0.042895 +v 0.342000 -0.009327 0.046821 +v 0.342000 -0.007482 0.047834 +v 0.002973 0.033476 0.072964 +v -0.000887 0.037443 0.059037 +v 0.289505 0.007602 0.054008 +v -0.023599 0.034922 0.003138 +v 0.207298 0.016390 0.066690 +v 0.330127 0.001784 0.051376 +v 0.341005 0.000601 0.051107 +v 0.341005 0.000317 0.051112 +v 0.330109 0.001350 0.051407 +v 0.234842 0.013566 0.061617 +v 0.186167 0.019937 0.070536 +v 0.181579 0.022169 0.070762 +v 0.201076 0.018015 0.067585 +v -0.027508 0.029238 -0.000071 +v -0.026530 0.031012 0.003932 +v -0.018313 0.037723 0.008555 +v 0.128781 0.029611 0.082704 +v 0.289449 0.005972 0.054499 +v 0.260368 0.009792 0.057980 +v 0.181440 0.025220 0.067930 +v 0.206916 0.022428 0.061551 +v 0.162983 0.028702 0.069925 +v 0.234728 0.018536 0.057456 +v 0.234849 0.017179 0.059117 +v 0.254587 0.015805 0.055149 +v 0.320527 0.004641 0.051486 +v 0.300964 0.008607 0.051965 +v 0.280411 0.012053 0.052940 +v 0.275676 0.012749 0.053313 +v 0.260427 0.011728 0.057118 +v 0.260354 0.015001 0.054520 +v 0.259271 0.015160 0.054605 +v 0.008477 0.035117 0.077862 +v 0.010047 0.036454 0.076605 +v -0.002928 0.036005 0.060111 +v -0.013972 0.036071 0.035728 +v 0.029658 0.033928 0.094150 +v 0.030524 0.035309 0.092425 +v 0.042879 0.034991 0.096787 +v 0.042422 0.033621 0.098622 +v 0.101900 0.034396 0.087352 +v 0.076195 0.033592 0.097383 +v 0.075672 0.034848 0.095697 +v 0.069598 0.033533 0.099055 +v 0.062664 0.034814 0.098223 +v 0.055930 0.033503 0.100295 +v 0.055974 0.034840 0.098449 +v 0.018163 0.034443 0.087100 +v 0.019408 0.035812 0.085573 +v -0.009255 0.038534 0.028938 +v 0.010994 0.037031 0.074279 +v 0.062554 0.035424 0.096193 +v 0.077509 0.035466 0.093049 +v 0.102326 0.033232 0.088941 +v 0.155064 0.027864 0.075046 +v 0.208340 0.019592 0.064703 +v -0.016027 0.033209 0.036577 +v -0.004385 0.033830 0.060844 +v 0.007356 0.033146 0.078696 +v 0.011998 0.032793 0.083598 +v 0.017275 0.032461 0.088118 +v 0.029040 0.031952 0.095312 +v 0.035491 0.031784 0.097957 +v 0.042093 0.031677 0.099874 +v 0.055893 0.031618 0.101575 +v 0.048984 0.031623 0.101098 +v 0.069846 0.031728 0.100299 +v 0.062930 0.031655 0.101307 +v 0.089662 0.031951 0.094218 +v 0.076574 0.031831 0.098586 +v 0.113901 0.034224 0.081985 +v 0.239384 0.024511 0.042037 +v 0.340998 0.017140 0.040430 +v 0.253232 0.024347 0.033770 +v 0.320641 0.019271 0.035080 +v 0.340998 0.017557 0.039270 +v 0.340997 0.018581 0.036422 +v 0.340997 0.019094 0.032458 +v 0.340999 0.014892 0.043965 +v 0.320596 0.010931 0.048537 +v 0.341001 0.012008 0.046846 +v 0.341001 0.012108 0.046780 +v 0.341003 0.006483 0.049856 +v 0.341002 0.008616 0.049057 +v 0.341004 0.004675 0.050532 +v 0.298108 0.012022 0.050064 +v 0.275678 0.013709 0.052370 +v 0.253257 0.019219 0.050504 +v 0.208266 0.024276 0.056653 +v 0.162941 0.030415 0.063563 +v -0.004933 0.038542 0.034565 +v -0.007506 0.038545 0.024582 +v -0.004939 0.038559 0.020362 +v 0.010904 0.038686 0.032399 +v 0.235444 0.021756 0.050809 +v 0.275695 0.019986 0.043043 +v 0.167122 0.031551 0.055711 +v 0.298137 0.015832 0.046122 +v 0.162875 -0.033157 0.049554 +v 0.341005 -0.002158 0.050993 +v 0.310612 -0.006651 0.051729 +v 0.280319 -0.012067 0.052946 +v 0.275676 -0.012746 0.053322 +v 0.275678 -0.013680 0.052398 +v 0.172168 -0.027456 0.067923 +v 0.162983 -0.028695 0.069927 +v 0.162942 -0.030396 0.063640 +v 0.162832 -0.034591 0.035557 +v 0.010904 -0.038686 0.032408 +v -0.007392 -0.038545 0.024591 +v -0.006863 -0.038515 0.036935 +v 0.010132 -0.037104 0.073166 +v 0.068824 -0.035423 0.095342 +v 0.053833 -0.035468 0.096296 +v 0.091273 -0.035356 0.088658 +v 0.140268 -0.031761 0.074540 +v 0.108839 -0.034579 0.083422 +v 0.201062 -0.023269 0.062530 +v 0.208266 -0.024249 0.056718 +v 0.228899 -0.019342 0.058214 +v 0.230793 -0.021535 0.053473 +v 0.253257 -0.019187 0.050560 +v 0.253269 -0.015991 0.055274 +v 0.275694 -0.017256 0.048089 +v 0.256591 -0.015534 0.054873 +v 0.260355 -0.014985 0.054562 +v 0.267936 -0.015441 0.052185 +v 0.298108 -0.011991 0.050088 +v 0.320595 -0.010900 0.048559 +v 0.323588 -0.004033 0.051406 +v 0.341004 -0.005983 0.050151 +v 0.341004 -0.005345 0.050292 +v 0.341005 -0.002239 0.050975 +v 0.341002 -0.009733 0.048444 +v 0.340999 -0.015549 0.043097 +v 0.320623 -0.014859 0.044909 +v 0.341000 -0.012926 0.046069 +v 0.341001 -0.011001 0.047501 +v 0.340998 -0.017322 0.040051 +v 0.340997 -0.018640 0.036166 +v 0.239483 -0.024513 0.041981 +v 0.230768 -0.023916 0.047824 +v 0.208231 -0.026402 0.050656 +v -0.016027 -0.033209 0.036577 +v -0.018313 -0.037723 0.008555 +v -0.023599 -0.034922 0.003138 +v -0.026530 -0.031012 0.003933 +v -0.026903 -0.030662 0.000091 +v 0.208313 -0.017770 0.065900 +v 0.316490 -0.002812 0.052144 +v 0.289449 -0.005972 0.054499 +v 0.260368 -0.009792 0.057980 +v 0.234842 -0.013566 0.061617 +v 0.154860 -0.029096 0.073463 +v 0.208259 -0.021121 0.063150 +v 0.181440 -0.025220 0.067930 +v 0.181570 -0.023859 0.069520 +v 0.234890 -0.015493 0.060542 +v 0.330127 -0.001784 0.051376 +v 0.316525 -0.003730 0.052007 +v 0.289505 -0.007602 0.054008 +v 0.260427 -0.011728 0.057118 +v -0.000887 -0.037443 0.059037 +v 0.010047 -0.036454 0.076605 +v 0.019408 -0.035812 0.085573 +v 0.030524 -0.035309 0.092425 +v 0.042880 -0.034991 0.096788 +v 0.055974 -0.034840 0.098449 +v 0.075672 -0.034848 0.095697 +v 0.101900 -0.034396 0.087352 +v 0.102326 -0.033232 0.088941 +v 0.076195 -0.033592 0.097383 +v 0.069598 -0.033533 0.099055 +v 0.055930 -0.033503 0.100295 +v 0.042422 -0.033621 0.098622 +v 0.029658 -0.033928 0.094150 +v 0.018163 -0.034443 0.087100 +v 0.008477 -0.035117 0.077863 +v -0.002928 -0.036005 0.060111 +v -0.013972 -0.036071 0.035728 +v -0.004385 -0.033830 0.060845 +v 0.007356 -0.033146 0.078696 +v 0.017275 -0.032461 0.088118 +v 0.011998 -0.032793 0.083598 +v 0.022929 -0.032180 0.092005 +v 0.029040 -0.031952 0.095312 +v 0.042093 -0.031677 0.099874 +v 0.035491 -0.031784 0.097957 +v 0.055893 -0.031618 0.101575 +v 0.048985 -0.031623 0.101098 +v 0.069846 -0.031728 0.100299 +v 0.062930 -0.031655 0.101307 +v 0.076574 -0.031831 0.098586 +v 0.102609 -0.031631 0.090131 +v 0.342000 -0.008380 0.048049 +v 0.342000 -0.014518 0.042808 +v 0.342000 -0.016568 0.039279 +v 0.342000 0.017631 0.036075 +v 0.342000 0.016281 0.039902 +v 0.342000 0.014098 0.043350 +v 0.342000 -0.011745 0.045775 +v 0.342000 0.011366 0.046059 +v 0.342000 0.011212 0.046212 +v 0.342000 -0.005056 0.049336 +v 0.342000 -0.004584 0.049519 +v 0.342000 0.007765 0.048356 +v 0.342000 -0.017650 0.035991 +v 0.342000 0.003938 0.049676 +v 0.342000 0.000567 0.050103 +v 0.262174 0.023501 0.031663 +v 0.154007 0.035454 0.029847 +v 0.147335 0.034335 0.030075 +v 0.147307 0.035928 0.030078 +v 0.141847 0.036298 0.031097 +v 0.112842 0.036445 0.038649 +v 0.112900 0.038031 0.038642 +v 0.096342 0.037123 0.039056 +v 0.096401 0.038709 0.039059 +v 0.037085 0.039019 0.029194 +v 0.005100 0.037039 0.020513 +v 0.005173 0.038627 0.020544 +v -0.011092 0.036957 0.011410 +v -0.011089 0.038545 0.011413 +v -0.023467 0.034929 0.000957 +v -0.022070 0.036086 0.001292 +v -0.021217 0.034753 0.001512 +v -0.017025 0.038123 0.004082 +v -0.027523 0.029196 -0.000075 +v -0.025948 0.028884 0.000342 +v -0.025535 0.032805 0.000447 +v -0.023982 0.032286 0.000838 +v -0.025329 0.033138 0.000501 +v 0.282900 -0.020049 0.032138 +v 0.318313 -0.019585 0.032035 +v 0.153599 -0.033887 0.029896 +v 0.147135 -0.035940 0.030095 +v 0.148997 -0.034221 0.029944 +v 0.144275 -0.036133 0.030630 +v 0.142003 -0.036287 0.031054 +v 0.144000 -0.034561 0.030574 +v 0.105412 -0.038369 0.039115 +v 0.112740 -0.038039 0.038660 +v 0.113195 -0.036420 0.038505 +v 0.113137 -0.038018 0.038595 +v 0.116890 -0.036238 0.038085 +v 0.119551 -0.037681 0.037530 +v 0.108659 -0.036643 0.039021 +v 0.103916 -0.038437 0.039208 +v 0.088770 -0.037332 0.038431 +v 0.018061 -0.038771 0.025024 +v 0.023771 -0.037259 0.026480 +v 0.006459 -0.037051 0.021079 +v -0.005880 -0.036971 0.015042 +v -0.008181 -0.038551 0.013605 +v -0.009566 -0.036960 0.012629 +v -0.010511 -0.036955 0.011805 +v -0.018784 -0.035978 0.002533 +v -0.018994 -0.037575 0.002432 +v -0.016494 -0.038220 0.004795 +v -0.016210 -0.038275 0.005156 +v -0.012664 -0.036945 0.009928 +v -0.018981 -0.035901 0.002417 +v -0.019412 -0.037403 0.002225 +v -0.021308 -0.036546 0.001487 +v -0.023660 -0.032662 0.000916 +v -0.024177 -0.034408 0.000790 +v -0.026910 -0.030640 0.000089 +v -0.026883 -0.030702 0.000096 +v -0.025511 -0.032789 0.000452 +v -0.025794 -0.029272 0.000382 +v 0.027483 0.019682 -0.013158 +v 0.030994 0.021543 -0.010090 +v 0.034808 0.022779 -0.007293 +v 0.036315 0.023073 -0.006321 +v 0.040203 0.023364 -0.004120 +v 0.043792 0.023045 -0.002442 +v 0.047638 0.022048 -0.000981 +v 0.051384 0.020331 0.000134 +v 0.054769 0.017968 0.000898 +v 0.055823 0.016941 0.001077 +v 0.057189 0.015609 0.001309 +v 0.062581 0.004560 0.001829 +v 0.062430 0.005303 0.001823 +v 0.061130 0.009372 0.001745 +v 0.059692 0.012193 0.001620 +v 0.063000 0.000096 0.001844 +v 0.062581 -0.004560 0.001829 +v 0.061413 -0.008674 0.001765 +v 0.059961 -0.011732 0.001646 +v 0.057550 -0.015192 0.001361 +v 0.055156 -0.017636 0.000971 +v 0.051818 -0.020076 0.000244 +v 0.048927 -0.021548 -0.000565 +v 0.045077 -0.022790 -0.001917 +v 0.044774 -0.022839 -0.002046 +v 0.042231 -0.023253 -0.003133 +v 0.038190 -0.023296 -0.005207 +v 0.035478 -0.022923 -0.006852 +v 0.031477 -0.021741 -0.009706 +v 0.023985 -0.017828 -0.016700 +v 0.015000 -0.016000 -0.025143 +v 0.015962 -0.016020 -0.024512 +v 0.019269 -0.016400 -0.021869 +v 0.015000 0.016000 -0.025143 +v 0.018634 0.016289 -0.022442 +v 0.023566 0.017655 -0.017159 +v 0.267514 0.016951 0.017281 +v 0.040825 0.037583 0.006232 +v 0.029084 0.036535 -0.001435 +v -0.006346 0.030850 -0.024358 +v -0.005407 0.032269 -0.022692 +v -0.002665 0.031582 -0.023613 +v -0.008118 0.027127 -0.026848 +v -0.007264 0.029112 -0.025766 +v -0.003889 0.028426 -0.026696 +v -0.014829 0.038015 -0.000497 +v -0.014895 0.038232 0.002280 +v -0.021788 0.036204 0.000122 +v -0.019531 0.037262 -0.000126 +v -0.023838 0.034709 0.000396 +v -0.023379 0.034064 -0.005931 +v -0.025168 0.032121 -0.005975 +v -0.026535 0.029920 -0.005918 +v -0.028169 0.025628 -0.003183 +v -0.027523 0.029196 -0.000075 +v 0.340993 0.001134 0.012941 +v 0.340991 0.000883 0.012925 +v 0.331223 0.003880 0.013166 +v 0.323918 0.004475 0.013299 +v 0.318584 0.007208 0.013784 +v 0.341000 0.001906 0.012990 +v 0.337824 0.003407 0.013162 +v 0.331425 0.005525 0.013529 +v 0.333259 0.005483 0.013686 +v 0.331513 0.006277 0.013887 +v 0.230181 0.025966 0.024424 +v 0.216668 0.028446 0.026785 +v 0.136482 0.036579 0.028581 +v 0.138374 0.035833 0.024730 +v 0.138408 0.036453 0.028709 +v 0.250094 0.024040 0.025170 +v 0.267879 0.019550 0.019789 +v 0.138521 0.031072 0.017866 +v 0.112789 0.031683 0.015456 +v 0.055111 0.027804 0.002892 +v 0.049624 0.031757 0.002610 +v 0.046705 0.027432 -0.000303 +v 0.077325 0.028216 0.008567 +v 0.074272 0.032088 0.009671 +v 0.065328 0.028076 0.005888 +v 0.111545 0.028065 0.013477 +v 0.038189 0.030963 -0.002938 +v 0.032974 0.030228 -0.006363 +v 0.029030 0.025057 -0.011070 +v 0.028203 0.029151 -0.010237 +v 0.023971 0.027670 -0.014493 +v 0.033889 0.026140 -0.007306 +v 0.020812 0.021718 -0.019824 +v 0.011804 0.023974 -0.025988 +v 0.013568 0.020349 -0.025792 +v 0.015398 0.024511 -0.023725 +v 0.017447 0.020967 -0.023086 +v -0.005036 0.024409 -0.028569 +v -0.000915 0.023946 -0.028988 +v -0.000257 0.019806 -0.029592 +v 0.003433 0.023680 -0.028721 +v 0.004512 0.019741 -0.029147 +v 0.009369 0.019936 -0.027794 +v 0.007762 0.023683 -0.027700 +v 0.004829 0.019754 -0.029058 +v 0.024462 0.023408 -0.015509 +v -0.013852 0.021165 -0.026127 +v -0.012604 0.025669 -0.025926 +v -0.008874 0.024984 -0.027564 +v -0.009309 0.020535 -0.028144 +v -0.017895 0.021896 -0.023375 +v -0.019252 0.027194 -0.020842 +v -0.021083 0.022586 -0.020309 +v -0.015139 0.026208 -0.024369 +v -0.027414 0.024886 -0.008044 +v -0.026000 0.024122 -0.012407 +v -0.024843 0.028981 -0.012040 +v -0.023857 0.023323 -0.016588 +v -0.022339 0.028061 -0.016912 +v -0.004794 0.020082 -0.029250 +v 0.039627 0.026899 -0.003756 +v 0.048536 0.035366 0.005399 +v 0.042501 0.035090 0.002664 +v 0.036718 0.034622 -0.000574 +v 0.007226 0.027338 -0.026056 +v 0.010718 0.027546 -0.024577 +v 0.009249 0.030485 -0.022310 +v 0.013831 0.028043 -0.022590 +v 0.015647 0.032365 -0.016356 +v 0.019177 0.034055 -0.011430 +v 0.026298 0.032797 -0.008640 +v -0.023482 0.031247 -0.011896 +v -0.021719 0.033259 -0.011552 +v -0.021259 0.035631 -0.005788 +v -0.019643 0.034896 -0.011021 +v -0.018931 0.036746 -0.005554 +v -0.017376 0.036080 -0.010337 +v -0.000282 0.027840 -0.027110 +v 0.003489 0.027447 -0.026916 +v 0.003357 0.030527 -0.024096 +v -0.007307 0.035159 -0.016296 +v -0.009954 0.033592 -0.020021 +v -0.011439 0.032229 -0.021559 +v -0.012844 0.030487 -0.022838 +v -0.014096 0.028445 -0.023788 +v -0.013008 0.034563 -0.017191 +v -0.014847 0.033258 -0.018516 +v -0.017441 0.034099 -0.015166 +v -0.016561 0.031534 -0.019604 +v -0.019376 0.032407 -0.016011 +v -0.018053 0.029474 -0.020390 +v -0.021036 0.030354 -0.016601 +v -0.014796 0.037909 -0.001852 +v -0.013921 0.037463 -0.005837 +v -0.012411 0.036894 -0.009487 +v -0.004382 0.034251 -0.018494 +v -0.000841 0.033305 -0.020098 +v 0.280665 0.017472 0.018604 +v 0.280951 0.019443 0.021311 +v 0.293425 0.015133 0.017269 +v 0.340996 0.001388 0.012957 +v 0.331324 0.004708 0.013322 +v 0.318942 0.010169 0.015062 +v 0.318766 0.008725 0.014337 +v 0.306364 0.014075 0.017191 +v 0.306135 0.012227 0.015747 +v 0.293687 0.017135 0.019444 +v 0.324583 0.009260 0.014929 +v 0.327074 0.008261 0.014448 +v 0.327734 0.007996 0.014321 +v 0.268957 0.022355 0.026167 +v 0.295953 0.018198 0.021462 +v 0.112609 0.034752 0.018401 +v 0.285993 0.011062 0.014732 +v 0.317707 0.005782 0.013435 +v 0.305892 0.010164 0.014634 +v 0.298558 0.009104 0.014194 +v 0.135151 -0.027662 0.015615 +v 0.118408 -0.024296 0.012985 +v 0.021433 -0.020539 -0.019258 +v 0.010602 -0.016000 -0.027416 +v 0.011010 -0.016000 -0.027205 +v 0.010940 -0.019426 -0.027166 +v 0.050736 -0.024908 0.000743 +v 0.069227 -0.008727 0.003597 +v 0.050736 0.024908 0.000743 +v -0.028091 0.016000 -0.007837 +v -0.028631 0.016000 -0.005366 +v -0.026470 0.016000 -0.012436 +v -0.023921 0.016000 -0.017007 +v -0.020882 0.016000 -0.020757 +v -0.016955 0.016000 -0.024173 +v -0.012889 0.016000 -0.026637 +v -0.008209 0.016000 -0.028465 +v -0.003516 0.016000 -0.029404 +v 0.001268 0.016000 -0.029548 +v 0.004886 0.016000 -0.029042 +v 0.005986 0.016000 -0.028888 +v 0.010602 0.016000 -0.027416 +v 0.025784 0.021344 -0.014488 +v 0.030802 0.022250 -0.010128 +v 0.036586 0.023190 -0.006141 +v 0.043208 0.024098 -0.002518 +v 0.059235 0.025554 0.003647 +v 0.069054 0.017402 0.004574 +v 0.059537 -0.017112 0.002188 +v 0.043208 -0.024098 -0.002518 +v 0.036586 -0.023190 -0.006141 +v 0.030802 -0.022250 -0.010128 +v 0.016541 -0.019896 -0.023869 +v 0.004848 -0.019119 -0.029091 +v 0.005986 -0.016000 -0.028888 +v 0.001268 -0.016000 -0.029548 +v 0.002134 -0.019744 -0.029474 +v -0.003516 -0.016000 -0.029404 +v -0.002530 -0.019922 -0.029513 +v -0.007929 -0.016000 -0.028521 +v -0.007368 -0.020320 -0.028719 +v -0.007892 -0.020383 -0.028539 +v -0.008209 -0.016000 -0.028465 +v -0.012889 -0.016000 -0.026637 +v -0.011504 -0.020814 -0.027295 +v -0.016955 -0.016000 -0.024173 +v -0.013842 -0.021181 -0.026035 +v -0.015381 -0.021423 -0.025207 +v -0.018903 -0.022102 -0.022508 +v -0.019054 -0.022137 -0.022347 +v -0.020882 -0.016000 -0.020757 +v -0.023536 -0.016000 -0.017482 +v -0.022079 -0.022827 -0.019118 +v -0.023921 -0.016000 -0.017007 +v -0.026470 -0.016000 -0.012436 +v -0.024551 -0.023553 -0.015409 +v -0.028091 -0.016000 -0.007837 +v -0.026571 -0.024391 -0.010909 +v -0.027790 -0.025174 -0.006235 +v -0.028567 -0.016000 -0.005658 +v -0.027842 -0.025257 -0.005658 +v -0.028631 -0.016000 -0.005366 +v -0.028249 -0.025918 -0.001104 +v 0.011165 -0.020082 -0.027041 +v 0.007935 -0.019871 -0.028217 +v 0.006825 -0.019799 -0.028622 +v 0.015410 -0.020613 -0.024625 +v 0.018906 -0.021262 -0.021797 +v 0.025665 -0.023899 -0.014263 +v 0.029645 -0.025218 -0.010548 +v 0.034684 -0.026272 -0.006763 +v 0.040539 -0.026986 -0.003260 +v 0.047543 -0.027478 0.000053 +v 0.055316 -0.027815 0.002961 +v 0.065320 -0.028076 0.005886 +v 0.068766 -0.025971 0.006196 +v 0.074563 -0.028183 0.007946 +v 0.079389 -0.026096 0.008395 +v 0.077469 -0.028216 0.008594 +v 0.091977 -0.028198 0.011028 +v 0.189437 -0.018698 0.015469 +v 0.340991 -0.000884 0.012925 +v 0.118408 0.024296 0.012985 +v 0.068766 0.025971 0.006196 +v 0.091622 0.000000 0.006896 +v 0.091571 0.008708 0.007270 +v 0.104386 0.016946 0.009851 +v 0.118628 0.016320 0.011043 +v 0.151182 -0.014607 0.012731 +v 0.091571 -0.008708 0.007270 +v 0.079824 -0.008778 0.005578 +v 0.091430 -0.038253 0.023624 +v 0.134958 -0.036668 0.028842 +v 0.005535 -0.038627 0.017852 +v 0.139061 -0.036366 0.028686 +v 0.127254 -0.037039 0.027765 +v 0.039603 -0.038650 0.010433 +v 0.037249 -0.038559 0.009058 +v 0.021571 -0.037071 -0.002872 +v 0.010504 -0.033122 -0.017206 +v -0.003807 -0.034084 -0.018829 +v 0.005618 -0.032404 -0.020293 +v -0.012086 -0.036780 -0.010095 +v -0.009478 -0.035876 -0.014011 +v -0.014905 -0.038223 0.002142 +v 0.008469 -0.038641 0.012557 +v 0.342000 -0.009191 0.017097 +v 0.342000 -0.004980 0.015213 +v 0.342000 -0.001308 0.014539 +v 0.342000 -0.005812 0.015483 +v 0.342000 -0.010947 0.018335 +v 0.342000 -0.016484 0.026102 +v 0.342000 -0.014853 0.022731 +v 0.342000 -0.013601 0.020975 +v 0.342000 -0.017082 0.028167 +v 0.342000 0.016556 0.026310 +v 0.342000 0.017387 0.029962 +v 0.342000 0.013739 0.021147 +v 0.342000 0.015732 0.024317 +v 0.342000 0.012301 0.019540 +v 0.342000 0.009372 0.017210 +v 0.342000 0.007482 0.016169 +v 0.342000 0.003945 0.014940 +v 0.342000 0.001827 0.014586 +v 0.342000 0.001806 0.013990 +v 0.342000 -0.001806 0.013990 +v 0.341000 -0.001906 0.012990 +v 0.340998 -0.001646 0.012974 +v 0.340996 -0.001388 0.012957 +v 0.341000 -0.004962 0.013607 +v 0.337535 -0.003544 0.013182 +v 0.341000 -0.005612 0.013737 +v 0.331513 -0.006279 0.013882 +v 0.327074 -0.008261 0.014448 +v 0.319098 -0.011461 0.015988 +v 0.286131 -0.019918 0.023430 +v 0.312573 -0.018825 0.025679 +v 0.268995 -0.022350 0.026161 +v 0.242681 -0.025622 0.028953 +v 0.283501 -0.021563 0.030687 +v 0.340997 -0.017995 0.025915 +v 0.340997 -0.018764 0.028436 +v 0.340998 -0.015458 0.020778 +v 0.327133 -0.016628 0.022100 +v 0.327138 -0.018127 0.025290 +v 0.340998 -0.017554 0.024472 +v 0.340999 -0.015134 0.020419 +v 0.340999 -0.012726 0.017753 +v 0.341000 -0.009403 0.015369 +v 0.342000 -0.017657 0.028041 +v 0.342000 -0.016356 0.024258 +v 0.342000 0.017882 0.029233 +v 0.342000 0.009360 0.016508 +v 0.342000 0.012535 0.018945 +v 0.342000 0.015098 0.022022 +v 0.342000 0.016928 0.025605 +v 0.342000 0.017881 0.029229 +v 0.342000 -0.014352 0.021010 +v 0.342000 -0.014246 0.020838 +v 0.342000 -0.011434 0.017969 +v 0.342000 0.005717 0.014826 +v 0.342000 0.005538 0.014788 +v 0.342000 -0.008301 0.015915 +v 0.342000 -0.004705 0.014540 +v 0.342000 -0.004543 0.014479 +v 0.341000 0.009090 0.015197 +v 0.340999 0.012483 0.017539 +v 0.341000 0.005835 0.013850 +v 0.341000 0.005430 0.013683 +v 0.327138 0.018127 0.025290 +v 0.340998 0.016859 0.023179 +v 0.340998 0.015265 0.020516 +v 0.340997 0.018785 0.029085 +v 0.312575 0.019620 0.029195 +v 0.340997 0.018662 0.027936 +v 0.340997 0.018036 0.026073 +v 0.340998 0.017325 0.023958 +v 0.283502 0.021129 0.027020 +v 0.312568 0.017474 0.022419 +v -0.018931 -0.036746 -0.005554 +v -0.006346 -0.030850 -0.024358 +v -0.007264 -0.029112 -0.025766 +v -0.003889 -0.028426 -0.026696 +v -0.023379 -0.034064 -0.005931 +v -0.021719 -0.033259 -0.011552 +v -0.019643 -0.034896 -0.011021 +v -0.012844 -0.030487 -0.022838 +v 0.230172 -0.025887 0.024236 +v 0.216668 -0.028446 0.026785 +v 0.138373 -0.035833 0.024730 +v -0.025168 -0.032121 -0.005975 +v 0.331324 -0.004708 0.013322 +v -0.026883 -0.030702 0.000096 +v -0.026535 -0.029920 -0.005918 +v -0.023838 -0.034709 0.000396 +v -0.021788 -0.036204 0.000122 +v -0.021308 -0.036546 0.001487 +v 0.241787 -0.020779 0.018747 +v 0.250395 -0.024025 0.025214 +v 0.267879 -0.019550 0.019789 +v 0.138520 -0.031072 0.017866 +v 0.112789 -0.031683 0.015456 +v 0.074272 -0.032088 0.009671 +v 0.049624 -0.031757 0.002610 +v 0.061734 -0.032056 0.006655 +v 0.038189 -0.030963 -0.002938 +v 0.032974 -0.030228 -0.006363 +v 0.028203 -0.029151 -0.010237 +v 0.015398 -0.024511 -0.023725 +v 0.011804 -0.023974 -0.025988 +v 0.018496 -0.025225 -0.021039 +v -0.000915 -0.023946 -0.028988 +v -0.005037 -0.024409 -0.028568 +v 0.003433 -0.023680 -0.028721 +v 0.007762 -0.023683 -0.027700 +v -0.012604 -0.025669 -0.025926 +v -0.008874 -0.024984 -0.027564 +v -0.019252 -0.027194 -0.020842 +v -0.022339 -0.028061 -0.016912 +v -0.015139 -0.026208 -0.024369 +v -0.024843 -0.028981 -0.012040 +v -0.014096 -0.028445 -0.023787 +v -0.008118 -0.027127 -0.026848 +v -0.023482 -0.031247 -0.011896 +v -0.021036 -0.030354 -0.016601 +v -0.018053 -0.029474 -0.020390 +v 0.047097 -0.037793 0.009144 +v -0.017441 -0.034099 -0.015166 +v -0.019376 -0.032407 -0.016011 +v -0.014847 -0.033258 -0.018516 +v -0.017376 -0.036080 -0.010337 +v -0.013008 -0.034563 -0.017191 +v -0.009954 -0.033592 -0.020021 +v -0.016561 -0.031534 -0.019604 +v -0.011439 -0.032229 -0.021559 +v -0.005407 -0.032269 -0.022692 +v 0.029084 -0.036535 -0.001435 +v 0.023829 -0.035513 -0.006190 +v 0.009249 -0.030485 -0.022310 +v 0.013969 -0.031581 -0.018574 +v 0.003357 -0.030527 -0.024096 +v -0.021259 -0.035631 -0.005788 +v -0.002665 -0.031582 -0.023613 +v 0.042501 -0.035090 0.002664 +v 0.031286 -0.033887 -0.004344 +v 0.021881 -0.031288 -0.013369 +v 0.016523 -0.028763 -0.020200 +v 0.013831 -0.028043 -0.022590 +v 0.010718 -0.027546 -0.024577 +v 0.007226 -0.027338 -0.026056 +v 0.003489 -0.027447 -0.026916 +v -0.000282 -0.027840 -0.027110 +v 0.331425 -0.005526 0.013529 +v 0.280951 -0.019443 0.021311 +v 0.280665 -0.017472 0.018605 +v 0.318942 -0.010169 0.015062 +v 0.164476 -0.032419 0.022540 +v 0.060955 -0.035550 0.009564 +v 0.267514 -0.016951 0.017281 +v 0.113573 0.037799 0.034445 +v 0.008469 0.038640 0.012548 +v 0.009731 0.040315 0.033342 +v 0.010073 0.040320 0.033196 +v 0.011202 0.040339 0.033435 +v 0.010236 0.040323 0.033708 +v 0.011339 0.040341 0.033753 +v 0.010486 0.040328 0.031239 +v 0.010290 0.040325 0.030943 +v 0.009715 0.040315 0.032098 +v 0.012111 0.040353 0.033139 +v 0.011974 0.040351 0.032576 +v 0.009347 0.040309 0.032433 +v 0.009544 0.040312 0.031589 +v 0.012271 0.040356 0.032799 +v 0.012336 0.040357 0.032178 +v 0.011724 0.040348 0.031122 +v 0.011616 0.040346 0.031478 +v 0.010905 0.040334 0.030838 +v 0.010906 0.032683 0.033634 +v 0.011861 0.032698 0.033279 +v 0.012267 0.032705 0.032344 +v 0.012012 0.032701 0.031561 +v 0.011133 0.032687 0.031046 +v 0.010152 0.032671 0.031323 +v 0.009671 0.032663 0.032431 +v 0.010138 0.032671 0.033336 +v 0.010893 0.032883 0.033833 +v 0.011134 0.032886 0.033825 +v 0.011041 0.038686 0.033827 +v 0.011995 0.032900 0.033424 +v 0.011902 0.038700 0.033425 +v 0.012383 0.032907 0.032820 +v 0.012290 0.038706 0.032821 +v 0.012464 0.032908 0.032345 +v 0.012370 0.038707 0.032347 +v 0.012297 0.038706 0.031871 +v 0.012169 0.032904 0.031442 +v 0.012076 0.038703 0.031444 +v 0.011824 0.032898 0.031107 +v 0.011731 0.038697 0.031108 +v 0.011523 0.038694 0.030986 +v 0.011155 0.032887 0.030847 +v 0.011062 0.038687 0.030849 +v 0.010674 0.032880 0.030863 +v 0.010581 0.038679 0.030865 +v 0.010023 0.032869 0.031167 +v 0.009848 0.032866 0.031333 +v 0.009755 0.038666 0.031334 +v 0.009588 0.032862 0.031738 +v 0.009495 0.038661 0.031739 +v 0.009468 0.032860 0.032446 +v 0.009375 0.038659 0.032447 +v 0.009580 0.032862 0.032914 +v 0.009487 0.038661 0.032915 +v 0.010007 0.032868 0.033491 +v 0.009914 0.038668 0.033492 +v 0.010422 0.032875 0.033734 +v 0.010329 0.038674 0.033735 +v 0.009956 0.038668 0.035036 +v 0.008066 0.038638 0.031830 +v 0.008825 0.038650 0.034320 +v 0.008262 0.038641 0.033483 +v 0.011620 0.038695 0.035086 +v 0.009647 0.038664 0.029763 +v 0.010620 0.038680 0.029498 +v 0.008828 0.038651 0.030350 +v 0.013640 0.038728 0.033008 +v 0.013233 0.038721 0.033930 +v 0.013543 0.038726 0.031346 +v 0.011944 0.038701 0.029696 +v 0.012248 0.038706 0.029842 +v 0.012796 0.038715 0.030235 +v 0.009931 0.038998 0.035029 +v 0.009291 0.038987 0.034712 +v 0.008750 0.038979 0.034246 +v 0.008342 0.038972 0.033660 +v 0.008240 0.038971 0.033444 +v 0.008066 0.038968 0.031806 +v 0.008120 0.038969 0.031574 +v 0.008667 0.038978 0.030523 +v 0.009001 0.038984 0.030181 +v 0.009595 0.038993 0.029785 +v 0.010743 0.039012 0.029489 +v 0.010981 0.039016 0.029489 +v 0.011911 0.039031 0.029685 +v 0.012725 0.039044 0.030177 +v 0.013059 0.039049 0.030517 +v 0.013609 0.039058 0.031567 +v 0.013640 0.039058 0.032984 +v 0.013494 0.039055 0.033438 +v 0.013273 0.039052 0.033861 +v 0.012241 0.039035 0.034832 +v 0.011577 0.039024 0.035096 +v 0.010745 0.039217 0.029612 +v 0.009257 0.039193 0.030132 +v 0.009078 0.039191 0.030274 +v 0.008305 0.039178 0.031389 +v 0.008235 0.039177 0.031606 +v 0.013540 0.039262 0.031822 +v 0.013488 0.039261 0.031600 +v 0.012446 0.039626 0.030489 +v 0.012595 0.039628 0.030629 +v 0.013085 0.039809 0.031908 +v 0.013121 0.039810 0.032477 +v 0.012607 0.040110 0.033074 +v 0.012539 0.040109 0.033218 +v 0.012109 0.039434 0.034604 +v 0.011915 0.039431 0.034701 +v 0.010010 0.039400 0.034783 +v 0.010075 0.040069 0.034080 +v 0.009932 0.040067 0.034009 +v 0.009429 0.039391 0.034495 +v 0.008945 0.040051 0.032459 +v 0.009011 0.040052 0.031826 +v 0.008507 0.039562 0.031684 +v 0.008364 0.039375 0.031643 +v 0.008570 0.039563 0.031490 +v 0.010973 0.039221 0.029612 +v 0.010083 0.039671 0.033196 +v 0.011213 0.039689 0.033435 +v 0.009725 0.039665 0.032098 +v 0.010496 0.039678 0.031239 +v 0.011626 0.039696 0.031478 +v 0.011984 0.039701 0.032575 +v -0.008324 0.040203 0.025516 +v -0.007194 0.040214 0.025755 +v -0.008381 0.040202 0.025907 +v -0.007550 0.040209 0.026157 +v -0.007057 0.040214 0.026073 +v -0.007909 0.040210 0.023559 +v -0.008105 0.040209 0.023263 +v -0.008681 0.040201 0.024418 +v -0.006285 0.040223 0.025459 +v -0.006422 0.040223 0.024896 +v -0.009049 0.040197 0.024752 +v -0.008784 0.040201 0.023802 +v -0.006436 0.040221 0.025660 +v -0.006671 0.040223 0.023443 +v -0.006780 0.040221 0.023798 +v -0.006146 0.040227 0.024133 +v -0.007539 0.032560 0.025942 +v -0.006583 0.032569 0.025588 +v -0.006177 0.032575 0.024653 +v -0.006432 0.032574 0.023870 +v -0.007311 0.032566 0.023354 +v -0.008292 0.032556 0.023631 +v -0.008774 0.032550 0.024739 +v -0.008307 0.032553 0.025645 +v -0.007550 0.032759 0.026142 +v -0.007309 0.032761 0.026134 +v -0.007366 0.038561 0.026144 +v -0.006448 0.032771 0.025733 +v -0.006504 0.038570 0.025743 +v -0.006060 0.032775 0.025129 +v -0.006116 0.038575 0.025139 +v -0.005979 0.032777 0.024655 +v -0.006036 0.038577 0.024665 +v -0.006274 0.032776 0.023752 +v -0.006330 0.038575 0.023762 +v -0.006618 0.032773 0.023416 +v -0.006675 0.038573 0.023426 +v -0.007288 0.032767 0.023156 +v -0.007344 0.038566 0.023166 +v -0.007769 0.032762 0.023172 +v -0.007825 0.038562 0.023182 +v -0.008419 0.032755 0.023475 +v -0.008595 0.032753 0.023641 +v -0.008651 0.038553 0.023651 +v -0.008855 0.032750 0.024046 +v -0.008911 0.038550 0.024056 +v -0.008975 0.032748 0.024754 +v -0.009032 0.038547 0.024764 +v -0.008863 0.032748 0.025222 +v -0.008920 0.038548 0.025232 +v -0.008666 0.038549 0.025641 +v -0.008436 0.032751 0.025799 +v -0.008493 0.038551 0.025809 +v -0.008021 0.032755 0.026043 +v -0.008078 0.038554 0.026053 +v -0.008764 0.038546 0.027226 +v -0.009060 0.038543 0.027062 +v -0.010340 0.038536 0.024147 +v -0.009803 0.038537 0.026381 +v -0.010145 0.038535 0.025800 +v -0.007118 0.038561 0.027473 +v -0.005614 0.038577 0.026759 +v -0.007785 0.038564 0.021815 +v -0.009329 0.038548 0.022439 +v -0.004766 0.038588 0.025327 +v -0.004863 0.038590 0.023665 +v -0.006462 0.038577 0.022014 +v -0.005610 0.038584 0.022553 +v -0.009114 0.038873 0.027030 +v -0.010165 0.038865 0.025761 +v -0.010383 0.038864 0.024836 +v -0.010339 0.038866 0.024123 +v -0.010119 0.038869 0.023443 +v -0.009403 0.038878 0.022499 +v -0.007661 0.038896 0.021807 +v -0.007422 0.038898 0.021807 +v -0.006492 0.038907 0.022004 +v -0.006274 0.038909 0.022101 +v -0.005679 0.038914 0.022496 +v -0.004795 0.038920 0.023886 +v -0.004764 0.038918 0.025303 +v -0.004911 0.038916 0.025757 +v -0.005586 0.038908 0.026730 +v -0.006164 0.038901 0.027151 +v -0.007061 0.038892 0.027464 +v -0.008012 0.038883 0.027465 +v -0.007657 0.039101 0.021930 +v -0.008217 0.039086 0.027297 +v -0.007993 0.039089 0.027344 +v -0.004863 0.039125 0.024142 +v -0.004915 0.039124 0.023919 +v -0.006330 0.039113 0.022211 +v -0.006539 0.039112 0.022118 +v -0.006711 0.039664 0.022542 +v -0.006371 0.039667 0.022711 +v -0.006006 0.040110 0.023928 +v -0.005653 0.039979 0.024455 +v -0.006243 0.039971 0.026046 +v -0.006287 0.039661 0.026548 +v -0.006493 0.039968 0.026244 +v -0.006293 0.039302 0.026923 +v -0.006488 0.039300 0.027020 +v -0.006620 0.039658 0.026731 +v -0.007543 0.039475 0.027093 +v -0.008149 0.039469 0.027017 +v -0.008556 0.039800 0.026493 +v -0.008974 0.039276 0.026813 +v -0.009150 0.039274 0.026686 +v -0.008981 0.039797 0.026185 +v -0.009362 0.039942 0.025247 +v -0.009707 0.039630 0.025360 +v -0.009917 0.039455 0.025214 +v -0.009759 0.039630 0.025177 +v -0.009452 0.039942 0.024778 +v -0.009977 0.039455 0.024811 +v -0.008253 0.039957 0.022884 +v -0.008205 0.039649 0.022480 +v -0.008102 0.039958 0.022831 +v -0.007833 0.039653 0.022401 +v -0.007429 0.039103 0.021930 +v -0.008317 0.039553 0.025514 +v -0.007188 0.039564 0.025754 +v -0.008675 0.039551 0.024417 +v -0.007903 0.039560 0.023558 +v -0.006774 0.039571 0.023797 +v -0.006416 0.039573 0.024895 +v 0.007574 -0.040268 0.013190 +v 0.008704 -0.040280 0.013429 +v 0.007737 -0.040275 0.013702 +v 0.008841 -0.040284 0.013747 +v 0.006964 -0.040260 0.012914 +v 0.007987 -0.040253 0.011234 +v 0.007792 -0.040248 0.010938 +v 0.007216 -0.040255 0.012093 +v 0.009475 -0.040278 0.012570 +v 0.007113 -0.040248 0.011477 +v 0.009837 -0.040277 0.012173 +v 0.009461 -0.040285 0.013334 +v 0.009226 -0.040262 0.011117 +v 0.009117 -0.040264 0.011472 +v 0.008407 -0.040252 0.010833 +v 0.008347 -0.032629 0.013704 +v 0.008958 -0.032633 0.013584 +v 0.009556 -0.032632 0.013018 +v 0.009709 -0.032628 0.012415 +v 0.009453 -0.032618 0.011632 +v 0.008574 -0.032606 0.011117 +v 0.007593 -0.032600 0.011393 +v 0.007112 -0.032607 0.012502 +v 0.007580 -0.032620 0.013407 +v 0.008336 -0.032831 0.013902 +v 0.008578 -0.032833 0.013894 +v 0.008530 -0.038632 0.013838 +v 0.009041 -0.032835 0.013763 +v 0.009203 -0.038635 0.013588 +v 0.009439 -0.032836 0.013493 +v 0.009391 -0.038635 0.013436 +v 0.009730 -0.032835 0.013110 +v 0.009682 -0.038634 0.013054 +v 0.009907 -0.032829 0.012414 +v 0.009859 -0.038629 0.012358 +v 0.009612 -0.032818 0.011511 +v 0.009564 -0.038618 0.011455 +v 0.009268 -0.032812 0.011175 +v 0.009220 -0.038611 0.011119 +v 0.008598 -0.032804 0.010916 +v 0.008550 -0.038603 0.010860 +v 0.007885 -0.032799 0.010998 +v 0.007837 -0.038598 0.010941 +v 0.007466 -0.032798 0.011236 +v 0.007291 -0.032798 0.011402 +v 0.007243 -0.038597 0.011345 +v 0.007031 -0.032800 0.011807 +v 0.006983 -0.038599 0.011750 +v 0.006911 -0.032806 0.012515 +v 0.006863 -0.038605 0.012458 +v 0.007023 -0.032811 0.012983 +v 0.006975 -0.038611 0.012926 +v 0.007450 -0.032820 0.013559 +v 0.007403 -0.038620 0.013503 +v 0.007865 -0.032826 0.013803 +v 0.007818 -0.038625 0.013746 +v 0.007444 -0.038635 0.015047 +v 0.005555 -0.038588 0.011841 +v 0.006313 -0.038619 0.014331 +v 0.005750 -0.038606 0.013494 +v 0.009108 -0.038649 0.015097 +v 0.010281 -0.038653 0.014452 +v 0.010019 -0.038653 0.014664 +v 0.007136 -0.038581 0.009774 +v 0.008108 -0.038587 0.009509 +v 0.006316 -0.038580 0.010361 +v 0.011129 -0.038646 0.013019 +v 0.010722 -0.038651 0.013941 +v 0.011032 -0.038629 0.011357 +v 0.009432 -0.038599 0.009707 +v 0.010284 -0.038612 0.010246 +v 0.007422 -0.038965 0.015037 +v 0.007200 -0.038962 0.014949 +v 0.006241 -0.038947 0.014254 +v 0.006088 -0.038944 0.014070 +v 0.005731 -0.038935 0.013452 +v 0.005507 -0.038922 0.012288 +v 0.005556 -0.038918 0.011814 +v 0.005776 -0.038913 0.011134 +v 0.006158 -0.038910 0.010530 +v 0.006492 -0.038910 0.010189 +v 0.007086 -0.038911 0.009793 +v 0.008234 -0.038918 0.009497 +v 0.009402 -0.038929 0.009693 +v 0.010216 -0.038941 0.010185 +v 0.010550 -0.038947 0.010525 +v 0.011100 -0.038961 0.011574 +v 0.011132 -0.038975 0.012992 +v 0.010765 -0.038981 0.013868 +v 0.010310 -0.038983 0.014419 +v 0.009068 -0.038979 0.015104 +v 0.006054 -0.039147 0.013806 +v 0.011033 -0.039169 0.011828 +v 0.010981 -0.039166 0.011606 +v 0.009432 -0.039859 0.010541 +v 0.009716 -0.039863 0.010747 +v 0.009942 -0.039528 0.010491 +v 0.010091 -0.039531 0.010631 +v 0.010024 -0.040159 0.012010 +v 0.010045 -0.040160 0.012152 +v 0.007504 -0.039364 0.014787 +v 0.007574 -0.040025 0.014077 +v 0.007303 -0.039362 0.014707 +v 0.007431 -0.040024 0.014006 +v 0.006185 -0.039150 0.013994 +v 0.006433 -0.039702 0.013557 +v 0.006590 -0.040008 0.013075 +v 0.006535 -0.040006 0.012925 +v 0.006189 -0.039695 0.013042 +v 0.006138 -0.039693 0.012859 +v 0.005792 -0.039330 0.012722 +v 0.005764 -0.039326 0.012289 +v 0.008247 -0.039508 0.009903 +v 0.008654 -0.039512 0.009920 +v 0.007579 -0.039618 0.013197 +v 0.008709 -0.039630 0.013435 +v 0.007221 -0.039605 0.012099 +v 0.007993 -0.039603 0.011240 +v 0.009123 -0.039614 0.011479 +v 0.009481 -0.039628 0.012576 +v 0.009731 -0.040286 0.033342 +v 0.010073 -0.040292 0.033196 +v 0.011202 -0.040310 0.033435 +v 0.010236 -0.040294 0.033708 +v 0.011339 -0.040312 0.033753 +v 0.010486 -0.040299 0.031239 +v 0.009715 -0.040286 0.032098 +v 0.012111 -0.040324 0.033139 +v 0.011974 -0.040322 0.032576 +v 0.009347 -0.040280 0.032433 +v 0.009544 -0.040284 0.031589 +v 0.009399 -0.040281 0.031935 +v 0.012336 -0.040328 0.032178 +v 0.011724 -0.040319 0.031122 +v 0.011616 -0.040317 0.031478 +v 0.011276 -0.040312 0.030900 +v 0.010905 -0.040306 0.030838 +v 0.010906 -0.032654 0.033634 +v 0.011861 -0.032669 0.033279 +v 0.012267 -0.032676 0.032344 +v 0.011713 -0.032668 0.031270 +v 0.010716 -0.032652 0.031060 +v 0.010152 -0.032642 0.031323 +v 0.009707 -0.032635 0.032015 +v 0.009864 -0.032637 0.033022 +v 0.010893 -0.032854 0.033833 +v 0.010800 -0.038653 0.033835 +v 0.011598 -0.032865 0.033695 +v 0.011504 -0.038664 0.033696 +v 0.011995 -0.032872 0.033424 +v 0.011902 -0.038671 0.033425 +v 0.012383 -0.032878 0.032820 +v 0.012290 -0.038677 0.032821 +v 0.012464 -0.032879 0.032345 +v 0.012370 -0.038679 0.032347 +v 0.012169 -0.032875 0.031442 +v 0.012076 -0.038674 0.031444 +v 0.011824 -0.032869 0.031107 +v 0.011731 -0.038669 0.031108 +v 0.011155 -0.032859 0.030847 +v 0.011062 -0.038658 0.030849 +v 0.010674 -0.032851 0.030863 +v 0.010581 -0.038650 0.030865 +v 0.010130 -0.038643 0.031032 +v 0.010023 -0.032840 0.031167 +v 0.009848 -0.032838 0.031333 +v 0.009755 -0.038637 0.031334 +v 0.009588 -0.032833 0.031738 +v 0.009495 -0.038633 0.031739 +v 0.009510 -0.032832 0.031966 +v 0.009468 -0.032831 0.032446 +v 0.009375 -0.038630 0.032447 +v 0.009580 -0.032833 0.032914 +v 0.009487 -0.038632 0.032915 +v 0.009691 -0.032835 0.033128 +v 0.010007 -0.032840 0.033491 +v 0.009914 -0.038639 0.033492 +v 0.009956 -0.038639 0.035036 +v 0.008066 -0.038610 0.031830 +v 0.008264 -0.038613 0.031186 +v 0.008825 -0.038621 0.034320 +v 0.008262 -0.038612 0.033483 +v 0.011620 -0.038666 0.035086 +v 0.009647 -0.038635 0.029763 +v 0.010620 -0.038651 0.029498 +v 0.008828 -0.038622 0.030350 +v 0.009351 -0.038631 0.029925 +v 0.013640 -0.038699 0.033008 +v 0.013233 -0.038692 0.033931 +v 0.013543 -0.038698 0.031346 +v 0.011944 -0.038672 0.029696 +v 0.012796 -0.038686 0.030235 +v 0.009931 -0.038969 0.035029 +v 0.009291 -0.038959 0.034712 +v 0.008750 -0.038950 0.034246 +v 0.008342 -0.038944 0.033660 +v 0.008240 -0.038942 0.033444 +v 0.008066 -0.038940 0.031806 +v 0.008120 -0.038941 0.031574 +v 0.008667 -0.038950 0.030523 +v 0.009001 -0.038955 0.030181 +v 0.009595 -0.038965 0.029785 +v 0.010743 -0.038983 0.029489 +v 0.010981 -0.038987 0.029489 +v 0.011911 -0.039002 0.029685 +v 0.012725 -0.039015 0.030177 +v 0.013059 -0.039020 0.030517 +v 0.013609 -0.039029 0.031567 +v 0.013640 -0.039029 0.032984 +v 0.013494 -0.039026 0.033438 +v 0.013273 -0.039023 0.033861 +v 0.012241 -0.039006 0.034832 +v 0.011577 -0.038995 0.035096 +v 0.010745 -0.039189 0.029612 +v 0.009257 -0.039165 0.030132 +v 0.009078 -0.039162 0.030274 +v 0.008305 -0.039149 0.031389 +v 0.008235 -0.039148 0.031606 +v 0.013540 -0.039233 0.031822 +v 0.013488 -0.039232 0.031600 +v 0.011934 -0.039923 0.030543 +v 0.012218 -0.039928 0.030749 +v 0.012446 -0.039597 0.030489 +v 0.012595 -0.039599 0.030629 +v 0.012523 -0.040213 0.032015 +v 0.012544 -0.040213 0.032156 +v 0.012361 -0.040210 0.033126 +v 0.012289 -0.040209 0.033250 +v 0.012109 -0.039405 0.034604 +v 0.011915 -0.039402 0.034701 +v 0.010010 -0.039372 0.034783 +v 0.009429 -0.039362 0.034495 +v 0.009331 -0.040028 0.033492 +v 0.009239 -0.040027 0.033361 +v 0.008766 -0.039872 0.032120 +v 0.008832 -0.039873 0.031776 +v 0.008507 -0.039533 0.031684 +v 0.008364 -0.039346 0.031643 +v 0.008570 -0.039534 0.031490 +v 0.010973 -0.039192 0.029612 +v 0.010083 -0.039642 0.033196 +v 0.011213 -0.039660 0.033435 +v 0.009725 -0.039636 0.032098 +v 0.010496 -0.039649 0.031239 +v 0.011626 -0.039667 0.031478 +v 0.011984 -0.039673 0.032575 +v -0.008666 -0.040171 0.025661 +v -0.008324 -0.040174 0.025516 +v -0.007194 -0.040185 0.025755 +v -0.008381 -0.040173 0.025907 +v -0.007550 -0.040181 0.026157 +v -0.007909 -0.040182 0.023559 +v -0.008105 -0.040180 0.023263 +v -0.008681 -0.040173 0.024418 +v -0.006285 -0.040194 0.025459 +v -0.006422 -0.040194 0.024896 +v -0.009049 -0.040169 0.024752 +v -0.008784 -0.040173 0.023802 +v -0.006436 -0.040192 0.025660 +v -0.006671 -0.040194 0.023443 +v -0.006780 -0.040192 0.023798 +v -0.007119 -0.040190 0.023220 +v -0.006146 -0.040198 0.024133 +v -0.007539 -0.032531 0.025942 +v -0.006583 -0.032541 0.025588 +v -0.006177 -0.032546 0.024653 +v -0.006432 -0.032545 0.023870 +v -0.007311 -0.032537 0.023354 +v -0.008292 -0.032527 0.023631 +v -0.008774 -0.032521 0.024739 +v -0.008307 -0.032524 0.025645 +v -0.007550 -0.032730 0.026142 +v -0.007607 -0.038530 0.026152 +v -0.006846 -0.032737 0.026004 +v -0.006902 -0.038537 0.026014 +v -0.006448 -0.032742 0.025733 +v -0.006504 -0.038542 0.025743 +v -0.006060 -0.032747 0.025129 +v -0.006116 -0.038546 0.025139 +v -0.005979 -0.032748 0.024655 +v -0.006036 -0.038548 0.024665 +v -0.006274 -0.032747 0.023752 +v -0.006330 -0.038547 0.023762 +v -0.006618 -0.032744 0.023416 +v -0.006675 -0.038544 0.023426 +v -0.006883 -0.038542 0.023304 +v -0.007288 -0.032738 0.023156 +v -0.007344 -0.038538 0.023166 +v -0.007769 -0.032733 0.023172 +v -0.007825 -0.038533 0.023182 +v -0.008419 -0.032726 0.023475 +v -0.008595 -0.032724 0.023641 +v -0.008651 -0.038524 0.023651 +v -0.008855 -0.032721 0.024046 +v -0.008911 -0.038521 0.024056 +v -0.008975 -0.032719 0.024754 +v -0.009032 -0.038519 0.024764 +v -0.008863 -0.032719 0.025222 +v -0.008920 -0.038519 0.025232 +v -0.008436 -0.032722 0.025799 +v -0.008493 -0.038522 0.025809 +v -0.008451 -0.038520 0.027353 +v -0.010340 -0.038507 0.024147 +v -0.009583 -0.038510 0.026637 +v -0.010145 -0.038506 0.025800 +v -0.006788 -0.038536 0.027404 +v -0.005877 -0.038546 0.026972 +v -0.007785 -0.038536 0.021815 +v -0.009329 -0.038520 0.022439 +v -0.004766 -0.038559 0.025327 +v -0.005174 -0.038554 0.026249 +v -0.004863 -0.038561 0.023665 +v -0.006462 -0.038548 0.022014 +v -0.006157 -0.038551 0.022160 +v -0.005610 -0.038556 0.022553 +v -0.008474 -0.038850 0.027347 +v -0.009114 -0.038844 0.027030 +v -0.009655 -0.038839 0.026563 +v -0.010165 -0.038836 0.025761 +v -0.010383 -0.038835 0.024836 +v -0.010339 -0.038837 0.024123 +v -0.010119 -0.038840 0.023443 +v -0.009403 -0.038849 0.022499 +v -0.007661 -0.038867 0.021807 +v -0.007422 -0.038869 0.021807 +v -0.006492 -0.038878 0.022004 +v -0.005679 -0.038885 0.022496 +v -0.005345 -0.038888 0.022836 +v -0.004795 -0.038891 0.023886 +v -0.004764 -0.038889 0.025303 +v -0.004911 -0.038887 0.025757 +v -0.005131 -0.038884 0.026180 +v -0.006164 -0.038872 0.027151 +v -0.006828 -0.038866 0.027414 +v -0.007298 -0.038861 0.027494 +v -0.007657 -0.039072 0.021930 +v -0.004863 -0.039096 0.024142 +v -0.004915 -0.039096 0.023919 +v -0.006464 -0.039798 0.022863 +v -0.006667 -0.040076 0.023195 +v -0.006548 -0.040077 0.023274 +v -0.006180 -0.039800 0.023069 +v -0.005953 -0.039469 0.022809 +v -0.005804 -0.039470 0.022948 +v -0.006006 -0.040081 0.023928 +v -0.005653 -0.039951 0.024455 +v -0.006287 -0.039632 0.026548 +v -0.006293 -0.039273 0.026923 +v -0.006488 -0.039271 0.027020 +v -0.006620 -0.039629 0.026732 +v -0.008974 -0.039247 0.026813 +v -0.009150 -0.039246 0.026686 +v -0.009362 -0.039913 0.025247 +v -0.009707 -0.039601 0.025360 +v -0.009917 -0.039426 0.025214 +v -0.009759 -0.039601 0.025177 +v -0.009452 -0.039913 0.024778 +v -0.009977 -0.039426 0.024811 +v -0.008253 -0.039928 0.022884 +v -0.008205 -0.039621 0.022480 +v -0.008102 -0.039930 0.022831 +v -0.007833 -0.039624 0.022401 +v -0.007429 -0.039074 0.021930 +v -0.008317 -0.039524 0.025514 +v -0.007188 -0.039535 0.025754 +v -0.008675 -0.039523 0.024417 +v -0.007903 -0.039532 0.023558 +v -0.006774 -0.039542 0.023797 +v -0.006416 -0.039544 0.024895 +v 0.249273 -0.025808 0.024904 +v 0.250005 -0.025998 0.025777 +v 0.249084 -0.025984 0.025376 +v 0.249480 -0.026087 0.025847 +v 0.250801 -0.025241 0.023745 +v 0.249671 -0.025429 0.023889 +v 0.248921 -0.025741 0.024560 +v 0.251135 -0.025810 0.025633 +v 0.249852 -0.025253 0.023415 +v 0.249525 -0.025346 0.023576 +v 0.251229 -0.025910 0.025979 +v 0.250530 -0.026065 0.026188 +v 0.251533 -0.025431 0.024617 +v 0.250338 -0.025165 0.023333 +v 0.251890 -0.025479 0.024903 +v 0.251549 -0.025194 0.023892 +v 0.251820 -0.025600 0.025252 +v 0.248646 -0.018791 0.028001 +v 0.249609 -0.018778 0.028336 +v 0.250358 -0.018592 0.028051 +v 0.250784 -0.018259 0.027187 +v 0.250656 -0.018086 0.026603 +v 0.249893 -0.017967 0.025938 +v 0.249484 -0.017994 0.025863 +v 0.248426 -0.018290 0.026366 +v 0.248205 -0.018559 0.027112 +v 0.248540 -0.019041 0.028079 +v 0.249229 -0.024520 0.026305 +v 0.248946 -0.019073 0.028335 +v 0.249634 -0.024552 0.026562 +v 0.249650 -0.019027 0.028465 +v 0.250339 -0.024506 0.026692 +v 0.250113 -0.018937 0.028369 +v 0.250802 -0.024416 0.026596 +v 0.250515 -0.018811 0.028136 +v 0.250679 -0.018739 0.027975 +v 0.251368 -0.024218 0.026202 +v 0.251007 -0.018427 0.027139 +v 0.251696 -0.023906 0.025366 +v 0.250858 -0.018228 0.026466 +v 0.250737 -0.018177 0.026263 +v 0.251426 -0.023657 0.024490 +v 0.250199 -0.018093 0.025795 +v 0.250888 -0.023573 0.024021 +v 0.249978 -0.018090 0.025698 +v 0.250667 -0.023569 0.023925 +v 0.249506 -0.018121 0.025611 +v 0.250195 -0.023600 0.023838 +v 0.249267 -0.018155 0.025623 +v 0.249956 -0.023634 0.023849 +v 0.248815 -0.018254 0.025755 +v 0.249504 -0.023734 0.023981 +v 0.248285 -0.018463 0.026192 +v 0.248974 -0.023942 0.024419 +v 0.248084 -0.018620 0.026600 +v 0.248773 -0.024099 0.024827 +v 0.248030 -0.018773 0.027053 +v 0.248130 -0.018907 0.027505 +v 0.248819 -0.024386 0.025731 +v 0.247666 -0.024736 0.026365 +v 0.248515 -0.024957 0.027377 +v 0.248336 -0.023615 0.023163 +v 0.247469 -0.024151 0.024479 +v 0.249411 -0.024994 0.027838 +v 0.250406 -0.024913 0.027978 +v 0.250841 -0.023133 0.022646 +v 0.251162 -0.023126 0.022748 +v 0.249192 -0.023357 0.022697 +v 0.250175 -0.023187 0.022553 +v 0.250510 -0.023154 0.022581 +v 0.251949 -0.024554 0.027466 +v 0.252775 -0.024137 0.026499 +v 0.252487 -0.023282 0.023744 +v 0.253001 -0.023603 0.024938 +v 0.247741 -0.025066 0.026333 +v 0.247556 -0.024951 0.025908 +v 0.247465 -0.024526 0.024559 +v 0.247519 -0.024448 0.024340 +v 0.248393 -0.023920 0.023047 +v 0.250123 -0.023510 0.022451 +v 0.251283 -0.023438 0.022680 +v 0.252264 -0.023528 0.023338 +v 0.252567 -0.023606 0.023699 +v 0.253025 -0.023890 0.024754 +v 0.253046 -0.024181 0.025659 +v 0.252857 -0.024414 0.026307 +v 0.252503 -0.024645 0.026883 +v 0.252008 -0.024859 0.027351 +v 0.251182 -0.025094 0.027758 +v 0.250488 -0.025219 0.027875 +v 0.248492 -0.025261 0.027228 +v 0.250152 -0.023741 0.022505 +v 0.247592 -0.024996 0.025387 +v 0.252178 -0.024235 0.023572 +v 0.252864 -0.024441 0.025081 +v 0.252085 -0.025303 0.024823 +v 0.252082 -0.025347 0.024959 +v 0.252838 -0.024577 0.025491 +v 0.251304 -0.025499 0.027139 +v 0.250814 -0.025969 0.026386 +v 0.250529 -0.025766 0.027094 +v 0.247697 -0.025120 0.025813 +v 0.248191 -0.025552 0.025525 +v 0.248104 -0.025448 0.025170 +v 0.248693 -0.025691 0.024703 +v 0.248702 -0.025646 0.024568 +v 0.248583 -0.024600 0.023302 +v 0.248731 -0.024540 0.023174 +v 0.249926 -0.023773 0.022515 +v 0.252042 -0.024204 0.023423 +v 0.249196 -0.025194 0.025103 +v 0.249928 -0.025384 0.025975 +v 0.249593 -0.024815 0.024087 +v 0.250723 -0.024627 0.023944 +v 0.251456 -0.024817 0.024816 +v 0.251058 -0.025196 0.025832 +v 0.238186 -0.026234 0.042494 +v 0.238540 -0.026166 0.042587 +v 0.239246 -0.025843 0.043441 +v 0.238718 -0.025879 0.043533 +v 0.239147 -0.025764 0.043764 +v 0.238252 -0.026361 0.042014 +v 0.240105 -0.026327 0.041353 +v 0.240146 -0.026418 0.041012 +v 0.238969 -0.026408 0.041543 +v 0.240382 -0.025762 0.043251 +v 0.238833 -0.026511 0.041232 +v 0.240912 -0.025723 0.043167 +v 0.239884 -0.025661 0.043821 +v 0.240812 -0.026004 0.042207 +v 0.241041 -0.026098 0.041777 +v 0.241117 -0.025824 0.042722 +v 0.237935 -0.018605 0.041290 +v 0.238888 -0.018408 0.041591 +v 0.239795 -0.018431 0.041126 +v 0.240060 -0.018720 0.039983 +v 0.239436 -0.019006 0.039229 +v 0.238839 -0.019115 0.039092 +v 0.238058 -0.019134 0.039351 +v 0.237657 -0.019050 0.039819 +v 0.237541 -0.018843 0.040607 +v 0.237823 -0.018771 0.041489 +v 0.238011 -0.018710 0.041627 +v 0.238666 -0.024259 0.043184 +v 0.238923 -0.018544 0.041837 +v 0.239578 -0.024092 0.043393 +v 0.239604 -0.018527 0.041611 +v 0.240259 -0.024075 0.043167 +v 0.239969 -0.018571 0.041300 +v 0.240624 -0.024119 0.042856 +v 0.240943 -0.024258 0.042229 +v 0.240322 -0.018770 0.040441 +v 0.240977 -0.024319 0.041997 +v 0.240274 -0.018905 0.039981 +v 0.240079 -0.019045 0.039564 +v 0.240734 -0.024593 0.041121 +v 0.240410 -0.024724 0.040790 +v 0.239555 -0.019234 0.039111 +v 0.240210 -0.024782 0.040668 +v 0.238866 -0.019359 0.038953 +v 0.238627 -0.019382 0.038974 +v 0.239282 -0.024930 0.040531 +v 0.238170 -0.019393 0.039125 +v 0.238825 -0.024942 0.040682 +v 0.237965 -0.019382 0.039252 +v 0.237626 -0.019327 0.039589 +v 0.238281 -0.024876 0.041146 +v 0.237502 -0.019285 0.039792 +v 0.237344 -0.019113 0.040471 +v 0.237999 -0.024662 0.042028 +v 0.237368 -0.019046 0.040701 +v 0.237430 -0.018976 0.040924 +v 0.238085 -0.024525 0.042481 +v 0.241377 -0.024874 0.039851 +v 0.236911 -0.024470 0.043168 +v 0.237480 -0.024184 0.043950 +v 0.237680 -0.025297 0.039899 +v 0.236772 -0.025020 0.041266 +v 0.238613 -0.023870 0.044591 +v 0.239606 -0.023725 0.044692 +v 0.241114 -0.024959 0.039657 +v 0.238552 -0.025336 0.039394 +v 0.239541 -0.025271 0.039209 +v 0.242249 -0.024032 0.042484 +v 0.241167 -0.023703 0.044114 +v 0.242155 -0.023955 0.042798 +v 0.241994 -0.024592 0.040597 +v 0.242297 -0.024299 0.041512 +v 0.237225 -0.024626 0.043712 +v 0.236982 -0.024763 0.043325 +v 0.236698 -0.025169 0.041996 +v 0.236821 -0.025346 0.041315 +v 0.237559 -0.025591 0.040130 +v 0.237736 -0.025615 0.039972 +v 0.239486 -0.025596 0.039300 +v 0.240192 -0.025498 0.039355 +v 0.241254 -0.025243 0.039815 +v 0.241896 -0.024985 0.040467 +v 0.242017 -0.024916 0.040661 +v 0.242322 -0.024640 0.041518 +v 0.242347 -0.024444 0.042204 +v 0.242106 -0.024222 0.043097 +v 0.241734 -0.024098 0.043694 +v 0.241224 -0.024020 0.044188 +v 0.240384 -0.023995 0.044632 +v 0.239685 -0.024036 0.044778 +v 0.238977 -0.024127 0.044752 +v 0.238747 -0.024167 0.044705 +v 0.237532 -0.024494 0.044052 +v 0.241705 -0.024582 0.043479 +v 0.241578 -0.024548 0.043651 +v 0.239361 -0.024967 0.044430 +v 0.238811 -0.025063 0.044318 +v 0.238430 -0.025583 0.043774 +v 0.237887 -0.025103 0.043919 +v 0.237749 -0.025158 0.043779 +v 0.238205 -0.025668 0.043564 +v 0.237370 -0.025722 0.042575 +v 0.237174 -0.025680 0.042161 +v 0.237374 -0.025875 0.042027 +v 0.238043 -0.026163 0.040721 +v 0.238336 -0.026196 0.040481 +v 0.240176 -0.025820 0.039709 +v 0.240384 -0.025781 0.039760 +v 0.238466 -0.025544 0.042413 +v 0.239173 -0.025221 0.043267 +v 0.238896 -0.025786 0.041368 +v 0.240032 -0.025705 0.041179 +v 0.240738 -0.025382 0.042033 +v 0.240309 -0.025140 0.043077 +v 0.229311 -0.027719 0.024006 +v 0.230041 -0.027972 0.024865 +v 0.229121 -0.027926 0.024464 +v 0.229515 -0.028062 0.024928 +v 0.230845 -0.027085 0.022890 +v 0.230877 -0.026951 0.022563 +v 0.230315 -0.028097 0.025260 +v 0.229714 -0.027276 0.023019 +v 0.228961 -0.027627 0.023666 +v 0.231172 -0.027782 0.024736 +v 0.229221 -0.027340 0.023028 +v 0.230016 -0.027041 0.022525 +v 0.231461 -0.027827 0.024938 +v 0.231575 -0.027338 0.023749 +v 0.231793 -0.027150 0.023344 +v 0.228723 -0.020922 0.027566 +v 0.229685 -0.020939 0.027903 +v 0.230436 -0.020738 0.027632 +v 0.230866 -0.020350 0.026794 +v 0.230503 -0.020036 0.025895 +v 0.229570 -0.019989 0.025488 +v 0.228795 -0.020169 0.025700 +v 0.228333 -0.020470 0.026312 +v 0.228311 -0.020702 0.026888 +v 0.228614 -0.021177 0.027627 +v 0.228807 -0.021210 0.027769 +v 0.229465 -0.026562 0.025632 +v 0.229724 -0.021195 0.028015 +v 0.230382 -0.026547 0.025879 +v 0.230188 -0.021103 0.027926 +v 0.230846 -0.026455 0.025789 +v 0.230591 -0.020964 0.027703 +v 0.230756 -0.020882 0.027547 +v 0.231414 -0.026233 0.025411 +v 0.230994 -0.020702 0.027169 +v 0.231652 -0.026053 0.025033 +v 0.231087 -0.020517 0.026735 +v 0.231077 -0.020428 0.026511 +v 0.231735 -0.025780 0.024374 +v 0.230668 -0.020154 0.025698 +v 0.231326 -0.025506 0.023561 +v 0.230285 -0.020088 0.025415 +v 0.230943 -0.025440 0.023278 +v 0.229592 -0.020099 0.025228 +v 0.229353 -0.020132 0.025237 +v 0.230011 -0.025484 0.023101 +v 0.228698 -0.020307 0.025473 +v 0.229356 -0.025659 0.023337 +v 0.228165 -0.020654 0.026179 +v 0.228823 -0.026006 0.024042 +v 0.228767 -0.026189 0.024484 +v 0.228139 -0.020923 0.026844 +v 0.228797 -0.026275 0.024708 +v 0.228310 -0.021071 0.027269 +v 0.228968 -0.026423 0.025132 +v 0.232089 -0.025007 0.022545 +v 0.227580 -0.026636 0.025238 +v 0.228554 -0.027031 0.026529 +v 0.228392 -0.025409 0.022414 +v 0.227425 -0.026283 0.024306 +v 0.227452 -0.026155 0.023995 +v 0.227519 -0.026025 0.023690 +v 0.229449 -0.027105 0.026988 +v 0.230444 -0.027041 0.027134 +v 0.229571 -0.025054 0.021888 +v 0.230570 -0.024923 0.021868 +v 0.231990 -0.026658 0.026651 +v 0.232821 -0.026182 0.025715 +v 0.233053 -0.025546 0.024194 +v 0.227598 -0.026921 0.025062 +v 0.227478 -0.026497 0.023962 +v 0.228116 -0.025866 0.022580 +v 0.228448 -0.025705 0.022278 +v 0.229481 -0.025385 0.021794 +v 0.229711 -0.025339 0.021749 +v 0.230655 -0.025224 0.021754 +v 0.231558 -0.025231 0.022049 +v 0.232148 -0.025316 0.022442 +v 0.232622 -0.025463 0.022956 +v 0.233076 -0.025820 0.023991 +v 0.233094 -0.026171 0.024875 +v 0.232901 -0.026446 0.025505 +v 0.232545 -0.026713 0.026064 +v 0.232047 -0.026954 0.026516 +v 0.231219 -0.027211 0.026904 +v 0.230524 -0.027340 0.027011 +v 0.228530 -0.027325 0.026360 +v 0.227816 -0.027155 0.025158 +v 0.232666 -0.025748 0.023126 +v 0.232545 -0.025689 0.022941 +v 0.232203 -0.026582 0.023131 +v 0.232351 -0.026684 0.023433 +v 0.232192 -0.026863 0.023431 +v 0.232241 -0.026915 0.023575 +v 0.232755 -0.026732 0.024585 +v 0.232215 -0.027326 0.024597 +v 0.232526 -0.027047 0.024831 +v 0.232662 -0.026889 0.024949 +v 0.231921 -0.027566 0.025108 +v 0.232175 -0.027333 0.025440 +v 0.231709 -0.027676 0.025319 +v 0.230911 -0.027859 0.025932 +v 0.230568 -0.028036 0.025508 +v 0.230564 -0.027833 0.026195 +v 0.230284 -0.028066 0.025495 +v 0.228973 -0.027821 0.025675 +v 0.228830 -0.027790 0.025553 +v 0.227738 -0.027084 0.024956 +v 0.227938 -0.027088 0.023992 +v 0.228122 -0.027232 0.023939 +v 0.228134 -0.027160 0.023763 +v 0.228230 -0.026355 0.022749 +v 0.228360 -0.026277 0.022595 +v 0.229871 -0.026677 0.022250 +v 0.230025 -0.026646 0.022220 +v 0.230966 -0.026562 0.022299 +v 0.231261 -0.026574 0.022421 +v 0.229238 -0.027120 0.024245 +v 0.229967 -0.027373 0.025104 +v 0.229640 -0.026676 0.023258 +v 0.230772 -0.026485 0.023129 +v 0.231501 -0.026739 0.023988 +v 0.231099 -0.027182 0.024975 +v 0.249273 0.025759 0.024904 +v 0.250005 0.025950 0.025777 +v 0.249084 0.025936 0.025376 +v 0.249916 0.026063 0.026092 +v 0.250801 0.025192 0.023745 +v 0.249671 0.025381 0.023889 +v 0.251135 0.025761 0.025633 +v 0.249178 0.025447 0.023903 +v 0.251229 0.025861 0.025979 +v 0.251798 0.025250 0.024312 +v 0.251533 0.025382 0.024617 +v 0.250214 0.025134 0.023338 +v 0.251549 0.025145 0.023892 +v 0.248646 0.018742 0.028001 +v 0.249609 0.018730 0.028336 +v 0.250358 0.018543 0.028051 +v 0.250784 0.018210 0.027187 +v 0.250656 0.018037 0.026603 +v 0.249893 0.017918 0.025938 +v 0.248710 0.018115 0.026088 +v 0.248205 0.018510 0.027112 +v 0.248540 0.018993 0.028079 +v 0.249229 0.024472 0.026305 +v 0.248946 0.019025 0.028335 +v 0.249634 0.024504 0.026562 +v 0.249650 0.018978 0.028465 +v 0.250339 0.024457 0.026692 +v 0.250113 0.018889 0.028369 +v 0.250802 0.024368 0.026596 +v 0.250515 0.018763 0.028136 +v 0.250679 0.018690 0.027975 +v 0.251368 0.024169 0.026202 +v 0.251007 0.018378 0.027139 +v 0.251696 0.023858 0.025366 +v 0.250858 0.018179 0.026466 +v 0.250737 0.018129 0.026263 +v 0.251426 0.023608 0.024490 +v 0.250199 0.018045 0.025795 +v 0.250888 0.023524 0.024021 +v 0.249978 0.018041 0.025698 +v 0.249267 0.018106 0.025623 +v 0.249956 0.023585 0.023849 +v 0.248815 0.018206 0.025755 +v 0.249504 0.023685 0.023981 +v 0.248614 0.018269 0.025872 +v 0.248285 0.018414 0.026192 +v 0.248974 0.023893 0.024419 +v 0.248084 0.018571 0.026600 +v 0.248773 0.024050 0.024827 +v 0.248030 0.018725 0.027053 +v 0.248130 0.018858 0.027505 +v 0.248819 0.024337 0.025731 +v 0.247445 0.024517 0.025752 +v 0.248259 0.024870 0.027160 +v 0.248886 0.023386 0.022819 +v 0.247714 0.023881 0.023891 +v 0.247378 0.024318 0.025111 +v 0.249411 0.024945 0.027838 +v 0.249095 0.024946 0.027718 +v 0.250406 0.024865 0.027978 +v 0.251162 0.023077 0.022748 +v 0.251471 0.023083 0.022886 +v 0.250175 0.023138 0.022553 +v 0.251949 0.024505 0.027466 +v 0.252775 0.024088 0.026499 +v 0.252487 0.023233 0.023744 +v 0.253001 0.023555 0.024938 +v 0.247741 0.025017 0.026333 +v 0.247492 0.024839 0.025687 +v 0.247592 0.024321 0.024126 +v 0.247793 0.024166 0.023723 +v 0.248221 0.023942 0.023196 +v 0.248983 0.023682 0.022691 +v 0.250123 0.023461 0.022451 +v 0.251283 0.023389 0.022680 +v 0.252264 0.023479 0.023338 +v 0.252567 0.023558 0.023699 +v 0.253025 0.023842 0.024754 +v 0.253071 0.024056 0.025434 +v 0.252857 0.024365 0.026307 +v 0.252008 0.024810 0.027351 +v 0.250488 0.025171 0.027875 +v 0.249547 0.025254 0.027766 +v 0.249100 0.025257 0.027601 +v 0.248313 0.025185 0.027073 +v 0.250152 0.023693 0.022505 +v 0.252178 0.024187 0.023572 +v 0.251884 0.025375 0.026563 +v 0.251783 0.025501 0.026387 +v 0.251651 0.025552 0.026491 +v 0.249598 0.025787 0.026948 +v 0.249422 0.025786 0.026876 +v 0.248125 0.025378 0.026286 +v 0.248601 0.025741 0.025890 +v 0.248887 0.025875 0.025497 +v 0.248017 0.025333 0.026103 +v 0.248378 0.025620 0.025430 +v 0.248738 0.025768 0.025110 +v 0.247983 0.024943 0.024280 +v 0.248046 0.024876 0.024097 +v 0.248731 0.025227 0.023873 +v 0.248816 0.025176 0.023748 +v 0.249018 0.025077 0.023521 +v 0.249680 0.024447 0.022839 +v 0.249926 0.023724 0.022515 +v 0.250050 0.024380 0.022777 +v 0.252042 0.024155 0.023423 +v 0.249196 0.025145 0.025103 +v 0.249928 0.025336 0.025975 +v 0.249593 0.024767 0.024087 +v 0.250723 0.024578 0.023944 +v 0.251456 0.024768 0.024816 +v 0.251058 0.025147 0.025832 +v 0.238540 0.026117 0.042587 +v 0.238464 0.025933 0.043275 +v 0.239246 0.025794 0.043441 +v 0.238216 0.026115 0.042733 +v 0.238252 0.026312 0.042014 +v 0.240105 0.026279 0.041353 +v 0.239510 0.025652 0.043838 +v 0.238969 0.026359 0.041543 +v 0.240382 0.025713 0.043251 +v 0.238476 0.026408 0.041577 +v 0.240026 0.026392 0.040983 +v 0.239285 0.026470 0.041016 +v 0.240912 0.025675 0.043167 +v 0.239884 0.025612 0.043821 +v 0.240812 0.025955 0.042207 +v 0.241041 0.026049 0.041777 +v 0.237935 0.018556 0.041290 +v 0.238888 0.018359 0.041591 +v 0.239795 0.018382 0.041126 +v 0.240060 0.018672 0.039983 +v 0.239436 0.018957 0.039229 +v 0.238839 0.019066 0.039092 +v 0.238058 0.019086 0.039351 +v 0.237657 0.019001 0.039819 +v 0.237541 0.018794 0.040607 +v 0.237823 0.018722 0.041489 +v 0.238011 0.018661 0.041627 +v 0.238666 0.024210 0.043184 +v 0.238923 0.018495 0.041837 +v 0.239578 0.024044 0.043393 +v 0.239389 0.018472 0.041721 +v 0.240044 0.024021 0.043278 +v 0.239969 0.018522 0.041300 +v 0.240624 0.024071 0.042856 +v 0.240322 0.018721 0.040441 +v 0.240977 0.024270 0.041997 +v 0.240274 0.018856 0.039981 +v 0.240079 0.018996 0.039564 +v 0.240734 0.024545 0.041121 +v 0.239555 0.019185 0.039111 +v 0.240210 0.024734 0.040668 +v 0.238866 0.019311 0.038953 +v 0.239521 0.024859 0.040509 +v 0.238627 0.019333 0.038974 +v 0.239282 0.024882 0.040531 +v 0.239048 0.024893 0.040589 +v 0.238170 0.019345 0.039125 +v 0.238825 0.024893 0.040682 +v 0.237965 0.019333 0.039252 +v 0.237626 0.019279 0.039589 +v 0.238281 0.024827 0.041146 +v 0.237502 0.019236 0.039792 +v 0.237344 0.019065 0.040471 +v 0.237999 0.024613 0.042028 +v 0.237368 0.018997 0.040701 +v 0.237430 0.018927 0.040924 +v 0.238085 0.024476 0.042481 +v 0.236911 0.024422 0.043168 +v 0.238242 0.025286 0.039529 +v 0.237035 0.025110 0.040661 +v 0.236697 0.024891 0.041586 +v 0.238005 0.023965 0.044337 +v 0.239940 0.023649 0.044650 +v 0.239270 0.023714 0.044697 +v 0.241114 0.024911 0.039657 +v 0.238552 0.025287 0.039394 +v 0.239206 0.025255 0.039233 +v 0.239541 0.025222 0.039209 +v 0.241167 0.023654 0.044114 +v 0.242155 0.023906 0.042798 +v 0.241994 0.024543 0.040597 +v 0.242297 0.024250 0.041512 +v 0.236982 0.024714 0.043325 +v 0.236810 0.024853 0.042902 +v 0.236720 0.025182 0.041767 +v 0.236901 0.025349 0.041096 +v 0.237114 0.025441 0.040680 +v 0.237926 0.025584 0.039828 +v 0.238338 0.025602 0.039589 +v 0.239486 0.025548 0.039300 +v 0.241254 0.025195 0.039815 +v 0.241896 0.024936 0.040467 +v 0.242017 0.024867 0.040661 +v 0.242322 0.024591 0.041518 +v 0.242347 0.024395 0.042204 +v 0.242106 0.024173 0.043097 +v 0.241734 0.024050 0.043694 +v 0.241224 0.023971 0.044188 +v 0.239448 0.024013 0.044788 +v 0.239212 0.024043 0.044780 +v 0.238094 0.024266 0.044454 +v 0.237707 0.024383 0.044201 +v 0.239738 0.025684 0.039473 +v 0.239511 0.025711 0.039474 +v 0.239475 0.024242 0.044725 +v 0.239702 0.024218 0.044715 +v 0.241705 0.024533 0.043479 +v 0.241357 0.025149 0.043365 +v 0.241578 0.024500 0.043651 +v 0.239899 0.025440 0.043987 +v 0.239758 0.025452 0.044005 +v 0.238089 0.024748 0.044234 +v 0.237919 0.024802 0.044112 +v 0.237269 0.025403 0.042935 +v 0.238000 0.026012 0.042748 +v 0.237188 0.025520 0.042553 +v 0.237977 0.026053 0.042612 +v 0.237347 0.025827 0.041391 +v 0.237431 0.025868 0.041209 +v 0.237597 0.025998 0.041323 +v 0.237794 0.026064 0.041005 +v 0.238454 0.026251 0.040662 +v 0.238918 0.026265 0.040416 +v 0.239751 0.025836 0.039658 +v 0.240384 0.025732 0.039760 +v 0.238466 0.025495 0.042413 +v 0.239173 0.025172 0.043267 +v 0.238896 0.025738 0.041368 +v 0.240032 0.025657 0.041179 +v 0.240738 0.025334 0.042033 +v 0.240309 0.025091 0.043077 +v 0.229311 0.027671 0.024006 +v 0.230041 0.027924 0.024865 +v 0.228991 0.027760 0.024131 +v 0.229950 0.028057 0.025171 +v 0.231109 0.026912 0.022659 +v 0.230845 0.027037 0.022890 +v 0.230315 0.028048 0.025260 +v 0.229714 0.027227 0.023019 +v 0.230930 0.027954 0.025214 +v 0.231172 0.027733 0.024736 +v 0.229221 0.027291 0.023028 +v 0.230016 0.026993 0.022525 +v 0.231575 0.027290 0.023749 +v 0.231930 0.027359 0.024031 +v 0.231419 0.026956 0.022866 +v 0.228723 0.020874 0.027566 +v 0.229685 0.020890 0.027903 +v 0.230436 0.020690 0.027632 +v 0.230866 0.020302 0.026794 +v 0.230503 0.019988 0.025895 +v 0.229979 0.019921 0.025566 +v 0.229161 0.020009 0.025534 +v 0.228509 0.020262 0.025969 +v 0.228311 0.020654 0.026888 +v 0.228614 0.021128 0.027627 +v 0.228807 0.021161 0.027769 +v 0.229465 0.026513 0.025632 +v 0.229724 0.021147 0.028015 +v 0.230382 0.026498 0.025879 +v 0.230188 0.021054 0.027926 +v 0.230846 0.026406 0.025789 +v 0.230591 0.020915 0.027703 +v 0.230756 0.020833 0.027547 +v 0.231414 0.026185 0.025411 +v 0.230994 0.020653 0.027169 +v 0.231652 0.026005 0.025033 +v 0.231087 0.020468 0.026735 +v 0.231077 0.020380 0.026511 +v 0.231735 0.025732 0.024374 +v 0.230668 0.020105 0.025698 +v 0.231326 0.025457 0.023561 +v 0.230285 0.020039 0.025415 +v 0.230943 0.025391 0.023278 +v 0.230064 0.020028 0.025318 +v 0.229353 0.020083 0.025237 +v 0.230011 0.025435 0.023101 +v 0.229120 0.020130 0.025282 +v 0.228698 0.020258 0.025473 +v 0.229356 0.025610 0.023337 +v 0.228368 0.020422 0.025783 +v 0.228165 0.020605 0.026179 +v 0.228823 0.025957 0.024042 +v 0.228139 0.020874 0.026844 +v 0.228797 0.026226 0.024708 +v 0.228865 0.026305 0.024926 +v 0.228310 0.021023 0.027269 +v 0.228968 0.026374 0.025132 +v 0.227708 0.026689 0.025533 +v 0.227580 0.026587 0.025238 +v 0.228554 0.026983 0.026529 +v 0.227873 0.026781 0.025813 +v 0.228392 0.025360 0.022414 +v 0.227943 0.025593 0.022860 +v 0.227452 0.026107 0.023995 +v 0.229449 0.027056 0.026988 +v 0.230444 0.026992 0.027134 +v 0.231223 0.024862 0.022038 +v 0.229901 0.024947 0.021844 +v 0.231990 0.026609 0.026651 +v 0.232821 0.026133 0.025715 +v 0.232545 0.025093 0.023023 +v 0.233053 0.025497 0.024194 +v 0.227598 0.026872 0.025062 +v 0.227478 0.026448 0.023962 +v 0.228116 0.025818 0.022580 +v 0.228448 0.025656 0.022278 +v 0.229481 0.025336 0.021794 +v 0.229711 0.025290 0.021749 +v 0.231342 0.025169 0.021949 +v 0.231963 0.025232 0.022296 +v 0.232622 0.025414 0.022956 +v 0.233076 0.025771 0.023991 +v 0.233094 0.026122 0.024875 +v 0.232901 0.026397 0.025505 +v 0.232047 0.026906 0.026516 +v 0.231652 0.027045 0.026743 +v 0.230524 0.027291 0.027011 +v 0.228530 0.027276 0.026359 +v 0.231914 0.025466 0.022310 +v 0.232637 0.026708 0.024140 +v 0.232613 0.026852 0.024491 +v 0.230548 0.027567 0.026621 +v 0.229558 0.027741 0.026250 +v 0.229709 0.027918 0.025832 +v 0.229640 0.027976 0.025554 +v 0.228973 0.027772 0.025675 +v 0.227965 0.027254 0.025042 +v 0.227890 0.027187 0.024850 +v 0.228691 0.026848 0.022838 +v 0.228230 0.026307 0.022749 +v 0.228360 0.026229 0.022595 +v 0.228913 0.026725 0.022596 +v 0.229871 0.026628 0.022250 +v 0.230025 0.026598 0.022220 +v 0.232092 0.025500 0.022449 +v 0.229238 0.027071 0.024245 +v 0.229967 0.027324 0.025104 +v 0.229640 0.026627 0.023258 +v 0.230772 0.026437 0.023129 +v 0.231501 0.026690 0.023988 +v 0.231099 0.027134 0.024975 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.750000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.250000 0.250000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vt 0.750000 0.750000 +vn 0.0015 0.9882 0.1529 +vn -0.0014 0.9548 0.2973 +vn 0.0014 0.8277 0.5612 +vn -0.0016 0.7159 0.6982 +vn 0.0007 0.4827 0.8758 +vn -0.0003 0.3701 0.9290 +vn 0.0004 -0.0223 0.9998 +vn 0.0003 0.0215 0.9998 +vn 0.0014 -0.4589 0.8885 +vn -0.0007 -0.4244 0.9055 +vn -0.0012 -0.7954 0.6061 +vn 0.0016 -0.8567 0.5158 +vn -0.0017 -0.9948 0.1023 +vn 0.0017 -0.9998 -0.0216 +vn -0.0015 -0.9007 -0.4345 +vn 0.0018 -0.8333 -0.5528 +vn -0.0016 -0.5840 -0.8118 +vn 0.0019 -0.4228 -0.9062 +vn -0.0019 -0.1271 -0.9919 +vn 0.0016 0.0597 -0.9982 +vn -0.0017 0.3969 -0.9178 +vn 0.0019 0.5410 -0.8410 +vn -0.0019 0.7870 -0.6170 +vn 0.0023 0.9234 -0.3838 +vn -0.0017 0.9836 -0.1802 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0168 -0.9986 -0.0495 +vn -0.0103 -0.9991 0.0401 +vn 0.0126 -0.9910 -0.1332 +vn -0.2793 -0.9597 -0.0298 +vn -0.0103 0.9990 0.0442 +vn -0.3027 0.9528 0.0245 +vn -0.0926 0.9748 0.2029 +vn -0.2276 0.9085 0.3505 +vn -0.1102 0.9270 0.3585 +vn -0.2970 0.7198 0.6274 +vn -0.1750 0.8139 0.5540 +vn -0.1310 0.6578 0.7417 +vn -0.2732 0.4500 0.8502 +vn -0.1409 0.4729 0.8698 +vn -0.2797 0.0721 0.9574 +vn -0.1171 0.2844 0.9515 +vn -0.0549 0.0323 0.9980 +vn -0.1137 -0.2003 0.9731 +vn -0.2715 -0.3312 0.9036 +vn -0.1475 -0.4487 0.8814 +vn -0.2723 -0.6322 0.7254 +vn -0.1190 -0.6856 0.7182 +vn -0.2941 -0.7920 0.5350 +vn -0.1848 -0.8700 0.4571 +vn 0.1276 -0.9418 0.3109 +vn -0.2743 -0.9390 0.2074 +vn -0.0907 -0.9726 0.2138 +vn -0.2707 -0.8901 -0.3667 +vn 0.0024 -0.9160 -0.4012 +vn -0.2834 -0.7106 -0.6440 +vn 0.0008 -0.8029 -0.5961 +vn 0.0045 -0.6450 -0.7641 +vn -0.2395 -0.4494 -0.8606 +vn 0.0034 -0.4865 -0.8737 +vn 0.0024 -0.2626 -0.9649 +vn -0.2849 -0.2058 -0.9362 +vn -0.2965 0.1445 -0.9440 +vn 0.0037 -0.0009 -1.0000 +vn 0.0038 0.2700 -0.9628 +vn -0.2365 0.4940 -0.8367 +vn 0.3713 0.3284 -0.8685 +vn -0.2661 0.7140 -0.6477 +vn 0.1971 0.6241 -0.7561 +vn 0.2644 0.7764 -0.5721 +vn -0.2800 0.8890 -0.3624 +vn 0.3185 0.8730 -0.3693 +vn 0.0024 0.9971 -0.0756 +vn 0.2489 -0.0021 0.9685 +vn 0.0638 -0.0164 0.9978 +vn 0.2061 -0.0241 0.9782 +vn 0.0627 0.0086 0.9980 +vn 0.0605 0.0090 0.9981 +vn 0.0495 -0.1142 0.9922 +vn 0.0603 0.0127 0.9981 +vn 0.0224 -0.2889 0.9571 +vn 0.0564 0.0016 0.9984 +vn 0.0565 0.0011 0.9984 +vn 0.0596 -0.0356 0.9976 +vn 0.0470 -0.6699 0.7409 +vn 0.0003 -0.4589 0.8885 +vn 0.1331 -0.8970 0.4214 +vn 0.0942 -0.7099 0.6980 +vn 0.0506 -0.5518 0.8324 +vn -0.0097 -0.9999 0.0068 +vn -0.0050 -1.0000 0.0061 +vn -0.0104 -0.9999 0.0064 +vn -0.0018 -1.0000 0.0021 +vn -0.0160 -0.9999 0.0042 +vn 0.1603 -0.9837 0.0817 +vn 0.0053 -1.0000 0.0039 +vn 0.0093 -1.0000 0.0028 +vn 0.5000 -0.7974 0.3379 +vn 0.0077 -1.0000 -0.0009 +vn -0.0000 -1.0000 -0.0000 +vn -0.0000 -1.0000 0.0020 +vn 0.0002 -1.0000 0.0011 +vn 0.4460 -0.8782 0.1729 +vn -0.0008 -1.0000 0.0040 +vn -0.3709 0.5927 0.7149 +vn -0.3392 0.4569 0.8223 +vn -0.4844 0.5062 0.7135 +vn -0.3779 0.7833 0.4937 +vn -0.3744 0.7409 0.5575 +vn -0.3968 -0.6579 0.6401 +vn -0.4198 -0.7495 0.5118 +vn -0.5141 -0.5143 0.6864 +vn -0.3792 -0.4852 0.7879 +vn -0.0063 1.0000 0.0054 +vn -0.1129 0.9828 0.1462 +vn -0.0207 0.9998 0.0034 +vn -0.0007 1.0000 -0.0017 +vn -0.0029 -1.0000 0.0019 +vn -0.0128 -0.9999 0.0008 +vn -0.0737 -0.9934 0.0876 +vn -0.0005 -1.0000 0.0055 +vn -0.3012 0.8721 0.3856 +vn -0.2296 0.1752 0.9574 +vn -0.2198 -0.2168 0.9512 +vn 0.9870 -0.0053 -0.1609 +vn 0.9919 0.0139 -0.1264 +vn 0.9898 0.0049 -0.1425 +vn 0.9937 0.0231 -0.1098 +vn 0.9046 -0.0329 0.4250 +vn 0.8588 0.0204 0.5119 +vn 0.8790 -0.0015 0.4769 +vn 0.8290 0.0497 0.5570 +vn 0.3355 -0.0580 0.9402 +vn 0.2806 -0.0189 0.9596 +vn 0.3004 -0.0329 0.9532 +vn 0.2374 0.0113 0.9713 +vn 0.6397 0.0447 -0.7673 +vn 0.7663 -0.0142 -0.6424 +vn 0.5707 -0.0248 -0.8208 +vn 0.2383 0.0435 -0.9702 +vn -0.1581 -0.0433 -0.9865 +vn -0.5504 0.0449 -0.8337 +vn -0.8281 -0.0402 -0.5591 +vn -0.8788 0.0280 -0.4764 +vn -0.9699 -0.0629 -0.2351 +vn -0.9586 0.0589 0.2786 +vn -0.9493 0.0356 0.3124 +vn -0.9531 0.0446 0.2995 +vn -0.9403 0.0162 0.3400 +vn -0.4436 -0.0019 0.8962 +vn -0.4998 -0.0461 0.8649 +vn -0.4628 -0.0168 0.8863 +vn -0.4025 0.0291 0.9150 +vn -0.0093 0.8127 0.5826 +vn 0.1766 0.8882 0.4242 +vn 0.0037 0.9992 0.0409 +vn -0.0098 0.9997 0.0217 +vn -0.0125 0.9999 0.0105 +vn -0.0116 0.9997 0.0203 +vn 0.0304 0.9989 -0.0369 +vn 0.3743 0.8919 -0.2538 +vn 0.3576 0.9329 -0.0434 +vn 0.0111 0.9999 -0.0002 +vn 0.0192 0.9997 0.0161 +vn 0.3535 0.9098 0.2174 +vn -0.0307 -0.9995 0.0090 +vn -0.0053 -0.9994 0.0329 +vn -0.0419 -0.9991 0.0056 +vn -0.0693 -0.9975 -0.0120 +vn 0.0337 -0.9990 0.0306 +vn 0.0323 -0.9992 -0.0256 +vn 0.0333 -0.9992 -0.0216 +vn 0.0326 -0.9993 0.0203 +vn 0.4360 -0.8551 0.2805 +vn 0.0296 -0.9995 0.0145 +vn 0.9869 -0.0062 -0.1610 +vn 0.9952 0.0311 -0.0929 +vn 0.9928 -0.0209 0.1178 +vn 0.9360 0.0398 0.3498 +vn 0.6754 -0.0411 0.7363 +vn 0.3970 0.0345 0.9172 +vn 0.2345 -0.0281 0.9717 +vn 0.0497 0.0619 0.9968 +vn -0.4998 -0.0625 0.8639 +vn -0.5982 0.0027 0.8014 +vn -0.7699 -0.0298 0.6375 +vn -0.8821 0.0361 0.4697 +vn -0.9989 -0.0352 0.0318 +vn -0.9688 0.0361 -0.2454 +vn -0.9090 -0.0167 -0.4164 +vn -0.8018 0.0827 -0.5919 +vn -0.3432 -0.0555 -0.9376 +vn -0.2564 -0.0004 -0.9666 +vn -0.2818 -0.0163 -0.9593 +vn -0.1896 0.0408 -0.9810 +vn 0.3628 -0.0551 -0.9303 +vn 0.5314 0.0234 -0.8468 +vn 0.5927 -0.0132 -0.8053 +vn 0.7790 0.3247 0.5364 +vn 0.8635 0.2265 0.4506 +vn 0.8202 0.0100 0.5720 +vn 0.8174 -0.0046 0.5761 +vn 0.8862 -0.0021 0.4634 +vn 0.8176 -0.0052 0.5758 +vn 0.8671 0.3748 0.3282 +vn 0.9371 0.0010 0.3490 +vn -0.0046 1.0000 0.0056 +vn -0.0026 1.0000 0.0022 +vn 0.0000 1.0000 0.0000 +vn 0.2161 0.9699 0.1126 +vn 0.4708 0.8223 0.3197 +vn 0.0136 0.9999 0.0051 +vn 0.0081 1.0000 -0.0013 +vn 0.0113 0.9999 0.0041 +vn 0.3904 0.9082 0.1510 +vn -0.0120 0.9999 0.0056 +vn -0.0099 0.9999 0.0105 +vn 0.0001 1.0000 0.0020 +vn -0.0001 1.0000 0.0006 +vn -0.0158 0.9999 0.0050 +vn -0.0149 0.9998 0.0125 +vn 0.4413 -0.0188 0.8972 +vn 0.6279 0.0088 0.7783 +vn 0.6650 -0.0122 0.7467 +vn 0.8576 -0.0165 0.5140 +vn 0.9212 0.0147 0.3889 +vn 0.9882 -0.0228 0.1514 +vn 0.9936 0.0100 -0.1129 +vn 0.9769 -0.0119 -0.2132 +vn 0.8618 -0.0179 -0.5070 +vn 0.8617 -0.0085 -0.5073 +vn 0.7137 -0.0176 -0.7002 +vn 0.7005 -0.0684 -0.7104 +vn 0.6879 -0.1083 -0.7177 +vn 0.8594 0.0048 -0.5112 +vn 0.6223 0.4136 -0.6646 +vn 0.8186 0.0222 -0.5739 +vn 0.6391 -0.3478 -0.6860 +vn 0.7047 0.0665 -0.7063 +vn 0.7043 0.0408 -0.7087 +vn 0.5593 0.3575 -0.7479 +vn 0.7044 -0.0840 -0.7048 +vn 0.7261 0.0048 -0.6876 +vn 0.0521 -0.0164 0.9985 +vn 0.0556 -0.0046 0.9984 +vn 0.0289 0.1140 0.9931 +vn 0.0061 0.2866 0.9580 +vn 0.1916 0.0310 0.9810 +vn 0.0677 0.0108 0.9976 +vn 0.2433 0.0043 0.9699 +vn 0.0707 0.0251 0.9972 +vn 0.0595 -0.0188 0.9981 +vn 0.0565 -0.0007 0.9984 +vn 0.5128 0.0231 0.8582 +vn 0.6339 -0.0117 0.7733 +vn 0.7656 0.0226 0.6429 +vn 0.9212 -0.0025 0.3891 +vn 0.9204 0.0311 0.3897 +vn 0.9997 0.0204 0.0138 +vn 0.9943 -0.0097 -0.1062 +vn 0.9403 0.0278 -0.3392 +vn 0.4941 -0.8319 -0.2527 +vn 0.6436 -0.7304 -0.2287 +vn 0.5645 -0.7890 -0.2428 +vn 0.4158 -0.8711 -0.2613 +vn -0.0667 -0.9977 -0.0069 +vn -0.1203 -0.9902 0.0707 +vn -0.0907 -0.9955 0.0276 +vn -0.1573 -0.9796 0.1248 +vn -0.8289 -0.4294 0.3585 +vn -0.6415 -0.6646 0.3832 +vn -0.7305 -0.5696 0.3768 +vn -0.8746 -0.3425 0.3431 +vn -0.8232 0.2748 0.4968 +vn -0.6683 0.7028 0.2439 +vn 0.0475 0.9972 -0.0579 +vn -0.1564 0.9770 0.1451 +vn 0.2103 0.9762 -0.0537 +vn 0.3104 0.9322 -0.1862 +vn 0.5931 0.7855 -0.1768 +vn 0.8893 -0.0256 -0.4565 +vn 0.8571 0.0494 -0.5127 +vn 0.8617 0.0399 -0.5058 +vn 0.8315 0.0984 -0.5468 +vn -0.2395 0.9597 0.1473 +vn -0.2131 0.9648 0.1542 +vn -0.2238 0.9628 0.1514 +vn -0.1986 0.9673 0.1579 +vn 0.4848 0.8319 -0.2700 +vn 0.6463 0.7220 -0.2470 +vn 0.5900 0.7655 -0.2565 +vn 0.7175 0.6569 -0.2320 +vn 0.8150 0.2220 -0.5353 +vn -0.2789 -0.9345 0.2211 +vn -0.2089 -0.9707 0.1191 +vn -0.2375 -0.9580 0.1604 +vn -0.1419 -0.9896 0.0241 +vn 0.7284 -0.6201 -0.2913 +vn 0.6454 -0.6847 -0.3384 +vn 0.7206 -0.6269 -0.2962 +vn 0.7928 -0.5571 -0.2472 +vn -0.8667 -0.1183 0.4847 +vn -0.8664 -0.2568 0.4283 +vn -0.8465 -0.3907 0.3617 +vn -0.8532 -0.0072 0.5215 +vn -0.7929 0.5248 0.3097 +vn 0.4461 -0.0001 0.8950 +vn 0.4461 -0.0000 0.8950 +vn 0.4460 0.0003 0.8951 +vn -0.4408 -0.0047 -0.8976 +vn -0.4461 0.0001 -0.8950 +vn -0.4462 0.0008 -0.8949 +vn -0.4460 -0.0001 -0.8950 +vn -0.4415 -0.0041 -0.8972 +vn 0.4475 -0.0069 0.8942 +vn 0.4464 -0.0005 0.8948 +vn 0.4494 -0.0030 0.8934 +vn 0.6991 -0.5910 0.4025 +vn 0.7166 -0.6938 0.0714 +vn 0.7240 -0.6839 0.0900 +vn 0.6815 -0.6840 -0.2601 +vn 0.6287 -0.7756 -0.0561 +vn 0.3289 -0.7924 0.5137 +vn 0.4820 -0.6999 0.5270 +vn 0.5650 -0.7358 -0.3734 +vn 0.4365 -0.7907 -0.4293 +vn 0.4371 -0.7196 -0.5395 +vn 0.4599 -0.5860 -0.6671 +vn 0.5986 -0.2897 -0.7468 +vn 0.5851 0.0808 -0.8069 +vn 0.7226 -0.2081 -0.6592 +vn 0.5894 0.6572 -0.4697 +vn 0.6099 -0.0582 -0.7903 +vn 0.5758 0.7911 -0.2066 +vn 0.6039 0.7938 0.0719 +vn 0.8025 0.5966 0.0085 +vn 0.5305 0.8297 0.1735 +vn 0.8023 0.5774 0.1517 +vn 0.3874 0.8189 0.4235 +vn 0.3609 0.7075 0.6076 +vn 0.0982 0.7980 0.5946 +vn 0.0367 0.5862 0.8093 +vn 0.0304 0.5596 0.8282 +vn -0.5528 0.7883 0.2700 +vn -0.5769 0.7558 0.3098 +vn -0.5200 0.8257 0.2186 +vn -0.6011 0.7173 0.3523 +vn -0.9056 0.0614 0.4197 +vn -0.8938 0.0120 0.4483 +vn -0.9204 0.1673 0.3533 +vn -0.8557 -0.1008 0.5076 +vn -0.5958 -0.7595 0.2611 +vn -0.6027 -0.7485 0.2768 +vn -0.6003 -0.7523 0.2714 +vn -0.6055 -0.7436 0.2834 +vn -0.6545 0.7042 0.2753 +vn -0.6702 0.6664 0.3267 +vn -0.6609 0.6899 0.2954 +vn -0.6359 0.7389 0.2227 +vn -0.8463 0.0514 0.5302 +vn -0.7824 -0.5399 0.3105 +vn -0.7350 -0.5944 0.3264 +vn -0.8689 -0.4141 0.2711 +vn -0.5878 -0.7245 0.3601 +vn 0.6334 0.6990 0.3319 +vn 0.5478 -0.7859 0.2869 +vn 0.6038 -0.6833 0.4105 +vn 0.7382 -0.5557 0.3824 +vn 0.6633 -0.7038 0.2544 +vn -0.4894 -0.8611 -0.1376 +vn -0.4877 -0.7431 -0.4582 +vn -0.4670 -0.4830 -0.7407 +vn -0.4852 -0.0513 -0.8729 +vn -0.4621 0.3750 -0.8036 +vn -0.5094 0.6933 -0.5097 +vn -0.4378 0.8842 -0.1631 +vn -0.4853 0.8013 0.3497 +vn -0.4833 0.5378 0.6908 +vn -0.4650 0.2316 0.8545 +vn -0.4335 -0.1607 0.8867 +vn -0.5020 -0.5068 0.7008 +vn -0.4447 -0.8267 0.3447 +vn -1.0000 -0.0001 0.0001 +vn -1.0000 -0.0003 -0.0001 +vn -1.0000 -0.0004 -0.0000 +vn -1.0000 -0.0002 -0.0001 +vn -1.0000 -0.0003 0.0007 +vn -1.0000 0.0001 0.0001 +vn -1.0000 0.0001 0.0000 +vn -1.0000 -0.0005 -0.0002 +vn -1.0000 -0.0004 -0.0001 +vn 0.4461 0.0001 0.8950 +vn 0.4503 -0.0015 0.8929 +vn 0.4485 -0.0059 0.8938 +vn -0.4340 -0.0109 -0.9009 +vn 0.4458 -0.0017 0.8952 +vn 0.4379 -0.0101 0.8990 +vn 0.4465 -0.0017 0.8948 +vn 0.4538 -0.0070 0.8911 +vn 0.4524 -0.0059 0.8918 +vn 0.4622 -0.0150 0.8866 +vn -0.4411 -0.0054 -0.8974 +vn -0.4461 0.0000 -0.8950 +vn -0.4419 -0.0045 -0.8970 +vn 0.4461 -0.0002 0.8950 +vn -0.4360 -0.0109 -0.8999 +vn 0.4462 0.0002 0.8949 +vn -0.2648 -0.9158 0.3021 +vn 0.0725 0.9862 0.1491 +vn 0.0207 0.9943 0.1046 +vn 0.0862 0.9955 0.0399 +vn 0.0967 0.9951 0.0202 +vn 0.0983 0.9952 0.0012 +vn -0.1089 0.9921 0.0623 +vn -0.0643 0.9955 0.0692 +vn -0.0140 0.9952 0.0964 +vn -0.0203 0.9951 0.0964 +vn 0.1160 0.9881 -0.1007 +vn 0.0991 0.9938 -0.0513 +vn 0.0530 0.9950 -0.0843 +vn -0.0413 0.9975 -0.0568 +vn -0.0584 0.9950 -0.0809 +vn -0.1525 0.9881 -0.0181 +vn -0.0739 0.9967 -0.0327 +vn -0.1038 0.9943 0.0229 +vn -0.0145 0.9948 -0.1005 +vn -0.0326 0.9950 -0.0940 +vn 0.9962 -0.0085 0.0862 +vn 0.9538 0.0079 0.3003 +vn 0.8778 -0.0057 0.4791 +vn 0.8102 0.0068 0.5861 +vn 0.3930 -0.0105 0.9195 +vn 0.1233 0.0126 0.9923 +vn 0.0330 -0.0125 0.9994 +vn -0.2741 0.0120 0.9616 +vn -0.3533 -0.0137 0.9354 +vn -0.6097 0.0106 0.7926 +vn -0.9470 -0.0089 0.3212 +vn -0.9253 -0.0015 0.3794 +vn -0.9275 -0.0023 0.3737 +vn -0.9483 -0.0094 0.3174 +vn -0.8881 -0.0090 -0.4596 +vn -0.9483 0.0094 -0.3174 +vn -0.9432 0.0076 -0.3320 +vn -0.8808 -0.0109 -0.4733 +vn -0.1866 -0.0098 -0.9824 +vn -0.3835 0.0094 -0.9235 +vn -0.0947 0.0088 -0.9955 +vn 0.2003 -0.0117 -0.9797 +vn 0.5494 0.0093 -0.8355 +vn 0.7922 -0.0109 -0.6102 +vn 0.9508 0.0089 -0.3095 +vn -0.0151 -0.9978 -0.0648 +vn -0.0010 -0.9978 -0.0669 +vn 0.0562 -0.9832 -0.1735 +vn 0.0786 -0.9897 -0.1200 +vn 0.0965 -0.9903 -0.1002 +vn -0.0436 -0.9935 0.1047 +vn -0.0653 -0.9917 0.1109 +vn -0.0772 -0.9967 0.0265 +vn -0.0813 -0.9965 0.0210 +vn -0.1341 -0.9901 -0.0425 +vn 0.0767 -0.9942 0.0752 +vn 0.0697 -0.9937 0.0881 +vn -0.0063 -0.9936 0.1124 +vn 0.0071 -0.9975 0.0705 +vn 0.1174 -0.9923 -0.0401 +vn 0.2722 -0.9620 -0.0195 +vn 0.1065 -0.9942 0.0120 +vn -0.1428 -0.9894 -0.0277 +vn -0.0684 -0.9970 -0.0358 +vn -0.9918 0.0067 0.1275 +vn -0.9970 -0.0032 -0.0777 +vn -0.9384 -0.0060 0.3454 +vn -0.7187 0.0084 0.6953 +vn -0.7033 -0.0030 0.7109 +vn -0.3285 0.0030 0.9445 +vn -0.2515 0.0037 0.9679 +vn 0.2663 0.0037 0.9639 +vn 0.0557 -0.0001 0.9984 +vn 0.4272 -0.0014 0.9042 +vn 0.6980 0.0022 0.7161 +vn 0.7423 -0.0024 0.6701 +vn 0.9365 0.0003 0.3507 +vn 0.9217 -0.0045 0.3879 +vn 0.9992 -0.0001 -0.0401 +vn 0.9951 0.0039 -0.0988 +vn 0.8704 -0.0008 -0.4924 +vn 0.8667 -0.0008 -0.4989 +vn 0.4904 -0.0052 -0.8715 +vn 0.5686 0.0019 -0.8226 +vn 0.1717 0.0029 -0.9851 +vn -0.0224 -0.0083 -0.9997 +vn -0.2906 0.0031 -0.9568 +vn -0.5146 0.0051 -0.8574 +vn -0.6905 0.0071 -0.7233 +vn -0.8636 0.0064 -0.5041 +vn -0.9214 0.0058 -0.3886 +vn 0.2460 -0.8031 0.5427 +vn -0.1491 -0.8450 0.5136 +vn -0.5122 -0.8234 -0.2443 +vn -0.7083 0.1241 -0.6949 +vn -0.2418 -0.7766 -0.5818 +vn 0.4947 -0.8684 -0.0346 +vn -0.1689 0.8754 -0.4529 +vn 0.5105 0.8455 0.1568 +vn 1.0000 -0.0003 -0.0000 +vn 1.0000 -0.0011 0.0001 +vn 1.0000 0.0000 0.0001 +vn 1.0000 -0.0001 -0.0000 +vn 1.0000 0.0001 -0.0000 +vn 1.0000 -0.0006 0.0006 +vn 1.0000 0.0006 -0.0001 +vn 0.4093 -0.0127 0.9123 +vn 0.4257 -0.0233 0.9046 +vn 0.4152 0.0104 0.9097 +vn 0.4381 0.0309 0.8984 +vn 0.4235 0.0355 0.9052 +vn 0.4422 -0.0344 0.8962 +vn 0.4662 -0.0324 0.8841 +vn 0.4716 -0.0115 0.8818 +vn 0.4789 0.0042 0.8779 +vn 0.4596 0.0316 0.8876 +vn -0.4416 0.0244 -0.8969 +vn -0.4734 -0.1205 -0.8726 +vn -0.5774 -0.0670 -0.8137 +vn -0.4488 -0.0431 -0.8926 +vn -0.5270 0.1934 -0.8275 +vn -0.9168 0.1713 0.3607 +vn -0.8910 0.0736 0.4480 +vn -0.9096 0.1905 0.3692 +vn -0.4568 0.8568 0.2393 +vn -0.4405 0.8691 0.2249 +vn -0.3518 0.9243 0.1478 +vn -0.3319 0.9342 0.1308 +vn 0.3693 0.9033 -0.2185 +vn 0.4582 0.8559 -0.2398 +vn 0.5706 0.7552 -0.3227 +vn 0.7763 0.5033 -0.3794 +vn 0.8740 0.0633 -0.4818 +vn 0.9026 -0.0285 -0.4296 +vn 0.7954 -0.4107 -0.4457 +vn 0.4304 -0.8716 -0.2348 +vn 0.4032 -0.8908 -0.2094 +vn 0.4249 -0.8757 -0.2296 +vn 0.3989 -0.8937 -0.2055 +vn -0.4393 -0.8797 0.1823 +vn -0.4746 -0.8528 0.2179 +vn -0.4464 -0.8746 0.1894 +vn -0.4827 -0.8461 0.2262 +vn -0.8892 0.0466 0.4552 +vn -0.5264 -0.0464 -0.8490 +vn -0.5075 -0.0840 -0.8576 +vn -0.5392 0.0017 -0.8422 +vn -0.4425 0.1066 -0.8904 +vn -0.3939 0.0954 -0.9142 +vn -0.3671 0.0498 -0.9288 +vn -0.3563 0.0358 -0.9337 +vn -0.3613 -0.0581 -0.9307 +vn -0.3486 -0.0372 -0.9365 +vn -0.5223 0.0568 -0.8509 +vn -0.4563 -0.1102 -0.8830 +vn -0.5247 0.0701 -0.8484 +vn -0.4728 0.1074 -0.8746 +vn -0.4174 -0.1024 -0.9029 +vn -0.8340 0.3162 0.4522 +vn -0.9122 -0.0361 0.4081 +vn -0.8122 -0.3649 0.4551 +vn -0.7577 -0.5306 0.3800 +vn -0.5667 -0.7181 0.4041 +vn -0.2746 -0.9615 -0.0098 +vn 0.2900 -0.9569 -0.0173 +vn 0.7655 -0.5274 -0.3685 +vn 0.5769 -0.7154 -0.3943 +vn 0.8092 -0.3709 -0.4557 +vn 0.8810 -0.2474 -0.4034 +vn 0.8589 0.0288 -0.5114 +vn 0.7661 0.5694 -0.2982 +vn 0.7293 0.6070 -0.3157 +vn 0.7412 0.5952 -0.3103 +vn 0.6938 0.6397 -0.3309 +vn -0.0081 0.9991 0.0407 +vn 0.0827 0.9916 -0.0996 +vn -0.2098 0.9745 0.0795 +vn -0.4347 0.8598 0.2679 +vn -0.7357 0.5924 0.3283 +vn -0.2855 0.9584 0.0038 +vn -0.3449 0.9224 0.1738 +vn -0.3435 0.9238 0.1694 +vn -0.3916 0.8575 0.3337 +vn 0.8029 -0.2564 -0.5382 +vn 0.8886 -0.1268 -0.4408 +vn 0.8867 -0.1302 -0.4435 +vn 0.9434 0.0036 -0.3317 +vn -0.6828 -0.7022 0.2018 +vn -0.5413 -0.7958 0.2715 +vn -0.5452 -0.7937 0.2698 +vn -0.3858 -0.8613 0.3306 +vn 0.4460 -0.0000 0.8950 +vn -0.6751 -0.3894 -0.6266 +vn 0.0667 -0.0033 -0.9978 +vn -0.6676 0.3520 -0.6560 +vn -0.9672 0.1850 0.1739 +vn 0.4133 0.0081 0.9105 +vn 0.4123 0.0204 0.9108 +vn 0.4128 -0.0158 0.9107 +vn 0.4429 0.0368 0.8958 +vn 0.4771 -0.0134 0.8787 +vn 0.4663 -0.0386 0.8838 +vn 0.4854 -0.0104 0.8742 +vn 0.4332 -0.0335 0.9007 +vn 0.4330 -0.0341 0.9007 +vn 0.4746 0.0227 0.8799 +vn 0.4559 0.0311 0.8895 +vn -0.3968 -0.1508 -0.9054 +vn -0.4156 0.1242 -0.9010 +vn -0.3722 -0.1961 -0.9072 +vn -0.4313 0.1310 -0.8926 +vn -0.4884 0.8643 0.1201 +vn -0.5445 0.7979 0.2587 +vn -0.5271 0.8143 0.2429 +vn -0.4658 0.8732 0.1432 +vn 0.1130 0.9932 -0.0281 +vn 0.5283 0.7614 -0.3758 +vn 0.7062 0.6147 -0.3512 +vn 0.5410 0.7419 -0.3961 +vn 0.7348 0.5779 -0.3552 +vn 0.8563 -0.2459 -0.4542 +vn 0.8530 -0.2702 -0.4466 +vn 0.8557 -0.2507 -0.4527 +vn 0.8523 -0.2744 -0.4453 +vn 0.5470 -0.7777 -0.3098 +vn 0.3907 -0.9006 -0.1902 +vn 0.5284 -0.7960 -0.2953 +vn 0.3700 -0.9124 -0.1748 +vn -0.2194 -0.9725 0.0783 +vn -0.3465 -0.9197 0.1847 +vn -0.2465 -0.9639 0.1008 +vn -0.3710 -0.9056 0.2056 +vn -0.8990 -0.1659 0.4054 +vn -0.8940 -0.0278 0.4473 +vn -0.8995 -0.1336 0.4160 +vn -0.8898 0.0070 0.4564 +vn -0.5258 -0.0597 -0.8485 +vn -0.5384 -0.0687 -0.8399 +vn -0.5305 0.0263 -0.8473 +vn -0.3887 0.0987 -0.9161 +vn -0.3733 0.0932 -0.9230 +vn -0.3541 0.0302 -0.9347 +vn -0.3500 0.0028 -0.9367 +vn -0.3693 -0.0725 -0.9265 +vn -0.5216 0.0616 -0.8509 +vn -0.4618 0.1034 -0.8809 +vn -0.4771 0.0942 -0.8738 +vn -0.3830 -0.0925 -0.9191 +vn -0.4361 -0.1041 -0.8939 +vn -0.4632 -0.1026 -0.8803 +vn -0.8458 0.0751 0.5283 +vn -0.8900 -0.0764 0.4494 +vn -0.8798 -0.0316 0.4744 +vn -0.9051 -0.1895 0.3805 +vn -0.5997 -0.7208 0.3476 +vn -0.5691 -0.7730 0.2803 +vn -0.5804 -0.7554 0.3042 +vn -0.5455 -0.8052 0.2328 +vn 0.1220 -0.9925 -0.0117 +vn 0.1649 -0.9823 -0.0892 +vn 0.1526 -0.9860 -0.0667 +vn 0.1948 -0.9702 -0.1442 +vn 0.7350 -0.5893 -0.3355 +vn 0.7564 -0.5103 -0.4092 +vn 0.7505 -0.5362 -0.3863 +vn 0.7649 -0.4590 -0.4519 +vn 0.9150 0.1915 -0.3550 +vn 0.8337 0.3486 -0.4282 +vn 0.8583 0.3082 -0.4104 +vn 0.7510 0.4600 -0.4736 +vn 0.2844 0.9488 -0.1378 +vn 0.2521 0.9667 -0.0439 +vn 0.2771 0.9538 -0.1161 +vn 0.3055 0.9302 -0.2036 +vn -0.4150 0.8686 0.2707 +vn -0.5503 0.8008 0.2365 +vn -0.5297 0.8129 0.2423 +vn -0.6454 0.7355 0.2062 +vn -0.3956 0.8970 0.1971 +vn -0.4227 0.8669 0.2642 +vn -0.4298 0.8575 0.2826 +vn -0.4517 0.8240 0.3420 +vn 0.7387 0.4679 -0.4852 +vn 0.7357 0.5191 -0.4351 +vn 0.7340 0.5342 -0.4194 +vn 0.7250 0.5863 -0.3613 +vn 0.3956 -0.8970 -0.1971 +vn 0.4655 -0.8669 -0.1784 +vn 0.4845 -0.8575 -0.1730 +vn 0.5451 -0.8240 -0.1547 +vn -0.8322 -0.4679 0.2976 +vn -0.7903 -0.5191 0.3254 +vn -0.7768 -0.5342 0.3335 +vn -0.7251 -0.5863 0.3613 +vn 0.4462 -0.0001 0.8949 +vn -0.9149 -0.1039 -0.3901 +vn -0.9096 -0.1062 -0.4016 +vn -0.8937 -0.1127 -0.4344 +vn -0.8877 -0.1149 -0.4459 +vn -0.4116 -0.8184 -0.4010 +vn -0.3104 -0.4858 -0.8171 +vn 0.1377 0.0197 -0.9903 +vn 0.3935 0.7185 -0.5735 +vn -0.3888 0.4299 -0.8149 +vn -0.5336 0.8454 -0.0233 +vn -0.0384 0.9991 -0.0158 +vn 0.0365 0.9992 0.0150 +vn -0.0364 0.9992 -0.0150 +vn 0.0384 0.9991 0.0158 +vn -0.3800 0.0019 0.9250 +vn -0.3045 -0.0018 0.9525 +vn -0.3778 0.0018 0.9259 +vn -0.3023 -0.0019 0.9532 +vn -0.0396 -0.9991 -0.0126 +vn 0.0376 -0.9992 0.0120 +vn -0.0376 -0.9992 -0.0120 +vn 0.0396 -0.9991 0.0126 +vn 0.3811 0.0019 -0.9245 +vn 0.3045 -0.0018 -0.9525 +vn 0.3789 0.0018 -0.9254 +vn 0.3023 -0.0019 -0.9532 +vn 0.9397 -0.0000 0.3420 +vn -0.9397 -0.0000 -0.3420 +vn -0.0330 0.9991 -0.0252 +vn 0.0313 0.9992 0.0239 +vn -0.0314 0.9992 -0.0239 +vn 0.0330 0.9991 0.0252 +vn -0.6078 0.0019 0.7941 +vn -0.5410 -0.0018 0.8410 +vn -0.6059 0.0018 0.7955 +vn -0.5390 -0.0019 0.8423 +vn -0.0349 -0.9991 -0.0224 +vn 0.0332 -0.9992 0.0213 +vn -0.0332 -0.9992 -0.0213 +vn 0.0349 -0.9991 0.0224 +vn 0.6070 0.0019 -0.7947 +vn 0.5409 -0.0018 -0.8411 +vn 0.6051 0.0018 -0.7961 +vn 0.5390 -0.0019 -0.8423 +vn 0.8191 -0.0000 0.5736 +vn 0.8192 0.0000 0.5736 +vn -0.8191 0.0000 -0.5736 +vn -0.0004 1.0000 0.0088 +vn 0.0046 1.0000 -0.0084 +vn 0.0113 0.9991 -0.0398 +vn -0.0035 0.9983 -0.0587 +vn 0.0597 0.9539 -0.2940 +vn 0.0032 1.0000 -0.0014 +vn 0.0038 0.9998 -0.0206 +vn -0.2873 0.9286 -0.2350 +vn -0.0453 0.9990 0.0026 +vn 0.0280 0.9995 0.0166 +vn -0.0009 0.9999 0.0134 +vn 0.0007 0.9994 -0.0336 +vn 0.0033 1.0000 -0.0049 +vn 0.2842 0.9016 -0.3262 +vn 0.0004 1.0000 -0.0040 +vn 0.0008 1.0000 0.0020 +vn 0.2192 0.9699 -0.1057 +vn -0.0327 0.9994 -0.0062 +vn 0.1794 0.9838 0.0039 +vn 0.0102 0.9999 0.0080 +vn 0.2306 0.9682 0.0969 +vn 0.2723 0.9348 0.2281 +vn 0.0011 1.0000 0.0002 +vn -0.0009 1.0000 -0.0023 +vn -0.0012 1.0000 -0.0028 +vn -0.0062 0.9997 -0.0215 +vn -0.0010 1.0000 -0.0072 +vn -0.0042 0.9999 -0.0154 +vn -0.0081 0.9999 -0.0116 +vn -0.0002 1.0000 -0.0003 +vn -0.0002 1.0000 -0.0007 +vn 0.0107 0.9999 -0.0020 +vn 0.0071 1.0000 -0.0003 +vn 0.0007 1.0000 0.0033 +vn 0.0368 0.9989 -0.0279 +vn -0.0007 1.0000 0.0016 +vn -0.2844 0.8998 0.3309 +vn 0.0088 0.9999 -0.0115 +vn 0.0049 0.9998 0.0173 +vn -0.4848 0.8746 0.0112 +vn -0.4424 0.8875 0.1293 +vn -0.3669 0.9217 -0.1259 +vn -0.0054 0.9999 -0.0088 +vn -0.0305 0.9991 -0.0296 +vn -0.0001 1.0000 -0.0017 +vn 0.0009 0.9999 0.0110 +vn -0.0028 0.9988 0.0487 +vn -0.0003 0.9997 0.0254 +vn 0.1914 0.9679 -0.1630 +vn 0.0000 1.0000 0.0002 +vn 0.2742 0.8786 -0.3909 +vn -0.0042 1.0000 0.0054 +vn -0.0059 1.0000 0.0052 +vn 0.0118 0.9999 -0.0069 +vn -0.0002 1.0000 0.0091 +vn 0.0036 1.0000 0.0016 +vn 0.1441 0.0042 0.9896 +vn -0.0399 0.0146 0.9991 +vn -0.0459 0.0640 0.9969 +vn -0.0652 0.3277 0.9425 +vn -0.0590 0.3023 0.9514 +vn -0.0058 0.0855 0.9963 +vn -0.0008 -0.9999 -0.0144 +vn 0.0130 -0.9996 -0.0257 +vn 0.0053 -0.9997 -0.0224 +vn -0.0165 -0.9998 0.0063 +vn 0.0005 -0.9998 0.0212 +vn -0.1060 -0.9448 -0.3101 +vn -0.0072 -0.9997 0.0243 +vn 0.0264 -0.9977 -0.0623 +vn 0.0104 -0.9990 -0.0433 +vn -0.0065 -1.0000 -0.0015 +vn 0.1821 -0.9833 -0.0003 +vn 0.2191 -0.9704 0.1012 +vn -0.0199 -0.9882 -0.1520 +vn -0.1167 -0.9927 0.0321 +vn -0.2033 -0.9785 0.0346 +vn -0.0234 -0.9992 -0.0320 +vn -0.0317 -0.9983 -0.0488 +vn -0.0386 -0.9915 -0.1241 +vn -0.0155 -0.9947 -0.1014 +vn -0.0773 -0.9958 -0.0481 +vn -0.0417 -0.9981 -0.0452 +vn -0.0010 -0.9923 -0.1237 +vn -0.0213 -0.9994 -0.0289 +vn -0.8495 0.0068 -0.5276 +vn -0.8791 -0.0128 -0.4764 +vn -0.8784 -0.0047 -0.4779 +vn -0.8889 -0.0162 -0.4578 +vn -0.9000 -0.0098 -0.4358 +vn 0.0001 -1.0000 -0.0001 +vn 0.0009 -1.0000 -0.0008 +vn 0.0015 -1.0000 -0.0014 +vn 0.0804 0.3931 -0.9160 +vn 0.0617 0.0031 -0.9981 +vn 0.2686 0.2406 -0.9327 +vn 0.4972 0.0188 -0.8674 +vn 0.5252 -0.0101 -0.8509 +vn 0.7159 0.1504 -0.6818 +vn 0.7589 0.0221 -0.6509 +vn 0.8065 0.0183 -0.5910 +vn 0.7243 0.0021 -0.6895 +vn 0.3394 0.0387 -0.9398 +vn 0.2935 0.0121 -0.9559 +vn 0.1505 0.0032 -0.9886 +vn 0.2546 -0.0106 -0.9670 +vn 0.0457 -0.0058 -0.9989 +vn 0.2953 -0.9484 -0.1159 +vn 0.0844 -0.9729 0.2153 +vn 0.0395 -0.9992 -0.0097 +vn 0.2714 -0.9309 0.2445 +vn 0.2761 -0.1943 -0.9413 +vn 0.0320 -0.2483 -0.9681 +vn 0.0538 -0.1261 -0.9906 +vn 0.0571 -0.3717 -0.9266 +vn 0.2724 -0.4594 -0.8455 +vn 0.0693 -0.5069 -0.8592 +vn 0.0700 -0.6543 -0.7530 +vn 0.0960 -0.7516 -0.6526 +vn -0.1324 -0.9449 0.2992 +vn 0.3047 -0.7913 -0.5300 +vn 0.0415 -0.9142 -0.4031 +vn 0.0327 -0.8475 -0.5297 +vn 0.0763 -0.9690 -0.2350 +vn 0.0475 -0.5405 0.8400 +vn 0.3004 -0.6686 0.6803 +vn 0.3015 -0.3376 0.8917 +vn 0.0583 -0.3078 0.9497 +vn -0.1467 -0.3457 0.9268 +vn 0.2794 0.0239 0.9599 +vn 0.0747 -0.0214 0.9970 +vn 0.0606 0.1158 0.9914 +vn 0.2658 0.2643 0.9271 +vn 0.0569 0.2727 0.9604 +vn 0.0712 0.4740 0.8776 +vn 0.0814 0.6647 0.7426 +vn 0.3273 0.5903 0.7378 +vn 0.3246 0.8596 0.3946 +vn 0.0719 0.8300 0.5532 +vn 0.0298 0.9560 0.2920 +vn 0.0765 0.9953 0.0586 +vn 0.1951 0.9790 0.0585 +vn 0.0222 0.9881 -0.1523 +vn 0.3484 0.8906 -0.2923 +vn 0.0776 0.9365 -0.3419 +vn 0.2877 0.6862 -0.6681 +vn 0.0471 0.8255 -0.5624 +vn 0.0377 0.6798 -0.7325 +vn 0.0402 0.5263 -0.8494 +vn 0.2501 0.4320 -0.8665 +vn 0.0504 0.2877 -0.9564 +vn 0.0568 0.1305 -0.9898 +vn 0.2816 0.1205 -0.9519 +vn 0.0649 0.0010 -0.9979 +vn 0.4943 -0.0595 -0.8672 +vn 0.4967 0.3449 -0.7965 +vn 0.3826 0.7525 -0.5361 +vn 0.7206 0.6612 -0.2087 +vn 0.4433 0.8959 0.0278 +vn 0.6839 0.6866 0.2467 +vn 0.3444 0.7106 0.6135 +vn 0.4380 0.3706 0.8191 +vn 0.4659 -0.1089 0.8781 +vn 0.4087 -0.5003 0.7633 +vn 0.4917 -0.7379 0.4623 +vn 0.2783 -0.8650 0.4175 +vn 0.4216 -0.9022 0.0907 +vn 0.4572 -0.8227 -0.3378 +vn 0.4463 -0.5337 -0.7183 +vn -0.8496 -0.0058 -0.5273 +vn -0.9645 0.0149 -0.2636 +vn -0.9460 0.0261 -0.3231 +vn -0.7346 -0.0422 0.6772 +vn -0.8217 -0.0405 0.5685 +vn -0.7059 -0.1679 0.6881 +vn -0.8716 -0.0195 0.4898 +vn -0.9529 -0.0255 0.3023 +vn -0.9585 -0.0017 0.2852 +vn 0.0583 -0.9982 -0.0145 +vn 0.0955 -0.9954 -0.0099 +vn 0.0670 -0.9977 -0.0096 +vn 0.0168 -0.9998 0.0056 +vn -0.5325 -0.3857 0.7535 +vn -0.5142 -0.0619 0.8554 +vn -0.9996 0.0063 -0.0283 +vn -0.9880 0.0295 -0.1516 +vn -0.9987 0.0239 -0.0455 +vn -0.9947 -0.0053 0.1029 +vn -0.0178 -0.0012 0.9998 +vn 0.1443 -0.0065 0.9895 +vn 0.3821 -0.0348 0.9234 +vn 0.3892 0.0330 0.9206 +vn 0.3737 -0.0010 0.9276 +vn 0.8020 0.0197 -0.5970 +vn 0.6369 0.0104 -0.7709 +vn 0.3699 -0.0150 -0.9290 +vn 0.4315 0.0121 -0.9020 +vn 0.2059 0.0005 -0.9786 +vn -0.1002 -0.0203 -0.9948 +vn 0.0021 0.0127 -0.9999 +vn -0.2749 0.3510 -0.8951 +vn -0.5759 -0.0165 -0.8173 +vn -0.5307 0.4393 -0.7248 +vn -0.8021 0.0133 -0.5971 +vn 0.5710 0.0012 -0.8209 +vn 0.5719 -0.0050 -0.8203 +vn 0.3850 -0.0129 -0.9228 +vn 0.1945 -0.2650 -0.9444 +vn 0.3594 0.0132 -0.9331 +vn -0.2118 0.0147 -0.9772 +vn -0.0460 -0.0174 0.9988 +vn -0.0596 0.0012 0.9982 +vn -0.1425 -0.0348 0.9892 +vn 0.0106 0.0524 0.9986 +vn -0.0007 -0.0505 0.9987 +vn -0.4169 -0.1203 0.9009 +vn -0.4214 -0.1063 0.9006 +vn -0.4324 -0.0695 0.8990 +vn -0.4497 -0.0547 0.8915 +vn -0.9179 0.0360 -0.3952 +vn -0.9169 0.0367 -0.3974 +vn -0.9178 0.0361 -0.3955 +vn -0.9168 0.0367 -0.3978 +vn 0.0197 -0.9998 0.0082 +vn 0.0164 -0.9999 0.0027 +vn 0.0140 -0.9997 0.0196 +vn -0.8993 0.0032 -0.4374 +vn -0.8599 -0.1607 -0.4845 +vn -0.9910 -0.0052 -0.1341 +vn -0.7077 -0.2201 -0.6713 +vn -0.2442 -0.2363 -0.9405 +vn 0.1953 0.9796 -0.0481 +vn 0.1164 0.9856 -0.1224 +vn 0.5047 0.4195 0.7545 +vn 0.5242 0.3960 0.7540 +vn 0.4653 0.0790 0.8816 +vn 0.2374 0.3010 0.9236 +vn 0.3112 0.4556 0.8340 +vn 0.3292 0.3022 0.8946 +vn 0.2960 0.1381 0.9451 +vn 0.1587 0.1844 0.9700 +vn 0.2958 0.6961 0.6541 +vn 0.3789 0.7552 0.5348 +vn 0.4099 0.5188 0.7502 +vn 0.4646 0.6870 0.5588 +vn 0.4254 0.2864 0.8585 +vn 0.3940 0.0935 0.9143 +vn 0.4017 0.8604 0.3136 +vn 0.3639 0.9206 0.1417 +vn 0.1893 0.9695 0.1558 +vn 0.1198 0.9497 0.2895 +vn 0.2150 0.8950 0.3907 +vn 0.1800 0.7956 0.5785 +vn 0.1405 0.3679 0.9192 +vn 0.1940 0.5445 0.8160 +vn 0.3169 0.9426 -0.1056 +vn 0.3800 0.8864 -0.2644 +vn 0.4440 0.7426 -0.5015 +vn 0.4185 0.5173 -0.7465 +vn 0.4871 0.6264 -0.6085 +vn 0.1280 0.6981 -0.7045 +vn 0.1311 0.5865 -0.7992 +vn 0.1312 0.3831 -0.9143 +vn 0.1741 0.2807 -0.9439 +vn 0.1709 0.8107 -0.5600 +vn 0.1861 0.9573 -0.2211 +vn 0.2252 0.8751 -0.4284 +vn 0.2381 0.5233 -0.8182 +vn 0.2908 0.6814 -0.6717 +vn 0.2347 0.1442 -0.9613 +vn 0.2954 0.3268 -0.8978 +vn 0.2622 0.9637 0.0504 +vn 0.2897 0.9327 0.2149 +vn 0.3232 0.8381 0.4394 +vn 0.3387 0.5801 -0.7408 +vn 0.3597 0.7714 -0.5249 +vn 0.3005 0.9175 -0.2607 +vn 0.3616 0.1345 -0.9226 +vn 0.4506 0.2327 -0.8619 +vn 0.3191 -0.2306 -0.9192 +vn 0.3339 -0.1057 -0.9367 +vn 0.2944 -0.0489 -0.9544 +vn 0.2112 -0.0463 -0.9763 +vn 0.2557 0.0394 -0.9659 +vn 0.2310 -0.1876 -0.9547 +vn 0.1456 0.0137 -0.9893 +vn 0.1683 0.1009 -0.9806 +vn 0.1349 -0.0620 -0.9889 +vn 0.1480 -0.2912 -0.9452 +vn 0.4532 -0.1245 0.8827 +vn 0.3240 0.0249 0.9457 +vn 0.3205 -0.0386 0.9465 +vn 0.2525 0.0652 0.9654 +vn 0.2399 0.0017 0.9708 +vn 0.2576 -0.0728 0.9635 +vn 0.3541 -0.1137 0.9283 +vn 0.2831 -0.2459 0.9270 +vn -0.3117 -0.5190 0.7959 +vn 0.1601 -0.1011 0.9819 +vn 0.1529 0.0038 0.9882 +vn 0.1657 0.0941 0.9817 +vn 0.1595 -0.2403 0.9575 +vn 0.4282 -0.6262 -0.6516 +vn 0.4318 -0.6900 -0.5810 +vn 0.3940 -0.3591 -0.8461 +vn 0.3885 -0.8896 -0.2404 +vn 0.3181 -0.9440 -0.0879 +vn 0.2149 -0.9765 0.0191 +vn 0.2927 -0.9305 -0.2204 +vn 0.2955 -0.8664 -0.4025 +vn 0.3844 -0.8159 -0.4319 +vn 0.3281 -0.6306 -0.7034 +vn 0.3531 -0.4950 -0.7939 +vn 0.3920 -0.8923 0.2238 +vn 0.5114 -0.6753 0.5314 +vn 0.0747 -0.8768 0.4750 +vn 0.4632 -0.7668 0.4444 +vn 0.4775 -0.5508 0.6846 +vn 0.0766 -0.7114 0.6986 +vn 0.5280 -0.3605 0.7689 +vn 0.5203 -0.4287 0.7386 +vn 0.1402 -0.4380 0.8880 +vn 0.1279 -0.8837 -0.4502 +vn 0.1262 -0.9899 -0.0651 +vn 0.1791 -0.7861 0.5916 +vn 0.2018 -0.6086 0.7674 +vn 0.1624 -0.6367 -0.7538 +vn 0.1219 -0.9902 0.0678 +vn 0.1678 -0.8980 0.4068 +vn 0.2269 -0.4013 0.8874 +vn 0.2146 -0.8326 -0.5106 +vn 0.2031 -0.9255 -0.3198 +vn 0.1772 -0.9736 -0.1436 +vn 0.1961 -0.9596 0.2017 +vn 0.2777 -0.7943 0.5404 +vn 0.3036 -0.5745 0.7601 +vn 0.2754 -0.4598 -0.8442 +vn 0.2610 -0.7377 -0.6227 +vn 0.2542 -0.9027 0.3471 +vn 0.3945 -0.6413 0.6581 +vn 0.3911 -0.3704 0.8425 +vn 0.2959 -0.9330 0.2050 +vn 0.3549 -0.8344 0.4216 +vn 0.3001 -0.9512 0.0716 +vn 0.4214 -0.0694 0.9042 +vn 0.2658 -0.1290 0.9554 +vn 0.0419 -0.0817 0.9958 +vn 0.0038 -0.0546 0.9985 +vn 0.5479 -0.1081 0.8296 +vn 0.7431 -0.0480 0.6675 +vn 0.7985 -0.0467 0.6001 +vn 0.8858 -0.1577 0.4364 +vn 0.9635 -0.0609 0.2606 +vn 0.9850 -0.0775 0.1542 +vn 0.9890 -0.0314 -0.1445 +vn 0.9910 -0.1333 0.0137 +vn 0.8988 -0.0440 -0.4361 +vn 0.8839 -0.0407 -0.4660 +vn 0.8118 0.0026 -0.5840 +vn -0.7822 -0.0031 0.6230 +vn -0.9125 0.0024 0.4091 +vn -0.9352 -0.0229 0.3533 +vn -0.7195 -0.0178 0.6942 +vn -0.5367 0.0112 0.8437 +vn -0.3769 -0.0213 0.9260 +vn -0.2032 -0.0302 0.9787 +vn 0.7993 0.0030 -0.6010 +vn 0.7057 -0.0205 -0.7082 +vn 0.6071 0.0003 -0.7946 +vn 0.4216 -0.0160 -0.9067 +vn 0.3831 -0.0040 -0.9237 +vn 0.0659 -0.0203 -0.9976 +vn 0.0801 -0.0016 -0.9968 +vn -0.3676 -0.0296 -0.9295 +vn -0.2225 -0.0039 -0.9749 +vn -0.4373 0.0082 -0.8993 +vn -0.7079 -0.0299 -0.7057 +vn -0.6211 -0.0031 -0.7837 +vn -0.8398 0.0058 -0.5429 +vn -0.9153 -0.0197 -0.4022 +vn -0.9734 0.0138 -0.2285 +vn -0.9982 -0.0227 -0.0547 +vn -0.9937 0.0058 0.1120 +vn 0.8974 0.4343 -0.0779 +vn 0.9314 -0.1579 -0.3279 +vn 0.7893 0.4502 -0.4175 +vn 0.7809 0.0251 -0.6242 +vn 0.8295 -0.0558 -0.5557 +vn 0.6738 0.1644 -0.7204 +vn 0.6070 0.1892 -0.7718 +vn 0.5887 0.3212 -0.7418 +vn 0.2638 -0.3932 -0.8808 +vn 0.2751 -0.3695 -0.8876 +vn 0.2836 -0.2105 -0.9356 +vn -0.3456 0.7668 -0.5409 +vn -0.2510 0.8392 -0.4825 +vn -0.3237 0.7661 -0.5552 +vn -0.7336 -0.3810 -0.5627 +vn -0.9413 0.2023 -0.2701 +vn -0.9328 0.2350 -0.2731 +vn -0.9198 0.2839 -0.2710 +vn -0.9167 0.2935 -0.2711 +vn 0.9758 -0.2176 0.0218 +vn 0.8605 0.4239 0.2826 +vn 0.8626 0.4196 0.2826 +vn 0.8745 0.3685 0.3154 +vn 0.8801 0.2207 0.4203 +vn 0.6311 -0.6404 0.4377 +vn 0.6166 0.4219 0.6647 +vn 0.5634 0.2501 0.7874 +vn 0.5930 -0.1155 0.7969 +vn 0.5937 -0.0592 0.8025 +vn 0.3231 0.3228 0.8896 +vn 0.3231 0.3321 0.8862 +vn 0.3178 0.1590 0.9347 +vn 0.0320 0.2953 0.9549 +vn -0.3022 -0.4043 0.8633 +vn -0.3519 0.6290 0.6932 +vn -0.5227 -0.5558 0.6465 +vn -0.6953 0.5359 0.4789 +vn -0.7446 -0.5447 0.3858 +vn -0.7930 0.5941 0.1345 +vn -0.9468 -0.3122 0.0782 +vn -0.9865 -0.1462 0.0735 +vn -0.9842 -0.1606 0.0740 +vn -0.5839 -0.8051 -0.1044 +vn -0.4376 -0.8985 0.0355 +vn -0.4507 -0.8702 -0.1989 +vn -0.4291 -0.8720 -0.2356 +vn -0.6133 -0.5905 -0.5245 +vn -0.6199 -0.5761 -0.5328 +vn -0.2321 -0.9034 -0.3606 +vn -0.3091 -0.3486 -0.8848 +vn -0.1323 -0.8127 -0.5675 +vn -0.0219 -0.8689 -0.4946 +vn -0.0952 -0.8336 -0.5441 +vn 0.0079 -0.8809 -0.4733 +vn 0.2763 -0.2692 -0.9226 +vn 0.2534 -0.4181 -0.8723 +vn 0.1858 -0.9544 -0.2337 +vn 0.7925 -0.2036 -0.5748 +vn 0.3547 -0.9159 -0.1876 +vn 0.4102 -0.8963 -0.1683 +vn 0.6088 -0.7885 -0.0876 +vn 0.3858 -0.9202 0.0660 +vn 0.6207 -0.7834 -0.0332 +vn 0.3462 -0.9347 0.0810 +vn 0.8508 0.0166 0.5253 +vn 0.5757 -0.7436 0.3400 +vn 0.6298 -0.6955 0.3458 +vn 0.3131 -0.8983 0.3081 +vn 0.3877 -0.7337 0.5580 +vn 0.2024 -0.8734 0.4430 +vn 0.1585 -0.7112 0.6849 +vn -0.0006 -0.8827 0.4699 +vn -0.1102 -0.6639 0.7397 +vn -0.1188 -0.6336 0.7645 +vn -0.1667 -0.9298 0.3281 +vn -0.1713 -0.9268 0.3343 +vn -0.3508 -0.8509 0.3910 +vn -0.3567 -0.8428 0.4032 +vn -0.3901 -0.8923 0.2272 +vn -0.5759 -0.7987 0.1746 +vn 0.0001 1.0000 0.0000 +vn 0.0002 1.0000 0.0002 +vn 0.0001 1.0000 0.0003 +vn 0.0000 1.0000 -0.0003 +vn 0.0000 1.0000 -0.0001 +vn 0.3623 0.0099 -0.9320 +vn 0.3537 0.0021 -0.9354 +vn 0.3555 0.0038 -0.9347 +vn 0.3472 -0.0037 -0.9378 +vn -0.4852 0.0179 -0.8742 +vn -0.2635 -0.0240 -0.9644 +vn -0.3004 -0.0173 -0.9536 +vn -0.5176 0.0244 -0.8553 +vn -0.5409 0.0234 -0.8408 +vn -0.2062 -0.0225 -0.9783 +vn -0.4611 -0.0065 -0.8873 +vn -0.5906 0.0250 -0.8066 +vn -0.6705 0.0022 -0.7419 +vn -0.9881 0.0053 0.1539 +vn -0.9847 0.0009 0.1744 +vn -0.9876 0.0047 0.1570 +vn -0.9841 0.0002 0.1775 +vn -0.8929 -0.0016 -0.4503 +vn -0.9021 0.0018 -0.4315 +vn -0.9011 0.0014 -0.4337 +vn -0.8917 -0.0020 -0.4526 +vn -0.0244 -0.0007 -0.9997 +vn -0.0383 -0.0123 -0.9992 +vn -0.4986 -0.8668 0.0031 +vn -0.4986 -0.8668 0.0025 +vn -0.4995 -0.8663 -0.0005 +vn -0.4997 -0.8662 -0.0002 +vn -0.4999 -0.8661 0.0001 +vn -0.4993 -0.8664 0.0037 +vn -0.4949 -0.8688 0.0182 +vn -0.2879 -0.9554 0.0660 +vn -0.2220 -0.9719 0.0777 +vn 0.0441 -0.9986 0.0290 +vn 0.0578 -0.9973 0.0454 +vn -0.3197 -0.6492 0.6902 +vn -0.3770 -0.6898 0.6181 +vn -0.6045 -0.5377 0.5877 +vn -0.3878 -0.8378 0.3844 +vn -0.7077 -0.5496 -0.4440 +vn -0.4409 -0.5944 -0.6725 +vn -0.4413 -0.8182 -0.3685 +vn 0.0747 -0.7621 -0.6432 +vn 0.2392 -0.8012 -0.5485 +vn 0.0150 0.8578 -0.5138 +vn -0.2489 0.8138 0.5251 +vn -0.3091 0.7819 0.5413 +vn 0.0416 -0.9986 0.0339 +vn 0.0971 -0.9938 0.0533 +vn 0.3030 0.6035 -0.7376 +vn 0.3418 0.6764 -0.6525 +vn 0.4769 0.6920 -0.5419 +vn 0.3499 0.8246 -0.4445 +vn 0.4708 0.8236 -0.3163 +vn -0.4154 0.8691 0.2684 +vn -0.7614 0.6211 0.1857 +vn -0.5269 0.6901 0.4961 +vn -0.5712 0.7011 -0.4268 +vn -0.5885 0.6949 -0.4133 +vn -0.1053 0.6429 -0.7587 +vn 0.1719 0.7230 -0.6691 +vn 0.0253 0.7550 -0.6552 +vn 0.1325 0.7132 -0.6883 +vn 0.2563 0.7782 -0.5733 +vn -0.6229 0.7381 -0.2592 +vn -0.3516 0.5721 -0.7410 +vn 0.4948 0.6513 -0.5753 +vn 0.3203 0.9137 -0.2499 +vn -0.5049 0.8611 -0.0595 +vn -0.7739 0.6330 -0.0225 +vn -0.7093 0.6996 0.0869 +vn 0.5058 -0.8503 0.1457 +vn 0.1748 -0.9841 0.0331 +vn 0.0176 -0.9970 -0.0747 +vn 0.6172 -0.7446 0.2541 +vn 0.8792 -0.2887 0.3790 +vn 0.8726 -0.2847 0.3968 +vn -0.0343 0.9954 0.0895 +vn 0.8914 0.1512 0.4273 +vn 0.9126 0.0517 0.4056 +vn 0.7960 0.4033 0.4513 +vn 0.4808 0.8398 0.2521 +vn 0.4817 0.8389 0.2533 +vn 0.4811 0.8395 0.2525 +vn 0.4821 0.8385 0.2539 +vn -0.5844 0.0058 0.8114 +vn -0.3987 0.1572 0.9035 +vn -0.5307 0.2554 0.8082 +vn -0.4613 0.0031 0.8872 +vn -0.3131 0.2014 0.9281 +vn -0.2549 0.0010 0.9670 +vn -0.1073 0.2166 0.9704 +vn -0.3495 -0.5974 0.7218 +vn -0.0710 -0.6612 0.7468 +vn -0.3066 -0.7605 0.5724 +vn -0.2197 -0.8489 0.4808 +vn -0.0324 -0.6248 0.7801 +vn -0.3040 0.4333 0.8484 +vn -0.1706 0.8468 0.5038 +vn -0.2052 0.8432 0.4969 +vn -0.1202 0.8377 0.5327 +vn -0.2670 -0.3332 0.9043 +vn -0.2880 -0.6678 0.6864 +vn -0.1478 -0.8324 0.5341 +vn -0.1333 0.7609 0.6350 +vn -0.4285 0.6102 0.6664 +vn -0.2767 0.5801 0.7661 +vn 0.1058 -0.5613 0.8208 +vn 0.1603 -0.1588 0.9742 +vn 0.2579 -0.6656 0.7003 +vn 0.4325 -0.2655 0.8617 +vn 0.1926 0.5337 0.8235 +vn 0.1104 0.2176 0.9698 +vn 0.3711 0.1473 0.9168 +vn 0.3972 0.0135 -0.9176 +vn 0.4008 0.0194 -0.9160 +vn 0.4029 0.0229 -0.9150 +vn 0.4067 0.0290 -0.9131 +vn 0.9755 0.0273 0.2184 +vn 0.9115 -0.0049 0.4112 +vn 0.9596 0.0125 0.2811 +vn 0.9823 0.0310 0.1849 +vn 0.9862 0.0253 0.1638 +vn 0.8591 0.0146 -0.5116 +vn 0.8509 0.0094 -0.5253 +vn 0.8571 0.0132 -0.5151 +vn 0.8489 0.0081 -0.5285 +vn 0.9007 0.0000 0.4345 +vn 0.9061 0.0085 0.4230 +vn 0.8299 0.0207 0.5575 +vn 0.7733 -0.0119 0.6339 +vn 0.6059 0.0041 0.7955 +vn 0.5539 -0.0241 0.8322 +vn 0.4897 0.0272 0.8715 +vn 0.3759 0.0309 0.9261 +vn 0.1215 -0.0214 0.9924 +vn 0.2899 0.0164 0.9569 +vn 0.4223 0.0418 0.9055 +vn 0.4081 0.0457 0.9118 +vn -0.4487 0.0249 0.8933 +vn -0.4603 0.0170 0.8876 +vn -0.4535 0.0217 0.8910 +vn -0.4422 0.0293 0.8965 +vn -0.8708 0.0158 -0.4914 +vn -0.9421 -0.2091 -0.2623 +vn -0.9908 -0.0723 -0.1142 +vn -0.9171 0.0570 0.3947 +vn -0.8827 0.0333 0.4687 +vn -0.9095 0.0514 0.4125 +vn -0.8695 0.0251 0.4933 +vn -0.9934 0.0119 -0.1137 +vn -0.9944 0.0184 -0.1041 +vn -0.9719 0.0180 -0.2347 +vn -0.9661 0.0086 -0.2581 +vn -0.8849 0.0168 -0.4655 +vn -0.8749 0.0130 -0.4841 +vn -0.5063 0.0514 -0.8608 +vn -0.2418 -0.0209 -0.9701 +vn -0.5452 -0.0023 -0.8383 +vn -0.6091 0.0540 -0.7913 +vn -0.7840 -0.0095 -0.6207 +vn -0.3169 0.9103 -0.2664 +vn -0.8937 -0.4275 -0.1363 +vn 0.6913 -0.6900 0.2146 +vn 0.1439 -0.7568 0.6376 +vn 0.4882 0.8441 0.2215 +vn 0.8757 0.1711 0.4516 +vn 0.4089 0.8319 0.3753 +vn 0.5577 0.2782 0.7820 +vn 0.3172 0.1489 0.9366 +vn -0.0100 0.7538 0.6570 +vn -0.1053 0.0100 0.9944 +vn -0.1455 0.8961 0.4193 +vn -0.5094 0.0388 0.8597 +vn -0.3033 0.8758 0.3755 +vn -0.8266 -0.0239 0.5623 +vn -0.3870 0.9000 0.2007 +vn -0.9440 -0.3205 0.0784 +vn -0.9254 0.2604 -0.2755 +vn -0.4704 0.8367 -0.2804 +vn -0.6933 -0.1209 -0.7105 +vn -0.3295 0.7926 -0.5130 +vn -0.2646 0.1280 -0.9558 +vn -0.2623 0.1430 -0.9543 +vn -0.0391 0.6044 -0.7958 +vn -0.1558 0.4920 -0.8565 +vn 0.0082 0.6551 -0.7555 +vn 0.1786 0.0227 -0.9837 +vn 0.2073 0.8605 -0.4653 +vn 0.5606 0.4455 -0.6980 +vn 0.2149 0.9334 -0.2874 +vn -0.3477 0.6103 -0.7118 +vn -0.5112 -0.8240 -0.2443 +vn -0.5961 -0.7956 -0.1081 +vn -0.5646 -0.8093 -0.1620 +vn -0.6424 -0.7662 -0.0189 +vn -0.0003 1.0000 0.0004 +vn -0.0021 -0.9934 0.1147 +vn -0.4058 -0.0678 0.9115 +vn -0.4071 -0.0663 0.9110 +vn 0.0600 0.0094 -0.9982 +vn 0.1255 0.0488 -0.9909 +vn -0.1209 0.0136 -0.9926 +vn 0.8566 0.0085 -0.5159 +vn 0.7900 -0.0025 -0.6132 +vn 0.7689 0.0058 -0.6394 +vn 0.5870 -0.0162 -0.8094 +vn 0.5918 0.0092 -0.8060 +vn 0.6545 0.0073 -0.7560 +vn 0.2895 -0.0141 -0.9571 +vn -0.1001 -0.0056 -0.9950 +vn 0.2018 -0.0046 -0.9794 +vn -0.8419 0.0187 0.5393 +vn -0.6430 -0.0145 0.7657 +vn -0.5663 0.0131 0.8241 +vn -0.9870 0.0191 0.1595 +vn -0.9996 -0.0152 0.0223 +vn -0.9213 -0.0201 0.3882 +vn -0.9518 0.0210 -0.3059 +vn -0.9166 -0.0140 -0.3996 +vn -0.6791 0.0080 -0.7340 +vn -0.6333 -0.0137 -0.7738 +vn -0.2621 -0.0084 -0.9650 +vn -0.2695 0.0038 -0.9630 +vn 0.1112 0.0037 -0.9938 +vn 0.2125 -0.0186 -0.9770 +vn 0.5035 0.0135 -0.8639 +vn 0.5573 -0.0034 -0.8303 +vn 0.7726 0.0091 -0.6348 +vn 0.7120 0.0054 -0.7021 +vn 0.7947 -0.0040 -0.6069 +vn 0.8415 0.0019 -0.5402 +vn -0.4990 -0.0050 0.8666 +vn -0.1646 -0.0085 0.9863 +vn -0.5580 0.0096 0.8298 +vn -0.1912 0.0055 0.9815 +vn -0.3986 -0.0210 0.9169 +vn -0.3965 -0.0556 0.9164 +vn -0.4022 -0.0118 0.9155 +vn -0.6701 0.0028 0.7422 +vn -0.8759 0.0101 0.4823 +vn -0.6378 -0.0069 0.7702 +vn -0.7148 0.0072 0.6993 +vn -0.8595 0.0082 0.5111 +vn -0.9880 0.0484 0.1464 +vn -0.9934 0.0148 -0.1138 +vn -0.8512 0.0328 0.5239 +vn -0.9901 0.0695 -0.1217 +vn -0.9369 0.0084 -0.3495 +vn -0.7901 0.0223 -0.6126 +vn -0.8393 0.0052 -0.5437 +vn -0.3393 0.0136 -0.9406 +vn -0.5855 0.0153 -0.8105 +vn -0.5713 0.0120 -0.8206 +vn -0.0670 0.0217 -0.9975 +vn 0.0001 -1.0000 0.0001 +vn -0.0003 -1.0000 0.0028 +vn -0.0011 -0.9999 0.0112 +vn 0.0023 -1.0000 -0.0013 +vn 0.0038 -1.0000 0.0013 +vn 0.0000 -1.0000 -0.0005 +vn -0.0000 -1.0000 -0.0003 +vn -0.0002 -1.0000 -0.0005 +vn -0.0015 -1.0000 -0.0005 +vn -0.0000 -1.0000 0.0001 +vn 0.0014 -1.0000 0.0002 +vn 0.1826 0.0219 -0.9829 +vn 0.6461 0.0151 -0.7631 +vn 0.6264 -0.0160 -0.7793 +vn 0.4270 0.0107 -0.9042 +vn 0.8162 0.0138 -0.5776 +vn 0.9000 -0.0114 -0.4356 +vn 0.9651 0.0209 -0.2609 +vn 0.8165 0.0069 0.5773 +vn 0.9574 -0.0041 0.2888 +vn 0.9246 0.0105 0.3808 +vn 0.9942 0.0201 0.1058 +vn 0.9971 -0.0080 -0.0754 +vn 0.7806 -0.0062 0.6249 +vn 0.6086 0.0091 0.7934 +vn 0.4931 -0.0103 0.8699 +vn 0.3860 0.0061 0.9225 +vn 0.1219 -0.0037 0.9925 +vn 0.1493 0.0135 0.9887 +vn -0.1894 0.0176 0.9817 +vn -0.2790 -0.0059 0.9603 +vn -0.5622 0.0194 0.8268 +vn -0.6299 -0.0026 0.7766 +vn -0.8488 -0.0020 0.5287 +vn 0.0003 -1.0000 0.0024 +vn -0.0032 -1.0000 0.0075 +vn -0.0025 -1.0000 -0.0024 +vn 0.0002 -1.0000 0.0010 +vn -0.0030 -1.0000 -0.0016 +vn 0.0003 -1.0000 -0.0004 +vn 0.0005 -1.0000 -0.0019 +vn 0.0001 -1.0000 -0.0072 +vn 0.0006 -1.0000 0.0000 +vn -0.0001 -1.0000 0.0016 +vn 0.0003 -1.0000 -0.0023 +vn 0.0004 -1.0000 0.0004 +vn -0.0001 -1.0000 0.0015 +vn -0.0057 -1.0000 -0.0032 +vn 0.0001 -1.0000 -0.0008 +vn 0.0001 -1.0000 -0.0010 +vn 0.0004 -1.0000 0.0000 +vn -0.0007 -1.0000 0.0002 +vn 0.0000 -1.0000 0.0004 +vn 0.0001 -1.0000 -0.0000 +vn -0.0001 -1.0000 -0.0011 +vn 0.0004 -0.9999 -0.0164 +vn -0.0719 -0.9966 -0.0408 +vn -0.0093 -0.9999 -0.0053 +vn -0.0038 -1.0000 -0.0021 +vn -0.0010 -1.0000 -0.0019 +vn -0.0032 -1.0000 -0.0010 +vn 0.0006 -1.0000 0.0004 +vn 0.0005 -1.0000 -0.0001 +vn 0.0000 -1.0000 -0.0001 +vn -0.0008 -1.0000 0.0006 +vn 0.0010 0.9999 -0.0157 +vn 0.0020 1.0000 0.0010 +vn 0.0021 0.9999 -0.0115 +vn 0.0152 0.9998 0.0104 +vn -0.0029 1.0000 0.0002 +vn 0.0026 0.9991 0.0421 +vn -0.0031 1.0000 -0.0048 +vn 0.0126 0.9997 0.0221 +vn 0.0005 1.0000 -0.0044 +vn -0.0029 1.0000 0.0029 +vn -0.0009 1.0000 0.0068 +vn -0.8963 -0.0292 -0.4424 +vn -0.9991 -0.0100 -0.0404 +vn -0.9916 -0.0143 -0.1283 +vn -0.9523 -0.0394 -0.3027 +vn -0.8805 -0.0941 -0.4645 +vn -0.7997 -0.1286 -0.5864 +vn -0.3227 -0.0858 -0.9426 +vn -0.7079 -0.0765 -0.7021 +vn -0.5742 -0.0007 -0.8187 +vn -0.4192 0.0441 -0.9068 +vn -0.2509 0.0554 -0.9664 +vn -0.0740 0.0331 -0.9967 +vn 0.1275 -0.0307 -0.9914 +vn 0.3202 -0.0354 -0.9467 +vn 0.6087 -0.0575 -0.7913 +vn 0.5479 0.0145 -0.8364 +vn 0.6968 0.0106 -0.7172 +vn 0.8290 -0.0422 -0.5577 +vn 0.9992 -0.0395 -0.0014 +vn 0.9178 -0.0393 -0.3952 +vn 0.9885 0.0424 -0.1454 +vn 0.9974 0.0557 0.0451 +vn 0.9745 0.0336 0.2220 +vn 0.9200 -0.0214 0.3913 +vn 0.8592 -0.0258 0.5110 +vn 0.9779 -0.0023 0.2089 +vn 0.8029 0.0088 0.5961 +vn 0.7964 0.0160 0.6046 +vn 0.9783 -0.0112 0.2067 +vn 0.9405 -0.0019 0.3397 +vn 0.9662 -0.0286 0.2561 +vn 0.9051 0.0152 0.4249 +vn 0.8135 0.0264 0.5810 +vn 0.7516 0.0207 0.6593 +vn 0.7431 0.0182 0.6689 +vn 0.5584 -0.0490 0.8281 +vn 0.6400 -0.0111 0.7683 +vn 0.5668 -0.0289 0.8233 +vn 0.1919 -0.0471 0.9803 +vn 0.4349 -0.0142 0.9003 +vn 0.2649 0.0141 0.9642 +vn 0.1783 0.0195 0.9838 +vn 0.0883 0.0093 0.9961 +vn -0.1006 -0.0401 0.9941 +vn -0.6230 -0.0503 0.7806 +vn -0.2577 -0.0370 0.9655 +vn -0.5555 0.0394 0.8306 +vn -0.8560 -0.0151 0.5167 +vn -0.9972 -0.0403 -0.0631 +vn -0.9867 0.0038 0.1627 +vn -0.9783 0.0410 -0.2030 +vn -0.9227 -0.0002 -0.3856 +vn -0.8668 -0.0151 -0.4985 +vn -0.9931 -0.0007 -0.1173 +vn 0.7650 0.0301 0.6434 +vn 0.8665 -0.0130 0.4990 +vn 0.7858 -0.0300 0.6177 +vn 0.8680 0.0303 0.4957 +vn 0.6995 0.0063 0.7146 +vn 0.5424 -0.0764 0.8367 +vn -0.1504 -0.0909 0.9844 +vn 0.4519 -0.1109 0.8851 +vn 0.2901 -0.0191 0.9568 +vn 0.1158 0.0428 0.9924 +vn -0.0634 0.0714 0.9954 +vn -0.3231 0.0553 0.9448 +vn -0.6923 -0.0585 0.7192 +vn -0.7930 -0.1048 0.6002 +vn -0.9165 0.0214 0.3995 +vn -0.9726 0.0664 0.2227 +vn -0.9422 -0.0294 -0.3338 +vn -0.9956 0.0769 0.0542 +vn -0.9971 0.0661 -0.0374 +vn -0.9761 0.0263 -0.2157 +vn -0.9216 -0.0461 -0.3855 +vn -0.8711 -0.0328 -0.4901 +vn -0.8931 -0.0430 -0.4478 +vn -0.8364 0.0142 -0.5480 +vn 0.0368 0.0264 -0.9990 +vn -0.1313 -0.0074 -0.9913 +vn -0.2952 -0.0268 -0.9550 +vn -0.4514 -0.0314 -0.8917 +vn -0.5940 -0.0211 -0.8042 +vn -0.7191 0.0037 -0.6949 +vn -0.8346 0.0716 -0.5462 +vn -0.8897 0.1019 -0.4449 +vn -0.9548 0.0492 -0.2932 +vn -0.9913 0.0083 -0.1311 +vn 0.5856 0.0003 -0.8106 +vn 0.7263 -0.0223 -0.6870 +vn 0.8322 -0.0269 -0.5538 +vn 0.9138 -0.0170 -0.4059 +vn 0.9682 0.0074 -0.2501 +vn 0.9950 0.0224 -0.0973 +vn 0.9969 0.0057 0.0780 +vn 0.9490 -0.0103 0.3152 +vn 0.8505 -0.0006 0.5259 +vn -0.6963 -0.0086 0.7177 +vn -0.8112 -0.0054 0.5848 +vn -0.9042 0.0245 0.4265 +vn -0.9551 0.0324 0.2944 +vn -0.9924 -0.0031 0.1232 +vn -0.9984 -0.0233 -0.0522 +vn -0.9738 -0.0273 -0.2260 +vn -0.8928 -0.0080 -0.4503 +vn 0.2382 -0.0113 0.9712 +vn 0.4410 0.0254 0.8972 +vn 0.5674 0.0258 0.8231 +vn 0.7019 -0.0029 0.7123 +vn 0.8290 -0.0164 0.5590 +vn 0.9487 0.0008 0.3161 +vn 0.4028 0.0828 0.9115 +vn 0.6414 -0.0165 0.7670 +vn -0.8718 -0.0050 -0.4899 +vn -0.9499 0.0304 0.3109 +vn -0.9934 -0.0298 0.1112 +vn -0.9415 -0.0034 0.3371 +vn -0.8022 -0.0043 0.5970 +vn -0.6779 -0.0154 0.7349 +vn 0.7673 0.0285 -0.6407 +vn 0.8136 0.0017 -0.5814 +vn 0.6624 -0.0172 -0.7490 +vn 0.7018 0.0182 -0.7122 +vn 0.4443 -0.0558 -0.8941 +vn -0.2494 0.0258 -0.9680 +vn -0.2834 0.0059 -0.9590 +vn -0.2673 0.0153 -0.9635 +vn -0.3034 -0.0060 -0.9528 +vn -0.9432 -0.0013 -0.3321 +vn -0.9057 0.0109 -0.4237 +vn -0.9416 -0.0053 -0.3368 +vn -0.8910 0.0066 -0.4539 +vn -0.8415 0.0173 -0.5400 +vn -0.8341 0.0038 -0.5516 +vn -0.9648 0.0050 0.2630 +vn -0.9585 -0.0053 0.2850 +vn -0.9777 0.0127 0.2097 +vn -0.9823 -0.0086 0.1873 +vn -0.9943 0.0050 0.1066 +vn -0.9840 0.0363 0.1742 +vn -0.5358 0.0144 0.8442 +vn -0.5597 -0.0071 0.8286 +vn -0.5405 0.0102 0.8413 +vn -0.5172 0.0306 0.8553 +vn 0.3909 0.0350 0.9198 +vn 0.1197 -0.0640 0.9907 +vn 0.2210 -0.0281 0.9749 +vn 0.4837 0.0713 0.8723 +vn 0.9407 -0.0266 0.3381 +vn 0.8643 -0.0023 0.5030 +vn 0.9423 -0.0221 0.3341 +vn 0.8549 0.0040 0.5188 +vn 0.7434 0.0232 0.6684 +vn 0.7453 0.0265 0.6662 +vn 0.9706 0.0433 -0.2369 +vn 0.9876 -0.0623 0.1439 +vn 0.9452 -0.0346 -0.3247 +vn 0.8986 0.0494 -0.4360 +vn 0.7005 -0.0421 -0.7124 +vn 0.2484 0.0231 -0.9684 +vn 0.2099 0.0078 -0.9777 +vn 0.2358 0.0181 -0.9716 +vn 0.1941 0.0016 -0.9810 +vn 0.2430 0.9288 0.2798 +vn -0.0178 0.9221 -0.3866 +vn 0.0007 1.0000 -0.0067 +vn 0.0008 1.0000 0.0038 +vn 0.0013 1.0000 0.0009 +vn 0.0010 1.0000 -0.0014 +vn 0.0009 1.0000 0.0051 +vn 0.0001 1.0000 -0.0010 +vn 0.0003 1.0000 0.0046 +vn -0.0000 1.0000 0.0034 +vn -0.8291 -0.0747 -0.5541 +vn -0.8252 -0.0591 -0.5618 +vn -0.9205 -0.0904 -0.3802 +vn -0.8339 -0.0447 -0.5501 +vn -0.9207 -0.1555 -0.3579 +vn -0.9953 0.0401 -0.0879 +vn -0.9897 -0.0137 -0.1424 +vn -0.9606 0.2276 0.1595 +vn -0.9636 0.2073 0.1689 +vn -0.9692 0.1518 0.1937 +vn -0.9713 0.0851 0.2223 +vn -0.1298 0.1162 0.9847 +vn -0.1524 0.0391 0.9875 +vn -0.1076 0.1884 0.9762 +vn -0.1024 0.2051 0.9734 +vn 0.4284 0.0557 0.9019 +vn 0.3762 -0.0151 0.9264 +vn 0.4056 0.2007 0.8917 +vn 0.3085 0.4084 0.8591 +vn 0.8429 0.1126 0.5262 +vn 0.7905 -0.0371 0.6113 +vn 0.7609 -0.0997 0.6412 +vn 0.8542 0.1612 0.4944 +vn -0.8444 -0.2899 0.4505 +vn -0.7412 0.0227 0.6709 +vn -0.8173 -0.0755 0.5713 +vn -0.8434 -0.1166 0.5245 +vn -0.8658 -0.2755 0.4177 +vn 0.9478 -0.1353 0.2886 +vn 0.8914 -0.0720 0.4475 +vn 0.7667 -0.2655 0.5845 +vn 0.8090 -0.0707 0.5835 +vn 0.6483 -0.1747 0.7411 +vn 0.5122 -0.4560 0.7278 +vn 0.1900 0.0549 0.9803 +vn 0.3521 -0.0109 0.9359 +vn 0.2712 0.0224 0.9623 +vn 0.1335 0.0768 0.9881 +vn -0.1568 -0.2774 0.9479 +vn 0.2481 0.4993 0.8301 +vn 0.2269 0.3825 0.8956 +vn 0.1766 0.0839 0.9807 +vn 0.3285 0.2971 0.8965 +vn 0.2931 0.4125 0.8625 +vn 0.6758 -0.1686 0.7175 +vn 0.5476 -0.1771 0.8178 +vn 0.6558 -0.2028 0.7271 +vn 0.7386 -0.1978 0.6445 +vn 0.8309 -0.1032 0.5467 +vn 0.8810 -0.1333 0.4539 +vn 0.9094 -0.1348 0.3934 +vn 0.9658 -0.1000 0.2393 +vn -0.8425 -0.2204 0.4916 +vn -0.6385 -0.2256 0.7358 +vn -0.6690 -0.1764 0.7220 +vn -0.7997 -0.1127 0.5897 +vn -0.8962 -0.1222 0.4265 +vn -0.9466 -0.2042 0.2496 +vn -0.9522 -0.2087 0.2232 +vn -0.9643 -0.2564 0.0656 +vn -0.9843 -0.0773 -0.1589 +vn -0.8999 -0.2208 -0.3761 +vn -0.9196 0.2571 -0.2971 +vn -0.6198 -0.3466 0.7040 +vn -0.5808 -0.4204 0.6971 +vn 0.0248 0.0977 -0.9949 +vn 0.7772 0.0383 -0.6280 +vn 0.7678 -0.0314 -0.6399 +vn 0.6341 -0.4047 -0.6589 +vn 0.9233 0.1071 -0.3689 +vn 0.9777 0.1143 0.1761 +vn 0.7365 0.3234 0.5942 +vn 0.6247 -0.3219 0.7114 +vn 0.3651 -0.7840 0.5020 +vn 0.5569 -0.6656 0.4968 +vn 0.5035 0.3222 0.8017 +vn -0.0923 0.4590 0.8836 +vn -0.1088 0.3438 0.9327 +vn -0.0711 0.5851 0.8078 +vn -0.0697 0.5925 0.8025 +vn -0.4409 0.4129 0.7970 +vn -0.8968 0.1320 0.4222 +vn -0.1071 -0.3857 -0.9164 +vn 0.1276 -0.1546 -0.9797 +vn 0.1490 -0.2893 -0.9456 +vn -0.9316 0.3627 -0.0236 +vn -0.9732 0.2297 0.0071 +vn -0.9088 0.4156 -0.0361 +vn -0.9297 -0.3148 -0.1913 +vn -0.9162 -0.1945 -0.3503 +vn -0.8932 -0.1762 -0.4138 +vn -0.8930 -0.3134 -0.3229 +vn -0.8085 -0.1534 -0.5681 +vn -0.6922 -0.1774 -0.6995 +vn -0.6409 -0.1939 -0.7427 +vn -0.9447 0.1049 -0.3106 +vn -0.4538 -0.2426 -0.8574 +vn -0.3173 -0.0977 -0.9433 +vn -0.1383 -0.0502 -0.9891 +vn 0.0486 -0.1048 -0.9933 +vn 0.7977 0.1606 0.5812 +vn 0.7959 0.2158 0.5656 +vn 0.7956 0.2224 0.5636 +vn 0.9561 0.0014 0.2931 +vn 0.9447 0.0267 0.3269 +vn 0.8873 0.2408 0.3934 +vn 0.9404 0.0238 0.3393 +vn 0.9884 -0.0761 -0.1317 +vn 0.9846 -0.1699 -0.0407 +vn 0.9803 -0.0064 -0.1973 +vn 0.9665 0.0525 -0.2512 +vn 0.7751 0.2324 -0.5876 +vn 0.7730 0.2090 -0.5990 +vn 0.5405 -0.1893 -0.8197 +vn 0.7296 0.0186 -0.6836 +vn 0.5502 -0.2236 -0.8045 +vn 0.4108 -0.2960 -0.8623 +vn 0.1151 0.1312 -0.9847 +vn 0.1248 0.1900 -0.9738 +vn -0.0358 -0.0479 -0.9982 +vn -0.0436 -0.0816 -0.9957 +vn -0.3339 0.3262 -0.8844 +vn -0.6898 -0.1317 -0.7119 +vn -0.3104 0.3711 -0.8752 +vn -0.4593 -0.2084 -0.8635 +vn -0.1661 -0.1982 -0.9660 +vn -0.5153 -0.1048 -0.8506 +vn -0.6751 -0.2577 -0.6912 +vn -0.8609 0.3047 -0.4074 +vn -0.8358 -0.0270 -0.5484 +vn -0.8837 0.2704 -0.3820 +vn -0.9121 0.1839 -0.3663 +vn -0.9771 0.2127 0.0109 +vn 0.7601 -0.3091 -0.5715 +vn 0.5482 -0.1019 -0.8301 +vn 0.5768 -0.1358 -0.8055 +vn 0.7271 -0.1049 -0.6785 +vn 0.8324 -0.1541 -0.5323 +vn 0.9644 -0.1857 -0.1881 +vn 0.8879 0.0525 -0.4571 +vn 0.9762 0.2079 -0.0624 +vn 0.9867 -0.1125 0.1177 +vn 0.8398 -0.3966 0.3708 +vn 0.7974 0.1211 0.5912 +vn 0.6072 -0.2957 -0.7375 +vn 0.7606 -0.0883 -0.6432 +vn -0.4443 -0.5330 0.7201 +vn -0.5011 -0.1978 0.8425 +vn -0.6237 -0.5463 0.5591 +vn -0.8477 0.4635 -0.2580 +vn -0.6702 0.4505 -0.5898 +vn -0.5084 0.0235 -0.8608 +vn -0.4445 -0.5178 -0.7310 +vn -0.5971 -0.3169 -0.7369 +vn 0.4736 -0.4062 -0.7815 +vn 0.4704 -0.6290 -0.6189 +vn 0.4119 -0.4020 -0.8177 +vn 0.6938 -0.1487 -0.7046 +vn 0.7148 -0.1270 -0.6877 +vn 0.7628 -0.1554 -0.6277 +vn 0.8054 -0.2369 -0.5433 +vn 0.7806 -0.3914 -0.4872 +vn -0.3526 0.3683 0.8603 +vn -0.2346 0.2249 -0.9457 +vn -0.0202 0.9998 -0.0018 +vn -0.0141 0.9999 -0.0029 +vn -0.0162 0.9999 0.0033 +vn -0.0191 0.9998 0.0116 +vn -0.0221 0.9997 -0.0103 +vn -0.0232 0.9995 -0.0196 +vn -0.0069 0.9997 -0.0251 +vn 0.4420 0.0476 0.8958 +vn -0.3236 0.7390 -0.5909 +vn -0.0015 1.0000 -0.0002 +vn -0.0071 1.0000 0.0034 +vn -0.0146 0.9995 -0.0283 +vn -0.0100 0.9999 0.0078 +vn -0.1665 0.8801 -0.4447 +vn 0.2884 0.4383 0.8513 +vn 0.0031 1.0000 -0.0077 +vn -0.0275 0.9995 0.0121 +vn -0.0002 1.0000 0.0004 +vn 0.0638 0.9846 -0.1630 +vn -0.0063 1.0000 0.0044 +vn 0.0324 0.9993 -0.0196 +vn -0.2584 0.9371 0.2346 +vn -0.0009 1.0000 0.0035 +vn -0.0248 0.9997 -0.0021 +vn 0.0107 0.9999 0.0041 +vn 0.0261 0.9997 -0.0024 +vn 0.0066 0.9999 0.0143 +vn 0.0414 0.9979 -0.0496 +vn 0.0193 0.9994 -0.0285 +vn -0.0018 1.0000 0.0014 +vn -0.0077 1.0000 -0.0020 +vn -0.1076 0.9939 -0.0225 +vn 0.0027 0.9999 -0.0129 +vn -0.0017 1.0000 0.0085 +vn 0.0001 0.9998 0.0175 +vn 0.0024 1.0000 -0.0096 +vn 0.0069 0.9998 -0.0166 +vn -0.0036 0.9996 0.0271 +vn -0.0008 1.0000 0.0003 +vn 0.0020 1.0000 -0.0012 +vn -0.0370 0.9988 0.0319 +vn -0.0014 0.9999 0.0121 +vn -0.0050 1.0000 0.0045 +vn 0.0523 0.9984 0.0194 +vn -0.1313 0.9904 0.0426 +vn -0.1506 0.9874 0.0484 +vn 0.3390 0.9240 -0.1771 +vn 0.0355 0.9992 -0.0165 +vn -0.0919 0.9905 0.1019 +vn -0.0162 0.9998 -0.0063 +vn -0.0009 1.0000 -0.0006 +vn 0.0156 0.9992 -0.0369 +vn 0.3242 0.4612 -0.8259 +vn -0.0141 0.9989 0.0440 +vn -0.0681 0.9969 0.0403 +vn -0.0014 0.9992 0.0389 +vn 0.0289 0.9995 -0.0129 +vn -0.0152 0.9998 0.0106 +vn -0.3975 0.0840 -0.9138 +vn 0.3386 0.6107 0.7158 +vn -0.0005 1.0000 -0.0005 +vn 0.0150 0.9999 -0.0082 +vn -0.0015 1.0000 0.0001 +vn 0.4924 0.8658 -0.0889 +vn -0.1372 0.9886 0.0620 +vn -0.2681 0.9557 0.1212 +vn -0.2318 0.9671 0.1048 +vn 0.8309 -0.0430 -0.5547 +vn -0.3460 0.8569 0.3822 +vn -0.4888 0.7535 0.4396 +vn -0.3684 0.8431 0.3917 +vn -0.5988 0.6432 0.4772 +vn -0.0383 0.9979 0.0516 +vn -0.0044 0.9999 0.0125 +vn -0.0001 1.0000 -0.0055 +vn 0.0056 0.9996 0.0277 +vn -0.0030 0.9999 -0.0129 +vn -0.0382 0.9891 -0.1420 +vn -0.0963 0.9287 -0.3580 +vn 0.0598 0.9866 0.1518 +vn 0.0889 0.9701 0.2259 +vn 0.0390 0.9943 0.0990 +vn -0.0100 0.9999 -0.0031 +vn 0.0157 0.9997 -0.0180 +vn 0.0005 0.2728 -0.9621 +vn 0.0645 0.9978 0.0158 +vn 0.0614 0.9981 0.0024 +vn -0.0031 0.9935 0.1135 +vn -0.0071 0.9917 0.1281 +vn -0.1333 0.9393 0.3160 +vn -0.0719 0.8014 -0.5938 +vn 0.0844 0.9954 0.0460 +vn 0.0753 0.9967 0.0302 +vn 0.0845 0.9952 0.0485 +vn 0.1207 0.9873 0.1031 +vn 0.1256 0.9859 0.1103 +vn 0.4668 0.6701 0.5772 +vn 0.0086 0.9999 -0.0089 +vn 0.0436 0.9962 0.0758 +vn 0.0406 0.9981 0.0470 +vn 0.0442 0.9980 0.0440 +vn 0.0004 0.9965 0.0837 +vn 0.0165 0.9955 0.0936 +vn -0.0246 0.9975 0.0657 +vn 0.0015 0.9985 0.0552 +vn -0.1056 0.9926 0.0608 +vn 0.8468 0.3517 -0.3991 +vn -0.0099 0.9999 0.0062 +vn 0.0352 0.9922 0.1199 +vn 0.0517 0.9980 0.0365 +vn 0.0573 0.9980 0.0274 +vn 0.0337 0.9892 0.1429 +vn 0.0115 0.9699 0.2431 +vn -0.0139 0.9926 0.1209 +vn 0.0010 0.9940 0.1097 +vn -0.0024 0.9998 -0.0196 +vn -0.0111 0.9854 -0.1699 +vn -0.0231 0.9997 -0.0125 +vn -0.0010 0.9985 -0.0549 +vn 0.0506 0.9977 0.0443 +vn 0.0041 1.0000 -0.0037 +vn 0.0082 0.9993 0.0366 +vn -0.0921 0.9927 0.0774 +vn -0.0145 0.9999 -0.0068 +vn -0.0472 0.9989 0.0057 +vn -0.0220 0.9995 -0.0219 +vn -0.0100 0.9969 -0.0777 +vn 0.0001 1.0000 0.0060 +vn 0.0113 0.9999 -0.0108 +vn 0.0102 0.9999 -0.0058 +vn -0.0013 0.9999 0.0117 +vn 0.0100 0.9998 0.0158 +vn 0.1711 0.9195 0.3540 +vn 0.0034 0.9999 0.0112 +vn -0.0103 0.9999 -0.0037 +vn -0.0173 0.9998 -0.0040 +vn 0.0188 0.9992 -0.0361 +vn -0.0002 0.9998 0.0202 +vn -0.0026 1.0000 0.0005 +vn -0.0076 0.9993 -0.0379 +vn 0.0636 0.6757 -0.7344 +vn 0.0278 0.9974 -0.0660 +vn 0.0295 0.9977 -0.0612 +vn -0.0076 1.0000 -0.0035 +vn -0.0031 0.9999 -0.0116 +vn 0.0485 0.9968 -0.0637 +vn 0.0463 0.9986 -0.0267 +vn 0.9217 0.1946 -0.3355 +vn -0.0193 0.9998 0.0069 +vn 0.0971 0.9948 -0.0320 +vn 0.1272 0.9855 -0.1123 +vn 0.1113 0.9933 -0.0322 +vn 0.1032 0.9933 -0.0515 +vn 0.0898 0.9938 -0.0662 +vn 0.0849 0.9931 -0.0805 +vn 0.0866 0.9917 -0.0954 +vn -0.9557 0.1021 0.2759 +vn -0.9339 0.1534 0.3229 +vn -0.9199 0.1810 0.3478 +vn 0.5786 0.7024 -0.4145 +vn 0.0432 0.9974 0.0575 +vn 0.0596 0.9981 0.0151 +vn 0.0181 0.9982 0.0566 +vn 0.0021 1.0000 0.0077 +vn 0.0068 0.9997 0.0224 +vn -0.0260 0.9953 -0.0930 +vn 0.2839 0.4715 0.8349 +vn -0.0324 0.9985 -0.0450 +vn -0.0315 0.9952 0.0929 +vn -0.0884 0.9912 0.0981 +vn 0.0166 0.5275 -0.8494 +vn 0.1165 0.9931 0.0085 +vn 0.1030 0.9945 0.0179 +vn 0.0818 0.9960 0.0349 +vn 0.0950 0.9949 -0.0340 +vn -0.0557 0.9949 -0.0837 +vn 0.1465 -0.7830 0.6046 +vn -0.0590 0.9757 -0.2112 +vn -0.0426 0.9875 -0.1518 +vn -0.8325 -0.0924 0.5462 +vn -0.3866 0.9025 0.1900 +vn -0.1942 0.9763 0.0954 +vn 0.0354 0.9990 -0.0275 +vn 0.1115 0.9928 -0.0431 +vn 0.1666 0.9839 -0.0645 +vn -0.0063 0.9998 -0.0166 +vn 0.1806 0.9778 -0.1062 +vn 0.2902 0.9416 -0.1707 +vn -0.2087 0.8797 0.4274 +vn 0.0906 0.9653 -0.2448 +vn 0.4022 0.6237 0.6703 +vn -0.1126 0.9857 -0.1256 +vn -0.0676 0.9949 -0.0746 +vn -0.1546 0.6167 0.7719 +vn 0.1148 0.4408 -0.8902 +vn -0.0164 0.9920 0.1254 +vn -0.0071 0.9999 -0.0117 +vn -0.0008 1.0000 -0.0003 +vn 0.0039 0.9911 -0.1333 +vn -0.5099 0.2905 0.8097 +vn -0.5272 0.2679 0.8064 +vn -0.5133 0.2861 0.8091 +vn 0.3255 0.7274 -0.6042 +vn -0.2225 0.1186 0.9677 +vn -0.0274 0.9992 -0.0307 +vn -0.0396 0.9980 -0.0494 +vn -0.0367 0.9983 -0.0453 +vn -0.0110 0.9999 -0.0061 +vn -0.0213 0.9995 -0.0254 +vn 0.6630 -0.3462 0.6637 +vn -0.6327 0.6319 -0.4477 +vn -0.0063 0.9996 0.0286 +vn -0.0294 0.9969 0.0736 +vn -0.0729 0.9961 0.0492 +vn 0.1939 -0.9513 0.2398 +vn -0.0249 0.9995 0.0171 +vn 0.0518 0.9952 -0.0834 +vn -0.0139 0.9999 0.0017 +vn 0.5960 -0.4767 -0.6462 +vn -0.0847 -0.5678 0.8188 +vn -0.0350 -0.8088 0.5870 +vn 0.0085 -0.6275 0.7785 +vn -0.8181 -0.4835 0.3113 +vn -0.7022 -0.5639 0.4346 +vn -0.7007 -0.6288 0.3371 +vn -0.2623 -0.4821 0.8359 +vn -0.2535 -0.4493 0.8567 +vn -0.2748 -0.4659 0.8411 +vn -0.7020 -0.3478 0.6214 +vn -0.7038 -0.5238 0.4799 +vn -0.4232 -0.6838 0.5944 +vn -0.5244 -0.5664 0.6357 +vn 0.1861 -0.8915 0.4130 +vn 0.1524 -0.6585 0.7370 +vn 0.4937 -0.7022 0.5130 +vn 0.7966 -0.5559 0.2374 +vn 0.9162 -0.3907 -0.0894 +vn 0.6461 -0.7604 0.0654 +vn 0.8834 -0.4684 -0.0145 +vn 0.3512 -0.7881 -0.5056 +vn 0.3078 -0.4244 -0.8515 +vn 0.3125 -0.4270 -0.8485 +vn 0.2276 -0.4602 -0.8581 +vn -0.0098 -1.0000 0.0014 +vn -0.0136 -0.9997 0.0223 +vn -0.1754 -0.9688 0.1750 +vn -0.3046 -0.7372 0.6031 +vn 0.1344 -0.3492 0.9273 +vn 0.3031 -0.6147 0.7282 +vn 0.7585 -0.4938 0.4253 +vn 0.7716 -0.4616 0.4378 +vn 0.7878 -0.5384 0.2992 +vn 0.8594 -0.4806 -0.1747 +vn 0.8393 -0.5098 -0.1889 +vn 0.0505 -0.9986 -0.0134 +vn 0.4568 -0.8508 -0.2597 +vn 0.4110 -0.8958 -0.1692 +vn 0.7026 -0.5794 -0.4130 +vn 0.7591 -0.4786 -0.4412 +vn 0.3169 -0.8183 -0.4795 +vn 0.3812 -0.4192 -0.8240 +vn 0.2256 -0.4644 -0.8564 +vn 0.0268 -0.8380 -0.5450 +vn 0.0180 -0.9985 -0.0508 +vn -0.0127 -0.9397 -0.3417 +vn -0.8507 -0.4261 0.3078 +vn -0.5042 -0.4963 0.7067 +vn 0.0767 -0.7085 -0.7015 +vn 0.1503 -0.4209 -0.8945 +vn 0.0009 0.1178 -0.9930 +vn 0.0555 -0.4723 -0.8797 +vn 0.0427 -0.5024 -0.8636 +vn -0.0092 -0.8840 -0.4674 +vn 0.0006 -0.9718 -0.2359 +vn -0.9110 -0.3428 -0.2291 +vn -0.4952 -0.2966 -0.8166 +vn -0.5261 -0.3025 -0.7948 +vn -0.7834 -0.3323 -0.5253 +vn -0.8881 -0.3975 -0.2306 +vn -0.8873 -0.4268 -0.1746 +vn -0.9019 -0.4292 0.0478 +vn -0.9661 0.0722 0.2480 +vn -0.7801 -0.0087 0.6256 +vn -0.6776 0.1735 0.7146 +vn -0.7309 0.0225 0.6821 +vn -0.7229 -0.0600 0.6884 +vn -0.7292 -0.1025 0.6766 +vn -0.3187 -0.3223 0.8914 +vn -0.2705 -0.4315 0.8606 +vn -0.0997 -0.5157 0.8509 +vn 0.1839 -0.5986 0.7797 +vn -0.0490 -0.5178 0.8541 +vn 0.5409 -0.1652 0.8247 +vn 0.6707 -0.6744 0.3088 +vn 0.5973 -0.7852 0.1632 +vn 0.6410 -0.7371 0.2141 +vn -0.5328 -0.7776 0.3338 +vn -0.5578 -0.7835 0.2739 +vn -0.3359 -0.8181 0.4668 +vn -0.3550 -0.2206 0.9084 +vn 0.1892 -0.8361 0.5149 +vn 0.3276 -0.8418 0.4290 +vn 0.3570 -0.8182 0.4506 +vn 0.1092 0.1133 -0.9875 +vn 0.9458 -0.0234 0.3240 +vn 0.7135 -0.4245 0.5574 +vn 0.8526 -0.5046 0.1359 +vn -0.8258 -0.5346 -0.1799 +vn -0.1261 -0.5641 -0.8160 +vn -0.2455 -0.7220 -0.6469 +vn -0.2133 -0.6579 -0.7222 +vn -0.6950 -0.5846 -0.4185 +vn -0.7583 -0.5064 -0.4105 +vn -0.7096 -0.6330 -0.3096 +vn 0.6021 -0.6273 -0.4939 +vn 0.6468 -0.4933 -0.5816 +vn 0.6680 -0.3883 -0.6349 +vn 0.6262 -0.7796 -0.0082 +vn 0.6821 -0.7241 0.1020 +vn 0.6920 -0.7023 0.1671 +vn 0.0246 -0.7631 -0.6458 +vn 0.0537 -0.8125 -0.5804 +vn 0.5838 -0.6675 -0.4621 +vn 0.4584 -0.8497 0.2607 +vn 0.3160 -0.9149 0.2513 +vn 0.4644 -0.5845 0.6654 +vn 0.7992 -0.5796 -0.1591 +vn -0.3662 -0.2983 0.8815 +vn -0.2480 -0.7789 0.5761 +vn -0.2496 -0.7766 0.5785 +vn -0.2494 -0.7768 0.5783 +vn -0.2479 -0.7791 0.5758 +vn 0.7465 -0.4485 -0.4915 +vn 0.6870 -0.1599 -0.7088 +vn 0.5156 -0.7552 -0.4048 +vn 0.5687 -0.6368 -0.5206 +vn 0.5229 -0.7434 -0.4171 +vn 0.3381 -0.7998 -0.4959 +vn 0.3324 -0.8099 -0.4832 +vn 0.4151 -0.7743 -0.4777 +vn 0.5251 -0.8110 -0.2579 +vn 0.4072 -0.6701 -0.6207 +vn -0.9167 -0.3991 0.0191 +vn -0.8572 -0.4733 0.2028 +vn -0.8970 -0.4057 0.1753 +vn -0.9707 -0.2237 -0.0879 +vn -0.3999 -0.8683 0.2934 +vn -0.5915 -0.5454 0.5939 +vn -0.7646 -0.4033 0.5028 +vn 0.7820 -0.4046 -0.4742 +vn 0.0778 -0.4217 -0.9034 +vn -0.0237 -0.3009 -0.9534 +vn -0.1398 -0.4490 -0.8825 +vn -0.0258 -0.9966 -0.0777 +vn -0.2546 -0.9240 -0.2854 +vn -0.8569 -0.4442 0.2616 +vn -0.8156 -0.4084 0.4099 +vn -0.8478 -0.4475 0.2845 +vn 0.3201 -0.8787 -0.3542 +vn 0.0488 -0.9972 -0.0562 +vn 0.2622 -0.8204 -0.5080 +vn 0.2566 -0.3904 -0.8841 +vn 0.2207 -0.3987 -0.8901 +vn 0.1316 -0.8915 -0.4336 +vn 0.0284 -0.9946 -0.0998 +vn 0.0922 -0.4616 -0.8823 +vn -0.2437 -0.3999 -0.8836 +vn -0.0259 -0.8861 -0.4628 +vn -0.0311 -0.9587 -0.2828 +vn -0.3157 -0.5134 -0.7980 +vn -0.3229 -0.5391 -0.7779 +vn -0.5222 -0.6818 -0.5123 +vn -0.7066 -0.5138 -0.4865 +vn -0.7401 -0.5296 -0.4145 +vn -0.5494 -0.8102 -0.2041 +vn -0.7086 -0.6960 -0.1156 +vn -0.9534 -0.2968 0.0537 +vn -0.8292 -0.5525 -0.0849 +vn -0.3305 -0.9438 0.0100 +vn -0.0175 -0.9998 -0.0043 +vn -0.0418 -0.9991 -0.0046 +vn -0.9233 -0.3498 0.1583 +vn -0.4857 -0.8352 0.2581 +vn -0.5316 0.2620 0.8055 +vn 0.4422 -0.5890 0.6764 +vn 0.4984 -0.6178 0.6082 +vn 0.4430 -0.5883 0.6765 +vn 0.9105 -0.3118 0.2714 +vn 0.9255 -0.2766 0.2588 +vn 0.8570 -0.2798 0.4328 +vn -0.8221 -0.4881 -0.2929 +vn -0.8313 -0.4994 -0.2439 +vn -0.8413 -0.4744 -0.2593 +vn -0.7821 -0.5506 0.2918 +vn -0.6974 -0.6929 0.1828 +vn -0.7454 -0.6214 0.2411 +vn 0.0015 -0.6025 0.7981 +vn -0.0222 -0.6272 0.7786 +vn 0.1931 -0.5862 0.7868 +vn 0.8291 -0.2636 0.4930 +vn -0.4081 -0.6829 0.6059 +vn -0.5771 -0.4327 0.6926 +vn -0.5176 -0.5362 0.6668 +vn 0.2295 -0.5676 0.7907 +vn -0.5208 -0.7859 -0.3334 +vn -0.6411 -0.6927 -0.3304 +vn -0.6490 -0.7496 0.1300 +vn -0.3587 -0.7358 0.5743 +vn 0.2331 -0.9532 0.1926 +vn 0.0607 -0.9953 0.0755 +vn 0.2608 -0.8427 0.4710 +vn 0.0701 0.9792 0.1904 +vn -0.0491 -0.7614 0.6464 +vn 0.0425 -0.6438 0.7641 +vn 0.2922 -0.5070 0.8109 +vn 0.7203 -0.1589 0.6752 +vn -0.2692 -0.7369 0.6201 +vn -0.3564 -0.4378 0.8254 +vn -0.2216 -0.8516 0.4750 +vn 0.3637 -0.7365 0.5703 +vn 0.3490 -0.7389 0.5764 +vn 0.3755 -0.7344 0.5653 +vn 0.3315 -0.7415 0.5834 +vn 0.7759 -0.6277 -0.0634 +vn 0.7375 -0.6750 -0.0220 +vn 0.7836 -0.6170 -0.0723 +vn 0.8007 -0.5918 -0.0928 +vn -0.5179 -0.6363 0.5717 +vn -0.4700 -0.6704 0.5742 +vn -0.5938 -0.5748 0.5630 +vn 0.0673 -0.4038 0.9124 +vn -0.3597 -0.7365 0.5729 +vn -0.6898 -0.7158 -0.1092 +vn -0.7317 -0.3367 -0.5927 +vn -0.2141 -0.7207 -0.6594 +vn 0.4629 -0.5570 -0.6896 +vn 0.3874 -0.6218 -0.6806 +vn 0.3868 -0.6223 -0.6805 +vn 0.3424 -0.6562 -0.6724 +vn -0.8101 -0.0090 -0.5863 +vn -0.6361 -0.7477 -0.1904 +vn -0.5794 -0.7909 0.1970 +vn -0.5835 -0.2058 0.7856 +vn 0.0188 -0.7439 0.6680 +vn -0.2626 -0.6604 -0.7035 +vn -0.4389 -0.5637 -0.6997 +vn -0.2908 -0.6471 -0.7048 +vn -0.0409 -0.7400 -0.6713 +vn 0.6247 -0.5380 -0.5659 +vn 0.6181 -0.4790 -0.6233 +vn 0.6268 -0.5753 -0.5255 +vn 0.6232 -0.6649 -0.4117 +vn 0.6798 -0.6291 0.3770 +vn 0.6877 -0.5509 0.4728 +vn 0.6880 -0.5303 0.4954 +vn 0.6865 -0.4840 0.5426 +vn 0.5269 -0.6362 -0.5636 +vn 0.5050 -0.6584 -0.5581 +vn 0.4730 -0.6889 -0.5493 +vn 0.4362 -0.7211 -0.5383 +vn -0.2220 -0.4092 -0.8851 +vn -0.2867 -0.5144 -0.8082 +vn -0.3634 -0.6374 -0.6794 +vn -0.4056 -0.7040 -0.5830 +vn 0.7995 -0.5261 0.2900 +vn 0.7701 -0.5957 0.2284 +vn 0.7580 -0.6189 0.2061 +vn 0.7394 -0.6503 0.1744 +vn -0.1333 -0.4946 0.8588 +vn -0.1254 -0.5054 0.8537 +vn -0.1219 -0.5101 0.8514 +vn -0.1186 -0.5147 0.8491 +vn -0.6775 -0.7170 0.1639 +vn -0.7747 -0.6294 0.0599 +vn -0.7901 -0.6116 0.0407 +vn -0.8423 -0.5381 -0.0329 +vn 0.4226 -0.6268 0.6546 +vn 0.2748 -0.7119 0.6463 +vn 0.5192 -0.5561 0.6490 +vn 0.6323 -0.4536 0.6281 +vn 0.7364 -0.6747 0.0510 +vn 0.6826 -0.7181 0.1360 +vn 0.7468 -0.6643 0.0327 +vn 0.7887 -0.6126 -0.0506 +vn 0.4910 -0.6976 -0.5217 +vn 0.4937 -0.7368 -0.4619 +vn 0.2155 -0.7205 -0.6592 +vn 0.1879 -0.6741 -0.7144 +vn -0.2856 -0.6701 -0.6852 +vn -0.4437 -0.7113 -0.5452 +vn -0.4029 -0.6654 0.6284 +vn -0.2951 -0.5548 0.7779 +vn -0.4124 -0.6745 0.6124 +vn -0.5035 -0.7541 0.4216 +vn -0.7652 -0.6365 -0.0963 +vn -0.8405 -0.5364 0.0763 +vn -0.6986 -0.6464 -0.3070 +vn 0.6760 -0.6228 -0.3939 +vn 0.6386 -0.6559 -0.4024 +vn 0.6101 -0.6792 -0.4080 +vn 0.5531 -0.7212 -0.4171 +vn -0.0012 -0.4961 -0.8682 +vn -0.3519 -0.6682 -0.6555 +vn 0.0742 -0.4029 -0.9122 +vn -0.4055 -0.7409 -0.5354 +vn 0.7204 -0.6107 0.3287 +vn 0.7050 -0.6246 0.3359 +vn 0.7230 -0.6083 0.3275 +vn 0.7492 -0.5830 0.3145 +vn 0.1113 -0.7148 0.6904 +vn -0.0414 -0.5997 0.7991 +vn -0.0688 -0.5759 0.8146 +vn -0.1661 -0.4828 0.8598 +vn -0.5906 -0.7135 0.3768 +vn -0.7317 -0.6304 0.2591 +vn -0.7199 -0.6866 0.1013 +vn -0.6751 -0.6960 -0.2446 +vn 0.3045 -0.6328 -0.7120 +vn 0.3313 -0.6899 -0.6436 +vn 0.2948 -0.6122 -0.7337 +vn 0.5055 -0.7399 0.4439 +vn 0.8667 -0.4950 -0.0613 +vn 0.8470 -0.5257 -0.0793 +vn 0.8299 -0.5499 -0.0939 +vn 0.7772 -0.6148 -0.1342 +vn 0.2782 -0.5768 -0.7681 +vn -0.5460 -0.5895 -0.5953 +vn -0.5186 -0.6090 -0.6001 +vn -0.3529 -0.7061 -0.6140 +vn -0.1100 -0.1053 0.9883 +vn 0.1454 -0.5869 0.7965 +vn -0.8131 -0.5393 0.2194 +vn -0.7257 -0.6337 0.2680 +vn -0.7053 -0.6522 0.2777 +vn -0.6448 -0.7014 0.3037 +vn -0.6492 -0.5044 -0.5693 +vn -0.1887 -0.4824 0.8554 +vn -0.1449 -0.5373 0.8308 +vn -0.0992 -0.5906 0.8009 +vn -0.0184 -0.6748 0.7377 +vn 0.5464 -0.6475 0.5312 +vn 0.5458 -0.6466 0.5330 +vn 0.5384 -0.6344 0.5547 +vn 0.5538 -0.6599 0.5078 +vn -0.6472 -0.7173 0.2582 +vn -0.9311 -0.3603 -0.0568 +vn -0.3711 -0.7862 -0.4941 +vn 0.1776 -0.4900 -0.8534 +vn 0.1361 -0.4318 -0.8916 +vn 0.1963 -0.5157 -0.8340 +vn 0.2727 -0.6169 -0.7383 +vn 0.7386 -0.6548 -0.1603 +vn 0.7852 -0.6092 -0.1114 +vn 0.7873 -0.6069 -0.1090 +vn 0.8150 -0.5745 -0.0763 +vn -0.8939 -0.4484 0.0007 +vn -0.8192 -0.5707 0.0566 +vn -0.7994 -0.5968 0.0691 +vn -0.7700 -0.6321 0.0866 +vn -0.3268 -0.6531 0.6831 +vn -0.3395 -0.6877 0.6417 +vn -0.3655 -0.7609 0.5362 +vn -0.3038 -0.5925 0.7461 +vn -0.4927 -0.6131 -0.6175 +vn -0.5016 -0.6391 -0.5830 +vn -0.5017 -0.6394 -0.5826 +vn -0.5069 -0.6553 -0.5600 +vn 0.3257 -0.5472 -0.7711 +vn 0.2987 -0.5719 -0.7640 +vn 0.2952 -0.5750 -0.7630 +vn 0.2806 -0.5878 -0.7587 +vn 0.7472 -0.6641 -0.0266 +vn 0.7762 -0.6304 0.0086 +vn 0.7837 -0.6209 0.0181 +vn 0.8002 -0.5983 0.0402 +vn 0.2522 -0.5631 0.7869 +vn 0.2984 -0.6316 0.7156 +vn 0.2960 -0.6282 0.7195 +vn 0.3285 -0.6749 0.6608 +vn -0.0009 -0.9981 0.0615 +vn 0.0005 -0.9999 0.0110 +vn 0.0036 -1.0000 -0.0070 +vn 0.0098 -0.9998 -0.0166 +vn 0.0040 -1.0000 -0.0091 +vn -0.0032 -1.0000 -0.0048 +vn -0.0074 -1.0000 -0.0034 +vn -0.0219 -0.9995 0.0220 +vn -0.0103 -0.9999 0.0018 +vn 0.0074 -0.9999 -0.0149 +vn -0.0167 -0.9998 -0.0131 +vn -0.0021 -1.0000 0.0094 +vn 0.0015 -1.0000 0.0023 +vn 0.0015 -1.0000 0.0001 +vn 0.0015 -1.0000 -0.0053 +vn 0.0007 -1.0000 0.0020 +vn -0.0033 -0.9996 0.0283 +vn -0.0051 -0.9989 0.0455 +vn 0.0178 -0.9846 -0.1741 +vn 0.0064 -0.9999 -0.0128 +vn 0.0036 -1.0000 0.0023 +vn 0.0075 -0.9999 -0.0083 +vn 0.0003 -1.0000 -0.0050 +vn -0.0046 -1.0000 0.0080 +vn -0.0048 -0.9999 -0.0113 +vn 0.0007 -1.0000 0.0013 +vn 0.0217 -0.9993 -0.0301 +vn 0.0027 -1.0000 0.0053 +vn 0.0021 -1.0000 -0.0031 +vn -0.0020 -1.0000 0.0009 +vn 0.0007 -0.9999 0.0126 +vn 0.0038 -1.0000 0.0049 +vn -0.0072 -0.9999 0.0133 +vn -0.0060 -1.0000 -0.0020 +vn 0.0289 -0.9995 0.0119 +vn 0.0005 -1.0000 0.0070 +vn -0.0247 -0.9995 -0.0211 +vn 0.0257 -0.9992 -0.0309 +vn -0.0016 -0.9992 -0.0389 +vn -0.0005 -1.0000 -0.0024 +vn 0.0026 -1.0000 -0.0067 +vn -0.0141 -0.9988 0.0474 +vn 0.0248 -0.9995 -0.0210 +vn -0.0041 -1.0000 -0.0010 +vn 0.0017 -0.9998 0.0216 +vn 0.0220 -0.9997 0.0051 +vn 0.0055 -0.9999 0.0140 +vn -0.0084 -0.9995 -0.0316 +vn -0.0127 -0.9987 -0.0487 +vn -0.0012 -0.9995 -0.0330 +vn 0.0002 -1.0000 0.0063 +vn -0.0172 -0.9995 -0.0262 +vn -0.0004 -1.0000 0.0099 +vn -0.0229 -0.9995 0.0227 +vn -0.0054 -0.9998 0.0207 +vn 0.2613 0.9645 0.0379 +vn -0.0178 0.9554 0.2947 +vn 0.1911 0.9681 0.1619 +vn 0.7846 -0.0090 -0.6200 +vn 0.7854 0.1443 -0.6019 +vn 0.7860 0.1023 -0.6096 +vn 0.7807 -0.0052 -0.6249 +vn 0.7983 -0.0109 0.6021 +vn 0.8356 0.0086 0.5493 +vn 0.8199 0.0002 0.5725 +vn 0.7890 -0.0155 0.6142 +vn 0.1413 0.1409 0.9799 +vn -0.6254 -0.1413 0.7674 +vn -0.9628 0.1023 0.2500 +vn -0.9536 0.1720 0.2470 +vn -0.9528 0.1769 0.2468 +vn -0.6898 -0.0981 -0.7173 +vn -0.5729 -0.0126 -0.8195 +vn -0.6303 -0.0529 -0.7746 +vn -0.4911 0.0407 -0.8701 +vn 0.1677 0.5666 -0.8067 +vn 0.6054 0.7214 -0.3363 +vn 0.6176 0.6757 -0.4025 +vn 0.6186 0.6708 -0.4090 +vn 0.6285 0.5968 -0.4989 +vn 0.6150 0.6884 0.3844 +vn 0.6256 0.6120 0.4838 +vn 0.6157 0.6851 0.3893 +vn 0.6012 0.7371 0.3085 +vn 0.2932 0.5912 0.7513 +vn -0.4047 0.6723 0.6199 +vn -0.4175 0.6989 0.5807 +vn -0.4203 0.7048 0.5715 +vn -0.4329 0.7315 0.5268 +vn -0.8280 0.5605 0.0175 +vn -0.4615 0.7297 -0.5045 +vn -0.4665 0.7432 -0.4797 +vn -0.4610 0.7284 -0.5069 +vn -0.4553 0.7138 -0.5322 +vn 0.7006 0.4757 -0.5319 +vn 0.5142 0.8575 -0.0182 +vn -0.1131 0.8692 0.4813 +vn -0.9159 0.3246 0.2361 +vn -0.3081 0.7897 -0.5305 +vn -0.3060 0.7913 -0.5294 +vn -0.3031 0.7933 -0.5280 +vn -0.3004 0.7953 -0.5265 +vn 0.0452 -0.9988 0.0190 +vn 0.0381 -0.9993 -0.0008 +vn 0.0529 -0.9983 -0.0231 +vn -0.0255 -0.9992 0.0313 +vn -0.0084 -0.9982 0.0588 +vn -0.0433 -0.9986 0.0295 +vn 0.0147 -0.9991 0.0400 +vn 0.0323 -0.9988 -0.0356 +vn -0.0526 -0.9986 0.0010 +vn 0.0088 -0.9990 -0.0448 +vn -0.0128 -0.9994 -0.0327 +vn -0.0400 -0.9990 -0.0205 +vn -0.0241 0.9995 0.0207 +vn 0.1226 0.9821 0.1431 +vn 0.1018 0.9923 -0.0707 +vn 0.0185 0.9860 0.1657 +vn -0.0772 0.9880 -0.1340 +vn 0.9257 -0.0022 0.3782 +vn 0.9973 -0.0098 -0.0722 +vn 0.9408 0.0178 0.3386 +vn 0.6299 -0.0012 -0.7767 +vn 0.4723 -0.0026 -0.8814 +vn 0.6196 0.0008 -0.7849 +vn 0.4561 -0.0047 -0.8899 +vn -0.6196 0.0085 -0.7849 +vn -0.5877 0.0043 -0.8090 +vn -0.5900 0.0046 -0.8074 +vn -0.6215 0.0087 -0.7834 +vn -0.9972 0.0134 -0.0732 +vn -0.9861 0.0062 -0.1659 +vn -0.9869 0.0066 -0.1612 +vn -0.9976 0.0138 -0.0682 +vn -0.7836 0.0111 0.6212 +vn -0.7424 0.0061 0.6699 +vn -0.7812 0.0108 0.6242 +vn -0.7404 0.0059 0.6721 +vn -0.2920 0.0143 0.9563 +vn -0.0097 -0.0026 0.9999 +vn -0.2802 0.0136 0.9599 +vn 0.0034 -0.0033 1.0000 +vn 0.6168 0.0078 0.7871 +vn 0.6653 0.0046 0.7466 +vn 0.8044 0.0139 0.5939 +vn 0.1076 0.9933 0.0423 +vn 0.1172 0.9931 -0.0067 +vn 0.0995 0.9934 -0.0572 +vn -0.0821 0.9947 -0.0621 +vn -0.0961 0.9943 -0.0454 +vn -0.1159 0.9930 0.0243 +vn 0.0869 0.9929 0.0813 +vn 0.0424 0.9936 0.1044 +vn -0.0152 0.9927 -0.1193 +vn -0.0467 0.9922 -0.1156 +vn 0.0564 0.9939 -0.0943 +vn -0.0452 0.9937 0.1025 +vn -0.0006 0.9932 0.1160 +vn -0.0868 0.9941 0.0656 +vn 0.9704 0.0345 0.2390 +vn 0.9123 -0.0281 0.4086 +vn 0.9972 -0.0499 0.0561 +vn 0.8678 0.0623 -0.4930 +vn 0.8521 0.0401 -0.5219 +vn 0.8591 0.0497 -0.5094 +vn 0.8385 0.0222 -0.5445 +vn 0.1656 0.0334 -0.9856 +vn 0.3641 -0.0701 -0.9287 +vn -0.0294 -0.0344 -0.9990 +vn -0.3384 0.0447 -0.9399 +vn -0.5177 -0.0212 -0.8553 +vn -0.6648 0.0654 -0.7442 +vn -0.9979 0.0487 -0.0428 +vn -0.9458 -0.0642 -0.3183 +vn -0.9998 -0.0077 0.0200 +vn -0.9811 0.0555 0.1855 +vn -0.9404 -0.0378 0.3380 +vn -0.4315 0.0241 0.9018 +vn -0.4676 -0.0059 0.8839 +vn -0.4420 0.0154 0.8969 +vn -0.4081 0.0430 0.9119 +vn 0.3184 0.0291 0.9475 +vn 0.2144 -0.0172 0.9766 +vn 0.4620 -0.0240 0.8866 +vn 0.7100 0.0433 0.7029 +vn 0.9852 0.1238 0.1185 +vn 0.9679 -0.0016 0.2512 +vn 0.9688 0.0016 0.2478 +vn 0.9198 -0.1237 0.3723 +vn -0.3898 0.1237 -0.9125 +vn -0.2663 -0.0017 -0.9639 +vn -0.2697 0.0016 -0.9629 +vn -0.1374 -0.1239 -0.9827 +vn -0.5951 0.1239 0.7940 +vn -0.7014 -0.0016 0.7128 +vn -0.6989 0.0017 0.7152 +vn -0.7822 -0.1238 0.6105 +vn 0.0731 0.8794 0.4704 +vn -0.0963 0.9356 -0.3397 +vn 0.6267 -0.0791 -0.7752 +vn 0.5007 0.8656 0.0074 +vn 0.0338 -0.9992 0.0219 +vn 0.0544 -0.9981 0.0281 +vn 0.0157 -0.9987 0.0480 +vn 0.0422 -0.9990 -0.0120 +vn -0.0320 -0.9993 0.0202 +vn -0.0171 -0.9989 0.0434 +vn -0.0406 -0.9992 -0.0063 +vn -0.0065 -0.9991 -0.0407 +vn 0.0206 -0.9991 -0.0374 +vn -0.0306 -0.9988 -0.0394 +vn 0.1390 0.9809 0.1362 +vn -0.1034 0.9945 0.0163 +vn 0.1005 0.9832 0.1527 +vn -0.1361 0.9904 -0.0248 +vn 0.9830 0.0875 -0.1613 +vn 0.9769 -0.0075 0.2133 +vn 0.9819 -0.0060 0.1893 +vn 0.9801 0.0862 -0.1789 +vn 0.2652 0.0231 -0.9639 +vn 0.6561 -0.0149 -0.7546 +vn 0.6307 -0.0121 -0.7760 +vn 0.2326 0.0259 -0.9722 +vn -0.6544 -0.0116 -0.7561 +vn -0.4576 0.0232 -0.8888 +vn -0.6420 -0.0092 -0.7666 +vn -0.4422 0.0257 -0.8966 +vn -0.9428 0.0162 0.3329 +vn -0.9996 -0.0168 -0.0246 +vn -0.9999 -0.0146 -0.0002 +vn -0.9334 0.0186 0.3585 +vn -0.2823 0.0138 0.9592 +vn -0.3824 0.0040 0.9240 +vn -0.3756 0.0047 0.9268 +vn -0.2742 0.0145 0.9616 +vn 0.6590 0.0149 0.7520 +vn 0.4946 0.0021 0.8691 +vn 0.5058 0.0029 0.8627 +vn 0.6682 0.0157 0.7439 +vn 0.0900 0.9936 0.0680 +vn 0.0833 0.9942 0.0684 +vn 0.1039 0.9942 -0.0274 +vn 0.1126 0.9936 0.0065 +vn -0.0948 0.9935 -0.0625 +vn -0.0546 0.9929 -0.1061 +vn -0.1093 0.9933 -0.0383 +vn 0.0311 0.9938 0.1069 +vn -0.0030 0.9948 0.1021 +vn 0.0098 0.9944 -0.1052 +vn 0.0377 0.9937 -0.1058 +vn -0.0870 0.9944 0.0604 +vn -0.0994 0.9940 0.0452 +vn 0.0883 0.9938 -0.0682 +vn 0.7560 0.0464 0.6529 +vn 0.9092 -0.0342 0.4149 +vn 0.9994 0.0334 0.0018 +vn 0.9609 -0.0400 -0.2741 +vn 0.7990 0.0269 -0.6008 +vn 0.7217 -0.0307 -0.6915 +vn 0.5511 0.0619 -0.8321 +vn -0.0390 -0.0474 -0.9981 +vn -0.0369 -0.0457 -0.9983 +vn -0.0374 -0.0462 -0.9982 +vn -0.0357 -0.0448 -0.9984 +vn -0.7260 0.0645 -0.6846 +vn -0.8305 -0.0335 -0.5561 +vn -0.8053 -0.0072 -0.5928 +vn -0.8803 -0.0943 -0.4650 +vn -0.9953 0.0890 0.0384 +vn -0.9425 -0.0376 0.3322 +vn -0.9711 0.0039 0.2386 +vn -0.8617 -0.1131 0.4947 +vn -0.5459 0.1257 0.8283 +vn 0.2380 0.0142 0.9712 +vn -0.0462 -0.1062 0.9933 +vn 0.3724 -0.0413 0.9271 +vn 0.8719 0.1237 0.4738 +vn 0.8070 -0.0016 0.5906 +vn 0.8090 0.0017 0.5878 +vn 0.7177 -0.1236 0.6853 +vn -0.0256 0.1236 -0.9920 +vn 0.1081 -0.0018 -0.9941 +vn 0.1046 0.0015 -0.9945 +vn 0.2349 -0.1239 -0.9641 +vn -0.8464 0.1237 0.5180 +vn -0.9150 -0.0016 0.4034 +vn -0.9136 0.0017 0.4066 +vn -0.9524 -0.1237 0.2787 +vn -0.3008 0.9512 -0.0681 +vn 0.2501 0.8769 -0.4105 +vn 0.9352 0.3113 -0.1686 +vn 0.4518 0.8348 0.3145 +vn -0.0411 -0.9988 0.0262 +vn -0.0254 -0.9984 0.0512 +vn -0.0534 -0.9985 0.0126 +vn 0.0515 -0.9980 -0.0367 +vn 0.0497 -0.9987 0.0078 +vn 0.0456 -0.9987 -0.0206 +vn 0.0178 -0.9992 0.0353 +vn 0.0184 -0.9991 0.0382 +vn -0.0410 -0.9988 -0.0280 +vn -0.0220 -0.9991 -0.0354 +vn 0.0051 -0.9989 -0.0468 +vn 0.0387 0.9973 0.0622 +vn 0.0208 0.9987 0.0474 +vn 0.0671 0.9960 0.0585 +vn -0.0832 0.9949 0.0578 +vn -0.1401 0.9877 0.0693 +vn 0.7940 0.0138 0.6077 +vn 0.8922 -0.0032 0.4516 +vn 0.8037 0.0123 0.5949 +vn 0.8976 -0.0044 0.4407 +vn 0.9655 0.0227 -0.2593 +vn 0.7997 0.0026 -0.6003 +vn 0.7738 0.0229 -0.6330 +vn 0.4287 -0.0038 -0.9034 +vn 0.3845 0.0182 -0.9229 +vn -0.0261 -0.0098 -0.9996 +vn -0.6470 0.0507 -0.7608 +vn -0.8784 -0.0106 -0.4778 +vn -0.6632 0.0475 -0.7470 +vn -0.8920 -0.0130 -0.4518 +vn -0.9182 0.0132 0.3959 +vn -0.8763 0.0053 0.4817 +vn -0.9154 0.0126 0.4023 +vn -0.8729 0.0047 0.4879 +vn -0.2014 0.0144 0.9794 +vn -0.0808 0.0027 0.9967 +vn -0.1926 0.0135 0.9812 +vn -0.0725 0.0019 0.9974 +vn 0.0451 0.9941 0.0985 +vn 0.0884 0.9939 0.0663 +vn 0.1144 0.9933 -0.0142 +vn 0.1116 0.9930 -0.0381 +vn -0.0609 0.9933 -0.0977 +vn -0.0966 0.9929 -0.0694 +vn -0.1079 0.9942 0.0017 +vn 0.0035 0.9942 0.1077 +vn -0.0176 0.9935 -0.1123 +vn 0.0463 0.9947 -0.0916 +vn 0.0483 0.9945 -0.0924 +vn -0.0475 0.9943 0.0955 +vn -0.0604 0.9950 0.0800 +vn -0.1141 0.9934 0.0105 +vn 0.7940 0.0516 0.6057 +vn 0.9796 -0.0441 0.1959 +vn 0.9996 0.0280 0.0064 +vn 0.9682 -0.0891 -0.2336 +vn 0.7362 0.0822 -0.6717 +vn 0.5410 -0.0097 -0.8410 +vn 0.4762 0.0350 -0.8786 +vn 0.3512 -0.0284 -0.9359 +vn 0.1883 0.0373 -0.9814 +vn -0.4428 0.0034 -0.8966 +vn -0.3513 -0.0602 -0.9343 +vn -0.4137 -0.0173 -0.9103 +vn -0.5063 0.0502 -0.8609 +vn -0.9690 -0.0168 -0.2464 +vn -0.9737 -0.0331 -0.2252 +vn -0.9726 -0.0288 -0.2308 +vn -0.9762 -0.0429 -0.2124 +vn -0.8857 0.0547 0.4610 +vn -0.8237 -0.0174 0.5668 +vn -0.8468 0.0072 0.5319 +vn -0.7755 -0.0631 0.6282 +vn -0.2536 0.0526 0.9659 +vn -0.1003 -0.0267 0.9946 +vn 0.0835 0.0360 0.9959 +vn 0.4373 -0.0534 0.8977 +vn 0.9452 0.1049 0.3091 +vn 0.9294 0.0614 0.3640 +vn 0.9236 0.0481 0.3803 +vn 0.8992 0.0000 0.4375 +vn 0.2802 0.0000 -0.9599 +vn 0.3388 -0.0479 -0.9397 +vn 0.3546 -0.0611 -0.9330 +vn 0.4058 -0.1045 -0.9080 +vn -0.9453 0.1047 -0.3090 +vn -0.9295 0.0612 -0.3638 +vn -0.9237 0.0480 -0.3800 +vn -0.8994 0.0000 -0.4372 +vn -0.2798 0.0000 0.9601 +vn -0.3386 -0.0481 0.9397 +vn -0.3546 -0.0614 0.9330 +vn -0.4059 -0.1049 0.9079 +vn -0.4449 0.8941 0.0504 +vn -0.6397 0.1628 -0.7512 +vn 0.0305 0.8655 -0.5000 +vn 0.0110 -0.9998 0.0145 +vn -0.0039 -1.0000 0.0087 +vn 0.0078 -0.9994 0.0326 +vn 0.0189 -0.9995 -0.0259 +vn -0.0069 -1.0000 -0.0000 +vn -0.0416 -0.9991 0.0086 +vn -0.0209 -0.9998 -0.0017 +vn 0.0082 -0.9999 -0.0090 +vn 0.0428 -0.9969 -0.0662 +vn 0.0109 -0.9997 -0.0237 +vn -0.0138 -0.9998 0.0134 +vn -0.0198 -0.9994 0.0273 +vn -0.0888 0.9720 -0.2175 +vn -0.1439 0.9895 0.0103 +vn -0.0838 0.9761 0.2003 +vn 0.1069 0.0214 0.9940 +vn 0.1290 0.1780 0.9755 +vn 0.1182 0.0143 0.9929 +vn 0.1384 0.1018 0.9851 +vn -0.9638 -0.0549 0.2610 +vn -0.9000 0.0272 0.4351 +vn -0.9345 -0.0111 0.3558 +vn -0.9772 -0.0843 0.1948 +vn -0.8393 0.0759 -0.5383 +vn -0.3998 -0.0625 -0.9145 +vn 0.4419 -0.0226 -0.8968 +vn 0.1301 0.2003 -0.9711 +vn 0.1993 0.2319 -0.9521 +vn 0.5479 -0.0572 -0.8346 +vn 0.9952 0.0021 0.0983 +vn 0.9935 0.0853 -0.0756 +vn 0.9988 0.0480 0.0029 +vn 0.9817 -0.0406 0.1860 +vn 0.6567 0.6788 0.3287 +vn 0.4647 0.7460 0.4769 +vn 0.2013 0.6832 0.7020 +vn -0.0096 0.6911 0.7227 +vn -0.0958 0.6361 0.7656 +vn -0.6251 0.6076 0.4900 +vn -0.6421 0.7051 0.3010 +vn -0.7011 0.6945 0.1618 +vn -0.6983 0.7158 0.0044 +vn -0.7590 0.6347 -0.1450 +vn -0.4810 0.6139 -0.6260 +vn -0.3813 0.6693 -0.6376 +vn -0.1832 0.6716 -0.7179 +vn 0.0475 0.7306 -0.6812 +vn 0.4140 0.6820 -0.6029 +vn 0.6328 0.7347 -0.2444 +vn 0.7324 0.6676 -0.1337 +vn 0.1190 0.4782 0.8701 +vn -0.2053 0.8743 0.4398 +vn -0.7595 0.5385 0.3650 +vn -0.6754 0.5979 -0.4317 +vn -0.2087 0.8703 -0.4461 +vn 0.1099 0.5468 -0.8300 +vn 0.7227 0.6887 -0.0591 +vn 0.7093 0.7031 -0.0497 +vn 0.6813 0.7314 -0.0305 +vn 0.6612 0.7500 -0.0174 +vn -0.0244 -0.9996 -0.0149 +vn -0.0352 -0.9994 -0.0059 +vn -0.0343 -0.9993 -0.0166 +vn 0.0036 -1.0000 0.0038 +vn -0.0011 -0.9998 -0.0202 +vn 0.0290 -0.9996 -0.0066 +vn 0.0164 -0.9997 0.0159 +vn 0.0068 -0.9999 0.0089 +vn 0.0140 -0.9992 0.0384 +vn 0.0012 -1.0000 0.0027 +vn -0.0119 -0.9994 0.0328 +vn -0.0256 -0.9996 -0.0149 +vn 0.0107 0.9998 -0.0191 +vn -0.0925 0.9639 0.2495 +vn -0.0683 0.9801 0.1866 +vn 0.2112 0.0146 0.9773 +vn 0.1353 0.2174 0.9667 +vn 0.1788 0.0337 0.9833 +vn 0.1196 0.1511 0.9813 +vn -0.9070 -0.0487 0.4182 +vn -0.9730 0.0825 0.2157 +vn -0.9448 -0.0018 0.3276 +vn -0.9817 0.1224 0.1460 +vn -0.6359 -0.0917 -0.7663 +vn -0.1500 0.1238 -0.9809 +vn -0.1473 0.2124 -0.9660 +vn -0.1451 0.2659 -0.9530 +vn 0.6106 -0.0921 -0.7865 +vn 0.9945 0.0071 0.1049 +vn 0.9774 0.1174 -0.1759 +vn 0.9948 0.0755 -0.0680 +vn 0.9675 -0.0507 0.2478 +vn 0.6902 0.6694 0.2749 +vn 0.4753 0.7286 0.4932 +vn 0.1703 0.6707 0.7220 +vn -0.0036 0.6893 0.7244 +vn -0.1700 0.6047 0.7781 +vn -0.6065 0.6599 0.4435 +vn -0.6181 0.7020 0.3537 +vn -0.6859 0.6845 0.2470 +vn -0.6898 0.7003 0.1837 +vn -0.7704 0.6371 0.0227 +vn -0.4979 0.7013 -0.5102 +vn -0.4850 0.6535 -0.5811 +vn -0.4970 0.6977 -0.5159 +vn -0.5050 0.7332 -0.4553 +vn -0.0598 0.6167 -0.7849 +vn 0.4472 0.6832 -0.5773 +vn 0.4503 0.6814 -0.5770 +vn 0.4475 0.6830 -0.5773 +vn 0.4447 0.6846 -0.5775 +vn 0.7943 0.6013 -0.0866 +vn 0.7375 0.6741 0.0405 +vn 0.1029 0.4860 0.8679 +vn -0.1690 0.8778 0.4482 +vn -0.9659 0.2152 0.1441 +vn -0.2734 0.8592 -0.4324 +vn -0.1307 0.4822 -0.8663 +vn 0.6846 0.7134 -0.1499 +vn 0.6655 0.7298 -0.1566 +vn 0.7126 0.6875 -0.1396 +vn 0.7241 0.6763 -0.1352 +vn -0.0334 -0.9994 0.0101 +vn -0.0138 -0.9998 0.0110 +vn -0.0195 -0.9998 -0.0034 +vn 0.0242 -0.9996 0.0119 +vn 0.0262 -0.9996 0.0101 +vn 0.0141 -0.9995 0.0274 +vn 0.0378 -0.9993 0.0022 +vn -0.0058 -1.0000 0.0008 +vn -0.0272 -0.9991 0.0328 +vn -0.0087 -0.9999 -0.0135 +vn 0.0262 -0.9994 -0.0225 +vn 0.0068 -1.0000 0.0052 +vn -0.1288 0.9664 0.2225 +vn -0.1391 0.9628 0.2317 +vn -0.0070 0.9936 0.1129 +vn 0.6698 0.1082 0.7346 +vn -0.1136 -0.0516 0.9922 +vn 0.0087 0.0143 0.9999 +vn -0.0412 -0.0126 0.9991 +vn -0.1526 -0.0727 0.9856 +vn -0.9938 -0.0141 -0.1099 +vn -0.9855 0.1335 0.1045 +vn -0.9959 0.0892 0.0139 +vn -0.9692 -0.0849 -0.2313 +vn 0.0824 -0.0283 -0.9962 +vn -0.0849 0.0507 -0.9951 +vn -0.0001 0.0107 -0.9999 +vn 0.1620 -0.0660 -0.9846 +vn 0.8860 0.0957 -0.4538 +vn 0.8701 0.2088 -0.4464 +vn 0.8715 0.2012 -0.4471 +vn 0.9760 -0.1178 0.1834 +vn 0.5026 0.5975 0.6248 +vn -0.1167 0.7117 0.6928 +vn -0.1043 0.7198 0.6863 +vn -0.1172 0.7114 0.6930 +vn -0.1292 0.7032 0.6991 +vn -0.6737 0.5723 0.4675 +vn -0.6957 0.7127 -0.0897 +vn -0.6637 0.7363 -0.1317 +vn -0.6505 0.7057 -0.2808 +vn -0.6241 0.7031 -0.3407 +vn -0.5697 0.6118 -0.5488 +vn 0.1107 0.6869 -0.7182 +vn 0.1155 0.6832 -0.7210 +vn 0.1102 0.6873 -0.7180 +vn 0.1061 0.6904 -0.7156 +vn 0.6465 0.5882 -0.4858 +vn 0.7172 0.6929 0.0744 +vn 0.6932 0.7135 0.1020 +vn 0.6938 0.7130 0.1013 +vn 0.6693 0.7319 0.1279 +vn 0.5019 0.8301 0.2430 +vn -0.2821 0.8908 0.3562 +vn -0.9675 0.2307 0.1037 +vn -0.0899 0.8304 -0.5499 +vn -0.1118 0.8588 -0.4999 +vn -0.0629 0.7914 -0.6080 +vn -0.0410 0.7571 -0.6520 +vn 0.8126 0.4060 -0.4182 +vn -0.0373 -0.9992 0.0114 +vn -0.0240 -0.9997 -0.0011 +vn -0.0242 -0.9997 -0.0091 +vn 0.0216 -0.9997 0.0079 +vn 0.0278 -0.9996 -0.0016 +vn 0.0038 -1.0000 0.0054 +vn 0.0146 -0.9999 0.0077 +vn 0.0028 -0.9999 -0.0157 +vn 0.0441 -0.9990 -0.0064 +vn -0.0054 -1.0000 0.0035 +vn -0.0257 -0.9996 -0.0131 +vn -0.0128 -0.9996 0.0260 +vn 0.0466 0.9523 0.3017 +vn 0.0599 0.9632 0.2621 +vn 0.1122 0.9888 0.0989 +vn 0.3089 0.1396 0.9408 +vn -0.4907 -0.1471 0.8588 +vn -0.8839 0.0985 0.4572 +vn -0.8748 0.1731 0.4526 +vn -0.8729 0.1848 0.4516 +vn -0.8284 -0.0808 -0.5543 +vn -0.6962 0.0144 -0.7177 +vn -0.7717 -0.0365 -0.6349 +vn -0.6157 0.0621 -0.7855 +vn 0.3759 -0.0571 -0.9249 +vn 0.4876 0.1371 -0.8622 +vn 0.4177 -0.0363 -0.9079 +vn 0.5186 0.1741 -0.8371 +vn 0.9600 -0.0365 0.2777 +vn 0.9900 0.0221 0.1397 +vn 0.9774 -0.0080 0.2111 +vn 0.9455 -0.0553 0.3209 +vn 0.6909 0.6956 0.1969 +vn 0.5948 0.7036 0.3889 +vn 0.5702 0.5936 0.5680 +vn 0.0568 0.6018 0.7966 +vn -0.1733 0.7193 0.6728 +vn -0.2376 0.7122 0.6605 +vn -0.3791 0.7394 0.5564 +vn -0.4521 0.7014 0.5510 +vn -0.7854 0.5964 0.1654 +vn -0.6285 0.6835 -0.3712 +vn -0.6058 0.6985 -0.3809 +vn -0.6056 0.6987 -0.3810 +vn -0.5805 0.7142 -0.3910 +vn -0.1235 0.6047 -0.7868 +vn 0.1037 0.6842 -0.7219 +vn 0.1393 0.6805 -0.7194 +vn 0.2905 0.7040 -0.6481 +vn 0.3260 0.6875 -0.6489 +vn 0.7920 0.5759 -0.2026 +vn 0.7172 0.6968 -0.0090 +vn -0.0129 0.8834 0.4685 +vn -0.8336 0.3447 0.4316 +vn -0.3938 0.7670 -0.5066 +vn -0.3537 0.7940 -0.4944 +vn -0.3069 0.8224 -0.4790 +vn -0.2652 0.8451 -0.4642 +vn 0.4622 0.4829 -0.7437 +vn 0.6113 0.7857 -0.0946 +vn 0.0199 -0.9998 0.0079 +vn 0.0220 -0.9997 0.0103 +vn 0.0121 -0.9998 0.0165 +vn -0.0553 -0.9983 0.0179 +vn -0.0210 -0.9997 0.0081 +vn -0.0267 -0.9996 -0.0053 +vn 0.0161 -0.9998 0.0117 +vn -0.0226 -0.9997 -0.0039 +vn 0.0007 -1.0000 0.0083 +vn -0.0173 -0.9997 -0.0187 +vn 0.0167 -0.9999 -0.0030 +vn -0.0356 -0.9989 0.0316 +vn -0.0253 -0.9995 -0.0174 +vn -0.1950 0.9804 -0.0280 +vn -0.0391 0.9960 -0.0810 +vn -0.1917 0.9811 -0.0280 +vn -0.0421 0.9958 -0.0819 +vn 0.7376 -0.0142 0.6751 +vn 0.6410 0.0445 0.7662 +vn 0.5557 0.0900 0.8265 +vn -0.3161 -0.0705 0.9461 +vn -0.5835 0.1962 0.7880 +vn -0.4256 -0.0261 0.9045 +vn -0.6476 0.1845 0.7393 +vn -0.9979 -0.0631 0.0111 +vn -0.9436 0.0350 -0.3291 +vn -0.9957 -0.0361 -0.0855 +vn -0.9077 0.0612 -0.4152 +vn -0.5222 -0.0066 -0.8528 +vn -0.3192 0.0682 -0.9452 +vn -0.4679 0.0145 -0.8837 +vn -0.2444 0.0933 -0.9652 +vn 0.7744 0.0460 -0.6311 +vn 0.7999 0.0184 -0.5998 +vn 0.7882 0.0314 -0.6147 +vn 0.7603 0.0604 -0.6467 +vn 0.8084 -0.0646 0.5851 +vn 0.5652 0.6838 0.4614 +vn 0.2041 0.7505 0.6286 +vn 0.1990 0.6542 0.7297 +vn -0.2182 0.6882 0.6920 +vn -0.3384 0.6984 0.6307 +vn -0.4743 0.6358 0.6089 +vn -0.7389 0.6736 0.0166 +vn -0.7435 0.6686 0.0099 +vn -0.7393 0.6731 0.0160 +vn -0.7359 0.6767 0.0209 +vn -0.4692 0.6951 -0.5448 +vn -0.4292 0.5723 -0.6987 +vn 0.0711 0.7486 -0.6592 +vn -0.3510 0.7322 -0.5837 +vn 0.1067 0.6457 -0.7561 +vn 0.5427 0.6800 -0.4930 +vn 0.6024 0.7038 -0.3766 +vn 0.7078 0.6439 -0.2904 +vn 0.7208 0.6461 0.2511 +vn 0.6273 0.7022 0.3368 +vn 0.3836 0.6393 0.6665 +vn 0.3819 0.5721 0.7259 +vn 0.3827 0.6915 0.6127 +vn 0.3814 0.7174 0.5830 +vn -0.5736 0.4889 0.6572 +vn -0.4534 0.8888 0.0669 +vn 0.6142 0.7364 -0.2835 +vn 0.0065 -0.9998 0.0176 +vn -0.0056 -0.9998 0.0179 +vn 0.0029 -0.9995 0.0316 +vn -0.0123 -0.9999 -0.0101 +vn 0.0163 -0.9976 -0.0672 +vn -0.0148 -0.9998 -0.0107 +vn 0.0028 -1.0000 0.0037 +vn -0.0199 -0.9998 0.0033 +vn 0.0098 -1.0000 -0.0010 +vn -0.0036 -1.0000 -0.0017 +vn 0.0414 -0.9962 -0.0760 +vn -0.0098 -0.9999 -0.0086 +vn -0.0162 -0.9991 0.0398 +vn -0.0826 0.9925 0.0904 +vn -0.1598 0.9615 0.2236 +vn -0.1482 0.9678 0.2035 +vn -0.1835 -0.0103 0.9830 +vn 0.0379 0.0900 0.9952 +vn -0.0398 0.0553 0.9977 +vn -0.2660 -0.0489 0.9627 +vn -0.9940 0.0160 0.1080 +vn -0.9807 0.0371 0.1918 +vn -0.9865 0.0294 0.1613 +vn -0.9961 0.0110 0.0880 +vn -0.8831 0.1021 -0.4580 +vn -0.4696 -0.0847 -0.8788 +vn 0.3703 0.1243 -0.9205 +vn 0.3687 0.1512 -0.9172 +vn 0.3684 0.1551 -0.9166 +vn 0.7804 -0.0969 -0.6177 +vn 0.8447 0.0510 0.5327 +vn 0.8967 0.0903 0.4332 +vn 0.8764 0.0740 0.4758 +vn 0.8209 0.0352 0.5699 +vn 0.5517 0.6737 0.4918 +vn 0.2192 0.7393 0.6367 +vn 0.0978 0.6749 0.7314 +vn -0.1650 0.6847 0.7099 +vn -0.1889 0.7030 0.6856 +vn -0.6732 0.6130 0.4136 +vn -0.7193 0.6685 0.1889 +vn -0.7050 0.6931 0.1503 +vn -0.7182 0.6958 0.0113 +vn -0.7485 0.6599 0.0652 +vn -0.6147 0.6500 -0.4468 +vn -0.4272 0.7056 -0.5653 +vn -0.4417 0.6942 -0.5684 +vn -0.2189 0.7014 -0.6784 +vn -0.1776 0.6862 -0.7054 +vn 0.0087 0.6507 -0.7592 +vn 0.4841 0.7034 -0.5205 +vn 0.5089 0.7307 -0.4551 +vn 0.6034 0.7065 -0.3698 +vn 0.6671 0.7450 0.0024 +vn 0.7480 0.6623 0.0430 +vn 0.1938 -0.8805 -0.4327 +vn -0.2405 0.8996 0.3645 +vn -0.3309 0.8465 -0.4171 +vn 0.3632 0.2201 -0.9054 +vn 0.5082 0.8610 0.0225 +vn 0.0132 -0.9998 0.0157 +vn 0.0078 -0.9999 0.0149 +vn 0.0069 -0.9996 0.0288 +vn -0.0237 -0.9996 0.0156 +vn -0.0235 -0.9997 -0.0092 +vn -0.0223 -0.9996 -0.0190 +vn 0.0191 -0.9998 0.0039 +vn -0.0090 -1.0000 -0.0020 +vn -0.0229 -0.9993 -0.0282 +vn 0.0004 -0.9995 -0.0313 +vn -0.0081 -0.9999 -0.0076 +vn 0.1017 0.9712 0.2153 +vn 0.1119 0.9853 0.1291 +vn 0.0699 0.9963 0.0491 +vn 0.1036 0.9930 -0.0563 +vn 0.4746 -0.0868 0.8759 +vn -0.6012 0.0289 0.7985 +vn -0.2433 0.0861 0.9661 +vn -0.5933 0.0761 0.8014 +vn -0.7183 0.0290 0.6952 +vn -0.8420 0.0768 0.5339 +vn -0.9761 -0.0723 -0.2051 +vn -0.7480 0.0988 -0.6563 +vn -0.7310 0.2322 -0.6416 +vn -0.7367 0.1983 -0.6465 +vn 0.0598 -0.0700 -0.9958 +vn 0.2704 0.0189 -0.9626 +vn 0.1278 -0.0418 -0.9909 +vn 0.3484 0.0531 -0.9358 +vn 0.9625 0.0229 -0.2703 +vn 0.9252 0.0617 -0.3746 +vn 0.9392 0.0486 -0.3399 +vn 0.9700 0.0128 -0.2428 +vn 0.8396 0.0885 0.5359 +vn 0.3449 0.6994 0.6260 +vn 0.3440 0.6999 0.6259 +vn 0.3441 0.6998 0.6260 +vn 0.3432 0.7003 0.6259 +vn -0.2703 0.5873 0.7629 +vn -0.3725 0.6672 0.6451 +vn -0.5279 0.6685 0.5238 +vn -0.6491 0.7333 0.2023 +vn -0.7386 0.6740 -0.0164 +vn -0.7044 0.6703 -0.2335 +vn -0.7162 0.6257 -0.3091 +vn -0.0813 0.6133 -0.7857 +vn -0.0345 0.6539 -0.7558 +vn -0.0205 0.6654 -0.7462 +vn 0.0395 0.7116 -0.7015 +vn 0.6840 0.5816 -0.4404 +vn 0.6852 0.6531 -0.3226 +vn 0.7436 0.6636 -0.0814 +vn 0.7203 0.6935 0.0154 +vn 0.7495 0.6042 0.2706 +vn 0.1827 0.8995 0.3968 +vn -0.6105 0.7759 0.1588 +vn -0.6743 0.4410 -0.5923 +vn -0.0544 0.8442 -0.5333 +vn 0.2225 0.0775 -0.9718 +vn 0.4095 0.0696 -0.9096 +vn 0.4084 0.0693 -0.9102 +vn 0.4098 0.0689 -0.9096 +vn 0.4099 0.0687 -0.9095 +vn 0.4099 0.0687 -0.9096 +vn 0.4099 0.0688 -0.9095 +vn 0.4101 0.0691 -0.9094 +vn 0.4105 0.0689 -0.9092 +vn 0.4100 0.0688 -0.9095 +vn 0.4093 0.0691 -0.9098 +vn 0.4098 0.0688 -0.9096 +vn 0.4098 0.0689 -0.9095 +vn 0.4100 0.0689 -0.9095 +vn 0.4099 0.0689 -0.9095 +vn 0.4053 0.0684 -0.9116 +vn 0.4019 0.0690 -0.9131 +vn 0.4100 0.0690 -0.9095 +vn 0.4111 0.0693 -0.9089 +vn 0.4095 0.0681 -0.9098 +vn 0.4099 0.0690 -0.9095 +vn 0.4084 0.0656 -0.9104 +vn 0.1672 0.0725 -0.9832 +vn 0.4063 0.0651 -0.9114 +vn 0.0103 -0.9991 0.0413 +vn -0.8370 0.3989 -0.3745 +vn -0.8337 0.4378 -0.3365 +vn -0.8161 0.5242 -0.2433 +vn -0.8353 0.3052 -0.4573 +vn -0.5037 -0.7925 -0.3439 +vn -0.5608 -0.7586 -0.3317 +vn -0.6793 -0.6701 -0.2991 +vn -0.3899 -0.8465 -0.3624 +vn 0.8905 0.3136 0.3297 +vn 0.8889 0.0016 0.4581 +vn 0.9019 0.1268 0.4130 +vn 0.2051 0.9656 0.1600 +vn 0.2563 0.9406 0.2227 +vn 0.3147 0.9021 0.2952 +vn 0.1386 0.9872 0.0794 +vn -0.6390 0.7332 -0.2328 +vn -0.6172 0.7633 -0.1909 +vn -0.5909 0.7938 -0.1439 +vn -0.6632 0.6926 -0.2838 +vn -0.8893 -0.2489 -0.3836 +vn -0.8866 -0.2913 -0.3593 +vn -0.8895 -0.1877 -0.4165 +vn -0.8813 -0.3360 -0.3323 +vn -0.3390 -0.8826 -0.3258 +vn 0.0181 -0.9956 0.0917 +vn 0.7310 -0.6663 0.1469 +vn 0.8490 -0.1588 0.5040 +vn -0.9263 0.0358 -0.3751 +vn -0.9170 0.0364 -0.3972 +vn -0.9266 0.0358 -0.3744 +vn -0.9167 0.0364 -0.3978 +vn -0.4130 -0.0705 0.9080 +vn -0.4139 -0.0688 0.9077 +vn -0.4111 -0.0682 0.9090 +vn -0.9044 -0.0283 0.4258 +vn -0.8996 -0.0288 0.4358 +vn -0.8997 -0.0288 0.4355 +vn -0.9044 -0.0283 0.4257 +vn -0.2941 0.6113 0.7347 +vn -0.2801 0.6687 0.6887 +vn -0.2739 0.6852 0.6749 +vn -0.2842 0.6605 0.6950 +vn -0.2846 0.6596 0.6956 +vn -0.2952 0.6067 0.7381 +vn 0.3038 0.1927 0.9330 +vn 0.3142 0.1260 0.9409 +vn 0.3132 0.4310 0.8462 +vn -0.0538 -0.0762 0.9956 +vn 0.3699 -0.0754 0.9260 +vn 0.3657 -0.0701 0.9281 +vn 0.3286 -0.0846 0.9407 +vn 0.3201 -0.2356 0.9176 +vn 0.3480 -0.0760 0.9344 +vn 0.3177 -0.3010 0.8991 +vn 0.3288 -0.0612 0.9424 +vn 0.3451 -0.4828 0.8049 +vn -0.3085 -0.7142 0.6283 +vn -0.2815 -0.7647 0.5797 +vn -0.2843 -0.7598 0.5848 +vn -0.3050 -0.7224 0.6205 +vn -0.3016 -0.7348 0.6075 +vn -0.3050 -0.7222 0.6208 +vn 0.7319 -0.5653 0.3805 +vn 0.6745 0.5914 0.4420 +vn -0.0049 -0.9968 -0.0799 +vn -0.0055 -0.9969 -0.0788 +vn -0.0056 -0.9967 -0.0815 +vn 0.0213 -0.9932 -0.1143 +vn -0.0067 -0.9976 -0.0684 +vn 0.0235 -0.9927 -0.1179 +vn 0.0053 0.9969 0.0781 +vn 0.0057 0.9970 0.0773 +vn 0.0055 0.9971 0.0765 +vn 0.0034 0.9962 0.0865 +vn 0.0543 0.9980 0.0318 +vn 0.0021 0.9957 0.0924 +vn 0.0654 0.9977 0.0192 +vn 0.9437 -0.0151 0.3305 +vn 0.9141 -0.0363 0.4039 +vn 0.9467 -0.0129 0.3218 +vn 0.9441 -0.0464 0.3263 +vn 0.9471 -0.0473 0.3174 +vn -0.4099 -0.0679 0.9096 +vn -0.4107 -0.0705 0.9090 +vn -0.4126 -0.0700 0.9082 +vn -0.4086 -0.0689 0.9101 +vn -0.4101 -0.0697 0.9094 +vn -0.4087 -0.0687 0.9101 +vn -0.4097 -0.0926 0.9075 +vn -0.4097 -0.0647 0.9099 +vn -0.4100 -0.0680 0.9096 +vn -0.4096 -0.0690 0.9096 +vn -0.4114 -0.0677 0.9089 +vn -0.4099 -0.0689 0.9095 +vn -0.4098 -0.0681 0.9096 +vn -0.4099 -0.0687 0.9095 +vn -0.4098 -0.0684 0.9096 +vn -0.4099 -0.0688 0.9095 +vn -0.4098 -0.0689 0.9096 +vn -0.4098 -0.0688 0.9096 +vn -0.4100 -0.0687 0.9095 +vn -0.4098 -0.0687 0.9096 +vn -0.4100 -0.0691 0.9095 +vn -0.4101 -0.0693 0.9094 +vn -0.4101 -0.0696 0.9094 +vn -0.4099 -0.0688 0.9096 +vn -0.4098 -0.0666 0.9097 +vn -0.4138 -0.0687 0.9078 +vn -0.4081 -0.0694 0.9103 +vn -0.4098 -0.0693 0.9096 +vn -0.4085 -0.0690 0.9101 +vn -0.4094 -0.0718 0.9095 +vn -0.4104 -0.0676 0.9094 +vn -0.4090 -0.0624 0.9104 +vn -0.4105 -0.0697 0.9092 +vn -0.4101 -0.0603 0.9100 +vn -0.4112 -0.0754 0.9084 +vn -0.4126 -0.0706 0.9082 +vn -0.4154 -0.0679 0.9071 +vn -0.4120 -0.0696 0.9085 +vn -0.4120 -0.0688 0.9086 +vn -0.4150 -0.0681 0.9072 +vn -0.4104 -0.0686 0.9093 +vn -0.4127 -0.0679 0.9083 +vn -0.4103 -0.0696 0.9093 +vn -0.4115 -0.0710 0.9087 +vn -0.4134 -0.0688 0.9080 +vn -0.2816 -0.0544 0.9580 +vn -0.4134 -0.0694 0.9079 +vn -0.4106 -0.1057 0.9057 +vn -0.4135 -0.0673 0.9080 +vn -0.4096 -0.0689 0.9097 +vn -0.4035 -0.0714 0.9122 +vn -0.3973 -0.0736 0.9147 +vn -0.4106 -0.0612 0.9097 +vn -0.4091 -0.0611 0.9105 +vn -0.4122 -0.0700 0.9084 +vn -0.4125 -0.0715 0.9081 +vn 0.0192 0.0820 -0.9964 +vn -0.0833 0.0744 -0.9937 +vn -0.4099 -0.0683 0.9096 +vn 0.5622 0.7660 0.3117 +vn 0.5834 0.7534 0.3034 +vn 0.4811 0.8079 0.3405 +vn 0.6579 0.7026 0.2711 +vn 0.8272 -0.0716 0.5574 +vn 0.8887 -0.0390 0.4568 +vn 0.8181 -0.0758 0.5701 +vn 0.8990 -0.0327 0.4368 +vn 0.7717 -0.6246 0.1200 +vn -0.0321 -0.9990 0.0315 +vn 0.0406 -0.9726 -0.2288 +vn 0.0470 -0.9668 -0.2511 +vn -0.0390 -0.9976 0.0565 +vn -0.6422 -0.7473 -0.1704 +vn -0.9157 0.0644 -0.3966 +vn -0.8480 0.0459 -0.5280 +vn -0.9243 0.0671 -0.3757 +vn -0.8379 0.0435 -0.5440 +vn -0.0118 0.9987 0.0498 +vn -0.0080 0.9993 0.0365 +vn -0.0123 0.9986 0.0514 +vn -0.0076 0.9994 0.0350 +vn -0.4855 -0.7065 0.5149 +vn -0.8254 -0.3539 0.4399 +vn -0.8048 -0.4645 0.3694 +vn -0.4219 -0.7186 0.5528 +vn -0.2057 -0.8078 0.5524 +vn 0.1938 -0.5532 0.8102 +vn 0.1942 -0.5548 0.8090 +vn 0.1884 -0.5264 0.8291 +vn 0.2017 -0.5926 0.7798 +vn 0.3825 0.1421 0.9130 +vn 0.3847 0.1454 0.9115 +vn 0.3677 0.1203 0.9221 +vn 0.3935 0.1587 0.9055 +vn -0.4165 0.6452 0.6405 +vn -0.1717 0.6661 0.7259 +vn -0.1541 0.6729 0.7235 +vn -0.4580 0.6179 0.6391 +vn -0.7737 0.4374 0.4583 +vn -0.8362 0.2948 0.4624 +vn -0.9339 0.0156 0.3571 +vn -0.7877 0.1097 -0.6063 +vn -0.6782 0.7270 -0.1072 +vn -0.6464 0.7515 -0.1320 +vn -0.5771 0.7963 -0.1816 +vn -0.7192 0.6909 -0.0730 +vn 0.1996 0.9459 0.2558 +vn 0.1741 0.9840 0.0384 +vn 0.1871 0.9722 0.1405 +vn 0.2076 0.9150 0.3459 +vn 0.8524 0.0650 0.5188 +vn 0.9288 0.2400 0.2824 +vn 0.9074 0.1695 0.3845 +vn 0.8045 -0.0011 0.5939 +vn 0.7225 -0.6910 -0.0223 +vn 0.0665 -0.9277 0.3674 +vn -0.2209 -0.7945 -0.5657 +vn -0.9084 -0.4124 -0.0687 +vn -0.8374 -0.4330 0.3335 +vn -0.8391 -0.4319 0.3308 +vn -0.8471 -0.4263 0.3172 +vn -0.8247 -0.4412 0.3539 +vn -0.2686 -0.7903 0.5507 +vn -0.2680 -0.7897 0.5519 +vn -0.2729 -0.7948 0.5420 +vn -0.2602 -0.7814 0.5671 +vn 0.2551 -0.5072 0.8232 +vn 0.2431 -0.5115 0.8242 +vn 0.1533 -0.5407 0.8271 +vn 0.3124 -0.4852 0.8167 +vn 0.3584 0.1427 0.9226 +vn 0.3607 0.1471 0.9210 +vn 0.3279 0.0865 0.9407 +vn 0.3815 0.1870 0.9053 +vn -0.1821 0.6905 0.7001 +vn -0.1704 0.6630 0.7290 +vn -0.1805 0.6868 0.7041 +vn -0.1883 0.7049 0.6839 +vn -0.8367 0.3870 0.3875 +vn -0.8399 0.3858 0.3818 +vn -0.8182 0.3933 0.4194 +vn -0.8509 0.3815 0.3613 +vn -0.6953 0.6814 -0.2286 +vn -0.6758 0.6091 -0.4151 +vn -0.6872 0.6421 -0.3399 +vn -0.6950 0.7041 -0.1458 +vn 0.2146 0.9703 0.1120 +vn 0.2249 0.9491 0.2205 +vn 0.2052 0.9783 0.0303 +vn 0.2308 0.9255 0.3004 +vn 0.8543 0.0548 0.5169 +vn 0.9280 0.2032 0.3122 +vn 0.9050 0.1426 0.4008 +vn 0.8128 -0.0001 0.5825 +vn 0.7306 -0.6812 0.0461 +vn 0.0696 -0.9958 0.0595 +vn 0.0914 -0.9779 0.1879 +vn 0.1082 -0.9505 0.2911 +vn 0.0396 -0.9934 -0.1077 +vn -0.8443 -0.4528 -0.2866 +vn -0.7098 -0.5319 -0.4618 +vn -0.7698 -0.5030 -0.3929 +vn -0.8808 -0.4189 -0.2207 +vn -0.9132 -0.2259 0.3393 +vn -0.9202 -0.0571 0.3872 +vn -0.9335 0.1260 0.3357 +vn -0.8299 -0.4211 0.3660 +vn -0.8086 -0.4843 0.3341 +vn -0.0843 -0.7243 0.6843 +vn -0.2850 -0.7456 0.6023 +vn -0.3197 -0.7723 0.5489 +vn 0.0679 -0.5574 0.8274 +vn 0.3264 -0.3077 0.8937 +vn 0.3611 -0.0950 0.9277 +vn 0.4411 0.0278 0.8970 +vn 0.0873 0.5290 0.8441 +vn 0.1032 0.4263 0.8987 +vn 0.0873 0.5289 0.8442 +vn 0.0734 0.6069 0.7914 +vn -0.5619 0.6381 0.5264 +vn -0.5619 0.6380 0.5265 +vn -0.5780 0.6155 0.5357 +vn -0.5322 0.6765 0.5090 +vn -0.8698 0.2290 0.4371 +vn -0.7785 0.5586 -0.2862 +vn -0.7663 0.6105 -0.2002 +vn -0.7774 0.4256 -0.4631 +vn -0.7268 0.6853 -0.0472 +vn -0.2591 0.9302 -0.2599 +vn 0.1624 0.8873 0.4317 +vn 0.6967 0.7135 0.0742 +vn 0.9225 -0.1838 0.3395 +vn 0.8526 -0.0789 0.5165 +vn 0.7850 -0.0080 0.6195 +vn 0.9461 -0.2557 0.1987 +vn 0.1428 -0.9885 -0.0494 +vn 0.1476 -0.9812 0.1246 +vn 0.1484 -0.9658 0.2126 +vn 0.1379 -0.9789 -0.1507 +vn -0.8541 -0.4287 -0.2944 +vn -0.8365 -0.4430 -0.3225 +vn -0.8651 -0.4190 -0.2758 +vn -0.8202 -0.4551 -0.3467 +vn -0.9474 -0.0345 0.3183 +vn -0.9502 -0.0266 0.3104 +vn -0.9581 -0.0030 0.2865 +vn -0.9332 -0.0691 0.3526 +vn -0.5105 -0.7399 0.4381 +vn -0.5186 -0.7429 0.4233 +vn -0.5451 -0.7514 0.3718 +vn -0.4636 -0.7198 0.5166 +vn 0.2050 -0.6208 0.7567 +vn 0.2060 -0.6207 0.7565 +vn 0.1788 -0.6230 0.7615 +vn 0.2203 -0.6193 0.7537 +vn 0.2790 0.1748 0.9442 +vn 0.3150 -0.1015 0.9437 +vn 0.3826 0.0265 0.9235 +vn 0.2484 0.3451 0.9051 +vn 0.1137 0.5032 0.8567 +vn 0.0980 0.5756 0.8118 +vn -0.5535 0.6309 0.5437 +vn -0.5371 0.6218 0.5700 +vn -0.5512 0.6296 0.5474 +vn -0.5628 0.6358 0.5283 +vn -0.7248 -0.0066 -0.6889 +vn -0.9012 0.4328 -0.0231 +vn -0.1881 0.8999 -0.3934 +vn 0.0669 0.8792 0.4717 +vn 0.7110 0.6937 0.1152 +vn 0.8247 -0.0223 0.5652 +vn 0.8450 -0.0431 0.5330 +vn 0.8759 -0.0785 0.4760 +vn 0.8027 -0.0013 0.5963 +vn 0.6676 -0.7439 0.0300 +vn 0.1772 -0.9384 0.2967 +vn -0.1384 -0.9033 -0.4060 +vn -0.7539 -0.6532 -0.0703 +vn -0.9410 0.0341 0.3368 +vn -0.9426 0.0309 0.3324 +vn -0.9606 -0.0080 0.2777 +vn -0.9272 0.0583 0.3701 +vn -0.7126 -0.5638 0.4175 +vn -0.7005 -0.5693 0.4304 +vn -0.8047 -0.5098 0.3041 +vn -0.5789 -0.6105 0.5405 +vn 0.1698 -0.5801 0.7967 +vn -0.0282 -0.7421 0.6697 +vn -0.1050 -0.8605 0.4986 +vn 0.2878 -0.2933 0.9116 +vn 0.3598 0.0786 0.9297 +vn 0.2000 0.2822 0.9383 +vn 0.0914 0.5094 0.8557 +vn -0.0319 0.5728 0.8191 +vn -0.0658 0.6328 0.7715 +vn -0.6156 0.5954 0.5162 +vn -0.6160 0.5949 0.5164 +vn -0.5912 0.6296 0.5041 +vn -0.6490 0.5438 0.5320 +vn -0.7965 0.0563 -0.6021 +vn -0.8968 0.4392 -0.0525 +vn -0.3852 0.8372 -0.3883 +vn 0.2133 0.9145 0.3438 +vn 0.1025 0.9057 0.4113 +vn 0.3828 0.8963 0.2238 +vn 0.4983 0.8575 0.1281 +vn 0.8408 0.0178 0.5411 +vn 0.8522 0.0085 0.5231 +vn 0.8618 0.0003 0.5073 +vn 0.8244 0.0306 0.5653 +vn 0.6940 -0.7199 -0.0128 +vn 0.1579 -0.9305 0.3304 +vn -0.2899 -0.8288 -0.4786 +vn -0.7341 -0.6615 -0.1530 +vn -0.9012 -0.2162 0.3757 +vn -0.7735 -0.5153 0.3690 +vn -0.5620 -0.6555 0.5044 +vn -0.1875 -0.7542 0.6293 +vn 0.0816 -0.5589 0.8252 +vn 0.3023 -0.3847 0.8722 +vn 0.3368 -0.1944 0.9213 +vn 0.3882 -0.1343 0.9118 +vn 0.2076 0.4643 0.8610 +vn 0.0026 0.5444 0.8388 +vn 0.2045 0.3923 0.8968 +vn -0.1275 0.6286 0.7672 +vn -0.5180 0.5940 0.6154 +vn -0.6233 0.5783 0.5264 +vn -0.8478 0.2891 0.4446 +vn -0.9235 0.1243 0.3628 +vn -0.8513 0.1240 -0.5098 +vn -0.8959 0.4403 -0.0588 +vn -0.5495 0.7656 -0.3345 +vn 0.0918 0.9463 0.3101 +vn 0.0488 0.9975 0.0520 +vn 0.0744 0.9762 0.2037 +vn 0.1062 0.9098 0.4012 +vn 0.7667 0.6207 0.1641 +vn 0.7779 -0.0041 0.6284 +vn 0.9449 -0.2818 0.1664 +vn 0.1690 -0.9830 -0.0720 +vn 0.1907 -0.9738 0.1242 +vn 0.2011 -0.9467 0.2518 +vn 0.1504 -0.9673 -0.2043 +vn -0.7258 -0.6154 -0.3075 +vn -0.7242 -0.6404 -0.2558 +vn -0.7199 -0.6642 -0.2012 +vn -0.7239 -0.5760 -0.3797 +vn 0.0161 0.9981 0.0601 +vn 0.0109 0.9980 0.0618 +vn 0.0404 0.9978 0.0520 +vn -0.0116 0.9975 0.0692 +vn 0.7068 -0.6807 0.1926 +vn 0.7362 -0.6266 0.2558 +vn 0.6572 -0.7467 0.1028 +vn 0.7734 -0.5212 0.3607 +vn 0.8267 0.4073 0.3881 +vn 0.8260 0.4132 0.3835 +vn 0.8247 0.4223 0.3762 +vn 0.8277 0.3989 0.3947 +vn -0.3941 -0.0954 0.9141 +vn -0.3876 -0.0675 0.9194 +vn -0.3948 -0.0837 0.9150 +vn -0.4266 -0.0733 0.9015 +vn -0.4454 -0.0722 0.8924 +vn -0.4327 -0.0748 0.8984 +vn -0.4333 -0.0634 0.8990 +vn -0.4071 -0.0960 0.9083 +vn -0.3934 -0.1097 0.9128 +vn -0.4065 -0.0487 0.9124 +vn -0.3930 -0.0511 0.9181 +vn -0.4034 -0.0357 0.9143 +vn -0.4192 -0.0446 0.9068 +vn 0.3868 0.0800 -0.9187 +vn 0.3945 0.0899 -0.9145 +vn 0.3778 0.1332 -0.9163 +vn 0.4066 0.1457 -0.9019 +vn 0.3678 0.1364 -0.9198 +vn -0.7113 0.6565 -0.2510 +vn -0.6971 0.6555 -0.2903 +vn -0.8522 0.3461 -0.3924 +vn -0.8038 -0.4627 -0.3738 +vn -0.8607 -0.2787 -0.4260 +vn -0.8542 -0.3079 -0.4190 +vn -0.7956 -0.4818 -0.3672 +vn -0.0510 -0.9952 -0.0830 +vn -0.2727 -0.9344 -0.2290 +vn -0.2496 -0.9445 -0.2134 +vn -0.0192 -0.9978 -0.0633 +vn 0.6861 -0.6800 0.2584 +vn 0.5912 -0.7848 0.1862 +vn 0.6062 -0.7705 0.1972 +vn 0.6964 -0.6663 0.2666 +vn 0.8722 0.2301 0.4316 +vn 0.9185 -0.1587 0.3622 +vn 0.9208 -0.1083 0.3748 +vn 0.8551 0.2807 0.4359 +vn 0.2829 0.9352 0.2129 +vn 0.4880 0.8267 0.2800 +vn 0.4653 0.8443 0.2659 +vn 0.2456 0.9476 0.2042 +vn -0.6672 0.7095 -0.2267 +vn -0.4284 0.8914 -0.1480 +vn -0.2935 0.4013 -0.8677 +vn -0.2855 0.1441 -0.9475 +vn -0.3965 0.0248 -0.9177 +vn -0.2583 -0.3352 -0.9060 +vn 0.0032 -0.5200 -0.8542 +vn 0.0354 -0.6121 -0.7900 +vn 0.3856 -0.6624 -0.6423 +vn 0.5559 -0.5758 -0.5995 +vn 0.7794 -0.4512 -0.4346 +vn 0.9123 -0.0923 -0.3989 +vn 0.9433 0.0601 -0.3266 +vn 0.7382 0.5186 -0.4314 +vn 0.7697 0.5149 -0.3774 +vn 0.4068 0.7554 -0.5137 +vn 0.3535 0.7549 -0.5523 +vn 0.1697 0.8064 -0.5666 +vn -0.1922 0.5289 -0.8266 +vn -0.1854 0.5307 -0.8270 +vn 0.1845 0.9799 -0.0757 +vn -0.0948 0.9886 0.1167 +vn 0.0535 0.9985 0.0153 +vn -0.2247 0.9528 0.2041 +vn 0.8054 -0.5865 0.0852 +vn 0.7859 -0.4690 0.4030 +vn 0.8079 -0.5389 0.2386 +vn 0.7447 -0.3938 0.5388 +vn -0.7292 -0.3493 -0.5885 +vn -0.7856 -0.5354 -0.3101 +vn -0.7669 -0.4436 -0.4639 +vn -0.7808 -0.6028 -0.1643 +vn -0.0426 -0.1984 -0.9792 +vn -0.2572 -0.9301 -0.2621 +vn 0.5105 -0.3703 -0.7761 +vn 0.8087 0.1071 -0.5784 +vn 0.4504 0.8177 0.3586 +vn 0.3401 0.4132 -0.8448 +vn -0.6858 -0.4674 -0.5579 +vn -0.7962 -0.4691 -0.3821 +vn -0.8123 -0.3873 -0.4360 +vn -0.8938 -0.1859 -0.4081 +vn -0.6161 -0.7222 -0.3145 +vn -0.0354 -0.9762 -0.2141 +vn 0.0714 -0.9971 -0.0269 +vn 0.0490 -0.9980 -0.0412 +vn -0.1009 -0.9788 -0.1784 +vn 0.8102 -0.5369 0.2350 +vn 0.7582 -0.5796 0.2988 +vn 0.6537 -0.7491 0.1077 +vn 0.8857 -0.2531 0.3892 +vn 0.8972 -0.2529 0.3620 +vn 0.8977 0.0984 0.4295 +vn 0.5053 0.8213 0.2650 +vn 0.5588 0.7700 0.3079 +vn 0.6725 0.6651 0.3246 +vn 0.2019 0.9638 0.1741 +vn -0.2196 0.9740 -0.0555 +vn -0.5578 0.8108 -0.1777 +vn -0.6978 0.6087 -0.3776 +vn -0.8030 0.3275 -0.4979 +vn -0.8103 0.4885 -0.3238 +vn 0.9089 -0.2559 0.3292 +vn 0.6291 -0.7668 -0.1276 +vn 0.0964 -0.9324 -0.3484 +vn -0.0352 -0.9655 -0.2580 +vn -0.4478 -0.5114 -0.7334 +vn -0.7105 -0.4351 -0.5530 +vn -0.6981 0.2021 -0.6869 +vn -0.4802 0.8295 -0.2852 +vn 0.0977 0.8980 -0.4289 +vn 0.6873 0.6591 0.3052 +vn 0.9824 0.1866 0.0043 +vn 0.6649 -0.0232 -0.7465 +vn 0.7647 0.0096 -0.6443 +vn 0.6900 -0.1947 -0.6972 +vn 0.5107 0.4484 -0.7335 +vn 0.4559 0.3125 -0.8334 +vn 0.1907 0.3338 -0.9231 +vn 0.0245 0.2247 -0.9741 +vn 0.1641 0.0350 -0.9858 +vn 0.0070 0.0022 -1.0000 +vn 0.2591 -0.2208 -0.9403 +vn 0.4941 -0.2485 -0.8332 +vn 0.6782 0.2494 -0.6913 +vn 0.4479 -0.0530 -0.8925 +vn -0.2662 -0.2326 0.9354 +vn -0.4797 -0.0013 0.8774 +vn -0.5212 -0.3213 0.7907 +vn -0.6727 -0.0286 0.7393 +vn -0.6841 -0.2594 0.6817 +vn -0.4941 -0.4713 0.7306 +vn -0.4695 0.2293 0.8526 +vn -0.5966 0.2692 0.7561 +vn -0.2782 0.3453 0.8963 +vn -0.1407 0.0942 0.9856 +vn -0.0369 0.1452 0.9887 +vn -0.0506 -0.1623 0.9854 +vn -0.1979 -0.4006 0.8946 +vn -0.7656 -0.4986 -0.4066 +vn -0.7339 -0.5737 -0.3637 +vn -0.8463 -0.3132 -0.4309 +vn -0.8940 -0.1836 -0.4087 +vn -0.5715 -0.7539 -0.3241 +vn -0.4384 -0.8640 -0.2477 +vn 0.5335 -0.8448 0.0412 +vn 0.1343 -0.9907 -0.0216 +vn 0.1431 -0.9892 -0.0312 +vn 0.1338 -0.9908 -0.0218 +vn 0.9380 -0.2581 0.2313 +vn 0.7995 -0.5017 0.3303 +vn 0.6588 -0.7100 0.2489 +vn 0.9022 0.1048 0.4184 +vn 0.8409 0.3717 0.3934 +vn 0.7675 0.5214 0.3729 +vn 0.8022 0.4502 0.3922 +vn 0.3507 0.9328 0.0830 +vn 0.3519 0.9108 0.2160 +vn 0.3513 0.9307 0.1018 +vn -0.4223 0.8820 -0.2092 +vn -0.5020 0.8508 -0.1550 +vn -0.1846 0.9828 0.0047 +vn -0.6308 0.6855 -0.3636 +vn -0.7687 0.4229 -0.4799 +vn -0.7494 0.5946 -0.2913 +vn 0.8106 -0.5846 -0.0344 +vn 0.2987 -0.9466 -0.1211 +vn 0.3032 -0.4505 -0.8397 +vn -0.0499 -0.7812 -0.6223 +vn 0.0543 -0.3772 -0.9245 +vn -0.8329 -0.3058 -0.4613 +vn -0.6772 0.2900 -0.6762 +vn -0.3176 0.8952 -0.3125 +vn 0.3349 0.9315 -0.1419 +vn 0.9769 -0.1949 -0.0873 +vn 0.6298 0.3728 -0.6814 +vn 0.7584 0.1785 -0.6269 +vn 0.6892 0.0776 -0.7204 +vn 0.6088 -0.1584 -0.7773 +vn 0.2507 -0.2300 -0.9403 +vn 0.0744 0.3186 -0.9450 +vn 0.1548 0.1581 -0.9752 +vn 0.0135 0.0257 -0.9996 +vn 0.4876 0.3115 -0.8156 +vn 0.3183 0.4073 -0.8560 +vn 0.4450 -0.0398 -0.8946 +vn -0.6935 -0.2942 0.6577 +vn -0.4150 -0.5262 0.7422 +vn -0.5512 -0.3903 0.7375 +vn -0.6510 0.0158 0.7589 +vn -0.4334 -0.1509 0.8885 +vn -0.7595 0.0351 0.6496 +vn -0.5799 0.2986 0.7580 +vn -0.3953 0.2189 0.8921 +vn -0.3286 0.3676 0.8700 +vn -0.1229 0.2642 0.9566 +vn -0.0710 0.1093 0.9915 +vn -0.1846 -0.1058 0.9771 +vn 0.0432 -0.0390 0.9983 +vn -0.0480 -0.2690 0.9620 +vn -0.2591 -0.3838 0.8863 +vn -0.1825 -0.4564 0.8709 +vn -0.4334 -0.0783 0.8978 +vn -0.4371 -0.0663 0.8970 +vn -0.4368 -0.0897 0.8951 +vn -0.4196 -0.0496 0.9064 +vn -0.4048 -0.0402 0.9135 +vn -0.4280 -0.0498 0.9024 +vn -0.4408 -0.0961 0.8925 +vn -0.4041 -0.0881 0.9105 +vn -0.3932 -0.0842 0.9156 +vn -0.3986 -0.0326 0.9166 +vn -0.3907 -0.0579 0.9187 +vn -0.3861 -0.0873 0.9183 +vn -0.3788 -0.0723 0.9226 +vn -0.3770 -0.0972 0.9211 +vn -0.4003 -0.0482 0.9151 +vn 0.4489 0.1562 -0.8798 +vn 0.2974 0.0470 -0.9536 +vn 0.3236 0.0389 -0.9454 +vn 0.6808 -0.2116 -0.7012 +vn 0.5495 0.0832 -0.8313 +vn -0.7726 0.5606 -0.2981 +vn -0.7224 0.6186 -0.3091 +vn -0.8075 0.4989 -0.3147 +vn -0.8804 0.2668 -0.3921 +vn -0.8498 -0.3487 -0.3953 +vn -0.7610 -0.5137 -0.3963 +vn -0.8422 -0.3658 -0.3960 +vn -0.7492 -0.5313 -0.3955 +vn -0.3035 -0.9233 -0.2356 +vn -0.2462 -0.9498 -0.1931 +vn -0.2525 -0.9472 -0.1978 +vn -0.3123 -0.9186 -0.2421 +vn 0.2640 -0.9618 0.0718 +vn 0.8189 -0.4573 0.3468 +vn 0.7260 -0.6390 0.2541 +vn 0.7421 -0.6140 0.2687 +vn 0.8298 -0.4265 0.3599 +vn 0.7556 0.5339 0.3795 +vn 0.9032 0.1624 0.3973 +vn 0.8261 0.4088 0.3878 +vn 0.7383 0.5613 0.3741 +vn 0.7110 0.6064 0.3560 +vn 0.0115 0.9960 0.0890 +vn -0.0165 0.9975 0.0693 +vn 0.0091 0.9961 0.0874 +vn -0.0201 0.9976 0.0668 +vn -0.4807 0.8544 -0.1973 +vn -0.4062 -0.0992 -0.9084 +vn -0.3545 -0.1492 -0.9231 +vn -0.2786 -0.3230 -0.9045 +vn -0.1421 -0.4248 -0.8941 +vn 0.0406 -0.6172 -0.7858 +vn 0.2861 -0.6457 -0.7079 +vn 0.3521 -0.6685 -0.6551 +vn 0.7076 -0.4825 -0.5162 +vn 0.6279 -0.5741 -0.5255 +vn 0.8691 -0.3035 -0.3905 +vn 0.9155 0.1026 -0.3889 +vn 0.9428 0.0858 -0.3223 +vn 0.8260 0.4387 -0.3541 +vn 0.5916 0.6363 -0.4951 +vn 0.6018 0.6661 -0.4407 +vn 0.2132 0.7665 -0.6059 +vn -0.0174 0.6403 -0.7679 +vn -0.1827 0.5856 -0.7898 +vn -0.2796 0.4304 -0.8583 +vn -0.2770 0.4189 -0.8648 +vn -0.8647 0.3467 -0.3636 +vn -0.9279 0.2548 -0.2721 +vn -0.9077 0.2880 -0.3052 +vn -0.9555 0.1998 -0.2171 +vn 0.3319 0.9430 0.0225 +vn 0.2208 0.9711 0.0907 +vn 0.2638 0.9624 0.0648 +vn 0.1407 0.9805 0.1375 +vn 0.8647 -0.3464 0.3636 +vn 0.8334 -0.2706 0.4819 +vn 0.8465 -0.2981 0.4411 +vn 0.8077 -0.2246 0.5451 +vn -0.1840 -0.9183 -0.3505 +vn -0.1595 -0.9608 -0.2266 +vn -0.1693 -0.9466 -0.2746 +vn -0.1407 -0.9805 -0.1375 +vn 0.0258 -0.0104 -0.9996 +vn 0.1839 -0.6280 -0.7562 +vn 0.8217 -0.4680 -0.3252 +vn 0.7472 -0.1572 -0.6457 +vn 0.5869 0.4380 -0.6810 +vn -0.4281 -0.0809 0.9001 +vn -0.4164 -0.0917 0.9046 +vn -0.4300 -0.0741 0.8998 +vn -0.3947 -0.0808 0.9152 +vn -0.3645 -0.0915 0.9267 +vn -0.3870 -0.0634 0.9199 +vn -0.4496 -0.0663 0.8907 +vn -0.4355 -0.0573 0.8983 +vn -0.4060 -0.0830 0.9101 +vn -0.4103 -0.0478 0.9107 +vn -0.4209 -0.0457 0.9060 +vn -0.3962 -0.0278 0.9177 +vn -0.3990 -0.0398 0.9161 +vn -0.3753 -0.0712 0.9242 +vn 0.4746 -0.0652 -0.8778 +vn 0.4149 0.1023 -0.9041 +vn 0.3997 0.1144 -0.9095 +vn 0.4351 -0.1096 -0.8937 +vn 0.4284 0.1379 -0.8930 +vn 0.4654 0.1682 -0.8690 +vn -0.9020 -0.0920 -0.4217 +vn -0.8951 -0.0614 -0.4417 +vn -0.8883 -0.0652 -0.4546 +vn -0.9019 -0.0969 -0.4209 +vn -0.5803 -0.7559 -0.3030 +vn -0.3540 -0.9008 -0.2513 +vn -0.5561 -0.7758 -0.2981 +vn -0.3303 -0.9115 -0.2452 +vn 0.2074 -0.9780 0.0237 +vn 0.2078 -0.9779 0.0238 +vn 0.2078 -0.9779 0.0239 +vn 0.8949 -0.2156 0.3906 +vn 0.9018 -0.3091 0.3022 +vn 0.8969 -0.2945 0.3299 +vn 0.8961 -0.2020 0.3952 +vn 0.5893 0.7285 0.3494 +vn 0.7996 0.4701 0.3736 +vn 0.7745 0.5112 0.3727 +vn 0.5597 0.7540 0.3439 +vn 0.0812 0.9936 0.0780 +vn -0.4880 0.8630 -0.1306 +vn -0.6003 0.7681 -0.2226 +vn -0.5037 0.8520 -0.1430 +vn -0.6195 0.7476 -0.2393 +vn -0.4386 0.1905 -0.8783 +vn -0.3806 0.0852 -0.9208 +vn -0.3623 -0.0796 -0.9287 +vn -0.2384 -0.2725 -0.9322 +vn -0.1742 -0.4695 -0.8656 +vn 0.1518 -0.6131 -0.7753 +vn 0.2426 -0.6581 -0.7128 +vn 0.7425 -0.4256 -0.5173 +vn 0.5685 -0.6150 -0.5465 +vn 0.8386 -0.3642 -0.4051 +vn 0.9374 -0.0025 -0.3483 +vn 0.8729 0.2598 -0.4131 +vn 0.8864 0.3307 -0.3238 +vn 0.6897 0.5945 -0.4134 +vn 0.3441 0.7026 -0.6229 +vn 0.3599 0.7792 -0.5131 +vn 0.0387 0.7145 -0.6986 +vn -0.0632 0.6403 -0.7655 +vn -0.1046 0.6355 -0.7650 +vn -0.0947 0.9886 0.1167 +vn -0.2246 0.9528 0.2041 +vn 0.7859 -0.4690 0.4031 +vn 0.7447 -0.3937 0.5390 +vn -0.7293 -0.3494 -0.5883 +vn -0.7670 -0.4436 -0.4636 +vn -0.4097 -0.0687 0.9096 +vn -0.8312 -0.0651 -0.5522 +vn 0.0446 -0.4386 -0.8976 +vn 0.5578 -0.4386 -0.7046 +vn 0.9507 -0.3039 0.0621 +vn 0.5262 0.2948 -0.7976 +vn -0.4095 -0.0493 0.9110 +vn -0.3934 -0.0657 0.9170 +vn -0.4159 -0.0384 0.9086 +vn -0.3925 -0.0775 0.9165 +vn -0.3766 -0.0723 0.9236 +vn -0.3829 -0.0693 0.9212 +vn -0.4252 -0.0752 0.9019 +vn -0.4412 -0.0628 0.8952 +vn -0.4216 -0.0806 0.9032 +vn -0.4325 -0.0614 0.8995 +vn -0.4191 -0.0278 0.9075 +vn -0.4220 -0.0465 0.9054 +vn -0.4167 -0.1002 0.9035 +vn -0.4121 -0.0940 0.9063 +vn -0.3899 -0.0858 0.9168 +vn 0.3956 -0.0052 -0.9184 +vn 0.3306 0.0277 -0.9434 +vn 0.3237 0.0806 -0.9427 +vn 0.4184 0.0470 -0.9071 +vn 0.3817 -0.0092 -0.9243 +vn -0.8861 -0.2205 -0.4078 +vn -0.9019 0.0490 -0.4291 +vn -0.8456 -0.3134 -0.4321 +vn -0.8655 -0.2953 -0.4045 +vn -0.6718 -0.6349 -0.3815 +vn -0.2361 -0.9603 -0.1488 +vn 0.0923 -0.9945 -0.0503 +vn 0.1710 -0.9851 0.0177 +vn 0.5070 -0.8516 0.1334 +vn 0.7647 -0.5668 0.3065 +vn 0.7900 -0.5433 0.2841 +vn 0.8909 -0.2208 0.3970 +vn 0.5803 0.7388 0.3426 +vn 0.8483 0.3830 0.3655 +vn 0.8184 0.4423 0.3668 +vn 0.5294 0.7802 0.3332 +vn -0.2237 0.9741 -0.0340 +vn 0.0464 0.9982 -0.0370 +vn -0.2488 0.9636 -0.0981 +vn -0.5350 0.8269 -0.1733 +vn -0.5603 0.8018 -0.2079 +vn -0.7615 0.5828 -0.2838 +vn -0.3274 0.3406 -0.8814 +vn -0.3196 0.1909 -0.9281 +vn -0.3632 -0.0334 -0.9311 +vn -0.1220 -0.4235 -0.8977 +vn -0.2896 -0.3159 -0.9035 +vn -0.0310 -0.5716 -0.8200 +vn 0.4118 -0.6344 -0.6542 +vn 0.3609 -0.6693 -0.6494 +vn 0.7165 -0.5166 -0.4688 +vn 0.8198 -0.3457 -0.4565 +vn 0.9171 -0.1718 -0.3597 +vn 0.8752 0.2724 -0.3998 +vn 0.9089 0.2767 -0.3121 +vn 0.7124 0.5762 -0.4005 +vn 0.4087 0.7128 -0.5700 +vn 0.4730 0.7314 -0.4912 +vn 0.1227 0.7539 -0.6454 +vn -0.0917 0.6181 -0.7808 +vn -0.1668 0.5868 -0.7923 +vn 0.8054 -0.5866 0.0855 +vn 0.7858 -0.4692 0.4030 +vn 0.8078 -0.5390 0.2388 +vn 0.7447 -0.3940 0.5388 +vn -0.7293 -0.3497 -0.5880 +vn -0.7856 -0.5354 -0.3102 +vn -0.7669 -0.4437 -0.4636 +vn -0.7808 -0.6027 -0.1647 +vn 0.0244 0.2193 -0.9754 +vn 0.3003 -0.2098 -0.9305 +vn 0.7570 0.3439 -0.5557 +vn 0.2226 0.9237 -0.3117 +vn -0.4118 -0.0887 0.9069 +vn -0.4015 -0.1023 0.9101 +vn -0.3959 -0.0881 0.9141 +vn -0.4232 -0.0605 0.9040 +vn -0.4368 -0.0730 0.8966 +vn -0.4312 -0.0801 0.8987 +vn -0.4313 -0.0620 0.9001 +vn -0.4163 -0.0953 0.9042 +vn -0.4123 -0.0094 0.9110 +vn -0.3946 -0.0608 0.9168 +vn -0.3984 -0.0217 0.9169 +vn -0.3883 -0.0703 0.9188 +vn -0.3848 -0.0526 0.9215 +vn 0.4936 -0.0555 -0.8679 +vn 0.2997 0.0245 -0.9537 +vn 0.3168 0.0957 -0.9437 +vn 0.5045 0.0283 -0.8629 +vn 0.3796 -0.0415 -0.9242 +vn -0.8624 0.3768 -0.3382 +vn -0.8989 0.1110 -0.4239 +vn -0.8712 0.3429 -0.3512 +vn -0.8984 0.0744 -0.4329 +vn -0.6749 -0.6510 -0.3475 +vn -0.6864 -0.6336 -0.3568 +vn -0.6847 -0.6362 -0.3555 +vn -0.6734 -0.6532 -0.3462 +vn 0.1667 -0.9860 -0.0007 +vn 0.1868 -0.9824 -0.0068 +vn 0.1693 -0.9856 -0.0002 +vn 0.1917 -0.9814 -0.0124 +vn 0.8421 -0.4236 0.3338 +vn 0.8613 -0.3557 0.3628 +vn 0.8590 -0.3649 0.3591 +vn 0.8393 -0.4320 0.3300 +vn 0.8714 0.2713 0.4088 +vn 0.8348 0.3960 0.3825 +vn 0.8674 0.2883 0.4057 +vn 0.8298 0.4096 0.3791 +vn 0.3965 0.8778 0.2687 +vn 0.0357 0.9974 0.0620 +vn 0.0386 0.9940 0.1021 +vn -0.2571 0.9640 -0.0684 +vn -0.3306 0.9405 -0.0790 +vn -0.4971 0.8496 -0.1762 +vn -0.2882 0.4302 -0.8555 +vn -0.3002 -0.0494 -0.9526 +vn -0.3820 0.0480 -0.9229 +vn -0.2409 -0.3739 -0.8956 +vn 0.1102 -0.5846 -0.8038 +vn 0.0729 -0.6266 -0.7759 +vn 0.4875 -0.6467 -0.5867 +vn 0.6983 -0.4887 -0.5230 +vn 0.8026 -0.4219 -0.4217 +vn 0.9343 -0.0490 -0.3531 +vn 0.9316 -0.0152 -0.3631 +vn 0.8590 0.3835 -0.3393 +vn 0.7807 0.4761 -0.4048 +vn 0.5988 0.6709 -0.4374 +vn 0.3307 0.7272 -0.6016 +vn 0.2570 0.7444 -0.6163 +vn -0.1441 0.5496 -0.8229 +vn -0.0269 0.6750 -0.7373 +vn -0.3592 0.3533 0.8638 +vn -0.4842 0.5841 -0.6515 +vn -0.3956 0.9026 0.1698 +vn 0.9031 0.3788 0.2025 +vn 0.9199 0.3551 0.1664 +vn 0.9130 0.3653 0.1818 +vn 0.9313 0.3367 0.1389 +vn 0.0628 -0.8877 -0.4560 +vn 0.2224 -0.9483 0.2265 +vn -0.9279 -0.3372 -0.1588 +vn -0.4100 -0.0689 0.9095 +vn 0.0238 0.2196 -0.9753 +vn 0.2407 -0.2539 -0.9368 +vn 0.2166 -0.9738 -0.0689 +vn 0.7568 -0.2128 -0.6181 +vn 0.8185 0.3901 -0.4218 +vn 0.2711 0.8813 -0.3871 +vn -0.3901 -0.0838 0.9169 +vn -0.3830 -0.0737 0.9208 +vn -0.3945 -0.0623 0.9168 +vn -0.4236 -0.0556 0.9042 +vn -0.4360 -0.0646 0.8977 +vn -0.4308 -0.0798 0.8989 +vn -0.4296 -0.0477 0.9018 +vn -0.3869 -0.0577 0.9203 +vn -0.4122 -0.0893 0.9067 +vn -0.4258 -0.0957 0.8997 +vn -0.4099 -0.0993 0.9067 +vn -0.3961 -0.0935 0.9134 +vn -0.4143 -0.0428 0.9091 +vn -0.4052 -0.0470 0.9130 +vn 0.4623 -0.0805 -0.8831 +vn 0.3349 0.1037 -0.9365 +vn 0.3191 0.1254 -0.9394 +vn 0.4437 -0.0958 -0.8910 +vn 0.3644 0.0625 -0.9291 +vn -0.7698 -0.5297 -0.3560 +vn -0.8720 -0.1339 -0.4708 +vn -0.8540 -0.1826 -0.4872 +vn -0.7430 -0.5772 -0.3389 +vn 0.0724 -0.9965 -0.0422 +vn -0.3168 -0.9165 -0.2444 +vn -0.0452 -0.9921 -0.1168 +vn 0.1276 -0.9917 -0.0146 +vn 0.2240 -0.9745 0.0158 +vn 0.7828 -0.5304 0.3254 +vn 0.8797 -0.4009 0.2557 +vn 0.7920 -0.5153 0.3275 +vn 0.8769 -0.3908 0.2797 +vn 0.8677 0.2669 0.4194 +vn 0.8230 0.4449 0.3531 +vn 0.7293 0.5658 0.3848 +vn 0.8081 0.4892 0.3282 +vn 0.5036 0.8067 0.3092 +vn -0.1593 0.9872 -0.0026 +vn -0.0038 0.9990 0.0436 +vn -0.0233 0.9990 0.0379 +vn -0.1818 0.9833 -0.0094 +vn -0.7844 0.5445 -0.2971 +vn -0.6689 0.6945 -0.2649 +vn -0.6859 0.6758 -0.2698 +vn -0.7959 0.5258 -0.3001 +vn -0.2164 0.5330 -0.8180 +vn -0.3045 0.0323 -0.9520 +vn -0.3824 0.1721 -0.9078 +vn -0.3023 -0.2386 -0.9229 +vn -0.0804 -0.5171 -0.8521 +vn 0.0643 -0.5590 -0.8267 +vn 0.3035 -0.6762 -0.6713 +vn 0.6441 -0.5268 -0.5546 +vn 0.6061 -0.5962 -0.5265 +vn 0.8385 -0.3615 -0.4077 +vn 0.9247 -0.0410 -0.3786 +vn 0.9434 -0.0310 -0.3302 +vn 0.8552 0.3856 -0.3463 +vn 0.8039 0.4516 -0.3869 +vn 0.5628 0.6974 -0.4438 +vn 0.4294 0.7191 -0.5463 +vn 0.1494 0.7619 -0.6303 +vn -0.0674 0.6154 -0.7853 +vn -0.4842 0.5842 -0.6513 +vn -0.3957 0.9026 0.1697 +vn 0.9032 0.3786 0.2023 +vn 0.9198 0.3552 0.1666 +vn 0.9130 0.3652 0.1818 +vn 0.9311 0.3370 0.1394 +vn 0.0629 -0.8878 -0.4559 +vn 0.2225 -0.9482 0.2266 +vn -0.9280 -0.3372 -0.1588 +vn -0.4097 -0.0688 0.9096 +vn 0.0444 0.2232 -0.9737 +vn -0.7690 -0.1164 -0.6286 +vn 0.0512 -0.4398 -0.8966 +vn 0.5749 -0.3968 -0.7156 +vn 0.9407 -0.3373 -0.0360 +vn 0.7988 0.0763 -0.5968 +vn 0.8716 0.4599 0.1700 +vn 0.4279 0.5678 -0.7032 +vn 0.1245 0.9836 0.1305 +vn 0.0055 0.9969 0.0779 +vn 0.1136 -0.9932 -0.0240 +vn -0.0055 -0.9969 -0.0779 +vn 0.9121 -0.0369 0.4083 +vn 0.9121 -0.0369 0.4082 +vn 0.4099 0.0685 -0.9096 +vn 0.2414 0.9534 0.1809 +vn 0.2307 -0.9725 0.0304 +vn -0.9121 0.0369 -0.4082 +vn -0.9121 0.0369 -0.4083 +vn -0.1511 0.9532 -0.2618 +vn -0.3685 0.9248 -0.0942 +vn -0.0082 0.9999 -0.0097 +vn -0.2196 -0.7700 0.5990 +vn -0.4276 -0.7574 0.4934 +vn -0.0026 -0.7635 0.6459 +vn 0.6961 0.1608 -0.6997 +vn 0.6896 0.1648 -0.7052 +vn 0.7222 0.0723 -0.6878 +vn 0.1617 -0.4521 -0.8772 +vn 0.2287 -0.2922 -0.9286 +vn 0.1965 -0.3273 -0.9243 +vn -0.8757 -0.0673 0.4781 +vn -0.8532 -0.1710 0.4928 +vn -0.8217 -0.0014 0.5699 +vn 0.1134 0.9227 -0.3684 +vn 0.6904 0.7038 -0.1671 +vn 0.7342 0.6566 -0.1728 +vn 0.6782 0.7314 -0.0707 +vn -0.2198 -0.8808 -0.4193 +vn 0.2855 -0.8861 -0.3651 +vn -0.1694 -0.9507 -0.2598 +vn -0.1188 0.9447 0.3057 +vn -0.1188 0.9447 0.3058 +vn -0.2404 -0.9132 -0.3290 +vn -0.4055 -0.9139 0.0173 +vn -0.4935 -0.8436 -0.2118 +vn 0.6770 -0.7303 -0.0909 +vn 0.7592 -0.6481 0.0600 +vn 0.7406 -0.6110 0.2796 +vn -0.5501 0.6268 0.5518 +vn -0.5749 0.3720 0.7288 +vn -0.4416 0.4201 0.7928 +vn -0.9917 -0.1252 -0.0288 +vn -0.9213 -0.2025 -0.3320 +vn -0.9911 -0.1307 -0.0250 +vn -0.0082 -0.9999 -0.0097 +vn 0.0097 -1.0000 -0.0017 +vn -0.7347 -0.6554 -0.1753 +vn -0.7481 -0.6623 -0.0424 +vn -0.8291 -0.5559 0.0593 +vn 0.4521 0.0013 -0.8920 +vn 0.5093 0.0021 -0.8606 +vn 0.5091 0.0015 -0.8607 +vn 0.8085 -0.3251 -0.4905 +vn 0.5188 -0.2754 -0.8094 +vn 0.6705 -0.0758 -0.7380 +vn -0.5761 -0.8152 0.0593 +vn -0.4676 -0.8685 0.1646 +vn -0.5131 -0.8123 0.2772 +vn 0.6036 -0.7961 0.0427 +vn 0.9100 -0.3695 0.1883 +vn 0.5124 -0.7518 0.4149 +vn -0.1188 -0.9447 0.3057 +vn 0.1633 -0.9201 0.3559 +vn 0.1737 -0.8857 0.4305 +vn 0.1961 -0.8888 0.4141 +vn -0.1157 0.3935 0.9120 +vn -0.0106 0.4074 0.9132 +vn -0.2827 0.5098 0.8125 +vn 0.3976 0.7149 -0.5752 +vn 0.5170 0.7696 -0.3748 +vn 0.5989 0.7016 -0.3861 +vn -0.9744 -0.1299 -0.1835 +vn -0.9267 -0.0467 0.3729 +vn -0.9574 -0.2713 0.0985 +vn -0.7801 0.5904 -0.2068 +vn -0.7265 0.5697 -0.3842 +vn -0.8400 0.3732 -0.3940 +vn -0.0097 1.0000 0.0017 +vn -0.7010 0.7124 0.0328 +vn -0.5423 0.7952 0.2711 +vn -0.4126 0.9105 0.0264 +vn 0.0161 0.9999 -0.0003 +vn 0.0161 0.9999 -0.0002 +vn 0.0428 -0.3364 -0.9408 +vn 0.0004 -0.1239 -0.9923 +vn 0.0861 -0.2376 -0.9675 +vn -0.4132 -0.5114 0.7535 +vn -0.4611 -0.4376 0.7720 +vn -0.5924 -0.5088 0.6246 +vn -0.5248 -0.5209 0.6732 +vn -0.6457 -0.6099 0.4595 +vn -0.7154 -0.6579 0.2354 +vn -0.9063 -0.0034 0.4225 +vn -0.8035 -0.0008 0.5953 +vn -0.0547 -0.5095 0.8587 +vn -0.0476 -0.4544 0.8895 +vn -0.2976 -0.5498 0.7805 +vn 0.3658 0.5517 0.7496 +vn 0.4643 0.6795 0.5681 +vn 0.3501 0.6266 0.6963 +vn 0.0161 -0.9999 -0.0002 +vn 0.1152 0.7653 -0.6333 +vn 0.1188 0.9447 -0.3058 +vn 0.1188 0.9447 -0.3057 +vn 0.1188 0.0835 -0.9894 +vn 0.0965 -0.0045 -0.9953 +vn 0.1991 0.0570 -0.9783 +vn -0.1496 0.9882 0.0337 +vn -0.2118 0.9743 0.0771 +vn -0.0050 1.0000 0.0007 +vn 0.5193 -0.7760 0.3580 +vn 0.4603 -0.8662 0.1947 +vn 0.6325 -0.7476 0.2024 +vn -0.9072 -0.0059 0.4206 +vn -0.7310 -0.1024 0.6746 +vn -0.5456 -0.1610 0.8225 +vn -0.1134 -0.9227 0.3684 +vn -0.0175 0.4026 0.9152 +vn -0.0157 0.6968 0.7171 +vn -0.1115 0.4368 0.8926 +vn 0.7091 0.3247 0.6259 +vn 0.7097 0.2943 0.6400 +vn 0.7072 0.4371 0.5557 +vn -0.9507 0.0048 0.3102 +vn -0.6390 -0.7006 0.3176 +vn -0.7316 -0.5919 0.3383 +vn -0.7633 -0.6139 0.2013 +vn -0.2861 -0.9274 0.2411 +vn -0.0097 -1.0000 0.0017 +vn 0.1671 -0.0029 -0.9859 +vn -0.1933 0.0029 -0.9811 +vn 0.1629 0.6727 -0.7218 +vn 0.3325 0.7539 -0.5666 +vn 0.3068 0.6361 -0.7080 +vn -0.8268 -0.2480 -0.5049 +vn -0.7815 -0.2523 -0.5706 +vn 0.0938 -0.6337 0.7679 +vn -0.1837 -0.6527 0.7350 +vn 0.2115 -0.6703 0.7113 +vn -0.6323 0.7031 -0.3253 +vn -0.7347 0.6554 -0.1753 +vn -0.7481 0.6623 -0.0424 +vn -0.2280 -0.5390 -0.8109 +vn -0.0119 -0.4926 -0.8702 +vn -0.0565 -0.5224 -0.8508 +vn 0.2977 -0.7870 -0.5403 +vn 0.4501 -0.6527 -0.6094 +vn 0.2224 -0.8672 -0.4455 +vn 0.4198 -0.4840 -0.7678 +vn 0.2007 -0.7615 -0.6163 +vn 0.2285 -0.4519 -0.8623 +vn -0.5035 0.2081 -0.8386 +vn -0.2066 0.2777 -0.9382 +vn -0.2065 0.2777 -0.9382 +vn -0.9183 0.0522 0.3924 +vn -0.9744 0.1299 -0.1835 +vn -0.9574 0.2713 0.0985 +vn -0.7511 0.2498 0.6110 +vn -0.5726 -0.0134 0.8197 +vn -0.5598 0.2739 0.7821 +vn 0.0379 0.5468 -0.8364 +vn 0.0689 0.7872 -0.6129 +vn 0.0387 0.6820 -0.7303 +vn 0.0122 0.9542 -0.2988 +vn -0.0371 0.9764 -0.2126 +vn 0.1581 0.9175 -0.3650 +vn -0.1222 0.0101 -0.9925 +vn 0.1203 0.1300 -0.9842 +vn -0.1093 -0.2646 -0.9581 +vn 0.9193 0.3604 0.1583 +vn 0.9412 0.2155 -0.2602 +vn 0.8319 0.5511 -0.0647 +vn -0.8000 0.1534 -0.5800 +vn -0.8088 0.3700 -0.4571 +vn 0.8512 0.5191 -0.0779 +vn 0.6417 0.7448 -0.1832 +vn 0.6939 0.7159 0.0776 +vn -0.7010 -0.7124 0.0328 +vn -0.4126 -0.9105 0.0264 +vn -0.5423 -0.7952 0.2711 +vn 0.8490 0.0092 -0.5283 +vn 0.5405 0.0067 -0.8413 +vn -0.9813 0.0100 -0.1925 +vn -0.6562 -0.3091 0.6884 +vn -0.3876 -0.6322 0.6709 +vn -0.4743 -0.2393 0.8472 +vn -0.9102 -0.2266 0.3466 +vn -0.9917 -0.1285 0.0094 +vn -0.9370 -0.2141 0.2759 +vn -0.6495 -0.6754 -0.3492 +vn -0.6000 -0.7649 -0.2342 +vn -0.7502 -0.6489 -0.1270 +vn -0.3693 -0.3603 -0.8567 +vn -0.5515 -0.0113 -0.8341 +vn -0.3644 -0.0069 -0.9312 +vn 0.7437 -0.0061 0.6685 +vn -0.4363 0.3215 0.8404 +vn -0.2414 0.3159 0.9176 +vn -0.4495 0.3227 0.8329 +vn -0.7307 0.5317 -0.4281 +vn -0.6991 0.5634 -0.4402 +vn -0.6113 0.5304 -0.5874 +vn 0.7246 -0.0023 0.6892 +vn 0.6888 -0.0778 0.7207 +vn 0.8634 -0.1975 0.4644 +vn 0.1047 -0.7582 -0.6436 +vn 0.1231 -0.7045 -0.6989 +vn 0.3311 -0.7893 -0.5171 +vn -0.7702 -0.0126 -0.6376 +vn -0.9325 -0.0112 -0.3609 +vn -0.7179 -0.0094 -0.6961 +vn -0.1129 -0.9567 -0.2684 +vn 0.3217 -0.0171 -0.9467 +vn 0.3135 0.3618 -0.8780 +vn 0.5063 0.0740 -0.8592 +vn 0.3581 0.0194 -0.9335 +vn 0.3376 0.0096 -0.9413 +vn -0.0032 0.0279 -0.9996 +vn 0.0097 1.0000 -0.0017 +vn 0.5719 0.4907 -0.6574 +vn 0.6315 0.7450 -0.2148 +vn 0.7617 0.5508 -0.3411 +vn 0.7983 -0.3488 -0.4911 +vn 0.2848 -0.4037 -0.8695 +vn 0.5976 -0.2539 -0.7605 +vn -0.0161 -0.9999 0.0003 +vn -0.0161 -0.9999 0.0002 +vn 0.2568 -0.5758 -0.7762 +vn 0.2598 -0.5465 -0.7962 +vn 0.3976 -0.7149 -0.5752 +vn -0.9506 0.0153 0.3102 +vn -0.3899 -0.7123 -0.5835 +vn -0.1354 -0.7955 -0.5906 +vn -0.6168 0.7848 -0.0600 +vn -0.5560 0.7491 -0.3601 +vn -0.8291 0.5559 0.0593 +vn -0.8693 0.3047 0.3892 +vn -0.7633 0.6139 0.2013 +vn 0.2035 0.1888 -0.9607 +vn -0.0310 0.0431 -0.9986 +vn 0.1554 0.1843 -0.9705 +vn -0.8212 0.3258 -0.4684 +vn -0.6441 0.2830 -0.7107 +vn -0.5940 0.2396 -0.7680 +vn 0.2414 0.1769 0.9542 +vn 0.2675 -0.0419 0.9626 +vn 0.1743 0.0400 0.9839 +vn -0.7439 0.0126 -0.6681 +vn -0.1129 0.9567 -0.2684 +vn -0.4113 -0.9114 0.0158 +vn -0.4326 -0.7554 0.4921 +vn -0.5412 -0.7991 0.2618 +vn -0.3252 -0.0098 0.9456 +vn -0.0873 -0.0092 0.9961 +vn -0.3610 -0.0061 0.9325 +vn 0.2056 0.9324 -0.2973 +vn 0.4129 0.9048 -0.1043 +vn 0.5362 0.8310 0.1479 +vn 0.4596 0.8772 -0.1389 +vn -0.4973 -0.7665 -0.4064 +vn -0.3050 -0.6642 -0.6825 +vn -0.1731 -0.9132 -0.3689 +vn -0.8536 -0.0642 0.5170 +vn -0.9645 -0.0299 0.2624 +vn -0.9402 -0.0602 0.3353 +vn 0.1658 0.5151 0.8410 +vn -0.0748 0.4333 0.8981 +vn -0.0719 0.3900 0.9180 +vn 0.0903 -0.7568 -0.6474 +vn 0.3297 -0.7957 -0.5082 +vn 0.5667 -0.7382 -0.3658 +vn -0.9674 -0.0953 0.2345 +vn -0.9813 -0.0882 0.1710 +vn -0.9662 -0.1901 0.1743 +vn 0.3861 -0.7983 -0.4623 +vn 0.6122 -0.6227 -0.4873 +vn 0.6659 -0.6635 -0.3412 +vn 0.8557 -0.2713 -0.4407 +vn 0.0083 -0.9999 0.0097 +vn 0.0082 -0.9999 0.0097 +vn 0.9907 0.0765 0.1127 +vn 0.9800 0.1626 -0.1146 +vn 0.9637 0.1924 -0.1853 +vn -0.6550 0.7555 -0.0150 +vn -0.7816 0.6042 -0.1550 +vn -0.7133 0.6859 -0.1439 +vn 0.1019 -0.9852 0.1378 +vn 0.1479 -0.9408 0.3049 +vn 0.1633 -0.9606 0.2251 +vn -0.8853 -0.1718 -0.4321 +vn -0.8937 -0.3554 -0.2738 +vn -0.9812 -0.0557 -0.1849 +vn -0.5635 -0.7158 0.4124 +vn -0.6047 -0.5984 0.5256 +vn -0.7230 -0.5573 0.4083 +vn -0.8880 -0.1044 0.4479 +vn -0.8674 -0.2650 0.4212 +vn -0.4041 0.7410 -0.5363 +vn -0.5618 0.7681 -0.3074 +vn -0.6146 0.7746 -0.1493 +vn 0.6134 0.7897 -0.0079 +vn 0.7268 0.6104 -0.3148 +vn -0.2693 -0.6687 0.6931 +vn -0.3998 -0.7382 0.5434 +vn -0.8690 0.2662 0.4170 +vn -0.8952 0.2077 0.3943 +vn -0.8823 0.1007 0.4599 +vn -0.7301 -0.6460 0.2229 +vn -0.5878 -0.7594 0.2790 +vn -0.6619 -0.6512 0.3712 +vn -0.0031 1.0000 0.0008 +vn -0.0172 0.9998 0.0046 +vn -0.3679 -0.7890 0.4921 +vn -0.7379 -0.3035 0.6029 +vn -0.5196 -0.6518 0.5525 +vn -0.5347 -0.1869 0.8241 +vn 0.3292 -0.4727 0.8174 +vn 0.0746 -0.5014 0.8620 +vn 0.2664 -0.5637 0.7818 +vn 0.2893 -0.9571 -0.0146 +vn -0.0083 -0.9999 -0.0097 +vn 0.1962 -0.9271 0.3193 +vn 0.2220 -0.8148 0.5355 +vn 0.2184 -0.8505 0.4786 +vn 0.4781 -0.1812 -0.8594 +vn 0.6446 -0.1347 -0.7526 +vn 0.3754 -0.2136 -0.9019 +vn -0.5061 -0.7671 -0.3942 +vn 0.8414 0.0134 0.5402 +vn 0.9324 0.0149 0.3610 +vn -0.7815 0.2523 -0.5707 +vn -0.8268 0.2480 -0.5049 +vn -0.6119 0.2800 -0.7397 +vn -0.1635 0.3484 -0.9230 +vn 0.2317 -0.7220 0.6520 +vn 0.1966 -0.7074 0.6790 +vn 0.1154 -0.9061 0.4070 +vn 0.4921 -0.6981 0.5201 +vn 0.2351 -0.7859 0.5720 +vn 0.4458 -0.7610 0.4713 +vn -0.9177 0.1665 0.3606 +vn -0.9317 0.1336 0.3378 +vn -0.9058 0.1330 0.4023 +vn 0.4478 0.0007 -0.8941 +vn 0.9506 -0.0154 -0.3102 +vn -0.5976 -0.4468 0.6658 +vn -0.5438 -0.4042 0.7354 +vn -0.5991 -0.1180 0.7919 +vn -0.8564 -0.1377 -0.4977 +vn -0.8409 -0.3736 -0.3914 +vn -0.9241 -0.1583 -0.3478 +vn 0.3757 0.2523 -0.8917 +vn 0.3255 0.1473 -0.9340 +vn 0.3654 0.1769 -0.9139 +vn -0.6905 -0.7230 0.0209 +vn -0.5442 -0.8268 -0.1421 +vn -0.3502 -0.9355 0.0475 +vn -0.4637 -0.5235 -0.7148 +vn -0.5115 -0.4782 -0.7139 +vn -0.3258 -0.5365 -0.7784 +vn -0.4418 0.5809 -0.6837 +vn -0.2629 0.7548 -0.6009 +vn -0.3836 0.3110 -0.8696 +vn 0.2031 0.1411 0.9689 +vn 0.2081 0.2436 0.9473 +vn 0.1810 0.0043 0.9835 +vn -0.9993 -0.0161 0.0334 +vn -0.9324 -0.0149 -0.3610 +vn 0.7323 -0.4680 0.4947 +vn 0.5614 -0.5755 0.5947 +vn 0.3967 0.2371 0.8868 +vn 0.4315 0.2314 0.8719 +vn 0.0481 0.3021 0.9521 +vn -0.6394 0.7640 0.0863 +vn -0.4167 0.8988 0.1361 +vn -0.5705 0.8144 -0.1063 +vn 0.9255 -0.2164 -0.3107 +vn 0.7639 -0.2836 -0.5796 +vn 0.8337 -0.2576 -0.4885 +vn -0.4829 -0.5758 -0.6597 +vn -0.4551 -0.8614 -0.2256 +vn -0.5366 -0.7822 -0.3166 +vn 0.1129 -0.9567 0.2684 +vn -0.0988 -0.8774 0.4694 +vn 0.1130 -0.9567 0.2684 +vn -0.5736 0.0094 0.8191 +vn -0.6045 0.0066 0.7966 +vn -0.3609 0.0060 0.9326 +vn 0.1577 -0.9010 0.4042 +vn 0.1680 -0.6808 0.7129 +vn 0.1686 -0.8772 0.4495 +vn -0.9813 -0.0100 -0.1925 +vn -0.8088 -0.3700 -0.4571 +vn 0.4566 -0.7335 0.5035 +vn 0.4790 -0.6994 0.5305 +vn 0.1760 -0.7578 0.6283 +vn 0.0794 -0.4552 0.8868 +vn -0.0104 -0.6998 0.7142 +vn 0.1137 -0.7421 0.6606 +vn -0.5336 -0.6366 -0.5568 +vn -0.7712 -0.2891 -0.5672 +vn -0.5456 0.1610 0.8225 +vn -0.7310 0.1024 0.6746 +vn -0.9066 0.0047 0.4219 +vn 0.9973 0.0098 -0.0732 +vn 0.0871 0.6000 0.7952 +vn 0.1115 0.6401 0.7601 +vn 0.1340 0.5609 0.8170 +vn 0.1357 -0.3884 0.9114 +vn -0.5325 -0.5846 0.6122 +vn 0.3700 -0.2599 -0.8920 +vn 0.3041 -0.4883 -0.8180 +vn 0.4090 -0.4625 -0.7866 +vn 0.1105 0.9868 0.1187 +vn 0.0633 0.9813 0.1816 +vn 0.1285 0.9636 0.2345 +vn -0.2891 -0.6364 -0.7151 +vn -0.6527 -0.2184 -0.7255 +vn 0.1635 -0.3484 0.9230 +vn -0.6103 -0.2674 -0.7457 +vn -0.8559 -0.0006 -0.5171 +vn -0.7399 0.1220 -0.6616 +vn -0.4526 0.8302 -0.3254 +vn -0.2490 0.9295 -0.2721 +vn -0.3764 0.8236 -0.4242 +vn -0.0161 0.9999 0.0002 +vn 0.0191 0.9987 -0.0466 +vn 0.0014 0.9996 -0.0277 +vn -0.0613 0.9957 -0.0699 +vn 0.0111 -0.9951 -0.0980 +vn -0.1187 -0.9447 0.3057 +vn 0.3986 -0.0052 -0.9171 +vn 0.1654 -0.0001 -0.9862 +vn 0.5423 -0.0034 -0.8402 +vn 0.9542 0.1860 -0.2342 +vn 0.9255 0.2164 -0.3107 +vn 0.9712 0.1746 -0.1622 +vn 0.2388 -0.0309 -0.9706 +vn 0.1908 -0.0189 -0.9814 +vn 0.2083 -0.0980 -0.9731 +vn -0.1096 0.2565 -0.9603 +vn 0.1208 0.3016 -0.9457 +vn -0.0155 -0.0722 -0.9973 +vn 0.5851 -0.6685 -0.4592 +vn 0.5938 -0.3066 -0.7439 +vn 0.7851 -0.2538 -0.5650 +vn 0.7065 0.1530 0.6910 +vn 0.7165 0.1871 0.6720 +vn 0.7081 0.0508 0.7042 +vn 0.0082 0.9999 0.0097 +vn 0.2970 -0.2678 -0.9165 +vn 0.2261 -0.5250 -0.8205 +vn 0.2378 -0.0031 -0.9713 +vn 0.2473 -0.0021 -0.9689 +vn 0.2620 -0.0030 -0.9651 +vn 0.1553 -0.7573 0.6343 +vn 0.2682 -0.6314 -0.7276 +vn 0.2547 -0.7522 -0.6078 +vn 0.0733 -0.6271 -0.7755 +vn -0.9028 0.1492 -0.4033 +vn -0.9128 0.0490 -0.4054 +vn -0.9610 0.0642 -0.2691 +vn -0.7987 0.0921 -0.5947 +vn -0.9324 0.0085 -0.3614 +vn -0.9994 0.0098 0.0330 +vn 0.1457 0.2861 -0.9471 +vn 0.1890 0.0785 -0.9788 +vn 0.0096 0.0718 -0.9974 +vn 0.1665 -0.1166 -0.9791 +vn 0.1760 -0.2047 -0.9629 +vn 0.2135 -0.1889 -0.9585 +vn -0.8200 0.1224 -0.5591 +vn -0.9305 0.0314 -0.3650 +vn -0.9434 0.0197 -0.3310 +vn 0.2708 0.0302 0.9622 +vn 0.2714 0.0290 0.9620 +vn 0.2513 -0.0254 0.9676 +vn -0.4596 -0.7145 0.5276 +vn -0.5361 -0.8021 0.2631 +vn -0.0565 0.5224 -0.8508 +vn 0.2568 0.5758 -0.7762 +vn 0.2598 0.5465 -0.7962 +vn 0.9972 -0.0160 -0.0736 +vn 0.8487 -0.0138 -0.5287 +vn -0.5109 0.2907 -0.8090 +vn -0.9160 0.2837 0.2835 +vn -0.9657 0.1902 0.1767 +vn -0.9516 0.1419 0.2727 +vn 0.4308 0.1604 -0.8881 +vn 0.4505 0.2758 -0.8491 +vn 0.7828 -0.0807 -0.6170 +vn 0.0273 -0.9813 -0.1907 +vn 0.0212 -0.9954 -0.0932 +vn 0.0407 -0.9988 0.0288 +vn -0.0036 0.1081 -0.9941 +vn 0.0255 0.3976 -0.9172 +vn 0.0076 0.2210 -0.9753 +vn -0.2068 0.0078 0.9784 +vn 0.3467 -0.8465 -0.4041 +vn 0.5099 -0.8183 -0.2651 +vn 0.1723 -0.9618 -0.2125 +vn 0.7439 -0.0118 0.6682 +vn 0.0083 0.9999 0.0097 +vn 0.1802 -0.3280 -0.9273 +vn -0.1322 -0.9308 -0.3409 +vn 0.0937 -0.9401 -0.3277 +vn -0.2950 -0.9046 -0.3075 +vn -0.0767 0.9510 0.2997 +vn -0.1831 0.8456 0.5014 +vn 0.1594 0.8686 0.4691 +vn -0.8961 -0.0720 -0.4380 +vn -0.7284 0.0457 -0.6836 +vn -0.3902 -0.2944 -0.8724 +vn -0.2837 -0.2675 -0.9208 +vn -0.2194 -0.4639 -0.8583 +vn 0.2391 -0.1881 0.9526 +vn 0.2559 -0.0963 0.9619 +vn 0.2551 -0.0494 0.9656 +vn 0.4643 -0.7950 0.3903 +vn 0.5557 -0.8030 0.2153 +vn 0.6558 -0.7022 0.2770 +vn -0.2048 0.9609 0.1863 +vn -0.3850 0.9192 0.0831 +vn -0.5148 0.8033 0.2995 +vn -0.7437 0.0061 -0.6685 +vn -0.0764 -0.6643 0.7436 +vn -0.6209 0.2162 -0.7535 +vn -0.5462 0.5938 -0.5908 +vn 0.1579 0.0060 0.9874 +vn 0.2224 0.0788 0.9718 +vn -0.2519 0.0342 0.9671 +vn 0.6001 -0.7998 0.0115 +vn 0.2704 -0.9623 -0.0277 +vn 0.5576 -0.7862 0.2663 +vn 0.0318 0.3114 -0.9498 +vn 0.0319 0.3114 -0.9497 +vn 0.4694 0.7529 0.4613 +vn 0.5780 0.7842 0.2259 +vn 0.6615 0.7490 -0.0378 +vn -0.4034 -0.0160 -0.9149 +vn -0.8756 0.4587 0.1516 +vn -0.9543 0.2874 0.0817 +vn 0.6063 0.1934 -0.7713 +vn 0.5991 0.3903 -0.6992 +vn 0.8490 -0.0092 -0.5283 +vn 0.6065 -0.0073 -0.7951 +vn 0.3704 0.0533 -0.9273 +vn -0.9213 0.2021 -0.3322 +vn -0.9213 0.2020 -0.3322 +vn 0.0483 -0.0822 0.9954 +vn 0.0382 -0.1340 0.9903 +vn 0.0370 -0.0483 0.9981 +vn 0.3399 0.5542 -0.7599 +vn 0.2312 0.7823 -0.5783 +vn 0.4352 0.5790 -0.6894 +vn 0.4489 -0.6464 -0.6169 +vn 0.2691 -0.7416 -0.6145 +vn 0.3227 -0.3361 -0.8848 +vn -0.7639 0.2837 0.5796 +vn -0.0211 -0.2677 0.9633 +vn -0.4449 -0.1928 0.8746 +vn -0.0211 -0.2678 0.9633 +vn -0.2567 -0.0002 0.9665 +vn -0.2558 0.0008 0.9667 +vn -0.2531 -0.0013 0.9674 +vn 0.0986 -0.9936 0.0548 +vn 0.1181 -0.9850 0.1261 +vn 0.6572 0.0496 -0.7521 +vn 0.6216 0.1378 -0.7711 +vn -0.7439 0.0118 -0.6682 +vn -0.6323 -0.7031 -0.3253 +vn -0.6168 -0.7848 -0.0600 +vn 0.2452 0.2523 0.9361 +vn 0.0732 -0.0219 0.9971 +vn -0.1971 -0.0228 -0.9801 +vn 0.1199 0.1294 -0.9843 +vn -0.1568 -0.2711 -0.9497 +vn 0.4786 0.3021 -0.8244 +vn 0.2787 0.3443 -0.8965 +vn 0.3284 0.4420 -0.8347 +vn -0.2556 0.3753 -0.8910 +vn 0.0490 0.5089 -0.8594 +vn -0.1544 0.3603 -0.9200 +vn 0.0362 -0.9055 -0.4228 +vn 0.0701 -0.8705 -0.4871 +vn 0.0587 -0.7258 -0.6854 +vn 0.1602 0.0033 0.9871 +vn 0.2221 0.0072 0.9750 +vn 0.4291 0.0336 0.9027 +vn -0.9072 0.0114 0.4206 +vn -0.8267 0.0132 0.5624 +vn -0.4726 -0.8560 -0.2096 +vn -0.3308 -0.8706 -0.3641 +vn 0.4205 -0.1629 -0.8925 +vn 0.3959 -0.1608 -0.9041 +vn 0.7405 -0.6116 -0.2785 +vn 0.9195 -0.3636 0.1492 +vn -0.2683 0.0037 -0.9633 +vn 0.1675 0.0033 -0.9859 +vn -0.6781 -0.7228 0.1331 +vn 0.1677 0.2878 0.9429 +vn 0.4011 0.5322 0.7456 +vn 0.2691 0.5991 0.7541 +vn 0.5878 -0.4472 0.6742 +vn 0.4547 -0.4600 0.7627 +vn 0.1723 -0.4262 0.8881 +vn -0.9065 0.0095 0.4221 +vn -0.8037 0.0088 0.5949 +vn 0.0520 0.9299 -0.3642 +vn 0.4468 -0.7737 -0.4492 +vn 0.6895 -0.7243 -0.0075 +vn 0.7129 -0.7012 -0.0138 +vn 0.0678 -0.0834 0.9942 +vn 0.0752 -0.1423 0.9870 +vn -0.1222 -0.0190 -0.9923 +vn -0.0972 0.0018 -0.9953 +vn 0.1149 -0.1535 -0.9814 +vn -0.1620 0.9318 0.3250 +vn 0.1129 0.9567 0.2684 +vn -0.7828 0.0807 0.6170 +vn 0.9213 0.2020 0.3322 +vn 0.9213 0.2019 0.3322 +vn -0.3966 0.7907 -0.4664 +vn 0.1607 -0.8892 0.4284 +vn 0.0439 0.9957 -0.0811 +vn 0.0648 0.9945 -0.0820 +vn 0.0684 0.9396 -0.3352 +vn -0.5120 0.7671 -0.3866 +vn -0.2502 0.9178 -0.3083 +vn -0.4164 0.7158 -0.5606 +vn 0.2123 -0.1083 -0.9712 +vn 0.4193 -0.0007 -0.9078 +vn 0.3872 -0.0508 -0.9206 +vn -0.3172 0.6333 -0.7059 +vn -0.2211 0.7565 -0.6155 +vn -0.0970 0.7201 -0.6871 +vn 0.4330 -0.2446 -0.8676 +vn 0.5052 -0.1562 -0.8487 +vn 0.2397 -0.7114 0.6607 +vn 0.2205 -0.4540 0.8633 +vn 0.2609 -0.5657 0.7823 +vn 0.2067 0.0036 -0.9784 +vn -0.2454 -0.9452 0.2155 +vn -0.4092 0.0007 0.9124 +vn -0.4050 0.0012 0.9143 +vn -0.4642 -0.0032 0.8857 +vn -0.1402 -0.7937 -0.5919 +vn 0.0095 0.9987 -0.0502 +vn -0.6539 -0.3492 -0.6712 +vn 0.9973 -0.0098 -0.0733 +vn 0.9324 -0.0085 0.3614 +vn -0.2280 0.4602 -0.8581 +vn -0.4058 0.4980 -0.7663 +vn -0.9775 -0.0587 0.2025 +vn -0.5437 -0.5211 -0.6580 +vn -0.4390 -0.6663 -0.6028 +vn -0.5294 -0.6916 -0.4913 +vn 0.5503 0.7042 -0.4486 +vn 0.3840 0.7000 -0.6022 +vn 0.3451 0.7999 -0.4910 +vn -0.9317 0.0116 -0.3630 +vn -0.9783 0.0154 -0.2067 +vn -0.9004 0.0144 -0.4349 +vn -0.5909 0.0013 -0.8068 +vn -0.6183 0.0989 -0.7797 +vn -0.4736 0.0828 -0.8768 +vn -0.1931 0.1226 0.9735 +vn -0.1793 -0.1410 0.9736 +vn -0.1453 -0.1097 0.9833 +vn 0.2853 -0.3692 -0.8845 +vn 0.4930 -0.1788 -0.8514 +vn 0.6064 -0.5060 -0.6134 +vn -0.0402 -0.0026 0.9992 +vn -0.0283 -0.0091 0.9996 +vn -0.0433 -0.0838 0.9955 +vn -0.2330 0.9723 0.0197 +vn -0.3870 0.9186 0.0806 +vn -0.6065 0.7897 0.0925 +vn -0.6543 0.7427 -0.1423 +vn -0.8830 0.4549 0.1158 +vn -0.7899 -0.5978 -0.1365 +vn -0.8256 -0.5636 -0.0263 +vn -0.8193 -0.5385 -0.1969 +vn 0.0731 -0.9967 0.0359 +vn 0.0720 -0.9966 0.0397 +vn 0.6885 -0.0111 0.7251 +vn 0.4958 -0.0157 0.8683 +vn 0.7164 -0.0127 0.6976 +vn 0.0905 -0.8661 -0.4917 +vn 0.0668 -0.7541 -0.6534 +vn 0.1049 -0.9112 -0.3984 +vn 0.3443 0.0921 -0.9343 +vn 0.2852 0.2923 -0.9128 +vn 0.4135 0.3063 -0.8575 +vn -0.1134 0.9227 0.3684 +vn -0.1135 0.9227 0.3684 +vn 0.1752 0.1892 0.9662 +vn 0.1860 0.1861 0.9648 +vn 0.1775 0.0981 0.9792 +vn 0.2360 0.7920 0.5630 +vn -0.0445 0.7314 0.6804 +vn -0.0521 0.7086 0.7037 +vn 0.2753 0.0006 -0.9614 +vn 0.3074 -0.0038 -0.9516 +vn -0.9560 0.0256 -0.2924 +vn -0.9729 0.0565 -0.2244 +vn -0.7995 -0.0884 -0.5941 +vn 0.2781 0.1190 0.9531 +vn 0.2828 0.1213 0.9515 +vn 0.2966 0.2027 0.9333 +vn 0.1763 -0.2108 0.9615 +vn 0.1490 -0.2512 0.9564 +vn 0.1846 -0.1074 0.9769 +vn 0.4007 0.4766 -0.7825 +vn 0.2907 0.5041 -0.8133 +vn -0.1222 -0.0101 -0.9925 +vn -0.4034 -0.0100 -0.9150 +vn -0.3848 0.3396 -0.8582 +vn -0.6209 0.6815 -0.3873 +vn -0.7731 0.2511 -0.5824 +vn -0.3889 0.9032 0.1819 +vn -0.1807 0.9746 0.1319 +vn 0.0160 0.9999 -0.0003 +vn 0.7186 0.0334 -0.6946 +vn 0.7617 -0.0157 -0.6477 +vn 0.7193 0.0129 -0.6946 +vn 0.2696 -0.9597 -0.0790 +vn -0.8416 0.3629 -0.4001 +vn -0.1406 0.8797 -0.4542 +vn 0.4464 -0.7202 0.5310 +vn 0.2044 -0.7453 0.6346 +vn 0.0555 -0.6382 -0.7679 +vn 0.0294 -0.4564 -0.8893 +vn -0.4592 0.8574 -0.2323 +vn -0.3357 0.9372 -0.0950 +vn -0.2952 0.9050 -0.3063 +vn 0.0260 -0.8948 -0.4456 +vn 0.0264 -0.9554 -0.2942 +vn 0.0486 -0.9455 -0.3218 +vn 0.0317 0.6479 -0.7611 +vn 0.0185 0.4766 -0.8790 +vn 0.0585 0.5164 -0.8543 +vn 0.5658 0.3679 0.7379 +vn 0.7260 0.5077 0.4638 +vn 0.9226 0.2140 0.3210 +vn 0.5175 0.8467 0.1239 +vn 0.5871 0.7817 0.2102 +vn 0.8028 -0.5962 -0.0062 +vn 0.6821 -0.7197 -0.1296 +vn 0.8333 -0.4970 -0.2420 +vn 0.0161 -0.9999 -0.0003 +vn 0.2225 0.8348 0.5035 +vn 0.1972 0.8906 0.4098 +vn 0.1727 0.9140 0.3672 +vn 0.0003 -0.0008 1.0000 +vn -0.0143 -0.0059 0.9999 +vn -0.0203 -0.0034 0.9998 +vn 0.2807 -0.1198 -0.9523 +vn 0.2443 -0.1050 -0.9640 +vn 0.2689 -0.1493 -0.9515 +vn 0.1784 -0.7068 0.6846 +vn -0.1398 -0.6467 0.7498 +vn -0.4948 0.8429 -0.2114 +vn -0.3716 0.7299 -0.5737 +vn -0.4993 0.6617 -0.5593 +vn 0.5379 -0.8216 -0.1889 +vn 0.7311 -0.6242 -0.2755 +vn 0.8190 -0.5705 -0.0608 +vn -0.8820 0.4701 0.0338 +vn -0.8474 0.3735 0.3773 +vn -0.5550 -0.6213 0.5532 +vn -0.6695 -0.7278 0.1485 +vn -0.4578 -0.8784 0.1373 +vn 0.9507 0.0048 -0.3102 +vn -0.8193 0.5385 -0.1969 +vn -0.8193 0.5731 -0.0198 +vn -0.7899 0.5999 -0.1275 +vn 0.0358 0.7763 0.6293 +vn 0.0817 0.7528 0.6531 +vn 0.0620 0.6022 0.7959 +vn 0.0780 0.5868 -0.8060 +vn 0.0823 0.5147 -0.8534 +vn -0.1436 0.5570 -0.8180 +vn 0.0959 -0.6021 -0.7926 +vn 0.5989 -0.7016 -0.3861 +vn 0.5170 -0.7696 -0.3748 +vn -0.1549 0.1167 0.9810 +vn -0.3958 0.1219 0.9102 +vn -0.1093 0.2646 -0.9581 +vn 0.1203 -0.1300 -0.9842 +vn -0.8254 0.4712 0.3108 +vn -0.4643 -0.7123 0.5264 +vn 0.2406 0.0001 -0.9706 +vn 0.2502 -0.0002 -0.9682 +vn 0.2444 0.0007 -0.9697 +vn 0.1010 0.2577 -0.9609 +vn 0.4803 0.1839 -0.8576 +vn 0.1009 0.2577 -0.9609 +vn 0.5402 -0.0089 -0.8415 +vn -0.3234 0.5988 -0.7327 +vn -0.1016 0.9060 -0.4108 +vn -0.2209 -0.5395 0.8125 +vn 0.9738 -0.0603 -0.2194 +vn 0.9798 -0.1148 -0.1637 +vn 0.8768 -0.0143 -0.4806 +vn 0.5667 0.7382 -0.3659 +vn 0.7129 0.7012 -0.0138 +vn 0.6040 0.7049 -0.3719 +vn 0.9488 0.2146 -0.2317 +vn 0.7497 0.5935 -0.2928 +vn 0.2877 -0.2944 -0.9113 +vn 0.2494 -0.1490 -0.9569 +vn 0.3239 0.0094 -0.9460 +vn -0.7639 -0.2837 0.5796 +vn -0.5001 -0.8418 -0.2034 +vn -0.5120 -0.7671 -0.3866 +vn -0.2502 -0.9178 -0.3083 +vn 0.4497 -0.6387 -0.6244 +vn 0.5033 -0.5690 -0.6503 +vn 0.5856 -0.6693 -0.4573 +vn 0.2661 0.0759 -0.9609 +vn 0.2038 0.1562 -0.9665 +vn 0.2927 0.0568 -0.9545 +vn -0.5001 0.8418 -0.2034 +vn 0.6048 0.1838 0.7749 +vn 0.5821 0.1824 0.7924 +vn 0.8824 0.0244 0.4700 +vn -0.3194 0.7881 -0.5262 +vn -0.4390 0.6663 -0.6028 +vn 0.9680 -0.2276 -0.1060 +vn 0.9573 -0.2077 -0.2009 +vn 0.9248 -0.3129 0.2164 +vn -0.1838 -0.5481 0.8160 +vn -0.2565 -0.0004 0.9665 +vn -0.2597 -0.0006 0.9657 +vn -0.2585 -0.0002 0.9660 +vn -0.2646 0.3780 -0.8872 +vn -0.3868 0.3425 -0.8562 +vn 0.2034 0.8278 0.5229 +vn 0.9786 -0.0705 0.1934 +vn 0.1415 0.2585 0.9556 +vn 0.1415 0.1392 0.9801 +vn 0.1646 0.3098 0.9364 +vn 0.0588 0.3703 -0.9271 +vn 0.0475 0.3427 -0.9382 +vn 0.0324 0.3233 -0.9457 +vn -0.7424 -0.6634 -0.0938 +vn -0.5440 -0.7593 -0.3572 +vn 0.5331 0.2463 -0.8094 +vn 0.9324 -0.0149 0.3610 +vn 0.9325 -0.0149 0.3610 +vn -0.7035 0.1359 -0.6976 +vn -0.5954 -0.1293 -0.7929 +vn -0.8262 -0.3138 -0.4679 +vn 0.9729 0.2084 -0.1002 +vn 0.9904 -0.0592 0.1247 +vn 0.9523 -0.1133 -0.2833 +vn -0.5647 0.4543 0.6891 +vn -0.2976 0.5498 0.7805 +vn -0.5248 0.5209 0.6732 +vn 0.0735 -0.9951 -0.0662 +vn 0.0533 -0.9901 0.1299 +vn -0.8776 0.4673 -0.1070 +vn -0.8207 0.5550 -0.1359 +vn -0.6008 -0.6268 0.4961 +vn -0.4457 -0.6463 0.6194 +vn -0.4720 -0.5367 0.6994 +vn -0.3197 0.9475 0.0113 +vn 0.2108 0.1686 0.9629 +vn 0.1261 0.2067 0.9702 +vn 0.1849 0.0714 0.9802 +vn 0.1659 -0.8979 0.4076 +vn 0.1624 -0.9481 0.2733 +vn -0.3498 0.7837 0.5133 +vn -0.4177 0.8136 0.4044 +vn -0.5494 0.6355 0.5425 +vn 0.9973 0.0098 -0.0733 +vn 0.7852 -0.2462 -0.5681 +vn 0.9343 0.0029 -0.3564 +vn 0.9505 -0.2048 -0.2337 +vn 0.8759 0.0589 0.4788 +vn 0.6770 0.2005 0.7082 +vn 0.6223 0.1568 0.7669 +vn 0.9846 -0.0365 0.1707 +vn 0.9343 -0.0029 -0.3564 +vn 0.9505 0.2048 -0.2337 +vn -0.0470 -0.8261 -0.5615 +vn -0.7636 -0.6359 -0.1123 +vn -0.8232 -0.5585 -0.1020 +vn -0.7802 -0.5891 -0.2104 +vn 0.4559 -0.7128 0.5329 +vn 0.4483 -0.6210 0.6430 +vn 0.3440 -0.5747 0.7425 +vn 0.0772 0.6671 -0.7409 +vn 0.0492 0.6240 -0.7799 +vn 0.1159 0.4018 -0.9083 +vn 0.7141 -0.0762 -0.6959 +vn 0.6068 -0.1424 -0.7820 +vn 0.6749 -0.1654 -0.7192 +vn -0.3194 -0.7881 -0.5262 +vn -0.3764 -0.8236 -0.4242 +vn 0.9488 -0.2146 -0.2317 +vn -0.4351 -0.8528 0.2889 +vn -0.2785 -0.9162 0.2882 +vn -0.2806 -0.9161 0.2863 +vn 0.1209 0.8394 -0.5299 +vn 0.2283 0.6244 -0.7470 +vn -0.0296 0.7789 -0.6265 +vn -0.2635 -0.0001 0.9646 +vn -0.2601 0.0001 0.9656 +vn -0.2640 -0.0002 0.9645 +vn -0.2917 0.9406 -0.1736 +vn -0.4973 0.8446 -0.1981 +vn 0.6040 -0.7049 -0.3719 +vn 0.6945 0.6775 -0.2422 +vn 0.7039 0.5985 -0.3825 +vn 0.7211 0.6084 -0.3315 +vn -0.5398 -0.8040 0.2493 +vn -0.1951 0.3115 0.9300 +vn 0.1186 0.2788 0.9530 +vn 0.1588 0.2793 0.9470 +vn 0.4446 -0.8887 -0.1117 +vn 0.2548 -0.9311 -0.2610 +vn -0.8989 0.0630 0.4335 +vn -0.8557 0.1737 0.4874 +vn -0.9213 -0.2021 -0.3322 +vn -0.9213 -0.2020 -0.3322 +vn -0.0110 0.9999 0.0001 +vn -0.0061 1.0000 0.0003 +vn -0.0084 0.9998 0.0197 +vn 0.7439 0.0126 0.6682 +vn 0.1896 0.3548 -0.9155 +vn 0.1980 0.7005 -0.6856 +vn 0.0763 0.8756 -0.4770 +vn -0.5959 0.7527 -0.2798 +vn -0.6986 0.7083 -0.1015 +vn -0.6022 0.7783 -0.1778 +vn -0.8955 -0.3945 -0.2061 +vn -0.9659 -0.1706 -0.1948 +vn 0.2283 -0.3014 0.9258 +vn 0.2206 -0.2898 0.9313 +vn 0.0006 0.2263 0.9741 +vn -0.2864 0.0631 0.9560 +vn -0.2945 0.0025 0.9557 +vn -0.3444 0.3280 0.8796 +vn -0.6819 0.3014 0.6665 +vn 0.5443 0.3314 -0.7706 +vn 0.7266 0.6859 -0.0402 +vn 0.0903 -0.0254 0.9956 +vn 0.0637 -0.0421 0.9971 +vn 0.1116 0.0017 0.9938 +vn -0.0416 0.7404 0.6709 +vn -0.2256 0.7623 0.6066 +vn -0.0545 0.7004 0.7117 +vn 0.3100 -0.8976 0.3133 +vn 0.3527 -0.8219 0.4473 +vn 0.8435 0.0664 0.5329 +vn 0.9313 0.0009 0.3644 +vn 0.8003 0.0946 0.5921 +vn -0.4692 -0.8800 -0.0734 +vn -0.5697 -0.7886 -0.2313 +vn -0.4766 -0.7930 -0.3796 +vn 0.9324 0.0085 0.3614 +vn 0.8413 0.0073 0.5406 +vn 0.8413 0.0073 0.5405 +vn -0.1787 0.6356 0.7511 +vn 0.0938 0.6337 0.7679 +vn 0.2118 0.6701 0.7114 +vn 0.0948 0.9736 -0.2076 +vn 0.1065 0.9552 -0.2762 +vn 0.0960 0.9907 -0.0969 +vn -0.1188 -0.9447 0.3058 +vn 0.1391 0.7078 0.6926 +vn -0.1629 0.9040 -0.3952 +vn 0.1273 0.0086 -0.9918 +vn -0.3462 0.0087 -0.9381 +vn -0.3101 0.0118 -0.9506 +vn -0.4525 0.7472 -0.4868 +vn -0.6563 0.6768 -0.3334 +vn -0.3948 0.8842 -0.2497 +vn 0.3420 0.9280 0.1476 +vn 0.6413 0.7075 0.2971 +vn -0.6467 -0.5468 -0.5317 +vn -0.6005 -0.7130 -0.3621 +vn -0.7265 -0.5697 -0.3842 +vn -0.8316 0.1329 -0.5392 +vn 0.1473 -0.2887 -0.9460 +vn 0.0016 -0.9997 -0.0226 +vn -0.0038 -0.9999 -0.0131 +vn 0.0346 -0.9899 -0.1376 +vn 0.3773 0.7193 -0.5833 +vn -0.4113 0.9114 0.0158 +vn -0.4988 0.8401 -0.2132 +vn -0.7000 0.7137 0.0244 +vn 0.6846 -0.7283 -0.0295 +vn 0.7178 -0.6947 -0.0470 +vn 0.5780 -0.7842 0.2259 +vn -0.4346 0.1143 0.8933 +vn -0.5825 0.1187 0.8041 +vn -0.5021 -0.1175 0.8568 +vn 0.1427 -0.0789 0.9866 +vn 0.4318 -0.2566 0.8647 +vn -0.3889 0.7715 0.5035 +vn -0.1649 0.8523 0.4963 +vn -0.5294 0.7620 0.3730 +vn 0.8811 0.2673 0.3902 +vn -0.6452 0.4868 -0.5889 +vn -0.8883 0.3770 -0.2624 +vn 0.3677 -0.4975 0.7856 +vn -0.1477 -0.7856 0.6008 +vn -0.3962 0.8137 -0.4253 +vn 0.0628 -0.9949 -0.0793 +vn 0.0494 -0.9984 -0.0264 +vn 0.0525 -0.9929 -0.1068 +vn -0.6302 -0.2409 -0.7382 +vn -0.5104 0.8596 -0.0242 +vn -0.6340 0.7733 0.0034 +vn 0.0620 0.7947 0.6038 +vn -0.1886 0.8079 0.5583 +vn -0.9994 -0.0098 0.0330 +vn -0.9324 -0.0085 -0.3614 +vn 0.2494 0.5522 -0.7955 +vn 0.3849 0.9046 0.1833 +vn -0.0282 0.9060 0.4223 +vn 0.3769 0.8584 0.3480 +vn -0.7999 -0.2527 0.5443 +vn -0.7759 -0.4565 0.4354 +vn -0.1971 0.0228 -0.9801 +vn -0.3742 0.0837 -0.9236 +vn -0.4845 0.5027 -0.7159 +vn 0.6718 -0.0673 -0.7377 +vn 0.5261 -0.3220 -0.7871 +vn 0.5987 -0.0838 -0.7966 +vn -0.0192 0.9924 -0.1213 +vn 0.0784 0.9962 0.0375 +vn -0.0141 0.9983 -0.0566 +vn 0.5402 -0.0037 -0.8415 +vn 0.7789 0.0003 -0.6271 +vn 0.8472 -0.0032 -0.5313 +vn 0.9660 0.2457 -0.0801 +vn 0.9162 0.3017 0.2636 +vn 0.9594 -0.1047 -0.2621 +vn -0.1187 0.9447 0.3057 +vn 0.1049 0.5772 -0.8099 +vn 0.9172 0.3685 0.1512 +vn -0.9865 -0.1572 0.0458 +vn -0.8051 -0.5772 0.1368 +vn -0.9033 -0.2748 0.3294 +vn 0.1134 -0.9227 -0.3684 +vn 0.1135 -0.9227 -0.3684 +vn 0.6117 -0.3425 -0.7131 +vn 0.5562 -0.4084 -0.7238 +vn 0.1188 -0.9447 -0.3057 +vn 0.4784 0.2891 0.8292 +vn 0.2946 0.2902 0.9105 +vn 0.9995 0.0032 -0.0303 +vn 0.9999 0.0083 0.0068 +vn 0.8646 0.0186 0.5021 +vn 0.9213 -0.2020 0.3322 +vn 0.9836 -0.1459 0.1061 +vn 0.9922 -0.1199 0.0346 +vn 0.0536 0.2135 -0.9755 +vn 0.0261 0.4495 -0.8929 +vn 0.1434 -0.5122 -0.8468 +vn 0.5106 -0.4328 -0.7429 +vn 0.3816 -0.7615 -0.5239 +vn 0.0479 -0.9985 -0.0279 +vn -0.7419 0.6305 -0.2282 +vn 0.5803 -0.6784 -0.4506 +vn 0.0448 0.9874 0.1515 +vn 0.0171 0.9708 0.2394 +vn 0.0247 0.9918 0.1250 +vn -0.1538 0.6959 0.7015 +vn -0.2098 0.3945 0.8946 +vn 0.3255 0.1641 -0.9312 +vn 0.2663 0.1661 -0.9495 +vn 0.1437 -0.1489 0.9784 +vn -0.9815 -0.1202 0.1492 +vn -0.9944 0.0998 -0.0346 +vn -0.9897 0.0942 -0.1081 +vn -0.9610 -0.1084 0.2543 +vn -0.0629 0.8879 -0.4558 +vn -0.1308 0.9852 -0.1112 +vn 0.1492 0.9217 -0.3579 +vn 0.9692 -0.0104 0.2459 +vn 0.9005 -0.0117 0.4348 +vn 0.2515 0.0732 0.9651 +vn 0.2623 -0.0017 0.9650 +vn -0.0547 0.5095 0.8587 +vn 0.1639 0.5716 0.8040 +vn 0.1075 0.9125 -0.3947 +vn 0.1368 -0.7684 -0.6252 +vn 0.2376 -0.7637 -0.6002 +vn 0.1318 -0.8833 -0.4499 +vn 0.7437 0.0061 0.6685 +vn -0.2884 -0.6973 0.6562 +vn -0.4606 -0.4353 0.7736 +vn -0.4071 -0.7052 0.5805 +vn 0.1641 -0.8341 -0.5266 +vn -0.0592 0.9871 -0.1484 +vn -0.0735 0.9919 -0.1034 +vn -0.5624 -0.0083 -0.8269 +vn -0.7702 -0.0122 -0.6377 +vn -0.6901 -0.0059 -0.7237 +vn 0.0474 0.8758 0.4803 +vn 0.1143 0.8999 0.4208 +vn 0.0182 0.9833 0.1811 +vn -0.7913 -0.0044 0.6114 +vn -0.7262 -0.0078 0.6874 +vn -0.8113 -0.0184 0.5843 +vn -0.3401 0.9403 0.0127 +vn 0.0420 0.0003 -0.9991 +vn 0.1124 0.0017 -0.9937 +vn 0.0415 0.0004 -0.9991 +vn 0.2068 0.0078 -0.9784 +vn 0.2067 0.0078 -0.9784 +vn 0.0257 -0.0012 0.9997 +vn 0.0256 0.0168 0.9995 +vn 0.0507 0.1030 0.9934 +vn -0.8536 0.0642 0.5170 +vn -0.7099 0.0582 0.7019 +vn -0.9402 0.0602 0.3353 +vn 0.0599 -0.9974 -0.0409 +vn 0.0609 -0.9974 -0.0377 +vn 0.0696 -0.9924 -0.1013 +vn 0.1273 -0.7047 -0.6979 +vn 0.3359 -0.7879 -0.5161 +vn 0.1093 -0.7584 -0.6425 +vn -0.2986 0.6930 0.6562 +vn -0.4100 0.3922 0.8235 +vn -0.2936 0.4333 0.8521 +vn -0.8995 0.4343 0.0469 +vn -0.7052 0.7072 0.0504 +vn -0.6855 0.6920 0.2264 +vn -0.7948 0.5996 0.0932 +vn -0.4729 0.8361 0.2780 +vn -0.3780 0.9251 0.0374 +vn -0.2847 0.9586 0.0108 +vn -0.0161 0.9999 0.0003 +vn 0.8904 0.0532 0.4522 +vn 0.9235 0.0067 0.3836 +vn 0.5072 0.8612 -0.0318 +vn 0.6028 0.7387 0.3016 +vn 0.6168 0.7327 0.2877 +vn 0.2687 0.9306 -0.2484 +vn 0.1073 0.8991 -0.4244 +vn -0.7902 -0.1529 -0.5935 +vn -0.9513 -0.0993 -0.2918 +vn -0.0615 -0.2812 -0.9577 +vn -0.4762 -0.2923 -0.8293 +vn -0.4068 -0.2910 -0.8660 +vn 0.0589 -0.5904 0.8049 +vn 0.0337 -0.5054 0.8622 +vn 0.0403 -0.3212 0.9461 +vn -0.7700 -0.0064 -0.6380 +vn -0.6898 -0.0005 -0.7240 +vn 0.0098 1.0000 -0.0017 +vn -0.3130 0.6339 -0.7073 +vn 0.5658 -0.7413 0.3611 +vn 0.4290 -0.8026 0.4145 +vn 0.6395 -0.7438 0.1943 +vn 0.8575 0.5077 -0.0835 +vn 0.9639 -0.2044 -0.1707 +vn 0.9744 -0.2082 -0.0843 +vn 0.3134 -0.9399 -0.1353 +vn 0.6073 -0.7771 -0.1649 +vn 0.5664 -0.8239 0.0187 +vn 0.0747 -0.9524 0.2954 +vn 0.0810 -0.9490 0.3046 +vn 0.0284 -0.9688 0.2463 +vn -0.3085 0.9237 -0.2272 +vn -0.4243 0.6251 -0.6552 +vn -0.5336 0.6366 -0.5568 +vn -0.1942 0.3762 -0.9060 +vn -0.3731 0.3825 -0.8453 +vn -0.3261 0.5461 -0.7716 +vn 0.4443 -0.7322 0.5162 +vn 0.4516 -0.5968 0.6633 +vn 0.1805 -0.7486 0.6379 +vn 0.9502 -0.2089 -0.2311 +vn 0.2730 0.1504 -0.9502 +vn 0.3144 0.1544 -0.9366 +vn -0.7289 0.6774 0.0986 +vn -0.6657 0.7068 0.2395 +vn -0.4613 0.8845 0.0689 +vn -0.0077 -0.7644 0.6447 +vn -0.2247 -0.7695 0.5978 +vn 0.7102 0.5499 0.4397 +vn 0.7078 0.6332 0.3131 +vn 0.7084 0.5522 0.4395 +vn 0.0391 -0.7998 -0.5990 +vn -0.9027 -0.1111 0.4157 +vn -0.8554 -0.0675 0.5136 +vn -0.3172 -0.6333 -0.7059 +vn -0.0668 -0.7250 -0.6855 +vn -0.2211 -0.7565 -0.6155 +vn 0.2781 0.8098 -0.5167 +vn -0.1130 -0.9567 -0.2684 +vn -0.4080 -0.1164 0.9055 +vn -0.3850 -0.3977 0.8329 +vn -0.9156 -0.2832 0.2854 +vn -0.9419 -0.1225 0.3127 +vn -0.9507 -0.1428 0.2754 +vn -0.5083 0.7211 0.4707 +vn -0.1955 0.9250 0.3259 +vn -0.2849 0.9123 0.2942 +vn -0.3195 -0.4991 -0.8055 +vn -0.5106 -0.5713 -0.6426 +vn 0.2013 -0.5253 0.8268 +vn 0.2107 -0.7968 0.5664 +vn -0.0752 0.9233 0.3767 +vn -0.6912 0.1222 0.7123 +vn -0.5973 0.4463 0.6664 +vn -0.6780 0.4115 0.6090 +vn -0.2597 -0.0008 0.9657 +vn -0.2595 -0.0003 0.9658 +vn 0.8157 -0.5540 -0.1664 +vn -0.3933 0.2988 -0.8695 +vn -0.2419 0.3340 -0.9110 +vn -0.2564 -0.0005 0.9666 +vn -0.2547 0.0004 0.9670 +vn -0.2550 -0.0005 0.9669 +vn -0.5299 -0.8470 0.0414 +vn -0.6912 -0.7206 0.0549 +vn -0.8228 -0.5586 -0.1050 +vn 0.6919 0.0418 -0.7208 +vn 0.5701 -0.8215 -0.0074 +vn 0.5073 -0.8612 -0.0318 +vn 0.3735 -0.9142 -0.1572 +vn 0.0893 -0.9911 -0.0989 +vn 0.0791 -0.9939 -0.0763 +vn 0.0766 -0.9537 -0.2908 +vn -0.6522 0.7294 -0.2066 +vn -0.7213 -0.6888 -0.0723 +vn -0.7711 -0.6350 -0.0465 +vn -0.7419 -0.6305 -0.2282 +vn -0.4985 -0.4768 0.7240 +vn -0.0748 -0.4333 0.8981 +vn -0.3485 -0.4538 0.8201 +vn 0.5359 0.7197 0.4414 +vn 0.6149 0.7307 0.2966 +vn 0.0414 -0.9983 -0.0403 +vn 0.0388 -0.9924 -0.1167 +vn 0.0399 -0.9982 -0.0437 +vn 0.0215 -0.9989 -0.0410 +vn 0.9928 0.0875 -0.0817 +vn 0.9601 0.0348 -0.2775 +vn 0.9835 0.1499 0.1017 +vn -0.5412 0.7991 0.2618 +vn 0.8313 0.0585 -0.5527 +vn 0.1042 0.9886 0.1084 +vn 0.1073 0.9858 0.1295 +vn 0.1152 0.9644 0.2381 +vn -0.6005 0.7130 -0.3621 +vn -0.9560 -0.0256 -0.2924 +vn 0.8235 -0.5634 -0.0664 +vn 0.5443 -0.8154 -0.1970 +vn -0.5515 -0.7070 -0.4428 +vn -0.4481 -0.7124 -0.5401 +vn 0.5781 -0.0488 -0.8145 +vn 0.6730 -0.0735 -0.7360 +vn 0.1791 0.4173 0.8910 +vn 0.1015 0.1455 0.9841 +vn 0.6001 0.4128 0.6852 +vn 0.7545 0.4270 0.4984 +vn 0.6200 0.5910 0.5161 +vn -0.3465 -0.6653 0.6613 +vn -0.0248 -0.7726 0.6344 +vn -0.1799 -0.6777 0.7130 +vn -0.0102 0.8053 0.5927 +vn -0.2971 -0.6539 -0.6958 +vn -0.4845 -0.5027 -0.7159 +vn 0.2528 0.4357 0.8639 +vn 0.2329 0.2187 0.9476 +vn 0.1025 -0.1229 -0.9871 +vn 0.1387 -0.2683 -0.9533 +vn -0.2934 -0.4333 0.8522 +vn -0.1538 -0.6959 0.7015 +vn -0.7669 -0.1199 -0.6305 +vn -0.7547 -0.3506 -0.5546 +vn -0.9707 -0.2246 0.0849 +vn -0.6055 -0.7149 0.3496 +vn -0.8336 -0.3042 0.4612 +vn 0.7600 0.3613 -0.5402 +vn 0.6900 0.4626 -0.5567 +vn -0.0442 -0.0003 0.9990 +vn 0.0933 0.0009 0.9956 +vn 0.0925 0.0006 0.9957 +vn -0.9325 0.0112 -0.3609 +vn -0.9994 0.0079 0.0335 +vn -0.5786 0.7913 -0.1976 +vn -0.6477 0.6804 -0.3429 +vn -0.6014 0.0037 0.7989 +vn -0.5447 -0.0124 0.8385 +vn -0.4641 -0.1182 0.8779 +vn 0.6151 0.7211 0.3187 +vn 0.6418 0.6985 0.3165 +vn -0.4526 -0.8302 -0.3254 +vn -0.5641 0.0121 -0.8256 +vn -0.2305 0.0067 -0.9730 +vn -0.4931 0.0063 -0.8700 +vn -0.0743 0.9940 -0.0802 +vn -0.5952 0.0125 -0.8035 +vn -0.7179 0.0094 -0.6961 +vn -0.7702 0.0126 -0.6376 +vn 0.6800 0.7326 -0.0303 +vn 0.5729 0.7881 0.2250 +vn 0.7134 0.6991 -0.0478 +vn -0.0965 -0.0010 -0.9953 +vn -0.1631 -0.0004 -0.9866 +vn -0.1631 -0.0008 -0.9866 +vn 0.9213 0.2020 0.3321 +vn 0.6907 -0.0108 0.7230 +vn 0.6732 -0.0622 0.7368 +vn 0.8377 -0.0045 0.5461 +vn 0.7007 0.2205 -0.6786 +vn 0.7115 0.3270 -0.6219 +vn 0.7060 0.3744 -0.6011 +vn 0.7090 0.6868 0.1597 +vn 0.7082 0.6855 0.1691 +vn 0.7044 0.6688 0.2378 +vn -0.9902 -0.0675 -0.1226 +vn -0.9976 -0.0075 -0.0695 +vn -0.9083 -0.1532 -0.3892 +vn -0.0957 -0.0007 -0.9954 +vn 0.3891 -0.3778 -0.8402 +vn 0.2338 -0.3847 -0.8929 +vn -0.1240 -0.3470 -0.9296 +vn -0.6843 0.7247 0.0811 +vn -0.5557 0.8290 0.0627 +vn -0.4654 -0.2679 -0.8436 +vn -0.3766 0.0798 -0.9229 +vn 0.3464 -0.1743 -0.9217 +vn -0.9141 -0.1717 0.3674 +vn -0.9317 -0.1309 0.3388 +vn 0.0463 -0.2146 0.9756 +vn 0.0629 -0.1760 0.9824 +vn 0.5067 -0.1568 0.8477 +vn 0.1932 -0.0255 0.9808 +vn 0.0938 0.9956 -0.0025 +vn 0.0903 0.9910 0.0992 +vn 0.1417 0.7783 -0.6117 +vn 0.0526 0.7970 -0.6017 +vn 0.1011 0.9067 -0.4096 +vn -0.0166 0.0260 -0.9995 +vn 0.0045 -0.0171 -0.9998 +vn 0.0096 0.9410 0.3382 +vn 0.0168 0.9998 0.0124 +vn 0.0309 0.8187 -0.5734 +vn -0.8003 0.2473 -0.5463 +vn -0.6226 0.2189 -0.7513 +vn -0.7380 -0.0854 -0.6694 +vn 0.9193 -0.3604 0.1583 +vn 0.8319 -0.5511 -0.0647 +vn 0.7101 0.6947 -0.1148 +vn 0.6676 0.7427 -0.0520 +vn 0.7556 0.6517 0.0662 +vn -0.8936 0.3989 -0.2060 +vn -0.2513 -0.9629 0.0988 +vn -0.0935 -0.9885 0.1192 +vn -0.2751 -0.9453 0.1751 +vn -0.9855 0.1491 0.0808 +vn -0.9920 0.0845 0.0938 +vn 0.0248 0.3894 0.9208 +vn 0.0275 0.4439 0.8956 +vn -0.7140 0.0518 0.6982 +vn -0.5647 -0.4543 0.6891 +vn 0.3512 -0.7014 -0.6203 +vn 0.4710 -0.4469 -0.7605 +vn 0.1606 0.6267 0.7625 +vn 0.1647 0.6590 0.7339 +vn 0.1727 0.5091 0.8432 +vn 0.1576 0.3745 0.9137 +vn 0.1579 0.3833 0.9100 +vn -0.4765 0.6432 0.5993 +vn -0.0175 0.9080 0.4186 +vn 0.7907 -0.0242 -0.6117 +vn 0.8863 0.0059 -0.4630 +vn 0.8999 -0.0208 -0.4355 +vn 0.1943 -0.9442 -0.2658 +vn -0.3256 0.9445 0.0427 +vn -0.1203 0.7419 -0.6597 +vn 0.1211 0.7914 -0.5992 +vn -0.1510 0.7092 -0.6886 +vn 0.6207 -0.7071 0.3388 +vn 0.5430 -0.7736 0.3268 +vn 0.3474 -0.9213 0.1747 +vn 0.7658 -0.3703 0.5258 +vn 0.9738 0.0603 -0.2194 +vn 0.9812 0.0955 -0.1677 +vn -0.3052 0.1175 0.9450 +vn -0.6824 -0.7258 0.0866 +vn -0.1673 -0.2845 -0.9440 +vn -0.3782 0.6285 0.6797 +vn -0.1477 0.7856 0.6008 +vn -0.6245 -0.7773 -0.0767 +vn -0.8264 -0.4710 0.3086 +vn -0.0160 -0.9999 0.0002 +vn 0.1901 0.1635 0.9681 +vn 0.1889 0.1520 0.9702 +vn 0.1642 -0.9360 0.3114 +vn -0.0894 -0.8658 0.4924 +vn -0.0836 -0.8961 0.4360 +vn 0.1942 0.1867 0.9630 +vn -0.6852 -0.3414 0.6434 +vn -0.4909 -0.3775 0.7852 +vn -0.4222 -0.3804 0.8229 +vn 0.8337 0.2576 -0.4885 +vn 0.2068 -0.3425 0.9165 +vn 0.2060 -0.3466 0.9151 +vn 0.7054 -0.1394 -0.6950 +vn 0.0221 0.3940 -0.9188 +vn 0.0471 -0.5638 -0.8246 +vn -0.3429 -0.7797 -0.5239 +vn -0.9645 0.0299 0.2624 +vn 0.1678 -0.6839 -0.7100 +vn 0.1157 -0.9268 -0.3573 +vn 0.2735 0.0246 0.9616 +vn 0.2707 0.0252 0.9623 +vn -0.1377 0.3707 -0.9185 +vn 0.5827 -0.1678 0.7952 +vn 0.0499 -0.3249 0.9444 +vn 0.3041 -0.0512 0.9513 +vn 0.6355 -0.7237 0.2691 +vn 0.4548 0.0190 0.8904 +vn 0.3856 0.0122 0.9226 +vn 0.6877 0.0134 0.7259 +vn 0.8235 0.5634 -0.0664 +vn 0.6069 0.7944 0.0253 +vn 0.2698 -0.7402 -0.6159 +vn -0.5226 0.8479 -0.0895 +vn 0.6028 -0.7387 0.3016 +vn -0.2520 0.0316 0.9672 +vn 0.2221 -0.0072 0.9750 +vn 0.5362 -0.8310 0.1479 +vn 0.0595 0.9980 -0.0234 +vn 0.0388 0.9934 -0.1080 +vn -0.0437 -0.0003 0.9990 +vn -0.1772 0.2836 -0.9424 +vn -0.1385 0.2826 -0.9492 +vn -0.5834 -0.8103 0.0545 +vn -0.7111 -0.6908 0.1310 +vn 0.0115 -0.8056 -0.5924 +vn 0.0234 -0.9189 -0.3938 +vn -0.6991 -0.5634 -0.4402 +vn -0.6113 -0.5304 -0.5874 +vn 0.0787 0.5139 -0.8542 +vn 0.0863 0.6366 -0.7664 +vn -0.0083 0.9999 -0.0098 +vn 0.2818 0.9590 -0.0307 +vn -0.0083 0.9999 -0.0097 +vn -0.2460 0.9112 -0.3304 +vn -0.5107 0.7634 -0.3955 +vn -0.6776 -0.7312 -0.0792 +vn -0.8863 -0.4348 0.1595 +vn 0.0778 -0.9964 0.0344 +vn 0.0460 -0.8858 0.4618 +vn -0.2882 -0.9126 0.2901 +vn -0.9919 -0.0562 -0.1135 +vn -0.9936 -0.0040 -0.1132 +vn -0.8572 -0.2905 -0.4253 +vn 0.1250 0.3754 0.9184 +vn 0.9150 0.0094 0.4033 +vn 0.4158 -0.3060 -0.8564 +vn 0.4223 -0.0898 -0.9020 +vn 0.5489 -0.0952 -0.8305 +vn 0.7153 0.4428 0.5406 +vn 0.7151 0.4895 0.4990 +vn -0.9533 0.1389 0.2682 +vn -0.1278 -0.2908 -0.9482 +vn -0.0906 -0.2918 -0.9522 +vn 0.2297 -0.3252 -0.9173 +vn -0.1130 0.9567 -0.2684 +vn 0.1508 -0.5491 -0.8220 +vn -0.6682 -0.0017 0.7440 +vn 0.0677 0.9960 -0.0581 +vn 0.0754 0.9850 -0.1551 +vn 0.1385 0.2827 0.9492 +vn -0.8244 0.1680 0.5405 +vn 0.1508 0.5491 -0.8220 +vn 0.1603 0.0005 0.9871 +vn 0.1603 0.0008 0.9871 +vn 0.1385 -0.9077 -0.3960 +vn 0.0633 -0.9326 -0.3554 +vn -0.0113 -0.8323 -0.5542 +vn 0.0246 0.0016 0.9997 +vn 0.0608 -0.1283 0.9899 +vn 0.4464 -0.7883 -0.4234 +vn 0.4446 -0.6484 -0.6180 +vn -0.1589 0.8668 -0.4727 +vn -0.3429 0.7797 -0.5239 +vn -0.7099 -0.0582 0.7019 +vn -0.2519 -0.0342 0.9671 +vn -0.5325 -0.1705 0.8291 +vn -0.3486 0.4538 0.8201 +vn -0.4985 0.4767 0.7240 +vn -0.5639 0.4107 0.7165 +vn 0.5237 0.3212 -0.7890 +vn 0.7639 0.2836 -0.5796 +vn -0.1908 -0.8656 0.4629 +vn 0.1474 -0.7256 0.6722 +vn -0.0089 -1.0000 -0.0023 +vn -0.0075 -1.0000 -0.0050 +vn -0.0053 -0.9993 -0.0375 +vn 0.2358 0.7134 0.6599 +vn 0.2389 0.7477 0.6196 +vn 0.1469 0.9239 0.3534 +vn 0.1243 -0.9906 0.0567 +vn 0.1194 -0.9904 -0.0700 +vn 0.8897 0.0169 0.4562 +vn 0.9227 -0.0251 0.3847 +vn 0.7670 0.3170 -0.5579 +vn 0.7669 0.3170 -0.5579 +vn 0.7204 -0.0758 -0.6894 +vn 0.1922 0.9122 0.3619 +vn -0.1758 0.8005 -0.5730 +vn 0.1639 -0.5716 0.8040 +vn 0.0320 0.9965 -0.0775 +vn 0.0417 0.9979 -0.0485 +vn 0.0018 -0.8950 0.4461 +vn -0.6342 -0.1645 -0.7555 +vn -0.8218 -0.0793 -0.5643 +vn 0.2250 0.8714 -0.4359 +vn -0.0828 -0.9132 0.3989 +vn 0.0236 -0.9986 -0.0477 +vn -0.0682 -0.9966 -0.0467 +vn -0.0585 -0.9940 -0.0925 +vn 0.5238 0.3212 -0.7890 +vn -0.9970 0.0258 -0.0723 +vn -0.9250 -0.2327 -0.3005 +vn -0.9976 0.0075 -0.0695 +vn -0.1244 -0.6341 -0.7632 +vn -0.4108 -0.6372 -0.6521 +vn 0.8999 0.0208 -0.4355 +vn -0.9858 0.1508 0.0741 +vn -0.9657 0.0152 -0.2593 +vn -0.9804 0.1630 0.1110 +vn 0.3399 -0.5542 -0.7599 +vn -0.1738 0.5999 -0.7810 +vn -0.2582 0.2326 0.9377 +vn -0.4449 0.1928 0.8746 +vn -0.1385 -0.2826 -0.9492 +vn 0.2067 -0.0036 -0.9784 +vn 0.9637 -0.1924 -0.1853 +vn 0.7669 -0.3170 -0.5579 +vn 0.7670 -0.3170 -0.5579 +vn -0.7364 0.5672 0.3689 +vn -0.2071 -0.0037 0.9783 +vn 0.2621 0.5505 0.7927 +vn 0.0540 0.6933 -0.7186 +vn -0.0948 0.7566 -0.6470 +vn 0.7236 -0.6892 -0.0381 +vn 0.3962 0.3566 -0.8461 +vn 0.5975 0.4828 -0.6403 +vn 0.4062 -0.0347 -0.9131 +vn 0.0410 -0.5689 -0.8214 +vn 0.0243 -0.4870 -0.8731 +vn 0.0403 -0.6617 -0.7487 +vn 0.0742 -0.9803 -0.1833 +vn -0.5856 -0.6747 -0.4492 +vn -0.6126 -0.5067 -0.6066 +vn 0.1966 0.7419 0.6411 +vn 0.1692 0.8009 0.5744 +vn -0.2683 -0.0037 -0.9633 +vn -0.2323 0.0006 -0.9726 +vn -0.3942 0.7090 -0.5847 +vn -0.3577 -0.9331 -0.0360 +vn -0.5788 -0.8152 -0.0231 +vn -0.1802 0.1369 0.9741 +vn -0.1053 0.0006 0.9944 +vn -0.1203 0.0054 0.9927 +vn -0.3742 -0.0837 -0.9236 +vn -0.0082 -0.9999 -0.0098 +vn -0.1311 0.9795 -0.1530 +vn 0.7307 0.4031 0.5510 +vn 0.6351 0.7286 0.2565 +vn 0.5470 0.7421 0.3874 +vn 0.1143 -0.7128 0.6920 +vn -0.0324 0.9616 0.2725 +vn -0.5956 0.5878 0.5475 +vn -0.6979 0.2584 0.6680 +vn 0.8632 -0.0059 0.5049 +vn 0.9807 0.0103 0.1955 +vn 0.1988 -0.9502 -0.2402 +vn -0.6834 -0.6880 0.2442 +vn -0.0384 -0.9793 -0.1989 +vn 0.0755 -0.9635 -0.2568 +vn 0.0704 -0.6892 0.7211 +vn 0.0215 -0.6715 0.7407 +vn 0.0264 -0.6036 0.7969 +vn 0.8695 -0.0422 -0.4921 +vn 0.0298 -0.9940 -0.1052 +vn 0.4217 -0.3220 -0.8476 +vn 0.5237 -0.3212 -0.7890 +vn 0.0222 0.0090 0.9997 +vn -0.6434 0.3260 -0.6927 +vn -0.5145 0.3010 -0.8029 +vn 0.6842 0.6664 0.2964 +vn 0.9333 0.3229 0.1572 +vn -0.5437 0.5211 -0.6580 +vn -0.0841 -0.3605 -0.9289 +vn 0.6919 -0.0385 -0.7210 +vn 0.7832 0.2580 -0.5657 +vn 0.9343 0.0080 -0.3564 +vn -0.5901 0.7364 0.3309 +vn -0.7806 0.4534 0.4303 +vn -0.7097 0.4843 0.5116 +vn 0.1259 0.7217 0.6807 +vn -0.0370 -0.0008 0.9993 +vn -0.0516 -0.0015 0.9987 +vn -0.0334 -0.0013 0.9994 +vn 0.0590 -0.0036 -0.9983 +vn -0.1116 -0.0117 -0.9937 +vn 0.0471 0.5638 -0.8246 +vn -0.8200 -0.1217 -0.5593 +vn -0.9443 -0.0082 -0.3291 +vn -0.1108 -0.9917 -0.0651 +vn 0.2224 -0.0788 0.9718 +vn 0.7816 -0.0251 0.6233 +vn 0.5472 0.1115 0.8296 +vn 0.2572 -0.4290 0.8659 +vn 0.2467 -0.1338 0.9598 +vn -0.6669 -0.0111 0.7451 +vn -0.7791 -0.0089 0.6268 +vn -0.9073 -0.0128 0.4202 +vn -0.6917 -0.0035 0.7222 +vn -0.2520 -0.0316 0.9672 +vn -0.4743 0.2393 0.8472 +vn 0.0284 0.4940 -0.8690 +vn 0.4987 -0.5794 -0.6446 +vn 0.7832 -0.2580 -0.5657 +vn -0.2131 -0.0149 0.9769 +vn -0.9536 -0.1386 0.2674 +vn -0.9569 -0.1229 0.2631 +vn 0.1611 0.3087 -0.9374 +vn 0.4501 -0.8880 -0.0940 +vn 0.1187 -0.9447 -0.3057 +vn 0.6978 -0.6703 0.2524 +vn -0.7437 -0.0061 -0.6685 +vn -0.1899 0.9797 0.0643 +vn -0.2342 0.9717 0.0295 +vn -0.1932 0.9805 0.0354 +vn -0.2616 0.9019 0.3437 +vn -0.5441 0.8020 0.2467 +vn -0.9213 0.2025 -0.3320 +vn 0.8753 -0.4766 -0.0821 +vn 0.7924 -0.6078 0.0527 +vn 0.4048 -0.8050 0.4337 +vn -0.4967 -0.8453 -0.1969 +vn -0.0379 0.8400 -0.5413 +vn 0.5729 -0.7881 0.2249 +vn 0.4518 -0.7371 0.5026 +vn 0.6800 -0.7326 -0.0304 +vn 0.2169 0.7309 0.6471 +vn 0.4194 0.6063 0.6756 +vn -0.1287 -0.5402 -0.8316 +vn 0.8434 0.2307 -0.4852 +vn 0.9506 0.0146 -0.3102 +vn 0.9998 0.0161 0.0068 +vn 0.9975 0.0096 -0.0694 +vn 0.2544 0.7525 -0.6074 +vn -0.3000 0.9502 -0.0844 +vn 0.9345 -0.0026 -0.3561 +vn -0.1758 -0.8005 -0.5730 +vn -0.0789 0.1286 0.9886 +vn -0.0284 -0.1101 0.9935 +vn 0.0263 0.1474 0.9887 +vn -0.2460 -0.9112 -0.3304 +vn -0.3854 -0.9192 0.0811 +vn -0.4735 -0.8787 0.0614 +vn -0.3901 -0.9205 0.0230 +vn -0.2518 -0.9677 0.0154 +vn -0.7937 -0.6050 0.0634 +vn -0.6942 -0.7197 0.0134 +vn -0.6668 -0.7386 0.0993 +vn 0.6337 0.2982 -0.7138 +vn 0.1185 0.9930 -0.0007 +vn 0.0943 0.9898 0.1071 +vn 0.0960 0.9948 -0.0342 +vn 0.6343 0.1649 0.7553 +vn 0.0450 -0.9963 0.0736 +vn 0.0810 -0.9752 0.2062 +vn 0.0168 -0.9974 0.0699 +vn -0.0302 -0.7172 -0.6962 +vn -0.1436 -0.5570 -0.8180 +vn 0.7691 0.3050 -0.5617 +vn 0.4824 0.6429 -0.5949 +vn -0.5294 0.6916 -0.4913 +vn 0.1651 -0.0003 -0.9863 +vn -0.2686 0.0006 -0.9632 +vn 0.1273 0.0023 -0.9919 +vn -0.7577 -0.0250 0.6522 +vn -0.9227 -0.0096 0.3853 +vn 0.1256 -0.3703 0.9204 +vn 0.0972 -0.3951 0.9135 +vn 0.0790 -0.1950 0.9776 +vn -0.1413 -0.9837 -0.1110 +vn -0.1651 -0.9752 -0.1471 +vn 0.1709 -0.3284 0.9289 +vn 0.1727 -0.5045 0.8459 +vn 0.1311 -0.2243 0.9657 +vn 0.4677 -0.0032 -0.8839 +vn 0.4278 0.0194 -0.9037 +vn 0.4333 -0.0113 -0.9012 +vn -0.0083 0.0671 -0.9977 +vn -0.1934 -0.9265 0.3228 +vn -0.2790 -0.9146 0.2928 +vn -0.7565 0.3476 -0.5539 +vn 0.3953 0.7005 -0.5942 +vn 0.3742 0.7638 -0.5259 +vn -0.0784 0.8372 0.5413 +vn 0.1878 0.8586 0.4769 +vn 0.0823 -0.5147 -0.8534 +vn 0.4266 0.6620 0.6162 +vn 0.7579 0.3538 0.5481 +vn 0.1056 0.4853 -0.8680 +vn 0.0170 -0.4758 -0.8794 +vn -0.8208 -0.0099 0.5711 +vn -0.8231 -0.0001 0.5679 +vn -0.8225 -0.0026 0.5687 +vn -0.3970 -0.4993 -0.7701 +vn -0.0437 -0.3212 -0.9460 +vn 0.0439 -0.9979 -0.0480 +vn 0.0421 -0.9981 -0.0455 +vn 0.0917 0.9566 0.2766 +vn -0.1381 -0.9250 0.3540 +vn -0.2323 -0.0006 -0.9726 +vn -0.5621 -0.0036 -0.8271 +vn -0.9519 0.1670 -0.2569 +vn 0.5420 0.0056 -0.8404 +vn 0.3982 0.0064 -0.9173 +vn -0.5325 0.1705 0.8291 +vn -0.2554 -0.0001 0.9668 +vn 0.5724 -0.7301 -0.3732 +vn 0.6095 -0.6964 -0.3790 +vn 0.0570 -0.9390 -0.3391 +vn 0.6116 -0.0139 -0.7911 +vn 0.6733 -0.0582 -0.7371 +vn -0.1286 -0.2867 -0.9494 +vn -0.2487 -0.0846 -0.9649 +vn -0.0725 -0.0681 -0.9950 +vn 0.9849 -0.0305 0.1703 +vn 0.7828 0.0807 -0.6170 +vn -0.5299 -0.8024 0.2745 +vn -0.5949 -0.7494 0.2907 +vn 0.1134 0.0002 0.9936 +vn 0.2636 0.2445 0.9331 +vn 0.1134 0.0285 0.9931 +vn 0.7104 0.6952 0.1095 +vn 0.7360 -0.6156 -0.2817 +vn 0.4264 0.7240 -0.5422 +vn 0.1746 0.9392 -0.2957 +vn 0.5157 0.8022 -0.3009 +vn -0.9135 -0.3524 -0.2033 +vn -0.9614 0.0566 -0.2693 +vn -0.5086 0.7914 0.3390 +vn -0.6070 0.7689 0.2010 +vn -0.5743 0.7163 0.3965 +vn -0.5979 0.6550 0.4621 +vn -0.6139 0.5514 0.5648 +vn -0.3647 -0.3962 -0.8426 +vn -0.1791 -0.5140 -0.8389 +vn -0.4473 -0.4742 -0.7583 +vn -0.7347 0.1145 -0.6687 +vn -0.0529 -0.7004 0.7118 +vn -0.0454 -0.7235 0.6888 +vn -0.1345 0.9859 -0.0995 +vn -0.0909 0.9945 -0.0524 +vn -0.1132 -0.4331 0.8942 +vn -0.0605 -0.1599 0.9853 +vn -0.2075 -0.3924 0.8961 +vn 0.7163 -0.0113 0.6977 +vn 0.7163 -0.0113 0.6976 +vn 0.7056 -0.4413 -0.5544 +vn 0.7106 -0.4756 -0.5185 +vn 0.7075 -0.3534 -0.6120 +vn -0.9376 -0.3300 -0.1090 +vn -0.9839 -0.1654 -0.0681 +vn 0.2460 0.7378 0.6286 +vn -0.1571 0.8587 0.4878 +vn 0.5468 0.8080 -0.2194 +vn 0.1348 -0.5622 0.8160 +vn 0.1089 -0.6124 0.7830 +vn -0.0158 -0.0261 0.9995 +vn 0.0175 -0.8907 0.4543 +vn 0.0155 -0.9578 0.2869 +vn 0.7936 -0.4591 0.3993 +vn 0.7713 -0.5927 0.2319 +vn -0.6250 0.0107 0.7806 +vn -0.7078 -0.0114 0.7063 +vn 0.7048 -0.3251 0.6306 +vn 0.7200 -0.2370 0.6523 +vn 0.7205 -0.2190 0.6579 +vn 0.1273 -0.0086 -0.9918 +vn 0.1274 -0.0086 -0.9918 +vn 0.9508 -0.0098 -0.3098 +vn 0.0788 0.9850 -0.1535 +vn 0.0437 0.9969 -0.0655 +vn 0.0293 0.9949 -0.0968 +vn -0.1294 0.2861 -0.9494 +vn -0.1526 0.0703 -0.9858 +vn -0.3163 0.0754 -0.9457 +vn -0.3988 -0.6436 -0.6532 +vn 0.2191 -0.9607 0.1706 +vn -0.9462 -0.2925 0.1381 +vn -0.8975 -0.1476 0.4155 +vn 0.3856 -0.0060 0.9226 +vn 0.1933 -0.0029 0.9811 +vn -0.5801 0.8118 0.0666 +vn -0.8773 -0.4544 0.1543 +vn -0.8882 -0.4573 0.0445 +vn -0.4790 -0.8416 -0.2497 +vn -0.6052 -0.7655 -0.2184 +vn -0.0098 1.0000 0.0017 +vn 0.7169 0.0768 -0.6929 +vn 0.7146 -0.0695 -0.6961 +vn 0.7206 -0.0121 -0.6932 +vn 0.1164 -0.9750 0.1895 +vn 0.0929 -0.9950 0.0377 +vn 0.0565 -0.9896 0.1320 +vn 0.1675 -0.9555 0.2426 +vn 0.2646 -0.9640 0.0244 +vn 0.2120 -0.9757 0.0548 +vn 0.3043 -0.9526 0.0030 +vn 0.4018 -0.9107 0.0961 +vn 0.3760 -0.9198 0.1125 +vn 0.4305 -0.9018 0.0392 +vn 0.4842 -0.8739 -0.0429 +vn 0.5717 -0.8167 -0.0785 +vn 0.0159 0.2881 -0.9575 +vn -0.6812 0.0511 0.7303 +vn 0.3333 -0.7572 0.5618 +vn 0.9373 -0.2231 -0.2679 +vn 0.7787 -0.6049 -0.1666 +vn 0.7598 -0.6239 -0.1829 +vn 0.1204 -0.3548 -0.9272 +vn 0.9497 -0.1816 -0.2549 +vn 0.9132 0.2822 -0.2940 +vn 0.9040 0.3144 -0.2896 +vn 0.2255 0.0184 -0.9741 +vn 0.2261 0.0104 -0.9741 +vn 0.2082 0.1698 -0.9632 +vn -0.5151 -0.3023 -0.8021 +vn -0.6545 -0.1044 -0.7488 +vn -0.5274 -0.0778 -0.8461 +vn 0.4711 -0.8552 0.2163 +vn 0.4321 -0.8848 0.1744 +vn 0.4760 -0.8675 -0.1445 +vn 0.5557 0.8206 -0.1334 +vn 0.7064 0.6658 -0.2401 +vn 0.6812 0.6925 -0.2374 +vn 0.3006 0.9243 -0.2354 +vn 0.5244 0.8477 -0.0806 +vn 0.3233 0.9456 -0.0357 +vn 0.5379 0.8340 -0.1233 +vn 0.1086 0.9882 -0.1082 +vn 0.2225 0.9741 -0.0403 +vn 0.1839 0.9593 0.2143 +vn -0.3768 -0.9208 -0.1006 +vn -0.4110 -0.9079 -0.0824 +vn -0.5026 -0.8603 -0.0859 +vn 0.7815 0.2523 0.5706 +vn 0.8031 0.2513 0.5402 +vn 0.3992 0.8851 0.2393 +vn 0.2613 0.5164 -0.8155 +vn -0.0280 0.9974 -0.0669 +vn -0.0526 0.9981 0.0330 +vn -0.0709 0.9963 0.0484 +vn -0.3347 -0.6836 -0.6486 +vn -0.3020 -0.7448 -0.5950 +vn -0.2197 0.9650 -0.1429 +vn -0.1838 0.9772 -0.1060 +vn -0.1582 0.7765 0.6100 +vn -0.3301 0.9434 -0.0312 +vn -0.3804 0.9247 -0.0181 +vn -0.9315 0.3436 0.1191 +vn -0.7592 0.6486 0.0546 +vn -0.8436 0.5316 0.0753 +vn 0.4559 0.7128 0.5329 +vn 0.3440 0.5747 0.7425 +vn 0.4483 0.6210 0.6430 +vn 0.2696 0.9597 -0.0790 +vn -0.9115 -0.3294 0.2461 +vn -0.7027 -0.6541 0.2800 +vn -0.9168 -0.3112 0.2503 +vn -0.9787 0.1140 0.1707 +vn -0.9765 0.1243 0.1759 +vn -0.9606 0.1866 0.2062 +vn -0.8585 0.3774 0.3472 +vn -0.2971 0.6539 -0.6958 +vn -0.1568 0.2711 -0.9497 +vn -0.8671 0.4908 0.0850 +vn -0.1497 -0.9083 0.3905 +vn -0.1719 -0.9704 0.1697 +vn -0.2071 -0.9468 0.2465 +vn 0.5139 0.7728 0.3725 +vn -0.6405 0.1347 0.7560 +vn -0.3442 0.1979 0.9178 +vn -0.3759 0.2064 0.9034 +vn 0.2032 0.9568 0.2080 +vn 0.4953 0.7745 0.3934 +vn 0.0421 0.2453 0.9685 +vn 0.0908 0.1562 0.9835 +vn 0.0482 0.0967 0.9941 +vn 0.4820 -0.5858 -0.6515 +vn 0.4150 -0.5728 -0.7069 +vn -0.8751 0.0365 0.4827 +vn -0.8821 0.0895 0.4625 +vn 0.0776 -0.0055 0.9970 +vn 0.0075 0.9991 -0.0416 +vn 0.0281 0.9962 -0.0830 +vn 0.3692 -0.9294 -0.0032 +vn 0.1134 -0.9228 -0.3683 +vn -0.9506 -0.0153 0.3102 +vn 0.7041 0.3939 0.5908 +vn 0.0073 -0.0762 -0.9971 +vn 0.4894 0.1073 -0.8655 +vn -0.1858 0.0001 0.9826 +vn -0.1857 0.0010 0.9826 +vn 0.1278 0.3473 0.9290 +vn 0.0762 0.3401 0.9373 +vn 0.3579 0.1041 0.9279 +vn -0.3204 -0.9473 0.0006 +vn -0.1988 -0.9727 -0.1194 +vn 0.7062 -0.6919 0.1504 +vn 0.7055 -0.7043 0.0781 +vn 0.7078 -0.6899 0.1519 +vn 0.1187 0.9447 -0.3057 +vn 0.7057 -0.1818 0.6848 +vn 0.7655 -0.0952 0.6364 +vn 0.6965 -0.1661 0.6980 +vn 0.0754 0.8676 -0.4916 +vn 0.0796 0.8732 -0.4807 +vn 0.7600 -0.3613 -0.5402 +vn 0.6865 -0.4621 -0.5614 +vn 0.6120 -0.2890 -0.7361 +vn 0.3640 0.6091 -0.7046 +vn 0.6296 0.4586 -0.6272 +vn 0.6560 0.3490 -0.6692 +vn 0.0160 -0.9999 -0.0002 +vn -0.9853 -0.1519 0.0783 +vn -0.9513 -0.2984 0.0772 +vn -0.7269 -0.0940 -0.6802 +vn 0.2887 -0.5910 -0.7533 +vn 0.2787 -0.7518 -0.5975 +vn 0.1253 -0.6649 -0.7364 +vn 0.0176 -0.9674 -0.2527 +vn -0.4720 0.5367 0.6994 +vn -0.0620 0.2799 -0.9580 +vn 0.0057 0.3894 -0.9211 +vn -0.7507 0.5316 -0.3922 +vn -0.4737 0.8583 0.1972 +vn -0.3252 -0.0022 0.9457 +vn -0.3609 -0.0060 0.9326 +vn -0.0873 -0.0014 0.9962 +vn -0.4858 0.4328 -0.7594 +vn -0.4637 0.5235 -0.7148 +vn 0.6207 0.7071 0.3388 +vn 0.5430 0.7736 0.3268 +vn -0.0476 0.4544 0.8895 +vn -0.5801 0.5805 0.5713 +vn 0.4878 0.1549 -0.8591 +vn 0.7546 0.0544 0.6539 +vn 0.9226 0.0033 -0.3857 +vn 0.0704 -0.9227 -0.3792 +vn -0.9432 0.1235 0.3083 +vn -0.9402 0.1223 0.3180 +vn 0.7213 0.6264 -0.2955 +vn 0.4140 0.8442 0.3403 +vn 0.7100 -0.6690 -0.2197 +vn 0.7044 -0.6392 -0.3086 +vn 0.7070 -0.6877 -0.1648 +vn 0.1730 -0.6084 0.7745 +vn 0.2549 -0.6113 0.7492 +vn 0.4931 -0.2613 0.8298 +vn -0.6755 -0.7351 0.0579 +vn 0.6623 0.3363 -0.6695 +vn 0.8297 0.1708 -0.5314 +vn 0.7253 0.0250 -0.6879 +vn 0.3853 -0.0022 0.9228 +vn 0.7161 -0.0058 0.6979 +vn 0.0080 0.3374 -0.9413 +vn 0.0616 0.4643 -0.8835 +vn 0.6643 -0.6712 -0.3288 +vn -0.4534 -0.8911 0.0190 +vn 0.8143 0.4409 -0.3776 +vn -0.4851 -0.7592 0.4339 +vn 0.6850 -0.3053 -0.6615 +vn 0.5504 -0.3397 -0.7627 +vn -0.6797 0.0164 0.7333 +vn 0.3877 -0.8757 -0.2879 +vn 0.6316 -0.2195 0.7436 +vn 0.7482 -0.1679 0.6419 +vn 0.7968 -0.1370 0.5885 +vn -0.9246 -0.1903 -0.3301 +vn -0.4501 -0.7885 -0.4192 +vn 0.0556 -0.8972 0.4381 +vn -0.0305 -0.9720 0.2331 +vn 0.1878 -0.9700 0.1541 +vn 0.1277 -0.0029 -0.9918 +vn 0.1560 -0.7800 0.6061 +vn 0.4286 -0.6617 0.6152 +vn -0.1398 0.6467 0.7498 +vn -0.2837 0.7664 0.5763 +vn -0.4070 0.6105 0.6795 +vn -0.9313 -0.0009 -0.3643 +vn -0.9313 -0.0008 -0.3643 +vn -0.9508 0.0098 0.3098 +vn -0.9063 0.0034 0.4225 +vn -0.0708 -0.9567 0.2823 +vn -0.6456 0.6099 0.4595 +vn -0.7345 0.6319 0.2473 +vn -0.7852 0.5777 0.2230 +vn -0.9616 -0.0631 -0.2673 +vn -0.9128 -0.0455 -0.4059 +vn -0.7195 0.0001 0.6945 +vn -0.7195 0.0001 0.6944 +vn -0.6657 0.0000 0.7462 +vn 0.7093 0.2954 0.6401 +vn 0.7947 0.4565 0.4001 +vn -0.2802 0.5058 0.8158 +vn -0.9059 0.3166 0.2813 +vn 0.3947 0.5788 -0.7136 +vn 0.4071 0.5181 -0.7522 +vn 0.2472 0.5756 -0.7794 +vn 0.1933 0.0111 0.9811 +vn -0.3033 -0.1177 0.9456 +vn -0.8412 0.4685 -0.2699 +vn -0.2414 -0.0002 0.9704 +vn -0.2459 -0.0018 0.9693 +vn -0.2501 0.0004 0.9682 +vn 0.2811 0.1176 0.9524 +vn -0.4757 0.8463 0.2395 +vn -0.2248 0.9591 0.1722 +vn -0.6878 -0.1223 0.7155 +vn -0.6819 -0.3014 0.6665 +vn -0.9267 0.0124 0.3756 +vn 0.2326 0.0035 0.9726 +vn 0.1557 0.0056 0.9878 +vn 0.0346 -0.9982 -0.0488 +vn -0.9914 0.1288 -0.0244 +vn -0.2283 -0.9258 0.3014 +vn 0.9434 -0.0197 0.3310 +vn 0.2071 -0.0037 -0.9783 +vn 0.4042 0.8308 0.3827 +vn 0.6165 -0.4869 -0.6188 +vn -0.2373 0.0024 0.9714 +vn -0.2611 0.0028 0.9653 +vn -0.2379 0.0035 0.9713 +vn -0.1643 -0.9016 -0.4002 +vn -0.0934 -0.8748 -0.4753 +vn -0.6821 -0.0115 0.7312 +vn -0.7303 0.0064 0.6831 +vn -0.6574 -0.0405 0.7524 +vn -0.9959 0.0822 0.0379 +vn -0.1135 -0.9227 0.3684 +vn -0.1670 -0.2721 -0.9477 +vn 0.0479 0.5938 0.8032 +vn 0.2762 0.5773 0.7684 +vn 0.4315 -0.2314 0.8719 +vn 0.6343 -0.1649 0.7553 +vn 0.3967 -0.2371 0.8868 +vn 0.1935 0.3461 0.9180 +vn 0.2231 0.6101 0.7603 +vn 0.5851 -0.1103 0.8034 +vn 0.0537 -0.2603 0.9640 +vn 0.3061 0.0148 0.9519 +vn 0.0017 0.0064 1.0000 +vn 0.0136 -0.1509 0.9885 +vn -0.0028 -0.0049 1.0000 +vn 0.1543 -0.0873 0.9842 +vn 0.0117 -0.0221 0.9997 +vn 0.0378 0.0570 0.9977 +vn 0.1556 0.0429 0.9869 +vn -0.4987 -0.8401 -0.2132 +vn -0.5107 -0.7633 -0.3955 +vn 0.1179 -0.0969 0.9883 +vn -0.3610 0.0061 0.9325 +vn 0.1702 -0.0224 0.9851 +vn 0.1443 0.0354 0.9889 +vn 0.1669 -0.0704 0.9835 +vn 0.0976 0.0466 0.9941 +vn 0.1017 -0.1292 0.9864 +vn 0.0688 -0.0663 0.9954 +vn 0.5402 0.0037 -0.8415 +vn -0.0262 0.1649 0.9860 +vn -0.1156 0.0097 -0.9933 +vn 0.4215 -0.0109 0.9068 +vn 0.1613 -0.6272 0.7620 +vn 0.1960 -0.0495 -0.9793 +vn 0.0543 0.0051 -0.9985 +vn 0.2385 -0.0221 -0.9709 +vn 0.9849 0.0305 0.1703 +vn 0.9165 0.0725 0.3934 +vn 0.5184 -0.2313 -0.8233 +vn -0.2860 0.1607 0.9447 +vn -0.4007 -0.0133 0.9161 +vn -0.3568 0.0077 0.9341 +vn -0.3983 -0.0943 -0.9124 +vn -0.3039 -0.0840 -0.9490 +vn 0.0903 0.7568 -0.6474 +vn 0.3297 0.7957 -0.5082 +vn 0.0959 0.7131 -0.6944 +vn -0.0213 0.8409 -0.5408 +vn -0.6745 0.0382 0.7372 +vn -0.7773 -0.0116 0.6290 +vn -0.6070 0.0011 0.7947 +vn -0.6650 0.0003 0.7469 +vn -0.6732 -0.1366 0.7267 +vn -0.7638 -0.1479 0.6283 +vn -0.5076 0.0049 0.8616 +vn -0.5191 0.0068 0.8547 +vn -0.4183 -0.0005 0.9083 +vn -0.0410 0.7274 -0.6850 +vn 0.0285 -0.0300 0.9991 +vn 0.4322 0.8884 0.1549 +vn 0.1957 0.9352 0.2952 +vn 0.4875 0.8508 0.1963 +vn 0.3979 -0.7757 -0.4899 +vn -0.0387 0.5718 -0.8195 +vn 0.1124 0.0019 -0.9937 +vn 0.8466 0.0072 -0.5323 +vn 0.0480 0.2874 -0.9566 +vn 0.1106 0.1758 -0.9782 +vn -0.4253 0.9036 -0.0509 +vn -0.2747 0.9561 -0.1023 +vn -0.6082 0.7916 0.0590 +vn -0.5650 0.8234 -0.0531 +vn 0.0946 -0.9794 0.1782 +vn -0.7073 0.2687 0.6539 +vn -0.9345 -0.0181 0.3555 +vn -0.9791 0.1689 -0.1133 +vn -0.9857 0.1619 -0.0468 +vn -0.9418 0.3201 -0.1027 +vn 0.0885 -0.0746 -0.9933 +vn 0.0043 -0.2893 -0.9572 +vn -0.0121 0.0830 -0.9965 +vn -0.0184 0.0665 -0.9976 +vn -0.0152 0.1358 -0.9906 +vn -0.0014 0.1106 -0.9939 +vn -0.5544 -0.8082 0.1987 +vn -0.7978 0.1396 0.5865 +vn 0.8014 -0.5855 0.1222 +vn 0.6061 0.0099 -0.7953 +vn -0.9827 -0.1844 -0.0170 +vn -0.8916 -0.2166 0.3976 +vn 0.6733 0.0582 -0.7371 +vn 0.7994 0.5217 -0.2979 +vn 0.1006 0.0638 0.9929 +vn 0.1298 0.2335 0.9636 +vn 0.6003 -0.2103 -0.7716 +vn 0.5071 -0.0720 -0.8589 +vn 0.2523 0.2914 -0.9227 +vn -0.6876 -0.6731 0.2724 +vn 0.4847 0.4373 -0.7575 +vn 0.2414 0.4261 0.8719 +vn 0.2367 0.3778 0.8951 +vn -0.7978 -0.2162 0.5628 +vn 0.1062 -0.9492 -0.2963 +vn 0.1938 -0.8952 -0.4012 +vn 0.3269 0.3643 -0.8720 +vn 0.3238 0.3312 -0.8863 +vn -0.7138 -0.1086 -0.6919 +vn -0.6428 -0.3261 -0.6931 +vn 0.0617 -0.7853 -0.6160 +vn 0.2071 0.0037 -0.9783 +vn -0.0082 0.9999 -0.0098 +vn 0.7128 0.7011 -0.0212 +vn -0.7308 -0.5317 -0.4281 +vn 0.4009 -0.0283 -0.9157 +vn 0.3767 -0.0304 -0.9258 +vn 0.9846 0.0370 0.1706 +vn 0.9159 0.0789 0.3936 +vn 0.7332 0.6791 0.0364 +vn 0.7428 0.6544 -0.1411 +vn 0.6082 0.7899 0.0781 +vn 0.0836 0.9791 -0.1856 +vn 0.4282 0.2922 0.8551 +vn 0.0042 0.3703 0.9289 +vn 0.3933 0.2988 0.8695 +vn -0.9373 0.0151 0.3482 +vn -0.5899 -0.7330 0.3388 +vn 0.0531 0.7825 -0.6204 +vn -0.5233 -0.7146 0.4642 +vn 0.7816 0.0251 0.6233 +vn 0.7567 -0.3659 0.5418 +vn -0.6467 0.5468 -0.5317 +vn 0.4743 -0.7032 0.5296 +vn 0.1710 -0.7598 0.6272 +vn 0.0025 0.2877 -0.9577 +vn 0.4760 0.8675 -0.1445 +vn -0.3562 -0.3081 -0.8821 +vn -0.6002 -0.2318 -0.7655 +vn -0.6288 -0.2108 -0.7484 +vn -0.0641 0.9421 -0.3292 +vn 0.1609 0.9640 -0.2116 +vn -0.1838 0.5481 0.8160 +vn 0.2518 0.6867 0.6820 +vn 0.0270 -0.8404 0.5413 +vn 0.2377 -0.0020 -0.9713 +vn 0.1959 0.7076 0.6789 +vn -0.5560 -0.7491 -0.3601 +vn -0.2131 0.0149 0.9769 +vn -0.7221 -0.2919 0.6272 +vn 0.1985 0.2394 0.9504 +vn 0.1837 0.1865 0.9651 +vn -0.6156 -0.7864 0.0514 +vn 0.0641 0.7436 -0.6655 +vn -0.3255 -0.0016 0.9455 +vn -0.3613 -0.0051 0.9324 +vn 0.9162 -0.3017 0.2636 +vn 0.1380 -0.9275 0.3474 +vn -0.9382 0.0267 0.3451 +vn -0.8194 0.1498 0.5533 +vn -0.6694 0.1587 0.7257 +vn -0.7006 -0.6663 -0.2554 +vn 0.5368 0.0664 0.8411 +vn 0.5515 -0.3271 0.7674 +vn 0.7260 -0.5077 0.4638 +vn -0.9370 0.2141 0.2759 +vn -0.9917 0.1285 0.0094 +vn 0.9973 -0.0098 -0.0732 +vn -0.7844 -0.4977 -0.3701 +vn 0.7154 -0.0190 -0.6985 +vn 0.6868 0.0226 -0.7265 +vn 0.6908 -0.0128 -0.7230 +vn 0.0482 0.3393 0.9394 +vn 0.2813 0.5373 0.7951 +vn 0.9325 0.0149 0.3610 +vn 0.9508 0.0098 -0.3098 +vn 0.7968 0.1370 0.5885 +vn 0.9434 0.0197 0.3310 +vn 0.7482 0.1679 0.6419 +vn -0.3462 -0.0087 -0.9381 +vn -0.3101 -0.0118 -0.9506 +vn -0.5952 -0.0125 -0.8035 +vn -0.0096 0.9999 -0.0062 +vn 0.6134 -0.7897 -0.0079 +vn 0.4931 -0.3742 -0.7854 +vn -0.9045 -0.1333 0.4052 +vn -0.8976 -0.1271 0.4222 +vn 0.5916 0.3093 -0.7445 +vn -0.4540 0.5471 0.7033 +vn -0.2878 0.2747 -0.9174 +vn -0.3759 0.3172 -0.8707 +vn -0.6219 0.7827 0.0258 +vn 0.2340 -0.0788 0.9690 +vn 0.2407 -0.0213 0.9704 +vn -0.9857 0.0715 -0.1528 +vn 0.7243 0.0249 0.6890 +vn 0.6933 -0.1939 -0.6940 +vn 0.7053 -0.0839 -0.7039 +vn 0.2068 -0.0078 -0.9784 +vn 0.2067 -0.0078 -0.9784 +vn -0.4438 -0.0071 -0.8961 +vn -0.4952 0.2312 -0.8375 +vn -0.8429 0.1743 -0.5090 +vn -0.6535 0.0885 -0.7518 +vn -0.6399 -0.7008 -0.3151 +vn -0.7639 0.2836 0.5796 +vn 0.7101 -0.6930 -0.1247 +vn 0.1423 -0.0077 -0.9898 +vn 0.2531 0.0880 -0.9634 +vn 0.2254 0.0127 -0.9742 +vn 0.3879 0.0214 -0.9214 +vn -0.3268 -0.0010 0.9451 +vn -0.3629 0.0002 0.9318 +vn 0.5328 0.0384 -0.8454 +vn -0.1435 -0.3385 -0.9300 +vn 0.6597 0.1086 -0.7436 +vn 0.5849 0.1049 -0.8043 +vn -0.5940 -0.2396 -0.7680 +vn 0.4852 -0.0859 -0.8702 +vn -0.4150 -0.7280 0.5457 +vn -0.4254 -0.7049 0.5676 +vn 0.9754 0.1128 0.1895 +vn -0.1798 0.5079 -0.8424 +vn -0.4433 0.5147 -0.7339 +vn 0.3963 -0.0887 -0.9138 +vn 0.4442 -0.1303 -0.8864 +vn 0.4840 0.3694 -0.7933 +vn 0.4824 0.3910 -0.7839 +vn 0.4689 -0.2826 -0.8368 +vn 0.5817 -0.1034 -0.8068 +vn 0.5621 0.4101 -0.7182 +vn 0.5593 0.4268 -0.7107 +vn -0.0763 -0.6334 -0.7701 +vn 0.2494 -0.5522 -0.7955 +vn 0.4722 -0.0314 -0.8809 +vn 0.4885 -0.0906 -0.8679 +vn -0.9861 -0.1655 -0.0130 +vn -0.9928 -0.0804 -0.0889 +vn 0.5680 -0.7331 -0.3741 +vn 0.6052 -0.6997 -0.3798 +vn 0.7134 -0.6991 -0.0478 +vn -0.6502 0.7322 -0.2028 +vn -0.7052 0.7074 0.0464 +vn -0.4427 0.8963 0.0251 +vn 0.7084 0.2370 0.6648 +vn -0.1016 0.0000 -0.9948 +vn -0.0930 -0.0002 -0.9957 +vn -0.2260 0.0002 -0.9741 +vn -0.2016 0.0102 -0.9794 +vn -0.2761 0.0062 -0.9611 +vn 0.0516 -0.3786 -0.9241 +vn 0.0171 -0.3994 -0.9166 +vn -0.4499 0.0048 -0.8931 +vn -0.4609 -0.0789 -0.8840 +vn 0.7127 0.5555 -0.4284 +vn 0.7053 0.4977 -0.5048 +vn 0.7115 0.4525 -0.5376 +vn -0.5884 -0.0029 -0.8085 +vn -0.7230 -0.0131 -0.6907 +vn -0.7768 -0.0149 -0.6296 +vn -0.0052 1.0000 0.0031 +vn -0.0076 1.0000 -0.0014 +vn -0.8303 -0.0282 -0.5566 +vn 0.3220 0.0178 -0.9466 +vn -0.1265 0.3496 -0.9283 +vn 0.0758 0.3773 -0.9230 +vn 0.3890 0.3781 -0.8401 +vn -0.9748 -0.0729 -0.2108 +vn -0.9790 -0.1704 -0.1121 +vn -0.9854 -0.0792 -0.1506 +vn 0.3375 0.3906 -0.8565 +vn 0.1028 0.9529 -0.2855 +vn 0.5472 -0.1115 0.8296 +vn -0.7504 -0.5490 0.3681 +vn 0.9313 0.0009 0.3643 +vn 0.3367 -0.1742 -0.9254 +vn 0.9800 -0.1626 -0.1146 +vn 0.9907 -0.0765 0.1127 +vn -0.9927 -0.0865 0.0839 +vn -0.9959 -0.0822 0.0379 +vn -0.0342 -0.3462 -0.9375 +vn -0.6612 -0.2892 0.6923 +vn -0.4375 -0.3686 0.8202 +vn -0.5923 -0.3179 0.7404 +vn -0.7325 -0.5824 0.3525 +vn -0.6794 -0.7202 0.1404 +vn 0.7130 -0.4031 0.5737 +vn 0.7089 -0.4501 0.5430 +vn 0.2863 0.8187 0.4978 +vn 0.0874 0.9430 0.3212 +vn -0.0877 -0.0023 0.9961 +vn 0.2323 0.0006 0.9726 +vn 0.1553 0.0032 0.9879 +vn -0.0719 -0.3900 0.9180 +vn 0.7984 0.3425 -0.4953 +vn -0.0345 -0.2641 -0.9639 +vn -0.1628 -0.2406 -0.9569 +vn 0.0237 -0.2078 -0.9779 +vn 0.1408 -0.8469 0.5127 +vn -0.8021 0.5934 -0.0671 +vn -0.7206 0.6833 -0.1176 +vn 0.3501 -0.6266 0.6963 +vn 0.3658 -0.5517 0.7496 +vn 0.4099 0.1726 -0.8957 +vn 0.0296 0.6371 0.7702 +vn -0.0417 0.0636 0.9971 +vn -0.0367 0.0528 0.9979 +vn -0.0026 -0.0203 0.9998 +vn 0.5596 -0.4230 -0.7127 +vn 0.5592 -0.4272 -0.7105 +vn -0.2635 0.0001 0.9646 +vn 0.4513 0.7000 0.5534 +vn 0.5720 0.6332 0.5214 +vn -0.2802 0.8290 0.4840 +vn 0.2007 -0.3937 0.8971 +vn 0.5680 0.7331 -0.3741 +vn 0.6052 0.6997 -0.3798 +vn 0.8494 0.0539 -0.5250 +vn 0.8068 0.0693 -0.5867 +vn 0.1130 0.9566 0.2684 +vn 0.1130 0.9567 0.2684 +vn 0.2698 -0.0475 0.9618 +vn -0.2376 -0.0003 0.9714 +vn -0.2497 -0.0009 0.9683 +vn -0.2780 -0.0021 0.9606 +vn -0.6161 0.7049 0.3514 +vn -0.5826 0.6727 0.4561 +vn 0.1880 0.7448 -0.6403 +vn 0.7149 0.1955 -0.6714 +vn 0.7085 0.0870 -0.7003 +vn 0.7070 -0.3147 -0.6333 +vn 0.7137 -0.2130 -0.6673 +vn 0.7095 -0.2361 -0.6640 +vn 0.9304 0.0313 0.3651 +vn 0.9305 0.0314 0.3651 +vn -0.9915 0.1277 -0.0259 +vn -0.9775 0.0625 0.2014 +vn 0.2274 -0.0619 -0.9718 +vn -0.2456 -0.9321 -0.2661 +vn -0.5876 0.6104 -0.5311 +vn -0.7446 0.6606 -0.0960 +vn -0.3635 0.9073 -0.2115 +vn -0.2508 0.8929 -0.3739 +vn -0.6871 0.6461 0.3324 +vn -0.3631 -0.8555 0.3691 +vn -0.3479 0.0049 0.9375 +vn -0.5315 -0.7847 -0.3190 +vn 0.1345 0.9758 0.1726 +vn 0.7630 0.6052 0.2273 +vn 0.4526 -0.7805 -0.4312 +vn 0.3115 0.8821 -0.3533 +vn 0.7121 -0.5709 -0.4086 +vn 0.7182 -0.6469 -0.2564 +vn -0.6855 -0.4255 0.5907 +vn 0.0787 -0.5139 -0.8542 +vn -0.4075 -0.4992 -0.7647 +vn -0.2800 -0.0128 -0.9599 +vn 0.0155 -0.8514 0.5243 +vn -0.2071 0.0037 0.9783 +vn -0.2287 0.9543 -0.1926 +vn 0.2545 -0.9319 0.2586 +vn -0.5280 -0.8486 -0.0320 +vn -0.6501 -0.7583 -0.0488 +vn -0.6852 0.3414 0.6434 +vn -0.4222 0.3804 0.8229 +vn -0.4909 0.3775 0.7852 +vn 0.1187 0.9447 -0.3058 +vn 0.7093 -0.2954 0.6401 +vn 0.6737 0.0456 -0.7376 +vn 0.9343 -0.0080 -0.3564 +vn -0.9942 0.0712 -0.0810 +vn 0.0949 -0.0259 0.9952 +vn -0.5192 0.8161 -0.2537 +vn -0.2536 0.9103 -0.3271 +vn -0.5246 0.8083 -0.2673 +vn -0.1132 -0.0017 0.9936 +vn -0.1132 -0.0019 0.9936 +vn 0.1910 0.1696 0.9668 +vn 0.6116 0.0139 -0.7911 +vn -0.5949 0.7494 0.2907 +vn -0.3631 0.8555 0.3691 +vn -0.5299 0.8024 0.2745 +vn 0.7111 -0.6998 -0.0682 +vn -0.9747 0.0522 -0.2172 +vn 0.0886 0.4462 0.8906 +vn 0.2331 -0.1824 0.9552 +vn 0.0264 -0.7525 -0.6581 +vn 0.2714 0.4803 0.8341 +vn 0.0340 0.0758 0.9965 +vn 0.0098 -1.0000 -0.0017 +vn 0.9836 0.1766 0.0361 +vn -0.6954 -0.7181 0.0258 +vn 0.6924 -0.5396 -0.4790 +vn 0.6983 -0.5666 -0.4373 +vn 0.7111 -0.5912 -0.3806 +vn 0.6902 -0.1476 -0.7084 +vn -0.9292 0.0516 0.3661 +vn -0.0120 0.4925 -0.8702 +vn -0.2202 -0.0865 0.9716 +vn 0.0242 0.9476 -0.3185 +vn 0.0115 0.9049 -0.4254 +vn 0.0372 0.9189 -0.3928 +vn -0.0157 -0.1355 -0.9907 +vn -0.0019 -0.1124 -0.9937 +vn 0.0391 -0.1975 -0.9795 +vn 0.1009 0.8905 0.4436 +vn 0.1454 0.8439 0.5165 +vn -0.2731 0.3974 0.8760 +vn 0.0082 0.3786 -0.9255 +vn 0.0134 0.2985 -0.9543 +vn 0.3161 0.7227 -0.6147 +vn 0.2687 -0.9306 -0.2484 +vn 0.0180 0.8630 -0.5049 +vn 0.1643 0.9571 0.2389 +vn 0.1134 0.9227 -0.3683 +vn -0.4213 0.6638 -0.6180 +vn -0.9313 0.0009 -0.3643 +vn -0.9313 0.0008 -0.3643 +vn 0.4080 0.6112 0.6782 +vn 0.0513 0.9355 -0.3495 +vn 0.6971 0.7135 -0.0702 +vn 0.6744 0.7282 -0.1221 +vn 0.7118 0.1587 -0.6842 +vn 0.6946 0.2700 -0.6668 +vn -0.2608 0.9510 0.1661 +vn -0.0098 -1.0000 0.0017 +vn 0.8077 -0.0657 -0.5860 +vn 0.6928 0.6912 -0.2057 +vn 0.7427 0.5943 -0.3087 +vn -0.1738 -0.5999 -0.7810 +vn -0.0397 -0.5757 -0.8167 +vn 0.0890 -0.9243 -0.3711 +vn 0.0190 -0.1967 -0.9803 +vn -0.0187 -0.0669 -0.9976 +vn -0.7247 0.0323 0.6883 +vn -0.7711 0.0053 0.6367 +vn -0.4028 0.7002 0.5894 +vn -0.1337 0.9272 0.3499 +vn 0.7133 0.6990 0.0510 +vn -0.4330 -0.2278 -0.8721 +vn -0.5013 -0.2055 -0.8405 +vn -0.9305 0.0313 -0.3651 +vn -0.6065 -0.0073 0.7951 +vn -0.7670 -0.3170 0.5579 +vn 0.6252 -0.1061 0.7732 +vn 0.8032 -0.0055 0.5957 +vn -0.9936 -0.1067 -0.0381 +vn -0.9800 -0.1626 0.1145 +vn -0.1673 0.2845 -0.9440 +vn -0.1674 0.2845 -0.9440 +vn 0.6116 0.0012 -0.7912 +vn 0.3724 0.0182 -0.9279 +vn 0.4643 -0.6795 0.5681 +vn 0.9165 -0.0725 0.3934 +vn 0.3677 0.4975 0.7856 +vn 0.8557 0.2713 -0.4407 +vn 0.0282 0.0092 -0.9996 +vn 0.0401 0.0025 -0.9992 +vn 0.0432 0.0835 -0.9956 +vn 0.5700 0.8216 -0.0074 +vn 0.3735 0.9142 -0.1572 +vn -0.3444 -0.3280 0.8796 +vn -0.6819 -0.3014 0.6664 +vn 0.1981 0.1079 0.9742 +vn 0.1999 0.1085 0.9738 +vn 0.1135 0.9227 -0.3684 +vn -0.0250 -0.3953 0.9182 +vn 0.1148 -0.3835 -0.9164 +vn 0.1279 -0.2523 -0.9592 +vn 0.7083 -0.0391 -0.7048 +vn 0.4221 0.0026 0.9065 +vn 0.2836 -0.0014 0.9589 +vn 0.2834 0.0115 0.9589 +vn 0.5338 0.4237 -0.7318 +vn -0.6781 0.7228 0.1330 +vn -0.0489 -0.7079 0.7046 +vn 0.7178 0.6947 -0.0470 +vn -0.3613 0.6942 0.6225 +vn 0.9507 -0.0048 -0.3102 +vn -0.7213 0.6888 -0.0723 +vn -0.7711 0.6350 -0.0465 +vn -0.5243 0.4016 0.7509 +vn 0.1187 -0.9447 -0.3058 +vn -0.1402 0.7937 -0.5919 +vn -0.1019 -0.7671 -0.6333 +vn -0.7052 0.6705 0.2302 +vn -0.6526 0.7490 0.1147 +vn -0.2848 0.7463 -0.6016 +vn -0.1184 0.6279 -0.7693 +vn -0.7577 0.0250 0.6522 +vn 0.0959 -0.7131 -0.6944 +vn 0.0513 0.6464 -0.7613 +vn -0.9729 -0.0565 -0.2244 +vn 0.7071 -0.6492 0.2802 +vn -0.1781 -0.2852 -0.9418 +vn -0.9065 -0.0114 0.4220 +vn -0.6541 0.6912 0.3072 +vn 0.7081 0.6407 -0.2967 +vn -0.1398 0.9854 0.0970 +vn 0.6073 -0.1754 0.7749 +vn -0.5126 -0.2498 0.8215 +vn -0.0971 0.8711 -0.4814 +vn 0.8181 -0.2855 -0.4992 +vn 0.9050 0.0594 0.4212 +vn -0.0160 0.9999 0.0002 +vn -0.6504 -0.7304 -0.2086 +vn 0.0470 -0.3288 -0.9432 +vn 0.1854 0.0202 -0.9825 +vn 0.0268 0.0025 -0.9996 +vn 0.0082 0.9999 0.0098 +vn -0.0789 0.6660 -0.7418 +vn -0.2152 -0.2722 0.9379 +vn -0.1321 -0.2920 0.9473 +vn -0.0368 0.0010 0.9993 +vn -0.4553 0.7925 0.4058 +vn -0.0048 -0.3018 -0.9534 +vn 0.6285 -0.7451 -0.2234 +vn -0.0270 -0.0026 0.9996 +vn -0.1574 0.5085 -0.8466 +vn -0.0675 0.8917 0.4475 +vn 0.0463 0.9976 -0.0523 +vn -0.6119 -0.2800 -0.7397 +vn -0.8302 0.0316 -0.5565 +vn -0.7232 0.0143 -0.6905 +vn 0.7292 -0.3699 0.5757 +vn 0.7536 0.0054 0.6573 +vn -0.1129 -0.8183 -0.5635 +vn -0.2548 0.0004 0.9670 +vn 0.8435 -0.0664 0.5329 +vn 0.9313 -0.0009 0.3644 +vn 0.9313 -0.0008 0.3644 +vn 0.7109 -0.5620 0.4228 +vn 0.7109 -0.4832 0.5110 +vn 0.7107 -0.5767 0.4029 +vn 0.3311 0.7893 -0.5171 +vn 0.1047 0.7581 -0.6436 +vn 1.0000 0.0003 0.0000 +vn -0.9305 0.0314 -0.3651 +vn -0.5544 0.8082 0.1987 +vn -0.8432 -0.0800 -0.5317 +vn -0.7060 -0.3895 -0.5916 +vn -0.8772 -0.1408 -0.4591 +vn 0.2374 0.0994 0.9663 +vn -0.2209 0.5395 0.8125 +vn 0.6167 -0.7327 0.2877 +vn 0.2531 -0.0005 -0.9674 +vn 0.1231 0.7045 -0.6989 +vn 0.0684 -0.9975 0.0158 +vn 0.0522 -0.9960 -0.0728 +vn 0.4966 -0.0467 -0.8667 +vn -0.1507 -0.9880 0.0340 +vn -0.0171 -0.9998 0.0047 +vn -0.0104 -0.9999 0.0019 +vn -0.0113 -0.6879 0.7257 +vn -0.9102 0.2266 0.3466 +vn -0.0078 -0.9824 0.1866 +vn 0.0363 -0.9713 0.2350 +vn -0.9637 -0.1925 0.1852 +vn 0.0222 -0.8017 -0.5973 +vn -0.4336 0.7491 0.5008 +vn -0.4652 0.7055 0.5346 +vn 0.7083 0.0390 -0.7048 +vn 0.7083 0.0391 -0.7048 +vn -0.4781 -0.8299 0.2875 +vn 0.1199 -0.1294 -0.9843 +vn 0.3026 -0.0019 -0.9531 +vn 0.3521 -0.0489 -0.9347 +vn 0.5119 0.8068 -0.2952 +vn -0.6681 -0.0109 0.7440 +vn 0.4224 0.0066 0.9064 +vn 0.7480 -0.5116 -0.4228 +vn -0.2734 -0.9475 -0.1661 +vn 0.9005 0.0117 0.4348 +vn -0.1921 0.6895 0.6983 +vn -0.0961 0.5533 0.8274 +vn -0.0461 0.6365 -0.7699 +vn -0.4346 -0.2116 0.8754 +vn -0.2280 0.5390 -0.8109 +vn -0.4079 0.2894 -0.8659 +vn -0.2946 0.2901 -0.9105 +vn -0.2067 0.0078 0.9784 +vn -0.5090 -0.8511 0.1285 +vn 0.4830 0.5685 -0.6659 +vn 0.5088 0.4350 -0.7429 +vn -0.1835 -0.9469 -0.2640 +vn 0.7741 0.5476 -0.3178 +vn 0.1749 0.7798 0.6012 +vn 0.0190 0.0313 0.9993 +vn -0.6819 0.3014 0.6664 +vn -0.4272 0.0065 -0.9041 +vn -0.1000 0.0018 -0.9950 +vn -0.2513 -0.0003 0.9679 +vn -0.2449 0.0000 0.9696 +vn 0.1929 -0.0002 0.9812 +vn 0.9846 -0.1653 -0.0575 +vn -0.3148 -0.8721 0.3747 +vn -0.7700 0.0064 -0.6380 +vn -0.3899 0.7123 -0.5836 +vn -0.5061 0.7671 -0.3942 +vn 0.0398 0.9948 0.0936 +vn 0.0670 0.9976 0.0165 +vn -0.9689 0.1385 0.2049 +vn -0.1886 -0.8079 0.5583 +vn 0.6685 0.0457 -0.7423 +vn -0.2352 0.0024 0.9719 +vn -0.2473 0.0027 0.9689 +vn -0.0000 -0.0059 1.0000 +vn -0.7508 0.5574 -0.3546 +vn -0.9561 0.1250 0.2651 +vn -0.0400 0.0002 0.9992 +vn -0.0634 0.8691 0.4906 +vn 0.0148 0.2036 -0.9789 +vn -0.0035 -1.0000 0.0008 +vn -0.0067 -1.0000 -0.0013 +vn 0.7286 -0.6742 0.1208 +vn 0.4082 0.6734 -0.6163 +vn 0.2805 -0.0231 0.9596 +vn 0.3933 -0.2988 0.8695 +vn 0.0042 -0.3703 0.9289 +vn -0.7694 0.1590 0.6187 +vn 0.1453 -0.1734 0.9741 +vn -0.8062 0.0838 -0.5857 +vn -0.8572 0.2905 -0.4253 +vn -0.7269 0.0940 -0.6802 +vn 0.1010 -0.2582 -0.9608 +vn -0.7523 0.5418 0.3749 +vn 0.2256 0.2004 -0.9534 +vn -0.3477 -0.8716 -0.3456 +vn -0.2079 -0.1795 0.9615 +vn -0.2270 -0.0103 0.9738 +vn -0.2263 -0.0190 0.9739 +vn 0.3317 -0.3715 -0.8672 +vn -0.8014 0.2238 -0.5547 +vn -0.9362 0.1280 -0.3273 +vn -0.7702 0.0122 -0.6377 +vn 0.0069 0.9982 0.0598 +vn -0.9553 -0.1192 -0.2706 +vn -0.9766 0.1217 -0.1772 +vn -0.1953 -0.3786 -0.9047 +vn 0.7104 -0.6360 0.3015 +vn 0.4645 0.7565 0.4604 +vn 0.0430 0.7503 -0.6597 +vn 0.1412 0.3851 -0.9120 +vn 0.1151 0.4196 -0.9004 +vn 0.5293 0.4850 0.6961 +vn -0.0077 -0.9998 0.0184 +vn -0.3258 0.5365 -0.7784 +vn -0.9112 -0.2507 0.3268 +vn -0.2067 0.0035 0.9784 +vn -0.2067 0.0036 0.9784 +vn 0.0298 -0.1482 0.9885 +vn 0.7051 -0.7048 0.0780 +vn -0.0844 0.8262 -0.5570 +vn 0.0169 0.6846 0.7287 +vn -0.4924 0.7493 0.4427 +vn -0.0095 0.0000 1.0000 +vn -0.2326 -0.0035 -0.9726 +vn -0.7852 -0.5777 0.2230 +vn -0.8987 0.1210 0.4215 +vn -0.3088 -0.7614 0.5701 +vn -0.6803 0.7179 -0.1478 +vn 0.1657 -0.3246 -0.9312 +vn 0.0926 0.9717 -0.2173 +vn 0.0981 0.9626 -0.2524 +vn 0.9599 -0.2786 0.0302 +vn -0.8000 -0.1534 -0.5800 +vn -0.4141 0.7348 0.5372 +vn -0.0301 0.9187 -0.3938 +vn 0.9542 -0.1860 -0.2342 +vn 0.8488 -0.0019 -0.5287 +vn -0.1674 -0.2845 -0.9440 +vn 0.7085 0.6362 0.3055 +vn 0.8003 -0.0946 0.5921 +vn 0.9315 -0.2369 0.2761 +vn -0.7000 -0.7137 0.0244 +vn -0.8382 -0.2907 0.4613 +vn -0.8583 -0.2778 0.4314 +vn 0.9712 -0.1746 -0.1622 +vn 0.0076 -0.9995 -0.0318 +vn 0.4282 -0.2923 0.8551 +vn 0.0299 0.9926 -0.1179 +vn 0.0288 0.9939 -0.1065 +vn 0.0798 -0.9960 -0.0414 +vn 0.1304 -0.9748 -0.1810 +vn 0.1067 -0.9793 -0.1719 +vn 0.1989 -0.9186 0.3416 +vn 0.1137 -0.0172 0.9934 +vn -0.3942 -0.7090 -0.5848 +vn -0.9508 -0.0098 0.3098 +vn -0.9507 -0.0098 0.3098 +vn -0.7844 0.4977 -0.3701 +vn -0.1119 -0.9028 0.4152 +vn -0.1144 -0.6784 -0.7257 +vn -0.9149 0.3727 -0.1552 +vn 0.2084 0.5415 0.8145 +vn 0.2084 0.5416 0.8144 +vn 0.0049 -0.9982 0.0606 +vn 0.1487 0.9037 0.4015 +vn -0.7584 -0.6202 -0.2003 +vn -0.4245 0.7120 0.5594 +vn -0.2068 -0.0078 0.9784 +vn -0.2067 -0.0078 0.9784 +vn 0.2988 0.7315 0.6129 +vn 0.4482 0.7581 0.4738 +vn 0.1536 -0.0109 0.9881 +vn 0.7105 0.0114 0.7036 +vn -0.2833 0.0014 -0.9590 +vn -0.2315 0.0004 -0.9728 +vn -0.8203 -0.0121 0.5719 +vn -0.8766 -0.0355 0.4798 +vn -0.8944 0.0054 0.4472 +vn -0.2138 -0.4004 0.8911 +vn -0.1962 -0.5189 0.8320 +vn -0.0611 -0.3818 0.9222 +vn 0.2567 0.0078 0.9665 +vn 0.1755 0.8270 0.5342 +vn 0.1381 -0.7873 -0.6009 +vn 0.1996 0.2408 0.9498 +vn -0.0468 0.7519 0.6576 +vn -0.3084 0.8201 0.4820 +vn -0.0474 0.7079 0.7047 +vn -0.2018 -0.8603 -0.4682 +vn -0.9994 -0.0079 0.0335 +vn 0.0753 -0.4447 -0.8925 +vn -0.0227 0.8031 0.5954 +vn -0.5237 0.8221 0.2233 +vn 0.0859 -0.0133 0.9962 +vn -0.9062 -0.0147 0.4225 +vn 0.0268 0.9431 -0.3313 +vn 0.2971 -0.1667 -0.9402 +vn 0.1297 -0.9654 0.2261 +vn 0.9313 0.0008 0.3644 +vn -0.9072 -0.4072 -0.1054 +vn -0.8654 -0.4897 -0.1057 +vn 0.4221 0.3804 -0.8229 +vn -0.0503 0.3079 -0.9501 +vn 0.3582 -0.0047 -0.9336 +vn -0.7446 0.0102 -0.6674 +vn 0.9601 -0.0348 -0.2775 +vn -0.7439 -0.0118 -0.6682 +vn 0.9313 -0.0009 0.3643 +vn 0.7439 -0.0126 0.6682 +vn 0.7439 -0.0126 0.6681 +vn 0.3893 0.0383 -0.9203 +vn 0.7207 0.0121 -0.6932 +vn -0.0519 0.9976 0.0455 +vn -0.0843 0.9894 0.1181 +vn 0.0728 -0.9930 -0.0925 +vn -0.4416 -0.4201 0.7928 +vn -0.6165 -0.3539 0.7034 +vn -0.9275 0.2312 0.2938 +vn -0.8580 0.2765 0.4329 +vn -0.9305 -0.0313 -0.3651 +vn -0.9305 -0.0314 -0.3651 +vn 0.9213 -0.2019 0.3322 +vn -0.1635 -0.3484 -0.9230 +vn 0.5799 -0.2828 0.7640 +vn 0.4068 -0.2910 0.8659 +vn 0.1097 -0.9666 -0.2316 +vn 0.0789 -0.3605 0.9294 +vn -0.7948 -0.0692 -0.6028 +vn 0.1658 -0.5151 0.8410 +vn -0.1583 0.3224 0.9333 +vn 0.0656 0.2790 0.9580 +vn -0.9594 0.1124 0.2586 +vn -0.0814 0.9860 -0.1455 +vn -0.0120 0.9999 0.0065 +vn -0.0537 -0.7086 0.7036 +vn 0.1379 0.9747 -0.1761 +vn 0.1088 0.9803 -0.1650 +vn 0.8114 -0.1086 0.5744 +vn 0.0298 -0.0470 0.9984 +vn 0.0989 0.0675 0.9928 +vn 0.0748 -0.6385 -0.7660 +vn 0.2233 0.0200 0.9746 +vn 0.5428 0.8138 0.2076 +vn -0.6915 -0.7210 -0.0456 +vn 0.0320 0.9023 0.4299 +vn -0.0085 -1.0000 -0.0010 +vn 0.1184 0.9844 0.1302 +vn 0.0887 0.9903 0.1071 +vn 0.0603 0.9945 0.0861 +vn 0.9159 -0.0758 0.3942 +vn 0.2413 0.7897 0.5641 +vn 0.1918 0.1744 0.9658 +vn 0.0481 -0.3021 0.9521 +vn -0.9638 0.1004 0.2469 +vn -0.3116 -0.1419 -0.9396 +vn 0.0369 0.7998 -0.5991 +vn -0.0100 0.9986 0.0521 +vn -0.9065 0.0114 0.4220 +vn 0.2686 0.0258 0.9629 +vn -0.7639 -0.2836 0.5796 +vn 0.8034 0.0111 0.5953 +vn 0.6827 0.0954 -0.7245 +vn -0.6068 0.0016 0.7949 +vn 0.4596 -0.8772 -0.1389 +vn -0.2451 -0.9629 0.1131 +vn -0.2722 -0.9106 0.3109 +vn 0.6316 0.2195 0.7436 +vn -0.7730 -0.5348 0.3412 +vn -0.6384 -0.5286 0.5595 +vn 0.9305 -0.0314 0.3651 +vn 0.9305 -0.0313 0.3651 +vn 0.6285 0.7451 -0.2234 +vn 0.5470 0.7876 -0.2839 +vn 0.1385 -0.2827 0.9492 +vn 0.2311 -0.8405 -0.4901 +vn 0.0972 -0.9409 -0.3244 +vn -0.7670 0.3170 0.5579 +vn -0.7670 0.3171 0.5579 +vn 0.0203 0.3543 -0.9349 +vn 0.0200 -0.3046 -0.9523 +vn -0.0326 0.9559 -0.2920 +vn 0.4223 -0.0570 -0.9047 +vn 0.0052 0.0201 0.9998 +vn 0.3045 0.6983 0.6478 +vn 0.6045 -0.2309 0.7624 +vn 0.9304 0.0314 0.3651 +vn -0.0055 0.0012 1.0000 +vn -0.9411 -0.1222 0.3151 +vn 0.2410 0.0006 -0.9705 +vn 0.2365 -0.0011 -0.9716 +vn 0.2945 0.2981 -0.9079 +vn 0.5118 0.7028 0.4941 +vn -0.1939 0.9444 0.2655 +vn -0.8954 0.1135 0.4305 +vn -0.8902 0.1079 0.4426 +vn 0.1673 0.2845 0.9440 +vn 0.9304 -0.0314 0.3651 +vn -0.6601 -0.7390 -0.1348 +vn 0.0760 0.6857 0.7239 +vn -0.0014 -0.0143 -0.9999 +vn -0.0118 -0.1230 -0.9923 +vn 0.0010 -0.0073 -1.0000 +vn 0.3275 0.9447 0.0173 +vn -0.6542 -0.7517 -0.0830 +vn 0.5896 -0.7304 0.3447 +vn 0.1999 0.1086 0.9738 +vn -0.0092 -0.9995 0.0286 +vn 0.1885 0.1464 0.9711 +vn -0.4034 0.0160 -0.9149 +vn -0.6193 0.0637 -0.7826 +vn 0.7060 0.7042 -0.0755 +vn -0.0010 -0.0049 -1.0000 +vn -0.0010 -0.0048 -1.0000 +vn 0.0240 -0.8140 0.5803 +vn 0.7439 0.0118 0.6682 +vn 0.5912 0.1170 -0.7980 +vn -0.0559 -0.5496 -0.8335 +vn -0.9993 0.0128 0.0355 +vn 0.7101 -0.6947 -0.1148 +vn 0.0804 -0.9497 0.3025 +vn -0.6824 0.7258 0.0866 +vn -0.7465 0.6650 0.0228 +vn -0.7487 0.6623 0.0294 +vn -0.7730 0.5348 0.3412 +vn 0.8824 -0.2685 0.3864 +vn 0.8034 0.0131 -0.5953 +vn 0.6801 -0.0333 -0.7324 +vn 0.1579 -0.0060 0.9874 +vn -0.2554 0.0001 0.9668 +vn -0.4163 -0.7158 -0.5606 +vn -0.5178 0.4141 0.7486 +vn -0.5610 0.8278 0.0033 +vn -0.2430 0.0012 0.9700 +vn -0.2385 -0.0006 0.9711 +vn 0.2473 0.0260 0.9686 +vn 0.6642 -0.0002 -0.7475 +vn 0.6062 -0.0011 -0.7953 +vn 0.6647 -0.0000 -0.7471 +vn 0.1702 0.2919 -0.9412 +vn 0.5647 0.1087 -0.8181 +vn -0.5115 0.4782 -0.7139 +vn 0.1598 0.9571 0.2417 +vn -0.2067 -0.0035 0.9784 +vn -0.2067 -0.0036 0.9784 +vn 0.2513 0.0920 -0.9635 +vn 0.2529 0.0918 -0.9631 +vn -0.0207 -0.0012 -0.9998 +vn -0.0206 -0.0015 -0.9998 +vn 0.2656 0.0747 0.9612 +vn -0.9654 -0.1539 -0.2107 +vn 0.1114 0.9605 -0.2551 +vn 0.0512 -0.9780 0.2022 +vn -0.5723 0.0235 0.8197 +vn 0.7186 -0.0001 -0.6954 +vn 0.1140 0.7266 0.6775 +vn 0.7117 0.0048 0.7025 +vn 0.0406 0.5458 0.8369 +vn 0.0730 -0.9456 0.3169 +vn 0.0801 0.9923 0.0945 +vn 0.0038 -0.0118 0.9999 +vn -0.7842 0.0125 0.6203 +vn -0.9972 0.0160 0.0736 +vn 0.0458 0.3263 0.9441 +vn -0.0534 -0.0015 0.9986 +vn -0.6898 0.0005 -0.7240 +vn -0.5621 0.0036 -0.8271 +vn 0.0868 0.9923 -0.0880 +vn -0.9507 -0.0048 0.3102 +vn 0.5165 0.6988 0.4949 +vn 0.2726 0.1101 0.9558 +vn 0.3994 -0.3200 -0.8591 +vn 0.7183 0.6925 0.0662 +vn -0.8161 0.3008 0.4934 +vn -0.2749 -0.0005 0.9615 +vn -0.2466 0.0016 0.9691 +vn 0.0824 -0.8978 -0.4326 +vn -0.1918 0.3235 -0.9266 +vn 0.0655 -0.9951 -0.0740 +vn 0.9506 0.0154 -0.3102 +vn -0.1034 -0.3407 0.9345 +vn 0.0828 -0.2967 0.9514 +vn 0.1673 -0.2845 0.9440 +vn 0.2635 -0.3031 -0.9158 +vn -0.4272 -0.0186 0.9040 +vn -0.4701 0.0043 0.8826 +vn -0.4398 -0.0120 0.8980 +vn 0.7639 -0.2837 -0.5796 +vn -0.0120 0.9999 -0.0012 +vn 0.0105 -0.0011 0.9999 +vn -0.9768 0.0884 0.1951 +vn 0.3885 -0.0104 -0.9214 +vn 0.3884 -0.0112 -0.9214 +vn 0.7230 -0.0280 0.6903 +vn 0.1893 0.0436 0.9809 +vn 0.9482 0.1849 0.2582 +vn -0.0368 0.0008 0.9993 +vn -0.0057 1.0000 0.0005 +vn -0.3064 0.0043 0.9519 +vn 0.0862 0.9910 0.1027 +vn -0.5638 -0.4107 0.7165 +vn -0.2407 -0.9641 -0.1118 +vn 0.9213 -0.2020 0.3321 +vn 0.5843 0.2817 0.7611 +vn -0.3478 0.0057 0.9376 +vn -0.7948 0.0693 -0.6029 +vn -0.1994 -0.7789 0.5946 +vn 0.1940 0.1731 0.9656 +vn 0.2744 0.1176 0.9544 +vn 0.9305 0.0314 0.3650 +vn 0.7064 -0.7047 -0.0660 +vn 0.2260 0.3733 0.8997 +vn 0.0387 -0.5025 0.8637 +vn -0.7828 -0.0807 0.6170 +vn -0.8899 -0.1132 0.4420 +vn 0.0699 -0.9943 0.0805 +vn 0.0009 0.0065 1.0000 +vn 0.0009 0.0048 1.0000 +vn -0.2552 0.0014 0.9669 +vn 0.6060 -0.0016 -0.7955 +vn -0.5786 0.5317 -0.6184 +vn 0.5262 0.0832 -0.8463 +vn -0.2411 -0.0005 0.9705 +vn -0.2442 -0.0031 0.9697 +vn 0.0721 0.9971 0.0260 +vn 0.0318 0.9970 0.0711 +vn 0.7075 0.7066 0.0087 +vn -0.7439 -0.0126 -0.6681 +vn 0.1635 0.3484 0.9230 +vn -0.9773 0.0124 -0.2115 +vn -0.1824 -0.7697 0.6117 +vn 0.0219 -0.8141 0.5803 +vn 0.3603 -0.1635 -0.9184 +vn -0.0094 0.0000 1.0000 +vn 0.1134 0.9228 -0.3683 +vn 0.1821 0.0003 -0.9833 +vn -0.3613 0.0051 0.9324 +vn 0.2684 0.3270 -0.9061 +vn -0.4643 -0.0037 0.8857 +vn -0.0124 -0.9999 -0.0005 +vn -0.7439 -0.0126 -0.6682 +vn -0.3893 -0.0383 0.9203 +vn -0.2528 0.0013 0.9675 +vn -0.1359 -0.3542 0.9252 +vn -0.6384 0.5286 0.5595 +vn -0.7505 0.5546 0.3594 +vn 0.0726 0.9957 0.0575 +vn 0.1409 0.7382 -0.6597 +vn 0.0013 -0.0051 -1.0000 +vn 0.7639 0.2837 -0.5796 +vn 0.7125 -0.0001 0.7017 +vn -0.1134 -0.9228 0.3683 +vn 0.2352 -0.0024 -0.9719 +vn 0.0009 0.0047 1.0000 +vn 0.9506 0.0153 -0.3102 +vn 0.2272 0.0864 0.9700 +vn -0.1076 -0.4021 0.9093 +vn -0.1386 0.2826 -0.9492 +vn -0.2366 0.0010 0.9716 +vn -0.1858 0.0000 0.9826 +vn -0.0129 0.0002 0.9999 +vn -0.1076 0.4021 0.9093 +vn 0.6906 0.6795 0.2476 +vn 0.0400 -0.0002 -0.9992 +vn -0.8943 -0.1190 0.4314 +vn -0.2597 0.0002 0.9657 +vn 0.0268 -0.9936 0.1100 +vn -0.0274 0.1499 -0.9883 +vn -0.2532 0.0005 0.9674 +vn -0.1852 -0.0202 0.9825 +vn -0.1821 -0.0003 0.9833 +vn -0.2640 0.0002 0.9645 +s 1 +f 1/1/1 2/2/2 3/3/3 +f 3/3/3 2/2/2 4/4/4 +f 3/3/3 4/4/4 5/5/5 +f 5/5/5 4/4/4 6/6/6 +f 5/5/5 6/6/6 7/7/7 +f 5/5/5 7/7/7 8/8/8 +f 8/8/8 7/7/7 9/9/9 +f 9/9/9 7/7/7 10/10/10 +f 9/9/9 10/10/10 11/11/11 +f 9/9/9 11/11/11 12/12/12 +f 12/12/12 11/11/11 13/13/13 +f 12/12/12 13/13/13 14/14/14 +f 14/14/14 13/13/13 15/15/15 +f 14/14/14 15/15/15 16/16/16 +f 16/16/16 15/15/15 17/17/17 +f 16/16/16 17/17/17 18/18/18 +f 18/18/18 17/17/17 19/19/19 +f 18/18/18 19/19/19 20/20/20 +f 20/20/20 19/19/19 21/21/21 +f 20/20/20 21/21/21 22/22/22 +f 22/22/22 21/21/21 23/23/23 +f 22/22/22 23/23/23 24/24/24 +f 24/24/24 23/23/23 25/25/25 +f 24/24/24 25/25/25 1/1/1 +f 1/1/1 25/25/25 2/2/2 +f 24/24/26 3/3/26 5/5/26 +f 5/5/26 22/22/26 24/24/26 +f 1/1/26 3/3/26 24/24/26 +f 8/8/26 22/22/26 5/5/26 +f 8/8/26 18/18/26 22/22/26 +f 18/18/26 20/20/26 22/22/26 +f 9/9/26 14/14/26 18/18/26 +f 12/12/26 14/14/26 9/9/26 +f 8/8/26 9/9/26 18/18/26 +f 16/16/26 18/18/26 14/14/26 +f 25/25/27 23/23/27 4/4/27 +f 2/2/27 25/25/27 4/4/27 +f 17/17/27 15/15/27 19/19/27 +f 23/23/27 21/21/27 4/4/27 +f 21/21/27 6/6/27 4/4/27 +f 7/7/27 6/6/27 21/21/27 +f 7/7/27 21/21/27 19/19/27 +f 19/19/27 10/10/27 7/7/27 +f 19/19/27 11/11/27 10/10/27 +f 15/15/27 11/11/27 19/19/27 +f 11/11/27 15/15/27 13/13/27 +f 26/26/28 27/27/29 28/28/30 +f 28/28/30 27/27/29 29/29/31 +f 30/30/32 31/31/33 32/32/34 +f 32/32/34 31/31/33 33/33/35 +f 32/32/34 33/33/35 34/34/36 +f 35/35/37 36/36/38 33/33/35 +f 33/33/35 36/36/38 34/34/36 +f 35/35/37 37/37/39 36/36/38 +f 37/37/39 35/35/37 38/38/40 +f 37/37/39 38/38/40 39/39/41 +f 40/40/42 41/41/43 38/38/40 +f 38/38/40 41/41/43 39/39/41 +f 41/41/43 40/40/42 42/42/44 +f 42/42/44 40/40/42 43/43/45 +f 43/43/45 40/40/42 44/44/46 +f 44/44/46 45/45/47 43/43/45 +f 46/46/48 47/47/49 45/45/47 +f 46/46/48 45/45/47 44/44/46 +f 47/47/49 46/46/48 48/48/50 +f 47/47/49 48/48/50 49/49/51 +f 48/48/50 50/50/52 49/49/51 +f 50/50/52 48/48/50 51/51/53 +f 50/50/52 51/51/53 52/52/54 +f 29/29/31 27/27/29 52/52/54 +f 29/29/31 52/52/54 51/51/53 +f 53/53/55 28/28/30 29/29/31 +f 53/53/55 54/54/56 28/28/30 +f 55/55/57 56/56/58 53/53/55 +f 53/53/55 56/56/58 54/54/56 +f 55/55/57 57/57/59 56/56/58 +f 58/58/60 59/59/61 57/57/59 +f 58/58/60 57/57/59 55/55/57 +f 60/60/62 59/59/61 58/58/60 +f 61/61/63 60/60/62 58/58/60 +f 62/62/64 63/63/65 61/61/63 +f 61/61/63 63/63/65 60/60/62 +f 63/63/65 62/62/64 64/64/66 +f 65/65/67 64/64/66 62/62/64 +f 65/65/67 66/66/68 64/64/66 +f 67/67/69 66/66/68 65/65/67 +f 67/67/69 68/68/70 66/66/68 +f 69/69/71 68/68/70 67/67/69 +f 69/69/71 67/67/69 70/70/72 +f 69/69/71 70/70/72 71/71/73 +f 71/71/73 70/70/72 31/31/33 +f 30/30/32 71/71/73 31/31/33 +f 71/71/73 30/30/32 72/72/74 +f 73/73/75 74/74/76 75/75/77 +f 76/76/78 77/77/79 78/78/80 +f 79/79/81 74/74/76 73/73/75 +f 78/78/80 80/80/82 76/76/78 +f 81/81/83 82/82/84 79/79/81 +f 81/81/83 79/79/81 73/73/75 +f 75/75/77 74/74/76 83/83/85 +f 82/82/84 81/81/83 76/76/78 +f 76/76/78 81/81/83 77/77/79 +f 80/80/82 78/78/80 84/84/86 +f 84/84/86 78/78/80 85/85/87 +f 84/84/86 86/86/88 75/75/89 +f 84/84/86 75/75/89 83/83/90 +f 86/86/88 84/84/86 85/85/87 +f 87/87/91 88/88/92 89/89/93 +f 88/88/92 90/90/94 89/89/93 +f 87/87/91 89/89/93 91/91/95 +f 92/92/96 93/93/97 94/94/98 +f 92/92/96 94/94/98 95/95/99 +f 94/94/98 96/96/100 95/95/99 +f 90/90/94 88/88/92 97/97/101 +f 98/98/102 99/99/103 100/100/101 +f 99/99/103 98/98/102 101/101/104 +f 101/101/104 98/98/102 102/102/105 +f 101/101/104 102/102/105 93/93/97 +f 101/101/104 93/93/97 92/92/96 +f 100/100/101 103/103/101 97/97/101 +f 97/97/101 103/103/101 104/104/101 +f 97/97/101 104/104/101 90/90/94 +f 99/99/103 105/105/101 100/100/101 +f 100/100/101 105/105/101 103/103/101 +f 106/106/106 107/107/107 95/95/108 +f 106/106/106 108/108/109 109/109/110 +f 95/95/108 108/108/109 106/106/106 +f 110/110/111 111/111/112 112/112/113 +f 110/110/111 112/112/113 113/113/114 +f 114/114/115 115/115/116 116/116/117 +f 117/117/118 72/72/74 30/30/32 +f 30/30/32 115/115/116 114/114/115 +f 117/117/118 30/30/32 114/114/115 +f 118/118/119 119/119/120 120/120/121 +f 121/121/122 27/27/29 26/26/28 +f 27/27/29 121/121/122 118/118/119 +f 120/120/121 27/27/29 118/118/119 +f 36/36/38 122/122/123 34/34/36 +f 34/34/36 122/122/123 32/32/34 +f 107/107/107 41/41/43 123/123/124 +f 110/110/111 113/113/114 45/45/47 +f 47/47/49 110/110/111 45/45/47 +f 106/106/106 109/109/110 37/37/39 +f 37/37/39 109/109/110 36/36/38 +f 42/42/44 43/43/45 124/124/125 +f 49/49/51 110/110/111 47/47/49 +f 113/113/114 124/124/125 45/45/47 +f 45/45/47 124/124/125 43/43/45 +f 41/41/43 42/42/44 123/123/124 +f 106/106/106 37/37/39 107/107/107 +f 124/124/125 123/123/124 42/42/44 +f 107/107/107 39/39/41 41/41/43 +f 39/39/41 107/107/107 37/37/39 +f 109/109/110 122/122/123 36/36/38 +f 116/116/126 96/96/127 114/114/128 +f 114/114/128 96/96/127 94/94/129 +f 114/114/130 94/94/131 117/117/132 +f 117/117/132 94/94/131 93/93/133 +f 117/117/134 93/93/135 72/72/136 +f 72/72/136 93/93/135 102/102/137 +f 87/87/138 125/125/139 126/126/140 +f 87/87/138 126/126/140 88/88/141 +f 88/88/141 126/126/140 127/127/142 +f 88/88/141 127/127/142 97/97/143 +f 97/97/143 127/127/142 128/128/144 +f 97/97/143 128/128/144 100/100/145 +f 100/100/145 128/128/144 129/129/146 +f 100/100/147 129/129/148 98/98/149 +f 98/98/149 129/129/148 130/130/150 +f 98/98/151 130/130/152 72/72/153 +f 98/98/151 72/72/153 102/102/154 +f 131/131/155 132/132/156 127/127/157 +f 131/131/155 127/127/157 126/126/158 +f 125/125/159 133/133/160 126/126/158 +f 126/126/158 133/133/160 131/131/155 +f 71/71/73 72/72/74 130/130/161 +f 71/71/73 130/130/161 134/134/162 +f 134/134/162 130/130/161 135/135/163 +f 129/129/164 135/135/163 130/130/161 +f 128/128/165 135/135/163 129/129/164 +f 127/127/157 136/136/166 128/128/165 +f 127/127/157 132/132/156 136/136/166 +f 128/128/165 136/136/166 135/135/163 +f 137/137/167 138/138/168 85/85/169 +f 138/138/168 86/86/88 85/85/169 +f 139/139/170 137/137/167 85/85/169 +f 140/140/171 86/86/88 138/138/168 +f 26/26/28 28/28/30 141/141/172 +f 141/141/172 28/28/30 142/142/173 +f 143/143/174 144/144/175 140/140/171 +f 140/140/171 144/144/175 86/86/88 +f 143/143/174 145/145/176 144/144/175 +f 141/141/172 142/142/173 145/145/176 +f 141/141/172 145/145/176 143/143/174 +f 146/146/177 119/119/178 147/147/179 +f 147/147/179 119/119/178 118/118/180 +f 147/147/179 118/118/180 148/148/181 +f 148/148/181 118/118/180 121/121/182 +f 148/148/181 121/121/182 149/149/183 +f 121/121/182 26/26/184 149/149/183 +f 149/149/185 26/26/186 150/150/187 +f 150/150/187 26/26/186 141/141/188 +f 150/150/187 141/141/188 151/151/189 +f 151/151/189 141/141/188 143/143/190 +f 151/151/189 143/143/190 152/152/191 +f 152/152/191 143/143/190 140/140/192 +f 152/152/193 140/140/194 153/153/195 +f 153/153/195 140/140/194 138/138/196 +f 153/153/197 138/138/198 154/154/199 +f 154/154/199 138/138/198 137/137/138 +f 154/154/199 137/137/138 155/155/139 +f 113/113/200 156/156/201 124/124/202 +f 156/156/201 123/123/203 124/124/202 +f 157/157/204 107/107/205 156/156/201 +f 156/156/201 107/107/205 123/123/203 +f 158/158/206 159/159/207 156/156/201 +f 156/156/201 159/159/207 157/157/204 +f 153/153/208 73/73/209 152/152/210 +f 160/160/211 112/112/212 147/147/213 +f 112/112/212 146/146/214 147/147/213 +f 160/160/211 147/147/213 148/148/215 +f 160/160/211 148/148/215 161/161/216 +f 73/73/209 153/153/208 81/81/217 +f 81/81/217 153/153/208 154/154/218 +f 149/149/219 162/162/220 161/161/216 +f 81/81/217 154/154/218 163/163/221 +f 163/163/221 154/154/218 155/155/222 +f 161/161/216 148/148/215 149/149/219 +f 149/149/219 150/150/210 162/162/220 +f 162/162/220 150/150/210 164/164/210 +f 164/164/210 150/150/210 151/151/210 +f 152/152/210 73/73/209 165/165/210 +f 165/165/210 166/166/210 152/152/210 +f 152/152/210 166/166/210 151/151/210 +f 151/151/210 166/166/210 164/164/210 +f 73/73/75 75/75/77 167/167/223 +f 167/167/223 165/165/224 73/73/75 +f 165/165/224 167/167/223 168/168/225 +f 169/169/226 166/166/227 165/165/224 +f 169/169/226 165/165/224 168/168/225 +f 170/170/228 166/166/227 169/169/226 +f 170/170/228 164/164/229 166/166/227 +f 171/171/230 164/164/229 170/170/228 +f 172/172/231 162/162/232 164/164/229 +f 172/172/231 164/164/229 171/171/230 +f 59/59/233 158/158/234 57/57/235 +f 99/99/236 173/173/237 174/174/238 +f 172/172/231 175/175/239 162/162/232 +f 101/101/240 159/159/241 176/176/242 +f 176/176/242 159/159/241 66/66/68 +f 99/99/236 176/176/242 173/173/237 +f 101/101/240 176/176/242 99/99/236 +f 57/57/235 161/161/243 175/175/239 +f 175/175/239 161/161/243 162/162/232 +f 59/59/233 63/63/244 66/66/68 +f 59/59/233 66/66/68 159/159/241 +f 59/59/233 159/159/241 158/158/234 +f 177/177/245 178/178/246 179/179/247 +f 179/179/247 178/178/246 180/180/248 +f 181/181/249 182/182/250 90/90/251 +f 181/181/249 183/183/252 182/182/250 +f 184/184/253 89/89/254 90/90/251 +f 90/90/251 182/182/250 184/184/253 +f 178/178/246 177/177/245 89/89/254 +f 178/178/246 89/89/254 184/184/253 +f 181/181/249 90/90/251 185/185/255 +f 104/104/256 185/185/255 90/90/251 +f 185/185/255 104/104/256 186/186/257 +f 103/103/258 186/186/257 104/104/256 +f 103/103/258 187/187/259 186/186/257 +f 187/187/259 103/103/258 188/188/260 +f 105/105/261 188/188/260 103/103/258 +f 188/188/260 105/105/261 189/189/262 +f 99/99/236 189/189/262 105/105/261 +f 189/189/262 99/99/236 174/174/238 +f 180/180/263 190/190/264 191/191/265 +f 180/180/263 191/191/265 192/192/266 +f 193/193/267 183/183/268 191/191/269 +f 191/191/269 183/183/268 192/192/270 +f 183/183/271 193/193/272 194/194/273 +f 183/183/271 194/194/273 182/182/274 +f 182/182/275 194/194/275 195/195/275 +f 182/182/276 195/195/276 184/184/276 +f 184/184/277 195/195/278 196/196/279 +f 184/184/277 196/196/279 178/178/280 +f 178/178/280 196/196/279 197/197/281 +f 190/190/282 180/180/283 197/197/284 +f 197/197/284 180/180/283 178/178/285 +f 198/198/286 84/84/287 199/199/288 +f 199/199/288 84/84/287 83/83/289 +f 84/84/290 198/198/291 80/80/292 +f 80/80/292 198/198/291 200/200/293 +f 200/200/294 76/76/294 80/80/294 +f 201/201/295 79/79/296 202/202/297 +f 202/202/297 79/79/296 82/82/298 +f 202/202/299 82/82/300 76/76/301 +f 202/202/299 76/76/301 200/200/302 +f 201/201/303 74/74/304 79/79/305 +f 199/199/306 74/74/304 201/201/303 +f 83/83/307 74/74/307 199/199/307 +f 193/193/308 190/190/309 194/194/308 +f 194/194/308 190/190/309 197/197/308 +f 194/194/308 197/197/308 195/195/308 +f 193/193/308 191/191/310 190/190/309 +f 125/125/311 203/203/312 133/133/313 +f 125/125/311 204/204/314 203/203/312 +f 125/125/311 91/91/315 204/204/314 +f 116/116/316 115/115/317 108/108/318 +f 169/169/319 144/144/175 170/170/320 +f 145/145/321 142/142/322 170/170/320 +f 170/170/320 142/142/322 171/171/323 +f 86/86/88 167/167/324 75/75/89 +f 168/168/325 167/167/324 144/144/175 +f 144/144/175 167/167/324 86/86/88 +f 169/169/319 168/168/325 144/144/175 +f 170/170/320 144/144/175 145/145/321 +f 172/172/326 171/171/323 142/142/322 +f 172/172/326 142/142/322 205/205/327 +f 205/205/327 142/142/322 28/28/328 +f 66/66/68 68/68/70 176/176/242 +f 68/68/70 69/69/71 176/176/242 +f 173/173/237 69/69/71 71/71/73 +f 205/205/327 28/28/328 175/175/239 +f 175/175/239 28/28/328 54/54/329 +f 176/176/242 69/69/71 173/173/237 +f 175/175/239 54/54/329 56/56/330 +f 63/63/244 64/64/331 66/66/68 +f 172/172/231 205/205/332 175/175/239 +f 175/175/239 56/56/330 57/57/235 +f 173/173/237 71/71/73 174/174/333 +f 161/161/243 57/57/235 158/158/234 +f 59/59/233 60/60/334 63/63/244 +f 71/71/73 134/134/162 174/174/333 +f 189/189/335 135/135/163 206/206/336 +f 189/189/335 206/206/336 188/188/337 +f 189/189/335 174/174/333 134/134/162 +f 134/134/162 135/135/163 189/189/335 +f 206/206/336 135/135/163 187/187/338 +f 206/206/336 187/187/339 188/188/337 +f 136/136/166 187/187/338 135/135/163 +f 187/187/338 136/136/166 186/186/340 +f 136/136/166 132/132/156 186/186/340 +f 186/186/340 132/132/156 185/185/341 +f 132/132/156 181/181/342 185/185/341 +f 183/183/343 181/181/342 192/192/344 +f 192/192/344 181/181/342 131/131/155 +f 192/192/344 131/131/155 180/180/248 +f 180/180/248 131/131/155 179/179/247 +f 132/132/156 131/131/155 181/181/342 +f 203/203/345 131/131/346 133/133/347 +f 131/131/346 203/203/345 179/179/348 +f 204/204/349 179/179/350 203/203/351 +f 179/179/350 204/204/349 177/177/352 +f 177/177/353 204/204/354 89/89/355 +f 89/89/355 204/204/354 91/91/356 +f 81/81/357 163/163/358 207/207/359 +f 81/81/357 207/207/359 77/77/360 +f 207/207/361 78/78/361 77/77/361 +f 139/139/362 78/78/363 207/207/364 +f 85/85/365 78/78/363 139/139/362 +f 112/112/212 208/208/366 113/113/200 +f 113/113/200 208/208/366 156/156/201 +f 112/112/212 160/160/211 208/208/366 +f 158/158/206 156/156/201 208/208/366 +f 158/158/206 208/208/366 161/161/216 +f 208/208/366 160/160/211 161/161/216 +f 95/95/99 209/209/367 92/92/96 +f 209/209/367 95/95/99 107/107/368 +f 209/209/367 107/107/368 157/157/369 +f 101/101/104 92/92/96 209/209/367 +f 101/101/104 209/209/367 159/159/370 +f 159/159/370 209/209/367 157/157/369 +f 29/29/31 210/210/371 53/53/55 +f 53/53/55 210/210/371 211/211/372 +f 53/53/55 211/211/372 55/55/57 +f 55/55/57 211/211/372 212/212/373 +f 55/55/57 212/212/373 58/58/60 +f 58/58/60 212/212/373 61/61/63 +f 61/61/63 212/212/373 213/213/374 +f 61/61/63 213/213/374 62/62/64 +f 62/62/64 213/213/374 214/214/375 +f 62/62/64 214/214/375 65/65/67 +f 65/65/67 214/214/375 67/67/69 +f 67/67/69 214/214/375 215/215/376 +f 67/67/69 215/215/376 70/70/72 +f 70/70/72 215/215/376 216/216/377 +f 70/70/72 216/216/377 31/31/33 +f 31/31/33 216/216/377 217/217/378 +f 31/31/33 217/217/378 33/33/35 +f 33/33/35 217/217/378 35/35/37 +f 35/35/37 217/217/378 218/218/379 +f 35/35/37 218/218/379 38/38/40 +f 38/38/40 218/218/379 219/219/380 +f 38/38/40 219/219/380 40/40/42 +f 40/40/42 219/219/380 220/220/381 +f 40/40/42 220/220/381 44/44/46 +f 44/44/46 220/220/381 221/221/382 +f 44/44/46 221/221/382 46/46/48 +f 46/46/48 221/221/382 222/222/383 +f 46/46/48 222/222/383 48/48/50 +f 48/48/50 222/222/383 51/51/53 +f 51/51/53 222/222/383 29/29/31 +f 29/29/31 222/222/383 210/210/371 +f 215/215/384 217/217/385 216/216/386 +f 217/217/385 215/215/384 218/218/387 +f 215/215/384 219/219/27 218/218/387 +f 214/214/388 213/213/389 215/215/384 +f 219/219/27 213/213/389 220/220/390 +f 220/220/390 213/213/389 212/212/390 +f 220/220/390 212/212/390 222/222/27 +f 221/221/390 220/220/390 222/222/27 +f 222/222/27 212/212/390 211/211/391 +f 211/211/391 210/210/392 222/222/27 +f 213/213/389 219/219/27 215/215/384 +f 195/195/308 197/197/308 196/196/393 +f 95/95/394 96/96/395 108/108/318 +f 125/125/311 87/87/396 91/91/315 +f 96/96/395 116/116/316 108/108/318 +f 112/112/397 111/111/398 223/223/399 +f 146/146/400 112/112/397 223/223/399 +f 223/223/399 120/120/401 146/146/400 +f 119/119/402 146/146/400 120/120/401 +f 155/155/403 207/207/404 163/163/404 +f 155/155/403 139/139/405 207/207/404 +f 202/202/406 200/200/309 201/201/308 +f 201/201/308 200/200/309 199/199/309 +f 155/155/403 137/137/407 139/139/405 +f 199/199/309 200/200/309 198/198/408 +f 120/120/121 223/223/409 52/52/54 +f 110/110/111 49/49/51 111/111/112 +f 49/49/51 52/52/54 111/111/112 +f 111/111/112 52/52/54 223/223/409 +f 52/52/54 27/27/29 120/120/121 +f 52/52/54 49/49/51 50/50/52 +f 109/109/110 108/108/109 122/122/123 +f 115/115/116 32/32/34 122/122/123 +f 115/115/116 122/122/123 108/108/109 +f 30/30/32 32/32/34 115/115/116 +f 224/224/410 225/225/411 226/226/412 +f 224/224/410 226/226/412 227/227/413 +f 227/227/413 226/226/412 228/228/414 +f 229/229/415 230/230/416 231/231/417 +f 231/231/417 230/230/416 232/232/418 +f 231/231/417 232/232/418 225/225/411 +f 231/231/417 225/225/411 224/224/410 +f 227/227/413 228/228/414 233/233/419 +f 233/233/419 228/228/414 234/234/420 +f 233/233/419 234/234/420 235/235/421 +f 236/236/422 237/237/423 238/238/424 +f 238/238/424 237/237/423 239/239/425 +f 238/238/424 239/239/425 240/240/426 +f 238/238/424 240/240/426 229/229/415 +f 229/229/415 240/240/426 230/230/416 +f 233/233/419 235/235/421 241/241/427 +f 233/233/419 241/241/427 242/242/428 +f 242/242/428 241/241/427 236/236/422 +f 236/236/422 241/241/427 237/237/423 +f 238/238/429 243/243/430 236/236/431 +f 236/236/431 243/243/430 244/244/432 +f 236/236/433 244/244/434 242/242/435 +f 242/242/435 244/244/434 245/245/436 +f 242/242/435 245/245/436 233/233/437 +f 233/233/437 245/245/436 246/246/438 +f 233/233/439 246/246/440 247/247/441 +f 233/233/439 247/247/441 227/227/442 +f 227/227/443 247/247/444 248/248/445 +f 227/227/443 248/248/445 224/224/446 +f 224/224/447 248/248/448 249/249/449 +f 224/224/447 249/249/449 231/231/450 +f 231/231/450 249/249/449 250/250/451 +f 231/231/450 250/250/451 229/229/452 +f 229/229/452 250/250/451 251/251/453 +f 229/229/452 251/251/453 238/238/429 +f 238/238/429 251/251/453 243/243/430 +f 244/244/454 252/252/455 245/245/456 +f 245/245/456 252/252/455 253/253/457 +f 245/245/456 253/253/457 246/246/458 +f 250/250/459 254/254/460 255/255/461 +f 250/250/459 255/255/461 251/251/462 +f 251/251/462 255/255/461 243/243/463 +f 248/248/464 256/256/465 257/257/466 +f 248/248/464 257/257/466 249/249/467 +f 249/249/467 257/257/466 250/250/459 +f 250/250/459 257/257/466 254/254/460 +f 246/246/458 253/253/457 258/258/468 +f 246/246/458 258/258/468 247/247/469 +f 247/247/469 258/258/468 259/259/470 +f 247/247/469 259/259/470 248/248/464 +f 248/248/464 259/259/470 256/256/465 +f 243/243/463 255/255/461 260/260/471 +f 243/243/463 260/260/471 261/261/472 +f 243/243/463 261/261/472 244/244/454 +f 244/244/454 261/261/472 252/252/455 +f 240/240/473 260/260/474 255/255/475 +f 240/240/473 255/255/475 230/230/476 +f 230/230/476 255/255/475 254/254/477 +f 254/254/477 262/262/478 230/230/476 +f 230/230/476 262/262/478 232/232/479 +f 232/232/479 262/262/478 225/225/480 +f 262/262/478 257/257/481 225/225/480 +f 225/225/480 257/257/481 263/263/482 +f 225/225/480 263/263/482 226/226/483 +f 263/263/482 256/256/484 226/226/483 +f 226/226/483 256/256/484 264/264/485 +f 264/264/485 256/256/484 259/259/486 +f 259/259/486 265/265/487 264/264/485 +f 264/264/485 265/265/487 228/228/488 +f 228/228/488 265/265/487 234/234/489 +f 265/265/487 258/258/490 234/234/489 +f 234/234/489 258/258/490 253/253/491 +f 234/234/489 253/253/491 235/235/492 +f 235/235/492 253/253/491 241/241/493 +f 253/253/491 252/252/494 241/241/493 +f 241/241/493 252/252/494 266/266/495 +f 266/266/495 252/252/494 267/267/496 +f 266/266/495 267/267/496 237/237/497 +f 267/267/496 268/268/498 237/237/497 +f 237/237/497 268/268/498 239/239/499 +f 239/239/499 268/268/498 260/260/474 +f 239/239/499 260/260/474 240/240/473 +f 256/256/500 263/263/500 257/257/500 +f 257/257/466 262/262/501 254/254/460 +f 260/260/471 268/268/502 261/261/472 +f 261/261/503 268/268/498 267/267/496 +f 261/261/504 267/267/504 252/252/504 +f 258/258/468 265/265/505 259/259/470 +f 266/266/506 237/237/423 241/241/427 +f 264/264/507 228/228/414 226/226/412 +f 269/269/101 270/270/101 271/271/101 +f 270/270/101 269/269/101 272/272/101 +f 273/273/101 274/274/101 275/275/101 +f 270/270/101 272/272/101 276/276/101 +f 270/270/101 276/276/101 277/277/101 +f 270/270/101 277/277/101 278/278/101 +f 278/278/101 277/277/101 273/273/101 +f 278/278/101 273/273/101 275/275/101 +f 279/279/508 280/280/509 281/281/510 +f 279/279/508 281/281/510 282/282/26 +f 282/282/26 283/283/511 279/279/508 +f 282/282/26 284/284/512 283/283/511 +f 284/284/512 282/282/26 285/285/26 +f 285/285/26 286/286/512 284/284/512 +f 285/285/26 287/287/510 286/286/512 +f 286/286/512 287/287/510 288/288/511 +f 287/287/510 289/289/513 290/290/514 +f 288/288/511 287/287/510 290/290/514 +f 291/291/515 292/292/516 293/293/517 +f 293/293/517 292/292/516 294/294/518 +f 294/294/518 295/295/519 293/293/517 +f 296/296/520 297/297/521 292/292/516 +f 292/292/516 297/297/521 298/298/522 +f 292/292/516 291/291/515 296/296/520 +f 298/298/522 299/299/523 300/300/524 +f 297/297/521 299/299/523 298/298/522 +f 294/294/518 300/300/524 295/295/519 +f 298/298/522 300/300/524 294/294/518 +f 301/301/525 302/302/526 303/303/527 +f 304/304/528 302/302/526 301/301/525 +f 301/301/525 303/303/527 305/305/529 +f 306/306/530 307/307/531 308/308/532 +f 307/307/533 309/309/534 308/308/535 +f 308/308/535 309/309/534 305/305/536 +f 305/305/537 309/309/538 301/301/539 +f 301/301/539 309/309/538 310/310/540 +f 301/301/539 310/310/540 311/311/541 +f 310/310/540 312/312/542 311/311/541 +f 311/311/541 312/312/542 304/304/543 +f 304/304/544 312/312/545 302/302/546 +f 302/302/546 312/312/545 313/313/547 +f 302/302/548 313/313/549 306/306/550 +f 313/313/549 314/314/551 306/306/550 +f 306/306/530 314/314/552 307/307/531 +f 314/314/553 315/315/554 316/316/555 +f 309/309/556 317/317/557 310/310/558 +f 310/310/558 318/318/559 312/312/560 +f 312/312/560 318/318/559 319/319/561 +f 310/310/558 317/317/557 318/318/559 +f 314/314/553 316/316/555 307/307/562 +f 313/313/563 315/315/554 314/314/553 +f 307/307/562 320/320/564 321/321/565 +f 307/307/562 321/321/565 309/309/556 +f 307/307/562 316/316/555 320/320/564 +f 312/312/560 322/322/566 313/313/563 +f 309/309/556 321/321/565 317/317/557 +f 313/313/563 322/322/566 315/315/554 +f 312/312/560 319/319/561 322/322/566 +f 293/293/567 316/316/568 291/291/569 +f 291/291/569 316/316/568 315/315/570 +f 291/291/569 315/315/570 296/296/571 +f 296/296/572 315/315/572 322/322/572 +f 296/296/573 322/322/573 297/297/573 +f 297/297/574 322/322/575 319/319/576 +f 297/297/574 319/319/576 299/299/577 +f 299/299/577 319/319/576 318/318/578 +f 299/299/579 318/318/580 300/300/581 +f 300/300/581 318/318/580 317/317/582 +f 300/300/583 317/317/584 321/321/585 +f 300/300/583 321/321/585 295/295/586 +f 295/295/586 321/321/585 320/320/587 +f 295/295/586 320/320/587 293/293/567 +f 293/293/567 320/320/587 316/316/568 +f 292/292/588 298/298/589 323/323/590 +f 323/323/590 298/298/589 324/324/591 +f 294/294/592 292/292/593 325/325/594 +f 325/325/594 292/292/593 323/323/595 +f 298/298/596 294/294/597 324/324/598 +f 324/324/598 294/294/597 325/325/599 +f 324/324/600 325/325/600 323/323/600 +f 306/306/601 303/303/527 302/302/526 +f 311/311/602 304/304/602 301/301/602 +f 308/308/603 305/305/529 303/303/527 +f 308/308/532 303/303/604 306/306/530 +f 326/326/605 327/327/606 328/328/607 +f 329/329/608 327/327/606 326/326/605 +f 330/330/609 331/331/610 332/332/611 +f 333/333/612 334/334/613 331/331/610 +f 333/333/612 331/331/610 330/330/609 +f 332/332/611 335/335/614 330/330/609 +f 328/328/607 334/334/613 326/326/605 +f 326/326/605 334/334/613 333/333/612 +f 329/329/608 326/326/605 336/336/615 +f 335/335/614 329/329/608 336/336/615 +f 330/330/609 335/335/614 336/336/615 +f 337/337/616 338/338/617 339/339/618 +f 340/340/619 338/338/617 337/337/616 +f 341/341/620 342/342/621 343/343/622 +f 341/341/620 343/343/622 344/344/623 +f 344/344/624 343/343/624 345/345/624 +f 344/344/625 345/345/626 346/346/627 +f 345/345/626 347/347/628 346/346/627 +f 346/346/629 347/347/630 339/339/631 +f 347/347/630 348/348/632 339/339/631 +f 339/339/633 348/348/634 349/349/635 +f 349/349/635 348/348/634 350/350/636 +f 349/349/637 350/350/638 351/351/639 +f 351/351/639 350/350/638 352/352/640 +f 351/351/641 352/352/642 341/341/643 +f 341/341/643 352/352/642 342/342/644 +f 352/352/645 353/353/646 354/354/647 +f 345/345/648 355/355/649 347/347/650 +f 347/347/650 356/356/651 348/348/652 +f 347/347/650 355/355/649 356/356/651 +f 352/352/645 354/354/647 342/342/653 +f 342/342/653 357/357/654 343/343/655 +f 342/342/653 354/354/647 357/357/654 +f 348/348/652 358/358/656 350/350/657 +f 350/350/657 358/358/656 359/359/658 +f 343/343/655 357/357/654 345/345/648 +f 345/345/648 357/357/654 355/355/649 +f 350/350/657 359/359/658 352/352/645 +f 352/352/645 359/359/658 353/353/646 +f 356/356/651 358/358/656 348/348/652 +f 327/327/659 354/354/660 328/328/661 +f 328/328/661 354/354/660 353/353/662 +f 328/328/663 353/353/664 334/334/665 +f 334/334/665 353/353/664 359/359/666 +f 334/334/667 359/359/668 331/331/669 +f 331/331/669 359/359/668 358/358/670 +f 331/331/671 358/358/672 332/332/673 +f 332/332/673 358/358/672 356/356/674 +f 332/332/675 356/356/676 335/335/677 +f 335/335/677 356/356/676 355/355/678 +f 335/335/679 355/355/680 357/357/681 +f 335/335/679 357/357/681 329/329/682 +f 329/329/683 357/357/684 327/327/685 +f 327/327/685 357/357/684 354/354/686 +f 333/333/687 330/330/688 360/360/689 +f 360/360/689 330/330/688 361/361/690 +f 326/326/691 333/333/692 362/362/693 +f 362/362/693 333/333/692 360/360/694 +f 336/336/695 326/326/696 363/363/697 +f 363/363/697 326/326/696 362/362/698 +f 330/330/699 336/336/700 361/361/701 +f 361/361/701 336/336/700 363/363/702 +f 363/363/703 362/362/703 361/361/703 +f 361/361/703 362/362/703 360/360/703 +f 341/341/704 340/340/705 351/351/706 +f 351/351/706 340/340/705 337/337/707 +f 351/351/708 337/337/708 349/349/708 +f 349/349/709 337/337/616 339/339/618 +f 346/346/710 339/339/710 338/338/710 +f 346/346/627 338/338/711 344/344/625 +f 344/344/712 338/338/617 340/340/619 +f 344/344/623 340/340/713 341/341/620 +f 364/364/714 365/365/715 366/366/716 +f 366/366/716 365/365/715 367/367/717 +f 365/365/718 368/368/719 367/367/720 +f 367/367/720 368/368/719 369/369/721 +f 368/368/722 370/370/723 369/369/724 +f 369/369/724 370/370/723 371/371/725 +f 366/366/726 371/371/727 364/364/728 +f 364/364/728 371/371/727 370/370/729 +f 369/369/730 371/371/730 367/367/730 +f 367/367/730 371/371/730 366/366/730 +f 364/364/731 370/370/731 368/368/731 +f 368/368/731 365/365/731 364/364/731 +f 372/372/732 373/373/733 374/374/734 +f 374/374/734 373/373/733 375/375/735 +f 373/373/736 376/376/737 375/375/738 +f 375/375/738 376/376/737 377/377/739 +f 376/376/740 378/378/741 377/377/742 +f 377/377/742 378/378/741 379/379/743 +f 374/374/744 379/379/745 372/372/746 +f 372/372/746 379/379/745 378/378/747 +f 377/377/748 379/379/748 375/375/748 +f 375/375/748 379/379/748 374/374/749 +f 372/372/750 378/378/750 376/376/750 +f 376/376/750 373/373/750 372/372/750 +f 380/380/751 381/381/752 382/382/753 +f 383/383/754 384/384/755 380/380/751 +f 381/381/752 380/380/751 384/384/755 +f 381/381/752 384/384/755 385/385/756 +f 385/385/756 384/384/755 386/386/757 +f 382/382/758 387/387/759 388/388/760 +f 383/383/754 389/389/761 390/390/762 +f 391/391/763 390/390/762 389/389/761 +f 392/392/764 391/391/763 393/393/765 +f 393/393/765 391/391/763 389/389/761 +f 394/394/766 392/392/764 393/393/765 +f 394/394/766 395/395/767 392/392/764 +f 396/396/768 397/397/769 394/394/766 +f 394/394/766 397/397/769 395/395/767 +f 398/398/770 399/399/771 396/396/768 +f 399/399/771 397/397/769 396/396/768 +f 398/398/770 400/400/772 399/399/771 +f 401/401/773 400/400/772 398/398/770 +f 402/402/774 403/403/775 401/401/773 +f 402/402/774 401/401/773 398/398/770 +f 404/404/776 405/405/777 406/406/778 +f 404/404/776 406/406/778 407/407/779 +f 408/408/780 409/409/781 402/402/774 +f 402/402/774 409/409/781 403/403/775 +f 409/409/781 408/408/780 405/405/777 +f 409/409/781 405/405/777 404/404/776 +f 410/410/782 411/411/783 412/412/784 +f 410/410/782 412/412/784 413/413/785 +f 407/407/779 412/412/784 414/414/786 +f 412/412/784 407/407/779 406/406/778 +f 406/406/778 413/413/785 412/412/784 +f 415/415/787 416/416/788 417/417/789 +f 407/407/779 414/414/786 415/415/787 +f 415/415/787 414/414/786 416/416/788 +f 418/418/790 419/419/791 420/420/792 +f 420/420/792 421/421/793 422/422/794 +f 420/420/792 423/423/795 421/421/793 +f 420/420/792 424/424/796 423/423/795 +f 424/424/796 425/425/797 426/426/798 +f 424/424/796 426/426/798 427/427/799 +f 424/424/796 428/428/800 423/423/795 +f 426/426/798 425/425/797 385/385/756 +f 426/426/798 385/385/756 386/386/757 +f 424/424/796 427/427/799 429/429/801 +f 424/424/796 429/429/801 428/428/800 +f 388/388/760 387/387/759 430/430/802 +f 430/430/802 387/387/759 431/431/803 +f 430/430/802 431/431/803 410/410/782 +f 410/410/782 431/431/803 411/411/783 +f 417/417/789 432/432/804 420/420/792 +f 433/433/805 424/424/796 420/420/792 +f 420/420/792 432/432/804 434/434/806 +f 420/420/792 434/434/806 433/433/805 +f 435/435/807 436/436/808 437/437/809 +f 438/438/810 439/439/811 440/440/812 +f 435/435/807 437/437/809 440/440/812 +f 435/435/807 440/440/812 439/439/811 +f 441/441/813 439/439/814 442/442/815 +f 441/441/813 442/442/815 443/443/816 +f 444/444/817 445/445/818 446/446/819 +f 446/446/819 445/445/818 447/447/820 +f 446/446/819 447/447/820 443/443/816 +f 443/443/816 447/447/820 441/441/813 +f 441/441/813 448/448/821 439/439/814 +f 449/449/822 450/450/823 451/451/824 +f 452/452/825 450/450/823 453/453/826 +f 454/454/827 452/452/825 453/453/826 +f 455/455/828 456/456/829 457/457/830 +f 457/457/830 456/456/829 435/435/831 +f 449/449/822 451/451/824 458/458/832 +f 458/458/832 451/451/824 459/459/833 +f 439/439/814 448/448/821 460/460/834 +f 439/439/814 460/460/834 435/435/831 +f 435/435/831 460/460/834 457/457/830 +f 455/455/828 459/459/833 461/461/835 +f 458/458/832 459/459/833 455/455/828 +f 453/453/826 450/450/823 449/449/822 +f 455/455/828 461/461/835 456/456/829 +f 462/462/836 463/463/837 464/464/838 +f 464/464/838 463/463/837 465/465/839 +f 464/464/838 465/465/839 466/466/840 +f 272/272/101 269/269/101 467/467/841 +f 467/467/841 269/269/101 468/468/842 +f 467/467/841 468/468/842 469/469/843 +f 270/270/101 466/466/101 470/470/101 +f 471/471/101 472/472/101 473/473/101 +f 464/464/101 466/466/101 270/270/101 +f 270/270/101 471/471/101 474/474/101 +f 270/270/101 474/474/101 462/462/101 +f 270/270/101 475/475/101 271/271/101 +f 270/270/101 462/462/101 464/464/101 +f 270/270/101 278/278/101 476/476/101 +f 472/472/101 471/471/101 270/270/101 +f 472/472/101 270/270/101 476/476/101 +f 477/477/844 473/473/845 478/478/846 +f 472/472/847 478/478/846 473/473/845 +f 478/478/846 472/472/847 479/479/848 +f 472/472/847 480/480/849 479/479/848 +f 476/476/850 480/480/849 472/472/847 +f 480/480/849 476/476/850 481/481/851 +f 481/481/851 476/476/850 278/278/852 +f 390/390/853 482/482/854 483/483/855 +f 483/483/855 482/482/854 484/484/856 +f 484/484/856 485/485/857 483/483/855 +f 486/486/858 487/487/859 488/488/860 +f 486/486/858 489/489/861 487/487/859 +f 490/490/862 491/491/863 492/492/864 +f 493/493/865 491/491/863 494/494/866 +f 494/494/866 491/491/863 490/490/862 +f 494/494/866 495/495/867 493/493/865 +f 496/496/868 495/495/867 494/494/866 +f 497/497/869 496/496/868 494/494/866 +f 498/498/870 497/497/870 499/499/870 +f 499/499/871 497/497/869 494/494/866 +f 499/499/871 500/500/872 498/498/873 +f 486/486/858 501/501/874 500/500/872 +f 486/486/858 500/500/872 499/499/871 +f 488/488/860 501/501/874 486/486/858 +f 502/502/875 503/503/876 504/504/877 +f 504/504/877 505/505/878 502/502/875 +f 506/506/879 505/505/878 504/504/877 +f 507/507/880 506/506/879 504/504/877 +f 507/507/880 508/508/881 506/506/879 +f 507/507/880 509/509/882 508/508/881 +f 510/510/883 511/511/884 507/507/880 +f 507/507/880 511/511/884 509/509/882 +f 512/512/885 511/511/884 510/510/883 +f 513/513/886 512/512/885 514/514/887 +f 514/514/887 512/512/885 510/510/883 +f 515/515/888 516/516/889 514/514/887 +f 515/515/888 517/517/890 516/516/889 +f 518/518/891 517/517/890 519/519/892 +f 519/519/892 517/517/890 515/515/888 +f 519/519/892 520/520/893 518/518/891 +f 521/521/894 520/520/893 519/519/892 +f 522/522/895 520/520/893 521/521/894 +f 523/523/896 524/524/897 521/521/894 +f 521/521/894 524/524/897 522/522/895 +f 523/523/896 525/525/898 524/524/897 +f 523/523/896 526/526/899 525/525/898 +f 526/526/899 523/523/896 527/527/900 +f 528/528/901 526/526/899 527/527/900 +f 529/529/902 528/528/901 530/530/903 +f 528/528/901 527/527/900 530/530/903 +f 531/531/904 529/529/902 530/530/903 +f 490/490/862 492/492/864 530/530/903 +f 530/530/903 492/492/864 531/531/904 +f 284/284/905 530/530/903 283/283/906 +f 283/283/906 530/530/903 527/527/900 +f 283/283/906 527/527/900 523/523/896 +f 283/283/906 523/523/896 279/279/907 +f 523/523/896 521/521/894 279/279/907 +f 279/279/908 521/521/894 280/280/909 +f 521/521/894 519/519/892 280/280/909 +f 519/519/892 515/515/888 280/280/909 +f 280/280/909 515/515/888 281/281/910 +f 281/281/911 515/515/888 514/514/887 +f 281/281/911 514/514/887 282/282/912 +f 514/514/887 510/510/883 282/282/912 +f 282/282/912 510/510/883 507/507/880 +f 282/282/912 507/507/880 285/285/913 +f 507/507/880 504/504/877 285/285/913 +f 285/285/913 504/504/877 287/287/914 +f 287/287/914 504/504/877 503/503/876 +f 287/287/914 503/503/876 289/289/915 +f 503/503/876 532/532/916 289/289/915 +f 289/289/915 532/532/916 290/290/917 +f 532/532/916 489/489/861 290/290/917 +f 489/489/861 486/486/858 290/290/917 +f 290/290/917 486/486/858 288/288/918 +f 288/288/918 486/486/858 499/499/871 +f 288/288/918 499/499/871 286/286/919 +f 499/499/871 494/494/866 286/286/919 +f 286/286/919 494/494/866 284/284/905 +f 494/494/866 490/490/862 284/284/905 +f 284/284/905 490/490/862 530/530/903 +f 277/277/920 276/276/921 533/533/922 +f 534/534/923 469/469/924 535/535/925 +f 469/469/924 534/534/923 536/536/926 +f 469/469/924 536/536/926 467/467/927 +f 467/467/927 536/536/926 537/537/928 +f 538/538/929 539/539/930 540/540/931 +f 541/541/101 542/542/932 543/543/101 +f 534/534/923 535/535/925 544/544/933 +f 534/534/923 544/544/933 545/545/934 +f 272/272/935 546/546/936 276/276/921 +f 546/546/936 272/272/935 547/547/937 +f 547/547/937 272/272/935 548/548/938 +f 548/548/938 272/272/935 467/467/927 +f 548/548/938 467/467/927 537/537/928 +f 436/436/808 435/435/807 549/549/939 +f 409/409/940 549/549/939 435/435/807 +f 409/409/940 435/435/807 456/456/941 +f 409/409/940 456/456/941 403/403/942 +f 403/403/942 456/456/941 550/550/943 +f 481/481/851 278/278/852 551/551/944 +f 551/551/944 278/278/852 552/552/945 +f 275/275/946 553/553/947 552/552/945 +f 275/275/946 552/552/945 278/278/852 +f 553/553/947 275/275/946 554/554/948 +f 554/554/948 275/275/946 274/274/949 +f 554/554/948 274/274/949 555/555/950 +f 274/274/949 556/556/951 555/555/950 +f 556/556/951 274/274/949 273/273/952 +f 556/556/951 273/273/952 557/557/953 +f 273/273/952 558/558/954 557/557/953 +f 277/277/920 558/558/954 273/273/952 +f 558/558/954 277/277/920 533/533/922 +f 540/540/955 559/559/956 543/543/957 +f 543/543/957 559/559/956 560/560/958 +f 543/543/957 560/560/958 271/271/959 +f 271/271/959 560/560/958 269/269/960 +f 409/409/940 561/561/961 549/549/939 +f 404/404/962 562/562/963 563/563/964 +f 409/409/940 564/564/965 561/561/961 +f 404/404/962 563/563/964 564/564/965 +f 404/404/962 564/564/965 409/409/940 +f 439/439/966 438/438/967 442/442/968 +f 438/438/967 565/565/969 442/442/968 +f 442/442/968 565/565/969 562/562/963 +f 442/442/968 562/562/963 404/404/962 +f 407/407/970 443/443/971 404/404/972 +f 542/542/932 538/538/929 540/540/931 +f 404/404/972 443/443/971 442/442/973 +f 566/566/974 567/567/975 568/568/976 +f 533/533/922 276/276/921 546/546/936 +f 468/468/977 535/535/978 469/469/979 +f 569/569/980 535/535/978 468/468/977 +f 569/569/980 468/468/977 269/269/960 +f 569/569/980 269/269/960 570/570/981 +f 570/570/981 269/269/960 560/560/958 +f 571/571/982 518/518/891 572/572/983 +f 573/573/984 401/401/985 403/403/942 +f 573/573/984 403/403/942 574/574/986 +f 513/513/886 514/514/887 516/516/889 +f 575/575/987 576/576/988 577/577/989 +f 575/575/987 577/577/989 578/578/990 +f 575/575/987 578/578/990 579/579/991 +f 580/580/992 581/581/993 582/582/994 +f 580/580/992 582/582/994 576/576/988 +f 576/576/988 582/582/994 577/577/989 +f 581/581/993 583/583/995 582/582/994 +f 577/577/989 582/582/994 584/584/996 +f 577/577/989 584/584/996 578/578/990 +f 578/578/990 584/584/996 585/585/997 +f 401/401/985 573/573/984 583/583/995 +f 401/401/985 583/583/995 400/400/772 +f 399/399/771 400/400/772 586/586/998 +f 399/399/771 586/586/998 587/587/999 +f 399/399/771 587/587/999 397/397/769 +f 518/518/891 571/571/982 588/588/1000 +f 518/518/891 588/588/1000 589/589/1001 +f 589/589/1001 588/588/1000 590/590/1002 +f 589/589/1001 590/590/1002 591/591/1003 +f 592/592/1004 593/593/1005 575/575/987 +f 592/592/1004 575/575/987 579/579/991 +f 594/594/1006 395/395/767 397/397/769 +f 595/595/1007 392/392/764 395/395/767 +f 596/596/1008 392/392/764 595/595/1007 +f 597/597/1009 392/392/764 596/596/1008 +f 392/392/764 597/597/1009 391/391/1010 +f 598/598/1011 524/524/897 599/599/1012 +f 599/599/1012 524/524/897 525/525/898 +f 599/599/1012 525/525/898 526/526/899 +f 599/599/1012 526/526/899 600/600/1013 +f 600/600/1013 526/526/899 528/528/901 +f 579/579/991 511/511/884 592/592/1004 +f 592/592/1004 511/511/884 512/512/885 +f 589/589/1001 516/516/889 517/517/890 +f 589/589/1001 517/517/890 518/518/891 +f 572/572/983 518/518/891 520/520/893 +f 572/572/983 520/520/893 522/522/895 +f 601/601/1014 600/600/1013 528/528/901 +f 592/592/1004 512/512/885 593/593/1005 +f 593/593/1005 512/512/885 513/513/886 +f 593/593/1005 513/513/886 591/591/1003 +f 591/591/1003 513/513/886 516/516/889 +f 591/591/1003 516/516/889 589/589/1001 +f 602/602/1015 522/522/895 524/524/897 +f 602/602/1015 524/524/897 598/598/1011 +f 571/571/982 572/572/983 603/603/1016 +f 603/603/1016 572/572/983 522/522/895 +f 603/603/1016 522/522/895 604/604/1017 +f 604/604/1017 522/522/895 602/602/1015 +f 602/602/1015 598/598/1011 605/605/1018 +f 605/605/1018 598/598/1011 599/599/1012 +f 605/605/1018 599/599/1012 601/601/1014 +f 601/601/1014 599/599/1012 600/600/1013 +f 606/606/1019 602/602/1015 605/605/1018 +f 575/575/987 593/593/1005 576/576/988 +f 576/576/988 593/593/1005 580/580/992 +f 580/580/992 593/593/1005 591/591/1003 +f 580/580/992 591/591/1003 590/590/1002 +f 604/604/1017 602/602/1015 606/606/1019 +f 607/607/1020 608/608/1021 601/601/1014 +f 601/601/1014 608/608/1021 605/605/1018 +f 571/571/982 609/609/1022 588/588/1000 +f 588/588/1000 610/610/1023 590/590/1002 +f 590/590/1002 610/610/1023 611/611/1024 +f 590/590/1002 611/611/1024 580/580/992 +f 605/605/1018 608/608/1021 612/612/1025 +f 605/605/1018 612/612/1025 606/606/1019 +f 606/606/1019 612/612/1025 613/613/1026 +f 606/606/1019 613/613/1026 604/604/1017 +f 604/604/1017 613/613/1026 614/614/1027 +f 604/604/1017 614/614/1027 603/603/1016 +f 603/603/1016 614/614/1027 571/571/982 +f 609/609/1022 610/610/1023 588/588/1000 +f 611/611/1024 581/581/993 580/580/992 +f 607/607/1020 615/615/1028 608/608/1021 +f 608/608/1021 615/615/1028 597/597/1009 +f 608/608/1021 597/597/1009 612/612/1025 +f 612/612/1025 597/597/1009 613/613/1026 +f 614/614/1027 594/594/1006 571/571/982 +f 571/571/982 594/594/1006 609/609/1022 +f 610/610/1023 586/586/998 611/611/1024 +f 611/611/1024 586/586/998 581/581/993 +f 584/584/996 582/582/994 573/573/984 +f 573/573/984 582/582/994 583/583/995 +f 587/587/999 586/586/998 610/610/1023 +f 587/587/999 610/610/1023 397/397/769 +f 397/397/769 610/610/1023 609/609/1022 +f 397/397/769 609/609/1022 594/594/1006 +f 595/595/1007 594/594/1006 614/614/1027 +f 595/595/1007 614/614/1027 596/596/1008 +f 596/596/1008 614/614/1027 613/613/1026 +f 596/596/1008 613/613/1026 597/597/1009 +f 391/391/1029 597/597/1009 615/615/1028 +f 574/574/986 585/585/997 584/584/996 +f 574/574/986 584/584/996 573/573/984 +f 583/583/995 581/581/993 400/400/772 +f 400/400/772 581/581/993 586/586/998 +f 395/395/767 594/594/1006 595/595/1007 +f 390/390/853 391/391/1029 615/615/1028 +f 616/616/1030 617/617/1031 618/618/1032 +f 617/617/1031 484/484/856 618/618/1032 +f 482/482/854 618/618/1032 484/484/856 +f 619/619/1033 618/618/1032 482/482/854 +f 619/619/1033 482/482/854 620/620/1034 +f 621/621/1035 618/618/1032 619/619/1033 +f 622/622/1036 619/619/1033 620/620/1034 +f 622/622/1036 620/620/1034 623/623/1037 +f 621/621/1035 619/619/1033 624/624/1038 +f 624/624/1038 619/619/1033 622/622/1036 +f 625/625/1039 621/621/1035 624/624/1038 +f 482/482/854 390/390/853 615/615/1028 +f 492/492/864 625/625/1039 624/624/1038 +f 492/492/864 624/624/1038 531/531/904 +f 531/531/904 624/624/1038 622/622/1036 +f 531/531/904 622/622/1036 529/529/902 +f 529/529/902 622/622/1036 623/623/1037 +f 529/529/902 623/623/1037 601/601/1014 +f 601/601/1014 528/528/901 529/529/902 +f 492/492/864 491/491/863 625/625/1039 +f 620/620/1034 482/482/854 615/615/1028 +f 620/620/1034 615/615/1028 607/607/1020 +f 623/623/1037 620/620/1034 607/607/1020 +f 623/623/1037 607/607/1020 601/601/1014 +f 574/574/986 403/403/942 550/550/943 +f 550/550/943 456/456/941 626/626/1040 +f 585/585/997 574/574/986 627/627/1041 +f 627/627/1041 574/574/986 550/550/943 +f 627/627/1041 550/550/943 628/628/1042 +f 628/628/1042 550/550/943 626/626/1040 +f 578/578/990 585/585/997 629/629/1043 +f 629/629/1043 585/585/997 627/627/1041 +f 629/629/1043 627/627/1041 630/630/1044 +f 630/630/1044 627/627/1041 628/628/1042 +f 630/630/1044 628/628/1042 631/631/1045 +f 631/631/1045 628/628/1042 632/632/1046 +f 633/633/1047 631/631/1045 632/632/1046 +f 505/505/878 506/506/879 508/508/1048 +f 579/579/991 509/509/882 511/511/884 +f 628/628/1042 626/626/1040 632/632/1046 +f 631/631/1045 633/633/1047 634/634/1049 +f 631/631/1045 634/634/1049 630/630/1044 +f 630/630/1044 634/634/1049 635/635/1050 +f 630/630/1044 635/635/1050 629/629/1043 +f 629/629/1043 635/635/1050 636/636/1051 +f 629/629/1043 636/636/1051 578/578/990 +f 578/578/990 636/636/1051 579/579/991 +f 633/633/1047 637/637/1052 634/634/1049 +f 637/637/1052 505/505/878 634/634/1049 +f 634/634/1049 505/505/878 508/508/881 +f 634/634/1049 508/508/881 635/635/1050 +f 635/635/1050 508/508/881 509/509/882 +f 635/635/1050 509/509/882 636/636/1051 +f 636/636/1051 509/509/882 579/579/991 +f 638/638/1053 639/639/1054 640/640/1055 +f 452/452/825 641/641/1056 642/642/1057 +f 452/452/825 642/642/1057 450/450/823 +f 643/643/1058 642/642/1057 644/644/1059 +f 645/645/1060 644/644/1059 646/646/1061 +f 646/646/1061 638/638/1053 647/647/1062 +f 647/647/1062 638/638/1053 648/648/1063 +f 644/644/1059 642/642/1057 641/641/1056 +f 644/644/1059 641/641/1056 646/646/1061 +f 648/648/1063 638/638/1053 640/640/1055 +f 648/648/1063 640/640/1055 616/616/1030 +f 616/616/1030 640/640/1055 617/617/1031 +f 451/451/824 450/450/823 649/649/1064 +f 451/451/824 649/649/1064 459/459/1065 +f 489/489/861 532/532/916 650/650/1066 +f 459/459/1065 649/649/1064 651/651/1067 +f 650/650/1066 532/532/916 503/503/876 +f 459/459/1065 651/651/1067 652/652/1068 +f 650/650/1066 503/503/876 653/653/1069 +f 653/653/1069 503/503/876 502/502/875 +f 461/461/1070 459/459/1065 654/654/1071 +f 653/653/1069 502/502/875 655/655/1072 +f 655/655/1072 502/502/875 505/505/878 +f 497/497/869 498/498/873 656/656/1073 +f 656/656/1073 498/498/873 500/500/872 +f 656/656/1073 500/500/872 501/501/874 +f 657/657/1074 501/501/874 488/488/860 +f 487/487/859 489/489/861 650/650/1066 +f 658/658/1075 653/653/1069 659/659/1076 +f 659/659/1076 653/653/1069 655/655/1072 +f 625/625/1039 491/491/863 493/493/865 +f 625/625/1039 493/493/865 495/495/867 +f 495/495/867 496/496/868 660/660/1077 +f 660/660/1077 496/496/868 497/497/869 +f 657/657/1074 488/488/860 661/661/1078 +f 661/661/1078 488/488/860 487/487/859 +f 487/487/859 650/650/1066 662/662/1079 +f 662/662/1079 650/650/1066 658/658/1075 +f 658/658/1075 650/650/1066 653/653/1069 +f 659/659/1076 655/655/1072 663/663/1080 +f 625/625/1039 495/495/867 660/660/1077 +f 660/660/1077 497/497/869 664/664/1081 +f 664/664/1081 497/497/869 656/656/1073 +f 664/664/1081 656/656/1073 665/665/1082 +f 665/665/1082 656/656/1073 501/501/874 +f 665/665/1082 501/501/874 666/666/1083 +f 666/666/1083 501/501/874 657/657/1074 +f 667/667/1084 661/661/1078 487/487/859 +f 667/667/1084 487/487/859 662/662/1079 +f 668/668/1085 658/658/1075 669/669/1086 +f 669/669/1086 658/658/1075 659/659/1076 +f 669/669/1086 659/659/1076 663/663/1080 +f 621/621/1035 625/625/1039 670/670/1087 +f 670/670/1087 625/625/1039 660/660/1077 +f 670/670/1087 660/660/1077 671/671/1088 +f 671/671/1088 660/660/1077 664/664/1081 +f 657/657/1074 661/661/1078 643/643/1058 +f 643/643/1058 661/661/1078 667/667/1084 +f 667/667/1084 662/662/1079 672/672/1089 +f 672/672/1089 662/662/1079 668/668/1085 +f 668/668/1085 662/662/1079 658/658/1075 +f 669/669/1086 663/663/1080 633/633/1047 +f 647/647/1062 670/670/1087 671/671/1088 +f 671/671/1088 664/664/1081 645/645/1060 +f 645/645/1060 664/664/1081 665/665/1082 +f 666/666/1083 657/657/1074 643/643/1058 +f 673/673/1090 668/668/1085 669/669/1086 +f 673/673/1090 669/669/1086 674/674/1091 +f 674/674/1091 669/669/1086 633/633/1047 +f 674/674/1091 633/633/1047 632/632/1046 +f 618/618/1032 621/621/1035 616/616/1030 +f 616/616/1030 621/621/1035 670/670/1087 +f 616/616/1030 670/670/1087 648/648/1063 +f 648/648/1063 670/670/1087 647/647/1062 +f 647/647/1062 671/671/1088 646/646/1061 +f 646/646/1061 671/671/1088 645/645/1060 +f 644/644/1059 645/645/1060 665/665/1082 +f 644/644/1059 665/665/1082 666/666/1083 +f 644/644/1059 666/666/1083 643/643/1058 +f 675/675/1092 643/643/1058 667/667/1084 +f 675/675/1092 667/667/1084 672/672/1089 +f 675/675/1092 672/672/1089 676/676/1093 +f 676/676/1093 672/672/1089 668/668/1085 +f 676/676/1093 668/668/1085 673/673/1090 +f 677/677/1094 643/643/1058 675/675/1092 +f 649/649/1064 675/675/1092 676/676/1093 +f 677/677/1094 675/675/1092 649/649/1064 +f 649/649/1064 676/676/1093 651/651/1067 +f 651/651/1067 676/676/1093 652/652/1068 +f 652/652/1068 676/676/1093 673/673/1090 +f 652/652/1068 673/673/1090 674/674/1091 +f 652/652/1068 674/674/1091 626/626/1040 +f 626/626/1040 674/674/1091 632/632/1046 +f 655/655/1072 505/505/878 637/637/1052 +f 655/655/1072 637/637/1052 663/663/1080 +f 663/663/1080 637/637/1052 633/633/1047 +f 639/639/1054 638/638/1053 646/646/1061 +f 639/639/1054 646/646/1061 452/452/825 +f 452/452/825 646/646/1061 641/641/1056 +f 642/642/1057 677/677/1094 450/450/823 +f 450/450/823 677/677/1094 649/649/1064 +f 459/459/1065 652/652/1068 654/654/1071 +f 654/654/1071 652/652/1068 626/626/1040 +f 461/461/1070 654/654/1071 456/456/941 +f 456/456/941 654/654/1071 626/626/1040 +f 678/678/1095 679/679/1096 680/680/1097 +f 680/680/1097 679/679/1096 681/681/1098 +f 679/679/1096 678/678/1095 566/566/1099 +f 566/566/1099 678/678/1095 682/682/1100 +f 566/566/1099 682/682/1100 683/683/1101 +f 683/683/1101 682/682/1100 684/684/1102 +f 684/684/1102 682/682/1100 685/685/1103 +f 684/684/1102 685/685/1103 686/686/1104 +f 686/686/1104 685/685/1103 687/687/1105 +f 686/686/1104 687/687/1105 538/538/1106 +f 538/538/1106 687/687/1105 539/539/1107 +f 539/539/1107 687/687/1105 688/688/1108 +f 539/539/1107 688/688/1108 447/447/1109 +f 689/689/1110 454/454/1111 690/690/1112 +f 689/689/1110 690/690/1112 691/691/1113 +f 689/689/1110 691/691/1113 692/692/1114 +f 692/692/1114 691/691/1113 693/693/1115 +f 692/692/1114 693/693/1115 694/694/1116 +f 694/694/1116 693/693/1115 680/680/1097 +f 680/680/1097 681/681/1098 694/694/1116 +f 688/688/1108 441/441/1117 447/447/1109 +f 695/695/1118 441/441/1117 688/688/1108 +f 695/695/1118 696/696/1119 441/441/1117 +f 697/697/1120 696/696/1119 695/695/1118 +f 697/697/1120 448/448/1121 696/696/1119 +f 698/698/1122 448/448/1121 697/697/1120 +f 698/698/1122 460/460/1123 448/448/1121 +f 699/699/1124 457/457/1125 698/698/1122 +f 698/698/1122 457/457/1125 460/460/1123 +f 699/699/1124 700/700/1126 457/457/1125 +f 701/701/1127 455/455/1128 699/699/1124 +f 699/699/1124 455/455/1128 700/700/1126 +f 701/701/1127 458/458/1129 455/455/1128 +f 702/702/1130 458/458/1129 701/701/1127 +f 702/702/1130 703/703/1131 458/458/1129 +f 704/704/1132 703/703/1131 702/702/1130 +f 704/704/1132 453/453/1133 703/703/1131 +f 690/690/1112 453/453/1133 704/704/1132 +f 690/690/1112 454/454/1111 453/453/1133 +f 705/705/1134 410/410/1134 706/706/1134 +f 706/706/1135 410/410/1135 413/413/1135 +f 706/706/1136 413/413/1136 707/707/1136 +f 707/707/1137 413/413/1138 406/406/1139 +f 707/707/1137 406/406/1139 708/708/1140 +f 708/708/1140 406/406/1139 709/709/1141 +f 708/708/1142 709/709/1143 710/710/1144 +f 711/711/1145 712/712/1146 713/713/1147 +f 714/714/1148 713/713/1148 715/715/1148 +f 714/714/1149 715/715/1150 716/716/1151 +f 716/716/1151 715/715/1150 396/396/1152 +f 410/410/1153 705/705/1153 430/430/1153 +f 430/430/1154 705/705/1155 388/388/1156 +f 388/388/1156 705/705/1155 717/717/1157 +f 717/717/1158 718/718/1158 719/719/1158 +f 719/719/1159 718/718/1159 720/720/1159 +f 719/719/1160 720/720/1161 380/380/1162 +f 380/380/1163 720/720/1164 721/721/1165 +f 722/722/1166 721/721/1166 723/723/1166 +f 722/722/1167 723/723/1167 724/724/1167 +f 724/724/1168 723/723/1168 725/725/1168 +f 724/724/1169 725/725/1169 726/726/1169 +f 726/726/1170 725/725/1170 727/727/1170 +f 726/726/1171 727/727/1171 728/728/1171 +f 728/728/1172 727/727/1172 716/716/1172 +f 728/728/1173 716/716/1174 396/396/1175 +f 716/716/1176 729/729/1177 730/730/1178 +f 716/716/1176 730/730/1178 714/714/1179 +f 714/714/1179 730/730/1178 713/713/1180 +f 713/713/1180 730/730/1178 731/731/1181 +f 713/713/1182 731/731/1182 711/711/1182 +f 711/711/1183 731/731/1183 732/732/1183 +f 711/711/1184 732/732/1185 733/733/1186 +f 733/733/1186 732/732/1185 710/710/1187 +f 710/710/1144 732/732/1188 708/708/1142 +f 708/708/1142 732/732/1188 734/734/1189 +f 708/708/1190 734/734/1190 707/707/1190 +f 707/707/1191 734/734/1191 735/735/1191 +f 707/707/1192 735/735/1193 706/706/1194 +f 706/706/1194 735/735/1193 736/736/1195 +f 706/706/1194 736/736/1195 705/705/1196 +f 705/705/1196 736/736/1195 717/717/1197 +f 717/717/1198 736/736/1198 718/718/1198 +f 718/718/1199 736/736/1200 737/737/1201 +f 718/718/1199 737/737/1201 720/720/1202 +f 720/720/1202 737/737/1201 738/738/1203 +f 720/720/1202 738/738/1203 721/721/1204 +f 721/721/1204 738/738/1203 739/739/1205 +f 721/721/1204 739/739/1205 723/723/1206 +f 723/723/1206 739/739/1205 740/740/1207 +f 723/723/1208 740/740/1209 725/725/1210 +f 725/725/1210 740/740/1209 741/741/1211 +f 725/725/1210 741/741/1211 742/742/1212 +f 725/725/1210 742/742/1212 727/727/1213 +f 727/727/1213 742/742/1212 729/729/1177 +f 727/727/1213 729/729/1177 716/716/1176 +f 732/732/1214 731/731/1215 730/730/1214 +f 739/739/1216 738/738/210 740/740/210 +f 734/734/1217 730/730/1214 735/735/210 +f 740/740/210 738/738/210 742/742/1218 +f 730/730/1214 729/729/210 736/736/210 +f 735/735/210 730/730/1214 736/736/210 +f 470/470/1219 542/542/1220 270/270/1221 +f 270/270/1221 542/542/1220 541/541/1222 +f 542/542/1223 470/470/1224 466/466/1225 +f 542/542/1223 466/466/1225 465/465/1226 +f 543/543/1227 271/271/1228 475/475/1229 +f 543/543/1227 475/475/1229 541/541/1230 +f 541/541/1230 475/475/1229 270/270/1231 +f 463/463/1232 462/462/1233 567/567/1234 +f 567/567/1234 462/462/1233 474/474/1235 +f 567/567/1236 474/474/1237 471/471/1238 +f 567/567/1236 471/471/1238 568/568/1239 +f 473/473/845 477/477/844 483/483/855 +f 483/483/855 485/485/857 473/473/845 +f 568/568/1240 471/471/1241 485/485/857 +f 485/485/857 471/471/1241 473/473/845 +f 447/447/1109 559/559/956 540/540/955 +f 539/539/1107 447/447/1109 540/540/955 +f 452/452/825 454/454/827 689/689/1242 +f 689/689/1242 639/639/1243 452/452/825 +f 689/689/1242 640/640/1244 639/639/1243 +f 689/689/1242 617/617/1245 640/640/1244 +f 692/692/1246 617/617/1245 689/689/1242 +f 617/617/1245 692/692/1246 484/484/1247 +f 692/692/1246 694/694/1248 484/484/1247 +f 484/484/1247 694/694/1248 485/485/1249 +f 681/681/1250 485/485/1249 694/694/1248 +f 686/686/1251 542/542/932 465/465/1252 +f 542/542/932 540/540/931 543/543/101 +f 443/443/1253 544/544/933 446/446/1254 +f 544/544/933 535/535/925 743/743/1255 +f 444/444/1256 446/446/1254 743/743/1255 +f 743/743/1255 446/446/1254 544/544/933 +f 535/535/978 569/569/980 743/743/1257 +f 743/743/1257 569/569/980 744/744/1258 +f 743/743/1257 744/744/1258 444/444/1259 +f 444/444/1259 744/744/1258 445/445/818 +f 569/569/980 570/570/981 744/744/1258 +f 744/744/1258 570/570/981 745/745/1260 +f 744/744/1258 745/745/1260 445/445/818 +f 570/570/981 560/560/958 745/745/1260 +f 745/745/1260 447/447/820 445/445/818 +f 745/745/1260 559/559/1261 447/447/820 +f 560/560/958 559/559/1261 745/745/1260 +f 384/384/755 483/483/1262 477/477/844 +f 384/384/755 390/390/762 483/483/1262 +f 390/390/762 384/384/755 383/383/754 +f 407/407/1263 415/415/787 545/545/1264 +f 686/686/1251 463/463/1265 683/683/1266 +f 386/386/1267 478/478/846 479/479/1268 +f 479/479/1268 480/480/849 746/746/1269 +f 746/746/1269 480/480/849 481/481/851 +f 386/386/1267 479/479/1268 426/426/1270 +f 426/426/1270 479/479/1268 746/746/1269 +f 426/426/1270 746/746/1269 427/427/799 +f 427/427/799 746/746/1269 481/481/1271 +f 478/478/846 386/386/1267 477/477/844 +f 477/477/844 386/386/1267 384/384/755 +f 536/536/1272 419/419/791 537/537/1273 +f 415/415/787 419/419/791 536/536/1272 +f 415/415/787 536/536/1272 534/534/1274 +f 545/545/1264 415/415/787 534/534/1274 +f 420/420/792 422/422/1275 558/558/1276 +f 423/423/1277 428/428/1278 555/555/1279 +f 555/555/1279 428/428/1278 554/554/1280 +f 428/428/1278 429/429/801 553/553/1281 +f 533/533/1282 420/420/792 558/558/1276 +f 557/557/953 558/558/1276 422/422/1275 +f 557/557/953 422/422/1275 421/421/1283 +f 557/557/953 421/421/1283 556/556/951 +f 423/423/1277 556/556/951 421/421/1283 +f 556/556/951 423/423/1277 555/555/1279 +f 428/428/1278 553/553/1281 554/554/1280 +f 429/429/801 552/552/1284 553/553/1281 +f 429/429/801 551/551/1285 552/552/1284 +f 427/427/799 551/551/1285 429/429/801 +f 551/551/1285 427/427/799 481/481/1271 +f 418/418/790 420/420/792 546/546/1286 +f 418/418/790 546/546/1286 547/547/1287 +f 548/548/1288 418/418/790 547/547/1287 +f 419/419/791 418/418/790 548/548/1288 +f 419/419/791 548/548/1288 537/537/1273 +f 533/533/1282 546/546/1286 420/420/792 +f 563/563/1289 747/747/1290 564/564/1291 +f 747/747/1290 563/563/1289 748/748/1292 +f 562/562/1293 748/748/1292 563/563/1289 +f 562/562/1293 749/749/1294 748/748/1292 +f 750/750/1295 438/438/1295 440/440/1295 +f 749/749/1294 562/562/1293 751/751/1296 +f 751/751/1296 562/562/1293 565/565/1297 +f 751/751/1296 565/565/1297 752/752/1298 +f 438/438/1299 750/750/1300 565/565/1301 +f 565/565/1301 750/750/1300 752/752/1302 +f 753/753/1303 754/754/1304 755/755/1305 +f 753/753/1303 755/755/1305 756/756/1306 +f 756/756/1306 755/755/1305 757/757/1307 +f 757/757/1307 758/758/1308 756/756/1306 +f 759/759/1309 758/758/1308 757/757/1307 +f 759/759/1309 561/561/961 758/758/1308 +f 436/436/808 549/549/939 561/561/961 +f 561/561/961 759/759/1309 436/436/808 +f 437/437/809 436/436/808 759/759/1309 +f 756/756/1310 758/758/1311 760/760/1312 +f 758/758/1311 564/564/1313 760/760/1312 +f 758/758/1311 561/561/1314 564/564/1313 +f 757/757/1307 761/761/1315 759/759/1309 +f 759/759/1309 440/440/812 437/437/809 +f 761/761/1316 440/440/1317 759/759/1318 +f 753/753/1319 756/756/1310 760/760/1312 +f 753/753/1319 760/760/1312 762/762/1320 +f 762/762/1320 760/760/1312 747/747/1321 +f 747/747/1321 760/760/1312 564/564/1313 +f 750/750/1322 440/440/1317 763/763/1323 +f 755/755/1305 754/754/1304 764/764/1324 +f 763/763/1323 755/755/1305 764/764/1324 +f 755/755/1305 763/763/1323 761/761/1315 +f 755/755/1305 761/761/1315 757/757/1307 +f 763/763/1323 764/764/1324 750/750/1322 +f 761/761/1316 763/763/1323 440/440/1317 +f 753/753/1319 762/762/1320 765/765/1325 +f 753/753/1319 765/765/1325 766/766/1326 +f 762/762/1320 747/747/1321 765/765/1325 +f 765/765/1325 748/748/1327 749/749/1328 +f 765/765/1325 749/749/1328 766/766/1326 +f 747/747/1321 748/748/1327 765/765/1325 +f 752/752/1329 750/750/1322 764/764/1324 +f 764/764/1324 754/754/1304 767/767/1330 +f 752/752/1329 767/767/1330 751/751/1331 +f 767/767/1330 752/752/1329 764/764/1324 +f 749/749/1328 751/751/1331 766/766/1326 +f 766/766/1326 751/751/1331 767/767/1330 +f 766/766/1326 767/767/1330 753/753/1319 +f 753/753/1319 767/767/1330 754/754/1304 +f 768/768/1332 416/416/1333 769/769/1334 +f 769/769/1334 416/416/1333 414/414/1335 +f 770/770/1336 432/432/1337 771/771/1338 +f 770/770/1336 771/771/1338 772/772/1339 +f 772/772/1339 771/771/1338 417/417/1340 +f 772/772/1341 417/417/1342 768/768/1343 +f 768/768/1343 417/417/1342 416/416/1344 +f 773/773/1345 424/424/1346 433/433/1347 +f 773/773/1345 433/433/1347 774/774/1348 +f 774/774/1348 433/433/1347 434/434/1349 +f 774/774/1348 434/434/1349 770/770/1350 +f 770/770/1350 434/434/1349 432/432/1351 +f 775/775/1352 425/425/1353 776/776/1354 +f 775/775/1352 776/776/1354 773/773/1355 +f 773/773/1355 776/776/1354 424/424/1356 +f 777/777/1357 385/385/1358 425/425/1359 +f 777/777/1357 425/425/1359 775/775/1360 +f 778/778/1361 779/779/1362 381/381/1363 +f 778/778/1364 381/381/1365 777/777/1366 +f 777/777/1366 381/381/1365 385/385/1367 +f 780/780/1368 411/411/1369 431/431/1370 +f 780/780/1368 431/431/1370 781/781/1371 +f 781/781/1371 431/431/1370 387/387/1372 +f 781/781/1371 387/387/1372 782/782/1373 +f 782/782/1373 387/387/1372 779/779/1362 +f 782/782/1373 779/779/1362 778/778/1361 +f 769/769/1374 414/414/1375 412/412/1376 +f 769/769/1374 412/412/1376 780/780/1377 +f 780/780/1377 412/412/1376 411/411/1378 +f 769/769/210 770/770/210 768/768/210 +f 777/777/210 782/782/210 778/778/210 +f 781/781/210 774/774/210 780/780/210 +f 770/770/210 769/769/210 780/780/210 +f 774/774/210 781/781/210 782/782/210 +f 774/774/210 782/782/210 773/773/210 +f 773/773/210 782/782/210 777/777/210 +f 773/773/210 777/777/210 775/775/210 +f 770/770/210 780/780/210 774/774/210 +f 770/770/210 772/772/210 768/768/210 +f 387/387/759 382/382/758 779/779/1379 +f 779/779/1362 382/382/1380 381/381/1363 +f 771/771/1381 432/432/1381 417/417/1381 +f 776/776/1382 425/425/1382 424/424/1382 +f 683/683/1383 684/684/1383 686/686/1383 +f 388/388/1156 717/717/1157 382/382/1384 +f 717/717/1385 719/719/1385 382/382/1385 +f 382/382/1386 719/719/1160 380/380/1162 +f 380/380/1163 721/721/1165 383/383/1387 +f 721/721/1388 722/722/1388 383/383/1388 +f 383/383/1389 722/722/1389 389/389/1389 +f 722/722/1390 724/724/1390 389/389/1390 +f 389/389/1391 724/724/1391 393/393/1391 +f 724/724/1392 726/726/1392 393/393/1392 +f 393/393/1393 726/726/1393 394/394/1393 +f 726/726/1394 728/728/1394 394/394/1394 +f 394/394/1395 728/728/1173 396/396/1175 +f 396/396/1152 715/715/1150 398/398/1396 +f 715/715/1397 713/713/1397 398/398/1397 +f 398/398/1398 713/713/1398 402/402/1398 +f 713/713/1147 712/712/1146 402/402/1399 +f 712/712/1146 711/711/1145 402/402/1399 +f 402/402/1400 711/711/1401 408/408/1402 +f 408/408/1402 711/711/1401 733/733/1403 +f 733/733/1403 710/710/1404 408/408/1402 +f 408/408/1405 710/710/1405 405/405/1405 +f 710/710/1406 709/709/1406 405/405/1406 +f 405/405/1407 709/709/1141 406/406/1139 +f 441/441/1408 696/696/1408 448/448/1408 +f 457/457/1409 700/700/1409 455/455/1409 +f 458/458/1410 703/703/1411 449/449/1412 +f 703/703/1411 453/453/1413 449/449/1412 +f 734/734/1217 732/732/1214 730/730/1214 +f 736/736/210 729/729/210 742/742/1218 +f 737/737/1218 736/736/210 742/742/1218 +f 741/741/1414 740/740/210 742/742/1218 +f 738/738/210 737/737/1218 742/742/1218 +f 691/691/101 682/682/101 678/678/101 +f 695/695/101 701/701/101 697/697/101 +f 701/701/101 698/698/101 697/697/101 +f 701/701/101 695/695/101 702/702/101 +f 702/702/101 695/695/101 688/688/101 +f 698/698/101 701/701/101 699/699/101 +f 702/702/101 688/688/101 687/687/101 +f 702/702/101 687/687/101 704/704/101 +f 682/682/101 690/690/101 685/685/101 +f 704/704/101 687/687/101 685/685/101 +f 704/704/101 685/685/101 690/690/101 +f 690/690/101 682/682/101 691/691/101 +f 691/691/101 678/678/101 693/693/101 +f 693/693/101 678/678/101 680/680/101 +f 679/679/1415 568/568/976 485/485/1249 +f 686/686/1251 538/538/929 542/542/932 +f 545/545/934 544/544/933 407/407/1416 +f 566/566/974 683/683/1266 463/463/1265 +f 544/544/933 443/443/1417 407/407/1416 +f 566/566/974 463/463/1265 567/567/975 +f 568/568/976 679/679/1415 566/566/974 +f 681/681/1250 679/679/1415 485/485/1249 +f 686/686/1251 465/465/1252 463/463/1265 +f 419/419/791 415/415/787 420/420/792 +f 417/417/789 420/420/792 415/415/787 +f 783/783/1418 784/784/1419 785/785/1420 +f 786/786/1421 787/787/1422 788/788/1423 +f 788/788/1423 787/787/1422 789/789/1424 +f 788/788/1423 789/789/1424 790/790/1425 +f 790/790/1425 789/789/1424 791/791/1426 +f 791/791/1426 789/789/1424 792/792/1427 +f 791/791/1426 792/792/1427 785/785/1420 +f 793/793/1428 783/783/1418 792/792/1427 +f 792/792/1427 783/783/1418 785/785/1420 +f 793/793/1428 794/794/1429 783/783/1418 +f 795/795/1430 796/796/1431 797/797/1432 +f 798/798/1433 799/799/1434 800/800/1435 +f 798/798/1433 800/800/1435 795/795/1430 +f 795/795/1430 800/800/1435 796/796/1431 +f 799/799/1434 798/798/1433 801/801/1436 +f 799/799/1434 801/801/1436 802/802/1437 +f 802/802/1437 801/801/1436 803/803/1438 +f 802/802/1437 803/803/1438 804/804/1439 +f 804/804/1439 803/803/1438 805/805/1440 +f 805/805/1440 803/803/1438 806/806/1441 +f 805/805/1440 806/806/1441 807/807/1442 +f 805/805/1440 807/807/1442 808/808/1443 +f 808/808/1443 807/807/1442 809/809/1444 +f 808/808/1443 809/809/1444 810/810/1445 +f 810/810/1445 809/809/1444 811/811/1446 +f 810/810/1445 811/811/1446 812/812/1447 +f 812/812/1447 811/811/1446 813/813/1448 +f 813/813/1448 811/811/1446 814/814/1449 +f 814/814/1449 811/811/1446 786/786/1421 +f 786/786/1421 811/811/1446 787/787/1422 +f 815/815/1450 816/816/1451 817/817/1452 +f 817/817/1452 816/816/1451 818/818/1453 +f 797/797/1432 796/796/1431 819/819/1454 +f 819/819/1454 796/796/1431 820/820/1455 +f 821/821/1456 817/817/1452 818/818/1453 +f 821/821/1456 818/818/1453 822/822/1457 +f 821/821/1456 822/822/1457 823/823/1458 +f 817/817/1452 821/821/1456 819/819/1454 +f 819/819/1454 821/821/1456 797/797/1432 +f 822/822/1457 824/824/1459 825/825/1460 +f 826/826/1461 823/823/1458 825/825/1460 +f 825/825/1460 823/823/1458 822/822/1457 +f 827/827/1462 828/828/1463 823/823/1458 +f 827/827/1462 823/823/1458 829/829/1464 +f 830/830/1465 828/828/1463 827/827/1462 +f 831/831/1466 828/828/1463 830/830/1465 +f 832/832/1467 833/833/1468 831/831/1466 +f 831/831/1466 833/833/1468 828/828/1463 +f 834/834/1469 835/835/1470 836/836/1471 +f 836/836/1471 835/835/1470 833/833/1468 +f 836/836/1471 833/833/1468 832/832/1467 +f 837/837/1472 793/793/1428 834/834/1469 +f 834/834/1469 793/793/1428 835/835/1470 +f 794/794/1429 793/793/1428 837/837/1472 +f 838/838/101 839/839/101 840/840/101 +f 839/839/101 841/841/101 840/840/101 +f 842/842/101 785/785/101 841/841/101 +f 841/841/101 785/785/101 840/840/101 +f 791/791/101 785/785/101 842/842/101 +f 843/843/1473 844/844/1474 845/845/1475 +f 846/846/1476 847/847/1477 848/848/1478 +f 849/849/1479 846/846/1476 850/850/1480 +f 851/851/101 852/852/101 843/843/1473 +f 814/814/1481 853/853/1482 810/810/1483 +f 854/854/1484 794/794/1429 837/837/1472 +f 855/855/1485 856/856/1486 857/857/1487 +f 857/857/1487 856/856/1486 794/794/1429 +f 857/857/1487 794/794/1429 854/854/1484 +f 858/858/1488 856/856/1486 855/855/1485 +f 858/858/1488 859/859/1489 856/856/1486 +f 860/860/1490 859/859/1489 858/858/1488 +f 861/861/1491 843/843/1492 862/862/1493 +f 862/862/1493 843/843/1492 863/863/1494 +f 863/863/1494 843/843/1492 864/864/1495 +f 863/863/1494 864/864/1495 860/860/1490 +f 860/860/1490 864/864/1495 859/859/1489 +f 861/861/1491 865/865/1496 843/843/1492 +f 865/865/1496 861/861/1491 866/866/1497 +f 865/865/1496 866/866/1497 867/867/1498 +f 867/867/1498 866/866/1497 868/868/1499 +f 867/867/1498 868/868/1499 869/869/1500 +f 869/869/1500 868/868/1499 870/870/1501 +f 871/871/210 835/835/210 872/872/210 +f 793/793/210 792/792/210 835/835/210 +f 835/835/210 792/792/210 872/872/210 +f 797/797/210 787/787/210 811/811/210 +f 797/797/210 821/821/210 873/873/210 +f 871/871/210 874/874/210 833/833/210 +f 789/789/210 875/875/210 876/876/210 +f 789/789/210 787/787/210 875/875/210 +f 877/877/1502 869/869/1500 870/870/1501 +f 877/877/1502 878/878/1503 869/869/1500 +f 879/879/210 872/872/210 792/792/210 +f 880/880/1504 881/881/1505 878/878/1503 +f 880/880/1504 878/878/1503 877/877/1502 +f 829/829/1464 881/881/1505 880/880/1504 +f 823/823/1458 826/826/1461 829/829/1464 +f 829/829/1464 826/826/1461 882/882/1506 +f 829/829/1464 882/882/1506 881/881/1505 +f 869/869/101 865/865/101 867/867/101 +f 881/881/101 882/882/1507 869/869/101 +f 882/882/1507 865/865/101 869/869/101 +f 883/883/1508 884/884/1509 885/885/1510 +f 882/882/1507 843/843/1473 865/865/101 +f 886/886/101 887/887/1479 888/888/1511 +f 889/889/1512 890/890/1513 891/891/101 +f 824/824/101 843/843/1473 825/825/1514 +f 892/892/101 843/843/1473 824/824/101 +f 893/893/101 843/843/1473 892/892/101 +f 851/851/101 843/843/1473 893/893/101 +f 894/894/841 895/895/1515 884/884/1509 +f 843/843/1473 852/852/101 896/896/101 +f 843/843/1473 896/896/101 897/897/101 +f 843/843/1473 897/897/101 898/898/101 +f 843/843/1473 898/898/101 899/899/1516 +f 843/843/1473 899/899/1516 900/900/1517 +f 901/901/101 902/902/101 783/783/101 +f 903/903/101 816/816/101 904/904/101 +f 904/904/101 816/816/101 905/905/101 +f 905/905/101 816/816/101 906/906/101 +f 906/906/101 816/816/101 907/907/101 +f 907/907/101 816/816/101 908/908/101 +f 908/908/101 816/816/101 909/909/101 +f 884/884/1509 910/910/1518 885/885/1510 +f 909/909/101 816/816/101 911/911/101 +f 859/859/841 846/846/1476 849/849/1479 +f 911/911/101 816/816/101 912/912/101 +f 912/912/101 816/816/101 815/815/101 +f 912/912/101 815/815/101 891/891/101 +f 843/843/1473 900/900/1517 844/844/1474 +f 891/891/101 815/815/101 913/913/101 +f 891/891/101 913/913/101 914/914/101 +f 891/891/101 914/914/101 915/915/1519 +f 915/915/1519 889/889/1512 891/891/101 +f 916/916/1520 917/917/1521 847/847/1477 +f 917/917/1521 918/918/1522 847/847/1477 +f 919/919/1523 920/920/101 921/921/101 +f 890/890/1513 922/922/101 891/891/101 +f 888/888/1511 887/887/1479 916/916/1520 +f 922/922/101 923/923/101 891/891/101 +f 923/923/101 924/924/101 891/891/101 +f 924/924/101 925/925/101 891/891/101 +f 926/926/101 927/927/101 925/925/101 +f 925/925/101 928/928/101 926/926/101 +f 928/928/101 929/929/101 926/926/101 +f 921/921/101 920/920/101 930/930/101 +f 928/928/101 883/883/1508 929/929/101 +f 884/884/1509 919/919/1523 910/910/1518 +f 853/853/1482 805/805/1524 808/808/1525 +f 864/864/1526 846/846/1476 859/859/841 +f 931/931/1527 847/847/1477 918/918/1522 +f 825/825/1514 843/843/1473 826/826/1528 +f 932/932/101 919/919/1523 921/921/101 +f 925/925/101 927/927/101 891/891/101 +f 933/933/1529 820/820/1530 934/934/1531 +f 935/935/101 936/936/101 783/783/101 +f 843/843/1473 846/846/1476 864/864/1526 +f 930/930/101 886/886/101 888/888/1511 +f 937/937/1532 894/894/841 884/884/1509 +f 938/938/101 934/934/1531 796/796/101 +f 939/939/101 938/938/101 796/796/101 +f 940/940/101 939/939/101 796/796/101 +f 853/853/1482 940/940/101 796/796/101 +f 887/887/1479 917/917/1521 916/916/1520 +f 853/853/1482 786/786/1533 788/788/1534 +f 799/799/101 853/853/1482 800/800/101 +f 853/853/1482 799/799/101 802/802/101 +f 850/850/1480 846/846/1476 848/848/1478 +f 920/920/101 886/886/101 930/930/101 +f 941/941/1535 919/919/1523 884/884/1509 +f 849/849/1479 794/794/101 859/859/841 +f 794/794/101 856/856/101 859/859/841 +f 910/910/1518 919/919/1523 932/932/101 +f 849/849/1479 942/942/101 794/794/101 +f 942/942/101 943/943/101 783/783/101 +f 869/869/101 878/878/101 881/881/101 +f 944/944/101 783/783/101 945/945/101 +f 843/843/1473 845/845/1475 846/846/1476 +f 794/794/101 942/942/101 783/783/101 +f 946/946/101 947/947/101 783/783/101 +f 947/947/101 948/948/101 783/783/101 +f 944/944/101 946/946/101 783/783/101 +f 948/948/101 901/901/101 783/783/101 +f 894/894/841 937/937/1532 949/949/101 +f 943/943/101 945/945/101 783/783/101 +f 936/936/101 950/950/101 783/783/101 +f 902/902/101 935/935/101 783/783/101 +f 783/783/101 950/950/101 951/951/101 +f 949/949/101 952/952/101 953/953/101 +f 783/783/101 951/951/101 954/954/101 +f 783/783/101 954/954/101 784/784/101 +f 784/784/101 954/954/101 955/955/101 +f 784/784/101 955/955/101 956/956/1536 +f 941/941/1535 884/884/1509 895/895/1515 +f 952/952/101 957/957/101 953/953/101 +f 958/958/101 957/957/101 959/959/101 +f 959/959/101 957/957/101 960/960/101 +f 960/960/101 957/957/101 961/961/101 +f 961/961/101 957/957/101 962/962/101 +f 962/962/101 957/957/101 963/963/101 +f 963/963/101 957/957/101 964/964/101 +f 964/964/101 957/957/101 965/965/101 +f 965/965/101 957/957/101 966/966/101 +f 966/966/101 957/957/101 967/967/101 +f 967/967/101 957/957/101 790/790/101 +f 790/790/101 957/957/101 788/788/1534 +f 934/934/1531 820/820/1530 796/796/101 +f 853/853/1482 796/796/101 800/800/101 +f 957/957/101 853/853/1482 788/788/1534 +f 853/853/1482 802/802/101 804/804/101 +f 786/786/1533 853/853/1482 814/814/1481 +f 814/814/1481 810/810/1483 812/812/1537 +f 853/853/1482 804/804/101 805/805/1524 +f 882/882/1507 826/826/1528 843/843/1473 +f 813/813/101 814/814/1481 812/812/1537 +f 937/937/1532 952/952/101 949/949/101 +f 848/848/1478 847/847/1477 931/931/1527 +f 883/883/1508 885/885/1510 929/929/101 +f 810/810/1483 853/853/1482 808/808/1525 +f 957/957/101 958/958/101 953/953/101 +f 857/857/1538 854/854/1539 834/834/1540 +f 868/868/1541 877/877/1542 870/870/1543 +f 868/868/1541 880/880/1544 877/877/1542 +f 880/880/1544 868/868/1541 861/861/1545 +f 861/861/1545 862/862/1546 880/880/1544 +f 880/880/1544 862/862/1546 829/829/1547 +f 862/862/1546 827/827/1548 829/829/1547 +f 840/840/1549 947/947/1550 946/946/1551 +f 840/840/1549 946/946/1551 944/944/1552 +f 840/840/1549 944/944/1552 945/945/1553 +f 840/840/1549 945/945/1553 943/943/1554 +f 840/840/1549 943/943/1554 838/838/1555 +f 838/838/1555 943/943/1554 942/942/1556 +f 838/838/1555 942/942/1556 849/849/1557 +f 838/838/1555 849/849/1557 850/850/1558 +f 838/838/1555 850/850/1558 848/848/1559 +f 848/848/1559 931/931/1560 838/838/1555 +f 838/838/1555 931/931/1560 918/918/1561 +f 838/838/1555 918/918/1561 917/917/1562 +f 838/838/1555 917/917/1562 839/839/1563 +f 839/839/1563 917/917/1562 887/887/1564 +f 839/839/1563 887/887/1564 886/886/1565 +f 839/839/1563 886/886/1565 920/920/1566 +f 839/839/1563 920/920/1566 841/841/1567 +f 841/841/1567 920/920/1566 919/919/1568 +f 841/841/1567 919/919/1568 941/941/1569 +f 841/841/1567 941/941/1569 895/895/1570 +f 841/841/1567 895/895/1570 894/894/1571 +f 841/841/1567 894/894/1571 949/949/1572 +f 841/841/1567 949/949/1572 953/953/1573 +f 841/841/1567 953/953/1573 842/842/1574 +f 842/842/1574 953/953/1573 958/958/1575 +f 968/968/1576 909/909/1577 969/969/1578 +f 969/969/1578 909/909/1577 911/911/1579 +f 969/969/1578 911/911/1579 912/912/1580 +f 912/912/1580 891/891/1581 969/969/1578 +f 969/969/1578 891/891/1581 927/927/1582 +f 969/969/1578 927/927/1582 926/926/1583 +f 969/969/1584 926/926/1585 929/929/1586 +f 969/969/1584 929/929/1586 970/970/1587 +f 970/970/1587 929/929/1586 885/885/1588 +f 885/885/1588 910/910/1589 970/970/1587 +f 970/970/1587 910/910/1589 932/932/1590 +f 970/970/1587 932/932/1590 921/921/1591 +f 970/970/1587 921/921/1591 930/930/1592 +f 970/970/1587 930/930/1592 971/971/1593 +f 971/971/1593 930/930/1592 888/888/1594 +f 971/971/1593 888/888/1594 916/916/1595 +f 916/916/1595 847/847/1596 971/971/1593 +f 971/971/1593 847/847/1596 972/972/1597 +f 972/972/1597 847/847/1596 846/846/1598 +f 972/972/1597 846/846/1598 845/845/1599 +f 972/972/1597 845/845/1599 844/844/1600 +f 972/972/1597 844/844/1600 900/900/1601 +f 972/972/1597 900/900/1601 973/973/1602 +f 974/974/1603 933/933/1604 975/975/1605 +f 975/975/1605 933/933/1604 934/934/1606 +f 975/975/1605 934/934/1606 938/938/1607 +f 975/975/1605 938/938/1607 939/939/1608 +f 975/975/1605 939/939/1608 976/976/1609 +f 976/976/1609 939/939/1608 940/940/1610 +f 976/976/1609 940/940/1610 853/853/1611 +f 976/976/1609 853/853/1611 957/957/1612 +f 976/976/1609 957/957/1612 952/952/1613 +f 976/976/1609 952/952/1613 937/937/1614 +f 937/937/1614 884/884/1615 976/976/1609 +f 976/976/1609 884/884/1615 977/977/1616 +f 977/977/1616 884/884/1615 883/883/1617 +f 977/977/1616 883/883/1617 928/928/1618 +f 977/977/1619 928/928/1620 925/925/1621 +f 977/977/1619 925/925/1621 924/924/1622 +f 977/977/1619 924/924/1622 923/923/1623 +f 977/977/1619 923/923/1623 922/922/1624 +f 977/977/1619 922/922/1624 978/978/1625 +f 978/978/1625 922/922/1624 890/890/1626 +f 785/785/1420 784/784/1419 956/956/1627 +f 785/785/1420 956/956/1627 955/955/1628 +f 785/785/1420 955/955/1628 954/954/1629 +f 785/785/1420 954/954/1629 951/951/1630 +f 785/785/1420 951/951/1630 950/950/1631 +f 785/785/1420 950/950/1631 936/936/1632 +f 785/785/1420 936/936/1632 935/935/1633 +f 785/785/1420 935/935/1633 840/840/1549 +f 840/840/1549 935/935/1633 902/902/1634 +f 840/840/1549 902/902/1634 901/901/1635 +f 840/840/1549 901/901/1635 948/948/1636 +f 840/840/1549 948/948/1636 947/947/1550 +f 790/790/1425 791/791/1426 967/967/1637 +f 967/967/1637 791/791/1426 966/966/1638 +f 966/966/1638 791/791/1426 965/965/1639 +f 965/965/1639 791/791/1426 964/964/1640 +f 964/964/1640 791/791/1426 963/963/1641 +f 963/963/1641 791/791/1426 962/962/1642 +f 962/962/1642 791/791/1426 842/842/1574 +f 962/962/1642 842/842/1574 961/961/1643 +f 961/961/1643 842/842/1574 960/960/1644 +f 960/960/1644 842/842/1574 959/959/1645 +f 959/959/1645 842/842/1574 958/958/1575 +f 824/824/1459 822/822/1457 892/892/1646 +f 892/892/1646 822/822/1457 893/893/1647 +f 893/893/1647 822/822/1457 851/851/1648 +f 851/851/1648 822/822/1457 973/973/1602 +f 851/851/1648 973/973/1602 852/852/1649 +f 852/852/1649 973/973/1602 896/896/1650 +f 896/896/1650 973/973/1602 897/897/1651 +f 897/897/1651 973/973/1602 898/898/1652 +f 898/898/1652 973/973/1602 899/899/1653 +f 899/899/1653 973/973/1602 900/900/1601 +f 818/818/1453 816/816/1451 903/903/1654 +f 818/818/1453 903/903/1654 904/904/1655 +f 818/818/1453 904/904/1655 905/905/1656 +f 818/818/1453 905/905/1656 968/968/1576 +f 968/968/1576 905/905/1656 906/906/1657 +f 968/968/1576 906/906/1657 907/907/1658 +f 968/968/1576 907/907/1658 908/908/1659 +f 968/968/1576 908/908/1659 909/909/1577 +f 819/819/1660 820/820/1661 974/974/1603 +f 974/974/1603 820/820/1661 933/933/1604 +f 978/978/1625 890/890/1626 889/889/1662 +f 978/978/1663 889/889/1664 915/915/1665 +f 978/978/1663 915/915/1665 817/817/1452 +f 915/915/1665 914/914/1666 817/817/1452 +f 817/817/1452 914/914/1666 913/913/1667 +f 817/817/1452 913/913/1667 815/815/1450 +f 979/979/1668 980/980/1669 981/981/1670 +f 979/979/1668 981/981/1670 982/982/1671 +f 982/982/1671 981/981/1670 983/983/1672 +f 982/982/1673 983/983/1674 984/984/1675 +f 984/984/1675 983/983/1674 985/985/1676 +f 985/985/1677 874/874/1678 984/984/1679 +f 984/984/1679 874/874/1678 986/986/1680 +f 986/986/1680 874/874/1678 871/871/1681 +f 986/986/1680 871/871/1681 987/987/1682 +f 987/987/1683 871/871/1684 988/988/1685 +f 988/988/1685 871/871/1684 872/872/1686 +f 988/988/1685 872/872/1686 879/879/1687 +f 988/988/1685 879/879/1687 989/989/1688 +f 989/989/1689 879/879/1690 876/876/1691 +f 989/989/1689 876/876/1691 990/990/1692 +f 990/990/1693 876/876/1694 875/875/1695 +f 990/990/1693 875/875/1695 991/991/1696 +f 875/875/1697 992/992/1698 991/991/1699 +f 991/991/1699 992/992/1698 993/993/1700 +f 993/993/1700 992/992/1698 994/994/1701 +f 993/993/1700 994/994/1701 995/995/1702 +f 995/995/1703 994/994/1704 873/873/1705 +f 995/995/1703 873/873/1705 996/996/1706 +f 996/996/1706 873/873/1705 997/997/1707 +f 996/996/1708 997/997/1709 979/979/1710 +f 979/979/1710 997/997/1709 980/980/1711 +f 979/979/210 988/988/210 993/993/210 +f 988/988/210 979/979/210 987/987/210 +f 993/993/210 989/989/210 991/991/210 +f 991/991/210 989/989/210 990/990/210 +f 993/993/210 995/995/210 979/979/210 +f 988/988/210 989/989/210 993/993/210 +f 979/979/210 995/995/210 996/996/210 +f 986/986/210 987/987/210 979/979/210 +f 979/979/210 982/982/210 986/986/210 +f 982/982/210 984/984/210 986/986/210 +f 866/866/1712 861/861/1545 868/868/1541 +f 837/837/1713 834/834/1540 854/854/1539 +f 806/806/210 809/809/210 807/807/210 +f 797/797/210 809/809/210 806/806/210 +f 797/797/210 806/806/210 803/803/210 +f 809/809/210 797/797/210 811/811/210 +f 798/798/210 797/797/210 801/801/210 +f 798/798/210 795/795/210 797/797/210 +f 994/994/210 992/992/210 797/797/210 +f 968/968/101 973/973/101 822/822/101 +f 818/818/101 968/968/101 822/822/101 +f 968/968/101 969/969/101 972/972/101 +f 968/968/101 972/972/101 973/973/101 +f 972/972/101 969/969/101 971/971/101 +f 971/971/101 969/969/101 970/970/101 +f 978/978/101 817/817/101 819/819/101 +f 974/974/101 975/975/101 978/978/101 +f 975/975/101 977/977/101 978/978/101 +f 978/978/101 819/819/101 974/974/101 +f 976/976/101 977/977/101 975/975/101 +f 862/862/1546 863/863/1714 827/827/1548 +f 827/827/1548 863/863/1714 830/830/1715 +f 863/863/1714 860/860/1716 830/830/1715 +f 860/860/1716 831/831/1717 830/830/1715 +f 860/860/1716 858/858/1718 831/831/1717 +f 858/858/1718 832/832/1719 831/831/1717 +f 858/858/1718 855/855/1720 832/832/1719 +f 855/855/1720 836/836/1721 832/832/1719 +f 836/836/1721 855/855/1720 857/857/1538 +f 857/857/1538 834/834/1540 836/836/1721 +f 821/821/210 823/823/210 828/828/210 +f 828/828/210 983/983/210 821/821/210 +f 879/879/210 792/792/210 789/789/210 +f 983/983/210 981/981/210 821/821/210 +f 985/985/210 983/983/210 828/828/210 +f 821/821/210 981/981/210 980/980/210 +f 821/821/210 980/980/210 997/997/210 +f 821/821/210 997/997/210 873/873/210 +f 789/789/210 876/876/210 879/879/210 +f 985/985/210 828/828/210 874/874/210 +f 833/833/210 835/835/210 871/871/210 +f 873/873/210 994/994/210 797/797/210 +f 801/801/210 797/797/210 803/803/210 +f 828/828/210 833/833/210 874/874/210 +f 875/875/210 787/787/210 992/992/210 +f 787/787/210 797/797/210 992/992/210 +f 998/998/1722 890/890/1723 999/999/1724 +f 999/999/1724 890/890/1723 922/922/1725 +f 999/999/1724 922/922/1725 923/923/1726 +f 1000/1000/1727 999/999/1724 924/924/1728 +f 924/924/1728 999/999/1724 923/923/1726 +f 1000/1000/1729 928/928/1730 1001/1001/1731 +f 1001/1001/1731 928/928/1730 883/883/1732 +f 1002/1002/1733 937/937/1734 952/952/1735 +f 952/952/1735 1003/1003/1736 1002/1002/1733 +f 1003/1003/1737 853/853/1738 940/940/1739 +f 1003/1003/1737 940/940/1739 1004/1004/1740 +f 934/934/1741 1004/1004/1742 938/938/1743 +f 1004/1004/1742 934/934/1741 1005/1005/1744 +f 1006/1006/1745 913/913/1746 914/914/1747 +f 1006/1006/1745 914/914/1747 1007/1007/1748 +f 1006/1006/1745 1007/1007/1748 915/915/1749 +f 908/908/1750 1008/1008/1751 1009/1009/1752 +f 1009/1009/1752 1008/1008/1751 907/907/1753 +f 1009/1009/1752 907/907/1753 906/906/1754 +f 1009/1009/1752 906/906/1754 1010/1010/1755 +f 1010/1010/1756 904/904/1757 903/903/1758 +f 1010/1010/1756 903/903/1758 1011/1011/1759 +f 1012/1012/1760 888/888/1760 930/930/1760 +f 910/910/1761 1012/1012/1762 932/932/1763 +f 885/885/1764 1013/1013/1765 910/910/1761 +f 910/910/1761 1013/1013/1765 1012/1012/1762 +f 1014/1014/1766 1013/1013/1767 926/926/1768 +f 1014/1014/1766 926/926/1768 927/927/1769 +f 1014/1014/1766 927/927/1769 891/891/1770 +f 1014/1014/1766 891/891/1770 912/912/1771 +f 1014/1014/1766 912/912/1771 1015/1015/1772 +f 1015/1015/1772 912/912/1771 911/911/1773 +f 911/911/1773 908/908/1750 1015/1015/1772 +f 1016/1016/1774 824/824/1775 892/892/1776 +f 1016/1016/1774 892/892/1776 893/893/1777 +f 1016/1016/1774 893/893/1777 851/851/1778 +f 1016/1016/1774 851/851/1778 852/852/1779 +f 1016/1016/1774 852/852/1779 896/896/1780 +f 1016/1016/1774 896/896/1780 1017/1017/1781 +f 1017/1017/1781 898/898/1782 1018/1018/1783 +f 1018/1018/1783 898/898/1782 899/899/1784 +f 1019/1019/1785 826/826/1786 824/824/1775 +f 1019/1019/1785 824/824/1775 1016/1016/1774 +f 1020/1020/1787 1021/1021/1787 1022/1022/1787 +f 1023/1023/1788 1024/1024/1789 1025/1025/1790 +f 1026/1026/1791 1027/1027/1791 1023/1023/1791 +f 1028/1028/1792 1029/1029/1792 1030/1030/1792 +f 1031/1031/1793 1032/1032/1793 1033/1033/1793 +f 1033/1033/1794 1034/1034/1795 1031/1031/1796 +f 1035/1035/1797 1034/1034/1797 1033/1033/1797 +f 1036/1036/1798 1037/1037/1799 1038/1038/1800 +f 1036/1036/1798 1038/1038/1800 1039/1039/1801 +f 1040/1040/1802 1036/1036/1802 1041/1041/1802 +f 1042/1042/1803 1043/1043/1803 826/826/1803 +f 1044/1044/1804 784/784/1805 1045/1045/1806 +f 1046/1046/1807 947/947/1808 948/948/1809 +f 1046/1046/1810 901/901/1811 902/902/1812 +f 1046/1046/1810 902/902/1812 1047/1047/1813 +f 1047/1047/1813 902/902/1812 935/935/1814 +f 1047/1047/1813 935/935/1814 936/936/1815 +f 1047/1047/1813 936/936/1815 950/950/1816 +f 1047/1047/1817 950/950/1817 1048/1048/1817 +f 1048/1048/1818 954/954/1819 1044/1044/1804 +f 1044/1044/1804 954/954/1819 955/955/1820 +f 1044/1044/1804 955/955/1820 956/956/1821 +f 1044/1044/1804 956/956/1821 784/784/1805 +f 1049/1049/1822 958/958/1823 1050/1050/1824 +f 894/894/1825 1051/1051/1826 949/949/1827 +f 949/949/1827 1051/1051/1826 1050/1050/1828 +f 1051/1051/1829 895/895/1830 941/941/1831 +f 1051/1051/1829 941/941/1831 1052/1052/1832 +f 1052/1052/1833 920/920/1834 1053/1053/1835 +f 1053/1053/1835 920/920/1834 886/886/1836 +f 1053/1053/1835 886/886/1836 887/887/1837 +f 887/887/1837 1054/1054/1838 1053/1053/1835 +f 1054/1054/1839 918/918/1840 1055/1055/1841 +f 1055/1055/1841 918/918/1840 931/931/1842 +f 850/850/1843 1056/1056/1844 848/848/1845 +f 1056/1056/1846 1055/1055/1846 848/848/1846 +f 848/848/1847 1055/1055/1841 931/931/1842 +f 1056/1056/1844 850/850/1843 849/849/1848 +f 1056/1056/1844 849/849/1848 942/942/1849 +f 945/945/1850 1056/1056/1844 943/943/1851 +f 943/943/1851 1056/1056/1844 942/942/1849 +f 1056/1056/1844 945/945/1850 1057/1057/1852 +f 1057/1057/1852 945/945/1850 944/944/1853 +f 947/947/1808 1046/1046/1807 1057/1057/1854 +f 1058/1058/1855 1059/1059/1856 967/967/1857 +f 1058/1058/1855 967/967/1857 966/966/1858 +f 1058/1058/1855 966/966/1858 965/965/1859 +f 1058/1058/1855 965/965/1859 1060/1060/1860 +f 1060/1060/1860 963/963/1861 962/962/1862 +f 1060/1060/1860 962/962/1862 961/961/1863 +f 1060/1060/1860 961/961/1863 1049/1049/1864 +f 1049/1049/1822 959/959/1865 958/958/1823 +f 1061/1061/1866 1062/1062/1867 1059/1059/1856 +f 1063/1063/1868 1064/1064/1869 1065/1065/1870 +f 1066/1066/1871 1067/1067/1871 1068/1068/1871 +f 1069/1069/1872 1066/1066/1872 1070/1070/1872 +f 1071/1071/1873 1072/1072/1874 1070/1070/1875 +f 810/810/1876 1073/1073/1877 1074/1074/1878 +f 1073/1073/1879 812/812/1880 1075/1075/1881 +f 1075/1075/1881 812/812/1880 813/813/1882 +f 1075/1075/1881 813/813/1882 786/786/1883 +f 1076/1076/1884 1064/1064/1884 1077/1077/1884 +f 1078/1078/1885 938/938/1885 1004/1004/1885 +f 1079/1079/1886 933/933/1887 1078/1078/1888 +f 1078/1078/1888 933/933/1887 1005/1005/1889 +f 1078/1078/1888 1005/1005/1889 934/934/1890 +f 1078/1078/1888 934/934/1890 938/938/1891 +f 933/933/1887 1079/1079/1886 1076/1076/1892 +f 853/853/1738 1003/1003/1737 1080/1080/1893 +f 1080/1080/1894 1003/1003/1894 952/952/1894 +f 1080/1080/210 952/952/210 937/937/210 +f 1080/1080/1895 1081/1081/1896 853/853/1897 +f 853/853/1897 1081/1081/1896 1078/1078/1898 +f 853/853/1897 1078/1078/1898 940/940/1899 +f 940/940/1739 1078/1078/1900 1004/1004/1740 +f 1082/1082/1901 1083/1083/1902 1070/1070/1903 +f 1084/1084/1904 1082/1082/1901 1064/1064/1905 +f 1079/1079/1886 1084/1084/1904 1076/1076/1892 +f 1076/1076/1892 1084/1084/1904 1064/1064/1905 +f 1085/1085/1906 1065/1065/1907 1064/1064/1905 +f 1070/1070/1903 1086/1086/1908 1087/1087/1909 +f 1070/1070/1903 1087/1087/1909 1064/1064/1905 +f 1088/1088/1910 1089/1089/1911 1090/1090/1912 +f 1090/1090/1912 1086/1086/1908 1070/1070/1903 +f 1091/1091/1913 1089/1089/1911 1085/1085/1906 +f 1085/1085/1906 1089/1089/1911 1088/1088/1910 +f 1064/1064/1905 1087/1087/1909 1092/1092/1914 +f 1064/1064/1905 1092/1092/1914 1085/1085/1906 +f 1085/1085/1906 1092/1092/1914 1091/1091/1913 +f 1093/1093/1915 1066/1066/1916 1068/1068/1917 +f 1071/1071/1918 1094/1094/1919 1095/1095/1920 +f 1070/1070/1921 1096/1096/1922 1071/1071/1918 +f 1071/1071/1918 1096/1096/1922 1094/1094/1919 +f 1097/1097/1923 1074/1074/1924 808/808/1925 +f 1097/1097/1923 808/808/1925 1098/1098/1926 +f 786/786/1927 813/813/1928 1097/1097/1929 +f 1097/1097/1929 813/813/1928 812/812/1930 +f 812/812/1930 1073/1073/1931 1097/1097/1929 +f 1097/1097/1923 1073/1073/1932 810/810/1933 +f 1097/1097/1923 810/810/1933 1074/1074/1924 +f 1062/1062/1934 1099/1099/1935 1059/1059/1936 +f 1059/1059/1936 1099/1099/1935 1100/1100/1937 +f 1070/1070/1938 1100/1100/1938 1101/1101/1938 +f 1070/1070/1921 1101/1101/1939 1097/1097/1923 +f 1062/1062/1934 1102/1102/1940 1099/1099/1935 +f 1097/1097/1929 1103/1103/1941 786/786/1927 +f 1103/1103/1941 1102/1102/1940 786/786/1927 +f 786/786/1927 1102/1102/1940 1062/1062/1934 +f 1059/1059/1936 1050/1050/1942 958/958/1943 +f 895/895/1944 1051/1051/1944 1080/1080/1944 +f 1080/1080/1945 1051/1051/1945 894/894/1945 +f 1080/1080/1895 894/894/1946 1059/1059/1936 +f 1059/1059/1936 894/894/1946 949/949/1947 +f 1059/1059/1936 949/949/1947 1050/1050/1942 +f 1059/1059/1936 958/958/1943 967/967/1948 +f 967/967/1948 958/958/1943 959/959/210 +f 967/967/1949 959/959/1949 1049/1049/1949 +f 967/967/1950 1049/1049/1951 961/961/1952 +f 967/967/1950 961/961/1952 962/962/210 +f 962/962/210 963/963/210 967/967/1950 +f 967/967/1953 963/963/1861 1060/1060/1860 +f 967/967/1954 1060/1060/1955 966/966/1956 +f 966/966/1956 1060/1060/1955 965/965/1957 +f 918/918/1958 1054/1054/1959 1104/1104/1960 +f 1054/1054/1959 887/887/1961 1080/1080/1962 +f 1080/1080/1962 887/887/1961 886/886/210 +f 1080/1080/1962 886/886/210 920/920/1963 +f 920/920/1963 1052/1052/1964 1080/1080/1962 +f 1080/1080/1965 1052/1052/1966 941/941/1967 +f 1080/1080/1965 941/941/1967 895/895/210 +f 1105/1105/1968 1106/1106/1969 1104/1104/1960 +f 848/848/210 931/931/210 1104/1104/1960 +f 1104/1104/1960 931/931/210 918/918/1958 +f 1107/1107/1970 1046/1046/1970 948/948/1970 +f 1107/1107/1971 948/948/1972 947/947/1973 +f 1107/1107/1971 947/947/1973 1106/1106/1974 +f 1106/1106/1974 947/947/1973 1057/1057/1975 +f 1106/1106/1976 1057/1057/1976 944/944/1976 +f 1106/1106/1977 944/944/1978 945/945/1979 +f 1106/1106/1977 945/945/1979 943/943/1980 +f 943/943/1980 942/942/1981 1106/1106/1977 +f 1106/1106/1982 942/942/1982 849/849/1982 +f 1106/1106/1969 849/849/1983 1104/1104/1960 +f 1104/1104/1960 849/849/1983 850/850/210 +f 1104/1104/1960 850/850/210 848/848/210 +f 1107/1107/1984 950/950/1985 936/936/1986 +f 1108/1108/1987 955/955/1988 954/954/1989 +f 1108/1108/1987 954/954/1989 1107/1107/1990 +f 1107/1107/1990 954/954/1989 1048/1048/1991 +f 1107/1107/1992 1048/1048/1992 950/950/1992 +f 1108/1108/1987 1109/1109/1993 1045/1045/1994 +f 936/936/1986 935/935/1995 1107/1107/1984 +f 1107/1107/1984 935/935/1995 902/902/1996 +f 1107/1107/1984 902/902/1996 901/901/1997 +f 1107/1107/1984 901/901/1997 1046/1046/1998 +f 1108/1108/1987 784/784/1999 956/956/2000 +f 1108/1108/1987 956/956/2000 955/955/1988 +f 784/784/1999 1108/1108/1987 1045/1045/1994 +f 1020/1020/2001 1022/1022/2002 1109/1109/1993 +f 1109/1109/1993 1022/1022/2002 1045/1045/1994 +f 1104/1104/1960 1025/1025/2003 1110/1110/2004 +f 1110/1110/2004 1111/1111/2005 1104/1104/1960 +f 1104/1104/1960 1112/1112/2006 1113/1113/2007 +f 1025/1025/2003 1113/1113/2007 1114/1114/2008 +f 1025/1025/2003 1114/1114/2008 1023/1023/2009 +f 1023/1023/2009 1115/1115/2010 1116/1116/2011 +f 1104/1104/1960 1117/1117/2012 1112/1112/2006 +f 1104/1104/1960 1113/1113/2007 1025/1025/2003 +f 1115/1115/2010 1023/1023/2009 1114/1114/2008 +f 1116/1116/2011 1117/1117/2012 1023/1023/2009 +f 1023/1023/2009 1117/1117/2012 1104/1104/1960 +f 1023/1023/2009 1104/1104/1960 1026/1026/2013 +f 1032/1032/2014 1028/1028/2015 1104/1104/1960 +f 1104/1104/1960 1030/1030/2016 1026/1026/2013 +f 1104/1104/1960 1028/1028/2015 1030/1030/2016 +f 1033/1033/2017 1032/1032/2014 1104/1104/1960 +f 1035/1035/2018 1033/1033/2017 1039/1039/2019 +f 1033/1033/2017 1118/1118/2020 1039/1039/2019 +f 1039/1039/2019 1118/1118/2020 1119/1119/2021 +f 1120/1120/2022 1121/1121/2023 1041/1041/2024 +f 1119/1119/2021 1122/1122/2025 1039/1039/2019 +f 1039/1039/2026 1122/1122/2026 1036/1036/2026 +f 1122/1122/2027 1120/1120/2022 1036/1036/2028 +f 1036/1036/2028 1120/1120/2022 1041/1041/2024 +f 1033/1033/2017 1121/1121/2023 1118/1118/2020 +f 1123/1123/2029 1041/1041/2024 1104/1104/1960 +f 1041/1041/2024 1123/1123/2029 1124/1124/2030 +f 1124/1124/2030 1125/1125/2031 826/826/2032 +f 846/846/2033 1126/1126/2033 1127/1127/2033 +f 1043/1043/2034 1124/1124/2030 826/826/2032 +f 1041/1041/2024 1124/1124/2030 1043/1043/2034 +f 1128/1128/2035 896/896/2036 852/852/2037 +f 1128/1128/2035 852/852/2037 851/851/2038 +f 1128/1128/2035 851/851/2038 893/893/2039 +f 1128/1128/2035 893/893/2039 1125/1125/2031 +f 1125/1125/2031 893/893/2039 892/892/2040 +f 1125/1125/2031 892/892/2040 824/824/2041 +f 1125/1125/2031 824/824/2041 826/826/2032 +f 846/846/2042 1129/1129/2043 1126/1126/2044 +f 1126/1126/2045 1129/1129/2045 845/845/2045 +f 1126/1126/2046 845/845/2047 900/900/2048 +f 1130/1130/2049 847/847/2050 1104/1104/2051 +f 1104/1104/2052 847/847/2052 1127/1127/2052 +f 1126/1126/2053 1123/1123/2029 1104/1104/1960 +f 1126/1126/2046 900/900/2048 1131/1131/2054 +f 1131/1131/2054 900/900/2048 1018/1018/2055 +f 1131/1131/2056 1018/1018/2056 899/899/2056 +f 1131/1131/2057 899/899/2058 1128/1128/2035 +f 1128/1128/2035 899/899/2058 898/898/2059 +f 1128/1128/2035 898/898/2059 1017/1017/2060 +f 1128/1128/2035 1017/1017/2060 896/896/2036 +f 1127/1127/2061 1126/1126/2053 1104/1104/1960 +f 888/888/2062 1012/1012/2062 1104/1104/2062 +f 1012/1012/2063 916/916/2064 1104/1104/2051 +f 1104/1104/2051 916/916/2064 1130/1130/2049 +f 1012/1012/2065 930/930/2065 1080/1080/2065 +f 1080/1080/1962 930/930/210 888/888/210 +f 1013/1013/2066 885/885/2067 1080/1080/2068 +f 926/926/2069 1013/1013/2070 1080/1080/2071 +f 885/885/2067 910/910/210 1080/1080/2068 +f 1080/1080/2068 910/910/210 932/932/2072 +f 1080/1080/2068 932/932/2072 1012/1012/2073 +f 927/927/210 922/922/210 890/890/210 +f 926/926/210 883/883/210 928/928/210 +f 928/928/2074 1000/1000/2074 926/926/2074 +f 926/926/2075 1000/1000/2075 924/924/2075 +f 926/926/210 924/924/210 927/927/210 +f 927/927/210 924/924/210 923/923/210 +f 927/927/210 923/923/210 922/922/210 +f 937/937/2076 1002/1002/2076 1080/1080/2076 +f 1080/1080/2071 1002/1002/2077 884/884/2078 +f 890/890/2079 998/998/2079 927/927/2079 +f 927/927/2080 998/998/2080 889/889/2080 +f 889/889/2081 1132/1132/2082 927/927/2083 +f 927/927/2083 1132/1132/2082 915/915/2084 +f 1080/1080/2071 884/884/2078 926/926/2069 +f 926/926/2085 884/884/2086 1001/1001/2087 +f 926/926/2088 1001/1001/2088 883/883/2088 +f 927/927/2083 915/915/2084 1007/1007/210 +f 927/927/2083 1007/1007/210 891/891/210 +f 908/908/2089 913/913/2089 1006/1006/2089 +f 908/908/2090 1006/1006/2091 1011/1011/2092 +f 913/913/210 908/908/210 914/914/210 +f 914/914/210 908/908/210 911/911/210 +f 914/914/210 911/911/210 1007/1007/210 +f 1007/1007/210 911/911/210 912/912/210 +f 1007/1007/210 912/912/210 891/891/210 +f 908/908/2090 1011/1011/2092 1008/1008/2093 +f 1008/1008/2093 1011/1011/2092 903/903/2094 +f 1008/1008/2093 903/903/2094 904/904/210 +f 904/904/2095 1010/1010/2095 1008/1008/2095 +f 1008/1008/2096 1010/1010/2096 906/906/2096 +f 1008/1008/210 906/906/210 907/907/210 +f 1095/1095/1920 1094/1094/1919 1098/1098/2097 +f 1133/1133/2098 1134/1134/2099 1098/1098/1926 +f 1094/1094/2100 1133/1133/2100 1098/1098/2100 +f 1098/1098/1926 1134/1134/2099 1135/1135/2101 +f 1097/1097/1923 1136/1136/2102 1096/1096/1922 +f 1098/1098/1926 1135/1135/2101 1097/1097/1923 +f 1135/1135/2101 1136/1136/2102 1097/1097/1923 +f 1090/1090/1912 1070/1070/1903 1088/1088/1910 +f 1088/1088/1910 1070/1070/1903 1093/1093/1915 +f 1093/1093/1915 1070/1070/1903 1066/1066/1916 +f 888/888/210 1104/1104/1960 1080/1080/1962 +f 1080/1080/1962 1104/1104/1960 1054/1054/1959 +f 1080/1080/1895 1059/1059/1936 1070/1070/1903 +f 1070/1070/1903 1059/1059/1936 1100/1100/1937 +f 1081/1081/1896 1080/1080/1895 1070/1070/1903 +f 1083/1083/1902 1081/1081/1896 1070/1070/1903 +f 1064/1064/1905 1082/1082/1901 1070/1070/1903 +f 1070/1070/1921 1097/1097/1923 1096/1096/1922 +f 1121/1121/2023 1033/1033/2017 1041/1041/2024 +f 1041/1041/2024 1033/1033/2017 1104/1104/1960 +f 1137/1137/2103 1104/1104/1960 1111/1111/2005 +f 1137/1137/2103 1111/1111/2005 1109/1109/1993 +f 1109/1109/1993 1111/1111/2005 1020/1020/2001 +f 1104/1104/1960 1137/1137/2103 1105/1105/1968 +f 1024/1024/1789 1138/1138/2104 1025/1025/1790 +f 1037/1037/2105 1139/1139/2106 1038/1038/2107 +f 1140/1140/2108 1141/1141/2109 1042/1042/2110 +f 1142/1142/2111 1037/1037/2112 1036/1036/2113 +f 1141/1141/2109 1143/1143/2114 1043/1043/2115 +f 1143/1143/2114 1144/1144/2116 1041/1041/2117 +f 1139/1139/2106 1145/1145/2118 1146/1146/2119 +f 1145/1145/2118 1147/1147/2120 1034/1034/1795 +f 1148/1148/2121 1149/1149/2122 1029/1029/2123 +f 1029/1029/2123 1149/1149/2122 1030/1030/2124 +f 1138/1138/2104 1110/1110/2125 1025/1025/1790 +f 1111/1111/2126 1150/1150/2127 1020/1020/2128 +f 1043/1043/2115 1042/1042/2110 1141/1141/2109 +f 1041/1041/2117 1043/1043/2115 1143/1143/2114 +f 1141/1141/2129 1144/1144/2130 1143/1143/2131 +f 1040/1040/2132 1041/1041/2117 1144/1144/2116 +f 1144/1144/2116 1142/1142/2111 1040/1040/2132 +f 1040/1040/2132 1142/1142/2111 1036/1036/2113 +f 1139/1139/2106 1146/1146/2119 1038/1038/2107 +f 1038/1038/2107 1146/1146/2119 1039/1039/2133 +f 1035/1035/2134 1039/1039/2133 1146/1146/2119 +f 1035/1035/2134 1146/1146/2119 1145/1145/2118 +f 1035/1035/2134 1145/1145/2118 1034/1034/1795 +f 1031/1031/1796 1034/1034/1795 1147/1147/2120 +f 1151/1151/2135 1031/1031/1796 1147/1147/2120 +f 1031/1031/1796 1151/1151/2135 1032/1032/2136 +f 1028/1028/2137 1032/1032/2136 1151/1151/2135 +f 1028/1028/2137 1151/1151/2135 1148/1148/2121 +f 1029/1029/2123 1028/1028/2137 1148/1148/2121 +f 1030/1030/2124 1149/1149/2122 1026/1026/2138 +f 1027/1027/2139 1026/1026/2138 1149/1149/2122 +f 1149/1149/2140 1152/1152/2141 1027/1027/2142 +f 1027/1027/2142 1152/1152/2141 1024/1024/2143 +f 1027/1027/2142 1024/1024/2143 1023/1023/2144 +f 1110/1110/2125 1138/1138/2104 1150/1150/2145 +f 1111/1111/2126 1110/1110/2146 1150/1150/2127 +f 1021/1021/2147 1020/1020/2128 1150/1150/2127 +f 1021/1021/2148 1150/1150/2149 1153/1153/2150 +f 1140/1140/2108 1042/1042/2110 826/826/2151 +f 826/826/1786 1019/1019/1785 1140/1140/2152 +f 1154/1154/2153 1044/1044/1804 1155/1155/2154 +f 1044/1044/1804 1045/1045/1806 1155/1155/2154 +f 1045/1045/2155 1022/1022/2155 1155/1155/2155 +f 1155/1155/2156 1022/1022/2157 1153/1153/2150 +f 1155/1155/2158 1153/1153/2150 1156/1156/2159 +f 1022/1022/2157 1021/1021/2148 1153/1153/2150 +f 1018/1018/1783 1157/1157/2160 1017/1017/1781 +f 1017/1017/1781 1157/1157/2160 1016/1016/1774 +f 1044/1044/1804 1154/1154/2161 1048/1048/1818 +f 1048/1048/1818 1154/1154/2161 1047/1047/2162 +f 1015/1015/1772 908/908/1750 1009/1009/1752 +f 1018/1018/1783 900/900/2163 1158/1158/2164 +f 1158/1158/2164 900/900/2163 845/845/2165 +f 1158/1158/2164 845/845/2165 1129/1129/2166 +f 1129/1129/2043 846/846/2042 1127/1127/2167 +f 847/847/2168 1130/1130/2169 1127/1127/2170 +f 1127/1127/2170 1130/1130/2169 916/916/2171 +f 1127/1127/2170 916/916/2171 1159/1159/2172 +f 1159/1159/2173 916/916/2174 1012/1012/2175 +f 1012/1012/2175 1013/1013/2176 1160/1160/2177 +f 1018/1018/1783 1158/1158/2164 1157/1157/2160 +f 1159/1159/2173 1012/1012/2175 1160/1160/2177 +f 1160/1160/2178 1013/1013/1767 1014/1014/1766 +f 1015/1015/2179 1009/1009/2180 1161/1161/2181 +f 1158/1158/2164 1129/1129/2166 1162/1162/2182 +f 1162/1162/2182 1129/1129/2166 1127/1127/2183 +f 1162/1162/2182 1127/1127/2183 1159/1159/2184 +f 1162/1162/2185 1159/1159/2173 1160/1160/2177 +f 1160/1160/2186 1014/1014/2187 1163/1163/2188 +f 1014/1014/2187 1015/1015/2179 1163/1163/2188 +f 1163/1163/2188 1015/1015/2179 1161/1161/2181 +f 1055/1055/1841 1053/1053/2189 1054/1054/1839 +f 1051/1051/1826 1164/1164/2190 1050/1050/1828 +f 1050/1050/2191 1164/1164/2192 1049/1049/1864 +f 1057/1057/2193 1046/1046/1810 1047/1047/1813 +f 1055/1055/2194 1056/1056/2195 1165/1165/2196 +f 1165/1165/2197 1056/1056/2198 1057/1057/2193 +f 1166/1166/2199 1057/1057/2193 1047/1047/1813 +f 1057/1057/2193 1166/1166/2199 1165/1165/2197 +f 1053/1053/2200 1167/1167/2201 1052/1052/2202 +f 1052/1052/2203 1167/1167/2204 1051/1051/2205 +f 1055/1055/2194 1165/1165/2196 1168/1168/2206 +f 1055/1055/2194 1168/1168/2206 1053/1053/2207 +f 1053/1053/2200 1168/1168/2208 1167/1167/2201 +f 1051/1051/2205 1167/1167/2204 1169/1169/2209 +f 1051/1051/2205 1169/1169/2209 1164/1164/2210 +f 1010/1010/1755 1161/1161/2211 1009/1009/1752 +f 1060/1060/1860 1164/1164/2192 1169/1169/2212 +f 1060/1060/1860 1169/1169/2212 1058/1058/1855 +f 1164/1164/2192 1060/1060/1860 1049/1049/1864 +f 1011/1011/2213 1006/1006/2213 1010/1010/2213 +f 1010/1010/2214 1006/1006/2215 1170/1170/2216 +f 1010/1010/2214 1170/1170/2216 1161/1161/2217 +f 786/786/1883 1062/1062/1867 1171/1171/2218 +f 1062/1062/1867 1172/1172/2219 1171/1171/2218 +f 1171/1171/2220 1172/1172/2221 1173/1173/2222 +f 1058/1058/2223 1169/1169/2224 1174/1174/2225 +f 1175/1175/2226 1171/1171/2226 1176/1176/2226 +f 1173/1173/2222 1172/1172/2221 1174/1174/2225 +f 1172/1172/2219 1062/1062/1867 1061/1061/1866 +f 1172/1172/2221 1061/1061/2227 1174/1174/2225 +f 1061/1061/1866 1059/1059/1856 1058/1058/1855 +f 1061/1061/2227 1058/1058/2223 1174/1174/2225 +f 998/998/2228 1170/1170/2229 1132/1132/2230 +f 1132/1132/2230 1170/1170/2229 1006/1006/1745 +f 889/889/2231 998/998/2228 1132/1132/2230 +f 1132/1132/2230 1006/1006/1745 915/915/1749 +f 1177/1177/2232 1178/1178/2233 1179/1179/2234 +f 1178/1178/2233 1063/1063/1868 1065/1065/1870 +f 1175/1175/2235 1075/1075/1881 786/786/1883 +f 1098/1098/2236 1180/1180/2237 1095/1095/2238 +f 1181/1181/2239 1182/1182/2240 1072/1072/1874 +f 1183/1183/2241 1085/1085/2242 1088/1088/2243 +f 1171/1171/2218 1175/1175/2235 786/786/1883 +f 1075/1075/2244 1175/1175/2245 1184/1184/2246 +f 1075/1075/2244 1184/1184/2246 1073/1073/1877 +f 1074/1074/1878 1073/1073/1877 1184/1184/2246 +f 808/808/2247 1074/1074/1878 1184/1184/2246 +f 1184/1184/2246 1185/1185/2248 808/808/2247 +f 1185/1185/2249 1184/1184/2246 1186/1186/2250 +f 808/808/2247 1185/1185/2248 1098/1098/2236 +f 1186/1186/2251 1098/1098/2236 1185/1185/2248 +f 1186/1186/2251 1180/1180/2237 1098/1098/2236 +f 1095/1095/2238 1180/1180/2237 1181/1181/2252 +f 1181/1181/2239 1180/1180/2253 1187/1187/2254 +f 1071/1071/2255 1095/1095/2238 1181/1181/2252 +f 1181/1181/2252 1072/1072/2256 1071/1071/2255 +f 1069/1069/2257 1070/1070/1875 1072/1072/1874 +f 1069/1069/2257 1072/1072/1874 1182/1182/2240 +f 1182/1182/2240 1188/1188/2258 1069/1069/2257 +f 1066/1066/2259 1069/1069/2257 1188/1188/2258 +f 1067/1067/2260 1066/1066/2259 1188/1188/2258 +f 1188/1188/2258 1189/1189/2261 1067/1067/2260 +f 1189/1189/2261 1190/1190/2262 1067/1067/2260 +f 1067/1067/2260 1190/1190/2262 1068/1068/2263 +f 1190/1190/2264 1189/1189/2265 1183/1183/2266 +f 1068/1068/2263 1190/1190/2262 1093/1093/2267 +f 1088/1088/2243 1093/1093/2267 1190/1190/2262 +f 1088/1088/2243 1190/1190/2262 1183/1183/2241 +f 1179/1179/2234 1085/1085/2242 1183/1183/2241 +f 1179/1179/2268 1183/1183/2268 1191/1191/2268 +f 1065/1065/1870 1085/1085/2242 1179/1179/2234 +f 1065/1065/1870 1179/1179/2234 1178/1178/2233 +f 1001/1001/2087 884/884/2086 1002/1002/2269 +f 1004/1004/2270 1005/1005/2271 1192/1192/2272 +f 1192/1192/2273 1005/1005/2274 933/933/2275 +f 999/999/2276 1000/1000/2277 1193/1193/2278 +f 1000/1000/2279 1001/1001/2280 1193/1193/2281 +f 1194/1194/2282 1002/1002/2283 1003/1003/2284 +f 1192/1192/2273 933/933/2275 1195/1195/2285 +f 1001/1001/2286 1002/1002/2287 1194/1194/2288 +f 1196/1196/2289 1003/1003/2284 1004/1004/2270 +f 998/998/2290 999/999/2276 1170/1170/2291 +f 1196/1196/2289 1004/1004/2270 1192/1192/2272 +f 1170/1170/2291 999/999/2276 1193/1193/2278 +f 1193/1193/2281 1001/1001/2280 1197/1197/2292 +f 1197/1197/2293 1001/1001/2286 1194/1194/2288 +f 1194/1194/2282 1003/1003/2284 1196/1196/2289 +f 1198/1198/2294 1192/1192/2295 1195/1195/2296 +f 1194/1194/2297 1196/1196/2297 1192/1192/2297 +f 1199/1199/2298 1198/1198/2294 1195/1195/2296 +f 1077/1077/2299 1199/1199/2298 1195/1195/2296 +f 1077/1077/2299 1195/1195/2296 1076/1076/2300 +f 1076/1076/2301 1195/1195/2285 933/933/2275 +f 1200/1200/2302 1201/1201/2303 1063/1063/1868 +f 1178/1178/2304 1200/1200/2302 1063/1063/1868 +f 1063/1063/1868 1077/1077/2299 1064/1064/1869 +f 1063/1063/1868 1201/1201/2303 1077/1077/2299 +f 1077/1077/2299 1201/1201/2303 1199/1199/2298 +f 1107/1107/2305 1154/1154/2306 1108/1108/2307 +f 1107/1107/2305 1047/1047/2308 1154/1154/2306 +f 1047/1047/2309 1107/1107/2310 1106/1106/2311 +f 1047/1047/2309 1106/1106/2311 1166/1166/2312 +f 1109/1109/2313 1155/1155/2314 1156/1156/2315 +f 1108/1108/2316 1154/1154/2316 1155/1155/2316 +f 1108/1108/2317 1155/1155/2314 1109/1109/2313 +f 1109/1109/2318 1156/1156/2318 1137/1137/2318 +f 1137/1137/2319 1156/1156/2319 1202/1202/2319 +f 1137/1137/2320 1202/1202/2320 1105/1105/2320 +f 1105/1105/2321 1202/1202/2322 1106/1106/2323 +f 1106/1106/2323 1202/1202/2322 1166/1166/2324 +f 1115/1115/2325 1024/1024/2325 1116/1116/2325 +f 1116/1116/2326 1024/1024/2326 1152/1152/2326 +f 1024/1024/2327 1115/1115/2327 1114/1114/2327 +f 1024/1024/2328 1114/1114/2328 1138/1138/2328 +f 1113/1113/2329 1138/1138/2329 1114/1114/2329 +f 1116/1116/2330 1152/1152/2331 1203/1203/2332 +f 1116/1116/2330 1203/1203/2332 1117/1117/2333 +f 1117/1117/2334 1203/1203/2335 1204/1204/2336 +f 1117/1117/2334 1204/1204/2336 1112/1112/2337 +f 1112/1112/2338 1204/1204/2339 1113/1113/2340 +f 1113/1113/2340 1204/1204/2339 1138/1138/2341 +f 1142/1142/2342 1120/1120/2343 1037/1037/2344 +f 1037/1037/2344 1120/1120/2343 1122/1122/2345 +f 1037/1037/2346 1122/1122/2347 1139/1139/2348 +f 1139/1139/2348 1122/1122/2347 1119/1119/2349 +f 1120/1120/2350 1142/1142/2351 1121/1121/2352 +f 1121/1121/2352 1142/1142/2351 1205/1205/2353 +f 1121/1121/2354 1205/1205/2355 1118/1118/2356 +f 1118/1118/2356 1205/1205/2355 1206/1206/2357 +f 1118/1118/2358 1206/1206/2359 1119/1119/2360 +f 1119/1119/2360 1206/1206/2359 1139/1139/2361 +f 1158/1158/2362 1126/1126/2363 1131/1131/2364 +f 1158/1158/2362 1131/1131/2364 1157/1157/2365 +f 1157/1157/2366 1131/1131/2367 1128/1128/2368 +f 1016/1016/2369 1157/1157/2366 1128/1128/2368 +f 1016/1016/2370 1128/1128/2371 1125/1125/2372 +f 1016/1016/2370 1125/1125/2372 1019/1019/2373 +f 1140/1140/2374 1019/1019/2373 1125/1125/2372 +f 1124/1124/2375 1140/1140/2374 1125/1125/2372 +f 1126/1126/2376 1158/1158/2377 1207/1207/2378 +f 1126/1126/2376 1207/1207/2378 1123/1123/2379 +f 1123/1123/2380 1207/1207/2381 1208/1208/2382 +f 1123/1123/2380 1208/1208/2382 1124/1124/2375 +f 1124/1124/2375 1208/1208/2382 1140/1140/2374 +f 1200/1200/2383 1082/1082/2384 1201/1201/2385 +f 1201/1201/2385 1082/1082/2384 1084/1084/2386 +f 1084/1084/2387 1199/1199/2388 1201/1201/2389 +f 1079/1079/2390 1199/1199/2388 1084/1084/2387 +f 1082/1082/2391 1200/1200/2392 1209/1209/2393 +f 1082/1082/2391 1209/1209/2393 1083/1083/2394 +f 1083/1083/2395 1209/1209/2396 1081/1081/2397 +f 1081/1081/2397 1209/1209/2396 1210/1210/2398 +f 1081/1081/2399 1210/1210/2400 1078/1078/2401 +f 1078/1078/2401 1210/1210/2400 1198/1198/2402 +f 1078/1078/2401 1198/1198/2402 1079/1079/2390 +f 1079/1079/2390 1198/1198/2402 1199/1199/2388 +f 1179/1179/2403 1091/1091/2404 1092/1092/2405 +f 1089/1089/2406 1191/1191/2406 1090/1090/2406 +f 1191/1191/2407 1089/1089/2408 1179/1179/2409 +f 1179/1179/2409 1089/1089/2408 1091/1091/2410 +f 1177/1177/2411 1179/1179/2403 1092/1092/2405 +f 1087/1087/2412 1177/1177/2413 1092/1092/2414 +f 1090/1090/2415 1191/1191/2415 1086/1086/2415 +f 1086/1086/2416 1191/1191/2416 1211/1211/2416 +f 1086/1086/2417 1211/1211/2418 1087/1087/2419 +f 1087/1087/2419 1211/1211/2418 1212/1212/2420 +f 1087/1087/2412 1212/1212/2421 1177/1177/2413 +f 1186/1186/2422 1134/1134/2423 1180/1180/2424 +f 1180/1180/2424 1134/1134/2423 1133/1133/2425 +f 1133/1133/2426 1187/1187/2427 1180/1180/2428 +f 1094/1094/2429 1187/1187/2427 1133/1133/2426 +f 1134/1134/2430 1186/1186/2430 1135/1135/2430 +f 1135/1135/2431 1186/1186/2431 1213/1213/2431 +f 1135/1135/2432 1213/1213/2432 1136/1136/2432 +f 1136/1136/2433 1213/1213/2434 1214/1214/2435 +f 1136/1136/2433 1214/1214/2435 1096/1096/2436 +f 1096/1096/2437 1214/1214/2438 1094/1094/2439 +f 1094/1094/2439 1214/1214/2438 1187/1187/2440 +f 1102/1102/2441 1171/1171/2442 1099/1099/2443 +f 1099/1099/2443 1171/1171/2442 1173/1173/2444 +f 1103/1103/2445 1171/1171/2446 1102/1102/2447 +f 1171/1171/2446 1103/1103/2445 1176/1176/2448 +f 1099/1099/2449 1173/1173/2450 1100/1100/2451 +f 1100/1100/2451 1173/1173/2450 1215/1215/2452 +f 1100/1100/2453 1215/1215/2454 1101/1101/2455 +f 1101/1101/2455 1215/1215/2454 1216/1216/2456 +f 1101/1101/2457 1216/1216/2458 1097/1097/2459 +f 1097/1097/2459 1216/1216/2458 1217/1217/2460 +f 1097/1097/2461 1217/1217/2462 1103/1103/2463 +f 1103/1103/2463 1217/1217/2462 1176/1176/2464 +f 1142/1142/2465 1144/1144/2130 1205/1205/2466 +f 1217/1217/2467 1175/1175/2245 1176/1176/2468 +f 1213/1213/2469 1211/1211/2470 1214/1214/2471 +f 1193/1193/2472 1197/1197/2473 1163/1163/2474 +f 1214/1214/2471 1181/1181/2239 1187/1187/2254 +f 1165/1165/2475 1162/1162/2476 1168/1168/2477 +f 1145/1145/2118 1206/1206/2478 1147/1147/2479 +f 1147/1147/2479 1206/1206/2478 1151/1151/2480 +f 1205/1205/2466 1141/1141/2129 1140/1140/2481 +f 1151/1151/2480 1206/1206/2478 1140/1140/2481 +f 1140/1140/2481 1208/1208/2482 1151/1151/2480 +f 1208/1208/2482 1207/1207/2483 1151/1151/2480 +f 1207/1207/2483 1158/1158/2484 1148/1148/2485 +f 1162/1162/2476 1204/1204/2486 1158/1158/2484 +f 1162/1162/2476 1160/1160/2487 1168/1168/2477 +f 1161/1161/2488 1170/1170/2489 1163/1163/2474 +f 1163/1163/2474 1170/1170/2489 1193/1193/2472 +f 1194/1194/2490 1192/1192/2295 1210/1210/2491 +f 1205/1205/2466 1144/1144/2130 1141/1141/2129 +f 1149/1149/2140 1203/1203/2492 1152/1152/2141 +f 1198/1198/2294 1210/1210/2491 1192/1192/2295 +f 1209/1209/2493 1194/1194/2490 1210/1210/2491 +f 1211/1211/2470 1194/1194/2490 1209/1209/2493 +f 1194/1194/2490 1167/1167/2494 1197/1197/2473 +f 1197/1197/2473 1167/1167/2494 1160/1160/2487 +f 1178/1178/2495 1212/1212/2496 1209/1209/2493 +f 1200/1200/2497 1178/1178/2495 1209/1209/2493 +f 1206/1206/2478 1205/1205/2466 1140/1140/2481 +f 1202/1202/2498 1162/1162/2476 1165/1165/2475 +f 1204/1204/2486 1202/1202/2498 1153/1153/2150 +f 1204/1204/2486 1153/1153/2150 1150/1150/2149 +f 1167/1167/2494 1168/1168/2477 1160/1160/2487 +f 1177/1177/2499 1212/1212/2496 1178/1178/2495 +f 1217/1217/2467 1216/1216/2500 1213/1213/2469 +f 1148/1148/2485 1203/1203/2492 1149/1149/2140 +f 1165/1165/2475 1166/1166/2501 1202/1202/2498 +f 1204/1204/2486 1150/1150/2149 1138/1138/2502 +f 1202/1202/2498 1156/1156/2159 1153/1153/2150 +f 1183/1183/2266 1211/1211/2470 1191/1191/2503 +f 1204/1204/2486 1203/1203/2492 1158/1158/2484 +f 1211/1211/2470 1169/1169/2504 1194/1194/2490 +f 1158/1158/2484 1203/1203/2492 1148/1148/2485 +f 1204/1204/2486 1162/1162/2476 1202/1202/2498 +f 1189/1189/2265 1211/1211/2470 1183/1183/2266 +f 1169/1169/2504 1167/1167/2494 1194/1194/2490 +f 1207/1207/2483 1148/1148/2485 1151/1151/2480 +f 1169/1169/2504 1211/1211/2470 1174/1174/2505 +f 1216/1216/2500 1215/1215/2506 1174/1174/2505 +f 1213/1213/2469 1184/1184/2246 1217/1217/2467 +f 1174/1174/2505 1215/1215/2506 1173/1173/2507 +f 1212/1212/2496 1211/1211/2470 1209/1209/2493 +f 1216/1216/2500 1211/1211/2470 1213/1213/2469 +f 1188/1188/2508 1211/1211/2470 1189/1189/2265 +f 1174/1174/2505 1211/1211/2470 1216/1216/2500 +f 1214/1214/2471 1211/1211/2470 1188/1188/2508 +f 1182/1182/2240 1214/1214/2471 1188/1188/2508 +f 1175/1175/2245 1217/1217/2467 1184/1184/2246 +f 1197/1197/2473 1160/1160/2487 1163/1163/2474 +f 1206/1206/2478 1145/1145/2118 1139/1139/2106 +f 1182/1182/2240 1181/1181/2239 1214/1214/2471 +f 1184/1184/2246 1213/1213/2469 1186/1186/2250 +f 1218/1218/2509 1219/1219/2510 1220/1220/2511 +f 1221/1221/2512 1222/1222/2513 1223/1223/2514 +f 1224/1224/2515 1219/1219/2510 1218/1218/2509 +f 1221/1221/2512 1225/1225/2516 1222/1222/2513 +f 1226/1226/2517 1227/1227/2518 1225/1225/2516 +f 1218/1218/2509 1220/1220/2511 1228/1228/2519 +f 1223/1223/2514 1219/1219/2510 1224/1224/2515 +f 1221/1221/2512 1223/1223/2514 1224/1224/2515 +f 1226/1226/2517 1225/1225/2516 1221/1221/2512 +f 1228/1228/2519 1227/1227/2518 1218/1218/2509 +f 1218/1218/2509 1227/1227/2518 1226/1226/2517 +f 1229/1229/2520 1230/1230/2521 1231/1231/2522 +f 1232/1232/2523 1233/1233/2524 1234/1234/2525 +f 1232/1232/2523 1234/1234/2525 1235/1235/2526 +f 1235/1235/2527 1234/1234/2528 1231/1231/2529 +f 1235/1235/2527 1231/1231/2529 1236/1236/2530 +f 1236/1236/2531 1231/1231/2531 1237/1237/2531 +f 1236/1236/2532 1237/1237/2532 1238/1238/2532 +f 1238/1238/2533 1237/1237/2534 1239/1239/2535 +f 1238/1238/2536 1239/1239/2537 1232/1232/2538 +f 1232/1232/2538 1239/1239/2537 1233/1233/2539 +f 1222/1222/2540 1232/1232/2540 1223/1223/2540 +f 1223/1223/2541 1232/1232/2542 1219/1219/2543 +f 1219/1219/2543 1232/1232/2542 1235/1235/2544 +f 1219/1219/2545 1235/1235/2546 1236/1236/2547 +f 1219/1219/2545 1236/1236/2547 1220/1220/2548 +f 1220/1220/2549 1236/1236/2549 1228/1228/2549 +f 1228/1228/2550 1236/1236/2551 1227/1227/2552 +f 1227/1227/2552 1236/1236/2551 1238/1238/2553 +f 1227/1227/2554 1238/1238/2554 1225/1225/2554 +f 1225/1225/2555 1238/1238/2556 1232/1232/2557 +f 1225/1225/2555 1232/1232/2557 1222/1222/2558 +f 1226/1226/2517 1221/1221/2512 1218/1218/2509 +f 1218/1218/2509 1221/1221/2512 1224/1224/2515 +f 1233/1233/2524 1229/1229/2559 1234/1234/2525 +f 1234/1234/2560 1229/1229/2520 1231/1231/2522 +f 1237/1237/2561 1231/1231/2522 1230/1230/2521 +f 1237/1237/2534 1230/1230/2562 1239/1239/2535 +f 1239/1239/2563 1230/1230/2564 1233/1233/2565 +f 1233/1233/2565 1230/1230/2564 1229/1229/2566 +f 1240/1240/2567 1241/1241/2568 1242/1242/2569 +f 1243/1243/2570 1244/1244/2571 1245/1245/2572 +f 1240/1240/2567 1246/1246/2573 1241/1241/2568 +f 1247/1247/2574 1242/1242/2569 1241/1241/2568 +f 1245/1245/2572 1248/1248/2575 1243/1243/2570 +f 1249/1249/2576 1247/1247/2574 1250/1250/2577 +f 1250/1250/2577 1247/1247/2574 1241/1241/2568 +f 1251/1251/2578 1249/1249/2576 1250/1250/2577 +f 1241/1241/2568 1246/1246/2573 1243/1243/2570 +f 1243/1243/2570 1246/1246/2573 1244/1244/2571 +f 1243/1243/2570 1248/1248/2575 1251/1251/2578 +f 1243/1243/2570 1251/1251/2578 1250/1250/2577 +f 1252/1252/2579 1253/1253/2580 1254/1254/2581 +f 1252/1252/2579 1255/1255/2582 1253/1253/2580 +f 1252/1252/2579 1254/1254/2581 1256/1256/2583 +f 1257/1257/2584 1258/1258/2585 1259/1259/2586 +f 1259/1259/2587 1258/1258/2588 1260/1260/2589 +f 1260/1260/2589 1258/1258/2588 1261/1261/2590 +f 1260/1260/2591 1261/1261/2592 1262/1262/2593 +f 1260/1260/2591 1262/1262/2593 1256/1256/2594 +f 1256/1256/2595 1262/1262/2596 1263/1263/2597 +f 1256/1256/2595 1263/1263/2597 1252/1252/2598 +f 1252/1252/2599 1263/1263/2600 1255/1255/2601 +f 1263/1263/2600 1264/1264/2602 1255/1255/2601 +f 1255/1255/2603 1264/1264/2604 1265/1265/2605 +f 1265/1265/2605 1264/1264/2604 1266/1266/2606 +f 1265/1265/2607 1266/1266/2608 1253/1253/2609 +f 1253/1253/2609 1266/1266/2608 1257/1257/2584 +f 1253/1253/2609 1257/1257/2584 1259/1259/2586 +f 1257/1257/2610 1267/1267/2611 1258/1258/2612 +f 1262/1262/2613 1268/1268/2614 1263/1263/2615 +f 1257/1257/2610 1269/1269/2616 1267/1267/2611 +f 1266/1266/2617 1269/1269/2616 1257/1257/2610 +f 1261/1261/2618 1270/1270/2619 1268/1268/2614 +f 1261/1261/2618 1268/1268/2614 1262/1262/2613 +f 1261/1261/2618 1271/1271/2620 1270/1270/2619 +f 1264/1264/2621 1272/1272/2622 1266/1266/2617 +f 1266/1266/2617 1272/1272/2622 1269/1269/2616 +f 1264/1264/2621 1273/1273/2623 1272/1272/2622 +f 1258/1258/2612 1271/1271/2620 1261/1261/2618 +f 1258/1258/2612 1267/1267/2611 1271/1271/2620 +f 1263/1263/2615 1273/1273/2623 1264/1264/2621 +f 1263/1263/2615 1268/1268/2614 1273/1273/2623 +f 1267/1267/2624 1240/1240/2625 1242/1242/2626 +f 1267/1267/2627 1242/1242/2628 1271/1271/2629 +f 1242/1242/2628 1247/1247/2630 1271/1271/2629 +f 1271/1271/2631 1247/1247/2632 1249/1249/2633 +f 1271/1271/2631 1249/1249/2633 1270/1270/2634 +f 1270/1270/2634 1249/1249/2633 1251/1251/2635 +f 1270/1270/2634 1251/1251/2635 1268/1268/2636 +f 1268/1268/2637 1251/1251/2638 1248/1248/2639 +f 1268/1268/2637 1248/1248/2639 1273/1273/2640 +f 1248/1248/2639 1245/1245/2641 1273/1273/2640 +f 1273/1273/2642 1245/1245/2643 1244/1244/2644 +f 1273/1273/2642 1244/1244/2644 1272/1272/2645 +f 1272/1272/2646 1244/1244/2647 1246/1246/2648 +f 1272/1272/2646 1246/1246/2648 1269/1269/2649 +f 1269/1269/2649 1246/1246/2648 1240/1240/2625 +f 1269/1269/2649 1240/1240/2625 1267/1267/2624 +f 1243/1243/2650 1250/1250/2651 1274/1274/2652 +f 1274/1274/2652 1250/1250/2651 1275/1275/2653 +f 1241/1241/2654 1243/1243/2655 1276/1276/2656 +f 1276/1276/2656 1243/1243/2655 1274/1274/2657 +f 1250/1250/2658 1241/1241/2659 1275/1275/2660 +f 1275/1275/2660 1241/1241/2659 1276/1276/2661 +f 1275/1275/101 1276/1276/101 1274/1274/101 +f 1265/1265/2662 1253/1253/2580 1255/1255/2582 +f 1260/1260/2663 1256/1256/2583 1254/1254/2581 +f 1260/1260/2589 1254/1254/2664 1259/1259/2587 +f 1259/1259/2665 1254/1254/2581 1253/1253/2580 +f 1277/1277/2666 1278/1278/2667 1279/1279/2668 +f 1277/1277/2666 1280/1280/2669 1278/1278/2667 +f 1281/1281/2670 1282/1282/2671 1283/1283/2672 +f 1284/1284/2673 1285/1285/2674 1280/1280/2669 +f 1284/1284/2673 1280/1280/2669 1277/1277/2666 +f 1286/1286/2675 1285/1285/2674 1284/1284/2673 +f 1277/1277/2666 1279/1279/2668 1282/1282/2671 +f 1277/1277/2666 1282/1282/2671 1281/1281/2670 +f 1281/1281/2670 1283/1283/2672 1286/1286/2675 +f 1281/1281/2670 1286/1286/2675 1284/1284/2673 +f 1287/1287/2676 1288/1288/2677 1289/1289/2678 +f 1290/1290/2679 1288/1288/2677 1287/1287/2676 +f 1291/1291/2680 1292/1292/2681 1293/1293/2682 +f 1291/1291/2680 1293/1293/2682 1294/1294/2683 +f 1294/1294/2684 1293/1293/2685 1295/1295/2686 +f 1294/1294/2684 1295/1295/2686 1290/1290/2687 +f 1290/1290/2688 1295/1295/2689 1296/1296/2690 +f 1296/1296/2690 1295/1295/2689 1297/1297/2691 +f 1296/1296/2692 1297/1297/2693 1298/1298/2694 +f 1296/1296/2692 1298/1298/2694 1288/1288/2695 +f 1288/1288/2696 1298/1298/2697 1299/1299/2698 +f 1288/1288/2696 1299/1299/2698 1289/1289/2699 +f 1289/1289/2700 1299/1299/2701 1292/1292/2702 +f 1289/1289/2700 1292/1292/2702 1291/1291/2703 +f 1292/1292/2704 1300/1300/2705 1293/1293/2706 +f 1293/1293/2706 1300/1300/2705 1301/1301/2707 +f 1297/1297/2708 1302/1302/2709 1303/1303/2710 +f 1299/1299/2711 1304/1304/2712 1292/1292/2704 +f 1292/1292/2704 1304/1304/2712 1300/1300/2705 +f 1295/1295/2713 1302/1302/2709 1297/1297/2708 +f 1295/1295/2713 1305/1305/2714 1302/1302/2709 +f 1298/1298/2715 1304/1304/2712 1299/1299/2711 +f 1298/1298/2715 1306/1306/2716 1304/1304/2712 +f 1293/1293/2706 1307/1307/2717 1295/1295/2713 +f 1295/1295/2713 1307/1307/2717 1305/1305/2714 +f 1293/1293/2706 1301/1301/2707 1307/1307/2717 +f 1297/1297/2708 1303/1303/2710 1298/1298/2715 +f 1298/1298/2715 1303/1303/2710 1306/1306/2716 +f 1300/1300/2718 1278/1278/2719 1301/1301/2720 +f 1301/1301/2720 1278/1278/2719 1280/1280/2721 +f 1301/1301/2720 1280/1280/2721 1307/1307/2722 +f 1280/1280/2721 1285/1285/2723 1307/1307/2722 +f 1307/1307/2722 1285/1285/2723 1305/1305/2724 +f 1305/1305/2725 1285/1285/2726 1302/1302/2727 +f 1285/1285/2726 1286/1286/2728 1302/1302/2727 +f 1302/1302/2729 1286/1286/2730 1303/1303/2731 +f 1303/1303/2731 1286/1286/2730 1283/1283/2732 +f 1303/1303/2733 1283/1283/2734 1306/1306/2735 +f 1306/1306/2735 1283/1283/2734 1282/1282/2736 +f 1306/1306/2737 1282/1282/2737 1304/1304/2737 +f 1304/1304/2738 1282/1282/2739 1279/1279/2740 +f 1304/1304/2738 1279/1279/2740 1300/1300/2718 +f 1279/1279/2740 1278/1278/2719 1300/1300/2718 +f 1281/1281/2741 1284/1284/2742 1308/1308/2743 +f 1308/1308/2743 1284/1284/2742 1309/1309/2744 +f 1277/1277/2745 1281/1281/2746 1310/1310/2747 +f 1310/1310/2747 1281/1281/2746 1308/1308/2748 +f 1284/1284/2749 1277/1277/2750 1309/1309/2751 +f 1309/1309/2751 1277/1277/2750 1310/1310/2752 +f 1309/1309/101 1310/1310/101 1308/1308/101 +f 1296/1296/2753 1288/1288/2677 1290/1290/2679 +f 1294/1294/2754 1290/1290/2754 1287/1287/2754 +f 1294/1294/2683 1287/1287/2755 1291/1291/2680 +f 1291/1291/2756 1287/1287/2676 1289/1289/2678 +f 1311/1311/2757 1312/1312/2758 1313/1313/2759 +f 1314/1314/2760 1315/1315/2761 1316/1316/2762 +f 1315/1315/2761 1317/1317/2763 1316/1316/2762 +f 1316/1316/2762 1317/1317/2763 1318/1318/2764 +f 1313/1313/2759 1319/1319/2765 1311/1311/2757 +f 1320/1320/2766 1321/1321/2767 1316/1316/2762 +f 1318/1318/2764 1317/1317/2763 1311/1311/2757 +f 1311/1311/2757 1317/1317/2763 1312/1312/2758 +f 1316/1316/2762 1321/1321/2767 1314/1314/2760 +f 1311/1311/2757 1319/1319/2765 1320/1320/2766 +f 1320/1320/2766 1319/1319/2765 1321/1321/2767 +f 1322/1322/2768 1323/1323/2769 1324/1324/2770 +f 1322/1322/2768 1325/1325/2771 1323/1323/2769 +f 1322/1322/2768 1326/1326/2772 1325/1325/2771 +f 1323/1323/2773 1327/1327/2774 1324/1324/2775 +f 1327/1327/2774 1328/1328/2776 1324/1324/2775 +f 1324/1324/2777 1328/1328/2778 1322/1322/2779 +f 1328/1328/2778 1329/1329/2780 1322/1322/2779 +f 1322/1322/2779 1329/1329/2780 1330/1330/2781 +f 1330/1330/2781 1329/1329/2780 1331/1331/2782 +f 1330/1330/2783 1331/1331/2784 1332/1332/2785 +f 1331/1331/2784 1333/1333/2786 1332/1332/2785 +f 1332/1332/2787 1333/1333/2788 1325/1325/2789 +f 1333/1333/2788 1334/1334/2790 1325/1325/2789 +f 1325/1325/2791 1334/1334/2792 1323/1323/2793 +f 1323/1323/2793 1334/1334/2792 1327/1327/2794 +f 1327/1327/2795 1335/1335/2796 1328/1328/2797 +f 1328/1328/2797 1335/1335/2796 1336/1336/2798 +f 1331/1331/2799 1337/1337/2800 1333/1333/2801 +f 1327/1327/2795 1338/1338/2802 1335/1335/2796 +f 1331/1331/2799 1339/1339/2803 1337/1337/2800 +f 1329/1329/2804 1340/1340/2805 1339/1339/2803 +f 1329/1329/2804 1339/1339/2803 1331/1331/2799 +f 1334/1334/2806 1341/1341/2807 1327/1327/2795 +f 1327/1327/2795 1341/1341/2807 1338/1338/2802 +f 1329/1329/2804 1336/1336/2798 1340/1340/2805 +f 1328/1328/2797 1336/1336/2798 1329/1329/2804 +f 1333/1333/2801 1342/1342/2808 1341/1341/2807 +f 1333/1333/2801 1341/1341/2807 1334/1334/2806 +f 1333/1333/2801 1337/1337/2800 1342/1342/2808 +f 1335/1335/2809 1315/1315/2810 1336/1336/2811 +f 1315/1315/2810 1314/1314/2812 1336/1336/2811 +f 1336/1336/2813 1314/1314/2814 1340/1340/2815 +f 1340/1340/2815 1314/1314/2814 1321/1321/2816 +f 1340/1340/2815 1321/1321/2816 1339/1339/2817 +f 1339/1339/2818 1321/1321/2819 1319/1319/2820 +f 1339/1339/2818 1319/1319/2820 1337/1337/2821 +f 1337/1337/2822 1319/1319/2823 1342/1342/2824 +f 1319/1319/2823 1313/1313/2825 1342/1342/2824 +f 1342/1342/2826 1313/1313/2827 1341/1341/2828 +f 1313/1313/2827 1312/1312/2829 1341/1341/2828 +f 1341/1341/2830 1312/1312/2831 1338/1338/2832 +f 1312/1312/2831 1317/1317/2833 1338/1338/2832 +f 1338/1338/2832 1317/1317/2833 1335/1335/2809 +f 1335/1335/2809 1317/1317/2833 1315/1315/2810 +f 1311/1311/2834 1320/1320/2835 1343/1343/2836 +f 1343/1343/2836 1320/1320/2835 1344/1344/2837 +f 1318/1318/2838 1311/1311/2839 1345/1345/2840 +f 1345/1345/2840 1311/1311/2839 1343/1343/2841 +f 1316/1316/2842 1318/1318/2843 1346/1346/2844 +f 1346/1346/2844 1318/1318/2843 1345/1345/2845 +f 1320/1320/2846 1316/1316/2847 1344/1344/2848 +f 1344/1344/2848 1316/1316/2847 1346/1346/2849 +f 1344/1344/101 1346/1346/101 1345/1345/101 +f 1344/1344/101 1345/1345/101 1343/1343/101 +f 1332/1332/2850 1325/1325/2771 1326/1326/2772 +f 1332/1332/2785 1326/1326/2851 1330/1330/2783 +f 1330/1330/2852 1326/1326/2852 1322/1322/2852 +f 1347/1347/2853 1348/1348/2854 1349/1349/2855 +f 1350/1350/2856 1348/1348/2854 1347/1347/2853 +f 1351/1351/2857 1352/1352/2858 1353/1353/2859 +f 1354/1354/2860 1355/1355/2861 1350/1350/2856 +f 1354/1354/2860 1356/1356/2862 1355/1355/2861 +f 1352/1352/2858 1357/1357/2863 1353/1353/2859 +f 1358/1358/2864 1352/1352/2858 1351/1351/2857 +f 1357/1357/2863 1356/1356/2862 1353/1353/2859 +f 1347/1347/2853 1349/1349/2855 1351/1351/2857 +f 1351/1351/2857 1349/1349/2855 1358/1358/2864 +f 1354/1354/2860 1350/1350/2856 1347/1347/2853 +f 1353/1353/2859 1356/1356/2862 1354/1354/2860 +f 1359/1359/2865 1360/1360/2866 1361/1361/2867 +f 1362/1362/2868 1363/1363/2869 1364/1364/2870 +f 1364/1364/2870 1363/1363/2869 1365/1365/2871 +f 1364/1364/2872 1365/1365/2873 1366/1366/2874 +f 1364/1364/2872 1366/1366/2874 1367/1367/2875 +f 1367/1367/2876 1366/1366/2876 1368/1368/2876 +f 1367/1367/2877 1368/1368/2877 1369/1369/2877 +f 1369/1369/2878 1368/1368/2879 1370/1370/2880 +f 1369/1369/2878 1370/1370/2880 1371/1371/2881 +f 1371/1371/2882 1370/1370/2883 1363/1363/2884 +f 1371/1371/2882 1363/1363/2884 1362/1362/2885 +f 1348/1348/2886 1362/1362/2887 1349/1349/2888 +f 1349/1349/2888 1362/1362/2887 1364/1364/2889 +f 1349/1349/2888 1364/1364/2889 1358/1358/2890 +f 1358/1358/2891 1364/1364/2892 1352/1352/2893 +f 1352/1352/2893 1364/1364/2892 1367/1367/2894 +f 1352/1352/2893 1367/1367/2894 1357/1357/2895 +f 1357/1357/2896 1367/1367/2897 1356/1356/2898 +f 1356/1356/2898 1367/1367/2897 1369/1369/2899 +f 1356/1356/2898 1369/1369/2899 1355/1355/2900 +f 1355/1355/2900 1369/1369/2899 1371/1371/2901 +f 1355/1355/2900 1371/1371/2901 1350/1350/2902 +f 1350/1350/2902 1371/1371/2901 1348/1348/2886 +f 1348/1348/2886 1371/1371/2901 1362/1362/2887 +f 1354/1354/2860 1347/1347/2853 1353/1353/2859 +f 1353/1353/2859 1347/1347/2853 1351/1351/2857 +f 1363/1363/2869 1361/1361/2903 1365/1365/2871 +f 1365/1365/2904 1361/1361/2867 1360/1360/2866 +f 1365/1365/2905 1360/1360/2905 1366/1366/2905 +f 1366/1366/2906 1360/1360/2906 1368/1368/2906 +f 1368/1368/2907 1360/1360/2866 1359/1359/2865 +f 1368/1368/2879 1359/1359/2908 1370/1370/2880 +f 1370/1370/2909 1359/1359/2910 1363/1363/2911 +f 1363/1363/2911 1359/1359/2910 1361/1361/2912 +f 1372/1372/2913 1373/1373/2914 1374/1374/2915 +f 1375/1375/2916 1376/1376/2917 1377/1377/2918 +f 1378/1378/2919 1379/1379/2920 1380/1380/2921 +f 1381/1381/2922 1373/1373/2914 1372/1372/2913 +f 1382/1382/2923 1373/1373/2914 1381/1381/2922 +f 1377/1377/2918 1379/1379/2920 1378/1378/2919 +f 1374/1374/2915 1383/1383/2924 1372/1372/2913 +f 1372/1372/2913 1383/1383/2924 1376/1376/2917 +f 1378/1378/2919 1380/1380/2921 1381/1381/2922 +f 1381/1381/2922 1380/1380/2921 1382/1382/2923 +f 1375/1375/2916 1377/1377/2918 1378/1378/2919 +f 1372/1372/2913 1376/1376/2917 1375/1375/2916 +f 1384/1384/2925 1385/1385/2926 1386/1386/2927 +f 1387/1387/2928 1388/1388/2929 1389/1389/2930 +f 1389/1389/2930 1388/1388/2929 1390/1390/2931 +f 1389/1389/2932 1390/1390/2933 1391/1391/2934 +f 1391/1391/2934 1390/1390/2933 1392/1392/2935 +f 1391/1391/2936 1392/1392/2936 1393/1393/2936 +f 1393/1393/2937 1392/1392/2938 1394/1394/2939 +f 1393/1393/2940 1394/1394/2940 1395/1395/2940 +f 1395/1395/2941 1394/1394/2942 1388/1388/2943 +f 1395/1395/2941 1388/1388/2943 1387/1387/2944 +f 1379/1379/2945 1387/1387/2946 1380/1380/2947 +f 1380/1380/2947 1387/1387/2946 1389/1389/2948 +f 1380/1380/2947 1389/1389/2948 1382/1382/2949 +f 1382/1382/2950 1389/1389/2951 1373/1373/2952 +f 1373/1373/2952 1389/1389/2951 1391/1391/2953 +f 1373/1373/2952 1391/1391/2953 1374/1374/2954 +f 1374/1374/2955 1391/1391/2956 1393/1393/2957 +f 1374/1374/2955 1393/1393/2957 1383/1383/2958 +f 1383/1383/2959 1393/1393/2959 1376/1376/2959 +f 1376/1376/2960 1393/1393/2961 1395/1395/2962 +f 1376/1376/2960 1395/1395/2962 1377/1377/2963 +f 1377/1377/2964 1395/1395/2965 1379/1379/2945 +f 1379/1379/2945 1395/1395/2965 1387/1387/2946 +f 1375/1375/2916 1378/1378/2919 1372/1372/2913 +f 1372/1372/2913 1378/1378/2919 1381/1381/2922 +f 1388/1388/2929 1386/1386/2966 1390/1390/2931 +f 1390/1390/2967 1386/1386/2927 1385/1385/2926 +f 1390/1390/2933 1385/1385/2968 1392/1392/2935 +f 1392/1392/2969 1385/1385/2969 1384/1384/2969 +f 1392/1392/2938 1384/1384/2970 1394/1394/2939 +f 1394/1394/2971 1384/1384/2972 1386/1386/2973 +f 1394/1394/2971 1386/1386/2973 1388/1388/2974 +f 1396/1396/2975 1397/1397/2976 1398/1398/2977 +f 1399/1399/2978 1400/1400/2979 1401/1401/2980 +f 1399/1399/2978 1402/1402/2981 1400/1400/2979 +f 1403/1403/2982 1396/1396/2975 1398/1398/2977 +f 1403/1403/2982 1404/1404/2983 1396/1396/2975 +f 1397/1397/2976 1405/1405/2984 1398/1398/2977 +f 1399/1399/2978 1401/1401/2980 1403/1403/2982 +f 1403/1403/2982 1401/1401/2980 1404/1404/2983 +f 1406/1406/2985 1402/1402/2981 1407/1407/2986 +f 1407/1407/2986 1402/1402/2981 1399/1399/2978 +f 1398/1398/2977 1405/1405/2984 1407/1407/2986 +f 1407/1407/2986 1405/1405/2984 1406/1406/2985 +f 1408/1408/2987 1409/1409/2988 1410/1410/2989 +f 1411/1411/2990 1412/1412/2990 1409/1409/2990 +f 1411/1411/2991 1409/1409/2992 1413/1413/2993 +f 1411/1411/2991 1413/1413/2993 1414/1414/2994 +f 1414/1414/2995 1413/1413/2996 1415/1415/2997 +f 1414/1414/2995 1415/1415/2997 1416/1416/2998 +f 1416/1416/2999 1415/1415/3000 1417/1417/3001 +f 1416/1416/2999 1417/1417/3001 1418/1418/3002 +f 1418/1418/3003 1417/1417/3004 1412/1412/3005 +f 1418/1418/3006 1412/1412/3006 1411/1411/3006 +f 1400/1400/3007 1411/1411/3007 1401/1401/3007 +f 1401/1401/3008 1411/1411/3009 1414/1414/3010 +f 1401/1401/3008 1414/1414/3010 1404/1404/3011 +f 1404/1404/3012 1414/1414/3012 1396/1396/3012 +f 1396/1396/3013 1414/1414/3014 1397/1397/3015 +f 1397/1397/3015 1414/1414/3014 1416/1416/3016 +f 1397/1397/3015 1416/1416/3016 1405/1405/3017 +f 1405/1405/3018 1416/1416/3019 1418/1418/3020 +f 1405/1405/3018 1418/1418/3020 1406/1406/3021 +f 1406/1406/3022 1418/1418/3022 1402/1402/3022 +f 1402/1402/3023 1418/1418/3024 1400/1400/3025 +f 1400/1400/3025 1418/1418/3024 1411/1411/3026 +f 1407/1407/2986 1399/1399/2978 1398/1398/2977 +f 1398/1398/2977 1399/1399/2978 1403/1403/2982 +f 1412/1412/3027 1410/1410/3027 1409/1409/3027 +f 1413/1413/3028 1409/1409/2988 1408/1408/2987 +f 1413/1413/2996 1408/1408/3029 1415/1415/2997 +f 1415/1415/3030 1408/1408/3031 1410/1410/3032 +f 1415/1415/3030 1410/1410/3032 1417/1417/3033 +f 1417/1417/3004 1410/1410/3034 1412/1412/3005 +f 1419/1419/3035 1420/1420/3036 1421/1421/3037 +f 1422/1422/3038 1423/1423/3039 1424/1424/3040 +f 1425/1425/3041 1426/1426/3042 1427/1427/3043 +f 1428/1428/3044 1419/1419/3035 1421/1421/3037 +f 1421/1421/3037 1420/1420/3036 1429/1429/3045 +f 1428/1428/3044 1430/1430/3046 1419/1419/3035 +f 1427/1427/3043 1423/1423/3039 1422/1422/3038 +f 1429/1429/3045 1426/1426/3042 1421/1421/3037 +f 1424/1424/3040 1430/1430/3046 1422/1422/3038 +f 1422/1422/3038 1430/1430/3046 1428/1428/3044 +f 1425/1425/3041 1427/1427/3043 1422/1422/3038 +f 1421/1421/3037 1426/1426/3042 1425/1425/3041 +f 1431/1431/3047 1432/1432/3048 1433/1433/3049 +f 1434/1434/3050 1432/1432/3050 1435/1435/3050 +f 1434/1434/3051 1435/1435/3051 1436/1436/3051 +f 1436/1436/3052 1435/1435/3053 1437/1437/3054 +f 1436/1436/3055 1437/1437/3056 1438/1438/3057 +f 1438/1438/3057 1437/1437/3056 1439/1439/3058 +f 1438/1438/3059 1439/1439/3060 1440/1440/3061 +f 1440/1440/3061 1439/1439/3060 1441/1441/3062 +f 1440/1440/3063 1441/1441/3064 1432/1432/3065 +f 1440/1440/3063 1432/1432/3065 1434/1434/3066 +f 1423/1423/3067 1434/1434/3068 1424/1424/3069 +f 1424/1424/3070 1434/1434/3071 1430/1430/3072 +f 1430/1430/3072 1434/1434/3071 1436/1436/3073 +f 1430/1430/3072 1436/1436/3073 1419/1419/3074 +f 1419/1419/3075 1436/1436/3075 1420/1420/3075 +f 1420/1420/3076 1436/1436/3077 1429/1429/3078 +f 1429/1429/3078 1436/1436/3077 1438/1438/3079 +f 1429/1429/3080 1438/1438/3081 1426/1426/3082 +f 1426/1426/3082 1438/1438/3081 1440/1440/3083 +f 1426/1426/3082 1440/1440/3083 1427/1427/3084 +f 1427/1427/3085 1440/1440/3086 1423/1423/3067 +f 1423/1423/3067 1440/1440/3086 1434/1434/3068 +f 1425/1425/3041 1422/1422/3038 1421/1421/3037 +f 1421/1421/3037 1422/1422/3038 1428/1428/3044 +f 1435/1435/3087 1432/1432/3048 1431/1431/3047 +f 1435/1435/3053 1431/1431/3088 1437/1437/3054 +f 1437/1437/3089 1431/1431/3090 1439/1439/3091 +f 1439/1439/3091 1431/1431/3090 1433/1433/3092 +f 1439/1439/3060 1433/1433/3093 1441/1441/3062 +f 1441/1441/3094 1433/1433/3094 1432/1432/3094 +f 1442/1442/3095 1443/1443/3096 1444/1444/3097 +f 1445/1445/3098 1446/1446/3099 1447/1447/3100 +f 1443/1443/3096 1442/1442/3095 1448/1448/3101 +f 1449/1449/3102 1445/1445/3098 1447/1447/3100 +f 1450/1450/3103 1451/1451/3104 1452/1452/3105 +f 1449/1449/3102 1453/1453/3106 1445/1445/3098 +f 1452/1452/3105 1448/1448/3101 1442/1442/3095 +f 1447/1447/3100 1446/1446/3099 1454/1454/3107 +f 1454/1454/3107 1451/1451/3104 1447/1447/3100 +f 1442/1442/3095 1444/1444/3097 1449/1449/3102 +f 1449/1449/3102 1444/1444/3097 1453/1453/3106 +f 1450/1450/3103 1452/1452/3105 1442/1442/3095 +f 1447/1447/3100 1451/1451/3104 1450/1450/3103 +f 1455/1455/3108 1456/1456/3109 1457/1457/3110 +f 1455/1455/3108 1458/1458/3111 1456/1456/3109 +f 1459/1459/3112 1460/1460/3113 1461/1461/3114 +f 1459/1459/3115 1461/1461/3116 1462/1462/3117 +f 1462/1462/3117 1461/1461/3116 1463/1463/3118 +f 1462/1462/3119 1463/1463/3120 1464/1464/3121 +f 1464/1464/3121 1463/1463/3120 1457/1457/3122 +f 1464/1464/3123 1457/1457/3124 1465/1465/3125 +f 1465/1465/3125 1457/1457/3124 1456/1456/3126 +f 1465/1465/3127 1456/1456/3128 1460/1460/3129 +f 1465/1465/3127 1460/1460/3129 1466/1466/3130 +f 1466/1466/3131 1460/1460/3113 1459/1459/3112 +f 1443/1443/3132 1459/1459/3133 1444/1444/3134 +f 1444/1444/3134 1459/1459/3133 1453/1453/3135 +f 1453/1453/3135 1459/1459/3133 1462/1462/3136 +f 1453/1453/3135 1462/1462/3136 1445/1445/3137 +f 1445/1445/3138 1462/1462/3139 1464/1464/3140 +f 1445/1445/3138 1464/1464/3140 1446/1446/3141 +f 1446/1446/3142 1464/1464/3143 1465/1465/3144 +f 1446/1446/3142 1465/1465/3144 1454/1454/3145 +f 1454/1454/3145 1465/1465/3144 1451/1451/3146 +f 1451/1451/3146 1465/1465/3144 1452/1452/3147 +f 1452/1452/3147 1465/1465/3144 1466/1466/3148 +f 1452/1452/3147 1466/1466/3148 1448/1448/3149 +f 1448/1448/3150 1466/1466/3151 1443/1443/3132 +f 1443/1443/3132 1466/1466/3151 1459/1459/3133 +f 1450/1450/3103 1442/1442/3095 1447/1447/3100 +f 1447/1447/3100 1442/1442/3095 1449/1449/3102 +f 1460/1460/3152 1458/1458/3153 1455/1455/3154 +f 1460/1460/3152 1455/1455/3154 1461/1461/3155 +f 1461/1461/3116 1455/1455/3156 1463/1463/3118 +f 1463/1463/3157 1455/1455/3108 1457/1457/3110 +f 1460/1460/3158 1456/1456/3158 1458/1458/3158 +f 1467/1467/3159 1468/1468/3160 1469/1469/3161 +f 1470/1470/3162 1471/1471/3163 1472/1472/3164 +f 1473/1473/3165 1474/1474/3166 1472/1472/3164 +f 1467/1467/3159 1475/1475/3167 1468/1468/3160 +f 1476/1476/3168 1471/1471/3163 1477/1477/3169 +f 1472/1472/3164 1474/1474/3166 1478/1478/3170 +f 1473/1473/3165 1479/1479/3171 1474/1474/3166 +f 1478/1478/3170 1470/1470/3162 1472/1472/3164 +f 1467/1467/3159 1469/1469/3161 1473/1473/3165 +f 1473/1473/3165 1469/1469/3161 1479/1479/3171 +f 1477/1477/3169 1475/1475/3167 1476/1476/3168 +f 1476/1476/3168 1475/1475/3167 1467/1467/3159 +f 1472/1472/3164 1471/1471/3163 1476/1476/3168 +f 1480/1480/3172 1481/1481/3173 1482/1482/3174 +f 1483/1483/3175 1482/1482/3176 1484/1484/3177 +f 1483/1483/3175 1484/1484/3177 1485/1485/3178 +f 1485/1485/3179 1484/1484/3180 1481/1481/3181 +f 1485/1485/3179 1481/1481/3181 1486/1486/3182 +f 1486/1486/3183 1481/1481/3183 1487/1487/3183 +f 1486/1486/3184 1487/1487/3184 1488/1488/3184 +f 1488/1488/3185 1487/1487/3186 1489/1489/3187 +f 1488/1488/3188 1489/1489/3188 1490/1490/3188 +f 1490/1490/3189 1489/1489/3190 1482/1482/3191 +f 1490/1490/3189 1482/1482/3191 1483/1483/3192 +f 1468/1468/3193 1483/1483/3194 1469/1469/3195 +f 1469/1469/3195 1483/1483/3194 1479/1479/3196 +f 1479/1479/3196 1483/1483/3194 1485/1485/3197 +f 1479/1479/3198 1485/1485/3199 1474/1474/3200 +f 1474/1474/3200 1485/1485/3199 1478/1478/3201 +f 1478/1478/3201 1485/1485/3199 1486/1486/3202 +f 1478/1478/3203 1486/1486/3204 1470/1470/3205 +f 1470/1470/3205 1486/1486/3204 1488/1488/3206 +f 1470/1470/3205 1488/1488/3206 1471/1471/3207 +f 1471/1471/3207 1488/1488/3206 1491/1491/3208 +f 1491/1491/3209 1488/1488/3210 1477/1477/3211 +f 1477/1477/3211 1488/1488/3210 1490/1490/3212 +f 1477/1477/3211 1490/1490/3212 1475/1475/3213 +f 1475/1475/3213 1490/1490/3212 1468/1468/3193 +f 1468/1468/3193 1490/1490/3212 1483/1483/3194 +f 1471/1471/3163 1491/1491/3214 1477/1477/3169 +f 1476/1476/3168 1467/1467/3159 1472/1472/3164 +f 1472/1472/3164 1467/1467/3159 1473/1473/3165 +f 1484/1484/3215 1482/1482/3174 1481/1481/3173 +f 1481/1481/3216 1480/1480/3216 1487/1487/3216 +f 1487/1487/3186 1480/1480/3217 1489/1489/3187 +f 1489/1489/3218 1480/1480/3218 1482/1482/3218 +f 1492/1492/3219 1493/1493/3220 1494/1494/3221 +f 1495/1495/3222 1496/1496/3223 1497/1497/3224 +f 1493/1493/3220 1492/1492/3219 1498/1498/3225 +f 1499/1499/3226 1495/1495/3222 1497/1497/3224 +f 1497/1497/3224 1496/1496/3223 1500/1500/3227 +f 1499/1499/3226 1494/1494/3221 1495/1495/3222 +f 1500/1500/3227 1501/1501/3228 1497/1497/3224 +f 1492/1492/3219 1494/1494/3221 1499/1499/3226 +f 1501/1501/3228 1498/1498/3225 1502/1502/3229 +f 1502/1502/3229 1498/1498/3225 1492/1492/3219 +f 1497/1497/3224 1501/1501/3228 1502/1502/3229 +f 1503/1503/3230 1504/1504/3231 1505/1505/3232 +f 1505/1505/3232 1504/1504/3231 1506/1506/3233 +f 1507/1507/3234 1508/1508/3234 1509/1509/3234 +f 1509/1509/3235 1508/1508/3236 1503/1503/3237 +f 1509/1509/3235 1503/1503/3237 1510/1510/3238 +f 1510/1510/3238 1503/1503/3237 1511/1511/3239 +f 1510/1510/3240 1511/1511/3240 1512/1512/3240 +f 1512/1512/3241 1511/1511/3242 1513/1513/3243 +f 1512/1512/3244 1513/1513/3245 1514/1514/3246 +f 1514/1514/3246 1513/1513/3245 1506/1506/3247 +f 1514/1514/3248 1506/1506/3249 1504/1504/3250 +f 1514/1514/3248 1504/1504/3250 1507/1507/3251 +f 1507/1507/3252 1504/1504/3252 1508/1508/3252 +f 1493/1493/3253 1507/1507/3254 1494/1494/3255 +f 1494/1494/3255 1507/1507/3254 1509/1509/3256 +f 1494/1494/3257 1509/1509/3258 1495/1495/3259 +f 1495/1495/3259 1509/1509/3258 1510/1510/3260 +f 1495/1495/3259 1510/1510/3260 1496/1496/3261 +f 1496/1496/3261 1510/1510/3260 1512/1512/3262 +f 1496/1496/3261 1512/1512/3262 1500/1500/3263 +f 1500/1500/3264 1512/1512/3265 1501/1501/3266 +f 1501/1501/3266 1512/1512/3265 1514/1514/3267 +f 1501/1501/3268 1514/1514/3269 1498/1498/3270 +f 1498/1498/3270 1514/1514/3269 1507/1507/3271 +f 1498/1498/3270 1507/1507/3271 1493/1493/3272 +f 1502/1502/3229 1492/1492/3219 1497/1497/3224 +f 1497/1497/3224 1492/1492/3219 1499/1499/3226 +f 1508/1508/3273 1504/1504/3231 1503/1503/3230 +f 1503/1503/3274 1505/1505/3274 1511/1511/3274 +f 1511/1511/3242 1505/1505/3275 1513/1513/3243 +f 1513/1513/3276 1505/1505/3276 1506/1506/3276 +f 1515/1515/3277 1516/1516/3278 1517/1517/3279 +f 1518/1518/3280 1519/1519/3281 1520/1520/3282 +f 1516/1516/3278 1518/1518/3280 1521/1521/3283 +f 1522/1522/3284 1523/1523/3283 1524/1524/3285 +f 1519/1519/3281 1525/1525/3283 1526/1526/3283 +f 1527/1527/3283 1528/1528/3283 1529/1529/3286 +f 1521/1521/3283 1518/1518/3280 1520/1520/3282 +f 1515/1515/3277 1517/1517/3279 1530/1530/3287 +f 1526/1526/3283 1531/1531/3283 1532/1532/3283 +f 1526/1526/3283 1525/1525/3283 1531/1531/3283 +f 1533/1533/3288 1534/1534/3283 1535/1535/3289 +f 1536/1536/3283 1521/1521/3283 1537/1537/3280 +f 1537/1537/3280 1538/1538/3283 1536/1536/3283 +f 1539/1539/3290 1540/1540/3283 1541/1541/3291 +f 1542/1542/3283 1543/1543/3291 1544/1544/3288 +f 1532/1532/3283 1545/1545/3283 1546/1546/3291 +f 1546/1546/3291 1523/1523/3283 1537/1537/3280 +f 1547/1547/3292 1522/1522/3284 1524/1524/3285 +f 1530/1530/3287 1536/1536/3283 1548/1548/3293 +f 1515/1515/3277 1530/1530/3287 1548/1548/3293 +f 1540/1540/3283 1529/1529/3286 1541/1541/3291 +f 1548/1548/3293 1538/1538/3283 1549/1549/3283 +f 1545/1545/3283 1532/1532/3283 1539/1539/3290 +f 1519/1519/3281 1518/1518/3280 1525/1525/3283 +f 1550/1550/3280 1543/1543/3291 1542/1542/3283 +f 1539/1539/3290 1541/1541/3291 1551/1551/3294 +f 1521/1521/3283 1520/1520/3282 1537/1537/3280 +f 1523/1523/3283 1542/1542/3283 1534/1534/3283 +f 1548/1548/3293 1549/1549/3283 1552/1552/3295 +f 1523/1523/3283 1546/1546/3291 1550/1550/3280 +f 1532/1532/3283 1540/1540/3283 1539/1539/3290 +f 1528/1528/3283 1527/1527/3283 1525/1525/3283 +f 1547/1547/3292 1548/1548/3293 1552/1552/3295 +f 1516/1516/3278 1515/1515/3277 1518/1518/3280 +f 1532/1532/3283 1546/1546/3291 1526/1526/3283 +f 1545/1545/3283 1550/1550/3280 1546/1546/3291 +f 1523/1523/3283 1538/1538/3283 1537/1537/3280 +f 1552/1552/3295 1522/1522/3284 1547/1547/3292 +f 1553/1553/3283 1551/1551/3294 1541/1541/3291 +f 1527/1527/3283 1531/1531/3283 1525/1525/3283 +f 1529/1529/3286 1528/1528/3283 1541/1541/3291 +f 1553/1553/3283 1554/1554/3291 1544/1544/3288 +f 1534/1534/3283 1524/1524/3285 1523/1523/3283 +f 1553/1553/3283 1544/1544/3288 1543/1543/3291 +f 1533/1533/3288 1524/1524/3285 1534/1534/3283 +f 1555/1555/3291 1542/1542/3283 1544/1544/3288 +f 1554/1554/3291 1541/1541/3291 1556/1556/3283 +f 1535/1535/3289 1557/1557/3296 1533/1533/3288 +f 1541/1541/3291 1558/1558/3291 1556/1556/3283 +f 1555/1555/3291 1544/1544/3288 1559/1559/3297 +f 1559/1559/3297 1558/1558/3291 1555/1555/3291 +f 1557/1557/3296 1560/1560/3298 1533/1533/3288 +f 1558/1558/3291 1561/1561/3291 1555/1555/3291 +f 1561/1561/3291 1557/1557/3296 1535/1535/3289 +f 1562/1562/3288 1558/1558/3291 1559/1559/3297 +f 1557/1557/3296 1563/1563/3299 1560/1560/3298 +f 1560/1560/3298 1563/1563/3299 1564/1564/3300 +f 1547/1547/3292 1564/1564/3300 1563/1563/3299 +f 1562/1562/3288 1556/1556/3283 1558/1558/3291 +f 1523/1523/3283 1550/1550/3280 1542/1542/3283 +f 1553/1553/3283 1541/1541/3291 1554/1554/3291 +f 1548/1548/3293 1536/1536/3283 1538/1538/3283 +f 1558/1558/3291 1557/1557/3296 1561/1561/3291 +f 1539/1539/3301 1565/1565/3301 1545/1545/3301 +f 1566/1566/3302 1551/1551/3303 1553/1553/3304 +f 1567/1567/3305 1551/1551/3303 1566/1566/3302 +f 1567/1567/3306 1539/1539/3307 1551/1551/3308 +f 1565/1565/3309 1539/1539/3307 1567/1567/3306 +f 1568/1568/3310 1552/1552/3311 1569/1569/3312 +f 1568/1568/3313 1522/1522/3314 1552/1552/3315 +f 1570/1570/3316 1522/1522/3314 1568/1568/3313 +f 1570/1570/3317 1523/1523/3318 1522/1522/3319 +f 1571/1571/3320 1523/1523/3318 1570/1570/3317 +f 1572/1572/3321 1523/1523/3322 1571/1571/3323 +f 1572/1572/3321 1538/1538/3324 1523/1523/3322 +f 1573/1573/3325 1538/1538/3325 1572/1572/3325 +f 1573/1573/3326 1549/1549/3326 1538/1538/3326 +f 1569/1569/3327 1549/1549/3327 1573/1573/3327 +f 1569/1569/3312 1552/1552/3311 1549/1549/3328 +f 1574/1574/3329 1575/1575/3330 1576/1576/3331 +f 1574/1574/3329 1577/1577/3332 1575/1575/3330 +f 1578/1578/3333 1579/1579/3334 1580/1580/3335 +f 1578/1578/3336 1580/1580/3337 1577/1577/3338 +f 1578/1578/3336 1577/1577/3338 1574/1574/3339 +f 1581/1581/3340 1582/1582/3341 1583/1583/3342 +f 1577/1577/3343 1582/1582/3341 1581/1581/3340 +f 1580/1580/3344 1582/1582/3341 1577/1577/3343 +f 1583/1583/3342 1584/1584/3345 1581/1581/3340 +f 1584/1584/3346 1585/1585/3347 1581/1581/3348 +f 1586/1586/3349 1587/1587/3350 1588/1588/3351 +f 1589/1589/3352 1590/1590/3353 1591/1591/3354 +f 1589/1589/3352 1592/1592/3355 1590/1590/3353 +f 1588/1588/3351 1587/1587/3350 1591/1591/3354 +f 1588/1588/3351 1591/1591/3354 1590/1590/3353 +f 1593/1593/3356 1588/1588/3351 1585/1585/3347 +f 1585/1585/3347 1588/1588/3351 1590/1590/3353 +f 1584/1584/3346 1593/1593/3356 1585/1585/3347 +f 1592/1592/3355 1594/1594/3357 1590/1590/3353 +f 1595/1595/3358 1578/1578/3359 1574/1574/3360 +f 1594/1594/3361 1595/1595/3358 1574/1574/3360 +f 1594/1594/3361 1596/1596/3362 1595/1595/3358 +f 1594/1594/3361 1592/1592/3363 1596/1596/3362 +f 1594/1594/3364 1558/1558/3364 1590/1590/3364 +f 1528/1528/3365 1581/1581/3365 1585/1585/3365 +f 1563/1563/3366 1574/1574/3367 1576/1576/3368 +f 1594/1594/3369 1557/1557/3370 1558/1558/3371 +f 1574/1574/3367 1557/1557/3370 1594/1594/3369 +f 1574/1574/3367 1563/1563/3366 1557/1557/3370 +f 1577/1577/3372 1515/1515/3373 1575/1575/3374 +f 1577/1577/3372 1518/1518/3375 1515/1515/3373 +f 1581/1581/3376 1518/1518/3375 1577/1577/3372 +f 1581/1581/3376 1525/1525/3377 1518/1518/3375 +f 1581/1581/3376 1528/1528/3378 1525/1525/3377 +f 1585/1585/3379 1541/1541/3380 1528/1528/3381 +f 1590/1590/3382 1541/1541/3380 1585/1585/3379 +f 1590/1590/3382 1558/1558/3383 1541/1541/3380 +f 1597/1597/3384 1583/1583/3385 1598/1598/3386 +f 1597/1597/3384 1599/1599/3387 1583/1583/3385 +f 1582/1582/3388 1600/1600/3389 1601/1601/3390 +f 1597/1597/3384 1602/1602/3391 1603/1603/3392 +f 1603/1603/3392 1600/1600/3389 1582/1582/3388 +f 1604/1604/3393 1600/1600/3389 1603/1603/3392 +f 1603/1603/3392 1602/1602/3391 1604/1604/3393 +f 1597/1597/3384 1605/1605/3394 1602/1602/3391 +f 1582/1582/3388 1601/1601/3390 1583/1583/3385 +f 1598/1598/3386 1605/1605/3394 1597/1597/3384 +f 1601/1601/3390 1598/1598/3386 1583/1583/3385 +f 1586/1586/3349 1597/1597/3384 1565/1565/3395 +f 1606/1606/3396 1597/1597/3384 1586/1586/3349 +f 1607/1607/3397 1603/1603/3392 1608/1608/3398 +f 1609/1609/3388 1610/1610/3399 1597/1597/3384 +f 1609/1609/3388 1566/1566/3400 1611/1611/3401 +f 1586/1586/3349 1566/1566/3400 1609/1609/3388 +f 1586/1586/3349 1567/1567/3395 1566/1566/3400 +f 1586/1586/3349 1565/1565/3395 1567/1567/3395 +f 1610/1610/3399 1565/1565/3395 1597/1597/3384 +f 1609/1609/3388 1611/1611/3401 1610/1610/3399 +f 1608/1608/3398 1569/1569/3401 1573/1573/3402 +f 1579/1579/3334 1570/1570/3399 1568/1568/3403 +f 1579/1579/3334 1612/1612/3404 1570/1570/3399 +f 1579/1579/3334 1613/1613/3405 1612/1612/3404 +f 1614/1614/3406 1613/1613/3405 1579/1579/3334 +f 1608/1608/3398 1573/1573/3402 1607/1607/3397 +f 1579/1579/3334 1569/1569/3401 1608/1608/3398 +f 1568/1568/3403 1569/1569/3401 1579/1579/3334 +f 1607/1607/3397 1573/1573/3402 1572/1572/3407 +f 1612/1612/3404 1571/1571/3400 1570/1570/3399 +f 1607/1607/3397 1571/1571/3400 1612/1612/3404 +f 1572/1572/3407 1571/1571/3400 1607/1607/3397 +f 1596/1596/3408 1609/1609/3388 1615/1615/3409 +f 1596/1596/3408 1616/1616/3410 1609/1609/3388 +f 1617/1617/3411 1618/1618/3412 1619/1619/3413 +f 1595/1595/3414 1618/1618/3412 1617/1617/3411 +f 1620/1620/3415 1618/1618/3412 1595/1595/3414 +f 1609/1609/3388 1621/1621/3416 1615/1615/3409 +f 1609/1609/3388 1619/1619/3413 1621/1621/3416 +f 1617/1617/3411 1619/1619/3413 1609/1609/3388 +f 1595/1595/3414 1622/1622/3417 1620/1620/3415 +f 1596/1596/3408 1622/1622/3417 1595/1595/3414 +f 1615/1615/3409 1622/1622/3417 1596/1596/3408 +f 1613/1613/3405 1617/1617/3411 1612/1612/3404 +f 1595/1595/3414 1623/1623/3418 1578/1578/3333 +f 1624/1624/3419 1578/1578/3333 1623/1623/3418 +f 1595/1595/3414 1625/1625/3420 1623/1623/3418 +f 1578/1578/3333 1626/1626/3421 1579/1579/3334 +f 1578/1578/3333 1624/1624/3419 1626/1626/3421 +f 1579/1579/3334 1626/1626/3421 1614/1614/3406 +f 1595/1595/3414 1627/1627/3422 1625/1625/3420 +f 1617/1617/3411 1627/1627/3422 1595/1595/3414 +f 1627/1627/3422 1617/1617/3411 1613/1613/3405 +f 1603/1603/3392 1628/1628/3423 1608/1608/3398 +f 1579/1579/3334 1629/1629/3424 1630/1630/3425 +f 1608/1608/3398 1629/1629/3424 1579/1579/3334 +f 1580/1580/3335 1630/1630/3425 1631/1631/3426 +f 1579/1579/3334 1630/1630/3425 1580/1580/3335 +f 1580/1580/3335 1632/1632/3427 1582/1582/3388 +f 1580/1580/3335 1631/1631/3426 1632/1632/3427 +f 1603/1603/3392 1633/1633/3428 1628/1628/3423 +f 1582/1582/3388 1633/1633/3428 1603/1603/3392 +f 1632/1632/3427 1633/1633/3428 1582/1582/3388 +f 1634/1634/3429 1606/1606/3396 1586/1586/3349 +f 1584/1584/3430 1635/1635/3431 1593/1593/3432 +f 1583/1583/3385 1635/1635/3431 1584/1584/3430 +f 1597/1597/3384 1606/1606/3396 1599/1599/3387 +f 1583/1583/3385 1599/1599/3387 1636/1636/3433 +f 1634/1634/3429 1586/1586/3349 1588/1588/3351 +f 1636/1636/3433 1635/1635/3431 1583/1583/3385 +f 1637/1637/3434 1587/1587/3435 1586/1586/3349 +f 1596/1596/3408 1638/1638/3436 1639/1639/3437 +f 1592/1592/3438 1638/1638/3436 1596/1596/3408 +f 1609/1609/3388 1637/1637/3434 1586/1586/3349 +f 1609/1609/3388 1640/1640/3411 1637/1637/3434 +f 1592/1592/3438 1589/1589/3439 1638/1638/3436 +f 1596/1596/3408 1639/1639/3437 1616/1616/3410 +f 1616/1616/3410 1640/1640/3411 1609/1609/3388 +f 1575/1575/3440 1563/1563/3299 1576/1576/3441 +f 1515/1515/3277 1563/1563/3299 1575/1575/3440 +f 1548/1548/3293 1563/1563/3299 1515/1515/3277 +f 1548/1548/3293 1547/1547/3292 1563/1563/3299 +f 1641/1641/3399 1642/1642/3397 1643/1643/3442 +f 1644/1644/3399 1642/1642/3397 1641/1641/3399 +f 1645/1645/3395 1642/1642/3397 1644/1644/3399 +f 1645/1645/3395 1644/1644/3399 1646/1646/3399 +f 1642/1642/3443 1617/1617/3444 1643/1643/3445 +f 1642/1642/3443 1612/1612/3446 1617/1617/3444 +f 1607/1607/3447 1642/1642/3448 1645/1645/3449 +f 1612/1612/3450 1642/1642/3448 1607/1607/3447 +f 1645/1645/3451 1603/1603/3451 1607/1607/3451 +f 1603/1603/3452 1646/1646/3453 1597/1597/3454 +f 1603/1603/3452 1645/1645/3455 1646/1646/3453 +f 1644/1644/3456 1597/1597/3456 1646/1646/3456 +f 1609/1609/3457 1644/1644/3458 1641/1641/3459 +f 1597/1597/3460 1644/1644/3458 1609/1609/3457 +f 1617/1617/3461 1641/1641/3462 1643/1643/3463 +f 1609/1609/3464 1641/1641/3462 1617/1617/3461 +f 1637/1637/3465 1647/1647/3466 1587/1587/3467 +f 1648/1648/3468 1647/1647/3466 1637/1637/3465 +f 1640/1640/3469 1648/1648/3468 1637/1637/3465 +f 1616/1616/3470 1648/1648/3471 1640/1640/3472 +f 1616/1616/3470 1649/1649/3473 1648/1648/3471 +f 1616/1616/3474 1650/1650/3475 1649/1649/3476 +f 1639/1639/3477 1650/1650/3475 1616/1616/3474 +f 1638/1638/3478 1650/1650/3479 1639/1639/3480 +f 1638/1638/3478 1651/1651/3481 1650/1650/3479 +f 1589/1589/3482 1651/1651/3481 1638/1638/3478 +f 1652/1652/3483 1651/1651/3481 1589/1589/3482 +f 1591/1591/3484 1652/1652/3483 1589/1589/3482 +f 1591/1591/3484 1647/1647/3466 1652/1652/3483 +f 1587/1587/3467 1647/1647/3466 1591/1591/3484 +f 1556/1556/3485 1652/1652/3485 1647/1647/3485 +f 1652/1652/3486 1562/1562/3487 1651/1651/3488 +f 1652/1652/3486 1556/1556/3489 1562/1562/3487 +f 1650/1650/3490 1651/1651/3491 1562/1562/3492 +f 1650/1650/3490 1562/1562/3492 1559/1559/3493 +f 1649/1649/3494 1650/1650/3495 1559/1559/3496 +f 1649/1649/3494 1559/1559/3496 1544/1544/3497 +f 1648/1648/3498 1649/1649/3498 1544/1544/3498 +f 1554/1554/3499 1648/1648/3499 1544/1544/3499 +f 1554/1554/3500 1647/1647/3500 1648/1648/3500 +f 1647/1647/3501 1554/1554/3501 1556/1556/3501 +f 1621/1621/3502 1653/1653/3503 1615/1615/3504 +f 1621/1621/3502 1654/1654/3505 1653/1653/3503 +f 1619/1619/3506 1654/1654/3507 1621/1621/3508 +f 1655/1655/3509 1654/1654/3507 1619/1619/3506 +f 1619/1619/3510 1656/1656/3511 1655/1655/3512 +f 1618/1618/3513 1656/1656/3511 1619/1619/3510 +f 1618/1618/3514 1657/1657/3515 1656/1656/3516 +f 1620/1620/3517 1657/1657/3515 1618/1618/3514 +f 1658/1658/3518 1657/1657/3519 1620/1620/3520 +f 1622/1622/3521 1658/1658/3518 1620/1620/3520 +f 1622/1622/3522 1653/1653/3523 1658/1658/3524 +f 1615/1615/3525 1653/1653/3523 1622/1622/3522 +f 1658/1658/3526 1653/1653/3527 1555/1555/3528 +f 1658/1658/3526 1555/1555/3528 1561/1561/3529 +f 1561/1561/3530 1657/1657/3531 1658/1658/3532 +f 1657/1657/3531 1561/1561/3530 1535/1535/3533 +f 1656/1656/3534 1657/1657/3535 1535/1535/3536 +f 1656/1656/3534 1535/1535/3536 1534/1534/3537 +f 1534/1534/3538 1655/1655/3538 1656/1656/3538 +f 1542/1542/3539 1655/1655/3540 1534/1534/3541 +f 1542/1542/3539 1654/1654/3542 1655/1655/3540 +f 1653/1653/3543 1654/1654/3544 1542/1542/3545 +f 1653/1653/3543 1542/1542/3545 1555/1555/3546 +f 1627/1627/3547 1659/1659/3548 1625/1625/3549 +f 1660/1660/3550 1659/1659/3548 1627/1627/3547 +f 1613/1613/3551 1660/1660/3550 1627/1627/3547 +f 1614/1614/3552 1660/1660/3553 1613/1613/3554 +f 1661/1661/3555 1660/1660/3553 1614/1614/3552 +f 1661/1661/3555 1614/1614/3552 1626/1626/3556 +f 1626/1626/3556 1662/1662/3557 1661/1661/3555 +f 1624/1624/3558 1662/1662/3557 1626/1626/3556 +f 1663/1663/3559 1662/1662/3560 1624/1624/3561 +f 1623/1623/3562 1663/1663/3559 1624/1624/3561 +f 1625/1625/3563 1663/1663/3564 1623/1623/3565 +f 1625/1625/3563 1664/1664/3566 1663/1663/3564 +f 1625/1625/3549 1659/1659/3548 1664/1664/3567 +f 1533/1533/3568 1664/1664/3569 1659/1659/3570 +f 1664/1664/3569 1533/1533/3568 1560/1560/3571 +f 1663/1663/3572 1664/1664/3572 1560/1560/3572 +f 1663/1663/3573 1560/1560/3573 1564/1564/3573 +f 1564/1564/3574 1662/1662/3574 1663/1663/3574 +f 1547/1547/3575 1662/1662/3576 1564/1564/3577 +f 1661/1661/3578 1662/1662/3576 1547/1547/3575 +f 1524/1524/3579 1661/1661/3580 1547/1547/3581 +f 1524/1524/3579 1660/1660/3582 1661/1661/3580 +f 1659/1659/3583 1524/1524/3584 1533/1533/3585 +f 1660/1660/3586 1524/1524/3584 1659/1659/3583 +f 1598/1598/3587 1665/1665/3588 1605/1605/3589 +f 1598/1598/3587 1666/1666/3590 1665/1665/3588 +f 1601/1601/3591 1666/1666/3592 1598/1598/3593 +f 1667/1667/3594 1666/1666/3592 1601/1601/3591 +f 1601/1601/3595 1668/1668/3596 1667/1667/3597 +f 1600/1600/3598 1668/1668/3596 1601/1601/3595 +f 1669/1669/3599 1668/1668/3600 1600/1600/3601 +f 1604/1604/3602 1669/1669/3599 1600/1600/3601 +f 1604/1604/3602 1670/1670/3603 1669/1669/3599 +f 1602/1602/3604 1670/1670/3603 1604/1604/3602 +f 1665/1665/3605 1670/1670/3606 1602/1602/3607 +f 1605/1605/3608 1665/1665/3605 1602/1602/3607 +f 1526/1526/3609 1665/1665/3609 1666/1666/3609 +f 1546/1546/3610 1665/1665/3610 1526/1526/3610 +f 1546/1546/3611 1670/1670/3611 1665/1665/3611 +f 1670/1670/3612 1546/1546/3612 1537/1537/3612 +f 1669/1669/3613 1670/1670/3613 1537/1537/3613 +f 1669/1669/3614 1520/1520/3615 1668/1668/3616 +f 1669/1669/3614 1537/1537/3617 1520/1520/3615 +f 1520/1520/3618 1667/1667/3618 1668/1668/3618 +f 1519/1519/3619 1667/1667/3619 1520/1520/3619 +f 1667/1667/3620 1519/1519/3620 1666/1666/3620 +f 1526/1526/3621 1666/1666/3621 1519/1519/3621 +f 1628/1628/3622 1671/1671/3623 1672/1672/3624 +f 1633/1633/3625 1671/1671/3623 1628/1628/3622 +f 1632/1632/3626 1671/1671/3627 1633/1633/3628 +f 1632/1632/3626 1673/1673/3629 1671/1671/3627 +f 1631/1631/3630 1673/1673/3631 1632/1632/3632 +f 1631/1631/3630 1674/1674/3633 1673/1673/3631 +f 1630/1630/3634 1674/1674/3633 1631/1631/3630 +f 1630/1630/3634 1675/1675/3635 1674/1674/3633 +f 1629/1629/3636 1675/1675/3635 1630/1630/3634 +f 1676/1676/3637 1675/1675/3635 1629/1629/3636 +f 1608/1608/3638 1676/1676/3637 1629/1629/3636 +f 1628/1628/3639 1676/1676/3640 1608/1608/3641 +f 1672/1672/3642 1676/1676/3640 1628/1628/3639 +f 1521/1521/3643 1672/1672/3643 1671/1671/3643 +f 1536/1536/3644 1672/1672/3644 1521/1521/3644 +f 1672/1672/3645 1536/1536/3645 1676/1676/3645 +f 1676/1676/3646 1536/1536/3647 1530/1530/3648 +f 1675/1675/3649 1676/1676/3646 1530/1530/3648 +f 1517/1517/3650 1675/1675/3651 1530/1530/3652 +f 1517/1517/3650 1674/1674/3653 1675/1675/3651 +f 1673/1673/3654 1674/1674/3654 1517/1517/3654 +f 1516/1516/3655 1673/1673/3655 1517/1517/3655 +f 1671/1671/3656 1673/1673/3656 1516/1516/3656 +f 1521/1521/3657 1671/1671/3657 1516/1516/3657 +f 1677/1677/3658 1593/1593/3659 1678/1678/3660 +f 1635/1635/3661 1678/1678/3660 1593/1593/3659 +f 1635/1635/3661 1679/1679/3662 1678/1678/3660 +f 1636/1636/3663 1679/1679/3662 1635/1635/3661 +f 1636/1636/3663 1680/1680/3664 1679/1679/3662 +f 1599/1599/3665 1680/1680/3664 1636/1636/3663 +f 1599/1599/3666 1681/1681/3667 1680/1680/3668 +f 1606/1606/3669 1681/1681/3667 1599/1599/3666 +f 1606/1606/3669 1682/1682/3670 1681/1681/3667 +f 1634/1634/3671 1682/1682/3670 1606/1606/3669 +f 1634/1634/3671 1683/1683/3672 1682/1682/3670 +f 1588/1588/3673 1683/1683/3672 1634/1634/3671 +f 1588/1588/3673 1677/1677/3658 1683/1683/3672 +f 1593/1593/3659 1677/1677/3658 1588/1588/3673 +f 1529/1529/3674 1683/1683/3674 1677/1677/3674 +f 1540/1540/3675 1683/1683/3675 1529/1529/3675 +f 1683/1683/3676 1540/1540/3676 1682/1682/3676 +f 1681/1681/3677 1682/1682/3678 1540/1540/3679 +f 1681/1681/3677 1540/1540/3679 1532/1532/3680 +f 1680/1680/3681 1681/1681/3681 1532/1532/3681 +f 1680/1680/3682 1532/1532/3682 1531/1531/3682 +f 1679/1679/3683 1680/1680/3683 1531/1531/3683 +f 1527/1527/3684 1679/1679/3685 1531/1531/3686 +f 1678/1678/3687 1679/1679/3685 1527/1527/3684 +f 1529/1529/3688 1678/1678/3689 1527/1527/3690 +f 1529/1529/3688 1677/1677/3691 1678/1678/3689 +f 1543/1543/3692 1566/1566/3693 1553/1553/3694 +f 1611/1611/3695 1566/1566/3693 1543/1543/3692 +f 1610/1610/3696 1545/1545/3697 1565/1565/3698 +f 1610/1610/3696 1550/1550/3699 1545/1545/3697 +f 1610/1610/3700 1543/1543/3701 1550/1550/3702 +f 1611/1611/3703 1543/1543/3701 1610/1610/3700 +f 1684/1684/3704 1685/1685/3705 1686/1686/3706 +f 1687/1687/3707 1688/1688/3708 1689/1689/3709 +f 1687/1687/3707 1690/1690/3710 1688/1688/3708 +f 1691/1691/3711 1686/1686/3706 1687/1687/3707 +f 1691/1691/3711 1692/1692/3712 1686/1686/3706 +f 1690/1690/3710 1687/1687/3707 1693/1693/3713 +f 1694/1694/3714 1695/1695/3715 1693/1693/3713 +f 1693/1693/3713 1695/1695/3715 1696/1696/3716 +f 1686/1686/3706 1692/1692/3712 1684/1684/3704 +f 1687/1687/3707 1689/1689/3709 1691/1691/3711 +f 1693/1693/3713 1696/1696/3716 1690/1690/3710 +f 1686/1686/3706 1685/1685/3705 1694/1694/3714 +f 1686/1686/3706 1694/1694/3714 1693/1693/3713 +f 1697/1697/3717 1698/1698/3718 1699/1699/3719 +f 1697/1697/3717 1700/1700/3720 1698/1698/3718 +f 1697/1697/3717 1699/1699/3719 1701/1701/3721 +f 1702/1702/3722 1699/1699/3723 1698/1698/3724 +f 1702/1702/3725 1698/1698/3726 1703/1703/3727 +f 1702/1702/3725 1703/1703/3727 1704/1704/3728 +f 1704/1704/3729 1703/1703/3730 1705/1705/3731 +f 1704/1704/3729 1705/1705/3731 1706/1706/3732 +f 1706/1706/3733 1705/1705/3734 1697/1697/3735 +f 1706/1706/3733 1697/1697/3735 1707/1707/3736 +f 1707/1707/3737 1697/1697/3738 1708/1708/3739 +f 1707/1707/3737 1708/1708/3739 1709/1709/3740 +f 1709/1709/3741 1708/1708/3742 1710/1710/3743 +f 1709/1709/3741 1710/1710/3743 1711/1711/3744 +f 1711/1711/3745 1710/1710/3746 1699/1699/3723 +f 1711/1711/3745 1699/1699/3723 1702/1702/3722 +f 1690/1690/3747 1702/1702/3748 1688/1688/3749 +f 1688/1688/3749 1702/1702/3748 1689/1689/3750 +f 1689/1689/3750 1702/1702/3748 1704/1704/3751 +f 1689/1689/3750 1704/1704/3751 1691/1691/3752 +f 1691/1691/3752 1704/1704/3751 1692/1692/3753 +f 1692/1692/3753 1704/1704/3751 1706/1706/3754 +f 1692/1692/3753 1706/1706/3754 1684/1684/3755 +f 1684/1684/3755 1706/1706/3754 1707/1707/3756 +f 1684/1684/3755 1707/1707/3756 1685/1685/3757 +f 1685/1685/3757 1707/1707/3756 1709/1709/3758 +f 1685/1685/3757 1709/1709/3758 1694/1694/3759 +f 1694/1694/3759 1709/1709/3758 1695/1695/3760 +f 1695/1695/3760 1709/1709/3758 1711/1711/3761 +f 1695/1695/3760 1711/1711/3761 1696/1696/3762 +f 1696/1696/3763 1711/1711/3764 1702/1702/3748 +f 1696/1696/3763 1702/1702/3748 1690/1690/3747 +f 1687/1687/3765 1686/1686/3766 1712/1712/3767 +f 1712/1712/3767 1686/1686/3766 1713/1713/3768 +f 1693/1693/3769 1687/1687/3770 1714/1714/3771 +f 1714/1714/3771 1687/1687/3770 1712/1712/3772 +f 1686/1686/3773 1693/1693/3774 1713/1713/3775 +f 1713/1713/3775 1693/1693/3774 1714/1714/3776 +f 1712/1712/3395 1713/1713/3395 1714/1714/3395 +f 1703/1703/3777 1698/1698/3777 1700/1700/3777 +f 1703/1703/3730 1700/1700/3778 1705/1705/3731 +f 1705/1705/3779 1700/1700/3779 1697/1697/3779 +f 1708/1708/3780 1697/1697/3780 1701/1701/3780 +f 1708/1708/3742 1701/1701/3781 1710/1710/3743 +f 1710/1710/3782 1701/1701/3721 1699/1699/3719 +f 1715/1715/3783 1716/1716/3784 1717/1717/3785 +f 1717/1717/3785 1716/1716/3784 1718/1718/3786 +f 1715/1715/3783 1719/1719/3787 1716/1716/3784 +f 1720/1720/3788 1721/1721/3789 1719/1719/3790 +f 1720/1720/3788 1719/1719/3790 1715/1715/3791 +f 1722/1722/3792 1721/1721/3793 1720/1720/3794 +f 1722/1722/3792 1723/1723/3795 1721/1721/3793 +f 1724/1724/3796 1723/1723/3795 1722/1722/3792 +f 1724/1724/3796 1725/1725/3797 1723/1723/3795 +f 1726/1726/3798 1725/1725/3799 1724/1724/3800 +f 1726/1726/3798 1727/1727/3801 1725/1725/3799 +f 1728/1728/3802 1727/1727/3801 1726/1726/3798 +f 1728/1728/3802 1729/1729/3803 1727/1727/3801 +f 1730/1730/3804 1729/1729/3803 1728/1728/3802 +f 1717/1717/3805 1718/1718/3806 1730/1730/3804 +f 1730/1730/3804 1718/1718/3806 1729/1729/3803 +f 1722/1722/3792 1731/1731/3807 1724/1724/3796 +f 1722/1722/3792 1720/1720/3794 1732/1732/3808 +f 1732/1732/3809 1720/1720/3788 1733/1733/3810 +f 1733/1733/3810 1720/1720/3788 1715/1715/3791 +f 1733/1733/3811 1715/1715/3783 1734/1734/3812 +f 1734/1734/3812 1715/1715/3783 1717/1717/3785 +f 1734/1734/3813 1717/1717/3805 1730/1730/3804 +f 1735/1735/3814 1730/1730/3804 1728/1728/3802 +f 1735/1735/3815 1728/1728/3815 1726/1726/3815 +f 1736/1736/3816 1726/1726/3798 1724/1724/3800 +f 1736/1736/3817 1724/1724/3817 1731/1731/3817 +f 1737/1737/3818 1731/1731/3819 1722/1722/3820 +f 1726/1726/3821 1738/1738/3822 1735/1735/3823 +f 1730/1730/3824 1739/1739/3825 1734/1734/3826 +f 1730/1730/3824 1735/1735/3823 1739/1739/3825 +f 1734/1734/3826 1739/1739/3825 1733/1733/3827 +f 1722/1722/3820 1732/1732/3828 1737/1737/3818 +f 1731/1731/3819 1737/1737/3818 1736/1736/3829 +f 1736/1736/3829 1738/1738/3822 1726/1726/3821 +f 1737/1737/3818 1738/1738/3822 1736/1736/3829 +f 1733/1733/3827 1740/1740/3830 1732/1732/3828 +f 1732/1732/3828 1740/1740/3830 1737/1737/3818 +f 1738/1738/3822 1739/1739/3825 1735/1735/3823 +f 1733/1733/3827 1739/1739/3825 1740/1740/3830 +f 1738/1738/3822 1737/1737/3818 1740/1740/3830 +f 1738/1738/3822 1740/1740/3830 1739/1739/3825 +f 1741/1741/3831 1742/1742/3832 1743/1743/3833 +f 1743/1743/3833 1718/1718/3834 1716/1716/3835 +f 1716/1716/3835 1719/1719/3836 1743/1743/3833 +f 1742/1742/3832 1718/1718/3834 1743/1743/3833 +f 1744/1744/3837 1718/1718/3834 1742/1742/3832 +f 1744/1744/3837 1729/1729/3838 1718/1718/3834 +f 1727/1727/3839 1729/1729/3838 1744/1744/3837 +f 1745/1745/3840 1727/1727/3839 1744/1744/3837 +f 1745/1745/3840 1744/1744/3837 1742/1742/3832 +f 1725/1725/3841 1727/1727/3839 1745/1745/3840 +f 1741/1741/3831 1745/1745/3840 1742/1742/3832 +f 1723/1723/3842 1725/1725/3841 1745/1745/3840 +f 1723/1723/3842 1745/1745/3840 1741/1741/3831 +f 1721/1721/3843 1723/1723/3842 1741/1741/3831 +f 1743/1743/3833 1721/1721/3843 1741/1741/3831 +f 1719/1719/3836 1721/1721/3843 1743/1743/3833 +f 1746/1746/3844 1747/1747/3845 1748/1748/3846 +f 1748/1748/3846 1747/1747/3845 1749/1749/3847 +f 1750/1750/3848 1747/1747/3845 1746/1746/3844 +f 1750/1750/3848 1751/1751/3849 1747/1747/3845 +f 1752/1752/3850 1753/1753/3851 1750/1750/3852 +f 1750/1750/3852 1753/1753/3851 1751/1751/3853 +f 1754/1754/3854 1755/1755/3855 1752/1752/3850 +f 1752/1752/3850 1755/1755/3855 1753/1753/3856 +f 1754/1754/3854 1756/1756/3857 1755/1755/3855 +f 1757/1757/3858 1756/1756/3857 1754/1754/3854 +f 1758/1758/3859 1759/1759/3860 1757/1757/3858 +f 1757/1757/3858 1759/1759/3860 1756/1756/3857 +f 1760/1760/3861 1761/1761/3862 1758/1758/3863 +f 1758/1758/3863 1761/1761/3862 1759/1759/3862 +f 1760/1760/3864 1762/1762/3865 1761/1761/3866 +f 1763/1763/3867 1762/1762/3865 1760/1760/3864 +f 1748/1748/3868 1749/1749/3869 1763/1763/3867 +f 1763/1763/3867 1749/1749/3869 1762/1762/3865 +f 1764/1764/3870 1754/1754/3854 1752/1752/3850 +f 1764/1764/3870 1752/1752/3850 1765/1765/3871 +f 1765/1765/3871 1752/1752/3850 1750/1750/3852 +f 1765/1765/3872 1750/1750/3873 1746/1746/3874 +f 1766/1766/3875 1746/1746/3844 1748/1748/3846 +f 1766/1766/3876 1748/1748/3868 1763/1763/3867 +f 1763/1763/3867 1760/1760/3864 1767/1767/3877 +f 1767/1767/3878 1760/1760/3861 1758/1758/3863 +f 1754/1754/3854 1764/1764/3870 1757/1757/3879 +f 1758/1758/3880 1757/1757/3881 1768/1768/3882 +f 1757/1757/3881 1764/1764/3883 1768/1768/3882 +f 1765/1765/3872 1746/1746/3874 1769/1769/3884 +f 1763/1763/3885 1770/1770/3886 1766/1766/3887 +f 1766/1766/3887 1769/1769/3884 1746/1746/3874 +f 1758/1758/3880 1771/1771/3888 1767/1767/3889 +f 1767/1767/3889 1770/1770/3886 1763/1763/3885 +f 1766/1766/3887 1770/1770/3886 1769/1769/3884 +f 1765/1765/3872 1769/1769/3884 1764/1764/3883 +f 1758/1758/3880 1768/1768/3882 1771/1771/3888 +f 1767/1767/3889 1771/1771/3888 1770/1770/3886 +f 1769/1769/3884 1772/1772/3890 1764/1764/3883 +f 1764/1764/3883 1772/1772/3890 1768/1768/3882 +f 1769/1769/3884 1770/1770/3886 1772/1772/3890 +f 1768/1768/3882 1772/1772/3890 1771/1771/3888 +f 1771/1771/3888 1772/1772/3890 1770/1770/3886 +f 1747/1747/3891 1751/1751/3892 1773/1773/3893 +f 1774/1774/3894 1773/1773/3893 1775/1775/3895 +f 1747/1747/3891 1773/1773/3893 1774/1774/3894 +f 1749/1749/3896 1747/1747/3891 1774/1774/3894 +f 1762/1762/3897 1749/1749/3896 1774/1774/3894 +f 1776/1776/3898 1762/1762/3897 1774/1774/3894 +f 1776/1776/3898 1774/1774/3894 1775/1775/3895 +f 1761/1761/3899 1762/1762/3897 1776/1776/3898 +f 1759/1759/3900 1761/1761/3899 1776/1776/3898 +f 1777/1777/3901 1759/1759/3900 1776/1776/3898 +f 1778/1778/3902 1777/1777/3901 1776/1776/3898 +f 1778/1778/3902 1776/1776/3898 1775/1775/3895 +f 1756/1756/3903 1759/1759/3900 1777/1777/3901 +f 1756/1756/3903 1777/1777/3901 1778/1778/3902 +f 1755/1755/3904 1756/1756/3903 1778/1778/3902 +f 1779/1779/3905 1755/1755/3904 1778/1778/3902 +f 1753/1753/3906 1755/1755/3904 1779/1779/3905 +f 1779/1779/3905 1778/1778/3902 1775/1775/3895 +f 1751/1751/3892 1753/1753/3906 1779/1779/3905 +f 1773/1773/3893 1751/1751/3892 1779/1779/3905 +f 1773/1773/3893 1779/1779/3905 1775/1775/3895 +f 1780/1780/3907 1781/1781/3908 1782/1782/3909 +f 1783/1783/3910 1784/1784/3911 1785/1785/3912 +f 1786/1786/3913 1787/1787/3914 1780/1780/3907 +f 1787/1787/3914 1788/1788/3915 1780/1780/3907 +f 1781/1781/3908 1780/1780/3907 1783/1783/3910 +f 1789/1789/3916 1784/1784/3911 1790/1790/3917 +f 1790/1790/3917 1784/1784/3911 1783/1783/3910 +f 1791/1791/3918 1792/1792/3919 1790/1790/3917 +f 1788/1788/3915 1787/1787/3914 1793/1793/3920 +f 1782/1782/3909 1786/1786/3913 1780/1780/3907 +f 1783/1783/3910 1785/1785/3912 1781/1781/3908 +f 1792/1792/3919 1794/1794/3921 1790/1790/3917 +f 1790/1790/3917 1794/1794/3921 1789/1789/3916 +f 1788/1788/3915 1793/1793/3920 1791/1791/3918 +f 1788/1788/3915 1791/1791/3918 1790/1790/3917 +f 1795/1795/3922 1796/1796/3923 1797/1797/3924 +f 1798/1798/3925 1796/1796/3923 1795/1795/3922 +f 1795/1795/3922 1799/1799/3926 1798/1798/3925 +f 1800/1800/3927 1797/1797/3928 1801/1801/3929 +f 1801/1801/3929 1797/1797/3928 1802/1802/3930 +f 1801/1801/3931 1802/1802/3932 1803/1803/3933 +f 1803/1803/3933 1802/1802/3932 1796/1796/3934 +f 1803/1803/3935 1796/1796/3936 1804/1804/3937 +f 1803/1803/3935 1804/1804/3937 1805/1805/3938 +f 1805/1805/3939 1804/1804/3939 1806/1806/3939 +f 1806/1806/3940 1804/1804/3941 1807/1807/3942 +f 1806/1806/3940 1807/1807/3942 1808/1808/3943 +f 1808/1808/3944 1807/1807/3945 1799/1799/3946 +f 1808/1808/3944 1799/1799/3946 1809/1809/3947 +f 1809/1809/3947 1799/1799/3946 1810/1810/3948 +f 1809/1809/3949 1810/1810/3950 1800/1800/3951 +f 1800/1800/3951 1810/1810/3950 1795/1795/3952 +f 1800/1800/3927 1795/1795/3953 1797/1797/3928 +f 1781/1781/3954 1801/1801/3955 1782/1782/3956 +f 1782/1782/3956 1801/1801/3955 1803/1803/3957 +f 1782/1782/3956 1803/1803/3957 1786/1786/3958 +f 1786/1786/3958 1803/1803/3957 1805/1805/3959 +f 1786/1786/3958 1805/1805/3959 1787/1787/3960 +f 1787/1787/3960 1805/1805/3959 1806/1806/3961 +f 1787/1787/3960 1806/1806/3961 1793/1793/3962 +f 1793/1793/3962 1806/1806/3961 1791/1791/3963 +f 1791/1791/3963 1806/1806/3961 1808/1808/3964 +f 1791/1791/3963 1808/1808/3964 1792/1792/3965 +f 1792/1792/3965 1808/1808/3964 1794/1794/3966 +f 1794/1794/3966 1808/1808/3964 1809/1809/3967 +f 1794/1794/3966 1809/1809/3967 1789/1789/3968 +f 1789/1789/3968 1809/1809/3967 1784/1784/3969 +f 1784/1784/3969 1809/1809/3967 1800/1800/3970 +f 1784/1784/3969 1800/1800/3970 1785/1785/3971 +f 1785/1785/3971 1800/1800/3970 1781/1781/3972 +f 1781/1781/3972 1800/1800/3970 1801/1801/3973 +f 1788/1788/3974 1790/1790/3975 1811/1811/3976 +f 1811/1811/3976 1790/1790/3975 1812/1812/3977 +f 1780/1780/3978 1788/1788/3979 1813/1813/3980 +f 1813/1813/3980 1788/1788/3979 1811/1811/3981 +f 1783/1783/3982 1780/1780/3983 1814/1814/3984 +f 1814/1814/3984 1780/1780/3983 1813/1813/3985 +f 1790/1790/3986 1783/1783/3987 1812/1812/3988 +f 1812/1812/3988 1783/1783/3987 1814/1814/3989 +f 1813/1813/3399 1811/1811/3399 1812/1812/3399 +f 1813/1813/3399 1812/1812/3399 1814/1814/3399 +f 1802/1802/3990 1797/1797/3924 1796/1796/3923 +f 1796/1796/3991 1798/1798/3991 1804/1804/3991 +f 1804/1804/3992 1798/1798/3925 1807/1807/3993 +f 1807/1807/3993 1798/1798/3925 1799/1799/3926 +f 1810/1810/3994 1799/1799/3926 1795/1795/3922 +f 1815/1815/3995 1816/1816/3996 1817/1817/3997 +f 1818/1818/3998 1819/1819/3999 1820/1820/4000 +f 1817/1817/3997 1821/1821/4001 1815/1815/3995 +f 1817/1817/3997 1822/1822/4002 1821/1821/4001 +f 1816/1816/3996 1818/1818/3998 1817/1817/3997 +f 1818/1818/3998 1816/1816/3996 1823/1823/4003 +f 1824/1824/4004 1825/1825/4005 1822/1822/4002 +f 1822/1822/4002 1817/1817/3997 1824/1824/4004 +f 1824/1824/4004 1826/1826/4006 1827/1827/4007 +f 1824/1824/4004 1827/1827/4007 1825/1825/4005 +f 1818/1818/3998 1828/1828/4008 1819/1819/3999 +f 1818/1818/3998 1820/1820/4000 1824/1824/4004 +f 1820/1820/4000 1826/1826/4006 1824/1824/4004 +f 1818/1818/3998 1823/1823/4003 1828/1828/4008 +f 1829/1829/4009 1830/1830/4010 1831/1831/4011 +f 1832/1832/4012 1830/1830/4010 1829/1829/4009 +f 1829/1829/4009 1833/1833/4013 1834/1834/4014 +f 1829/1829/4009 1831/1831/4011 1833/1833/4013 +f 1835/1835/4015 1831/1831/4016 1836/1836/4017 +f 1835/1835/4015 1836/1836/4017 1837/1837/4018 +f 1837/1837/4019 1836/1836/4020 1838/1838/4021 +f 1838/1838/4021 1836/1836/4020 1832/1832/4022 +f 1838/1838/4023 1832/1832/4024 1839/1839/4023 +f 1839/1839/4023 1832/1832/4024 1840/1840/4025 +f 1839/1839/4026 1840/1840/4027 1834/1834/4028 +f 1839/1839/4026 1834/1834/4028 1841/1841/4029 +f 1841/1841/4030 1834/1834/4031 1842/1842/4032 +f 1841/1841/4030 1842/1842/4032 1843/1843/4033 +f 1843/1843/4034 1842/1842/4034 1833/1833/4034 +f 1843/1843/4035 1833/1833/4036 1835/1835/4037 +f 1835/1835/4037 1833/1833/4036 1831/1831/4038 +f 1822/1822/4039 1835/1835/4040 1821/1821/4041 +f 1821/1821/4041 1835/1835/4040 1837/1837/4042 +f 1821/1821/4041 1837/1837/4042 1815/1815/4043 +f 1815/1815/4043 1837/1837/4042 1838/1838/4044 +f 1815/1815/4043 1838/1838/4044 1816/1816/4045 +f 1816/1816/4045 1838/1838/4044 1839/1839/4046 +f 1816/1816/4045 1839/1839/4046 1823/1823/4047 +f 1823/1823/4047 1839/1839/4046 1828/1828/4048 +f 1828/1828/4048 1839/1839/4046 1819/1819/4049 +f 1819/1819/4049 1839/1839/4046 1841/1841/4050 +f 1819/1819/4049 1841/1841/4050 1820/1820/4051 +f 1820/1820/4051 1841/1841/4050 1826/1826/4052 +f 1826/1826/4052 1841/1841/4050 1843/1843/4053 +f 1826/1826/4052 1843/1843/4053 1827/1827/4054 +f 1827/1827/4054 1843/1843/4053 1825/1825/4055 +f 1825/1825/4055 1843/1843/4053 1835/1835/4056 +f 1825/1825/4055 1835/1835/4056 1822/1822/4057 +f 1817/1817/3765 1818/1818/4058 1844/1844/3767 +f 1844/1844/3767 1818/1818/4058 1845/1845/4059 +f 1824/1824/3769 1817/1817/4060 1846/1846/3771 +f 1846/1846/3771 1817/1817/4060 1844/1844/4061 +f 1818/1818/4062 1824/1824/3774 1845/1845/4063 +f 1845/1845/4063 1824/1824/3774 1846/1846/3776 +f 1844/1844/4064 1845/1845/4064 1846/1846/4064 +f 1831/1831/4016 1830/1830/4065 1836/1836/4017 +f 1836/1836/4066 1830/1830/4066 1832/1832/4066 +f 1840/1840/4067 1832/1832/4012 1829/1829/4009 +f 1840/1840/4027 1829/1829/4068 1834/1834/4028 +f 1842/1842/4069 1834/1834/4014 1833/1833/4013 +f 1847/1847/4070 1848/1848/4071 1849/1849/4072 +f 1850/1850/4073 1851/1851/4074 1852/1852/4075 +f 1853/1853/4076 1854/1854/4077 1855/1855/4078 +f 1853/1853/4076 1856/1856/4079 1854/1854/4077 +f 1847/1847/4070 1857/1857/4080 1858/1858/4081 +f 1853/1853/4076 1859/1859/4082 1860/1860/4083 +f 1860/1860/4083 1850/1850/4073 1853/1853/4076 +f 1856/1856/4079 1853/1853/4076 1847/1847/4070 +f 1847/1847/4070 1849/1849/4072 1857/1857/4080 +f 1850/1850/4073 1860/1860/4083 1861/1861/4084 +f 1855/1855/4078 1859/1859/4082 1853/1853/4076 +f 1847/1847/4070 1858/1858/4081 1856/1856/4079 +f 1850/1850/4073 1852/1852/4075 1847/1847/4070 +f 1847/1847/4070 1852/1852/4075 1848/1848/4071 +f 1850/1850/4073 1861/1861/4084 1851/1851/4074 +f 1862/1862/4085 1863/1863/4086 1864/1864/4087 +f 1864/1864/4087 1865/1865/4088 1862/1862/4085 +f 1864/1864/4087 1866/1866/4089 1865/1865/4088 +f 1867/1867/4090 1868/1868/4091 1863/1863/4092 +f 1867/1867/4090 1863/1863/4092 1869/1869/4093 +f 1869/1869/4093 1863/1863/4092 1870/1870/4094 +f 1869/1869/4095 1870/1870/4096 1871/1871/4097 +f 1871/1871/4097 1870/1870/4096 1862/1862/4098 +f 1871/1871/4097 1862/1862/4098 1872/1872/4099 +f 1872/1872/4099 1862/1862/4098 1865/1865/4100 +f 1872/1872/4099 1865/1865/4100 1873/1873/4101 +f 1873/1873/4102 1865/1865/4103 1874/1874/4104 +f 1873/1873/4102 1874/1874/4104 1875/1875/4105 +f 1875/1875/4106 1874/1874/4107 1864/1864/4108 +f 1875/1875/4106 1864/1864/4108 1876/1876/4109 +f 1876/1876/4109 1864/1864/4108 1868/1868/4110 +f 1876/1876/4109 1868/1868/4110 1867/1867/4111 +f 1856/1856/4112 1867/1867/4113 1854/1854/4114 +f 1854/1854/4114 1867/1867/4113 1869/1869/4115 +f 1854/1854/4114 1869/1869/4115 1855/1855/4116 +f 1855/1855/4116 1869/1869/4115 1859/1859/4117 +f 1859/1859/4117 1869/1869/4115 1871/1871/4118 +f 1859/1859/4117 1871/1871/4118 1860/1860/4119 +f 1860/1860/4119 1871/1871/4118 1861/1861/4120 +f 1861/1861/4120 1871/1871/4118 1872/1872/4121 +f 1861/1861/4120 1872/1872/4121 1851/1851/4122 +f 1851/1851/4122 1872/1872/4121 1873/1873/4123 +f 1851/1851/4122 1873/1873/4123 1852/1852/4124 +f 1852/1852/4124 1873/1873/4123 1848/1848/4125 +f 1848/1848/4125 1873/1873/4123 1875/1875/4126 +f 1848/1848/4125 1875/1875/4126 1849/1849/4127 +f 1849/1849/4127 1875/1875/4126 1857/1857/4128 +f 1857/1857/4128 1875/1875/4126 1876/1876/4129 +f 1857/1857/4128 1876/1876/4129 1858/1858/4130 +f 1858/1858/4130 1876/1876/4129 1867/1867/4113 +f 1858/1858/4130 1867/1867/4113 1856/1856/4112 +f 1853/1853/3765 1850/1850/3766 1877/1877/3767 +f 1877/1877/3767 1850/1850/3766 1878/1878/3768 +f 1847/1847/4131 1853/1853/4132 1879/1879/4133 +f 1879/1879/4133 1853/1853/4132 1877/1877/4134 +f 1850/1850/4135 1847/1847/4136 1878/1878/4137 +f 1878/1878/4137 1847/1847/4136 1879/1879/4138 +f 1877/1877/3399 1878/1878/3399 1879/1879/3399 +f 1868/1868/4139 1864/1864/4087 1863/1863/4086 +f 1870/1870/4140 1863/1863/4086 1862/1862/4085 +f 1874/1874/4141 1865/1865/4141 1866/1866/4141 +f 1874/1874/4107 1866/1866/4142 1864/1864/4108 +f 1880/1880/4143 1881/1881/4144 1882/1882/4145 +f 1883/1883/4146 1884/1884/4147 1885/1885/4148 +f 1884/1884/4147 1883/1883/4146 1886/1886/4149 +f 1881/1881/4144 1880/1880/4143 1887/1887/4150 +f 1883/1883/4146 1885/1885/4148 1880/1880/4143 +f 1883/1883/4146 1888/1888/4151 1886/1886/4149 +f 1889/1889/4152 1890/1890/4153 1888/1888/4151 +f 1889/1889/4152 1888/1888/4151 1883/1883/4146 +f 1885/1885/4148 1887/1887/4150 1880/1880/4143 +f 1891/1891/4154 1892/1892/4155 1889/1889/4152 +f 1889/1889/4152 1892/1892/4155 1890/1890/4153 +f 1880/1880/4143 1882/1882/4145 1889/1889/4152 +f 1889/1889/4152 1882/1882/4145 1891/1891/4154 +f 1893/1893/4156 1894/1894/4157 1895/1895/4158 +f 1895/1895/4158 1896/1896/4159 1893/1893/4156 +f 1897/1897/4160 1896/1896/4159 1895/1895/4158 +f 1898/1898/4161 1899/1899/4162 1900/1900/4163 +f 1900/1900/4163 1899/1899/4162 1894/1894/4164 +f 1900/1900/4165 1894/1894/4166 1901/1901/4167 +f 1900/1900/4165 1901/1901/4167 1902/1902/4168 +f 1902/1902/4169 1901/1901/4170 1903/1903/4171 +f 1903/1903/4171 1901/1901/4170 1904/1904/4172 +f 1903/1903/4173 1904/1904/4174 1896/1896/4175 +f 1903/1903/4173 1896/1896/4175 1905/1905/4176 +f 1905/1905/4177 1896/1896/4178 1906/1906/4179 +f 1906/1906/4179 1896/1896/4178 1907/1907/4180 +f 1906/1906/4181 1907/1907/4182 1908/1908/4183 +f 1908/1908/4183 1907/1907/4182 1895/1895/4184 +f 1908/1908/4183 1895/1895/4184 1898/1898/4185 +f 1898/1898/4185 1895/1895/4184 1899/1899/4186 +f 1886/1886/4187 1900/1900/4188 1884/1884/4189 +f 1884/1884/4189 1900/1900/4188 1885/1885/4190 +f 1885/1885/4190 1900/1900/4188 1902/1902/4191 +f 1885/1885/4190 1902/1902/4191 1887/1887/4192 +f 1887/1887/4192 1902/1902/4191 1881/1881/4193 +f 1881/1881/4193 1902/1902/4191 1903/1903/4194 +f 1881/1881/4193 1903/1903/4194 1882/1882/4195 +f 1882/1882/4195 1903/1903/4194 1891/1891/4196 +f 1891/1891/4196 1903/1903/4194 1905/1905/4197 +f 1891/1891/4196 1905/1905/4197 1892/1892/4198 +f 1892/1892/4198 1905/1905/4197 1906/1906/4199 +f 1892/1892/4198 1906/1906/4199 1890/1890/4200 +f 1890/1890/4200 1906/1906/4199 1908/1908/4201 +f 1890/1890/4200 1908/1908/4201 1909/1909/4202 +f 1909/1909/4202 1908/1908/4201 1898/1898/4203 +f 1909/1909/4202 1898/1898/4203 1888/1888/4204 +f 1888/1888/4204 1898/1898/4203 1886/1886/4187 +f 1886/1886/4187 1898/1898/4203 1900/1900/4188 +f 1890/1890/4153 1909/1909/4205 1888/1888/4151 +f 1880/1880/4206 1889/1889/4206 1910/1910/4206 +f 1911/1911/4207 1880/1880/4207 1910/1910/4207 +f 1883/1883/4208 1880/1880/4209 1912/1912/4210 +f 1912/1912/4210 1880/1880/4209 1911/1911/4211 +f 1889/1889/4212 1883/1883/4212 1913/1913/4212 +f 1913/1913/4213 1883/1883/4213 1912/1912/4213 +f 1910/1910/4214 1889/1889/4214 1913/1913/4214 +f 1911/1911/4215 1910/1910/4215 1912/1912/4215 +f 1912/1912/4215 1910/1910/4215 1913/1913/4215 +f 1899/1899/4216 1895/1895/4158 1894/1894/4157 +f 1901/1901/4217 1894/1894/4157 1893/1893/4156 +f 1901/1901/4170 1893/1893/4218 1904/1904/4172 +f 1904/1904/4219 1893/1893/4156 1896/1896/4159 +f 1896/1896/4220 1897/1897/4220 1907/1907/4220 +f 1907/1907/4221 1897/1897/4221 1895/1895/4221 +f 1914/1914/4222 1915/1915/4223 1916/1916/4224 +f 1917/1917/4225 1918/1918/4226 1919/1919/4227 +f 1918/1918/4226 1917/1917/4225 1920/1920/4228 +f 1915/1915/4223 1921/1921/4229 1916/1916/4224 +f 1922/1922/4230 1923/1923/4231 1924/1924/4232 +f 1922/1922/4230 1924/1924/4232 1925/1925/4233 +f 1917/1917/4225 1919/1919/4227 1922/1922/4230 +f 1922/1922/4230 1919/1919/4227 1923/1923/4231 +f 1917/1917/4225 1926/1926/4234 1920/1920/4228 +f 1916/1916/4224 1927/1927/4235 1926/1926/4234 +f 1916/1916/4224 1926/1926/4234 1917/1917/4225 +f 1916/1916/4224 1921/1921/4229 1927/1927/4235 +f 1922/1922/4230 1925/1925/4233 1914/1914/4222 +f 1922/1922/4230 1914/1914/4222 1916/1916/4224 +f 1928/1928/4236 1929/1929/4237 1930/1930/4238 +f 1931/1931/4239 1929/1929/4237 1928/1928/4236 +f 1930/1930/4238 1932/1932/4240 1928/1928/4236 +f 1933/1933/4241 1934/1934/4242 1935/1935/4243 +f 1933/1933/4241 1935/1935/4243 1936/1936/4244 +f 1936/1936/4245 1935/1935/4246 1931/1931/4247 +f 1936/1936/4245 1931/1931/4247 1937/1937/4248 +f 1937/1937/4248 1931/1931/4247 1938/1938/4249 +f 1937/1937/4250 1938/1938/4251 1939/1939/4252 +f 1939/1939/4252 1938/1938/4251 1940/1940/4253 +f 1939/1939/4254 1940/1940/4255 1941/1941/4256 +f 1941/1941/4256 1940/1940/4255 1942/1942/4257 +f 1941/1941/4256 1942/1942/4257 1943/1943/4258 +f 1943/1943/4259 1942/1942/4260 1930/1930/4261 +f 1943/1943/4259 1930/1930/4261 1944/1944/4262 +f 1944/1944/4263 1930/1930/4264 1934/1934/4265 +f 1944/1944/4263 1934/1934/4265 1933/1933/4266 +f 1920/1920/4267 1933/1933/4268 1918/1918/4269 +f 1918/1918/4269 1933/1933/4268 1919/1919/4270 +f 1919/1919/4270 1933/1933/4268 1923/1923/4271 +f 1923/1923/4271 1933/1933/4268 1936/1936/4272 +f 1923/1923/4271 1936/1936/4272 1924/1924/4273 +f 1924/1924/4273 1936/1936/4272 1937/1937/4274 +f 1924/1924/4273 1937/1937/4274 1925/1925/4275 +f 1925/1925/4275 1937/1937/4274 1914/1914/4276 +f 1914/1914/4276 1937/1937/4274 1939/1939/4277 +f 1914/1914/4276 1939/1939/4277 1915/1915/4278 +f 1915/1915/4278 1939/1939/4277 1921/1921/4279 +f 1921/1921/4279 1939/1939/4277 1941/1941/4280 +f 1921/1921/4279 1941/1941/4280 1927/1927/4281 +f 1927/1927/4281 1941/1941/4280 1943/1943/4282 +f 1927/1927/4281 1943/1943/4282 1926/1926/4283 +f 1926/1926/4283 1943/1943/4282 1944/1944/4284 +f 1926/1926/4283 1944/1944/4284 1920/1920/4267 +f 1920/1920/4267 1944/1944/4284 1933/1933/4268 +f 1922/1922/4285 1916/1916/4285 1945/1945/4285 +f 1946/1946/4286 1922/1922/4286 1945/1945/4286 +f 1917/1917/4287 1922/1922/4288 1947/1947/4289 +f 1947/1947/4289 1922/1922/4288 1946/1946/4290 +f 1916/1916/4291 1917/1917/4291 1948/1948/4291 +f 1948/1948/4292 1917/1917/4292 1947/1947/4292 +f 1945/1945/4293 1916/1916/4293 1948/1948/4293 +f 1946/1946/3400 1945/1945/3400 1947/1947/3400 +f 1947/1947/3400 1945/1945/3400 1948/1948/4294 +f 1934/1934/4295 1930/1930/4238 1929/1929/4237 +f 1934/1934/4242 1929/1929/4296 1935/1935/4243 +f 1935/1935/4297 1929/1929/4297 1931/1931/4297 +f 1938/1938/4298 1931/1931/4239 1928/1928/4236 +f 1938/1938/4251 1928/1928/4299 1940/1940/4253 +f 1940/1940/4300 1928/1928/4300 1932/1932/4300 +f 1940/1940/4255 1932/1932/4301 1942/1942/4257 +f 1942/1942/4302 1932/1932/4302 1930/1930/4302 +f 677/677/1094 642/642/1057 643/643/1058 +f 1949/1949/4303 1950/1950/4303 1951/1951/4304 +f 1949/1949/4303 1951/1951/4304 1952/1952/4304 +f 1953/1953/4305 1954/1954/4305 1955/1955/4306 +f 1955/1955/4306 1954/1954/4305 1956/1956/4306 +f 1957/1957/4307 1958/1958/4307 1959/1959/4308 +f 1957/1957/4307 1959/1959/4308 1960/1960/4308 +f 1955/1955/3283 1951/1951/3283 1957/1957/3283 +f 1951/1951/3283 1950/1950/4309 1957/1957/3283 +f 1957/1957/3283 1960/1960/3280 1953/1953/3283 +f 1953/1953/3283 1955/1955/3283 1957/1957/3283 +f 1952/1952/3399 1956/1956/3399 1954/1954/3399 +f 1959/1959/3399 1958/1958/3401 1949/1949/3399 +f 1954/1954/3399 1949/1949/3399 1952/1952/3399 +f 1949/1949/3399 1954/1954/3399 1959/1959/3399 +f 1950/1950/4303 1949/1949/4303 1957/1957/4310 +f 1957/1957/4310 1949/1949/4303 1958/1958/4310 +f 1960/1960/4311 1959/1959/4311 1953/1953/4305 +f 1953/1953/4305 1959/1959/4311 1954/1954/4305 +f 1952/1952/4312 1951/1951/4312 1956/1956/4313 +f 1951/1951/4312 1955/1955/4313 1956/1956/4313 +f 1969/1961/4314 1973/1962/4315 1970/1963/4316 +f 3138/1964/4317 3107/1965/4318 3100/1966/4319 +f 2737/1967/4320 2750/1968/4321 2685/1969/4322 +f 3024/1970/4323 2896/1971/4324 2898/1972/4325 +f 2334/1973/4326 2331/1974/4327 2358/1975/4328 +f 4289/1976/4329 4294/1977/4329 4296/1978/4329 +f 2978/1979/4330 2996/1980/4331 2994/1981/4332 +f 3922/1982/4333 3824/1983/4334 3827/1984/4335 +f 3721/1985/4336 3719/1986/4336 3720/1987/4337 +f 3105/1988/4338 3106/1989/4339 3130/1990/4340 +f 3831/1991/4341 3900/1992/4342 3832/1993/4343 +f 4375/1994/4344 4347/1995/4345 4352/1996/4346 +f 3869/1997/4347 3868/1998/4348 3870/1999/4349 +f 3341/2000/4350 3337/2001/4350 3339/2002/4350 +f 3273/2003/4351 3271/2004/4351 3240/2005/4351 +f 3652/2006/4352 3689/2007/4353 3651/2008/4354 +f 2104/2009/4355 2102/2010/4356 2103/2011/4357 +f 4119/2012/4358 4115/2013/4359 4129/2014/4360 +f 3439/2015/4361 3336/2016/4362 3438/2017/4363 +f 3431/2018/4364 3419/2019/4365 3343/2020/4366 +f 4090/2021/4367 4120/2022/4367 4087/2023/4367 +f 2498/2024/4368 2499/2025/4369 2497/2026/4370 +f 4256/2027/4371 4261/2028/4372 4268/2029/4373 +f 3855/2030/4374 3836/2031/4375 3854/2032/4376 +f 3263/2033/4377 3265/2034/4378 3276/2035/4379 +f 2701/2036/4380 2776/2037/4381 2761/2038/4382 +f 3326/2039/4383 3327/2040/4383 3330/2041/4383 +f 3380/2042/4384 3382/2043/4385 3354/2044/4386 +f 3500/2045/4387 3510/2046/4388 3503/2047/4388 +f 2910/2048/4389 2902/2049/4390 2823/2050/4391 +f 3915/2051/4392 3909/2052/4393 3889/2053/4394 +f 3767/2054/4337 3744/2055/4336 3773/2056/4336 +f 4067/2057/4395 4104/2058/4396 4074/2059/4397 +f 2010/2060/4398 2013/2061/4399 2011/2062/4398 +f 4068/2063/4400 4079/2064/4401 4077/2065/4402 +f 3735/2066/4403 3736/2067/4404 3720/1987/4405 +f 3144/2068/4406 3140/2069/4406 3110/2070/4406 +f 4065/2071/4407 4058/2072/4408 4066/2073/4409 +f 2907/2074/4410 2906/2075/4411 2661/2076/4412 +f 2099/2077/4413 2429/2078/4414 2471/2079/4415 +f 4014/2080/4416 4031/2081/4417 4030/2082/4418 +f 4223/2083/4419 4192/2084/4420 4194/2085/4421 +f 4306/2086/4422 4305/2087/4422 4304/2088/4422 +f 4090/2021/4367 4092/2089/4367 4119/2012/4367 +f 2444/2090/4423 2425/2091/4424 2445/2092/4425 +f 2463/2093/4426 2585/2094/4427 2582/2095/4428 +f 3340/2096/4429 3451/2097/4429 3450/2098/4429 +f 3685/2099/4430 3650/2100/4431 3686/2101/4432 +f 3578/2102/4433 3579/2103/4434 3581/2104/4434 +f 3491/2105/4435 3492/2106/4435 3494/2107/4436 +f 2039/2108/4437 2052/2109/4438 2040/2110/4439 +f 3867/2111/4440 3868/1998/4348 3866/2112/4441 +f 3544/2113/4442 3562/2114/4443 3561/2115/4444 +f 3278/2116/4445 3277/2117/4446 3320/2118/4447 +f 4210/2119/4448 4208/2120/4449 4188/2121/4450 +f 4314/2122/4422 4347/1995/4422 4344/2123/4422 +f 3061/2124/4451 3067/2125/4452 3059/2126/4453 +f 4047/2127/4454 3936/2128/4455 4046/2129/4456 +f 3752/2130/4457 3749/2131/4458 3750/2132/4459 +f 3636/2133/4460 3634/2134/4461 3651/2008/4462 +f 3264/2135/4463 3262/2136/4464 3274/2137/4465 +f 2810/2138/4466 2811/2139/4467 2809/2140/4468 +f 2785/2141/4469 2799/2142/4470 2688/2143/4471 +f 3516/2144/4472 3535/2145/4473 3534/2146/4474 +f 3286/2147/4475 3285/2148/4476 3295/2149/4477 +f 3640/2150/4478 3653/2151/4479 3634/2134/4461 +f 3180/2152/4480 3184/2153/4481 3185/2154/4482 +f 2008/2155/4483 1983/2156/4484 2010/2060/4485 +f 3239/2157/4486 3241/2158/4487 3242/2159/4487 +f 4352/1996/4422 4347/1995/4422 4314/2122/4422 +f 3651/2008/4462 3634/2134/4461 3652/2006/4488 +f 3405/2160/4489 3434/2161/4490 3404/2162/4491 +f 3758/2163/4492 3757/2164/4493 3759/2165/4494 +f 3570/2166/4495 3567/2167/4496 3568/2168/4497 +f 3533/2169/4498 3518/2170/4499 3515/2171/4500 +f 3697/2172/4501 3585/2173/4501 3583/2174/4501 +f 4112/2175/4502 4111/2176/4503 4137/2177/4504 +f 3868/1998/4505 3840/2178/4506 3866/2112/4507 +f 3288/2179/4508 3267/2180/4509 3287/2181/4510 +f 3226/2182/4511 3243/2183/4512 3241/2158/4513 +f 2004/2184/4514 2007/2185/4515 2005/2186/4516 +f 3697/2172/4434 3699/2187/4434 3695/2188/4434 +f 4238/2189/4517 4236/2190/4517 4202/2191/4517 +f 3151/2192/4518 3166/2193/4519 3152/2194/4520 +f 3401/2195/4521 3415/2196/4522 3414/2197/4523 +f 3606/2198/4524 3638/2199/4524 3608/2200/4524 +f 4302/2201/4525 4301/2202/4526 4377/2203/4527 +f 4358/2204/4528 4354/2205/4529 4367/2206/4530 +f 3457/2207/4531 3467/2208/4531 3466/2209/4532 +f 4187/2210/4533 4206/2211/4534 4204/2212/4535 +f 3576/2213/4536 3466/2209/4536 3460/2214/4536 +f 3127/2215/4537 3125/2216/4538 3105/1988/4338 +f 3319/2217/4539 3217/2218/4540 3278/2116/4445 +f 3276/2035/4541 3275/2219/4542 3317/2220/4543 +f 3766/2221/4544 3780/2222/4545 3770/2223/4546 +f 4002/2224/4547 3989/2225/4548 4003/2226/4549 +f 2147/2227/4550 2618/2228/4551 2619/2229/4552 +f 3451/2097/4553 3340/2096/4553 3333/2230/4553 +f 3839/2231/4554 3836/2031/4554 3838/2232/4554 +f 3228/2233/4555 3229/2234/4556 3254/2235/4557 +f 3387/2236/4558 3356/2237/4559 3386/2238/4560 +f 1975/2239/4561 1967/2240/4316 1968/2241/4316 +f 3950/2242/4562 3968/2243/4563 3970/2244/4564 +f 3806/2245/4565 3710/2246/4566 3707/2247/4567 +f 3157/2248/4568 3158/2249/4569 3143/2250/4570 +f 3960/2251/4571 3947/2252/4572 3958/2253/4573 +f 1981/2254/4574 1997/2255/4575 1980/2256/4576 +f 2349/2257/4577 2351/2258/4578 2350/2259/4579 +f 3945/2260/4580 4023/2261/4581 4024/2262/4582 +f 3116/2263/4406 3117/2264/4406 3150/2265/4406 +f 4130/2266/4583 4119/2012/4358 4129/2014/4360 +f 1986/2267/4584 1988/2268/4585 2018/2269/4585 +f 3967/2270/4586 3969/2271/4587 3968/2243/4588 +f 2699/2272/4589 2611/2273/4590 2083/2274/4591 +f 2478/2275/4592 2522/2276/4593 2486/2277/4594 +f 3992/2278/4595 4001/2279/4596 3991/2280/4597 +f 3437/2281/4598 3436/2282/4599 3423/2283/4600 +f 2334/1973/4326 2335/2284/4601 2333/2285/4602 +f 3474/2286/4603 3499/2287/4604 3475/2288/4605 +f 3302/2289/4606 3295/2149/4477 3296/2290/4607 +f 3914/2291/4608 3915/2051/4392 3917/2292/4609 +f 2238/2293/4610 2233/2294/4611 2237/2295/4612 +f 3528/2296/4613 3565/2297/4614 3527/2298/4615 +f 2103/2011/4616 2101/2299/4617 2471/2079/4415 +f 3139/2300/4406 3110/2070/4406 3140/2069/4406 +f 3435/2301/4618 3438/2017/4363 3336/2016/4362 +f 3649/2302/4619 3683/2303/4620 3648/2304/4621 +f 3905/2305/4622 3912/2306/4623 3829/2307/4624 +f 3342/2308/4625 3340/2096/4626 3345/2309/4350 +f 2485/2310/4627 2535/2311/4628 2533/2312/4629 +f 3858/2313/4630 3857/2314/4631 3859/2315/4632 +f 3128/2316/4633 3127/2215/4537 3105/1988/4338 +f 3112/2317/4634 3111/2318/4634 3113/2319/4635 +f 4216/2320/4636 4217/2321/4637 4215/2322/4638 +f 4053/2323/4639 3940/2324/4639 3932/2325/4639 +f 2550/2326/4640 2551/2327/4641 2548/2328/4642 +f 1989/2329/4643 1987/2330/4644 1978/2331/4645 +f 2231/2332/4646 2230/2333/4647 2232/2334/4648 +f 2104/2009/4355 2103/2011/4357 2105/2335/4649 +f 3458/2336/4650 3572/2337/4650 3453/2338/4650 +f 2563/2339/4651 2562/2340/4652 2329/2341/4653 +f 2877/2342/4654 3042/2343/4655 2879/2344/4656 +f 2726/2345/4657 2830/2346/4658 2656/2347/4659 +f 3566/2348/4660 3463/2349/4661 3461/2350/4662 +f 4189/2351/4663 4215/2322/4664 4213/2352/4665 +f 2048/2353/4666 2066/2354/4667 2036/2355/4668 +f 2282/2356/4669 2283/2357/4670 2286/2358/4671 +f 3132/2359/4672 3131/2360/4673 3130/1990/4673 +f 3832/1993/4343 3910/2361/4674 3828/2362/4675 +f 4081/2363/4676 4082/2364/4677 4080/2365/4678 +f 4149/2366/4679 4147/2367/4680 4150/2368/4681 +f 4088/2369/4682 4089/2370/4683 4090/2021/4684 +f 3894/2371/4685 3921/2372/4686 3893/2373/4687 +f 3819/2374/4688 3820/2375/4689 3818/2376/4690 +f 2027/2377/4585 1996/2378/4585 1998/2379/4585 +f 3836/2031/4554 3834/2380/4554 3835/2381/4554 +f 3507/2382/4691 3508/2383/4692 3478/2384/4693 +f 2504/2385/4694 2505/2386/4695 2502/2387/4696 +f 3263/2033/4377 3277/2117/4697 3278/2116/4698 +f 3101/2388/4699 3111/2318/4700 3109/2389/4701 +f 2571/2390/4702 2553/2391/4703 2552/2392/4704 +f 3547/2393/4705 3570/2166/4495 3531/2394/4706 +f 3844/2395/4707 3842/2396/4708 3873/2397/4709 +f 3237/2398/4710 3239/2157/4486 3240/2005/4486 +f 2406/2399/4711 2465/2400/4712 2407/2401/4713 +f 3906/2402/4714 3912/2306/4623 3905/2305/4622 +f 3917/2292/4609 3915/2051/4392 3916/2403/4715 +f 2894/2404/4716 3025/2405/4717 3027/2406/4718 +f 2139/2407/26 2140/2408/26 2938/2409/511 +f 2121/2410/4719 2432/2411/4720 2450/2412/4721 +f 3882/2413/4722 3894/2371/4685 3877/2414/4723 +f 3938/2415/4724 4051/2416/4724 4050/2417/4724 +f 4349/2418/4725 4350/2419/4726 4362/2420/4727 +f 3634/2134/4461 3653/2151/4479 3652/2006/4488 +f 2779/2421/4728 2781/2422/4729 2792/2423/4730 +f 3096/2424/4731 3097/2425/4731 3098/2426/4731 +f 2099/2077/4732 2602/2427/4733 2696/2428/4734 +f 4072/2429/4735 4071/2430/4736 4070/2431/4367 +f 3617/2432/4737 3618/2433/4738 3615/2434/4739 +f 3739/2435/4740 3740/2436/4741 3738/2437/4742 +f 3699/2187/4434 3697/2172/4434 3698/2438/4434 +f 2666/2439/4743 2665/2440/4744 2829/2441/4745 +f 4158/2442/4746 4139/2443/4747 4127/2444/4748 +f 3675/2445/4749 3658/2446/4750 3659/2447/4751 +f 2587/2448/4752 2464/2449/4753 2386/2450/4754 +f 3381/2451/4755 3379/2452/4755 3389/2453/4755 +f 2895/2454/4756 2896/1971/4324 3026/2455/4757 +f 2082/2456/4758 2080/2457/4759 2081/2458/4760 +f 2504/2385/4694 2506/2459/4761 2505/2386/4695 +f 3536/2460/4762 3552/2461/4763 3571/2462/4764 +f 2760/2463/4765 2833/2464/4766 2831/2465/4767 +f 3752/2130/4457 3753/2466/4768 3751/2467/4457 +f 4080/2365/4367 4082/2364/4367 4113/2468/4367 +f 3626/2469/4769 3627/2470/4770 3625/2471/4769 +f 2745/2472/4771 2746/2473/4772 2744/2474/4773 +f 4206/2211/4534 4188/2121/4450 4208/2120/4449 +f 2912/2475/4774 2899/2476/4775 2897/2477/4776 +f 3978/2478/4777 3980/2479/4778 3979/2480/4779 +f 2272/2481/4780 2273/2482/4781 2271/2483/4782 +f 3136/2484/4783 3134/2485/4784 3107/1965/4318 +f 3838/2232/4785 3837/2486/4786 3858/2313/4787 +f 3877/2414/4554 3864/2487/4554 3882/2413/4554 +f 3485/2488/4788 3488/2489/4789 3487/2490/4789 +f 4217/2321/4637 4214/2491/4790 4215/2322/4638 +f 2014/2492/4585 2016/2493/4585 2013/2061/4585 +f 2228/2494/4791 2221/2495/4792 2226/2496/4793 +f 2847/2497/4794 2765/2498/4795 2726/2345/4657 +f 3819/2374/4796 3818/2376/4796 3925/2499/4796 +f 2963/2500/4797 2180/2501/4798 2613/2502/4799 +f 2707/2503/4800 2808/2504/4801 2806/2505/4802 +f 1976/2506/4803 2071/2507/4803 2072/2508/4803 +f 3672/2509/4804 3676/2510/4805 3591/2511/4806 +f 3457/2207/4807 3574/2512/4807 3458/2336/4807 +f 3364/2513/4808 3398/2514/4755 3366/2515/4755 +f 2900/2516/4809 2898/1972/4325 2899/2476/4775 +f 4332/2517/4810 4308/2518/4811 4309/2519/4812 +f 4381/2520/4813 4380/2521/4814 4379/2522/4815 +f 3531/2394/4706 3511/2523/4816 3517/2524/4817 +f 3037/2525/4818 3038/2526/4819 3044/2527/4820 +f 2318/2528/4821 2356/2529/4822 2278/2530/4823 +f 3559/2531/4824 3558/2532/4825 3541/2533/4826 +f 1961/2534/4827 1966/2535/4828 2061/2536/4829 +f 3580/2537/4830 3696/2538/4830 3700/2539/4830 +f 3829/2307/4624 3912/2306/4623 3821/2540/4831 +f 2035/2541/4832 2049/2542/4833 2048/2353/4666 +f 3544/2113/4834 3514/2543/4835 3509/2544/4836 +f 3557/2545/4837 3558/2532/4825 3464/2546/4838 +f 1990/2547/4839 1989/2329/4643 1978/2331/4645 +f 3580/2537/4434 3582/2548/4434 3579/2103/4434 +f 3747/2549/4840 3748/2550/4841 3749/2131/4458 +f 2368/2551/26 2367/2552/26 2579/2553/26 +f 3470/2554/4842 3483/2555/4843 3471/2556/4844 +f 2035/2541/4832 2036/2355/4668 2020/2557/4845 +f 2221/2495/4792 2394/2558/4846 2393/2559/4847 +f 2733/2560/4848 2750/1968/4321 2735/2561/4849 +f 3613/2562/4850 3616/2563/4851 3615/2434/4739 +f 2068/2564/4316 2069/2565/4316 2072/2508/4316 +f 2018/2269/4585 2014/2492/4585 1986/2267/4584 +f 4128/2566/4852 4129/2014/4360 4115/2013/4359 +f 4175/2567/4853 4286/2568/4854 4287/2569/4853 +f 2221/2495/4792 2228/2494/4791 2394/2558/4846 +f 2538/2570/4855 2479/2571/4856 2306/2572/4857 +f 2770/2573/4858 2771/2574/4859 2772/2575/4860 +f 3674/2576/4861 3670/2577/4862 3657/2578/4863 +f 4064/2579/4864 4164/2580/4864 4165/2581/4864 +f 4196/2582/4865 4193/2583/4866 4195/2584/4867 +f 3523/2585/4388 3488/2489/4388 3521/2586/4388 +f 2169/2587/4868 2168/2588/4869 2649/2589/4870 +f 2487/2590/4871 2176/2591/4872 2478/2275/4592 +f 2684/2592/4873 2741/2593/4874 2737/1967/4320 +f 3454/2594/4875 3577/2595/4875 3460/2214/4875 +f 3689/2007/4353 3653/2151/4876 3688/2596/4877 +f 4262/2597/4878 4261/2028/4372 4255/2598/4879 +f 3639/2599/4880 3656/2600/4881 3655/2601/4882 +f 4376/2602/4883 4366/2603/4884 4292/2604/4885 +f 3340/2096/4429 3450/2098/4429 3345/2309/4429 +f 3575/2605/4532 3572/2337/4532 3574/2512/4532 +f 4232/2606/4886 4246/2607/4887 4233/2608/4888 +f 2965/2609/4889 3075/2610/4890 3076/2611/4891 +f 2047/2612/4892 2018/2269/4893 2019/2613/4894 +f 3505/2614/4895 3508/2383/4692 3506/2615/4896 +f 4335/2616/4897 4334/2617/4898 4309/2519/4812 +f 2894/2404/4716 2851/2618/4899 2674/2619/4900 +f 3669/2620/4901 3675/2445/4749 3659/2447/4751 +f 3541/2533/4826 3558/2532/4825 3540/2621/4902 +f 3246/2622/4903 3244/2623/4904 3243/2183/4904 +f 3685/2099/4430 3686/2101/4432 3687/2624/4905 +f 3290/2625/4906 3289/2626/4907 3307/2627/4908 +f 3911/2628/4909 3904/2629/4910 3829/2307/4624 +f 3112/2317/4406 3114/2630/4406 3149/2631/4406 +f 2552/2392/4704 2570/2632/4911 2571/2390/4702 +f 3630/2633/4912 3631/2634/4913 3629/2635/4912 +f 2800/2636/4914 2785/2141/4469 2688/2143/4471 +f 3670/2577/4862 3674/2576/4861 3673/2637/4915 +f 4350/2419/4422 4349/2418/4422 4336/2638/4422 +f 1979/2639/4916 1992/2640/4917 1990/2547/4839 +f 2309/2641/4918 2529/2642/4919 2538/2570/4855 +f 2021/2643/4920 2037/2644/4921 2038/2645/4922 +f 4170/2646/4923 4168/2647/4924 4167/2648/4924 +f 3823/2649/4925 3830/2650/4925 3929/2651/4925 +f 3825/2652/4926 3925/2499/4926 3818/2376/4927 +f 3435/2301/4618 3437/2281/4598 3438/2017/4363 +f 2048/2353/4666 2065/2653/4928 2066/2354/4667 +f 2522/2276/4593 2500/2654/4929 2498/2024/4368 +f 3349/2655/4755 3352/2656/4755 3348/2657/4808 +f 2717/2658/4930 2719/2659/4931 2718/2660/4932 +f 4393/2661/4329 4394/2662/4329 4397/2663/4329 +f 3376/2664/4933 3353/2665/4934 3375/2666/4935 +f 2039/2108/4936 2040/2110/4937 2026/2667/4938 +f 2788/2668/4939 2787/2669/4940 2689/2670/4941 +f 3330/2041/4383 3329/2671/4383 3328/2672/4383 +f 2893/2673/4942 2852/2674/4943 2851/2618/4899 +f 2536/2675/4944 2528/2676/4945 2573/2677/4946 +f 3085/2678/4947 3201/2679/4947 3200/2680/4947 +f 3461/2350/4662 3453/2338/4532 3452/2681/4948 +f 2599/2682/4949 2600/2683/4950 2103/2011/4951 +f 3243/2183/4512 3226/2182/4511 3245/2684/4952 +f 2696/2428/4734 2602/2427/4733 3082/2685/4953 +f 4001/2279/4596 3992/2278/4595 4002/2224/4954 +f 3612/2686/4955 3609/2687/4956 3610/2688/4956 +f 2692/2689/4957 2789/2690/4958 2788/2668/4939 +f 3870/1999/4349 3871/2691/4959 3869/1997/4347 +f 3047/2692/4960 3055/2693/4961 3050/2694/4962 +f 3183/2695/4963 3182/2696/4964 3097/2425/4965 +f 3500/2045/4966 3501/2697/4967 3499/2287/4968 +f 3828/2362/4675 3911/2628/4909 3829/2307/4624 +f 3762/2698/4336 3754/2699/4336 3752/2130/4336 +f 2836/2700/4969 2755/2701/4970 2751/2702/4971 +f 2246/2703/4972 2320/2704/4973 2321/2705/4974 +f 3896/2706/4975 3881/2707/4976 3897/2708/4977 +f 2131/2709/4978 2137/2710/4979 2589/2711/4980 +f 2099/2077/4413 2097/2712/4981 2395/2713/4982 +f 4384/2714/4983 4385/2715/4984 4360/2716/4985 +f 3569/2717/4986 3529/2718/4987 3549/2719/4988 +f 3889/2053/4394 3916/2403/4715 3915/2051/4392 +f 2146/2720/4989 2145/2721/4990 2487/2590/4871 +f 3361/2722/4991 3360/2723/4992 3362/2724/4993 +f 3078/2725/4994 3019/2726/4995 3009/2727/4996 +f 2747/2728/4997 2748/2729/4998 2738/2730/4999 +f 3985/2731/5000 3983/2732/5001 3987/2733/5000 +f 2298/2734/5002 2288/2735/5003 2284/2736/5004 +f 3605/2737/5005 3595/2738/5006 3603/2739/5007 +f 2078/2740/5008 2079/2741/5009 2081/2458/4760 +f 4101/2742/5010 4102/2743/5011 4100/2744/5012 +f 2256/2745/5013 2257/2746/5014 2251/2747/5015 +f 2312/2748/5016 2313/2749/5017 2212/2750/5018 +f 3752/2130/4457 3754/2699/4768 3753/2466/4768 +f 2731/2751/5019 2725/2752/5020 2726/2345/4657 +f 3734/2753/4336 3732/2754/4336 3765/2755/4337 +f 4210/2119/4448 4189/2351/4663 4213/2352/4665 +f 3658/2446/4750 3674/2576/4861 3657/2578/4863 +f 3146/2756/5021 3145/2757/5022 3163/2758/5023 +f 2064/2759/5024 2049/2542/4833 2034/2760/5025 +f 4383/2761/5026 4381/2520/4813 4382/2762/5027 +f 3514/2543/4388 3482/2763/4388 3480/2764/5028 +f 4247/2765/5029 4248/2766/5030 4231/2767/5031 +f 3591/2511/4806 3676/2510/4805 3594/2768/5032 +f 3992/2278/5033 3989/2225/4548 4002/2224/4547 +f 4054/2769/4408 4059/2770/4409 4061/2771/5034 +f 3421/2772/5035 3335/2773/5036 3343/2020/4366 +f 3076/2611/4891 3080/2774/5037 3077/2775/5038 +f 2005/2186/4584 2022/2776/4585 2020/2557/4585 +f 2585/2094/26 2587/2448/26 2364/2777/26 +f 4277/2778/5039 4176/2779/5040 4278/2780/5041 +f 2966/2781/5042 2962/2782/5043 2958/2783/5044 +f 2988/2784/5045 2987/2785/5046 2812/2786/5047 +f 3885/2787/5048 3903/2788/5049 3886/2789/5050 +f 3185/2154/4482 3095/2790/5051 3186/2791/5052 +f 3798/2792/5053 3797/2793/5054 3795/2794/5055 +f 3105/1988/4338 3104/2795/5056 3103/2796/4406 +f 2021/2643/4920 2020/2557/4845 2036/2355/4668 +f 2399/2797/5057 2400/2798/5058 2468/2799/5059 +f 2120/2800/5060 2129/2801/5061 2130/2802/5062 +f 2669/2803/5063 2668/2804/5064 2850/2805/5065 +f 3635/2806/4524 3630/2633/4524 3636/2133/4524 +f 3422/2807/5066 3432/2808/5067 3335/2773/5036 +f 4290/2809/5068 4298/2810/5069 4386/2811/5070 +f 3556/2812/5071 3551/2813/5072 3550/2814/5073 +f 4122/2815/5074 4121/2816/5075 4149/2366/4679 +f 4017/2817/5076 4018/2818/5077 4037/2819/5078 +f 2068/2564/5079 1970/1963/5079 1962/2820/5079 +f 3179/2821/5080 3159/2822/5081 3197/2823/5082 +f 2458/2824/5083 2477/2825/5084 2459/2826/5085 +f 3325/2827/5086 3281/2828/5087 3292/2829/5088 +f 3657/2578/4863 3670/2577/4862 3694/2830/5089 +f 4204/2212/4535 4203/2831/5090 4186/2832/5091 +f 3291/2833/5092 3274/2137/4465 3261/2834/5093 +f 4107/2835/4367 4105/2836/4367 4076/2837/4367 +f 3146/2756/5021 3164/2838/5094 3165/2839/5095 +f 2394/2558/4846 2228/2494/4791 2436/2840/5096 +f 3229/2234/4556 3257/2841/5097 3254/2235/4557 +f 2087/2842/5098 2086/2843/5099 2085/2844/5100 +f 4209/2845/5101 4207/2846/5102 4208/2120/5103 +f 3653/2151/4876 3689/2007/4353 3652/2006/4352 +f 3490/2847/5104 3491/2105/4435 3489/2848/5104 +f 4245/2849/5105 4278/2780/5041 4279/2850/5106 +f 3524/2851/5107 3562/2114/4443 3544/2113/4442 +f 4250/2852/5108 4238/2189/5109 4237/2853/5110 +f 2078/2740/5008 2081/2458/4760 2080/2457/4759 +f 3351/2854/5111 3365/2855/5112 3367/2856/5113 +f 3169/2857/5114 3181/2858/5115 3180/2152/4480 +f 3036/2859/5116 2887/2860/5117 2886/2861/5118 +f 3713/2862/5119 3815/2863/5119 3814/2864/5119 +f 2006/2865/5120 2004/2184/5121 1982/2866/5122 +f 2896/1971/4324 2895/2454/4756 2850/2805/5065 +f 3428/2867/5123 3416/2868/5124 3429/2869/5125 +f 2663/2870/5126 2849/2871/5127 2662/2872/5128 +f 3354/2044/4386 3378/2873/5129 3380/2042/4384 +f 4134/2874/5130 4117/2875/5131 4118/2876/5132 +f 3529/2718/4987 3566/2348/4660 3528/2296/4613 +f 2791/2877/5133 2788/2668/4939 2793/2878/5134 +f 4181/2879/4924 4175/2567/4924 4179/2880/4924 +f 4120/2022/5135 4131/2881/5136 4132/2882/5137 +f 3403/2883/5138 3432/2808/5067 3422/2807/5066 +f 3401/2195/4808 3370/2884/4755 3402/2885/4755 +f 2607/2886/5139 2091/2887/5140 2090/2888/5141 +f 3989/2225/4548 3995/2889/5142 4004/2890/5143 +f 4180/2891/5144 4175/2567/4924 4169/2892/4924 +f 3270/2893/5145 3286/2147/4475 3287/2181/4510 +f 2297/2894/5146 2299/2895/5147 2398/2896/5148 +f 2714/2897/5149 2713/2898/5150 2712/2899/5151 +f 3439/2015/4361 3443/2900/5152 3341/2000/5153 +f 2765/2498/4795 2847/2497/4794 2736/2901/5154 +f 3486/2902/4788 3483/2555/5155 3484/2903/5156 +f 3762/2698/5157 3779/2904/5158 3778/2905/5159 +f 3774/2906/5160 3785/2907/5161 3784/2908/5162 +f 3727/2909/5163 3729/2910/5164 3718/2911/5165 +f 2961/2912/5166 2963/2500/4797 2181/2913/5167 +f 2094/2914/5168 2609/2915/5169 2701/2036/4380 +f 3526/2916/5170 3563/2917/5171 3525/2918/5172 +f 3217/2218/4383 3216/2919/5173 3213/2920/4383 +f 3978/2478/4777 3979/2480/4779 3977/2921/4777 +f 2253/2922/5174 2250/2923/5175 2268/2924/5176 +f 2533/2312/4629 2549/2925/5177 2495/2926/5178 +f 2058/2927/5179 2060/2928/5180 2059/2929/5181 +f 3237/2398/4710 3240/2005/4486 3238/2930/5182 +f 3372/2931/4755 3370/2884/4755 3401/2195/4808 +f 2936/2932/26 2178/2933/26 2971/2934/26 +f 3417/2935/5183 3400/2936/5184 3418/2937/5185 +f 3470/2554/4388 3476/2938/4388 3469/2939/4387 +f 4357/2940/5186 4372/2941/5187 4356/2942/5188 +f 2023/2943/5189 2025/2944/5190 2043/2945/5191 +f 3895/2946/5192 3922/1982/4333 3894/2371/4685 +f 2170/2947/5193 2648/2948/5194 3012/2949/5195 +f 4322/2950/5196 4320/2951/5197 4305/2087/5198 +f 2722/2952/5199 2686/2953/5200 2730/2954/5201 +f 2679/2955/5202 2853/2956/5203 2890/2957/5204 +f 3055/2693/4961 3051/2958/5205 3049/2959/5206 +f 3539/2960/5207 3550/2814/5073 3551/2813/5072 +f 2296/2961/5208 2295/2962/5209 2193/2963/5210 +f 4280/2964/5211 4259/2965/5212 4260/2966/5213 +f 2088/2967/5214 2091/2887/5215 2089/2968/5216 +f 2933/2969/26 2936/2932/26 2971/2934/26 +f 2780/2970/5217 2779/2421/4728 2778/2971/5218 +f 1997/2255/4575 1995/2972/5219 1980/2256/4576 +f 2977/2973/5220 2976/2974/5221 2992/2975/5222 +f 3683/2303/4620 3684/2976/5223 3578/2102/4433 +f 4136/2977/5224 4113/2468/5225 4135/2978/5226 +f 4395/2979/4329 4393/2661/4329 4397/2663/4329 +f 4307/2980/5227 4308/2518/4811 4329/2981/5228 +f 2218/2982/5229 2358/1975/4328 2239/2983/5230 +f 3826/2984/5231 3929/2651/5232 3830/2650/5232 +f 2107/2985/5233 2105/2335/5234 2473/2986/5235 +f 1968/2241/5236 2070/2987/5236 2071/2507/5236 +f 2728/2988/5237 2766/2989/5238 2817/2990/5239 +f 3516/2144/4472 3533/2169/4498 3515/2171/4500 +f 4243/2991/5240 4242/2992/5241 4275/2993/5242 +f 3015/2994/5243 2880/2995/5244 2879/2344/4656 +f 2315/2996/5245 2528/2676/4945 2314/2997/5246 +f 3666/2998/5247 3633/2999/5248 3647/3000/5249 +f 4077/2065/5250 4078/3001/5250 4076/2837/5251 +f 3697/2172/4501 3583/2174/4501 3698/2438/4501 +f 2735/2561/4849 2740/3002/5252 2772/2575/4860 +f 4378/3003/5253 4377/2203/4527 4301/2202/4526 +f 2214/3004/5254 2305/3005/5255 2215/3006/5256 +f 3347/3007/5257 3386/2238/5258 3356/2237/5259 +f 4032/3008/5260 4014/2080/4416 4015/3009/5261 +f 4084/3010/5262 4087/2023/5263 4085/3011/5264 +f 3933/3012/5265 4040/3013/5266 3939/3014/5267 +f 3216/2919/5173 3206/3015/4383 3213/2920/4383 +f 3226/2182/4351 3225/3016/4351 3229/2234/4351 +f 3235/3017/5268 3234/3018/5269 3233/3019/5270 +f 3190/3020/5271 3174/3021/5272 3189/3022/5273 +f 3672/2509/4804 3673/2637/4915 3676/2510/4805 +f 2815/3023/5274 2720/3024/5275 2589/2711/5276 +f 4068/2063/5277 4067/2057/4367 4070/2431/4367 +f 2477/2825/5084 2466/3025/5278 2465/2400/4712 +f 4202/2191/4517 4236/2190/4517 4200/3026/4517 +f 2781/2422/4729 2799/2142/4470 2790/3027/5279 +f 3371/3028/5280 3374/3029/5281 3373/3030/5282 +f 4154/3031/5283 4152/3032/5284 4151/3033/5285 +f 3214/3034/5286 3287/2181/5287 3302/2289/4606 +f 3046/3035/5288 3006/3036/5289 3045/3037/5290 +f 3238/2930/5182 3235/3017/5268 3237/2398/4710 +f 2762/3038/5291 2833/2464/4766 2760/2463/4765 +f 2887/2860/5117 3036/2859/5116 3035/3039/5292 +f 2148/3040/5293 2629/3041/5294 2919/3042/5295 +f 4246/2607/4887 4259/2965/5212 4281/3043/5296 +f 3601/3044/5297 3625/2471/5298 3627/2470/5299 +f 3396/3045/4808 3374/3029/4755 3372/2931/4755 +f 3102/3046/5300 3115/3047/5301 3113/2319/5302 +f 4118/2876/4367 4085/3011/4367 4087/2023/4367 +f 2244/3048/5303 2243/3049/5304 2326/3050/5305 +f 3055/2693/4961 3049/2959/5206 3050/2694/4962 +f 3290/2625/4906 3266/3051/5306 3289/2626/5307 +f 3192/3052/5308 3086/3053/5309 3083/3054/5310 +f 3886/2789/5050 3903/2788/5049 3902/3055/5311 +f 4387/3056/5312 4362/2420/4727 4361/3057/5313 +f 4320/2951/5197 4319/3058/5314 4305/2087/5198 +f 3433/3059/5315 3434/2161/4490 3435/2301/4618 +f 4076/2837/4367 4078/3001/4367 4112/2175/4367 +f 3938/2415/4724 3935/3060/4724 4051/2416/4724 +f 2297/2894/5146 2284/2736/5004 2299/2895/5147 +f 4245/2849/5105 4244/3061/5316 4278/2780/5041 +f 2914/3062/5317 2147/2227/5318 2917/3063/5319 +f 3532/3064/5320 3518/2170/4499 3533/2169/4498 +f 3264/2135/4351 3265/2034/4351 3255/3065/4351 +f 4276/3066/5321 4275/2993/5242 4274/3067/5322 +f 4374/3068/5323 4375/1994/4344 4352/1996/5324 +f 3252/3069/5325 3251/3070/5326 3250/3071/5326 +f 4375/1994/4344 4383/2761/5026 4384/2714/4983 +f 2738/2730/4999 2769/3072/5327 2770/2573/4858 +f 4062/3073/5328 4144/3074/5329 4143/3075/5330 +f 2330/3076/5331 2331/1974/4327 2560/3077/5332 +f 3268/3078/5333 3269/3079/5334 3279/3080/5335 +f 2889/3081/5336 3030/3082/5337 2854/3083/5338 +f 2201/3084/5339 2278/2530/5340 2280/3085/5341 +f 3689/2007/4353 3687/2624/4905 3686/2101/4432 +f 4177/3086/4924 4172/3087/4924 4182/3088/4924 +f 1998/2379/5342 1996/2378/5343 1995/2972/5344 +f 3999/3089/5345 4011/3090/5346 4010/3091/5347 +f 3744/2055/4336 3767/2054/4337 3746/3092/5348 +f 2817/2990/5239 2722/2952/5199 2723/3093/5349 +f 2023/2943/5189 2043/2945/5191 2044/3094/5350 +f 3015/2994/5243 2879/2344/4656 3042/2343/4655 +f 3408/3095/5351 3442/3096/5352 3407/3097/5353 +f 3942/3098/5354 3935/3060/5354 3938/2415/5355 +f 3032/3099/5356 3029/3100/5357 3067/2125/4452 +f 3815/2863/5358 3812/3101/5358 3814/2864/5358 +f 3265/2034/4351 3263/2033/4351 3253/3102/4351 +f 3847/3103/5359 3845/3104/5360 3846/3105/5360 +f 1992/2640/5361 1993/3106/5362 1991/3107/5363 +f 4199/3108/5364 4201/3109/5365 4202/2191/5366 +f 2904/3110/5367 2730/2954/5201 2818/3111/5368 +f 3714/3112/5369 3810/3113/5370 3716/3114/5371 +f 2780/2970/5217 2781/2422/4729 2779/2421/4728 +f 2147/2227/5318 2625/3115/5372 2917/3063/5319 +f 3869/1997/5373 3840/2178/4506 3868/1998/4505 +f 3271/2004/4351 3238/2930/4351 3240/2005/4351 +f 3556/2812/5071 3555/3116/5374 3551/2813/5072 +f 2454/3117/5375 2456/3118/5376 2457/3119/5377 +f 2551/2327/4641 2550/2326/4640 2573/2677/4946 +f 2419/3120/5378 2443/3121/5379 2445/2092/4425 +f 2657/3122/5380 2830/2346/4658 2848/3123/5381 +f 2313/2749/5017 2311/3124/5382 2212/2750/5018 +f 4240/3125/5383 4241/3126/5384 4227/3127/5385 +f 2347/3128/5386 2349/2257/4577 2350/2259/4579 +f 3747/2549/5387 3724/3129/5388 3723/3130/5389 +f 3365/2855/5390 3364/2513/5391 3366/2515/5390 +f 3637/3131/5392 3666/2998/5247 3665/3132/5393 +f 2178/2933/26 2179/3133/26 2971/2934/26 +f 3719/1986/5394 3733/3134/5395 3720/1987/4405 +f 2243/3049/5304 2329/2341/4653 2326/3050/5305 +f 2722/2952/5199 2817/2990/5239 2715/3135/5396 +f 3062/3136/5397 3060/3137/5398 2923/3138/5399 +f 3329/2671/5400 3213/2920/5400 3328/2672/5400 +f 2555/3139/5401 2564/3140/5402 2556/3141/5403 +f 3923/3142/5404 3922/1982/4333 3895/2946/5192 +f 2798/3143/5405 2797/3144/5406 3082/2685/4953 +f 3266/3051/4351 3261/2834/4351 3260/3145/4351 +f 3127/2215/5407 3128/2316/5408 3129/3146/5409 +f 4110/3147/4367 4109/3148/4367 4102/2743/4367 +f 2424/3149/5410 2422/3150/5411 2431/3151/5412 +f 2793/2878/5134 2792/2423/4730 2791/2877/5133 +f 2157/3152/5413 2159/3153/5414 2639/3154/5415 +f 3434/2161/4490 3437/2281/4598 3435/2301/4618 +f 2978/1979/26 2973/3155/26 2938/2409/511 +f 4148/3156/5416 4151/3033/5285 4150/2368/4681 +f 3143/2250/4406 3133/3157/4406 3135/3158/5056 +f 2113/3159/5417 2112/3160/5418 2114/3161/5419 +f 3446/3162/5420 3447/3163/5421 3333/2230/5420 +f 2303/3164/5422 2387/3165/5423 2388/3166/5424 +f 3527/2298/5425 3512/3167/5426 3513/3168/5427 +f 2617/3169/5428 2618/2228/5429 2916/3170/5430 +f 3509/2544/4388 3478/2384/4388 3508/2383/4388 +f 3146/2756/5021 3163/2758/5023 3164/2838/5094 +f 3123/3171/5431 3120/3172/5432 3104/2795/5433 +f 2416/3173/5434 2441/3174/5435 2442/3175/5436 +f 2393/2559/4847 2394/2558/4846 2094/2914/5437 +f 2082/2456/5438 2083/2274/5439 2394/2558/4846 +f 2083/2274/5439 2085/2844/5440 2394/2558/4846 +f 1968/2241/5236 1970/1963/5236 2070/2987/5236 +f 2074/3176/5441 2076/3177/5442 2095/3178/5443 +f 3098/2426/4731 3099/3179/5444 3088/3180/5444 +f 3785/2907/5161 3772/3181/5445 3786/3182/5446 +f 3722/3183/5447 3721/1985/5448 3738/2437/5449 +f 3630/2633/4912 3632/3184/4913 3631/2634/4913 +f 3723/3130/5389 3743/3185/5450 3745/3186/5451 +f 3877/2414/4723 3893/2373/5452 3878/3187/5453 +f 3862/3188/5454 3864/2487/5455 3863/3189/5456 +f 2508/3190/5457 2513/3191/5458 2510/3192/5459 +f 3248/3193/5460 3251/3070/5326 3249/3194/5461 +f 3640/2150/4524 3626/2469/4524 3624/3195/5462 +f 4061/2771/5034 4065/2071/4407 4156/3196/5463 +f 2900/2516/4809 3024/1970/4323 2898/1972/4325 +f 3788/3197/5464 3799/3198/5465 3787/3199/5466 +f 4370/3200/5467 4377/2203/4527 4378/3003/5253 +f 4369/3201/5468 4359/3202/5469 4358/2204/4528 +f 3943/3203/5470 4026/3204/5471 4029/3205/5472 +f 2262/3206/5473 2261/3207/5474 2211/3208/5475 +f 3094/3209/5476 3176/3210/5477 3177/3211/5478 +f 3814/2864/5358 3812/3101/5358 3813/3212/5358 +f 4364/3213/5479 4363/3214/5480 4389/3215/5481 +f 3678/3216/5482 3679/3217/5483 3681/3218/5484 +f 3669/2620/4901 3659/2447/4751 3660/3219/5485 +f 2659/3220/5486 2658/3221/5487 2848/3123/5381 +f 4274/3067/5322 4241/3126/5488 4272/3222/5489 +f 2077/3223/5490 2395/2713/4982 2076/3177/5442 +f 4192/2084/4420 4193/2583/4866 4194/2085/4421 +f 1982/2866/5122 1981/2254/4585 1984/3224/4585 +f 3229/2234/4556 3222/3225/5491 3259/3226/5492 +f 2579/2553/5493 2452/3227/5494 2458/2824/5495 +f 3064/3228/5496 3062/3136/5397 2923/3138/5399 +f 4224/3229/5497 4239/3230/5498 4240/3125/5383 +f 3008/3231/5499 3002/3232/5500 3056/3233/5501 +f 3822/3234/4688 3825/2652/4690 3818/2376/4690 +f 2771/2574/4859 2773/3235/5502 2772/2575/4860 +f 2522/2276/4593 2498/2024/4368 2497/2026/4370 +f 4207/2846/5503 4209/2845/5503 4234/3236/4517 +f 2324/3237/5504 2326/3050/5305 2565/3238/5505 +f 2342/3239/5506 2344/3240/5507 2345/3241/5508 +f 2618/2228/5429 2147/2227/5318 2914/3062/5317 +f 2412/3242/5509 2428/3243/5510 2413/3244/5511 +f 3808/3245/5512 3807/3246/5513 3779/2904/5158 +f 2537/3247/5514 2534/3248/5515 2505/2386/4695 +f 2416/3173/5434 2419/3120/5378 2418/3249/5516 +f 2242/3250/5517 2439/3251/5518 2438/3252/5519 +f 2580/3253/26 2371/3254/26 2378/3255/26 +f 2167/3256/5520 2166/3257/5521 2169/2587/4868 +f 4024/2262/4582 4025/3258/5522 4026/3204/5471 +f 3978/2478/5523 3977/2921/5523 3975/3259/5524 +f 2093/3260/5525 2092/3261/5526 2094/2914/5527 +f 3803/3262/5528 3802/3263/5529 3793/3264/5530 +f 3658/2446/4750 3646/3265/5531 3659/2447/4751 +f 4088/2369/5532 4071/2430/5533 4089/2370/5534 +f 2144/3266/5535 2143/3267/5536 3011/3268/5537 +f 2700/3269/5538 2776/2037/4381 2701/2036/4380 +f 4191/3270/5539 4221/3271/5540 4219/3272/5541 +f 2017/3273/4585 2015/3274/4585 2009/3275/4585 +f 4303/3276/5542 4304/2088/5543 4313/3277/5544 +f 4134/2874/5545 4141/3278/5546 4143/3075/5330 +f 2781/2422/4729 2780/2970/5217 2798/3143/5405 +f 2917/3063/5319 2623/3279/5547 2913/3280/5548 +f 2627/3281/5549 2150/3282/5550 2913/3280/5548 +f 3742/3283/4336 3773/2056/4336 3744/2055/4336 +f 3146/2756/4406 3151/2192/4406 3124/3284/4406 +f 3853/3285/5551 3854/2032/5552 3852/3286/5553 +f 3629/2635/5554 3601/3044/5297 3627/2470/5299 +f 4368/3287/5555 4358/2204/4528 4367/2206/4530 +f 4359/3202/4422 4323/3288/4422 4326/3289/4422 +f 2453/3290/5556 2132/3291/5557 2451/3292/5558 +f 2778/2971/5218 2779/2421/4728 2777/3293/5559 +f 3754/2699/4768 3755/3294/5560 3753/2466/4768 +f 3424/3295/5561 3431/2018/4364 3430/3296/5562 +f 3411/3297/5563 3412/3298/5564 3341/2000/5153 +f 2854/3083/5338 2681/3299/5565 2682/3300/5566 +f 2250/2923/5175 2446/3301/5567 2249/3302/5568 +f 4265/3303/5569 4263/3304/5570 4264/3305/5571 +f 3882/2413/4554 3864/2487/4554 3862/3188/4554 +f 3682/3306/5572 3582/2548/5573 3647/3000/5574 +f 4173/3307/5575 4169/2892/4924 4168/2647/4924 +f 3655/2601/4882 3691/3308/5576 3654/3309/5577 +f 2449/3310/5578 2253/2922/5174 2252/3311/5579 +f 2899/2476/4775 2911/3312/5580 2901/3313/5581 +f 2567/3314/5582 2555/3139/5401 2554/3315/5583 +f 2874/3316/5584 3040/3317/5585 2877/2342/4654 +f 4307/2980/4422 4306/2086/4422 4309/2519/4422 +f 3891/3318/5586 3918/3319/5587 3890/3320/5588 +f 4130/2266/5589 4129/2014/4360 4140/3321/5590 +f 3584/3322/4434 3583/2174/4434 3589/3323/4434 +f 2596/3324/5591 2594/3325/5592 2595/3326/5593 +f 3379/2452/5594 3380/2042/5595 3378/2873/5594 +f 3195/3327/5596 3094/3209/5476 3198/3328/5597 +f 2634/3329/5598 2633/3330/5599 2632/3331/5600 +f 3365/2855/5112 3349/2655/5601 3363/3332/5602 +f 3050/2694/4962 3007/3333/5603 3006/3036/5289 +f 2020/2557/4585 2021/2643/4584 2002/3334/4585 +f 3496/3335/5604 3493/3336/5605 3495/3337/5606 +f 2695/3338/5607 2696/2428/4734 3082/2685/4953 +f 3375/2666/5608 3377/3339/5609 3376/2664/5610 +f 3597/3340/5611 3609/2687/5612 3611/3341/5613 +f 2115/3342/5614 2118/3343/5615 2117/3344/5616 +f 3825/2652/4926 3927/3345/5617 3925/2499/4926 +f 3393/3346/5618 3421/2772/5619 3399/3347/5620 +f 4356/2942/4422 4318/3348/4422 4321/3349/4422 +f 2982/3350/5621 2987/2785/5622 2974/3351/5623 +f 2577/3352/5624 2456/3118/5625 2455/3353/5626 +f 3141/3354/5627 3159/2822/5628 3160/3355/5629 +f 2116/3356/5630 2115/3342/5614 2113/3159/5417 +f 4330/3357/5631 4331/3358/5632 4333/3359/5633 +f 2394/2558/4846 2383/3360/5634 2082/2456/5438 +f 2082/2456/5438 2383/3360/5634 2080/2457/5635 +f 4127/2444/4748 4108/3361/5636 4126/3362/5637 +f 4358/2204/4422 4359/3202/4422 4326/3289/4422 +f 2828/3363/5638 2894/2404/4716 2674/2619/4900 +f 2342/3239/5506 2340/3364/5639 2341/3365/5640 +f 2510/3192/5459 2511/3366/5641 2509/3367/5642 +f 3421/2772/5619 3394/3368/5643 3422/2807/5644 +f 2133/3369/5645 2453/3290/5556 2138/3370/5646 +f 2784/3371/5647 2691/3372/5648 2801/3373/5649 +f 2706/3374/5650 2903/3375/5651 2707/2503/4800 +f 2455/3353/5652 2456/3118/5376 2454/3117/5375 +f 2141/3376/5653 2134/3377/5653 2457/3119/5653 +f 2457/3119/5654 2134/3377/5654 2135/3378/5654 +f 3161/3379/5655 3162/3380/5656 3147/3381/5657 +f 3661/3382/5658 3668/3383/5659 3660/3219/5485 +f 4249/3384/5660 4182/3088/5661 4250/2852/5662 +f 2094/2914/5168 2701/2036/4380 2702/3385/5663 +f 2490/3386/5664 2491/3387/5665 2542/3388/5666 +f 2091/2887/5667 2219/3389/5668 2221/2495/4792 +f 2459/2826/5085 2462/3390/5669 2463/2093/5670 +f 3649/2302/4619 3635/2806/5671 3636/2133/4460 +f 4075/3391/5672 4067/2057/4395 4077/2065/4402 +f 3066/3392/5673 3029/3100/5357 3028/3393/5674 +f 2408/3394/5675 2410/3395/5676 2409/3396/5677 +f 2466/3025/5278 2404/3397/5678 2411/3398/5679 +f 3113/2319/5302 3101/2388/4699 3102/3046/5300 +f 3193/3399/5680 3192/3052/5308 3083/3054/5310 +f 2798/3143/5405 2799/2142/4470 2781/2422/4729 +f 2418/3249/5516 2425/2091/4424 2426/3400/5681 +f 3898/3401/5682 3887/3402/5683 3899/3403/5684 +f 3634/2134/4524 3626/2469/4524 3640/2150/4524 +f 3345/2309/4350 3346/3404/4350 3344/3405/5685 +f 3093/3406/5686 3094/3209/5476 3195/3327/5596 +f 2314/2997/5246 2312/2748/5016 2212/2750/5018 +f 3473/3407/5687 3491/2105/5688 3493/3336/5689 +f 4324/3408/5690 4322/2950/5196 4306/2086/5691 +f 3678/3216/5482 3586/3409/5692 3663/3410/5693 +f 3900/1992/5694 3887/3402/5683 3888/3411/5695 +f 2324/3237/5504 2245/3412/5696 2244/3048/5303 +f 3826/2984/4688 3832/1993/4690 3828/2362/4688 +f 4222/3413/5697 4221/3271/5540 4191/3270/5539 +f 4060/3414/5698 4166/3415/5698 4162/3416/5698 +f 2057/3417/5699 2056/3418/5700 2058/2927/5179 +f 4309/2519/4812 4310/3419/5701 4335/2616/4897 +f 3374/3029/5281 3375/2666/5608 3373/3030/5282 +f 2523/3420/5702 2560/3077/5332 2333/2285/4602 +f 3463/2349/5703 3458/2336/5703 3461/2350/4662 +f 4186/2832/4517 4185/3421/4517 4184/3422/4517 +f 2292/3423/5704 2293/3424/5705 2284/2736/5004 +f 4197/3425/5706 4195/2584/5707 4184/3422/5708 +f 2284/2736/5004 2288/2735/5003 2289/3426/5709 +f 3955/3427/5710 3957/3428/5711 3956/3429/5712 +f 3742/3283/5713 3740/2436/4741 3739/2435/4740 +f 2262/3206/5714 2263/3430/5715 2251/2747/5015 +f 3487/2490/4789 3488/2489/4789 3490/2847/5104 +f 3874/3431/5716 3897/2708/4977 3881/2707/4976 +f 2818/3111/5368 2686/2953/5200 2820/3432/5717 +f 3062/3136/5397 3064/3228/5496 3073/3433/5718 +f 3691/3308/5576 3690/3434/5719 3654/3309/5577 +f 3527/2298/5425 3513/3168/5427 3528/2296/5720 +f 3079/3435/5721 3078/2725/4994 3011/3268/5537 +f 3048/3436/5722 3079/3435/5721 3011/3268/5537 +f 2274/3437/5723 2275/3438/5724 2271/2483/4782 +f 4004/2890/5143 3995/2889/5142 4005/3439/5725 +f 3222/3225/4351 3229/2234/4351 3225/3016/4351 +f 3997/3440/5726 3994/3441/5727 4015/3009/5728 +f 3663/3410/5693 3586/3409/5692 3662/3442/5729 +f 1988/2268/5730 1987/2330/5731 1989/2329/5732 +f 3636/2133/4524 3628/3443/4524 3634/2134/4524 +f 2050/3444/5733 2054/3445/5734 2044/3094/5350 +f 3065/3446/5735 3027/2406/4718 3025/2405/4717 +f 2697/3447/5736 2700/3269/5538 2699/2272/4589 +f 4088/2369/5532 4070/2431/5737 4071/2430/5533 +f 3388/3448/5738 3422/2807/5644 3392/3449/5739 +f 2511/3366/5641 2512/3450/5641 2509/3367/5642 +f 3981/3451/5001 3980/2479/5000 3991/2280/5000 +f 3516/2144/4472 3534/2146/4474 3533/2169/4498 +f 4325/3452/5740 4324/3408/5690 4306/2086/5691 +f 2593/3453/5741 2719/2659/4931 3081/3454/5742 +f 3141/3354/5627 3158/2249/4569 3159/2822/5628 +f 2596/3324/5591 2595/3326/5593 2597/3455/5743 +f 4210/2119/5744 4211/3456/5745 4209/2845/5101 +f 3269/3079/4351 3268/3078/4351 3246/2622/4351 +f 2565/3238/5505 2564/3140/5402 2555/3139/5401 +f 3920/3457/5746 3918/3319/5587 3919/3458/5747 +f 2964/3459/5748 2967/3460/5749 2965/2609/4889 +f 3683/2303/4620 3685/2099/4430 3684/2976/5223 +f 4189/2351/4663 4190/3461/5750 4216/2320/5751 +f 4217/2321/4517 4225/3462/5503 4214/2491/4517 +f 3151/2192/4406 3152/2194/4406 3122/3463/4406 +f 3166/2193/4519 3165/2839/5752 3199/3464/5753 +f 1971/3465/5754 1974/3466/5755 1972/3467/5756 +f 3625/2471/5298 3600/3468/5757 3623/3469/5758 +f 4001/2279/4596 4038/3470/5759 4000/3471/5760 +f 3918/3319/5587 3916/2403/4715 3890/3320/5588 +f 3550/2814/5073 3557/2545/4837 3556/2812/5071 +f 3712/3472/5761 3801/3473/5762 3704/3474/5763 +f 2015/3274/5764 2032/3475/5765 2033/3476/5766 +f 2407/2401/4713 2408/3394/5675 2382/3477/5767 +f 4132/2882/5137 4133/3478/5768 4118/2876/5132 +f 3638/2199/4524 3606/2198/4524 3637/3131/4524 +f 3514/2543/4388 3478/2384/4388 3509/2544/4388 +f 3031/3479/5769 2885/3480/5770 2888/3481/5771 +f 2533/2312/4629 2536/2675/4944 2550/2326/4640 +f 2461/3482/5772 2581/3483/5773 2579/2553/5493 +f 2225/3484/5774 2226/2496/4793 2221/2495/4792 +f 2026/2667/4584 2027/2377/4585 1998/2379/4585 +f 4094/3485/5775 4095/3486/5776 4093/3487/5777 +f 3838/2232/4554 3836/2031/4554 3837/2486/5778 +f 1971/3465/5754 1972/3467/5756 1963/3488/4316 +f 3072/3489/5779 3062/3136/5397 3073/3433/5718 +f 4233/2608/4517 4209/2845/5503 4211/3456/5503 +f 3384/3490/5780 3385/3491/5780 3387/2236/4558 +f 2592/3492/5781 2590/3493/5782 2719/2659/4931 +f 3928/3494/5783 3825/2652/5783 3823/2649/5783 +f 2241/3495/5784 2239/2983/5230 2358/1975/4328 +f 2748/2729/4998 2745/2472/4771 2783/3496/5785 +f 4351/3497/4422 4350/2419/4422 4339/3498/4422 +f 2118/3343/5786 2594/3325/5592 2117/3344/5787 +f 3400/2936/4755 3366/2515/4755 3398/2514/4755 +f 3060/3137/5398 3061/2124/4451 2921/3499/5788 +f 2922/3500/5789 3057/3501/5790 3064/3228/5496 +f 2301/3502/5791 2304/3503/5792 2306/2572/4857 +f 2771/2574/4859 2770/2573/4858 2769/3072/5327 +f 2064/2759/5024 2065/2653/4928 2049/2542/4833 +f 3042/2343/4655 3012/2949/5195 3015/2994/5243 +f 3555/3116/5374 3553/3504/5793 3554/3505/5794 +f 3217/2218/4540 3212/3506/5795 3321/3507/5796 +f 3142/3508/5797 3140/2069/5798 3155/3509/5799 +f 3956/3429/5800 3946/3510/5801 3955/3427/5802 +f 3742/3283/5713 3743/3185/5803 3741/3511/5804 +f 3335/2773/5036 3433/3059/5315 3334/3512/5805 +f 2505/2386/4695 2506/2459/4761 2483/3513/5806 +f 2153/3514/5807 2915/3515/5808 2927/3516/5809 +f 2433/3517/5810 2434/3518/5811 2420/3519/5812 +f 2182/3520/5813 2175/3521/5814 2176/2591/4872 +f 4011/3090/5346 3998/3522/5815 4012/3523/5816 +f 3971/3524/5817 3970/2244/5818 3968/2243/4588 +f 2679/2955/5202 2890/2957/5204 2824/3525/5819 +f 3432/2808/5067 3434/2161/4490 3433/3059/5315 +f 2401/3526/5820 2450/2412/4721 2420/3519/5812 +f 3353/2665/4934 3373/3030/5821 3375/2666/4935 +f 4081/2363/5822 4079/2064/4401 4068/2063/4400 +f 2597/3455/5823 2595/3326/5824 3081/3454/5742 +f 3113/2319/5302 3111/2318/4700 3101/2388/4699 +f 3720/1987/4405 3733/3134/5395 3735/2066/4403 +f 2548/2328/4642 2552/2392/4704 2547/3527/5825 +f 4098/3528/5826 4099/3529/5827 4100/2744/5012 +f 2774/3530/5828 2773/3235/5502 2801/3373/5649 +f 3153/3531/4406 3150/2265/4406 3119/3532/4406 +f 2553/2391/4703 2546/3533/5829 2547/3527/5825 +f 2158/3534/5830 2639/3154/5831 2926/3535/5832 +f 3742/3283/5713 3744/2055/5833 3743/3185/5803 +f 3510/2046/5834 3530/3536/5835 3529/2718/5836 +f 3545/3537/5837 3546/3538/5838 3533/2169/4498 +f 4248/2766/5030 4249/3384/5839 4237/2853/5110 +f 3133/3157/4406 3141/3354/4406 3131/2360/4406 +f 4341/3539/5840 4338/3540/5841 4340/3541/5842 +f 3098/2426/4731 3092/3542/4731 3096/2424/4731 +f 3030/3082/5337 3070/3543/5843 3031/3479/5769 +f 1991/3107/4585 1993/3106/4585 2023/2943/4585 +f 2788/2668/4939 2689/2670/4941 2693/3544/5844 +f 3846/3105/5845 3845/3104/5845 3843/3545/5846 +f 3926/3546/5847 3826/2984/5847 3819/2374/5847 +f 3454/2594/5848 3572/2337/5848 3573/3547/5848 +f 3454/2594/5848 3453/2338/5848 3572/2337/5848 +f 4325/3452/5849 4327/3548/5850 4328/3549/5851 +f 4241/3126/5488 4240/3125/5852 4272/3222/5489 +f 3220/3550/5853 3329/2671/5853 3330/2041/5853 +f 2434/3518/5811 2433/3517/5810 2396/3551/5854 +f 2052/2109/4438 2038/2645/5855 2067/3552/5856 +f 4026/3204/5471 4025/3258/5522 4027/3553/5857 +f 3767/2054/5858 3782/3554/5859 3781/3555/5860 +f 2015/3274/4585 2007/2185/4585 2009/3275/4585 +f 2956/3556/5861 2970/3557/5862 2969/3558/5863 +f 2975/3559/26 2941/3560/26 2942/3561/26 +f 2916/3170/5430 2143/3267/5536 2145/2721/5864 +f 4041/3562/5865 4001/2279/4596 4042/3563/5866 +f 3050/2694/4962 3049/2959/5206 3007/3333/5603 +f 2403/3564/5867 2410/3395/5676 2404/3397/5868 +f 3618/2433/4738 3621/3565/5869 3620/3566/5870 +f 3623/3469/5758 3600/3468/5757 3622/3567/5871 +f 4073/3568/5872 4074/2059/4397 4099/3529/5873 +f 2148/3040/5874 2150/3282/5875 2628/3569/5876 +f 3654/3309/5577 3640/2150/5877 3639/2599/4880 +f 3339/2002/4350 3332/3570/5878 3336/2016/4350 +f 4054/2769/4408 4061/2771/5034 4056/3571/5879 +f 2046/3572/5880 2045/3573/5881 1971/3465/5882 +f 2504/2385/4694 2503/3574/5883 2506/2459/4761 +f 4057/3575/5884 4056/3571/5879 4148/3156/5416 +f 4137/2177/4504 4138/3576/5885 4107/2835/5886 +f 3870/1999/4349 3868/1998/4348 3867/2111/4440 +f 3420/3577/5887 3419/2019/4365 3398/2514/5888 +f 3464/2546/4838 3466/2209/4532 3465/3578/5889 +f 3440/3579/5890 3407/3097/5353 3442/3096/5352 +f 2919/3042/5295 2924/3580/5891 2920/3581/5892 +f 2515/3582/5893 2516/3583/5894 2517/3584/5895 +f 2930/3585/26 2929/3586/26 2986/3587/26 +f 3856/3588/5896 3854/2032/5552 3853/3285/5551 +f 3617/2432/4737 3615/2434/4739 3616/2563/4851 +f 2913/3280/5548 2918/3589/5897 3048/3436/5722 +f 3945/2260/4580 3943/3203/5470 3944/3590/5354 +f 4092/2089/5898 4091/3591/5899 4093/3487/5777 +f 3151/2192/4518 3146/2756/5021 3165/2839/5095 +f 4050/2417/5354 4052/3592/5354 4048/3593/5354 +f 2302/3594/5900 2387/3165/5423 2303/3164/5422 +f 3781/3555/5860 3766/2221/4544 3767/2054/5858 +f 4230/3595/4517 4228/3596/4517 4194/2085/4517 +f 2755/2701/4970 2756/3597/5901 2758/3598/5902 +f 3171/3599/5903 3170/3600/5904 3185/2154/4482 +f 3566/2348/4660 3565/2297/4614 3528/2296/4613 +f 2793/2878/5134 2789/2690/4958 2795/3601/5905 +f 4331/3358/5632 4332/2517/5906 4333/3359/5633 +f 3153/3531/5907 3168/3602/5908 3150/2265/5909 +f 2414/3603/5910 2437/3604/5911 2380/3605/5912 +f 2424/3149/5410 2423/3606/5913 2422/3150/5411 +f 2119/3607/5914 2123/3608/5915 2122/3609/5916 +f 3376/2664/5610 3377/3339/5609 3379/2452/5594 +f 2241/3495/5784 2380/3605/5912 2437/3604/5911 +f 4118/2876/5132 4120/2022/5135 4132/2882/5137 +f 2744/2474/4773 2840/3610/5917 2839/3611/5918 +f 2745/2472/4771 2782/3612/5919 2783/3496/5785 +f 4337/3613/5920 4338/3540/5841 4339/3498/5921 +f 3689/2007/4353 3688/2596/4877 3687/2624/4905 +f 2639/3154/5831 2638/3614/5922 2926/3535/5832 +f 3144/2068/5923 3149/2631/5924 3173/3615/5925 +f 2572/3616/5926 2315/2996/5245 2316/3617/5927 +f 3257/2841/5928 3256/3618/5929 3254/2235/5930 +f 2016/2493/5931 2014/2492/5932 2029/3619/5933 +f 2420/3519/5812 2422/3150/5411 2433/3517/5810 +f 2965/2609/4889 2958/2783/5044 3075/2610/4890 +f 2807/3620/5934 2809/2140/4468 2988/2784/5045 +f 3555/3116/5374 3537/3621/5935 3538/3622/5936 +f 3388/3448/5738 3403/2883/5937 3422/2807/5644 +f 2346/3623/5938 2348/3624/5939 2350/2259/4579 +f 2730/2954/5201 2904/3110/5367 2727/3625/5940 +f 3717/3626/5941 3708/3627/5358 3713/2862/5942 +f 4014/2080/4416 4030/2082/4418 4013/3628/5943 +f 3207/3629/5944 3215/3630/5944 3331/3631/5944 +f 2287/3632/5945 2285/3633/5946 2184/3634/5947 +f 4138/3576/5885 4145/3635/5948 4146/3636/5949 +f 4217/2321/4637 4216/2320/4636 4218/3637/5950 +f 4011/3090/5951 4028/3638/5952 4025/3258/5522 +f 3586/3409/5692 3678/3216/5482 3590/3639/5953 +f 3063/3640/5954 3006/3036/5289 3007/3333/5603 +f 2478/2275/4592 2495/2926/5178 2487/2590/4871 +f 1969/1961/4314 1967/2240/5955 2067/3552/5856 +f 3235/3017/5956 3223/3641/5957 3224/3642/5958 +f 3308/3643/5959 3307/2627/4908 3306/3644/5960 +f 3836/2031/4375 3855/2030/4374 3837/2486/4786 +f 2070/2987/4316 2068/2564/4316 2072/2508/4316 +f 3147/3381/4406 3129/3146/4406 3131/2360/4406 +f 3124/3284/4406 3151/2192/4406 3122/3463/4406 +f 3710/2246/4566 3808/3245/5512 3709/3645/5961 +f 4010/3091/5347 4009/3646/5962 3999/3089/5345 +f 3117/2264/5963 3116/2263/5964 3115/3047/5965 +f 3689/2007/4353 3686/2101/4432 3651/2008/4354 +f 2767/3647/5966 2766/2989/5238 2725/2752/5020 +f 2697/3447/5736 2698/3648/5967 2778/2971/5218 +f 3515/2171/4388 3494/2107/4388 3516/2144/4388 +f 3646/3265/5531 3643/3649/5968 3659/2447/4751 +f 2927/3516/5809 2919/3042/5295 2629/3041/5294 +f 1981/2254/4574 1982/2866/5122 2001/3650/5969 +f 2248/3651/5970 2323/3652/5971 2247/3653/5972 +f 1989/2329/5732 1991/3107/5363 1988/2268/5730 +f 3226/2182/4511 3227/3654/5973 3245/2684/4952 +f 3511/2523/4816 3530/3536/5835 3510/2046/5834 +f 2524/3655/5974 2162/3656/5975 2161/3657/5976 +f 2524/3655/5974 2161/3657/5976 2160/3658/5977 +f 2170/2947/5978 2172/3659/5979 2525/3660/5980 +f 4302/2201/4525 4392/3661/5981 4376/2602/4883 +f 2272/2481/5982 2200/3662/5983 2199/3663/5984 +f 4082/2364/4677 4081/2363/4676 4083/3664/5985 +f 2149/3665/5986 2494/3666/5987 2150/3282/5988 +f 2022/2776/4585 2005/2186/4584 2007/2185/4585 +f 3476/2938/4388 3474/2286/4388 3475/2288/4388 +f 3273/2003/4351 3240/2005/4351 3242/2159/4351 +f 3694/2830/5089 3693/3667/5989 3667/3668/5990 +f 3141/3354/5627 3143/2250/4570 3158/2249/4569 +f 3517/2524/4817 3532/3064/5320 3531/2394/4706 +f 2052/2109/4438 2042/3669/5991 2041/3670/5992 +f 2795/3601/5905 2794/3671/5993 2793/2878/5134 +f 3181/2858/5115 3168/3602/5908 3183/2695/4963 +f 3123/3171/5994 3126/3672/5995 3124/3284/5996 +f 3142/3508/5797 3156/3673/5997 3157/2248/4568 +f 3253/3102/5325 3254/2235/5930 3255/3065/5998 +f 4149/2366/4679 4121/2816/5075 4146/3636/5949 +f 4205/3674/4517 4207/2846/5503 4231/2767/5503 +f 2540/3675/5999 2480/3676/6000 2539/3677/6001 +f 2160/3658/6002 2637/3678/6003 2926/3535/5832 +f 2531/3679/6004 2541/3680/6005 2530/3681/6006 +f 2075/3682/6007 2079/2741/6008 2077/3223/6009 +f 2707/2503/4800 2806/2505/4802 2705/3683/6010 +f 2544/3684/6011 2543/3685/6012 2491/3387/5665 +f 2776/2037/4381 2763/3686/6013 2761/2038/4382 +f 3627/2470/4770 3630/2633/4912 3629/2635/4912 +f 4382/2762/5027 4290/2809/5068 4383/2761/5026 +f 3489/2848/6014 3491/2105/5688 3472/3687/6015 +f 4136/2977/6016 4135/2978/6017 4144/3074/5329 +f 3657/2578/4863 3694/2830/5089 3656/2600/6018 +f 3079/3435/5721 3026/2455/4757 3024/1970/4323 +f 3188/3688/6019 3173/3615/5925 3172/3689/6020 +f 4139/2443/4747 4159/3690/6021 4128/2566/4852 +f 3936/2128/4455 4045/3691/6022 4046/2129/4456 +f 3461/2350/4662 3565/2297/4614 3566/2348/4660 +f 2096/3692/6023 2098/3693/6024 2099/2077/6025 +f 4349/2418/4725 4364/3213/6026 4355/3694/6027 +f 3472/3687/6015 3491/2105/5688 3473/3407/5687 +f 2621/3695/6028 2620/3696/6029 2913/3280/5548 +f 3467/2208/4531 3457/2207/4531 3468/3697/4531 +f 2973/3155/26 2139/2407/26 2938/2409/511 +f 4081/2363/4676 4080/2365/4678 4079/2064/4678 +f 4379/2522/4815 4294/1977/6030 4381/2520/4813 +f 2286/2358/4671 2212/2750/5018 2311/3124/5382 +f 2556/3141/5403 2544/3684/6011 2545/3698/6031 +f 3246/2622/4903 3245/2684/6032 3247/3699/6033 +f 3170/3600/5904 3169/2857/5114 3180/2152/4480 +f 3081/3454/5742 2717/2658/4930 2718/2660/4932 +f 3364/2513/4808 3362/2724/4755 3399/3347/4755 +f 2759/3700/6034 2761/2038/4382 2760/2463/4765 +f 3120/3172/6035 3123/3171/5994 3122/3463/6036 +f 2422/3150/5411 2420/3519/5812 2432/2411/4720 +f 2541/3680/6005 2537/3247/5514 2505/2386/4695 +f 3509/2544/4836 3525/2918/6037 3524/2851/6038 +f 3103/2796/6039 3118/3701/6040 3115/3047/5301 +f 3953/3702/5000 3949/3703/5000 3952/3704/5000 +f 3591/2511/4806 3592/3705/4434 3593/3706/6041 +f 2041/3670/6042 2027/2377/6043 2026/2667/4938 +f 3034/3707/6044 2862/3708/6045 2860/3709/6046 +f 3169/2857/5114 3170/3600/5904 3148/3710/6047 +f 3285/2148/4476 3296/2290/4607 3295/2149/4477 +f 4119/2012/4367 4120/2022/4367 4090/2021/4367 +f 2556/3141/5403 2545/3698/6031 2555/3139/5401 +f 2215/3006/5256 2286/2358/4671 2311/3124/5382 +f 4282/3711/6048 4167/2648/6048 4169/2892/6048 +f 4183/3712/6049 4192/2084/6050 4222/3413/5697 +f 2592/3492/6051 2593/3453/6052 2591/3713/6053 +f 4371/3714/6054 4370/3200/5467 4378/3003/5253 +f 2941/3560/26 2975/3559/26 2939/3715/26 +f 3430/3296/5562 3425/3716/6055 3424/3295/5561 +f 3300/3717/6056 3219/3718/6057 3301/3719/6058 +f 3777/3720/6059 3763/3721/6060 3778/2905/5159 +f 3476/2938/6061 3504/3722/6062 3506/2615/6063 +f 4270/3723/6064 4240/3125/5852 4239/3230/6065 +f 4003/2226/6066 4044/3724/6067 4043/3725/6068 +f 2757/3726/6069 2763/3686/6013 2756/3597/5901 +f 1987/2330/4644 1985/3727/6070 1977/3728/6071 +f 3046/3035/5288 3050/2694/4962 3006/3036/5289 +f 2606/3729/6072 2097/2712/6073 2696/2428/4734 +f 2569/3730/6074 2323/3652/5971 2322/3731/6075 +f 2570/2632/4911 2572/3616/5926 2318/2528/4821 +f 3993/3732/5000 3959/3733/5000 3957/3428/5000 +f 3520/3734/4388 3482/2763/4388 3514/2543/4388 +f 2566/3735/6076 2321/2705/4974 2320/2704/4973 +f 4180/2891/5144 4179/2880/4924 4175/2567/4924 +f 2629/3041/5294 2153/3514/5807 2927/3516/5809 +f 3654/3309/5577 3639/2599/4880 3655/2601/4882 +f 3482/2763/6077 3483/2555/5155 3481/3736/6078 +f 2981/3737/6079 2969/3558/6080 2970/3557/6081 +f 3015/2994/5243 2168/2588/6082 2884/3738/6083 +f 1965/3739/6084 1964/3740/6085 2056/3418/5700 +f 2050/3444/5733 2053/3741/6086 2054/3445/5734 +f 2481/3742/6087 2483/3513/5806 2507/3743/6088 +f 3124/3284/4406 3126/3672/4406 3146/2756/4406 +f 1964/3740/6085 2058/2927/5179 2056/3418/5700 +f 2122/3609/5916 2120/2800/5060 2121/2410/6089 +f 4055/3744/4409 4054/2769/4408 4056/3571/5879 +f 2390/3745/6090 2263/3430/6091 2211/3208/5475 +f 3902/3055/6092 3910/2361/4674 3901/3746/6093 +f 2637/3678/6094 2160/3658/6095 2159/3153/5414 +f 2574/3747/6096 2583/3748/6097 2510/3192/6098 +f 1999/3749/6099 2000/3750/6100 1998/2379/5342 +f 2462/3390/5669 2459/2826/5085 2406/2399/4711 +f 2120/2800/5060 2130/2802/5062 2121/2410/6089 +f 3718/2911/4336 3723/3130/4336 3726/3751/4336 +f 3695/2188/6101 3579/2103/6101 3585/2173/6101 +f 2999/3752/6102 2995/3753/6103 2996/1980/6104 +f 2742/3754/6105 2764/3755/6106 2754/3756/6107 +f 4043/3725/6068 3941/3757/6108 4042/3563/5866 +f 3459/3758/6109 3454/2594/4532 3460/2214/4532 +f 3763/3721/6060 3776/3759/6110 3760/3760/6111 +f 3246/2622/4903 3243/2183/4904 3245/2684/6032 +f 3766/2221/4337 3746/3092/5348 3767/2054/4337 +f 3479/3761/6112 3477/3762/6113 3478/2384/6113 +f 3702/3763/5804 3811/3764/5804 3812/3101/5804 +f 3475/2288/4605 3502/3765/6114 3476/2938/6061 +f 3597/3340/4524 3599/3766/4524 3595/2738/4524 +f 2170/2947/5978 2526/3767/6115 2527/3768/6116 +f 3580/2537/4830 3700/2539/4830 3587/3769/4830 +f 1975/2239/4561 1968/2241/4316 1976/2506/4316 +f 3805/3770/6117 3804/3771/6118 3777/3720/6059 +f 3874/3431/4554 3856/3588/5778 3887/3402/4554 +f 3327/2040/4383 3331/3631/6119 3330/2041/4383 +f 2946/3772/6120 2947/3773/6121 2903/3375/6122 +f 4117/2875/5131 4135/2978/5226 4113/2468/5225 +f 2515/3582/5893 2508/3190/5457 2507/3743/6088 +f 2206/3774/6123 2205/3775/6124 2259/3776/6125 +f 2206/3774/6123 2258/3777/6126 2207/3778/6127 +f 2258/3777/6126 2257/2746/6128 2207/3778/6127 +f 2257/2746/6128 2208/3779/6129 2207/3778/6127 +f 2208/3779/6129 2256/2745/6130 2209/3780/6131 +f 2209/3780/6131 2256/2745/6130 2255/3781/6132 +f 2209/3780/6131 2255/3781/6132 2210/3782/6133 +f 2210/3782/6133 2255/3781/6132 2254/3783/6134 +f 2709/3784/6135 2808/2504/4801 2707/2503/4800 +f 2155/3785/6136 2633/3330/5599 2634/3329/5598 +f 3799/3198/5465 3788/3197/5464 3789/3786/6137 +f 2268/2924/6138 2204/3787/6139 2269/3788/6140 +f 4136/2977/5224 4137/2177/4504 4111/2176/4503 +f 3781/3555/5860 3792/3789/6141 3780/2222/4545 +f 2202/3790/6142 2267/3791/6143 2203/3792/6144 +f 3376/2664/5610 3379/2452/5594 3378/2873/5594 +f 2106/3793/6145 2107/2985/6146 2108/3794/6147 +f 3041/3795/6148 2870/3796/6149 2869/3797/6150 +f 4199/3108/6151 4185/3421/6152 4201/3109/6153 +f 2276/3798/6154 2195/3799/6155 2277/3800/6156 +f 3335/2773/5878 3333/2230/5878 3343/2020/4626 +f 2196/3801/6157 2276/3798/6154 2275/3438/6158 +f 2196/3801/6157 2275/3438/6158 2197/3802/6159 +f 3185/2154/4482 3096/2424/6160 3095/2790/5051 +f 1972/3467/5756 1974/3466/5755 1976/2506/4316 +f 2198/3803/6161 2273/2482/6162 2199/3663/5984 +f 4134/2874/5130 4118/2876/5132 4133/3478/5768 +f 2200/3662/5983 2272/2481/5982 2270/3804/6163 +f 2642/3805/6164 3018/3806/6165 3017/3807/6166 +f 3723/3130/4336 3721/1985/4336 3722/3183/5348 +f 3850/3808/6167 3849/3809/6168 3847/3103/5359 +f 4301/2202/4526 4296/1978/6169 4378/3003/5253 +f 3282/3810/6170 3281/2828/5087 3325/2827/5086 +f 3394/3368/5643 3421/2772/5619 3393/3346/5618 +f 3949/3703/5000 3947/2252/5000 3948/3811/5000 +f 2194/3812/6171 2283/2357/6172 2282/2356/6173 +f 3413/3813/6174 3338/3814/6175 3412/3298/5564 +f 2183/3815/6176 2281/3816/6177 2184/3634/5947 +f 3191/3817/6178 3190/3020/5271 3189/3022/5273 +f 2185/3818/6179 2285/3633/5946 2294/3819/6180 +f 2291/3820/6181 2187/3821/6182 2292/3423/6183 +f 3384/3490/5780 3387/2236/4558 3386/2238/4560 +f 2958/2783/5044 2963/2500/4797 2961/2912/5166 +f 2780/2970/5217 2698/3648/5967 2797/3144/5406 +f 2068/2564/5079 2070/2987/5079 1970/1963/5079 +f 3965/3822/6184 3948/3811/6185 3963/3823/6186 +f 3215/3630/6119 3221/3824/6187 3220/3550/4383 +f 2778/2971/5218 2777/3293/5559 2700/3269/5538 +f 2289/3426/6188 2191/3825/6189 2190/3826/6190 +f 2290/3827/6191 2190/3826/6190 2188/3828/6192 +f 4360/2716/4985 4346/3829/6193 4345/3830/6194 +f 3322/3831/6195 3292/2829/5088 3280/3832/6196 +f 2623/3279/5547 2621/3695/6028 2913/3280/5548 +f 2291/3820/6181 2189/3833/6197 2187/3821/6182 +f 3385/3491/4755 3388/3448/4755 3387/2236/4755 +f 2360/3834/6198 2359/3835/6199 2384/3836/6200 +f 3172/3689/6020 3171/3599/5903 3187/3837/6201 +f 3701/3838/5358 3707/2247/4567 3706/3839/5358 +f 3844/2395/5778 3873/2397/4554 3876/3840/4554 +f 3909/2052/6202 3908/3841/6203 3879/3842/6204 +f 2829/2441/4745 2665/2440/4744 2912/2475/4774 +f 3214/3034/5286 3218/3843/6205 3303/3844/6206 +f 2464/2449/6207 2405/3845/6208 2385/3846/6209 +f 3068/3847/6210 3069/3848/6211 3030/3082/5337 +f 2353/3849/6212 2218/2982/5229 2217/3850/6213 +f 4367/2206/4530 4376/2602/4883 4392/3661/5981 +f 2000/3750/4585 2026/2667/4584 1998/2379/4585 +f 2271/2483/4782 2266/3851/6214 2318/2528/4821 +f 2110/3852/6215 2112/3160/6216 3082/2685/4953 +f 2065/2653/4928 2048/2353/4666 2049/2542/4833 +f 3040/3317/5585 3046/3035/5288 3045/3037/5290 +f 2536/2675/4944 2533/2312/4629 2535/2311/4628 +f 3474/2286/4603 3473/3407/5687 3493/3336/5689 +f 2779/2421/4728 2794/3671/5993 2777/3293/5559 +f 3717/3626/5941 3787/3199/5466 3711/3853/6217 +f 3933/3012/5355 3932/2325/5354 3934/3854/6218 +f 4184/3422/5708 4185/3421/6152 4197/3425/5706 +f 3092/3542/6219 3204/3855/6219 3205/3856/6219 +f 2581/3483/5773 2461/3482/5772 2460/3857/6220 +f 2581/3483/5773 2460/3857/6220 2582/2095/4428 +f 2950/3858/6221 2911/3312/5580 2906/2075/4411 +f 2739/3859/6222 2740/3002/5252 2741/2593/4874 +f 3840/2178/4554 3836/2031/4554 3839/2231/4554 +f 2110/3852/6223 2111/3860/6224 2112/3160/6224 +f 4374/3068/6225 4353/3861/6226 4373/3862/6227 +f 3585/2173/4434 3579/2103/4434 3588/3863/6228 +f 3703/3864/6229 3702/3763/5358 3704/3474/5358 +f 2519/3865/6230 2179/3133/6231 2586/3866/6232 +f 4066/2073/4409 4058/2072/4408 4064/2579/6233 +f 2509/3367/5642 2479/2571/4856 2538/2570/4855 +f 2584/3867/6234 2512/3450/6235 2511/3366/6236 +f 2584/3867/6234 2511/3366/6236 2583/3748/6097 +f 2816/3868/6237 2803/3869/6238 2815/3023/5274 +f 3783/3870/6239 3794/3871/6240 3782/3554/6241 +f 4007/3872/6242 3986/3873/6243 4008/3874/6244 +f 3830/2650/4690 3832/1993/4690 3826/2984/4688 +f 3121/3875/6245 3122/3463/4406 3152/2194/4406 +f 3551/2813/5072 3538/3622/5936 3539/2960/5207 +f 2350/2259/4579 2166/3257/6246 2168/2588/6247 +f 3656/2600/6018 3667/3668/5990 3655/2601/4882 +f 2022/2776/6248 2015/3274/5764 2033/3476/5766 +f 3950/2242/5001 3952/3704/5000 3949/3703/5000 +f 2593/3453/5741 2592/3492/5781 2719/2659/4931 +f 3415/2196/6249 3426/3876/6250 3445/3877/6251 +f 2925/3878/6252 2922/3500/5789 2921/3499/5788 +f 3797/2793/5054 3798/2792/5053 3717/3626/5941 +f 4119/2012/4358 4130/2266/4583 4131/2881/5136 +f 3190/3020/5271 3193/3399/5680 3155/3509/6253 +f 3518/2170/4499 3532/3064/5320 3517/2524/4817 +f 3599/3766/4524 3597/3340/4524 3598/3879/4524 +f 2814/3880/6254 2813/3881/6255 2987/2785/5046 +f 2813/3881/6255 2812/2786/5047 2987/2785/5046 +f 2814/3880/6254 2987/2785/5046 2714/2897/5149 +f 4123/3882/6256 4122/2815/5074 4152/3032/5284 +f 2078/2740/6257 2080/2457/5635 2383/3360/5634 +f 2004/2184/4514 2006/2865/4515 2007/2185/4515 +f 3139/2300/6258 3138/1964/6259 3108/3883/6260 +f 4363/3214/5480 4388/3884/6261 4389/3215/5481 +f 3840/2178/4506 3839/2231/6262 3866/2112/4507 +f 3967/2270/6263 3949/3703/6264 3965/3822/6184 +f 3719/1986/5394 3729/2910/5164 3731/3885/6265 +f 4211/3456/5503 4212/3886/4517 4232/2606/5503 +f 2246/2703/4972 2445/2092/4425 2443/3121/5379 +f 3184/2153/4481 3180/2152/4480 3181/2858/5115 +f 2342/3239/5506 2350/2259/4579 2526/3767/6115 +f 3275/2219/4542 3274/2137/4465 3313/3887/6266 +f 2847/2497/4794 2846/3888/6267 2736/2901/5154 +f 3850/3808/6167 3847/3103/5359 3848/3889/5359 +f 2542/3388/5666 2524/3655/5974 2490/3386/5664 +f 3772/3181/5445 3787/3199/6268 3786/3182/5446 +f 2820/3432/5717 2810/2138/4466 2709/3784/6135 +f 3837/2486/4786 3855/2030/4374 3858/2313/4787 +f 3595/2738/4524 3601/3044/5297 3602/3890/4524 +f 1995/2972/5344 1996/2378/5343 1994/3891/6269 +f 3150/2265/4406 3117/2264/4406 3119/3532/4406 +f 2958/2783/5044 2957/3892/6270 3075/2610/4890 +f 2228/2494/4791 2227/3893/6271 2229/3894/6272 +f 2481/3742/6087 2480/3676/6000 2540/3675/5999 +f 2051/3895/6273 2042/3669/5991 2053/3741/6086 +f 2923/3138/5399 2922/3500/5789 3064/3228/5496 +f 4379/2522/4815 4374/3068/5323 4373/3862/6274 +f 2962/2782/6275 2972/3896/6276 2971/2934/6277 +f 3665/3132/6278 3680/3897/6279 3664/3898/6280 +f 3441/3899/6281 3439/2015/4361 3440/3579/5890 +f 3284/3900/6282 3271/2004/6283 3273/2003/6284 +f 3605/2737/6285 3606/2198/6285 3608/2200/6286 +f 4365/3901/6287 4364/3213/5479 4391/3902/6288 +f 3794/3871/6240 3796/3903/6289 3716/3114/5371 +f 3822/3234/6290 3920/3457/5746 3921/2372/4686 +f 3137/3904/4406 3139/2300/4406 3140/2069/4406 +f 3105/1988/4338 3125/2216/4538 3104/2795/5433 +f 4370/3200/5467 4369/3201/6291 4377/2203/4527 +f 3417/2935/5183 3429/2869/5125 3416/2868/5124 +f 3564/3905/6292 3527/2298/4615 3565/2297/4614 +f 2025/2944/4585 1994/3891/4585 1996/2378/4585 +f 2246/2703/4972 2248/3651/5970 2445/2092/4425 +f 4009/3646/5962 4020/3906/6293 4008/3874/6294 +f 3404/2162/4491 3390/3907/6295 3405/2160/4489 +f 3715/3908/6296 3797/2793/5054 3717/3626/5941 +f 3962/3909/6297 3964/3910/6298 3963/3823/6299 +f 3891/3318/5586 3878/3187/5453 3892/3911/6300 +f 3821/2540/4831 3914/2291/4608 3820/2375/4689 +f 4100/2744/4367 4102/2743/4367 4109/3148/4367 +f 3567/2167/4496 3570/2166/4495 3462/3912/6301 +f 3107/1965/4318 3134/2485/4784 3106/1989/4339 +f 4034/3913/6302 4035/3914/6303 4033/3915/6304 +f 2453/3290/5556 2133/3369/5645 2132/3291/5557 +f 2737/1967/4320 2741/2593/4874 2740/3002/5252 +f 3595/2738/4524 3599/3766/4524 3601/3044/5297 +f 3536/2460/4762 3554/3505/5794 3552/2461/4763 +f 3289/2626/4907 3306/3644/5960 3307/2627/4908 +f 3824/1983/4688 3823/2649/4688 3827/1984/4690 +f 3280/3832/6196 3279/3080/5335 3322/3831/6195 +f 3804/3771/6118 3805/3770/6117 3803/3262/5528 +f 3618/2433/4738 3617/2432/4737 3619/3916/6305 +f 3456/3917/6306 3560/3918/6307 3561/2115/4444 +f 2055/3919/6308 2057/3417/5699 2029/3619/5933 +f 4162/3416/4409 4166/3415/4409 4164/2580/4409 +f 3311/3920/6309 3313/3887/6266 3312/3921/6310 +f 2692/2689/4957 2788/2668/4939 2693/3544/5844 +f 4166/3415/6311 4060/3414/6311 4064/2579/6312 +f 3699/2187/6313 3587/3769/6313 3700/2539/6313 +f 3382/2043/6314 3385/3491/5780 3384/3490/5780 +f 2211/3208/5475 2361/3922/6315 2390/3745/6090 +f 3758/2163/6316 3726/3751/6317 3757/2164/6318 +f 2879/2344/4656 2878/3923/6319 2876/3924/6320 +f 3171/3599/5903 3186/2791/5052 3187/3837/6201 +f 2099/2077/6321 2098/3693/6322 2601/3925/6323 +f 4253/3926/6324 4252/3927/6325 4263/3304/5570 +f 3998/3522/5815 4011/3090/5346 3999/3089/5345 +f 2248/3651/5970 2247/3653/5972 2444/2090/4423 +f 3312/3921/6310 3274/2137/4465 3293/3928/6326 +f 3506/2615/4896 3508/2383/4692 3507/2382/4691 +f 3398/2514/5888 3418/2937/5185 3400/2936/5184 +f 2015/3274/5764 2031/3929/6327 2032/3475/5765 +f 3297/3930/6328 3283/3931/6329 3298/3932/6330 +f 1987/2330/5731 1986/2267/6331 1985/3727/6331 +f 2325/3933/6332 2320/2704/4973 2246/2703/4972 +f 3160/3355/6333 3159/2822/5081 3179/2821/5080 +f 2610/3934/6334 2609/2915/6335 2086/2843/6336 +f 2257/2746/5014 2258/3777/6337 2251/2747/5015 +f 2784/3371/5647 2783/3496/5785 2782/3612/5919 +f 4273/3935/6338 4171/3936/6339 4276/3066/5321 +f 2563/2339/4651 2329/2341/4653 2327/3937/6340 +f 2148/3040/5293 2919/3042/5295 2918/3589/5897 +f 2499/2025/4369 2500/2654/4929 2502/2387/4696 +f 3758/2163/4492 3759/2165/4494 3728/3938/6341 +f 3650/2100/6342 3636/2133/4460 3651/2008/4462 +f 4074/2059/4367 4073/3568/5872 4070/2431/4367 +f 3108/3883/6260 3109/2389/6343 3110/2070/6344 +f 2155/3785/6345 2158/3534/5830 2926/3535/5832 +f 3206/3015/4383 3209/3939/6119 3207/3629/6119 +f 3593/3706/6041 3583/2174/4434 3584/3322/4434 +f 4220/3940/6346 4217/2321/4637 4218/3637/5950 +f 3100/1966/4319 3101/2388/4699 3109/2389/4701 +f 3918/3319/5587 3920/3457/5746 3817/3941/6347 +f 3963/3823/6299 3964/3910/6298 3966/3942/6348 +f 3695/2188/6349 3580/2537/6349 3579/2103/6349 +f 2509/3367/5642 2538/2570/4855 2539/3677/6001 +f 3095/2790/5051 3091/3943/6350 3186/2791/5052 +f 4008/3874/6294 4021/3944/6351 4047/2127/4454 +f 2084/3945/6352 2605/3946/6353 2603/3947/6354 +f 2925/3878/6252 3053/3948/6355 3054/3949/6356 +f 2075/3682/6357 2606/3729/6358 2074/3176/6359 +f 2089/2968/6360 2219/3389/5668 2091/2887/5667 +f 3883/3950/4554 3859/2315/4554 3881/2707/4554 +f 3576/2213/4536 3460/2214/4536 3577/2595/4536 +f 4303/3276/4422 4311/3951/6361 4309/2519/4422 +f 1991/3107/4585 2019/2613/4585 1988/2268/4585 +f 3779/2904/5158 3809/3952/6362 3808/3245/5512 +f 4267/3953/6363 4266/3954/6364 4180/2891/5144 +f 2290/3827/6191 2289/3426/6188 2190/3826/6190 +f 3734/2753/6365 3735/2066/6366 3733/3134/6367 +f 2389/3955/6368 2409/3396/5677 2435/3956/6369 +f 3771/3957/6370 3765/2755/6371 3789/3786/6372 +f 3457/2207/4531 3458/2336/5703 3462/3912/4532 +f 4385/2715/4984 4290/2809/5068 4361/3057/5313 +f 3640/2150/4524 3621/3565/4524 3639/2599/4524 +f 2150/3282/5550 2148/3040/5293 2913/3280/5548 +f 2181/2913/6373 2613/2502/6374 2178/2933/6375 +f 3142/3508/4406 3135/3158/5056 3137/3904/4406 +f 3504/3722/6062 3476/2938/6061 3502/3765/6114 +f 2615/3958/6376 2614/3959/6377 2616/3960/6378 +f 2615/3958/6376 2616/3960/6378 2617/3169/6379 +f 3250/3071/6380 3248/3193/6381 3227/3654/5973 +f 3149/2631/4406 3144/2068/4406 3112/2317/4406 +f 3388/3448/5738 3404/2162/4491 3403/2883/5937 +f 2311/3124/5382 2310/3961/6382 2215/3006/5256 +f 2012/3962/6383 1986/2267/6383 2013/2061/6383 +f 2624/3963/6384 2623/3279/6385 2625/3115/6386 +f 3473/3407/4388 3476/2938/4388 3472/3687/4388 +f 3675/2445/4749 3676/2510/4805 3673/2637/4915 +f 2622/3964/6387 2626/3965/6388 2620/3696/6389 +f 3694/2830/5089 3667/3668/5990 3656/2600/6018 +f 3371/3028/5280 3369/3966/6390 3370/2884/6390 +f 2627/3281/6391 2626/3965/6388 2628/3569/5876 +f 4314/2122/4422 4316/3967/4422 4352/1996/4422 +f 2862/3708/6045 2859/3968/6392 2860/3709/6046 +f 4176/2779/5040 4277/2778/5039 4276/3066/5321 +f 3359/3969/6393 3360/2723/4992 3361/2722/4991 +f 2482/3970/6394 2540/3675/5999 2541/3680/6005 +f 2914/3062/5317 2916/3170/5430 2618/2228/5429 +f 3103/2796/6039 3115/3047/5301 3102/3046/5300 +f 3458/2336/4650 3574/2512/4650 3572/2337/4650 +f 2855/3971/6395 2857/3972/6396 2856/3973/6397 +f 3540/2621/4902 3519/3974/6398 3541/2533/6399 +f 2852/2674/4943 2893/2673/4942 2892/3975/6400 +f 2194/3812/6171 2201/3084/5339 2280/3085/5341 +f 4048/3593/5817 3932/2325/5817 3931/3976/5817 +f 2238/2293/4610 2436/2840/5096 2233/2294/4611 +f 2253/2922/5174 2446/3301/5567 2250/2923/5175 +f 2629/3041/6401 2631/3977/6402 2153/3514/6403 +f 3038/2526/4819 2866/3978/6404 2863/3979/6405 +f 3352/2656/6406 3369/3966/6407 3371/3028/6408 +f 3746/3092/5348 3766/2221/4337 3770/2223/4337 +f 2801/3373/5649 2691/3372/5648 2690/3980/6409 +f 3936/2128/4455 4047/2127/4454 3945/2260/4580 +f 2155/3785/6136 2635/3981/6410 2158/3534/6411 +f 2102/2010/6412 2602/2427/6413 2601/3925/6323 +f 2418/3249/5516 2426/3400/5681 2431/3151/5412 +f 2640/3982/6414 2158/3534/6411 2635/3981/6410 +f 2328/3983/6415 2327/3937/6340 2242/3250/5517 +f 2637/3678/6094 2641/3984/6416 2161/3657/6417 +f 2161/3657/6417 2641/3984/6416 2163/3985/6418 +f 3325/2827/5086 3292/2829/5088 3324/3986/6419 +f 2731/2751/5019 2765/2498/4795 2736/2901/5154 +f 2479/2571/4856 2307/3987/6420 2306/2572/4857 +f 3193/3399/5680 3190/3020/5271 3192/3052/5308 +f 3835/2381/6421 3847/3103/6422 3849/3809/6423 +f 3896/2706/4975 3924/3988/6424 3923/3142/5404 +f 3378/2873/5129 3353/2665/4934 3376/2664/4933 +f 2689/2670/4941 2690/3980/6409 2691/3372/5648 +f 2692/2689/4957 2693/3544/5844 2694/3989/6425 +f 2113/3159/5417 2111/3860/6426 2112/3160/5418 +f 3118/3701/6427 3117/2264/5963 3115/3047/5965 +f 2958/2783/5044 2962/2782/5043 2963/2500/4797 +f 2055/3919/6308 1965/3739/6084 2056/3418/5700 +f 2904/3110/5367 2909/3990/6428 2908/3991/6429 +f 2698/3648/5967 2078/2740/6430 2076/3177/6431 +f 2699/2272/4589 2603/3947/6432 2697/3447/5736 +f 2697/3447/5736 2603/3947/6432 2604/3992/6433 +f 2522/2276/4593 2478/2275/4592 2520/3993/6434 +f 2609/2915/5169 2611/2273/4590 2700/3269/5538 +f 2700/3269/5538 2701/2036/4380 2609/2915/5169 +f 2030/3994/6435 2031/3929/6327 2017/3273/6436 +f 2703/3995/6437 2091/2887/6438 2704/3996/6439 +f 2858/3997/6440 3033/3998/6441 2860/3709/6046 +f 2702/3385/5663 2704/3996/6439 2094/2914/5168 +f 2707/2503/4800 2708/3999/6442 2709/3784/6135 +f 2805/4000/6443 2711/4001/6444 2710/4002/6445 +f 4047/2127/4454 4021/3944/6351 3945/2260/4580 +f 2559/4003/6446 2525/3660/5980 2524/3655/5974 +f 3628/3443/4524 3636/2133/4524 3630/2633/4524 +f 3897/2708/4977 3874/3431/5716 3898/3401/5682 +f 2240/4004/6447 2380/3605/5912 2241/3495/5784 +f 3057/3501/5790 3054/3949/6356 3056/3233/5501 +f 2040/2110/4439 2052/2109/4438 2041/3670/5992 +f 3918/3319/5587 3891/3318/5586 3919/3458/5747 +f 2730/2954/5201 2723/3093/5349 2722/2952/5199 +f 2572/3616/5926 2570/2632/4911 2552/2392/4704 +f 4028/3638/5952 4012/3523/6448 4030/2082/4418 +f 3121/3875/6449 3120/3172/6035 3122/3463/6036 +f 4001/2279/4596 3990/4005/6450 3991/2280/4597 +f 4282/3711/6048 4169/2892/6048 4283/4006/6048 +f 3780/2222/4545 3809/3952/6362 3779/2904/5158 +f 2332/4007/6451 2340/3364/5639 2523/3420/5702 +f 3402/2885/6452 3400/2936/5184 3417/2935/5183 +f 2203/3792/6144 2265/4008/6453 2195/3799/6155 +f 3362/2724/4993 3363/3332/5391 3361/2722/4991 +f 3998/3522/5000 3966/3942/5000 3964/3910/5000 +f 2299/2895/5147 2300/4009/6454 2397/4010/6455 +f 3029/3100/5357 2890/2957/5204 2891/4011/6456 +f 3657/2578/4863 3645/4012/6457 3658/2446/4750 +f 2728/2988/5237 2727/3625/5940 2729/4013/6458 +f 3971/3524/5000 3986/3873/5000 3973/4014/5000 +f 4293/4015/4329 4292/2604/4329 4299/4016/4329 +f 2289/3426/6188 2288/2735/6459 2191/3825/6189 +f 2732/4017/6460 2731/2751/5019 2736/2901/5154 +f 3382/2043/6314 3383/4018/6314 3385/3491/5780 +f 2391/4019/6461 2396/3551/5854 2263/3430/6462 +f 2398/2896/5148 2389/3955/6368 2298/2734/5002 +f 3406/4020/6463 3423/2283/4600 3436/2282/4599 +f 3020/4021/6464 2958/2783/5044 2961/2912/5166 +f 4277/2778/5039 4243/2991/5240 4275/2993/5242 +f 3065/3446/5735 3048/3436/5722 3058/4022/6465 +f 2311/3124/5382 2530/3681/6006 2310/3961/6382 +f 3084/4023/4731 3086/3053/4731 3085/2678/4731 +f 4387/3056/5312 4388/3884/6261 4362/2420/4727 +f 4246/2607/4887 4247/2765/6466 4231/2767/6467 +f 2027/2377/6043 2042/3669/5991 2025/2944/5190 +f 2871/4024/6468 2870/3796/6149 3039/4025/6469 +f 2932/4026/26 2935/4027/512 2981/3737/26 +f 4028/3638/5952 4030/2082/4418 4027/3553/5857 +f 4339/3498/4422 4341/3539/4422 4351/3497/4422 +f 3021/4028/6470 3076/2611/4891 3075/2610/4890 +f 3207/3629/6471 3327/2040/6471 3326/2039/6471 +f 1970/1963/4316 1966/2535/4828 1962/2820/6472 +f 3351/2854/5111 3350/4029/6473 3365/2855/5112 +f 4190/3461/5750 4218/3637/6474 4216/2320/5751 +f 2827/4030/6475 2856/3973/6397 2825/4031/6476 +f 2797/3144/5406 2695/3338/5607 3082/2685/4953 +f 3641/4032/6477 3662/3442/6478 3661/3382/5658 +f 4055/3744/4409 4056/3571/5879 4057/3575/4409 +f 4133/3478/6479 4132/2882/6480 4142/4033/6481 +f 2590/3493/5782 2124/4034/6482 2718/2660/4932 +f 4318/3348/6483 4315/4035/6484 4317/4036/6485 +f 3504/3722/6486 3505/2614/4895 3506/2615/4896 +f 4186/2832/5091 4187/2210/4533 4204/2212/4535 +f 3716/3114/5371 3810/3113/5370 3794/3871/6240 +f 4261/2028/4372 4262/2597/4878 4267/3953/6363 +f 2560/3077/5332 2559/4003/6446 2558/4037/6487 +f 2221/2495/4792 2393/2559/4847 2091/2887/5667 +f 2285/3633/5946 2185/3818/6179 2184/3634/5947 +f 3437/2281/4598 3434/2161/4490 3436/2282/4599 +f 2617/3169/6379 2619/2229/4552 2618/2228/4551 +f 3265/2034/4378 3264/2135/4463 3275/2219/4542 +f 2721/4038/6488 2686/2953/5200 2715/3135/5396 +f 2693/3544/5844 2689/2670/4941 2694/3989/6425 +f 2557/4039/6489 2544/3684/6011 2556/3141/5403 +f 3541/2533/6399 3520/3734/6490 3542/4040/6491 +f 2777/3293/5559 2796/4041/6492 2776/2037/4381 +f 4084/3010/5262 4085/3011/5264 4083/3664/5985 +f 3223/3641/5957 3233/3019/6493 3231/4042/6494 +f 2564/3140/5402 2329/2341/4653 2562/2340/4652 +f 3256/3618/5929 3255/3065/5998 3254/2235/5930 +f 2701/2036/4380 2761/2038/4382 2702/3385/5663 +f 2774/3530/5828 2801/3373/5649 2800/2636/4914 +f 2743/4043/6495 2744/2474/4773 2764/3755/6106 +f 3036/2859/5116 3072/3489/5779 3035/3039/5292 +f 3836/2031/4375 3852/3286/6496 3854/2032/4376 +f 4334/2617/6497 4335/2616/6498 4336/2638/6499 +f 3922/1982/4333 3921/2372/4686 3894/2371/4685 +f 3819/2374/4796 3925/2499/4796 3926/3546/4796 +f 3813/3212/5358 3812/3101/5358 3811/3764/5358 +f 3951/4044/6500 3950/2242/4562 3972/4045/6501 +f 2028/4046/6502 2047/2612/6503 2055/3919/6308 +f 3025/2405/4717 2894/2404/4716 2895/2454/4756 +f 2345/3241/5508 2346/3623/5938 2350/2259/4579 +f 2503/3574/5883 2518/4047/6504 2515/3582/5893 +f 2918/3589/5897 2919/3042/5295 3048/3436/5722 +f 3277/2117/4446 3276/2035/4541 3320/2118/4447 +f 3334/3512/5805 3433/3059/5315 3435/2301/4618 +f 2081/2458/4760 2084/3945/6505 2082/2456/4758 +f 2478/2275/4592 2486/2277/4594 2495/2926/5178 +f 2422/3150/5411 2421/4048/6506 2433/3517/5810 +f 3589/3323/6507 3654/3309/5577 3690/3434/5719 +f 2014/2492/5932 2047/2612/4892 2028/4046/6508 +f 2931/4049/26 2928/4050/26 2984/4051/26 +f 2745/2472/4771 2744/2474/4773 2743/4043/6495 +f 2974/3351/26 2942/3561/26 2943/4052/26 +f 2947/3773/26 2946/3772/26 2930/3585/26 +f 4258/4053/6509 4239/3230/5498 4224/3229/5497 +f 2298/2734/5002 2295/2962/6510 2296/2961/6511 +f 2397/4010/6455 2398/2896/5148 2299/2895/5147 +f 4101/2742/6512 4099/3529/5873 4074/2059/4397 +f 3510/2046/5834 3528/2296/5720 3513/3168/5427 +f 2812/2786/5047 2807/3620/5934 2988/2784/5045 +f 4127/2444/4748 4126/3362/5637 4158/2442/4746 +f 2802/4054/6513 2721/4038/6488 2803/3869/6238 +f 2712/2899/5151 2813/3881/6255 2814/3880/6254 +f 3420/3577/5887 3398/2514/5888 3399/3347/5620 +f 2327/3937/6340 2243/3049/5304 2242/3250/5517 +f 3518/2170/4388 3495/3337/4388 3515/2171/4388 +f 4012/3523/6448 4028/3638/5952 4011/3090/5951 +f 3260/3145/6514 3257/2841/5928 3259/3226/6515 +f 3119/3532/4406 3121/3875/6245 3153/3531/4406 +f 2406/2399/4711 2407/2401/4713 2382/3477/5767 +f 3522/4055/4388 3490/2847/4388 3523/2585/4388 +f 3472/3687/4388 3470/2554/4388 3471/2556/4388 +f 2811/2139/4467 2816/3868/6237 2809/2140/4468 +f 4359/3202/5469 4369/3201/5468 4370/3200/6516 +f 2521/4056/6517 2522/2276/4593 2520/3993/6434 +f 3875/4057/6518 3889/2053/6519 3876/3840/6520 +f 2983/4058/26 2943/4052/26 2944/4059/26 +f 4038/3470/5759 4039/4060/6521 4018/2818/5077 +f 4254/4061/6522 4235/4062/6523 4253/3926/6524 +f 4105/2836/6525 4102/2743/5011 4103/4063/6526 +f 3611/3341/6527 3614/4064/4850 3613/2562/4850 +f 3569/2717/4986 3549/2719/4988 3548/4065/6528 +f 3781/3555/5860 3714/3112/5369 3792/3789/6141 +f 2096/3692/6529 2075/3682/6530 2095/3178/6531 +f 1968/2241/4316 1967/2240/4316 1969/1961/4314 +f 3551/2813/5072 3555/3116/5374 3538/3622/5936 +f 3880/4066/6532 3905/2305/6533 3885/2787/5048 +f 2745/2472/4771 2743/4043/6495 2782/3612/5919 +f 2303/3164/5422 2304/3503/5792 2301/3502/5791 +f 4112/2175/4502 4137/2177/4504 4107/2835/5886 +f 3112/2317/4634 3113/2319/4635 3114/2630/6534 +f 3206/3015/6535 3328/2672/6535 3213/2920/6535 +f 4363/3214/5480 4362/2420/4727 4388/3884/6261 +f 4320/2951/6536 4323/3288/6537 4321/3349/6538 +f 2002/3334/6539 2001/3650/6540 2003/4067/6541 +f 2243/3049/5304 2439/3251/5518 2242/3250/5517 +f 2805/4000/6443 2705/3683/6010 2806/2505/4802 +f 3933/3012/5265 4018/2818/5077 4040/3013/5266 +f 2110/3852/6215 3082/2685/4953 2598/4068/6542 +f 3769/4069/4336 3750/2132/4336 3748/2550/4336 +f 2231/2332/4646 2228/2494/4791 2230/2333/4647 +f 3586/3409/5692 3677/4070/6543 3662/3442/5729 +f 3954/4071/5000 3949/3703/5000 3953/3702/5000 +f 4374/3068/5323 4379/2522/4815 4380/2521/4814 +f 2049/2542/4833 2035/2541/4832 2034/2760/5025 +f 2290/3827/6191 2189/3833/6197 2291/3820/6181 +f 3787/3199/5466 3799/3198/5465 3711/3853/6217 +f 2348/3624/5939 2347/3128/5386 2350/2259/4579 +f 3771/3957/4336 3734/2753/4336 3765/2755/4337 +f 4329/2981/6544 4328/3549/5851 4327/3548/5850 +f 2425/2091/4424 2419/3120/5378 2445/2092/4425 +f 2339/4072/6545 2332/4007/6451 2338/4073/6546 +f 3396/3045/4808 3372/2931/4755 3401/2195/4808 +f 4254/4061/6522 4265/3303/5569 4264/3305/5571 +f 3182/2696/4964 3183/2695/4963 3167/4074/6547 +f 2480/3676/6000 2508/3190/5457 2510/3192/5459 +f 3150/2265/4406 3148/3710/4406 3116/2263/4406 +f 3060/3137/5398 3070/3543/5843 3069/3848/6211 +f 4190/3461/5750 4191/3270/5539 4219/3272/5541 +f 4329/2981/6544 4330/3357/5631 4328/3549/5851 +f 4270/3723/6064 4239/3230/6065 4269/4075/6548 +f 2692/2689/4957 2742/3754/6105 2753/4076/6549 +f 2692/2689/4957 2753/4076/6549 2789/2690/4958 +f 2789/2690/4958 2753/4076/6549 2752/4077/6550 +f 2789/2690/4958 2752/4077/6550 2758/3598/5902 +f 3147/3381/5657 3162/3380/5656 3145/2757/5022 +f 2186/4078/6551 2292/3423/6183 2187/3821/6182 +f 2854/3083/5338 2682/3300/5566 2824/3525/5819 +f 2357/4079/6552 2212/2750/5018 2279/4080/6553 +f 2412/3242/5509 2414/3603/5910 2380/3605/5912 +f 2832/4081/6554 2759/3700/6034 2831/2465/4767 +f 3252/3069/5325 3253/3102/5325 3251/3070/5326 +f 2760/2463/4765 2831/2465/4767 2759/3700/6034 +f 2587/2448/4752 2386/2450/4754 2588/4082/6555 +f 2986/3587/6556 2948/4083/6557 2947/3773/6121 +f 3092/3542/4731 3095/2790/4731 3096/2424/4731 +f 3526/2916/5170 3564/3905/6292 3563/2917/5171 +f 1963/3488/6558 2069/2565/6559 2068/2564/6558 +f 2836/2700/4969 2751/2702/4971 2837/4084/6560 +f 4225/3462/6561 4226/4085/6562 4244/3061/6563 +f 3410/4086/6564 3411/3297/5563 3341/2000/5153 +f 4064/2579/4864 4058/2072/6565 4164/2580/4864 +f 2971/2934/6277 2963/2500/6566 2962/2782/6275 +f 2746/2473/4772 2840/3610/5917 2744/2474/4773 +f 2841/4087/6567 2746/2473/4772 2749/4088/6568 +f 2841/4087/6567 2749/4088/6568 2842/4089/6569 +f 2842/4089/6569 2747/2728/4997 2843/4090/6570 +f 2052/2109/4438 1975/2239/4561 2053/3741/6086 +f 2739/3859/6222 2843/4090/6570 2747/2728/4997 +f 2643/4091/6571 2642/3805/6572 2163/3985/6418 +f 4148/3156/5416 4150/2368/4681 4147/2367/4680 +f 2395/2713/4982 2095/3178/5443 2076/3177/5442 +f 2741/2593/4874 2683/4092/6573 2739/3859/6222 +f 4386/2811/5070 4387/3056/5312 4361/3057/5313 +f 4364/3213/6026 4365/3901/6574 4355/3694/6027 +f 2650/4093/6575 2733/2560/4848 2845/4094/6576 +f 4362/2420/4727 4363/3214/6577 4349/2418/4725 +f 2654/4095/6578 2846/3888/6267 2847/2497/4794 +f 1984/3224/6579 1985/3727/6070 2012/3962/6580 +f 3902/3055/5311 3884/4096/6581 3886/2789/5050 +f 2530/3681/6006 2540/3675/5999 2529/2642/4919 +f 4157/4097/6582 4125/4098/6583 4156/3196/5463 +f 2712/2899/5151 2806/2505/4802 2813/3881/6255 +f 2828/3363/5638 2674/2619/4900 2673/4099/6584 +f 2675/4100/6585 2851/2618/4899 2676/4101/6586 +f 2676/4101/6586 2851/2618/4899 2852/2674/6587 +f 2677/4102/6588 2676/4101/6588 2852/2674/6588 +f 2853/2956/5203 2678/4103/6589 2677/4102/6590 +f 2853/2956/5203 2677/4102/6590 2852/2674/6591 +f 3941/3757/6108 4044/3724/6067 3942/3098/6592 +f 2398/2896/5148 2298/2734/5002 2284/2736/5004 +f 3644/4104/4524 3619/3916/4524 3617/2432/4524 +f 2976/2974/26 2940/4105/26 2939/3715/26 +f 3070/3543/5843 3060/3137/5398 3071/4106/6593 +f 4262/2597/4878 4254/4061/6522 4266/3954/6364 +f 2854/3083/5338 2826/4107/6594 2680/4108/6595 +f 2884/3738/6083 2166/3257/6596 2164/4109/6597 +f 3225/3016/6598 3239/2157/6599 3237/2398/6600 +f 3753/2466/6601 3755/3294/6602 3725/4110/6603 +f 3397/4111/4755 3379/2452/4755 3377/3339/4808 +f 4232/2606/5503 4212/3886/4517 4214/2491/4517 +f 2462/3390/6604 2587/2448/4752 2585/2094/4427 +f 3035/3039/5292 3072/3489/5779 3073/3433/5718 +f 2128/4112/6605 2127/4113/6606 2125/4114/6607 +f 2861/4115/6608 2862/3708/6045 2863/3979/6405 +f 2861/4115/6608 2863/3979/6405 2864/4116/6609 +f 2954/4117/6610 2970/3557/5862 2955/4118/6611 +f 2866/3978/6404 2864/4116/6609 2863/3979/6405 +f 2865/4119/6612 2866/3978/6404 2868/4120/6613 +f 3416/2868/5124 3428/2867/5123 3415/2196/6249 +f 4344/2123/4422 4345/3830/4422 4342/4121/4422 +f 2993/4122/6614 2975/3559/6615 2988/2784/6616 +f 2867/4123/6617 2869/3797/6150 2870/3796/6149 +f 2872/4124/6618 2874/3316/5584 2873/4125/6619 +f 2103/2011/6620 2600/2683/6621 3082/2685/4953 +f 2874/3316/5584 2875/4126/6622 2873/4125/6619 +f 3644/4104/6623 3656/2600/4881 3639/2599/4880 +f 3976/4127/6624 3974/4128/6625 3973/4014/6626 +f 2539/3677/6001 2538/2570/4855 2529/2642/4919 +f 2879/2344/4656 2876/3924/6320 2877/2342/4654 +f 2228/2494/4791 2231/2332/4646 2436/2840/5096 +f 2881/4129/6627 2880/2995/5244 2882/4130/6628 +f 2881/4129/6627 2882/4130/6628 2883/4131/6629 +f 3277/2117/4697 3263/2033/4377 3276/2035/4379 +f 2827/4030/6475 2886/2861/5118 2855/3971/6395 +f 2855/3971/6395 2886/2861/5118 2887/2860/6630 +f 2827/4030/6475 2825/4031/6476 2826/4107/6594 +f 3075/2610/4890 3020/4021/6464 3021/4028/6470 +f 2824/3525/5819 2889/3081/5336 2854/3083/5338 +f 2523/3420/5702 2526/3767/6115 2525/3660/5980 +f 2687/4132/6631 3081/3454/5742 2817/2990/5239 +f 3514/2543/4835 3543/4133/6632 3520/3734/6490 +f 3802/3263/5529 3803/3262/5528 3775/4134/6633 +f 3566/2348/4660 3568/2168/4497 3567/2167/4496 +f 4163/4135/5263 4054/2769/6634 4161/4136/6634 +f 3087/4137/4731 3091/3943/4731 3085/2678/4731 +f 3936/2128/4455 3935/3060/5354 3942/3098/5354 +f 2671/4138/6635 2895/2454/4756 2828/3363/5638 +f 3547/2393/4705 3531/2394/4706 3532/3064/5320 +f 4326/3289/6636 4323/3288/6537 4324/3408/6637 +f 4043/3725/6068 4044/3724/6067 3941/3757/6108 +f 2352/4139/6638 2164/4109/6639 2166/3257/6246 +f 2558/4037/6487 2543/3685/6012 2557/4039/6489 +f 4044/3724/6067 4005/3439/6640 4045/3691/6022 +f 3791/4140/6641 3764/4141/6642 3761/4142/6643 +f 4114/4143/5277 4115/2013/5277 4092/2089/4367 +f 4311/3951/6644 4338/3540/6645 4310/3419/5701 +f 3714/3112/5369 3781/3555/5860 3810/3113/5370 +f 3829/2307/4688 3826/2984/4688 3828/2362/4688 +f 3733/3134/5395 3719/1986/5394 3731/3885/6265 +f 2517/3584/6646 2580/3253/6647 2574/3747/6096 +f 3762/2698/4336 3752/2130/4336 3768/4144/4336 +f 3305/4145/6648 3218/3843/6205 3210/4146/6649 +f 3454/2594/4532 3459/3758/6109 3456/3917/4532 +f 3230/4147/6650 3231/4042/6651 3232/4148/6652 +f 4304/2088/5543 4315/4035/6653 4313/3277/5544 +f 4244/3061/5316 4243/2991/5240 4277/2778/5039 +f 3782/3554/5859 3767/2054/5858 3773/2056/6654 +f 3895/2946/6655 3882/2413/6656 3883/3950/6657 +f 2502/2387/4696 2500/2654/4929 2501/4149/6658 +f 2032/3475/6659 2031/3929/6327 2063/4150/6660 +f 2735/2561/4849 2737/1967/4320 2740/3002/5252 +f 2526/3767/6115 2170/2947/5978 2525/3660/5980 +f 4069/4151/6661 4083/3664/6662 4081/2363/5822 +f 2655/4152/6663 2847/2497/4794 2726/2345/4657 +f 2459/2826/5085 2461/3482/6664 2458/2824/5083 +f 2175/3521/6665 2177/4153/6666 2612/4154/6667 +f 2652/4155/6668 2845/4094/6669 2846/3888/6267 +f 2744/2474/4773 2839/3611/5918 2764/3755/6106 +f 2424/3149/5410 2426/3400/5681 2425/2091/4424 +f 2167/3256/5520 2165/4156/6670 2166/3257/5521 +f 1982/2866/5122 1983/2156/4484 2006/2865/5120 +f 2880/2995/5244 2881/4129/6627 2878/3923/6319 +f 3303/3844/6206 3304/4157/6671 3288/2179/6672 +f 4144/3074/5329 4137/2177/6673 4136/2977/6016 +f 2254/3783/6134 2269/3788/6140 2204/3787/6139 +f 2531/3679/6004 2312/2748/5016 2532/4158/6674 +f 3598/3879/6675 3611/3341/5613 3613/2562/6676 +f 4207/2846/5102 4205/3674/6677 4204/2212/6678 +f 2743/4043/6495 2764/3755/6106 2742/3754/6105 +f 4176/2779/6679 4171/3936/6339 4174/4159/6680 +f 2270/3804/6681 2272/2481/4780 2271/2483/4782 +f 2645/4160/6682 2174/4161/6683 2173/4162/6684 +f 3080/2774/5037 3021/4028/6470 3019/2726/4995 +f 3083/3054/5310 3157/2248/6685 3156/3673/6686 +f 3299/4163/6687 3300/3717/6056 3297/3930/6328 +f 3923/3142/5404 3895/2946/5192 3896/2706/4975 +f 2015/3274/4585 2022/2776/4585 2007/2185/4585 +f 2990/4164/6688 2946/3772/6120 2710/4002/6689 +f 1999/3749/6099 2001/3650/6540 2002/3334/6539 +f 2984/4051/6690 2953/4165/6691 2985/4166/6692 +f 3820/2375/4689 3819/2374/4688 3821/2540/4688 +f 4395/2979/6693 4295/4167/6693 4288/4168/6694 +f 4219/3272/6695 4221/3271/6696 4223/2083/4419 +f 2667/4169/6697 2666/2439/4743 2829/2441/4745 +f 2240/4004/6447 2241/3495/5784 2358/1975/4328 +f 3049/2959/5206 3053/3948/6355 3052/4170/6698 +f 4153/4171/6699 4152/3032/5284 4154/3031/5283 +f 3039/4025/6469 3046/3035/5288 3040/3317/5585 +f 3198/3328/5597 3196/4172/6700 3195/3327/5596 +f 3751/2467/6701 3724/3129/5388 3749/2131/6702 +f 2860/3709/6046 2857/3972/6396 2858/3997/6440 +f 3782/3554/6241 3794/3871/6240 3810/3113/5370 +f 1966/2535/4828 2063/4150/6660 2062/4173/6703 +f 4184/3422/5708 4195/2584/5707 4193/2583/6704 +f 2106/3793/6705 2600/2683/4950 2599/2682/4949 +f 4099/3529/5873 4098/3528/6706 4073/3568/5872 +f 2505/2386/4695 2534/3248/5515 2502/2387/4696 +f 2031/3929/6327 2030/3994/6435 2062/4173/6703 +f 3322/3831/6195 3279/3080/5335 3321/3507/5796 +f 4080/2365/4367 4111/2176/4367 4078/3001/4367 +f 2588/4082/26 2374/4174/26 2362/4175/26 +f 2121/2410/4719 2450/2412/4721 2476/4176/6707 +f 4251/4177/6708 4250/2852/5662 4182/3088/5661 +f 3429/2869/5125 3427/4178/6709 3428/2867/5123 +f 3640/2150/4524 3624/3195/5462 3621/3565/4524 +f 4279/2850/5106 4177/3086/6710 4280/2964/5211 +f 3947/2252/4572 3960/2251/4571 3948/3811/6185 +f 2964/3459/6711 2972/3896/6276 2967/3460/6712 +f 2396/3551/5854 2391/4019/6461 2434/3518/5811 +f 2560/3077/5332 2557/4039/6489 2561/4179/6713 +f 4332/2517/5906 4334/2617/6497 4333/3359/5633 +f 3545/3537/5837 3535/2145/6714 3571/2462/4764 +f 2060/2928/5180 2061/2536/4829 2059/2929/5181 +f 4196/2582/4865 4194/2085/4421 4193/2583/4866 +f 3695/2188/4434 3699/2187/4434 3696/2538/4434 +f 3510/2046/4388 3500/2045/4387 3511/2523/4388 +f 3764/4141/4336 3730/4180/4337 3761/4142/4336 +f 4188/2121/4450 4189/2351/4663 4210/2119/4448 +f 3037/2525/4818 3044/2527/4820 3043/4181/6715 +f 4363/3214/6577 4364/3213/6026 4349/2418/4725 +f 3212/3506/4383 3217/2218/4383 3211/4182/4383 +f 3795/2794/5055 3794/3871/6240 3784/2908/5162 +f 4075/3391/5672 4104/2058/4396 4067/2057/4395 +f 4147/2367/4680 4146/3636/5949 4145/3635/5948 +f 2754/3756/6107 2838/4183/6716 2837/4084/6560 +f 2929/3586/26 2931/4049/26 2985/4166/26 +f 4016/4184/6717 4034/3913/6302 4015/3009/5261 +f 2642/3805/6572 2161/3657/6417 2163/3985/6418 +f 3149/2631/5924 3172/3689/6020 3173/3615/5925 +f 3592/3705/6718 3699/2187/6718 3698/2438/6718 +f 2695/3338/5607 2074/3176/6719 2696/2428/4734 +f 3387/2236/4755 3388/3448/4755 3358/4185/4755 +f 3800/4186/6720 3799/3198/5465 3801/3473/5762 +f 4209/2845/5503 4233/2608/4517 4234/3236/4517 +f 2174/4161/6721 3016/4187/6722 3017/3807/6166 +f 2911/3312/5580 2950/3858/6221 2910/2048/4389 +f 4018/2818/5077 4000/3471/5760 4038/3470/5759 +f 2898/1972/4325 2897/2477/4776 2899/2476/4775 +f 3212/3506/4383 3211/4182/4383 3219/3718/6057 +f 4312/4188/6723 4313/3277/6724 4314/2122/6725 +f 4068/2063/4400 4069/4151/6661 4081/2363/5822 +f 4062/3073/4408 4060/3414/6726 4055/3744/4409 +f 4070/2431/4367 4069/4151/5277 4068/2063/5277 +f 1983/2156/4484 1984/3224/6579 2010/2060/4485 +f 3556/2812/5071 3553/3504/5793 3555/3116/5374 +f 3903/2788/6727 3910/2361/4674 3902/3055/6092 +f 3523/2585/6728 3521/2586/6729 3538/3622/5936 +f 2089/2968/6730 2091/2887/6438 2703/3995/6437 +f 3426/3876/6250 3415/2196/6249 3428/2867/5123 +f 2530/3681/6006 2213/4189/6731 2310/3961/6382 +f 3637/3131/4524 3604/4190/4524 3633/2999/4524 +f 4108/3361/4367 4116/4191/4367 4095/3486/4367 +f 4151/3033/5285 4148/3156/5416 4056/3571/5879 +f 3952/3704/6732 3975/3259/6733 3977/2921/6734 +f 2112/3160/6735 2111/3860/6736 2596/3324/5591 +f 2291/3820/6737 2292/3423/5704 2284/2736/5004 +f 3416/2868/6738 3415/2196/4522 3401/2195/4521 +f 3152/2194/4406 3153/3531/4406 3121/3875/6245 +f 3842/2396/6739 3843/3545/6740 3833/4192/6741 +f 2179/3133/6742 2963/2500/6566 2971/2934/6277 +f 3204/3855/4731 3203/4193/5444 3202/4194/4731 +f 4169/2892/4924 4167/2648/4924 4168/2647/4924 +f 4346/3829/6193 4361/3057/5313 4351/3497/6743 +f 2425/2091/4424 2444/2090/4423 2447/4195/6744 +f 2262/3206/5714 2251/2747/5015 2260/4196/6745 +f 3588/3863/6228 3684/2976/5223 3688/2596/4877 +f 1973/1962/4315 1966/2535/4828 1970/1963/4316 +f 2537/3247/5514 2531/3679/6004 2532/4158/6674 +f 3239/2157/4486 3242/2159/4487 3240/2005/4486 +f 2964/3459/5748 2965/2609/4889 2968/4197/6746 +f 2448/4198/6747 2449/3310/5578 2251/2747/5015 +f 2791/2877/5133 2787/2669/4940 2788/2668/4939 +f 1978/2331/4584 1977/3728/4585 1980/2256/4585 +f 2386/2450/6748 2464/2449/6207 2385/3846/6209 +f 2029/3619/5933 2028/4046/6502 2055/3919/6308 +f 3612/2686/4955 3611/3341/6527 3609/2687/4956 +f 2034/2760/5025 2022/2776/6248 2033/3476/5766 +f 3225/3016/4351 3224/3642/6749 3223/3641/4351 +f 3888/3411/5695 3901/3746/6750 3900/1992/5694 +f 3134/2485/4784 3132/2359/6751 3106/1989/4339 +f 3407/3097/5353 3440/3579/5890 3423/2283/4600 +f 3341/2000/5153 3443/2900/5152 3410/4086/6564 +f 3660/3219/5485 3668/3383/5659 3669/2620/4901 +f 3681/3218/5484 3679/3217/5483 3680/3897/6279 +f 4120/2022/4367 4118/2876/4367 4087/2023/4367 +f 2968/4197/6752 2980/4199/6753 2979/4200/6754 +f 2463/2093/4426 2582/2095/4428 2460/3857/6220 +f 2951/4201/6755 2986/3587/6556 2985/4166/6692 +f 4151/3033/5285 4056/3571/5879 4061/2771/5034 +f 3391/4202/6756 3408/3095/5351 3407/3097/5353 +f 2979/4200/6754 2964/3459/6711 2968/4197/6752 +f 3838/2232/4785 3858/2313/4787 3860/4203/6757 +f 2629/3041/6401 2148/3040/5874 2630/4204/6758 +f 2997/4205/6759 2998/4206/6760 2991/4207/6761 +f 2481/3742/6087 2482/3970/6394 2483/3513/5806 +f 2442/3175/5436 2441/3174/5435 2244/3048/5303 +f 2952/4208/6762 2948/4083/6763 2951/4201/6764 +f 2475/4209/6765 2467/4210/6766 2477/2825/5084 +f 4257/4211/6767 4256/2027/4371 4268/2029/4373 +f 4354/2205/4422 4358/2204/4422 4328/3549/4422 +f 2714/2897/5149 2989/4212/6768 2713/2898/5150 +f 2713/2898/5150 2989/4212/6768 2990/4164/6769 +f 4316/3967/6484 4313/3277/6724 4315/4035/6484 +f 2893/2673/4942 2851/2618/4899 2894/2404/4716 +f 2768/4213/6770 2731/2751/5019 2732/4017/6460 +f 4091/3591/6771 4089/2370/5534 4071/2430/5533 +f 1963/3488/6558 2068/2564/6558 1962/2820/6558 +f 2991/4207/6761 2998/4206/6760 2992/2975/6772 +f 2401/3526/5820 2468/2799/5059 2469/4214/6773 +f 2984/4051/6690 2970/3557/6081 2953/4165/6691 +f 4289/1976/4329 4288/4168/6774 4290/2809/6774 +f 4061/2771/5034 4155/4215/6775 4154/3031/5283 +f 3844/2395/5778 3879/3842/4554 3846/3105/4554 +f 3221/3824/6187 3214/3034/5286 3302/2289/4606 +f 1999/3749/6099 2002/3334/6539 2000/3750/6100 +f 4344/2123/4422 4348/4216/4422 4345/3830/4422 +f 3816/4217/6776 3815/2863/6777 3713/2862/6777 +f 3431/2018/4364 3343/2020/4366 3342/2308/4625 +f 3085/2678/4947 3200/2680/4947 3084/4023/4947 +f 3817/3941/6347 3920/3457/5746 3822/3234/6290 +f 2661/2076/4412 2662/2872/5128 2849/2871/5127 +f 4179/2880/6778 4180/2891/5144 4266/3954/6364 +f 3170/3600/5904 3180/2152/4480 3185/2154/4482 +f 3519/3974/6398 3520/3734/6490 3541/2533/6399 +f 2991/4207/6761 3000/4218/6779 2999/3752/6102 +f 2310/3961/6382 2213/4189/6731 2215/3006/5256 +f 3472/3687/4388 3476/2938/4388 3470/2554/4388 +f 2382/3477/5767 2397/4010/6455 2405/3845/6208 +f 2994/1981/4332 2139/2407/6780 2973/3155/6781 +f 2978/1979/4330 2994/1981/4332 2973/3155/6781 +f 2983/4058/6782 2990/4164/6688 2989/4212/6783 +f 2983/4058/6782 2989/4212/6783 2982/3350/5621 +f 2395/2713/4982 2381/4219/6784 2429/2078/4414 +f 2869/3797/6150 3037/2525/4818 3041/3795/6148 +f 3696/2538/4434 3699/2187/4434 3700/2539/6785 +f 3157/2248/4568 3143/2250/4570 3142/3508/5797 +f 3855/2030/6786 3857/2314/4631 3858/2313/4630 +f 2703/3995/6437 2702/3385/5663 2759/3700/6034 +f 1981/2254/4585 1980/2256/4585 1984/3224/4585 +f 2997/4205/6787 2977/2973/5220 2998/4206/6788 +f 2978/1979/4330 2997/4205/6787 2996/1980/4331 +f 3106/1989/4339 3132/2359/6751 3130/1990/4340 +f 2870/3796/6149 2871/4024/6468 2872/4124/6618 +f 3002/3232/5500 3003/4220/6789 3004/4221/6790 +f 4308/2518/4811 4331/3358/6791 4329/2981/5228 +f 4286/2568/4924 4285/4222/4924 4282/3711/4924 +f 3107/1965/4406 3105/1988/4338 3103/2796/4406 +f 4324/3408/6637 4325/3452/5849 4326/3289/6636 +f 3485/2488/4788 3486/2902/4788 3488/2489/4789 +f 3013/4223/6792 2950/3858/6221 2949/4224/6793 +f 3821/2540/4688 3819/2374/4688 3829/2307/4688 +f 3676/2510/4805 3675/2445/4749 3669/2620/4901 +f 3659/2447/4751 3643/3649/5968 3660/3219/5485 +f 2168/2588/6082 2166/3257/6596 2884/3738/6083 +f 2606/3729/6358 2096/3692/6794 2097/2712/6795 +f 2427/4225/6796 2417/4226/6797 2428/3243/5510 +f 3676/2510/4805 3669/2620/4901 3677/4070/6543 +f 2457/3119/6798 2456/3118/5625 2577/3352/5624 +f 4096/4227/6799 4098/3528/5826 4097/4228/6800 +f 4052/3592/6801 3940/2324/6801 4053/2323/6801 +f 3870/1999/4554 3867/2111/5778 3878/3187/5778 +f 3942/3098/6592 4045/3691/6022 3936/2128/4455 +f 4155/4215/6775 4125/4098/6583 4153/4171/6699 +f 2556/3141/5403 2563/2339/4651 2557/4039/6489 +f 3260/3145/6514 3258/4229/6802 3257/2841/5928 +f 2782/3612/5919 2694/3989/6425 2691/3372/5648 +f 3365/2855/5390 3363/3332/5391 3364/2513/5391 +f 3651/2008/4354 3686/2101/4432 3650/2100/4431 +f 3935/3060/6803 4052/3592/6803 4051/2416/6803 +f 3638/2199/6804 3663/3410/5693 3642/4230/6805 +f 3712/3472/5761 3708/3627/5358 3711/3853/6217 +f 3979/2480/4779 3981/3451/6806 3982/4231/6807 +f 3708/3627/6808 3702/3763/6809 3812/3101/6808 +f 3537/3621/6810 3522/4055/6811 3523/2585/6728 +f 4069/4151/6661 4070/2431/5737 4084/3010/6812 +f 3148/3710/6047 3170/3600/5904 3171/3599/6813 +f 3963/3823/6186 3948/3811/6185 3962/3909/6814 +f 2625/3115/5372 2623/3279/5547 2917/3063/5319 +f 2497/2026/4370 2534/3248/5515 2535/2311/4628 +f 3628/3443/4524 3626/2469/4524 3634/2134/4524 +f 2757/3726/6069 2762/3038/5291 2763/3686/6013 +f 3691/3308/5576 3667/3668/5990 3693/3667/5989 +f 3600/3468/5757 3625/2471/5298 3601/3044/5297 +f 3782/3554/5859 3773/2056/6654 3783/3870/6815 +f 2928/4050/26 2932/4026/26 2981/3737/26 +f 3284/3900/6282 3283/3931/6329 3297/3930/6328 +f 2890/2957/5204 3032/3099/5356 2889/3081/5336 +f 2352/4139/6638 2166/3257/6246 2350/2259/4579 +f 2137/2710/6816 2131/2709/6817 2133/3369/6818 +f 2999/3752/6102 3000/4218/6779 2815/3023/5274 +f 3740/2436/6819 3741/3511/6820 3722/3183/5447 +f 3809/3952/6362 3780/2222/4545 3792/3789/6141 +f 3911/2628/4909 3828/2362/4675 3910/2361/4674 +f 3728/3938/6341 3729/2910/6821 3727/2909/6822 +f 4247/2765/6466 4246/2607/4887 4281/3043/5296 +f 2285/3633/6823 2287/3632/6824 2286/2358/4671 +f 4295/4167/6825 4299/4016/4329 4298/2810/6825 +f 4207/2846/5102 4204/2212/6678 4206/2211/5102 +f 3037/2525/4818 2868/4120/6613 3038/2526/4819 +f 2553/2391/4703 2568/4232/6826 2569/3730/6074 +f 4224/3229/4517 4227/3127/4517 4220/3940/4517 +f 3023/4233/6827 3078/2725/6828 3079/3435/5721 +f 2947/3773/6121 2950/3858/6829 2903/3375/6122 +f 3708/3627/6808 3812/3101/6808 3816/4217/6808 +f 3143/2250/4406 3141/3354/4406 3133/3157/4406 +f 3747/2549/5387 3723/3130/5389 3745/3186/5451 +f 3231/4042/6651 3233/3019/6830 3234/3018/6830 +f 3986/3873/6243 4009/3646/5962 4008/3874/6244 +f 2593/3453/6052 2118/3343/6831 2117/3344/6832 +f 3077/2775/5038 2955/4118/6611 2956/3556/5861 +f 3044/2527/4820 3038/2526/4819 3034/3707/6044 +f 2733/2560/4848 2734/4234/6833 2736/2901/5154 +f 3632/3184/4524 3630/2633/4524 3635/2806/4524 +f 3484/2903/4388 3482/2763/4388 3520/3734/4388 +f 3320/2118/4447 3318/4235/6834 3319/2217/4539 +f 3043/4181/6715 3041/3795/6148 3037/2525/4818 +f 2254/3783/6134 2204/3787/6139 2210/3782/6133 +f 2982/3350/5621 2989/4212/6783 2987/2785/5622 +f 2981/3737/6079 2970/3557/6081 2984/4051/6690 +f 3100/1966/4319 3108/3883/6835 3138/1964/4317 +f 3471/2556/4844 3483/2555/4843 3485/2488/6836 +f 4173/3307/5575 4168/2647/6837 4268/2029/4373 +f 3339/2002/6838 3448/4236/6838 3446/3162/6838 +f 3248/3193/5460 3250/3071/5326 3251/3070/5326 +f 4135/2978/6017 4134/2874/5545 4143/3075/5330 +f 3841/4237/6839 3869/1997/5373 3871/2691/6840 +f 3645/4012/4524 3616/2563/4524 3646/3265/4524 +f 2243/3049/5304 2441/3174/5435 2440/4238/6841 +f 3812/3101/5358 3815/2863/5358 3816/4217/6842 +f 3057/3501/5790 3002/3232/5500 3004/4221/6790 +f 2945/4239/26 2946/3772/26 2944/4059/26 +f 3981/3451/6806 3979/2480/4779 3980/2479/4778 +f 3600/3468/5757 3620/3566/6843 3622/3567/5871 +f 3546/3538/5838 3545/3537/5837 3468/3697/6844 +f 3158/2249/6845 3157/2248/6685 3194/4240/6846 +f 3089/4241/6847 3175/4242/6848 3163/2758/5023 +f 3526/2916/6849 3525/2918/6037 3512/3167/5426 +f 2001/3650/5969 1999/3749/6850 1981/2254/4574 +f 2811/2139/4467 2804/4243/6851 2803/3869/6238 +f 4063/4244/6233 4066/2073/4409 4064/2579/6233 +f 3611/3341/6527 3612/2686/4955 3614/4064/4850 +f 2924/3580/5891 3053/3948/6355 2925/3878/6252 +f 3759/2165/4494 3757/2164/4493 3756/4245/6852 +f 3417/2935/5183 3425/3716/6055 3429/2869/5125 +f 2576/4246/6853 2519/3865/6230 2586/3866/6232 +f 2747/2728/4997 2738/2730/4999 2739/3859/6222 +f 2067/3552/5856 2066/2354/4667 1969/1961/4314 +f 3862/3188/5454 3863/3189/5456 3861/4247/6854 +f 2753/4076/6549 2751/2702/4971 2752/4077/6550 +f 2756/3597/5901 2796/4041/6492 2795/3601/5905 +f 3004/4221/6790 3064/3228/5496 3057/3501/5790 +f 3522/4055/6811 3535/2145/4473 3516/2144/4472 +f 4221/3271/6696 4222/3413/6855 4223/2083/4419 +f 3474/2286/4388 3476/2938/4388 3473/3407/4388 +f 4001/2279/4596 4039/4060/6521 4038/3470/5759 +f 2921/3499/5788 3061/2124/4451 3059/2126/4453 +f 2911/3312/5580 2823/2050/4391 2901/3313/5581 +f 3275/2219/4542 3313/3887/6266 3316/4248/6856 +f 4132/2882/6480 4063/4244/6857 4142/4033/6481 +f 4297/4249/4329 4296/1978/4329 4301/2202/4329 +f 2697/3447/5736 2604/3992/6433 2078/2740/6430 +f 2211/3208/5475 2263/3430/6091 2262/3206/5473 +f 2620/3696/6029 2627/3281/5549 2913/3280/5548 +f 2968/4197/6746 3076/2611/4891 2969/3558/5863 +f 3594/2768/5032 3592/3705/4434 3591/2511/4806 +f 4294/1977/6030 4291/4250/6858 4382/2762/5027 +f 3787/3199/6268 3771/3957/6370 3788/3197/6859 +f 3994/3441/5000 3959/3733/5000 3993/3732/5000 +f 4158/2442/4746 4126/3362/5637 4157/4097/6582 +f 4224/3229/5497 4228/3596/6860 4258/4053/6509 +f 2786/4251/6861 2791/2877/5133 2790/3027/5279 +f 4009/3646/5962 4019/4252/6862 4020/3906/6293 +f 4361/3057/5313 4362/2420/4727 4350/2419/4726 +f 4370/3200/6516 4371/3714/6863 4357/2940/5186 +f 3275/2219/4542 3264/2135/4463 3274/2137/4465 +f 3687/2624/4905 3688/2596/4877 3684/2976/5223 +f 3094/3209/5476 3093/3406/5686 3090/4253/6864 +f 3017/3807/6166 3005/4254/6865 3063/3640/5954 +f 3664/3898/6280 3637/3131/5392 3665/3132/5393 +f 3074/4255/6866 2955/4118/6611 3077/2775/5038 +f 2170/2947/5193 3005/4254/6865 3016/4187/6722 +f 3196/4172/6700 3198/3328/5597 3197/2823/5082 +f 2926/3535/5832 2924/3580/5891 2927/3516/5809 +f 2109/4256/6867 2106/3793/6145 2108/3794/6147 +f 3267/2180/4509 3270/2893/5145 3287/2181/4510 +f 2133/3369/6818 2138/3370/6868 2137/2710/6816 +f 3395/4257/6869 3374/3029/4755 3396/3045/4808 +f 4337/3613/5920 4339/3498/5921 4336/2638/6499 +f 3763/3721/4336 3754/2699/4336 3762/2698/4336 +f 3645/4012/6457 3657/2578/4863 3644/4104/6623 +f 3683/2303/4620 3649/2302/4619 3685/2099/4430 +f 2067/3552/5856 2038/2645/5855 2037/2644/6870 +f 3003/4220/6789 3044/2527/4820 3004/4221/6790 +f 2742/3754/6105 2692/2689/4957 2694/3989/6425 +f 4256/2027/6871 4230/3595/6872 4255/2598/4879 +f 4018/2818/5077 4017/2817/5076 4000/3471/5760 +f 3045/3037/5290 3005/4254/6865 3012/2949/5195 +f 3789/3786/6137 3801/3473/5762 3799/3198/5465 +f 2480/3676/6000 2510/3192/5459 2509/3367/5642 +f 4171/3936/6339 4170/2646/4923 4167/2648/4924 +f 2132/3291/6873 2130/2802/5062 2129/2801/5061 +f 2686/2953/5200 2722/2952/5199 2715/3135/5396 +f 4271/4258/6874 4272/3222/5489 4270/3723/6064 +f 3140/2069/4406 3142/3508/4406 3137/3904/4406 +f 2687/4132/6631 2112/3160/6216 3081/3454/5742 +f 4127/2444/4748 4116/4191/6875 4108/3361/5636 +f 3336/2016/4350 3332/3570/5878 3334/3512/5878 +f 3898/3401/6876 3831/1991/4341 3897/2708/4977 +f 4224/3229/4517 4220/3940/4517 4223/2083/4517 +f 4260/2966/5213 4246/2607/4887 4245/2849/5105 +f 3537/3621/5935 3554/3505/5794 3536/2460/4762 +f 2569/3730/6074 2554/3315/5583 2553/2391/4703 +f 2987/2785/5046 2989/4212/6768 2714/2897/5149 +f 1973/1962/4315 1969/1961/4314 2065/2653/4928 +f 3287/2181/5287 3286/2147/4475 3302/2289/4606 +f 2137/2710/4979 2136/4259/6877 2589/2711/4980 +f 4390/4260/6878 4391/3902/6288 4364/3213/5479 +f 3390/3907/6295 3406/4020/6463 3405/2160/4489 +f 3779/2904/5158 3807/3246/5513 3778/2905/5159 +f 3516/2144/4388 3492/2106/4388 3522/4055/4388 +f 3834/2380/6879 3847/3103/6422 3835/2381/6421 +f 2595/3326/5824 2118/3343/6880 3081/3454/5742 +f 4190/3461/4517 4186/2832/4517 4184/3422/4517 +f 3438/2017/4363 3440/3579/5890 3439/2015/4361 +f 2740/3002/5252 2770/2573/4858 2772/2575/4860 +f 3865/4261/6881 3867/2111/4440 3866/2112/4441 +f 3128/2316/5408 3130/1990/4673 3131/2360/4673 +f 2834/4262/6882 2757/3726/6069 2835/4263/6883 +f 3989/2225/4548 4004/2890/5143 4003/2226/4549 +f 3305/4145/6648 3303/3844/6206 3218/3843/6205 +f 2014/2492/4585 2013/2061/4585 1986/2267/4584 +f 2574/3747/6096 2513/3191/6884 2517/3584/6646 +f 3998/3522/5815 4013/3628/6885 4012/3523/5816 +f 3693/3667/5989 3692/4264/6886 3691/3308/5576 +f 2719/2659/4931 2717/2658/4930 3081/3454/5742 +f 2988/2784/6616 2975/3559/6615 2974/3351/5623 +f 2607/2886/5139 2090/2888/5141 2608/4265/6887 +f 3218/3843/6205 3207/3629/6119 3210/4146/6649 +f 3823/2649/4688 3831/1991/4690 3830/2650/4690 +f 4231/2767/5031 4248/2766/5030 4237/2853/5110 +f 3976/4127/5000 3973/4014/5000 3996/4266/5000 +f 3557/2545/4837 3540/2621/4902 3558/2532/4825 +f 3285/2148/4476 3286/2147/4475 3270/2893/5145 +f 2713/2898/5150 2711/4001/6444 2712/2899/5151 +f 3711/3853/6217 3708/3627/5358 3717/3626/5941 +f 4289/1976/5851 4393/2661/5851 4288/4168/5851 +f 3978/2478/5523 3975/3259/5524 3976/4127/6624 +f 3590/3639/5953 3681/3218/5484 3582/2548/5573 +f 3736/2067/6888 3739/2435/6889 3738/2437/6890 +f 2539/3677/6001 2480/3676/6000 2509/3367/5642 +f 3054/3949/6356 3051/2958/5205 3056/3233/5501 +f 3462/3912/4532 3458/2336/5703 3463/2349/5703 +f 3797/2793/5054 3715/3908/6296 3796/3903/6289 +f 2409/3396/5677 2398/2896/5148 2382/3477/5767 +f 2787/2669/4940 2690/3980/6409 2689/2670/4941 +f 2575/4267/6891 2516/3583/6892 2514/4268/6893 +f 3343/2020/4626 3340/2096/4626 3342/2308/4625 +f 2384/3836/6200 2193/2963/5210 2295/2962/5209 +f 4368/3287/5555 4367/2206/4530 4392/3661/5981 +f 4225/3462/5503 4232/2606/5503 4214/2491/4517 +f 3389/2453/4755 3379/2452/4755 3397/4111/4755 +f 3531/2394/4706 3570/2166/4495 3548/4065/6528 +f 2058/2927/5179 1964/3740/6085 2060/2928/5180 +f 4083/3664/6662 4069/4151/6661 4084/3010/6812 +f 2575/4267/26 2576/4246/26 2372/4269/26 +f 3274/2137/4465 3262/2136/4464 3261/2834/5093 +f 3560/3918/6307 3559/2531/4824 3542/4040/6491 +f 3598/3879/6675 3615/2434/6894 3599/3766/6895 +f 3533/2169/4498 3546/3538/5838 3532/3064/5320 +f 2370/4270/512 2140/2408/26 2139/2407/26 +f 2982/3350/6896 2974/3351/26 2943/4052/26 +f 3637/3131/5392 3664/3898/6280 3638/2199/6804 +f 4388/3884/6261 4386/2811/5070 4389/3215/5481 +f 4052/3592/6801 3944/3590/6897 3940/2324/6801 +f 2395/2713/4982 2415/4271/6898 2381/4219/6784 +f 3944/3590/5354 3943/3203/5470 3940/2324/5354 +f 1980/2256/4576 1995/2972/5219 1992/2640/4917 +f 4202/2191/4517 4205/3674/4517 4238/2189/4517 +f 3301/3719/6058 3302/2289/4606 3296/2290/4607 +f 3768/4144/4336 3750/2132/4336 3769/4069/4336 +f 3169/2857/5114 3148/3710/6047 3150/2265/5909 +f 3784/2908/5162 3783/3870/6815 3773/2056/6654 +f 3792/3789/6141 3714/3112/5369 3809/3952/6362 +f 3694/2830/5089 3670/2577/4862 3693/3667/5989 +f 3195/3327/5596 3194/4240/6846 3093/3406/5686 +f 3909/2052/6202 3879/3842/6204 3876/3840/6520 +f 4124/4272/6899 4125/4098/6900 4109/3148/6901 +f 2906/2075/4411 2911/3312/5580 2912/2475/4774 +f 2269/3788/6902 2252/3311/5579 2253/2922/5174 +f 4117/2875/5131 4134/2874/5130 4135/2978/5226 +f 3154/4273/6903 3174/3021/5272 3190/3020/5271 +f 3394/3368/4808 3393/3346/4808 3362/2724/4755 +f 4088/2369/5532 4086/4274/6904 4070/2431/5737 +f 2253/2922/5174 2449/3310/5578 2446/3301/5567 +f 4097/4228/5277 4108/3361/4367 4095/3486/4367 +f 2086/2843/5099 2094/2914/6905 2085/2844/5100 +f 3987/2733/5000 3983/2732/5001 3990/4005/5001 +f 3618/2433/6906 3620/3566/6843 3599/3766/6895 +f 1980/2256/4576 1992/2640/4917 1979/2639/4916 +f 3261/2834/4351 3262/2136/4351 3260/3145/4351 +f 3287/2181/5287 3214/3034/5286 3303/3844/6206 +f 2177/4153/6907 2181/2913/6908 2520/3993/6434 +f 3283/3931/6909 3284/3900/6282 3273/2003/6284 +f 3284/3900/6282 3285/2148/4476 3271/2004/6283 +f 2158/3534/6910 2155/3785/6911 2489/4275/6912 +f 3166/2193/4519 3199/3464/5753 3182/2696/4964 +f 3582/2548/5573 3681/3218/5484 3666/2998/6913 +f 3827/1984/4335 3921/2372/4686 3922/1982/4333 +f 3997/3440/5000 3961/4276/5000 3994/3441/5000 +f 3258/4229/4351 3260/3145/4351 3262/2136/4351 +f 4103/4063/6526 4104/2058/6914 4105/2836/6525 +f 2547/3527/5825 2493/4277/6915 2492/4278/6916 +f 3353/2665/4934 3378/2873/5129 3354/2044/4386 +f 3982/4231/6807 3981/3451/6806 3983/2732/6917 +f 3214/3034/5286 3221/3824/6187 3215/3630/6119 +f 3445/3877/6251 3426/3876/6250 3346/3404/6918 +f 3992/2278/5000 3980/2479/5000 3989/2225/5001 +f 3217/2218/4540 3321/3507/5796 3279/3080/5335 +f 2920/3581/5892 3058/4022/6465 2919/3042/5295 +f 3355/4279/6919 3382/2043/4385 3384/3490/6920 +f 4380/2521/4814 4383/2761/5026 4375/1994/4344 +f 3288/2179/6672 3287/2181/5287 3303/3844/6206 +f 2705/3683/6921 2805/4000/6922 2946/3772/6120 +f 2288/2735/6459 2192/4280/6923 2191/3825/6189 +f 3051/2958/5205 3008/3231/5499 3056/3233/5501 +f 3495/3337/5606 3493/3336/5605 3494/2107/4436 +f 3371/3028/5280 3372/2931/5280 3374/3029/5281 +f 3219/3718/6057 3221/3824/6187 3301/3719/6058 +f 2404/3397/5868 2466/3025/5278 2467/4210/6766 +f 4057/3575/4409 4062/3073/4408 4055/3744/4409 +f 3390/3907/4755 3383/4018/4755 3391/4202/4755 +f 2003/4067/6541 2004/2184/4514 2005/2186/4516 +f 4216/2320/5751 4215/2322/4664 4189/2351/4663 +f 3281/2828/6924 3282/3810/6925 3272/4281/6926 +f 3339/2002/6838 3446/3162/6838 3332/3570/6838 +f 2612/4154/6667 2177/4153/6666 2181/2913/6373 +f 2023/2943/4585 2024/4282/4584 1991/3107/4585 +f 3432/2808/5067 3433/3059/5315 3335/2773/5036 +f 4117/2875/4367 4082/2364/4367 4085/3011/4367 +f 3160/3355/5629 3161/3379/5655 3147/3381/5657 +f 3824/1983/4334 3897/2708/4977 3831/1991/4341 +f 3479/3761/6112 3478/2384/6113 3480/2764/6112 +f 3471/2556/4844 3487/2490/6927 3472/3687/6015 +f 3329/2671/5400 3211/4182/5400 3213/2920/5400 +f 4332/2517/4810 4331/3358/6791 4308/2518/4811 +f 3128/2316/5408 3131/2360/4673 3129/3146/5409 +f 3139/2300/6258 3136/2484/6928 3138/1964/6259 +f 3819/2374/4688 3826/2984/4688 3829/2307/4688 +f 4330/3357/6361 4333/3359/4422 4354/2205/4422 +f 4242/2992/5241 4274/3067/5322 4275/2993/5242 +f 3112/2317/6929 3110/2070/6344 3109/2389/6343 +f 3803/3262/5528 3793/3264/5530 3804/3771/6118 +f 4025/3258/5522 4022/4283/6930 4010/3091/5347 +f 3486/2902/4788 3485/2488/4788 3483/2555/5155 +f 3296/2290/4607 3285/2148/4476 3284/3900/6282 +f 3001/4284/6931 2642/3805/6164 3017/3807/6166 +f 1989/2329/5732 1990/2547/6932 1991/3107/5363 +f 3997/3440/5726 4013/3628/6885 3998/3522/5815 +f 3310/4285/6933 3293/3928/6326 3294/4286/6934 +f 3657/2578/4863 3656/2600/4881 3644/4104/6623 +f 4391/3902/6288 4390/4260/6878 4299/4016/6935 +f 2575/4267/6891 2580/3253/6647 2516/3583/6892 +f 2505/2386/4695 2482/3970/6394 2541/3680/6005 +f 4228/3596/6860 4257/4211/6936 4258/4053/6509 +f 3498/4287/4388 3511/2523/4388 3500/2045/4387 +f 2829/2441/4745 2668/2804/5064 2667/4169/6697 +f 3860/4203/6757 3861/4247/6937 3838/2232/4785 +f 4097/4228/6800 4098/3528/5826 4100/2744/5012 +f 3773/2056/4336 3742/3283/4336 3774/2906/4336 +f 4213/2352/6938 4214/2491/4790 4212/3886/6939 +f 2587/2448/26 2588/4082/26 2362/4175/26 +f 4273/3935/6338 4271/4258/6874 4170/2646/4923 +f 4031/2081/4417 4032/3008/5260 3943/3203/5470 +f 1976/2506/4803 1968/2241/6940 2071/2507/4803 +f 2174/4161/6941 2525/3660/5980 2172/3659/5979 +f 2041/3670/6042 2042/3669/5991 2027/2377/6043 +f 4142/4033/6481 4141/3278/5546 4133/3478/6479 +f 4065/2071/4407 4066/2073/6942 4160/4288/6943 +f 3882/2413/4554 3862/3188/4554 3883/3950/4554 +f 2576/4246/26 2586/3866/26 2375/4289/26 +f 3945/2260/4580 4026/3204/5471 3943/3203/5470 +f 4072/2429/4735 4073/3568/5872 4094/3485/6944 +f 3354/2044/4386 3352/2656/4755 3353/2665/4934 +f 2834/4262/6882 2762/3038/5291 2757/3726/6069 +f 3834/2380/4554 3840/2178/4554 3833/4192/4554 +f 2397/4010/6455 2385/3846/6209 2405/3845/6208 +f 3193/3399/5680 3083/3054/5310 3156/3673/6686 +f 2526/3767/6115 2168/2588/6247 2527/3768/6116 +f 3772/3181/5445 3785/2907/5161 3774/2906/5160 +f 3756/4245/6852 3757/2164/4493 3755/3294/5560 +f 3227/3654/5973 3226/2182/4351 3229/2234/4351 +f 2562/2340/4652 2563/2339/4651 2556/3141/5403 +f 4039/4060/6521 4001/2279/4596 4041/3562/5865 +f 4131/2881/6945 4130/2266/5589 4140/3321/5590 +f 2582/2095/512 2585/2094/26 2366/4290/26 +f 2764/3755/6106 2838/4183/6716 2754/3756/6107 +f 3197/2823/5082 3159/2822/5081 3196/4172/6700 +f 4067/2057/4367 4074/2059/4367 4070/2431/4367 +f 4145/3635/5948 4144/3074/5329 4057/3575/5884 +f 4295/4167/6825 4293/4015/4329 4299/4016/4329 +f 3087/4137/6946 3086/3053/5309 3191/3817/6178 +f 2590/3493/6947 2592/3492/6051 2591/3713/6053 +f 4168/2647/6837 4271/4258/6874 4270/3723/6064 +f 4104/2058/6914 4075/3391/6948 4076/2837/5251 +f 3413/3813/6949 3396/3045/6950 3414/2197/4523 +f 2122/3609/5916 2121/2410/6089 2119/3607/5914 +f 4297/4249/4329 4289/1976/4329 4296/1978/4329 +f 3725/4110/6603 3755/3294/6602 3726/3751/6317 +f 4066/2073/6942 4140/3321/5590 4160/4288/6943 +f 2283/2357/6172 2194/3812/6171 2280/3085/5341 +f 2647/4291/6951 2171/4292/6952 2649/2589/4870 +f 3605/2737/6285 3603/2739/6953 3604/4190/6953 +f 2977/2973/26 2978/1979/26 2937/4293/26 +f 2118/3343/6880 2593/3453/5741 3081/3454/5742 +f 2555/3139/5401 2545/3698/6031 2546/3533/5829 +f 3220/3550/5853 3211/4182/5853 3329/2671/5853 +f 3597/3340/4524 3595/2738/4524 3596/4294/4524 +f 2892/3975/6400 3028/3393/5674 2891/4011/6456 +f 3285/2148/4476 3270/2893/5145 3271/2004/6954 +f 1980/2256/4585 1979/2639/4584 1978/2331/4584 +f 4210/2119/5744 4213/2352/6938 4212/3886/6939 +f 4095/3486/5776 4092/2089/5898 4093/3487/5777 +f 3791/4140/6955 3803/3262/5528 3704/3474/5763 +f 4101/2742/5010 4100/2744/5012 4099/3529/5827 +f 4353/3861/4422 4316/3967/4422 4318/3348/4422 +f 2682/3300/5566 2679/2955/5202 2824/3525/5819 +f 3938/2415/5355 3941/3757/5355 3942/3098/5354 +f 3626/2469/4769 3625/2471/4769 3623/3469/6956 +f 3496/3335/6957 3497/4295/6958 3474/2286/4603 +f 3418/2937/5185 3424/3295/5561 3425/3716/6055 +f 4188/2121/4517 4187/2210/5503 4186/2832/4517 +f 4183/3712/4517 4191/3270/5503 4190/3461/4517 +f 4021/3944/6351 4020/3906/6293 4019/4252/6862 +f 4333/3359/5633 4334/2617/6497 4336/2638/6499 +f 3092/3542/6219 3098/2426/6219 3204/3855/6219 +f 2135/3378/6959 2136/4259/6960 2454/3117/5375 +f 2908/3991/6429 2849/2871/5127 2727/3625/5940 +f 4121/2816/5075 4122/2815/5074 4106/4296/6961 +f 3543/4133/6632 3514/2543/4835 3544/2113/4834 +f 4275/2993/5242 4276/3066/5321 4277/2778/5039 +f 4016/4184/6717 3993/3732/6962 4017/2817/5076 +f 2075/3682/6530 2074/3176/6963 2095/3178/6531 +f 3484/2903/4388 3519/3974/4388 3486/2902/4388 +f 2603/3947/6354 2083/2274/6964 2084/3945/6352 +f 2647/4291/6951 2648/2948/6965 2171/4292/6952 +f 2799/2142/4470 2785/2141/4469 2790/3027/5279 +f 3776/3759/6110 3793/3264/5530 3802/3263/5529 +f 2613/2502/6374 2180/2501/6966 2178/2933/6375 +f 3827/1984/4690 3823/2649/4688 3825/2652/4690 +f 2305/3005/5255 2397/4010/6455 2300/4009/6454 +f 2064/2759/5024 2033/3476/6967 2063/4150/6660 +f 1971/3465/5882 2045/3573/5881 2044/3094/5350 +f 4285/4222/4924 4284/4297/4924 4282/3711/4924 +f 3088/3180/5444 3089/4241/5444 3094/3209/5476 +f 2224/4298/6968 2225/3484/5774 2221/2495/4792 +f 3342/2308/4625 3345/2309/4350 3344/3405/5685 +f 2439/3251/5518 2440/4238/6841 2427/4225/6796 +f 2132/3291/6969 2131/2709/4978 2589/2711/4980 +f 1967/2240/5955 2052/2109/4438 2067/3552/5856 +f 3847/3103/6422 3834/2380/6879 3845/3104/6970 +f 2507/3743/6088 2503/3574/5883 2515/3582/5893 +f 4066/2073/6942 4063/4244/6857 4140/3321/5590 +f 3546/3538/5838 3468/3697/6844 3462/3912/6301 +f 3181/2858/5115 3169/2857/5114 3168/3602/5908 +f 2709/3784/6135 2708/3999/6442 2819/4299/6971 +f 3440/3579/5890 3442/3096/5352 3441/3899/6281 +f 3027/2406/4718 2892/3975/6400 2893/2673/4942 +f 4172/3087/4924 4181/2879/4924 4182/3088/4924 +f 2156/4300/6972 2154/4301/6973 2489/4275/6912 +f 3284/3900/6282 3297/3930/6328 3300/3717/6056 +f 3943/3203/5470 4029/3205/5472 4031/2081/4417 +f 3786/3182/6974 3798/2792/5053 3785/2907/5161 +f 2030/3994/6435 2017/3273/6436 2016/2493/5931 +f 2012/3962/6383 1985/3727/6383 1986/2267/6383 +f 3264/2135/4351 3256/3618/4351 3258/4229/4351 +f 2775/4302/6975 2772/2575/4860 2773/3235/5502 +f 1992/2640/5361 1995/2972/5344 1994/3891/6269 +f 3074/4255/6866 2902/2049/4390 3013/4223/6792 +f 2144/3266/5535 2182/3520/5813 2487/2590/4871 +f 2874/3316/5584 2877/2342/4654 2875/4126/6622 +f 2333/2285/4602 2332/4007/6451 2523/3420/5702 +f 4229/4303/6976 4235/4062/6523 4254/4061/6522 +f 2037/2644/6870 2036/2355/4668 2067/3552/5856 +f 3960/2251/6977 3958/2253/6978 3959/3733/6978 +f 2328/3983/6415 2242/3250/5517 2216/4304/6979 +f 2200/3662/5983 2270/3804/6163 2278/2530/5340 +f 2317/4305/6980 2571/2390/4702 2570/2632/4911 +f 2524/3655/5974 2160/3658/5977 2158/3534/6910 +f 2668/2804/5064 2829/2441/4745 2850/2805/5065 +f 3411/3297/6981 3410/4086/6982 3397/4111/6983 +f 4157/4097/6582 4159/3690/6021 4158/2442/4746 +f 2356/2529/4822 2572/3616/5926 2316/3617/5927 +f 3423/2283/4600 3440/3579/5890 3437/2281/4598 +f 3518/2170/4388 3498/4287/4388 3495/3337/4388 +f 3862/3188/5454 3860/4203/6984 3859/2315/4632 +f 3861/4247/6854 3860/4203/6984 3862/3188/5454 +f 3854/2032/5552 3856/3588/5896 3855/2030/6786 +f 2739/3859/6222 2683/4092/6573 2843/4090/6570 +f 4211/3456/5745 4210/2119/5744 4212/3886/6939 +f 3832/1993/4343 3900/1992/4342 3901/3746/6093 +f 2938/2409/511 2937/4293/26 2978/1979/26 +f 3030/3082/5337 3069/3848/6211 3070/3543/5843 +f 2447/4195/6744 2249/3302/5568 2446/3301/5567 +f 2756/3597/5901 2763/3686/6013 2796/4041/6492 +f 4214/2491/4790 4213/2352/6938 4215/2322/4638 +f 4347/1995/4345 4375/1994/4344 4348/4216/6985 +f 2860/3709/6046 2859/3968/6392 2857/3972/6396 +f 2849/2871/5127 2905/4306/6986 2727/3625/5940 +f 3702/3763/5358 3703/3864/6229 3701/3838/5358 +f 4073/3568/5872 4098/3528/6706 4096/4227/6987 +f 3536/2460/4762 3571/2462/4764 3535/2145/6714 +f 2598/4068/6988 2107/2985/6989 2106/3793/6990 +f 4291/4250/4329 4289/1976/4329 4290/2809/6774 +f 4353/3861/4422 4352/1996/4422 4316/3967/4422 +f 2740/3002/5252 2738/2730/4999 2770/2573/4858 +f 4354/2205/4529 4366/2603/6991 4367/2206/4530 +f 3688/2596/4877 3653/2151/4876 3589/3323/6507 +f 4045/3691/6022 3942/3098/6592 4044/3724/6067 +f 4243/2991/6992 4226/4085/6562 4242/2992/6993 +f 2727/3625/5940 2904/3110/5367 2908/3991/6429 +f 3497/4295/6994 3500/2045/4966 3499/2287/4968 +f 3947/2252/5000 3949/3703/5000 3946/3510/5000 +f 2629/3041/6401 2630/4204/6758 2631/3977/6402 +f 2431/3151/5412 2432/2411/4720 2112/3160/6995 +f 3270/2893/4351 3267/2180/6749 3236/4307/6749 +f 2835/4263/6883 2757/3726/6069 2755/2701/4970 +f 4123/3882/6996 4124/4272/6899 4109/3148/6901 +f 2427/4225/6796 2412/3242/5509 2439/3251/5518 +f 3389/2453/6997 3408/3095/5351 3391/4202/6756 +f 2935/4027/512 2934/4308/26 2979/4200/26 +f 3465/3578/5889 3553/3504/5793 3556/2812/5071 +f 3566/2348/4660 3529/2718/4987 3569/2717/4986 +f 3562/2114/4443 3524/2851/5107 3525/2918/5172 +f 4226/4085/4517 4225/3462/5503 4217/2321/4517 +f 2566/3735/6076 2325/3933/6332 2567/3314/5582 +f 2526/3767/6115 2523/3420/5702 2342/3239/5506 +f 2054/3445/5734 1971/3465/5882 2044/3094/5350 +f 4004/2890/6998 4044/3724/6067 4003/2226/6066 +f 3060/3137/5398 3062/3136/5397 3071/4106/6593 +f 4229/4303/6976 4254/4061/6522 4255/2598/4879 +f 3928/3494/4688 3925/2499/4688 3927/3345/4688 +f 4323/3288/4422 4357/2940/4422 4321/3349/4422 +f 2299/2895/5147 2284/2736/5004 2286/2358/4671 +f 2518/4047/6999 2575/4267/6891 2514/4268/6893 +f 3108/3883/6835 3100/1966/4319 3109/2389/4701 +f 3596/4294/7000 3595/2738/5006 3605/2737/5005 +f 3888/3411/4554 3853/3285/4554 3884/4096/5778 +f 2517/3584/6646 2516/3583/6892 2580/3253/6647 +f 2288/2735/6459 2296/2961/5208 2192/4280/6923 +f 4280/2964/5211 4260/2966/5213 4279/2850/5106 +f 3199/3464/5753 3175/4242/6848 3099/3179/7001 +f 4294/1977/4329 4289/1976/4329 4291/4250/4329 +f 2548/2328/4642 2547/3527/5825 2492/4278/6916 +f 3691/3308/5576 3655/2601/4882 3667/3668/5990 +f 4006/4309/7002 3996/4266/7003 4007/3872/6242 +f 2549/2925/5177 2533/2312/4629 2550/2326/4640 +f 3391/4202/4755 3381/2451/4755 3389/2453/4755 +f 2046/3572/5880 2047/2612/6503 2019/2613/7004 +f 2583/3748/26 2379/4310/26 2373/4311/26 +f 3194/4240/6846 3195/3327/5596 3196/4172/6700 +f 3787/3199/5466 3717/3626/5941 3786/3182/6974 +f 3177/3211/5478 3161/3379/5655 3198/3328/5597 +f 2491/3387/5665 2490/3386/5664 2488/4312/7005 +f 3225/3016/6598 3237/2398/6600 3224/3642/5958 +f 3695/2188/6349 3696/2538/6349 3580/2537/6349 +f 3838/2232/4785 3863/3189/7006 3839/2231/6262 +f 4191/3270/5539 4183/3712/6049 4222/3413/5697 +f 2034/2760/5025 2035/2541/4832 2022/2776/6248 +f 3355/4279/4755 3352/2656/4755 3354/2044/4386 +f 3712/3472/5761 3702/3763/5358 3708/3627/5358 +f 3304/4157/6671 3308/3643/5959 3306/3644/5960 +f 4017/2817/5076 3987/2733/7007 4000/3471/5760 +f 3466/2209/7008 3576/2213/7008 3575/2605/7009 +f 2324/3237/5504 2325/3933/6332 2245/3412/5696 +f 4168/2647/6837 4170/2646/4923 4271/4258/6874 +f 2323/3652/5971 2319/4313/7010 2247/3653/5972 +f 3390/3907/6295 3404/2162/4491 3388/3448/5738 +f 2519/3865/6230 2180/2501/7011 2179/3133/6231 +f 4113/2468/4367 4111/2176/4367 4080/2365/4367 +f 3263/2033/4351 3269/3079/4351 3251/3070/4351 +f 3879/3842/4554 3844/2395/5778 3876/3840/4554 +f 3664/3898/6280 3663/3410/5693 3638/2199/6804 +f 4121/2816/5075 4106/4296/6961 4107/2835/5886 +f 3321/3507/5796 3323/4314/7012 3322/3831/6195 +f 2057/3417/5699 2055/3919/6308 2056/3418/5700 +f 3281/2828/5087 3280/3832/6196 3292/2829/5088 +f 2567/3314/5582 2565/3238/5505 2555/3139/5401 +f 3706/3839/5358 3714/3112/5358 3705/4315/5358 +f 3290/2625/4906 3307/2627/4908 3309/4316/7013 +f 3311/3920/6309 3314/4317/7014 3313/3887/6266 +f 2141/3376/7015 2140/2408/7015 2139/2407/7015 +f 3132/2359/4672 3133/3157/4672 3131/2360/4673 +f 3123/3171/5994 3125/2216/7016 3126/3672/5995 +f 4104/2058/4396 4103/4063/7017 4074/2059/4397 +f 4237/2853/4517 4238/2189/4517 4205/3674/4517 +f 2564/3140/5402 2326/3050/5305 2329/2341/4653 +f 2232/2334/4648 2234/4318/7018 2233/2294/4611 +f 1964/3740/4316 1965/3739/4316 1963/3488/4316 +f 4292/2604/4885 4366/2603/4884 4391/3902/6288 +f 3581/2104/7019 3683/2303/4620 3578/2102/4433 +f 4177/3086/6710 4281/3043/5296 4280/2964/5211 +f 3272/4281/4351 3273/2003/4351 3242/2159/4351 +f 3475/2288/4605 3499/2287/4604 3501/2697/7020 +f 4129/2014/4360 4160/4288/6943 4140/3321/5590 +f 2356/2529/4822 2318/2528/4821 2572/3616/5926 +f 4006/4309/7021 4045/3691/6022 4005/3439/6640 +f 4080/2365/4678 4077/2065/5250 4079/2064/4678 +f 3724/3129/5388 3726/3751/4336 3723/3130/4336 +f 4306/2086/4422 4304/2088/4422 4309/2519/4422 +f 3194/4240/6846 3196/4172/6700 3159/2822/5081 +f 3829/2307/4624 3904/2629/4910 3905/2305/4622 +f 2119/3607/7022 2121/2410/7023 2718/2660/4932 +f 3635/2806/5671 3648/2304/4621 3633/2999/5248 +f 4281/3043/5296 4177/3086/6710 4182/3088/5661 +f 3642/4230/6805 3662/3442/6478 3641/4032/6477 +f 4250/2852/5108 4251/4177/7024 4238/2189/5109 +f 2416/3173/5434 2418/3249/5516 2417/4226/6797 +f 3269/3079/7025 3263/2033/4377 3278/2116/4698 +f 3099/3179/5444 3089/4241/5444 3088/3180/5444 +f 3322/3831/6195 3324/3986/6419 3292/2829/5088 +f 2089/2968/6730 2703/3995/6437 2832/4081/6554 +f 2321/2705/4974 2569/3730/6074 2322/3731/6075 +f 4152/3032/5284 4122/2815/5074 4150/2368/4681 +f 2266/3851/6214 2250/2923/5175 2249/3302/5568 +f 3603/2739/5007 3595/2738/5006 3602/3890/7026 +f 3975/3259/6733 3951/4044/6500 3974/4128/7027 +f 3996/4266/7003 3986/3873/6243 4007/3872/6242 +f 3758/2163/4492 3728/3938/6341 3727/2909/6822 +f 3548/4065/6528 3570/2166/4495 3569/2717/4986 +f 4087/2023/7028 4088/2369/4682 4090/2021/4684 +f 3342/2308/4625 3430/3296/5562 3431/2018/4364 +f 2952/4208/6762 2949/4224/6793 2948/4083/6763 +f 3875/4057/4554 3870/1999/4554 3878/3187/5778 +f 3519/3974/4388 3484/2903/4388 3520/3734/4388 +f 3097/2425/4965 3096/2424/6160 3184/2153/4481 +f 3778/2905/5159 3806/2245/4565 3777/3720/6059 +f 3510/2046/5834 3529/2718/5836 3528/2296/5720 +f 3613/2562/6676 3615/2434/6894 3598/3879/6675 +f 3367/2856/7029 3368/4319/7029 3370/2884/6390 +f 3218/3843/6205 3215/3630/6119 3207/3629/6119 +f 4309/2519/4812 4334/2617/4898 4332/2517/4810 +f 3485/2488/6836 3487/2490/6927 3471/2556/4844 +f 3929/2651/4688 3925/2499/4688 3928/3494/4688 +f 3778/2905/5159 3807/3246/5513 3806/2245/4565 +f 2000/3750/4585 2002/3334/4585 2021/2643/4584 +f 3268/3078/5333 3281/2828/6924 3272/4281/6926 +f 4060/3414/5698 4162/3416/5698 4055/3744/7030 +f 3257/2841/5097 3229/2234/4556 3259/3226/5492 +f 3139/2300/6258 3137/3904/6928 3136/2484/6928 +f 3238/2930/5182 3236/4307/5268 3235/3017/5268 +f 2412/3242/5509 2427/4225/6796 2428/3243/5510 +f 2579/2553/5493 2578/4320/7031 2452/3227/5494 +f 3561/2115/4444 3562/2114/4443 3456/3917/6306 +f 2420/3519/5812 2450/2412/4721 2432/2411/4720 +f 3560/3918/6307 3542/4040/6491 3543/4133/6632 +f 2805/4000/6443 2806/2505/4802 2712/2899/5151 +f 4118/2876/4367 4117/2875/4367 4085/3011/4367 +f 3514/2543/4388 3480/2764/5028 3478/2384/4388 +f 4104/2058/6914 4076/2837/5251 4105/2836/6525 +f 2409/3396/5677 2389/3955/6368 2398/2896/5148 +f 3736/2067/6888 3737/4321/7032 3739/2435/6889 +f 2806/2505/4802 2807/3620/5934 2813/3881/6255 +f 2466/3025/5278 2410/3395/5676 2408/3394/5675 +f 3589/3323/4434 3585/2173/4434 3588/3863/6228 +f 2628/3569/5876 2150/3282/5875 2627/3281/6391 +f 3775/4134/6633 3761/4142/6643 3760/3760/6111 +f 2490/3386/5664 2524/3655/5974 2158/3534/6910 +f 3147/3381/5657 3141/3354/5627 3160/3355/5629 +f 4238/2189/5109 4251/4177/7024 4236/2190/7033 +f 3974/4128/7027 3951/4044/6500 3972/4045/6501 +f 2815/3023/5274 3000/4218/6779 2816/3868/6237 +f 3223/3641/4351 3222/3225/4351 3225/3016/4351 +f 4227/3127/4517 4217/2321/4517 4220/3940/4517 +f 3254/2235/4557 3252/3069/7034 3228/2233/4555 +f 3985/2731/7035 3955/3427/5710 3984/4322/7036 +f 2738/2730/4999 2748/2729/4998 2769/3072/5327 +f 4086/4274/7037 4088/2369/4682 4087/2023/7028 +f 3565/2297/4614 3452/2681/4948 3564/3905/6292 +f 3707/2247/4567 3805/3770/6117 3806/2245/4565 +f 2992/2975/5222 2998/4206/6788 2977/2973/5220 +f 3947/2252/4572 3956/3429/5800 3958/2253/4573 +f 2633/3330/7038 2155/3785/6345 2926/3535/5832 +f 2795/3601/5905 2758/3598/5902 2756/3597/5901 +f 3960/2251/6977 3961/4276/7039 3962/3909/6297 +f 4193/2583/6704 4192/2084/6050 4183/3712/6049 +f 3421/2772/5035 3422/2807/5066 3335/2773/5036 +f 3720/1987/4405 3736/2067/4404 3721/1985/5448 +f 3138/1964/4317 3136/2484/4783 3107/1965/4318 +f 2141/3376/7040 2994/1981/7041 2995/3753/6103 +f 2962/2782/6275 2967/3460/6712 2972/3896/6276 +f 3996/4266/5000 3973/4014/5000 3986/3873/5000 +f 1992/2640/5361 1991/3107/5363 1990/2547/6932 +f 1974/3466/5755 1975/2239/4561 1976/2506/4316 +f 3430/3296/5562 3429/2869/5125 3425/3716/6055 +f 2177/4153/7042 2175/3521/7043 2960/4323/7044 +f 3559/2531/4824 3459/3758/6109 3558/2532/4825 +f 4122/2815/5074 4149/2366/4679 4150/2368/4681 +f 4033/3915/6304 4032/3008/5260 4034/3913/6302 +f 3352/2656/4755 3350/4029/4755 3351/2854/4755 +f 3162/3380/5656 3161/3379/5655 3177/3211/5478 +f 3265/2034/4378 3275/2219/4542 3276/2035/4379 +f 2450/2412/4721 2469/4214/6773 2476/4176/6707 +f 4073/3568/5872 4072/2429/4735 4070/2431/4367 +f 2486/2277/4594 2497/2026/4370 2484/4324/7045 +f 3991/2280/5000 3980/2479/5000 3992/2278/5000 +f 2311/3124/5382 2313/2749/5017 2531/3679/6004 +f 1966/2535/4828 1961/2534/4827 1962/2820/6472 +f 4259/2965/5212 4280/2964/5211 4281/3043/5296 +f 3582/2548/4434 3580/2537/4434 3590/3639/4434 +f 3360/2723/4992 3359/3969/6393 3358/4185/7046 +f 2940/4105/26 2977/2973/26 2937/4293/26 +f 3227/3654/5973 3247/3699/7047 3245/2684/4952 +f 2036/2355/4668 2035/2541/4832 2048/2353/4666 +f 2448/4198/6747 2251/2747/5015 2396/3551/5854 +f 3215/3630/7048 3220/3550/7049 3330/2041/7048 +f 2578/4320/7031 2577/3352/5624 2455/3353/5626 +f 3161/3379/5655 3160/3355/6333 3178/4325/7050 +f 3772/3181/4336 3737/4321/4336 3771/3957/4336 +f 1987/2330/5731 1988/2268/5730 1986/2267/6331 +f 4282/3711/4924 4283/4006/4924 4287/2569/4924 +f 2512/3450/6235 2584/3867/6234 2588/4082/6555 +f 3771/3957/4336 3737/4321/4336 3734/2753/4336 +f 4227/3127/4517 4226/4085/4517 4217/2321/4517 +f 2367/2552/26 2363/4326/26 2578/4320/26 +f 2810/2138/4466 2809/2140/4468 2808/2504/4801 +f 4391/3902/6288 4299/4016/6935 4292/2604/4885 +f 3864/2487/5455 3867/2111/4440 3865/4261/6881 +f 3086/3053/4731 3087/4137/4731 3085/2678/4731 +f 3344/3405/5685 3430/3296/5562 3342/2308/4625 +f 2360/3834/6198 2384/3836/6200 2392/4327/7051 +f 3229/2234/4351 3228/2233/4555 3227/3654/5973 +f 2069/2565/4316 2073/4328/5756 2072/2508/4316 +f 3747/2549/5387 3749/2131/6702 3724/3129/5388 +f 3247/3699/7047 3227/3654/5973 3248/3193/6381 +f 3346/3404/6918 3444/4329/7052 3445/3877/6251 +f 2790/3027/5279 2791/2877/5133 2792/2423/4730 +f 4110/3147/7053 4106/4296/6961 4122/2815/5074 +f 2260/4196/7054 2261/3207/7055 2262/3206/7055 +f 3212/3506/5795 3219/3718/6057 3323/4314/7012 +f 2494/3666/5987 2492/4278/6916 2151/4330/7056 +f 2307/3987/6420 2301/3502/5791 2306/2572/4857 +f 4392/3661/5981 4302/2201/4525 4368/3287/5555 +f 3089/4241/6847 3099/3179/7001 3175/4242/6848 +f 4198/4331/4517 4200/3026/4517 4235/4062/4517 +f 3438/2017/4363 3437/2281/4598 3440/3579/5890 +f 2869/3797/6150 2868/4120/6613 3037/2525/4818 +f 3228/2233/4555 3252/3069/7034 3250/3071/6380 +f 2468/2799/5059 2474/4332/7057 2451/3292/5558 +f 3752/2130/4457 3751/2467/4457 3749/2131/4458 +f 2497/2026/4370 2499/2025/4369 2534/3248/5515 +f 2731/2751/5019 2768/4213/6770 2767/3647/5966 +f 2325/3933/6332 2246/2703/4972 2245/3412/5696 +f 3562/2114/4443 3525/2918/5172 3563/2917/5171 +f 3176/3210/5477 3089/4241/6847 3163/2758/5023 +f 3601/3044/5297 3629/2635/5554 3602/3890/7026 +f 3577/2595/4532 3572/2337/4532 3576/2213/4532 +f 3542/4040/6491 3559/2531/4824 3541/2533/4826 +f 3215/3630/7048 3330/2041/7048 3331/3631/7048 +f 2412/3242/5509 2438/3252/5519 2439/3251/5518 +f 4325/3452/5849 4328/3549/5851 4326/3289/6636 +f 1983/2156/4484 2008/2155/4483 2006/2865/5120 +f 3409/4333/7058 3443/2900/5152 3408/3095/5351 +f 1984/3224/6579 1977/3728/6071 1985/3727/6070 +f 3602/3890/7026 3629/2635/5554 3631/2634/7059 +f 3449/4334/7060 3337/2001/7061 3345/2309/7060 +f 3348/2657/7062 3361/2722/7063 3349/2655/5601 +f 3969/2271/4587 3967/2270/4586 3966/3942/6348 +f 3202/4194/4731 3200/2680/4731 3204/3855/4731 +f 3358/4185/7046 3359/3969/6393 3357/4335/7064 +f 1990/2547/4839 1978/2331/4645 1979/2639/4916 +f 2560/3077/5332 2558/4037/6487 2557/4039/6489 +f 2708/3999/6442 2707/2503/4800 2903/3375/5651 +f 2820/3432/5717 2709/3784/6135 2819/4299/6971 +f 3608/2200/6286 3609/2687/4956 3607/4336/6286 +f 2525/3660/5980 2174/4161/6941 2162/3656/5975 +f 2002/3334/4585 2005/2186/4584 2020/2557/4585 +f 4269/4075/6548 4168/2647/6837 4270/3723/6064 +f 3545/3537/5837 3534/2146/4474 3535/2145/6714 +f 2869/3797/6150 2867/4123/6617 2868/4120/6613 +f 3145/2757/4406 3126/3672/4406 3129/3146/4406 +f 2449/3310/5578 2448/4198/6747 2421/4048/6506 +f 1993/3106/4585 1994/3891/4585 2025/2944/4585 +f 2588/4082/6555 2386/2450/4754 2387/3165/7065 +f 3112/2317/6929 3109/2389/6343 3111/2318/6929 +f 2117/3344/7066 2118/3343/7066 2126/4337/7067 +f 2096/3692/6023 2099/2077/6025 2097/2712/7068 +f 2797/3144/5406 2798/3143/5405 2780/2970/5217 +f 2355/4338/7069 2354/4339/7070 2353/3849/6212 +f 2276/3798/6154 2196/3801/6157 2195/3799/6155 +f 3399/3347/5620 3421/2772/5619 3420/3577/5887 +f 3931/3976/5355 3941/3757/5355 3938/2415/5355 +f 3908/3841/7071 3913/4340/7072 3907/4341/7073 +f 3641/4032/6477 3660/3219/5485 3643/3649/5968 +f 4160/4288/6943 4129/2014/4360 4128/2566/4852 +f 2855/3971/6395 2858/3997/6440 2857/3972/6396 +f 2350/2259/4579 2351/2258/4578 2352/4139/6638 +f 2260/4196/6745 2251/2747/5015 2264/4342/7074 +f 4156/3196/5463 4155/4215/6775 4061/2771/5034 +f 2400/2798/5058 2402/4343/7075 2468/2799/5059 +f 2576/4246/6853 2518/4047/6999 2519/3865/6230 +f 2751/2702/4971 2758/3598/5902 2752/4077/6550 +f 4269/4075/6548 4268/2029/4373 4168/2647/6837 +f 3754/2699/4768 3756/4245/6852 3755/3294/5560 +f 2101/2299/4617 2099/2077/4413 2471/2079/4415 +f 4244/3061/6563 4245/2849/5105 4225/3462/6561 +f 3467/2208/7076 3552/2461/4763 3465/3578/5889 +f 4346/3829/6361 4351/3497/4422 4341/3539/4422 +f 2994/1981/7041 2996/1980/6104 2995/3753/6103 +f 3103/2796/4406 3102/3046/4406 3101/2388/4406 +f 2384/3836/7077 2295/2962/6510 2389/3955/6368 +f 2690/3980/6409 2786/4251/6861 2800/2636/4914 +f 2976/2974/26 2977/2973/26 2940/4105/26 +f 3429/2869/5125 3430/3296/5562 3427/4178/6709 +f 2155/3785/6911 2156/4300/6972 2489/4275/6912 +f 3270/2893/4351 3236/4307/6749 3238/2930/4351 +f 2893/2673/4942 2894/2404/4716 3027/2406/4718 +f 4397/2663/4329 4396/4344/4329 4395/2979/4329 +f 2491/3387/5665 2493/4277/6915 2545/3698/6031 +f 4175/2567/4853 4181/2879/4854 4286/2568/4854 +f 3469/2939/7078 3507/2382/7079 3477/3762/7080 +f 3463/2349/4661 3567/2167/4496 3462/3912/6301 +f 3443/2900/5152 3441/3899/6281 3442/3096/5352 +f 3692/4264/6886 3584/3322/7081 3690/3434/5719 +f 4065/2071/4407 4059/2770/4409 4058/2072/4408 +f 3517/2524/4388 3498/4287/4388 3518/2170/4388 +f 2008/2155/7082 2009/3275/7082 2007/2185/4515 +f 3531/2394/4706 3548/4065/6528 3530/3536/5835 +f 2822/4345/7083 2823/2050/4391 2902/2049/4390 +f 2890/2957/5204 2889/3081/5336 2824/3525/5819 +f 2365/4346/26 2364/2777/26 2587/2448/26 +f 4336/2638/6499 4335/2616/6498 4337/3613/5920 +f 3457/2207/4807 3575/2605/4807 3574/2512/4807 +f 3310/4285/6933 3309/4316/7013 3209/3939/7084 +f 2030/3994/6435 2016/2493/5931 2029/3619/5933 +f 3777/3720/6059 3806/2245/4565 3805/3770/6117 +f 3216/2919/5173 3319/2217/4539 3315/4347/7085 +f 4173/3307/5575 4180/2891/5144 4169/2892/4924 +f 2591/3713/6053 2593/3453/6052 2117/3344/6832 +f 2903/3375/5651 2906/2075/4411 2819/4299/6971 +f 3951/4044/5000 3952/3704/5000 3950/2242/5001 +f 3725/4110/6603 3751/2467/6701 3753/2466/6601 +f 2214/3004/5254 2213/4189/6731 2308/4348/7086 +f 3133/3157/4672 3134/2485/7087 3135/3158/7087 +f 2419/3120/5378 2416/3173/5434 2442/3175/5436 +f 3960/2251/6977 3959/3733/6978 3961/4276/7039 +f 4166/3415/6311 4064/2579/6312 4165/2581/6312 +f 2996/1980/7088 2997/4205/6759 2991/4207/6761 +f 2671/4138/6635 2670/4349/7089 2895/2454/4756 +f 3291/2833/5092 3294/4286/6934 3293/3928/6326 +f 2031/3929/6327 2062/4173/6703 2063/4150/6660 +f 2494/3666/5987 2496/4350/7090 2549/2925/5177 +f 3465/3578/5889 3556/2812/5071 3464/2546/4838 +f 3120/3172/5432 3118/3701/6040 3103/2796/6039 +f 4105/2836/4367 4110/3147/4367 4102/2743/4367 +f 3513/3168/4388 3503/2047/4388 3510/2046/4388 +f 3090/4253/6864 3088/3180/5444 3094/3209/5476 +f 3692/4264/6886 3593/3706/6041 3584/3322/7081 +f 4227/3127/5385 4224/3229/5497 4240/3125/5383 +f 2708/3999/6442 2903/3375/5651 2819/4299/6971 +f 2805/4000/6922 2710/4002/6689 2946/3772/6120 +f 2909/3990/6428 2904/3110/5367 2818/3111/5368 +f 4084/3010/5262 4086/4274/7091 4087/2023/5263 +f 2540/3675/5999 2539/3677/6001 2529/2642/4919 +f 2646/4351/7092 3015/2994/5243 3014/4352/7093 +f 3113/2319/4635 3115/3047/5965 3116/2263/5964 +f 3971/3524/5817 3972/4045/7094 3970/2244/5818 +f 3769/4069/7095 3770/2223/4546 3780/2222/4545 +f 3167/4074/6547 3166/2193/4519 3182/2696/4964 +f 3796/3903/6289 3794/3871/6240 3795/2794/5055 +f 3536/2460/7096 3535/2145/4473 3522/4055/6811 +f 4163/4135/5263 4059/2770/5263 4054/2769/6634 +f 4271/4258/6874 4273/3935/6338 4272/3222/5489 +f 1963/3488/4316 1962/2820/6472 1964/3740/4316 +f 3969/2271/5000 3999/3089/5000 3971/3524/5000 +f 2315/2996/5245 2572/3616/5926 2573/2677/4946 +f 3023/4233/6827 2901/3313/5581 2822/4345/7083 +f 3894/2371/4685 3893/2373/5452 3877/2414/4723 +f 3603/2739/5007 3602/3890/7026 3631/2634/7059 +f 4366/2603/4884 4365/3901/6287 4391/3902/6288 +f 2467/4210/6766 2474/4332/7057 2402/4343/7075 +f 4305/2087/5198 4306/2086/5691 4322/2950/5196 +f 3735/2066/6366 3737/4321/7032 3736/2067/6888 +f 2427/4225/6796 2416/3173/5434 2417/4226/6797 +f 4273/3935/6338 4170/2646/4923 4171/3936/6339 +f 3968/2243/4563 3949/3703/6264 3967/2270/6263 +f 4032/3008/5260 4031/2081/4417 4014/2080/4416 +f 3496/3335/5604 3498/4287/7097 3497/4295/6994 +f 4311/3951/6361 4310/3419/4422 4309/2519/4422 +f 3740/2436/4741 3742/3283/5713 3741/3511/5804 +f 3239/2157/6599 3225/3016/6598 3241/2158/4513 +f 4205/3674/6677 4202/2191/5366 4203/2831/7098 +f 3598/3879/6675 3597/3340/5611 3611/3341/5613 +f 3205/3856/7099 3085/2678/7099 3092/3542/7099 +f 3701/3838/7100 3813/3212/6889 3811/3764/7100 +f 3304/4157/6671 3306/3644/5960 3288/2179/6672 +f 3207/3629/6471 3326/2039/6471 3206/3015/6471 +f 3449/4334/7101 3339/2002/7101 3337/2001/7102 +f 2079/2741/6008 2078/2740/7103 2077/3223/6009 +f 2903/3375/6122 2706/3374/7104 2946/3772/6120 +f 3746/3092/5348 3770/2223/4337 3748/2550/4336 +f 1969/1961/4314 2066/2354/4667 2065/2653/4928 +f 3435/2301/4618 3336/2016/4362 3334/3512/5805 +f 2691/3372/5648 2784/3371/5647 2782/3612/5919 +f 3149/2631/5924 3148/3710/6047 3171/3599/6813 +f 4199/3108/5364 4202/2191/5366 4200/3026/5364 +f 2323/3652/5971 2569/3730/6074 2568/4232/6826 +f 2470/4353/7105 2429/2078/4414 2430/4354/7106 +f 4142/4033/6481 4143/3075/5330 4141/3278/5546 +f 3512/3167/4387 3505/2614/4387 3513/3168/4388 +f 3225/3016/6598 3226/2182/4511 3241/2158/4513 +f 3973/4014/6626 3974/4128/6625 3972/4045/7094 +f 3586/3409/5692 3587/3769/6785 3594/2768/5032 +f 3674/2576/4861 3658/2446/4750 3675/2445/4749 +f 3985/2731/7035 3984/4322/7036 3982/4231/6807 +f 3937/4355/7107 3940/2324/5354 3943/3203/5470 +f 2658/3221/5487 2657/3122/5380 2848/3123/5381 +f 3291/2833/5092 3290/2625/4906 3294/4286/6934 +f 2077/3223/5490 2078/2740/6257 2383/3360/5634 +f 3379/2452/5594 3381/2451/5595 3380/2042/5595 +f 2272/2481/5982 2199/3663/5984 2273/2482/6162 +f 4017/2817/5076 3993/3732/7108 3988/4356/7109 +f 3881/2707/4554 3857/2314/4554 3874/3431/4554 +f 3786/3182/6974 3717/3626/5941 3798/2792/5053 +f 2804/4243/6851 2686/2953/5200 2802/4054/6513 +f 3267/2180/4509 3288/2179/4508 3289/2626/5307 +f 4173/3307/5575 4268/2029/4373 4267/3953/6363 +f 3358/4185/7046 3356/2237/4559 3387/2236/4558 +f 3539/2960/5207 3519/3974/6398 3540/2621/4902 +f 3316/4248/6856 3314/4317/7014 3315/4347/7085 +f 4342/4121/7110 4340/3541/5842 4343/4357/7111 +f 3763/3721/4336 3756/4245/4336 3754/2699/4336 +f 4266/3954/6364 4267/3953/6363 4262/2597/4878 +f 3044/2527/4820 3034/3707/6044 3004/4221/6790 +f 4297/4249/7112 4300/4358/7113 4397/2663/7112 +f 3123/3171/5994 3124/3284/5996 3122/3463/6036 +f 4174/4159/5364 4167/2648/7114 4282/3711/5364 +f 3627/2470/4770 3628/3443/4770 3630/2633/4912 +f 3661/3382/5658 3677/4070/6543 3668/3383/5659 +f 4289/1976/7115 4297/4249/7115 4398/4359/7115 +f 4193/2583/6704 4183/3712/6049 4184/3422/5708 +f 3145/2757/4406 3146/2756/4406 3126/3672/4406 +f 4026/3204/5471 3945/2260/4580 4024/2262/4582 +f 2564/3140/5402 2562/2340/4652 2556/3141/5403 +f 3931/3976/5355 3932/2325/5354 3933/3012/5355 +f 3876/3840/6520 3889/2053/6519 3909/2052/6202 +f 3273/2003/6284 3272/4281/6926 3283/3931/6909 +f 4005/3439/5725 3996/4266/7003 4006/4309/7002 +f 3453/2338/4532 3461/2350/4662 3458/2336/5703 +f 4102/2743/5011 4101/2742/5010 4103/4063/6526 +f 4199/3108/7116 4198/4331/7117 4197/3425/7117 +f 3999/3089/5345 4009/3646/5962 3986/3873/6243 +f 3078/2725/4994 3009/2727/4996 3010/4360/7118 +f 4126/3362/5637 4125/4098/6583 4157/4097/6582 +f 4015/3009/5728 3994/3441/5727 4016/4184/7119 +f 4369/3201/6291 4368/3287/5555 4377/2203/4527 +f 2679/2955/5202 2678/4103/6589 2853/2956/5203 +f 3348/2657/4808 3352/2656/4755 3347/3007/4755 +f 3221/3824/6187 3219/3718/6057 3220/3550/4383 +f 3278/2116/4698 3279/3080/7120 3269/3079/7025 +f 4329/2981/6544 4331/3358/5632 4330/3357/5631 +f 4304/2088/5543 4305/2087/5198 4317/4036/7121 +f 3880/4066/6532 3907/4341/7122 3906/2402/7123 +f 4023/2261/4581 4021/3944/6351 4022/4283/6930 +f 3141/3354/4406 3147/3381/4406 3131/2360/4406 +f 3449/4334/4350 3446/3162/4350 3448/4236/4626 +f 3163/2758/5023 3162/3380/5656 3176/3210/5477 +f 3244/2623/4351 3246/2622/4351 3268/3078/4351 +f 2905/4306/6986 2849/2871/5127 2848/3123/5381 +f 3446/3162/4350 3451/2097/4350 3447/3163/4350 +f 3041/3795/6148 3047/2692/4960 3039/4025/6469 +f 3997/3440/5000 3964/3910/5000 3961/4276/5000 +f 3381/2451/5595 3383/4018/6314 3382/2043/6314 +f 3101/2388/4406 3107/1965/4406 3103/2796/4406 +f 3576/2213/4532 3572/2337/4532 3575/2605/4532 +f 3915/2051/4392 3913/4340/7072 3908/3841/7071 +f 2222/4361/7124 2224/4298/6968 2221/2495/4792 +f 3207/3629/5944 3331/3631/5944 3327/2040/5944 +f 2019/2613/4585 2018/2269/4585 1988/2268/4585 +f 2484/4324/7045 2497/2026/4370 2535/2311/4628 +f 2495/2926/5178 2485/2310/4627 2533/2312/4629 +f 2318/2528/4821 2270/3804/6681 2271/2483/4782 +f 2493/4277/6915 2491/3387/5665 2151/4330/7056 +f 3130/1990/4340 3128/2316/4633 3105/1988/4338 +f 3456/3917/6306 3559/2531/4824 3560/3918/6307 +f 3642/4230/5462 3610/2688/5462 3608/2200/4524 +f 3394/3368/4808 3362/2724/4755 3360/2723/4755 +f 4316/3967/6484 4314/2122/6725 4313/3277/6724 +f 3197/2823/5082 3178/4325/7050 3179/2821/5080 +f 2959/4362/7125 2958/2783/7125 3020/4021/7125 +f 2085/2844/5440 2094/2914/5437 2394/2558/4846 +f 2462/3390/6604 2464/2449/4753 2587/2448/4752 +f 3019/2726/4995 3021/4028/6470 3009/2727/4996 +f 2473/2986/5235 2108/3794/7126 2107/2985/5233 +f 3230/4147/7127 3222/3225/5491 3231/4042/6494 +f 3579/2103/4434 3582/2548/4434 3581/2104/4434 +f 2437/3604/5911 2436/2840/5096 2238/2293/4610 +f 2706/3374/7104 2705/3683/6921 2946/3772/6120 +f 2715/3135/5396 2130/2802/7128 2132/3291/7129 +f 2849/2871/5127 2907/2074/4410 2661/2076/4412 +f 1998/2379/5342 1995/2972/5344 1997/2255/5342 +f 3552/2461/4763 3554/3505/5794 3553/3504/5793 +f 2783/3496/5785 2784/3371/5647 2769/3072/5327 +f 3775/4134/6633 3803/3262/5528 3791/4140/6955 +f 3402/2885/4755 3370/2884/4755 3368/4319/4755 +f 2804/4243/6851 2820/3432/5717 2686/2953/5200 +f 4042/3563/5866 4002/2224/4954 4043/3725/6068 +f 2479/2571/7130 2512/3450/6235 2588/4082/6555 +f 3255/3065/4351 3256/3618/4351 3264/2135/4351 +f 2615/3958/6376 2145/2721/7131 2614/3959/6377 +f 2027/2377/4585 2025/2944/4585 1996/2378/4585 +f 2622/3964/6387 2620/3696/6389 2621/3695/7132 +f 3019/2726/4995 3022/4363/7133 2822/4345/7083 +f 4347/1995/4422 4348/4216/4422 4344/2123/4422 +f 4228/3596/6860 4256/2027/6871 4257/4211/6936 +f 2433/3517/5810 2421/4048/6506 2448/4198/6747 +f 4264/3305/5571 4251/4177/6708 4182/3088/5661 +f 2800/2636/4914 2801/3373/5649 2690/3980/6409 +f 2271/2483/4782 2265/4008/7134 2266/3851/6214 +f 4372/2941/7135 4371/3714/6054 4378/3003/5253 +f 4003/2226/6066 4043/3725/6068 4002/2224/4954 +f 3251/3070/4351 3269/3079/4351 3249/3194/6749 +f 3907/4341/7073 3913/4340/7072 3912/2306/4623 +f 3678/3216/5482 3663/3410/5693 3679/3217/5483 +f 2872/4124/6618 2871/4024/6468 2874/3316/5584 +f 4289/1976/7115 4398/4359/7115 4394/2662/7115 +f 3599/3766/6895 3620/3566/6843 3600/3468/5757 +f 3081/3454/5742 2718/2660/4932 2817/2990/5239 +f 4039/4060/6521 4041/3562/5865 4040/3013/5266 +f 3016/4187/6722 2645/4160/7136 2170/2947/5193 +f 4063/4244/6857 4132/2882/6480 4131/2881/6945 +f 1984/3224/6579 2012/3962/6580 2010/2060/4485 +f 2511/3366/6236 2510/3192/6098 2583/3748/6097 +f 2025/2944/4585 2023/2943/4585 1993/3106/4585 +f 2452/3227/7137 2475/4209/6765 2477/2825/5084 +f 3386/2238/5258 3355/4279/6919 3384/3490/6920 +f 3474/2286/4603 3493/3336/5689 3496/3335/6957 +f 2970/3557/5862 2956/3556/5861 2955/4118/6611 +f 2808/2504/4801 2807/3620/5934 2806/2505/4802 +f 2488/4312/7005 2489/4275/6912 2153/3514/7138 +f 3704/3474/5763 3801/3473/5762 3791/4140/6955 +f 3446/3162/5420 3333/2230/5420 3332/3570/5420 +f 3114/2630/4406 3116/2263/4406 3148/3710/4406 +f 1966/2535/4828 1973/1962/4315 2063/4150/6660 +f 2014/2492/5932 2028/4046/6508 2029/3619/5933 +f 3318/4235/6834 3316/4248/6856 3315/4347/7085 +f 3626/2469/4769 3628/3443/4770 3627/2470/4770 +f 3300/3717/6056 3301/3719/6058 3284/3900/6282 +f 3699/2187/6313 3592/3705/6313 3587/3769/6313 +f 4296/1978/6169 4373/3862/6274 4372/2941/7135 +f 3365/2855/6838 3366/2515/6838 3368/4319/7029 +f 1963/3488/4316 1965/3739/4316 1971/3465/5754 +f 2121/2410/4719 2451/3292/5558 2130/2802/7139 +f 3337/2001/4350 3341/2000/4350 3338/3814/4350 +f 2043/2945/5191 2042/3669/5991 2051/3895/6273 +f 2800/2636/4914 2688/2143/4471 2774/3530/5828 +f 3369/3966/6407 3351/2854/5111 3367/2856/5113 +f 3722/3183/5447 3738/2437/5449 3740/2436/6819 +f 2356/2529/4822 2357/4079/6552 2278/2530/4823 +f 3468/3697/4531 3457/2207/4531 3462/3912/4532 +f 2685/1969/4322 2684/2592/4873 2737/1967/4320 +f 3333/2230/5878 3334/3512/5878 3332/3570/5878 +f 3765/2755/4337 3732/2754/4336 3764/4141/4336 +f 2885/3480/5770 3031/3479/5769 3036/2859/5116 +f 3450/2098/4350 3446/3162/4350 3449/4334/4350 +f 3532/3064/5320 3546/3538/5838 3547/2393/4705 +f 2743/4043/6495 2742/3754/6105 2694/3989/6425 +f 3462/3912/6301 3570/2166/4495 3547/2393/4705 +f 4067/2057/4395 4068/2063/4400 4077/2065/4402 +f 3709/3645/5358 3706/3839/5358 3710/2246/5358 +f 4202/2191/5366 4201/3109/5365 4203/2831/7098 +f 2432/2411/4720 2118/3343/7140 2116/3356/7141 +f 2751/2702/4971 2755/2701/4970 2758/3598/5902 +f 4085/3011/5264 4082/2364/4677 4083/3664/5985 +f 2297/2894/5146 2398/2896/5148 2284/2736/5004 +f 2268/2924/6138 2202/3790/6142 2204/3787/6139 +f 4341/3539/5840 4339/3498/5921 4338/3540/5841 +f 3618/2433/4738 3619/3916/6305 3621/3565/5869 +f 2044/3094/5350 2045/3573/7142 2023/2943/5189 +f 2728/2988/5237 2723/3093/5349 2727/3625/5940 +f 2436/2840/5096 2231/2332/4646 2233/2294/4611 +f 3188/3688/6019 3172/3689/6020 3187/3837/6201 +f 2560/3077/5332 2331/1974/4327 2333/2285/4602 +f 4298/2810/5069 4389/3215/5481 4386/2811/5070 +f 3266/3051/5306 3290/2625/4906 3291/2833/5092 +f 3470/2554/4842 3469/2939/7078 3479/3761/7143 +f 2290/3827/7144 2291/3820/6737 2284/2736/5004 +f 1967/2240/5955 1975/2239/4561 2052/2109/4438 +f 2872/4124/6618 2867/4123/6617 2870/3796/6149 +f 3064/3228/5496 3004/4221/6790 3073/3433/5718 +f 2284/2736/5004 2285/3633/6823 2286/2358/4671 +f 2138/3370/5646 2453/3290/5556 2451/3292/5558 +f 3732/2754/7145 3731/3885/7145 3729/2910/6821 +f 3859/2315/4632 3860/4203/6984 3858/2313/4630 +f 2041/3670/6042 2026/2667/4938 2040/2110/4937 +f 3464/2546/4838 3558/2532/4825 3459/3758/6109 +f 4357/2940/5186 4359/3202/5469 4370/3200/6516 +f 2222/4361/7124 2221/2495/4792 2223/4364/7146 +f 2795/3601/5905 2789/2690/4958 2758/3598/5902 +f 3768/4144/7147 3779/2904/5158 3762/2698/5157 +f 4287/2569/5745 4169/2892/5745 4175/2567/5745 +f 2980/4199/26 2981/3737/26 2935/4027/512 +f 2164/4109/6597 2883/4131/6629 2882/4130/6628 +f 3701/3838/7100 3706/3839/6889 3813/3212/6889 +f 2851/2618/4899 2675/4100/6585 2674/2619/4900 +f 3543/4133/6632 3561/2115/4444 3560/3918/6307 +f 3227/3654/5973 3228/2233/4555 3250/3071/6380 +f 3293/3928/6326 3310/4285/6933 3312/3921/6310 +f 2617/3169/6379 2616/3960/6378 2619/2229/4552 +f 3840/2178/4506 3869/1997/5373 3841/4237/6839 +f 4232/2606/4886 4225/3462/6561 4245/2849/5105 +f 3000/4218/6779 2992/2975/6772 2993/4122/7148 +f 3243/2183/4904 3244/2623/4904 3242/2159/4487 +f 4294/1977/6030 4382/2762/5027 4381/2520/4813 +f 2993/4122/6614 2976/2974/5221 2975/3559/6615 +f 3164/2838/5094 3163/2758/5023 3175/4242/6848 +f 2360/3834/6198 2392/4327/7051 2361/3922/6315 +f 3599/3766/6895 3615/2434/6894 3618/2433/6906 +f 3808/3245/5512 3710/2246/4566 3807/3246/5513 +f 2969/3558/6080 2980/4199/6753 2968/4197/6752 +f 3030/3082/5337 2888/3481/5771 2854/3083/5338 +f 3167/4074/6547 3168/3602/5908 3153/3531/5907 +f 2309/2641/4918 2304/3503/5792 2214/3004/5254 +f 3878/3187/5778 3867/2111/5778 3877/2414/4554 +f 2551/2327/4641 2572/3616/5926 2552/2392/4704 +f 4224/3229/4517 4223/2083/4517 4194/2085/4517 +f 2924/3580/5891 3052/4170/6698 3053/3948/6355 +f 2112/3160/6995 2110/3852/7149 2473/2986/5235 +f 3777/3720/6059 3804/3771/6118 3793/3264/5530 +f 3728/3938/4337 3761/4142/4336 3730/4180/4337 +f 3788/3197/6859 3771/3957/6370 3789/3786/6372 +f 2524/3655/5974 2542/3388/5666 2559/4003/6446 +f 3835/2381/6421 3852/3286/6496 3836/2031/4375 +f 3641/4032/6477 3661/3382/5658 3660/3219/5485 +f 3818/2376/4690 3817/3941/6347 3822/3234/4688 +f 3956/3429/5800 3947/2252/4572 3946/3510/5801 +f 3234/3018/4351 3266/3051/4351 3232/4148/4351 +f 3823/2649/4925 3929/2651/4925 3928/3494/4925 +f 2866/3978/6404 2865/4119/6612 2864/4116/6609 +f 4289/1976/5851 4394/2662/5851 4393/2661/5851 +f 3873/2397/4709 3842/2396/4708 3872/4365/7150 +f 3104/2795/5433 3120/3172/5432 3103/2796/6039 +f 2275/3438/5724 2276/3798/7151 2271/2483/4782 +f 2700/3269/5538 2777/3293/5559 2776/2037/4381 +f 3713/2862/5119 3814/2864/5119 3705/4315/7152 +f 4159/3690/6021 4157/4097/6582 4065/2071/4407 +f 3512/3167/5426 3525/2918/6037 3509/2544/4836 +f 2023/2943/5189 2045/3573/7142 2024/4282/7153 +f 3324/3986/6419 3323/4314/7012 3299/4163/6687 +f 2259/3776/6125 2258/3777/6126 2206/3774/6123 +f 1974/3466/5755 2054/3445/5734 2053/3741/6086 +f 2997/4205/6787 2978/1979/4330 2977/2973/5220 +f 3337/2001/4350 3346/3404/4350 3345/2309/4350 +f 2650/4093/6575 2685/1969/4322 2844/4366/7154 +f 3486/2902/4388 3521/2586/4388 3488/2489/4388 +f 2583/3748/26 2574/3747/26 2379/4310/26 +f 2102/2010/6412 2103/2011/7155 2602/2427/6413 +f 3199/3464/5753 3099/3179/7001 3182/2696/4964 +f 4092/2089/4367 4115/2013/5277 4119/2012/4367 +f 4329/2981/5228 4327/3548/7156 4307/2980/5227 +f 3395/4257/6869 3377/3339/4808 3374/3029/4755 +f 3971/3524/5817 3973/4014/6626 3972/4045/7094 +f 3934/3854/7157 4036/4367/7158 4037/2819/5078 +f 4094/3485/6944 4073/3568/5872 4096/4227/6987 +f 3582/2548/5573 3682/3306/5572 3581/2104/7019 +f 2820/3432/5717 2804/4243/6851 2810/2138/4466 +f 3336/2016/4362 3439/2015/4361 3341/2000/5153 +f 3733/3134/6367 3731/3885/7145 3732/2754/7145 +f 4318/3348/6483 4317/4036/6485 4319/3058/7159 +f 3961/4276/7039 3964/3910/6298 3962/3909/6297 +f 3971/3524/5817 3968/2243/4588 3969/2271/4587 +f 3266/3051/5306 3267/2180/4509 3289/2626/5307 +f 3566/2348/4660 3569/2717/4986 3568/2168/4497 +f 2166/3257/5521 2168/2588/4869 2169/2587/4868 +f 3190/3020/5271 3191/3817/6178 3192/3052/5308 +f 2523/3420/5702 2340/3364/5639 2342/3239/5506 +f 3022/4363/7133 3023/4233/6827 2822/4345/7083 +f 2331/1974/4327 2330/3076/5331 2358/1975/4328 +f 2112/3160/6735 2596/3324/5591 2597/3455/5743 +f 2335/2284/4601 2332/4007/6451 2333/2285/4602 +f 3592/3705/6718 3698/2438/6718 3583/2174/6718 +f 4263/3304/5570 4265/3303/5569 4253/3926/6324 +f 2999/3752/6102 2815/3023/5274 2589/2711/5276 +f 3310/4285/6933 3311/3920/6309 3312/3921/6310 +f 3907/4341/7073 3912/2306/4623 3906/2402/4714 +f 2585/2094/4427 2463/2093/4426 2462/3390/6604 +f 4340/3541/7160 4311/3951/6644 4343/4357/7161 +f 2443/3121/5379 2245/3412/5696 2246/2703/4972 +f 1994/3891/6269 1993/3106/5362 1992/2640/5361 +f 3086/3053/5309 3192/3052/5308 3191/3817/6178 +f 3187/3837/6201 3087/4137/6946 3188/3688/6019 +f 4048/3593/7162 3931/3976/7162 3938/2415/7163 +f 4182/3088/5661 4248/2766/7164 4247/2765/7165 +f 4048/3593/7162 3938/2415/7163 4050/2417/7163 +f 4285/4222/7166 4172/3087/7166 4174/4159/7166 +f 3443/2900/5152 3439/2015/4361 3441/3899/6281 +f 2212/2750/5018 2286/2358/4671 2279/4080/6553 +f 3593/3706/6041 3670/2577/4862 3671/4368/7167 +f 3978/2478/5000 3989/2225/5001 3980/2479/5000 +f 3320/2118/4447 3317/2220/4543 3318/4235/6834 +f 2218/2982/5229 2353/3849/6212 2358/1975/4328 +f 3001/4284/6931 3063/3640/5954 3007/3333/5603 +f 2999/3752/6102 2996/1980/7088 2991/4207/6761 +f 2461/3482/5772 2579/2553/5493 2458/2824/5495 +f 2957/3892/6270 2959/4362/7168 3075/2610/4890 +f 4397/2663/7169 4293/4015/7169 4396/4344/7170 +f 4040/3013/5266 4018/2818/5077 4039/4060/6521 +f 3704/3474/5358 3702/3763/5358 3712/3472/5761 +f 2909/3990/6428 2821/4369/7171 2907/2074/4410 +f 3031/3479/5769 2888/3481/5771 3030/3082/5337 +f 4207/2846/5102 4206/2211/5102 4208/2120/5103 +f 1978/2331/4645 1987/2330/4644 1977/3728/6071 +f 3184/2153/4481 3181/2858/5115 3183/2695/4963 +f 3876/3840/4554 3873/2397/4554 3875/4057/4554 +f 3633/2999/4524 3632/3184/4524 3635/2806/4524 +f 2554/3315/5583 2566/3735/6076 2567/3314/5582 +f 2383/3360/5634 2394/2558/4846 2436/2840/5096 +f 3718/2911/5165 3729/2910/5164 3719/1986/5394 +f 3497/4295/6994 3498/4287/7097 3500/2045/4966 +f 2954/4117/6610 2953/4165/7172 2970/3557/5862 +f 3162/3380/5656 3163/2758/5023 3145/2757/5022 +f 3762/2698/5157 3778/2905/5159 3763/3721/6060 +f 3093/3406/5686 3083/3054/6864 3084/4023/4731 +f 4178/4370/6680 4176/2779/6679 4174/4159/6680 +f 4208/2120/5103 4210/2119/5744 4209/2845/5101 +f 3801/3473/5762 3712/3472/5761 3800/4186/6720 +f 2279/4080/6553 2278/2530/4823 2357/4079/6552 +f 2213/4189/6731 2530/3681/6006 2529/2642/4919 +f 4178/4370/7173 4279/2850/5106 4278/2780/5041 +f 3044/2527/4820 3003/4220/6789 3008/3231/5499 +f 3031/3479/5769 3070/3543/5843 3071/4106/6593 +f 2076/3177/7174 2074/3176/7174 2075/3682/7174 +f 2946/3772/26 2983/4058/26 2944/4059/26 +f 2155/3785/6136 2634/3329/5598 2635/3981/6410 +f 4302/2201/4329 4292/2604/4329 4293/4015/4329 +f 2409/3396/5677 2382/3477/5767 2408/3394/5675 +f 3107/1965/4406 3106/1989/4339 3105/1988/4338 +f 2947/3773/6121 2949/4224/6829 2950/3858/6829 +f 2759/3700/6034 2702/3385/5663 2761/2038/4382 +f 2423/3606/5913 2446/3301/5567 2449/3310/5578 +f 2588/4082/26 2584/3867/26 2374/4174/26 +f 3260/3145/6514 3259/3226/6515 3230/4147/6650 +f 2477/2825/5084 2458/2824/5083 2452/3227/7137 +f 3827/1984/4690 3825/2652/4690 3822/3234/4688 +f 3054/3949/6356 3053/3948/6355 3051/2958/5205 +f 3842/2396/4708 3844/2395/4707 3843/3545/5846 +f 3319/2217/4539 3216/2919/5173 3217/2218/4540 +f 2123/3608/7175 2590/3493/6947 2591/3713/6053 +f 2181/2913/5167 2177/4153/7042 2961/2912/5166 +f 2177/4153/7042 2960/4323/7044 3020/4021/6464 +f 3361/2722/7063 3348/2657/7062 3359/3969/7176 +f 2723/3093/5349 2728/2988/5237 2817/2990/5239 +f 2408/3394/5675 2407/2401/4713 2466/3025/5278 +f 3639/2599/4524 3619/3916/4524 3644/4104/4524 +f 2382/3477/5767 2398/2896/5148 2397/4010/6455 +f 3432/2808/5067 3404/2162/4491 3434/2161/4490 +f 4161/4136/4409 4162/3416/4409 4164/2580/4409 +f 2395/2713/4982 2097/2712/4981 2095/3178/5443 +f 3605/2737/6285 3608/2200/6286 3607/4336/6286 +f 2650/4093/6575 2844/4366/7154 2733/2560/4848 +f 3390/3907/4755 3385/3491/4755 3383/4018/4755 +f 2499/2025/4369 2502/2387/4696 2534/3248/5515 +f 3509/2544/4388 3508/2383/4388 3512/3167/4387 +f 3108/3883/6260 3110/2070/6344 3139/2300/6258 +f 3201/2679/4731 3205/3856/4731 3204/3855/4731 +f 3989/2225/5001 3978/2478/5000 3995/2889/5000 +f 4341/3539/4422 4342/4121/4422 4346/3829/6361 +f 4014/2080/7177 3997/3440/5726 4015/3009/5728 +f 3709/3645/5961 3808/3245/5512 3809/3952/6362 +f 4190/3461/4517 4189/2351/4517 4186/2832/4517 +f 4323/3288/6537 4322/2950/7178 4324/3408/6637 +f 3945/2260/4580 3944/3590/5354 3935/3060/5354 +f 4261/2028/4372 4267/3953/6363 4268/2029/4373 +f 2561/4179/6713 2328/3983/6415 2330/3076/5331 +f 2268/2924/5176 2269/3788/6902 2253/2922/5174 +f 2499/2025/4369 2498/2024/4368 2500/2654/4929 +f 3666/2998/6913 3680/3897/6279 3665/3132/6278 +f 4019/4252/6862 4022/4283/6930 4021/3944/6351 +f 3737/4321/4336 3772/3181/4336 3739/2435/4336 +f 2726/2345/4657 2765/2498/4795 2731/2751/5019 +f 2142/4371/7179 2144/3266/7179 2175/3521/7179 +f 3014/4352/7093 3015/2994/5243 3012/2949/5195 +f 3540/2621/4902 3557/2545/4837 3550/2814/5073 +f 2341/3365/5640 2343/4372/7180 2342/3239/5506 +f 2321/2705/4974 2566/3735/6076 2569/3730/6074 +f 3693/3667/5989 3593/3706/6041 3692/4264/6886 +f 3735/2066/6366 3734/2753/6365 3737/4321/7032 +f 2503/3574/5883 2483/3513/5806 2506/2459/4761 +f 4359/3202/4422 4357/2940/4422 4323/3288/4422 +f 2087/2842/5098 2083/2274/7181 2084/3945/7182 +f 4357/2940/5186 4371/3714/6863 4372/2941/5187 +f 2739/3859/6222 2738/2730/4999 2740/3002/5252 +f 3507/2382/4691 3478/2384/4693 3477/3762/4693 +f 2688/2143/4471 2687/4132/6631 2768/4213/6770 +f 2755/2701/4970 2757/3726/6069 2756/3597/5901 +f 2353/3849/6212 2354/4339/7070 2358/1975/4328 +f 2305/3005/5255 2214/3004/5254 2388/3166/5424 +f 4138/3576/5885 4137/2177/6673 4145/3635/5948 +f 2725/2752/5020 2724/4373/7183 2726/2345/4657 +f 3476/2938/6061 3507/2382/7079 3469/2939/7078 +f 4167/2648/4924 4174/4159/6680 4171/3936/6339 +f 2339/4072/6545 2341/3365/5640 2340/3364/5639 +f 3609/2687/5612 3596/4294/7000 3607/4336/7184 +f 3216/2919/5173 3208/4374/7185 3206/3015/4383 +f 4306/2086/5691 4307/2980/5227 4325/3452/5740 +f 3913/4340/7072 3915/2051/4392 3914/2291/4608 +f 2176/2591/4872 2177/4153/6907 2520/3993/6434 +f 2266/3851/6214 2317/4305/6980 2318/2528/4821 +f 2178/2933/6375 2612/4154/6667 2181/2913/6373 +f 2021/2643/4584 2026/2667/4584 2000/3750/4585 +f 3939/3014/5354 3931/3976/5355 3933/3012/5355 +f 4366/2603/6991 4355/3694/6027 4365/3901/6574 +f 2915/3515/5808 2633/3330/7038 2926/3535/5832 +f 3851/4375/4554 3886/2789/5778 3884/4096/5778 +f 3219/3718/6057 3300/3717/6056 3299/4163/6687 +f 2235/4376/7186 2236/4377/7187 2233/2294/4611 +f 3928/3494/5783 3927/3345/5783 3825/2652/5783 +f 3999/3089/5000 3966/3942/5000 3998/3522/5000 +f 4059/2770/7188 4163/4135/7188 4164/2580/7188 +f 3530/3536/5835 3548/4065/6528 3549/2719/4988 +f 3966/3942/6348 3967/2270/4586 3965/3822/7189 +f 2466/3025/5278 2411/3398/5679 2410/3395/5676 +f 3810/3113/5370 3781/3555/5860 3782/3554/6241 +f 3601/3044/5297 3599/3766/4524 3600/3468/5757 +f 3346/3404/6918 3426/3876/6250 3344/3405/5685 +f 4235/4062/6523 4236/2190/7033 4253/3926/6524 +f 4338/3540/6645 4337/3613/7190 4310/3419/5701 +f 2968/4197/6746 2965/2609/4889 3076/2611/4891 +f 2315/2996/7191 2573/2677/7191 2528/2676/7191 +f 3571/2462/4764 3468/3697/6844 3545/3537/5837 +f 2520/3993/6434 2478/2275/4592 2176/2591/4872 +f 4186/2832/5091 4203/2831/5090 4201/3109/6153 +f 3274/2137/4465 3312/3921/6310 3313/3887/6266 +f 3948/3811/6185 3960/2251/4571 3962/3909/6814 +f 2021/2643/4920 2036/2355/4668 2037/2644/4921 +f 3539/2960/5207 3521/2586/6729 3519/3974/6398 +f 2858/3997/6440 3035/3039/5292 3033/3998/6441 +f 3091/3943/6350 3187/3837/6201 3186/2791/5052 +f 2855/3971/6395 2887/2860/5117 3035/3039/5292 +f 4235/4062/4517 4229/4303/4517 4198/4331/4517 +f 3267/2180/6749 3266/3051/4351 3234/3018/4351 +f 2827/4030/6475 2855/3971/6395 2856/3973/6397 +f 2135/3378/7192 2134/3377/7193 2140/2408/7194 +f 2275/3438/6158 2274/3437/7195 2197/3802/6159 +f 3921/2372/4686 3892/3911/7196 3893/2373/4687 +f 3338/3814/6175 3413/3813/6174 3444/4329/7052 +f 2724/4373/7183 2725/2752/5020 2729/4013/6458 +f 2972/3896/26 2979/4200/26 2934/4308/26 +f 2574/3747/26 2378/3255/26 2379/4310/26 +f 3420/3577/7197 3343/2020/4366 3419/2019/4365 +f 2698/3648/5967 2076/3177/6431 2695/3338/5607 +f 2287/3632/6824 2281/3816/7198 2286/2358/4671 +f 2884/3738/6083 2882/4130/6628 3015/2994/5243 +f 2960/4323/7044 2175/3521/7043 3009/2727/4996 +f 2148/3040/7199 2151/4330/7056 2488/4312/7005 +f 2289/3426/5709 2290/3827/7144 2284/2736/5004 +f 3959/3733/6978 3958/2253/6978 3956/3429/5712 +f 4151/3033/5285 4061/2771/5034 4154/3031/5283 +f 3521/2586/4388 3486/2902/4388 3519/3974/4388 +f 3010/4360/7118 3009/2727/4996 2175/3521/7043 +f 2175/3521/7043 2144/3266/5535 3010/4360/7118 +f 3303/3844/6206 3305/4145/6648 3304/4157/6671 +f 2294/3819/7200 2285/3633/6823 2284/2736/5004 +f 2821/4369/7171 2909/3990/6428 2818/3111/5368 +f 3063/3640/5954 3005/4254/6865 3006/3036/5289 +f 3677/4070/6543 3594/2768/5032 3676/2510/4805 +f 2956/3556/5861 3076/2611/4891 3077/2775/5038 +f 3397/4111/6983 3395/4257/7201 3412/3298/7202 +f 4177/3086/4924 4178/4370/6680 4172/3087/4924 +f 2994/1981/4332 2141/3376/7203 2139/2407/6780 +f 2137/2710/7204 2136/4259/7205 2135/3378/7192 +f 3749/2131/4458 3748/2550/4841 3750/2132/4459 +f 2579/2553/26 2581/3483/512 2368/2551/26 +f 2518/4047/6504 2514/4268/7206 2515/3582/5893 +f 2953/4165/7172 2954/4117/6610 2952/4208/6762 +f 3371/3028/6408 3373/3030/5821 3352/2656/6406 +f 3491/2105/4435 3494/2107/4436 3493/3336/5605 +f 2548/2328/4642 2549/2925/5177 2550/2326/4640 +f 2560/3077/5332 2561/4179/6713 2330/3076/5331 +f 4184/3422/4517 4183/3712/4517 4190/3461/4517 +f 3913/4340/7072 3914/2291/4608 3821/2540/4831 +f 3202/4194/7207 3088/3180/7207 3090/4253/7207 +f 3863/3189/7006 3838/2232/4785 3861/4247/6937 +f 4128/2566/4852 4116/4191/6875 4127/2444/4748 +f 3308/3643/5959 3305/4145/6648 3210/4146/6649 +f 3157/2248/6685 3083/3054/5310 3194/4240/6846 +f 4071/2430/5533 4072/2429/4735 4091/3591/6771 +f 2896/1971/4324 3024/1970/4323 3026/2455/4757 +f 3039/4025/6469 3047/2692/4960 3046/3035/5288 +f 1999/3749/6099 1998/2379/5342 1997/2255/5342 +f 3649/2302/4619 3636/2133/4460 3650/2100/6342 +f 2726/2345/4657 2656/2347/4659 2655/4152/6663 +f 2771/2574/4859 2784/3371/5647 2801/3373/5649 +f 2651/4378/7208 2650/4093/6575 2845/4094/6576 +f 2240/4004/6447 2216/4304/6979 2438/3252/5519 +f 2567/3314/5582 2325/3933/6332 2324/3237/5504 +f 3045/3037/5290 3006/3036/5289 3005/4254/6865 +f 2753/4076/6549 2754/3756/6107 2751/2702/4971 +f 2424/3149/5410 2431/3151/5412 2426/3400/5681 +f 4022/4283/6930 4025/3258/5522 4024/2262/4582 +f 3520/3734/6490 3543/4133/6632 3542/4040/6491 +f 3444/4329/7052 3413/3813/6174 3414/2197/7209 +f 3282/3810/6170 3325/2827/5086 3298/3932/6330 +f 2306/2572/4857 2309/2641/4918 2538/2570/4855 +f 3333/2230/5878 3335/2773/5878 3334/3512/5878 +f 2586/3866/26 2179/3133/26 2376/4379/26 +f 3639/2599/4524 3621/3565/4524 3619/3916/4524 +f 2559/4003/6446 2523/3420/5702 2525/3660/5980 +f 3710/2246/5358 3706/3839/5358 3707/2247/4567 +f 3078/2725/4994 3022/4363/7133 3019/2726/4995 +f 2545/3698/6031 2544/3684/6011 2491/3387/5665 +f 3410/4086/6564 3443/2900/5152 3409/4333/7058 +f 3596/4294/7000 3609/2687/5612 3597/3340/5611 +f 3001/4284/6931 3052/4170/6698 2924/3580/5891 +f 2228/2494/4791 2229/3894/6272 2230/2333/4647 +f 3504/3722/6486 3503/2047/7210 3505/2614/4895 +f 4340/3541/7160 4338/3540/6645 4311/3951/6644 +f 2374/4174/26 2584/3867/26 2373/4311/26 +f 3900/1992/4342 3831/1991/4341 3899/3403/7211 +f 2259/3776/6125 2205/3775/6124 2264/4342/7212 +f 2296/2961/5208 2193/2963/5210 2192/4280/6923 +f 3872/4365/7213 3833/4192/6741 3841/4237/6839 +f 2217/3850/6213 2218/2982/5229 2239/2983/5230 +f 3949/3703/6264 3968/2243/4563 3950/2242/4562 +f 3232/4148/6652 3260/3145/6514 3230/4147/6650 +f 4125/4098/6900 4126/3362/5637 4108/3361/5636 +f 3208/4374/7185 3209/3939/6119 3206/3015/4383 +f 3200/2680/4731 3201/2679/4731 3204/3855/4731 +f 3404/2162/4491 3432/2808/5067 3403/2883/5138 +f 3953/3702/7214 3979/2480/7215 3982/4231/7216 +f 4144/3074/5329 4145/3635/5948 4137/2177/6673 +f 3041/3795/6148 3039/4025/6469 2870/3796/6149 +f 3879/3842/6204 3907/4341/7122 3880/4066/6532 +f 2414/3603/5910 2412/3242/5509 2413/3244/5511 +f 3402/2885/4755 3368/4319/4755 3400/2936/4755 +f 2064/2759/5024 1973/1962/4315 2065/2653/4928 +f 3641/4032/4524 3612/2686/4524 3610/2688/5462 +f 3552/2461/4763 3467/2208/7076 3468/3697/6844 +f 3887/3402/4554 3856/3588/5778 3888/3411/4554 +f 2922/3500/5789 2923/3138/5399 2921/3499/5788 +f 2430/4354/7106 2431/3151/5412 2112/3160/6995 +f 2966/2781/5042 2958/2783/5044 2965/2609/4889 +f 4256/2027/4371 4255/2598/4879 4261/2028/4372 +f 4236/2190/7033 4252/3927/7217 4253/3926/6524 +f 3118/3701/6427 3121/3875/6449 3119/3532/7218 +f 2095/3178/6531 2097/2712/7219 2096/3692/6529 +f 3174/3021/7220 3140/2069/5798 3144/2068/5923 +f 3427/4178/6709 3430/3296/5562 3344/3405/5685 +f 4299/4016/6935 4390/4260/6878 4389/3215/5481 +f 3687/2624/4905 3684/2976/5223 3685/2099/4430 +f 2298/2734/5002 2296/2961/6511 2288/2735/5003 +f 3884/4096/5778 3853/3285/4554 3851/4375/4554 +f 3235/3017/5956 3233/3019/6493 3223/3641/5957 +f 3174/3021/7220 3154/4273/7221 3140/2069/5798 +f 3155/3509/5799 3156/3673/5997 3142/3508/5797 +f 3398/2514/4755 3364/2513/4808 3399/3347/4755 +f 2047/2612/6503 2046/3572/5880 1965/3739/6084 +f 2004/2184/5121 2003/4067/7222 1982/2866/5122 +f 4239/3230/6065 4258/4053/7223 4269/4075/6548 +f 3125/2216/4538 3123/3171/5431 3104/2795/5433 +f 3328/2672/4383 3326/2039/4383 3330/2041/4383 +f 3271/2004/4351 3270/2893/4351 3238/2930/4351 +f 2522/2276/4593 2521/4056/6517 2500/2654/4929 +f 4109/3148/4367 4108/3361/4367 4100/2744/4367 +f 3664/3898/6280 3680/3897/6279 3679/3217/5483 +f 3850/3808/4554 3886/2789/5778 3851/4375/4554 +f 3875/4057/6518 3891/3318/5586 3890/3320/5588 +f 2186/4078/6551 2293/3424/7224 2292/3423/6183 +f 2497/2026/4370 2486/2277/4594 2522/2276/4593 +f 4373/3862/6274 4296/1978/6169 4379/2522/4815 +f 3253/3102/4351 3255/3065/4351 3265/2034/4351 +f 3377/3339/5609 3375/2666/5608 3374/3029/5281 +f 4017/2817/5076 4037/2819/5078 4036/4367/7158 +f 4290/2809/5068 4384/2714/4983 4383/2761/5026 +f 4000/3471/5760 3990/4005/6450 4001/2279/4596 +f 2140/2408/7194 2137/2710/7204 2135/3378/7192 +f 2170/2947/7225 2645/4160/6682 2644/4380/7226 +f 2924/3580/5891 2926/3535/5832 3001/4284/6931 +f 2130/2802/7139 2451/3292/5558 2132/3291/5557 +f 2277/3800/7227 2265/4008/7134 2271/2483/4782 +f 2016/2493/4585 2017/3273/4585 2011/2062/4585 +f 2101/2299/7228 2102/2010/7229 2100/4381/7230 +f 4246/2607/4887 4231/2767/6467 4234/3236/7231 +f 2845/4094/6576 2652/4155/7232 2651/4378/7208 +f 2061/2536/4829 2060/2928/5180 1961/2534/4827 +f 3990/4005/5001 3983/2732/5001 3981/3451/5001 +f 3948/3811/6185 3965/3822/6184 3949/3703/6264 +f 3839/2231/6262 3863/3189/7006 3865/4261/7233 +f 3806/2245/4565 3807/3246/5513 3710/2246/4566 +f 2410/3395/5676 2411/3398/7234 2404/3397/5868 +f 4245/2849/5105 4279/2850/5106 4260/2966/5213 +f 2485/2310/4627 2484/4324/7045 2535/2311/4628 +f 2395/2713/4982 2077/3223/5490 2383/3360/5634 +f 2821/4369/7171 2819/4299/6971 2907/2074/4410 +f 3098/2426/7235 3203/4193/7236 3204/3855/7235 +f 2660/4382/7237 2849/2871/5127 2664/4383/7238 +f 2906/2075/4411 2665/2440/4744 2661/2076/4412 +f 3080/2774/5037 3019/2726/4995 2822/4345/7083 +f 3454/2594/4875 3573/3547/4875 3577/2595/4875 +f 2901/3313/5581 2900/2516/4809 2899/2476/4775 +f 2488/4312/7005 2490/3386/5664 2489/4275/6912 +f 2127/4113/6606 2124/4034/7239 2123/3608/7240 +f 3113/2319/4635 3116/2263/5964 3114/2630/6534 +f 2451/3292/5558 2476/4176/6707 2468/2799/5059 +f 2259/3776/7241 2264/4342/7074 2251/2747/5015 +f 3224/3642/5958 3237/2398/6600 3235/3017/5956 +f 3530/3536/5835 3511/2523/4816 3531/2394/4706 +f 3183/2695/4963 3097/2425/4965 3184/2153/4481 +f 4176/2779/5040 4178/4370/7173 4278/2780/5041 +f 3413/3813/6949 3395/4257/7201 3396/3045/6950 +f 4229/4303/4517 4196/2582/4517 4198/4331/4517 +f 2905/4306/6986 2729/4013/6458 2727/3625/5940 +f 3675/2445/4749 3673/2637/4915 3674/2576/4861 +f 4109/3148/6901 4110/3147/7242 4123/3882/6996 +f 3166/2193/4519 3167/4074/6547 3152/2194/4520 +f 2718/2660/4932 2716/4384/7243 2715/3135/5396 +f 2181/2913/6908 2519/3865/7244 2520/3993/6434 +f 2401/3526/5820 2399/2797/5057 2468/2799/5059 +f 3985/2731/7035 3982/4231/6807 3983/2732/6917 +f 4090/2021/4684 4091/3591/5899 4092/2089/5898 +f 3587/3769/6785 3592/3705/4434 3594/2768/5032 +f 3360/2723/4755 3392/3449/4755 3394/3368/4808 +f 2010/2060/4398 2012/3962/4399 2013/2061/4399 +f 2636/4385/7245 2641/3984/6416 2637/3678/6094 +f 2854/3083/5338 2680/4108/6595 2681/3299/5565 +f 2099/2077/7246 2100/4381/7230 2098/3693/7246 +f 3348/2657/7062 3357/4335/7247 3359/3969/7176 +f 2430/4354/7106 2429/2078/4414 2381/4219/6784 +f 3817/3941/6347 3917/2292/4609 3918/3319/5587 +f 2029/3619/5933 2057/3417/5699 2059/2929/5181 +f 3008/3231/5499 3003/4220/6789 3002/3232/5500 +f 3492/2106/4388 3490/2847/4388 3522/4055/4388 +f 2715/3135/5396 2817/2990/5239 2718/2660/4932 +f 2005/2186/4516 2002/3334/6539 2003/4067/6541 +f 3716/3114/5371 3796/3903/6289 3715/3908/6296 +f 4350/2419/4422 4336/2638/4422 4339/3498/4422 +f 4027/3553/5857 4025/3258/5522 4028/3638/5952 +f 2387/3165/7065 2302/3594/7248 2588/4082/6555 +f 3083/3054/6864 3086/3053/4731 3084/4023/4731 +f 2842/4089/6569 2749/4088/6568 2747/2728/4997 +f 3594/2768/5032 3677/4070/6543 3586/3409/5692 +f 3713/2862/5942 3715/3908/6296 3717/3626/5941 +f 2460/3857/7249 2459/2826/5085 2463/2093/5670 +f 2428/3243/5510 2417/4226/6797 2430/4354/7106 +f 3760/3760/6111 3776/3759/6110 3775/4134/6633 +f 2519/3865/7244 2518/4047/7250 2520/3993/6434 +f 3347/3007/4755 3352/2656/4755 3355/4279/4755 +f 2492/4278/6916 2493/4277/6915 2151/4330/7056 +f 2234/4318/7018 2235/4376/7186 2233/2294/4611 +f 4206/2211/4534 4187/2210/4533 4188/2121/4450 +f 2170/2947/5193 3012/2949/5195 3005/4254/6865 +f 3094/3209/5476 3177/3211/5478 3198/3328/5597 +f 2423/3606/5913 2421/4048/6506 2422/3150/5411 +f 2126/4337/7251 2118/3343/7140 2432/2411/4720 +f 4030/2082/4418 4031/2081/4417 4029/3205/5472 +f 2062/4173/6703 2061/2536/4829 1966/2535/4828 +f 4185/3421/6152 4186/2832/5091 4201/3109/6153 +f 3101/2388/4406 3100/1966/5056 3107/1965/4406 +f 3847/3103/5359 3846/3105/5360 3848/3889/5359 +f 2090/2888/5141 2093/3260/5525 2091/2887/5140 +f 3099/3179/7001 3097/2425/4965 3182/2696/4964 +f 4272/3222/5489 4273/3935/6338 4274/3067/5322 +f 3202/4194/7207 3203/4193/7207 3088/3180/7207 +f 2687/4132/6631 2767/3647/5966 2768/4213/6770 +f 2383/3360/5634 2415/4271/6898 2395/2713/4982 +f 4222/3413/6855 4192/2084/4420 4223/2083/4419 +f 2145/2721/7131 2143/3267/7252 2614/3959/6377 +f 3711/3853/6217 3799/3198/5465 3800/4186/6720 +f 2008/2155/7082 2007/2185/4515 2006/2865/4515 +f 2473/2986/5235 2470/4353/7105 2430/4354/7106 +f 3718/2911/5165 3758/2163/6316 3727/2909/5163 +f 3856/3588/5896 3857/2314/4631 3855/2030/6786 +f 3878/3187/5453 3893/2373/5452 3892/3911/6300 +f 3397/4111/4755 3377/3339/4808 3395/4257/6869 +f 2318/2528/4821 2317/4305/6980 2570/2632/4911 +f 2014/2492/5932 2018/2269/4893 2047/2612/4892 +f 2782/3612/5919 2743/4043/6495 2694/3989/6425 +f 3165/2839/5095 3166/2193/4519 3151/2192/4518 +f 3707/2247/4567 3701/3838/5358 3703/3864/6229 +f 2153/3514/6403 2631/3977/6402 2632/3331/5600 +f 3703/3864/6229 3805/3770/6117 3707/2247/4567 +f 2657/3122/5380 2656/2347/4659 2830/2346/4658 +f 3916/2403/4715 3918/3319/5587 3917/2292/4609 +f 3028/3393/5674 3029/3100/5357 2891/4011/6456 +f 3840/2178/4554 3834/2380/4554 3836/2031/4554 +f 3921/2372/4686 3920/3457/5746 3892/3911/7196 +f 2421/4048/6506 2423/3606/5913 2449/3310/5578 +f 4273/3935/6338 4276/3066/5321 4274/3067/5322 +f 2638/3614/7253 2639/3154/5415 2159/3153/5414 +f 4382/2762/5027 4291/4250/6858 4290/2809/5068 +f 3324/3986/6419 3322/3831/6195 3323/4314/7012 +f 3206/3015/6535 3326/2039/6535 3328/2672/6535 +f 2415/4271/6898 2414/3603/5910 2381/4219/6784 +f 3501/2697/4967 3503/2047/7210 3502/3765/7254 +f 4164/2580/4409 4163/4135/4409 4161/4136/4409 +f 3990/4005/5001 3981/3451/5001 3991/2280/5000 +f 4159/3690/6021 4065/2071/4407 4160/4288/6943 +f 3527/2298/4615 3564/3905/6292 3526/2916/5170 +f 2127/4113/6606 2128/4112/6605 2124/4034/7239 +f 3901/3746/6750 3884/4096/6581 3902/3055/5311 +f 2902/2049/4390 2910/2048/4389 3013/4223/6792 +f 2362/4175/26 2365/4346/26 2587/2448/26 +f 3343/2020/4626 3333/2230/5878 3340/2096/4626 +f 2551/2327/4641 2552/2392/4704 2548/2328/4642 +f 3488/2489/4388 3523/2585/4388 3490/2847/4388 +f 2867/4123/6617 2865/4119/6612 2868/4120/6613 +f 2491/3387/5665 2543/3685/6012 2542/3388/5666 +f 3118/3701/6427 3120/3172/6035 3121/3875/6449 +f 2686/2953/5200 2818/3111/5368 2730/2954/5201 +f 3365/2855/5112 3350/4029/6473 3349/2655/5601 +f 2019/2613/7004 2024/4282/7153 2046/3572/5880 +f 3017/3807/6166 3016/4187/6722 3005/4254/6865 +f 4025/3258/5522 4010/3091/5347 4011/3090/5951 +f 2259/3776/7241 2251/2747/5015 2258/3777/6337 +f 3963/3823/6299 3966/3942/6348 3965/3822/7189 +f 3399/3347/4755 3362/2724/4755 3393/3346/4808 +f 3168/3602/5908 3169/2857/5114 3150/2265/5909 +f 2405/3845/6208 2464/2449/6207 2462/3390/7255 +f 2119/3607/5914 2124/4034/7256 2123/3608/5915 +f 3978/2478/5000 3976/4127/5000 3995/2889/5000 +f 4116/4191/4367 4114/4143/5277 4092/2089/4367 +f 3406/4020/6463 3390/3907/6295 3391/4202/6756 +f 4119/2012/4358 4131/2881/5136 4120/2022/5135 +f 3733/3134/6367 3732/2754/7145 3734/2753/6365 +f 2521/4056/6517 2501/4149/6658 2500/2654/4929 +f 3624/3195/7257 3622/3567/7258 3621/3565/5869 +f 2380/3605/5912 2438/3252/5519 2412/3242/5509 +f 2136/4259/7259 2141/3376/7040 2995/3753/6103 +f 1977/3728/4585 1984/3224/4585 1980/2256/4585 +f 3567/2167/4496 3463/2349/4661 3566/2348/4660 +f 2946/3772/26 2945/4239/26 2930/3585/26 +f 2406/2399/4711 2459/2826/5085 2465/2400/4712 +f 2047/2612/6503 1965/3739/6084 2055/3919/6308 +f 3724/3129/5388 3751/2467/6701 3725/4110/6603 +f 3670/2577/4862 3672/2509/4804 3671/4368/7167 +f 1972/3467/7260 2072/2508/7260 2073/4328/7260 +f 3711/3853/6217 3800/4186/6720 3712/3472/5761 +f 3759/2165/4336 3756/4245/4336 3763/3721/4336 +f 3554/3505/5794 3537/3621/5935 3555/3116/5374 +f 3784/2908/5162 3773/2056/6654 3774/2906/5160 +f 3208/4374/7185 3216/2919/5173 3315/4347/7085 +f 2112/3160/6995 2473/2986/5235 2430/4354/7106 +f 3769/4069/4336 3748/2550/4336 3770/2223/4337 +f 3481/3736/7261 3470/2554/4842 3479/3761/7143 +f 2252/3311/5579 2269/3788/6902 2254/3783/7262 +f 3882/2413/4722 3895/2946/5192 3894/2371/4685 +f 2899/2476/4775 2912/2475/4774 2911/3312/5580 +f 4390/4260/6878 4364/3213/5479 4389/3215/5481 +f 4008/3874/6294 4047/2127/4454 4007/3872/7263 +f 4321/3349/6538 4318/3348/6483 4319/3058/7159 +f 3048/3436/5722 3065/3446/5735 3079/3435/5721 +f 4196/2582/4865 4195/2584/4867 4197/3425/7117 +f 4320/2951/6536 4322/2950/7178 4323/3288/6537 +f 3349/2655/5601 3361/2722/7063 3363/3332/5602 +f 3723/3130/4336 3719/1986/4336 3721/1985/4336 +f 3258/4229/6802 3256/3618/5929 3257/2841/5928 +f 2577/3352/5624 2139/2407/7264 2457/3119/6798 +f 2382/3477/5767 2462/3390/5669 2406/2399/4711 +f 4314/2122/6725 4344/2123/7265 4312/4188/6723 +f 3775/4134/6633 3791/4140/6641 3761/4142/6643 +f 2078/2740/7266 2604/3992/7267 2605/3946/6353 +f 2991/4207/6761 2992/2975/6772 3000/4218/6779 +f 3316/4248/6856 3318/4235/6834 3317/2220/4543 +f 3568/2168/4497 3569/2717/4986 3570/2166/4495 +f 3945/2260/4580 3935/3060/5354 3936/2128/4455 +f 2646/4351/7092 2168/2588/6082 3015/2994/5243 +f 4072/2429/4735 4093/3487/7268 4091/3591/6771 +f 2153/3514/5807 2633/3330/7038 2915/3515/5808 +f 3301/3719/6058 3296/2290/4607 3284/3900/6282 +f 3043/4181/6715 3055/2693/4961 3047/2692/4960 +f 2623/3279/6385 2624/3963/6384 2622/3964/6387 +f 2143/3267/5536 2916/3170/5430 3011/3268/5537 +f 3215/3630/6119 3218/3843/6205 3214/3034/5286 +f 2323/3652/5971 2568/4232/6826 2319/4313/7010 +f 2064/2759/5024 2063/4150/6660 1973/1962/4315 +f 3040/3317/5585 3045/3037/5290 3042/2343/4655 +f 3044/2527/4820 3008/3231/5499 3043/4181/6715 +f 3294/4286/6934 3290/2625/4906 3309/4316/7013 +f 3780/2222/4545 3768/4144/7269 3769/4069/7095 +f 3134/2485/7087 3137/3904/6928 3135/3158/7087 +f 4030/2082/4418 4026/3204/5471 4027/3553/5857 +f 2748/2729/4998 2747/2728/4997 2749/4088/6568 +f 4121/2816/5075 4138/3576/5885 4146/3636/5949 +f 2214/3004/5254 2215/3006/5256 2213/4189/6731 +f 2916/3170/5430 2145/2721/5864 2615/3958/7270 +f 3833/4192/6741 3872/4365/7213 3842/2396/6739 +f 3934/3854/6218 3932/2325/5354 3937/4355/7107 +f 3161/3379/5655 3178/4325/7050 3198/3328/5597 +f 4288/4168/6774 4295/4167/6825 4298/2810/6825 +f 2550/2326/4640 2536/2675/4944 2573/2677/4946 +f 3381/2451/5595 3382/2043/6314 3380/2042/5595 +f 3743/3185/5450 3722/3183/5447 3741/3511/6820 +f 3670/2577/4862 3593/3706/6041 3693/3667/5989 +f 2294/3819/6180 2293/3424/7224 2186/4078/6551 +f 2117/3344/7066 2126/4337/7067 2125/4114/6607 +f 3537/3621/6810 3523/2585/6728 3538/3622/5936 +f 3041/3795/6148 3043/4181/6715 3047/2692/4960 +f 2182/3520/5813 2176/2591/4872 2487/2590/4871 +f 2327/3937/6340 2561/4179/6713 2563/2339/4651 +f 2776/2037/4381 2796/4041/6492 2763/3686/6013 +f 4077/2065/5250 4076/2837/5251 4075/3391/6948 +f 3874/3431/5716 3887/3402/5683 3898/3401/5682 +f 2760/2463/4765 2761/2038/4382 2763/3686/6013 +f 3795/2794/5055 3785/2907/5161 3798/2792/5053 +f 3824/1983/4334 3923/3142/5404 3924/3988/6424 +f 4141/3278/5546 4134/2874/5545 4133/3478/6479 +f 3200/2680/7271 3090/4253/7271 3084/4023/7271 +f 2515/3582/5893 2517/3584/5895 2508/3190/5457 +f 3764/4141/7272 3790/4386/7273 3765/2755/6371 +f 3904/2629/4910 3911/2628/4909 3903/2788/6727 +f 3492/2106/4388 3516/2144/4388 3494/2107/4388 +f 2316/3617/5927 2314/2997/5246 2357/4079/6552 +f 3814/2864/7274 3706/3839/7274 3705/4315/7274 +f 3352/2656/6406 3373/3030/5821 3353/2665/4934 +f 2604/3992/7267 2603/3947/6354 2605/3946/6353 +f 2750/1968/4321 2733/2560/4848 2844/4366/7154 +f 4128/2566/4852 4159/3690/6021 4160/4288/6943 +f 3895/2946/6655 3883/3950/6657 3896/2706/4975 +f 4115/2013/4359 4114/4143/7275 4128/2566/4852 +f 3572/2337/4532 3577/2595/4532 3573/3547/4531 +f 3356/2237/5259 3357/4335/7247 3347/3007/5257 +f 3129/3146/5409 3126/3672/5995 3127/2215/5407 +f 2959/4362/7168 2957/3892/6270 2958/2783/5044 +f 3388/3448/4755 3385/3491/4755 3390/3907/4755 +f 3098/2426/7235 3088/3180/7236 3203/4193/7236 +f 2043/2945/5191 2051/3895/6273 2050/3444/5733 +f 2746/2473/4772 2841/4087/6567 2840/3610/5917 +f 3690/3434/5719 3691/3308/5576 3692/4264/6886 +f 2812/2786/5047 2813/3881/6255 2807/3620/5934 +f 3513/3168/4388 3505/2614/4387 3503/2047/4388 +f 3460/2214/4532 3466/2209/4532 3464/2546/4838 +f 3278/2116/4445 3217/2218/4540 3279/3080/5335 +f 2079/2741/7276 2075/3682/7277 2076/3177/7278 +f 4342/4121/4422 4345/3830/4422 4346/3829/6361 +f 2877/2342/4654 2876/3924/6320 2875/4126/6622 +f 4161/4136/4683 4054/2769/7279 4055/3744/4683 +f 2809/2140/4468 2993/4122/7148 2988/2784/5045 +f 2816/3868/6237 2811/2139/4467 2803/3869/6238 +f 4345/3830/6194 4348/4216/6985 4360/2716/4985 +f 2328/3983/6415 2216/4304/6979 2358/1975/4328 +f 3419/2019/4365 3424/3295/5561 3418/2937/5185 +f 3084/4023/4731 3090/4253/6864 3093/3406/5686 +f 3935/3060/6803 3944/3590/6803 4052/3592/6803 +f 2576/4246/26 2375/4289/26 2372/4269/26 +f 2484/4324/7045 2485/2310/4627 2486/2277/4594 +f 3222/3225/5491 3230/4147/7127 3259/3226/5492 +f 2250/2923/5175 2266/3851/6214 2268/2924/5176 +f 2150/3282/5988 2494/3666/5987 2151/4330/7056 +f 3633/2999/5248 3648/2304/4621 3647/3000/5249 +f 2042/3669/5991 2043/2945/5191 2025/2944/5190 +f 2495/2926/5178 2496/4350/7090 2487/2590/4871 +f 2660/4382/7237 2659/3220/5486 2849/2871/5127 +f 3082/2685/4953 2600/2683/6621 2107/2985/7280 +f 3209/3939/7084 3208/4374/7185 3311/3920/6309 +f 3666/2998/6913 3647/3000/5574 3582/2548/5573 +f 2542/3388/5666 2558/4037/6487 2559/4003/6446 +f 2143/3267/7252 2142/4371/7281 2614/3959/6377 +f 2221/2495/4792 2220/4387/7282 2223/4364/7146 +f 2106/3793/7283 2105/2335/4649 2107/2985/7284 +f 2160/3658/6095 2638/3614/7253 2159/3153/5414 +f 4367/2206/4530 4366/2603/4884 4376/2602/4883 +f 2786/4251/6861 2787/2669/4940 2791/2877/5133 +f 2507/3743/6088 2508/3190/5457 2480/3676/6000 +f 3025/2405/4717 3026/2455/4757 3079/3435/5721 +f 2475/4209/6765 2454/3117/5375 2451/3292/5558 +f 3816/4217/6776 3713/2862/6777 3708/3627/6776 +f 3286/2147/4475 3295/2149/4477 3302/2289/4606 +f 3608/2200/6286 3610/2688/4956 3609/2687/4956 +f 2083/2274/4591 2603/3947/6432 2699/2272/4589 +f 2307/3987/7285 2479/2571/7130 2588/4082/6555 +f 4189/2351/4517 4188/2121/4517 4186/2832/4517 +f 4281/3043/5296 4182/3088/5661 4247/2765/7165 +f 4161/4136/4683 4055/3744/4683 4162/3416/4683 +f 4380/2521/4814 4381/2520/4813 4383/2761/5026 +f 3452/2681/4948 3565/2297/4614 3461/2350/4662 +f 2995/3753/6103 2999/3752/6102 2136/4259/7259 +f 4140/3321/5590 4063/4244/6857 4131/2881/6945 +f 3688/2596/4877 3589/3323/6507 3588/3863/6228 +f 4041/3562/5865 4042/3563/5866 3941/3757/6108 +f 3809/3952/6362 3714/3112/5369 3709/3645/5961 +f 2200/3662/5983 2278/2530/5340 2201/3084/5339 +f 2555/3139/5401 2546/3533/5829 2554/3315/5583 +f 4228/3596/4517 4224/3229/4517 4194/2085/4517 +f 2951/4201/6755 2985/4166/6692 2953/4165/6691 +f 3031/3479/5769 3071/4106/6593 3036/2859/5116 +f 3934/3854/7157 4035/3914/6303 4036/4367/7158 +f 2951/4201/6764 2953/4165/7172 2952/4208/6762 +f 3643/3649/4524 3612/2686/4524 3641/4032/4524 +f 2265/4008/7134 2267/3791/7286 2266/3851/6214 +f 3941/3757/5355 3931/3976/5355 3939/3014/5354 +f 3678/3216/5482 3681/3218/5484 3590/3639/5953 +f 4117/2875/4367 4113/2468/4367 4082/2364/4367 +f 4366/2603/6991 4354/2205/4529 4355/3694/6027 +f 2897/2477/4776 2896/1971/4324 2850/2805/5065 +f 2890/2957/5204 3029/3100/5357 3032/3099/5356 +f 2243/3049/5304 2440/4238/6841 2439/3251/5518 +f 2488/4312/7005 2151/4330/7056 2491/3387/5665 +f 3585/2173/4434 3589/3323/4434 3583/2174/4434 +f 2518/4047/6999 2576/4246/6853 2575/4267/6891 +f 2391/4019/6461 2435/3956/6369 2434/3518/5811 +f 2447/4195/6744 2247/3653/5972 2249/3302/5568 +f 4234/3236/4517 4231/2767/5503 4207/2846/5503 +f 2240/4004/6447 2438/3252/5519 2380/3605/5912 +f 2793/2878/5134 2788/2668/4939 2789/2690/4958 +f 2425/2091/4424 2423/3606/5913 2424/3149/5410 +f 2990/4164/6688 2983/4058/6782 2946/3772/6120 +f 4255/2598/4879 4254/4061/6522 4262/2597/4878 +f 2009/3275/4585 2011/2062/4585 2017/3273/4585 +f 3490/2847/5104 3492/2106/4435 3491/2105/4435 +f 3581/2104/7019 3682/3306/5572 3683/2303/4620 +f 3459/3758/6109 3460/2214/4532 3464/2546/4838 +f 2545/3698/6031 2493/4277/6915 2546/3533/5829 +f 2273/2482/4781 2274/3437/5723 2271/2483/4782 +f 3995/2889/5142 3996/4266/7003 4005/3439/5725 +f 2615/3958/7270 2617/3169/5428 2916/3170/5430 +f 2407/2401/4713 2465/2400/4712 2466/3025/5278 +f 2085/2844/5100 2083/2274/7181 2087/2842/5098 +f 4264/3305/5571 4179/2880/6778 4266/3954/6364 +f 2969/3558/5863 3076/2611/4891 2956/3556/5861 +f 3852/3286/5553 3851/4375/7287 3853/3285/5551 +f 4142/4033/6481 4062/3073/5328 4143/3075/5330 +f 2971/2934/26 2972/3896/26 2933/2969/26 +f 3988/4356/5000 3957/3428/5000 3985/2731/5000 +f 2784/3371/5647 2771/2574/4859 2769/3072/5327 +f 2045/3573/7142 2046/3572/5880 2024/4282/7153 +f 2132/3291/6873 2129/2801/5061 2131/2709/7288 +f 2927/3516/5809 2915/3515/5808 2926/3535/5832 +f 3298/3932/6330 3299/4163/6687 3297/3930/6328 +f 2350/2259/4579 2168/2588/6247 2526/3767/6115 +f 3244/2623/4351 3272/4281/4351 3242/2159/4351 +f 3849/3809/6423 3852/3286/6496 3835/2381/6421 +f 2174/4161/6683 2643/4091/6571 2173/4162/6684 +f 3449/4334/7101 3448/4236/7101 3339/2002/7101 +f 2470/4353/7105 2472/4388/7289 2471/2079/4415 +f 2696/2428/4734 2097/2712/6073 2099/2077/4732 +f 3831/1991/4690 3823/2649/4688 3824/1983/4688 +f 2605/3946/6353 2079/2741/7290 2078/2740/7266 +f 2366/4290/26 2369/4389/26 2582/2095/512 +f 2432/2411/4720 2121/2410/4719 2119/3607/7291 +f 3814/2864/7274 3813/3212/7274 3706/3839/7274 +f 2388/3166/5424 2387/3165/5423 2386/2450/6748 +f 4106/4296/4367 4110/3147/4367 4105/2836/4367 +f 4290/2809/5068 4386/2811/5070 4361/3057/5313 +f 4230/3595/6872 4229/4303/6976 4255/2598/4879 +f 2044/3094/5350 2043/2945/5191 2050/3444/5733 +f 4303/3276/5542 4312/4188/7292 4343/4357/7161 +f 2566/3735/6076 2320/2704/4973 2325/3933/6332 +f 3728/3938/6341 3730/4180/6821 3729/2910/6821 +f 4218/3637/5950 4219/3272/6695 4220/3940/6346 +f 2720/3024/5275 2715/3135/5396 2132/3291/7129 +f 4015/3009/5261 4034/3913/6302 4032/3008/5260 +f 4152/3032/5284 4150/2368/4681 4151/3033/5285 +f 2154/4301/6973 2153/3514/7138 2489/4275/6912 +f 2858/3997/6440 2855/3971/6395 3035/3039/5292 +f 3589/3323/6507 3690/3434/5719 3584/3322/7081 +f 4317/4036/7121 4315/4035/6653 4304/2088/5543 +f 4250/2852/5108 4237/2853/5110 4249/3384/5839 +f 4010/3091/5347 4019/4252/6862 4009/3646/5962 +f 3035/3039/5292 3073/3433/5718 3033/3998/6441 +f 3096/2424/6160 3185/2154/4482 3184/2153/4481 +f 3173/3615/5925 3174/3021/7220 3144/2068/5923 +f 2241/3495/5784 2437/3604/5911 2239/2983/5230 +f 3397/4111/6983 3410/4086/6982 3389/2453/6997 +f 1982/2866/5122 2003/4067/7222 2001/3650/5969 +f 2442/3175/5436 2244/3048/5303 2245/3412/5696 +f 1964/3740/6085 1961/2534/4827 2060/2928/5180 +f 2128/4112/6605 2125/4114/6607 2126/4337/7067 +f 3001/4284/6931 2161/3657/7293 2642/3805/6164 +f 2094/2914/5527 2607/2886/5139 2608/4265/6887 +f 4229/4303/4517 4230/3595/4517 4196/2582/4517 +f 3472/3687/6015 3487/2490/6927 3489/2848/6014 +f 3946/3510/5000 3949/3703/5000 3954/4071/5000 +f 4139/2443/4747 4158/2442/4746 4159/3690/6021 +f 3650/2100/4431 3685/2099/4430 3649/2302/4619 +f 3943/3203/5470 4032/3008/5260 4033/3915/6304 +f 2249/3302/5568 2247/3653/5972 2266/3851/6214 +f 4296/1978/6169 4294/1977/6030 4379/2522/4815 +f 3018/3806/6165 2174/4161/6721 3017/3807/6166 +f 2625/3115/6386 2147/2227/4550 2624/3963/6384 +f 3721/1985/5448 3736/2067/4404 3738/2437/5449 +f 4037/2819/5078 3933/3012/5265 3934/3854/7157 +f 4279/2850/5106 4178/4370/7173 4177/3086/6710 +f 2709/3784/6135 2810/2138/4466 2808/2504/4801 +f 3095/2790/4731 3092/3542/4731 3091/3943/4731 +f 3483/2555/4843 3470/2554/4842 3481/3736/7261 +f 4171/3936/6339 4176/2779/5040 4276/3066/5321 +f 2054/3445/5734 1974/3466/5755 1971/3465/5882 +f 2979/4200/26 2980/4199/26 2935/4027/512 +f 4070/2431/5737 4086/4274/6904 4084/3010/6812 +f 2304/3503/5792 2303/3164/5422 2214/3004/5254 +f 3406/4020/6463 3391/4202/6756 3407/3097/5353 +f 4174/4159/5364 4282/3711/5364 4284/4297/7294 +f 3607/4336/7184 3596/4294/7000 3605/2737/5005 +f 4053/2323/4639 3932/2325/4639 4049/4390/4639 +f 2052/2109/4438 2039/2108/4437 2038/2645/5855 +f 3826/2984/5231 3930/4391/5231 3929/2651/5232 +f 3937/4355/7107 4033/3915/6304 4035/3914/6303 +f 2377/4392/26 2575/4267/26 2372/4269/26 +f 3904/2629/7295 3903/2788/5049 3885/2787/5048 +f 2106/3793/6705 2107/2985/7296 2600/2683/4950 +f 2897/2477/4776 2898/1972/4325 2896/1971/4324 +f 2460/3857/7249 2461/3482/6664 2459/2826/5085 +f 2521/4056/6517 2518/4047/6504 2503/3574/5883 +f 3653/2151/4479 3640/2150/4478 3654/3309/7297 +f 2009/3275/7082 2010/2060/4398 2011/2062/4398 +f 3939/3014/5267 4040/3013/5266 4041/3562/5865 +f 2402/4343/7075 2400/2798/5058 2403/3564/5867 +f 3456/3917/6306 3562/2114/4443 3455/4393/7298 +f 3512/3167/4387 3508/2383/4388 3505/2614/4387 +f 3059/2126/4453 3067/2125/4452 3066/3392/5673 +f 3189/3022/5273 3087/4137/6946 3191/3817/6178 +f 1975/2239/4561 1974/3466/5755 2053/3741/6086 +f 3648/2304/4621 3683/2303/4620 3682/3306/5572 +f 2961/2912/5166 2177/4153/7042 3020/4021/6464 +f 3885/2787/5048 3905/2305/6533 3904/2629/7295 +f 2400/2798/5058 2399/2797/5057 2403/3564/5867 +f 3260/3145/4351 3232/4148/4351 3266/3051/4351 +f 4305/2087/5198 4319/3058/5314 4317/4036/7121 +f 2077/3223/6009 2076/3177/7174 2075/3682/6007 +f 3247/3699/6033 3248/3193/5460 3249/3194/5461 +f 4228/3596/6860 4230/3595/6872 4256/2027/6871 +f 3479/3761/7143 3469/2939/7078 3477/3762/7080 +f 2251/2747/5015 2263/3430/6462 2396/3551/5854 +f 3617/2432/4524 3616/2563/4524 3645/4012/4524 +f 3323/4314/7012 3321/3507/5796 3212/3506/5795 +f 2298/2734/5002 2389/3955/6368 2295/2962/6510 +f 2503/3574/5883 2507/3743/6088 2483/3513/5806 +f 3817/3941/6347 3818/2376/4690 3820/2375/4689 +f 2261/3207/5474 2264/4342/7212 2211/3208/5475 +f 2637/3678/6003 2161/3657/7293 2926/3535/5832 +f 3642/4230/5462 3608/2200/4524 3638/2199/4524 +f 2773/3235/5502 2774/3530/5828 2775/4302/6975 +f 4109/3148/6901 4125/4098/6900 4108/3361/5636 +f 2565/3238/5505 2567/3314/5582 2324/3237/5504 +f 3320/2118/4447 3319/2217/4539 3278/2116/4445 +f 2922/3500/5789 2925/3878/6252 3054/3949/6356 +f 2423/3606/5913 2425/2091/4424 2447/4195/6744 +f 2496/4350/7090 2495/2926/5178 2549/2925/5177 +f 2389/3955/6368 2391/4019/6461 2392/4327/7299 +f 2392/4327/7299 2384/3836/7077 2389/3955/6368 +f 4036/4367/7158 4034/3913/6302 4017/2817/5076 +f 2630/4204/6758 2148/3040/5874 2628/3569/5876 +f 2254/3783/7262 2255/3781/7300 2251/2747/5015 +f 2197/3802/6159 2273/2482/6162 2198/3803/6161 +f 2057/3417/5699 2058/2927/5179 2059/2929/5181 +f 2584/3867/26 2583/3748/26 2373/4311/26 +f 3704/3474/5763 3803/3262/5528 3703/3864/6229 +f 3761/4142/4336 3728/3938/4337 3760/3760/4336 +f 2719/2659/4931 2590/3493/5782 2718/2660/4932 +f 2418/3249/5516 2419/3120/5378 2425/2091/4424 +f 4014/2080/7177 4013/3628/6885 3997/3440/5726 +f 2950/3858/6221 2906/2075/4411 2903/3375/5651 +f 3356/2237/4559 3358/4185/7046 3357/4335/7064 +f 4360/2716/4985 4375/1994/4344 4384/2714/4983 +f 4240/3125/5852 4270/3723/6064 4272/3222/5489 +f 2432/2411/4720 2431/3151/5412 2422/3150/5411 +f 2319/4313/7010 2568/4232/6826 2571/2390/4702 +f 2854/3083/5338 2888/3481/5771 2826/4107/6594 +f 2775/4302/6975 2734/4234/6833 2735/2561/4849 +f 4395/2979/6693 4288/4168/6694 4393/2661/7301 +f 2385/3846/6209 2305/3005/5255 2388/3166/5424 +f 3583/2174/4434 3593/3706/6041 3592/3705/4434 +f 4384/2714/4983 4290/2809/5068 4385/2715/4984 +f 3243/2183/4904 3242/2159/4487 3241/2158/4487 +f 4389/3215/5481 4298/2810/5069 4299/4016/6935 +f 2664/4383/7238 2849/2871/5127 2663/2870/5126 +f 2835/4263/6883 2755/2701/4970 2836/2700/4969 +f 2179/3133/6742 2180/2501/7302 2963/2500/6566 +f 2720/3024/5275 2803/3869/6238 2721/4038/6488 +f 2716/4384/7243 2130/2802/7128 2715/3135/5396 +f 2263/3430/6462 2390/3745/7303 2391/4019/6461 +f 2124/4034/6482 2119/3607/7022 2718/2660/4932 +f 3716/3114/5371 3705/4315/5358 3714/3112/5358 +f 3537/3621/6810 3536/2460/7096 3522/4055/6811 +f 2687/4132/6631 2688/2143/4471 2798/3143/5405 +f 2563/2339/4651 2561/4179/6713 2557/4039/6489 +f 2799/2142/4470 2798/3143/5405 2688/2143/4471 +f 2053/3741/6086 2050/3444/5733 2051/3895/6273 +f 3785/2907/5161 3795/2794/5055 3784/2908/5162 +f 2513/3191/5458 2508/3190/5457 2517/3584/5895 +f 3875/4057/4554 3873/2397/4554 3870/1999/4554 +f 3613/2562/4850 3614/4064/4850 3616/2563/4851 +f 2926/3535/5832 2638/3614/5922 2160/3658/6002 +f 3011/3268/5537 2917/3063/5319 2913/3280/5548 +f 3622/3567/7258 3624/3195/7257 3623/3469/6956 +f 2612/4154/7304 2142/4371/7304 2175/3521/7304 +f 4172/3087/7305 4286/2568/7305 4181/2879/7305 +f 4049/4390/5354 4052/3592/5354 4053/2323/5354 +f 3716/3114/5371 3715/3908/6296 3713/2862/5942 +f 3945/2260/4580 4021/3944/6351 4023/2261/4581 +f 3885/2787/4554 3848/3889/4554 3880/4066/4554 +f 2900/2516/4809 2901/3313/5581 3024/1970/4323 +f 3083/3054/5310 3093/3406/5686 3194/4240/6846 +f 3719/1986/4336 3723/3130/4336 3718/2911/4336 +f 3909/2052/4393 3915/2051/4392 3908/3841/7071 +f 3272/4281/6926 3282/3810/6925 3283/3931/6909 +f 3673/2637/4915 3672/2509/4804 3670/2577/4862 +f 2435/3956/6369 2403/3564/5867 2399/2797/5057 +f 2955/4118/6611 3074/4255/6866 2954/4117/6610 +f 2402/4343/7075 2403/3564/5867 2404/3397/5868 +f 2358/1975/4328 2330/3076/5331 2328/3983/6415 +f 2474/4332/7057 2475/4209/6765 2451/3292/5558 +f 3418/2937/5185 3425/3716/6055 3417/2935/5183 +f 2787/2669/4940 2786/4251/6861 2690/3980/6409 +f 2321/2705/4974 2322/3731/6075 2248/3651/5970 +f 3679/3217/5483 3663/3410/5693 3664/3898/6280 +f 3317/2220/4543 3320/2118/4447 3276/2035/4541 +f 3309/4316/7013 3310/4285/6933 3294/4286/6934 +f 4297/4249/7112 4397/2663/7112 4398/4359/7112 +f 2986/3587/26 2947/3773/26 2930/3585/26 +f 2639/3154/5415 2158/3534/6411 2157/3152/5413 +f 4232/2606/5503 4233/2608/4517 4211/3456/5503 +f 2106/3793/7283 2104/2009/4355 2105/2335/4649 +f 2750/1968/4321 2737/1967/4320 2735/2561/4849 +f 2621/3695/7132 2623/3279/6385 2622/3964/6387 +f 3092/3542/4731 3085/2678/4731 3091/3943/4731 +f 4357/2940/4422 4356/2942/4422 4321/3349/4422 +f 3614/4064/4524 3646/3265/4524 3616/2563/4524 +f 3426/3876/6250 3428/2867/5123 3427/4178/6709 +f 2786/4251/6861 2785/2141/4469 2800/2636/4914 +f 1965/3739/6084 2046/3572/5880 1971/3465/5882 +f 3633/2999/5248 3666/2998/5247 3637/3131/5392 +f 2332/4007/6451 2335/2284/4601 2336/4394/7306 +f 2487/2590/4871 2494/3666/5987 2147/2227/7307 +f 2141/3376/7308 2137/2710/7309 2140/2408/7308 +f 2174/4161/6721 2645/4160/7136 3016/4187/6722 +f 3878/3187/5453 3891/3318/5586 3875/4057/6518 +f 2030/3994/6435 2059/2929/5181 2062/4173/6703 +f 1970/1963/4316 1968/2241/4316 1969/1961/4314 +f 3017/3807/6166 3063/3640/5954 3001/4284/6931 +f 2528/2676/4945 2532/4158/6674 2312/2748/5016 +f 3306/3644/5960 3289/2626/4907 3288/2179/6672 +f 3347/3007/5257 3357/4335/7247 3348/2657/7062 +f 3392/3449/4755 3358/4185/4755 3388/3448/4755 +f 2239/2983/5230 2238/2293/4610 2237/2295/4612 +f 3119/3532/7218 3117/2264/5963 3118/3701/6427 +f 4065/2071/4407 4157/4097/6582 4156/3196/5463 +f 2646/4351/7310 2647/4291/6951 2649/2589/4870 +f 4062/3073/5328 4057/3575/5884 4144/3074/5329 +f 2528/2676/4945 2536/2675/4944 2537/3247/5514 +f 3833/4192/4554 3840/2178/4554 3841/4237/5778 +f 2105/2335/5234 2103/2011/4616 2472/4388/7289 +f 2121/2410/7023 2130/2802/7128 2716/4384/7243 +f 3549/2719/4988 3529/2718/4987 3530/3536/5835 +f 2962/2782/5043 2966/2781/5042 2967/3460/5749 +f 2101/2299/7228 2103/2011/7311 2102/2010/7229 +f 4369/3201/5468 4358/2204/4528 4368/3287/5555 +f 2882/4130/6628 2884/3738/6083 2164/4109/6597 +f 4125/4098/6583 4124/4272/7312 4153/4171/6699 +f 3768/4144/4336 3752/2130/4336 3750/2132/4336 +f 2846/3888/6267 2654/4095/6578 2653/4395/7313 +f 3062/3136/5397 3072/3489/5779 3071/4106/6593 +f 3925/2499/4688 3930/4391/4688 3926/3546/4688 +f 3648/2304/4621 3635/2806/5671 3649/2302/4619 +f 2655/4152/6663 2654/4095/6578 2847/2497/4794 +f 3414/2197/7209 3445/3877/6251 3444/4329/7052 +f 2469/4214/6773 2468/2799/5059 2476/4176/6707 +f 3820/2375/4689 3917/2292/4609 3817/3941/6347 +f 2455/3353/5626 2452/3227/5494 2578/4320/7031 +f 4356/2942/4422 4353/3861/4422 4318/3348/4422 +f 3210/4146/6649 3209/3939/7084 3308/3643/5959 +f 2076/3177/6431 2074/3176/6719 2695/3338/5607 +f 3681/3218/5484 3680/3897/6279 3666/2998/6913 +f 4292/2604/4885 4302/2201/4525 4376/2602/4883 +f 4180/2891/5144 4173/3307/5575 4267/3953/6363 +f 2560/3077/5332 2523/3420/5702 2559/4003/6446 +f 4354/2205/4422 4328/3549/4422 4330/3357/6361 +f 4274/3067/5322 4242/2992/5241 4241/3126/5488 +f 3249/3194/6749 3269/3079/4351 3246/2622/4351 +f 2467/4210/6766 2475/4209/6765 2474/4332/7057 +f 3776/3759/6110 3763/3721/6060 3777/3720/6059 +f 3171/3599/6813 3172/3689/6020 3149/2631/5924 +f 3988/4356/5000 3985/2731/5000 3987/2733/5000 +f 4397/2663/7169 4300/4358/7169 4293/4015/7169 +f 3371/3028/5280 3370/2884/6390 3372/2931/5280 +f 3849/3809/6168 3851/4375/7287 3852/3286/5553 +f 2577/3352/512 2578/4320/26 2363/4326/26 +f 3365/2855/6838 3368/4319/7029 3367/2856/7029 +f 3658/2446/4750 3645/4012/6457 3646/3265/5531 +f 3504/3722/6486 3502/3765/7254 3503/2047/7210 +f 2083/2274/7314 2611/2273/7315 2610/3934/6334 +f 2811/2139/4467 2810/2138/4466 2804/4243/6851 +f 3900/1992/5694 3899/3403/5684 3887/3402/5683 +f 2128/4112/7316 2126/4337/7251 2119/3607/7291 +f 2112/3160/6995 2432/2411/4720 2114/3161/7317 +f 2967/3460/5749 2966/2781/5042 2965/2609/4889 +f 3350/4029/4755 3352/2656/4755 3349/2655/4755 +f 3398/2514/5888 3419/2019/4365 3418/2937/5185 +f 2793/2878/5134 2794/3671/5993 2792/2423/4730 +f 2809/2140/4468 2816/3868/6237 2993/4122/7148 +f 3148/3710/4406 3149/2631/4406 3114/2630/4406 +f 2026/2667/4938 2021/2643/4920 2038/2645/4922 +f 2558/4037/6487 2542/3388/5666 2543/3685/6012 +f 2116/3356/5630 2113/3159/5417 2114/3161/5419 +f 3052/4170/6698 3007/3333/5603 3049/2959/5206 +f 3880/4066/4554 3848/3889/4554 3846/3105/4554 +f 2849/2871/5127 2659/3220/5486 2848/3123/5381 +f 3784/2908/5162 3794/3871/6240 3783/3870/6239 +f 3074/4255/6866 2952/4208/6762 2954/4117/6610 +f 2606/3729/6358 2075/3682/6357 2096/3692/6794 +f 3211/4182/4383 3220/3550/4383 3219/3718/6057 +f 3051/2958/5205 3055/2693/4961 3008/3231/5499 +f 2139/2407/7264 2141/3376/7318 2457/3119/6798 +f 4023/2261/4581 4022/4283/6930 4024/2262/4582 +f 3993/3732/5000 3957/3428/5000 3988/4356/5000 +f 2414/3603/5910 2413/3244/5511 2381/4219/6784 +f 2317/4305/6980 2266/3851/6214 2319/4313/7010 +f 1963/3488/7319 1972/3467/7319 2073/4328/7319 +f 3183/2695/4963 3168/3602/5908 3167/4074/6547 +f 3346/3404/4350 3337/2001/4350 3338/3814/4350 +f 3540/2621/4902 3550/2814/5073 3539/2960/5207 +f 2514/4268/7206 2516/3583/5894 2515/3582/5893 +f 4005/3439/6640 4044/3724/6067 4004/2890/6998 +f 4395/2979/7320 4396/4344/7320 4293/4015/7320 +f 2573/2677/4946 2572/3616/5926 2551/2327/4641 +f 4185/3421/6152 4199/3108/6151 4197/3425/5706 +f 3389/2453/6997 3410/4086/6982 3409/4333/7321 +f 3926/3546/5847 3930/4391/5847 3826/2984/5847 +f 3058/4022/6465 3048/3436/5722 2919/3042/5295 +f 4116/4191/4367 4092/2089/4367 4095/3486/4367 +f 3758/2163/6316 3718/2911/5165 3726/3751/6317 +f 4312/4188/7292 4303/3276/5542 4313/3277/5544 +f 4266/3954/6364 4254/4061/6522 4264/3305/5571 +f 3951/4044/6500 3975/3259/6733 3952/3704/6732 +f 3283/3931/6329 3282/3810/6170 3298/3932/6330 +f 2236/4377/7187 2237/2295/4612 2233/2294/4611 +f 3482/2763/6077 3484/2903/5156 3483/2555/5155 +f 3057/3501/5790 3056/3233/5501 3002/3232/5500 +f 2283/2357/4670 2279/4080/6553 2286/2358/4671 +f 2644/4380/7226 2645/4160/6682 2173/4162/6684 +f 2467/4210/6766 2402/4343/7075 2404/3397/5868 +f 2826/4107/6594 2888/3481/5771 2827/4030/6475 +f 3028/3393/5674 3027/2406/4718 3066/3392/5673 +f 3498/4287/4388 3517/2524/4388 3511/2523/4388 +f 2302/3594/5900 2303/3164/5422 2301/3502/5791 +f 3534/2146/4474 3545/3537/5837 3533/2169/4498 +f 3919/3458/5747 3891/3318/5586 3920/3457/5746 +f 3764/4141/7322 3791/4140/6955 3790/4386/7323 +f 4245/2849/5105 4246/2607/4887 4232/2606/4886 +f 3682/3306/5572 3647/3000/5574 3648/2304/4621 +f 2388/3166/5424 2386/2450/6748 2385/3846/6209 +f 3977/2921/6734 3979/2480/7215 3953/3702/7214 +f 3591/2511/4806 3671/4368/7167 3672/2509/4804 +f 3590/3639/4434 3587/3769/6785 3586/3409/5692 +f 2024/4282/4584 2019/2613/4585 1991/3107/4585 +f 2871/4024/6468 3039/4025/6469 2874/3316/5584 +f 3641/4032/4524 3610/2688/5462 3642/4230/5462 +f 2270/3804/6681 2318/2528/4821 2278/2530/4823 +f 4342/4121/7110 4341/3539/5840 4340/3541/5842 +f 3462/3912/6301 3547/2393/4705 3546/3538/5838 +f 2574/3747/26 2580/3253/26 2378/3255/26 +f 2115/3342/5614 2116/3356/5630 2118/3343/5615 +f 3097/2425/4731 3099/3179/5444 3098/2426/4731 +f 3851/4375/7287 3849/3809/6168 3850/3808/6167 +f 2877/2342/4654 3040/3317/5585 3042/2343/4655 +f 4307/2980/5227 4327/3548/7156 4325/3452/5740 +f 3822/3234/6290 3921/2372/4686 3827/1984/4335 +f 3856/3588/5778 3853/3285/4554 3888/3411/4554 +f 2247/3653/5972 2319/4313/7010 2266/3851/6214 +f 2828/3363/5638 2672/4396/7324 2671/4138/6635 +f 4108/3361/4367 4097/4228/5277 4100/2744/4367 +f 3314/4317/7014 3208/4374/7185 3315/4347/7085 +f 3846/3105/5845 3843/3545/5846 3844/2395/4707 +f 4296/1978/6169 4372/2941/7135 4378/3003/5253 +f 2795/3601/5905 2796/4041/6492 2794/3671/5993 +f 2830/2346/4658 2726/2345/4657 2848/3123/5381 +f 3866/2112/4507 3839/2231/6262 3865/4261/7233 +f 3917/2292/4609 3820/2375/4689 3914/2291/4608 +f 3451/2097/4553 3333/2230/4553 3447/3163/4553 +f 2309/2641/4918 2308/4348/7086 2529/2642/4919 +f 3787/3199/6268 3772/3181/5445 3771/3957/6370 +f 2736/2901/5154 2846/3888/6267 2733/2560/4848 +f 4080/2365/4678 4078/3001/5250 4077/2065/5250 +f 2670/4349/7089 2850/2805/5065 2895/2454/4756 +f 4196/2582/4865 4197/3425/7117 4198/4331/7117 +f 2179/3133/7325 2178/2933/6375 2180/2501/6966 +f 2474/4332/7057 2468/2799/5059 2402/4343/7075 +f 3211/4182/4383 3217/2218/4383 3213/2920/4383 +f 3677/4070/6543 3669/2620/4901 3668/3383/5659 +f 3068/3847/6210 3032/3099/5356 3067/2125/4452 +f 3302/2289/4606 3301/3719/6058 3221/3824/6187 +f 4304/2088/4422 4303/3276/4422 4309/2519/4422 +f 2184/3634/5947 2281/3816/6177 2287/3632/5945 +f 4346/3829/6193 4360/2716/4985 4361/3057/5313 +f 3009/2727/4996 3021/4028/6470 3020/4021/6464 +f 3407/3097/5353 3423/2283/4600 3406/4020/6463 +f 4297/4249/4329 4301/2202/4329 4300/4358/7326 +f 2022/2776/6248 2035/2541/4832 2020/2557/4845 +f 2733/2560/4848 2846/3888/6267 2845/4094/6576 +f 2118/3343/5786 2595/3326/5593 2594/3325/5592 +f 2147/2227/7307 2146/2720/4989 2487/2590/4871 +f 3057/3501/5790 2922/3500/5789 3054/3949/6356 +f 4152/3032/5284 4153/4171/6699 4123/3882/6256 +f 2735/2561/4849 2772/2575/4860 2775/4302/6975 +f 4199/3108/7116 4200/3026/7116 4198/4331/7117 +f 3253/3102/5325 3252/3069/5325 3254/2235/5930 +f 2698/3648/5967 2695/3338/5607 2797/3144/5406 +f 3498/4287/7097 3496/3335/5604 3495/3337/5606 +f 3316/4248/6856 3313/3887/6266 3314/4317/7014 +f 2383/3360/5634 2436/2840/5096 2415/4271/6898 +f 2482/3970/6394 2505/2386/4695 2483/3513/5806 +f 3010/4360/7118 2144/3266/5535 3011/3268/5537 +f 3588/3863/6228 3579/2103/4434 3578/2102/4433 +f 3034/3707/6044 3038/2526/4819 2863/3979/6405 +f 3280/3832/6196 3281/2828/6924 3268/3078/5333 +f 4302/2201/4525 4377/2203/4527 4368/3287/5555 +f 2326/3050/5305 2564/3140/5402 2565/3238/5505 +f 3205/3856/7099 3201/2679/7099 3085/2678/7099 +f 3341/2000/4350 3339/2002/4350 3336/2016/4350 +f 2627/3281/6391 2620/3696/6389 2626/3965/6388 +f 3000/4218/6779 2993/4122/7148 2816/3868/6237 +f 3427/4178/6709 3344/3405/5685 3426/3876/6250 +f 2358/1975/4328 2354/4339/7070 2355/4338/7069 +f 2108/3794/6147 2110/3852/7327 2109/4256/6867 +f 3058/4022/6465 2920/3581/5892 3059/2126/4453 +f 3024/1970/4323 3023/4233/6827 3079/3435/5721 +f 3653/2151/4876 3654/3309/5577 3589/3323/6507 +f 2829/2441/4745 2912/2475/4774 2897/2477/4776 +f 4246/2607/4887 4260/2966/5213 4259/2965/5212 +f 2725/2752/5020 2731/2751/5019 2767/3647/5966 +f 2415/4271/6898 2436/2840/5096 2437/3604/5911 +f 2611/2273/7315 2609/2915/6335 2610/3934/6334 +f 3957/3428/5711 3955/3427/5710 3985/2731/7035 +f 2105/2335/5234 2472/4388/7289 2473/2986/5235 +f 2389/3955/6368 2435/3956/6369 2391/4019/6461 +f 3058/4022/6465 3059/2126/4453 3066/3392/5673 +f 3943/3203/5470 4033/3915/6304 3937/4355/7107 +f 4388/3884/6261 4387/3056/5312 4386/2811/5070 +f 2775/4302/6975 2768/4213/6770 2732/4017/6460 +f 3267/2180/6749 3234/3018/4351 3236/4307/6749 +f 3455/4393/7298 3564/3905/6292 3452/2681/4948 +f 3631/2634/7328 3632/3184/7328 3604/4190/7328 +f 2637/3678/6094 2159/3153/5414 2636/4385/7245 +f 2969/3558/6080 2981/3737/6079 2980/4199/6753 +f 3986/3873/5000 3971/3524/5000 3999/3089/5000 +f 3159/2822/5081 3158/2249/6845 3194/4240/6846 +f 3873/2397/4709 3871/2691/4959 3870/1999/4349 +f 2144/3266/5535 2487/2590/4871 2143/3267/5536 +f 2728/2988/5237 2725/2752/5020 2766/2989/5238 +f 4034/3913/6302 4036/4367/7158 4035/3914/6303 +f 2981/3737/26 2984/4051/26 2928/4050/26 +f 2990/4164/6769 2710/4002/6445 2711/4001/6444 +f 4029/3205/5472 4026/3204/5471 4030/2082/4418 +f 2072/2508/4316 2071/2507/4316 2070/2987/4316 +f 3646/3265/4524 3614/4064/4524 3643/3649/4524 +f 4048/3593/5354 4052/3592/5354 4049/4390/5354 +f 3922/1982/4333 3923/3142/5404 3824/1983/4334 +f 3932/2325/5354 3940/2324/5354 3937/4355/7107 +f 2882/4130/6628 2880/2995/5244 3015/2994/5243 +f 2267/3791/6143 2265/4008/6453 2203/3792/6144 +f 3165/2839/5752 3164/2838/5094 3175/4242/6848 +f 2314/2997/5246 2316/3617/5927 2315/2996/5245 +f 1984/3224/4585 1983/2156/4484 1982/2866/5122 +f 3732/2754/4336 3730/4180/4337 3764/4141/4336 +f 4246/2607/4887 4234/3236/7231 4233/2608/4888 +f 3443/2900/5152 3442/3096/5352 3408/3095/5351 +f 2975/3559/26 2976/2974/26 2939/3715/26 +f 4030/2082/4418 4012/3523/6448 4013/3628/5943 +f 2343/4372/7180 2344/3240/5507 2342/3239/5506 +f 2290/3827/6191 2188/3828/6192 2189/3833/6197 +f 2748/2729/4998 2783/3496/5785 2769/3072/5327 +f 4251/4177/7024 4252/3927/7217 4236/2190/7033 +f 3743/3185/5803 3746/3092/7329 3745/3186/7329 +f 4020/3906/6293 4021/3944/6351 4008/3874/6294 +f 3324/3986/6419 3299/4163/6687 3325/2827/5086 +f 3994/3441/5000 3961/4276/5000 3959/3733/5000 +f 4344/2123/7265 4343/4357/7111 4312/4188/6723 +f 4252/3927/6325 4251/4177/6708 4264/3305/5571 +f 2808/2504/4801 2809/2140/4468 2807/3620/5934 +f 3087/4137/6946 3189/3022/5273 3188/3688/6019 +f 3020/4021/6464 2960/4323/7044 3009/2727/4996 +f 4062/3073/4408 4064/2579/6233 4060/3414/6726 +f 4007/3872/7263 4046/2129/4456 4006/4309/7021 +f 3310/4285/6933 3209/3939/7084 3311/3920/6309 +f 3890/3320/5588 3916/2403/4715 3889/2053/4394 +f 3066/3392/5673 3065/3446/5735 3058/4022/6465 +f 2849/2871/5127 2908/3991/6429 2907/2074/4410 +f 3027/2406/4718 3065/3446/5735 3066/3392/5673 +f 3112/2317/4406 3144/2068/4406 3110/2070/4406 +f 4311/3951/6644 4303/3276/5542 4343/4357/7161 +f 2281/3816/7198 2282/2356/4669 2286/2358/4671 +f 3695/2188/6101 3585/2173/6101 3697/2172/6101 +f 2078/2740/6430 2698/3648/5967 2697/3447/5736 +f 4310/3419/5701 4337/3613/7190 4335/2616/4897 +f 2723/3093/5349 2730/2954/5201 2727/3625/5940 +f 2446/3301/5567 2423/3606/5913 2447/4195/6744 +f 3268/3078/5333 3279/3080/5335 3280/3832/6196 +f 3998/3522/5000 3964/3910/5000 3997/3440/5000 +f 2599/2682/4949 2103/2011/4951 2102/2010/7330 +f 4254/4061/6522 4253/3926/6324 4265/3303/5569 +f 2503/3574/5883 2501/4149/6658 2521/4056/6517 +f 2707/2503/4800 2705/3683/6010 2706/3374/5650 +f 2216/4304/6979 2240/4004/6447 2358/1975/4328 +f 4052/3592/5354 4050/2417/5354 4051/2416/5354 +f 4059/2770/7188 4164/2580/7188 4058/2072/7188 +f 4349/2418/4422 4355/3694/4422 4336/2638/4422 +f 3544/2113/4834 3509/2544/4836 3524/2851/6038 +f 2322/3731/6075 2323/3652/5971 2248/3651/5970 +f 2530/3681/6006 2541/3680/6005 2540/3675/5999 +f 3760/3760/4336 3728/3938/4337 3759/2165/4336 +f 3134/2485/7087 3136/2484/6928 3137/3904/6928 +f 3454/2594/4532 3455/4393/4532 3453/2338/4532 +f 2983/4058/26 2982/3350/6896 2943/4052/26 +f 4112/2175/4367 4107/2835/4367 4076/2837/4367 +f 2481/3742/6087 2507/3743/6088 2480/3676/6000 +f 2153/3514/7138 2152/4397/7331 2488/4312/7005 +f 4103/4063/7017 4101/2742/6512 4074/2059/4397 +f 2327/3937/6340 2329/2341/4653 2243/3049/5304 +f 1963/3488/7319 2073/4328/7319 2069/2565/7332 +f 2431/3151/5412 2430/4354/7106 2417/4226/6797 +f 2764/3755/6106 2839/3611/5918 2838/4183/6716 +f 2532/4158/6674 2528/2676/4945 2537/3247/5514 +f 2907/2074/4410 2908/3991/6429 2909/3990/6428 +f 3466/2209/7008 3575/2605/7009 3457/2207/7009 +f 4355/3694/4422 4354/2205/4422 4333/3359/4422 +f 4006/4309/7021 4046/2129/4456 4045/3691/6022 +f 2078/2740/7333 2079/2741/7276 2076/3177/7278 +f 2094/2914/5527 2092/3261/5526 2086/2843/7334 +f 2276/3798/7151 2277/3800/7227 2271/2483/4782 +f 2451/3292/5558 2454/3117/5375 2136/4259/6960 +f 3338/3814/6175 3444/4329/7052 3346/3404/6918 +f 3261/2834/7335 3266/3051/5306 3291/2833/5092 +f 2243/3049/5304 2244/3048/5303 2441/3174/5435 +f 2465/2400/4712 2459/2826/5085 2477/2825/5084 +f 2015/3274/5764 2017/3273/6436 2031/3929/6327 +f 3415/2196/6249 3445/3877/6251 3414/2197/7209 +f 3367/2856/7029 3370/2884/6390 3369/3966/6390 +f 3984/4322/7336 3946/3510/5801 3954/4071/7337 +f 3662/3442/6478 3642/4230/6805 3663/3410/5693 +f 3386/2238/5258 3347/3007/5257 3355/4279/6919 +f 3832/1993/4690 3830/2650/4690 3831/1991/4690 +f 3156/3673/6686 3155/3509/6253 3193/3399/5680 +f 3877/2414/4554 3867/2111/5778 3864/2487/4554 +f 3789/3786/6372 3765/2755/6371 3790/4386/7273 +f 3725/4110/6603 3726/3751/4336 3724/3129/5388 +f 3834/2380/6879 3843/3545/6740 3845/3104/6970 +f 3872/4365/7150 3871/2691/4959 3873/2397/4709 +f 3512/3167/5426 3527/2298/5425 3526/2916/6849 +f 4166/3415/4409 4165/2581/4408 4164/2580/4409 +f 2233/2294/4611 2231/2332/4646 2232/2334/4648 +f 2434/3518/5811 2399/2797/5057 2420/3519/5812 +f 3343/2020/4366 3420/3577/7197 3421/2772/5035 +f 3747/2549/4840 3746/3092/7329 3748/2550/4841 +f 2492/4278/6916 2494/3666/5987 2548/2328/4642 +f 2913/3280/5548 2148/3040/5293 2918/3589/5897 +f 2476/4176/6707 2451/3292/5558 2121/2410/4719 +f 3880/4066/4554 3846/3105/4554 3879/3842/4554 +f 3299/4163/6687 3298/3932/6330 3325/2827/5086 +f 4017/2817/5076 3988/4356/7109 3987/2733/7007 +f 2061/2536/4829 2062/4173/6703 2059/2929/5181 +f 2183/3815/6176 2194/3812/6171 2282/2356/6173 +f 3857/2314/4554 3856/3588/5778 3874/3431/4554 +f 2798/3143/5405 2112/3160/6216 2687/4132/6631 +f 4227/3127/5385 4241/3126/5384 4242/2992/6993 +f 4278/2780/5041 4244/3061/5316 4277/2778/5039 +f 3580/2537/4434 3587/3769/6785 3590/3639/4434 +f 3479/3761/6112 3480/2764/6112 3482/2763/6077 +f 3140/2069/5798 3154/4273/7221 3155/3509/5799 +f 2848/3123/5381 2724/4373/7183 2905/4306/6986 +f 3714/3112/5358 3706/3839/5358 3709/3645/5358 +f 2326/3050/5305 2324/3237/5504 2244/3048/5303 +f 2734/4234/6833 2732/4017/6460 2736/2901/5154 +f 2170/2947/7225 2644/4380/7226 2171/4292/6952 +f 3959/3733/6978 3956/3429/5712 3957/3428/5711 +f 4248/2766/7164 4182/3088/5661 4249/3384/5660 +f 3643/3649/4524 3614/4064/4524 3612/2686/4524 +f 2868/4120/6613 2866/3978/6404 3038/2526/4819 +f 4172/3087/4924 4178/4370/6680 4174/4159/6680 +f 2473/2986/5235 2472/4388/7289 2470/4353/7105 +f 4223/2083/4419 4220/3940/6346 4219/3272/6695 +f 2119/3607/7291 2124/4034/7338 2128/4112/7316 +f 2741/2593/4874 2684/2592/4873 2683/4092/6573 +f 3977/2921/6734 3953/3702/7214 3952/3704/6732 +f 2361/3922/6315 2392/4327/7051 2390/3745/6090 +f 2817/2990/7339 2766/2989/5238 2687/4132/6631 +f 4258/4053/7223 4257/4211/6767 4268/2029/4373 +f 2952/4208/6762 3074/4255/6866 2949/4224/6793 +f 3538/3622/5936 3521/2586/6729 3539/2960/5207 +f 4226/4085/6562 4243/2991/6992 4244/3061/6563 +f 2134/3377/7193 2141/3376/7340 2140/2408/7194 +f 3147/3381/4406 3145/2757/4406 3129/3146/4406 +f 2074/3176/6719 2606/3729/6072 2696/2428/4734 +f 3626/2469/4769 3623/3469/6956 3624/3195/7257 +f 4287/2569/4924 4286/2568/4924 4282/3711/4924 +f 2862/3708/6045 2861/4115/6608 2859/3968/6392 +f 2350/2259/4579 2342/3239/5506 2345/3241/5508 +f 2132/3291/7129 2589/2711/5276 2720/3024/5275 +f 3791/4140/6955 3801/3473/5762 3790/4386/7323 +f 3362/2724/4993 3364/2513/5391 3363/3332/5391 +f 2575/4267/26 2377/4392/26 2371/3254/26 +f 2168/2588/4869 2646/4351/7310 2649/2589/4870 +f 2665/2440/4744 2906/2075/4411 2912/2475/4774 +f 2319/4313/7010 2571/2390/4702 2317/4305/6980 +f 3702/3763/5804 3701/3838/7341 3811/3764/5804 +f 4107/2835/4367 4106/4296/4367 4105/2836/4367 +f 2462/3390/7255 2382/3477/5767 2405/3845/6208 +f 2370/4270/512 2577/3352/512 2363/4326/26 +f 2754/3756/6107 2837/4084/6560 2751/2702/4971 +f 2161/3657/7293 3001/4284/6931 2926/3535/5832 +f 2293/3424/5705 2294/3819/7200 2284/2736/5004 +f 2443/3121/5379 2419/3120/5378 2442/3175/5436 +f 4010/3091/5347 4022/4283/6930 4019/4252/6862 +f 1972/3467/7260 1976/2506/7260 2072/2508/7260 +f 3034/3707/6044 2860/3709/6046 3033/3998/6441 +f 4219/3272/5541 4218/3637/6474 4190/3461/5750 +f 3451/2097/4350 3446/3162/4350 3450/2098/4350 +f 3341/2000/5153 3412/3298/5564 3338/3814/6175 +f 3026/2455/4757 3025/2405/4717 2895/2454/4756 +f 4128/2566/4852 4114/4143/7275 4116/4191/6875 +f 4353/3861/6226 4356/2942/5188 4373/3862/6227 +f 3318/4235/6834 3315/4347/7085 3319/2217/4539 +f 3023/4233/6827 3022/4363/7133 3078/2725/4994 +f 2828/3363/5638 2673/4099/6584 2672/4396/7324 +f 4285/4222/7166 4174/4159/7166 4284/4297/7166 +f 2988/2784/6616 2974/3351/5623 2987/2785/5622 +f 2818/3111/5368 2820/3432/5717 2821/4369/7171 +f 3953/3702/7214 3982/4231/7216 3954/4071/7337 +f 2238/2293/4610 2239/2983/5230 2437/3604/5911 +f 4037/2819/5078 4018/2818/5077 3933/3012/5265 +f 2301/3502/7342 2307/3987/7285 2588/4082/6555 +f 2254/3783/7262 2251/2747/5015 2252/3311/5579 +f 3774/2906/4336 3739/2435/4336 3772/3181/4336 +f 3247/3699/6033 3249/3194/5461 3246/2622/4903 +f 3316/4248/6856 3317/2220/4543 3275/2219/4542 +f 2501/4149/6658 2503/3574/5883 2504/2385/4694 +f 2580/3253/26 2575/4267/26 2371/3254/26 +f 2801/3373/5649 2773/3235/5502 2771/2574/4859 +f 3268/3078/4351 3272/4281/4351 3244/2623/4351 +f 3079/3435/5721 3065/3446/5735 3025/2405/4717 +f 3990/4005/6450 4000/3471/5760 3987/2733/7007 +f 4226/4085/6562 4227/3127/5385 4242/2992/6993 +f 3897/2708/4977 3924/3988/6424 3896/2706/4975 +f 3972/4045/6501 3950/2242/4562 3970/2244/4564 +f 4375/1994/4344 4374/3068/5323 4380/2521/4814 +f 2589/2711/5276 2136/4259/7259 2999/3752/6102 +f 2212/2750/5018 2357/4079/6552 2314/2997/5246 +f 2340/3364/5639 2332/4007/6451 2339/4072/6545 +f 3863/3189/5456 3864/2487/5455 3865/4261/6881 +f 3449/4334/7060 3345/2309/7060 3450/2098/7060 +f 4062/3073/4408 4063/4244/6233 4064/2579/6233 +f 2179/3133/26 2178/2933/26 2376/4379/26 +f 3080/2774/5037 3076/2611/4891 3021/4028/6470 +f 2042/3669/5991 2052/2109/4438 2053/3741/6086 +f 3209/3939/6119 3210/4146/6649 3207/3629/6119 +f 4328/3549/4422 4358/2204/4422 4326/3289/4422 +f 3068/3847/6210 3061/2124/4451 3069/3848/6211 +f 3995/2889/5000 3976/4127/5000 3996/4266/5000 +f 2785/2141/4469 2786/4251/6861 2790/3027/5279 +f 4309/2519/4422 4308/2518/7343 4307/2980/4422 +f 3605/2737/6285 3604/4190/6953 3606/2198/6285 +f 2083/2274/7344 2082/2456/4758 2084/3945/6505 +f 2924/3580/5891 2925/3878/6252 2921/3499/5788 +f 4172/3087/7305 4285/4222/7305 4286/2568/7305 +f 2327/3937/6340 2328/3983/6415 2561/4179/6713 +f 4356/2942/5188 4372/2941/5187 4373/3862/6227 +f 2440/4238/6841 2441/3174/5435 2416/3173/5434 +f 4094/3485/5775 4097/4228/6800 4095/3486/5776 +f 2261/3207/7055 2260/4196/7054 2264/4342/7054 +f 2452/3227/7137 2455/3353/5652 2454/3117/5375 +f 2724/4373/7183 2848/3123/5381 2726/2345/4657 +f 2368/2551/26 2581/3483/512 2369/4389/26 +f 2574/3747/6096 2510/3192/6098 2513/3191/6884 +f 2366/4290/26 2585/2094/26 2364/2777/26 +f 4144/3074/5329 4135/2978/6017 4143/3075/5330 +f 2745/2472/4771 2748/2729/4998 2749/4088/6568 +f 1961/2534/4827 1964/3740/4316 1962/2820/6472 +f 2670/4349/7089 2669/2803/5063 2850/2805/5065 +f 2531/3679/6004 2313/2749/5017 2312/2748/5016 +f 4153/4171/6699 4154/3031/5283 4155/4215/6775 +f 2333/2285/4602 2331/1974/4327 2334/1973/4326 +f 2086/2843/7334 2094/2914/5527 2608/4265/6887 +f 4181/2879/4924 4179/2880/4924 4182/3088/4924 +f 2775/4302/6975 2774/3530/5828 2688/2143/4471 +f 4094/3485/5775 4096/4227/6799 4097/4228/6800 +f 3859/2315/4554 3857/2314/4554 3881/2707/4554 +f 3465/3578/5889 3466/2209/4532 3467/2208/4531 +f 2569/3730/6074 2566/3735/6076 2554/3315/5583 +f 3742/3283/4336 3739/2435/4336 3774/2906/4336 +f 3409/4333/7321 3408/3095/5351 3389/2453/6997 +f 3621/3565/5869 3622/3567/7258 3620/3566/5870 +f 2248/3651/5970 2246/2703/4972 2321/2705/4974 +f 3859/2315/4554 3883/3950/4554 3862/3188/4554 +f 2009/3275/7082 2008/2155/7082 2010/2060/4398 +f 2257/2746/6128 2256/2745/6130 2208/3779/6129 +f 2880/2995/5244 2878/3923/6319 2879/2344/4656 +f 4057/3575/5884 4148/3156/5416 4147/2367/4680 +f 3501/2697/4967 3500/2045/4966 3503/2047/7210 +f 2923/3138/5399 3060/3137/5398 2921/3499/5788 +f 4230/3595/4517 4194/2085/4517 4196/2582/4517 +f 3637/3131/4524 3606/2198/4524 3604/4190/4524 +f 3969/2271/5000 3966/3942/5000 3999/3089/5000 +f 3235/3017/5268 3236/4307/5268 3234/3018/5269 +f 2242/3250/5517 2438/3252/5519 2216/4304/6979 +f 4059/2770/4409 4065/2071/4407 4061/2771/5034 +f 3899/3403/7211 3831/1991/4341 3898/3401/6876 +f 2205/3775/6124 2211/3208/5475 2264/4342/7212 +f 2802/4054/6513 2686/2953/5200 2721/4038/6488 +f 2430/4354/7106 2413/3244/5511 2428/3243/5510 +f 3464/2546/4838 3556/2812/5071 3557/2545/4837 +f 3001/4284/6931 3007/3333/5603 3052/4170/6698 +f 2141/3376/7308 2136/4259/7345 2137/2710/7309 +f 3155/3509/6253 3154/4273/6903 3190/3020/5271 +f 4149/2366/4679 4146/3636/5949 4147/2367/4680 +f 3061/2124/4451 3068/3847/6210 3067/2125/4452 +f 2197/3802/6159 2274/3437/7195 2273/2482/6162 +f 3937/4355/7107 4035/3914/6303 3934/3854/7157 +f 2829/2441/4745 2897/2477/4776 2850/2805/5065 +f 3033/3998/6441 3073/3433/5718 3004/4221/6790 +f 3034/3707/6044 3033/3998/6441 3004/4221/6790 +f 4394/2662/4329 4398/4359/4329 4397/2663/4329 +f 3200/2680/7271 3202/4194/7346 3090/4253/7271 +f 4395/2979/7320 4293/4015/7320 4295/4167/7320 +f 3251/3070/4351 3253/3102/4351 3263/2033/4351 +f 3906/2402/7123 3905/2305/6533 3880/4066/6532 +f 3487/2490/4789 3490/2847/5104 3489/2848/5104 +f 2202/3790/6142 2268/2924/6138 2267/3791/6143 +f 3593/3706/6041 3671/4368/7167 3591/2511/4806 +f 2777/3293/5559 2794/3671/5993 2796/4041/6492 +f 2697/3447/5736 2778/2971/5218 2700/3269/5538 +f 2145/2721/4990 2143/3267/5536 2487/2590/4871 +f 2283/2357/4670 2280/3085/7347 2279/4080/6553 +f 2613/2502/4799 2181/2913/5167 2963/2500/4797 +f 4145/3635/5948 4057/3575/5884 4147/2367/4680 +f 2924/3580/5891 2919/3042/5295 2927/3516/5809 +f 2481/3742/6087 2540/3675/5999 2482/3970/6394 +f 2986/3587/6556 2951/4201/6755 2948/4083/6557 +f 4124/4272/7312 4123/3882/6256 4153/4171/6699 +f 2420/3519/5812 2399/2797/5057 2401/3526/5820 +f 2853/2956/5203 2852/2674/4943 2892/3975/6400 +f 2832/4081/6554 2703/3995/6437 2759/3700/6034 +f 3178/4325/7050 3197/2823/5082 3198/3328/5597 +f 2219/3389/5668 2220/4387/7282 2221/2495/4792 +f 3175/4242/6848 3199/3464/5753 3165/2839/5752 +f 4351/3497/6743 4361/3057/5313 4350/2419/4726 +f 2781/2422/4729 2790/3027/5279 2792/2423/4730 +f 4318/3348/6483 4316/3967/6484 4315/4035/6484 +f 2823/2050/4391 2822/4345/7083 2901/3313/5581 +f 3993/3732/7348 4016/4184/7119 3994/3441/5727 +f 2863/3979/6405 2862/3708/6045 3034/3707/6044 +f 2418/3249/5516 2431/3151/5412 2417/4226/6797 +f 2528/2676/4945 2312/2748/5016 2314/2997/5246 +f 2916/3170/5430 2914/3062/5317 3011/3268/5537 +f 4107/2835/5886 4138/3576/5885 4121/2816/5075 +f 3802/3263/5529 3775/4134/6633 3776/3759/6110 +f 4287/2569/5745 4283/4006/7349 4169/2892/5745 +f 3013/4223/6792 2949/4224/6793 3074/4255/6866 +f 3571/2462/4764 3552/2461/4763 3468/3697/6844 +f 3563/2917/5171 3455/4393/7298 3562/2114/4443 +f 3416/2868/6738 3401/2195/4521 3402/2885/6452 +f 3746/3092/7329 3743/3185/5803 3744/2055/5833 +f 4046/2129/4456 4007/3872/7263 4047/2127/4454 +f 3142/3508/4406 3143/2250/4406 3135/3158/5056 +f 3631/2634/7328 3604/4190/7328 3603/2739/7328 +f 3924/3988/6424 3897/2708/4977 3824/1983/4334 +f 3309/4316/7013 3308/3643/5959 3209/3939/7084 +f 3796/3903/6289 3795/2794/5055 3797/2793/5054 +f 3074/4255/6866 3077/2775/5038 3080/2774/5037 +f 2119/3607/7291 2126/4337/7251 2432/2411/4720 +f 2152/4397/7331 2148/3040/7199 2488/4312/7005 +f 2385/3846/6209 2397/4010/6455 2305/3005/5255 +f 2742/3754/6105 2754/3756/6107 2753/4076/6549 +f 2357/4079/6552 2356/2529/4822 2316/3617/5927 +f 3010/4360/7118 3011/3268/5537 3078/2725/4994 +f 3391/4202/4755 3383/4018/4755 3381/2451/4755 +f 2084/3945/7350 2083/2274/7314 2610/3934/6334 +f 3061/2124/4451 3060/3137/5398 3069/3848/6211 +f 2477/2825/5084 2467/4210/6766 2466/3025/5278 +f 3036/2859/5116 3071/4106/6593 3072/3489/5779 +f 3422/2807/5644 3394/3368/5643 3392/3449/5739 +f 3974/4128/6625 3976/4127/6624 3975/3259/5524 +f 2099/2077/6321 2601/3925/6323 2602/2427/6413 +f 2279/4080/6553 2280/3085/7347 2278/2530/4823 +f 2552/2392/4704 2553/2391/4703 2547/3527/5825 +f 3790/4386/7323 3801/3473/5762 3789/3786/6137 +f 2300/4009/6454 2299/2895/5147 2215/3006/5256 +f 2038/2645/4922 2039/2108/4936 2026/2667/4938 +f 2110/3852/6223 2109/4256/7351 2111/3860/6224 +f 2512/3450/5641 2479/2571/4856 2509/3367/5642 +f 3411/3297/6981 3397/4111/6983 3412/3298/7202 +f 3479/3761/6112 3482/2763/6077 3481/3736/6078 +f 2450/2412/4721 2401/3526/5820 2469/4214/6773 +f 2553/2391/4703 2554/3315/5583 2546/3533/5829 +f 2974/3351/26 2975/3559/26 2942/3561/26 +f 2895/2454/4756 2894/2404/4716 2828/3363/5638 +f 2548/2328/4642 2494/3666/5987 2549/2925/5177 +f 3726/3751/6317 3755/3294/6602 3757/2164/6318 +f 1999/3749/6850 1997/2255/4575 1981/2254/4574 +f 3126/3672/5995 3125/2216/7016 3127/2215/5407 +f 3889/2053/6519 3875/4057/6518 3890/3320/5588 +f 2147/2227/7307 2494/3666/5987 2149/3665/5986 +f 3030/3082/5337 3032/3099/5356 3068/3847/6210 +f 2798/3143/5405 3082/2685/4953 2112/3160/6216 +f 2107/2985/7280 2598/4068/6542 3082/2685/4953 +f 4094/3485/6944 4093/3487/7268 4072/2429/4735 +f 3262/2136/4351 3264/2135/4351 3258/4229/4351 +f 2124/4034/7352 2590/3493/6947 2123/3608/7175 +f 4319/3058/7159 4320/2951/6536 4321/3349/6538 +f 4263/3304/5570 4252/3927/6325 4264/3305/5571 +f 3419/2019/4365 3431/2018/4364 3424/3295/5561 +f 2535/2311/4628 2534/3248/5515 2536/2675/4944 +f 2985/4166/26 2986/3587/26 2929/3586/26 +f 3400/2936/4755 3368/4319/4755 3366/2515/4755 +f 2215/3006/5256 2305/3005/5255 2300/4009/6454 +f 2139/2407/26 2577/3352/512 2370/4270/512 +f 2805/4000/6443 2712/2899/5151 2711/4001/6444 +f 3162/3380/5656 3177/3211/5478 3176/3210/5477 +f 2443/3121/5379 2442/3175/5436 2245/3412/5696 +f 4300/4358/7326 4302/2201/4329 4293/4015/4329 +f 2403/3564/5867 2435/3956/6369 2409/3396/5677 +f 3167/4074/6547 3153/3531/5907 3152/2194/4520 +f 2448/4198/6747 2396/3551/5854 2433/3517/5810 +f 3745/3186/7329 3746/3092/7329 3747/2549/4840 +f 2803/3869/6238 2804/4243/6851 2802/4054/6513 +f 3803/3262/5528 3805/3770/6117 3703/3864/6229 +f 3412/3298/7202 3395/4257/7201 3413/3813/6949 +f 3452/2681/4948 3453/2338/4532 3455/4393/4532 +f 2099/2077/7246 2101/2299/7228 2100/4381/7230 +f 2144/3266/5535 2175/3521/5814 2182/3520/5813 +f 3833/4192/6741 3843/3545/6740 3834/2380/6879 +f 2891/4011/6456 2853/2956/5203 2892/3975/6400 +f 2286/2358/4671 2215/3006/5256 2299/2895/5147 +f 3187/3837/6201 3091/3943/6350 3087/4137/6946 +f 2746/2473/4772 2745/2472/4771 2749/4088/6568 +f 2712/2899/5151 2814/3880/6254 2714/2897/5149 +f 2112/3160/6216 2597/3455/5823 3081/3454/5742 +f 2721/4038/6488 2715/3135/5396 2720/3024/5275 +f 2648/2948/5194 3014/4352/7093 3012/2949/5195 +f 3358/4185/4755 3392/3449/4755 3360/2723/4755 +f 3578/2102/4433 3684/2976/5223 3588/3863/6228 +f 2429/2078/4414 2099/2077/4413 2395/2713/4982 +f 2819/4299/6971 2821/4369/7171 2820/3432/5717 +f 3354/2044/4386 3382/2043/4385 3355/4279/6919 +f 3722/3183/5447 3743/3185/5450 3723/3130/5389 +f 2066/2354/4667 2067/3552/5856 2036/2355/4668 +f 2581/3483/512 2582/2095/512 2369/4389/26 +f 2762/3038/5291 2834/4262/6882 2833/2464/4766 +f 3042/2343/4655 3045/3037/5290 3012/2949/5195 +f 3779/2904/5158 3768/4144/7147 3780/2222/4545 +f 3231/4042/6651 3234/3018/6830 3232/4148/6652 +f 4111/2176/4367 4112/2175/4367 4078/3001/4367 +f 3501/2697/7020 3502/3765/6114 3475/2288/4605 +f 4017/2817/5076 4034/3913/6302 4016/4184/6717 +f 4048/3593/5817 4049/4390/5817 3932/2325/5817 +f 3416/2868/6738 3402/2885/6452 3417/2935/5183 +f 2768/4213/6770 2775/4302/6975 2688/2143/4471 +f 3760/3760/4336 3759/2165/4336 3763/3721/4336 +f 2911/3312/5580 2910/2048/4389 2823/2050/4391 +f 2384/3836/6200 2359/3835/6199 2193/2963/5210 +f 2334/1973/4326 2358/1975/4328 2355/4338/7069 +f 4361/3057/5313 4360/2716/4985 4385/2715/4984 +f 4236/2190/4517 4235/4062/4517 4200/3026/4517 +f 2703/3995/6437 2704/3996/6439 2702/3385/5663 +f 2432/2411/4720 2116/3356/7141 2114/3161/7317 +f 3036/2859/5116 2886/2861/5118 2885/3480/5770 +f 2237/2295/4612 2217/3850/6213 2239/2983/5230 +f 2138/3370/6868 2136/4259/6868 2137/2710/6816 +f 3886/2789/5778 3850/3808/4554 3885/2787/4554 +f 2444/2090/4423 2445/2092/4425 2248/3651/5970 +f 3308/3643/5959 3304/4157/6671 3305/4145/6648 +f 2496/4350/7090 2494/3666/5987 2487/2590/4871 +f 4352/1996/7353 4353/3861/6226 4374/3068/6225 +f 2578/4320/26 2579/2553/26 2367/2552/26 +f 3563/2917/5171 3564/3905/6292 3455/4393/7298 +f 4269/4075/6548 4258/4053/7223 4268/2029/4373 +f 2947/3773/6121 2948/4083/6557 2949/4224/6829 +f 4203/2831/7098 4204/2212/6678 4205/3674/6677 +f 2435/3956/6369 2399/2797/5057 2434/3518/5811 +f 3907/4341/7122 3879/3842/6204 3908/3841/6203 +f 2213/4189/6731 2529/2642/4919 2308/4348/7086 +f 3401/2195/4521 3414/2197/4523 3396/3045/6950 +f 4231/2767/5503 4237/2853/4517 4205/3674/4517 +f 2624/3963/6384 2147/2227/4550 2619/2229/4552 +f 3048/3436/5722 3011/3268/5537 2913/3280/5548 +f 4156/3196/5463 4125/4098/6583 4155/4215/6775 +f 2760/2463/4765 2763/3686/6013 2762/3038/5291 +f 3494/2107/4388 3515/2171/4388 3495/3337/4388 +f 4182/3088/5661 4179/2880/7354 4264/3305/5571 +f 2294/3819/6180 2186/4078/6551 2185/3818/6179 +f 3047/2692/4960 3050/2694/4962 3046/3035/5288 +f 4136/2977/5224 4111/2176/4503 4113/2468/5225 +f 4301/2202/4329 4302/2201/4329 4300/4358/7326 +f 3552/2461/4763 3553/3504/5793 3465/3578/5889 +f 2308/4348/7086 2309/2641/4918 2214/3004/5254 +f 3901/3746/6093 3910/2361/4674 3832/1993/4343 +f 3499/2287/4604 3474/2286/4603 3497/4295/6958 +f 4041/3562/5865 3941/3757/6108 3939/3014/5267 +f 2920/3581/5892 2921/3499/5788 3059/2126/4453 +f 2131/2709/6817 2132/3291/7355 2133/3369/6818 +f 3777/3720/6059 3793/3264/5530 3776/3759/6110 +f 2255/3781/7300 2256/2745/5013 2251/2747/5015 +f 2016/2493/4585 2011/2062/4585 2013/2061/4585 +f 3049/2959/5206 3051/2958/5205 3053/3948/6355 +f 2815/3023/5274 2803/3869/6238 2720/3024/5275 +f 2699/2272/4589 2700/3269/5538 2611/2273/4590 +f 2158/3534/6411 2640/3982/6414 2157/3152/5413 +f 3883/3950/6657 3881/2707/4976 3896/2706/4975 +f 3506/2615/6063 3507/2382/7079 3476/2938/6061 +f 4090/2021/4684 4089/2370/4683 4091/3591/5899 +f 2524/3655/5974 2525/3660/5980 2162/3656/5975 +f 2485/2310/4627 2495/2926/5178 2486/2277/4594 +f 4343/4357/7111 4344/2123/7265 4342/4121/7110 +f 2413/3244/5511 2430/4354/7106 2381/4219/6784 +f 3821/2540/4831 3912/2306/4623 3913/4340/7072 +f 2490/3386/5664 2158/3534/6910 2489/4275/6912 +f 3174/3021/5272 3173/3615/5925 3189/3022/5273 +f 2375/4289/26 2586/3866/26 2376/4379/26 +f 2735/2561/4849 2734/4234/6833 2733/2560/4848 +f 3176/3210/5477 3094/3209/5476 3089/4241/6847 +f 3351/2854/5111 3369/3966/6407 3352/2656/6406 +f 3984/4322/7336 3954/4071/7337 3982/4231/7216 +f 4128/2566/4852 4127/2444/4748 4139/2443/4747 +f 2440/4238/6841 2416/3173/5434 2427/4225/6796 +f 2822/4345/7083 3074/4255/6866 3080/2774/5037 +f 3274/2137/4465 3291/2833/5092 3293/3928/6326 +f 2493/4277/6915 2547/3527/5825 2546/3533/5829 +f 2886/2861/5118 2827/4030/6475 2885/3480/5770 +f 3848/3889/4554 3885/2787/4554 3850/3808/4554 +f 2652/4155/6668 2846/3888/6267 2653/4395/7313 +f 3930/4391/4688 3925/2499/4688 3929/2651/4688 +f 2332/4007/6451 2337/4398/7356 2338/4073/6546 +f 3043/4181/6715 3008/3231/5499 3055/2693/4961 +f 2689/2670/4941 2691/3372/5648 2694/3989/6425 +f 3544/2113/4442 3561/2115/4444 3543/4133/6632 +f 2265/4008/6453 2277/3800/6156 2195/3799/6155 +f 2475/4209/6765 2452/3227/7137 2454/3117/5375 +f 2472/4388/7289 2103/2011/4616 2471/2079/4415 +f 2088/2967/5214 2090/2888/7357 2091/2887/5215 +f 2990/4164/6769 2711/4001/6444 2713/2898/5150 +f 2214/3004/5254 2303/3164/5422 2388/3166/5424 +f 3186/2791/5052 3171/3599/5903 3185/2154/4482 +f 2410/3395/5676 2403/3564/5867 2409/3396/5677 +f 2332/4007/6451 2336/4394/7306 2337/4398/7356 +f 2034/2760/5025 2033/3476/6967 2064/2759/5024 +f 4355/3694/4422 4333/3359/4422 4336/2638/4422 +f 3884/4096/6581 3901/3746/6750 3888/3411/5695 +f 3160/3355/6333 3179/2821/5080 3178/4325/7050 +f 2181/2913/6908 2180/2501/7358 2519/3865/7244 +f 2729/4013/6458 2905/4306/6986 2724/4373/7183 +f 2531/3679/6004 2530/3681/6006 2311/3124/5382 +f 2907/2074/4410 2819/4299/6971 2906/2075/4411 +f 2964/3459/6711 2979/4200/6754 2972/3896/6276 +f 3716/3114/5371 3713/2862/5942 3705/4315/5358 +f 3459/3758/6109 3559/2531/4824 3456/3917/6306 +f 3314/4317/7014 3311/3920/6309 3208/4374/7185 +f 3074/4255/6866 2822/4345/7359 2902/2049/4390 +f 2457/3119/5377 2135/3378/6959 2454/3117/5375 +f 2030/3994/6435 2029/3619/5933 2059/2929/5181 +f 3662/3442/5729 3677/4070/6543 3661/3382/5658 +f 2766/2989/5238 2767/3647/5966 2687/4132/6631 +f 4123/3882/6256 4110/3147/7053 4122/2815/5074 +f 2874/3316/5584 3039/4025/6469 3040/3317/5585 +f 2648/2948/6965 2170/2947/7225 2171/4292/6952 +f 2920/3581/5892 2924/3580/5891 2921/3499/5788 +f 2725/2752/5020 2728/2988/5237 2729/4013/6458 +f 2136/4259/6960 2138/3370/5646 2451/3292/5558 +f 2853/2956/5203 2891/4011/6456 2890/2957/5204 +f 2415/4271/6898 2437/3604/5911 2414/3603/5910 +f 2033/3476/6967 2032/3475/6659 2063/4150/6660 +f 3133/3157/4672 3132/2359/4672 3134/2485/7087 +f 2779/2421/4728 2792/2423/4730 2794/3671/5993 +f 2502/2387/4696 2501/4149/6658 2504/2385/4694 +f 3027/2406/4718 3028/3393/5674 2892/3975/6400 +f 4042/3563/5866 4001/2279/4596 4002/2224/4954 +f 2247/3653/5972 2447/4195/6744 2444/2090/4423 +f 3911/2628/4909 3910/2361/4674 3903/2788/6727 +f 2888/3481/5771 2885/3480/5770 2827/4030/6475 +f 2309/2641/4918 2306/2572/4857 2304/3503/5792 +f 2518/4047/7250 2521/4056/6517 2520/3993/6434 +f 2984/4051/26 2985/4166/26 2931/4049/26 +f 2110/3852/7149 2108/3794/7126 2473/2986/5235 +f 3946/3510/5801 3984/4322/7336 3955/3427/5802 +f 3309/4316/7013 3307/2627/4908 3308/3643/5959 +f 2732/4017/6460 2734/4234/6833 2775/4302/6975 +f 2976/2974/5221 2993/4122/6614 2992/2975/5222 +f 3436/2282/4599 3405/2160/4489 3406/4020/6463 +f 2534/3248/5515 2537/3247/5514 2536/2675/4944 +f 2609/2915/6335 2094/2914/7360 2086/2843/6336 +f 4063/4244/6857 4062/3073/5328 4142/4033/6481 +f 3644/4104/4524 3617/2432/4524 3645/4012/4524 +f 3632/3184/4524 3633/2999/4524 3604/4190/4524 +f 3032/3099/5356 3030/3082/5337 2889/3081/5336 +f 4290/2809/6774 4288/4168/6774 4298/2810/6825 +f 2716/4384/7243 2718/2660/4932 2121/2410/7023 +f 2092/3261/5526 2093/3260/5525 2090/2888/5141 +f 2531/3679/6004 2537/3247/5514 2541/3680/6005 +f 3892/3911/7196 3920/3457/5746 3891/3318/5586 +f 2557/4039/6489 2543/3685/6012 2544/3684/6011 +f 3020/4021/6464 3075/2610/4890 2959/4362/7168 +f 2390/3745/7303 2392/4327/7299 2391/4019/6461 +f 2109/4256/7361 2110/3852/7362 2598/4068/6988 +f 2602/2427/4733 2103/2011/6620 3082/2685/4953 +f 3436/2282/4599 3434/2161/4490 3405/2160/4489 +f 2901/3313/5581 3023/4233/6827 3024/1970/4323 +f 2571/2390/4702 2568/4232/6826 2553/2391/4703 +f 2914/3062/5317 2917/3063/5319 3011/3268/5537 +f 3872/4365/7213 3841/4237/6839 3871/2691/6840 +f 3732/2754/7145 3729/2910/6821 3730/4180/6821 +f 2698/3648/5967 2780/2970/5217 2778/2971/5218 +f 2165/4156/6670 2164/4109/7363 2166/3257/5521 +f 2470/4353/7105 2471/2079/4415 2429/2078/4414 +f 2226/2496/4793 2227/3893/6271 2228/2494/4791 +f 3455/4393/4532 3454/2594/4532 3456/3917/4532 +f 3173/3615/5925 3188/3688/6019 3189/3022/5273 +f 2173/4162/6684 2643/4091/6571 2163/3985/6418 +f 2449/3310/5578 2252/3311/5579 2251/2747/5015 +f 2281/3816/6177 2183/3815/6176 2282/2356/6173 +f 2950/3858/6221 3013/4223/6792 2910/2048/4389 +f 3222/3225/5491 3223/3641/5957 3231/4042/6494 +f 2844/4366/7154 2685/1969/4322 2750/1968/4321 +f 2934/4308/26 2933/2969/26 2972/3896/26 +f 2302/3594/7248 2301/3502/7342 2588/4082/6555 +f 3029/3100/5357 3066/3392/5673 3067/2125/4452 +f 4375/1994/4344 4360/2716/4985 4348/4216/6985 +f 3219/3718/6057 3299/4163/6687 3323/4314/7012 +f 2106/3793/6990 2109/4256/7361 2598/4068/6988 +f 2268/2924/5176 2266/3851/6214 2267/3791/7286 +f 2633/3330/5599 2153/3514/6403 2632/3331/5600 +f 3780/2222/4545 3766/2221/4544 3781/3555/5860 diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 9609464ec7..87f9ea3b7b 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -54,7 +54,7 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); - AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base); + AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, "examples/Cassie/urdf/cassie_v2_shells.urdf"); if (FLAGS_floating_base) { // Ground direction Eigen::Vector3d ground_normal(sin(FLAGS_ground_incline), 0, From 85c218fa6ec73688ca6ca5d57b25d62def52fd5b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 15 Sep 2022 15:37:49 -0400 Subject: [PATCH 315/758] lighting on drake visualizer looks weird still --- examples/Cassie/urdf/cassie_v2_shells.urdf | 15 ++++++++------- 1 file changed, 8 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/urdf/cassie_v2_shells.urdf b/examples/Cassie/urdf/cassie_v2_shells.urdf index e92e03e89e..479f6f3201 100644 --- a/examples/Cassie/urdf/cassie_v2_shells.urdf +++ b/examples/Cassie/urdf/cassie_v2_shells.urdf @@ -290,13 +290,13 @@ + + + - - - @@ -427,7 +427,7 @@ xyz="0 0 0" rpy="1.570796 0 0" /> - + @@ -454,7 +454,7 @@ xyz="0 0 0" rpy="1.570796 0 0" /> - + @@ -562,9 +562,10 @@ + rpy="1.570796 0 3.14159" /> - + From f20d213150466bbc539c3c5c7a77cf1e38f91b1f Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 28 Sep 2022 14:41:32 -0400 Subject: [PATCH 316/758] working on making visualization scripts in python --- bindings/__init__.py | 0 bindings/pydairlib/lcm/BUILD.bazel | 26 ------- .../pydairlib/lcm/visualization/BUILD.bazel | 52 ++++++++++++++ .../pydairlib/lcm/visualization/__init__.py | 0 .../dircon_trajectory_plotter.py | 0 .../lcm_trajectory_plotter.py | 0 .../visualize_configs/long_jump.yaml | 8 +++ .../lcm/visualization/visualize_params.py | 21 ++++++ .../lcm/visualization/visualize_trajectory.py | 68 +++++++++++++++++++ bindings/pydairlib/multibody/BUILD.bazel | 1 + bindings/pydairlib/multibody/multibody_py.cc | 8 ++- examples/Cassie/run_dircon_jumping.cc | 61 +++++++++-------- examples/Cassie/urdf/cassie_v2_shells.urdf | 7 +- examples/Cassie/visualizer.cc | 3 +- multibody/visualization_utils.cc | 4 +- multibody/visualization_utils.h | 2 +- 16 files changed, 195 insertions(+), 66 deletions(-) create mode 100644 bindings/__init__.py create mode 100644 bindings/pydairlib/lcm/visualization/BUILD.bazel create mode 100644 bindings/pydairlib/lcm/visualization/__init__.py rename bindings/pydairlib/lcm/{ => visualization}/dircon_trajectory_plotter.py (100%) rename bindings/pydairlib/lcm/{ => visualization}/lcm_trajectory_plotter.py (100%) create mode 100644 bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml create mode 100644 bindings/pydairlib/lcm/visualization/visualize_params.py create mode 100644 bindings/pydairlib/lcm/visualization/visualize_trajectory.py diff --git a/bindings/__init__.py b/bindings/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index 126e076dd0..89629a01a8 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -45,30 +45,6 @@ pybind_py_library( py_imports = ["."], ) -py_binary( - name = "lcm_trajectory_plotter", - srcs = [":lcm_trajectory_plotter.py"], - deps = [ - ":lcm_trajectory_py", - ":module_py", - "//lcmtypes:lcmtypes_robot_py", - ], -) - -py_binary( - name = "dircon_trajectory_plotter", - srcs = [":dircon_trajectory_plotter.py"], - deps = [ - ":lcm_trajectory_py", - ":lcm_py", - ":module_py", - "//bindings/pydairlib/common", - "//bindings/pydairlib/multibody:multibody_py", - "//bindings/pydairlib/cassie:cassie_utils_py", - "//lcmtypes:lcmtypes_robot_py", - ], -) - # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") @@ -85,8 +61,6 @@ py_library( ) PY_LIBRARIES = [ - ":dircon_trajectory_plotter", - ":lcm_trajectory_plotter", ":lcm_trajectory_py", ":lcm_py", ] diff --git a/bindings/pydairlib/lcm/visualization/BUILD.bazel b/bindings/pydairlib/lcm/visualization/BUILD.bazel new file mode 100644 index 0000000000..e5de1218c0 --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/BUILD.bazel @@ -0,0 +1,52 @@ + # -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +py_binary( + name = "lcm_trajectory_plotter", + srcs = ["lcm_trajectory_plotter.py"], + deps = [ + "//bindings/pydairlib/lcm", + "//lcmtypes:lcmtypes_robot_py", + ], +) + +py_library( + name = "visualize_params", + srcs = ["visualize_params.py"], + deps = [], +) + +py_binary( + name = "visualize_trajectory", + srcs = ["visualize_trajectory.py"], + deps = [ + ":visualize_params", + "//bindings/pydairlib/lcm", + "//lcmtypes:lcmtypes_robot_py", + "//bindings/pydairlib/multibody", + "//bindings/pydairlib/common", + "//bindings/pydairlib/cassie:cassie_utils_py", + ], +) + +py_binary( + name = "dircon_trajectory_plotter", + srcs = ["dircon_trajectory_plotter.py"], + deps = [ + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/common", + "//bindings/pydairlib/multibody:multibody_py", + "//bindings/pydairlib/cassie:cassie_utils_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/bindings/pydairlib/lcm/visualization/__init__.py b/bindings/pydairlib/lcm/visualization/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/bindings/pydairlib/lcm/dircon_trajectory_plotter.py b/bindings/pydairlib/lcm/visualization/dircon_trajectory_plotter.py similarity index 100% rename from bindings/pydairlib/lcm/dircon_trajectory_plotter.py rename to bindings/pydairlib/lcm/visualization/dircon_trajectory_plotter.py diff --git a/bindings/pydairlib/lcm/lcm_trajectory_plotter.py b/bindings/pydairlib/lcm/visualization/lcm_trajectory_plotter.py similarity index 100% rename from bindings/pydairlib/lcm/lcm_trajectory_plotter.py rename to bindings/pydairlib/lcm/visualization/lcm_trajectory_plotter.py diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml new file mode 100644 index 0000000000..564c6788c9 --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -0,0 +1,8 @@ +filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.75d_2 +spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf +visualize_mode: 2 +realtime_rate: 1.0 +num_poses: 10 +use_transparency: 1 +use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_params.py b/bindings/pydairlib/lcm/visualization/visualize_params.py new file mode 100644 index 0000000000..e7e7301107 --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/visualize_params.py @@ -0,0 +1,21 @@ +import io +from yaml import load, dump + +try: + from yaml import CLoader as Loader, CDumper as Dumper +except ImportError: + from yaml import Loader, Dumper + + +class DirconVisualizationParams(): + def __init__(self, filename): + data = load(io.open(filename, 'r'), Loader=Loader) + self.filename = data['filename'] + self.spring_urdf = data['spring_urdf'] + self.fixed_spring_urdf = data['fixed_spring_urdf'] + self.visualize_mode = data['visualize_mode'] + self.realtime_rate = data['realtime_rate'] + self.num_poses = data['num_poses'] + self.use_transparency = data['use_transparency'] + self.use_springs = data['use_springs'] + diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py new file mode 100644 index 0000000000..7c818dd41a --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -0,0 +1,68 @@ +import sys +import matplotlib.pyplot as plt +from pydairlib.lcm import lcm_trajectory +from pydairlib.common import FindResourceOrThrow +from pydrake.trajectories import PiecewisePolynomial +import numpy as np + +from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator) +from pydairlib.cassie.cassie_utils import AddCassieMultibody +from pydairlib.multibody import MultiposeVisualizer, ConnectTrajectoryVisualizer +from visualize_params import DirconVisualizationParams + + +def main(): + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' + params = DirconVisualizationParams(visualization_config_file) + + builder = DiagramBuilder() + plant_wo_spr, scene_graph_wo_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + AddCassieMultibody(plant_wo_spr, scene_graph_wo_spr, + True, "examples/Cassie/urdf/cassie_fixed_springs.urdf", + False, False) + + plant_wo_spr.Finalize() + plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + AddCassieMultibody(plant_w_spr, scene_graph_w_spr, + True, "examples/Cassie/urdf/cassie_v2_shells.urdf", + False, False) + + plant_w_spr.Finalize() + + nq = plant_wo_spr.num_positions() + nv = plant_wo_spr.num_velocities() + nx = nq + nv + + filename = FindResourceOrThrow(params.filename) + + dircon_traj = lcm_trajectory.DirconTrajectory(plant_wo_spr, filename) + + optimal_traj = dircon_traj.ReconstructStateTrajectory() + t_vec = optimal_traj.get_segment_times() + + + if params.visualize_mode == 0 or params.visualize_mode == 1: + ConnectTrajectoryVisualizer(plant_wo_spr, builder, scene_graph_wo_spr, + optimal_traj) + diagram = builder.Build() + + while params.visualize_mode == 1: + simulator = Simulator(diagram) + simulator.set_target_realtime_rate(params.realtime_rate) + simulator.Initialize() + simulator.AdvanceTo(optimal_traj.end_time()) + + elif params.visualize_mode == 2: + poses = np.zeros((params.num_poses, nx)) + for i in range(params.num_poses): + poses[i] = optimal_traj.value(t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] + if params.use_transparency: + alpha_scale = np.linspace(0.2, 1.0, params.num_poses) + visualizer = MultiposeVisualizer(FindResourceOrThrow( + params.fixed_spring_urdf), + params.num_poses, np.square(alpha_scale), "") + visualizer.DrawPoses(poses.T) + + +if __name__ == "__main__": + main() diff --git a/bindings/pydairlib/multibody/BUILD.bazel b/bindings/pydairlib/multibody/BUILD.bazel index 9de8f1de70..3318ce1930 100644 --- a/bindings/pydairlib/multibody/BUILD.bazel +++ b/bindings/pydairlib/multibody/BUILD.bazel @@ -15,6 +15,7 @@ pybind_py_library( name = "multibody_py", cc_deps = [ "//multibody:multipose_visualizer", + "//multibody:visualization_utils", "//multibody:utils", "@drake//:drake_shared_library", ], diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index 852d3cd26c..c82ed9987b 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -5,6 +5,7 @@ #include "multibody/multibody_utils.h" #include "multibody/multipose_visualizer.h" +#include "multibody/visualization_utils.h" namespace py = pybind11; @@ -24,6 +25,10 @@ PYBIND11_MODULE(multibody, m) { .def(py::init()) .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses")); + m.def("ConnectTrajectoryVisualizer", + &dairlib::multibody::ConnectTrajectoryVisualizer, py::arg("plant"), + py::arg("builder"), py::arg("scene_graph"), py::arg("trajectory")); + m.def("MakeNameToPositionsMap", &dairlib::multibody::MakeNameToPositionsMap, py::arg("plant")) .def("MakeNameToVelocitiesMap", @@ -42,8 +47,7 @@ PYBIND11_MODULE(multibody, m) { py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"), py::arg("mu_kinetic"), py::arg("normal_W") = Eigen::Vector3d(0, 0, 1), - py::arg("stiffness") = 0, - py::arg("dissipation_rate") = 0, + py::arg("stiffness") = 0, py::arg("dissipation_rate") = 0, py::arg("show_ground") = 1); } diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index e6f308eacd..ba805a0129 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -2,7 +2,6 @@ #include #include #include -#include #include #include @@ -269,7 +268,7 @@ void DoMain() { // auto land_mode = DirconMode(double_stance_constraints, // stance_knotpoints, 0.4, 0.6); auto crouch_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.5, 1.0); + stance_knotpoints, 1.0, 2.0); auto flight_mode = DirconMode(flight_phase_constraints, flight_phase_knotpoints, 0.2, 2.0); auto land_mode = DirconMode(double_stance_constraints, @@ -470,12 +469,12 @@ void SetKinematicConstraints(Dircon* trajopt, // auto state_vars_ij = trajopt->state_vars(i, j); // auto input_vars_ij = trajopt->input_vars(i, j); auto force_vars_ij = trajopt->force_vars(i, j); - prog->AddBoundingBoxConstraint(VectorXd::Constant(force_vars_ij.rows(), -200), - VectorXd::Constant(force_vars_ij.rows(), 200), - force_vars_ij); - prog->AddBoundingBoxConstraint(VectorXd::Constant(force_vars_ij.rows(), -200), - VectorXd::Constant(force_vars_ij.rows(), 200), - force_vars_ij); + prog->AddBoundingBoxConstraint( + VectorXd::Constant(force_vars_ij.rows(), -200), + VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); + prog->AddBoundingBoxConstraint( + VectorXd::Constant(force_vars_ij.rows(), -200), + VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); } } @@ -652,11 +651,11 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_y_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - 0.1 * VectorXd::Ones(1), 0.15 * VectorXd::Ones(1)); + 0.1 * VectorXd::Ones(1), 0.2 * VectorXd::Ones(1)); auto right_foot_y_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - -0.15 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + -0.2 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); auto left_foot_z_ground_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), @@ -908,26 +907,28 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; - // MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); - // W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e-3; - // W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e-3; - // W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 1e-3; - // W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 1e-3; - // W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; - // W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; - // W *= 2.0 * FLAGS_cost_scaling; - // vector> joint_accel_costs; - // for (int mode : {0, 1, 2}) { - // joint_accel_costs.push_back(std::make_shared( - // W, plant, &constraints->mode(mode).evaluators())); - // for (int index = 0; index < mode_lengths[mode]; index++) { - // // Assumes mode_lengths are the same across modes - // auto x_i = trajopt->state_vars(mode, index); - // auto u_i = trajopt->input_vars(mode, index); - // auto l_i = trajopt->force_vars(mode, index); - // trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - // } - // } + MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e1; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e1; + W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; + W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; + W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; + W(vel_map["hip_yaw_rightdot"], vel_map["hip_yaw_rightdot"]) *= 1e2; + W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + W *= 2.0 * FLAGS_cost_scaling; + vector> joint_accel_costs; + for (int mode : {0, 1, 2}) { + joint_accel_costs.push_back(std::make_shared( + W, plant, &constraints->mode(mode).evaluators())); + for (int index = 0; index < mode_lengths[mode]; index++) { + // Assumes mode_lengths are the same across modes + auto x_i = trajopt->state_vars(mode, index); + auto u_i = trajopt->input_vars(mode, index); + auto l_i = trajopt->force_vars(mode, index); + trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + } + } } /****** diff --git a/examples/Cassie/urdf/cassie_v2_shells.urdf b/examples/Cassie/urdf/cassie_v2_shells.urdf index 479f6f3201..2379af4c5a 100644 --- a/examples/Cassie/urdf/cassie_v2_shells.urdf +++ b/examples/Cassie/urdf/cassie_v2_shells.urdf @@ -398,9 +398,10 @@ + rpy="1.570796 0 3.14159" /> - + @@ -512,7 +513,6 @@ rpy="1.570796 0 0" /> - @@ -566,7 +566,6 @@ - diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 11518d1b2f..ce3f89d896 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -114,10 +114,11 @@ int do_main(int argc, char* argv[]) { DrakeVisualizer::AddToBuilder(&builder, scene_graph, lcm); drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0/30.0; + params.publish_period = 1.0/60.0; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); + meshcat->AddButton("switch_to_running"); // state_receiver->set_publish_period(1.0/30.0); // framerate auto diagram = builder.Build(); diff --git a/multibody/visualization_utils.cc b/multibody/visualization_utils.cc index b5d819fc0c..e127abdd06 100644 --- a/multibody/visualization_utils.cc +++ b/multibody/visualization_utils.cc @@ -37,11 +37,11 @@ void ConnectTrajectoryVisualizer( drake::geometry::SceneGraph* scene_graph, const Trajectory& trajectory) { auto empty_plant = std::make_unique>(0.0); - ConnectTrajectoryVisualizer(plant, builder, scene_graph, trajectory, + ConnectTrajectoryVisualizerWithCoM(plant, builder, scene_graph, trajectory, *empty_plant); } -void ConnectTrajectoryVisualizer( +void ConnectTrajectoryVisualizerWithCoM( const MultibodyPlant* plant, drake::systems::DiagramBuilder* builder, drake::geometry::SceneGraph* scene_graph, diff --git a/multibody/visualization_utils.h b/multibody/visualization_utils.h index 31de4481c2..fba3f5f21a 100644 --- a/multibody/visualization_utils.h +++ b/multibody/visualization_utils.h @@ -27,7 +27,7 @@ void ConnectTrajectoryVisualizer( drake::systems::DiagramBuilder* builder, drake::geometry::SceneGraph* scene_graph, const drake::trajectories::Trajectory& trajectory); -void ConnectTrajectoryVisualizer( +void ConnectTrajectoryVisualizerWithCoM( const drake::multibody::MultibodyPlant* plant, drake::systems::DiagramBuilder* builder, drake::geometry::SceneGraph* scene_graph, From 1ccbd03fa468698d745c46340833f0b027aeebbd Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 30 Sep 2022 13:51:26 -0400 Subject: [PATCH 317/758] adding meshcat in places --- .../visualize_configs/long_jump.yaml | 2 +- .../lcm/visualization/visualize_trajectory.py | 33 +- bindings/pydairlib/multibody/BUILD.bazel | 2 +- director/BUILD.bazel | 1 + director/scripts/VisualizationGUI.py | 1134 +++++++++-------- director/scripts/cassie_test.json | 4 +- examples/Cassie/visualizer.cc | 2 - multibody/multipose_visualizer.cc | 8 + multibody/multipose_visualizer.h | 3 + multibody/visualization_utils.cc | 3 + 10 files changed, 647 insertions(+), 545 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 564c6788c9..7cb8cb20c9 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,7 +1,7 @@ filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.75d_2 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 2 +visualize_mode: 1 realtime_rate: 1.0 num_poses: 10 use_transparency: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 7c818dd41a..bd6890fdcc 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -5,7 +5,8 @@ from pydrake.trajectories import PiecewisePolynomial import numpy as np -from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator) +from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator, SceneGraph, MultibodyPlant) +from pydrake.geometry import MeshcatVisualizer, StartMeshcat, MeshcatVisualizerParams from pydairlib.cassie.cassie_utils import AddCassieMultibody from pydairlib.multibody import MultiposeVisualizer, ConnectTrajectoryVisualizer from visualize_params import DirconVisualizationParams @@ -16,18 +17,20 @@ def main(): params = DirconVisualizationParams(visualization_config_file) builder = DiagramBuilder() - plant_wo_spr, scene_graph_wo_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + scene_graph_wo_spr = builder.AddSystem(SceneGraph()) + # plant_wo_spr, scene_graph_wo_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + plant_wo_spr = MultibodyPlant(0.0) AddCassieMultibody(plant_wo_spr, scene_graph_wo_spr, True, "examples/Cassie/urdf/cassie_fixed_springs.urdf", False, False) plant_wo_spr.Finalize() - plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) - AddCassieMultibody(plant_w_spr, scene_graph_w_spr, - True, "examples/Cassie/urdf/cassie_v2_shells.urdf", - False, False) + # plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + # AddCassieMultibody(plant_w_spr, scene_graph_w_spr, + # True, "examples/Cassie/urdf/cassie_v2_shells.urdf", + # False, False) - plant_w_spr.Finalize() + # plant_w_spr.Finalize() nq = plant_wo_spr.num_positions() nv = plant_wo_spr.num_velocities() @@ -39,11 +42,16 @@ def main(): optimal_traj = dircon_traj.ReconstructStateTrajectory() t_vec = optimal_traj.get_segment_times() - + # meshcat.SetLine() if params.visualize_mode == 0 or params.visualize_mode == 1: ConnectTrajectoryVisualizer(plant_wo_spr, builder, scene_graph_wo_spr, optimal_traj) + meschat_params = MeshcatVisualizerParams() + meschat_params.publish_period = 1.0/60.0 + meshcat = StartMeshcat() + visualizer = MeshcatVisualizer.AddToBuilder( + builder, scene_graph_wo_spr, meshcat, meschat_params) diagram = builder.Build() while params.visualize_mode == 1: @@ -56,11 +64,10 @@ def main(): poses = np.zeros((params.num_poses, nx)) for i in range(params.num_poses): poses[i] = optimal_traj.value(t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] - if params.use_transparency: - alpha_scale = np.linspace(0.2, 1.0, params.num_poses) - visualizer = MultiposeVisualizer(FindResourceOrThrow( - params.fixed_spring_urdf), - params.num_poses, np.square(alpha_scale), "") + alpha_scale = np.linspace(0.2, 1.0, params.num_poses) + visualizer = MultiposeVisualizer(FindResourceOrThrow( + params.fixed_spring_urdf), + params.num_poses, np.square(alpha_scale), "") visualizer.DrawPoses(poses.T) diff --git a/bindings/pydairlib/multibody/BUILD.bazel b/bindings/pydairlib/multibody/BUILD.bazel index 3318ce1930..0995b385bf 100644 --- a/bindings/pydairlib/multibody/BUILD.bazel +++ b/bindings/pydairlib/multibody/BUILD.bazel @@ -22,7 +22,7 @@ pybind_py_library( cc_so_name = "multibody", cc_srcs = ["multibody_py.cc"], py_deps = [ - "@drake//bindings/pydrake", +# "@drake//bindings/pydrake", ":module_py", ], py_imports = ["."], diff --git a/director/BUILD.bazel b/director/BUILD.bazel index a3af482263..eb32577969 100644 --- a/director/BUILD.bazel +++ b/director/BUILD.bazel @@ -8,6 +8,7 @@ py_binary( deps = [ "//lcmtypes:lcmtypes_robot_py", "@drake//tools:drake_visualizer_py", +# "//bindings/pydairlib/multibody:multibody_py", "@pydrake_pegged", ], ) diff --git a/director/scripts/VisualizationGUI.py b/director/scripts/VisualizationGUI.py index 58f4abf6a9..3ccd8d0a13 100644 --- a/director/scripts/VisualizationGUI.py +++ b/director/scripts/VisualizationGUI.py @@ -17,8 +17,10 @@ import pydrake.multibody.plant import pydrake.multibody.parsing from pydrake.common.eigen_geometry import Quaternion +from pydrake.geometry import StartMeshcat, Rgba -# stadard library imports +from pydairlib.multibody import MakeNameToPositionsMap, MakeNameToVelocitiesMap, MakeNameToActuatorsMap +# standard library imports import numpy as np import json from collections import deque @@ -26,559 +28,639 @@ import os import pydrake + drake_root = f"{os.path.dirname(pydrake.__file__)}/share" os.environ["DRAKE_RESOURCE_ROOT"] = drake_root + class VisualizationGui(QWidget): - def __init__(self, parent = None): - super(VisualizationGui, self).__init__(parent) + def __init__(self, parent=None): + super(VisualizationGui, self).__init__(parent) - self.resetGUI() + self.resetGUI() - # create the GUI - self.setWindowTitle("Visualization GUI") - self.vbox = QVBoxLayout() - self.hbox = QHBoxLayout() - - # create the JSON directory reader - self.readJSON = QPushButton("Select JSON file") - self.readJSON.clicked.connect(self.readJSONFile) - self.hbox.addWidget(self.readJSON) - self.vbox.addLayout(self.hbox) - - def resetGUI(self): - ''' - Function for (re)setting the GUI and JSON attrbutes - ''' - # GUI attributes - self.checkBoxes = {} - self.resetBtn = None - self.clearBtn = None - self.checkBoxArea = None - self.delete = False - self.clear = False - self.ready = False - self.lcmObjects = {} - self.subscriptions = [] - - # JSON attributes - self.data = None - self.modelFile = None - self.weldBody = None - self.shapes = {} - self.plant = None - - - def readJSONFile(self): - ''' - Function for reading the JSON input file and populating the JSON - and GUI attributes - ''' - - # use dialog box to get JSON directory - mainWindow = director.applogic.getMainWindow() - fileFilters = "Data Files (*.json)"; - filename = QtGui.QFileDialog.getOpenFileName(mainWindow, "Open...", os.getcwd(), fileFilters, "", QtGui.QFileDialog.DontUseNativeDialog) - - if not filename: - return - - # load only if input is not empty - self.json_file = filename - with open(self.json_file) as json_file: - self.data = json.load(json_file) - - self.modelFile = self.data['model_file'] - - if ('weld-body' in self.data): - self.weldBody = self.data['weld-body'] - - # create each object/shape to be drawn - for data in self.data['data']: - newObject = ObjectToDraw(data) - - # if this is a shape of type lcm then create an additional separate object - if (newObject.category == "lcm"): - if (newObject.name not in self.lcmObjects): - if (newObject.type == "axes"): - self.lcmObjects[newObject.name] = LCMMessage(newObject.source_data, axis = True) - else: - self.lcmObjects[newObject.name] = LCMMessage(newObject.source_data) - else: - if (newObject.type == "axes"): - self.lcmObjects[newObject.name].update( - newObject.source_data, axis = True) - else: - self.lcmObjects[newObject.name].update( - newObject.source_data) - - # if there exists a shape with the given name then simply update it - if (newObject.name not in self.shapes): - self.shapes[newObject.name] = newObject - else: - self.shapes[newObject.name].update(newObject) - - # fill the checkboxes for each data with its name and add the "reset" and "clear" buttons - self.placeCheckBoxes() - if (self.resetBtn == None): - self.resetBtn = QPushButton('Reset') - self.resetBtn.clicked.connect(self.deleteShapes) - self.vbox.addWidget(self.resetBtn) - - if (self.clearBtn == None): - self.clearBtn = QPushButton('Clear History') - self.clearBtn.clicked.connect(self.clearHistory) - self.vbox.addWidget(self.clearBtn) - - if (self.plant == None): - # Create the plant - builder = pydrake.systems.framework.DiagramBuilder() - self.plant, scene_graph = \ - pydrake.multibody.plant.AddMultibodyPlantSceneGraph(builder, 0) - - file = os.getcwd() + '/' + self.modelFile - pydrake.multibody.parsing.Parser(self.plant).AddModelFromFile(file) - - # determine if there is a need to use the weld a body part - if (self.weldBody != None): - self.plant.WeldFrames(self.plant.world_frame(), - self.plant.GetFrameByName(self.weldBody), RigidTransform.Identity()) - self.plant.Finalize() - self.context = self.plant.CreateDefaultContext() - - # start listenning to the main state LCM messages - lcmUtils.addSubscriber(self.data['channelName'], messageClass=dairlib.lcmt_robot_output, callback=self.state_handler) - - # add more LCM subscriptions depending on the number of "lcm" data - for name in self.lcmObjects: - lcmMessage = self.lcmObjects[name] - subscriber = lcmUtils.addSubscriber(lcmMessage.channel, messageClass=eval(lcmMessage.type), callback=lambda msg, lcmMessage=lcmMessage, name=name: self.abstract_handler(msg, name, lcmMessage)) - - self.subscriptions.append(subscriber) - - self.ready = True - - def deleteShapes(self): - ''' - Function for setting the flag for deleting all shapes currently present - ''' - self.delete = True - - def clearHistory(self): - ''' - Function for setting the flag for clearing the history of any line present - ''' - self.clear = True - self.state_handler(self.msg) - - def placeCheckBoxes(self): - ''' - Function for placing the checkboxes of the GUI. Each checkbox corresponds - to a shape/object that has been drawn with the corresponding color and - extension - ''' - - addToGUI = False - if (self.checkBoxArea == None): - self.checkBoxArea = QVBoxLayout() - addToGUI = True - for name in self.shapes: - # create appropriate symbol extention - extension = " •" - type = self.shapes[name].type - if (type == "point"): - extension = " •" - elif (type == "line"): - extension = " ---" - elif (type == "axes"): - extension = " |/_" - - # create each checkbox and conditionally add it to the GUI - addToList = False - if (name not in self.checkBoxes): - self.checkBoxes[name] = QCheckBox(name + extension) - - if (self.shapes[name].type == "point" or self.shapes[name].type == "line"): - color = self.shapes[name].color - self.checkBoxes[name].setStyleSheet("color: rgb("+str(color[0] * 255)+", "+str(color[1] * 255)+", "+str(color[2] * 255)+")") - - addToList = True - self.checkBoxes[name].setChecked(True) - if (addToList == True): - self.checkBoxArea.addWidget(self.checkBoxes[name]) - if (addToGUI == True): - self.vbox.addLayout(self.checkBoxArea) - - def abstract_handler(self, msg, name, lcmMessage): - ''' - Function for handling LCM messages originating from a different - channel than the main one - - msg: the returning LCM message - field: the field name/path - name: name of corresponding shape - x, y, z: indices for each of the 3 dimensions of the location where - the shape is to be drawn. When the shape is an axis then x - will be the first index of the quaternion array and the other - 3 will be the next indices in sequence - ''' - self.handle_checkBox(name) - attribute = msg - field = lcmMessage.field - - # if there is a %d in the field replace it with the actual index - if ("%d" in field): - arr = self.getVector(attribute, lcmMessage.index_field) - if (lcmMessage.index_element in arr): - i = arr.index(lcmMessage.index_element) - field = field.replace("%d", str(i)) - - if ("%d" not in field): - # parse field to get the appropriate information. This is done by - # recursively searching for the right attribute in the given message's field - attribute = self.getVector(attribute, field) - currShape = self.shapes[name] - x = lcmMessage.x - - # special case of an axis data - if (currShape.type == "axes"): - # get quaternion array, normalize it, and get the corresponding rotation matrix - quaternion = [] - for i in range(x, x+4): - quaternion.append(attribute[i]) - norm = np.linalg.norm(quaternion) - quaternion = [x / norm for x in quaternion] - rot_matrix = Quaternion(quaternion).rotation() - - pt_world = self.plant.CalcPointsPositions(self.context, - self.plant.GetFrameByName(currShape.frame), - currShape.point, self.plant.world_frame()) - next_loc = pt_world.transpose()[0] - - self.drawShape(self.shapes[name], next_loc, msg, rotation_matrix = rot_matrix) + # create the GUI + self.setWindowTitle("Visualization GUI") + self.vbox = QVBoxLayout() + self.hbox = QHBoxLayout() - else: - next_loc = [attribute[x], attribute[x+1], attribute[x+2]] - self.drawShape(self.shapes[name], next_loc, msg) + self.meshcat = StartMeshcat() + + # create the JSON directory reader + self.readJSON = QPushButton("Select JSON file") + self.readJSON.clicked.connect(self.readJSONFile) + self.hbox.addWidget(self.readJSON) + self.vbox.addLayout(self.hbox) + + def resetGUI(self): + ''' + Function for (re)setting the GUI and JSON attrbutes + ''' + # GUI attributes + self.checkBoxes = {} + self.resetBtn = None + self.clearBtn = None + self.checkBoxArea = None + self.delete = False + self.clear = False + self.ready = False + self.lcmObjects = {} + self.subscriptions = [] + + # JSON attributes + self.data = None + self.modelFile = None + self.weldBody = None + self.shapes = {} + self.plant = None + + def readJSONFile(self): + ''' + Function for reading the JSON input file and populating the JSON + and GUI attributes + ''' + + # use dialog box to get JSON directory + mainWindow = director.applogic.getMainWindow() + fileFilters = "Data Files (*.json)"; + filename = QtGui.QFileDialog.getOpenFileName(mainWindow, "Open...", + os.getcwd() + '/director/scripts/', + fileFilters, "", + QtGui.QFileDialog.DontUseNativeDialog) + + if not filename: + return + + # load only if input is not empty + self.json_file = filename + with open(self.json_file) as json_file: + self.data = json.load(json_file) + + self.modelFile = self.data['model_file'] + + if ('weld-body' in self.data): + self.weldBody = self.data['weld-body'] + + # create each object/shape to be drawn + for data in self.data['data']: + newObject = ObjectToDraw(data) + + # if this is a shape of type lcm then create an additional separate object + if (newObject.category == "lcm"): + if (newObject.name not in self.lcmObjects): + if (newObject.type == "axes"): + self.lcmObjects[newObject.name] = LCMMessage(newObject.source_data, + axis=True) + else: + self.lcmObjects[newObject.name] = LCMMessage(newObject.source_data) else: - print(lcmMessage.index_element + "is not present in " + lcmMessage.index_field + " and so it cannot be visualized") - print("") - - def getVector(self, attribute, path): - ''' - Function for getting the pointer to a specific field of a given - attribute using the given path - - attribute: the object containing the desired field - path: the string path to get the attribute's field - ''' - field = path.split(".") - regExpr = re.compile('.+\[\d+\]') - newAtribute = attribute - for part in field: - index = None - attName = None - - if regExpr.match(part) is not None: - index = part.split("[")[1].split("]")[0] - attName = part.split("[")[0] - newAtribute = getattr(newAtribute, attName)[int(index)] - else: - index = None - attName = part - newAtribute = getattr(newAtribute, attName) + if (newObject.type == "axes"): + self.lcmObjects[newObject.name].update( + newObject.source_data, axis=True) + else: + self.lcmObjects[newObject.name].update( + newObject.source_data) + + # if there exists a shape with the given name then simply update it + if (newObject.name not in self.shapes): + self.shapes[newObject.name] = newObject + else: + self.shapes[newObject.name].update(newObject) + + # fill the checkboxes for each data with its name and add the "reset" and "clear" buttons + self.placeCheckBoxes() + if (self.resetBtn == None): + self.resetBtn = QPushButton('Reset') + self.resetBtn.clicked.connect(self.deleteShapes) + self.vbox.addWidget(self.resetBtn) + + if (self.clearBtn == None): + self.clearBtn = QPushButton('Clear History') + self.clearBtn.clicked.connect(self.clearHistory) + self.vbox.addWidget(self.clearBtn) + + if (self.plant == None): + # Create the plant + builder = pydrake.systems.framework.DiagramBuilder() + self.plant, scene_graph = \ + pydrake.multibody.plant.AddMultibodyPlantSceneGraph(builder, 0) + + file = os.getcwd() + '/' + self.modelFile + pydrake.multibody.parsing.Parser(self.plant).AddModelFromFile(file) + + # determine if there is a need to use the weld a body part + if (self.weldBody != None): + self.plant.WeldFrames(self.plant.world_frame(), + self.plant.GetFrameByName(self.weldBody), + RigidTransform.Identity()) + self.plant.Finalize() + # self.position_idx_map = MakeNameToPositionsMap(self.plant) + # self.velocity_idx_map = MakeNameToVelocitiesMap(self.plant) + # self.effort_idx_map = MakeNameToActuatorsMap(self.plant) + # self.nq = self.plant.num_positions() + # self.nv = self.plant.num_velocities() + # self.nu = self.plant.num_actuators() + self.context = self.plant.CreateDefaultContext() + + # start listenning to the main state LCM messages + lcmUtils.addSubscriber(self.data['channelName'], + messageClass=dairlib.lcmt_robot_output, + callback=self.state_handler) + # self.state_recevier = RobotOutputReceiver(self.plant) + + # add more LCM subscriptions depending on the number of "lcm" data + for name in self.lcmObjects: + lcmMessage = self.lcmObjects[name] + subscriber = lcmUtils.addSubscriber(lcmMessage.channel, + messageClass=eval(lcmMessage.type), + callback=lambda msg, + lcmMessage=lcmMessage, + name=name: self.abstract_handler( + msg, name, lcmMessage)) + + self.subscriptions.append(subscriber) + + self.ready = True + + def deleteShapes(self): + ''' + Function for setting the flag for deleting all shapes currently present + ''' + self.delete = True + + def clearHistory(self): + ''' + Function for setting the flag for clearing the history of any line present + ''' + self.clear = True + self.state_handler(self.msg) + + def placeCheckBoxes(self): + ''' + Function for placing the checkboxes of the GUI. Each checkbox corresponds + to a shape/object that has been drawn with the corresponding color and + extension + ''' + + addToGUI = False + if (self.checkBoxArea == None): + self.checkBoxArea = QVBoxLayout() + addToGUI = True + for name in self.shapes: + # create appropriate symbol extention + extension = " •" + type = self.shapes[name].type + if (type == "point"): + extension = " •" + elif (type == "line"): + extension = " ---" + elif (type == "axes"): + extension = " |/_" + + # create each checkbox and conditionally add it to the GUI + addToList = False + if (name not in self.checkBoxes): + self.checkBoxes[name] = QCheckBox(name + extension) + + if (self.shapes[name].type == "point" or self.shapes[ + name].type == "line"): + color = self.shapes[name].color + self.checkBoxes[name].setStyleSheet( + "color: rgb(" + str(color[0] * 255) + ", " + str( + color[1] * 255) + ", " + str(color[2] * 255) + ")") + + addToList = True + self.checkBoxes[name].setChecked(True) + if (addToList == True): + self.checkBoxArea.addWidget(self.checkBoxes[name]) + if (addToGUI == True): + self.vbox.addLayout(self.checkBoxArea) + + def abstract_handler(self, msg, name, lcmMessage): + ''' + Function for handling LCM messages originating from a different + channel than the main one + + msg: the returning LCM message + field: the field name/path + name: name of corresponding shape + x, y, z: indices for each of the 3 dimensions of the location where + the shape is to be drawn. When the shape is an axis then x + will be the first index of the quaternion array and the other + 3 will be the next indices in sequence + ''' + self.handle_checkBox(name) + attribute = msg + field = lcmMessage.field + + # if there is a %d in the field replace it with the actual index + if ("%d" in field): + arr = self.GetVector(attribute, lcmMessage.index_field) + if (lcmMessage.index_element in arr): + i = arr.index(lcmMessage.index_element) + field = field.replace("%d", str(i)) + + if ("%d" not in field): + # parse field to get the appropriate information. This is done by + # recursively searching for the right attribute in the given message's field + attribute = self.GetVector(attribute, field) + curr_shape = self.shapes[name] + x = lcmMessage.x + + # special case of an axis data + if (curr_shape.type == "axes"): + # get quaternion array, normalize it, and get the corresponding rotation matrix + quaternion = [] + for i in range(x, x + 4): + quaternion.append(attribute[i]) + norm = np.linalg.norm(quaternion) + quaternion = [x / norm for x in quaternion] + rot_matrix = Quaternion(quaternion).rotation() + + pt_world = self.plant.CalcPointsPositions(self.context, + self.plant.GetFrameByName( + curr_shape.frame), + curr_shape.point, + self.plant.world_frame()) + next_loc = pt_world.transpose()[0] + + self.drawShape(self.shapes[name], next_loc, msg, + rotation_matrix=rot_matrix) + + else: + next_loc = [attribute[x], attribute[x + 1], attribute[x + 2]] + self.drawShape(self.shapes[name], next_loc, msg) + else: + print( + lcmMessage.index_element + "is not present in " + lcmMessage.index_field + " and so it cannot be visualized") + print("") + + def GetVector(self, attribute, path): + """ + Function for getting the pointer to a specific field of a given + attribute using the given path + + attribute: the object containing the desired field + path: the string path to get the attribute's field + """ + field = path.split(".") + regExpr = re.compile('.+\[\d+\]') + newAtribute = attribute + for part in field: + index = None + attName = None + + if regExpr.match(part) is not None: + index = part.split("[")[1].split("]")[0] + attName = part.split("[")[0] + newAtribute = getattr(newAtribute, attName)[int(index)] + else: + index = None + attName = part + newAtribute = getattr(newAtribute, attName) + + return newAtribute + + def handle_checkBox(self, name): + ''' + Function for checking if a checkBox is checked or not + + name: name of corresponding shape + ''' + if (self.checkBoxes[name].isChecked() == True): + if (self.shapes[name].object != None and self.shapes[ + name].object.getProperty('Visible') == False): + self.shapes[name].object.setProperty('Visible', True) + + else: + if (self.shapes[name].object != None and self.shapes[ + name].object.getProperty('Visible') == True): + self.shapes[name].object.setProperty('Visible', False) + + def state_handler(self, msg): + ''' + Function for handling main lcm channel - return newAtribute + msg: the returning LCM message + ''' + # start listening to messages once the JSON file has been read + if (self.ready == True): + # TODO (for Michael): bind our more robust decoding mechanisms to python + self.msg = msg + positions = np.zeros(self.nq) + for i in range(self.nq): + j = self.position_idx_map[msg.position_names[i]] + positions[j] = msg.position[i] + velocities = np.zeros(self.nv) + for i in range(self.nv): + j = self.velocity_idx_map[msg.velocity_names[i]] + velocities[j] = msg.velocity[i] + efforts = np.zeros(self.nu) + for i in range(self.nu): + j = self.effort_idx_map[msg.effort_names[i]] + efforts[j] = msg.effort[i] + self.plant.SetPositions(self.context, positions) + self.plant.SetVelocities(self.context, velocities) + + # iterate through each shape to draw it + for name in self.shapes: + self.handle_checkBox(name) + currShape = self.shapes[name] + + # define next_loc according to each shape/object to be drawn + next_loc = None + if (currShape.category == "kinematic"): + # Use Drake's CalcPointsPositions to determine where that point is + # in the world + pt_world = self.plant.CalcPointsPositions(self.context, + self.plant.GetFrameByName( + currShape.frame), + currShape.point, + self.plant.world_frame()) + next_loc = pt_world.transpose()[0] + + elif (currShape.category == "com"): + next_loc = self.plant.CalcCenterOfMassPositionInWorld( + context=self.context) + + elif (currShape.category == "lcm"): + # in the case of an lcm message do not do anything as this is + # handled by the abstract handler + continue + + self.drawShape(currShape, next_loc, self.msg) + + # handle flags for clearing line histories + if (self.clear == True): + for shape in self.shapes.values(): + if (shape.type == "line"): + om.removeFromObjectModel(shape.object) + shape.object = None + shape.points = deque() + self.clear = False + # handle flags for deleting objects + if (self.delete == True): + for shape in self.shapes.values(): + om.removeFromObjectModel(shape.object) + + self.delete = False - def handle_checkBox(self, name): - ''' - Function for checking if a checkBox is checked or not + # delete checkboxes from GUI + for i in reversed(range(self.checkBoxArea.count())): + self.checkBoxArea.itemAt(i).widget().deleteLater() - name: name of corresponding shape - ''' - if (self.checkBoxes[name].isChecked() == True): - if (self.shapes[name].object != None and self.shapes[name].object.getProperty('Visible') == False): - self.shapes[name].object.setProperty('Visible', True) + # delete "reset" and "clear history" buttons + self.resetBtn.deleteLater() + self.clearBtn.deleteLater() + + # remove all lcm channels except for the state one + for subscription in self.subscriptions: + lcmUtils.removeSubscriber(subscription) + + self.resetGUI() + + def drawShape(self, curr_shape, next_loc, msg, rotation_matrix=None): + ''' + Function for drawing shapes. Currently this supports lines, points, and + 3D axes + + currShape: the current shape to be drawn + next_loc: the location where to draw the shape + msg: the message from the LCM hendler that called this function + rotation_matrix: the rotation matrix to be used for the axis shape. + Mainly used by the abstract handler + ''' + # draw a continuous line + if (curr_shape.type == "line"): + # check if the duration has been initialized + if (curr_shape.duration == None or len(curr_shape.points) == 0): + curr_shape.duration = msg.utime / 1000000 + + # visualize and trace line for 'history' seconds, adding points at a distance at least 10e-5 + if ((( + msg.utime / 1000000) - curr_shape.duration <= curr_shape.history) or curr_shape.history <= 0): + # make sure to add at least 2 points before starting to check for the distance between points + if (len(curr_shape.points) < 2): + curr_shape.points.append(next_loc) + d = DebugData() + d.addPolyLine(curr_shape.points, radius=curr_shape.thickness, + color=curr_shape.color) + self.meshcat.SetLine(curr_shape.name, np.array(curr_shape.points).T, + line_width=curr_shape.thickness * 1000, + rgba=Rgba(curr_shape.color[0], + curr_shape.color[1], + curr_shape.color[2], + 1.0)) + + if (curr_shape.object == None): + curr_shape.object = vis.showPolyData(d.getPolyData(), + curr_shape.name) + curr_shape.object.setProperty('Color', curr_shape.color) + else: + curr_shape.object.setPolyData(d.getPolyData()) else: - if (self.shapes[name].object != None and self.shapes[name].object.getProperty('Visible') == True): - self.shapes[name].object.setProperty('Visible', False) - - def state_handler(self, msg): - ''' - Function for handling main lcm channel - - msg: the returning LCM message - ''' - # start listenning to messages once the JSON file has been read - if (self.ready == True): - # TODO (for Michael): bind our more robust decoding mechanisms to python - self.msg = msg - self.plant.SetPositions(self.context, self.msg.position) - self.plant.SetVelocities(self.context, self.msg.velocity) - - # iterate through each shape to draw it - for name in self.shapes: - self.handle_checkBox(name) - currShape = self.shapes[name] - - # define next_loc according to each shape/object to be drawn - next_loc = None - if (currShape.category == "kinematic"): - # Use Drake's CalcPointsPositions to determine where that point is - # in the world - pt_world = self.plant.CalcPointsPositions(self.context, - self.plant.GetFrameByName(currShape.frame), - currShape.point, self.plant.world_frame()) - next_loc = pt_world.transpose()[0] - - elif (currShape.category == "com"): - next_loc = self.plant.CalcCenterOfMassPositionInWorld(context = self.context) - - elif (currShape.category == "lcm"): - # in the case of an lcm message do not do anything as this is - # handled by the abstract handler - continue - - self.drawShape(currShape, next_loc, self.msg) - - # handle flags for clearing line histories - if (self.clear == True): - for shape in self.shapes.values(): - if (shape.type == "line"): - om.removeFromObjectModel(shape.object) - shape.object = None - shape.points = deque() - self.clear = False - - # handle flags for deleting objects - if (self.delete == True): - for shape in self.shapes.values(): - om.removeFromObjectModel(shape.object) - - self.delete = False - - # delete checkboxes from GUI - for i in reversed(range(self.checkBoxArea.count())): - self.checkBoxArea.itemAt(i).widget().deleteLater() - - # delete "reset" and "clear history" buttons - self.resetBtn.deleteLater() - self.clearBtn.deleteLater() - - # remove all lcm channels except for the state one - for subscription in self.subscriptions: - lcmUtils.removeSubscriber(subscription) - - self.resetGUI() - - - def drawShape(self, currShape, next_loc, msg, rotation_matrix = None): - ''' - Function for drawing shapes. Currently this supports lines, points, and - 3D axes - - currShape: the current shape to be drawn - next_loc: the location where to draw the shape - msg: the message from the LCM hendler that called this function - rotation_matrix: the rotation matrix to be used for the axis shape. - Mainly used by the abstract handler - ''' - # draw a continuous line - if (currShape.type == "line"): - # check if the duration has been initialized - if (currShape.duration == None or len(currShape.points) == 0): - currShape.duration = msg.utime / 1000000 - - # visualize and trace line for 'history' seconds, adding points at a distance at least 10e-5 - if (((msg.utime / 1000000) - currShape.duration <= currShape.history) or currShape.history <= 0): - # make sure to add at least 2 points before starting to check for the distance between points - if (len(currShape.points) < 2): - currShape.points.append(next_loc) - d = DebugData() - d.addPolyLine(currShape.points, radius=currShape.thickness, color=currShape.color) - - if (currShape.object == None): - currShape.object = vis.showPolyData(d.getPolyData(), currShape.name) - currShape.object.setProperty('Color', currShape.color) - else: - currShape.object.setPolyData(d.getPolyData()) - - else: - if (np.linalg.norm(np.array(next_loc) -np.array(currShape.points[-1])) >= 10e-5): - currShape.points.append(next_loc) - d = DebugData() - d.addPolyLine(currShape.points, radius=currShape.thickness, color=currShape.color) - - if (currShape.object == None): - currShape.object = vis.showPolyData(d.getPolyData(), currShape.name) - else: - currShape.object.setPolyData(d.getPolyData()) - - elif (currShape.history > 0): - if (len(currShape.points) == 0): - currShape.duration = msg.utime / 1000000 - else: - # visualize and trace line for 'history' seconds, adding points at a distance at least 10e-5 - if (np.linalg.norm(np.array(next_loc) -np.array(currShape.points[-1])) >= 10e-5): - currShape.points.popleft() - currShape.points.append(next_loc) - d = DebugData() - d.addPolyLine(currShape.points, radius=currShape.thickness, color=currShape.color) - if (currShape.object == None): - currShape.object = vis.showPolyData(d.getPolyData(), currShape.name) - else: - currShape.object.setPolyData(d.getPolyData()) - - # draw a point - elif (currShape.type == "point"): + if (np.linalg.norm( + np.array(next_loc) - np.array(curr_shape.points[-1])) >= 10e-5): + curr_shape.points.append(next_loc) d = DebugData() - d.addSphere(next_loc, radius = currShape.radius) - # create a new point - if (currShape.created == True): - currShape.object = vis.showPolyData(d.getPolyData(), currShape.name) - # set color and transparency of point - currShape.object.setProperty('Color', currShape.color) - currShape.object.setProperty('Alpha', currShape.alpha) - currShape.created = False + d.addPolyLine(curr_shape.points, radius=curr_shape.thickness, + color=curr_shape.color) + self.meshcat.SetLine(curr_shape.name, np.array(curr_shape.points).T, + line_width=curr_shape.thickness * 1000, + rgba=Rgba(curr_shape.color[0], + curr_shape.color[1], + curr_shape.color[2], + 1.0)) + + if (curr_shape.object == None): + curr_shape.object = vis.showPolyData(d.getPolyData(), + curr_shape.name) else: - # update the location of the last point - currShape.object.setPolyData(d.getPolyData()) - - # draw a set of axes - elif (currShape.type == "axes"): - # get the rotation matrix - rot_matrix = None - if (currShape.category != "lcm"): - rigTrans = self.plant.EvalBodyPoseInWorld(self.context, self.plant.GetBodyByName(currShape.frame)) - rot_matrix = rigTrans.rotation().matrix().transpose() - else: - rot_matrix = rotation_matrix - - colors = [[1, 0, 0], [0, 1, 0], [0, 0, 1]] + curr_shape.object.setPolyData(d.getPolyData()) + elif (curr_shape.history > 0): + if (len(curr_shape.points) == 0): + curr_shape.duration = msg.utime / 1000000 + else: + # visualize and trace line for 'history' seconds, adding points at a distance at least 10e-5 + if (np.linalg.norm( + np.array(next_loc) - np.array(curr_shape.points[-1])) >= 10e-5): + curr_shape.points.popleft() + curr_shape.points.append(next_loc) d = DebugData() - for i in range(3): - d.addArrow(next_loc, next_loc + (rot_matrix[i]*currShape.length), headRadius=0.03, color = colors[i]) - - # create the 3 axes - if (currShape.created == True): - currShape.object = vis.showPolyData(d.getPolyData(), currShape.name, colorByName='RGB255') - currShape.object.setProperty('Alpha', currShape.alpha) - currShape.created = False + d.addPolyLine(curr_shape.points, radius=curr_shape.thickness, + color=curr_shape.color) + self.meshcat.SetLine(curr_shape.name, np.array(curr_shape.points).T, + line_width=curr_shape.thickness * 1000, + rgba=Rgba(curr_shape.color[0], + curr_shape.color[1], + curr_shape.color[2], + 1.0)) + if (curr_shape.object == None): + curr_shape.object = vis.showPolyData(d.getPolyData(), + curr_shape.name) else: - # update the location of the last point - currShape.object.setPolyData(d.getPolyData()) + curr_shape.object.setPolyData(d.getPolyData()) + + # draw a point + elif (curr_shape.type == "point"): + d = DebugData() + d.addSphere(next_loc, radius=curr_shape.radius) + # create a new point + if (curr_shape.created == True): + curr_shape.object = vis.showPolyData(d.getPolyData(), curr_shape.name) + # set color and transparency of point + curr_shape.object.setProperty('Color', curr_shape.color) + curr_shape.object.setProperty('Alpha', curr_shape.alpha) + curr_shape.created = False + else: + # update the location of the last point + curr_shape.object.setPolyData(d.getPolyData()) + + # draw a set of axes + elif (curr_shape.type == "axes"): + # get the rotation matrix + rot_matrix = None + if (curr_shape.category != "lcm"): + rigTrans = self.plant.EvalBodyPoseInWorld(self.context, + self.plant.GetBodyByName( + curr_shape.frame)) + rot_matrix = rigTrans.rotation().matrix().transpose() + else: + rot_matrix = rotation_matrix + + colors = [[1, 0, 0], [0, 1, 0], [0, 0, 1]] + + d = DebugData() + for i in range(3): + d.addArrow(next_loc, next_loc + (rot_matrix[i] * curr_shape.length), + headRadius=0.03, color=colors[i]) + + # create the 3 axes + if (curr_shape.created == True): + curr_shape.object = vis.showPolyData(d.getPolyData(), curr_shape.name, + colorByName='RGB255') + curr_shape.object.setProperty('Alpha', curr_shape.alpha) + curr_shape.created = False + else: + # update the location of the last point + curr_shape.object.setPolyData(d.getPolyData()) + class ObjectToDraw(): + ''' + Wrapper class for any object/shape being drawn + ''' + + def __init__(self, data): + # set attributes from given data (originating from input JSON file) + self.name = data['name'] + + self.source_data = data['source_data'] + type_data = data['type_data'] + + self.category = self.source_data['category'] + + if (self.category == "kinematic"): + self.frame = self.source_data['frame'] + self.point = self.source_data['point'] + + self.alpha = type_data['alpha'] + self.type = type_data['type'] + self.created = True + self.object = None + + if (self.type == "line"): + self.color = type_data['color'] + self.thickness = type_data['thickness'] + self.history = type_data['history'] + self.duration = None + self.points = deque() + + elif (self.type == "point"): + self.color = type_data['color'] + self.radius = type_data['radius'] + + elif (self.type == "axes"): + if (self.category == "lcm"): + self.frame = self.source_data['frame'] + self.point = self.source_data['point'] + self.quaternion_index = self.source_data['quaternion_index'] + self.thickness = type_data['thickness'] + self.length = type_data['length'] + + def update(self, otherObject): ''' - Wrapper class for any object/shape being drawn + Function for updating certain attributes of already existing object + + otherObject: the other ObcectToDraw instance ''' - def __init__(self, data): - # set attributes from given data (originating from input JSON file) - self.name = data['name'] - - self.source_data = data['source_data'] - type_data = data['type_data'] - - self.category = self.source_data['category'] - - if (self.category == "kinematic"): - self.frame = self.source_data['frame'] - self.point = self.source_data['point'] - - self.alpha = type_data['alpha'] - self.type = type_data['type'] - self.created = True - self.object = None - - if (self.type == "line"): - self.color = type_data['color'] - self.thickness = type_data['thickness'] - self.history = type_data['history'] - self.duration = None - self.points = deque() - - elif (self.type == "point"): - self.color = type_data['color'] - self.radius = type_data['radius'] - - elif (self.type == "axes"): - if (self.category == "lcm"): - self.frame = self.source_data['frame'] - self.point = self.source_data['point'] - self.quaternion_index = self.source_data['quaternion_index'] - self.thickness = type_data['thickness'] - self.length = type_data['length'] - - def update(self, otherObject): - ''' - Function for updating certain attributes of already existing object - - otherObject: the other ObcectToDraw instance - ''' - self.alpha = otherObject.alpha - - if (self.category == "kinematic"): - self.frame = otherObject.frame - self.point = otherObject.point - - if (self.category == "lcm"): - self.source_data = otherObject.source_data - - if (self.type == "line"): - self.color = otherObject.color - self.thickness = otherObject.thickness - self.history = otherObject.history - - elif (self.type == "point"): - self.color = otherObject.color - self.radius = otherObject.radius - - elif (self.type == "axes"): - self.thickness = otherObject.thickness - self.length = otherObject.length + self.alpha = otherObject.alpha + + if (self.category == "kinematic"): + self.frame = otherObject.frame + self.point = otherObject.point + + if (self.category == "lcm"): + self.source_data = otherObject.source_data + + if (self.type == "line"): + self.color = otherObject.color + self.thickness = otherObject.thickness + self.history = otherObject.history + + elif (self.type == "point"): + self.color = otherObject.color + self.radius = otherObject.radius + + elif (self.type == "axes"): + self.thickness = otherObject.thickness + self.length = otherObject.length + class LCMMessage(): + ''' + Wrapper class for LCM messages + ''' + + def __init__(self, source_data, axis=False): ''' - Wrapper class for LCM messages + Constructor ''' - def __init__(self, source_data, axis = False): - ''' - Constructor - ''' - self.channel = source_data['abstract_channel'] - self.type = source_data['abstract_type'] - self.field = source_data['abstract_field'] - - if ("[%d]" in self.field): - self.index_field = source_data['index_field'] - self.index_element = source_data['index_element'] - - if (axis == True): - self.x = source_data["quaternion_index"] - else: - self.x = source_data["x_index"] - - def update(self, source_data, axis = False): - ''' - Same as constructor but is used to update an LCMMessage - object with new source_data - ''' - self.channel = source_data['abstract_channel'] - self.type = source_data['abstract_type'] - self.field = source_data['abstract_field'] - - if ("[%d]" in self.field): - self.index_field = source_data['index_field'] - self.index_element = source_data['index_element'] - - if (axis == True): - self.x = source_data["quaternion_index"] - else: - self.x = source_data["x_index"] + self.channel = source_data['abstract_channel'] + self.type = source_data['abstract_type'] + self.field = source_data['abstract_field'] + + if ("[%d]" in self.field): + self.index_field = source_data['index_field'] + self.index_element = source_data['index_element'] + + if (axis == True): + self.x = source_data["quaternion_index"] + else: + self.x = source_data["x_index"] + + def update(self, source_data, axis=False): + ''' + Same as constructor but is used to update an LCMMessage + object with new source_data + ''' + self.channel = source_data['abstract_channel'] + self.type = source_data['abstract_type'] + self.field = source_data['abstract_field'] + + if ("[%d]" in self.field): + self.index_field = source_data['index_field'] + self.index_element = source_data['index_element'] + + if (axis == True): + self.x = source_data["quaternion_index"] + else: + self.x = source_data["x_index"] + # Adding the widget panel = VisualizationGui() diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index 72499cbb5d..5d044c00c8 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -125,7 +125,7 @@ "abstract_type": "dairlib.lcmt_osc_output", "abstract_field": "tracking_data[%d].y", "index_field": "tracking_data_names", - "index_element": "left_ft_z_traj", + "index_element": "left_ft_traj", "x_index": 0 }, "type_data": { @@ -148,7 +148,7 @@ "abstract_type": "dairlib.lcmt_osc_output", "abstract_field": "tracking_data[%d].y_des", "index_field": "tracking_data_names", - "index_element": "left_ft_z_traj", + "index_element": "left_ft_traj", "x_index": 0 }, "type_data": { diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index ce3f89d896..f06719773b 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -118,8 +118,6 @@ int do_main(int argc, char* argv[]) { auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); - meshcat->AddButton("switch_to_running"); - // state_receiver->set_publish_period(1.0/30.0); // framerate auto diagram = builder.Build(); diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index 2406c3f337..7116b58f2d 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -2,6 +2,7 @@ #include "drake/geometry/drake_visualizer.h" #include "drake/geometry/scene_graph.h" +#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" @@ -88,6 +89,12 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, } } + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0/60.0; + meshcat_ = std::make_shared(); + meshcat_visualizer_ = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, *scene_graph, meshcat_, std::move(params)); + DrakeVisualizer::AddToBuilder(&builder, *scene_graph, lcm); diagram_ = builder.Build(); diagram_context_ = diagram_->CreateDefaultContext(); @@ -106,6 +113,7 @@ void MultiposeVisualizer::DrawPoses(MatrixXd poses) { // Publish diagram diagram_->Publish(*diagram_context_); + } } // namespace multibody diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index 3d4f28b0d7..ff764c181b 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -4,6 +4,7 @@ #include #include "drake/geometry/scene_graph.h" +#include "drake/geometry/meshcat_visualizer.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/diagram.h" @@ -57,6 +58,8 @@ class MultiposeVisualizer { int num_poses_; drake::multibody::MultibodyPlant* plant_; std::unique_ptr> diagram_; + std::shared_ptr meshcat_; + drake::geometry::MeshcatVisualizer* meshcat_visualizer_; std::unique_ptr> diagram_context_; std::vector model_indices_; }; diff --git a/multibody/visualization_utils.cc b/multibody/visualization_utils.cc index e127abdd06..5464b2e921 100644 --- a/multibody/visualization_utils.cc +++ b/multibody/visualization_utils.cc @@ -4,6 +4,8 @@ #include "multibody/com_pose_system.h" #include "systems/primitives/subvector_pass_through.h" #include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/primitives/trajectory_source.h" @@ -82,6 +84,7 @@ void ConnectTrajectoryVisualizerWithCoM( } DrakeVisualizer::AddToBuilder(builder, *scene_graph); + } } // namespace multibody From fb4c680618840fea87a84fb9d26326dc0ecf0762 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 30 Sep 2022 14:44:49 -0400 Subject: [PATCH 318/758] not publishing when tracking datas aren't active --- .../osc/operational_space_control.cc | 26 +++++++++++++------ 1 file changed, 18 insertions(+), 8 deletions(-) diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 9fd10babbb..d3f88a855d 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1021,15 +1021,20 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; +// output->tracking_data = +// std::vector(tracking_data_vec_->size()); +// output->tracking_costs = std::vector(tracking_data_vec_->size()); +// output->tracking_data_names = +// std::vector(tracking_data_vec_->size()); output->tracking_data = - std::vector(tracking_data_vec_->size()); - output->tracking_costs = std::vector(tracking_data_vec_->size()); + std::vector(); + output->tracking_costs = std::vector(); output->tracking_data_names = - std::vector(tracking_data_vec_->size()); + std::vector(); for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i).get(); - output->tracking_data_names[i] = tracking_data->GetName(); +// output->tracking_data_names[i] = tracking_data->GetName(); lcmt_osc_tracking_data osc_output; osc_output.y_dim = tracking_data->GetYDim(); @@ -1046,7 +1051,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command = std::vector(osc_output.ydot_dim); osc_output.yddot_command_sol = std::vector(osc_output.ydot_dim); - output->tracking_costs[i] = 0; +// output->tracking_costs[i] = 0; + if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && time_since_last_state_switch <= t_e_vec_.at(i)) { @@ -1067,10 +1073,14 @@ void OperationalSpaceControl::AssignOscLcmOutput( VectorXd y_tracking_cost = VectorXd::Zero(1); tracking_costs_[i]->Eval(*dv_sol_, &y_tracking_cost); - output->tracking_costs[i] = y_tracking_cost[0]; - total_cost += output->tracking_costs[i]; +// output->tracking_costs[i] = y_tracking_cost[0]; +// total_cost += output->tracking_costs[i]; + total_cost += y_tracking_cost[0]; + output->tracking_costs.push_back(y_tracking_cost[0]); + output->tracking_data.push_back(osc_output); + output->tracking_data_names.push_back(tracking_data->GetName()); } - output->tracking_data[i] = osc_output; +// output->tracking_data[i] = osc_output; } // output->regularization_costs.push_back(total_cost); // output->regularization_cost_names.push_back("total_cost"); From 3b02f1d9c2dc6ee9f6d8c3959c093605fbe64c31 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 30 Sep 2022 14:45:00 -0400 Subject: [PATCH 319/758] updating visualization script --- director/scripts/cassie_test.json | 16 ++++++++-------- 1 file changed, 8 insertions(+), 8 deletions(-) diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index 5d044c00c8..7957a21e7d 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -1,6 +1,6 @@ { "model_file": "examples/Cassie/urdf/cassie_v2.urdf", - "channelName": "CASSIE_STATE_SIMULATION", + "channelName": "CASSIE_STATE_DISPATCHER", "data": [ { "name": "pelvis", @@ -91,7 +91,7 @@ "alpha": 0.5, "type": "line", "thickness": 0.005, - "history": 5 + "history": 1 } }, { @@ -108,13 +108,13 @@ "type_data": { "color": [ 1, - 0, + 1, 1 ], "alpha": 0.5, "type": "line", "thickness": 0.005, - "history": 5 + "history": 1 } }, { @@ -125,7 +125,7 @@ "abstract_type": "dairlib.lcmt_osc_output", "abstract_field": "tracking_data[%d].y", "index_field": "tracking_data_names", - "index_element": "left_ft_traj", + "index_element": "right_ft_traj", "x_index": 0 }, "type_data": { @@ -137,7 +137,7 @@ "alpha": 0.5, "type": "line", "thickness": 0.005, - "history": 5 + "history": 1 } }, { @@ -148,7 +148,7 @@ "abstract_type": "dairlib.lcmt_osc_output", "abstract_field": "tracking_data[%d].y_des", "index_field": "tracking_data_names", - "index_element": "left_ft_traj", + "index_element": "right_ft_traj", "x_index": 0 }, "type_data": { @@ -160,7 +160,7 @@ "alpha": 0.5, "type": "line", "thickness": 0.005, - "history": 5 + "history": 1 } } ] From 8e4c0e11f069e7df1543835adda827652562524d Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 30 Sep 2022 14:53:00 -0400 Subject: [PATCH 320/758] adding offset for relative trajectories --- director/scripts/VisualizationGUI.py | 38 +++++++++++++++++----------- 1 file changed, 23 insertions(+), 15 deletions(-) diff --git a/director/scripts/VisualizationGUI.py b/director/scripts/VisualizationGUI.py index 3ccd8d0a13..8024642947 100644 --- a/director/scripts/VisualizationGUI.py +++ b/director/scripts/VisualizationGUI.py @@ -19,7 +19,7 @@ from pydrake.common.eigen_geometry import Quaternion from pydrake.geometry import StartMeshcat, Rgba -from pydairlib.multibody import MakeNameToPositionsMap, MakeNameToVelocitiesMap, MakeNameToActuatorsMap +# from pydairlib.multibody import MakeNameToPositionsMap, MakeNameToVelocitiesMap, MakeNameToActuatorsMap # standard library imports import numpy as np import json @@ -289,6 +289,14 @@ def abstract_handler(self, msg, name, lcmMessage): rotation_matrix=rot_matrix) else: + pelvis_pos = self.plant.CalcPointsPositions(self.context, + self.plant.GetFrameByName( + "pelvis"), + np.zeros(3), + self.plant.world_frame()) + # print(pelvis_pos.shape) + # print(np.array(attribute).shape) + attribute = np.array(attribute) + pelvis_pos[:, 0] next_loc = [attribute[x], attribute[x + 1], attribute[x + 2]] self.drawShape(self.shapes[name], next_loc, msg) else: @@ -348,20 +356,20 @@ def state_handler(self, msg): if (self.ready == True): # TODO (for Michael): bind our more robust decoding mechanisms to python self.msg = msg - positions = np.zeros(self.nq) - for i in range(self.nq): - j = self.position_idx_map[msg.position_names[i]] - positions[j] = msg.position[i] - velocities = np.zeros(self.nv) - for i in range(self.nv): - j = self.velocity_idx_map[msg.velocity_names[i]] - velocities[j] = msg.velocity[i] - efforts = np.zeros(self.nu) - for i in range(self.nu): - j = self.effort_idx_map[msg.effort_names[i]] - efforts[j] = msg.effort[i] - self.plant.SetPositions(self.context, positions) - self.plant.SetVelocities(self.context, velocities) + # positions = np.zeros(self.nq) + # for i in range(self.nq): + # j = self.position_idx_map[msg.position_names[i]] + # positions[j] = msg.position[i] + # velocities = np.zeros(self.nv) + # for i in range(self.nv): + # j = self.velocity_idx_map[msg.velocity_names[i]] + # velocities[j] = msg.velocity[i] + # efforts = np.zeros(self.nu) + # for i in range(self.nu): + # j = self.effort_idx_map[msg.effort_names[i]] + # efforts[j] = msg.effort[i] + self.plant.SetPositions(self.context, self.msg.position) + self.plant.SetVelocities(self.context, self.msg.velocity) # iterate through each shape to draw it for name in self.shapes: From 6e163b67bd28ae9ea77fd625ecc88ee044c9bbbb Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 6 Oct 2022 10:24:48 -0400 Subject: [PATCH 321/758] updating channel --- director/scripts/cassie_test.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/director/scripts/cassie_test.json b/director/scripts/cassie_test.json index 7957a21e7d..66c4233f22 100644 --- a/director/scripts/cassie_test.json +++ b/director/scripts/cassie_test.json @@ -1,6 +1,6 @@ { "model_file": "examples/Cassie/urdf/cassie_v2.urdf", - "channelName": "CASSIE_STATE_DISPATCHER", + "channelName": "CASSIE_STATE_SIMULATION", "data": [ { "name": "pelvis", From 9852cd62b1ef799610fb5bc66f21c0ac3c1ce30f Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 6 Oct 2022 11:01:18 -0400 Subject: [PATCH 322/758] cleaning up kinodynamic planner --- .../visualize_configs/long_jump.yaml | 2 +- .../lcm/visualization/visualize_trajectory.py | 11 ++--- .../contact_scheduler/kinodynamic_planner.cc | 46 +------------------ .../contact_scheduler/kinodynamic_planner.h | 12 ----- 4 files changed, 7 insertions(+), 64 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 7cb8cb20c9..2c8cf1f443 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -2,7 +2,7 @@ filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.75d_2 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 -realtime_rate: 1.0 +realtime_rate: 0.2 num_poses: 10 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index bd6890fdcc..cff75e7c91 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -25,12 +25,12 @@ def main(): False, False) plant_wo_spr.Finalize() - # plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) - # AddCassieMultibody(plant_w_spr, scene_graph_w_spr, - # True, "examples/Cassie/urdf/cassie_v2_shells.urdf", - # False, False) + plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + AddCassieMultibody(plant_w_spr, scene_graph_w_spr, + True, "examples/Cassie/urdf/cassie_v2_shells.urdf", + False, False) - # plant_w_spr.Finalize() + plant_w_spr.Finalize() nq = plant_wo_spr.num_positions() nv = plant_wo_spr.num_velocities() @@ -42,7 +42,6 @@ def main(): optimal_traj = dircon_traj.ReconstructStateTrajectory() t_vec = optimal_traj.get_segment_times() - # meshcat.SetLine() if params.visualize_mode == 0 or params.visualize_mode == 1: ConnectTrajectoryVisualizer(plant_wo_spr, builder, scene_graph_wo_spr, diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc index 7f75690583..d372908232 100644 --- a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc @@ -67,36 +67,6 @@ KinodynamicPlanner::KinodynamicPlanner( x_des_ = VectorXd ::Zero(n_r_ + n_h_); } -// void KinodynamicPlanner::print_constraint( -// const std::vector& constraints) const { -// for (auto& x0_const : constraints) { -// std::cout << x0_const->get_description() << ":\n A:\n" -// << x0_const->A() << "\nub:\n" -// << x0_const->upper_bound() << "\nlb\n" -// << x0_const->lower_bound() << std::endl; -// } -//} -// -// void KinodynamicPlanner::print_constraint( -// const std::vector& constraints) -// const { -// for (auto& x0_const : constraints) { -// std::cout << x0_const->get_description() << ":\n A:\n" -// << x0_const->A() << "\nb:\n" -// << x0_const->upper_bound() << std::endl; -// } -//} -// -// void KinodynamicPlanner::print_constraint( -// const std::vector& constraints) const { -// for (auto& constraint : constraints) { -// auto constr = dynamic_cast(constraint); -// std::cout << constr->get_description() << ":\n A:\n" -// << constr->A() << "\nb:\n" -// << constr->upper_bound() << std::endl; -// } -//} - void KinodynamicPlanner::AddCoMDynamicsConstraint() { for (int i = 0; i < n_knot_points_; ++i) { prog_.AddLinearEqualityConstraint( @@ -109,11 +79,6 @@ void KinodynamicPlanner::AddCentroidalMomentumConstraint() { centroidal_momentum_constraints_.push_back( std::make_shared(&plant_ad_, std::nullopt, &context_ad_, true)); -// VectorXDecisionVariable x; - // constraint.ComposeVariable(q_.at(i).eval(), v_.at(i).eval(), - // h_.at(i).eval(), x); constraint.ComposeVariable(q_.at(i), v_.at(i), - // h_.at(i), &x); constraint.ComposeVariable(q_.at(i), v_.at(i), - // h_.at(i), &q_.at(i)); prog_.AddConstraint(centroidal_momentum_constraints_[i], {q_.at(i), v_.at(i), h_.at(i)}); } @@ -124,11 +89,7 @@ void KinodynamicPlanner::AddAngularMomentumDynamicsConstraint() { centroidal_momentum_constraints_.push_back( std::make_shared(&plant_ad_, std::nullopt, &context_ad_, true)); -// VectorXDecisionVariable x; - // constraint.ComposeVariable(q_.at(i).eval(), v_.at(i).eval(), - // h_.at(i).eval(), x); constraint.ComposeVariable(q_.at(i), v_.at(i), - // h_.at(i), &x); constraint.ComposeVariable(q_.at(i), v_.at(i), - // h_.at(i), &q_.at(i)); + // prog_.AddConstraint(dh_.at(i) == (c_[i][0] - r_[i][0]).cross(F_[i][0]), // {q_.at(i), v_.at(i), h_.at(i)}); } @@ -161,10 +122,5 @@ void KinodynamicPlanner::AddKinematicConstraints(){ } -void KinodynamicPlanner::CheckSquareMatrixDimensions(const MatrixXd& M, - const int n) const { - DRAKE_DEMAND(M.rows() == n); - DRAKE_DEMAND(M.cols() == n); -} } // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.h b/examples/Cassie/contact_scheduler/kinodynamic_planner.h index 63b6f7ee22..dba6ccefa8 100644 --- a/examples/Cassie/contact_scheduler/kinodynamic_planner.h +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.h @@ -102,7 +102,6 @@ class KinodynamicPlanner : public drake::systems::LeafSystem { void CheckSquareMatrixDimensions(const Eigen::MatrixXd& M, int n) const; void GetMostRecentMotionPlan(const drake::systems::Context& context, lcmt_saved_traj* traj_msg) const; - void MakeKinematicReachabilityConstraints(); void MakeTerrainConstraints(const Eigen::Vector3d& normal = {0, 0, 1}, const Eigen::Vector3d& origin = {0, 0, 0}); void MakeDynamicsConstraints(); @@ -177,17 +176,6 @@ class KinodynamicPlanner : public drake::systems::LeafSystem { - - - - - - // parameters and constants - // const bool use_fsm_; - // const bool use_residuals_; - // const bool traj_tracking_; - // static constexpr int nx_ = 12; - // static constexpr int nu_ = 5; static constexpr int kLinearDim_ = 3; static constexpr int kAngularDim_ = 3; // const double dt_; From 4c110ffdf34217f696e3dd6e93db4f45915054a2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Oct 2022 10:34:36 -0400 Subject: [PATCH 323/758] working on long jump --- .../visualization/visualize_configs/long_jump.yaml | 2 +- .../lcm/visualization/visualize_trajectory.py | 13 ++++++------- examples/Cassie/run_dircon_jumping.cc | 2 +- 3 files changed, 8 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 2c8cf1f443..b2a4063d6d 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,4 +1,4 @@ -filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.75d_2 +filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.4d_3 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index cff75e7c91..f6a110a299 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -23,14 +23,13 @@ def main(): AddCassieMultibody(plant_wo_spr, scene_graph_wo_spr, True, "examples/Cassie/urdf/cassie_fixed_springs.urdf", False, False) - plant_wo_spr.Finalize() - plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) - AddCassieMultibody(plant_w_spr, scene_graph_w_spr, - True, "examples/Cassie/urdf/cassie_v2_shells.urdf", - False, False) - - plant_w_spr.Finalize() + # plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) + # AddCassieMultibody(plant_w_spr, scene_graph_w_spr, + # True, "examples/Cassie/urdf/cassie_v2_shells.urdf", + # False, False) + # + # plant_w_spr.Finalize() nq = plant_wo_spr.num_positions() nv = plant_wo_spr.num_velocities() diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index ba805a0129..487b3de7c9 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -324,7 +324,7 @@ void DoMain() { solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); // NOLINT solver_options.SetOption(id, "acceptable_tol", 1e2); // NOLINT solver_options.SetOption(id, "acceptable_iter", 5); // NOLINT - solver_options.SetOption(id, "max_iter", 10000); // NOLINT + solver_options.SetOption(id, "max_iter", 50); // NOLINT } else { // Snopt settings From 75048b29b8f204789a9386b9004535f51f44eced Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 7 Dec 2022 17:00:40 -0500 Subject: [PATCH 324/758] using sap solver and other changes --- .../pydairlib/analysis/log_plotter_cassie.py | 17 +-- .../analysis/osqp_settings_sandbox.py | 112 ++++++++++++++++-- .../plot_configs/cassie_running_plot.yaml | 18 +-- examples/Cassie/BUILD.bazel | 1 + examples/Cassie/cassie_utils.cc | 27 +++-- examples/Cassie/director_scripts/show_time.py | 84 ------------- examples/Cassie/multibody_sim.cc | 12 +- examples/Cassie/osc/high_level_command.cc | 44 ++++--- examples/Cassie/osc_run/osc_running_gains.h | 3 + .../Cassie/osc_run/osc_running_gains.yaml | 11 +- .../osc_run/osc_running_qp_settings.yaml | 6 +- examples/Cassie/run_osc_running_controller.cc | 30 ++++- multibody/multibody_solvers.cc | 4 +- solvers/nonlinear_constraint.h | 2 +- .../trajectory_optimization/dircon/dircon.h | 2 +- .../dircon/dircon_opt_constraints.h | 2 +- .../dircon_opt_constraints.h | 2 +- .../trajectory_optimization/hybrid_dircon.h | 2 +- 18 files changed, 214 insertions(+), 165 deletions(-) delete mode 100644 examples/Cassie/director_scripts/show_time.py diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index fbb66f27cb..ac82184cf4 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -13,6 +13,7 @@ def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' @@ -59,18 +60,6 @@ def main(): t_osc_slice = slice(osc_debug['t_osc'].size) print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) - # import time - # time_start = time.time() - # time.sleep(1) - # print(time.time() - time_start) - # spring_compensation = SpringCompensation() - # samples, t_samples = spring_compensation.sample_simulate_forward(robot_output['q'][0], robot_output['v'][0], robot_output['u'][0], 10) - # print(time.time() - time_start) - # plt.plot(t_samples, samples[:, :23]) - # plt.plot(t_samples, samples[:, -22:]) - # print(t_samples) - # plt.show() - # import pdb; pdb.set_trace() ''' Plot Positions ''' # Plot floating base positions if applicable @@ -135,12 +124,12 @@ def main(): if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plt.ylim([0, 400]) + plt.ylim([0, 1e4]) if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_qp_solutions: - plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 6)) + plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index d015bab7e9..4f6d0b751a 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -6,9 +6,10 @@ import matplotlib.pyplot as plt import osqp +import proxsuite from scipy.sparse import csc_matrix -saved_sols_folder = '/home/yangwill/Documents/research/projects/cassie/hardware/gain_tuning/qp_settings/cost_tuning/qp_formulation/' +saved_sols_folder = '/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/hardware/gain_tuning/qp_settings/cost_tuning/qp_formulation/' def ParseQP(data): @@ -32,6 +33,19 @@ def ParseQP(data): return qp_list +def ConvertIneq(A_ineq, ineq_lb, ineq_ub): + is_equality = ineq_ub - ineq_lb < 1e-6 + + # Parse out equality constraints + b_eq = ineq_ub[is_equality] + A_eq = A_ineq[is_equality, :] + A_ineq = A_ineq[is_equality == False, :] + ineq_lb = ineq_lb[is_equality == False] + ineq_ub = ineq_ub[is_equality == False] + + return (A_ineq, ineq_lb, ineq_ub, A_eq, b_eq) + + def solve_osqp(qp, settings): Q = qp["Q"] # Q = qp["Q"] + qp["Q"].T - np.diag(np.diag(qp["Q"])) @@ -68,11 +82,70 @@ def solve_osqp(qp, settings): 'sol': qp_result.x} +def solve_proxsuite(qp_list, settings): + run_times = np.zeros((len(qp_list),)) + obj_vals = np.zeros((len(qp_list),)) + iter = np.zeros((len(qp_list),)) + prim_res = np.zeros((len(qp_list),)) + dual_res = np.zeros((len(qp_list),)) + sol = np.zeros((len(qp_list),)) + # import pdb; pdb.set_trace() + +def solve_proxsuite(qp_list, settings): + run_times = np.zeros((len(qp_list),)) + obj_vals = np.zeros((len(qp_list),)) + iter = np.zeros((len(qp_list),)) + prim_res = np.zeros((len(qp_list),)) + dual_res = np.zeros((len(qp_list),)) + sol = np.zeros((len(qp_list),60)) + + for i, qp in enumerate(qp_list): + # Q = qp["Q"] + qp["Q"].T - np.diag(np.diag(qp["Q"])) + # Q = Q + 1e-7*np.eye(Q.shape[0]) + Q = qp["Q"] + C, l, u, A, b = ConvertIneq(qp["A_ineq"], qp["ineq_lb"], qp["ineq_ub"]) + H = Q + g = qp["w"] + n = H.shape[0] + n_eq = A.shape[0] + n_in = C.shape[0] + qp = proxsuite.proxqp.sparse.QP(n, n_eq, n_in) + # qp.init(csc_matrix(H), g, csc_matrix(A), b, csc_matrix(C), l, u, rho=settings['rho']) + qp.init(H, g, A, b, C, l, u, rho=settings['rho']) + + qp.settings.eps_abs = settings["eps_abs"] + qp.settings.eps_rel = settings["eps_rel"] + qp.settings.eps_primal_inf = settings["eps_prim_inf"] + qp.settings.eps_dual_inf = settings["eps_dual_inf"] + qp.settings.verbose = settings["verbose"] + qp.settings.max_iter = settings["max_iter"] + # qp.settings.default_rho = settings['rho'], + # check_termination=settings['check_termination'] + qp.settings.initial_guess = proxsuite.proxqp.InitialGuess.NO_INITIAL_GUESS + + qp.solve() + run_times[i] = qp.results.info.run_time * 1e-6 + obj_vals[i] = qp.results.info.objValue + iter[i] = qp.results.info.iter + prim_res[i] = qp.results.info.pri_res + dual_res[i] = qp.results.info.dua_res + sol[i] = qp.results.x + + return { + 'iter': iter, + 'run_time': run_times, + 'obj_val': obj_vals, + 'prim_res': prim_res, + 'dual_res': dual_res, + 'sol': sol, + } + def main(): # filename = "/home/brian/workspace/logs/qp_logging/lcmlog00" filename = sys.argv[1] + log = lcm.EventLog(filename, "r") - qp_list = get_log_data(log, {"QP_LOG": lcmt_qp}, ParseQP) + qp_list = get_log_data(log, {"QP_LOG": lcmt_qp}, 0, 5000, ParseQP) # qp_list = qp_list[:2000][::10] # qp_list = qp_list[:5000][::10] @@ -80,17 +153,17 @@ def main(): obj_vals = np.zeros((len(qp_list),)) pri_eps_vals = np.zeros((len(qp_list, ))) # sols = np.zeros((len(qp_list,), 60)) - sols = np.zeros((len(qp_list, ), 52)) + sols = np.zeros((len(qp_list, ), 60)) iters = np.zeros((len(qp_list, ),)) osqp_settings = \ {'rho': 1e-4, 'sigma': 1e-6, - 'max_iter': 100, + 'max_iter': 500, 'eps_abs': 1e-5, 'eps_rel': 1e-5, - 'eps_prim_inf': 1e-5, - 'eps_dual_inf': 1e-5, + 'eps_prim_inf': 1e-6, + 'eps_dual_inf': 1e-6, 'alpha': 1.6, 'linsys_solver': 0, 'delta': 1e-6, @@ -110,15 +183,38 @@ def main(): run_times[i] = osqp_result['run_time'] obj_vals[i] = osqp_result['obj_val'] pri_eps_vals[i] = osqp_result['pri_res'] - pri_eps_vals[i] = osqp_result['pri_res'] sols[i] = osqp_result['sol'] iters[i] = osqp_result['iter'] - # import pdb; pdb.set_trace() + osqp_result = solve_proxsuite(qp_list, osqp_settings) + fig, axs = plt.subplots(4, 1, sharex='all') + axs[0].plot(osqp_result['sol'][:, 32:42]) + axs[0].legend(['0', '1', '2', '3', '4']) + axs[0].set_title('Objective values per QP') + axs[1].plot(osqp_result['run_time']) + axs[1].set_title('Solve times per QP') + axs[2].plot(osqp_result['sol'][:, 22:24]) + axs[2].plot(osqp_result['sol'][:, 28:30]) + axs[3].plot(osqp_result['sol'][:, 24:28]) + axs[3].plot(osqp_result['sol'][:, 30:32]) + axs[3].set_title('QP solutions') + + # for key in osqp_result.keys(): + # plt.figure() + # # plt.plot(osqp_result[key], label='osqp') + # plt.plot(osqp_result[key], label='proxqp') + # plt.title(key) + # plt.legend() + # plt.show() + + # import pdb; pdb.set_trace() log_name = filename.split('/')[-1] np.save(saved_sols_folder + log_name + '_' + str(osqp_settings['max_iter']), sols) print(f'OSQP mean runtime: {np.mean(run_times)}') + # print(f'PROXQP mean runtime: {np.mean(osqp_result['run_time'])}) + proxqp_runtime = osqp_result['run_time'] + print(f'PROXQP mean runtime: {np.mean(proxqp_runtime)}') print(f'OSQP mean objective: {np.mean(obj_vals)}') print(f'OSQP mean primal residuals: {np.mean(pri_eps_vals)}') diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index f009ded63b..f4c8338d46 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 0.5 -duration: 4 +start_time: 2 +duration: 6 # Plant properties use_springs: true @@ -24,7 +24,7 @@ plot_commanded_efforts: true plot_contact_forces: false #special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right' ] special_positions_to_plot: [ 'hip_pitch_left', 'hip_pitch_right', 'hip_roll_left', 'hip_roll_right' ] -special_velocities_to_plot: ['hip_roll_leftdot', 'hip_roll_rightdot' ] +special_velocities_to_plot: [ 'hip_roll_leftdot', 'hip_roll_rightdot' ] special_efforts_to_plot: [ ] # Finite State Machine Names @@ -44,15 +44,15 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [1, 2 ], 'derivs': [ 'pos', 'vel' ] }, -# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' ] }, -# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, + # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' ] }, + # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, -# right_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, + # right_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, # left_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel'] }, - right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel'] }, +# left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, +# right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, } \ No newline at end of file diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index bec639c45d..1b1dc7646f 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -52,6 +52,7 @@ cc_library( "//examples/Cassie:run_osc_walking_controller", "//examples/Cassie:run_osc_walking_controller_alip", "//examples/Cassie:run_pd_controller", + "//examples/Cassie/contact_scheduler:state_based_controller_switch", "//examples/Cassie/osc", ], ) diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index 26e74cca4e..b8f08bda64 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -153,13 +153,25 @@ void AddCassieMultibody(MultibodyPlant* plant, Vector3d rod_on_thigh_left = LeftRodOnThigh(*plant).first; Vector3d rod_on_thigh_right = RightRodOnThigh(*plant).first; - plant->AddForceElement( - heel_spring_left, rod_on_heel_spring, thigh_left, rod_on_thigh_left, - kCassieAchillesLength, achilles_stiffness, achilles_damping); + if(plant->get_discrete_contact_solver() == drake::multibody::DiscreteContactSolver::kSap){ + plant->AddDistanceConstraint( + heel_spring_left, rod_on_heel_spring, thigh_left, rod_on_thigh_left, + kCassieAchillesLength, achilles_stiffness, achilles_damping); + plant->AddDistanceConstraint( + heel_spring_right, rod_on_heel_spring, thigh_right, rod_on_thigh_right, + kCassieAchillesLength, achilles_stiffness, achilles_damping); + } + else{ + plant->AddForceElement( + heel_spring_left, rod_on_heel_spring, thigh_left, + rod_on_thigh_left, kCassieAchillesLength, achilles_stiffness, + achilles_damping); - plant->AddForceElement( - heel_spring_right, rod_on_heel_spring, thigh_right, rod_on_thigh_right, - kCassieAchillesLength, achilles_stiffness, achilles_damping); + plant->AddForceElement( + heel_spring_right, rod_on_heel_spring, thigh_right, + rod_on_thigh_right, kCassieAchillesLength, achilles_stiffness, + achilles_damping); + } } bool add_reflected_inertia = true; @@ -226,7 +238,8 @@ const systems::GearedMotor& AddMotorModel( {"hip_pitch_left_motor", 136.136}, {"hip_pitch_right_motor", 136.136}, {"knee_left_motor", 136.136}, {"knee_right_motor", 136.136}, {"toe_left_motor", 575.958}, {"toe_right_motor", 575.958}}; - auto cassie_motor = builder->AddSystem(plant, omega_max); + auto cassie_motor = + builder->AddSystem(plant, omega_max); return *cassie_motor; } diff --git a/examples/Cassie/director_scripts/show_time.py b/examples/Cassie/director_scripts/show_time.py deleted file mode 100644 index 060da7676c..0000000000 --- a/examples/Cassie/director_scripts/show_time.py +++ /dev/null @@ -1,84 +0,0 @@ -# Note that this script runs in the main context of drake-visulizer, -# where many modules and variables already exist in the global scope. -from director import lcmUtils -from director import applogic -import time -import dairlib.lcmt_robot_output - - -class TimeVisualizer(object): - - def __init__(self): - self._name = "Time Visualizer" - self._real_time = [] - self._msg_time = [] - self._subscriber = None - # Number of messages used to average for real time factor. - self._num_msg_for_average = 50 - - self.set_enabled(True) - - def add_subscriber(self): - if (self._subscriber is not None): - return - - if 'pd_panel_state_channel' in globals(): - channel = pd_panel_state_channel - else: - channel = "CASSIE_STATE_SIMULATION" - - self._subscriber = lcmUtils.addSubscriber( - channel, - messageClass=dairlib.lcmt_robot_output, - callback=self.handle_message) - - def remove_subscriber(self): - if (self._subscriber is None): - return - - lcmUtils.removeSubscriber(self._subscriber) - self._subscriber = None - vis.updateText('', 'text') - - def is_enabled(self): - return self._subscriber is not None - - def set_enabled(self, enable): - if enable: - self.add_subscriber() - else: - self.remove_subscriber() - - def handle_message(self, msg): - msg_time = msg.utime * 1e-6 # convert from microseconds - self._real_time.append(time.time()) - self._msg_time.append(msg_time) - - my_text = 'time: %.3f' % msg_time - - if (len(self._real_time) >= self._num_msg_for_average): - self._real_time.pop(0) - self._msg_time.pop(0) - - dt = self._msg_time[-1] - self._msg_time[0] - dt_real_time = self._real_time[-1] - self._real_time[0] - - rt_ratio = dt / dt_real_time - - my_text = my_text + ', real time factor: %.2f' % rt_ratio - - vis.updateText(my_text, 'text') - - -def init_visualizer(): - time_viz = TimeVisualizer() - - # Adds to the "Tools" menu. - applogic.MenuActionToggleHelper( - 'Tools', time_viz._name, - time_viz.is_enabled, time_viz.set_enabled) - return time_viz - - -# Creates the visualizer when this script is executed. -time_viz = init_visualizer() diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 44df2eac6f..2d62bb4fa3 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -88,7 +88,7 @@ int do_main(int argc, char* argv[]) { const double time_step = FLAGS_time_stepping ? FLAGS_dt : 0.0; MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8, {0, 0, 1}, 1e4, 1e2); + multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8, {0, 0, 1}); } std::string urdf; @@ -98,13 +98,13 @@ int do_main(int argc, char* argv[]) { urdf = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; } + plant.set_discrete_contact_solver(drake::multibody::DiscreteContactSolver::kSap); +// plant.set_penetration_allowance(FLAGS_penetration_allowance); +// plant.set_stiction_tolerance(FLAGS_v_stiction); AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, urdf, FLAGS_spring_model, true); plant.Finalize(); - plant.set_penetration_allowance(FLAGS_penetration_allowance); - plant.set_stiction_tolerance(FLAGS_v_stiction); - // Create lcm systems. auto lcm = builder.AddSystem(); auto input_sub = @@ -199,10 +199,10 @@ int do_main(int argc, char* argv[]) { // Note that we cannot use the plant from the above diagram, because after the // diagram is built, plant.get_input_port_actuation().HasValue(*context) // throws a segfault error - drake::multibody::MultibodyPlant plant_for_solver(0.0); + drake::multibody::MultibodyPlant plant_for_solver(FLAGS_dt); AddCassieMultibody(&plant_for_solver, nullptr, FLAGS_floating_base /*floating base*/, urdf, - FLAGS_spring_model, true); + FLAGS_spring_model, false); plant_for_solver.Finalize(); if (FLAGS_floating_base) { CassieFixedPointSolver(plant_for_solver, FLAGS_init_height, mu_fp, diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index f501241d80..d37b5566c2 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -85,16 +85,16 @@ HighLevelCommand::HighLevelCommand( context_(context), world_(plant_.world_frame()), pelvis_(plant_.GetBodyByName("pelvis")) { - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); + .get_index(); - yaw_port_ = this->DeclareVectorOutputPort("pelvis_yaw", BasicVector(1), - &HighLevelCommand::CopyHeadingAngle) - .get_index(); + yaw_port_ = + this->DeclareVectorOutputPort("pelvis_yaw", BasicVector(1), + &HighLevelCommand::CopyHeadingAngle) + .get_index(); xy_port_ = this->DeclareVectorOutputPort("pelvis_xy", BasicVector(2), &HighLevelCommand::CopyDesiredHorizontalVel) @@ -110,8 +110,8 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( const Context& context, DiscreteValues* discrete_state) const { if (use_radio_command_) { - const auto& radio_out = this->EvalInputValue( - context, radio_out_port_); + const auto& radio_out = + this->EvalInputValue(context, radio_out_port_); // TODO(yangwill) make sure there is a message available // des_vel indices: 0: yaw_vel (right joystick left/right) // 1: saggital_vel (left joystick up/down) @@ -119,13 +119,16 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( double vel_scale_trans_sagital = (radio_out->channel[6] + 1.0) * vel_scale_trans_sagital_; - double a = .001 / (stick_filter_dt_ + .001); // approximately 1KHz sampling rate - no need to be too precise + double a = + .001 / + (stick_filter_dt_ + + .001); // approximately 1KHz sampling rate - no need to be too precise Vector3d des_vel_prev = discrete_state->get_value(des_vel_idx_); Vector3d des_vel; -// des_vel << vel_scale_rot_ * radio_out->channel[3], -// vel_scale_trans_sagital_ * radio_out->channel[0], -// vel_scale_trans_lateral_ * radio_out->channel[1]; -// discrete_state->get_mutable_vector(des_vel_idx_).set_value(des_vel); + // des_vel << vel_scale_rot_ * radio_out->channel[3], + // vel_scale_trans_sagital_ * radio_out->channel[0], + // vel_scale_trans_lateral_ * radio_out->channel[1]; + // discrete_state->get_mutable_vector(des_vel_idx_).set_value(des_vel); des_vel << vel_scale_rot_ * radio_out->channel[3], vel_scale_trans_sagital * radio_out->channel[0], vel_scale_trans_lateral_ * radio_out->channel[1]; @@ -180,7 +183,9 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( // PD position control double des_yaw_vel = kp_yaw_ * heading_error + kd_yaw_ * (-yaw_vel); - des_yaw_vel = drake::math::saturate(des_yaw_vel, -vel_max_yaw_, vel_max_yaw_); + // des_yaw_vel = drake::math::saturate(des_yaw_vel, -vel_max_yaw_, + // vel_max_yaw_); + des_yaw_vel = std::clamp(des_yaw_vel, -vel_max_yaw_, vel_max_yaw_); // Convex combination of 0 and desired yaw velocity double weight = 1 / (1 + exp(-params_of_no_turning_(0) * @@ -217,14 +222,17 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( des_sagital_vel = kp_pos_sagital_ * (local_com_pos_to_target_pos(0) + target_pos_offset_) + kd_pos_sagital_ * (-com_vel_sagital); - des_sagital_vel = drake::math::saturate(des_sagital_vel, -vel_max_sagital_, - vel_max_sagital_); + // des_sagital_vel = drake::math::saturate(des_sagital_vel, + // -vel_max_sagital_, + // vel_max_sagital_); + des_sagital_vel = + std::clamp(des_sagital_vel, -vel_max_sagital_, vel_max_sagital_); // Frontal plane position PD control. TODO(yminchen): tune this double com_vel_lateral = local_com_vel(1); des_lateral_vel = kp_pos_lateral_ * (local_com_pos_to_target_pos(1)) + kd_pos_lateral_ * (-com_vel_lateral); - des_lateral_vel = drake::math::saturate(des_lateral_vel, -vel_max_lateral_, + des_lateral_vel = std::clamp(des_lateral_vel, -vel_max_lateral_, vel_max_lateral_); } Vector3d des_vel; diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 0563775043..e87cb8cdba 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -8,6 +8,8 @@ using Eigen::MatrixXd; struct OSCRunningGains : OSCGains { + double controller_frequency; + double weight_scaling; double w_swing_toe; double swing_toe_kp; @@ -85,6 +87,7 @@ struct OSCRunningGains : OSCGains { template void Serialize(Archive* a) { OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(controller_frequency)); a->Visit(DRAKE_NVP(weight_scaling)); a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index d4af03d841..5eed4855f0 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,3 +1,6 @@ +# target_frequency Hz +controller_frequency: 500 + w_input: 0.000001 w_input_reg: 0.01 w_accel: 0.0001 @@ -30,8 +33,8 @@ ekf_filter_tau: [ 0.05, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -2 -vel_scale_trans_sagital: 1.0 -vel_scale_trans_lateral: -0.1 +vel_scale_trans_sagital: 2.0 +vel_scale_trans_lateral: -0.5 target_vel_filter_alpha: 0.001 # SLIP parameters @@ -40,8 +43,8 @@ rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 # max percent variance -stance_variance: 0.3 -flight_variance: 0.3 +stance_variance: 0.0 +flight_variance: 0.0 w_swing_toe: 0.01 swing_toe_kp: 1500 diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index b548c7d8b1..e10d3aae8f 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,4 +1,4 @@ -rho: 0.0001 +rho: 0.001 sigma: 1e-6 max_iter: 500 eps_abs: 1e-5 @@ -9,8 +9,8 @@ alpha: 1.6 linsys_solver: 0 delta: 1e-6 polish: 1 -polish_refine_iter: 0 -verbose: 0 +polish_refine_iter: 1 +verbose: 1 scaled_termination: 1 check_termination: 25 warm_start: 1 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 637add2b63..42dda60592 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -3,6 +3,7 @@ #include #include #include +#include #include "common/find_resource.h" #include "dairlib/lcmt_robot_input.hpp" @@ -155,9 +156,9 @@ int DoMain(int argc, char* argv[]) { osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; vector accumulated_state_durations; accumulated_state_durations.push_back(0); - for (double state_duration : state_durations) { + for (double state_duration: state_durations) { accumulated_state_durations.push_back(accumulated_state_durations.back() + - state_duration); + state_duration); } accumulated_state_durations.pop_back(); @@ -203,10 +204,10 @@ int DoMain(int argc, char* argv[]) { /// REGULARIZATION COSTS osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * - osc_gains.W_input_regularization); + osc_gains.W_input_regularization); osc->SetInputSmoothingConstraintWeights(osc_gains.w_input_accel); osc->SetInputCostWeights(osc_gains.w_input * - osc_gains.W_input_regularization); + osc_gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight( osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight( @@ -483,7 +484,7 @@ int DoMain(int argc, char* argv[]) { pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - if (osc_gains.rot_filter_tau > 0) { + if (osc_gains.rot_filter_tau>0) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {0, 1, 2}); } @@ -543,6 +544,9 @@ int DoMain(int argc, char* argv[]) { VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); + auto controller_frequency_regulator = + builder.AddSystem>(osc_gains.controller_frequency, + osc->get_osc_output_port().size()); osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem @@ -643,6 +647,10 @@ int DoMain(int argc, char* argv[]) { high_level_command->get_radio_input_port()); builder.Connect(osc->get_osc_output_port(), command_sender->get_input_port(0)); +// builder.Connect(osc->get_osc_output_port(), +// controller_frequency_regulator->get_input_port()); +// builder.Connect(controller_frequency_regulator->get_output_port(), +// command_sender->get_input_port(0)); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_osc_debug_port(), osc_debug_pub->get_input_port()); @@ -657,11 +665,21 @@ int DoMain(int argc, char* argv[]) { // Create the diagram auto owned_diagram = builder.Build(); owned_diagram->set_name(("osc_running_controller")); - // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); + +// std::cout << "waiting for messages" << std::endl; +// LcmHandleSubscriptionsUntil(&lcm, [&]() { +// return cassie_out_receiver->GetInternalMessageCount()>2; +// }); +// controller_frequency_regulator->LatchInputPortToState(&loop.get_diagram()->GetMutableSubsystemContext( +// *controller_frequency_regulator, +// &loop.get_diagram_mutable_context())); +// +// std::cout << "got message, starting simulator" << std::endl; +// loop.Simulate(); return 0; diff --git a/multibody/multibody_solvers.cc b/multibody/multibody_solvers.cc index cdecfb7d57..a93a9c3e83 100644 --- a/multibody/multibody_solvers.cc +++ b/multibody/multibody_solvers.cc @@ -1,6 +1,8 @@ #include "multibody/multibody_solvers.h" #include "multibody/multibody_utils.h" +#include + namespace dairlib { namespace multibody { @@ -151,7 +153,7 @@ template void MultibodyProgram::AddJointLimitConstraints(VectorXDecisionVariable q) { for (int i = 0; i < plant_.num_joints(); i++) { const auto& joint = plant_.get_joint(drake::multibody::JointIndex(i)); - if (joint.num_positions() > 0) { + if (joint.num_positions() == 1) { auto q_joint = q.segment(joint.position_start(), joint.num_positions()); AddConstraint(q_joint <= joint.position_upper_limits()); AddConstraint(q_joint >= joint.position_lower_limits()); diff --git a/solvers/nonlinear_constraint.h b/solvers/nonlinear_constraint.h index cdae0c1740..5f65743cbb 100644 --- a/solvers/nonlinear_constraint.h +++ b/solvers/nonlinear_constraint.h @@ -2,7 +2,7 @@ #include #include -#include "drake/common/symbolic.h" +#include "drake/common/symbolic/expression.h" #include "drake/solvers/constraint.h" namespace dairlib { diff --git a/systems/trajectory_optimization/dircon/dircon.h b/systems/trajectory_optimization/dircon/dircon.h index 6ac4ef9721..bdcf24ceaa 100644 --- a/systems/trajectory_optimization/dircon/dircon.h +++ b/systems/trajectory_optimization/dircon/dircon.h @@ -9,7 +9,7 @@ #include "systems/trajectory_optimization/dircon/dynamics_cache.h" #include "drake/common/drake_copyable.h" -#include "drake/common/symbolic.h" +#include "drake/common/symbolic/expression.h" #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/solvers/constraint.h" #include "drake/systems/trajectory_optimization/multiple_shooting.h" diff --git a/systems/trajectory_optimization/dircon/dircon_opt_constraints.h b/systems/trajectory_optimization/dircon/dircon_opt_constraints.h index b09c2d4405..340d93a7a9 100644 --- a/systems/trajectory_optimization/dircon/dircon_opt_constraints.h +++ b/systems/trajectory_optimization/dircon/dircon_opt_constraints.h @@ -7,7 +7,7 @@ #include "systems/trajectory_optimization/dircon/dircon_mode.h" #include "systems/trajectory_optimization/dircon/dynamics_cache.h" #include "drake/common/drake_copyable.h" -#include "drake/common/symbolic.h" +#include "drake/common/symbolic/expression.h" #include "drake/solvers/constraint.h" #include "drake/systems/trajectory_optimization/multiple_shooting.h" diff --git a/systems/trajectory_optimization/dircon_opt_constraints.h b/systems/trajectory_optimization/dircon_opt_constraints.h index 9c233857a7..69b2be05df 100644 --- a/systems/trajectory_optimization/dircon_opt_constraints.h +++ b/systems/trajectory_optimization/dircon_opt_constraints.h @@ -8,7 +8,7 @@ #include "systems/trajectory_optimization/dircon_kinematic_data.h" #include "systems/trajectory_optimization/dircon_kinematic_data_set.h" #include "drake/common/drake_copyable.h" -#include "drake/common/symbolic.h" +#include "drake/common/symbolic/expression.h" #include "drake/solvers/constraint.h" #include "drake/systems/trajectory_optimization/multiple_shooting.h" diff --git a/systems/trajectory_optimization/hybrid_dircon.h b/systems/trajectory_optimization/hybrid_dircon.h index 6c0502e363..98796905de 100644 --- a/systems/trajectory_optimization/hybrid_dircon.h +++ b/systems/trajectory_optimization/hybrid_dircon.h @@ -11,7 +11,7 @@ #include "systems/trajectory_optimization/dircon_options.h" #include "drake/common/drake_copyable.h" -#include "drake/common/symbolic.h" +#include "drake/common/symbolic/expression.h" #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/solvers/constraint.h" #include "drake/systems/framework/context.h" From 0f647593db906ee013b77069660da7cb1b5745d3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 8 Dec 2022 11:12:29 -0500 Subject: [PATCH 325/758] updating visualization script --- examples/Cassie/director_scripts/show_time_hardware.py | 2 +- examples/Cassie/director_scripts/show_time_sim.py | 2 +- examples/Cassie/osc_run/osc_running_gains.yaml | 8 ++++---- solvers/nonlinear_cost.h | 2 +- 4 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/director_scripts/show_time_hardware.py b/examples/Cassie/director_scripts/show_time_hardware.py index e123096cd9..a145ab05c5 100644 --- a/examples/Cassie/director_scripts/show_time_hardware.py +++ b/examples/Cassie/director_scripts/show_time_hardware.py @@ -55,7 +55,7 @@ def set_enabled(self, enable): def handle_message(self, msg): msg_time = msg.utime * 1e-6 # convert from microseconds pelvis_height = (msg.position)[6] # convert from microseconds - pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[4:6]) # convert from microseconds # pelvis_height = (msg.position)[2] # convert from microseconds # pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds self._real_time.append(time.time()) diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 0ed188c336..633297456f 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -55,7 +55,7 @@ def handle_message(self, msg): msg_time = msg.utime * 1e-6 # convert from microseconds # Drake Sim pelvis_height = (msg.position)[6] # convert from microseconds - pelvis_velocity = np.linalg.norm((msg.velocity)[3:4]) # convert from microseconds + pelvis_velocity = np.linalg.norm((msg.velocity)[3:5]) # convert from microseconds # pelvis_height = (msg.position)[2] # convert from microseconds # pelvis_velocity = np.linalg.norm((msg.velocity)[0:2]) # convert from microseconds self._real_time.append(time.time()) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 5eed4855f0..863625e1df 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -32,10 +32,10 @@ rot_filter_tau: 0.005 ekf_filter_tau: [ 0.05, 0.01, 0.001 ] # High level command gains (with radio) -vel_scale_rot: -2 -vel_scale_trans_sagital: 2.0 +vel_scale_rot: -4 +vel_scale_trans_sagital: 6 vel_scale_trans_lateral: -0.5 -target_vel_filter_alpha: 0.001 +target_vel_filter_alpha: 0.01 # SLIP parameters rest_length: 0.85 @@ -57,7 +57,7 @@ hip_yaw_kd: 5 #footstep_offset: -0.05 footstep_sagital_offset: -0.03 footstep_lateral_offset: 0.06 # drake -mid_foot_height: 0.15 +mid_foot_height: 0.2 FootstepKd: [ 0.01, 0, 0, 0, 0.3, 0, diff --git a/solvers/nonlinear_cost.h b/solvers/nonlinear_cost.h index 94284415ac..6fc2d45f7a 100644 --- a/solvers/nonlinear_cost.h +++ b/solvers/nonlinear_cost.h @@ -2,7 +2,7 @@ #include #include -#include "drake/common/symbolic.h" +#include "drake/common/symbolic/expression.h" #include "drake/solvers/cost.h" namespace dairlib { From 9b5f98739edd69bb341257caf7d4d90357ce6d88 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 12 Dec 2022 13:27:04 -0500 Subject: [PATCH 326/758] updating gains from sim --- examples/Cassie/osc_run/osc_running_gains.yaml | 10 +++++----- examples/Cassie/osc_run/osc_running_qp_settings.yaml | 4 ++-- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 863625e1df..7b944100e0 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,10 +1,10 @@ # target_frequency Hz -controller_frequency: 500 +controller_frequency: 1000 w_input: 0.000001 w_input_reg: 0.01 w_accel: 0.0001 -w_soft_constraint: 1000 +w_soft_constraint: 100 w_lambda: 0.1 w_input_accel: 0.1 w_joint_limit: 0 @@ -44,7 +44,7 @@ stance_duration: 0.3 flight_duration: 0.09 # max percent variance stance_variance: 0.0 -flight_variance: 0.0 +flight_variance: 0.1 w_swing_toe: 0.01 swing_toe_kp: 1500 @@ -56,7 +56,7 @@ hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.03 -footstep_lateral_offset: 0.06 # drake +footstep_lateral_offset: 0.03 # drake mid_foot_height: 0.2 FootstepKd: [ 0.01, 0, 0, @@ -69,7 +69,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 40, 0, - 0, 0, 155] + 0, 0, 125] PelvisKd: [ 0, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index e10d3aae8f..9ec13c9f16 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.001 sigma: 1e-6 -max_iter: 500 +max_iter: 250 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 @@ -10,7 +10,7 @@ linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 1 -verbose: 1 +verbose: 0 scaled_termination: 1 check_termination: 25 warm_start: 1 From 2aa23ef6dc667f8db65c995d614b8581e89454a0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 12 Dec 2022 17:45:52 -0500 Subject: [PATCH 327/758] fixed bug in tracking cost logging --- .../analysis/cassie_plotting_utils.py | 4 +- .../pydairlib/analysis/log_plotter_cassie.py | 2 +- .../pydairlib/analysis/mbp_plotting_utils.py | 2 + bindings/pydairlib/analysis/osc_debug.py | 6 +-- .../plot_configs/cassie_default_plot.yaml | 7 +-- .../plot_configs/cassie_running_plot.yaml | 4 +- .../osc/operational_space_control.cc | 52 +++++++++---------- 7 files changed, 38 insertions(+), 39 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 8c00056066..700abb3a44 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -50,10 +50,10 @@ def make_plant_and_context(floating_base=True, springs=True): plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) if springs: AddCassieMultibody(plant, scene_graph, - floating_base, cassie_urdf, True, True) + floating_base, cassie_urdf, True, True, True) else: AddCassieMultibody(plant, scene_graph, - floating_base, cassie_urdf_no_springs, False, True) + floating_base, cassie_urdf_no_springs, False, True, True) plant.Finalize() return plant, plant.CreateDefaultContext() diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index ac82184cf4..fb9090abf3 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -124,7 +124,7 @@ def main(): if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plt.ylim([0, 1e4]) + # plt.ylim([0, 1e4]) if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 84f9a12178..986bf273c3 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -437,6 +437,8 @@ def plot_tracking_costs(osc_debug, time_slice): data_dict = \ {key: val for key, val in osc_debug['tracking_cost'].items()} data_dict['t_osc'] = osc_debug['t_osc'] + # import pdb; pdb.set_trace() + # data_dict['t_osc'] = osc_debug['trac'] plotting_utils.make_plot( data_dict, 't_osc', diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 52abf035d7..59d874f384 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -76,9 +76,9 @@ def append(self, tracking_data_list, tracking_cost_list): for name, cost in zip(tracking_data_list, tracking_cost_list): self.tracking_costs[name].append(cost) - # for name in self.tracking_costs: - # if name not in tracking_data_list: - # self.tracking_costs[name].append(0.0) + for name in self.tracking_costs: + if name not in tracking_data_list: + self.tracking_costs[name].append(0.0) def convertToNP(self): for name in self.tracking_costs: diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml index f260a10bd8..b96dee5762 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml @@ -36,10 +36,11 @@ pt_on_foot_to_plot: 'mid' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true -plot_tracking_costs: false +plot_tracking_costs: true plot_qp_solutions: true plot_qp_solve_time: true plot_active_tracking_datas: false tracking_datas_to_plot: - alip_com_traj: { 'dims': [ 0, 1 ], 'derivs': [ 'vel' ] } - swing_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'accel' ] } +# alip_com_traj: { 'dims': [ 0, 1 ], 'derivs': [ 'vel' ] } +# swing_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'pos', 'accel' ] } + left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] } diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index f4c8338d46..e17561db68 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 2 -duration: 6 +start_time: 4 +duration: -1 # Plant properties use_springs: true diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index d3f88a855d..0fe92a7579 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -492,7 +492,7 @@ void OperationalSpaceControl::Build() { // .get(); for (int i = -1; i < 5; ++i) { -// solvers_[i] = std::make_unique(); + // solvers_[i] = std::make_unique(); solvers_[i] = std::make_unique(); } prog_->SetSolverOptions(solver_options_); @@ -711,7 +711,7 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd constant_term = (JdotV_t - ddy_t); tracking_costs_.at(i)->UpdateCoefficients( - J_t.transpose() * W * J_t, J_t.transpose() * W * (JdotV_t - ddy_t), + 2 * J_t.transpose() * W * J_t, 2 * J_t.transpose() * W * (JdotV_t - ddy_t), constant_term.transpose() * W * constant_term, true); } else { tracking_costs_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), @@ -791,14 +791,14 @@ VectorXd OperationalSpaceControl::SolveQp( VectorXd::Zero(n_h_)); } -// if (!solvers_.at(0)->IsInitialized()) { -// solvers_.at(0)->InitializeSolver(*prog_, solver_options_); -// } -// -// if (initial_guess_x_.count(0) > 0) { -// solvers_.at(0)->WarmStart(initial_guess_x_.at(0), -// initial_guess_y_.at(0)); -// } + // if (!solvers_.at(0)->IsInitialized()) { + // solvers_.at(0)->InitializeSolver(*prog_, solver_options_); + // } + // + // if (initial_guess_x_.count(0) > 0) { + // solvers_.at(0)->WarmStart(initial_guess_x_.at(0), + // initial_guess_y_.at(0)); + // } // Solve the QP MathematicalProgramResult result; @@ -846,7 +846,6 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( int row_start = 0; for (unsigned int i = 0; i < all_contacts_.size(); i++) { if (next_contact_set.find(i) != next_contact_set.end()) { - // std::cout << i << std::endl; J_next.block(row_start, 0, kSpaceDim, n_v_) = all_contacts_[i]->EvalFullJacobian(*context_wo_spr_); row_start += kSpaceDim; @@ -1021,20 +1020,18 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; -// output->tracking_data = -// std::vector(tracking_data_vec_->size()); -// output->tracking_costs = std::vector(tracking_data_vec_->size()); -// output->tracking_data_names = -// std::vector(tracking_data_vec_->size()); - output->tracking_data = - std::vector(); + // output->tracking_data = + // std::vector(tracking_data_vec_->size()); + // output->tracking_costs = std::vector(tracking_data_vec_->size()); + // output->tracking_data_names = + // std::vector(tracking_data_vec_->size()); + output->tracking_data = std::vector(); output->tracking_costs = std::vector(); - output->tracking_data_names = - std::vector(); + output->tracking_data_names = std::vector(); for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i).get(); -// output->tracking_data_names[i] = tracking_data->GetName(); + // output->tracking_data_names[i] = tracking_data->GetName(); lcmt_osc_tracking_data osc_output; osc_output.y_dim = tracking_data->GetYDim(); @@ -1051,7 +1048,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command = std::vector(osc_output.ydot_dim); osc_output.yddot_command_sol = std::vector(osc_output.ydot_dim); -// output->tracking_costs[i] = 0; + // output->tracking_costs[i] = 0; if (tracking_data->IsActive(fsm_state) && time_since_last_state_switch >= t_s_vec_.at(i) && @@ -1072,18 +1069,17 @@ void OperationalSpaceControl::AssignOscLcmOutput( CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); VectorXd y_tracking_cost = VectorXd::Zero(1); - tracking_costs_[i]->Eval(*dv_sol_, &y_tracking_cost); -// output->tracking_costs[i] = y_tracking_cost[0]; -// total_cost += output->tracking_costs[i]; + tracking_costs_.at(i)->Eval(*dv_sol_, &y_tracking_cost); total_cost += y_tracking_cost[0]; output->tracking_costs.push_back(y_tracking_cost[0]); output->tracking_data.push_back(osc_output); output->tracking_data_names.push_back(tracking_data->GetName()); + } else { + output->tracking_costs.push_back(0); + output->tracking_data.push_back(osc_output); + output->tracking_data_names.push_back(tracking_data->GetName()); } -// output->tracking_data[i] = osc_output; } - // output->regularization_costs.push_back(total_cost); - // output->regularization_cost_names.push_back("total_cost"); *u_prev_ = *u_sol_; output->num_tracking_data = output->tracking_data_names.size(); From b0c017994fbdc888bb4109e727d6f700ae00581d Mon Sep 17 00:00:00 2001 From: dair Date: Tue, 13 Dec 2022 10:03:50 -0500 Subject: [PATCH 328/758] changing initial standing pose --- examples/Cassie/director_scripts/cassie_operator.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/director_scripts/cassie_operator.py b/examples/Cassie/director_scripts/cassie_operator.py index 7e0324435a..a715593f33 100644 --- a/examples/Cassie/director_scripts/cassie_operator.py +++ b/examples/Cassie/director_scripts/cassie_operator.py @@ -34,7 +34,7 @@ # Set of gains with which COM is within support polygon when we lower the hoist -joint_default = [-0.01, .01, 0, 0, 0.55, 0.55, -1.5, -1.5, -1.8, -1.8] +joint_default = [0.05, -.05, 0, 0, 0.55, 0.55, -1.5, -1.5, -1.8, -1.8] kp_default = [80, 80, 50, 50, 50, 50, 50, 50, 10, 10] kd_default = [1, 1, 1, 1, 1, 1, 2, 2, 1, 1] From 98516d14b16da193872cd1eaab84c6e4c278e0d3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 20 Dec 2022 11:21:41 -0500 Subject: [PATCH 329/758] updating acceleration target --- .../plot_configs/cassie_running_plot.yaml | 2 +- examples/Cassie/osc/high_level_command.cc | 10 +++--- .../Cassie/osc_run/osc_running_gains.yaml | 6 ++-- .../osc_run/pelvis_trans_traj_generator.cc | 32 +++++++++++++------ 4 files changed, 30 insertions(+), 20 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index e17561db68..b72cdfb5b8 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,7 +6,7 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 4 +start_time: 0 duration: -1 # Plant properties diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index d37b5566c2..4b430a3731 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -119,10 +119,8 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( double vel_scale_trans_sagital = (radio_out->channel[6] + 1.0) * vel_scale_trans_sagital_; - double a = - .001 / - (stick_filter_dt_ + - .001); // approximately 1KHz sampling rate - no need to be too precise + // approximately 1KHz sampling rate - no need to be too precise + double a = .001 / (stick_filter_dt_ + .001); Vector3d des_vel_prev = discrete_state->get_value(des_vel_idx_); Vector3d des_vel; // des_vel << vel_scale_rot_ * radio_out->channel[3], @@ -232,8 +230,8 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( double com_vel_lateral = local_com_vel(1); des_lateral_vel = kp_pos_lateral_ * (local_com_pos_to_target_pos(1)) + kd_pos_lateral_ * (-com_vel_lateral); - des_lateral_vel = std::clamp(des_lateral_vel, -vel_max_lateral_, - vel_max_lateral_); + des_lateral_vel = + std::clamp(des_lateral_vel, -vel_max_lateral_, vel_max_lateral_); } Vector3d des_vel; des_vel << desired_filtered_yaw_vel, des_sagital_vel, des_lateral_vel; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 7b944100e0..c424b549d9 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,7 +4,7 @@ controller_frequency: 1000 w_input: 0.000001 w_input_reg: 0.01 w_accel: 0.0001 -w_soft_constraint: 100 +w_soft_constraint: 1000 w_lambda: 0.1 w_input_accel: 0.1 w_joint_limit: 0 @@ -43,7 +43,7 @@ rest_length_offset: 0.025 stance_duration: 0.3 flight_duration: 0.09 # max percent variance -stance_variance: 0.0 +stance_variance: 0.1 flight_variance: 0.1 w_swing_toe: 0.01 @@ -69,7 +69,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 40, 0, - 0, 0, 125] + 0, 0, 150] PelvisKd: [ 0, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 6acc6ec391..57dd4d0bbb 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -1,11 +1,12 @@ #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" +#include + #include "multibody/multibody_utils.h" #include "systems/framework/output_vector.h" #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" -#include using std::string; using std::vector; @@ -90,7 +91,8 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( return PiecewisePolynomial(); } - Vector3d f_g = {0, 0, -9.81}; +// Vector3d f_g = {0, 0, -9.81}; + Vector3d f_g = drake::multibody::UniformGravityFieldElement().gravity_vector(); Vector3d foot_pos = Vector3d::Zero(); Vector3d pelvis_pos = Vector3d::Zero(); Vector3d pelvis_vel = Vector3d::Zero(); @@ -108,9 +110,10 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( double compression = leg_length.norm() - rest_length_; Vector3d f_leg = k_leg_ * compression * leg_length.normalized() + b_leg_ * pelvis_vel; - VectorXd rddot = f_g + f_leg; +// Vector3d rddot = f_g + f_leg; + Vector3d rddot = f_g; - // double dt = 1e-3; + double dt = 1e-3; Eigen::Vector2d breaks; // if (t <= 0.3) { // breaks << 0, 0.25, 0.4; @@ -121,8 +124,8 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( MatrixXd samples(3, 2); MatrixXd samples_dot(3, 2); -// std::cout << "t0:" << t0 << std::endl; -// std::cout << "tf:" << tf << std::endl; + // std::cout << "t0:" << t0 << std::endl; + // std::cout << "tf:" << tf << std::endl; // samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; // samples_dot << pelvis_vel, pelvis_vel + rddot * dt; @@ -134,11 +137,20 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( } else if (fsm_state == 1) { y_dist_des = 0.1; } -// samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + rest_length_offset_; - samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_; -// samples_dot << 0, 0, 0, 0, 0.25, 0.0; + // samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + + // rest_length_offset_; + + samples << 0, 0 + 0.5 * rddot[0] * dt * dt, + y_dist_des, y_dist_des + 0.5 * rddot[1] * dt * dt, + rest_length_, rest_length_ + 0.5 * rddot[2] * dt * dt; + samples_dot << 0, 0 + rddot[0] * dt, + 0, 0 + rddot[1] * dt, + 0, 0 + rddot[2] * dt; // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); - return PiecewisePolynomial::FirstOrderHold(breaks, samples); + + // return PiecewisePolynomial::FirstOrderHold(breaks, samples); + return PiecewisePolynomial::CubicHermite(breaks, samples, samples_dot); + // return PiecewisePolynomial::CubicHermite( // breaks, samples, samples_dot); // return PiecewisePolynomial::CubicShapePreserving(breaks, samples); From e7a51924d93904d972141ff5c05124e9744af44b Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 9 Jan 2023 14:13:59 -0500 Subject: [PATCH 330/758] adding long jump gait --- .../Cassie/osc_jump/osc_jumping_gains.yaml | 8 +- examples/Cassie/run_dircon_jumping.cc | 130 +++++++++++------- .../cassie_fixed_springs_conservative.urdf | 20 +-- 3 files changed, 95 insertions(+), 63 deletions(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index e37ffc1137..0f0fa6d586 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,6 +1,6 @@ -w_input: 0.000 -w_lambda: 0.000 -w_accel: 0.0000001 +w_input: 0.000001 +w_lambda: 0.1 +w_accel: 0.0001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, @@ -13,7 +13,7 @@ W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.1, 0.01] W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -w_input_reg: 0.001 +w_input_reg: 0.01 w_soft_constraint: 100 x_offset: 0.0 relative_feet: true diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 487b3de7c9..82c2b414ff 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -65,6 +65,7 @@ using drake::solvers::MatrixXDecisionVariable; using drake::solvers::SolutionResult; using drake::solvers::VectorXDecisionVariable; using drake::systems::trajectory_optimization::MultipleShooting; +using drake::trajectories::PiecewisePolynomial; DEFINE_int32(knot_points, 10, "Number of knot points per contact mode"); DEFINE_double(height, 0.2, "Target height for jumping."); @@ -96,6 +97,7 @@ DEFINE_double(actuator_limit, 1.0, "is at the actual actuator limits."); DEFINE_double(input_delta, 50.0, "Maximum change in torques between knot points."); +DEFINE_double(ipopt_iter, 50, "Maximum iterations for IPOPT."); namespace dairlib { @@ -108,11 +110,14 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, void AddCostsSprings(Dircon* trajopt, const MultibodyPlant& plant, DirconModeSequence*); -void SetInitialGuessFromTrajectory( +void SetInitialGuessFromDirconTrajectory( Dircon& trajopt, const MultibodyPlant& plant, const string& filepath, bool same_knot_points = false, Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); +void SetInitialGuessFromKCTrajectory(Dircon& trajopt, + const string& filepath); + class JointAccelCost : public solvers::NonlinearCost { public: JointAccelCost(const MatrixXd& W_Q, @@ -261,26 +266,26 @@ void DoMain() { /**** * Mode duration constraints */ - // auto crouch_mode = DirconMode(double_stance_constraints, - // stance_knotpoints, 0.5, 0.75); - // auto flight_mode = DirconMode(flight_phase_constraints, - // flight_phase_knotpoints, 0.25, 0.5); - // auto land_mode = DirconMode(double_stance_constraints, - // stance_knotpoints, 0.4, 0.6); auto crouch_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 1.0, 2.0); + stance_knotpoints, 0.86, 0.86); auto flight_mode = DirconMode(flight_phase_constraints, - flight_phase_knotpoints, 0.2, 2.0); + flight_phase_knotpoints, 0.4, 0.4); auto land_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.4, 1.0); + stance_knotpoints, 1.2875, 1.2875); + // auto crouch_mode = DirconMode(double_stance_constraints, + // stance_knotpoints, 0.1, 2.0); + // auto flight_mode = DirconMode(flight_phase_constraints, + // flight_phase_knotpoints, 0.1, 2.0); + // auto land_mode = DirconMode(double_stance_constraints, + // stance_knotpoints, 0.1, 1.0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); - crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 0); + // crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 0); crouch_mode.MakeConstraintRelative(left_heel_eval_ind, 1); crouch_mode.MakeConstraintRelative(right_toe_eval_ind, 0); crouch_mode.MakeConstraintRelative(right_toe_eval_ind, 1); - crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 0); + // crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 0); crouch_mode.MakeConstraintRelative(right_heel_eval_ind, 1); land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); @@ -324,7 +329,7 @@ void DoMain() { solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); // NOLINT solver_options.SetOption(id, "acceptable_tol", 1e2); // NOLINT solver_options.SetOption(id, "acceptable_iter", 5); // NOLINT - solver_options.SetOption(id, "max_iter", 50); // NOLINT + solver_options.SetOption(id, "max_iter", (int)FLAGS_ipopt_iter); // NOLINT } else { // Snopt settings @@ -377,9 +382,14 @@ void DoMain() { if (!FLAGS_load_filename.empty()) { std::cout << "Loading: " << FLAGS_load_filename << std::endl; - SetInitialGuessFromTrajectory(trajopt, plant, - FLAGS_data_directory + FLAGS_load_filename, - FLAGS_same_knotpoints, spr_map); + if (FLAGS_load_filename.find("kc") != -1) { + SetInitialGuessFromKCTrajectory( + trajopt, FLAGS_data_directory + FLAGS_load_filename); + } else { + SetInitialGuessFromDirconTrajectory( + trajopt, plant, FLAGS_data_directory + FLAGS_load_filename, + FLAGS_same_knotpoints, spr_map); + } } double alpha = .2; @@ -651,11 +661,11 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_y_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - 0.1 * VectorXd::Ones(1), 0.2 * VectorXd::Ones(1)); + 0.05 * VectorXd::Ones(1), 0.2 * VectorXd::Ones(1)); auto right_foot_y_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - -0.2 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + -0.2 * VectorXd::Ones(1), -0.05 * VectorXd::Ones(1)); auto left_foot_z_ground_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), @@ -762,13 +772,13 @@ void SetKinematicConstraints(Dircon* trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - for (int index = 0; index < (mode_lengths[0] - 2); index++) { - auto lambda = trajopt->force_vars(0, index); - prog->AddLinearConstraint(lambda(2) >= 60); - prog->AddLinearConstraint(lambda(5) >= 60); - prog->AddLinearConstraint(lambda(8) >= 60); - prog->AddLinearConstraint(lambda(11) >= 60); - } +// for (int index = 0; index < (mode_lengths[0] - 2); index++) { +// auto lambda = trajopt->force_vars(0, index); +// prog->AddLinearConstraint(lambda(2) >= 60); +// prog->AddLinearConstraint(lambda(5) >= 60); +// prog->AddLinearConstraint(lambda(8) >= 60); +// prog->AddLinearConstraint(lambda(11) >= 60); +// } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); @@ -836,12 +846,12 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, x(vel_map.at(sym_joint_name + l_r_pair.second + "dot")); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - if (sym_joint_name != "ankle_joint") { - auto act_diff = - u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - - u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); - trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } + // if (sym_joint_name != "ankle_joint") { + // auto act_diff = + // u(act_map.at(sym_joint_name + l_r_pair.first + "_motor")) - + // u(act_map.at(sym_joint_name + l_r_pair.second + "_motor")); + // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + // } } } for (const auto& l_r_pair : l_r_pairs) { @@ -852,12 +862,12 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, x(vel_map.at(asy_joint_name + l_r_pair.second + "dot")); trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - if (asy_joint_name != "ankle_joint") { - auto act_diff = - u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + - u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); - trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); - } + // if (asy_joint_name != "ankle_joint") { + // auto act_diff = + // u(act_map.at(asy_joint_name + l_r_pair.first + "_motor")) + + // u(act_map.at(asy_joint_name + l_r_pair.second + "_motor")); + // trajopt->AddRunningCost(w_symmetry_u * act_diff * act_diff); + // } } } @@ -897,6 +907,8 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, MatrixXd Q_left = FLAGS_cost_scaling * MatrixXd::Identity(4, 4); MatrixXd Q_right = FLAGS_cost_scaling * MatrixXd::Identity(3, 3); + Q_left(2, 2) = FLAGS_cost_scaling * 1e2; + Q_right(2, 2) = FLAGS_cost_scaling * 1e2; trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); trajopt->AddRunningCost((x.segment(6, 4) - q_f_target_left).transpose() * @@ -908,8 +920,8 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, FLAGS_knot_points}; MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); - W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 5e1; - W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 5e1; + W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 1e2; + W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 1e2; W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; @@ -1021,11 +1033,11 @@ void AddCostsSprings(Dircon* trajopt, } } -void SetInitialGuessFromTrajectory(Dircon& trajopt, - const MultibodyPlant& plant, - const string& filepath, - bool same_knot_points, - Eigen::MatrixXd spr_map) { +void SetInitialGuessFromDirconTrajectory(Dircon& trajopt, + const MultibodyPlant& plant, + const string& filepath, + bool same_knot_points, + Eigen::MatrixXd spr_map) { DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); if (same_knot_points) { trajopt.prog().SetInitialGuessForAllVariables( @@ -1045,11 +1057,31 @@ void SetInitialGuessFromTrajectory(Dircon& trajopt, auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); trajopt.SetInitialTrajectory(input_traj, state_traj); - // for (int mode = 0; mode < trajopt.num_modes(); ++mode) { - // trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], - // lambda_c_traj[mode], - // gamma_traj[mode]); - // } + for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], + lambda_c_traj[mode], gamma_traj[mode]); + } +} + +void SetInitialGuessFromKCTrajectory(Dircon& trajopt, + const string& filepath) { + LcmTrajectory previous_traj = LcmTrajectory(filepath); + + const auto state_traj_block = previous_traj.GetTrajectory("state_traj"); + const auto lambda_traj_block = + previous_traj.GetTrajectory("contact_force_traj"); + auto state_traj = PiecewisePolynomial::FirstOrderHold( + state_traj_block.time_vector, state_traj_block.datapoints); + auto input_traj = PiecewisePolynomial::ZeroOrderHold( + state_traj_block.time_vector, + MatrixXd::Zero(10, state_traj_block.time_vector.size())); + auto lambda_traj = PiecewisePolynomial::FirstOrderHold( + lambda_traj_block.time_vector, lambda_traj_block.datapoints); + + trajopt.SetInitialTrajectory(input_traj, state_traj); + trajopt.SetInitialForceTrajectory(0, lambda_traj); + trajopt.SetInitialForceTrajectory(1, lambda_traj); + trajopt.SetInitialForceTrajectory(2, lambda_traj); } } // namespace dairlib diff --git a/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf index 904add7e7b..6c3196f40b 100644 --- a/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf +++ b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf @@ -617,7 +617,7 @@ - + @@ -626,7 +626,7 @@ - + @@ -636,7 +636,7 @@ - + @@ -645,7 +645,7 @@ - + @@ -655,7 +655,7 @@ - + @@ -664,7 +664,7 @@ - + @@ -673,7 +673,7 @@ - + @@ -682,7 +682,7 @@ - + @@ -791,7 +791,7 @@ - + @@ -800,7 +800,7 @@ - + From 85591a3062ba9113e89370086a4d876c0c7ce6f1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 9 Jan 2023 14:38:29 -0500 Subject: [PATCH 331/758] cleaning up running files --- .../contact_scheduler/contact_scheduler.cc | 23 +++++++------- .../osc_running_controller_diagram.cc | 4 +-- .../Cassie/osc_run/foot_traj_generator.cc | 25 +++++++--------- examples/Cassie/osc_run/foot_traj_generator.h | 3 +- examples/Cassie/run_dircon_jumping.cc | 30 ++++++++++--------- examples/Cassie/run_osc_running_controller.cc | 4 +-- 6 files changed, 42 insertions(+), 47 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index e8ae86ebda..8fb27b700c 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -3,8 +3,6 @@ #include #include -#include - #include "common/eigen_utils.h" #include "examples/Cassie/cassie_utils.h" #include "multibody/multibody_utils.h" @@ -103,12 +101,12 @@ EventStatus ContactScheduler::UpdateTransitionTimes( auto stored_fsm_state = (RUNNING_FSM_STATE)state->get_mutable_discrete_state( stored_fsm_state_index_)[0]; - double stored_transition_time = - state->get_discrete_state(stored_transition_time_index_)[0]; - double nominal_stance_duration = - state->get_discrete_state(nominal_state_durations_index_)[0]; - double nominal_flight_duration = - state->get_discrete_state(nominal_state_durations_index_)[1]; +// double stored_transition_time = +// state->get_discrete_state(stored_transition_time_index_)[0]; +// double nominal_stance_duration = +// state->get_discrete_state(nominal_state_durations_index_)[0]; +// double nominal_flight_duration = +// state->get_discrete_state(nominal_state_durations_index_)[1]; auto transition_times = state->get_mutable_discrete_state(transition_times_index_) .get_mutable_value(); @@ -180,8 +178,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // TODO(yangwill): calculate end of stance duration double stance_scale = (rest_length_) / (pelvis_z); - stance_scale = drake::math::saturate(stance_scale, 1 - stance_variance_, - 1 + stance_variance_); + stance_scale = + std::clamp(stance_scale, 1 - stance_variance_, 1 + stance_variance_); double next_transition_time = stored_transition_time + stance_scale * stance_duration_; // double next_transition_time = stored_transition_time + @@ -202,7 +200,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; } } else { - // set default to minimum touchdown time in case pelvis is below rest length + // set default to minimum touchdown time in case pelvis is below rest + // length double time_to_touchdown = (1 - flight_variance_) * flight_duration_; if (pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z) > 0) { time_to_touchdown = @@ -210,7 +209,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( 2 * g * (rest_length_ - pelvis_z))) / g; } - double time_to_touchdown_saturated = drake::math::saturate( + double time_to_touchdown_saturated = std::clamp( time_to_touchdown, (1 - flight_variance_) * flight_duration_, (1 + flight_variance_) * flight_duration_); double next_transition_time = diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 152b609a03..5fe57435d0 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -230,10 +230,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.rest_length, osc_running_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_left", "pelvis", - osc_running_gains.relative_feet, LEFT_STANCE); + LEFT_STANCE); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", - osc_running_gains.relative_feet, RIGHT_STANCE); + RIGHT_STANCE); l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 22c09ebc55..4b66be37a2 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -2,8 +2,6 @@ #include -#include - #include "dairlib/lcmt_radio_out.hpp" #include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include "multibody/multibody_utils.h" @@ -34,19 +32,17 @@ namespace dairlib::examples::osc_run { FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, Context* context, const string& foot_name, - const string& hip_name, bool relative_feet, + const string& hip_name, const int stance_state) : plant_(plant), context_(context), world_(plant.world_frame()), foot_frame_(plant.GetFrameByName(foot_name)), hip_frame_(plant.GetFrameByName(hip_name)), - relative_feet_(relative_feet), stance_state_(stance_state) { PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; - target_vel_filter_ = - std::make_unique(1.0, 2); + target_vel_filter_ = std::make_unique(1.0, 2); if (foot_name == "toe_left") { is_left_foot_ = true; @@ -156,12 +152,11 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( this->template EvalVectorInput(context, state_port_); const auto desired_pelvis_vel_xy = this->EvalVectorInput(context, target_vel_port_)->get_value(); - double clock = this->EvalVectorInput(context, clock_port_)->get_value()(0); const auto& mode_lengths = this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); - double pelvis_t0 = mode_lengths[0]; - double pelvis_tf = mode_lengths[1]; +// double pelvis_t0 = mode_lengths[0]; +// double pelvis_tf = mode_lengths[1]; double left_t0 = mode_lengths[2]; double left_tf = mode_lengths[3]; double right_t0 = mode_lengths[4]; @@ -243,16 +238,16 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( // corrections if (is_left_foot_) { // Y[1](1) -= lateral_offset_; - Y[1](1) = drake::math::saturate(Y[1](1), lateral_offset_, 0.2); - Y[2](1) = drake::math::saturate(Y[2](1), lateral_offset_, 0.2); + Y[1](1) = std::clamp(Y[1](1), lateral_offset_, 0.2); + Y[2](1) = std::clamp(Y[2](1), lateral_offset_, 0.2); } else { // Y[1](1) += lateral_offset_; - Y[1](1) = drake::math::saturate(Y[1](1), -0.2, -lateral_offset_); - Y[2](1) = drake::math::saturate(Y[2](1), -0.2, -lateral_offset_); + Y[1](1) = std::clamp(Y[1](1), -0.2, -lateral_offset_); + Y[2](1) = std::clamp(Y[2](1), -0.2, -lateral_offset_); } - Y[1](0) = drake::math::saturate(Y[1](0), -0.4, 0.4); - Y[2](0) = drake::math::saturate(Y[2](0), -0.4, 0.4); + Y[1](0) = std::clamp(Y[1](0), -0.4, 0.4); + Y[2](0) = std::clamp(Y[2](0), -0.4, 0.4); PiecewisePolynomial swing_foot_spline = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index dd94a84218..c255189ed3 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -15,7 +15,7 @@ class FootTrajGenerator : public drake::systems::LeafSystem { FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, const std::string& foot_name, const std::string& hip_name, - bool relative_feet, int stance_state); + int stance_state); const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); @@ -82,7 +82,6 @@ class FootTrajGenerator : public drake::systems::LeafSystem { Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(3, 3); bool is_left_foot_; - bool relative_feet_; int stance_state_; drake::systems::InputPortIndex state_port_; diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 82c2b414ff..e055b78934 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -290,16 +290,16 @@ void DoMain() { land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); land_mode.MakeConstraintRelative(left_toe_eval_ind, 1); - // land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); land_mode.MakeConstraintRelative(left_heel_eval_ind, 0); land_mode.MakeConstraintRelative(left_heel_eval_ind, 1); - // land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); land_mode.MakeConstraintRelative(right_toe_eval_ind, 0); land_mode.MakeConstraintRelative(right_toe_eval_ind, 1); - // land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); land_mode.MakeConstraintRelative(right_heel_eval_ind, 0); land_mode.MakeConstraintRelative(right_heel_eval_ind, 1); - // land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); auto all_modes = DirconModeSequence(plant); all_modes.AddMode(&crouch_mode); @@ -329,7 +329,7 @@ void DoMain() { solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); // NOLINT solver_options.SetOption(id, "acceptable_tol", 1e2); // NOLINT solver_options.SetOption(id, "acceptable_iter", 5); // NOLINT - solver_options.SetOption(id, "max_iter", (int)FLAGS_ipopt_iter); // NOLINT + solver_options.SetOption(id, "max_iter", (int)FLAGS_ipopt_iter); // NOLINT } else { // Snopt settings @@ -681,8 +681,10 @@ void SetKinematicConstraints(Dircon* trajopt, auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); prog->AddConstraint(left_foot_y_constraint, x_i.head(n_q)); prog->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); - prog->AddConstraint(left_foot_z_ground_constraint, x_i.head(n_q)); - prog->AddConstraint(right_foot_z_ground_constraint, x_i.head(n_q)); + if(FLAGS_height >= 0){ + prog->AddConstraint(left_foot_z_ground_constraint, x_i.head(n_q)); + prog->AddConstraint(right_foot_z_ground_constraint, x_i.head(n_q)); + } } } @@ -772,13 +774,13 @@ void SetKinematicConstraints(Dircon* trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground -// for (int index = 0; index < (mode_lengths[0] - 2); index++) { -// auto lambda = trajopt->force_vars(0, index); -// prog->AddLinearConstraint(lambda(2) >= 60); -// prog->AddLinearConstraint(lambda(5) >= 60); -// prog->AddLinearConstraint(lambda(8) >= 60); -// prog->AddLinearConstraint(lambda(11) >= 60); -// } + // for (int index = 0; index < (mode_lengths[0] - 2); index++) { + // auto lambda = trajopt->force_vars(0, index); + // prog->AddLinearConstraint(lambda(2) >= 60); + // prog->AddLinearConstraint(lambda(5) >= 60); + // prog->AddLinearConstraint(lambda(8) >= 60); + // prog->AddLinearConstraint(lambda(11) >= 60); + // } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 15eacc30a9..5b2ce27c5d 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -301,11 +301,11 @@ int DoMain(int argc, char* argv[]) { osc_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", osc_gains.relative_feet, + plant, plant_context.get(), "toe_left", "pelvis", LEFT_STANCE); auto r_foot_traj_generator = builder.AddSystem( plant, plant_context.get(), "toe_right", "pelvis", - osc_gains.relative_feet, RIGHT_STANCE); + RIGHT_STANCE); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( From 11697f1776183303fabb45ea01c86a6e5999ef67 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 11 Jan 2023 12:35:28 -0500 Subject: [PATCH 332/758] tuning pelvis accel --- examples/Cassie/osc_run/osc_running_gains.yaml | 8 ++++---- examples/Cassie/osc_run/pelvis_trans_traj_generator.cc | 2 +- systems/controllers/osc/operational_space_control.cc | 2 +- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c424b549d9..938ce81ece 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -55,9 +55,9 @@ hip_yaw_kp: 100 hip_yaw_kd: 5 # Foot placement parameters #footstep_offset: -0.05 -footstep_sagital_offset: -0.03 -footstep_lateral_offset: 0.03 # drake -mid_foot_height: 0.2 +footstep_sagital_offset: -0.00 +footstep_lateral_offset: 0.04 # drake +mid_foot_height: 0.3 FootstepKd: [ 0.01, 0, 0, 0, 0.3, 0, @@ -69,7 +69,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 40, 0, - 0, 0, 150] + 0, 0, 125] PelvisKd: [ 0, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 57dd4d0bbb..aeba3e5761 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -113,7 +113,7 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( // Vector3d rddot = f_g + f_leg; Vector3d rddot = f_g; - double dt = 1e-3; + double dt = 1e-2; Eigen::Vector2d breaks; // if (t <= 0.3) { // breaks << 0, 0.25, 0.4; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 02efae0f8b..2c5624688d 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1115,7 +1115,7 @@ void OperationalSpaceControl::CheckTracking( if (soft_constraint_cost_ != nullptr) { soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); } - if (y_soft_constraint_cost[0] > 5e3 || isnan(y_soft_constraint_cost[0])) { + if (y_soft_constraint_cost[0] > 1e4 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } From 91cf23deda955abf774469c052d8244a7d211c6b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 Jan 2023 12:19:21 -0500 Subject: [PATCH 333/758] fixing cassie gym --- .../pydairlib/analysis/log_plotter_cassie.py | 10 +- .../plot_configs/cassie_running_plot.yaml | 20 +- .../cassie/gym_envs/cassie_gym_test.py | 6 +- .../cassie/gym_envs/drake_cassie_gym.py | 3 +- examples/Cassie/closed_loop_running_sim.cc | 22 +- .../Cassie/diagrams/cassie_sim_diagram.cc | 5 +- .../osc_running_controller_diagram.cc | 202 ++++++++++-------- .../osc_walking_controller_diagram.cc | 194 +++++++---------- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_osc_running_controller.cc | 38 ++-- examples/Cassie/run_osc_walking_controller.cc | 65 +++--- .../Cassie/run_osc_walking_controller_alip.cc | 8 +- .../controllers/osc/options_tracking_data.cc | 28 +-- .../controllers/osc/options_tracking_data.h | 8 +- 14 files changed, 285 insertions(+), 326 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index fb9090abf3..04a96bed73 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -64,8 +64,10 @@ def main(): ''' Plot Positions ''' # Plot floating base positions if applicable if use_floating_base and plot_config.plot_floating_base_positions: - mbp_plots.plot_floating_base_positions( + plot = mbp_plots.plot_floating_base_positions( robot_output, pos_names, 7, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + # Plot joint positions if plot_config.plot_joint_positions: @@ -163,9 +165,9 @@ def main(): plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - if plot_config.plot_active_tracking_datas: - plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plot.save_fig('active_tracking_datas.png') + # if plot_config.plot_active_tracking_datas: + # plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + # plot.save_fig('active_tracking_datas.png') plt.show() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index b72cdfb5b8..9eb4efc655 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 0 -duration: -1 +start_time: 7 +duration: 3 # Plant properties use_springs: true @@ -22,8 +22,8 @@ plot_joint_velocities: false plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -#special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right' ] -special_positions_to_plot: [ 'hip_pitch_left', 'hip_pitch_right', 'hip_roll_left', 'hip_roll_right' ] +special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right', 'ankle_spring_joint_left', 'ankle_spring_joint_right' ] +#special_positions_to_plot: [ 'hip_pitch_left', 'hip_pitch_right', 'hip_roll_left', 'hip_roll_right' ] special_velocities_to_plot: [ 'hip_roll_leftdot', 'hip_roll_rightdot' ] special_efforts_to_plot: [ ] @@ -44,15 +44,15 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, - # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' ] }, + # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos','vel', 'accel' ] }, # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - # right_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, -# left_ft_traj: { 'dims': [1, 2], 'derivs': [ 'pos' ] }, + # right_ft_traj: { 'dims': [0, 1, 2], 'derivs': [ 'pos' ] }, + left_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' , 'vel'] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, -# left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, -# right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, + # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, + # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, } \ No newline at end of file diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 0eb8d739b6..3e13970570 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -14,15 +14,15 @@ def main(): osc_walking_gains_filename = 'examples/Cassie/osc/osc_walking_gains_alip.yaml' osqp_settings = 'examples/Cassie/osc_run/osc_running_qp_settings.yaml' default_osqp_settings = 'examples/Cassie/osc/solver_settings/osqp_options_walking.yaml' - urdf = 'examples/Cassie/urdf/cassie_v2.urdf' + urdf = 'examples/Cassie/urdf/cassie_v2_conservative.urdf' reward_function_weights = '' action = np.zeros(18) action[2] = 1.0 cumulative_reward = 0 while 1: - controller_plant = MultibodyPlant(8e-5) - AddCassieMultibody(controller_plant, None, True, urdf, False, False) + controller_plant = MultibodyPlant(1e-3) + AddCassieMultibody(controller_plant, None, True, urdf, False, False, False) controller_plant.Finalize() controller = OSCRunningControllerFactory(controller_plant, osc_running_gains_filename, osqp_settings) # controller = OSCWalkingControllerFactory(controller_plant, True, osc_walking_gains_filename, osqp_settings) diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 6b34d0adf1..0b7167ac5c 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -38,7 +38,7 @@ def __init__(self, reward_func, visualize=False): def make(self, controller, urdf='examples/Cassie/urdf/cassie_v2.urdf'): self.builder = DiagramBuilder() - self.dt = 8e-5 + self.dt = 1e-3 self.plant = MultibodyPlant(self.dt) self.controller = controller self.simulator = CassieSimDiagram(self.plant, urdf, self.visualize, 0.8, 1e4, 1e2) @@ -91,7 +91,6 @@ def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.sim_dt - action[2] = 1.0 self.simulator.get_input_port_radio().FixValue(self.simulator_context, action) self.controller.get_input_port_radio().FixValue(self.controller_context, action) self.sim.AdvanceTo(next_timestep) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index 1844369d2a..b37d7c7b87 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -2,23 +2,14 @@ #include #include -#include "dairlib/lcmt_pd_config.hpp" -#include "dairlib/lcmt_robot_input.hpp" -#include "dairlib/lcmt_robot_output.hpp" #include "examples/Cassie/cassie_utils.h" #include "examples/Cassie/diagrams/cassie_sim_diagram.h" #include "examples/Cassie/diagrams/osc_running_controller_diagram.h" #include "examples/Cassie/diagrams/osc_walking_controller_diagram.h" -#include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" -#include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/primitives/zero_order_hold.h" namespace dairlib { @@ -29,24 +20,23 @@ namespace examples { int DoMain(int argc, char* argv[]) { DiagramBuilder builder; - std::string urdf = "examples/Cassie/urdf/cassie_v2.urdf"; + std::string urdf = "examples/Cassie/urdf/cassie_v2_conservative.urdf"; std::string osc_running_gains = "examples/Cassie/osc_run/osc_running_gains.yaml"; - std::string osc_walking_gains = "examples/Cassie/osc/osc_walking_gains.yaml"; + std::string osc_walking_gains = "examples/Cassie/osc/osc_walking_gains_alip.yaml"; std::string osqp_settings = "examples/Cassie/osc_run/osc_running_qp_settings.yaml"; std::unique_ptr> plant = - std::make_unique>(8e-5); + std::make_unique>(1e-3); MultibodyPlant controller_plant = - MultibodyPlant(8e-5); + MultibodyPlant(1e-3); // Built the Cassie MBPs AddCassieMultibody(&controller_plant, nullptr, true, "examples/Cassie/urdf/cassie_v2_conservative.urdf", false /*spring model*/, false /*loop closure*/); controller_plant.Finalize(); -// auto controller_context = controller_plant.CreateDefaultContext(); auto sim_diagram = builder.AddSystem( - std::move(plant), urdf, 0.4, 1e5, 1e2); + std::move(plant), urdf, 0.4); MultibodyPlant& new_plant = sim_diagram->get_plant(); auto controller_diagram = builder.AddSystem( @@ -87,7 +77,7 @@ int DoMain(int argc, char* argv[]) { simulator.Initialize(); // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; - simulator.AdvanceTo(5.0); + simulator.AdvanceTo(1.0); } }} diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index c88682f624..c6c18ed745 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -50,10 +50,11 @@ CassieSimDiagram::CassieSimDiagram( scene_graph_->set_name("scene_graph"); plant_ = builder.AddSystem(std::move(plant)); + plant_->set_discrete_contact_solver( + drake::multibody::DiscreteContactSolver::kSap); AddCassieMultibody(plant_, scene_graph_, true, urdf, true, true); multibody::AddFlatTerrain(plant_, scene_graph_, mu, mu, - Eigen::Vector3d(0, 0, 1), stiffness, - dissipation_rate); + Eigen::Vector3d(0, 0, 1)); plant_->Finalize(); auto input_receiver = builder.AddSystem(*plant_); diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 5fe57435d0..ebab779a04 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -136,26 +136,16 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( FindResourceOrThrow(osc_gains_filename)); /**** FSM and contact mode configuration ****/ - int left_stance_state = 0; - int right_stance_state = 1; - int right_touchdown_air_phase = 2; - int left_touchdown_air_phase = 3; - - fsm_states = vector(); - fsm_states.push_back(left_stance_state); - fsm_states.push_back(right_touchdown_air_phase); - fsm_states.push_back(right_stance_state); - fsm_states.push_back(left_touchdown_air_phase); - fsm_states.push_back(left_stance_state); - - state_durations = vector(); - state_durations.push_back(osc_running_gains.stance_duration); - state_durations.push_back(osc_running_gains.flight_duration); - state_durations.push_back(osc_running_gains.stance_duration); - state_durations.push_back(osc_running_gains.flight_duration); - state_durations.push_back(0.0); - - accumulated_state_durations = vector(); + vector fsm_states = { + RUNNING_FSM_STATE::LEFT_STANCE, RUNNING_FSM_STATE::LEFT_FLIGHT, + RUNNING_FSM_STATE::RIGHT_STANCE, RUNNING_FSM_STATE::RIGHT_FLIGHT, + RUNNING_FSM_STATE::LEFT_STANCE}; + + vector state_durations = {osc_running_gains.stance_duration, + osc_running_gains.flight_duration, + osc_running_gains.stance_duration, + osc_running_gains.flight_duration, 0.0}; + vector accumulated_state_durations; accumulated_state_durations.push_back(0); for (double state_duration : state_durations) { accumulated_state_durations.push_back(accumulated_state_durations.back() + @@ -167,6 +157,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto contact_scheduler = builder.AddSystem( plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); + contact_scheduler->SetSLIPParams(osc_running_gains.rest_length); + contact_scheduler->SetNominalStepTimings(osc_running_gains.stance_duration, + osc_running_gains.flight_duration); + contact_scheduler->SetMaxStepTimingVariance( + osc_running_gains.stance_variance, osc_running_gains.flight_variance); auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); @@ -177,30 +172,36 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( builder.AddSystem( control_channel_name_, 1); std::vector tau = {.05, .01, .01}; -// auto ekf_filter = -// builder.AddSystem(plant, tau); + // auto ekf_filter = + // builder.AddSystem(plant, tau); /**** OSC setup ****/ - // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingCostWeights(1e-3 * gains.W_input_regularization); - osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaContactRegularizationWeight(1e-4 * - gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); - + osc->SetAccelerationCostWeights(osc_running_gains.w_accel * + osc_running_gains.W_acceleration); + osc->SetInputSmoothingCostWeights(osc_running_gains.w_input_reg * + osc_running_gains.W_input_regularization); + osc->SetInputCostWeights(osc_running_gains.w_input * + osc_running_gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight( + osc_running_gains.w_lambda * osc_running_gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight( + osc_running_gains.w_lambda * osc_running_gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetContactSoftConstraintWeight(osc_running_gains.w_soft_constraint); + osc->SetJointLimitWeight(osc_running_gains.w_joint_limit); // Contact information for OSC osc->SetContactFriction(osc_running_gains.mu); - osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); - osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + &left_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + &left_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + &right_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + &right_heel_evaluator); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); @@ -229,11 +230,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( pelvis_trans_traj_generator->SetSLIPParams( osc_running_gains.rest_length, osc_running_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", - LEFT_STANCE); + plant, plant_context.get(), "toe_left", "pelvis", LEFT_STANCE); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "pelvis", - RIGHT_STANCE); + plant, plant_context.get(), "toe_right", "pelvis", RIGHT_STANCE); l_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_running_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( @@ -262,20 +261,22 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_ft_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - pelvis_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); - pelvis_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); - stance_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, - "toe_left"); - stance_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, - "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack(right_stance_state, - "toe_left"); - right_foot_tracking_data->AddStateAndPointToTrack(left_stance_state, - "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "toe_left"); - right_foot_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "toe_right"); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, + "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, + "pelvis"); + stance_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_left"); + stance_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); left_foot_yz_tracking_data = std::make_unique( "left_ft_traj", osc_running_gains.K_p_swing_foot, @@ -285,10 +286,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_ft_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - left_foot_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "toe_left"); - right_foot_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "toe_right"); + left_foot_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + right_foot_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); left_hip_tracking_data = std::make_unique( "left_hip_traj", osc_running_gains.K_p_swing_foot, @@ -298,12 +299,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack(right_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(left_stance_state, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "pelvis"); - left_hip_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_running_gains.K_p_swing_foot, @@ -313,10 +316,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - left_hip_yz_tracking_data->AddStateAndPointToTrack(right_touchdown_air_phase, - "hip_left"); - right_hip_yz_tracking_data->AddStateAndPointToTrack(left_touchdown_air_phase, - "hip_right"); + left_hip_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + right_hip_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); left_foot_rel_tracking_data = std::make_unique( @@ -353,8 +356,25 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); - left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); - right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); + auto foot_traj_weight_trajectory = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + {0, osc_running_gains.stance_duration + + 2 * osc_running_gains.flight_duration}, + {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)})); + auto foot_traj_gain_trajectory = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + {0, osc_running_gains.stance_duration + + 2 * osc_running_gains.flight_duration}, + {0.5 * MatrixXd::Identity(3, 3), + 2.0 * MatrixXd::Identity(3, 3)})); + left_foot_rel_tracking_data->SetTimeVaryingWeights( + foot_traj_weight_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingWeights( + foot_traj_weight_trajectory); + left_foot_rel_tracking_data->SetTimeVaryingGains(foot_traj_gain_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingGains(foot_traj_gain_trajectory); left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); @@ -365,8 +385,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); - osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); - osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); auto heading_traj_generator = builder.AddSystem(plant, @@ -376,14 +394,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "pelvis_rot_traj", osc_running_gains.K_p_pelvis_rot, osc_running_gains.K_d_pelvis_rot, osc_running_gains.W_pelvis_rot, plant, plant); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_stance_state, - "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_stance_state, - "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(left_touchdown_air_phase, - "pelvis"); - pelvis_rot_tracking_data->AddStateAndFrameToTrack(right_touchdown_air_phase, - "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -405,17 +423,17 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.K_d_swing_toe, osc_running_gains.W_swing_toe, plant, plant); left_toe_angle_tracking_data->AddStateAndJointToTrack( - right_stance_state, "toe_left", "toe_leftdot"); + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data->AddStateAndJointToTrack( - right_touchdown_air_phase, "toe_left", "toe_leftdot"); + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data->AddStateAndJointToTrack( - left_touchdown_air_phase, "toe_left", "toe_leftdot"); + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left", "toe_leftdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - left_stance_state, "toe_right", "toe_rightdot"); + RUNNING_FSM_STATE::LEFT_STANCE, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - right_touchdown_air_phase, "toe_right", "toe_rightdot"); + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - left_touchdown_air_phase, "toe_right", "toe_rightdot"); + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right", "toe_rightdot"); left_toe_angle_tracking_data->SetImpactInvariantProjection(true); right_toe_angle_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); @@ -450,7 +468,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->get_input_port_impact_info()); builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); - builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); // FSM connections @@ -458,7 +475,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( contact_scheduler->get_input_port_state()); // Trajectory generator connections - builder.Connect( contact_scheduler->get_output_port_contact_scheduler(), pelvis_trans_traj_generator->get_contact_scheduler_input_port()); @@ -481,6 +497,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( l_foot_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), r_foot_traj_generator->get_input_port_state()); + builder.Connect(radio_parser->get_output_port(), + l_foot_traj_generator->get_input_port_radio()); + builder.Connect(radio_parser->get_output_port(), + r_foot_traj_generator->get_input_port_radio()); builder.Connect(contact_scheduler->get_output_port_clock(), l_foot_traj_generator->get_input_port_clock()); @@ -507,10 +527,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("right_ft_traj")); - builder.Connect(l_foot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("left_ft_z_traj")); - builder.Connect(r_foot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("right_ft_z_traj")); + // builder.Connect(l_foot_traj_generator->get_output_port(0), + // osc->get_input_port_tracking_data("left_ft_z_traj")); + // builder.Connect(r_foot_traj_generator->get_output_port(0), + // osc->get_input_port_tracking_data("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index 1f8f421e90..44ad2d4fd7 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -6,11 +6,14 @@ #include "examples/Cassie/osc/heading_traj_generator.h" #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/osc_walking_gains.h" +#include "examples/Cassie/osc/osc_walking_gains_alip.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc/walking_speed_control.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/alip_swing_ft_traj_gen.h" +#include "systems/controllers/alip_traj_gen.h" #include "systems/controllers/fsm_event_time.h" #include "systems/controllers/lipm_traj_gen.h" #include "systems/controllers/osc/com_tracking_data.h" @@ -30,9 +33,6 @@ #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" -#include "examples/Cassie/osc/osc_walking_gains_alip.h" -#include "systems/controllers/alip_swing_ft_traj_gen.h" -#include "systems/controllers/alip_traj_gen.h" namespace dairlib { @@ -54,8 +54,8 @@ using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; -//using drake::systems::lcm::LcmPublisherSystem; -//using drake::systems::lcm::LcmSubscriberSystem; +// using drake::systems::lcm::LcmPublisherSystem; +// using drake::systems::lcm::LcmSubscriberSystem; using drake::trajectories::PiecewisePolynomial; using multibody::FixedJointEvaluator; using multibody::WorldYawViewFrame; @@ -68,10 +68,9 @@ namespace examples { namespace controllers { OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( - drake::multibody::MultibodyPlant &plant, - bool has_double_stance, - const string &osc_walking_gains_filename, - const string &osqp_settings_filename) + drake::multibody::MultibodyPlant& plant, bool has_double_stance, + const string& osc_walking_gains_filename, + const string& osqp_settings_filename) : plant_(&plant), pos_map(multibody::MakeNameToPositionsMap(plant)), vel_map(multibody::MakeNameToVelocitiesMap(plant)), @@ -80,15 +79,15 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( left_heel(LeftToeRear(plant)), right_toe(RightToeFront(plant)), right_heel(RightToeRear(plant)), - left_toe_mid(std::pair &>( + left_toe_mid(std::pair&>( (left_toe.first + left_heel.first) / 2, plant.GetFrameByName("toe_left"))), - right_toe_mid(std::pair &>( + right_toe_mid(std::pair&>( (left_toe.first + left_heel.first) / 2, plant.GetFrameByName("toe_right"))), - left_toe_origin(std::pair &>( + left_toe_origin(std::pair&>( Vector3d::Zero(), plant.GetFrameByName("toe_left"))), - right_toe_origin(std::pair &>( + right_toe_origin(std::pair&>( Vector3d::Zero(), plant.GetFrameByName("toe_right"))), left_right_foot({left_toe_origin, right_toe_origin}), left_foot_points({left_heel, left_toe}), @@ -126,10 +125,10 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( DiagramBuilder builder; plant_context = plant.CreateDefaultContext(); feet_contact_points[0] = std::vector< - std::pair &>>( + std::pair&>>( {left_toe, left_heel}); feet_contact_points[1] = std::vector< - std::pair &>>( + std::pair&>>( {right_toe, right_heel}); // Read-in the parameters @@ -138,8 +137,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( OSCGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(osc_walking_gains_filename), {}, {}, yaml_options); OSCWalkingGainsALIP osc_walking_gains = - drake::yaml::LoadYamlFile(osc_walking_gains_filename); - + drake::yaml::LoadYamlFile( + osc_walking_gains_filename); /**** FSM and contact mode configuration ****/ int left_stance_state = 0; @@ -183,19 +182,19 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( right_support_duration}; swing_ft_gain_multiplier_breaks = {0, left_support_duration / 2, left_support_duration}; - swing_ft_gain_multiplier_samples = - std::vector< - drake::MatrixX>(3, drake::MatrixX::Identity(3, 3)); + swing_ft_gain_multiplier_samples = std::vector>( + 3, drake::MatrixX::Identity(3, 3)); swing_ft_gain_multiplier_samples[2](2, 2) *= 0.3; - swing_ft_gain_multiplier_gain_multiplier = - PiecewisePolynomial::FirstOrderHold( - swing_ft_gain_multiplier_breaks, swing_ft_gain_multiplier_samples); + auto swing_ft_gain_multiplier_gain_multiplier = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + swing_ft_gain_multiplier_breaks, + swing_ft_gain_multiplier_samples)); swing_ft_accel_gain_multiplier_breaks = {0, left_support_duration / 2, left_support_duration * 3 / 4, left_support_duration}; - swing_ft_accel_gain_multiplier_samples = - std::vector< - drake::MatrixX>(4, drake::MatrixX::Identity(3, 3)); + swing_ft_accel_gain_multiplier_samples = std::vector>( + 4, drake::MatrixX::Identity(3, 3)); swing_ft_accel_gain_multiplier_samples[2](2, 2) *= 0; swing_ft_accel_gain_multiplier_samples[3](2, 2) *= 0; swing_ft_accel_gain_multiplier_gain_multiplier = @@ -227,8 +226,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( int n_u = plant.num_actuators(); MatrixXd Q_accel = osc_walking_gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingCostWeights( - osc_walking_gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingCostWeights(osc_walking_gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Soft constraint on contacts osc->SetContactSoftConstraintWeight(osc_walking_gains.w_soft_constraint); @@ -273,7 +272,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( std::cout << "Creating output trajectory leaf systems. " << std::endl; - cassie::osc::HighLevelCommand *high_level_command; + cassie::osc::HighLevelCommand* high_level_command; high_level_command = builder.AddSystem( plant, plant_context.get(), osc_walking_gains.vel_scale_rot, osc_walking_gains.vel_scale_trans_sagital, @@ -281,30 +280,18 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( auto head_traj_gen = builder.AddSystem( plant, plant_context.get()); auto lipm_traj_generator = builder.AddSystem( - plant, - plant_context.get(), - osc_walking_gains.lipm_height, - unordered_fsm_states, - unordered_state_durations, + plant, plant_context.get(), osc_walking_gains.lipm_height, + unordered_fsm_states, unordered_state_durations, contact_points_in_each_state); auto pelvis_traj_generator = builder.AddSystem( - plant, - plant_context.get(), - osc_walking_gains.lipm_height, - unordered_fsm_states, - unordered_state_durations, - contact_points_in_each_state, - false); + plant, plant_context.get(), osc_walking_gains.lipm_height, + unordered_fsm_states, unordered_state_durations, + contact_points_in_each_state, false); auto swing_ft_traj_generator = builder.AddSystem( - plant, - plant_context.get(), - left_right_support_fsm_states, - left_right_support_state_durations, - left_right_foot, - "pelvis", - double_support_duration, - osc_walking_gains.mid_foot_height, + plant, plant_context.get(), left_right_support_fsm_states, + left_right_support_state_durations, left_right_foot, "pelvis", + double_support_duration, osc_walking_gains.mid_foot_height, osc_walking_gains.final_foot_height, osc_walking_gains.final_foot_velocity_z, osc_walking_gains.max_CoM_to_footstep_dist, @@ -320,11 +307,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( "right_toe_angle_traj"); auto alip_traj_generator = builder.AddSystem( - plant, - plant_context.get(), - osc_walking_gains.lipm_height, - unordered_fsm_states, - unordered_state_durations, + plant, plant_context.get(), osc_walking_gains.lipm_height, + unordered_fsm_states, unordered_state_durations, contact_points_in_each_state, osc_walking_gains.Q_alip_kalman_filter.asDiagonal(), osc_walking_gains.R_alip_kalman_filter.asDiagonal()); @@ -341,35 +325,28 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( std::cout << "Creating tracking data. " << std::endl; swing_foot_data = std::make_unique( - "swing_ft_data", - osc_walking_gains.K_p_swing_foot, - osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, - plant, + "swing_ft_data", osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant, plant); swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); com_data = std::make_unique( - "com_data", - osc_walking_gains.K_p_swing_foot, - osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, - plant, + "com_data", osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant, plant); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); swing_ft_traj_local = std::make_unique( - "swing_ft_traj", - osc_walking_gains.K_p_swing_foot, - osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, - plant, - plant, - swing_foot_data.get(), - com_data.get()); -// WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); + "swing_ft_traj", osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant, + plant, swing_foot_data.get(), com_data.get()); + // WorldYawViewFrame pelvis_view_frame(plant.GetBodyByName("pelvis")); swing_ft_traj_local->SetViewFrame(view_frame); + swing_ft_traj_global = std::make_unique( + "swing_ft_traj", osc_walking_gains.K_p_swing_foot, + osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant, + plant); swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); swing_ft_traj_local->SetTimeVaryingGains( @@ -380,49 +357,33 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( bool use_pelvis_for_lipm_tracking = true; pelvis_traj = std::make_unique( - "lipm_traj", - osc_walking_gains.K_p_com, - osc_walking_gains.K_d_com, - osc_walking_gains.W_com, - plant, - plant); + "lipm_traj", osc_walking_gains.K_p_com, osc_walking_gains.K_d_com, + osc_walking_gains.W_com, plant, plant); pelvis_traj->AddPointToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_traj)); pelvis_balance_traj = std::make_unique( - "pelvis_balance_traj", - osc_walking_gains.K_p_pelvis_balance, - osc_walking_gains.K_d_pelvis_balance, - osc_walking_gains.W_pelvis_balance, - plant, - plant); + "pelvis_balance_traj", osc_walking_gains.K_p_pelvis_balance, + osc_walking_gains.K_d_pelvis_balance, osc_walking_gains.W_pelvis_balance, + plant, plant); pelvis_balance_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) pelvis_heading_traj = std::make_unique( - "pelvis_heading_traj", - osc_walking_gains.K_p_pelvis_heading, - osc_walking_gains.K_d_pelvis_heading, - osc_walking_gains.W_pelvis_heading, - plant, - plant); + "pelvis_heading_traj", osc_walking_gains.K_p_pelvis_heading, + osc_walking_gains.K_d_pelvis_heading, osc_walking_gains.W_pelvis_heading, + plant, plant); pelvis_heading_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_heading_traj), osc_walking_gains.period_of_no_heading_control); swing_toe_traj_left = std::make_unique( - "left_toe_angle_traj", - osc_walking_gains.K_p_swing_toe, - osc_walking_gains.K_d_swing_toe, - osc_walking_gains.W_swing_toe, - plant, + "left_toe_angle_traj", osc_walking_gains.K_p_swing_toe, + osc_walking_gains.K_d_swing_toe, osc_walking_gains.W_swing_toe, plant, plant); swing_toe_traj_right = std::make_unique( - "right_toe_angle_traj", - osc_walking_gains.K_p_swing_toe, - osc_walking_gains.K_d_swing_toe, - osc_walking_gains.W_swing_toe, - plant, + "right_toe_angle_traj", osc_walking_gains.K_p_swing_toe, + osc_walking_gains.K_d_swing_toe, osc_walking_gains.W_swing_toe, plant, plant); swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", "toe_leftdot"); @@ -432,21 +393,14 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( osc->AddTrackingData(std::move(swing_toe_traj_right)); swing_hip_yaw_traj = std::make_unique( - "swing_hip_yaw_traj", - osc_walking_gains.K_p_hip_yaw, - osc_walking_gains.K_d_hip_yaw, - osc_walking_gains.W_hip_yaw, - plant, - plant); - swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, - "hip_yaw_right", - "hip_yaw_rightdot"); - swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, - "hip_yaw_left", - "hip_yaw_leftdot"); + "swing_hip_yaw_traj", osc_walking_gains.K_p_hip_yaw, + osc_walking_gains.K_d_hip_yaw, osc_walking_gains.W_hip_yaw, plant, plant); + swing_hip_yaw_traj->AddStateAndJointToTrack( + left_stance_state, "hip_yaw_right", "hip_yaw_rightdot"); + swing_hip_yaw_traj->AddStateAndJointToTrack( + right_stance_state, "hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); - /**** OSC settings ****/ // Build OSC problem @@ -464,8 +418,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( /*****Connect ports*****/ // OSC connections -// builder.Connect(cassie_out_receiver->get_output_port(), -// high_level_command->get_cassie_out_input_port()); + // builder.Connect(cassie_out_receiver->get_output_port(), + // high_level_command->get_cassie_out_input_port()); builder.Connect(state_receiver->get_output_port(0), high_level_command->get_state_input_port()); builder.Connect(state_receiver->get_output_port(0), @@ -511,9 +465,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); builder.Connect(fsm->get_output_port(0), osc->get_input_port_fsm()); - builder.Connect( - pelvis_traj_generator->get_output_port_lipm_from_touchdown(), - osc->get_input_port_tracking_data("lipm_traj")); + builder.Connect(pelvis_traj_generator->get_output_port_lipm_from_touchdown(), + osc->get_input_port_tracking_data("lipm_traj")); builder.Connect(swing_ft_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("swing_ft_traj")); builder.Connect(head_traj_gen->get_output_port(0), @@ -530,8 +483,7 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( // Publisher connections builder.ExportInput(state_receiver->get_input_port(), "x, u, t"); - builder.ExportInput(radio_parser->get_input_port(), - "raw_radio"); + builder.ExportInput(radio_parser->get_input_port(), "raw_radio"); builder.ExportOutput(command_sender->get_output_port(), "lcmt_robot_input"); builder.ExportOutput(osc->get_output_port_osc_command(), "u, t"); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 938ce81ece..4afb3dafdd 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,7 +40,7 @@ target_vel_filter_alpha: 0.01 # SLIP parameters rest_length: 0.85 rest_length_offset: 0.025 -stance_duration: 0.3 +stance_duration: 0.31 flight_duration: 0.09 # max percent variance stance_variance: 0.1 diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 5b2ce27c5d..2ad936ea24 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -64,6 +64,7 @@ using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; using examples::osc::PelvisPitchTrajGenerator; using examples::osc::PelvisRollTrajGenerator; using examples::osc::PelvisTransTrajGenerator; @@ -205,8 +206,6 @@ int DoMain(int argc, char* argv[]) { osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * osc_gains.W_input_regularization); -// osc->SetInputSmoothingCostWeights(osc_gains.w_input_accel * -// MatrixXd::Identity(nu, nu)); osc->SetInputCostWeights(osc_gains.w_input * osc_gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight( @@ -301,11 +300,9 @@ int DoMain(int argc, char* argv[]) { osc_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", - LEFT_STANCE); + plant, plant_context.get(), "toe_left", "pelvis", LEFT_STANCE); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "pelvis", - RIGHT_STANCE); + plant, plant_context.get(), "toe_right", "pelvis", RIGHT_STANCE); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( @@ -431,17 +428,17 @@ int DoMain(int argc, char* argv[]) { right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); - PiecewisePolynomial foot_traj_weight_trajectory = - PiecewisePolynomial::FirstOrderHold( - {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, - {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)}); - PiecewisePolynomial foot_traj_gain_trajectory = - PiecewisePolynomial::FirstOrderHold( - {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, - {0.5 * MatrixXd::Identity(3, 3), 2.0 * MatrixXd::Identity(3, 3)}); - // PiecewisePolynomial foot_traj_weight_trajectory = - // PiecewisePolynomial::FirstOrderHold( - // {0, 0.25 + 0.2}, {VectorXd::Ones(1), VectorXd::Ones(1)}); + auto foot_traj_weight_trajectory = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, + {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)})); + auto foot_traj_gain_trajectory = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, + {0.5 * MatrixXd::Identity(3, 3), + 2.0 * MatrixXd::Identity(3, 3)})); left_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); right_foot_rel_tracking_data->SetTimeVaryingWeights( @@ -564,13 +561,6 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_impact_info()); builder.Connect(contact_scheduler->get_output_port_clock(), osc->get_input_port_clock()); - - // if (osc_gains.ekf_filter_tau[0] > 0) { - // builder.Connect(state_receiver->get_output_port(0), - // ekf_filter->get_input_port()); - // builder.Connect(ekf_filter->get_output_port(), - // osc->get_robot_output_input_port()); - // } else { builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); // } diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index e6aaee7d31..7ea753fd4c 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -48,9 +48,9 @@ using Eigen::VectorXd; using drake::multibody::Frame; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using multibody::WorldYawViewFrame; using systems::controllers::ComTrackingData; @@ -166,8 +166,7 @@ int DoMain(int argc, char* argv[]) { gains.yaw_deadband_radius); cassie::osc::HighLevelCommand* high_level_command; - auto cassie_out_to_radio = - builder.AddSystem(); + auto cassie_out_to_radio = builder.AddSystem(); if (FLAGS_use_radio) { high_level_command = builder.AddSystem( @@ -373,8 +372,8 @@ int DoMain(int argc, char* argv[]) { int n_u = plant_w_spr.num_actuators(); MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetInputSmoothingCostWeights( - gains.w_input_reg * MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingCostWeights(gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -462,9 +461,11 @@ int DoMain(int argc, char* argv[]) { std::vector> swing_ft_gain_multiplier_samples( 3, drake::MatrixX::Identity(3, 3)); swing_ft_gain_multiplier_samples[2](2, 2) *= 0.3; - PiecewisePolynomial swing_ft_gain_multiplier_gain_multiplier = - PiecewisePolynomial::FirstOrderHold( - swing_ft_gain_multiplier_breaks, swing_ft_gain_multiplier_samples); + auto swing_ft_gain_multiplier_gain_multiplier = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + swing_ft_gain_multiplier_breaks, + swing_ft_gain_multiplier_samples)); std::vector swing_ft_accel_gain_multiplier_breaks{ 0, left_support_duration / 2, left_support_duration * 3 / 4, left_support_duration}; @@ -477,24 +478,24 @@ int DoMain(int argc, char* argv[]) { swing_ft_accel_gain_multiplier_breaks, swing_ft_accel_gain_multiplier_samples); - auto swing_foot_data = std::make_unique ( + auto swing_foot_data = std::make_unique( "swing_ft_data", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); - auto com_data = std::make_unique ("com_data", gains.K_p_swing_foot, - gains.K_d_swing_foot, gains.W_swing_foot, - plant_w_spr, plant_w_spr); + auto com_data = std::make_unique( + "com_data", gains.K_p_swing_foot, gains.K_d_swing_foot, + gains.W_swing_foot, plant_w_spr, plant_w_spr); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); - auto swing_ft_traj_local = std::make_unique ( + auto swing_ft_traj_local = std::make_unique( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), com_data.get()); WorldYawViewFrame pelvis_view_frame(plant_w_spr.GetBodyByName("pelvis")); swing_ft_traj_local->SetViewFrame(pelvis_view_frame); - auto swing_ft_traj_global = std::make_unique ( + auto swing_ft_traj_global = std::make_unique( "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, gains.W_swing_foot, plant_w_spr, plant_w_spr); swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); @@ -521,25 +522,26 @@ int DoMain(int argc, char* argv[]) { // Center of mass tracking bool use_pelvis_for_lipm_tracking = true; - auto pelvis_traj = std::make_unique ("lipm_traj", gains.K_p_com, - gains.K_d_com, gains.W_com, - plant_w_spr, plant_w_spr); + auto pelvis_traj = std::make_unique( + "lipm_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, + plant_w_spr); pelvis_traj->AddPointToTrack("pelvis"); - auto center_of_mass_traj = std::make_unique ("lipm_traj", gains.K_p_com, gains.K_d_com, - gains.W_com, plant_w_spr, plant_w_spr); + auto center_of_mass_traj = std::make_unique( + "lipm_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, + plant_w_spr); if (use_pelvis_for_lipm_tracking) { osc->AddTrackingData(std::move(pelvis_traj)); } else { osc->AddTrackingData(std::move(center_of_mass_traj)); } // Pelvis rotation tracking (pitch and roll) - auto pelvis_balance_traj = std::make_unique ( + auto pelvis_balance_traj = std::make_unique( "pelvis_balance_traj", gains.K_p_pelvis_balance, gains.K_d_pelvis_balance, gains.W_pelvis_balance, plant_w_spr, plant_w_spr); pelvis_balance_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) - auto pelvis_heading_traj = std::make_unique ( + auto pelvis_heading_traj = std::make_unique( "pelvis_heading_traj", gains.K_p_pelvis_heading, gains.K_d_pelvis_heading, gains.W_pelvis_heading, plant_w_spr, plant_w_spr); pelvis_heading_traj->AddFrameToTrack("pelvis"); @@ -547,27 +549,27 @@ int DoMain(int argc, char* argv[]) { gains.period_of_no_heading_control); // Swing toe joint tracking - auto swing_toe_traj_left = std::make_unique ( + auto swing_toe_traj_left = std::make_unique( "left_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, gains.W_swing_toe, plant_w_spr, plant_w_spr); - auto swing_toe_traj_right = std::make_unique ( + auto swing_toe_traj_right = std::make_unique( "right_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, gains.W_swing_toe, plant_w_spr, plant_w_spr); swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", - "toe_rightdot"); + "toe_rightdot"); swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", - "toe_leftdot"); + "toe_leftdot"); osc->AddTrackingData(std::move(swing_toe_traj_left)); osc->AddTrackingData(std::move(swing_toe_traj_right)); // Swing hip yaw joint tracking - auto swing_hip_yaw_traj = std::make_unique ( + auto swing_hip_yaw_traj = std::make_unique( "swing_hip_yaw_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, gains.W_hip_yaw, plant_w_spr, plant_w_spr); - swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", - "hip_yaw_rightdot"); - swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", - "hip_yaw_leftdot"); + swing_hip_yaw_traj->AddStateAndJointToTrack( + left_stance_state, "hip_yaw_right", "hip_yaw_rightdot"); + swing_hip_yaw_traj->AddStateAndJointToTrack( + right_stance_state, "hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(swing_hip_yaw_traj), VectorXd::Zero(1)); // Set double support duration for force blending @@ -609,7 +611,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_WALKING", &lcm_local, TriggerTypeSet({TriggerType::kForced}))); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); } // Create the diagram diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 4f42a5034f..44f6c5f1a4 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -456,9 +456,11 @@ int DoMain(int argc, char* argv[]) { std::vector> swing_ft_gain_multiplier_samples( 3, drake::MatrixX::Identity(3, 3)); swing_ft_gain_multiplier_samples[2](2, 2) *= 0.3; - PiecewisePolynomial swing_ft_gain_multiplier_gain_multiplier = - PiecewisePolynomial::FirstOrderHold( - swing_ft_gain_multiplier_breaks, swing_ft_gain_multiplier_samples); + auto swing_ft_gain_multiplier_gain_multiplier = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + swing_ft_gain_multiplier_breaks, + swing_ft_gain_multiplier_samples)); std::vector swing_ft_accel_gain_multiplier_breaks{ 0, left_support_duration / 2, left_support_duration * 3 / 4, left_support_duration}; diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index be8d39d26f..5583443e78 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -67,11 +67,10 @@ void OptionsTrackingData::UpdateFilters(double t) { } // Assign filtered values - if (n_y_ == 4){ + if (n_y_ == 4) { y_ = filtered_y_; ydot_ = filtered_ydot_; - } - else{ + } else { for (auto idx : low_pass_filter_element_idx_) { y_(idx) = filtered_y_(idx); ydot_(idx) = filtered_ydot_(idx); @@ -132,7 +131,7 @@ void OptionsTrackingData::SetLowPassFilter(double tau, DRAKE_DEMAND(tau > 0); tau_ = tau; -// DRAKE_DEMAND(n_y_ == n_ydot_); // doesn't support quaternion yet + // DRAKE_DEMAND(n_y_ == n_ydot_); // doesn't support quaternion yet if (element_idx.empty()) { for (int i = 0; i < n_y_; i++) { low_pass_filter_element_idx_.insert(i); @@ -143,19 +142,20 @@ void OptionsTrackingData::SetLowPassFilter(double tau, } void OptionsTrackingData::SetTimeVaryingGains( - const drake::trajectories::Trajectory& gain_multiplier) { - DRAKE_DEMAND(gain_multiplier.cols() == n_ydot_); - DRAKE_DEMAND(gain_multiplier.rows() == n_ydot_); - DRAKE_DEMAND(gain_multiplier.start_time() == 0); - gain_multiplier_ = &gain_multiplier; + std::shared_ptr> gain_multiplier) { + DRAKE_DEMAND(gain_multiplier->cols() == n_ydot_); + DRAKE_DEMAND(gain_multiplier->rows() == n_ydot_); + DRAKE_DEMAND(gain_multiplier->start_time() == 0); + gain_multiplier_ = gain_multiplier; } void OptionsTrackingData::SetTimeVaryingWeights( - const drake::trajectories::Trajectory& weight_trajectory) { - // DRAKE_DEMAND(weight_trajectory.cols() == n_ydot_); - // DRAKE_DEMAND(weight_trajectory.rows() == n_ydot_); - // DRAKE_DEMAND(weight_trajectory.start_time() == 0); - weight_trajectory_ = &weight_trajectory; + std::shared_ptr> + weight_trajectory) { +// DRAKE_DEMAND(weight_trajectory->cols() == n_ydot_); +// DRAKE_DEMAND(weight_trajectory->rows() == n_ydot_); +// DRAKE_DEMAND(weight_trajectory->start_time() == 0); + weight_trajectory_ = weight_trajectory; } void OptionsTrackingData::SetFeedforwardAccelMultiplier( const drake::trajectories::Trajectory& ff_accel_multiplier) { diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index 79ca8d8370..49c9f165ed 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -23,9 +23,9 @@ class OptionsTrackingData : public OscTrackingData { // TOOD(yminchen): You can make ratio dictionary so that we have one ratio per // finite state void SetTimeVaryingGains( - const drake::trajectories::Trajectory& gain_multiplier); + std::shared_ptr> gain_multiplier); void SetTimeVaryingWeights( - const drake::trajectories::Trajectory& weight_trajectory); + std::shared_ptr> weight_trajectory); void SetFeedforwardAccelMultiplier( const drake::trajectories::Trajectory& ff_accel_multiplier); @@ -69,8 +69,8 @@ class OptionsTrackingData : public OscTrackingData { void UpdateYddotCmd(double t, double t_since_state_switch) override; void UpdateW(double t, double t_since_state_switch); - const drake::trajectories::Trajectory* gain_multiplier_ = nullptr; - const drake::trajectories::Trajectory* weight_trajectory_ = nullptr; + std::shared_ptr> gain_multiplier_; + std::shared_ptr> weight_trajectory_; void UpdateFilters(double t); From 70e85ce13d6b9ea04a754c071d75441865a19061 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 12 Jan 2023 13:09:16 -0500 Subject: [PATCH 334/758] cleaning up running controller --- examples/Cassie/closed_loop_running_sim.cc | 2 +- .../osc_running_controller_diagram.cc | 22 ++++++++++++++----- examples/Cassie/run_osc_running_controller.cc | 3 --- 3 files changed, 17 insertions(+), 10 deletions(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index b37d7c7b87..e9fefdf2c5 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -77,7 +77,7 @@ int DoMain(int argc, char* argv[]) { simulator.Initialize(); // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; - simulator.AdvanceTo(1.0); + simulator.AdvanceTo(5.0); } }} diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index ebab779a04..678b421bf1 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -1,7 +1,5 @@ #include "osc_running_controller_diagram.h" -#include - #include #include #include @@ -17,9 +15,6 @@ #include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" -#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" -#include "lcm/dircon_saved_trajectory.h" -#include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" #include "systems/controllers/controller_failure_aggregator.h" @@ -171,7 +166,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto failure_aggregator = builder.AddSystem( control_channel_name_, 1); - std::vector tau = {.05, .01, .01}; +// std::vector tau = {.05, .01, .01}; // auto ekf_filter = // builder.AddSystem(plant, tau); @@ -278,6 +273,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_foot_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); + left_foot_yz_tracking_data = std::make_unique( "left_ft_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, @@ -308,6 +308,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( left_hip_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, @@ -402,6 +407,11 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + + if (osc_running_gains.rot_filter_tau > 0) { + pelvis_rot_tracking_data->SetLowPassFilter(osc_running_gains.rot_filter_tau, + {0, 1, 2}); + } pelvis_rot_tracking_data->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 2ad936ea24..e94477c207 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -21,7 +21,6 @@ #include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" #include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" -#include "lcm/dircon_saved_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" @@ -37,7 +36,6 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -563,7 +561,6 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_clock()); builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); - // } // FSM connections builder.Connect(state_receiver->get_output_port(0), From 5b21140f8006a0b1f25f169057d224de401d6eb3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 13 Jan 2023 10:56:24 -0500 Subject: [PATCH 335/758] fixing platform sim to use sap --- examples/Cassie/multibody_sim_w_platform.cc | 17 +++++++++++++---- 1 file changed, 13 insertions(+), 4 deletions(-) diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 5d0db3e9b0..45703f61a8 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -48,7 +48,7 @@ DEFINE_bool(floating_base, true, "Fixed or floating base model"); DEFINE_double(target_realtime_rate, 1.0, "Desired rate relative to real time. See documentation for " "Simulator::set_target_realtime_rate() for details."); -DEFINE_double(dt, 8e-5, +DEFINE_double(dt, 1e-3, "The step size to use for time_stepping, ignored for continuous"); DEFINE_double(v_stiction, 1e-3, "Stiction tolernace (m/s)"); DEFINE_double(penetration_allowance, 1e-5, @@ -75,6 +75,8 @@ DEFINE_double(actuator_delay, 0.0, "Duration of actuator delay. Set to 0.0 by default."); DEFINE_bool(use_traj_state, false, "Whether to intialize the sim from a specific state"); +DEFINE_string(contact_solver, "SAP", + "Contact solver to use. Either TAMSI or SAP."); int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -94,6 +96,16 @@ int do_main(int argc, char* argv[]) { ? "examples/Cassie/urdf/cassie_v2.urdf" : "examples/Cassie/urdf/cassie_fixed_springs.urdf"; + if (FLAGS_contact_solver == "SAP") { + plant.set_discrete_contact_solver( + drake::multibody::DiscreteContactSolver::kSap); + } else if (FLAGS_contact_solver == "TAMSI") { + plant.set_discrete_contact_solver( + drake::multibody::DiscreteContactSolver::kTamsi); + } else { + std::cerr << "Unknown contact solver setting." << std::endl; + } + if (FLAGS_platform_height != 0) { Parser parser(&plant, &scene_graph); std::string terrain_name = @@ -105,9 +117,6 @@ int do_main(int argc, char* argv[]) { drake::math::RigidTransform(offset)); } - plant.set_penetration_allowance(FLAGS_penetration_allowance); - plant.set_stiction_tolerance(FLAGS_v_stiction); - AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, urdf, FLAGS_spring_model, true); From 87ef454da7ae02f6f6328dfda5df1705aeac85b2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 13 Jan 2023 11:29:30 -0500 Subject: [PATCH 336/758] fixing rabbit example --- .../impact_invariant_examples.pmd | 4 +-- .../run_dircon_walking.cc | 29 +++++++++--------- .../saved_trajectories/rabbit_walking | Bin 26837 -> 27973 bytes .../osc/operational_space_control.cc | 27 ++++++++++------ .../osc/operational_space_control.h | 2 +- 5 files changed, 35 insertions(+), 27 deletions(-) diff --git a/examples/impact_invariant_control/impact_invariant_examples.pmd b/examples/impact_invariant_control/impact_invariant_examples.pmd index 3c2036041a..4253c24c12 100644 --- a/examples/impact_invariant_control/impact_invariant_examples.pmd +++ b/examples/impact_invariant_control/impact_invariant_examples.pmd @@ -19,7 +19,7 @@ group "5.trajectory-optimization" { host = "localhost"; } cmd "visualize_jumping_trajectory" { - exec = "bazel-bin/examples/Cassie/visualize_trajectory --folder_path=\"examples/Cassie/saved_trajectories/\" --realtime_rate=0.1 --num_poses=20 --visualize_mode=2 --use_transparency=1 --trajectory_name=\"jumping_0.15h_0.3d\""; + exec = "bazel-bin/examples/Cassie/visualize_trajectory --folder_path=\"examples/Cassie/saved_trajectories/\" --realtime_rate=0.5 --num_poses=20 --visualize_mode=1 --use_transparency=1 --trajectory_name=\"jumping_0.15h_0.3d\""; host = "localhost"; } cmd "convert_traj_for_controller" { @@ -46,7 +46,7 @@ group "1.simulated-robot" { host = "localhost"; } cmd "five_link_biped_sim" { - exec = "bazel-bin/examples/impact_invariant_control/five_link_biped_sim --folder_path=\"/home/yangwill/Documents/research/projects/five_link_biped/walking/saved_trajs/\" --trajectory_name=\"rabbit_walking\" --sim_time=1.0 --target_realtime_rate=0.25"; + exec = "bazel-bin/examples/impact_invariant_control/five_link_biped_sim --folder_path=\"examples/impact_invariant_control/saved_trajectories/\" --trajectory_name=\"rabbit_walking\" --sim_time=1.0 --target_realtime_rate=0.25"; host = "localhost"; } } diff --git a/examples/impact_invariant_control/run_dircon_walking.cc b/examples/impact_invariant_control/run_dircon_walking.cc index 24d1af030e..1ed097c4a9 100644 --- a/examples/impact_invariant_control/run_dircon_walking.cc +++ b/examples/impact_invariant_control/run_dircon_walking.cc @@ -39,14 +39,13 @@ DEFINE_double(mu_kinetic, 0.7, "The dynamic coefficient of friction"); DEFINE_double(v_tol, 0.01, "The maximum slipping speed allowed during stiction (m/s)"); DEFINE_double(height, 0.75, "The jump height wrt to the torso COM (m)"); -DEFINE_int64(knot_points, 10, "Number of knot points per mode"); +DEFINE_int32(knot_points, 10, "Number of knot points per mode"); DEFINE_double(max_duration, 1.0, "Maximum trajectory duration (s)"); // Simulation parameters. -DEFINE_double(timestep, 1e-5, "The simulator time step (s)"); DEFINE_string(data_directory, - "examples/impact_invariant_control/saved_trajectories", + "examples/impact_invariant_control/saved_trajectories/", "Directory path to save decision vars to."); DEFINE_string(save_filename, "rabbit_walking", "Filename to save decision " @@ -92,14 +91,14 @@ drake::trajectories::PiecewisePolynomial run_traj_opt( const Body& left_lower_leg = plant->GetBodyByName("left_lower_leg"); const Body& right_lower_leg = plant->GetBodyByName("right_lower_leg"); - Vector3d pt; - pt << 0, 0, -0.4; + Vector3d foot_on_leg; + foot_on_leg << 0, 0, -0.4; bool isXZ = true; auto leftFootConstraint = - DirconPositionData(*plant, left_lower_leg, pt, isXZ); + DirconPositionData(*plant, left_lower_leg, foot_on_leg, isXZ); auto rightFootConstraint = - DirconPositionData(*plant, right_lower_leg, pt, isXZ); + DirconPositionData(*plant, right_lower_leg, foot_on_leg, isXZ); // Specifies that the foot has to be on the // ground with normal/friction specified by normal/mu @@ -244,6 +243,11 @@ drake::trajectories::PiecewisePolynomial run_traj_opt( trajopt->AddRunningCost(u.transpose() * R * u); trajopt->AddRunningCost(x.transpose() * Q * x); + double alpha = .2; + int num_poses = std::max((int)(timesteps.size() + 1), FLAGS_knot_points); + trajopt->CreateVisualizationCallback(FindResourceOrThrow( + "examples/impact_invariant_control/five_link_biped.urdf"), num_poses, alpha); + // Solve the traj optimization problem auto start = std::chrono::high_resolution_clock::now(); const auto result = Solve(prog, prog.initial_guess()); @@ -282,13 +286,12 @@ int doMain(int argc, char* argv[]) { plant.Finalize(); - // print_state_map(&plant); - // Generate guesses for states, inputs, and contact forces std::srand(time(0)); // Initialize random number generator. int nx = plant.num_positions() + plant.num_velocities(); // Eigen::VectorXd x_0(nx); - Eigen::VectorXd x_0 = Eigen::VectorXd::Zero(nx); + Eigen::VectorXd x_0 = Eigen::VectorXd::Random(nx); +// x_0(0) = 1; Eigen::VectorXd init_l_vec(2); init_l_vec << 0, 15 * FLAGS_gravity; @@ -317,9 +320,9 @@ int doMain(int argc, char* argv[]) { } auto init_x_traj = - PiecewisePolynomial::ZeroOrderHold(init_time, init_x); + PiecewisePolynomial::FirstOrderHold(init_time, init_x); auto init_u_traj = - PiecewisePolynomial::ZeroOrderHold(init_time, init_u); + PiecewisePolynomial::FirstOrderHold(init_time, init_u); for (int j = 0; j < n_modes; ++j) { std::vector init_l_j; @@ -349,8 +352,6 @@ int doMain(int argc, char* argv[]) { drake::trajectories::PiecewisePolynomial optimal_traj = run_traj_opt(&plant, init_x_traj, init_u_traj, init_l_traj, init_lc_traj, init_vc_traj); - multibody::ConnectTrajectoryVisualizer(&plant, &builder, &scene_graph, - optimal_traj); return 0; } diff --git a/examples/impact_invariant_control/saved_trajectories/rabbit_walking b/examples/impact_invariant_control/saved_trajectories/rabbit_walking index f9d9238e8f4459470cd4ee21298d98ddc6b223b3..889c10f9b4c85d6927f0ed599e07d37804e3942f 100644 GIT binary patch literal 27973 zcmeIbcT^P1_B~EE017Hb6fhzfV47&4+JITFVnR_75Cuhv2Fw^SU30(yW{ikAPqm7O z0tyHiP$UVWsDL6UDBqs$I@L4Y`__BE^}CNLB6I#Jm#2MGp5$oJ*=4?R<@=xD;ZOte^ISvkcX$IZ;1PR55HNyb7r`Q z1bNK#_6qS23RS$?ufMmKZ?Lcb9MgFoLB1ZIe%`^R9&@Id28Vcrcz5@m6EHW#l>UY< z|KfE2AXD**rsRr>%UIZY%B-zztfo6yS=o75d0J1G*-p2%bF{LxpC*&pO!Ky}vYuw= z?J0)Tg#Qg);o3qpiVGO?|I<!AE1lE{1v)3wM8g< zehj)T;7RC?fnj>i;Awu7+5>?FF z{$koqA5?VW+zeCZ5xU>jxNN%PS)652ydpEs5tnIK_wlRP&FQQzIPq?mGpFBn#lpi| z)wu?bwQF1q^*Fuw^_xP@CUNz8-Sx^mm&Iw0T9<8cX(Fx&Uoa=Y?gdUc=lXqr_)An+ z5Ha#?=WiyRbeLMLOt1jC-D0I3buBcz-pVa*`E;IOfw=<9p6 z3%h-Op&vU=FYh{O8Tz*8x?|P;lc?(Wea*J7y0hvpi@c0d9a;6pkq?)+ykOPt4A#1C zK7iF&v2Xl{(pjiFe{aajD2yI#9kKlQ+64SF%e?*e>-L=P*1Q+>y1H-;+UY*nePKP< z;Enmtk6+ev`nfJ0W_=#V={3Dv)-7xxS8v6Ey*k|{aoXvJ{C;Gpaq14czYOc2g{!UV zFX`Bm<@DB1zu~qiozuHCCh&933r;UOy-NFqJEyZO{LIXUEdIV~aMi|-G5GnSj;^ac zvQY8Sjt|E4VOTX;+J+gXN7(vjjzrau7=m8uR<7BuGZsHj$%`1=<1o6sF-+g>#V(X| zW0=RP7DrIZfT&l77s60Xg_g<4K5-)ISTKoRg zKlh$fvkNj9Rg%Q1ow--Nwemcty|LXTx#nR`Kel9<@!@lv0rNw1Y(#smVcWZFGIRQI z4Wjnd|MGkrpMQ=+%^&kQy~NBZo9*Y}*9li5be|o<1xAx}m!^i`4>i+nCibqxWftMh zV{H8KmruypY3WP+?as6_-d^VT`<5@2r{rb0#%N*Q{%uzHm+pi`znYnGYUdX9UY1de zYjZk}tr^st({9-$?{V}whYiM5`Qu=NPr+>DxWM1J4uE7Zu_4(LUPIIpl z_p1CQdUto<{pxy+P*ut1)7_Tc$NBw-pNzFUfa7%Q>h7G<0m)@2b(d%PqQ|zS7st+A ziPFXlw7#YH0i~8}q)n=&a*6mN!!wPMm>8mY&^#S{pCEsYe#K=H44 z??BhutYwL)c~)YhLK^bo4Y-yyeyF%J&P=?9c9~Todiu(w*3A118iD->4H~-`Ul{Ny z?BYEQT+y>(7rX9b(HisX=MMO5@_fcVQ~WNY0GB4aD!n!Ep#bj1z*{*|etDi9Vtvxl z+k`b2Z1kI;r^PkSE3Osb1=-_Wd!R0Ona0xSQ)PbWMP$d0W7;*x3mqn>9n5}(9*qj0 z62B_~*A&jMy87lg+8VfBx7{UERQ%`LS~sHyXy(sNqkFw6#(Qn+-g{S7CGiDc9&}Ud zA}Uxry=~2(BT>d1Gu^T4m*Z7tZAOjT`whp&xLB=QdKhK@D7rd$NKdqFMr8NV9=A}A zb&{4vQX5WV<<`^r!y2MJK3iP&E_Fu58{b*l%W{$HdDr`gwSDoH5y5wE_2v0Kw(K2~ zJQ$}Rd-SsEdoIeW*sEE0{9E)aBfr`rY(Cy{$YET{>;)L3=CSt==cAm{h8r}U!qA=Z zZoj^Ew?gmrd)U`??!f6>(O$A^u?dR$wkUqxM0ZrY?pUv$xwr7xyt*E3Qe-%^&vF<4 z0e8{OHqq~{c(uS!=SQr|A61KT4O`c84xZ@6?YN=m&(6Yo3;dmKIjQ0J@P(~x+a5u0 z!kesGTr>tfub1GY*|!jtRqnjHE&n@L|L2q%tsxuGQC(CtuaOTbUKQM=`)W-**P;Db zl-dY+?WoM(x!MWcetgR!zW!F6TI}5WBsUMeKEH??v91JVZ7;^1X1~YBm{S{=o(?#< z*)uz{#xCeZx4l94JDQ+(I;Y>ij+%?Uy-E7kbV)qdaQM5z-H$TSiK+MI|J-l-S+SomFWIp z9t5L@Ej`-w7_N`rRCqsWn|21r9ekk`_pL6@sLF`*jVi;><32swHg!0w{iFZE2LtM` z>V!&P1$6_2>T{X1E=Wb{OzGUqK#{BF^U_4(dM(Tyhl?=HTuMaAKom!humeBBT2ynDwP-`uld zY-(Hslrz{tJ805Ze4*yRvB4wD&<)p+P=CA6=<%!7XWQ)KE4=)>&#)K=bjiPGyXYTX z@z=cmi(NW2WHn_Sn|S}>iqf0bIa9t0;|CK{_gv~+hHhK8+)#KQ@$0Yjp0(p^yu0qi zr5-N*@Pj#xSmUZisK7-2_{*D-IClA&vtN5%fc1|aejb%JE=?URwcav1{*E?^Gik8Z zuyPu%IPy8D&j?fWGj)92YUTmD`sJ8kWaxFYU|m$Jip%`{(YWnfYg>wnH=nedJT4Kh zzuKnaLdGzhGUR23i}_kq_&9vl=`OiA=FX)&`Otb2-=rB{H|w59K{d?>exJ|<#jo1` z#%+BlF0W}F*lt%oD$72(rptmFbm56<;^$avJiWu|x7}wBM|T!k#f7{t=D#1z%MY8* z!LtiYZtT@Fz)!z*Up+hB1-%o$NAMY&$=kCVrBlAd?*mK|{BEMjOV|Eb(ajg#i#AwR zuc92k&-`=y=oTwb!tl18odVh;xwhL$=f@b$8@Ffk9NkcKk5T;d=J{l!dfl@^K1Lk^ z*Q_kX8MWvB)CqD$MdNckxmHXcO($RVociNH+Tcdc==Dtfd1gz@(ImA+S-sS!AbF*3*LMALQP$&xtk305aCEQX zW91VQadPiV+k#TuP^G=^z@6!5xQ6oZilB@DlsRm&MM=R`^kL|Ii`!Rwpu|7>h8^TP)VYc*$tOAO^LHE{ap z?+=pw)t{U>at##+y*Xj%sf7=OwHtGK<{^yB7k_KoY$m!px8|{KbTQubXS=BfN|&Sb zUfnXzna@R;&!a|j8WAWaz~VzEt@)U{@@LpXvstL@VpP!NI`?qtJgH`C}r!8dYOhIKvO!UVGZn;Mq;YDMgDdts7`Qq0OPuDBmF{tKM&2t$cgC*k+;5>T zx^v@_e6sCd)uR<~CD#5?;2 z#CTR)Q%um%s1j(k1i*D*KkX;F4=^l-4SAu+f?u{C@DvfwFfu z@Un#Y^Nt!f#%G6nEgl-$jq;_)Eer`wQjvJKucp+2JTHvZC{%izE1YHpXka z@g?l;=C{S}h6_I3scvy^ji!_@ed(Nu$4$OLJw?gteLq(}Uy5AzPka3{?;X065!d_p z{4#WR<>xmJdL8kgN0%yE2H4?3Cm)**MoTg0oBt!`cyshrQ9fn-Nl~$%ukaG~^Jz5$ z$$lO_FOg(FKjydn{9bWCKi*B)&lhQC|GWJ>bRgiQ4kubT`9Ws_PVjKjg%crkEZ}4h zCtx@!LMH=G{Pbi@PLQ<2K{^5S#7s_>wDUna1aOju6DM>;Xy<^Ou<1#ZbV{J304HyH zLM0s(=rq8IoSs}sXN7hk$VnYew9s*Z&IFv`=}DJ#VxVIICwqDVCLJ2+WWb4^o{UN7 z209$j37{ut($Rs=2XqMFBn_P&=!ih)08ZGn14KF{&{3c#Z|Dp`2ZeMRq!YQ=F`}In z(t&`JI&_j~$Axqz-~DhXXnR(5a#w9n$%L z4gqwqXs3sCM4)p3oh{k{BApWGC_u*xIz!MwfldSMgwc)>>8y|r1nq1>hg1BSL-5@H z_~)6muCv!HwneHxZOHsT|9Qk@<>^5NC((cQ^C)@W??01JR{I@KLMQY?w-$~vx^iJF zejI&G*VFF>&YyVK*x$^b)!vtP?N9X|=*NYlFIOy2z%^rHudF;X9A$+s%J8fghHh1K z-DI#mA3vEoKKe-H6ZE6Je2deg{kXW2O3iDGZFSDkWR(W|}kF!Cx?=tV3RUB2YL1nc?&r@vQSGvn1e|%y6U0WI6-}0R8XOp1uDY=;S>-+v~d6y3IPLIqq&+hFg zpFMtLv+BVIwAo+X3N*s-!ggU31@k5xOx+F>o4*P z=jJ|sQocvNE^*B~=bN_j`*SqCu8b{|?{75GXk~+P`O|i`ldDsv$xjb@QRjKFk373H zKTt>gsQikt{fSRo_sI)p#I#{R)oRFB-rZ=Wc&sWO9xT%H43lWtjojqOogBd4LWZ ztXE&Ze_L-(?aj2^#OdmRsZ82uk<{lk%*r35p zOgcqPW4rblxpKVgL^klf>&xfu_1NBfgCkGwIL8M3jA)kEvoqUow`q@=`_=hqJI1Em zjNnWTg<1r)E@1=9x{3`tXWFCCVK3Ke*jW8;-#)WJwI?e3U6{%l z96F`Gwqh+CRIcB0=a#W}W7IOXOK=PubpAlX`sce@gChoWHq9T#2Kibi+`6XCwx8>j za15EVK}LBw`&%qvZ6jx<>P&9V21YyzzwvP%+b6!zWcJaztpARLmX7tV$SY5{R0mdB zBGcQ+w}U@g%5${ROorumK#eZF>yXvOKz{Rw>#4zEaZXiC^utZB-^pipZJ4B0o9=X~ zv&E*?Z>!`%OO8Z-d_G#fC(Pkkv5vMps9|H9SymV1iJRI^{QTWn9;-IN^LmV#yr`wc zq>^pc^0IqNj}7TD5LC2O+hIqO4o~+u9maRvi^?;f7IT{OFGaMf zyvCXZ>p#*&r#NGiZ+io(GueQ#(~fMG@8`_=Iu6xZxq}T%3r?|Z;Le$z(AL#i|D6q5 zJAH1`(nDOE>W3M312?ikIjtAU9_-;-8OX&?I7qB+9`#n_a$Qd_~+(@d~Dex1MGvfI=59o)*c z*z<66=mGw7HFosZF1`&p(;i8=yHcLBfj!)ZpIm#5GxJ^$`Irk~gV6Ms5jMv-(}@>4 zHgWV|gXD>AVsnpjZR`jCyxO)C8}xnk9|l94aV;9Iz3zYW02{1*?r2G20oMQ@jkf&S zj14NWIqEnd6ql_S9q9Tbjt#mu$)?ri1?b1F$+|`H%h{k^d$#Rv^pS1!qQzs&fHC~% zAlUu&&tLLqZbr47<`Ji#zlNvPYyDCl-?ri8KE8dOzP31&H;RdrU+J0CeafG4P9JV> zSS0IsRDO_edF5`O=JeA3dWpsk1G(??>pfOX4t6?H=f%zJ(b{t7&xsY9XS+JBd@}2* zjX{Zgp!YfR@)fD_!2^6XA8gntA0F1TkaM^#-+0nJz~^DIe9GJHBP@F#mG7F z4yV1j6mm_5yRO&WbJqKd^>@315Pzo2+&#Ynui zVkBN%F%qw?7>SoxjKu3JMk0Y?Br+&QB86f^Ib@VWMmc1ZLq<7dltV^2WRycjIb@VW zMmZSD!B7r{axj#Gp&Sh5U?>MeIT*^pP!1c)VM94=D2EN@u%R3_l*5K{*ia4|%3(t} zY$=B=<*=n3wv@w`a@bN1TgqWeIczD1E#*^$haKgxqa1dW z!=7^3Qx1E|VNW^iDTh7fu%{gMl*68K*i#M%%Hcpc94Lna<#3=J4wS=zayU>92g>0< zIUFg6Bjs?U9FCO3k#aav4oAx2NI4uShoi_*hhHgHB8e~*S%jfTBMe0zVJH#_Ly<`s zid4c-t$dXr}WX%ghiH)p!0hQRux))H1jjVhDmDtGISD<9^3qvV4vit>9 z%8e8N0hMwiB|t!>+(;1+P$@T31{5f%1Hw?sjZ^{wm2xAsKtQG3NHq{pDK}CN6euYO z!cfYMlmr2lawA1SK&9MBSrAYuH&Pe`RLYH%1_erLgD{kGBh^7brQAq;5Kt*MQXvFX z%8k?r1xkv9FqCp5WkNuu+(@AiP$@T3Dg;!@jT8$3m2xBHLV=QcAq=J5NW~CPDK}Cx z1XRk6R1E=@awBy^fs(=@45i#i=@3vUH&Q$VRLYH%4*`{OBLzf2rQApfQJ|!T2tz41 zQbhz*%8k?!0hMwil|(?L+@x9}lWK{~isr^YnsuqPfYeD4WcR<|ebEY%(jF zo6L%`$*gE@GO3pEPa{zZvVl;rNwq{qwh#g;v5`%LfJ$s+8zG<)n^a3=WGA6`gH%go zWG^A0Qf_27A)r!jWIrLGQf_2Np+KctB9m%~jBF}|H%NDqY%2s*%8hI+1XRk6Y%K&- z%1x>zGP1i+yg{lZGP1uAP$@UE!w^s@H?qeNP$@UE%TS#RLV`NB{H%LQM^H_B{H%P5l|^NvJ(+dDL1kg z5l|^NvKvvLQZ125wM0fXB*Gh{+{l(hK&9NsrbIxc+{m^>KxuA_R7)7CmM~H+VWe8Z zNVSBKY6&CN5=N>ej8sb)sg^KOEn%cu!br7*k!lGe)e=V9moQQ-VWfQtBh?Z{+Ltg= zEn%cu!br7*k!lGe?MoP`mN3%3gpq0qBkfBVsg^KOEn%cu!vA*&D4G0!laPk=Q^H95 z5=N>ejI=Ldq*}sA`w~W~C5%){7^#*pQY~SmeF-Dg5=PpWFj6gHqFxOoCjPfsupHO}vem?nuSXKCe zSi$&#SW)UP2Xq>EjB-GyfyXEZbQ*Y!azLknzaf+ZIt@HVIiSnMmeC!8baOk~OdG0~N*xDvS?Q7$2xGK2TwNpu+e-h4Fz3;{z4O2PzDIK~iD( z5xIl>h*TJUMD8FzA{B-okvqtbNQL1?)6 zVmNdv#zUuKKy)fbM5kg%bSlQA?>~Kduy=^``GR$0{riIE0Wlb*cZlIA0b)Q(fEbbz zAO@ubh+!!KBrvjEd0N#4%>$|nS`nC7W?=y-5HVI|L=09L5u;T`#Bh}nFJsVXHu5+$xY5xC$gjt^$dnt3YDxD$wr>nvd)E z1+55G3}0GU3QUY&6%!Ls#l#F$F);;IOw2(Q6O&NI#4Lm*#fKqA1~V}xn2FKAOpF6& zVgxV~xnU-4a~$iU?xTYGm#r+A}h>P`IHtt&nMn1VJ#}y z#bD@EjD}9daOhNwhfc+S=v0h|PQ{SuRE!B0J-rQd(f=(XhNCBF$OVPBAc|C|(Hnp$ z@}H7aQ^7wuMua6G_y8dW2qZwb0D=N|&|ehP?u7?e zK?nl^6)GG7K?eveKmY;41R@xK2l?RvSP;}up$iC5Ko|mo4G>a*zyX8@3W2Xe5I`QJ z1z`>dW>n@n)AEL~& zkjxt@@e)YVwe!~?n4tc-}kY|FD+-Z*2-< zw*Re7A~yRsYm-ykX_Gs(qB;I)(KvHvqlUODfAIeOk8N6OsOUC*HxZ{~$PIs66bY}HX%R8|+ zX4U57a~rDTYZ2=mL!WG5>y)n69CBp?TetAWUX*l-)pSNO8pY=PA%2%rW z?E1Mr%CUH5#eRH+t{4_{ZQ3RtXXkdPIbmXr%Wda&mX&$pYP&~Eb3VyAYiIeA>3=Ta zET@j^zOem#uESlUbp^UpIOC`;4O$vpsTac*3Xp{p-^!v|gZyQO9?K%Zk4 zhAf_A#;RS+_B}MpmDQ;|&>_)y3Tqd;&ne}77uL$9qF`IR8Ef9UM~Hk|ENi?l+Rj}z z230=V)?(GR$@qCig?i$$2Iz)vNKwwiVjOblT2{}Gr|`)ntxBWC!%>RipXQOvE^_TR z&8+SAwLaI<-M{&d!ckn)&EHNhez1kpJ>6$xo}E6<%ziVWr)CVR_VUZ}Z}U2`21|Zf zYkpbGwn)7jc+a{eYxd<%VnW#|wxe@&=*W>1*$#DQWXPHx;u;>f@}b_d3a(MPL45w; zPh6`h8g*v3p1`$>`Qdyp>;h*l_w>|nKAh`Px-vf7@;qmC(z|=#A9ft0*~i=|B89Wn z>$RdbxEEhap?v?>)$-GIRN8}Xq!?>Yy=Q=MtXb=Wh2iM#pvEmrSF548YevxqyKYhC3n*Sd z=>iHDP_}@g1(YnHU;*U{C}%)114%A}XbS``P&ycSiUe)e}}#p;^0KP7Ma3qS38V$~W`= z3#*&xMjK2)#aHzPxNY@8?~Ap<3>t-?l9n|$VQHAlsQz914{H=|D#Z`Z=nb1HByRx;W6o5q%!$@<5LVIy|bs1Kl0y z?LcP-`Z}Vk<8%Jk^+u_2B-9w8am4?I@Q*5J|9^S|QYS5NxB}-XaD)P;#TW)Cmck&%lukoWj7t3!JsU@d})%z#$5p zo4`?tIH-ZM86u8j-~cRu0|zs376ZpGaN;5kS>Rkno$82#95}my;~F@jfkPQMhk>IPIBkIg z7Bqaoi4Gj%z_|?^)xhZt9LT^K3>>?_NsBL5|FwsWzi%A<-_>$(H~in)B<_R%TbqJA z;J;d%sC?W?!*84OQN_&0?RuIzq3?ZC6E9xlT_-Gy+)}j?(06b5q#)lgR25-o|MpG^ zstmi<$@cyWRMFR}pvX2HmF5hI9D3dnmDJv9(`#@Gd^M$PY|ody@vRbH|0?q&e79SQ z_OnPcoYH4)k$>n{oMoKlJ@&f^E?D<&c2$}){_K2e&b*In`G%EMe!9hTPHTSE#__@VAGoLc_@(VNb9;xt3G9@=~4aCKg0r8vAc;_7bK?^`u~WbzL>L`HvK|Iw+|@RAxN#jOB+9)gG+LUIpbX2-s}GeJI2<1XZL!q@n*JdMD$j< z{0wWQXH;jhek5zZ=B|ZZv*|3`6rFhfE{5%&8#ruvlLc%)yEhXuedVnA`G7OaO3PTw zafL_X-`8ckJ;xDY4STazX4~t=p)IVHZR0UhPGzxH)_B7;yp`=UDMHdO0uaovfs^MoVsxSq4xo!#xdfpZ-CsrRaqXPkXfUF+MfU;dkG zxzcfk7H|!5EB?n4_yGK8?GfpyD;(~`qwd2n^&hGJrYL2UpKgn_&Ct`l@y#ENJAj@A z_wBf-V>^_k)z!wb;v~x6*}TuI``uA)WA*6xM-x$A*8FZ!vNovTNXg~-5jkK+0wyG2 zJ_4pA)NBMyM!;MIOhv#% zC)j8bdrL%YC&3O9Y#PBP3G7m-jVaiRg6$`<;{=;bYF`Pql3@1;c1y%|73@&KrWEW$ z!Pb-7Z4w(yu%`suNU&`J`&O`31-nzQAq9I-u0xn_;aw#Mm&_f^AB-TJNW5}1v+9qAEuE^S8n z+P6b0jGCY?S2l0&Z_pZj4|{Spz5QNPnf$Wx2HPpiO$8FQOcU$fJwUHUSv&hlq+bi6*NJs|6xNyq)T$}=sxo@XW3E~Gp; z_~dD>x!dcBx1BAxdY^~1Q~&xDeLEboey5u+Yk1$WRjcQVS(CKBUlJ@>w)0W*!y9#~ zSu5S^OPd8eWUZRz=!II|VmrOg}Uh@{}Jgd*y&+hc->7ih*=i&r|eFcZOUVc5l$-bCz_GZJG zoHvU&>%e7x>f48N=4W)?q_=C!8P}xL!CFbUq?f~!=r%Ek+jjoK3-6}rTTpDXke};V zL+`VHZ0P6BYQFI~_V#TnuJyqWLoXL0&bo7#afimvX6^bc&41Y-ob7UK27bM!JKOq5 z@45yP2jGm&6IW}mu7|cRd(OqY8}u*1`5PR$!6_RYtif3t z9G}67861+SbFt`D4i4hr>ELJ%PUGMJ4$j=*m<>+W;4lr&&(x8bIIx2=IyjbtlQ=kh zQ>R$shz(BF)Ipj&hzI>ka99WDb8sXFr*Lra24`*Rcnwa};1CV{OK@rj2X)%NRs0`D zMC|=*|CZq3XblhI{ckHIIL!ZVDRh1K};Ah=NwT{QOt@6n3!rs zK`@XpD=44{29RXr>*=mtJ$TPq-}|n0-(UB-*128vOw-Ta4YjBG*?ae$w6060=|{E6 z>S}6gf4KyD8Ta?{FgCU~mRa_&vFl-N#Sdhb+Wd!Vf63jaPxqPcw!nSPY#-m5Zu8~t zv%Ea!&yz1ye%g=!IiCQZdA`O$?s6aZ>2tgSjNN@bjRWSp&-d!?hW?XXEK^?=ZvK*28PM zV3HpH6D7Ok_ADoZ&kI)ZA#jB59vs$Zc~MqST&aVt-V8ME5NcBQNapLdj#?TDJ~u zf|47jTu&dIk5W)0y}1^p=)w1mEyn&-ptOT)ZZ8~Kgl-ll49d4?g)X=c&Iq06hr+uA z*Krxoq3umtJn1N_M4?`HM|m~eh8E=>Z`(Q$qks#&yq7GFKtBCjwmdO69F3{k@$~7a zWITD1`a(66A2`+H(dE9uQ!y8}yqD3s$#|EMEc!)VQ*=42*WH#D?a{3fzpvIfhNHWE zS{&6_+YKe2Ok7tv-w54}s`%E`;uE@+Rj#g+FcrmiG)x{~u?c-Ij>x~ZZxkv$r<3iR z>wxmJ&Gl~&*?_WUmOgslcOSZSqx5l6t4bx0=8TmSw?ld&PV_|nn3`@6ivrOTeJ^b@z@ibHNk4-liVTr=h#8P$s3yB zFIOCX$g&J@Zv2Vz_!03qvE@16#G>_hTiZIGhnjCf{yMK)J!#~N$1J@4CaU-;a@?eU zXA8i%xXHCE&G;>P`> zEm*ZFN%Dc(ozZvg2~)?6*G8pPVLb!t?Lc`pNjsMXeZySgn#m7Z=-?8^>?F^tdpNbQ z7jBokJjA~&Tt~k)h{M%yyEn*q=!DBO9a}vMIgj5&QdyToXt{#fH@O|^1 zjpNYMM@462>UT%)4qU&R>aYZT+5Y>X%q17s?7Vu$Xw2*1 zY!qvlrMGF*Vf^YA`+58-gv&Y|JMrW6as0!ycYW?~vdjtp2*K)3&@Bz#6`+^QN<{8EaDAq5Yif@vK?Dl0$Qcy0Er4=G)x#EM+bG z>((t?_nPh4AYsWswuCiuzd7OP%7>_G=gZ`ZZjbPjn?+|l_k^KqPbw}s&l!UQFT}TA z&-&q0$>?}Z=I7(9JV8(HGt;{^BAhbY*UJme zX(XPb3c+=QJ?G6=wALr5`=A&GO+^ zl+o(4?)_%_P{xsFPEj4rP$nb%Lq!w)MxZxaQIY&rMCgS*sA%~lwVX`;xHe>LWL{HL zw9y&Qc-ym_uwmYw_Rt)2hgMKkzobeu;x}yws zFU5zvmz9@oH^Sk@x?W#)n&Bhu$5mu%dEkTf+~<1)VZ6Khrh!ec9B($;|I{huI9|5q zoWa&;BItnzw+OK|JiYDGP*y{q+BbbKgzOC((Tx&H+r_~NOhmMD<~H&UJ+0)61~aq zv;X%44i&Tvuc=qi92Me)3;I|0M(^bZ-pf6wC3c=<}7xh@NBhIb)}cALBb>&Sde) zqgjidamKR~8l`qQ%(ZceIM_zRfHO4zdaCF6N1Wa#@4Q|mUvX)%@%oUc$LM?e?E!X* zU93S|Y*L%iW~_hDiwQq^&tm1Q*R!7=)L1#TpW>%6j+K9lt=wTXn+?!Bo#3)WkCm6y zpY!{%BP&m6X3;SIHY?vVvi{eT<*eMtzu;--OT2Fl$zAaf?~61Q?#$mm$O#{b4{~>_ zW;8T!*BCuCtdQxCn}IUg^zE|bt~<)UxE`0fZA4GmbZ4(`G3Z4`%fe?nU!z>BOTEqa z)WUFzlKw?uDmSEYqnb)kQb&rO<+Z+tZuWx1GNiM+?6M_JP>j9lBG--knJ|v1`|k%hMcX zc%4a)va1bpaHRDl?SeTa_|A$JX~XYj;71YRE-^_AzIb}|pw=^Xp(~35V-HoFMR&}~ z?R2gyP~v987o%eaql9z55fi%1MNvQMZqk{x4qu*{6;^Q420!e(XHr0*EzVhZ-#mV6 zE`B@a@X!X^6`UirGOL4!Gh}{fLa`18~`|Q@+Rg-^U+PcjZhE8-UaN zeD1mZo`>?*x@-@%>VT?jDnsU{USTyF4!r3;tquAfk#notm9FT+&uIIjNrzFE=F!Q! zb}mM7DJ?p+`5cWdUl_S&-;T8?{>z&#B{AVB{fg5#kI)t9mFABkvo6h0&h%+_`wlk1 zS+9K9&4blg%{{lD3`;uAYCf5;;JDU9wvO%1m$@?>(61-I+^2D$Q0a@9Sv`AxM@bLU z91_ig@n^S{gV|pVxjL3#7f<0HagAa_r?j;C$~C)eHM&p9c>J^1)>~zp`{MW0Hec{M z5|5J{>K2q;|B4p&jad*g)*R39ZSux#<`5KQGlVNn`M^IYmsOgbxrw6J?a`PJwiOlI zpY9!*@{`pZT(4`#Eh{;-EbE(D3ohgD8H-k>J=ugyw|}y;&%cK=M_erIVx$EY%^Pg7Z8uho4`p%>9 zyHO!dcaEIL8Oy3uo%dDYbAIWC9j)r&$Op#D^S1=!i%q`Py{EecM{ho8;)?d+%=)fV zS))4m%l%V7bhPd&I%2RqCMU^}9b;lp=&NiOD7J31PepN_ALD& zt}ENTjjZ{?Ww~7At$TVHxrA{>_rHEgKbFLqFVD#sII1bvRWa$2e;0F3HuPZ6H(K2| zyIJ?<*4h1u>**DFsv!CT*UO$AW;%T)XZwB1-eGOdv9|VCe;sIjlpPYuMHs zXK_m>zr;C1H8c05oItw=rpi{9wnUlfNAFFTAA-NGE4kBk#s;=YXw$Ku7HYHhS{1i` z#BXE!uQWRS=&d;)@cwi60n&q<@D(ToaQ=n}|Ip4gJNLD__Y55;$Ma4vJ*~SAM$y9j zIlAg?AJTcTE{YfM3Fua{TOHcWdw>#z&-WqnMbO((KGs=Y>3{+)rZ0Qw+Xk(%uxz=m zW&qkQzd0l9l@8iB>%`2l?~bD*-+njHyLAFZ=su5fKckLLdD>6@@wFa0SN-{L^*D8O zDR+TicK;9J16V~R|6uld)X0u|`J=IB&@g9IwB^I6J!aadXw&ETjei-VqV<=uv;53Z z(W=ngxx+r9q9yMBJ-V5oqIs+Ll<(F@MUy+R8?{;C0jzk@Bjjs)>&{FQ7vvX~Xcy7U z1kFD9F4NrQ2%7kDgxTmsE$njLGu7Vb5uRVE{qXTncf4x2(c50y2ycD7EAd6rb-c&5 z$pz;U5Apyu7Ds%)aK6v*nfU0s(b4Dq((wULE>-u|eY`FB+Mu<+3-H35BQ{kxbVVLb z%3F-itAm#R=zY9H`C+t*ZGUt3$4e*(M}FMieF=F0i^bXHvXW+(TI1~3DaR{xopH8b zLT2gUN}P3U#?Qa*cgC3k*WH(WbH(WeTDPlBt#Im>$-UL@oxu0Kvkrc*Ohe-qxb~9h3Ah~qg$iukN(Ro9^FMI-|B75 zLHFy8yt&!Tj68ruH&n0P+r5P-ggV) z(aVUE!Mo$V(38zBH=OP)K^fVtJ5O)@3nlCI+|ca$F`~G>=Qj?1Gv}5Cq0IcnhvM?j zq3oyck1T2(h#sfsA35TYkDgv%>aioDK6<___-VJj;ppXnU(;r~2cuUv)Lgfke-`7pk->vlJTalu4!twJaF99!UXI}9&<=MkIW z+8tjCZ&g}1U4gNqc@;KjgA+G7_0!t24L@wPeM*N(9dY`uv^TBZ_QP4G$5ssN*#&2p zI$N{FF`&4j%*+$U209DS(`_dd({o0lSCuQC4EVSN7tm4~Ko);Y%Cez6x$~7(e0G=md599Yfrb&s;Tn}FhqD@Nwr`4*Fie^whmaPcz?4!8PhPqTS8FYh2@aowM^^_U4*g_giRjON(o^XX5?T9V_@?^&cC+ z|KTx3*o}*iDaq^3A3k`q7fKs@c>3+&AtddJPg0r3>mF}d z|Gn3GOp9v3$}fJu_MwJ9)>K-@hE}rj(yu>nZ`EbxQI3wj)9{$gn{r;Pdg#uZ_q^J%>R%`3{r*KAhgODdrXC zFFBn@#dmjyuH_n_Rna@lYPdSX)V#awv&9vwYC6Y6mEyGcWhWB8)}X?>n~g?%X^pBo zg%qD|wHH<2smgype-f%xZ?2`@%L0Atc45YZ^r@`cN=;Y)9L%a;eSFTeWHhVZK>pde zza^{QdLsT3&5cVmH^BMEy9^8J=;8DV zkC`z!V^H{&jgisA=b)UZ39i0{V^P7&ebwPB9-uD<`>!Y(Xrl5v&xb~K|A@ZFG>VuO zZ-y#wJl+%-ortRA9%SB$8^x;U+qYi#a2>1O?56zymd|k{o4(RZnaXOcwVyd>$PDze z-hdwZi_Ou!0rD~7nlJIM%(dSKT`A=nZq``ikeAKrwb_n!-nQcOp3d)FzO+B5`{YfX zdZCLs9sPth_RY$<1`EeU-{`Z7(@gcr2#&kSsWTl6*M8fEe{^fpJ+3Y0bapCMZf~f= z>0DeE)x)3zr*k4eYwgDvuHKdQ&-%4lj=z0)zTjGP5Pll8d$hCP5>(`K;dA#JTC5tg zG20S#WVP|n$@y(Qpch9Atg4O&8KrumIvaDD#;%{fWq}AK{6xW>pexXdGAE(AvTRuPCfm4f~ zno<_AoYUOdru~4$HJt7hk3j}H`kcP(?6T|^d0ZotqxWJ4|K#+J3~X-IYyzj7mk@H_ zV>PFfzTdQG*gE`j#pu@oM~~vSIZI@2Pfc-g$h9Mf^!4zU7sI^DbSm)I8 zy}kB^p`_bMZxa)zqTqR3^`d=#;)l!XFMf4@Fdtf^bPJzx_Yd?^h8vZ1iwY>ETO?35 z-6Em?5adPCiod=F3MD)AL&8pc5IQC7%p0R9VMorP7^Ng*QjV@a)h_LxB}4f7#mDw* zg3;{}7E{B+Way6KXL>}13u~0hWL2%NVNJetK;y5z*y;TdMidg@P$ATOUO<4b_zZ_4_Sj_s}pNv*+Y0l1@`oqO)f>Ed1G2pIh3rC9ZzZrDeY=H?HpN&R@nAwBmGJcKaoL@aEJU%-6WK`M}ljxt1}& zFpASkjO$R-rkJaLYb5^LZE{5!%I;yh zc7BXMr>!}4=TD7f&gkjaO;_8E=FBtfhhLj>hqLmD3|Ka67-uU6gcB4jdWdW?E(S!TL9=~TTyO@P~882lm+XY6yiZWumUv1T<{yYA> zx^pV*Wt&zLSE^3>mg?{{{v>aF1DWprs?u4KC?)p@j#lRT6l3 z^!swQ-ITV??=8E>cK_JtQ{y$$Si40xecFH5XW6E@ectvkV*3}gO1L%qCEL%w%e0>5 zrkrhQN@4iyX`Fo*Yc@cw9@nGpcDJcdTXQ|zUTJ;!!UwKrRO6oY19G@tjr}*R`qhu? zrG9kltp*#po`ykXT`j9Q`}d8|-D%;RUBb!uN8OzHfcGE!D5E1~S!e*);BScV@87j! zXAM{9zSFba$QrlxHTB+fiEW=_e9U|Bb=D$t%&t8#4y?>{g+|`k1+3k;w~LY#`fRVN z{3U^>bJ;%goNUWIPqY1-Et_vL*PiWb-FInT!3b79sLi6-oo=k$c75h|`D|8hdZokN z^(m}>P0ZaBgL7H`2T=yjht{(Gn??p@?@eU=O-2|5^!mj5xeV`LjxVuuBQ_0K8PtTG zbtA_$KGT4A7Sd4S*E>nY2#+*+o}_k9NZcv!3ttVWktW>CKM>}`k1n?fY-IC z9wjF7W2xRFCeEwjOAT}qs&7Cg7^&a_9RQx+sh$Tq9MR9H?nU$}bdBgtpbrsU2lN=w zQ9%E|pj&|6Ky(7C8-m_PbULc95nYV>2RandkErfL^ct$O5Pbx64bUT~J_))a(F3WD zNAx$!2YMILsi?k0bRkL4Avz4vPeAveIwR3d7qPh|2 zJw&GgeTC|+L?@;CCebB9Poz2^=yybSqk0+9xu`w`x)RZYK*yoFF41E_M+N;8bW5r? zf=)>EJ*vwQJ&o#MpkEQ)3G^bW9~0dd^jgqaK_8{MCg_nwN2K~6(d|HQqdFPUw?LPo zIyKRkK^F!+7j#&vpMvg5^h&BTf<8!eJ<#JoM+5y!(!)g^8}w(Y8-v~pIxXm{po4?*_>y$*CX6x%**cHlxyRJ3^4Um4x!;KMJG)r!!r_=J7&-8H>R@bz~o-gDi5 zp~q7Kyx%@;g18axJNkaQM-#Us;R=aTNN_@85)z7#2t?PL6^=SKSr-+p(+bJnz6>93 z>w9Wq^?Q8dfS!L^^Rf8yuhhWoC!#|4);hm4{LVo29mMy}2%F+8se>I%sf4+Ff`Cxo$)!w%SU!qZd+p;`|S!HzH zLn0ay$RzO#30sBoRv!sJ9k(n`RM&`TR-8vZ_1h@SGn( zi%svR;mmI?m(pK^;&XiqI`uFAixyTvUH}s7Bq0uoY)C-U#4$Ei(JAS$Hjb>nJFYV40D3oe(ZJs?CI3hQ9}@30VGfCIlAwmfGEE5I z^*B52zVlf=547#-;kPr;tYN;>#`W%lvp1|v9{Fe~-Z#vlw6vlI*HaSoN@w2+h(fYQQED7Ykr zlC;1P3KOA&04o2XVxLsn(+YV~*$x%yv|yDKn$iMMDC{H!ne^`x3Lv3V0XhtzGk{d| z(@K0&K~F2+p)i&dw9-OUC?F+;pOg;@EukX>L1+`EJOFCAd(}e8jH$k2e@`Hcw=OKFlDm$prpxQ!K0n~R;sX@(!Yy+tB zpk9N@3t0$I>#3?u)L)vNASympyNN1Hvlc|%2NfLDV#sDt)t{*2R7ECP4#)<8YEIQ< zlKp@z0jTLzbtYL6nmr&YJ5{4ewgj>YpuSU;nq*NR+W@LORj)~Q1+oyJ)>BoRWL+RT z0V+OKyGb?%vKFB3g9;8=8pvjV>JRET&EAkK2V?`NY7SW)$bOJ40aepUwg<8zkUapE z9kM_)TSBr5puR(Ph-Ohpwt=ehBx^*oDfCqTuAEECPfkgNr$`;dL2 zSsIef0M#F|QZ#!*vK){NfNT|Hbs+lzSpu5HqS+pj6(QLJs&R;QH_yrZ&ttNPCtHxC zx_C^SCLZr6qjMX29gIjHLymHC9R3eSCxZ7U$G-G<+_?E^TPJNK90%8kN2dn=%cCBG z0!~tRNed=Pp(7M1LSZ2k1k!?j(s>6RbI|EVJJd*L8SMxIjR&+D(0V|l0nG=r8qj_~ zvjGhVv>VWZK*Iq|2(%o~hCtH+jR>?I(29u0L$fT9C4p=UWJ@6H0$CHtzCiW_vM`WE zfou$9Qy?n?Sry36Kz0SPG$hNS=-6(P&gq2?in+EeyaznaS1_m5Z6}QlQUvXmHy+s2 zNHOL^;P1GomWtKC`}FFOX{882LBo@MW-Bgx_%v^QCswika!!v|F*7}(u ztVKb^#)4UjO#1_Q)^(dJ&bl5AEZRRq@w)B3p>AOTide^?5j(4XDDscoZM$k}N5^rq z?Jw19ztb^oWh3k5QD@Nn75B0l$xFDu7UU#smK|XI+)}ozbn3wwn|!_8!lflEA263S z(r(WgjShs0+uc zPtWYi?R{Xp z?=878>sRAB?#9_`Y`^`jiq>n5VP}PYPEA^91|<Vm*r4mr;Kuac| zE z`pzTszO=#)HVx;U9CaMucFV8u%~t1=3syeCm%g$lUgs;vOpZq4FLo_@M%yR`Nq7K2-FRihRZ6?aMabI6lttx6iFXZNl0p66*}z zU>bMY@$0wx#nbObDPr62)v{P5cP!q!`)2;UA&MgfBTjC5h8&+Yt$dJ}rlar~P`YEv zaO8OG-Aj2+{71z=?eq$l0(HmGJWs=+&3-BdxwYIq?$t8Ipw}BScjp)=hR^?@HFDy4 z#iq^Cp>|%g6jKks>TYUptT^y~Km^|Hh%@rKG1wY&ta z8QjsblTwf72UakU!GM8*H4JQEU<(5~7}&$WK^WBIFDPDGITEj}9ElfKj>M}gN8;s` zBk}smkw~B%i44k-NTD224jJW;Q4Sg9kWmg9<&aSh8Rd{s4jJW;Q4WT3FqDI#91P`P zCr5v`D!?nsF<*=h1c9g@Oa@bQ2d&*%?IqWHiJ>{^c9QKsMo^sez4hPENKsg*JhXdts zpd1dA!+~-*P!0#m;UIEo@hinrBoT%pi!c;vgrUeI3`HVgC^88{kxCefT*6Q!6NVBS zS@KGhta)K5v5{3Tpb{Hd_W~-hk(Do?5*u0jN|Y>qVJP`VmcM{XzL5YRpptJS1PG|) z8wmmeD)~mjfD$EfKp0BCkw_q*l5Zpy2&m*6i3S2H`9|V_5+wma7)rj8kRYIvZzL!P zsN@?73j!+nMgoI?O1_cMphQV*5QdU(BsvJFzL7X0pptJS zk_f2en-oiAQY?{KQs4OZ*a%CbOh$GE3^4Oo}Bk zDVE5{213au#S$6WLI|kDMm7-wDzTAmgn&wHQY?{?orLlPDVE5{UP3@6-^gx4KqcSE zenLPc-^h+aiAu3VCdCpN*;EK8NOzKKD+E;XjchCgRPv2%Ed*5ZO^PKlvb#{8AjJ|H z*l5b?!A)u0PWZxm6l5b?^p+u!vB9mf?jBGxH6C~fr_Cr7= z-^d0;KqcSE7DPZL-=tU~BfAjg2~sSPk$s4OO1_buh=5AIk-dn3O1_cZh!T}ziA;(m zGO{5NPLO;fTM_}4d?T9@0hN3s+Y$k#zA;iPVWe2XNU?;GVhJO~5=M$8j1)^4DV8u& zEMcTr!bq`%kzxrW#S%t}C5#kH7-?U^NU?;G_9cuIOBiWi!bq`%kzxrW#S%t}C5*H$ zVWe2XNc$2-iY1J+FJYuu!bq`%kzxrW#S%WL3jvyuVhJPdOBgAZFw(w+kzxrW?MoOb zmM~H*VWe2XNU?;G_9cuIOBiWi!bq`%k@h8w6iXN>mM~H*VWe2XNc$2-iY1J+FJYuu z!btlPMv5hjv@c<#Si(rLgppziBgGO%+Ltg=EMcU52_wZ4M%tG!QY>MlSi(rLgppzi zBkfBVDV8wOzJ!rt2_x-G7%7%8(!PX|VhJO~5=M$8j1)^4X{6ITEj~9Eq1#j>PLLMPWV?jS!R5r!X;JIIen zgyBcz4)P-sVfYdGE%CNe4u~*3MmZqD@EGNQ2*YFK)&;rwk-MO!9FpIIa!7s;$|3nZ zD2L?tpd6ClgL0^HG4gv*qU86W9EvvAR}RUY5yv8*I2H-TvB;<^7DrFEbR{;b0OC)o z0OF6U0RM6g(RP(HL=RK|(GL|s^hN~`eNq8L&-5fqiGQkyXsaqB8mo$k)~X_+xvGe0 zuPP!Mtcr*ht0JPws)%TFBX|ptbbo6>qSdt^(d=4~Xm>40G`tohT3!nhO|J!sw%3A0 z<7+{p_4=yTlY3qp6YZ~!i4N4pL=S3Xq6@V#(TCcY=tONy^g=tx%|p7eFcWQpnP?5n zL_1(6S^zVV8)hOa%xd$AHw-=#?^Q!$3%N~nDq2IQqB(Rb+C!(JL3AowM5m%jbSm1U zJ8#B}0I&JdZGd%S_2+`-0nr$hGemP#0MQ^7Kr~4O5RFm+M6*-?Vi;MjJZ%U; zw9+s!%)$avBBHITh-j=TB3i48h~}yyqP?n!Xs{|GTC9rHUeHQ={#?*JCK@d*9OY@k zV_hvsG`kig+Fc704X*`>me+zr(`!MZ?X{pk7c_6zp9@-Ps%XBnu#}i+e{D>3pf)CY zP#Y6nsEvs})W$?7YGa}o!jj_65G{k5XcNptYhWhY0W;A8n2Fpl6Io$an@?py(|aYX zGwC+bsb~$IissO%Xb+u=2GOZ#5uJ)A(Wz(?ENFTg^nB*}1-T99aaE$Gih&olnH=#{4ax#*RcXuq@|m6+&2ZA|o_HYU1I8xwt~jfqaw#zZfK zCCO8&EPAB@!aar0L~CFs+5t1s0+@;1FcVo}R+~>{(er%by%N@A?`i|AA|iB3hEVA0dtKo|YrBBD7e&7Snlks9#Auz%NURiJFHG$=rW!ZRp1qlIQrU1xOY|}fW z_wT+#w1o^>yP)L?TA`pt30jAsr3YGVpaq7urjS>vkrpv%-GY`XXmx@XB>pJ220_aX zX{CX8bwf)VZ8d`yFlfz!mMPN81T99i^#@vV$h*2}YaFz!K`R-wctPtGv_wIx60{JJ z)*kw8s*G@c|DpdU34i}?8sT-@ zDzROhORqi<=Kt`*AK|mVzpU^Tp>kQ_ J_h*dv == -JdotV_h - holonomic_constraint_->UpdateCoefficients(J_h, -JdotV_h); + if (n_h_ > 0){ + holonomic_constraint_->UpdateCoefficients(J_h, -JdotV_h); + } // 3. Contact constraint if (!all_contacts_.empty()) { if (w_soft_constraint_ <= 0) { @@ -880,20 +882,25 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } // int n_holonomic_constraints = n_h_; - MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + n_h_, active_constraint_dim + n_h_); - MatrixXd C = J_h * M_Jt_; - VectorXd Ab = A.transpose() * ydot_err_vec; - VectorXd d = J_h * x_w_spr.tail(n_v_); A_constrained.block(0, 0, active_constraint_dim, active_constraint_dim) = A.transpose() * A; - A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = - C; - A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = - C.transpose(); VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); - b_constrained << Ab, d; + VectorXd Ab = A.transpose() * ydot_err_vec; + if (n_h_ > 0){ + MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); + MatrixXd C = J_h * M_Jt_; + VectorXd d = J_h * x_w_spr.tail(n_v_); + A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = + C; + A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = + C.transpose(); + b_constrained << Ab, d; + } + else{ + b_constrained << Ab; + } ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition() .solve(b_constrained) diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 5a72cb1978..28a78a870b 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -362,7 +362,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int n_c_active_; // Manually specified holonomic constraints (only valid for plants_wo_springs) - const multibody::KinematicEvaluatorSet* kinematic_evaluators_; + const multibody::KinematicEvaluatorSet* kinematic_evaluators_ = nullptr; // robot input limits Eigen::VectorXd u_min_; From 0ec8809dc13649160b838cf5c0ed4c85a1c01502 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 13 Jan 2023 14:31:57 -0500 Subject: [PATCH 337/758] keeping five_link_biped impact invariant plotter --- .../impact_invariant_control/BUILD.bazel | 28 +++++ .../plot_five_link_biped.py | 114 ++++++++++++++++++ 2 files changed, 142 insertions(+) create mode 100644 bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel create mode 100644 bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py diff --git a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel new file mode 100644 index 0000000000..5839d87027 --- /dev/null +++ b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel @@ -0,0 +1,28 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +py_binary( + name = "plot_five_link_biped", + srcs = ["plot_five_link_biped.py"], + data = [ + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py new file mode 100644 index 0000000000..7bf31f939c --- /dev/null +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -0,0 +1,114 @@ +import sys +import lcm +import numpy as np +import scipy.linalg as linalg +import pathlib + +import matplotlib.pyplot as plt +import matplotlib +from pydairlib.lcm import lcm_trajectory +import pydairlib.multibody +from pydairlib.common import FindResourceOrThrow +from pydrake.trajectories import PiecewisePolynomial +from pydairlib.common import plot_styler, plotting_utils +from pydairlib.cassie.cassie_utils import * + +from pydrake.multibody.parsing import Parser +from pydrake.multibody.plant import AddMultibodyPlantSceneGraph +from pydrake.multibody.tree import JacobianWrtVariable +from pydrake.systems.framework import DiagramBuilder + +def rabbit_main(): + + builder = DiagramBuilder() + plant, _ = AddMultibodyPlantSceneGraph(builder, 0.0) + Parser(plant).AddModelFromFile( + "examples/impact_invariant_control/five_link_biped.urdf") + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")) + plant.Finalize() + context = plant.CreateDefaultContext() + + world = plant.world_frame() + + l_contact_frame = plant.GetBodyByName("left_foot").body_frame() + r_contact_frame = plant.GetBodyByName("right_foot").body_frame() + + pos_map = pydairlib.multibody.MakeNameToPositionsMap(plant) + vel_map = pydairlib.multibody.MakeNameToVelocitiesMap(plant) + act_map = pydairlib.multibody.MakeNameToActuatorsMap(plant) + + nq = plant.num_positions() + nv = plant.num_velocities() + nx = plant.num_positions() + plant.num_velocities() + nu = plant.num_actuators() + nc = 2 + n_samples = 1000 + window_size = 0.05 + + + # Map to 2d + TXZ = np.array([[1, 0, 0], [0, 0, 1]]) + + filename = "examples/impact_invariant_control/saved_trajectories/rabbit_walking" + dircon_traj = lcm_trajectory.DirconTrajectory(plant, filename) + state_traj = dircon_traj.ReconstructStateTrajectory() + breaks = dircon_traj.GetBreaks() + + x_pre = state_traj.value(dircon_traj.GetStateBreaks(0)[-1] - 1e-6) + x_post = state_traj.value(dircon_traj.GetStateBreaks(1)[0]) + + plant.SetPositionsAndVelocities(context, x_pre) + M = plant.CalcMassMatrixViaInverseDynamics(context) + M_inv = np.linalg.inv(M) + pt_on_body = np.zeros(3) + J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, r_contact_frame, pt_on_body, world, world) + J_l = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, l_contact_frame, pt_on_body, world, world) + M_Jt = M_inv @ J_r.T + P = linalg.null_space(M_Jt.T).T + + proj_ii = np.eye(nv) - M_Jt @ np.linalg.inv(M_Jt.T @ M_Jt) @ M_Jt.T + J_M_Jt = J_r @ M_inv @ J_r.T + proj_y_ii = np.eye(2) - J_M_Jt @ J_M_Jt @ np.linalg.inv(J_M_Jt.T @ J_M_Jt) @ J_M_Jt.T + + v_pre = x_pre[-nv:] + v_post = x_post[-nv:] + t_impact = dircon_traj.GetStateBreaks(0)[-1] + + ydot_pre = J_r @ v_pre + ydot_post = J_r @ v_post + transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) + + t = np.linspace(t_impact - window_size, t_impact + window_size, n_samples) + + cc = np.eye(nv) - M_Jt @ np.linalg.inv(M_Jt.T @ M_Jt) @ M_Jt.T + # cc_vel = np.zeros((t.shape[0], nv - nc)) + cc_vel = np.zeros((t.shape[0], nv)) + # TV_cc_vel = np.zeros((t.shape[0], nv - nc)) + TV_cc_vel = np.zeros((t.shape[0], nv)) + vel = np.zeros((t.shape[0], nv)) + for i in range(t.shape[0]): + x = state_traj.value(t[i]) + vel[i] = x[-nv:, 0] + plant.SetPositionsAndVelocities(context, x) + M = plant.CalcMassMatrixViaInverseDynamics(context) + M_inv = np.linalg.inv(M) + J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, r_contact_frame, pt_on_body, world, world) + TV_J = M_inv @ J_r.T + TV_J_space = linalg.null_space(TV_J.T).T + cc_vel[i] = P.T @ P @ vel[i] + TV_cc_vel[i] = TV_J_space.T @ TV_J_space @ vel[i] + + gen_vel_plot = plot_styler.PlotStyler() + gen_vel_plot.plot(t, vel, title='Generalized Velocities near Impact', xlabel='time (s)', ylabel='velocity (m/s)') + ylim = gen_vel_plot.fig.gca().get_ylim() + # ps.save_fig('generalized_velocities_around_impact.png') + proj_vel_plot = plot_styler.PlotStyler() + # proj_vel_plot.plot(t, cc_vel, title='Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)') + proj_vel_plot.plot(t, cc_vel, title='Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + # tv_proj_vel_plot = plot_styler.PlotStyler() + # tv_proj_vel_plot.plot(t, TV_cc_vel, title='Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + # ps.save_fig('projected_velocities_around_impact.png') + plt.show() + +if __name__ == '__main__': + rabbit_main() \ No newline at end of file From 438c5d512887f5235291b1d5df4b5fb3cefbab5b Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 13 Jan 2023 16:16:49 -0500 Subject: [PATCH 338/758] adding example that shows nuances of impact invariant control --- .../plot_five_link_biped.py | 82 ++++++++++++++----- 1 file changed, 61 insertions(+), 21 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 7bf31f939c..d47de80471 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -1,7 +1,7 @@ import sys import lcm import numpy as np -import scipy.linalg as linalg +from scipy.linalg import null_space import pathlib import matplotlib.pyplot as plt @@ -18,6 +18,10 @@ from pydrake.multibody.tree import JacobianWrtVariable from pydrake.systems.framework import DiagramBuilder +def blend_sigmoid(t, tau, window): + x = (t + window) / tau + return np.exp(x) / (1 + np.exp(x)) + def rabbit_main(): builder = DiagramBuilder() @@ -43,7 +47,10 @@ def rabbit_main(): nu = plant.num_actuators() nc = 2 n_samples = 1000 - window_size = 0.05 + window_length = 0.05 + tau = 0.005 + # selected_joint_idxs = slice(6,7) + selected_joint_idxs = slice(0,7) # Map to 2d @@ -54,8 +61,9 @@ def rabbit_main(): state_traj = dircon_traj.ReconstructStateTrajectory() breaks = dircon_traj.GetBreaks() - x_pre = state_traj.value(dircon_traj.GetStateBreaks(0)[-1] - 1e-6) - x_post = state_traj.value(dircon_traj.GetStateBreaks(1)[0]) + transition_time = dircon_traj.GetStateBreaks(1)[0] + x_pre = state_traj.value(transition_time - 1e-6) + x_post = state_traj.value(transition_time) plant.SetPositionsAndVelocities(context, x_pre) M = plant.CalcMassMatrixViaInverseDynamics(context) @@ -64,7 +72,7 @@ def rabbit_main(): J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, r_contact_frame, pt_on_body, world, world) J_l = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, l_contact_frame, pt_on_body, world, world) M_Jt = M_inv @ J_r.T - P = linalg.null_space(M_Jt.T).T + P = null_space(M_Jt.T).T proj_ii = np.eye(nv) - M_Jt @ np.linalg.inv(M_Jt.T @ M_Jt) @ M_Jt.T J_M_Jt = J_r @ M_inv @ J_r.T @@ -76,38 +84,70 @@ def rabbit_main(): ydot_pre = J_r @ v_pre ydot_post = J_r @ v_post - transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) + # transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) + transform = M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) + + t = np.linspace(t_impact - 2*window_length, t_impact + 2*window_length, n_samples) + t_proj = np.array([t_impact[0] - window_length, t_impact[0] + window_length]) - t = np.linspace(t_impact - window_size, t_impact + window_size, n_samples) - cc = np.eye(nv) - M_Jt @ np.linalg.inv(M_Jt.T @ M_Jt) @ M_Jt.T - # cc_vel = np.zeros((t.shape[0], nv - nc)) - cc_vel = np.zeros((t.shape[0], nv)) - # TV_cc_vel = np.zeros((t.shape[0], nv - nc)) - TV_cc_vel = np.zeros((t.shape[0], nv)) + vel_proj = np.zeros((t.shape[0], nv)) + vel_time_varying_proj = np.zeros((t.shape[0], nv)) vel = np.zeros((t.shape[0], nv)) + vel_corrected = np.zeros((t.shape[0], nv)) + vel_corrected_blend = np.zeros((t.shape[0], nv)) + alphas = np.zeros((t.shape[0], 1)) for i in range(t.shape[0]): x = state_traj.value(t[i]) vel[i] = x[-nv:, 0] - plant.SetPositionsAndVelocities(context, x) + vel_proj[i] = P.T @ P @ vel[i] + + plant.SetPositions(context, x[:nq]) M = plant.CalcMassMatrixViaInverseDynamics(context) M_inv = np.linalg.inv(M) J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, r_contact_frame, pt_on_body, world, world) TV_J = M_inv @ J_r.T - TV_J_space = linalg.null_space(TV_J.T).T - cc_vel[i] = P.T @ P @ vel[i] - TV_cc_vel[i] = TV_J_space.T @ TV_J_space @ vel[i] + TV_J_space = null_space(TV_J.T).T + + if (t[i] < transition_time): + alpha = blend_sigmoid(t[i] - transition_time, tau, 0.5 * window_length) + else: + alpha = blend_sigmoid(transition_time - t[i], tau, 0.5 * window_length) + alphas[i] = alpha + vel_time_varying_proj[i] = TV_J_space.T @ TV_J_space @ vel[i] + # import pdb; pdb.set_trace() + vel_correction = transform @ (J_r @ (vel[i] - np.zeros(nv))) + # vel_correction = transform @ (J_r @ (vel[i] - np.ones(nv))) + vel_corrected[i] = vel[i] - vel_correction + vel_corrected_blend[i] = vel[i] - alpha * vel_correction gen_vel_plot = plot_styler.PlotStyler() gen_vel_plot.plot(t, vel, title='Generalized Velocities near Impact', xlabel='time (s)', ylabel='velocity (m/s)') ylim = gen_vel_plot.fig.gca().get_ylim() + gen_vel_plot.save_fig('gen_vel_plot.png') # ps.save_fig('generalized_velocities_around_impact.png') + proj_vel_plot = plot_styler.PlotStyler() - # proj_vel_plot.plot(t, cc_vel, title='Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)') - proj_vel_plot.plot(t, cc_vel, title='Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - # tv_proj_vel_plot = plot_styler.PlotStyler() - # tv_proj_vel_plot.plot(t, TV_cc_vel, title='Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - # ps.save_fig('projected_velocities_around_impact.png') + proj_vel_plot.plot(t, vel_proj, title='Constant Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + proj_vel_plot.save_fig('proj_vel_plot.png') + + corrected_vel_plot = plot_styler.PlotStyler() + corrected_vel_plot.plot(t, vel_corrected, title='Impact-Invariant Correction', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + corrected_vel_plot.save_fig('corrected_vel_plot.png') + + blended_vel_plot = plot_styler.PlotStyler() + ax = blended_vel_plot.fig.axes[0] + blended_vel_plot.plot(t, vel[:,selected_joint_idxs], title='Blended Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + blended_vel_plot.plot(t, vel_corrected_blend[:,selected_joint_idxs], title='Blended Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + ax.fill_between(t_proj, ylim[0], ylim[1], color=blended_vel_plot.grey, alpha=0.2) + blended_vel_plot.save_fig('blended_vel_plot.png') + + blending_function_plot = plot_styler.PlotStyler() + ax = blending_function_plot.fig.axes[0] + blending_function_plot.plot(t, alphas, title="Blending Function") + ax.fill_between(t_proj, ax.get_ylim()[0], ax.get_ylim()[1], color=blending_function_plot.grey, alpha=0.2) + blending_function_plot.save_fig('blending_function_plot.png') + plt.show() if __name__ == '__main__': From 558f637f98da3aa5c2dea645c9fbba5c12c031dc Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 16 Jan 2023 14:33:20 -0500 Subject: [PATCH 339/758] reorganizing bindings, rerunning five link biped studies --- bindings/pydairlib/analysis/BUILD.bazel | 37 ++++- bindings/pydairlib/analysis/__init__.py | 2 + .../impact_invariant_control/BUILD.bazel | 3 + .../plot_five_link_biped.py | 139 +++++++++++++----- .../pydairlib/analysis/log_plotter_cassie.py | 6 +- .../pydairlib/analysis/mbp_plotting_utils.py | 6 +- .../analysis/osqp_settings_sandbox.py | 2 +- bindings/pydairlib/analysis/qp_test.py | 3 +- bindings/pydairlib/common/plot_styler.py | 2 +- bindings/pydairlib/lcm/BUILD.bazel | 8 + .../{analysis => lcm}/process_lcm_log.py | 1 + examples/Cassie/osc/osc_standing_gains.yaml | 1 + .../Cassie/osc/osc_standing_gains_sim.yaml | 1 + examples/Cassie/osc_run/osc_running_gains.h | 1 - .../Cassie/osc_run/osc_running_gains.yaml | 10 +- examples/Cassie/run_osc_running_controller.cc | 12 +- .../impact_invariant_examples.pmd | 53 ------- systems/controllers/osc/osc_gains.h | 3 + 18 files changed, 174 insertions(+), 116 deletions(-) create mode 100644 bindings/pydairlib/analysis/__init__.py rename bindings/pydairlib/{analysis => lcm}/process_lcm_log.py (98%) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index a070cc9479..3010f612aa 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -11,12 +11,6 @@ load( "pybind_py_library", ) -py_binary( - name = "process_lcm_log", - srcs = ["process_lcm_log.py"], - deps = ["@lcm//:lcm-python"], -) - py_binary( name = "qp_test", srcs = ["qp_test.py"], @@ -110,3 +104,34 @@ py_binary( "//lcmtypes:lcmtypes_robot_py", ], ) + + +# This determines how `PYTHONPATH` is configured, and how to install the +# bindings. +PACKAGE_INFO = get_pybind_package_info("//bindings") + +py_library( + name = "module_py", + srcs = [ + "__init__.py", + ], + imports = PACKAGE_INFO.py_imports, + deps = [ + "//bindings/pydairlib:module_py", + ], +) + +PY_LIBRARIES = [ + ":cassie_plotting_utils", + ":mbp_plotting_utils", + ":spring_compensation", + ":osc_debug_py", + ":cassie_plot_config", +] + +# Package roll-up (for Bazel dependencies). +py_library( + name = "analysis", + imports = PACKAGE_INFO.py_imports, + deps = PY_LIBRARIES, +) diff --git a/bindings/pydairlib/analysis/__init__.py b/bindings/pydairlib/analysis/__init__.py new file mode 100644 index 0000000000..c4361f107d --- /dev/null +++ b/bindings/pydairlib/analysis/__init__.py @@ -0,0 +1,2 @@ +# Importing everything in this directory to this package +from .analysis import * \ No newline at end of file diff --git a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel index 5839d87027..38e5c00161 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel +++ b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel @@ -20,6 +20,9 @@ py_binary( deps = [ "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", + "//bindings/pydairlib/lcm:process_lcm_log", + "//bindings/pydairlib/analysis:mbp_plotting_utils", + "//bindings/pydairlib/analysis:osc_debug_py", "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index d47de80471..165eb9722d 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -1,29 +1,70 @@ import sys import lcm +import matplotlib.pyplot as plt import numpy as np + from scipy.linalg import null_space -import pathlib -import matplotlib.pyplot as plt -import matplotlib -from pydairlib.lcm import lcm_trajectory -import pydairlib.multibody -from pydairlib.common import FindResourceOrThrow -from pydrake.trajectories import PiecewisePolynomial -from pydairlib.common import plot_styler, plotting_utils -from pydairlib.cassie.cassie_utils import * +import dairlib +from bindings.pydairlib.lcm import lcm_trajectory +from bindings.pydairlib.multibody import MakeNameToPositionsMap, \ + MakeNameToVelocitiesMap, MakeNameToActuatorsMap, \ + CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap +from bindings.pydairlib.common import FindResourceOrThrow +from bindings.pydairlib.common import plot_styler, plotting_utils +from bindings.pydairlib.cassie.cassie_utils import * +from bindings.pydairlib.lcm.process_lcm_log import get_log_data +import pydairlib.analysis.mbp_plotting_utils as mbp_plots + +from pydrake.trajectories import PiecewisePolynomial from pydrake.multibody.parsing import Parser from pydrake.multibody.plant import AddMultibodyPlantSceneGraph from pydrake.multibody.tree import JacobianWrtVariable from pydrake.systems.framework import DiagramBuilder + def blend_sigmoid(t, tau, window): x = (t + window) / tau return np.exp(x) / (1 + np.exp(x)) -def rabbit_main(): +def compute_control_law(N, d): + nu = d.shape[0] + nc = N.shape[1] + # A = np.array([[np.eye(nu), N], [N.T, np.zeros((nc, nc))]]) + A = np.zeros((nc + nu, nc + nu)) + b = np.zeros((nc + nu)) + A[:nu, :nu] = np.eye(nu) + A[-nc:, :nu] = N.T + A[:nu, -nc:] = N + A[-nc:, -nc:] = np.zeros((nc, nc)) + b[:nu] = d + b[-nc:] = N.T @ d + + A_inv = np.linalg.inv(A) + u = A_inv @ b + + +def load_logs(plant, t_impact, window): + log_dir = '/media/yangwill/backups/home/yangwill/Documents/research/projects/five_link_biped/invariant_impacts/logs/nominal/' + # filename = 'lcmlog-000' + filename = 'lcmlog-025-iros21' + print(log_dir + filename) + log = lcm.EventLog(log_dir + filename, "r") + default_channels = {'RABBIT_STATE': dairlib.lcmt_robot_output, + 'RABBIT_INPUT': dairlib.lcmt_robot_input, + 'OSC_DEBUG_WALKING': dairlib.lcmt_osc_output} + callback = mbp_plots.load_default_channels + start_time = 0 + duration = -1 + robot_output, robot_input, osc_debug = \ + get_log_data(log, default_channels, start_time, duration, callback, + plant, + 'RABBIT_STATE', 'RABBIT_INPUT', 'OSC_DEBUG_WALKING') + + +def main(): builder = DiagramBuilder() plant, _ = AddMultibodyPlantSceneGraph(builder, 0.0) Parser(plant).AddModelFromFile( @@ -31,15 +72,14 @@ def rabbit_main(): plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")) plant.Finalize() context = plant.CreateDefaultContext() - world = plant.world_frame() l_contact_frame = plant.GetBodyByName("left_foot").body_frame() r_contact_frame = plant.GetBodyByName("right_foot").body_frame() - pos_map = pydairlib.multibody.MakeNameToPositionsMap(plant) - vel_map = pydairlib.multibody.MakeNameToVelocitiesMap(plant) - act_map = pydairlib.multibody.MakeNameToActuatorsMap(plant) + pos_map = MakeNameToPositionsMap(plant) + vel_map = MakeNameToVelocitiesMap(plant) + act_map = MakeNameToActuatorsMap(plant) nq = plant.num_positions() nv = plant.num_velocities() @@ -50,8 +90,7 @@ def rabbit_main(): window_length = 0.05 tau = 0.005 # selected_joint_idxs = slice(6,7) - selected_joint_idxs = slice(0,7) - + selected_joint_idxs = slice(0, 7) # Map to 2d TXZ = np.array([[1, 0, 0], [0, 0, 1]]) @@ -59,24 +98,36 @@ def rabbit_main(): filename = "examples/impact_invariant_control/saved_trajectories/rabbit_walking" dircon_traj = lcm_trajectory.DirconTrajectory(plant, filename) state_traj = dircon_traj.ReconstructStateTrajectory() - breaks = dircon_traj.GetBreaks() transition_time = dircon_traj.GetStateBreaks(1)[0] x_pre = state_traj.value(transition_time - 1e-6) x_post = state_traj.value(transition_time) + load_logs(plant, transition_time, window_length) + plant.SetPositionsAndVelocities(context, x_pre) M = plant.CalcMassMatrixViaInverseDynamics(context) M_inv = np.linalg.inv(M) pt_on_body = np.zeros(3) - J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, r_contact_frame, pt_on_body, world, world) - J_l = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, l_contact_frame, pt_on_body, world, world) + J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, + JacobianWrtVariable.kV, + r_contact_frame, + pt_on_body, world, + world) + J_l = TXZ @ plant.CalcJacobianTranslationalVelocity(context, + JacobianWrtVariable.kV, + l_contact_frame, + pt_on_body, world, + world) M_Jt = M_inv @ J_r.T + # compute_control_law(M_Jt, np.ones(nv)) + P = null_space(M_Jt.T).T proj_ii = np.eye(nv) - M_Jt @ np.linalg.inv(M_Jt.T @ M_Jt) @ M_Jt.T J_M_Jt = J_r @ M_inv @ J_r.T - proj_y_ii = np.eye(2) - J_M_Jt @ J_M_Jt @ np.linalg.inv(J_M_Jt.T @ J_M_Jt) @ J_M_Jt.T + proj_y_ii = np.eye(2) - J_M_Jt @ J_M_Jt @ np.linalg.inv( + J_M_Jt.T @ J_M_Jt) @ J_M_Jt.T v_pre = x_pre[-nv:] v_post = x_post[-nv:] @@ -87,9 +138,10 @@ def rabbit_main(): # transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) transform = M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) - t = np.linspace(t_impact - 2*window_length, t_impact + 2*window_length, n_samples) - t_proj = np.array([t_impact[0] - window_length, t_impact[0] + window_length]) - + t = np.linspace(t_impact - 2 * window_length, t_impact + 2 * window_length, + n_samples) + t_proj = np.array( + [t_impact[0] - window_length, t_impact[0] + window_length]) vel_proj = np.zeros((t.shape[0], nv)) vel_time_varying_proj = np.zeros((t.shape[0], nv)) @@ -105,14 +157,20 @@ def rabbit_main(): plant.SetPositions(context, x[:nq]) M = plant.CalcMassMatrixViaInverseDynamics(context) M_inv = np.linalg.inv(M) - J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, JacobianWrtVariable.kV, r_contact_frame, pt_on_body, world, world) + J_r = TXZ @ plant.CalcJacobianTranslationalVelocity(context, + JacobianWrtVariable.kV, + r_contact_frame, + pt_on_body, world, + world) TV_J = M_inv @ J_r.T TV_J_space = null_space(TV_J.T).T if (t[i] < transition_time): - alpha = blend_sigmoid(t[i] - transition_time, tau, 0.5 * window_length) + alpha = blend_sigmoid(t[i] - transition_time, tau, + 0.5 * window_length) else: - alpha = blend_sigmoid(transition_time - t[i], tau, 0.5 * window_length) + alpha = blend_sigmoid(transition_time - t[i], tau, + 0.5 * window_length) alphas[i] = alpha vel_time_varying_proj[i] = TV_J_space.T @ TV_J_space @ vel[i] # import pdb; pdb.set_trace() @@ -122,33 +180,46 @@ def rabbit_main(): vel_corrected_blend[i] = vel[i] - alpha * vel_correction gen_vel_plot = plot_styler.PlotStyler() - gen_vel_plot.plot(t, vel, title='Generalized Velocities near Impact', xlabel='time (s)', ylabel='velocity (m/s)') + gen_vel_plot.plot(t, vel, title='Generalized Velocities near Impact', + xlabel='time (s)', ylabel='velocity (m/s)') ylim = gen_vel_plot.fig.gca().get_ylim() gen_vel_plot.save_fig('gen_vel_plot.png') # ps.save_fig('generalized_velocities_around_impact.png') proj_vel_plot = plot_styler.PlotStyler() - proj_vel_plot.plot(t, vel_proj, title='Constant Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + proj_vel_plot.plot(t, vel_proj, + title='Constant Impact-Invariant Projection', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) proj_vel_plot.save_fig('proj_vel_plot.png') corrected_vel_plot = plot_styler.PlotStyler() - corrected_vel_plot.plot(t, vel_corrected, title='Impact-Invariant Correction', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + corrected_vel_plot.plot(t, vel_corrected, + title='Impact-Invariant Correction', + xlabel='time (s)', ylabel='velocity (m/s)', + ylim=ylim) corrected_vel_plot.save_fig('corrected_vel_plot.png') blended_vel_plot = plot_styler.PlotStyler() ax = blended_vel_plot.fig.axes[0] - blended_vel_plot.plot(t, vel[:,selected_joint_idxs], title='Blended Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - blended_vel_plot.plot(t, vel_corrected_blend[:,selected_joint_idxs], title='Blended Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - ax.fill_between(t_proj, ylim[0], ylim[1], color=blended_vel_plot.grey, alpha=0.2) + blended_vel_plot.plot(t, vel[:, selected_joint_idxs], + title='Blended Impact-Invariant Correction', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + blended_vel_plot.plot(t, vel_corrected_blend[:, selected_joint_idxs], + title='Blended Impact-Invariant Projection', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + ax.fill_between(t_proj, ylim[0], ylim[1], color=blended_vel_plot.grey, + alpha=0.2) blended_vel_plot.save_fig('blended_vel_plot.png') blending_function_plot = plot_styler.PlotStyler() ax = blending_function_plot.fig.axes[0] blending_function_plot.plot(t, alphas, title="Blending Function") - ax.fill_between(t_proj, ax.get_ylim()[0], ax.get_ylim()[1], color=blending_function_plot.grey, alpha=0.2) + ax.fill_between(t_proj, ax.get_ylim()[0], ax.get_ylim()[1], + color=blending_function_plot.grey, alpha=0.2) blending_function_plot.save_fig('blending_function_plot.png') plt.show() + if __name__ == '__main__': - rabbit_main() \ No newline at end of file + main() diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 04a96bed73..9dd205de93 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -1,15 +1,13 @@ import sys import lcm import matplotlib.pyplot as plt -import code import numpy as np -import dairlib -from process_lcm_log import get_log_data +from bindings.pydairlib.lcm.process_lcm_log import get_log_data from cassie_plot_config import CassiePlotConfig import cassie_plotting_utils as cassie_plots import mbp_plotting_utils as mbp_plots -from spring_compensation import SpringCompensation + def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 986bf273c3..9f69f3cf51 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -2,9 +2,9 @@ import matplotlib.pyplot as plt from matplotlib.patches import Patch -from pydairlib.common import plot_styler, plotting_utils -from osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost, osc_regularlization_tracking_cost -from pydairlib.multibody import MakeNameToPositionsMap, \ +from bindings.pydairlib.common import plot_styler, plotting_utils +from bindings.pydairlib.analysis.osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost, osc_regularlization_tracking_cost +from bindings.pydairlib.multibody import MakeNameToPositionsMap, \ MakeNameToVelocitiesMap, MakeNameToActuatorsMap, \ CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index 4f6d0b751a..a22860747b 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -1,6 +1,6 @@ import lcm import numpy as np -from process_lcm_log import get_log_data +from bindings.pydairlib.lcm.process_lcm_log import get_log_data from dairlib import lcmt_qp import sys import matplotlib.pyplot as plt diff --git a/bindings/pydairlib/analysis/qp_test.py b/bindings/pydairlib/analysis/qp_test.py index bc6225fb44..0741a550af 100644 --- a/bindings/pydairlib/analysis/qp_test.py +++ b/bindings/pydairlib/analysis/qp_test.py @@ -1,9 +1,8 @@ import lcm import numpy as np -from process_lcm_log import get_log_data +from bindings.pydairlib.lcm.process_lcm_log import get_log_data from dairlib import lcmt_qp # import qpoases -import time import sys # import qpsolvers diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 20d2ca27a7..affefc2a4f 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -20,8 +20,8 @@ def __init__(self, figure=None): # self.directory = None self.dpi = 200 self.directory = '/home/yangwill/Pictures/plot_styler/' + # matplotlib.rcParams['figure.figsize'] = 8, 4 self.fig = plt.figure(dpi=self.dpi) if figure is None else figure - matplotlib.rcParams['figure.figsize'] = 8, 4 self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] self.fig_id = self.fig.number diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index 89629a01a8..b1fd003b9f 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -31,6 +31,13 @@ pybind_py_library( py_imports = ["."], ) +py_library( + name = "process_lcm_log", + srcs = ["process_lcm_log.py"], + data = ["@lcm//:lcm-python"], + deps = [ + ], +) pybind_py_library( name = "lcm_trajectory_py", @@ -63,6 +70,7 @@ py_library( PY_LIBRARIES = [ ":lcm_trajectory_py", ":lcm_py", + ":process_lcm_log", ] # Package roll-up (for Bazel dependencies). diff --git a/bindings/pydairlib/analysis/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py similarity index 98% rename from bindings/pydairlib/analysis/process_lcm_log.py rename to bindings/pydairlib/lcm/process_lcm_log.py index 75c1a6ea83..a07235e65f 100644 --- a/bindings/pydairlib/analysis/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -40,6 +40,7 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca if 0 < duration <= (event.timestamp - t) * 1e-6: break event = lcm_log.read_next_event() + import pdb; pdb.set_trace() return data_processing_callback(data_to_process, *args, *kwargs) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index ce723b453a..957d497ea2 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -5,6 +5,7 @@ # -Kp * x - Kd * xdot = # -Kp * x + Kd * sqrt(g/l) * x = g/l * x # Kp = sqrt(g/l) * Kd - g/l +controller_frequency: 1000 rows: 3 cols: 3 diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index d6f17ec0a6..bf8564197e 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -5,6 +5,7 @@ # -Kp * x - Kd * xdot = # -Kp * x + Kd * sqrt(g/l) * x = g/l * x # Kp = sqrt(g/l) * Kd - g/l +controller_frequency: 1000 rows: 3 cols: 3 diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index e87cb8cdba..23ad4054aa 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -8,7 +8,6 @@ using Eigen::MatrixXd; struct OSCRunningGains : OSCGains { - double controller_frequency; double weight_scaling; double w_swing_toe; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4afb3dafdd..c47d62c852 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -33,17 +33,17 @@ ekf_filter_tau: [ 0.05, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -4 -vel_scale_trans_sagital: 6 +vel_scale_trans_sagital: 15 vel_scale_trans_lateral: -0.5 target_vel_filter_alpha: 0.01 # SLIP parameters rest_length: 0.85 rest_length_offset: 0.025 -stance_duration: 0.31 +stance_duration: 0.3 flight_duration: 0.09 # max percent variance -stance_variance: 0.1 +stance_variance: 0.2 flight_variance: 0.1 w_swing_toe: 0.01 @@ -57,7 +57,7 @@ hip_yaw_kd: 5 #footstep_offset: -0.05 footstep_sagital_offset: -0.00 footstep_lateral_offset: 0.04 # drake -mid_foot_height: 0.3 +mid_foot_height: 0.4 FootstepKd: [ 0.01, 0, 0, 0, 0.3, 0, @@ -69,7 +69,7 @@ PelvisW: PelvisKp: [ 0, 0, 0, 0, 40, 0, - 0, 0, 125] + 0, 0, 115] PelvisKd: [ 0, 0, 0, 0, 10, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index e94477c207..4e2e05135e 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -430,13 +430,13 @@ int DoMain(int argc, char* argv[]) { std::make_shared>( PiecewisePolynomial::FirstOrderHold( {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, - {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)})); + {0.5 * VectorXd::Ones(1), 4.0 * VectorXd::Ones(1)})); auto foot_traj_gain_trajectory = std::make_shared>( PiecewisePolynomial::FirstOrderHold( {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, {0.5 * MatrixXd::Identity(3, 3), - 2.0 * MatrixXd::Identity(3, 3)})); + 1.5 * MatrixXd::Identity(3, 3)})); left_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); right_foot_rel_tracking_data->SetTimeVaryingWeights( @@ -540,10 +540,10 @@ int DoMain(int argc, char* argv[]) { VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); - auto controller_frequency_regulator = - builder.AddSystem>( - osc_gains.controller_frequency, - osc->get_output_port_osc_command().size()); +// auto controller_frequency_regulator = +// builder.AddSystem>( +// 1 / gains.controller_frequency, +// osc->get_output_port_osc_command().size()); osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem diff --git a/examples/impact_invariant_control/impact_invariant_examples.pmd b/examples/impact_invariant_control/impact_invariant_examples.pmd index 4253c24c12..661fd1da53 100644 --- a/examples/impact_invariant_control/impact_invariant_examples.pmd +++ b/examples/impact_invariant_control/impact_invariant_examples.pmd @@ -69,56 +69,3 @@ group "2.controllers" { } } - -script "osc-jumping (drake)" { - stop cmd "osc_jumping_controller"; - stop cmd "mbp_sim" wait "stopped"; - start cmd "osc_jumping_controller" wait "running"; - start cmd "mbp_sim"; -} - -script "osc-jumping (mujoco)" { - stop cmd "osc_jumping_controller (mujoco)"; - stop cmd "dispatcher-robot-in"; - stop cmd "cassie-mujoco" wait "stopped"; - start cmd "osc_jumping_controller (mujoco)" wait "running"; - start cmd "dispatcher-robot-in"; - start cmd "cassie-mujoco"; -} - -script "osc_standing (mujoco)" { - start cmd "cassie-mujoco"; - start cmd "dispatcher-robot-in"; - start cmd "osc_standing_controller"; -} - -script "run-mujoco-lcm-pd-control" { - run_script "start-operator-MBP"; - start cmd "3.cassie-mujoco-fixed-base"; - start cmd "2.a.dispatcher-robot-out (lcm)"; - start cmd "3.dispatcher-robot-in"; - start cmd "0.pd-controller"; -} - -script "run-real-robot-pd-control" { - run_script "start-operator-real-robot"; - start cmd "0.dispatcher-robot-out-real-robot"; - start cmd "1.dispatcher-robot-in-real-robot"; - start cmd "2.pd-controller-real-robot"; -} - -script "run_gazebo" { - start cmd "2.b.dispatcher-robot-out (gazebo)"; - wait ms 500; - start cmd "0.launch-gazebo"; -} - -script "switch-to-standing" { - start cmd "osc_standing_controller"; - stop cmd "osc_walking_controller"; -} - -script "switch-to-walking" { - start cmd "osc_walking_controller"; - stop cmd "osc_standing_controller"; -} diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index efb837526c..ca76bae336 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -7,6 +7,8 @@ using Eigen::MatrixXd; struct OSCGains { + double controller_frequency; + // costs double w_input; double w_accel; @@ -28,6 +30,7 @@ struct OSCGains { template void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(controller_frequency)); a->Visit(DRAKE_NVP(w_input)); a->Visit(DRAKE_NVP(w_accel)); a->Visit(DRAKE_NVP(w_lambda)); From 9b26c670fce2fb25764ad72a0001256e0f334817 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 16 Jan 2023 16:04:28 -0500 Subject: [PATCH 340/758] updating plotting scripts --- .../plot_five_link_biped.py | 80 +++++++++++++++---- bindings/pydairlib/lcm/process_lcm_log.py | 1 - 2 files changed, 63 insertions(+), 18 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 165eb9722d..226bfa5d9c 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -47,9 +47,11 @@ def compute_control_law(N, d): def load_logs(plant, t_impact, window): - log_dir = '/media/yangwill/backups/home/yangwill/Documents/research/projects/five_link_biped/invariant_impacts/logs/nominal/' + # log_dir = '/media/yangwill/backups/home/yangwill/Documents/research/projects/five_link_biped/invariant_impacts/logs/nominal/' + log_dir = '/home/yangwill/Documents/research/papers/impact_invariant_control/data/five_link_biped/' # filename = 'lcmlog-000' - filename = 'lcmlog-025-iros21' + # filename = 'lcmlog-nominal' + filename = 'lcmlog-error' print(log_dir + filename) log = lcm.EventLog(log_dir + filename, "r") default_channels = {'RABBIT_STATE': dairlib.lcmt_robot_output, @@ -62,6 +64,7 @@ def load_logs(plant, t_impact, window): get_log_data(log, default_channels, start_time, duration, callback, plant, 'RABBIT_STATE', 'RABBIT_INPUT', 'OSC_DEBUG_WALKING') + return robot_output, robot_input, osc_debug def main(): @@ -88,7 +91,7 @@ def main(): nc = 2 n_samples = 1000 window_length = 0.05 - tau = 0.005 + tau = 0.0025 # selected_joint_idxs = slice(6,7) selected_joint_idxs = slice(0, 7) @@ -103,7 +106,7 @@ def main(): x_pre = state_traj.value(transition_time - 1e-6) x_post = state_traj.value(transition_time) - load_logs(plant, transition_time, window_length) + robot_output, robot_input, osc_debug = load_logs(plant, transition_time, window_length) plant.SetPositionsAndVelocities(context, x_pre) M = plant.CalcMassMatrixViaInverseDynamics(context) @@ -120,6 +123,7 @@ def main(): pt_on_body, world, world) M_Jt = M_inv @ J_r.T + # compute_control_law(M_Jt, np.ones(nv)) P = null_space(M_Jt.T).T @@ -133,26 +137,45 @@ def main(): v_post = x_post[-nv:] t_impact = dircon_traj.GetStateBreaks(0)[-1] + J_y = np.zeros((4, 7)) + J_y[0, 3] = 1 + J_y[1, 4] = 1 + J_y[2, 5] = 1 + J_y[3, 6] = 1 ydot_pre = J_r @ v_pre ydot_post = J_r @ v_post # transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) - transform = M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) + transform = M_inv @ J_r.T @ np.linalg.pinv(J_y @ M_inv @ J_r.T) + - t = np.linspace(t_impact - 2 * window_length, t_impact + 2 * window_length, - n_samples) + start_time = t_impact - 2 * window_length + end_time = t_impact + 2 * window_length + start_idx = np.argwhere(np.abs(robot_output['t_x'] - start_time) < 1e-3)[0][0] + end_idx = np.argwhere(np.abs(robot_output['t_x'] - end_time) < 1e-3)[0][0] + t = np.linspace(start_time, end_time, + end_idx - start_idx) + print(start_idx) + print(end_idx) t_proj = np.array( [t_impact[0] - window_length, t_impact[0] + window_length]) vel_proj = np.zeros((t.shape[0], nv)) + vel_proj_actual = np.zeros((t.shape[0], nv)) vel_time_varying_proj = np.zeros((t.shape[0], nv)) vel = np.zeros((t.shape[0], nv)) + vel_actual = np.zeros((t.shape[0], nv)) vel_corrected = np.zeros((t.shape[0], nv)) + vel_correction = np.zeros((t.shape[0], nv)) vel_corrected_blend = np.zeros((t.shape[0], nv)) alphas = np.zeros((t.shape[0], 1)) for i in range(t.shape[0]): - x = state_traj.value(t[i]) + # for i in range(0, end_idx - start_idx): + # x = state_traj.value(t[i]) + x = state_traj.value(robot_output['t_x'][i + start_idx]) vel[i] = x[-nv:, 0] + vel_actual[i] = robot_output['v'][i + start_idx] vel_proj[i] = P.T @ P @ vel[i] + vel_proj_actual[i] = P.T @ P @ vel_actual[i] plant.SetPositions(context, x[:nq]) M = plant.CalcMassMatrixViaInverseDynamics(context) @@ -173,15 +196,17 @@ def main(): 0.5 * window_length) alphas[i] = alpha vel_time_varying_proj[i] = TV_J_space.T @ TV_J_space @ vel[i] - # import pdb; pdb.set_trace() - vel_correction = transform @ (J_r @ (vel[i] - np.zeros(nv))) - # vel_correction = transform @ (J_r @ (vel[i] - np.ones(nv))) - vel_corrected[i] = vel[i] - vel_correction - vel_corrected_blend[i] = vel[i] - alpha * vel_correction + # vel_correction[i] = transform @ (J_r @ (vel[i] - vel_actual[i])) + vel_correction[i] = transform @ (J_y @ vel[i] - J_y @ vel_actual[i]) + vel_corrected[i] = vel_actual[i] + vel_correction[i] + vel_corrected_blend[i] = vel_actual[i] + alpha * vel_correction[i] + # t_plot = robot_output['t_x'][start_idx:end_idx] gen_vel_plot = plot_styler.PlotStyler() gen_vel_plot.plot(t, vel, title='Generalized Velocities near Impact', xlabel='time (s)', ylabel='velocity (m/s)') + gen_vel_plot.plot(t, vel_actual, title='Generalized Velocities near Impact', + xlabel='time (s)', ylabel='velocity (m/s)') ylim = gen_vel_plot.fig.gca().get_ylim() gen_vel_plot.save_fig('gen_vel_plot.png') # ps.save_fig('generalized_velocities_around_impact.png') @@ -190,6 +215,9 @@ def main(): proj_vel_plot.plot(t, vel_proj, title='Constant Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + proj_vel_plot.plot(t, vel_proj_actual, + title='Constant Impact-Invariant Projection', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) proj_vel_plot.save_fig('proj_vel_plot.png') corrected_vel_plot = plot_styler.PlotStyler() @@ -201,16 +229,34 @@ def main(): blended_vel_plot = plot_styler.PlotStyler() ax = blended_vel_plot.fig.axes[0] - blended_vel_plot.plot(t, vel[:, selected_joint_idxs], - title='Blended Impact-Invariant Correction', - xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + # blended_vel_plot.plot(t, vel_actual[:, selected_joint_idxs], + # title='Blended Impact-Invariant Correction', + # xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) blended_vel_plot.plot(t, vel_corrected_blend[:, selected_joint_idxs], - title='Blended Impact-Invariant Projection', + title='Blended Impact-Invariant Correction', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=blended_vel_plot.grey, alpha=0.2) blended_vel_plot.save_fig('blended_vel_plot.png') + projected_vel_error = plot_styler.PlotStyler() + ax = projected_vel_error.fig.axes[0] + projected_vel_error.plot(t, vel_proj - vel_proj_actual[:, selected_joint_idxs], + title='Impact-Invariant Projection Error', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + ax.fill_between(t_proj, ylim[0], ylim[1], color=projected_vel_error.grey, + alpha=0.2) + projected_vel_error.save_fig('projected_vel_error.png') + + corrected_vel_error = plot_styler.PlotStyler() + ax = corrected_vel_error.fig.axes[0] + corrected_vel_error.plot(t, vel - vel_corrected[:, selected_joint_idxs], + title='Impact-Invariant Correction Error', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + ax.fill_between(t_proj, ylim[0], ylim[1], color=corrected_vel_error.grey, + alpha=0.2) + corrected_vel_error.save_fig('corrected_vel_error.png') + blending_function_plot = plot_styler.PlotStyler() ax = blending_function_plot.fig.axes[0] blending_function_plot.plot(t, alphas, title="Blending Function") diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index a07235e65f..75c1a6ea83 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -40,7 +40,6 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca if 0 < duration <= (event.timestamp - t) * 1e-6: break event = lcm_log.read_next_event() - import pdb; pdb.set_trace() return data_processing_callback(data_to_process, *args, *kwargs) From d0b520db1b1624dc2d5f38f48de29d059b14d9f9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 17 Jan 2023 14:14:40 -0500 Subject: [PATCH 341/758] changes for plots --- bindings/pydairlib/analysis/BUILD.bazel | 1 + .../impact_invariant_control/plot_five_link_biped.py | 9 +++++++++ bindings/pydairlib/analysis/log_plotter_cassie.py | 2 +- .../analysis/plot_configs/cassie_running_plot.yaml | 6 +++--- bindings/pydairlib/common/plot_styler.py | 2 +- examples/Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/impact_invariant_control/five_link_biped_sim.cc | 5 ++++- .../impact_invariant_examples.pmd | 3 ++- 8 files changed, 22 insertions(+), 8 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 3010f612aa..6aecc3e44b 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -94,6 +94,7 @@ py_binary( ], deps = [ ":cassie_plot_config", + "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", "//bindings/pydairlib/common:plot_styler", diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 226bfa5d9c..bbda417d17 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -239,6 +239,15 @@ def main(): alpha=0.2) blended_vel_plot.save_fig('blended_vel_plot.png') + gen_vel_error = plot_styler.PlotStyler() + ax = gen_vel_error.fig.axes[0] + gen_vel_error.plot(t, vel - vel_actual[:, selected_joint_idxs], + title='Generalized Velocity Error', + xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) + ax.fill_between(t_proj, ylim[0], ylim[1], color=gen_vel_error.grey, + alpha=0.2) + gen_vel_error.save_fig('gen_vel_error.png') + projected_vel_error = plot_styler.PlotStyler() ax = projected_vel_error.fig.axes[0] projected_vel_error.plot(t, vel_proj - vel_proj_actual[:, selected_joint_idxs], diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 9dd205de93..bab3ddeb87 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -6,7 +6,7 @@ from bindings.pydairlib.lcm.process_lcm_log import get_log_data from cassie_plot_config import CassiePlotConfig import cassie_plotting_utils as cassie_plots -import mbp_plotting_utils as mbp_plots +import pydairlib.analysis.mbp_plotting_utils as mbp_plots def main(): diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 9eb4efc655..90996a916b 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,7 +6,7 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 7 +start_time: 1 duration: 3 # Plant properties @@ -45,12 +45,12 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos','vel', 'accel' ] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # right_ft_traj: { 'dims': [0, 1, 2], 'derivs': [ 'pos' ] }, - left_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'pos' , 'vel'] }, + left_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index affefc2a4f..789f2254a7 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -20,7 +20,7 @@ def __init__(self, figure=None): # self.directory = None self.dpi = 200 self.directory = '/home/yangwill/Pictures/plot_styler/' - # matplotlib.rcParams['figure.figsize'] = 8, 4 + matplotlib.rcParams['figure.figsize'] = 8, 12 self.fig = plt.figure(dpi=self.dpi) if figure is None else figure self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] self.fig_id = self.fig.number diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c47d62c852..bc66760793 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -57,7 +57,7 @@ hip_yaw_kd: 5 #footstep_offset: -0.05 footstep_sagital_offset: -0.00 footstep_lateral_offset: 0.04 # drake -mid_foot_height: 0.4 +mid_foot_height: 0.2 FootstepKd: [ 0.01, 0, 0, 0, 0.3, 0, diff --git a/examples/impact_invariant_control/five_link_biped_sim.cc b/examples/impact_invariant_control/five_link_biped_sim.cc index e0ad093cd3..c9525e709e 100644 --- a/examples/impact_invariant_control/five_link_biped_sim.cc +++ b/examples/impact_invariant_control/five_link_biped_sim.cc @@ -101,6 +101,7 @@ int do_main(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_channel_u, lcm)); auto input_receiver = builder.AddSystem(plant); + // connect input receiver auto passthrough = builder.AddSystem( input_receiver->get_output_port(0).size(), 0, @@ -116,7 +117,7 @@ int do_main(int argc, char* argv[]) { LcmPublisherSystem::Make( "CONTACT_RESULTS", lcm, 1.0 / FLAGS_publish_rate)); contact_results_publisher.set_name("contact_results_publisher"); - auto state_sender = builder.AddSystem(plant); + auto state_sender = builder.AddSystem(plant, true); // Contact results to lcm msg. builder.Connect(*input_sub, *input_receiver); @@ -129,6 +130,8 @@ int do_main(int argc, char* argv[]) { contact_results_publisher.get_input_port()); builder.Connect(plant.get_state_output_port(), state_sender->get_input_port_state()); + builder.Connect(passthrough->get_output_port(), + state_sender->get_input_port_effort()); builder.Connect(state_sender->get_output_port(0), state_pub->get_input_port()); builder.Connect( diff --git a/examples/impact_invariant_control/impact_invariant_examples.pmd b/examples/impact_invariant_control/impact_invariant_examples.pmd index 661fd1da53..f35fc12e7c 100644 --- a/examples/impact_invariant_control/impact_invariant_examples.pmd +++ b/examples/impact_invariant_control/impact_invariant_examples.pmd @@ -46,7 +46,7 @@ group "1.simulated-robot" { host = "localhost"; } cmd "five_link_biped_sim" { - exec = "bazel-bin/examples/impact_invariant_control/five_link_biped_sim --folder_path=\"examples/impact_invariant_control/saved_trajectories/\" --trajectory_name=\"rabbit_walking\" --sim_time=1.0 --target_realtime_rate=0.25"; + exec = "bazel-bin/examples/impact_invariant_control/five_link_biped_sim --folder_path=\"examples/impact_invariant_control/saved_trajectories/\" --trajectory_name=\"rabbit_walking\" --sim_time=1.0 --target_realtime_rate=0.25 --error=0.1"; host = "localhost"; } } @@ -69,3 +69,4 @@ group "2.controllers" { } } + From a3c31e00935bd45c0892cb5c02058ebafb12a970 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 20 Jan 2023 13:32:32 -0500 Subject: [PATCH 342/758] updating plotting --- .../plot_five_link_biped.py | 48 ++++++++++++------- bindings/pydairlib/common/plot_styler.py | 2 +- 2 files changed, 33 insertions(+), 17 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index bbda417d17..dced17a5e4 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -92,8 +92,8 @@ def main(): n_samples = 1000 window_length = 0.05 tau = 0.0025 - # selected_joint_idxs = slice(6,7) - selected_joint_idxs = slice(0, 7) + selected_joint_idxs = slice(6,7) + # selected_joint_idxs = slice(0, 7) # Map to 2d TXZ = np.array([[1, 0, 0], [0, 0, 1]]) @@ -137,11 +137,15 @@ def main(): v_post = x_post[-nv:] t_impact = dircon_traj.GetStateBreaks(0)[-1] - J_y = np.zeros((4, 7)) - J_y[0, 3] = 1 - J_y[1, 4] = 1 - J_y[2, 5] = 1 - J_y[3, 6] = 1 + # J_y = np.zeros((4, 7)) + J_y = np.eye((7)) + # J_y[0, 0] = 1 + # J_y[0, 1] = 1 + # J_y[0, 2] = 1 + # J_y[0, 3] = 1 + # J_y[1, 4] = 1 + # J_y[2, 5] = 1 + # J_y[3, 6] = 1 ydot_pre = J_r @ v_pre ydot_post = J_r @ v_post # transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) @@ -203,10 +207,13 @@ def main(): # t_plot = robot_output['t_x'][start_idx:end_idx] gen_vel_plot = plot_styler.PlotStyler() - gen_vel_plot.plot(t, vel, title='Generalized Velocities near Impact', + gen_vel_plot.plot(t, vel[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)') - gen_vel_plot.plot(t, vel_actual, title='Generalized Velocities near Impact', + gen_vel_plot.plot(t, vel_actual[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)') + gen_vel_plot.plot(t, vel[:, selected_joint_idxs] - vel_actual[:, selected_joint_idxs], + xlabel='time (s)', ylabel='velocity (m/s)', grid=False) + gen_vel_plot.add_legend(['Desired Velocity', 'Measured Velocity', 'Velocity Error']) ylim = gen_vel_plot.fig.gca().get_ylim() gen_vel_plot.save_fig('gen_vel_plot.png') # ps.save_fig('generalized_velocities_around_impact.png') @@ -239,18 +246,27 @@ def main(): alpha=0.2) blended_vel_plot.save_fig('blended_vel_plot.png') + + gen_vel_error = plot_styler.PlotStyler() ax = gen_vel_error.fig.axes[0] - gen_vel_error.plot(t, vel - vel_actual[:, selected_joint_idxs], - title='Generalized Velocity Error', - xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - ax.fill_between(t_proj, ylim[0], ylim[1], color=gen_vel_error.grey, - alpha=0.2) + gen_vel_error.plot(t, vel[:, selected_joint_idxs], + xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.blue) + gen_vel_error.plot(t, vel_actual[:, selected_joint_idxs], + xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.red) + gen_vel_error.plot(t, vel[:, selected_joint_idxs] - vel_actual[:, selected_joint_idxs], + xlabel='Time', ylabel='Velocity', grid=False, color=gen_vel_error.grey) + gen_vel_error.add_legend(['Desired Velocity', 'Measured Velocity', 'Velocity Error']) + ax.set_yticklabels([]) + ax.set_xticklabels([]) + # ax.spines['bottom'].set_visible(False) + # ax.spines['left'].set_visible(False) + ylim = gen_vel_error.fig.gca().get_ylim() gen_vel_error.save_fig('gen_vel_error.png') projected_vel_error = plot_styler.PlotStyler() ax = projected_vel_error.fig.axes[0] - projected_vel_error.plot(t, vel_proj - vel_proj_actual[:, selected_joint_idxs], + projected_vel_error.plot(t, vel_proj[:, selected_joint_idxs] - vel_proj_actual[:, selected_joint_idxs], title='Impact-Invariant Projection Error', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=projected_vel_error.grey, @@ -259,7 +275,7 @@ def main(): corrected_vel_error = plot_styler.PlotStyler() ax = corrected_vel_error.fig.axes[0] - corrected_vel_error.plot(t, vel - vel_corrected[:, selected_joint_idxs], + corrected_vel_error.plot(t, vel[:, selected_joint_idxs] - vel_corrected[:, selected_joint_idxs], title='Impact-Invariant Correction Error', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=corrected_vel_error.grey, diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 789f2254a7..bddf4151b5 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -20,7 +20,7 @@ def __init__(self, figure=None): # self.directory = None self.dpi = 200 self.directory = '/home/yangwill/Pictures/plot_styler/' - matplotlib.rcParams['figure.figsize'] = 8, 12 + matplotlib.rcParams['figure.figsize'] = 6, 4 self.fig = plt.figure(dpi=self.dpi) if figure is None else figure self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] self.fig_id = self.fig.number From 57567ed38528f1d49c9bd4a0bf744f2f3bf1b3a1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 24 Jan 2023 15:06:25 -0500 Subject: [PATCH 343/758] small changes, some formatting --- .../analysis/plot_configs/cassie_running_plot.yaml | 6 +++--- bindings/pydairlib/lcm/process_lcm_log.py | 14 ++------------ .../visualization/visualize_configs/box_jump.yaml | 8 ++++++++ .../visualization/visualize_configs/long_jump.yaml | 2 +- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 1 + examples/Cassie/osc_run/osc_running_gains.yaml | 6 +++--- .../controllers/osc/operational_space_control.cc | 7 +++---- 7 files changed, 21 insertions(+), 23 deletions(-) create mode 100644 bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 90996a916b..1f5a6bc746 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 1 -duration: 3 +start_time: 2.2 +duration: 2 # Plant properties use_springs: true @@ -45,7 +45,7 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel', 'accel'] }, # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index 75c1a6ea83..1923462e2b 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -18,6 +18,8 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca data_to_process = {} print('Processing LCM log (this may take a while)...') lcm_log.seek(0) + while lcm_log.read_next_event().channel not in lcm_channels: + pass first_timestamp = lcm_log.read_next_event().timestamp start_timestamp = int(first_timestamp + start_time * 1e6) print('Start time: ' + str(start_time)) @@ -65,15 +67,3 @@ def print_log_summary(filename, log): def passthrough_callback(data, *args, **kwargs): return data - -# def main(): -# import lcm -# import sys -# -# logfile = sys.argv[1] -# log = lcm.EventLog(logfile, "r") -# print_log_summary(logfile, log) -# -# -# if __name__ == "__main__": -# main() diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml new file mode 100644 index 0000000000..219542970e --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml @@ -0,0 +1,8 @@ +filename: examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1 +spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf +visualize_mode: 1 +realtime_rate: 0.5 +num_poses: 10 +use_transparency: 1 +use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index b2a4063d6d..61b9260814 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -2,7 +2,7 @@ filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.4d_3 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 -realtime_rate: 0.2 +realtime_rate: 0.5 num_poses: 10 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 0f0fa6d586..a96094965b 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,3 +1,4 @@ +controller_frequency: 1000 w_input: 0.000001 w_lambda: 0.1 w_accel: 0.0001 diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index bc66760793..ef6ea1bc3a 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -73,7 +73,7 @@ PelvisKp: PelvisKd: [ 0, 0, 0, 0, 10, 0, - 0, 0, 5 ] + 0, 0, 5] PelvisRotW: [10, 0, 0, 0, 5, 0, @@ -104,8 +104,8 @@ LiftoffSwingFootW: 0, 0, 0] LiftoffSwingFootKp: [0, 0, 0, - 0, 0, 0, - 0, 0, 0] + 0, 0, 0, + 0, 0, 0] LiftoffSwingFootKd: [ 0, 0, 0, 0, 0, 0, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 5582740f51..c216989aa6 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -618,7 +618,7 @@ VectorXd OperationalSpaceControl::SolveQp( // 2. Holonomic constraint /// JdotV_h + J_h*dv == 0 /// -> J_h*dv == -JdotV_h - if (n_h_ > 0){ + if (n_h_ > 0) { holonomic_constraint_->UpdateCoefficients(J_h, -JdotV_h); } // 3. Contact constraint @@ -888,7 +888,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( A.transpose() * A; VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); VectorXd Ab = A.transpose() * ydot_err_vec; - if (n_h_ > 0){ + if (n_h_ > 0) { MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); MatrixXd C = J_h * M_Jt_; VectorXd d = J_h * x_w_spr.tail(n_v_); @@ -897,8 +897,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = C.transpose(); b_constrained << Ab, d; - } - else{ + } else { b_constrained << Ab; } From 6e6246033cc6f29e921c7c47e10639e09554b468 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 25 Jan 2023 16:10:51 -0500 Subject: [PATCH 344/758] fixing visualization bug --- lcm/dircon_saved_trajectory.cc | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index c6b51c6a2f..37d8eefa5f 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -299,6 +299,7 @@ PiecewisePolynomial DirconTrajectory::ReconstructStateTrajectoryWithSprings( Eigen::MatrixXd& spr_to_wo_spr_map) const { PiecewisePolynomial state_traj; + DRAKE_DEMAND(spr_to_wo_spr_map.cols() == x_[0]->datapoints.rows()); for (int mode = 0; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -306,8 +307,8 @@ DirconTrajectory::ReconstructStateTrajectoryWithSprings( continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, spr_to_wo_spr_map * x_[mode]->datapoints, - spr_to_wo_spr_map * xdot_[mode]->datapoints)); + x_[mode]->time_vector, spr_to_wo_spr_map * state_map_ * x_[mode]->datapoints, + spr_to_wo_spr_map * state_map_ * xdot_[mode]->datapoints)); } return state_traj; } From 6748c726b4191f773efab7b020bc43c4686bba4a Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 25 Jan 2023 20:57:05 -0500 Subject: [PATCH 345/758] improving plotstyler --- .../pydairlib/analysis/mbp_plotting_utils.py | 6 +- .../plot_configs/cassie_running_plot.yaml | 2 +- bindings/pydairlib/common/plot_styler.py | 80 ++++++++++--------- bindings/pydairlib/common/plotting_utils.py | 70 ++++++++-------- 4 files changed, 84 insertions(+), 74 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 9f69f3cf51..226d2fecd8 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -9,6 +9,10 @@ CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap +OSC_DERIV_UNITS = {'pos' : 'Position (m)', + 'vel' : 'Velocity (m/s)', + 'accel' : '$Acceleration (m/s^2)$'} + def make_name_to_mbp_maps(plant): return MakeNameToPositionsMap(plant), \ MakeNameToVelocitiesMap(plant), \ @@ -463,7 +467,7 @@ def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): {}, {key: [key] for key in keys}, {'xlabel': 'Time', - 'ylabel': '', + 'ylabel': OSC_DERIV_UNITS[deriv], 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) return ps diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1f5a6bc746..3459f0dba9 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -7,7 +7,7 @@ use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) start_time: 2.2 -duration: 2 +duration: 6 # Plant properties use_springs: true diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index bddf4151b5..d55868c1f1 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -9,7 +9,9 @@ class PlotStyler(): - def __init__(self, figure=None): + def __init__(self, figure=None, nrows=1, ncols=1): + + # self.cmap = plt.get_cmap('tab10') self.cmap = plt.get_cmap('tab20') self.blue = '#011F5B' @@ -21,20 +23,27 @@ def __init__(self, figure=None): self.dpi = 200 self.directory = '/home/yangwill/Pictures/plot_styler/' matplotlib.rcParams['figure.figsize'] = 6, 4 - self.fig = plt.figure(dpi=self.dpi) if figure is None else figure - self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] - self.fig_id = self.fig.number + matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" + if figure is None: + self.fig, self.axes = plt.subplots(nrows=nrows, ncols=ncols, + sharex='all', dpi=self.dpi) + else: + self.fig = figure + self.axes = figure.get_axes() + if not isinstance(self.axes, np.ndarray): + self.axes = [self.axes] + + # self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] + self.fig_id = self.fig.number return def attach(self): plt.figure(self.fig_id) def set_default_styling(self, directory=None): - plt.figure(self.fig_id) self.directory = directory matplotlib.rcParams["savefig.directory"] = directory - matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" # matplotlib.rcParams['figure.figsize'] = 20, 12 # matplotlib.rcParams['figure.figsize'] = 20, 6 matplotlib.rcParams['figure.figsize'] = 8, 16 @@ -43,32 +52,30 @@ def set_default_styling(self, directory=None): matplotlib.rc('font', **font) matplotlib.rcParams['lines.linewidth'] = 4 plt.set_cmap('tab20') - self.directory = directory - - def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, linestyle=None, - grid=True, xlabel=None, ylabel=None, title=None, legend=None, data_label=None): - plt.figure(self.fig_id) - plt.plot(xdata, ydata, color=color, linestyle=linestyle, label=data_label) + def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, + linestyle=None, + grid=True, xlabel=None, ylabel=None, title=None, legend=None, + data_label=None, subplot_index=0): + self.axes[subplot_index].plot(xdata, ydata, color=color, + linestyle=linestyle, label=data_label) if xlim: - plt.xlim(xlim) + self.axes[subplot_index].set_xlim(xlim) if ylim: - plt.ylim(ylim) + self.axes[subplot_index].set_ylim(ylim) if xlabel: - # plt.xlabel(xlabel, fontweight="bold") - plt.xlabel(xlabel) + self.axes[subplot_index].set_xlabel(xlabel) if ylabel: - # plt.ylabel(ylabel, fontweight="bold") - plt.ylabel(ylabel) + self.axes[subplot_index].set_ylabel(ylabel) if title: - # plt.title(title, fontweight="bold") - plt.title(title) + self.axes[subplot_index].set_title(title) if legend: - plt.legend(legend) + self.axes[subplot_index].legend(legend) - plt.grid(grid, which='major') + self.axes[subplot_index].grid(grid, which='major') - def plot_bands(self, x_low, x_high, y_low, y_high, color='C0'): + def plot_bands(self, x_low, x_high, y_low, y_high, color='C0', + subplot_index=0): plt.figure(self.fig_id) vertices = np.block([[x_low, x_high[::-1]], [y_low, y_high[::-1]]]).T @@ -76,30 +83,29 @@ def plot_bands(self, x_low, x_high, y_low, y_high, color='C0'): codes[0] = Path.MOVETO path = Path(vertices, codes) patch = PathPatch(path, facecolor=color, edgecolor='none', alpha=0.3) - ax = plt.gca() - # ax.plot(xdata, ydata) - ax.add_patch(patch) + self.axes[subplot_index].add_patch(patch) def show_fig(self): self.fig.show() return def save_fig(self, filename): - plt.figure(self.fig_id) - plt.savefig(self.directory + filename, dpi=self.dpi) + self.fig.savefig(self.directory + filename, dpi=self.dpi) return - def add_legend(self, labels, loc=0): - plt.figure(self.fig_id) - ax = plt.gca() - legend = ax.legend(labels, loc=loc) - ax.add_artist(legend) + def add_legend(self, labels, loc=0, subplot_index=0): + legend = self.axes[subplot_index].legend(labels, loc=loc) + self.axes[subplot_index].add_artist(legend) return - def annotate(self, text, x, y, x_text, y_text, arrowprops=None): - plt.figure(self.fig_id) - ax = plt.gca() + def annotate(self, text, x, y, x_text, y_text, arrowprops=None, subplot_index=0): if not arrowprops: arrowprops = dict(facecolor='black') # arrowstyle='->' - ax.annotate(text, xy=(x, y), xytext=( + self.axes[subplot_index].annotate(text, xy=(x, y), xytext=( x_text, y_text), arrowprops=arrowprops) + + def set_subplot_options(self, sharex=None, sharey=None): + if sharex is not None: + plt.setp(self.axes, sharex=sharex) + if sharey is not None: + plt.setp(self.axes, sharex=sharey) diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index fc26141146..673b562706 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -20,49 +20,49 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, slices_to_plot, legend_entries, plot_labels, ps): - legend = [] - for key in keys_to_plot: - if key not in slices_to_plot: - ps.plot(data_dictionary[time_key][time_slice], - data_dictionary[key][time_slice]) - else: - ps.plot(data_dictionary[time_key][time_slice], - data_dictionary[key][time_slice, slices_to_plot[key]]) - if key in legend_entries: - legend.extend(legend_entries[key]) + legend = [] + for key in keys_to_plot: + if key not in slices_to_plot: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice], xlabel=plot_labels['xlabel'], + ylabel=plot_labels['ylabel'], title=plot_labels['title']) + else: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice, slices_to_plot[key]], + xlabel=plot_labels['xlabel'], ylabel=plot_labels['ylabel'], + title=plot_labels['title']) + if key in legend_entries: + legend.extend(legend_entries[key]) - ps.add_legend(legend) - plt.xlabel(plot_labels['xlabel']) - plt.ylabel(plot_labels['ylabel']) - plt.title(plot_labels['title']) + ps.add_legend(legend) def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, keys_to_plot, slices_to_plot, legend_entries, plot_labels, ps): - legend = [] - for i, data_dictionary in enumerate(data_dictionaries): - time_key = time_keys[i] - time_slice = time_slices[i] - for key in keys_to_plot[i]: - if key not in slices_to_plot[i]: - ps.plot(data_dictionary[time_key][time_slice], - data_dictionary[key][time_slice]) - else: - ps.plot(data_dictionary[time_key][time_slice], - data_dictionary[key][time_slice, slices_to_plot[key]]) - legend.extend(legend_entries[key]) + legend = [] + for i, data_dictionary in enumerate(data_dictionaries): + time_key = time_keys[i] + time_slice = time_slices[i] + for key in keys_to_plot[i]: + if key not in slices_to_plot[i]: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice]) + else: + ps.plot(data_dictionary[time_key][time_slice], + data_dictionary[key][time_slice, slices_to_plot[key]]) + legend.extend(legend_entries[key]) - ps.add_legend(legend) - plt.xlabel(plot_labels['xlabel']) - plt.ylabel(plot_labels['ylabel']) - plt.title(plot_labels['title']) + ps.add_legend(legend) + plt.xlabel(plot_labels['xlabel']) + plt.ylabel(plot_labels['ylabel']) + plt.title(plot_labels['title']) def slice_to_string_list(slice_): - if isinstance(slice_, slice): - return [str(i) for i in range(slice_.start, slice_.stop, - slice_.step if slice_.step else 1)] - if isinstance(slice_, list): - return [str(i) for i in slice_] + if isinstance(slice_, slice): + return [str(i) for i in range(slice_.start, slice_.stop, + slice_.step if slice_.step else 1)] + if isinstance(slice_, list): + return [str(i) for i in slice_] From f15993f11bf799940de55e1c33a023632cf99acb Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 26 Jan 2023 11:44:58 -0500 Subject: [PATCH 346/758] changes for figures --- .../pydairlib/analysis/mbp_plotting_utils.py | 6 +- examples/Cassie/run_dircon_jumping.cc | 85 ++++++++++--------- examples/Cassie/visualize_trajectory.cc | 76 +++++++++++++---- multibody/multipose_visualizer.h | 4 + 4 files changed, 109 insertions(+), 62 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 226d2fecd8..6f1c300a8b 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -9,9 +9,9 @@ CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap -OSC_DERIV_UNITS = {'pos' : 'Position (m)', - 'vel' : 'Velocity (m/s)', - 'accel' : '$Acceleration (m/s^2)$'} +OSC_DERIV_UNITS = {'pos' : 'Position $(m)$', + 'vel' : 'Velocity $(m/s)$', + 'accel' : 'Acceleration $(m/s^2)$'} def make_name_to_mbp_maps(plant): return MakeNameToPositionsMap(plant), \ diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index e055b78934..40ef2501ca 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -271,7 +271,7 @@ void DoMain() { auto flight_mode = DirconMode(flight_phase_constraints, flight_phase_knotpoints, 0.4, 0.4); auto land_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 1.2875, 1.2875); + stance_knotpoints, 0.5, 1.2875); // auto crouch_mode = DirconMode(double_stance_constraints, // stance_knotpoints, 0.1, 2.0); // auto flight_mode = DirconMode(flight_phase_constraints, @@ -474,19 +474,19 @@ void SetKinematicConstraints(Dircon* trajopt, double midpoint = 0.045; // bounding box constraints on all decision variables - for (int i = 0; i < mode_lengths.size(); ++i) { - for (int j = 0; j < mode_lengths[i]; ++i) { - // auto state_vars_ij = trajopt->state_vars(i, j); - // auto input_vars_ij = trajopt->input_vars(i, j); - auto force_vars_ij = trajopt->force_vars(i, j); - prog->AddBoundingBoxConstraint( - VectorXd::Constant(force_vars_ij.rows(), -200), - VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); - prog->AddBoundingBoxConstraint( - VectorXd::Constant(force_vars_ij.rows(), -200), - VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); - } - } +// for (int i = 0; i < mode_lengths.size(); ++i) { +// for (int j = 0; j < mode_lengths[i]; ++i) { +// // auto state_vars_ij = trajopt->state_vars(i, j); +// // auto input_vars_ij = trajopt->input_vars(i, j); +// auto force_vars_ij = trajopt->force_vars(i, j); +// prog->AddBoundingBoxConstraint( +// VectorXd::Constant(force_vars_ij.rows(), -200), +// VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); +// prog->AddBoundingBoxConstraint( +// VectorXd::Constant(force_vars_ij.rows(), -200), +// VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); +// } +// } // position constraints prog->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, @@ -533,16 +533,16 @@ void SetKinematicConstraints(Dircon* trajopt, // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); - // if (FLAGS_height < 0) { - // prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, - // 0.5 * FLAGS_height + rest_height - eps, - // x_top(pos_map.at("base_z"))); - // - // } else { - // prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, - // FLAGS_height + rest_height + eps, - // x_top(pos_map.at("base_z"))); - // } + if (FLAGS_height < 0) { + prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, + 0.5 * FLAGS_height + rest_height - eps, + x_top(pos_map.at("base_z"))); + + } else { + prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, + FLAGS_height + rest_height + eps, + x_top(pos_map.at("base_z"))); + } prog->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, 0.8 * FLAGS_height + rest_height + eps, x_f(pos_map.at("base_z"))); @@ -681,7 +681,7 @@ void SetKinematicConstraints(Dircon* trajopt, auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); prog->AddConstraint(left_foot_y_constraint, x_i.head(n_q)); prog->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); - if(FLAGS_height >= 0){ + if (FLAGS_height >= 0) { prog->AddConstraint(left_foot_z_ground_constraint, x_i.head(n_q)); prog->AddConstraint(right_foot_z_ground_constraint, x_i.head(n_q)); } @@ -733,18 +733,20 @@ void SetKinematicConstraints(Dircon* trajopt, // Foot ground clearance constraint // Foot clearance constraint - // auto left_foot_z_box_constraint = - // std::make_shared>( - // plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - // (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - // (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); - // auto right_foot_z_box_constraint = - // std::make_shared>( - // plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - // (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - // (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); - // prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); - // prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); + if (fLD::FLAGS_height > 0.3) { + auto left_foot_z_box_constraint = + std::make_shared>( + plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), + (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); + auto right_foot_z_box_constraint = + std::make_shared>( + plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), + (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); + prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); + } auto left_foot_rear_z_final_constraint = std::make_shared>( @@ -1059,10 +1061,11 @@ void SetInitialGuessFromDirconTrajectory(Dircon& trajopt, auto gamma_traj = previous_traj.ReconstructGammaCTrajectory(); trajopt.SetInitialTrajectory(input_traj, state_traj); - for (int mode = 0; mode < trajopt.num_modes(); ++mode) { - trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], - lambda_c_traj[mode], gamma_traj[mode]); - } + // for (int mode = 0; mode < trajopt.num_modes(); ++mode) { + // trajopt.SetInitialForceTrajectory(mode, lambda_traj[mode], + // lambda_c_traj[mode], + // gamma_traj[mode]); + // } } void SetInitialGuessFromKCTrajectory(Dircon& trajopt, diff --git a/examples/Cassie/visualize_trajectory.cc b/examples/Cassie/visualize_trajectory.cc index ca9e4293f3..6453f2123d 100644 --- a/examples/Cassie/visualize_trajectory.cc +++ b/examples/Cassie/visualize_trajectory.cc @@ -45,13 +45,34 @@ int DoMain() { // Drake system initialization stuff drake::systems::DiagramBuilder builder; SceneGraph& scene_graph = *builder.AddSystem(); + SceneGraph& scene_graph_w_spr = *builder.AddSystem(); scene_graph.set_name("scene_graph"); - MultibodyPlant plant(1e-5); + MultibodyPlant plant(1e-3); Parser parser(&plant, &scene_graph); - parser.AddModelFromFile( - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); + const std::string& fixed_spring_urdf = + "examples/Cassie/urdf/cassie_fixed_springs.urdf"; + parser.AddModelFromFile(fixed_spring_urdf); plant.Finalize(); + MultibodyPlant plant_w_spr(1e-3); + const std::string& spring_urdf = "examples/Cassie/urdf/cassie_v2_shells.urdf"; + Parser parser_w_spr(&plant_w_spr, &scene_graph_w_spr); + + parser_w_spr.AddModelFromFile(spring_urdf); + plant_w_spr.Finalize(); + auto pos_spr_map = + multibody::CreateWithSpringsToWithoutSpringsMapPos(plant_w_spr, plant); + auto vel_spr_map = + multibody::CreateWithSpringsToWithoutSpringsMapVel(plant_w_spr, plant); + pos_spr_map.transposeInPlace(); + vel_spr_map.transposeInPlace(); + MatrixXd state_spr_map = + MatrixXd::Zero(plant_w_spr.num_positions() + plant_w_spr.num_velocities(), + plant.num_positions() + plant.num_velocities()); + state_spr_map.block(0, 0, 23, 19) = pos_spr_map; + state_spr_map.block(23, 19, 22, 18) = vel_spr_map; + auto vis_urdf = FLAGS_use_springs ? spring_urdf : fixed_spring_urdf; + int nq = plant.num_positions(); int nv = plant.num_positions(); int nx = nq + nv; @@ -66,6 +87,10 @@ int DoMain() { PiecewisePolynomial optimal_traj = saved_traj.ReconstructStateTrajectory(); + if (FLAGS_use_springs) { + optimal_traj = + saved_traj.ReconstructStateTrajectoryWithSprings(state_spr_map); + } std::vector time_vector = optimal_traj.get_segment_times(); if (FLAGS_mirror_traj) { @@ -109,27 +134,42 @@ int DoMain() { simulator.AdvanceTo(optimal_traj.end_time()); } while (FLAGS_visualize_mode == 1); } else if (FLAGS_visualize_mode == 2) { - MatrixXd poses = MatrixXd::Zero(nq, FLAGS_num_poses); + MatrixXd poses = MatrixXd::Zero(23, FLAGS_num_poses); for (int i = 0; i < FLAGS_num_poses; ++i) { poses.col(i) = optimal_traj.value( time_vector[i * time_vector.size() / FLAGS_num_poses]); + // poses(6, i) += 0.4; } + VectorXd alpha_scale = VectorXd::Ones(FLAGS_num_poses); if (FLAGS_use_transparency) { - VectorXd alpha_scale = VectorXd::LinSpaced(FLAGS_num_poses, 0.2, 1.0); - multibody::MultiposeVisualizer visualizer = - multibody::MultiposeVisualizer( - FindResourceOrThrow( - "examples/Cassie/urdf/cassie_fixed_springs.urdf"), - FLAGS_num_poses, alpha_scale.array().square()); - visualizer.DrawPoses(poses); - } else { - multibody::MultiposeVisualizer visualizer = - multibody::MultiposeVisualizer( - FindResourceOrThrow( - "examples/Cassie/urdf/cassie_fixed_springs.urdf"), - FLAGS_num_poses); - visualizer.DrawPoses(poses); + alpha_scale = VectorXd::LinSpaced(FLAGS_num_poses, 0.2, 1.0); } + multibody::MultiposeVisualizer visualizer = multibody::MultiposeVisualizer( + vis_urdf, FLAGS_num_poses, alpha_scale.array().square()); + auto ortho_camera = drake::geometry::Meshcat::OrthographicCamera(); + ortho_camera.top = 2; + ortho_camera.bottom = -0.1; + ortho_camera.left = -1; + ortho_camera.right = 4; + ortho_camera.near = 0; + ortho_camera.far = 500; + ortho_camera.zoom = 1; + auto perspective_camera = drake::geometry::Meshcat::PerspectiveCamera(); + perspective_camera.fov = 75; + perspective_camera.aspect = 1; + perspective_camera.near = 1; + perspective_camera.far = 1000; + perspective_camera.zoom = 1; + auto translation = Vector3d(); + translation << 0.45, 0, 0.25; + auto origin = drake::math::RigidTransform(translation); + auto box = drake::geometry::Box(0.5, 1.0, 0.5); + visualizer.GetMeshcat()->SetObject("box", box); + visualizer.GetMeshcat()->SetTransform("box", origin); +// visualizer.GetMeshcat()->SetCamera(perspective_camera); + visualizer.GetMeshcat()->SetCamera(ortho_camera); + visualizer.DrawPoses(poses); + while (true){} } return 0; diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index ff764c181b..f7d2690a11 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -54,6 +54,10 @@ class MultiposeVisualizer { /// ignored. void DrawPoses(Eigen::MatrixXd poses); + const std::shared_ptr GetMeshcat(){ + return meshcat_; + } + private: int num_poses_; drake::multibody::MultibodyPlant* plant_; From 15936a65b65ba93494656dc4ccf700f40013eb3f Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 27 Jan 2023 16:33:40 -0500 Subject: [PATCH 347/758] reformatting status message --- examples/Cassie/director_scripts/controller_status.py | 2 +- examples/Cassie/director_scripts/show_time_sim.py | 11 +++++++++-- 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/examples/Cassie/director_scripts/controller_status.py b/examples/Cassie/director_scripts/controller_status.py index e27603ee0f..24d24d2639 100644 --- a/examples/Cassie/director_scripts/controller_status.py +++ b/examples/Cassie/director_scripts/controller_status.py @@ -17,7 +17,7 @@ def __init__(self): self.text_box = vis.TextItem('safety_info', 'safety_info', view) self.text_box.setProperty('Position', [10, 600]) - self.text_box.setProperty('Font Size', 24) + self.text_box.setProperty('Font Size', 36) self.text_box.setProperty('Bold', True) self.set_enabled(True) diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 633297456f..3d66a52c6e 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -16,8 +16,13 @@ def __init__(self): self._subscriber = None # Number of messages used to average for real time factor. self._num_msg_for_average = 20 - + self.text_time = vis.TextItem('sim_info', 'sim_info', view) + self.text_time.setProperty('Position', [10, 900]) + self.text_time.setProperty('Font Size', 36) + self.text_time.setProperty('Bold', True) self.set_enabled(True) + gridObj.setProperty('Grid Half Width', 100) + gridObj.setProperty('Major Tick Resolution', 100) def add_subscriber(self): if (self._subscriber is not None): @@ -81,7 +86,9 @@ def handle_message(self, msg): realtime_text = 'realtime rate: %.2f' % rt_ratio # my_text = my_text + ', real time factor: %.2f' % rt_ratio - vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text, 'text') + # vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text, 'text') + self.text_time.setProperty('Text', my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text) + # vis.updateText(my_text + '\n' + pelvis_velocity_text, 'text') From eb82b3a58571633b1a8431eb068832c4044f5b08 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Feb 2023 11:17:10 -0500 Subject: [PATCH 348/758] moving visualiation to python --- .../plot_configs/cassie_running_plot.yaml | 6 +- bindings/pydairlib/lcm/lcm_trajectory_py.cc | 5 +- .../visualize_configs/box_jump.yaml | 2 +- .../visualize_configs/down_jump.yaml | 8 + .../visualization/visualize_configs/jump.yaml | 8 + .../visualize_configs/long_jump.yaml | 2 +- .../lcm/visualization/visualize_trajectory.py | 149 +++++++++++------- bindings/pydairlib/multibody/multibody_py.cc | 6 + lcm/dircon_saved_trajectory.cc | 8 +- .../osc/operational_space_control.cc | 2 +- 10 files changed, 127 insertions(+), 69 deletions(-) create mode 100644 bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml create mode 100644 bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 3459f0dba9..9c07f0f285 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,8 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 2.2 -duration: 6 +start_time: 5 +duration: 10 # Plant properties use_springs: true @@ -16,7 +16,7 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: true plot_floating_base_velocities: true -plot_floating_base_velocity_body_frame: false +plot_floating_base_velocity_body_frame: true plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: true diff --git a/bindings/pydairlib/lcm/lcm_trajectory_py.cc b/bindings/pydairlib/lcm/lcm_trajectory_py.cc index f6902b9343..ffd5c6cb9b 100644 --- a/bindings/pydairlib/lcm/lcm_trajectory_py.cc +++ b/bindings/pydairlib/lcm/lcm_trajectory_py.cc @@ -82,7 +82,10 @@ PYBIND11_MODULE(lcm_trajectory, m) { .def("ReconstructLambdaCTrajectory", &DirconTrajectory::ReconstructLambdaCTrajectory) .def("ReconstructGammaCTrajectory", - &DirconTrajectory::ReconstructGammaCTrajectory); + &DirconTrajectory::ReconstructGammaCTrajectory) + .def("ReconstructStateTrajectoryWithSprings", + &DirconTrajectory::ReconstructStateTrajectoryWithSprings, + py::arg("wo_spr_to_spr_map")); } } // namespace pydairlib diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml index 219542970e..d77f5a0cb6 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml @@ -1,7 +1,7 @@ filename: examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 1 +visualize_mode: 2 realtime_rate: 0.5 num_poses: 10 use_transparency: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml new file mode 100644 index 0000000000..52a368ccf0 --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml @@ -0,0 +1,8 @@ +filename: examples/Cassie/saved_trajectories/jumping_down_0.15h_0.3d_8 +spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf +visualize_mode: 1 +realtime_rate: 0.5 +num_poses: 9 +use_transparency: 1 +use_springs: 0 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml new file mode 100644 index 0000000000..8191698ad3 --- /dev/null +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml @@ -0,0 +1,8 @@ +filename: examples/Cassie/saved_trajectories/jumping_0.15h_0.3d +spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf +visualize_mode: 1 +realtime_rate: 0.5 +num_poses: 10 +use_transparency: 1 +use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 61b9260814..4c8b37e375 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,4 +1,4 @@ -filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.4d_3 +filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.7d_8 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index f6a110a299..38c1f88877 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -5,69 +5,102 @@ from pydrake.trajectories import PiecewisePolynomial import numpy as np -from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator, SceneGraph, MultibodyPlant) -from pydrake.geometry import MeshcatVisualizer, StartMeshcat, MeshcatVisualizerParams +from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator, + SceneGraph, MultibodyPlant) +from pydrake.geometry import MeshcatVisualizer, StartMeshcat, \ + MeshcatVisualizerParams from pydairlib.cassie.cassie_utils import AddCassieMultibody -from pydairlib.multibody import MultiposeVisualizer, ConnectTrajectoryVisualizer +from pydairlib.multibody import MultiposeVisualizer, \ + ConnectTrajectoryVisualizer, CreateWithSpringsToWithoutSpringsMapPos, \ + CreateWithSpringsToWithoutSpringsMapVel from visualize_params import DirconVisualizationParams def main(): - visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' - params = DirconVisualizationParams(visualization_config_file) - - builder = DiagramBuilder() - scene_graph_wo_spr = builder.AddSystem(SceneGraph()) - # plant_wo_spr, scene_graph_wo_spr = AddMultibodyPlantSceneGraph(builder, 0.0) - plant_wo_spr = MultibodyPlant(0.0) - AddCassieMultibody(plant_wo_spr, scene_graph_wo_spr, - True, "examples/Cassie/urdf/cassie_fixed_springs.urdf", - False, False) - plant_wo_spr.Finalize() - # plant_w_spr, scene_graph_w_spr = AddMultibodyPlantSceneGraph(builder, 0.0) - # AddCassieMultibody(plant_w_spr, scene_graph_w_spr, - # True, "examples/Cassie/urdf/cassie_v2_shells.urdf", - # False, False) - # - # plant_w_spr.Finalize() - - nq = plant_wo_spr.num_positions() - nv = plant_wo_spr.num_velocities() - nx = nq + nv - - filename = FindResourceOrThrow(params.filename) - - dircon_traj = lcm_trajectory.DirconTrajectory(plant_wo_spr, filename) - - optimal_traj = dircon_traj.ReconstructStateTrajectory() - t_vec = optimal_traj.get_segment_times() - - if params.visualize_mode == 0 or params.visualize_mode == 1: - ConnectTrajectoryVisualizer(plant_wo_spr, builder, scene_graph_wo_spr, - optimal_traj) - meschat_params = MeshcatVisualizerParams() - meschat_params.publish_period = 1.0/60.0 - meshcat = StartMeshcat() - visualizer = MeshcatVisualizer.AddToBuilder( - builder, scene_graph_wo_spr, meshcat, meschat_params) - diagram = builder.Build() - - while params.visualize_mode == 1: - simulator = Simulator(diagram) - simulator.set_target_realtime_rate(params.realtime_rate) - simulator.Initialize() - simulator.AdvanceTo(optimal_traj.end_time()) - - elif params.visualize_mode == 2: - poses = np.zeros((params.num_poses, nx)) - for i in range(params.num_poses): - poses[i] = optimal_traj.value(t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] - alpha_scale = np.linspace(0.2, 1.0, params.num_poses) - visualizer = MultiposeVisualizer(FindResourceOrThrow( - params.fixed_spring_urdf), - params.num_poses, np.square(alpha_scale), "") - visualizer.DrawPoses(poses.T) + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' + params = DirconVisualizationParams(visualization_config_file) + + builder = DiagramBuilder() + scene_graph_wo_spr = builder.AddSystem(SceneGraph()) + scene_graph_w_spr = builder.AddSystem(SceneGraph()) + plant_wo_spr = MultibodyPlant(1e-3) + plant_w_spr = MultibodyPlant(1e-3) + AddCassieMultibody(plant_wo_spr, scene_graph_wo_spr, + True, params.fixed_spring_urdf, + False, False, False) + AddCassieMultibody(plant_w_spr, scene_graph_w_spr, + True, params.spring_urdf, + False, False, False) + plant_wo_spr.Finalize() + plant_w_spr.Finalize() + + pos_spr_map = CreateWithSpringsToWithoutSpringsMapPos(plant_w_spr, + plant_wo_spr) + vel_spr_map = CreateWithSpringsToWithoutSpringsMapVel(plant_w_spr, + plant_wo_spr) + + + + nq = plant_wo_spr.num_positions() + nv = plant_wo_spr.num_velocities() + nx = nq + nv + nq_spr = plant_w_spr.num_positions() + nv_spr = plant_w_spr.num_velocities() + nx_spr = nq_spr + nv_spr + state_spr_map = np.zeros((nx_spr, nx)) + state_spr_map[:nq_spr, :nq] = pos_spr_map.T + state_spr_map[-nv_spr:, -nv:] = vel_spr_map.T + + + filename = FindResourceOrThrow(params.filename) + dircon_traj = lcm_trajectory.DirconTrajectory(plant_wo_spr, filename) + + optimal_traj = dircon_traj.ReconstructStateTrajectory() + if params.use_springs: + optimal_traj = dircon_traj.ReconstructStateTrajectoryWithSprings(state_spr_map) + t_vec = optimal_traj.get_segment_times() + + vis_urdf = params.fixed_spring_urdf + vis_plant = plant_wo_spr + vis_scene_graph = scene_graph_wo_spr + nx_vis = nx + if params.use_springs: + vis_urdf = params.spring_urdf + nx_vis = nx_spr + vis_plant = plant_w_spr + vis_scene_graph = scene_graph_w_spr + + if params.visualize_mode == 0 or params.visualize_mode == 1: + + ConnectTrajectoryVisualizer(vis_plant, builder, vis_scene_graph, + optimal_traj) + meschat_params = MeshcatVisualizerParams() + meschat_params.publish_period = 1.0 / 60.0 + meshcat = StartMeshcat() + visualizer = MeshcatVisualizer.AddToBuilder( + builder, vis_scene_graph, meshcat, meschat_params) + diagram = builder.Build() + + while params.visualize_mode == 1: + simulator = Simulator(diagram) + simulator.set_target_realtime_rate(params.realtime_rate) + simulator.Initialize() + simulator.AdvanceTo(optimal_traj.end_time()) + + elif params.visualize_mode == 2: + poses = np.zeros((params.num_poses, nx_vis)) + for i in range(params.num_poses): + poses[i] = optimal_traj.value( + t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] + alpha_scale = np.linspace(0.2, 1.0, params.num_poses) + visualizer = MultiposeVisualizer(FindResourceOrThrow( + vis_urdf), + params.num_poses, np.square(alpha_scale), "") + visualizer.DrawPoses(poses.T) if __name__ == "__main__": - main() + main() diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index c82ed9987b..d31a951da3 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -43,6 +43,12 @@ PYBIND11_MODULE(multibody, m) { .def("CreateActuatorNameVectorFromMap", &dairlib::multibody::CreateActuatorNameVectorFromMap, py::arg("plant")) + .def("CreateWithSpringsToWithoutSpringsMapPos", + &dairlib::multibody::CreateWithSpringsToWithoutSpringsMapPos, + py::arg("plant_w_spr"), py::arg("plant_wo_spr")) + .def("CreateWithSpringsToWithoutSpringsMapVel", + &dairlib::multibody::CreateWithSpringsToWithoutSpringsMapVel, + py::arg("plant_w_spr"), py::arg("plant_wo_spr")) .def("AddFlatTerrain", &dairlib::multibody::AddFlatTerrain, py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"), py::arg("mu_kinetic"), diff --git a/lcm/dircon_saved_trajectory.cc b/lcm/dircon_saved_trajectory.cc index 37d8eefa5f..d046c5bcd9 100644 --- a/lcm/dircon_saved_trajectory.cc +++ b/lcm/dircon_saved_trajectory.cc @@ -297,9 +297,9 @@ const { PiecewisePolynomial DirconTrajectory::ReconstructStateTrajectoryWithSprings( - Eigen::MatrixXd& spr_to_wo_spr_map) const { + Eigen::MatrixXd& wo_spr_to_spr_map) const { PiecewisePolynomial state_traj; - DRAKE_DEMAND(spr_to_wo_spr_map.cols() == x_[0]->datapoints.rows()); + DRAKE_DEMAND(wo_spr_to_spr_map.cols() == x_[0]->datapoints.rows()); for (int mode = 0; mode < num_modes_; ++mode) { // Cannot form trajectory with only a single break @@ -307,8 +307,8 @@ DirconTrajectory::ReconstructStateTrajectoryWithSprings( continue; } state_traj.ConcatenateInTime(PiecewisePolynomial::CubicHermite( - x_[mode]->time_vector, spr_to_wo_spr_map * state_map_ * x_[mode]->datapoints, - spr_to_wo_spr_map * state_map_ * xdot_[mode]->datapoints)); + x_[mode]->time_vector, wo_spr_to_spr_map * state_map_ * x_[mode]->datapoints, + wo_spr_to_spr_map * state_map_ * xdot_[mode]->datapoints)); } return state_traj; } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index c216989aa6..4ed54176ce 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1121,7 +1121,7 @@ void OperationalSpaceControl::CheckTracking( if (soft_constraint_cost_ != nullptr) { soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); } - if (y_soft_constraint_cost[0] > 1e4 || isnan(y_soft_constraint_cost[0])) { + if (y_soft_constraint_cost[0] > 2e4 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } From bace9e7203291db39fd9f4922d9cfeefb4e1de4a Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Feb 2023 17:06:37 -0500 Subject: [PATCH 349/758] refining jumping trajs --- .../visualize_configs/long_jump.yaml | 2 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 52 +- .../Cassie/osc_run/osc_running_gains.yaml | 4 +- examples/Cassie/run_dircon_jumping.cc | 703 ++++++++---------- examples/Cassie/run_osc_jumping_controller.cc | 5 +- .../Cassie/run_osc_standing_controller.cc | 8 - .../cassie_fixed_springs_conservative.urdf | 16 +- 7 files changed, 341 insertions(+), 449 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 4c8b37e375..f70f597573 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,4 +1,4 @@ -filename: examples/Cassie/saved_trajectories/jumping_0.0h_0.7d_8 +filename: examples/Cassie/saved_trajectories/long_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index a96094965b..74ba5a03e5 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -6,8 +6,8 @@ w_accel: 0.0001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 1, + 0.5, 0.9, 0.5, 0.1, 1] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, @@ -15,36 +15,28 @@ W_lambda_c_reg: [1, 0.001, 0.01, W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 -w_soft_constraint: 100 -x_offset: 0.0 +w_soft_constraint: 1000 +x_offset: 0.00 relative_feet: true -mu: 0.4 +mu: 0.6 -w_swing_toe: 1 -swing_toe_kp: 2000 +w_swing_toe: 0.01 +swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 1 -hip_yaw_kp: 40 +w_hip_yaw: 2.5 +hip_yaw_kp: 100 hip_yaw_kd: 5 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.0 +landing_delay: 0.06 CoMW: [20, 0, 0, 0, 2, 0, 0, 0, 20] -PelvisRotW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] -FlightFootW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] CoMKp: [30, 0, 0, 0, 50, 0, @@ -53,20 +45,28 @@ CoMKd: [ 7.5, 0, 0, 0, 5, 0, 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] PelvisRotKp: - [25, 0, 0, - 0, 50, 0, - 0, 0, 50] + [150., 0, 0, + 0, 200., 0, + 0, 0, 0.] PelvisRotKd: - [5, 0, 0, - 0, 10, 0, - 0, 0, 1] + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +FlightFootW: + [10, 0, 0, + 0, 100, 0, + 0, 0, 10] FlightFootKp: - [100, 0, 0, + [125, 0, 0, 0, 100, 0, 0, 0, 100] FlightFootKd: - [10, 0, 0, + [5, 0, 0, 0, 10, 0, 0, 0, 0] diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index ef6ea1bc3a..c38b1cca46 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -16,8 +16,8 @@ mu: 0.6 W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001 ] -W_input_reg: [ 1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5 ] +W_input_reg: [ 1, 0.9, 0.5, 0.1, 1, + 1, 0.9, 0.5, 0.1, 1 ] W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.001, 0.01, diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 40ef2501ca..e4a30bd107 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -21,6 +21,7 @@ #include "solvers/nonlinear_cost.h" #include "systems/trajectory_optimization/dircon/dircon.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/multibody/parsing/parser.h" #include "drake/solvers/solve.h" #include "drake/systems/trajectory_optimization/multiple_shooting.h" @@ -67,57 +68,10 @@ using drake::solvers::VectorXDecisionVariable; using drake::systems::trajectory_optimization::MultipleShooting; using drake::trajectories::PiecewisePolynomial; -DEFINE_int32(knot_points, 10, "Number of knot points per contact mode"); -DEFINE_double(height, 0.2, "Target height for jumping."); -DEFINE_double(start_height, 1.0, "Starting pelvis height for the trajectory."); -DEFINE_double(distance, 0.0, "Target distance (x) from the initial position."); -DEFINE_double(duration, 0.0, "Duration of the total gait"); -DEFINE_int32(scale_option, 0, - "Scale option of SNOPT" - "Use 2 if seeing snopta exit 40 in log file"); -DEFINE_double(tol, 1e-6, "Tolerance for constraint violation and dual gap"); -DEFINE_string(load_filename, "", "File to load decision vars from."); -DEFINE_string(data_directory, "examples/Cassie/saved_trajectories/", - "Directory path to save decision vars to."); -DEFINE_string(save_filename, "default_filename", - "Filename to save decision " - "vars to."); -DEFINE_string(traj_name, "", "File to load saved LCM trajs from."); -DEFINE_bool(use_springs, false, "Whether or not to use the spring model"); -DEFINE_bool( - convert_to_springs, false, - "Whether the loaded trajectory needs to be converted to with springs"); -DEFINE_bool(ipopt, false, "Set flag to true to use ipopt instead of snopt"); -DEFINE_bool(same_knotpoints, false, - "Set flag to true if seeding with a trajectory with the same " - "number of knotpoints"); -DEFINE_double(cost_scaling, 1.0, "Common scaling factor for costs."); -DEFINE_double(actuator_limit, 1.0, - "Conservative estimate scaling factor for actuator limits, 1.0 " - "is at the actual actuator limits."); -DEFINE_double(input_delta, 50.0, - "Maximum change in torques between knot points."); -DEFINE_double(ipopt_iter, 50, "Maximum iterations for IPOPT."); +DEFINE_string(jumping_parameters, "", "Jumping parameters"); namespace dairlib { -HybridDircon* createDircon(MultibodyPlant& plant); - -void SetKinematicConstraints(Dircon* trajopt, - const MultibodyPlant& plant); -void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, - DirconModeSequence*); -void AddCostsSprings(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence*); -void SetInitialGuessFromDirconTrajectory( - Dircon& trajopt, const MultibodyPlant& plant, - const string& filepath, bool same_knot_points = false, - Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); - -void SetInitialGuessFromKCTrajectory(Dircon& trajopt, - const string& filepath); - class JointAccelCost : public solvers::NonlinearCost { public: JointAccelCost(const MatrixXd& W_Q, @@ -166,6 +120,86 @@ class JointAccelCost : public solvers::NonlinearCost { MatrixXd W_Q_; }; +struct DirconJumpingParameters { + // model urdfs + std::string spring_urdf; + std::string fixed_spring_urdf; + // trajectory parameters + int knot_points; + double delta_height; + double start_height; + double distance; + double min_stance_duration; + double max_stance_duration; + double min_flight_duration; + double max_flight_duration; + double actuator_limit; + double input_delta; + // solver parameters + double snopt_scale_option; + double tol; + double dual_inf_tol; + double constr_viol_tol; + double compl_inf_tol; + int acceptable_tol; + double acceptable_iter; + double cost_scaling; + bool use_ipopt; + int ipopt_iter; + // warmstart settings + std::string data_directory; + std::string load_filename; + std::string save_filename; + bool use_springs; + bool convert_to_springs; + bool same_knotpoints; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(spring_urdf)); + a->Visit(DRAKE_NVP(fixed_spring_urdf)); + a->Visit(DRAKE_NVP(knot_points)); + a->Visit(DRAKE_NVP(delta_height)); + a->Visit(DRAKE_NVP(start_height)); + a->Visit(DRAKE_NVP(distance)); + a->Visit(DRAKE_NVP(min_stance_duration)); + a->Visit(DRAKE_NVP(max_stance_duration)); + a->Visit(DRAKE_NVP(min_flight_duration)); + a->Visit(DRAKE_NVP(max_flight_duration)); + a->Visit(DRAKE_NVP(actuator_limit)); + a->Visit(DRAKE_NVP(input_delta)); + a->Visit(DRAKE_NVP(snopt_scale_option)); + a->Visit(DRAKE_NVP(tol)); + a->Visit(DRAKE_NVP(dual_inf_tol)); + a->Visit(DRAKE_NVP(constr_viol_tol)); + a->Visit(DRAKE_NVP(compl_inf_tol)); + a->Visit(DRAKE_NVP(acceptable_tol)); + a->Visit(DRAKE_NVP(acceptable_iter)); + a->Visit(DRAKE_NVP(cost_scaling)); + a->Visit(DRAKE_NVP(use_ipopt)); + a->Visit(DRAKE_NVP(ipopt_iter)); + a->Visit(DRAKE_NVP(data_directory)); + a->Visit(DRAKE_NVP(load_filename)); + a->Visit(DRAKE_NVP(save_filename)); + a->Visit(DRAKE_NVP(use_springs)); + a->Visit(DRAKE_NVP(convert_to_springs)); + a->Visit(DRAKE_NVP(same_knotpoints)); + } +}; + +void SetKinematicConstraints(Dircon* trajopt, + const MultibodyPlant& plant, + DirconJumpingParameters& gait_params); +void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, + DirconModeSequence*, + DirconJumpingParameters& gait_params); +void SetInitialGuessFromDirconTrajectory( + Dircon& trajopt, const MultibodyPlant& plant, + DirconJumpingParameters& gait_params, + Eigen::MatrixXd spr_map = Eigen::MatrixXd::Zero(1, 1)); +void SetInitialGuessFromKCTrajectory(Dircon& trajopt, + const string& filepath); + void DoMain() { // Drake system initialization stuff drake::systems::DiagramBuilder builder; @@ -173,15 +207,15 @@ void DoMain() { scene_graph.set_name("scene_graph"); MultibodyPlant plant(0.0); MultibodyPlant plant_vis(0.0); + auto gait_params = + drake::yaml::LoadYamlFile(FindResourceOrThrow( + "examples/Cassie/saved_trajectories/gait_parameters/" + + FLAGS_jumping_parameters)); - string file_name = - "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf"; - - if (FLAGS_use_springs) { - file_name = "examples/Cassie/urdf/cassie_v2_conservative.urdf"; - } + string file_name = gait_params.fixed_spring_urdf; + if (gait_params.use_springs) file_name = gait_params.spring_urdf; - AddCassieMultibody(&plant, nullptr, true, file_name, FLAGS_use_springs, + AddCassieMultibody(&plant, nullptr, true, file_name, gait_params.use_springs, false); Parser parser_vis(&plant_vis, &scene_graph); @@ -195,7 +229,7 @@ void DoMain() { int n_x = n_q + n_v; MatrixXd spr_map = MatrixXd::Zero(n_x, n_x); - if (FLAGS_use_springs && FLAGS_convert_to_springs) { + if (gait_params.use_springs && gait_params.convert_to_springs) { MultibodyPlant plant_wo_spr(0.0); Parser parser(&plant_wo_spr); parser.AddModelFromFile( @@ -260,24 +294,21 @@ void DoMain() { flight_phase_constraints.add_evaluator(&left_loop_eval); flight_phase_constraints.add_evaluator(&right_loop_eval); - int stance_knotpoints = FLAGS_knot_points; - int flight_phase_knotpoints = FLAGS_knot_points; + int stance_knotpoints = gait_params.knot_points; + int flight_phase_knotpoints = gait_params.knot_points; /**** * Mode duration constraints */ - auto crouch_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.86, 0.86); - auto flight_mode = DirconMode(flight_phase_constraints, - flight_phase_knotpoints, 0.4, 0.4); - auto land_mode = DirconMode(double_stance_constraints, - stance_knotpoints, 0.5, 1.2875); - // auto crouch_mode = DirconMode(double_stance_constraints, - // stance_knotpoints, 0.1, 2.0); - // auto flight_mode = DirconMode(flight_phase_constraints, - // flight_phase_knotpoints, 0.1, 2.0); - // auto land_mode = DirconMode(double_stance_constraints, - // stance_knotpoints, 0.1, 1.0); + auto crouch_mode = DirconMode( + double_stance_constraints, stance_knotpoints, + gait_params.min_stance_duration, gait_params.max_stance_duration); + auto flight_mode = DirconMode( + flight_phase_constraints, flight_phase_knotpoints, + gait_params.min_flight_duration, gait_params.max_flight_duration); + auto land_mode = DirconMode( + double_stance_constraints, stance_knotpoints, + gait_params.min_stance_duration, gait_params.max_stance_duration); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 0); crouch_mode.MakeConstraintRelative(left_toe_eval_ind, 1); @@ -290,16 +321,18 @@ void DoMain() { land_mode.MakeConstraintRelative(left_toe_eval_ind, 0); land_mode.MakeConstraintRelative(left_toe_eval_ind, 1); - land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); land_mode.MakeConstraintRelative(left_heel_eval_ind, 0); land_mode.MakeConstraintRelative(left_heel_eval_ind, 1); - land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); land_mode.MakeConstraintRelative(right_toe_eval_ind, 0); land_mode.MakeConstraintRelative(right_toe_eval_ind, 1); - land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); land_mode.MakeConstraintRelative(right_heel_eval_ind, 0); land_mode.MakeConstraintRelative(right_heel_eval_ind, 1); - land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); + if (gait_params.delta_height != 0) { + land_mode.MakeConstraintRelative(left_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(left_heel_eval_ind, 2); + land_mode.MakeConstraintRelative(right_toe_eval_ind, 2); + land_mode.MakeConstraintRelative(right_heel_eval_ind, 2); + } auto all_modes = DirconModeSequence(plant); all_modes.AddMode(&crouch_mode); @@ -309,27 +342,31 @@ void DoMain() { auto trajopt = Dircon(all_modes); auto& prog = trajopt.prog(); - double tol = FLAGS_tol; - drake::solvers::SolverOptions solver_options; - if (FLAGS_ipopt) { + if (gait_params.use_ipopt) { // Ipopt settings adapted from CaSaDi and FROST auto id = drake::solvers::IpoptSolver::id(); - solver_options.SetOption(id, "tol", tol); // NOLINT - solver_options.SetOption(id, "dual_inf_tol", tol); // NOLINT - solver_options.SetOption(id, "constr_viol_tol", tol); // NOLINT - solver_options.SetOption(id, "compl_inf_tol", tol); // NOLINT - solver_options.SetOption(id, "nlp_lower_bound_inf", -1e6); // NOLINT - solver_options.SetOption(id, "nlp_upper_bound_inf", 1e6); // NOLINT - solver_options.SetOption(id, "print_timing_statistics", "yes"); // NOLINT - solver_options.SetOption(id, "print_level", 5); // NOLINT - solver_options.SetOption(id, "output_file", "../ipopt.out"); // NOLINT - solver_options.SetOption(id, "acceptable_compl_inf_tol", tol); // NOLINT - solver_options.SetOption(id, "acceptable_constr_viol_tol", tol); // NOLINT - solver_options.SetOption(id, "acceptable_obj_change_tol", 1e-3); // NOLINT - solver_options.SetOption(id, "acceptable_tol", 1e2); // NOLINT - solver_options.SetOption(id, "acceptable_iter", 5); // NOLINT - solver_options.SetOption(id, "max_iter", (int)FLAGS_ipopt_iter); // NOLINT + solver_options.SetOption(id, "tol", gait_params.tol); // NOLINT + solver_options.SetOption(id, "dual_inf_tol", + gait_params.dual_inf_tol); // NOLINT + solver_options.SetOption(id, "constr_viol_tol", + gait_params.constr_viol_tol); // NOLINT + solver_options.SetOption(id, "compl_inf_tol", + gait_params.compl_inf_tol); // NOLINT + solver_options.SetOption(id, "nlp_lower_bound_inf", -1e6); // NOLINT + solver_options.SetOption(id, "nlp_upper_bound_inf", 1e6); // NOLINT + solver_options.SetOption(id, "print_timing_statistics", "yes"); // NOLINT + solver_options.SetOption(id, "print_level", 5); // NOLINT + solver_options.SetOption(id, "output_file", "../ipopt.out"); // NOLINT + // solver_options.SetOption(id, "acceptable_compl_inf_tol", tol); // + // NOLINT solver_options.SetOption(id, "acceptable_constr_viol_tol", + // tol); // NOLINT solver_options.SetOption(id, + // "acceptable_obj_change_tol", 1e-3); // NOLINT + solver_options.SetOption(id, "acceptable_tol", + gait_params.acceptable_tol); // NOLINT + solver_options.SetOption(id, "acceptable_iter", + gait_params.acceptable_iter); // NOLINT + solver_options.SetOption(id, "max_iter", gait_params.ipopt_iter); // NOLINT } else { // Snopt settings @@ -340,7 +377,8 @@ void DoMain() { solver_options.SetOption(id, "Verify level", 0); // NOLINT solver_options.SetOption(id, "Major optimality tolerance", 1e-5); // NOLINT solver_options.SetOption(id, "Solution", "No"); // NOLINT - solver_options.SetOption(id, "Major feasibility tolerance", tol); // NOLINT + solver_options.SetOption(id, "Major feasibility tolerance", + gait_params.tol); // NOLINT // prog.SetSolverOption(id, "Print file", "../snopt.out"); // prog.SetSolverOption(id, "Major iterations limit", 1e5); @@ -361,53 +399,37 @@ void DoMain() { } std::cout << "Adding kinematic constraints: " << std::endl; - SetKinematicConstraints(&trajopt, plant); + SetKinematicConstraints(&trajopt, plant, gait_params); std::cout << "Adding costs: " << std::endl; - // if (FLAGS_use_springs) { - // AddCostsSprings(&trajopt, plant, &all_modes); - // } else { - // AddCosts(&trajopt, plant, &all_modes); - // } - AddCosts(&trajopt, plant, &all_modes); + AddCosts(&trajopt, plant, &all_modes, gait_params); std::cout << "Setting initial conditions: " << std::endl; - vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, - FLAGS_knot_points}; + vector mode_lengths = {gait_params.knot_points, gait_params.knot_points, + gait_params.knot_points}; int num_knot_points = trajopt.N(); - std::cout << "nq: " << n_q << endl; - std::cout << "nv: " << n_v << endl; - std::cout << "nu: " << plant.num_actuators() << endl; - cout << "N: " << num_knot_points << endl; - cout << "Num decision vars: " << prog.decision_variables().size() << endl; - - if (!FLAGS_load_filename.empty()) { - std::cout << "Loading: " << FLAGS_load_filename << std::endl; - if (FLAGS_load_filename.find("kc") != -1) { + + if (!gait_params.load_filename.empty()) { + std::cout << "Loading: " << gait_params.load_filename << std::endl; + if (gait_params.load_filename.find("kc") != -1) { SetInitialGuessFromKCTrajectory( - trajopt, FLAGS_data_directory + FLAGS_load_filename); + trajopt, gait_params.data_directory + gait_params.load_filename); } else { - SetInitialGuessFromDirconTrajectory( - trajopt, plant, FLAGS_data_directory + FLAGS_load_filename, - FLAGS_same_knotpoints, spr_map); + SetInitialGuessFromDirconTrajectory(trajopt, plant, gait_params, spr_map); } } double alpha = .2; - // int num_poses = std::min(FLAGS_knot_points + 1, 3); - int num_poses = std::max((int)(mode_lengths.size() + 1), FLAGS_knot_points); - // int num_poses = mode_lengths.size() * FLAGS_knot_points - 1; + int num_poses = + std::max((int)(mode_lengths.size() + 1), gait_params.knot_points); trajopt.CreateVisualizationCallback(file_name, num_poses, alpha); - // cout << "\nChoose the best solver: " - // << drake::solvers::ChooseBestSolver(prog).name() << endl; - cout << "Solving DIRCON\n\n"; auto ipopt_solver = drake::solvers::IpoptSolver(); auto snopt_solver = drake::solvers::SnoptSolver(); MathematicalProgramResult result; auto start = std::chrono::high_resolution_clock::now(); - if (FLAGS_ipopt) { + if (gait_params.use_ipopt) { result = ipopt_solver.Solve(prog, prog.initial_guess(), solver_options); } else { result = snopt_solver.Solve(prog, prog.initial_guess(), solver_options); @@ -423,8 +445,10 @@ void DoMain() { DirconTrajectory saved_traj(plant, trajopt, result, "jumping_trajectory", "Decision variables and state/input trajectories " "for jumping"); - saved_traj.WriteToFile(FLAGS_data_directory + FLAGS_save_filename); - std::cout << "Wrote to file: " << FLAGS_data_directory + FLAGS_save_filename + saved_traj.WriteToFile(gait_params.data_directory + + gait_params.save_filename); + std::cout << "Wrote to file: " + << gait_params.data_directory + gait_params.save_filename << std::endl; drake::trajectories::PiecewisePolynomial optimal_traj = trajopt.ReconstructStateTrajectory(result); @@ -442,7 +466,8 @@ void DoMain() { } void SetKinematicConstraints(Dircon* trajopt, - const MultibodyPlant& plant) { + const MultibodyPlant& plant, + DirconJumpingParameters& gait_params) { auto* prog = &trajopt->prog(); // Create maps for joints map pos_map = multibody::MakeNameToPositionsMap(plant); @@ -455,8 +480,9 @@ void SetKinematicConstraints(Dircon* trajopt, // Get the decision variables that will be used int N = trajopt->N(); - std::vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, - FLAGS_knot_points}; + std::vector mode_lengths = {gait_params.knot_points, + gait_params.knot_points, + gait_params.knot_points}; auto x_0 = trajopt->initial_state(); auto x_top = trajopt->state(N / 2); auto x_f = trajopt->final_state(); @@ -468,34 +494,34 @@ void SetKinematicConstraints(Dircon* trajopt, // Duration Bounds // Standing constraints - double rest_height = FLAGS_start_height; + double rest_height = gait_params.start_height; double eps = 1e-4; double midpoint = 0.045; - // bounding box constraints on all decision variables -// for (int i = 0; i < mode_lengths.size(); ++i) { -// for (int j = 0; j < mode_lengths[i]; ++i) { -// // auto state_vars_ij = trajopt->state_vars(i, j); -// // auto input_vars_ij = trajopt->input_vars(i, j); -// auto force_vars_ij = trajopt->force_vars(i, j); -// prog->AddBoundingBoxConstraint( -// VectorXd::Constant(force_vars_ij.rows(), -200), -// VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); -// prog->AddBoundingBoxConstraint( -// VectorXd::Constant(force_vars_ij.rows(), -200), -// VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); -// } -// } +// bounding box constraints on all decision variables + for (int i = 0; i < mode_lengths.size(); ++i) { + for (int j = 0; j < mode_lengths[i]; ++i) { + // auto state_vars_ij = trajopt->state_vars(i, j); + // auto input_vars_ij = trajopt->input_vars(i, j); + auto force_vars_ij = trajopt->force_vars(i, j); + prog->AddBoundingBoxConstraint( + VectorXd::Constant(force_vars_ij.rows(), -200), + VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); + prog->AddBoundingBoxConstraint( + VectorXd::Constant(force_vars_ij.rows(), -200), + VectorXd::Constant(force_vars_ij.rows(), 200), force_vars_ij); + } + } // position constraints prog->AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, x_0(pos_map.at("base_x"))); - prog->AddBoundingBoxConstraint(FLAGS_distance + midpoint, - FLAGS_distance + midpoint, + prog->AddBoundingBoxConstraint(gait_params.distance + midpoint, + gait_params.distance + midpoint, x_f(pos_map.at("base_x"))); - prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); - prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); + prog->AddBoundingBoxConstraint(-eps, eps, x_0(pos_map.at("base_y"))); + prog->AddBoundingBoxConstraint(-eps, eps, x_f(pos_map.at("base_y"))); // initial fb orientation constraint VectorXd quat_identity(4); @@ -507,9 +533,9 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); - prog->AddBoundingBoxConstraint(0.00, 0.1, x_0(pos_map.at("hip_roll_left"))); - prog->AddBoundingBoxConstraint(-0.1, -0.00, - x_0(pos_map.at("hip_roll_right"))); +// prog->AddBoundingBoxConstraint(0.00, 0.1, x_0(pos_map.at("hip_roll_left"))); +// prog->AddBoundingBoxConstraint(-0.1, -0.00, +// x_0(pos_map.at("hip_roll_right"))); // hip yaw and roll constraints prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); @@ -520,32 +546,35 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_left"))); // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_right"))); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) >= -2.1); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) >= -2.1); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) <= -1.1); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) <= -1.1); - - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) >= -2.2); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) >= -2.2); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) <= -1.6); - trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) <= -1.6); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) >= -2.1); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) >= -2.1); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) <= -1.1); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) <= -1.1); +// +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) >= -2.2); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) >= -2.2); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) <= -1.6); +// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) <= -1.6); // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, x_0(pos_map.at("base_z"))); - if (FLAGS_height < 0) { - prog->AddBoundingBoxConstraint(FLAGS_height + rest_height + eps, - 0.5 * FLAGS_height + rest_height - eps, - x_top(pos_map.at("base_z"))); + if (gait_params.delta_height < 0) { + prog->AddBoundingBoxConstraint( + gait_params.delta_height + rest_height + eps, + 0.5 * gait_params.delta_height + rest_height - eps, + x_top(pos_map.at("base_z"))); } else { - prog->AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, - FLAGS_height + rest_height + eps, - x_top(pos_map.at("base_z"))); + prog->AddBoundingBoxConstraint( + 0.5 * gait_params.delta_height + rest_height - eps, + gait_params.delta_height + rest_height + eps, + x_top(pos_map.at("base_z"))); } - prog->AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, - 0.8 * FLAGS_height + rest_height + eps, - x_f(pos_map.at("base_z"))); + prog->AddBoundingBoxConstraint( + 0.8 * gait_params.delta_height + rest_height - eps, + 0.8 * gait_params.delta_height + rest_height + eps, + x_f(pos_map.at("base_z"))); // Zero starting and final velocities prog->AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); @@ -578,7 +607,7 @@ void SetKinematicConstraints(Dircon* trajopt, motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); } } - if (FLAGS_use_springs) { + if (gait_params.use_springs) { for (const auto& spring_joint_name : spring_joint_names) { joint_names.push_back(spring_joint_name + l_r_pair.first); } @@ -586,38 +615,6 @@ void SetKinematicConstraints(Dircon* trajopt, } l_r_pairs.pop_back(); - // Symmetry constraints - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& sym_joint_name : sym_joint_names) { - // trajopt->AddConstraintToAllKnotPoints( - // x_0(pos_map[sym_joint_name + l_r_pair.first]) == - // x_0(pos_map[sym_joint_name + l_r_pair.second])); - // prog->AddLinearConstraint(x_0(pos_map[sym_joint_name + - // l_r_pair.first]) == - // x_0(pos_map[sym_joint_name + l_r_pair.second])); - // prog->AddLinearConstraint(x_f(pos_map[sym_joint_name + - // l_r_pair.first]) == - // x_f(pos_map[sym_joint_name + l_r_pair.second])); - if (sym_joint_name != "ankle_joint") { // No actuator at ankle - // trajopt->AddConstraintToAllKnotPoints( - // u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] - // - - // u[act_map.at(sym_joint_name + l_r_pair.second + - // "_motor")] <= - // 10); - // trajopt->AddConstraintToAllKnotPoints( - // u[act_map.at(sym_joint_name + l_r_pair.first + "_motor")] - // - - // u[act_map.at(sym_joint_name + l_r_pair.second + - // "_motor")] >= - // -10); - // prog->AddConstraint( - // u_f(act_map.at(sym_joint_name + l_r_pair.first + - // "_motor")) == u_f(act_map.at(sym_joint_name + - // l_r_pair.second + "_motor"))); - } - } - } // joint limits std::cout << "Joint limit constraints: " << std::endl; @@ -634,10 +631,10 @@ void SetKinematicConstraints(Dircon* trajopt, VectorXd u_min(n_u); VectorXd u_max(n_u); for (drake::multibody::JointActuatorIndex i(0); i < n_u; ++i) { - u_min[i] = - FLAGS_actuator_limit * -plant.get_joint_actuator(i).effort_limit(); + u_min[i] = gait_params.actuator_limit * + -plant.get_joint_actuator(i).effort_limit(); u_max[i] = - FLAGS_actuator_limit * plant.get_joint_actuator(i).effort_limit(); + gait_params.actuator_limit * plant.get_joint_actuator(i).effort_limit(); } for (int i = 0; i < trajopt->N(); i++) { auto ui = trajopt->input(i); @@ -647,9 +644,9 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); // prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); prog->AddConstraint(ui - uip1 <= - VectorXd::Constant(n_u, FLAGS_input_delta)); + VectorXd::Constant(n_u, gait_params.input_delta)); prog->AddConstraint(ui - uip1 >= - VectorXd::Constant(n_u, -FLAGS_input_delta)); + VectorXd::Constant(n_u, -gait_params.input_delta)); } } @@ -669,11 +666,11 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_z_ground_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), - VectorXd::Zero(1), 0.5 * VectorXd::Ones(1)); + VectorXd::Zero(1), 1.0 * VectorXd::Ones(1)); auto right_foot_z_ground_constraint = std::make_shared>( plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), - VectorXd::Zero(1), 0.5 * VectorXd::Ones(1)); + VectorXd::Zero(1), 1.0 * VectorXd::Ones(1)); for (int mode : {0, 1, 2}) { for (int index = 0; index < mode_lengths[mode]; index++) { @@ -681,14 +678,42 @@ void SetKinematicConstraints(Dircon* trajopt, auto x_i = trajopt->state((mode_lengths[mode] - 1) * mode + index); prog->AddConstraint(left_foot_y_constraint, x_i.head(n_q)); prog->AddConstraint(right_foot_y_constraint, x_i.head(n_q)); - if (FLAGS_height >= 0) { + if (gait_params.delta_height >= 0) { prog->AddConstraint(left_foot_z_ground_constraint, x_i.head(n_q)); prog->AddConstraint(right_foot_z_ground_constraint, x_i.head(n_q)); } } } - // Jumping distance constraint for platform clearance + // Constraint for platform clearance + if (gait_params.delta_height > 0.3) { + auto left_foot_x_box_constraint = + std::make_shared>( + plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (gait_params.distance - eps) * VectorXd::Ones(1), + 0.4 * (gait_params.distance + eps) * VectorXd::Ones(1)); + auto right_foot_x_box_constraint = + std::make_shared>( + plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), + 0.4 * (gait_params.distance - eps) * VectorXd::Ones(1), + 0.4 * (gait_params.distance + eps) * VectorXd::Ones(1)); + prog->AddConstraint(left_foot_x_box_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_x_box_constraint, x_top.head(n_q)); + auto left_foot_z_box_constraint = + std::make_shared>( + plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + (0.1 + gait_params.delta_height - eps) * VectorXd::Ones(1), + (0.3 + gait_params.delta_height + eps) * VectorXd::Ones(1)); + auto right_foot_z_box_constraint = + std::make_shared>( + plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), + (0.1 + gait_params.delta_height - eps) * VectorXd::Ones(1), + (0.3 + gait_params.delta_height + eps) * VectorXd::Ones(1)); + prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); + prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); + } + + // Foot start constraint auto left_foot_x_start_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), @@ -700,79 +725,45 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddConstraint(left_foot_x_start_constraint, x_0.head(n_q)); prog->AddConstraint(right_foot_x_start_constraint, x_0.head(n_q)); - // Jumping distance constraint for platform clearance - if (FLAGS_height > 0.3) { - auto left_foot_x_platform_constraint = - std::make_shared>( - plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), - 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); - auto right_foot_x_platform_constraint = - std::make_shared>( - plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.4 * (FLAGS_distance - eps) * VectorXd::Ones(1), - 0.4 * (FLAGS_distance + eps) * VectorXd::Ones(1)); - prog->AddConstraint(left_foot_x_platform_constraint, x_top.head(n_q)); - prog->AddConstraint(right_foot_x_platform_constraint, x_top.head(n_q)); - } - // Jumping distance constraint auto left_foot_x_constraint = std::make_shared>( plant, "toe_left", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), - (FLAGS_distance - eps) * VectorXd::Ones(1), - (FLAGS_distance + eps) * VectorXd::Ones(1)); + (gait_params.distance - eps) * VectorXd::Ones(1), + (gait_params.distance + eps) * VectorXd::Ones(1)); auto right_foot_x_constraint = std::make_shared>( plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(1, 0, 0), - (FLAGS_distance - eps) * VectorXd::Ones(1), - (FLAGS_distance + eps) * VectorXd::Ones(1)); + (gait_params.distance - eps) * VectorXd::Ones(1), + (gait_params.distance + eps) * VectorXd::Ones(1)); prog->AddConstraint(left_foot_x_constraint, x_f.head(n_q)); prog->AddConstraint(right_foot_x_constraint, x_f.head(n_q)); - // Foot ground clearance constraint - - // Foot clearance constraint - if (fLD::FLAGS_height > 0.3) { - auto left_foot_z_box_constraint = - std::make_shared>( - plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); - auto right_foot_z_box_constraint = - std::make_shared>( - plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 0, 1), - (0.1 + FLAGS_height - eps) * VectorXd::Ones(1), - (0.3 + FLAGS_height + eps) * VectorXd::Ones(1)); - prog->AddConstraint(left_foot_z_box_constraint, x_top.head(n_q)); - prog->AddConstraint(right_foot_z_box_constraint, x_top.head(n_q)); - } - + // Foot ground constraint auto left_foot_rear_z_final_constraint = std::make_shared>( plant, "toe_left", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), - (FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (gait_params.delta_height - eps) * VectorXd::Ones(1), + (gait_params.delta_height + eps) * VectorXd::Ones(1)); auto right_foot_rear_z_final_constraint = std::make_shared>( plant, "toe_right", pt_rear_contact, Eigen::RowVector3d(0, 0, 1), - (FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); - prog->AddConstraint(left_foot_rear_z_final_constraint, x_f.head(n_q)); - prog->AddConstraint(right_foot_rear_z_final_constraint, x_f.head(n_q)); - + (gait_params.delta_height - eps) * VectorXd::Ones(1), + (gait_params.delta_height + eps) * VectorXd::Ones(1)); auto left_foot_front_z_final_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), - (FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (gait_params.delta_height - eps) * VectorXd::Ones(1), + (gait_params.delta_height + eps) * VectorXd::Ones(1)); auto right_foot_front_z_final_constraint = std::make_shared>( plant, "toe_right", pt_front_contact, Eigen::RowVector3d(0, 0, 1), - (FLAGS_height - eps) * VectorXd::Ones(1), - (FLAGS_height + eps) * VectorXd::Ones(1)); + (gait_params.delta_height - eps) * VectorXd::Ones(1), + (gait_params.delta_height + eps) * VectorXd::Ones(1)); prog->AddConstraint(left_foot_front_z_final_constraint, x_f.head(n_q)); prog->AddConstraint(right_foot_front_z_final_constraint, x_f.head(n_q)); + prog->AddConstraint(left_foot_rear_z_final_constraint, x_f.head(n_q)); + prog->AddConstraint(right_foot_rear_z_final_constraint, x_f.head(n_q)); // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground @@ -784,24 +775,25 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddLinearConstraint(lambda(11) >= 60); // } // Limit the ground reaction forces in the landing phase - for (int index = 0; index < mode_lengths[2]; index++) { - auto lambda = trajopt->force_vars(2, index); - prog->AddLinearConstraint(lambda(2) <= 350); - prog->AddLinearConstraint(lambda(5) <= 350); - prog->AddLinearConstraint(lambda(8) <= 350); - prog->AddLinearConstraint(lambda(11) <= 350); - prog->AddLinearConstraint(lambda(2) >= 50); - prog->AddLinearConstraint(lambda(5) >= 50); - prog->AddLinearConstraint(lambda(8) >= 50); - prog->AddLinearConstraint(lambda(11) >= 50); - } +// for (int index = 0; index < mode_lengths[2]; index++) { +// auto lambda = trajopt->force_vars(2, index); +// prog->AddLinearConstraint(lambda(2) <= 350); +// prog->AddLinearConstraint(lambda(5) <= 350); +// prog->AddLinearConstraint(lambda(8) <= 350); +// prog->AddLinearConstraint(lambda(11) <= 350); +// prog->AddLinearConstraint(lambda(2) >= 50); +// prog->AddLinearConstraint(lambda(5) >= 50); +// prog->AddLinearConstraint(lambda(8) >= 50); +// prog->AddLinearConstraint(lambda(11) >= 50); +// } } /****** COSTS ******/ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, - DirconModeSequence* constraints) { + DirconModeSequence* constraints, + DirconJumpingParameters& gait_params) { auto x = trajopt->state(); auto u = trajopt->input(); @@ -839,9 +831,9 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, } l_r_pairs.pop_back(); - double w_symmetry_pos = FLAGS_cost_scaling * 1e5; - double w_symmetry_vel = FLAGS_cost_scaling * 1e2; - double w_symmetry_u = FLAGS_cost_scaling * 1e2; + double w_symmetry_pos = gait_params.cost_scaling * 1e5; + double w_symmetry_vel = gait_params.cost_scaling * 1e2; + double w_symmetry_u = gait_params.cost_scaling * 1e2; for (const auto& l_r_pair : l_r_pairs) { for (const auto& sym_joint_name : sym_joint_names) { auto pos_diff = x(pos_map.at(sym_joint_name + l_r_pair.first)) - @@ -875,9 +867,9 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, } } - MatrixXd Q = FLAGS_cost_scaling * 0.02 * MatrixXd::Identity(n_v, n_v); + MatrixXd Q = gait_params.cost_scaling * 0.02 * MatrixXd::Identity(n_v, n_v); // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); - MatrixXd R = FLAGS_cost_scaling * 1e-1 * MatrixXd::Identity(n_u, n_u); + MatrixXd R = gait_params.cost_scaling * 1e-1 * MatrixXd::Identity(n_u, n_u); // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = // 5e-1; // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) @@ -905,14 +897,15 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, q_f(pos_map.at("hip_roll_right")) = 0; q_f(pos_map.at("hip_pitch_left")) = 0.67; q_f(pos_map.at("hip_pitch_right")) = 0.67; - q_f(pos_map.at("base_z")) = 0.8 * FLAGS_height + FLAGS_start_height; + q_f(pos_map.at("base_z")) = + 0.8 * gait_params.delta_height + gait_params.start_height; VectorXd q_f_target_left = q_f.segment(6, 4); VectorXd q_f_target_right = q_f.segment(13, 3); - MatrixXd Q_left = FLAGS_cost_scaling * MatrixXd::Identity(4, 4); - MatrixXd Q_right = FLAGS_cost_scaling * MatrixXd::Identity(3, 3); - Q_left(2, 2) = FLAGS_cost_scaling * 1e2; - Q_right(2, 2) = FLAGS_cost_scaling * 1e2; + MatrixXd Q_left = gait_params.cost_scaling * MatrixXd::Identity(4, 4); + MatrixXd Q_right = gait_params.cost_scaling * MatrixXd::Identity(3, 3); + Q_left(2, 2) = gait_params.cost_scaling * 1e2; + Q_right(2, 2) = gait_params.cost_scaling * 1e2; trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); trajopt->AddRunningCost((x.segment(6, 4) - q_f_target_left).transpose() * @@ -921,135 +914,45 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, Q_right * (x.segment(13, 3) - q_f_target_right)); trajopt->AddRunningCost(u.transpose() * R * u); - vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, - FLAGS_knot_points}; - MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); - W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 1e2; - W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 1e2; - W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; - W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; - W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; - W(vel_map["hip_yaw_rightdot"], vel_map["hip_yaw_rightdot"]) *= 1e2; - W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; - W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; - W *= 2.0 * FLAGS_cost_scaling; - vector> joint_accel_costs; - for (int mode : {0, 1, 2}) { - joint_accel_costs.push_back(std::make_shared( - W, plant, &constraints->mode(mode).evaluators())); - for (int index = 0; index < mode_lengths[mode]; index++) { - // Assumes mode_lengths are the same across modes - auto x_i = trajopt->state_vars(mode, index); - auto u_i = trajopt->input_vars(mode, index); - auto l_i = trajopt->force_vars(mode, index); - trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - } - } -} - -/****** -COSTS -******/ -void AddCostsSprings(Dircon* trajopt, - const MultibodyPlant& plant, - DirconModeSequence* constraints) { - auto x = trajopt->state(); - auto u = trajopt->input(); - - map pos_map = multibody::MakeNameToPositionsMap(plant); - map vel_map = multibody::MakeNameToVelocitiesMap(plant); - map act_map = multibody::MakeNameToActuatorsMap(plant); - - int n_v = plant.num_velocities(); - int n_u = plant.num_actuators(); - - // create joint/motor names - vector> l_r_pairs{ - std::pair("_left", "_right"), - std::pair("_right", "_left"), - }; - vector asy_joint_names{ - "hip_roll", - "hip_yaw", - }; - vector sym_joint_names{"hip_pitch", "knee", "ankle_joint", "toe"}; - vector joint_names{}; - vector motor_names{}; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& asy_joint_name : asy_joint_names) { - joint_names.push_back(asy_joint_name + l_r_pair.first); - motor_names.push_back(asy_joint_name + l_r_pair.first + "_motor"); - } - for (const auto& sym_joint_name : sym_joint_names) { - joint_names.push_back(sym_joint_name + l_r_pair.first); - if (sym_joint_name != "ankle_joint") { - motor_names.push_back(sym_joint_name + l_r_pair.first + "_motor"); - } - } - } - l_r_pairs.pop_back(); - - double w_symmetry_pos = FLAGS_cost_scaling * 1e3; - double w_symmetry_vel = FLAGS_cost_scaling * 1e1; - for (const auto& l_r_pair : l_r_pairs) { - for (const auto& sym_joint_name : sym_joint_names) { - auto pos_diff = x(pos_map[sym_joint_name + l_r_pair.first]) - - x(pos_map[sym_joint_name + l_r_pair.second]); - auto vel_diff = x(vel_map[sym_joint_name + l_r_pair.first + "dot"]) - - x(vel_map[sym_joint_name + l_r_pair.second + "dot"]); - trajopt->AddRunningCost(w_symmetry_pos * pos_diff * pos_diff); - trajopt->AddRunningCost(w_symmetry_vel * vel_diff * vel_diff); - } - } - - std::cout << "n_v_: " << n_v << std::endl; - MatrixXd Q = FLAGS_cost_scaling * 0.01 * MatrixXd::Identity(n_v, n_v); - MatrixXd R = FLAGS_cost_scaling * 1e-4 * MatrixXd::Identity(n_u, n_u); - - trajopt->AddRunningCost(x.tail(n_v).transpose() * Q * x.tail(n_v)); - trajopt->AddRunningCost(u.transpose() * R * u); - - vector mode_lengths = {FLAGS_knot_points, FLAGS_knot_points, - FLAGS_knot_points}; - MatrixXd W = 1e-3 * MatrixXd::Identity(n_v, n_v); - W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) *= 1e1; - W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) *= 1e1; - W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) *= 1e1; - W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) *= 1e1; - // Add no costs on spring acceleration because we can't control for that - W(vel_map["knee_joint_leftdot"], vel_map["knee_joint_leftdot"]) = 0.0; - W(vel_map["knee_joint_rightdot"], vel_map["knee_joint_rightdot"]) = 0.0; - W(vel_map["ankle_spring_joint_leftdot"], - vel_map["ankle_spring_joint_leftdot"]) = 0.0; - W(vel_map["ankle_spring_joint_rightdot"], - vel_map["ankle_spring_joint_rightdot"]) = 0.0; - vector> joint_accel_costs; - for (int mode : {0, 1, 2}) { - joint_accel_costs.push_back(std::make_shared( - FLAGS_cost_scaling * W, plant, &constraints->mode(mode).evaluators())); - for (int index = 0; index < mode_lengths[mode]; index++) { - // Assumes mode_lengths are the same across modes - auto x_i = trajopt->state_vars(mode, index); - auto u_i = trajopt->input_vars(mode, index); - auto l_i = trajopt->force_vars(mode, index); - trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - } - } +// vector mode_lengths = {gait_params.knot_points, gait_params.knot_points, +// gait_params.knot_points}; +// MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); +// W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 1e2; +// W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 1e2; +// W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; +// W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; +// W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; +// W(vel_map["hip_yaw_rightdot"], vel_map["hip_yaw_rightdot"]) *= 1e2; +// W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; +// W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; +// W *= 2.0 * gait_params.cost_scaling; +// vector> joint_accel_costs; +// for (int mode : {0, 1, 2}) { +// joint_accel_costs.push_back(std::make_shared( +// W, plant, &constraints->mode(mode).evaluators())); +// for (int index = 0; index < mode_lengths[mode]; index++) { +// // Assumes mode_lengths are the same across modes +// auto x_i = trajopt->state_vars(mode, index); +// auto u_i = trajopt->input_vars(mode, index); +// auto l_i = trajopt->force_vars(mode, index); +// trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); +// } +// } } void SetInitialGuessFromDirconTrajectory(Dircon& trajopt, const MultibodyPlant& plant, - const string& filepath, - bool same_knot_points, + DirconJumpingParameters& gait_params, Eigen::MatrixXd spr_map) { - DirconTrajectory previous_traj = DirconTrajectory(plant, filepath); - if (same_knot_points) { + DirconTrajectory previous_traj = DirconTrajectory( + plant, gait_params.data_directory + gait_params.load_filename); + if (gait_params.same_knotpoints) { trajopt.prog().SetInitialGuessForAllVariables( previous_traj.GetDecisionVariables()); return; } drake::trajectories::PiecewisePolynomial state_traj; - if (FLAGS_use_springs && FLAGS_convert_to_springs) { + if (gait_params.use_springs && gait_params.convert_to_springs) { std::cout << "Using spring conversion" << std::endl; state_traj = previous_traj.ReconstructStateTrajectoryWithSprings(spr_map); } else { diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 6af7605553..56bb0eb975 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -364,14 +364,11 @@ int DoMain(int argc, char* argv[]) { auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_com, osc_gains.K_d_com, osc_gains.W_com, plant_w_spr, plant_w_spr); - for (auto mode : stance_modes) { - pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); - } - auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_tracking_data", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { + pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(mode, "pelvis"); } pelvis_rot_tracking_data->SetImpactInvariantProjection(true); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 1a8920c96d..14fa4c601f 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -87,16 +87,8 @@ int DoMain(int argc, char* argv[]) { "examples/Cassie/urdf/cassie_v2_conservative.urdf", true /*spring model*/, false /*loop closure*/); plant.Finalize(); - // Build fix-spring Cassie MBP - // drake::multibody::MultibodyPlant plant(0.0); - // AddCassieMultibody( - // &plant, nullptr, true, - // "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf", false, - // false); - // plant.Finalize(); auto context_w_spr = plant.CreateDefaultContext(); - // auto context_wo_spr = plant.CreateDefaultContext(); // Get contact frames and position (doesn't matter whether we use // plant or plant because the contact frames exit in both diff --git a/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf index 6c3196f40b..9333be2430 100644 --- a/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf +++ b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf @@ -617,7 +617,7 @@ - + @@ -626,7 +626,7 @@ - + @@ -636,7 +636,7 @@ - + @@ -645,7 +645,7 @@ - + @@ -655,7 +655,7 @@ - + @@ -664,7 +664,7 @@ - + @@ -791,7 +791,7 @@ - + @@ -800,7 +800,7 @@ - + From c7be18f09984607f0fc98eb43c48fb0ab784f1a7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Feb 2023 12:09:18 -0500 Subject: [PATCH 350/758] adding generated trajectories --- examples/Cassie/run_dircon_jumping.cc | 2 +- examples/Cassie/saved_trajectories/box_jump | Bin 0 -> 52477 bytes examples/Cassie/saved_trajectories/down_jump | Bin 0 -> 52477 bytes 3 files changed, 1 insertion(+), 1 deletion(-) create mode 100644 examples/Cassie/saved_trajectories/box_jump create mode 100644 examples/Cassie/saved_trajectories/down_jump diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index e4a30bd107..7a6facc71d 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -141,7 +141,7 @@ struct DirconJumpingParameters { double dual_inf_tol; double constr_viol_tol; double compl_inf_tol; - int acceptable_tol; + double acceptable_tol; double acceptable_iter; double cost_scaling; bool use_ipopt; diff --git a/examples/Cassie/saved_trajectories/box_jump b/examples/Cassie/saved_trajectories/box_jump new file mode 100644 index 0000000000000000000000000000000000000000..8f94ab0a5b384c52c6c25571c5ac7fc409ddfda1 GIT binary patch literal 52477 zcmeGF2{=_>{0I7*=Xt8gm`r7EFs~I#lpS*O1J|G#_hbMOEE+~?k#=lOp3S$lu>Is5FKb@s8|=d~Q77B|U$q;sUF zqoWgD73d|k%EMJkN>fT*O=sy+9St=p4K)o-4$4M4!Rzx!UjBYkyIlgkTwHxTc1pSUxl8Tb<+95|)ypp+XqOai4=>6_PyawE>RtWZ zU&+NZ4C`~Z8uL34^P)69_sEMOI&^(1Z5A-**l#* zjGuQPLiulY+s_8Lm}IFUt$PAw&n{y?;b?K!xxwq8l-jP43M_v9NDEZXuD=1EK4xXx zEF=c%g}$B|(s>9PE4{AX8VCc;!EXwEQ#8O!#r2Ps*Y<%|ugb68l2Qb1F-xNsk9vU) ziRVjf-E2T-oWmWXeQQA1Os9(4*%hEWVCzlsJIg^&$B+U?wK8~bxhs9VM;3f2`!3x* zBMSO84qa@VCy3q&$voTJxD54g@)+JL=!)K#G8AX~%${^>I~a6k^6DyIfyFN~$~@Tb zj74@GvDqeZ9rGKVn@(6hvI z?OuBiGdQG;4=T>VjCarTIxcvKnLY%p>T)#(?OF21wSxv=VCRADhLNwqhrmImEuyL#8B;CY`1}$e=E5 zc-4s?(xrYf^lK}G^vfU4(F?r^8SEdlS!^nYjDwH&(8m`*rVE+#=PX_ZIkRtPZd_9j z+CEPSoLPDnbp{H{4WC|uKFKW-uG~?DM%OrBI=avweF~QMbM)DUzSr0fZLzq88kO3n z&Q=7&Mb~VmLKeznRYhkP$Gn?ZxNFnEy2N%UVJCdClI}K?7FDBP*EKq5mhZs@!Oa#}{?qM{+cr>DPupW)8Ux}dn%b+i5k0dUZd`3exOUCVu zH>2(iJlQ-&MVK?B^|9Lx3)HTyD|%M!0qAsMyY+zm2l&M7S?sNu3`T<`HP;1Cg3sw@ zJ2m67z_@>5^i6CIS}cPHo_{aKiw=x_6yBNxRYf1I7jHZTg}XcieZ>W_#4#_?K35|w z)xN3w6I}xqjCJT2>RyK#`gR|RiHrmvnVa4+CYXaB^^!!{MeSrHf)?b)^8 zM*)0^VUWJb{s9cVE4r2Dp9J3Zyh?T|zW_}F@2a?8+X{uOUK@VC#)oAu1$^5te+Msr z9k#FNg)Lrjr*hnOqcC1&)ADKAsw!+&c1uz8+$L=J@R9Q7Wvp2K+>3B^4OjF{=hdD)&3(HM&Dh3U#!(v0R_f#yzFg@3(tXq>OG_l?N+7Ssu z!3G8^agz!x8(nu=h{+c(zg=I=`Z^Y`IQ1#7q{JJqGHijzwa;R+%c&Fb9eLRBCG!iq z^VhNbT>I95{4VtEfw_xuwKZIHM!NO|#}c?w#iajLwIDPYt$!4C=?4^h#y_xY?n9{h z&CRCL=PXuR>aF|v^d+ng_PjhBe+sKyesfjw#3H3#7>2s#|`-*#%q0&ZH8r?*4#4Rqeo`|OQxK6I_l z=!z}a3~f{IzmK&$167&p^tKo0V)N1%wH}KmZ2co}v2NcZEdB1J%iDEw&}{wiAz9m} zaDC5}Bl*`ZK}-53x4Mc@Xwcztad}=Y+@PY74tw;KY)6m4 zP4Wr$rv6FL*_~s)tHcrL`pB-lUrY$vX7KB+E_H#bYR9@(jb%7eGq}y^CQTU!g%;S+ddnvv7m#)%c|iyP(DQ z%>1!OiqJw)ZSQpL0JN~=V-q!A3@vim^f>g_K}%mH<pn_>U*ei;;yH8#y!aAV3i)W{4-X*UwS*O|0Grs-CsbLVS`nUb0zN3I)GIbjwS^K znqk$)Jg>|?euJ_O3>>Okq@em(-H--D5Y#kP84z*+Kla348LbxQi z>H5h+xZIz2e6y%F6bm$2Yx>q1OWW2jWceh86;Y;Uv~VU~V(xZ*Nwg-EzN570lGh5j zaI@M#L#z{K7VfNe$*_a-a7F(mC0?i!L01tcFAe#4zi=C+*I?yL(ZXfYJFp6SfWV&S zbyy|Tl-^?ME>;zN@16Bj0;?8IrRVksP~M7#ws{3O2m1T?IQw{b?sE3^r(7}oe2W&Q ztq=6ty6uk*f!&R~e6&Z$OaGP7i0wrO!@{pHJ@RWfTv&IKb?$+3%#+H-YIj60t3P zx1hl4%`f_0OfhqC|A&t$R%mQc_p;ZCosegf=UtJ(R?ObA`9=416`JZP%6aZo3I$d^ zG7<{5z|0}%oANsf!PvPJ$X^=RE|Ffa>XG8mEgM)em>a&MHYt0@5tu=cP zwASoV@VHa2BWF+M&wHYrOV-~Pb|XJm{m(z>8i#(sl@<;lx>8tUax1L?HVGzFY=(bNhd(N6+zQT$O=Gt9N|kNU$; zz{3hk{fawLmoHH2ugLIcT2bmnwpJCL(4YIQ$WVfA7pX6?RJ~BZ;FVZnX~D1aH13PO z`ANaVEk2|A+7_8Nj;yFCG4tHY$QrSz#CU0d=freY@w(TA(tb};OB5q6jz+N_&^Mgh zoDxD0^$jbwy|vxgR$^Q)kv0*0Ri9aCL(?gR27QxOW2e*UZ}r)BxA?to*{^T4yGX#{ zQ7n0UFg%$+7s6Kr=pq~^(6TIW`HEYYOKMqZ@2C5&dW+AZtIr!VAAQIHqIGdff#LH( zU-BE~{wszc{>XXVBz|pRm928_dJhBWE5BRbCU+A3xRYOZX`Vf#lXcNf=4wS#CO_Q9 z>kgy%P$6G~InU9C=HurVA)Q|kA4wJv{wrdEpwi<)Ku*Y>LH zZkuJ0PbK$C*RB)DwOlwW)Io9F>Srr{IzVF$n+P@=_GV~vj0G23w^d;mH1 z$z!Ev3n3rZcX}Qvd+>f+sbay$BJ|#U`Kg>wCLqyn`C$L+4XM%RYEjOnWeB+M zhkQH>g6LRE!23;>E_SYK(R;gRx!=-?z@^ad`3z=UV7Re-&a=YLfHgm753bAy58B0_ z#;~s}9f@O$u1d$~a_XrToh^z$jIn4HcyJu_Rd3kE1|NX97Vh;^`?-L3NOvT+fJ8`1<`rvy?g})x@nsu^55+L7@t( z{VPlRU&_S~3Ce?Jp`4t7owreP-U2J19Db1d<(BxBJ-m=#W>MFk#+zWWfBSNUr>1DK z*MPCb>kWA4A#`m)NhL^*KRzUNXFbY&9+TPcU`MIfvAg+kAEmxaJMyUwrM|%K{^A($ z&i$s0$^I5Fe8`CTi`7=Ze4ufT#k4f2^v$eylFKXoG<{A{<+CkHPHkSQYI7Wjq5?}N zlneTeHu?n~cn)H#E?>RScZ9w0J&IAkgE&O&@w zJ|-9;@v05-ms%O@N%cT%hlP{7)~*9B8z$Ox*YqJ4gZTT=y9Ggy!x(SMq9-Vw+wmg5 ziW$guI@pPyb3?Yrs$3~@nvmJf>&xN$*_hcTI$V79WiaN^+J0%*RdA(Lak=~kHk8fA zlqiHYQR;){o|gPUsdwXbyl+gYKWr1J-$SXla%8R&1jEwo_6(}$0bA9zZuzvm}Iu77``%=s9OJQKH zU-`kW+f2b=@cf8}Pt8Eon9R;?fhJ(TQ~q`5$qex6@)5Y;LnRtF*&fDFg z96^&u9aj1>TA-*``^6H&@1lK|X6~lDucOpoSM7;upw#cXlMysRsZWI;glZ}Ep@(%o zh@%i+sXq1>_29?%0`6q!0_@@zrhf4)2Hi`w9G$;8AstTVyR6?z!1t-NgBw-epj4H> zs)I!sQ2wd-*B`l$Ceor_8+J27k#T``!3st!GT9RoI`9s1yzmlFU*icfprDo7>P8gw zK29cJ?h!PRRneCA3PF({tdjI^=3w_OFzB1!1d?JAr574{2j_Gt}m;d@u8w1rTl*k^QdQ z4?c88ZMgDm97zx4`VP!@h72XLx0qA?QPMKm7h6ZypmQr8uQV`J!$KQ9RlPbMLdhPL z-0JRwSaQ^6k+U`*6gYY0VpEi@uv^o>~Sn0b@9) zE*%hlGF*1x#2PTNRiWc#_(>2crNoq5nE^r)-XCSE&j)=DWrf=p)S=-+bYs#<;$YP3 z#-PwwfAn>s)ijiSgCb#N?5WNI6cTYa$pSA2eU4V9k;%qrI9#ksJUkzaS}#v_GI?5j|9Ii~V zXrbLp&(ew4aiLpfSvv78tJzgN)H!8S49Exauoc>@TgEsM0 zglOBY0@vC0>jf9;U>X0GeWkGyZ~=$)c|kokyg*{nGcLC+P()pmX?+tT7%t*o%)(>| z=;aQ*?HgJNaKcVD*SrNlBx1j*p4KGD-*JIwu=G3-bcF%>!SdkK0PB$IXEhMj|Kmpb zls3qCSIetQFv=KV znU~Eu0GeI8HN>+1tX~`7dpw;|pG+UAehujGs%=PfUw|d!Lm2xW^#P0SitTgz5rsn4p09!o&g@ukO;K6Bs4V{{; zKxnI>I9-M-7^PcXJDleW@}GOmd&jjDJRGWf()-yNoh{FIj7>{J{X4Ri*6zs#BUOnF z773GRQXw?q#_h)_zgdvqO0@?)94s)s^jry@ef&_Rt8xkI4~$=HZSw$(JYf!Vl5s?n zip7`jo2>=wMz?Tu`Y_>zbgtg^;E z&EVxxWv$2M^{7e0QV8GCFRfC7lY@cZL8-*c7t8sB!CXGKx@xv^FuLb*fKtIIsI=L? zVPir!C{iq*c(G{-s$y{&U|6{jjlYHa&t`Ri@4G{lmUYd+^!E}^?D*h;DsANl1kG|# zky3o5@5ei+imq7K3_CZ zj5hauTku7;1vIrvcUv!T1Ue2SCd%Hrpn;WBr$Ac(jH`?US)o|WWO}_!a~`?Uhat(l`&*_N%Nf9KV3oU9zH@Uw5N%g;g38bXkyTO+TJd&BY9%$BQ#;nXy`E zxkJF|XsEWg_Jo$*Ijp`}!?0EEEf|d3{WeRW4e@`f6Qa8lg5I>n$c!>PHW z2g>HxRxiv>24d|^-P4axfzb$ub=9>Q;K}))KS{{bt^PpH5d%bRW4c>ok!QMILWYpb zdTXXQF*CJ}x*cp~2)tmBbca$OH~3@!G^IYzVs+#crQZ2XZ~`x_-os?`yy)p%EZ}Iy z{5JLq5{-P_FXPe;+UM@Sf45{eSX8~+dGV_?=t>WVP3ip%R5`*RdA@H9({EaESut-A zGMsq&#&iPV6HuX*f|!OfKNyr3L0Q|<(A>FdN*VhZP`gjhpyf7cgFbVQ zC)M*#frks#Y^pcz1M^j%`i2x5g3&{4N*Ao2fl7^tc>bV`=%!Jeh=V;3Fj*NXwWHGm zGs--PFu7j}nFee#_HkNb#$!^8IMrKFrKXxkE|(s-X(4pUZ*46wzv0B%@YtPF|F+{4 z_ZX$#=h&h2P|SFI)3}paJTSf*TW7W@8B8c03*eG(My9v38XFxKfbQx|QARuoNOJMq z=mLE^aK_%LZ<=j48ggzZ7qk~f)vap}Wr?~%(Z#`4%^KY$?)06#6Q7$i( z-W_DiDDemkxt)uRuTBNk)m6(cev5^o$~Ne6b_C{(9_#-4BMEYPnS>cE%z)CngkHEm zz7IYs>nc2PT!i>oqA%NM(V}kW1gyPt`u~od~W#q7HQDPvc6=6wmfEdE9iADUIsE<`z-BAABO3VSO|8}1Vo$7Lsvzyn|uAdi8eEEEcaXc4v z@}4pD@11~icC4?9i+Kx$J|1{r^2P=WH9NOEeAfi;?ntzJRA~bfUq6J1)Y+g;No&(b zmL_nH@39pU-eOQ_cwu7O-Z3oH!dQ}Q5DwlA?0T9#HwX-6tUp+P_K3kyeU#x_wGq_l zu_Av-f=21*3$D*uoO8f4t3zMDUzY$vNK2}oGaQUYxt`{2-41SAr}uP;DxtLLoEwGr zs=?dsAqhClAI%iW*%-?wK>Ez9G6U1inBH;G#Yc?@-8A#B8xb=Fm+2TkeO+HJgu@9D{;OK2(^hmO^=-v-uY;X<>QS*Is_} z??Uc#NAYu?`(QXXmsQio70~n5rhVFS83w(Iy!3q~x^4R0dVcVHa57i(1@Bx3N`0wIlfwZ@eOD^~X=h4(kM^27&oI3oLz}rz zA5!v~dF*wq3eH_xYRx-72dsMjhWSI+3(9qYc7o*F8$d|Z%e+ls0jj<=$7Tl?C%8X< z(>Xsz3D8n1ULBmH1?LJMF9WMaQOyw+&5yhnK~0Fr3oM=nPPgrHf4*81-4|ICI(RS` zwLJOpnE%mkO1*kT$fPc+35%CJ!yX7~{H~n(VX6<#C?Bk6%8CWU-%}L5cC0g)Ix^N8 zd~hyGEe~Sg8p|$y71g*~Rrw}poL}u%Q-2VMyv~@s_gN8)uKZlsE-49eWWm9Z^?@j$ zbL~*euEmtkQvuu#jZB!1eR6}(rPGl9`L`v*=SwmD2GK=c+VLnymTPa)p+XQaUhd|> zI6e9DWI`8OJ}|lG zW}Akb;MTT zxb0D$TBQ`F-sX|9bQGn2!-MXerIh-$oK6>1DD~5M*?P|qpM%WuPSI~5f1=fzW&J2% zs#r0yW8X{gJdaT=mt7FhDcD>U^e9J(H>~MD9rptkht);RAJ~DQwTE9To=`zA`&S*+ z&=W-ulixg*X08Jd6QZhHPH}^FrJ%2kbCb||2hOVrEuknVAvh_~u8vaQcPqKJ7(Gn- zQY`Er1RkDDH8Jcl1?`JiZ!vXMf#Dx-eBVTw7)(wYj<-m$fE4@X(MOM|8`KuuG2S%# z8Z<{A+u)YY4CY!_b7EdjFuK%6STcbXesl>NRb!xQtAs1 zv$%j@0`=Qu6I9pvZCY7yyk@lKQ0tyhhHi~ zQKQ>8cD^hHp^~?y9xU-h88)V?4jHDSksH@V^n^UnQ;iZ%|DDglQ@Mox$RC2>g@VMU zz|=|}#M_7$18Wahd`_oDa1 z2FG-5*CMIan|qTY1i)Qxp{gsrM@qjWl-JGM&X4wux9dKw+75zWy}vu(hYMxSN%*wT zrxXn>3Uzfac1IP-X_H1O?VuuI&2SO60Z)|bF55OQMgg+bk2yxqgG^0zgSz@WG^898 zdCO7;RUDIGRGhK^6$k2SPt*^BCz=P`+0!b(|He21cp((pX_74j=E^2Ll(;VkMm3(= zU5l&$Iok7I_b{aV{yTf99#}r@hw0#l_|+B4kb$#y&XDzOOqWhSeR28;%AsUOKH!`` z>doqfzrUc=zf!rM)J>^JSJ=cLr9Oo9hU)=+^KXhiH#!vcEi(o@r0yq`7;f&E`{w;_ zeFygdx(&CH-m&GcSJ&^otq;fT^ZG;c^aV%Mf~B=ymn?fJ6J~O6ufA}1%)>{IZj`L| za(uge?JmK|5A%hIiH zZIj-*@#--WP$9t&5~v_S1zG@r46Ks@Ycdc_23V;Bmn7&y3y_dt1~u?Nf&^rMo;L7J z29(J_Ep-5t1ZGGOg#(g0vYJ14xp336$vuY0z%Z_4K2_@4T_Ke1_?HhzyKMDC&4XRAc`6^A^{#+Fopz9 zNRWdBBuMapI-pMiV6`LOkVXr7Q3F&Ym_!0UBuGOGsF2_X2~<#n3MAM@0%IhIMFLK=;1D&C zLkqf)00{|ZPy-JnAV-2{B+x~IQnUaPHQ4hzFhdQZPy-&c-~=^jM*?gl7)AnDv>+2T zAoM$U^DEFo3yP2c1~srpf^Z~YMuJv>*^QU_%S8kU$7EKuCglB=AOpWVC=5HTXme6j6gZzXLGTUyLoAuz9QLfFGL%gxquS&A~dp}+36$~`mR6akSM+b6E zM4m36l!Sqa>-)>j2mf79+R(_~!bmZ5H|9PmSQHf91OsEY`{4E}e547F)_=Q*k2LUK zHxqRu^<-Hj@aq;dt6lWL{M-)6?pUjMIPD?a`AuTPift3ABg-N_QjbP?=goPE*~^}} zNyLrAox^C-@k$$xvaUL}o!$jUnJV>4B*~Kfic`rg>i!nfO;5gV;fKsG7VW2xaDcm) zS0|{X+5NZbcMDn!aK}xH&&SL^)H0Y+KisV}eYUP_21l=0ti3eo9*$OFx&OKK%kMq@ zdkfkKR97(M@#A`+2POEPg-6pSPgHtKv0tCE_sqYVY;W+|I#+9NAZOuYbk~1vTMJ?y)!_OZc(h zG1_(JpZos24Q(Hd$IqFL1YdJoB{(N{z@R5?O$m!;9t8Yd`Kt|W^PC&sOfdDp8kV3%akVeK;8qcVCTGZa3yojn}r9L;jL++he59h-r5poC=hW$~ z<5=&48pT;#ImZv6!AI3W*e({bjlF!78Iu5c>)&a-nMs7+%d?NksrtYx?i%kehPXo4pMFl?!$Za?Zp?Bw&1-wRl3{t z9>e7)?}qzb^FVdaHcocCUPDbqq4n_{3UFETlbbc{_aL{>p7NI-+u+Vs8uyMhe1J=l zF`HlDeo)suw!D+&6l%H@T*1068fs#6E=sQpF#!`A>?PiM;OP84aK(nfYTGHw>o40*Yew`r4C3HethUb! zAFJbrTyBN<7`o1l%xB=LA9rV*eBw~4inMG6e?Dq$mXCNM7z*{r;U+2Ln~?bpY>0nx z5(a;txzOJQ;EG0`bvMf~DCV2bt0wstwc=#slE_`qXp$w=?sP9^v3io8^4b>$f1Dag zNO^a?@)k6`pZaiOd?SeOLqRJ0qS3I{#s$X(lib}DV`8Hc_ zv`#^A<<;93c~9P9MiK2NYu~3suVvQSCs`Lm+a|e_H#t1fpk4nF0fX(3Z^t#d{FEfD zFUbB?4tqexEfU`y%GjZo@d0zke1Ci}wr8e4?-D+kxMDFocQR@(;htW@&IjaV@20Gm zRz@cE-<_W=3<2$BW2?IPj{~NB5M2fXjMj6pESY$Eh9lxW7NFel6*J<4(plCZ1OyBN`UI^2vm&@HmBI_R2 z+9Zb}MZ3zxfn6ftg>dGPXpdMRbVBPw$L;~3$fPdX(G7sqw34s3&2}IayJJbA_Eo5$ z%u>-@eF?Co-m{!IZ&5n(%ywn-S0k*T%o^4z6^wWWHb>nOQ!f45WE={b#i10#%ETu5 z2E@>Gi)BrI3*f>pOV&(!V<`sHRTr{F0Gre0;oufFBrzkdsQ7R`n6GR5a(7P~5UUzx zF7MTX%J1@~_B|Le$Qk--vf4fg%rW9Da%Q*-xW;-d{+<1 z#0OHA*&>BEG(DiM81sRVl5?eBPSWQvu6T(!+&D*aLf&9qF_w~Ayado)UNSi>7K`NE z%8fcS0^kAx@3+YtwjtJ$80)c`5F|Zw%08k_3NH}wx%kCY&|n6cGCkk-8A-HTnY#3Z z0oiVb6FfrOz@o#vyE#JCuGl{>D^Gy^jyf`LK`kl8y&hQDCu7E6p96zcGGwV~sFklYZS7nZ6eR z9maZ9J8L95zml&-t_&?bW8jyY@fdGV74>!-d4c4aBF)e5oCZp9i(hn@_reXT^A%OR z4*+SiTRU_P1Oelzx$KDxS+RZZ1Fp@7FC&>v6>)U>=M1KA887&DLJCsW%fw9N1DStRmiC?8I)7j54IqDzrMQi2yFojX<4Mu2)9@GFNF54xpg$K0VsVp76^Iwx$al@|5lWg4~>l$iJA zQ!#cge?0Mw=`?n4Znv-ZvccPQC$5ZT$KY-1?0V+PSFmV@@Yk*JJy`T@Q?^{z0jSCm z!~M4R2vl97nVdN<9=c23w0vh_0o~OC-M`u1pd_YlzOOGSfi9XMxhFv$`+RqOE@Tp)sNUP%MAX9aRkWzX%gZFg(-kzWH4JO4*<+GCMkapOo8+Y<- zk@j)EXbTrU#F=m|Oi5-L5_g4LWlh!Jtby zXU2YjMc2||D8FXhW{bw6GqMXX#8*GeEz=PA#JQI zAujqn%nq`j%3ZgS+aB8P!92$U9LRRvcyjC45-STBUz6Ogi#cq6+ zd`=+C;)DO)kF+4K!dl;tJ+_#4%R;6VgQd_X^1`~ek5u&jr|Uo7LB^~TjG2%(g=5k+ z;wJRj8>=DrLIy{egOt5(p*X_i){TXY7a_}htB+S}FJbp?OeouzqDcmX>~QnSb~m z8rUHk=yY=oy7&$F_j}&Q;f>E#R;6#p;ZGL%tlhZ;!;Y5qTgw(>#`MP2%et}9UEy5i zW2G15dFuW3{4wkr?vePQ3>l+E1RZNxD6bQD|MNHJKA_g={9PZ8KjiIAk;dVLjW%(m zo*1s3tnJIknBK|C^?{fqbYH}4@XfDGH-tRmuchvmUrP+lryn(BJc9JrsgGCQc7pCQ z44w8VTmM^4M^{AZ!&7v4EMK+Y@Pq@VPDZaW+|Px3&0nD@{-C4xie{j@xyYN=Rqy}a zpR_RyJ9L-t@DP|{XT4`MPzc?P*RAmQwx~FYRQz{Id7R1BIh!C3Kh7-s$n`#6@ycqS z*b0okPR+0Yga6r4w`pXyjaM{0jBM~11YhmXdup{rLHE?XS}A3; z=ch~EjVy6^c3hxp-!>e6jbG+KVmLO66MX1<@)P=WE~9PboP*{Nnyq$>fsf8D#R{l%w0N@j2Bw!_&a<@Y2}9@bONCpO#Uv^{RfWH*7@hH&+JhIr~AFYNhVFV?Fo~(k9gViXOUi2XWpJJAkdi^m2|XrGwAG zLbh?6%TdP$-qQ=2^5F)f8V7leQq&*mS(kG1Ep%sJa&+fdKHhWZOAh__db}rV>lf}w zZ*1)Rv9&|77c-0=G?dxd1N9?JY;3<7K_krrvTs8R(Ae};#O9`2=sAIoJ#wzY>kz|B z?$J)jkj}8{K+JropJ98=U&9}opXjPmjQI+_X0Tp6eL4ktzIW6+ohyhV_+5CGCRXAI z_ENcnE8b#5=9o*Wd0LqB7-w|a2YTpu!2Y)5dI(hx?sB_#}NvT)9_hM-y)OMb5eXZ(@S~;?7(9`YEa>HPBwn-5VuQYBg zQrM5fi?@3JxU&!Io!oY3U1mOJxKYoW?e-D6EAh9BwKHG=kGPHoT?>#Lax%I@Zx1@C z!Smv}q9xYtGEa#LwSx>v42A86&!M~2uxnTa9k8?~m~o#~SC^?*GVZ!gRXs{r0w&&|S|ha*OE@UTl9zvbkz5xF%Jg z^VRMtI>+SJ8pJ{QLRH5Qn@@!;q+3eo&6d6bx@$(qbxLJo%_jSv>YA76nts;4&7VY2 z(n6q7UtEsEPlxp7^B%(CF;Zpv;R#qxgx&Wsm_d_<2k%Xw>N4_x$(wq5JbeFG1C6 ztm&?5qs8cjZu3Vtn43zYJH8KH@3QA$IXU2bU8o0)S_X9%goHr%>gIAAm0ql~*jGW! zwH4%8q=;rM-h^_KMcwx}P2lhcJa0A{mE!O_shLxub=Y;SUk0a0+<63K)EIM(%A?WjcDe$Ph>wCED73iuMc-urd670^LZmD@%0Lrw*Y81`{ zVOK@}NF4;xPWLT`^Tb9_*;)gi-J4zkPxfthuI_vSJQWA*Q za11~-^S0T?r^dr=jxBqbjN?#DU};ZhU?QlI3{btr7z?-RCU0oGw+9^W71VOJHvp9x zd&Mqit-xD#Q=~ubpFz>PNT|8(10~`u_{=!=*7nN-})}?112`TFvuXDzrL(Z`mqgypWnTz}Rjf~5nMfIbeWJ7Hb zU@}yG@;CsuhxvMW=dHt(^_M)CYomaJEYGv&kD=TBopmFAEu|xOpE9Ku)s~I~oEeps zZonqC1qU}g=>*=P{Qt%q+X!1PJ@*>@EGu)t8w%} z_+V+%`L4vHN@q$RcP+`cXSTx}vSF>KRU&}mVFu}qW9GdDzb^1C^U|JEu!lQtHADXY6i*N+))2I^JkEe@Lx~(uP6N16aMQ7 z|Mi6bdcuD_;lG~nUr+e2C;ZnF{_6?<^@RU=!hb#Czn<`4Px!AV{MQryzoIAPnw`{T zcIFk0pHG;L^4~(Do&O)53WZ2rG>M8TEfGnGNI67;A<_wvJc#f`1S=vm5rK#ZJ4BEn zLdwr4@bibrU_`zmvJ;Vuh|ELe86vCv+MAA!h+;&{A|ezKkBI0)#2O;9ko{>A8IiV# zBt@hoA^{QUhDa_%Dj|Xy5xR&#MT8|H2oWKN2rx9^gespA*^9_kL}nuL5Rr9=97ALj zs+dMZFd|;jL?&jfiDLB<5xIvXGl^J7L^dLh(L^mGMo~p1 zBL0v>Cz0-Gk{glAs1g@VnxaZdL<*uML5Yw@1UMp`Q3Wp|R1txR2t%|4DUtPv97kj{ zB7ae3DMHWjS)$UNKr&Wq9t94 z07w43Gk0hgMVk8j}iTFoEJ0iAG zMKU68kwi63nk14UkphW?N2E8ZWJaVe%5ku{x=<#e*)fZ8P;ZC)JUr^{J%8K|{dt>p zwtlwc*Uj0AUpHq9cxZF<{G7Yz=PulTPR{dl1@G@!c1R5eZF-%b1^h04-aa1A+x@-# zcFoSY^K&ITnONs%WA-j)X9${|SLf%d*$1Xg_VaTM-|xqvRdN2Fv*%}tz@LvqE8?I{ z*z>dI*Qp5p7uTjok!`9`H!fpd48WX>KfrcAA9z^ zQ8#eYP91f{oL?9I?jC_&yIpp9?e_Tp^=E)#x7(dX4e8)jbg&BFumQ+gA6+x2eg}%F zSH61F`XI9VQ5C6Cd;mmLu#P^?It%<%CT`3e&Hwo?`|}6b_YA%N^dk((^pCA#UdxZz z#}sa-2b@Cm0a37!-yP9ip?_+2rVt3|sq0&X(j)ygxwP+(OfK zZpfVO&j-FUIxhTh>lo-QZao~DO_}9l%v;pIy9>QAU%71^YDFzWpSS5`r0K8trS+ke zFLU>NW7-bX`6}cloR$Io9Qv&G$XLMs%qvTDl*8b2ga{w&KJn7lym<-{J`RW{N9ykN z!u2H@zm&g!@4>&mrSk7R_?J%n?>+dJF8qI&_h3}PzMb#9#tXDFN4w(dGky?kc&Sk2 z>m?L)#xA~QlO_mUT2ihowh;unyDgAQ^hMXzB5deVKY{{emT^vXJ2c+=>4(F&5Ns(? zw(`o0E!fPD5rkCB;uUSW%8v)^v6lBawjPZPyfE#M-wKWQQ1W8uk=l-BP;1KQ_~dha zloZT#!_-I`+?rPqQ?8Q7R?IlrgaU8R*wvdI1J>X79&y^9gDj&aZoCQ8L@QQxezT2n zN7A8fr@_tm(jQH}*-T-J(H3_&93xW)Je7-NX=G&TH$Dcg7OujfMn0ns1In=QZ>GyOX;(^6R4q+z4$KrR~R z>21gt=YcF+yO_^3d4Z|w$6A}duLk8yCC9EvEyD}}-^-f=s;~h2*6r?dgt7R|O!JwP zb5J!??J>Q251hAxcY~ld7iG2w7MvDdfSFZQQ|&*0#jKW%k3)H*Fpo#W$#pfpSTJV7 z$f@TM7%2{r;8T);oLAPHINCl1A46N`=(S{;G;Ib^)01?0$Qx zP7m}9F?@-**p1$*HMhtM#iMTlksSMFQs8PKC12NO3v46!Y;0q(H8zj@l;_4{OgaB! zl@AQ~DCb{llXoROmOS*l*lgu~C~x=RsqkDTsNb@y?Q+q4^f~{-w%Rp1P}=mMGTmJd zFh2LnJe!=Wn8n-0i*4W(ntC_0@9h2OsQiN9`LpN0K!&^DS*%v5K>jx(CPL2g;B)4c zZLJ;oSlWavX;9RMo_+{SIMzd!{v&l9`xUGqy*0wL50Du6UF5 z<}~J6y|+NCg8>U()wXog-buLxqF(F&`wT$&wDIpV!2cgU1I%@!%;oCuM!Ed=_j9I9 z;_miq+S6H2kCpNZ$OBGL=U&gC&aIwDoooHU>>TT&pln&q_0M+>fJYp2>Iz?e0#$7; zV_|fzgxDkW9UPaBvc_G1PSd&$UQ>g5u%O|ii9>KWNQgp02NKecPPhcqm zJ`sqC07(QcBB0RkJ*kgR1*r%WMF1xPD-rOBKtwc{i-1{F$co(W-|*AlP!a*X2((22 zEWLx|9{$&t1Og*K7lE_LUbh#OrSIxU`Aju8u&$pxCoF%g{x@$ z{{q%%@EHNg2oy#DF9K^(!7Iv9u~Ykn*-HV^nC%frWA^1v8nb-?Y0UOfq%qq=k;bn{ z$EkNc+dGjhT0hSOY0UOa9Mm%Eq~oMDdknN~vj;(I%^t;nu4#7qxVU-G&OZKs{+fm` zse~^jtSI3=3ByTvOu|+YR+Vt4gdrt7C}BGZr%9Mg!mtt^m9V9R6D7qJS$;S31>=}Q5u6wcv>nOOE^~=vr6SpX)Gy~%_W>IVP*;cN?2CHrP3HvDzi)D zZwX6FxL7LVO5;@tdrD<_371P4Tf)l{_LXp~gh{2mV1Hj~%)Y#SH~(*aP4k}~DFY4AdtTl1ki7!KxQ(!fLl84_TS3jYz1k3e}e$dLex1U{sKgaisC zfFFVN2>eJuMgk=gz>vU#1pFfqAAuqX;7DLa8hA(`LMjkQ;64IN67Z2gj08v|a3KK& zY0w{mC`40#_1Hl0c6HU?eai0Sl>+;Qu>%kl)uJvsWws=Xww- zy+}wzLKPB1kkEdF+@n!=RH~5>ii9>K9SAdTju(vgI8B-A1y5D864$Uqw9N2MkS0ZC{^LM9T*kPw4}{v$Lc zAtMRpNQgy3AJRxdDiuhhED145=tn{_QmI55VMwI~34KXONp^FO z>&@TCPl4`ZeWjk)2=0WNj2buZ9tFLC*P4v4G7lwb!OkQuA)6 z!eP7gm73`os>r4+Tr;zrv`J>xqUQ6{2(w;+fSTnJBi>XJnwrJ5dh%^sX*Al5JqNr>Uky{sIz`=W|Jprkwz?GVW zHi?iZa2t@Hqg5jTJUZ+OIwDMfr#(i}_Z%F zV-ql1TUOgI76(2IBuX4g><7~|?`ciwOu!6&LiIYt1I%Qchaw{lV48pNajoX>VASeC zshdbUTI$_idCK1$Efo~Er*iK@OMIh`A6#2RU)g>;#`HaNczkO`RqABy^Pzk|?Juve*(5L>ui@Qs`cQl@jL73Ut+A`R;(w^E3V6n?OUA zwG{@71JNu|#hzsI)Zpww zF>kf6+T{$Ps7?(p;R;_AdGJIC$AwW8-W#|f;anLCyS)5dg@+o2!G@^B*Cj;!kxBQ( zf!<9gk=yH=hpV<`Apg>Y^cm@W=+wURY7#3K(V5hhvMk3v=ydU`P^zPw(D9J6tHyX6 z0sqiPpuUcP|F^M(=2ry#7rmXoMS^L>ePPgx63jfHKUZ=$lz@MZ?C_;01pM1n*wik9 zQEOAZu#_DH{51>0Gp-Zxf43)bR0S>ZZ%$q>?oPn}Dd)Dp4+Q*+zYTHu5b!@!knKN> z<`zrENJAyj)VU2!eCLV@_-6_;-!>)Sf5P>}wr2$VO?%ffb%5nu?t3x^^}#nmn%jPy zqXhiZ;0RkA_#E3WBR?=?-KhqBckDiarLQIQDbODEJ8mw&eajfr=XQrwzW7$XSN3`dnQH>l zy;~6v>@~o~J=$^Fl-h_Yls)Cm?mb9t%d{4AS{1O25l#E(Sq0b!I5vJ&8(Xu?2&vv{ z%&giR^AXf-e(64@yB%~)u+^Cc>VO`Tg?=@IQ7~}!Qw()PCK%ePY<=*HEf{$nZj#yh znP|14ZWza!VCOLhSl3NO?>iM#Gxl68c9K;bQEJ3iLm<3P80o(_=Hx&6b}(e)Jv~w)(_)P3jStS;%sK zwax{6{gxiQU#1U|Rd4*ABF&3v?NP0N*qMBNh!l!wr?8}pA3-TaBBmbs%qWZA`UbO% zKDr44vnY(OpfnlZrr=79t}1PO<~(PB0=8Zu;cKU>-m%sD@WOH~$nQw`RHH8n3P1kN zmwAE_W}}XVmK^&1L9S|SPi@tnm!(2S9;HDh zy04@Rg8Lw|u+*Cqop&Ksqb%JuF-5|Q85dMuNra+>^zfHjL*$rk|6y6zSM^xfM@055 z$D8U+Avfm2*9U?3E;XAE!rZEHGy-bx?(gXnCTpRp&BjvA-Xr8IC=)h~Ncpo!D-PR5yT6PA>*h{cb|i zB=*M>%chX#nJZtG!C}Y}cmBrHA|A-0_+fd(Sh#ve2Y>p)F#^gjP0}Kh+CWO|#Yw>e zBam6MX`8qS709~BMB^sy2C^ZmsobtkaQTXh^C5dDWW!K*T*YFiIt81_(?p3UDBng2 z0mnd8*mddln3W~Uqgt21hHOw;$~%$6$}7nKeT=X-*LiT6TqG(^sddeoMO9t*#SYuc zS%Z*?LByYgvYLRus^#4eX9)QFb6pl#0@Dmt>$=EaqJ`YL{`6ji+4e>4asE6;v~*FY z3g|iVvL_I{x7llN>9CuC{~MLCW^)4mhZwCZc0h*lk=q*c%aCJfy#Q$+7ZiBA6$zG~ zgd#L%$*kL{)J+2_S*#vLq4$=pgW% z4P$|s1F5Jx8;kHuwbC83BmVzE>dCLgWcqaAt>ax`-M}6K{-)LxO{|dgN)U@j3J0X= z6HrZXu7@nKnJ_DyA9Bbmt}}W{P8k1-gz}T}{)>e2A0VOpGZFpY7XuLg1E}yt^WoV` z7``g0Zv*FUgRr&?Qs zO-e>sM@=0O{c{fF`za2PlwaaL{k0JYUs~UHHM|(Pnn|Q=>D2({iGh|n^v&Q9=Vy5H zDJSvzkVI;(>_q}2B=@W0eCbpHNsrUhkKf|~3loB;&mHRl;}b8`b@#kSt=mqY=gUw) zOO=nJ)bQSF&9yaHgV+xAOrV*x0;x?)tTq8r?8 zZz^y<6^d>uM18$nD1v$p(ga7}mF))Ahod#SE~tuF?jj&bM4){9Fi1-tW5MGmtY zt8*;4{p@bSZqgtSsx2qm_T&OeJ`zakACm(dsT4;YgAV}IkfPFI`wcZml?7bOFa(`u zVq;%6$3ad7s(UdLWRO`?f~<4p45YOUWIwj87SarM_|>)+L8d-uY6DV9$o2SyNB1RG zNLxO^E7Sc5eS8u0;Z5!ra88kPQZ+Iic}~S8aq@>EdygYkTkN66d^$_n!*5f_r^xM+ z%SkO1wQ|uyFX}Q#Ww(4>l4XM8j|w|s=|M~kqt%8Hk`aQQw}%H zHzdb!hCun>=tT~#ghJ)RuRFQb~X&k}eQ_{@2%PVG({sEId zPc{Z4d6Bz#3JXxf>kV5vc21*_E8=WIv{dLrYi*;*vt~3j>TJ6qQ35S^M|$w$H|T@= z#(3eEcF@!LNohy!9k^p%m+gM@R;(DMpxCzV6*kl?zIEgZ2{zj+zi`IyD7J9may8Bh z#12W^&pRBbv7J1x*Vf|oP<|NY0IfR^w1Sh=?| zeFM$zStR8y^Freq28wEet*E+243|{ZAeMi_%`*Ek0)vL!lw&rw7+f7~xa$>%HI03B z*&^exu7~-ZpvH1+R%Keu$LN8L2gbX3jApP#$mITn^&7Did+T22h*wZ%n(V%JMi5kj z6MHMvjiIWZSK9~ON(kzNg9KSJp>Ac?hzj}uwWBFNeu|!l3U5BGpn?Qc>+jv<{UsI* zb?2)i&5huV)rSPl9oxY}1=4^?%MNriIqjBsUohzC;9c+&okoiXOOF@cy$|x3)?M>5 zw!^et7ZM)&2cz*c%BBr@G@zl)E!TyR(;7*-LmukX0VaQ2j*r~s2*wt)hn^m31rs*c zZF6ULfEkvqN%699=;=XHqDjXHwU;F?2{=E;it#cE<$CehP{Y#qT0tH*Gf~33kUzFK z;#$qpyazi(T&1~p%NEwnFeqCNB7X00ddpiCdqMKutZ-5t+)} zP}ez&ul?OyXjU(@DO-338ef=7e?(2NYkrOL5S18~FO)x3daMnD-rw%AUev@Oqy4>P z`5e|XFq&ARXvVq(N8c^|HrVWmSQ@lc#m2WwuLisNU?8rOdL^#~OIhS-C$^J8S?X?^ zsvA;JN#}K;_=GA{)hfv5wQ+% z|E&7k{$E>3NYwJbAE{*dd&~EIpmlwHrd&CIO)YORgDTW-lNvEh z@`1+7PanjMZaJp|S$uz=&%fH=Zv4IFzW2ZC@$Wfa$@Kqro=Umz{jgGrzsAHa5~%HEti9=W z0MtiwjNF{hq479<%rYM@G+Q)q5lkqDR=rgQT>LT6qUd1f+vN)wv(<5(;GBcEdG2d#(rV?JYwCAn-0G=?d-MfRurY{t~P+>KffC805{#4rb+Imj5~ z0FH7eLAyD+0~yENp>LF%2OemGN2k!Db!I;dkX*jf{$K^3Kw`|MIyNwvChw+N&MfqA z<5G^!7=k(!`F*0nN<=?jeEun(>-cg5hnqDexslrANKI*#t^VaWW@D34UCKrrU-J0e zI>#t{QLN*{Yz#kkPUi^)?>K&rf5M!j&vOWe>q)-jzq%1e%1~C!zW9h^=$D#aob?Ff_T~(NFWkb(`q6 zz2>t0!(E%`s!ep$UUSj@>C#Pf=O(&x|8V18bKxesZ+~~)Cfw^!Uf$|2`{(ZJY#3ZU zz5P81ViN)OzDHM&{2_k#qu5ON{`ZY~_xD#BR?kM%7AHhs=bAlDqv=A zi(+7K_MNgB zefjw|u=v(+kGt>2T296oGw${e(ix7!>?KCCLDHKrYuSZbL&Gze#6fyEz4aLw)~eq3 zEMfqX_LBRW%JD+_kzJ}2v2ZOXlMQq_zhtwL*CVS}_Ll9Y8c4QE>U4SMbD$zzbazv` zBU0<%RlokgU8HswPrPc1*BBYwp&)sRgjg2=@Af)YKa?l{y|{hDSN9z7^o7unnTRzQ z;0mlLs}2A|EjHoW4Dn#(21}Ajh$$E=@z(RXU-`W*Vi}2q1gMqXN7VzFM724AvtB^e zs#ZH5J+5w|%yw%Txg%KY-D}a*Pqx<$nyHu5BUKMZh!uBEQ`F z7)W8U_1OFKAHZjsX@64`g&L;G1d>NTp~-_!YFYQOqlJ&NXURVoqWLrZ?bEd6#JUKi zG@PuKmL3G77K;(<06AW#m-9eC+LrKgt4PMCq6yUUV)xlx9tZH6@i#56cMIsXv$4GD z5m#be1d9er_usyM4RdzMDV_96#bn1V4Q>u+L9*!PK0Omk$RmABarBElwMctBX8=v|lB8S}!hO35lV@cddJ|+-aeBHicv?#)7$8eUmV4c%gFFmlu%j zL(qNQK65DUsW0S|aE4eH!F1MV7-Pg)p@d0ag@1H6lnazGD*b#Nic#9{?DErxw1=rb zRu(d1w(f%iR$mpd_@Ssu8$)tpT?8{Jk|bM9YGTnxmae5K(OBL-H@y4h5GwK_J;iEf z1cd_pEy(#Fg0}_yJs)KHA^qh+iib%qYju%RsC!vRxiMq~Q`r9g?g`0W^jTu3!U9Py zXc*d;)hB8PCJ!Y=#kQn@h53==9PQ>{K907cUi%mvxL6%QtczgLppRTTol7w1hxr5h;Su%HPS#p^Uyj6Ltc+K$g*#%}$WKG_OIIP=lxRZ#=}%DH<4W=MRApja1k>4# zNFMM|fD&e>-R>mIL%Gv!(aM%d1pEse`a9zxt*h=S4bg1O)#x_RO)d0=ymfYtG~HhxADo zaF<5~db6{|=UE>c=qT2u9B?~?TE1Qww2JdZSKpf3(0-c*rB-T*X>ydHpu**b^aCSM zsBGvQRj-RG#cFez?%lxqCGvx-2=!SDOc%E>@CF-kGDc(vQ$f>dvE@dtr|@te&3aFx zL3lvQp7!JANT^pnhhS1FH1+1s(lmMtx)~`QZ}nxMPRdRt|F=FU{K1l<4);8$U3Z9` zY~=*Xxg;C1-tvCOG)cB@c;x8+?vL-lPD%SL;??b@jVUT?eZc9@k7tjNTwUyiawWle;~ zx6_BPsEf$5gjWNkWv-=iE9-_jrnWuF*)EVqNmOCa?sB}t>-jgmU2ie8eW0wVz=S0~ z2aO>s11uWGC$^9u2^A0NAJO)RhBU)FIScgkp`BiIxeK`=c8qiGdQifJl_}X>Jnqy& zot;Lq+sw@1PSqUho|qk2q@nVLl$H?Iv)UAtt^1x@=T%=u3|#{qi- zLftj}aKOIKg=5$pWjM%woN9Rnv0(QU7%|q!B zge}ReZSE$fLEE9BhwRdB*x%f#Rf4P+Te|fL8{VA2F2bOKr}_yz*Y|Cfm%;#A?AXk4 zruH)S={WZ$IjaylcarCK@rI!#3zdS?O`=#Q-_X5s;0&hnUJ_LHQieMYe~>!$nG_Pd zfO6LKreEuy>=(D9-Q71^7o zP?<6yrRX3N)-mFvbNEDscS<)Ha?UhCk+3a}XFKhn=2Jp$fMw_pDnwMFY(Q z>~}{x6yt#XeY{UQKH>n2h6Wmw8feBOA$z5f0y-5u+*W?y1v>ZC__~{KhwizFQWi&* zp~ahANkOC2*zC+q-!?`@7?9%MWqc+c2IwY)bE)0KX0|6|n;R3cQ?=fBi2Eb#TvPEj zfsq5dU*S>W_Kv`ol*}28uP(rY$~6|(A4p(->qX`a%~#m+9*Tw%})|^iPq~pD3&U#t>(XdJ3j0>7^;x?FCa4%yr@ZDqu2VR>r_F9ZbXo z4Cb=*g9&jClHy|)si(ucIW(SM*sR=G+ku#8 z+Sy17jw3EEImzrmGQ>m~nPIL>@E{i-p2 zTPr}dG)808(CJYNcVf-EuH-NCEfPe{g{l^8 z7Wt%;Zmudm-yI0&^h~@*L<}#6bIy1h0Qg&7j%#rMBn=0}Ib0;#qB}?YO zT!_`4mbPp#ca}=>x@jwzi^!Mqoo51bYnsbz)Kd^Xwsa@!n+hoIa^ikVw-q#)2b%1U z9|Dh(|JbgA28EDVX8--5rjem3kM0^EYAzG0r`d1YXf*xiK>cLI%=Y{A1Bih zMa1jt>VygUymkVelt$H>D&k;GbD2mzMMJq%@?xVW(3nr2h^cqR80K`ZxD z*l%y1V{+j~A-WYcm~4>MH7Qn@sJTp}o`Uh}J%X>PqQG=h!V}~8MesG?q@>atPDpk< zW4pmOTDWf9BKr*OUbybotk7Z7Q*cdl`3Lp%LbYj}VlimG8l%=Z#rD3Dw{=&1E9>6otolAA7fD3Ke&=GMmZ{qXrA{aaR3&;`~vA zqMTD9-F8${Pia=A@EQ>{m)EGLD0`ZcJCAl8)lZb@rFKc8O3BzT&kqH_nauaP#?=CF z*O)E!$nG|f*;=+&bw2us=JFc#6m;7UDQw6k;NMs;^QK`7Y9gspb2>XnxPHvUQs6Q$ zykoomNuwhHf7_Io9f*Mcs^&70dioQ8-`L$|=JyHsCre3`r4#TkGTs&Tje!5)t3>)w zm~3E0I(%N6sJTp}o)Yli9sBNL7MOlSamrTMnt*>Nx;zz4!2e+1v3N!T{vHu$vrZE5 z?@yhLJ50boZ7zjPfJi+>A1|hmhRNSTi<_!4D)e__(u%O+vsV*-;(yWRv#owCCJoyY zAuvu!!2fr(NcNmH>S+g1Wt1~XcN778=Im%*d#pp=9!E;WtwfQN?g8$|mYr zO$u;}v*^6<6blYF8QSU%Xs=OEm#{$Waq`iJqgb@I{|4Pzb-Xc$N`2N?8namIQw&CB zf(6M4Z#waA$eOs_&)bX|3aBJ|7N%scQBR|Q@lc%`*JwQQR`%Yh7Vm@(jD8XMxUmQE zguNUSwjV-z_i{Tstwn$o(x&Aet+^L{|5%m{Jj7G literal 0 HcmV?d00001 diff --git a/examples/Cassie/saved_trajectories/down_jump b/examples/Cassie/saved_trajectories/down_jump new file mode 100644 index 0000000000000000000000000000000000000000..fce9a4ee1d0958f21ef3fbefe4db554c4ef8f555 GIT binary patch literal 52477 zcmeF)2|QKb|1W-HW|1)>W5|#x%Cr^-lQ4uOdk*H)ygJErvF`1er z5h0lsGW}0F>wNlt?)^Rf|Hr-m;c@>rk4J55o%cRx+m3biv0k3b?vz}c#1PdkYAPx! z0fQiK5d(J@5fK#;B}I+(${MQ5BFc)&D$JxCskrv+-y7iV=jj+6{qvz zzPqdUK5u_Nkr3w~Z)X=@_kAMHer_WBf}Mli*LnK|><<>9?BPwi(ZfGTgnU=O_FwDb z?CQSJU0qpGMR}u=n~Tau54VjTsvDJ+-8Q;9$`DkP~-=F?+NEJXzWjpz>=+_0ghuP)}|*r?5+UCxwDGa{n8xyPg+Xv%x#L z@pI=|!a=)``olBLHlTy;aA$OrJoq?Y;o+Bh3w%02^CPE_19bUIY6$Z;f^JX4BMC=i zKo6G|^_g1^pcg5gIMJ*O`g|mr!e^F&0lt;72Swk5ua)ea!N&K%H-DN$zkSERu)x$x zuPZiS^oM+X!scyYGVhv?am6s0)7t;U{9PBMO?VQaJ#Yy!5838j>fQ}G-M1!b#h-`V zjPa~J8|xuIRj>R$;d@XdGuuC>Pzs7R3tqpoT>`F*P04;)P=yw>)$CsTo+DQ3iFNW0 zA0~K%m_OWoSxKayTyiw+8*5Gha{!@aW-BJ4}!_1ms z7P@%wLQgTlDYufKS)N01%WR{1>>^0;@GU+Inu}YOPxyR9xxN8?H_o3$ z4F~&`7vD&uGXL}sZCeY$i=byk$;;C~3;l+A$HF57U6I#n7^a67n2ZODxw{FmvzJfz zJ4_KmZ$6})Z7RoB@DtQ0 z;*uK-H==p(%gddi8k)(eSQilr&=ila?wsp98u#^c_-VWvb<2q+hlYiL3se=7TBZr8 zxy9Hl;l&n^V|%_xh`SLy7kt&~@^P?B38!J(R-#KB%xjNMBLiOmvMR`bfN#W-W zzms52U-&hzT|N{W`fic-Lj?*k?Ql-#e<*W0b$6ilqB?JbJGQ4X3a zuSULnkOjW?j6XK8iigw(ves3HQ}!a76yg1Xulg4IayHb=cW+}eS}9){&XYn29@tx0>Jp}tW<(`6AT zeLFE+{;?sUDiigt9|RM|kNeKewtIp0OsVf$Y|DwwL1!5@@3tURYp2Cm(a;le3r@uk z`|lBJi{~P?uZt%nT$m(`l>-U3K)$gXwYwq9lT6Ml^Wjj)-9wr>%?t9-2Wxnyz5}Cg zy6*`24G>(%yxo;(3kYdL&MhZGz7blxMKW&j*OHFcQF&Tt8Nq6LVs{VKNz(CNe#PH8 z53ScXNqhA9Ktt{OyDWX!p!E5khRgnY303w;9sWnl2;+3=tC{!Rz(>>7H4Phvh|M;S zT5LGd2-U~BAtDZ^3AwNAy8=f(6Km672f45vBqX+l@1R$ZAlT9$b@iI^K^9Af%7D)G zP{m7dn@3SC+?WvCv#!t?>b^_wOuGIU8pg&Zl&c1`c~;B0Jpy5yscpR9GWqxazoZkXza(P@<7`GZV_dQf5SEl zw}40QlTr^t<7EqyLBFgIXtNIpb z>@GF6uQdT~;s3T`!D~0%qJF3B*$NK0WoEsudY}sA`A0 zi`a{6fc}>Fc-nW;1mpIdi!s_3gmn8c8s4f_Lb1?q-NxOg;mXezRj+L>K@C$bs?ke# zq2L8+h4y40LXoG0x-{N^P@ttV^Y^bOvNyt#2kPAj*<;a*Wo_hdz!TFI=#{Yh60zh0twDE&d+o?d_4!1e2f zFy{mRs$aUFU)}#IU%HwbRU@ULAseEi(q|5eSo)c3E#<-z{{uH*RC z^{+B^@4W&0efPOLk}iGrDgXN7eqBbf1_kw`mis z(dW)>+IbN4mDK4wnFT`WCLVhJ3|)fx%HeL_ZdOPoFGua_5dbCms<|^6+z3|s6Ajxl z*P#BK*q*BVQ7HYK&hbZVAffl{O~TbP;e=k*$z)ky7SdxgnL6)vadUQ5{B zvv5cFkP@1EY@*GXEC;EiWuNrWcAEzCzvVYX`8mzIWA=T?%PD%G5 z)vp=kf3Zla_oT6VXkKQ!!`E;$)=x`CkB4Vxe0tetc|Rs@KS6CR6XPHuHwJt^+6KX| z6@;Zav<<@~Dw9rjXd5$DF7wL}!?%|TsORk;zFVp#^OAj`i+4_2_x6b-n{#2>itMTl zY3_~Mn_q?$oqL>LW>obpCALbvlz-WA`Lo?;HRl+YaX-yoI=#Q{3yduA$$u$BI@6&E z%MTgf0!f0IOc6m0<)1zR#ofJmC`;At#!J~7NWi?yw0t*0RkLEQwzT1dKkO(cz%0X?jlbhBE>Y~J*y1||tDyZVZZO7jz#DijgRHL2u^SS@rKLfeU4FAJ=P&f{F_{G(C?dz(RG;1|QKu)O|98KEYxW z=ss5H)6wLL-qIdOKA<%SMh1+vzBJP6%tD8}wSA=L&-HU@yUK1r zs>_A7hnu^G^k=2(;?X zA=UT3-G}&*#BK|PY^i=otM>BFYOMocU98&hn`J$K*gf5R$%h{CabI(Jv0DOlNv#|I zv_cb|YmQUBJ$VQ{7kM20;M5PuaM0^VChI;loK&~_b5s==jvMrQI-i5OY^ABy9j}4- z*tQ|FoX_AnfA)NDdI_msAy#QH84V|{raJK;5DdraZmBYPi@I!92y|b(3r6nieK!c= z)R}LwJzBBZ2~;${8t2~8T3*YydvTJ5WlnkA;KTh0J2sC33$9jgY#&-B~|+)_X) zzxn15K_5u<&C+QLuSoSt_c{1qk?JqeZ8M%B)sMC*ox24#>q^%aUa^O?V-n9DFS!Gy za?L$2ORPX$5nz1HVL`f(*IRIiDXtm_=qQpz(|SnAk%L>eyB~gbG%d*W~sdHe%pG z2`QRBhv=)&s)8B^+m4Ok%b5+tx@tL8TzZO-7b!y-A6UYfWp;y!^;EfgCYaD-Af4)W zY5=K^-=KYSXd7BM%JbMRF$NSr+9hFX`xIn!3|{OL3L@3>jCr<;lIq3k-w=hQ`U0am zyZfYi+0!*DwaB`CC;dzD$6)Tkz{*$RPmx5_gGkwV0nj?EwziM90&g#onAlHM1+m4RtMn z+1>-;mUE_{X4wB_yY@G*m?FA1SS%Wib;>1`aP0wOZ`U#cjpe9jyeY2bVJH~Uc2GaM z_D6Z2y=*~-dKqXab!De+=tp$V{8Cd5c_^8AR2_4y>(CNDo^kzPenA#YD9#2aR_p*vRzD%o2HSL$&=>K{q7kF7~xccAjFMI(3cP?Ak3$?rAD zyprqA;4uHI{?`ixsXo!McxMEuK5C#oc8pZNndwAF3bJv3pde3rqu6!rMAN|}e&iN< z{rabqFTwko70KW7v&sirorAd)=o^u+;MG7%*f zxOl{g{y;58AK3Xa7r@uWQl%Rrw1h;NVCn7GS!j&?$}O&h=U|K;RF&j$fVuwM^VA-? zpv3}cv!33BzAhe?+c)V;NR&3caMX)MV_eoMt1otgF{X)U?0h{Cr_>N;agqB;WBkCl<}hSnc}k&rUi|9zI>A zwkVTMM?&4)4K(nsJ$5NxoK)|3DSUVtsh;U|JM$q@z3o+*D~%}PkcIK%fvv>a6&pB$ zI`hDxpl31xdqzR`kDqHonlFP@#QhiUR~^ucE{}lHb9cad)q`IS+Z%!JVYl2KSl%KO zU#?tkXH0;%ecCN-5hCdA+k!Mp$1=#?c;q?H3rqCw%$en!CmqrEx^=pS49`jRK^!l1 zY{5Itz0~tvYUrI@{x0wCt&shtit{-|T`)8mTDv~#3lh_xnq|4|gI*tBJ-^F?2k>5s z8{bt>0}3*EOkQtXj`-`IwB$GNgB~<7b*&)-JxHun^{saR`2vf_$|h1#-S6iYK~-~_ zLBmWE(wvv-Y<;#HO*32%y+S!gzgB!oYu8>Y?r5maw?h@C6ffmAOpY-3Y;FXi$;SqE7hdV-N(!%M*0XE7D@3f+9{Cs<-7N}HTGySR9^?oEC+@AT+-vRcu?lI zJ%ix}U8pX3Yrw9vsjWaO?dM2`998sl@`A{Fql0jjzfELJ z$9qDktoEVl4hbl9BlXj!lrhMw!9H_vWe94G(l1M8paHWgdRsVd2*Oo?a%zPA2SVuS zRu7Bg-=R>p$Qstw*^pOTQSdyQJs75GZ>lT0hE@lqhw?BiL$BBWC}qe+I*Yq98ZWX0 zg3{_7;^oL%#3{HslUCLpbidPtgslYz31e@!*-D-f;DDLsI=`(d_~4qAJ-XKN+;g%~C-mD-87eb=JCX4n_RN^^GIzuA+&H zq2{~?>%i2|YfXWKMuK)s@AQVcCs3h(&+Pcy^@KnYH|n@p4F&cz=1Q!73~7V*sR~@~ zKvQp$)j#lkfwZFrseXG@p+esx?R3u~A#jPyen=_`3i#C02eLat+Te4duG5iVgq1@# zeVH{9kPSQ{%hQLNsJ`UXcg2?XQJorF!7TzRs@QsXzmlF$5;s;c5Kf@$_xlzQ9k#2J z#``lWDiDt*))s=ESAp+W58o%~T6Hy;pR2%Sm-?0JPxGL0{sq@Of)z!3pHNG;=LJPi zHVG!lz9iLeICkUf3sSw!#E+khr24r!x~V`kE}%OfyUGd#1h`DDW$J(;dR6jqmNdxi zlD+KK#ZoZB=l}YvG%A0-)>{U&8lmsX#fvQOk3(8^PlqF^Us3;4+~aoFrarO*A6+9y^Z>JFA}nS`g{ zSqZI(<8Cd)S#e_K)rSJ`Y1@m3)<4rh0d*1!_lhH^AhbO49gi>=y}X!iS)EDHHa@i) zes&(xC)zjO)_Q~{p0ym>Y)PO3I-ha2ZJR+s__64S%hjZMjU=I0%SiP^X81)hQoY?= z!t6&hQDYE(R5uC)&2>pQ$O}U;{ho=0qf9^~MsJtiIT0{g`lTt5KMRR|sVyA4l7uFG z#1@CeRY||l*E$x$7YWANf~HbjuS2nSt0Si89zijx3`MEzNV(Tn zJ~a6t`J=`d>AJG}nyH)N11R>!sZRdeW++B|)ZoosEmHlg=b;E1LZ~FNS1C~&jLg4& zxqRcG&XlmIz!Tf+;8N7pQ!Eh%<=+}73rC~HL0#oW77<}y#HC~WNiDb@d<5B7B&Ae9 zalFLxH`@!*)nreRLN0nR-n+ff>$x34Wh+`hw^##dMCUT^7i6IsmI%2wJKIt5MfyY1 zKU2WfQ!{)Mx7opX&y5VX22N5v$Hgs~p``k+ug*j8ha(u&)xkksdwzq75n`u8d+XohP!U3r9ckq z5xuNy$Rr3=I(ws%gp&!C*Yw;umqZ9zPw8Ayb9->rSUbwy`#PGDDjT*I)%6%DDjbJRFWwH&nXYu> zPyKulGu+=~-8av$4+_6)m~azl#h41VKQvJ~f)sg#2 z^)%OZ$i$%eTI%x*I=aBe<7s6b<3=dh+G<#Ol@qu{Z4r$=w-<~hTOFG(??vo4;|`sW z%3pL>-7LEC@gr>27^9f5;G-a`T z`_R-y&>wcZ;b_t>G~4_5aE_hMd=>K6sGoWn}mDvY;tF_j{>dYrqJY z&K}=C1Zcl73$PUI0}Zj}^YsTd>&)-h{&0xc-S3OLL4S0vfsB|RFYVp(9i$&S!FBZgJ9Q`WX7~zEf3L_dDr44bjuZBm=sFj#X+42B0BMOrtTT2vDu*+~vK! z5www(Vfn zlZI30aRKQ(=@o6?eueaW^7|fe+!Cd~&#q`(i2b8JY2>5s7BK7aB6a=iD70{pchc}| z29Rw43gQe`(eM}R>F+dZNObP3eZ%k@(9!8NJo@Ac5TL(ui1bp5(iEL?)zap`O|e~~ zU(fcS{7+ve4AMyxe|=6L@@sWa57m>`x4QO$9$GV%S@j<9YVd6N!`uz%W=K{*L_!J3 zfAj9t4ecjr^2@ZFp6e*;q5dNKq|OKQ(1m_KEVvQ88o2ZA-Qg@SazLVC#~L$0yZ3P_ z(_}ZOF}>8UVX{|err;URrn6k&rG)g{@S4|%IrGVh#_)RZW+>sunkV9*u$JY>*lPl$ z=~*6J%N`2GcL-Dn)y$)5j)moc{JdZ`Tbn9G!X7QKU2!ZedVvaSw|mubo1wJrXC>^f z#gpn+spyEjAk|lf$0awC>SysTPC2Z09i>wo> zTP*GxuUi0jb2p7 zc_^vE${Lh$7ZpSSW6)J{znHVg4&7*~ugsFy1_b+T!_3JGqiRoM{-Ex)7@Nkg=|2xXl@YES_LY$TJdm&hwDtl4TP;^tOKt^j<&}r zb|U5m?w^Cl>A>5ld*7=CTtShk%-l|K0g!aMM~^Yy5R7`9$bElS22G1R5_5Sn3uYhA zSg3NXK=WxuI=jzIq9W7O%hRiMP*U=+*#4a^r23fqTE<+Y`hyMWAd^&IGS)ZDissW} z?nxNr0V?CdQ|tT_N#nef&-=mqNGaz?trW8XXl$KrJt|CJ{`G2IU6XzfsG+mBQ@yqi z+)&7?-QYKgswR(%#W)=#=y<74R}Ef8_io1Y@mpfht9ozNM}%sLG;OaU-0VDn%93PIT7{{6_q~Sbf_)}#pr$K zd#<5Rs`szYlQ=@EHyPwQA495-dsH-b9?csT^UoZS1ZvmrYc#2xC1?a`nO}#BA+?rw zqMu(40YcZO)v-6J{Pp&O;l0;9z|)GrLm6SxAf;v%TU0XX_bP{D=c6L|2)faM3Fd4* z^w6bh)nk_J;Gw&Wx&6i>@J2Gb-)`s)NFBepwqt;Ipob-~$?EDmZw>u#^U<8voSVLg2A)V?sC_j%d%KO>sK zYwAZAY?R+2mbejQE-D7z?Z5Amp0E)VjXORD=E)#nN6YlfcLt#Uc+%l_nL22Cv$%5K zc78DX!E^ac@D!R~=DnMyD}}bv5{!Ov^VIn!YfoPy&)xoBM=m?b+BC#{T4Ks|Cm*Wb>RPG z9s#`OKGidfkqimstv<1Zj1((R`_Ax-gy80xWA-Jv8pH7&#CnIvvcdtsibKeirve4 z%ecNw*}SI0{O~GmkscGX(>s#2bp>jk?V!3`lH9+vD-NjO;0Gm8K@KWV0sweo9Zy)} ziC{dzN}jmHK^IDZgdEJkfd?EUz!UV8iEliij3;Wz6QDRSgM%nI;6VvakOK*LqMtH> zjwhz^gfE^*B?oVCpoJ0?AqOxh!3J_*fHDz}C%Ey%F`kem2Y7HW1_w@Xkb@GCAO{a9 z6Z&|f98W;wiCuCK2nTF%a0LfKC_xKyfPoSWz!UCxA{$Q-lLJMRpbj|zgM%fMzy>)8 zK?xY(iF-UDjwhPQ!6Y2`!9f}vP{F|uN}z%qRKNiM%EUUJuqFqbD8V6eAcqok!2uF- zFoP0!AO{I36ZClEn;ev)1dzzV9vqmV1X0KV4;-AJ1QN&-{dfW$2d;3C2?vC5@P-m- z!9fumz#s=3a9{vW#N*%=B@jgp8sPvB4#wcX2_?uu4oFaf2Y5oC8~~#PtH^;R90Z~S zY{QlmXHG*I0%6Q1~`z0gI+j5g@Z{r z@PmUilz<8je&9d_IjDexZ8$K7gIJIpaH0f<$blS6&;@$c)$TU96ZB;E*zAi z1dzzV9!g*a2T{lY4;-ApK|35^!@)2dxS|A^$N?cr@P-^{p#(+90Sp}2!$CM4FvGzu zN+60HG@=A}$iWy&;Dj9Hz`;KpsKY@u8~~#PtH^<+e}X{212&Z43ONvh1B5u3M+v-< zgJd|MMF~FPKoL2p^G^Wgcd!Hp5h(#b9Gt^}G#vE80V*6!A_snOkOl`-C_&NRfl-3o z{`dANxgT#U!8JOoa5S{%Ut4cd+sM!NVJdl>^51N8kP*m;)dIh_n*ZAVm;Ly4{NGzp zEzXvwGms29#ZBh&j#@&?825d(OiRIvf7kwMljbX$&M{{35uAe8gmc>~p`~f>55-Du z!ofsQZQgExuzwZX?ieER-`n?B9~8J9zTvs(CCDEx{xJ2~H@N-jo)6-W@=C4#`+Gn^ zu{;92G$;5AMW4!Be1_ZOU7Gi(ohCd!>3W^iUqg62EaPvxuczhoU+llGI;L4edO5TY@>ciHNYc9gU)A@qog8f7AVhlwnf&iQg!Wsw6VK==5P`dvPib3^6M;sI zwUGm6|K7VK;CBzy_~2k$eo6~UO|12&diD&uG@Z^EiSj9h|G9@|Jg!G!5eb&LgjC0~ zxs*$l(4`dpP-<9Dgi4#hWWh)xl>Nul`F`5}^6S$#rakWNtPT~Z=hF5WNkC8Ln#{1b zb^rNjR8*SZ$d9Mb-bVNKWg4Nt+h7o2bs2h0^Tiqz?jgb(*mft1oF>9=2upstx9z{# z{}FkA%fr-PyI$l&Wi$4}ujcik&uz8(=&1aE*W)&{RLM8gWB5iWZ%C1LXm*4?aqGY2 z30o0SUnF)<8|V;Gerp`+zJqa0pTkm z(@q%>v4M>Ot6WuxSRVm~)8>@N!N;jH4eW#DtfipD-4yn!?U7(%aA2l)fEQYF99P@p z$gD;Fe&Kq&g%YJZcX9CDBdA`LJBsPsKugy95i&X{gmbtZ^-F_3()Q!G#_n<`|Nhpw z_H%To%3wtLs%r_l*`jz>H2D*;<|&gZ|7po&m-7v78>M_M-V*W=F`?s*r7G;o9?+5JHnNX|F8+i7Q&@HZr8Q! zEW%{ad2n=_IeHQ3QE&T117&+qx0Yx+K+C2Vae4a-;cAYO)_Y74?kqB&8MW{vOqY2D z*H~$S7ekVgmxU5gHh0(g7|yrQ^0VY&Mq5r|wOod&kJ32YdGhS8^B%l}@5^1aPZ}8s z-@BZvUKFblMiZqxEI&Qbi&KrUobPx+bg$8}UWIbFwUvrlR=5mGx)nTua_rElStvGG?MRmSfNv?{rz~~AR@SG zNIBP`oCv=6^!tH2al$}3H@an&OaW%WYh`c|HV zZc{{H`0Xo%vE0SdGx`FctU(-Yx_1mbu6lZkI7AANy0Y~*?(`sJfoD4(j~R6970x_; z{3CH_o-SL_sgpSLA>w9`OD?fx`e?Dqwk+`c-1hwsa=1bDr?rIpwUf|J$*Ludc@tDT z(ac2UrwzURs|sj&Qwhr`r;Ger1?V|d+RTGo0IIF%Cv+TFLi=bjeYVs!gkt2fk*ogl z(0j-2%V7!6iDLnBkyVkqiDOows)xny5r)EgU1MX+kmlZG%uSW2sG}e((kVe4I=^-{ ze^apll?R$1a$EL8zt7T{65FQJ#iwTCwA02TXZ-t#(_84pWfJTN3stIj*N0WmWYg3j-I_7aJ~(*UjMywGCq_6Be=m1f`4lOlL-oi}@0IaA)FoW?S@(@bYh zE6_vf&}vBPPmM7;1o(E*+e~OT1M1JyL$_E(5of(;*p+Rah^^;Ht>&IS$d#BR*JkKl zK6u3WWmE2#@*k1Is$L!639iJ%-ZER;@^*LD&Sx+406i`LnEpdWG?r9z%g})ZaWpO) zXA9vhpG{Y8yIOh>j3qU#^qJuXJXbp}KlW4y3_Ct3Sjw-`=@B~>_&irq=f0jD^F_sT zP+C3EJLJkI#4GdKRaT<_G2UhK+MyaikowKMeAWW~n%ulS4<~h|j9NePlY-Z)7d`k1 z2Vua|Z!qe5(GW4jiw8bZ<|jz~f{Hx?h`+}qD3qT;XZ%nWn`QR_z&&W4IULsvc<#uG z#Zy&7g>9!SIHy;jl@lMgiWiR|28Jdrb?q|*sb9os>>iN(ROeRgEUz=g`U=*ZKMAEG zg4_zT)pVw|v(*}G-U2vTcfI<_f0dAm2szg=C4~6eJorBFS0hp99+t^RzCg$&Kx#-* z3Glpe)t&oU12w07&c;UW0&3Na$F?2}0|rcdIq`$kgyz&?W&tk&pwVITq=nBGSqN?A zT=_l=%BW<`eVcrRRJe;zRI*$Jn`(t!-MHci8I@<7%YB`Yj#|w3){-;GczaRat&{GE zrSh{=sH6p=pPakU?chV$O6)o8ap(a$et0tRG_5rX{n={KJoOsdN^F%{`Drsa|H|2- zFrgPXbmYsIj-DaRofMw+ua^gr3wxg2P%}fmFA}4ARxv_z$5~oGFIjY6xL>3VS|Uq7 z@c<#aArO+d-?i59A~^7L-^xI}SH#wJE8oxS-vyTnM`-j`NrR&@dWxd!KESOCUskN7 zjYjD-W}Z234S;GZ;i?joLF}}oXH$JNfX)XeZwgi!L7uVS_A&?2z?~M2KbNr^fGf|L z7;oqofRh^Mlf91mqMMCZ=~51@K{wwVU)`<9f>vx3-RmITgXn8T;`bPqmABpKo;-3y z576eTeLj|kz{bN*k6J&T0{fmD`h)~Upa5Y(^hNan65uti-R|Fp@;El{ax^U=Z8xPR z#&;tD{#lpLKDR)gqzkXqR|(SAP0qaQ8nL-pIqJh=F|qkk;mK0DYcMdlA#zJ$A8G4( zeN6}pbUt?Fb?_#B(zf+o!d7|0t}RmSt57sy*S~_b(j9WxYqv=NIbcKG|rbZFykf$-- zP!|jx?tN;WuG$XwNG>zCGfyUM8P{n%y8_i?{M9>GjYDj*!Uo2{ecT7;jb z;?&A5=ZG+O?{p!aXd=u_;p3jx`$TYb?X&uN4I((QU?sHz4Wa#ToqX5M5<>e>!uhan z4J6edr1Lf7G?H63Bk`S83s5aL>}Fhb0dO+-o!@Qq9_T)>ydvi(3sioxd(-jgpg{JI z1sPf;D6lI^gJZ-T1WZ;`Nk#UW2muZDe%yoB*mgk{>ZSS~EI6fi2 zrykLk%v->=g0$E(8#Rz>xp9i#&O~G`!c=*-V+4t77=_2(kSzZx-Es2u!7G5*?7ZVZ zt~*+_tG&dB-r)aQ&gZ(x|64g9e0`&3i9h?jB}CBoQAg=mG!d45?V-aqXcy4Oy!Smf zuF{IYpW*rswyJ&yOTmP%aV~X5KD684siToHNqCcQCvOqM+N);foda6%cR%28zRfqoHPveGFe9yy!l=A&;LM#<*vs5z2AuC#UaW}T{%$oYvPgC zu^AY;^FooL`D@|~&-gX&`Z?kZwdcczEuLsKEw&k#}p?U|; zawz4vbA$RfXXu$Z+I8&8TH^R2-W}49TZrR$iJi zm_@20TM7BP8h<64lfOSBbmb<-X{@`U@V)!b))pOt?y-6Xt5sA=9T%6bT}#N{ml7v( zeZ-lD`NkU=L`0PLK>pMzLTjDnft_+U3BhR9b8Ovd(6uS>=FXjuw9YO5z>oE7tJ$Ks z)FiazV#RG9zJ`L4`yzJsy@IZ_so72fcX2I#9+Wiy?jeqfZ4q~u8zPSK9QO$+u_QLO z^3_PC+7bL^HS^Wqy`js^*Q(Xt%Ky##o^KJqA8+G}o!$Ab`e-`}m zi&p6G+kZdGKmU`i!wzPvZE_|KwaQ+0XYwXAlT#$sy5 zfA6DtoxHvOdrN3W_Z{?C_JX{7W>q`o!=MZ6!xtO61~r|2-;V#+%p%tx6!y8uT=|?h zxKiFy<7E(`^Ht+ea8nS$!)NRKR8aytk3YW6Dfg{}eE+5734xN*qNO_^bei%mJ9)Q3 zo}I6ko%7;^&fh*CI6FZ3Jv)9pyd}b9xp>3%^oTHt{<1^T8=zs>CkYK54m6Bxxx|M$ zNICeykoWm_2$O=yfK!Us2#J_G;;#gop??rt>wC9YXl3oFp0w=;7`|BiQ|%*yR4c-& zPFC< z+PVDK2+lm$O`Pj3q5V&{$PArfXw)p=U$uV^!N)T$6VSFB+QzK|{N=le9VyXgcQrXc z&O341dmL<_{p^@is>^3+1|CvFmvLnYOL zO7(=(woGrYTscB$CCj~KckV*ByBt}k9X#QVo{_$kgr6v2&4)r=H9$WI+8ahE)<+F<6NPDN4MTH_M?`S(#xjDC!2v5DLm%yAu zgr9v+1I}g>j?H495}CxJ&st}Tbcr0tX?K4OT$j2YEPXGZ1aT!XHc zhu`bBAr$}m$0mbqHK1ns4HYeqVCZg966mJoGqLM-%?5716l~|}u zcmq(ATxr~fWz3M&pJ>57f-WivRTXHcf+mIh3u{j8hn~^yZHD}N!O_n_Nce*ZC=PGD zz96bkkovz(isqxE{c`0MpO2y9BQCB-D!(A94dw%p8!jQ{+INa=bMu6=q*}J#n_dv( zdTy%J=@zPzDR#TOnjMn*)4E4QQH*QP&076VP$d&o#_doCx6Pz2E>lqkdo<*=f4mR| zH(9TREcj#)r2hKRbBE9#)ni|%GA7VX7U%N#ZIwVIahHA3@dcd*)HuFc;Wc5h@ngp~ zR(TLySHbH_Q;qT_znvYbRfMGeyhp;yD7dWx`HdQays1s2RF4v&VwCTdi57F9|9)zp zZS@xre(h0H@1P4o>L0v$fD`Fo*vMqfXph2kj*D)zy^WMoeVSW_NF&JmPI{&0AB19$ zk5f`9HP}&|PN&QN5nagFxyfKt1r>X|LwILX(9Q*MWoMKME@U~>-0xo?RupaexajZ< z@tu92#&OyJIb}UflF8l)R}^U;iS8Byl4otqirXcDlXYS~>#RSb@h@jAYx#y))IW#x z=miiWXGeRd4*3IP+1HF}9|O^GEvgMAqU)f@*{}9R*5=4!dkk@TUo1E_?LD`tP@52~ zR_e1-x`{NTj5aH0RiFTSjUhjyJSbW%f6G4qBha$|RE#G3f&Y{_yVgf>pnU3?n-Ck9 zPKHI=t;5?Qfx+8gmVIh*XtU%yxv%XFcC%5jn->-LKQaz*)!K~2&Ntb=8`FzzMqzXUL#a0e_I%A6tty2yS)~T zT%TVYd6S9a&0;D%+Bbu?=<3Ed8J{4ReqMp$g+_ud$M2jwryr!t|H7x0D33f z(QUGa)E>-wFcS2;&QAXSgTIyh^|zW!f3W%YzrQEq?~~#0&%)pF;O|KIcO?8f68;?t z|Bi%zN5a1&;op()?@0J}B>X!P{v8Sbj)Z?l!oMTo-;wa|NceXo{5ul<9SQ%AgnviE zza!z_k?`+G_;)1yI}-jK3IC3S|67cNtV@f!EUmn<^oOR5q_0{MYv=#NOQB$?3rkd3 zTEdbLmU6HJgQb(vU+0|km#tX%!h#hRny^5Gg&i!&kcE`rdz1Dj%V1c(qR38Uxd_WV zSf0VM3f>=!ViYlpEJ9)N2#Y>gtid7+-XBY3SlYsp6qb^(1cap#)p*)Dq%5* zBI1yxJS@SH&i|5hh9xg7Rbhz+GBa35L)WTvE7Ll;{LrHX!r8|n`MwZI3#6^*&$dVG4 zf+$H)vXF-bI4qoD!3zsjSYX1!5G6s1Wj!p%k!3V2e_`1Q%S~7&!pT!C@?mifi)vU5 z!y*0rl7%}gxM86T3tU*3!h#Y`$YME= zBIA+eH!PcBxeLow`1y~MwG?rXEb3t~4vT0M@rx{4VX+A(anzOZD4lgbpqkt`Hqfe#CF6hVzFgkb>-C!DeT zh-E`8_hFe1%WGH`!*Ui*Mq@FOA|hh(4~uqKY$JH9>&##W<|E#iuYnUm^>-;L{ukp=TYksa{uBfG3v|Cybq1z*GMnCUombx?f(__?f8hp!fm*`fa9i zAW`U(Lz>U@ukY-y4+EqInwOTZ*UzB27*FIXp}h$5Z9`8&&=8G>kMDGw_{${ z0Ib<_zb*5m6VfM?TzHQtYm59=_rSvLE`VUU+>YJ?ifbOn7`E z0gWo=3vaaaLF251$h+~~=;Zp0YE2V-}!AtaQRQ0vZG%E zl99NFKhrYyEr`EjR{)*n7!qD}jnAWMBa$##e?Yr2xpd;U^7r>O`1fC_{Cy23>%@Ow zgO_yS|5aXt(Ze*K^P$J9!Tm1kl^>)Zpi7Hk?&`0;fupzDbu3Kvz{YF2-!#_Lfat^p zUwhm2DF1PE@T9~EP%6=AruxDQ((UJ%iS(5rw(nsxw>o+`H! zqU9I18J(*Gu`N9+)5;8Ry-n7xTg9j0W}oH#rP0kOe#+V_rQs5ac(lLZ`R3E;*hSWi z`p?l|uLx(-)<`X6wRZDo8nbW6vN=s}@X8}(twu*fOO$~4+4&pZ=GRbPQs$!@k&Fag z==3p39Xm9=RYsk(Y7Rlqq$W4L`5{3=#Xz_A#TGO#79x8%|1g@+HnyVe4??{U%^X+X zr9xXj>vAim>LTv}<1M4vPtabaM;R8e?~sc4f)&$LAChUd@abqz13J=|Yoh5cwo-(DVlkVXAes}qy=E(0^s!hHe-0VunR&f4&+2)LwoucTsy z2r7EaXr=5Qie72ZT)opcit06;=L-|Jp{hH~A9a2n23>Z{Hb+N`2*Ks!S7VPepzj$} zrLv52sITM76xTv1>g&32SKm$urEh+^&Pz1{%rYZl-X<Eq2iGy20%t zzaIoQ57n5}u4_;y@?2?SP$g9Iwc`@+tA=!0E|N6W`ly3je7LMK4h`ljGuqjm1AWpb z7i1?-!evaplB3xWa(!>eZV=f<=$v_Sme7KPl0U;u_D>{@IlJ!goeO6`2k+e5h#RJ0 zu&|6FYyys!<|OZ+w|Y52IOEl^NF~Ye4Y; z3bh;Cfv(#k?(Jb-tC2~M|;a`Ddb8&a;k&gp3pgJl=iGefKUqNOtXvAAm}d3 zRc1Uj108||JUJ5Iz~KD4D=Yg=P=EXQRt4E|g5GgO%kbNa1f8vPhhfltxE{6V52SyA zVolesI|YA1qls_ruNjV_#oTV3G!O& zHRLtc8$X%eE@yuWT6MpFpOlOOuP!{h#I)%OCiXCWheJ1ZYmXo>JJlqn8w3o9j4?k@rDUPOao%F4^w)WxTDZ>n1myfg_shg5PxKP z50iM9s-qBcWa1FhgO~)wR39evFl~p)IZPsAst^-`nD)cu9;WapL>-w>#IzwM2QdYR zi9Sr{QAj&7xrix5OcY`|5R-nG+M^J7m}tawA|?$nHHZm7O!Hwf50j3VTEqk*rU@|_ zh$%lZu}At@V)6aGjIZnOg?#^MF0J$WPjhJ&?w{t;Lc0GnRe$|x{?lClpUtI3egC<2 zX<6TYnj8MJc;l}oE9IzuFYfzCd+E6TXfGYuAMK?hWBq5;piCc97EAsgoj&|^V81>v zM1_GU3fzQ2B@7*5fQSqOVITqm6W$v` zVi@?s@D>KKFjR#BDGWOiBEO+C43J?M41-4bZJZz(_;hRevH7>2&^^XotN z`lp3qH4L6%h^)lvcMXQS@E#bt!fgu3hM_bJm|<89gI^fp!ax>=t1#$B2G%I>83xHP z6ovsW3~Q0WE7EZ=k;jFlO99+i8WC_~>Bk*6mc|0ySQ?{nV`+rKjo*uolka+Ibi%hR zjZL_*G%_)h%gBq4)2n879Uw3v;haITnHCG)2gmXyrqQaD>OGmH6G3d@SQRLq!?nO)4^Qdn9t7mFEJ z%&St^Q!>koxm?WHVqO-rub5-SOe$%V_~+VU>BsAz=Ks>yH2*Pz{OkJW_q(Fc+PWz2 z{3PfZP}_8>q!xThTw8Oj=L+c8U2SrNEdUG*aWx%K(+7hojMjmU{9s6b?u}3MHw+14 z;Ew|DVGs{Pbr_H%!)_QJ#2_Gs`Y@n}VLJ@YQ6M-nREPmV3hal$Jq+PtppFd3QD8$d zIEW!Y4D?|*4}*3Xn!^wx1`078NCEvYw1)vaGE7H-6ESE=h6XVJh+#eq=3&SVLyH(d z#4sTS12N=>fjtc0VVIEuCSu4C1A`d;!yq4q^2m@Q1{NvsAqELC6i5O5e#3egex!hm z7)m4qh8Pya;2(zgC{QE@9LcaE1`jbrh=D*1_hDEPgO3VV$zR7?U5-+Of+IT5tD|P z8pH%3h2|sEk(hME)FLJjF-?fcKnmqYrY11~iD^bmCSuAE6N8xk!!#u(BQfQOiA78w zVv-P3ffULT6O)*J#3Un`N~92mWLgl@mzbo)R3s)GF|CNnLrf83Diafyn3lxkBc>QJ zk%;L+3ayFBOH5H>B9cruQb~-R6;~yZ9?XRBJ*5^%o#%7{dk<7;eFoscm3Yq z_j_Hx_qy8uth4ssYn{FC>zuRp=X2lZ{*ZvyjjZb@;hFI8_kN&*L*`{@qY>!Za-k>q zoe1b&Ep>2>dklKdlgwx2(t|#?U9y}k^#nOL!EpYk(fo$N{7++ff}uRYNPfdWo?smR zC!>0TLH&j?J;9KkU_?(apeGp5|86*s-vc4U`_FOZpM>b^2iJw@_=xrGXKANb>-lI5 zyxGV{*KG6~H}cZW8~X`JO>K;y{IOkRxEO)S5iR-QdQvd?T=|=tCj*$Yy)%6{r3p+b zSjk-4GY=*!H4^vOu!BiEB@jE$yYco!ii=(mbiP`T6<7EpPMBu)D6YOYzErAe14vxM zy6+B>mVCAp%1M$bRxEHECEghnhG?x_H+LV(CX5GBY$=rfo)jRL=Hhi4)w=qjF$V96}MXaxT7P<=|*0f(5VjL7b-vo!{DXka=lZu%d$tv8tWA z@nEkzV%6s+sAC4w9lwY+&L36kWM0ysn`*M$wRL`L8Ic zliH6;&;q4gA?=~J+=gO;Ypu&d2Ed~qUW-wCYQSez&Mv>N;^50Nd?bG;6nx!Pmhj+o zADCvwY_1IzgV}vVna;D6zX_#vzCK9+lQs8x7moXYTBa`DvCSQ5rBGXeAx0RjES);- z63T*B6T|PD7bl}1{+HDEC?udYk4;kFhyg|<^w?*I@-~d<{xe2}$n6+W-R;~nv1yP< zK|#NF zfjQqH<1+Aa*A|W_*N>nuHeR|ZIstDTT>6TP3HSpy7D??B%&H(%ZV`kKFM~K1UDZy{ zPLR|!7WtXO6Qsmv+T-E`5HtTM;Epm6O4+2yC!=eJi37)fIH-ee z4#&Sy;Qo&fIQ~r2jvd@Th3b>FRKydz8S&C+doD-c;>Gb-x)=M<0mnaxb+^?i9RIZW zFkfLD|ETBmEFWIXIQ|)T)~=Z0_`62?O_1aG?;c}mSi|vG=2Utb zhU1TU==W#f_(yLt&|1Rr&(WwhdyeBDI8qZfjpJ`!+&c9J$Di_J2bC|5zaxp+OI;lQ zLl;$@`f>b++D;=D9RI0i@$knu{zBK^N><_ct5ODa#p3u^`8UcjpT%L(H2yC@RY{;KH{KE*?Jy;4;Vnc)_IaWrw{IZXJ=t%#tCt8R zEaWAXnV3v(Jp_xLBM)P1xFM-@%afh*=OO7dU!8TdJy^*b+3|t54D~$-dgl|xf^qK? z+S^gOfbH43pWd@4t5{XUm6Fkw4M|0ovL5?L4)%sgPqdN`0`U?#=a$#{h%YcNKxmZ} z*?A=<_Fip4LeC#sXw1z3U(X6bcjqYud2KCE4m%3)oJsD1@b+|oSu8e2yO4qE`lqSk zWg(zxLVC|<(o)d=c5BRdb}Hx%oxdt~l?e3Df8Tws@gCvxgGksguiVrOw4L$6u?7o1 zwCT;sc-6IIh&D29IZ&CTWF%c$kN7(o;63GL^kmmvz>Ym{uurg3P&@Ncl#{;;H80N{ z+|8zh`uO+G^lp_ygZJ6*ZaOE82AVUHlb@NPj&myI(n)scZq6}>o80q+(jE%x-h6MO zu6Cijrb=fV=_OHk<4vjbIbWa|j8b`*bAZ9!)E8UMtf3cO?%dnN52N=QowVCiet>o< zpWzFZ8VXvQ-;lc|@u1R6<7(BK<*1IUFgWiTK7X3fy*3zz-eL=+L*>38b}WWrEUg@j zt`&(VbCH5?-jD6_^d1xLAN;5Y)J>f@0V#Y=%%{+th7=i%AMPYJgSEIP#%XJM=&O36 zD&1>yjIWrjDE(t9Cf2fp&P)p{VwK4{JMpv#^1_H~`^u);S*E-2) zx<7#BILj+ERj)Lie?AFK)5bsE7EuS()xZjQN@ zt!9Af5updF$IpT3j*E^wt>Iv*!b#nnZWv6Hf%4Z`^r)>Z=f0kGv4T>1P?S-)H)>s_ zrBQh|J5Y2h{Ffb#NC}l zL3ti%ddk?SJPdDpgri<>b4F7&MFA9Q7@FR8RB~rzKlmhfig>k8T5e@CIb&IxIOxBe z>(ce^IG6}i(k$0*1Jk3i2a;XW!F1c6%|Mn8OqC7o?@PA<)0DFnGec+4C*f>!r~V^^ z&kt%NJs)#kehl>)ZDs9`e2TgqhFOwKa?snEcQ@a^^a8D>>e_E)w}F+R<{c(_y^yv= z(l%U72_OGUgz`&-;&_4}cK%0I`W z$s1LAcgOg=8U)X7WF7BVy#RU-&l-uA(x5p7BHglJhGO-NHCQ&}%tcyHakQgMv#QBW z2S`SWkUSv~LkG9K)e5arLkHB1Xj)S2f%tYU%$@uxa?b7Rs$k5M=iOL?zjU1XAm6@8-V>din>j`*TT|ei)_D3ScZjJ9+M3K=s@q@DZiinH6!{bOn8gP|e>0o|7 z@M{hJwFduMga7xg!6270e`@FTB=kt|bR0`M1?Wg>QU0B z9mS-Uxnk{n%djI%`(wRF+ptshnOm(TLZNPSrCfI~35vO0-H^vp3PQMU@6->D2R@B` z?fEMsD1cw!R7ylA!fThlt8%-D@{VqH@w_kyDg?wt79zfa?CJa3A;&Di?B!rXW)}u9 zdu%xE)0PDAZF{~|#933Y#FzJ4fpGy6Ey12O{pXNOa-_?Rr2zCD{5X16xeL-VIt>zQ!oZE3bll|v9dLGb zytmEi4)WR6%^)E{j*G zGKFK2^yVZiFCfifR(tK5rfOpa7XAnJ?#qtP}YPk(~l$sCL1cFjhh!q=Ns?pgq{a%h>b?7o zB4{wd%`xw!>ryaY5hCf6ox&KS#`oBs^Id3xSKx8)1uL+4h$dj``Ey{=dW_mvF%WW? z8EM^cJ(Wi@Djy;3m~v=@u*j4IByArLCaHgd61yB&<(C%4)s$C#Gp3 zu@hC)u5(jhn!aOjsG%q{nLq%O7t><*%&ZN_9%qbiOMc0umWuKZ=I zyHKs_Qo`n{I;i0OCTr;?fj|uWh@W!|)V!WI?qF98;Fh)&oxADFbwBWULQ&#K}Sc28nohCQI zg5BI=IF~Nuu)n0WI1vx!`;E)1h}Sz*Y#Loeg}`-eFG?+bhabisn@qa9mC z527VKGpW@RX=uSS&}^cC4CAmcj+-j4!Q|f;4j!&7#<+`86|Q7hW6bg)HRh-fQ>2&LvmydtY(XZ_@kF zn3>`tu=Er@$`2}ew`3`f#6Z?`zx{RG(Qt2NNTV#*Gbr0>Wn6Mi9;#@OUa_~8fqEB+ zNBbJGp$(ZA_pr#Tpob-pe|C=>QAGt5 zC0@CIT7wTt=+IvHu&M%OispBBa^!;_Vq(P=F3^$cZHjkWHFQart_cpzhVEC6y6Dd0*F%3r+S!_laF<2;zrT`C{JkZ} zUJ1tuEn>E0ALN$lmcK>V^MBVO3R2pXZjavo(Pcp+D^rX^8O*(GtpWG1sX;xO=l+6EEd%iu`rK%R`%nPn5~}~af{k#%<@B6hxIu=%;9A* zOY?JO%tK>yRltZ2=0!WdaQh1>=9kR5tM{1!7Fd!b)2KC#g}Ja&T-Tk#$9Ip{_m|+% z{?~LL;mEosg3$T@RYv-U2yC5<{Y}C_0@|eBEk`slg7#fZykU)_pp(f=`}(^w&`tJ$ zXIW|#^n4pg?pXZ%o>}wf4!+s@sHW+Z$E3e^%EfRMjR_)843}{iiD3 z8`Zf9Rk;b(xCvFb3DviMueyz2>mRzj^&i(iy6bmC>vYQf>`B~g;+(DL>GeIoncw{+ zoAK9w-zX3L{#S0`p0mn|f7uTLDdsQzmx!vvKr~m>}MZ@nrSW>}M#K8BIqFOK= zqknm|WaxKZBvBivh6F`To~{MTou_nFbnYM)t(yADy$L0Cdz=J8lLq1*uF9Q`k3wQS zkDuya+&YG;=nx5PhG!!_}_ggON@vU*BK-3VoU8 z)XINe2&S7o7h;bmf+fakQ$5xUuslcQKCvx{z>8p zSfdzGS7asnAYzM!&OL%WL`h=&X>Xup&ro0#XAG2s(bTf5qXb?A5;fd8*mg1vawNy~ z9*muatj_hBd^-z4%Ze3CPs1|CJ;=*AQ$2`Dek5beh~~oNwA>nl^rQ&92;^eTTC8V{ zh0LAjMTAI3cHPiBLpQ)+Rp&QjpZs()6`mqnacdT_{2Jr6DM7f&4JR6@%` zg%>iE)d;)@#@X|heR_-vvU>HEWh#xq7U33ZH+rqAP?~+wbrNd zIR3pN&$6%L`0E+-bUF}t5lHl2!)}~d4|1e&?WWn823cLI$UJDRLCaLnCr!ax9RFoU zUw;xz^23^?Bg+_$zo5|RA!-6I0=c%`Osu5%3Yite*lusJgrsM}xsNXfpbkHaEhit7 zV;rvohQ#kGU_vMP8UsGcW!D|YY^7?zMOPAtwuU3c;lISSIh>Ew;bo%lo_G^F&Xi@n##~)=wVJH`4;H* zk)`@nA>aRZaQnxVASR}B=jD!yGP za6pZgK_;y_1?bf$6GbXdQxuW!bZArkIgqhEYYW+oE5N8fUMXC=0g^sh-97J%(AA6H zO=Qz9kUnknVC45;v@&n~eq<&Od_PQ|{dm_d$W~=OaPu(+L9F$NPPa(ZR=Y626XIQHO&)Evg;wnxGJ`UY z2lrAQ83^mKTIu69*MFLkFR<*eYAC(?PJ>s4fzF`50u) z>Yb@6ISE0_0bAMhb{L>WA#`0s7W%C4&UMJlL7Tnx9UnIZU{@vPh%Gi*!?($`^xHUc*&mQw4XM_Nqb z;BzZ@mck^=vY`xmJy6@rwtWt23uW4?&;$(=zA4M`=wUYe zb>-2odod5c%69@!S+FxJPZJ-uTVr1Nk$g`pt1+EJ_h^*pxS$8!Jt><+M|kAvc+8n9 zCCqkyPP~FD4l}&C**c|pGiJIXYTFvijd@B;NXT(q#q5T>v}YI!V9+Bst`?J9n0V`v zEs6AT`0wq>rq+^COsG-F_vlCirv0ihUP?j}^4P2;vrfw6IiQi?__NO-tZ`21NH2r? zOu~=66$*pGycz+XpSz$Qmss)5>x=M^n3$1w+fhtd=&AG>mnF>LTX`UJa~-B^Fe2Xf zb}RZ`!&Bm&8G`M&(n?`wF%Lnj$s@O`5XWE1;J`Ui=(BoQ@LOX6v=Qtx`<^X{St;vn zJHqdbxnlg!#Y`?cq0zAr>D!&1Z2OZSiA z_-9;#{4&rZeewHj>JU6j-c@e*MiF`?yt*=}t^u|8t-g&UamUQbv~QO#h(Y&D>2GRU zUqZv1kNvh8QsDT1-9bE?f_Vh&{NkpPhT|{w)!VxV^U9<8cKyydOvh+^i8-eYdQf$T zzVZ@)M=n2}cJz_MY@4sJ?zzf_879p;m43^@OlR&-&L%Kpp8Mi12Jqa*?8fiirWfjj zK^YXF;n}ZT&M#xJ^VWa11^YMfxqtcl%pc|cIPC?zXtAerR4$v7}Dvf68My&kK7GDF>2HIB4P3+zHc=0fPupGwuMnU zko->Tw24U(dGrO!(ogCFcjk$ZVYL{ft*d0gU6O@d%N&CBs5J4g=Z{e7pCYF}Nml=L zAr3)$3ck*HRqYEL249W2$N9fgfeDh1chxT*fJqv9rHAB4!DJoL=AAvpU~=_i3*CV+ zu;IB(ke(tQm4#*MbQi>;_LScwsSWM)eCWkQL5^63JT3|`eMV$%X}9yA?zSCS0TT zS0i{X6QrkrIr`>|dCprvd#*i#E&i(Fnt4)vB(+D$XQFGP@N zR4^~WbD1DL1vx29+8+Nf|d zxj2~#p34O3DPpO9^*+0n1u-NUJxH{zLkw&?Q%HsE5d&W`JN|=<7)pbdK6K)Ka*A5L z(r0SWhUYRtdI|>7?81ZEBrxz*v0G?$4)lMLgSna-pl?Ic+H278^62-6pc|yc@8XvP z8=lJq=_$&)`$p< za{<9~nIJvQW?j2nJR1j6MzYWDGM++l_gS*5deYI09Nu7TPcF*wDhc?+#EBAO9JzA0 zk^S^sCP+`KH>9xDv6prDCO?A;mg$F$lnG$)gGc+$iRWPI-r7UG$`mj&WSD!R&I}I~ zQ!{nit`elD7}4A76tX(IFcRuryqXHJ7-?VA3cHaowy8-;ma0w?BdssfpQyNvd)ad5 zY+8GZHawRJ(o;xso4=>2!UB@Ed}_~pYYEBHbppu8#vpn07x9|wOpxrZWqrDQ0VLsG zNqL@=3N}2K3DQ%vNRj9jPrQoeyi^py5*?a}>i`}yc+2wRcos&3W-H$Ns_J2AiP~Sd z)wBa`crFv9rywt9%;&ZjHOM`E?BUH+CXn&!J=kKt4Fx*|Nk6n?Mmd{YX0{lpqWnlQ zUxDwjh~T-rAw5OeifSi)`Q=c`xbv8wS|5nZN)y$-i2EMBI>;6!)B#qr;k*l^k($A5s^(7gl4-)MIJ`(_+}EX6O92gjd2QZvO1$Ny4Z zWx!d2^c0dr)Wn`zeT?H@-)tpfxf{oS^h4-gRvdql z2PT3c1nDVS+$?5Spn>D>LsvDs_avIR*A;Wy$QjMBDy@dG<01cBHNQ(rfoN$9TG7Ap z7!f>|{e2H>6^&l|DWz5l-Ny zKTEe+u@Sg9l)b6me1IT5#W+>eiih88gTX;+t~|~bbLDU@a9r)i3v{jx*ad2G2Zx{fm16l_dipEH@+-yizcIyvKehd$tAEke|5m!1 z+R4@Z?3s1LWc=es^cMzYozSASvp?>1`Zrg#-$<3;&iPZUuztorGbQVX{t`g_K|QTU zAb%pt|MR(j1Y7Ip{ulH7cjMNN{pmf{!8eCdC`y#MYJ)~EdoYU_LcdE)g$ Pf4P@G?(^^0Cr Date: Fri, 3 Feb 2023 12:20:01 -0500 Subject: [PATCH 351/758] prepping jumping experiments --- .../lcm/visualization/visualize_configs/long_jump.yaml | 2 +- examples/Cassie/run_dircon_jumping.cc | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index f70f597573..60dcec6923 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,4 +1,4 @@ -filename: examples/Cassie/saved_trajectories/long_jump +filename: examples/Cassie/saved_trajectories/long_jump_conservative_3 spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index e4a30bd107..590bc5cab4 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -141,7 +141,7 @@ struct DirconJumpingParameters { double dual_inf_tol; double constr_viol_tol; double compl_inf_tol; - int acceptable_tol; + double acceptable_tol; double acceptable_iter; double cost_scaling; bool use_ipopt; @@ -658,11 +658,11 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_y_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - 0.05 * VectorXd::Ones(1), 0.2 * VectorXd::Ones(1)); + 0.1 * VectorXd::Ones(1), 0.2 * VectorXd::Ones(1)); auto right_foot_y_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - -0.2 * VectorXd::Ones(1), -0.05 * VectorXd::Ones(1)); + -0.2 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); auto left_foot_z_ground_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), From 2558af81f0bc43dcfc028bbd03cafbb0b32930e7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Feb 2023 12:29:23 -0500 Subject: [PATCH 352/758] adding gait parameters --- .../gait_parameters/dircon_box_jump.yaml | 32 +++++++++++++++++++ .../gait_parameters/dircon_down_jump.yaml | 32 +++++++++++++++++++ .../gait_parameters/dircon_jump.yaml | 32 +++++++++++++++++++ .../gait_parameters/dircon_long_jump.yaml | 32 +++++++++++++++++++ 4 files changed, 128 insertions(+) create mode 100644 examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml create mode 100644 examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml create mode 100644 examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml create mode 100644 examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml new file mode 100644 index 0000000000..4806f558d1 --- /dev/null +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml @@ -0,0 +1,32 @@ +spring_urdf: examples/Cassie/urdf/cassie_v2.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf + +knot_points: 8 +delta_height: 0.5 +start_height: 0.8 +distance: 0.3 +min_stance_duration: 0.2 +max_stance_duration: 1.0 +min_flight_duration: 0.1 +max_flight_duration: 1.0 +actuator_limit: 1.0 +input_delta: 75 + +snopt_scale_option: 0 +tol: 1e-4 +dual_inf_tol: 1e-4 +constr_viol_tol: 1e-4 +compl_inf_tol: 1e-4 +acceptable_tol: 1e-3 +acceptable_iter: 10 +cost_scaling: 1e-3 +use_ipopt: false +ipopt_iter: 100 + +data_directory: examples/Cassie/saved_trajectories/ +load_filename: jumping_box_0.5h_0.3d_3 +save_filename: box_jump +use_springs: false +convert_to_springs: false +same_knotpoints: true + diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml new file mode 100644 index 0000000000..8e47ef42a8 --- /dev/null +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml @@ -0,0 +1,32 @@ +spring_urdf: examples/Cassie/urdf/cassie_v2.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf + +knot_points: 8 +delta_height: -0.5 +start_height: 0.8 +distance: 0.3 +min_stance_duration: 0.2 +max_stance_duration: 1.0 +min_flight_duration: 0.1 +max_flight_duration: 1.0 +actuator_limit: 1.0 +input_delta: 75 + +snopt_scale_option: 0 +tol: 1e-4 +dual_inf_tol: 1e-4 +constr_viol_tol: 1e-4 +compl_inf_tol: 1e-4 +acceptable_tol: 1e-3 +acceptable_iter: 10 +cost_scaling: 1e-3 +use_ipopt: false +ipopt_iter: 100 + +data_directory: examples/Cassie/saved_trajectories/ +load_filename: down_jump_1 +save_filename: down_jump +use_springs: false +convert_to_springs: false +same_knotpoints: true + diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml new file mode 100644 index 0000000000..625f35bfa6 --- /dev/null +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml @@ -0,0 +1,32 @@ +spring_urdf: examples/Cassie/urdf/cassie_v2.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf + +knot_points: 8 +delta_height: 0.5 +start_height: 0.8 +distance: 0.3 +min_stance_duration: 0.2 +max_stance_duration: 1.0 +min_flight_duration: 0.1 +max_flight_duration: 1.0 +actuator_limit: 1.0 +input_delta: 75 + +snopt_scale_option: 0 +tol: 1e-4 +dual_inf_tol: 1e-4 +constr_viol_tol: 1e-4 +compl_inf_tol: 1e-4 +acceptable_tol: 1e-3 +acceptable_iter: 10 +cost_scaling: 1e-3 +use_ipopt: false +ipopt_iter: 100 + +data_directory: examples/Cassie/saved_trajectories/ +load_filename: jumping_box_0.5h_0.3d_2 +save_filename: jumping_box_0.5h_0.3d_3 +use_springs: false +convert_to_springs: false +same_knotpoints: true + diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml new file mode 100644 index 0000000000..258c0bfec1 --- /dev/null +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml @@ -0,0 +1,32 @@ +spring_urdf: examples/Cassie/urdf/cassie_v2.urdf +fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf + +knot_points: 8 +delta_height: 0.0 +start_height: 0.8 +distance: 0.7 +min_stance_duration: 0.2 +max_stance_duration: 1.0 +min_flight_duration: 0.1 +max_flight_duration: 1.0 +actuator_limit: 1.0 +input_delta: 75 + +snopt_scale_option: 0 +tol: 1e-4 +dual_inf_tol: 1e-4 +constr_viol_tol: 1e-4 +compl_inf_tol: 1e-4 +acceptable_tol: 1e-3 +acceptable_iter: 10 +cost_scaling: 1e-3 +use_ipopt: false +ipopt_iter: 100 + +data_directory: examples/Cassie/saved_trajectories/ +load_filename: long_jump_conservative_1 +save_filename: long_jump_conservative_2 +use_springs: false +convert_to_springs: false +same_knotpoints: true + From f4889a085762ca402f5af1a61296154dd0038409 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Feb 2023 12:52:33 -0500 Subject: [PATCH 353/758] updating jumping gaits --- .../visualize_configs/box_jump.yaml | 4 ++-- .../visualize_configs/long_jump.yaml | 4 ++-- .../lcm/visualization/visualize_trajectory.py | 4 ++-- .../gait_parameters/dircon_jump.yaml | 6 +++--- examples/Cassie/saved_trajectories/long_jump | Bin 0 -> 52425 bytes 5 files changed, 9 insertions(+), 9 deletions(-) create mode 100644 examples/Cassie/saved_trajectories/long_jump diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml index d77f5a0cb6..6fc01c80a0 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml @@ -1,7 +1,7 @@ -filename: examples/Cassie/saved_trajectories/jumping_box_0.5h_0.3d_1 +filename: examples/Cassie/saved_trajectories/box_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 2 +visualize_mode: 1 realtime_rate: 0.5 num_poses: 10 use_transparency: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 60dcec6923..1d34c64afe 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,7 +1,7 @@ -filename: examples/Cassie/saved_trajectories/long_jump_conservative_3 +filename: examples/Cassie/saved_trajectories/long_jump_conservative spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 1 +visualize_mode: 2 realtime_rate: 0.5 num_poses: 10 use_transparency: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 38c1f88877..e893a45cdb 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -17,8 +17,8 @@ def main(): - visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' - # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' params = DirconVisualizationParams(visualization_config_file) diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml index 625f35bfa6..05546d850a 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_jump.yaml @@ -2,7 +2,7 @@ spring_urdf: examples/Cassie/urdf/cassie_v2.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf knot_points: 8 -delta_height: 0.5 +delta_height: 0.0 start_height: 0.8 distance: 0.3 min_stance_duration: 0.2 @@ -24,8 +24,8 @@ use_ipopt: false ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ -load_filename: jumping_box_0.5h_0.3d_2 -save_filename: jumping_box_0.5h_0.3d_3 +load_filename: jump +save_filename: jump use_springs: false convert_to_springs: false same_knotpoints: true diff --git a/examples/Cassie/saved_trajectories/long_jump b/examples/Cassie/saved_trajectories/long_jump new file mode 100644 index 0000000000000000000000000000000000000000..21fab0038e0a19b33e4fc9a99067da46160be9de GIT binary patch literal 52425 zcmeF)2{hH;|1W;?JkKdnLMZcC*c)Xi8B!_|k}{L2(xjpkAsR$8nhhxproD?asbol| zP$DX0#tiqwd!J9=&;S0`UF+WefBo0JH*0-9`|S65y^nW0w)e50J+@=?qN)Wy7@Qax z7#JkYg1ltRJT}Y7Xv(N-EYZ+iqNyXJp{Ak9MSGG#*gMoO(93_DOGuELw}*R3K+vw= zhYgl_xO)YA1^CN^xdnN-ZT9sDmT~jnA`=|q7UH4mwwFap1XxseNHgBdD0}p9a+;db6dZ4Z(-$#gU0PHy*>Obpf@$~SSMdHWT`j=#jE1R<;Umj%lQ1;P0FcMF0d z<3PVk`{~KnGVn#$tmNu&1*jf;Zd_t{78NO<1D|slP-EDe+J&mos86f&+1XKmem%To z@x6I9=GcB{xG3Tt=H9MpVdwi0GYb6Lq@$M$MLH$+)>rdFLBRx<9jo-QzyqJx?OwC7 z$efKJk7+#?Z`VnC>8OF{_3oegwlx;dljaqAUHkw`^qxMuYp@*)r6p!;>{*QYGL=QK zO(163@dovDkE8LtrwhQ`G1MP5>vcwa3u^P;$7Lhik7_k*x9_id3}FAqd^Z0#2+RD+ zUAVCZRqb}K`OL3@YKE^@TxgR6b*l?IuIao))psYIeLaNG2f4b#dsePQ?QUe4{!D!WCcHOc z{EY)Ot?kMTV~+ym@f_D~ge!utceyLZb6Y`spzp@>hc1AoxgLgZ4K%^~rB+Jnj@ID) zHHFu_TM-D;nKf~5r8vOtcUG%a6oIPL_7=^$lc36C*v?>2JgQ?n^3`EqG^lKZ=W_ea zKm+&El4ai)gEx61BA>YLLm^qmm%p6+@%+eRLRrzeSe@f|+~mMs)OSzdt?%<1sJ6m< zP58qxsD9&gi}!LyG$Cv0(<#{q8WlDl+sC7c$}cHkzE1|IGwKivzcmMH&-*04M6V4s zRpfG*%(g`D`7U{JZt_R9I&8P#{Af_~CHm^<#4Xex604|{c@A?*w!YXo?ujOLey(j( z{t6W*+&vA3%CHXK#OF0qJ=h`Q_qQhl)?qoiW@OC+xMFX?+Cw!N&|Z1=wiW&fQ2yR< zrb=rS7EBLmZ+H3#nr|y@5_)+Xn}u(+6NBVp!6hmIwQ*V7({e4f_Pr~%cW^`Vnq7}m#J0lK^di>ESsOpZsN15-<8XDQO8(hL7{Urp&9!}vaGhhtD`le# z&_wIXLcshUI@Q~WNFVqHH=Q+$HBo;A9U|T{OIegaJGMwM{$_S)$+vSW<8cNEkMG%6 zlfVLXc#IZGyUvDU6$|8-n2JChOVICpa{`*bJX^T1yc4cY7-G8@w*xwQWUXy{?+D#q zowfh0$OzXYvdCsHaD-AaCQJI4U&OXQel^-QT*c=3&AFTIo4}>VV5&({1YG^0yhoGo z1cXg{dCJZwz;$c#yL)%qLlf5Sv)@H+pwp9Kt0Atda8p8C@cTkH=&*J1C;1KAp&fJh z2J@HR(2}F?ppRKQgwcM>c`FgrVc48su-FSS964h)H-8xvyv=p0LO2M@sP6~}aB_qS zjdRYF8^45V%v$bI7D7;a_Ts#r2OpvAUFYfd#uzDFMaOZDJ+*>>TR%E7|ZaU1G9e4!Lv+PX}`SZNt^#ScH}GTK*6-( z0E3rWP)6Z4=Mk*|sBrxIg}9`6s5(67h5fCEwCfekk5uA;0(}nD3~B6-0c;E}qzm!LY<7J&*lRy7hpTiA^=s=ZqT7 zOJRZfht6o~YAU12caI#F)j46M%1)U~$t76s;-*?Y*~3_dE6>-!`!$}WCcJ_7x;1Sy zL_EC$U4jC9eO-J#wuZR)1<>voeh-o;{dkbqHqSqv5dQtdF1H>3s-J$H--rKIKK(j@ zULo$D|2jeJ_v_3&@vl<^eEdB;{#7kFee7R_{2>AVt`qou=wD@gUVee0zQGf`9h|; zHx|8q^SsYJbGFn}Aw{;&UoN2kB_yNPTZ(P23$zWX>d#5X{ zwRL>R9!LA!oK|jro42^RsQtbe(oz4jGkuxl8O=YR(fYHa{bxt#&yMb&9lbw0`oB9| z)D@^tUjn^1eGT;9^hMBn(^tW_g}RTN9?ajbL>o(Xw%-qae}LYZ_P_c+y2fP~m{!YW z^zA46+m{x{L1*%_PY2;cbY(!(xRceEoCi8K9c5wKBZ9_jtjlt%pFjp3rTenV2u(oA z#}d~X!IiNm^?Uh8{-{5+lPmNTt={tZ)0D5Y`h}8OT+e9r5=^&+9vAjI;&aEG)eTKY z^2OJvjukDsuo1rAre&zl!gIgm>E*!_b2HYKQ~ZYAc~fJs%#Q7CkjA3oai1^78e+rf zYF>0!6<%)CyTs~O%+4y%IZvn-wz{CS)n%Qv9FL8fnR=x)S6%}hU)_|r+(yxaw~{z} zhbm-TiyCe| zQQTN2gicMdXYs!ZM&dh;589~dfRCs3at~E8qdwtUfljHHppXCVD#z~GsL}ezmWF^P zaMISN`K!1Z@Zd2#vm)mZ_;~4kqgb>)>JzPPTDjT;^az-Vk4}K$vhycxKR-v!J*jJ*YSn4uWM<25{mf|4DzC%On;*o$yD>p~)r=-TXL#`4 zVni1%Bl#C|O^kjWo{aT;yB@T^SXz+0T?J*B{=B{R#Vlkm@MDZKO9ga=v#i;2;}d2O zH51&`b{I0YfH3UcgC<=Xj_Go?gA5~&pWV0hfZhC8cSRz$fv#O0zDM?E(dz9~xrF^` z^(&Cd{#;u9b362C4Oq1+|8tk34EQR4b#!aqGq6-`qvo?H7f_*NLzixDj?KRO1^jp%Yr8b*7#h%6XuLWo01PPZ=2*Kf8kHHU zGdxdS56iqNLiRczX4pPgTS>7MGA;e4Ei;b?OL<8#i#lob`s?z=WFeCQTezmcLRx*8ij7MlvW!{(J!F*+6j-7c zYg4=!nKsmSNk}GwR`&F(qfZti<87_&8a~6QQhrfYxAS>$#M?l)DgqHk9L-0PglZR1N0(6fbV6$mERa~uk?`}P}7ZU<>E1{9iXJ{AAkDxH_1{*-O$N)~(qS&~6+8b|rJ?O1}f@+-USJ_UTgc3ad2c(;7(3)PS4Xby`f$yVF?$undK4EFn;;?)pOPk zs3Zt%uus1NUb>mY9gAzE)t_=GcDM%_uFn~5Weld(_gZ>nT7mJ4IOa5X3c8I{T?}{^ z0KvLV-Xqn=Ky{bbO~bq&NW@+Nhz-911z`Q*yvJFHdDq(1Yqk({xM}Y>YZ!$t?yPR| zE&GO&!#cO#)sO-M?{6^-Ml_=d)$5`H_bx&P_f;#*jD*nG?yR(a@1~^ai za6JRhzLz&!yiZ1KJ`YYkJ^T)INd@L-EPRBn9A!OmUmT(h^{kh}0+xXf8VL~`XS2}Q z>KE&_fm$%pC8hZ5p*0$6GvqBg%?hqW^uA_IIslx$$Z+q^wg4YA&5s+@XQDBC>7Usx zhP3+Nl1~2PwEBSfLz)kem)AZ1dgy_b)|Wi4*E>z_=U?v^c!E^KJ{8r|Yn_ zdy5|EcY7GIUU)Ouu2nVc{cbz>xM~g)Q&t34zx{J*a+4M0O8Gjs;b0HuI@_}2%+4$* z#I<8UBxM)amRKNHl%bD4zR|gQ_~Hmw&pbL2?7a(eUE;EOzP=c9U1V&!CdCMacxP<{ zB8{NO=GdI$s|}6%;z5Fyk{^2Mn_`f)-r4Az;*XREK8)aX!HzQ2^Sj7^}u+;my91%B53$o$}NNM z{NTD*u;q;?Efl&>tRv@#FRlLfM+&XpsjTPXFIs(0xi8liH2mCMe{5GZ(AaOqctI57 z`4uTaAA8mzdwIRt&5;*DKXa<><~<=`N#5nA!kR6hp7&%J|1S&FdG%gq)QM_TA;Nk4 zmKqD5&tC0l%PEGL<44OZ(m5e>LIUrOohf*JL;Wwoxf7t%^XtRqofklbldNOpp)p#$ zgS5HAC}uuZ7TweR9x}&l{H}QB3!eYU$nssB73ki(o@4Rbc}4@_d|uLAyHJ(Cv`Egz z?BanB_HiA1`@y?IuTHDB#TO5;IGyX|u>s%IX6=yia6tFZ2D)yW8bR@4d1n<5O8x$G zqeWMS(4_SydtkBzGV~w3v&nfUX7IW45Z^rk?nm_2@R`ej_-2y~fd>4${`rA)V>G!6 zzcgqzq19`#^gPtY489+3a~W+w0fvPJLKo(vZzdi4Z?Jv?=7T2%kLAUJUWK9W1+Py6 z1^swWiH47;T*T9|f7e;`-ERCrILmz0e&WT&+<{a$udZ@oqt!;N*iqBhr1}6VHg}y` z9eDw32n`4SnzI*tH}SPwkuLz+UHe=2eT{?jKCm>X%h_PXFM29+KIKrc$@;lgZ!y*o zjxgJ{djaTvZYz7;zZK1@lFv33U_w8sUu6ykD*7@*TY47wTCuU&p=I{@OVY;XUu$Ljfd~UbCA`>QSru)qnI(gZLsBa zK6rHYxS4j|D{$e{-gR%vE`XXljmu9k&ce)xv0~A@amZ?2RwB0B88hzTyR`fAK@>Qg z8~-dx2eNRbD?AOHM6S0IUtA9<0{t6!4Y`!xBe`$&gFT|TsC`h-ug9eu6zAuxZ>%u{ z4FN3G?|64Yl~&QRl8aJUNy;iYAt4Yd4i{aR?KT@~FCUc8Wr|0IrefWx7voXGLvYIV z$!@69VzT_{nkQIEdePFaV!lvu^a{@<7Jpj($0yz13ZQ3J1#|nCNHlx1fTTvsS@dR} zY3Fe2J;Wa4WT_M=0cw})PRc#3D4uwqx@?@w8FZ%j*yi-_p^a0@&um8_kmBnZjEWY3 zu2SxT<60V+&FG7(i1Y=>G4l=p4V>MY*!<9oHcoqZO(r=|ipQc;ufMMcT_x5x?2oC^ z>f0^lW!-<*i)HQXK?5nZndsGO;N^4R*Vp`PF!t=qws)O@C}>vHZ3 zZJa`GXMQY0_xGXRkhGh$d8Tkuu*+t8TvfLh(Z{vVbe-2$O>W>4x+S<@#T_yk@9ve> z-wK?o`E1X62Z3Q`Rgbp};Yiy+J+OjL3VqZ5dD6@OBdGcyc}QC~i4B zwd~DO$bO-4nns|E;7D+y`jYGo{Rps2a)%_8Ty2L&iy}0|5R)0Tb(Q^aH ze&+Zt#S@*FT}{FC<{LRIa{cFBtL@uB&$)~{Y?by#MIAgW#@72$N%PmafcshT=*=bO zvl%DAM8$vfp*`~-8#$J3pFFby$Op43%09~`ytF?0X95q zUJKdy*;mhVSc=AG*|3gA1cSTp&w1v+T$Cry?jmOi|EL$bcrE=RWaF#v$J?GcwV!M2rR;TF82V9+3ANrbEqQmEDVqIfYEeY5a2J8m)z zzMfuVb)@+n>a$GdRb>8v#)NOK_jb^O@>jAyAKv&0%kLEb`UoPdCoAK$C-NKm`o1(@ z@Y#LPXUxHT$Iu;(F`F*F^h23eAL6^y!~o0hXin>LypQ$fp1!HD?J4M~xM`XjXAh(c z2gf!`HKKy>;f}C~E5$whbNQ1O+JcsXwp+DETakcZYo5$656~Xme{^My8@l#dXK$p` z6o@Quknyh<2fYQMwcXEJ(d7PTlfMq6K}K%X@}FN?F;mm8@UIG+!L@5jb82~|QRKC5 z?j*x-T7A>Ho#jnvGGf(&xOxv-eb9>SyI*6bk7~^gEk?lg$-2m;IR_!XTj`u<>G@#o zi>>99mLz1(WcK5Ncqi&rmy5R!wgo@f^E))f-(sc#)sR~ZBUo%CGM;7D zDAdffQwp1vi#4yYJ{vr+91CVZ&70fJ zjh~uf&2)LbO*JD}kf}{V?Wi>9`PDDM5c9gYZQl36hUGuerP-Rct*If1HMnWv)QcQQGikYA0hpX`ZZ$Uf3r+R3hORYQ0j8R=?IhQ|MNf5|Ja%m_0$B+ccCO5L2l5^# zE=j!;04AjzuS9o$p}n7YA>RG{3z+(l;;W-G7#r!HjO7T#FU!A@d?B)d!xNFjM`XzgTAy|mMH z+Bk9gtkG7b)sH-lek(?+*Ni+TYe%d95MEqk3S5+5m72WE096a*)^3pw1FClpxMQzk z(DqqaB!1&jAb%^guStF!6v*bKRd$Jj2*a2AmG3@432#ckc-cYp?M-1$JG_a?L-yKa z6qkW=*A*fL9)_U*j%a&U6c0K&wDL)-m?xAnbkJg~5NK~G>o0HK+1e709 zKBl~767**Y?Q>jEL>s5P##0IofGaS^Gq!FCIG|_a6tr#@g&7yU+k*oPN^+K3e^N4(IVw&@(BZWla0M z6wlod!Bnv$;IwI-#fQF#;$PuL8>i|&f%aZgo?7#6#J#&SyzxyOXxAS-RjE{qu8Y}@ zS(fo4S35=_#|QnO&+h!UR*uz}K`$~#$H^HoG5gOupwEFB#jkeES-%uq=W`6Gy}1Rr zsjF_XyQ)B|f5*KmmUdsMciyYCY$L7y@LMZRV_JQQ&}#mBV4h6!C3DBy;K`i@Un2*n zfOM{8hkMdbP~)~ET;skRT2R;gY5w41@O6Jq!kzmS;AX|`*yyTZ6l|$~H?zeY4Mh&| zWE__UW2`SeZCqJ^Mn^q;l`mL>kvBVT;s8%{^JOEeoq0P5+M0PbD!UvFMa}Zf=37Rq zU-6lT!3vFzbf#_jahg_ttGeXpJlZ&IlUy8{19&dqnGjs(1y1U%*AofSEFP*j5u3T( z3v@)pK5<#4LYv2pf<=UUKt~JnhBYd;(bYiZ#~V+lA*b_KmGjrqzJCMa9`C%-+gjs=b_;tMuq1_5}^OE z!SRZ%S5aEb`8d4B6GfxT_hh-Q{;ofJmeCRnkB{4XoX$bRg91}YBj0KD>svz@GHKs; zk17ShUcjx_`?MmU0Yp4zluC<-#jVT-okE+&Ku2k{!07f;B&gl{n#tG+bk3DY{1Cec zWw->bEv>3Y%il4s=UZD0zF*i{T>8iWP3YUt%Kdp9GI-7x-YDLUrp`?=Zw$W(GMrwo zQ7`HPX5Ydaj%)JK>Tk6HZy8$sQRR|J9a_Din0l=+nmRw9E5u?GTGKt47&e-YY8Cjl zd@|humS_e_@6r?pccL#$G6u~-!o%xj%mN)iUH7<_&#)&rz3AEHiba7S?(y-rOniq> zuX%QR#8?&h@$mZHB9|ESOopPqjh&fA+5gh+|!hnBIszmWjkZB!TY-s$3AeU6q!YO#A@$-VYqyX=f>t) z>V}s5`PZIbEHYe`#`KhL%K&-Z!a*0d*phoU4AoPY{gi&Qyb!LGId@7>z|exvOU^l$ zhtw71e0OgC5Pq_-_mR_Ak3Hr^BCc-9d+x6`=)86`YMr%zL5Ny<-G-Iay9(NR3l&fy z!4DFspa&JG005vC*69n@WFeR=uu=<`B*KAPe-=!Z!&@kpL12_K?5~J%~aDJVr`G71$s_ z2ztPP3Z#*s7d=2l1(QhNhXiTp0TmMbAb|=JRG@-wBrrw~Vo?DndT@veA3#Dj-LKXC%-?f>QJV5*6&B2WChRg$j6(-~C?OP(%fF=m8iiSV9jXl7Jr-oTCTQNYIM}s7Nr03jB~D z4GE~wgQ7Em(R8YxO0^fL_8irorXNpxbjPWq`4^aOTR5nemuk6aZD!ORTl1OLu6m}m zb_BV6X0=25OJ`cWQ&jtWrZp6%p6{XBF4B^p-}y7sFvF4%JbeiKLIa-HY*vEaM~l{X zKC^|!2SdBRdCfdYt0<%=9;V9~z{tq+1j8L}s26VVT*a9MjXkA;qnt;vjV$BXB#RQZ z&ap{~|5-It&A?C~O^-lKAA)j5%stwR%^=r>#4TY->2S@XYU$i$dhnKZ7-V^^0SHT?szKS#}ZqS$qN;5u*Y14@J#y{s=Ye0u-vr{x-DJYBI~vW zYOA`h|h;P=Rrm^47B^^j2-zp4g0E_o17W!y&h%{$yIauPNFn4=RTGGPtlFTiP;n{r_&^eC9KH zvda|lOsfPHca<$Nv^rV%yt%r;QP90G^F`S3)JEOHlBy>E?j0j|m4E%vu;Msg6*Bg@ zve6B?R(!bfK)(y^=}jtsIl+OPHeBALx-h6p?8}6Vw+0V8zB7QUUNiD&t@4L1 zJ`8ii1YAK>)tr0RWHXS5r$>|z-xciKawp(W=>TRtz@xtRVLe<`u=PFbNHca(y|ZUO zPd;`Ly!vw7t^iwp=6javuM18N#I#v|i2x68nk{cG&VY8R!y_$a#ZdTKT>L04_~^`2 z9Kdt)E4DB{KdMu562+;e%*B^nz$0~w(DXa2pl$H!6&tVFVBv$pnog`wp)=pZPN8Us zw{I}4dgFftZ{IriSn<~ZyuQSNA@pq}I2UHNyLPc8c(E{dU&A3|=sI7$+9&!El&)N# z<}Nh{ZVkGqbV2_qw!J#`meEfhT{n5@6Dhw5l(~(W+7?>D^}?6jcr1OfjBIvsZqPTl z6&$tX)2+gLXFph)p&5_&R4?7SR1IU>JFIF><-+Km>LTk7UyM$(567CmSq>dr@=vb% zmc6lU-heHv@@)m?_<$n)*lIte?a24w?nhjb0g(0^Chn%4OjtoG z&Ts6oBJ_Lg7<+P|JdV^VHIa%uizE35cky#ca;aA=7`a>mFq{K<;tgQ zf#=znRIZiQ99&JQato6_b`;%>APh? zl0954QOABfP#SBfGdT38TfyLmTfNGjD&PdxCF^R|wc-Q@fr~~>t(d`73xC-Wffwxv zWocFKfyy3oL6&Q6p#zunF`2y!p-%ZW`QmSfp^KI7-MZLHxXM?Bspr=jxJYr*zNBI^ zR2u8CL<%e6(oF|CZW=GcIv20=)@|U2E}L}9$82NpKKsq;*$QfS-4H+?>uQrrY;8MxdJAUvr@6$7Dj0g-f=DOM@EfB zX6Y5p&Ul+xl~UHlE;L6nU}vTJ55#n8yNGMF7^EFny@6JM`QC?DWHKlsM*Hx&od;6z zHg-+s{Cj&4L!8LKoBYb+p{}Mwd6Q2e?KuDHRo=yw>9?8!HPaA#Xrat5$@xIo$CHUi z*~I9*N$9n#x)XTww_8(_27z+z+DJtR=ucJutm!-o9qvr|-Bfo&K2sAz8nW}y z%DilT;he)DuwgJ_2WuP%EQy1Y7eC@P9N#xP@7)0o`{A~%?m}=fh{>W-y$r75SXHl* za~R1L`uLryQ$c4}T`I3gKZG4x?rm)-{(z#iTt=U~7X?YNDeHC1WuZfh=)u=jx(G_f zdnd>oK*^;qLiCx3kg0FUobn|YX?iNVuzW3m``L=pBbP4%(Xp#il|EI0y3ltoyZl-4 zezx=6jI8%iQsOHur=Y#)L&=S|%Sz9{5bfbb%lgXE_DQErIoI_;#pS1B@0W7n5bc_& zZktQs$b-+1O7_l2Z(nwoE)S|g=kLB9(7cg@F4*s^myP!^a$M2*&^X|pQR?dKoLci< zz$<1%TkGBc?3qX6OJ_YrHp4;^Or1F(=9l{8(#~EKy*TX1zD-_8Qr~(k=h#d1sA_71 zvid<{$g&k}>IRSA>gJxQy+UjCa?*L4uvXPo4|&gZSgY1qE^{Xr45-@l z`Yh8a81U}8uY5`&^wBfW+QPmL`e<}ss5MK%>)Xc^)gA@o^~E6Z=?QHd@hy3N^rSG3 z=xw-_yyr9aJ-@X}HqZLHO+Tp9(dP%M%Fu%HFy^-0kLeKFWwpV!r-{{ZM-w4o2RjDA>NpFOXN$A zC*GL;DxTjl5Up_tXJl2;L~9&f~8VN6@(sjAg6`7xr%Mf#Z!tFCUXsa0P|737j z|3S_t{9ier;r}A%!%XFT8fNZ-{-6KHW*j9R*0wt_OQL^w^|_C59d_DRkt0FwpUD{o z8Z(dZ@~qantrwCYoP?Yo+;eJUexnciv&WJYp3@d0yFJVAikWZ#J`vq zFAHe3+%s1esx9dqf8Uu8L&aO=V^-D|x4rnVO7AHX(1{NoaPrjymixuyf<`~%Wr16s zmcOdRYT~-ySnu}0kaWtK7aFr+kYin-w` zj%z$_9rig7$Gx#R`)kuttatDF!n9;=C>Vdmx;2RfI$QN+h!||ZvJPCvdY+oJ_b2Z! z8?29l8}4n)&eIFW+OI+p5Fl7@7H)$_>LPykUznH zw%A1Rr0uNi=XlPcO8d%&1n8ct<-z#H@IR~m>EVMb_g7|yN#TQLe(^Vg9%H?-#yjGC zZcsGM>yeUSJ>1mt?6Ruh#6M^J=Oe6Fs-#;9i?QhL6MN6=oQ9j~wN8j;W&UT?KRp~C zda7ILM+puONc2ghec!8>PJB7OL<;iWOpQOG&<-8cU5+>{KKIWV|M>{3KNM;*`!axe z-`6Owdp*JusZ_C9xaLGoC}tKVMDGXnY;4{GqYu;7EL z86uYK+wj48kydA_?D2-tW~bIYf}m^V-7%xnR_JMGSbbT(AGF13=f;+69iTcgVDZ ziYuZnPf3nIAGv)WEUVw)wTWu>=L1C0M4fB*t-Fh$)y?4mlUWkbYC-2s!$@tccwZ(uf;_0-gLJ)eUSf&+Mgm$Fzd^S+zr=%LS$Jhf z%kFb_AJHwlT>l@l20=}C(mqX_1$h64>xH*27UBJNrT$stU3vDVIr`Oi@HoHNW#hv-9NN3LI5bKhhv zL-7GS<`@i`cR6S`=sW%p;x37QY_X2$Ct~z+88Ur`pnCo z?L2;Xoly$Y0@n=SeqJ$dNh2Rp)4v-jx+WH`GdgQ3vXB+|@}-7-n%E4?A0M-NZ~F_n zCXcYXn|7eEfwE6$tq!8aImW%g`Rv#=d00hZ!$GiH%{NwrF@d(;`M8pK&n9FZS-DxW zkpo#ASk;&of$X<_F|bj8<@ni^E=crb z+Pdrq<8bp5uam3GcLKTHl5XvxB4FOJY+J=E^YG>+-g3(r1(5!IgXj_QDWmZ(RqG~o z5|Plm4})J)bC7h7?xt?qclGK!JMZ32Rs-C}&xpkomm$rg62l{Q&*17i;qF@XcM)%C zZ;(jVU7%yZC6FSl3SCno+wZ8oL36M7-ZZ%sg*0@P2BequV%l+`mXUoxx@zOzhLAj< zbs=#dOC>uHdLWz~y7xK|wbLt%+oKEhHD+0+zCB$$c3}MxnXiI~bx2t>ePs^T*O0Kf zY6XpYGu+PERLRkD>Xt9^vmvzRRoaMo#enD`8y5w;4#ZZrbKTilr?EA!Vx8_pCK49m zNV8_7Ftv)lN^PH2+%+$u+En%yq#fVW zr+cw@^g>J9w>4VD_f_1}W%uhE4RtTwwxg2UsPFQ}XTqbS*kj0FuGix%Qr@jN_d~g9 z@%KK6xqehZ+Hs}oD`{X6@0re0x%A?(o^mdQ(3{wQ_}!zjBUgdM2Twbtr>ha;Zg_1~ z^*E#*e`{NtiX_#0O&5yy7LVTFu(V#$4RD2{`ws@M1A!M2W#8{Xw1&xUp$2~uve?|z zILOR~xa5}0zey=C&MfPFQ!V?txMo2X`lP$C_?`M2vGOOEj0WBIcWyiQ5^P(eQFZkQ z0-tUDC8T*$k;Bl_raF5$(0fnSB{@0(XierWx+Z!I^(;s@9{;%!{zySCz(?}!-4nYu7<%Z_A_kgc+$Yp4(W ztUIF-W^If)g&c&eHT@wcmrZ}Z-D%WrYPCIPV+Q&*wkbfnGX_0kQV);WDoktD;^T@J z(vCY%_Qc77M~pka&wHLrYj=H<_WJq%!@q_6{cka+|3T*8|NR|^zh4Z0zZd?_2Y+Y6 zzcbB#r*fA=Rxi*Mx|cLo^slJNf;$^ZSD+Uv$Na zQksZDM3fz($PguE=4=KAqJt6ris(*6FCsb*(PxORLe3|u7*Vr`3Psc-qWTcEhNvub zb%fH$h_*#EDWWA24TxwrL~}tzE1?uKqI403iYQA&5dxHwLlhXgazg26ME4?k6+)s5A8OqqH@mgApx@Xi!8uBAO4;YUmmZrLtRI4BKi}h8xg&Sq%-Mi9Z}gR zb&RN5M2#XU5>bEXsZOHZQJNcFDnN)$l4az_+5N+}}>7g45&qC`@%bUl#hc$EG|bTguN5uJ+YOC()O)Iqwc zN2zf{MI-7LQLTvDL{hm#DVKB78yT! z3YgLniT+1)JEFJIbuvodBDxekJxo+ZN)03`9$kGSsu`tr5tWLhj_DdB(FQ3^k7#j3 zLnGQ3(X2>XnJA8QrI1qih%!eMHKK$O1&gGdiT+4*L!$Q)osQ^hL>D7^7CjwJ)JUQt z67`R$c0_HXR5CLDw3cJD8*M|G?K^%Sq8{)3FyB9eMja9T^K(y+8}$S)edwqI;xjk?TReii z!rVfrZ)NtGOP!X)yLHH+x6WJQilAEFWivw=HD z${e{AhHYCD7G@0ZhM6mmAYJSmahc@ zW_@=A?$`mDTOz&|Cgx~aubQ;^mAgf1GlCwd(roCz@!=Bq<{z@@`JEAzigVZDEUy-znPY$Hk$XRo z^sCSjHT#GZ%3fRd+5`eV2RAN<)ysg)rI4udUSptCJYjJ&<9d{6hIxjCQDf$p)8#(~mS|MxzAAi@I`~ zPlFR3f*P-GyQ565A5jkn)j(dw7Ay8#pjL$UFVPo0Wpk!LAM6tH#?FqRqSA@q0~sv~N{mxWf%)@TF!m zuTB_07Ph=y64`2shL1R}5i6X)ELX3bSt4nKS?_G$>(gn7CUWnh^sDt~z^6Q^?Zh|K z@w39v{xv`eJzZs|*bKpbw#5?r#!}JNqPY(Xvk~%tr@cb)>S|zmnV(BMkq>N0tzK%( zaRjXiwh1bb!3yQG^^Xa7SVMl%PX(WD#G^M; zv$%aZ_F8>DV(( zEl_GX?h9xlN=b-t`kqQXR3Z1ZCAcC9y}D%lA&l)Os(Td1I&Y~17SY(H`b^FMa%cr7 z^F6jkKhj;+t>d@{>MYGI_`c+TYPV3|$%z(FS|rc1Gy6G8Lr__M-z8Lgt+KE(lm%|o z8oU-PW`Ngfh=fbXo(7|z7aytJDS@S4AxHKJgnkY`7H{ff24gSgA8ce$hx5`meONgr z12yBieVk(%p!~OLnYa@XQ0v}~I}a2NL&F$3<$_24P;Q{Y-=E7K{LEZas*`sBi!h`~ zUJs$k_1D+U?U6fz7k?UkaO+hDmj6{)xNji`*2?Pn(0d>R8-|(YH-Em5<+^ga&PvKAx{AKvu=D`SD+_dy_Bl{Gd_1!^ep1uy$cAj0Xzxo3Je!GhVt=`mh#%jIasu`giEEHV!r&_M&| z+u9EI{y;za21l-)+=*VM#cLd@Ed|dwHUvC<-2`48pI6-zvJuo6X?>8+E(PUvw%n)U zo3yE?X-1v!1k(lFSvSq z=fs!67VzQzF@Ymy>)}SlLEYoa+3{NCEa-5m4UDd79jm&ihNYhRrQ5e%MuS|+x@|Zf zj5QXG%~I}w^HPi-IqoQhnrF7T9RAb{75vYYuAUl#TF2jTs|5K%!*dIbeeEZpT&Hrz z;nV%#XZ70$W9OT&2ruX6CnHQ){v?+L3pBtg4EZXr_PJt(eXat5`wg&Gv}4E_`Muci z$P)LQa1JcjBD&CVu_YR0v#|(xHVTD*-Bgpf_Yum+4sRRG9D|F;hF%C9!FZO=HTKo& z7ohgCy&u(-Q=w{iQ|FV=C!kF_+w6=37LRas zbViQi-RS%v#RAf~K8n#Jyd9mLqc}Li6%s~}@P35dqjPwKsiXKf!W$BHkZ^#6=_7m| zVeRPL9K|6LrjYP~g!Lob9%1n4JRQX+64sD#gM zdxXCuJR@Nf31>(#gM|O1vwRenNBdsl_MO?1*L`MF-haB&TjKuHonD3er>jXj^^bG4 z{IGI${>Qg;(x!T<6H#IBA6A0O#S!IqG7+&f5Qw6 z1oa}=7D2EGPW4}%PmUMBnMZV_i^8+$s1?Dc2m(cLCJId=uS0Mz(kB=eL8=HIMNlV# zEfIW-pkM^+B8V2jtq3|rFerjF5wwhsi4o+B!nerv{8uf(&Im$Aa4>>){rkLs<5L7l zBX}7>#R&HG@ALoNr{ijL^o+vD2ogr{E`n+i?1~^%1ZShLG&*8Na4~{@5sZrFL>tJTv{3OFGjt6BkuR zZ6Hp1)7L7B&?*Y9Zvc}gf!LWB~!laQK(x+DZ8AyVmd zDMgAB>XS}z5*m|`l@zH;s8d3a5*n0{orKaP#3dnE35`m~QbLIm;*-#ugv2CdE1gm$ z#3@CO(n(N4by9>TAzlf+N=Q^fl@daf(4K_cBqS`MS_z>_Xj4Lt5(<<~bW(&YpejS>Qs5VeGkC8R5%RtbShXi_>EN|CmNnk57* zon|FuDn*$RVw4cLgr+5AETLQpu}Y^;2}w$kxrDN%6SIVVrASsfl}Zt&gxDqYEg@+M z6-x+LLaP$;lr~HJb8j*I?e$Ohf9rdi|CmAkb$>JSuBfBJBI)7jPoPUk(Eow+B=~M$ zZ+Tx%1azNDTX64t5a{*Eo2skp1AVb6ej5xEK!4`G`VW^?2ntBBK02aDa61Z}BN!Y( z+USTNh5OObJ%Zs8q>kWm6zWFMK{^IVkUk2}Bd8r6o1+joI#NjRKnnFE*d9Uf2u?@P zI67)but9G>`4J4Q!LG}oKM@Q)>G?8G21Q{gwA06c*SRRGg z5oD2$A5thG!2${5M{qrY-Vv0MjwKSrkirEC`bRK6I+8~rjs#bvqlW||BuF5I_YqW& zppOJ&BuFB`3kfPn$NngUk06l*ZzQN9q_9JR5E2}aj`k5$l3v+w%^(z`NO(iS4iXNKFnxs2Bdi@^7wH@# zVG1cekk0y1+#X@@2-8UTM8X;pZjdm5gy*BPc@*nNxJAMs5}uH-frRrT%pPGN={zH0 z6DiK{A7*fd|066PVIv9WNSH;!9}9|_AyxJ1Gj5?+wb{t=dv;vxy- zNO(oU9ukg_&ID47CE+Cr`$#xO!Xy&Dkg$S;y(AnZVIm3NNLWR}9nu*>!esup_P#ux zs_$R_m@^ZJC`!l>G9}YmrbOnch)^kGiOecA$q*tHMMY7OB29+1BBYVXJS3UtWXy0+ zvg`Bt-p{>%+~58FaeuGQA7`C?)?WMU^X%6?`>gl#?B`jsuOw_G3A;zahLNyGBy0073qGB)J$z?M8?@u8GtNF+ z!ROhyt0LcYz!ybH?-TUfL8n)RLF*bPLe5Q?$Nw^oUowmTWfD)A!xN_POJ?wd3H)!< zdBSX-FqtRJP z7wgf@pmK3J0n{wkrBy-w;`^U}AvLlzet2OaaeS5>FTOCnT61d`x!r0^XIKt~yKUT6 zEd9XHYzVEP0CJ%c|91O>-6Jf4qEznlG?YGw@t2Us;f;q;=EPzN7csl^Sa$# zSONWxEO+bB#G)G6hq;Z6T;$)G-7Zr#;ebtCI4!`#o){0bOlaSG%1D5HbIvif&=o|$ z+z8L3(jd2PIjQ5gAb39^9#M059jNJZzN4Bq2rkMw9&E_vCB_%cx^}9|a7`l0=)3FL z>;=^3J8n9%+@&aLp4lZ!Sx&L2jcW+H%V@?Fuw7<~d0Lpe%kQ1wWyV?ej^ z!tPaLZIt#3_}t>OK*`sUaK#!81H``C#Yiyyy2o`M{gDZMB!w z`oGb=f3+=2ZA3}`dxT%L+QhBCj~9)r)xMvek92y!Q!U5yjZu-kMA7&C{CPLU+!2+( zMN+ykM6|AtFO;6HA_V22ckS{z*lq`UXyB|dwIJxKP|m+}SQ2#h9D<61-#}*r^*JEQ z4!RxWgD$I{0)4AJp55H=6x|q;Rqv%SMyaM{y>-i;qqNQWZow{d=%(hkOp6L0bTe~< zEPv2BbmMu4MblADl;T&@;#Ss=Zk(lweY6r1_^Gu~j_}KFPe*H&m~O_)u_80J!5R8{ zk|>aF)5aU_)F?iy$lvHP4Z7shyFXWEHL_}?x$bj_Og`^EOHCQX3A%e6#26f=K`(P> z4!u|;=nJ4W-*@{n7&`PkSTKX-w@|wFE@?ct4b;oT1TVXM56ylwEX%1WMsqG=E9ttW z(0nni)q~<{Oj@y(-T%vJOgg+qUQD!|EL7wh*S%MU=A<%KusuvcGo}?g4uCpHQV@G2 zD2^a0_)I{vB-w^vLNlLNIKfmjXF;*NfIlA1 zJWrfEd&2-td{JdCOrQZbW{Mk+vQB|i!;Vetn_q%7Df-5ug(PrO&GFk%rXskRGV7QPKCw# zgFgRmw=+lYk@25n*j(8A8~-|n^xli1pk7udN~JN2jK6MFX<`o9li@@$X^YV#id%Zg_5(j5I3R2)UUKhVZw1 z#LPo&J1a+?FU43C6iOu9z_$nFkhz5#$$-HFSo3KxM+XK0WoaAP@>6z5v#GIWNk0qJ7COX$cBYV)jr&DxDE!yy}r+pnLo?-lOVp zp_UaW>5|%wR{BPb8%Zl5zhzaH^UvGSwL5zvv#)oe(t!Z6Ce2<{F+k_O!NCudaJ(vw z*?VOv79_Y(U08S1ic52#H9;}wL^T!Y*t?lS1qpz`=aI(Bap90TA=2P@j5K6xRpVJH z_8RkM1yZPJ>JV`vs!W`&6KlS`K%*RWY`v>rp~?6CyU$RVpfQ;Z>ZYEDQ0mQvoRC!# zkd&Tb*kB1D?f%Z#iW_{8A+cvoQ|Pd&HrAB9Dm4N|S#u4nhj_tcd7XZ4q&gTA4P0ii zBMhV_wYo7!IbhPYz}P{cfoUD8QY7NTFvI0fz8C%O70T082Sk5chnfus_ca}AL2a|y zjowQ0s7!Se>1EPRQ2Xf8-L{wlFnc}f))hlbNbeFWo0P%~moxZ|aV9QGb$|SZfOuoq zww{&J;9B$5O<518z}07QdFUPuiodEibdxC;m3RUxv$PxF))gh&SHWRKT#D*8s#g@ zyQe|!&c5Z4;TnVf%bi84V$4bh8X~;GD0}W@uRAhevg~TSamPzACZ2S6GA$pZ8pM2h z)~rg#e?-?YOCQtPmNwka)xZoX6fNniDGImTvh7XKQbx_YcrO%A+(vD~Nfx{6Hj(i^ zII%XS9@OUaGEqozgV_`ukpM~|y^~lO*SDah7@21B{{Io7{1KrXa3aL+{{|7tKMT?S z_vQe^Iat(ns&P$s-#N7Qc!TBP(mHe`*1ICkhvb?or&s~=_n=nwsVIb+TS)aP=ipE0Wkb9|JA?lkwH%n_w~@lR5qMXq=PMHm&9nxgF}baB9* zJklnXCN@|yl|8WD`~|udEw(;_rU2}1@6hows|AnNK5nzqC_zQ?wq+MiJqJ1Ts!9p0 zedt+uQOc)s8u0LY`gd053UJHWn5TYNA7Je>Qo4nAK(|w5-&|!m_%1jmXOfZx>BShY zysgrOT-DK&BvE?EyOM|V)0KCSDblRNmm?BQr^zVC9Qz6^YZWADW_!TagIp~7uepK4 zfT`?Dt2^i{ZPyj43J)NcYc%4fpaPEXl-51!D~W7nUd0%k&<3l+S`{wo`{K3CBZ-*{ zmUx9)*bUWJ0cfaHfS)d^9@0JEb2!`bA>=ZOIKSPA4oc9rSMiFOLy6L7)q1IJSSs}? z%Xuvt)buXgTeY?&LECims%z;*bv1GsWxN{zu zJN0?(skh;fi*LA^a&jlkzJ%G6aQghCd;QC%!z0dJ2kR#CMX{%Tc>T+#p=kBS5Le>?n zQ_3%)8I2UvE*gW}dtE$@|tW2LBQ zrpMt6SWu*zqQ8_Cv$rX&5G%2P)CwOgK8RF8eyZV)>mM)_lFsL<>q&~~z$pEdGjSLkYK~-E@NvlP6qgjCf`4gu5 z(X_qCr@b9ckms(HX5+XpUeS_$iSBF}$aOCoSKrJ4B0WKyS0zSAbs`j19+JRdL_NP8 zB?&T?SnFSEglM6_w5cWF1z!7F@3V#W8dP0$)x;_l!}SxxPPxs!ki)0leZ_|k)SY&A z!$90=DCAd}{3Klgno&Idbh@5|b+TXfsi~2$7he_MFjFU1J8Yz}xwQ(*JLFi&Psm_V z-P1Gc%xutC_1>#W{cdnQ_w&u~#q1wu79T^DR zy-ZvZHK4R*TYP!GF_g4+NpCVw`ZEXkb2F;lUvDM-H_QS4LU;W7#KYLUpw{$+`E){@F8TLfBJR$4L=b!r9CW!HWdy~9?e~y1nWYQ}g!T-9- z;&Q%#+hPmk*UTod*jT8@+nr*F3MN76*Jn1ov2P%bLHnv$0^J!`6{{AzwaD9DTHv;*=TN`FW_T0 zKaaBqBdAbVI2w&>z+2^&dfURS!HbKc9IwN6fmdUkHsvM3OEsBzMEk}_{LQUIw5zgv zwJv7~+QYlRx9gGwFcLJBdf#&l7!PrNu6xG?oP)cs#ZNK;lUnp>R|SFdXWfQa*AE$i+l) zFW2a2BE-`V_86_pvk zCVjfz0jld)olu;R0X+%k`e)jzz#!eTZrPRZiMVuB$w{AiSDG4i#a5)`j3t4lL)0}@ z%zlux$G?QKG70qJQAT%CHX7Bv#4Jixk15Bbj@%_p5xfXqM^|HQOwR?^HhkF7tZxG) z+gFs8q^yR5-EjpBY1MG0E^kuVJ7qM(ac8HCr6T5=nb6cgitSqHMiHrI|qy4Ww-vzrE?@Qv(_(>9->Y?g_b4^Ixki$JQF7-nC; zL@3(Ucfs^zG8COGOy+gqg{<~35AFA{*) zH8p-`Uo(egmQQ+p=Q|4Jwa0~XD5K%V9b8%=Pwr#ROJ@!&lhMVBf&#mOPWEHAK2j>R z0TscEfL^DbC)&NqU_isoMDH0JD$wK_N=k_arLDzZPaSta)%P=vHxGuPp4u1B*vlWG zfq`YRtHH@7UStwf?h>>Z9R3%^f^YK={h z?qZa`Xe{}r=o?4e{4`Xc?483p>ZMzkco8Z{6=5?Vda)CVwiv#Y8!3XK(>Iu|Q6Ge? zE@lm@QmZhXw20=NcS2a$w=K2L`Vp2*6K2`{acYSdX~OG1tLavq)5kI#!CMamt|#N) zT0G<;0yo<2irk{bh&eO9%Ez1~r{z{!^FrW8G1xJ)ALJu<#|_4PZl`N~yw&bX~@{pjYj@bTJF32;SO zafDhs5`{Ae-~00XFxnG$SKxRkH*k4d5-#=WHj3Z4dWQ4$Yb-S;rI0yWgk_J0gq}1% zf+c4Zw!D4x9k1T5tCLaP0I7Roo_Q?D;1xACJ*!&ILe3ac(b+zJETMxWBK1~dwlh+f zXiC|zdS?n-n7<6oZ z!%^PB2tBSwu1SnngjUT}?A{a*dh5;hWts1W=6l~8N0#- zC~r?*P$CwOeJ)$v!Vfvj);*7UUkSG~1#EusNDJ~9^Z1SACSsFl(JzypRG9kEgpO{v zCET8)8|M~D&*s7;7 zkXNG&J8EyO+S;Oyw~G()SX!-O!2k)Pg)j zclleg=QUQ!SjW$wrHK_pq&!NxY2MneuYJ zbIqs~b~90{8y+V-mkH@9dgYd=a&M70Cw; z&x%f?lD3{TfU%tLTqdNaYW<>viH}_=ipJ{A&UGLC3h0-q>W^7HM063mbj3Wl5$Cy1 z$qQkOMbmebba*M|2+w6gdJ5it=;SKTrv_CgUMEO>i3T;iSzMK^3ZPDV^SscLO3?W3 zj9Kmze$c9>asF^ZEaACKNKX+>WD$doVNcNn^{y);Oh!fX<0@ai`cV|k)h21pGT0(2 z<&*CW_)no_xj|e4pjZ(~{pBPn_gG4tcFI2c5JPK(Y zb2*>`9?orhy#BECFVAH{dRlQgF-zvFBC5E28A;rj03Y)>W-D_#K;H|-{3tmY@ReF5 zgk6sEmvnN;bD5ByqG_#|*{05$gA1IH^fmOsZd*S{V`MFQd+;n=s=7hCg@s6m+Du5xN@u#( zQW-9JE)&vIG+CZ_S7m^eT-CVo1n0(LihwWUpWZ%0W0&`zZ+qg5Ml}Yx3v5}@4381b zbg&oUxlBk;L58!J?(I`@;8F0%M;09+@bq%jR{6Zw+7yjy?r`2O%ZO%p*9Y9QAmiUE-PZI;ZAp5%3dkJS zr$}Cb(IM3WmF3CnkjG?Bba|WtaCQy(-t#OQ*m>{s`YO2>_{nIDUFycbzIew;<@=#a z($jprt}@ZHb$AEr*XTZeo2DO9Go*=>dd!2F@*4-LdOaYedf*8Emi>?vce*S1dKP4L zc)?em_Uxzh6iy&BVMX4ylPN%FJf1x~FA~|`JztS=q!4-XoSKhXg@J7ii}7U_PjFy6 zSHL#r6~Lk*@%-rVxj!Wq13pU1dm(>HEPqNY{})Rvf2KHp=<0trUCrox(8K%4qG9q6 zZscza$|9k~vd?j^v)2z-wI8I)k9GbsS6E!*pP7=yuD?y7ep642GmyU!<^Orz-;=Gy zb^nX){CDFP`~LD7i_@CF?E2z%|9RK{b@%?eU0B@g-%wk8=btyc*!8#X^80)K>;7#b F{RgL8KBWKv literal 0 HcmV?d00001 From 9fb2ca6726377548e70512ed9620c1ba4ca7a0ba Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Feb 2023 12:57:18 -0500 Subject: [PATCH 354/758] adding jump trajectory --- examples/Cassie/saved_trajectories/jump | Bin 0 -> 52425 bytes 1 file changed, 0 insertions(+), 0 deletions(-) create mode 100644 examples/Cassie/saved_trajectories/jump diff --git a/examples/Cassie/saved_trajectories/jump b/examples/Cassie/saved_trajectories/jump new file mode 100644 index 0000000000000000000000000000000000000000..b95266ff18a79fd99d7c282f303861e99170e720 GIT binary patch literal 52425 zcmeF)2{ct-95;Mqo-z|1kEIM5QW_*wnj|VyNyrclh>~HSk|JbG zsgyBO88T&lFYdno{{OX}^{n+g@4Mdhyl<_QefGJ(eH{nex%SuR>urC~+0ob2+kbwy zuD-LQtBmUmRFS+`1n&KC_(EB_;g8X_q&7`@I_&z^bD&RXnvzMw$hgud~;s=#-h0f zw4AwXq%ZXvv~3gp?Od}Pbnx9uK7aBX==>^dlCFFKbfrd3zx}EXdc644eq5LXeQP64 zIkh~%PkL_J)osma{AbL;2BSl0N+t5di&7(kX80OkO#E+xo|oe+$BXj><6X6mTXc~G zQ^J8VRJ4)c+^65r)zSpU>>Zu;0+&O{bD{dSlaJuC&O_I@hdx5uE%)~u8&(m#X4M`A z;5#9f=hNMHw2}~)V5yR>_aua)p18eXQ6RW$*2-2Dn-EJQMK+mR?jV+=-u(JiMungs zt}gZtEFkC(K9ciZww$05xw?GsB}p{Xe&{v3$#pP(`MU_6KqQ#DbH^r0@eZWOI(e6d_3JQ;EU)VdG0J&rL)3PTU z!==%p7T?u(!6jKaRs6^U(%1MDaWJogblT&ERu{@3jb@aueY7u_VQ^h?R;&vA8qBXf z#MB46zi5axd6j}x{nS*3%jKy1p@6@a_Zl?GnqQY#RZTGS_OmxlpCN>{n2b-}nnlAZ z*`f^3qftB05zzt7x2VJ2Y33I35lpZ3yS-ELGUOLvM?T`pklQVxkH5_TOrM8$h&p3b zH?$@*%fE+UnlbJQefJRkB3%zPAMqoY15JuEy|vK9r_>{HTjbFQW5%JguF0tPaY4^I zwj$I#P}96^{TTXHS-73)^F7pEdFbnr_yLsCR1jZ=Sr8EKK*FbkgV-{o4cJSF^R9 z!sFiFRV9kCmB@B3Q$mY`X|X4w=Y2zLR&dlKqeaJSBK->(Jj!xXrJ_m)(~TJjLpJrLR9n%`tS!`@jBzGS$Z(cGBxW zk!U3RgPs+XN^RRK`(Bt3XI=X|eEJ!ozOgSov56B3 z={mBl>op=aoL+Ov`7;lpx|8QX*Op6!OybugV+}@x)VG1^rfo`uxZOm&%!*G0&lmMg zGh2_K&-_m$TDea^(y7%|zQiiHf$0jPY{MpK@NxLTjQ>$+lra6Z_Cp@rnX9}$P$eIl zo=sh~L*X$rzdB+%n4t-^LG9j`nYDyri{Kv7^c%#6*1n=KUI!@Oz~}27&J4HpHg3tf z9u9Zsi1zYWtb^wF3nn`g8lcXD<=gqXqM*gf&AexIzQa8~=8h>e?SMOFn_?@bo1k&s z?=;(jR=8E?B%j5qhj6p^k2hm&xp31|?CBtBGf1*ymWg2A0oP9^4NovnL4)#pv37Zl z(CF&!tz35n;Lc3X713+;py^2wm$&gW&^)}fD(^%c)ZQql)ihv87=HD2ie$DTHgsBE z?72Sx<*PzA6sZ37o}UEcAPe7q6LW$%wd^EAsJ<C)|HuJMOECBNqpr>{ffcb^h@XS3i|%{wPo>F~qNo)!1EyXC=6W4{B&$6r99H33=8 z2P&ZmyBDoeiYFA$xmaiY(jQ9KoH58QREG*z?S3oy<-k=QzBeyD+z3_PtUb7$=NT0F zWvk9Rmk*}t>f-mnAT;Dcdu{yE27>cK{osc*MM6aR+s^h|O@w^e;Ag25?u7W8?Z-I} z3q#?p7m|MVBtUIni4xiym*7f<1YyOEjD$jm?-3K8w}j&FZn=-@Muhx;OG(~+M98rx zH?T}>B4qhxj;jCEg+kKZN4DAxK;cQwjm#`sP&^&nb~HN&rC)VORyoZ;g^(+nl21>< zRZfpa&06l0kN2hVXtn|r8Ijo}I_CtYZukG##B~D=Nma4yyS^nj?`5?pvT_k3vco3s z+`NQ*BXf|^^GHHG^Vam?rWH_FFC>&{{07waINdVn`w1#`Iwvj-u_qKp4PHk-?jRJ0 zN%{pUD+&1@muFX+vk`J^gB*@~tO!|-33ayBfc&GF?||!JTW?P{H(NJn7hhXV9w6{RjSdfOq}@fBU2Vsb6@W`Q861UwEFwuD*^3{xd*e{&^N3_|FioLmtk~ z|EcC)*!Q2prM{m3t>c>C^`A0MSNFq5+z~Aq8Gse{r^hCdD z3xdx;-m`$C@{Kuo9O&9oAGWD(E1D+69zA{44{283*z!Oo63uAp8z;m(LU}pAB*ZL_ z{89h)$ss^Pu3tIj{waf8ALqVvq@G-F_%7ojvmR%Bs+lF7rrweW{vyqin|fPLGMdpa z6czyio?NLC=OVq^Er$#G9~Rk+a9YrtCgbPTBb7ff-v9Guk=&g!ha-Rgl6o3n#KQ90V)ab!tvTGZK3?y}9`$0@MB}2UGx2vS8Fv@P zg?J60<%=w$FMM?6OWhtYFddr`I=GoMeto@aQEeNzePX-6-zN9s&N_O-c+=JB-uD9W z`uYn%KrA4lVI%_dxJ`lp-AIsE%d|x)Utsxl7D%&( zLzQPR3(f3uQwqGDi1JW<{d+fkI@6?>PLTg>(s`}^dfV|mV56X-Ti|h8wIK6RMi{AbeqKVm5 zfHtxaH;O*&2jy(VCLu5%F1hkll%HK6RZSS_%{mo;s$o^TC2gIkCV_#`X=^&#IXuO| zI5UIF2F6vMj4Xpo!pde8&ZnYxEP)miN4J7^OYA>5DM_Q6R8z}m-*$t6Ca;6i27aVT zxsut8Q`z9zyK&4(@(pXEu{f@SFE+{ z*k-`BB5|RaF%i%&yVj`6<|UfpIj&f1(+p|$y_2^|^KdQ}O89lyH2qc~YwW2*MP+c6`+9&58lIum4CpRBJ4YGD@ zyN`VX4H9GJ2keib+O#>bXk9um5Kv6xFThQj)^CgO7$bq#DKxo^N2f^dChpTW-|j)N z?Imjk>2m?!pxOS-S`;BHEi~D?7Nsn@C{TM2j-bD$kXBw*foyhf4g=gM*k?RjQZ82I$u2)QO z?=~aX>x6#Gd9y zcbO*XcV+IQ3)YFCS}?w9X;nFCCh}P8*;`B~lv&-ehD#6d#=c8^FV_INX$*tJ_U{8v z3R|C_FFpcNmMQ(DaWp1ha4$?`XvSq_q5jPnNE2{DRF20T&0O#FZ4gU9PYR6riE3|@ zBCT)Vt5x+!{r-IW)M0XcD*v$)2gvn5uHQP*ADtUL4rU0)f0 zId0Pua9x(Tpzd=7G=8}(*Z>B>lQuSR;T04sTBB(xa#t}q* zFyb8AI|>>*J@nj*y+MC(b9Ko1oum$HCcn3l&YiJVA__t52X9@+FUt&1Qpd~WW~zw zAm~11{c1Xq4k{8~#BJbkLKU}kky*MZ=zp(qk}KvZx_>^hItS%~;^+BU1tT>C-Fw=E zHEe4^MT}lb?9mKV5%K)#&7z~Azw$*bxDpHoGVf@}m@NZ5;)fd8R5-y)ZIZ0UyK%%) zEtV+Au?pNR)%NTyUk;cRb5B|!H_-h+lKK3(Pasd_{?fS>G$2;y)5Lp;2=KE-=U%v_ zA(~mLa6g(>1k&v0;kjJ2A59HE2tCT(f%4Wi39eh_iDG^+m!w^f2R~aCPbtUClk1Z% zN$7Es>$i`d&+K6C8uTuWY@p{;AY?1u^dk~CfL5ZyqO9XGYAyW1bs)_Q(mG_M z9!+`+2JW~IMQ(c8xTOYVTO#s{zCIXuub??9n!9}Aev5X#Pdyai1}>~dD> zYeKmdp%)bMe}lMmjgb(!Gob8a$gP^r88pr3_0g91IJrKyfdBeKa{c+ewr8%PQ~RH* zEme#o6j~o0EKeE(2R>@$UO)5|bPUJMs_Pjc-JLdxjgB0keda^xhK<+I``PWY%a1%j zLs`pve?k#LC45c8mVydMbF{|u@p31E=7@1lmvJ8C*zq|yR$dV_)^p|-$KMA-Cyg0? zAEzZ$uAToDnal15t@|_-#`w@*0B4EP7{=?@c)gInuS$)(BV z{iITI{mzY74tbO7!w{E64jTWWI1pwdi1zC?CTVq(2=TPRLI%)lGMUb{mXsEWAt{YOFfD9Na}Y&!m>Mt@3}4N-q-2XBNzm_ z&7~u384Dou2aR&&lEa|B+F_q4p9ARPk?Ipxk|!jrJQ8WA?NRrpLr$lWIq2T-fX-+1 z3}h}+HhUcH3Hs^YtnRtDqPV^OHcNN+HPoo(vURT@4{5kVY^q{)F34AJxtm?Lfi$y| zb({Vc@_90l@v6yr2C{$hg!|1Ip~t~n{b_l4Pp$w{ zJ#vFQ`=X;YwET$`ftiKl=Rd&}{=>UR4dPJE7tt;2b6nB8liVAw-n|082&>3T_r8KW zHX81mw{Q?Ef@Yt+%p<`SC-t9gR?k8;&6;m6a#wQdpCNomDgr< z^l5RdnO>6hy?dZ297q-0Jt0k~p2;Zr9SeGy5_>oENq{^pe*qy8j=f=~AJVPb=fr5iiN=Q%=o|%_P@YOtf4)l%$PUYx?hva3N%lPFLp)8$ z^+^#;#xvylqn||{TA=Y?zU`-r)*^>V8s$&!sgP|f_LX_d2V_^a#D4RUD)2onf834p z8q#p{GgvVK(C6yml9Q$Wpqsb$%>iO1D*fE42G+$uh2H}gh_lc1o0dnC#x3S~2vineX50Zk82-ng}gfuJ3eNZgfv9xg%Mv7yIG(ZmTg z2X)pwRFJ(QU+euwldoGcqCD>F$44#Z{e z322fOAJWRTfXWZ@pIg9SLg4JLL$6Nlh63Kn@;Ue45qw+^cI1A&je1|`-nuANjG6?5 zr%I1!Lgh?DFYeG#LLg-Cp7<*dpnw-kmN(QQ*Pl;LAMynU=xDN>pN`p z@k^nwxuQ7eP7Tc|843i&JZxdz+&9oIzIQFX*C6Qspp>vLbR9u!`%8qE=`dWPxXQ5S z5G_HYbp#q%-bTfOr=GjNjRm*Fh2^f?@dy2lCAqI-myzq6Z)940A=fXfXT4WT&}bKK z@YuxyJlIzOl3XoZ1{Fo(T}{AtI#|`W?n_ES5kbxR-cf{HR??Z_XPu!h5-txrvTHv+*QG% z+fb6I)`OgVn~R$}9owtBJ@XVYhU>wTf{W{>r2+H8Q0aMz6D zp2J{3<$7e)hs#L+o}=|#1RH9_=ZZ3XJ(9hmj#s^IF^ zXRFc&4-u=;%2l?C1E@uwE{E}$4(Q#`7!&pSDeA}xI~5wQ0O~!Rwuot(!__6_2~FqI ziPeRkyd~{R(YLsgeaoC?z(6;5^gj1NQfHK6nB4vtkaOip4`)XU=~s$-%Hy;Rp!(uO zY~}O7;<2Z?>_RIALD$xF&%J)!AV0-pr1{iVaP@R455r9>>h<-ke4yIpjI)sDTa3xW zF)M=hq>Acy<2NWjc?rDkp@Xg_TpNAF!TLviQs05GrR4eyxsTR*})Wu&c%0lc@W_WJ~+rHqf1tW3x+V7pRU2TcLD(9XMm`xW8oOQ&jy#mF4zY zen`9HLdbMdJnByO9-PqS0^Ny9A@9XnL3OT+&`7T|82D^{dLToNG(;y8o;K16o~b0q zh6k9Cey79)Mt_$CwGFI?Ws3QWr!Sd@D&DFGU7G7SiuYat`Da=6FL3&TNPlbjd61g#pI>yCZSC_kugpzZd06dCrrM=JI9ANA^m)}uD$`tL3; zIRwb{OEc_T_<<20D;L`hP4t1SujhFT32mu?Z&y8M2Q4qM$_1yVkkIR>y^lZJgE!3) zYBAeX(Y5VrU21g^DB0l4l^aX-(J0^BhgIf3K+5-fIa!~MqLgp@>=_>>g8nC#NpDlW zfUr;5E+X6;L2~n}+sjs%qEYT{_5KsaASElzaKrUflyZM}7`#HRe{^YX zUf?c3`}BSI!)RIXL~3qshmB8hV}tOuva(a4K2-mS)#Z(dw#)WP#>Ug2ij+ndl0xexLe0)-C~lS-;wNS9uQ2uJn*ws(KL8v@ZR!D#M?k$rJ6`NXLZoCAY}X zHcz6fO-jvsl)}mNznZwVo09AATdY5mN3K`?VHYk=uGe_A`AZB?ZsqC>i4sJeA$?)} zrqXC@NR%tONDn@xc{ep?av`bU9)}{{MDU^9B`S;mG`efsTA_JgA7vkvIdj@g2~9g_ zINou|2CdKZzVc~rLajM85`E5QU??;E_OaM);I8z?CCniPAp7HV*H@8IG;OzpefzuZ zp!KQI#WKaUs5P6jtf58$4Bh|j|HM5E3=BOj4O$-$=n}UkjIX{8930_k#OPL1RF?!mx10IwC874C!+gg#Fu> zJYHilUa1C_OxuV>i==}@?Nu|XyWNWWOoxLdRz3pnFE>8;%oc=Ls*Y=`IOl*K2J7!F z*KNQv-GbX;NjJcWXKz>RUDFTxOT@e$74f1O{-}_Rj%JX?Y|FN7OBB&ujhquZPZD}Y zvQ7M=vmKoX@LqHHLJGP5=0St*o#gt~b4y>1k?Y;{m!?~h>#a4uy|e`CVm?goR+pn6 zMQcmImFJ|6qGj>fJn`UF^rx$7|U*AAnTSdN}Kjx66$^xSIIvTED_WWSK>?VPh0=gu*?u?e(;QUyV;8_Wu z;%1uid)nuQ!TZtT=YBtw5nK75Q_*zs?g z&*Cpz{m<4BKqKGr*3A$35J#A~!Rb%#)OCcXt>4BZ4esIJ--ABA{+b6)H_`NsuJZ}J zQjkXA6qvNlM{}z`F^r`Kqo*I4Zb(I5P#l=SK@@7h0|zH4fdstJPhCLA3)6VPm$HzG zgEu(Pf`cMBfI$s5Pyz$gg?PNcjTeq73$i%CgM%?RaDsyz)PMvfctBmy#|!0n0h+R~ zi-SNoV1t7zI1oY&T2KNE)L;N!aK{VTlm%iOD8fM<9Du>W5^7+B5`>@z4DiA|UJ$1& zG~-|r4*cLC4GyT_;0HBOK?y40003TC#|zdt;Dm!iIFN&bF4O=CC73}CJWzrJc!3@- zeB+=L4j@s3J(R!J8g#({5**B+1Riie4hPS0pbH13r~xEOu!kC$!9f&C zz=Il`paku3fDH%3aNvp>WTFIwsKFabpoJO~!2t|PU=Ii3aKH=)x2SL=6H_0yfm(3J!!&0)#l2hXZdoNQMJiIQT>j z6j6dY)Bp@6SV9dVQUZQBIEMpiIOs(UP~l(_CGdlTG&rC_4T>%VMisml`wFIuEjd`X zu-|@Uu|-Xb?d1v(({hUEd)$3W`|f|xexU5f?Q@VB_35Q>Sp%hgxzLKR-l4Sdi~9>- zFSf7yaEpH~<5o9taSMzJ`rbGx`>DY3w4ee-QkA62D6_&7i|Jrc6V7fq%aj@^ud7IHAU@ zyV1vo8IZrbZ@iLK7CLMY)aGHeA&#W2Kv~=s#E}F=??XZWpAY;zx_CUStl;Mqpe00S zCr_;&u7fT;JhzvODB?Q&ess+j_dr-?XV{-R0Y!WCrA=y+pi4813JnP&PQLTctb98_ zoFs~8$7PK1c-$5yQN|lO@F*02s3l|s^X~qZ&Vg=la8*mUV4*m!Tx<(-RTeg&p#cra zJT(GJcPX~@lH8!1N_*n_xWb>^Vb(TG?(5yJJa& z!V4NACeQJBd|q_#l`ZUoc9KtTsx~bnRHE4Sz8EZnKCQXVs(O0V`k=)v{P`f)r`hhW zHHRvN1I}NKDxpuCI(T{iDRHI6G^pkaH*ux)Q2cqbC_MhZE#yDOW3n`LkYFqi+)=XD z3~uA^JeB^8AJ^%o1uksrX4x&Ykl%g!`MtXk())gRA2hxUZsRVM*f^9%nAShwIdpu8 zFs)jCf6eNfkSQh5YRyV1@H%*((^tWCRBV~PLhh*^WYn_r@)(FAm?wkiQve;@$1x(p zci4@bM-Us#JMtdA{!&qxHRz6tU+jOudE5rl%VnjjH1C4U{i54z8~CBcY*&=ONHuXV zv4uWcvzIt{^T#^&VRb03?z7%@2l@8_?4n`o!j(`7yeVi6nc#|stcPYbjRcST?q$7` zdeCl0nXyP$;Fi*$i4f+%CFb;I864^fHktBQl(2rgfhbu=be67uZI8IxfefObY6 zH*+_z6W*8g=>)FF65i+T%F*1v0~MFI`_XQQL8;_8>?Kxr^ibI?&%Z_hDxG1ED!M#O z2wVR4IrMfHbV`zmQ4ukMvY}&VAMe`&QcM!^T%+EjheEd$emd|$6_!&LQs={=@UE3x z6qPHXQ}ipnH8xube*;T_yEn%P|8*f6wR-EI2D5W;U4|ec5~2@Zv(NyK{j!7f&uKu- z{*&K*J`@p>65Ay>Ppd)KTQ^rI?4*b4&!0D1Fq{L$-MZm*X}RR}vS7oDW;0MrWaQG= z&-YN0*`YT7Y&sa*F^-mXT@O%O{p9@>H`|KzflvFye z8%F}opYEmR{4Rk;`EQpx90?#)>bYP1ex?e&YZ@Cz+bp5MO{UZl`AjreCUZBWHV%AM ze>;`&W&|1sobT95w-u_i|46cP_yoP*7R^1aJwjYE(pbsjsY+ZTwPpCf@P;OW2Y&O% z2&1;JnX1>9i_q^kAxB?b6@x37gJn!a=Lm6>H?vtP1G*5kV$bbYK@-#7V_Oe=06*CF zMXov%g(hV4g_f+?43|mQ%d+cpKye;&gfGeyy1cjtNu#pF>4|-g;V6qZJ-K^4_1aeO z`)q33%XQDtil3fVJ0V~4z&EdPW3*7UazejskLk@NUl&9ATl+A6X8y$v_!0ReC7G8UTgPmX4(ybS%6yN2xJL>ChH!N$006AM9Wn4~&w830tWyHIDxaloL$MyKBK z9>}PXrli*C0~zZfse(*Z$ntT5`1D!~NMGT&c3Qw2h%#3SJi3htmL`EOLOz2?^Ns=- zoG?WSp0{_Ue*Fl__UGvu#?fSA>Ap?}kkhFYJ*_ z!{o1DVP;^(vv_J*G6j1FTLoUpMX8>9$Y=yG4TP6 z?b&iF+r%DSUUg*iAvtqobNyLh(FI?ENhheYb{#7^+w?TF;`v9k>({$uwgwv@)0(rw zGT)NHWouD;w$mlZ=HjL0(Xn;Fcg69Jm9}?*Zx8d5U+;E+Ifa2@cU>BE=fRrl7b8zW zbavehrp6a&PA!UE!X1D_$)RGqeS=0*fgi}DDqa4G4BsZ8{)j1h(8ZDs8N{051Mp?;5e6LoSLECyZy-17WSUKIe?x zsJyP$HH2*sxvgn0I-s_&pT_wID6a^V;}uh#Z=-m5S_t(^IfR3!cc|1ORK|Z7Ou{(f2EkVop5%ZNV`)X zPB?qsZa+0NM0jNmA4z*xLwMa^9vgn@1K~61nb|wCobc(<)h^lA236^~w!YHzhALyV zI~fA2p>1iCX@iXxxiv|ioBIUa^{%U=Sy@4M@Z#-FgN@|tyWJ_SUd`loR5U4ykJ!Cb zs%O|+j@T{g=y5%WfpFJkY)UWdB;2)qxV)o25k6ag-adL}i1698qWYX(Ghye)IV@RG zOW1iWQ;Ukff>f1z9<3~(L#k_aLRNhn1L6h0M{mU50^&8_Rroh}0*NfA2lYX@K;rR% z4efSM(F&^*z-Gs4w8B@Cox{x%ZEWyck|`#LHdYpWE|fhEv@G=23HEscE$0Bn6(Zk| z+V6*F^FwzdwUIHFt5&bTmQ^+SD{?21%n=2-Tc*wk4!&YlIdc?A9zVThy+1?o)aFVD zyL)D&FTVL-i(b4U4fzM9Xr1JyY&@t>TJ(*Gpq zv-00LAOFe!NzO+VUr#MuFhD}JCggM*{8|$)@Jg$&(-KcvVE{+#DSycX^PK{9G zD?U@j5ekpcK0Bsr=&kz%k63IAs}@^g`5u9XH^!`?nq*g(^0yS|JK_8M?B+ehCDXYh z65qLqOItRlzB_rDSe|9g9Vx$+;1|jLww6^0>P7hQuQ}aEEHh$r*SxMn2(z!LQYT#C zp?7rP?+0=^cJm1amQ2zbq zmXF_vkO{Y{+XpR)kYDuudu2ZpoBf}_gWbPCr;$MQv0g9e*!4^Hy7f2|+dk}=;@wXy zwu4Ys%6(~ASU;i9>R!_FNdtWuzTM-!`W30K<(_MV|L8H5yGJb8SVdlmQA&~FQ{+pb{186sB za_VN^eO!-Q-L?Y@o5YDnqZgWnBZw0Zgl`SEXAo=7s|*L%ITJiGG@1#4GSKGn`CfCo z0Xz=3x+%oMCb8zY!+_zH2*|Tc#hSJ{3feq8O`Euf7uOZS#VysHa_L909_ zzDJE`@#DBH^j_Q|{Is1c%KSSBztz$kYwPq0Rr7I&BWs?cDfi}@<7>)5>&egkCsZXN zKh24fW9JSM{O3fu>MC!+gCnDbzkZMi!!u*DZOV)$LY!eccRX3~-QE z)JBjW#?|u2O~HeGJ2j?1L=%CXyY1Z%MG%2sPb{M!lqOVicexKU3KLAyO51%OBtfMv z-*j4yPAK9$m*JY0O~?&^W8E)IpqE3}6Ag{ygo9dqX|aX+(6<)ZM!YX?Gck<;%DE`*q%eRRuPX zy%8h3>*iF@u;mrz+8;4cB*sre?BPmi_3fyU+P6DI@ZoslW}_EG@WIZ}GjD?l(nB-T zrTdHtdIJw1V*?fFxc5fZ_sbjvcl!0b=6kn^rP(2t+hm%cz)ckKtGtfTdvI!>T>lQp zpt@qZp*@LQ@0k|IbDiL?jGFss90@tA-=48DdkXpctrAzBArXOJ7zNto$mjFpVZjHd zdWm&3Vs;WYUl9BSPYoox&O!UHjZfk%?xMNA)Tk8YEhyb->yF8tXTejY%dJ;BDhS<^ zE(e+!X(0b6+QZ*Mq@ev5-olOI^r%H3|MaO_pFsM79~aG;?aB42xe@^(#HpyX`nK9J z;#8!huA4wGvF=7fJ#S_K!K)gOJa~6Iw3Ag8dY7C9X)QjaF?%(l)LoY*+cZevvTLb? zan2(`*WvlQ92-B#3uEq0cQ`^j>8oa}R^gDDExh|hKnO_g8%w$;m;%Dp(jM?ubQ1m( zHeSnS{0RTwVh=k%<`ATI#-Sw^CIr`e*36}=x}f!Q9gVdm5>V)?h;KmGW|W=FYhZUd z7`a)onw{3LBJ>=Ot+ecmfLwzkl?*IN&^lK;_$Z4i;j?$mc@A-{*3j$^=Wa7-layVpr0ps&zOA3Dj@Qs9B!jcozV!ei!@bupf|KOzzH2-F9^7F~{(p(gw6!+;31P<~Bhu z8cF`6t0%y>Z>ak5Xcn;E^~lKba0vQ(`s2BE;2JoXuTUm`As6kQe9YNalMB9v{5-Ji z&ROK^V_1}Bq5!O0{d9HjT|$})GXf8I$+@qo7rc!+7a*wqn~>Bjv!W{sC(Y=^ zeKMsNCur48`H1b)K+0%mOt>*kai>G+p6hP2s4ENJ3$>R3(jL?9t5)=oCKbFh_ed#$ zt}Lar7uTK3*#dsvD5IZ+^2Og<&U7>B zup=g^Ia9kVSM>8nhR&`*Nm56~spoD3w1E96w@84SJ3*f%xie@P`8R{e%1nJ!3NcQv zdHHps7t&`bIQ){yDDDv2dZE>f1lY8iw`og9k*aiF1}ob4keY-U^ahnrqL1%cv&LeZ zNY$RpT31EM7k5oIjwhUZ0Y1JLcB+iLRb1ZLXd?fvj`YL0eQG>hnP5}x$d>%cRa|r5 zR=nJJV{v!ohb0xltdLFhd$#0xX;MYSW;fk_6VlJkaymU(eWYw3m*H2_4Wz7d`aX4e zZUlFA!F~TBFTgBM6Ko-|jP#xAbG!v^_p0~5#;E&p67A#u+;fW-4PX}<}IF=V#nx7 z&HA;sx2mW>`HJmN%ae})jwzQm?iy!6Q!k%Or}T-CuQ0Jb5WF9)STCdN?i+)+mTKF$ z&kjJj4#Ln`qY3dZpB~+BaG%saaAFBZeVo zH+If^)T+Mkk&~ zWd42g_eA{tV)*;L@OM7=I}`q$3IEQ7e`mtKGvVKv@b66ccP9Kh6aJkE|IUPeXTrZT z;oq6??@ai2Cj2`S{+$W`&V+ww!oM@&-qN+exy}_yrR!auw&o5c|rf6MQqoQg{ zSQElp4%T2O+R5T*8XBy8VZ{n7O;{nq$_`d!u#$quV;v0ZS6Fw#dJ)!nus(xz6+9lR zVpz?>Dil_au9R(UAu4E6j`v^A_=QCo@z zg|#EB`CzSvswfrE{nPw*2}QYh4m?{D`7nd>o{0{ z!73b9&#>x+)hepWgw-Le>R>g7qRCOUG^~MP?Fws7SS!LB4@H~73LRF~up)+)EUZ9b z|u$ zQE?WvJgmWC?F?&PSgXPs6V`^Xrh}C|tjJ*{4J%+&<%*&>QI#T!!h=(mSf9hX8dVRY z=vY+!iJ}`}y$7c=v06t}*|0i>RV|7dg;gZ1{!mk$6zvXcZdfbB8W&ZYqG(E33&Lqo ztmI(@4l8F^@xn?KR+z9dL`{)mU5}#2VI2+YUs$)odK1=(aQYOhd{~{ssv1_qu!@D% zC#)Lb)GF5es9GJ?*swN+H7$x3g*7CccEt)HRk_288&=A&!bMT0@Yg?1$x`(|ijIf% zH>{gsy$kD9SYN{FTBSop zyRb@yQ^!<|k)jP^O%H2vSVP0w7uKwBTA8XiQj|ih@L^>RD{5E?!=Hbga>n{2)(x@V zhjluvuVGybkH_g~sv3z^M6CW{)efs|6qO9CTjb|qcCaVkP{!-%{8Li4kNvT|@P|v3 z{m19`GcD9Flq_y8R4i^T6mU}Sw=;hqp7|jhf8J(?wEsXSgE(lnJ?hB_c-L{ zY_M?HTg zDEoN+IqpC9a!^kZrHt>-WB;R&9iON_pYES?McKP>G}O~Y*|~5}q(AOuMA^;x&q<@~ z;s5h}FPt~Z102*-N7*5`c;WBl?Ct7j@9XO4{D1drfIRoBm2TI9(9_3JEqyK1;M$>y z(;^i~AWq<#NP(^ah|&;>=6$gQgj>;wRg~@qUguJ##QpBhe`e?Z0VBQi-sKj`XtPJ% ziAIM=Kw?s{fA z1dzRUWspA7tw?%N?ECvOc=0bz{{9T6NW*`B1}{j#|EK&6MsII)gl#H#3Z5nu-HCge zjm|eD*>x&;p>w&~cDo-Af*nZ@`Idak1?N<_KC8>vp@-tNg%b|S;3!GP|6Pjf@w@QZ59gQn}PYon!(NK`{y=Ob3(8*`U>WTLEz=3;gKepJVpgkN+FO4MM zqAe;8MRvAbz^EnIPECXnnC%Uu`L<~m?F?(Z8a}QE+(R8lJGK=P0*;Nc%hNwXg@CG~ z=YHBlq5Ac;x56HPR_0XI(9J`r`znLr4$>Vo9UGA8FnNt&c)lw5{)zPjtN-Mx=H43g zOUvX{m!T~BP!XD3Ao>iorra%A*O-YO(|2r2lQIOw*H~L=wi$s}nL9K;o*e|W`3EKr znjHYI>$iWkJ8%rr{ubveJ=;x4R$aVSZbs(o+&qSKfD8!xa;eHdh6YvHvN+$o)s6DD zH4KRc4}$MIj*vcGjR4au`v}#VpHN$@rJ%GZiLi|S>0`B5fKc~(ol;iY0vSC#%Q}Co z20zE^P5G6^AnT=_T`9@lP*E-E)z?u&sB_KlxM9{9!KcnrCy=-M;bs=veb)(9bUASv!#pSucjJwtce$D#|Gs1u(}!ow!b$jdXqlZ?<55!l5Tn zIZDC;X2KgoJo*p*6M)1b6?ENr84^`XrJ_bZ=gyL>{gMB6r5RB(eq|NpSg{)tS2C zL-0Dw>{}(FL<UQa((~zH30e5#^2Wf{|~$d5OO5nm(|me zeEIL`VN1RtyW`?5Oc$&VCh`{`Cy1upM?HJ~KIuCuK=J&2)16L%()s(P8ybL$_Pb#m z`|Ut2o5=0H(kjp(?c!VWDH?Nmn6bmW9A@7z$A+0S%$H$akILR*jt(<%m~W%7YEFhhrVILx+DIW-FRhZ#Q1<6*WAb8?t@qw;H* z2gGb2=JYUghxs|o!eOqB!UH^l59<^VC%hxt6r+F@=EbBLHJ#C#xT{V=zO89dC>QTRm6 z8e(n`Gk}=q!)zXvv%}mXW)Lw?h}l5Q`C(=c^LG@U5wnSyGsMgw=KnCuhq*lR_Y#}i z;w^a{7jMe@Pgj-v;2)1Jtit{CsQSMj)%bT;^WR;qe|NS2-CgtVuFiayoqAM@H|qVP zzi?cC^cN27kN(1uvHvq`P?ry>H$MJfT|WFTUPZ;8CUAo6GoLVc7zckj00gT3nNw-m!hIi6pRTYNf2+7<1B1Ar=Sz=PgFMFrI}`D~wGM6a)(6 zOc+i2&(n}moJDktieX`-3gb~2b)sNP7$3tZ7{n{a1gW@4or0p$kbxVLZ&)W;SMg4$a+iho_x__*0S z9$L7Q`2YSj4JJ=9MT&_~Om|XAO-x;4f|5d{V!9NQqL})m5}cUEq>z|**BleCzM#e^%SRWW%=o+bXdOj-E$ z`ltJU^fk@DW|03}-z>f=YIU)b+%w4z+E+Kf^Gk^V9TS$vqfIry_m@qw&l$dg?#pI% zpPwuPy`~KTGj>|whuE%_V(cjx1*Bqq7}3MH9Y*Ic21h~KFd~R?KaB2S3=bo97>~oK z8x?WousM&Kw&A;tr#s2>H}!w4S6=`b3HQA3OkVgwN5d>GBcm>ovu zFoKA2LW~At%nu`b7{8;UbQClZV}=+R#P}aZ`7oA;5j%`5Qt?BK5@IY6BYqgyqo8+G zlo4Zz6vPnYf*AdyVtg3M!-yjVSH$Qc#t1PIi19v*>QT{0j4@&)k%AXeQ9+FTQ4l_i zL}I)Vqly?i#0VkA0jX#oMkO)!h!IANBVx1=V}cm@!w4nDAu-yBF-43VVtkN-0{;JF z2Knb2WZ`P%e`^N8j3VX@F*}GkK+N=EK99=UQP@Q)he%-xF&~IoKg{h>89WNpi1|d! z8e(n`Gk}=qqq2Dv))8}ym_fumA!Y+H=SOAsC=4W(XQZ%+m@~x8Am;z5EFXo9#GE5$ z7BPQ_SwhSOV#bfkOj7tq%rasw5i^FE7o@U(n5Cp}kyOT!!Yg9-5Oai>3B-&g<|Q%v zh&e{gBx1f0vw~FilEP79CKB_Fm{r8w;s4d%na4xf_Wgg7lqK1PkS%*CQMThC5mELn zS&AfkmQuKEWhp94i9%$HvTs?AGfT+6mS~~Kk}dmI&m^Pky6)?K{&;@R{m1irHUG?< z%W*pAGc(RPzTeNhKN}cA0w!}EU%7#mT*o~UFpLB|;s&;mfYn^bT@o;q8+gcdY$E}u zNWdHtFq|8B%yn$#22PTIc_iQ$*RhBMY$pMyNx)nZ@RI~ABmvh*z$pHI`yb>_b(OX6 zQa^0jM4sr=v0E- zr&C+qUWQu&n%y=X-D&H$JJU@>x9z3{m+}-Vn9Vlv=S8v(x0bV5I@<}c(gJ#Cq z#vP4ypvA|3sNC5AR7lG05pSADmG`zr(RG|6j4vN(BUXvk6)7Lub|^2P|BhVK;$z~s z4~FGd!!Pw+y}wm%&L4KwIh;qN&Fl$`+xM2wTI`eLc$S4y$YdQ8Uy-4t!IItW?LjCZ z?RC-U$|V&2u~LeWI3ERW+kd8oN*4I=><{o8ItU(COFE3y?E+aB$*xCy90l~_Zg=ik zs{jUeudt4pFhHNd6Y%2pTR^w;GLbs&8K8}BO6lb708}or^h*~wz&3$=4`XBth-jwW z%s-BA#AXiLE&(r@a4@t|IK;FA2ZkKe4VPE7zz|Nwm)*(;e4b-cs8>-3Lr*xj1zdXr zhKJM6$lbaJ3W~fg@^$5cf^rI{6D3ZdAmo&U8Tl&6Z;o{|m+uF8rG3u=%3VR8MRqc+ zFgYj?eZ1p4D-Pt>2=8BBK1R?FxRQm0n|`|mZkO%exjM%J;zbmVf^5S;EUX$wE8TS7brGa!mFBWQtI1omdTf9GWz#ma zdRDMh@yQ$|*s_RLckn-s+QfoZXeUbdjFLi}VC2y!JmC;`aJv}IWH!X<6wiKB z-V1R~R42rY79h?mh>e%V4&q$A^H*L}L!34Z&5bfE@I8HJPJY%=w0b~MJ^o%M{`j^+ z-VYMc>h+P`TO7;KYSwP&SAxW7HDbV}gFPOtG8}*1l`@Bxr=J8~r2d2!!?Y}gM!Qi# z?pF@>ldh-$wYPWLDx!j$#kKcTdr*F>+m?nM4^du;Iz85W0p*!!@4P8=92H1)GfFc# zp#1v4Ac5iqg8s#zHebQ2D*|FyaIF)n!hxk`PSoc>k+J^@eRSUynu z+W&sbz$#vU!DYKQ>3ID?bNHAgUjI}oJ$@6s{^u-?s!8MZw<m0I_Xob${wJGgoy#6tEnltTq{W&`*`>*5mZ~6GFsspdTK)l_M9$xzHjJA^4)>ZQU@SD-87i7pBS8eY}C@BEV&*>5hJ@fjK1tZrL$h0sP;yq=7|6@ zP;;w9w?D-Q3>`H2lt@Ik9@BAq6pJi-WrY&77zNrQ@1VRFZ6zn{+)$qMxDt7G z0!VYAH3@Na1$BFb2B)+92=N}Wa&>v?R$~>Qj=WsM9~OhQutwjDx&XBCzgHR=9Rn}C zE*kSGiJ-E!^z3N96KHs<9VEuFpsDO#BV&-Ij5n_Kv}F?Iqlp@eKSX^?W=9c%u{UClYzFlS&tnv}TY$bU2VxR4Nr=1H;*hn=Le^!sO_`Sr zBWRo!Guzxh06I9^QN`#uXv`Un-pR}bBKBZG`<-1;{e2mvm&S(r+OFTx_3puNuIjm; z)eB@*rB9Zt@o=J+_$?$Bs%fY-opko{;hiWwI_fNm1rg}#y}{T4Cc${8xChm}Lb&Oy zOStmeopAe!9=~Wl0a@{0_RxabQkk|hDQ9+_0$m=Hukv7)o zaX@%;F3LxBZxURgmz2*z zvQu6@+-#&^c{nVvbl*pesB=^NL2@ZcgHD-YL6?`bxi0olDijaDVic z5pirOBQDJh>21?NEh)Mui{5La*3|FpQ8Gj*-NSotB*lBsHDE7mSAGGEH#~0zA%1Yv z>GYI~i7(-H17gg&_($yFZxhNd%lmH=%74Iw^3O)}|GhbY_xe9^6whCF{i~oosuH_8 z&8nJ;+Rj%AFMan#EvK1+_B>PuH6(Fj!hX46fbP}Om8@ViksHh(ENdb2ZT%X2$o=-g zrGY=tw#WJnlcJn}DR1D?$p=F@6erpjrPYYd&&MC-D z|GWl+sUU5lzLXiT_$B)fzGzjjc>nZkS6v@4dGatt)tnR>xRuzUU^9o&=&%_Kl1^hx z;kUAnz1EUFxPA>5;v^k?o%9)Sv!`7NioF7W-Jy{?-4Z~GBPGM0GaG5BhV+tjHXtqQ zeDMS9^}vFUCewGq|MxZc_ci$UHTeJTH5lYKjg>LA#GzC>`o{A*H6TbaN6?^c1-Qk} z-d~`+f|BPd^XH{fLC!!8agv=Ga<13fCiKo2y?UbUGwCx3)oN}Y=F2(-B*!Sa`w&2iS;E?tICa24S zPl$lx0XJKn)>dB9hFkS=pIiBL zfpM;C{Q(pKw^os{Xg9nBW-d}1KH37v%vl{jr;Y(s=L~krcb-AYv+s0d9(f`M*+Ti7 z(?aNU^Wv?ujrqVi$t%%SiVX$n@4CTS?~TzNQl2u4n!vU{i!D9<&>bzHc^HyL3T8f2 zuz2sChjiOm9`$g1f!ue-F2qb8g1l^M^1hu(7=Kr%KXJeisQhwBL%Z)8>PXZME@pm& zCY39F_4j0=LAkJNCSUG@FXl5cXXcN<9mAiJAMW5l-{%(u-V&K%ds1IoPz+N*x{%fH z&b=mZTc+>blJhHI%+1S5$X)h!0KOj~4ycKfDMle%d$4AJzyuNXK=_#gsj7#v-z1^5eh%dG0 zk{RYGL@J%#@&+CsBB5vKslpgZb-SlRR56M&)x`e7aZq$tf<_6DKvH)udYQx&$dKM7 zva6CB(grX|GtbsTF}{Xswxc*G%|7@d1h_#);(9AF;yOrCFgLwbK?fCi1k@%U?!!o( zlYMXO(!v;$^>)9xz=zTL=ESE9reb0|md(A}%rNQQ2g3?RV=>kW^MN3mHyCNSXtC7@ zC*GJJ*V7zo4VmpIb7=+ML2jM>`ew(XposqWPf-iLP%-Or;>u%9NafSR=Vf#Nb;c8a z5WI8~^k^KHcM4Vv2S=|y|c~nY87nTOi(WnJ&wlV=SH=!rC_oy`*pflDkKYGg-Nd^AV;66tZ8j2 z6gR%gH}4mKao?sa^(Bsi8sZNd)DAg8h1!DeHs3-ahxDxIQ-&~1)Qx`5`YsV(|JtDj z`!>uZP;Be`J5J0|Sm<)GWEDLAiq?L{c^+dt9DJzCK?b96A9bmGa1azws~qPk9)zT} z6uUhQQX#`jo3a@Xe3X~Q=dagh1ECnln?-iH7AWn|QGTMX1v1LbNL}zOffUYhU**^^)-g?W znlK!G|3Gz*7CpFWDekIc5gBB5_?BJT%n!K@{kT5cs6vr_kItBdo`s4<3&#_`AK7u>IfN z%Q*hKEq`4vWAL|S@1M)17C-OHl&+*JN7h6Wj#rxaxBZi9|FQziGP*>1?8$;$&hiq> zTb@Jl`BVy)7hfQ3sHdl7*aTHh)9{zSYK1xlDM6bVw?Q+`!aHK!OpyK(jmD0YNsNf; zAz#wr3XG!CKU>*p3Zoz8Sg6d*LJU@3VhC0JH3_Vl^ozAy?EeZPDv@Q2d*n+Uuw35Z0QhjOQ;x z6(yXUK}s0Zxk1z%X!QuMf2yffs{y39TX~lB5JDpT2rBoOosh!LFM36PC!`-5oo^u9 z1KEZZxiwl7A@^s2{t-D_C`?)r8P@CsMN20v->Ee~VwYE)zVl2_Uxz+?r}vL6ISx;yVrLz= z&$^av#_UUKkL1xbVy>yID4V(-^JsFxtVNN!#lQ+k|9oLZUVyN&9DlHvU|H`SRA@@V^$opk~r01|D*|NU?aMYbQJ(i9``j-z1D25mV&igL9+q+_cuJ1H2MbHvBmDYZP zHR>o(7rSAKGa6j4$!KFcKE>}-E9J)jh|u}=QwbKZWIi0Mxr-f=P;*#z_$foup!=%% zMb{uHodAVtts^8;D3kSL&;41GnKA?_UW=7ITQrf@QQ>;vg^w8@1}5$0N$7w_ivK10 zJS0|I9&;dE0toxp)#Mz|0Y~?Ap5D$ZN{AB&1LG=HZ$IjR0gjS|JF3QDFs69kmhv_j zDL+cxY`F}^SxCI6M+Crlv!-NHZw;6bjR?Q{>INZ(9I@|?PjHU%100^Jq?h=1AaPqa zCDs{$_Ce2cG>4nf{x0Xj42CWwr!zA8*`gFFCY?F;J&c?XUk>Vd%}3<+g`&zZZY0vr zgnF8%D?O^+(MRIVZ(U+Y(MMw?Q42BC3M2J7Vl&W~ z+4#tm*#->Jw$_}(1i?t|xvAHA8sKG?Pygh?4beqc=K zi(nilhwjlmGleupQBmR&?vQ_BA~@DyFBE=K{LB#gLEgx?-Ig8CAuYME%OdGh(9U;y zn=DZyp)Z1lj0T*B8GSKU?~Kyk2TnUa)1R`+S`S)~}rdFr#BP0;{kxbTQC_i+=NidcT$XkvnK zwSP*BUeUrtklk_WANNQVs2-ka zo;lQpx*3?4t1oAuaWCJ?A&#SHY`&v&WyKDC$_@1ljO8cvMKBIy`-Dv^=8(oj+)nxE zcF4aZ+WK`l3<_tcI8g@%Lf-ILAKp)Z1lj@VfIfebKK z-)}_~1#)=(KQ8rOV8Iyt^>t!Ho`9(wxh<3USa_~JkkY(uFBGY)i|-CdBlJbUkirup z=UE@f>Y-SqygwUqnnc*M+B850C(`T-Py$WGJ5D(8YvJ`566lmt#6(IRXe&SNSnrF7 z!EI&2dRb8psO9Z}nqcY%Y>T0;V@!b&UjKkc$yX^c&Z6-0n7E@DSH9Xv>Ma-aKBm%$ z$zm0~e#)ge3YEZMx*3Thv!E$}!K4xL819!p>Bf{s$T7ZNC_q1j#Un**(U@L1RPNb?bK z$d|`S>qXLqfq@f@i>|!zh`Y24aWxMp`*NCfHSrdzD;74nlm8fH(}-RBsBr@_bZ4%*1_4M!;p-q=J1VI>S)?TC{)HT0re!( zlyKP2Ln_jnkG|qxHwKX_mS0^;;O0uD(XhR7=%u0b#THLqFgbtZoo&hxdf=;B^4@6( zq`#Rf6t%2E4?(MIT!$GlR}-mv-ee9g%+!)xetH18eX%h6;($X}Vy;^jQg|abqMhJymY;r#d8d^{)AB!w@Dw!l-zOlNaNZ0Ng>=D;UYkD;Xpglp#)(ckcbLdo+dkII(#LJ<@gapk%(#@86mYO+5J zli!rXI_BJpN!FV3=-!F~ergL#%tScIbKS|x?Mo>XvzhxwlFk6xE{;B7G7*M**}1rt zUPCDJ>ZC!+o><72z9T&C<#CM1eEC~U0L8g)^g zn6oZhV`rEdcAh~%l;sdDR6%)Q_DU4ASrrZ^en$bFHHA+h(Rp|&+&9!d@C(#(&M?fKuHJj3zXv*N4Wu8trU%b&tBejyUBXl*m4`nuKg4XtR(RWwNny^iQy4Fa5_Tyh zrmo3o4%5neK9#EX7}_84sqeHZ#4OATx_9UZW5ze9QXELlG2N5Cmj!jWFhjTduQkS7 zvGZBvpNIv7p$=W}*=Si3=w14qHTvvTC>YZ7!angBCN3JtNEO(GNyufUhxdzPqT3@* zh`<=g$5G;|p;QFrw;Z`jX<7v(TNQSAK6eA1+=rpz;%YL)_se;ai7cxQ(lJNRBw6F@_z*H6l58SukirGxdQ66sh z$Lmk=R3fAWyA+59=Ysn%t$bi}#L*Vo!)lixzYfg8vrKOvmp5iC-*!3nm@%e%gTpvd zPZKlLrQGs)Y!N%(rieRZoe6a^AM|h2Sb^S|7jL?~cgBB{`(4ZVUCa58)^h&x^O;}f z_q9pD|I^F~i3ty93YHLo-6adNkq6@6o=QIntZPRrn9fuc^{M&7A&ZS^eLe;t;H-VEm!V_RggnV4SE%WH^ZxjEjEc zwRpP-#$P1TrsXGt36t}TA>r9zqE?o%qt9@Ixx8*YEuU55m*7yFEdSX4fOKf+Hro7| z%9%Px8*M*v`{8h0IwCq$YxWJf$aP9YE@j@nMqn-ztf#2$TCAa@5;f|QIIF79NP{{h z3i^#N7NXX`y`~=-V^N*j-m9rngQ%?add>wQYXWnbU_Avy8Bvyph6UuNKd~>@i{zI_ z>&YgbN=hmph*MTIGps6~K0Wh|t=p`8*0}Iy)6ql%b9uvhn%Ao+*>yJ;6z~7=FsDrc zl-&Yc!9S0bWw$aG?>H&s#@mC#6YzIRrfw`4a-hjYdUbmitTsc#fq316_&KS)t zx9@78K*F72r(85BDWRUZYjPJqCEfbRPW=T?PD36#L>&p%nac$0DN1X*L2_6~6=nIU zx^JSPK{=rw@`W#nQ4UEpTmP{Z^!SsEbmih@bf2#2!^my8!CWR-Pb-5jq)*pALUs3k z+@e9EZfZXbQx)ib>JfQgXAAiJX>T)~{uCI0B@}NIC=J$`%LMBwT6RBaimpsK>hHW-M+)w86hV^v5Cj;w$egw^H z%Q~Ms^ajmO@e`e4=thfI_MP5OR)AJirMEDh7{G86u2AXZ13dFLa&g>UnP5FdxxyD* zKha8}oKfL-S0(SF0@3dA;rNBQJF2qQ*~woY3@@PwZ_VXREGD*8MW@c=-H;&4KUW{%&U8kT`b&b9uvhT6ukG z*SK8uFa6DF0{k5`KzHWIP3}}ly#8d@IB{%XysI+*MKlwb{K;GSRxc{Sd0<`OzkG!lZ>|7~Q3VJ}|)7xbw`E(Gf-UjI-;WtfZC zKa03pKOC?B#U7TYhHx{sRlWOFA71|tMrm)w@%l5hlO?s{^*4$Vdptt0o}&3)fr(HP zMl`R}^RRw+7R`Tk`S?ef6k7CnuhXnofmYOHxD4LQVK~WB1$!-0y#7yHJtE$%TTgS5 zl}uNn#E=}&6f2X?=5Iu&mvF*w>{7tt@D&}3`-#9xEoF)I%M`Gu*bC%%TY+(pZjpYw z%ewV+9^0KdnEySV49&Ss$V=LXLh`xjDuWNNAj4FvDw(7(WZuqqmGXTiWP$=LvDO-p zS=nCxV86*v>#0L9IR5oL^}FDm$ZVhFGX`mHWLCS`T-mh|9m|?Y;Ot6Af=?x$h*_Tm z$BC>-o>9916XwsW0y>VrODt>F)88eQ-zAp+lO>klQ=H%Icbxt<6CG)F}Vg zeSb~1*7p53$NBHZt!?|$-&mX0{OQ!!j{DE2{`b@S?@nRuuzyi)ZOuO)cx}^Pp3AT2 K`S Date: Fri, 3 Feb 2023 15:10:18 -0500 Subject: [PATCH 355/758] updating box jump traj to have more clearance --- common/discrete_time_filter.cc | 60 ++++++++++++++++-- common/discrete_time_filter.h | 17 ++++- .../Cassie/osc_jump/osc_jumping_gains.yaml | 8 +-- examples/Cassie/run_dircon_jumping.cc | 8 +-- examples/Cassie/saved_trajectories/box_jump | Bin 52477 -> 52477 bytes .../gait_parameters/dircon_box_jump.yaml | 2 +- .../impact_invariant_control/platform.urdf | 4 +- 7 files changed, 83 insertions(+), 16 deletions(-) diff --git a/common/discrete_time_filter.cc b/common/discrete_time_filter.cc index f38e92cfd9..525f892dc5 100644 --- a/common/discrete_time_filter.cc +++ b/common/discrete_time_filter.cc @@ -5,10 +5,8 @@ using Eigen::VectorXd; namespace dairlib { -void DiscreteTimeFilter::Update(Eigen::VectorXd value){ -} -void DiscreteTimeFilter::Reset(){ -} +void DiscreteTimeFilter::Update(Eigen::VectorXd value) {} +void DiscreteTimeFilter::Reset() {} FirstOrderLowPassFilter::FirstOrderLowPassFilter(double alpha, int vector_size) : alpha_(alpha) { @@ -31,4 +29,58 @@ void FirstOrderLowPassFilter::UpdateParameters(double alpha) { alpha_ = alpha; } +ButterworthFilter::ButterworthFilter(VectorXd& a, VectorXd& b, + int vector_size) { + data_size_ = vector_size; + this->nb_ = b.size(); + this->na_ = a.size(); + this->b_ = b; + this->a_ = a; + this->y_.resize(vector_size, na_); + this->y_.setZero(); + this->x_.resize(vector_size, nb_); + this->x_.setZero(); +} + +void ButterworthFilter::Reset() { + y_.setZero(); + x_.setZero(); +} + +void ButterworthFilter::Update(VectorXd value) { + DRAKE_DEMAND(value.size() == data_size_); + // Modified code from Jenna Reher's smoothing.cpp + + // Shift the data back and append the raw + for (long i = nb_ - 1; i > 0; i--) { + x_.col(i) = x_.col(i - 1); + } + for (long i = na_ - 1; i > 0; i--) { + y_.col(i) = y_.col(i - 1); + } + x_.col(0) = value; + + // Get the solution -- MATLAB pseudocode... + // a(1)*y(n) = b(1)*x(n) + b(2)*x(n-1) + ... + b(nb+1)*x(n-nb) + // - a(2)*y(n-1) - ... - a(na+1)*y(n-na) + VectorXd y = VectorXd::Zero(data_size_); + for (long i = 0; i < nb_; i++) { + y += b_(i) * x_.col(i); + } + for (long i = 1; i < na_; i++) { + y -= a_(i) * y_.col(i); + } + + // Multiply solution... a(0) should be 1 from MATLAB + y *= a_(0); + y_.col(0) = y; +} + +void ButterworthFilter::UpdateParameters(Eigen::VectorXd &b, Eigen::VectorXd &a) { + DRAKE_DEMAND(b.size() == nb_); + DRAKE_DEMAND(a.size() == na_); + this->b_ = b; + this->a_ = a; +} + } // namespace dairlib \ No newline at end of file diff --git a/common/discrete_time_filter.h b/common/discrete_time_filter.h index 41bc40948b..75812d039f 100644 --- a/common/discrete_time_filter.h +++ b/common/discrete_time_filter.h @@ -38,6 +38,21 @@ class FirstOrderLowPassFilter : public DiscreteTimeFilter { double alpha_; }; -class ButterworthFilter : public DiscreteTimeFilter {}; +class ButterworthFilter : public DiscreteTimeFilter { + public: + ButterworthFilter(Eigen::VectorXd& a, Eigen::VectorXd& b, int vector_size); + void Reset() override; + void Update(Eigen::VectorXd) override; + void UpdateParameters(Eigen::VectorXd &b, Eigen::VectorXd &a); + + private: + int nb_; + int na_; + int data_size_; + Eigen::MatrixXd y_; // Array of previously filtered values + Eigen::MatrixXd x_; // Array of raw values + Eigen::VectorXd b_; // filter coefficient + Eigen::VectorXd a_; // filter coefficient +}; } // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 74ba5a03e5..72ee06217f 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -6,8 +6,8 @@ w_accel: 0.0001 W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [0.5, 0.9, 0.5, 0.1, 1, - 0.5, 0.9, 0.5, 0.1, 1] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, + 0.5, 0.9, 0.5, 0.1, 0.1] W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, @@ -16,7 +16,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -x_offset: 0.00 +x_offset: 0.04 relative_feet: true mu: 0.6 @@ -31,7 +31,7 @@ hip_yaw_kd: 5 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.06 +landing_delay: 0.1 CoMW: [20, 0, 0, diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 590bc5cab4..cfbd235cf6 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -690,13 +690,13 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_x_box_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.4 * (gait_params.distance - eps) * VectorXd::Ones(1), - 0.4 * (gait_params.distance + eps) * VectorXd::Ones(1)); + 0.3 * (gait_params.distance - eps) * VectorXd::Ones(1), + 0.3 * (gait_params.distance + eps) * VectorXd::Ones(1)); auto right_foot_x_box_constraint = std::make_shared>( plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.4 * (gait_params.distance - eps) * VectorXd::Ones(1), - 0.4 * (gait_params.distance + eps) * VectorXd::Ones(1)); + 0.3 * (gait_params.distance - eps) * VectorXd::Ones(1), + 0.3 * (gait_params.distance + eps) * VectorXd::Ones(1)); prog->AddConstraint(left_foot_x_box_constraint, x_top.head(n_q)); prog->AddConstraint(right_foot_x_box_constraint, x_top.head(n_q)); auto left_foot_z_box_constraint = diff --git a/examples/Cassie/saved_trajectories/box_jump b/examples/Cassie/saved_trajectories/box_jump index 8f94ab0a5b384c52c6c25571c5ac7fc409ddfda1..b8b76f2ef6b1b732f91430c3c2d258c9beacf3a3 100644 GIT binary patch literal 52477 zcmeF)2{={XA3u6indc!>A~IBj2Fb9NR5B)nl9?n52}xy$G*HGS6`E8MN|Ue_BBjBY z6otr8h9X0ud$8B}_WR!d@454HpZmY{Jhji-=d;e)b}ajx^**n)<;db%xn2f4Mg|53 z@pZdBrPsN;NJ}r3R$I1enc6CKRcUoq^`#uNI~fFb1nl(n+~wi8XSeeXch@~WyMw28 zYp-#4_4N1j*(Dw5yxY^+#oOIq+Ig3owErIGJ?=|9clieFk*4?Xq}{pAXSX!u$(4?2Aq zQx70Q`#XK#R0CYltDCD=Ck3*o?Y(b~!rvT4K;cxo<}D~OluIy_9ROuh`yDF4v$Iow zOu%dD#3RDLR6&hp`C~&B8Bjk*|4y_+9B6olZ#KnPrR?oRhce;_7k3E9%CKgGdJ^-)Nk)V=kW`r4c+rWH-|Z09W?q~IZl3!k(kB+v1nnfpz zwuqhuMG0*t`#au2R@JC+o1`Ylx3%q`ye2w)X)TGe8r~eF9rF*P@>-Hxpc%<&Jrn%tmp-rsmF5-}#4p6C$6cRSB4#~i@yufVZlQ?zdY7Z*@A6o>?g5(t$5G72 z@>b(#dNGvD-K{6>tOteJOF5P)`9WUJ6Z#8Mx5C-E$%9|+-vyK5S0!|1wZNo;?xSB? zt>7278eH~i7)+EYowy-=0Wuhb+tj9WKqjuyxNrv*$Yf@Gz2D7pH6>xd{0hUfTPsm-HX3bak3@gmr;_O)V7|WLJ z@wqVp@T|`8R*mmjpe=OS$mZ5o$OP-lTYDFPL3d+|27w$f)X~RsPdOh9rk+{uC*=gb z+2-fW%Nqbag*y5bvcjM>NYgXnErRAhB@SVq4Or5_pmdCr7YjfAC7m!d2QS;RTbEH& z9>cEJ92|`M@jAZ~1EM?MVB`LV=A_2QSbyyBB@QNaykh>sn=(1oXyU#>=zE11T#XLI@i$t7`X|Rr=ILz3Oc@22_U`$C;o}79lzp{Wy=0SBTHXj& zc=0ufxBVoRSFmo}bi)A8?<;KA=CH=1pAV|)FXO{ZA2!~o75xCszdVsVrne2x)i2Vp z>rTNUY!~#yV$$%kjWP91msl};E%fvL9U;8V`RtA-^|9EvTA(F%OEz93sZ_DJ)E+N? zox4ElTQnAy#(BCD%y9Xy?Wejo>OhknQGI7;^~2S-HV?Ln8h~b}>O8y4ZJ7DUY7rTw zD;VAmh(K!Ju=<{Pin2a>lBU!VR=;tVYe(6JpYG#_~~`=Sd94$!@XKL%#@ZN zBX?mKZalx(auu%+wEp?VfALp)xVg!te*Wy2(7x_-PCoM!=v;O9wve?lbi2H#>Otfr zv_9OO?!!I_RWwXF_ipILrr#GA%6y%Tt+rP^lF^XB;<20wf_~Z1u-+`;=r?g_F7k+L z*VWn3T=K+w;a|t0`s{S z@8MN2{Jalt)Eng8_`nEmoIF-s%eo(KjNLNac61xG;nnRc8+r#f_t->ngnoziO*Pr= zT`thMW;kw3y&818=Dh#IU_7*rDH$v5l!hwX=Dh6JoP|w4@8gP8E5cS@{v5Km^Rf5? z)k~|sT!n^J+XKh^gQ2-l2|B2}iFUj@!nGvVLG?QuZHjBep@kJU5Id&;&BvA~x^fA@ z4a>GX&&=S48(Nnb)UU9E=Dy*%pPzWajryNfjIIxc7L4~*b9mdJ;=L0M%i_L4Rax7Y zu}BlDKhN@t(i4O$uJud!994zd+l>buJ)c3n_*qe|w*FAV^7p-2Pp?6V2S$2rgDqJ6 zm~p+ClnGY6>w4Mdt}R|x%UIucI}M6$*ui?hCk@J1A1s^~V~JTBJW?1ew?Ux=Iq3;( z;!w4=Fg-hB7F02a3fO*E3@_4Bx@qYsg%>+*xYx~EjFtU&7W2hUV3mtE?>)-0z)KRB zy|olpfr{zAwU>wXK-DERugt#FzW&-S);9?OaK$Z$#S+jAYI|`xEK~}GdI=}LWb)pF z8umxuN+%~miD%#Mmz>PR;t3^J%0GHw#mB<#ML!$xvKO-9*M-KR*z#kRC9QLyd{yvD z$;hXeCF7*&m6A{>#P2VaX8#hZK9zqu@1r+VQBk=kyF3doQhN6~VAFcM*t*kxfJ+xE z`{-=hW^xv*TwYkh5q%jiN%l}YTep+;t5|5er?2B~A8&6*Z})9`9C!NAt{A3%MGMpS z@AmZA{>L4HQ+EVA2mPyl`f;Xq|EqlZaeO`ZxNiSf2a&1AnYrU%UHH6qxx4?XntyuV zzY2Nx`24$$Z)(@S%6L3?`UZIWyF1b@ef-s@zPPE&C?0ZgfZ1JhHkUPxfgy>qPgi!w zK>oood!|h}n58vQce(mD)bUgNxKMx||6H~F@DBqu&`3$XNW1}?`skg zG{KnVW8$Uyp7Wq%4Kv@{taFe%@`q<-b~0Xg@PO&};?TrujSE)`Rv~wVsUrdF@m3fc5CVv+i@4Rt+ zJ=5kw_1U}Ql{4dX7$eIv93OlpkNf}B7W9vnFFj`<1O(NaizjgYI*SHuvy&0FRe?St?0#U@2$Fo~FAzphxc5H*B4{>WSGCx%rWZ{nlR?b^DP!b+w{g1=E(LVg^^tv%=vAgX8~_T(SaRk{I=TG zB;R~med>pK3z}&4Ci!j33?Q(&L1VsZ8RYj_@hk3?A+oq0CUoFz04P0>x!EUpGf)?t zyga+EA7pXeEN^o&Mqy~zrLU>VAja7z+OK0bM|cRzrBYI z91~TE%eZg_`B~gosPHvIQ6X8!gxA*!#`i#X zvG`@rPXl1vc0T_wwI5)u-9{Gi@gC6oL&RG#s}+qe96Ff0#smB=5o_JG>nNI7GregiO2 zGO+4~@Cv0*ygG&Pok|bxSi!M)s+IH$j_k zcG+ZtWvk53-fJ}kpA5g)`nlgl2dp$tkF7fnqTRALcJD5OoXv5^g8UCd79$qld-@ZY zW&JEh&PPsQ@LHZ^#pbzS-{iBlV}e5H@Y;pjua-B^>Md6MnDC?3=eF=%>ZR4^-b=|m z1O_vfJp6KV4(OL$`7Jvn7tDECtl|1m9lRW~lWH7^FB%+cFjlm@gW|@ANAI5JLjs$_ z?aK1cfu7FxP0zq<;5s)|Yprc0*u-Mi5%{1Bd}lhIb?2Nq8ml~a=Fw3eFyZpeCPDK8 z8fSJ9+tIuqxvo+_u0OH~Su71ppETG^tM3##9pa6~UWk`vm1%$pSHD98sXu7-g@Rie z_aYsJMEhauZIF+9r2N5&Y_vc?VQzRq1o*HiI_iU6K3LBEPCNhYDe!HR#%l3>+9+bt z5%1lv4}?xWRLT0{j|)9N`nXy3k|FL##pgtR7@JugFQt|SIE za}CrgZzdoHzXiFk#2b)NLdhppGcLsUsD82dnRxJ3mBrKd=tJOqMPsS8@p546pWr!X zRTB7aUo+3h+#8L=aozlVZ!`F%pp|G8vk3jf+zA)Ya3iPU7U3$MK4dk!#nDqy7<_kN zk9$^PNUMk5D@VW5>V38fCh5`Y*Z503-Gai527rCvddL=UP(3&539wlmWyo?R9JB|h z+AcHM2>AB%*SN@5fN}0E)sCjeki+{Q%8xoffc>jGr92+3L=7IT0eg9FKv4T4cHeza06C*f-4)~)fRn6d?RHM?XytZE*=TQR)Q}b}8G0rkipsp(p)ci!MHe`= zJUMv;a>jTXelY$4`rOXssWBBHwi{sK^PlFRZgw-1XS_IKaeCnldQ zK`{rTC3b_pIc0AqJ-UJOtf1O=!Yp75e|qA9hG6h*-$#3nLq%u^nidDN+kufciEld> zuR^2m3%A(3c!umQ-lv#1W z20PaV`Pv_e1z*+8`jyNMBO|l)Kr15EO+9-rWNKMh*7$K1irm-{ zXQ^C?cJA6SkouGd^Zc-!WKwH@($^+E`N9B}&KlUuYuyS3dER}n67dH1Eg!Y!X{|sk zfd{(|34~#u?_L$D`Ujx&)zs3ii1k?dR{TIwiaZqLb~|-dYBA_LB*yur!~%#-#D0xl zybRPDHZj#&A1nI0`E7Nq$t7@&+Z5_+dZ7Wqz`cw${tm zLGMm$KRM+jG$6FWR^MKnHV(Yf-x6qphWGNc3A>Jh1NRtAB{pYZmNHEg655pvV^0aB-7*(7%1qiFNlV5HR#zAg^5rDuNE3)Gdn!Lb{y}OpNQm-3O*i znz9oS!}Z`v*S)mypzQ6??F=L2-I22?772oz<|Su;w~tgn7DTEI?2b9JXg7x>(C`|2U}8$f*zPC1e63>oxB?VQ&&!)Sk^5vJJ_6_L;cc0sU?*oz^hlX-N?xd~jQ7>ES4aIZd z>d5P*I=>51kBoxG{C6k8KpOi(SDcQzuoGpw9;k88|TW9yN#TtM4le%G-esvDHJyHnDh~^RB`GULmYt-zWOWr~oQNcOPCB z9DwB{%oJ44ZNluvc^X&8`%%ZT3LBy1Ry=QO$;i_51z5r1UN=+sFjP2_y>P;#0L#t4 zdbVEE3G`(QN@&)|0v6QsrjF?ss@byfmV%N*(LI@K8Qss^K%wD+4U7F)bjLeCeQp1y z4F>lVOEv%W0_Eo;GrW_!LE&SD%~5igeEn!7r|G@>7H{xtJ)h^CQ{I@-NPoiR3KuF* zjlALP?t%)7tY$Yc$o^43=(FuyCaqq9L2Y3zW;B-m@|cwk`MK*Wp1dZE7vycd%~e!} zTtmP6OC22m)z8Dbt%n+bnN51G;QA_1Q&Qc5BrbsA*Qd5Nhx%YP>Fc-J^jR>cWZ0Qp zS39iA_ey2kUP-7b$k?`SNEWNz%VF*6ynu$EFZ8%7d<3$|T<81{YK%F>500FfosCs_ zyJGG+YC}~4N!B9*O;{~A>HSCqH~3nez1eweHsXAxJl8qA0==*HJlQ+3Qn!VdeOYXW zH^3Ld&#NkH0=^(iJ7x|K;s~&{CGUFg?kYEuGSQL&twky287^nf+dzW6uV8L4ULfY%97Zy|3rM=SkZ|!jBMI8KjSs5$x(Yr8}aXZr&wCktri#2mcKxxr) zchy!SFh@G|X03fS7(8}-^`(&(P;MI`yXwqrbcz40NJo|rD0wWXa^g83X4c=$wqtY` zoW)r`|NM(vn7Pky=;^x&RK9gf3~#{~a7pR$X1-GwKneQkRwD09tM_cw+F?Vhe=(`t z8ibkqA06Jjs0BD~w{fuL=!X0m=CQBKU6Hx_W|;?u1E8a{E8yjz9MFi8dvf($9k~7I z&SZXWANtDl-F0`g2B>TLsO}||0vD_=Kj?Vv6XuTGTl->52jsTTv1^G~2W4~<6l86E zz?ad+*KF#~P+gtc9i^*L&C=Zs4T>d*_59w(bIXE31=H;XEg|Ya^dVP#y|_FWOji5kE;$a0 zE+5MN=FfrxM?xN|X6^)^Y*<_LPH9%|g)I*gfyKCZOCYfG!Y;w`YN05g{LS0ABWZ}=MjC=}|6fl?nI ze~y1!2j=FRgLyeSLC>=&s2G_In2YARF8=unTvlgbE3y(qV|O=nUo!0kt%tePj}MK) z`Or#a#il?g^64h~gImT}q$2X!8})~v(?BiZYex$hd(_cBv3)OUjXU8IaZne|2OV#B z*nNW{Z6kR4F#NiMx(TED(+E&)y|y4F;pER2pizz^!w-UVhJF(9so&%%4&$z}MVW=+fFs z^xOE3#Q4V;$mqwYyjJWvX3Qy0Y&_6_Zk?4f36{(UM^D!5S+Zdee7&Rh>AqVG`fak{ ze6(UCt$tNQY_bWheiBYxP2@RD(>TsIOW}q6@3eA@MuSY*t+^L06*-1jygTv?R zigRec@67nk4#xr>p-;y@277{w_%dU|g`uL+V?}*+Rd+y@pO4S^ZR%id3plzpSrrVf zxzWDG@)XFj5oC9_9|hj2Urg%22JpQ!*{}My75W`{Y<0_gCde4;vV`xMHDND zFO+2^zgk;*Hu8END#hq_gjU~&q#him)qk{0nQuv}kGUDLqKa1k;^V#SapeA(RVyN| z5Av#aIsV-76S%t;WUpDM4%)?{i=HyWX=sLden0>+M#pl@PkHtI!#o%ccDEeO@;!wI13J=?B)VOh}M^}=1dtVFjbGk(oOvvF`2c5C@< z`=UGEnD=FLNi(QXaOKIZGy~ELjx86nEd+z|b)p|lHi0b7Og^WHZ6N%@`ploTw2796 z={Ks-?}}%)7inLIjM@JE?6L`%@xc0YtHNrOHP4g%j`L|0UKXPITYu9Z^}meg_uQk^ z$J`Zr)kCW{`Y7#`4wma(l&(6h1KPwM>v*2H04#Ni_ou3vfmWVe=7ap}fwYeduWATC zx*~B}uiEDv@)P#hKT>}Pqz*Z5ywz=o3eM#B*M0tuYQ^7HpIN8_Y6WT<&-vDYjvGJJ z`1pdrE`jz>W06THUGa49&WC$Z!6S`&g?m=0R)#UeZ1oFJD>|Agt@AR@O4jGkfhHTf-Vv@FXtvs?wYSXdz}5Kuk6-OI0+yfMQJXbFDP?0R@^O=B zaBq@tOLjY|bS^SrU9tsKZfe+YIp+@O+_FCIcRma9&7FNo!b}oeIDNIQ`%n%V+>>F- z({mS92H1)JGGzgko;!-SEn)(lmTS&5vTOkT-$TXki1-5T^T_0F@j;N~a`%CwTwT%q zG1H;wUN%ry(qI$Wb|1_O>1?h(+5-kv!$w5+od;P)X*-=fhCm2+`+B_QM$9nA<|(EijAXYxZL-UlkG|eJUUfy;4jEMs%s)N&1k|zD!uy~U$*tYO z!7lPU51kx;BC8qz0@!d3g->E|J+vyWScs*I6Rf0 z)!(k^iF}1#ymgR0oF)WbJpUERdN&ljZF{!cDqtSy{~f)i-Rl_O=JnftD`ho^8cUKM z?{+M@Q#87CPE8f4|1R_^ef4js?F%Gs{6=l-McD_H8HgMhIGz@ zJ(yt?gYq+Yg;w9yV?A#lX2@pTpI=>!TsR7smc*2z9-U3vjaO}e;$pbTL&ga_IQUB4 z(j^Hgv?cOb4{t**8a)c*N0Pz*VySy>t2UzRPC}wwgN|rmuXUD;(oIx)@$meJ$Zk-Y zyjVJZAOlpgaQLoWc>p;%cSIgtzYtuXcfe{wjrRI|KQH*~(t%3%2#jUE@c^YeUYy|P z@d1_6l`ZDd%HV%v9s#@&+Sh7uTL_SOghBP^HW`OYK~~vGoWd$b-nR$+`!}3TSur0o z=rxL3E8nLD5Q_M(?lqxZZyyf2^dtjiUGVFw$bI@p{Z5%N?{-@K=b$-FI<)#q&!Man zwEEbpUMZbIqZVep8=KDQn9lF%6=94lT(jWJJlP$%a6aEvy)mB(owYksB%fcAC^QXQ zxA5elx?kgff|^r6xd0V1^z*%X2^f$-8VP!l02K))(E~qJkcJ*mA;Aw4 zsGx!hB-lm*VGOjJPVpWw|*poJb3p#m5rut$P$Bw$8@Tl7E_6*Qs;c&K0u zJ#a#T98~a+1nNjojRe5x!73`SL=OT{0ULU7g#<#V03iwHk-!@XlFn1amc^sRdu#df3Yn2uB(;B-G|FZbM)*EPy&-uo> z5epyok>YMy0{u*H|2WCI07r=iSm~b7$5G494C*D;{rCPK?rH?7YC+L5$+gea>Y%^A zpOM`B#{XXbUCK%2vo01*VdbnF4TAorwO-w8i*d9<+NY-XW;l9zzwGgyO#ijN`MY7R zr8-?uLUQ%mm7T*dNY<>)YWI=O!@vNoEk4gR z%P7V37FO))`g#lQzZN4_7e0jJL9~*6k~xmoUJ$d!J)GXpY37!;`OFq>wNGW9JZA}I z&Ye2BCNKepyHxB|c^*iwpN{J=Fce6WdaLTCl_64izEY#PK(arrKC;v^oF69{lsj7a z#NniM{7dTA+}DQW5oWfe4Xxk88*`SZKz@Nh9X0NCFd%g!_dc)Z1=RD9UfSDdZb9oZ z6>YveP0Y1gV_)O9uQ1@6)*dy{c6`iqn^)v3XMD^s-qi7NLqQnnIkVM1M)e14+;Xb} z>@layPG{xzLby)i$4K0n3hjuQ`wJqedM8q!H%r%}CknDzuQFp{%z*25v|o`O3#?;SVCgUAKN8myaH(KUug;tT?Uw>pGNs=zW!uP6jH8j_{ITmxZf7t3PoUjl?45EbWsc zY;d=6!neZOaC~^4cSNH3AU?b-jhXL)3e*&j)e@DKL9dVf42yRWrM+Lq%==Br5klkT zxs$86LGkt^xzZawFhGsR^y|=WsI^WICI2)8Rr?e&My@YGZx@}a@{H?)y4!jh2V5Dk z`1K!72X&lafW`@js~`8{qxUoGV%({)m{*d6b39et_gbl`_=Ua*Vy= zrYO{3s(xPf!Yw%Wiv7BHQ6?DNyz5-v+GkLIv-Pim4Yb#Nr+I`Hao5qt{VNA9o85-` zdHb83yuRbPN8UW_NHvGSAJ*%vlVisx?QUI{Pd|@O+Wc7eVO1Ag|LeZX((ohbzIWOY z*=#d3aOc406-K+E;jtG#PQ1y0(wY9pR4kNWXvV$vxO;n{Ay1=f^*u&#MWSSL+=vq%1TenWH;0B#J1X>> zgh9Hbw?EXm41RDP%45%zg@!GjA}SheP@K#9qVwD$xPRmKE;IfY(C}r=7pWu%a5Ag* z;w-&LF!U`H?xy77xJM3s3zPQYxcdV;tqpHL z5aXf#-k}+EJLebLZIXw)0pZIs-FHIZ_OyC_>|9j)IhiqOUNrQSb*bL7wg`fN-=%RW z@~E>b_m`6hKjghy=YJ_C4uS-e0IeUs;GI_8^;>r)pyx`#j!x#CIIPHO*y7ka99D66 zW#&b8^x?t5k;h9ASSZZQ^kLu)+H$CU!G~uz!H41>>)QE`A!$X8^e|dZ!u_2|uyFtf z=5FE|t^S<=gh%ePT%BBxY~~6b3(*sR+|7#;i#|L?a(qT}A8kJg+=P}EW;}d}^xV7h zd{R1)&hs4#do~?{B8%A*-S@ld1{pes9k6Kuvw4NPZxwZ6k;R<3yP{X?p8chlTx#Wp zIPK#3AAVSY-U!#vPl)}Y+hp@Y>sDDA;P@81ymHxAa62fd6?nrUrftwMECbxB(Mi^qLPaIS}_^so`8?Kej!e03XcUN_is z?S}4z=z;N94g)}no5|)&78{WKCGgW@>^xNdba&!F{(x@Uyn{^MyAEjDw3gHKt_fn-;I41k#EMo}alDY_=|{2}w>EhUSR?HtOJaH-Zp0Q# z#JyZ;-3ba@vskFYa9mu(?I?|o30M_)o2{11{i)}wYdJ*g8 ziWGu8h77p{faI-(`!;vwLEF#y^J7NyfZUE_$6vmD0a*Nm;@N#>Axq(#H$(JqAb870 zmG^!QvejnU5~iW3+afFxlElR?pN_}z9??gnl9?Sty=w=?@)UIF}TNxVQ^Ds8LEsTg_!TV^>O zxcKoowj6jjCKYc7t;XvzCmt8WP3GdawDzxq9tIpMKWNgnt0g%cmwtm*8l#6l%5Q~M za(zn4=eJ>V>rnsL#tv+5=$6#G>@jv{@?E||SRA`^*?oWGfv~64@PiZlD%ext-D>rv zg;?g%#PcVo7h{=s$0|=eoCBJ!iMw6wb^-6%@3q@Lu7u9w?>?N!+XbCfT-J_iG(#8B zFA<%J0J`u#+Y^K5K?TG1A3J)4pu(!!j9BvsZ2#owXY`8|+gHdQIxLlnw}-?uwQ2|B z?ZFrQOt{0b_4bGT-Ju-V+R-QBcSJKt;Ass!&YukumY)z)+_n?sZ84C$d3G1b^Qd5x zTK66$@o;6?_&cMdS&paeUL6EB6}vk)X{tcF zKj%{O#7!_iw=v+U#VKSU(A}x5JdO+)L{_fP_6JMn>x?#5WT2JF#+hGlc>}G`<}*hM zuK_2s6!y5!(a1q#akjy`M`*qBPn5Xd0C5DV%xzJ6HIwt{cBXPZF4H-mG`~J7=hHNu z^XZFuOyzve|CgK({y&)W5%@1TpXQmXn}7b*_6wVCfFD)eo|otLK!&dhPmT@0g_bEG zWdZkevU{q4Tvw6nB{0VQt)%qJLCmD`V^QclD`=T`p;qT&w zqY~23iq$dUs4#z?kBf2&(q`)a{Vy2y8ZUHjXu#Zyb+&$f^ALJ5a7vy#_vPPpqzwkn zr<+@xdjPq-@9PySt%W;2Ds9ytmBJBoO4Nm!jd1w5=(Q5b%XoEvr-M@7cl1;3wU_Y& z3+O6kXLephQ9EtskqRniw%T}Ri&uYc?REO81xBrt%fELVg|32}4aJy#)vKLD^*ck= zhwo?dj6E=k!~N#hem*f5>)n2rYL_L1hGFo?O0Or-)jNOkvhl~6YTCyw<7RGYCs6(M z(wm}^wrl~z+G*V`s>9IL-K|h%-45-RnfnVcwe547zJbH@6jQ#Y`{D50jvJhf<*=TH zvaQvoW$61^ko|4D33PqY%mbu;&Ge#uU*yf)(!MjZ#d@lrTs_=(fbZQA3M$(^Lf2=3 z+PW`;492M*0$v#baQ_2OZ%5z0d@Y!`7g+pp6-AnoP1Wd*Cyf! z*Ea1C|3Iv7`f+D%K>%t?W39idLHhtwqr;jD9ohwZspq>%ZOiY6P2Ix!wsOjcp0j}N zG|7nTvBA*o{Tds8yCvlRTbrDZl9_%uB2%m^>QyO@xMh}-*sBZ1H`_~38W*9#)9)jc z`T;1{Z+tmq)&?0Ab=a;+d`B(2o9(u38h~zhu386vbA~LjXPlld-~vPJ!Rs3z6@YS| z7h6O>IDw&O^#dJg??HX%lJD#<9@E~>ExnvK_XG~2P{KW<4SA!Wa7x3iL&<%gJwpI~mWlFW4N34?WxO9lyyKAG#Czrln>O zOUy}2>>s&2w!qCRx7A{{f-s%9M_a)!%N$PI_epTe9UEgm?%z1PxIoTB`7rJK zGqN<}Whz#m({lge(`#t-ESo@9nFn-TyWv=yEgx3*vK{Vw$qUXi?n`a=KMpc4-M_-d zERWTtN)=Xg=zx*)i-PrkM?qI@W}UVIf2?lS`YPgD6goBkz1zb6HQ;7M9E)YA01iKW zB+67R7>A!!xd3lm$7)Agm(6*w2Ms-biMh`mhOXyxWEcZ`vDzA& z-J@)Q!{7X3+P%>phu8EdD!(qmYFtRQ^Rhk~I8`57Y)JdQ5P{FNeIH?U!3(?XOk0q9 z&FRmhV=O3rrIK;-yZ2ZPi`1Sv(h3Il242jLxC-5btM+Y}V8?1UOb2gy)AHeuL$yyz z+N0FEC%0`9YjDJ3Z?@D=S~x;^_PHA)##no~y3kxH2Gr5>*xTU)t$)fbo^;g$Ec4a$ z?#j!1P|gb>uTLW{P?FM{9gQu8cv*O`7H(z*UAH=ude8obZWq@Lstk%?)m$qa^~DF= z<*|G>mX?k#F|F!5`2GZrh;&I^i%Nex&C^}4q;dkR>@S?BpssZ;b=%JNjQS&eu#JtXktd09go7WeV z65n?XduW~Y@K=6?P8@O_xqikMRqDOkKe~b+X- zk?OCdOV?STO2J+ow)bx#ZGW)t;ZbztI*TPoU>K+r4st&DstdZxoG^&GaREfhFf3Cw zyba3t%=XETOUAVQ>_Qb*D9ZS~$b{l{RKC05T#kuk(WrF8x=jhFXdv%_b;^kfY@hV# zd`rqW2%EbqX4uC76+7$@EYx`gY5UXWI_01+iEF`G^KO7*hln)B^i*hGS=N!VS`+Nv zG%NGK)l_izk^cJAine%aza;WRyKMuVo#762_tAXYccmAKDq8GozY0Dpddwu={4gyK z8(7~9vv}4DJa?#k3C&!FGCh`F@nzTyY5RR=y);Cg9*s-bIX8n$k7XQ~Z3rrSl8c-C zBm#`2tZxo5jDQ%v6R9TS3o&i~%eChI$Veg5S=Q?YisADO48IvuRCOcS^zCZ7q8eW2 zwDBDxcyXugylOQIuwk{4@AK2?DDJyB)61JNaB-*2hWMxywBgdqA95zEL0tci**AEf zV!nVR{S8*)NcEM1*nr7O<}us%D=aOf9N$^_6tbeOB}= zquS12`K4~_<;t7=l2G?Ik9?fs&H><2dS-5ly)~R$yh~Ohl?}jm3agjYv4YOr!Yf})0mYSZ zW@3Vw=X!P{v8Sbj)Z?l!oMTo-;wa|NceXo{5ul<9SQ%AgnviEza!z_k?`+G z_;)1yI}-jK3IC3Se@DW2t-8KA%YAgq|EeYU?4IWk*|pC zMC2kO^ALH4$SU;ylqg2TEFwY?@rZ~%M64kq3+Ydn$cVH>Bq<^#5ebM$H$-wFQV9{v zh|om@Dk3ZqL5K)BM1Y|SCzO0fWG^CD5t)g|Lqyggatx7CC^3yLf)VkGh)zT-A|ekF zXDCsHF0Bzsj7V8Tf+Erpk$fnrhJOAip^XS+M9de;CjmTd_wjy#9k%>t1l!$zEagGwz zh!{phEFwM;(TF5g>5?BM)zKw3B8^d!7LlTeghZ0AL;$1!(X*ZcbOs+?+1pp|8<1wRX=`7w$h7 z=b75U`_C#nq=tjOyv|eszw<6HZ+FKXKAyYwOs}~!wUeDJtTWY^eu(K6f~MEinc6k| z#Pr2}ruOjt^E~t_&VSbInJN+Z^O@*H9P|ZyrfO!s{GdNhOVA&uC20Dqo~a4^qbBf= zn!xEA{{J{LZa&i|XZje)%0<*Zfq#yB>ikf9x#_2f+9CAkvHwxXMNZV85BJZxqV`T7 z4gGXcJEzxC`eXegYB$e6Cym-8{O5B|pEv3bZu+UCcFdW%@ON|H?HTC2$1~9V|L)fS zje|F$D(45GtY3$(E>6ot$xkP3-vnI&341vo@M&j*bM``u4umcT2??u8);N@a-7F)# z-s|2>{m)MQ0ajy&w=3n$K{k>uY0Ij(f%MLRZuRaOu(qnTpm)<7#32qnN~>Ccx_rwC zK8tzCg6r<(4AH8>RWs@y}#xf(3c(V5ZukYZJN;+j5PVA1|9r_;U|=m&j&{^9Lj1Z%ez zuL@N}nr>BQu}M)t(5B(oMOIrN!N$Vhnju}dY)1L}`#X5%Q!0Od2U9xn-`~O0y72#3 zeg~td}{+wu!@3W6`uVA>67SQM>K!%96Q>lKX;Z!dz*lWInF_DvC#+_ z7{;Eu^#D9qK6KJv@fOxYNio`w*I~O?uABortFT_S_W_fFt$4u!u^7h>%2?v9ccR{n z2dMKvhyTj%Mw$X5w*5K#38+ymU*3H=3EZygR9Ddq24}y`#zwtn=)oMWpI7AWqp107 zN|{?#!8!fPllj%_!Lce4$?;e0C_MM=vk%@HVEf@a&mMXUq3>Z#N~4yCaf48T*JO_ zZI3?+yv2D@MzjRkci%tUoqGudFrMWX4AKV+jtMtQE?fwVG&w4KE~KJuEjGUm1>S(j z5AzS7X%E9v0te6TD3*uf{;UE6{pTUy%3nuy<4&TFXISGa!93Jx4Op$&A4Xfb9k1isGmmhYSgN;*>gExF1jhjn{cJt3B2ylVF)PO3$8u7 zoI1PQ7hU_hDgEfE3rOd$;9Za|hwA4TW-IKBLBC{e#pAskvDisj_1QW}==UAPjXDpf;2c)ossEA!dNIhz7ln$&$a0I!H8blFWN(+IzW3)yS2sF0Lb*t@^J5F zX~@sq{`1gnW+)rINovnYZt&9m(bjWw-7sHL*lD#ruRup~dHk8cgW&bru*qbalGA?U zaHUG%HOy3ft|BD=H|G15^AxE%fw!BJIlk6-LZx>drvto=q3A^8igkVOG4F2J56`4v zt^!*Q&x%i&%Oh$~O1T>I?R|RSh}tzQ=r20=Wz!SLmgp+6;ebE*)LgvSL{SL6KJ_?F zZ-)@dJ%@!a{oq4)gN<18f5(9HH-9pmWX9ly;OHuSS3XoQVfo18*?KU%J&@Nin-Pj_ za#4J9W(#Ea5K}n6ybFBlcWl^px(GBpJiu7>q6J)8@%_%yMu-LNqMscDo?a z4C_rg$ehDP*x|R;ajlCbcuk?`OH*$FEMX+gQ^U3ib9{1R_WwXT{}JjU`6pALiuq7g zOWrxCeW%y6-L?zMZj3!FpR9&nE%kW_3}~MowcYUfTv#COdAfveXXT-)*R_pLf(t-< zNG_L5wisj%T9M8*5efMs!Bc!;*M?Ar!qP zz<;h?81rf}7i?KthPfUDxQYcRVlJoGl{QDdU_Pt)l?ywLW5I{4_2V1#X_r9M_5I)1 z0JK*de_sRqKkynr)RnfDtB)(~^518dBW)3P*O_HcRj01MS!sWHKrFT9`c-Pp^*d8* zt;;2VM^j7GoEZT)fYm%;_HFQF?o{Dc@U(2dP1$}9LhKRxj*xVOiX(&@q16a^Mo2z7 zl}89WLd#L)8=YdKh%`d@5n7LscZ8xNL>!%NBcvK3{|LoLh&)2q5mJs&Zxq2sCjtrG zM@T(F-4TM0qT%Rd8zBV=^+yOkLgNv#j!<%hc%ukHLIV=Ak5GDqxFhr&A>rs`Aw>xi z;*ZdKgv29M9UaO2?0oGK0@YEq$8mg34usx zLP7=-%8w9xw4WtT@0n$MT^*-?y#8rUFQfZUb9xr;pXT&Jy8kqnP5o&8)0|$?_n+o8 z{q#>$<3Ed6{%2Ejs>ww^s+q-o|7cGi*B|Za1N);rePmq!j2iUmL;7OL|7WKUrw(lD z4*{qO(x#g<@OB1nBA^n1jtD?RV4#`mfBKU)0iOuOM1Uj$7ZFg109)Elr02|*Kv4v6 zBCrwxj|fCWhq)*)i$GS|Y5)0nq(z`40vHj{i$Gfhz#=db0i*s6IcZby5rM!6&_&=Z zZ9Mag1e*Fc%%n|$N#wW)=tbHD!on0#Mc^n*fldTkDhQkD@$dcw&?2xE0jCHAMSvy( zmK9i$XP(&-c#D8o1gau{6oH)xbOxnn05SrDkw+tt7HJcBiv0i3fiwb_QJ@$d`oc3k z$@eAw|0Qo`KY`TmP(Sa-quA=v! z0oLg783D-%6h;6q0&7v=7455Fr^bcpv5GXNM+DNC{&6Rb>9K$`rpGAKm>!`>V|sid zjp@;eG^WQU($JhbjU3bwP>YU}*7PyZ@0&gddTaV9{^Od)-`m;MYkKwZ|LfN@gh?fQ zDPctk_emH|!ebJ)lCY|TJ0%P$;Xw)8NjOcyT+$gO34=>`S~?p`ajtY`mEuq7EGc1gDbAKKvxI*oEGyws>5M61b}9ar&e9St zmSSA#yeeT&DVCRTxrDJLyewf~3CBv9RNBwzKbIQ+GhNgC#|ZMT>zkQZMJ?4`Pq*?3 zfj0Aq@+4Mi@aeT=S>>c2=rFxs#{8oNe12j6M6358=rZal^=~f+-OnORGMhx`kRS#8 z5qOV)cm%2=fE*omBk&*v0urc?0D1(rBj6l?;0RPm2LvhDkAQmw!XrQ(f#V2lNCyWg z2#^4M1kNL%9UYpZAVdNb5;%|!`ccpx9l)btIy#(4Ktl=|Bmf|R`3RUtAUgsr5&)6F zgaiyEkRJi|=-w^1TG|?ARYQ65G4U3>2MAO%;_K}iBV5`dAwhy*O8Ai@8Cj3ED9gG^to{9hVD2)#&1L_!r3LXgmY zgxsT3cofx02t`605^|7GfQ0Cy(|Hu_NXSJ(ArhjH(1C>Xqf>hn1xbiTLMIZ^kWhn! z0Ho7=6dg%OM?x(U0+G;!gbbupeiSuH2uMOR5;BochJ+X-^dF%q2^mQ!M?x$T`jAc% zQdA(FvLwVLp&tp!NKuJ&!jPf`34KXON#YrbJDY}x7l7xCB1S6pl3EfFZO*(Z+2ueB)Ns)~d zrAVkxLU0lqlaQ5!k|e|g6 z0rhkA??gMqfrfYZMp^tYcz01Jow@8PXm-v&qc>_s;@kwBr$h4un5STQIw(&dc>>52 zIG#ZDbfBKV^aP|Q5Iq6t2|Pao&eOgI@)GZV{krmxAo}#3(?N7vkLf@3rJAy+_oMGo z??)F-wQJsjlBxHlWd}gn)P9Ew`k5M_`uC5PFFj`<1o~^D_qG{kf&M7|zR`EtpkH$3 zx9pHy(3d;QdO}(g^tqkMQ)4OueTT$2zm!-|PtO1Z)tls_lS_fb(e_o#k3|8|HA+xm z=X)^cWwD0qM|CiJUWU|MNsQQTfQ8S0ngg+k*ssxxr(X$AJqEZMIwC&wumt4)FYR4< zI9A=>Mnsv1gpipE8G6lGEAtSUhs^UlPl*bJCPhh7y`m&@N*TghB}K?sQWPTd6cM5C zdFAPS&-u=Gu5*3YIoI`l*OhW}y?*ypkXW930(iF7HH}+8S_Mn z3(`zE1S|DUT@mAZh$KL;_$5atBDXJdbgQ(h9=Ckcny^0;Wv@9CZ$?>F)T>%5k5T4Z zMwK_dgXr4gryFdh{U~vH{_Fi~3`pm~laCVmG$2_~J*0l}F}S_?vR%V6Gg=pvBeq=O z#oSa~#M-)lf3xlb#L~$?Xa0~KFMS2Xuz}{G=p&oau5GgWngk^?dw&y z5iq@*Q-SxfG4L=br`MC(0^FMR6^JJb09SX0peV^Nz=hL=pUo=*IB}&bs#}}@4!2~b z&2)bQ4isVSZwc1rR^xn6#d|*fynfQu5y9Q}>43VGAvwqLC@`>09&?(~1g7NrgQ2Cv zz#`~^$5w@8aF8+M;*rj9U}{YNc`!#83^~?T^K|Y5qXMUA3>YQA#1~d?kpe=g<|oq% zIh;qqXRs=OCk?naLo`L>|tg2o-!r}v@d zopVQv)!fiGP*%0SaVJ`ANJ}k0MTZs=X>z|mutalE?{Ub06`E!aJw)0T1WDxkea-w5 zAqk(4zFk2k`2K{w&)4@9Sbe>0Kwtj|tT@h?Uy#2Jz6mQ{)H%BgEWEz>W=K>4%-)_m zH?2*AR#arKXH_bo72VAx{*T$w%C5!2(Hw8I{G7Ja<>EWEyup#(vnLWQVcHA7r_!RY z@2U=(H`b&1uycLI@#4ru_)@Fh1~KHiZ&7$F{}ghSP)wq%eU6-)7wkm6t|KP}DT0-} zDYAduyQPJ05?TFzuU&i@A=^~a6-g2cBK}Bt!B=)eML&YA0*22Oliuu2Iapmy}FAQ8#!tVYGn!dLvOjS<7f`_9uytJXqx4Kg{ln)0sr2q=jF(2$YM8IDyXxsCH1pKcAWTjy= ze~7Msi__P=CX|IV;&wD3w6#-~PolPZRsf=vtG!5mGtKl_?p3sxZ)A|sPv%?VOKr$>CL+Mvdj>Lfg?+igJqHnyp;1Pr= zI1*$M=8CS20p=>P+T^#Qk&b@Gr3}SeYnB-qNfcGOJ~?-^$Sgt4kvvPka7)m9tZr&5 zUl6fjVh^)fk|R{i9m{Z_2$No zDIh+5t8G{72-u@waOFXtHu#P9ty0CC6u=P4*yc#EC{m0`ca|zTv}VyUc0Xb->51BG zyV6gffF}1@zq2lAlQMW0;#~wjYL8h2xZDRbrm`v=hn2uG?ZH+%z0;7acV}(a2ZeQO zkD#CTZxr&)98VWRK~WMkmvb+mBPQ~f7d6hHm|Z8m1DoTJ?Yl2x|nfYC$YI)8oOf0#}5qz5B7yjtIXnwbS0oxenPM_&h= zr_>*?vUdSCy&n{}E6SjtrFcHIa^;`#u@MEQx2Tz;Q!HN-#Fvavocd1ptY@7l61Hd< zUw1`v?wtJb-aLpr^yu($rYK-gUx%7&Fzmd$Bl>h?% z5l<#(i&5u|c+O*~6`1a`S6#a55zM1|(2#xuGcg_v%PL-N*HkCqKiC}Ky-L8pxR)+- zf`I?DRru0j$j1BDQztCsEecr=NV0lJ{RCl>dMTt z|9v^Y&u6IA$EzvHaSv*ilZ+|s+=t$7Oc9lODu>=P$F}9zd!ctN&Y6A=htcD#$jQDh zk)Ufc%jv79N%pF(_rb2Wq}lSA?jbIA%@I$9^GNEnVshiQ2qa!*FXg3t5&37G$$MwJ z3)m#@g3L8Cz{|DIXD}tTYTtSvOzNe%Yv9TNBn#jTw>;(o$&%=9T{n3HzRNmfPP}OX z3yB;fMy?pVeg2X^xX&HUHmwvh`I}WKuJ^%eo5uJxx5WU7-GMe2aw));>^CFVi@MRC zkn|z#MOOq%D&)UCssKAF^n4X{?t+80nn{gQLcjXpA9uj7KKNH3{Qt2J2A}Mr&RVv3 zp*H=w$QXPVJz6wg6u;mG9&8O!eR_rql^pSBQS~iD?>>C}2;GCh=XXNlq5I0w=*=FF zj5t0R)N+#M+2AWoAt9yuGWrUXVLztVQSODs<7FE7{H|lT>-bZ{nJXBq1YW*z&=lKV zrQh_;Kmgk%^vmp6ia?DAbY2WN^8rko{8*(`9b8e!;FIvahwdbeDbvU%qhOic-50rx z0P=UL@LBXnZI+a68ve_m)6I|O#nHWRd&8$ZZ^CRHO78ROg%pn=?S7U6^6veRPPAKw zOv?Z==cVqJyCDlXrZq}=Lf9eoc31C8nO$gxs-

z#Wh(-`$hTBZ#~okI#AxvI5l) z9S@8T>;M6&?K&yGmyt)=D{B$`aFkGSN-d9O5!~eBIHVN%23>yQUzjU*2~(ah3@fUA z1UWUdTo%})A@9wm={`qwxJ$C2+$^I9?%|E&iK;S!3Oz0N4d%L_c>a^IXS;4=7Vb}R z#(@cF#Q3)q<7)(gbE>OttOx@*@kZNNosi4brn!#)i*#B zD|m!=+yKmQ41IAXZv(S3O`K0hdr?iG_axJG46eM*d${}R4fHVSDg>7PsB)=VL)ADD zB&BtvM~aZ3p;MzRpATq(V0l=h-%A36hi=}vx>Ss%1ItAMyc@xHehEtn6LPGc^*-g? zECn_^8s0Q?_Z&90RbNDphL! zU$pI?eU3pz+8wd)&RDfwDxHuqV?BZFSHi>L*!;poQ@(6DHb~U{vUSH}tgyIfy)Sk* zmOS+Pwm^w!C{ZtQ73~ zy*Ck;i01NLZ+T>3Fcd5orgY>M`p7*{NoF})w^36SZMD%(Nx>mRzzn~p;RVJji_!5pX%bMt+Helb?| zF*v_@mlT%KIGXHv<2D9O1v1eJ*_^}na2|p zoJLUPD`n>GyBJE$wB<|)zxkB|{F;pVLw>(LbM!xu1N?>V`1#^bM|^Sr-wys0R*lc(eCeMqW@}i<=VuKKV_=K{VS~x`(u@f_%d?Ik5FSZPmIp48*0A4FB>MI z2o2uO(@5_fhGx#x>V6~((Ap+_!)lr_Gr49| zORVxzw%w|l3~I_QZ=InugqokZ?ZrPSLxbkhy_)h?(9Gx)mwt8)v^Hs#ZiwK9X0_r< z3?=dqlu#(UjmBb@6|H4K^9OiKoF6xB?{3U?m6E#SYZ&H0QX2HnkKye*>wJgD^D*C! zE(4}ZL6}BG_HftCIHWRD&?hI&hED#*<|kL(V1QoXm-Cc@Fi5Z6YefAq3=^W1rj>^< z^7dKwj_5f8{wHcYq8VYxZN*?owgIT&IdC&p(TeEji(}bBOq9>5;&|a3AG_b_@}>;-v$2@AD@qecKh-=m~5yUV5 zS7oGsion*$*gqs3WT4T8HL>%BGHCfs1#-7^gZ2lpGQ%1c;B`2exX>Y0(4}-t&^hlV zc=vsoGxPltcwZCF+{chlblv{xwoP=|UU%32>8ee1(_VMc{?nzK=*~@asTYv=bz-MgP;GvV{!|83g;V=BYib4UEL7Wt3I za@JO@@wq>F+5aVj{bNk#)EpQt1^HJ(oY1q}+x)j*@u9DSKG7)$ThXAD3#9(2_$5&_Yh2ORG^0BChfxl%m*rv>?^?!v6& zQaPYYM|-TNoC>tQh#oPU>jXVCRi+Q)oxxzua7fdv02r;0g(4@4z}Q`RTZ=gfqIEft z3dUE@U2*^#LtN_9lYT(oJfoOds|9G*KDwB$mJ4KK1)gT5b$|`kTu!1(FAeVfnq)isDIdQ;LMD+JqUk z^~`UYKfX%jMZl?juMT#Q_`^*q4~1uitiXJ8ignL1Kh)4mf8D5l6pfR8b_$G_MT_?j zjAZH!p_#BMW7hDEL|z0^KYzU<@JJgBva8JLnkQf?o;&&ds^sW9$`|ueF9RLjAEdmv zuY$ff8mTjLU(wifXZaFY!#Xd5vCyG$V&h0wELYR;(CVkaxeFcIzLOgjq& zwVoZdyZsUJK@(OP(@@B)dNii+bRv-#fppf9A=yhtSlDKgtz4%POEA0?cRj?3h4we_ zo?y1cv?mU=Hy#{>tRHhXmFDY0k;AkxDc&PQUIf$Ck|y+y?}x(iBXN7eL!bmRX}`uC zKNNyNu1Ogpkk;m|Rd0+2X01C>|5~aHi}+WXW0f65UIbHY>)9mqS|1B+(-#&`GsTh* z?otj9T}R8sSENH^k3wGM3&Q*seqcyb^1}FFFQhzMZqUQhN909Nl$!0b_3?XnlWvJ@ z*76jZf3edoYs*Q{@ZrpfUfNkO_O+{-N~#_#mJbfBxE}&DCxPdulVn6*1XE-6S~7(O zG`OeEoaIsS`r)$=?3A#O9<%!3%qL8H{IN$wcMoLkUnp7fBZDHL zXM+#9O%Zt!OxIMmeQLuID15SL=Zae;lwjhdJjv8ez`s&ZeNz>rwO-OI31-2p&pRG{ zt*O8wK8iTSigTS8>A@5{jn+=rFJl3|tShhN?XhHW^1Fo?S_0qPXhh(*Ag@Bw?At@b zV5k~vxZJ9Qlt<^Ubv(X{hFCNEJ;r80ORcLrt#TTATCTj;G>jLO1=dozv6g^(W~mO+ zG)@%%Dbe72Tpg%>yqvtPJO$OOJ!c&c9K+U*to}-yRR84O8#P|0owRV zXIVz6K=1Jr*Dk8GKznhA!vgn8A*gt=iNrex(}skxF~LRf?ttGWbCLU~b^f!KD}NTc zadd2BA$t(0>{t38Y-xegxQ(ygKK~p9TvTM6)Jp(&=zLD+w@89}QQuCJeX<1gUE6FJ z*flYed*A(+u34DR<3;0EFCj>-owIcBz&FSOUyM%23BfHa!`HWz)qy2DS-EgGK2&hd zDdeo#0hD>WQ-G{K2b}jjkaEHJ6gY0m+@Wzc2L&Em$q)HlhiqSZHtwTrL+2#r`yRf1 z1xy)>OSxFnQTWCO{Kr3OW6t(XGn{_E;a#N{ztwVV#BwCM?Wq=by}m>a3S*f^aQX3`?o43emuO&*%8wX*-8qKe(8g zO+>SCH1E~A%yKsy3~s81+h_z zw2|VTL})zzq$CX$87VMxn>g+4IMyQx2J6f{)9F&M6o4$T-0&+c#^^P!3#ER9CO-gg!n4$I}8PIRW z&ZbXgVq6=cmzSKCIYGz3Nj1Q}l|>TopQ3l|@y)^NN{jbqJfA?twCQRZ@ea86TK3gz z!C$c(MS50y+&#F@nPkQ|-h_aER(tBMOlVzSEShIb3Vqlfr5uwmhK5I|LS7#xJZDBST_h%izLq=h#JDeL#s@9Tm66JCsaeciHOYQDFYeq$jjG z8EI^6WpuwG0r-l$LY^C?AWafhIjy2U#6SN$bNY*9_1~D{tV>V9l>4kbW#CsZwd|iO zU!?{nvuC%-xABAV)*?%X#f@Ns=V8953q6=DsCrN^ss)HOm)E7IfJxh5P)Ml?uq{j6 zwm8!R$kFKQ4zh2E`lT3`Lv$V5%ve&8EmKkb(ar3OXN}6wn#=3bQ&1On{Je5)JoxC_SC2eKS{> ztph$!bGjX$D+aT{kGXr6yuj>YK-lW`f88vF0*SdYWtSs5oHp2K0j+NuS-us&tUjrbhRI3Ei_B- z{a%IY|0vmUC5^ZQPaZLgpL@XoKAKbZ?mM>`tk+y7N>9;1K9!`I@i)N#B)HIT~lt1l+|LUkm#wx3vYnJ7I4V^#XJgNor``o^Z6PB;U6 z(_--0n&J(~{KA}D;&dPd^(($>jrowgswql-{|sEOx%^XlI_I9J(^8j?7WZ6yPYIkb zsgCN3<1HFY@#8%3hRJ}r=Wkaq>C=(KI0tRKUUQi!Jq11;5nQd4QmFWQ;z`p>Ht1RU zi5v$PN8RaJggwAh4#G1?N(o>Xc>fxpD9{IC}#+ae$l2Vt zAl6(aN>A7D9~f{a;P0ngB$i3QUzkL4XFCCZ9UVP!8v_1~t73g&1pIG#Gx=5$@K@+e zxU`=rJw>LAt&I!3RmTu zen?M891z$j>fg(C5*T?IWnES8K>;qRBIj>!LH64oHN3241a|J`wicU5fWPjSDwff+ zz**X8aBxO#U3%(>d3F?x2k0JT(CsvkelOpE*J9 z505@2z3G6wd$X)ESX0-er#Av7ft9Sh%Fwo96riKLP!vsroQ{1C;yyKv4s_n-D;n=b z1}>JorP|YgtHJV6 zA;D_}lL@yQ$=@(2YlIe^vx}2Q&>vOR{vcKUX!Dm`VXehKW=hsp{Y?V(C-t<(w)}-C z|L<-8Ot#kA{tw&vXK`!m{<4p?wB|2|zP8nAW);9Y$sIC3yA8&YV)!&@U MpXd4a$0tehUlmco!vFvP literal 52477 zcmeGF2{=_>{0I7*=Xt8gm`r7EFs~I#lpS*O1J|G#_hbMOEE+~?k#=lOp3S$lu>Is5FKb@s8|=d~Q77B|U$q;sUF zqoWgD73d|k%EMJkN>fT*O=sy+9St=p4K)o-4$4M4!Rzx!UjBYkyIlgkTwHxTc1pSUxl8Tb<+95|)ypp+XqOai4=>6_PyawE>RtWZ zU&+NZ4C`~Z8uL34^P)69_sEMOI&^(1Z5A-**l#* zjGuQPLiulY+s_8Lm}IFUt$PAw&n{y?;b?K!xxwq8l-jP43M_v9NDEZXuD=1EK4xXx zEF=c%g}$B|(s>9PE4{AX8VCc;!EXwEQ#8O!#r2Ps*Y<%|ugb68l2Qb1F-xNsk9vU) ziRVjf-E2T-oWmWXeQQA1Os9(4*%hEWVCzlsJIg^&$B+U?wK8~bxhs9VM;3f2`!3x* zBMSO84qa@VCy3q&$voTJxD54g@)+JL=!)K#G8AX~%${^>I~a6k^6DyIfyFN~$~@Tb zj74@GvDqeZ9rGKVn@(6hvI z?OuBiGdQG;4=T>VjCarTIxcvKnLY%p>T)#(?OF21wSxv=VCRADhLNwqhrmImEuyL#8B;CY`1}$e=E5 zc-4s?(xrYf^lK}G^vfU4(F?r^8SEdlS!^nYjDwH&(8m`*rVE+#=PX_ZIkRtPZd_9j z+CEPSoLPDnbp{H{4WC|uKFKW-uG~?DM%OrBI=avweF~QMbM)DUzSr0fZLzq88kO3n z&Q=7&Mb~VmLKeznRYhkP$Gn?ZxNFnEy2N%UVJCdClI}K?7FDBP*EKq5mhZs@!Oa#}{?qM{+cr>DPupW)8Ux}dn%b+i5k0dUZd`3exOUCVu zH>2(iJlQ-&MVK?B^|9Lx3)HTyD|%M!0qAsMyY+zm2l&M7S?sNu3`T<`HP;1Cg3sw@ zJ2m67z_@>5^i6CIS}cPHo_{aKiw=x_6yBNxRYf1I7jHZTg}XcieZ>W_#4#_?K35|w z)xN3w6I}xqjCJT2>RyK#`gR|RiHrmvnVa4+CYXaB^^!!{MeSrHf)?b)^8 zM*)0^VUWJb{s9cVE4r2Dp9J3Zyh?T|zW_}F@2a?8+X{uOUK@VC#)oAu1$^5te+Msr z9k#FNg)Lrjr*hnOqcC1&)ADKAsw!+&c1uz8+$L=J@R9Q7Wvp2K+>3B^4OjF{=hdD)&3(HM&Dh3U#!(v0R_f#yzFg@3(tXq>OG_l?N+7Ssu z!3G8^agz!x8(nu=h{+c(zg=I=`Z^Y`IQ1#7q{JJqGHijzwa;R+%c&Fb9eLRBCG!iq z^VhNbT>I95{4VtEfw_xuwKZIHM!NO|#}c?w#iajLwIDPYt$!4C=?4^h#y_xY?n9{h z&CRCL=PXuR>aF|v^d+ng_PjhBe+sKyesfjw#3H3#7>2s#|`-*#%q0&ZH8r?*4#4Rqeo`|OQxK6I_l z=!z}a3~f{IzmK&$167&p^tKo0V)N1%wH}KmZ2co}v2NcZEdB1J%iDEw&}{wiAz9m} zaDC5}Bl*`ZK}-53x4Mc@Xwcztad}=Y+@PY74tw;KY)6m4 zP4Wr$rv6FL*_~s)tHcrL`pB-lUrY$vX7KB+E_H#bYR9@(jb%7eGq}y^CQTU!g%;S+ddnvv7m#)%c|iyP(DQ z%>1!OiqJw)ZSQpL0JN~=V-q!A3@vim^f>g_K}%mH<pn_>U*ei;;yH8#y!aAV3i)W{4-X*UwS*O|0Grs-CsbLVS`nUb0zN3I)GIbjwS^K znqk$)Jg>|?euJ_O3>>Okq@em(-H--D5Y#kP84z*+Kla348LbxQi z>H5h+xZIz2e6y%F6bm$2Yx>q1OWW2jWceh86;Y;Uv~VU~V(xZ*Nwg-EzN570lGh5j zaI@M#L#z{K7VfNe$*_a-a7F(mC0?i!L01tcFAe#4zi=C+*I?yL(ZXfYJFp6SfWV&S zbyy|Tl-^?ME>;zN@16Bj0;?8IrRVksP~M7#ws{3O2m1T?IQw{b?sE3^r(7}oe2W&Q ztq=6ty6uk*f!&R~e6&Z$OaGP7i0wrO!@{pHJ@RWfTv&IKb?$+3%#+H-YIj60t3P zx1hl4%`f_0OfhqC|A&t$R%mQc_p;ZCosegf=UtJ(R?ObA`9=416`JZP%6aZo3I$d^ zG7<{5z|0}%oANsf!PvPJ$X^=RE|Ffa>XG8mEgM)em>a&MHYt0@5tu=cP zwASoV@VHa2BWF+M&wHYrOV-~Pb|XJm{m(z>8i#(sl@<;lx>8tUax1L?HVGzFY=(bNhd(N6+zQT$O=Gt9N|kNU$; zz{3hk{fawLmoHH2ugLIcT2bmnwpJCL(4YIQ$WVfA7pX6?RJ~BZ;FVZnX~D1aH13PO z`ANaVEk2|A+7_8Nj;yFCG4tHY$QrSz#CU0d=freY@w(TA(tb};OB5q6jz+N_&^Mgh zoDxD0^$jbwy|vxgR$^Q)kv0*0Ri9aCL(?gR27QxOW2e*UZ}r)BxA?to*{^T4yGX#{ zQ7n0UFg%$+7s6Kr=pq~^(6TIW`HEYYOKMqZ@2C5&dW+AZtIr!VAAQIHqIGdff#LH( zU-BE~{wszc{>XXVBz|pRm928_dJhBWE5BRbCU+A3xRYOZX`Vf#lXcNf=4wS#CO_Q9 z>kgy%P$6G~InU9C=HurVA)Q|kA4wJv{wrdEpwi<)Ku*Y>LH zZkuJ0PbK$C*RB)DwOlwW)Io9F>Srr{IzVF$n+P@=_GV~vj0G23w^d;mH1 z$z!Ev3n3rZcX}Qvd+>f+sbay$BJ|#U`Kg>wCLqyn`C$L+4XM%RYEjOnWeB+M zhkQH>g6LRE!23;>E_SYK(R;gRx!=-?z@^ad`3z=UV7Re-&a=YLfHgm753bAy58B0_ z#;~s}9f@O$u1d$~a_XrToh^z$jIn4HcyJu_Rd3kE1|NX97Vh;^`?-L3NOvT+fJ8`1<`rvy?g})x@nsu^55+L7@t( z{VPlRU&_S~3Ce?Jp`4t7owreP-U2J19Db1d<(BxBJ-m=#W>MFk#+zWWfBSNUr>1DK z*MPCb>kWA4A#`m)NhL^*KRzUNXFbY&9+TPcU`MIfvAg+kAEmxaJMyUwrM|%K{^A($ z&i$s0$^I5Fe8`CTi`7=Ze4ufT#k4f2^v$eylFKXoG<{A{<+CkHPHkSQYI7Wjq5?}N zlneTeHu?n~cn)H#E?>RScZ9w0J&IAkgE&O&@w zJ|-9;@v05-ms%O@N%cT%hlP{7)~*9B8z$Ox*YqJ4gZTT=y9Ggy!x(SMq9-Vw+wmg5 ziW$guI@pPyb3?Yrs$3~@nvmJf>&xN$*_hcTI$V79WiaN^+J0%*RdA(Lak=~kHk8fA zlqiHYQR;){o|gPUsdwXbyl+gYKWr1J-$SXla%8R&1jEwo_6(}$0bA9zZuzvm}Iu77``%=s9OJQKH zU-`kW+f2b=@cf8}Pt8Eon9R;?fhJ(TQ~q`5$qex6@)5Y;LnRtF*&fDFg z96^&u9aj1>TA-*``^6H&@1lK|X6~lDucOpoSM7;upw#cXlMysRsZWI;glZ}Ep@(%o zh@%i+sXq1>_29?%0`6q!0_@@zrhf4)2Hi`w9G$;8AstTVyR6?z!1t-NgBw-epj4H> zs)I!sQ2wd-*B`l$Ceor_8+J27k#T``!3st!GT9RoI`9s1yzmlFU*icfprDo7>P8gw zK29cJ?h!PRRneCA3PF({tdjI^=3w_OFzB1!1d?JAr574{2j_Gt}m;d@u8w1rTl*k^QdQ z4?c88ZMgDm97zx4`VP!@h72XLx0qA?QPMKm7h6ZypmQr8uQV`J!$KQ9RlPbMLdhPL z-0JRwSaQ^6k+U`*6gYY0VpEi@uv^o>~Sn0b@9) zE*%hlGF*1x#2PTNRiWc#_(>2crNoq5nE^r)-XCSE&j)=DWrf=p)S=-+bYs#<;$YP3 z#-PwwfAn>s)ijiSgCb#N?5WNI6cTYa$pSA2eU4V9k;%qrI9#ksJUkzaS}#v_GI?5j|9Ii~V zXrbLp&(ew4aiLpfSvv78tJzgN)H!8S49Exauoc>@TgEsM0 zglOBY0@vC0>jf9;U>X0GeWkGyZ~=$)c|kokyg*{nGcLC+P()pmX?+tT7%t*o%)(>| z=;aQ*?HgJNaKcVD*SrNlBx1j*p4KGD-*JIwu=G3-bcF%>!SdkK0PB$IXEhMj|Kmpb zls3qCSIetQFv=KV znU~Eu0GeI8HN>+1tX~`7dpw;|pG+UAehujGs%=PfUw|d!Lm2xW^#P0SitTgz5rsn4p09!o&g@ukO;K6Bs4V{{; zKxnI>I9-M-7^PcXJDleW@}GOmd&jjDJRGWf()-yNoh{FIj7>{J{X4Ri*6zs#BUOnF z773GRQXw?q#_h)_zgdvqO0@?)94s)s^jry@ef&_Rt8xkI4~$=HZSw$(JYf!Vl5s?n zip7`jo2>=wMz?Tu`Y_>zbgtg^;E z&EVxxWv$2M^{7e0QV8GCFRfC7lY@cZL8-*c7t8sB!CXGKx@xv^FuLb*fKtIIsI=L? zVPir!C{iq*c(G{-s$y{&U|6{jjlYHa&t`Ri@4G{lmUYd+^!E}^?D*h;DsANl1kG|# zky3o5@5ei+imq7K3_CZ zj5hauTku7;1vIrvcUv!T1Ue2SCd%Hrpn;WBr$Ac(jH`?US)o|WWO}_!a~`?Uhat(l`&*_N%Nf9KV3oU9zH@Uw5N%g;g38bXkyTO+TJd&BY9%$BQ#;nXy`E zxkJF|XsEWg_Jo$*Ijp`}!?0EEEf|d3{WeRW4e@`f6Qa8lg5I>n$c!>PHW z2g>HxRxiv>24d|^-P4axfzb$ub=9>Q;K}))KS{{bt^PpH5d%bRW4c>ok!QMILWYpb zdTXXQF*CJ}x*cp~2)tmBbca$OH~3@!G^IYzVs+#crQZ2XZ~`x_-os?`yy)p%EZ}Iy z{5JLq5{-P_FXPe;+UM@Sf45{eSX8~+dGV_?=t>WVP3ip%R5`*RdA@H9({EaESut-A zGMsq&#&iPV6HuX*f|!OfKNyr3L0Q|<(A>FdN*VhZP`gjhpyf7cgFbVQ zC)M*#frks#Y^pcz1M^j%`i2x5g3&{4N*Ao2fl7^tc>bV`=%!Jeh=V;3Fj*NXwWHGm zGs--PFu7j}nFee#_HkNb#$!^8IMrKFrKXxkE|(s-X(4pUZ*46wzv0B%@YtPF|F+{4 z_ZX$#=h&h2P|SFI)3}paJTSf*TW7W@8B8c03*eG(My9v38XFxKfbQx|QARuoNOJMq z=mLE^aK_%LZ<=j48ggzZ7qk~f)vap}Wr?~%(Z#`4%^KY$?)06#6Q7$i( z-W_DiDDemkxt)uRuTBNk)m6(cev5^o$~Ne6b_C{(9_#-4BMEYPnS>cE%z)CngkHEm zz7IYs>nc2PT!i>oqA%NM(V}kW1gyPt`u~od~W#q7HQDPvc6=6wmfEdE9iADUIsE<`z-BAABO3VSO|8}1Vo$7Lsvzyn|uAdi8eEEEcaXc4v z@}4pD@11~icC4?9i+Kx$J|1{r^2P=WH9NOEeAfi;?ntzJRA~bfUq6J1)Y+g;No&(b zmL_nH@39pU-eOQ_cwu7O-Z3oH!dQ}Q5DwlA?0T9#HwX-6tUp+P_K3kyeU#x_wGq_l zu_Av-f=21*3$D*uoO8f4t3zMDUzY$vNK2}oGaQUYxt`{2-41SAr}uP;DxtLLoEwGr zs=?dsAqhClAI%iW*%-?wK>Ez9G6U1inBH;G#Yc?@-8A#B8xb=Fm+2TkeO+HJgu@9D{;OK2(^hmO^=-v-uY;X<>QS*Is_} z??Uc#NAYu?`(QXXmsQio70~n5rhVFS83w(Iy!3q~x^4R0dVcVHa57i(1@Bx3N`0wIlfwZ@eOD^~X=h4(kM^27&oI3oLz}rz zA5!v~dF*wq3eH_xYRx-72dsMjhWSI+3(9qYc7o*F8$d|Z%e+ls0jj<=$7Tl?C%8X< z(>Xsz3D8n1ULBmH1?LJMF9WMaQOyw+&5yhnK~0Fr3oM=nPPgrHf4*81-4|ICI(RS` zwLJOpnE%mkO1*kT$fPc+35%CJ!yX7~{H~n(VX6<#C?Bk6%8CWU-%}L5cC0g)Ix^N8 zd~hyGEe~Sg8p|$y71g*~Rrw}poL}u%Q-2VMyv~@s_gN8)uKZlsE-49eWWm9Z^?@j$ zbL~*euEmtkQvuu#jZB!1eR6}(rPGl9`L`v*=SwmD2GK=c+VLnymTPa)p+XQaUhd|> zI6e9DWI`8OJ}|lG zW}Akb;MTT zxb0D$TBQ`F-sX|9bQGn2!-MXerIh-$oK6>1DD~5M*?P|qpM%WuPSI~5f1=fzW&J2% zs#r0yW8X{gJdaT=mt7FhDcD>U^e9J(H>~MD9rptkht);RAJ~DQwTE9To=`zA`&S*+ z&=W-ulixg*X08Jd6QZhHPH}^FrJ%2kbCb||2hOVrEuknVAvh_~u8vaQcPqKJ7(Gn- zQY`Er1RkDDH8Jcl1?`JiZ!vXMf#Dx-eBVTw7)(wYj<-m$fE4@X(MOM|8`KuuG2S%# z8Z<{A+u)YY4CY!_b7EdjFuK%6STcbXesl>NRb!xQtAs1 zv$%j@0`=Qu6I9pvZCY7yyk@lKQ0tyhhHi~ zQKQ>8cD^hHp^~?y9xU-h88)V?4jHDSksH@V^n^UnQ;iZ%|DDglQ@Mox$RC2>g@VMU zz|=|}#M_7$18Wahd`_oDa1 z2FG-5*CMIan|qTY1i)Qxp{gsrM@qjWl-JGM&X4wux9dKw+75zWy}vu(hYMxSN%*wT zrxXn>3Uzfac1IP-X_H1O?VuuI&2SO60Z)|bF55OQMgg+bk2yxqgG^0zgSz@WG^898 zdCO7;RUDIGRGhK^6$k2SPt*^BCz=P`+0!b(|He21cp((pX_74j=E^2Ll(;VkMm3(= zU5l&$Iok7I_b{aV{yTf99#}r@hw0#l_|+B4kb$#y&XDzOOqWhSeR28;%AsUOKH!`` z>doqfzrUc=zf!rM)J>^JSJ=cLr9Oo9hU)=+^KXhiH#!vcEi(o@r0yq`7;f&E`{w;_ zeFygdx(&CH-m&GcSJ&^otq;fT^ZG;c^aV%Mf~B=ymn?fJ6J~O6ufA}1%)>{IZj`L| za(uge?JmK|5A%hIiH zZIj-*@#--WP$9t&5~v_S1zG@r46Ks@Ycdc_23V;Bmn7&y3y_dt1~u?Nf&^rMo;L7J z29(J_Ep-5t1ZGGOg#(g0vYJ14xp336$vuY0z%Z_4K2_@4T_Ke1_?HhzyKMDC&4XRAc`6^A^{#+Fopz9 zNRWdBBuMapI-pMiV6`LOkVXr7Q3F&Ym_!0UBuGOGsF2_X2~<#n3MAM@0%IhIMFLK=;1D&C zLkqf)00{|ZPy-JnAV-2{B+x~IQnUaPHQ4hzFhdQZPy-&c-~=^jM*?gl7)AnDv>+2T zAoM$U^DEFo3yP2c1~srpf^Z~YMuJv>*^QU_%S8kU$7EKuCglB=AOpWVC=5HTXme6j6gZzXLGTUyLoAuz9QLfFGL%gxquS&A~dp}+36$~`mR6akSM+b6E zM4m36l!Sqa>-)>j2mf79+R(_~!bmZ5H|9PmSQHf91OsEY`{4E}e547F)_=Q*k2LUK zHxqRu^<-Hj@aq;dt6lWL{M-)6?pUjMIPD?a`AuTPift3ABg-N_QjbP?=goPE*~^}} zNyLrAox^C-@k$$xvaUL}o!$jUnJV>4B*~Kfic`rg>i!nfO;5gV;fKsG7VW2xaDcm) zS0|{X+5NZbcMDn!aK}xH&&SL^)H0Y+KisV}eYUP_21l=0ti3eo9*$OFx&OKK%kMq@ zdkfkKR97(M@#A`+2POEPg-6pSPgHtKv0tCE_sqYVY;W+|I#+9NAZOuYbk~1vTMJ?y)!_OZc(h zG1_(JpZos24Q(Hd$IqFL1YdJoB{(N{z@R5?O$m!;9t8Yd`Kt|W^PC&sOfdDp8kV3%akVeK;8qcVCTGZa3yojn}r9L;jL++he59h-r5poC=hW$~ z<5=&48pT;#ImZv6!AI3W*e({bjlF!78Iu5c>)&a-nMs7+%d?NksrtYx?i%kehPXo4pMFl?!$Za?Zp?Bw&1-wRl3{t z9>e7)?}qzb^FVdaHcocCUPDbqq4n_{3UFETlbbc{_aL{>p7NI-+u+Vs8uyMhe1J=l zF`HlDeo)suw!D+&6l%H@T*1068fs#6E=sQpF#!`A>?PiM;OP84aK(nfYTGHw>o40*Yew`r4C3HethUb! zAFJbrTyBN<7`o1l%xB=LA9rV*eBw~4inMG6e?Dq$mXCNM7z*{r;U+2Ln~?bpY>0nx z5(a;txzOJQ;EG0`bvMf~DCV2bt0wstwc=#slE_`qXp$w=?sP9^v3io8^4b>$f1Dag zNO^a?@)k6`pZaiOd?SeOLqRJ0qS3I{#s$X(lib}DV`8Hc_ zv`#^A<<;93c~9P9MiK2NYu~3suVvQSCs`Lm+a|e_H#t1fpk4nF0fX(3Z^t#d{FEfD zFUbB?4tqexEfU`y%GjZo@d0zke1Ci}wr8e4?-D+kxMDFocQR@(;htW@&IjaV@20Gm zRz@cE-<_W=3<2$BW2?IPj{~NB5M2fXjMj6pESY$Eh9lxW7NFel6*J<4(plCZ1OyBN`UI^2vm&@HmBI_R2 z+9Zb}MZ3zxfn6ftg>dGPXpdMRbVBPw$L;~3$fPdX(G7sqw34s3&2}IayJJbA_Eo5$ z%u>-@eF?Co-m{!IZ&5n(%ywn-S0k*T%o^4z6^wWWHb>nOQ!f45WE={b#i10#%ETu5 z2E@>Gi)BrI3*f>pOV&(!V<`sHRTr{F0Gre0;oufFBrzkdsQ7R`n6GR5a(7P~5UUzx zF7MTX%J1@~_B|Le$Qk--vf4fg%rW9Da%Q*-xW;-d{+<1 z#0OHA*&>BEG(DiM81sRVl5?eBPSWQvu6T(!+&D*aLf&9qF_w~Ayado)UNSi>7K`NE z%8fcS0^kAx@3+YtwjtJ$80)c`5F|Zw%08k_3NH}wx%kCY&|n6cGCkk-8A-HTnY#3Z z0oiVb6FfrOz@o#vyE#JCuGl{>D^Gy^jyf`LK`kl8y&hQDCu7E6p96zcGGwV~sFklYZS7nZ6eR z9maZ9J8L95zml&-t_&?bW8jyY@fdGV74>!-d4c4aBF)e5oCZp9i(hn@_reXT^A%OR z4*+SiTRU_P1Oelzx$KDxS+RZZ1Fp@7FC&>v6>)U>=M1KA887&DLJCsW%fw9N1DStRmiC?8I)7j54IqDzrMQi2yFojX<4Mu2)9@GFNF54xpg$K0VsVp76^Iwx$al@|5lWg4~>l$iJA zQ!#cge?0Mw=`?n4Znv-ZvccPQC$5ZT$KY-1?0V+PSFmV@@Yk*JJy`T@Q?^{z0jSCm z!~M4R2vl97nVdN<9=c23w0vh_0o~OC-M`u1pd_YlzOOGSfi9XMxhFv$`+RqOE@Tp)sNUP%MAX9aRkWzX%gZFg(-kzWH4JO4*<+GCMkapOo8+Y<- zk@j)EXbTrU#F=m|Oi5-L5_g4LWlh!Jtby zXU2YjMc2||D8FXhW{bw6GqMXX#8*GeEz=PA#JQI zAujqn%nq`j%3ZgS+aB8P!92$U9LRRvcyjC45-STBUz6Ogi#cq6+ zd`=+C;)DO)kF+4K!dl;tJ+_#4%R;6VgQd_X^1`~ek5u&jr|Uo7LB^~TjG2%(g=5k+ z;wJRj8>=DrLIy{egOt5(p*X_i){TXY7a_}htB+S}FJbp?OeouzqDcmX>~QnSb~m z8rUHk=yY=oy7&$F_j}&Q;f>E#R;6#p;ZGL%tlhZ;!;Y5qTgw(>#`MP2%et}9UEy5i zW2G15dFuW3{4wkr?vePQ3>l+E1RZNxD6bQD|MNHJKA_g={9PZ8KjiIAk;dVLjW%(m zo*1s3tnJIknBK|C^?{fqbYH}4@XfDGH-tRmuchvmUrP+lryn(BJc9JrsgGCQc7pCQ z44w8VTmM^4M^{AZ!&7v4EMK+Y@Pq@VPDZaW+|Px3&0nD@{-C4xie{j@xyYN=Rqy}a zpR_RyJ9L-t@DP|{XT4`MPzc?P*RAmQwx~FYRQz{Id7R1BIh!C3Kh7-s$n`#6@ycqS z*b0okPR+0Yga6r4w`pXyjaM{0jBM~11YhmXdup{rLHE?XS}A3; z=ch~EjVy6^c3hxp-!>e6jbG+KVmLO66MX1<@)P=WE~9PboP*{Nnyq$>fsf8D#R{l%w0N@j2Bw!_&a<@Y2}9@bONCpO#Uv^{RfWH*7@hH&+JhIr~AFYNhVFV?Fo~(k9gViXOUi2XWpJJAkdi^m2|XrGwAG zLbh?6%TdP$-qQ=2^5F)f8V7leQq&*mS(kG1Ep%sJa&+fdKHhWZOAh__db}rV>lf}w zZ*1)Rv9&|77c-0=G?dxd1N9?JY;3<7K_krrvTs8R(Ae};#O9`2=sAIoJ#wzY>kz|B z?$J)jkj}8{K+JropJ98=U&9}opXjPmjQI+_X0Tp6eL4ktzIW6+ohyhV_+5CGCRXAI z_ENcnE8b#5=9o*Wd0LqB7-w|a2YTpu!2Y)5dI(hx?sB_#}NvT)9_hM-y)OMb5eXZ(@S~;?7(9`YEa>HPBwn-5VuQYBg zQrM5fi?@3JxU&!Io!oY3U1mOJxKYoW?e-D6EAh9BwKHG=kGPHoT?>#Lax%I@Zx1@C z!Smv}q9xYtGEa#LwSx>v42A86&!M~2uxnTa9k8?~m~o#~SC^?*GVZ!gRXs{r0w&&|S|ha*OE@UTl9zvbkz5xF%Jg z^VRMtI>+SJ8pJ{QLRH5Qn@@!;q+3eo&6d6bx@$(qbxLJo%_jSv>YA76nts;4&7VY2 z(n6q7UtEsEPlxp7^B%(CF;Zpv;R#qxgx&Wsm_d_<2k%Xw>N4_x$(wq5JbeFG1C6 ztm&?5qs8cjZu3Vtn43zYJH8KH@3QA$IXU2bU8o0)S_X9%goHr%>gIAAm0ql~*jGW! zwH4%8q=;rM-h^_KMcwx}P2lhcJa0A{mE!O_shLxub=Y;SUk0a0+<63K)EIM(%A?WjcDe$Ph>wCED73iuMc-urd670^LZmD@%0Lrw*Y81`{ zVOK@}NF4;xPWLT`^Tb9_*;)gi-J4zkPxfthuI_vSJQWA*Q za11~-^S0T?r^dr=jxBqbjN?#DU};ZhU?QlI3{btr7z?-RCU0oGw+9^W71VOJHvp9x zd&Mqit-xD#Q=~ubpFz>PNT|8(10~`u_{=!=*7nN-})}?112`TFvuXDzrL(Z`mqgypWnTz}Rjf~5nMfIbeWJ7Hb zU@}yG@;CsuhxvMW=dHt(^_M)CYomaJEYGv&kD=TBopmFAEu|xOpE9Ku)s~I~oEeps zZonqC1qU}g=>*=P{Qt%q+X!1PJ@*>@EGu)t8w%} z_+V+%`L4vHN@q$RcP+`cXSTx}vSF>KRU&}mVFu}qW9GdDzb^1C^U|JEu!lQtHADXY6i*N+))2I^JkEe@Lx~(uP6N16aMQ7 z|Mi6bdcuD_;lG~nUr+e2C;ZnF{_6?<^@RU=!hb#Czn<`4Px!AV{MQryzoIAPnw`{T zcIFk0pHG;L^4~(Do&O)53WZ2rG>M8TEfGnGNI67;A<_wvJc#f`1S=vm5rK#ZJ4BEn zLdwr4@bibrU_`zmvJ;Vuh|ELe86vCv+MAA!h+;&{A|ezKkBI0)#2O;9ko{>A8IiV# zBt@hoA^{QUhDa_%Dj|Xy5xR&#MT8|H2oWKN2rx9^gespA*^9_kL}nuL5Rr9=97ALj zs+dMZFd|;jL?&jfiDLB<5xIvXGl^J7L^dLh(L^mGMo~p1 zBL0v>Cz0-Gk{glAs1g@VnxaZdL<*uML5Yw@1UMp`Q3Wp|R1txR2t%|4DUtPv97kj{ zB7ae3DMHWjS)$UNKr&Wq9t94 z07w43Gk0hgMVk8j}iTFoEJ0iAG zMKU68kwi63nk14UkphW?N2E8ZWJaVe%5ku{x=<#e*)fZ8P;ZC)JUr^{J%8K|{dt>p zwtlwc*Uj0AUpHq9cxZF<{G7Yz=PulTPR{dl1@G@!c1R5eZF-%b1^h04-aa1A+x@-# zcFoSY^K&ITnONs%WA-j)X9${|SLf%d*$1Xg_VaTM-|xqvRdN2Fv*%}tz@LvqE8?I{ z*z>dI*Qp5p7uTjok!`9`H!fpd48WX>KfrcAA9z^ zQ8#eYP91f{oL?9I?jC_&yIpp9?e_Tp^=E)#x7(dX4e8)jbg&BFumQ+gA6+x2eg}%F zSH61F`XI9VQ5C6Cd;mmLu#P^?It%<%CT`3e&Hwo?`|}6b_YA%N^dk((^pCA#UdxZz z#}sa-2b@Cm0a37!-yP9ip?_+2rVt3|sq0&X(j)ygxwP+(OfK zZpfVO&j-FUIxhTh>lo-QZao~DO_}9l%v;pIy9>QAU%71^YDFzWpSS5`r0K8trS+ke zFLU>NW7-bX`6}cloR$Io9Qv&G$XLMs%qvTDl*8b2ga{w&KJn7lym<-{J`RW{N9ykN z!u2H@zm&g!@4>&mrSk7R_?J%n?>+dJF8qI&_h3}PzMb#9#tXDFN4w(dGky?kc&Sk2 z>m?L)#xA~QlO_mUT2ihowh;unyDgAQ^hMXzB5deVKY{{emT^vXJ2c+=>4(F&5Ns(? zw(`o0E!fPD5rkCB;uUSW%8v)^v6lBawjPZPyfE#M-wKWQQ1W8uk=l-BP;1KQ_~dha zloZT#!_-I`+?rPqQ?8Q7R?IlrgaU8R*wvdI1J>X79&y^9gDj&aZoCQ8L@QQxezT2n zN7A8fr@_tm(jQH}*-T-J(H3_&93xW)Je7-NX=G&TH$Dcg7OujfMn0ns1In=QZ>GyOX;(^6R4q+z4$KrR~R z>21gt=YcF+yO_^3d4Z|w$6A}duLk8yCC9EvEyD}}-^-f=s;~h2*6r?dgt7R|O!JwP zb5J!??J>Q251hAxcY~ld7iG2w7MvDdfSFZQQ|&*0#jKW%k3)H*Fpo#W$#pfpSTJV7 z$f@TM7%2{r;8T);oLAPHINCl1A46N`=(S{;G;Ib^)01?0$Qx zP7m}9F?@-**p1$*HMhtM#iMTlksSMFQs8PKC12NO3v46!Y;0q(H8zj@l;_4{OgaB! zl@AQ~DCb{llXoROmOS*l*lgu~C~x=RsqkDTsNb@y?Q+q4^f~{-w%Rp1P}=mMGTmJd zFh2LnJe!=Wn8n-0i*4W(ntC_0@9h2OsQiN9`LpN0K!&^DS*%v5K>jx(CPL2g;B)4c zZLJ;oSlWavX;9RMo_+{SIMzd!{v&l9`xUGqy*0wL50Du6UF5 z<}~J6y|+NCg8>U()wXog-buLxqF(F&`wT$&wDIpV!2cgU1I%@!%;oCuM!Ed=_j9I9 z;_miq+S6H2kCpNZ$OBGL=U&gC&aIwDoooHU>>TT&pln&q_0M+>fJYp2>Iz?e0#$7; zV_|fzgxDkW9UPaBvc_G1PSd&$UQ>g5u%O|ii9>KWNQgp02NKecPPhcqm zJ`sqC07(QcBB0RkJ*kgR1*r%WMF1xPD-rOBKtwc{i-1{F$co(W-|*AlP!a*X2((22 zEWLx|9{$&t1Og*K7lE_LUbh#OrSIxU`Aju8u&$pxCoF%g{x@$ z{{q%%@EHNg2oy#DF9K^(!7Iv9u~Ykn*-HV^nC%frWA^1v8nb-?Y0UOfq%qq=k;bn{ z$EkNc+dGjhT0hSOY0UOa9Mm%Eq~oMDdknN~vj;(I%^t;nu4#7qxVU-G&OZKs{+fm` zse~^jtSI3=3ByTvOu|+YR+Vt4gdrt7C}BGZr%9Mg!mtt^m9V9R6D7qJS$;S31>=}Q5u6wcv>nOOE^~=vr6SpX)Gy~%_W>IVP*;cN?2CHrP3HvDzi)D zZwX6FxL7LVO5;@tdrD<_371P4Tf)l{_LXp~gh{2mV1Hj~%)Y#SH~(*aP4k}~DFY4AdtTl1ki7!KxQ(!fLl84_TS3jYz1k3e}e$dLex1U{sKgaisC zfFFVN2>eJuMgk=gz>vU#1pFfqAAuqX;7DLa8hA(`LMjkQ;64IN67Z2gj08v|a3KK& zY0w{mC`40#_1Hl0c6HU?eai0Sl>+;Qu>%kl)uJvsWws=Xww- zy+}wzLKPB1kkEdF+@n!=RH~5>ii9>K9SAdTju(vgI8B-A1y5D864$Uqw9N2MkS0ZC{^LM9T*kPw4}{v$Lc zAtMRpNQgy3AJRxdDiuhhED145=tn{_QmI55VMwI~34KXONp^FO z>&@TCPl4`ZeWjk)2=0WNj2buZ9tFLC*P4v4G7lwb!OkQuA)6 z!eP7gm73`os>r4+Tr;zrv`J>xqUQ6{2(w;+fSTnJBi>XJnwrJ5dh%^sX*Al5JqNr>Uky{sIz`=W|Jprkwz?GVW zHi?iZa2t@Hqg5jTJUZ+OIwDMfr#(i}_Z%F zV-ql1TUOgI76(2IBuX4g><7~|?`ciwOu!6&LiIYt1I%Qchaw{lV48pNajoX>VASeC zshdbUTI$_idCK1$Efo~Er*iK@OMIh`A6#2RU)g>;#`HaNczkO`RqABy^Pzk|?Juve*(5L>ui@Qs`cQl@jL73Ut+A`R;(w^E3V6n?OUA zwG{@71JNu|#hzsI)Zpww zF>kf6+T{$Ps7?(p;R;_AdGJIC$AwW8-W#|f;anLCyS)5dg@+o2!G@^B*Cj;!kxBQ( zf!<9gk=yH=hpV<`Apg>Y^cm@W=+wURY7#3K(V5hhvMk3v=ydU`P^zPw(D9J6tHyX6 z0sqiPpuUcP|F^M(=2ry#7rmXoMS^L>ePPgx63jfHKUZ=$lz@MZ?C_;01pM1n*wik9 zQEOAZu#_DH{51>0Gp-Zxf43)bR0S>ZZ%$q>?oPn}Dd)Dp4+Q*+zYTHu5b!@!knKN> z<`zrENJAyj)VU2!eCLV@_-6_;-!>)Sf5P>}wr2$VO?%ffb%5nu?t3x^^}#nmn%jPy zqXhiZ;0RkA_#E3WBR?=?-KhqBckDiarLQIQDbODEJ8mw&eajfr=XQrwzW7$XSN3`dnQH>l zy;~6v>@~o~J=$^Fl-h_Yls)Cm?mb9t%d{4AS{1O25l#E(Sq0b!I5vJ&8(Xu?2&vv{ z%&giR^AXf-e(64@yB%~)u+^Cc>VO`Tg?=@IQ7~}!Qw()PCK%ePY<=*HEf{$nZj#yh znP|14ZWza!VCOLhSl3NO?>iM#Gxl68c9K;bQEJ3iLm<3P80o(_=Hx&6b}(e)Jv~w)(_)P3jStS;%sK zwax{6{gxiQU#1U|Rd4*ABF&3v?NP0N*qMBNh!l!wr?8}pA3-TaBBmbs%qWZA`UbO% zKDr44vnY(OpfnlZrr=79t}1PO<~(PB0=8Zu;cKU>-m%sD@WOH~$nQw`RHH8n3P1kN zmwAE_W}}XVmK^&1L9S|SPi@tnm!(2S9;HDh zy04@Rg8Lw|u+*Cqop&Ksqb%JuF-5|Q85dMuNra+>^zfHjL*$rk|6y6zSM^xfM@055 z$D8U+Avfm2*9U?3E;XAE!rZEHGy-bx?(gXnCTpRp&BjvA-Xr8IC=)h~Ncpo!D-PR5yT6PA>*h{cb|i zB=*M>%chX#nJZtG!C}Y}cmBrHA|A-0_+fd(Sh#ve2Y>p)F#^gjP0}Kh+CWO|#Yw>e zBam6MX`8qS709~BMB^sy2C^ZmsobtkaQTXh^C5dDWW!K*T*YFiIt81_(?p3UDBng2 z0mnd8*mddln3W~Uqgt21hHOw;$~%$6$}7nKeT=X-*LiT6TqG(^sddeoMO9t*#SYuc zS%Z*?LByYgvYLRus^#4eX9)QFb6pl#0@Dmt>$=EaqJ`YL{`6ji+4e>4asE6;v~*FY z3g|iVvL_I{x7llN>9CuC{~MLCW^)4mhZwCZc0h*lk=q*c%aCJfy#Q$+7ZiBA6$zG~ zgd#L%$*kL{)J+2_S*#vLq4$=pgW% z4P$|s1F5Jx8;kHuwbC83BmVzE>dCLgWcqaAt>ax`-M}6K{-)LxO{|dgN)U@j3J0X= z6HrZXu7@nKnJ_DyA9Bbmt}}W{P8k1-gz}T}{)>e2A0VOpGZFpY7XuLg1E}yt^WoV` z7``g0Zv*FUgRr&?Qs zO-e>sM@=0O{c{fF`za2PlwaaL{k0JYUs~UHHM|(Pnn|Q=>D2({iGh|n^v&Q9=Vy5H zDJSvzkVI;(>_q}2B=@W0eCbpHNsrUhkKf|~3loB;&mHRl;}b8`b@#kSt=mqY=gUw) zOO=nJ)bQSF&9yaHgV+xAOrV*x0;x?)tTq8r?8 zZz^y<6^d>uM18$nD1v$p(ga7}mF))Ahod#SE~tuF?jj&bM4){9Fi1-tW5MGmtY zt8*;4{p@bSZqgtSsx2qm_T&OeJ`zakACm(dsT4;YgAV}IkfPFI`wcZml?7bOFa(`u zVq;%6$3ad7s(UdLWRO`?f~<4p45YOUWIwj87SarM_|>)+L8d-uY6DV9$o2SyNB1RG zNLxO^E7Sc5eS8u0;Z5!ra88kPQZ+Iic}~S8aq@>EdygYkTkN66d^$_n!*5f_r^xM+ z%SkO1wQ|uyFX}Q#Ww(4>l4XM8j|w|s=|M~kqt%8Hk`aQQw}%H zHzdb!hCun>=tT~#ghJ)RuRFQb~X&k}eQ_{@2%PVG({sEId zPc{Z4d6Bz#3JXxf>kV5vc21*_E8=WIv{dLrYi*;*vt~3j>TJ6qQ35S^M|$w$H|T@= z#(3eEcF@!LNohy!9k^p%m+gM@R;(DMpxCzV6*kl?zIEgZ2{zj+zi`IyD7J9may8Bh z#12W^&pRBbv7J1x*Vf|oP<|NY0IfR^w1Sh=?| zeFM$zStR8y^Freq28wEet*E+243|{ZAeMi_%`*Ek0)vL!lw&rw7+f7~xa$>%HI03B z*&^exu7~-ZpvH1+R%Keu$LN8L2gbX3jApP#$mITn^&7Did+T22h*wZ%n(V%JMi5kj z6MHMvjiIWZSK9~ON(kzNg9KSJp>Ac?hzj}uwWBFNeu|!l3U5BGpn?Qc>+jv<{UsI* zb?2)i&5huV)rSPl9oxY}1=4^?%MNriIqjBsUohzC;9c+&okoiXOOF@cy$|x3)?M>5 zw!^et7ZM)&2cz*c%BBr@G@zl)E!TyR(;7*-LmukX0VaQ2j*r~s2*wt)hn^m31rs*c zZF6ULfEkvqN%699=;=XHqDjXHwU;F?2{=E;it#cE<$CehP{Y#qT0tH*Gf~33kUzFK z;#$qpyazi(T&1~p%NEwnFeqCNB7X00ddpiCdqMKutZ-5t+)} zP}ez&ul?OyXjU(@DO-338ef=7e?(2NYkrOL5S18~FO)x3daMnD-rw%AUev@Oqy4>P z`5e|XFq&ARXvVq(N8c^|HrVWmSQ@lc#m2WwuLisNU?8rOdL^#~OIhS-C$^J8S?X?^ zsvA;JN#}K;_=GA{)hfv5wQ+% z|E&7k{$E>3NYwJbAE{*dd&~EIpmlwHrd&CIO)YORgDTW-lNvEh z@`1+7PanjMZaJp|S$uz=&%fH=Zv4IFzW2ZC@$Wfa$@Kqro=Umz{jgGrzsAHa5~%HEti9=W z0MtiwjNF{hq479<%rYM@G+Q)q5lkqDR=rgQT>LT6qUd1f+vN)wv(<5(;GBcEdG2d#(rV?JYwCAn-0G=?d-MfRurY{t~P+>KffC805{#4rb+Imj5~ z0FH7eLAyD+0~yENp>LF%2OemGN2k!Db!I;dkX*jf{$K^3Kw`|MIyNwvChw+N&MfqA z<5G^!7=k(!`F*0nN<=?jeEun(>-cg5hnqDexslrANKI*#t^VaWW@D34UCKrrU-J0e zI>#t{QLN*{Yz#kkPUi^)?>K&rf5M!j&vOWe>q)-jzq%1e%1~C!zW9h^=$D#aob?Ff_T~(NFWkb(`q6 zz2>t0!(E%`s!ep$UUSj@>C#Pf=O(&x|8V18bKxesZ+~~)Cfw^!Uf$|2`{(ZJY#3ZU zz5P81ViN)OzDHM&{2_k#qu5ON{`ZY~_xD#BR?kM%7AHhs=bAlDqv=A zi(+7K_MNgB zefjw|u=v(+kGt>2T296oGw${e(ix7!>?KCCLDHKrYuSZbL&Gze#6fyEz4aLw)~eq3 zEMfqX_LBRW%JD+_kzJ}2v2ZOXlMQq_zhtwL*CVS}_Ll9Y8c4QE>U4SMbD$zzbazv` zBU0<%RlokgU8HswPrPc1*BBYwp&)sRgjg2=@Af)YKa?l{y|{hDSN9z7^o7unnTRzQ z;0mlLs}2A|EjHoW4Dn#(21}Ajh$$E=@z(RXU-`W*Vi}2q1gMqXN7VzFM724AvtB^e zs#ZH5J+5w|%yw%Txg%KY-D}a*Pqx<$nyHu5BUKMZh!uBEQ`F z7)W8U_1OFKAHZjsX@64`g&L;G1d>NTp~-_!YFYQOqlJ&NXURVoqWLrZ?bEd6#JUKi zG@PuKmL3G77K;(<06AW#m-9eC+LrKgt4PMCq6yUUV)xlx9tZH6@i#56cMIsXv$4GD z5m#be1d9er_usyM4RdzMDV_96#bn1V4Q>u+L9*!PK0Omk$RmABarBElwMctBX8=v|lB8S}!hO35lV@cddJ|+-aeBHicv?#)7$8eUmV4c%gFFmlu%j zL(qNQK65DUsW0S|aE4eH!F1MV7-Pg)p@d0ag@1H6lnazGD*b#Nic#9{?DErxw1=rb zRu(d1w(f%iR$mpd_@Ssu8$)tpT?8{Jk|bM9YGTnxmae5K(OBL-H@y4h5GwK_J;iEf z1cd_pEy(#Fg0}_yJs)KHA^qh+iib%qYju%RsC!vRxiMq~Q`r9g?g`0W^jTu3!U9Py zXc*d;)hB8PCJ!Y=#kQn@h53==9PQ>{K907cUi%mvxL6%QtczgLppRTTol7w1hxr5h;Su%HPS#p^Uyj6Ltc+K$g*#%}$WKG_OIIP=lxRZ#=}%DH<4W=MRApja1k>4# zNFMM|fD&e>-R>mIL%Gv!(aM%d1pEse`a9zxt*h=S4bg1O)#x_RO)d0=ymfYtG~HhxADo zaF<5~db6{|=UE>c=qT2u9B?~?TE1Qww2JdZSKpf3(0-c*rB-T*X>ydHpu**b^aCSM zsBGvQRj-RG#cFez?%lxqCGvx-2=!SDOc%E>@CF-kGDc(vQ$f>dvE@dtr|@te&3aFx zL3lvQp7!JANT^pnhhS1FH1+1s(lmMtx)~`QZ}nxMPRdRt|F=FU{K1l<4);8$U3Z9` zY~=*Xxg;C1-tvCOG)cB@c;x8+?vL-lPD%SL;??b@jVUT?eZc9@k7tjNTwUyiawWle;~ zx6_BPsEf$5gjWNkWv-=iE9-_jrnWuF*)EVqNmOCa?sB}t>-jgmU2ie8eW0wVz=S0~ z2aO>s11uWGC$^9u2^A0NAJO)RhBU)FIScgkp`BiIxeK`=c8qiGdQifJl_}X>Jnqy& zot;Lq+sw@1PSqUho|qk2q@nVLl$H?Iv)UAtt^1x@=T%=u3|#{qi- zLftj}aKOIKg=5$pWjM%woN9Rnv0(QU7%|q!B zge}ReZSE$fLEE9BhwRdB*x%f#Rf4P+Te|fL8{VA2F2bOKr}_yz*Y|Cfm%;#A?AXk4 zruH)S={WZ$IjaylcarCK@rI!#3zdS?O`=#Q-_X5s;0&hnUJ_LHQieMYe~>!$nG_Pd zfO6LKreEuy>=(D9-Q71^7o zP?<6yrRX3N)-mFvbNEDscS<)Ha?UhCk+3a}XFKhn=2Jp$fMw_pDnwMFY(Q z>~}{x6yt#XeY{UQKH>n2h6Wmw8feBOA$z5f0y-5u+*W?y1v>ZC__~{KhwizFQWi&* zp~ahANkOC2*zC+q-!?`@7?9%MWqc+c2IwY)bE)0KX0|6|n;R3cQ?=fBi2Eb#TvPEj zfsq5dU*S>W_Kv`ol*}28uP(rY$~6|(A4p(->qX`a%~#m+9*Tw%})|^iPq~pD3&U#t>(XdJ3j0>7^;x?FCa4%yr@ZDqu2VR>r_F9ZbXo z4Cb=*g9&jClHy|)si(ucIW(SM*sR=G+ku#8 z+Sy17jw3EEImzrmGQ>m~nPIL>@E{i-p2 zTPr}dG)808(CJYNcVf-EuH-NCEfPe{g{l^8 z7Wt%;Zmudm-yI0&^h~@*L<}#6bIy1h0Qg&7j%#rMBn=0}Ib0;#qB}?YO zT!_`4mbPp#ca}=>x@jwzi^!Mqoo51bYnsbz)Kd^Xwsa@!n+hoIa^ikVw-q#)2b%1U z9|Dh(|JbgA28EDVX8--5rjem3kM0^EYAzG0r`d1YXf*xiK>cLI%=Y{A1Bih zMa1jt>VygUymkVelt$H>D&k;GbD2mzMMJq%@?xVW(3nr2h^cqR80K`ZxD z*l%y1V{+j~A-WYcm~4>MH7Qn@sJTp}o`Uh}J%X>PqQG=h!V}~8MesG?q@>atPDpk< zW4pmOTDWf9BKr*OUbybotk7Z7Q*cdl`3Lp%LbYj}VlimG8l%=Z#rD3Dw{=&1E9>6otolAA7fD3Ke&=GMmZ{qXrA{aaR3&;`~vA zqMTD9-F8${Pia=A@EQ>{m)EGLD0`ZcJCAl8)lZb@rFKc8O3BzT&kqH_nauaP#?=CF z*O)E!$nG|f*;=+&bw2us=JFc#6m;7UDQw6k;NMs;^QK`7Y9gspb2>XnxPHvUQs6Q$ zykoomNuwhHf7_Io9f*Mcs^&70dioQ8-`L$|=JyHsCre3`r4#TkGTs&Tje!5)t3>)w zm~3E0I(%N6sJTp}o)Yli9sBNL7MOlSamrTMnt*>Nx;zz4!2e+1v3N!T{vHu$vrZE5 z?@yhLJ50boZ7zjPfJi+>A1|hmhRNSTi<_!4D)e__(u%O+vsV*-;(yWRv#owCCJoyY zAuvu!!2fr(NcNmH>S+g1Wt1~XcN778=Im%*d#pp=9!E;WtwfQN?g8$|mYr zO$u;}v*^6<6blYF8QSU%Xs=OEm#{$Waq`iJqgb@I{|4Pzb-Xc$N`2N?8namIQw&CB zf(6M4Z#waA$eOs_&)bX|3aBJ|7N%scQBR|Q@lc%`*JwQQR`%Yh7Vm@(jD8XMxUmQE zguNUSwjV-z_i{Tstwn$o(x&Aet+^L{|5%m{Jj7G diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml index 4806f558d1..70a3815953 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml @@ -24,7 +24,7 @@ use_ipopt: false ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ -load_filename: jumping_box_0.5h_0.3d_3 +load_filename: box_jump save_filename: box_jump use_springs: false convert_to_springs: false diff --git a/examples/impact_invariant_control/platform.urdf b/examples/impact_invariant_control/platform.urdf index 9bf231e9c1..e8476dcaa6 100644 --- a/examples/impact_invariant_control/platform.urdf +++ b/examples/impact_invariant_control/platform.urdf @@ -7,8 +7,8 @@ - - + + From 8a1dd0ea61b245a712ec22d57489ea6cb90c12a6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Feb 2023 16:51:51 -0500 Subject: [PATCH 356/758] updating jmping plot --- bindings/pydairlib/analysis/log_plotter_cassie.py | 4 ++-- .../analysis/plot_configs/cassie_jumping_plot.yaml | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index bab3ddeb87..106fe79e0d 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -10,11 +10,11 @@ def main(): - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 871ad24b36..2ab084bfb5 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -38,8 +38,8 @@ pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true -plot_qp_solve_time: true -plot_qp_solutions: true +plot_qp_solve_time: false +plot_qp_solutions: false plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { @@ -47,7 +47,7 @@ tracking_datas_to_plot: { # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, - left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, + left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']}, # right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} From 2f81c312339dd5fcc204f0be70c20e41c59b6b81 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Feb 2023 16:52:05 -0500 Subject: [PATCH 357/758] tuning jumping gains --- .../Cassie/osc_jump/osc_jumping_gains.yaml | 6 ++--- examples/Cassie/run_dircon_jumping.cc | 22 +++++++++---------- 2 files changed, 14 insertions(+), 14 deletions(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 72ee06217f..952a70f79f 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -63,10 +63,10 @@ FlightFootW: 0, 0, 10] FlightFootKp: [125, 0, 0, - 0, 100, 0, + 0, 50, 0, 0, 0, 100] FlightFootKd: - [5, 0, 0, - 0, 10, 0, + [2.5, 0, 0, + 0, 2.5, 0, 0, 0, 0] diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index cfbd235cf6..6916ae6eb3 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -775,17 +775,17 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddLinearConstraint(lambda(11) >= 60); // } // Limit the ground reaction forces in the landing phase -// for (int index = 0; index < mode_lengths[2]; index++) { -// auto lambda = trajopt->force_vars(2, index); -// prog->AddLinearConstraint(lambda(2) <= 350); -// prog->AddLinearConstraint(lambda(5) <= 350); -// prog->AddLinearConstraint(lambda(8) <= 350); -// prog->AddLinearConstraint(lambda(11) <= 350); -// prog->AddLinearConstraint(lambda(2) >= 50); -// prog->AddLinearConstraint(lambda(5) >= 50); -// prog->AddLinearConstraint(lambda(8) >= 50); -// prog->AddLinearConstraint(lambda(11) >= 50); -// } + for (int index = 0; index < mode_lengths[2]; index++) { + auto lambda = trajopt->force_vars(2, index); + prog->AddLinearConstraint(lambda(2) <= 350); + prog->AddLinearConstraint(lambda(5) <= 350); + prog->AddLinearConstraint(lambda(8) <= 350); + prog->AddLinearConstraint(lambda(11) <= 350); + prog->AddLinearConstraint(lambda(2) >= 50); + prog->AddLinearConstraint(lambda(5) >= 50); + prog->AddLinearConstraint(lambda(8) >= 50); + prog->AddLinearConstraint(lambda(11) >= 50); + } } /****** From 80f83c860c0e4283fccdc1d74235242615f475e2 Mon Sep 17 00:00:00 2001 From: Brian-Acosta Date: Tue, 7 Feb 2023 10:47:13 -0500 Subject: [PATCH 358/758] updating script to use two cameras --- record_video.py | 49 +++++++++++++++++++++++++++++++------------------ 1 file changed, 31 insertions(+), 18 deletions(-) diff --git a/record_video.py b/record_video.py index 17dcc21091..2bd474b67f 100644 --- a/record_video.py +++ b/record_video.py @@ -2,35 +2,48 @@ import sys import os import glob +import signal + from datetime import date def main(): + # get devices + dev_names = [] + cmd = 'v4l2-ctl --list-devices'.split(' ') + process = subprocess.check_output(cmd) + lines = process.decode("utf-8").split('\n') + for i, line in enumerate(lines): + if 'HD' in line: + dev_names.append(lines[i+1].split('\t')[1]) + + cmds = [] + + # determine log number curr_date = date.today().strftime("%m_%d_%y") year = date.today().strftime("%Y") logdir = f"{os.getenv('HOME')}/Videos/cassie_experiments/{year}/{curr_date}/" os.makedirs(logdir, exist_ok=True) - current_logs = sorted(glob.glob(logdir + 'log_*')) + current_logs = sorted(glob.glob(logdir + '*log_*')) if current_logs: - last_log = int(current_logs[-1].split('_')[-1].split('.')[0]) + last_log = int(current_logs[-1].split('_')[-2].split('.')[0]) log_num = f'{last_log+1:02}' else: log_num = '00' - print(log_num) - print(current_logs) - experiment_name = logdir + 'log_' + log_num + '.mp4' - cmd = 'v4l2-ctl --list-devices'.split(' ') - process = subprocess.check_output(cmd) - lines = process.decode("utf-8").split('\n') - dev_name = '' - for i, line in enumerate(lines): - if 'HD' in line: - dev_name = lines[i+1].split('\t')[1] - print(dev_name) - cmds = ('ffmpeg -y -f alsa -i default -i ' + dev_name + ' -vcodec libx264 -acodec aac -qp 0').split(' ') - cmds.append(experiment_name) - print(cmds) - print(' '.join(cmds)) + + # construct video writing commands + for i, name in enumerate(dev_names): + experiment_name = logdir + 'log_' + log_num + '_cam' + str(i) + '.mp4' + # print(experiment_name) + cmd = ('ffmpeg -y -f alsa -i default -i ' + name + ' -vcodec libx264 -acodec aac -qp 0').split(' ') + cmd.append(experiment_name) + print(' '.join(cmd)) + cmds.append(cmd) # import pdb; pdb.set_trace() - subprocess.run(cmds) + processes = [] + for cmd in cmds: + processes.append(subprocess.Popen(cmd)) + for process in processes: + process.communicate() + if __name__ == '__main__': main() From dd0859522c06c785f14e30e674841d46f40b61ba Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Feb 2023 12:27:57 -0500 Subject: [PATCH 359/758] updating plotting for paper --- .../pydairlib/analysis/log_plotter_cassie.py | 15 +++++-- .../pydairlib/analysis/mbp_plotting_utils.py | 43 +++++++++++++++++-- .../plot_configs/cassie_running_plot.yaml | 9 ++-- bindings/pydairlib/common/plot_styler.py | 32 ++++++++------ bindings/pydairlib/common/plotting_utils.py | 2 +- 5 files changed, 75 insertions(+), 26 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 106fe79e0d..557ffb4c78 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -7,14 +7,15 @@ from cassie_plot_config import CassiePlotConfig import cassie_plotting_utils as cassie_plots import pydairlib.analysis.mbp_plotting_utils as mbp_plots +from pydairlib.common import plot_styler def main(): - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base @@ -24,6 +25,8 @@ def main(): channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc + plot_styler.PlotStyler.set_default_styling() + ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( floating_base=use_floating_base, springs=use_springs) @@ -88,8 +91,10 @@ def main(): mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_floating_base_velocity_body_frame: - mbp_plots.plot_floating_base_body_frame_velocities( + plot = mbp_plots.plot_floating_base_body_frame_velocities( robot_output, t_x_slice, plant, context, "pelvis") + # plot.tight_layout() + # plot.save_fig('running_speed_plot.png') # Plot all joint velocities if plot_config.plot_joint_velocities: @@ -142,7 +147,9 @@ def main(): plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') + # plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') + plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) + # plot.save_fig('swing_foot_target_trajectory.png') ''' Plot Foot Positions ''' if plot_config.foot_positions_to_plot: diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 6f1c300a8b..9f5bde15e3 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -420,7 +420,7 @@ def plot_floating_base_body_frame_velocities(robot_output, time_slice, plant, data_dict['base_vel'] = get_floating_base_velocity_in_body_frame( robot_output, plant, context, plant.GetBodyByName(fb_frame_name).body_frame()) - legend_entries = {'base_vel': ['base_vx', 'base_vy', 'base_vz']} + legend_entries = {'base_vel': ['forward', 'lateral', 'vertical']} ps = plot_styler.PlotStyler() plotting_utils.make_plot( data_dict, @@ -430,9 +430,8 @@ def plot_floating_base_body_frame_velocities(robot_output, time_slice, plant, {}, legend_entries, {'title': 'Floating Base Velocity (Body Frame)', - 'xlabel': 'time (s)', + 'xlabel': 'Time (s)', 'ylabel': 'Velocity (m/s)'}, ps) - return ps @@ -471,6 +470,20 @@ def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) return ps +def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): + ps = plot_styler.PlotStyler() + keys = [key for key in data.keys() if key != 't'] + plotting_utils.make_plot( + data, + 't', + time_slice, + keys, + {}, + {key: [key] for key in keys}, + {'xlabel': 'Time', + 'ylabel': OSC_DERIV_UNITS[deriv], + 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) + return ps def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): tracking_data = osc_debug['osc_debug_tracking_datas'][traj] @@ -492,6 +505,30 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['t'] = tracking_data.t return plot_general_osc_tracking_data(traj, deriv, dim, data, time_slice) +def plot_osc_tracking_data_in_space(osc_debug, traj, dims, deriv, time_slice): + tracking_data = osc_debug['osc_debug_tracking_datas'][traj] + data = {} + for dim in dims: + if deriv == 'pos': + data['y_des_' + str(dim)] = tracking_data.y_des[:, dim] + data['y_' + str(dim)] = tracking_data.y[:, dim] + data['error_y_' + str(dim)] = tracking_data.error_y[:, dim] + elif deriv == 'vel': + data['ydot_des_' + str(dim)] = tracking_data.ydot_des[:, dim] + data['ydot_' + str(dim)] = tracking_data.ydot[:, dim] + data['error_ydot_' + str(dim)] = tracking_data.ydot_des[:, dim] - tracking_data.ydot[:, dim] + data['projected_error_ydot_' + str(dim)] = tracking_data.error_ydot[:, dim] + elif deriv == 'accel': + data['yddot_des_' + str(dim)] = tracking_data.yddot_des[:, dim] + data['yddot_command_' + str(dim)] = tracking_data.yddot_command[:, dim] + data['yddot_command_sol_' + str(dim)] = tracking_data.yddot_command_sol[:, dim] + + data['t'] = tracking_data.t + ps = plot_styler.PlotStyler() + ps.plot(data['y_des_' + str(0)], data['y_des_' + str(2)] - data['y_des_' + str(2)][0], xlabel='Forward Position (m)', ylabel='Vertical Position (m)', grid=False) + # ps.tight_layout() + # ps.axes[0].set_ylim([-0.05, 0.5]) + return ps def plot_qp_costs(osc_debug, time_slice): ps = plot_styler.PlotStyler() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 9c07f0f285..70e149e1ba 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -6,8 +6,9 @@ channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false # Log time to stop at (seconds, -1 for whole log) -start_time: 5 -duration: 10 +start_time: 4 +#duration: 0.47 +duration: 5.1 # Plant properties use_springs: true @@ -45,12 +46,12 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel', 'accel'] }, +# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel', 'accel'] }, # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # right_ft_traj: { 'dims': [0, 1, 2], 'derivs': [ 'pos' ] }, - left_ft_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, + left_ft_traj: { 'dims': [0, 2 ], 'derivs': [ 'pos'] }, # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index d55868c1f1..6dc1c9503b 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -8,10 +8,21 @@ class PlotStyler(): + @staticmethod + def set_default_styling(): + # matplotlib.rcParams['figure.figsize'] = 20, 12 + # matplotlib.rcParams['figure.figsize'] = 20, 6 + matplotlib.rcParams['figure.figsize'] = 8, 6 + matplotlib.rcParams['figure.autolayout'] = True + font = {'size': 20} + matplotlib.rc('font', **font) + matplotlib.rcParams['lines.linewidth'] = 2 + plt.set_cmap('tab20') def __init__(self, figure=None, nrows=1, ncols=1): - + plt.subplots_adjust(left=0.1, right=0.85, bottom=0.15, top=0.75) # List is [left, bottom, width, height] + # plt.subplots_adjust(left=0.0, right=1.0, bottom=0.0, top=1.0) # List is [left, bottom, width, height] # self.cmap = plt.get_cmap('tab10') self.cmap = plt.get_cmap('tab20') self.blue = '#011F5B' @@ -22,7 +33,7 @@ def __init__(self, figure=None, nrows=1, ncols=1): # self.directory = None self.dpi = 200 self.directory = '/home/yangwill/Pictures/plot_styler/' - matplotlib.rcParams['figure.figsize'] = 6, 4 + matplotlib.rcParams['figure.figsize'] = 12, 7 matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" if figure is None: @@ -41,17 +52,6 @@ def __init__(self, figure=None, nrows=1, ncols=1): def attach(self): plt.figure(self.fig_id) - def set_default_styling(self, directory=None): - self.directory = directory - matplotlib.rcParams["savefig.directory"] = directory - # matplotlib.rcParams['figure.figsize'] = 20, 12 - # matplotlib.rcParams['figure.figsize'] = 20, 6 - matplotlib.rcParams['figure.figsize'] = 8, 16 - matplotlib.rcParams['figure.autolayout'] = True - font = {'size': 20} - matplotlib.rc('font', **font) - matplotlib.rcParams['lines.linewidth'] = 4 - plt.set_cmap('tab20') def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, linestyle=None, @@ -90,7 +90,7 @@ def show_fig(self): return def save_fig(self, filename): - self.fig.savefig(self.directory + filename, dpi=self.dpi) + self.fig.savefig(self.directory + filename, dpi=self.dpi, bbox_inches='tight') return def add_legend(self, labels, loc=0, subplot_index=0): @@ -109,3 +109,7 @@ def set_subplot_options(self, sharex=None, sharey=None): plt.setp(self.axes, sharex=sharex) if sharey is not None: plt.setp(self.axes, sharex=sharey) + + def tight_layout(self): + self.axes[0].autoscale(enable=True, axis='y', tight=True) + self.axes[0].autoscale(enable=True, axis='x', tight=True) diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index 673b562706..aca420b5e3 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -34,7 +34,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, if key in legend_entries: legend.extend(legend_entries[key]) - ps.add_legend(legend) + ps.add_legend(legend, loc='upper right') def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, From 39d9f5c40a3f5346ce304ec091cc7be2e44230ad Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Feb 2023 15:21:37 -0500 Subject: [PATCH 360/758] adding option to use no derivative feedback in gains --- examples/Cassie/osc_run/osc_running_gains.h | 2 + .../Cassie/osc_run/osc_running_gains.yaml | 3 +- examples/Cassie/run_osc_running_controller.cc | 75 ++++++++++--------- .../osc/operational_space_control.cc | 5 +- .../controllers/osc/options_tracking_data.cc | 37 ++++----- systems/controllers/osc/osc_tracking_data.h | 8 ++ 6 files changed, 73 insertions(+), 57 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 23ad4054aa..72355943ce 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -28,6 +28,7 @@ struct OSCRunningGains : OSCGains { double target_vel_filter_alpha; bool relative_feet; bool relative_pelvis; + bool no_derivative_feedback; double rest_length; double rest_length_offset; double stance_duration; @@ -90,6 +91,7 @@ struct OSCRunningGains : OSCGains { a->Visit(DRAKE_NVP(weight_scaling)); a->Visit(DRAKE_NVP(relative_feet)); a->Visit(DRAKE_NVP(relative_pelvis)); + a->Visit(DRAKE_NVP(no_derivative_feedback)); a->Visit(DRAKE_NVP(rest_length)); a->Visit(DRAKE_NVP(rest_length_offset)); a->Visit(DRAKE_NVP(stance_duration)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index c38b1cca46..08831c27f8 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -4,7 +4,7 @@ controller_frequency: 1000 w_input: 0.000001 w_input_reg: 0.01 w_accel: 0.0001 -w_soft_constraint: 1000 +w_soft_constraint: 10000 w_lambda: 0.1 w_input_accel: 0.1 w_joint_limit: 0 @@ -28,6 +28,7 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true +no_derivative_feedback: true rot_filter_tau: 0.005 ekf_filter_tau: [ 0.05, 0.01, 0.001 ] diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 7eb6405dd1..c9504a95d1 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -217,10 +217,11 @@ int DoMain(int argc, char* argv[]) { // Contact information for OSC osc->SetContactFriction(osc_gains.mu); - auto pelvis_view_frame = std::make_shared>(plant.GetBodyByName("pelvis")); + auto pelvis_view_frame = std::make_shared>( + plant.GetBodyByName("pelvis")); auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant, left_toe.first, left_toe.second, *pelvis_view_frame, Matrix3d::Identity(), - Vector3d::Zero(), {1, 2}); + plant, left_toe.first, left_toe.second, *pelvis_view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); auto left_heel_evaluator = multibody::WorldPointEvaluator( plant, left_heel.first, left_heel.second, *pelvis_view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); @@ -440,28 +441,10 @@ int DoMain(int argc, char* argv[]) { foot_traj_weight_trajectory); right_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); - left_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier(foot_traj_gain_trajectory); - right_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier(foot_traj_gain_trajectory); - - // left_foot_rel_tracking_data->DisableFeedforwardAccel({2}); - // right_foot_rel_tracking_data->DisableFeedforwardAccel({2}); - // pelvis_trans_rel_tracking_data->DisableFeedforwardAccel({2}); - // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); - // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({2}); - // left_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); - // right_foot_yz_rel_tracking_data->DisableFeedforwardAccel({0, 1, 2}); - - left_foot_rel_tracking_data->SetImpactInvariantProjection(true); - right_foot_rel_tracking_data->SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); - right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); - pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); - - osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); - osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); - osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); - // osc->AddTrackingData(std::move(left_foot_yz_rel_tracking_data)); - // osc->AddTrackingData(std::move(right_foot_yz_rel_tracking_data)); + left_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier( + foot_traj_gain_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier( + foot_traj_gain_trajectory); auto heading_traj_generator = builder.AddSystem(plant, @@ -483,8 +466,6 @@ int DoMain(int argc, char* argv[]) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {0, 1, 2}); } - pelvis_rot_tracking_data->SetImpactInvariantProjection(true); - osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); // Swing toe joint trajectory vector&>> left_foot_points = { @@ -517,10 +498,6 @@ int DoMain(int argc, char* argv[]) { RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right", "toe_rightdot"); - left_toe_angle_tracking_data->SetImpactInvariantProjection(true); - right_toe_angle_tracking_data->SetImpactInvariantProjection(true); - osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); - osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); // Swing hip yaw joint tracking auto left_hip_yaw_tracking_data = std::make_unique( @@ -533,16 +510,40 @@ int DoMain(int argc, char* argv[]) { "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); - right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + + if (osc_gains.no_derivative_feedback) { + left_foot_rel_tracking_data->SetNoDerivativeFeedback(true); + right_foot_rel_tracking_data->SetNoDerivativeFeedback(true); + left_foot_yz_rel_tracking_data->SetNoDerivativeFeedback(true); + right_foot_yz_rel_tracking_data->SetNoDerivativeFeedback(true); + pelvis_trans_rel_tracking_data->SetNoDerivativeFeedback(true); + left_hip_yaw_tracking_data->SetNoDerivativeFeedback(true); + right_hip_yaw_tracking_data->SetNoDerivativeFeedback(true); + pelvis_rot_tracking_data->SetNoDerivativeFeedback(true); + left_toe_angle_tracking_data->SetNoDerivativeFeedback(true); + right_toe_angle_tracking_data->SetNoDerivativeFeedback(true); + } else { + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + left_toe_angle_tracking_data->SetImpactInvariantProjection(true); + right_toe_angle_tracking_data->SetImpactInvariantProjection(true); + } + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); + osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); -// auto controller_frequency_regulator = -// builder.AddSystem>( -// 1 / gains.controller_frequency, -// osc->get_output_port_osc_command().size()); osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); // Build OSC problem diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 4ed54176ce..fb3e2ea2f4 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -523,7 +523,8 @@ VectorXd OperationalSpaceControl::SolveQp( } else { static const drake::logging::Warn log_once(const_cast( (std::to_string(fsm_state) + - " is not a valid finite state machine state in OSC.") + " is not a valid finite state machine state in OSC. This can happen " + "if there are modes with no active contacts.") .c_str())); } } @@ -564,7 +565,7 @@ VectorXd OperationalSpaceControl::SolveQp( t_since_last_state_switch, fsm_state, next_fsm_state, M); // Need to call Update before this to get the updated jacobian - v_proj = alpha * M_Jt_ * ii_lambda_sol_; + v_proj = alpha * M_Jt_ * ii_lambda_sol_ + 1e-13 * VectorXd::Ones(n_v_); } // Get J and JdotV for holonomic constraint diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index 77176009e1..a6c0c167f0 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -85,6 +85,8 @@ void OptionsTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { error_ydot_ = ydot_des_ - ydot_; if (impact_invariant_projection_) { error_ydot_ -= GetJ() * v_proj; + } else if (no_derivative_feedback_ && v_proj.isZero()) { + error_ydot_ = VectorXd::Zero(n_ydot_); } } @@ -97,23 +99,24 @@ void OptionsTrackingData::UpdateYddotDes(double t, if (ff_accel_multiplier_traj_ != nullptr) { yddot_des_converted_ = ff_accel_multiplier_traj_->value(t_since_state_switch) * - yddot_des_converted_; + yddot_des_converted_; } } void OptionsTrackingData::UpdateYddotCmd(double t, double t_since_state_switch) { // 4. Update command output (desired output with pd control) - MatrixXd p_gain_multiplier = (p_gain_multiplier_traj_ != nullptr) ? - p_gain_multiplier_traj_->value(t_since_state_switch) : - MatrixXd::Identity(n_ydot_, n_ydot_); + MatrixXd p_gain_multiplier = + (p_gain_multiplier_traj_ != nullptr) + ? p_gain_multiplier_traj_->value(t_since_state_switch) + : MatrixXd::Identity(n_ydot_, n_ydot_); - MatrixXd d_gain_multiplier = (d_gain_multiplier_traj_ != nullptr) ? - d_gain_multiplier_traj_->value(t_since_state_switch) : - MatrixXd::Identity(n_ydot_, n_ydot_); + MatrixXd d_gain_multiplier = + (d_gain_multiplier_traj_ != nullptr) + ? d_gain_multiplier_traj_->value(t_since_state_switch) + : MatrixXd::Identity(n_ydot_, n_ydot_); - yddot_command_ = yddot_des_converted_ + - p_gain_multiplier * K_p_ * error_y_ + + yddot_command_ = yddot_des_converted_ + p_gain_multiplier * K_p_ * error_y_ + d_gain_multiplier * K_d_ * error_ydot_; UpdateW(t, t_since_state_switch); } @@ -144,23 +147,23 @@ void OptionsTrackingData::SetLowPassFilter(double tau, void OptionsTrackingData::SetTimeVaryingWeights( std::shared_ptr> - weight_trajectory) { -// DRAKE_DEMAND(weight_trajectory->cols() == n_ydot_); -// DRAKE_DEMAND(weight_trajectory->rows() == n_ydot_); -// DRAKE_DEMAND(weight_trajectory->start_time() == 0); + weight_trajectory) { + // DRAKE_DEMAND(weight_trajectory->cols() == n_ydot_); + // DRAKE_DEMAND(weight_trajectory->rows() == n_ydot_); + // DRAKE_DEMAND(weight_trajectory->start_time() == 0); weight_trajectory_ = weight_trajectory; } void OptionsTrackingData::SetTimeVaryingPDGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory) { + gain_multiplier_trajectory) { SetTimeVaryingProportionalGainMultiplier(gain_multiplier_trajectory); SetTimeVaryingDerivativeGainMultiplier(gain_multiplier_trajectory); } void OptionsTrackingData::SetTimeVaryingProportionalGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory) { + gain_multiplier_trajectory) { DRAKE_DEMAND(gain_multiplier_trajectory->cols() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->rows() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->start_time() == 0); @@ -169,7 +172,7 @@ void OptionsTrackingData::SetTimeVaryingProportionalGainMultiplier( void OptionsTrackingData::SetTimeVaryingDerivativeGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory) { + gain_multiplier_trajectory) { DRAKE_DEMAND(gain_multiplier_trajectory->cols() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->rows() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->start_time() == 0); @@ -178,7 +181,7 @@ void OptionsTrackingData::SetTimeVaryingDerivativeGainMultiplier( void OptionsTrackingData::SetTimerVaryingFeedForwardAccelMultiplier( std::shared_ptr> - ff_accel_multiplier_traj) { + ff_accel_multiplier_traj) { DRAKE_DEMAND(ff_accel_multiplier_traj->cols() == n_ydot_); DRAKE_DEMAND(ff_accel_multiplier_traj->rows() == n_ydot_); DRAKE_DEMAND(ff_accel_multiplier_traj->start_time() == 0); diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index 399422adb1..94bcb81883 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -67,7 +67,14 @@ class OscTrackingData { } // Set whether to use the impact invariant projection + void SetNoDerivativeFeedback(bool no_derivative_feedback) { + no_derivative_feedback_ = no_derivative_feedback; + } + + // Get whether to use the impact invariant projection bool GetImpactInvariantProjection() { return impact_invariant_projection_; } + // Get whether to use no derivative feedback near impacts + bool GetNoDerivativeFeedback() { return no_derivative_feedback_; } // Getters for debugging const Eigen::VectorXd& GetY() const { return y_; } @@ -120,6 +127,7 @@ class OscTrackingData { // Flags bool use_springs_in_eval_ = true; bool impact_invariant_projection_ = false; + bool no_derivative_feedback_ = false; double time_through_trajectory_ = 0; From 42d2d3c1d0f2682096a46e8035673bd963b2922d Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Feb 2023 15:57:14 -0500 Subject: [PATCH 361/758] fixing no deriv feedback --- systems/controllers/osc/options_tracking_data.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index a6c0c167f0..e2a4a3a7b8 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -85,7 +85,7 @@ void OptionsTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { error_ydot_ = ydot_des_ - ydot_; if (impact_invariant_projection_) { error_ydot_ -= GetJ() * v_proj; - } else if (no_derivative_feedback_ && v_proj.isZero()) { + } else if (no_derivative_feedback_ && !v_proj.isZero()) { error_ydot_ = VectorXd::Zero(n_ydot_); } } From 6e5370c4a4606f370269f69ed7ebc7846c80960a Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Feb 2023 10:38:17 -0500 Subject: [PATCH 362/758] finalizing reference trajectory visualizations --- .../pydairlib/analysis/cassie_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_cassie.py | 5 +++-- .../plot_configs/cassie_running_plot.yaml | 11 +++++------ .../visualize_configs/box_jump.yaml | 4 ++-- .../visualize_configs/down_jump.yaml | 6 +++--- .../visualization/visualize_configs/jump.yaml | 4 ++-- .../visualize_configs/long_jump.yaml | 2 +- .../lcm/visualization/visualize_trajectory.py | 11 ++++++++++- bindings/pydairlib/multibody/multibody_py.cc | 3 ++- examples/Cassie/cassie_xbox_remote.py | 11 +++++++++-- .../Cassie/osc_run/foot_traj_generator.cc | 9 ++++++--- .../Cassie/osc_run/osc_running_gains.yaml | 6 +++--- examples/Cassie/saved_trajectories/down_jump | Bin 52477 -> 52477 bytes .../gait_parameters/dircon_down_jump.yaml | 4 ++-- .../cassie_fixed_springs_conservative.urdf | 4 ++-- 15 files changed, 51 insertions(+), 30 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index d258f348c2..ef034215b7 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -14,6 +14,7 @@ def __init__(self, filename): self.channel_u = data['channel_u'] self.channel_osc = data['channel_osc'] self.use_archived_lcmtypes = data['use_archived_lcmtypes'] + self.use_default_styling = data['use_default_styling'] self.use_floating_base = data['use_floating_base'] self.use_springs = data['use_springs'] self.start_time = data['start_time'] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 557ffb4c78..09cde855ef 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -25,7 +25,8 @@ def main(): channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc - plot_styler.PlotStyler.set_default_styling() + if plot_config.use_default_styling: + plot_styler.PlotStyler.set_default_styling() ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( @@ -148,7 +149,7 @@ def main(): deriv, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) # plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') - plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) + # plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) # plot.save_fig('swing_foot_target_trajectory.png') ''' Plot Foot Positions ''' diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 70e149e1ba..1df9bd7f71 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -4,6 +4,7 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false +use_default_styling: false # Log time to stop at (seconds, -1 for whole log) start_time: 4 @@ -46,14 +47,12 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, -# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel', 'accel'] }, - # pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, + pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - # right_ft_traj: { 'dims': [0, 1, 2], 'derivs': [ 'pos' ] }, - left_ft_traj: { 'dims': [0, 2 ], 'derivs': [ 'pos'] }, - # left_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, - # right_ft_z_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'accel' ] }, + right_ft_traj: { 'dims': [0, 1, 2], 'derivs': [ 'pos' ] }, +# left_ft_traj: { 'dims': [0, 2 ], 'derivs': [ 'pos'] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, } \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml index 6fc01c80a0..b4b6ff44f0 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml @@ -1,8 +1,8 @@ filename: examples/Cassie/saved_trajectories/box_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 1 +visualize_mode: 2 realtime_rate: 0.5 -num_poses: 10 +num_poses: 8 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml index 52a368ccf0..ef4f818b27 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml @@ -1,8 +1,8 @@ -filename: examples/Cassie/saved_trajectories/jumping_down_0.15h_0.3d_8 +filename: examples/Cassie/saved_trajectories/down_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 1 +visualize_mode: 2 realtime_rate: 0.5 num_poses: 9 use_transparency: 1 -use_springs: 0 \ No newline at end of file +use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml index 8191698ad3..5fc2823e5a 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml @@ -1,8 +1,8 @@ filename: examples/Cassie/saved_trajectories/jumping_0.15h_0.3d spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 1 +visualize_mode: 2 realtime_rate: 0.5 -num_poses: 10 +num_poses: 5 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 1d34c64afe..16187491f0 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -3,6 +3,6 @@ spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 2 realtime_rate: 0.5 -num_poses: 10 +num_poses: 5 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index e893a45cdb..4bfb919509 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -2,7 +2,7 @@ import matplotlib.pyplot as plt from pydairlib.lcm import lcm_trajectory from pydairlib.common import FindResourceOrThrow -from pydrake.trajectories import PiecewisePolynomial +from pydrake.all import PiecewisePolynomial, Box, RigidTransform import numpy as np from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator, @@ -95,11 +95,20 @@ def main(): for i in range(params.num_poses): poses[i] = optimal_traj.value( t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] + # poses[i, 6] += 0.5 alpha_scale = np.linspace(0.2, 1.0, params.num_poses) visualizer = MultiposeVisualizer(FindResourceOrThrow( vis_urdf), params.num_poses, np.square(alpha_scale), "") + # translation = np.array([-0.25, 0, 0.25]) + translation = np.array([0.5, 0, 0.25]) + origin = RigidTransform(translation) + box = Box(0.5, 1.0, 0.5) + visualizer.GetMeshcat().SetObject("box", box) + visualizer.GetMeshcat().SetTransform("box", origin) visualizer.DrawPoses(poses.T) + while(True): + continue if __name__ == "__main__": diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index d31a951da3..d535516068 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -23,7 +23,8 @@ PYBIND11_MODULE(multibody, m) { .def(py::init()) .def(py::init()) .def(py::init()) - .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses")); + .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses")) + .def("GetMeshcat", &MultiposeVisualizer::GetMeshcat); m.def("ConnectTrajectoryVisualizer", &dairlib::multibody::ConnectTrajectoryVisualizer, py::arg("plant"), diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 23b192822e..08873ed82b 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -66,7 +66,12 @@ def main(): joystick.init() done = False - + max_speed = 1.0 + ramp_up = np.arange(0, max_speed, 0.02) + stay = max_speed * np.ones(125) + ramp_down = np.flip(np.arange(0, max_speed, 0.02)) + speeds = np.hstack((ramp_up, stay, ramp_down)) + i = 0 while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands @@ -107,7 +112,8 @@ def main(): # Send LCM message radio_msg = dairlib.lcmt_radio_out() - radio_msg.channel[0] = -joystick.get_axis(1) + radio_msg.channel[0] = speeds[i] + radio_msg.channel[1] = joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(4) radio_msg.channel[3] = joystick.get_axis(3) @@ -122,6 +128,7 @@ def main(): # Limit to 20 frames per second clock.tick(20) + i += 1 pygame.quit() diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 4b66be37a2..4ae7051e31 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -217,10 +217,13 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( std::vector T_waypoints_1; std::vector T_waypoints_2; + double x_mid_point_ratio = 0.8; + double t_mid_point_ratio = 0.6; + if (is_left_foot_) { - T_waypoints = {left_t0, left_t0 + 0.6 * (left_tf - left_t0), left_tf}; + T_waypoints = {left_t0, left_t0 + t_mid_point_ratio * (left_tf - left_t0), left_tf}; } else { - T_waypoints = {right_t0, right_t0 + 0.6 * (right_tf - right_t0), right_tf}; + T_waypoints = {right_t0, right_t0 + t_mid_point_ratio * (right_tf - right_t0), right_tf}; } auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); @@ -231,7 +234,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( Y[0](2) = -rest_length_; } // Y[0](2) -= rest_length_offset_; - Y[1] = start_pos + 0.8 * (foot_end_pos_des - start_pos); + Y[1] = start_pos + x_mid_point_ratio * (foot_end_pos_des - start_pos); Y[1](2) += mid_foot_height_; Y[2] = foot_end_pos_des; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 08831c27f8..5117da6058 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -9,7 +9,7 @@ w_lambda: 0.1 w_input_accel: 0.1 w_joint_limit: 0 impact_threshold: 0.050 -impact_tau: 0.005 +impact_tau: 0.002 weight_scaling: 1.0 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe @@ -53,12 +53,12 @@ swing_toe_kd: 10 w_hip_yaw: 2.5 hip_yaw_kp: 100 -hip_yaw_kd: 5 +hip_yaw_kd: 7 # Foot placement parameters #footstep_offset: -0.05 footstep_sagital_offset: -0.00 footstep_lateral_offset: 0.04 # drake -mid_foot_height: 0.2 +mid_foot_height: 0.3 FootstepKd: [ 0.01, 0, 0, 0, 0.3, 0, diff --git a/examples/Cassie/saved_trajectories/down_jump b/examples/Cassie/saved_trajectories/down_jump index fce9a4ee1d0958f21ef3fbefe4db554c4ef8f555..670b25fb3eb7111fa7e6225614d0931da15c86dd 100644 GIT binary patch literal 52477 zcmeF)2{cvTA3uC^hRh^GB2$KpQO3PdLK({t$`FMz4@o2{DN>@+pgB@1qye#aBF%+D zvnk0CQO5AxIQ!PG|N5uD|2)6$|n(A46jZDbJij|d3%3*6uy9_s1uvo1U+bjz>R z21|U_`Gxrf1xiJFhWdGWZSo0|@(lEr3JdoP_fhi;42}qwqVM5H+qga`REj#(ulXFk z0JCWSO>O(t09VIM7kVo9fpThDZ4kP_yy-i5Hr4(C>eg^F+$r4(8m88dg16#tp1xv> z2Jf5hz84%g4w~#=Mk)rYf#w^_#vio50j(mXyL{L1fwpKh?iqEPz^8X-Gjc4f!Dlc_ z!VIZ{FVEQY6<_ZK-EM;}GY8th*RJ-cJ|08RSGIBamkc}5&(iAZD!mO1tZ?;za`iI! zo?aJir2ig$sakQ~ptBsD_B*iGf6)r?4Gs*>FOh&OM=haBese2wuAW@*0= zJ41#E3$%n+CiNf0qN|?O)Z912d@tpfsCGBO**#m+OMLsVhNX3KlE)pa#kI_YHIN;Q zaJY#ZuGfOfwYw!R?F@lZxjwC{Ma99-@qI26?a|OEa+|1O;Tt$7|IM}GHy%*zZdm}A z1PkQ(teT^--V`!EVY)t>^#&M-K~Vw0b)aiM3yb-ZT+s5|aZO!c5~{lIoIhON4Ib2Q z_>9-AMbE8HWg5LcgId0)b?!fU6;(W#qkVoMFS>X=V`IeV7pMrf)G$izfHP+YA9U`s zfh^TUruK!;pdvP!3+6q?GkGUiT3u4{!h3OYw}QRV*av;EwNwBra;=uhtslnnmxW87 zx6a1gues;v@5lf>i6@10wRJF~`!(*FtcTEK)Va4Gc4IWaIDR%UavZhVZV(Fi`W_Uy z50<_9auV8!vM+Uoc%keiQXRMq^V-?@9(1?6`gE0anL(9*v7rpw-;m=jpA*P|7UtTcqg*xKu$vFK_oJ zXdZaHCoOvr>&<&0`>t>nwq#cg{w^O6b$ZW9iWH9HWp-v;%9&4Mo|i8`+J+zW`-g@aYKa>)0n9sBD zJzTo*=860}`q13}eRW&`C)QJ162g$xg)L_Ue!0)F6Y6}MrxMmZh?l9#f6rmOjkzDR zj#mXTV%hCmwZp9&@qEcW>t`H!gy&h6Z|Hfp77N9kJnvNJ3zW4Ama5WA9r$ADW70=~m4<3|+k~bQgRThQ{UxLtWn~ z(cA8xtCJKD*g=Qj`#ZL6bb(es#dO;{Mxn`x*>+BeDbP^%&9X>wFKGBIDsQWnDD8Y_ z>7~r^!u;ANWX6JOp^0t(uyMdrxN^2aMdY5daE(|k&tbtwaNUWqF-3bRxN69lr^=Wa zN|&%lDzOV=+obYudgbF(TNIkRN%u0vhC#K4TSxERnFmezo5hz3`a@Tr*;n-!nLuMp z4Y$a^1bW-uUiE|5sWIr_H$P@^i5s-)PYdE@dIwE1g!)bv>Ow=A6PzPoO`+kVANyI2 z_n;@i(e)8OFM%`Voa1rI5247363H6b3@Crz?Jm2VD^&N7yzO9d3u-Hud0lnv!E-sk zlvFfjLgBWXr!ML+U{&$>pKiMuFkegTRl)5taLLr$n*j}-9XGO8+>fR6F1_YDc^Mnt zymaf*{Z#Z-VaZ`raoTZ{B(%N@8$k6dJP)!@6k|E{)x4{i#j%+ArY*v^axt?Q#~Z^+ z8Pq>;>*tXbbI`Dil$}N3A@pR^vy)PxFHxfC4~{e6w?dJSw|Ob2wnF*jz@dhyNvQ5O zYt+8B2x_a&XRVp~}rOv8wXn;(MwKFyCVt>Ab!0_xVO#vGCB` zho!GC;OnTp!%NWZ0U6cQ2kthzr27UmXokWFJlw1*aD4% z!zT(bQ%}RW8AeK||KnTT;|vpMSoEu5%sfE58bZE)!S10!n>M*`@>w759uP#kWB7HE zgz4);{Wkdiu|e?HhAp0(|Eixl&ac&fl}{Zf*e`sY?_WF2`gNS?4S(&zw=vMi=dWu1 zsdax9@`eZfUB~xp)n8>iegVM|o5FnDX}3OMn!jG$uiGdda&v$M_$rq(h#r7^8!E%g zmxV(41y&KlXP09>m8uN_JLX}*n?AvVt4pDbf!pGYz3y0G{#PSD>mkf%oij@--wevD zGF7#89Kn42yK2*aDnr5S;hnel3_%(F;F#V|G|3jNKesIWv!VTGL+8)NqCXpp|7_^~YH(6#pfPm{^w!il&|6a{ zL2pf+1&=p%A31d~e;tW-Eoc0`vFrP_>c4-X98SaFa}At`(^2R`QQ&6qC9}FE0p3RE zzdvfJpL>Vw2|lmU-Td^168c&9?xCH^IAqWcdDk(A7mb6krH3Sv!3DM`rwV!eNBsgn zk<3H1`sYy>c$#SS8?`%M>C@^1%q8XW%I5E@FFL+7r_99h`R=^pm@?VQ=d#C`9m`h8 z9sWF6$X#Z_l4|Wz6#~Ur>NH7*oZjG@4B*Nd;}e%X=A5Ptw9&IKW}Hhq6t_p>dtFG)aD1;0rp6%9Plt<%-Yph)u1Hgs-SF0}Xs7K4!T^`)&tVXLhaP17Wq}AU| zkh$@cR{tcFqb8nK|7u+oyCGQBdVJ+)>2v61t+stN_Z?(We(>5n(fR1`qb-McQnn+8 z=!w0fVpXWk`lBE7!=>n~e{1}KuajUu|9Hvz8>65xr7OmuIu?ywRDJZOxC4xwNjt9e z#samUiuCzV5lS1rGuQ{lUlu!P~KyTu}Q3 z8!v{$E41qr`maQ2^?kXCZ1-vPt(z@G^C06Hwz?tHC|dpA(-UDUf$3z} zP4VG6@G!2WqA=VUDcu{Z{gfaEGB%fP9eT=u=DR%L(s`qf`VzKfF4?&q<*zh)Zq1yA zVu!D8+sUZ}z6%5>4;^}hnU@Wjm-h8TW;khc`qYgRY7@4o@!YJ|?X zZqxza1wECQo|MDP=1Jm}Tit2(Cz6K(a#7#Q1^kO#e$uYfXnm8DHu`RTEUx_*I*l6|oTi=hx1GkfWNft`#;B$9-TJmxSu+D~EYecjj+*@H^ z9elF^&5v7|zp}O&_4&T8bszhJuCwXyH)#w&=NI=Y;zmv|Z01&2Z<&o5tGW&sRz8A^ zB@J`mX&a!980H2>epOHyx%a|Hybhdc+jDawLKO@zVS6Yp%ZM4PZ=YZ5@DMWIIeUCE z;R5Q2*vfCEtPOgAXnXeE^KMO8>Srn1pT?lv|&6)d6KMx(7XIA2{-vbFp zT3=jdDFs@0i|0MKbOc>i-dAF0d=qW<*tF~DI&aWB<}&_loc6(?VSP(sDqbRJo~+YT)5e*IuF`3$@XXR_gYsDL#4E;PMJnuFQ{*;_ngPoXS% zjr!_cW~gdt`0(mgqL7nIpw(agD*D#)%~OhR0(^U^sq_BnS9AyM*wTJ{CO8GHbk@(1 z0#%)#(~jrAgq)le8)7r;Y4v&yqMK8|x4NzD#~$23cdn;ZJ+TZ2y+J3Atn>>39BGq! zv+#XT-6P)aTzt~#+lTnU(Y5D6;^MQnlCQHOv0EY8b+7nAOX;eI3O6yzeHDHyxNj!P z@MXLA-g68LG)#5)nDOh$T$U%dAoJ}_9EIGiXwqvzv$4Ml$omDw-QYiF9Kp?Qm5V=%Ttf>fl1HL>Gwks0v zLkpbcOpYa-MVBVn6dTvL1H|^4`P8C*^g`{+GmULSkXI%p+0P;qbS2bWZ#H&9T^l23 z1{=Hp-yiIgRAUT4Wi4xa87o=Ai<~(_oteJ0`p(r-rOKcy?dH9(?XyrfYWb4q;+>Z~od=3Box{W9Kh4b%2=9#wKz0DAfufVR~i!?!w z=Tda|T_HHeXtF=2!sn0r=7W2OPtxi&&&4jK_4_McMAj8%A@7WJ7g`VSVZPagEjeWo zU{&-S5#Qv`ps&4j(TB-bNO<)QpSZ)bz~{7bwwlQTbR`*Vh^|fpj|^QMI~!`S_?JgJ zlAa8KA0?d?HvGEiN1nt^!xIs3#@Pz}I`KyffS0sYeO? zz{!qot9#Iog5o+mlWI8Qe4V$(w-ROsfVQ4_vHHSKQSMH*%=nhQAk6oDwkj(hcwJJ)JXzm?8PY>f zrAa=5Oluc>dSMZPMv~if4_~SUxdRG5g^QM;aI`ok;WQ6;U7XUG|8Y01oYg+y8;2#z9kpGG8bU~Gi~@g_6gNezIn z*KAJOjGsYrpE$xg;1yIm|Mf}*xs7G~t-4@5IMF*2eRPt z70y-Fn4#b+>zlSE=op^cKJ;`1?p)UowO)vJx5dm=>D()I~37`(Vxk#iV*kv{A+ zJaax|e(F?aoG<`-oKhN?4_<^E4r3d)+!Df4pCsI1h$obKF@CM~)B`MDlqS@D`#ENQ z&myXOxES>?t=RkRLl)$)ws~kVavV#wyGgZ8ctNRJeckVaepvkS3>%j5$Dn5+58DnN zA2i?6DV=NUeDp>s&babj1rS@8%mr87123F?KE~-5AU=t^+c%rWf>z01rMkotP|>>O zDoH6_M0bB7M=%@So$%i96sG>!)l26VC zVOc{fu8)=IP$S2dLz}E=^{#iTj@8lXZ}7UQC!n7m#d1bhP9oRiKT3R>Zh*Fe4;Ab; z>d|_~pFh^ent*Qwrx=D0IU?qca^`^fuBeZdbH=RQERZ?9;Jf6gK4fI52>Twh8_xD@ z{J>Am+n8f9efovvUP0ZKyqz3(Vq6X;Z^C@ybOhpMqRr$ zoX~$X1nLS6oKV#s#QWq_H&4+3XrBJu0;umZ`tr4vpKtWLtC-E`lZRS}F=U_q1c2Jt zPkoX18(D(a%U7r0m$RF$4-NiZzoGIrEw3M$*?AHRJ~6pgs;7B0W=6Absb zA3P$y3Ch^@3_HXg0==Fq%1+8PpxJr{xq8_Q(L;gDhqeZ$Aik32-fmwRK!dl}{WT{p zA_2u8yU)(x10OY2dS{<82UX$$rI*|D>DQ@Gk2hv32kZ3fUZ42;byL@=O1uES+h1sK320+$RS%E8`TVht&(6Yln4GS6X z%NE|R5Bd|&Eh%Ke;En&g1JVh3wEB|hZslE&_2i_W@#Z{Qy@BD@34biKtX}`(@CwlT z@$A!6V(Lam7e_CNlzW11mfouAQn`y}&Wv_@T7$rw_g)qq^9PWSW$=*hu?SlG%AA4l z4WKOMQ#gEI2kuoh&Z!)Uq5qs`K3Z}}=>dYQo)=QRnq1Jp>l^+;sn)10{;c-Iejar1 z5u?kFkIH}4zf@hLDoLwHjPAnjC>pzFxa%8&! z`fFYv4LB=})ccmOF{#y~p(8$e<==HtZ?@oV;bZNXA)vDCy2@wFu*5@edlVB?32|Hf z`5eG1%Qk(SaFxN@FCWBO=PH5TGgkV?KDI-K^;NI-Ffd~VlhKf6zR6G}xa;27?p~~7 zHWs7QcMfYexxm+R2a9F6UZCMimOvo$B=~83 za1z*s+8hHX!G^AEn+Xx1?l#of-Qxh@A{&9`*Y`EwqjR-fJKdvt%$7_ zHJ(A8Pn$34nCzjwpTLT}eExuSP-od0Bn*=8>BOat<{J&&RzCSr`2%Q)dN-TzkQ-vZ z$!IVT8V(*^HhXQ(KO2;sU%s%UQx>d$yJ)Kj+W`1>yuwtfQw~iYOp=TBIs+Lq)~*zN zGlCh{2zzuMOG70W)GoA~HAWkP-?avQ9;ekmQtL^)MXR^0u4!nb)r0(#U*BWKwbw42 zer^SN`-)Wki!P%dI*Dp^D#wu)hob4N`_I6;?nP;9-j)EF+mlQ!%T9n@5x#5G9zF+& zSqc)0y^qk{j3myYwi3($q&0u?h@$tF_iv?kF9h$6Mt>+<*@O1ymAfBaK7{rt*(Te2l!0SEc%`go#T)hco+)t{xeZ$Pcm;o# z7KjK}7HHa70s79L;}$)djV6lMTBPPCK}Lmd+m6q?gBh+Is}rZ)XBQthyL2JCk0Q`Nbrq$o7){7pe)yphNl|4wSf62zt-Gmvg>Av*Iyn#esOm2vLBmurv7lpq}RRSEh z(yYJtMS*(wF~TR@4G9}H^YGuz0WD8N`-ZP*pj!#^B7+o{gHny6j=7;_sNzETaQNAW zVDMs_IR8U$GR{yjxk@pm>{_8I5 zQ9D|_RXcO19<5$*{a|1$=!0|gE%wOLP}zhl@4ZtW}CpA^Onl7!l?VX7vgbQuT&xeE0YgZLJ z1!bdK)o0c*4?u8kRo92YhUKXJMAqpq+j+rw@y4D_wIXQz`lt=hU^EzbaH0j+z6G~F zytsXV+ZCN#dvbO6s4r^IS~&OX#ZR>QQ;w}HPH4PHRW`?DEv>%ifr8#v(A&pl6j>7o z*jkKtiic}~Ykd{{!IO4I--HVCHaWj|Nodrfd*f|0X<9u@Kk|44O;}|+Ua(pS^lxYGTy(q`HMd;sUBp_9 zWP(%EWi4NU>uYV+57i5Lr~55v<4_QeHnBpNJK2-ZDDk4a;MAW-q?*xiqobc= z<^nK`&dhF-6GFq~#km5S9JKyeF0I&L2e`cJ+wOe+a*!8Q=5-`W1`RiyP7^GP2gBuI zIoshIT@oM3J)(64teYX5%W;aCmr zbMNWv*JPYSkiY@aF#QG0pz#)`cWRF%xUsaxYbXUk7wE9Pv zq}<$SKL`8+)lCYJ%}Zw%elObZ;b?Ez7QP2at30E=x92oS%a%6Iys`$(k<7{!{b&td zy?@xcS9=&8YDQ)}Wqs)8(zDBchH#*f#Zi}w;aAXcr#0J5cP{EE4`8_R>=bC;ZhCRG z`XI=h@oN9u$yji6gIoP~3kEczd;ICAx4fXEVo1;7!W-048E?MArVTVFeEA+Pw+sB= zj3a`w%+(|IjUKeTO6o-EH zD{TK%zuw@x&Qj&xo|k2I8SFT&Vv(W7()0seLFHxUfoXE8*%@W*Ibz(cYd75K6;NXR z*7brM_rER6%v~$hDov~nZMSX|q}{Rox4OUAm)V^IT`|Q)^neN#{GbOasGtG~0FZ%o z`hYbx5KIPG$-pH&=t2cZ=)nvs@IZnDWPqLwe3JoXGEhqfKuKVR1W`!9g9Il?Ab||@ z(+AMWz%&`~B?GBc@P-6hNKk|XFi5b09vC14@nnFT3>=dISt`Iof-xj;LV_G5AVGo$ z^Z|V`P)-J*$-piZ1R?<&5?rANLP*ep3NX-v0c60P8ptLC#PmQB3F=S*7<#b8ar@L; zg9IVy0Rw8_o(zbSfo6Izi3C&sM0y89tLINJs=VwO(31pz344{+16$vttfDk=+ zLjo=Ipa>PfAi)MIFhB<4NpOn?AcP89&;txqFn|QfNI;7OpGcsH1a;^E7!oX@0vjX`LOkVb-DBtS(E zCQ*SO5~QIARH)zw2~?1v0tvQ}z!(W)k$@9DI79_<=s_0}D4_>4rUMToAV-2{B+x~I zQuF{473_f|FhhbURKSBCoS=esB)~?3VI*)x4>C~!A$stJ3bfFJA|!x81@=e~js(m| zaEl&@qJl>B01p+6p$AT=AO{Klkw6^@s*wN~Jy=BrmgqqsDqur`EA&7J6(A(RJbK`b z3X+k47Crbx4-`!Yb?5;Y5-cG>L@MA%f^#I0MuJ`>Kt+N{^uP}Z(og{vdQg-EM*m}} z!ZN*Gg^j8krIwQ*TVe5*AwRC^<$9s%rT?YrlCQ=v;SPy%^^RZ@7R(@(@TTxf3-9Jvwi2U?PTj6kLgDS)DkM6kk)0F;HNFk zTC2ihNgY`lP|u46-lgx)+zQZ>!%?OzcNat12X8w+-gF~%v^VbhE6S-ivHn$3INB|_A3=pGl}X9ojt zXiUSQz}`}WyW|Md%RBkh^OklO;42;4`u> z2*xs<67sCW>!823%+{Gjhw%xDHYCDxR__U1*x)Pq);R@6DeOvqcWe5tfmTXh7dc<( zHZq{*q-B5?<{X`IV_+_fQaa(cSzixl)VIywzveE^cpdC_#P|?gV)H3J%!vuF%2glR z8uJ0JSl$kN}5S5~qydA=)vZn6>itT%)40lO83=Q@wz1Ge)uKh#8#*GK>Nr|xW_T-lC- zyu?tbQu<=>xzHF~Xy-iAESyE^$&%~`<#N{^zi}WKtDLJ+JL?t!7eZ&X8J6kT+T!*8 z{IVWwt<-)X`@9TPcN(Qx17TWBl4efbj;1(_UMME*z?h%gy?sP|e9^v*ul#D5?LFB_Hah}Nk9r!U@f`V_efJUbV5mFclCw8x3>>Z_Bm ziCiG@Y~`1DW8}Sd>Wg zk7sbz{REj9+Bn(#6IGjJ{gq*myf%Z=ibTB3lFPm4&;i=-9l!YQD=Y-BoL@D+J(ma_ zZ#iYFI=sR2PnCAIA4-BjLat*wXC~m?2PV_Y&wAqB@x$HW=ku_M(%MyLt3IOP2(BOd z*j&KXq9d2{xTWBl{>m>IJ;G2+E@tNT)BzYV@8gJI;o|pagqc`^T%XS`ruE=O9OD(tTiN zK({7baUNLQ3V8=TE$^*mZoY??EgUc`R8)mQ$)hN|NCF?cA)@!%#+J4$4ZTvl4%-yp znh?LJh^>|!8742#g6mAE;MCs*{#mo;HX<2B{pW9WoXGNbLELmbeKlQdO;Dv^$hK0&exUQP%ZtULtGug%^RBb1 zR(VNP$=XxR524`x75<;TD1f;kv5h5_GC;WS=2+w2LM*u7wnK1JArd;<)N9K#j2Pw~ zf>N`*(YM2ImKeWxN1_uymd6H;1F=}6cRBl{z_-I_)`*QZ;JLF?#k+C?;$k+`>wRz> z37G3FXQln#oNxAkt6ickoUba}C(Cmch$joqbErv2LS65l9W?R4^HqgvIxA)(Ap!l? z?iF!Hmn_bAUj@dKMq6IaD#NPQJ)1u0 zCm;_)huMO2nUHm{n!dlbHB{J~W#yLEjl6AK=Yol!z#{e10oxV{g}s}*1V(pUoO_gN>282h52yK$%dUmiyO{^KfNHC?cN zpX?0Jmx;hnG(TzO@u$GIYjoQJ5k9D>XK1hW))54_Irnj+r)YzU@)H?gAb`x=GV z7_|PT=atZ0aj;&j`$qUm3_Ru~mVRS60@g;@Mja^7!%nlVZCvi!1X4c6DrXlz0tfcE zpK#$@51nT5jr)ky00!FHy=>0si`?TdT2u0yE$c}X^s&ijpZ;c0z?1qVAp03QS705;yG#RSXYb0 zbXq#y4lYNkFcxb_ zH5f|teuW{8e!UNlZG$1NeOnY9)?pLfO${zg3D{(X<5ipahiN}Yvl0wM)bPr?InAwY zmDn^s+&p3I6*etkLjt25I3k_RV@8ZBj@Vze{P{{*92+`6u;=j++A>eHwQ31m)3Wod z+%8YJrmcoC$uAaqI_?=dZR`j=o$q+`o4Y`dz%pnW%?&*Q5)a$YSmU&eOFvEw3#YHW9bm$Ssy8vB|TKffuWh<%s0D!rP!1#df+qmpQh@wTI_wpmdX z*dbxwDBJgB><}Lp$S5I>Jop_dhk8em$L!Owsge@FXZa%@j-hJccHZJuE0q$?L}{zh0E4!2i^<`4!k5!_aIJy#Vaq zx~NCC=L*{M{x<9Py&Y&z^I4U{QtrS@I7xO(*>U8ptoHSyz*=B0_3g;5Y&)dy;hl1D z&JU!(R6bmPsun4nVR@qKeH@s{=Z(uds!!*9(kiK(kK}aDXM;JF^Rb`G`BeKvQ#qd< zf8~72sGQHk|C00J{43|f64iL#!~(QT?&$n(D=$$EV%wQw3xp0!BiV_U8>RZ zlo6$`UpP6#?9;$TvYozO=b-!R@*p0_rI@@jY_1f2y&rWvY6*sHf+8Ze*I?b?EdzidYnqDCF1mMl>Eg@Kk`9TUBN;rpJ!l2>1$ zxTA=cq9cG|FF5YiR*vD+&+<>>vOnR}*P**_q%OgHmB)lF?zv-Gb<+=aDxc{41F_1Y zn|zgchM2vBh36;?8C~r$Ah-$(9~l&}3@?DP*K?TkQjO^KM$F@4I?MPWb6e4OrTy73 zq^IA_P+%QSIedRZ^X&^bWrw@pV2=@AuxN#fWbGczy3YJ`pY(C)4QzY&NL|M|H^$#; z*&e|nA^~g?Cs)#stI9qp9GaXCX%VHgtBVw%xAv`54qz+RS(bI7<&-L%^_7o(!J^aj z`dyc2FB6|rgLj?LgnX~{v8?nqJnM=*>g77kq+Ij_x^3Fx@y0a=&;4K%cl=Nip1pLI z(PV`geSc{_iAI^utDr}OTP=TJA$0S|I|%A>@VxKo-VZDy;OvCkJPS8i((AVkj8&yG z+Td*+m%}bK@Y9aF&$zIEBWhnZt6ieIAKD%>s{Q%e8CB_MjhsKsjrry01dhhW)A#3l ze|3*y)^+eHsinJjb~v;>z{WI#_a)|CaN48oUM}P}9!}tin@g_`EBhM1bLDXyR`g0w z#qBeees|bUWJ@6G!zR*BhmuJhnAG26_Q|>iv%h7jyy@UY)??nl)@7GE-9g_P!&91H zMd<6Tkr}?_blo&!irE{s*FxsYJ$IYE zJmH3-IfF~Di$klKqDIR6&+(l3y9&PR&Uj{5YXGhrN2+cP#N%zMr$1dZ2X*?#Kc}MWdYaHixt1{tP+M|hs6$a47WE-2t5nE{X zWb@oJ+ib8sR!6K%EI?tOJp@p6)%Rxh1yzaG#GpG#&6MG|sylk|gr)tWzPw#Z0 zN8*C(&2_0z#Jq{={lOe)p_+efsO$|+h%aDx`mhQoY#G?JP{|Fi<@VZpJ!U@ova8n= zpXP>+sZX!udU!*Zw~vLm@-(neN&Olr|6ph_N5j51YCZP4DQY=%H5qhx8Rop5SPdQb z=!a`>9)g~8MozH55`#ibpBT2-)B0fn)n{J^=HV^60dJ+o-SHMRJ^uKBc)T|5(7S9d z71a5fTexmn8|}VaM&i(}D(H5!J>gxxH|9n)6Zb86p@lG;S_1P6yl%Brj%`gH=v-^R ze*KOawECAXK5j0CUhCWZ*iMx|?vEcVe7TlG3r?X2N6$>)kb`^WUhWykA*m|nH(c*v zJJ)diSe8|2Anpk0Uwaf<@G)_|S#}m$ixw={qVg28wWmMVOC5(6TyxrzM!WIq_))bR za<$;QfpwJH2~B7*OVD?Biy3rU7{5c)PzkctZszPtl!O*6=azPqIN^YoaU!0HM{vL^ z1IfFwhw-|C6Z;k>uSfAmwq1I;;VCL_{UG9|#|hUJ9G#3X&IMa;=@zvf(FNt3FPopT zu7y5UbD7fP?x738oe}CQOo5fb{PEi@UD(G;T3)-w3}m08h z2KU)q1HnaXD{sijo30;2xsQCqTei;xCVV?g z_4v$Du;S|3GMXVMSjt%6{rWQOA172Fzo8kV_ZmM0!n082w=C}N`v%ZIPVB5LeEcpxvI6`T%vd+>&M8K$VLK@j;OUp$*J z5d^%FWO%YJ78r`ux_LJb0)zDi1z9Q2u;+Xsm-p?o%pHHFc2uteD)~@)Vm0?JNLwGB zV=skvrrb9uXlVu|&3O$H#=>ybx4Q}kXB)ULL%UjHB zgtYa&C?W&-9eZ)r`_o)-Vf8hU`k*GLo?rvyGpdmA+~K>nF^Nb>ZuJj~n9YR@*;=i4?kp7o50=;3k=z3sA7S1?_!gHKBTkdZgQ)OI%3YACweH4 z6$+&LhU*pI1PkAIR0>@F0a)w9UHh|g0BhjN&4ayVMw2G2Ef>{0u~dpuzVl;FV14h3 z$hV?xD5|~qm8S9%D3vmgr;C3at%^&A+Pexslu320S<(U8A4(dVH*&@xkj|_#_h2

6Ce{qsP~yfm{u@(~bAsQ%!-Zw$EH3%)IU zw2Sus{d7!1#Sl4Iu%Fz%&j|=WnN=w2%2hsoU3_F!;{n7m*XoPvT@RqLj%Pfm=m_xe zmNCAQ_X&LSe12RDrUJJXpT|8~YM^_@2EVzzp+HwjSfNMV91S)^wTWq@gS*j7E6P&( z!L1|pl69}cAls54janCD%zu_?-R;3V$bZhLpeCUcjp>gbT6K_?oaSQ4ZC0;Bx7YJ| zpHoPNY)cgj7tZ3u{O9`o{Wc^*{tGG}GcNU`F{3l3Pm4rRN43&zk0q$g#UWNe?8&9p738!_^&7Y*AxEh3IFwk z|Ht%%Gp8nXnVNZJO7Q+=(8&?){C{>T6uQ(!B&uFYS|XAVk#dLxL!^_wU*CH)iGvcp z=z`z27B4!a0iik%<^dVvm z5n0IoL?R>77LlZgltd&TBHa+lg)Ws)f*BFIh(JYzB_aqBA%_Ssbm4@^XGHcQaut!8 zh&)7O9U{jN8HEzl=pq;quZZYG#3CZ{5OIbQRp`f*299hyX=|BO>@vLJg7Yh|EUhF(PXb zIf}?gME?2X`cH{>e_a15v5bgZM4Td`5)p%F*Pjw`rlmZZFgzu}5$TLbUPP)Q5)+Yz z=#ma4>=8kZ2x&wBBf=FCoQP0F1Rf&u5qXZtYIHe_$XJy8M3;>yxrZb(>0%ub*(h<0 zE@}}miV~5C_(M;066ubT+~`snC2`TEDN0fzQV>ak5+RQ+z!Bk$61<2|MFb`y4AB#$ zMAjp693`U>`HRR_L~bH75lNmBk&lRTL{uYU7!k3E_(Vh_l31lnenhIHBsLGQdNt=WwWb>~>Qjeqlcsw;vAGJRE z*ZLV#^;0F&52q@oA5InU(C6s+HFwXiUAX_8oafgH-ruwAkQz?<^g6!^_&ozRZt`*W z5Aq8PpPF;$*GdjDvCgl?)FGy32%4H#=hv#KC#FyK^J@*?@8_Xcas8gN=U0iqpU*@u z;-pX5^Q&h10;!K?*nYoBsC-D2c ze_bDHEjRrVQ7eT0Joi5eXOau`=iz=|D{Af3+0ZW+wQ_16r9b9BqE_?#zG&1M;Xj{y z>bg-IxapUUS|KuhKEx5?icCv|MX`7kar^J%L08AUw2Y4)+GoeZ1DZuvtJVJ z``+*(=jun4=Kk%f#XL2T_C}U%@A5q$rC;fSyxa9(|FXZnfNkna-xnU&k(ukWlXeA+ zV1C1BLqy#p#C$l#bdg^M;ux&0wUyQb%2(jE_ESa(bg|7FN|QHen^yNgv*+`rbCk_N ziPPRk*UE>{CmpuU!7p1t^L?q4oVwkhhQV*a4zCPU^SZ1P-Q9?q660JO52%zGPiuW( zxtsW7$w#};EIv`qRhiXDlK;$-qPYjluUqIljyi8Q`pzpnQ5(J;am3zP`23hVnx{44 zHm}^(P}{S2PgiU0i!rgY)|pZp9)6+Klu`I4AGfqP4Iwf<3*`dasB zn^7KEncp?OT=fHT5A#qd-W>)~9*%9ado6=<+~&4~)@%j&$`^TD?p=f~<&RQFMzZl5 zKJ{!7sWxaET%U5Z(*=y)w-1(keFLi*^tIny7mpPgjtqVjev4l1c(QseGZS3=erbcu z@M3gn$6%05|0A?B|MsB#h8Ms_?CXVl&gEcBxsrQS3^$4jI{UD7jU8C_AbytK<83I+ zGT6QXz5ppa!lR|lOF$c2$4&bRek`=k`pb_RgdT)Dq{o)O#LNTrsoHXH(O6|o{pN$~ zP_MLzM5(+OYI5JbO84whkUM;6&++mrC}{oQu|(c}usW}LSxJ5>irCRR`&_~~v?O58 z>=&PxAztmA`KPQxfu_52inEC}f@jsjpRA7peoL1KS{%5Cg%V@VAJf)?s`ng1t?!va z`PG+Zo;`I6a<00;D7(BC)C>ll?HlUGGXmS}5?w|x-`&p4>z|4+zd!fb&jJnb@vDBt z#`(uUk8F_r>hgTdoEVh~xnZQS=2YHeUjyUSP)wbr~;XBJ9_rgIjYV(Qom ziP-gV7nz)D|U&{!o(h|<+b2> zP@y$870xPm6v)7GdJ|309hRXNPxQPq-(^Cn(PJ%Ky(gi(B4m8kdJ;!Fp0!)Vukm7wPiS@dGi@1FJh2T+

V;a|3MelE zw0aL%L8)gpF%I1Z;CZnpx1s3=sLg9xr676-svJ?MNQjUG?ZU3Hr&&kP57$e1LgKbq z&{u2D*8nRl`oUSp?}0X!X!q_O75nweSnB@%-)8{Yr;UG~0sde33^02gZ7$cKb+p_6 zpg?!pB<|~`r#)5wb^kqs_8$*8NzJ)_i<)!&-qc*{k>K&v9P8nrCcxoo=F8okaUEKBZM2BR-?!>I>|>-d4#Ydv>YMd2*pN-G(z|hT91%- zgrcJpafEK8NHs$K(J4Mc z#v^1Mq2vhhMhHSe0}`^2PhIX zZ?E4?jbGnwznfE|aKD>c|G9N)Lf_w8r>6A%-JF`#_jhw@THoKz#s7II-Cxa_^s}0t z-1m?6)Or2Uo;tBV+EZsX^LMX7A3mf{mi#|Ed`Q46Iz&Z)C;~T8pb~+O2tY(&AOd9( zz>2_91biY869JM4T=X|6L_i?=l7gZL;6z|0`u4wJE&^r|$cg|{6#PU$COVWv03!VJpWr8Q-BzOy$HC4DF_QwKozFoC;~cR3R%NfQ!Ib1g!cCk|N+4fyn+o&;QoO1Y{#n8Uf4*EJnaD0&x)_i@;U% z{V8CLz-I&`BTyItya=pCfmgJCfrIK7rur(w!kZFylyIPQrjuf1 z3GYhSRl=bXrj+oZbk>uwvlItQXIcrLN?23EjS>cwVrmH=OITOJtr7;6@T7D$lwxfO zH%k~;!m|=Km2jqXW|T0v6i-WMV+rRm9VUIE|p?T3A0Q1 zTf)-Pxmd!uQoJf*PYKIQxLm^65?+?DuY_YIOe(FH_sda)KLSUdzBy?BA z5&{X*fjIfi5U^fB}5)hC;eFV@WupI&C=nxzQ6%s&@4*L;sk3e_?sH5OG z0vi%=kU)S0=p%3*0qqDhM<7H36cRX)fPMtpBLE&9rXz471sW1)kN|)L<|AMpf$Zqe zA_X84n2>;h1o9)m9)a)ZFe3pIDaeojg9QE~ARisdqaa5DEYjga0umA^kN|!ZtVf3* z3CKvGL;@HRSdf5!6vRh|A_?F~U_}BR5{QrhfduZOU`YZ#5{Quii3BbrpdcOkBM>D4 zA_?3`Kt%!_5`d7vfCR22pd^7F3BX8TL;@C4kl_CrJ;?8Skg2g5vq|8ii9>KX~>Bs3u*1L>3>MNJX{lF*EVOeB;cAqENkM`%hyMiR=A5Q~I9 zBqSl73M7;zMNAUk;+hlJv!h)hCP5>k>-kAz^P(})z^Nk~mXT@r$l(2#^| zq*IC%^+^a$LSquLl2DR_cqH`V|F%8IAHP?b`o!}qmdym-PW{$38oY11`(AM1IB2qe z8L1eo2AXdy8-LLL2DFNl?($v32il_5xM$RD0-xTU&B(E^CUI^8&J$>!4$Ko+o`CWM zlBWQ90>}S`>IqO!V0r@56NsJ;&{OdIG&oOt4df%<|MEwn+B^ikgSH-l?#|THGZ?*j|Hfy0wJDhS?W#h;33b4C z`2T9}%fqqy+P2M82&KpnnF=XH#@0f~92rAJR8%Bm86rb6ltdCri4e)yU}!BOLo%e0 z3}v{@8B$32?r`@Tp5OZ%-|>F$a~$7$9PK}>d+#;ub)Vb5*S@an+}D}Po*Q2a_-<+F ztc^+n^pT4S>+s9xUx&7SND+F3_=HntxiwCa`lG-!-?2wX0tIWUW*?>u21i7%db>{& zz=Oe^Zc!t-pmLOpVD{`bXrS+Cd$A`9rS(kl``&m!>i@jG+UINRb0b7v9Ym$E2%qN^ z7n+cV&V$u8JR2tzGj~mNUikL?P%@(Q>8){6)d#GBRT2TlX(*K_d`VQlM5!0TC7KIP zqSR71Y2zFvlwzqnRMfEp#cfhAG>)(W7v++kgym6#oa>o%@4qJlTrZIifB|AKS(}pY z=z$oXms(IocOj;%BlbUDw;{HZ0d7UCGl<AZ!tcZJ|)1p#S0`Z8v zc;e6K00v_#yZzx)Fz`Kc?oQ%C(64>yS#Zr5=-ahXqtfLV=n3Y^ta@+*bQc*_i#*1l z$Btcmul7gKJG#k7k^MDFo~r3?-dK!M{OSpG52a8l*Qrq!9UqjgQ7L|=-xXzuT`n|G zd5qHExju0kXGE#esh2MaHlg%Dn%E27p(Ol(&JO1%PLB$J!N4VtX(MMOZvCFNQI!&T zSe**GX=96`?Py+fSkIxG>0MRlKDz=JyN>%3)GVO?puETH0#VR^T-H?u1cE`q5D~SU zEHK>p?Zo|BOE5NPK3_L4`->?3<)_lw)rYOgjBpGWga6%T`ya?xVO z{fZ66k(g}0cFWfE0ZiUQva)Bt#AH#=T3(hqm@L zXu6?!;IijBH&N;}rcuwF+yO24>PIzErlZAEd^v_Ol4!AGgK}O37g{{B^^?j8aUx+G zTTJCkq1mur`IrZ9Knl%S(=uTUQX;Y{G6I@G>KfE z5B92#nHzyr>pdu@Jr|^Z5jmQ>b43u5_(F!ZO~$uCvu$XfJ==uhyY)bPVas(`90lC% z97WBBK7;7fkvXrZXh9sgYD8+;QRIr`y#4PGJ;?{R+OLnjPQ+iyV#ryGi2r!{MVgmj zxJwK%))A$3=MJgoNO}A#{?Ec&v%7+c_}8CJVg5+Oztmr#;58Bd9uG~5A5X(i(C)e3@l5b>9~=d(u`QXDK#iX}=~&jSYyUZG4P{_kum=#+{0 zhu&FmF(l%z=+!ZIfrvk|*+Z*VBL3TmNth*w_&2yW<=!IVAMEtCY*WeR%gy=mds2Z> zPrPA2|2?3#=<=9rrU_WyX1Sy(x*f@~`lxF)kE4?TULmW5ijZxzO-j#ImSqWxFsl+( zlltJyXWr=T8=3u;OvRwux4SIY)eQ8H5F*30jUl~=Y>jTaA6#3@#^(4@8MAQYcBhuO ztw>*NEDl2AZXxJ5?9!ka=0z!7`UN zVC2cO-Y%?vSu*1&O^J?BO#ioBCKOY1?mBb0ABgrS@|u24243jwuXK9c0@_?D_OVop zfWaDegM6-WFit4i*}3>`MQUTTM3w4_+TcDaMCQ2=`h7zM+H796O15n~+U#qXZTRLB zk{VC>*l>vlZ8Z~8jq^`J><0pl`o^qVlIW-kpDkgT+}*GGEDiPQb=gx^??L1K=VNyV z`k`^V_iql*4I+XgUAMJQB6_euv!(UmVbCA>oThOxXGPk>QCVx)B{S;CX_R!L=fc&` zizwT0SG^u(B+8>vj8JWLK(~Y?n=6CV0itEf(t~j z&KDjlAf^bP$vPj%Ac~UZCb!^L22?RU6LY|b6E$obtdl%H4QiAvOomz-LGOWi;nu!b zW!3GO60bd1f!6S0Z>35fFvaE|HhsMY%&1%DHf!C746E3BP6%hg)dJyR_L{N8_*+fD zrP}Eg36dJp?;n~?lc;HXHh?MjPHPm6Ph#?l;h5a=8Z^;8Va>;~0EYb=^FFDVg0F=` zW&2p=Nzx^x{$TcQWV~pbCZvRnhUw+?ki4*EW4nwJn0PBC+wuA{8b0aH=%mzuzGiX< zDkr$11@WDskKKPs`yoQ2`_ayP6Exn$HC|+1j|RLcTgX`@P%#QPM~G(xQ&pFFw~;$Q z+N3g#>Q`fs&9{&vPK)i=`R{JKwo`qc9AryXwj7Qq0J-j=DP7nGBtl);W3+szr2Ehq zc{w%6Hji@)rHUX)tdwX=gayxCe1pPTe~7jc%z zHJ2bcWMC*e?i0PAi2u+5z9KQqHFST!>8R+6qzfX=AI)auR5`3UfhjdEag}==#^jYx zlMfkJ6Y*DQ;q(Xx!;z0)xcIFDUvZd;<$+O>6bz|9m`z#p)aQXY5&wj+X@_)3UYr!a z=$`^6n!M=ZstVAsr|yDc^Q_50wGu5T)KIsO_b6|lwr6k?K8FY?`;L%Zd`Kko zY-QbP{sRrTd9mt>$)MuA$ckDmS1|QbCp&(q4bmoGl>T^F3$k5MrETZ?LOlO(63QQx z_unLx{{RW)pNZ)Ib2b3!9zy2btK$!xHU#@4>KGSnZz65cTlxk^_M-xktqWUO{5O8xaybeN_sheCt4L~3OXE^i#`p`vdB&wSmB!&T%#%SaE+ zd$mJgmRDcxCc{Ta<)|pAct9B~ik>*{>=TbU6X!g)cL zqkgde%W$W~x(2XWRG!Bm^&>JmXd@uv%ni1yaoogPwSev2fh*w`Fa2JFf3Lwm?}6WI z@c+&=7{#8v`5${ME`=EL5=zm5kKJHL8&H`;*I5oEyNIk-2Nx5h>_aZsTY|&@f1Sp^Q|-Z-Qj9 z+xD~mFHnBjO^*TUSagSfGu!^od!X!-%}fQ6knQF)kB3~|ph5CeHS<@~K$LCJ_OiK6 z;G2X(ms>?4q#ZfgS+<@AuA3Zuz2HCvdELa`vel=L_>vWZ2h(!Y;(Ys&w5v&} zA&p7utqeY*9H^hu~Ch3Dglh7Tf4 zQ)d;Wt;URRzle>yX@a3R*GML!T$GsHNgbW3G&Cr&E`Pxx8jG-51f&3ppl^`H4@TXkbo46PG5uUL=pG&1^oSs2>fZpjT&Pg2 zyBY`~d1ppt&||1*f4{#Wdj<+3Peo(5LeML$w(Iyc7VvTOM=eBo=3eLten9e=p!<>|eo%Xd9fxVcF)Xh#uozG>O~jwDI5+Nu*O&IC z=uGQiLWD(#FEJX$Mr>@35(rLlR3y zNF4GXR)TU(x|`Bf1EF&Aj@sQN8158cO^y>bgRHA6&U6$#Aj*_G`<*)xg%x@3&Q|vm zUl34jX3(EifResFd;5)JvD_=e&y`PVu`uBSO;{xZ7CEwgO?~+dkm8|{7kk2TZWaPV0!X}10BzP+W@~`MqQ@gue>?>AFu)b z6z=%-;Ll8YaR2W*|4IG-UMiI?A1QYFYYj>Fo^-TWpY&;^{hhz=|9uY|rEj0}^6n(* z(Uao2CTRu{py<94*yAG5ci4@ay_X%W^0d%i1h++`}j$9 z&cJLUS^Gz_Am0SkX41bu7|0AQr`IzlDbzy4x8ctnRkuQ+l7O7di_XiV5Fh+%W6r8k zmCC`j{kg5oA0I(Mw#a0=eorWV&vX9)Ee5!w#g6xbS@^I1;zbSL>etRG#V(Hk1*<*` zbv?F(2V-qaw4*ZMiQUhNa;WN{Gc%3!;AAR1D-sme{zL*=t}-;;$0*Bjbe9c9JO*^ZuQ4sC2zl_9i?N-$NuHI z{=%Pc&DZ=VFaCc0@EZG#loTo(pyZm$mvnd^RAXb=wLixRYCTIX@Yp;IEoZ-MGnH0? zhJ^hAw-f`RQ2L?xf~!uXaX_UNFkfHkfZ5g3I;d=2i9g)j!qhW1SbRcBPcps@??}B# zTkvHgQQw({!n!>Ni{Go*mSpLsWVJkBD4@h0$#F0h9`p!3%zb7%JRu|C#h4!hohdu} zQ$3>LS{n!cafM(lhwW6R{0>3;RH!Ix0{!DVgGaWmJnA_D|bHD-A zocSCI&N$q9tfgM=K8|kg-5hbS6kj#aQNA~H1M6wNkH{_=CH7bEsc`Xu{M1&aIA<6; zd$(M794o>Bx$pXaL|JUI@ zQq2-4g0%DhD~f9t% zZju@|NrjuFzP+rvO`Pk$r|B`ibqt{t}m0|nO z3ewI}&wuviELAPVbAQEU|C*6zt8##@Ce!UVe4IB{LsIcT>W1e+NTQapZuG#b+sC%dT^bmaSpgC!;3`_TH!;vozpGLi}D#+iOoFW2p+c z!pjlB^i~Gf?!i!C<;c-C%ykD?Umx|pNwx(XNXj>IaeTGnlM%#B_0N=Jwt1tkre{lM zow~rA?v7*NWId$Gh^R>=yoU7BYB%R?_kj7iV_yV>Bp?j~)ArBz zG_THz6={Kyg)06rI7KRx_Iq;m)VY3BVf0ZiYQ=c3Xool9f!e4;4kME|T*w&0> zWd!Oc=C+e0&rux(-8;T?ZZyarV>-jQ8I4mj(5?%nLQ^|_BytXOqgk0}_|b6!n!a&V z;rWz2`oSr(2lcX$;v%3g%Q!2T`YNP+ZCaw@{{>P;QYnyBb7nL~L=o_IfI*R54~yX6Q;njLQ#*=SB?!Vc+;=T4q`vKDe!w{}vf1wk>r z0=V8d7>cONOPdZkV6xp-3VvrPFfYM)tMBd@Qd|Txt?Di!3T$G&K5k2R#u~Hvhrce$ z&qA{Yh%&BpEs#3#mZM?478E~Yd7%Fufb!Ydx)(35CdEY{y4_D9U&H*PH;Gk{ zP51F)FNIeDu;qF`rJ*ov7)Jq__woDEP+h zP`HLEJE%D2W1eBkQ1uie_gx^jlSO*&c?p=jcyD(u1qNexbrs{f2ifN7*Wcak6_8yyKn@v`89T|PDnUpurC7wN|WZqa8;3`#Lq2JJqo`BzZko6MewYkp9`V06aV z=Q>`yw^=c5MhDBZWb({Y%ws;?fkWlS_ff$6H&oIus6gW>-`o!#PN;R$Djll6G0?c^ z*&^*c0b*vm7^gj}fNI5F%vC3VuARxSJtA9%G88#9d@t!j;bN_at5|yANk4KQ<+~bC z;$x_QrCJs|Li6kqg$XybXfN!@5`BpcSygu)UC_dsH-vAzaDE5PLr3U0$_0kd*_5fu3#3mJAU&YgMx60U0(X}P=62-4GigsNR{F?9&<_7>AZ zOkKQt|44rzWX+#)9zq0gnn}K!ejo}YWck?G+v%X>Cl9x#2wef8eV*!{*auM{OJvEO z@}s~xO=`!17y|O6Gu&(Td zHK8VJhy@Q%-xJR=$E&=bW@Nh-Kpwu3PXFDXv8+w-D9fn=%xU`hcu21oR1qilZj_;b zdoO5b%Y3+sH3;!7Zy2?(PJqS-A*B&aulZ=iKr;mYhk8}kNI1eZb@Jpd z=p?atKd*IUt}s-aX3abp7xRa1g9TrxpaWHowV7-cZf{FAzHnq;| z$%?s*rR1B}E3cx0=flhV94mHWcF(@#J?UZ4>hkWjd}}D6y>yD$;G-<;#8Z0VVG|ej zIPidlKcfa3GkSGNmC!?-V_8(e0ZG{T-Tp8p`*El%dHFz`h#9n|KH|<{Ne20&$okh& zZHBfUR6KdCyzs2sNBz0yui$~3=bxCQ1!5g@`djr?P0+dKOlmJ<8rJoVs=mFk9$SsE zNzz{6!~A!4evrp|u0{`)Ugt}=pWCCo!<}SSMo7H-9!A9Tssd#YqDI6 zn)({ZpRVW+&wPZou4=b3K1{*0?w?OqYBRzE$x`7pfzDXRFhntZ#tk~x(@0!Y?Zdj6 zv_|7MwqUEF6L%Bp1u*|(0Z;cIPS{qA=3U-ZHGKA>f1=%OV{C5fxtTYp3L3nu@X5%t z!(JaZ$~?;UgZ6e|HcrL*@QQZ(hoKiVIFv^3(e5)&*e+9$^4y6gBK|H3*KVr7fOT66 z2^t>6=e6JQ+~4us<94LvW&Z(R&R<@i`Gfra|86-UD^}z3>9OzNsCErA{d6U8y64!- zHTf7=+%V#|W|u~hqDQ_a+K+)?Z?aFSo?B5!$5ZO5&;ew{amVKhFE==9VLE~?76PZ3 zhkM-LC;*EKwO3b#P@zZ>*4Ngb-hp7Rouh)I4^hacB=H!&!^E5A-&;<9qOAVUnK&fs zDfs+o-|c<#cfn|qk`~V_2N>PKOcTI-6ny5~rEk(pq`q0}l-w3-0b^ZBuM;ChDtF-d={@6?tVwi*%uCwv6juj^XHW(UZnu@zP&8 zmshB#fS=`&#QqQdV0}I(ov>~Q*kBX33L3rGH5_z2L9u2Uu@q|CT7D)&jEtU^uNx65 z=Q4?U3SKJjBVV&x4!jawe7VEa9W#b?4r`IE+|ic^wB|jvyB9Qa=whAGEqQafCVl3u4>yH8_cu1+CR`nwF1q zLn}F#Nz_x&Czxg|PF4zfkJ74bv#td_yknwG#Q&a8E0oqQDe*CmyBfsvKjiu1dK|3e zTqaRZQF20ESSwj8h>N|3CBv?QvYvCd)5wp5>YG2eI8edmP?SN)1|{BouCSvCka8}Q zsHb;YtECtGSwW_^`MI2pbO3KOi&c+*`>Q``oEH_XJms_Azj7{zyV~1}p86McawX?7iF%639K~6_uF}91GfL~@&dFkGqr*DQX$qKT zSD)3kGb+pFv5T1UX5n?wDuia1b1svpr;tMK`y7*`Hl)JyI%XA>ke1`=Rei1i_|p+U z+xZNJJd?+Z?> zy`o3TxlE#-g5<9j0|yrqQ5@b#n0`Hr%DSb>S%mie!lQyK2e)6|k4i2i$t*-LBT~-g z73wLv3(_P%pFV>!0~wOfY}|&hptA0&uJT{~Nw~hKAvX``5+mhY2Jcs>r=XKX-yK{+31JWGof7%ZzIC-@~7lm zul<4lhe*x0@e8D!%gfZ$$Z}xacbWOe3pONBG(a}OD zRe5hgGjPV;0A(sa0d`HXb-O1YuTW2U@y2y;#j{iSG3~0N!1J^Tpf{(pjIN*=a%|Wp zDwCZ9Idcn|7K|7nGiR%*e7g%=$H0`UL1(l~Jw2`gjBZOrGgN*Cq61z974J@>VxzcRQcKFPqxBRi+_%k zELHu*fchi!v=nXmQ=t4`+x}r}Ew%kG#`$;smg@d=jwQ3^Pg7qS_n)W!_v!t+DJ%{9 Z7u1%H{PVy|Re$*|e|*os&rg!<{{Ro_8NmPm literal 52477 zcmeF)2|QKb|1W-HW|1)>W5|#x%Cr^-lQ4uOdk*H)ygJErvF`1er z5h0lsGW}0F>wNlt?)^Rf|Hr-m;c@>rk4J55o%cRx+m3biv0k3b?vz}c#1PdkYAPx! z0fQiK5d(J@5fK#;B}I+(${MQ5BFc)&D$JxCskrv+-y7iV=jj+6{qvz zzPqdUK5u_Nkr3w~Z)X=@_kAMHer_WBf}Mli*LnK|><<>9?BPwi(ZfGTgnU=O_FwDb z?CQSJU0qpGMR}u=n~Tau54VjTsvDJ+-8Q;9$`DkP~-=F?+NEJXzWjpz>=+_0ghuP)}|*r?5+UCxwDGa{n8xyPg+Xv%x#L z@pI=|!a=)``olBLHlTy;aA$OrJoq?Y;o+Bh3w%02^CPE_19bUIY6$Z;f^JX4BMC=i zKo6G|^_g1^pcg5gIMJ*O`g|mr!e^F&0lt;72Swk5ua)ea!N&K%H-DN$zkSERu)x$x zuPZiS^oM+X!scyYGVhv?am6s0)7t;U{9PBMO?VQaJ#Yy!5838j>fQ}G-M1!b#h-`V zjPa~J8|xuIRj>R$;d@XdGuuC>Pzs7R3tqpoT>`F*P04;)P=yw>)$CsTo+DQ3iFNW0 zA0~K%m_OWoSxKayTyiw+8*5Gha{!@aW-BJ4}!_1ms z7P@%wLQgTlDYufKS)N01%WR{1>>^0;@GU+Inu}YOPxyR9xxN8?H_o3$ z4F~&`7vD&uGXL}sZCeY$i=byk$;;C~3;l+A$HF57U6I#n7^a67n2ZODxw{FmvzJfz zJ4_KmZ$6})Z7RoB@DtQ0 z;*uK-H==p(%gddi8k)(eSQilr&=ila?wsp98u#^c_-VWvb<2q+hlYiL3se=7TBZr8 zxy9Hl;l&n^V|%_xh`SLy7kt&~@^P?B38!J(R-#KB%xjNMBLiOmvMR`bfN#W-W zzms52U-&hzT|N{W`fic-Lj?*k?Ql-#e<*W0b$6ilqB?JbJGQ4X3a zuSULnkOjW?j6XK8iigw(ves3HQ}!a76yg1Xulg4IayHb=cW+}eS}9){&XYn29@tx0>Jp}tW<(`6AT zeLFE+{;?sUDiigt9|RM|kNeKewtIp0OsVf$Y|DwwL1!5@@3tURYp2Cm(a;le3r@uk z`|lBJi{~P?uZt%nT$m(`l>-U3K)$gXwYwq9lT6Ml^Wjj)-9wr>%?t9-2Wxnyz5}Cg zy6*`24G>(%yxo;(3kYdL&MhZGz7blxMKW&j*OHFcQF&Tt8Nq6LVs{VKNz(CNe#PH8 z53ScXNqhA9Ktt{OyDWX!p!E5khRgnY303w;9sWnl2;+3=tC{!Rz(>>7H4Phvh|M;S zT5LGd2-U~BAtDZ^3AwNAy8=f(6Km672f45vBqX+l@1R$ZAlT9$b@iI^K^9Af%7D)G zP{m7dn@3SC+?WvCv#!t?>b^_wOuGIU8pg&Zl&c1`c~;B0Jpy5yscpR9GWqxazoZkXza(P@<7`GZV_dQf5SEl zw}40QlTr^t<7EqyLBFgIXtNIpb z>@GF6uQdT~;s3T`!D~0%qJF3B*$NK0WoEsudY}sA`A0 zi`a{6fc}>Fc-nW;1mpIdi!s_3gmn8c8s4f_Lb1?q-NxOg;mXezRj+L>K@C$bs?ke# zq2L8+h4y40LXoG0x-{N^P@ttV^Y^bOvNyt#2kPAj*<;a*Wo_hdz!TFI=#{Yh60zh0twDE&d+o?d_4!1e2f zFy{mRs$aUFU)}#IU%HwbRU@ULAseEi(q|5eSo)c3E#<-z{{uH*RC z^{+B^@4W&0efPOLk}iGrDgXN7eqBbf1_kw`mis z(dW)>+IbN4mDK4wnFT`WCLVhJ3|)fx%HeL_ZdOPoFGua_5dbCms<|^6+z3|s6Ajxl z*P#BK*q*BVQ7HYK&hbZVAffl{O~TbP;e=k*$z)ky7SdxgnL6)vadUQ5{B zvv5cFkP@1EY@*GXEC;EiWuNrWcAEzCzvVYX`8mzIWA=T?%PD%G5 z)vp=kf3Zla_oT6VXkKQ!!`E;$)=x`CkB4Vxe0tetc|Rs@KS6CR6XPHuHwJt^+6KX| z6@;Zav<<@~Dw9rjXd5$DF7wL}!?%|TsORk;zFVp#^OAj`i+4_2_x6b-n{#2>itMTl zY3_~Mn_q?$oqL>LW>obpCALbvlz-WA`Lo?;HRl+YaX-yoI=#Q{3yduA$$u$BI@6&E z%MTgf0!f0IOc6m0<)1zR#ofJmC`;At#!J~7NWi?yw0t*0RkLEQwzT1dKkO(cz%0X?jlbhBE>Y~J*y1||tDyZVZZO7jz#DijgRHL2u^SS@rKLfeU4FAJ=P&f{F_{G(C?dz(RG;1|QKu)O|98KEYxW z=ss5H)6wLL-qIdOKA<%SMh1+vzBJP6%tD8}wSA=L&-HU@yUK1r zs>_A7hnu^G^k=2(;?X zA=UT3-G}&*#BK|PY^i=otM>BFYOMocU98&hn`J$K*gf5R$%h{CabI(Jv0DOlNv#|I zv_cb|YmQUBJ$VQ{7kM20;M5PuaM0^VChI;loK&~_b5s==jvMrQI-i5OY^ABy9j}4- z*tQ|FoX_AnfA)NDdI_msAy#QH84V|{raJK;5DdraZmBYPi@I!92y|b(3r6nieK!c= z)R}LwJzBBZ2~;${8t2~8T3*YydvTJ5WlnkA;KTh0J2sC33$9jgY#&-B~|+)_X) zzxn15K_5u<&C+QLuSoSt_c{1qk?JqeZ8M%B)sMC*ox24#>q^%aUa^O?V-n9DFS!Gy za?L$2ORPX$5nz1HVL`f(*IRIiDXtm_=qQpz(|SnAk%L>eyB~gbG%d*W~sdHe%pG z2`QRBhv=)&s)8B^+m4Ok%b5+tx@tL8TzZO-7b!y-A6UYfWp;y!^;EfgCYaD-Af4)W zY5=K^-=KYSXd7BM%JbMRF$NSr+9hFX`xIn!3|{OL3L@3>jCr<;lIq3k-w=hQ`U0am zyZfYi+0!*DwaB`CC;dzD$6)Tkz{*$RPmx5_gGkwV0nj?EwziM90&g#onAlHM1+m4RtMn z+1>-;mUE_{X4wB_yY@G*m?FA1SS%Wib;>1`aP0wOZ`U#cjpe9jyeY2bVJH~Uc2GaM z_D6Z2y=*~-dKqXab!De+=tp$V{8Cd5c_^8AR2_4y>(CNDo^kzPenA#YD9#2aR_p*vRzD%o2HSL$&=>K{q7kF7~xccAjFMI(3cP?Ak3$?rAD zyprqA;4uHI{?`ixsXo!McxMEuK5C#oc8pZNndwAF3bJv3pde3rqu6!rMAN|}e&iN< z{rabqFTwko70KW7v&sirorAd)=o^u+;MG7%*f zxOl{g{y;58AK3Xa7r@uWQl%Rrw1h;NVCn7GS!j&?$}O&h=U|K;RF&j$fVuwM^VA-? zpv3}cv!33BzAhe?+c)V;NR&3caMX)MV_eoMt1otgF{X)U?0h{Cr_>N;agqB;WBkCl<}hSnc}k&rUi|9zI>A zwkVTMM?&4)4K(nsJ$5NxoK)|3DSUVtsh;U|JM$q@z3o+*D~%}PkcIK%fvv>a6&pB$ zI`hDxpl31xdqzR`kDqHonlFP@#QhiUR~^ucE{}lHb9cad)q`IS+Z%!JVYl2KSl%KO zU#?tkXH0;%ecCN-5hCdA+k!Mp$1=#?c;q?H3rqCw%$en!CmqrEx^=pS49`jRK^!l1 zY{5Itz0~tvYUrI@{x0wCt&shtit{-|T`)8mTDv~#3lh_xnq|4|gI*tBJ-^F?2k>5s z8{bt>0}3*EOkQtXj`-`IwB$GNgB~<7b*&)-JxHun^{saR`2vf_$|h1#-S6iYK~-~_ zLBmWE(wvv-Y<;#HO*32%y+S!gzgB!oYu8>Y?r5maw?h@C6ffmAOpY-3Y;FXi$;SqE7hdV-N(!%M*0XE7D@3f+9{Cs<-7N}HTGySR9^?oEC+@AT+-vRcu?lI zJ%ix}U8pX3Yrw9vsjWaO?dM2`998sl@`A{Fql0jjzfELJ z$9qDktoEVl4hbl9BlXj!lrhMw!9H_vWe94G(l1M8paHWgdRsVd2*Oo?a%zPA2SVuS zRu7Bg-=R>p$Qstw*^pOTQSdyQJs75GZ>lT0hE@lqhw?BiL$BBWC}qe+I*Yq98ZWX0 zg3{_7;^oL%#3{HslUCLpbidPtgslYz31e@!*-D-f;DDLsI=`(d_~4qAJ-XKN+;g%~C-mD-87eb=JCX4n_RN^^GIzuA+&H zq2{~?>%i2|YfXWKMuK)s@AQVcCs3h(&+Pcy^@KnYH|n@p4F&cz=1Q!73~7V*sR~@~ zKvQp$)j#lkfwZFrseXG@p+esx?R3u~A#jPyen=_`3i#C02eLat+Te4duG5iVgq1@# zeVH{9kPSQ{%hQLNsJ`UXcg2?XQJorF!7TzRs@QsXzmlF$5;s;c5Kf@$_xlzQ9k#2J z#``lWDiDt*))s=ESAp+W58o%~T6Hy;pR2%Sm-?0JPxGL0{sq@Of)z!3pHNG;=LJPi zHVG!lz9iLeICkUf3sSw!#E+khr24r!x~V`kE}%OfyUGd#1h`DDW$J(;dR6jqmNdxi zlD+KK#ZoZB=l}YvG%A0-)>{U&8lmsX#fvQOk3(8^PlqF^Us3;4+~aoFrarO*A6+9y^Z>JFA}nS`g{ zSqZI(<8Cd)S#e_K)rSJ`Y1@m3)<4rh0d*1!_lhH^AhbO49gi>=y}X!iS)EDHHa@i) zes&(xC)zjO)_Q~{p0ym>Y)PO3I-ha2ZJR+s__64S%hjZMjU=I0%SiP^X81)hQoY?= z!t6&hQDYE(R5uC)&2>pQ$O}U;{ho=0qf9^~MsJtiIT0{g`lTt5KMRR|sVyA4l7uFG z#1@CeRY||l*E$x$7YWANf~HbjuS2nSt0Si89zijx3`MEzNV(Tn zJ~a6t`J=`d>AJG}nyH)N11R>!sZRdeW++B|)ZoosEmHlg=b;E1LZ~FNS1C~&jLg4& zxqRcG&XlmIz!Tf+;8N7pQ!Eh%<=+}73rC~HL0#oW77<}y#HC~WNiDb@d<5B7B&Ae9 zalFLxH`@!*)nreRLN0nR-n+ff>$x34Wh+`hw^##dMCUT^7i6IsmI%2wJKIt5MfyY1 zKU2WfQ!{)Mx7opX&y5VX22N5v$Hgs~p``k+ug*j8ha(u&)xkksdwzq75n`u8d+XohP!U3r9ckq z5xuNy$Rr3=I(ws%gp&!C*Yw;umqZ9zPw8Ayb9->rSUbwy`#PGDDjT*I)%6%DDjbJRFWwH&nXYu> zPyKulGu+=~-8av$4+_6)m~azl#h41VKQvJ~f)sg#2 z^)%OZ$i$%eTI%x*I=aBe<7s6b<3=dh+G<#Ol@qu{Z4r$=w-<~hTOFG(??vo4;|`sW z%3pL>-7LEC@gr>27^9f5;G-a`T z`_R-y&>wcZ;b_t>G~4_5aE_hMd=>K6sGoWn}mDvY;tF_j{>dYrqJY z&K}=C1Zcl73$PUI0}Zj}^YsTd>&)-h{&0xc-S3OLL4S0vfsB|RFYVp(9i$&S!FBZgJ9Q`WX7~zEf3L_dDr44bjuZBm=sFj#X+42B0BMOrtTT2vDu*+~vK! z5www(Vfn zlZI30aRKQ(=@o6?eueaW^7|fe+!Cd~&#q`(i2b8JY2>5s7BK7aB6a=iD70{pchc}| z29Rw43gQe`(eM}R>F+dZNObP3eZ%k@(9!8NJo@Ac5TL(ui1bp5(iEL?)zap`O|e~~ zU(fcS{7+ve4AMyxe|=6L@@sWa57m>`x4QO$9$GV%S@j<9YVd6N!`uz%W=K{*L_!J3 zfAj9t4ecjr^2@ZFp6e*;q5dNKq|OKQ(1m_KEVvQ88o2ZA-Qg@SazLVC#~L$0yZ3P_ z(_}ZOF}>8UVX{|err;URrn6k&rG)g{@S4|%IrGVh#_)RZW+>sunkV9*u$JY>*lPl$ z=~*6J%N`2GcL-Dn)y$)5j)moc{JdZ`Tbn9G!X7QKU2!ZedVvaSw|mubo1wJrXC>^f z#gpn+spyEjAk|lf$0awC>SysTPC2Z09i>wo> zTP*GxuUi0jb2p7 zc_^vE${Lh$7ZpSSW6)J{znHVg4&7*~ugsFy1_b+T!_3JGqiRoM{-Ex)7@Nkg=|2xXl@YES_LY$TJdm&hwDtl4TP;^tOKt^j<&}r zb|U5m?w^Cl>A>5ld*7=CTtShk%-l|K0g!aMM~^Yy5R7`9$bElS22G1R5_5Sn3uYhA zSg3NXK=WxuI=jzIq9W7O%hRiMP*U=+*#4a^r23fqTE<+Y`hyMWAd^&IGS)ZDissW} z?nxNr0V?CdQ|tT_N#nef&-=mqNGaz?trW8XXl$KrJt|CJ{`G2IU6XzfsG+mBQ@yqi z+)&7?-QYKgswR(%#W)=#=y<74R}Ef8_io1Y@mpfht9ozNM}%sLG;OaU-0VDn%93PIT7{{6_q~Sbf_)}#pr$K zd#<5Rs`szYlQ=@EHyPwQA495-dsH-b9?csT^UoZS1ZvmrYc#2xC1?a`nO}#BA+?rw zqMu(40YcZO)v-6J{Pp&O;l0;9z|)GrLm6SxAf;v%TU0XX_bP{D=c6L|2)faM3Fd4* z^w6bh)nk_J;Gw&Wx&6i>@J2Gb-)`s)NFBepwqt;Ipob-~$?EDmZw>u#^U<8voSVLg2A)V?sC_j%d%KO>sK zYwAZAY?R+2mbejQE-D7z?Z5Amp0E)VjXORD=E)#nN6YlfcLt#Uc+%l_nL22Cv$%5K zc78DX!E^ac@D!R~=DnMyD}}bv5{!Ov^VIn!YfoPy&)xoBM=m?b+BC#{T4Ks|Cm*Wb>RPG z9s#`OKGidfkqimstv<1Zj1((R`_Ax-gy80xWA-Jv8pH7&#CnIvvcdtsibKeirve4 z%ecNw*}SI0{O~GmkscGX(>s#2bp>jk?V!3`lH9+vD-NjO;0Gm8K@KWV0sweo9Zy)} ziC{dzN}jmHK^IDZgdEJkfd?EUz!UV8iEliij3;Wz6QDRSgM%nI;6VvakOK*LqMtH> zjwhz^gfE^*B?oVCpoJ0?AqOxh!3J_*fHDz}C%Ey%F`kem2Y7HW1_w@Xkb@GCAO{a9 z6Z&|f98W;wiCuCK2nTF%a0LfKC_xKyfPoSWz!UCxA{$Q-lLJMRpbj|zgM%fMzy>)8 zK?xY(iF-UDjwhPQ!6Y2`!9f}vP{F|uN}z%qRKNiM%EUUJuqFqbD8V6eAcqok!2uF- zFoP0!AO{I36ZClEn;ev)1dzzV9vqmV1X0KV4;-AJ1QN&-{dfW$2d;3C2?vC5@P-m- z!9fumz#s=3a9{vW#N*%=B@jgp8sPvB4#wcX2_?uu4oFaf2Y5oC8~~#PtH^;R90Z~S zY{QlmXHG*I0%6Q1~`z0gI+j5g@Z{r z@PmUilz<8je&9d_IjDexZ8$K7gIJIpaH0f<$blS6&;@$c)$TU96ZB;E*zAi z1dzzV9!g*a2T{lY4;-ApK|35^!@)2dxS|A^$N?cr@P-^{p#(+90Sp}2!$CM4FvGzu zN+60HG@=A}$iWy&;Dj9Hz`;KpsKY@u8~~#PtH^<+e}X{212&Z43ONvh1B5u3M+v-< zgJd|MMF~FPKoL2p^G^Wgcd!Hp5h(#b9Gt^}G#vE80V*6!A_snOkOl`-C_&NRfl-3o z{`dANxgT#U!8JOoa5S{%Ut4cd+sM!NVJdl>^51N8kP*m;)dIh_n*ZAVm;Ly4{NGzp zEzXvwGms29#ZBh&j#@&?825d(OiRIvf7kwMljbX$&M{{35uAe8gmc>~p`~f>55-Du z!ofsQZQgExuzwZX?ieER-`n?B9~8J9zTvs(CCDEx{xJ2~H@N-jo)6-W@=C4#`+Gn^ zu{;92G$;5AMW4!Be1_ZOU7Gi(ohCd!>3W^iUqg62EaPvxuczhoU+llGI;L4edO5TY@>ciHNYc9gU)A@qog8f7AVhlwnf&iQg!Wsw6VK==5P`dvPib3^6M;sI zwUGm6|K7VK;CBzy_~2k$eo6~UO|12&diD&uG@Z^EiSj9h|G9@|Jg!G!5eb&LgjC0~ zxs*$l(4`dpP-<9Dgi4#hWWh)xl>Nul`F`5}^6S$#rakWNtPT~Z=hF5WNkC8Ln#{1b zb^rNjR8*SZ$d9Mb-bVNKWg4Nt+h7o2bs2h0^Tiqz?jgb(*mft1oF>9=2upstx9z{# z{}FkA%fr-PyI$l&Wi$4}ujcik&uz8(=&1aE*W)&{RLM8gWB5iWZ%C1LXm*4?aqGY2 z30o0SUnF)<8|V;Gerp`+zJqa0pTkm z(@q%>v4M>Ot6WuxSRVm~)8>@N!N;jH4eW#DtfipD-4yn!?U7(%aA2l)fEQYF99P@p z$gD;Fe&Kq&g%YJZcX9CDBdA`LJBsPsKugy95i&X{gmbtZ^-F_3()Q!G#_n<`|Nhpw z_H%To%3wtLs%r_l*`jz>H2D*;<|&gZ|7po&m-7v78>M_M-V*W=F`?s*r7G;o9?+5JHnNX|F8+i7Q&@HZr8Q! zEW%{ad2n=_IeHQ3QE&T117&+qx0Yx+K+C2Vae4a-;cAYO)_Y74?kqB&8MW{vOqY2D z*H~$S7ekVgmxU5gHh0(g7|yrQ^0VY&Mq5r|wOod&kJ32YdGhS8^B%l}@5^1aPZ}8s z-@BZvUKFblMiZqxEI&Qbi&KrUobPx+bg$8}UWIbFwUvrlR=5mGx)nTua_rElStvGG?MRmSfNv?{rz~~AR@SG zNIBP`oCv=6^!tH2al$}3H@an&OaW%WYh`c|HV zZc{{H`0Xo%vE0SdGx`FctU(-Yx_1mbu6lZkI7AANy0Y~*?(`sJfoD4(j~R6970x_; z{3CH_o-SL_sgpSLA>w9`OD?fx`e?Dqwk+`c-1hwsa=1bDr?rIpwUf|J$*Ludc@tDT z(ac2UrwzURs|sj&Qwhr`r;Ger1?V|d+RTGo0IIF%Cv+TFLi=bjeYVs!gkt2fk*ogl z(0j-2%V7!6iDLnBkyVkqiDOows)xny5r)EgU1MX+kmlZG%uSW2sG}e((kVe4I=^-{ ze^apll?R$1a$EL8zt7T{65FQJ#iwTCwA02TXZ-t#(_84pWfJTN3stIj*N0WmWYg3j-I_7aJ~(*UjMywGCq_6Be=m1f`4lOlL-oi}@0IaA)FoW?S@(@bYh zE6_vf&}vBPPmM7;1o(E*+e~OT1M1JyL$_E(5of(;*p+Rah^^;Ht>&IS$d#BR*JkKl zK6u3WWmE2#@*k1Is$L!639iJ%-ZER;@^*LD&Sx+406i`LnEpdWG?r9z%g})ZaWpO) zXA9vhpG{Y8yIOh>j3qU#^qJuXJXbp}KlW4y3_Ct3Sjw-`=@B~>_&irq=f0jD^F_sT zP+C3EJLJkI#4GdKRaT<_G2UhK+MyaikowKMeAWW~n%ulS4<~h|j9NePlY-Z)7d`k1 z2Vua|Z!qe5(GW4jiw8bZ<|jz~f{Hx?h`+}qD3qT;XZ%nWn`QR_z&&W4IULsvc<#uG z#Zy&7g>9!SIHy;jl@lMgiWiR|28Jdrb?q|*sb9os>>iN(ROeRgEUz=g`U=*ZKMAEG zg4_zT)pVw|v(*}G-U2vTcfI<_f0dAm2szg=C4~6eJorBFS0hp99+t^RzCg$&Kx#-* z3Glpe)t&oU12w07&c;UW0&3Na$F?2}0|rcdIq`$kgyz&?W&tk&pwVITq=nBGSqN?A zT=_l=%BW<`eVcrRRJe;zRI*$Jn`(t!-MHci8I@<7%YB`Yj#|w3){-;GczaRat&{GE zrSh{=sH6p=pPakU?chV$O6)o8ap(a$et0tRG_5rX{n={KJoOsdN^F%{`Drsa|H|2- zFrgPXbmYsIj-DaRofMw+ua^gr3wxg2P%}fmFA}4ARxv_z$5~oGFIjY6xL>3VS|Uq7 z@c<#aArO+d-?i59A~^7L-^xI}SH#wJE8oxS-vyTnM`-j`NrR&@dWxd!KESOCUskN7 zjYjD-W}Z234S;GZ;i?joLF}}oXH$JNfX)XeZwgi!L7uVS_A&?2z?~M2KbNr^fGf|L z7;oqofRh^Mlf91mqMMCZ=~51@K{wwVU)`<9f>vx3-RmITgXn8T;`bPqmABpKo;-3y z576eTeLj|kz{bN*k6J&T0{fmD`h)~Upa5Y(^hNan65uti-R|Fp@;El{ax^U=Z8xPR z#&;tD{#lpLKDR)gqzkXqR|(SAP0qaQ8nL-pIqJh=F|qkk;mK0DYcMdlA#zJ$A8G4( zeN6}pbUt?Fb?_#B(zf+o!d7|0t}RmSt57sy*S~_b(j9WxYqv=NIbcKG|rbZFykf$-- zP!|jx?tN;WuG$XwNG>zCGfyUM8P{n%y8_i?{M9>GjYDj*!Uo2{ecT7;jb z;?&A5=ZG+O?{p!aXd=u_;p3jx`$TYb?X&uN4I((QU?sHz4Wa#ToqX5M5<>e>!uhan z4J6edr1Lf7G?H63Bk`S83s5aL>}Fhb0dO+-o!@Qq9_T)>ydvi(3sioxd(-jgpg{JI z1sPf;D6lI^gJZ-T1WZ;`Nk#UW2muZDe%yoB*mgk{>ZSS~EI6fi2 zrykLk%v->=g0$E(8#Rz>xp9i#&O~G`!c=*-V+4t77=_2(kSzZx-Es2u!7G5*?7ZVZ zt~*+_tG&dB-r)aQ&gZ(x|64g9e0`&3i9h?jB}CBoQAg=mG!d45?V-aqXcy4Oy!Smf zuF{IYpW*rswyJ&yOTmP%aV~X5KD684siToHNqCcQCvOqM+N);foda6%cR%28zRfqoHPveGFe9yy!l=A&;LM#<*vs5z2AuC#UaW}T{%$oYvPgC zu^AY;^FooL`D@|~&-gX&`Z?kZwdcczEuLsKEw&k#}p?U|; zawz4vbA$RfXXu$Z+I8&8TH^R2-W}49TZrR$iJi zm_@20TM7BP8h<64lfOSBbmb<-X{@`U@V)!b))pOt?y-6Xt5sA=9T%6bT}#N{ml7v( zeZ-lD`NkU=L`0PLK>pMzLTjDnft_+U3BhR9b8Ovd(6uS>=FXjuw9YO5z>oE7tJ$Ks z)FiazV#RG9zJ`L4`yzJsy@IZ_so72fcX2I#9+Wiy?jeqfZ4q~u8zPSK9QO$+u_QLO z^3_PC+7bL^HS^Wqy`js^*Q(Xt%Ky##o^KJqA8+G}o!$Ab`e-`}m zi&p6G+kZdGKmU`i!wzPvZE_|KwaQ+0XYwXAlT#$sy5 zfA6DtoxHvOdrN3W_Z{?C_JX{7W>q`o!=MZ6!xtO61~r|2-;V#+%p%tx6!y8uT=|?h zxKiFy<7E(`^Ht+ea8nS$!)NRKR8aytk3YW6Dfg{}eE+5734xN*qNO_^bei%mJ9)Q3 zo}I6ko%7;^&fh*CI6FZ3Jv)9pyd}b9xp>3%^oTHt{<1^T8=zs>CkYK54m6Bxxx|M$ zNICeykoWm_2$O=yfK!Us2#J_G;;#gop??rt>wC9YXl3oFp0w=;7`|BiQ|%*yR4c-& zPFC< z+PVDK2+lm$O`Pj3q5V&{$PArfXw)p=U$uV^!N)T$6VSFB+QzK|{N=le9VyXgcQrXc z&O341dmL<_{p^@is>^3+1|CvFmvLnYOL zO7(=(woGrYTscB$CCj~KckV*ByBt}k9X#QVo{_$kgr6v2&4)r=H9$WI+8ahE)<+F<6NPDN4MTH_M?`S(#xjDC!2v5DLm%yAu zgr9v+1I}g>j?H495}CxJ&st}Tbcr0tX?K4OT$j2YEPXGZ1aT!XHc zhu`bBAr$}m$0mbqHK1ns4HYeqVCZg966mJoGqLM-%?5716l~|}u zcmq(ATxr~fWz3M&pJ>57f-WivRTXHcf+mIh3u{j8hn~^yZHD}N!O_n_Nce*ZC=PGD zz96bkkovz(isqxE{c`0MpO2y9BQCB-D!(A94dw%p8!jQ{+INa=bMu6=q*}J#n_dv( zdTy%J=@zPzDR#TOnjMn*)4E4QQH*QP&076VP$d&o#_doCx6Pz2E>lqkdo<*=f4mR| zH(9TREcj#)r2hKRbBE9#)ni|%GA7VX7U%N#ZIwVIahHA3@dcd*)HuFc;Wc5h@ngp~ zR(TLySHbH_Q;qT_znvYbRfMGeyhp;yD7dWx`HdQays1s2RF4v&VwCTdi57F9|9)zp zZS@xre(h0H@1P4o>L0v$fD`Fo*vMqfXph2kj*D)zy^WMoeVSW_NF&JmPI{&0AB19$ zk5f`9HP}&|PN&QN5nagFxyfKt1r>X|LwILX(9Q*MWoMKME@U~>-0xo?RupaexajZ< z@tu92#&OyJIb}UflF8l)R}^U;iS8Byl4otqirXcDlXYS~>#RSb@h@jAYx#y))IW#x z=miiWXGeRd4*3IP+1HF}9|O^GEvgMAqU)f@*{}9R*5=4!dkk@TUo1E_?LD`tP@52~ zR_e1-x`{NTj5aH0RiFTSjUhjyJSbW%f6G4qBha$|RE#G3f&Y{_yVgf>pnU3?n-Ck9 zPKHI=t;5?Qfx+8gmVIh*XtU%yxv%XFcC%5jn->-LKQaz*)!K~2&Ntb=8`FzzMqzXUL#a0e_I%A6tty2yS)~T zT%TVYd6S9a&0;D%+Bbu?=<3Ed8J{4ReqMp$g+_ud$M2jwryr!t|H7x0D33f z(QUGa)E>-wFcS2;&QAXSgTIyh^|zW!f3W%YzrQEq?~~#0&%)pF;O|KIcO?8f68;?t z|Bi%zN5a1&;op()?@0J}B>X!P{v8Sbj)Z?l!oMTo-;wa|NceXo{5ul<9SQ%AgnviE zza!z_k?`+G_;)1yI}-jK3IC3S|67cNtV@f!EUmn<^oOR5q_0{MYv=#NOQB$?3rkd3 zTEdbLmU6HJgQb(vU+0|km#tX%!h#hRny^5Gg&i!&kcE`rdz1Dj%V1c(qR38Uxd_WV zSf0VM3f>=!ViYlpEJ9)N2#Y>gtid7+-XBY3SlYsp6qb^(1cap#)p*)Dq%5* zBI1yxJS@SH&i|5hh9xg7Rbhz+GBa35L)WTvE7Ll;{LrHX!r8|n`MwZI3#6^*&$dVG4 zf+$H)vXF-bI4qoD!3zsjSYX1!5G6s1Wj!p%k!3V2e_`1Q%S~7&!pT!C@?mifi)vU5 z!y*0rl7%}gxM86T3tU*3!h#Y`$YME= zBIA+eH!PcBxeLow`1y~MwG?rXEb3t~4vT0M@rx{4VX+A(anzOZD4lgbpqkt`Hqfe#CF6hVzFgkb>-C!DeT zh-E`8_hFe1%WGH`!*Ui*Mq@FOA|hh(4~uqKY$JH9>&##W<|E#iuYnUm^>-;L{ukp=TYksa{uBfG3v|Cybq1z*GMnCUombx?f(__?f8hp!fm*`fa9i zAW`U(Lz>U@ukY-y4+EqInwOTZ*UzB27*FIXp}h$5Z9`8&&=8G>kMDGw_{${ z0Ib<_zb*5m6VfM?TzHQtYm59=_rSvLE`VUU+>YJ?ifbOn7`E z0gWo=3vaaaLF251$h+~~=;Zp0YE2V-}!AtaQRQ0vZG%E zl99NFKhrYyEr`EjR{)*n7!qD}jnAWMBa$##e?Yr2xpd;U^7r>O`1fC_{Cy23>%@Ow zgO_yS|5aXt(Ze*K^P$J9!Tm1kl^>)Zpi7Hk?&`0;fupzDbu3Kvz{YF2-!#_Lfat^p zUwhm2DF1PE@T9~EP%6=AruxDQ((UJ%iS(5rw(nsxw>o+`H! zqU9I18J(*Gu`N9+)5;8Ry-n7xTg9j0W}oH#rP0kOe#+V_rQs5ac(lLZ`R3E;*hSWi z`p?l|uLx(-)<`X6wRZDo8nbW6vN=s}@X8}(twu*fOO$~4+4&pZ=GRbPQs$!@k&Fag z==3p39Xm9=RYsk(Y7Rlqq$W4L`5{3=#Xz_A#TGO#79x8%|1g@+HnyVe4??{U%^X+X zr9xXj>vAim>LTv}<1M4vPtabaM;R8e?~sc4f)&$LAChUd@abqz13J=|Yoh5cwo-(DVlkVXAes}qy=E(0^s!hHe-0VunR&f4&+2)LwoucTsy z2r7EaXr=5Qie72ZT)opcit06;=L-|Jp{hH~A9a2n23>Z{Hb+N`2*Ks!S7VPepzj$} zrLv52sITM76xTv1>g&32SKm$urEh+^&Pz1{%rYZl-X<Eq2iGy20%t zzaIoQ57n5}u4_;y@?2?SP$g9Iwc`@+tA=!0E|N6W`ly3je7LMK4h`ljGuqjm1AWpb z7i1?-!evaplB3xWa(!>eZV=f<=$v_Sme7KPl0U;u_D>{@IlJ!goeO6`2k+e5h#RJ0 zu&|6FYyys!<|OZ+w|Y52IOEl^NF~Ye4Y; z3bh;Cfv(#k?(Jb-tC2~M|;a`Ddb8&a;k&gp3pgJl=iGefKUqNOtXvAAm}d3 zRc1Uj108||JUJ5Iz~KD4D=Yg=P=EXQRt4E|g5GgO%kbNa1f8vPhhfltxE{6V52SyA zVolesI|YA1qls_ruNjV_#oTV3G!O& zHRLtc8$X%eE@yuWT6MpFpOlOOuP!{h#I)%OCiXCWheJ1ZYmXo>JJlqn8w3o9j4?k@rDUPOao%F4^w)WxTDZ>n1myfg_shg5PxKP z50iM9s-qBcWa1FhgO~)wR39evFl~p)IZPsAst^-`nD)cu9;WapL>-w>#IzwM2QdYR zi9Sr{QAj&7xrix5OcY`|5R-nG+M^J7m}tawA|?$nHHZm7O!Hwf50j3VTEqk*rU@|_ zh$%lZu}At@V)6aGjIZnOg?#^MF0J$WPjhJ&?w{t;Lc0GnRe$|x{?lClpUtI3egC<2 zX<6TYnj8MJc;l}oE9IzuFYfzCd+E6TXfGYuAMK?hWBq5;piCc97EAsgoj&|^V81>v zM1_GU3fzQ2B@7*5fQSqOVITqm6W$v` zVi@?s@D>KKFjR#BDGWOiBEO+C43J?M41-4bZJZz(_;hRevH7>2&^^XotN z`lp3qH4L6%h^)lvcMXQS@E#bt!fgu3hM_bJm|<89gI^fp!ax>=t1#$B2G%I>83xHP z6ovsW3~Q0WE7EZ=k;jFlO99+i8WC_~>Bk*6mc|0ySQ?{nV`+rKjo*uolka+Ibi%hR zjZL_*G%_)h%gBq4)2n879Uw3v;haITnHCG)2gmXyrqQaD>OGmH6G3d@SQRLq!?nO)4^Qdn9t7mFEJ z%&St^Q!>koxm?WHVqO-rub5-SOe$%V_~+VU>BsAz=Ks>yH2*Pz{OkJW_q(Fc+PWz2 z{3PfZP}_8>q!xThTw8Oj=L+c8U2SrNEdUG*aWx%K(+7hojMjmU{9s6b?u}3MHw+14 z;Ew|DVGs{Pbr_H%!)_QJ#2_Gs`Y@n}VLJ@YQ6M-nREPmV3hal$Jq+PtppFd3QD8$d zIEW!Y4D?|*4}*3Xn!^wx1`078NCEvYw1)vaGE7H-6ESE=h6XVJh+#eq=3&SVLyH(d z#4sTS12N=>fjtc0VVIEuCSu4C1A`d;!yq4q^2m@Q1{NvsAqELC6i5O5e#3egex!hm z7)m4qh8Pya;2(zgC{QE@9LcaE1`jbrh=D*1_hDEPgO3VV$zR7?U5-+Of+IT5tD|P z8pH%3h2|sEk(hME)FLJjF-?fcKnmqYrY11~iD^bmCSuAE6N8xk!!#u(BQfQOiA78w zVv-P3ffULT6O)*J#3Un`N~92mWLgl@mzbo)R3s)GF|CNnLrf83Diafyn3lxkBc>QJ zk%;L+3ayFBOH5H>B9cruQb~-R6;~yZ9?XRBJ*5^%o#%7{dk<7;eFoscm3Yq z_j_Hx_qy8uth4ssYn{FC>zuRp=X2lZ{*ZvyjjZb@;hFI8_kN&*L*`{@qY>!Za-k>q zoe1b&Ep>2>dklKdlgwx2(t|#?U9y}k^#nOL!EpYk(fo$N{7++ff}uRYNPfdWo?smR zC!>0TLH&j?J;9KkU_?(apeGp5|86*s-vc4U`_FOZpM>b^2iJw@_=xrGXKANb>-lI5 zyxGV{*KG6~H}cZW8~X`JO>K;y{IOkRxEO)S5iR-QdQvd?T=|=tCj*$Yy)%6{r3p+b zSjk-4GY=*!H4^vOu!BiEB@jE$yYco!ii=(mbiP`T6<7EpPMBu)D6YOYzErAe14vxM zy6+B>mVCAp%1M$bRxEHECEghnhG?x_H+LV(CX5GBY$=rfo)jRL=Hhi4)w=qjF$V96}MXaxT7P<=|*0f(5VjL7b-vo!{DXka=lZu%d$tv8tWA z@nEkzV%6s+sAC4w9lwY+&L36kWM0ysn`*M$wRL`L8Ic zliH6;&;q4gA?=~J+=gO;Ypu&d2Ed~qUW-wCYQSez&Mv>N;^50Nd?bG;6nx!Pmhj+o zADCvwY_1IzgV}vVna;D6zX_#vzCK9+lQs8x7moXYTBa`DvCSQ5rBGXeAx0RjES);- z63T*B6T|PD7bl}1{+HDEC?udYk4;kFhyg|<^w?*I@-~d<{xe2}$n6+W-R;~nv1yP< zK|#NF zfjQqH<1+Aa*A|W_*N>nuHeR|ZIstDTT>6TP3HSpy7D??B%&H(%ZV`kKFM~K1UDZy{ zPLR|!7WtXO6Qsmv+T-E`5HtTM;Epm6O4+2yC!=eJi37)fIH-ee z4#&Sy;Qo&fIQ~r2jvd@Th3b>FRKydz8S&C+doD-c;>Gb-x)=M<0mnaxb+^?i9RIZW zFkfLD|ETBmEFWIXIQ|)T)~=Z0_`62?O_1aG?;c}mSi|vG=2Utb zhU1TU==W#f_(yLt&|1Rr&(WwhdyeBDI8qZfjpJ`!+&c9J$Di_J2bC|5zaxp+OI;lQ zLl;$@`f>b++D;=D9RI0i@$knu{zBK^N><_ct5ODa#p3u^`8UcjpT%L(H2yC@RY{;KH{KE*?Jy;4;Vnc)_IaWrw{IZXJ=t%#tCt8R zEaWAXnV3v(Jp_xLBM)P1xFM-@%afh*=OO7dU!8TdJy^*b+3|t54D~$-dgl|xf^qK? z+S^gOfbH43pWd@4t5{XUm6Fkw4M|0ovL5?L4)%sgPqdN`0`U?#=a$#{h%YcNKxmZ} z*?A=<_Fip4LeC#sXw1z3U(X6bcjqYud2KCE4m%3)oJsD1@b+|oSu8e2yO4qE`lqSk zWg(zxLVC|<(o)d=c5BRdb}Hx%oxdt~l?e3Df8Tws@gCvxgGksguiVrOw4L$6u?7o1 zwCT;sc-6IIh&D29IZ&CTWF%c$kN7(o;63GL^kmmvz>Ym{uurg3P&@Ncl#{;;H80N{ z+|8zh`uO+G^lp_ygZJ6*ZaOE82AVUHlb@NPj&myI(n)scZq6}>o80q+(jE%x-h6MO zu6Cijrb=fV=_OHk<4vjbIbWa|j8b`*bAZ9!)E8UMtf3cO?%dnN52N=QowVCiet>o< zpWzFZ8VXvQ-;lc|@u1R6<7(BK<*1IUFgWiTK7X3fy*3zz-eL=+L*>38b}WWrEUg@j zt`&(VbCH5?-jD6_^d1xLAN;5Y)J>f@0V#Y=%%{+th7=i%AMPYJgSEIP#%XJM=&O36 zD&1>yjIWrjDE(t9Cf2fp&P)p{VwK4{JMpv#^1_H~`^u);S*E-2) zx<7#BILj+ERj)Lie?AFK)5bsE7EuS()xZjQN@ zt!9Af5updF$IpT3j*E^wt>Iv*!b#nnZWv6Hf%4Z`^r)>Z=f0kGv4T>1P?S-)H)>s_ zrBQh|J5Y2h{Ffb#NC}l zL3ti%ddk?SJPdDpgri<>b4F7&MFA9Q7@FR8RB~rzKlmhfig>k8T5e@CIb&IxIOxBe z>(ce^IG6}i(k$0*1Jk3i2a;XW!F1c6%|Mn8OqC7o?@PA<)0DFnGec+4C*f>!r~V^^ z&kt%NJs)#kehl>)ZDs9`e2TgqhFOwKa?snEcQ@a^^a8D>>e_E)w}F+R<{c(_y^yv= z(l%U72_OGUgz`&-;&_4}cK%0I`W z$s1LAcgOg=8U)X7WF7BVy#RU-&l-uA(x5p7BHglJhGO-NHCQ&}%tcyHakQgMv#QBW z2S`SWkUSv~LkG9K)e5arLkHB1Xj)S2f%tYU%$@uxa?b7Rs$k5M=iOL?zjU1XAm6@8-V>din>j`*TT|ei)_D3ScZjJ9+M3K=s@q@DZiinH6!{bOn8gP|e>0o|7 z@M{hJwFduMga7xg!6270e`@FTB=kt|bR0`M1?Wg>QU0B z9mS-Uxnk{n%djI%`(wRF+ptshnOm(TLZNPSrCfI~35vO0-H^vp3PQMU@6->D2R@B` z?fEMsD1cw!R7ylA!fThlt8%-D@{VqH@w_kyDg?wt79zfa?CJa3A;&Di?B!rXW)}u9 zdu%xE)0PDAZF{~|#933Y#FzJ4fpGy6Ey12O{pXNOa-_?Rr2zCD{5X16xeL-VIt>zQ!oZE3bll|v9dLGb zytmEi4)WR6%^)E{j*G zGKFK2^yVZiFCfifR(tK5rfOpa7XAnJ?#qtP}YPk(~l$sCL1cFjhh!q=Ns?pgq{a%h>b?7o zB4{wd%`xw!>ryaY5hCf6ox&KS#`oBs^Id3xSKx8)1uL+4h$dj``Ey{=dW_mvF%WW? z8EM^cJ(Wi@Djy;3m~v=@u*j4IByArLCaHgd61yB&<(C%4)s$C#Gp3 zu@hC)u5(jhn!aOjsG%q{nLq%O7t><*%&ZN_9%qbiOMc0umWuKZ=I zyHKs_Qo`n{I;i0OCTr;?fj|uWh@W!|)V!WI?qF98;Fh)&oxADFbwBWULQ&#K}Sc28nohCQI zg5BI=IF~Nuu)n0WI1vx!`;E)1h}Sz*Y#Loeg}`-eFG?+bhabisn@qa9mC z527VKGpW@RX=uSS&}^cC4CAmcj+-j4!Q|f;4j!&7#<+`86|Q7hW6bg)HRh-fQ>2&LvmydtY(XZ_@kF zn3>`tu=Er@$`2}ew`3`f#6Z?`zx{RG(Qt2NNTV#*Gbr0>Wn6Mi9;#@OUa_~8fqEB+ zNBbJGp$(ZA_pr#Tpob-pe|C=>QAGt5 zC0@CIT7wTt=+IvHu&M%OispBBa^!;_Vq(P=F3^$cZHjkWHFQart_cpzhVEC6y6Dd0*F%3r+S!_laF<2;zrT`C{JkZ} zUJ1tuEn>E0ALN$lmcK>V^MBVO3R2pXZjavo(Pcp+D^rX^8O*(GtpWG1sX;xO=l+6EEd%iu`rK%R`%nPn5~}~af{k#%<@B6hxIu=%;9A* zOY?JO%tK>yRltZ2=0!WdaQh1>=9kR5tM{1!7Fd!b)2KC#g}Ja&T-Tk#$9Ip{_m|+% z{?~LL;mEosg3$T@RYv-U2yC5<{Y}C_0@|eBEk`slg7#fZykU)_pp(f=`}(^w&`tJ$ zXIW|#^n4pg?pXZ%o>}wf4!+s@sHW+Z$E3e^%EfRMjR_)843}{iiD3 z8`Zf9Rk;b(xCvFb3DviMueyz2>mRzj^&i(iy6bmC>vYQf>`B~g;+(DL>GeIoncw{+ zoAK9w-zX3L{#S0`p0mn|f7uTLDdsQzmx!vvKr~m>}MZ@nrSW>}M#K8BIqFOK= zqknm|WaxKZBvBivh6F`To~{MTou_nFbnYM)t(yADy$L0Cdz=J8lLq1*uF9Q`k3wQS zkDuya+&YG;=nx5PhG!!_}_ggON@vU*BK-3VoU8 z)XINe2&S7o7h;bmf+fakQ$5xUuslcQKCvx{z>8p zSfdzGS7asnAYzM!&OL%WL`h=&X>Xup&ro0#XAG2s(bTf5qXb?A5;fd8*mg1vawNy~ z9*muatj_hBd^-z4%Ze3CPs1|CJ;=*AQ$2`Dek5beh~~oNwA>nl^rQ&92;^eTTC8V{ zh0LAjMTAI3cHPiBLpQ)+Rp&QjpZs()6`mqnacdT_{2Jr6DM7f&4JR6@%` zg%>iE)d;)@#@X|heR_-vvU>HEWh#xq7U33ZH+rqAP?~+wbrNd zIR3pN&$6%L`0E+-bUF}t5lHl2!)}~d4|1e&?WWn823cLI$UJDRLCaLnCr!ax9RFoU zUw;xz^23^?Bg+_$zo5|RA!-6I0=c%`Osu5%3Yite*lusJgrsM}xsNXfpbkHaEhit7 zV;rvohQ#kGU_vMP8UsGcW!D|YY^7?zMOPAtwuU3c;lISSIh>Ew;bo%lo_G^F&Xi@n##~)=wVJH`4;H* zk)`@nA>aRZaQnxVASR}B=jD!yGP za6pZgK_;y_1?bf$6GbXdQxuW!bZArkIgqhEYYW+oE5N8fUMXC=0g^sh-97J%(AA6H zO=Qz9kUnknVC45;v@&n~eq<&Od_PQ|{dm_d$W~=OaPu(+L9F$NPPa(ZR=Y626XIQHO&)Evg;wnxGJ`UY z2lrAQ83^mKTIu69*MFLkFR<*eYAC(?PJ>s4fzF`50u) z>Yb@6ISE0_0bAMhb{L>WA#`0s7W%C4&UMJlL7Tnx9UnIZU{@vPh%Gi*!?($`^xHUc*&mQw4XM_Nqb z;BzZ@mck^=vY`xmJy6@rwtWt23uW4?&;$(=zA4M`=wUYe zb>-2odod5c%69@!S+FxJPZJ-uTVr1Nk$g`pt1+EJ_h^*pxS$8!Jt><+M|kAvc+8n9 zCCqkyPP~FD4l}&C**c|pGiJIXYTFvijd@B;NXT(q#q5T>v}YI!V9+Bst`?J9n0V`v zEs6AT`0wq>rq+^COsG-F_vlCirv0ihUP?j}^4P2;vrfw6IiQi?__NO-tZ`21NH2r? zOu~=66$*pGycz+XpSz$Qmss)5>x=M^n3$1w+fhtd=&AG>mnF>LTX`UJa~-B^Fe2Xf zb}RZ`!&Bm&8G`M&(n?`wF%Lnj$s@O`5XWE1;J`Ui=(BoQ@LOX6v=Qtx`<^X{St;vn zJHqdbxnlg!#Y`?cq0zAr>D!&1Z2OZSiA z_-9;#{4&rZeewHj>JU6j-c@e*MiF`?yt*=}t^u|8t-g&UamUQbv~QO#h(Y&D>2GRU zUqZv1kNvh8QsDT1-9bE?f_Vh&{NkpPhT|{w)!VxV^U9<8cKyydOvh+^i8-eYdQf$T zzVZ@)M=n2}cJz_MY@4sJ?zzf_879p;m43^@OlR&-&L%Kpp8Mi12Jqa*?8fiirWfjj zK^YXF;n}ZT&M#xJ^VWa11^YMfxqtcl%pc|cIPC?zXtAerR4$v7}Dvf68My&kK7GDF>2HIB4P3+zHc=0fPupGwuMnU zko->Tw24U(dGrO!(ogCFcjk$ZVYL{ft*d0gU6O@d%N&CBs5J4g=Z{e7pCYF}Nml=L zAr3)$3ck*HRqYEL249W2$N9fgfeDh1chxT*fJqv9rHAB4!DJoL=AAvpU~=_i3*CV+ zu;IB(ke(tQm4#*MbQi>;_LScwsSWM)eCWkQL5^63JT3|`eMV$%X}9yA?zSCS0TT zS0i{X6QrkrIr`>|dCprvd#*i#E&i(Fnt4)vB(+D$XQFGP@N zR4^~WbD1DL1vx29+8+Nf|d zxj2~#p34O3DPpO9^*+0n1u-NUJxH{zLkw&?Q%HsE5d&W`JN|=<7)pbdK6K)Ka*A5L z(r0SWhUYRtdI|>7?81ZEBrxz*v0G?$4)lMLgSna-pl?Ic+H278^62-6pc|yc@8XvP z8=lJq=_$&)`$p< za{<9~nIJvQW?j2nJR1j6MzYWDGM++l_gS*5deYI09Nu7TPcF*wDhc?+#EBAO9JzA0 zk^S^sCP+`KH>9xDv6prDCO?A;mg$F$lnG$)gGc+$iRWPI-r7UG$`mj&WSD!R&I}I~ zQ!{nit`elD7}4A76tX(IFcRuryqXHJ7-?VA3cHaowy8-;ma0w?BdssfpQyNvd)ad5 zY+8GZHawRJ(o;xso4=>2!UB@Ed}_~pYYEBHbppu8#vpn07x9|wOpxrZWqrDQ0VLsG zNqL@=3N}2K3DQ%vNRj9jPrQoeyi^py5*?a}>i`}yc+2wRcos&3W-H$Ns_J2AiP~Sd z)wBa`crFv9rywt9%;&ZjHOM`E?BUH+CXn&!J=kKt4Fx*|Nk6n?Mmd{YX0{lpqWnlQ zUxDwjh~T-rAw5OeifSi)`Q=c`xbv8wS|5nZN)y$-i2EMBI>;6!)B#qr;k*l^k($A5s^(7gl4-)MIJ`(_+}EX6O92gjd2QZvO1$Ny4Z zWx!d2^c0dr)Wn`zeT?H@-)tpfxf{oS^h4-gRvdql z2PT3c1nDVS+$?5Spn>D>LsvDs_avIR*A;Wy$QjMBDy@dG<01cBHNQ(rfoN$9TG7Ap z7!f>|{e2H>6^&l|DWz5l-Ny zKTEe+u@Sg9l)b6me1IT5#W+>eiih88gTX;+t~|~bbLDU@a9r)i3v{jx*ad2G2Zx{fm16l_dipEH@+-yizcIyvKehd$tAEke|5m!1 z+R4@Z?3s1LWc=es^cMzYozSASvp?>1`Zrg#-$<3;&iPZUuztorGbQVX{t`g_K|QTU zAb%pt|MR(j1Y7Ip{ulH7cjMNN{pmf{!8eCdC`y#MYJ)~EdoYU_LcdE)g$ Pf4P@G?(^^0Cr - + @@ -800,7 +800,7 @@ - + From 6fc0c8662d2aeb4c5bdf266a154e85528da67ece Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Feb 2023 12:55:32 -0500 Subject: [PATCH 363/758] adjusting controllers to quickly test jumping experiments --- .../plot_five_link_biped.py | 35 ++++++++++--------- .../plot_configs/cassie_running_plot.yaml | 6 ++-- .../visualize_configs/box_jump.yaml | 4 +-- .../visualize_configs/down_jump.yaml | 4 +-- .../lcm/visualization/visualize_trajectory.py | 4 +-- examples/Cassie/cassie_xbox_remote.py | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 5 ++- .../Cassie/osc_jump/osc_jumping_gains.yaml | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- examples/Cassie/run_dircon_jumping.cc | 10 +++--- .../Cassie/run_osc_standing_controller.cc | 2 +- .../gait_parameters/dircon_box_jump.yaml | 16 ++++----- 12 files changed, 49 insertions(+), 43 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index dced17a5e4..075dee7df1 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -91,7 +91,7 @@ def main(): nc = 2 n_samples = 1000 window_length = 0.05 - tau = 0.0025 + tau = 0.002 selected_joint_idxs = slice(6,7) # selected_joint_idxs = slice(0, 7) @@ -160,6 +160,8 @@ def main(): end_idx - start_idx) print(start_idx) print(end_idx) + # t_proj = np.array( + # [t_impact[0] - 1.5*window_length, t_impact[0] + 1.5*window_length]) t_proj = np.array( [t_impact[0] - window_length, t_impact[0] + window_length]) @@ -191,13 +193,14 @@ def main(): world) TV_J = M_inv @ J_r.T TV_J_space = null_space(TV_J.T).T - - if (t[i] < transition_time): - alpha = blend_sigmoid(t[i] - transition_time, tau, - 0.5 * window_length) - else: - alpha = blend_sigmoid(transition_time - t[i], tau, - 0.5 * window_length) + alpha = 0 + if (np.abs(t[i] - transition_time) < 1.5 * window_length): + if (t[i] < transition_time): + alpha = blend_sigmoid(t[i] - transition_time, tau, + window_length) + else: + alpha = blend_sigmoid(transition_time - t[i], tau, + window_length) alphas[i] = alpha vel_time_varying_proj[i] = TV_J_space.T @ TV_J_space @ vel[i] # vel_correction[i] = transform @ (J_r @ (vel[i] - vel_actual[i])) @@ -215,7 +218,7 @@ def main(): xlabel='time (s)', ylabel='velocity (m/s)', grid=False) gen_vel_plot.add_legend(['Desired Velocity', 'Measured Velocity', 'Velocity Error']) ylim = gen_vel_plot.fig.gca().get_ylim() - gen_vel_plot.save_fig('gen_vel_plot.png') + # gen_vel_plot.save_fig('gen_vel_plot.png') # ps.save_fig('generalized_velocities_around_impact.png') proj_vel_plot = plot_styler.PlotStyler() @@ -225,14 +228,14 @@ def main(): proj_vel_plot.plot(t, vel_proj_actual, title='Constant Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - proj_vel_plot.save_fig('proj_vel_plot.png') + # proj_vel_plot.save_fig('proj_vel_plot.png') corrected_vel_plot = plot_styler.PlotStyler() corrected_vel_plot.plot(t, vel_corrected, title='Impact-Invariant Correction', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) - corrected_vel_plot.save_fig('corrected_vel_plot.png') + # corrected_vel_plot.save_fig('corrected_vel_plot.png') blended_vel_plot = plot_styler.PlotStyler() ax = blended_vel_plot.fig.axes[0] @@ -244,7 +247,7 @@ def main(): xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=blended_vel_plot.grey, alpha=0.2) - blended_vel_plot.save_fig('blended_vel_plot.png') + # blended_vel_plot.save_fig('blended_vel_plot.png') @@ -262,7 +265,7 @@ def main(): # ax.spines['bottom'].set_visible(False) # ax.spines['left'].set_visible(False) ylim = gen_vel_error.fig.gca().get_ylim() - gen_vel_error.save_fig('gen_vel_error.png') + # gen_vel_error.save_fig('gen_vel_error.png') projected_vel_error = plot_styler.PlotStyler() ax = projected_vel_error.fig.axes[0] @@ -271,7 +274,7 @@ def main(): xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=projected_vel_error.grey, alpha=0.2) - projected_vel_error.save_fig('projected_vel_error.png') + # projected_vel_error.save_fig('projected_vel_error.png') corrected_vel_error = plot_styler.PlotStyler() ax = corrected_vel_error.fig.axes[0] @@ -280,14 +283,14 @@ def main(): xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=corrected_vel_error.grey, alpha=0.2) - corrected_vel_error.save_fig('corrected_vel_error.png') + # corrected_vel_error.save_fig('corrected_vel_error.png') blending_function_plot = plot_styler.PlotStyler() ax = blending_function_plot.fig.axes[0] blending_function_plot.plot(t, alphas, title="Blending Function") ax.fill_between(t_proj, ax.get_ylim()[0], ax.get_ylim()[1], color=blending_function_plot.grey, alpha=0.2) - blending_function_plot.save_fig('blending_function_plot.png') + # blending_function_plot.save_fig('blending_function_plot.png') plt.show() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 1df9bd7f71..fca2060ccd 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -47,11 +47,11 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, - pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, +# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_ft_traj: { 'dims': [0, 1, 2], 'derivs': [ 'pos' ] }, + right_ft_traj: { 'dims': [2], 'derivs': [ 'vel' ] }, # left_ft_traj: { 'dims': [0, 2 ], 'derivs': [ 'pos'] }, # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml index b4b6ff44f0..fb3db70055 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml @@ -1,8 +1,8 @@ filename: examples/Cassie/saved_trajectories/box_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 2 +visualize_mode: 1 realtime_rate: 0.5 num_poses: 8 use_transparency: 1 -use_springs: 1 \ No newline at end of file +use_springs: 1ss \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml index ef4f818b27..6fc6fd254a 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml @@ -1,8 +1,8 @@ filename: examples/Cassie/saved_trajectories/down_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 2 -realtime_rate: 0.5 +visualize_mode: 1 +realtime_rate: 1.0 num_poses: 9 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 4bfb919509..9c72aba548 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -18,8 +18,8 @@ def main(): # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' - visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' - # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' params = DirconVisualizationParams(visualization_config_file) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 08873ed82b..3a71ba94a3 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -67,7 +67,7 @@ def main(): done = False max_speed = 1.0 - ramp_up = np.arange(0, max_speed, 0.02) + ramp_up = np.arange(0, max_speed, 0.05) stay = max_speed * np.ones(125) ramp_down = np.flip(np.arange(0, max_speed, 0.02)) speeds = np.hstack((ramp_up, stay, ramp_down)) diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 45703f61a8..cd928239f3 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -73,7 +73,7 @@ DEFINE_bool(spring_model, true, "Use a URDF with or without legs springs"); DEFINE_bool(visualize, true, "Set to true to visualize the platform"); DEFINE_double(actuator_delay, 0.0, "Duration of actuator delay. Set to 0.0 by default."); -DEFINE_bool(use_traj_state, false, +DEFINE_bool(use_traj_state, true, "Whether to intialize the sim from a specific state"); DEFINE_string(contact_solver, "SAP", "Contact solver to use. Either TAMSI or SAP."); @@ -211,6 +211,9 @@ int do_main(int argc, char* argv[]) { Eigen::VectorXd x_traj_init = state_traj.value(FLAGS_start_time); if (FLAGS_use_traj_state){ + if(FLAGS_platform_x < 0){ + x_traj_init(6) += FLAGS_platform_height; + } plant.SetPositionsAndVelocities(&plant_context, x_traj_init); }else{ Eigen::VectorXd q_init, u_init, lambda_init; diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 952a70f79f..12865efc2b 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -31,7 +31,7 @@ hip_yaw_kd: 5 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.1 +landing_delay: 0.0 CoMW: [20, 0, 0, diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 5117da6058..e9e0184c62 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -28,7 +28,7 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true -no_derivative_feedback: true +no_derivative_feedback: false rot_filter_tau: 0.005 ekf_filter_tau: [ 0.05, 0.01, 0.001 ] diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 6916ae6eb3..7166e660c7 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -142,7 +142,7 @@ struct DirconJumpingParameters { double constr_viol_tol; double compl_inf_tol; double acceptable_tol; - double acceptable_iter; + int acceptable_iter; double cost_scaling; bool use_ipopt; int ipopt_iter; @@ -690,13 +690,13 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_x_box_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.3 * (gait_params.distance - eps) * VectorXd::Ones(1), - 0.3 * (gait_params.distance + eps) * VectorXd::Ones(1)); + 0.2 * (gait_params.distance - eps) * VectorXd::Ones(1), + 0.2 * (gait_params.distance + eps) * VectorXd::Ones(1)); auto right_foot_x_box_constraint = std::make_shared>( plant, "toe_right", pt_front_contact, Eigen::RowVector3d(1, 0, 0), - 0.3 * (gait_params.distance - eps) * VectorXd::Ones(1), - 0.3 * (gait_params.distance + eps) * VectorXd::Ones(1)); + 0.2 * (gait_params.distance - eps) * VectorXd::Ones(1), + 0.2 * (gait_params.distance + eps) * VectorXd::Ones(1)); prog->AddConstraint(left_foot_x_box_constraint, x_top.head(n_q)); prog->AddConstraint(right_foot_x_box_constraint, x_top.head(n_q)); auto left_foot_z_box_constraint = diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 14fa4c601f..99a4a5bab6 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -54,7 +54,7 @@ using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", +DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", "LCM channel for receiving state. " "Use CASSIE_STATE_SIMULATION to get state from simulator, and " "use CASSIE_STATE_DISPATCHER to get state from state estimator"); diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml index 70a3815953..d8a5b9a758 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml @@ -1,16 +1,16 @@ spring_urdf: examples/Cassie/urdf/cassie_v2.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf -knot_points: 8 +knot_points: 10 delta_height: 0.5 start_height: 0.8 distance: 0.3 min_stance_duration: 0.2 -max_stance_duration: 1.0 +max_stance_duration: 1.5 min_flight_duration: 0.1 max_flight_duration: 1.0 -actuator_limit: 1.0 -input_delta: 75 +actuator_limit: 0.85 +input_delta: 60 snopt_scale_option: 0 tol: 1e-4 @@ -20,13 +20,13 @@ compl_inf_tol: 1e-4 acceptable_tol: 1e-3 acceptable_iter: 10 cost_scaling: 1e-3 -use_ipopt: false +use_ipopt: true ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ -load_filename: box_jump -save_filename: box_jump +load_filename: box_jump_4 +save_filename: box_jump_5 use_springs: false convert_to_springs: false -same_knotpoints: true +same_knotpoints: false From 8dd1a198e6b55ee84151b18c82caea67c78a0cf9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Feb 2023 13:36:31 -0500 Subject: [PATCH 364/758] removing offsets --- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 12865efc2b..be0e1a1898 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -16,7 +16,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -x_offset: 0.04 +x_offset: 0.00 relative_feet: true mu: 0.6 From 87b1f776225b3e313e4ac8fca99817d23e2feb9c Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Feb 2023 16:15:54 -0500 Subject: [PATCH 365/758] comparing running controllers --- .../pydairlib/analysis/mbp_plotting_utils.py | 8 +++-- bindings/pydairlib/analysis/osc_debug.py | 4 +-- .../plot_configs/cassie_running_plot.yaml | 24 ++++++------- examples/Cassie/cassie_xbox_remote.py | 4 +-- examples/Cassie/osc/osc_walking_gains.yaml | 1 + .../Cassie/osc/osc_walking_gains_alip.yaml | 2 ++ .../Cassie/osc_run/foot_traj_generator.cc | 35 ++++++++++--------- .../Cassie/osc_run/osc_running_gains.yaml | 2 +- 8 files changed, 45 insertions(+), 35 deletions(-) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 9f5bde15e3..c0612ceaf0 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -161,7 +161,7 @@ def process_osc_channel(data): for tracking_data in msg.tracking_data: if tracking_data.name not in osc_debug_tracking_datas: osc_debug_tracking_datas[tracking_data.name] = \ - lcmt_osc_tracking_data_t() + lcmt_osc_tracking_data_t(name=tracking_data.name) osc_debug_tracking_datas[tracking_data.name].append( tracking_data, msg.utime / 1e6) @@ -419,7 +419,7 @@ def plot_floating_base_body_frame_velocities(robot_output, time_slice, plant, data_dict = {'t': robot_output['t_x']} data_dict['base_vel'] = get_floating_base_velocity_in_body_frame( robot_output, plant, context, - plant.GetBodyByName(fb_frame_name).body_frame()) + plant.GetBodyByName(fb_frame_name).body_frame())[:, 0] legend_entries = {'base_vel': ['forward', 'lateral', 'vertical']} ps = plot_styler.PlotStyler() plotting_utils.make_plot( @@ -492,6 +492,9 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['y_des'] = tracking_data.y_des[:, dim] data['y'] = tracking_data.y[:, dim] data['error_y'] = tracking_data.error_y[:, dim] + print(tracking_data.name + str(dim)) + # print('mean error: ' + str(np.nanmean(np.sqrt(tracking_data.error_y[:, :].flatten()**2)))) + print('mean error: ' + str(np.nanmax(np.sqrt(tracking_data.error_y[:, dim].flatten()**2)))) elif deriv == 'vel': data['ydot_des'] = tracking_data.ydot_des[:, dim] data['ydot'] = tracking_data.ydot[:, dim] @@ -503,6 +506,7 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['yddot_command_sol'] = tracking_data.yddot_command_sol[:, dim] data['t'] = tracking_data.t + return plot_general_osc_tracking_data(traj, deriv, dim, data, time_slice) def plot_osc_tracking_data_in_space(osc_debug, traj, dims, deriv, time_slice): diff --git a/bindings/pydairlib/analysis/osc_debug.py b/bindings/pydairlib/analysis/osc_debug.py index 59d874f384..5ba8d2741a 100644 --- a/bindings/pydairlib/analysis/osc_debug.py +++ b/bindings/pydairlib/analysis/osc_debug.py @@ -4,11 +4,11 @@ # Class to easily convert list of lcmt_osc_tracking_data_t to numpy arrays class lcmt_osc_tracking_data_t: - def __init__(self, gap_threshold=0.01): + def __init__(self, gap_threshold=0.01, name=''): self.t_thresh = gap_threshold self.t = [] self.y_dim = 0 - self.name = "" + self.name = name self.is_active = [] self.y = [] self.y_des = [] diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index fca2060ccd..5e8ea5797a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,15 +1,15 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_DISPATCHER" -#channel_x: "CASSIE_STATE_SIMULATION" +#channel_x: "CASSIE_STATE_DISPATCHER" +channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false use_default_styling: false # Log time to stop at (seconds, -1 for whole log) -start_time: 4 +start_time: 6 #duration: 0.47 -duration: 5.1 +duration: 10 # Plant properties use_springs: true @@ -47,12 +47,12 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, -# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'vel'] }, -# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, - # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'accel' ] }, - right_ft_traj: { 'dims': [2], 'derivs': [ 'vel' ] }, -# left_ft_traj: { 'dims': [0, 2 ], 'derivs': [ 'pos'] }, - # left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, - # right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos', 'vel', 'accel' ] }, + pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos'] }, + pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, + hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, + right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos'] }, + right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos'] }, } \ No newline at end of file diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 3a71ba94a3..3bf97318d2 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -67,9 +67,9 @@ def main(): done = False max_speed = 1.0 - ramp_up = np.arange(0, max_speed, 0.05) + ramp_up = np.arange(0, max_speed, 0.01) stay = max_speed * np.ones(125) - ramp_down = np.flip(np.arange(0, max_speed, 0.02)) + ramp_down = np.flip(np.arange(0, max_speed, 0.01)) speeds = np.hstack((ramp_up, stay, ramp_down)) i = 0 while not done: diff --git a/examples/Cassie/osc/osc_walking_gains.yaml b/examples/Cassie/osc/osc_walking_gains.yaml index 49a2d568ff..ee2ad81118 100644 --- a/examples/Cassie/osc/osc_walking_gains.yaml +++ b/examples/Cassie/osc/osc_walking_gains.yaml @@ -1,3 +1,4 @@ +controller_frequency: 1000 rows: 3 cols: 3 diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index d4f97a0f39..3e0da9b29e 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -1,3 +1,5 @@ +controller_frequency: 1000 + # OSC gains w_input: 0.0000 w_input_reg: 0.000001 diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 4ae7051e31..020e1926e6 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -155,8 +155,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( const auto& mode_lengths = this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); -// double pelvis_t0 = mode_lengths[0]; -// double pelvis_tf = mode_lengths[1]; + double pelvis_t0 = mode_lengths[0]; + double pelvis_tf = mode_lengths[1]; double left_t0 = mode_lengths[2]; double left_tf = mode_lengths[3]; double right_t0 = mode_lengths[4]; @@ -201,6 +201,23 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( VectorXd pelvis_vel = v.segment(3, 3); VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; + + std::vector T_waypoints; + + double x_mid_point_ratio = 0.8; + double t_mid_point_ratio = 0.6; + + if (is_left_foot_) { + T_waypoints = {left_t0, left_t0 + t_mid_point_ratio * (left_tf - left_t0), + left_tf}; + } else { + T_waypoints = {right_t0, + right_t0 + t_mid_point_ratio * (right_tf - right_t0), + right_tf}; + } + + // TODO(yangwill): Footsteps are planned with constant stance duration T_s of + // 0.3s VectorXd foot_end_pos_des = 0.5 * (0.3) * rot.transpose() * pelvis_vel + Kd_ * (pelvis_vel_err); @@ -212,20 +229,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( foot_end_pos_des(0) += sagital_radio_tuning * sagital_offset_; foot_end_pos_des(2) = -rest_length_ - rest_length_offset_; - std::vector T_waypoints; - std::vector T_waypoints_0; - std::vector T_waypoints_1; - std::vector T_waypoints_2; - - double x_mid_point_ratio = 0.8; - double t_mid_point_ratio = 0.6; - - if (is_left_foot_) { - T_waypoints = {left_t0, left_t0 + t_mid_point_ratio * (left_tf - left_t0), left_tf}; - } else { - T_waypoints = {right_t0, right_t0 + t_mid_point_ratio * (right_tf - right_t0), right_tf}; - } - auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); VectorXd start_pos = foot_pos - hip_pos; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index e9e0184c62..4f703b77dc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -9,7 +9,7 @@ w_lambda: 0.1 w_input_accel: 0.1 w_joint_limit: 0 impact_threshold: 0.050 -impact_tau: 0.002 +impact_tau: 0.005 weight_scaling: 1.0 mu: 0.6 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe From 27c31756786be55f1ca304a06b0dc6f07ed9ecff Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Feb 2023 13:27:07 -0500 Subject: [PATCH 366/758] small changes --- .../pydairlib/analysis/log_plotter_cassie.py | 13 ++- .../pydairlib/analysis/mbp_plotting_utils.py | 3 - .../plot_configs/cassie_jumping_plot.yaml | 9 +- .../plot_configs/cassie_running_plot.yaml | 22 ++-- .../cassie/gym_envs/drake_cassie_gym.py | 1 + .../Cassie/osc_jump/osc_jumping_gains.yaml | 8 +- .../Cassie/osc_run/osc_running_gains.yaml | 8 +- examples/Cassie/run_dircon_jumping.cc | 100 +++++++++--------- examples/Cassie/run_osc_jumping_controller.cc | 19 ++-- examples/Cassie/run_osc_running_controller.cc | 10 +- examples/Cassie/saved_trajectories/down_jump | Bin 52477 -> 52477 bytes .../gait_parameters/dircon_down_jump.yaml | 6 +- .../osc/operational_space_control.cc | 2 +- 13 files changed, 106 insertions(+), 95 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 09cde855ef..21fcb12447 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -11,11 +11,11 @@ def main(): - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base @@ -94,8 +94,9 @@ def main(): if plot_config.plot_floating_base_velocity_body_frame: plot = mbp_plots.plot_floating_base_body_frame_velocities( robot_output, t_x_slice, plant, context, "pelvis") - # plot.tight_layout() - # plot.save_fig('running_speed_plot.png') + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.tight_layout() + # plot.save_fig('running_speed_plot_kd0.png') # Plot all joint velocities if plot_config.plot_joint_velocities: @@ -149,6 +150,10 @@ def main(): deriv, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) # plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') + tracking_data = osc_debug['osc_debug_tracking_datas'][traj_name] + # print(tracking_data.name + str(dim)) + # print('mean error: ' + str(np.nanmax(np.sqrt(tracking_data.error_y[:, dim].flatten()**2)))) + # print('mean error at end of tracking: ' + str(np.mean(np.sqrt(tracking_data.error_y[:, dim][np.append(np.isnan(tracking_data.error_y[:, dim][1:]), False)]**2)))) # plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) # plot.save_fig('swing_foot_target_trajectory.png') diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index c0612ceaf0..ca745d0bcf 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -492,9 +492,6 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['y_des'] = tracking_data.y_des[:, dim] data['y'] = tracking_data.y[:, dim] data['error_y'] = tracking_data.error_y[:, dim] - print(tracking_data.name + str(dim)) - # print('mean error: ' + str(np.nanmean(np.sqrt(tracking_data.error_y[:, :].flatten()**2)))) - print('mean error: ' + str(np.nanmax(np.sqrt(tracking_data.error_y[:, dim].flatten()**2)))) elif deriv == 'vel': data['ydot_des'] = tracking_data.ydot_des[:, dim] data['ydot'] = tracking_data.ydot[:, dim] diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 2ab084bfb5..1895e04c43 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -4,9 +4,10 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_JUMPING" channel_osc: "OSC_DEBUG_JUMPING" use_archived_lcmtypes: false +use_default_styling: false # Log time to stop at (seconds, -1 for whole log) -start_time: 20 +start_time: 7 duration: 5 # Plant properties @@ -34,12 +35,12 @@ foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] foot_xyz_to_plot: { 'right': [2], 'left': [2] } #foot_xyz_to_plot: { } -pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' +pt_on_foot_to_plot: 'front' # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_qp_solve_time: false -plot_qp_solutions: false +plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { @@ -47,7 +48,7 @@ tracking_datas_to_plot: { # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, - left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']}, +# left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']}, # right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 5e8ea5797a..e6b392a168 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -1,6 +1,6 @@ # LCM channels to read data from -#channel_x: "CASSIE_STATE_DISPATCHER" -channel_x: "CASSIE_STATE_SIMULATION" +channel_x: "CASSIE_STATE_DISPATCHER" +#channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false @@ -9,7 +9,7 @@ use_default_styling: false # Log time to stop at (seconds, -1 for whole log) start_time: 6 #duration: 0.47 -duration: 10 +duration: 5 # Plant properties use_springs: true @@ -47,12 +47,12 @@ plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, - pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos'] }, - pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, - hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, - hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, - right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, - left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, - left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos'] }, - right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos'] }, +# pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos'] }, +# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, +# hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, +# right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# left_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, +# left_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos'] }, +# right_toe_angle_traj: { 'dims': [ 0 ], 'derivs': [ 'pos'] }, } \ No newline at end of file diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index 0b7167ac5c..b06c20a9ee 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -100,6 +100,7 @@ def step(self, action=np.zeros(18)): self.plant.GetMyMutableContextFromRoot( self.sim.get_context())) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp + print(u) self.cassie_state = CassieEnvState(self.current_time, x, u, action) reward = self.reward_func.compute_reward(self.sim_dt, self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index be0e1a1898..0dc4d5f7da 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -8,10 +8,12 @@ W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, 0.5, 0.9, 0.5, 0.1, 0.1] +# left toe, left heel, right toe, right heel: x y z W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] +# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 @@ -31,14 +33,14 @@ hip_yaw_kd: 5 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.0 +landing_delay: 0.03 CoMW: [20, 0, 0, 0, 2, 0, 0, 0, 20] CoMKp: - [30, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 50] CoMKd: @@ -62,7 +64,7 @@ FlightFootW: 0, 100, 0, 0, 0, 10] FlightFootKp: - [125, 0, 0, + [150, 0, 0, 0, 50, 0, 0, 0, 100] FlightFootKd: diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4f703b77dc..35bf976ce8 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -18,10 +18,10 @@ W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001 ] W_input_reg: [ 1, 0.9, 0.5, 0.1, 1, 1, 0.9, 0.5, 0.1, 1 ] -W_lambda_c_reg: [ 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.001, 0.01 ] +W_lambda_c_reg: [ 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] #w_soft_constraint: 1000000 diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 7166e660c7..f60a155a32 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -499,7 +499,7 @@ void SetKinematicConstraints(Dircon* trajopt, double midpoint = 0.045; -// bounding box constraints on all decision variables + // bounding box constraints on all decision variables for (int i = 0; i < mode_lengths.size(); ++i) { for (int j = 0; j < mode_lengths[i]; ++i) { // auto state_vars_ij = trajopt->state_vars(i, j); @@ -533,9 +533,10 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_left"))); prog->AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("hip_yaw_right"))); -// prog->AddBoundingBoxConstraint(0.00, 0.1, x_0(pos_map.at("hip_roll_left"))); -// prog->AddBoundingBoxConstraint(-0.1, -0.00, -// x_0(pos_map.at("hip_roll_right"))); + // prog->AddBoundingBoxConstraint(0.00, 0.1, + // x_0(pos_map.at("hip_roll_left"))); prog->AddBoundingBoxConstraint(-0.1, + // -0.00, + // x_0(pos_map.at("hip_roll_right"))); // hip yaw and roll constraints prog->AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("hip_yaw_left"))); @@ -546,15 +547,16 @@ void SetKinematicConstraints(Dircon* trajopt, // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_left"))); // prog->AddBoundingBoxConstraint(-2.2, -1.6, x_f(pos_map.at("toe_right"))); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) >= -2.1); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) >= -2.1); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) <= -1.1); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) <= -1.1); -// -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) >= -2.2); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) >= -2.2); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) <= -1.6); -// trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) <= -1.6); + // trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) >= -2.1); + // trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) >= + // -2.1); trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_left")) <= + // -1.1); trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("knee_right")) + // <= -1.1); + // + // trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) >= -2.2); + // trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) >= -2.2); + // trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_left")) <= -1.6); + // trajopt->AddConstraintToAllKnotPoints(x(pos_map.at("toe_right")) <= -1.6); // Jumping height constraints prog->AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, @@ -615,7 +617,6 @@ void SetKinematicConstraints(Dircon* trajopt, } l_r_pairs.pop_back(); - // joint limits std::cout << "Joint limit constraints: " << std::endl; for (const auto& member : joint_names) { @@ -767,20 +768,20 @@ void SetKinematicConstraints(Dircon* trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - // for (int index = 0; index < (mode_lengths[0] - 2); index++) { - // auto lambda = trajopt->force_vars(0, index); - // prog->AddLinearConstraint(lambda(2) >= 60); - // prog->AddLinearConstraint(lambda(5) >= 60); - // prog->AddLinearConstraint(lambda(8) >= 60); - // prog->AddLinearConstraint(lambda(11) >= 60); - // } + for (int index = 0; index < (mode_lengths[0] - 2); index++) { + auto lambda = trajopt->force_vars(0, index); + prog->AddLinearConstraint(lambda(2) >= 60); + prog->AddLinearConstraint(lambda(5) >= 60); + prog->AddLinearConstraint(lambda(8) >= 60); + prog->AddLinearConstraint(lambda(11) >= 60); + } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); - prog->AddLinearConstraint(lambda(2) <= 350); - prog->AddLinearConstraint(lambda(5) <= 350); - prog->AddLinearConstraint(lambda(8) <= 350); - prog->AddLinearConstraint(lambda(11) <= 350); + prog->AddLinearConstraint(lambda(2) <= 300); + prog->AddLinearConstraint(lambda(5) <= 300); + prog->AddLinearConstraint(lambda(8) <= 300); + prog->AddLinearConstraint(lambda(11) <= 300); prog->AddLinearConstraint(lambda(2) >= 50); prog->AddLinearConstraint(lambda(5) >= 50); prog->AddLinearConstraint(lambda(8) >= 50); @@ -914,30 +915,31 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, Q_right * (x.segment(13, 3) - q_f_target_right)); trajopt->AddRunningCost(u.transpose() * R * u); -// vector mode_lengths = {gait_params.knot_points, gait_params.knot_points, -// gait_params.knot_points}; -// MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); -// W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 1e2; -// W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 1e2; -// W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; -// W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; -// W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; -// W(vel_map["hip_yaw_rightdot"], vel_map["hip_yaw_rightdot"]) *= 1e2; -// W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; -// W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; -// W *= 2.0 * gait_params.cost_scaling; -// vector> joint_accel_costs; -// for (int mode : {0, 1, 2}) { -// joint_accel_costs.push_back(std::make_shared( -// W, plant, &constraints->mode(mode).evaluators())); -// for (int index = 0; index < mode_lengths[mode]; index++) { -// // Assumes mode_lengths are the same across modes -// auto x_i = trajopt->state_vars(mode, index); -// auto u_i = trajopt->input_vars(mode, index); -// auto l_i = trajopt->force_vars(mode, index); -// trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); -// } -// } + // vector mode_lengths = {gait_params.knot_points, + // gait_params.knot_points, + // gait_params.knot_points}; + // MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); + // W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 1e2; + // W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 1e2; + // W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; + // W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; + // W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; + // W(vel_map["hip_yaw_rightdot"], vel_map["hip_yaw_rightdot"]) *= 1e2; + // W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; + // W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; + // W *= 2.0 * gait_params.cost_scaling; + // vector> joint_accel_costs; + // for (int mode : {0, 1, 2}) { + // joint_accel_costs.push_back(std::make_shared( + // W, plant, &constraints->mode(mode).evaluators())); + // for (int index = 0; index < mode_lengths[mode]; index++) { + // // Assumes mode_lengths are the same across modes + // auto x_i = trajopt->state_vars(mode, index); + // auto u_i = trajopt->input_vars(mode, index); + // auto l_i = trajopt->force_vars(mode, index); + // trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); + // } + // } } void SetInitialGuessFromDirconTrajectory(Dircon& trajopt, diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 56bb0eb975..d2ec364534 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -298,15 +298,14 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - - // Soft constraint on contacts - osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); - - // Soft constraint on contacts osc->SetInputSmoothingCostWeights(1e-3 * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight( + gains.w_lambda * gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); + // Soft constraint on contacts + osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); // Contact information for OSC osc->SetContactFriction(gains.mu); @@ -332,11 +331,8 @@ int DoMain(int argc, char* argv[]) { osc->AddStateAndContactPoint(mode, &right_heel_evaluator); } + multibody::KinematicEvaluatorSet evaluators(plant_w_spr); - auto left_loop = LeftLoopClosureEvaluator(plant_w_spr); - auto right_loop = RightLoopClosureEvaluator(plant_w_spr); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); // Fix the springs in the dynamics auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_spr); @@ -358,6 +354,11 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); + auto left_loop = LeftLoopClosureEvaluator(plant_w_spr); + auto right_loop = RightLoopClosureEvaluator(plant_w_spr); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c9504a95d1..1df52fa2ad 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -242,10 +242,7 @@ int DoMain(int argc, char* argv[]) { &right_heel_evaluator); multibody::KinematicEvaluatorSet evaluators(plant); - auto left_loop = LeftLoopClosureEvaluator(plant); - auto right_loop = RightLoopClosureEvaluator(plant); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); + // Fix the springs in the dynamics auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); @@ -266,6 +263,11 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); + + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, // &left_fixed_knee_spring); // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, diff --git a/examples/Cassie/saved_trajectories/down_jump b/examples/Cassie/saved_trajectories/down_jump index 670b25fb3eb7111fa7e6225614d0931da15c86dd..80f06ae0f78b65d258a2b4a58599e506bf69bae1 100644 GIT binary patch literal 52477 zcmeF)2{hH;|1W;C$UF}vGtofi!rqaoOwAEx425J&6BSJ&Gzb+%$Pf*NGVEPRQA#p5 zn1@oKlp(`CarUWiYyH-5t$Y9fb=SSO*7|(jXYccRAKN=;d$XTCw(W^UuVp{eZKbE9 zqZ8ZU9w2G#>Le+tBdMygTtjWShKl4em1Sz|lqc!FVsi+c)@E zx9%!eXAeJ*-QJRcj=mm_PM)rQl8)Xkl79Y<{;o?synO=vC241PP@dee+gFnMQoqhu z($;cP-JzwWxonw+lbWlVs+z01qqFu7XGa|!ZB;FoWooX=cDOp}IL{7(a>m@57o8c# zuNM%a{5SL5uLig|o@u@@=M5;M9-pk3z6T8g!HZw*o6O*~UFPomh!)T|)9(V_h;L-5 z8jS<*+O#GUUOI!eb&&@&*7bw-yHjJA^ryD60LR0gsO~v=35rdW)rzy zW8f$EgC8Av6>t%+beWUXD=6vtKKf$zMljx5=M*o(3H5iy7%uE|hV%1+4843zq1drr zJ?pAc$W{5{XLk7%q#xXM)pKVy_%cbkYz?dD($Q>&rag!aUv!%MaUPj#I_SY%ytA{l*UW(ZRE5qW@NFR9F>O>>^~XZ z7YFz1YYrUeQ~(u5kKI1p8$wT_yl%by#0{QrcYO0^(g%=Lr-K+3^BjikKjQcDx4AnF0^&KlN zf{8uP{1(@TL&dhuX{D+1Q2wek`}&W^AP4u)9V4}`(B~sXL7|+FA${bx&RzK@!E_c+ z&z$vY;G6IKm36mrK*xu}BaisKP^m-zm!!v*nDg-Wq(XaZ$XRrvNVPZvzsFZV&Hi;$0?+-hiTIw(8(lV-x6sk4 z?~(?VliigcDmQ=?iWbe|vyH~mMt$Ix_Zch@@I08^+7L1f`W0)fT8248Kc$tP{0TWf zRE9ToxTC8q!Y3m|&SA#lv|d|-LvVp1N7@^|Rn+lL{2p(KaL|O35VVjQUPb@$JCtPV zdD}lF2aVv?{k3w}p{ZNZd<*q*yj4rYLXXt-h6O8@KLN+@+L zc;sw_F}9A#d%$^Ii`q7VrYB3EeyCQ5OXYgEGsfFNLn*hpTi5=CTV3Y3CViHGD@}Qx zffij_d;7_=)0#t_(BSgT_ivW;Lp_;O6`7OGP_O#Pxzm;Y zl<^8pf$Q%u4_KSO!O0LBNI&R*{PPZ6&ws4bLXIEWD@qlMFls{QOVdMamIH9ZxBYao zof%Lnv58(`zCN}-9X9=D-WF;bK+|YH{mGVOxKyj&mVZt>G!*S#P-It48DBN4bjRh%T&O1v7@t?MK)p)( zNSA1Up8Eu~xIgFuw=%Py#h6>A?{ka`j zBLDNU@98I?V5?tNgFL{Czm`0 z^==ouI7IJ(zDRv)tu*X`Dj|p2e(H}v74g;;ds63Mxz%@5j8a;$Xzi`>qVqd3qeNh| zWV0UnI(5l&gzqyNRgN|4U2TedpLw z^b1(3_@4O^zI?2gFI{aT6ooH)+3T>`2cE?RO$qaUh>-Vp6@zJTSlq=Z&4kHDg( ze!3c%2Q$=99guM7Ltp#%ui)VVXjIlk`{zXy%GD5X_wd>7yW7)qyQk|8|LtD8DR&IN zE|MUv-`B&<{f{U3e?1ZG81z^D%{;PcEb$mSho!$RBLFm`(%s%ngDLlKpU0wgG z=AG&LtB~7&_uq9qzqvuoy?`du5%34e*Z!Wd7d0gRXqH979{Ng z1Jlt00OJA21#i0+Lf4u+lG+t()}r8k!@)5!a?Ddsiok0 zRNgJw>!*-8_iGnr;bcnvc^fac^)E`b5e7qQJNH}CB72JRt zHcw@U@B|_=-w@kko^Etuavj5NnewvUMwx=$UVBj&Y_}E(VnWwknOCmABnF~m{Og^0 z{6WK$4=l-YS!nF)!*_1iy1`hYLSk{2Ch7^vYiwAk1Fp(zMnnc|L6JixE;g&*gNE9j zryVD9(Aae#zWJan7`t+9%tWpW^@Q(VS)5f)xlZ=Wwl%K+93o}+rsXx!$*{{q+n26H zj4T7Ea7R|e8~E3H+8qtV*s9_}%Z?}HCK3O9XJ)>G=& zc7(`EQ|ikU0(C>s)FHNZInz%7R?2ZQ-D?C-u1x4eS63mh@5VKjH>Kd5{;FnM#mh+A z?8t``x3;3eki7>^zFmp()(Kh8FVsN6XU|uD*Lx4XJ@K%NyqtUde@v2 zmS>y64I}Y$+uno%`ABzxNYqBDuk*LNl}@Q|`kE8Ch*H04yX~zBO1;{8X}8;8!)3pq z$8l_+FD+hX%T+pHyYT6Ti>r5nN2}>{-VTo=nd^3ERsi?Xeq{e%fnL z>K4C`k!kzDXrYk%zUZx({`sbT1%0WI{(-(`^uBu3mlDWZeZhKqmxU6z_Vf`? z=>7pPnxDBN=u0%FuZ{!o>0U_x@L)}Vi6-hxI^vge_X-#o#$_Dki-6b#EoQgZ;vn0w z5DbhKg@qc6VEV?4#b20jLdL5n9(OLTL(}hcRn-`eHs<0XYVs6Beo~#GDmjy*4 z<93d(hEZwE&l}fDTS1cN5BB!nCQv~a&(U@*j8f0Jz5UX9G}Np8&Nll87;5qx+f&Cj( z%T(E~Zi@o_QO9|#6dt4gpapqhT_s@nnaFU#gcvFlty9;2x*F8Pm|71Tj#KI%1e9sT zg8sOtM+B?BqyA7E4&~?FV7LmH4@7c`|~zntn1zA z0vS0ryg1?#jwa0;Ze4E?0qM56-)!=-K>XmnoB|K`nR<_#4VZrAs9`XRC#BwO)%Th) zN_|_=e;$HXUuh9w$(>uy)~(RZFn=M;EE>lR@D7gJiLHsZHqn?P|5nCI=wv^)~hk``>{) zg{xWj&00~_p6%wbw_alLe!KP?+bqHN$EWx@0xHq>g1h(J-+4jS^vPFRE+4_bk9E^N z_n47L?)&b`9g!%bEzZJX-9aGC#lO9h^EkjY+fi-SMkMAoIeZBwg09c9M@9up(T&K2 ze(7l*;HM7<$_i3I^Zm=sKQ+uT-C5i3nqQ|O!!{vPc+U}yMP!sNX?_oGe26t-82N$x zyXW4} z#V1plz?A-d!!K>i(9{ygLsPj|Am3q)D~;R5QRZ|MgH^8y>gs!Vs7vz*rGEQ-qiQ8E zWyNuQVcs`1rJp0cX8JYcJJJ=MrYZxzp!|3K$REN=MF@~Q0jxVvmU&n)N6n9os7hExtm)TzgM8#XFagrVzLRdikRq}XGuaj zYG15QISYZ$bVVsYd=!A@-Xl!AOECJNz_uRg?1zl?Vu3|snc%bU*wdKxOpwhgE$ir( zxmdDaU3j11M=06IQp$1T1{QD5yzd{thZ)~{ON~C-k3P#7h8Qb~LAKQs2BKjBSn|_C zp;n=OO8waV>(g>ryoQx`%4-UIRy*=#=-Do`(5v*bVs$cVS@em^Vo(o=?ZNZfwJSi4 zE$`b0+ER%7nbr&2gR4QO#Mu;4jZW~e&-zquUOK?i7xx4in4|NZo90LF*1*ggzwE0> zyaZXr49zxtR6`Tns_#fJq@jnMR|Iy&Z9!NuKMRb8_^QzZ8n<@2e4Z&N^QtCCH z4Ls&V6AmK%96b%lPPt4-_GKUFy4i9hcwr)P>2@2j7-0iL`J>PCvl9{T#_7Si4+7C3 z*x!(+HOjj8B$4 zpu>z8x5}@0)Q{<=yf*JUT?|FGq*S|9zr=ijQ&sQvG$5aWLRCVCG+aK!)_!3BXYfT- z^<@LYS0s0hV`uI1Zd6~42ds3@=zpaPPdOcW8oa(+{LSj;AmV1_91+cz1MQTbTaLgY zKz*Olj?JcTKQH}$0<-9MJ1pI^0nVAd^G7{9b~ttM*pv6!uj7UG@&%yTNI>)moyG=fe7e={jRMtgB6BJ*M-V>=JplN+j27!n7D%O)?UcUU6_G(^-M+_kFoC`<57WdHJE*))`2$0u92!&FSmO717>t&%YeaN&LK$mzb=Jj6 zAm4bQ9D{Hl>Z@8&ojINhmDiuq7VBS$#+IbA3!ZZaqu3~gOJ@m`*Eo1Iq8eBOrkT)#i>9Xp&AOl8nx_Luu>-+w083k)t_-JPi+H+x-u z_5ZBjLHPrGk9oFKJQIhacWt7%;`7jEIBXKsXAi!w&2(*B_W`L~xP2ki!2ykFGK@zt zR-vz{7BR=>K1D5Gk?>^m9H?M=!58QsfXs0LT3=%6F|+pTU881+SYWk(uIr7oQ1(z!pt zqml&$F9mFA_XUjceeX}2szYYS*Jnd3_o8nt`#o=-e2Pll>XbV|hS4MZNFnw_=uCZ; zpd@CDpUy276{pmHG*lLdLEqkP&Xh6t20m<(0amT=AeX@FxvZkxz_r^_%yxqe_*!3k z+<47Wr2eK#-c_{+jl{KoPwuHg1LixKxo$LII-j`=y1W?ESzSsDu5g8md~Uw7)LV-e z8J8B6Z##fBYJaYaEU5d zXs#E%Nx~FMd|L3qp`ixq1{-}B$j8OqC)Aa@uqMT{iRgd;qk)X^=s-& zUL$2ny(8#xE64P<*AAuCe?!(SH#CPXgn^nePfg=J3lPJ@IgZzJQ$RQOY3JUsk6;;! z<~6<%j|SDxZ8PY&3s4^WYXzx&AY@4P2myEV=wEcRlVv zA1j|;4lqwgXiY7{0tF6~{()uAIp_q2qBn=d^{Zi)I~?8C3#TDVPI0gIej)U+V#;&% z;WRKX)f_Ki?+(}&?^b@f4!EBb@PKh!4)6qp8I8TRVCb$=YN`J)nm)s+e@T<_b7bt**yru4nBLB!>U!#8 zbpI;n)@l_UZwr!CsrCxLTU5YfCj%s}yShN;`ux-Mx9fUF1jStJJg5&3Qf{?Ev=z$;{ zn0qJ^O}|;ZPpm@?y_3`QdALp;yc0b!b<&zPtC@^Q!{wu~{ zu+ZMV_3Ioom49)))bk~fUY=X7*eM&+Wq%rEep83;MO0<4dgF_N(wV2+>3J#j{&wQ* zjFfuU&75nDAido8JpG18nC@n%qW$z2q=*%&Wg1_B!QSOUTc24YVU@?NwRdiV27Vb0 z{q-`4J;v1bsZb{9_-NByp(Bn8qtl*kTW}QIyVG@0N#6uj>Gsx{GBSW4x0zl&N;r*v zWV$W+sWc6S`R@sP?)XOe+vV?5^B6_Rbyn3v&^N%k7@= z`C*{;T7LaSu4Yhps>ZnckUKabtuZim z8C><)+w|Gn4E2sM!nwy9!DK;da{bF)X!4d$Y31vE;9JdHWo4^EP?%rzb&k(#bk+Oz zrW-uUl={=>8Y_Y*^=-zd6_hCT0gvQXZ=%$1s=Jy?xlV)T#kRXA01MqEzha+Akekbx z;k4FY|C50-_cP&U&=qFY<38w*xQjrps%vP<%q)1L#Tit<>K=ai(qa@o3{)BuSt#|!xe59X zl=|a$-wiJXldW$)gBmeGs&ze{Cr)3gP5)+@7T zz&^z1ac)y$M;+**(|c@gG#6!+-xy6yvq9O8Rsr+fC(vm1H4fWTd%}^73bV|kiA_{`q=X#O1*D0Q=S0j_fYXie8qO5(YyIfWii*m z!0X~Wg)!$S@4NBh6`AV+Q{C7LhU7IM@r8Idqx3ob&P&PLn8TSsS8|Sq!xJXNYxqrs zVM_>TD(v9S)%Z-gPus`5O%Va#UBy=q&1(i9)MTA*DtDpLr_L|uWz>L)?RO*;x*wuR zvu`T~Sq`FnV1L#dbF-LlDpQXfz(pq+;%EqGc$J~uMo zcB*F4hEz1T%cN5Gr6W=mR+hbO^9ID+<6zByXolwVKE3VXnhfe|vj?v^XP^trig6#4 zDfcx}^x4I^3(=TxDd&Ull;86eJzX^2{S5WpUyJG;l0f@j9nKL(F%b8|XRiF)E1*Cx zUhKndJ~Srs@KEbP-@3FM8;1CJqke~}KKtc^>kiY{863`atsSDpEC`AHDv|tYj%#a`o33$wo&xiyP z$U;9^KqrAK5@aF)AzJW;1X^f85o!Q~1RJP<0kRNJf?FgIMS?~oz(ayDByd6ta!>;j zBzS;Es0;ek02m2Yk-!oO0?`6C)Zhv&5JC-F&;kt9U;qh{0ct>t1fNKthy-c2 zp$0Zc5P}2@NFa>_y-0wH7EGcBen^mp7EqxEKS-d01QkfIjReL>5Q_wyXu%pamzWK|2y)Bf&5dxS|D_ zr~x5b@P-;_p#?=q0D~IXBSAP4FeAY&S|ExVG@=D~sKFRo;Dj3FAi+Nps3So&5&)wG ztEhn`S`dgDupz+}S|EfPASA&&THuWuBqISWTJVV$D4GrG&;l?dSVDq`)PNre&XGVG z33`zL6$vKM0zV{3Lk+0Vf}$iaI&-`!Iop3zZ}ym0GJCvhIeWYn57HEb8x9q0pFQ3= zH+wA8nLXZrH+#I-PCf3OJr;R^yWS$1A9N>XkNT_s^QfyteSY&_#|_0P6XaX-%&|C| zI&u6*@9#zl_tftO8JPFEZ>{KB zMO0zJyk7iv43rm)$YMF#MP9FjJfI#iAFy2I#Ni7b1*|9>I>`%VU*_s5B-Drq?X z02Ub8wasjd3ED4>-8!Nhgncb+UcC9HGH1Rt4N$Fi^)<0GRc z;@H~bKTi6i0oN!*)v5XP!9@j2b=W4up|4os%}&v5T|G4X!-hVYl$IEI);6O{m2h?c zi$w9~lX&r*xtzyMOQA34lhYgm)A;n>d8+U3?7*k(_x)gcnxyM9duG`Y2dxSlYdZZ` z`|7?glca-oKW*Q=DSHRiE7t}2Hg1J`7wIMjI{p6p`|G+uyRn}#X}Wu`dV)Mhag!9> zs}#HTo#ID)?u~Aim!}*)*W9FK+4US6XBu67!!Lt3oJpVLOL2ns`~zZ3qLkpe+}o~~ z1hwG$KD|4&)27f)VbMmFqaUH^9gFd2LQ!x-K&_d(!((VS;QDdvfJ zc&sV4@jb2HfjpW$Lb-(Vw78XnCNW zLK)uwe&1;0QvtmH6@Ht#r3D+V=Ll%GJ%MTuJ3q@jwH(wJJ}#fywgqmeay1FcI}a68 z9vEl&?1#Hmgu8(yGd3~0gxP9Vf|}qn6MhUILA`9Y^9TR$a8s#?|6%Q;STTF`=;x#7 z;cl^575ef}eEi~tw;yBc@bMGDh-sTBHfRq`UG*v)jUHnkv=H_Ic^2_IpM39w+csT3 zvtGR(s>$x?KN2JY1C#-8>Ctq&nwigYaZEZG>lO1!bejNo!WYHIpMDJ;KJh8#UQEPl zYCd^TngIsLykfk>XNO~o&hfg5AHgxV6ow+ic`-K(Nc} zE_9B_O)kh)hbBAKmc=!`hP$IU{W~JA;-!Z+&A(S&0S#)9v$IJ!H1~U!X7;cQI$C7F z>*6-p#CUDZ#Enk4`+}bq%iw$*oBvd1YAg`P-aT~baMmccX3sX}rA#&E!yJR>9&V!C z7Z-SWoIC^_a?VDFtX~4HrGId(n|=wc9vJIa?zYG31*(G|U45bX>-iqlhc7|%$xeo5 zPJX!Q$RqP@?L63;2QDofmxfmF-+!2>P{*N_b8Md&D&o+JjQZUMff?F0}KddH<^w)%m<+Z&7nu%6Z{y*N9ecd#rqF8gYtkLrQbwlN=kYBDb z-M_*P%rnaOv=n*`1k9S&9|g6TU+zsy`uszPr(ABbXtcU)vd?KQPjn#~I<-3MX{a_5 zGCy{+f6j3r(sfbKQT{L(I;F}H*Te;wKTdPpx*LettPCaK`)`Qng<=nX!3g3E^szeV zwi7Cz;+EPKJrB%l+`V_C!vG2F(4#-58i*B7aS1M= zOxWM_FcmG>lyUT%s00$JyC~)=dlD}wJTHAL49V%g*d zD<&WkiDLr9a^T{cwMVxuyAE6p1~XoSeg_8hbu7E%!|~#p;Fjm&SCNBEZiQ>^PGmWJ z=9_(0C{&1KasK($54kKWw&0_80jALzC%u^Eu|lN&;0#GV}(JMPXw)QpJeQ}f2i+ed}r@g4@o?IQgqGx=ui?BQJU_7zJ3Yy;=pLGd{4h-^Fk#L#LaW`yf$#(bZ&$%c%Z*SZ(pKT!K+&P|GtZ$&D`SS}RS2dBW z(W1ZxeS35X-90JG5&O@bk->~(U6(9GmH%BKD+3ud6*NKu1a<0VZ zj6v%!7jkM9r@^MX8wc43EI}I1+V${(A>PvY!q&LD9z>R=nT3}Ope&YjGSGK6f4XHKh?strG{3q49Ur@2VkCVOiD`E9&oelQ?lG`i z+sh!zk6KO1Lb&uLA6K*tMY0uZ8r(RD&JCXmddiiJuN@( zJj|sW-zw3iD_z9~3r8l)!&9*Vd`;J2(Tq3fPU*9}OvD?sQa7JDvl1J`tPRyIh{py` za!-!zV8Hjg~4*=o}9dcl*q)AL*L+SG(% z;rwj8_U3ZKE0aI5`!d6Pj?{eYuBoYz0+{ik%Lmd^P8`99F2$(}a~;GRk4qKBC5z&X z$BtIZ?O{d^!W{d?rc;rFL~GYbO*L?}uGtYJ%mQ2;>+jH)e*!*_eGUx4DBzRd|M`jY z4`9#m(8K?WJFsi7sF{qcL@`>&)I7XzqZqY&#&V0@!SRzmsVZ}r!SNHj#23dLMkn7I zw>bCuqLXbpnmajbfRmu=(I;=bjT;bdIl&)=#~o#ndDC8bv35Wd$Rak#ft@f?TvZtpa+c;%Emf z;{EbE#{p~T_wuIsycI&2ktG*d=14;sQ{O~;Z$VnUx|hAtgN|}2vRQ{^;K?!Q_e=

Wbc)q`|e?owy1m8!bZ#t z;-#4kr{JDfd|a)q%2>#8U(aZoGL#Fn(AV|Z4p+C=f8Cq*1?z9xtW)7+4;jwhR?b=p z;GQSB4OPc@@ad-M@4Ec4_;h)y^Skt8c&YQA$dhcXnAudUAlSwUx>#LqvVJ;*HDZ|O zgtpmX;q{&EJCtA2J`WYi!%KfeS3&0Uccjhr>Y$79e&!C_#aKh?0M8BYJy2N6^mems zKCM3dzVWvU&Jj2~FR{psVI`K6+$ACG>xcRp?2o5}l~L}Swb^gD8Q}RT3rdWh>SB@D z<7E}qZnX2ItRz*R?B@l&1}suPx1ND^5*H6SvYBA%b4j1HWG_LHnvsZ}@=#j+p}f_b zM`c^_p$yYz>#cLJWSmvEQnWK_J;hsHT+|J%FXe7mi@OgVh1EV1*sF|rJ8nzNIVVIr zpXc#Zp_J)b(8e}6JXSaett046R~DvV?&9+XarOC-xAel@mUZ7~^?qdwRM*5BV886A zCq+$PVClV|qaycxL|^3@dKz2YNgZU6KTx+S`7EAezWifQ_)^l3xsS3MiEpt2L!DDu zmOVqX{yD-et8(VPfpbD~rp2@TX#L)UPhHxU*J1CW<%Smiudq~kj&7>yGc-1>c;bEh zby^)mSjd-)CCf3R@%ptHF0QnG5e??AM|8J>pYFQglUXsXUm(y-cKj|2B@bC6uxZGf z*6-O-WGLzth&{U{7HCuQOYrq}>+`DKa2|Kw_#u_gaP@`m!efa6ca+8Ab{}7Wx6r?LlwrDwS?63-8@Brh z-7>7~ALL8mBkhXjc85*zk+;g@>2#B5a!gV>p=vXh?~SV5yi6UMIfY=|9)7$cf6aMp zjceWJt!y~9L&D%QQyGq3W+T*z4b zaK(v@KcMdgA+S}v6GxW3th~Q@BaX~DQF*ub6JFnWWJp>v77MT7;qclw4sBn_ZaC*| z0!{cgy|fq)#{w(3&(Xg)2wfUaIz$HKV4I%z_f7lOLgAaQ-ZiQpg0>YZraQ15Tzg7S z*H(@4Z(4$cYjym+>#h?5-!n>g%g-e&uBk@X4*zdXYJ2mXWi7pU16hO;+e#DL(N9$DE|P~ z3fjW$4d;JuWE+9P39fT?MN+QQ;_%arG57G1px6i=bQd4-d6F)-&<)$e?01{%A?lpZ z7yZ()0&enJRwm>S2yJ!KMMBvhp`aP(XY;!u(2VcyWK`~194xX^xm(8)2hV+Y^6I98*uL#~ zK3no2>T8u~DOMSV7E8r7be_zGTYs*;+;sg0<^q?L60b)>GlA$3@itTJZ0@w;PJI>V z8}zGx7i|qK6!P??bRR+|n``!JF5e)R{7H45I~SlCJL~GT+VXhMS^A&GWkz_-J7LA7~~xdF<)yb#Sw!)EraC+mMA%t0~m!1Toh&_2z%9^ren2y zioF`1-O6~f6FV0P8)hW1p(DZtvb8?hsC0@oyuMcgIu{8pzO5Dw_Mf>B>Lr)}O5-y1 z1}O8t>)cNN%0uNSby(|ZU}_vNsyZq(o-T=9=XPu5W>0{$xdIwaPIHmNamQVYZl45u zO18c$No=Cr2N-`5t#ZS=l-7N}z4JRbef#Km#5pTeUiE6|*u0%^m(oVIeN!9IQNJ8d z$AuZ7{NtsOD@y~R=Tg;24|p6vT0=kg=^RrafBH4YdZyjjbLmn;FRv@;hWtcg^YUn5 z_Uidcvx*SpZ6%m`W@8ZYhWjIXUDEN+>z^!k{^$c|gXGxRtv;c0r)4pFDJij?*N0xL z<=%o~292FcmaGBgkp(Lr;akvcMDy*9aw~LT-+re_MjzxD(fFnN@C)oVqN;u%yA1?7 zZELADmIj`u>+It;Rs!8F(J8SH!eE6X-9d$wme^5t%|KJS9yqG6^Df%_7P>bfAlkNo z89K_E&%0Fj1s%<169`VE+&@l-?X*4B1~PZH}}{1>D9OZyLQ#kigt;=jT2+gZPa?BQ_iJ;5826jhC)H0v=I&pN@{k zqSUe`nG)B_aE-&UJ)NAn$bC{jAlk4Sq&|4bvDCE=s? zGF^LtRq7w=iCPquJ-DcUt4zWk2(7>PL~5i$zkQLjanRl^`kkIuVo^ycSf$1E*~_E+ zV58+L7lYhDfYPLvO-u#aw!D@?77cC+}`zz9ffFi!9TSMtz-3 z$(KIF$o6yX`OJ%uFUcje^wn0NZoq%cMqCIm-c33oe!T`T1*F*eM0x|d6GvFWunCsb zQt>>$_6@LPxU9FYw;Bb-z1-5>J_IGT6nW{+h@uU=T4w~cyg=Y^QCjt5eJoY@xOCV? z0s%JPS8EFRf$}_si*8p(pj2Vm?JRynV0N9?L**C?(&jsG@`7q%3@%D=N_@eAbdY6t#;s!KF*{w&(tg=G2=Ix=VeO6wrai|PrJ#%RA#dvWz7Uro^i$2oa&ff=ddSeX z<7?_xRJ8nYP<;1EO8p}rZjK<#dtJ8KnIQ%8ra7#C6vu{sYP>iZ|KmC8d!lr&kM#zs zQce6S1M5KR^s%qER@YG4!*RS8H$fZSt3u%|t-tDCUyC{ms#HTpUQbL>``an)Q1=+K zm$U6nZ2uentt9=gJL7-<`*#igeI5LJ8~mFJ{>_B{X2O3n;lG*i-%R*#Cj2)O{+kK^ z&4mAE!hbX2znSpgO!#jm{5KQ+n+gBTg#Tv3e>35~neg9C_-`isHxvGw3IEN6|7OB} zGvU9P@ZU`M|IAFtF|(=5%+4#zetqHpGU()pcK$!R6$(x2A`%smmWU)oq#Po_5b0#_ z*AOVO237c?306dCA_5T+c8DND6;fu;rlTV=7?H1t>_p@uBJ&V=hR7=9d?JbwF^h;$ zL_8v*4-spK$U@F15*d-Uh$Ka%Bq9M3>4r!yG^vCtm=U3i2vkH^B7zVRa)wZb4iRIBBuAt)B7xDQDqx6>5lF zM`Si4j}cjm$WcT_BJ$54*MCO5`{Vl0h-F0NBH|Pgm53PhTf~`_^3de01V^MZB6$(1 zibzaE8lp)$RAG+@azscY0vHjlh~PwoA|mh*nUBbGL{_88VMNBF%1<=eh${DxWF}3l zBO)7B9HWU^M2w<}NJRXhB|3?8N0r=&R7NB&nlwd~l!z2WlAuJ$BLW;vIHL+)M5rPH z6A^}J2~r~K5jl=3qY?Rw$W}ydA~F$4o)VFdh;u|#BVrg4v55FYL?e<|rAdB7s-sG5 zL>eQK7LlTeghWfa5&@71cT~ZR2xT;Ziz-YJL5U<}i5y5|JR-l*WHTanQDrJ3FOg&| z5eI3a9#xDZA{r6Dh-gK`CX&b{QXx&^qe^o`QX^6rk+8`7k0g1Ca7Y9{BGeIqjR<2z z&?4v462Md$k;s2E*^bCgctm`oiDp!>i-=StaZHmKi8M$g zJ*pH(Bs3y@k&jQ3%0zIa358UFj|g)_P$NPZ5wJ+YnaGbc*^nyt5t)w2YeW{KeSB&% znuw7^L?q%L5$%ZBMnp1lJ}psAq)8$v5-E@-;ZdbGs$^D7mAWXeGsnr1vI)(epkFUZ zeZ2RN$H9L*-uLS<>rDMj$?U_KirI%V1zfZ}dVcNQ^XnAOKR4(3)xrIHmmN~WPTOAR zR{^i1_byM@?K^jSc>B-nx$~=&jcly*t1WxEhuX_YyF}Cufj`IoMJyx_OGoVxp1tvRarN~GboBQKbp8MOX8^dEw_k->7ahCdV%X;K z92}c}KZ4FW0G&~^Pf~bqfui|)ofccRfS8*StlKr+!RZr`dmp{9`}H^b>kqJaJ!+>{ z_#D9`rcF(|_khL9YTk|UmPkm4@0-JYMZ|D+{@rVzMu2dD`x4QBdZgfT}H)6cs!P2UB(7|3kh9qX&_^>h_9*;I^V_ z^CoR>l%RaOeR}>w5G?Y!T1H$Q?K*+`1Tq$ZqfPD3g^ls(s!!~==IKVtt|Dnq_ww$7 zwk1C4!;izU-R;o(U3UASHQn)fZ-l;qA&;bW-5y3jwo)2RtKEwA1 zeG<^mRcjQJ6>`y+@i)(X=CPqRx4bX6rhkGPs)zcoN+%%Cn3Z?xi?xBPvFN%}3y-3} zMs+(GAv>h8WYgRmm#u+T-GW^^a@HdYI{|-*r<)Pq1F?o`mu#>@EU-1Z?*SGFk5JW5 zrh`jzECuY2O+fhw*Ka4TZ-(r-@+j9^98~7*<2Z2D3bO_sYxwZeoU-v?GowaV66W;? zf;+DUg4T86$;S@pgHLMn%ui%%W5%@F^QRr2qn45+J)ih4(DXWK@BPFE&{ki`F}YL( zG?X9h?%{a~s*4;hnIBMrGMYz6#aymn`K?WiokG4)Yz6A|U$7V5=baD`zKPL~YYgQI zr@PS?!OQs)efL4StO%|?l?LfFJ2LjYvxK(s0W88YtFgm}%%45^FQMuA0nJpmXwax5 z{4QOb2`e34<6pr)is#22ZwLQfT&02sv@>92R~y%gTag6@Ql|$Ci&u`1o2_eLLX8jmz9BpD>->xIwI-I<&pebbX7aCU)o>cxZOf zmU8`r_c$Nj1{x)Q@*Yhvrd0yJ(IU5R@q*Y;eCMeMi!m&x+YMf{I-|LK%6EZXkeq_!>-&+8}+Hh=PoatrkDXMo>7ZT$Ng;Qxo80YscBd%5m* zrriGT_TEm}#NByz+f$Wa_us6P|G2;v>YnR`)V%j)`Fs5dIXMk4|V-A710LfsL9j?i#~Y$K!~ zmHHzDAEEIGSw|>2Lc9@zkkEjH>?4#OA?^r0M@TqA7Sbp|Li`bWk4obGrs`%1IYJx~ zdXSKSgzBRadW5#4l5>PaBvc_G1PSd&$UQ>g5u%O|ii9>KHBSa&OP9&rup#}*7NN7GPnMWfX3AIQFL_!l1GLTSyRAP_vUYhGU zyN$2&>_)!7n={+!{%+2!!u@W}Y^3|Uss8J&`MWu@rSI?N%%;A-n={+`{%&gj=eat+ znjExI&2H}dM|);mf3#-?_D6eWWE{U|4chV{ZL{S6+2un5UeO>b0z?tGi3%za=!gJB z1O_5d76GgXEJeU40x=OFiNHmFgF*xZA|Mrkq6pwbU?p1J-!K;evj}8GfGH~cL_j7Q zltcg{D(FR^EdpQ>n2LZ=1acz4(%B+0zv%^G||RK1-=NpML;Y9Rnh9m^`}B-ms~j z1kxhF6{f;dn1E0ONF#6=0mTUPMF1`WV-c|GFGz}jX9Obqdz}AOn?P(dD2)JS1QsLU z7lF74kVW7s0=f}kjlgFFBqLB50lWyTMFp=Y^8y=nUYNNRAdQ(Bfiz~`?xZm@7m&ux z97P(ln~qaoZFbXfYGZcOacW~`ZX)N*%uMXmXQ-Qwlh(`_XwS_Ig4UWD#edw>_<1@y z@0!_t{D1wPhA^pwFD0xf;XVn&Nq9^eTS;YAY1}E5AtgL0VLJ(@NnR%!exVM(cMF5zqmGfVha z!m`r1R4QXim|eo(5|)<6#S+Gq%BvFgl(4*n%O#90;bjT?N;p=+q*7*y-}e?XZ?E6Y z|D*3|{$mFD>;7i;r=q^_wBY{3b3i}8#~IU%67c!zqSWg($H1U)&^!7ALSSf{jawdf z3;23{`PXeJ$>7_kc?UVQTnHpc1O5oSM+NZ+R7U_g0=p4-kbr;$>LY+2f$a!5M}y#~ zP$2;XX|Nvw_XvbXfI2E1M_@w&4iX5E0DT0`BcL6mLURN{BtRj70}1FypgjWM(O^0P zCsIK}0u2%XkidKd%p;H;fffmXNMJ$&1`^1R0DA>Or%1F1Q;an9|8GjP#zU> zB)}pKK6IplgaisCfFBjsqrr~^WF$}`0SpN&NWecT#7Bc73E)UzMFJiYh>!q*1n#54 zk_3Dt5F-H+30z1(K^pW&AW8y661b6oiUc|&03m?^scC4NWelWB>4Zv z4D$OPWae(=e`y9G^dcb<2~|i4K|=cxa*t4WglZ&&BB2clIY=l#LiEw-JSy!-$VEaS z5~7gMfrRvX~>Bs3u*18I~Wm6{|3B%v7z znMf!@LJSi6kIx#J z5XumdiYS#L8dO52NQ%;6wpIffl6lNLOOZmzaGqrM9nSZ>zw7#)^ZxN(SNorJt-bbI z&))arvG!+u?seZIp!?~ zafygd>aleEv}$_z9uzIFN55HGkM;rYe$+FlLEVpa>5HwPX?dNRKAdbwA{@9){ zqCYyjA*A-PcRjjrCU$(k)Hbk>;c3{;PG)ewW<36}%>nRcq*@Zx-UHQiIVQ%ZtGt^sl=^DANdBlWx@$w;d{#&YMQ;=;yErui zLd4AzX?bJ8CU?;a0o-8auo}^gYo1;|M1xkRd&mWQ zIioeMichLn>mqjdlHp8ESHyWy=aI641>$m?pNN6C!SKyDJtdE_z|d@G7S#0vgSsho zeh>P)jRQ*MzE4JVF%_k0#g?)!M4@!C^Pyd}*(j~SQ&%|O8l`RtOFJ+245fudj|eO> z5%>Y!t}wYqe+poDZAF@xX9=%4YZifszmXv4wKCnh0e3D!{kl(BuA+;F!^X} ziF%JACReAdA2hbdWLM266}~J&GI@{7dsmx7vY5Pu9URt>JpN8cdJ`L@C{*wqQwKJ8J;sB&>RP)TQW{=WIB#0}T6yK%@ z{E_bJI(u>Uc(iAWvr}Yo9uNt0VhKYeY2;Y=Hler~T=Sx$z8$CvZhg*u_}tkE9qqGv z_)xlzgumpZpHT}5|LbOMj_1HIlW2y!v>^%q`lFVQQ%U&uX$lTJ{tN!j8I7PNS4>9M zfS!bZ_1eeM`6T>r`!q=HBjLZNCqPJmgn#pwhdvS{{M+0ZuKb|AuU(i}cl6a@g$qaR1 z;3na(y?wHJ22xn%zJEFNg@nIbxYX%T68@*7KNm})g;R9h!df3m_-{58aLgj%udNiU zA5Fslj0$zwB@+H!ImLdhB>WX#%ek`@ZlCNLTi1FU7)77b=J#s^uuPbNDz^z3#d;kp zCQ0|g64sHY58{xGn?`GPbSg4^%$$_N82!`2A~#IMIh|6l-Ygn5nk?MoVDbTP;^vei zDoIk~DYpbo6UZQ)=C;_#w6l=q?NCb3c^b^b{-;_C|HPEe~|f2I@0zGFwbY| zN8or`BF+0kU@lf_bW`UL*p<|xd~hcN(rV4VabUg>m`Z-u)$?=#$C56kFj!is7)Zaq zYIJZDikja`aYXPnxTdzf#e737c%?(8+%_=_T92MjpBW|npQxC6|B#jxK@V#TW;N3O zwAxs4r*Jpfy@`w(yQ0A+!RJTZe35{5(D3=k7D(`}<>jrk6-eeOJJoUd5+rWS>%Vc= zEyQ`yVA^x>>XJoAgU>ltgZ8OBkCrCX2fGb8j*-X=0lp_Lv~5G5J>}eLY=qH(Zv~Ym z-5YctRd#j&H86Pn_BpNTTR*KmdJYr{oo{|_c0dOuI#6#jjNw9$_Oj`(&z477Gimx> zO1n@jy|;SF^FC12P^HLl$O=8|QdaUBI6zo}sEP;l%jB3Pf{4hY4R%aNk>AzpWs|BM zDB0BOLs-gjRKi-gX?yxKs^00N*L`a@C>N_0o7%n!^x3Xt+#_pU$i`&^2E~~`>g}JMV$3=N~JpBk!V7Co^~f;u~MilS}e|6aR7yl7ucKWbbyohnx2m}DuTq) zS4@HaW1xiW7JXOZ8BiUmWiX*Ji^@Ir>t1El)5=<6{uIceE0}H$9?}|P8O7sUaafvfK zh5JbOU(;!$7Kh|7PgZ;HQ~=}6UNauGLue$>j9&b0Kbn00G}o!!4K1iW6xg*`S19f5 zHNbnv1r40_-i9uVcaJ z@*J%EcJS$yoYzQN^DLVQy&cdF)*f_wo&}_p(F220DWth^z1a<91h)CRaO`Gl8pdFU^PTepuMT?v@hycP!+sAbvDt2VRkNZ1ovwEx01dK$Uyp z23+5{F8r{%C6ut(eq06e|p?P|t z+^{nq1^075r}D>OAyA{$wxI)3c7(m&mwBaD~52LJjY5sH$5=Af?IqyUlnRB zcQ|X5m4#ZO_X*HHxPb;8ISU8Ye#G>{lq=>|=70~IWoY=kbfNfOHA{zeJJ7JkwGUiI z5mu*C|gq>rtrb7;uHr}D)^y> zd2sk^)@&?uoA2ohnpCJ%J}Upr)Bvj9v){F*bs8$tCr)d+v642Y?)}=!&X0vwkVPtV zuESf|wNz!Mk6;a*zH=kN8Bpfp+f(oQw_>H2U%$0cr(uziGZww^&RCS$MbPu&4pfp_ zd-u?dX((`+XEz7^b|_Y4O5eHVID}NX5q3M&;a1lRQf?pOp-}FkUOBA`=o6xndU913 zbTv7+DNUDxHnN#rQD>r2NsEQeoM0E4`LyYk*y|Kb{mf_UY=>Ddhi~WYBU0^xzaAf_vk@=;kwm_zfppI(_2-ILiLbQn1gA@;$<|9yz^W~Phjzy zPOn_2d!T>jL)27M9~Nb6dX~fg3d*NePHd(cfxIV0vc4b8gH&%kxhvGpK%I_R<*oF4 zu<};x9b_M8@zEScU%3E5%$`-BxJug)tKL^;e?;ew6?tP8*0#i9=4&|~jXVlaa3H&6 zZ+rmU3YqfKgAAaC(Vl?)HB@9PA(xX`0hy1e zg}G66VZjeyHaow*gSSd(9A0s)3~Ox9;dgyr0%ZcO+&*{76f2chwQybN#3BP7&-hYT zV^O~R>hJ>%=tWgWjF{##C~zr1<1Be26e}bfUC~qkAsOF^AwzAr^%PA&>*@1QD4|6n zE>q%n4Dfq1>i$1(CH*(V0Dnq%{Ce?cBwpPAe;5DrljfF&$Xg&r`dJnj{I#y){inR&-1w?-+!g?{CCb$n;>1)(#WT?SIs^7Nnl3{_KT-h1DoDZO{gvxE71AQb~ ztc0<2@CPU-In$in)KRedZ@?1+E|)5*XkyBYJf1iWwVvqBR83ZE&at2t{<^aroJ zw`PxDV8$%pT&%TcsIXvnL8ANE0+w8{is77AA(o34q0evT$A;Aw1J5r~V+k)~@|h>U zzCS2bm8mKkeF$1fU9tG4LfRcCaq(K2V*&JJcyo!KWfA&ryt1c#!v|=o&slj?j0wu| zu#e7CYC`cCJ|5|?LCB2fnA%#Ju&16`O`W$V4qDhtBi4fPCEs;2?N1KkYwuOk-CTun zg#IP_yw~|ypGAMph-W3K|IXQP=lhUDyY~yZnm_i0tEl)%6ME1z$(-K68DFwGK1Ee} z2VZMxR@Co%izD=m^}0ecu-=%X@{WdB()0h%={}<6KY~X32MKH`8T*66K>^xMmITW7 z&Vx?%G=GY`7|=~wvSnDS9rPSj%-JKC0(wi+*q>`MHM@~!O>)-fu^uEMH}tBYZ#~kw9JOzEavZYrIJYunsu1le zZ9khdl?4o0Bkld66tGy~+I@D?oUkAVpR$LjU7N(gC$gNRDR)sY{%rc~vj?}qMA3X~ zYL5Y!+;iWdYws}l(olPD2g#~(Vl$&}VE)Bl*5x~V>T_4r)&d3JAgUt;7%>|!eqQy$ z2eCLd$KW-dNIEJjD$vFT$-OTZagZ56%3f;x3QppL^+%!X5zqi;95C*udo(HuuXW^-;Dkrx5|VQN$1+4PXIfy*a{ z>prB6zrwlJ?JIh2>^K?OLxsL1>qUmFDn(n~gOe6h^~-sY2+;L@_H1(X zGw{iCrZm!!3X;uaa_-kM14DhzTDOxdQR^4PKHstelew>=P+`WHbzA(Lmvah{7r|U3 znmbPCjX=8HDe1wct00HP*X^y+kPbunCH{M(@y*+ ziM$AA;MTW|+8K-aM&#I!vwpy9d|RYkm6OrTM&kmn;t5E7!&`Cm3OST;K?-2;^~ zpH}MoOA~n!$UtvVzQ8dA`I=}7>C@8S8jbJiZdn>(zuJYlTkhu_^Z(TUZ*TJ{aAC%8znR8gH>A@*4#&Ljmfuzez{QenuKEy3ZJmvLZ`(zT?7LLv+11qxsU5 z1G?)mYEaY90Yy>{jB47igDwG29!7mU2{*ZNc->R3f(O`Ap1&)33oYv7s-6kuVM8vV zRIQX)tet#=NsUGYnunfxa!>LluwdKu>|=2{DlG}-lG|JhGShjku_SFl*&p0q^j8%j z%Q1DMO2ZydbTh--VRHv~k{&m|H|8}uDKB%dx#l?NWZSeeR(A?B3-p z>tDOI(G*{$s^HqhOvYBZ9xRblI(cO<8ftvJ;h{iIdgX5L?^ROW zhxPrUV&{Tsu*hdd=B7m+tbaj`_a^TxY+^QISF&Cg%ZeQPzTR03o(g;MT1zklvz;^K z;}Mg9HdmFN_O17Y&T5rT-|n$ucfsGj;nSA;((Fl==uez%lh4rCn=Q8QYYsHKdEe@N zvK7`-W2k!c zgBhq>IV^gutN>ER1z77!>0+6p>-^&h{Mf+qiF?q&J$UUGW%Ou`DwGlcl#NH^@%D&_ zj5WUgSV*^yLt0W9>YHA1+BskkMc$mu4N;|s`q!W&bjHx+RJ6LWr8AbLS{=*J%mYt_ zAMhXRm%!|!+)R^+qR=KT*`eJ^2|BCjleX&%VRxZ@kA{2_N%(I}C@%7b#!OpErM;g( zU5zi|*5)GEv#m;dQ{N)gGi|)d5-AC7`K*$^_3eYa&9(dL+Pa{Aea2J^_Ah=svEPLrI#X6GoE_W^!%gL`24%3| zQ0mCX^|J@CQ(n&a(R~Ue{FQ5cdevd@+Ngc(o1;iCa=-Jrzw^2O)_m??w$J=QeqRa# z{#TI`vSFt`KC_q%91N-t9%H8g?#1pW#$h@ieN0<}yJ&MYS73I@Wy752On^Ob6}g!0H^AkA*L5qE zsC^+jn{+Ag5?bwMJlKShtOK2_=)KgFb>@QwEy%khQMj8mLss`2O%xy1} z_(9#%{I9#ee+EsCj*L>TN+JxpZK|Mw6xq{Jq;;j+mIx4xG_Yr7yh2lH& zlR9WMEyFj?XToR=nua*$!R>DLu8jgwDG#CfZ$N@a>yVw z^HC}&yY=IU2E}xxoY8MoK%qUuYk|xuKxi%#)YJHekku`a6FfK{sBX~v9$>&m zfAuHEc~!vsyo$yAm*z4-JzZ``r1FY{u_C(OyKjBO5qZ#})%Hnh@;vyw#hBLQ!1iC% z$z{!Df_jR{4m)`%2^(UH8B;;$^eIejJbJw3b_}Lb>$j2eFj^`#tQaxnt)Y$!T5@Rm zr{*$2J%tp?ifX&pXh5o$9MmbIc951!L)+-XX82K-M zie|~w)toMfVX}ue>Q=rRM|0MdPk1O&(7?fi2l|+-ew22iT7u|ntG{c;g;GLunV_D6 z61{RhkkDNIMLi`xrz}ct)!4;I z6h&pSy^hHQwCv1d`P7#{!e6KVzP#`f{^hKEU^HP#bD5x?lJKX@I}O}O`1>iPzo;SM z-__`6dUXkRGY09O--D+b3ID~+d`@l>{t|K@lQ$F8Q%Ipyo2xHbNWx#~tLJGEF)qJ4Df(4aW%mKqDG( z%#@ZtcHsy9KMwS@&E&qI?qNc6`6u>NFMHl|ThB#I%du1WI?Wx>m(d#J zCw3ch2)_GvZ$A^{d}_Zk<;|nJ zL+#j*eZS*3y>E2LBQsDrJKzQ~ffGBA4Osz)etj-;BSCQ3>}4HuCd=<7mL=-x?@+pgB@1qye#aBF%+D zvnk0CQO5AxIQ!PG|N5uD|2)6$|n(A46jZDbJij|d3%3*6uy9_s1uvo1U+bjz>R z21|U_`Gxrf1xiJFhWdGWZSo0|@(lEr3JdoP_fhi;42}qwqVM5H+qga`REj#(ulXFk z0JCWSO>O(t09VIM7kVo9fpThDZ4kP_yy-i5Hr4(C>eg^F+$r4(8m88dg16#tp1xv> z2Jf5hz84%g4w~#=Mk)rYf#w^_#vio50j(mXyL{L1fwpKh?iqEPz^8X-Gjc4f!Dlc_ z!VIZ{FVEQY6<_ZK-EM;}GY8th*RJ-cJ|08RSGIBamkc}5&(iAZD!mO1tZ?;za`iI! zo?aJir2ig$sakQ~ptBsD_B*iGf6)r?4Gs*>FOh&OM=haBese2wuAW@*0= zJ41#E3$%n+CiNf0qN|?O)Z912d@tpfsCGBO**#m+OMLsVhNX3KlE)pa#kI_YHIN;Q zaJY#ZuGfOfwYw!R?F@lZxjwC{Ma99-@qI26?a|OEa+|1O;Tt$7|IM}GHy%*zZdm}A z1PkQ(teT^--V`!EVY)t>^#&M-K~Vw0b)aiM3yb-ZT+s5|aZO!c5~{lIoIhON4Ib2Q z_>9-AMbE8HWg5LcgId0)b?!fU6;(W#qkVoMFS>X=V`IeV7pMrf)G$izfHP+YA9U`s zfh^TUruK!;pdvP!3+6q?GkGUiT3u4{!h3OYw}QRV*av;EwNwBra;=uhtslnnmxW87 zx6a1gues;v@5lf>i6@10wRJF~`!(*FtcTEK)Va4Gc4IWaIDR%UavZhVZV(Fi`W_Uy z50<_9auV8!vM+Uoc%keiQXRMq^V-?@9(1?6`gE0anL(9*v7rpw-;m=jpA*P|7UtTcqg*xKu$vFK_oJ zXdZaHCoOvr>&<&0`>t>nwq#cg{w^O6b$ZW9iWH9HWp-v;%9&4Mo|i8`+J+zW`-g@aYKa>)0n9sBD zJzTo*=860}`q13}eRW&`C)QJ162g$xg)L_Ue!0)F6Y6}MrxMmZh?l9#f6rmOjkzDR zj#mXTV%hCmwZp9&@qEcW>t`H!gy&h6Z|Hfp77N9kJnvNJ3zW4Ama5WA9r$ADW70=~m4<3|+k~bQgRThQ{UxLtWn~ z(cA8xtCJKD*g=Qj`#ZL6bb(es#dO;{Mxn`x*>+BeDbP^%&9X>wFKGBIDsQWnDD8Y_ z>7~r^!u;ANWX6JOp^0t(uyMdrxN^2aMdY5daE(|k&tbtwaNUWqF-3bRxN69lr^=Wa zN|&%lDzOV=+obYudgbF(TNIkRN%u0vhC#K4TSxERnFmezo5hz3`a@Tr*;n-!nLuMp z4Y$a^1bW-uUiE|5sWIr_H$P@^i5s-)PYdE@dIwE1g!)bv>Ow=A6PzPoO`+kVANyI2 z_n;@i(e)8OFM%`Voa1rI5247363H6b3@Crz?Jm2VD^&N7yzO9d3u-Hud0lnv!E-sk zlvFfjLgBWXr!ML+U{&$>pKiMuFkegTRl)5taLLr$n*j}-9XGO8+>fR6F1_YDc^Mnt zymaf*{Z#Z-VaZ`raoTZ{B(%N@8$k6dJP)!@6k|E{)x4{i#j%+ArY*v^axt?Q#~Z^+ z8Pq>;>*tXbbI`Dil$}N3A@pR^vy)PxFHxfC4~{e6w?dJSw|Ob2wnF*jz@dhyNvQ5O zYt+8B2x_a&XRVp~}rOv8wXn;(MwKFyCVt>Ab!0_xVO#vGCB` zho!GC;OnTp!%NWZ0U6cQ2kthzr27UmXokWFJlw1*aD4% z!zT(bQ%}RW8AeK||KnTT;|vpMSoEu5%sfE58bZE)!S10!n>M*`@>w759uP#kWB7HE zgz4);{Wkdiu|e?HhAp0(|Eixl&ac&fl}{Zf*e`sY?_WF2`gNS?4S(&zw=vMi=dWu1 zsdax9@`eZfUB~xp)n8>iegVM|o5FnDX}3OMn!jG$uiGdda&v$M_$rq(h#r7^8!E%g zmxV(41y&KlXP09>m8uN_JLX}*n?AvVt4pDbf!pGYz3y0G{#PSD>mkf%oij@--wevD zGF7#89Kn42yK2*aDnr5S;hnel3_%(F;F#V|G|3jNKesIWv!VTGL+8)NqCXpp|7_^~YH(6#pfPm{^w!il&|6a{ zL2pf+1&=p%A31d~e;tW-Eoc0`vFrP_>c4-X98SaFa}At`(^2R`QQ&6qC9}FE0p3RE zzdvfJpL>Vw2|lmU-Td^168c&9?xCH^IAqWcdDk(A7mb6krH3Sv!3DM`rwV!eNBsgn zk<3H1`sYy>c$#SS8?`%M>C@^1%q8XW%I5E@FFL+7r_99h`R=^pm@?VQ=d#C`9m`h8 z9sWF6$X#Z_l4|Wz6#~Ur>NH7*oZjG@4B*Nd;}e%X=A5Ptw9&IKW}Hhq6t_p>dtFG)aD1;0rp6%9Plt<%-Yph)u1Hgs-SF0}Xs7K4!T^`)&tVXLhaP17Wq}AU| zkh$@cR{tcFqb8nK|7u+oyCGQBdVJ+)>2v61t+stN_Z?(We(>5n(fR1`qb-McQnn+8 z=!w0fVpXWk`lBE7!=>n~e{1}KuajUu|9Hvz8>65xr7OmuIu?ywRDJZOxC4xwNjt9e z#samUiuCzV5lS1rGuQ{lUlu!P~KyTu}Q3 z8!v{$E41qr`maQ2^?kXCZ1-vPt(z@G^C06Hwz?tHC|dpA(-UDUf$3z} zP4VG6@G!2WqA=VUDcu{Z{gfaEGB%fP9eT=u=DR%L(s`qf`VzKfF4?&q<*zh)Zq1yA zVu!D8+sUZ}z6%5>4;^}hnU@Wjm-h8TW;khc`qYgRY7@4o@!YJ|?X zZqxza1wECQo|MDP=1Jm}Tit2(Cz6K(a#7#Q1^kO#e$uYfXnm8DHu`RTEUx_*I*l6|oTi=hx1GkfWNft`#;B$9-TJmxSu+D~EYecjj+*@H^ z9elF^&5v7|zp}O&_4&T8bszhJuCwXyH)#w&=NI=Y;zmv|Z01&2Z<&o5tGW&sRz8A^ zB@J`mX&a!980H2>epOHyx%a|Hybhdc+jDawLKO@zVS6Yp%ZM4PZ=YZ5@DMWIIeUCE z;R5Q2*vfCEtPOgAXnXeE^KMO8>Srn1pT?lv|&6)d6KMx(7XIA2{-vbFp zT3=jdDFs@0i|0MKbOc>i-dAF0d=qW<*tF~DI&aWB<}&_loc6(?VSP(sDqbRJo~+YT)5e*IuF`3$@XXR_gYsDL#4E;PMJnuFQ{*;_ngPoXS% zjr!_cW~gdt`0(mgqL7nIpw(agD*D#)%~OhR0(^U^sq_BnS9AyM*wTJ{CO8GHbk@(1 z0#%)#(~jrAgq)le8)7r;Y4v&yqMK8|x4NzD#~$23cdn;ZJ+TZ2y+J3Atn>>39BGq! zv+#XT-6P)aTzt~#+lTnU(Y5D6;^MQnlCQHOv0EY8b+7nAOX;eI3O6yzeHDHyxNj!P z@MXLA-g68LG)#5)nDOh$T$U%dAoJ}_9EIGiXwqvzv$4Ml$omDw-QYiF9Kp?Qm5V=%Ttf>fl1HL>Gwks0v zLkpbcOpYa-MVBVn6dTvL1H|^4`P8C*^g`{+GmULSkXI%p+0P;qbS2bWZ#H&9T^l23 z1{=Hp-yiIgRAUT4Wi4xa87o=Ai<~(_oteJ0`p(r-rOKcy?dH9(?XyrfYWb4q;+>Z~od=3Box{W9Kh4b%2=9#wKz0DAfufVR~i!?!w z=Tda|T_HHeXtF=2!sn0r=7W2OPtxi&&&4jK_4_McMAj8%A@7WJ7g`VSVZPagEjeWo zU{&-S5#Qv`ps&4j(TB-bNO<)QpSZ)bz~{7bwwlQTbR`*Vh^|fpj|^QMI~!`S_?JgJ zlAa8KA0?d?HvGEiN1nt^!xIs3#@Pz}I`KyffS0sYeO? zz{!qot9#Iog5o+mlWI8Qe4V$(w-ROsfVQ4_vHHSKQSMH*%=nhQAk6oDwkj(hcwJJ)JXzm?8PY>f zrAa=5Oluc>dSMZPMv~if4_~SUxdRG5g^QM;aI`ok;WQ6;U7XUG|8Y01oYg+y8;2#z9kpGG8bU~Gi~@g_6gNezIn z*KAJOjGsYrpE$xg;1yIm|Mf}*xs7G~t-4@5IMF*2eRPt z70y-Fn4#b+>zlSE=op^cKJ;`1?p)UowO)vJx5dm=>D()I~37`(Vxk#iV*kv{A+ zJaax|e(F?aoG<`-oKhN?4_<^E4r3d)+!Df4pCsI1h$obKF@CM~)B`MDlqS@D`#ENQ z&myXOxES>?t=RkRLl)$)ws~kVavV#wyGgZ8ctNRJeckVaepvkS3>%j5$Dn5+58DnN zA2i?6DV=NUeDp>s&babj1rS@8%mr87123F?KE~-5AU=t^+c%rWf>z01rMkotP|>>O zDoH6_M0bB7M=%@So$%i96sG>!)l26VC zVOc{fu8)=IP$S2dLz}E=^{#iTj@8lXZ}7UQC!n7m#d1bhP9oRiKT3R>Zh*Fe4;Ab; z>d|_~pFh^ent*Qwrx=D0IU?qca^`^fuBeZdbH=RQERZ?9;Jf6gK4fI52>Twh8_xD@ z{J>Am+n8f9efovvUP0ZKyqz3(Vq6X;Z^C@ybOhpMqRr$ zoX~$X1nLS6oKV#s#QWq_H&4+3XrBJu0;umZ`tr4vpKtWLtC-E`lZRS}F=U_q1c2Jt zPkoX18(D(a%U7r0m$RF$4-NiZzoGIrEw3M$*?AHRJ~6pgs;7B0W=6Absb zA3P$y3Ch^@3_HXg0==Fq%1+8PpxJr{xq8_Q(L;gDhqeZ$Aik32-fmwRK!dl}{WT{p zA_2u8yU)(x10OY2dS{<82UX$$rI*|D>DQ@Gk2hv32kZ3fUZ42;byL@=O1uES+h1sK320+$RS%E8`TVht&(6Yln4GS6X z%NE|R5Bd|&Eh%Ke;En&g1JVh3wEB|hZslE&_2i_W@#Z{Qy@BD@34biKtX}`(@CwlT z@$A!6V(Lam7e_CNlzW11mfouAQn`y}&Wv_@T7$rw_g)qq^9PWSW$=*hu?SlG%AA4l z4WKOMQ#gEI2kuoh&Z!)Uq5qs`K3Z}}=>dYQo)=QRnq1Jp>l^+;sn)10{;c-Iejar1 z5u?kFkIH}4zf@hLDoLwHjPAnjC>pzFxa%8&! z`fFYv4LB=})ccmOF{#y~p(8$e<==HtZ?@oV;bZNXA)vDCy2@wFu*5@edlVB?32|Hf z`5eG1%Qk(SaFxN@FCWBO=PH5TGgkV?KDI-K^;NI-Ffd~VlhKf6zR6G}xa;27?p~~7 zHWs7QcMfYexxm+R2a9F6UZCMimOvo$B=~83 za1z*s+8hHX!G^AEn+Xx1?l#of-Qxh@A{&9`*Y`EwqjR-fJKdvt%$7_ zHJ(A8Pn$34nCzjwpTLT}eExuSP-od0Bn*=8>BOat<{J&&RzCSr`2%Q)dN-TzkQ-vZ z$!IVT8V(*^HhXQ(KO2;sU%s%UQx>d$yJ)Kj+W`1>yuwtfQw~iYOp=TBIs+Lq)~*zN zGlCh{2zzuMOG70W)GoA~HAWkP-?avQ9;ekmQtL^)MXR^0u4!nb)r0(#U*BWKwbw42 zer^SN`-)Wki!P%dI*Dp^D#wu)hob4N`_I6;?nP;9-j)EF+mlQ!%T9n@5x#5G9zF+& zSqc)0y^qk{j3myYwi3($q&0u?h@$tF_iv?kF9h$6Mt>+<*@O1ymAfBaK7{rt*(Te2l!0SEc%`go#T)hco+)t{xeZ$Pcm;o# z7KjK}7HHa70s79L;}$)djV6lMTBPPCK}Lmd+m6q?gBh+Is}rZ)XBQthyL2JCk0Q`Nbrq$o7){7pe)yphNl|4wSf62zt-Gmvg>Av*Iyn#esOm2vLBmurv7lpq}RRSEh z(yYJtMS*(wF~TR@4G9}H^YGuz0WD8N`-ZP*pj!#^B7+o{gHny6j=7;_sNzETaQNAW zVDMs_IR8U$GR{yjxk@pm>{_8I5 zQ9D|_RXcO19<5$*{a|1$=!0|gE%wOLP}zhl@4ZtW}CpA^Onl7!l?VX7vgbQuT&xeE0YgZLJ z1!bdK)o0c*4?u8kRo92YhUKXJMAqpq+j+rw@y4D_wIXQz`lt=hU^EzbaH0j+z6G~F zytsXV+ZCN#dvbO6s4r^IS~&OX#ZR>QQ;w}HPH4PHRW`?DEv>%ifr8#v(A&pl6j>7o z*jkKtiic}~Ykd{{!IO4I--HVCHaWj|Nodrfd*f|0X<9u@Kk|44O;}|+Ua(pS^lxYGTy(q`HMd;sUBp_9 zWP(%EWi4NU>uYV+57i5Lr~55v<4_QeHnBpNJK2-ZDDk4a;MAW-q?*xiqobc= z<^nK`&dhF-6GFq~#km5S9JKyeF0I&L2e`cJ+wOe+a*!8Q=5-`W1`RiyP7^GP2gBuI zIoshIT@oM3J)(64teYX5%W;aCmr zbMNWv*JPYSkiY@aF#QG0pz#)`cWRF%xUsaxYbXUk7wE9Pv zq}<$SKL`8+)lCYJ%}Zw%elObZ;b?Ez7QP2at30E=x92oS%a%6Iys`$(k<7{!{b&td zy?@xcS9=&8YDQ)}Wqs)8(zDBchH#*f#Zi}w;aAXcr#0J5cP{EE4`8_R>=bC;ZhCRG z`XI=h@oN9u$yji6gIoP~3kEczd;ICAx4fXEVo1;7!W-048E?MArVTVFeEA+Pw+sB= zj3a`w%+(|IjUKeTO6o-EH zD{TK%zuw@x&Qj&xo|k2I8SFT&Vv(W7()0seLFHxUfoXE8*%@W*Ibz(cYd75K6;NXR z*7brM_rER6%v~$hDov~nZMSX|q}{Rox4OUAm)V^IT`|Q)^neN#{GbOasGtG~0FZ%o z`hYbx5KIPG$-pH&=t2cZ=)nvs@IZnDWPqLwe3JoXGEhqfKuKVR1W`!9g9Il?Ab||@ z(+AMWz%&`~B?GBc@P-6hNKk|XFi5b09vC14@nnFT3>=dISt`Iof-xj;LV_G5AVGo$ z^Z|V`P)-J*$-piZ1R?<&5?rANLP*ep3NX-v0c60P8ptLC#PmQB3F=S*7<#b8ar@L; zg9IVy0Rw8_o(zbSfo6Izi3C&sM0y89tLINJs=VwO(31pz344{+16$vttfDk=+ zLjo=Ipa>PfAi)MIFhB<4NpOn?AcP89&;txqFn|QfNI;7OpGcsH1a;^E7!oX@0vjX`LOkVb-DBtS(E zCQ*SO5~QIARH)zw2~?1v0tvQ}z!(W)k$@9DI79_<=s_0}D4_>4rUMToAV-2{B+x~I zQuF{473_f|FhhbURKSBCoS=esB)~?3VI*)x4>C~!A$stJ3bfFJA|!x81@=e~js(m| zaEl&@qJl>B01p+6p$AT=AO{Klkw6^@s*wN~Jy=BrmgqqsDqur`EA&7J6(A(RJbK`b z3X+k47Crbx4-`!Yb?5;Y5-cG>L@MA%f^#I0MuJ`>Kt+N{^uP}Z(og{vdQg-EM*m}} z!ZN*Gg^j8krIwQ*TVe5*AwRC^<$9s%rT?YrlCQ=v;SPy%^^RZ@7R(@(@TTxf3-9Jvwi2U?PTj6kLgDS)DkM6kk)0F;HNFk zTC2ihNgY`lP|u46-lgx)+zQZ>!%?OzcNat12X8w+-gF~%v^VbhE6S-ivHn$3INB|_A3=pGl}X9ojt zXiUSQz}`}WyW|Md%RBkh^OklO;42;4`u> z2*xs<67sCW>!823%+{Gjhw%xDHYCDxR__U1*x)Pq);R@6DeOvqcWe5tfmTXh7dc<( zHZq{*q-B5?<{X`IV_+_fQaa(cSzixl)VIywzveE^cpdC_#P|?gV)H3J%!vuF%2glR z8uJ0JSl$kN}5S5~qydA=)vZn6>itT%)40lO83=Q@wz1Ge)uKh#8#*GK>Nr|xW_T-lC- zyu?tbQu<=>xzHF~Xy-iAESyE^$&%~`<#N{^zi}WKtDLJ+JL?t!7eZ&X8J6kT+T!*8 z{IVWwt<-)X`@9TPcN(Qx17TWBl4efbj;1(_UMME*z?h%gy?sP|e9^v*ul#D5?LFB_Hah}Nk9r!U@f`V_efJUbV5mFclCw8x3>>Z_Bm ziCiG@Y~`1DW8}Sd>Wg zk7sbz{REj9+Bn(#6IGjJ{gq*myf%Z=ibTB3lFPm4&;i=-9l!YQD=Y-BoL@D+J(ma_ zZ#iYFI=sR2PnCAIA4-BjLat*wXC~m?2PV_Y&wAqB@x$HW=ku_M(%MyLt3IOP2(BOd z*j&KXq9d2{xTWBl{>m>IJ;G2+E@tNT)BzYV@8gJI;o|pagqc`^T%XS`ruE=O9OD(tTiN zK({7baUNLQ3V8=TE$^*mZoY??EgUc`R8)mQ$)hN|NCF?cA)@!%#+J4$4ZTvl4%-yp znh?LJh^>|!8742#g6mAE;MCs*{#mo;HX<2B{pW9WoXGNbLELmbeKlQdO;Dv^$hK0&exUQP%ZtULtGug%^RBb1 zR(VNP$=XxR524`x75<;TD1f;kv5h5_GC;WS=2+w2LM*u7wnK1JArd;<)N9K#j2Pw~ zf>N`*(YM2ImKeWxN1_uymd6H;1F=}6cRBl{z_-I_)`*QZ;JLF?#k+C?;$k+`>wRz> z37G3FXQln#oNxAkt6ickoUba}C(Cmch$joqbErv2LS65l9W?R4^HqgvIxA)(Ap!l? z?iF!Hmn_bAUj@dKMq6IaD#NPQJ)1u0 zCm;_)huMO2nUHm{n!dlbHB{J~W#yLEjl6AK=Yol!z#{e10oxV{g}s}*1V(pUoO_gN>282h52yK$%dUmiyO{^KfNHC?cN zpX?0Jmx;hnG(TzO@u$GIYjoQJ5k9D>XK1hW))54_Irnj+r)YzU@)H?gAb`x=GV z7_|PT=atZ0aj;&j`$qUm3_Ru~mVRS60@g;@Mja^7!%nlVZCvi!1X4c6DrXlz0tfcE zpK#$@51nT5jr)ky00!FHy=>0si`?TdT2u0yE$c}X^s&ijpZ;c0z?1qVAp03QS705;yG#RSXYb0 zbXq#y4lYNkFcxb_ zH5f|teuW{8e!UNlZG$1NeOnY9)?pLfO${zg3D{(X<5ipahiN}Yvl0wM)bPr?InAwY zmDn^s+&p3I6*etkLjt25I3k_RV@8ZBj@Vze{P{{*92+`6u;=j++A>eHwQ31m)3Wod z+%8YJrmcoC$uAaqI_?=dZR`j=o$q+`o4Y`dz%pnW%?&*Q5)a$YSmU&eOFvEw3#YHW9bm$Ssy8vB|TKffuWh<%s0D!rP!1#df+qmpQh@wTI_wpmdX z*dbxwDBJgB><}Lp$S5I>Jop_dhk8em$L!Owsge@FXZa%@j-hJccHZJuE0q$?L}{zh0E4!2i^<`4!k5!_aIJy#Vaq zx~NCC=L*{M{x<9Py&Y&z^I4U{QtrS@I7xO(*>U8ptoHSyz*=B0_3g;5Y&)dy;hl1D z&JU!(R6bmPsun4nVR@qKeH@s{=Z(uds!!*9(kiK(kK}aDXM;JF^Rb`G`BeKvQ#qd< zf8~72sGQHk|C00J{43|f64iL#!~(QT?&$n(D=$$EV%wQw3xp0!BiV_U8>RZ zlo6$`UpP6#?9;$TvYozO=b-!R@*p0_rI@@jY_1f2y&rWvY6*sHf+8Ze*I?b?EdzidYnqDCF1mMl>Eg@Kk`9TUBN;rpJ!l2>1$ zxTA=cq9cG|FF5YiR*vD+&+<>>vOnR}*P**_q%OgHmB)lF?zv-Gb<+=aDxc{41F_1Y zn|zgchM2vBh36;?8C~r$Ah-$(9~l&}3@?DP*K?TkQjO^KM$F@4I?MPWb6e4OrTy73 zq^IA_P+%QSIedRZ^X&^bWrw@pV2=@AuxN#fWbGczy3YJ`pY(C)4QzY&NL|M|H^$#; z*&e|nA^~g?Cs)#stI9qp9GaXCX%VHgtBVw%xAv`54qz+RS(bI7<&-L%^_7o(!J^aj z`dyc2FB6|rgLj?LgnX~{v8?nqJnM=*>g77kq+Ij_x^3Fx@y0a=&;4K%cl=Nip1pLI z(PV`geSc{_iAI^utDr}OTP=TJA$0S|I|%A>@VxKo-VZDy;OvCkJPS8i((AVkj8&yG z+Td*+m%}bK@Y9aF&$zIEBWhnZt6ieIAKD%>s{Q%e8CB_MjhsKsjrry01dhhW)A#3l ze|3*y)^+eHsinJjb~v;>z{WI#_a)|CaN48oUM}P}9!}tin@g_`EBhM1bLDXyR`g0w z#qBeees|bUWJ@6G!zR*BhmuJhnAG26_Q|>iv%h7jyy@UY)??nl)@7GE-9g_P!&91H zMd<6Tkr}?_blo&!irE{s*FxsYJ$IYE zJmH3-IfF~Di$klKqDIR6&+(l3y9&PR&Uj{5YXGhrN2+cP#N%zMr$1dZ2X*?#Kc}MWdYaHixt1{tP+M|hs6$a47WE-2t5nE{X zWb@oJ+ib8sR!6K%EI?tOJp@p6)%Rxh1yzaG#GpG#&6MG|sylk|gr)tWzPw#Z0 zN8*C(&2_0z#Jq{={lOe)p_+efsO$|+h%aDx`mhQoY#G?JP{|Fi<@VZpJ!U@ova8n= zpXP>+sZX!udU!*Zw~vLm@-(neN&Olr|6ph_N5j51YCZP4DQY=%H5qhx8Rop5SPdQb z=!a`>9)g~8MozH55`#ibpBT2-)B0fn)n{J^=HV^60dJ+o-SHMRJ^uKBc)T|5(7S9d z71a5fTexmn8|}VaM&i(}D(H5!J>gxxH|9n)6Zb86p@lG;S_1P6yl%Brj%`gH=v-^R ze*KOawECAXK5j0CUhCWZ*iMx|?vEcVe7TlG3r?X2N6$>)kb`^WUhWykA*m|nH(c*v zJJ)diSe8|2Anpk0Uwaf<@G)_|S#}m$ixw={qVg28wWmMVOC5(6TyxrzM!WIq_))bR za<$;QfpwJH2~B7*OVD?Biy3rU7{5c)PzkctZszPtl!O*6=azPqIN^YoaU!0HM{vL^ z1IfFwhw-|C6Z;k>uSfAmwq1I;;VCL_{UG9|#|hUJ9G#3X&IMa;=@zvf(FNt3FPopT zu7y5UbD7fP?x738oe}CQOo5fb{PEi@UD(G;T3)-w3}m08h z2KU)q1HnaXD{sijo30;2xsQCqTei;xCVV?g z_4v$Du;S|3GMXVMSjt%6{rWQOA172Fzo8kV_ZmM0!n082w=C}N`v%ZIPVB5LeEcpxvI6`T%vd+>&M8K$VLK@j;OUp$*J z5d^%FWO%YJ78r`ux_LJb0)zDi1z9Q2u;+Xsm-p?o%pHHFc2uteD)~@)Vm0?JNLwGB zV=skvrrb9uXlVu|&3O$H#=>ybx4Q}kXB)ULL%UjHB zgtYa&C?W&-9eZ)r`_o)-Vf8hU`k*GLo?rvyGpdmA+~K>nF^Nb>ZuJj~n9YR@*;=i4?kp7o50=;3k=z3sA7S1?_!gHKBTkdZgQ)OI%3YACweH4 z6$+&LhU*pI1PkAIR0>@F0a)w9UHh|g0BhjN&4ayVMw2G2Ef>{0u~dpuzVl;FV14h3 z$hV?xD5|~qm8S9%D3vmgr;C3at%^&A+Pexslu320S<(U8A4(dVH*&@xkj|_#_h2

6Ce{qsP~yfm{u@(~bAsQ%!-Zw$EH3%)IU zw2Sus{d7!1#Sl4Iu%Fz%&j|=WnN=w2%2hsoU3_F!;{n7m*XoPvT@RqLj%Pfm=m_xe zmNCAQ_X&LSe12RDrUJJXpT|8~YM^_@2EVzzp+HwjSfNMV91S)^wTWq@gS*j7E6P&( z!L1|pl69}cAls54janCD%zu_?-R;3V$bZhLpeCUcjp>gbT6K_?oaSQ4ZC0;Bx7YJ| zpHoPNY)cgj7tZ3u{O9`o{Wc^*{tGG}GcNU`F{3l3Pm4rRN43&zk0q$g#UWNe?8&9p738!_^&7Y*AxEh3IFwk z|Ht%%Gp8nXnVNZJO7Q+=(8&?){C{>T6uQ(!B&uFYS|XAVk#dLxL!^_wU*CH)iGvcp z=z`z27B4!a0iik%<^dVvm z5n0IoL?R>77LlZgltd&TBHa+lg)Ws)f*BFIh(JYzB_aqBA%_Ssbm4@^XGHcQaut!8 zh&)7O9U{jN8HEzl=pq;quZZYG#3CZ{5OIbQRp`f*299hyX=|BO>@vLJg7Yh|EUhF(PXb zIf}?gME?2X`cH{>e_a15v5bgZM4Td`5)p%F*Pjw`rlmZZFgzu}5$TLbUPP)Q5)+Yz z=#ma4>=8kZ2x&wBBf=FCoQP0F1Rf&u5qXZtYIHe_$XJy8M3;>yxrZb(>0%ub*(h<0 zE@}}miV~5C_(M;066ubT+~`snC2`TEDN0fzQV>ak5+RQ+z!Bk$61<2|MFb`y4AB#$ zMAjp693`U>`HRR_L~bH75lNmBk&lRTL{uYU7!k3E_(Vh_l31lnenhIHBsLGQdNt=WwWb>~>Qjeqlcsw;vAGJRE z*ZLV#^;0F&52q@oA5InU(C6s+HFwXiUAX_8oafgH-ruwAkQz?<^g6!^_&ozRZt`*W z5Aq8PpPF;$*GdjDvCgl?)FGy32%4H#=hv#KC#FyK^J@*?@8_Xcas8gN=U0iqpU*@u z;-pX5^Q&h10;!K?*nYoBsC-D2c ze_bDHEjRrVQ7eT0Joi5eXOau`=iz=|D{Af3+0ZW+wQ_16r9b9BqE_?#zG&1M;Xj{y z>bg-IxapUUS|KuhKEx5?icCv|MX`7kar^J%L08AUw2Y4)+GoeZ1DZuvtJVJ z``+*(=jun4=Kk%f#XL2T_C}U%@A5q$rC;fSyxa9(|FXZnfNkna-xnU&k(ukWlXeA+ zV1C1BLqy#p#C$l#bdg^M;ux&0wUyQb%2(jE_ESa(bg|7FN|QHen^yNgv*+`rbCk_N ziPPRk*UE>{CmpuU!7p1t^L?q4oVwkhhQV*a4zCPU^SZ1P-Q9?q660JO52%zGPiuW( zxtsW7$w#};EIv`qRhiXDlK;$-qPYjluUqIljyi8Q`pzpnQ5(J;am3zP`23hVnx{44 zHm}^(P}{S2PgiU0i!rgY)|pZp9)6+Klu`I4AGfqP4Iwf<3*`dasB zn^7KEncp?OT=fHT5A#qd-W>)~9*%9ado6=<+~&4~)@%j&$`^TD?p=f~<&RQFMzZl5 zKJ{!7sWxaET%U5Z(*=y)w-1(keFLi*^tIny7mpPgjtqVjev4l1c(QseGZS3=erbcu z@M3gn$6%05|0A?B|MsB#h8Ms_?CXVl&gEcBxsrQS3^$4jI{UD7jU8C_AbytK<83I+ zGT6QXz5ppa!lR|lOF$c2$4&bRek`=k`pb_RgdT)Dq{o)O#LNTrsoHXH(O6|o{pN$~ zP_MLzM5(+OYI5JbO84whkUM;6&++mrC}{oQu|(c}usW}LSxJ5>irCRR`&_~~v?O58 z>=&PxAztmA`KPQxfu_52inEC}f@jsjpRA7peoL1KS{%5Cg%V@VAJf)?s`ng1t?!va z`PG+Zo;`I6a<00;D7(BC)C>ll?HlUGGXmS}5?w|x-`&p4>z|4+zd!fb&jJnb@vDBt z#`(uUk8F_r>hgTdoEVh~xnZQS=2YHeUjyUSP)wbr~;XBJ9_rgIjYV(Qom ziP-gV7nz)D|U&{!o(h|<+b2> zP@y$870xPm6v)7GdJ|309hRXNPxQPq-(^Cn(PJ%Ky(gi(B4m8kdJ;!Fp0!)Vukm7wPiS@dGi@1FJh2T+

V;a|3MelE zw0aL%L8)gpF%I1Z;CZnpx1s3=sLg9xr676-svJ?MNQjUG?ZU3Hr&&kP57$e1LgKbq z&{u2D*8nRl`oUSp?}0X!X!q_O75nweSnB@%-)8{Yr;UG~0sde33^02gZ7$cKb+p_6 zpg?!pB<|~`r#)5wb^kqs_8$*8NzJ)_i<)!&-qc*{k>K&v9P8nrCcxoo=F8okaUEKBZM2BR-?!>I>|>-d4#Ydv>YMd2*pN-G(z|hT91%- zgrcJpafEK8NHs$K(J4Mc z#v^1Mq2vhhMhHSe0}`^2PhIX zZ?E4?jbGnwznfE|aKD>c|G9N)Lf_w8r>6A%-JF`#_jhw@THoKz#s7II-Cxa_^s}0t z-1m?6)Or2Uo;tBV+EZsX^LMX7A3mf{mi#|Ed`Q46Iz&Z)C;~T8pb~+O2tY(&AOd9( zz>2_91biY869JM4T=X|6L_i?=l7gZL;6z|0`u4wJE&^r|$cg|{6#PU$COVWv03!VJpWr8Q-BzOy$HC4DF_QwKozFoC;~cR3R%NfQ!Ib1g!cCk|N+4fyn+o&;QoO1Y{#n8Uf4*EJnaD0&x)_i@;U% z{V8CLz-I&`BTyItya=pCfmgJCfrIK7rur(w!kZFylyIPQrjuf1 z3GYhSRl=bXrj+oZbk>uwvlItQXIcrLN?23EjS>cwVrmH=OITOJtr7;6@T7D$lwxfO zH%k~;!m|=Km2jqXW|T0v6i-WMV+rRm9VUIE|p?T3A0Q1 zTf)-Pxmd!uQoJf*PYKIQxLm^65?+?DuY_YIOe(FH_sda)KLSUdzBy?BA z5&{X*fjIfi5U^fB}5)hC;eFV@WupI&C=nxzQ6%s&@4*L;sk3e_?sH5OG z0vi%=kU)S0=p%3*0qqDhM<7H36cRX)fPMtpBLE&9rXz471sW1)kN|)L<|AMpf$Zqe zA_X84n2>;h1o9)m9)a)ZFe3pIDaeojg9QE~ARisdqaa5DEYjga0umA^kN|!ZtVf3* z3CKvGL;@HRSdf5!6vRh|A_?F~U_}BR5{QrhfduZOU`YZ#5{Quii3BbrpdcOkBM>D4 zA_?3`Kt%!_5`d7vfCR22pd^7F3BX8TL;@C4kl_CrJ;?8Skg2g5vq|8ii9>KX~>Bs3u*1L>3>MNJX{lF*EVOeB;cAqENkM`%hyMiR=A5Q~I9 zBqSl73M7;zMNAUk;+hlJv!h)hCP5>k>-kAz^P(})z^Nk~mXT@r$l(2#^| zq*IC%^+^a$LSquLl2DR_cqH`V|F%8IAHP?b`o!}qmdym-PW{$38oY11`(AM1IB2qe z8L1eo2AXdy8-LLL2DFNl?($v32il_5xM$RD0-xTU&B(E^CUI^8&J$>!4$Ko+o`CWM zlBWQ90>}S`>IqO!V0r@56NsJ;&{OdIG&oOt4df%<|MEwn+B^ikgSH-l?#|THGZ?*j|Hfy0wJDhS?W#h;33b4C z`2T9}%fqqy+P2M82&KpnnF=XH#@0f~92rAJR8%Bm86rb6ltdCri4e)yU}!BOLo%e0 z3}v{@8B$32?r`@Tp5OZ%-|>F$a~$7$9PK}>d+#;ub)Vb5*S@an+}D}Po*Q2a_-<+F ztc^+n^pT4S>+s9xUx&7SND+F3_=HntxiwCa`lG-!-?2wX0tIWUW*?>u21i7%db>{& zz=Oe^Zc!t-pmLOpVD{`bXrS+Cd$A`9rS(kl``&m!>i@jG+UINRb0b7v9Ym$E2%qN^ z7n+cV&V$u8JR2tzGj~mNUikL?P%@(Q>8){6)d#GBRT2TlX(*K_d`VQlM5!0TC7KIP zqSR71Y2zFvlwzqnRMfEp#cfhAG>)(W7v++kgym6#oa>o%@4qJlTrZIifB|AKS(}pY z=z$oXms(IocOj;%BlbUDw;{HZ0d7UCGl<AZ!tcZJ|)1p#S0`Z8v zc;e6K00v_#yZzx)Fz`Kc?oQ%C(64>yS#Zr5=-ahXqtfLV=n3Y^ta@+*bQc*_i#*1l z$Btcmul7gKJG#k7k^MDFo~r3?-dK!M{OSpG52a8l*Qrq!9UqjgQ7L|=-xXzuT`n|G zd5qHExju0kXGE#esh2MaHlg%Dn%E27p(Ol(&JO1%PLB$J!N4VtX(MMOZvCFNQI!&T zSe**GX=96`?Py+fSkIxG>0MRlKDz=JyN>%3)GVO?puETH0#VR^T-H?u1cE`q5D~SU zEHK>p?Zo|BOE5NPK3_L4`->?3<)_lw)rYOgjBpGWga6%T`ya?xVO z{fZ66k(g}0cFWfE0ZiUQva)Bt#AH#=T3(hqm@L zXu6?!;IijBH&N;}rcuwF+yO24>PIzErlZAEd^v_Ol4!AGgK}O37g{{B^^?j8aUx+G zTTJCkq1mur`IrZ9Knl%S(=uTUQX;Y{G6I@G>KfE z5B92#nHzyr>pdu@Jr|^Z5jmQ>b43u5_(F!ZO~$uCvu$XfJ==uhyY)bPVas(`90lC% z97WBBK7;7fkvXrZXh9sgYD8+;QRIr`y#4PGJ;?{R+OLnjPQ+iyV#ryGi2r!{MVgmj zxJwK%))A$3=MJgoNO}A#{?Ec&v%7+c_}8CJVg5+Oztmr#;58Bd9uG~5A5X(i(C)e3@l5b>9~=d(u`QXDK#iX}=~&jSYyUZG4P{_kum=#+{0 zhu&FmF(l%z=+!ZIfrvk|*+Z*VBL3TmNth*w_&2yW<=!IVAMEtCY*WeR%gy=mds2Z> zPrPA2|2?3#=<=9rrU_WyX1Sy(x*f@~`lxF)kE4?TULmW5ijZxzO-j#ImSqWxFsl+( zlltJyXWr=T8=3u;OvRwux4SIY)eQ8H5F*30jUl~=Y>jTaA6#3@#^(4@8MAQYcBhuO ztw>*NEDl2AZXxJ5?9!ka=0z!7`UN zVC2cO-Y%?vSu*1&O^J?BO#ioBCKOY1?mBb0ABgrS@|u24243jwuXK9c0@_?D_OVop zfWaDegM6-WFit4i*}3>`MQUTTM3w4_+TcDaMCQ2=`h7zM+H796O15n~+U#qXZTRLB zk{VC>*l>vlZ8Z~8jq^`J><0pl`o^qVlIW-kpDkgT+}*GGEDiPQb=gx^??L1K=VNyV z`k`^V_iql*4I+XgUAMJQB6_euv!(UmVbCA>oThOxXGPk>QCVx)B{S;CX_R!L=fc&` zizwT0SG^u(B+8>vj8JWLK(~Y?n=6CV0itEf(t~j z&KDjlAf^bP$vPj%Ac~UZCb!^L22?RU6LY|b6E$obtdl%H4QiAvOomz-LGOWi;nu!b zW!3GO60bd1f!6S0Z>35fFvaE|HhsMY%&1%DHf!C746E3BP6%hg)dJyR_L{N8_*+fD zrP}Eg36dJp?;n~?lc;HXHh?MjPHPm6Ph#?l;h5a=8Z^;8Va>;~0EYb=^FFDVg0F=` zW&2p=Nzx^x{$TcQWV~pbCZvRnhUw+?ki4*EW4nwJn0PBC+wuA{8b0aH=%mzuzGiX< zDkr$11@WDskKKPs`yoQ2`_ayP6Exn$HC|+1j|RLcTgX`@P%#QPM~G(xQ&pFFw~;$Q z+N3g#>Q`fs&9{&vPK)i=`R{JKwo`qc9AryXwj7Qq0J-j=DP7nGBtl);W3+szr2Ehq zc{w%6Hji@)rHUX)tdwX=gayxCe1pPTe~7jc%z zHJ2bcWMC*e?i0PAi2u+5z9KQqHFST!>8R+6qzfX=AI)auR5`3UfhjdEag}==#^jYx zlMfkJ6Y*DQ;q(Xx!;z0)xcIFDUvZd;<$+O>6bz|9m`z#p)aQXY5&wj+X@_)3UYr!a z=$`^6n!M=ZstVAsr|yDc^Q_50wGu5T)KIsO_b6|lwr6k?K8FY?`;L%Zd`Kko zY-QbP{sRrTd9mt>$)MuA$ckDmS1|QbCp&(q4bmoGl>T^F3$k5MrETZ?LOlO(63QQx z_unLx{{RW)pNZ)Ib2b3!9zy2btK$!xHU#@4>KGSnZz65cTlxk^_M-xktqWUO{5O8xaybeN_sheCt4L~3OXE^i#`p`vdB&wSmB!&T%#%SaE+ zd$mJgmRDcxCc{Ta<)|pAct9B~ik>*{>=TbU6X!g)cL zqkgde%W$W~x(2XWRG!Bm^&>JmXd@uv%ni1yaoogPwSev2fh*w`Fa2JFf3Lwm?}6WI z@c+&=7{#8v`5${ME`=EL5=zm5kKJHL8&H`;*I5oEyNIk-2Nx5h>_aZsTY|&@f1Sp^Q|-Z-Qj9 z+xD~mFHnBjO^*TUSagSfGu!^od!X!-%}fQ6knQF)kB3~|ph5CeHS<@~K$LCJ_OiK6 z;G2X(ms>?4q#ZfgS+<@AuA3Zuz2HCvdELa`vel=L_>vWZ2h(!Y;(Ys&w5v&} zA&p7utqeY*9H^hu~Ch3Dglh7Tf4 zQ)d;Wt;URRzle>yX@a3R*GML!T$GsHNgbW3G&Cr&E`Pxx8jG-51f&3ppl^`H4@TXkbo46PG5uUL=pG&1^oSs2>fZpjT&Pg2 zyBY`~d1ppt&||1*f4{#Wdj<+3Peo(5LeML$w(Iyc7VvTOM=eBo=3eLten9e=p!<>|eo%Xd9fxVcF)Xh#uozG>O~jwDI5+Nu*O&IC z=uGQiLWD(#FEJX$Mr>@35(rLlR3y zNF4GXR)TU(x|`Bf1EF&Aj@sQN8158cO^y>bgRHA6&U6$#Aj*_G`<*)xg%x@3&Q|vm zUl34jX3(EifResFd;5)JvD_=e&y`PVu`uBSO;{xZ7CEwgO?~+dkm8|{7kk2TZWaPV0!X}10BzP+W@~`MqQ@gue>?>AFu)b z6z=%-;Ll8YaR2W*|4IG-UMiI?A1QYFYYj>Fo^-TWpY&;^{hhz=|9uY|rEj0}^6n(* z(Uao2CTRu{py<94*yAG5ci4@ay_X%W^0d%i1h++`}j$9 z&cJLUS^Gz_Am0SkX41bu7|0AQr`IzlDbzy4x8ctnRkuQ+l7O7di_XiV5Fh+%W6r8k zmCC`j{kg5oA0I(Mw#a0=eorWV&vX9)Ee5!w#g6xbS@^I1;zbSL>etRG#V(Hk1*<*` zbv?F(2V-qaw4*ZMiQUhNa;WN{Gc%3!;AAR1D-sme{zL*=t}-;;$0*Bjbe9c9JO*^ZuQ4sC2zl_9i?N-$NuHI z{=%Pc&DZ=VFaCc0@EZG#loTo(pyZm$mvnd^RAXb=wLixRYCTIX@Yp;IEoZ-MGnH0? zhJ^hAw-f`RQ2L?xf~!uXaX_UNFkfHkfZ5g3I;d=2i9g)j!qhW1SbRcBPcps@??}B# zTkvHgQQw({!n!>Ni{Go*mSpLsWVJkBD4@h0$#F0h9`p!3%zb7%JRu|C#h4!hohdu} zQ$3>LS{n!cafM(lhwW6R{0>3;RH!Ix0{!DVgGaWmJnA_D|bHD-A zocSCI&N$q9tfgM=K8|kg-5hbS6kj#aQNA~H1M6wNkH{_=CH7bEsc`Xu{M1&aIA<6; zd$(M794o>Bx$pXaL|JUI@ zQq2-4g0%DhD~f9t% zZju@|NrjuFzP+rvO`Pk$r|B`ibqt{t}m0|nO z3ewI}&wuviELAPVbAQEU|C*6zt8##@Ce!UVe4IB{LsIcT>W1e+NTQapZuG#b+sC%dT^bmaSpgC!;3`_TH!;vozpGLi}D#+iOoFW2p+c z!pjlB^i~Gf?!i!C<;c-C%ykD?Umx|pNwx(XNXj>IaeTGnlM%#B_0N=Jwt1tkre{lM zow~rA?v7*NWId$Gh^R>=yoU7BYB%R?_kj7iV_yV>Bp?j~)ArBz zG_THz6={Kyg)06rI7KRx_Iq;m)VY3BVf0ZiYQ=c3Xool9f!e4;4kME|T*w&0> zWd!Oc=C+e0&rux(-8;T?ZZyarV>-jQ8I4mj(5?%nLQ^|_BytXOqgk0}_|b6!n!a&V z;rWz2`oSr(2lcX$;v%3g%Q!2T`YNP+ZCaw@{{>P;QYnyBb7nL~L=o_IfI*R54~yX6Q;njLQ#*=SB?!Vc+;=T4q`vKDe!w{}vf1wk>r z0=V8d7>cONOPdZkV6xp-3VvrPFfYM)tMBd@Qd|Txt?Di!3T$G&K5k2R#u~Hvhrce$ z&qA{Yh%&BpEs#3#mZM?478E~Yd7%Fufb!Ydx)(35CdEY{y4_D9U&H*PH;Gk{ zP51F)FNIeDu;qF`rJ*ov7)Jq__woDEP+h zP`HLEJE%D2W1eBkQ1uie_gx^jlSO*&c?p=jcyD(u1qNexbrs{f2ifN7*Wcak6_8yyKn@v`89T|PDnUpurC7wN|WZqa8;3`#Lq2JJqo`BzZko6MewYkp9`V06aV z=Q>`yw^=c5MhDBZWb({Y%ws;?fkWlS_ff$6H&oIus6gW>-`o!#PN;R$Djll6G0?c^ z*&^*c0b*vm7^gj}fNI5F%vC3VuARxSJtA9%G88#9d@t!j;bN_at5|yANk4KQ<+~bC z;$x_QrCJs|Li6kqg$XybXfN!@5`BpcSygu)UC_dsH-vAzaDE5PLr3U0$_0kd*_5fu3#3mJAU&YgMx60U0(X}P=62-4GigsNR{F?9&<_7>AZ zOkKQt|44rzWX+#)9zq0gnn}K!ejo}YWck?G+v%X>Cl9x#2wef8eV*!{*auM{OJvEO z@}s~xO=`!17y|O6Gu&(Td zHK8VJhy@Q%-xJR=$E&=bW@Nh-Kpwu3PXFDXv8+w-D9fn=%xU`hcu21oR1qilZj_;b zdoO5b%Y3+sH3;!7Zy2?(PJqS-A*B&aulZ=iKr;mYhk8}kNI1eZb@Jpd z=p?atKd*IUt}s-aX3abp7xRa1g9TrxpaWHowV7-cZf{FAzHnq;| z$%?s*rR1B}E3cx0=flhV94mHWcF(@#J?UZ4>hkWjd}}D6y>yD$;G-<;#8Z0VVG|ej zIPidlKcfa3GkSGNmC!?-V_8(e0ZG{T-Tp8p`*El%dHFz`h#9n|KH|<{Ne20&$okh& zZHBfUR6KdCyzs2sNBz0yui$~3=bxCQ1!5g@`djr?P0+dKOlmJ<8rJoVs=mFk9$SsE zNzz{6!~A!4evrp|u0{`)Ugt}=pWCCo!<}SSMo7H-9!A9Tssd#YqDI6 zn)({ZpRVW+&wPZou4=b3K1{*0?w?OqYBRzE$x`7pfzDXRFhntZ#tk~x(@0!Y?Zdj6 zv_|7MwqUEF6L%Bp1u*|(0Z;cIPS{qA=3U-ZHGKA>f1=%OV{C5fxtTYp3L3nu@X5%t z!(JaZ$~?;UgZ6e|HcrL*@QQZ(hoKiVIFv^3(e5)&*e+9$^4y6gBK|H3*KVr7fOT66 z2^t>6=e6JQ+~4us<94LvW&Z(R&R<@i`Gfra|86-UD^}z3>9OzNsCErA{d6U8y64!- zHTf7=+%V#|W|u~hqDQ_a+K+)?Z?aFSo?B5!$5ZO5&;ew{amVKhFE==9VLE~?76PZ3 zhkM-LC;*EKwO3b#P@zZ>*4Ngb-hp7Rouh)I4^hacB=H!&!^E5A-&;<9qOAVUnK&fs zDfs+o-|c<#cfn|qk`~V_2N>PKOcTI-6ny5~rEk(pq`q0}l-w3-0b^ZBuM;ChDtF-d={@6?tVwi*%uCwv6juj^XHW(UZnu@zP&8 zmshB#fS=`&#QqQdV0}I(ov>~Q*kBX33L3rGH5_z2L9u2Uu@q|CT7D)&jEtU^uNx65 z=Q4?U3SKJjBVV&x4!jawe7VEa9W#b?4r`IE+|ic^wB|jvyB9Qa=whAGEqQafCVl3u4>yH8_cu1+CR`nwF1q zLn}F#Nz_x&Czxg|PF4zfkJ74bv#td_yknwG#Q&a8E0oqQDe*CmyBfsvKjiu1dK|3e zTqaRZQF20ESSwj8h>N|3CBv?QvYvCd)5wp5>YG2eI8edmP?SN)1|{BouCSvCka8}Q zsHb;YtECtGSwW_^`MI2pbO3KOi&c+*`>Q``oEH_XJms_Azj7{zyV~1}p86McawX?7iF%639K~6_uF}91GfL~@&dFkGqr*DQX$qKT zSD)3kGb+pFv5T1UX5n?wDuia1b1svpr;tMK`y7*`Hl)JyI%XA>ke1`=Rei1i_|p+U z+xZNJJd?+Z?> zy`o3TxlE#-g5<9j0|yrqQ5@b#n0`Hr%DSb>S%mie!lQyK2e)6|k4i2i$t*-LBT~-g z73wLv3(_P%pFV>!0~wOfY}|&hptA0&uJT{~Nw~hKAvX``5+mhY2Jcs>r=XKX-yK{+31JWGof7%ZzIC-@~7lm zul<4lhe*x0@e8D!%gfZ$$Z}xacbWOe3pONBG(a}OD zRe5hgGjPV;0A(sa0d`HXb-O1YuTW2U@y2y;#j{iSG3~0N!1J^Tpf{(pjIN*=a%|Wp zDwCZ9Idcn|7K|7nGiR%*e7g%=$H0`UL1(l~Jw2`gjBZOrGgN*Cq61z974J@>VxzcRQcKFPqxBRi+_%k zELHu*fchi!v=nXmQ=t4`+x}r}Ew%kG#`$;smg@d=jwQ3^Pg7qS_n)W!_v!t+DJ%{9 Z7u1%H{PVy|Re$*|e|*os&rg!<{{Ro_8NmPm diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml index d1d674b50b..f210958b54 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_down_jump.yaml @@ -13,7 +13,7 @@ actuator_limit: 1.0 input_delta: 75 snopt_scale_option: 0 -tol: 1e-4 +tol: 1e-5 dual_inf_tol: 1e-4 constr_viol_tol: 1e-4 compl_inf_tol: 1e-4 @@ -24,8 +24,8 @@ use_ipopt: false ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ -load_filename: down_jump_2 -save_filename: down_jump +load_filename: down_jump_4 +save_filename: down_jump_4 use_springs: false convert_to_springs: false same_knotpoints: true diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index fb3e2ea2f4..27b98eb5b7 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1122,7 +1122,7 @@ void OperationalSpaceControl::CheckTracking( if (soft_constraint_cost_ != nullptr) { soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); } - if (y_soft_constraint_cost[0] > 2e4 || isnan(y_soft_constraint_cost[0])) { + if (y_soft_constraint_cost[0] > 2e6 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } From 924c3c0d87b2e0299ba440b8a01d24155b445551 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Feb 2023 08:57:34 -0500 Subject: [PATCH 367/758] adding bounds on acceleration --- common/eigen_utils.cc | 11 ++++++ common/eigen_utils.h | 10 ++++-- examples/Cassie/osc_jump/osc_jumping_gains.h | 4 +++ .../Cassie/osc_jump/osc_jumping_gains.yaml | 13 ++++--- examples/Cassie/run_osc_jumping_controller.cc | 3 ++ examples/Cassie/saved_trajectories/down_jump | Bin 52477 -> 52477 bytes systems/controllers/osc/BUILD.bazel | 1 + .../controllers/osc/options_tracking_data.cc | 14 +++++++- .../controllers/osc/options_tracking_data.h | 32 +++++++++++------- 9 files changed, 67 insertions(+), 21 deletions(-) diff --git a/common/eigen_utils.cc b/common/eigen_utils.cc index 094b732e88..fdaa6d9d1b 100644 --- a/common/eigen_utils.cc +++ b/common/eigen_utils.cc @@ -4,4 +4,15 @@ std::vector CopyVectorXdToStdVector( const Eigen::VectorXd& eigen_vec) { return std::vector(eigen_vec.data(), eigen_vec.data() + eigen_vec.size()); +} + +Eigen::VectorXd eigen_clamp( + const Eigen::VectorXd& value, const Eigen::VectorXd& lb, const Eigen::VectorXd& ub){ + DRAKE_DEMAND(value.size() == lb.size()); + DRAKE_DEMAND(value.size() == ub.size()); + Eigen::VectorXd clamped_value(value.size()); + for (int i = 0; i < value.size(); ++i){ + clamped_value[i] = std::clamp(value[i], lb[i], ub[i]); + } + return clamped_value; } \ No newline at end of file diff --git a/common/eigen_utils.h b/common/eigen_utils.h index 2843f3d037..17d6cff4c0 100644 --- a/common/eigen_utils.h +++ b/common/eigen_utils.h @@ -1,7 +1,13 @@ #include + #include +#include "drake/common/drake_assert.h" + /// CopyVectorXdToStdVector returns an std::vector which is converted /// from an Eigen::VectorXd. -std::vector CopyVectorXdToStdVector( - const Eigen::VectorXd& eigen_vec); +std::vector CopyVectorXdToStdVector(const Eigen::VectorXd& eigen_vec); + +Eigen::VectorXd eigen_clamp(const Eigen::VectorXd& value, + const Eigen::VectorXd& lb, + const Eigen::VectorXd& ub); diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.h b/examples/Cassie/osc_jump/osc_jumping_gains.h index ca80962910..21934de792 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.h +++ b/examples/Cassie/osc_jump/osc_jumping_gains.h @@ -28,6 +28,8 @@ struct OSCJumpingGains : OSCGains { double w_hip_yaw; double hip_yaw_kp; double hip_yaw_kd; + double min_pelvis_acc; + double max_pelvis_acc; double landing_delay; bool relative_feet; @@ -63,6 +65,8 @@ struct OSCJumpingGains : OSCGains { a->Visit(DRAKE_NVP(w_hip_yaw)); a->Visit(DRAKE_NVP(hip_yaw_kp)); a->Visit(DRAKE_NVP(hip_yaw_kd)); + a->Visit(DRAKE_NVP(min_pelvis_acc)); + a->Visit(DRAKE_NVP(max_pelvis_acc)); a->Visit(DRAKE_NVP(landing_delay)); a->Visit(DRAKE_NVP(relative_feet)); diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 0dc4d5f7da..d1d2935f2c 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -18,7 +18,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -x_offset: 0.00 +x_offset: 0.043 relative_feet: true mu: 0.6 @@ -31,18 +31,21 @@ w_hip_yaw: 2.5 hip_yaw_kp: 100 hip_yaw_kd: 5 +min_pelvis_acc: -5 +max_pelvis_acc: 25 impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.03 +#landing_delay: -0.035 +landing_delay: -0.0 CoMW: [20, 0, 0, 0, 2, 0, 0, 0, 20] CoMKp: - [50, 0, 0, + [30, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 40] CoMKd: [ 7.5, 0, 0, 0, 5, 0, @@ -64,7 +67,7 @@ FlightFootW: 0, 100, 0, 0, 0, 10] FlightFootKp: - [150, 0, 0, + [125, 0, 0, 0, 50, 0, 0, 0, 100] FlightFootKd: diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index d2ec364534..8783bf4a27 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -374,6 +374,9 @@ int DoMain(int argc, char* argv[]) { } pelvis_rot_tracking_data->SetImpactInvariantProjection(true); pelvis_tracking_data->SetImpactInvariantProjection(true); + VectorXd pelvis_acc_lb = osc_gains.min_pelvis_acc * Vector3d::Ones(); + VectorXd pelvis_acc_ub = osc_gains.max_pelvis_acc * Vector3d::Ones(); + pelvis_tracking_data->SetCmdAccelerationBounds(pelvis_acc_lb, pelvis_acc_ub); auto left_foot_tracking_data = std::make_unique( "left_ft_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, diff --git a/examples/Cassie/saved_trajectories/down_jump b/examples/Cassie/saved_trajectories/down_jump index 80f06ae0f78b65d258a2b4a58599e506bf69bae1..670b25fb3eb7111fa7e6225614d0931da15c86dd 100644 GIT binary patch literal 52477 zcmeF)2{cvTA3uC^hRh^GB2$KpQO3PdLK({t$`FMz4@o2{DN>@+pgB@1qye#aBF%+D zvnk0CQO5AxIQ!PG|N5uD|2)6$|n(A46jZDbJij|d3%3*6uy9_s1uvo1U+bjz>R z21|U_`Gxrf1xiJFhWdGWZSo0|@(lEr3JdoP_fhi;42}qwqVM5H+qga`REj#(ulXFk z0JCWSO>O(t09VIM7kVo9fpThDZ4kP_yy-i5Hr4(C>eg^F+$r4(8m88dg16#tp1xv> z2Jf5hz84%g4w~#=Mk)rYf#w^_#vio50j(mXyL{L1fwpKh?iqEPz^8X-Gjc4f!Dlc_ z!VIZ{FVEQY6<_ZK-EM;}GY8th*RJ-cJ|08RSGIBamkc}5&(iAZD!mO1tZ?;za`iI! zo?aJir2ig$sakQ~ptBsD_B*iGf6)r?4Gs*>FOh&OM=haBese2wuAW@*0= zJ41#E3$%n+CiNf0qN|?O)Z912d@tpfsCGBO**#m+OMLsVhNX3KlE)pa#kI_YHIN;Q zaJY#ZuGfOfwYw!R?F@lZxjwC{Ma99-@qI26?a|OEa+|1O;Tt$7|IM}GHy%*zZdm}A z1PkQ(teT^--V`!EVY)t>^#&M-K~Vw0b)aiM3yb-ZT+s5|aZO!c5~{lIoIhON4Ib2Q z_>9-AMbE8HWg5LcgId0)b?!fU6;(W#qkVoMFS>X=V`IeV7pMrf)G$izfHP+YA9U`s zfh^TUruK!;pdvP!3+6q?GkGUiT3u4{!h3OYw}QRV*av;EwNwBra;=uhtslnnmxW87 zx6a1gues;v@5lf>i6@10wRJF~`!(*FtcTEK)Va4Gc4IWaIDR%UavZhVZV(Fi`W_Uy z50<_9auV8!vM+Uoc%keiQXRMq^V-?@9(1?6`gE0anL(9*v7rpw-;m=jpA*P|7UtTcqg*xKu$vFK_oJ zXdZaHCoOvr>&<&0`>t>nwq#cg{w^O6b$ZW9iWH9HWp-v;%9&4Mo|i8`+J+zW`-g@aYKa>)0n9sBD zJzTo*=860}`q13}eRW&`C)QJ162g$xg)L_Ue!0)F6Y6}MrxMmZh?l9#f6rmOjkzDR zj#mXTV%hCmwZp9&@qEcW>t`H!gy&h6Z|Hfp77N9kJnvNJ3zW4Ama5WA9r$ADW70=~m4<3|+k~bQgRThQ{UxLtWn~ z(cA8xtCJKD*g=Qj`#ZL6bb(es#dO;{Mxn`x*>+BeDbP^%&9X>wFKGBIDsQWnDD8Y_ z>7~r^!u;ANWX6JOp^0t(uyMdrxN^2aMdY5daE(|k&tbtwaNUWqF-3bRxN69lr^=Wa zN|&%lDzOV=+obYudgbF(TNIkRN%u0vhC#K4TSxERnFmezo5hz3`a@Tr*;n-!nLuMp z4Y$a^1bW-uUiE|5sWIr_H$P@^i5s-)PYdE@dIwE1g!)bv>Ow=A6PzPoO`+kVANyI2 z_n;@i(e)8OFM%`Voa1rI5247363H6b3@Crz?Jm2VD^&N7yzO9d3u-Hud0lnv!E-sk zlvFfjLgBWXr!ML+U{&$>pKiMuFkegTRl)5taLLr$n*j}-9XGO8+>fR6F1_YDc^Mnt zymaf*{Z#Z-VaZ`raoTZ{B(%N@8$k6dJP)!@6k|E{)x4{i#j%+ArY*v^axt?Q#~Z^+ z8Pq>;>*tXbbI`Dil$}N3A@pR^vy)PxFHxfC4~{e6w?dJSw|Ob2wnF*jz@dhyNvQ5O zYt+8B2x_a&XRVp~}rOv8wXn;(MwKFyCVt>Ab!0_xVO#vGCB` zho!GC;OnTp!%NWZ0U6cQ2kthzr27UmXokWFJlw1*aD4% z!zT(bQ%}RW8AeK||KnTT;|vpMSoEu5%sfE58bZE)!S10!n>M*`@>w759uP#kWB7HE zgz4);{Wkdiu|e?HhAp0(|Eixl&ac&fl}{Zf*e`sY?_WF2`gNS?4S(&zw=vMi=dWu1 zsdax9@`eZfUB~xp)n8>iegVM|o5FnDX}3OMn!jG$uiGdda&v$M_$rq(h#r7^8!E%g zmxV(41y&KlXP09>m8uN_JLX}*n?AvVt4pDbf!pGYz3y0G{#PSD>mkf%oij@--wevD zGF7#89Kn42yK2*aDnr5S;hnel3_%(F;F#V|G|3jNKesIWv!VTGL+8)NqCXpp|7_^~YH(6#pfPm{^w!il&|6a{ zL2pf+1&=p%A31d~e;tW-Eoc0`vFrP_>c4-X98SaFa}At`(^2R`QQ&6qC9}FE0p3RE zzdvfJpL>Vw2|lmU-Td^168c&9?xCH^IAqWcdDk(A7mb6krH3Sv!3DM`rwV!eNBsgn zk<3H1`sYy>c$#SS8?`%M>C@^1%q8XW%I5E@FFL+7r_99h`R=^pm@?VQ=d#C`9m`h8 z9sWF6$X#Z_l4|Wz6#~Ur>NH7*oZjG@4B*Nd;}e%X=A5Ptw9&IKW}Hhq6t_p>dtFG)aD1;0rp6%9Plt<%-Yph)u1Hgs-SF0}Xs7K4!T^`)&tVXLhaP17Wq}AU| zkh$@cR{tcFqb8nK|7u+oyCGQBdVJ+)>2v61t+stN_Z?(We(>5n(fR1`qb-McQnn+8 z=!w0fVpXWk`lBE7!=>n~e{1}KuajUu|9Hvz8>65xr7OmuIu?ywRDJZOxC4xwNjt9e z#samUiuCzV5lS1rGuQ{lUlu!P~KyTu}Q3 z8!v{$E41qr`maQ2^?kXCZ1-vPt(z@G^C06Hwz?tHC|dpA(-UDUf$3z} zP4VG6@G!2WqA=VUDcu{Z{gfaEGB%fP9eT=u=DR%L(s`qf`VzKfF4?&q<*zh)Zq1yA zVu!D8+sUZ}z6%5>4;^}hnU@Wjm-h8TW;khc`qYgRY7@4o@!YJ|?X zZqxza1wECQo|MDP=1Jm}Tit2(Cz6K(a#7#Q1^kO#e$uYfXnm8DHu`RTEUx_*I*l6|oTi=hx1GkfWNft`#;B$9-TJmxSu+D~EYecjj+*@H^ z9elF^&5v7|zp}O&_4&T8bszhJuCwXyH)#w&=NI=Y;zmv|Z01&2Z<&o5tGW&sRz8A^ zB@J`mX&a!980H2>epOHyx%a|Hybhdc+jDawLKO@zVS6Yp%ZM4PZ=YZ5@DMWIIeUCE z;R5Q2*vfCEtPOgAXnXeE^KMO8>Srn1pT?lv|&6)d6KMx(7XIA2{-vbFp zT3=jdDFs@0i|0MKbOc>i-dAF0d=qW<*tF~DI&aWB<}&_loc6(?VSP(sDqbRJo~+YT)5e*IuF`3$@XXR_gYsDL#4E;PMJnuFQ{*;_ngPoXS% zjr!_cW~gdt`0(mgqL7nIpw(agD*D#)%~OhR0(^U^sq_BnS9AyM*wTJ{CO8GHbk@(1 z0#%)#(~jrAgq)le8)7r;Y4v&yqMK8|x4NzD#~$23cdn;ZJ+TZ2y+J3Atn>>39BGq! zv+#XT-6P)aTzt~#+lTnU(Y5D6;^MQnlCQHOv0EY8b+7nAOX;eI3O6yzeHDHyxNj!P z@MXLA-g68LG)#5)nDOh$T$U%dAoJ}_9EIGiXwqvzv$4Ml$omDw-QYiF9Kp?Qm5V=%Ttf>fl1HL>Gwks0v zLkpbcOpYa-MVBVn6dTvL1H|^4`P8C*^g`{+GmULSkXI%p+0P;qbS2bWZ#H&9T^l23 z1{=Hp-yiIgRAUT4Wi4xa87o=Ai<~(_oteJ0`p(r-rOKcy?dH9(?XyrfYWb4q;+>Z~od=3Box{W9Kh4b%2=9#wKz0DAfufVR~i!?!w z=Tda|T_HHeXtF=2!sn0r=7W2OPtxi&&&4jK_4_McMAj8%A@7WJ7g`VSVZPagEjeWo zU{&-S5#Qv`ps&4j(TB-bNO<)QpSZ)bz~{7bwwlQTbR`*Vh^|fpj|^QMI~!`S_?JgJ zlAa8KA0?d?HvGEiN1nt^!xIs3#@Pz}I`KyffS0sYeO? zz{!qot9#Iog5o+mlWI8Qe4V$(w-ROsfVQ4_vHHSKQSMH*%=nhQAk6oDwkj(hcwJJ)JXzm?8PY>f zrAa=5Oluc>dSMZPMv~if4_~SUxdRG5g^QM;aI`ok;WQ6;U7XUG|8Y01oYg+y8;2#z9kpGG8bU~Gi~@g_6gNezIn z*KAJOjGsYrpE$xg;1yIm|Mf}*xs7G~t-4@5IMF*2eRPt z70y-Fn4#b+>zlSE=op^cKJ;`1?p)UowO)vJx5dm=>D()I~37`(Vxk#iV*kv{A+ zJaax|e(F?aoG<`-oKhN?4_<^E4r3d)+!Df4pCsI1h$obKF@CM~)B`MDlqS@D`#ENQ z&myXOxES>?t=RkRLl)$)ws~kVavV#wyGgZ8ctNRJeckVaepvkS3>%j5$Dn5+58DnN zA2i?6DV=NUeDp>s&babj1rS@8%mr87123F?KE~-5AU=t^+c%rWf>z01rMkotP|>>O zDoH6_M0bB7M=%@So$%i96sG>!)l26VC zVOc{fu8)=IP$S2dLz}E=^{#iTj@8lXZ}7UQC!n7m#d1bhP9oRiKT3R>Zh*Fe4;Ab; z>d|_~pFh^ent*Qwrx=D0IU?qca^`^fuBeZdbH=RQERZ?9;Jf6gK4fI52>Twh8_xD@ z{J>Am+n8f9efovvUP0ZKyqz3(Vq6X;Z^C@ybOhpMqRr$ zoX~$X1nLS6oKV#s#QWq_H&4+3XrBJu0;umZ`tr4vpKtWLtC-E`lZRS}F=U_q1c2Jt zPkoX18(D(a%U7r0m$RF$4-NiZzoGIrEw3M$*?AHRJ~6pgs;7B0W=6Absb zA3P$y3Ch^@3_HXg0==Fq%1+8PpxJr{xq8_Q(L;gDhqeZ$Aik32-fmwRK!dl}{WT{p zA_2u8yU)(x10OY2dS{<82UX$$rI*|D>DQ@Gk2hv32kZ3fUZ42;byL@=O1uES+h1sK320+$RS%E8`TVht&(6Yln4GS6X z%NE|R5Bd|&Eh%Ke;En&g1JVh3wEB|hZslE&_2i_W@#Z{Qy@BD@34biKtX}`(@CwlT z@$A!6V(Lam7e_CNlzW11mfouAQn`y}&Wv_@T7$rw_g)qq^9PWSW$=*hu?SlG%AA4l z4WKOMQ#gEI2kuoh&Z!)Uq5qs`K3Z}}=>dYQo)=QRnq1Jp>l^+;sn)10{;c-Iejar1 z5u?kFkIH}4zf@hLDoLwHjPAnjC>pzFxa%8&! z`fFYv4LB=})ccmOF{#y~p(8$e<==HtZ?@oV;bZNXA)vDCy2@wFu*5@edlVB?32|Hf z`5eG1%Qk(SaFxN@FCWBO=PH5TGgkV?KDI-K^;NI-Ffd~VlhKf6zR6G}xa;27?p~~7 zHWs7QcMfYexxm+R2a9F6UZCMimOvo$B=~83 za1z*s+8hHX!G^AEn+Xx1?l#of-Qxh@A{&9`*Y`EwqjR-fJKdvt%$7_ zHJ(A8Pn$34nCzjwpTLT}eExuSP-od0Bn*=8>BOat<{J&&RzCSr`2%Q)dN-TzkQ-vZ z$!IVT8V(*^HhXQ(KO2;sU%s%UQx>d$yJ)Kj+W`1>yuwtfQw~iYOp=TBIs+Lq)~*zN zGlCh{2zzuMOG70W)GoA~HAWkP-?avQ9;ekmQtL^)MXR^0u4!nb)r0(#U*BWKwbw42 zer^SN`-)Wki!P%dI*Dp^D#wu)hob4N`_I6;?nP;9-j)EF+mlQ!%T9n@5x#5G9zF+& zSqc)0y^qk{j3myYwi3($q&0u?h@$tF_iv?kF9h$6Mt>+<*@O1ymAfBaK7{rt*(Te2l!0SEc%`go#T)hco+)t{xeZ$Pcm;o# z7KjK}7HHa70s79L;}$)djV6lMTBPPCK}Lmd+m6q?gBh+Is}rZ)XBQthyL2JCk0Q`Nbrq$o7){7pe)yphNl|4wSf62zt-Gmvg>Av*Iyn#esOm2vLBmurv7lpq}RRSEh z(yYJtMS*(wF~TR@4G9}H^YGuz0WD8N`-ZP*pj!#^B7+o{gHny6j=7;_sNzETaQNAW zVDMs_IR8U$GR{yjxk@pm>{_8I5 zQ9D|_RXcO19<5$*{a|1$=!0|gE%wOLP}zhl@4ZtW}CpA^Onl7!l?VX7vgbQuT&xeE0YgZLJ z1!bdK)o0c*4?u8kRo92YhUKXJMAqpq+j+rw@y4D_wIXQz`lt=hU^EzbaH0j+z6G~F zytsXV+ZCN#dvbO6s4r^IS~&OX#ZR>QQ;w}HPH4PHRW`?DEv>%ifr8#v(A&pl6j>7o z*jkKtiic}~Ykd{{!IO4I--HVCHaWj|Nodrfd*f|0X<9u@Kk|44O;}|+Ua(pS^lxYGTy(q`HMd;sUBp_9 zWP(%EWi4NU>uYV+57i5Lr~55v<4_QeHnBpNJK2-ZDDk4a;MAW-q?*xiqobc= z<^nK`&dhF-6GFq~#km5S9JKyeF0I&L2e`cJ+wOe+a*!8Q=5-`W1`RiyP7^GP2gBuI zIoshIT@oM3J)(64teYX5%W;aCmr zbMNWv*JPYSkiY@aF#QG0pz#)`cWRF%xUsaxYbXUk7wE9Pv zq}<$SKL`8+)lCYJ%}Zw%elObZ;b?Ez7QP2at30E=x92oS%a%6Iys`$(k<7{!{b&td zy?@xcS9=&8YDQ)}Wqs)8(zDBchH#*f#Zi}w;aAXcr#0J5cP{EE4`8_R>=bC;ZhCRG z`XI=h@oN9u$yji6gIoP~3kEczd;ICAx4fXEVo1;7!W-048E?MArVTVFeEA+Pw+sB= zj3a`w%+(|IjUKeTO6o-EH zD{TK%zuw@x&Qj&xo|k2I8SFT&Vv(W7()0seLFHxUfoXE8*%@W*Ibz(cYd75K6;NXR z*7brM_rER6%v~$hDov~nZMSX|q}{Rox4OUAm)V^IT`|Q)^neN#{GbOasGtG~0FZ%o z`hYbx5KIPG$-pH&=t2cZ=)nvs@IZnDWPqLwe3JoXGEhqfKuKVR1W`!9g9Il?Ab||@ z(+AMWz%&`~B?GBc@P-6hNKk|XFi5b09vC14@nnFT3>=dISt`Iof-xj;LV_G5AVGo$ z^Z|V`P)-J*$-piZ1R?<&5?rANLP*ep3NX-v0c60P8ptLC#PmQB3F=S*7<#b8ar@L; zg9IVy0Rw8_o(zbSfo6Izi3C&sM0y89tLINJs=VwO(31pz344{+16$vttfDk=+ zLjo=Ipa>PfAi)MIFhB<4NpOn?AcP89&;txqFn|QfNI;7OpGcsH1a;^E7!oX@0vjX`LOkVb-DBtS(E zCQ*SO5~QIARH)zw2~?1v0tvQ}z!(W)k$@9DI79_<=s_0}D4_>4rUMToAV-2{B+x~I zQuF{473_f|FhhbURKSBCoS=esB)~?3VI*)x4>C~!A$stJ3bfFJA|!x81@=e~js(m| zaEl&@qJl>B01p+6p$AT=AO{Klkw6^@s*wN~Jy=BrmgqqsDqur`EA&7J6(A(RJbK`b z3X+k47Crbx4-`!Yb?5;Y5-cG>L@MA%f^#I0MuJ`>Kt+N{^uP}Z(og{vdQg-EM*m}} z!ZN*Gg^j8krIwQ*TVe5*AwRC^<$9s%rT?YrlCQ=v;SPy%^^RZ@7R(@(@TTxf3-9Jvwi2U?PTj6kLgDS)DkM6kk)0F;HNFk zTC2ihNgY`lP|u46-lgx)+zQZ>!%?OzcNat12X8w+-gF~%v^VbhE6S-ivHn$3INB|_A3=pGl}X9ojt zXiUSQz}`}WyW|Md%RBkh^OklO;42;4`u> z2*xs<67sCW>!823%+{Gjhw%xDHYCDxR__U1*x)Pq);R@6DeOvqcWe5tfmTXh7dc<( zHZq{*q-B5?<{X`IV_+_fQaa(cSzixl)VIywzveE^cpdC_#P|?gV)H3J%!vuF%2glR z8uJ0JSl$kN}5S5~qydA=)vZn6>itT%)40lO83=Q@wz1Ge)uKh#8#*GK>Nr|xW_T-lC- zyu?tbQu<=>xzHF~Xy-iAESyE^$&%~`<#N{^zi}WKtDLJ+JL?t!7eZ&X8J6kT+T!*8 z{IVWwt<-)X`@9TPcN(Qx17TWBl4efbj;1(_UMME*z?h%gy?sP|e9^v*ul#D5?LFB_Hah}Nk9r!U@f`V_efJUbV5mFclCw8x3>>Z_Bm ziCiG@Y~`1DW8}Sd>Wg zk7sbz{REj9+Bn(#6IGjJ{gq*myf%Z=ibTB3lFPm4&;i=-9l!YQD=Y-BoL@D+J(ma_ zZ#iYFI=sR2PnCAIA4-BjLat*wXC~m?2PV_Y&wAqB@x$HW=ku_M(%MyLt3IOP2(BOd z*j&KXq9d2{xTWBl{>m>IJ;G2+E@tNT)BzYV@8gJI;o|pagqc`^T%XS`ruE=O9OD(tTiN zK({7baUNLQ3V8=TE$^*mZoY??EgUc`R8)mQ$)hN|NCF?cA)@!%#+J4$4ZTvl4%-yp znh?LJh^>|!8742#g6mAE;MCs*{#mo;HX<2B{pW9WoXGNbLELmbeKlQdO;Dv^$hK0&exUQP%ZtULtGug%^RBb1 zR(VNP$=XxR524`x75<;TD1f;kv5h5_GC;WS=2+w2LM*u7wnK1JArd;<)N9K#j2Pw~ zf>N`*(YM2ImKeWxN1_uymd6H;1F=}6cRBl{z_-I_)`*QZ;JLF?#k+C?;$k+`>wRz> z37G3FXQln#oNxAkt6ickoUba}C(Cmch$joqbErv2LS65l9W?R4^HqgvIxA)(Ap!l? z?iF!Hmn_bAUj@dKMq6IaD#NPQJ)1u0 zCm;_)huMO2nUHm{n!dlbHB{J~W#yLEjl6AK=Yol!z#{e10oxV{g}s}*1V(pUoO_gN>282h52yK$%dUmiyO{^KfNHC?cN zpX?0Jmx;hnG(TzO@u$GIYjoQJ5k9D>XK1hW))54_Irnj+r)YzU@)H?gAb`x=GV z7_|PT=atZ0aj;&j`$qUm3_Ru~mVRS60@g;@Mja^7!%nlVZCvi!1X4c6DrXlz0tfcE zpK#$@51nT5jr)ky00!FHy=>0si`?TdT2u0yE$c}X^s&ijpZ;c0z?1qVAp03QS705;yG#RSXYb0 zbXq#y4lYNkFcxb_ zH5f|teuW{8e!UNlZG$1NeOnY9)?pLfO${zg3D{(X<5ipahiN}Yvl0wM)bPr?InAwY zmDn^s+&p3I6*etkLjt25I3k_RV@8ZBj@Vze{P{{*92+`6u;=j++A>eHwQ31m)3Wod z+%8YJrmcoC$uAaqI_?=dZR`j=o$q+`o4Y`dz%pnW%?&*Q5)a$YSmU&eOFvEw3#YHW9bm$Ssy8vB|TKffuWh<%s0D!rP!1#df+qmpQh@wTI_wpmdX z*dbxwDBJgB><}Lp$S5I>Jop_dhk8em$L!Owsge@FXZa%@j-hJccHZJuE0q$?L}{zh0E4!2i^<`4!k5!_aIJy#Vaq zx~NCC=L*{M{x<9Py&Y&z^I4U{QtrS@I7xO(*>U8ptoHSyz*=B0_3g;5Y&)dy;hl1D z&JU!(R6bmPsun4nVR@qKeH@s{=Z(uds!!*9(kiK(kK}aDXM;JF^Rb`G`BeKvQ#qd< zf8~72sGQHk|C00J{43|f64iL#!~(QT?&$n(D=$$EV%wQw3xp0!BiV_U8>RZ zlo6$`UpP6#?9;$TvYozO=b-!R@*p0_rI@@jY_1f2y&rWvY6*sHf+8Ze*I?b?EdzidYnqDCF1mMl>Eg@Kk`9TUBN;rpJ!l2>1$ zxTA=cq9cG|FF5YiR*vD+&+<>>vOnR}*P**_q%OgHmB)lF?zv-Gb<+=aDxc{41F_1Y zn|zgchM2vBh36;?8C~r$Ah-$(9~l&}3@?DP*K?TkQjO^KM$F@4I?MPWb6e4OrTy73 zq^IA_P+%QSIedRZ^X&^bWrw@pV2=@AuxN#fWbGczy3YJ`pY(C)4QzY&NL|M|H^$#; z*&e|nA^~g?Cs)#stI9qp9GaXCX%VHgtBVw%xAv`54qz+RS(bI7<&-L%^_7o(!J^aj z`dyc2FB6|rgLj?LgnX~{v8?nqJnM=*>g77kq+Ij_x^3Fx@y0a=&;4K%cl=Nip1pLI z(PV`geSc{_iAI^utDr}OTP=TJA$0S|I|%A>@VxKo-VZDy;OvCkJPS8i((AVkj8&yG z+Td*+m%}bK@Y9aF&$zIEBWhnZt6ieIAKD%>s{Q%e8CB_MjhsKsjrry01dhhW)A#3l ze|3*y)^+eHsinJjb~v;>z{WI#_a)|CaN48oUM}P}9!}tin@g_`EBhM1bLDXyR`g0w z#qBeees|bUWJ@6G!zR*BhmuJhnAG26_Q|>iv%h7jyy@UY)??nl)@7GE-9g_P!&91H zMd<6Tkr}?_blo&!irE{s*FxsYJ$IYE zJmH3-IfF~Di$klKqDIR6&+(l3y9&PR&Uj{5YXGhrN2+cP#N%zMr$1dZ2X*?#Kc}MWdYaHixt1{tP+M|hs6$a47WE-2t5nE{X zWb@oJ+ib8sR!6K%EI?tOJp@p6)%Rxh1yzaG#GpG#&6MG|sylk|gr)tWzPw#Z0 zN8*C(&2_0z#Jq{={lOe)p_+efsO$|+h%aDx`mhQoY#G?JP{|Fi<@VZpJ!U@ova8n= zpXP>+sZX!udU!*Zw~vLm@-(neN&Olr|6ph_N5j51YCZP4DQY=%H5qhx8Rop5SPdQb z=!a`>9)g~8MozH55`#ibpBT2-)B0fn)n{J^=HV^60dJ+o-SHMRJ^uKBc)T|5(7S9d z71a5fTexmn8|}VaM&i(}D(H5!J>gxxH|9n)6Zb86p@lG;S_1P6yl%Brj%`gH=v-^R ze*KOawECAXK5j0CUhCWZ*iMx|?vEcVe7TlG3r?X2N6$>)kb`^WUhWykA*m|nH(c*v zJJ)diSe8|2Anpk0Uwaf<@G)_|S#}m$ixw={qVg28wWmMVOC5(6TyxrzM!WIq_))bR za<$;QfpwJH2~B7*OVD?Biy3rU7{5c)PzkctZszPtl!O*6=azPqIN^YoaU!0HM{vL^ z1IfFwhw-|C6Z;k>uSfAmwq1I;;VCL_{UG9|#|hUJ9G#3X&IMa;=@zvf(FNt3FPopT zu7y5UbD7fP?x738oe}CQOo5fb{PEi@UD(G;T3)-w3}m08h z2KU)q1HnaXD{sijo30;2xsQCqTei;xCVV?g z_4v$Du;S|3GMXVMSjt%6{rWQOA172Fzo8kV_ZmM0!n082w=C}N`v%ZIPVB5LeEcpxvI6`T%vd+>&M8K$VLK@j;OUp$*J z5d^%FWO%YJ78r`ux_LJb0)zDi1z9Q2u;+Xsm-p?o%pHHFc2uteD)~@)Vm0?JNLwGB zV=skvrrb9uXlVu|&3O$H#=>ybx4Q}kXB)ULL%UjHB zgtYa&C?W&-9eZ)r`_o)-Vf8hU`k*GLo?rvyGpdmA+~K>nF^Nb>ZuJj~n9YR@*;=i4?kp7o50=;3k=z3sA7S1?_!gHKBTkdZgQ)OI%3YACweH4 z6$+&LhU*pI1PkAIR0>@F0a)w9UHh|g0BhjN&4ayVMw2G2Ef>{0u~dpuzVl;FV14h3 z$hV?xD5|~qm8S9%D3vmgr;C3at%^&A+Pexslu320S<(U8A4(dVH*&@xkj|_#_h2

6Ce{qsP~yfm{u@(~bAsQ%!-Zw$EH3%)IU zw2Sus{d7!1#Sl4Iu%Fz%&j|=WnN=w2%2hsoU3_F!;{n7m*XoPvT@RqLj%Pfm=m_xe zmNCAQ_X&LSe12RDrUJJXpT|8~YM^_@2EVzzp+HwjSfNMV91S)^wTWq@gS*j7E6P&( z!L1|pl69}cAls54janCD%zu_?-R;3V$bZhLpeCUcjp>gbT6K_?oaSQ4ZC0;Bx7YJ| zpHoPNY)cgj7tZ3u{O9`o{Wc^*{tGG}GcNU`F{3l3Pm4rRN43&zk0q$g#UWNe?8&9p738!_^&7Y*AxEh3IFwk z|Ht%%Gp8nXnVNZJO7Q+=(8&?){C{>T6uQ(!B&uFYS|XAVk#dLxL!^_wU*CH)iGvcp z=z`z27B4!a0iik%<^dVvm z5n0IoL?R>77LlZgltd&TBHa+lg)Ws)f*BFIh(JYzB_aqBA%_Ssbm4@^XGHcQaut!8 zh&)7O9U{jN8HEzl=pq;quZZYG#3CZ{5OIbQRp`f*299hyX=|BO>@vLJg7Yh|EUhF(PXb zIf}?gME?2X`cH{>e_a15v5bgZM4Td`5)p%F*Pjw`rlmZZFgzu}5$TLbUPP)Q5)+Yz z=#ma4>=8kZ2x&wBBf=FCoQP0F1Rf&u5qXZtYIHe_$XJy8M3;>yxrZb(>0%ub*(h<0 zE@}}miV~5C_(M;066ubT+~`snC2`TEDN0fzQV>ak5+RQ+z!Bk$61<2|MFb`y4AB#$ zMAjp693`U>`HRR_L~bH75lNmBk&lRTL{uYU7!k3E_(Vh_l31lnenhIHBsLGQdNt=WwWb>~>Qjeqlcsw;vAGJRE z*ZLV#^;0F&52q@oA5InU(C6s+HFwXiUAX_8oafgH-ruwAkQz?<^g6!^_&ozRZt`*W z5Aq8PpPF;$*GdjDvCgl?)FGy32%4H#=hv#KC#FyK^J@*?@8_Xcas8gN=U0iqpU*@u z;-pX5^Q&h10;!K?*nYoBsC-D2c ze_bDHEjRrVQ7eT0Joi5eXOau`=iz=|D{Af3+0ZW+wQ_16r9b9BqE_?#zG&1M;Xj{y z>bg-IxapUUS|KuhKEx5?icCv|MX`7kar^J%L08AUw2Y4)+GoeZ1DZuvtJVJ z``+*(=jun4=Kk%f#XL2T_C}U%@A5q$rC;fSyxa9(|FXZnfNkna-xnU&k(ukWlXeA+ zV1C1BLqy#p#C$l#bdg^M;ux&0wUyQb%2(jE_ESa(bg|7FN|QHen^yNgv*+`rbCk_N ziPPRk*UE>{CmpuU!7p1t^L?q4oVwkhhQV*a4zCPU^SZ1P-Q9?q660JO52%zGPiuW( zxtsW7$w#};EIv`qRhiXDlK;$-qPYjluUqIljyi8Q`pzpnQ5(J;am3zP`23hVnx{44 zHm}^(P}{S2PgiU0i!rgY)|pZp9)6+Klu`I4AGfqP4Iwf<3*`dasB zn^7KEncp?OT=fHT5A#qd-W>)~9*%9ado6=<+~&4~)@%j&$`^TD?p=f~<&RQFMzZl5 zKJ{!7sWxaET%U5Z(*=y)w-1(keFLi*^tIny7mpPgjtqVjev4l1c(QseGZS3=erbcu z@M3gn$6%05|0A?B|MsB#h8Ms_?CXVl&gEcBxsrQS3^$4jI{UD7jU8C_AbytK<83I+ zGT6QXz5ppa!lR|lOF$c2$4&bRek`=k`pb_RgdT)Dq{o)O#LNTrsoHXH(O6|o{pN$~ zP_MLzM5(+OYI5JbO84whkUM;6&++mrC}{oQu|(c}usW}LSxJ5>irCRR`&_~~v?O58 z>=&PxAztmA`KPQxfu_52inEC}f@jsjpRA7peoL1KS{%5Cg%V@VAJf)?s`ng1t?!va z`PG+Zo;`I6a<00;D7(BC)C>ll?HlUGGXmS}5?w|x-`&p4>z|4+zd!fb&jJnb@vDBt z#`(uUk8F_r>hgTdoEVh~xnZQS=2YHeUjyUSP)wbr~;XBJ9_rgIjYV(Qom ziP-gV7nz)D|U&{!o(h|<+b2> zP@y$870xPm6v)7GdJ|309hRXNPxQPq-(^Cn(PJ%Ky(gi(B4m8kdJ;!Fp0!)Vukm7wPiS@dGi@1FJh2T+

V;a|3MelE zw0aL%L8)gpF%I1Z;CZnpx1s3=sLg9xr676-svJ?MNQjUG?ZU3Hr&&kP57$e1LgKbq z&{u2D*8nRl`oUSp?}0X!X!q_O75nweSnB@%-)8{Yr;UG~0sde33^02gZ7$cKb+p_6 zpg?!pB<|~`r#)5wb^kqs_8$*8NzJ)_i<)!&-qc*{k>K&v9P8nrCcxoo=F8okaUEKBZM2BR-?!>I>|>-d4#Ydv>YMd2*pN-G(z|hT91%- zgrcJpafEK8NHs$K(J4Mc z#v^1Mq2vhhMhHSe0}`^2PhIX zZ?E4?jbGnwznfE|aKD>c|G9N)Lf_w8r>6A%-JF`#_jhw@THoKz#s7II-Cxa_^s}0t z-1m?6)Or2Uo;tBV+EZsX^LMX7A3mf{mi#|Ed`Q46Iz&Z)C;~T8pb~+O2tY(&AOd9( zz>2_91biY869JM4T=X|6L_i?=l7gZL;6z|0`u4wJE&^r|$cg|{6#PU$COVWv03!VJpWr8Q-BzOy$HC4DF_QwKozFoC;~cR3R%NfQ!Ib1g!cCk|N+4fyn+o&;QoO1Y{#n8Uf4*EJnaD0&x)_i@;U% z{V8CLz-I&`BTyItya=pCfmgJCfrIK7rur(w!kZFylyIPQrjuf1 z3GYhSRl=bXrj+oZbk>uwvlItQXIcrLN?23EjS>cwVrmH=OITOJtr7;6@T7D$lwxfO zH%k~;!m|=Km2jqXW|T0v6i-WMV+rRm9VUIE|p?T3A0Q1 zTf)-Pxmd!uQoJf*PYKIQxLm^65?+?DuY_YIOe(FH_sda)KLSUdzBy?BA z5&{X*fjIfi5U^fB}5)hC;eFV@WupI&C=nxzQ6%s&@4*L;sk3e_?sH5OG z0vi%=kU)S0=p%3*0qqDhM<7H36cRX)fPMtpBLE&9rXz471sW1)kN|)L<|AMpf$Zqe zA_X84n2>;h1o9)m9)a)ZFe3pIDaeojg9QE~ARisdqaa5DEYjga0umA^kN|!ZtVf3* z3CKvGL;@HRSdf5!6vRh|A_?F~U_}BR5{QrhfduZOU`YZ#5{Quii3BbrpdcOkBM>D4 zA_?3`Kt%!_5`d7vfCR22pd^7F3BX8TL;@C4kl_CrJ;?8Skg2g5vq|8ii9>KX~>Bs3u*1L>3>MNJX{lF*EVOeB;cAqENkM`%hyMiR=A5Q~I9 zBqSl73M7;zMNAUk;+hlJv!h)hCP5>k>-kAz^P(})z^Nk~mXT@r$l(2#^| zq*IC%^+^a$LSquLl2DR_cqH`V|F%8IAHP?b`o!}qmdym-PW{$38oY11`(AM1IB2qe z8L1eo2AXdy8-LLL2DFNl?($v32il_5xM$RD0-xTU&B(E^CUI^8&J$>!4$Ko+o`CWM zlBWQ90>}S`>IqO!V0r@56NsJ;&{OdIG&oOt4df%<|MEwn+B^ikgSH-l?#|THGZ?*j|Hfy0wJDhS?W#h;33b4C z`2T9}%fqqy+P2M82&KpnnF=XH#@0f~92rAJR8%Bm86rb6ltdCri4e)yU}!BOLo%e0 z3}v{@8B$32?r`@Tp5OZ%-|>F$a~$7$9PK}>d+#;ub)Vb5*S@an+}D}Po*Q2a_-<+F ztc^+n^pT4S>+s9xUx&7SND+F3_=HntxiwCa`lG-!-?2wX0tIWUW*?>u21i7%db>{& zz=Oe^Zc!t-pmLOpVD{`bXrS+Cd$A`9rS(kl``&m!>i@jG+UINRb0b7v9Ym$E2%qN^ z7n+cV&V$u8JR2tzGj~mNUikL?P%@(Q>8){6)d#GBRT2TlX(*K_d`VQlM5!0TC7KIP zqSR71Y2zFvlwzqnRMfEp#cfhAG>)(W7v++kgym6#oa>o%@4qJlTrZIifB|AKS(}pY z=z$oXms(IocOj;%BlbUDw;{HZ0d7UCGl<AZ!tcZJ|)1p#S0`Z8v zc;e6K00v_#yZzx)Fz`Kc?oQ%C(64>yS#Zr5=-ahXqtfLV=n3Y^ta@+*bQc*_i#*1l z$Btcmul7gKJG#k7k^MDFo~r3?-dK!M{OSpG52a8l*Qrq!9UqjgQ7L|=-xXzuT`n|G zd5qHExju0kXGE#esh2MaHlg%Dn%E27p(Ol(&JO1%PLB$J!N4VtX(MMOZvCFNQI!&T zSe**GX=96`?Py+fSkIxG>0MRlKDz=JyN>%3)GVO?puETH0#VR^T-H?u1cE`q5D~SU zEHK>p?Zo|BOE5NPK3_L4`->?3<)_lw)rYOgjBpGWga6%T`ya?xVO z{fZ66k(g}0cFWfE0ZiUQva)Bt#AH#=T3(hqm@L zXu6?!;IijBH&N;}rcuwF+yO24>PIzErlZAEd^v_Ol4!AGgK}O37g{{B^^?j8aUx+G zTTJCkq1mur`IrZ9Knl%S(=uTUQX;Y{G6I@G>KfE z5B92#nHzyr>pdu@Jr|^Z5jmQ>b43u5_(F!ZO~$uCvu$XfJ==uhyY)bPVas(`90lC% z97WBBK7;7fkvXrZXh9sgYD8+;QRIr`y#4PGJ;?{R+OLnjPQ+iyV#ryGi2r!{MVgmj zxJwK%))A$3=MJgoNO}A#{?Ec&v%7+c_}8CJVg5+Oztmr#;58Bd9uG~5A5X(i(C)e3@l5b>9~=d(u`QXDK#iX}=~&jSYyUZG4P{_kum=#+{0 zhu&FmF(l%z=+!ZIfrvk|*+Z*VBL3TmNth*w_&2yW<=!IVAMEtCY*WeR%gy=mds2Z> zPrPA2|2?3#=<=9rrU_WyX1Sy(x*f@~`lxF)kE4?TULmW5ijZxzO-j#ImSqWxFsl+( zlltJyXWr=T8=3u;OvRwux4SIY)eQ8H5F*30jUl~=Y>jTaA6#3@#^(4@8MAQYcBhuO ztw>*NEDl2AZXxJ5?9!ka=0z!7`UN zVC2cO-Y%?vSu*1&O^J?BO#ioBCKOY1?mBb0ABgrS@|u24243jwuXK9c0@_?D_OVop zfWaDegM6-WFit4i*}3>`MQUTTM3w4_+TcDaMCQ2=`h7zM+H796O15n~+U#qXZTRLB zk{VC>*l>vlZ8Z~8jq^`J><0pl`o^qVlIW-kpDkgT+}*GGEDiPQb=gx^??L1K=VNyV z`k`^V_iql*4I+XgUAMJQB6_euv!(UmVbCA>oThOxXGPk>QCVx)B{S;CX_R!L=fc&` zizwT0SG^u(B+8>vj8JWLK(~Y?n=6CV0itEf(t~j z&KDjlAf^bP$vPj%Ac~UZCb!^L22?RU6LY|b6E$obtdl%H4QiAvOomz-LGOWi;nu!b zW!3GO60bd1f!6S0Z>35fFvaE|HhsMY%&1%DHf!C746E3BP6%hg)dJyR_L{N8_*+fD zrP}Eg36dJp?;n~?lc;HXHh?MjPHPm6Ph#?l;h5a=8Z^;8Va>;~0EYb=^FFDVg0F=` zW&2p=Nzx^x{$TcQWV~pbCZvRnhUw+?ki4*EW4nwJn0PBC+wuA{8b0aH=%mzuzGiX< zDkr$11@WDskKKPs`yoQ2`_ayP6Exn$HC|+1j|RLcTgX`@P%#QPM~G(xQ&pFFw~;$Q z+N3g#>Q`fs&9{&vPK)i=`R{JKwo`qc9AryXwj7Qq0J-j=DP7nGBtl);W3+szr2Ehq zc{w%6Hji@)rHUX)tdwX=gayxCe1pPTe~7jc%z zHJ2bcWMC*e?i0PAi2u+5z9KQqHFST!>8R+6qzfX=AI)auR5`3UfhjdEag}==#^jYx zlMfkJ6Y*DQ;q(Xx!;z0)xcIFDUvZd;<$+O>6bz|9m`z#p)aQXY5&wj+X@_)3UYr!a z=$`^6n!M=ZstVAsr|yDc^Q_50wGu5T)KIsO_b6|lwr6k?K8FY?`;L%Zd`Kko zY-QbP{sRrTd9mt>$)MuA$ckDmS1|QbCp&(q4bmoGl>T^F3$k5MrETZ?LOlO(63QQx z_unLx{{RW)pNZ)Ib2b3!9zy2btK$!xHU#@4>KGSnZz65cTlxk^_M-xktqWUO{5O8xaybeN_sheCt4L~3OXE^i#`p`vdB&wSmB!&T%#%SaE+ zd$mJgmRDcxCc{Ta<)|pAct9B~ik>*{>=TbU6X!g)cL zqkgde%W$W~x(2XWRG!Bm^&>JmXd@uv%ni1yaoogPwSev2fh*w`Fa2JFf3Lwm?}6WI z@c+&=7{#8v`5${ME`=EL5=zm5kKJHL8&H`;*I5oEyNIk-2Nx5h>_aZsTY|&@f1Sp^Q|-Z-Qj9 z+xD~mFHnBjO^*TUSagSfGu!^od!X!-%}fQ6knQF)kB3~|ph5CeHS<@~K$LCJ_OiK6 z;G2X(ms>?4q#ZfgS+<@AuA3Zuz2HCvdELa`vel=L_>vWZ2h(!Y;(Ys&w5v&} zA&p7utqeY*9H^hu~Ch3Dglh7Tf4 zQ)d;Wt;URRzle>yX@a3R*GML!T$GsHNgbW3G&Cr&E`Pxx8jG-51f&3ppl^`H4@TXkbo46PG5uUL=pG&1^oSs2>fZpjT&Pg2 zyBY`~d1ppt&||1*f4{#Wdj<+3Peo(5LeML$w(Iyc7VvTOM=eBo=3eLten9e=p!<>|eo%Xd9fxVcF)Xh#uozG>O~jwDI5+Nu*O&IC z=uGQiLWD(#FEJX$Mr>@35(rLlR3y zNF4GXR)TU(x|`Bf1EF&Aj@sQN8158cO^y>bgRHA6&U6$#Aj*_G`<*)xg%x@3&Q|vm zUl34jX3(EifResFd;5)JvD_=e&y`PVu`uBSO;{xZ7CEwgO?~+dkm8|{7kk2TZWaPV0!X}10BzP+W@~`MqQ@gue>?>AFu)b z6z=%-;Ll8YaR2W*|4IG-UMiI?A1QYFYYj>Fo^-TWpY&;^{hhz=|9uY|rEj0}^6n(* z(Uao2CTRu{py<94*yAG5ci4@ay_X%W^0d%i1h++`}j$9 z&cJLUS^Gz_Am0SkX41bu7|0AQr`IzlDbzy4x8ctnRkuQ+l7O7di_XiV5Fh+%W6r8k zmCC`j{kg5oA0I(Mw#a0=eorWV&vX9)Ee5!w#g6xbS@^I1;zbSL>etRG#V(Hk1*<*` zbv?F(2V-qaw4*ZMiQUhNa;WN{Gc%3!;AAR1D-sme{zL*=t}-;;$0*Bjbe9c9JO*^ZuQ4sC2zl_9i?N-$NuHI z{=%Pc&DZ=VFaCc0@EZG#loTo(pyZm$mvnd^RAXb=wLixRYCTIX@Yp;IEoZ-MGnH0? zhJ^hAw-f`RQ2L?xf~!uXaX_UNFkfHkfZ5g3I;d=2i9g)j!qhW1SbRcBPcps@??}B# zTkvHgQQw({!n!>Ni{Go*mSpLsWVJkBD4@h0$#F0h9`p!3%zb7%JRu|C#h4!hohdu} zQ$3>LS{n!cafM(lhwW6R{0>3;RH!Ix0{!DVgGaWmJnA_D|bHD-A zocSCI&N$q9tfgM=K8|kg-5hbS6kj#aQNA~H1M6wNkH{_=CH7bEsc`Xu{M1&aIA<6; zd$(M794o>Bx$pXaL|JUI@ zQq2-4g0%DhD~f9t% zZju@|NrjuFzP+rvO`Pk$r|B`ibqt{t}m0|nO z3ewI}&wuviELAPVbAQEU|C*6zt8##@Ce!UVe4IB{LsIcT>W1e+NTQapZuG#b+sC%dT^bmaSpgC!;3`_TH!;vozpGLi}D#+iOoFW2p+c z!pjlB^i~Gf?!i!C<;c-C%ykD?Umx|pNwx(XNXj>IaeTGnlM%#B_0N=Jwt1tkre{lM zow~rA?v7*NWId$Gh^R>=yoU7BYB%R?_kj7iV_yV>Bp?j~)ArBz zG_THz6={Kyg)06rI7KRx_Iq;m)VY3BVf0ZiYQ=c3Xool9f!e4;4kME|T*w&0> zWd!Oc=C+e0&rux(-8;T?ZZyarV>-jQ8I4mj(5?%nLQ^|_BytXOqgk0}_|b6!n!a&V z;rWz2`oSr(2lcX$;v%3g%Q!2T`YNP+ZCaw@{{>P;QYnyBb7nL~L=o_IfI*R54~yX6Q;njLQ#*=SB?!Vc+;=T4q`vKDe!w{}vf1wk>r z0=V8d7>cONOPdZkV6xp-3VvrPFfYM)tMBd@Qd|Txt?Di!3T$G&K5k2R#u~Hvhrce$ z&qA{Yh%&BpEs#3#mZM?478E~Yd7%Fufb!Ydx)(35CdEY{y4_D9U&H*PH;Gk{ zP51F)FNIeDu;qF`rJ*ov7)Jq__woDEP+h zP`HLEJE%D2W1eBkQ1uie_gx^jlSO*&c?p=jcyD(u1qNexbrs{f2ifN7*Wcak6_8yyKn@v`89T|PDnUpurC7wN|WZqa8;3`#Lq2JJqo`BzZko6MewYkp9`V06aV z=Q>`yw^=c5MhDBZWb({Y%ws;?fkWlS_ff$6H&oIus6gW>-`o!#PN;R$Djll6G0?c^ z*&^*c0b*vm7^gj}fNI5F%vC3VuARxSJtA9%G88#9d@t!j;bN_at5|yANk4KQ<+~bC z;$x_QrCJs|Li6kqg$XybXfN!@5`BpcSygu)UC_dsH-vAzaDE5PLr3U0$_0kd*_5fu3#3mJAU&YgMx60U0(X}P=62-4GigsNR{F?9&<_7>AZ zOkKQt|44rzWX+#)9zq0gnn}K!ejo}YWck?G+v%X>Cl9x#2wef8eV*!{*auM{OJvEO z@}s~xO=`!17y|O6Gu&(Td zHK8VJhy@Q%-xJR=$E&=bW@Nh-Kpwu3PXFDXv8+w-D9fn=%xU`hcu21oR1qilZj_;b zdoO5b%Y3+sH3;!7Zy2?(PJqS-A*B&aulZ=iKr;mYhk8}kNI1eZb@Jpd z=p?atKd*IUt}s-aX3abp7xRa1g9TrxpaWHowV7-cZf{FAzHnq;| z$%?s*rR1B}E3cx0=flhV94mHWcF(@#J?UZ4>hkWjd}}D6y>yD$;G-<;#8Z0VVG|ej zIPidlKcfa3GkSGNmC!?-V_8(e0ZG{T-Tp8p`*El%dHFz`h#9n|KH|<{Ne20&$okh& zZHBfUR6KdCyzs2sNBz0yui$~3=bxCQ1!5g@`djr?P0+dKOlmJ<8rJoVs=mFk9$SsE zNzz{6!~A!4evrp|u0{`)Ugt}=pWCCo!<}SSMo7H-9!A9Tssd#YqDI6 zn)({ZpRVW+&wPZou4=b3K1{*0?w?OqYBRzE$x`7pfzDXRFhntZ#tk~x(@0!Y?Zdj6 zv_|7MwqUEF6L%Bp1u*|(0Z;cIPS{qA=3U-ZHGKA>f1=%OV{C5fxtTYp3L3nu@X5%t z!(JaZ$~?;UgZ6e|HcrL*@QQZ(hoKiVIFv^3(e5)&*e+9$^4y6gBK|H3*KVr7fOT66 z2^t>6=e6JQ+~4us<94LvW&Z(R&R<@i`Gfra|86-UD^}z3>9OzNsCErA{d6U8y64!- zHTf7=+%V#|W|u~hqDQ_a+K+)?Z?aFSo?B5!$5ZO5&;ew{amVKhFE==9VLE~?76PZ3 zhkM-LC;*EKwO3b#P@zZ>*4Ngb-hp7Rouh)I4^hacB=H!&!^E5A-&;<9qOAVUnK&fs zDfs+o-|c<#cfn|qk`~V_2N>PKOcTI-6ny5~rEk(pq`q0}l-w3-0b^ZBuM;ChDtF-d={@6?tVwi*%uCwv6juj^XHW(UZnu@zP&8 zmshB#fS=`&#QqQdV0}I(ov>~Q*kBX33L3rGH5_z2L9u2Uu@q|CT7D)&jEtU^uNx65 z=Q4?U3SKJjBVV&x4!jawe7VEa9W#b?4r`IE+|ic^wB|jvyB9Qa=whAGEqQafCVl3u4>yH8_cu1+CR`nwF1q zLn}F#Nz_x&Czxg|PF4zfkJ74bv#td_yknwG#Q&a8E0oqQDe*CmyBfsvKjiu1dK|3e zTqaRZQF20ESSwj8h>N|3CBv?QvYvCd)5wp5>YG2eI8edmP?SN)1|{BouCSvCka8}Q zsHb;YtECtGSwW_^`MI2pbO3KOi&c+*`>Q``oEH_XJms_Azj7{zyV~1}p86McawX?7iF%639K~6_uF}91GfL~@&dFkGqr*DQX$qKT zSD)3kGb+pFv5T1UX5n?wDuia1b1svpr;tMK`y7*`Hl)JyI%XA>ke1`=Rei1i_|p+U z+xZNJJd?+Z?> zy`o3TxlE#-g5<9j0|yrqQ5@b#n0`Hr%DSb>S%mie!lQyK2e)6|k4i2i$t*-LBT~-g z73wLv3(_P%pFV>!0~wOfY}|&hptA0&uJT{~Nw~hKAvX``5+mhY2Jcs>r=XKX-yK{+31JWGof7%ZzIC-@~7lm zul<4lhe*x0@e8D!%gfZ$$Z}xacbWOe3pONBG(a}OD zRe5hgGjPV;0A(sa0d`HXb-O1YuTW2U@y2y;#j{iSG3~0N!1J^Tpf{(pjIN*=a%|Wp zDwCZ9Idcn|7K|7nGiR%*e7g%=$H0`UL1(l~Jw2`gjBZOrGgN*Cq61z974J@>VxzcRQcKFPqxBRi+_%k zELHu*fchi!v=nXmQ=t4`+x}r}Ew%kG#`$;smg@d=jwQ3^Pg7qS_n)W!_v!t+DJ%{9 Z7u1%H{PVy|Re$*|e|*os&rg!<{{Ro_8NmPm literal 52477 zcmeF)2{hH;|1W;C$UF}vGtofi!rqaoOwAEx425J&6BSJ&Gzb+%$Pf*NGVEPRQA#p5 zn1@oKlp(`CarUWiYyH-5t$Y9fb=SSO*7|(jXYccRAKN=;d$XTCw(W^UuVp{eZKbE9 zqZ8ZU9w2G#>Le+tBdMygTtjWShKl4em1Sz|lqc!FVsi+c)@E zx9%!eXAeJ*-QJRcj=mm_PM)rQl8)Xkl79Y<{;o?synO=vC241PP@dee+gFnMQoqhu z($;cP-JzwWxonw+lbWlVs+z01qqFu7XGa|!ZB;FoWooX=cDOp}IL{7(a>m@57o8c# zuNM%a{5SL5uLig|o@u@@=M5;M9-pk3z6T8g!HZw*o6O*~UFPomh!)T|)9(V_h;L-5 z8jS<*+O#GUUOI!eb&&@&*7bw-yHjJA^ryD60LR0gsO~v=35rdW)rzy zW8f$EgC8Av6>t%+beWUXD=6vtKKf$zMljx5=M*o(3H5iy7%uE|hV%1+4843zq1drr zJ?pAc$W{5{XLk7%q#xXM)pKVy_%cbkYz?dD($Q>&rag!aUv!%MaUPj#I_SY%ytA{l*UW(ZRE5qW@NFR9F>O>>^~XZ z7YFz1YYrUeQ~(u5kKI1p8$wT_yl%by#0{QrcYO0^(g%=Lr-K+3^BjikKjQcDx4AnF0^&KlN zf{8uP{1(@TL&dhuX{D+1Q2wek`}&W^AP4u)9V4}`(B~sXL7|+FA${bx&RzK@!E_c+ z&z$vY;G6IKm36mrK*xu}BaisKP^m-zm!!v*nDg-Wq(XaZ$XRrvNVPZvzsFZV&Hi;$0?+-hiTIw(8(lV-x6sk4 z?~(?VliigcDmQ=?iWbe|vyH~mMt$Ix_Zch@@I08^+7L1f`W0)fT8248Kc$tP{0TWf zRE9ToxTC8q!Y3m|&SA#lv|d|-LvVp1N7@^|Rn+lL{2p(KaL|O35VVjQUPb@$JCtPV zdD}lF2aVv?{k3w}p{ZNZd<*q*yj4rYLXXt-h6O8@KLN+@+L zc;sw_F}9A#d%$^Ii`q7VrYB3EeyCQ5OXYgEGsfFNLn*hpTi5=CTV3Y3CViHGD@}Qx zffij_d;7_=)0#t_(BSgT_ivW;Lp_;O6`7OGP_O#Pxzm;Y zl<^8pf$Q%u4_KSO!O0LBNI&R*{PPZ6&ws4bLXIEWD@qlMFls{QOVdMamIH9ZxBYao zof%Lnv58(`zCN}-9X9=D-WF;bK+|YH{mGVOxKyj&mVZt>G!*S#P-It48DBN4bjRh%T&O1v7@t?MK)p)( zNSA1Up8Eu~xIgFuw=%Py#h6>A?{ka`j zBLDNU@98I?V5?tNgFL{Czm`0 z^==ouI7IJ(zDRv)tu*X`Dj|p2e(H}v74g;;ds63Mxz%@5j8a;$Xzi`>qVqd3qeNh| zWV0UnI(5l&gzqyNRgN|4U2TedpLw z^b1(3_@4O^zI?2gFI{aT6ooH)+3T>`2cE?RO$qaUh>-Vp6@zJTSlq=Z&4kHDg( ze!3c%2Q$=99guM7Ltp#%ui)VVXjIlk`{zXy%GD5X_wd>7yW7)qyQk|8|LtD8DR&IN zE|MUv-`B&<{f{U3e?1ZG81z^D%{;PcEb$mSho!$RBLFm`(%s%ngDLlKpU0wgG z=AG&LtB~7&_uq9qzqvuoy?`du5%34e*Z!Wd7d0gRXqH979{Ng z1Jlt00OJA21#i0+Lf4u+lG+t()}r8k!@)5!a?Ddsiok0 zRNgJw>!*-8_iGnr;bcnvc^fac^)E`b5e7qQJNH}CB72JRt zHcw@U@B|_=-w@kko^Etuavj5NnewvUMwx=$UVBj&Y_}E(VnWwknOCmABnF~m{Og^0 z{6WK$4=l-YS!nF)!*_1iy1`hYLSk{2Ch7^vYiwAk1Fp(zMnnc|L6JixE;g&*gNE9j zryVD9(Aae#zWJan7`t+9%tWpW^@Q(VS)5f)xlZ=Wwl%K+93o}+rsXx!$*{{q+n26H zj4T7Ea7R|e8~E3H+8qtV*s9_}%Z?}HCK3O9XJ)>G=& zc7(`EQ|ikU0(C>s)FHNZInz%7R?2ZQ-D?C-u1x4eS63mh@5VKjH>Kd5{;FnM#mh+A z?8t``x3;3eki7>^zFmp()(Kh8FVsN6XU|uD*Lx4XJ@K%NyqtUde@v2 zmS>y64I}Y$+uno%`ABzxNYqBDuk*LNl}@Q|`kE8Ch*H04yX~zBO1;{8X}8;8!)3pq z$8l_+FD+hX%T+pHyYT6Ti>r5nN2}>{-VTo=nd^3ERsi?Xeq{e%fnL z>K4C`k!kzDXrYk%zUZx({`sbT1%0WI{(-(`^uBu3mlDWZeZhKqmxU6z_Vf`? z=>7pPnxDBN=u0%FuZ{!o>0U_x@L)}Vi6-hxI^vge_X-#o#$_Dki-6b#EoQgZ;vn0w z5DbhKg@qc6VEV?4#b20jLdL5n9(OLTL(}hcRn-`eHs<0XYVs6Beo~#GDmjy*4 z<93d(hEZwE&l}fDTS1cN5BB!nCQv~a&(U@*j8f0Jz5UX9G}Np8&Nll87;5qx+f&Cj( z%T(E~Zi@o_QO9|#6dt4gpapqhT_s@nnaFU#gcvFlty9;2x*F8Pm|71Tj#KI%1e9sT zg8sOtM+B?BqyA7E4&~?FV7LmH4@7c`|~zntn1zA z0vS0ryg1?#jwa0;Ze4E?0qM56-)!=-K>XmnoB|K`nR<_#4VZrAs9`XRC#BwO)%Th) zN_|_=e;$HXUuh9w$(>uy)~(RZFn=M;EE>lR@D7gJiLHsZHqn?P|5nCI=wv^)~hk``>{) zg{xWj&00~_p6%wbw_alLe!KP?+bqHN$EWx@0xHq>g1h(J-+4jS^vPFRE+4_bk9E^N z_n47L?)&b`9g!%bEzZJX-9aGC#lO9h^EkjY+fi-SMkMAoIeZBwg09c9M@9up(T&K2 ze(7l*;HM7<$_i3I^Zm=sKQ+uT-C5i3nqQ|O!!{vPc+U}yMP!sNX?_oGe26t-82N$x zyXW4} z#V1plz?A-d!!K>i(9{ygLsPj|Am3q)D~;R5QRZ|MgH^8y>gs!Vs7vz*rGEQ-qiQ8E zWyNuQVcs`1rJp0cX8JYcJJJ=MrYZxzp!|3K$REN=MF@~Q0jxVvmU&n)N6n9os7hExtm)TzgM8#XFagrVzLRdikRq}XGuaj zYG15QISYZ$bVVsYd=!A@-Xl!AOECJNz_uRg?1zl?Vu3|snc%bU*wdKxOpwhgE$ir( zxmdDaU3j11M=06IQp$1T1{QD5yzd{thZ)~{ON~C-k3P#7h8Qb~LAKQs2BKjBSn|_C zp;n=OO8waV>(g>ryoQx`%4-UIRy*=#=-Do`(5v*bVs$cVS@em^Vo(o=?ZNZfwJSi4 zE$`b0+ER%7nbr&2gR4QO#Mu;4jZW~e&-zquUOK?i7xx4in4|NZo90LF*1*ggzwE0> zyaZXr49zxtR6`Tns_#fJq@jnMR|Iy&Z9!NuKMRb8_^QzZ8n<@2e4Z&N^QtCCH z4Ls&V6AmK%96b%lPPt4-_GKUFy4i9hcwr)P>2@2j7-0iL`J>PCvl9{T#_7Si4+7C3 z*x!(+HOjj8B$4 zpu>z8x5}@0)Q{<=yf*JUT?|FGq*S|9zr=ijQ&sQvG$5aWLRCVCG+aK!)_!3BXYfT- z^<@LYS0s0hV`uI1Zd6~42ds3@=zpaPPdOcW8oa(+{LSj;AmV1_91+cz1MQTbTaLgY zKz*Olj?JcTKQH}$0<-9MJ1pI^0nVAd^G7{9b~ttM*pv6!uj7UG@&%yTNI>)moyG=fe7e={jRMtgB6BJ*M-V>=JplN+j27!n7D%O)?UcUU6_G(^-M+_kFoC`<57WdHJE*))`2$0u92!&FSmO717>t&%YeaN&LK$mzb=Jj6 zAm4bQ9D{Hl>Z@8&ojINhmDiuq7VBS$#+IbA3!ZZaqu3~gOJ@m`*Eo1Iq8eBOrkT)#i>9Xp&AOl8nx_Luu>-+w083k)t_-JPi+H+x-u z_5ZBjLHPrGk9oFKJQIhacWt7%;`7jEIBXKsXAi!w&2(*B_W`L~xP2ki!2ykFGK@zt zR-vz{7BR=>K1D5Gk?>^m9H?M=!58QsfXs0LT3=%6F|+pTU881+SYWk(uIr7oQ1(z!pt zqml&$F9mFA_XUjceeX}2szYYS*Jnd3_o8nt`#o=-e2Pll>XbV|hS4MZNFnw_=uCZ; zpd@CDpUy276{pmHG*lLdLEqkP&Xh6t20m<(0amT=AeX@FxvZkxz_r^_%yxqe_*!3k z+<47Wr2eK#-c_{+jl{KoPwuHg1LixKxo$LII-j`=y1W?ESzSsDu5g8md~Uw7)LV-e z8J8B6Z##fBYJaYaEU5d zXs#E%Nx~FMd|L3qp`ixq1{-}B$j8OqC)Aa@uqMT{iRgd;qk)X^=s-& zUL$2ny(8#xE64P<*AAuCe?!(SH#CPXgn^nePfg=J3lPJ@IgZzJQ$RQOY3JUsk6;;! z<~6<%j|SDxZ8PY&3s4^WYXzx&AY@4P2myEV=wEcRlVv zA1j|;4lqwgXiY7{0tF6~{()uAIp_q2qBn=d^{Zi)I~?8C3#TDVPI0gIej)U+V#;&% z;WRKX)f_Ki?+(}&?^b@f4!EBb@PKh!4)6qp8I8TRVCb$=YN`J)nm)s+e@T<_b7bt**yru4nBLB!>U!#8 zbpI;n)@l_UZwr!CsrCxLTU5YfCj%s}yShN;`ux-Mx9fUF1jStJJg5&3Qf{?Ev=z$;{ zn0qJ^O}|;ZPpm@?y_3`QdALp;yc0b!b<&zPtC@^Q!{wu~{ zu+ZMV_3Ioom49)))bk~fUY=X7*eM&+Wq%rEep83;MO0<4dgF_N(wV2+>3J#j{&wQ* zjFfuU&75nDAido8JpG18nC@n%qW$z2q=*%&Wg1_B!QSOUTc24YVU@?NwRdiV27Vb0 z{q-`4J;v1bsZb{9_-NByp(Bn8qtl*kTW}QIyVG@0N#6uj>Gsx{GBSW4x0zl&N;r*v zWV$W+sWc6S`R@sP?)XOe+vV?5^B6_Rbyn3v&^N%k7@= z`C*{;T7LaSu4Yhps>ZnckUKabtuZim z8C><)+w|Gn4E2sM!nwy9!DK;da{bF)X!4d$Y31vE;9JdHWo4^EP?%rzb&k(#bk+Oz zrW-uUl={=>8Y_Y*^=-zd6_hCT0gvQXZ=%$1s=Jy?xlV)T#kRXA01MqEzha+Akekbx z;k4FY|C50-_cP&U&=qFY<38w*xQjrps%vP<%q)1L#Tit<>K=ai(qa@o3{)BuSt#|!xe59X zl=|a$-wiJXldW$)gBmeGs&ze{Cr)3gP5)+@7T zz&^z1ac)y$M;+**(|c@gG#6!+-xy6yvq9O8Rsr+fC(vm1H4fWTd%}^73bV|kiA_{`q=X#O1*D0Q=S0j_fYXie8qO5(YyIfWii*m z!0X~Wg)!$S@4NBh6`AV+Q{C7LhU7IM@r8Idqx3ob&P&PLn8TSsS8|Sq!xJXNYxqrs zVM_>TD(v9S)%Z-gPus`5O%Va#UBy=q&1(i9)MTA*DtDpLr_L|uWz>L)?RO*;x*wuR zvu`T~Sq`FnV1L#dbF-LlDpQXfz(pq+;%EqGc$J~uMo zcB*F4hEz1T%cN5Gr6W=mR+hbO^9ID+<6zByXolwVKE3VXnhfe|vj?v^XP^trig6#4 zDfcx}^x4I^3(=TxDd&Ull;86eJzX^2{S5WpUyJG;l0f@j9nKL(F%b8|XRiF)E1*Cx zUhKndJ~Srs@KEbP-@3FM8;1CJqke~}KKtc^>kiY{863`atsSDpEC`AHDv|tYj%#a`o33$wo&xiyP z$U;9^KqrAK5@aF)AzJW;1X^f85o!Q~1RJP<0kRNJf?FgIMS?~oz(ayDByd6ta!>;j zBzS;Es0;ek02m2Yk-!oO0?`6C)Zhv&5JC-F&;kt9U;qh{0ct>t1fNKthy-c2 zp$0Zc5P}2@NFa>_y-0wH7EGcBen^mp7EqxEKS-d01QkfIjReL>5Q_wyXu%pamzWK|2y)Bf&5dxS|D_ zr~x5b@P-;_p#?=q0D~IXBSAP4FeAY&S|ExVG@=D~sKFRo;Dj3FAi+Nps3So&5&)wG ztEhn`S`dgDupz+}S|EfPASA&&THuWuBqISWTJVV$D4GrG&;l?dSVDq`)PNre&XGVG z33`zL6$vKM0zV{3Lk+0Vf}$iaI&-`!Iop3zZ}ym0GJCvhIeWYn57HEb8x9q0pFQ3= zH+wA8nLXZrH+#I-PCf3OJr;R^yWS$1A9N>XkNT_s^QfyteSY&_#|_0P6XaX-%&|C| zI&u6*@9#zl_tftO8JPFEZ>{KB zMO0zJyk7iv43rm)$YMF#MP9FjJfI#iAFy2I#Ni7b1*|9>I>`%VU*_s5B-Drq?X z02Ub8wasjd3ED4>-8!Nhgncb+UcC9HGH1Rt4N$Fi^)<0GRc z;@H~bKTi6i0oN!*)v5XP!9@j2b=W4up|4os%}&v5T|G4X!-hVYl$IEI);6O{m2h?c zi$w9~lX&r*xtzyMOQA34lhYgm)A;n>d8+U3?7*k(_x)gcnxyM9duG`Y2dxSlYdZZ` z`|7?glca-oKW*Q=DSHRiE7t}2Hg1J`7wIMjI{p6p`|G+uyRn}#X}Wu`dV)Mhag!9> zs}#HTo#ID)?u~Aim!}*)*W9FK+4US6XBu67!!Lt3oJpVLOL2ns`~zZ3qLkpe+}o~~ z1hwG$KD|4&)27f)VbMmFqaUH^9gFd2LQ!x-K&_d(!((VS;QDdvfJ zc&sV4@jb2HfjpW$Lb-(Vw78XnCNW zLK)uwe&1;0QvtmH6@Ht#r3D+V=Ll%GJ%MTuJ3q@jwH(wJJ}#fywgqmeay1FcI}a68 z9vEl&?1#Hmgu8(yGd3~0gxP9Vf|}qn6MhUILA`9Y^9TR$a8s#?|6%Q;STTF`=;x#7 z;cl^575ef}eEi~tw;yBc@bMGDh-sTBHfRq`UG*v)jUHnkv=H_Ic^2_IpM39w+csT3 zvtGR(s>$x?KN2JY1C#-8>Ctq&nwigYaZEZG>lO1!bejNo!WYHIpMDJ;KJh8#UQEPl zYCd^TngIsLykfk>XNO~o&hfg5AHgxV6ow+ic`-K(Nc} zE_9B_O)kh)hbBAKmc=!`hP$IU{W~JA;-!Z+&A(S&0S#)9v$IJ!H1~U!X7;cQI$C7F z>*6-p#CUDZ#Enk4`+}bq%iw$*oBvd1YAg`P-aT~baMmccX3sX}rA#&E!yJR>9&V!C z7Z-SWoIC^_a?VDFtX~4HrGId(n|=wc9vJIa?zYG31*(G|U45bX>-iqlhc7|%$xeo5 zPJX!Q$RqP@?L63;2QDofmxfmF-+!2>P{*N_b8Md&D&o+JjQZUMff?F0}KddH<^w)%m<+Z&7nu%6Z{y*N9ecd#rqF8gYtkLrQbwlN=kYBDb z-M_*P%rnaOv=n*`1k9S&9|g6TU+zsy`uszPr(ABbXtcU)vd?KQPjn#~I<-3MX{a_5 zGCy{+f6j3r(sfbKQT{L(I;F}H*Te;wKTdPpx*LettPCaK`)`Qng<=nX!3g3E^szeV zwi7Cz;+EPKJrB%l+`V_C!vG2F(4#-58i*B7aS1M= zOxWM_FcmG>lyUT%s00$JyC~)=dlD}wJTHAL49V%g*d zD<&WkiDLr9a^T{cwMVxuyAE6p1~XoSeg_8hbu7E%!|~#p;Fjm&SCNBEZiQ>^PGmWJ z=9_(0C{&1KasK($54kKWw&0_80jALzC%u^Eu|lN&;0#GV}(JMPXw)QpJeQ}f2i+ed}r@g4@o?IQgqGx=ui?BQJU_7zJ3Yy;=pLGd{4h-^Fk#L#LaW`yf$#(bZ&$%c%Z*SZ(pKT!K+&P|GtZ$&D`SS}RS2dBW z(W1ZxeS35X-90JG5&O@bk->~(U6(9GmH%BKD+3ud6*NKu1a<0VZ zj6v%!7jkM9r@^MX8wc43EI}I1+V${(A>PvY!q&LD9z>R=nT3}Ope&YjGSGK6f4XHKh?strG{3q49Ur@2VkCVOiD`E9&oelQ?lG`i z+sh!zk6KO1Lb&uLA6K*tMY0uZ8r(RD&JCXmddiiJuN@( zJj|sW-zw3iD_z9~3r8l)!&9*Vd`;J2(Tq3fPU*9}OvD?sQa7JDvl1J`tPRyIh{py` za!-!zV8Hjg~4*=o}9dcl*q)AL*L+SG(% z;rwj8_U3ZKE0aI5`!d6Pj?{eYuBoYz0+{ik%Lmd^P8`99F2$(}a~;GRk4qKBC5z&X z$BtIZ?O{d^!W{d?rc;rFL~GYbO*L?}uGtYJ%mQ2;>+jH)e*!*_eGUx4DBzRd|M`jY z4`9#m(8K?WJFsi7sF{qcL@`>&)I7XzqZqY&#&V0@!SRzmsVZ}r!SNHj#23dLMkn7I zw>bCuqLXbpnmajbfRmu=(I;=bjT;bdIl&)=#~o#ndDC8bv35Wd$Rak#ft@f?TvZtpa+c;%Emf z;{EbE#{p~T_wuIsycI&2ktG*d=14;sQ{O~;Z$VnUx|hAtgN|}2vRQ{^;K?!Q_e=

Wbc)q`|e?owy1m8!bZ#t z;-#4kr{JDfd|a)q%2>#8U(aZoGL#Fn(AV|Z4p+C=f8Cq*1?z9xtW)7+4;jwhR?b=p z;GQSB4OPc@@ad-M@4Ec4_;h)y^Skt8c&YQA$dhcXnAudUAlSwUx>#LqvVJ;*HDZ|O zgtpmX;q{&EJCtA2J`WYi!%KfeS3&0Uccjhr>Y$79e&!C_#aKh?0M8BYJy2N6^mems zKCM3dzVWvU&Jj2~FR{psVI`K6+$ACG>xcRp?2o5}l~L}Swb^gD8Q}RT3rdWh>SB@D z<7E}qZnX2ItRz*R?B@l&1}suPx1ND^5*H6SvYBA%b4j1HWG_LHnvsZ}@=#j+p}f_b zM`c^_p$yYz>#cLJWSmvEQnWK_J;hsHT+|J%FXe7mi@OgVh1EV1*sF|rJ8nzNIVVIr zpXc#Zp_J)b(8e}6JXSaett046R~DvV?&9+XarOC-xAel@mUZ7~^?qdwRM*5BV886A zCq+$PVClV|qaycxL|^3@dKz2YNgZU6KTx+S`7EAezWifQ_)^l3xsS3MiEpt2L!DDu zmOVqX{yD-et8(VPfpbD~rp2@TX#L)UPhHxU*J1CW<%Smiudq~kj&7>yGc-1>c;bEh zby^)mSjd-)CCf3R@%ptHF0QnG5e??AM|8J>pYFQglUXsXUm(y-cKj|2B@bC6uxZGf z*6-O-WGLzth&{U{7HCuQOYrq}>+`DKa2|Kw_#u_gaP@`m!efa6ca+8Ab{}7Wx6r?LlwrDwS?63-8@Brh z-7>7~ALL8mBkhXjc85*zk+;g@>2#B5a!gV>p=vXh?~SV5yi6UMIfY=|9)7$cf6aMp zjceWJt!y~9L&D%QQyGq3W+T*z4b zaK(v@KcMdgA+S}v6GxW3th~Q@BaX~DQF*ub6JFnWWJp>v77MT7;qclw4sBn_ZaC*| z0!{cgy|fq)#{w(3&(Xg)2wfUaIz$HKV4I%z_f7lOLgAaQ-ZiQpg0>YZraQ15Tzg7S z*H(@4Z(4$cYjym+>#h?5-!n>g%g-e&uBk@X4*zdXYJ2mXWi7pU16hO;+e#DL(N9$DE|P~ z3fjW$4d;JuWE+9P39fT?MN+QQ;_%arG57G1px6i=bQd4-d6F)-&<)$e?01{%A?lpZ z7yZ()0&enJRwm>S2yJ!KMMBvhp`aP(XY;!u(2VcyWK`~194xX^xm(8)2hV+Y^6I98*uL#~ zK3no2>T8u~DOMSV7E8r7be_zGTYs*;+;sg0<^q?L60b)>GlA$3@itTJZ0@w;PJI>V z8}zGx7i|qK6!P??bRR+|n``!JF5e)R{7H45I~SlCJL~GT+VXhMS^A&GWkz_-J7LA7~~xdF<)yb#Sw!)EraC+mMA%t0~m!1Toh&_2z%9^ren2y zioF`1-O6~f6FV0P8)hW1p(DZtvb8?hsC0@oyuMcgIu{8pzO5Dw_Mf>B>Lr)}O5-y1 z1}O8t>)cNN%0uNSby(|ZU}_vNsyZq(o-T=9=XPu5W>0{$xdIwaPIHmNamQVYZl45u zO18c$No=Cr2N-`5t#ZS=l-7N}z4JRbef#Km#5pTeUiE6|*u0%^m(oVIeN!9IQNJ8d z$AuZ7{NtsOD@y~R=Tg;24|p6vT0=kg=^RrafBH4YdZyjjbLmn;FRv@;hWtcg^YUn5 z_Uidcvx*SpZ6%m`W@8ZYhWjIXUDEN+>z^!k{^$c|gXGxRtv;c0r)4pFDJij?*N0xL z<=%o~292FcmaGBgkp(Lr;akvcMDy*9aw~LT-+re_MjzxD(fFnN@C)oVqN;u%yA1?7 zZELADmIj`u>+It;Rs!8F(J8SH!eE6X-9d$wme^5t%|KJS9yqG6^Df%_7P>bfAlkNo z89K_E&%0Fj1s%<169`VE+&@l-?X*4B1~PZH}}{1>D9OZyLQ#kigt;=jT2+gZPa?BQ_iJ;5826jhC)H0v=I&pN@{k zqSUe`nG)B_aE-&UJ)NAn$bC{jAlk4Sq&|4bvDCE=s? zGF^LtRq7w=iCPquJ-DcUt4zWk2(7>PL~5i$zkQLjanRl^`kkIuVo^ycSf$1E*~_E+ zV58+L7lYhDfYPLvO-u#aw!D@?77cC+}`zz9ffFi!9TSMtz-3 z$(KIF$o6yX`OJ%uFUcje^wn0NZoq%cMqCIm-c33oe!T`T1*F*eM0x|d6GvFWunCsb zQt>>$_6@LPxU9FYw;Bb-z1-5>J_IGT6nW{+h@uU=T4w~cyg=Y^QCjt5eJoY@xOCV? z0s%JPS8EFRf$}_si*8p(pj2Vm?JRynV0N9?L**C?(&jsG@`7q%3@%D=N_@eAbdY6t#;s!KF*{w&(tg=G2=Ix=VeO6wrai|PrJ#%RA#dvWz7Uro^i$2oa&ff=ddSeX z<7?_xRJ8nYP<;1EO8p}rZjK<#dtJ8KnIQ%8ra7#C6vu{sYP>iZ|KmC8d!lr&kM#zs zQce6S1M5KR^s%qER@YG4!*RS8H$fZSt3u%|t-tDCUyC{ms#HTpUQbL>``an)Q1=+K zm$U6nZ2uentt9=gJL7-<`*#igeI5LJ8~mFJ{>_B{X2O3n;lG*i-%R*#Cj2)O{+kK^ z&4mAE!hbX2znSpgO!#jm{5KQ+n+gBTg#Tv3e>35~neg9C_-`isHxvGw3IEN6|7OB} zGvU9P@ZU`M|IAFtF|(=5%+4#zetqHpGU()pcK$!R6$(x2A`%smmWU)oq#Po_5b0#_ z*AOVO237c?306dCA_5T+c8DND6;fu;rlTV=7?H1t>_p@uBJ&V=hR7=9d?JbwF^h;$ zL_8v*4-spK$U@F15*d-Uh$Ka%Bq9M3>4r!yG^vCtm=U3i2vkH^B7zVRa)wZb4iRIBBuAt)B7xDQDqx6>5lF zM`Si4j}cjm$WcT_BJ$54*MCO5`{Vl0h-F0NBH|Pgm53PhTf~`_^3de01V^MZB6$(1 zibzaE8lp)$RAG+@azscY0vHjlh~PwoA|mh*nUBbGL{_88VMNBF%1<=eh${DxWF}3l zBO)7B9HWU^M2w<}NJRXhB|3?8N0r=&R7NB&nlwd~l!z2WlAuJ$BLW;vIHL+)M5rPH z6A^}J2~r~K5jl=3qY?Rw$W}ydA~F$4o)VFdh;u|#BVrg4v55FYL?e<|rAdB7s-sG5 zL>eQK7LlTeghWfa5&@71cT~ZR2xT;Ziz-YJL5U<}i5y5|JR-l*WHTanQDrJ3FOg&| z5eI3a9#xDZA{r6Dh-gK`CX&b{QXx&^qe^o`QX^6rk+8`7k0g1Ca7Y9{BGeIqjR<2z z&?4v462Md$k;s2E*^bCgctm`oiDp!>i-=StaZHmKi8M$g zJ*pH(Bs3y@k&jQ3%0zIa358UFj|g)_P$NPZ5wJ+YnaGbc*^nyt5t)w2YeW{KeSB&% znuw7^L?q%L5$%ZBMnp1lJ}psAq)8$v5-E@-;ZdbGs$^D7mAWXeGsnr1vI)(epkFUZ zeZ2RN$H9L*-uLS<>rDMj$?U_KirI%V1zfZ}dVcNQ^XnAOKR4(3)xrIHmmN~WPTOAR zR{^i1_byM@?K^jSc>B-nx$~=&jcly*t1WxEhuX_YyF}Cufj`IoMJyx_OGoVxp1tvRarN~GboBQKbp8MOX8^dEw_k->7ahCdV%X;K z92}c}KZ4FW0G&~^Pf~bqfui|)ofccRfS8*StlKr+!RZr`dmp{9`}H^b>kqJaJ!+>{ z_#D9`rcF(|_khL9YTk|UmPkm4@0-JYMZ|D+{@rVzMu2dD`x4QBdZgfT}H)6cs!P2UB(7|3kh9qX&_^>h_9*;I^V_ z^CoR>l%RaOeR}>w5G?Y!T1H$Q?K*+`1Tq$ZqfPD3g^ls(s!!~==IKVtt|Dnq_ww$7 zwk1C4!;izU-R;o(U3UASHQn)fZ-l;qA&;bW-5y3jwo)2RtKEwA1 zeG<^mRcjQJ6>`y+@i)(X=CPqRx4bX6rhkGPs)zcoN+%%Cn3Z?xi?xBPvFN%}3y-3} zMs+(GAv>h8WYgRmm#u+T-GW^^a@HdYI{|-*r<)Pq1F?o`mu#>@EU-1Z?*SGFk5JW5 zrh`jzECuY2O+fhw*Ka4TZ-(r-@+j9^98~7*<2Z2D3bO_sYxwZeoU-v?GowaV66W;? zf;+DUg4T86$;S@pgHLMn%ui%%W5%@F^QRr2qn45+J)ih4(DXWK@BPFE&{ki`F}YL( zG?X9h?%{a~s*4;hnIBMrGMYz6#aymn`K?WiokG4)Yz6A|U$7V5=baD`zKPL~YYgQI zr@PS?!OQs)efL4StO%|?l?LfFJ2LjYvxK(s0W88YtFgm}%%45^FQMuA0nJpmXwax5 z{4QOb2`e34<6pr)is#22ZwLQfT&02sv@>92R~y%gTag6@Ql|$Ci&u`1o2_eLLX8jmz9BpD>->xIwI-I<&pebbX7aCU)o>cxZOf zmU8`r_c$Nj1{x)Q@*Yhvrd0yJ(IU5R@q*Y;eCMeMi!m&x+YMf{I-|LK%6EZXkeq_!>-&+8}+Hh=PoatrkDXMo>7ZT$Ng;Qxo80YscBd%5m* zrriGT_TEm}#NByz+f$Wa_us6P|G2;v>YnR`)V%j)`Fs5dIXMk4|V-A710LfsL9j?i#~Y$K!~ zmHHzDAEEIGSw|>2Lc9@zkkEjH>?4#OA?^r0M@TqA7Sbp|Li`bWk4obGrs`%1IYJx~ zdXSKSgzBRadW5#4l5>PaBvc_G1PSd&$UQ>g5u%O|ii9>KHBSa&OP9&rup#}*7NN7GPnMWfX3AIQFL_!l1GLTSyRAP_vUYhGU zyN$2&>_)!7n={+!{%+2!!u@W}Y^3|Uss8J&`MWu@rSI?N%%;A-n={+`{%&gj=eat+ znjExI&2H}dM|);mf3#-?_D6eWWE{U|4chV{ZL{S6+2un5UeO>b0z?tGi3%za=!gJB z1O_5d76GgXEJeU40x=OFiNHmFgF*xZA|Mrkq6pwbU?p1J-!K;evj}8GfGH~cL_j7Q zltcg{D(FR^EdpQ>n2LZ=1acz4(%B+0zv%^G||RK1-=NpML;Y9Rnh9m^`}B-ms~j z1kxhF6{f;dn1E0ONF#6=0mTUPMF1`WV-c|GFGz}jX9Obqdz}AOn?P(dD2)JS1QsLU z7lF74kVW7s0=f}kjlgFFBqLB50lWyTMFp=Y^8y=nUYNNRAdQ(Bfiz~`?xZm@7m&ux z97P(ln~qaoZFbXfYGZcOacW~`ZX)N*%uMXmXQ-Qwlh(`_XwS_Ig4UWD#edw>_<1@y z@0!_t{D1wPhA^pwFD0xf;XVn&Nq9^eTS;YAY1}E5AtgL0VLJ(@NnR%!exVM(cMF5zqmGfVha z!m`r1R4QXim|eo(5|)<6#S+Gq%BvFgl(4*n%O#90;bjT?N;p=+q*7*y-}e?XZ?E6Y z|D*3|{$mFD>;7i;r=q^_wBY{3b3i}8#~IU%67c!zqSWg($H1U)&^!7ALSSf{jawdf z3;23{`PXeJ$>7_kc?UVQTnHpc1O5oSM+NZ+R7U_g0=p4-kbr;$>LY+2f$a!5M}y#~ zP$2;XX|Nvw_XvbXfI2E1M_@w&4iX5E0DT0`BcL6mLURN{BtRj70}1FypgjWM(O^0P zCsIK}0u2%XkidKd%p;H;fffmXNMJ$&1`^1R0DA>Or%1F1Q;an9|8GjP#zU> zB)}pKK6IplgaisCfFBjsqrr~^WF$}`0SpN&NWecT#7Bc73E)UzMFJiYh>!q*1n#54 zk_3Dt5F-H+30z1(K^pW&AW8y661b6oiUc|&03m?^scC4NWelWB>4Zv z4D$OPWae(=e`y9G^dcb<2~|i4K|=cxa*t4WglZ&&BB2clIY=l#LiEw-JSy!-$VEaS z5~7gMfrRvX~>Bs3u*18I~Wm6{|3B%v7z znMf!@LJSi6kIx#J z5XumdiYS#L8dO52NQ%;6wpIffl6lNLOOZmzaGqrM9nSZ>zw7#)^ZxN(SNorJt-bbI z&))arvG!+u?seZIp!?~ zafygd>aleEv}$_z9uzIFN55HGkM;rYe$+FlLEVpa>5HwPX?dNRKAdbwA{@9){ zqCYyjA*A-PcRjjrCU$(k)Hbk>;c3{;PG)ewW<36}%>nRcq*@Zx-UHQiIVQ%ZtGt^sl=^DANdBlWx@$w;d{#&YMQ;=;yErui zLd4AzX?bJ8CU?;a0o-8auo}^gYo1;|M1xkRd&mWQ zIioeMichLn>mqjdlHp8ESHyWy=aI641>$m?pNN6C!SKyDJtdE_z|d@G7S#0vgSsho zeh>P)jRQ*MzE4JVF%_k0#g?)!M4@!C^Pyd}*(j~SQ&%|O8l`RtOFJ+245fudj|eO> z5%>Y!t}wYqe+poDZAF@xX9=%4YZifszmXv4wKCnh0e3D!{kl(BuA+;F!^X} ziF%JACReAdA2hbdWLM266}~J&GI@{7dsmx7vY5Pu9URt>JpN8cdJ`L@C{*wqQwKJ8J;sB&>RP)TQW{=WIB#0}T6yK%@ z{E_bJI(u>Uc(iAWvr}Yo9uNt0VhKYeY2;Y=Hler~T=Sx$z8$CvZhg*u_}tkE9qqGv z_)xlzgumpZpHT}5|LbOMj_1HIlW2y!v>^%q`lFVQQ%U&uX$lTJ{tN!j8I7PNS4>9M zfS!bZ_1eeM`6T>r`!q=HBjLZNCqPJmgn#pwhdvS{{M+0ZuKb|AuU(i}cl6a@g$qaR1 z;3na(y?wHJ22xn%zJEFNg@nIbxYX%T68@*7KNm})g;R9h!df3m_-{58aLgj%udNiU zA5Fslj0$zwB@+H!ImLdhB>WX#%ek`@ZlCNLTi1FU7)77b=J#s^uuPbNDz^z3#d;kp zCQ0|g64sHY58{xGn?`GPbSg4^%$$_N82!`2A~#IMIh|6l-Ygn5nk?MoVDbTP;^vei zDoIk~DYpbo6UZQ)=C;_#w6l=q?NCb3c^b^b{-;_C|HPEe~|f2I@0zGFwbY| zN8or`BF+0kU@lf_bW`UL*p<|xd~hcN(rV4VabUg>m`Z-u)$?=#$C56kFj!is7)Zaq zYIJZDikja`aYXPnxTdzf#e737c%?(8+%_=_T92MjpBW|npQxC6|B#jxK@V#TW;N3O zwAxs4r*Jpfy@`w(yQ0A+!RJTZe35{5(D3=k7D(`}<>jrk6-eeOJJoUd5+rWS>%Vc= zEyQ`yVA^x>>XJoAgU>ltgZ8OBkCrCX2fGb8j*-X=0lp_Lv~5G5J>}eLY=qH(Zv~Ym z-5YctRd#j&H86Pn_BpNTTR*KmdJYr{oo{|_c0dOuI#6#jjNw9$_Oj`(&z477Gimx> zO1n@jy|;SF^FC12P^HLl$O=8|QdaUBI6zo}sEP;l%jB3Pf{4hY4R%aNk>AzpWs|BM zDB0BOLs-gjRKi-gX?yxKs^00N*L`a@C>N_0o7%n!^x3Xt+#_pU$i`&^2E~~`>g}JMV$3=N~JpBk!V7Co^~f;u~MilS}e|6aR7yl7ucKWbbyohnx2m}DuTq) zS4@HaW1xiW7JXOZ8BiUmWiX*Ji^@Ir>t1El)5=<6{uIceE0}H$9?}|P8O7sUaafvfK zh5JbOU(;!$7Kh|7PgZ;HQ~=}6UNauGLue$>j9&b0Kbn00G}o!!4K1iW6xg*`S19f5 zHNbnv1r40_-i9uVcaJ z@*J%EcJS$yoYzQN^DLVQy&cdF)*f_wo&}_p(F220DWth^z1a<91h)CRaO`Gl8pdFU^PTepuMT?v@hycP!+sAbvDt2VRkNZ1ovwEx01dK$Uyp z23+5{F8r{%C6ut(eq06e|p?P|t z+^{nq1^075r}D>OAyA{$wxI)3c7(m&mwBaD~52LJjY5sH$5=Af?IqyUlnRB zcQ|X5m4#ZO_X*HHxPb;8ISU8Ye#G>{lq=>|=70~IWoY=kbfNfOHA{zeJJ7JkwGUiI z5mu*C|gq>rtrb7;uHr}D)^y> zd2sk^)@&?uoA2ohnpCJ%J}Upr)Bvj9v){F*bs8$tCr)d+v642Y?)}=!&X0vwkVPtV zuESf|wNz!Mk6;a*zH=kN8Bpfp+f(oQw_>H2U%$0cr(uziGZww^&RCS$MbPu&4pfp_ zd-u?dX((`+XEz7^b|_Y4O5eHVID}NX5q3M&;a1lRQf?pOp-}FkUOBA`=o6xndU913 zbTv7+DNUDxHnN#rQD>r2NsEQeoM0E4`LyYk*y|Kb{mf_UY=>Ddhi~WYBU0^xzaAf_vk@=;kwm_zfppI(_2-ILiLbQn1gA@;$<|9yz^W~Phjzy zPOn_2d!T>jL)27M9~Nb6dX~fg3d*NePHd(cfxIV0vc4b8gH&%kxhvGpK%I_R<*oF4 zu<};x9b_M8@zEScU%3E5%$`-BxJug)tKL^;e?;ew6?tP8*0#i9=4&|~jXVlaa3H&6 zZ+rmU3YqfKgAAaC(Vl?)HB@9PA(xX`0hy1e zg}G66VZjeyHaow*gSSd(9A0s)3~Ox9;dgyr0%ZcO+&*{76f2chwQybN#3BP7&-hYT zV^O~R>hJ>%=tWgWjF{##C~zr1<1Be26e}bfUC~qkAsOF^AwzAr^%PA&>*@1QD4|6n zE>q%n4Dfq1>i$1(CH*(V0Dnq%{Ce?cBwpPAe;5DrljfF&$Xg&r`dJnj{I#y){inR&-1w?-+!g?{CCb$n;>1)(#WT?SIs^7Nnl3{_KT-h1DoDZO{gvxE71AQb~ ztc0<2@CPU-In$in)KRedZ@?1+E|)5*XkyBYJf1iWwVvqBR83ZE&at2t{<^aroJ zw`PxDV8$%pT&%TcsIXvnL8ANE0+w8{is77AA(o34q0evT$A;Aw1J5r~V+k)~@|h>U zzCS2bm8mKkeF$1fU9tG4LfRcCaq(K2V*&JJcyo!KWfA&ryt1c#!v|=o&slj?j0wu| zu#e7CYC`cCJ|5|?LCB2fnA%#Ju&16`O`W$V4qDhtBi4fPCEs;2?N1KkYwuOk-CTun zg#IP_yw~|ypGAMph-W3K|IXQP=lhUDyY~yZnm_i0tEl)%6ME1z$(-K68DFwGK1Ee} z2VZMxR@Co%izD=m^}0ecu-=%X@{WdB()0h%={}<6KY~X32MKH`8T*66K>^xMmITW7 z&Vx?%G=GY`7|=~wvSnDS9rPSj%-JKC0(wi+*q>`MHM@~!O>)-fu^uEMH}tBYZ#~kw9JOzEavZYrIJYunsu1le zZ9khdl?4o0Bkld66tGy~+I@D?oUkAVpR$LjU7N(gC$gNRDR)sY{%rc~vj?}qMA3X~ zYL5Y!+;iWdYws}l(olPD2g#~(Vl$&}VE)Bl*5x~V>T_4r)&d3JAgUt;7%>|!eqQy$ z2eCLd$KW-dNIEJjD$vFT$-OTZagZ56%3f;x3QppL^+%!X5zqi;95C*udo(HuuXW^-;Dkrx5|VQN$1+4PXIfy*a{ z>prB6zrwlJ?JIh2>^K?OLxsL1>qUmFDn(n~gOe6h^~-sY2+;L@_H1(X zGw{iCrZm!!3X;uaa_-kM14DhzTDOxdQR^4PKHstelew>=P+`WHbzA(Lmvah{7r|U3 znmbPCjX=8HDe1wct00HP*X^y+kPbunCH{M(@y*+ ziM$AA;MTW|+8K-aM&#I!vwpy9d|RYkm6OrTM&kmn;t5E7!&`Cm3OST;K?-2;^~ zpH}MoOA~n!$UtvVzQ8dA`I=}7>C@8S8jbJiZdn>(zuJYlTkhu_^Z(TUZ*TJ{aAC%8znR8gH>A@*4#&Ljmfuzez{QenuKEy3ZJmvLZ`(zT?7LLv+11qxsU5 z1G?)mYEaY90Yy>{jB47igDwG29!7mU2{*ZNc->R3f(O`Ap1&)33oYv7s-6kuVM8vV zRIQX)tet#=NsUGYnunfxa!>LluwdKu>|=2{DlG}-lG|JhGShjku_SFl*&p0q^j8%j z%Q1DMO2ZydbTh--VRHv~k{&m|H|8}uDKB%dx#l?NWZSeeR(A?B3-p z>tDOI(G*{$s^HqhOvYBZ9xRblI(cO<8ftvJ;h{iIdgX5L?^ROW zhxPrUV&{Tsu*hdd=B7m+tbaj`_a^TxY+^QISF&Cg%ZeQPzTR03o(g;MT1zklvz;^K z;}Mg9HdmFN_O17Y&T5rT-|n$ucfsGj;nSA;((Fl==uez%lh4rCn=Q8QYYsHKdEe@N zvK7`-W2k!c zgBhq>IV^gutN>ER1z77!>0+6p>-^&h{Mf+qiF?q&J$UUGW%Ou`DwGlcl#NH^@%D&_ zj5WUgSV*^yLt0W9>YHA1+BskkMc$mu4N;|s`q!W&bjHx+RJ6LWr8AbLS{=*J%mYt_ zAMhXRm%!|!+)R^+qR=KT*`eJ^2|BCjleX&%VRxZ@kA{2_N%(I}C@%7b#!OpErM;g( zU5zi|*5)GEv#m;dQ{N)gGi|)d5-AC7`K*$^_3eYa&9(dL+Pa{Aea2J^_Ah=svEPLrI#X6GoE_W^!%gL`24%3| zQ0mCX^|J@CQ(n&a(R~Ue{FQ5cdevd@+Ngc(o1;iCa=-Jrzw^2O)_m??w$J=QeqRa# z{#TI`vSFt`KC_q%91N-t9%H8g?#1pW#$h@ieN0<}yJ&MYS73I@Wy752On^Ob6}g!0H^AkA*L5qE zsC^+jn{+Ag5?bwMJlKShtOK2_=)KgFb>@QwEy%khQMj8mLss`2O%xy1} z_(9#%{I9#ee+EsCj*L>TN+JxpZK|Mw6xq{Jq;;j+mIx4xG_Yr7yh2lH& zlR9WMEyFj?XToR=nua*$!R>DLu8jgwDG#CfZ$N@a>yVw z^HC}&yY=IU2E}xxoY8MoK%qUuYk|xuKxi%#)YJHekku`a6FfK{sBX~v9$>&m zfAuHEc~!vsyo$yAm*z4-JzZ``r1FY{u_C(OyKjBO5qZ#})%Hnh@;vyw#hBLQ!1iC% z$z{!Df_jR{4m)`%2^(UH8B;;$^eIejJbJw3b_}Lb>$j2eFj^`#tQaxnt)Y$!T5@Rm zr{*$2J%tp?ifX&pXh5o$9MmbIc951!L)+-XX82K-M zie|~w)toMfVX}ue>Q=rRM|0MdPk1O&(7?fi2l|+-ew22iT7u|ntG{c;g;GLunV_D6 z61{RhkkDNIMLi`xrz}ct)!4;I z6h&pSy^hHQwCv1d`P7#{!e6KVzP#`f{^hKEU^HP#bD5x?lJKX@I}O}O`1>iPzo;SM z-__`6dUXkRGY09O--D+b3ID~+d`@l>{t|K@lQ$F8Q%Ipyo2xHbNWx#~tLJGEF)qJ4Df(4aW%mKqDG( z%#@ZtcHsy9KMwS@&E&qI?qNc6`6u>NFMHl|ThB#I%du1WI?Wx>m(d#J zCw3ch2)_GvZ$A^{d}_Zk<;|nJ zL+#j*eZS*3y>E2LBQsDrJKzQ~ffGBA4Osz)etj-;BSCQ3>}4HuCd=<7mL=-x?& plant_w_spr, const MultibodyPlant& plant_wo_spr) : OscTrackingData(name, n_y, n_ydot, K_p, K_d, W, plant_w_spr, - plant_wo_spr) {} + plant_wo_spr) { + yddot_cmd_lb_ = -100 * VectorXd::Ones(n_ydot_); + yddot_cmd_ub_ = 100 * VectorXd::Ones(n_ydot_); +} void OptionsTrackingData::UpdateActual( const Eigen::VectorXd& x_w_spr, @@ -118,6 +122,7 @@ void OptionsTrackingData::UpdateYddotCmd(double t, yddot_command_ = yddot_des_converted_ + p_gain_multiplier * K_p_ * error_y_ + d_gain_multiplier * K_d_ * error_ydot_; + yddot_command_ = eigen_clamp(yddot_command_, yddot_cmd_lb_, yddot_cmd_ub_); UpdateW(t, t_since_state_switch); } @@ -188,4 +193,11 @@ void OptionsTrackingData::SetTimerVaryingFeedForwardAccelMultiplier( ff_accel_multiplier_traj_ = ff_accel_multiplier_traj; } +void OptionsTrackingData::SetCmdAccelerationBounds(Eigen::VectorXd& lb, Eigen::VectorXd& ub){ + DRAKE_DEMAND(lb.size() == n_ydot_); + DRAKE_DEMAND(ub.size() == n_ydot_); + yddot_cmd_lb_ = lb; + yddot_cmd_ub_ = ub; +}; + } // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index fc8593af7a..3b1484fd1a 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -23,7 +23,8 @@ class OptionsTrackingData : public OscTrackingData { // TOOD(yminchen): You can make ratio dictionary so that we have one ratio per // finite state void SetTimeVaryingWeights( - std::shared_ptr> weight_trajectory); + std::shared_ptr> + weight_trajectory); void SetTimeVaryingPDGainMultiplier( std::shared_ptr> @@ -31,22 +32,26 @@ class OptionsTrackingData : public OscTrackingData { void SetTimeVaryingProportionalGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory); + gain_multiplier_trajectory); void SetTimeVaryingDerivativeGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory); + gain_multiplier_trajectory); void SetTimerVaryingFeedForwardAccelMultiplier( std::shared_ptr> - ff_accel_multiplier_traj); + ff_accel_multiplier_traj); + + void SetCmdAccelerationBounds(Eigen::VectorXd& lb, Eigen::VectorXd& ub); void SetViewFrame(std::shared_ptr> view_frame) { view_frame_ = view_frame; with_view_frame_ = true; } - const Eigen::MatrixXd& GetWeight() const override { return time_varying_weight_; } + const Eigen::MatrixXd& GetWeight() const override { + return time_varying_weight_; + } // disable feedforward acceleration for the components of the task space given // by indices @@ -59,21 +64,23 @@ class OptionsTrackingData : public OscTrackingData { void AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, int fsm_state); protected: - std::shared_ptr< - drake::trajectories::Trajectory> ff_accel_multiplier_traj_; - std::shared_ptr< - drake::trajectories::Trajectory> p_gain_multiplier_traj_; - std::shared_ptr< - drake::trajectories::Trajectory> d_gain_multiplier_traj_; + std::shared_ptr> + ff_accel_multiplier_traj_; + std::shared_ptr> + p_gain_multiplier_traj_; + std::shared_ptr> + d_gain_multiplier_traj_; std::shared_ptr> weight_trajectory_; + Eigen::VectorXd yddot_cmd_lb_; + Eigen::VectorXd yddot_cmd_ub_; + std::set idx_zero_feedforward_accel_ = {}; std::shared_ptr> view_frame_; Eigen::Matrix3d view_frame_rot_T_; bool with_view_frame_ = false; private: - // This method is called from the parent class (OscTrackingData) due to C++ // polymorphism. void UpdateActual(const Eigen::VectorXd& x_w_spr, @@ -104,7 +111,6 @@ class OptionsTrackingData : public OscTrackingData { double tau_ = -1; std::set low_pass_filter_element_idx_; double last_timestamp_ = -1; - }; } // namespace controllers From 9baf77ba66eebff00e19bb1bf41647f1329c69f8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Feb 2023 15:08:38 -0500 Subject: [PATCH 368/758] adjusting xoffset at land --- .../pydairlib/analysis/log_plotter_cassie.py | 18 ++++++++------- .../pydairlib/analysis/mbp_plotting_utils.py | 7 ++++-- .../plot_configs/cassie_jumping_plot.yaml | 8 +++---- .../lcm/visualization/visualize_trajectory.py | 4 ++-- .../Cassie/osc_jump/osc_jumping_gains.yaml | 2 +- .../osc_jump/pelvis_trans_traj_generator.h | 2 +- examples/Cassie/run_dircon_jumping.cc | 22 +++++++++---------- .../gait_parameters/dircon_box_jump.yaml | 14 ++++++------ 8 files changed, 41 insertions(+), 36 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 21fcb12447..feb5c13e49 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -163,14 +163,16 @@ def main(): foot_frames = [] dims = {} pts = {} - for pos in plot_config.foot_positions_to_plot: - foot_frames.append('toe_' + pos) - dims['toe_' + pos] = plot_config.foot_xyz_to_plot[pos] - pts['toe_' + pos] = pts_map[plot_config.pt_on_foot_to_plot] - - plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, - foot_frames, pts, dims) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot = None + for pt_on_foot_to_plot in plot_config.pt_on_foot_to_plot: + for pos in plot_config.foot_positions_to_plot: + foot_frames.append('toe_' + pos) + dims['toe_' + pos] = plot_config.foot_xyz_to_plot[pos] + pts['toe_' + pos] = pts_map[pt_on_foot_to_plot] + + plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, + foot_frames, pts, dims, plot) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_qp_solve_time: plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index ca745d0bcf..2ce5c02433 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -388,7 +388,10 @@ def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): def plot_points_positions(robot_output, time_slice, plant, context, frame_names, - pts, dims): + pts, dims, ps=None): + if ps is None: + ps = plot_styler.PlotStyler() + dim_map = ['_x', '_y', '_z'] data_dict = {'t': robot_output['t_x']} legend_entries = {} @@ -399,7 +402,7 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, plant, context, frame, pt) legend_entries[name] = [name + dim_map[dim] for dim in dims[name]] - ps = plot_styler.PlotStyler() + plotting_utils.make_plot( data_dict, 't', diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 1895e04c43..52961783ff 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -7,8 +7,8 @@ use_archived_lcmtypes: false use_default_styling: false # Log time to stop at (seconds, -1 for whole log) -start_time: 7 -duration: 5 +start_time: 15 +duration: 10 # Plant properties use_springs: true @@ -35,7 +35,7 @@ foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] foot_xyz_to_plot: { 'right': [2], 'left': [2] } #foot_xyz_to_plot: { } -pt_on_foot_to_plot: 'front' # takes value 'front', 'mid', or 'rear' +pt_on_foot_to_plot: ['front', 'rear'] # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true @@ -44,7 +44,7 @@ plot_qp_solutions: true plot_tracking_costs: true plot_active_tracking_datas: true tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel'] }, + pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 9c72aba548..4bfb919509 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -18,8 +18,8 @@ def main(): # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' - # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' - visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' params = DirconVisualizationParams(visualization_config_file) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index d1d2935f2c..8ea45ec06c 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -43,7 +43,7 @@ CoMW: 0, 2, 0, 0, 0, 20] CoMKp: - [30, 0, 0, + [40, 0, 0, 0, 50, 0, 0, 0, 40] CoMKd: diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h index 56ab16efe7..27efe858eb 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h @@ -69,7 +69,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { // The trajectory optimization solution sets the final CoM very close to // rear toe contacts - this is an offset to move it closer to the center of // the support polygon - static constexpr double kLandingOffset = 0.00; // 0.04 m (4cm) + static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) // static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) }; diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index f60a155a32..743c259ace 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -768,20 +768,20 @@ void SetKinematicConstraints(Dircon* trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground - for (int index = 0; index < (mode_lengths[0] - 2); index++) { - auto lambda = trajopt->force_vars(0, index); - prog->AddLinearConstraint(lambda(2) >= 60); - prog->AddLinearConstraint(lambda(5) >= 60); - prog->AddLinearConstraint(lambda(8) >= 60); - prog->AddLinearConstraint(lambda(11) >= 60); - } +// for (int index = 0; index < (mode_lengths[0] - 2); index++) { +// auto lambda = trajopt->force_vars(0, index); +// prog->AddLinearConstraint(lambda(2) >= 60); +// prog->AddLinearConstraint(lambda(5) >= 60); +// prog->AddLinearConstraint(lambda(8) >= 60); +// prog->AddLinearConstraint(lambda(11) >= 60); +// } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); - prog->AddLinearConstraint(lambda(2) <= 300); - prog->AddLinearConstraint(lambda(5) <= 300); - prog->AddLinearConstraint(lambda(8) <= 300); - prog->AddLinearConstraint(lambda(11) <= 300); + prog->AddLinearConstraint(lambda(2) <= 100); + prog->AddLinearConstraint(lambda(5) <= 100); + prog->AddLinearConstraint(lambda(8) <= 100); + prog->AddLinearConstraint(lambda(11) <= 100); prog->AddLinearConstraint(lambda(2) >= 50); prog->AddLinearConstraint(lambda(5) >= 50); prog->AddLinearConstraint(lambda(8) >= 50); diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml index d8a5b9a758..2108932f92 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_box_jump.yaml @@ -1,7 +1,7 @@ spring_urdf: examples/Cassie/urdf/cassie_v2.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf -knot_points: 10 +knot_points: 8 delta_height: 0.5 start_height: 0.8 distance: 0.3 @@ -9,8 +9,8 @@ min_stance_duration: 0.2 max_stance_duration: 1.5 min_flight_duration: 0.1 max_flight_duration: 1.0 -actuator_limit: 0.85 -input_delta: 60 +actuator_limit: 1.0 +input_delta: 80 snopt_scale_option: 0 tol: 1e-4 @@ -20,13 +20,13 @@ compl_inf_tol: 1e-4 acceptable_tol: 1e-3 acceptable_iter: 10 cost_scaling: 1e-3 -use_ipopt: true +use_ipopt: false ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ -load_filename: box_jump_4 -save_filename: box_jump_5 +load_filename: box_jump_5 +save_filename: box_jump_6 use_springs: false convert_to_springs: false -same_knotpoints: false +same_knotpoints: true From 56837f59f6b8f9f7c283ff879159293439c47443 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Feb 2023 17:07:47 -0500 Subject: [PATCH 369/758] adding landing offset to gains --- examples/Cassie/osc_jump/osc_jumping_gains.h | 6 ++++-- examples/Cassie/osc_jump/osc_jumping_gains.yaml | 5 +++-- .../Cassie/osc_jump/pelvis_trans_traj_generator.cc | 14 +++++++------- .../Cassie/osc_jump/pelvis_trans_traj_generator.h | 13 +++++++++---- examples/Cassie/run_osc_jumping_controller.cc | 4 +++- 5 files changed, 26 insertions(+), 16 deletions(-) diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.h b/examples/Cassie/osc_jump/osc_jumping_gains.h index 21934de792..29ee3efc5e 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.h +++ b/examples/Cassie/osc_jump/osc_jumping_gains.h @@ -7,7 +7,8 @@ using Eigen::MatrixXd; struct OSCJumpingGains : OSCGains { // costs - double x_offset; + double crouch_x_offset; + double land_x_offset; // center of mass tracking std::vector CoMW; std::vector CoMKp; @@ -49,7 +50,8 @@ struct OSCJumpingGains : OSCGains { template void Serialize(Archive* a) { OSCGains::Serialize(a); - a->Visit(DRAKE_NVP(x_offset)); + a->Visit(DRAKE_NVP(crouch_x_offset)); + a->Visit(DRAKE_NVP(land_x_offset)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); a->Visit(DRAKE_NVP(CoMKd)); diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 8ea45ec06c..ecafcbca8e 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -18,7 +18,8 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -x_offset: 0.043 +crouch_x_offset: 0.043 +land_x_offset: 0.04 relative_feet: true mu: 0.6 @@ -33,7 +34,7 @@ hip_yaw_kd: 5 min_pelvis_acc: -5 max_pelvis_acc: 25 -impact_threshold: 0.050 +impact_threshold: 0.000 impact_tau: 0.005 #landing_delay: -0.035 landing_delay: -0.0 diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc index ea59ad508e..0d488cdf54 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc @@ -102,7 +102,7 @@ EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( switch_time << timestamp; } // Offset desired pelvis location based on final landing location - pelvis_x_offset(0) = kLandingOffset; + pelvis_x_offset(0) = landing_x_offset_; } if (initial_pelvis_pos == VectorXd::Zero(3)) { VectorXd q = robot_output->GetPositions(); @@ -117,7 +117,7 @@ EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( } drake::trajectories::PiecewisePolynomial -PelvisTransTrajGenerator::generateBalanceTraj( +PelvisTransTrajGenerator::GenerateBalanceTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const { plant_.SetPositionsAndVelocities(context_, x); @@ -150,7 +150,7 @@ PelvisTransTrajGenerator::generateBalanceTraj( } drake::trajectories::PiecewisePolynomial -PelvisTransTrajGenerator::generateCrouchTraj(const Eigen::VectorXd& x, +PelvisTransTrajGenerator::GenerateCrouchTraj(const Eigen::VectorXd& x, double time) const { // This assumes that the crouch is starting at the exact position as the // start of the target trajectory which should be handled by balance @@ -175,7 +175,7 @@ PelvisTransTrajGenerator::generateCrouchTraj(const Eigen::VectorXd& x, } drake::trajectories::PiecewisePolynomial -PelvisTransTrajGenerator::generateLandingTraj( +PelvisTransTrajGenerator::GenerateLandingTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const { plant_.SetPositionsAndVelocities(context_, x); @@ -230,11 +230,11 @@ void PelvisTransTrajGenerator::CalcTraj( const drake::VectorX& x = robot_output->GetState(); if (fsm_state[0] == BALANCE) - *casted_traj = generateBalanceTraj(context, x, time); + *casted_traj = GenerateBalanceTraj(context, x, time); else if (fsm_state[0] == CROUCH) - *casted_traj = generateCrouchTraj(x, time); + *casted_traj = GenerateCrouchTraj(x, time); else if (fsm_state[0] == LAND) - *casted_traj = generateLandingTraj(context, x, time); + *casted_traj = GenerateLandingTraj(context, x, time); } } // namespace dairlib::examples::osc_jump \ No newline at end of file diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h index 27efe858eb..ddbf25ce8b 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h @@ -28,13 +28,17 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { return this->get_input_port(fsm_port_); } + void SetLandingOffset(double landing_x_offset){ + landing_x_offset_ = landing_x_offset; + } + private: - drake::trajectories::PiecewisePolynomial generateBalanceTraj( + drake::trajectories::PiecewisePolynomial GenerateBalanceTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const; - drake::trajectories::PiecewisePolynomial generateCrouchTraj( + drake::trajectories::PiecewisePolynomial GenerateCrouchTraj( const Eigen::VectorXd& x, double time) const; - drake::trajectories::PiecewisePolynomial generateLandingTraj( + drake::trajectories::PiecewisePolynomial GenerateLandingTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const; @@ -62,6 +66,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { std::pair&>>& feet_contact_points_; double time_offset_; + double landing_x_offset_ = 0.00; drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex fsm_port_; @@ -69,7 +74,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { // The trajectory optimization solution sets the final CoM very close to // rear toe contacts - this is an offset to move it closer to the center of // the support polygon - static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) +// static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) // static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) }; diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 8783bf4a27..dd93d12f5a 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -227,7 +227,7 @@ int DoMain(int argc, char* argv[]) { // Offset the output trajectories to account for the starting global position // of the robot Vector3d support_center_offset; - support_center_offset << osc_gains.x_offset, 0.0, 0.0; + support_center_offset << osc_gains.crouch_x_offset, 0.0, 0.0; std::vector breaks = pelvis_trans_traj.get_segment_times(); VectorXd breaks_vector = Eigen::Map(breaks.data(), breaks.size()); MatrixXd offset_points = support_center_offset.replicate(1, breaks.size()); @@ -295,6 +295,8 @@ int DoMain(int argc, char* argv[]) { std::cerr << "Unknown simulator type!" << std::endl; } + pelvis_trans_traj_generator->SetLandingOffset(osc_gains.land_x_offset); + /**** OSC setup ****/ // Cost osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); From 9dbef2f642ec871cf9c0b09bf1c53f1a85d858bd Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 11 Feb 2023 19:16:15 -0500 Subject: [PATCH 370/758] small visualization changes --- .../plot_configs/cassie_jumping_plot.yaml | 6 +++--- .../visualize_configs/box_jump.yaml | 4 ++-- .../lcm/visualization/visualize_trajectory.py | 19 +++++++++++++++---- examples/Cassie/multibody_sim_w_platform.cc | 2 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 6 +++--- 5 files changed, 24 insertions(+), 13 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 52961783ff..4ed22b87ff 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -7,8 +7,8 @@ use_archived_lcmtypes: false use_default_styling: false # Log time to stop at (seconds, -1 for whole log) -start_time: 15 -duration: 10 +start_time: 7 +duration: -1 # Plant properties use_springs: true @@ -48,7 +48,7 @@ tracking_datas_to_plot: { # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, -# left_ft_traj: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel']}, + left_ft_traj: {'dims': [2], 'derivs': ['pos']}, # right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml index fb3db70055..3a18a9c795 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml @@ -1,8 +1,8 @@ filename: examples/Cassie/saved_trajectories/box_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 1 +visualize_mode: 2 realtime_rate: 0.5 -num_poses: 8 +num_poses: 1 use_transparency: 1 use_springs: 1ss \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 4bfb919509..98100d6e55 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -2,7 +2,8 @@ import matplotlib.pyplot as plt from pydairlib.lcm import lcm_trajectory from pydairlib.common import FindResourceOrThrow -from pydrake.all import PiecewisePolynomial, Box, RigidTransform +from pydrake.all import PiecewisePolynomial, Box, RigidTransform, Meshcat + import numpy as np from pydrake.all import (DiagramBuilder, AddMultibodyPlantSceneGraph, Simulator, @@ -96,16 +97,26 @@ def main(): poses[i] = optimal_traj.value( t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] # poses[i, 6] += 0.5 - alpha_scale = np.linspace(0.2, 1.0, params.num_poses) + # alpha_scale = np.linspace(0.2, 1.0, params.num_poses) + alpha_scale = np.linspace(1.0, 1.0, params.num_poses) visualizer = MultiposeVisualizer(FindResourceOrThrow( vis_urdf), params.num_poses, np.square(alpha_scale), "") # translation = np.array([-0.25, 0, 0.25]) + ortho_camera = Meshcat.OrthographicCamera() + ortho_camera.top = 1 + ortho_camera.bottom = -0.1 + ortho_camera.left = -1 + ortho_camera.right = 2 + ortho_camera.near = -10 + ortho_camera.far = 500 + ortho_camera.zoom = 1 translation = np.array([0.5, 0, 0.25]) origin = RigidTransform(translation) box = Box(0.5, 1.0, 0.5) - visualizer.GetMeshcat().SetObject("box", box) - visualizer.GetMeshcat().SetTransform("box", origin) + # visualizer.GetMeshcat().SetObject("box", box) + # visualizer.GetMeshcat().SetTransform("box", origin) + visualizer.GetMeshcat().SetCamera(ortho_camera) visualizer.DrawPoses(poses.T) while(True): continue diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index cd928239f3..fe53534a44 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -89,7 +89,7 @@ int do_main(int argc, char* argv[]) { const double time_step = FLAGS_dt; MultibodyPlant& plant = *builder.AddSystem(time_step); if (FLAGS_floating_base) { - multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); + multibody::AddFlatTerrain(&plant, &scene_graph, .6, .6); } std::string urdf = FLAGS_spring_model diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index ecafcbca8e..6c55f5cfdf 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -18,7 +18,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: 0.043 +crouch_x_offset: 0.01 land_x_offset: 0.04 relative_feet: true @@ -36,8 +36,8 @@ min_pelvis_acc: -5 max_pelvis_acc: 25 impact_threshold: 0.000 impact_tau: 0.005 -#landing_delay: -0.035 -landing_delay: -0.0 +landing_delay: 0.15 +#landing_delay: 0. CoMW: [20, 0, 0, From 20ee41af051043fe899f51abb88cbfc130181c4d Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Feb 2023 10:46:39 -0500 Subject: [PATCH 371/758] small controller fixes --- .../visualize_configs/down_jump.yaml | 2 +- .../visualize_configs/long_jump.yaml | 2 +- .../lcm/visualization/visualize_trajectory.py | 4 +- examples/Cassie/osc/osc_standing_gains.h | 4 -- .../Cassie/osc/osc_standing_gains_sim.yaml | 39 ++++++++----------- .../Cassie/osc_jump/osc_jumping_gains.yaml | 14 +++---- .../Cassie/run_osc_standing_controller.cc | 17 +++++--- .../controllers/osc/options_tracking_data.cc | 4 +- 8 files changed, 41 insertions(+), 45 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml index 6fc6fd254a..044a719068 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml @@ -2,7 +2,7 @@ filename: examples/Cassie/saved_trajectories/down_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 -realtime_rate: 1.0 +realtime_rate: 0.1 num_poses: 9 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml index 16187491f0..1c76ce8490 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml @@ -1,7 +1,7 @@ filename: examples/Cassie/saved_trajectories/long_jump_conservative spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 2 +visualize_mode: 1 realtime_rate: 0.5 num_poses: 5 use_transparency: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 98100d6e55..67c3e15fe4 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -18,8 +18,8 @@ def main(): - # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' - visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' params = DirconVisualizationParams(visualization_config_file) diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h index 6a6f05ca35..a6a832fecb 100644 --- a/examples/Cassie/osc/osc_standing_gains.h +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -9,8 +9,6 @@ using Eigen::MatrixXd; struct OSCStandingGains : OSCGains { double weight_scaling; - int rows; - int cols; double HipYawKp; double HipYawKd; double HipYawW; @@ -39,8 +37,6 @@ struct OSCStandingGains : OSCGains { void Serialize(Archive* a) { OSCGains::Serialize(a); a->Visit(DRAKE_NVP(weight_scaling)); - a->Visit(DRAKE_NVP(rows)); - a->Visit(DRAKE_NVP(cols)); a->Visit(DRAKE_NVP(PelvisW)); a->Visit(DRAKE_NVP(PelvisKp)); a->Visit(DRAKE_NVP(PelvisKd)); diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index bf8564197e..89da19d882 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -6,29 +6,24 @@ # -Kp * x + Kd * sqrt(g/l) * x = g/l * x # Kp = sqrt(g/l) * Kd - g/l controller_frequency: 1000 - -rows: 3 -cols: 3 -w_input: 0.0 -w_accel: 0.000 -w_lambda: 0.000000 -#W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, -# 1, 1, 1, 1, 0.01, 0.001, -# 1, 1, 1, 1, 0.01, 0.001 ] -W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] -W_input_reg: [ 1, 0.9, 0.6, 0.3, 5, - 1, 0.9, 0.5, 0.1, 5 ] -W_lambda_c_reg: [ 1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01 ] -#W_lambda_h_reg: [ 0.02, 0.02 ] -W_lambda_h_reg: [ 0.001, 0.001, 0.001, - 0.001, 0.002, 0.002 ] +w_input: 0.000001 +w_lambda: 0.1 +w_accel: 0.0001 +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, + 0.5, 0.9, 0.5, 0.1, 0.1] +# left toe, left heel, right toe, right heel: x y z +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] w_soft_constraint: 0 -w_input_reg: 0.00 +w_input_reg: 0.01 impact_threshold: 0.00 center_of_mass_filter_tau: 0.0001 rot_filter_tau: 0.001 diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index 6c55f5cfdf..e9b0b731b9 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -18,8 +18,8 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: 0.01 -land_x_offset: 0.04 +crouch_x_offset: 0.04 +land_x_offset: 0.00 relative_feet: true mu: 0.6 @@ -32,11 +32,11 @@ w_hip_yaw: 2.5 hip_yaw_kp: 100 hip_yaw_kd: 5 -min_pelvis_acc: -5 -max_pelvis_acc: 25 +min_pelvis_acc: -7 +max_pelvis_acc: 10000 impact_threshold: 0.000 impact_tau: 0.005 -landing_delay: 0.15 +landing_delay: 0.0 #landing_delay: 0. CoMW: @@ -44,7 +44,7 @@ CoMW: 0, 2, 0, 0, 0, 20] CoMKp: - [40, 0, 0, + [50, 0, 0, 0, 50, 0, 0, 0, 40] CoMKd: @@ -70,7 +70,7 @@ FlightFootW: FlightFootKp: [125, 0, 0, 0, 50, 0, - 0, 0, 100] + 0, 0, 200] FlightFootKd: [2.5, 0, 0, 0, 2.5, 0, diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 99a4a5bab6..103494d210 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -220,14 +220,18 @@ int DoMain(int argc, char* argv[]) { int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingCostWeights(gains.w_input_reg * - gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * + osc_gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * + osc->SetLambdaContactRegularizationWeight(gains.w_lambda * + gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(1e-5 * gains.W_lambda_h_regularization); - osc->SetJointLimitWeight(1.0); + // Soft constraint on contacts + osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); - auto pelvis_view_frame = std::make_shared>(plant.GetBodyByName("pelvis")); + auto pelvis_view_frame = std::make_shared>( + plant.GetBodyByName("pelvis")); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), plant, plant); @@ -275,7 +279,8 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(osc->get_output_port_osc_command(), command_sender->get_input_port(0)); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); builder.Connect(com_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("pelvis_trans_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index 6ecfc48e8a..3d126639dc 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -23,8 +23,8 @@ OptionsTrackingData::OptionsTrackingData( const MultibodyPlant& plant_wo_spr) : OscTrackingData(name, n_y, n_ydot, K_p, K_d, W, plant_w_spr, plant_wo_spr) { - yddot_cmd_lb_ = -100 * VectorXd::Ones(n_ydot_); - yddot_cmd_ub_ = 100 * VectorXd::Ones(n_ydot_); + yddot_cmd_lb_ = std::numeric_limits::lowest() * VectorXd::Ones(n_ydot_); + yddot_cmd_ub_ = std::numeric_limits::max() * VectorXd::Ones(n_ydot_); } void OptionsTrackingData::UpdateActual( From 0531389aa15c00537e0c9c758735b2fa29c48052 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 15 Feb 2023 14:40:46 -0500 Subject: [PATCH 372/758] working on long jumping in sim --- .../Cassie/osc/osc_standing_gains_sim.yaml | 37 ++++++++++--------- .../Cassie/osc_jump/osc_jumping_gains.yaml | 2 +- examples/Cassie/run_dircon_jumping.cc | 12 +++--- .../Cassie/run_osc_standing_controller.cc | 21 ++++------- .../gait_parameters/dircon_long_jump.yaml | 6 +-- .../cassie_fixed_springs_conservative.urdf | 12 +++--- 6 files changed, 44 insertions(+), 46 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index 89da19d882..0f1d60a8ef 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -6,24 +6,27 @@ # -Kp * x + Kd * sqrt(g/l) * x = g/l * x # Kp = sqrt(g/l) * Kd - g/l controller_frequency: 1000 -w_input: 0.000001 -w_lambda: 0.1 -w_accel: 0.0001 -W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, - 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, - 0.5, 0.9, 0.5, 0.1, 0.1] -# left toe, left heel, right toe, right heel: x y z -W_lambda_c_reg: [1, 0.001, 0.01, - 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01] -# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop -W_lambda_h_reg: [0.01, 0.01, 0.01, - 0.01, 0.02, 0.02] + +w_input: 0.0 +w_accel: 0.000 +w_lambda: 0.000000 +#W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, +# 1, 1, 1, 1, 0.01, 0.001, +# 1, 1, 1, 1, 0.01, 0.001 ] +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] +W_input_reg: [ 1, 0.9, 0.6, 0.3, 5, + 1, 0.9, 0.5, 0.1, 5 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01 ] +#W_lambda_h_reg: [ 0.02, 0.02 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.002, 0.002 ] w_soft_constraint: 0 -w_input_reg: 0.01 +w_input_reg: 0.00 impact_threshold: 0.00 center_of_mass_filter_tau: 0.0001 rot_filter_tau: 0.001 diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index e9b0b731b9..fe2b064bd3 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -34,7 +34,7 @@ hip_yaw_kd: 5 min_pelvis_acc: -7 max_pelvis_acc: 10000 -impact_threshold: 0.000 +impact_threshold: 0.050 impact_tau: 0.005 landing_delay: 0.0 #landing_delay: 0. diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 743c259ace..9684e39574 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -659,11 +659,11 @@ void SetKinematicConstraints(Dircon* trajopt, auto left_foot_y_constraint = std::make_shared>( plant, "toe_left", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - 0.1 * VectorXd::Ones(1), 0.2 * VectorXd::Ones(1)); + 0.1 * VectorXd::Ones(1), 0.15 * VectorXd::Ones(1)); auto right_foot_y_constraint = std::make_shared>( plant, "toe_right", Vector3d::Zero(), Eigen::RowVector3d(0, 1, 0), - -0.2 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); + -0.15 * VectorXd::Ones(1), -0.1 * VectorXd::Ones(1)); auto left_foot_z_ground_constraint = std::make_shared>( plant, "toe_left", pt_front_contact, Eigen::RowVector3d(0, 0, 1), @@ -778,10 +778,10 @@ void SetKinematicConstraints(Dircon* trajopt, // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); - prog->AddLinearConstraint(lambda(2) <= 100); - prog->AddLinearConstraint(lambda(5) <= 100); - prog->AddLinearConstraint(lambda(8) <= 100); - prog->AddLinearConstraint(lambda(11) <= 100); + prog->AddLinearConstraint(lambda(2) <= 325); + prog->AddLinearConstraint(lambda(5) <= 325); + prog->AddLinearConstraint(lambda(8) <= 325); + prog->AddLinearConstraint(lambda(11) <= 325); prog->AddLinearConstraint(lambda(2) >= 50); prog->AddLinearConstraint(lambda(5) >= 50); prog->AddLinearConstraint(lambda(8) >= 50); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 103494d210..25f7d77211 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -220,18 +220,14 @@ int DoMain(int argc, char* argv[]) { int n_v = plant.num_velocities(); osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * - osc_gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.w_input_reg * + gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaContactRegularizationWeight(gains.w_lambda * - gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); - // Soft constraint on contacts - osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); - - auto pelvis_view_frame = std::make_shared>( - plant.GetBodyByName("pelvis")); + osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * + gains.W_lambda_h_regularization); + osc->SetJointLimitWeight(1.0); + + auto pelvis_view_frame = std::make_shared>(plant.GetBodyByName("pelvis")); auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), plant, plant); @@ -279,8 +275,7 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(osc->get_output_port_osc_command(), command_sender->get_input_port(0)); - builder.Connect(osc->get_output_port_osc_debug(), - osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); builder.Connect(com_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("pelvis_trans_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml index 258c0bfec1..81575740ad 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml @@ -3,14 +3,14 @@ fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf knot_points: 8 delta_height: 0.0 -start_height: 0.8 +start_height: 0.85 distance: 0.7 min_stance_duration: 0.2 max_stance_duration: 1.0 min_flight_duration: 0.1 max_flight_duration: 1.0 actuator_limit: 1.0 -input_delta: 75 +input_delta: 80 snopt_scale_option: 0 tol: 1e-4 @@ -25,7 +25,7 @@ ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ load_filename: long_jump_conservative_1 -save_filename: long_jump_conservative_2 +save_filename: long_jump_conservative use_springs: false convert_to_springs: false same_knotpoints: true diff --git a/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf index e4ea5951c2..0bc93d7fac 100644 --- a/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf +++ b/examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf @@ -617,7 +617,7 @@ - + @@ -626,7 +626,7 @@ - + @@ -636,7 +636,7 @@ - + @@ -645,7 +645,7 @@ - + @@ -673,7 +673,7 @@ - + @@ -682,7 +682,7 @@ - + From 8a557c53031ed656cdbbf59b5b58ebf81b23eba2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 15 Feb 2023 15:40:44 -0500 Subject: [PATCH 373/758] adding task space example --- .../plot_five_link_biped.py | 77 +++++++++++++------ 1 file changed, 52 insertions(+), 25 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 075dee7df1..68a9e3b0d1 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -89,11 +89,11 @@ def main(): nx = plant.num_positions() + plant.num_velocities() nu = plant.num_actuators() nc = 2 + ny = 5 n_samples = 1000 window_length = 0.05 tau = 0.002 - selected_joint_idxs = slice(6,7) - # selected_joint_idxs = slice(0, 7) + selected_joint_idxs = slice(0, 7) # Map to 2d TXZ = np.array([[1, 0, 0], [0, 0, 1]]) @@ -123,22 +123,23 @@ def main(): pt_on_body, world, world) M_Jt = M_inv @ J_r.T - - # compute_control_law(M_Jt, np.ones(nv)) - P = null_space(M_Jt.T).T proj_ii = np.eye(nv) - M_Jt @ np.linalg.inv(M_Jt.T @ M_Jt) @ M_Jt.T - J_M_Jt = J_r @ M_inv @ J_r.T - proj_y_ii = np.eye(2) - J_M_Jt @ J_M_Jt @ np.linalg.inv( + J_y_stack = np.vstack((J_l, J_r, np.array([0, 0, 1, 0, 0, 0, 0]))) + J_M_Jt = J_y_stack @ M_inv @ J_r.T + proj_y_ii = np.eye(5) - J_M_Jt @ np.linalg.inv( J_M_Jt.T @ J_M_Jt) @ J_M_Jt.T + P_y = null_space(J_M_Jt.T) + P_y = P_y @ P_y.T v_pre = x_pre[-nv:] v_post = x_post[-nv:] t_impact = dircon_traj.GetStateBreaks(0)[-1] + J_y = J_y_stack # J_y = np.zeros((4, 7)) - J_y = np.eye((7)) + # J_y = np.eye((7)) # J_y[0, 0] = 1 # J_y[0, 1] = 1 # J_y[0, 2] = 1 @@ -160,16 +161,21 @@ def main(): end_idx - start_idx) print(start_idx) print(end_idx) - # t_proj = np.array( - # [t_impact[0] - 1.5*window_length, t_impact[0] + 1.5*window_length]) t_proj = np.array( - [t_impact[0] - window_length, t_impact[0] + window_length]) + [t_impact[0] - 1.5*window_length, t_impact[0] + 1.5*window_length]) - vel_proj = np.zeros((t.shape[0], nv)) + vel_proj_desired = np.zeros((t.shape[0], nv)) vel_proj_actual = np.zeros((t.shape[0], nv)) vel_time_varying_proj = np.zeros((t.shape[0], nv)) - vel = np.zeros((t.shape[0], nv)) + vel_desired = np.zeros((t.shape[0], nv)) vel_actual = np.zeros((t.shape[0], nv)) + taskspace_vel_actual = np.zeros((t.shape[0], ny)) + taskspace_vel_desired = np.zeros((t.shape[0], ny)) + taskspace_vel_error = np.zeros((t.shape[0], ny)) + taskspace_vel_actual_proj = np.zeros((t.shape[0], ny)) + taskspace_vel_desired_proj = np.zeros((t.shape[0], ny)) + taskspace_vel_error_proj = np.zeros((t.shape[0], ny)) + taskspace_vel_error_osc = np.zeros((t.shape[0], ny)) vel_corrected = np.zeros((t.shape[0], nv)) vel_correction = np.zeros((t.shape[0], nv)) vel_corrected_blend = np.zeros((t.shape[0], nv)) @@ -178,10 +184,16 @@ def main(): # for i in range(0, end_idx - start_idx): # x = state_traj.value(t[i]) x = state_traj.value(robot_output['t_x'][i + start_idx]) - vel[i] = x[-nv:, 0] + vel_desired[i] = x[-nv:, 0] vel_actual[i] = robot_output['v'][i + start_idx] - vel_proj[i] = P.T @ P @ vel[i] + vel_proj_desired[i] = P.T @ P @ vel_desired[i] vel_proj_actual[i] = P.T @ P @ vel_actual[i] + taskspace_vel_actual[i] = J_y @ vel_actual[i] + taskspace_vel_desired[i] = J_y @ vel_desired[i] + taskspace_vel_error[i] = taskspace_vel_desired[i] - taskspace_vel_actual[i] + taskspace_vel_actual_proj[i] = P_y @ taskspace_vel_actual[i] + taskspace_vel_desired_proj[i] = P_y @ taskspace_vel_desired[i] + taskspace_vel_error_proj[i] = P_y @ taskspace_vel_error[i] plant.SetPositions(context, x[:nq]) M = plant.CalcMassMatrixViaInverseDynamics(context) @@ -202,19 +214,20 @@ def main(): alpha = blend_sigmoid(transition_time - t[i], tau, window_length) alphas[i] = alpha - vel_time_varying_proj[i] = TV_J_space.T @ TV_J_space @ vel[i] - # vel_correction[i] = transform @ (J_r @ (vel[i] - vel_actual[i])) - vel_correction[i] = transform @ (J_y @ vel[i] - J_y @ vel_actual[i]) + vel_time_varying_proj[i] = TV_J_space.T @ TV_J_space @ vel_desired[i] + # vel_correction[i] = transform @ (J_r @ (vel_desired[i] - vel_actual[i])) + vel_correction[i] = transform @ (J_y @ vel_desired[i] - J_y @ vel_actual[i]) vel_corrected[i] = vel_actual[i] + vel_correction[i] + taskspace_vel_error_osc[i] = J_y @ (vel_desired[i] - vel_corrected[i]) vel_corrected_blend[i] = vel_actual[i] + alpha * vel_correction[i] # t_plot = robot_output['t_x'][start_idx:end_idx] gen_vel_plot = plot_styler.PlotStyler() - gen_vel_plot.plot(t, vel[:, selected_joint_idxs], + gen_vel_plot.plot(t, vel_desired[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)') gen_vel_plot.plot(t, vel_actual[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)') - gen_vel_plot.plot(t, vel[:, selected_joint_idxs] - vel_actual[:, selected_joint_idxs], + gen_vel_plot.plot(t, vel_desired[:, selected_joint_idxs] - vel_actual[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)', grid=False) gen_vel_plot.add_legend(['Desired Velocity', 'Measured Velocity', 'Velocity Error']) ylim = gen_vel_plot.fig.gca().get_ylim() @@ -222,7 +235,7 @@ def main(): # ps.save_fig('generalized_velocities_around_impact.png') proj_vel_plot = plot_styler.PlotStyler() - proj_vel_plot.plot(t, vel_proj, + proj_vel_plot.plot(t, vel_proj_desired, title='Constant Impact-Invariant Projection', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) proj_vel_plot.plot(t, vel_proj_actual, @@ -253,11 +266,11 @@ def main(): gen_vel_error = plot_styler.PlotStyler() ax = gen_vel_error.fig.axes[0] - gen_vel_error.plot(t, vel[:, selected_joint_idxs], + gen_vel_error.plot(t, vel_desired[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.blue) gen_vel_error.plot(t, vel_actual[:, selected_joint_idxs], xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.red) - gen_vel_error.plot(t, vel[:, selected_joint_idxs] - vel_actual[:, selected_joint_idxs], + gen_vel_error.plot(t, vel_desired[:, selected_joint_idxs] - vel_actual[:, selected_joint_idxs], xlabel='Time', ylabel='Velocity', grid=False, color=gen_vel_error.grey) gen_vel_error.add_legend(['Desired Velocity', 'Measured Velocity', 'Velocity Error']) ax.set_yticklabels([]) @@ -269,7 +282,7 @@ def main(): projected_vel_error = plot_styler.PlotStyler() ax = projected_vel_error.fig.axes[0] - projected_vel_error.plot(t, vel_proj[:, selected_joint_idxs] - vel_proj_actual[:, selected_joint_idxs], + projected_vel_error.plot(t, vel_proj_desired[:, selected_joint_idxs] - vel_proj_actual[:, selected_joint_idxs], title='Impact-Invariant Projection Error', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=projected_vel_error.grey, @@ -278,11 +291,25 @@ def main(): corrected_vel_error = plot_styler.PlotStyler() ax = corrected_vel_error.fig.axes[0] - corrected_vel_error.plot(t, vel[:, selected_joint_idxs] - vel_corrected[:, selected_joint_idxs], + corrected_vel_error.plot(t, vel_desired[:, selected_joint_idxs] - vel_corrected[:, selected_joint_idxs], title='Impact-Invariant Correction Error', xlabel='time (s)', ylabel='velocity (m/s)', ylim=ylim) ax.fill_between(t_proj, ylim[0], ylim[1], color=corrected_vel_error.grey, alpha=0.2) + + taskspace_error_plot = plot_styler.PlotStyler() + ax = taskspace_error_plot.fig.axes[0] + taskspace_error_plot.plot(t, taskspace_vel_error, + title='Task Space', + xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.blue) + taskspace_error_plot.plot(t, taskspace_vel_error_proj, + title='Task Space', + xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.red) + taskspace_error_plot.plot(t, taskspace_vel_error_osc, + title='Task Space', + xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.grey) + # ax.fill_between(t_proj, ylim[0], ylim[1], color=corrected_vel_error.grey, + # alpha=0.2) # corrected_vel_error.save_fig('corrected_vel_error.png') blending_function_plot = plot_styler.PlotStyler() From 2905f1260c94d2a08debceecbbe4c2969c7aabd2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 16 Feb 2023 14:08:24 -0500 Subject: [PATCH 374/758] rot space view frame aand task space impact invariant formulation --- .../plot_five_link_biped.py | 16 ++++++++-------- systems/controllers/osc/options_tracking_data.cc | 6 ++++-- systems/controllers/osc/options_tracking_data.h | 1 + .../controllers/osc/rot_space_tracking_data.cc | 16 ++++++++++------ 4 files changed, 23 insertions(+), 16 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 68a9e3b0d1..5ac493a237 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -191,9 +191,9 @@ def main(): taskspace_vel_actual[i] = J_y @ vel_actual[i] taskspace_vel_desired[i] = J_y @ vel_desired[i] taskspace_vel_error[i] = taskspace_vel_desired[i] - taskspace_vel_actual[i] - taskspace_vel_actual_proj[i] = P_y @ taskspace_vel_actual[i] - taskspace_vel_desired_proj[i] = P_y @ taskspace_vel_desired[i] - taskspace_vel_error_proj[i] = P_y @ taskspace_vel_error[i] + taskspace_vel_actual_proj[i] = proj_y_ii @ taskspace_vel_actual[i] + taskspace_vel_desired_proj[i] = proj_y_ii @ taskspace_vel_desired[i] + taskspace_vel_error_proj[i] = proj_y_ii @ taskspace_vel_error[i] plant.SetPositions(context, x[:nq]) M = plant.CalcMassMatrixViaInverseDynamics(context) @@ -299,15 +299,15 @@ def main(): taskspace_error_plot = plot_styler.PlotStyler() ax = taskspace_error_plot.fig.axes[0] - taskspace_error_plot.plot(t, taskspace_vel_error, + taskspace_error_plot.plot(t, taskspace_vel_actual, title='Task Space', xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.blue) - taskspace_error_plot.plot(t, taskspace_vel_error_proj, + taskspace_error_plot.plot(t, taskspace_vel_actual_proj, title='Task Space', xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.red) - taskspace_error_plot.plot(t, taskspace_vel_error_osc, - title='Task Space', - xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.grey) + # taskspace_error_plot.plot(t, taskspace_vel_error_osc, + # title='Task Space', + # xlabel='time (s)', ylabel='velocity (m/s)', color=gen_vel_error.grey) # ax.fill_between(t_proj, ylim[0], ylim[1], color=corrected_vel_error.grey, # alpha=0.2) # corrected_vel_error.save_fig('corrected_vel_error.png') diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index 3d126639dc..e982888c04 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -38,8 +38,10 @@ void OptionsTrackingData::UpdateActual( if (with_view_frame_) { view_frame_rot_T_ = view_frame_->CalcWorldToFrameRotation(plant_w_spr_, context_w_spr); - y_ = view_frame_rot_T_ * y_; - ydot_ = view_frame_rot_T_ * ydot_; + if (!is_rotational_tracking_data_) { + y_ = view_frame_rot_T_ * y_; + ydot_ = view_frame_rot_T_ * ydot_; + } J_ = view_frame_rot_T_ * J_; JdotV_ = view_frame_rot_T_ * JdotV_; } diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index 3b1484fd1a..eff035991c 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -79,6 +79,7 @@ class OptionsTrackingData : public OscTrackingData { std::shared_ptr> view_frame_; Eigen::Matrix3d view_frame_rot_T_; bool with_view_frame_ = false; + bool is_rotational_tracking_data_ = false; private: // This method is called from the parent class (OscTrackingData) due to C++ diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index 7745731cbe..a271628b46 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -22,7 +22,9 @@ RotTaskSpaceTrackingData::RotTaskSpaceTrackingData( const MatrixXd& W, const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) : OptionsTrackingData(name, kQuaternionDim, kSpaceDim, K_p, K_d, W, - plant_w_spr, plant_wo_spr) {} + plant_w_spr, plant_wo_spr) { + is_rotational_tracking_data_ = true; +} void RotTaskSpaceTrackingData::AddFrameToTrack( @@ -51,7 +53,7 @@ void RotTaskSpaceTrackingData::UpdateY(const VectorXd& x_w_spr, context_w_spr, plant_w_spr_.world_frame(), *body_frames_w_spr_[fsm_state_]); Quaterniond y_quat(transform_mat.rotation() * - frame_poses_[fsm_state_].linear()); + frame_poses_[fsm_state_].linear()); Eigen::Vector4d y_4d; y_4d << y_quat.w(), y_quat.vec(); y_ = y_4d; @@ -69,6 +71,7 @@ void RotTaskSpaceTrackingData::UpdateYError() { double theta = 2 * acos(relative_qaut.w()); Vector3d rot_axis = relative_qaut.vec().normalized(); error_y_ = theta * rot_axis; + if (with_view_frame_) error_y_ = view_frame_rot_T_ * error_y_; } void RotTaskSpaceTrackingData::UpdateYdot( @@ -79,7 +82,7 @@ void RotTaskSpaceTrackingData::UpdateYdot( frame_poses_[fsm_state_].translation(), world_w_spr_, world_w_spr_, &J_spatial); ydot_ = J_spatial.block(0, 0, kSpaceDim, J_spatial.cols()) * - x_w_spr.tail(plant_w_spr_.num_velocities()); + x_w_spr.tail(plant_w_spr_.num_velocities()); } void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { @@ -89,6 +92,7 @@ void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { ydot_des_(3)); Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); error_ydot_ = w_des_ - ydot_ - GetJ() * v_proj; + if (with_view_frame_) error_ydot_ = view_frame_rot_T_ * error_ydot_; ydot_des_ = w_des_; // Overwrite 4d quat_dot with 3d omega. Need this for osc logging @@ -132,8 +136,8 @@ void RotTaskSpaceTrackingData::UpdateYddotDes(double, double) { } void RotTaskSpaceTrackingData::CheckDerivedOscTrackingData() { - if (!body_frames_w_spr_.empty()) { - body_frames_w_spr_ = body_frames_wo_spr_; - } + if (!body_frames_w_spr_.empty()) { + body_frames_w_spr_ = body_frames_wo_spr_; + } } } // namespace dairlib::systems::controllers From 4197ed563aa43432f082293ea28e73a0b473d9a6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 17 Feb 2023 13:37:47 -0500 Subject: [PATCH 375/758] adding files for parameter stud --- .../impact_invariant_control/BUILD.bazel | 21 ++ .../jumping_parameter_study.py | 240 ++++++++++++++++++ bindings/pydairlib/common/plot_styler.py | 2 +- bindings/pydairlib/lcm/process_lcm_log.py | 12 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 16 +- .../osc_jump/osc_jumping_gains_box.yaml | 78 ++++++ .../osc_jump/osc_jumping_gains_down.yaml | 78 ++++++ .../osc_jump/osc_jumping_gains_long.yaml | 78 ++++++ .../gait_parameters/dircon_long_jump.yaml | 4 +- examples/Cassie/saved_trajectories/long_jump | Bin 52425 -> 52425 bytes .../osc/operational_space_control.cc | 2 +- 11 files changed, 513 insertions(+), 18 deletions(-) create mode 100644 bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py create mode 100644 examples/Cassie/osc_jump/osc_jumping_gains_box.yaml create mode 100644 examples/Cassie/osc_jump/osc_jumping_gains_down.yaml create mode 100644 examples/Cassie/osc_jump/osc_jumping_gains_long.yaml diff --git a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel index 38e5c00161..58a2a15599 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel +++ b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel @@ -29,3 +29,24 @@ py_binary( "//lcmtypes:lcmtypes_robot_py", ], ) + + +py_binary( + name = "jumping_parameter_study", + srcs = ["jumping_parameter_study.py"], + data = [ + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", + "//bindings/pydairlib/lcm:process_lcm_log", + "//bindings/pydairlib/analysis:mbp_plotting_utils", + "//bindings/pydairlib/analysis:cassie_plotting_utils", + "//bindings/pydairlib/analysis:osc_debug_py", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py new file mode 100644 index 0000000000..dfed03c0c8 --- /dev/null +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -0,0 +1,240 @@ +import subprocess +import time +import lcm +import matplotlib.pyplot as plt +from matplotlib.patches import Patch +import matplotlib.colors +import fileinput +import dairlib +from bindings.pydairlib.common import plot_styler, plotting_utils +from bindings.pydairlib.cassie.cassie_utils import * +from bindings.pydairlib.lcm.process_lcm_log import get_log_data +import pydairlib.analysis.mbp_plotting_utils as mbp_plots +from bindings.pydairlib.lcm import lcm_trajectory +from bindings.pydairlib.multibody import MakeNameToPositionsMap, \ + MakeNameToVelocitiesMap, MakeNameToActuatorsMap, \ + CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap +import pydairlib.analysis.cassie_plotting_utils as cassie_plots +import numpy as np +import glob +from matplotlib.ticker import FormatStrFormatter + + + +def main(): + trajectory_path = "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/" + controller_type = "jumping" + parameter = "landing_delay" + simulator = 'DRAKE' + # trajectory_names = ['jump', 'box_jump', 'long_jump', 'down_jump'] + trajectory_names = ['down_jump'] + gains_path = '' + trajectory_name = '' + results_folder = '' + delay_time = 2.0 + traj_time = 5.0 + sim_time = 0 + start_time = 0 + if controller_type == 'jumping': + gains_path = "/home/yangwill/workspace/dairlib/examples/Cassie/osc_jump/" + results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" + sim_time = delay_time + traj_time + + landing_times = np.arange(0.000, 0.055, 0.005) + # nominal_delay = 0.040 # box + # nominal_delay = 0.025 # long + nominal_delay = 0.065 # down + # nominal_delay = 0.000 # jump + landing_times += nominal_delay - 0.5 * 0.05 + # impact_thresholds = np.arange(0.000, 0.100, 0.025) + impact_thresholds = np.arange(0.000, 0.125, 0.025) + + realtime_rate = 0.5 + publish_rate = 2000.0 + + # Add an extra second to the runtime of the simulator process to account for start up and stopping time + sim_run_time = sim_time / realtime_rate + 1.0 + controller_startup_time = 1.0 + parameter_file = open(results_folder + 'command_list.txt', 'w') + controller_cmd = '' + simulator_cmd = '' + lcm_logger_cmd = '' + save_gains_cmd = '' + + # for i in range(0, disturbances.shape[0]): + for traj in trajectory_names: + for impact_threshold in impact_thresholds: + for landing_time in landing_times: + log_suffix = '' + if parameter == 'landing_delay': + log_suffix = 't_%.3f' % (landing_time) + '_duration_%.3f' % ( + impact_threshold) + log_path = results_folder + traj + '/lcmlog-' + log_suffix + print(log_path) + gain_filename = '' + if traj == 'jump' or traj == 'long_jump': + if traj == 'jump': + gain_filename = 'osc_jumping_gains.yaml' + elif traj == 'long_jump': + gain_filename = 'osc_jumping_gains_long.yaml' + controller_cmd = [ + 'bazel-bin/examples/Cassie/run_osc_jumping_controller', + '--delay_time=%.1f' % delay_time, + '--channel_u=OSC_JUMPING', + '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', + '--traj_name=%s' % traj, + ] + simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim', + '--init_height=%.1f' % 0.9, + '--toe_spread=0.12', + '--target_realtime_rate=%.2f' % realtime_rate, + '--dt=%.5f' % 1e-3, + '--publish_rate=%d' % publish_rate, + '--end_time=%.3f' % sim_time, + '--channel_u=OSC_JUMPING', + ] + elif traj == 'box_jump': + controller_cmd = [ + 'bazel-bin/examples/Cassie/run_osc_jumping_controller', + '--delay_time=%.1f' % delay_time, + '--channel_u=OSC_JUMPING', + '--traj_name=%s' % traj, + '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', + ] + simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim_w_platform', + '--init_height=%.1f' % 0.9, + '--target_realtime_rate=%.2f' % realtime_rate, + '--dt=%.5f' % 1e-3, + '--publish_rate=%d' % publish_rate, + '--end_time=%.3f' % sim_time, + '--channel_u=OSC_JUMPING', + '--traj_name=box_jump', + '--platform_height=0.5', + '--platform_x=0.25', + '--visualize=1', + ] + gain_filename = 'osc_jumping_gains_box.yaml' + elif traj == 'down_jump': + controller_cmd = [ + 'bazel-bin/examples/Cassie/run_osc_jumping_controller', + '--delay_time=%.1f' % delay_time, + '--channel_u=OSC_JUMPING', + '--traj_name=%s' % traj, + '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', + ] + simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim_w_platform', + '--init_height=%.1f' % 0.9, + '--target_realtime_rate=%.2f' % realtime_rate, + '--dt=%.5f' % 1e-3, + '--publish_rate=%d' % publish_rate, + '--end_time=%.3f' % sim_time, + '--channel_u=OSC_JUMPING', + '--traj_name=down_jump', + '--platform_height=0.5', + '--platform_x=-0.99', + '--visualize=1', + ] + gain_filename = 'osc_jumping_gains_down.yaml' + + f = open(gains_path + gain_filename, 'r') + filedata = f.read() + f.close() + newdata = filedata.replace('impact_threshold: %.3f' % 0.025, + 'impact_threshold: %.3f' % impact_threshold) + newdata = newdata.replace('landing_delay: %.3f' % nominal_delay, + 'landing_delay: %.3f' % landing_time) + f = open(gains_path + 'osc_jumping_gains_param.yaml', 'w') + f.write(newdata) + f.close() + + lcm_logger_cmd = ['lcm-logger', + '-f', + '%s' % log_path, + ] + + parameter_file.write(log_path + '\n') + parameter_file.write(' '.join(controller_cmd) + '\n') + parameter_file.write(' '.join(simulator_cmd) + '\n') + parameter_file.write('**********\n') + controller_process = subprocess.Popen(controller_cmd) + logger_process = subprocess.Popen(lcm_logger_cmd) + time.sleep(controller_startup_time) + simulator_process = subprocess.Popen(simulator_cmd) + time.sleep(sim_run_time) + simulator_process.kill() + controller_process.kill() + logger_process.kill() + + parameter_file.close() + + +def construct_success_plot(): + results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" + all_logs = sorted(glob.glob(results_folder + 'down_jump/' + 'lcmlog-*')) + + landing_times = np.arange(0.000, 0.055, 0.005) + # nominal_delay = 0.040 # box + # nominal_delay = 0.025 # long + nominal_delay = 0.065 # down + # nominal_delay = 0.000 # jump + landing_times += nominal_delay - 0.5 * 0.05 + impact_thresholds = np.arange(0.000, 0.125, 0.025) + success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) + # xx, yy = np.meshgrid(landing_times, impact_thresholds) + for log_filename in all_logs: + landing_time = log_filename.split('_')[-3] + impact_threshold = log_filename.split('_')[-1] + default_channels = {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, + 'OSC_JUMPING': dairlib.lcmt_robot_input, + 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output} + callback = mbp_plots.load_default_channels + start_time = 4 + duration = -1 + plant, context = cassie_plots.make_plant_and_context( + floating_base=True, springs=True) + log = lcm.EventLog(log_filename, "r") + robot_output, robot_input, osc_debug = \ + get_log_data(log, default_channels, start_time, duration, callback, + plant, + 'CASSIE_STATE_SIMULATION', 'OSC_JUMPING', + 'OSC_DEBUG_JUMPING') + land_idx = int(np.round((float(landing_time) - (nominal_delay - 0.025)) / 0.005)) + print(landing_time) + print(land_idx) + impact_idx = int(np.round(float(impact_threshold)/0.02500)) + success[land_idx, impact_idx] = not np.any(robot_output['q'][:, 6] < 0.4) + np.save('down_jump_success', success) + plt.imshow(success) + plt.show() + +def plot_success(): + landing_times = np.linspace(0.000, 0.050, 11) + landing_times -= 0.025 + impact_thresholds = np.linspace(0.000, 0.100, 5) + + success = np.load('long_jump_success.npy') + # plt.imshow(success, cmap='tab20') + ps = plot_styler.PlotStyler() + plot_styler.PlotStyler.set_default_styling() + cmap = matplotlib.colors.ListedColormap([ps.grey, ps.blue]) + plt.figure() + plt.imshow(success, cmap=cmap) + plt.xlabel('Projection Window Duration (s)') + plt.ylabel('Deviation from Nominal Transition Time (s)') + ax = plt.gca() + np.set_printoptions(precision=3) + ax.set_xticks(np.arange(0, 5, 1)) + ax.set_yticks(np.arange(0, 11, 1)) + ax.set_xticklabels(np.around(impact_thresholds, 3).tolist()) + ax.set_yticklabels(np.around(landing_times, 3).tolist()) + ax.grid(which="minor", color='k', linestyle='-', linewidth=2) + + legend_elements = [Patch(facecolor=ps.grey, alpha=0.7, label='Fail'), Patch(facecolor=ps.blue, alpha=0.3, label='Success')] + legend = ax.legend(handles=legend_elements, loc=1) + plt.savefig('long_jump_success.png', dpi=240) + plt.show() + +if __name__ == "__main__": + # main() + # construct_success_plot() + plot_success() diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 6dc1c9503b..31b4abb6bc 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -14,7 +14,7 @@ def set_default_styling(): # matplotlib.rcParams['figure.figsize'] = 20, 6 matplotlib.rcParams['figure.figsize'] = 8, 6 matplotlib.rcParams['figure.autolayout'] = True - font = {'size': 20} + font = {'size': 12} matplotlib.rc('font', **font) matplotlib.rcParams['lines.linewidth'] = 2 plt.set_cmap('tab20') diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index 1923462e2b..8c7ea8e764 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -16,14 +16,14 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca """ data_to_process = {} - print('Processing LCM log (this may take a while)...') + # print('Processing LCM log (this may take a while)...') lcm_log.seek(0) while lcm_log.read_next_event().channel not in lcm_channels: pass first_timestamp = lcm_log.read_next_event().timestamp start_timestamp = int(first_timestamp + start_time * 1e6) - print('Start time: ' + str(start_time)) - print('Duration: ' + str(duration)) + # print('Start time: ' + str(start_time)) + # print('Duration: ' + str(duration)) lcm_log.seek_to_timestamp(start_timestamp) t = lcm_log.read_next_event().timestamp lcm_log.seek_to_timestamp(start_timestamp) @@ -36,9 +36,9 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca else: data_to_process[event.channel] = \ [lcm_channels[event.channel].decode(event.data)] - if event.eventnum % 50000 == 0: - print(f'processed {(event.timestamp - t) * 1e-6:.1f}' - f' seconds of log data') + # if event.eventnum % 50000 == 0: + # print(f'processed {(event.timestamp - t) * 1e-6:.1f}' + # f' seconds of log data') if 0 < duration <= (event.timestamp - t) * 1e-6: break event = lcm_log.read_next_event() diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index fe2b064bd3..948009b922 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -18,7 +18,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: 0.04 +crouch_x_offset: 0.00 land_x_offset: 0.00 relative_feet: true @@ -32,19 +32,19 @@ w_hip_yaw: 2.5 hip_yaw_kp: 100 hip_yaw_kd: 5 -min_pelvis_acc: -7 -max_pelvis_acc: 10000 -impact_threshold: 0.050 +min_pelvis_acc: -25 +max_pelvis_acc: 100 +impact_threshold: 0.000 impact_tau: 0.005 -landing_delay: 0.0 -#landing_delay: 0. +landing_delay: 0.000 +#landing_delay: -0.0 CoMW: [20, 0, 0, 0, 2, 0, 0, 0, 20] CoMKp: - [50, 0, 0, + [40, 0, 0, 0, 50, 0, 0, 0, 40] CoMKd: @@ -70,7 +70,7 @@ FlightFootW: FlightFootKp: [125, 0, 0, 0, 50, 0, - 0, 0, 200] + 0, 0, 150] FlightFootKd: [2.5, 0, 0, 0, 2.5, 0, diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_box.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_box.yaml new file mode 100644 index 0000000000..bb9c5a8ed2 --- /dev/null +++ b/examples/Cassie/osc_jump/osc_jumping_gains_box.yaml @@ -0,0 +1,78 @@ +controller_frequency: 1000 +w_input: 0.000001 +w_lambda: 0.1 +w_accel: 0.0001 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, + 0.5, 0.9, 0.5, 0.1, 0.1] +# left toe, left heel, right toe, right heel: x y z +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] +w_input_reg: 0.01 +w_soft_constraint: 1000 +crouch_x_offset: 0.04 +land_x_offset: 0.03 +relative_feet: true + +mu: 0.6 + +w_swing_toe: 0.01 +swing_toe_kp: 1500 +swing_toe_kd: 10 + +w_hip_yaw: 2.5 +hip_yaw_kp: 100 +hip_yaw_kd: 5 + +min_pelvis_acc: -25 +max_pelvis_acc: 100 +impact_threshold: 0.050 +impact_tau: 0.005 +landing_delay: 0.040 +#landing_delay: -0.0 + +CoMW: + [20, 0, 0, + 0, 2, 0, + 0, 0, 20] +CoMKp: + [40, 0, 0, + 0, 50, 0, + 0, 0, 40] +CoMKd: + [ 7.5, 0, 0, + 0, 5, 0, + 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] +PelvisRotKp: + [150., 0, 0, + 0, 200., 0, + 0, 0, 0.] +PelvisRotKd: + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +FlightFootW: + [10, 0, 0, + 0, 100, 0, + 0, 0, 10] +FlightFootKp: + [125, 0, 0, + 0, 50, 0, + 0, 0, 150] +FlightFootKd: + [2.5, 0, 0, + 0, 2.5, 0, + 0, 0, 0] + diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml new file mode 100644 index 0000000000..a45e65433a --- /dev/null +++ b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml @@ -0,0 +1,78 @@ +controller_frequency: 1000 +w_input: 0.000001 +w_lambda: 0.1 +w_accel: 0.0001 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, + 0.5, 0.9, 0.5, 0.1, 0.1] +# left toe, left heel, right toe, right heel: x y z +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] +w_input_reg: 0.01 +w_soft_constraint: 1000 +crouch_x_offset: -0.015 +land_x_offset: 0.00 +relative_feet: true + +mu: 0.6 + +w_swing_toe: 0.01 +swing_toe_kp: 2500 +swing_toe_kd: 10 + +w_hip_yaw: 100 +hip_yaw_kp: 100 +hip_yaw_kd: 10 + +min_pelvis_acc: -5 +max_pelvis_acc: 10000 +impact_threshold: 0.025 +impact_tau: 0.005 +landing_delay: 0.065 +#landing_delay: 0. + +CoMW: + [20, 0, 0, + 0, 20, 0, + 0, 0, 20] +CoMKp: + [100, 0, 0, + 0, 100, 0, + 0, 0, 100] +CoMKd: + [ 15, 0, 0, + 0, 5, 0, + 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] +PelvisRotKp: + [400., 0, 0, + 0, 400., 0, + 0, 0, 0.] +PelvisRotKd: + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +FlightFootW: + [10, 0, 0, + 0, 100, 0, + 0, 0, 10] +FlightFootKp: + [250, 0, 0, + 0, 250, 0, + 0, 0, 250] +FlightFootKd: + [10, 0, 0, + 0, 10, 0, + 0, 0, 10] + diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml new file mode 100644 index 0000000000..9c4d07b36a --- /dev/null +++ b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml @@ -0,0 +1,78 @@ +controller_frequency: 1000 +w_input: 0.000001 +w_lambda: 0.1 +w_accel: 0.0001 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, + 0.5, 0.9, 0.5, 0.1, 0.1] +# left toe, left heel, right toe, right heel: x y z +W_lambda_c_reg: [1, 0.001, 0.01, + 5, 0.001, 0.01, + 1, 0.1, 0.01, + 5, 0.1, 0.01] +# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] +w_input_reg: 0.01 +w_soft_constraint: 1000 +crouch_x_offset: -0.045 +land_x_offset: 0.02 +relative_feet: true + +mu: 0.6 + +w_swing_toe: 1 +swing_toe_kp: 2500 +swing_toe_kd: 10 + +w_hip_yaw: 2.5 +hip_yaw_kp: 100 +hip_yaw_kd: 5 + +min_pelvis_acc: -6 +max_pelvis_acc: 10000 +impact_threshold: 0.100 +impact_tau: 0.005 +landing_delay: 0.025 +#landing_delay: 0. + +CoMW: + [20, 0, 0, + 0, 20, 0, + 0, 0, 20] +CoMKp: + [100, 0, 0, + 0, 100, 0, + 0, 0, 100] +CoMKd: + [ 15, 0, 0, + 0, 5, 0, + 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] +PelvisRotKp: + [400., 0, 0, + 0, 400., 0, + 0, 0, 0.] +PelvisRotKd: + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +FlightFootW: + [100, 0, 0, + 0, 100, 0, + 0, 0, 10] +FlightFootKp: + [350, 0, 0, + 0, 250, 0, + 0, 0, 250] +FlightFootKd: + [25, 0, 0, + 0, 10, 0, + 0, 0, 10] + diff --git a/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml b/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml index 81575740ad..756344d1f1 100644 --- a/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml +++ b/examples/Cassie/saved_trajectories/gait_parameters/dircon_long_jump.yaml @@ -24,8 +24,8 @@ use_ipopt: false ipopt_iter: 100 data_directory: examples/Cassie/saved_trajectories/ -load_filename: long_jump_conservative_1 -save_filename: long_jump_conservative +load_filename: long_jump_conservative +save_filename: long_jump use_springs: false convert_to_springs: false same_knotpoints: true diff --git a/examples/Cassie/saved_trajectories/long_jump b/examples/Cassie/saved_trajectories/long_jump index 21fab0038e0a19b33e4fc9a99067da46160be9de..7168ed279e72799605071c38d0a82b0dd23ad41f 100644 GIT binary patch literal 52425 zcmeF)2|QKb|1W-HgbZaaWlW|rlW8p~Lkbn5k~t(ZMFWkb5e+}1lx($v#UQcaujpPrVco|>AZx~jSc7voN*S)0TB0)70woI`_MH+#B=1_Vb; zbQ>)7boUAI3GkQP>Kg3h>bAu*MAFsYLoy`PHPmyFkAGlTs3g6I597{F0l|{gLrv_j zsJ>WLYm=I~wyOJLO%HWfRb3BHH+N4@cQ-drO?UOh+Kb(FTwUEf)Ta)Du?P3$gH9gC z!~+O3{-3;Wq5*DHDD}@Z=m2o7tT>3E6lkLWR?qIlZc`5qn zZo=L#FoJ4D6uM>aUqF4o*{t8ozeo4Nn;QkbxPq3dD!=F1L#U9QtN+T$xoE7|Vj!Vh z470u{nky-$i$x_^wI7wTV+m_`H@i{*3pd=?@cx<$XD0vRcK)S@=MV4P=JzrN%N+gs zK=8f>=qk{vDVfI&6@znY>oc=4$M9PX-8&{&^YS`5>(XLq3AC~n)ue+~g^mD^@=(yf zWzl{G<6od-Mo~y=+B(oup&RaEauYOVpS+MYZ3`I4d$3!v>LkcJJtlPQ({J?nLB--@ z$x5K|L(%}>7cq3@-1D3HH?2_PvDLfIny*92k%jYq+6;hBPPU)jQtD9l()G+9Q!dbN zkt8g5u>}k4XlvuVr4Q#R1kAf?J{w9uFL05&$&UHw?vn43EyqfGH$V7f{0K|E7km-( zAqdZIzhXB!kdNos&rgin$pOk0-h<_S^D&oa0egCd6=*m3wwr5Z2spIz!9+qY5q+aT^m?Q1o4K!_Dy%;79ntSA*%6AZh#To80># z>XL6W&V2j>%LY1fcr0~7gU3`hMDXo|Gh?>R+i3R`OK#gMo1xi{rS)2p%|zBgu1AfJ z!@u-F6(^qCB`U|D6t|K9-?T??_K#9v6Wt3X_h{5% zwf6i_#br==*Kgx^!B#AMvtniNx2I49f33b^FNS$OY_XkJZvllv3Yg88k3hi$)A4Gd z1z7G??bDRxWXw~%a(^4k3@kG~@#iXt~iI`1Ey(}(9C$ug)8c!7m-1Qy>b8KRDN_@CqTmv>eAUIne5wp(xJJposotP|IW z6M*VF()=XLFQTTjm+x#=&cI7zgavqVYq9a85<4jtVQ8vneEI9|7OE|Rji1;}@BBH8 zSwj^*>G(_HIk(fMCHfu45~>+*`_7GFu}HU%>zETk59gV-0rnv*CBnB+Q)CgIrEp~T zhmkgD^sB)oIW`5_wT^6!fTqx;;BFr)^EK!t61-mdk^)?}@W&lTn>A3kFyW)8u{E~5 zpnYPcvm-W}#?2RDeGkH4eO=Kv%;A!^2|{HO8BlQ~$?r+;R%p}4@$jo%A+#{gb?^A_ z0=n4vI*i;=g--B=u#cx6v=d=&9`4u)t%Xc}ZdLV!%Qz!tkL_Cof#%yUrETUAYINO6 z`CfsggdZE`-ZH`h5oVr}MimeWrpguk%7nHF9cs5UnxV_9%a>9vML{p&m<4G9CUBh! z?X02(tXhTOVl1ee@*yZ++XW2hAK)U+ab z6|{M8yz_?TN5=6cNHd>W4_yonn5{gs3OdPYOYYM>0&SZ-o!2ke39XWj&5*4>36~!H zF7|nQ0tAZ>_!q9<48gHpu4!uzqgT4yeDCKjKu@!lTreL>go4V$uWO%;K}D^m+QGd0 zP-8>QR;`)2aPe7(5)S71SUo*2v@J{l&UVO0g*Gd&Ezp+ z2@Jh*-@}_Bh2`JJ&2$`CfsKuo(AS(rU{vX0%v!EgtaWAgK0THNSY1i`oOGK2mO93t z%A{nA#ZBJz%@uUT)ARUG`Hsh+5z#=MqL%`wul19&oEI;8rIn*8c;x^p>23a|;1L4_ zU!HQ5L z?a#5AN;mToVP5)pfAQoC2RZs;`9`S{J`V|OY|wJc?WztK6^NSlt=bN2CGhUC3vtHk z->q!;(loI2`Va0uPsU;~wZ(S#)^}kJ1J{(OyQApW*~~*@d9i4qxK-@f5^=`a5cKv5 zbPf*Kvc-9e=cZ6+zW~M+!^BAvqWgn=yuAOoW7fnS5w6?*RX_PS6W#wRpM0D^pHO%2 zf9)VV@iKk6wH|T{%;tM?-w#Tl_j_CWZSnLtuXW4=Bh+>n&YYE)x-ZQU3$bKm zy>8`zo{1or=L0%Jznp|Jl&_v!VNEWAQ|T zi#h_e$wQ!9lgB`}CJ%ycO&$fW2X!4ec`_#+iSc?krcKRx>(qC?RnC2vL9&J8t~L#d=nZj&30b6K@yBP^sif^-HJw6 z*oBwmrh$toL(1%OJb%<5>{4F(fl*(2yh6qhj5+efYNg0C>fHp+ZZ9@mE~s#>YAdIq zK=mP&vz|4EdJo>eY*;(9*fQ5L^nrk9v2Fd;1JVxh#eDsXA_Wrj3{8q&+B@&{FJ9i( zYIWrxfAOkN<7wO8m=~{E_(3g?&Znd432Ih_cRNw`p?nr`a2AMv z|L)H7#u&72Tb*$8Gc(Gtun-l;A;9u_%BaA~hoGT&{pFPJhG?XetyXxy5Eyq@oOB{k z1&tPcT`8;o6J)4xqb9@WXqlV^m-L~RjQR^b_S?)E^)tk>L)S3sjVnZ263}Qdm%jD* zab#BDY?1XS29+vB`0DI>hJtl9_MS2NhE9f^?pUtF0wkLfjB*>yP@{^jm63KQN^j>9 zY%zTS4w%lV2;A@xG#>ERxxZ`=`pq=Qukg|#Fgm)jTT4p^wLX^XRr##|&a1mTJ`$mU z9E5VcKe+dU#^b4>`$hB7=-Ay_BafG0bhu?ttt@lv&sjvp=$4h`T+cD*q&Cfw|@J1hPF-4TwB2c7$V*yf& zYuL9o`z&Y?P_&DEmW0Oimql2POoL3#zZ6)$>_ETUyAB@n-Uu=)9$&rJ*9?|z7`P=L z#L1{X=@P|%nNct0_`*wyQQsu-Qoa-Y{;6HrYL$l8$!mm}1$%;SmSe;6-c4Z7Jdvi9 zxA7odSGR2Wjq_lQ!^JqUD@my5z_0N`Hv-XhDZ5Lt=G)Pg{)VF1M_V8(v*qBkgH4$I z;Je~thwG4iuhV9Ya!J%Tl)1dWECF2KcXddmQ5sxS?Fc-)NgJ{Zm&WtHOvUWc$bB;i zf$Y1@n?($qQD5_w=pXCkKxhA8sHQ?065X`wfT?9Q$gvZ;J12ZIP;OGFI_Iv6GD2=H znw=^D6dNj-5@oJ{h5?z<3ohO0lIUQxo8>|j`kSrF*i;mB_`Z(d<~)U&BK?_#bz~rm zh30m}J?dy&b+x97n;p2s!Krx2v;YJdsNMc@v=MY{Rz)9bv>EkQ`#4oh81+KjJA4|^ z_#(SkEVH7JY3zZYKlZtSzOU;XHfmi$ZYT3TEYceWj~YZQ=PQLGZ6EvU!BrHN`<<#Y9hr7vyK&*igs2HC5F z8(Cc3LDStp-pGj;K2?Vy^D`+vhf9@=`djNmH7XeOPa11}Zbv_@nZ-M9E&!d?@mHMe z+L36wt$VoLIJoa6^8S^x2a-C+Z`r7!f==G#%1+(d353h%DUbEM06*rRE?!#Mk8;lC z?Vi;hhW5|(IcpNk3c5ABHM&oaVP?T z!2IhfeD*A$TWfKV6)y{;zI@cFb~&S-jb&d!1R6hW$9$Q?5lzpEo>n6_44HqkTeE$t zMmufeBU)*5uF02H&~|@C8f#n`c(u&@7VkU>a9B4i6RC;)4|8hqCu;OEcA0(gR>uazU_`onr|KC)I9KLj_h?XUgNTr(>@uEKQf6mTGt4f^!W~bd0`DY zf+BCPsviJcnvpqq*2duN-5;zARs;jC=UK5mg zEsZV=j|=iPN}@Bd!I@9kw~*J3#%Bzm*bUW?dG*52%N>HzhU0=ffh=kt55GFSE`B58aG%`kx-g;+h+OdoN;xJZ`V} zeq7yvc^nSzOb_ybJpDV*B?qVhOTMD#Rrl-B!vknr^rCz$u6D5NV1gv%S(oXupUWEa z*to%TAsxum+5A@LpfzJ0R~GGG{2fRiPBt#a(%|TvV{wPBJ~HZXyIHR#_zOHepIqd% zViw}8=}YS`N(3#Tt^zLM0A&gd-qHS5R#vT(|k76B?PBd-^bQ8W_vz zUn|{NhX&f0s`szV2N^Y*mAs8cVD<5`^&Gq(81?r$t0RQa$Sn5_`YB()*ySrc!{^%> z^*+D8^hls6r?Z38S}x)R%dBHHYL5WV7e@^AQn!QtW!iJD=^a5!cDLP0mV{s^IE=|O zXcNf1l9jaZ1}CV!5zC*KCxcagS6@-eTm%KWWcKvSzQ6(w6{NvUDpD=09y;7+b&ITq+oTfc_n6}O~YtUjZ*H6h*~_Ctz$kj?@4f3X!^Eb zi#&8$_)VSVtzaw=P%~r9s19Y{k{cErvI6l}PJETwAC2cSWo5i{`3SNh0`ZUV^ z;-}K6w`ngbQIs#$1m#fLMd;JI`5Un8!M^JGt#hI5f%wD8p>0_C`oWaI&Y!4l zr0mZ8HS7QdbjAhQN;2w|o3{ksVAOBEI_w_JsGr8<-erW9FPs1HV7!kzoqzWCR7#@x zISxxBHZ4KV7IF`7<}@sMFZ4F(`US=hT7Pu8#%ly3A-^mSCWo1zEoYr|xKt2G3aoQZ zy&(@y+{;eesn!HO1Y9@P{JtDBqc9~k@0pM_)@SpF^Sx+vyK(%Fv^^+kno-P*5eIbQ zS$<~P=2hTBptQ2voKi-;+l6+$07kuix98WFXmrP_<4d1kMG-I6etu;B2>Hc+T)e{L zj(qOsU$)s~1Nu&u$CdgkApIHY(O#00==IL=CB?ntpzoH1$*OW4(9N^!vp$fC| znr{xzu*`Y4^tn>}P$vHRq8kw!Q2V3q7jWtp>N|LH`Lt7Is9Vf!Q0bf;RAF*p9$Y7c zWzx!XYg{fsnd9Qu1b8+;?HWJDxrJ>+%`Q znyn7$dci0JH@(Y66yb}wK)plX3`3tstNU3Q*P|NEJ=mC2v=`fTR4 zjQZY#dmcmN>R+STuCfyHS5!9*t#<+YGk8y(d(sC6{mxem*ZfAt10!x<9%-S^^?C=6 zDkq_`yIvlPcou?T>+I=D3oxAj)gL-V=VP`@C;55HgCJY1sQmTEDNtc-_R)(PPN1w) zVW*5DHyT-1cJb%uTa5ZEmU1o&FkAkdMze+-$d(Xq7PRgqRAfn6@kT@(bPfpGH<+>@ zt?eCIXByw2992iDzTMS8+xMW7Kd^`;A&j^1FP#H03Iy*653vqyVj$vO0cTW#hV-20WBHNMdH6SgOh2=Hx8OQ zfIG*k$Mp7@f!?5(bzLWBV3s9ozQzWxgKRuib`GTtsDJ)(9a}$76z>{zEoXZsy3^J* z#^i7U^ai|Z@#bv9EXJv~9vo_gY}}I1GzYe$e)*`{VxAd5H}KU`d%ZK5=~I|Z%% z)~YyvaW(?|v%MO2?=MAW4Q~|fciN-IZJDb$n{R+`Z+6J<0lsKRYC)E)yDS#stkCXA zHinWWeZF(2UB;3crx)*iFazt!MR&}1-;2I|n7MwX&POoxc9)|6!!ax*aAWrMEK?|H zitZj;7l$QvHib3*D#d!z7FmHM9iX#egZOW|#Ym&M=+2uY5p*lPbGHPr14^kcA9l^J z1>gBa9X?zPMhcFy?+(342hEp9^>d!=17~AerGXiTE#TT9JRVJc%vAIFe+J)Fi;K#f_*jwef0%8LW4hC zH+@CzEyu?)*Hoaos)I{XxMMKaTc6H?R8}k`#usgP`V?F=D0_>?U^ZUVy)pqR?8j2$ z?M@DCvEZA*D;(f>3Ua;c3wtq`hlTi<-gfMm1{byYd!7GV^M7a1ZqX)w$cHxn7llAE_slo?I3}@((Pwxy8%_jg3fE z)Oa6AP4Q6o7OMg-i)=g%ruBkerDw`fK8Mj*>!KY&zr7(dT$TTH+78ToBW&MTY8FaO zN!rBkoq)V~Yp&bbMlk9VH#j|EL1S%U5(=qH81;S21FKRP^_zSAgSf!va?_h&`$x#@ zpb@gzXC3mW8p1jqhd{@xOg}l>`A9GD?#gS|XQS_9eK1PJ8w4gcd^Zs10>x%Q8oY16 zL!Ly*ds)A)p?)ocr={aApkL*AXr{q$@ItUCYR&OTwEv#py4V>`s4%|&or}pY$dh_p zI4Us(^&1Y(vdS+8{n}A!$8TH%<+sGj0}bDU&hOjHcAtC%cwaY!-`ywzZr{mPT6;nk z2zkBLdv9O>8r3U~4qJ;L<;>Fj*VC#%V{nUgdpIjdZN#GUvfMyO?VXaHE9%I2gT}AT zd>{1AA2MH<%YV`$2s5v(5Dj-QMX9^i?LH-_ghD^t^oif%`lCLnpM!UVQSZvOOnxP! z{%wZQ>eVPDv~+K?;0WrDWZO6`{RZ-5W$SOKFg z@GZ+MaN$hSETQEJn8|K7U-^^wsK_n${vOtHP-I`zyj;`{bZksvUti1)I>+?(^V>-p z{V)~yp=q-ToU%0Oo%MRZ(RlwhW2ynRq<1 zwYw{Mcyk$}UO(d3ofJm>^REfZH!$jF@{LNGGwP4(FJiI*8=^|N7PF6|{%L9}b5JC* zvl(nm4_N{#jAk`|ycZ2zG+Gos3ETvATe@Z^WgDW?o*J?lKklH5@?qh;t41&zPoVGR za&FM^?d*=9XVp+gmC!rYSjPL9Pt@9VqXmeKlTPwvs{|R-A4)q&reiiP>*kF{8$idW zdBL~p9Z|>Yls&Q^7@x#PQdT0)0^Ve0S@PHj)=NqT~ZV1yyoP6 zRnQc$c2ma7e4{$gbuyO=c7f)skE!CDTfmv4sd~W=cL4KM;~6^@%0P#BM^fo08}u9T z!$mXiK&H!GbNa?EU?!0(2XyK((V3cqK}9P=ky%FeBe&TrK*wxHwo22(jC%Lu&lk%> zrYmCiYgx4z^^cykj!7Zs^J?a&c46>dTPJN;wj8(|Yb@K7APXMWDtf0KZvq>x2rIKy zvx52yDXoPDmrx@6>#psBOkl^g!mpJvVW^SMu0Ftz4-9ro_-HWQMT4!SkDf+^g05p1 z2HGt?gVPU;FCJ-bL(z(==R`6%QKQ7n+1843U~oV{HuAGR8tlB8ZmH!Bx=wLBTWx9u zoxdLyTIt?Hv#hwR4x6t8iQk&-*0PKnbxe1$+a)Rnnr_*jAG8Vp!ixipD;e*DmY&QD z#v68k6zh=870uyb&D{Q-7N+i?{o-aXnVv^zRFaED#;pX5-&LC(eK8J=%UnM&cego8 z(I2>vvu-0>iHyr}*|$LZg*Ql7T@sDXOE!F}vKEZr!9E_Hl8ky!SEb#aXkBgQuAp6_ z;Laz`+#@@#qsZ^m?c3^$z-?0rmgmCj!II}ZEDvjn!MF3y%Y!A2QQVi;e9kv9*n506 zlTpJEYH~P~W&}GxKTF+*TBl8@Z#;FDt?y6Js&ucT+Mfl)YYvWm$S?unSDX8erk+Jj zOI6=Wh8zd|Tn|pVEcHSC9J|yY`&`f}ez;TaBM;;2Zmey71b4|#?uHGfZk!;F<003| z9ll5-<>%5F)4qVFH>T$b)_()Dw`4o%d|U)tzplMud^;5+n;cRNDAEG~qlYZ!NQ0-7qkAGV;UH!7?j%0UYxW*Zh234zwzTyGP(&YLhyqGXxM!?&S6?IYKVLu zci`B1M!nb%k6%CjNAn1vY3k=hKzwmfs@SKuWF7$|a}ER?Msf7d*;`ah&K;Qf7!6;z zIgs`E7Z}rHtryCikH+NjCjonLlx)fK`Dzv^X96uM+J$myOpN+VUY0v_z}Vs;Tkq&b zMm^()Hv`qh@}I!fwWddljT*J)d@+$Um}c%&e&MF6;qpxDy7QcC4TTcyx9J$z6l*9| z)bg{WkOwX{JrTR;S+Qxc(XQ`%uitYoIy$#i>ZtkTj18%o*y=}p)75yS%B0^S`)l|_ ztya-^c6EHb(z!ot{=7{GR7miH1S+VY0to<+iFJCynwkivCs?V8OA>S;0TMcxK?NS@ zAOST&PbR*}gff|^B@>_|FhhbUB;Y}U6C{v8Ci>|KbTTnbCVa_6DiypTfff=JAps0J z*gypa=!tkT!A&NP$%HHw;32^nI&eY-Ip}}{6+ECP^vOgynSdq}yHpT}1Z+rfg${&} zpvBa7m<|Sz33qBDn@kYXfg%#rp#m@@SV9LN>~~MTE$Dy&HE~ZS#K}Z69ZaGEKO{&) z0xBfURPciYDo9X)1lvepj0CYr z!0BJdCqf5Zr~nBa%pidWDj-J(&!|8b2}+Rw5()Ouff*`@LI*sk-~cLUizk3bfEc5h{Q|0(*22jtZEO;1(T-qJlC>@D58QobO43~OGprr3iy%W90{b6 zpce^Hkzf)X_#r_WDxg9KMJEHJDj}0?iN|qM{j5Dx?H{UB+j{+}ZNCJ_i1h5<%EvRg z4g0xnYCB{$we78=w)|7up5s(|7s#vXF-|B-rM4%i?Otkoh}s^Zwu~U-Wc|fIzbF5B zyHIkfRfMOu`Z~L(Zv5--Le+nD{HqBS8uxGF5lv@oYfiqoy8d5x(@iX*Wm~K9tPQ;^ zVdXIk?tqd$^7Y}}8wl5GjMfD2m5&@fMYd#rxUA>*TaGR!JpWx*?@wFuUR*p;Uvg>>qa|wFFNbaH(_b*vhO6Ew+APf*gsKNcxZNZ2VAxWTZ^dis z3)883i{JC@XP#d%)nXjq>IaM0-%k357x}5OE>iM_VPQiq8%`g^aa$7-cV+3|xMIQS z%Fh4w`Ejx5SRrX$4|V)zjqkl&0(Uy>9Ny2Ttbf+V!b!2{J9(bMTE%1=kLl^q#r9XK zDlaG2k?@WmWgUh)*S^`nIlT^_PHC_&vo64=lOG@1KO6w9qMM7)?kdBUapAk&Mb1K> znNhL9HSW+-9QylZuB5kX6ou~W5m^JRsxnsAMKD22F|%{osx8oGar+jnGS!O_4|L)< zqxMBN(DRDaQH>SCplG^=WO%j>-grhdaiQfM@V<9rcKB`?C{VsfJO4I2RN1MwFD=6i zs>E=V){hipt4%ZWUI>Mw!`>$jG8ZoZue|#_I(u26wRb9R zwZSW9aE+ez(*=dRiGtrXd%>H6u^GQg4#1Ulj<(!++tKj0@}o;kyr7luGAz2}HD1pZ z?p~!-iJe}D*0Mi4gx9vN>Hbpx6E!FuuGyQr9aI|*DHqI4ht2_Pj@3maP-1;$X>QUC zxXJF0m^c!cMAyHyqg;`t8nxQd!}=8GEhaT8^}>hAQ*%TsyV~H#HvUc_E|W zQ2s%@D{xOwXv}%MbDh`u1nB^5mf$ZR?0gg4b$lgod|f~Ibl3I$wcRh_x>JT*_S)Cr$L1j&q`d&zzVTnquk;8jZQYdk z^k5GR8n@!QGk+dFd~PT)-K8BL>QlbD@p=(7x+=1yrE4?l4G?`)@I@Bnzc;syE29PfJ_gJ`C--TQc{eX;`;-Y^4W2VD7=bpI7RhV@PoPysy_ammWwkLTer)bltzjb118sulshE!L!TX;7bTcdI#{0_C_WwN2gZ-X-vbQ=K zidL)75qaHt5oxk-Zf%|?4E>&bUe>BF16Di6x;Pt~0HC9kWCt>EV5`&PJ$GjTo1NBI zend$jt-M#?KAy>kfvp=2A{&d4&25&gmGfo-!}bfj9OmLBgGo$-i6{0N4ay~_uUPg4 z2k+FK*)__HmX$x)dnDBv%x~%X+9Q+%gLmq5FGUW(eAmnN#1v*E|JB)v<)uINp82*+ zK%fSwO9#EIS*Q%ug51*0`yC;pe~TpBBc!dHRXlB^9?jqD8Cz>6Uh<2H=Z>-WO(ZGx zi|>iPINtPNSKx)sH^5qpy25(zP^WwTF zyy@w)0}cg_$gc8i!}a&WNQpc8h(q}&$ms9#x>5}6{XB+x^df=6*{q7d{*Z`ryFqKO22x$%M}>!J{|MY`xA7F&m8+DG7Z^}yB)jRREaE^ z4#gk&P>h|64{u!NCWkgil@!OT6odKxJshL9QP8>gNPf`~eXw4W&DQGIWwf|`^UgW9 zWPpqy)7i^>MI}EY);pNFuEQI?mdQU7WCfuP%XS1|Q4kuO^27CX0o?EvE7nAgps>^G zHoS+U(bikqYt6b3V*3pn7sSk3kAlvL1vbRp071v@vGB=ng7zC6!%Av`L2zYIFhBT> zLfY3W?bf*p)UA8DeUucDreAka-B&KWCdIE#Y*iSDZpf=2z2^^3CXaHMf>FSApxW{3_IEHcy2W;dk~J{xuH_nIx&f+Bb=n79 z3B!@mFQ)mgzK!-?NZa_RT@<~qdHwdDwkHgI$065w@D+&m(#!Dc`vfWs-nwRKC*jby zEmuvAIFYBL=aX%WUm$ta+pFcwejlZ)*7kmiU5wJbJRcc+0VU&@Uu=KPL8ESkmPUae zZiwy7NRyM%E}**Z&5>#=BcQfV*!^-}3^?u~&}Wwa79FmeZvX689}ov#uh`b^MEAKG z1=K?w8QUK}#9tNyaruIh{!7{5KKC169?5dX_O1P9-EM3ie!C=7?;SSxXI7QlxC#1i zoD(r@Cky?ZxO!vl4#7>O#~N&*F*C3K z8=ri*F0^G!huKoNF5;M!QP*HdwZs~y|NgZy_v1Dp3fV* zyzw?KN*ly3WgnHHdIOJGSHru#-H`?&P$JtM2DOi0l=IZm$dx2ev#BxDD4`kV)@F{(W1uY*jSr{d| z3@wY@-rMdPkCy4oc#o^3fXms#`Wp-HBimgoR5LoWX{KsmCE^q4o>BK z4tP!FeDdE>IUnW!BIomZD(ADga4P3hoAW=)`C#MR9eCEJ`*3P|4_ZuJ_fY-!{)_(m z)ctq=RZsfw)BQfw50WQ-B`WFDK{>x4jT?xUt{@p zp5EW$~2uVmn|^w5L){mJl|az39EfmOyCaf2V4j*FVpf;Pc#7p4SQ| zICwb(^yOe($11^snr1A|yzgAKRu}Z=y7q?u@e>S>J4S{co* zStAAKY&jy6H?t4=AN%cebmu|p_1?jAer`K3{%a{+A18lH^QTuEjyvHIQ0C=>r7Bh~ zdorUBY96_m^xXIWblbRniV-3XWQvuRjtUd!wwWyjzKK24oo zk3uZflaXU#=?29XXWw}c(MR@2Z40*RM!oKZ;^DWqB@m5%;C$Ol&)QBE@HE5|a%&*Nc4A!>GkBaJ6E zlX@IhnLIqd^E?idlbxI6)ra{{jSZSe@L{lB!BM-L@ryjIZ>l=?sH1_!F;!3E_Ccuo z`&weqdwPF8Tn+3GfRVc@3>*6r|UOX2kfEGD|w#>c5-^{O-#Xo z`RSfJJ`Y3fu610$$L2v`e8Eo4w~~I`sjrW_7|gz|_3P|$x?dQW@}FIK^#Ag>GZ&ez z`09ED{`>37f98$1XAukbFJCOaQ(y=$wcK+q_-g^w)vW$n+o}aUTAv0PpE-?9&a89_ zvv>p*jBXEqS5}0U9H&LQMisCvjAmw*)W*8sKG&vvUI9JcbNVjL`w4lr>!-(Q}OyYVmGa)Rb3$D4oNl)|p8>+T;tKNrils;F^oEQEnB`xf47O@yls zDAvnVj==fjNzFCU0Ggi)`>?~u2*GfICnC0SExpvqI&37up-)gg&%om3n9 ze(z0arnM*M_V@}oXWqA_rVL$1{dvLCemxxf{Y`GU?jC&T2=fU4MNKg9)HD3pzCk$W z8Fq33g3!d_<6$rMaV&K{`b1FA zPw1lZ*1hCOB(@2T6a1-V1?Op78f{#1kx@VYr<1J)-jfjIvcu~+-g7DF-f<~TsJvdQ zASQb@=2uT=VXBLUYZpzc&N`Nh4Sr`86rGEM{KxbA%@nktg>YhO!FD%j?1$dp-}W1F zZ(Eg=9-jj3_XbIBJ~E2UU&&RtCbVL{a*Ov@E{Z~nS;C#~hx_sN4Zp?CT(`s#_r`QW zmQ2U$ZXOAKOXIQX3EwrlPbER?m7mQwTvvv2XKpvn-FOP-1-n&aGgwZv%b!F zKMd}|XYNC_RcwBv1E-+XmXPbeB;BEad`ra^(+5~xXtvQ|y9Q`6V*xMDJ%B?Tz_M5Q zGC26h+H+g-<*{YJ9t$fwVRUWHaONStm(U{S+EEqD>(KOL)uznXLZB(QK>mH_J7_+{ z#~YH?h?lu6GPDbvftq@+E3`D(K?`?g@MYIYXsqEMoArzZH(2g9}q(=(8W?mpt#FcuS@a;ty<5%EwNQbDSDD^w~%K0iK88uz$Mdu-Frj zZsQhz($xj{r&`9Fbld{oL7XmC{Y7{!bLxHHt|BCNm`!E1X#jFv=&awGXA9Rdr`J^9 z7X(0k?bLtq>AbUoh| zbLhb?`yrBV1#s=)PBzd~Kz3DS5p6sT(2cLa=7nQE(7rMK0FSW@uoErtd*8ekyYUqr z&i&+t)LHjrJ=~s+Y+s)Ge&cR9vXHv;r1MEGvYH!T(0pq#UhTMmA7Xo8Jqoqm51zUFARlqh zvHiv5QVn=GbkAp;j>OvThlKRqeF0aYH@E+_PBg2u{^O-B!Ej~#&FagJjzC7|ceK(O zMWbiBgT{ePYcQk#f>PZtBt0vpf27pfsOh7|^;fxpMgy!YaPznlVs{Wa8UIWY8vk10 zUV66PXz-oK@{a455&PMSzGXvOu<K2>!CfO~HQA7`W{TpYAM=!|c8$yX+i#BrU#Qsr*|u5_r~}x^ICLn5}lz zL-$%P_ROF2Jx4hQh<4>~4tlW=NL*K)=CJ5BWb|Jc`mqMdolo0mnWm0JPv7uY*x`Wv zn-A;t1#2PMkL6YJ*XJ9J#l9N*u3`=u{R-?Go~D~c>z&Q_aq9+~dvuYcnqhGeJ9=r;-PN6@r9N-HSHs3-Awxf{pkJOV_$~83 zYGw6ou|Kd5?8{ld!v4i;bfm!R@}A@(bZH=ev(ei!%(?oi_s6RSkkd-9xZb`UJ$R~l ze!AB~bcvbyw6^yt5FsDiTzWSLWl73}`@3Xe&Mi%B+0{0X(>pk3@WTmIb|A%Q<*_={ zHtbZl<;X5n=CTb1C@-AYnlOu{F#0!6t13mH%%$Ue^_+c-ZKs$qd;0$ezY96>`;ZgA zMELiwzvtlZ`{3`F!QY|a?@0J}B>X!P{v8Sbj)Z?l!oMTo-;wa|NceXo{5ul<9SQ%A zgnviEza!z_k?`+G_;)1yI}-jK3IC3Se@DW!Y7{y)2{2~oFbRf?!dlnO+vHWs3>iT)`Tc6 zhiEWFJDC`yCjQXM7g4N;(nKjlMA;#V3{g_1_GT#KLMM4utL3cWw2 ziV-!7s8B>bBB~Fq))1A2Qb&kJMzk%WNf9lH)_{n1Lo^qnl@P^@C|yLMBFYj`gou(u z6c|cNC;Az!d!P*QId!PM3ft%xDefq=w(FbBKj23m53fhbR43; z5EYK7XGHZPY89s%1pwBI*=Tm53TdR2-t^ z5e<%LXGHTNS{2clh&Dtt9ir?JMUE(GL;<6fE2212N)b_bNXnAvb3|98^)O1uqV*?A zHzIluNoUe(9Z}gRb&OWEh#EzyNJRZ1sZOHZ5zUR($|#MC)}|;;iD*G|8kAD2qx3DJOVR0JN>wCkAW`v%`bJbUqIMCLilmN- z#z?e5qUjMWj%a8^`y!eZNh=e@kyZ*Rg^wt6L{TG37+nqMGULyMb|yOb{#h}H)Ns*D z=XA12&O~GKAtqP*nOq}hqHFSr>4keHdiei&9=eMApY?YpN@o7~OmqV&D5#b z_Qz@2_Qz@2HuKf{^)${-1&j4t*ZOh4zmIu(SgqUQ<-q|3#cwYEJA2x7!gu}?8fEBqf z4nBmWWYH>KQHysgl0o3Oy^gcYl8JxWi9cX(+_9rSq=kTMW<_cSt1xmq5F}vX`5de; z%a!l;-Z# zxy3$h_%L$5=D()(i#A%iw|vQwmp#BnQTbZUYf}`!EM{wyH3V!Ng0^hceXc(+CHDRO z9z69MCx5>OPf5dnzXwxN@c$;?gVBv&2G2N__@a0Ac###qDY$=Df3c8k4!FHHr(W=< zBzk(w#DXIw1UxoP+|RKm7v+_jv8tJPfjHCX>1P;A5BhT5R~v8e!nQX~{{9$~h^@>| znSGlj1LWbZbXaSooZi;L&;MwrXw#RMW^NI4d88pO3>U)(V4=(wMTFe42RH9QQ^phXE*`9K(KeTMCq!D?R#jjXxM) zb2GH5RuA1RUVOu=vI(<|?Pi*uB#Zf~pSbGw`(Odb`JY~zZvpM~9xtP==b@+FpBm-b z0ug$q9DjI~DyqJte_wUR2T+-JFL>jO1a$Lf8vpF@r=W6y{fgHgkAU<1HlhX&s!%jw z^$)f^?U?yql8)2(gz&ptpd}y?45b&?vMAUfZ2B`V%C7=EIp&w4s9}lPB9jgZmT`h! zC%LNT^mOR^Aj59v>1o)(Y5C(~qc3=s#-pke(frWjLStgx@N~$(Ym~_e>EKz+ZA))| zsl^-)EY26Yu0q57>@%xQyFo)k=4Dp5A3@EgytbJ&R&b#%YP{F887en)?^=-R4~BMi zuYB0O8qZ;=iP+uckLQ2&4HUi;gC)gkm-ZM|VngHogXzcpvF7*P3fpcU#tW4llO^wQ zVC646K57m~p`mj%sw<^0!`XudGgj_62SOi`TcZzp|Dw}Vd z%W86hl2L5ywlddarnV2)4RT#DbD#h0=^GhK+4ikWW*@(fMYjgrG0e@tb42$Z2!1_= z8e81%hqu>()(b1!7OoCO#RtSC&k6>D(k`!or^nMlx%S%q6*EmyRmch6>XH=X+Hqma zZ%Zarmh2a@@61Uo>@DVTMqd=NMlS=MW_@7TSLw;yeV0-H*#+M%_1Vy~-M!NtTbsd; zNXG%m;w$J=`ONI4W5M9wO6e=bCEpn5KebMmBNRJ$O!uga7{#kJb(IYT*`URh+de(J zjzPXpZY@%EFY(Nob80)yzTxR-7dW~13qiwys&_^B1T-||yHs2e1-0hiYSCxe0~gL* z{nhQ*L#X^Red7aI1%|=ZSY@NPc+T45n-X|6Y@6^Sto%qlPsZ354ZAM<_PD1Q&RH?z;GX7RaQ?SF%&BpGP?EJz z^0=xi7EymC;s5LtRLPigH=s-rN=7cb>c?>sGy7fd$+{kgnHtJcoF64&fmaQ=!fQgY zNZ7Qu%F$1;1gFQwwuA{zkGj_X`x$`oY2)u_fd3ah1Bkja)@2QFXI%aV_&YNeWOtuh z!gSJ#oOlEBf^=#f_4^a+r?1Hdk0#bl&w2-5POO)n917mFs)dw3D*@GW4T7edTm_$2 zoB7)m-yvKcVeAMmN7y&QvC&K##g`FYkFa+%M@KPngl{9P8sW|e$48hv!q*X2j^^G7 z!$$FFgzqD)9?jhmhK}%Xgl(fZHNyST3?Jd~2wO)uIl{aVevR;e6x&BQJ;L14{2XE7 z2-ik&f`s|Q6u(DUJi^t{j2y+g(flCI0#aNbVe}~8j%Md54vuhzgb^gXA7S@s4v#Q( z6dy-;L&6Rc4v;W?gwG?a9pUB(he()0!Uq!8k8pd0!J~OP!Y5L!A>jrI14wv2!sZdq zj&O@KgGhKn!Uht~k1%@_e@F9-giR!zA;k<5{*Pw)C@zojwZy$;YDr%AsYQAJX-+PQ z`%iOn7Ve*>24mMh_SO8)=H&9c{}fMh@BcI>m+1Ycsr#S%E}m%e&_^}3Q12h@$>aK? zJ$Yb%v?q^@=bur7o<5`(KK`GbKBUl{`9{L?b^0=bmNlyQR-RLAoeB3sa~S!KMfTg(;i~{|il`aW4wpqA@HA zsiN^H3U#7iKZQ6E6pUb91kob66+x#621Q;cef$(AMz!yd$EQ&&3ag?KDGGNY`xAtW z#=$7Gi(py=xgw7X$@`8R|NrC``%HXkGBII-o)L_UAYlaWBB&O@t_VU!?@wWA1TiDH z7(u@X#zi4n1g~N|^>k`nn7kAqjj091se2~B+{rzYV*zPQj!~pBwSYLa&*b<-?wK5& zNMmwrB8|zBiHq8YT0oq%rWOzWzkW?a$Wua*5+an) zorKgR)FmM(X(E--r4%VjQ=f$3Bs3;PRuWQ`P^W|-B{V1@I|-#ph)Y7S5*n3|rGyeC z#3!LQ35iLQt%On~#3`XiDH4>XIw?Yv5U+$@B_t}LN(muKXiq|J5)zhBt%Oh|v?(D+ z2?a_MofIKUXjhtCr6^QFl+tu4MS2o)mQb*SXeD$iAx#N2N(fLw)Dk+DkgkMUB?Ky= zNog{aB5esZOB1jZ%}SH0gfgXwQ9|GnnwF5UgmNXsDxpsaNlM6ELfO*9EJeQ(l9f=Y zgfJzP%xS zX38G7)5j?j{Df8y&)n7qojYdmyyAHRx@sCO?^ag^-9t-XB|8m(UZIOU`LT$gfCTF! zh#rmG5p<4Va1_!;BZ36?Bj_H5;Sr>c;BhqSMxlc=21t-T3eO{`9gWRV2po+RQg|SZ z`Vnl8Ab13)qtG~l8WL=fAb>Q^N6@6n;mebOcQ#m?4D> z68w*#d<4rQh#f%|34TaWLK+Jsh#!UP(dZpP83~q15JL(VBGv3NIw6Ai@4j?gplBXG}=c{NrF8RgpuHg z1T7?(AVK~JLP>B)3T-5qB8?mpe2_u`|Nk+9{BsR5dA0JtHiA%$BH;}QJ4iS{!t@b7 zk7n%%yGS@h!W0rdkYfD^w?`N}!ZZ>-k+6n@8zc-M;rVDbk76AOw@4U7!V?lUkZ^v4 z*`paq!ZQ*!k#L3-Gf4P9!txO|l5mcMStR@+VF?KrNEkoDOcMT)u#ALDB#a^91!?w= zVkv1Zk}!@GuSnQK!VwZCkT8~nmn7^X;TQ>%Nccj+3KI5`aFm3JBzz-b6$y7pGlUeA zN%NJ2m87^w!Y~pZk+6k?)ug#gilHPtBw-tAPLW~`3ByVAn1rpQI7ym$r1(XeMWonH z!f6ublJJv+g(O@fVHE$59YOy1xyt0V)I=$Ksq4;lpmtR3ij0u~s9V;ndFgi_ z`2OG8yYg_Xx_XVLYYFGCp>!J?|Z*FdMJd|=$gTNQ}QxEjJCW-AtIVX0m*x{6qNSZMU#}6Xzye}X+X(boRRFE@smwe*WxyYCUAYYNFP}aE1?hd1Qcp?*J}kz0T9Pp! z^8kC%`s0q^u^q>|SLQaLCRlmis?rC%De9)!qU`}LuD=v{KIiF5f0}4X-IAga#AS2z zaLV8#AlfI~c-vY6@!e+D>Xi~h^qI{@)6NNiR&!GSTy(S27psD<9cm zAiO#bd~vGtqoa-iW71<%W3lr@g7oUCb8G8Yh|*0;Ydaj@o1vMCbaQc2UNl=l`Dtx1 zJDT66?x!_Ng$buz$kxgVV6vlgRd>mxF_~yW)~Q|ww7@Wl!cCjd?3%l=5oEW(yz#`L z{W61K!FXrf6*nINE-g*L(Ye@Tx1a5~E64L3Er_3PvVYou?LvX zoH)oo(t+l*4;(MQdkf8#w&`rz^%?yb9u2!>e*`T^7)Xm*9Y6~)WBEJyIney^bk!bb zS~P2&P%+h!h$e^CwomBfgOvDb(N%&(n=>&w)Tj6Y+^K(-^Ju&uWUQtZIlsFYWF|DP zmZlT|>9@wtY%oX$$zxgGMUS;XYK!!1#$F{7{zzR=gO>k%El@X|EEIC52JQ-y4_Ytw zf{@Mk#h8r9LCnb3Cl7-)!3_gd9U0y%U~swW@M^|pBK~2cqH4r>S@KsS-@QcquUedD z&H`T?B~WvV3>e$7vs9OnddG{Md>3S6r?aP$c5dz?JT`pNK!7$xAyv zBL2ET)M6?`{A=dSK4}v1_bi~vdWsep<)gghThT15wdt<-RxoeE6uu)~h={*(J;y*a z5&u4(TA>jl{_J!o9D0fPQ<4W2`w{VfedGM=3q<_))z7NBgZZp%`kAC*BK}q^H~q`d zTp8^yy@ku@$7h+>gSxlS!nOmi$XQRLh1dgRS*uNm_~*Z{r~FRDKPJztpO1*Y!}r#& zJc^oZ!nYfJsL`HcbB(m8=g=V`DepZVN73%^kk8#gR){7ol&VE=2H16kOTD%A0muD# zp!eydMLPE!KZ61c zqx=S1B!Ra`}P|jG(U}-xtp3x}mZAGWCQsMMECg)WQ6baN4aj(PONdrAG*^rQ)UobbPGqz)gEL?Tg%u%X_7m|N$ zGF7WJ1VfLtZ&5^6p@ruy6YnxzFuieDK%zU5#Pj7!v}8DYN$zCjKKA-pH26&Lo7fLw zG(LStbD}C5eb!tT;BK@Xyi(s=$heUQ5_XuLXy>~O=_dkiUw4&+tlsD7hLq}8em`lu z#j^{3Qs912&a_xBKgdm^rE{mT0ugfFo*#&IKviBJt9s0xffiHgi^j)YOLi%JYs<7O z+Y<76HX&p7yY|i26Cg$6i(7=P49J_k^3tI(0$@>D5!+!S@WS_@z%8c^^dtoNhHlGW zvRUcWQ&dt@4`>|Z2ECUPyn;FNA^A*26k}}yB&+6QGR}An2|Uq>W&O7xwRFhS^_%Wv zZppCGuxMVAJ&U5cVGixVfO0f9U-U`IrWUUXMb?hMlZb!eVK1qAG*rE{j(JTOSZJ~E zp*Fe>=?~qp2&UD8EK^$^-sP=Xx&FDCfxu5n&)}*vd;2*Q%!&B_(cALb9}GP(er}R< z7%e!XAWlfFcu(3%F$HAjE%k9@P8>=M5oO@Fj6;c zTfjrMz}u{MbQI;6$6&cG)+4mO8c6%fXid_?ABeyHwFvjx3xGKMc1vy;JmGS_m(A`v*Ri*G1jP+`nnCHKP z6wf}(#LtYONzK{LsklhYsdf)vD=bwMSssI}wtr?a<>~^eX4oQ=USD6 zWjXK5y;MH~CD%VV8Zq_?N`-&8waxhr7TDF4EAA-^RkC;Yjt!iEnwDCRiU|+6afb`9Q;CRkgtvRcK)AG=+6p5U7;OPap0&1}3{aD{Up8!_`qd@n&@` zkkj2VaF3lK6o@OpZ54T7^utu)Qzw1UR#V1!GH3*?>2zIA@fKgK#n4GIH*Uot8Ih z4=wDTm`+0-o4kWRq`9Ei1%VgdnaqPf@bM|1v>Y%aUVf-ob}yvuP}b|;R)KknO#I7K z=^=+?+(}-}G%$SB&>|}28ftGpP$Elq2~7p1d^YA|2P4Jibf?6Lgy6oOm}16DXn_9- zd3LHX6qIOYvj04UCc+sKpS7OBo4(ofyl1-#6-x^uytDn_j%pj1XyGC(8~1EigiQjJ z5K5CaJ){G-7tP%cll_i8CUib}*pFe+dS84oej$r2R<2M&f znV`rC@3kWfyCKw6d(!`%25R4?5&UuJEaop)*C=1>1HnjI$VmfD2rRx+398LN*+8bA zci&7P^BWO0j_s*fNez$vrbBTDuf~7&4`@AGb}90 z#6R!ej)i5eHa0I9V{!&|b?W3KC`!k4ES#nXi&nW)6A+*KnTjzKLd}c&iR3PGY)~l!O!t zOSqmjKYOtA31;OrbDVnl2n}02>iH582?iuzUrJ@z2U^=b*Ref_11#Bk8h*S-&0hv=)#kOf$;aqv9cCZeX)L@63fo!Y;-1{gH&Bg0XfccMjH$n69zN$%6b9mpq24E@7z1 zOBX-OhlRzwT@&|DW8wW4*<8X(n4tXqYeec>xYde5-Bc_B?ojtTRy2ML!YPXH3n@BK zG*EQ-{A@lHF|nnOjS(fjI{l6Te#ZcI_M{J9{|zy~pUNF8FaC^+Z|%f?{op}+N&hVGBjcnNSS#}Q8EcN4r1k%4zH7^0TR?|3r^7v3 ztVvr-c$bzi#}30!Qq@CH;KZki623X8kz?+LkNZRYw<7!0@}{7L(Q0j8y)LN54PBh? z=s<Ly0gBI%~f?DC^9+a5k%a zrT-?Eu^C4*nq9JI77qY<9fZ1$j~#&~-_IG2&+UY+TjRrB6|$kX8b^EC{w^3`9555i zBntP7us;ms*bg;^#qMP$lq~%^flxC4v*!J4QrhovR_N4ROiAL>wp};(X_$$Wc0%38 zRGkh#Lh12eZGSHPtNuzFKQMuxFv2aI5J$a+4Pap!(MzZ&r^Iph4x%!w=%xp@rf1 z1PMlJsCmtq>b>GCs8E$|A@1o!Iu3ZJ8fkC6>lCKjva#@#cMabBHmz6xy)545EJ3kt zt38(Gv5%Ugn88c^>#(4-qE-z1%6$O&YLrg%yo-m2%~FN}1UjMfI;RQR_tntbd)mS@ z_96^8*kDRc(*X@?uROfBFCS{uj}>p(kO_r*gKg@!8CM)tuSe!lunt?D{9d@uZHjpP|GL~q z+VdYlBmG4JTP()@yq(EGTcMOTU8@#oPbRG5(G3S31HCrVcOQZ-$(L2y3>=`_uYlkB zm@eq4xE|XPPa#k)v+a?mE8>n~p3;uG;}b@6H#9h}{~j}gTtd@MaY7q|RWIa?_<6PN#SqS0RZlwt8` zq?N^0yxv ziKj2|-TpR>@&q0jxpWSJhnF>;bG$=~Ihlc-IY>I$+S=N)3z=!t?|gcX961dPCEr*t ziJ)3~_1F*-3b^6*^q!#`;oGD$9@SrGKu7C@4k0gklA8>vw`NxAKqoGl!OPGTCA1puY4$N})fH z!AsU4p<_iz<#DFDTPiv52^ti9vBncv#qqE0NqdRxI4<+txS#-zj;7ksnOz~-iGy*^ zdXq~1Oz`#bw*eDTelUKuCbGgs7)&`Q)z7s20F&i5pWb%KfQfZ>J!gU|z@&$Rse7B# ziVZm(#}Om7%23409WNPAtOxI6*dA)f%ZrpJXRTVF?m&lI0%gR@Z=*du4I)MXMnIN* zs@u}GZK*Cov@ahD(kOqhu?5t5u07KrfQIjj9xm;)-4!h zpD-9n!>iCV-@>a}8hLnA*m%?C!3|g-$trOJ zA2X)RxXR2};|>Yy*IIb(h=9B*<4zl>vf#FqvDGl(n{@L#xmOZVHKtxb8(9 z+N17o%k`6jl;NC0_n*aM0!7$)o@4!(S1NYr*-8eyZA>Q`3I{LOMd~n%YYW4?QU?~j z9~SR6@)^p!mum$vg;02Y-Nh6sGt7Bvq-Hek36>WO{j%BmEaqDnHZ!ISU#g1`ZRFDn z1!vf%bqw-#Auk%^vYOg@TM*5vSEYRZScr1>Diqsqr3TY)PKvlZnTND* z$Gu-p<&o+lcmp9VwbtT25r5JCV{W-nj9^SQb%>paf3}vO#TLk1dPPg0nt<6^a@XBY z+l|?o2yecepd!^pK>CLlk0bPAiTFF_%vgtFfm=0qTP%_>W&Zl!Jw2I_AWu6e9;XL+ zccY?9ha%y&A%|w~K{--g1f{n+i}lJn6Y-}aSdS_}fy>l7~>eNb?!Xuj|0)nTg81Y;q{?b3^5=?rbQ&y{&6->nV6_zCkl*mpZg| znGb9BOoqzmy3K2SXRtWWdGW*)VQleePluwE6;_$55uV&61CNzjbbf7F0~!x26w1Xy z)WS445^kdh8qST?@@80}H^(h^7E?BZ&(HPBIEVbvH)qbT5nkz_KMlJMo3BRCE~y6= zL^gqOa>EADD_yJ2vhT^6OTqF3J-Y6c4E=B_>ExrqvM?!GcTUkC0}7kVT|$D_=*Aw0q= zLnzMW%o?n#1#%0&zA2*ph`d%CmV}JCV3GGUYE2osSYn*z;GCR2mRJ{mymF3!xndR) zc&0XEhF$U@uPtw4*3KJDu>^0>6DBoErL+kP?Q|~wdRPL@?aLf|lrap~nydDR3T=l# zyw)u4IO zFMMb#XMm1!{daT7h2Y^6)W&!3ZNOf3sy>Gqf{5QtG^Aw^?al2zB!agTO3*qYH|e?6 zFx0PpwBhWG1$0$=n{ab|3pA$)s?j|91s^`yxR7i22lTSfRJ4q@hPFlg(I*BtuwBO` z!x7&?Z0+uuyF6WH5huYHw^|uRm;I7FX zYm+Wqg?cq}N9|h7@g5z)E_tt$@U(({gQd$!=&dIgF_CYCwWJWeqR1s|;-CaX7Rlk9bKsipIaugnpcoQ^MxEp(UoX#5yx5c*ijy(Nl{uSEQ#I0X1 zqyVi$zP%5+VhRm5@Eqr^9)_;W9_)v1%R_VOy1c#8y7=&=rIe|)fkR~_%qa?Ql!Fdgg17o`qh-_*L<@StZn&@?ted!`nK<&|5r z(x(#NPb1MTwOQ*BB>gF5R*JY76EC@}C; z%`Fm{RyvqF3#fqu{uCUvAP%kU02@(~}FU!l_9MNWUBto}cSILp*i zFk<&oV8e+)@MZS=v76z_V8s0M#MjrnVC1D0SxzPw7@1@<>e)>WMn>ETZLuCJn#;@7 zQ$(mb!YfY~38xH{(dHh)VMeEktE*qD%=BzVS0nC|51MRCnPGNpqP* zJp~-QHtc$!>Vqgw>3EF=%9Oujf8%~XS*{!f^L%~vrW;6AI#7D#k6K1axqOrg2D$ms>2B6(oUoTV8A1rGw zlc=YN6?#lfG}j3-HR znM6GWgA0YIav>B96;kofUm$>?%tLy|`P{*fH07Y?1$HnPTs5v>)eHtwUvNaV_Jd{3 zWfJuirIvgRwtt<0;-$i#6y2c*ac&*v3AsWb%cbdrNXJtUH}XxmbB!*zdh2>_*luHz z=JE>lH1x6ze}{e-aOHG%B0HS}t~^S=6(HFM3P&^4b#gy}@<;kZAsZfnhnJe><%9OD zXfBher`6YgPVuNRrh5IpOJ$(h^}e!nrzZHkS|WBd>&7q2q>u63buKU1b6DC96TP5w+V2XS(Mk7kDl{vZU{x+;Y@M57@Fho2rr!iW>f5B|nZH4vo$ejIWS1mjQ`-x`KbCo^&GKqSMCNdsRevU{%vop%B(q>1|+zI{5YAg|d`t9X&F>UTZa8yZ{@dRvmftCs|HKr_ z?-1v=cJh*1+_KQ|zoA@B=iuVz?X@VF{IfRlmkP>aL5tDmsI`OVPgS*_MU|gz{uC=L zw)p!>$>OfR1W><9Pm2-Ap9WeuY)>Qr literal 52425 zcmeF)2{hH;|1W;?JkKdnLMZcC*c)Xi8B!_|k}{L2(xjpkAsR$8nhhxproD?asbol| zP$DX0#tiqwd!J9=&;S0`UF+WefBo0JH*0-9`|S65y^nW0w)e50J+@=?qN)Wy7@Qax z7#JkYg1ltRJT}Y7Xv(N-EYZ+iqNyXJp{Ak9MSGG#*gMoO(93_DOGuELw}*R3K+vw= zhYgl_xO)YA1^CN^xdnN-ZT9sDmT~jnA`=|q7UH4mwwFap1XxseNHgBdD0}p9a+;db6dZ4Z(-$#gU0PHy*>Obpf@$~SSMdHWT`j=#jE1R<;Umj%lQ1;P0FcMF0d z<3PVk`{~KnGVn#$tmNu&1*jf;Zd_t{78NO<1D|slP-EDe+J&mos86f&+1XKmem%To z@x6I9=GcB{xG3Tt=H9MpVdwi0GYb6Lq@$M$MLH$+)>rdFLBRx<9jo-QzyqJx?OwC7 z$efKJk7+#?Z`VnC>8OF{_3oegwlx;dljaqAUHkw`^qxMuYp@*)r6p!;>{*QYGL=QK zO(163@dovDkE8LtrwhQ`G1MP5>vcwa3u^P;$7Lhik7_k*x9_id3}FAqd^Z0#2+RD+ zUAVCZRqb}K`OL3@YKE^@TxgR6b*l?IuIao))psYIeLaNG2f4b#dsePQ?QUe4{!D!WCcHOc z{EY)Ot?kMTV~+ym@f_D~ge!utceyLZb6Y`spzp@>hc1AoxgLgZ4K%^~rB+Jnj@ID) zHHFu_TM-D;nKf~5r8vOtcUG%a6oIPL_7=^$lc36C*v?>2JgQ?n^3`EqG^lKZ=W_ea zKm+&El4ai)gEx61BA>YLLm^qmm%p6+@%+eRLRrzeSe@f|+~mMs)OSzdt?%<1sJ6m< zP58qxsD9&gi}!LyG$Cv0(<#{q8WlDl+sC7c$}cHkzE1|IGwKivzcmMH&-*04M6V4s zRpfG*%(g`D`7U{JZt_R9I&8P#{Af_~CHm^<#4Xex604|{c@A?*w!YXo?ujOLey(j( z{t6W*+&vA3%CHXK#OF0qJ=h`Q_qQhl)?qoiW@OC+xMFX?+Cw!N&|Z1=wiW&fQ2yR< zrb=rS7EBLmZ+H3#nr|y@5_)+Xn}u(+6NBVp!6hmIwQ*V7({e4f_Pr~%cW^`Vnq7}m#J0lK^di>ESsOpZsN15-<8XDQO8(hL7{Urp&9!}vaGhhtD`le# z&_wIXLcshUI@Q~WNFVqHH=Q+$HBo;A9U|T{OIegaJGMwM{$_S)$+vSW<8cNEkMG%6 zlfVLXc#IZGyUvDU6$|8-n2JChOVICpa{`*bJX^T1yc4cY7-G8@w*xwQWUXy{?+D#q zowfh0$OzXYvdCsHaD-AaCQJI4U&OXQel^-QT*c=3&AFTIo4}>VV5&({1YG^0yhoGo z1cXg{dCJZwz;$c#yL)%qLlf5Sv)@H+pwp9Kt0Atda8p8C@cTkH=&*J1C;1KAp&fJh z2J@HR(2}F?ppRKQgwcM>c`FgrVc48su-FSS964h)H-8xvyv=p0LO2M@sP6~}aB_qS zjdRYF8^45V%v$bI7D7;a_Ts#r2OpvAUFYfd#uzDFMaOZDJ+*>>TR%E7|ZaU1G9e4!Lv+PX}`SZNt^#ScH}GTK*6-( z0E3rWP)6Z4=Mk*|sBrxIg}9`6s5(67h5fCEwCfekk5uA;0(}nD3~B6-0c;E}qzm!LY<7J&*lRy7hpTiA^=s=ZqT7 zOJRZfht6o~YAU12caI#F)j46M%1)U~$t76s;-*?Y*~3_dE6>-!`!$}WCcJ_7x;1Sy zL_EC$U4jC9eO-J#wuZR)1<>voeh-o;{dkbqHqSqv5dQtdF1H>3s-J$H--rKIKK(j@ zULo$D|2jeJ_v_3&@vl<^eEdB;{#7kFee7R_{2>AVt`qou=wD@gUVee0zQGf`9h|; zHx|8q^SsYJbGFn}Aw{;&UoN2kB_yNPTZ(P23$zWX>d#5X{ zwRL>R9!LA!oK|jro42^RsQtbe(oz4jGkuxl8O=YR(fYHa{bxt#&yMb&9lbw0`oB9| z)D@^tUjn^1eGT;9^hMBn(^tW_g}RTN9?ajbL>o(Xw%-qae}LYZ_P_c+y2fP~m{!YW z^zA46+m{x{L1*%_PY2;cbY(!(xRceEoCi8K9c5wKBZ9_jtjlt%pFjp3rTenV2u(oA z#}d~X!IiNm^?Uh8{-{5+lPmNTt={tZ)0D5Y`h}8OT+e9r5=^&+9vAjI;&aEG)eTKY z^2OJvjukDsuo1rAre&zl!gIgm>E*!_b2HYKQ~ZYAc~fJs%#Q7CkjA3oai1^78e+rf zYF>0!6<%)CyTs~O%+4y%IZvn-wz{CS)n%Qv9FL8fnR=x)S6%}hU)_|r+(yxaw~{z} zhbm-TiyCe| zQQTN2gicMdXYs!ZM&dh;589~dfRCs3at~E8qdwtUfljHHppXCVD#z~GsL}ezmWF^P zaMISN`K!1Z@Zd2#vm)mZ_;~4kqgb>)>JzPPTDjT;^az-Vk4}K$vhycxKR-v!J*jJ*YSn4uWM<25{mf|4DzC%On;*o$yD>p~)r=-TXL#`4 zVni1%Bl#C|O^kjWo{aT;yB@T^SXz+0T?J*B{=B{R#Vlkm@MDZKO9ga=v#i;2;}d2O zH51&`b{I0YfH3UcgC<=Xj_Go?gA5~&pWV0hfZhC8cSRz$fv#O0zDM?E(dz9~xrF^` z^(&Cd{#;u9b362C4Oq1+|8tk34EQR4b#!aqGq6-`qvo?H7f_*NLzixDj?KRO1^jp%Yr8b*7#h%6XuLWo01PPZ=2*Kf8kHHU zGdxdS56iqNLiRczX4pPgTS>7MGA;e4Ei;b?OL<8#i#lob`s?z=WFeCQTezmcLRx*8ij7MlvW!{(J!F*+6j-7c zYg4=!nKsmSNk}GwR`&F(qfZti<87_&8a~6QQhrfYxAS>$#M?l)DgqHk9L-0PglZR1N0(6fbV6$mERa~uk?`}P}7ZU<>E1{9iXJ{AAkDxH_1{*-O$N)~(qS&~6+8b|rJ?O1}f@+-USJ_UTgc3ad2c(;7(3)PS4Xby`f$yVF?$undK4EFn;;?)pOPk zs3Zt%uus1NUb>mY9gAzE)t_=GcDM%_uFn~5Weld(_gZ>nT7mJ4IOa5X3c8I{T?}{^ z0KvLV-Xqn=Ky{bbO~bq&NW@+Nhz-911z`Q*yvJFHdDq(1Yqk({xM}Y>YZ!$t?yPR| zE&GO&!#cO#)sO-M?{6^-Ml_=d)$5`H_bx&P_f;#*jD*nG?yR(a@1~^ai za6JRhzLz&!yiZ1KJ`YYkJ^T)INd@L-EPRBn9A!OmUmT(h^{kh}0+xXf8VL~`XS2}Q z>KE&_fm$%pC8hZ5p*0$6GvqBg%?hqW^uA_IIslx$$Z+q^wg4YA&5s+@XQDBC>7Usx zhP3+Nl1~2PwEBSfLz)kem)AZ1dgy_b)|Wi4*E>z_=U?v^c!E^KJ{8r|Yn_ zdy5|EcY7GIUU)Ouu2nVc{cbz>xM~g)Q&t34zx{J*a+4M0O8Gjs;b0HuI@_}2%+4$* z#I<8UBxM)amRKNHl%bD4zR|gQ_~Hmw&pbL2?7a(eUE;EOzP=c9U1V&!CdCMacxP<{ zB8{NO=GdI$s|}6%;z5Fyk{^2Mn_`f)-r4Az;*XREK8)aX!HzQ2^Sj7^}u+;my91%B53$o$}NNM z{NTD*u;q;?Efl&>tRv@#FRlLfM+&XpsjTPXFIs(0xi8liH2mCMe{5GZ(AaOqctI57 z`4uTaAA8mzdwIRt&5;*DKXa<><~<=`N#5nA!kR6hp7&%J|1S&FdG%gq)QM_TA;Nk4 zmKqD5&tC0l%PEGL<44OZ(m5e>LIUrOohf*JL;Wwoxf7t%^XtRqofklbldNOpp)p#$ zgS5HAC}uuZ7TweR9x}&l{H}QB3!eYU$nssB73ki(o@4Rbc}4@_d|uLAyHJ(Cv`Egz z?BanB_HiA1`@y?IuTHDB#TO5;IGyX|u>s%IX6=yia6tFZ2D)yW8bR@4d1n<5O8x$G zqeWMS(4_SydtkBzGV~w3v&nfUX7IW45Z^rk?nm_2@R`ej_-2y~fd>4${`rA)V>G!6 zzcgqzq19`#^gPtY489+3a~W+w0fvPJLKo(vZzdi4Z?Jv?=7T2%kLAUJUWK9W1+Py6 z1^swWiH47;T*T9|f7e;`-ERCrILmz0e&WT&+<{a$udZ@oqt!;N*iqBhr1}6VHg}y` z9eDw32n`4SnzI*tH}SPwkuLz+UHe=2eT{?jKCm>X%h_PXFM29+KIKrc$@;lgZ!y*o zjxgJ{djaTvZYz7;zZK1@lFv33U_w8sUu6ykD*7@*TY47wTCuU&p=I{@OVY;XUu$Ljfd~UbCA`>QSru)qnI(gZLsBa zK6rHYxS4j|D{$e{-gR%vE`XXljmu9k&ce)xv0~A@amZ?2RwB0B88hzTyR`fAK@>Qg z8~-dx2eNRbD?AOHM6S0IUtA9<0{t6!4Y`!xBe`$&gFT|TsC`h-ug9eu6zAuxZ>%u{ z4FN3G?|64Yl~&QRl8aJUNy;iYAt4Yd4i{aR?KT@~FCUc8Wr|0IrefWx7voXGLvYIV z$!@69VzT_{nkQIEdePFaV!lvu^a{@<7Jpj($0yz13ZQ3J1#|nCNHlx1fTTvsS@dR} zY3Fe2J;Wa4WT_M=0cw})PRc#3D4uwqx@?@w8FZ%j*yi-_p^a0@&um8_kmBnZjEWY3 zu2SxT<60V+&FG7(i1Y=>G4l=p4V>MY*!<9oHcoqZO(r=|ipQc;ufMMcT_x5x?2oC^ z>f0^lW!-<*i)HQXK?5nZndsGO;N^4R*Vp`PF!t=qws)O@C}>vHZ3 zZJa`GXMQY0_xGXRkhGh$d8Tkuu*+t8TvfLh(Z{vVbe-2$O>W>4x+S<@#T_yk@9ve> z-wK?o`E1X62Z3Q`Rgbp};Yiy+J+OjL3VqZ5dD6@OBdGcyc}QC~i4B zwd~DO$bO-4nns|E;7D+y`jYGo{Rps2a)%_8Ty2L&iy}0|5R)0Tb(Q^aH ze&+Zt#S@*FT}{FC<{LRIa{cFBtL@uB&$)~{Y?by#MIAgW#@72$N%PmafcshT=*=bO zvl%DAM8$vfp*`~-8#$J3pFFby$Op43%09~`ytF?0X95q zUJKdy*;mhVSc=AG*|3gA1cSTp&w1v+T$Cry?jmOi|EL$bcrE=RWaF#v$J?GcwV!M2rR;TF82V9+3ANrbEqQmEDVqIfYEeY5a2J8m)z zzMfuVb)@+n>a$GdRb>8v#)NOK_jb^O@>jAyAKv&0%kLEb`UoPdCoAK$C-NKm`o1(@ z@Y#LPXUxHT$Iu;(F`F*F^h23eAL6^y!~o0hXin>LypQ$fp1!HD?J4M~xM`XjXAh(c z2gf!`HKKy>;f}C~E5$whbNQ1O+JcsXwp+DETakcZYo5$656~Xme{^My8@l#dXK$p` z6o@Quknyh<2fYQMwcXEJ(d7PTlfMq6K}K%X@}FN?F;mm8@UIG+!L@5jb82~|QRKC5 z?j*x-T7A>Ho#jnvGGf(&xOxv-eb9>SyI*6bk7~^gEk?lg$-2m;IR_!XTj`u<>G@#o zi>>99mLz1(WcK5Ncqi&rmy5R!wgo@f^E))f-(sc#)sR~ZBUo%CGM;7D zDAdffQwp1vi#4yYJ{vr+91CVZ&70fJ zjh~uf&2)LbO*JD}kf}{V?Wi>9`PDDM5c9gYZQl36hUGuerP-Rct*If1HMnWv)QcQQGikYA0hpX`ZZ$Uf3r+R3hORYQ0j8R=?IhQ|MNf5|Ja%m_0$B+ccCO5L2l5^# zE=j!;04AjzuS9o$p}n7YA>RG{3z+(l;;W-G7#r!HjO7T#FU!A@d?B)d!xNFjM`XzgTAy|mMH z+Bk9gtkG7b)sH-lek(?+*Ni+TYe%d95MEqk3S5+5m72WE096a*)^3pw1FClpxMQzk z(DqqaB!1&jAb%^guStF!6v*bKRd$Jj2*a2AmG3@432#ckc-cYp?M-1$JG_a?L-yKa z6qkW=*A*fL9)_U*j%a&U6c0K&wDL)-m?xAnbkJg~5NK~G>o0HK+1e709 zKBl~767**Y?Q>jEL>s5P##0IofGaS^Gq!FCIG|_a6tr#@g&7yU+k*oPN^+K3e^N4(IVw&@(BZWla0M z6wlod!Bnv$;IwI-#fQF#;$PuL8>i|&f%aZgo?7#6#J#&SyzxyOXxAS-RjE{qu8Y}@ zS(fo4S35=_#|QnO&+h!UR*uz}K`$~#$H^HoG5gOupwEFB#jkeES-%uq=W`6Gy}1Rr zsjF_XyQ)B|f5*KmmUdsMciyYCY$L7y@LMZRV_JQQ&}#mBV4h6!C3DBy;K`i@Un2*n zfOM{8hkMdbP~)~ET;skRT2R;gY5w41@O6Jq!kzmS;AX|`*yyTZ6l|$~H?zeY4Mh&| zWE__UW2`SeZCqJ^Mn^q;l`mL>kvBVT;s8%{^JOEeoq0P5+M0PbD!UvFMa}Zf=37Rq zU-6lT!3vFzbf#_jahg_ttGeXpJlZ&IlUy8{19&dqnGjs(1y1U%*AofSEFP*j5u3T( z3v@)pK5<#4LYv2pf<=UUKt~JnhBYd;(bYiZ#~V+lA*b_KmGjrqzJCMa9`C%-+gjs=b_;tMuq1_5}^OE z!SRZ%S5aEb`8d4B6GfxT_hh-Q{;ofJmeCRnkB{4XoX$bRg91}YBj0KD>svz@GHKs; zk17ShUcjx_`?MmU0Yp4zluC<-#jVT-okE+&Ku2k{!07f;B&gl{n#tG+bk3DY{1Cec zWw->bEv>3Y%il4s=UZD0zF*i{T>8iWP3YUt%Kdp9GI-7x-YDLUrp`?=Zw$W(GMrwo zQ7`HPX5Ydaj%)JK>Tk6HZy8$sQRR|J9a_Din0l=+nmRw9E5u?GTGKt47&e-YY8Cjl zd@|humS_e_@6r?pccL#$G6u~-!o%xj%mN)iUH7<_&#)&rz3AEHiba7S?(y-rOniq> zuX%QR#8?&h@$mZHB9|ESOopPqjh&fA+5gh+|!hnBIszmWjkZB!TY-s$3AeU6q!YO#A@$-VYqyX=f>t) z>V}s5`PZIbEHYe`#`KhL%K&-Z!a*0d*phoU4AoPY{gi&Qyb!LGId@7>z|exvOU^l$ zhtw71e0OgC5Pq_-_mR_Ak3Hr^BCc-9d+x6`=)86`YMr%zL5Ny<-G-Iay9(NR3l&fy z!4DFspa&JG005vC*69n@WFeR=uu=<`B*KAPe-=!Z!&@kpL12_K?5~J%~aDJVr`G71$s_ z2ztPP3Z#*s7d=2l1(QhNhXiTp0TmMbAb|=JRG@-wBrrw~Vo?DndT@veA3#Dj-LKXC%-?f>QJV5*6&B2WChRg$j6(-~C?OP(%fF=m8iiSV9jXl7Jr-oTCTQNYIM}s7Nr03jB~D z4GE~wgQ7Em(R8YxO0^fL_8irorXNpxbjPWq`4^aOTR5nemuk6aZD!ORTl1OLu6m}m zb_BV6X0=25OJ`cWQ&jtWrZp6%p6{XBF4B^p-}y7sFvF4%JbeiKLIa-HY*vEaM~l{X zKC^|!2SdBRdCfdYt0<%=9;V9~z{tq+1j8L}s26VVT*a9MjXkA;qnt;vjV$BXB#RQZ z&ap{~|5-It&A?C~O^-lKAA)j5%stwR%^=r>#4TY->2S@XYU$i$dhnKZ7-V^^0SHT?szKS#}ZqS$qN;5u*Y14@J#y{s=Ye0u-vr{x-DJYBI~vW zYOA`h|h;P=Rrm^47B^^j2-zp4g0E_o17W!y&h%{$yIauPNFn4=RTGGPtlFTiP;n{r_&^eC9KH zvda|lOsfPHca<$Nv^rV%yt%r;QP90G^F`S3)JEOHlBy>E?j0j|m4E%vu;Msg6*Bg@ zve6B?R(!bfK)(y^=}jtsIl+OPHeBALx-h6p?8}6Vw+0V8zB7QUUNiD&t@4L1 zJ`8ii1YAK>)tr0RWHXS5r$>|z-xciKawp(W=>TRtz@xtRVLe<`u=PFbNHca(y|ZUO zPd;`Ly!vw7t^iwp=6javuM18N#I#v|i2x68nk{cG&VY8R!y_$a#ZdTKT>L04_~^`2 z9Kdt)E4DB{KdMu562+;e%*B^nz$0~w(DXa2pl$H!6&tVFVBv$pnog`wp)=pZPN8Us zw{I}4dgFftZ{IriSn<~ZyuQSNA@pq}I2UHNyLPc8c(E{dU&A3|=sI7$+9&!El&)N# z<}Nh{ZVkGqbV2_qw!J#`meEfhT{n5@6Dhw5l(~(W+7?>D^}?6jcr1OfjBIvsZqPTl z6&$tX)2+gLXFph)p&5_&R4?7SR1IU>JFIF><-+Km>LTk7UyM$(567CmSq>dr@=vb% zmc6lU-heHv@@)m?_<$n)*lIte?a24w?nhjb0g(0^Chn%4OjtoG z&Ts6oBJ_Lg7<+P|JdV^VHIa%uizE35cky#ca;aA=7`a>mFq{K<;tgQ zf#=znRIZiQ99&JQato6_b`;%>APh? zl0954QOABfP#SBfGdT38TfyLmTfNGjD&PdxCF^R|wc-Q@fr~~>t(d`73xC-Wffwxv zWocFKfyy3oL6&Q6p#zunF`2y!p-%ZW`QmSfp^KI7-MZLHxXM?Bspr=jxJYr*zNBI^ zR2u8CL<%e6(oF|CZW=GcIv20=)@|U2E}L}9$82NpKKsq;*$QfS-4H+?>uQrrY;8MxdJAUvr@6$7Dj0g-f=DOM@EfB zX6Y5p&Ul+xl~UHlE;L6nU}vTJ55#n8yNGMF7^EFny@6JM`QC?DWHKlsM*Hx&od;6z zHg-+s{Cj&4L!8LKoBYb+p{}Mwd6Q2e?KuDHRo=yw>9?8!HPaA#Xrat5$@xIo$CHUi z*~I9*N$9n#x)XTww_8(_27z+z+DJtR=ucJutm!-o9qvr|-Bfo&K2sAz8nW}y z%DilT;he)DuwgJ_2WuP%EQy1Y7eC@P9N#xP@7)0o`{A~%?m}=fh{>W-y$r75SXHl* za~R1L`uLryQ$c4}T`I3gKZG4x?rm)-{(z#iTt=U~7X?YNDeHC1WuZfh=)u=jx(G_f zdnd>oK*^;qLiCx3kg0FUobn|YX?iNVuzW3m``L=pBbP4%(Xp#il|EI0y3ltoyZl-4 zezx=6jI8%iQsOHur=Y#)L&=S|%Sz9{5bfbb%lgXE_DQErIoI_;#pS1B@0W7n5bc_& zZktQs$b-+1O7_l2Z(nwoE)S|g=kLB9(7cg@F4*s^myP!^a$M2*&^X|pQR?dKoLci< zz$<1%TkGBc?3qX6OJ_YrHp4;^Or1F(=9l{8(#~EKy*TX1zD-_8Qr~(k=h#d1sA_71 zvid<{$g&k}>IRSA>gJxQy+UjCa?*L4uvXPo4|&gZSgY1qE^{Xr45-@l z`Yh8a81U}8uY5`&^wBfW+QPmL`e<}ss5MK%>)Xc^)gA@o^~E6Z=?QHd@hy3N^rSG3 z=xw-_yyr9aJ-@X}HqZLHO+Tp9(dP%M%Fu%HFy^-0kLeKFWwpV!r-{{ZM-w4o2RjDA>NpFOXN$A zC*GL;DxTjl5Up_tXJl2;L~9&f~8VN6@(sjAg6`7xr%Mf#Z!tFCUXsa0P|737j z|3S_t{9ier;r}A%!%XFT8fNZ-{-6KHW*j9R*0wt_OQL^w^|_C59d_DRkt0FwpUD{o z8Z(dZ@~qantrwCYoP?Yo+;eJUexnciv&WJYp3@d0yFJVAikWZ#J`vq zFAHe3+%s1esx9dqf8Uu8L&aO=V^-D|x4rnVO7AHX(1{NoaPrjymixuyf<`~%Wr16s zmcOdRYT~-ySnu}0kaWtK7aFr+kYin-w` zj%z$_9rig7$Gx#R`)kuttatDF!n9;=C>Vdmx;2RfI$QN+h!||ZvJPCvdY+oJ_b2Z! z8?29l8}4n)&eIFW+OI+p5Fl7@7H)$_>LPykUznH zw%A1Rr0uNi=XlPcO8d%&1n8ct<-z#H@IR~m>EVMb_g7|yN#TQLe(^Vg9%H?-#yjGC zZcsGM>yeUSJ>1mt?6Ruh#6M^J=Oe6Fs-#;9i?QhL6MN6=oQ9j~wN8j;W&UT?KRp~C zda7ILM+puONc2ghec!8>PJB7OL<;iWOpQOG&<-8cU5+>{KKIWV|M>{3KNM;*`!axe z-`6Owdp*JusZ_C9xaLGoC}tKVMDGXnY;4{GqYu;7EL z86uYK+wj48kydA_?D2-tW~bIYf}m^V-7%xnR_JMGSbbT(AGF13=f;+69iTcgVDZ ziYuZnPf3nIAGv)WEUVw)wTWu>=L1C0M4fB*t-Fh$)y?4mlUWkbYC-2s!$@tccwZ(uf;_0-gLJ)eUSf&+Mgm$Fzd^S+zr=%LS$Jhf z%kFb_AJHwlT>l@l20=}C(mqX_1$h64>xH*27UBJNrT$stU3vDVIr`Oi@HoHNW#hv-9NN3LI5bKhhv zL-7GS<`@i`cR6S`=sW%p;x37QY_X2$Ct~z+88Ur`pnCo z?L2;Xoly$Y0@n=SeqJ$dNh2Rp)4v-jx+WH`GdgQ3vXB+|@}-7-n%E4?A0M-NZ~F_n zCXcYXn|7eEfwE6$tq!8aImW%g`Rv#=d00hZ!$GiH%{NwrF@d(;`M8pK&n9FZS-DxW zkpo#ASk;&of$X<_F|bj8<@ni^E=crb z+Pdrq<8bp5uam3GcLKTHl5XvxB4FOJY+J=E^YG>+-g3(r1(5!IgXj_QDWmZ(RqG~o z5|Plm4})J)bC7h7?xt?qclGK!JMZ32Rs-C}&xpkomm$rg62l{Q&*17i;qF@XcM)%C zZ;(jVU7%yZC6FSl3SCno+wZ8oL36M7-ZZ%sg*0@P2BequV%l+`mXUoxx@zOzhLAj< zbs=#dOC>uHdLWz~y7xK|wbLt%+oKEhHD+0+zCB$$c3}MxnXiI~bx2t>ePs^T*O0Kf zY6XpYGu+PERLRkD>Xt9^vmvzRRoaMo#enD`8y5w;4#ZZrbKTilr?EA!Vx8_pCK49m zNV8_7Ftv)lN^PH2+%+$u+En%yq#fVW zr+cw@^g>J9w>4VD_f_1}W%uhE4RtTwwxg2UsPFQ}XTqbS*kj0FuGix%Qr@jN_d~g9 z@%KK6xqehZ+Hs}oD`{X6@0re0x%A?(o^mdQ(3{wQ_}!zjBUgdM2Twbtr>ha;Zg_1~ z^*E#*e`{NtiX_#0O&5yy7LVTFu(V#$4RD2{`ws@M1A!M2W#8{Xw1&xUp$2~uve?|z zILOR~xa5}0zey=C&MfPFQ!V?txMo2X`lP$C_?`M2vGOOEj0WBIcWyiQ5^P(eQFZkQ z0-tUDC8T*$k;Bl_raF5$(0fnSB{@0(XierWx+Z!I^(;s@9{;%!{zySCz(?}!-4nYu7<%Z_A_kgc+$Yp4(W ztUIF-W^If)g&c&eHT@wcmrZ}Z-D%WrYPCIPV+Q&*wkbfnGX_0kQV);WDoktD;^T@J z(vCY%_Qc77M~pka&wHLrYj=H<_WJq%!@q_6{cka+|3T*8|NR|^zh4Z0zZd?_2Y+Y6 zzcbB#r*fA=Rxi*Mx|cLo^slJNf;$^ZSD+Uv$Na zQksZDM3fz($PguE=4=KAqJt6ris(*6FCsb*(PxORLe3|u7*Vr`3Psc-qWTcEhNvub zb%fH$h_*#EDWWA24TxwrL~}tzE1?uKqI403iYQA&5dxHwLlhXgazg26ME4?k6+)s5A8OqqH@mgApx@Xi!8uBAO4;YUmmZrLtRI4BKi}h8xg&Sq%-Mi9Z}gR zb&RN5M2#XU5>bEXsZOHZQJNcFDnN)$l4az_+5N+}}>7g45&qC`@%bUl#hc$EG|bTguN5uJ+YOC()O)Iqwc zN2zf{MI-7LQLTvDL{hm#DVKB78yT! z3YgLniT+1)JEFJIbuvodBDxekJxo+ZN)03`9$kGSsu`tr5tWLhj_DdB(FQ3^k7#j3 zLnGQ3(X2>XnJA8QrI1qih%!eMHKK$O1&gGdiT+4*L!$Q)osQ^hL>D7^7CjwJ)JUQt z67`R$c0_HXR5CLDw3cJD8*M|G?K^%Sq8{)3FyB9eMja9T^K(y+8}$S)edwqI;xjk?TReii z!rVfrZ)NtGOP!X)yLHH+x6WJQilAEFWivw=HD z${e{AhHYCD7G@0ZhM6mmAYJSmahc@ zW_@=A?$`mDTOz&|Cgx~aubQ;^mAgf1GlCwd(roCz@!=Bq<{z@@`JEAzigVZDEUy-znPY$Hk$XRo z^sCSjHT#GZ%3fRd+5`eV2RAN<)ysg)rI4udUSptCJYjJ&<9d{6hIxjCQDf$p)8#(~mS|MxzAAi@I`~ zPlFR3f*P-GyQ565A5jkn)j(dw7Ay8#pjL$UFVPo0Wpk!LAM6tH#?FqRqSA@q0~sv~N{mxWf%)@TF!m zuTB_07Ph=y64`2shL1R}5i6X)ELX3bSt4nKS?_G$>(gn7CUWnh^sDt~z^6Q^?Zh|K z@w39v{xv`eJzZs|*bKpbw#5?r#!}JNqPY(Xvk~%tr@cb)>S|zmnV(BMkq>N0tzK%( zaRjXiwh1bb!3yQG^^Xa7SVMl%PX(WD#G^M; zv$%aZ_F8>DV(( zEl_GX?h9xlN=b-t`kqQXR3Z1ZCAcC9y}D%lA&l)Os(Td1I&Y~17SY(H`b^FMa%cr7 z^F6jkKhj;+t>d@{>MYGI_`c+TYPV3|$%z(FS|rc1Gy6G8Lr__M-z8Lgt+KE(lm%|o z8oU-PW`Ngfh=fbXo(7|z7aytJDS@S4AxHKJgnkY`7H{ff24gSgA8ce$hx5`meONgr z12yBieVk(%p!~OLnYa@XQ0v}~I}a2NL&F$3<$_24P;Q{Y-=E7K{LEZas*`sBi!h`~ zUJs$k_1D+U?U6fz7k?UkaO+hDmj6{)xNji`*2?Pn(0d>R8-|(YH-Em5<+^ga&PvKAx{AKvu=D`SD+_dy_Bl{Gd_1!^ep1uy$cAj0Xzxo3Je!GhVt=`mh#%jIasu`giEEHV!r&_M&| z+u9EI{y;za21l-)+=*VM#cLd@Ed|dwHUvC<-2`48pI6-zvJuo6X?>8+E(PUvw%n)U zo3yE?X-1v!1k(lFSvSq z=fs!67VzQzF@Ymy>)}SlLEYoa+3{NCEa-5m4UDd79jm&ihNYhRrQ5e%MuS|+x@|Zf zj5QXG%~I}w^HPi-IqoQhnrF7T9RAb{75vYYuAUl#TF2jTs|5K%!*dIbeeEZpT&Hrz z;nV%#XZ70$W9OT&2ruX6CnHQ){v?+L3pBtg4EZXr_PJt(eXat5`wg&Gv}4E_`Muci z$P)LQa1JcjBD&CVu_YR0v#|(xHVTD*-Bgpf_Yum+4sRRG9D|F;hF%C9!FZO=HTKo& z7ohgCy&u(-Q=w{iQ|FV=C!kF_+w6=37LRas zbViQi-RS%v#RAf~K8n#Jyd9mLqc}Li6%s~}@P35dqjPwKsiXKf!W$BHkZ^#6=_7m| zVeRPL9K|6LrjYP~g!Lob9%1n4JRQX+64sD#gM zdxXCuJR@Nf31>(#gM|O1vwRenNBdsl_MO?1*L`MF-haB&TjKuHonD3er>jXj^^bG4 z{IGI${>Qg;(x!T<6H#IBA6A0O#S!IqG7+&f5Qw6 z1oa}=7D2EGPW4}%PmUMBnMZV_i^8+$s1?Dc2m(cLCJId=uS0Mz(kB=eL8=HIMNlV# zEfIW-pkM^+B8V2jtq3|rFerjF5wwhsi4o+B!nerv{8uf(&Im$Aa4>>){rkLs<5L7l zBX}7>#R&HG@ALoNr{ijL^o+vD2ogr{E`n+i?1~^%1ZShLG&*8Na4~{@5sZrFL>tJTv{3OFGjt6BkuR zZ6Hp1)7L7B&?*Y9Zvc}gf!LWB~!laQK(x+DZ8AyVmd zDMgAB>XS}z5*m|`l@zH;s8d3a5*n0{orKaP#3dnE35`m~QbLIm;*-#ugv2CdE1gm$ z#3@CO(n(N4by9>TAzlf+N=Q^fl@daf(4K_cBqS`MS_z>_Xj4Lt5(<<~bW(&YpejS>Qs5VeGkC8R5%RtbShXi_>EN|CmNnk57* zon|FuDn*$RVw4cLgr+5AETLQpu}Y^;2}w$kxrDN%6SIVVrASsfl}Zt&gxDqYEg@+M z6-x+LLaP$;lr~HJb8j*I?e$Ohf9rdi|CmAkb$>JSuBfBJBI)7jPoPUk(Eow+B=~M$ zZ+Tx%1azNDTX64t5a{*Eo2skp1AVb6ej5xEK!4`G`VW^?2ntBBK02aDa61Z}BN!Y( z+USTNh5OObJ%Zs8q>kWm6zWFMK{^IVkUk2}Bd8r6o1+joI#NjRKnnFE*d9Uf2u?@P zI67)but9G>`4J4Q!LG}oKM@Q)>G?8G21Q{gwA06c*SRRGg z5oD2$A5thG!2${5M{qrY-Vv0MjwKSrkirEC`bRK6I+8~rjs#bvqlW||BuF5I_YqW& zppOJ&BuFB`3kfPn$NngUk06l*ZzQN9q_9JR5E2}aj`k5$l3v+w%^(z`NO(iS4iXNKFnxs2Bdi@^7wH@# zVG1cekk0y1+#X@@2-8UTM8X;pZjdm5gy*BPc@*nNxJAMs5}uH-frRrT%pPGN={zH0 z6DiK{A7*fd|066PVIv9WNSH;!9}9|_AyxJ1Gj5?+wb{t=dv;vxy- zNO(oU9ukg_&ID47CE+Cr`$#xO!Xy&Dkg$S;y(AnZVIm3NNLWR}9nu*>!esup_P#ux zs_$R_m@^ZJC`!l>G9}YmrbOnch)^kGiOecA$q*tHMMY7OB29+1BBYVXJS3UtWXy0+ zvg`Bt-p{>%+~58FaeuGQA7`C?)?WMU^X%6?`>gl#?B`jsuOw_G3A;zahLNyGBy0073qGB)J$z?M8?@u8GtNF+ z!ROhyt0LcYz!ybH?-TUfL8n)RLF*bPLe5Q?$Nw^oUowmTWfD)A!xN_POJ?wd3H)!< zdBSX-FqtRJP z7wgf@pmK3J0n{wkrBy-w;`^U}AvLlzet2OaaeS5>FTOCnT61d`x!r0^XIKt~yKUT6 zEd9XHYzVEP0CJ%c|91O>-6Jf4qEznlG?YGw@t2Us;f;q;=EPzN7csl^Sa$# zSONWxEO+bB#G)G6hq;Z6T;$)G-7Zr#;ebtCI4!`#o){0bOlaSG%1D5HbIvif&=o|$ z+z8L3(jd2PIjQ5gAb39^9#M059jNJZzN4Bq2rkMw9&E_vCB_%cx^}9|a7`l0=)3FL z>;=^3J8n9%+@&aLp4lZ!Sx&L2jcW+H%V@?Fuw7<~d0Lpe%kQ1wWyV?ej^ z!tPaLZIt#3_}t>OK*`sUaK#!81H``C#Yiyyy2o`M{gDZMB!w z`oGb=f3+=2ZA3}`dxT%L+QhBCj~9)r)xMvek92y!Q!U5yjZu-kMA7&C{CPLU+!2+( zMN+ykM6|AtFO;6HA_V22ckS{z*lq`UXyB|dwIJxKP|m+}SQ2#h9D<61-#}*r^*JEQ z4!RxWgD$I{0)4AJp55H=6x|q;Rqv%SMyaM{y>-i;qqNQWZow{d=%(hkOp6L0bTe~< zEPv2BbmMu4MblADl;T&@;#Ss=Zk(lweY6r1_^Gu~j_}KFPe*H&m~O_)u_80J!5R8{ zk|>aF)5aU_)F?iy$lvHP4Z7shyFXWEHL_}?x$bj_Og`^EOHCQX3A%e6#26f=K`(P> z4!u|;=nJ4W-*@{n7&`PkSTKX-w@|wFE@?ct4b;oT1TVXM56ylwEX%1WMsqG=E9ttW z(0nni)q~<{Oj@y(-T%vJOgg+qUQD!|EL7wh*S%MU=A<%KusuvcGo}?g4uCpHQV@G2 zD2^a0_)I{vB-w^vLNlLNIKfmjXF;*NfIlA1 zJWrfEd&2-td{JdCOrQZbW{Mk+vQB|i!;Vetn_q%7Df-5ug(PrO&GFk%rXskRGV7QPKCw# zgFgRmw=+lYk@25n*j(8A8~-|n^xli1pk7udN~JN2jK6MFX<`o9li@@$X^YV#id%Zg_5(j5I3R2)UUKhVZw1 z#LPo&J1a+?FU43C6iOu9z_$nFkhz5#$$-HFSo3KxM+XK0WoaAP@>6z5v#GIWNk0qJ7COX$cBYV)jr&DxDE!yy}r+pnLo?-lOVp zp_UaW>5|%wR{BPb8%Zl5zhzaH^UvGSwL5zvv#)oe(t!Z6Ce2<{F+k_O!NCudaJ(vw z*?VOv79_Y(U08S1ic52#H9;}wL^T!Y*t?lS1qpz`=aI(Bap90TA=2P@j5K6xRpVJH z_8RkM1yZPJ>JV`vs!W`&6KlS`K%*RWY`v>rp~?6CyU$RVpfQ;Z>ZYEDQ0mQvoRC!# zkd&Tb*kB1D?f%Z#iW_{8A+cvoQ|Pd&HrAB9Dm4N|S#u4nhj_tcd7XZ4q&gTA4P0ii zBMhV_wYo7!IbhPYz}P{cfoUD8QY7NTFvI0fz8C%O70T082Sk5chnfus_ca}AL2a|y zjowQ0s7!Se>1EPRQ2Xf8-L{wlFnc}f))hlbNbeFWo0P%~moxZ|aV9QGb$|SZfOuoq zww{&J;9B$5O<518z}07QdFUPuiodEibdxC;m3RUxv$PxF))gh&SHWRKT#D*8s#g@ zyQe|!&c5Z4;TnVf%bi84V$4bh8X~;GD0}W@uRAhevg~TSamPzACZ2S6GA$pZ8pM2h z)~rg#e?-?YOCQtPmNwka)xZoX6fNniDGImTvh7XKQbx_YcrO%A+(vD~Nfx{6Hj(i^ zII%XS9@OUaGEqozgV_`ukpM~|y^~lO*SDah7@21B{{Io7{1KrXa3aL+{{|7tKMT?S z_vQe^Iat(ns&P$s-#N7Qc!TBP(mHe`*1ICkhvb?or&s~=_n=nwsVIb+TS)aP=ipE0Wkb9|JA?lkwH%n_w~@lR5qMXq=PMHm&9nxgF}baB9* zJklnXCN@|yl|8WD`~|udEw(;_rU2}1@6hows|AnNK5nzqC_zQ?wq+MiJqJ1Ts!9p0 zedt+uQOc)s8u0LY`gd053UJHWn5TYNA7Je>Qo4nAK(|w5-&|!m_%1jmXOfZx>BShY zysgrOT-DK&BvE?EyOM|V)0KCSDblRNmm?BQr^zVC9Qz6^YZWADW_!TagIp~7uepK4 zfT`?Dt2^i{ZPyj43J)NcYc%4fpaPEXl-51!D~W7nUd0%k&<3l+S`{wo`{K3CBZ-*{ zmUx9)*bUWJ0cfaHfS)d^9@0JEb2!`bA>=ZOIKSPA4oc9rSMiFOLy6L7)q1IJSSs}? z%Xuvt)buXgTeY?&LECims%z;*bv1GsWxN{zu zJN0?(skh;fi*LA^a&jlkzJ%G6aQghCd;QC%!z0dJ2kR#CMX{%Tc>T+#p=kBS5Le>?n zQ_3%)8I2UvE*gW}dtE$@|tW2LBQ zrpMt6SWu*zqQ8_Cv$rX&5G%2P)CwOgK8RF8eyZV)>mM)_lFsL<>q&~~z$pEdGjSLkYK~-E@NvlP6qgjCf`4gu5 z(X_qCr@b9ckms(HX5+XpUeS_$iSBF}$aOCoSKrJ4B0WKyS0zSAbs`j19+JRdL_NP8 zB?&T?SnFSEglM6_w5cWF1z!7F@3V#W8dP0$)x;_l!}SxxPPxs!ki)0leZ_|k)SY&A z!$90=DCAd}{3Klgno&Idbh@5|b+TXfsi~2$7he_MFjFU1J8Yz}xwQ(*JLFi&Psm_V z-P1Gc%xutC_1>#W{cdnQ_w&u~#q1wu79T^DR zy-ZvZHK4R*TYP!GF_g4+NpCVw`ZEXkb2F;lUvDM-H_QS4LU;W7#KYLUpw{$+`E){@F8TLfBJR$4L=b!r9CW!HWdy~9?e~y1nWYQ}g!T-9- z;&Q%#+hPmk*UTod*jT8@+nr*F3MN76*Jn1ov2P%bLHnv$0^J!`6{{AzwaD9DTHv;*=TN`FW_T0 zKaaBqBdAbVI2w&>z+2^&dfURS!HbKc9IwN6fmdUkHsvM3OEsBzMEk}_{LQUIw5zgv zwJv7~+QYlRx9gGwFcLJBdf#&l7!PrNu6xG?oP)cs#ZNK;lUnp>R|SFdXWfQa*AE$i+l) zFW2a2BE-`V_86_pvk zCVjfz0jld)olu;R0X+%k`e)jzz#!eTZrPRZiMVuB$w{AiSDG4i#a5)`j3t4lL)0}@ z%zlux$G?QKG70qJQAT%CHX7Bv#4Jixk15Bbj@%_p5xfXqM^|HQOwR?^HhkF7tZxG) z+gFs8q^yR5-EjpBY1MG0E^kuVJ7qM(ac8HCr6T5=nb6cgitSqHMiHrI|qy4Ww-vzrE?@Qv(_(>9->Y?g_b4^Ixki$JQF7-nC; zL@3(Ucfs^zG8COGOy+gqg{<~35AFA{*) zH8p-`Uo(egmQQ+p=Q|4Jwa0~XD5K%V9b8%=Pwr#ROJ@!&lhMVBf&#mOPWEHAK2j>R z0TscEfL^DbC)&NqU_isoMDH0JD$wK_N=k_arLDzZPaSta)%P=vHxGuPp4u1B*vlWG zfq`YRtHH@7UStwf?h>>Z9R3%^f^YK={h z?qZa`Xe{}r=o?4e{4`Xc?483p>ZMzkco8Z{6=5?Vda)CVwiv#Y8!3XK(>Iu|Q6Ge? zE@lm@QmZhXw20=NcS2a$w=K2L`Vp2*6K2`{acYSdX~OG1tLavq)5kI#!CMamt|#N) zT0G<;0yo<2irk{bh&eO9%Ez1~r{z{!^FrW8G1xJ)ALJu<#|_4PZl`N~yw&bX~@{pjYj@bTJF32;SO zafDhs5`{Ae-~00XFxnG$SKxRkH*k4d5-#=WHj3Z4dWQ4$Yb-S;rI0yWgk_J0gq}1% zf+c4Zw!D4x9k1T5tCLaP0I7Roo_Q?D;1xACJ*!&ILe3ac(b+zJETMxWBK1~dwlh+f zXiC|zdS?n-n7<6oZ z!%^PB2tBSwu1SnngjUT}?A{a*dh5;hWts1W=6l~8N0#- zC~r?*P$CwOeJ)$v!Vfvj);*7UUkSG~1#EusNDJ~9^Z1SACSsFl(JzypRG9kEgpO{v zCET8)8|M~D&*s7;7 zkXNG&J8EyO+S;Oyw~G()SX!-O!2k)Pg)j zclleg=QUQ!SjW$wrHK_pq&!NxY2MneuYJ zbIqs~b~90{8y+V-mkH@9dgYd=a&M70Cw; z&x%f?lD3{TfU%tLTqdNaYW<>viH}_=ipJ{A&UGLC3h0-q>W^7HM063mbj3Wl5$Cy1 z$qQkOMbmebba*M|2+w6gdJ5it=;SKTrv_CgUMEO>i3T;iSzMK^3ZPDV^SscLO3?W3 zj9Kmze$c9>asF^ZEaACKNKX+>WD$doVNcNn^{y);Oh!fX<0@ai`cV|k)h21pGT0(2 z<&*CW_)no_xj|e4pjZ(~{pBPn_gG4tcFI2c5JPK(Y zb2*>`9?orhy#BECFVAH{dRlQgF-zvFBC5E28A;rj03Y)>W-D_#K;H|-{3tmY@ReF5 zgk6sEmvnN;bD5ByqG_#|*{05$gA1IH^fmOsZd*S{V`MFQd+;n=s=7hCg@s6m+Du5xN@u#( zQW-9JE)&vIG+CZ_S7m^eT-CVo1n0(LihwWUpWZ%0W0&`zZ+qg5Ml}Yx3v5}@4381b zbg&oUxlBk;L58!J?(I`@;8F0%M;09+@bq%jR{6Zw+7yjy?r`2O%ZO%p*9Y9QAmiUE-PZI;ZAp5%3dkJS zr$}Cb(IM3WmF3CnkjG?Bba|WtaCQy(-t#OQ*m>{s`YO2>_{nIDUFycbzIew;<@=#a z($jprt}@ZHb$AEr*XTZeo2DO9Go*=>dd!2F@*4-LdOaYedf*8Emi>?vce*S1dKP4L zc)?em_Uxzh6iy&BVMX4ylPN%FJf1x~FA~|`JztS=q!4-XoSKhXg@J7ii}7U_PjFy6 zSHL#r6~Lk*@%-rVxj!Wq13pU1dm(>HEPqNY{})Rvf2KHp=<0trUCrox(8K%4qG9q6 zZscza$|9k~vd?j^v)2z-wI8I)k9GbsS6E!*pP7=yuD?y7ep642GmyU!<^Orz-;=Gy zb^nX){CDFP`~LD7i_@CF?E2z%|9RK{b@%?eU0B@g-%wk8=btyc*!8#X^80)K>;7#b F{RgL8KBWKv diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 27b98eb5b7..b17dfcfa19 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1122,7 +1122,7 @@ void OperationalSpaceControl::CheckTracking( if (soft_constraint_cost_ != nullptr) { soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); } - if (y_soft_constraint_cost[0] > 2e6 || isnan(y_soft_constraint_cost[0])) { + if (y_soft_constraint_cost[0] > 1e5 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } From 0e8f2ba306dccdde8aec06a2909e1b603fa911aa Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 17 Feb 2023 16:15:16 -0500 Subject: [PATCH 376/758] adding plots for paper --- .../jumping_parameter_study.py | 18 +++++---- .../pydairlib/analysis/log_plotter_cassie.py | 6 +-- .../pydairlib/analysis/mbp_plotting_utils.py | 22 +++++++++-- .../plot_configs/cassie_jumping_plot.yaml | 18 ++++----- .../plot_configs/cassie_running_plot.yaml | 26 ++++++------- bindings/pydairlib/common/plot_styler.py | 2 +- bindings/pydairlib/lcm/process_lcm_log.py | 10 ++--- .../osc_jump/osc_jumping_gains_long.yaml | 37 +++++++++---------- examples/Cassie/run_osc_jumping_controller.cc | 13 ++++--- 9 files changed, 86 insertions(+), 66 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py index dfed03c0c8..ca9f240448 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -27,7 +27,7 @@ def main(): parameter = "landing_delay" simulator = 'DRAKE' # trajectory_names = ['jump', 'box_jump', 'long_jump', 'down_jump'] - trajectory_names = ['down_jump'] + trajectory_names = ['long_jump'] gains_path = '' trajectory_name = '' results_folder = '' @@ -42,14 +42,18 @@ def main(): landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - # nominal_delay = 0.025 # long - nominal_delay = 0.065 # down + nominal_delay = 0.025 # long + # nominal_delay = 0.065 # down # nominal_delay = 0.000 # jump + # nominal_threshold = 0.000 # box + nominal_threshold = 0.000 # long + # nominal_threshold = 0.000 # down + # nominal_threshold = 0.000 # jump landing_times += nominal_delay - 0.5 * 0.05 # impact_thresholds = np.arange(0.000, 0.100, 0.025) impact_thresholds = np.arange(0.000, 0.125, 0.025) - realtime_rate = 0.5 + realtime_rate = 0.25 publish_rate = 2000.0 # Add an extra second to the runtime of the simulator process to account for start up and stopping time @@ -139,7 +143,7 @@ def main(): f = open(gains_path + gain_filename, 'r') filedata = f.read() f.close() - newdata = filedata.replace('impact_threshold: %.3f' % 0.025, + newdata = filedata.replace('impact_threshold: %.3f' % nominal_threshold, 'impact_threshold: %.3f' % impact_threshold) newdata = newdata.replace('landing_delay: %.3f' % nominal_delay, 'landing_delay: %.3f' % landing_time) @@ -235,6 +239,6 @@ def plot_success(): plt.show() if __name__ == "__main__": - # main() + main() # construct_success_plot() - plot_success() + # plot_success() diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index feb5c13e49..495a0cbfb8 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -178,9 +178,9 @@ def main(): plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - # if plot_config.plot_active_tracking_datas: - # plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - # plot.save_fig('active_tracking_datas.png') + if plot_config.plot_active_tracking_datas: + plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.save_fig('active_tracking_datas.png') plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2ce5c02433..db5047cf5b 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -659,6 +659,16 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_ n_tracking_datas = len(tracking_data_names) tracking_data_legend_elements = [] + tracking_data_name_dict = {'pelvis_trans_traj': 'Pelvis Position', + 'left_ft_traj': 'Left Foot Position', + 'right_ft_traj': 'Right Foot Position', + 'pelvis_rot_tracking_data': 'Pelvis Orientation', + 'left_toe_angle_traj': 'Left Toe Joint Angle', + 'right_toe_angle_traj': 'Right Toe Joint Angle', + 'swing_hip_yaw_left_traj': 'Left Hip Yaw Angle', + 'swing_hip_yaw_right_traj': 'Right Hip Yaw Angle', + } + for i, tracking_data_name in enumerate(tracking_data_names): # tracking_data_name = tracking_data_names[i] tracking_data = osc_debug['osc_debug_tracking_datas'][ @@ -667,9 +677,9 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_ (i+0.75)/n_tracking_datas, where=tracking_data.is_active.astype(bool)[ :fsm_time.shape[0]], - color=ps.cmap(2 * i), alpha=0.5) + color=ps.cmap(2 * i), alpha=0.7) tracking_data_legend_elements.append(Patch(facecolor=ps.cmap(2 * i), - alpha=0.3, label=tracking_data_name)) + alpha=0.7, label=tracking_data_name_dict[tracking_data_name])) # uses default color map legend_elements = [] @@ -677,11 +687,17 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_ ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2 * i), alpha=0.2) if fsm_state_names: legend_elements.append(Patch(facecolor=ps.cmap(2 * i), alpha=0.3, label=fsm_state_names[i])) + ps.tight_layout() if len(legend_elements) > 0: legend = ax.legend(handles=legend_elements, loc=4) + ax.add_artist(legend) legend = ax.legend(handles=tracking_data_legend_elements, loc=1) - # ax.add_artist(legend) + ax.add_artist(legend) ax.relim() + ax.set_yticklabels([]) + ax.set_yticks([]) + ax.set_xlabel('Time (s)') + ax.set_ylabel('Tracking Objective') return ps \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 4ed22b87ff..1b5196595a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -4,24 +4,24 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_JUMPING" channel_osc: "OSC_DEBUG_JUMPING" use_archived_lcmtypes: false -use_default_styling: false +use_default_styling: true # Log time to stop at (seconds, -1 for whole log) -start_time: 7 -duration: -1 +start_time: 18.47 +duration: 1.5 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true -plot_floating_base_velocities: true +plot_floating_base_positions: false +plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false -plot_joint_positions: true -plot_joint_velocities: true -plot_measured_efforts: true -plot_commanded_efforts: true +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +plot_commanded_efforts: false plot_contact_forces: false special_positions_to_plot: [ 'hip_pitch_left'] special_velocities_to_plot: ['hip_pitch_leftdot'] diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index e6b392a168..233315560b 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -4,25 +4,25 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false -use_default_styling: false +use_default_styling: true # Log time to stop at (seconds, -1 for whole log) -start_time: 6 +start_time: 0.76 #duration: 0.47 -duration: 5 +duration: 1.58 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true -plot_floating_base_velocities: true -plot_floating_base_velocity_body_frame: true +plot_floating_base_positions: false +plot_floating_base_velocities: false +plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: true -plot_commanded_efforts: true +plot_measured_efforts: false +plot_commanded_efforts: false plot_contact_forces: false special_positions_to_plot: [ 'knee_joint_left', 'knee_joint_right', 'ankle_spring_joint_left', 'ankle_spring_joint_right' ] #special_positions_to_plot: [ 'hip_pitch_left', 'hip_pitch_right', 'hip_roll_left', 'hip_roll_right' ] @@ -37,13 +37,13 @@ foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] foot_xyz_to_plot: { 'right': [ 2 ], 'left': [ 2 ] } #foot_xyz_to_plot: { } -pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' +pt_on_foot_to_plot: ['rear'] # takes value 'front', 'mid', or 'rear' # Desired osc plots -plot_qp_costs: true -plot_qp_solve_time: true -plot_qp_solutions: true -plot_tracking_costs: true +plot_qp_costs: false +plot_qp_solve_time: false +plot_qp_solutions: false +plot_tracking_costs: false plot_active_tracking_datas: true tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 31b4abb6bc..cc6a6b3711 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -14,7 +14,7 @@ def set_default_styling(): # matplotlib.rcParams['figure.figsize'] = 20, 6 matplotlib.rcParams['figure.figsize'] = 8, 6 matplotlib.rcParams['figure.autolayout'] = True - font = {'size': 12} + font = {'size': 16} matplotlib.rc('font', **font) matplotlib.rcParams['lines.linewidth'] = 2 plt.set_cmap('tab20') diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index 8c7ea8e764..65e1fe28fd 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -22,8 +22,8 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca pass first_timestamp = lcm_log.read_next_event().timestamp start_timestamp = int(first_timestamp + start_time * 1e6) - # print('Start time: ' + str(start_time)) - # print('Duration: ' + str(duration)) + print('Start time: ' + str(start_time)) + print('Duration: ' + str(duration)) lcm_log.seek_to_timestamp(start_timestamp) t = lcm_log.read_next_event().timestamp lcm_log.seek_to_timestamp(start_timestamp) @@ -36,9 +36,9 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca else: data_to_process[event.channel] = \ [lcm_channels[event.channel].decode(event.data)] - # if event.eventnum % 50000 == 0: - # print(f'processed {(event.timestamp - t) * 1e-6:.1f}' - # f' seconds of log data') + if event.eventnum % 50000 == 0: + print(f'processed {(event.timestamp - t) * 1e-6:.1f}' + f' seconds of log data') if 0 < duration <= (event.timestamp - t) * 1e-6: break event = lcm_log.read_next_event() diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml index 9c4d07b36a..aabe377b76 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml @@ -18,8 +18,8 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: -0.045 -land_x_offset: 0.02 +crouch_x_offset: -0.04 +land_x_offset: 0.00 relative_feet: true mu: 0.6 @@ -32,23 +32,23 @@ w_hip_yaw: 2.5 hip_yaw_kp: 100 hip_yaw_kd: 5 -min_pelvis_acc: -6 +min_pelvis_acc: -8 max_pelvis_acc: 10000 -impact_threshold: 0.100 +impact_threshold: 0.000 impact_tau: 0.005 landing_delay: 0.025 #landing_delay: 0. CoMW: [20, 0, 0, - 0, 20, 0, + 0, 2, 0, 0, 0, 20] CoMKp: - [100, 0, 0, - 0, 100, 0, - 0, 0, 100] + [40, 0, 0, + 0, 50, 0, + 0, 0, 40] CoMKd: - [ 15, 0, 0, + [ 7.5, 0, 0, 0, 5, 0, 0, 0, 5] PelvisRotW: @@ -56,23 +56,22 @@ PelvisRotW: 0, 5, 0, 0, 0, 1] PelvisRotKp: - [400., 0, 0, - 0, 400., 0, + [150., 0, 0, + 0, 200., 0, 0, 0, 0.] PelvisRotKd: [10, 0, 0, 0, 10, 0, 0, 0, 5.] FlightFootW: - [100, 0, 0, + [10, 0, 0, 0, 100, 0, 0, 0, 10] FlightFootKp: - [350, 0, 0, - 0, 250, 0, - 0, 0, 250] + [125, 0, 0, + 0, 50, 0, + 0, 0, 150] FlightFootKd: - [25, 0, 0, - 0, 10, 0, - 0, 0, 10] - + [2.5, 0, 0, + 0, 2.5, 0, + 0, 0, 0] \ No newline at end of file diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index dd93d12f5a..6b10d8286f 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -254,7 +254,7 @@ int DoMain(int argc, char* argv[]) { r_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); auto pelvis_rot_traj_generator = builder.AddSystem( - pelvis_rot_trajectory, "pelvis_rot_tracking_data", FLAGS_delay_time); + pelvis_rot_trajectory, "pelvis_rot_traj", FLAGS_delay_time); auto fsm = builder.AddSystem( plant_w_spr, transition_times, FLAGS_contact_based_fsm, gains.impact_threshold, (osc_jump::JUMPING_FSM_STATE)FLAGS_init_fsm_state); @@ -368,7 +368,7 @@ int DoMain(int argc, char* argv[]) { "pelvis_trans_traj", osc_gains.K_p_com, osc_gains.K_d_com, osc_gains.W_com, plant_w_spr, plant_w_spr); auto pelvis_rot_tracking_data = std::make_unique( - "pelvis_rot_tracking_data", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); @@ -376,7 +376,8 @@ int DoMain(int argc, char* argv[]) { } pelvis_rot_tracking_data->SetImpactInvariantProjection(true); pelvis_tracking_data->SetImpactInvariantProjection(true); - VectorXd pelvis_acc_lb = osc_gains.min_pelvis_acc * Vector3d::Ones(); + VectorXd pelvis_acc_lb = Vector3d::Ones(); + pelvis_acc_lb << -10000, -10000, osc_gains.min_pelvis_acc; VectorXd pelvis_acc_ub = osc_gains.max_pelvis_acc * Vector3d::Ones(); pelvis_tracking_data->SetCmdAccelerationBounds(pelvis_acc_lb, pelvis_acc_ub); @@ -414,10 +415,10 @@ int DoMain(int argc, char* argv[]) { // Flight phase hip yaw tracking auto left_hip_yaw_tracking_data = std::make_unique( - "swing_hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant_w_spr, plant_w_spr); auto right_hip_yaw_tracking_data = std::make_unique( - "swing_hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant_w_spr, plant_w_spr); left_hip_yaw_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); @@ -504,7 +505,7 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("right_toe_angle_traj")); builder.Connect( pelvis_rot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("pelvis_rot_tracking_data")); + osc->get_input_port_tracking_data("pelvis_rot_traj")); // FSM connections builder.Connect(contact_results_sub->get_output_port(), From cde69d5d22481c6f36da832edeb2749c839c0e6b Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 17 Feb 2023 18:56:45 -0500 Subject: [PATCH 377/758] updating parameter study to run multiple experiments per set of parameters --- .../jumping_parameter_study.py | 234 +++++++++--------- 1 file changed, 121 insertions(+), 113 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py index ca9f240448..2d5d7963cb 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -32,7 +32,7 @@ def main(): trajectory_name = '' results_folder = '' delay_time = 2.0 - traj_time = 5.0 + traj_time = 4.0 sim_time = 0 start_time = 0 if controller_type == 'jumping': @@ -42,7 +42,7 @@ def main(): landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - nominal_delay = 0.025 # long + nominal_delay = 0.040 # long # nominal_delay = 0.065 # down # nominal_delay = 0.000 # jump # nominal_threshold = 0.000 # box @@ -66,120 +66,121 @@ def main(): save_gains_cmd = '' # for i in range(0, disturbances.shape[0]): - for traj in trajectory_names: - for impact_threshold in impact_thresholds: - for landing_time in landing_times: - log_suffix = '' - if parameter == 'landing_delay': - log_suffix = 't_%.3f' % (landing_time) + '_duration_%.3f' % ( - impact_threshold) - log_path = results_folder + traj + '/lcmlog-' + log_suffix - print(log_path) - gain_filename = '' - if traj == 'jump' or traj == 'long_jump': - if traj == 'jump': - gain_filename = 'osc_jumping_gains.yaml' - elif traj == 'long_jump': - gain_filename = 'osc_jumping_gains_long.yaml' - controller_cmd = [ - 'bazel-bin/examples/Cassie/run_osc_jumping_controller', - '--delay_time=%.1f' % delay_time, - '--channel_u=OSC_JUMPING', - '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', - '--traj_name=%s' % traj, - ] - simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim', - '--init_height=%.1f' % 0.9, - '--toe_spread=0.12', - '--target_realtime_rate=%.2f' % realtime_rate, - '--dt=%.5f' % 1e-3, - '--publish_rate=%d' % publish_rate, - '--end_time=%.3f' % sim_time, - '--channel_u=OSC_JUMPING', - ] - elif traj == 'box_jump': - controller_cmd = [ - 'bazel-bin/examples/Cassie/run_osc_jumping_controller', - '--delay_time=%.1f' % delay_time, - '--channel_u=OSC_JUMPING', - '--traj_name=%s' % traj, - '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', - ] - simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim_w_platform', - '--init_height=%.1f' % 0.9, - '--target_realtime_rate=%.2f' % realtime_rate, - '--dt=%.5f' % 1e-3, - '--publish_rate=%d' % publish_rate, - '--end_time=%.3f' % sim_time, - '--channel_u=OSC_JUMPING', - '--traj_name=box_jump', - '--platform_height=0.5', - '--platform_x=0.25', - '--visualize=1', - ] - gain_filename = 'osc_jumping_gains_box.yaml' - elif traj == 'down_jump': - controller_cmd = [ - 'bazel-bin/examples/Cassie/run_osc_jumping_controller', - '--delay_time=%.1f' % delay_time, - '--channel_u=OSC_JUMPING', - '--traj_name=%s' % traj, - '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', - ] - simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim_w_platform', - '--init_height=%.1f' % 0.9, - '--target_realtime_rate=%.2f' % realtime_rate, - '--dt=%.5f' % 1e-3, - '--publish_rate=%d' % publish_rate, - '--end_time=%.3f' % sim_time, - '--channel_u=OSC_JUMPING', - '--traj_name=down_jump', - '--platform_height=0.5', - '--platform_x=-0.99', - '--visualize=1', - ] - gain_filename = 'osc_jumping_gains_down.yaml' - - f = open(gains_path + gain_filename, 'r') - filedata = f.read() - f.close() - newdata = filedata.replace('impact_threshold: %.3f' % nominal_threshold, - 'impact_threshold: %.3f' % impact_threshold) - newdata = newdata.replace('landing_delay: %.3f' % nominal_delay, - 'landing_delay: %.3f' % landing_time) - f = open(gains_path + 'osc_jumping_gains_param.yaml', 'w') - f.write(newdata) - f.close() - - lcm_logger_cmd = ['lcm-logger', - '-f', - '%s' % log_path, - ] - - parameter_file.write(log_path + '\n') - parameter_file.write(' '.join(controller_cmd) + '\n') - parameter_file.write(' '.join(simulator_cmd) + '\n') - parameter_file.write('**********\n') - controller_process = subprocess.Popen(controller_cmd) - logger_process = subprocess.Popen(lcm_logger_cmd) - time.sleep(controller_startup_time) - simulator_process = subprocess.Popen(simulator_cmd) - time.sleep(sim_run_time) - simulator_process.kill() - controller_process.kill() - logger_process.kill() + for i in range(5): + for traj in trajectory_names: + for impact_threshold in impact_thresholds: + for landing_time in landing_times: + log_suffix = '' + if parameter == 'landing_delay': + log_suffix = 't_%.3f' % (landing_time) + '_duration_%.3f' % ( + impact_threshold) + log_path = results_folder + traj + '_' + str(i) + '/lcmlog-' + log_suffix + print(log_path) + gain_filename = '' + if traj == 'jump' or traj == 'long_jump': + if traj == 'jump': + gain_filename = 'osc_jumping_gains.yaml' + elif traj == 'long_jump': + gain_filename = 'osc_jumping_gains_long.yaml' + controller_cmd = [ + 'bazel-bin/examples/Cassie/run_osc_jumping_controller', + '--delay_time=%.1f' % delay_time, + '--channel_u=OSC_JUMPING', + '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', + '--traj_name=%s' % traj, + ] + simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim', + '--init_height=%.1f' % 0.9, + '--toe_spread=0.12', + '--target_realtime_rate=%.2f' % realtime_rate, + '--dt=%.5f' % 1e-3, + '--publish_rate=%d' % publish_rate, + '--end_time=%.3f' % sim_time, + '--channel_u=OSC_JUMPING', + ] + elif traj == 'box_jump': + controller_cmd = [ + 'bazel-bin/examples/Cassie/run_osc_jumping_controller', + '--delay_time=%.1f' % delay_time, + '--channel_u=OSC_JUMPING', + '--traj_name=%s' % traj, + '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', + ] + simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim_w_platform', + '--init_height=%.1f' % 0.9, + '--target_realtime_rate=%.2f' % realtime_rate, + '--dt=%.5f' % 1e-3, + '--publish_rate=%d' % publish_rate, + '--end_time=%.3f' % sim_time, + '--channel_u=OSC_JUMPING', + '--traj_name=box_jump', + '--platform_height=0.5', + '--platform_x=0.25', + '--visualize=1', + ] + gain_filename = 'osc_jumping_gains_box.yaml' + elif traj == 'down_jump': + controller_cmd = [ + 'bazel-bin/examples/Cassie/run_osc_jumping_controller', + '--delay_time=%.1f' % delay_time, + '--channel_u=OSC_JUMPING', + '--traj_name=%s' % traj, + '--gains_filename=examples/Cassie/osc_jump/osc_jumping_gains_param.yaml', + ] + simulator_cmd = ['bazel-bin/examples/Cassie/multibody_sim_w_platform', + '--init_height=%.1f' % 0.9, + '--target_realtime_rate=%.2f' % realtime_rate, + '--dt=%.5f' % 1e-3, + '--publish_rate=%d' % publish_rate, + '--end_time=%.3f' % sim_time, + '--channel_u=OSC_JUMPING', + '--traj_name=down_jump', + '--platform_height=0.5', + '--platform_x=-0.99', + '--visualize=1', + ] + gain_filename = 'osc_jumping_gains_down.yaml' + + f = open(gains_path + gain_filename, 'r') + filedata = f.read() + f.close() + newdata = filedata.replace('impact_threshold: %.3f' % nominal_threshold, + 'impact_threshold: %.3f' % impact_threshold) + newdata = newdata.replace('landing_delay: %.3f' % nominal_delay, + 'landing_delay: %.3f' % landing_time) + f = open(gains_path + 'osc_jumping_gains_param.yaml', 'w') + f.write(newdata) + f.close() + + lcm_logger_cmd = ['lcm-logger', + '-f', + '%s' % log_path, + ] + + parameter_file.write(log_path + '\n') + parameter_file.write(' '.join(controller_cmd) + '\n') + parameter_file.write(' '.join(simulator_cmd) + '\n') + parameter_file.write('**********\n') + controller_process = subprocess.Popen(controller_cmd) + logger_process = subprocess.Popen(lcm_logger_cmd) + time.sleep(controller_startup_time) + simulator_process = subprocess.Popen(simulator_cmd) + time.sleep(sim_run_time) + simulator_process.kill() + controller_process.kill() + logger_process.kill() parameter_file.close() def construct_success_plot(): results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" - all_logs = sorted(glob.glob(results_folder + 'down_jump/' + 'lcmlog-*')) + all_logs = sorted(glob.glob(results_folder + 'long_jump_0/' + 'lcmlog-*')) landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - # nominal_delay = 0.025 # long - nominal_delay = 0.065 # down + nominal_delay = 0.025 # long + # nominal_delay = 0.065 # down # nominal_delay = 0.000 # jump landing_times += nominal_delay - 0.5 * 0.05 impact_thresholds = np.arange(0.000, 0.125, 0.025) @@ -207,7 +208,7 @@ def construct_success_plot(): print(land_idx) impact_idx = int(np.round(float(impact_threshold)/0.02500)) success[land_idx, impact_idx] = not np.any(robot_output['q'][:, 6] < 0.4) - np.save('down_jump_success', success) + np.save('long_jump_0_success', success) plt.imshow(success) plt.show() @@ -215,14 +216,21 @@ def plot_success(): landing_times = np.linspace(0.000, 0.050, 11) landing_times -= 0.025 impact_thresholds = np.linspace(0.000, 0.100, 5) + success = np.load('long_jump_0_success.npy') + total_success = np.zeros(success.shape) + total_success += success + for i in range(1, 5): + success = np.load('long_jump_' + str(i) + '_success.npy') + total_success += success - success = np.load('long_jump_success.npy') # plt.imshow(success, cmap='tab20') ps = plot_styler.PlotStyler() plot_styler.PlotStyler.set_default_styling() cmap = matplotlib.colors.ListedColormap([ps.grey, ps.blue]) - plt.figure() - plt.imshow(success, cmap=cmap) + fig = plt.figure() + # plt.imshow(total_success, cmap=cmap) + im = plt.imshow(total_success, cmap='Reds') + plt.colorbar(im) plt.xlabel('Projection Window Duration (s)') plt.ylabel('Deviation from Nominal Transition Time (s)') ax = plt.gca() @@ -233,8 +241,8 @@ def plot_success(): ax.set_yticklabels(np.around(landing_times, 3).tolist()) ax.grid(which="minor", color='k', linestyle='-', linewidth=2) - legend_elements = [Patch(facecolor=ps.grey, alpha=0.7, label='Fail'), Patch(facecolor=ps.blue, alpha=0.3, label='Success')] - legend = ax.legend(handles=legend_elements, loc=1) + # legend_elements = [Patch(facecolor=ps.grey, alpha=0.7, label='Fail'), Patch(facecolor=ps.blue, alpha=0.7, label='Success')] + # legend = ax.legend(handles=legend_elements, loc=1) plt.savefig('long_jump_success.png', dpi=240) plt.show() From 6c1881e99a2b3e588f0f464fd76566c92a32ab09 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 19 Feb 2023 17:28:52 -0500 Subject: [PATCH 378/758] updating parameter study --- .../jumping_parameter_study.py | 28 +++++++++-------- .../pydairlib/analysis/log_plotter_cassie.py | 1 + .../plot_configs/cassie_jumping_plot.yaml | 8 ++--- .../osc_jump/osc_jumping_gains_down.yaml | 30 +++++++++---------- 4 files changed, 36 insertions(+), 31 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py index 2d5d7963cb..5e556eae9b 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -43,7 +43,7 @@ def main(): landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box nominal_delay = 0.040 # long - # nominal_delay = 0.065 # down + # nominal_delay = 0.055 # down # nominal_delay = 0.000 # jump # nominal_threshold = 0.000 # box nominal_threshold = 0.000 # long @@ -51,7 +51,7 @@ def main(): # nominal_threshold = 0.000 # jump landing_times += nominal_delay - 0.5 * 0.05 # impact_thresholds = np.arange(0.000, 0.100, 0.025) - impact_thresholds = np.arange(0.000, 0.125, 0.025) + impact_thresholds = np.arange(0.000, 0.110, 0.010) realtime_rate = 0.25 publish_rate = 2000.0 @@ -175,15 +175,15 @@ def main(): def construct_success_plot(): results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" - all_logs = sorted(glob.glob(results_folder + 'long_jump_0/' + 'lcmlog-*')) + all_logs = sorted(glob.glob(results_folder + 'down_jump_4/' + 'lcmlog-*')) landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - nominal_delay = 0.025 # long - # nominal_delay = 0.065 # down + # nominal_delay = 0.025 # long + nominal_delay = 0.055 # down # nominal_delay = 0.000 # jump landing_times += nominal_delay - 0.5 * 0.05 - impact_thresholds = np.arange(0.000, 0.125, 0.025) + impact_thresholds = np.arange(0.000, 0.110, 0.010) success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) # xx, yy = np.meshgrid(landing_times, impact_thresholds) for log_filename in all_logs: @@ -205,22 +205,25 @@ def construct_success_plot(): 'OSC_DEBUG_JUMPING') land_idx = int(np.round((float(landing_time) - (nominal_delay - 0.025)) / 0.005)) print(landing_time) + impact_idx = int(np.round(float(impact_threshold)/0.010)) print(land_idx) - impact_idx = int(np.round(float(impact_threshold)/0.02500)) + print(impact_idx) success[land_idx, impact_idx] = not np.any(robot_output['q'][:, 6] < 0.4) - np.save('long_jump_0_success', success) + np.save('down_jump_4_success', success) plt.imshow(success) plt.show() def plot_success(): landing_times = np.linspace(0.000, 0.050, 11) landing_times -= 0.025 - impact_thresholds = np.linspace(0.000, 0.100, 5) - success = np.load('long_jump_0_success.npy') + impact_thresholds = np.linspace(0.000, 0.100, 11) + # success = np.load('long_jump_0_success.npy') + success = np.load('down_jump_0_success.npy') total_success = np.zeros(success.shape) total_success += success for i in range(1, 5): - success = np.load('long_jump_' + str(i) + '_success.npy') + # success = np.load('long_jump_' + str(i) + '_success.npy') + success = np.load('down_jump_' + str(i) + '_success.npy') total_success += success # plt.imshow(success, cmap='tab20') @@ -243,7 +246,8 @@ def plot_success(): # legend_elements = [Patch(facecolor=ps.grey, alpha=0.7, label='Fail'), Patch(facecolor=ps.blue, alpha=0.7, label='Success')] # legend = ax.legend(handles=legend_elements, loc=1) - plt.savefig('long_jump_success.png', dpi=240) + # plt.savefig('long_jump_success.png', dpi=240) + plt.savefig('down_jump_success.png', dpi=240) plt.show() if __name__ == "__main__": diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 495a0cbfb8..0666359f35 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -173,6 +173,7 @@ def main(): plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, foot_frames, pts, dims, plot) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.save_fig('foot_contact_vertical_position.png') if plot_config.plot_qp_solve_time: plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 1b5196595a..2b98eb9e87 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -7,8 +7,8 @@ use_archived_lcmtypes: false use_default_styling: true # Log time to stop at (seconds, -1 for whole log) -start_time: 18.47 -duration: 1.5 +start_time: 0 +duration: -1 # Plant properties use_springs: true @@ -42,13 +42,13 @@ plot_qp_costs: true plot_qp_solve_time: false plot_qp_solutions: true plot_tracking_costs: true -plot_active_tracking_datas: true +plot_active_tracking_datas: false tracking_datas_to_plot: { pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, - left_ft_traj: {'dims': [2], 'derivs': ['pos']}, +# left_ft_traj: {'dims': [2], 'derivs': ['pos']}, # right_ft_z_traj: {'dims': [2], 'derivs': ['pos']} # left_toe_angle_traj: {'dims': [0], 'derivs': ['vel']} # right_toe_angle_traj: {'dims': [0], 'derivs': ['accel']} diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml index a45e65433a..72915406b7 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml @@ -18,7 +18,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: -0.015 +crouch_x_offset: -0.03 land_x_offset: 0.00 relative_feet: true @@ -32,21 +32,21 @@ w_hip_yaw: 100 hip_yaw_kp: 100 hip_yaw_kd: 10 -min_pelvis_acc: -5 +min_pelvis_acc: -3.5 max_pelvis_acc: 10000 -impact_threshold: 0.025 +impact_threshold: 0.000 impact_tau: 0.005 -landing_delay: 0.065 +landing_delay: 0.055 #landing_delay: 0. CoMW: [20, 0, 0, - 0, 20, 0, + 0, 2, 0, 0, 0, 20] CoMKp: [100, 0, 0, - 0, 100, 0, - 0, 0, 100] + 0, 50, 0, + 0, 0, 40] CoMKd: [ 15, 0, 0, 0, 5, 0, @@ -56,8 +56,8 @@ PelvisRotW: 0, 5, 0, 0, 0, 1] PelvisRotKp: - [400., 0, 0, - 0, 400., 0, + [150., 0, 0, + 0, 200., 0, 0, 0, 0.] PelvisRotKd: [10, 0, 0, @@ -68,11 +68,11 @@ FlightFootW: 0, 100, 0, 0, 0, 10] FlightFootKp: - [250, 0, 0, - 0, 250, 0, - 0, 0, 250] + [125, 0, 0, + 0, 50, 0, + 0, 0, 150] FlightFootKd: - [10, 0, 0, - 0, 10, 0, - 0, 0, 10] + [2.5, 0, 0, + 0, 2.5, 0, + 0, 0, 0] From fe850a6ef26134e16062217babe8f25b4cc615f8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 20 Feb 2023 15:46:53 -0500 Subject: [PATCH 379/758] updating jumping parameter study --- .../jumping_parameter_study.py | 73 ++++++++++--------- 1 file changed, 38 insertions(+), 35 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py index 5e556eae9b..8d64b612ac 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -175,43 +175,45 @@ def main(): def construct_success_plot(): results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" - all_logs = sorted(glob.glob(results_folder + 'down_jump_4/' + 'lcmlog-*')) - landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - # nominal_delay = 0.025 # long + # nominal_delay = 0.040 # long nominal_delay = 0.055 # down # nominal_delay = 0.000 # jump landing_times += nominal_delay - 0.5 * 0.05 impact_thresholds = np.arange(0.000, 0.110, 0.010) - success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) - # xx, yy = np.meshgrid(landing_times, impact_thresholds) - for log_filename in all_logs: - landing_time = log_filename.split('_')[-3] - impact_threshold = log_filename.split('_')[-1] - default_channels = {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, - 'OSC_JUMPING': dairlib.lcmt_robot_input, - 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output} - callback = mbp_plots.load_default_channels - start_time = 4 - duration = -1 - plant, context = cassie_plots.make_plant_and_context( - floating_base=True, springs=True) - log = lcm.EventLog(log_filename, "r") - robot_output, robot_input, osc_debug = \ - get_log_data(log, default_channels, start_time, duration, callback, - plant, - 'CASSIE_STATE_SIMULATION', 'OSC_JUMPING', - 'OSC_DEBUG_JUMPING') - land_idx = int(np.round((float(landing_time) - (nominal_delay - 0.025)) / 0.005)) - print(landing_time) - impact_idx = int(np.round(float(impact_threshold)/0.010)) - print(land_idx) - print(impact_idx) - success[land_idx, impact_idx] = not np.any(robot_output['q'][:, 6] < 0.4) - np.save('down_jump_4_success', success) - plt.imshow(success) - plt.show() + + start_time = 4 + duration = -1 + default_channels = {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, + 'OSC_JUMPING': dairlib.lcmt_robot_input, + 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output} + callback = mbp_plots.load_default_channels + plant, context = cassie_plots.make_plant_and_context( + floating_base=True, springs=True) + for i in range(5): + all_logs = sorted(glob.glob(results_folder + 'down_jump_' + str(i) + '/lcmlog-*')) + success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) + # xx, yy = np.meshgrid(landing_times, impact_thresholds) + for log_filename in all_logs: + landing_time = log_filename.split('_')[-3] + impact_threshold = log_filename.split('_')[-1] + + log = lcm.EventLog(log_filename, "r") + robot_output, robot_input, osc_debug = \ + get_log_data(log, default_channels, start_time, duration, callback, + plant, + 'CASSIE_STATE_SIMULATION', 'OSC_JUMPING', + 'OSC_DEBUG_JUMPING') + land_idx = int(np.round((float(landing_time) - (nominal_delay - 0.025)) / 0.005)) + print(landing_time) + impact_idx = int(np.round(float(impact_threshold)/0.010)) + print(land_idx) + print(impact_idx) + success[land_idx, impact_idx] = not np.any(robot_output['q'][:, 6] < 0.4) + np.save('down_jump_' + str(i) + '_success', success) + # plt.imshow(success) + # plt.show() def plot_success(): landing_times = np.linspace(0.000, 0.050, 11) @@ -232,13 +234,14 @@ def plot_success(): cmap = matplotlib.colors.ListedColormap([ps.grey, ps.blue]) fig = plt.figure() # plt.imshow(total_success, cmap=cmap) - im = plt.imshow(total_success, cmap='Reds') + im = plt.imshow(total_success, cmap='Reds', interpolation='gaussian') + # im = plt.contour(total_success, cmap='Reds') plt.colorbar(im) plt.xlabel('Projection Window Duration (s)') plt.ylabel('Deviation from Nominal Transition Time (s)') ax = plt.gca() np.set_printoptions(precision=3) - ax.set_xticks(np.arange(0, 5, 1)) + ax.set_xticks(np.arange(0, 11, 1)) ax.set_yticks(np.arange(0, 11, 1)) ax.set_xticklabels(np.around(impact_thresholds, 3).tolist()) ax.set_yticklabels(np.around(landing_times, 3).tolist()) @@ -251,6 +254,6 @@ def plot_success(): plt.show() if __name__ == "__main__": - main() + # main() # construct_success_plot() - # plot_success() + plot_success() From ddcbd49f5556496bba26ce3ad07c0b1459b135f5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Feb 2023 15:28:20 -0500 Subject: [PATCH 380/758] updated param study to plot costs --- .../jumping_parameter_study.py | 165 +++++++++++++++--- .../plot_configs/cassie_jumping_plot.yaml | 14 +- .../contact_scheduler/contact_scheduler.cc | 2 +- .../osc_jump/osc_jumping_gains_down.yaml | 2 +- .../osc_jump/osc_jumping_gains_long.yaml | 2 +- 5 files changed, 154 insertions(+), 31 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py index 8d64b612ac..0d037a0ff3 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -27,12 +27,12 @@ def main(): parameter = "landing_delay" simulator = 'DRAKE' # trajectory_names = ['jump', 'box_jump', 'long_jump', 'down_jump'] - trajectory_names = ['long_jump'] + trajectory_names = ['down_jump'] gains_path = '' trajectory_name = '' results_folder = '' - delay_time = 2.0 - traj_time = 4.0 + delay_time = 1.0 + traj_time = 3.0 sim_time = 0 start_time = 0 if controller_type == 'jumping': @@ -42,12 +42,12 @@ def main(): landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - nominal_delay = 0.040 # long - # nominal_delay = 0.055 # down + # nominal_delay = 0.030 # long + nominal_delay = 0.030 # down # nominal_delay = 0.000 # jump # nominal_threshold = 0.000 # box - nominal_threshold = 0.000 # long - # nominal_threshold = 0.000 # down + # nominal_threshold = 0.000 # long + nominal_threshold = 0.000 # down # nominal_threshold = 0.000 # jump landing_times += nominal_delay - 0.5 * 0.05 # impact_thresholds = np.arange(0.000, 0.100, 0.025) @@ -173,13 +173,90 @@ def main(): parameter_file.close() +def convert_logs_to_costs(): + results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" + data_directory = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/data/" + + default_channels = {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, + 'OSC_JUMPING': dairlib.lcmt_robot_input, + 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output} + callback = mbp_plots.load_default_channels + plant, context = cassie_plots.make_plant_and_context( + floating_base=True, springs=True) + + nx = plant.num_positions() + plant.num_velocities() + nu = plant.num_actuators() + + osc_traj0 = "pelvis_trans_traj" + osc_traj1 = "left_ft_traj" + osc_traj2 = "right_ft_traj" + osc_traj3 = "pelvis_rot_traj" + + # nominal_delay = 0.040 # box + nominal_delay = 0.030 # long + # nominal_delay = 0.030 # down + # nominal_delay = 0.000 # jump + + # For full jumping traj + t_samples = 7500 + u_samples = 7500 + start_time = 0 + duration = -1 + landing_times = np.arange(0.000, 0.055, 0.005) + impact_thresholds = np.arange(0.000, 0.110, 0.010) + success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) + + t_matrix = np.zeros((landing_times.shape[0], impact_thresholds.shape[0], t_samples)) + # x_matrix = np.zeros((landing_times.shape[0], impact_thresholds.shape[0], t_samples, nx)) + t_u_matrix = np.zeros((landing_times.shape[0], impact_thresholds.shape[0], u_samples)) + u_matrix = np.zeros((landing_times.shape[0], impact_thresholds.shape[0], u_samples, nu)) + t_osc_matrix = np.zeros((landing_times.shape[0], impact_thresholds.shape[0], u_samples)) + tracking_cost = np.zeros((landing_times.shape[0], impact_thresholds.shape[0], u_samples)) + + trial_name = 'long_jump_4' + all_logs = sorted(glob.glob(results_folder + trial_name + '/lcmlog-*')) + success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) + # xx, yy = np.meshgrid(landing_times, impact_thresholds) + for log_filename in all_logs: + landing_time = log_filename.split('_')[-3] + impact_threshold = log_filename.split('_')[-1] + land_idx = int(np.round((float(landing_time) - (nominal_delay - 0.025)) / 0.005)) + impact_idx = int(np.round(float(impact_threshold)/0.010)) + print(land_idx) + print(impact_idx) + + log = lcm.EventLog(log_filename, "r") + robot_output, robot_input, osc_debug = \ + get_log_data(log, default_channels, start_time, duration, callback, + plant, + 'CASSIE_STATE_SIMULATION', 'OSC_JUMPING', + 'OSC_DEBUG_JUMPING') + + t_matrix[land_idx, impact_idx, :] = robot_output['t_x'][:t_samples] + # x_matrix[land_idx, impact_idx, :, :] = robot_output['q'][:t_samples] + t_u_matrix[land_idx, impact_idx, :] = robot_input['t_u'][:u_samples] + u_matrix[land_idx, impact_idx, :, :] = robot_input['u'][:u_samples] + t_osc_matrix[land_idx, impact_idx, :] = osc_debug['t_osc'][:u_samples] + tracking_cost[land_idx, impact_idx, :] = osc_debug['tracking_cost'][osc_traj0][:u_samples] + tracking_cost[land_idx, impact_idx, :] += osc_debug['tracking_cost'][osc_traj1][:u_samples] + tracking_cost[land_idx, impact_idx, :] += osc_debug['tracking_cost'][osc_traj2][:u_samples] + tracking_cost[land_idx, impact_idx, :] += osc_debug['tracking_cost'][osc_traj3][:u_samples] + + np.save(data_directory + trial_name + '/t_u', t_u_matrix) + np.save(data_directory + trial_name + '/u', u_matrix) + np.save(data_directory + trial_name + '/t_osc', t_osc_matrix) + np.save(data_directory + trial_name + '/tracking_cost', tracking_cost) + return + def construct_success_plot(): results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" landing_times = np.arange(0.000, 0.055, 0.005) # nominal_delay = 0.040 # box - # nominal_delay = 0.040 # long - nominal_delay = 0.055 # down + # nominal_delay = 0.030 # long + nominal_delay = 0.030 # down # nominal_delay = 0.000 # jump + # trial_name = 'down_jump_' + trial_name = 'long_jump_' landing_times += nominal_delay - 0.5 * 0.05 impact_thresholds = np.arange(0.000, 0.110, 0.010) @@ -192,9 +269,8 @@ def construct_success_plot(): plant, context = cassie_plots.make_plant_and_context( floating_base=True, springs=True) for i in range(5): - all_logs = sorted(glob.glob(results_folder + 'down_jump_' + str(i) + '/lcmlog-*')) + all_logs = sorted(glob.glob(results_folder + trial_name + str(i) + '/lcmlog-*')) success = np.zeros((landing_times.shape[0], impact_thresholds.shape[0])) - # xx, yy = np.meshgrid(landing_times, impact_thresholds) for log_filename in all_logs: landing_time = log_filename.split('_')[-3] impact_threshold = log_filename.split('_')[-1] @@ -211,21 +287,20 @@ def construct_success_plot(): print(land_idx) print(impact_idx) success[land_idx, impact_idx] = not np.any(robot_output['q'][:, 6] < 0.4) - np.save('down_jump_' + str(i) + '_success', success) - # plt.imshow(success) - # plt.show() + np.save(trial_name + str(i) + '_success', success) def plot_success(): + trial_name = 'down_jump_' landing_times = np.linspace(0.000, 0.050, 11) landing_times -= 0.025 impact_thresholds = np.linspace(0.000, 0.100, 11) # success = np.load('long_jump_0_success.npy') - success = np.load('down_jump_0_success.npy') + success = np.load(trial_name + '0_success.npy') total_success = np.zeros(success.shape) total_success += success for i in range(1, 5): - # success = np.load('long_jump_' + str(i) + '_success.npy') - success = np.load('down_jump_' + str(i) + '_success.npy') + success = np.load(trial_name + str(i) + '_success.npy') + # success = np.load('down_jump_' + str(i) + '_success.npy') total_success += success # plt.imshow(success, cmap='tab20') @@ -234,7 +309,7 @@ def plot_success(): cmap = matplotlib.colors.ListedColormap([ps.grey, ps.blue]) fig = plt.figure() # plt.imshow(total_success, cmap=cmap) - im = plt.imshow(total_success, cmap='Reds', interpolation='gaussian') + im = plt.imshow(total_success, cmap='Reds') # im = plt.contour(total_success, cmap='Reds') plt.colorbar(im) plt.xlabel('Projection Window Duration (s)') @@ -249,11 +324,59 @@ def plot_success(): # legend_elements = [Patch(facecolor=ps.grey, alpha=0.7, label='Fail'), Patch(facecolor=ps.blue, alpha=0.7, label='Success')] # legend = ax.legend(handles=legend_elements, loc=1) - # plt.savefig('long_jump_success.png', dpi=240) - plt.savefig('down_jump_success.png', dpi=240) + plt.savefig(trial_name + 'success.png', dpi=240) + # plt.savefig('down_jump_success.png', dpi=240) + plt.show() + +def plot_costs(): + landing_times = np.linspace(0.000, 0.050, 11) + landing_times -= 0.025 + impact_thresholds = np.linspace(0.000, 0.100, 11) + results_folder = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/" + data_directory = "/media/yangwill/backups/home/yangwill/Documents/research/projects/cassie/sim/jumping/logs/2023/param_study/data/" + t_u_matrix = np.load(data_directory + 'long_jump_0' + '/t_u.npy') + u_cost = np.zeros((t_u_matrix.shape[0], t_u_matrix.shape[1])) + u_slice = slice(3000, 7000) + w_u = np.array([0.5, 0.9, 0.5, 0.1, 0.1, 0.5, 0.9, 0.5, 0.1, 0.1]) + W_u = np.diag(w_u) + trial_name = 'down_jump_' + for num in range(5): + exp_name = trial_name + str(num) + success = np.load(exp_name + '_success.npy') + t_u_matrix = np.load(data_directory + exp_name + '/t_u.npy') + u_matrix = np.load(data_directory + exp_name + '/u.npy') + t_osc_matrix = np.load(data_directory + exp_name + '/t_osc.npy') + tracking_cost = np.load(data_directory + exp_name + '/tracking_cost.npy') + u_cost_exp = np.zeros((t_u_matrix.shape[0], t_u_matrix.shape[1])) + for i in range(t_u_matrix.shape[0]): + for j in range(t_u_matrix.shape[1]): + # for t in range(t_u_matrix.shape[2] - 1): + for t in range(3000, 7000): + # print((u_matrix[i, j, t, :].T @ u_matrix[i, j, t, :])) + u_cost_exp[i, j] += (t_u_matrix[i, j, t+1] - t_u_matrix[i, j, t]) * (u_matrix[i, j, t, :].T @ W_u @ u_matrix[i, j, t, :]) + fail_bool = np.array(1 - success, dtype=bool) + u_cost_exp[u_cost_exp > 20000] = 20000 + u_cost_exp[fail_bool] = 25000 * np.ones(u_cost.shape)[fail_bool] + u_cost += u_cost_exp + # u_cost[u_cost > 3] = 3 + # u_cost[u_cost < 2.7] = 2.7 + im = plt.imshow(8e-6 * u_cost) + plt.colorbar(im) + plt.xlabel('Projection Window Duration (s)') + plt.ylabel('Deviation from Nominal Transition Time (s)') + ax = plt.gca() + np.set_printoptions(precision=3) + ax.set_xticks(np.arange(0, 11, 1)) + ax.set_yticks(np.arange(0, 11, 1)) + ax.set_xticklabels(np.around(impact_thresholds, 3).tolist()) + ax.set_yticklabels(np.around(landing_times, 3).tolist()) + ax.grid(which="minor", color='k', linestyle='-', linewidth=2) + plt.savefig(trial_name + 'cost.png', dpi=240) plt.show() if __name__ == "__main__": # main() # construct_success_plot() - plot_success() + # convert_logs_to_costs() + # plot_success() + plot_costs() diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 2b98eb9e87..00f746b39a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -1,10 +1,10 @@ # LCM channels to read data from -channel_x: "CASSIE_STATE_DISPATCHER" -#channel_x: "CASSIE_STATE_SIMULATION" +#channel_x: "CASSIE_STATE_DISPATCHER" +channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_JUMPING" channel_osc: "OSC_DEBUG_JUMPING" use_archived_lcmtypes: false -use_default_styling: true +use_default_styling: false # Log time to stop at (seconds, -1 for whole log) start_time: 0 @@ -15,12 +15,12 @@ use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false +plot_floating_base_positions: true plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: false +plot_measured_efforts: true plot_commanded_efforts: false plot_contact_forces: false special_positions_to_plot: [ 'hip_pitch_left'] @@ -40,11 +40,11 @@ pt_on_foot_to_plot: ['front', 'rear'] # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_qp_solve_time: false -plot_qp_solutions: true +plot_qp_solutions: false plot_tracking_costs: true plot_active_tracking_datas: false tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, +# pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 8fb27b700c..d7e5c3e2a1 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -177,7 +177,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( // Store the ground height of the stance foot // TODO(yangwill): calculate end of stance duration - double stance_scale = (rest_length_) / (pelvis_z); + double stance_scale = (pelvis_z)/ (rest_length_); stance_scale = std::clamp(stance_scale, 1 - stance_variance_, 1 + stance_variance_); double next_transition_time = diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml index 72915406b7..45248c3d7a 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml @@ -36,7 +36,7 @@ min_pelvis_acc: -3.5 max_pelvis_acc: 10000 impact_threshold: 0.000 impact_tau: 0.005 -landing_delay: 0.055 +landing_delay: 0.030 #landing_delay: 0. CoMW: diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml index aabe377b76..c943217c2e 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml @@ -36,7 +36,7 @@ min_pelvis_acc: -8 max_pelvis_acc: 10000 impact_threshold: 0.000 impact_tau: 0.005 -landing_delay: 0.025 +landing_delay: 0.030 #landing_delay: 0. CoMW: From 1c774d81976f2b1a7d8448f86b5b28da42197348 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 28 Feb 2023 15:34:11 -0500 Subject: [PATCH 381/758] committing plotting changes --- .../jumping_parameter_study.py | 31 ++++++++++++++----- .../pydairlib/analysis/log_plotter_cassie.py | 4 +-- .../plot_configs/cassie_jumping_plot.yaml | 20 ++++++------ .../plot_configs/cassie_running_plot.yaml | 8 ++--- bindings/pydairlib/common/plot_styler.py | 2 +- examples/Cassie/cassie_xbox_remote.py | 4 +-- 6 files changed, 42 insertions(+), 27 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py index 0d037a0ff3..081fc1ffbb 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/jumping_parameter_study.py @@ -1,5 +1,6 @@ import subprocess import time +from tqdm import * import lcm import matplotlib.pyplot as plt from matplotlib.patches import Patch @@ -290,7 +291,7 @@ def construct_success_plot(): np.save(trial_name + str(i) + '_success', success) def plot_success(): - trial_name = 'down_jump_' + trial_name = 'long_jump_' landing_times = np.linspace(0.000, 0.050, 11) landing_times -= 0.025 impact_thresholds = np.linspace(0.000, 0.100, 11) @@ -307,7 +308,7 @@ def plot_success(): ps = plot_styler.PlotStyler() plot_styler.PlotStyler.set_default_styling() cmap = matplotlib.colors.ListedColormap([ps.grey, ps.blue]) - fig = plt.figure() + # plt.imshow(total_success, cmap=cmap) im = plt.imshow(total_success, cmap='Reds') # im = plt.contour(total_success, cmap='Reds') @@ -339,8 +340,9 @@ def plot_costs(): u_slice = slice(3000, 7000) w_u = np.array([0.5, 0.9, 0.5, 0.1, 0.1, 0.5, 0.9, 0.5, 0.1, 0.1]) W_u = np.diag(w_u) - trial_name = 'down_jump_' - for num in range(5): + fails = np.zeros(u_cost.shape) + trial_name = 'long_jump_' + for num in trange(5): exp_name = trial_name + str(num) success = np.load(exp_name + '_success.npy') t_u_matrix = np.load(data_directory + exp_name + '/t_u.npy') @@ -355,15 +357,28 @@ def plot_costs(): # print((u_matrix[i, j, t, :].T @ u_matrix[i, j, t, :])) u_cost_exp[i, j] += (t_u_matrix[i, j, t+1] - t_u_matrix[i, j, t]) * (u_matrix[i, j, t, :].T @ W_u @ u_matrix[i, j, t, :]) fail_bool = np.array(1 - success, dtype=bool) - u_cost_exp[u_cost_exp > 20000] = 20000 - u_cost_exp[fail_bool] = 25000 * np.ones(u_cost.shape)[fail_bool] + fails += fail_bool + # u_cost_exp[u_cost_exp > 20000] = 20000 + # u_cost_exp[fail_bool] = 25000 * np.ones(u_cost.shape)[fail_bool] u_cost += u_cost_exp # u_cost[u_cost > 3] = 3 # u_cost[u_cost < 2.7] = 2.7 - im = plt.imshow(8e-6 * u_cost) - plt.colorbar(im) + + u_cost *= 8e-6 / .5801 + # u_cost[u_cost > 1] = 1 + u_cost[fails >= 2] = -1 + u_cost_masked = np.ma.masked_where(u_cost == -1, u_cost) + cmap = plt.get_cmap('Blues') + cmap.set_bad(color='black') + im = plt.imshow(u_cost_masked, cmap=cmap) + ax = plt.gca() + legend_elements = [Patch(facecolor='black', alpha=1.0, label='Fail')] + legend = ax.legend(handles=legend_elements, loc=1) + cbar = plt.colorbar(im) + # im = plt.imshow(u_cost, cmap=cmap) plt.xlabel('Projection Window Duration (s)') plt.ylabel('Deviation from Nominal Transition Time (s)') + cbar.set_label('Normalized Controller Effort Cost') ax = plt.gca() np.set_printoptions(precision=3) ax.set_xticks(np.arange(0, 11, 1)) diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index 0666359f35..f7bb75e3a2 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -11,11 +11,11 @@ def main(): - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) use_floating_base = plot_config.use_floating_base diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml index 00f746b39a..20dd4a5740 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml @@ -1,26 +1,26 @@ # LCM channels to read data from -#channel_x: "CASSIE_STATE_DISPATCHER" -channel_x: "CASSIE_STATE_SIMULATION" +channel_x: "CASSIE_STATE_DISPATCHER" +#channel_x: "CASSIE_STATE_SIMULATION" channel_u: "OSC_JUMPING" channel_osc: "OSC_DEBUG_JUMPING" use_archived_lcmtypes: false -use_default_styling: false +use_default_styling: true # Log time to stop at (seconds, -1 for whole log) -start_time: 0 -duration: -1 +start_time: 18.47 +duration: 1.5 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: true +plot_floating_base_positions: false plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: false plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: true +plot_measured_efforts: false plot_commanded_efforts: false plot_contact_forces: false special_positions_to_plot: [ 'hip_pitch_left'] @@ -40,11 +40,11 @@ pt_on_foot_to_plot: ['front', 'rear'] # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_qp_solve_time: false -plot_qp_solutions: false +plot_qp_solutions: true plot_tracking_costs: true -plot_active_tracking_datas: false +plot_active_tracking_datas: true tracking_datas_to_plot: { -# pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, + pelvis_trans_traj: { 'dims': [ 0, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, # pelvis_rot_traj: {'dims': [0, 1], 'derivs': ['vel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 233315560b..8173c1ff7a 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -7,9 +7,9 @@ use_archived_lcmtypes: false use_default_styling: true # Log time to stop at (seconds, -1 for whole log) -start_time: 0.76 +start_time: 2 #duration: 0.47 -duration: 1.58 +duration: -1 # Plant properties use_springs: true @@ -18,7 +18,7 @@ use_floating_base: true # Desired RobotOutput plots plot_floating_base_positions: false plot_floating_base_velocities: false -plot_floating_base_velocity_body_frame: false +plot_floating_base_velocity_body_frame: true plot_joint_positions: false plot_joint_velocities: false plot_measured_efforts: false @@ -44,7 +44,7 @@ plot_qp_costs: false plot_qp_solve_time: false plot_qp_solutions: false plot_tracking_costs: false -plot_active_tracking_datas: true +plot_active_tracking_datas: false tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos'] }, diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index cc6a6b3711..6dc1c9503b 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -14,7 +14,7 @@ def set_default_styling(): # matplotlib.rcParams['figure.figsize'] = 20, 6 matplotlib.rcParams['figure.figsize'] = 8, 6 matplotlib.rcParams['figure.autolayout'] = True - font = {'size': 16} + font = {'size': 20} matplotlib.rc('font', **font) matplotlib.rcParams['lines.linewidth'] = 2 plt.set_cmap('tab20') diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 3bf97318d2..0beef309d9 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -66,8 +66,8 @@ def main(): joystick.init() done = False - max_speed = 1.0 - ramp_up = np.arange(0, max_speed, 0.01) + max_speed = 2.6 + ramp_up = np.arange(0, max_speed, 0.03) stay = max_speed * np.ones(125) ramp_down = np.flip(np.arange(0, max_speed, 0.01)) speeds = np.hstack((ramp_up, stay, ramp_down)) From e38ae3ce7659647a9907ddf3e7a5d8c412a8803c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Mar 2023 12:24:28 -0500 Subject: [PATCH 382/758] final sim visualization --- .../visualization/visualize_configs/down_jump.yaml | 2 +- .../lcm/visualization/visualize_configs/jump.yaml | 4 ++-- .../lcm/visualization/visualize_trajectory.py | 10 +++++----- examples/Cassie/cassie_xbox_remote.py | 2 +- examples/Cassie/director_scripts/show_time_sim.py | 7 ++++--- examples/Cassie/multibody_sim_w_platform.cc | 2 +- .../Cassie/osc_jump/osc_jumping_gains_down.yaml | 12 ++++++------ .../Cassie/osc_jump/osc_jumping_gains_long.yaml | 14 +++++++------- examples/Cassie/visualizer.cc | 2 +- examples/impact_invariant_control/platform.urdf | 4 ++-- 10 files changed, 30 insertions(+), 29 deletions(-) diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml index 044a719068..ef9ceccbae 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml @@ -2,7 +2,7 @@ filename: examples/Cassie/saved_trajectories/down_jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf visualize_mode: 1 -realtime_rate: 0.1 +realtime_rate: 0.5 num_poses: 9 use_transparency: 1 use_springs: 1 \ No newline at end of file diff --git a/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml b/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml index 5fc2823e5a..1a15588279 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml +++ b/bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml @@ -1,7 +1,7 @@ -filename: examples/Cassie/saved_trajectories/jumping_0.15h_0.3d +filename: examples/Cassie/saved_trajectories/jump spring_urdf: examples/Cassie/urdf/cassie_v2_shells.urdf fixed_spring_urdf: examples/Cassie/urdf/cassie_fixed_springs.urdf -visualize_mode: 2 +visualize_mode: 1 realtime_rate: 0.5 num_poses: 5 use_transparency: 1 diff --git a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py index 67c3e15fe4..3827d2dc02 100644 --- a/bindings/pydairlib/lcm/visualization/visualize_trajectory.py +++ b/bindings/pydairlib/lcm/visualization/visualize_trajectory.py @@ -18,10 +18,10 @@ def main(): - visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' + # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/long_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/box_jump.yaml' # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/down_jump.yaml' - # visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' + visualization_config_file = 'bindings/pydairlib/lcm/visualization/visualize_configs/jump.yaml' params = DirconVisualizationParams(visualization_config_file) builder = DiagramBuilder() @@ -96,7 +96,7 @@ def main(): for i in range(params.num_poses): poses[i] = optimal_traj.value( t_vec[int(i * len(t_vec) / params.num_poses)])[:, 0] - # poses[i, 6] += 0.5 + poses[i, 6] += 0.5 # alpha_scale = np.linspace(0.2, 1.0, params.num_poses) alpha_scale = np.linspace(1.0, 1.0, params.num_poses) visualizer = MultiposeVisualizer(FindResourceOrThrow( @@ -114,8 +114,8 @@ def main(): translation = np.array([0.5, 0, 0.25]) origin = RigidTransform(translation) box = Box(0.5, 1.0, 0.5) - # visualizer.GetMeshcat().SetObject("box", box) - # visualizer.GetMeshcat().SetTransform("box", origin) + visualizer.GetMeshcat().SetObject("box", box) + visualizer.GetMeshcat().SetTransform("box", origin) visualizer.GetMeshcat().SetCamera(ortho_camera) visualizer.DrawPoses(poses.T) while(True): diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 0beef309d9..6cf34da7e2 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -66,7 +66,7 @@ def main(): joystick.init() done = False - max_speed = 2.6 + max_speed = 1.6 ramp_up = np.arange(0, max_speed, 0.03) stay = max_speed * np.ones(125) ramp_down = np.flip(np.arange(0, max_speed, 0.01)) diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 3d66a52c6e..227736a25d 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -21,8 +21,8 @@ def __init__(self): self.text_time.setProperty('Font Size', 36) self.text_time.setProperty('Bold', True) self.set_enabled(True) - gridObj.setProperty('Grid Half Width', 100) - gridObj.setProperty('Major Tick Resolution', 100) + gridObj.setProperty('Grid Half Width', 50) + gridObj.setProperty('Major Tick Resolution', 50) def add_subscriber(self): if (self._subscriber is not None): @@ -71,6 +71,7 @@ def handle_message(self, msg): pelvis_height_text = 'pelvis height: %.3f' % pelvis_height pelvis_velocity_text = 'pelvis velocity: %.3f' % np.array(self._pelvis_velocity).mean() + # pelvis_position_text = 'forward position: %.3f' % np.array(msg.position[4]).mean() realtime_text = '' if (len(self._real_time) >= self._num_msg_for_average): @@ -87,7 +88,7 @@ def handle_message(self, msg): # my_text = my_text + ', real time factor: %.2f' % rt_ratio # vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text, 'text') - self.text_time.setProperty('Text', my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text) + self.text_time.setProperty('Text', my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text + '\n' + realtime_text) # vis.updateText(my_text + '\n' + pelvis_velocity_text, 'text') diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index fe53534a44..fb102758c8 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -112,7 +112,7 @@ int do_main(int argc, char* argv[]) { FindResourceOrThrow("examples/impact_invariant_control/platform.urdf"); parser.AddModelFromFile(terrain_name); Eigen::Vector3d offset; - offset << FLAGS_platform_x, 0, FLAGS_platform_height; + offset << FLAGS_platform_x, 0, 0.25 + FLAGS_platform_height; plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform(offset)); } diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml index 45248c3d7a..333ece9911 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains_down.yaml @@ -18,7 +18,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: -0.03 +crouch_x_offset: -0.01 land_x_offset: 0.00 relative_feet: true @@ -32,11 +32,11 @@ w_hip_yaw: 100 hip_yaw_kp: 100 hip_yaw_kd: 10 -min_pelvis_acc: -3.5 +min_pelvis_acc: -7 max_pelvis_acc: 10000 -impact_threshold: 0.000 +impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.030 +landing_delay: 0.070 #landing_delay: 0. CoMW: @@ -56,8 +56,8 @@ PelvisRotW: 0, 5, 0, 0, 0, 1] PelvisRotKp: - [150., 0, 0, - 0, 200., 0, + [500., 0, 0, + 0, 750., 0, 0, 0, 0.] PelvisRotKd: [10, 0, 0, diff --git a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml index c943217c2e..85ab3baeef 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains_long.yaml @@ -18,7 +18,7 @@ W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] w_input_reg: 0.01 w_soft_constraint: 1000 -crouch_x_offset: -0.04 +crouch_x_offset: -0.033 land_x_offset: 0.00 relative_feet: true @@ -34,9 +34,9 @@ hip_yaw_kd: 5 min_pelvis_acc: -8 max_pelvis_acc: 10000 -impact_threshold: 0.000 +impact_threshold: 0.050 impact_tau: 0.005 -landing_delay: 0.030 +landing_delay: 0.03 #landing_delay: 0. CoMW: @@ -56,12 +56,12 @@ PelvisRotW: 0, 5, 0, 0, 0, 1] PelvisRotKp: - [150., 0, 0, - 0, 200., 0, + [200., 0, 0, + 0, 500., 0, 0, 0, 0.] PelvisRotKd: - [10, 0, 0, - 0, 10, 0, + [20, 0, 0, + 0, 25, 0, 0, 0, 5.] FlightFootW: [10, 0, 0, diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 726eda240a..0f7a0d1e9d 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -56,7 +56,7 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); - AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, "examples/Cassie/urdf/cassie_v2_shells.urdf"); + AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, "examples/Cassie/urdf/cassie_v2.urdf"); if (FLAGS_floating_base) { // Ground direction Eigen::Vector3d ground_normal(sin(FLAGS_ground_incline), 0, diff --git a/examples/impact_invariant_control/platform.urdf b/examples/impact_invariant_control/platform.urdf index e8476dcaa6..dc71d2af32 100644 --- a/examples/impact_invariant_control/platform.urdf +++ b/examples/impact_invariant_control/platform.urdf @@ -5,7 +5,7 @@ - + @@ -14,7 +14,7 @@ - + From 176e4a01236d8d44f30a9993310b1019f131ef44 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Mar 2023 10:12:20 -0500 Subject: [PATCH 383/758] working on a more stable standing controller --- examples/Cassie/osc/osc_standing_gains.h | 2 +- examples/Cassie/osc/osc_standing_gains.yaml | 8 ++-- .../Cassie/osc/osc_standing_gains_sim.yaml | 48 +++++++++---------- examples/Cassie/osc/standing_com_traj.cc | 10 ++-- .../Cassie/run_osc_standing_controller.cc | 45 ++++++++--------- solvers/default_osc_osqp_settings.yaml | 6 +-- 6 files changed, 59 insertions(+), 60 deletions(-) diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h index a6a832fecb..a89b0c5cfa 100644 --- a/examples/Cassie/osc/osc_standing_gains.h +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -81,6 +81,6 @@ struct OSCStandingGains : OSCGains { w_soft_constraint *= weight_scaling; W_pelvis_rot *= weight_scaling; W_pelvis *= weight_scaling; - W_pelvis_rot *= weight_scaling; W_hip_yaw *= weight_scaling; + W_hip_yaw *= weight_scaling; } }; diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 957d497ea2..1cb9a36abb 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -11,7 +11,7 @@ rows: 3 cols: 3 w_input: 0.0 w_accel: 0.001 -w_lambda: 0.000000 +w_lambda: 0.00001 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, # 1, 1, 1, 1, 0.01, 0.001 ] @@ -30,9 +30,9 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, w_soft_constraint: 100 w_input_reg: 0.00 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.001 -rot_filter_tau: 0.05 -center_of_mass_command_filter_alpha: 0.05 +center_of_mass_filter_tau: 0.000 +rot_filter_tau: 0.00 +center_of_mass_command_filter_alpha: 0.01 orientation_command_filter_alpha: 0.0005 impact_tau: 0.00 mu: 0.6 diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index 0f1d60a8ef..899cfec69e 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -7,60 +7,60 @@ # Kp = sqrt(g/l) * Kd - g/l controller_frequency: 1000 -w_input: 0.0 -w_accel: 0.000 -w_lambda: 0.000000 +w_input: 0.000001 +w_accel: 0.000001 +w_lambda: 0.000001 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, # 1, 1, 1, 1, 0.01, 0.001 ] W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] -W_input_reg: [ 1, 0.9, 0.6, 0.3, 5, - 1, 0.9, 0.5, 0.1, 5 ] +W_input_reg: [ 1, 0.9, 0.5, 0.3, 1, + 1, 0.9, 0.5, 0.3, 1 ] W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01 ] + 1, 0.001, 0.01, + 1, 0.001, 0.01 ] #W_lambda_h_reg: [ 0.02, 0.02 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] -w_soft_constraint: 0 -w_input_reg: 0.00 +w_soft_constraint: 1000 +w_input_reg: 0.00001 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.0001 -rot_filter_tau: 0.001 -center_of_mass_command_filter_alpha: 0.05 -orientation_command_filter_alpha: 0.0005 +center_of_mass_filter_tau: 0.000 +rot_filter_tau: 0.000 +center_of_mass_command_filter_alpha: 1.0 +orientation_command_filter_alpha: 1.0 impact_tau: 0.00 mu: 0.6 weight_scaling: 1.0 -HipYawKp: 40 +HipYawKp: 100 HipYawKd: 5 -HipYawW: 0 +HipYawW: 2.5 PelvisW: - [ 1, 0, 0, + [ 5, 0, 0, 0, 2, 0, 0, 0, 2 ] PelvisKp: - [ 50, 0, 0, + [ 40, 0, 0, 0, 50, 0, 0, 0, 75 ] PelvisKd: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 10 ] + [ 7.5, 0, 0, + 0, 5, 0, + 0, 0, 5] PelvisRotW: [ 5, 0, 0, 0, 5, 0, - 0, 0, 1 ] + 0, 0, 10 ] PelvisRotKp: - [ 25, 0, 0, - 0, 75, 0, + [150., 0, 0, + 0, 200., 0, 0, 0, 50 ] PelvisRotKd: [ 10, 0, 0, 0, 10, 0, - 0, 0, 10 ] + 0, 0, 5 ] diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index 545f187bff..44e5267e85 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -35,7 +35,6 @@ StandingComTraj::StandingComTraj( feet_contact_points_(feet_contact_points), height_(height), set_target_height_by_radio_(set_target_height_by_radio) { - target_pos_filter_ = std::make_unique(1.0, 3); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( @@ -122,9 +121,9 @@ void StandingComTraj::CalcDesiredTraj( right_toe_position + right_heel_position) / 4; // } - // double mid_point_x = ((left_toe_position[0] - left_heel_position[0]) + - // (right_toe_position[0] - right_heel_position[0])) / - // 2; + double mid_point_x = (left_toe_position[0] + right_toe_position[0] + + right_heel_position[0] - 3 * left_heel_position[0]) / + 6; double mid_point_y = ((left_toe_position[1] - right_toe_position[1]) + (left_heel_position[1] - right_heel_position[1])) / 4; @@ -144,12 +143,11 @@ void StandingComTraj::CalcDesiredTraj( // Desired com pos Vector3d desired_com_pos_offset; - desired_com_pos_offset << 0.04, -mid_point_y, contact_pos_sum(2); + desired_com_pos_offset << mid_point_x - 0.02, -mid_point_y, 0; Vector3d desired_com_pos = desired_com_pos_offset + target_pos; target_pos_filter_->Update(desired_com_pos); - // Assign traj PiecewisePolynomial* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 25f7d77211..005586575c 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -168,12 +168,7 @@ int DoMain(int argc, char* argv[]) { auto osc = builder.AddSystem( plant, plant, context_w_spr.get(), context_w_spr.get(), false); - // Distance constraint multibody::KinematicEvaluatorSet evaluators(plant); - auto left_loop = LeftLoopClosureEvaluator(plant); - auto right_loop = RightLoopClosureEvaluator(plant); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); // Fix the springs in the dynamics auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); @@ -184,17 +179,22 @@ int DoMain(int argc, char* argv[]) { auto right_fixed_knee_spring = FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), vel_idx_map.at("knee_joint_rightdot"), 0); - auto left_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), - vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - auto right_fixed_ankle_spring = - FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), - vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + auto left_fixed_ankle_spring = FixedJointEvaluator( + plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = FixedJointEvaluator( + plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); evaluators.add_evaluator(&left_fixed_knee_spring); evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + osc->AddKinematicConstraint(&evaluators); // Friction coefficient @@ -241,19 +241,20 @@ int DoMain(int argc, char* argv[]) { "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); - if (osc_gains.center_of_mass_filter_tau > 0) { - pelvis_trans_rel_tracking_data->SetLowPassFilter( - osc_gains.center_of_mass_filter_tau, {0, 1, 2}); - } +// if (osc_gains.center_of_mass_filter_tau > 0) { +// pelvis_trans_rel_tracking_data->SetLowPassFilter( +// osc_gains.center_of_mass_filter_tau, {0, 1, 2}); +// } pelvis_trans_rel_tracking_data->SetViewFrame(pelvis_view_frame); auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); +// pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); pelvis_rot_tracking_data->AddFrameToTrack("pelvis"); - if (osc_gains.rot_filter_tau > 0) { - pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, - {0, 1, 2}); - } +// if (osc_gains.rot_filter_tau > 0) { +// pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, +// {0, 1, 2}); +// } osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); @@ -265,8 +266,8 @@ int DoMain(int argc, char* argv[]) { osc_gains.W_hip_yaw, plant, plant); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); - right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); - osc->AddConstTrackingData(std::move(right_hip_yaw_traj), VectorXd::Zero(1)); +// right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); +// osc->AddConstTrackingData(std::move(right_hip_yaw_traj), VectorXd::Zero(1)); // Build OSC problem osc->Build(); @@ -283,7 +284,7 @@ int DoMain(int argc, char* argv[]) { // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc standing controller")); + owned_diagram->set_name(("osc_standing_controller")); // Build lcm-driven simulation systems::LcmDrivenLoop loop( diff --git a/solvers/default_osc_osqp_settings.yaml b/solvers/default_osc_osqp_settings.yaml index 7e854f7779..132e5afa05 100644 --- a/solvers/default_osc_osqp_settings.yaml +++ b/solvers/default_osc_osqp_settings.yaml @@ -1,4 +1,4 @@ -rho: 0.0001 +rho: 0.001 sigma: 1e-6 max_iter: 1000 eps_abs: 1e-7 @@ -14,9 +14,9 @@ verbose: 0 scaled_termination: 1 check_termination: 25 warm_start: 1 -scaling: 10 +scaling: 1 adaptive_rho: 1 adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 -time_limit: 0.0 +time_limit: 0 From c0e672e26512ddc5c57148dfeddac6d7b2f52ce9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Mar 2023 12:56:44 -0500 Subject: [PATCH 384/758] fixing contact force regularization for controllers that don't use impact projection --- examples/Cassie/cassie_xbox_remote.py | 2 +- examples/Cassie/osc/osc_standing_gains.yaml | 1 - examples/Cassie/osc/osc_standing_gains_sim.yaml | 6 +++--- examples/Cassie/run_osc_standing_controller.cc | 13 ++++++++----- .../controllers/osc/operational_space_control.cc | 12 ++++++++---- 5 files changed, 20 insertions(+), 14 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 6cf34da7e2..4063f068a9 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -112,7 +112,7 @@ def main(): # Send LCM message radio_msg = dairlib.lcmt_radio_out() - radio_msg.channel[0] = speeds[i] + # radio_msg.channel[0] = speeds[i] radio_msg.channel[1] = joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(4) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 1cb9a36abb..6e610120a3 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -24,7 +24,6 @@ W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01 ] -#W_lambda_h_reg: [ 0.02, 0.02 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] w_soft_constraint: 100 diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index 899cfec69e..332befbc59 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -9,7 +9,7 @@ controller_frequency: 1000 w_input: 0.000001 w_accel: 0.000001 -w_lambda: 0.000001 +w_lambda: 0.01 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, # 1, 1, 1, 1, 0.01, 0.001 ] @@ -28,7 +28,7 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, w_soft_constraint: 1000 w_input_reg: 0.00001 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.000 +center_of_mass_filter_tau: 0.00 rot_filter_tau: 0.000 center_of_mass_command_filter_alpha: 1.0 orientation_command_filter_alpha: 1.0 @@ -43,7 +43,7 @@ PelvisW: 0, 2, 0, 0, 0, 2 ] PelvisKp: - [ 40, 0, 0, + [ 20, 0, 0, 0, 50, 0, 0, 0, 75 ] PelvisKd: diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 005586575c..181809c2b8 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -223,9 +223,12 @@ int DoMain(int argc, char* argv[]) { osc->SetInputSmoothingCostWeights(gains.w_input_reg * gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight( + osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * gains.W_lambda_h_regularization); - osc->SetJointLimitWeight(1.0); + osc->SetContactSoftConstraintWeight(osc_gains.w_soft_constraint); +// osc->SetJointLimitWeight(osc_gains.w_joint_limit); auto pelvis_view_frame = std::make_shared>(plant.GetBodyByName("pelvis")); auto pelvis_tracking_data = std::make_unique( @@ -241,10 +244,10 @@ int DoMain(int argc, char* argv[]) { "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); -// if (osc_gains.center_of_mass_filter_tau > 0) { -// pelvis_trans_rel_tracking_data->SetLowPassFilter( -// osc_gains.center_of_mass_filter_tau, {0, 1, 2}); -// } + if (osc_gains.center_of_mass_filter_tau > 0) { + pelvis_trans_rel_tracking_data->SetLowPassFilter( + osc_gains.center_of_mass_filter_tau, {0, 1, 2}); + } pelvis_trans_rel_tracking_data->SetViewFrame(pelvis_view_frame); auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index b17dfcfa19..503c4cafa3 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -774,13 +774,17 @@ VectorXd OperationalSpaceControl::SolveQp( } if (W_lambda_c_reg_.size() > 0) { - lambda_c_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, - VectorXd::Zero(n_c_)); + if (fsm_state != -1){ + lambda_c_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, + VectorXd::Zero(n_c_)); + } } if (W_lambda_h_reg_.size() > 0) { - lambda_h_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, - VectorXd::Zero(n_h_)); + if (fsm_state != -1){ + lambda_h_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, + VectorXd::Zero(n_h_)); + } } if (!solver_->IsInitialized()) { solver_->InitializeSolver(*prog_, solver_options_); From b8c2ee1a2df29877f5b81eef8cbcf45cf002e3ed Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Mar 2023 13:59:15 -0500 Subject: [PATCH 385/758] updating standing gains for both sim and real --- examples/Cassie/cassie_xbox_remote.py | 2 +- examples/Cassie/osc/osc_standing_gains.yaml | 76 +++++++++---------- .../Cassie/osc/osc_standing_gains_sim.yaml | 4 +- 3 files changed, 37 insertions(+), 45 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 4063f068a9..6cf34da7e2 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -112,7 +112,7 @@ def main(): # Send LCM message radio_msg = dairlib.lcmt_radio_out() - # radio_msg.channel[0] = speeds[i] + radio_msg.channel[0] = speeds[i] radio_msg.channel[1] = joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(4) diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 6e610120a3..95395e7890 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -1,67 +1,59 @@ -# Set xy PD gains so they do not effect passive LIPM dynamics at capture -# point, when x = sqrt(l/g) * xdot -# Passive dynamics: xddot = g/l * x -# -# -Kp * x - Kd * xdot = -# -Kp * x + Kd * sqrt(g/l) * x = g/l * x -# Kp = sqrt(g/l) * Kd - g/l controller_frequency: 1000 -rows: 3 -cols: 3 -w_input: 0.0 -w_accel: 0.001 -w_lambda: 0.00001 +w_input: 0.000001 +w_accel: 0.000001 +w_lambda: 0.2 #W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, # 1, 1, 1, 1, 0.01, 0.001, # 1, 1, 1, 1, 0.01, 0.001 ] W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] -W_input_reg: [ 1, 0.9, 0.6, 0.3, 5, - 1, 0.9, 0.5, 0.1, 5 ] +W_input_reg: [ 1, 0.9, 0.5, 0.3, 1, + 1, 0.9, 0.5, 0.3, 1 ] W_lambda_c_reg: [ 1, 0.001, 0.01, 1, 0.001, 0.01, - 1, 0.1, 0.01, - 1, 0.1, 0.01 ] + 1, 0.001, 0.01, + 1, 0.001, 0.01 ] +#W_lambda_h_reg: [ 0.02, 0.02 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.002, 0.002 ] -w_soft_constraint: 100 -w_input_reg: 0.00 +w_soft_constraint: 1000 +w_input_reg: 0.3 impact_threshold: 0.00 -center_of_mass_filter_tau: 0.000 -rot_filter_tau: 0.00 -center_of_mass_command_filter_alpha: 0.01 -orientation_command_filter_alpha: 0.0005 +center_of_mass_filter_tau: 0.00 +rot_filter_tau: 0.000 +center_of_mass_command_filter_alpha: 0.8 +orientation_command_filter_alpha: 1.0 impact_tau: 0.00 mu: 0.6 weight_scaling: 1.0 -HipYawKp: 40 +HipYawKp: 100 HipYawKd: 5 -HipYawW: 0 +HipYawW: 2.5 PelvisW: - [1, 0, 0, - 0, 2, 0, - 0, 0, 10] + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 2 ] PelvisKp: - [50, 0, 0, - 0, 50, 0, - 0, 0, 75] + [ 75, 0, 0, + 0, 50, 0, + 0, 0, 40 ] PelvisKd: - [ 0.1, 0, 0, - 0, 0.1, 0, - 0, 0, 1] + [ 2, 0, 0, + 0, 2, 0, + 0, 0, 2] PelvisRotW: - [5, 0, 0, - 0, 5, 0, - 0, 0, 1] + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 10 ] PelvisRotKp: - [25, 0, 0, - 0, 10, 0, - 0, 0, 50] + [150., 0, 0, + 0, 200., 0, + 0, 0, 50 ] PelvisRotKd: - [0, 0, 0, - 0, 0.1, 0, - 0, 0, 0.1] + [ 2, 0, 0, + 0, 2, 0, + 0, 0, 2 ] diff --git a/examples/Cassie/osc/osc_standing_gains_sim.yaml b/examples/Cassie/osc/osc_standing_gains_sim.yaml index 332befbc59..3eecc8a92c 100644 --- a/examples/Cassie/osc/osc_standing_gains_sim.yaml +++ b/examples/Cassie/osc/osc_standing_gains_sim.yaml @@ -43,11 +43,11 @@ PelvisW: 0, 2, 0, 0, 0, 2 ] PelvisKp: - [ 20, 0, 0, + [ 75, 0, 0, 0, 50, 0, 0, 0, 75 ] PelvisKd: - [ 7.5, 0, 0, + [ 10, 0, 0, 0, 5, 0, 0, 0, 5] PelvisRotW: From 6849399adadaabb742244b082bea61001698b2cb Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Mar 2023 16:03:04 -0500 Subject: [PATCH 386/758] cleaning up controllers --- .../pydairlib/analysis/log_plotter_cassie.py | 4 +- .../plot_configs/cassie_standing_plot.yaml | 9 +- examples/Cassie/cassie_xbox_remote.py | 4 +- .../contact_scheduler/contact_scheduler.cc | 13 -- .../contact_scheduler/contact_scheduler.h | 8 +- .../osc_running_controller_diagram.cc | 4 - examples/Cassie/osc_run/BUILD.bazel | 25 ---- .../Cassie/osc_run/osc_running_gains.yaml | 43 +++---- .../osc_run/pelvis_pitch_traj_generator.cc | 121 ------------------ .../osc_run/pelvis_pitch_traj_generator.h | 60 --------- .../osc_run/pelvis_roll_traj_generator.cc | 116 ----------------- .../osc_run/pelvis_roll_traj_generator.h | 63 --------- .../osc_run/pelvis_trans_traj_generator.cc | 54 ++------ .../osc_run/pelvis_trans_traj_generator.h | 4 +- examples/Cassie/run_osc_running_controller.cc | 7 +- .../osc/operational_space_control.cc | 12 +- 16 files changed, 49 insertions(+), 498 deletions(-) delete mode 100644 examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc delete mode 100644 examples/Cassie/osc_run/pelvis_pitch_traj_generator.h delete mode 100644 examples/Cassie/osc_run/pelvis_roll_traj_generator.cc delete mode 100644 examples/Cassie/osc_run/pelvis_roll_traj_generator.h diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index f7bb75e3a2..f811f80ee0 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -11,9 +11,9 @@ def main(): - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml index 30c2ba6a0d..c890a47754 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml @@ -4,6 +4,7 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_STANDING" channel_osc: "OSC_DEBUG_STANDING" use_archived_lcmtypes: false +use_default_styling: false # Log time to stop at (seconds, -1 for whole log) start_time: 0 @@ -34,17 +35,17 @@ foot_positions_to_plot: [ 'right', 'left' ] #foot_positions_to_plot: [] foot_xyz_to_plot: { 'right': [2], 'left': [2] } #foot_xyz_to_plot: { } -pt_on_foot_to_plot: 'rear' # takes value 'front', 'mid', or 'rear' +pt_on_foot_to_plot: ['rear'] # takes value 'front', 'mid', or 'rear' # Desired osc plots plot_qp_costs: true plot_qp_solve_time: true plot_qp_solutions: true plot_tracking_costs: true -plot_active_tracking_datas: true +plot_active_tracking_datas: false tracking_datas_to_plot: { - pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': ['pos', 'vel', 'accel'] }, - pelvis_rot_traj: {'dims': [0, 1, 2], 'derivs': ['vel', 'accel']} + pelvis_trans_traj: { 'dims': [ 0, 1, 2 ], 'derivs': ['pos', 'vel'] }, +# pelvis_rot_traj: {'dims': [0, 1, 2], 'derivs': ['vel', 'accel']} # hip_yaw_left_traj: {'dims': [0], 'derivs': ['vel']} # right_ft_traj: {'dims': [2], 'derivs': ['pos'] }, # left_ft_traj: {'dims': [0, 2], 'derivs': ['pos']}, diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 6cf34da7e2..03f5eb9d5d 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -66,8 +66,8 @@ def main(): joystick.init() done = False - max_speed = 1.6 - ramp_up = np.arange(0, max_speed, 0.03) + max_speed = 2.5 + ramp_up = np.arange(0, max_speed, 0.02) stay = max_speed * np.ones(125) ramp_down = np.flip(np.arange(0, max_speed, 0.01)) speeds = np.hstack((ramp_up, stay, ramp_down)) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index d7e5c3e2a1..2b53752f1c 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -101,12 +101,6 @@ EventStatus ContactScheduler::UpdateTransitionTimes( auto stored_fsm_state = (RUNNING_FSM_STATE)state->get_mutable_discrete_state( stored_fsm_state_index_)[0]; -// double stored_transition_time = -// state->get_discrete_state(stored_transition_time_index_)[0]; -// double nominal_stance_duration = -// state->get_discrete_state(nominal_state_durations_index_)[0]; -// double nominal_flight_duration = -// state->get_discrete_state(nominal_state_durations_index_)[1]; auto transition_times = state->get_mutable_discrete_state(transition_times_index_) .get_mutable_value(); @@ -182,8 +176,6 @@ EventStatus ContactScheduler::UpdateTransitionTimes( std::clamp(stance_scale, 1 - stance_variance_, 1 + stance_variance_); double next_transition_time = stored_transition_time + stance_scale * stance_duration_; - // double next_transition_time = stored_transition_time + - // stance_duration_; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; if (active_state == LEFT_STANCE) { @@ -260,7 +252,6 @@ void ContactScheduler::CalcNextImpactInfo( auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; near_impact->set_timestamp(current_time); - // near_impact->SetCurrentContactMode(0); near_impact->SetAlpha(0); // Get current finite state @@ -334,10 +325,6 @@ void ContactScheduler::CalcContactScheduler( contact_timing->get_mutable_value()(5) = transition_times[RIGHT_FLIGHT] + 2 * nominal_flight_duration + nominal_stance_duration; - // std::cout << "contact_scheduler start: " - // << contact_timing->get_mutable_value()(2) << std::endl; - // std::cout << "contact_scheduler end: " - // << contact_timing->get_mutable_value()(3) << std::endl; } void ContactScheduler::OutputDebuggingInfo( diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 2fc2d1dfe0..f6ee15d879 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -88,18 +88,12 @@ class ContactScheduler : public drake::systems::LeafSystem { double tau_; const BLEND_FUNC blend_func_; - /// contains pairs (start of fsm, fsm_state) - /// the order of the vector goes: last transition, next upcoming three - /// transitions - // mutable std::vector> - // upcoming_transitions_; // sorted by upcoming time mutable - // std::vector transition_times_; // fixed order by RUNNING_FSM_STATE - int initial_state_ = 0; drake::systems::DiscreteStateIndex stored_fsm_state_index_; drake::systems::DiscreteStateIndex stored_robot_state_index_; drake::systems::DiscreteStateIndex stored_transition_time_index_; + // estimates of state durations for stance and flight in seconds drake::systems::DiscreteStateIndex nominal_state_durations_index_; drake::systems::DiscreteStateIndex transition_times_index_; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index d53c38543a..7117acc334 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -12,8 +12,6 @@ #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" #include "examples/Cassie/osc_run/osc_running_gains.h" -#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" -#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" @@ -54,8 +52,6 @@ using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; using drake::trajectories::PiecewisePolynomial; -using examples::osc::PelvisPitchTrajGenerator; -using examples::osc::PelvisRollTrajGenerator; using examples::osc::PelvisTransTrajGenerator; using examples::osc_run::FootTrajGenerator; using multibody::FixedJointEvaluator; diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 85de595457..225322cc63 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -27,8 +27,6 @@ cc_library( deps = [ ":foot_traj_generator", ":osc_running_gains", - ":pelvis_roll_traj_generator", - ":pelvis_pitch_traj_generator", ":pelvis_trans_traj_generator", ], ) @@ -67,29 +65,6 @@ cc_library( ], ) -cc_library( - name = "pelvis_roll_traj_generator", - srcs = ["pelvis_roll_traj_generator.cc"], - hdrs = ["pelvis_roll_traj_generator.h"], - deps = [ - "//multibody:utils", - "//systems/controllers/osc:osc_gains", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "pelvis_pitch_traj_generator", - srcs = ["pelvis_pitch_traj_generator.cc"], - hdrs = ["pelvis_pitch_traj_generator.h"], - deps = [ - "//multibody:utils", - "//systems/controllers/osc:osc_gains", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) cc_library( name = "foot_traj_generator", diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 35bf976ce8..a04206ff8a 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,11 +1,10 @@ -# target_frequency Hz controller_frequency: 1000 w_input: 0.000001 w_input_reg: 0.01 w_accel: 0.0001 w_soft_constraint: 10000 -w_lambda: 0.1 +w_lambda: 0.05 w_input_accel: 0.1 w_joint_limit: 0 impact_threshold: 0.050 @@ -29,8 +28,8 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true no_derivative_feedback: false -rot_filter_tau: 0.005 -ekf_filter_tau: [ 0.05, 0.01, 0.001 ] +rot_filter_tau: 0.0025 +ekf_filter_tau: [ 0.00, 0.00, 0.00 ] # High level command gains (with radio) vel_scale_rot: -4 @@ -39,17 +38,17 @@ vel_scale_trans_lateral: -0.5 target_vel_filter_alpha: 0.01 # SLIP parameters -rest_length: 0.85 -rest_length_offset: 0.025 -stance_duration: 0.3 +rest_length: 0.9 +rest_length_offset: 0.05 +stance_duration: 0.22 flight_duration: 0.09 # max percent variance -stance_variance: 0.2 -flight_variance: 0.1 +stance_variance: 0.3 +flight_variance: 0.3 -w_swing_toe: 0.01 -swing_toe_kp: 1500 -swing_toe_kd: 10 +w_swing_toe: 0.1 +swing_toe_kp: 2000 +swing_toe_kd: 5 w_hip_yaw: 2.5 hip_yaw_kp: 100 @@ -60,21 +59,21 @@ footstep_sagital_offset: -0.00 footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.3 FootstepKd: - [ 0.01, 0, 0, + [ 0.012, 0, 0, 0, 0.3, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, - 0, 1, 0, + 0, 0, 0, 0, 0, 5] PelvisKp: [ 0, 0, 0, - 0, 40, 0, - 0, 0, 115] + 0, 0, 0, + 0, 0, 125] PelvisKd: [ 0, 0, 0, - 0, 10, 0, - 0, 0, 5] + 0, 0, 0, + 0, 0, 7] PelvisRotW: [10, 0, 0, 0, 5, 0, @@ -92,13 +91,13 @@ SwingFootW: 0, 100, 0, 0, 0, 10] SwingFootKp: - [125, 0, 0, - 0, 75, 0, - 0, 0, 75] + [145, 0, 0, + 0, 150, 0, + 0, 0, 175] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 5.] + 0, 0, 7.5] LiftoffSwingFootW: [0, 0, 0, 0, 0, 0, diff --git a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc deleted file mode 100644 index 522a8eda58..0000000000 --- a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.cc +++ /dev/null @@ -1,121 +0,0 @@ -#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" - -#include "multibody/multibody_utils.h" -#include "systems/framework/output_vector.h" - -#include "drake/common/trajectories/piecewise_polynomial.h" -#include "drake/systems/framework/leaf_system.h" - -using std::string; -using std::vector; - -using Eigen::Map; -using Eigen::MatrixXd; -using Eigen::Vector2d; -using Eigen::Vector3d; -using Eigen::VectorXd; - -using dairlib::systems::OutputVector; -using drake::multibody::Frame; -using drake::multibody::MultibodyPlant; -using drake::systems::BasicVector; -using drake::systems::Context; -using drake::systems::DiscreteUpdateEvent; -using drake::systems::DiscreteValues; -using drake::systems::EventStatus; -using drake::trajectories::PiecewisePolynomial; -using drake::trajectories::Trajectory; - -namespace dairlib::examples::osc { - -PelvisPitchTrajGenerator::PelvisPitchTrajGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& hip_pitch_traj, - drake::trajectories::PiecewisePolynomial& pelvis_pitch_traj, - int axis, const std::string& system_name) - : plant_(plant), - context_(context), - world_(plant_.world_frame()), - hip_pitch_traj_(hip_pitch_traj), - pelvis_pitch_traj_(pelvis_pitch_traj), - axis_(axis) { - this->set_name(system_name); - // Input/Output Setup - state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); - fsm_port_ = - this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); - clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) - .get_index(); - - PiecewisePolynomial empty_pp_traj(VectorXd(0)); - Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("pelvis_rot_traj_" + std::to_string(axis), - traj_inst, - &PelvisPitchTrajGenerator::CalcTraj); - - DeclarePerStepDiscreteUpdateEvent( - &PelvisPitchTrajGenerator::DiscreteVariableUpdate); -} - -EventStatus PelvisPitchTrajGenerator::DiscreteVariableUpdate( - const Context& context, - DiscreteValues* discrete_state) const { - return EventStatus::Succeeded(); -} - -PiecewisePolynomial PelvisPitchTrajGenerator::GeneratePelvisTraj( - const systems::OutputVector* robot_output, double t, - int fsm_state) const { - VectorXd q = robot_output->GetPositions(); - VectorXd v = robot_output->GetVelocities(); - multibody::SetPositionsIfNew(plant_, q, context_); - - VectorXd correction = VectorXd::Zero(1); - - drake::math::RotationMatrix pelvis_rot = - plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) - .rotation(); - drake::math::RollPitchYawd pelvis_rpy = drake::math::RollPitchYaw(pelvis_rot); - double pelvis_pitch = pelvis_rpy.pitch_angle(); - - // correction << pelvis_pitch + q(7); - correction << pelvis_pitch; -// std::cout << correction << std::endl; - std::vector breaks = hip_pitch_traj_.get_segment_times(); - VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - MatrixXd offset_angles = correction.replicate(1, breaks.size()); -// for (int i = 0; i < breaks_vector.size(); ++i) { -// offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); -// } - PiecewisePolynomial offset_traj = - PiecewisePolynomial::FirstOrderHold(breaks_vector, offset_angles); - return hip_pitch_traj_ - offset_traj; - // return -offset_traj; -} - -void PelvisPitchTrajGenerator::CalcTraj( - const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const { - // Read in current state - const auto robot_output = - this->template EvalVectorInput(context, state_port_); - // Read in finite state machine - const auto& fsm_state = - this->EvalVectorInput(context, fsm_port_)->get_value()(0); - const auto& clock = - this->EvalVectorInput(context, clock_port_)->get_value()(0); - - auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - // if (fsm_state == 0 || fsm_state == 1) { - *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); - // } -} - -} // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.h b/examples/Cassie/osc_run/pelvis_pitch_traj_generator.h deleted file mode 100644 index 34475b8d0f..0000000000 --- a/examples/Cassie/osc_run/pelvis_pitch_traj_generator.h +++ /dev/null @@ -1,60 +0,0 @@ -#pragma once - -#include - -#include "systems/framework/output_vector.h" - -#include "drake/common/trajectories/piecewise_polynomial.h" -#include "drake/systems/framework/leaf_system.h" - -namespace dairlib::examples::osc { - -class PelvisPitchTrajGenerator : public drake::systems::LeafSystem { - public: - PelvisPitchTrajGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& hip_pitch_traj, - drake::trajectories::PiecewisePolynomial& pelvis_pitch_traj, - int axis, const std::string& system_name); - - const drake::systems::InputPort& get_state_input_port() const { - return this->get_input_port(state_port_); - } - const drake::systems::InputPort& get_fsm_input_port() const { - return this->get_input_port(fsm_port_); - } - const drake::systems::InputPort& get_clock_input_port() const { - return this->get_input_port(clock_port_); - } - - private: - drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( - const systems::OutputVector* robot_output, double t, int fsm_state) const; - - drake::systems::EventStatus DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - - void CalcTraj(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; - - // drake::systems::DiscreteStateIndex prev_fsm_idx_; - - // pelvis trajectory - drake::trajectories::PiecewisePolynomial hip_pitch_traj_; - drake::trajectories::PiecewisePolynomial pelvis_pitch_traj_; - - // A list of pairs of contact body frame and contact point - int axis_; - - drake::systems::InputPortIndex state_port_; - drake::systems::InputPortIndex fsm_port_; - drake::systems::InputPortIndex clock_port_; -}; - -} // namespace dairlib::examples::osc diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc b/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc deleted file mode 100644 index 2d2c7cea15..0000000000 --- a/examples/Cassie/osc_run/pelvis_roll_traj_generator.cc +++ /dev/null @@ -1,116 +0,0 @@ -#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" - -#include "multibody/multibody_utils.h" -#include "systems/framework/output_vector.h" - -#include "drake/common/trajectories/piecewise_polynomial.h" -#include "drake/systems/framework/leaf_system.h" - -using std::string; -using std::vector; - -using Eigen::Map; -using Eigen::MatrixXd; -using Eigen::Vector2d; -using Eigen::Vector3d; -using Eigen::VectorXd; - -using dairlib::systems::OutputVector; -using drake::multibody::Frame; -using drake::multibody::MultibodyPlant; -using drake::systems::BasicVector; -using drake::systems::Context; -using drake::systems::DiscreteUpdateEvent; -using drake::systems::DiscreteValues; -using drake::systems::EventStatus; -using drake::trajectories::PiecewisePolynomial; -using drake::trajectories::Trajectory; - -namespace dairlib::examples::osc { - -PelvisRollTrajGenerator::PelvisRollTrajGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& hip_roll_traj, int axis, - const std::string& system_name) - : plant_(plant), - context_(context), - world_(plant_.world_frame()), - hip_roll_traj_(hip_roll_traj), - axis_(axis) { - this->set_name(system_name); - // Input/Output Setup - state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); - fsm_port_ = - this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); - clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) - .get_index(); - - PiecewisePolynomial empty_pp_traj(VectorXd(0)); - Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("pelvis_rot_traj_" + std::to_string(axis), - traj_inst, - &PelvisRollTrajGenerator::CalcTraj); - - DeclarePerStepDiscreteUpdateEvent( - &PelvisRollTrajGenerator::DiscreteVariableUpdate); -} - -EventStatus PelvisRollTrajGenerator::DiscreteVariableUpdate( - const Context& context, - DiscreteValues* discrete_state) const { - return EventStatus::Succeeded(); -} - -PiecewisePolynomial PelvisRollTrajGenerator::GeneratePelvisTraj( - const systems::OutputVector* robot_output, double t, - int fsm_state) const { - VectorXd q = robot_output->GetPositions(); - VectorXd v = robot_output->GetVelocities(); - multibody::SetPositionsIfNew(plant_, q, context_); - - VectorXd correction = VectorXd::Zero(1); - - drake::math::RotationMatrix pelvis_rot = - plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) - .rotation(); - drake::math::RollPitchYawd pelvis_rpy = drake::math::RollPitchYaw(pelvis_rot); - double pelvis_roll = pelvis_rpy.roll_angle(); - - correction << pelvis_roll; - std::vector breaks = hip_roll_traj_.get_segment_times(); - VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - MatrixXd offset_angles = correction.replicate(1, breaks.size()); - // for (int i = 0; i < breaks_vector.size(); ++i) { - // offset_angles.col(i) = i * offset_angles.col(i) / breaks_vector.size(); - // } - // std::cout << "breaks vector: " << breaks_vector << std::endl; - PiecewisePolynomial offset_traj = - PiecewisePolynomial::ZeroOrderHold(breaks_vector, offset_angles); - return hip_roll_traj_ + offset_traj; - // return offset_traj; -} - -void PelvisRollTrajGenerator::CalcTraj( - const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const { - // Read in current state - const auto robot_output = - this->template EvalVectorInput(context, state_port_); - // Read in finite state machine - const auto& fsm_state = - this->EvalVectorInput(context, fsm_port_)->get_value()(0); - const auto& clock = - this->EvalVectorInput(context, clock_port_)->get_value()(0); - - auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - *casted_traj = GeneratePelvisTraj(robot_output, clock, fsm_state); -} - -} // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_roll_traj_generator.h b/examples/Cassie/osc_run/pelvis_roll_traj_generator.h deleted file mode 100644 index 617c628006..0000000000 --- a/examples/Cassie/osc_run/pelvis_roll_traj_generator.h +++ /dev/null @@ -1,63 +0,0 @@ -#pragma once - -#include - -#include "systems/framework/output_vector.h" - -#include "drake/common/trajectories/piecewise_polynomial.h" -#include "drake/systems/framework/leaf_system.h" - -namespace dairlib::examples::osc { - -class PelvisRollTrajGenerator : public drake::systems::LeafSystem { - public: - PelvisRollTrajGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& hip_roll_traj, int axis, - const std::string& system_name); - - PelvisRollTrajGenerator(const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, - double offset, int axis, - const std::string& system_name); - - const drake::systems::InputPort& get_state_input_port() const { - return this->get_input_port(state_port_); - } - const drake::systems::InputPort& get_fsm_input_port() const { - return this->get_input_port(fsm_port_); - } - const drake::systems::InputPort& get_clock_input_port() const { - return this->get_input_port(clock_port_); - } - - private: - drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( - const systems::OutputVector* robot_output, double t, - int fsm_state) const; - - drake::systems::EventStatus DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - - void CalcTraj(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; - - // pelvis trajectory - drake::trajectories::PiecewisePolynomial hip_roll_traj_; - double neutral_offset_; - - // A list of pairs of contact body frame and contact point - int axis_; - - drake::systems::InputPortIndex state_port_; - drake::systems::InputPortIndex fsm_port_; - drake::systems::InputPortIndex clock_port_; -}; - -} // namespace dairlib::examples::osc diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index aeba3e5761..6e3698861b 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -91,17 +91,14 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( return PiecewisePolynomial(); } -// Vector3d f_g = {0, 0, -9.81}; - Vector3d f_g = drake::multibody::UniformGravityFieldElement().gravity_vector(); + Vector3d f_g = + drake::multibody::UniformGravityFieldElement().gravity_vector(); Vector3d foot_pos = Vector3d::Zero(); Vector3d pelvis_pos = Vector3d::Zero(); Vector3d pelvis_vel = Vector3d::Zero(); plant_.CalcPointsPositions(*context_, feet_contact_points_.at(fsm_state)[0].second, Vector3d::Zero(), world_, &foot_pos); - // plant_.CalcPointsPositions(*context_, pelvis_frame_, Vector3d::Zero(), - // world_, - // &pelvis_pos); pelvis_pos = plant_.CalcCenterOfMassPositionInWorld(*context_); pelvis_vel = plant_.EvalBodySpatialVelocityInWorld(*context_, pelvis_).translational(); @@ -110,52 +107,30 @@ PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( double compression = leg_length.norm() - rest_length_; Vector3d f_leg = k_leg_ * compression * leg_length.normalized() + b_leg_ * pelvis_vel; -// Vector3d rddot = f_g + f_leg; + // ignoring f_leg, spring forces handled by OSC gains Vector3d rddot = f_g; double dt = 1e-2; Eigen::Vector2d breaks; - // if (t <= 0.3) { - // breaks << 0, 0.25, 0.4; - // } else { - // breaks << 0.4, 0.65, 0.8; - // } breaks << t0, tf; MatrixXd samples(3, 2); MatrixXd samples_dot(3, 2); - // std::cout << "t0:" << t0 << std::endl; - // std::cout << "tf:" << tf << std::endl; - // samples << pelvis_pos, pelvis_pos + 0.5 * rddot * dt * dt; - // samples_dot << pelvis_vel, pelvis_vel + rddot * dt; - - // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - // breaks, samples, pelvis_vel, pelvis_vel + rddot * dt); double y_dist_des = 0; if (fsm_state == 0) { y_dist_des = -0.1; } else if (fsm_state == 1) { y_dist_des = 0.1; } - // samples << 0, 0, y_dist_des, y_dist_des, rest_length_, rest_length_ + - // rest_length_offset_; - - samples << 0, 0 + 0.5 * rddot[0] * dt * dt, - y_dist_des, y_dist_des + 0.5 * rddot[1] * dt * dt, - rest_length_, rest_length_ + 0.5 * rddot[2] * dt * dt; - samples_dot << 0, 0 + rddot[0] * dt, - 0, 0 + rddot[1] * dt, - 0, 0 + rddot[2] * dt; - // return PiecewisePolynomial(Vector3d{0, y_dist_des, rest_length_}); - - // return PiecewisePolynomial::FirstOrderHold(breaks, samples); - return PiecewisePolynomial::CubicHermite(breaks, samples, samples_dot); - - // return PiecewisePolynomial::CubicHermite( - // breaks, samples, samples_dot); - // return PiecewisePolynomial::CubicShapePreserving(breaks, samples); - // return PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - // breaks, samples, VectorXd::Zero(3), VectorXd::Zero(3)); + + samples << 0, 0 + 0.5 * rddot[0] * dt * dt, y_dist_des, + y_dist_des + 0.5 * rddot[1] * dt * dt, rest_length_, + rest_length_ + 0.5 * rddot[2] * dt * dt; + samples_dot << 0, 0 + rddot[0] * dt, 0, 0 + rddot[1] * dt, 0, + 0 + rddot[2] * dt; + + return PiecewisePolynomial::CubicHermite(breaks, samples, + samples_dot); } void PelvisTransTrajGenerator::CalcTraj( @@ -172,11 +147,6 @@ void PelvisTransTrajGenerator::CalcTraj( const auto& mode_length = this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); - // std::cout << "fsm_state: " << fsm_state << std::endl; - // std::cout << "clock: " << clock << std::endl; - // std::cout << "mode_length start: " << mode_length[0] << std::endl; - // std::cout << "mode_length end: " << mode_length[1] << std::endl; - auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index 3b1bc97c75..1557d96042 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -61,8 +61,6 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::BodyFrame& pelvis_frame_; const bool relative_pelvis_; - // drake::systems::DiscreteStateIndex prev_fsm_idx_; - // pelvis trajectory drake::trajectories::PiecewisePolynomial traj_; @@ -79,7 +77,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { // SLIP parameters double rest_length_ = 0.8; - double rest_length_offset_ = 0.8; + double rest_length_offset_ = 0.0; double k_leg_ = 100.0; double b_leg_ = 5.0; }; diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1df52fa2ad..121ffd9dc6 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -17,10 +17,7 @@ #include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" #include "examples/Cassie/osc_run/osc_running_gains.h" -#include "examples/Cassie/osc_run/pelvis_pitch_traj_generator.h" -#include "examples/Cassie/osc_run/pelvis_roll_traj_generator.h" #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" -#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" #include "lcm/lcm_trajectory.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/multibody_utils.h" @@ -63,8 +60,6 @@ using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using drake::trajectories::PiecewisePolynomial; using drake::trajectories::Trajectory; -using examples::osc::PelvisPitchTrajGenerator; -using examples::osc::PelvisRollTrajGenerator; using examples::osc::PelvisTransTrajGenerator; using examples::osc_jump::BasicTrajectoryPassthrough; using examples::osc_run::FootTrajGenerator; @@ -466,7 +461,7 @@ int DoMain(int argc, char* argv[]) { if (osc_gains.rot_filter_tau > 0) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, - {0, 1, 2}); + {1, 2}); } // Swing toe joint trajectory diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 503c4cafa3..766b987b72 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -774,17 +774,13 @@ VectorXd OperationalSpaceControl::SolveQp( } if (W_lambda_c_reg_.size() > 0) { - if (fsm_state != -1){ - lambda_c_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, - VectorXd::Zero(n_c_)); - } + lambda_c_cost_->UpdateCoefficients((1 + alpha) * W_lambda_c_reg_, + VectorXd::Zero(n_c_)); } if (W_lambda_h_reg_.size() > 0) { - if (fsm_state != -1){ - lambda_h_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, - VectorXd::Zero(n_h_)); - } + lambda_h_cost_->UpdateCoefficients((1 + alpha) * W_lambda_h_reg_, + VectorXd::Zero(n_h_)); } if (!solver_->IsInitialized()) { solver_->InitializeSolver(*prog_, solver_options_); From 2a3f1c7eebe495ada8a2c320d06283e5bec5b021 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Mar 2023 16:51:57 -0500 Subject: [PATCH 387/758] working on fast running gains --- examples/Cassie/cassie_xbox_remote.py | 6 +++--- examples/Cassie/director_scripts/show_time_sim.py | 8 ++++---- examples/Cassie/osc_run/foot_traj_generator.cc | 3 ++- examples/Cassie/osc_run/osc_running_gains.yaml | 14 +++++++------- examples/Cassie/run_osc_running_controller.cc | 2 +- 5 files changed, 17 insertions(+), 16 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 03f5eb9d5d..7910aa94b6 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -66,9 +66,9 @@ def main(): joystick.init() done = False - max_speed = 2.5 - ramp_up = np.arange(0, max_speed, 0.02) - stay = max_speed * np.ones(125) + max_speed = 2.9 + ramp_up = np.arange(0, max_speed, 0.025) + stay = max_speed * np.ones(500) ramp_down = np.flip(np.arange(0, max_speed, 0.01)) speeds = np.hstack((ramp_up, stay, ramp_down)) i = 0 diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 227736a25d..7c026714a6 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -21,8 +21,8 @@ def __init__(self): self.text_time.setProperty('Font Size', 36) self.text_time.setProperty('Bold', True) self.set_enabled(True) - gridObj.setProperty('Grid Half Width', 50) - gridObj.setProperty('Major Tick Resolution', 50) + gridObj.setProperty('Grid Half Width', 100) + gridObj.setProperty('Major Tick Resolution', 100) def add_subscriber(self): if (self._subscriber is not None): @@ -71,7 +71,7 @@ def handle_message(self, msg): pelvis_height_text = 'pelvis height: %.3f' % pelvis_height pelvis_velocity_text = 'pelvis velocity: %.3f' % np.array(self._pelvis_velocity).mean() - # pelvis_position_text = 'forward position: %.3f' % np.array(msg.position[4]).mean() + pelvis_position_text = 'forward position: %.3f' % np.array(msg.position[4]).mean() realtime_text = '' if (len(self._real_time) >= self._num_msg_for_average): @@ -88,7 +88,7 @@ def handle_message(self, msg): # my_text = my_text + ', real time factor: %.2f' % rt_ratio # vis.updateText(my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text +'\n' + realtime_text, 'text') - self.text_time.setProperty('Text', my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text + '\n' + realtime_text) + self.text_time.setProperty('Text', my_text + '\n' + pelvis_height_text + '\n' + pelvis_velocity_text + '\n' + pelvis_position_text + '\n' + realtime_text) # vis.updateText(my_text + '\n' + pelvis_velocity_text, 'text') diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 020e1926e6..e812a982a2 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -238,7 +238,8 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( } // Y[0](2) -= rest_length_offset_; Y[1] = start_pos + x_mid_point_ratio * (foot_end_pos_des - start_pos); - Y[1](2) += mid_foot_height_; + double foot_height_scale = std::clamp(pelvis_vel[0] / 2.5, 1.0, 1.3); + Y[1](2) += foot_height_scale * mid_foot_height_; Y[2] = foot_end_pos_des; // corrections diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index a04206ff8a..8f737eb6e1 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -40,17 +40,17 @@ target_vel_filter_alpha: 0.01 # SLIP parameters rest_length: 0.9 rest_length_offset: 0.05 -stance_duration: 0.22 -flight_duration: 0.09 +stance_duration: 0.2 +flight_duration: 0.1 # max percent variance -stance_variance: 0.3 -flight_variance: 0.3 +stance_variance: 0.4 +flight_variance: 0.2 w_swing_toe: 0.1 swing_toe_kp: 2000 swing_toe_kd: 5 -w_hip_yaw: 2.5 +w_hip_yaw: 5 hip_yaw_kp: 100 hip_yaw_kd: 7 # Foot placement parameters @@ -73,7 +73,7 @@ PelvisKp: PelvisKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 7] + 0, 0, 5] PelvisRotW: [10, 0, 0, 0, 5, 0, @@ -89,7 +89,7 @@ PelvisRotKd: SwingFootW: [10, 0, 0, 0, 100, 0, - 0, 0, 10] + 0, 0, 50] SwingFootKp: [145, 0, 0, 0, 150, 0, diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 121ffd9dc6..c41075e807 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -458,7 +458,7 @@ int DoMain(int argc, char* argv[]) { RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - +// pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); if (osc_gains.rot_filter_tau > 0) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {1, 2}); From d5498275125524327fc958d59d1cf604afb00c35 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Mar 2023 12:18:06 -0500 Subject: [PATCH 388/758] fixing gym, start time matters --- .../pydairlib/analysis/log_plotter_cassie.py | 4 +- .../plot_configs/cassie_running_plot.yaml | 6 +- .../cassie/gym_envs/cassie_gym_test.py | 9 +- .../cassie/gym_envs/drake_cassie_gym.py | 16 ++- .../cassie/gym_envs/mujoco_cassie_gym.py | 7 +- .../mujoco/drake_to_mujoco_converter.py | 2 +- examples/Cassie/BUILD.bazel | 10 +- examples/Cassie/cassie_virtual_remote.py | 103 ---------------- .../Cassie/diagrams/cassie_sim_diagram.cc | 9 +- examples/Cassie/diagrams/cassie_sim_diagram.h | 8 +- .../osc_running_controller_diagram.cc | 108 ++++++----------- .../diagrams/osc_running_controller_diagram.h | 19 +-- examples/Cassie/forward_command.py | 53 +++++++++ .../Cassie/osc_run/foot_traj_generator.cc | 2 +- .../Cassie/osc_run/osc_running_gains.yaml | 55 ++++----- .../osc_run/osc_running_gains_fast.yaml | 112 ++++++++++++++++++ examples/Cassie/run_osc_running_controller.cc | 27 ----- 17 files changed, 270 insertions(+), 280 deletions(-) delete mode 100644 examples/Cassie/cassie_virtual_remote.py create mode 100644 examples/Cassie/forward_command.py create mode 100644 examples/Cassie/osc_run/osc_running_gains_fast.yaml diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index f811f80ee0..f7bb75e3a2 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -11,9 +11,9 @@ def main(): - # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_kcmpc_plot.yaml' - config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' + # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_standing_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_default_plot.yaml' # config_file = 'bindings/pydairlib/analysis/plot_configs/cassie_jumping_plot.yaml' plot_config = CassiePlotConfig(config_file) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 8173c1ff7a..7a8c91f78d 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -4,19 +4,19 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false -use_default_styling: true +use_default_styling: false # Log time to stop at (seconds, -1 for whole log) start_time: 2 #duration: 0.47 -duration: -1 +duration: 50 # Plant properties use_springs: true use_floating_base: true # Desired RobotOutput plots -plot_floating_base_positions: false +plot_floating_base_positions: true plot_floating_base_velocities: false plot_floating_base_velocity_body_frame: true plot_joint_positions: false diff --git a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py index 3e13970570..5b3e91760b 100644 --- a/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py +++ b/bindings/pydairlib/cassie/gym_envs/cassie_gym_test.py @@ -18,7 +18,6 @@ def main(): reward_function_weights = '' action = np.zeros(18) - action[2] = 1.0 cumulative_reward = 0 while 1: controller_plant = MultibodyPlant(1e-3) @@ -30,11 +29,11 @@ def main(): # reward_func = RewardOSUDRL(reward_function_weights) reward_func = RewardOSUDRL() - gym_env = DrakeCassieGym(reward_func, visualize=True) - # gym_env = MuJoCoCassieGym(reward_func, visualize=True) + # gym_env = DrakeCassieGym(reward_func, visualize=True) + gym_env = MuJoCoCassieGym(reward_func, visualize=True) gym_env.make(controller) - cumulative_reward = gym_env.advance_to(7.5) - print(cumulative_reward) + cumulative_reward = gym_env.advance_to(25) + # print(cumulative_reward) gym_env.free_sim() # gym_env.reset() # while gym_env.current_time < 5.0: diff --git a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py index b06c20a9ee..d8802db8fe 100644 --- a/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/drake_cassie_gym.py @@ -20,14 +20,14 @@ def __init__(self, reward_func, visualize=False): self.sim_dt = 1e-3 self.visualize = visualize self.reward_func = reward_func - self.start_time = 0.00 + self.start_time = 0.35 self.current_time = 0.00 - self.end_time = 0.05 + # self.end_time = 0.05 self.hardware_traj = None self.action_dim = 10 self.state_dim = 45 self.x_init = np.array( - [1, 0, 0, 0, 0, 0, 0.85, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, + [1, 0, 0, 0, 0, 0, 0.9, -0.0358636, 0, 0.67432, -1.588, -0.0458742, 1.90918, -0.0381073, -1.82312, 0.0358636, 0, 0.67432, -1.588, -0.0457885, 1.90919, -0.0382424, -1.82321, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]) self.prev_cassie_state = None @@ -91,6 +91,7 @@ def step(self, action=np.zeros(18)): if not self.initialized: print("Call make() before calling step() or advance()") next_timestep = self.sim.get_context().get_time() + self.sim_dt + action = self.velocity_profile(next_timestep) self.simulator.get_input_port_radio().FixValue(self.simulator_context, action) self.controller.get_input_port_radio().FixValue(self.controller_context, action) self.sim.AdvanceTo(next_timestep) @@ -100,13 +101,20 @@ def step(self, action=np.zeros(18)): self.plant.GetMyMutableContextFromRoot( self.sim.get_context())) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp - print(u) + # u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp + # print(u) self.cassie_state = CassieEnvState(self.current_time, x, u, action) reward = self.reward_func.compute_reward(self.sim_dt, self.cassie_state, self.prev_cassie_state) self.terminated = self.check_termination() self.prev_cassie_state = self.cassie_state return self.cassie_state, reward + def velocity_profile(self, timestep): + velocity_command = np.zeros(18) + velocity_command[2] = min(0.1 * timestep, 1.0) + # velocity_command[2] = 5.0 + return velocity_command + def get_traj(self): return self.traj diff --git a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py index 9f9bcebffd..75040a596a 100644 --- a/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py +++ b/bindings/pydairlib/cassie/gym_envs/mujoco_cassie_gym.py @@ -33,7 +33,7 @@ def __init__(self, reward_func, visualize=False, model_xml='cassie.xml', dynamic self.reward_func = reward_func # hardware logs are 50ms long and start approximately 5ms before impact # the simulator will check to make sure ground reaction forces are first detected within 3-7ms - self.start_time = 0.00 + self.start_time = 0.3 self.current_time = 0.00 self.end_time = 7.5 @@ -179,7 +179,7 @@ def check_termination(self): def velocity_profile(self, timestep): velocity_command = np.zeros(18) - velocity_command[2] = min(1.0 * timestep, 4.0) + velocity_command[2] = min(0.1 * timestep, 2.0) # velocity_command[2] = 5.0 return velocity_command @@ -199,7 +199,6 @@ def step(self, action=np.zeros(18)): self.radio_input_port.FixValue(self.controller_context, action) u = self.controller_output_port.Eval(self.controller_context)[:-1] # remove the timestamp cassie_in, u_mujoco = self.pack_input(self.cassie_in, u) - # import pdb; pdb.set_trace() self.drake_sim.AdvanceTo(next_timestep) # self.reward_func.reset_clock_reward() while self.simulator.time() < next_timestep: @@ -213,8 +212,6 @@ def step(self, action=np.zeros(18)): self.current_time = next_timestep t = self.simulator.time() - # q = np.copy() - # v = np.copy() q, v = self.drake_to_mujoco_converter.convert_to_drake(self.simulator.qpos(), self.simulator.qvel()) self.current_time = t x = np.hstack((q, v)) diff --git a/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py index b33ac9ecd7..8b8c95df1e 100644 --- a/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py +++ b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py @@ -24,7 +24,7 @@ def __init__(self, drake_sim_dt=5e-5): self.drake_sim_dt = drake_sim_dt self.plant, self.scene_graph = AddMultibodyPlantSceneGraph(self.builder, drake_sim_dt) AddCassieMultibody(self.plant, self.scene_graph, True, - 'examples/Cassie/urdf/cassie_v2.urdf', False, False) + 'examples/Cassie/urdf/cassie_v2.urdf', False, False, True) self.plant.Finalize() self.foot_crank_builder = DiagramBuilder() diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 7bd9193286..486105c670 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -573,12 +573,12 @@ py_binary( ) py_binary( - name = "cassie_virtual_remote_py", - srcs = ["cassie_virtual_remote.py"], + name = "forward_command_py", + srcs = ["forward_command.py"], data = [ "@lcm//:lcm-python", ], - main = "cassie_virtual_remote.py", + main = "forward_command.py", deps = [ "//lcmtypes:lcmtypes_robot_py", ], @@ -599,8 +599,8 @@ py_binary( load("@drake//tools/skylark:drake_runfiles_binary.bzl", "drake_runfiles_binary") drake_runfiles_binary( - name = "cassie_virtual_remote", - target = "cassie_virtual_remote_py", + name = "forward_command", + target = "forward_command_py", ) drake_runfiles_binary( diff --git a/examples/Cassie/cassie_virtual_remote.py b/examples/Cassie/cassie_virtual_remote.py deleted file mode 100644 index 72959b3158..0000000000 --- a/examples/Cassie/cassie_virtual_remote.py +++ /dev/null @@ -1,103 +0,0 @@ -''' -Uses Pygame (pip install pygame) to capture keyboard input. The virtual remote must be the active window to register commands. -W / S to increase/decrease sagittal velocity -A / D to increase/decrease longitudinal velocity - -use Keyboard Manager trim_x and trim_y member variables to add trim to the velocity commands -''' - -import sys -import pygame -from pygame.locals import * -import numpy as np - -import dairlib.lcmt_cassie_out - -import time -import lcm - - -class KeyboardManager(): - - def __init__(self): - pygame.init() - screen_size = 400 - self.screen = pygame.display.set_mode((screen_size, screen_size)) - self.vel = np.array([0.0, 0.0]) - self.trim_x = 0 - self.trim_y = 0 - self.delta_vx = 0.1 - self.delta_vy = 0.05 - self.delta_z = 0.05 - self.height_adjust = 0 - - - def switch_motion_key(self, key): - switcher = { - K_w: np.array([self.delta_vx, 0.0]), - K_s: np.array([-self.delta_vx, 0.0]), - K_a: np.array([0.0, self.delta_vy]), - K_d: np.array([0.0, -self.delta_vy]) - } - return switcher.get(key, np.array([0, 0])) - - def event_callback(self): - for event in pygame.event.get(): - if event.type == QUIT: - sys.exit(0) - elif event.type == KEYDOWN: - if (event.key == K_u): - self.height_adjust += self.delta_z - return - elif (event.key == K_d): - self.height_adjust -= self.delta_z - return - - self.vel += self.switch_motion_key(event.key) - if np.abs(self.vel[0]) < 1e-2: - self.vel[0] = 0.0 - if np.abs(self.vel[1]) < 1e-2: - self.vel[1] = 0.0 - - -def main(): - keyboard = KeyboardManager() - - lc = lcm.LCM() - - cassie_blue = (6, 61, 128) - white = (255, 255, 255) - pygame.display.set_caption('Cassie Virtual Radio Controller') - keyboard.screen.fill(cassie_blue) - fnt = pygame.font.Font('freesansbold.ttf', 32) - - while True: - # Get any keypresses - keyboard.event_callback() - - # Update display screen - display_text1 = 'Sagittal vel: ' + '%.2f'%(keyboard.vel[0]) - display_text2 = 'Coronal Vel: ' + '%.2f'%(keyboard.vel[1]) - text1 = fnt.render(display_text1, True, white, cassie_blue) - text2 = fnt.render(display_text2, True, white, cassie_blue) - text_rect1 = text1.get_rect() - text_rect2 = text2.get_rect() - text_rect1.center = (200, 150) - text_rect2.center = (200, 250) - keyboard.screen.fill(cassie_blue) - keyboard.screen.blit(text1, text_rect1) - keyboard.screen.blit(text2, text_rect2) - - # Send LCM message - cassie_out_msg = dairlib.lcmt_cassie_out() - cassie_out_msg.pelvis.radio.channel[0] = keyboard.vel[0] + keyboard.trim_x - cassie_out_msg.pelvis.radio.channel[1] = keyboard.vel[1] + keyboard.trim_y - cassie_out_msg.pelvis.radio.channel[3] = 0 - - lc.publish("CASSIE_OUTPUT_ECHO", cassie_out_msg.encode()) - - time.sleep(0.05) - pygame.display.update() - -if __name__ == '__main__': - main() diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index c6c18ed745..d6979ac5cb 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -105,10 +105,10 @@ CassieSimDiagram::CassieSimDiagram( builder.Connect(radio_parser->get_output_port(), sensor_aggregator_->get_input_port_radio()); - builder.ExportInput(input_receiver->get_input_port(), "lcmt_robot_input"); - builder.ExportInput(radio_parser->get_input_port(), "raw_radio"); - builder.ExportOutput(state_sender->get_output_port(0), "lcmt_robot_output"); - builder.ExportOutput(sensor_aggregator_->get_output_port(0), + actuation_port_ = builder.ExportInput(input_receiver->get_input_port(), "lcmt_robot_input"); + radio_port_ = builder.ExportInput(radio_parser->get_input_port(), "raw_radio"); + state_port_ = builder.ExportOutput(state_sender->get_output_port(0), "lcmt_robot_output"); + cassie_out_port_ = builder.ExportOutput(sensor_aggregator_->get_output_port(0), "lcmt_cassie_out"); if (visualize) { DrakeVisualizer::AddToBuilder(&builder, *scene_graph_); @@ -116,7 +116,6 @@ CassieSimDiagram::CassieSimDiagram( builder.BuildInto(this); this->set_name("cassie_sim_diagram"); DrawAndSaveDiagramGraph(*this); - std::cout << "Built simulator" << std::endl; } } // namespace examples } // namespace dairlib \ No newline at end of file diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index 3d34ca2641..e8ac694677 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -59,10 +59,10 @@ class CassieSimDiagram : public drake::systems::Diagram { const systems::GearedMotor* cassie_motor_; // const systems::RadioParser* radio_parser_; drake::geometry::SceneGraph* scene_graph_; - const int actuation_port_ = 0; - const int radio_port_ = 1; - const int state_port_ = 0; - const int cassie_out_port_ = 1; + drake::systems::InputPortIndex actuation_port_; + drake::systems::InputPortIndex radio_port_; + drake::systems::OutputPortIndex state_port_; + drake::systems::OutputPortIndex cassie_out_port_; const double actuator_delay = 5e-3; // 5ms const double actuator_update_rate = 1e-3; // 1ms const double dt_ = 8e-5; diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 7117acc334..7b0bbe0a8f 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -66,7 +66,7 @@ namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::multibody::MultibodyPlant& plant, - const string& osc_gains_filename, const string& osqp_settings_filename) + const string& osc_running_gains_filename, const string& osqp_settings_filename) : plant_(&plant), pos_map(multibody::MakeNameToPositionsMap(plant)), vel_map(multibody::MakeNameToVelocitiesMap(plant)), @@ -77,8 +77,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_heel(RightToeRear(plant)), left_foot_points({left_heel, left_toe}), right_foot_points({right_heel, right_toe}), - view_frame( - std::make_shared>(plant.GetBodyByName("pelvis"))), + view_frame(std::make_shared>( + plant.GetBodyByName("pelvis"))), left_toe_evaluator(multibody::WorldPointEvaluator( plant, left_toe.first, left_toe.second, *view_frame, Matrix3d::Identity(), Vector3d::Zero(), {1, 2})), @@ -121,10 +121,10 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gains_filename), {}, {}, yaml_options); + FindResourceOrThrow(osc_running_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_running_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(osc_gains_filename)); + FindResourceOrThrow(osc_running_gains_filename)); /**** FSM and contact mode configuration ****/ vector fsm_states = { @@ -162,18 +162,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto failure_aggregator = builder.AddSystem( control_channel_name_, 1); -// std::vector tau = {.05, .01, .01}; - // auto ekf_filter = - // builder.AddSystem(plant, tau); /**** OSC setup ****/ /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_running_gains.w_accel * - osc_running_gains.W_acceleration); + osc->SetAccelerationCostWeights(osc_running_gains.w_accel * osc_running_gains.W_acceleration); osc->SetInputSmoothingCostWeights(osc_running_gains.w_input_reg * - osc_running_gains.W_input_regularization); + osc_running_gains.W_input_regularization); osc->SetInputCostWeights(osc_running_gains.w_input * - osc_running_gains.W_input_regularization); + osc_running_gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight( osc_running_gains.w_lambda * osc_running_gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight( @@ -194,14 +190,14 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, &right_heel_evaluator); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); - // Fix the springs in the dynamics evaluators.add_evaluator(&left_fixed_knee_spring); evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + osc->AddKinematicConstraint(&evaluators); @@ -274,19 +270,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_foot_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); - left_foot_yz_tracking_data = std::make_unique( - "left_ft_traj", osc_running_gains.K_p_swing_foot, - osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, - plant); - right_foot_yz_tracking_data = std::make_unique( - "right_ft_traj", osc_running_gains.K_p_swing_foot, - osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, - plant); - left_foot_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); - right_foot_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); - left_hip_tracking_data = std::make_unique( "left_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, @@ -309,19 +292,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_hip_tracking_data->AddStateAndPointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); - left_hip_yz_tracking_data = std::make_unique( - "left_hip_traj", osc_running_gains.K_p_swing_foot, - osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, - plant); - right_hip_yz_tracking_data = std::make_unique( - "right_hip_traj", osc_running_gains.K_p_swing_foot, - osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, - plant); - left_hip_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); - right_hip_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); - left_foot_rel_tracking_data = std::make_unique( "left_ft_traj", osc_running_gains.K_p_swing_foot, @@ -334,18 +304,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), right_hip_tracking_data.get()); - left_foot_yz_rel_tracking_data = - std::make_unique( - "left_ft_z_traj", osc_running_gains.K_p_liftoff_swing_foot, - osc_running_gains.K_d_liftoff_swing_foot, - osc_running_gains.W_liftoff_swing_foot, plant, plant, - left_foot_yz_tracking_data.get(), left_hip_yz_tracking_data.get()); - right_foot_yz_rel_tracking_data = - std::make_unique( - "right_ft_z_traj", osc_running_gains.K_p_liftoff_swing_foot, - osc_running_gains.K_d_liftoff_swing_foot, - osc_running_gains.W_liftoff_swing_foot, plant, plant, - right_foot_yz_tracking_data.get(), right_hip_yz_tracking_data.get()); pelvis_trans_rel_tracking_data = std::make_unique( "pelvis_trans_traj", osc_running_gains.K_p_pelvis, @@ -353,8 +311,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( plant, pelvis_tracking_data.get(), stance_foot_tracking_data.get()); left_foot_rel_tracking_data->SetViewFrame(view_frame); right_foot_rel_tracking_data->SetViewFrame(view_frame); - left_foot_yz_rel_tracking_data->SetViewFrame(view_frame); - right_foot_yz_rel_tracking_data->SetViewFrame(view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(view_frame); auto foot_traj_weight_trajectory = @@ -362,30 +318,22 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( PiecewisePolynomial::FirstOrderHold( {0, osc_running_gains.stance_duration + 2 * osc_running_gains.flight_duration}, - {0.5 * VectorXd::Ones(1), 5.0 * VectorXd::Ones(1)})); + {0.5 * VectorXd::Ones(1), 4.0 * VectorXd::Ones(1)})); auto foot_traj_gain_trajectory = std::make_shared>( PiecewisePolynomial::FirstOrderHold( {0, osc_running_gains.stance_duration + 2 * osc_running_gains.flight_duration}, {0.5 * MatrixXd::Identity(3, 3), - 2.0 * MatrixXd::Identity(3, 3)})); + 1.5 * MatrixXd::Identity(3, 3)})); left_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); right_foot_rel_tracking_data->SetTimeVaryingWeights( foot_traj_weight_trajectory); - left_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier(foot_traj_gain_trajectory); - right_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier(foot_traj_gain_trajectory); - - left_foot_rel_tracking_data->SetImpactInvariantProjection(true); - right_foot_rel_tracking_data->SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); - right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); - pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); - - osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); - osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); - osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); + left_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier( + foot_traj_gain_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier( + foot_traj_gain_trajectory); auto heading_traj_generator = builder.AddSystem(plant, @@ -408,8 +356,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( pelvis_rot_tracking_data->SetLowPassFilter(osc_running_gains.rot_filter_tau, {0, 1, 2}); } - pelvis_rot_tracking_data->SetImpactInvariantProjection(true); - osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); + pelvis_rot_tracking_data->SetViewFrame(view_frame); // Swing toe joint trajectory auto left_toe_angle_traj_gen = builder.AddSystem( @@ -440,10 +387,6 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right", "toe_rightdot"); - left_toe_angle_tracking_data->SetImpactInvariantProjection(true); - right_toe_angle_tracking_data->SetImpactInvariantProjection(true); - osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); - osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); // Swing hip yaw joint tracking left_hip_yaw_tracking_data = std::make_unique( @@ -456,6 +399,21 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "hip_yaw_leftdot"); right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); + + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + left_toe_angle_tracking_data->SetImpactInvariantProjection(true); + right_toe_angle_tracking_data->SetImpactInvariantProjection(true); + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); + osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), VectorXd::Zero(1)); osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.h b/examples/Cassie/diagrams/osc_running_controller_diagram.h index 91d63e89ab..1df206e906 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.h +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.h @@ -54,7 +54,8 @@ class OSCRunningControllerDiagram final } /// @return the output port for the lcmt_robot_input message. - const drake::systems::OutputPort& get_output_port_robot_input() const { + const drake::systems::OutputPort& get_output_port_robot_input() + const { return this->get_output_port(control_port_); } @@ -117,18 +118,10 @@ class OSCRunningControllerDiagram final std::unique_ptr stance_foot_tracking_data; std::unique_ptr left_foot_tracking_data; std::unique_ptr right_foot_tracking_data; - std::unique_ptr left_foot_yz_tracking_data; - std::unique_ptr right_foot_yz_tracking_data; std::unique_ptr left_hip_tracking_data; std::unique_ptr right_hip_tracking_data; - std::unique_ptr left_hip_yz_tracking_data; - std::unique_ptr right_hip_yz_tracking_data; std::unique_ptr left_foot_rel_tracking_data; std::unique_ptr right_foot_rel_tracking_data; - std::unique_ptr - left_foot_yz_rel_tracking_data; - std::unique_ptr - right_foot_yz_rel_tracking_data; std::unique_ptr pelvis_trans_rel_tracking_data; std::unique_ptr pelvis_rot_tracking_data; @@ -137,10 +130,10 @@ class OSCRunningControllerDiagram final std::unique_ptr left_hip_yaw_tracking_data; std::unique_ptr right_hip_yaw_tracking_data; - const drake::systems::InputPortIndex - state_port_ = drake::systems::InputPortIndex(0); - const drake::systems::InputPortIndex - radio_port_ = drake::systems::InputPortIndex(1); + const drake::systems::InputPortIndex state_port_ = + drake::systems::InputPortIndex(0); + const drake::systems::InputPortIndex radio_port_ = + drake::systems::InputPortIndex(1); const drake::systems::OutputPortIndex control_port_ = drake::systems::OutputPortIndex(0); const drake::systems::OutputPortIndex torque_port_ = diff --git a/examples/Cassie/forward_command.py b/examples/Cassie/forward_command.py new file mode 100644 index 0000000000..d4e3ee05fc --- /dev/null +++ b/examples/Cassie/forward_command.py @@ -0,0 +1,53 @@ +import dairlib.lcmt_radio_out +import pygame +import lcm +import numpy as np + +# colors +cassie_blue = (6, 61, 128) +white = (255, 255, 255) + +def main(): + publisher = lcm.LCM() + + screen_size = 500 + # screen = pygame.display.set_mode((screen_size, screen_size)) + + # Used to manage how fast the screen updates + clock = pygame.time.Clock() + + done = False + max_speed = 2.9 + dt = .020 + acceleration = 1.25 # m/s^2 + deceleration = 0.75 # m/s^2 + max_speed_duration = 20 + velocity_step_up = acceleration * dt + velocity_step_down = deceleration * dt + ramp_up = np.arange(0, max_speed, velocity_step_up) + stay = max_speed * np.ones(int(max_speed_duration / dt)) + ramp_down = np.flip(np.arange(0, max_speed, velocity_step_down)) + speeds = np.hstack((ramp_up, stay, ramp_down)) + ramp_duration = speeds.shape[0] * .02 + print("total duration: ", ramp_duration) + i = 0 + while not done: + # DRAWING STEP + # First, clear the screen to blue. Don't put other drawing commands + # above this, or they will be erased with this command. + # screen.fill(cassie_blue) + + # Send LCM message + radio_msg = dairlib.lcmt_radio_out() + radio_msg.channel[0] = speeds[i] + + publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) + + # Limit to 20 frames per second + clock.tick(dt * 1000) + i += 1 + + pygame.quit() + +if __name__ == '__main__': + main() diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index e812a982a2..2c1137ef2c 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -238,7 +238,7 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( } // Y[0](2) -= rest_length_offset_; Y[1] = start_pos + x_mid_point_ratio * (foot_end_pos_des - start_pos); - double foot_height_scale = std::clamp(pelvis_vel[0] / 2.5, 1.0, 1.3); + double foot_height_scale = std::clamp(pelvis_vel[0] / 2.5, 1.0, 1.4); Y[1](2) += foot_height_scale * mid_foot_height_; Y[2] = foot_end_pos_des; diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 8f737eb6e1..4f703b77dc 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -1,10 +1,11 @@ +# target_frequency Hz controller_frequency: 1000 w_input: 0.000001 w_input_reg: 0.01 w_accel: 0.0001 w_soft_constraint: 10000 -w_lambda: 0.05 +w_lambda: 0.1 w_input_accel: 0.1 w_joint_limit: 0 impact_threshold: 0.050 @@ -17,10 +18,10 @@ W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001 ] W_input_reg: [ 1, 0.9, 0.5, 0.1, 1, 1, 0.9, 0.5, 0.1, 1 ] -W_lambda_c_reg: [ 0.001, 0.001, 0.01, - 0.001, 0.001, 0.01, - 0.001, 0.001, 0.01, - 0.001, 0.001, 0.01 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01 ] W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] #w_soft_constraint: 1000000 @@ -28,8 +29,8 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, relative_feet: true relative_pelvis: true no_derivative_feedback: false -rot_filter_tau: 0.0025 -ekf_filter_tau: [ 0.00, 0.00, 0.00 ] +rot_filter_tau: 0.005 +ekf_filter_tau: [ 0.05, 0.01, 0.001 ] # High level command gains (with radio) vel_scale_rot: -4 @@ -38,19 +39,19 @@ vel_scale_trans_lateral: -0.5 target_vel_filter_alpha: 0.01 # SLIP parameters -rest_length: 0.9 -rest_length_offset: 0.05 -stance_duration: 0.2 -flight_duration: 0.1 +rest_length: 0.85 +rest_length_offset: 0.025 +stance_duration: 0.3 +flight_duration: 0.09 # max percent variance -stance_variance: 0.4 -flight_variance: 0.2 +stance_variance: 0.2 +flight_variance: 0.1 -w_swing_toe: 0.1 -swing_toe_kp: 2000 -swing_toe_kd: 5 +w_swing_toe: 0.01 +swing_toe_kp: 1500 +swing_toe_kd: 10 -w_hip_yaw: 5 +w_hip_yaw: 2.5 hip_yaw_kp: 100 hip_yaw_kd: 7 # Foot placement parameters @@ -59,20 +60,20 @@ footstep_sagital_offset: -0.00 footstep_lateral_offset: 0.04 # drake mid_foot_height: 0.3 FootstepKd: - [ 0.012, 0, 0, + [ 0.01, 0, 0, 0, 0.3, 0, 0, 0, 0 ] PelvisW: [ 0, 0, 0, - 0, 0, 0, + 0, 1, 0, 0, 0, 5] PelvisKp: [ 0, 0, 0, - 0, 0, 0, - 0, 0, 125] + 0, 40, 0, + 0, 0, 115] PelvisKd: [ 0, 0, 0, - 0, 0, 0, + 0, 10, 0, 0, 0, 5] PelvisRotW: [10, 0, 0, @@ -89,15 +90,15 @@ PelvisRotKd: SwingFootW: [10, 0, 0, 0, 100, 0, - 0, 0, 50] + 0, 0, 10] SwingFootKp: - [145, 0, 0, - 0, 150, 0, - 0, 0, 175] + [125, 0, 0, + 0, 75, 0, + 0, 0, 75] SwingFootKd: [5., 0, 0, 0, 5., 0, - 0, 0, 7.5] + 0, 0, 5.] LiftoffSwingFootW: [0, 0, 0, 0, 0, 0, diff --git a/examples/Cassie/osc_run/osc_running_gains_fast.yaml b/examples/Cassie/osc_run/osc_running_gains_fast.yaml new file mode 100644 index 0000000000..58caf5a928 --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_gains_fast.yaml @@ -0,0 +1,112 @@ +controller_frequency: 1000 + +w_input: 0.000001 +w_input_reg: 0.01 +w_accel: 0.0001 +w_soft_constraint: 10000 +w_lambda: 0.05 +w_input_accel: 0.1 +w_joint_limit: 0 +impact_threshold: 0.050 +impact_tau: 0.005 +weight_scaling: 1.0 +mu: 0.6 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001 ] +W_input_reg: [ 1, 0.9, 0.5, 0.1, 1, + 1, 0.9, 0.5, 0.1, 1 ] +W_lambda_c_reg: [ 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.001, 0.001 ] +#w_soft_constraint: 1000000 + +relative_feet: true +relative_pelvis: true +no_derivative_feedback: false +rot_filter_tau: 0.0025 +ekf_filter_tau: [ 0.00, 0.00, 0.00 ] + +# High level command gains (with radio) +vel_scale_rot: -4 +vel_scale_trans_sagital: 15 +vel_scale_trans_lateral: -0.5 +target_vel_filter_alpha: 0.01 + +# SLIP parameters +rest_length: 0.9 +rest_length_offset: 0.05 +stance_duration: 0.2 +flight_duration: 0.11 +# max percent variance +stance_variance: 0.4 +flight_variance: 0.2 + +w_swing_toe: 0.1 +swing_toe_kp: 2000 +swing_toe_kd: 5 + +w_hip_yaw: 5 +hip_yaw_kp: 100 +hip_yaw_kd: 7 +# Foot placement parameters +#footstep_offset: -0.05 +footstep_sagital_offset: -0.00 +footstep_lateral_offset: 0.04 # drake +mid_foot_height: 0.3 +FootstepKd: + [ 0.012, 0, 0, + 0, 0.3, 0, + 0, 0, 0 ] +PelvisW: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 5] +PelvisKp: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 125] +PelvisKd: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] +PelvisRotKp: + [150., 0, 0, + 0, 200., 0, + 0, 0, 0.] +PelvisRotKd: + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +SwingFootW: + [10, 0, 0, + 0, 100, 0, + 0, 0, 50] +SwingFootKp: + [145, 0, 0, + 0, 150, 0, + 0, 0, 175] +SwingFootKd: + [5., 0, 0, + 0, 5., 0, + 0, 0, 7.5] +LiftoffSwingFootW: + [0, 0, 0, + 0, 0, 0, + 0, 0, 0] +LiftoffSwingFootKp: + [0, 0, 0, + 0, 0, 0, + 0, 0, 0] +LiftoffSwingFootKd: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 0] diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index c41075e807..032d0f7ce1 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -28,7 +28,6 @@ #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" -#include "systems/filters/floating_base_velocity_filter.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -263,14 +262,6 @@ int DoMain(int argc, char* argv[]) { auto right_loop = RightLoopClosureEvaluator(plant); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); - // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, - // &left_fixed_knee_spring); - // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, - // &right_fixed_knee_spring); - // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, - // &left_fixed_ankle_spring); - // osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, - // &right_fixed_ankle_spring); osc->AddKinematicConstraint(&evaluators); @@ -400,18 +391,6 @@ int DoMain(int argc, char* argv[]) { "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), right_hip_tracking_data.get()); - auto left_foot_yz_rel_tracking_data = - std::make_unique( - "left_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, - plant, plant, left_foot_yz_tracking_data.get(), - left_hip_yz_tracking_data.get()); - auto right_foot_yz_rel_tracking_data = - std::make_unique( - "right_ft_z_traj", osc_gains.K_p_liftoff_swing_foot, - osc_gains.K_d_liftoff_swing_foot, osc_gains.W_liftoff_swing_foot, - plant, plant, right_foot_yz_tracking_data.get(), - right_hip_yz_tracking_data.get()); auto pelvis_trans_rel_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, @@ -419,8 +398,6 @@ int DoMain(int argc, char* argv[]) { stance_foot_tracking_data.get()); left_foot_rel_tracking_data->SetViewFrame(pelvis_view_frame); right_foot_rel_tracking_data->SetViewFrame(pelvis_view_frame); - left_foot_yz_rel_tracking_data->SetViewFrame(pelvis_view_frame); - right_foot_yz_rel_tracking_data->SetViewFrame(pelvis_view_frame); pelvis_trans_rel_tracking_data->SetViewFrame(pelvis_view_frame); auto foot_traj_weight_trajectory = @@ -511,8 +488,6 @@ int DoMain(int argc, char* argv[]) { if (osc_gains.no_derivative_feedback) { left_foot_rel_tracking_data->SetNoDerivativeFeedback(true); right_foot_rel_tracking_data->SetNoDerivativeFeedback(true); - left_foot_yz_rel_tracking_data->SetNoDerivativeFeedback(true); - right_foot_yz_rel_tracking_data->SetNoDerivativeFeedback(true); pelvis_trans_rel_tracking_data->SetNoDerivativeFeedback(true); left_hip_yaw_tracking_data->SetNoDerivativeFeedback(true); right_hip_yaw_tracking_data->SetNoDerivativeFeedback(true); @@ -522,8 +497,6 @@ int DoMain(int argc, char* argv[]) { } else { left_foot_rel_tracking_data->SetImpactInvariantProjection(true); right_foot_rel_tracking_data->SetImpactInvariantProjection(true); - left_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); - right_foot_yz_rel_tracking_data->SetImpactInvariantProjection(true); pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); From 068cc5ccb5975c33d2ba1717858c86315b3eab86 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 10:49:19 -0500 Subject: [PATCH 389/758] cleaning up pelvis trajectory --- .../osc_running_controller_diagram.cc | 3 +- examples/Cassie/forward_command.py | 4 +-- examples/Cassie/osc_run/BUILD.bazel | 1 + .../Cassie/osc_run/foot_traj_generator.cc | 17 +--------- examples/Cassie/osc_run/osc_running_gains.h | 19 ----------- .../osc_run/pelvis_trans_traj_generator.cc | 33 ++++--------------- .../osc_run/pelvis_trans_traj_generator.h | 9 ----- examples/Cassie/run_osc_running_controller.cc | 4 +-- 8 files changed, 13 insertions(+), 77 deletions(-) diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 7b0bbe0a8f..691374c0a3 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -209,10 +209,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.vel_scale_trans_sagital, osc_running_gains.vel_scale_trans_lateral); - auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = builder.AddSystem( - plant, plant_context.get(), default_traj, feet_contact_points, + plant, plant_context.get(), feet_contact_points, osc_running_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams( osc_running_gains.rest_length, osc_running_gains.rest_length_offset); diff --git a/examples/Cassie/forward_command.py b/examples/Cassie/forward_command.py index d4e3ee05fc..35df29e94d 100644 --- a/examples/Cassie/forward_command.py +++ b/examples/Cassie/forward_command.py @@ -17,9 +17,9 @@ def main(): clock = pygame.time.Clock() done = False - max_speed = 2.9 + max_speed = 1.3 dt = .020 - acceleration = 1.25 # m/s^2 + acceleration = 0.5 # m/s^2 deceleration = 0.75 # m/s^2 max_speed_duration = 20 velocity_step_up = acceleration * dt diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 225322cc63..8432f50563 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -60,6 +60,7 @@ cc_library( deps = [ "//multibody:utils", "//systems/controllers/osc:osc_gains", + "//examples/Cassie/contact_scheduler:all", "//systems/primitives", "@drake//:drake_shared_library", ], diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 2c1137ef2c..045d64e164 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -130,18 +130,7 @@ EventStatus FootTrajGenerator::DiscreteVariableUpdate( &hip_pos); foot_pos = rot.transpose() * foot_pos; hip_pos = rot.transpose() * hip_pos; - // auto pelvis_vel = - // discrete_state->get_mutable_value(pelvis_vel_est_idx_); pelvis_vel = - // 0.99 * v.segment(3, 3) + 0.01 * pelvis_vel; auto last_stance_time = - // discrete_state->get_mutable_vector(pelvis_vel_est_idx_) - // .get_mutable_value(); - // last_stance_time[0] = robot_output->get_timestamp(); - // pelvis_vel = v.segment(3, 3); - // std::cout << "stance state: " << stance_state_ << std::endl; - // pelvis_vel = Vector3d::Zero(); } - // if (fsm_state(0) != stance_state_) { - // } return EventStatus::Succeeded(); } @@ -172,7 +161,6 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( sagital_radio_tuning += radio_out->channel[5]; } - VectorXd q = robot_output->GetPositions(); VectorXd v = robot_output->GetVelocities(); multibody::SetPositionsAndVelocitiesIfNew( plant_, robot_output->GetState(), context_); @@ -236,20 +224,17 @@ PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( if (start_pos(2) == 0) { Y[0](2) = -rest_length_; } - // Y[0](2) -= rest_length_offset_; Y[1] = start_pos + x_mid_point_ratio * (foot_end_pos_des - start_pos); double foot_height_scale = std::clamp(pelvis_vel[0] / 2.5, 1.0, 1.4); Y[1](2) += foot_height_scale * mid_foot_height_; Y[2] = foot_end_pos_des; - // corrections + // prevent foot collisions if (is_left_foot_) { - // Y[1](1) -= lateral_offset_; Y[1](1) = std::clamp(Y[1](1), lateral_offset_, 0.2); Y[2](1) = std::clamp(Y[2](1), lateral_offset_, 0.2); } else { - // Y[1](1) += lateral_offset_; Y[1](1) = std::clamp(Y[1](1), -0.2, -lateral_offset_); Y[2](1) = std::clamp(Y[2](1), -0.2, -lateral_offset_); } diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 72355943ce..52512cb828 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -16,12 +16,6 @@ struct OSCRunningGains : OSCGains { double w_hip_yaw; double hip_yaw_kp; double hip_yaw_kd; - double w_hip_pitch; - double hip_pitch_kp; - double hip_pitch_kd; - double w_hip_roll; - double hip_roll_kp; - double hip_roll_kd; double vel_scale_rot; double vel_scale_trans_sagital; double vel_scale_trans_lateral; @@ -74,9 +68,6 @@ struct OSCRunningGains : OSCGains { MatrixXd W_swing_foot; MatrixXd K_p_swing_foot; MatrixXd K_d_swing_foot; - MatrixXd W_liftoff_swing_foot; - MatrixXd K_p_liftoff_swing_foot; - MatrixXd K_d_liftoff_swing_foot; MatrixXd W_swing_toe; MatrixXd K_p_swing_toe; MatrixXd K_d_swing_toe; @@ -141,15 +132,6 @@ struct OSCRunningGains : OSCGains { K_d_swing_foot = Eigen::Map< Eigen::Matrix>( this->SwingFootKd.data(), 3, 3); - W_liftoff_swing_foot = Eigen::Map< - Eigen::Matrix>( - this->LiftoffSwingFootW.data(), 3, 3); - K_p_liftoff_swing_foot = Eigen::Map< - Eigen::Matrix>( - this->LiftoffSwingFootKp.data(), 3, 3); - K_d_liftoff_swing_foot = Eigen::Map< - Eigen::Matrix>( - this->LiftoffSwingFootKd.data(), 3, 3); W_pelvis = Eigen::Map< Eigen::Matrix>( this->PelvisW.data(), 3, 3); @@ -188,7 +170,6 @@ struct OSCRunningGains : OSCGains { W_pelvis *= weight_scaling; W_pelvis_rot *= weight_scaling; W_swing_foot *= weight_scaling; - W_liftoff_swing_foot *= weight_scaling; W_swing_toe *= weight_scaling; W_hip_yaw *= weight_scaling; } diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 6e3698861b..dc4cedb9de 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -2,6 +2,7 @@ #include +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" #include "multibody/multibody_utils.h" #include "systems/framework/output_vector.h" @@ -18,6 +19,7 @@ using Eigen::VectorXd; using dairlib::systems::OutputVector; using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; using drake::systems::Context; @@ -25,8 +27,6 @@ using drake::systems::DiscreteUpdateEvent; using drake::systems::DiscreteValues; using drake::systems::EventStatus; using drake::trajectories::PiecewisePolynomial; -// using drake::common::Polynomial; -using drake::multibody::JacobianWrtVariable; using drake::trajectories::Trajectory; namespace dairlib::examples::osc { @@ -34,7 +34,6 @@ namespace dairlib::examples::osc { PelvisTransTrajGenerator::PelvisTransTrajGenerator( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& traj, const std::unordered_map< int, std::vector&>>>& @@ -44,10 +43,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( context_(context), world_(plant_.world_frame()), pelvis_(plant_.GetBodyByName("pelvis")), - pelvis_frame_(pelvis_.body_frame()), - traj_(traj), - feet_contact_points_(feet_contact_points), - relative_pelvis_(relative_pelvis) { + feet_contact_points_(feet_contact_points){ this->set_name("pelvis_trans_traj_generator"); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( @@ -78,18 +74,9 @@ EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( return EventStatus::Succeeded(); } -PiecewisePolynomial PelvisTransTrajGenerator::GeneratePelvisTraj( - const VectorXd& x, double t, int fsm_state) const { - return traj_; -} - PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( const VectorXd& x, double t0, double tf, int fsm_state) const { - // fsm_state should be unused - if (fsm_state >= 2) { - // flight phase trajectory should be unused - return PiecewisePolynomial(); - } + DRAKE_DEMAND(fsm_state < 2); Vector3d f_g = drake::multibody::UniformGravityFieldElement().gravity_vector(); @@ -150,15 +137,9 @@ void PelvisTransTrajGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - // const drake::VectorX& x = robot_output->GetState(); - if (fsm_state == 0 || fsm_state == 1) { - if (relative_pelvis_) { - *casted_traj = GenerateSLIPTraj(robot_output->GetState(), mode_length[0], - mode_length[1], fsm_state); - } else { - *casted_traj = - GeneratePelvisTraj(robot_output->GetState(), clock, fsm_state); - } + if (fsm_state == LEFT_STANCE || fsm_state == RIGHT_STANCE) { + *casted_traj = GenerateSLIPTraj(robot_output->GetState(), mode_length[0], + mode_length[1], fsm_state); } } diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index 1557d96042..b8060b81ab 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -14,7 +14,6 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { PelvisTransTrajGenerator( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - drake::trajectories::PiecewisePolynomial& traj, const std::unordered_map< int, std::vector&>>>& @@ -41,9 +40,6 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { } private: - drake::trajectories::PiecewisePolynomial GeneratePelvisTraj( - const Eigen::VectorXd& x, double t, int fsm_state) const; - drake::trajectories::PiecewisePolynomial GenerateSLIPTraj( const Eigen::VectorXd& x, double t0, double tf, int fsm_state) const; @@ -58,11 +54,6 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { drake::systems::Context* context_; const drake::multibody::BodyFrame& world_; const drake::multibody::Body& pelvis_; - const drake::multibody::BodyFrame& pelvis_frame_; - const bool relative_pelvis_; - - // pelvis trajectory - drake::trajectories::PiecewisePolynomial traj_; // A list of pairs of contact body frame and contact point const std::unordered_map< diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 032d0f7ce1..05dd0766af 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -14,7 +14,6 @@ #include "examples/Cassie/osc/high_level_command.h" #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" -#include "examples/Cassie/osc_jump/toe_angle_traj_generator.h" #include "examples/Cassie/osc_run/foot_traj_generator.h" #include "examples/Cassie/osc_run/osc_running_gains.h" #include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" @@ -277,10 +276,9 @@ int DoMain(int argc, char* argv[]) { plant, plant_context.get(), osc_gains.vel_scale_rot, osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); - auto default_traj = PiecewisePolynomial(Vector3d{0, 0, 0}); auto pelvis_trans_traj_generator = builder.AddSystem( - plant, plant_context.get(), default_traj, feet_contact_points, + plant, plant_context.get(), feet_contact_points, osc_gains.relative_pelvis); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length, osc_gains.rest_length_offset); From acf8b5407b099ab2e558628765c0e3c7212373c3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 10:56:51 -0500 Subject: [PATCH 390/758] removing unused parts of code --- .../Cassie/diagrams/osc_running_controller_diagram.cc | 3 +-- examples/Cassie/osc_run/osc_running_gains.h | 4 ---- examples/Cassie/osc_run/osc_running_gains.yaml | 2 -- .../Cassie/osc_run/pelvis_trans_traj_generator.cc | 3 +-- examples/Cassie/osc_run/pelvis_trans_traj_generator.h | 3 +-- examples/Cassie/run_osc_running_controller.cc | 11 +++++------ 6 files changed, 8 insertions(+), 18 deletions(-) diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 691374c0a3..f5ce899a56 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -211,8 +211,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto pelvis_trans_traj_generator = builder.AddSystem( - plant, plant_context.get(), feet_contact_points, - osc_running_gains.relative_pelvis); + plant, plant_context.get(), feet_contact_points); pelvis_trans_traj_generator->SetSLIPParams( osc_running_gains.rest_length, osc_running_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h index 52512cb828..e1fe818dfe 100644 --- a/examples/Cassie/osc_run/osc_running_gains.h +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -20,8 +20,6 @@ struct OSCRunningGains : OSCGains { double vel_scale_trans_sagital; double vel_scale_trans_lateral; double target_vel_filter_alpha; - bool relative_feet; - bool relative_pelvis; bool no_derivative_feedback; double rest_length; double rest_length_offset; @@ -80,8 +78,6 @@ struct OSCRunningGains : OSCGains { OSCGains::Serialize(a); a->Visit(DRAKE_NVP(controller_frequency)); a->Visit(DRAKE_NVP(weight_scaling)); - a->Visit(DRAKE_NVP(relative_feet)); - a->Visit(DRAKE_NVP(relative_pelvis)); a->Visit(DRAKE_NVP(no_derivative_feedback)); a->Visit(DRAKE_NVP(rest_length)); a->Visit(DRAKE_NVP(rest_length_offset)); diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml index 4f703b77dc..4d0988cd35 100644 --- a/examples/Cassie/osc_run/osc_running_gains.yaml +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -26,8 +26,6 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] #w_soft_constraint: 1000000 -relative_feet: true -relative_pelvis: true no_derivative_feedback: false rot_filter_tau: 0.005 ekf_filter_tau: [ 0.05, 0.01, 0.001 ] diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index dc4cedb9de..43458eb5e7 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -37,8 +37,7 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( const std::unordered_map< int, std::vector&>>>& - feet_contact_points, - bool relative_pelvis) + feet_contact_points) : plant_(plant), context_(context), world_(plant_.world_frame()), diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index b8060b81ab..a6193b549a 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -17,8 +17,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const std::unordered_map< int, std::vector&>>>& - feet_contact_points, - bool relative_pelvis = false); + feet_contact_points); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 05dd0766af..8b874fa817 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -132,9 +132,9 @@ int DoMain(int argc, char* argv[]) { FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_gains_filename)); - // solvers::OSQPSettingsYaml osqp_settings = - // drake::yaml::LoadYamlFile( - // FindResourceOrThrow(FLAGS_osqp_settings)); + drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)) + .osqp_options; /**** FSM and contact mode configuration ****/ @@ -278,8 +278,7 @@ int DoMain(int argc, char* argv[]) { auto pelvis_trans_traj_generator = builder.AddSystem( - plant, plant_context.get(), feet_contact_points, - osc_gains.relative_pelvis); + plant, plant_context.get(), feet_contact_points); pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length, osc_gains.rest_length_offset); @@ -513,7 +512,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), VectorXd::Zero(1)); - osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); + osc->SetOsqpSolverOptions(solver_options); // Build OSC problem osc->Build(); std::cout << "Built OSC" << std::endl; From 0602a7a4ceab74e125bdf01529bf588563a816f5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 11:05:40 -0500 Subject: [PATCH 391/758] cleaning up main running controller file --- examples/Cassie/run_osc_running_controller.cc | 31 +++---------------- 1 file changed, 4 insertions(+), 27 deletions(-) diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 8b874fa817..ced95422d9 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -2,7 +2,6 @@ #include #include -#include #include #include "common/find_resource.h" @@ -104,8 +103,6 @@ int DoMain(int argc, char* argv[]) { auto right_toe = RightToeFront(plant); auto right_heel = RightToeRear(plant); - int nv = plant.num_velocities(); - // Create maps for joints map pos_map = multibody::MakeNameToPositionsMap(plant); map vel_map = multibody::MakeNameToVelocitiesMap(plant); @@ -115,10 +112,10 @@ int DoMain(int argc, char* argv[]) { int, std::vector&>>> feet_contact_points; - feet_contact_points[0] = std::vector< + feet_contact_points[LEFT_STANCE] = std::vector< std::pair&>>( {left_toe, left_heel}); - feet_contact_points[1] = std::vector< + feet_contact_points[RIGHT_STANCE] = std::vector< std::pair&>>( {right_toe, right_heel}); @@ -432,7 +429,7 @@ int DoMain(int argc, char* argv[]) { RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); -// pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); + pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); if (osc_gains.rot_filter_tau > 0) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, {1, 2}); @@ -587,10 +584,6 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("left_ft_traj")); builder.Connect(r_foot_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("right_ft_traj")); - // builder.Connect(l_foot_traj_generator->get_output_port(0), - // osc->get_input_port_tracking_data("left_ft_z_traj")); - // builder.Connect(r_foot_traj_generator->get_output_port(0), - // osc->get_input_port_tracking_data("right_ft_z_traj")); builder.Connect(left_toe_angle_traj_gen->get_output_port(0), osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), @@ -603,10 +596,6 @@ int DoMain(int argc, char* argv[]) { high_level_command->get_radio_input_port()); builder.Connect(osc->get_output_port_osc_command(), command_sender->get_input_port(0)); - // builder.Connect(osc->get_osc_output_port(), - // controller_frequency_regulator->get_input_port()); - // builder.Connect(controller_frequency_regulator->get_output_port(), - // command_sender->get_input_port(0)); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_debug(), @@ -618,25 +607,13 @@ int DoMain(int argc, char* argv[]) { builder.Connect(contact_scheduler->get_output_port_debug_info(), contact_scheduler_debug_publisher->get_input_port()); - // Run lcm-driven simulation - // Create the diagram auto owned_diagram = builder.Build(); owned_diagram->set_name(("osc_running_controller")); - // Run lcm-driven simulation + systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); - // std::cout << "waiting for messages" << std::endl; - // LcmHandleSubscriptionsUntil(&lcm, [&]() { - // return cassie_out_receiver->GetInternalMessageCount()>2; - // }); - // controller_frequency_regulator->LatchInputPortToState(&loop.get_diagram()->GetMutableSubsystemContext( - // *controller_frequency_regulator, - // &loop.get_diagram_mutable_context())); - // - // std::cout << "got message, starting simulator" << std::endl; - // loop.Simulate(); return 0; From 963007f7ad3f2933fee9801b96e6e98baa3a641b Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 14:00:33 -0500 Subject: [PATCH 392/758] working on cleaning up jumpnig controller --- .../Cassie/osc/swing_toe_traj_generator.cc | 15 +- .../osc_jump/flight_foot_traj_generator.cc | 40 +---- .../osc_jump/flight_foot_traj_generator.h | 3 +- .../osc_run/pelvis_trans_traj_generator.cc | 4 +- examples/Cassie/run_dircon_jumping.cc | 139 +----------------- examples/Cassie/run_osc_jumping_controller.cc | 54 +++---- 6 files changed, 45 insertions(+), 210 deletions(-) diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index 58db05345c..257b119def 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -26,16 +26,15 @@ SwingToeTrajGenerator::SwingToeTrajGenerator( feet_contact_points_(feet_contact_points) { DRAKE_DEMAND(feet_contact_points_.size() == 2); // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); + .get_index(); PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("toe_ang", traj_inst, + this->DeclareAbstractOutputPort("toe_angle", traj_inst, &SwingToeTrajGenerator::CalcTraj); } @@ -43,8 +42,6 @@ void SwingToeTrajGenerator::CalcTraj( const drake::systems::Context& context, Trajectory* traj) const { // Read in current state - - // Read in current state const OutputVector* robotOutput = (OutputVector*)this->EvalVectorInput(context, state_port_); VectorXd q = robotOutput->GetPositions(); @@ -54,6 +51,8 @@ void SwingToeTrajGenerator::CalcTraj( Vector3d pt_0; Vector3d pt_1; + // Calculate difference between toe and ground assuming flat ground + // Apply difference to current toe angle to use as desired plant_.CalcPointsPositions(*context_, feet_contact_points_[0].second, feet_contact_points_[0].first, world_, &pt_0); plant_.CalcPointsPositions(*context_, feet_contact_points_[1].second, @@ -61,10 +60,8 @@ void SwingToeTrajGenerator::CalcTraj( VectorXd foot = pt_0 - pt_1; double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); - // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; -// des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; auto* pp_traj = (PiecewisePolynomial*)dynamic_cast*>( diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc index 0893ac46dd..62ee294b3c 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc @@ -29,15 +29,13 @@ FlightFootTrajGenerator::FlightFootTrajGenerator( const string& hip_name, bool isLeftFoot, const PiecewisePolynomial& foot_traj, const PiecewisePolynomial& hip_traj, - bool relative_feet, double time_offset) : plant_(plant), context_(context), world_(plant.world_frame()), hip_frame_(plant.GetFrameByName(hip_name)), foot_traj_(foot_traj), - hip_traj_(hip_traj), - relative_feet_(relative_feet) { + hip_traj_(hip_traj){ PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -65,33 +63,6 @@ FlightFootTrajGenerator::FlightFootTrajGenerator( hip_traj_.shiftRight(time_offset); } -PiecewisePolynomial FlightFootTrajGenerator::GenerateFlightTraj( - const VectorXd& x, double t) const { - if (relative_feet_) { - plant_.SetPositionsAndVelocities(context_, x); - // Hip offset - Vector3d zero_offset = Vector3d::Zero(); - Vector3d hip_pos = Vector3d::Zero(); - plant_.CalcPointsPositions(*context_, hip_frame_, zero_offset, world_, - &hip_pos); - - const PiecewisePolynomial& foot_traj_segment = - foot_traj_.slice(foot_traj_.get_segment_index(t), 1); - - std::vector breaks = foot_traj_segment.get_segment_times(); - VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - MatrixXd hip_points(3, 2); - // Velocity estimates are generally bad - hip_points << hip_pos, hip_pos; - PiecewisePolynomial hip_offset = - PiecewisePolynomial::ZeroOrderHold(breaks_vector, hip_points); - - return foot_traj_segment + hip_offset; - } else { - return foot_traj_; - } -} - PiecewisePolynomial FlightFootTrajGenerator::GenerateRelativeTraj() const { return foot_traj_ - hip_traj_; @@ -104,17 +75,10 @@ void FlightFootTrajGenerator::CalcTraj( const auto robot_output = this->template EvalVectorInput(context, state_port_); VectorXd x = robot_output->GetState(); - double timestamp = robot_output->get_timestamp(); - auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if(relative_feet_){ - *casted_traj = GenerateRelativeTraj(); - } - else{ -// *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); - } + *casted_traj = GenerateRelativeTraj(); } } // namespace dairlib::examples::osc_jump diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.h b/examples/Cassie/osc_jump/flight_foot_traj_generator.h index c9a68341da..1d143ed869 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.h +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.h @@ -18,7 +18,7 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { bool isLeftFoot, const drake::trajectories::PiecewisePolynomial& foot_traj, const drake::trajectories::PiecewisePolynomial& hip_traj, - bool relative_feet = false, double time_offset = 0.0); + double time_offset = 0.0); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -43,7 +43,6 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { drake::trajectories::PiecewisePolynomial foot_traj_; drake::trajectories::PiecewisePolynomial hip_traj_; - bool relative_feet_; int state_port_; int fsm_port_; }; diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 43458eb5e7..0049e6796a 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -58,8 +58,8 @@ PelvisTransTrajGenerator::PelvisTransTrajGenerator( this->DeclareVectorInputPort("t_mode", BasicVector(6)) .get_index(); - PiecewisePolynomial empty_pp_traj(VectorXd(0)); - Trajectory& traj_inst = empty_pp_traj; + PiecewisePolynomial empty_traj(VectorXd(0)); + Trajectory& traj_inst = empty_traj; this->DeclareAbstractOutputPort("pelvis_trans_traj", traj_inst, &PelvisTransTrajGenerator::CalcTraj); diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 9684e39574..5c39c918e6 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -23,7 +23,6 @@ #include "drake/common/yaml/yaml_io.h" #include "drake/multibody/parsing/parser.h" -#include "drake/solvers/solve.h" #include "drake/systems/trajectory_optimization/multiple_shooting.h" using std::cout; @@ -36,7 +35,6 @@ using std::vector; using drake::geometry::SceneGraph; using drake::multibody::Parser; -using Eigen::Matrix3Xd; using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; @@ -47,16 +45,11 @@ using dairlib::multibody::KinematicEvaluator; using dairlib::multibody::KinematicEvaluatorSet; using dairlib::solvers::NonlinearCost; using dairlib::systems::trajectory_optimization::Dircon; -using dairlib::systems::trajectory_optimization::DirconDynamicConstraint; -using dairlib::systems::trajectory_optimization::DirconKinConstraintType; -using dairlib::systems::trajectory_optimization::DirconKinematicConstraint; using dairlib::systems::trajectory_optimization::DirconMode; using dairlib::systems::trajectory_optimization::DirconModeSequence; using dairlib::systems::trajectory_optimization::DirconOptions; -using dairlib::systems::trajectory_optimization::HybridDircon; using dairlib::systems::trajectory_optimization::PointPositionConstraint; using drake::VectorX; -using drake::math::RotationMatrix; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::Body; using drake::multibody::MultibodyPlant; @@ -72,54 +65,6 @@ DEFINE_string(jumping_parameters, "", "Jumping parameters"); namespace dairlib { -class JointAccelCost : public solvers::NonlinearCost { - public: - JointAccelCost(const MatrixXd& W_Q, - const drake::multibody::MultibodyPlant& plant, - const KinematicEvaluatorSet* constraints, - const std::string& description = "") - : solvers::NonlinearCost( - plant.num_positions() + plant.num_velocities() + - plant.num_actuators() + constraints->count_full(), - description), - plant_(plant), - context_(plant_.CreateDefaultContext()), - constraints_(constraints), - n_v_(plant.num_velocities()), - n_x_(plant.num_positions() + plant.num_velocities()), - n_u_(plant.num_actuators()), - n_lambda_(constraints->count_full()), - W_Q_(W_Q){}; - - private: - void EvaluateCost(const Eigen::Ref>& x, - drake::VectorX* y) const override { - DRAKE_ASSERT(x.size() == n_x_ + n_u_ + n_lambda_); - - // Extract our input variables: - const auto x0 = x.segment(0, n_x_); - const auto u0 = x.segment(n_x_, n_u_); - VectorXd l0 = x.segment(n_x_ + n_u_, n_lambda_); - - multibody::SetContext(plant_, x0, u0, context_.get()); - const VectorX xdot0 = - constraints_->CalcTimeDerivatives(*context_, &l0); - - (*y) = xdot0.tail(n_v_).transpose() * W_Q_ * xdot0.tail(n_v_); - }; - - const drake::multibody::MultibodyPlant& plant_; - std::unique_ptr> context_; - const KinematicEvaluatorSet* constraints_; - - int n_v_; - int n_x_; - int n_u_; - int n_lambda_; - - MatrixXd W_Q_; -}; - struct DirconJumpingParameters { // model urdfs std::string spring_urdf; @@ -358,10 +303,6 @@ void DoMain() { solver_options.SetOption(id, "print_timing_statistics", "yes"); // NOLINT solver_options.SetOption(id, "print_level", 5); // NOLINT solver_options.SetOption(id, "output_file", "../ipopt.out"); // NOLINT - // solver_options.SetOption(id, "acceptable_compl_inf_tol", tol); // - // NOLINT solver_options.SetOption(id, "acceptable_constr_viol_tol", - // tol); // NOLINT solver_options.SetOption(id, - // "acceptable_obj_change_tol", 1e-3); // NOLINT solver_options.SetOption(id, "acceptable_tol", gait_params.acceptable_tol); // NOLINT solver_options.SetOption(id, "acceptable_iter", @@ -379,23 +320,6 @@ void DoMain() { solver_options.SetOption(id, "Solution", "No"); // NOLINT solver_options.SetOption(id, "Major feasibility tolerance", gait_params.tol); // NOLINT - - // prog.SetSolverOption(id, "Print file", "../snopt.out"); - // prog.SetSolverOption(id, "Major iterations limit", 1e5); - // prog.SetSolverOption(id, "Iterations limit", 100000); - // prog.SetSolverOption(id, "Verify level", 0); - - // snopt doc said try 2 if seeing snopta exit 40 - // prog.SetSolverOption(id, "Scale option", 2); - // prog.SetSolverOption(id, ); - - // target nonlinear constraint violation - // prog.SetSolverOption(id, "Major optimality tolerance", 1e-5); - // prog.SetSolverOption(id, "Major optimality tolerance", - // 1e-5); - - // target complementarity gap - // prog.SetSolverOption(id, ); } std::cout << "Adding kinematic constraints: " << std::endl; @@ -502,8 +426,6 @@ void SetKinematicConstraints(Dircon* trajopt, // bounding box constraints on all decision variables for (int i = 0; i < mode_lengths.size(); ++i) { for (int j = 0; j < mode_lengths[i]; ++i) { - // auto state_vars_ij = trajopt->state_vars(i, j); - // auto input_vars_ij = trajopt->input_vars(i, j); auto force_vars_ij = trajopt->force_vars(i, j); prog->AddBoundingBoxConstraint( VectorXd::Constant(force_vars_ij.rows(), -200), @@ -642,8 +564,6 @@ void SetKinematicConstraints(Dircon* trajopt, prog->AddBoundingBoxConstraint(u_min, u_max, ui); if (i < trajopt->N() - 1) { auto uip1 = trajopt->input(i + 1); - // prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, 50)); - // prog->AddConstraint(ui - uip1 >= VectorXd::Constant(n_u, -50)); prog->AddConstraint(ui - uip1 <= VectorXd::Constant(n_u, gait_params.input_delta)); prog->AddConstraint(ui - uip1 >= @@ -768,13 +688,13 @@ void SetKinematicConstraints(Dircon* trajopt, // Only add constraints of lambdas for stance modes // ALL BUT THE LAST SEGMENT (to ensure the feet can leave the ground -// for (int index = 0; index < (mode_lengths[0] - 2); index++) { -// auto lambda = trajopt->force_vars(0, index); -// prog->AddLinearConstraint(lambda(2) >= 60); -// prog->AddLinearConstraint(lambda(5) >= 60); -// prog->AddLinearConstraint(lambda(8) >= 60); -// prog->AddLinearConstraint(lambda(11) >= 60); -// } + // for (int index = 0; index < (mode_lengths[0] - 2); index++) { + // auto lambda = trajopt->force_vars(0, index); + // prog->AddLinearConstraint(lambda(2) >= 60); + // prog->AddLinearConstraint(lambda(5) >= 60); + // prog->AddLinearConstraint(lambda(8) >= 60); + // prog->AddLinearConstraint(lambda(11) >= 60); + // } // Limit the ground reaction forces in the landing phase for (int index = 0; index < mode_lengths[2]; index++) { auto lambda = trajopt->force_vars(2, index); @@ -869,29 +789,10 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, } MatrixXd Q = gait_params.cost_scaling * 0.02 * MatrixXd::Identity(n_v, n_v); - // MatrixXd Q = 0.02 * MatrixXd::Identity(n_v - 3, n_v - 3); MatrixXd R = gait_params.cost_scaling * 1e-1 * MatrixXd::Identity(n_u, n_u); - // R(act_map.at("hip_roll_left_motor"), act_map.at("hip_roll_left_motor")) = - // 5e-1; - // R(act_map.at("hip_roll_right_motor"), act_map.at("hip_roll_right_motor")) - // = - // 5e-1; - // R(act_map.at("hip_yaw_left_motor"), act_map.at("hip_yaw_left_motor")) = - // 5e-1; R(act_map.at("hip_yaw_right_motor"), - // act_map.at("hip_yaw_right_motor")) = - // 5e-1; - // R(act_map.at("hip_pitch_left_motor"), act_map.at("hip_pitch_left_motor")) - // = - // 5e-5; - // R(act_map.at("hip_pitch_right_motor"), - // act_map.at("hip_pitch_right_motor")) = - // 5e-5; trajopt->AddRunningCost(x.tail(n_v - 3).transpose() * Q * x.tail(n_v - 3)); VectorXd q_f = VectorXd::Zero(n_q); - // VectorXd quat_identity(4); - // quat_identity << 1, 0, 0, 0; - // q_f.head(4) = quat_identity; q_f(pos_map.at("hip_yaw_left")) = 0; q_f(pos_map.at("hip_yaw_right")) = 0; q_f(pos_map.at("hip_roll_left")) = 0; @@ -914,32 +815,6 @@ void AddCosts(Dircon* trajopt, const MultibodyPlant& plant, trajopt->AddRunningCost((x.segment(13, 3) - q_f_target_right).transpose() * Q_right * (x.segment(13, 3) - q_f_target_right)); trajopt->AddRunningCost(u.transpose() * R * u); - - // vector mode_lengths = {gait_params.knot_points, - // gait_params.knot_points, - // gait_params.knot_points}; - // MatrixXd W = 1e-1 * MatrixXd::Identity(n_v, n_v); - // W(vel_map["hip_pitch_leftdot"], vel_map["hip_pitch_leftdot"]) = 1e2; - // W(vel_map["hip_pitch_rightdot"], vel_map["hip_pitch_rightdot"]) = 1e2; - // W(vel_map["hip_roll_leftdot"], vel_map["hip_roll_leftdot"]) = 5e1; - // W(vel_map["hip_roll_rightdot"], vel_map["hip_roll_rightdot"]) = 5e1; - // W(vel_map["hip_yaw_leftdot"], vel_map["hip_yaw_leftdot"]) *= 1e2; - // W(vel_map["hip_yaw_rightdot"], vel_map["hip_yaw_rightdot"]) *= 1e2; - // W(vel_map["toe_leftdot"], vel_map["toe_leftdot"]) = 1e-4; - // W(vel_map["toe_rightdot"], vel_map["toe_rightdot"]) = 1e-4; - // W *= 2.0 * gait_params.cost_scaling; - // vector> joint_accel_costs; - // for (int mode : {0, 1, 2}) { - // joint_accel_costs.push_back(std::make_shared( - // W, plant, &constraints->mode(mode).evaluators())); - // for (int index = 0; index < mode_lengths[mode]; index++) { - // // Assumes mode_lengths are the same across modes - // auto x_i = trajopt->state_vars(mode, index); - // auto u_i = trajopt->input_vars(mode, index); - // auto l_i = trajopt->force_vars(mode, index); - // trajopt->prog().AddCost(joint_accel_costs[mode], {x_i, u_i, l_i}); - // } - // } } void SetInitialGuessFromDirconTrajectory(Dircon& trajopt, diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 6b10d8286f..8e39aa5b6e 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -87,7 +87,8 @@ DEFINE_string(traj_name, "jumping_0.15h_0.3d", "File to load saved trajectories from"); DEFINE_string(gains_filename, "examples/Cassie/osc_jump/osc_jumping_gains.yaml", "Filepath containing gains"); -DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", "Filepath containing qp settings"); int DoMain(int argc, char* argv[]) { @@ -153,28 +154,28 @@ int DoMain(int argc, char* argv[]) { for (int mode = 0; mode < dircon_trajectory.GetNumModes(); ++mode) { const LcmTrajectory::Trajectory lcm_pelvis_trans_trajectory = output_trajs.GetTrajectory("pelvis_trans_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_foot_traj = output_trajs.GetTrajectory("left_foot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_foot_traj = output_trajs.GetTrajectory("right_foot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_hip_traj = output_trajs.GetTrajectory("left_hip_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_hip_traj = output_trajs.GetTrajectory("right_hip_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_toe_traj = output_trajs.GetTrajectory("left_toe_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_toe_traj = output_trajs.GetTrajectory("right_toe_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_pelvis_rot_traj = output_trajs.GetTrajectory("pelvis_rot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); pelvis_trans_traj.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_pelvis_trans_trajectory.time_vector, @@ -220,7 +221,7 @@ int DoMain(int argc, char* argv[]) { double flight_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(1)(0); double land_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(2)(0) + - osc_gains.landing_delay; + osc_gains.landing_delay; std::vector transition_times = {0.0, FLAGS_delay_time, flight_time, land_time}; @@ -248,16 +249,17 @@ int DoMain(int argc, char* argv[]) { feet_contact_points, FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_left", true, l_foot_trajectory, - l_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); + l_hip_trajectory, FLAGS_delay_time); auto r_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_right", false, r_foot_trajectory, - r_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); + r_hip_trajectory, FLAGS_delay_time); auto pelvis_rot_traj_generator = builder.AddSystem( pelvis_rot_trajectory, "pelvis_rot_traj", FLAGS_delay_time); auto fsm = builder.AddSystem( plant_w_spr, transition_times, FLAGS_contact_based_fsm, - gains.impact_threshold, (osc_jump::JUMPING_FSM_STATE)FLAGS_init_fsm_state); + gains.impact_threshold, + (osc_jump::JUMPING_FSM_STATE)FLAGS_init_fsm_state); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -289,8 +291,6 @@ int DoMain(int argc, char* argv[]) { contact_results_sub = builder.AddSystem( LcmSubscriberSystem::Make( "CASSIE_CONTACT_FOR_FSM_DISPATCHER", &lcm)); - // TODO(yangwill): Add PR for GM contact observer, currently in - // gm_contact_estimator branch } else { std::cerr << "Unknown simulator type!" << std::endl; } @@ -300,12 +300,13 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingCostWeights(1e-3 * gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.w_input * + gains.W_input_regularization); osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaContactRegularizationWeight( - gains.w_lambda * gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); + osc->SetLambdaContactRegularizationWeight(gains.w_lambda * + gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * + gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); @@ -324,8 +325,8 @@ int DoMain(int argc, char* argv[]) { auto right_heel_evaluator = multibody::WorldPointEvaluator( plant_w_spr, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - vector stance_modes = {osc_jump::BALANCE, - osc_jump::CROUCH, osc_jump::LAND}; + vector stance_modes = { + osc_jump::BALANCE, osc_jump::CROUCH, osc_jump::LAND}; for (auto mode : stance_modes) { osc->AddStateAndContactPoint(mode, &left_toe_evaluator); osc->AddStateAndContactPoint(mode, &left_heel_evaluator); @@ -333,7 +334,6 @@ int DoMain(int argc, char* argv[]) { osc->AddStateAndContactPoint(mode, &right_heel_evaluator); } - multibody::KinematicEvaluatorSet evaluators(plant_w_spr); // Fix the springs in the dynamics @@ -503,9 +503,8 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), osc->get_input_port_tracking_data("right_toe_angle_traj")); - builder.Connect( - pelvis_rot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("pelvis_rot_traj")); + builder.Connect(pelvis_rot_traj_generator->get_output_port(0), + osc->get_input_port_tracking_data("pelvis_rot_traj")); // FSM connections builder.Connect(contact_results_sub->get_output_port(), @@ -540,7 +539,8 @@ int DoMain(int argc, char* argv[]) { command_sender->get_input_port(0)); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); builder.Connect(osc->get_output_port_failure(), failure_aggregator->get_input_port(0)); builder.Connect(failure_aggregator->get_status_output_port(), From 111473a0086a2075b8c29d252faff3c9a66cd568 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 14:44:34 -0500 Subject: [PATCH 393/758] cleaning up contact scheduler --- .../contact_scheduler/contact_scheduler.cc | 36 +++++++++++-------- .../contact_scheduler/contact_scheduler.h | 12 +++---- .../osc/rot_space_tracking_data.cc | 22 ++++++------ .../osc/trans_space_tracking_data.cc | 25 +++---------- 4 files changed, 42 insertions(+), 53 deletions(-) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 2b53752f1c..934729f84f 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -37,6 +37,8 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, near_impact_threshold_(near_impact_threshold), tau_(tau), blend_func_(blend_func) { + DRAKE_DEMAND(tau_ > 0); + DRAKE_DEMAND(near_impact_threshold_ >= 0); this->set_name("ContactScheduler"); // Declare system ports state_port_ = this->DeclareVectorInputPort( @@ -75,8 +77,6 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, {0.00, LEFT_STANCE}, {0.25, LEFT_FLIGHT}, {0.35, RIGHT_STANCE}}; - // transition_times_index_ = DeclareAbstractState( - // drake::Value>{{0.1, 0.3, 0.4, 0.6}}); VectorXd initial_transition_times = VectorXd::Zero(4); initial_transition_times << -0.1, 0.0, 0.25, 0.35; transition_times_index_ = DeclareDiscreteState(initial_transition_times); @@ -95,6 +95,10 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, EventStatus ContactScheduler::UpdateTransitionTimes( const Context& context, State* state) const { + DRAKE_DEMAND(rest_length_ > 0); + DRAKE_DEMAND(stance_duration_ > 0); + DRAKE_DEMAND(flight_duration_ > 0); + const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); double current_time = robot_output->get_timestamp(); @@ -104,7 +108,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( auto transition_times = state->get_mutable_discrete_state(transition_times_index_) .get_mutable_value(); - std::vector>& upcoming_transitions = + auto& upcoming_transitions = state->get_mutable_abstract_state< std::vector>>( upcoming_transitions_index_); @@ -168,10 +172,8 @@ EventStatus ContactScheduler::UpdateTransitionTimes( double pelvis_zdot = robot_output->GetVelocityAtIndex(5); if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { - // Store the ground height of the stance foot - - // TODO(yangwill): calculate end of stance duration - double stance_scale = (pelvis_z)/ (rest_length_); + // This is a very crude approximation + double stance_scale = (pelvis_z) / (rest_length_); stance_scale = std::clamp(stance_scale, 1 - stance_variance_, 1 + stance_variance_); double next_transition_time = @@ -244,10 +246,9 @@ void ContactScheduler::CalcNextImpactInfo( const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); - const std::vector>& - upcoming_transitions = context.get_abstract_state< - std::vector>>( - upcoming_transitions_index_); + const auto& upcoming_transitions = context.get_abstract_state< + std::vector>>( + upcoming_transitions_index_); // Assign the blending function ptr auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; @@ -261,9 +262,6 @@ void ContactScheduler::CalcNextImpactInfo( RUNNING_FSM_STATE current_state = upcoming_transitions.at(2).second; double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ : near_impact_threshold_; - // Check if we're close to an impact event either upcoming or one that just - // happened - // Check if the upcoming state has an impact if (impact_states_.count(transition_state) != 0) { if (abs(current_time - transition_time) < blend_window) { @@ -302,7 +300,7 @@ void ContactScheduler::CalcClock(const Context& context, void ContactScheduler::CalcContactScheduler( const Context& context, BasicVector* contact_timing) const { // Read in lcm message time - RUNNING_FSM_STATE current_state_ = + auto current_state_ = (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; double nominal_stance_duration = context.get_discrete_state(nominal_state_durations_index_)[0]; @@ -310,6 +308,14 @@ void ContactScheduler::CalcContactScheduler( context.get_discrete_state(nominal_state_durations_index_)[1]; auto transition_times = context.get_discrete_state(transition_times_index_).value(); + /// Timing indices: order goes from start time to end time for when the + /// tracking objective is active. + /// PelvisTouchdown = 0 + /// PelvisLiftoff = 1 + /// LeftFootLiftoff = 2 + /// LeftFootTouchdown = 3 + /// RightFootLiftoff = 4 + /// RightFootTouchdown = 5 if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_FLIGHT) { contact_timing->get_mutable_value()(0) = transition_times[LEFT_STANCE]; contact_timing->get_mutable_value()(1) = transition_times[LEFT_FLIGHT]; diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index f6ee15d879..9ba4f2e92b 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -88,8 +88,6 @@ class ContactScheduler : public drake::systems::LeafSystem { double tau_; const BLEND_FUNC blend_func_; - int initial_state_ = 0; - drake::systems::DiscreteStateIndex stored_fsm_state_index_; drake::systems::DiscreteStateIndex stored_robot_state_index_; drake::systems::DiscreteStateIndex stored_transition_time_index_; @@ -102,11 +100,11 @@ class ContactScheduler : public drake::systems::LeafSystem { drake::systems::AbstractStateIndex upcoming_transitions_index_; /// SLIP parameters - double rest_length_; - double stance_duration_; - double flight_duration_; - double stance_variance_; - double flight_variance_; + double rest_length_ = 0.0; + double stance_duration_ = 0.0; + double flight_duration_ = 0.0; + double stance_variance_ = 0.0; + double flight_variance_ = 0.0; }; } // namespace dairlib diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index a271628b46..d5a065d6fb 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -1,4 +1,5 @@ #include "rot_space_tracking_data.h" + #include using Eigen::Isometry3d; @@ -26,7 +27,6 @@ RotTaskSpaceTrackingData::RotTaskSpaceTrackingData( is_rotational_tracking_data_ = true; } - void RotTaskSpaceTrackingData::AddFrameToTrack( const std::string& body_name, const Eigen::Isometry3d& frame_pose) { AddStateAndFrameToTrack(-1, body_name, frame_pose); @@ -35,7 +35,6 @@ void RotTaskSpaceTrackingData::AddStateAndFrameToTrack( int fsm_state, const std::string& body_name, const Eigen::Isometry3d& frame_pose) { AddFiniteStateToTrack(fsm_state); - // AddPointToTrack(body_name, pt_on_body); DRAKE_DEMAND(plant_w_spr_.HasBodyNamed(body_name)); DRAKE_DEMAND(plant_wo_spr_.HasBodyNamed(body_name)); body_frames_w_spr_[fsm_state] = @@ -45,15 +44,13 @@ void RotTaskSpaceTrackingData::AddStateAndFrameToTrack( frame_poses_[fsm_state] = frame_pose; } - - void RotTaskSpaceTrackingData::UpdateY(const VectorXd& x_w_spr, const Context& context_w_spr) { auto transform_mat = plant_w_spr_.CalcRelativeTransform( context_w_spr, plant_w_spr_.world_frame(), *body_frames_w_spr_[fsm_state_]); Quaterniond y_quat(transform_mat.rotation() * - frame_poses_[fsm_state_].linear()); + frame_poses_[fsm_state_].linear()); Eigen::Vector4d y_4d; y_4d << y_quat.w(), y_quat.vec(); y_ = y_4d; @@ -67,9 +64,9 @@ void RotTaskSpaceTrackingData::UpdateYError() { Quaterniond y_quat(y_(0), y_(1), y_(2), y_(3)); // Get relative quaternion (from current to desired) - Quaterniond relative_qaut = (y_quat_des * y_quat.inverse()).normalized(); - double theta = 2 * acos(relative_qaut.w()); - Vector3d rot_axis = relative_qaut.vec().normalized(); + Quaterniond relative_quat = (y_quat_des * y_quat.inverse()).normalized(); + double theta = 2 * acos(relative_quat.w()); + Vector3d rot_axis = relative_quat.vec().normalized(); error_y_ = theta * rot_axis; if (with_view_frame_) error_y_ = view_frame_rot_T_ * error_y_; } @@ -82,7 +79,7 @@ void RotTaskSpaceTrackingData::UpdateYdot( frame_poses_[fsm_state_].translation(), world_w_spr_, world_w_spr_, &J_spatial); ydot_ = J_spatial.block(0, 0, kSpaceDim, J_spatial.cols()) * - x_w_spr.tail(plant_w_spr_.num_velocities()); + x_w_spr.tail(plant_w_spr_.num_velocities()); } void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { @@ -92,7 +89,9 @@ void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { ydot_des_(3)); Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); error_ydot_ = w_des_ - ydot_ - GetJ() * v_proj; - if (with_view_frame_) error_ydot_ = view_frame_rot_T_ * error_ydot_; + if (with_view_frame_) { + error_ydot_ = view_frame_rot_T_ * error_ydot_; + } ydot_des_ = w_des_; // Overwrite 4d quat_dot with 3d omega. Need this for osc logging @@ -131,7 +130,8 @@ void RotTaskSpaceTrackingData::UpdateYddotDes(double, double) { "acceleration"; } if (ff_accel_multiplier_traj_ != nullptr) { - std::cerr << "RotTaskSpaceTrackingData does not support feedforward multipliers "; + std::cerr + << "RotTaskSpaceTrackingData does not support feedforward multipliers "; } } diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index ed0701fc9d..c6dd155001 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -1,4 +1,5 @@ #include "trans_space_tracking_data.h" + #include using Eigen::MatrixXd; @@ -19,8 +20,7 @@ TransTaskSpaceTrackingData::TransTaskSpaceTrackingData( const MatrixXd& W, const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) : OptionsTrackingData(name, kSpaceDim, kSpaceDim, K_p, K_d, W, plant_w_spr, - plant_wo_spr) { -} + plant_wo_spr) {} void TransTaskSpaceTrackingData::AddPointToTrack(const std::string& body_name, const Vector3d& pt_on_body) { @@ -63,21 +63,6 @@ void TransTaskSpaceTrackingData::UpdateJ( context_wo_spr, JacobianWrtVariable::kV, *body_frames_wo_spr_.at(fsm_state_), pts_on_body_[fsm_state_], world_wo_spr_, world_wo_spr_, &J_); -// if (fsm_state_ < 2) { -// J_(2, 8) = 0; -// J_(2, 16) = 0; -// J_(2, 6) = 0; -// J_(2, 14) = 0; -// } -// if (fsm_state_ >= 2) { -// J_(2, 7) = 0; -// J_(2, 15) = 0; -// J_(2, 6) = 0; -// J_(2, 14) = 0; -// } - if (J_.hasNaN()) { - std::cout << "Jacobian has NaNs" << std::endl; - } } void TransTaskSpaceTrackingData::UpdateJdotV( @@ -89,8 +74,8 @@ void TransTaskSpaceTrackingData::UpdateJdotV( } void TransTaskSpaceTrackingData::CheckDerivedOscTrackingData() { - if (!body_frames_w_spr_.empty()) { - body_frames_w_spr_ = body_frames_wo_spr_; - } + if (!body_frames_w_spr_.empty()) { + body_frames_w_spr_ = body_frames_wo_spr_; + } } } // namespace dairlib::systems::controllers From f65ca25cdd997fd051a9a48107de45fd2ccb5423 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 14:48:56 -0500 Subject: [PATCH 394/758] small cleanup in gym env --- examples/Cassie/closed_loop_running_sim.cc | 1 - 1 file changed, 1 deletion(-) diff --git a/examples/Cassie/closed_loop_running_sim.cc b/examples/Cassie/closed_loop_running_sim.cc index e9fefdf2c5..74aaf3cd41 100644 --- a/examples/Cassie/closed_loop_running_sim.cc +++ b/examples/Cassie/closed_loop_running_sim.cc @@ -75,7 +75,6 @@ int DoMain(int argc, char* argv[]) { new_plant.SetPositionsAndVelocities(&plant_context, x_init); simulator.Initialize(); - // auto sim = drake::systems::Simulator(diagram); std::cout << "advancing simulator: " << std::endl; simulator.AdvanceTo(5.0); } From 2d62517efc6558c91de49958a9776a08bbf8b8dd Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Mar 2023 16:40:24 -0500 Subject: [PATCH 395/758] adding running and jumping changes --- common/eigen_utils.cc | 11 + common/eigen_utils.h | 10 +- examples/Cassie/BUILD.bazel | 81 +-- examples/Cassie/cassie_state_estimator.cc | 7 +- examples/Cassie/cassie_state_estimator.h | 8 +- examples/Cassie/contact_scheduler/BUILD.bazel | 35 + .../contact_scheduler/contact_scheduler.cc | 363 ++++++++++ .../contact_scheduler/contact_scheduler.h | 110 +++ .../state_based_controller_switch.cc | 137 ++++ examples/Cassie/dispatcher_robot_in.cc | 38 +- examples/Cassie/dispatcher_robot_out.cc | 4 + examples/Cassie/osc/BUILD.bazel | 15 +- examples/Cassie/osc/high_level_command.cc | 43 +- examples/Cassie/osc/high_level_command.h | 12 +- examples/Cassie/osc/osc_standing_gains.h | 86 +++ examples/Cassie/osc/osc_standing_gains.yaml | 91 +-- examples/Cassie/osc/osc_walking_gains.h | 19 + examples/Cassie/osc/osc_walking_gains.yaml | 3 +- examples/Cassie/osc/osc_walking_gains_alip.h | 22 +- .../Cassie/osc/osc_walking_gains_alip.yaml | 33 +- .../Cassie/osc/swing_toe_traj_generator.cc | 14 +- .../Cassie/osc/swing_toe_traj_generator.h | 2 +- examples/Cassie/osc_jump/BUILD.bazel | 4 - .../osc_jump/flight_foot_traj_generator.cc | 40 +- .../osc_jump/flight_foot_traj_generator.h | 3 +- examples/Cassie/osc_jump/osc_jumping_gains.h | 10 +- .../Cassie/osc_jump/osc_jumping_gains.yaml | 79 ++- .../osc_jump/pelvis_trans_traj_generator.cc | 14 +- .../osc_jump/pelvis_trans_traj_generator.h | 13 +- .../osc_jump/toe_angle_traj_generator.cc | 10 +- examples/Cassie/osc_run/BUILD.bazel | 82 +++ .../osc_run/convert_traj_for_controller.cc | 392 +++++++++++ .../Cassie/osc_run/foot_traj_generator.cc | 272 ++++++++ examples/Cassie/osc_run/foot_traj_generator.h | 104 +++ examples/Cassie/osc_run/osc_running_gains.h | 172 +++++ .../Cassie/osc_run/osc_running_gains.yaml | 111 ++++ .../osc_run/osc_running_qp_settings.yaml | 22 + .../osc_run/pelvis_trans_traj_generator.cc | 145 ++++ .../osc_run/pelvis_trans_traj_generator.h | 75 +++ examples/Cassie/run_osc_jumping_controller.cc | 89 +-- examples/Cassie/run_osc_running_controller.cc | 626 ++++++++++++++++++ .../Cassie/run_osc_standing_controller.cc | 118 +--- examples/Cassie/run_osc_walking_controller.cc | 16 +- .../Cassie/run_osc_walking_controller_alip.cc | 16 +- examples/Cassie/systems/input_supervisor.cc | 51 +- examples/Cassie/systems/input_supervisor.h | 7 +- lcmtypes/lcmt_contact_timing.lcm | 11 + systems/controllers/BUILD.bazel | 11 + systems/controllers/lipm_traj_gen.cc | 2 +- systems/controllers/osc/BUILD.bazel | 1 + .../osc/joint_space_tracking_data.cc | 2 +- .../osc/operational_space_control.cc | 37 +- .../osc/operational_space_control.h | 2 +- .../controllers/osc/options_tracking_data.cc | 108 +-- .../controllers/osc/options_tracking_data.h | 36 +- systems/controllers/osc/osc_gains.h | 3 + systems/controllers/osc/osc_tracking_data.cc | 16 +- systems/controllers/osc/osc_tracking_data.h | 20 +- .../osc/relative_translation_tracking_data.cc | 2 +- .../osc/rot_space_tracking_data.cc | 28 +- .../osc/trans_space_tracking_data.cc | 11 +- systems/controllers/time_based_fsm.h | 8 +- 62 files changed, 3378 insertions(+), 535 deletions(-) create mode 100644 examples/Cassie/contact_scheduler/BUILD.bazel create mode 100644 examples/Cassie/contact_scheduler/contact_scheduler.cc create mode 100644 examples/Cassie/contact_scheduler/contact_scheduler.h create mode 100644 examples/Cassie/contact_scheduler/state_based_controller_switch.cc create mode 100644 examples/Cassie/osc/osc_standing_gains.h create mode 100644 examples/Cassie/osc_run/BUILD.bazel create mode 100644 examples/Cassie/osc_run/convert_traj_for_controller.cc create mode 100644 examples/Cassie/osc_run/foot_traj_generator.cc create mode 100644 examples/Cassie/osc_run/foot_traj_generator.h create mode 100644 examples/Cassie/osc_run/osc_running_gains.h create mode 100644 examples/Cassie/osc_run/osc_running_gains.yaml create mode 100644 examples/Cassie/osc_run/osc_running_qp_settings.yaml create mode 100644 examples/Cassie/osc_run/pelvis_trans_traj_generator.cc create mode 100644 examples/Cassie/osc_run/pelvis_trans_traj_generator.h create mode 100644 examples/Cassie/run_osc_running_controller.cc create mode 100644 lcmtypes/lcmt_contact_timing.lcm diff --git a/common/eigen_utils.cc b/common/eigen_utils.cc index 094b732e88..fdaa6d9d1b 100644 --- a/common/eigen_utils.cc +++ b/common/eigen_utils.cc @@ -4,4 +4,15 @@ std::vector CopyVectorXdToStdVector( const Eigen::VectorXd& eigen_vec) { return std::vector(eigen_vec.data(), eigen_vec.data() + eigen_vec.size()); +} + +Eigen::VectorXd eigen_clamp( + const Eigen::VectorXd& value, const Eigen::VectorXd& lb, const Eigen::VectorXd& ub){ + DRAKE_DEMAND(value.size() == lb.size()); + DRAKE_DEMAND(value.size() == ub.size()); + Eigen::VectorXd clamped_value(value.size()); + for (int i = 0; i < value.size(); ++i){ + clamped_value[i] = std::clamp(value[i], lb[i], ub[i]); + } + return clamped_value; } \ No newline at end of file diff --git a/common/eigen_utils.h b/common/eigen_utils.h index 2843f3d037..17d6cff4c0 100644 --- a/common/eigen_utils.h +++ b/common/eigen_utils.h @@ -1,7 +1,13 @@ #include + #include +#include "drake/common/drake_assert.h" + /// CopyVectorXdToStdVector returns an std::vector which is converted /// from an Eigen::VectorXd. -std::vector CopyVectorXdToStdVector( - const Eigen::VectorXd& eigen_vec); +std::vector CopyVectorXdToStdVector(const Eigen::VectorXd& eigen_vec); + +Eigen::VectorXd eigen_clamp(const Eigen::VectorXd& value, + const Eigen::VectorXd& lb, + const Eigen::VectorXd& ub); diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 0eb5ccfb6d..0e0bcdd211 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -47,9 +47,11 @@ cc_library( "//examples/Cassie:multibody_sim", "//examples/Cassie:run_controller_switch", "//examples/Cassie:run_osc_jumping_controller", + "//examples/Cassie:run_osc_running_controller", "//examples/Cassie:run_osc_standing_controller", "//examples/Cassie:run_osc_walking_controller_alip", "//examples/Cassie:run_pd_controller", + "//examples/Cassie/contact_scheduler:state_based_controller_switch", "//examples/Cassie/osc", ], ) @@ -164,22 +166,6 @@ cc_binary( ], ) -cc_binary( - name = "run_simple_sim", - srcs = ["run_simple_sim.cc"], - deprecation = "Attic/RigidBodyTree is deprecated.", - tags = ["manual"], - deps = [ - ":cassie_urdf", - ":cassie_utils", - "//attic/multibody:multibody_solvers", - "//systems:robot_lcm_systems", - "//systems/primitives", - "@drake//:drake_shared_library", - "@gflags", - ], -) - cc_binary( name = "multibody_sim", srcs = ["multibody_sim.cc"], @@ -190,9 +176,9 @@ cc_binary( "//examples/Cassie/systems:cassie_encoder", "//solvers:optimization_utils", "//systems:robot_lcm_systems", - "//systems:system_utils", - "//systems/framework:vector", + "//systems/framework:geared_motor", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -240,7 +226,6 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/primitives:vector_aggregator", "@drake//:drake_shared_library", - "@lcm", ], ) @@ -257,6 +242,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -276,6 +262,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems/controllers:linear_controller", "//systems/controllers:pd_config_lcm", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -300,8 +287,8 @@ cc_binary( deps = [ "//lcmtypes:lcmt_robot", "@drake//lcm", - "@gflags", "@lcm", + "@gflags", ], ) @@ -311,8 +298,8 @@ cc_binary( deps = [ "//lcmtypes:lcmt_robot", "@drake//lcm", - "@gflags", "@lcm", + "@gflags", ], ) @@ -342,6 +329,32 @@ cc_binary( "//systems:system_utils", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems/primitives:gaussian_noise_pass_through", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "run_osc_running_controller", + srcs = ["run_osc_running_controller.cc"], + deps = [ + ":cassie_urdf", + ":cassie_utils", + "//examples/Cassie/osc", + "//examples/Cassie/contact_scheduler:all", + "//examples/Cassie/systems:cassie_out_to_radio", + "//examples/Cassie/osc_jump", + "//examples/Cassie/osc_run", + "//lcm:trajectory_saver", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/filters:floating_base_velocity_filter", + "//systems/controllers/osc:osc_tracking_datas", + "//systems/controllers:controllers_all", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", "@drake//:drake_shared_library", "@gflags", ], @@ -361,9 +374,10 @@ cc_binary( "//multibody/kinematic", "//systems:robot_lcm_systems", "//systems/controllers:fsm_event_time", - "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems/controllers:controllers_all", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -376,6 +390,7 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//examples/Cassie/osc", + "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//examples/Cassie/systems:cassie_out_to_radio", "//examples/Cassie/systems:simulator_drift", "//multibody:utils", @@ -385,6 +400,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers:fsm_event_time", + "//systems/controllers:controllers_all", "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", @@ -405,8 +421,10 @@ cc_binary( "//multibody/kinematic", "//systems:robot_lcm_systems", "//systems/controllers/osc:operational_space_control", + "//systems/controllers/osc:osc_gains", "//systems/framework:lcm_driven_loop", "//systems/primitives", + "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -451,8 +469,8 @@ cc_binary( cc_binary( name = "run_dircon_jumping", srcs = ["run_dircon_jumping.cc"], - data = glob(["examples/Cassie/urdf/cassie_fixed_springs.urdf"]), deps = [ + ":cassie_urdf", ":cassie_utils", "//common", "//lcm:dircon_trajectory_saver", @@ -518,18 +536,6 @@ py_binary( ], ) -py_binary( - name = "cassie_virtual_remote_py", - srcs = ["cassie_virtual_remote.py"], - data = [ - "@lcm//:lcm-python", - ], - main = "cassie_virtual_remote.py", - deps = [ - "//lcmtypes:lcmtypes_robot_py", - ], -) - py_binary( name = "cassie_xbox_remote_py", srcs = ["cassie_xbox_remote.py"], @@ -544,11 +550,6 @@ py_binary( load("@drake//tools/skylark:drake_runfiles_binary.bzl", "drake_runfiles_binary") -drake_runfiles_binary( - name = "cassie_virtual_remote", - target = "cassie_virtual_remote_py", -) - drake_runfiles_binary( name = "cassie_xbox_remote", target = "cassie_xbox_remote_py", diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index b7dddf9e8b..9d55c02176 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -228,8 +228,7 @@ void CassieStateEstimator::solveFourbarLinkage( double spring_length = rod_on_heel_springs_[0].first.norm(); // Spring rest angle offset double spring_rest_offset = - atan(rod_on_heel_springs_[0].first(1) / rod_on_heel_springs_[0].first(0)); - + atan2(rod_on_heel_springs_[0].first(1), rod_on_heel_springs_[0].first(0)); plant_.SetPositions(context_.get(), q); for (int i = 0; i < 2; i++) { @@ -779,9 +778,9 @@ EventStatus CassieStateEstimator::Update( std::vector> contacts; contacts.push_back(std::pair(0, left_contact)); - contacts.push_back(std::pair(1, left_contact)); +// contacts.push_back(std::pair(1, left_contact)); contacts.push_back(std::pair(2, right_contact)); - contacts.push_back(std::pair(3, right_contact)); +// contacts.push_back(std::pair(3, right_contact)); ekf.setContacts(contacts); // Step 4 - EKF (measurement step) diff --git a/examples/Cassie/cassie_state_estimator.h b/examples/Cassie/cassie_state_estimator.h index 509506a2da..d0be8f4403 100644 --- a/examples/Cassie/cassie_state_estimator.h +++ b/examples/Cassie/cassie_state_estimator.h @@ -217,10 +217,10 @@ class CassieStateEstimator : public drake::systems::LeafSystem { // Heel ~??? // https://drive.google.com/file/d/1o7QS4ZksU91EBIpwtNnKpunob93BKiX_ // https://drive.google.com/file/d/1mlDzi0fa-YHopeRHaa-z88fPGuI2Aziv - const double knee_spring_threshold_ctrl_ = -0.015; - const double knee_spring_threshold_ekf_ = -0.015; - const double heel_spring_threshold_ctrl_ = -0.01; - const double heel_spring_threshold_ekf_ = -0.01; + const double knee_spring_threshold_ctrl_ = -0.020; + const double knee_spring_threshold_ekf_ = -0.020; + const double heel_spring_threshold_ctrl_ = -0.02; + const double heel_spring_threshold_ekf_ = -0.02; const double w_soft_constraint_ = 100; // Soft constraint cost const double contact_force_threshold_; // Soft constraint cost diff --git a/examples/Cassie/contact_scheduler/BUILD.bazel b/examples/Cassie/contact_scheduler/BUILD.bazel new file mode 100644 index 0000000000..9f029cba6d --- /dev/null +++ b/examples/Cassie/contact_scheduler/BUILD.bazel @@ -0,0 +1,35 @@ +# -*- mode: python -*- +# vi: set ft=python : + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name="all", + deps = [ + ":contact_scheduler", + ] +) + +cc_library( + name = "contact_scheduler", + srcs = ["contact_scheduler.cc"], + hdrs = ["contact_scheduler.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//common", + "//multibody:utils", + "//examples/Cassie:cassie_utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_binary( + name = "state_based_controller_switch", + srcs = ["state_based_controller_switch.cc"], + deps = [ + "@drake//:drake_shared_library", + "//lcmtypes:lcmt_robot", + "@gflags", + ], +) diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc new file mode 100644 index 0000000000..934729f84f --- /dev/null +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -0,0 +1,363 @@ +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" + +#include +#include + +#include "common/eigen_utils.h" +#include "examples/Cassie/cassie_utils.h" +#include "multibody/multibody_utils.h" + +using Eigen::Vector3d; +using Eigen::VectorXd; +using std::string; + +using drake::multibody::Frame; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::systems::State; +using drake::systems::UnrestrictedUpdateEvent; + +namespace dairlib { + +using drake::multibody::MultibodyPlant; +using drake::systems::Context; +using systems::ImpactInfoVector; +using systems::OutputVector; + +ContactScheduler::ContactScheduler(const MultibodyPlant& plant, + Context* plant_context, + std::set impact_states, + double near_impact_threshold, double tau, + BLEND_FUNC blend_func) + : plant_(plant), + plant_context_(plant_context), + impact_states_(std::move(impact_states)), + near_impact_threshold_(near_impact_threshold), + tau_(tau), + blend_func_(blend_func) { + DRAKE_DEMAND(tau_ > 0); + DRAKE_DEMAND(near_impact_threshold_ >= 0); + this->set_name("ContactScheduler"); + // Declare system ports + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); + fsm_port_ = this->DeclareVectorOutputPort("fsm", BasicVector(1), + &ContactScheduler::CalcFiniteState) + .get_index(); + impact_info_port_ = this->DeclareVectorOutputPort( + "near_impact", ImpactInfoVector(0, 0, 0), + &ContactScheduler::CalcNextImpactInfo) + .get_index(); + clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), + &ContactScheduler::CalcClock) + .get_index(); + contact_scheduler_port_ = + this->DeclareVectorOutputPort( + "contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, " + "right_t0, right_t0", + BasicVector(6), &ContactScheduler::CalcContactScheduler) + .get_index(); + + // Declare discrete states and update + stored_fsm_state_index_ = DeclareDiscreteState(3 * VectorXd::Ones(1)); + stored_robot_state_index_ = + DeclareDiscreteState(plant.num_positions() + plant.num_velocities()); + stored_transition_time_index_ = DeclareDiscreteState(1); + VectorXd nominal_state_durations = VectorXd::Zero(2); + nominal_state_durations << 0.25, 0.1; + nominal_state_durations_index_ = + DeclareDiscreteState(nominal_state_durations); + std::vector> initial_state_transitions = + {{-0.1, RIGHT_FLIGHT}, + {0.00, LEFT_STANCE}, + {0.25, LEFT_FLIGHT}, + {0.35, RIGHT_STANCE}}; + VectorXd initial_transition_times = VectorXd::Zero(4); + initial_transition_times << -0.1, 0.0, 0.25, 0.35; + transition_times_index_ = DeclareDiscreteState(initial_transition_times); + ground_height_index_ = DeclareDiscreteState(VectorXd::Zero(1)); + + upcoming_transitions_index_ = DeclareAbstractState( + drake::Value>>{ + initial_state_transitions}); + debug_port_ = this->DeclareAbstractOutputPort( + "status", &ContactScheduler::OutputDebuggingInfo) + .get_index(); + + DeclarePerStepUnrestrictedUpdateEvent( + &ContactScheduler::UpdateTransitionTimes); +} + +EventStatus ContactScheduler::UpdateTransitionTimes( + const Context& context, State* state) const { + DRAKE_DEMAND(rest_length_ > 0); + DRAKE_DEMAND(stance_duration_ > 0); + DRAKE_DEMAND(flight_duration_ > 0); + + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + double current_time = robot_output->get_timestamp(); + + auto stored_fsm_state = (RUNNING_FSM_STATE)state->get_mutable_discrete_state( + stored_fsm_state_index_)[0]; + auto transition_times = + state->get_mutable_discrete_state(transition_times_index_) + .get_mutable_value(); + auto& upcoming_transitions = + state->get_mutable_abstract_state< + std::vector>>( + upcoming_transitions_index_); + + auto active_state = stored_fsm_state; + double transition_time = upcoming_transitions.at(3).first; + RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; + if (current_time > transition_time) { + active_state = transition_state; + } + VectorXd q = robot_output->GetPositions(); + multibody::SetPositionsIfNew(plant_, q, plant_context_); + if (active_state == LEFT_STANCE) { + auto toe_front = LeftToeFront(plant_); + auto toe_rear = LeftToeRear(plant_); + Vector3d toe_front_pos; + Vector3d toe_rear_pos; + plant_.CalcPointsPositions(*plant_context_, toe_front.second, + toe_front.first, plant_.world_frame(), + &toe_front_pos); + plant_.CalcPointsPositions(*plant_context_, toe_rear.second, toe_rear.first, + plant_.world_frame(), &toe_rear_pos); + VectorXd height = + 0.5 * (toe_front_pos[2] + toe_rear_pos[2]) * VectorXd::Ones(1); + state->get_mutable_discrete_state(ground_height_index_) + .SetFromVector(height); + } else if (active_state == RIGHT_STANCE) { + auto toe_front = RightToeFront(plant_); + auto toe_rear = RightToeRear(plant_); + Vector3d toe_front_pos; + Vector3d toe_rear_pos; + plant_.CalcPointsPositions(*plant_context_, toe_front.second, + toe_front.first, plant_.world_frame(), + &toe_front_pos); + plant_.CalcPointsPositions(*plant_context_, toe_rear.second, toe_rear.first, + plant_.world_frame(), &toe_rear_pos); + VectorXd height = + 0.5 * (toe_front_pos[2] + toe_rear_pos[2]) * VectorXd::Ones(1); + state->get_mutable_discrete_state(ground_height_index_) + .SetFromVector(height); + } + + if (active_state != stored_fsm_state) { + state->get_mutable_discrete_state(stored_robot_state_index_) + .SetFromVector(robot_output->GetState()); + state->get_mutable_discrete_state(stored_transition_time_index_)[0] = + robot_output->get_timestamp(); + double stored_transition_time = + state->get_discrete_state(stored_transition_time_index_)[0]; + double g = + drake::multibody::UniformGravityFieldElement::kDefaultStrength; + + // Compute relative to stance foot + VectorXd pelvis_pos = Vector3d::Zero(); + plant_.CalcPointsPositions( + *plant_context_, plant_.GetBodyByName("pelvis").body_frame(), + Vector3d::Zero(), plant_.world_frame(), &pelvis_pos); + double pelvis_z = + pelvis_pos[2] - + state->get_discrete_state(ground_height_index_).value()[0]; + double pelvis_zdot = robot_output->GetVelocityAtIndex(5); + + if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { + // This is a very crude approximation + double stance_scale = (pelvis_z) / (rest_length_); + stance_scale = + std::clamp(stance_scale, 1 - stance_variance_, 1 + stance_variance_); + double next_transition_time = + stored_transition_time + stance_scale * stance_duration_; + state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = + next_transition_time - stored_transition_time; + if (active_state == LEFT_STANCE) { + transition_times[LEFT_FLIGHT] = next_transition_time; + upcoming_transitions = {{transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}}; + } else { + transition_times[RIGHT_FLIGHT] = next_transition_time; + upcoming_transitions = {{transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; + } + } else { + // set default to minimum touchdown time in case pelvis is below rest + // length + double time_to_touchdown = (1 - flight_variance_) * flight_duration_; + if (pelvis_zdot * pelvis_zdot - 2 * g * (rest_length_ - pelvis_z) > 0) { + time_to_touchdown = + (pelvis_zdot + sqrt(pelvis_zdot * pelvis_zdot - + 2 * g * (rest_length_ - pelvis_z))) / + g; + } + double time_to_touchdown_saturated = std::clamp( + time_to_touchdown, (1 - flight_variance_) * flight_duration_, + (1 + flight_variance_) * flight_duration_); + double next_transition_time = + stored_transition_time + time_to_touchdown_saturated; + state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = + next_transition_time - stored_transition_time; + if (active_state == LEFT_FLIGHT) { + transition_times[RIGHT_STANCE] = next_transition_time; + upcoming_transitions = {{transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}, + {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}}; + } else { + transition_times[LEFT_STANCE] = next_transition_time; + upcoming_transitions = {{transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, + {transition_times[RIGHT_STANCE], RIGHT_STANCE}, + {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, + {transition_times[LEFT_STANCE], LEFT_STANCE}}; + } + } + } + + state->get_mutable_discrete_state(stored_fsm_state_index_).get_mutable_value() + << active_state; + return drake::systems::EventStatus::Succeeded(); +} + +void ContactScheduler::CalcFiniteState(const Context& context, + BasicVector* fsm_state) const { + // Assign fsm_state + VectorXd current_finite_state = + context.get_discrete_state(stored_fsm_state_index_).CopyToVector(); + fsm_state->get_mutable_value() = current_finite_state; +} + +void ContactScheduler::CalcNextImpactInfo( + const Context& context, + ImpactInfoVector* near_impact) const { + // Read in lcm message time + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto current_time = static_cast(robot_output->get_timestamp()); + const auto& upcoming_transitions = context.get_abstract_state< + std::vector>>( + upcoming_transitions_index_); + // Assign the blending function ptr + auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; + + near_impact->set_timestamp(current_time); + near_impact->SetAlpha(0); + + // Get current finite state + double transition_time = upcoming_transitions.at(3).first; + RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; + double previous_transition_time = upcoming_transitions.at(2).first; + RUNNING_FSM_STATE current_state = upcoming_transitions.at(2).second; + double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; + // Check if the upcoming state has an impact + if (impact_states_.count(transition_state) != 0) { + if (abs(current_time - transition_time) < blend_window) { + // Apply the corresponding blending function + if (current_time <= transition_time) { + near_impact->SetAlpha(alpha_func(current_time - transition_time, tau_, + near_impact_threshold_)); + } + near_impact->SetCurrentContactMode(transition_state); + } + } + // Check if current state that we just transitioned to has an impact + if (impact_states_.count(current_state) != 0) { + if (abs(current_time - previous_transition_time) < blend_window) { + // Apply the corresponding blending function + if (current_time >= previous_transition_time) { + near_impact->SetAlpha( + alpha_func(previous_transition_time - current_time, tau_, + near_impact_threshold_)); + } + near_impact->SetCurrentContactMode(current_state); + } + } +} + +void ContactScheduler::CalcClock(const Context& context, + BasicVector* clock) const { + // Read in lcm message time + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto current_time = static_cast(robot_output->get_timestamp()); + + clock->get_mutable_value()(0) = current_time; +} + +void ContactScheduler::CalcContactScheduler( + const Context& context, BasicVector* contact_timing) const { + // Read in lcm message time + auto current_state_ = + (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; + double nominal_stance_duration = + context.get_discrete_state(nominal_state_durations_index_)[0]; + double nominal_flight_duration = + context.get_discrete_state(nominal_state_durations_index_)[1]; + auto transition_times = + context.get_discrete_state(transition_times_index_).value(); + /// Timing indices: order goes from start time to end time for when the + /// tracking objective is active. + /// PelvisTouchdown = 0 + /// PelvisLiftoff = 1 + /// LeftFootLiftoff = 2 + /// LeftFootTouchdown = 3 + /// RightFootLiftoff = 4 + /// RightFootTouchdown = 5 + if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_FLIGHT) { + contact_timing->get_mutable_value()(0) = transition_times[LEFT_STANCE]; + contact_timing->get_mutable_value()(1) = transition_times[LEFT_FLIGHT]; + } else { + contact_timing->get_mutable_value()(0) = transition_times[RIGHT_STANCE]; + contact_timing->get_mutable_value()(1) = transition_times[RIGHT_FLIGHT]; + } + contact_timing->get_mutable_value()(2) = transition_times[LEFT_FLIGHT]; + contact_timing->get_mutable_value()(3) = transition_times[LEFT_FLIGHT] + + 2 * nominal_flight_duration + + nominal_stance_duration; + contact_timing->get_mutable_value()(4) = transition_times[RIGHT_FLIGHT]; + contact_timing->get_mutable_value()(5) = transition_times[RIGHT_FLIGHT] + + 2 * nominal_flight_duration + + nominal_stance_duration; +} + +void ContactScheduler::OutputDebuggingInfo( + const drake::systems::Context& context, + dairlib::lcmt_contact_timing* debug_info) const { + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto& upcoming_transitions = context.get_abstract_state< + std::vector>>( + upcoming_transitions_index_); + auto stored_fsm_state = + (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; + debug_info->utime = robot_output->get_timestamp() * 1e6; + + debug_info->n_transitions = 4; + debug_info->active_fsm_state = stored_fsm_state; + debug_info->transition_times.clear(); + debug_info->transition_times = std::vector(4); + debug_info->transition_states.clear(); + debug_info->transition_states = std::vector(4); + debug_info->fsm_state_names = {"LEFT_STANCE (0)", "RIGHT_STANCE (1)", + "LEFT_FLIGHT (2)", "RIGHT_FLIGHT (3)"}; + + for (int i = 0; i < debug_info->n_transitions; ++i) { + debug_info->transition_times.at(i) = upcoming_transitions[i].first; + debug_info->transition_states.at(i) = upcoming_transitions[i].second; + } +} + +} // namespace dairlib diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h new file mode 100644 index 0000000000..9ba4f2e92b --- /dev/null +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -0,0 +1,110 @@ +#pragma once + +#include +#include +#include +#include + +#include "common/blending_utils.h" +#include "dairlib/lcmt_contact_timing.hpp" +#include "systems/framework/impact_info_vector.h" +#include "systems/framework/output_vector.h" + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +enum RUNNING_FSM_STATE { LEFT_STANCE, RIGHT_STANCE, LEFT_FLIGHT, RIGHT_FLIGHT }; + +class ContactScheduler : public drake::systems::LeafSystem { + public: + ContactScheduler(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* plant_context, + std::set impact_states, + double near_impact_threshold = 0, double tau = 0.0025, + BLEND_FUNC blend_func = SIGMOID); + + void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } + void SetNominalStepTimings(double stance_duration, double flight_duration) { + stance_duration_ = stance_duration; + flight_duration_ = flight_duration; + } + void SetMaxStepTimingVariance(double stance_variance, double flight_variance) { + stance_variance_ = stance_variance; + flight_variance_ = flight_variance; + } + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::OutputPort& get_output_port_fsm() const { + return this->get_output_port(fsm_port_); + } + const drake::systems::OutputPort& get_output_port_clock() const { + return this->get_output_port(clock_port_); + } + const drake::systems::OutputPort& get_output_port_impact_info() + const { + return this->get_output_port(impact_info_port_); + } + const drake::systems::OutputPort& get_output_port_contact_scheduler() + const { + return this->get_output_port(contact_scheduler_port_); + } + const drake::systems::OutputPort& get_output_port_debug_info() const { + return this->get_output_port(debug_port_); + } + + private: + drake::systems::EventStatus UpdateTransitionTimes( + const drake::systems::Context& context, + drake::systems::State* state) const; + void CalcNextImpactInfo(const drake::systems::Context& context, + systems::ImpactInfoVector* near_impact) const; + void CalcFiniteState(const drake::systems::Context& context, + drake::systems::BasicVector* fsm_state) const; + void CalcClock(const drake::systems::Context& context, + drake::systems::BasicVector* clock) const; + void CalcContactScheduler( + const drake::systems::Context& context, + drake::systems::BasicVector* contact_timing) const; + void OutputDebuggingInfo(const drake::systems::Context& context, + dairlib::lcmt_contact_timing* debug_info) const; + + drake::systems::InputPortIndex state_port_; + drake::systems::OutputPortIndex fsm_port_; + drake::systems::OutputPortIndex clock_port_; + drake::systems::OutputPortIndex impact_info_port_; + drake::systems::OutputPortIndex contact_scheduler_port_; + drake::systems::OutputPortIndex debug_port_; + + // Dynamics calculations + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* plant_context_; + + // For impact-invariant calculations + const std::set impact_states_; + double near_impact_threshold_; + double tau_; + const BLEND_FUNC blend_func_; + + drake::systems::DiscreteStateIndex stored_fsm_state_index_; + drake::systems::DiscreteStateIndex stored_robot_state_index_; + drake::systems::DiscreteStateIndex stored_transition_time_index_; + + // estimates of state durations for stance and flight in seconds + drake::systems::DiscreteStateIndex nominal_state_durations_index_; + drake::systems::DiscreteStateIndex transition_times_index_; + drake::systems::DiscreteStateIndex ground_height_index_; + + drake::systems::AbstractStateIndex upcoming_transitions_index_; + + /// SLIP parameters + double rest_length_ = 0.0; + double stance_duration_ = 0.0; + double flight_duration_ = 0.0; + double stance_variance_ = 0.0; + double flight_variance_ = 0.0; +}; + +} // namespace dairlib diff --git a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc new file mode 100644 index 0000000000..2873fc7348 --- /dev/null +++ b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc @@ -0,0 +1,137 @@ +#include +#include + +#include +#include + +#include "dairlib/lcmt_controller_switch.hpp" +#include "dairlib/lcmt_robot_output.hpp" + +#include "drake/lcm/drake_lcm.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/serializer.h" + +namespace dairlib { + +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; + +DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", + "The name of the channel which receives state"); +DEFINE_string(switch_channel, "INPUT_SWITCH", + "The name of the channel which sends the channel name that " + "dispatcher_in listens to"); +DEFINE_string(new_channel, "PD_CONTROL", + "The name of the new lcm channel that dispatcher_in listens to " + "after switch"); +DEFINE_string(contact_schedule_channel, "CONTACT_TIMING", + "The name of the lcm channel that publishes contact timings"); +DEFINE_double(trigger_state, -1.0, + " the period of TimeBasedFiniteStateMachine"); +DEFINE_double(fsm_offset, 0.0, + "a constant that's used to determined the publish time see the " + "documentation below for details"); +DEFINE_double(blend_duration, 1.0, + "Duration to blend efforts between previous and current " + "controller command"); + +/// This program is a one-time-use switch that tells dispatcher_robot_in which +/// channel to listen to. It publishes the lcm message, +/// dairlib::lcmt_controller_switch, which contains a string of the channel +/// name. + +/// The program is extended so that it could be used with +/// new controller is still in a middle of a discrete state). This requires that +/// the users provide two (or three) more arguments to the constructors besides +/// `new_channel`: +/// @param trigger_state, the FSM state to switch on` +/// + +int do_main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Parameters + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + + // Build the diagram + drake::systems::DiagramBuilder builder; + auto name_pub = builder.AddSystem( + LcmPublisherSystem::Make( + FLAGS_switch_channel, &lcm_local, + TriggerTypeSet({TriggerType::kForced}))); + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("switch publisher")); + + // Create simulator + drake::systems::Diagram* diagram_ptr = owned_diagram.get(); + drake::systems::Simulator simulator(std::move(owned_diagram)); + auto& diagram_context = simulator.get_mutable_context(); + + // Create subscriber for lcm driven loop + drake::lcm::Subscriber input_sub(&lcm_local, + FLAGS_channel_x); + drake::lcm::Subscriber timing_sub(&lcm_local, + FLAGS_contact_schedule_channel); + + // Wait for the first message and initialize the context time.. + drake::log()->info("Waiting for first lcm input message"); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); + const double t0 = input_sub.message().utime * 1e-6; + diagram_context.SetTime(t0); + + drake::log()->info(diagram_ptr->get_name() + " started"); + + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return timing_sub.count() > 0; }); + while(timing_sub.message().transition_states.back() != FLAGS_trigger_state){ + timing_sub.clear(); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return timing_sub.count() > 0; }); + } + const double transition_time = timing_sub.message().transition_times.back() + FLAGS_fsm_offset; + std::cout << "transition time: " << transition_time << std::endl; + + // Create output message + dairlib::lcmt_controller_switch msg; + msg.channel = FLAGS_new_channel; + msg.blend_duration = FLAGS_blend_duration; + + + int pub_count = 0; + while (pub_count < 1) { + // Wait for input message. + input_sub.clear(); + LcmHandleSubscriptionsUntil(&lcm_local, + [&]() { return input_sub.count() > 0; }); + + // Get message time from the input channel + double t_current = input_sub.message().utime * 1e-6; + if (t_current >= transition_time) { + std::cout << "publish at t = " << t_current << std::endl; + + msg.utime = (int)input_sub.message().utime; + name_pub->get_input_port().FixValue( + &(diagram_ptr->GetMutableSubsystemContext(*name_pub, + &diagram_context)), + msg); + + // Force-publish via the diagram + /// We don't need AdvanceTo(time) because we manually force publish lcm + /// message, and there is nothing in the diagram that needs to be updated. + diagram_ptr->Publish(diagram_context); + + pub_count++; + } + } + drake::log()->info(diagram_ptr->get_name() + " ended"); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 304c2d7a56..2b699691c9 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -6,6 +6,7 @@ #include "dairlib/lcmt_controller_failure.hpp" #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_lcm_driven_loop.h" #include "examples/Cassie/cassie_utils.h" #include "examples/Cassie/systems/input_supervisor.h" #include "examples/Cassie/networking/cassie_input_translator.h" @@ -13,8 +14,9 @@ #include "multibody/multibody_utils.h" #include "systems/controllers/linear_controller.h" #include "systems/controllers/pd_config_lcm.h" -#include "examples/Cassie/cassie_lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + #include "drake/lcm/drake_lcm.h" #include "drake/systems/framework/diagram.h" @@ -92,7 +94,7 @@ int do_main(int argc, char* argv[]) { auto command_receiver = builder.AddSystem(plant); // Safety Controller - auto controller = builder.AddSystem( + auto safety_controller = builder.AddSystem( plant.num_positions(), plant.num_velocities(), plant.num_actuators()); // Create config receiver. auto config_receiver = builder.AddSystem(plant); @@ -116,17 +118,17 @@ int do_main(int argc, char* argv[]) { auto state_receiver = builder.AddSystem(plant); auto input_supervisor_status_pub = builder.AddSystem( LcmPublisherSystem::Make( - "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, FLAGS_pub_rate)); + "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, + FLAGS_pub_rate)); builder.Connect(*state_sub, *state_receiver); double input_supervisor_update_period = 1.0 / 1000.0; - // Get input limits int nu = plant.num_actuators(); VectorXd input_limit(nu); for (drake::multibody::JointActuatorIndex i(0); i < nu; ++i) { - input_limit(i) = plant.get_joint_actuator(i).effort_limit(); + input_limit[i] = plant.get_joint_actuator(i).effort_limit(); } auto input_supervisor = builder.AddSystem( @@ -145,10 +147,10 @@ int do_main(int argc, char* argv[]) { builder.Connect(cassie_out_receiver->get_output_port(), input_supervisor->get_input_port_cassie()); builder.Connect(state_receiver->get_output_port(0), - controller->get_input_port_output()); + safety_controller->get_input_port_output()); builder.Connect(config_receiver->get_output_port(0), - controller->get_input_port_config()); - builder.Connect(controller->get_output_port(0), + safety_controller->get_input_port_config()); + builder.Connect(safety_controller->get_output_port(0), input_supervisor->get_input_port_safety_controller()); builder.Connect(input_supervisor->get_output_port_failure(), controller_error_pub->get_input_port()); @@ -167,22 +169,22 @@ int do_main(int argc, char* argv[]) { // Create and connect LCM command echo to network auto net_command_sender = builder.AddSystem(plant); - LcmPublisherSystem* command_pub; - if (FLAGS_sim) { - command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); - } else { - command_pub = + LcmPublisherSystem* command_pub_network; + if (!FLAGS_sim) { + command_pub_network = builder.AddSystem(LcmPublisherSystem::Make( "NETWORK_CASSIE_INPUT", &lcm_network, {TriggerType::kPeriodic}, FLAGS_pub_rate)); + builder.Connect(*net_command_sender, *command_pub_network); } + auto command_pub_local = + builder.AddSystem(LcmPublisherSystem::Make( + "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); builder.Connect(input_supervisor->get_output_port_command(), net_command_sender->get_input_port(0)); - builder.Connect(*net_command_sender, *command_pub); + builder.Connect(*net_command_sender, *command_pub_local); // Finish building the diagram auto owned_diagram = builder.Build(); @@ -201,7 +203,7 @@ int do_main(int argc, char* argv[]) { // Run lcm-driven simulation CassieLcmDrivenLoop + dairlib::lcmt_controller_switch> loop(&lcm_local, std::move(owned_diagram), command_receiver, input_channels, FLAGS_control_channel_name_initial, switch_channel, true, FLAGS_state_channel_name); @@ -222,7 +224,7 @@ int do_main(int argc, char* argv[]) { &(loop.get_diagram()->GetMutableSubsystemContext( *config_receiver, &loop.get_diagram_mutable_context())), msg); - + DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); return 0; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 8e2d036848..0afd7a708f 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -1,4 +1,5 @@ #include +#include #include @@ -16,6 +17,7 @@ #include "systems/framework/output_vector.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" #include "drake/lcm/drake_lcm.h" @@ -327,7 +329,9 @@ int do_main(int argc, char* argv[]) { // Create the diagram, simulator, and context. auto owned_diagram = builder.Build(); + owned_diagram->set_name(("dispatcher_robot_out")); const auto& diagram = *owned_diagram; + DrawAndSaveDiagramGraph(diagram); drake::systems::Simulator simulator(std::move(owned_diagram)); auto& diagram_context = simulator.get_mutable_context(); diff --git a/examples/Cassie/osc/BUILD.bazel b/examples/Cassie/osc/BUILD.bazel index 5ceee97dd8..a57a3d6c78 100644 --- a/examples/Cassie/osc/BUILD.bazel +++ b/examples/Cassie/osc/BUILD.bazel @@ -10,8 +10,9 @@ cc_library( "//examples/Cassie/osc:hip_yaw_traj_gen", "//examples/Cassie/osc:osc_walking_gains", "//examples/Cassie/osc:osc_walking_gains_alip", + "//examples/Cassie/osc:osc_standing_gains", "//examples/Cassie/osc:standing_com_traj", - "//examples/Cassie/osc:standing_pelvis_traj", + "//examples/Cassie/osc:standing_pelvis_orientation_traj", "//examples/Cassie/osc:swing_toe_traj", "//examples/Cassie/osc:walking_speed_control", "//systems/controllers:alip_swing_ft_traj_gen", @@ -77,6 +78,7 @@ cc_library( deps = [ "//lcmtypes:lcmt_robot", "//multibody:utils", + "//common:common", "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", @@ -84,13 +86,14 @@ cc_library( ) cc_library( - name = "standing_pelvis_traj", + name = "standing_pelvis_orientation_traj", srcs = ["standing_pelvis_orientation_traj.cc"], hdrs = ["standing_pelvis_orientation_traj.h"], deps = [ "//lcmtypes:lcmt_robot", "//systems/controllers:control_utils", "//systems/framework:vector", + "//common:common", "@drake//:drake_shared_library", ], ) @@ -122,3 +125,11 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "osc_standing_gains", + hdrs = ["osc_standing_gains.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index 31a57e7386..a7976d478f 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -43,11 +43,10 @@ HighLevelCommand::HighLevelCommand( double stick_filter_dt) : HighLevelCommand(plant, context) { radio_port_ = - this->DeclareAbstractInputPort("lcmt_cassie_output", + this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); use_radio_command_ = true; - vel_scale_rot_ = vel_scale_rot; vel_scale_trans_sagital_ = vel_scale_trans_sagital; vel_scale_trans_lateral_ = vel_scale_trans_lateral; @@ -86,16 +85,16 @@ HighLevelCommand::HighLevelCommand( context_(context), world_(plant_.world_frame()), pelvis_(plant_.GetBodyByName("pelvis")) { - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); + .get_index(); - yaw_port_ = this->DeclareVectorOutputPort("pelvis_yaw", BasicVector(1), - &HighLevelCommand::CopyHeadingAngle) - .get_index(); + yaw_port_ = + this->DeclareVectorOutputPort("pelvis_yaw", BasicVector(1), + &HighLevelCommand::CopyHeadingAngle) + .get_index(); xy_port_ = this->DeclareVectorOutputPort("pelvis_xy", BasicVector(2), &HighLevelCommand::CopyDesiredHorizontalVel) @@ -111,8 +110,8 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( const Context& context, DiscreteValues* discrete_state) const { if (use_radio_command_) { - const auto& radio_out = this->EvalInputValue( - context, radio_port_); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); // TODO(yangwill) make sure there is a message available // des_vel indices: 0: yaw_vel (right joystick left/right) // 1: saggital_vel (left joystick up/down) @@ -120,9 +119,14 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( double vel_scale_trans_sagital = (radio_out->channel[6] + 1.0) * vel_scale_trans_sagital_; - double a = .001 / (stick_filter_dt_ + .001); // approximately 1KHz sampling rate - no need to be too precise + // approximately 1KHz sampling rate - no need to be too precise + double a = .001 / (stick_filter_dt_ + .001); Vector3d des_vel_prev = discrete_state->get_value(des_vel_idx_); Vector3d des_vel; + // des_vel << vel_scale_rot_ * radio_out->channel[3], + // vel_scale_trans_sagital_ * radio_out->channel[0], + // vel_scale_trans_lateral_ * radio_out->channel[1]; + // discrete_state->get_mutable_vector(des_vel_idx_).set_value(des_vel); des_vel << vel_scale_rot_ * radio_out->channel[3], vel_scale_trans_sagital * radio_out->channel[0], vel_scale_trans_lateral_ * radio_out->channel[1]; @@ -177,7 +181,9 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( // PD position control double des_yaw_vel = kp_yaw_ * heading_error + kd_yaw_ * (-yaw_vel); - des_yaw_vel = drake::math::saturate(des_yaw_vel, -vel_max_yaw_, vel_max_yaw_); + // des_yaw_vel = drake::math::saturate(des_yaw_vel, -vel_max_yaw_, + // vel_max_yaw_); + des_yaw_vel = std::clamp(des_yaw_vel, -vel_max_yaw_, vel_max_yaw_); // Convex combination of 0 and desired yaw velocity double weight = 1 / (1 + exp(-params_of_no_turning_(0) * @@ -214,15 +220,18 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( des_sagital_vel = kp_pos_sagital_ * (local_com_pos_to_target_pos(0) + target_pos_offset_) + kd_pos_sagital_ * (-com_vel_sagital); - des_sagital_vel = drake::math::saturate(des_sagital_vel, -vel_max_sagital_, - vel_max_sagital_); + // des_sagital_vel = drake::math::saturate(des_sagital_vel, + // -vel_max_sagital_, + // vel_max_sagital_); + des_sagital_vel = + std::clamp(des_sagital_vel, -vel_max_sagital_, vel_max_sagital_); // Frontal plane position PD control. TODO(yminchen): tune this double com_vel_lateral = local_com_vel(1); des_lateral_vel = kp_pos_lateral_ * (local_com_pos_to_target_pos(1)) + kd_pos_lateral_ * (-com_vel_lateral); - des_lateral_vel = drake::math::saturate(des_lateral_vel, -vel_max_lateral_, - vel_max_lateral_); + des_lateral_vel = + std::clamp(des_lateral_vel, -vel_max_lateral_, vel_max_lateral_); } Vector3d des_vel; des_vel << desired_filtered_yaw_vel, des_sagital_vel, des_lateral_vel; diff --git a/examples/Cassie/osc/high_level_command.h b/examples/Cassie/osc/high_level_command.h index 7103e08ad2..eb63747bfc 100644 --- a/examples/Cassie/osc/high_level_command.h +++ b/examples/Cassie/osc/high_level_command.h @@ -69,16 +69,16 @@ class HighLevelCommand : public drake::systems::LeafSystem { const Eigen::Vector2d& params_of_no_turning); // Input/output ports - const drake::systems::InputPort& get_state_input_port() const { + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } - const drake::systems::OutputPort& get_yaw_output_port() const { - return this->get_output_port(yaw_port_); - } - const drake::systems::InputPort& get_radio_port() const { + const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); } - const drake::systems::OutputPort& get_xy_output_port() const { + const drake::systems::OutputPort& get_output_port_yaw() const { + return this->get_output_port(yaw_port_); + } + const drake::systems::OutputPort& get_output_port_xy() const { return this->get_output_port(xy_port_); } diff --git a/examples/Cassie/osc/osc_standing_gains.h b/examples/Cassie/osc/osc_standing_gains.h new file mode 100644 index 0000000000..a89b0c5cfa --- /dev/null +++ b/examples/Cassie/osc/osc_standing_gains.h @@ -0,0 +1,86 @@ +#pragma once + +#include "systems/controllers/osc/osc_gains.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct OSCStandingGains : OSCGains { + double weight_scaling; + double HipYawKp; + double HipYawKd; + double HipYawW; + double center_of_mass_filter_tau; + double rot_filter_tau; + double center_of_mass_command_filter_alpha; + double orientation_command_filter_alpha; + std::vector PelvisW; + std::vector PelvisKp; + std::vector PelvisKd; + std::vector PelvisRotW; + std::vector PelvisRotKp; + std::vector PelvisRotKd; + + MatrixXd W_pelvis; + MatrixXd K_p_pelvis; + MatrixXd K_d_pelvis; + MatrixXd W_pelvis_rot; + MatrixXd K_p_pelvis_rot; + MatrixXd K_d_pelvis_rot; + MatrixXd K_p_hip_yaw; + MatrixXd K_d_hip_yaw; + MatrixXd W_hip_yaw; + + template + void Serialize(Archive* a) { + OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(weight_scaling)); + a->Visit(DRAKE_NVP(PelvisW)); + a->Visit(DRAKE_NVP(PelvisKp)); + a->Visit(DRAKE_NVP(PelvisKd)); + a->Visit(DRAKE_NVP(PelvisRotW)); + a->Visit(DRAKE_NVP(PelvisRotKp)); + a->Visit(DRAKE_NVP(PelvisRotKd)); + a->Visit(DRAKE_NVP(HipYawKp)); + a->Visit(DRAKE_NVP(HipYawKd)); + a->Visit(DRAKE_NVP(HipYawW)); + a->Visit(DRAKE_NVP(center_of_mass_filter_tau)); + a->Visit(DRAKE_NVP(rot_filter_tau)); + a->Visit(DRAKE_NVP(center_of_mass_command_filter_alpha)); + a->Visit(DRAKE_NVP(orientation_command_filter_alpha)); + + W_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisW.data(), 3, 3); + K_p_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisKp.data(), 3, 3); + K_d_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisKd.data(), 3, 3); + W_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotW.data(), 3, 3); + K_p_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKp.data(), 3, 3); + K_d_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKd.data(), 3, 3); + K_p_hip_yaw = HipYawKp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = HipYawKd * MatrixXd::Identity(1, 1); + W_hip_yaw = HipYawW * MatrixXd::Identity(1, 1); + + + w_accel *= weight_scaling; + w_input *= weight_scaling; + w_input_reg *= weight_scaling; + w_lambda *= weight_scaling; + w_soft_constraint *= weight_scaling; + W_pelvis_rot *= weight_scaling; + W_pelvis *= weight_scaling; + W_hip_yaw *= weight_scaling; + } +}; diff --git a/examples/Cassie/osc/osc_standing_gains.yaml b/examples/Cassie/osc/osc_standing_gains.yaml index 4d28ca8b62..95395e7890 100644 --- a/examples/Cassie/osc/osc_standing_gains.yaml +++ b/examples/Cassie/osc/osc_standing_gains.yaml @@ -1,44 +1,59 @@ +controller_frequency: 1000 -# Set xy PD gains so they do not effect passive LIPM dynamics at capture -# point, when x = sqrt(l/g) * xdot -# Passive dynamics: xddot = g/l * x -# -# -Kp * x - Kd * xdot = -# -Kp * x + Kd * sqrt(g/l) * x = g/l * x -# Kp = sqrt(g/l) * Kd - g/l - -rows: 3 -cols: 3 -w_input: 0 -#w_accel: 0.00001 -w_accel: 0.00000001 -w_soft_constraint: 200 -HipYawKp: 10 -HipYawKd: 1 -HipYawW: 0 -CoMW: - [20, 0, 0, - 0, 20, 0, - 0, 0, 5] +w_input: 0.000001 +w_accel: 0.000001 +w_lambda: 0.2 +#W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, +# 1, 1, 1, 1, 0.01, 0.001, +# 1, 1, 1, 1, 0.01, 0.001 ] +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001 ] +W_input_reg: [ 1, 0.9, 0.5, 0.3, 1, + 1, 0.9, 0.5, 0.3, 1 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01 ] +#W_lambda_h_reg: [ 0.02, 0.02 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.002, 0.002 ] +w_soft_constraint: 1000 +w_input_reg: 0.3 +impact_threshold: 0.00 +center_of_mass_filter_tau: 0.00 +rot_filter_tau: 0.000 +center_of_mass_command_filter_alpha: 0.8 +orientation_command_filter_alpha: 1.0 +impact_tau: 0.00 +mu: 0.6 +weight_scaling: 1.0 +HipYawKp: 100 +HipYawKd: 5 +HipYawW: 2.5 PelvisW: - [2, 0, 0, - 0, 2, 0, - 0, 0, 0] -CoMKp: - [ 20, 0, 0, - 0, 20, 0, - 0, 0, 20] -CoMKd: - [ 0.5, 0, 0, - 0, 0.75, 0, - 0, 0, 1] + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 2 ] +PelvisKp: + [ 75, 0, 0, + 0, 50, 0, + 0, 0, 40 ] +PelvisKd: + [ 2, 0, 0, + 0, 2, 0, + 0, 0, 2] +PelvisRotW: + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 10 ] PelvisRotKp: - [10, 0, 0, - 0, 30, 0, - 0, 0, 10] + [150., 0, 0, + 0, 200., 0, + 0, 0, 50 ] PelvisRotKd: - [0.5, 0, 0, - 0, 0.5, 0, - 0, 0, 0.5] + [ 2, 0, 0, + 0, 2, 0, + 0, 0, 2 ] diff --git a/examples/Cassie/osc/osc_walking_gains.h b/examples/Cassie/osc/osc_walking_gains.h index 2f8ba87a8e..5c16148aa7 100644 --- a/examples/Cassie/osc/osc_walking_gains.h +++ b/examples/Cassie/osc/osc_walking_gains.h @@ -1,4 +1,5 @@ #pragma once + #include "drake/common/yaml/yaml_read_archive.h" #include "yaml-cpp/yaml.h" @@ -11,6 +12,7 @@ struct OSCWalkingGains { double w_accel; double w_soft_constraint; double w_input_reg; + double impact_threshold; bool relative_swing_ft; std::vector pelvis_xyz_vel_filter_tau; std::vector CoMW; @@ -82,6 +84,11 @@ struct OSCWalkingGains { MatrixXd K_p_hip_yaw; MatrixXd K_d_hip_yaw; + std::vector W_lambda_c_reg; + std::vector W_lambda_h_reg; + MatrixXd W_lambda_c_regularization; + MatrixXd W_lambda_h_regularization; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(rows)); @@ -91,6 +98,7 @@ struct OSCWalkingGains { a->Visit(DRAKE_NVP(w_soft_constraint)); a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(relative_swing_ft)); + a->Visit(DRAKE_NVP(impact_threshold)); a->Visit(DRAKE_NVP(pelvis_xyz_vel_filter_tau)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); @@ -190,5 +198,16 @@ struct OSCWalkingGains { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); + + a->Visit(DRAKE_NVP(W_lambda_c_reg)); + a->Visit(DRAKE_NVP(W_lambda_h_reg)); + Eigen::VectorXd w_lambda_c_regularization = + Eigen::Map( + this->W_lambda_c_reg.data(), this->W_lambda_c_reg.size()); + Eigen::VectorXd w_lambda_h_regularization = + Eigen::Map( + this->W_lambda_h_reg.data(), this->W_lambda_h_reg.size()); + W_lambda_c_regularization = w_lambda_c_regularization.asDiagonal(); + W_lambda_h_regularization = w_lambda_h_regularization.asDiagonal(); } }; diff --git a/examples/Cassie/osc/osc_walking_gains.yaml b/examples/Cassie/osc/osc_walking_gains.yaml index 4ed826acf8..ee2ad81118 100644 --- a/examples/Cassie/osc/osc_walking_gains.yaml +++ b/examples/Cassie/osc/osc_walking_gains.yaml @@ -1,3 +1,4 @@ +controller_frequency: 1000 rows: 3 cols: 3 @@ -48,7 +49,7 @@ final_foot_height: 0.0 final_foot_velocity_z: 0.0 # LIPM trajectory -lipm_height: 0.9 +lipm_height: 0.85 # OSC gains mu: 0.8 diff --git a/examples/Cassie/osc/osc_walking_gains_alip.h b/examples/Cassie/osc/osc_walking_gains_alip.h index e8db6cd573..57773f4624 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.h +++ b/examples/Cassie/osc/osc_walking_gains_alip.h @@ -1,17 +1,16 @@ #pragma once -#include "drake/common/yaml/yaml_read_archive.h" + +#include "systems/controllers/osc/osc_gains.h" #include "yaml-cpp/yaml.h" +#include "drake/common/yaml/yaml_read_archive.h" + using Eigen::MatrixXd; using Eigen::VectorXd; -struct OSCWalkingGainsALIP { +struct OSCWalkingGainsALIP : OSCGains { int rows; int cols; - double mu; - double w_accel; - double w_soft_constraint; - double w_input_reg; std::vector pelvis_xyz_vel_filter_tau; std::vector CoMW; std::vector CoMKp; @@ -85,12 +84,9 @@ struct OSCWalkingGainsALIP { template void Serialize(Archive* a) { + OSCGains::Serialize(a); a->Visit(DRAKE_NVP(rows)); a->Visit(DRAKE_NVP(cols)); - a->Visit(DRAKE_NVP(mu)); - a->Visit(DRAKE_NVP(w_accel)); - a->Visit(DRAKE_NVP(w_soft_constraint)); - a->Visit(DRAKE_NVP(w_input_reg)); a->Visit(DRAKE_NVP(pelvis_xyz_vel_filter_tau)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); @@ -192,7 +188,9 @@ struct OSCWalkingGainsALIP { W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); - Q_alip_kalman_filter = Eigen::Map(this->AlipKalmanQ.data(), 4); - R_alip_kalman_filter = Eigen::Map(this->AlipKalmanR.data(), 4); + Q_alip_kalman_filter = + Eigen::Map(this->AlipKalmanQ.data(), 4); + R_alip_kalman_filter = + Eigen::Map(this->AlipKalmanR.data(), 4); } }; diff --git a/examples/Cassie/osc/osc_walking_gains_alip.yaml b/examples/Cassie/osc/osc_walking_gains_alip.yaml index 28cba45890..3e0da9b29e 100644 --- a/examples/Cassie/osc/osc_walking_gains_alip.yaml +++ b/examples/Cassie/osc/osc_walking_gains_alip.yaml @@ -1,3 +1,27 @@ +controller_frequency: 1000 + +# OSC gains +w_input: 0.0000 +w_input_reg: 0.000001 +w_accel: 0.00000001 +w_lambda: 0.00000001 +w_soft_constraint: 80 +impact_threshold: 0.025 +impact_tau: 0.005 +mu: 0.6 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_input_reg: [1, 0.9, 0.5, 0.1, 5, + 1, 0.9, 0.5, 0.1, 5] +W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] +W_lambda_c_reg: [1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.1, 0.01, + 1, 0.1, 0.01] +W_lambda_h_reg: [0.01, 0.01, 0.01, + 0.01, 0.02, 0.02] + rows: 3 cols: 3 @@ -44,18 +68,11 @@ final_foot_velocity_z: 0.0 # LIPM trajectory lipm_height: 0.85 -# OSC gains -mu: 0.6 - -w_accel: 0.00000001 -w_soft_constraint: 80 -w_input_reg: 0.0000003 - w_swing_toe: 1 swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 2.0 +w_hip_yaw: 0.1 hip_yaw_kp: 40 hip_yaw_kd: 1 diff --git a/examples/Cassie/osc/swing_toe_traj_generator.cc b/examples/Cassie/osc/swing_toe_traj_generator.cc index ab17451608..257b119def 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.cc +++ b/examples/Cassie/osc/swing_toe_traj_generator.cc @@ -26,16 +26,15 @@ SwingToeTrajGenerator::SwingToeTrajGenerator( feet_contact_points_(feet_contact_points) { DRAKE_DEMAND(feet_contact_points_.size() == 2); // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort("x, u, t", - OutputVector(plant.num_positions(), + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators())) - .get_index(); + .get_index(); PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("toe_ang", traj_inst, + this->DeclareAbstractOutputPort("toe_angle", traj_inst, &SwingToeTrajGenerator::CalcTraj); } @@ -43,8 +42,6 @@ void SwingToeTrajGenerator::CalcTraj( const drake::systems::Context& context, Trajectory* traj) const { // Read in current state - - // Read in current state const OutputVector* robotOutput = (OutputVector*)this->EvalVectorInput(context, state_port_); VectorXd q = robotOutput->GetPositions(); @@ -54,6 +51,8 @@ void SwingToeTrajGenerator::CalcTraj( Vector3d pt_0; Vector3d pt_1; + // Calculate difference between toe and ground assuming flat ground + // Apply difference to current toe angle to use as desired plant_.CalcPointsPositions(*context_, feet_contact_points_[0].second, feet_contact_points_[0].first, world_, &pt_0); plant_.CalcPointsPositions(*context_, feet_contact_points_[1].second, @@ -61,7 +60,6 @@ void SwingToeTrajGenerator::CalcTraj( VectorXd foot = pt_0 - pt_1; double deviation_from_ground_plane = (atan2(foot(2), foot.head(2).norm())); - // Get current difference between VectorXd des_swing_toe_angle = VectorXd(1); des_swing_toe_angle << swing_toe_angle + deviation_from_ground_plane; diff --git a/examples/Cassie/osc/swing_toe_traj_generator.h b/examples/Cassie/osc/swing_toe_traj_generator.h index 5f47f5051a..245ac574fe 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.h +++ b/examples/Cassie/osc/swing_toe_traj_generator.h @@ -21,7 +21,7 @@ class SwingToeTrajGenerator : public drake::systems::LeafSystem { const std::string& traj_name); // Input/output ports - const drake::systems::InputPort& get_state_input_port() const { + const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } diff --git a/examples/Cassie/osc_jump/BUILD.bazel b/examples/Cassie/osc_jump/BUILD.bazel index 393d9caca5..4cbe0c03fe 100644 --- a/examples/Cassie/osc_jump/BUILD.bazel +++ b/examples/Cassie/osc_jump/BUILD.bazel @@ -35,7 +35,6 @@ cc_library( deps = [ ":jumping_event_based_fsm", "//multibody:utils", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -48,7 +47,6 @@ cc_library( deps = [ ":jumping_event_based_fsm", "//multibody:utils", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -61,7 +59,6 @@ cc_library( deps = [ ":jumping_event_based_fsm", "//multibody:utils", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], @@ -74,7 +71,6 @@ cc_library( deps = [ "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//lcmtypes:lcmt_robot", - "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", ], diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc index 0893ac46dd..62ee294b3c 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc @@ -29,15 +29,13 @@ FlightFootTrajGenerator::FlightFootTrajGenerator( const string& hip_name, bool isLeftFoot, const PiecewisePolynomial& foot_traj, const PiecewisePolynomial& hip_traj, - bool relative_feet, double time_offset) : plant_(plant), context_(context), world_(plant.world_frame()), hip_frame_(plant.GetFrameByName(hip_name)), foot_traj_(foot_traj), - hip_traj_(hip_traj), - relative_feet_(relative_feet) { + hip_traj_(hip_traj){ PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; @@ -65,33 +63,6 @@ FlightFootTrajGenerator::FlightFootTrajGenerator( hip_traj_.shiftRight(time_offset); } -PiecewisePolynomial FlightFootTrajGenerator::GenerateFlightTraj( - const VectorXd& x, double t) const { - if (relative_feet_) { - plant_.SetPositionsAndVelocities(context_, x); - // Hip offset - Vector3d zero_offset = Vector3d::Zero(); - Vector3d hip_pos = Vector3d::Zero(); - plant_.CalcPointsPositions(*context_, hip_frame_, zero_offset, world_, - &hip_pos); - - const PiecewisePolynomial& foot_traj_segment = - foot_traj_.slice(foot_traj_.get_segment_index(t), 1); - - std::vector breaks = foot_traj_segment.get_segment_times(); - VectorXd breaks_vector = Map(breaks.data(), breaks.size()); - MatrixXd hip_points(3, 2); - // Velocity estimates are generally bad - hip_points << hip_pos, hip_pos; - PiecewisePolynomial hip_offset = - PiecewisePolynomial::ZeroOrderHold(breaks_vector, hip_points); - - return foot_traj_segment + hip_offset; - } else { - return foot_traj_; - } -} - PiecewisePolynomial FlightFootTrajGenerator::GenerateRelativeTraj() const { return foot_traj_ - hip_traj_; @@ -104,17 +75,10 @@ void FlightFootTrajGenerator::CalcTraj( const auto robot_output = this->template EvalVectorInput(context, state_port_); VectorXd x = robot_output->GetState(); - double timestamp = robot_output->get_timestamp(); - auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if(relative_feet_){ - *casted_traj = GenerateRelativeTraj(); - } - else{ -// *casted_traj = GenerateFlightTraj(robot_output->GetState(), timestamp); - } + *casted_traj = GenerateRelativeTraj(); } } // namespace dairlib::examples::osc_jump diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.h b/examples/Cassie/osc_jump/flight_foot_traj_generator.h index c9a68341da..1d143ed869 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.h +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.h @@ -18,7 +18,7 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { bool isLeftFoot, const drake::trajectories::PiecewisePolynomial& foot_traj, const drake::trajectories::PiecewisePolynomial& hip_traj, - bool relative_feet = false, double time_offset = 0.0); + double time_offset = 0.0); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); @@ -43,7 +43,6 @@ class FlightFootTrajGenerator : public drake::systems::LeafSystem { drake::trajectories::PiecewisePolynomial foot_traj_; drake::trajectories::PiecewisePolynomial hip_traj_; - bool relative_feet_; int state_port_; int fsm_port_; }; diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.h b/examples/Cassie/osc_jump/osc_jumping_gains.h index ca80962910..29ee3efc5e 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.h +++ b/examples/Cassie/osc_jump/osc_jumping_gains.h @@ -7,7 +7,8 @@ using Eigen::MatrixXd; struct OSCJumpingGains : OSCGains { // costs - double x_offset; + double crouch_x_offset; + double land_x_offset; // center of mass tracking std::vector CoMW; std::vector CoMKp; @@ -28,6 +29,8 @@ struct OSCJumpingGains : OSCGains { double w_hip_yaw; double hip_yaw_kp; double hip_yaw_kd; + double min_pelvis_acc; + double max_pelvis_acc; double landing_delay; bool relative_feet; @@ -47,7 +50,8 @@ struct OSCJumpingGains : OSCGains { template void Serialize(Archive* a) { OSCGains::Serialize(a); - a->Visit(DRAKE_NVP(x_offset)); + a->Visit(DRAKE_NVP(crouch_x_offset)); + a->Visit(DRAKE_NVP(land_x_offset)); a->Visit(DRAKE_NVP(CoMW)); a->Visit(DRAKE_NVP(CoMKp)); a->Visit(DRAKE_NVP(CoMKd)); @@ -63,6 +67,8 @@ struct OSCJumpingGains : OSCGains { a->Visit(DRAKE_NVP(w_hip_yaw)); a->Visit(DRAKE_NVP(hip_yaw_kp)); a->Visit(DRAKE_NVP(hip_yaw_kd)); + a->Visit(DRAKE_NVP(min_pelvis_acc)); + a->Visit(DRAKE_NVP(max_pelvis_acc)); a->Visit(DRAKE_NVP(landing_delay)); a->Visit(DRAKE_NVP(relative_feet)); diff --git a/examples/Cassie/osc_jump/osc_jumping_gains.yaml b/examples/Cassie/osc_jump/osc_jumping_gains.yaml index e37ffc1137..948009b922 100644 --- a/examples/Cassie/osc_jump/osc_jumping_gains.yaml +++ b/examples/Cassie/osc_jump/osc_jumping_gains.yaml @@ -1,71 +1,78 @@ -w_input: 0.000 -w_lambda: 0.000 -w_accel: 0.0000001 +controller_frequency: 1000 +w_input: 0.000001 +w_lambda: 0.1 +w_accel: 0.0001 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001, 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.001] -W_input_reg: [1, 0.9, 0.5, 0.1, 5, - 1, 0.9, 0.5, 0.1, 5] +W_input_reg: [0.5, 0.9, 0.5, 0.1, 0.1, + 0.5, 0.9, 0.5, 0.1, 0.1] +# left toe, left heel, right toe, right heel: x y z W_lambda_c_reg: [1, 0.001, 0.01, 1, 0.001, 0.01, 1, 0.1, 0.01, 1, 0.1, 0.01] +# left_knee_spring, right_knee_spring, left_ankle_spring, right_ankle_spring, left_loop, right_loop W_lambda_h_reg: [0.01, 0.01, 0.01, 0.01, 0.02, 0.02] -w_input_reg: 0.001 -w_soft_constraint: 100 -x_offset: 0.0 +w_input_reg: 0.01 +w_soft_constraint: 1000 +crouch_x_offset: 0.00 +land_x_offset: 0.00 relative_feet: true -mu: 0.4 +mu: 0.6 -w_swing_toe: 1 -swing_toe_kp: 2000 +w_swing_toe: 0.01 +swing_toe_kp: 1500 swing_toe_kd: 10 -w_hip_yaw: 1 -hip_yaw_kp: 40 +w_hip_yaw: 2.5 +hip_yaw_kp: 100 hip_yaw_kd: 5 -impact_threshold: 0.050 +min_pelvis_acc: -25 +max_pelvis_acc: 100 +impact_threshold: 0.000 impact_tau: 0.005 -landing_delay: 0.0 +landing_delay: 0.000 +#landing_delay: -0.0 CoMW: [20, 0, 0, 0, 2, 0, 0, 0, 20] -PelvisRotW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] -FlightFootW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] CoMKp: - [30, 0, 0, + [40, 0, 0, 0, 50, 0, - 0, 0, 50] + 0, 0, 40] CoMKd: [ 7.5, 0, 0, 0, 5, 0, 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] PelvisRotKp: - [25, 0, 0, - 0, 50, 0, - 0, 0, 50] + [150., 0, 0, + 0, 200., 0, + 0, 0, 0.] PelvisRotKd: - [5, 0, 0, - 0, 10, 0, - 0, 0, 1] -FlightFootKp: - [100, 0, 0, + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +FlightFootW: + [10, 0, 0, 0, 100, 0, - 0, 0, 100] + 0, 0, 10] +FlightFootKp: + [125, 0, 0, + 0, 50, 0, + 0, 0, 150] FlightFootKd: - [10, 0, 0, - 0, 10, 0, + [2.5, 0, 0, + 0, 2.5, 0, 0, 0, 0] diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc index ea59ad508e..0d488cdf54 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.cc @@ -102,7 +102,7 @@ EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( switch_time << timestamp; } // Offset desired pelvis location based on final landing location - pelvis_x_offset(0) = kLandingOffset; + pelvis_x_offset(0) = landing_x_offset_; } if (initial_pelvis_pos == VectorXd::Zero(3)) { VectorXd q = robot_output->GetPositions(); @@ -117,7 +117,7 @@ EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( } drake::trajectories::PiecewisePolynomial -PelvisTransTrajGenerator::generateBalanceTraj( +PelvisTransTrajGenerator::GenerateBalanceTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const { plant_.SetPositionsAndVelocities(context_, x); @@ -150,7 +150,7 @@ PelvisTransTrajGenerator::generateBalanceTraj( } drake::trajectories::PiecewisePolynomial -PelvisTransTrajGenerator::generateCrouchTraj(const Eigen::VectorXd& x, +PelvisTransTrajGenerator::GenerateCrouchTraj(const Eigen::VectorXd& x, double time) const { // This assumes that the crouch is starting at the exact position as the // start of the target trajectory which should be handled by balance @@ -175,7 +175,7 @@ PelvisTransTrajGenerator::generateCrouchTraj(const Eigen::VectorXd& x, } drake::trajectories::PiecewisePolynomial -PelvisTransTrajGenerator::generateLandingTraj( +PelvisTransTrajGenerator::GenerateLandingTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const { plant_.SetPositionsAndVelocities(context_, x); @@ -230,11 +230,11 @@ void PelvisTransTrajGenerator::CalcTraj( const drake::VectorX& x = robot_output->GetState(); if (fsm_state[0] == BALANCE) - *casted_traj = generateBalanceTraj(context, x, time); + *casted_traj = GenerateBalanceTraj(context, x, time); else if (fsm_state[0] == CROUCH) - *casted_traj = generateCrouchTraj(x, time); + *casted_traj = GenerateCrouchTraj(x, time); else if (fsm_state[0] == LAND) - *casted_traj = generateLandingTraj(context, x, time); + *casted_traj = GenerateLandingTraj(context, x, time); } } // namespace dairlib::examples::osc_jump \ No newline at end of file diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h index 56ab16efe7..ddbf25ce8b 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h @@ -28,13 +28,17 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { return this->get_input_port(fsm_port_); } + void SetLandingOffset(double landing_x_offset){ + landing_x_offset_ = landing_x_offset; + } + private: - drake::trajectories::PiecewisePolynomial generateBalanceTraj( + drake::trajectories::PiecewisePolynomial GenerateBalanceTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const; - drake::trajectories::PiecewisePolynomial generateCrouchTraj( + drake::trajectories::PiecewisePolynomial GenerateCrouchTraj( const Eigen::VectorXd& x, double time) const; - drake::trajectories::PiecewisePolynomial generateLandingTraj( + drake::trajectories::PiecewisePolynomial GenerateLandingTraj( const drake::systems::Context& context, const Eigen::VectorXd& x, double time) const; @@ -62,6 +66,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { std::pair&>>& feet_contact_points_; double time_offset_; + double landing_x_offset_ = 0.00; drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex fsm_port_; @@ -69,7 +74,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { // The trajectory optimization solution sets the final CoM very close to // rear toe contacts - this is an offset to move it closer to the center of // the support polygon - static constexpr double kLandingOffset = 0.00; // 0.04 m (4cm) +// static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) // static constexpr double kLandingOffset = 0.04; // 0.04 m (4cm) }; diff --git a/examples/Cassie/osc_jump/toe_angle_traj_generator.cc b/examples/Cassie/osc_jump/toe_angle_traj_generator.cc index 78f9d21ae6..bb5edd1d4d 100644 --- a/examples/Cassie/osc_jump/toe_angle_traj_generator.cc +++ b/examples/Cassie/osc_jump/toe_angle_traj_generator.cc @@ -18,7 +18,7 @@ FlightToeAngleTrajGenerator::FlightToeAngleTrajGenerator( PiecewisePolynomial& toe_traj, int swing_toe_idx, const std::vector&>>& - feet_contact_points, + feet_contact_points, const std::string& traj_name) : plant_(plant), context_(context), @@ -30,10 +30,10 @@ FlightToeAngleTrajGenerator::FlightToeAngleTrajGenerator( use_traj_ = !toe_traj_.empty(); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector(plant.num_positions(), - plant.num_velocities(), - plant.num_actuators())) - .get_index(); + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel new file mode 100644 index 0000000000..8432f50563 --- /dev/null +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -0,0 +1,82 @@ +load("@drake//tools/lint:lint.bzl", "add_lint_tests") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:drake_lcm.bzl", + "drake_lcm_cc_library", + "drake_lcm_java_library", + "drake_lcm_py_library", +) +load( + "@drake//tools/skylark:drake_py.bzl", + "drake_py_binary", + "drake_py_library", + "drake_py_unittest", +) +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +cc_library( + name = "osc_run", + deps = [ + ":foot_traj_generator", + ":osc_running_gains", + ":pelvis_trans_traj_generator", + ], +) + +cc_binary( + name = "convert_traj_for_controller", + srcs = ["convert_traj_for_controller.cc"], + deps = [ + "//examples/Cassie:cassie_utils", + "//lcm:lcm_trajectory_saver", + "//lcm:dircon_trajectory_saver", + "//multibody:utils", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_library( + name = "osc_running_gains", + hdrs = ["osc_running_gains.h"], + deps = [ + "//systems/controllers/osc:osc_gains", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "pelvis_trans_traj_generator", + srcs = ["pelvis_trans_traj_generator.cc"], + hdrs = ["pelvis_trans_traj_generator.h"], + deps = [ + "//multibody:utils", + "//systems/controllers/osc:osc_gains", + "//examples/Cassie/contact_scheduler:all", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + + +cc_library( + name = "foot_traj_generator", + srcs = ["foot_traj_generator.cc"], + hdrs = ["foot_traj_generator.h"], + deps = [ + "//multibody:utils", + "//lcmtypes:lcmt_robot", + "//systems/controllers/osc:osc_gains", + "//examples/Cassie/contact_scheduler:all", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) diff --git a/examples/Cassie/osc_run/convert_traj_for_controller.cc b/examples/Cassie/osc_run/convert_traj_for_controller.cc new file mode 100644 index 0000000000..1a328e5f40 --- /dev/null +++ b/examples/Cassie/osc_run/convert_traj_for_controller.cc @@ -0,0 +1,392 @@ +#include +#include +#include + +#include "examples/Cassie/cassie_utils.h" +#include "lcm/dircon_saved_trajectory.h" +#include "lcm/lcm_trajectory.h" + +#include "drake/multibody/plant/multibody_plant.h" + +using drake::geometry::SceneGraph; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::Context; +using drake::trajectories::PiecewisePolynomial; +using Eigen::Matrix3Xd; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +DEFINE_string(trajectory_name, "", + "File name where the optimal trajectory is stored."); +DEFINE_string(folder_path, "", + "Folder path for where the trajectory names are stored"); +DEFINE_bool(mirror_traj, false, + "Whether or not to extend the trajectory by mirroring"); + +namespace dairlib { + +/// This program pre-pelvisputes the output trajectories (center of mass, pelvis +/// orientation, feet trajectories) for the OSC controller. +/// + +int DoMain() { + // Drake system initialization + drake::systems::DiagramBuilder builder; + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + MultibodyPlant plant(1e-5); // non-zero timestep to avoid continuous + // model warnings + Parser parser(&plant, &scene_graph); + parser.AddModelFromFile( + FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); + plant.mutable_gravity_field().set_gravity_vector(-9.81 * + Eigen::Vector3d::UnitZ()); + plant.Finalize(); + + std::unique_ptr> context = plant.CreateDefaultContext(); + + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + int nx = plant.num_positions() + plant.num_velocities(); + + auto l_toe_frame = &plant.GetBodyByName("toe_left").body_frame(); + auto r_toe_frame = &plant.GetBodyByName("toe_right").body_frame(); + auto hip_left_frame = &plant.GetBodyByName("hip_left").body_frame(); + auto hip_right_frame = &plant.GetBodyByName("hip_right").body_frame(); + auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); + auto world = &plant.world_frame(); + + DirconTrajectory dircon_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); + PiecewisePolynomial state_traj = + dircon_traj.ReconstructStateTrajectory(); + + MatrixXd M = dircon_traj.GetTrajectory("mirror_matrix").datapoints; + + double end_time = state_traj.end_time(); + + std::vector all_l_foot_points; + std::vector all_r_foot_points; + std::vector all_l_hip_points; + std::vector all_r_hip_points; + std::vector all_pelvis_points; + std::vector all_pelvis_orientation; + std::vector all_times; + Vector3d zero_offset = Vector3d::Zero(); + + for (int mode = 0; mode < dircon_traj.GetNumModes(); ++mode) { + if (dircon_traj.GetStateBreaks(mode).size() <= 1) { + continue; + } + VectorXd times = dircon_traj.GetStateBreaks(mode); + MatrixXd state_samples = dircon_traj.GetStateSamples(mode); + + int n_points = times.size(); + MatrixXd l_foot_points(9, n_points); + MatrixXd r_foot_points(9, n_points); + MatrixXd l_hip_points(9, n_points); + MatrixXd r_hip_points(9, n_points); + MatrixXd pelvis_points(9, n_points); + MatrixXd pelvis_orientation(12, n_points); + + for (unsigned int i = 0; i < times.size(); ++i) { + VectorXd x_i = state_samples.col(i).head(nx); + VectorXd xdot_i = state_samples.col(i).tail(nx); + + plant.SetPositionsAndVelocities(context.get(), x_i); + Eigen::Ref pelvis_pos_block = + pelvis_points.block(0, i, 3, 1); + Eigen::Ref l_foot_pos_block = + l_foot_points.block(0, i, 3, 1); + Eigen::Ref r_foot_pos_block = + r_foot_points.block(0, i, 3, 1); + Eigen::Ref l_hip_pos_block = + l_hip_points.block(0, i, 3, 1); + Eigen::Ref r_hip_pos_block = + r_hip_points.block(0, i, 3, 1); + plant.CalcPointsPositions(*context, *pelvis_frame, zero_offset, *world, + &pelvis_pos_block); + plant.CalcPointsPositions(*context, *l_toe_frame, zero_offset, *world, + &l_foot_pos_block); + plant.CalcPointsPositions(*context, *r_toe_frame, zero_offset, *world, + &r_foot_pos_block); + plant.CalcPointsPositions(*context, *hip_left_frame, zero_offset, *world, + &l_hip_pos_block); + plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, *world, + &r_hip_pos_block); + + pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); + pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); + + MatrixXd J_CoM(3, nv); + MatrixXd J_l_foot(3, nv); + MatrixXd J_r_foot(3, nv); + MatrixXd J_l_hip(3, nv); + MatrixXd J_r_hip(3, nv); + + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *pelvis_frame, zero_offset, + *world, *world, &J_CoM); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *l_toe_frame, zero_offset, *world, + *world, &J_l_foot); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *r_toe_frame, zero_offset, *world, + *world, &J_r_foot); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *hip_left_frame, zero_offset, + *world, *world, &J_l_hip); + plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, + *hip_right_frame, zero_offset, + *world, *world, &J_r_hip); + + VectorXd v_i = x_i.tail(nv); + pelvis_points.block(3, i, 3, 1) = J_CoM * v_i; + l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; + r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; + l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; + r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; + + VectorXd JdotV_CoM = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, *world, + *world); + VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, *world, + *world); + VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world); + + pelvis_points.block(6, i, 3, 1) = JdotV_CoM + J_CoM * xdot_i.tail(nv); + l_foot_points.block(6, i, 3, 1) = + JdotV_l_foot + J_l_foot * xdot_i.tail(nv); + r_foot_points.block(6, i, 3, 1) = + JdotV_r_foot + J_r_foot * xdot_i.tail(nv); + l_hip_points.block(6, i, 3, 1) = JdotV_l_hip + J_l_hip * xdot_i.tail(nv); + r_hip_points.block(6, i, 3, 1) = JdotV_r_hip + J_r_hip * xdot_i.tail(nv); + } + + all_times.push_back(times); + all_l_foot_points.push_back(l_foot_points); + all_r_foot_points.push_back(r_foot_points); + all_l_hip_points.push_back(l_hip_points); + all_r_hip_points.push_back(r_hip_points); + all_pelvis_points.push_back(pelvis_points); + all_pelvis_orientation.push_back(pelvis_orientation); + } + + if (FLAGS_mirror_traj) { + double x_offset = state_traj.value(state_traj.end_time())(4) - + state_traj.value(state_traj.start_time())(4); + // Extended trajectory + for (int mode = 0; mode < dircon_traj.GetNumModes(); ++mode) { + if (dircon_traj.GetStateBreaks(mode).size() <= 1) { + continue; + } + VectorXd times = + dircon_traj.GetStateBreaks(mode) + + end_time * VectorXd::Ones(dircon_traj.GetStateBreaks(mode).size()); + MatrixXd x_samples = M * dircon_traj.GetStateSamples(mode).topRows(nx); + MatrixXd xdot_samples = + M * dircon_traj.GetStateSamples(mode).bottomRows(nx); + + int n_points = times.size(); + MatrixXd l_foot_points(9, n_points); + MatrixXd r_foot_points(9, n_points); + MatrixXd l_hip_points(9, n_points); + MatrixXd r_hip_points(9, n_points); + MatrixXd pelvis_points(9, n_points); + MatrixXd pelvis_orientation(12, n_points); + + for (unsigned int i = 0; i < times.size(); ++i) { + // VectorXd x_i = M * state_samples.col(i).head(nx); + // VectorXd xdot_i = M * state_samples.col(i).tail(nx); + VectorXd x_i = x_samples.col(i); + VectorXd xdot_i = xdot_samples.col(i); + x_i(4) = x_i(4) + x_offset; + + plant.SetPositionsAndVelocities(context.get(), x_i); + Eigen::Ref pelvis_pos_block = + pelvis_points.block(0, i, 3, 1); + Eigen::Ref l_foot_pos_block = + l_foot_points.block(0, i, 3, 1); + Eigen::Ref r_foot_pos_block = + r_foot_points.block(0, i, 3, 1); + Eigen::Ref l_hip_pos_block = + l_hip_points.block(0, i, 3, 1); + Eigen::Ref r_hip_pos_block = + r_hip_points.block(0, i, 3, 1); + plant.CalcPointsPositions(*context, *pelvis_frame, zero_offset, *world, + &pelvis_pos_block); + plant.CalcPointsPositions(*context, *l_toe_frame, zero_offset, *world, + &l_foot_pos_block); + plant.CalcPointsPositions(*context, *r_toe_frame, zero_offset, *world, + &r_foot_pos_block); + plant.CalcPointsPositions(*context, *hip_left_frame, zero_offset, + *world, &l_hip_pos_block); + plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, + *world, &r_hip_pos_block); + + pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); + pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); + + MatrixXd J_CoM(3, nv); + MatrixXd J_l_foot(3, nv); + MatrixXd J_r_foot(3, nv); + MatrixXd J_l_hip(3, nv); + MatrixXd J_r_hip(3, nv); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, + *world, *world, &J_CoM); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, + *world, *world, &J_l_foot); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, + *world, *world, &J_r_foot); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world, &J_l_hip); + plant.CalcJacobianTranslationalVelocity( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world, &J_r_hip); + + VectorXd v_i = x_i.tail(nv); + pelvis_points.block(3, i, 3, 1) = J_CoM * v_i; + l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; + r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; + l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; + r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; + + VectorXd JdotV_CoM = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, + *world, *world); + VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, + *world, *world); + VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, + *world, *world); + VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( + *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, + *world, *world); + + pelvis_points.block(6, i, 3, 1) = JdotV_CoM + J_CoM * xdot_i.tail(nv); + l_foot_points.block(6, i, 3, 1) = + JdotV_l_foot + J_l_foot * xdot_i.tail(nv); + r_foot_points.block(6, i, 3, 1) = + JdotV_r_foot + J_r_foot * xdot_i.tail(nv); + l_hip_points.block(6, i, 3, 1) = + JdotV_l_hip + J_l_hip * xdot_i.tail(nv); + r_hip_points.block(6, i, 3, 1) = + JdotV_r_hip + J_r_hip * xdot_i.tail(nv); + } + + all_times.push_back(times); + all_l_foot_points.push_back(l_foot_points); + all_r_foot_points.push_back(r_foot_points); + all_l_hip_points.push_back(l_hip_points); + all_r_hip_points.push_back(r_hip_points); + all_pelvis_points.push_back(pelvis_points); + all_pelvis_orientation.push_back(pelvis_orientation); + } + } + + std::vector converted_trajectories; + std::vector trajectory_names; + + for (int mode = 0; mode < all_times.size(); ++mode) { + auto lfoot_traj_block = LcmTrajectory::Trajectory(); + lfoot_traj_block.traj_name = "left_foot_trajectory" + std::to_string(mode); + lfoot_traj_block.datapoints = all_l_foot_points[mode]; + lfoot_traj_block.time_vector = all_times[mode]; + lfoot_traj_block.datatypes = {"lfoot_x", "lfoot_y", "lfoot_z", + "lfoot_xdot", "lfoot_ydot", "lfoot_zdot", + "lfoot_xddot", "lfoot_yddot", "lfoot_zddot"}; + + auto rfoot_traj_block = LcmTrajectory::Trajectory(); + rfoot_traj_block.traj_name = "right_foot_trajectory" + std::to_string(mode); + rfoot_traj_block.datapoints = all_r_foot_points[mode]; + rfoot_traj_block.time_vector = all_times[mode]; + rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", + "rfoot_xdot", "rfoot_ydot", "rfoot_zdot", + "rfoot_xddot", "rfoot_yddot", "rfoot_zddot"}; + + auto lhip_traj_block = LcmTrajectory::Trajectory(); + lhip_traj_block.traj_name = "left_hip_trajectory" + std::to_string(mode); + lhip_traj_block.datapoints = all_l_hip_points[mode]; + lhip_traj_block.time_vector = all_times[mode]; + lhip_traj_block.datatypes = {"lhip_x", "lhip_y", "lhip_z", + "lhip_xdot", "lhip_ydot", "lhip_zdot", + "lhip_xddot", "lhip_yddot", "lhip_zddot"}; + + auto rhip_traj_block = LcmTrajectory::Trajectory(); + rhip_traj_block.traj_name = "right_hip_trajectory" + std::to_string(mode); + rhip_traj_block.datapoints = all_r_hip_points[mode]; + rhip_traj_block.time_vector = all_times[mode]; + rhip_traj_block.datatypes = {"rhip_x", "rhip_y", "rhip_z", + "rhip_xdot", "rhip_ydot", "rhip_zdot", + "rhip_xddot", "rhip_yddot", "rhip_zddot"}; + + auto pelvis_traj_block = LcmTrajectory::Trajectory(); + pelvis_traj_block.traj_name = + "pelvis_trans_trajectory" + std::to_string(mode); + pelvis_traj_block.datapoints = all_pelvis_points[mode]; + pelvis_traj_block.time_vector = all_times[mode]; + pelvis_traj_block.datatypes = { + "pelvis_x", "pelvis_y", "pelvis_z", + "pelvis_xdot", "pelvis_ydot", "pelvis_zdot", + "pelvis_xddot", "pelvis_yddot", "pelvis_zddot"}; + + auto pelvis_orientation_block = LcmTrajectory::Trajectory(); + pelvis_orientation_block.traj_name = + "pelvis_rot_trajectory" + std::to_string(mode); + pelvis_orientation_block.datapoints = all_pelvis_orientation[mode]; + pelvis_orientation_block.time_vector = all_times[mode]; + pelvis_orientation_block.datatypes = { + "pelvis_rotw", "pelvis_rotx", "pelvis_roty", + "pelvis_rotz", "pelvis_rotwdot", "pelvis_rotxdot", + "pelvis_rotydot", "pelvis_rotzdot", "pelvis_rotwddot", + "pelvis_rotxddot", "pelvis_rotyddot", "pelvis_rotzddot"}; + + converted_trajectories.push_back(lfoot_traj_block); + converted_trajectories.push_back(rfoot_traj_block); + converted_trajectories.push_back(lhip_traj_block); + converted_trajectories.push_back(rhip_traj_block); + converted_trajectories.push_back(pelvis_traj_block); + converted_trajectories.push_back(pelvis_orientation_block); + trajectory_names.push_back(lfoot_traj_block.traj_name); + trajectory_names.push_back(rfoot_traj_block.traj_name); + trajectory_names.push_back(lhip_traj_block.traj_name); + trajectory_names.push_back(rhip_traj_block.traj_name); + trajectory_names.push_back(pelvis_traj_block.traj_name); + trajectory_names.push_back(pelvis_orientation_block.traj_name); + } + + auto processed_traj = LcmTrajectory(converted_trajectories, trajectory_names, + "walking_trajectory", + "Output trajectories " + "for Cassie walking"); + + processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + + "_processed_rel"); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + dairlib::DoMain(); +} \ No newline at end of file diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc new file mode 100644 index 0000000000..045d64e164 --- /dev/null +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -0,0 +1,272 @@ +#include "foot_traj_generator.h" + +#include + +#include "dairlib/lcmt_radio_out.hpp" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::Vector4d; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::BodyFrame; +using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib::examples::osc_run { + +FootTrajGenerator::FootTrajGenerator(const MultibodyPlant& plant, + Context* context, + const string& foot_name, + const string& hip_name, + const int stance_state) + : plant_(plant), + context_(context), + world_(plant.world_frame()), + foot_frame_(plant.GetFrameByName(foot_name)), + hip_frame_(plant.GetFrameByName(hip_name)), + stance_state_(stance_state) { + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + target_vel_filter_ = std::make_unique(1.0, 2); + + if (foot_name == "toe_left") { + is_left_foot_ = true; + this->set_name("left_ft_traj"); + this->DeclareAbstractOutputPort("left_ft_traj", traj_inst, + &FootTrajGenerator::CalcTraj); + } else { + is_left_foot_ = false; + this->set_name("right_ft_traj"); + this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, + &FootTrajGenerator::CalcTraj); + } + + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + target_vel_port_ = this->DeclareVectorInputPort( + "v_des", BasicVector(VectorXd::Zero(2))) + .get_index(); + fsm_port_ = this->DeclareVectorInputPort( + "fsm", BasicVector(VectorXd::Zero(1))) + .get_index(); + clock_port_ = this->DeclareVectorInputPort( + "clock", BasicVector(VectorXd::Zero(1))) + .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + contact_scheduler_port_ = + this->DeclareVectorInputPort("t_mode", BasicVector(6)) + .get_index(); + + // The swing foot position in the beginning of the swing phase + initial_foot_pos_idx_ = this->DeclareDiscreteState(3); + initial_hip_pos_idx_ = this->DeclareDiscreteState(3); + pelvis_yaw_idx_ = this->DeclareDiscreteState(1); + pelvis_vel_est_idx_ = this->DeclareDiscreteState(3); + last_stance_timestamp_idx_ = this->DeclareDiscreteState(1); + + // State variables inside this controller block + DeclarePerStepDiscreteUpdateEvent(&FootTrajGenerator::DiscreteVariableUpdate); + + m_ = plant_.CalcTotalMass(*context_); +} + +EventStatus FootTrajGenerator::DiscreteVariableUpdate( + const Context& context, + DiscreteValues* discrete_state) const { + // Read in current state + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + // Read in finite state machine + VectorXd fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value(); + + VectorXd q = robot_output->GetPositions(); + VectorXd v = robot_output->GetVelocities(); + multibody::SetPositionsIfNew(plant_, q, context_); + + Vector3d pelvis_heading_vec = + plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) + .rotation() + .col(0); + double approx_pelvis_yaw = + atan2(pelvis_heading_vec(1), pelvis_heading_vec(0)); + discrete_state->get_mutable_vector(pelvis_yaw_idx_).get_mutable_value()(0) = + approx_pelvis_yaw; + + Eigen::Matrix3d rot; + rot << cos(approx_pelvis_yaw), -sin(approx_pelvis_yaw), 0, + sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; + + // Only update the current foot position when in stance ( + if (fsm_state(0) == stance_state_) { + auto foot_pos = discrete_state->get_mutable_vector(initial_foot_pos_idx_) + .get_mutable_value(); + plant_.CalcPointsPositions(*context_, foot_frame_, Vector3d::Zero(), world_, + &foot_pos); + auto hip_pos = discrete_state->get_mutable_vector(initial_hip_pos_idx_) + .get_mutable_value(); + plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, + &hip_pos); + foot_pos = rot.transpose() * foot_pos; + hip_pos = rot.transpose() * hip_pos; + } + + return EventStatus::Succeeded(); +} + +PiecewisePolynomial FootTrajGenerator::GenerateFlightTraj( + const drake::systems::Context& context) const { + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + const auto desired_pelvis_vel_xy = + this->EvalVectorInput(context, target_vel_port_)->get_value(); + const auto& mode_lengths = + this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); + + double pelvis_t0 = mode_lengths[0]; + double pelvis_tf = mode_lengths[1]; + double left_t0 = mode_lengths[2]; + double left_tf = mode_lengths[3]; + double right_t0 = mode_lengths[4]; + double right_tf = mode_lengths[5]; + + // Offset between 0 and 2 + double lateral_radio_tuning = 1.0; + double sagital_radio_tuning = 1.0; + if (this->get_input_port(radio_port_).HasValue(context)) { + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + lateral_radio_tuning += radio_out->channel[4]; + sagital_radio_tuning += radio_out->channel[5]; + } + + VectorXd v = robot_output->GetVelocities(); + multibody::SetPositionsAndVelocitiesIfNew( + plant_, robot_output->GetState(), context_); + + Vector3d pelvis_heading_vec = + plant_.EvalBodyPoseInWorld(*context_, plant_.GetBodyByName("pelvis")) + .rotation() + .col(0); + double approx_pelvis_yaw = + atan2(pelvis_heading_vec(1), pelvis_heading_vec(0)); + Eigen::Matrix3d rot; + rot << cos(approx_pelvis_yaw), -sin(approx_pelvis_yaw), 0, + sin(approx_pelvis_yaw), cos(approx_pelvis_yaw), 0, 0, 0, 1; + + // TODO(yangwill): should not use estimated pelvis velocity - from discussion + // with OSU DRL + + Vector3d desired_pelvis_vel; + target_vel_filter_->Update(desired_pelvis_vel_xy); + desired_pelvis_vel << target_vel_filter_->Value(), 0; + + auto foot_pos = context.get_discrete_state(initial_foot_pos_idx_).get_value(); + Vector3d pelvis_pos; + plant_.CalcPointsPositions(*context_, hip_frame_, Vector3d::Zero(), world_, + &pelvis_pos); + + VectorXd pelvis_vel = v.segment(3, 3); + VectorXd pelvis_vel_err = rot.transpose() * pelvis_vel - desired_pelvis_vel; + + std::vector T_waypoints; + + double x_mid_point_ratio = 0.8; + double t_mid_point_ratio = 0.6; + + if (is_left_foot_) { + T_waypoints = {left_t0, left_t0 + t_mid_point_ratio * (left_tf - left_t0), + left_tf}; + } else { + T_waypoints = {right_t0, + right_t0 + t_mid_point_ratio * (right_tf - right_t0), + right_tf}; + } + + // TODO(yangwill): Footsteps are planned with constant stance duration T_s of + // 0.3s + VectorXd foot_end_pos_des = + 0.5 * (0.3) * rot.transpose() * pelvis_vel + Kd_ * (pelvis_vel_err); + + if (is_left_foot_) { + foot_end_pos_des(1) += lateral_radio_tuning * lateral_offset_; + } else { + foot_end_pos_des(1) -= lateral_radio_tuning * lateral_offset_; + } + foot_end_pos_des(0) += sagital_radio_tuning * sagital_offset_; + foot_end_pos_des(2) = -rest_length_ - rest_length_offset_; + + auto hip_pos = context.get_discrete_state(initial_hip_pos_idx_).get_value(); + std::vector Y(T_waypoints.size(), VectorXd::Zero(3)); + VectorXd start_pos = foot_pos - hip_pos; + Y[0] = start_pos; + if (start_pos(2) == 0) { + Y[0](2) = -rest_length_; + } + Y[1] = start_pos + x_mid_point_ratio * (foot_end_pos_des - start_pos); + double foot_height_scale = std::clamp(pelvis_vel[0] / 2.5, 1.0, 1.4); + Y[1](2) += foot_height_scale * mid_foot_height_; + Y[2] = foot_end_pos_des; + + // prevent foot collisions + if (is_left_foot_) { + Y[1](1) = std::clamp(Y[1](1), lateral_offset_, 0.2); + Y[2](1) = std::clamp(Y[2](1), lateral_offset_, 0.2); + + } else { + Y[1](1) = std::clamp(Y[1](1), -0.2, -lateral_offset_); + Y[2](1) = std::clamp(Y[2](1), -0.2, -lateral_offset_); + } + Y[1](0) = std::clamp(Y[1](0), -0.4, 0.4); + Y[2](0) = std::clamp(Y[2](0), -0.4, 0.4); + + PiecewisePolynomial swing_foot_spline = + PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + T_waypoints, Y, false); + return swing_foot_spline; +} + +void FootTrajGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // // Read in finite state machine + const auto fsm_state = + this->EvalVectorInput(context, fsm_port_)->get_value()[0]; + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (is_left_foot_) { + if (fsm_state != LEFT_STANCE) { + *casted_traj = GenerateFlightTraj(context); + } + + } else { + if (fsm_state != RIGHT_STANCE) { + *casted_traj = GenerateFlightTraj(context); + } + } +} + +} // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h new file mode 100644 index 0000000000..c255189ed3 --- /dev/null +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -0,0 +1,104 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" +#include "common/discrete_time_filter.h" + +namespace dairlib::examples::osc_run { + +class FootTrajGenerator : public drake::systems::LeafSystem { + public: + FootTrajGenerator(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const std::string& foot_name, const std::string& hip_name, + int stance_state); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_fsm() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_input_port_clock() const { + return this->get_input_port(clock_port_); + } + const drake::systems::InputPort& get_input_port_target_vel() const { + return this->get_input_port(target_vel_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + const drake::systems::InputPort& get_input_port_contact_scheduler() const { + return this->get_input_port(contact_scheduler_port_); + } + + void SetCommandFilter(double alpha){ + target_vel_filter_->UpdateParameters(alpha); + } + + void SetFootstepGains(const Eigen::MatrixXd& Kd) { Kd_ = Kd; }; + + void SetFootPlacementOffsets(double rest_length, double rest_length_offset, double center_line_offset, + double footstep_offset, double mid_foot_height) { + rest_length_ = rest_length; + rest_length_offset_ = rest_length_offset; + lateral_offset_ = center_line_offset; + sagital_offset_ = footstep_offset; + mid_foot_height_ = mid_foot_height; + } + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + drake::trajectories::PiecewisePolynomial GenerateFlightTraj( + const drake::systems::Context& context) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::Frame& world_; + const drake::multibody::Frame& foot_frame_; + const drake::multibody::Frame& hip_frame_; + + // Foot spline parameters +// std::vector state_durations_; + + // Foot placement constants + double rest_length_; + double rest_length_offset_; + double lateral_offset_; + double sagital_offset_; + double mid_foot_height_; + double m_; + + // Raibert Footstep Gains + Eigen::MatrixXd Kd_ = Eigen::MatrixXd::Zero(3, 3); + + bool is_left_foot_; + int stance_state_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex target_vel_port_; + drake::systems::InputPortIndex fsm_port_; + drake::systems::InputPortIndex clock_port_; + drake::systems::InputPortIndex radio_port_; + drake::systems::InputPortIndex contact_scheduler_port_; + + int initial_foot_pos_idx_; + int initial_hip_pos_idx_; + int pelvis_yaw_idx_; + int pelvis_vel_est_idx_; + int last_stance_timestamp_idx_; + + std::unique_ptr target_vel_filter_; + +}; + +} // namespace dairlib::examples::osc_run diff --git a/examples/Cassie/osc_run/osc_running_gains.h b/examples/Cassie/osc_run/osc_running_gains.h new file mode 100644 index 0000000000..e1fe818dfe --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_gains.h @@ -0,0 +1,172 @@ +#pragma once + +#include "systems/controllers/osc/osc_gains.h" +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct OSCRunningGains : OSCGains { + + double weight_scaling; + double w_swing_toe; + double swing_toe_kp; + double swing_toe_kd; + double w_hip_yaw; + double hip_yaw_kp; + double hip_yaw_kd; + double vel_scale_rot; + double vel_scale_trans_sagital; + double vel_scale_trans_lateral; + double target_vel_filter_alpha; + bool no_derivative_feedback; + double rest_length; + double rest_length_offset; + double stance_duration; + double flight_duration; + double stance_variance; + double flight_variance; + + double footstep_lateral_offset; + double footstep_sagital_offset; + double mid_foot_height; + + std::vector ekf_filter_tau; + double rot_filter_tau; + double w_input_accel; + double w_joint_limit; + + // swing foot tracking + std::vector SwingFootW; + std::vector SwingFootKp; + std::vector SwingFootKd; + // swing foot tracking for the non-touchdown foot + std::vector LiftoffSwingFootW; + std::vector LiftoffSwingFootKp; + std::vector LiftoffSwingFootKd; + // pelvis tracking + std::vector PelvisW; + std::vector PelvisKp; + std::vector PelvisKd; + // pelvis tracking + std::vector PelvisRotW; + std::vector PelvisRotKp; + std::vector PelvisRotKd; + // pelvis orientation tracking + std::vector FootstepKd; + + MatrixXd K_d_footstep; + MatrixXd W_pelvis; + MatrixXd K_p_pelvis; + MatrixXd K_d_pelvis; + MatrixXd W_pelvis_rot; + MatrixXd K_p_pelvis_rot; + MatrixXd K_d_pelvis_rot; + MatrixXd W_swing_foot; + MatrixXd K_p_swing_foot; + MatrixXd K_d_swing_foot; + MatrixXd W_swing_toe; + MatrixXd K_p_swing_toe; + MatrixXd K_d_swing_toe; + MatrixXd W_hip_yaw; + MatrixXd K_p_hip_yaw; + MatrixXd K_d_hip_yaw; + + template + void Serialize(Archive* a) { + OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(controller_frequency)); + a->Visit(DRAKE_NVP(weight_scaling)); + a->Visit(DRAKE_NVP(no_derivative_feedback)); + a->Visit(DRAKE_NVP(rest_length)); + a->Visit(DRAKE_NVP(rest_length_offset)); + a->Visit(DRAKE_NVP(stance_duration)); + a->Visit(DRAKE_NVP(flight_duration)); + a->Visit(DRAKE_NVP(stance_variance)); + a->Visit(DRAKE_NVP(flight_variance)); + a->Visit(DRAKE_NVP(footstep_lateral_offset)); + a->Visit(DRAKE_NVP(footstep_sagital_offset)); + a->Visit(DRAKE_NVP(mid_foot_height)); + a->Visit(DRAKE_NVP(ekf_filter_tau)); + a->Visit(DRAKE_NVP(rot_filter_tau)); + a->Visit(DRAKE_NVP(w_input_accel)); + a->Visit(DRAKE_NVP(w_joint_limit)); + + + a->Visit(DRAKE_NVP(PelvisW)); + a->Visit(DRAKE_NVP(PelvisKp)); + a->Visit(DRAKE_NVP(PelvisKd)); + a->Visit(DRAKE_NVP(PelvisRotW)); + a->Visit(DRAKE_NVP(PelvisRotKp)); + a->Visit(DRAKE_NVP(PelvisRotKd)); + a->Visit(DRAKE_NVP(FootstepKd)); + a->Visit(DRAKE_NVP(SwingFootW)); + a->Visit(DRAKE_NVP(SwingFootKp)); + a->Visit(DRAKE_NVP(SwingFootKd)); + a->Visit(DRAKE_NVP(LiftoffSwingFootW)); + a->Visit(DRAKE_NVP(LiftoffSwingFootKp)); + a->Visit(DRAKE_NVP(LiftoffSwingFootKd)); + a->Visit(DRAKE_NVP(w_swing_toe)); + a->Visit(DRAKE_NVP(swing_toe_kp)); + a->Visit(DRAKE_NVP(swing_toe_kd)); + a->Visit(DRAKE_NVP(w_hip_yaw)); + a->Visit(DRAKE_NVP(hip_yaw_kp)); + a->Visit(DRAKE_NVP(hip_yaw_kd)); + // High level command gains (with radio) + a->Visit(DRAKE_NVP(vel_scale_rot)); + a->Visit(DRAKE_NVP(vel_scale_trans_sagital)); + a->Visit(DRAKE_NVP(vel_scale_trans_lateral)); + a->Visit(DRAKE_NVP(target_vel_filter_alpha)); + + W_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->SwingFootW.data(), 3, 3); + K_p_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->SwingFootKp.data(), 3, 3); + K_d_swing_foot = Eigen::Map< + Eigen::Matrix>( + this->SwingFootKd.data(), 3, 3); + W_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisW.data(), 3, 3); + K_p_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisKp.data(), 3, 3); + K_d_pelvis = Eigen::Map< + Eigen::Matrix>( + this->PelvisKd.data(), 3, 3); + W_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotW.data(), 3, 3); + K_p_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKp.data(), 3, 3); + K_d_pelvis_rot = Eigen::Map< + Eigen::Matrix>( + this->PelvisRotKd.data(), 3, 3); + K_d_footstep = Eigen::Map< + Eigen::Matrix>( + this->FootstepKd.data(), 3, 3); + + W_swing_toe = this->w_swing_toe * MatrixXd::Identity(1, 1); + K_p_swing_toe = this->swing_toe_kp * MatrixXd::Identity(1, 1); + K_d_swing_toe = this->swing_toe_kd * MatrixXd::Identity(1, 1); + W_hip_yaw = this->w_hip_yaw * MatrixXd::Identity(1, 1); + K_p_hip_yaw = this->hip_yaw_kp * MatrixXd::Identity(1, 1); + K_d_hip_yaw = this->hip_yaw_kd * MatrixXd::Identity(1, 1); + + w_accel *= weight_scaling; + w_input *= weight_scaling; + w_input_reg *= weight_scaling; + w_lambda *= weight_scaling; + w_soft_constraint *= weight_scaling; + w_joint_limit *= weight_scaling; + W_pelvis *= weight_scaling; + W_pelvis_rot *= weight_scaling; + W_swing_foot *= weight_scaling; + W_swing_toe *= weight_scaling; + W_hip_yaw *= weight_scaling; + } +}; \ No newline at end of file diff --git a/examples/Cassie/osc_run/osc_running_gains.yaml b/examples/Cassie/osc_run/osc_running_gains.yaml new file mode 100644 index 0000000000..4d0988cd35 --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_gains.yaml @@ -0,0 +1,111 @@ +# target_frequency Hz +controller_frequency: 1000 + +w_input: 0.000001 +w_input_reg: 0.01 +w_accel: 0.0001 +w_soft_constraint: 10000 +w_lambda: 0.1 +w_input_accel: 0.1 +w_joint_limit: 0 +impact_threshold: 0.050 +impact_tau: 0.005 +weight_scaling: 1.0 +mu: 0.6 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001, + 1, 1, 1, 1, 0.01, 0.01, 0.01, 0.0001 ] +W_input_reg: [ 1, 0.9, 0.5, 0.1, 1, + 1, 0.9, 0.5, 0.1, 1 ] +W_lambda_c_reg: [ 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01, + 1, 0.001, 0.01 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.001, 0.001 ] +#w_soft_constraint: 1000000 + +no_derivative_feedback: false +rot_filter_tau: 0.005 +ekf_filter_tau: [ 0.05, 0.01, 0.001 ] + +# High level command gains (with radio) +vel_scale_rot: -4 +vel_scale_trans_sagital: 15 +vel_scale_trans_lateral: -0.5 +target_vel_filter_alpha: 0.01 + +# SLIP parameters +rest_length: 0.85 +rest_length_offset: 0.025 +stance_duration: 0.3 +flight_duration: 0.09 +# max percent variance +stance_variance: 0.2 +flight_variance: 0.1 + +w_swing_toe: 0.01 +swing_toe_kp: 1500 +swing_toe_kd: 10 + +w_hip_yaw: 2.5 +hip_yaw_kp: 100 +hip_yaw_kd: 7 +# Foot placement parameters +#footstep_offset: -0.05 +footstep_sagital_offset: -0.00 +footstep_lateral_offset: 0.04 # drake +mid_foot_height: 0.3 +FootstepKd: + [ 0.01, 0, 0, + 0, 0.3, 0, + 0, 0, 0 ] +PelvisW: + [ 0, 0, 0, + 0, 1, 0, + 0, 0, 5] +PelvisKp: + [ 0, 0, 0, + 0, 40, 0, + 0, 0, 115] +PelvisKd: + [ 0, 0, 0, + 0, 10, 0, + 0, 0, 5] +PelvisRotW: + [10, 0, 0, + 0, 5, 0, + 0, 0, 1] +PelvisRotKp: + [150., 0, 0, + 0, 200., 0, + 0, 0, 0.] +PelvisRotKd: + [10, 0, 0, + 0, 10, 0, + 0, 0, 5.] +SwingFootW: + [10, 0, 0, + 0, 100, 0, + 0, 0, 10] +SwingFootKp: + [125, 0, 0, + 0, 75, 0, + 0, 0, 75] +SwingFootKd: + [5., 0, 0, + 0, 5., 0, + 0, 0, 5.] +LiftoffSwingFootW: + [0, 0, 0, + 0, 0, 0, + 0, 0, 0] +LiftoffSwingFootKp: + [0, 0, 0, + 0, 0, 0, + 0, 0, 0] +LiftoffSwingFootKd: + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 0] diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml new file mode 100644 index 0000000000..9ec13c9f16 --- /dev/null +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -0,0 +1,22 @@ +rho: 0.001 +sigma: 1e-6 +max_iter: 250 +eps_abs: 1e-5 +eps_rel: 1e-5 +eps_prim_inf: 1e-5 +eps_dual_inf: 1e-5 +alpha: 1.6 +linsys_solver: 0 +delta: 1e-6 +polish: 1 +polish_refine_iter: 1 +verbose: 0 +scaled_termination: 1 +check_termination: 25 +warm_start: 1 +scaling: 1 +adaptive_rho: 1 +adaptive_rho_interval: 0 +adaptive_rho_tolerance: 5 +adaptive_rho_fraction: 0.4 +time_limit: 0 diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc new file mode 100644 index 0000000000..0049e6796a --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -0,0 +1,145 @@ +#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" + +#include + +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" +#include "multibody/multibody_utils.h" +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +using std::string; +using std::vector; + +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::systems::OutputVector; +using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib::examples::osc { + +PelvisTransTrajGenerator::PelvisTransTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const std::unordered_map< + int, std::vector&>>>& + feet_contact_points) + : plant_(plant), + context_(context), + world_(plant_.world_frame()), + pelvis_(plant_.GetBodyByName("pelvis")), + feet_contact_points_(feet_contact_points){ + this->set_name("pelvis_trans_traj_generator"); + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + fsm_port_ = + this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); + clock_port_ = this->DeclareVectorInputPort("t_clock", BasicVector(1)) + .get_index(); + contact_scheduler_port_ = + this->DeclareVectorInputPort("t_mode", BasicVector(6)) + .get_index(); + + PiecewisePolynomial empty_traj(VectorXd(0)); + Trajectory& traj_inst = empty_traj; + this->DeclareAbstractOutputPort("pelvis_trans_traj", traj_inst, + &PelvisTransTrajGenerator::CalcTraj); + + DeclarePerStepDiscreteUpdateEvent( + &PelvisTransTrajGenerator::DiscreteVariableUpdate); +} + +EventStatus PelvisTransTrajGenerator::DiscreteVariableUpdate( + const Context& context, + DiscreteValues* discrete_state) const { + return EventStatus::Succeeded(); +} + +PiecewisePolynomial PelvisTransTrajGenerator::GenerateSLIPTraj( + const VectorXd& x, double t0, double tf, int fsm_state) const { + DRAKE_DEMAND(fsm_state < 2); + + Vector3d f_g = + drake::multibody::UniformGravityFieldElement().gravity_vector(); + Vector3d foot_pos = Vector3d::Zero(); + Vector3d pelvis_pos = Vector3d::Zero(); + Vector3d pelvis_vel = Vector3d::Zero(); + plant_.CalcPointsPositions(*context_, + feet_contact_points_.at(fsm_state)[0].second, + Vector3d::Zero(), world_, &foot_pos); + pelvis_pos = plant_.CalcCenterOfMassPositionInWorld(*context_); + pelvis_vel = + plant_.EvalBodySpatialVelocityInWorld(*context_, pelvis_).translational(); + Vector3d leg_length = pelvis_pos - foot_pos; + + double compression = leg_length.norm() - rest_length_; + Vector3d f_leg = + k_leg_ * compression * leg_length.normalized() + b_leg_ * pelvis_vel; + // ignoring f_leg, spring forces handled by OSC gains + Vector3d rddot = f_g; + + double dt = 1e-2; + Eigen::Vector2d breaks; + breaks << t0, tf; + MatrixXd samples(3, 2); + MatrixXd samples_dot(3, 2); + + double y_dist_des = 0; + if (fsm_state == 0) { + y_dist_des = -0.1; + } else if (fsm_state == 1) { + y_dist_des = 0.1; + } + + samples << 0, 0 + 0.5 * rddot[0] * dt * dt, y_dist_des, + y_dist_des + 0.5 * rddot[1] * dt * dt, rest_length_, + rest_length_ + 0.5 * rddot[2] * dt * dt; + samples_dot << 0, 0 + rddot[0] * dt, 0, 0 + rddot[1] * dt, 0, + 0 + rddot[2] * dt; + + return PiecewisePolynomial::CubicHermite(breaks, samples, + samples_dot); +} + +void PelvisTransTrajGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // Read in current state + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + // Read in finite state machine + const auto& fsm_state = + this->EvalVectorInput(context, fsm_port_)->get_value()(0); + const auto& clock = + this->EvalVectorInput(context, clock_port_)->get_value()(0); + const auto& mode_length = + this->EvalVectorInput(context, contact_scheduler_port_)->get_value(); + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (fsm_state == LEFT_STANCE || fsm_state == RIGHT_STANCE) { + *casted_traj = GenerateSLIPTraj(robot_output->GetState(), mode_length[0], + mode_length[1], fsm_state); + } +} + +} // namespace dairlib::examples::osc \ No newline at end of file diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h new file mode 100644 index 0000000000..a6193b549a --- /dev/null +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -0,0 +1,75 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib::examples::osc { + +class PelvisTransTrajGenerator : public drake::systems::LeafSystem { + public: + PelvisTransTrajGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const std::unordered_map< + int, std::vector&>>>& + feet_contact_points); + + const drake::systems::InputPort& get_state_input_port() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_fsm_input_port() const { + return this->get_input_port(fsm_port_); + } + const drake::systems::InputPort& get_clock_input_port() const { + return this->get_input_port(clock_port_); + } + const drake::systems::InputPort& get_contact_scheduler_input_port() + const { + return this->get_input_port(contact_scheduler_port_); + } + + void SetSLIPParams(double rest_length, double rest_length_offset) { + rest_length_ = rest_length; + rest_length_offset_ = rest_length_offset; + } + + private: + drake::trajectories::PiecewisePolynomial GenerateSLIPTraj( + const Eigen::VectorXd& x, double t0, double tf, int fsm_state) const; + + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::BodyFrame& world_; + const drake::multibody::Body& pelvis_; + + // A list of pairs of contact body frame and contact point + const std::unordered_map< + int, std::vector&>>>& + feet_contact_points_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex fsm_port_; + drake::systems::InputPortIndex clock_port_; + drake::systems::InputPortIndex contact_scheduler_port_; + + // SLIP parameters + double rest_length_ = 0.8; + double rest_length_offset_ = 0.0; + double k_leg_ = 100.0; + double b_leg_ = 5.0; +}; + +} // namespace dairlib::examples::osc diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index ff4ee934c9..8e39aa5b6e 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -87,7 +87,8 @@ DEFINE_string(traj_name, "jumping_0.15h_0.3d", "File to load saved trajectories from"); DEFINE_string(gains_filename, "examples/Cassie/osc_jump/osc_jumping_gains.yaml", "Filepath containing gains"); -DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", "Filepath containing qp settings"); int DoMain(int argc, char* argv[]) { @@ -111,9 +112,6 @@ int DoMain(int argc, char* argv[]) { auto right_toe = RightToeFront(plant_w_spr); auto right_heel = RightToeRear(plant_w_spr); - int n_v = plant_w_spr.num_velocities(); - int n_u = plant_w_spr.num_actuators(); - // Create maps for joints map pos_map = multibody::MakeNameToPositionsMap(plant_w_spr); map vel_map = multibody::MakeNameToVelocitiesMap(plant_w_spr); @@ -156,28 +154,28 @@ int DoMain(int argc, char* argv[]) { for (int mode = 0; mode < dircon_trajectory.GetNumModes(); ++mode) { const LcmTrajectory::Trajectory lcm_pelvis_trans_trajectory = output_trajs.GetTrajectory("pelvis_trans_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_foot_traj = output_trajs.GetTrajectory("left_foot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_foot_traj = output_trajs.GetTrajectory("right_foot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_hip_traj = output_trajs.GetTrajectory("left_hip_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_hip_traj = output_trajs.GetTrajectory("right_hip_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_left_toe_traj = output_trajs.GetTrajectory("left_toe_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_right_toe_traj = output_trajs.GetTrajectory("right_toe_trajectory" + - std::to_string(mode)); + std::to_string(mode)); const LcmTrajectory::Trajectory lcm_pelvis_rot_traj = output_trajs.GetTrajectory("pelvis_rot_trajectory" + - std::to_string(mode)); + std::to_string(mode)); pelvis_trans_traj.ConcatenateInTime( PiecewisePolynomial::CubicHermite( lcm_pelvis_trans_trajectory.time_vector, @@ -223,14 +221,14 @@ int DoMain(int argc, char* argv[]) { double flight_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(1)(0); double land_time = FLAGS_delay_time + dircon_trajectory.GetStateBreaks(2)(0) + - osc_gains.landing_delay; + osc_gains.landing_delay; std::vector transition_times = {0.0, FLAGS_delay_time, flight_time, land_time}; // Offset the output trajectories to account for the starting global position // of the robot Vector3d support_center_offset; - support_center_offset << osc_gains.x_offset, 0.0, 0.0; + support_center_offset << osc_gains.crouch_x_offset, 0.0, 0.0; std::vector breaks = pelvis_trans_traj.get_segment_times(); VectorXd breaks_vector = Eigen::Map(breaks.data(), breaks.size()); MatrixXd offset_points = support_center_offset.replicate(1, breaks.size()); @@ -251,16 +249,17 @@ int DoMain(int argc, char* argv[]) { feet_contact_points, FLAGS_delay_time); auto l_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_left", true, l_foot_trajectory, - l_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); + l_hip_trajectory, FLAGS_delay_time); auto r_foot_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), "hip_right", false, r_foot_trajectory, - r_hip_trajectory, osc_gains.relative_feet, FLAGS_delay_time); + r_hip_trajectory, FLAGS_delay_time); auto pelvis_rot_traj_generator = builder.AddSystem( - pelvis_rot_trajectory, "pelvis_rot_tracking_data", FLAGS_delay_time); + pelvis_rot_trajectory, "pelvis_rot_traj", FLAGS_delay_time); auto fsm = builder.AddSystem( plant_w_spr, transition_times, FLAGS_contact_based_fsm, - gains.impact_threshold, (osc_jump::JUMPING_FSM_STATE)FLAGS_init_fsm_state); + gains.impact_threshold, + (osc_jump::JUMPING_FSM_STATE)FLAGS_init_fsm_state); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -292,25 +291,25 @@ int DoMain(int argc, char* argv[]) { contact_results_sub = builder.AddSystem( LcmSubscriberSystem::Make( "CASSIE_CONTACT_FOR_FSM_DISPATCHER", &lcm)); - // TODO(yangwill): Add PR for GM contact observer, currently in - // gm_contact_estimator branch } else { std::cerr << "Unknown simulator type!" << std::endl; } + pelvis_trans_traj_generator->SetLandingOffset(osc_gains.land_x_offset); + /**** OSC setup ****/ // Cost osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - + osc->SetInputSmoothingCostWeights(gains.w_input * + gains.W_input_regularization); + osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight(gains.w_lambda * + gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * + gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); - // Soft constraint on contacts - osc->SetInputSmoothingCostWeights(1e-3 * gains.W_input_regularization); - osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - gains.W_lambda_h_regularization); - // Contact information for OSC osc->SetContactFriction(gains.mu); @@ -326,8 +325,8 @@ int DoMain(int argc, char* argv[]) { auto right_heel_evaluator = multibody::WorldPointEvaluator( plant_w_spr, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - vector stance_modes = {osc_jump::BALANCE, - osc_jump::CROUCH, osc_jump::LAND}; + vector stance_modes = { + osc_jump::BALANCE, osc_jump::CROUCH, osc_jump::LAND}; for (auto mode : stance_modes) { osc->AddStateAndContactPoint(mode, &left_toe_evaluator); osc->AddStateAndContactPoint(mode, &left_heel_evaluator); @@ -336,10 +335,6 @@ int DoMain(int argc, char* argv[]) { } multibody::KinematicEvaluatorSet evaluators(plant_w_spr); - auto left_loop = LeftLoopClosureEvaluator(plant_w_spr); - auto right_loop = RightLoopClosureEvaluator(plant_w_spr); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); // Fix the springs in the dynamics auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_spr); @@ -361,24 +356,30 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); + auto left_loop = LeftLoopClosureEvaluator(plant_w_spr); + auto right_loop = RightLoopClosureEvaluator(plant_w_spr); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + osc->AddKinematicConstraint(&evaluators); /**** Tracking Data for OSC *****/ auto pelvis_tracking_data = std::make_unique( "pelvis_trans_traj", osc_gains.K_p_com, osc_gains.K_d_com, osc_gains.W_com, plant_w_spr, plant_w_spr); - for (auto mode : stance_modes) { - pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); - } - auto pelvis_rot_tracking_data = std::make_unique( - "pelvis_rot_tracking_data", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + "pelvis_rot_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, osc_gains.W_pelvis, plant_w_spr, plant_w_spr); for (auto mode : stance_modes) { + pelvis_tracking_data->AddStateAndPointToTrack(mode, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack(mode, "pelvis"); } pelvis_rot_tracking_data->SetImpactInvariantProjection(true); pelvis_tracking_data->SetImpactInvariantProjection(true); + VectorXd pelvis_acc_lb = Vector3d::Ones(); + pelvis_acc_lb << -10000, -10000, osc_gains.min_pelvis_acc; + VectorXd pelvis_acc_ub = osc_gains.max_pelvis_acc * Vector3d::Ones(); + pelvis_tracking_data->SetCmdAccelerationBounds(pelvis_acc_lb, pelvis_acc_ub); auto left_foot_tracking_data = std::make_unique( "left_ft_traj", osc_gains.K_p_flight_foot, osc_gains.K_d_flight_foot, @@ -414,10 +415,10 @@ int DoMain(int argc, char* argv[]) { // Flight phase hip yaw tracking auto left_hip_yaw_tracking_data = std::make_unique( - "swing_hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant_w_spr, plant_w_spr); auto right_hip_yaw_tracking_data = std::make_unique( - "swing_hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, osc_gains.W_hip_yaw, plant_w_spr, plant_w_spr); left_hip_yaw_tracking_data->AddStateAndJointToTrack( osc_jump::FLIGHT, "hip_yaw_left", "hip_yaw_leftdot"); @@ -502,9 +503,8 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("left_toe_angle_traj")); builder.Connect(right_toe_angle_traj_gen->get_output_port(0), osc->get_input_port_tracking_data("right_toe_angle_traj")); - builder.Connect( - pelvis_rot_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("pelvis_rot_tracking_data")); + builder.Connect(pelvis_rot_traj_generator->get_output_port(0), + osc->get_input_port_tracking_data("pelvis_rot_traj")); // FSM connections builder.Connect(contact_results_sub->get_output_port(), @@ -539,7 +539,8 @@ int DoMain(int argc, char* argv[]) { command_sender->get_input_port(0)); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); builder.Connect(osc->get_output_port_failure(), failure_aggregator->get_input_port(0)); builder.Connect(failure_aggregator->get_status_output_port(), diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc new file mode 100644 index 0000000000..4cb9e12758 --- /dev/null +++ b/examples/Cassie/run_osc_running_controller.cc @@ -0,0 +1,626 @@ +#include + +#include +#include +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/contact_scheduler/contact_scheduler.h" +#include "examples/Cassie/osc/heading_traj_generator.h" +#include "examples/Cassie/osc/high_level_command.h" +#include "examples/Cassie/osc/swing_toe_traj_generator.h" +#include "examples/Cassie/osc_jump/basic_trajectory_passthrough.h" +#include "examples/Cassie/osc_run/foot_traj_generator.h" +#include "examples/Cassie/osc_run/osc_running_gains.h" +#include "examples/Cassie/osc_run/pelvis_trans_traj_generator.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/kinematic/fixed_joint_evaluator.h" +#include "multibody/multibody_utils.h" +#include "examples/Cassie/systems/cassie_out_to_radio.h" +#include "systems/controllers/controller_failure_aggregator.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" + +namespace dairlib { + +using std::map; +using std::pair; +using std::string; +using std::vector; + +using Eigen::Matrix3d; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using cassie::osc::SwingToeTrajGenerator; +using drake::geometry::SceneGraph; +using drake::multibody::Frame; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; +using examples::osc::PelvisTransTrajGenerator; +using examples::osc_jump::BasicTrajectoryPassthrough; +using examples::osc_run::FootTrajGenerator; +using multibody::FixedJointEvaluator; +using multibody::WorldYawViewFrame; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +namespace examples { + +DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", + "The name of the channel which receives state"); +DEFINE_string(channel_u, "CASSIE_INPUT", + "The name of the channel which publishes command"); +DEFINE_string(gains_filename, "examples/Cassie/osc_run/osc_running_gains.yaml", + "Filepath containing gains"); +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "Filepath containing qp settings"); +DEFINE_string( + channel_cassie_out, "CASSIE_OUTPUT_ECHO", + "The name of the channel to receive the cassie out structure from."); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Build the controller diagram + DiagramBuilder builder; + + // Built the Cassie MBPs + drake::multibody::MultibodyPlant plant(0.0); + AddCassieMultibody(&plant, nullptr, true, + "examples/Cassie/urdf/cassie_v2_conservative.urdf", + true /*spring model*/, false /*loop closure*/); + plant.Finalize(); + + auto plant_context = plant.CreateDefaultContext(); + + // Get contact frames and position + auto left_toe = LeftToeFront(plant); + auto left_heel = LeftToeRear(plant); + auto right_toe = RightToeFront(plant); + auto right_heel = RightToeRear(plant); + + // Create maps for joints + map pos_map = multibody::MakeNameToPositionsMap(plant); + map vel_map = multibody::MakeNameToVelocitiesMap(plant); + map act_map = multibody::MakeNameToActuatorsMap(plant); + + std::unordered_map< + int, std::vector&>>> + feet_contact_points; + feet_contact_points[LEFT_STANCE] = std::vector< + std::pair&>>( + {left_toe, left_heel}); + feet_contact_points[RIGHT_STANCE] = std::vector< + std::pair&>>( + {right_toe, right_heel}); + + /**** Get trajectory from optimization ****/ + + /**** OSC Gains ****/ + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); + OSCRunningGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename)); + drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)) + .osqp_options; + + /**** FSM and contact mode configuration ****/ + + vector fsm_states = { + RUNNING_FSM_STATE::LEFT_STANCE, RUNNING_FSM_STATE::LEFT_FLIGHT, + RUNNING_FSM_STATE::RIGHT_STANCE, RUNNING_FSM_STATE::RIGHT_FLIGHT, + RUNNING_FSM_STATE::LEFT_STANCE}; + + vector state_durations = { + osc_gains.stance_duration, osc_gains.flight_duration, + osc_gains.stance_duration, osc_gains.flight_duration, 0.0}; + vector accumulated_state_durations; + accumulated_state_durations.push_back(0); + for (double state_duration : state_durations) { + accumulated_state_durations.push_back(accumulated_state_durations.back() + + state_duration); + } + accumulated_state_durations.pop_back(); + + std::set impact_states = {LEFT_STANCE, RIGHT_STANCE}; + auto contact_scheduler = builder.AddSystem( + plant, plant_context.get(), impact_states, gains.impact_threshold, + gains.impact_tau); + contact_scheduler->SetSLIPParams(osc_gains.rest_length); + contact_scheduler->SetNominalStepTimings(osc_gains.stance_duration, + osc_gains.flight_duration); + contact_scheduler->SetMaxStepTimingVariance(osc_gains.stance_variance, + osc_gains.flight_variance); + + /**** Initialize all the leaf systems ****/ + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto state_receiver = builder.AddSystem(plant); + auto command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto command_sender = builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), true); + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto failure_aggregator = + builder.AddSystem(FLAGS_channel_u, + 1); + auto cassie_out_to_radio = builder.AddSystem(); + auto controller_failure_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "CONTROLLER_ERROR", &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto contact_scheduler_debug_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + "CONTACT_TIMING", &lcm, TriggerTypeSet({TriggerType::kForced}))); + // std::vector tau = {.05, .01, .01}; + // auto ekf_filter = builder.AddSystem( + // plant, osc_gains.ekf_filter_tau); + + /**** OSC setup ****/ + // Cost + /// REGULARIZATION COSTS + osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); + osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * + osc_gains.W_input_regularization); + osc->SetInputCostWeights(osc_gains.w_input * + osc_gains.W_input_regularization); + osc->SetLambdaContactRegularizationWeight( + osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); + osc->SetLambdaHolonomicRegularizationWeight( + osc_gains.w_lambda * osc_gains.W_lambda_h_regularization); + // Soft constraint on contacts + osc->SetContactSoftConstraintWeight(osc_gains.w_soft_constraint); + osc->SetJointLimitWeight(osc_gains.w_joint_limit); + + // Contact information for OSC + osc->SetContactFriction(osc_gains.mu); + + auto pelvis_view_frame = std::make_shared>( + plant.GetBodyByName("pelvis")); + auto left_toe_evaluator = multibody::WorldPointEvaluator( + plant, left_toe.first, left_toe.second, *pelvis_view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); + auto left_heel_evaluator = multibody::WorldPointEvaluator( + plant, left_heel.first, left_heel.second, *pelvis_view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + auto right_toe_evaluator = multibody::WorldPointEvaluator( + plant, right_toe.first, right_toe.second, *pelvis_view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); + auto right_heel_evaluator = multibody::WorldPointEvaluator( + plant, right_heel.first, right_heel.second, *pelvis_view_frame, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + &left_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + &left_heel_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + &right_toe_evaluator); + osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + &right_heel_evaluator); + + multibody::KinematicEvaluatorSet evaluators(plant); + + + // Fix the springs in the dynamics + auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); + auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant); + auto left_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = + FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + auto right_fixed_ankle_spring = + FixedJointEvaluator(plant, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(&left_fixed_knee_spring); + evaluators.add_evaluator(&right_fixed_knee_spring); + evaluators.add_evaluator(&left_fixed_ankle_spring); + evaluators.add_evaluator(&right_fixed_ankle_spring); + + auto left_loop = LeftLoopClosureEvaluator(plant); + auto right_loop = RightLoopClosureEvaluator(plant); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + + osc->AddKinematicConstraint(&evaluators); + + /**** Tracking Data *****/ + + std::cout << "Creating tracking data. " << std::endl; + + auto cassie_out_receiver = + builder.AddSystem(LcmSubscriberSystem::Make( + FLAGS_channel_cassie_out, &lcm)); + cassie::osc::HighLevelCommand* high_level_command; + high_level_command = builder.AddSystem( + plant, plant_context.get(), osc_gains.vel_scale_rot, + osc_gains.vel_scale_trans_sagital, osc_gains.vel_scale_trans_lateral); + + auto pelvis_trans_traj_generator = + builder.AddSystem( + plant, plant_context.get(), feet_contact_points); + pelvis_trans_traj_generator->SetSLIPParams(osc_gains.rest_length, + osc_gains.rest_length_offset); + + auto l_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "toe_left", "pelvis", LEFT_STANCE); + auto r_foot_traj_generator = builder.AddSystem( + plant, plant_context.get(), "toe_right", "pelvis", RIGHT_STANCE); + l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); + l_foot_traj_generator->SetFootPlacementOffsets( + osc_gains.rest_length, osc_gains.rest_length_offset, + osc_gains.footstep_lateral_offset, osc_gains.footstep_sagital_offset, + osc_gains.mid_foot_height); + r_foot_traj_generator->SetFootPlacementOffsets( + osc_gains.rest_length, osc_gains.rest_length_offset, + osc_gains.footstep_lateral_offset, osc_gains.footstep_sagital_offset, + osc_gains.mid_foot_height); + l_foot_traj_generator->SetCommandFilter(osc_gains.target_vel_filter_alpha); + r_foot_traj_generator->SetCommandFilter(osc_gains.target_vel_filter_alpha); + + auto pelvis_tracking_data = std::make_unique( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant); + auto stance_foot_tracking_data = std::make_unique( + "stance_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + auto left_foot_tracking_data = std::make_unique( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + auto right_foot_tracking_data = std::make_unique( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, + "pelvis"); + pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, + "pelvis"); + stance_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_left"); + stance_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_right"); + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); + + left_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + right_foot_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); + + auto left_foot_yz_tracking_data = + std::make_unique( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + auto right_foot_yz_tracking_data = + std::make_unique( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_foot_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + right_foot_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); + + auto left_hip_tracking_data = std::make_unique( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + auto right_hip_tracking_data = std::make_unique( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + + left_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + + auto left_hip_yz_tracking_data = std::make_unique( + "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + auto right_hip_yz_tracking_data = + std::make_unique( + "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant); + left_hip_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + right_hip_yz_tracking_data->AddStateAndPointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + + auto left_foot_rel_tracking_data = + std::make_unique( + "left_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, left_foot_tracking_data.get(), + left_hip_tracking_data.get()); + auto right_foot_rel_tracking_data = + std::make_unique( + "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, + osc_gains.W_swing_foot, plant, plant, right_foot_tracking_data.get(), + right_hip_tracking_data.get()); + auto pelvis_trans_rel_tracking_data = + std::make_unique( + "pelvis_trans_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis, plant, plant, pelvis_tracking_data.get(), + stance_foot_tracking_data.get()); + left_foot_rel_tracking_data->SetViewFrame(pelvis_view_frame); + right_foot_rel_tracking_data->SetViewFrame(pelvis_view_frame); + pelvis_trans_rel_tracking_data->SetViewFrame(pelvis_view_frame); + + auto foot_traj_weight_trajectory = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, + {0.5 * VectorXd::Ones(1), 4.0 * VectorXd::Ones(1)})); + auto foot_traj_gain_trajectory = + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + {0, osc_gains.stance_duration + 2 * osc_gains.flight_duration}, + {0.5 * MatrixXd::Identity(3, 3), + 1.5 * MatrixXd::Identity(3, 3)})); + left_foot_rel_tracking_data->SetTimeVaryingWeights( + foot_traj_weight_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingWeights( + foot_traj_weight_trajectory); + left_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier( + foot_traj_gain_trajectory); + right_foot_rel_tracking_data->SetTimeVaryingPDGainMultiplier( + foot_traj_gain_trajectory); + + auto heading_traj_generator = + builder.AddSystem(plant, + plant_context.get()); + + auto pelvis_rot_tracking_data = std::make_unique( + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot, plant, plant); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + pelvis_rot_tracking_data->AddStateAndFrameToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); + if (osc_gains.rot_filter_tau > 0) { + pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, + {1, 2}); + } + + // Swing toe joint trajectory + vector&>> left_foot_points = { + left_heel, left_toe}; + vector&>> right_foot_points = { + right_heel, right_toe}; + auto left_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_left"], left_foot_points, + "left_toe_angle_traj"); + auto right_toe_angle_traj_gen = builder.AddSystem( + plant, plant_context.get(), pos_map["toe_right"], right_foot_points, + "right_toe_angle_traj"); + + // Swing toe joint tracking + auto left_toe_angle_tracking_data = std::make_unique( + "left_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + auto right_toe_angle_tracking_data = std::make_unique( + "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, + osc_gains.W_swing_toe, plant, plant); + left_toe_angle_tracking_data->AddStateAndJointToTrack( + RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left", "toe_leftdot"); + left_toe_angle_tracking_data->AddStateAndJointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left", "toe_leftdot"); + left_toe_angle_tracking_data->AddStateAndJointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left", "toe_leftdot"); + right_toe_angle_tracking_data->AddStateAndJointToTrack( + RUNNING_FSM_STATE::LEFT_STANCE, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data->AddStateAndJointToTrack( + RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right", "toe_rightdot"); + right_toe_angle_tracking_data->AddStateAndJointToTrack( + RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right", "toe_rightdot"); + + // Swing hip yaw joint tracking + auto left_hip_yaw_tracking_data = std::make_unique( + "hip_yaw_left_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + auto right_hip_yaw_tracking_data = std::make_unique( + "hip_yaw_right_traj", osc_gains.K_p_hip_yaw, osc_gains.K_d_hip_yaw, + osc_gains.W_hip_yaw, plant, plant); + left_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_left", + "hip_yaw_leftdot"); + right_hip_yaw_tracking_data->AddJointToTrack("hip_yaw_right", + "hip_yaw_rightdot"); + + if (osc_gains.no_derivative_feedback) { + left_foot_rel_tracking_data->SetNoDerivativeFeedback(true); + right_foot_rel_tracking_data->SetNoDerivativeFeedback(true); + pelvis_trans_rel_tracking_data->SetNoDerivativeFeedback(true); + left_hip_yaw_tracking_data->SetNoDerivativeFeedback(true); + right_hip_yaw_tracking_data->SetNoDerivativeFeedback(true); + pelvis_rot_tracking_data->SetNoDerivativeFeedback(true); + left_toe_angle_tracking_data->SetNoDerivativeFeedback(true); + right_toe_angle_tracking_data->SetNoDerivativeFeedback(true); + } else { + left_foot_rel_tracking_data->SetImpactInvariantProjection(true); + right_foot_rel_tracking_data->SetImpactInvariantProjection(true); + pelvis_trans_rel_tracking_data->SetImpactInvariantProjection(true); + left_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + right_hip_yaw_tracking_data->SetImpactInvariantProjection(true); + pelvis_rot_tracking_data->SetImpactInvariantProjection(true); + left_toe_angle_tracking_data->SetImpactInvariantProjection(true); + right_toe_angle_tracking_data->SetImpactInvariantProjection(true); + } + osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); + osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); + osc->AddTrackingData(std::move(left_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(right_foot_rel_tracking_data)); + osc->AddTrackingData(std::move(left_toe_angle_tracking_data)); + osc->AddTrackingData(std::move(right_toe_angle_tracking_data)); + osc->AddConstTrackingData(std::move(left_hip_yaw_tracking_data), + VectorXd::Zero(1)); + osc->AddConstTrackingData(std::move(right_hip_yaw_tracking_data), + VectorXd::Zero(1)); + + osc->SetOsqpSolverOptions(solver_options); + // Build OSC problem + osc->Build(); + std::cout << "Built OSC" << std::endl; + + /*****Connect ports*****/ + + // OSC connections + builder.Connect(contact_scheduler->get_output_port_fsm(), + osc->get_input_port_fsm()); + builder.Connect(contact_scheduler->get_output_port_impact_info(), + osc->get_input_port_impact_info()); + builder.Connect(contact_scheduler->get_output_port_clock(), + osc->get_input_port_clock()); + builder.Connect(state_receiver->get_output_port(0), + osc->get_input_port_robot_output()); + + // FSM connections + builder.Connect(state_receiver->get_output_port(0), + contact_scheduler->get_input_port_state()); + + // Trajectory generator connections + + builder.Connect( + contact_scheduler->get_output_port_contact_scheduler(), + pelvis_trans_traj_generator->get_contact_scheduler_input_port()); + builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + l_foot_traj_generator->get_input_port_contact_scheduler()); + builder.Connect(contact_scheduler->get_output_port_contact_scheduler(), + r_foot_traj_generator->get_input_port_contact_scheduler()); + + builder.Connect(state_receiver->get_output_port(0), + pelvis_trans_traj_generator->get_state_input_port()); + builder.Connect(contact_scheduler->get_output_port_fsm(), + pelvis_trans_traj_generator->get_fsm_input_port()); + builder.Connect(contact_scheduler->get_output_port_clock(), + pelvis_trans_traj_generator->get_clock_input_port()); + builder.Connect(high_level_command->get_output_port_xy(), + l_foot_traj_generator->get_input_port_target_vel()); + builder.Connect(high_level_command->get_output_port_xy(), + r_foot_traj_generator->get_input_port_target_vel()); + builder.Connect(state_receiver->get_output_port(0), + l_foot_traj_generator->get_input_port_state()); + builder.Connect(state_receiver->get_output_port(0), + r_foot_traj_generator->get_input_port_state()); + builder.Connect(cassie_out_to_radio->get_output_port(), + l_foot_traj_generator->get_input_port_radio()); + builder.Connect(cassie_out_to_radio->get_output_port(), + r_foot_traj_generator->get_input_port_radio()); + + builder.Connect(contact_scheduler->get_output_port_clock(), + l_foot_traj_generator->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_clock(), + r_foot_traj_generator->get_input_port_clock()); + builder.Connect(contact_scheduler->get_output_port_fsm(), + l_foot_traj_generator->get_input_port_fsm()); + builder.Connect(contact_scheduler->get_output_port_fsm(), + r_foot_traj_generator->get_input_port_fsm()); + builder.Connect(state_receiver->get_output_port(0), + left_toe_angle_traj_gen->get_input_port_state()); + builder.Connect(state_receiver->get_output_port(0), + right_toe_angle_traj_gen->get_input_port_state()); + // OSC connections + builder.Connect(pelvis_trans_traj_generator->get_output_port(0), + osc->get_input_port_tracking_data("pelvis_trans_traj")); + builder.Connect(state_receiver->get_output_port(0), + heading_traj_generator->get_state_input_port()); + builder.Connect(high_level_command->get_output_port_yaw(), + heading_traj_generator->get_yaw_input_port()); + builder.Connect(heading_traj_generator->get_output_port(0), + osc->get_input_port_tracking_data("pelvis_rot_traj")); + builder.Connect(l_foot_traj_generator->get_output_port(0), + osc->get_input_port_tracking_data("left_ft_traj")); + builder.Connect(r_foot_traj_generator->get_output_port(0), + osc->get_input_port_tracking_data("right_ft_traj")); + builder.Connect(left_toe_angle_traj_gen->get_output_port(0), + osc->get_input_port_tracking_data("left_toe_angle_traj")); + builder.Connect(right_toe_angle_traj_gen->get_output_port(0), + osc->get_input_port_tracking_data("right_toe_angle_traj")); + + // Publisher connections + builder.Connect(cassie_out_receiver->get_output_port(), + cassie_out_to_radio->get_input_port()); + builder.Connect(cassie_out_to_radio->get_output_port(), + high_level_command->get_input_port_radio()); + builder.Connect(osc->get_output_port_osc_command(), + command_sender->get_input_port(0)); + builder.Connect(command_sender->get_output_port(0), + command_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_failure(), + failure_aggregator->get_input_port(0)); + builder.Connect(failure_aggregator->get_status_output_port(), + controller_failure_pub->get_input_port()); + builder.Connect(contact_scheduler->get_output_port_debug_info(), + contact_scheduler_debug_publisher->get_input_port()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("osc_running_controller")); + + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + + loop.Simulate(); + + return 0; +} +} // namespace examples +} // namespace dairlib + +int main(int argc, char* argv[]) { + return dairlib::examples::DoMain(argc, argv); +} diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 4f9a115782..c953253575 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -4,21 +4,23 @@ #include "dairlib/lcmt_robot_output.hpp" #include "dairlib/lcmt_target_standing_height.hpp" #include "examples/Cassie/cassie_utils.h" +#include "examples/Cassie/osc/osc_standing_gains.h" #include "examples/Cassie/osc/standing_com_traj.h" #include "examples/Cassie/osc/standing_pelvis_orientation_traj.h" #include "examples/Cassie/systems/cassie_out_to_radio.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" -#include "systems/controllers/osc/operational_space_control.h" -#include "systems/framework/lcm_driven_loop.h" -#include "systems/robot_lcm_systems.h" -#include "drake/common/yaml/yaml_io.h" -#include "systems/controllers/osc/options_tracking_data.h" -#include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/controllers/osc/com_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/options_tracking_data.h" +#include "systems/controllers/osc/osc_gains.h" #include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" @@ -37,9 +39,9 @@ using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::TriggerTypeSet; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; @@ -63,47 +65,6 @@ DEFINE_string(gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", DEFINE_bool(use_radio, false, "use the radio to set height or not"); DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); -// Currently the controller runs at the rate between 500 Hz and 200 Hz, so the -// publish rate of the robot state needs to be less than 500 Hz. Otherwise, the -// performance seems to degrade due to this. (Recommended publish rate: 200 Hz) -// Maybe we need to update the lcm driven loop to clear the queue of lcm message -// if it's more than one message? - -struct OSCStandingGains { - int rows; - int cols; - double w_input; - double w_accel; - double w_soft_constraint; - double HipYawKp; - double HipYawKd; - double HipYawW; - std::vector CoMKp; - std::vector CoMKd; - std::vector PelvisRotKp; - std::vector PelvisRotKd; - std::vector CoMW; - std::vector PelvisW; - - template - void Serialize(Archive* a) { - a->Visit(DRAKE_NVP(rows)); - a->Visit(DRAKE_NVP(cols)); - a->Visit(DRAKE_NVP(w_input)); - a->Visit(DRAKE_NVP(w_accel)); - a->Visit(DRAKE_NVP(w_soft_constraint)); - a->Visit(DRAKE_NVP(CoMKp)); - a->Visit(DRAKE_NVP(CoMKd)); - a->Visit(DRAKE_NVP(PelvisRotKp)); - a->Visit(DRAKE_NVP(PelvisRotKd)); - a->Visit(DRAKE_NVP(HipYawKp)); - a->Visit(DRAKE_NVP(HipYawKd)); - a->Visit(DRAKE_NVP(CoMW)); - a->Visit(DRAKE_NVP(PelvisW)); - a->Visit(DRAKE_NVP(HipYawW)); - } -}; - int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -135,38 +96,12 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; drake::lcm::DrakeLcm lcm_local; - auto gains = drake::yaml::LoadYamlFile(FLAGS_gains_filename); - - MatrixXd K_p_com = Eigen::Map< - Eigen::Matrix>( - gains.CoMKp.data(), gains.rows, gains.cols); - MatrixXd K_d_com = Eigen::Map< - Eigen::Matrix>( - gains.CoMKd.data(), gains.rows, gains.cols); - MatrixXd K_p_pelvis = Eigen::Map< - Eigen::Matrix>( - gains.PelvisRotKp.data(), gains.rows, gains.cols); - MatrixXd K_d_pelvis = Eigen::Map< - Eigen::Matrix>( - gains.PelvisRotKd.data(), gains.rows, gains.cols); - MatrixXd K_p_hip_yaw = gains.HipYawKp * MatrixXd::Identity(1, 1); - MatrixXd K_d_hip_yaw = gains.HipYawKd * MatrixXd::Identity(1, 1); - MatrixXd W_com = Eigen::Map< - Eigen::Matrix>( - gains.CoMW.data(), gains.rows, gains.cols); - MatrixXd W_pelvis = Eigen::Map< - Eigen::Matrix>( - gains.PelvisW.data(), gains.rows, gains.cols); - MatrixXd W_hip_yaw = gains.HipYawW * MatrixXd::Identity(1, 1); - std::cout << "w input (not used): \n" << gains.w_input << std::endl; - std::cout << "w accel: \n" << gains.w_accel << std::endl; - std::cout << "w soft constraint: \n" << gains.w_soft_constraint << std::endl; - std::cout << "COM Kp: \n" << K_p_com << std::endl; - std::cout << "COM Kd: \n" << K_d_com << std::endl; - std::cout << "Pelvis Rot Kp: \n" << K_p_pelvis << std::endl; - std::cout << "Pelvis Rot Kd: \n" << K_d_pelvis << std::endl; - std::cout << "COM W: \n" << W_com << std::endl; - std::cout << "Pelvis W: \n" << W_pelvis << std::endl; + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); + OSCStandingGains osc_gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_gains_filename)); // Create Lcm subsriber for lcmt_target_standing_height auto target_height_receiver = builder.AddSystem( @@ -180,8 +115,7 @@ int DoMain(int argc, char* argv[]) { auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); - auto cassie_out_to_radio = - builder.AddSystem(); + auto cassie_out_to_radio = builder.AddSystem(); builder.Connect(*cassie_out_receiver, *cassie_out_to_radio); // Create command sender. @@ -204,7 +138,8 @@ int DoMain(int argc, char* argv[]) { std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); + plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, + FLAGS_use_radio); auto pelvis_rot_traj_generator = builder.AddSystem( plant_w_springs, context_w_spr.get(), feet_contact_points, @@ -267,23 +202,25 @@ int DoMain(int argc, char* argv[]) { // W_com * FLAGS_cost_weight_multiplier, // plant_w_springs, plant_wo_springs); auto center_of_mass_traj = std::make_unique( - "com_traj", K_p_com, K_d_com, W_com * FLAGS_cost_weight_multiplier, - plant_w_springs, plant_wo_springs); + "com_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, + plant_wo_springs); center_of_mass_traj->AddPointToTrack("pelvis"); - double cutoff_freq = 5; // in Hz + double cutoff_freq = 5; // in Hz double tau = 1 / (2 * M_PI * cutoff_freq); center_of_mass_traj->SetLowPassFilter(tau, {1}); osc->AddTrackingData(std::move(center_of_mass_traj)); auto pelvis_rot_tracking_data = std::make_unique( - "pelvis_rot_traj", K_p_pelvis, K_d_pelvis, - W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, + "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, + osc_gains.W_pelvis_rot * FLAGS_cost_weight_multiplier, plant_w_springs, plant_wo_springs); pelvis_rot_tracking_data->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); // Hip yaw joint tracking // We use hip yaw joint tracking instead of pelvis yaw tracking because the - // foot sometimes rotates about yaw, and we need hip yaw joint to go back to 0. + // foot sometimes rotates about yaw, and we need hip yaw joint to go back to + // 0. double w_hip_yaw = 0.5; double hip_yaw_kp = 40; double hip_yaw_kd = 0.5; @@ -307,7 +244,8 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(osc->get_output_port_osc_command(), command_sender->get_input_port(0)); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); builder.Connect(com_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("com_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index f006b36dc8..c0bfd4d236 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -182,7 +182,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(*cassie_out_receiver, *cassie_out_to_radio); builder.Connect(cassie_out_to_radio->get_output_port(), - high_level_command->get_radio_port()); + high_level_command->get_input_port_radio()); } else { high_level_command = builder.AddSystem( plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, @@ -192,14 +192,14 @@ int DoMain(int argc, char* argv[]) { params_of_no_turning); } builder.Connect(state_receiver->get_output_port(0), - high_level_command->get_state_input_port()); + high_level_command->get_input_port_state()); // Create heading traj generator auto head_traj_gen = builder.AddSystem( plant_w_spr, context_w_spr.get()); builder.Connect(simulator_drift->get_output_port(0), head_traj_gen->get_state_input_port()); - builder.Connect(high_level_command->get_yaw_output_port(), + builder.Connect(high_level_command->get_output_port_yaw(), head_traj_gen->get_yaw_input_port()); // Create finite state machine @@ -224,7 +224,7 @@ int DoMain(int argc, char* argv[]) { auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); builder.Connect(simulator_drift->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); // Create leafsystem that record the switching time of the FSM std::vector single_support_states = {left_stance_state, @@ -307,7 +307,7 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), gains.k_ff_lateral, gains.k_fb_lateral, gains.k_ff_sagittal, gains.k_fb_sagittal, left_support_duration, 0, wrt_com_in_local_frame); - builder.Connect(high_level_command->get_xy_output_port(), + builder.Connect(high_level_command->get_output_port_xy(), walking_speed_control->get_input_port_des_hor_vel()); builder.Connect(simulator_drift->get_output_port(0), walking_speed_control->get_input_port_state()); @@ -363,9 +363,9 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); builder.Connect(state_receiver->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); // Create Operational space control auto osc = builder.AddSystem( @@ -585,7 +585,7 @@ int DoMain(int argc, char* argv[]) { if (FLAGS_use_radio) { builder.Connect(cassie_out_to_radio->get_output_port(), hip_yaw_traj_gen->get_radio_input_port()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(fsm->get_fsm_output_port(), hip_yaw_traj_gen->get_fsm_input_port()); osc->AddTrackingData(std::move(swing_hip_yaw_traj)); } else { diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 963ab69fe3..6b64069eaf 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -199,7 +199,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_cassie_out_channel, &lcm_local)); builder.Connect(*cassie_out_receiver, *cassie_out_to_radio); builder.Connect(cassie_out_to_radio->get_output_port(), - high_level_command->get_radio_port()); + high_level_command->get_input_port_radio()); } else { high_level_command = builder.AddSystem( plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, @@ -209,14 +209,14 @@ int DoMain(int argc, char* argv[]) { params_of_no_turning); } builder.Connect(pelvis_filt->get_output_port(0), - high_level_command->get_state_input_port()); + high_level_command->get_input_port_state()); // Create heading traj generator auto head_traj_gen = builder.AddSystem( plant_w_spr, context_w_spr.get()); builder.Connect(simulator_drift->get_output_port(0), head_traj_gen->get_state_input_port()); - builder.Connect(high_level_command->get_yaw_output_port(), + builder.Connect(high_level_command->get_output_port_yaw(), head_traj_gen->get_yaw_input_port()); // Create finite state machine @@ -241,7 +241,7 @@ int DoMain(int argc, char* argv[]) { auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); builder.Connect(simulator_drift->get_output_port(0), - fsm->get_input_port_state()); + fsm->get_state_input_port()); // Create leafsystem that record the switching time of the FSM std::vector single_support_states = {left_stance_state, @@ -332,7 +332,7 @@ int DoMain(int argc, char* argv[]) { swing_ft_traj_generator->get_input_port_state()); builder.Connect(alip_traj_generator->get_output_port_alip_state(), swing_ft_traj_generator->get_input_port_alip_state()); - builder.Connect(high_level_command->get_xy_output_port(), + builder.Connect(high_level_command->get_output_port_xy(), swing_ft_traj_generator->get_input_port_vdes()); // Swing toe joint trajectory @@ -350,9 +350,9 @@ int DoMain(int argc, char* argv[]) { plant_w_spr, context_w_spr.get(), pos_map["toe_right"], right_foot_points, "right_toe_angle_traj"); builder.Connect(pelvis_filt->get_output_port(0), - left_toe_angle_traj_gen->get_state_input_port()); + left_toe_angle_traj_gen->get_input_port_state()); builder.Connect(pelvis_filt->get_output_port(0), - right_toe_angle_traj_gen->get_state_input_port()); + right_toe_angle_traj_gen->get_input_port_state()); // Create Operational space control auto osc = builder.AddSystem( @@ -550,7 +550,7 @@ int DoMain(int argc, char* argv[]) { if (FLAGS_use_radio) { builder.Connect(cassie_out_to_radio->get_output_port(), hip_yaw_traj_gen->get_radio_input_port()); - builder.Connect(fsm->get_output_port_fsm(), + builder.Connect(fsm->get_fsm_output_port(), hip_yaw_traj_gen->get_fsm_input_port()); osc->AddTrackingData(std::move(swing_hip_yaw_traj)); } else { diff --git a/examples/Cassie/systems/input_supervisor.cc b/examples/Cassie/systems/input_supervisor.cc index 047f6c780d..28f311dcb4 100644 --- a/examples/Cassie/systems/input_supervisor.cc +++ b/examples/Cassie/systems/input_supervisor.cc @@ -19,8 +19,7 @@ using systems::TimestampedVector; InputSupervisor::InputSupervisor( const drake::multibody::MultibodyPlant& plant, const std::string& initial_channel, double max_joint_velocity, - double update_period, Eigen::VectorXd& input_limit, - int min_consecutive_failures) + double update_period, Eigen::VectorXd& input_limit, int min_consecutive_failures) : plant_(plant), num_actuators_(plant_.num_actuators()), num_positions_(plant_.num_positions()), @@ -29,6 +28,7 @@ InputSupervisor::InputSupervisor( min_consecutive_failures_(min_consecutive_failures), max_joint_velocity_(max_joint_velocity), input_limit_(input_limit) { + // Create input ports command_input_port_ = this->DeclareVectorInputPort("u, t", @@ -105,8 +105,7 @@ InputSupervisor::InputSupervisor( K_ *= kEStopGain; // Create update for error flag - DeclarePeriodicDiscreteUpdateEvent(update_period, 0, - &InputSupervisor::UpdateErrorFlag); + DeclarePerStepDiscreteUpdateEvent(&InputSupervisor::UpdateErrorFlag); } void InputSupervisor::SetMotorTorques(const Context& context, @@ -126,7 +125,7 @@ void InputSupervisor::SetMotorTorques(const Context& context, // iterate through all the possible error flags bool is_error = false; for (const auto& error_flags : error_indices_) { - is_error = is_error || context.get_discrete_state().get_value( + is_error = is_error || context.get_discrete_state().value( error_indices_index_)[error_flags.second]; } @@ -146,22 +145,22 @@ void InputSupervisor::SetMotorTorques(const Context& context, /// 2. safety_pd_controller /// 3. blended efforts from switching control signals /// 4. command from controller + auto prev_efforts = context.get_discrete_state(prev_efforts_index_).value(); // If the soft estop signal is triggered, applying only damping regardless of // any other controller signal - if (cassie_out->pelvis.radio.channel[15] == -1) { + if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[13] == -1) { Eigen::VectorXd u = -K_ * state->GetVelocities(); input_limit_ = 100 * Eigen::VectorXd::Ones(num_actuators_); output->set_timestamp(state->get_timestamp()); output->SetDataVector(u); } else if (is_error) { output->set_timestamp(safety_command->get_timestamp()); - output->SetDataVector(safety_command->get_value()); + output->SetDataVector(safety_command->value()); } else if (alpha < 1.0) { Eigen::VectorXd blended_effort = - alpha * command->get_value() + - (1 - alpha) * - context.get_discrete_state(prev_efforts_index_).get_value(); + alpha * command->value() + + (1 - alpha) * context.get_discrete_state(prev_efforts_index_).value(); output->SetDataVector(blended_effort); } else { output->get_mutable_data() = command->get_data(); @@ -175,6 +174,10 @@ void InputSupervisor::SetMotorTorques(const Context& context, } else if (command_value < -input_limit_(i)) { command_value = -input_limit_(i); } +// if(i < 2){ +// command_value += -0.2 * K_.row(i) * state->GetVelocities(); +// command_value = 0.95 * command_value + 0.05 * prev_efforts(i); +// } output->get_mutable_data()(i) = command_value; } } @@ -187,14 +190,14 @@ void InputSupervisor::SetStatus( command_input_port_); output->utime = command->get_timestamp() * 1e6; output->active_channel = active_channel_; - output->shutdown = context.get_discrete_state().get_value(shutdown_index_)[0]; + output->shutdown = context.get_discrete_state().value(shutdown_index_)[0]; output->num_status = error_indices_.size(); output->status_names = std::vector(error_indices_.size()); output->status_states = std::vector(error_indices_.size()); for (const auto& error_flags : error_indices_) { output->status_names[error_flags.second] = error_flags.first; output->status_states[error_flags.second] = - context.get_discrete_state().get_value( + context.get_discrete_state().value( error_indices_index_)[error_flags.second]; } } @@ -203,13 +206,12 @@ void InputSupervisor::SetFailureStatus( const drake::systems::Context& context, dairlib::lcmt_controller_failure* output) const { output->utime = context.get_time() * 1e6; - output->error_code = - context.get_discrete_state().get_value(shutdown_index_)[0]; + output->error_code = context.get_discrete_state().value(shutdown_index_)[0]; output->controller_channel = "GLOBAL_ERROR"; output->error_name = ""; } -void InputSupervisor::UpdateErrorFlag( +drake::systems::EventStatus InputSupervisor::UpdateErrorFlag( const Context& context, DiscreteValues* discrete_state) const { const auto* controller_switch = @@ -223,9 +225,9 @@ void InputSupervisor::UpdateErrorFlag( const TimestampedVector* command = (TimestampedVector*)this->EvalVectorInput(context, command_input_port_); - // Because we are only ever setting the error flags to true, all errors are - // latching. ie. the error flags will only be reset if the input supervisor is - // reconstructed + + // Note the += operator works as an or operator because we only check if the + // error flag != 0 if (controller_error->controller_channel == active_channel_ && controller_error->error_code != 0) { discrete_state->get_mutable_value( @@ -251,7 +253,7 @@ void InputSupervisor::UpdateErrorFlag( bool is_error = false; for (const auto& error_flags : error_indices_) { - is_error = is_error || context.get_discrete_state().get_value( + is_error = is_error || context.get_discrete_state().value( error_indices_index_)[error_flags.second]; } discrete_state->get_mutable_value(shutdown_index_)[0] = is_error; @@ -273,9 +275,9 @@ void InputSupervisor::UpdateErrorFlag( // efforts if (command->get_timestamp() - controller_switch->utime * 1e-6 >= blend_duration_) { - discrete_state->get_mutable_value(prev_efforts_index_) = - command->get_value(); + discrete_state->get_mutable_value(prev_efforts_index_) = command->value(); } + return drake::systems::EventStatus::Succeeded(); } void InputSupervisor::CheckVelocities( @@ -285,8 +287,7 @@ void InputSupervisor::CheckVelocities( (OutputVector*)this->EvalVectorInput(context, state_input_port_); const Eigen::VectorXd& velocities = state->GetVelocities(); - if (discrete_state->get_value(n_fails_index_)[0] < - min_consecutive_failures_) { + if (discrete_state->value(n_fails_index_)[0] < min_consecutive_failures_) { // If any velocity is above the threshold, set the error flag bool is_velocity_error = (velocities.array() > max_joint_velocity_).any() || (velocities.array() < -max_joint_velocity_).any(); @@ -296,7 +297,7 @@ void InputSupervisor::CheckVelocities( std::cout << "Error! Velocity has exceeded the threshold of " << max_joint_velocity_ << std::endl; std::cout << "Consecutive error " - << discrete_state->get_value(n_fails_index_)[0] << " of " + << discrete_state->value(n_fails_index_)[0] << " of " << min_consecutive_failures_ << std::endl; std::cout << "Velocity vector: " << std::endl << velocities << std::endl @@ -313,7 +314,7 @@ void InputSupervisor::CheckRadio( drake::systems::DiscreteValues* discrete_state) const { const auto& cassie_out = this->EvalInputValue( context, cassie_input_port_); - if (cassie_out->pelvis.radio.channel[15] == -1) { + if (cassie_out->pelvis.radio.channel[15] == -1 || cassie_out->pelvis.radio.channel[13] == -1) { discrete_state->get_mutable_value( error_indices_index_)[error_indices_.at("soft_estop")] = 1; } diff --git a/examples/Cassie/systems/input_supervisor.h b/examples/Cassie/systems/input_supervisor.h index 5d638cee13..736da9dbc0 100644 --- a/examples/Cassie/systems/input_supervisor.h +++ b/examples/Cassie/systems/input_supervisor.h @@ -1,8 +1,8 @@ #pragma once #include -#include "dairlib/lcmt_input_supervisor_status.hpp" #include "dairlib/lcmt_controller_failure.hpp" +#include "dairlib/lcmt_input_supervisor_status.hpp" #include "systems/framework/timestamped_vector.h" #include "drake/multibody/plant/multibody_plant.h" @@ -87,7 +87,7 @@ class InputSupervisor : public drake::systems::LeafSystem { void SetMotorTorques(const drake::systems::Context& context, systems::TimestampedVector* output) const; - void UpdateErrorFlag( + drake::systems::EventStatus UpdateErrorFlag( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; @@ -102,7 +102,7 @@ class InputSupervisor : public drake::systems::LeafSystem { // Output a failure message when any error is triggered void SetFailureStatus(const drake::systems::Context& context, - dairlib::lcmt_controller_failure* output) const; + dairlib::lcmt_controller_failure* output) const; void CheckVelocities( const drake::systems::Context& context, @@ -110,7 +110,6 @@ class InputSupervisor : public drake::systems::LeafSystem { void CheckRadio(const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; - private: const drake::multibody::MultibodyPlant& plant_; const int num_actuators_; const int num_positions_; diff --git a/lcmtypes/lcmt_contact_timing.lcm b/lcmtypes/lcmt_contact_timing.lcm new file mode 100644 index 0000000000..4325b6d3db --- /dev/null +++ b/lcmtypes/lcmt_contact_timing.lcm @@ -0,0 +1,11 @@ +package dairlib; + +struct lcmt_contact_timing +{ + int64_t utime; + int16_t n_transitions; + int16_t active_fsm_state; + int16_t transition_states[n_transitions]; + double transition_times[n_transitions]; + string fsm_state_names[n_transitions]; +} diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index a80493cfef..d760c8b3b7 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -2,6 +2,17 @@ load("@drake//tools/lint:lint.bzl", "add_lint_tests") package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "controllers_all", + srcs = [], + deps = [ + ":affine_controller", + ":controller_failure_aggregator", + ":fsm_event_time", + ], +) + cc_library( name = "control_utils", srcs = [ diff --git a/systems/controllers/lipm_traj_gen.cc b/systems/controllers/lipm_traj_gen.cc index 2e5d8964e8..c986e44255 100644 --- a/systems/controllers/lipm_traj_gen.cc +++ b/systems/controllers/lipm_traj_gen.cc @@ -92,7 +92,7 @@ LIPMTrajGenerator::LIPMTrajGenerator( // The stance foot position in the beginning of the swing phase stance_foot_pos_idx_ = this->DeclareDiscreteState(3); // COM state at touchdown - touchdown_com_pos_idx_ = this->DeclareDiscreteState(3); + touchdown_com_pos_idx_ = this->DeclareDiscreteState(Vector3d(0, 0, 0.9)); touchdown_com_vel_idx_ = this->DeclareDiscreteState(3); prev_fsm_idx_ = this->DeclareDiscreteState(-1 * VectorXd::Ones(1)); } diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index 1e290c4a2c..269e929bfd 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -56,6 +56,7 @@ cc_library( hdrs = ["options_tracking_data.h"], deps = [ ":osc_tracking_data", + "//common:eigen_utils", "//multibody:utils", "//multibody:view_frame", "//systems/framework:vector", diff --git a/systems/controllers/osc/joint_space_tracking_data.cc b/systems/controllers/osc/joint_space_tracking_data.cc index 22506e181c..37d0cf3488 100644 --- a/systems/controllers/osc/joint_space_tracking_data.cc +++ b/systems/controllers/osc/joint_space_tracking_data.cc @@ -22,7 +22,7 @@ JointSpaceTrackingData::JointSpaceTrackingData( const string& name, const MatrixXd& K_p, const MatrixXd& K_d, const MatrixXd& W, const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) - : OptionsTrackingData(name, K_p.rows(), K_p.rows(), K_p, K_d, W, + : OptionsTrackingData(name, K_p.rows(), K_d.rows(), K_p, K_d, W, plant_w_spr, plant_wo_spr) { } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 02efae0f8b..766b987b72 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -523,7 +523,8 @@ VectorXd OperationalSpaceControl::SolveQp( } else { static const drake::logging::Warn log_once(const_cast( (std::to_string(fsm_state) + - " is not a valid finite state machine state in OSC.") + " is not a valid finite state machine state in OSC. This can happen " + "if there are modes with no active contacts.") .c_str())); } } @@ -564,7 +565,7 @@ VectorXd OperationalSpaceControl::SolveQp( t_since_last_state_switch, fsm_state, next_fsm_state, M); // Need to call Update before this to get the updated jacobian - v_proj = alpha * M_Jt_ * ii_lambda_sol_; + v_proj = alpha * M_Jt_ * ii_lambda_sol_ + 1e-13 * VectorXd::Ones(n_v_); } // Get J and JdotV for holonomic constraint @@ -618,7 +619,9 @@ VectorXd OperationalSpaceControl::SolveQp( // 2. Holonomic constraint /// JdotV_h + J_h*dv == 0 /// -> J_h*dv == -JdotV_h - holonomic_constraint_->UpdateCoefficients(J_h, -JdotV_h); + if (n_h_ > 0) { + holonomic_constraint_->UpdateCoefficients(J_h, -JdotV_h); + } // 3. Contact constraint if (!all_contacts_.empty()) { if (w_soft_constraint_ <= 0) { @@ -771,12 +774,12 @@ VectorXd OperationalSpaceControl::SolveQp( } if (W_lambda_c_reg_.size() > 0) { - lambda_c_cost_->UpdateCoefficients(alpha * W_lambda_c_reg_, + lambda_c_cost_->UpdateCoefficients((1 + alpha) * W_lambda_c_reg_, VectorXd::Zero(n_c_)); } if (W_lambda_h_reg_.size() > 0) { - lambda_h_cost_->UpdateCoefficients(alpha * W_lambda_h_reg_, + lambda_h_cost_->UpdateCoefficients((1 + alpha) * W_lambda_h_reg_, VectorXd::Zero(n_h_)); } if (!solver_->IsInitialized()) { @@ -880,20 +883,24 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } // int n_holonomic_constraints = n_h_; - MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + n_h_, active_constraint_dim + n_h_); - MatrixXd C = J_h * M_Jt_; - VectorXd Ab = A.transpose() * ydot_err_vec; - VectorXd d = J_h * x_w_spr.tail(n_v_); A_constrained.block(0, 0, active_constraint_dim, active_constraint_dim) = A.transpose() * A; - A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = - C; - A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = - C.transpose(); VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); - b_constrained << Ab, d; + VectorXd Ab = A.transpose() * ydot_err_vec; + if (n_h_ > 0) { + MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); + MatrixXd C = J_h * M_Jt_; + VectorXd d = J_h * x_w_spr.tail(n_v_); + A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = + C; + A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = + C.transpose(); + b_constrained << Ab, d; + } else { + b_constrained << Ab; + } ii_lambda_sol_ = A_constrained.completeOrthogonalDecomposition() .solve(b_constrained) @@ -1115,7 +1122,7 @@ void OperationalSpaceControl::CheckTracking( if (soft_constraint_cost_ != nullptr) { soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); } - if (y_soft_constraint_cost[0] > 5e3 || isnan(y_soft_constraint_cost[0])) { + if (y_soft_constraint_cost[0] > 1e5 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 5a72cb1978..28a78a870b 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -362,7 +362,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int n_c_active_; // Manually specified holonomic constraints (only valid for plants_wo_springs) - const multibody::KinematicEvaluatorSet* kinematic_evaluators_; + const multibody::KinematicEvaluatorSet* kinematic_evaluators_ = nullptr; // robot input limits Eigen::VectorXd u_min_; diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index cd66bbd74e..e982888c04 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -1,6 +1,10 @@ #include "options_tracking_data.h" +#include "common/eigen_utils.h" + +#include "drake/common/trajectories/piecewise_quaternion.h" using Eigen::MatrixXd; +using Eigen::Quaterniond; using Eigen::Vector3d; using Eigen::VectorXd; using std::string; @@ -18,7 +22,10 @@ OptionsTrackingData::OptionsTrackingData( const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) : OscTrackingData(name, n_y, n_ydot, K_p, K_d, W, plant_w_spr, - plant_wo_spr) {} + plant_wo_spr) { + yddot_cmd_lb_ = std::numeric_limits::lowest() * VectorXd::Ones(n_ydot_); + yddot_cmd_ub_ = std::numeric_limits::max() * VectorXd::Ones(n_ydot_); +} void OptionsTrackingData::UpdateActual( const Eigen::VectorXd& x_w_spr, @@ -31,18 +38,14 @@ void OptionsTrackingData::UpdateActual( if (with_view_frame_) { view_frame_rot_T_ = view_frame_->CalcWorldToFrameRotation(plant_w_spr_, context_w_spr); - y_ = view_frame_rot_T_ * y_; - ydot_ = view_frame_rot_T_ * ydot_; + if (!is_rotational_tracking_data_) { + y_ = view_frame_rot_T_ * y_; + ydot_ = view_frame_rot_T_ * ydot_; + } J_ = view_frame_rot_T_ * J_; JdotV_ = view_frame_rot_T_ * JdotV_; } - if (joint_idx_to_ignore_.count(fsm_state_)) { - for (int idx : joint_idx_to_ignore_[fsm_state_]) { - J_.col(idx) = VectorXd::Zero(J_.rows()); - } - } - UpdateFilters(t); } @@ -55,14 +58,27 @@ void OptionsTrackingData::UpdateFilters(double t) { } else if (t != last_timestamp_) { double dt = t - last_timestamp_; double alpha = dt / (dt + tau_); - filtered_y_ = alpha * y_ + (1 - alpha) * filtered_y_; + if (n_y_ == 4) { // quaternion + auto slerp = drake::trajectories::PiecewiseQuaternionSlerp( + {0, 1}, {Quaterniond(y_[0], y_[1], y_[2], y_[3]), + Quaterniond(filtered_y_[0], filtered_y_[1], filtered_y_[2], + filtered_y_[3])}); + filtered_y_ = slerp.value(1 - alpha); + } else { + filtered_y_ = alpha * y_ + (1 - alpha) * filtered_y_; + } filtered_ydot_ = alpha * ydot_ + (1 - alpha) * filtered_ydot_; } // Assign filtered values - for (auto idx : low_pass_filter_element_idx_) { - y_(idx) = filtered_y_(idx); - ydot_(idx) = filtered_ydot_(idx); + if (n_y_ == 4) { + y_ = filtered_y_; + ydot_ = filtered_ydot_; + } else { + for (auto idx : low_pass_filter_element_idx_) { + y_(idx) = filtered_y_(idx); + ydot_(idx) = filtered_ydot_(idx); + } } // Update timestamp last_timestamp_ = t; @@ -75,6 +91,8 @@ void OptionsTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { error_ydot_ = ydot_des_ - ydot_; if (impact_invariant_projection_) { error_ydot_ -= GetJ() * v_proj; + } else if (no_derivative_feedback_ && !v_proj.isZero()) { + error_ydot_ = VectorXd::Zero(n_ydot_); } } @@ -87,24 +105,36 @@ void OptionsTrackingData::UpdateYddotDes(double t, if (ff_accel_multiplier_traj_ != nullptr) { yddot_des_converted_ = ff_accel_multiplier_traj_->value(t_since_state_switch) * - yddot_des_converted_; + yddot_des_converted_; } } void OptionsTrackingData::UpdateYddotCmd(double t, double t_since_state_switch) { // 4. Update command output (desired output with pd control) - MatrixXd p_gain_multiplier = (p_gain_multiplier_traj_ != nullptr) ? - p_gain_multiplier_traj_->value(t_since_state_switch) : - MatrixXd::Identity(n_ydot_, n_ydot_); + MatrixXd p_gain_multiplier = + (p_gain_multiplier_traj_ != nullptr) + ? p_gain_multiplier_traj_->value(t_since_state_switch) + : MatrixXd::Identity(n_ydot_, n_ydot_); - MatrixXd d_gain_multiplier = (d_gain_multiplier_traj_ != nullptr) ? - d_gain_multiplier_traj_->value(t_since_state_switch) : - MatrixXd::Identity(n_ydot_, n_ydot_); + MatrixXd d_gain_multiplier = + (d_gain_multiplier_traj_ != nullptr) + ? d_gain_multiplier_traj_->value(t_since_state_switch) + : MatrixXd::Identity(n_ydot_, n_ydot_); - yddot_command_ = yddot_des_converted_ + - p_gain_multiplier * K_p_ * error_y_ + + yddot_command_ = yddot_des_converted_ + p_gain_multiplier * K_p_ * error_y_ + d_gain_multiplier * K_d_ * error_ydot_; + yddot_command_ = eigen_clamp(yddot_command_, yddot_cmd_lb_, yddot_cmd_ub_); + UpdateW(t, t_since_state_switch); +} + +void OptionsTrackingData::UpdateW(double t, double t_since_state_switch) { + if (weight_trajectory_ != nullptr) { + time_varying_weight_ = + weight_trajectory_->value(time_through_trajectory_).row(0)[0] * W_; + } else { + time_varying_weight_ = W_; + } } void OptionsTrackingData::SetLowPassFilter(double tau, @@ -112,7 +142,7 @@ void OptionsTrackingData::SetLowPassFilter(double tau, DRAKE_DEMAND(tau > 0); tau_ = tau; - DRAKE_DEMAND(n_y_ == n_ydot_); // doesn't support quaternion yet + // DRAKE_DEMAND(n_y_ == n_ydot_); // doesn't support quaternion yet if (element_idx.empty()) { for (int i = 0; i < n_y_; i++) { low_pass_filter_element_idx_.insert(i); @@ -122,28 +152,25 @@ void OptionsTrackingData::SetLowPassFilter(double tau, } } -void OptionsTrackingData::AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, - int fsm_state) { - DRAKE_DEMAND(std::find(active_fsm_states_.begin(), - active_fsm_states_.end(), - fsm_state) != active_fsm_states_.end()); - if (joint_idx_to_ignore_.count(fsm_state)) { - joint_idx_to_ignore_[fsm_state].push_back(joint_vel_idx); - } else { - joint_idx_to_ignore_[fsm_state] = {joint_vel_idx}; - } +void OptionsTrackingData::SetTimeVaryingWeights( + std::shared_ptr> + weight_trajectory) { + // DRAKE_DEMAND(weight_trajectory->cols() == n_ydot_); + // DRAKE_DEMAND(weight_trajectory->rows() == n_ydot_); + // DRAKE_DEMAND(weight_trajectory->start_time() == 0); + weight_trajectory_ = weight_trajectory; } void OptionsTrackingData::SetTimeVaryingPDGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory) { + gain_multiplier_trajectory) { SetTimeVaryingProportionalGainMultiplier(gain_multiplier_trajectory); SetTimeVaryingDerivativeGainMultiplier(gain_multiplier_trajectory); } void OptionsTrackingData::SetTimeVaryingProportionalGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory) { + gain_multiplier_trajectory) { DRAKE_DEMAND(gain_multiplier_trajectory->cols() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->rows() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->start_time() == 0); @@ -152,7 +179,7 @@ void OptionsTrackingData::SetTimeVaryingProportionalGainMultiplier( void OptionsTrackingData::SetTimeVaryingDerivativeGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory) { + gain_multiplier_trajectory) { DRAKE_DEMAND(gain_multiplier_trajectory->cols() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->rows() == n_ydot_); DRAKE_DEMAND(gain_multiplier_trajectory->start_time() == 0); @@ -161,11 +188,18 @@ void OptionsTrackingData::SetTimeVaryingDerivativeGainMultiplier( void OptionsTrackingData::SetTimerVaryingFeedForwardAccelMultiplier( std::shared_ptr> - ff_accel_multiplier_traj) { + ff_accel_multiplier_traj) { DRAKE_DEMAND(ff_accel_multiplier_traj->cols() == n_ydot_); DRAKE_DEMAND(ff_accel_multiplier_traj->rows() == n_ydot_); DRAKE_DEMAND(ff_accel_multiplier_traj->start_time() == 0); ff_accel_multiplier_traj_ = ff_accel_multiplier_traj; } +void OptionsTrackingData::SetCmdAccelerationBounds(Eigen::VectorXd& lb, Eigen::VectorXd& ub){ + DRAKE_DEMAND(lb.size() == n_ydot_); + DRAKE_DEMAND(ub.size() == n_ydot_); + yddot_cmd_lb_ = lb; + yddot_cmd_ub_ = ub; +}; + } // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index ecc0324502..eff035991c 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -22,27 +22,37 @@ class OptionsTrackingData : public OscTrackingData { // Additional feature -- multipliers for gains and feedforward acceleration // TOOD(yminchen): You can make ratio dictionary so that we have one ratio per // finite state + void SetTimeVaryingWeights( + std::shared_ptr> + weight_trajectory); + void SetTimeVaryingPDGainMultiplier( std::shared_ptr> gain_multiplier_trajectory); void SetTimeVaryingProportionalGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory); + gain_multiplier_trajectory); void SetTimeVaryingDerivativeGainMultiplier( std::shared_ptr> - gain_multiplier_trajectory); + gain_multiplier_trajectory); void SetTimerVaryingFeedForwardAccelMultiplier( std::shared_ptr> ff_accel_multiplier_traj); + void SetCmdAccelerationBounds(Eigen::VectorXd& lb, Eigen::VectorXd& ub); + void SetViewFrame(std::shared_ptr> view_frame) { view_frame_ = view_frame; with_view_frame_ = true; } + const Eigen::MatrixXd& GetWeight() const override { + return time_varying_weight_; + } + // disable feedforward acceleration for the components of the task space given // by indices void DisableFeedforwardAccel(const std::set& indices) { @@ -54,20 +64,24 @@ class OptionsTrackingData : public OscTrackingData { void AddJointAndStateToIgnoreInJacobian(int joint_vel_idx, int fsm_state); protected: - std::shared_ptr< - drake::trajectories::Trajectory> ff_accel_multiplier_traj_; - std::shared_ptr< - drake::trajectories::Trajectory> p_gain_multiplier_traj_; - std::shared_ptr< - drake::trajectories::Trajectory> d_gain_multiplier_traj_; + std::shared_ptr> + ff_accel_multiplier_traj_; + std::shared_ptr> + p_gain_multiplier_traj_; + std::shared_ptr> + d_gain_multiplier_traj_; + std::shared_ptr> weight_trajectory_; + + Eigen::VectorXd yddot_cmd_lb_; + Eigen::VectorXd yddot_cmd_ub_; std::set idx_zero_feedforward_accel_ = {}; std::shared_ptr> view_frame_; Eigen::Matrix3d view_frame_rot_T_; bool with_view_frame_ = false; + bool is_rotational_tracking_data_ = false; private: - // This method is called from the parent class (OscTrackingData) due to C++ // polymorphism. void UpdateActual(const Eigen::VectorXd& x_w_spr, @@ -87,17 +101,17 @@ class OptionsTrackingData : public OscTrackingData { void UpdateYdotError(const Eigen::VectorXd& v_proj) override; void UpdateYddotDes(double t, double t_since_state_switch) override; void UpdateYddotCmd(double t, double t_since_state_switch) override; + void UpdateW(double t, double t_since_state_switch); void UpdateFilters(double t); // Members of low-pass filter Eigen::VectorXd filtered_y_; Eigen::VectorXd filtered_ydot_; + Eigen::MatrixXd time_varying_weight_; double tau_ = -1; std::set low_pass_filter_element_idx_; - std::unordered_map> joint_idx_to_ignore_; double last_timestamp_ = -1; - }; } // namespace controllers diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index efb837526c..ca76bae336 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -7,6 +7,8 @@ using Eigen::MatrixXd; struct OSCGains { + double controller_frequency; + // costs double w_input; double w_accel; @@ -28,6 +30,7 @@ struct OSCGains { template void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(controller_frequency)); a->Visit(DRAKE_NVP(w_input)); a->Visit(DRAKE_NVP(w_accel)); a->Visit(DRAKE_NVP(w_lambda)); diff --git a/systems/controllers/osc/osc_tracking_data.cc b/systems/controllers/osc/osc_tracking_data.cc index 17fe03ec0c..10417594b8 100644 --- a/systems/controllers/osc/osc_tracking_data.cc +++ b/systems/controllers/osc/osc_tracking_data.cc @@ -88,18 +88,26 @@ void OscTrackingData::UpdateDesired( const drake::trajectories::Trajectory& traj, double t, double t_since_state_switch) { // 2. Update desired output - y_des_ = traj.value(t); if (traj.has_derivative()) { - ydot_des_ = traj.EvalDerivative(t, 1); - yddot_des_ = traj.EvalDerivative(t, 2); + if (traj.rows() == 2 * n_ydot_) { + y_des_ = traj.value(t).topRows(n_y_); + ydot_des_ = traj.EvalDerivative(t, 1).topRows(n_ydot_); + yddot_des_ = traj.EvalDerivative(t, 1).bottomRows(n_ydot_); + } else { + y_des_ = traj.value(t); + ydot_des_ = traj.EvalDerivative(t, 1); + yddot_des_ = traj.EvalDerivative(t, 2); + } } // TODO (yangwill): Remove this edge case after EvalDerivative has been // implemented for ExponentialPlusPiecewisePolynomial else { + y_des_ = traj.value(t); ydot_des_ = traj.MakeDerivative(1)->value(t); yddot_des_ = traj.MakeDerivative(2)->value(t); } UpdateYddotDes(t, t_since_state_switch); + time_through_trajectory_ = t - traj.start_time(); } void OscTrackingData::UpdateYddotCmd(double t, double t_since_state_switch) { @@ -119,7 +127,7 @@ void OscTrackingData::AddFiniteStateToTrack(int state) { // Run this function in OSC constructor to make sure that users constructed // OscTrackingData correctly. void OscTrackingData::CheckOscTrackingData() { - cout << "Checking " << name_ << endl; + // cout << "Checking " << name_ << endl; CheckDerivedOscTrackingData(); DRAKE_DEMAND((K_p_.rows() == n_ydot_) && (K_p_.cols() == n_ydot_)); diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index 3c105a4c74..94bcb81883 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -25,6 +25,7 @@ class OscTrackingData { const drake::multibody::MultibodyPlant& plant_wo_spr); virtual ~OscTrackingData() = default; + // Update() updates the caches. It does the following things in order: // - updates the current fsm state // - update the actual outputs @@ -66,7 +67,14 @@ class OscTrackingData { } // Set whether to use the impact invariant projection + void SetNoDerivativeFeedback(bool no_derivative_feedback) { + no_derivative_feedback_ = no_derivative_feedback; + } + + // Get whether to use the impact invariant projection bool GetImpactInvariantProjection() { return impact_invariant_projection_; } + // Get whether to use no derivative feedback near impacts + bool GetNoDerivativeFeedback() { return no_derivative_feedback_; } // Getters for debugging const Eigen::VectorXd& GetY() const { return y_; } @@ -86,7 +94,7 @@ class OscTrackingData { const Eigen::MatrixXd& GetJ() const { return J_; } const Eigen::VectorXd& GetJdotTimesV() const { return JdotV_; } const Eigen::VectorXd& GetYddotCommand() const { return yddot_command_; } - const Eigen::MatrixXd& GetWeight() const { return W_; } + virtual const Eigen::MatrixXd& GetWeight() const { return W_; } // Getters const std::string& GetName() const { return name_; }; @@ -119,6 +127,9 @@ class OscTrackingData { // Flags bool use_springs_in_eval_ = true; bool impact_invariant_projection_ = false; + bool no_derivative_feedback_ = false; + + double time_through_trajectory_ = 0; // Actual outputs, Jacobian and dJ/dt * v Eigen::VectorXd y_; @@ -147,6 +158,9 @@ class OscTrackingData { // If `state_` is empty, then the tracking is always on. std::set active_fsm_states_; + // Cost weights + Eigen::MatrixXd W_; + /// OSC calculates feedback positions/velocities from `plant_w_spr_`, /// but in the optimization it uses `plant_wo_spr_`. The reason of using /// MultibodyPlant without springs is that the OSC cannot track desired @@ -159,7 +173,6 @@ class OscTrackingData { const drake::multibody::BodyFrame& world_wo_spr_; private: - void UpdateDesired(const drake::trajectories::Trajectory& traj, double t, double t_since_state_switch); // Update actual output methods @@ -187,9 +200,6 @@ class OscTrackingData { // Trajectory name std::string name_; - - // Cost weights - Eigen::MatrixXd W_; }; } // namespace controllers diff --git a/systems/controllers/osc/relative_translation_tracking_data.cc b/systems/controllers/osc/relative_translation_tracking_data.cc index 1936fb4669..eaf179611d 100644 --- a/systems/controllers/osc/relative_translation_tracking_data.cc +++ b/systems/controllers/osc/relative_translation_tracking_data.cc @@ -38,7 +38,7 @@ void RelativeTranslationTrackingData::Update( const drake::trajectories::Trajectory& traj, double t, double t_gait_cycle, const int fsm_state, const VectorXd& v_proj) { // Currently there are redundant calculation here. For both to_frame_data_, - // and from_frame_data_, we don't nee to run UpdateDesired, UpdateYError, + // and from_frame_data_, we don't nee to run UpdateDesired, UpdateYError, // UpdateYdotError and UpdateYddotCmd inside Update(). // TODO: improve this to make it slightly more efficient. to_frame_data_->Update(x_w_spr, context_w_spr, x_wo_spr, context_wo_spr, traj, diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index 7745731cbe..d5a065d6fb 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -1,4 +1,5 @@ #include "rot_space_tracking_data.h" + #include using Eigen::Isometry3d; @@ -22,8 +23,9 @@ RotTaskSpaceTrackingData::RotTaskSpaceTrackingData( const MatrixXd& W, const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) : OptionsTrackingData(name, kQuaternionDim, kSpaceDim, K_p, K_d, W, - plant_w_spr, plant_wo_spr) {} - + plant_w_spr, plant_wo_spr) { + is_rotational_tracking_data_ = true; +} void RotTaskSpaceTrackingData::AddFrameToTrack( const std::string& body_name, const Eigen::Isometry3d& frame_pose) { @@ -33,7 +35,6 @@ void RotTaskSpaceTrackingData::AddStateAndFrameToTrack( int fsm_state, const std::string& body_name, const Eigen::Isometry3d& frame_pose) { AddFiniteStateToTrack(fsm_state); - // AddPointToTrack(body_name, pt_on_body); DRAKE_DEMAND(plant_w_spr_.HasBodyNamed(body_name)); DRAKE_DEMAND(plant_wo_spr_.HasBodyNamed(body_name)); body_frames_w_spr_[fsm_state] = @@ -43,8 +44,6 @@ void RotTaskSpaceTrackingData::AddStateAndFrameToTrack( frame_poses_[fsm_state] = frame_pose; } - - void RotTaskSpaceTrackingData::UpdateY(const VectorXd& x_w_spr, const Context& context_w_spr) { auto transform_mat = plant_w_spr_.CalcRelativeTransform( @@ -65,10 +64,11 @@ void RotTaskSpaceTrackingData::UpdateYError() { Quaterniond y_quat(y_(0), y_(1), y_(2), y_(3)); // Get relative quaternion (from current to desired) - Quaterniond relative_qaut = (y_quat_des * y_quat.inverse()).normalized(); - double theta = 2 * acos(relative_qaut.w()); - Vector3d rot_axis = relative_qaut.vec().normalized(); + Quaterniond relative_quat = (y_quat_des * y_quat.inverse()).normalized(); + double theta = 2 * acos(relative_quat.w()); + Vector3d rot_axis = relative_quat.vec().normalized(); error_y_ = theta * rot_axis; + if (with_view_frame_) error_y_ = view_frame_rot_T_ * error_y_; } void RotTaskSpaceTrackingData::UpdateYdot( @@ -89,6 +89,9 @@ void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { ydot_des_(3)); Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); error_ydot_ = w_des_ - ydot_ - GetJ() * v_proj; + if (with_view_frame_) { + error_ydot_ = view_frame_rot_T_ * error_ydot_; + } ydot_des_ = w_des_; // Overwrite 4d quat_dot with 3d omega. Need this for osc logging @@ -127,13 +130,14 @@ void RotTaskSpaceTrackingData::UpdateYddotDes(double, double) { "acceleration"; } if (ff_accel_multiplier_traj_ != nullptr) { - std::cerr << "RotTaskSpaceTrackingData does not support feedforward multipliers "; + std::cerr + << "RotTaskSpaceTrackingData does not support feedforward multipliers "; } } void RotTaskSpaceTrackingData::CheckDerivedOscTrackingData() { - if (!body_frames_w_spr_.empty()) { - body_frames_w_spr_ = body_frames_wo_spr_; - } + if (!body_frames_w_spr_.empty()) { + body_frames_w_spr_ = body_frames_wo_spr_; + } } } // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/trans_space_tracking_data.cc b/systems/controllers/osc/trans_space_tracking_data.cc index 7962d0aa17..c6dd155001 100644 --- a/systems/controllers/osc/trans_space_tracking_data.cc +++ b/systems/controllers/osc/trans_space_tracking_data.cc @@ -1,5 +1,7 @@ #include "trans_space_tracking_data.h" +#include + using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; @@ -18,8 +20,7 @@ TransTaskSpaceTrackingData::TransTaskSpaceTrackingData( const MatrixXd& W, const MultibodyPlant& plant_w_spr, const MultibodyPlant& plant_wo_spr) : OptionsTrackingData(name, kSpaceDim, kSpaceDim, K_p, K_d, W, plant_w_spr, - plant_wo_spr) { -} + plant_wo_spr) {} void TransTaskSpaceTrackingData::AddPointToTrack(const std::string& body_name, const Vector3d& pt_on_body) { @@ -73,8 +74,8 @@ void TransTaskSpaceTrackingData::UpdateJdotV( } void TransTaskSpaceTrackingData::CheckDerivedOscTrackingData() { - if (!body_frames_w_spr_.empty()) { - body_frames_w_spr_ = body_frames_wo_spr_; - } + if (!body_frames_w_spr_.empty()) { + body_frames_w_spr_ = body_frames_wo_spr_; + } } } // namespace dairlib::systems::controllers diff --git a/systems/controllers/time_based_fsm.h b/systems/controllers/time_based_fsm.h index e7da411315..f22c596b68 100644 --- a/systems/controllers/time_based_fsm.h +++ b/systems/controllers/time_based_fsm.h @@ -41,17 +41,17 @@ class TimeBasedFiniteStateMachine : public drake::systems::LeafSystem { const std::vector& states, const std::vector& state_durations, double t0 = 0); - const drake::systems::InputPort& get_input_port_state() const { + const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); } - const drake::systems::OutputPort& get_output_port_fsm() const { + const drake::systems::OutputPort& get_fsm_output_port() const { return this->get_output_port(fsm_port_); } protected: - int state_port_; - int fsm_port_; + drake::systems::InputPortIndex state_port_; + drake::systems::OutputPortIndex fsm_port_; private: void CalcFiniteState(const drake::systems::Context& context, From b7278e1cfbb6de3a1431b6f753200a4e7fe2f93e Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Mar 2023 14:06:09 -0500 Subject: [PATCH 396/758] addressing PR commnets --- common/blending_utils.h | 2 +- .../contact_scheduler/contact_scheduler.cc | 148 +++---- .../contact_scheduler/contact_scheduler.h | 16 +- examples/Cassie/dispatcher_robot_in.cc | 2 +- examples/Cassie/dispatcher_robot_out.cc | 2 +- examples/Cassie/osc/high_level_command.cc | 53 +-- examples/Cassie/osc/high_level_command.h | 14 +- .../osc_jump/jumping_event_based_fsm.cc | 4 +- .../Cassie/osc_jump/jumping_event_based_fsm.h | 2 +- examples/Cassie/osc_run/BUILD.bazel | 13 - .../osc_run/convert_traj_for_controller.cc | 392 ------------------ .../Cassie/osc_run/foot_traj_generator.cc | 4 +- examples/Cassie/osc_run/foot_traj_generator.h | 13 +- .../osc_run/pelvis_trans_traj_generator.cc | 2 +- examples/Cassie/run_osc_running_controller.cc | 86 ++-- .../impact_aware_time_based_fsm.cc | 4 +- .../impact_aware_time_based_fsm.h | 2 +- .../controllers/osc/options_tracking_data.cc | 2 +- .../osc/rot_space_tracking_data.cc | 4 +- 19 files changed, 176 insertions(+), 589 deletions(-) delete mode 100644 examples/Cassie/osc_run/convert_traj_for_controller.cc diff --git a/common/blending_utils.h b/common/blending_utils.h index 453a5c3749..26b1c415c7 100644 --- a/common/blending_utils.h +++ b/common/blending_utils.h @@ -1,6 +1,6 @@ #pragma once -enum BLEND_FUNC { SIGMOID, EXP }; +enum BLEND_FUNC { kSigmoid, kExponential }; double blend_sigmoid(double t, double tau, double window); diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 934729f84f..185ece376b 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -26,11 +26,11 @@ using drake::systems::Context; using systems::ImpactInfoVector; using systems::OutputVector; -ContactScheduler::ContactScheduler(const MultibodyPlant& plant, - Context* plant_context, - std::set impact_states, - double near_impact_threshold, double tau, - BLEND_FUNC blend_func) +SLIPContactScheduler::SLIPContactScheduler(const MultibodyPlant& plant, + Context* plant_context, + std::set impact_states, + double near_impact_threshold, double tau, + BLEND_FUNC blend_func) : plant_(plant), plant_context_(plant_context), impact_states_(std::move(impact_states)), @@ -39,7 +39,7 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, blend_func_(blend_func) { DRAKE_DEMAND(tau_ > 0); DRAKE_DEMAND(near_impact_threshold_ >= 0); - this->set_name("ContactScheduler"); + this->set_name("SLIPContactScheduler"); // Declare system ports state_port_ = this->DeclareVectorInputPort( "x, u, t", OutputVector(plant.num_positions(), @@ -47,20 +47,20 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, plant.num_actuators())) .get_index(); fsm_port_ = this->DeclareVectorOutputPort("fsm", BasicVector(1), - &ContactScheduler::CalcFiniteState) + &SLIPContactScheduler::CalcFiniteState) .get_index(); impact_info_port_ = this->DeclareVectorOutputPort( "near_impact", ImpactInfoVector(0, 0, 0), - &ContactScheduler::CalcNextImpactInfo) + &SLIPContactScheduler::CalcNextImpactInfo) .get_index(); clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), - &ContactScheduler::CalcClock) + &SLIPContactScheduler::CalcClock) .get_index(); contact_scheduler_port_ = this->DeclareVectorOutputPort( "contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, " "right_t0, right_t0", - BasicVector(6), &ContactScheduler::CalcContactScheduler) + BasicVector(6), &SLIPContactScheduler::CalcContactScheduler) .get_index(); // Declare discrete states and update @@ -72,28 +72,28 @@ ContactScheduler::ContactScheduler(const MultibodyPlant& plant, nominal_state_durations << 0.25, 0.1; nominal_state_durations_index_ = DeclareDiscreteState(nominal_state_durations); - std::vector> initial_state_transitions = - {{-0.1, RIGHT_FLIGHT}, - {0.00, LEFT_STANCE}, - {0.25, LEFT_FLIGHT}, - {0.35, RIGHT_STANCE}}; + std::vector> initial_state_transitions = + {{-0.1, kRightFlight}, + {0.00, kLeftStance}, + {0.25, kLeftFlight}, + {0.35, kRightStance}}; VectorXd initial_transition_times = VectorXd::Zero(4); initial_transition_times << -0.1, 0.0, 0.25, 0.35; transition_times_index_ = DeclareDiscreteState(initial_transition_times); ground_height_index_ = DeclareDiscreteState(VectorXd::Zero(1)); upcoming_transitions_index_ = DeclareAbstractState( - drake::Value>>{ + drake::Value>>{ initial_state_transitions}); debug_port_ = this->DeclareAbstractOutputPort( - "status", &ContactScheduler::OutputDebuggingInfo) + "status", &SLIPContactScheduler::OutputDebuggingInfo) .get_index(); DeclarePerStepUnrestrictedUpdateEvent( - &ContactScheduler::UpdateTransitionTimes); + &SLIPContactScheduler::UpdateTransitionTimes); } -EventStatus ContactScheduler::UpdateTransitionTimes( +EventStatus SLIPContactScheduler::UpdateTransitionTimes( const Context& context, State* state) const { DRAKE_DEMAND(rest_length_ > 0); DRAKE_DEMAND(stance_duration_ > 0); @@ -103,25 +103,25 @@ EventStatus ContactScheduler::UpdateTransitionTimes( (OutputVector*)this->EvalVectorInput(context, state_port_); double current_time = robot_output->get_timestamp(); - auto stored_fsm_state = (RUNNING_FSM_STATE)state->get_mutable_discrete_state( + auto stored_fsm_state = (RunningFsmState)state->get_mutable_discrete_state( stored_fsm_state_index_)[0]; auto transition_times = state->get_mutable_discrete_state(transition_times_index_) .get_mutable_value(); auto& upcoming_transitions = state->get_mutable_abstract_state< - std::vector>>( + std::vector>>( upcoming_transitions_index_); auto active_state = stored_fsm_state; double transition_time = upcoming_transitions.at(3).first; - RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; + RunningFsmState transition_state = upcoming_transitions.at(3).second; if (current_time > transition_time) { active_state = transition_state; } VectorXd q = robot_output->GetPositions(); multibody::SetPositionsIfNew(plant_, q, plant_context_); - if (active_state == LEFT_STANCE) { + if (active_state == kLeftStance) { auto toe_front = LeftToeFront(plant_); auto toe_rear = LeftToeRear(plant_); Vector3d toe_front_pos; @@ -135,7 +135,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( 0.5 * (toe_front_pos[2] + toe_rear_pos[2]) * VectorXd::Ones(1); state->get_mutable_discrete_state(ground_height_index_) .SetFromVector(height); - } else if (active_state == RIGHT_STANCE) { + } else if (active_state == kRightStance) { auto toe_front = RightToeFront(plant_); auto toe_rear = RightToeRear(plant_); Vector3d toe_front_pos; @@ -171,7 +171,7 @@ EventStatus ContactScheduler::UpdateTransitionTimes( state->get_discrete_state(ground_height_index_).value()[0]; double pelvis_zdot = robot_output->GetVelocityAtIndex(5); - if (active_state == LEFT_STANCE || active_state == RIGHT_STANCE) { + if (active_state == kLeftStance || active_state == kRightStance) { // This is a very crude approximation double stance_scale = (pelvis_z) / (rest_length_); stance_scale = @@ -180,18 +180,18 @@ EventStatus ContactScheduler::UpdateTransitionTimes( stored_transition_time + stance_scale * stance_duration_; state->get_mutable_discrete_state(nominal_state_durations_index_)[0] = next_transition_time - stored_transition_time; - if (active_state == LEFT_STANCE) { - transition_times[LEFT_FLIGHT] = next_transition_time; - upcoming_transitions = {{transition_times[RIGHT_STANCE], RIGHT_STANCE}, - {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, - {transition_times[LEFT_STANCE], LEFT_STANCE}, - {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}}; + if (active_state == kLeftStance) { + transition_times[kLeftFlight] = next_transition_time; + upcoming_transitions = {{transition_times[kRightStance], kRightStance}, + {transition_times[kRightFlight], kRightFlight}, + {transition_times[kLeftStance], kLeftStance}, + {transition_times[kLeftFlight], kLeftFlight}}; } else { - transition_times[RIGHT_FLIGHT] = next_transition_time; - upcoming_transitions = {{transition_times[LEFT_STANCE], LEFT_STANCE}, - {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, - {transition_times[RIGHT_STANCE], RIGHT_STANCE}, - {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}}; + transition_times[kRightFlight] = next_transition_time; + upcoming_transitions = {{transition_times[kLeftStance], kLeftStance}, + {transition_times[kLeftFlight], kLeftFlight}, + {transition_times[kRightStance], kRightStance}, + {transition_times[kRightFlight], kRightFlight}}; } } else { // set default to minimum touchdown time in case pelvis is below rest @@ -210,18 +210,18 @@ EventStatus ContactScheduler::UpdateTransitionTimes( stored_transition_time + time_to_touchdown_saturated; state->get_mutable_discrete_state(nominal_state_durations_index_)[1] = next_transition_time - stored_transition_time; - if (active_state == LEFT_FLIGHT) { - transition_times[RIGHT_STANCE] = next_transition_time; - upcoming_transitions = {{transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, - {transition_times[LEFT_STANCE], LEFT_STANCE}, - {transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, - {transition_times[RIGHT_STANCE], RIGHT_STANCE}}; + if (active_state == kLeftFlight) { + transition_times[kRightStance] = next_transition_time; + upcoming_transitions = {{transition_times[kRightFlight], kRightFlight}, + {transition_times[kLeftStance], kLeftStance}, + {transition_times[kLeftFlight], kLeftFlight}, + {transition_times[kRightStance], kRightStance}}; } else { - transition_times[LEFT_STANCE] = next_transition_time; - upcoming_transitions = {{transition_times[LEFT_FLIGHT], LEFT_FLIGHT}, - {transition_times[RIGHT_STANCE], RIGHT_STANCE}, - {transition_times[RIGHT_FLIGHT], RIGHT_FLIGHT}, - {transition_times[LEFT_STANCE], LEFT_STANCE}}; + transition_times[kLeftStance] = next_transition_time; + upcoming_transitions = {{transition_times[kLeftFlight], kLeftFlight}, + {transition_times[kRightStance], kRightStance}, + {transition_times[kRightFlight], kRightFlight}, + {transition_times[kLeftStance], kLeftStance}}; } } } @@ -231,15 +231,15 @@ EventStatus ContactScheduler::UpdateTransitionTimes( return drake::systems::EventStatus::Succeeded(); } -void ContactScheduler::CalcFiniteState(const Context& context, - BasicVector* fsm_state) const { +void SLIPContactScheduler::CalcFiniteState(const Context& context, + BasicVector* fsm_state) const { // Assign fsm_state VectorXd current_finite_state = context.get_discrete_state(stored_fsm_state_index_).CopyToVector(); fsm_state->get_mutable_value() = current_finite_state; } -void ContactScheduler::CalcNextImpactInfo( +void SLIPContactScheduler::CalcNextImpactInfo( const Context& context, ImpactInfoVector* near_impact) const { // Read in lcm message time @@ -247,21 +247,21 @@ void ContactScheduler::CalcNextImpactInfo( (OutputVector*)this->EvalVectorInput(context, state_port_); auto current_time = static_cast(robot_output->get_timestamp()); const auto& upcoming_transitions = context.get_abstract_state< - std::vector>>( + std::vector>>( upcoming_transitions_index_); // Assign the blending function ptr - auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; + auto alpha_func = blend_func_ == kSigmoid ? &blend_sigmoid : &blend_exp; near_impact->set_timestamp(current_time); near_impact->SetAlpha(0); // Get current finite state double transition_time = upcoming_transitions.at(3).first; - RUNNING_FSM_STATE transition_state = upcoming_transitions.at(3).second; + RunningFsmState transition_state = upcoming_transitions.at(3).second; double previous_transition_time = upcoming_transitions.at(2).first; - RUNNING_FSM_STATE current_state = upcoming_transitions.at(2).second; - double blend_window = blend_func_ == SIGMOID ? 1.5 * near_impact_threshold_ - : near_impact_threshold_; + RunningFsmState current_state = upcoming_transitions.at(2).second; + double blend_window = blend_func_ == kSigmoid ? 1.5 * near_impact_threshold_ + : near_impact_threshold_; // Check if the upcoming state has an impact if (impact_states_.count(transition_state) != 0) { if (abs(current_time - transition_time) < blend_window) { @@ -287,8 +287,8 @@ void ContactScheduler::CalcNextImpactInfo( } } -void ContactScheduler::CalcClock(const Context& context, - BasicVector* clock) const { +void SLIPContactScheduler::CalcClock(const Context& context, + BasicVector* clock) const { // Read in lcm message time const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); @@ -297,11 +297,11 @@ void ContactScheduler::CalcClock(const Context& context, clock->get_mutable_value()(0) = current_time; } -void ContactScheduler::CalcContactScheduler( +void SLIPContactScheduler::CalcContactScheduler( const Context& context, BasicVector* contact_timing) const { // Read in lcm message time auto current_state_ = - (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; + (RunningFsmState)context.get_discrete_state(stored_fsm_state_index_)[0]; double nominal_stance_duration = context.get_discrete_state(nominal_state_durations_index_)[0]; double nominal_flight_duration = @@ -316,33 +316,33 @@ void ContactScheduler::CalcContactScheduler( /// LeftFootTouchdown = 3 /// RightFootLiftoff = 4 /// RightFootTouchdown = 5 - if (current_state_ == LEFT_STANCE || current_state_ == RIGHT_FLIGHT) { - contact_timing->get_mutable_value()(0) = transition_times[LEFT_STANCE]; - contact_timing->get_mutable_value()(1) = transition_times[LEFT_FLIGHT]; + if (current_state_ == kLeftStance || current_state_ == kRightFlight) { + contact_timing->get_mutable_value()(0) = transition_times[kLeftStance]; + contact_timing->get_mutable_value()(1) = transition_times[kLeftFlight]; } else { - contact_timing->get_mutable_value()(0) = transition_times[RIGHT_STANCE]; - contact_timing->get_mutable_value()(1) = transition_times[RIGHT_FLIGHT]; + contact_timing->get_mutable_value()(0) = transition_times[kRightStance]; + contact_timing->get_mutable_value()(1) = transition_times[kRightFlight]; } - contact_timing->get_mutable_value()(2) = transition_times[LEFT_FLIGHT]; - contact_timing->get_mutable_value()(3) = transition_times[LEFT_FLIGHT] + + contact_timing->get_mutable_value()(2) = transition_times[kLeftFlight]; + contact_timing->get_mutable_value()(3) = transition_times[kLeftFlight] + 2 * nominal_flight_duration + nominal_stance_duration; - contact_timing->get_mutable_value()(4) = transition_times[RIGHT_FLIGHT]; - contact_timing->get_mutable_value()(5) = transition_times[RIGHT_FLIGHT] + + contact_timing->get_mutable_value()(4) = transition_times[kRightFlight]; + contact_timing->get_mutable_value()(5) = transition_times[kRightFlight] + 2 * nominal_flight_duration + nominal_stance_duration; } -void ContactScheduler::OutputDebuggingInfo( +void SLIPContactScheduler::OutputDebuggingInfo( const drake::systems::Context& context, dairlib::lcmt_contact_timing* debug_info) const { const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); auto& upcoming_transitions = context.get_abstract_state< - std::vector>>( + std::vector>>( upcoming_transitions_index_); auto stored_fsm_state = - (RUNNING_FSM_STATE)context.get_discrete_state(stored_fsm_state_index_)[0]; + (RunningFsmState)context.get_discrete_state(stored_fsm_state_index_)[0]; debug_info->utime = robot_output->get_timestamp() * 1e6; debug_info->n_transitions = 4; @@ -351,8 +351,8 @@ void ContactScheduler::OutputDebuggingInfo( debug_info->transition_times = std::vector(4); debug_info->transition_states.clear(); debug_info->transition_states = std::vector(4); - debug_info->fsm_state_names = {"LEFT_STANCE (0)", "RIGHT_STANCE (1)", - "LEFT_FLIGHT (2)", "RIGHT_FLIGHT (3)"}; + debug_info->fsm_state_names = {"kLeftStance (0)", "kRightStance (1)", + "kLeftFlight (2)", "kRightFlight (3)"}; for (int i = 0; i < debug_info->n_transitions; ++i) { debug_info->transition_times.at(i) = upcoming_transitions[i].first; diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 9ba4f2e92b..9b10c7e08c 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -15,15 +15,15 @@ namespace dairlib { -enum RUNNING_FSM_STATE { LEFT_STANCE, RIGHT_STANCE, LEFT_FLIGHT, RIGHT_FLIGHT }; +enum RunningFsmState { kLeftStance, kRightStance, kLeftFlight, kRightFlight }; -class ContactScheduler : public drake::systems::LeafSystem { +class SLIPContactScheduler : public drake::systems::LeafSystem { public: - ContactScheduler(const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* plant_context, - std::set impact_states, - double near_impact_threshold = 0, double tau = 0.0025, - BLEND_FUNC blend_func = SIGMOID); + SLIPContactScheduler(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* plant_context, + std::set impact_states, + double near_impact_threshold = 0, double tau = 0.0025, + BLEND_FUNC blend_func = kSigmoid); void SetSLIPParams(double rest_length) { rest_length_ = rest_length; } void SetNominalStepTimings(double stance_duration, double flight_duration) { @@ -83,7 +83,7 @@ class ContactScheduler : public drake::systems::LeafSystem { drake::systems::Context* plant_context_; // For impact-invariant calculations - const std::set impact_states_; + const std::set impact_states_; double near_impact_threshold_; double tau_; const BLEND_FUNC blend_func_; diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 2b699691c9..3993e9dba2 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -224,7 +224,7 @@ int do_main(int argc, char* argv[]) { &(loop.get_diagram()->GetMutableSubsystemContext( *config_receiver, &loop.get_diagram_mutable_context())), msg); - DrawAndSaveDiagramGraph(*loop.get_diagram()); +// DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); return 0; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index 0afd7a708f..ba3bc860a6 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -331,7 +331,7 @@ int do_main(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("dispatcher_robot_out")); const auto& diagram = *owned_diagram; - DrawAndSaveDiagramGraph(diagram); +// DrawAndSaveDiagramGraph(diagram); drake::systems::Simulator simulator(std::move(owned_diagram)); auto& diagram_context = simulator.get_mutable_context(); diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index a7976d478f..6ef6d8852c 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -39,7 +39,7 @@ namespace osc { HighLevelCommand::HighLevelCommand( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, double vel_scale_rot, - double vel_scale_trans_sagital, double vel_scale_trans_lateral, + double vel_scale_trans_sagittal, double vel_scale_trans_lateral, double stick_filter_dt) : HighLevelCommand(plant, context) { radio_port_ = @@ -48,7 +48,7 @@ HighLevelCommand::HighLevelCommand( .get_index(); use_radio_command_ = true; vel_scale_rot_ = vel_scale_rot; - vel_scale_trans_sagital_ = vel_scale_trans_sagital; + vel_scale_trans_sagittal_ = vel_scale_trans_sagittal; vel_scale_trans_lateral_ = vel_scale_trans_lateral; stick_filter_dt_ = stick_filter_dt; } @@ -56,8 +56,8 @@ HighLevelCommand::HighLevelCommand( HighLevelCommand::HighLevelCommand( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, double kp_yaw, double kd_yaw, - double vel_max_yaw, double kp_pos_sagital, double kd_pos_sagital, - double vel_max_sagital, double kp_pos_lateral, double kd_pos_lateral, + double vel_max_yaw, double kp_pos_sagittal, double kd_pos_sagittal, + double vel_max_sagittal, double kp_pos_lateral, double kd_pos_lateral, double vel_max_lateral, double target_pos_offset, const Vector2d& global_target_position, const Vector2d& params_of_no_turning) @@ -66,9 +66,9 @@ HighLevelCommand::HighLevelCommand( kp_yaw_ = kp_yaw; kd_yaw_ = kd_yaw; vel_max_yaw_ = vel_max_yaw; - kp_pos_sagital_ = kp_pos_sagital; - kd_pos_sagital_ = kd_pos_sagital; - vel_max_sagital_ = vel_max_sagital; + kp_pos_sagittal_ = kp_pos_sagittal; + kd_pos_sagittal_ = kd_pos_sagittal; + vel_max_sagittal_ = vel_max_sagittal; target_pos_offset_ = target_pos_offset; kp_pos_lateral_ = kp_pos_lateral; kd_pos_lateral_ = kd_pos_lateral; @@ -92,11 +92,11 @@ HighLevelCommand::HighLevelCommand( .get_index(); yaw_port_ = - this->DeclareVectorOutputPort("pelvis_yaw", BasicVector(1), + this->DeclareVectorOutputPort("pelvis_yaw", 1, &HighLevelCommand::CopyHeadingAngle) .get_index(); xy_port_ = - this->DeclareVectorOutputPort("pelvis_xy", BasicVector(2), + this->DeclareVectorOutputPort("pelvis_xy", 2, &HighLevelCommand::CopyDesiredHorizontalVel) .get_index(); // Declare update event @@ -114,21 +114,19 @@ EventStatus HighLevelCommand::DiscreteVariableUpdate( this->EvalInputValue(context, radio_port_); // TODO(yangwill) make sure there is a message available // des_vel indices: 0: yaw_vel (right joystick left/right) - // 1: saggital_vel (left joystick up/down) + // 1: sagittal (left joystick up/down) // 2: lateral_vel (left joystick left/right) - double vel_scale_trans_sagital = - (radio_out->channel[6] + 1.0) * vel_scale_trans_sagital_; + // Side dial sets the scale + double vel_scale_trans_sagittal = + (radio_out->channel[6] + 1.0) * vel_scale_trans_sagittal_; // approximately 1KHz sampling rate - no need to be too precise double a = .001 / (stick_filter_dt_ + .001); Vector3d des_vel_prev = discrete_state->get_value(des_vel_idx_); Vector3d des_vel; - // des_vel << vel_scale_rot_ * radio_out->channel[3], - // vel_scale_trans_sagital_ * radio_out->channel[0], - // vel_scale_trans_lateral_ * radio_out->channel[1]; - // discrete_state->get_mutable_vector(des_vel_idx_).set_value(des_vel); + discrete_state->get_mutable_vector(des_vel_idx_).set_value(des_vel); des_vel << vel_scale_rot_ * radio_out->channel[3], - vel_scale_trans_sagital * radio_out->channel[0], + vel_scale_trans_sagittal * radio_out->channel[0], vel_scale_trans_lateral_ * radio_out->channel[1]; Vector3d des_vel_filt; des_vel_filt(0) = des_vel(0); @@ -181,8 +179,6 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( // PD position control double des_yaw_vel = kp_yaw_ * heading_error + kd_yaw_ * (-yaw_vel); - // des_yaw_vel = drake::math::saturate(des_yaw_vel, -vel_max_yaw_, - // vel_max_yaw_); des_yaw_vel = std::clamp(des_yaw_vel, -vel_max_yaw_, vel_max_yaw_); // Convex combination of 0 and desired yaw velocity @@ -198,7 +194,7 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( // Apply walking speed control only when the robot is facing the target // position. - double des_sagital_vel = 0; + double des_sagittal_vel = 0; double des_lateral_vel = 0; if (abs(filtered_heading_error) < M_PI / 2) { // Extract quaternion from floating base position @@ -215,16 +211,13 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( drake::math::quatRotateVec(quad_conj, global_com_pos_to_target_pos_3d); Vector3d local_com_vel = drake::math::quatRotateVec(quad_conj, com_vel); - // Sagital plane position PD control - double com_vel_sagital = local_com_vel(0); - des_sagital_vel = kp_pos_sagital_ * (local_com_pos_to_target_pos(0) + + // Sagittal plane position PD control + double com_vel_sagittal = local_com_vel(0); + des_sagittal_vel = kp_pos_sagittal_ * (local_com_pos_to_target_pos(0) + target_pos_offset_) + - kd_pos_sagital_ * (-com_vel_sagital); - // des_sagital_vel = drake::math::saturate(des_sagital_vel, - // -vel_max_sagital_, - // vel_max_sagital_); - des_sagital_vel = - std::clamp(des_sagital_vel, -vel_max_sagital_, vel_max_sagital_); + kd_pos_sagittal_ * (-com_vel_sagittal); + des_sagittal_vel = + std::clamp(des_sagittal_vel, -vel_max_sagittal_, vel_max_sagittal_); // Frontal plane position PD control. TODO(yminchen): tune this double com_vel_lateral = local_com_vel(1); @@ -234,7 +227,7 @@ VectorXd HighLevelCommand::CalcCommandFromTargetPosition( std::clamp(des_lateral_vel, -vel_max_lateral_, vel_max_lateral_); } Vector3d des_vel; - des_vel << desired_filtered_yaw_vel, des_sagital_vel, des_lateral_vel; + des_vel << desired_filtered_yaw_vel, des_sagittal_vel, des_lateral_vel; return des_vel; } diff --git a/examples/Cassie/osc/high_level_command.h b/examples/Cassie/osc/high_level_command.h index eb63747bfc..5912d5c25d 100644 --- a/examples/Cassie/osc/high_level_command.h +++ b/examples/Cassie/osc/high_level_command.h @@ -53,7 +53,7 @@ class HighLevelCommand : public drake::systems::LeafSystem { /// Designed to be used with hardware HighLevelCommand(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - double vel_scale_rot, double vel_scale_trans_sagital, + double vel_scale_rot, double vel_scale_trans_sagittal, double vel_scale_trans_lateral, double stick_filter_dt=0.0); /// Constructor that computes the desired yaw and translational velocities /// according to a global target position @@ -61,8 +61,8 @@ class HighLevelCommand : public drake::systems::LeafSystem { /// Designed to be used in simulation HighLevelCommand(const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, double kp_yaw, - double kd_yaw, double vel_max_yaw, double kp_pos_sagital, - double kd_pos_sagital, double vel_max_sagital, + double kd_yaw, double vel_max_yaw, double kp_pos_sagittal, + double kd_pos_sagittal, double vel_max_sagittal, double kp_pos_lateral, double kd_pos_lateral, double vel_max_lateral, double target_pos_offset, const Eigen::Vector2d& global_target_position, @@ -121,9 +121,9 @@ class HighLevelCommand : public drake::systems::LeafSystem { double vel_max_yaw_; // Position control (sagital plane) parameters - double kp_pos_sagital_; - double kd_pos_sagital_; - double vel_max_sagital_; + double kp_pos_sagittal_; + double kd_pos_sagittal_; + double vel_max_sagittal_; double target_pos_offset_; // Due to steady state error // Position control (frontal plane) parameters @@ -135,7 +135,7 @@ class HighLevelCommand : public drake::systems::LeafSystem { Eigen::Vector2d global_target_position_; Eigen::Vector2d params_of_no_turning_; double vel_scale_rot_; - double vel_scale_trans_sagital_; + double vel_scale_trans_sagittal_; double vel_scale_trans_lateral_; double stick_filter_dt_; }; diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc index 713f72adc9..407c01ebca 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.cc +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.cc @@ -164,12 +164,12 @@ void JumpingEventFsm::CalcNearImpact(const Context& context, near_impact->set_timestamp(timestamp); near_impact->SetCurrentContactMode(0); near_impact->SetAlpha(0); - auto alpha_func = blend_func_ == SIGMOID ? &alpha_sigmoid : &alpha_exp; + auto alpha_func = blend_func_ == kSigmoid ? &alpha_sigmoid : &alpha_exp; // Get current finite state if (abs(timestamp - transition_times_[FLIGHT]) < impact_threshold_) { double blend_window = - blend_func_ == SIGMOID ? 1.5 * impact_threshold_ : impact_threshold_; + blend_func_ == kSigmoid ? 1.5 * impact_threshold_ : impact_threshold_; if (abs(timestamp - transition_times_[FLIGHT]) < blend_window) { if (timestamp < transition_times_[FLIGHT]) { near_impact->SetAlpha(alpha_func(timestamp - transition_times_[FLIGHT], diff --git a/examples/Cassie/osc_jump/jumping_event_based_fsm.h b/examples/Cassie/osc_jump/jumping_event_based_fsm.h index 8b7f7054de..74c11a6e7a 100644 --- a/examples/Cassie/osc_jump/jumping_event_based_fsm.h +++ b/examples/Cassie/osc_jump/jumping_event_based_fsm.h @@ -27,7 +27,7 @@ class JumpingEventFsm : public drake::systems::LeafSystem { const std::vector& transition_times, bool contact_based = true, double impact_threshold = 0.0, JUMPING_FSM_STATE init_state = BALANCE, - BLEND_FUNC blend_func = SIGMOID); + BLEND_FUNC blend_func = kSigmoid); const drake::systems::InputPort& get_state_input_port() const { return this->get_input_port(state_port_); diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 8432f50563..53ffab7875 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -31,19 +31,6 @@ cc_library( ], ) -cc_binary( - name = "convert_traj_for_controller", - srcs = ["convert_traj_for_controller.cc"], - deps = [ - "//examples/Cassie:cassie_utils", - "//lcm:lcm_trajectory_saver", - "//lcm:dircon_trajectory_saver", - "//multibody:utils", - "@drake//:drake_shared_library", - "@gflags", - ], -) - cc_library( name = "osc_running_gains", hdrs = ["osc_running_gains.h"], diff --git a/examples/Cassie/osc_run/convert_traj_for_controller.cc b/examples/Cassie/osc_run/convert_traj_for_controller.cc deleted file mode 100644 index 1a328e5f40..0000000000 --- a/examples/Cassie/osc_run/convert_traj_for_controller.cc +++ /dev/null @@ -1,392 +0,0 @@ -#include -#include -#include - -#include "examples/Cassie/cassie_utils.h" -#include "lcm/dircon_saved_trajectory.h" -#include "lcm/lcm_trajectory.h" - -#include "drake/multibody/plant/multibody_plant.h" - -using drake::geometry::SceneGraph; -using drake::multibody::JacobianWrtVariable; -using drake::multibody::MultibodyPlant; -using drake::multibody::Parser; -using drake::systems::Context; -using drake::trajectories::PiecewisePolynomial; -using Eigen::Matrix3Xd; -using Eigen::MatrixXd; -using Eigen::Vector3d; -using Eigen::VectorXd; - -DEFINE_string(trajectory_name, "", - "File name where the optimal trajectory is stored."); -DEFINE_string(folder_path, "", - "Folder path for where the trajectory names are stored"); -DEFINE_bool(mirror_traj, false, - "Whether or not to extend the trajectory by mirroring"); - -namespace dairlib { - -/// This program pre-pelvisputes the output trajectories (center of mass, pelvis -/// orientation, feet trajectories) for the OSC controller. -/// - -int DoMain() { - // Drake system initialization - drake::systems::DiagramBuilder builder; - SceneGraph& scene_graph = *builder.AddSystem(); - scene_graph.set_name("scene_graph"); - MultibodyPlant plant(1e-5); // non-zero timestep to avoid continuous - // model warnings - Parser parser(&plant, &scene_graph); - parser.AddModelFromFile( - FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); - plant.mutable_gravity_field().set_gravity_vector(-9.81 * - Eigen::Vector3d::UnitZ()); - plant.Finalize(); - - std::unique_ptr> context = plant.CreateDefaultContext(); - - int nq = plant.num_positions(); - int nv = plant.num_velocities(); - int nx = plant.num_positions() + plant.num_velocities(); - - auto l_toe_frame = &plant.GetBodyByName("toe_left").body_frame(); - auto r_toe_frame = &plant.GetBodyByName("toe_right").body_frame(); - auto hip_left_frame = &plant.GetBodyByName("hip_left").body_frame(); - auto hip_right_frame = &plant.GetBodyByName("hip_right").body_frame(); - auto pelvis_frame = &plant.GetBodyByName("pelvis").body_frame(); - auto world = &plant.world_frame(); - - DirconTrajectory dircon_traj(plant, FLAGS_folder_path + FLAGS_trajectory_name); - PiecewisePolynomial state_traj = - dircon_traj.ReconstructStateTrajectory(); - - MatrixXd M = dircon_traj.GetTrajectory("mirror_matrix").datapoints; - - double end_time = state_traj.end_time(); - - std::vector all_l_foot_points; - std::vector all_r_foot_points; - std::vector all_l_hip_points; - std::vector all_r_hip_points; - std::vector all_pelvis_points; - std::vector all_pelvis_orientation; - std::vector all_times; - Vector3d zero_offset = Vector3d::Zero(); - - for (int mode = 0; mode < dircon_traj.GetNumModes(); ++mode) { - if (dircon_traj.GetStateBreaks(mode).size() <= 1) { - continue; - } - VectorXd times = dircon_traj.GetStateBreaks(mode); - MatrixXd state_samples = dircon_traj.GetStateSamples(mode); - - int n_points = times.size(); - MatrixXd l_foot_points(9, n_points); - MatrixXd r_foot_points(9, n_points); - MatrixXd l_hip_points(9, n_points); - MatrixXd r_hip_points(9, n_points); - MatrixXd pelvis_points(9, n_points); - MatrixXd pelvis_orientation(12, n_points); - - for (unsigned int i = 0; i < times.size(); ++i) { - VectorXd x_i = state_samples.col(i).head(nx); - VectorXd xdot_i = state_samples.col(i).tail(nx); - - plant.SetPositionsAndVelocities(context.get(), x_i); - Eigen::Ref pelvis_pos_block = - pelvis_points.block(0, i, 3, 1); - Eigen::Ref l_foot_pos_block = - l_foot_points.block(0, i, 3, 1); - Eigen::Ref r_foot_pos_block = - r_foot_points.block(0, i, 3, 1); - Eigen::Ref l_hip_pos_block = - l_hip_points.block(0, i, 3, 1); - Eigen::Ref r_hip_pos_block = - r_hip_points.block(0, i, 3, 1); - plant.CalcPointsPositions(*context, *pelvis_frame, zero_offset, *world, - &pelvis_pos_block); - plant.CalcPointsPositions(*context, *l_toe_frame, zero_offset, *world, - &l_foot_pos_block); - plant.CalcPointsPositions(*context, *r_toe_frame, zero_offset, *world, - &r_foot_pos_block); - plant.CalcPointsPositions(*context, *hip_left_frame, zero_offset, *world, - &l_hip_pos_block); - plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, *world, - &r_hip_pos_block); - - pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); - pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); - - MatrixXd J_CoM(3, nv); - MatrixXd J_l_foot(3, nv); - MatrixXd J_r_foot(3, nv); - MatrixXd J_l_hip(3, nv); - MatrixXd J_r_hip(3, nv); - - plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, - *pelvis_frame, zero_offset, - *world, *world, &J_CoM); - plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, - *l_toe_frame, zero_offset, *world, - *world, &J_l_foot); - plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, - *r_toe_frame, zero_offset, *world, - *world, &J_r_foot); - plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, - *hip_left_frame, zero_offset, - *world, *world, &J_l_hip); - plant.CalcJacobianTranslationalVelocity(*context, JacobianWrtVariable::kV, - *hip_right_frame, zero_offset, - *world, *world, &J_r_hip); - - VectorXd v_i = x_i.tail(nv); - pelvis_points.block(3, i, 3, 1) = J_CoM * v_i; - l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; - r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; - l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; - r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; - - VectorXd JdotV_CoM = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, *world, - *world); - VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, *world, - *world); - VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, *world, - *world); - VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, - *world, *world); - VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, - *world, *world); - - pelvis_points.block(6, i, 3, 1) = JdotV_CoM + J_CoM * xdot_i.tail(nv); - l_foot_points.block(6, i, 3, 1) = - JdotV_l_foot + J_l_foot * xdot_i.tail(nv); - r_foot_points.block(6, i, 3, 1) = - JdotV_r_foot + J_r_foot * xdot_i.tail(nv); - l_hip_points.block(6, i, 3, 1) = JdotV_l_hip + J_l_hip * xdot_i.tail(nv); - r_hip_points.block(6, i, 3, 1) = JdotV_r_hip + J_r_hip * xdot_i.tail(nv); - } - - all_times.push_back(times); - all_l_foot_points.push_back(l_foot_points); - all_r_foot_points.push_back(r_foot_points); - all_l_hip_points.push_back(l_hip_points); - all_r_hip_points.push_back(r_hip_points); - all_pelvis_points.push_back(pelvis_points); - all_pelvis_orientation.push_back(pelvis_orientation); - } - - if (FLAGS_mirror_traj) { - double x_offset = state_traj.value(state_traj.end_time())(4) - - state_traj.value(state_traj.start_time())(4); - // Extended trajectory - for (int mode = 0; mode < dircon_traj.GetNumModes(); ++mode) { - if (dircon_traj.GetStateBreaks(mode).size() <= 1) { - continue; - } - VectorXd times = - dircon_traj.GetStateBreaks(mode) + - end_time * VectorXd::Ones(dircon_traj.GetStateBreaks(mode).size()); - MatrixXd x_samples = M * dircon_traj.GetStateSamples(mode).topRows(nx); - MatrixXd xdot_samples = - M * dircon_traj.GetStateSamples(mode).bottomRows(nx); - - int n_points = times.size(); - MatrixXd l_foot_points(9, n_points); - MatrixXd r_foot_points(9, n_points); - MatrixXd l_hip_points(9, n_points); - MatrixXd r_hip_points(9, n_points); - MatrixXd pelvis_points(9, n_points); - MatrixXd pelvis_orientation(12, n_points); - - for (unsigned int i = 0; i < times.size(); ++i) { - // VectorXd x_i = M * state_samples.col(i).head(nx); - // VectorXd xdot_i = M * state_samples.col(i).tail(nx); - VectorXd x_i = x_samples.col(i); - VectorXd xdot_i = xdot_samples.col(i); - x_i(4) = x_i(4) + x_offset; - - plant.SetPositionsAndVelocities(context.get(), x_i); - Eigen::Ref pelvis_pos_block = - pelvis_points.block(0, i, 3, 1); - Eigen::Ref l_foot_pos_block = - l_foot_points.block(0, i, 3, 1); - Eigen::Ref r_foot_pos_block = - r_foot_points.block(0, i, 3, 1); - Eigen::Ref l_hip_pos_block = - l_hip_points.block(0, i, 3, 1); - Eigen::Ref r_hip_pos_block = - r_hip_points.block(0, i, 3, 1); - plant.CalcPointsPositions(*context, *pelvis_frame, zero_offset, *world, - &pelvis_pos_block); - plant.CalcPointsPositions(*context, *l_toe_frame, zero_offset, *world, - &l_foot_pos_block); - plant.CalcPointsPositions(*context, *r_toe_frame, zero_offset, *world, - &r_foot_pos_block); - plant.CalcPointsPositions(*context, *hip_left_frame, zero_offset, - *world, &l_hip_pos_block); - plant.CalcPointsPositions(*context, *hip_right_frame, zero_offset, - *world, &r_hip_pos_block); - - pelvis_orientation.block(0, i, 4, 1) = x_i.head(4); - pelvis_orientation.block(4, i, 4, 1) = xdot_i.head(4); - - MatrixXd J_CoM(3, nv); - MatrixXd J_l_foot(3, nv); - MatrixXd J_r_foot(3, nv); - MatrixXd J_l_hip(3, nv); - MatrixXd J_r_hip(3, nv); - plant.CalcJacobianTranslationalVelocity( - *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, - *world, *world, &J_CoM); - plant.CalcJacobianTranslationalVelocity( - *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, - *world, *world, &J_l_foot); - plant.CalcJacobianTranslationalVelocity( - *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, - *world, *world, &J_r_foot); - plant.CalcJacobianTranslationalVelocity( - *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, - *world, *world, &J_l_hip); - plant.CalcJacobianTranslationalVelocity( - *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, - *world, *world, &J_r_hip); - - VectorXd v_i = x_i.tail(nv); - pelvis_points.block(3, i, 3, 1) = J_CoM * v_i; - l_foot_points.block(3, i, 3, 1) = J_l_foot * v_i; - r_foot_points.block(3, i, 3, 1) = J_r_foot * v_i; - l_hip_points.block(3, i, 3, 1) = J_l_hip * v_i; - r_hip_points.block(3, i, 3, 1) = J_r_hip * v_i; - - VectorXd JdotV_CoM = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *pelvis_frame, zero_offset, - *world, *world); - VectorXd JdotV_l_foot = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *l_toe_frame, zero_offset, - *world, *world); - VectorXd JdotV_r_foot = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *r_toe_frame, zero_offset, - *world, *world); - VectorXd JdotV_l_hip = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *hip_left_frame, zero_offset, - *world, *world); - VectorXd JdotV_r_hip = plant.CalcBiasTranslationalAcceleration( - *context, JacobianWrtVariable::kV, *hip_right_frame, zero_offset, - *world, *world); - - pelvis_points.block(6, i, 3, 1) = JdotV_CoM + J_CoM * xdot_i.tail(nv); - l_foot_points.block(6, i, 3, 1) = - JdotV_l_foot + J_l_foot * xdot_i.tail(nv); - r_foot_points.block(6, i, 3, 1) = - JdotV_r_foot + J_r_foot * xdot_i.tail(nv); - l_hip_points.block(6, i, 3, 1) = - JdotV_l_hip + J_l_hip * xdot_i.tail(nv); - r_hip_points.block(6, i, 3, 1) = - JdotV_r_hip + J_r_hip * xdot_i.tail(nv); - } - - all_times.push_back(times); - all_l_foot_points.push_back(l_foot_points); - all_r_foot_points.push_back(r_foot_points); - all_l_hip_points.push_back(l_hip_points); - all_r_hip_points.push_back(r_hip_points); - all_pelvis_points.push_back(pelvis_points); - all_pelvis_orientation.push_back(pelvis_orientation); - } - } - - std::vector converted_trajectories; - std::vector trajectory_names; - - for (int mode = 0; mode < all_times.size(); ++mode) { - auto lfoot_traj_block = LcmTrajectory::Trajectory(); - lfoot_traj_block.traj_name = "left_foot_trajectory" + std::to_string(mode); - lfoot_traj_block.datapoints = all_l_foot_points[mode]; - lfoot_traj_block.time_vector = all_times[mode]; - lfoot_traj_block.datatypes = {"lfoot_x", "lfoot_y", "lfoot_z", - "lfoot_xdot", "lfoot_ydot", "lfoot_zdot", - "lfoot_xddot", "lfoot_yddot", "lfoot_zddot"}; - - auto rfoot_traj_block = LcmTrajectory::Trajectory(); - rfoot_traj_block.traj_name = "right_foot_trajectory" + std::to_string(mode); - rfoot_traj_block.datapoints = all_r_foot_points[mode]; - rfoot_traj_block.time_vector = all_times[mode]; - rfoot_traj_block.datatypes = {"rfoot_x", "rfoot_y", "rfoot_z", - "rfoot_xdot", "rfoot_ydot", "rfoot_zdot", - "rfoot_xddot", "rfoot_yddot", "rfoot_zddot"}; - - auto lhip_traj_block = LcmTrajectory::Trajectory(); - lhip_traj_block.traj_name = "left_hip_trajectory" + std::to_string(mode); - lhip_traj_block.datapoints = all_l_hip_points[mode]; - lhip_traj_block.time_vector = all_times[mode]; - lhip_traj_block.datatypes = {"lhip_x", "lhip_y", "lhip_z", - "lhip_xdot", "lhip_ydot", "lhip_zdot", - "lhip_xddot", "lhip_yddot", "lhip_zddot"}; - - auto rhip_traj_block = LcmTrajectory::Trajectory(); - rhip_traj_block.traj_name = "right_hip_trajectory" + std::to_string(mode); - rhip_traj_block.datapoints = all_r_hip_points[mode]; - rhip_traj_block.time_vector = all_times[mode]; - rhip_traj_block.datatypes = {"rhip_x", "rhip_y", "rhip_z", - "rhip_xdot", "rhip_ydot", "rhip_zdot", - "rhip_xddot", "rhip_yddot", "rhip_zddot"}; - - auto pelvis_traj_block = LcmTrajectory::Trajectory(); - pelvis_traj_block.traj_name = - "pelvis_trans_trajectory" + std::to_string(mode); - pelvis_traj_block.datapoints = all_pelvis_points[mode]; - pelvis_traj_block.time_vector = all_times[mode]; - pelvis_traj_block.datatypes = { - "pelvis_x", "pelvis_y", "pelvis_z", - "pelvis_xdot", "pelvis_ydot", "pelvis_zdot", - "pelvis_xddot", "pelvis_yddot", "pelvis_zddot"}; - - auto pelvis_orientation_block = LcmTrajectory::Trajectory(); - pelvis_orientation_block.traj_name = - "pelvis_rot_trajectory" + std::to_string(mode); - pelvis_orientation_block.datapoints = all_pelvis_orientation[mode]; - pelvis_orientation_block.time_vector = all_times[mode]; - pelvis_orientation_block.datatypes = { - "pelvis_rotw", "pelvis_rotx", "pelvis_roty", - "pelvis_rotz", "pelvis_rotwdot", "pelvis_rotxdot", - "pelvis_rotydot", "pelvis_rotzdot", "pelvis_rotwddot", - "pelvis_rotxddot", "pelvis_rotyddot", "pelvis_rotzddot"}; - - converted_trajectories.push_back(lfoot_traj_block); - converted_trajectories.push_back(rfoot_traj_block); - converted_trajectories.push_back(lhip_traj_block); - converted_trajectories.push_back(rhip_traj_block); - converted_trajectories.push_back(pelvis_traj_block); - converted_trajectories.push_back(pelvis_orientation_block); - trajectory_names.push_back(lfoot_traj_block.traj_name); - trajectory_names.push_back(rfoot_traj_block.traj_name); - trajectory_names.push_back(lhip_traj_block.traj_name); - trajectory_names.push_back(rhip_traj_block.traj_name); - trajectory_names.push_back(pelvis_traj_block.traj_name); - trajectory_names.push_back(pelvis_orientation_block.traj_name); - } - - auto processed_traj = LcmTrajectory(converted_trajectories, trajectory_names, - "walking_trajectory", - "Output trajectories " - "for Cassie walking"); - - processed_traj.WriteToFile(FLAGS_folder_path + FLAGS_trajectory_name + - "_processed_rel"); - return 0; -} - -} // namespace dairlib - -int main(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - dairlib::DoMain(); -} \ No newline at end of file diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 045d64e164..74cdec384b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -258,12 +258,12 @@ void FootTrajGenerator::CalcTraj( (PiecewisePolynomial*)dynamic_cast*>( traj); if (is_left_foot_) { - if (fsm_state != LEFT_STANCE) { + if (fsm_state != kLeftStance) { *casted_traj = GenerateFlightTraj(context); } } else { - if (fsm_state != RIGHT_STANCE) { + if (fsm_state != kRightStance) { *casted_traj = GenerateFlightTraj(context); } } diff --git a/examples/Cassie/osc_run/foot_traj_generator.h b/examples/Cassie/osc_run/foot_traj_generator.h index c255189ed3..1a156f33fe 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.h +++ b/examples/Cassie/osc_run/foot_traj_generator.h @@ -67,9 +67,6 @@ class FootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::Frame& foot_frame_; const drake::multibody::Frame& hip_frame_; - // Foot spline parameters -// std::vector state_durations_; - // Foot placement constants double rest_length_; double rest_length_offset_; @@ -91,11 +88,11 @@ class FootTrajGenerator : public drake::systems::LeafSystem { drake::systems::InputPortIndex radio_port_; drake::systems::InputPortIndex contact_scheduler_port_; - int initial_foot_pos_idx_; - int initial_hip_pos_idx_; - int pelvis_yaw_idx_; - int pelvis_vel_est_idx_; - int last_stance_timestamp_idx_; + drake::systems::DiscreteStateIndex initial_foot_pos_idx_; + drake::systems::DiscreteStateIndex initial_hip_pos_idx_; + drake::systems::DiscreteStateIndex pelvis_yaw_idx_; + drake::systems::DiscreteStateIndex pelvis_vel_est_idx_; + drake::systems::DiscreteStateIndex last_stance_timestamp_idx_; std::unique_ptr target_vel_filter_; diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc index 0049e6796a..9479471c7a 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.cc @@ -136,7 +136,7 @@ void PelvisTransTrajGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (fsm_state == LEFT_STANCE || fsm_state == RIGHT_STANCE) { + if (fsm_state == kLeftStance || fsm_state == kRightStance) { *casted_traj = GenerateSLIPTraj(robot_output->GetState(), mode_length[0], mode_length[1], fsm_state); } diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 4cb9e12758..c796092f06 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -112,10 +112,10 @@ int DoMain(int argc, char* argv[]) { int, std::vector&>>> feet_contact_points; - feet_contact_points[LEFT_STANCE] = std::vector< + feet_contact_points[kLeftStance] = std::vector< std::pair&>>( {left_toe, left_heel}); - feet_contact_points[RIGHT_STANCE] = std::vector< + feet_contact_points[kRightStance] = std::vector< std::pair&>>( {right_toe, right_heel}); @@ -136,9 +136,9 @@ int DoMain(int argc, char* argv[]) { /**** FSM and contact mode configuration ****/ vector fsm_states = { - RUNNING_FSM_STATE::LEFT_STANCE, RUNNING_FSM_STATE::LEFT_FLIGHT, - RUNNING_FSM_STATE::RIGHT_STANCE, RUNNING_FSM_STATE::RIGHT_FLIGHT, - RUNNING_FSM_STATE::LEFT_STANCE}; + RunningFsmState::kLeftStance, RunningFsmState::kLeftFlight, + RunningFsmState::kRightStance, RunningFsmState::kRightFlight, + RunningFsmState::kLeftStance}; vector state_durations = { osc_gains.stance_duration, osc_gains.flight_duration, @@ -151,8 +151,8 @@ int DoMain(int argc, char* argv[]) { } accumulated_state_durations.pop_back(); - std::set impact_states = {LEFT_STANCE, RIGHT_STANCE}; - auto contact_scheduler = builder.AddSystem( + std::set impact_states = {kLeftStance, kRightStance}; + auto contact_scheduler = builder.AddSystem( plant, plant_context.get(), impact_states, gains.impact_threshold, gains.impact_tau); contact_scheduler->SetSLIPParams(osc_gains.rest_length); @@ -222,13 +222,13 @@ int DoMain(int argc, char* argv[]) { plant, right_heel.first, right_heel.second, *pelvis_view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + osc->AddStateAndContactPoint(RunningFsmState::kLeftStance, &left_toe_evaluator); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::LEFT_STANCE, + osc->AddStateAndContactPoint(RunningFsmState::kLeftStance, &left_heel_evaluator); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + osc->AddStateAndContactPoint(RunningFsmState::kRightStance, &right_toe_evaluator); - osc->AddStateAndContactPoint(RUNNING_FSM_STATE::RIGHT_STANCE, + osc->AddStateAndContactPoint(RunningFsmState::kRightStance, &right_heel_evaluator); multibody::KinematicEvaluatorSet evaluators(plant); @@ -280,9 +280,9 @@ int DoMain(int argc, char* argv[]) { osc_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_left", "pelvis", LEFT_STANCE); + plant, plant_context.get(), "toe_left", "pelvis", kLeftStance); auto r_foot_traj_generator = builder.AddSystem( - plant, plant_context.get(), "toe_right", "pelvis", RIGHT_STANCE); + plant, plant_context.get(), "toe_right", "pelvis", kRightStance); l_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); r_foot_traj_generator->SetFootstepGains(osc_gains.K_d_footstep); l_foot_traj_generator->SetFootPlacementOffsets( @@ -308,27 +308,27 @@ int DoMain(int argc, char* argv[]) { auto right_foot_tracking_data = std::make_unique( "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); - pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::LEFT_STANCE, + pelvis_tracking_data->AddStateAndPointToTrack(RunningFsmState::kLeftStance, "pelvis"); - pelvis_tracking_data->AddStateAndPointToTrack(RUNNING_FSM_STATE::RIGHT_STANCE, + pelvis_tracking_data->AddStateAndPointToTrack(RunningFsmState::kRightStance, "pelvis"); stance_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_STANCE, "toe_left"); + RunningFsmState::kLeftStance, "toe_left"); stance_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_STANCE, "toe_right"); + RunningFsmState::kRightStance, "toe_right"); left_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left"); + RunningFsmState::kRightStance, "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_STANCE, "toe_right"); + RunningFsmState::kLeftStance, "toe_right"); left_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left"); + RunningFsmState::kRightFlight, "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right"); + RunningFsmState::kLeftFlight, "toe_right"); left_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + RunningFsmState::kLeftFlight, "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); + RunningFsmState::kRightFlight, "toe_right"); auto left_foot_yz_tracking_data = std::make_unique( @@ -339,9 +339,9 @@ int DoMain(int argc, char* argv[]) { "right_ft_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_foot_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left"); + RunningFsmState::kLeftFlight, "toe_left"); right_foot_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right"); + RunningFsmState::kRightFlight, "toe_right"); auto left_hip_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -350,18 +350,18 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + RunningFsmState::kRightStance, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + RunningFsmState::kLeftStance, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + RunningFsmState::kLeftFlight, "pelvis"); left_hip_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + RunningFsmState::kRightFlight, "pelvis"); left_hip_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + RunningFsmState::kLeftFlight, "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + RunningFsmState::kRightFlight, "pelvis"); auto left_hip_yz_tracking_data = std::make_unique( "left_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, @@ -371,9 +371,9 @@ int DoMain(int argc, char* argv[]) { "right_hip_traj", osc_gains.K_p_swing_foot, osc_gains.K_d_swing_foot, osc_gains.W_swing_foot, plant, plant); left_hip_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + RunningFsmState::kLeftFlight, "pelvis"); right_hip_yz_tracking_data->AddStateAndPointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + RunningFsmState::kRightFlight, "pelvis"); auto left_foot_rel_tracking_data = std::make_unique( @@ -422,13 +422,13 @@ int DoMain(int argc, char* argv[]) { "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant); pelvis_rot_tracking_data->AddStateAndFrameToTrack( - RUNNING_FSM_STATE::LEFT_STANCE, "pelvis"); + RunningFsmState::kLeftStance, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( - RUNNING_FSM_STATE::RIGHT_STANCE, "pelvis"); + RunningFsmState::kRightStance, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "pelvis"); + RunningFsmState::kRightFlight, "pelvis"); pelvis_rot_tracking_data->AddStateAndFrameToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "pelvis"); + RunningFsmState::kLeftFlight, "pelvis"); pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); if (osc_gains.rot_filter_tau > 0) { pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, @@ -455,17 +455,17 @@ int DoMain(int argc, char* argv[]) { "right_toe_angle_traj", osc_gains.K_p_swing_toe, osc_gains.K_d_swing_toe, osc_gains.W_swing_toe, plant, plant); left_toe_angle_tracking_data->AddStateAndJointToTrack( - RUNNING_FSM_STATE::RIGHT_STANCE, "toe_left", "toe_leftdot"); + RunningFsmState::kRightStance, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data->AddStateAndJointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_left", "toe_leftdot"); + RunningFsmState::kLeftFlight, "toe_left", "toe_leftdot"); left_toe_angle_tracking_data->AddStateAndJointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_left", "toe_leftdot"); + RunningFsmState::kRightFlight, "toe_left", "toe_leftdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - RUNNING_FSM_STATE::LEFT_STANCE, "toe_right", "toe_rightdot"); + RunningFsmState::kLeftStance, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - RUNNING_FSM_STATE::LEFT_FLIGHT, "toe_right", "toe_rightdot"); + RunningFsmState::kLeftFlight, "toe_right", "toe_rightdot"); right_toe_angle_tracking_data->AddStateAndJointToTrack( - RUNNING_FSM_STATE::RIGHT_FLIGHT, "toe_right", "toe_rightdot"); + RunningFsmState::kRightFlight, "toe_right", "toe_rightdot"); // Swing hip yaw joint tracking auto left_hip_yaw_tracking_data = std::make_unique( diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc index e3bdfdf18b..1cd90b0b09 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.cc +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.cc @@ -79,7 +79,7 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( double remainder = fmod(current_time, period_); // Assign the blending function ptr - auto alpha_func = blend_func_ == SIGMOID ? &blend_sigmoid : &blend_exp; + auto alpha_func = blend_func_ == kSigmoid ? &blend_sigmoid : &blend_exp; near_impact->set_timestamp(current_time); near_impact->SetCurrentContactMode(0); @@ -87,7 +87,7 @@ void ImpactTimeBasedFiniteStateMachine::CalcNearImpact( // Get current finite state if (current_time >= t0_) { for (int i = 0; i < impact_states_.size(); ++i) { - double blend_window = blend_func_ == SIGMOID + double blend_window = blend_func_ == kSigmoid ? 1.5 * near_impact_threshold_ : near_impact_threshold_; if (abs(remainder - impact_times_[i]) < blend_window) { diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index 3e6f88f107..579bfd6a97 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -20,7 +20,7 @@ class ImpactTimeBasedFiniteStateMachine const drake::multibody::MultibodyPlant& plant, const std::vector& states, const std::vector& state_durations, double t0 = 0, - double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = SIGMOID); + double near_impact_threshold = 0, double tau = 0.0025, BLEND_FUNC blend_func = kSigmoid); const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index e982888c04..9f9023f5ab 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -58,7 +58,7 @@ void OptionsTrackingData::UpdateFilters(double t) { } else if (t != last_timestamp_) { double dt = t - last_timestamp_; double alpha = dt / (dt + tau_); - if (n_y_ == 4) { // quaternion + if (this->is_rotational_tracking_data_) { // quaternion auto slerp = drake::trajectories::PiecewiseQuaternionSlerp( {0, 1}, {Quaterniond(y_[0], y_[1], y_[2], y_[3]), Quaterniond(filtered_y_[0], filtered_y_[1], filtered_y_[2], diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index d5a065d6fb..2be090883e 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -68,7 +68,9 @@ void RotTaskSpaceTrackingData::UpdateYError() { double theta = 2 * acos(relative_quat.w()); Vector3d rot_axis = relative_quat.vec().normalized(); error_y_ = theta * rot_axis; - if (with_view_frame_) error_y_ = view_frame_rot_T_ * error_y_; + if (with_view_frame_) { + error_y_ = view_frame_rot_T_ * error_y_; + } } void RotTaskSpaceTrackingData::UpdateYdot( From 4f4a6c5181c432239bcf847e7214cb184ed02142 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Mar 2023 11:58:30 -0400 Subject: [PATCH 397/758] adding franka_sim --- examples/franka/BUILD.bazel | 56 ++ examples/franka/franka_sim.cc | 138 +++++ examples/franka/franka_sim_params.h | 22 + examples/franka/franka_sim_params.yaml | 3 + examples/franka/franka_visualizer.cc | 117 ++++ examples/franka/urdf/franka_box.urdf | 709 +++++++++++++++++++++++++ systems/framework/lcm_driven_loop.h | 1 + 7 files changed, 1046 insertions(+) create mode 100644 examples/franka/BUILD.bazel create mode 100644 examples/franka/franka_sim.cc create mode 100644 examples/franka/franka_sim_params.h create mode 100644 examples/franka/franka_sim_params.yaml create mode 100644 examples/franka/franka_visualizer.cc create mode 100644 examples/franka/urdf/franka_box.urdf diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel new file mode 100644 index 0000000000..dd5ce70310 --- /dev/null +++ b/examples/franka/BUILD.bazel @@ -0,0 +1,56 @@ +# -*- mode: python -*- +# vi: set ft=python : + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "trifinger_urdf", + data = glob([ + "robot_properties_fingers/urdf/**", + "robot_properties_fingers/urdf/pro/**", + "robot_properties_fingers/urdf/edu/**", + "robot_properties_fingers/meshes/**", + "robot_properties_fingers/meshes/pro/**", + "robot_properties_fingers/meshes/pro/detailed/**", + "robot_properties_fingers/meshes/edu/**", + "robot_properties_fingers/cube/**"]) +) + +cc_binary( + name = "franka_sim", + srcs = ["franka_sim.cc"], + deps = [ + ":franka_sim_params", + "//systems:robot_lcm_systems", + "//systems/controllers", + "//systems/framework:lcm_driven_loop", + "//systems:system_utils", + "@drake//:drake_shared_library", + ], + data = [":trifinger_urdf", + "@drake//manipulation/models/franka_description:models"] +) + +cc_binary( + name = "franka_visualizer", + srcs = ["franka_visualizer.cc"], + deps = [ + "//multibody:utils", + "//multibody:visualization_utils", + "//systems:robot_lcm_systems", + "//systems/primitives", + "//systems:system_utils", + "@drake//:drake_shared_library", + "@gflags", + ], + data = [":trifinger_urdf", + "@drake//manipulation/models/franka_description:models"] +) + +cc_library( + name = "franka_sim_params", + hdrs = ["franka_sim_params.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc new file mode 100644 index 0000000000..6f6a3dcd78 --- /dev/null +++ b/examples/franka/franka_sim.cc @@ -0,0 +1,138 @@ +#include +#include + +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" + +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include +#include +#include +#include +#include +#include +#include "drake/common/yaml/yaml_io.h" +#include +#include + +#include "systems/robot_lcm_systems.h" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/franka/franka_sim_params.h" +#include "multibody/multibody_utils.h" +#include "systems/system_utils.h" + +#include "systems/robot_lcm_systems.h" +#include "systems/framework/lcm_driven_loop.h" + +namespace dairlib { + +using drake::geometry::SceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::math::RigidTransform; +using drake::systems::DiagramBuilder; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::systems::Context; +using drake::multibody::Parser; +using drake::trajectories::PiecewisePolynomial; +using drake::systems::VectorLogSink; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using systems::AddActuationRecieverAndStateSenderLcm; + +using Eigen::VectorXd; +using Eigen::MatrixXd; + +int DoMain(int argc, char* argv[]){ + // load parameters + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/franka_sim_params.yaml"); + + // load urdf and sphere + DiagramBuilder builder; + double sim_dt = sim_params.dt; + double output_dt = sim_params.dt; + auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); + + Parser parser(&plant); + parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + + RigidTransform X_WI = RigidTransform::Identity(); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); + plant.Finalize(); + + /* -------------------------------------------------------------------------------------------*/ + + drake::lcm::DrakeLcm drake_lcm; + auto lcm = builder.AddSystem(&drake_lcm); + + auto passthrough = AddActuationRecieverAndStateSenderLcm( + &builder, plant, lcm, "FRANKA_INPUT", "FRANKA_OUTPUT", + 1/output_dt, true, 0.0); + + /// meshcat visualizer +// drake::geometry::DrakeVisualizer::AddToBuilder(&builder, scene_graph); +// drake::geometry::MeshcatVisualizerParams params; +// params.publish_period = 1.0/30.0; +// auto meshcat = std::make_shared(); +// auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( +// &builder, scene_graph, meshcat, std::move(params)); + + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + int nu = plant.num_actuators(); + auto logger = builder.AddSystem>(nq+nv+nu, output_dt); + + // multiplex state and input for logger + std::vector input_sizes = {nq+nv, nu}; + auto mux = builder.AddSystem>(input_sizes); + + builder.Connect(plant.get_state_output_port(), mux->get_input_port(0)); + builder.Connect(passthrough->get_output_port(), mux->get_input_port(1)); + builder.Connect(mux->get_output_port(0), logger->get_input_port(0)); + + auto diagram = builder.Build(); + + drake::systems::Simulator simulator(*diagram); + + simulator.set_publish_every_time_step(false); + simulator.set_publish_at_initialization(false); + simulator.set_target_realtime_rate(sim_params.realtime_rate); + + auto& plant_context = diagram->GetMutableSubsystemContext( + plant, &simulator.get_mutable_context()); + + VectorXd q = VectorXd::Zero(nq); + std::map q_map = MakeNameToPositionsMap(plant); + + // initialize EE close to {0.5, 0, 0.12}[m] in task space + q[q_map["panda_joint3"]] = sim_params.q_init_franka[2]; + q[q_map["panda_joint4"]] = sim_params.q_init_franka[3]; + q[q_map["panda_joint5"]] = sim_params.q_init_franka[4]; + q[q_map["panda_joint6"]] = sim_params.q_init_franka[5]; + q[q_map["panda_joint2"]] = sim_params.q_init_franka[1]; + q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; + q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; + + plant.SetPositions(&plant_context, q); + + VectorXd v = VectorXd::Zero(nv); + plant.SetVelocities(&plant_context, v); + + simulator.Initialize(); + simulator.AdvanceTo(std::numeric_limits::infinity()); + + // do data logging here + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv);} diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h new file mode 100644 index 0000000000..0104072e00 --- /dev/null +++ b/examples/franka/franka_sim_params.h @@ -0,0 +1,22 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct FrankaSimParams { + + double dt; + double realtime_rate; + std::vector q_init_franka; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(dt)); + a->Visit(DRAKE_NVP(realtime_rate)); + a->Visit(DRAKE_NVP(q_init_franka)); + + } +}; \ No newline at end of file diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml new file mode 100644 index 0000000000..de1cd35cdf --- /dev/null +++ b/examples/franka/franka_sim_params.yaml @@ -0,0 +1,3 @@ +dt: 0.0001 +realtime_rate: 1.0 +q_init_franka: [0, 0.275, 0, -2.222, 0, 2.497, 0] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc new file mode 100644 index 0000000000..0fdd0d32af --- /dev/null +++ b/examples/franka/franka_visualizer.cc @@ -0,0 +1,117 @@ +#include + +#include "dairlib/lcmt_robot_output.hpp" +#include "multibody/com_pose_system.h" +#include "multibody/multibody_utils.h" +#include "multibody/visualization_utils.h" +#include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" + +#include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "drake/systems/rendering/multibody_position_to_geometry_pose.h" +#include +#include "systems/system_utils.h" +#include "drake/common/yaml/yaml_io.h" + +DEFINE_string(channel, "FRANKA_OUTPUT", + "LCM channel for receiving state. " + "Use FRANKA_OUTPUT to get state from simulator, and " + "use FRANKA_ROS_OUTPUT to get state from state estimator"); + +namespace dairlib { + +using dairlib::systems::RobotOutputReceiver; +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::DrakeVisualizer; +using drake::geometry::SceneGraph; +using drake::geometry::Sphere; +using drake::math::RigidTransformd; +using drake::multibody::MultibodyPlant; +using drake::multibody::RigidBody; +using drake::multibody::SpatialInertia; +using drake::multibody::UnitInertia; +using drake::systems::Simulator; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::systems::rendering::MultibodyPositionToGeometryPose; + +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::Parser; +using drake::math::RigidTransform; +using drake::systems::DiagramBuilder; + +int do_main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + drake::systems::DiagramBuilder builder; + + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + + MultibodyPlant plant(0.0); + + Parser parser(&plant, &scene_graph); + parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + RigidTransform X_WI = RigidTransform::Identity(); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); + + plant.Finalize(); + + auto lcm = builder.AddSystem(); + + // Create state receiver. + auto state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + FLAGS_channel, lcm)); + auto state_receiver = builder.AddSystem(plant); + builder.Connect(*state_sub, *state_receiver); + + auto passthrough = builder.AddSystem( + state_receiver->get_output_port(0).size(), 0, plant.num_positions()); + builder.Connect(*state_receiver, *passthrough); + + auto to_pose = + builder.AddSystem>(plant); + builder.Connect(*passthrough, *to_pose); + builder.Connect( + to_pose->get_output_port(), + scene_graph.get_source_pose_port(plant.get_source_id().value())); + + DrakeVisualizer::AddToBuilder(&builder, scene_graph); + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0/60.0; + auto meshcat = std::make_shared(); + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, scene_graph, meshcat, std::move(params)); + + // state_receiver->set_publish_period(1.0/30.0); // framerate + + auto diagram = builder.Build(); + + auto context = diagram->CreateDefaultContext(); + + /// Use the simulator to drive at a fixed rate + /// If set_publish_every_time_step is true, this publishes twice + /// Set realtime rate. Otherwise, runs as fast as possible + auto stepper = + std::make_unique>(*diagram, std::move(context)); + stepper->set_publish_every_time_step(false); + stepper->set_publish_at_initialization(false); + stepper->set_target_realtime_rate(1.0); // may need to change this to param.real_time_rate? + stepper->Initialize(); + + drake::log()->info("visualizer started"); + + stepper->AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/franka/urdf/franka_box.urdf b/examples/franka/urdf/franka_box.urdf new file mode 100644 index 0000000000..68b2c0cb30 --- /dev/null +++ b/examples/franka/urdf/franka_box.urdf @@ -0,0 +1,709 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + , + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index 6241d83426..19d29a2ed0 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -3,6 +3,7 @@ #include #include #include +#include #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" From 49e3eb71865583c3eb2c4f90118e8124b7bbab6e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Mar 2023 12:58:24 -0400 Subject: [PATCH 398/758] adding documentation to contact scheduler and cleaning up state estimator constants --- examples/Cassie/BUILD.bazel | 9 +++++++ examples/Cassie/cassie_state_estimator.cc | 10 ++++---- examples/Cassie/cassie_state_estimator.h | 19 +++++++++++---- .../Cassie/cassie_state_estimator_settings.h | 20 ++++++++++++++++ .../contact_scheduler/contact_scheduler.cc | 12 +++++----- .../contact_scheduler/contact_scheduler.h | 24 ++++++++++++++++++- .../default_state_estimator_settings.yaml | 3 +++ examples/Cassie/dispatcher_robot_out.cc | 12 +++++++--- .../running_state_estimator_settings.yaml | 2 ++ 9 files changed, 91 insertions(+), 20 deletions(-) create mode 100644 examples/Cassie/cassie_state_estimator_settings.h create mode 100644 examples/Cassie/default_state_estimator_settings.yaml create mode 100644 examples/Cassie/osc_run/running_state_estimator_settings.yaml diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 0e0bcdd211..78238e9915 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -61,6 +61,14 @@ cc_library( data = glob(["urdf/**"]), ) +cc_library( + name = "cassie_state_estimator_settings", + hdrs = ["cassie_state_estimator_settings.h"], + deps = [ + "@drake//:drake_shared_library", + ] +) + cc_library( name = "cassie_state_estimator", srcs = ["cassie_state_estimator.cc"], @@ -69,6 +77,7 @@ cc_library( ":cassie_utils", "//examples/Cassie/datatypes:cassie_names", "//examples/Cassie/datatypes:cassie_out_t", + "//examples/Cassie:cassie_state_estimator_settings", "//multibody:utils", "//multibody/kinematic", "//systems/framework:vector", diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 9d55c02176..58914d3188 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -511,9 +511,9 @@ void CassieStateEstimator::EstimateContactForEkf( const double& right_heel_spring = output.GetPositionAtIndex( position_idx_map_.at("ankle_spring_joint_right")); bool left_contact_spring = (left_knee_spring < knee_spring_threshold_ekf_ && - left_heel_spring < heel_spring_threshold_ekf_); + left_heel_spring < ankle_spring_threshold_ekf_); bool right_contact_spring = (right_knee_spring < knee_spring_threshold_ekf_ && - right_heel_spring < heel_spring_threshold_ekf_); + right_heel_spring < ankle_spring_threshold_ekf_); // Determine contacts based on both spring deflation and QP cost if (left_contact_spring) { @@ -527,7 +527,7 @@ void CassieStateEstimator::EstimateContactForEkf( cout << "left/right knee spring, threshold = " << left_knee_spring << ", " << right_knee_spring << ", " << knee_spring_threshold_ekf_ << endl; cout << "left/right heel spring, threshold = " << left_heel_spring << ", " - << right_heel_spring << ", " << heel_spring_threshold_ekf_ << endl; + << right_heel_spring << ", " << ankle_spring_threshold_ekf_ << endl; cout << "left/right contacts = " << *left_contact << ", " << *right_contact << endl; } @@ -574,10 +574,10 @@ void CassieStateEstimator::EstimateContactForController( const double& right_heel_spring = output.GetPositionAtIndex( position_idx_map_.at("ankle_spring_joint_right")); bool left_contact_spring = (left_knee_spring < knee_spring_threshold_ctrl_ || - left_heel_spring < heel_spring_threshold_ctrl_); + left_heel_spring < ankle_spring_threshold_ctrl_); bool right_contact_spring = (right_knee_spring < knee_spring_threshold_ctrl_ || - right_heel_spring < heel_spring_threshold_ctrl_); + right_heel_spring < ankle_spring_threshold_ctrl_); // Determine contacts based on both spring deflation and QP cost if (left_contact_spring) { diff --git a/examples/Cassie/cassie_state_estimator.h b/examples/Cassie/cassie_state_estimator.h index d0be8f4403..1aa90f5c99 100644 --- a/examples/Cassie/cassie_state_estimator.h +++ b/examples/Cassie/cassie_state_estimator.h @@ -107,6 +107,15 @@ class CassieStateEstimator : public drake::systems::LeafSystem { Eigen::Vector3d pelvis_vel = Eigen::Vector3d::Zero()) const; void setPreviousImuMeasurement(drake::systems::Context* context, const Eigen::VectorXd& imu_value) const; + void SetSpringDeflectionThresholds(double knee_spring_threshold, double ankle_spring_threshold) { + knee_spring_threshold_ctrl_ = knee_spring_threshold; + knee_spring_threshold_ekf_ = knee_spring_threshold; + ankle_spring_threshold_ctrl_ = ankle_spring_threshold; + ankle_spring_threshold_ekf_ = ankle_spring_threshold; + } + void SetContactForceThreshold(double force_threshold) { + contact_force_threshold_ = force_threshold; + } // Copy joint state from cassie_out_t to an OutputVector void AssignNonFloatingBaseStateToOutputVector(const cassie_out_t& cassie_out, @@ -217,12 +226,12 @@ class CassieStateEstimator : public drake::systems::LeafSystem { // Heel ~??? // https://drive.google.com/file/d/1o7QS4ZksU91EBIpwtNnKpunob93BKiX_ // https://drive.google.com/file/d/1mlDzi0fa-YHopeRHaa-z88fPGuI2Aziv - const double knee_spring_threshold_ctrl_ = -0.020; - const double knee_spring_threshold_ekf_ = -0.020; - const double heel_spring_threshold_ctrl_ = -0.02; - const double heel_spring_threshold_ekf_ = -0.02; + double knee_spring_threshold_ctrl_ = -0.015; + double knee_spring_threshold_ekf_ = -0.015; + double ankle_spring_threshold_ctrl_ = -0.01; + double ankle_spring_threshold_ekf_ = -0.01; const double w_soft_constraint_ = 100; // Soft constraint cost - const double contact_force_threshold_; // Soft constraint cost + double contact_force_threshold_ = 60; // Soft constraint cost // flag for testing and tuning std::unique_ptr> context_gt_; diff --git a/examples/Cassie/cassie_state_estimator_settings.h b/examples/Cassie/cassie_state_estimator_settings.h new file mode 100644 index 0000000000..13dcc9e5e9 --- /dev/null +++ b/examples/Cassie/cassie_state_estimator_settings.h @@ -0,0 +1,20 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + + +struct CassieStateEstimatorSettings{ + + double knee_spring_threshold; + double ankle_spring_threshold; + double contact_force_threshold; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(knee_spring_threshold)); + a->Visit(DRAKE_NVP(ankle_spring_threshold)); + a->Visit(DRAKE_NVP(contact_force_threshold)); + } +}; \ No newline at end of file diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.cc b/examples/Cassie/contact_scheduler/contact_scheduler.cc index 185ece376b..8009479dd6 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.cc +++ b/examples/Cassie/contact_scheduler/contact_scheduler.cc @@ -46,22 +46,25 @@ SLIPContactScheduler::SLIPContactScheduler(const MultibodyPlant& plant, plant.num_velocities(), plant.num_actuators())) .get_index(); - fsm_port_ = this->DeclareVectorOutputPort("fsm", BasicVector(1), + fsm_port_ = this->DeclareVectorOutputPort("fsm", 1, &SLIPContactScheduler::CalcFiniteState) .get_index(); impact_info_port_ = this->DeclareVectorOutputPort( "near_impact", ImpactInfoVector(0, 0, 0), &SLIPContactScheduler::CalcNextImpactInfo) .get_index(); - clock_port_ = this->DeclareVectorOutputPort("clock", BasicVector(1), + clock_port_ = this->DeclareVectorOutputPort("clock", 1, &SLIPContactScheduler::CalcClock) .get_index(); contact_scheduler_port_ = this->DeclareVectorOutputPort( "contact_scheduler (pelvis_t0, pelvis_tf, left_t0, left_tf, " "right_t0, right_t0", - BasicVector(6), &SLIPContactScheduler::CalcContactScheduler) + 6, &SLIPContactScheduler::CalcContactScheduler) .get_index(); + debug_port_ = this->DeclareAbstractOutputPort( + "status", &SLIPContactScheduler::OutputDebuggingInfo) + .get_index(); // Declare discrete states and update stored_fsm_state_index_ = DeclareDiscreteState(3 * VectorXd::Ones(1)); @@ -85,9 +88,6 @@ SLIPContactScheduler::SLIPContactScheduler(const MultibodyPlant& plant, upcoming_transitions_index_ = DeclareAbstractState( drake::Value>>{ initial_state_transitions}); - debug_port_ = this->DeclareAbstractOutputPort( - "status", &SLIPContactScheduler::OutputDebuggingInfo) - .get_index(); DeclarePerStepUnrestrictedUpdateEvent( &SLIPContactScheduler::UpdateTransitionTimes); diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index 9b10c7e08c..d02637b05a 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -17,6 +17,27 @@ namespace dairlib { enum RunningFsmState { kLeftStance, kRightStance, kLeftFlight, kRightFlight }; +/** + * Variable timing finite state machine that predicts the liftoff and touchdown + * timing assuming that the leg length is undeflected at touchdown and liftoff. + * This system is also responsible for outputting the upcoming contact mode as + * well as the blending function that is necessary for impact-invariant control + * + * + * + * @system + * name: SLIPContactScheduler + * input_ports: + * - state_port: robot_state + * output_ports: + * - fsm_port: current contact mode (RunningFsmState) + * - clock_port: current clock (phase variable) + * - impact_info_port: upcoming contact/impact event (ImpactInfoVector) + * - contact_scheduler_port: upcoming start and end times for pelvis and foot (BasicVector) + * trajectories + * - debug_port: lcm output for predicted contact mode switches + * (lcmt_contact_timing) + */ class SLIPContactScheduler : public drake::systems::LeafSystem { public: SLIPContactScheduler(const drake::multibody::MultibodyPlant& plant, @@ -30,7 +51,8 @@ class SLIPContactScheduler : public drake::systems::LeafSystem { stance_duration_ = stance_duration; flight_duration_ = flight_duration; } - void SetMaxStepTimingVariance(double stance_variance, double flight_variance) { + void SetMaxStepTimingVariance(double stance_variance, + double flight_variance) { stance_variance_ = stance_variance; flight_variance_ = flight_variance; } diff --git a/examples/Cassie/default_state_estimator_settings.yaml b/examples/Cassie/default_state_estimator_settings.yaml new file mode 100644 index 0000000000..4cc291a1e8 --- /dev/null +++ b/examples/Cassie/default_state_estimator_settings.yaml @@ -0,0 +1,3 @@ +knee_spring_threshold: -0.015 +ankle_spring_threshold: -0.01 +contact_force_threshold: 60 \ No newline at end of file diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index ba3bc860a6..cad8044ebc 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -29,6 +29,7 @@ #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" +#include "examples/Cassie/cassie_state_estimator_settings.h" namespace dairlib { @@ -62,9 +63,8 @@ DEFINE_string(state_channel_name, "CASSIE_STATE_SIMULATION", // Cassie model paramter DEFINE_bool(floating_base, true, "Fixed or floating base model"); -DEFINE_double(contact_force_threshold, 60, - "Contact force threshold. Set to 140 for walking"); DEFINE_string(joint_offset_yaml, "", "yaml with joint offset values"); +DEFINE_string(contact_detection_yaml, "examples/Cassie/default_state_estimator_settings.yaml", "Yaml with contact estimation values"); // Testing mode DEFINE_int64(test_mode, -1, @@ -211,12 +211,18 @@ int do_main(int argc, char* argv[]) { drake::yaml::LoadYamlFile>( FindResourceOrThrow(FLAGS_joint_offset_yaml)); + CassieStateEstimatorSettings settings = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_contact_detection_yaml)); + auto state_estimator = builder.AddSystem( plant, &fourbar_evaluator, &left_contact_evaluator, &right_contact_evaluator, joint_offset_map, FLAGS_test_with_ground_truth_state, FLAGS_print_ekf_info, - FLAGS_test_mode, FLAGS_contact_force_threshold); + FLAGS_test_mode); + state_estimator->SetSpringDeflectionThresholds(settings.knee_spring_threshold, + settings.ankle_spring_threshold); + state_estimator->SetContactForceThreshold(settings.contact_force_threshold); // Create and connect CassieOutputSender publisher (low-rate for the network) // This echoes the messages from the robot auto output_sender = builder.AddSystem(); diff --git a/examples/Cassie/osc_run/running_state_estimator_settings.yaml b/examples/Cassie/osc_run/running_state_estimator_settings.yaml new file mode 100644 index 0000000000..2e36ce4338 --- /dev/null +++ b/examples/Cassie/osc_run/running_state_estimator_settings.yaml @@ -0,0 +1,2 @@ +knee_spring_threshold: 0.02 +ankle_spring_threshold: 0.02 \ No newline at end of file From 3a99724dd4f388b85af9e4bdf2dcf51cbf212f00 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Mar 2023 16:51:30 -0400 Subject: [PATCH 399/758] adding franka controller --- examples/franka/BUILD.bazel | 24 ++++ examples/franka/franka_controller_params.h | 40 +++++++ examples/franka/franka_controller_params.yaml | 15 +++ examples/franka/franka_osc_controller.cc | 111 ++++++++++++++++++ examples/franka/franka_sim.cc | 80 +++++-------- examples/franka/franka_sim_params.h | 11 ++ examples/franka/franka_sim_params.yaml | 6 + 7 files changed, 237 insertions(+), 50 deletions(-) create mode 100644 examples/franka/franka_controller_params.h create mode 100644 examples/franka/franka_controller_params.yaml create mode 100644 examples/franka/franka_osc_controller.cc diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index dd5ce70310..0c2d4c64b7 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -31,6 +31,23 @@ cc_binary( "@drake//manipulation/models/franka_description:models"] ) +cc_binary( + name = "franka_osc_controller", + srcs = ["franka_osc_controller.cc"], + deps = [ + ":franka_controller_params", + "//systems:robot_lcm_systems", + "//systems/controllers", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems:system_utils", + "@drake//:drake_shared_library", + "@gflags", + ], + data = [":trifinger_urdf", + "@drake//manipulation/models/franka_description:models"] +) + cc_binary( name = "franka_visualizer", srcs = ["franka_visualizer.cc"], @@ -53,4 +70,11 @@ cc_library( deps = [ "@drake//:drake_shared_library", ], +) +cc_library( + name = "franka_controller_params", + hdrs = ["franka_controller_params.h"], + deps = [ + "@drake//:drake_shared_library", + ], ) \ No newline at end of file diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h new file mode 100644 index 0000000000..2c33847889 --- /dev/null +++ b/examples/franka/franka_controller_params.h @@ -0,0 +1,40 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct FrankaControllerParams { + + std::string state_channel; + std::string controller_channel; + + std::vector EndEffectorW; + std::vector EndEffectorKp; + std::vector EndEffectorKd; + + MatrixXd W_end_effector; + MatrixXd K_p_end_effector; + MatrixXd K_d_end_effector; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(state_channel)); + a->Visit(DRAKE_NVP(controller_channel)); + a->Visit(DRAKE_NVP(EndEffectorW)); + a->Visit(DRAKE_NVP(EndEffectorKp)); + a->Visit(DRAKE_NVP(EndEffectorKd)); + + W_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorW.data(), 3, 3); + K_p_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorKp.data(), 3, 3); + K_d_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorKd.data(), 3, 3); + } +}; \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml new file mode 100644 index 0000000000..d20c502eef --- /dev/null +++ b/examples/franka/franka_controller_params.yaml @@ -0,0 +1,15 @@ +state_channel: FRANKA_OUTPUT +controller_channel: FRANKA_INPUT + +EndEffectorW: + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] +EndEffectorKp: + [ 100, 0, 0, + 0, 100, 0, + 0, 0, 100 ] +EndEffectorKd: + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1 ] diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc new file mode 100644 index 0000000000..5c1a3087fa --- /dev/null +++ b/examples/franka/franka_osc_controller.cc @@ -0,0 +1,111 @@ + +#include + +#include "examples/franka/franka_controller_params.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/common/yaml/yaml_io.h" +#include "drake/multibody/parsing/parser.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" + +namespace dairlib { + +using drake::math::RigidTransform; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; + +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +DEFINE_string(controller_settings, "", + "Controller settings such as channels. Attempting to minimize " + "number of gflags"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // load parameters + FrankaControllerParams controller_params = + drake::yaml::LoadYamlFile( + "examples/franka/franka_controller_params.yaml"); + + DiagramBuilder builder; + + drake::multibody::MultibodyPlant plant(0.0); + Parser parser(&plant, nullptr); + parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + RigidTransform X_WI = RigidTransform::Identity(); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + X_WI); + plant.Finalize(); + auto plant_context = plant.CreateDefaultContext(); + + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto state_receiver = builder.AddSystem(plant); + auto command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + controller_params.controller_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto command_sender = builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), false); + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + "OSC_DEBUG_FRANKA", &lcm, TriggerTypeSet({TriggerType::kForced}))); + + auto end_effector_pose_tracking_data = + std::make_unique( + "end_effector_target", controller_params.K_p_end_effector, + controller_params.K_d_end_effector, controller_params.W_end_effector, + plant, plant); + osc->AddConstTrackingData(std::move(end_effector_pose_tracking_data), + Eigen::Vector3d::Ones()); + osc->SetContactFriction(0.4); + osc->Build(); + + builder.Connect(command_sender->get_output_port(0), + command_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_command(), + command_sender->get_input_port(0)); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); + builder.Connect(state_receiver->get_output_port(0), + osc->get_input_port_robot_output()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_controller")); + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, + controller_params.state_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 6f6a3dcd78..dad1bfc8cf 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -1,55 +1,52 @@ -#include #include -#include "drake/geometry/meshcat_visualizer.h" -#include "drake/geometry/meshcat_visualizer_params.h" +#include -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" -#include -#include -#include -#include #include +#include #include -#include "drake/common/yaml/yaml_io.h" -#include +#include #include +#include -#include "systems/robot_lcm_systems.h" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/franka/franka_sim_params.h" #include "multibody/multibody_utils.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "systems/robot_lcm_systems.h" -#include "systems/framework/lcm_driven_loop.h" +#include "drake/common/yaml/yaml_io.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" namespace dairlib { +using dairlib::systems::SubvectorPassThrough; using drake::geometry::SceneGraph; -using drake::multibody::MultibodyPlant; -using drake::multibody::AddMultibodyPlantSceneGraph; using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::Context; using drake::systems::DiagramBuilder; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::Context; -using drake::multibody::Parser; using drake::trajectories::PiecewisePolynomial; -using drake::systems::VectorLogSink; using multibody::MakeNameToPositionsMap; using multibody::MakeNameToVelocitiesMap; using systems::AddActuationRecieverAndStateSenderLcm; -using Eigen::VectorXd; using Eigen::MatrixXd; +using Eigen::VectorXd; -int DoMain(int argc, char* argv[]){ +int DoMain(int argc, char* argv[]) { // load parameters FrankaSimParams sim_params = drake::yaml::LoadYamlFile( "examples/franka/franka_sim_params.yaml"); @@ -64,38 +61,23 @@ int DoMain(int argc, char* argv[]){ parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); RigidTransform X_WI = RigidTransform::Identity(); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + X_WI); plant.Finalize(); /* -------------------------------------------------------------------------------------------*/ drake::lcm::DrakeLcm drake_lcm; - auto lcm = builder.AddSystem(&drake_lcm); - + auto lcm = + builder.AddSystem(&drake_lcm); auto passthrough = AddActuationRecieverAndStateSenderLcm( - &builder, plant, lcm, "FRANKA_INPUT", "FRANKA_OUTPUT", - 1/output_dt, true, 0.0); - - /// meshcat visualizer -// drake::geometry::DrakeVisualizer::AddToBuilder(&builder, scene_graph); -// drake::geometry::MeshcatVisualizerParams params; -// params.publish_period = 1.0/30.0; -// auto meshcat = std::make_shared(); -// auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( -// &builder, scene_graph, meshcat, std::move(params)); + &builder, plant, lcm, sim_params.controller_channel, + sim_params.state_channel, sim_params.publish_rate, + sim_params.publish_efforts, sim_params.actuator_delay); int nq = plant.num_positions(); int nv = plant.num_velocities(); int nu = plant.num_actuators(); - auto logger = builder.AddSystem>(nq+nv+nu, output_dt); - - // multiplex state and input for logger - std::vector input_sizes = {nq+nv, nu}; - auto mux = builder.AddSystem>(input_sizes); - - builder.Connect(plant.get_state_output_port(), mux->get_input_port(0)); - builder.Connect(passthrough->get_output_port(), mux->get_input_port(1)); - builder.Connect(mux->get_output_port(0), logger->get_input_port(0)); auto diagram = builder.Build(); @@ -128,11 +110,9 @@ int DoMain(int argc, char* argv[]){ simulator.Initialize(); simulator.AdvanceTo(std::numeric_limits::infinity()); - // do data logging here - return 0; } -} // namespace dairlib +} // namespace dairlib -int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv);} +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 0104072e00..29803539a6 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -12,8 +12,19 @@ struct FrankaSimParams { double realtime_rate; std::vector q_init_franka; + std::string state_channel; + std::string controller_channel; + double publish_rate; + bool publish_efforts; + double actuator_delay; + template void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(state_channel)); + a->Visit(DRAKE_NVP(controller_channel)); + a->Visit(DRAKE_NVP(publish_rate)); + a->Visit(DRAKE_NVP(publish_efforts)); + a->Visit(DRAKE_NVP(actuator_delay)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); a->Visit(DRAKE_NVP(q_init_franka)); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index de1cd35cdf..31764e26ec 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -1,3 +1,9 @@ +state_channel: FRANKA_OUTPUT +controller_channel: FRANKA_INPUT +publish_rate: 1000 +publish_efforts: true +actuator_delay: 0.000 + dt: 0.0001 realtime_rate: 1.0 q_init_franka: [0, 0.275, 0, -2.222, 0, 2.497, 0] From 7999be2959bdcd6ecfdf0fff8643039fe744e063 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Mar 2023 17:20:51 -0400 Subject: [PATCH 400/758] circle tracking working, need elbow up heuristic --- examples/Cassie/run_osc_running_controller.cc | 13 +- examples/franka/BUILD.bazel | 45 ++++--- examples/franka/franka_controller_params.h | 46 ++++++- examples/franka/franka_controller_params.yaml | 51 +++++++- examples/franka/franka_osc_controller.cc | 55 +++++++- examples/franka/systems/BUILD.bazel | 14 ++ .../franka/systems/end_effector_trajectory.cc | 121 ++++++++++++++++++ .../franka/systems/end_effector_trajectory.h | 49 +++++++ systems/controllers/osc/osc_gains.h | 10 +- 9 files changed, 365 insertions(+), 39 deletions(-) create mode 100644 examples/franka/systems/BUILD.bazel create mode 100644 examples/franka/systems/end_effector_trajectory.cc create mode 100644 examples/franka/systems/end_effector_trajectory.h diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 1df52fa2ad..da78728627 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -201,15 +201,13 @@ int DoMain(int argc, char* argv[]) { /**** OSC setup ****/ // Cost /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_gains.w_accel * osc_gains.W_acceleration); - osc->SetInputSmoothingCostWeights(osc_gains.w_input_reg * - osc_gains.W_input_regularization); - osc->SetInputCostWeights(osc_gains.w_input * - osc_gains.W_input_regularization); + osc->SetAccelerationCostWeights(osc_gains.W_acceleration); + osc->SetInputSmoothingCostWeights(osc_gains.W_input_regularization); + osc->SetInputCostWeights(osc_gains.W_input_smoothing_regularization); osc->SetLambdaContactRegularizationWeight( - osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); + osc_gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight( - osc_gains.w_lambda * osc_gains.W_lambda_h_regularization); + osc_gains.W_lambda_h_regularization); // Soft constraint on contacts osc->SetContactSoftConstraintWeight(osc_gains.w_soft_constraint); osc->SetJointLimitWeight(osc_gains.w_joint_limit); @@ -243,7 +241,6 @@ int DoMain(int argc, char* argv[]) { multibody::KinematicEvaluatorSet evaluators(plant); - // Fix the springs in the dynamics auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant); diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 0c2d4c64b7..639f5d4ffe 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -6,62 +6,70 @@ package(default_visibility = ["//visibility:public"]) cc_library( name = "trifinger_urdf", data = glob([ - "robot_properties_fingers/urdf/**", - "robot_properties_fingers/urdf/pro/**", - "robot_properties_fingers/urdf/edu/**", - "robot_properties_fingers/meshes/**", - "robot_properties_fingers/meshes/pro/**", - "robot_properties_fingers/meshes/pro/detailed/**", - "robot_properties_fingers/meshes/edu/**", - "robot_properties_fingers/cube/**"]) + "robot_properties_fingers/urdf/**", + "robot_properties_fingers/urdf/pro/**", + "robot_properties_fingers/urdf/edu/**", + "robot_properties_fingers/meshes/**", + "robot_properties_fingers/meshes/pro/**", + "robot_properties_fingers/meshes/pro/detailed/**", + "robot_properties_fingers/meshes/edu/**", + "robot_properties_fingers/cube/**", + ]), ) cc_binary( name = "franka_sim", srcs = ["franka_sim.cc"], + data = [ + ":trifinger_urdf", + "@drake//manipulation/models/franka_description:models", + ], deps = [ ":franka_sim_params", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/controllers", "//systems/framework:lcm_driven_loop", - "//systems:system_utils", "@drake//:drake_shared_library", ], - data = [":trifinger_urdf", - "@drake//manipulation/models/franka_description:models"] ) cc_binary( name = "franka_osc_controller", srcs = ["franka_osc_controller.cc"], + data = [ + ":trifinger_urdf", + "@drake//manipulation/models/franka_description:models", + ], deps = [ ":franka_controller_params", + "//examples/franka/systems:end_effector_trajectory", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/controllers", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], - data = [":trifinger_urdf", - "@drake//manipulation/models/franka_description:models"] ) cc_binary( name = "franka_visualizer", srcs = ["franka_visualizer.cc"], + data = [ + ":trifinger_urdf", + "@drake//manipulation/models/franka_description:models", + ], deps = [ "//multibody:utils", "//multibody:visualization_utils", "//systems:robot_lcm_systems", - "//systems/primitives", "//systems:system_utils", + "//systems/primitives", "@drake//:drake_shared_library", "@gflags", ], - data = [":trifinger_urdf", - "@drake//manipulation/models/franka_description:models"] ) cc_library( @@ -71,10 +79,11 @@ cc_library( "@drake//:drake_shared_library", ], ) + cc_library( name = "franka_controller_params", hdrs = ["franka_controller_params.h"], deps = [ "@drake//:drake_shared_library", ], -) \ No newline at end of file +) diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index 2c33847889..4b6790fb10 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -1,31 +1,55 @@ #pragma once +#include "systems/controllers/osc/osc_gains.h" #include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" using Eigen::MatrixXd; -struct FrankaControllerParams { - +struct FrankaControllerParams : OSCGains { std::string state_channel; std::string controller_channel; + std::string radio_channel; + std::string osc_debug_channel; std::vector EndEffectorW; std::vector EndEffectorKp; std::vector EndEffectorKd; + std::vector MidLinkW; + std::vector MidLinkKp; + std::vector MidLinkKd; + std::vector EndEffectorRotW; + std::vector EndEffectorRotKp; + std::vector EndEffectorRotKd; MatrixXd W_end_effector; MatrixXd K_p_end_effector; MatrixXd K_d_end_effector; + MatrixXd W_mid_link; + MatrixXd K_p_mid_link; + MatrixXd K_d_mid_link; + MatrixXd W_end_effector_rot; + MatrixXd K_p_end_effector_rot; + MatrixXd K_d_end_effector_rot; template void Serialize(Archive* a) { + OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(state_channel)); a->Visit(DRAKE_NVP(controller_channel)); + a->Visit(DRAKE_NVP(radio_channel)); + a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); + a->Visit(DRAKE_NVP(MidLinkW)); + a->Visit(DRAKE_NVP(MidLinkKp)); + a->Visit(DRAKE_NVP(MidLinkKd)); + a->Visit(DRAKE_NVP(EndEffectorRotW)); + a->Visit(DRAKE_NVP(EndEffectorRotKp)); + a->Visit(DRAKE_NVP(EndEffectorRotKd)); W_end_effector = Eigen::Map< Eigen::Matrix>( @@ -36,5 +60,23 @@ struct FrankaControllerParams { K_d_end_effector = Eigen::Map< Eigen::Matrix>( this->EndEffectorKd.data(), 3, 3); + W_mid_link = Eigen::Map< + Eigen::Matrix>( + this->MidLinkW.data(), 3, 3); + K_p_mid_link = Eigen::Map< + Eigen::Matrix>( + this->MidLinkKp.data(), 3, 3); + K_d_mid_link = Eigen::Map< + Eigen::Matrix>( + this->MidLinkKd.data(), 3, 3); + W_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotW.data(), 3, 3); + K_p_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotKp.data(), 3, 3); + K_d_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotKd.data(), 3, 3); } }; \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index d20c502eef..d6dbc85892 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -1,15 +1,60 @@ +controller_frequency: 1000 state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT +radio_channel: CASSIE_VIRTUAL_RADIO +osc_debug_channel: OSC_DEBUG_FRANKA + +w_input: 0.00 +w_input_reg: 0.0001 +w_accel: 0.1 +w_soft_constraint: 10000 +w_lambda: 0.1 +impact_threshold: 0.000 +impact_tau: 0.000 +mu: 0.6 +# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] +W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] +W_lambda_c_reg: [ 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.001, 0.001 ] EndEffectorW: [1, 0, 0, 0, 1, 0, 0, 0, 1] EndEffectorKp: - [ 100, 0, 0, - 0, 100, 0, - 0, 0, 100 ] + [ 200, 0, 0, + 0, 200, 0, + 0, 0, 200 ] EndEffectorKd: + [ 30, 0, 0, + 0, 30, 0, + 0, 0, 30 ] +MidLinkW: + [0.1, 0, 0, + 0, 0, 0, + 0, 0, 1.0] +MidLinkKp: + [ 1, 0, 0, + 0, 5, 0, + 0, 0, 5 ] +MidLinkKd: [ 1, 0, 0, 0, 1, 0, 0, 0, 1 ] +EndEffectorRotW: + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] +EndEffectorRotKp: + [ 500, 0, 0, + 0, 500, 0, + 0, 0, 500 ] +EndEffectorRotKd: + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 5c1a3087fa..5b8cccbc1f 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -1,5 +1,6 @@ #include +#include #include "examples/franka/franka_controller_params.h" #include "multibody/multibody_utils.h" @@ -19,6 +20,7 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" +#include "examples/franka/systems/end_effector_trajectory.h" namespace dairlib { @@ -47,9 +49,13 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // load parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; FrankaControllerParams controller_params = drake::yaml::LoadYamlFile( "examples/franka/franka_controller_params.yaml"); + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow("examples/franka/franka_controller_params.yaml"), {}, {}, yaml_options); DiagramBuilder builder; @@ -70,22 +76,63 @@ int DoMain(int argc, char* argv[]) { controller_params.controller_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); + auto end_effector_trajectory = + builder.AddSystem(plant, + plant_context.get()); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + controller_params.radio_channel, &lcm)); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), false); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( - "OSC_DEBUG_FRANKA", &lcm, TriggerTypeSet({TriggerType::kForced}))); + controller_params.osc_debug_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); - auto end_effector_pose_tracking_data = + osc->SetAccelerationCostWeights(gains.W_acceleration); + osc->SetInputCostWeights(gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); + + auto end_effector_position_tracking_data = std::make_unique( "end_effector_target", controller_params.K_p_end_effector, controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); - osc->AddConstTrackingData(std::move(end_effector_pose_tracking_data), - Eigen::Vector3d::Ones()); + end_effector_position_tracking_data->AddPointToTrack("panda_link10"); + osc->AddTrackingData(std::move(end_effector_position_tracking_data)); + auto mid_link_position_tracking_data = + std::make_unique( + "mid_link", controller_params.K_p_mid_link, + controller_params.K_d_mid_link, controller_params.W_mid_link, + plant, plant); + mid_link_position_tracking_data->AddPointToTrack("panda_link3"); + Eigen::Vector3d elbow_up_target = Eigen::Vector3d::Zero(); + elbow_up_target(1) = 0.2; + elbow_up_target(2) = 0.6; + osc->AddConstTrackingData(std::move(mid_link_position_tracking_data), + elbow_up_target); + auto end_effector_orientation_tracking_data = + std::make_unique( + "end_effector_orientation_target", controller_params.K_p_end_effector_rot, + controller_params.K_d_end_effector_rot, controller_params.W_end_effector_rot, + plant, plant); + end_effector_orientation_tracking_data->AddFrameToTrack("panda_link10"); + Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); + orientation_target(0) = 0.707; + orientation_target(2) = 0.707; +// orientation_target(1) = 1; +// orientation_target(3) = 0.707; + osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), + orientation_target); + osc->SetContactFriction(0.4); osc->Build(); + builder.Connect(state_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_trajectory->get_input_port_radio()); + builder.Connect(end_effector_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_target")); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_command(), diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel new file mode 100644 index 0000000000..df5a4749ba --- /dev/null +++ b/examples/franka/systems/BUILD.bazel @@ -0,0 +1,14 @@ +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "end_effector_trajectory", + srcs = ["end_effector_trajectory.cc"], + hdrs = ["end_effector_trajectory.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc new file mode 100644 index 0000000000..61b2fa25aa --- /dev/null +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -0,0 +1,121 @@ +#include "end_effector_trajectory.h" + +#include + +#include "dairlib/lcmt_radio_out.hpp" +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::Vector4d; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::BodyFrame; +using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib { + +EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator(const MultibodyPlant& plant, + Context* context) + : plant_(plant), + context_(context), + world_(plant.world_frame()) + { + + + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); +// target_vel_port_ = this->DeclareVectorInputPort( +// "v_des", BasicVector(VectorXd::Zero(2))) +// .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, + &EndEffectorTrajectoryGenerator::CalcTraj); + +} + +PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( + const drake::systems::Context& context) const { + const auto robot_output = + this->template EvalVectorInput(context, state_port_); +// const auto desired_pelvis_vel_xy = +// this->EvalVectorInput(context, target_vel_port_)->get_value(); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + double t = robot_output->get_timestamp(); + double dt = 0.1; + double frequency = 0.5 * (1 + radio_out->channel[2]) * M_PI; + double radius = radio_out->channel[0] * 0.2; + VectorXd y0 = VectorXd::Zero(3); + y0(0) = 0.8; + y0(1) = radius * cos(frequency * t); + y0(2) = radius * sin(frequency * t) + 0.3; + VectorXd ydot0 = VectorXd::Zero(3); + ydot0(0) = 0; + ydot0(1) = -radius * frequency * sin(frequency * t); + ydot0(2) = -radius * frequency * cos(frequency * t); + std::vector breaks = {t, t + dt}; + std::vector samples = {y0, y0 + dt * ydot0}; + return drake::trajectories::PiecewisePolynomial::FirstOrderHold(breaks, + samples); +} + +PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateLine( + const drake::systems::Context& context) const { + const auto robot_output = + this->template EvalVectorInput(context, state_port_); +// const auto desired_pelvis_vel_xy = +// this->EvalVectorInput(context, target_vel_port_)->get_value(); +// const auto radio_signal = +// this->EvalVectorInput(context, radio_port_)->get_value(); + double t = robot_output->get_timestamp(); + double dt = 0.1; + VectorXd y0 = VectorXd::Zero(3); + y0(0) = 0; + y0(1) = 0.8; + y0(2) = 0.2 * sin(M_PI * t) + 0.5; + VectorXd ydot0 = VectorXd::Zero(3); + ydot0(0) = 0; + ydot0(1) = 0; + ydot0(2) = -0.2 * M_PI * cos(M_PI * t); + std::vector breaks = {t, t + dt}; + std::vector samples = {y0, y0 + dt * ydot0}; + return drake::trajectories::PiecewisePolynomial::FirstOrderHold(breaks, + samples); +} + +void EndEffectorTrajectoryGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // // Read in finite state machine + + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + *casted_traj = GenerateCircle(context); +// *casted_traj = GenerateLine(context); +} + +} // namespace dairlib::examples::osc_run diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h new file mode 100644 index 0000000000..4d11f867e7 --- /dev/null +++ b/examples/franka/systems/end_effector_trajectory.h @@ -0,0 +1,49 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem { + public: + EndEffectorTrajectoryGenerator(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_target_vel() const { + return this->get_input_port(target_vel_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + drake::trajectories::PiecewisePolynomial GenerateCircle( + const drake::systems::Context& context) const; + drake::trajectories::PiecewisePolynomial GenerateLine( + const drake::systems::Context& context) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::Frame& world_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex target_vel_port_; + drake::systems::InputPortIndex radio_port_; + +}; + +} // namespace dairlib::examples::osc_run diff --git a/systems/controllers/osc/osc_gains.h b/systems/controllers/osc/osc_gains.h index ca76bae336..bff84ba0f8 100644 --- a/systems/controllers/osc/osc_gains.h +++ b/systems/controllers/osc/osc_gains.h @@ -25,6 +25,7 @@ struct OSCGains { MatrixXd W_acceleration; MatrixXd W_input_regularization; + MatrixXd W_input_smoothing_regularization; MatrixXd W_lambda_c_regularization; MatrixXd W_lambda_h_regularization; @@ -56,9 +57,10 @@ struct OSCGains { Eigen::VectorXd w_lambda_h_regularization = Eigen::Map( this->W_lambda_h_reg.data(), this->W_lambda_h_reg.size()); - W_acceleration = w_acceleration.asDiagonal(); - W_input_regularization = w_input_regularization.asDiagonal(); - W_lambda_c_regularization = w_lambda_c_regularization.asDiagonal(); - W_lambda_h_regularization = w_lambda_h_regularization.asDiagonal(); + W_acceleration = w_accel * w_acceleration.asDiagonal(); + W_input_regularization = w_input * w_input_regularization.asDiagonal(); + W_input_smoothing_regularization = w_input_reg * w_input_regularization.asDiagonal(); + W_lambda_c_regularization = w_lambda * w_lambda_c_regularization.asDiagonal(); + W_lambda_h_regularization = w_lambda * w_lambda_h_regularization.asDiagonal(); } }; \ No newline at end of file From 9b5e399110ed6c92b6db3ffbcea54f522d761a84 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 17 Mar 2023 14:44:09 -0400 Subject: [PATCH 401/758] adding table in sim --- examples/franka/franka_osc_controller.cc | 8 +- examples/franka/franka_sim.cc | 14 ++- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/franka_visualizer.cc | 16 ++- .../franka/systems/end_effector_trajectory.cc | 9 +- examples/franka/urdf/franka_box.urdf | 113 +----------------- examples/franka/urdf/table.urdf | 18 +++ 7 files changed, 59 insertions(+), 121 deletions(-) create mode 100644 examples/franka/urdf/table.urdf diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 5b8cccbc1f..af9629a03f 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -97,7 +97,7 @@ int DoMain(int argc, char* argv[]) { "end_effector_target", controller_params.K_p_end_effector, controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); - end_effector_position_tracking_data->AddPointToTrack("panda_link10"); + end_effector_position_tracking_data->AddPointToTrack("panda_link8"); osc->AddTrackingData(std::move(end_effector_position_tracking_data)); auto mid_link_position_tracking_data = std::make_unique( @@ -115,10 +115,10 @@ int DoMain(int argc, char* argv[]) { "end_effector_orientation_target", controller_params.K_p_end_effector_rot, controller_params.K_d_end_effector_rot, controller_params.W_end_effector_rot, plant, plant); - end_effector_orientation_tracking_data->AddFrameToTrack("panda_link10"); + end_effector_orientation_tracking_data->AddFrameToTrack("panda_link8"); Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); - orientation_target(0) = 0.707; - orientation_target(2) = 0.707; + orientation_target(0) = 1; +// orientation_target(2) = 1; // orientation_target(1) = 1; // orientation_target(3) = 0.707; osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index dad1bfc8cf..009f7c479f 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -2,6 +2,7 @@ #include +#include #include #include #include @@ -45,6 +46,7 @@ using systems::AddActuationRecieverAndStateSenderLcm; using Eigen::MatrixXd; using Eigen::VectorXd; +using Eigen::Vector3d; int DoMain(int argc, char* argv[]) { // load parameters @@ -55,14 +57,24 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; double sim_dt = sim_params.dt; double output_dt = sim_params.dt; + // auto scene_graph = + // builder.AddSystem(std::make_unique>()); auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); Parser parser(&plant); parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf")); RigidTransform X_WI = RigidTransform::Identity(); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + Vector3d shift = Eigen::VectorXd::Zero(3); + shift(2) = 0.7645; + RigidTransform R_X_W = RigidTransform(drake::math::RotationMatrix(), shift); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link"), X_WI); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); + plant.Finalize(); /* -------------------------------------------------------------------------------------------*/ diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 31764e26ec..95947f210b 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -2,7 +2,7 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT publish_rate: 1000 publish_efforts: true -actuator_delay: 0.000 +actuator_delay: 0.005 dt: 0.0001 realtime_rate: 1.0 diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 0fdd0d32af..18ae9fdd47 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -18,6 +18,7 @@ #include #include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" +#include "drake/common/find_resource.h" DEFINE_string(channel, "FRANKA_OUTPUT", "LCM channel for receiving state. " @@ -26,6 +27,11 @@ DEFINE_string(channel, "FRANKA_OUTPUT", namespace dairlib { + +using Eigen::VectorXd; +using Eigen::Vector3d; +using Eigen::MatrixXd; + using dairlib::systems::RobotOutputReceiver; using dairlib::systems::SubvectorPassThrough; using drake::geometry::DrakeVisualizer; @@ -57,8 +63,16 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf")); RigidTransform X_WI = RigidTransform::Identity(); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); + Vector3d shift = Eigen::VectorXd::Zero(3); + shift(2) = 0.7645; + RigidTransform R_X_W = RigidTransform(drake::math::RotationMatrix(), shift); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link"), + X_WI); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); plant.Finalize(); diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 61b2fa25aa..fd2d4dc5c7 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -68,13 +68,14 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( double dt = 0.1; double frequency = 0.5 * (1 + radio_out->channel[2]) * M_PI; double radius = radio_out->channel[0] * 0.2; + int index = radio_out->channel[15]; VectorXd y0 = VectorXd::Zero(3); - y0(0) = 0.8; - y0(1) = radius * cos(frequency * t); + y0(1 - index) = 0.7; + y0(index) = radius * cos(frequency * t); y0(2) = radius * sin(frequency * t) + 0.3; VectorXd ydot0 = VectorXd::Zero(3); - ydot0(0) = 0; - ydot0(1) = -radius * frequency * sin(frequency * t); + ydot0(1 - index) = 0; + ydot0(index) = -radius * frequency * sin(frequency * t); ydot0(2) = -radius * frequency * cos(frequency * t); std::vector breaks = {t, t + dt}; std::vector samples = {y0, y0 + dt * ydot0}; diff --git a/examples/franka/urdf/franka_box.urdf b/examples/franka/urdf/franka_box.urdf index 68b2c0cb30..0ed84d4ba4 100644 --- a/examples/franka/urdf/franka_box.urdf +++ b/examples/franka/urdf/franka_box.urdf @@ -503,19 +503,18 @@ - - + - + - + @@ -524,49 +523,6 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission @@ -643,67 +599,4 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/examples/franka/urdf/table.urdf b/examples/franka/urdf/table.urdf new file mode 100644 index 0000000000..1302bec5fb --- /dev/null +++ b/examples/franka/urdf/table.urdf @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + \ No newline at end of file From aa144a60b4e20fea2f14e8a7daf6b85ca02fc020 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 20 Mar 2023 10:53:57 -0400 Subject: [PATCH 402/758] small renaming changes --- examples/Cassie/cassie_xbox_remote.py | 2 +- examples/Cassie/director_scripts/show_time_sim.py | 2 +- examples/Cassie/forward_command.py | 8 ++++---- examples/Cassie/osc_run/osc_running_gains_fast.yaml | 4 +--- examples/Cassie/osc_run/osc_running_qp_settings.yaml | 2 +- examples/Cassie/run_osc_standing_controller.cc | 8 +++----- examples/Cassie/visualizer.cc | 2 +- 7 files changed, 12 insertions(+), 16 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 7910aa94b6..d36838e78b 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -66,7 +66,7 @@ def main(): joystick.init() done = False - max_speed = 2.9 + max_speed = 1.5 ramp_up = np.arange(0, max_speed, 0.025) stay = max_speed * np.ones(500) ramp_down = np.flip(np.arange(0, max_speed, 0.01)) diff --git a/examples/Cassie/director_scripts/show_time_sim.py b/examples/Cassie/director_scripts/show_time_sim.py index 7c026714a6..bf23264afc 100644 --- a/examples/Cassie/director_scripts/show_time_sim.py +++ b/examples/Cassie/director_scripts/show_time_sim.py @@ -17,7 +17,7 @@ def __init__(self): # Number of messages used to average for real time factor. self._num_msg_for_average = 20 self.text_time = vis.TextItem('sim_info', 'sim_info', view) - self.text_time.setProperty('Position', [10, 900]) + self.text_time.setProperty('Position', [10, 400]) self.text_time.setProperty('Font Size', 36) self.text_time.setProperty('Bold', True) self.set_enabled(True) diff --git a/examples/Cassie/forward_command.py b/examples/Cassie/forward_command.py index 35df29e94d..f02f8e0c85 100644 --- a/examples/Cassie/forward_command.py +++ b/examples/Cassie/forward_command.py @@ -17,11 +17,11 @@ def main(): clock = pygame.time.Clock() done = False - max_speed = 1.3 + max_speed = 2.8 dt = .020 - acceleration = 0.5 # m/s^2 - deceleration = 0.75 # m/s^2 - max_speed_duration = 20 + acceleration = 2.0 # m/s^2 + deceleration = 0.5 # m/s^2 + max_speed_duration = 9 velocity_step_up = acceleration * dt velocity_step_down = deceleration * dt ramp_up = np.arange(0, max_speed, velocity_step_up) diff --git a/examples/Cassie/osc_run/osc_running_gains_fast.yaml b/examples/Cassie/osc_run/osc_running_gains_fast.yaml index 58caf5a928..8e8eb6ce74 100644 --- a/examples/Cassie/osc_run/osc_running_gains_fast.yaml +++ b/examples/Cassie/osc_run/osc_running_gains_fast.yaml @@ -25,8 +25,6 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] #w_soft_constraint: 1000000 -relative_feet: true -relative_pelvis: true no_derivative_feedback: false rot_filter_tau: 0.0025 ekf_filter_tau: [ 0.00, 0.00, 0.00 ] @@ -41,7 +39,7 @@ target_vel_filter_alpha: 0.01 rest_length: 0.9 rest_length_offset: 0.05 stance_duration: 0.2 -flight_duration: 0.11 +flight_duration: 0.1 # max percent variance stance_variance: 0.4 flight_variance: 0.2 diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 9ec13c9f16..e71cdb3262 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,6 +1,6 @@ rho: 0.001 sigma: 1e-6 -max_iter: 250 +max_iter: 125 eps_abs: 1e-5 eps_rel: 1e-5 eps_prim_inf: 1e-5 diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 181809c2b8..8a14671d1c 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -66,7 +66,7 @@ DEFINE_string( DEFINE_double(cost_weight_multiplier, 1.0, "A cosntant times with cost weight of OSC traj tracking"); DEFINE_double(height, .8, "The initial COM height (m)"); -DEFINE_string(osc_gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", +DEFINE_string(gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", "Filepath containing osc_gains"); DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", "Filepath containing qp settings"); @@ -102,14 +102,12 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - // auto osc_gains = - // drake::yaml::LoadYamlFile(FLAGS_osc_gains_filename); drake::yaml::LoadYamlOptions yaml_options; yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osc_gains_filename), {}, {}, yaml_options); + FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCStandingGains osc_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osc_gains_filename)); + FindResourceOrThrow(FLAGS_gains_filename)); // Create Lcm subsriber for lcmt_target_standing_height auto target_height_receiver = builder.AddSystem( diff --git a/examples/Cassie/visualizer.cc b/examples/Cassie/visualizer.cc index 0f7a0d1e9d..726eda240a 100644 --- a/examples/Cassie/visualizer.cc +++ b/examples/Cassie/visualizer.cc @@ -56,7 +56,7 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); - AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, "examples/Cassie/urdf/cassie_v2.urdf"); + AddCassieMultibody(&plant, &scene_graph, FLAGS_floating_base, "examples/Cassie/urdf/cassie_v2_shells.urdf"); if (FLAGS_floating_base) { // Ground direction Eigen::Vector3d ground_normal(sin(FLAGS_ground_incline), 0, From 5662158fb8560ab92ddc443cd405185f8f5ea171 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 20 Mar 2023 15:11:28 -0400 Subject: [PATCH 403/758] renaming contact thresholds --- examples/Cassie/cassie_state_estimator_settings.h | 2 +- examples/Cassie/dispatcher_robot_out.cc | 4 ++-- ..._settings.yaml => state_estimator_contact_thresholds.yaml} | 0 3 files changed, 3 insertions(+), 3 deletions(-) rename examples/Cassie/{default_state_estimator_settings.yaml => state_estimator_contact_thresholds.yaml} (100%) diff --git a/examples/Cassie/cassie_state_estimator_settings.h b/examples/Cassie/cassie_state_estimator_settings.h index 13dcc9e5e9..40976c7c83 100644 --- a/examples/Cassie/cassie_state_estimator_settings.h +++ b/examples/Cassie/cassie_state_estimator_settings.h @@ -5,7 +5,7 @@ #include "drake/common/yaml/yaml_read_archive.h" -struct CassieStateEstimatorSettings{ +struct CassieStateEstimatorContactThresholds{ double knee_spring_threshold; double ankle_spring_threshold; diff --git a/examples/Cassie/dispatcher_robot_out.cc b/examples/Cassie/dispatcher_robot_out.cc index cad8044ebc..f87ad8f040 100644 --- a/examples/Cassie/dispatcher_robot_out.cc +++ b/examples/Cassie/dispatcher_robot_out.cc @@ -64,7 +64,7 @@ DEFINE_string(state_channel_name, "CASSIE_STATE_SIMULATION", // Cassie model paramter DEFINE_bool(floating_base, true, "Fixed or floating base model"); DEFINE_string(joint_offset_yaml, "", "yaml with joint offset values"); -DEFINE_string(contact_detection_yaml, "examples/Cassie/default_state_estimator_settings.yaml", "Yaml with contact estimation values"); +DEFINE_string(contact_detection_yaml, "examples/Cassie/state_estimator_contact_thresholds.yaml", "Yaml with contact estimation values"); // Testing mode DEFINE_int64(test_mode, -1, @@ -211,7 +211,7 @@ int do_main(int argc, char* argv[]) { drake::yaml::LoadYamlFile>( FindResourceOrThrow(FLAGS_joint_offset_yaml)); - CassieStateEstimatorSettings settings = drake::yaml::LoadYamlFile( + CassieStateEstimatorContactThresholds settings = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_contact_detection_yaml)); auto state_estimator = builder.AddSystem( diff --git a/examples/Cassie/default_state_estimator_settings.yaml b/examples/Cassie/state_estimator_contact_thresholds.yaml similarity index 100% rename from examples/Cassie/default_state_estimator_settings.yaml rename to examples/Cassie/state_estimator_contact_thresholds.yaml From d20b50428e34f58ef315e6c44293e309853f215d Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 20 Mar 2023 16:11:32 -0400 Subject: [PATCH 404/758] working on model instances --- examples/franka/franka_sim.cc | 19 ++++++- examples/franka/franka_sim_params.h | 2 + examples/franka/franka_sim_params.yaml | 1 + examples/franka/franka_visualizer.cc | 53 ++++++++++++++---- systems/robot_lcm_systems.cc | 76 +++++++++++++------------- systems/robot_lcm_systems.h | 19 ++++--- 6 files changed, 111 insertions(+), 59 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 009f7c479f..c6ae181176 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -62,10 +62,12 @@ int DoMain(int argc, char* argv[]) { auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); Parser parser(&plant); - parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); - parser.AddModelFromFile(drake::FindResourceOrThrow( + drake::multibody::ModelInstanceIndex franka_index = parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/table/" "extra_heavy_duty_table_surface_only_collision.sdf")); + drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d shift = Eigen::VectorXd::Zero(3); @@ -85,7 +87,18 @@ int DoMain(int argc, char* argv[]) { auto passthrough = AddActuationRecieverAndStateSenderLcm( &builder, plant, lcm, sim_params.controller_channel, sim_params.state_channel, sim_params.publish_rate, + franka_index, sim_params.publish_efforts, sim_params.actuator_delay); + auto tray_state_sender = + builder.AddSystem(plant, tray_index); + auto tray_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + sim_params.tray_state_channel, lcm, 1.0 / sim_params.publish_rate)); + + builder.Connect(plant.get_state_output_port(tray_index), + tray_state_sender->get_input_port_state()); + builder.Connect(tray_state_sender->get_output_port(), + tray_state_pub->get_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); @@ -114,6 +127,8 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; + q[plant.num_positions() - 4] = 1; + plant.SetPositions(&plant_context, q); VectorXd v = VectorXd::Zero(nv); diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 29803539a6..2541bfc1cc 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -14,6 +14,7 @@ struct FrankaSimParams { std::string state_channel; std::string controller_channel; + std::string tray_state_channel; double publish_rate; bool publish_efforts; double actuator_delay; @@ -22,6 +23,7 @@ struct FrankaSimParams { void Serialize(Archive* a) { a->Visit(DRAKE_NVP(state_channel)); a->Visit(DRAKE_NVP(controller_channel)); + a->Visit(DRAKE_NVP(tray_state_channel)); a->Visit(DRAKE_NVP(publish_rate)); a->Visit(DRAKE_NVP(publish_efforts)); a->Visit(DRAKE_NVP(actuator_delay)); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 95947f210b..a0b14f76e9 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -1,5 +1,6 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT +tray_state_channel: TRAY_OUTPUT publish_rate: 1000 publish_efforts: true actuator_delay: 0.005 diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 18ae9fdd47..8cbc765572 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -16,6 +16,7 @@ #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/rendering/multibody_position_to_geometry_pose.h" #include +#include #include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" #include "drake/common/find_resource.h" @@ -62,10 +63,13 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant, &scene_graph); - parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); - parser.AddModelFromFile(drake::FindResourceOrThrow( + drake::multibody::ModelInstanceIndex franka_index = parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/table/" "extra_heavy_duty_table_surface_only_collision.sdf")); + drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); + RigidTransform X_WI = RigidTransform::Identity(); Vector3d shift = Eigen::VectorXd::Zero(3); shift(2) = 0.7645; @@ -79,19 +83,37 @@ int do_main(int argc, char* argv[]) { auto lcm = builder.AddSystem(); // Create state receiver. - auto state_sub = + auto franka_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_channel, lcm)); - auto state_receiver = builder.AddSystem(plant); - builder.Connect(*state_sub, *state_receiver); - - auto passthrough = builder.AddSystem( - state_receiver->get_output_port(0).size(), 0, plant.num_positions()); - builder.Connect(*state_receiver, *passthrough); + auto tray_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + "TRAY_OUTPUT", lcm)); + auto franka_state_receiver = builder.AddSystem(plant); + auto tray_state_receiver = builder.AddSystem(plant); + + builder.Connect(*franka_state_sub, *franka_state_receiver); + builder.Connect(*tray_state_sub, *tray_state_receiver); + + auto franka_passthrough = builder.AddSystem( + franka_state_receiver->get_output_port(0).size(), 0, plant.num_positions(franka_index)); + auto tray_passthrough = builder.AddSystem( + tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); + builder.Connect(*franka_state_receiver, *franka_passthrough); + builder.Connect(*tray_state_receiver, *tray_passthrough); + + std::vector input_sizes = + {plant.num_positions(franka_index), plant.num_positions(tray_index)}; + auto mux = + builder.AddSystem>(input_sizes); + builder.Connect(franka_passthrough->get_output_port(), + mux->get_input_port(0)); + builder.Connect(tray_passthrough->get_output_port(), + mux->get_input_port(1)); auto to_pose = builder.AddSystem>(plant); - builder.Connect(*passthrough, *to_pose); + builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); @@ -106,9 +128,18 @@ int do_main(int argc, char* argv[]) { // state_receiver->set_publish_period(1.0/30.0); // framerate auto diagram = builder.Build(); - auto context = diagram->CreateDefaultContext(); + auto& franka_state_sub_context = diagram->GetMutableSubsystemContext( + *franka_state_sub, context.get()); + auto& tray_state_sub_context = diagram->GetMutableSubsystemContext( + *tray_state_sub, context.get()); + franka_state_receiver->InitializeSubscriberPositions(plant, + franka_state_sub_context); + tray_state_receiver->InitializeSubscriberPositions(plant, + tray_state_sub_context); + + /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice /// Set realtime rate. Otherwise, runs as fast as possible diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index b812225a48..ba3826e7c9 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -1,7 +1,9 @@ -#include - #include "robot_lcm_systems.h" +#include + +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" #include "multibody/multibody_utils.h" #include "drake/multibody/plant/multibody_plant.h" @@ -9,9 +11,6 @@ #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/primitives/discrete_time_delay.h" -#include "dairlib/lcmt_robot_input.hpp" -#include "dairlib/lcmt_robot_output.hpp" - namespace dairlib { namespace systems { @@ -19,9 +18,9 @@ using drake::multibody::JointActuatorIndex; using drake::multibody::JointIndex; using drake::multibody::MultibodyPlant; using drake::systems::Context; +using drake::systems::LeafSystem; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::LeafSystem; using Eigen::VectorXd; using std::string; using systems::OutputVector; @@ -30,9 +29,10 @@ using systems::OutputVector; // methods implementation for RobotOutputReceiver. RobotOutputReceiver::RobotOutputReceiver( - const drake::multibody::MultibodyPlant& plant) { - num_positions_ = plant.num_positions(); - num_velocities_ = plant.num_velocities(); + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index) { + num_positions_ = plant.num_positions(model_instance_index); + num_velocities_ = plant.num_velocities(model_instance_index); num_efforts_ = plant.num_actuators(); position_index_map_ = multibody::MakeNameToPositionsMap(plant); velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); @@ -41,7 +41,8 @@ RobotOutputReceiver::RobotOutputReceiver( drake::Value{}); this->DeclareVectorOutputPort( "x, u, t", - OutputVector(plant.num_positions(), plant.num_velocities(), + OutputVector(plant.num_positions(model_instance_index), + plant.num_velocities(model_instance_index), plant.num_actuators()), &RobotOutputReceiver::CopyOutput); } @@ -84,7 +85,7 @@ void RobotOutputReceiver::CopyOutput(const Context& context, void RobotOutputReceiver::InitializeSubscriberPositions( const MultibodyPlant& plant, - drake::systems::Context &context) const { + drake::systems::Context& context) const { auto& state_msg = context.get_mutable_abstract_state(0); // using the time from the context @@ -128,10 +129,11 @@ void RobotOutputReceiver::InitializeSubscriberPositions( RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index, const bool publish_efforts, const bool publish_imu) : publish_efforts_(publish_efforts), publish_imu_(publish_imu) { - num_positions_ = plant.num_positions(); - num_velocities_ = plant.num_velocities(); + num_positions_ = plant.num_positions(model_instance_index); + num_velocities_ = plant.num_velocities(model_instance_index); num_efforts_ = plant.num_actuators(); position_index_map_ = multibody::MakeNameToPositionsMap(plant); @@ -284,13 +286,10 @@ void RobotCommandSender::OutputCommand( SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const MultibodyPlant& plant, - drake::systems::lcm::LcmInterfaceSystem* lcm, - std::string actuator_channel, - std::string state_channel, - double publish_rate, - bool publish_efforts, - double actuator_delay) { - + drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, + std::string state_channel, double publish_rate, + drake::multibody::ModelInstanceIndex model_instance_index, + bool publish_efforts, double actuator_delay) { // Create LCM input for actuators auto input_sub = builder->AddSystem(LcmSubscriberSystem::Make( @@ -307,31 +306,32 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( builder->AddSystem(LcmPublisherSystem::Make( state_channel, lcm, 1.0 / publish_rate)); auto state_sender = builder->AddSystem( - plant, publish_efforts); - builder->Connect(plant.get_state_output_port(), + plant, model_instance_index, publish_efforts); + + builder->Connect(plant.get_state_output_port(model_instance_index), state_sender->get_input_port_state()); // Add delay, if used, and associated connections if (actuator_delay > 0) { - auto discrete_time_delay = - builder->AddSystem( - 1.0 / publish_rate, actuator_delay * publish_rate, - plant.num_actuators()); - builder->Connect(*passthrough, *discrete_time_delay); + auto discrete_time_delay = + builder->AddSystem( + 1.0 / publish_rate, actuator_delay * publish_rate, + plant.num_actuators()); + builder->Connect(*passthrough, *discrete_time_delay); + builder->Connect(discrete_time_delay->get_output_port(), + plant.get_actuation_input_port()); + + if (publish_efforts) { builder->Connect(discrete_time_delay->get_output_port(), - plant.get_actuation_input_port()); - - if (publish_efforts) { - builder->Connect(discrete_time_delay->get_output_port(), - state_sender->get_input_port_effort()); - } + state_sender->get_input_port_effort()); + } } else { + builder->Connect(passthrough->get_output_port(), + plant.get_actuation_input_port()); + if (publish_efforts) { builder->Connect(passthrough->get_output_port(), - plant.get_actuation_input_port()); - if (publish_efforts) { - builder->Connect(passthrough->get_output_port(), - state_sender->get_input_port_effort()); - } + state_sender->get_input_port_effort()); + } } builder->Connect(*state_sender, *state_pub); diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 3e1a88c0f6..ce4f748cf2 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -27,7 +27,9 @@ namespace systems { class RobotOutputReceiver : public drake::systems::LeafSystem { public: explicit RobotOutputReceiver( - const drake::multibody::MultibodyPlant& plant); + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index = + drake::multibody::default_model_instance()); /// Convenience function to initialize an lcmt_robot_output subscriber with /// positions and velocities which are all zero except for the quaternion @@ -54,6 +56,8 @@ class RobotOutputSender : public drake::systems::LeafSystem { public: explicit RobotOutputSender( const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index = + drake::multibody::default_model_instance(), const bool publish_efforts = false, const bool publish_imu = false); const drake::systems::InputPort& get_input_port_state() const { @@ -122,7 +126,6 @@ class RobotCommandSender : public drake::systems::LeafSystem { std::map actuator_index_map_; }; - /// /// Convenience method to add and connect leaf systems for controlling /// a MultibodyPlant via LCM. Makes two primary connections: @@ -148,11 +151,11 @@ class RobotCommandSender : public drake::systems::LeafSystem { SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const drake::multibody::MultibodyPlant& plant, - drake::systems::lcm::LcmInterfaceSystem* lcm, - std::string actuator_channel, - std::string state_channel, - double publish_rate, - bool publish_efforts = true, - double actuator_delay = 0); + drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, + std::string state_channel, double publish_rate, + drake::multibody::ModelInstanceIndex model_instance_index = + drake::multibody::default_model_instance(), + bool publish_efforts = true, double actuator_delay = 0); + } // namespace systems } // namespace dairlib From fc21fd14224e20498f4df4db0c9223bfdde9433e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 20 Mar 2023 23:41:05 -0400 Subject: [PATCH 405/758] added functions for ModelInstanceIndex --- examples/franka/franka_osc_controller.cc | 1 + examples/franka/franka_sim.cc | 3 +- examples/franka/franka_visualizer.cc | 90 +++++----- multibody/multibody_utils.cc | 206 +++++++++++++++++++---- multibody/multibody_utils.h | 20 ++- systems/robot_lcm_systems.cc | 77 ++++++--- systems/robot_lcm_systems.h | 19 ++- 7 files changed, 310 insertions(+), 106 deletions(-) diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index af9629a03f..76503ad86d 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -14,6 +14,7 @@ #include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" +#include "drake/common/find_resource.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index c6ae181176..5ac54f1062 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -127,7 +127,8 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; - q[plant.num_positions() - 4] = 1; + q[plant.num_positions() - 7] = 1; + q[plant.num_positions() - 1] = 2; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 8cbc765572..1e00fc3293 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -1,3 +1,7 @@ +#include + +#include +#include #include #include "dairlib/lcmt_robot_output.hpp" @@ -6,7 +10,10 @@ #include "multibody/visualization_utils.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/geometry/drake_visualizer.h" #include "drake/geometry/meshcat_visualizer.h" #include "drake/geometry/meshcat_visualizer_params.h" @@ -15,11 +22,6 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/rendering/multibody_position_to_geometry_pose.h" -#include -#include -#include "systems/system_utils.h" -#include "drake/common/yaml/yaml_io.h" -#include "drake/common/find_resource.h" DEFINE_string(channel, "FRANKA_OUTPUT", "LCM channel for receiving state. " @@ -28,10 +30,9 @@ DEFINE_string(channel, "FRANKA_OUTPUT", namespace dairlib { - -using Eigen::VectorXd; -using Eigen::Vector3d; using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; using dairlib::systems::RobotOutputReceiver; using dairlib::systems::SubvectorPassThrough; @@ -47,9 +48,9 @@ using drake::systems::Simulator; using drake::systems::lcm::LcmSubscriberSystem; using drake::systems::rendering::MultibodyPositionToGeometryPose; +using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::Parser; -using drake::math::RigidTransform; using drake::systems::DiagramBuilder; int do_main(int argc, char* argv[]) { @@ -63,22 +64,30 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant, &scene_graph); - drake::multibody::ModelInstanceIndex franka_index = parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); - drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf")); - drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + drake::multibody::ModelInstanceIndex table_index = + parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf")); + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d shift = Eigen::VectorXd::Zero(3); shift(2) = 0.7645; - RigidTransform R_X_W = RigidTransform(drake::math::RotationMatrix(), shift); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link"), - X_WI); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); + RigidTransform R_X_W = + RigidTransform(drake::math::RotationMatrix(), shift); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link"), X_WI); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); plant.Finalize(); + std::cout << "num floating base bodies " + << plant.GetFloatingBaseBodies().size() << std::endl; + std::cout << "num positions " << plant.num_positions(drake::multibody::ModelInstanceIndex(1)) << std::endl; + std::cout << "num positions " << plant.num_positions() << std::endl; auto lcm = builder.AddSystem(); @@ -89,27 +98,30 @@ int do_main(int argc, char* argv[]) { auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( "TRAY_OUTPUT", lcm)); - auto franka_state_receiver = builder.AddSystem(plant); - auto tray_state_receiver = builder.AddSystem(plant); + auto franka_state_receiver = + builder.AddSystem(plant, franka_index); + auto tray_state_receiver = + builder.AddSystem(plant, tray_index); builder.Connect(*franka_state_sub, *franka_state_receiver); builder.Connect(*tray_state_sub, *tray_state_receiver); auto franka_passthrough = builder.AddSystem( - franka_state_receiver->get_output_port(0).size(), 0, plant.num_positions(franka_index)); + franka_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(franka_index)); auto tray_passthrough = builder.AddSystem( - tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); + tray_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(tray_index)); builder.Connect(*franka_state_receiver, *franka_passthrough); builder.Connect(*tray_state_receiver, *tray_passthrough); - std::vector input_sizes = - {plant.num_positions(franka_index), plant.num_positions(tray_index)}; + std::vector input_sizes = {plant.num_positions(franka_index), + plant.num_positions(tray_index)}; auto mux = builder.AddSystem>(input_sizes); builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); - builder.Connect(tray_passthrough->get_output_port(), - mux->get_input_port(1)); + builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); auto to_pose = builder.AddSystem>(plant); @@ -120,7 +132,7 @@ int do_main(int argc, char* argv[]) { DrakeVisualizer::AddToBuilder(&builder, scene_graph); drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0/60.0; + params.publish_period = 1.0 / 60.0; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); @@ -130,24 +142,24 @@ int do_main(int argc, char* argv[]) { auto diagram = builder.Build(); auto context = diagram->CreateDefaultContext(); - auto& franka_state_sub_context = diagram->GetMutableSubsystemContext( - *franka_state_sub, context.get()); - auto& tray_state_sub_context = diagram->GetMutableSubsystemContext( - *tray_state_sub, context.get()); - franka_state_receiver->InitializeSubscriberPositions(plant, - franka_state_sub_context); - tray_state_receiver->InitializeSubscriberPositions(plant, - tray_state_sub_context); - + auto& franka_state_sub_context = + diagram->GetMutableSubsystemContext(*franka_state_sub, context.get()); + auto& tray_state_sub_context = + diagram->GetMutableSubsystemContext(*tray_state_sub, context.get()); + franka_state_receiver->InitializeSubscriberPositions( + plant, franka_state_sub_context); + tray_state_receiver->InitializeSubscriberPositions( + plant, tray_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice /// Set realtime rate. Otherwise, runs as fast as possible auto stepper = - std::make_unique>(*diagram, std::move(context)); + std::make_unique>(*diagram, std::move(context)); stepper->set_publish_every_time_step(false); stepper->set_publish_at_initialization(false); - stepper->set_target_realtime_rate(1.0); // may need to change this to param.real_time_rate? + stepper->set_target_realtime_rate( + 1.0); // may need to change this to param.real_time_rate? stepper->Initialize(); drake::log()->info("visualizer started"); diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 82966ee95d..4b06cca85a 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -1,11 +1,12 @@ #include "multibody/multibody_utils.h" +#include #include #include #include "drake/common/drake_assert.h" -#include "drake/math/autodiff_gradient.h" #include "drake/geometry/proximity_properties.h" +#include "drake/math/autodiff_gradient.h" namespace dairlib { namespace multibody { @@ -23,9 +24,9 @@ using drake::multibody::JointIndex; using drake::multibody::ModelInstanceIndex; using drake::multibody::MultibodyPlant; using drake::systems::Context; -using Eigen::VectorXd; -using Eigen::Vector3d; using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; using std::map; using std::string; using std::vector; @@ -119,7 +120,6 @@ void SetInputsIfNew(const MultibodyPlant& plant, } } - template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, @@ -136,36 +136,34 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, const drake::math::RigidTransformd X_WG( HalfSpace::MakePose(normal_W, point_W)); - - - if (stiffness != 0){ + if (stiffness != 0) { drake::geometry::ProximityProperties props; props.AddProperty("material", "point_contact_stiffness", stiffness); props.AddProperty("material", "hunt_crossley_dissipation", dissipation_rate); props.AddProperty(drake::geometry::internal::kMaterialGroup, - drake::geometry::internal::kFriction, - friction); + drake::geometry::internal::kFriction, friction); plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), "collision", props); - } - else{ + } else { plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), "collision", friction); } // Add visual for the ground. if (show_ground) { -// plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), -// "visual"); + // plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), + // "visual"); } } /// Get the ordered names from a NameTo___Map vector ExtractOrderedNamesFromMap(const map& map) { - vector names(map.size()); +// vector names(map.size()); + vector names; for (const auto& entry : map) { - names[entry.second] = entry.first; +// std::cout << "index: " << entry.second << std::endl; + names.push_back(entry.first); } return names; } @@ -235,6 +233,72 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant) { } } + return name_to_index_map; +} +/// Construct a map between joint names and position indices +/// such that q(index) has the given name +/// -Only accurately includes joints with a single position and single velocity +/// -Others are included as "position[ind]"" +/// -Index mapping can also be used as a state mapping (assumes x = [q;v]) +template +map MakeNameToPositionsMap(const MultibodyPlant& plant, + ModelInstanceIndex model_instance) { + map name_to_index_map; + std::set index_set; + for (auto i : plant.GetJointIndices(model_instance)) { + const drake::multibody::Joint& joint = plant.get_joint(i); + auto name = joint.name(); + + if (joint.num_velocities() == 1 && joint.num_positions() == 1) { + std::vector index_vector{i}; + auto selectorMatrix = plant.MakeStateSelectorMatrix(index_vector); + // find index and add + int selector_index = -1; + for (int j = 0; j < selectorMatrix.cols(); ++j) { + if (selectorMatrix(0, j) == 1) { + if (selector_index == -1) { + selector_index = j; + } else { + throw std::logic_error("Unable to create selector map."); + } + } + } + if (selector_index == -1) { + std::logic_error("Unable to create selector map."); + } + + name_to_index_map[name] = selector_index; + index_set.insert(selector_index); + } + } + + // TODO: once RBT fully deprecated, this block can likely be removed, using + // default coordinate names from Drake. + auto floating_bodies = plant.GetFloatingBaseBodies(); + DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); + if (plant.HasUniqueFreeBaseBody(model_instance)) { + for (auto body_index : floating_bodies) { + const auto& body = plant.get_body(body_index); + DRAKE_ASSERT(body.has_quaternion_dofs()); + int start = body.floating_positions_start(); + // should be body.name() once RBT is deprecated + std::string name = "base"; + name_to_index_map[name + "_qw"] = start; + name_to_index_map[name + "_qx"] = start + 1; + name_to_index_map[name + "_qy"] = start + 2; + name_to_index_map[name + "_qz"] = start + 3; + name_to_index_map[name + "_x"] = start + 4; + name_to_index_map[name + "_y"] = start + 5; + name_to_index_map[name + "_z"] = start + 6; + for (int i = 0; i < 7; i++) { + index_set.insert(start + i); + } + } + } + // if index has not already been captured, throw an error + DRAKE_THROW_UNLESS(plant.num_positions(model_instance) == index_set.size()); + + return name_to_index_map; } @@ -303,6 +367,75 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { } } + // if index has not already been captured, throw an error + DRAKE_THROW_UNLESS(plant.num_velocities() == index_set.size()); + return name_to_index_map; +} + +/// Construct a map between joint names and velocity indices +/// such that v(index) has the given name +/// -Only accurately includes joints with a single position and single velocity +/// -Others are included as "state[ind]" +/// -Index mapping can also be used as a state mapping, AFTER +/// an offset of num_positions is applied (assumes x = [q;v]) +template +map MakeNameToVelocitiesMap(const MultibodyPlant& plant, + ModelInstanceIndex model_instance) { + map name_to_index_map; + std::set index_set; + + for (auto i : plant.GetJointIndices(model_instance)) { + const drake::multibody::Joint& joint = plant.get_joint(i); + // TODO(posa): this "dot" should be removed, it's an anachronism from + // RBT + auto name = joint.name() + "dot"; + + if (joint.num_velocities() == 1 && joint.num_positions() == 1) { + std::vector index_vector{i}; + auto selectorMatrix = plant.MakeStateSelectorMatrix(index_vector); + // find index and add + int selector_index = -1; + for (int j = 0; j < selectorMatrix.cols(); ++j) { + if (selectorMatrix(1, j) == 1) { + if (selector_index == -1) { + selector_index = j; + } else { + throw std::logic_error("Unable to create selector map."); + } + } + } + if (selector_index == -1) { + throw std::logic_error("Unable to create selector map."); + } + + name_to_index_map[name] = selector_index - plant.num_positions(); + index_set.insert(selector_index - plant.num_positions()); + } + } + + auto floating_bodies = plant.GetFloatingBaseBodies(); + // Remove throw once RBT deprecated + DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); + if (plant.HasUniqueFreeBaseBody(model_instance)) { + for (auto body_index : floating_bodies) { + const auto& body = plant.get_body(body_index); + int start = body.floating_velocities_start() - plant.num_positions(); + std::string name = + "base"; // should be body.name() once RBT is deprecated + name_to_index_map[name + "_wx"] = start; + name_to_index_map[name + "_wy"] = start + 1; + name_to_index_map[name + "_wz"] = start + 2; + name_to_index_map[name + "_vx"] = start + 3; + name_to_index_map[name + "_vy"] = start + 4; + name_to_index_map[name + "_vz"] = start + 5; + for (int i = 0; i < 6; i++) { + index_set.insert(start + i); + } + } + } + + // if index has not already been captured, throw an error + DRAKE_THROW_UNLESS(plant.num_velocities(model_instance) == index_set.size()); return name_to_index_map; } @@ -341,8 +474,7 @@ map MakeNameToActuatorsMap(const MultibodyPlant& plant) { } template -vector CreateStateNameVectorFromMap( - const MultibodyPlant& plant) { +vector CreateStateNameVectorFromMap(const MultibodyPlant& plant) { map pos_map = MakeNameToPositionsMap(plant); map vel_map = MakeNameToVelocitiesMap(plant); vector state_names(pos_map.size() + vel_map.size()); @@ -358,8 +490,7 @@ vector CreateStateNameVectorFromMap( } template -vector CreateActuatorNameVectorFromMap( - const MultibodyPlant& plant) { +vector CreateActuatorNameVectorFromMap(const MultibodyPlant& plant) { map act_map = MakeNameToActuatorsMap(plant); return ExtractOrderedNamesFromMap(act_map); } @@ -471,10 +602,9 @@ Vector3d ReExpressWorldVector3InBodyYawFrame(const MultibodyPlant& plant, const Vector3d& vec) { Vector3d pelvis_x = plant.GetBodyByName(body_name).EvalPoseInWorld(context).rotation().col(0); - double yaw = atan2(pelvis_x(1), pelvis_x(0)); - return Vector3d(cos(yaw) * vec(0) + sin(yaw)*vec(1), - -sin(yaw) * vec(0) + cos(yaw)*vec(1), - vec(2)); + double yaw = atan2(pelvis_x(1), pelvis_x(0)); + return Vector3d(cos(yaw) * vec(0) + sin(yaw) * vec(1), + -sin(yaw) * vec(0) + cos(yaw) * vec(1), vec(2)); } template @@ -484,9 +614,9 @@ Vector2d ReExpressWorldVector2InBodyYawFrame(const MultibodyPlant& plant, const Vector2d& vec) { Vector3d pelvis_x = plant.GetBodyByName(body_name).EvalPoseInWorld(context).rotation().col(0); - double yaw = atan2(pelvis_x(1), pelvis_x(0)); - return Vector2d(cos(yaw) * vec(0) + sin(yaw)*vec(1), - -sin(yaw) * vec(0) + cos(yaw)*vec(1)); + double yaw = atan2(pelvis_x(1), pelvis_x(0)); + return Vector2d(cos(yaw) * vec(0) + sin(yaw) * vec(1), + -sin(yaw) * vec(0) + cos(yaw) * vec(1)); } Eigen::MatrixXd WToQuatDotMap(const Eigen::Vector4d& q) { @@ -501,30 +631,38 @@ Eigen::MatrixXd WToQuatDotMap(const Eigen::Vector4d& q) { return ret; } -Eigen::MatrixXd JwrtqdotToJwrtv( - const Eigen::VectorXd& q, const Eigen::MatrixXd& Jwrtqdot) { +Eigen::MatrixXd JwrtqdotToJwrtv(const Eigen::VectorXd& q, + const Eigen::MatrixXd& Jwrtqdot) { //[J_1:4, J_5:end] * [WToQuatDotMap, 0] = [J_1:4 * WToQuatDotMap, J_5:end] // [ 0 , I] DRAKE_DEMAND(Jwrtqdot.cols() == q.size()); - Eigen::MatrixXd ret(Jwrtqdot.rows(), q.size() -1); + Eigen::MatrixXd ret(Jwrtqdot.rows(), q.size() - 1); ret << Jwrtqdot.leftCols<4>() * WToQuatDotMap(q.head<4>()), Jwrtqdot.rightCols(q.size() - 4); return ret; } -template int QuaternionStartIndex(const MultibodyPlant& plant); // NOLINT -template int QuaternionStartIndex(const MultibodyPlant& plant); // NOLINT -template std::vector QuaternionStartIndices(const MultibodyPlant& plant); // NOLINT -template std::vector QuaternionStartIndices(const MultibodyPlant& plant); // NOLINT -template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT +template int QuaternionStartIndex( + const MultibodyPlant& plant); // NOLINT +template int QuaternionStartIndex( + const MultibodyPlant& plant); // NOLINT +template std::vector QuaternionStartIndices( + const MultibodyPlant& plant); // NOLINT +template std::vector QuaternionStartIndices( + const MultibodyPlant& plant); // NOLINT +template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT template Vector3d ReExpressWorldVector3InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector3d& vec); //NOLINT template Vector2d ReExpressWorldVector2InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector2d& vec); //NOLINT template map MakeNameToPositionsMap(const MultibodyPlant& plant); // NOLINT template map MakeNameToPositionsMap(const MultibodyPlant &plant); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant &plant, drake::multibody::ModelInstanceIndex); // NOLINT template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT template map MakeNameToActuatorsMap(const MultibodyPlant& plant); // NOLINT template map MakeNameToActuatorsMap(const MultibodyPlant& plant); // NOLINT template vector CreateStateNameVectorFromMap(const MultibodyPlant& plant); // NOLINT diff --git a/multibody/multibody_utils.h b/multibody/multibody_utils.h index 3528daf865..14cc00e932 100644 --- a/multibody/multibody_utils.h +++ b/multibody/multibody_utils.h @@ -80,11 +80,24 @@ template std::map MakeNameToPositionsMap( const drake::multibody::MultibodyPlant& plant); +/// Given a MultibodyPlant, builds a map from position name to position index +template +std::map MakeNameToPositionsMap( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index); + /// Given a MultiBodyTree, builds a map from velocity name to velocity index template std::map MakeNameToVelocitiesMap( const drake::multibody::MultibodyPlant& plant); + +/// Given a MultiBodyTree, builds a map from velocity name to velocity index +template +std::map MakeNameToVelocitiesMap( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index); + /// Given a MultiBodyTree, builds a map from actuator name to actuator index template std::map MakeNameToActuatorsMap( @@ -145,18 +158,15 @@ bool HasQuaternion(const drake::multibody::MultibodyPlant& plant); template Eigen::Vector3d ReExpressWorldVector3InBodyYawFrame( const drake::multibody::MultibodyPlant& plant, - const drake::systems::Context& context, - const std::string& body_name, + const drake::systems::Context& context, const std::string& body_name, const Eigen::Vector3d& vec); template Eigen::Vector2d ReExpressWorldVector2InBodyYawFrame( const drake::multibody::MultibodyPlant& plant, - const drake::systems::Context& context, - const std::string& body_name, + const drake::systems::Context& context, const std::string& body_name, const Eigen::Vector2d& vec); - /// Computes the matrix for mapping global roll-pitch-yaw angular velocity to /// quaternion derivatives /// Ref: equation 16 of https://arxiv.org/pdf/0811.2889.pdf diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index ba3826e7c9..dc83fda3c2 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -28,21 +28,53 @@ using systems::OutputVector; /*--------------------------------------------------------------------------*/ // methods implementation for RobotOutputReceiver. +RobotOutputReceiver::RobotOutputReceiver( + const drake::multibody::MultibodyPlant& plant) { + + num_positions_ = plant.num_positions(); + num_velocities_ = plant.num_velocities(); + num_efforts_ = plant.num_actuators(); + position_index_map_ = + multibody::MakeNameToPositionsMap(plant); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant); + model_instance_ = drake::multibody::ModelInstanceIndex(-1); + + positions_start_idx_ = 0; + velocities_start_idx_ = 0; + effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + this->DeclareAbstractInputPort("lcmt_robot_output", + drake::Value{}); + this->DeclareVectorOutputPort( + "x, u, t", + OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators()), + &RobotOutputReceiver::CopyOutput); +} + RobotOutputReceiver::RobotOutputReceiver( const drake::multibody::MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex model_instance_index) { - num_positions_ = plant.num_positions(model_instance_index); - num_velocities_ = plant.num_velocities(model_instance_index); + drake::multibody::ModelInstanceIndex model_instance) { + + model_instance_ = model_instance; + num_positions_ = plant.num_positions(model_instance); + num_velocities_ = plant.num_velocities(model_instance); num_efforts_ = plant.num_actuators(); - position_index_map_ = multibody::MakeNameToPositionsMap(plant); - velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); + position_index_map_ = + multibody::MakeNameToPositionsMap(plant, model_instance); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant, model_instance); + + positions_start_idx_ = plant.get_joint(plant.GetJointIndices(model_instance).front()).position_start(); + velocities_start_idx_ = plant.get_joint(plant.GetJointIndices(model_instance).front()).velocity_start(); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); this->DeclareAbstractInputPort("lcmt_robot_output", drake::Value{}); this->DeclareVectorOutputPort( "x, u, t", - OutputVector(plant.num_positions(model_instance_index), - plant.num_velocities(model_instance_index), + OutputVector(plant.num_positions(model_instance), + plant.num_velocities(model_instance), plant.num_actuators()), &RobotOutputReceiver::CopyOutput); } @@ -56,12 +88,12 @@ void RobotOutputReceiver::CopyOutput(const Context& context, VectorXd positions = VectorXd::Zero(num_positions_); for (int i = 0; i < state_msg.num_positions; i++) { int j = position_index_map_.at(state_msg.position_names[i]); - positions(j) = state_msg.position[i]; + positions(j - positions_start_idx_) = state_msg.position[i]; } VectorXd velocities = VectorXd::Zero(num_velocities_); for (int i = 0; i < state_msg.num_velocities; i++) { int j = velocity_index_map_.at(state_msg.velocity_names[i]); - velocities(j) = state_msg.velocity[i]; + velocities(j - velocities_start_idx_) = state_msg.velocity[i]; } VectorXd efforts = VectorXd::Zero(num_efforts_); for (int i = 0; i < state_msg.num_efforts; i++) { @@ -106,21 +138,18 @@ void RobotOutputReceiver::InitializeSubscriberPositions( state_msg.velocity.resize(num_positions_); for (int i = 0; i < num_positions_; i++) { - state_msg.position_names[i] = ordered_position_names[i]; - state_msg.position[i] = 0; + state_msg.position_names.at(i) = ordered_position_names.at(i); + state_msg.position.at(i) = 0; } // Set quaternion w = 1, assumes drake quaternion ordering of wxyz - for (const auto& body_idx : plant.GetFloatingBaseBodies()) { - const auto& body = plant.get_body(body_idx); - if (body.has_quaternion_dofs()) { - state_msg.position[body.floating_positions_start()] = 1; - } + if (model_instance_ >= 0 && plant.HasUniqueFreeBaseBody(model_instance_)) { + state_msg.position.at(0) = 1; } for (int i = 0; i < num_velocities_; i++) { - state_msg.velocity[i] = 0; - state_msg.velocity_names[i] = ordered_velocity_names[i]; + state_msg.velocity.at(i) = 0; + state_msg.velocity_names.at(i) = ordered_velocity_names[i]; } } @@ -129,15 +158,17 @@ void RobotOutputReceiver::InitializeSubscriberPositions( RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex model_instance_index, + drake::multibody::ModelInstanceIndex model_instance, const bool publish_efforts, const bool publish_imu) : publish_efforts_(publish_efforts), publish_imu_(publish_imu) { - num_positions_ = plant.num_positions(model_instance_index); - num_velocities_ = plant.num_velocities(model_instance_index); + num_positions_ = plant.num_positions(model_instance); + num_velocities_ = plant.num_velocities(model_instance); num_efforts_ = plant.num_actuators(); - position_index_map_ = multibody::MakeNameToPositionsMap(plant); - velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); + position_index_map_ = + multibody::MakeNameToPositionsMap(plant, model_instance); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant, model_instance); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); ordered_position_names_ = diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index ce4f748cf2..5182539cbc 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -26,10 +26,12 @@ namespace systems { /// robot states as a OutputVector. class RobotOutputReceiver : public drake::systems::LeafSystem { public: + explicit RobotOutputReceiver( + const drake::multibody::MultibodyPlant& plant); + explicit RobotOutputReceiver( const drake::multibody::MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex model_instance_index = - drake::multibody::default_model_instance()); + drake::multibody::ModelInstanceIndex model_instance); /// Convenience function to initialize an lcmt_robot_output subscriber with /// positions and velocities which are all zero except for the quaternion @@ -43,6 +45,9 @@ class RobotOutputReceiver : public drake::systems::LeafSystem { private: void CopyOutput(const drake::systems::Context& context, OutputVector* output) const; + drake::multibody::ModelInstanceIndex model_instance_; + int positions_start_idx_; + int velocities_start_idx_; int num_positions_; int num_velocities_; int num_efforts_; @@ -153,8 +158,14 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( const drake::multibody::MultibodyPlant& plant, drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, std::string state_channel, double publish_rate, - drake::multibody::ModelInstanceIndex model_instance_index = - drake::multibody::default_model_instance(), + drake::multibody::ModelInstanceIndex model_instance_index, + bool publish_efforts = true, double actuator_delay = 0); + +SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( + drake::systems::DiagramBuilder* builder, + const drake::multibody::MultibodyPlant& plant, + drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, + std::string state_channel, double publish_rate, bool publish_efforts = true, double actuator_delay = 0); } // namespace systems From 3d6d8e7cb9467e74a09f1223577d58ee8d0b9b39 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Mar 2023 11:36:37 -0400 Subject: [PATCH 406/758] cleaning up y error and fixing impact invariant bug when applying the view frame --- .../controllers/osc/rot_space_tracking_data.cc | 15 +++++++-------- 1 file changed, 7 insertions(+), 8 deletions(-) diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index 2be090883e..60e0174287 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -59,15 +59,10 @@ void RotTaskSpaceTrackingData::UpdateY(const VectorXd& x_w_spr, void RotTaskSpaceTrackingData::UpdateYError() { DRAKE_DEMAND(y_des_.size() == 4); Quaterniond y_quat_des(y_des_(0), y_des_(1), y_des_(2), y_des_(3)); - y_quat_des.normalize(); - Quaterniond y_quat(y_(0), y_(1), y_(2), y_(3)); - // Get relative quaternion (from current to desired) - Quaterniond relative_quat = (y_quat_des * y_quat.inverse()).normalized(); - double theta = 2 * acos(relative_quat.w()); - Vector3d rot_axis = relative_quat.vec().normalized(); - error_y_ = theta * rot_axis; + Eigen::AngleAxis angle_axis_diff(y_quat_des * y_quat.inverse()); + error_y_ = angle_axis_diff.angle() * angle_axis_diff.axis(); if (with_view_frame_) { error_y_ = view_frame_rot_T_ * error_y_; } @@ -90,7 +85,11 @@ void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { Quaterniond dy_quat_des(ydot_des_(0), ydot_des_(1), ydot_des_(2), ydot_des_(3)); Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); - error_ydot_ = w_des_ - ydot_ - GetJ() * v_proj; + // Because we transform the error here rather than in the parent + // options_tracking_data, and because J_y is already transformed in the view + // frame, we need to undo the transformation on J_y + error_ydot_ = + w_des_ - ydot_ - view_frame_rot_T_.transpose() * GetJ() * v_proj; if (with_view_frame_) { error_ydot_ = view_frame_rot_T_ * error_ydot_; } From e3235250942424574e4025ab99439dd75ce1e0a1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Mar 2023 16:00:49 -0400 Subject: [PATCH 407/758] moving table --- .../plot_configs/cassie_running_plot.yaml | 4 +- examples/Cassie/cassie_xbox_remote.py | 2 +- examples/franka/franka_osc_controller.cc | 22 +- examples/franka/franka_sim.cc | 69 +++-- examples/franka/franka_visualizer.cc | 32 +-- .../franka/systems/end_effector_trajectory.cc | 2 +- examples/franka/urdf/franka_box.urdf | 26 +- examples/franka/urdf/table.urdf | 252 ++++++++++++++++-- 8 files changed, 343 insertions(+), 66 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml index 8173c1ff7a..87a79914fd 100644 --- a/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/cassie_running_plot.yaml @@ -4,7 +4,7 @@ channel_x: "CASSIE_STATE_DISPATCHER" channel_u: "OSC_RUNNING" channel_osc: "OSC_DEBUG_RUNNING" use_archived_lcmtypes: false -use_default_styling: true +use_default_styling: false # Log time to stop at (seconds, -1 for whole log) start_time: 2 @@ -48,7 +48,7 @@ plot_active_tracking_datas: false tracking_datas_to_plot: { # pelvis_trans_traj: { 'dims': [0, 1, 2 ], 'derivs': [ 'accel' ] }, # pelvis_trans_traj: { 'dims': [ 2 ], 'derivs': [ 'pos'] }, -# pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, + pelvis_rot_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, # hip_yaw_left_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, # hip_yaw_right_traj: { 'dims': [ 0 ], 'derivs': [ 'pos' ] }, # right_ft_traj: { 'dims': [ 0, 1, 2 ], 'derivs': [ 'pos' ] }, diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 6cf34da7e2..53795dfd33 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -112,7 +112,7 @@ def main(): # Send LCM message radio_msg = dairlib.lcmt_radio_out() - radio_msg.channel[0] = speeds[i] + radio_msg.channel[0] = joystick.get_axis(1) radio_msg.channel[1] = joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(4) diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 76503ad86d..9ef23753bf 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -66,6 +66,24 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); + + VectorXd rotor_inertias(plant.num_actuators()); + rotor_inertias << 61, 61, 61, 61, 61, 61, 61; + rotor_inertias *= 1e-6; + VectorXd gear_ratios(plant.num_actuators()); + gear_ratios << 25, 25, 25, 25, 25, 25, 25; + std::vector motor_joint_names = { + "panda_motor1", "panda_motor2", "panda_motor3", + "panda_motor4", "panda_motor5", "panda_motor6", + "panda_motor7"}; + for (int i = 0; i < rotor_inertias.size(); ++i) { + auto& joint_actuator = plant.get_mutable_joint_actuator( + drake::multibody::JointActuatorIndex(i)); + joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); + joint_actuator.set_default_gear_ratio(gear_ratios(i)); + DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); + } + plant.Finalize(); auto plant_context = plant.CreateDefaultContext(); @@ -98,7 +116,7 @@ int DoMain(int argc, char* argv[]) { "end_effector_target", controller_params.K_p_end_effector, controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); - end_effector_position_tracking_data->AddPointToTrack("panda_link8"); + end_effector_position_tracking_data->AddPointToTrack("paddle"); osc->AddTrackingData(std::move(end_effector_position_tracking_data)); auto mid_link_position_tracking_data = std::make_unique( @@ -116,7 +134,7 @@ int DoMain(int argc, char* argv[]) { "end_effector_orientation_target", controller_params.K_p_end_effector_rot, controller_params.K_d_end_effector_rot, controller_params.W_end_effector_rot, plant, plant); - end_effector_orientation_tracking_data->AddFrameToTrack("panda_link8"); + end_effector_orientation_tracking_data->AddFrameToTrack("paddle"); Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); orientation_target(0) = 1; // orientation_target(2) = 1; diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 5ac54f1062..270bebcdfb 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -45,8 +45,8 @@ using multibody::MakeNameToVelocitiesMap; using systems::AddActuationRecieverAndStateSenderLcm; using Eigen::MatrixXd; -using Eigen::VectorXd; using Eigen::Vector3d; +using Eigen::VectorXd; int DoMain(int argc, char* argv[]) { // load parameters @@ -62,20 +62,55 @@ int DoMain(int argc, char* argv[]) { auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); Parser parser(&plant); - drake::multibody::ModelInstanceIndex franka_index = parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); - drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf")); - drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( + drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"), + "table0"); + drake::multibody::ModelInstanceIndex second_table_index = + parser.AddModelFromFile( + drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"), + "table1"); + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); RigidTransform X_WI = RigidTransform::Identity(); - Vector3d shift = Eigen::VectorXd::Zero(3); - shift(2) = 0.7645; - RigidTransform R_X_W = RigidTransform(drake::math::RotationMatrix(), shift); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link"), - X_WI); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); + Vector3d franka_origin = Eigen::VectorXd::Zero(3); + Vector3d second_table_origin = Eigen::VectorXd::Zero(3); + franka_origin(2) = 0.7645; + second_table_origin(0) = 0.75; + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + RigidTransform T_X_W = RigidTransform( + drake::math::RotationMatrix(), second_table_origin); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("link", table_index), X_WI); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("link", second_table_index), T_X_W); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); + + VectorXd rotor_inertias(plant.num_actuators()); + rotor_inertias << 61, 61, 61, 61, 61, 61, 61; + rotor_inertias *= 1e-6; + VectorXd gear_ratios(plant.num_actuators()); + gear_ratios << 25, 25, 25, 25, 25, 25, 25; + std::vector motor_joint_names = { + "panda_motor1", "panda_motor2", "panda_motor3", + "panda_motor4", "panda_motor5", "panda_motor6", + "panda_motor7"}; + for (int i = 0; i < rotor_inertias.size(); ++i) { + auto& joint_actuator = plant.get_mutable_joint_actuator( + drake::multibody::JointActuatorIndex(i)); + joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); + joint_actuator.set_default_gear_ratio(gear_ratios(i)); + DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); + } plant.Finalize(); @@ -86,8 +121,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(&drake_lcm); auto passthrough = AddActuationRecieverAndStateSenderLcm( &builder, plant, lcm, sim_params.controller_channel, - sim_params.state_channel, sim_params.publish_rate, - franka_index, + sim_params.state_channel, sim_params.publish_rate, franka_index, sim_params.publish_efforts, sim_params.actuator_delay); auto tray_state_sender = builder.AddSystem(plant, tray_index); @@ -119,16 +153,17 @@ int DoMain(int argc, char* argv[]) { std::map q_map = MakeNameToPositionsMap(plant); // initialize EE close to {0.5, 0, 0.12}[m] in task space + q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; + q[q_map["panda_joint2"]] = sim_params.q_init_franka[1]; q[q_map["panda_joint3"]] = sim_params.q_init_franka[2]; q[q_map["panda_joint4"]] = sim_params.q_init_franka[3]; q[q_map["panda_joint5"]] = sim_params.q_init_franka[4]; q[q_map["panda_joint6"]] = sim_params.q_init_franka[5]; - q[q_map["panda_joint2"]] = sim_params.q_init_franka[1]; q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; - q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; q[plant.num_positions() - 7] = 1; q[plant.num_positions() - 1] = 2; + q[plant.num_positions() - 3] = 0.75; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 1e00fc3293..5966fd2304 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -66,28 +66,30 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); drake::multibody::ModelInstanceIndex franka_index = parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); - drake::multibody::ModelInstanceIndex table_index = - parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf")); + drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"), "table0"); + drake::multibody::ModelInstanceIndex second_table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"), "table1"); drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); RigidTransform X_WI = RigidTransform::Identity(); - Vector3d shift = Eigen::VectorXd::Zero(3); - shift(2) = 0.7645; - RigidTransform R_X_W = - RigidTransform(drake::math::RotationMatrix(), shift); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link"), X_WI); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), - R_X_W); + Vector3d franka_origin = Eigen::VectorXd::Zero(3); + Vector3d second_table_origin = Eigen::VectorXd::Zero(3); + franka_origin(2) = 0.7645; + second_table_origin(0) = 0.75; + RigidTransform R_X_W = RigidTransform(drake::math::RotationMatrix(), franka_origin); + RigidTransform T_X_W = RigidTransform(drake::math::RotationMatrix(), second_table_origin); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", table_index), + X_WI); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", second_table_index), + T_X_W); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); plant.Finalize(); - std::cout << "num floating base bodies " - << plant.GetFloatingBaseBodies().size() << std::endl; - std::cout << "num positions " << plant.num_positions(drake::multibody::ModelInstanceIndex(1)) << std::endl; - std::cout << "num positions " << plant.num_positions() << std::endl; auto lcm = builder.AddSystem(); diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index fd2d4dc5c7..4cb734f599 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -68,7 +68,7 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( double dt = 0.1; double frequency = 0.5 * (1 + radio_out->channel[2]) * M_PI; double radius = radio_out->channel[0] * 0.2; - int index = radio_out->channel[15]; + int index = std::max(0.0, radio_out->channel[15]); VectorXd y0 = VectorXd::Zero(3); y0(1 - index) = 0.7; y0(index) = radius * cos(frequency * t); diff --git a/examples/franka/urdf/franka_box.urdf b/examples/franka/urdf/franka_box.urdf index 0ed84d4ba4..4fcde94629 100644 --- a/examples/franka/urdf/franka_box.urdf +++ b/examples/franka/urdf/franka_box.urdf @@ -500,28 +500,34 @@ - + - - - - - - + + + + + + + + + + + + - + - + - + transmission_interface/SimpleTransmission diff --git a/examples/franka/urdf/table.urdf b/examples/franka/urdf/table.urdf index 1302bec5fb..bc7bded15d 100644 --- a/examples/franka/urdf/table.urdf +++ b/examples/franka/urdf/table.urdf @@ -1,18 +1,234 @@ - - - - - - - - - - - - - - - - - - \ No newline at end of file + + + + + + + 53.5 + + + 5.177409 + 0 + 0 + 4.843753753 + 0 + 4.843753753 + + + 0 + + -0.33 -0.35 0.381 0 0 0 + + + 0.05 0.05 0.762 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0.33 0.35 0.381 0 0 0 + + + 0.05 0.05 0.762 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0.33 0 0.13335 0 0 0 + + + 0.05 0.662 0.05 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + -0.33 0 0.13335 0 0 0 + + + 0.05 0.662 0.05 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + -0.33 0.35 0.381 0 0 0 + + + 0.05 0.05 0.762 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0.33 -0.35 0.381 0 0 0 + + + 0.05 0.05 0.762 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0 0.35 0.13335 0 0 0 + + + 0.6112 0.05 0.05 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0 -0.35 0.13335 0 0 0 + + + 0.6112 0.05 0.05 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0 0 0.736 0 0 0 + + + 0.7112 0.762 0.057 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0 + 0 0 0.736 0 0 0 + + + 0.7112 0.762 0.057 + + + + + + 0.6 + 0.6 + 0 0 0 + 0 + 0 + + + 1 + 0 + 0 + 1 + + 0 + + + + + 0 + 1e+06 + + + 0 + 1 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + + + + + 0 0 0.7645 0 0 0 + + + + From 2c29cd5251d0562b72d01a68202647356e6ced93 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 21 Mar 2023 16:51:19 -0400 Subject: [PATCH 408/758] adding legs for table --- examples/franka/BUILD.bazel | 2 + examples/franka/franka_sim.cc | 10 ++-- examples/franka/franka_visualizer.cc | 37 +++++++----- .../franka/systems/end_effector_trajectory.cc | 2 +- .../franka/urdf/{table.urdf => table.sdf} | 56 +++++++++++++++++++ 5 files changed, 85 insertions(+), 22 deletions(-) rename examples/franka/urdf/{table.urdf => table.sdf} (83%) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 639f5d4ffe..c59a4dda02 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -29,6 +29,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", + "//common:find_resource", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", ], @@ -62,6 +63,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ + "//common:find_resource", "//multibody:utils", "//multibody:visualization_utils", "//systems:robot_lcm_systems", diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 270bebcdfb..3139b0204c 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -10,6 +10,7 @@ #include #include +#include "common/find_resource.h" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/franka/franka_sim_params.h" @@ -71,9 +72,7 @@ int DoMain(int argc, char* argv[]) { "table0"); drake::multibody::ModelInstanceIndex second_table_index = parser.AddModelFromFile( - drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"), + dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), "table1"); drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( @@ -101,9 +100,8 @@ int DoMain(int argc, char* argv[]) { VectorXd gear_ratios(plant.num_actuators()); gear_ratios << 25, 25, 25, 25, 25, 25, 25; std::vector motor_joint_names = { - "panda_motor1", "panda_motor2", "panda_motor3", - "panda_motor4", "panda_motor5", "panda_motor6", - "panda_motor7"}; + "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", + "panda_motor5", "panda_motor6", "panda_motor7"}; for (int i = 0; i < rotor_inertias.size(); ++i) { auto& joint_actuator = plant.get_mutable_joint_actuator( drake::multibody::JointActuatorIndex(i)); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 5966fd2304..4cf6392a3f 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -22,6 +22,7 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/rendering/multibody_position_to_geometry_pose.h" +#include "common/find_resource.h" DEFINE_string(channel, "FRANKA_OUTPUT", "LCM channel for receiving state. " @@ -66,12 +67,15 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); drake::multibody::ModelInstanceIndex franka_index = parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); - drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"), "table0"); - drake::multibody::ModelInstanceIndex second_table_index = parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"), "table1"); + drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( + drake::FindResourceOrThrow( + "drake/examples/kuka_iiwa_arm/models/table/" + "extra_heavy_duty_table_surface_only_collision.sdf"), + "table0"); + drake::multibody::ModelInstanceIndex second_table_index = + parser.AddModelFromFile( + dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), + "table1"); drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); @@ -81,13 +85,16 @@ int do_main(int argc, char* argv[]) { Vector3d second_table_origin = Eigen::VectorXd::Zero(3); franka_origin(2) = 0.7645; second_table_origin(0) = 0.75; - RigidTransform R_X_W = RigidTransform(drake::math::RotationMatrix(), franka_origin); - RigidTransform T_X_W = RigidTransform(drake::math::RotationMatrix(), second_table_origin); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", table_index), - X_WI); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", second_table_index), - T_X_W); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + RigidTransform T_X_W = RigidTransform( + drake::math::RotationMatrix(), second_table_origin); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("link", table_index), X_WI); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("link", second_table_index), T_X_W); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); plant.Finalize(); @@ -150,8 +157,8 @@ int do_main(int argc, char* argv[]) { diagram->GetMutableSubsystemContext(*tray_state_sub, context.get()); franka_state_receiver->InitializeSubscriberPositions( plant, franka_state_sub_context); - tray_state_receiver->InitializeSubscriberPositions( - plant, tray_state_sub_context); + tray_state_receiver->InitializeSubscriberPositions(plant, + tray_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 4cb734f599..1e47b12925 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -68,7 +68,7 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( double dt = 0.1; double frequency = 0.5 * (1 + radio_out->channel[2]) * M_PI; double radius = radio_out->channel[0] * 0.2; - int index = std::max(0.0, radio_out->channel[15]); + int index = 1 - std::max(0.0, radio_out->channel[15]); VectorXd y0 = VectorXd::Zero(3); y0(1 - index) = 0.7; y0(index) = radius * cos(frequency * t); diff --git a/examples/franka/urdf/table.urdf b/examples/franka/urdf/table.sdf similarity index 83% rename from examples/franka/urdf/table.urdf rename to examples/franka/urdf/table.sdf index bc7bded15d..d2156d331e 100644 --- a/examples/franka/urdf/table.urdf +++ b/examples/franka/urdf/table.sdf @@ -162,6 +162,62 @@ 0 0 0 1 + + 0.33 0.35 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + 0.33 -0.35 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + -0.33 0.35 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + + -0.33 -0.35 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + 0 0 0 0.736 0 0 0 From 3976f5fb3ed3773a4e48a2bd29df2cd9f17508c4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 22 Mar 2023 12:51:43 -0400 Subject: [PATCH 409/758] working on stable control --- examples/Cassie/cassie_xbox_remote.py | 10 ++--- examples/franka/franka_controller_params.yaml | 14 +++--- examples/franka/franka_osc_controller.cc | 20 ++++++--- examples/franka/franka_sim.cc | 2 +- examples/franka/franka_sim_params.yaml | 2 +- .../franka/systems/end_effector_trajectory.cc | 25 ++++++++++- .../franka/systems/end_effector_trajectory.h | 2 + examples/franka/urdf/table.sdf | 43 +++++++++++-------- 8 files changed, 79 insertions(+), 39 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 53795dfd33..a0bb6dfece 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -112,16 +112,16 @@ def main(): # Send LCM message radio_msg = dairlib.lcmt_radio_out() - radio_msg.channel[0] = joystick.get_axis(1) + radio_msg.channel[0] = -joystick.get_axis(1) - radio_msg.channel[1] = joystick.get_axis(0) - radio_msg.channel[2] = -joystick.get_axis(4) - radio_msg.channel[3] = joystick.get_axis(3) + radio_msg.channel[1] = -joystick.get_axis(0) + radio_msg.channel[2] = -joystick.get_axis(3) + radio_msg.channel[3] = joystick.get_axis(2) radio_msg.channel[4] = radio_channel_4_pos radio_msg.channel[5] = radio_channel_5_pos radio_msg.channel[6] = radio_channel_6_pos - radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) + # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index d6dbc85892..195fd31f18 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -35,16 +35,16 @@ EndEffectorKd: 0, 30, 0, 0, 0, 30 ] MidLinkW: - [0.1, 0, 0, + [0, 0, 0, 0, 0, 0, - 0, 0, 1.0] + 0, 0, 5] MidLinkKp: - [ 1, 0, 0, - 0, 5, 0, - 0, 0, 5 ] + [ 0, 0, 0, + 0, 0, 0, + 0, 0, 1 ] MidLinkKd: - [ 1, 0, 0, - 0, 1, 0, + [ 0, 0, 0, + 0, 0, 0, 0, 0, 1 ] EndEffectorRotW: [ 10, 0, 0, diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 9ef23753bf..7d6f2fd442 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -117,18 +117,21 @@ int DoMain(int argc, char* argv[]) { controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); end_effector_position_tracking_data->AddPointToTrack("paddle"); - osc->AddTrackingData(std::move(end_effector_position_tracking_data)); auto mid_link_position_tracking_data = std::make_unique( "mid_link", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant); - mid_link_position_tracking_data->AddPointToTrack("panda_link3"); - Eigen::Vector3d elbow_up_target = Eigen::Vector3d::Zero(); - elbow_up_target(1) = 0.2; - elbow_up_target(2) = 0.6; - osc->AddConstTrackingData(std::move(mid_link_position_tracking_data), - elbow_up_target); + mid_link_position_tracking_data->AddPointToTrack("panda_link5"); + auto wrist_relative_tracking_data = + std::make_unique( + "wrist_down_target", controller_params.K_p_mid_link, + controller_params.K_d_mid_link, controller_params.W_mid_link, + plant, plant, mid_link_position_tracking_data.get(), end_effector_position_tracking_data.get()); + Eigen::Vector3d wrist_down_target = Eigen::Vector3d::Zero(); + wrist_down_target(1) = -0.3; + wrist_down_target(2) = 0.2; + auto end_effector_orientation_tracking_data = std::make_unique( "end_effector_orientation_target", controller_params.K_p_end_effector_rot, @@ -140,6 +143,9 @@ int DoMain(int argc, char* argv[]) { // orientation_target(2) = 1; // orientation_target(1) = 1; // orientation_target(3) = 0.707; + osc->AddTrackingData(std::move(end_effector_position_tracking_data)); + osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), + wrist_down_target); osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), orientation_target); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 3139b0204c..3148e05e09 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -160,7 +160,7 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; q[plant.num_positions() - 7] = 1; - q[plant.num_positions() - 1] = 2; + q[plant.num_positions() - 1] = 1.25; q[plant.num_positions() - 3] = 0.75; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index a0b14f76e9..8602de20ba 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -7,4 +7,4 @@ actuator_delay: 0.005 dt: 0.0001 realtime_rate: 1.0 -q_init_franka: [0, 0.275, 0, -2.222, 0, 2.497, 0] +q_init_franka: [-0.8, 1.7, 1.8, -1.4, 1.4, 1.4, -0.56] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 1e47b12925..d7c1fc6e70 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -83,6 +83,28 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( samples); } +PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( + const drake::systems::Context& context) const { + const auto robot_output = + this->template EvalVectorInput(context, state_port_); +// const auto desired_pelvis_vel_xy = +// this->EvalVectorInput(context, target_vel_port_)->get_value(); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + double t = robot_output->get_timestamp(); + double dt = 0.1; + VectorXd y0 = VectorXd::Zero(3); + y0(0) = 0.7 + radio_out->channel[0] * 0.2; + y0(0) = std::clamp(y0(0), 0.0, 0.8); + y0(1) = radio_out->channel[1] * 0.2; + y0(2) = 0.3 + radio_out->channel[2] * 0.2; + VectorXd ydot0 = VectorXd::Zero(3); + std::vector breaks = {t, t + dt}; + std::vector samples = {y0, y0 + dt * ydot0}; + return drake::trajectories::PiecewisePolynomial::FirstOrderHold(breaks, + samples); +} + PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateLine( const drake::systems::Context& context) const { const auto robot_output = @@ -115,7 +137,8 @@ void EndEffectorTrajectoryGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - *casted_traj = GenerateCircle(context); +// *casted_traj = GenerateCircle(context); + *casted_traj = GeneratePose(context); // *casted_traj = GenerateLine(context); } diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index 4d11f867e7..b762c5eccd 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -30,6 +30,8 @@ class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem drake::systems::DiscreteValues* discrete_state) const; drake::trajectories::PiecewisePolynomial GenerateCircle( const drake::systems::Context& context) const; + drake::trajectories::PiecewisePolynomial GeneratePose( + const drake::systems::Context& context) const; drake::trajectories::PiecewisePolynomial GenerateLine( const drake::systems::Context& context) const; diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf index d2156d331e..5343f54e0c 100644 --- a/examples/franka/urdf/table.sdf +++ b/examples/franka/urdf/table.sdf @@ -163,7 +163,7 @@ - 0.33 0.35 0.9525 0 0 0 + 0.16 0.16 0.9525 0 0 0 0.05 0.05 0.381 @@ -177,7 +177,7 @@ - 0.33 -0.35 0.9525 0 0 0 + 0.16 -0.16 0.9525 0 0 0 0.05 0.05 0.381 @@ -191,21 +191,7 @@ - -0.33 0.35 0.9525 0 0 0 - - - 0.05 0.05 0.381 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - -0.33 -0.35 0.9525 0 0 0 + -0.16 0.16 0.9525 0 0 0 0.05 0.05 0.381 @@ -218,6 +204,29 @@ 0 0 0 1 + + + + 0.0 + + 0.16 0.16 1.143 0 0 0 + + + + + 0.0 + + + -0.16 0.16 1.143 0 0 0 + + + + + 0.0 + + + 0.16 -0.16 1.143 0 0 0 + 0 0 0 0.736 0 0 0 From 5d09c1aca428f57da8c7c5b54145aea441c714a4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 22 Mar 2023 13:08:25 -0400 Subject: [PATCH 410/758] still a hack, but can start working on controlling orientation --- examples/franka/franka_controller_params.yaml | 4 ++-- examples/franka/franka_osc_controller.cc | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 195fd31f18..b495df9e76 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -37,11 +37,11 @@ EndEffectorKd: MidLinkW: [0, 0, 0, 0, 0, 0, - 0, 0, 5] + 0, 0, 200] MidLinkKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 1 ] + 0, 0, 30 ] MidLinkKd: [ 0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 7d6f2fd442..0bb3062618 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -122,15 +122,15 @@ int DoMain(int argc, char* argv[]) { "mid_link", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant); - mid_link_position_tracking_data->AddPointToTrack("panda_link5"); + mid_link_position_tracking_data->AddPointToTrack("panda_link4"); auto wrist_relative_tracking_data = std::make_unique( "wrist_down_target", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant, mid_link_position_tracking_data.get(), end_effector_position_tracking_data.get()); Eigen::Vector3d wrist_down_target = Eigen::Vector3d::Zero(); - wrist_down_target(1) = -0.3; - wrist_down_target(2) = 0.2; + wrist_down_target(1) = 0.0; + wrist_down_target(2) = 0.0; auto end_effector_orientation_tracking_data = std::make_unique( From 314493a7a8d30e9c93677f08a53dbc7384016a88 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Mar 2023 12:55:00 -0400 Subject: [PATCH 411/758] fixing bindings --- bindings/pydairlib/multibody/multibody_py.cc | 5 +- .../pydairlib/systems/robot_lcm_systems_py.cc | 36 ++++++++-- .../Cassie/run_osc_standing_controller.cc | 6 +- examples/franka/franka_sim.cc | 6 +- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/franka_visualizer.cc | 4 +- examples/franka/urdf/plate.sdf | 34 +++++++++ systems/robot_lcm_systems.cc | 71 ++++++++++++++----- systems/robot_lcm_systems.h | 6 +- 9 files changed, 135 insertions(+), 35 deletions(-) create mode 100644 examples/franka/urdf/plate.sdf diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index d535516068..e01009d6a3 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -31,9 +31,10 @@ PYBIND11_MODULE(multibody, m) { py::arg("builder"), py::arg("scene_graph"), py::arg("trajectory")); m.def("MakeNameToPositionsMap", - &dairlib::multibody::MakeNameToPositionsMap, py::arg("plant")) + py::overload_cast&>(&dairlib::multibody::MakeNameToPositionsMap), + py::arg("plant")) .def("MakeNameToVelocitiesMap", - &dairlib::multibody::MakeNameToVelocitiesMap, + py::overload_cast&>(&dairlib::multibody::MakeNameToVelocitiesMap), py::arg("plant")) .def("MakeNameToActuatorsMap", &dairlib::multibody::MakeNameToActuatorsMap, diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index faf28fba7b..696769516f 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -21,26 +21,48 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::class_>( m, "RobotOutputReceiver") - .def(py::init&>()); + .def(py::init&>()) + .def(py::init&, + drake::multibody::ModelInstanceIndex>()); py::class_>( m, "RobotInputReceiver") .def(py::init&>()); py::class_>( m, "RobotOutputSender") - .def(py::init&, bool>()) - .def("get_input_port_state", &RobotOutputSender::get_input_port_state, py_rvp::reference_internal) - .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort, py_rvp::reference_internal) - .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu, py_rvp::reference_internal); + .def(py::init&, bool, bool>()) + .def(py::init&, + drake::multibody::ModelInstanceIndex, + bool, bool>()) + .def("get_input_port_state", &RobotOutputSender::get_input_port_state, + py_rvp::reference_internal) + .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort, + py_rvp::reference_internal) + .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu, + py_rvp::reference_internal); py::class_>( m, "RobotCommandSender") .def(py::init&>()); m.def("AddActuationRecieverAndStateSenderLcm", - &dairlib::systems::AddActuationRecieverAndStateSenderLcm, + py::overload_cast*, + const MultibodyPlant&, + drake::systems::lcm::LcmInterfaceSystem*, std::string, + std::string, double, + drake::multibody::ModelInstanceIndex, bool, double>( + &dairlib::systems::AddActuationRecieverAndStateSenderLcm), + py::arg("builder"), py::arg("plant"), py::arg("lcm"), + py::arg("actuator_channel"), py::arg("state_channel"), + py::arg("publish_rate"), py::arg("model_instance"), + py::arg("publish_efforts"), py::arg("actuator_delay")); + m.def("AddActuationRecieverAndStateSenderLcm", + py::overload_cast*, + const MultibodyPlant&, + drake::systems::lcm::LcmInterfaceSystem*, std::string, + std::string, double, bool, double>( + &dairlib::systems::AddActuationRecieverAndStateSenderLcm), py::arg("builder"), py::arg("plant"), py::arg("lcm"), py::arg("actuator_channel"), py::arg("state_channel"), py::arg("publish_rate"), py::arg("publish_efforts"), py::arg("actuator_delay")); - } } // namespace pydairlib diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 005586575c..a00ae60e4b 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -66,7 +66,7 @@ DEFINE_string( DEFINE_double(cost_weight_multiplier, 1.0, "A cosntant times with cost weight of OSC traj tracking"); DEFINE_double(height, .8, "The initial COM height (m)"); -DEFINE_string(osc_gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", +DEFINE_string(gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", "Filepath containing osc_gains"); DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", "Filepath containing qp settings"); @@ -107,9 +107,9 @@ int DoMain(int argc, char* argv[]) { drake::yaml::LoadYamlOptions yaml_options; yaml_options.allow_yaml_with_no_cpp = true; OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osc_gains_filename), {}, {}, yaml_options); + FindResourceOrThrow(FLAGS_gains_filename), {}, {}, yaml_options); OSCStandingGains osc_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osc_gains_filename)); + FindResourceOrThrow(FLAGS_gains_filename)); // Create Lcm subsriber for lcmt_target_standing_height auto target_height_receiver = builder.AddSystem( diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 3148e05e09..57310c0202 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -75,8 +75,8 @@ int DoMain(int argc, char* argv[]) { dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), "table1"); drake::multibody::ModelInstanceIndex tray_index = - parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); + parser.AddModelFromFile(FindResourceOrThrow( + "examples/franka/urdf/plate.sdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); @@ -161,7 +161,7 @@ int DoMain(int argc, char* argv[]) { q[plant.num_positions() - 7] = 1; q[plant.num_positions() - 1] = 1.25; - q[plant.num_positions() - 3] = 0.75; + q[plant.num_positions() - 3] = 0.8; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 8602de20ba..3f5959a2a7 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -7,4 +7,4 @@ actuator_delay: 0.005 dt: 0.0001 realtime_rate: 1.0 -q_init_franka: [-0.8, 1.7, 1.8, -1.4, 1.4, 1.4, -0.56] +q_init_franka: [-0.8, 1.6, 1.3, -1.4, 1.6, 1.3, -0.56] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 4cf6392a3f..ecddcf4721 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -77,8 +77,8 @@ int do_main(int argc, char* argv[]) { dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), "table1"); drake::multibody::ModelInstanceIndex tray_index = - parser.AddModelFromFile(drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/objects/open_top_box.urdf")); + parser.AddModelFromFile(FindResourceOrThrow( + "examples/franka/urdf/plate.sdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); diff --git a/examples/franka/urdf/plate.sdf b/examples/franka/urdf/plate.sdf new file mode 100644 index 0000000000..79e12df640 --- /dev/null +++ b/examples/franka/urdf/plate.sdf @@ -0,0 +1,34 @@ + + + + + + 1 + + + 1 + 0 + 0 + 1 + 0 + 1 + + + + + + 0.5 0.5 0.02 + + + + + + + 0.5 0.5 0.02 + + + + + + \ No newline at end of file diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index dc83fda3c2..4011a45c9a 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -30,14 +30,11 @@ using systems::OutputVector; RobotOutputReceiver::RobotOutputReceiver( const drake::multibody::MultibodyPlant& plant) { - num_positions_ = plant.num_positions(); num_velocities_ = plant.num_velocities(); num_efforts_ = plant.num_actuators(); - position_index_map_ = - multibody::MakeNameToPositionsMap(plant); - velocity_index_map_ = - multibody::MakeNameToVelocitiesMap(plant); + position_index_map_ = multibody::MakeNameToPositionsMap(plant); + velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); model_instance_ = drake::multibody::ModelInstanceIndex(-1); positions_start_idx_ = 0; @@ -47,8 +44,7 @@ RobotOutputReceiver::RobotOutputReceiver( drake::Value{}); this->DeclareVectorOutputPort( "x, u, t", - OutputVector(plant.num_positions(), - plant.num_velocities(), + OutputVector(plant.num_positions(), plant.num_velocities(), plant.num_actuators()), &RobotOutputReceiver::CopyOutput); } @@ -56,7 +52,6 @@ RobotOutputReceiver::RobotOutputReceiver( RobotOutputReceiver::RobotOutputReceiver( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance) { - model_instance_ = model_instance; num_positions_ = plant.num_positions(model_instance); num_velocities_ = plant.num_velocities(model_instance); @@ -66,8 +61,12 @@ RobotOutputReceiver::RobotOutputReceiver( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant, model_instance); - positions_start_idx_ = plant.get_joint(plant.GetJointIndices(model_instance).front()).position_start(); - velocities_start_idx_ = plant.get_joint(plant.GetJointIndices(model_instance).front()).velocity_start(); + positions_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + velocities_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); this->DeclareAbstractInputPort("lcmt_robot_output", drake::Value{}); @@ -138,23 +137,63 @@ void RobotOutputReceiver::InitializeSubscriberPositions( state_msg.velocity.resize(num_positions_); for (int i = 0; i < num_positions_; i++) { - state_msg.position_names.at(i) = ordered_position_names.at(i); - state_msg.position.at(i) = 0; + state_msg.position_names[i] = ordered_position_names[i]; + state_msg.position[i] = 0; } // Set quaternion w = 1, assumes drake quaternion ordering of wxyz - if (model_instance_ >= 0 && plant.HasUniqueFreeBaseBody(model_instance_)) { - state_msg.position.at(0) = 1; + for (const auto& body_idx : plant.GetFloatingBaseBodies()) { + const auto& body = plant.get_body(body_idx); + if (body.has_quaternion_dofs()) { + state_msg.position[body.floating_positions_start()] = 1; + } } for (int i = 0; i < num_velocities_; i++) { - state_msg.velocity.at(i) = 0; - state_msg.velocity_names.at(i) = ordered_velocity_names[i]; + state_msg.velocity[i] = 0; + state_msg.velocity_names[i] = ordered_velocity_names[i]; } } /*--------------------------------------------------------------------------*/ // methods implementation for RobotOutputSender. +RobotOutputSender::RobotOutputSender( + const drake::multibody::MultibodyPlant& plant, + const bool publish_efforts, const bool publish_imu) + : publish_efforts_(publish_efforts), publish_imu_(publish_imu) { + num_positions_ = plant.num_positions(); + num_velocities_ = plant.num_velocities(); + num_efforts_ = plant.num_actuators(); + + position_index_map_ = multibody::MakeNameToPositionsMap(plant); + velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); + effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + + ordered_position_names_ = + multibody::ExtractOrderedNamesFromMap(position_index_map_); + ordered_velocity_names_ = + multibody::ExtractOrderedNamesFromMap(velocity_index_map_); + ordered_effort_names_ = + multibody::ExtractOrderedNamesFromMap(effort_index_map_); + + state_input_port_ = + this->DeclareVectorInputPort( + "x", BasicVector(num_positions_ + num_velocities_)) + .get_index(); + if (publish_efforts_) { + effort_input_port_ = + this->DeclareVectorInputPort("u", BasicVector(num_efforts_)) + .get_index(); + } + if (publish_imu_) { + imu_input_port_ = + this->DeclareVectorInputPort("imu_acceleration", BasicVector(3)) + .get_index(); + } + + this->DeclareAbstractOutputPort("lcmt_robot_output", + &RobotOutputSender::Output); +} RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 5182539cbc..ad5e8bbdd3 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -62,7 +62,11 @@ class RobotOutputSender : public drake::systems::LeafSystem { explicit RobotOutputSender( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance_index = - drake::multibody::default_model_instance(), + drake::multibody::default_model_instance(), + const bool publish_efforts = false, const bool publish_imu = false); + + explicit RobotOutputSender( + const drake::multibody::MultibodyPlant& plant, const bool publish_efforts = false, const bool publish_imu = false); const drake::systems::InputPort& get_input_port_state() const { From dbb570f01d3bf31e21d5294e877bee4c4109817b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Mar 2023 14:17:08 -0400 Subject: [PATCH 412/758] working on more realistic sim --- examples/franka/franka_controller_params.h | 3 + examples/franka/franka_controller_params.yaml | 7 +- examples/franka/franka_osc_controller.cc | 25 +++++- examples/franka/franka_sim.cc | 2 +- .../franka/systems/end_effector_trajectory.cc | 4 +- examples/franka/urdf/plate.sdf | 8 +- examples/franka/urdf/table.sdf | 89 ++++++++++--------- multibody/multibody_utils.cc | 8 +- multibody/multibody_utils.h | 2 +- .../controllers/osc/options_tracking_data.cc | 2 +- .../controllers/osc/options_tracking_data.h | 2 +- systems/robot_lcm_systems.cc | 38 ++++++-- systems/robot_lcm_systems.h | 3 + 13 files changed, 118 insertions(+), 75 deletions(-) diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index 4b6790fb10..4534ad48dd 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -13,6 +13,8 @@ struct FrankaControllerParams : OSCGains { std::string radio_channel; std::string osc_debug_channel; + double end_effector_acceleration; + std::vector EndEffectorW; std::vector EndEffectorKp; std::vector EndEffectorKd; @@ -41,6 +43,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(radio_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); + a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index b495df9e76..15590a5059 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -12,6 +12,7 @@ w_lambda: 0.1 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 +end_effector_acceleration: 10.0 # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] @@ -37,15 +38,15 @@ EndEffectorKd: MidLinkW: [0, 0, 0, 0, 0, 0, - 0, 0, 200] + 0, 0, 1] MidLinkKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 30 ] + 0, 0, 100 ] MidLinkKd: [ 0, 0, 0, 0, 0, 0, - 0, 0, 1 ] + 0, 0, 20 ] EndEffectorRotW: [ 10, 0, 0, 0, 10, 0, diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 0bb3062618..4614c0a3d2 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -34,6 +34,7 @@ using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using Eigen::MatrixXd; using Eigen::VectorXd; +using Eigen::Vector3d; using multibody::MakeNameToPositionsMap; using multibody::MakeNameToVelocitiesMap; @@ -42,6 +43,9 @@ using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "Filepath containing qp settings"); DEFINE_string(controller_settings, "", "Controller settings such as channels. Attempting to minimize " "number of gflags"); @@ -57,7 +61,9 @@ int DoMain(int argc, char* argv[]) { "examples/franka/franka_controller_params.yaml"); OSCGains gains = drake::yaml::LoadYamlFile( FindResourceOrThrow("examples/franka/franka_controller_params.yaml"), {}, {}, yaml_options); - + drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)) + .osqp_options; DiagramBuilder builder; drake::multibody::MultibodyPlant plant(0.0); @@ -117,17 +123,26 @@ int DoMain(int argc, char* argv[]) { controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); end_effector_position_tracking_data->AddPointToTrack("paddle"); - auto mid_link_position_tracking_data = + const VectorXd& bound = controller_params.end_effector_acceleration * Vector3d::Ones(); + end_effector_position_tracking_data->SetCmdAccelerationBounds( + -bound, bound); + auto end_effector_position_tracking_data_for_rel = + std::make_unique( + "end_effector_target", controller_params.K_p_end_effector, + controller_params.K_d_end_effector, controller_params.W_end_effector, + plant, plant); + end_effector_position_tracking_data_for_rel->AddPointToTrack("paddle"); + auto mid_link_position_tracking_data_for_rel = std::make_unique( "mid_link", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant); - mid_link_position_tracking_data->AddPointToTrack("panda_link4"); + mid_link_position_tracking_data_for_rel->AddPointToTrack("panda_link4"); auto wrist_relative_tracking_data = std::make_unique( "wrist_down_target", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, - plant, plant, mid_link_position_tracking_data.get(), end_effector_position_tracking_data.get()); + plant, plant, mid_link_position_tracking_data_for_rel.get(), end_effector_position_tracking_data_for_rel.get()); Eigen::Vector3d wrist_down_target = Eigen::Vector3d::Zero(); wrist_down_target(1) = 0.0; wrist_down_target(2) = 0.0; @@ -150,6 +165,8 @@ int DoMain(int argc, char* argv[]) { orientation_target); osc->SetContactFriction(0.4); + osc->SetOsqpSolverOptions(solver_options); + osc->Build(); builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 57310c0202..0a60131bb9 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -161,7 +161,7 @@ int DoMain(int argc, char* argv[]) { q[plant.num_positions() - 7] = 1; q[plant.num_positions() - 1] = 1.25; - q[plant.num_positions() - 3] = 0.8; + q[plant.num_positions() - 3] = 0.68; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index d7c1fc6e70..cc9187cb30 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -94,8 +94,8 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( double t = robot_output->get_timestamp(); double dt = 0.1; VectorXd y0 = VectorXd::Zero(3); - y0(0) = 0.7 + radio_out->channel[0] * 0.2; - y0(0) = std::clamp(y0(0), 0.0, 0.8); + y0(0) = 0.65 + radio_out->channel[0] * 0.2; + y0(0) = std::clamp(y0(0), 0.0, 0.75); y0(1) = radio_out->channel[1] * 0.2; y0(2) = 0.3 + radio_out->channel[2] * 0.2; VectorXd ydot0 = VectorXd::Zero(3); diff --git a/examples/franka/urdf/plate.sdf b/examples/franka/urdf/plate.sdf index 79e12df640..d277378197 100644 --- a/examples/franka/urdf/plate.sdf +++ b/examples/franka/urdf/plate.sdf @@ -3,7 +3,7 @@ - 1 + 10 @@ -12,20 +12,20 @@ 0 1 0 - 1 + 0.1 - 0.5 0.5 0.02 + 0.3 0.3 0.02 - 0.5 0.5 0.02 + 0.3 0.3 0.02 diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf index 5343f54e0c..a95df66b3d 100644 --- a/examples/franka/urdf/table.sdf +++ b/examples/franka/urdf/table.sdf @@ -163,53 +163,54 @@ - 0.16 0.16 0.9525 0 0 0 - - - 0.05 0.05 0.381 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - + 0.04 0.12 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + - 0.16 -0.16 0.9525 0 0 0 - - - 0.05 0.05 0.381 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - + 0.04 -0.12 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + - -0.16 0.16 0.9525 0 0 0 - - - 0.05 0.05 0.381 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - + -0.20 0.12 0.9525 0 0 0 + + + 0.05 0.05 0.381 + + + + 0.3 0.3 0.3 1 + 0.7 0.7 0.7 1 + 0.01 0.01 0.01 1 + 0 0 0 1 + + + 0.0 - - 0.16 0.16 1.143 0 0 0 + + + 0.04 0.12 0.9525 0 0 0 @@ -217,7 +218,7 @@ 0.0 - -0.16 0.16 1.143 0 0 0 + 0.04 -0.12 0.9525 0 0 0 @@ -225,7 +226,7 @@ 0.0 - 0.16 -0.16 1.143 0 0 0 + -0.20 0.12 0.9525 0 0 0 0 diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 4b06cca85a..9bf1d45f73 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -158,12 +158,10 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, } /// Get the ordered names from a NameTo___Map -vector ExtractOrderedNamesFromMap(const map& map) { -// vector names(map.size()); - vector names; +vector ExtractOrderedNamesFromMap(const map& map, int index_start) { + vector names(map.size()); for (const auto& entry : map) { -// std::cout << "index: " << entry.second << std::endl; - names.push_back(entry.first); + names[entry.second - index_start] = entry.first; } return names; } diff --git a/multibody/multibody_utils.h b/multibody/multibody_utils.h index 14cc00e932..b0050ba7e4 100644 --- a/multibody/multibody_utils.h +++ b/multibody/multibody_utils.h @@ -73,7 +73,7 @@ void AddFlatTerrain(drake::multibody::MultibodyPlant* plant, /// Get the ordered names from a NameTo___Map std::vector ExtractOrderedNamesFromMap( - const std::map& map); + const std::map& map, int index_start = 0); /// Given a MultibodyPlant, builds a map from position name to position index template diff --git a/systems/controllers/osc/options_tracking_data.cc b/systems/controllers/osc/options_tracking_data.cc index e982888c04..490c3ee87f 100644 --- a/systems/controllers/osc/options_tracking_data.cc +++ b/systems/controllers/osc/options_tracking_data.cc @@ -195,7 +195,7 @@ void OptionsTrackingData::SetTimerVaryingFeedForwardAccelMultiplier( ff_accel_multiplier_traj_ = ff_accel_multiplier_traj; } -void OptionsTrackingData::SetCmdAccelerationBounds(Eigen::VectorXd& lb, Eigen::VectorXd& ub){ +void OptionsTrackingData::SetCmdAccelerationBounds(const Eigen::VectorXd& lb, const Eigen::VectorXd& ub){ DRAKE_DEMAND(lb.size() == n_ydot_); DRAKE_DEMAND(ub.size() == n_ydot_); yddot_cmd_lb_ = lb; diff --git a/systems/controllers/osc/options_tracking_data.h b/systems/controllers/osc/options_tracking_data.h index eff035991c..21485e226d 100644 --- a/systems/controllers/osc/options_tracking_data.h +++ b/systems/controllers/osc/options_tracking_data.h @@ -42,7 +42,7 @@ class OptionsTrackingData : public OscTrackingData { std::shared_ptr> ff_accel_multiplier_traj); - void SetCmdAccelerationBounds(Eigen::VectorXd& lb, Eigen::VectorXd& ub); + void SetCmdAccelerationBounds(const Eigen::VectorXd& lb, const Eigen::VectorXd& ub); void SetViewFrame(std::shared_ptr> view_frame) { view_frame_ = view_frame; diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 4011a45c9a..da54bf60b9 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -123,9 +123,11 @@ void RobotOutputReceiver::InitializeSubscriberPositions( state_msg.utime = context.get_time() * 1e6; std::vector ordered_position_names = - multibody::ExtractOrderedNamesFromMap(position_index_map_); + multibody::ExtractOrderedNamesFromMap(position_index_map_, + positions_start_idx_); std::vector ordered_velocity_names = - multibody::ExtractOrderedNamesFromMap(velocity_index_map_); + multibody::ExtractOrderedNamesFromMap(velocity_index_map_, + velocities_start_idx_); std::vector ordered_effort_names = multibody::ExtractOrderedNamesFromMap(effort_index_map_); @@ -142,10 +144,17 @@ void RobotOutputReceiver::InitializeSubscriberPositions( } // Set quaternion w = 1, assumes drake quaternion ordering of wxyz - for (const auto& body_idx : plant.GetFloatingBaseBodies()) { - const auto& body = plant.get_body(body_idx); - if (body.has_quaternion_dofs()) { - state_msg.position[body.floating_positions_start()] = 1; + if (model_instance_ != drake::multibody::ModelInstanceIndex(-1)) { + if (plant.HasUniqueFreeBaseBody(model_instance_)) { + state_msg.position.at(0) = 1; + } + } else { + for (const auto& body_idx : plant.GetFloatingBaseBodies()) { + const auto& body = plant.get_body(body_idx); + if (body.has_quaternion_dofs()) { + state_msg.position.at(body.floating_positions_start()) = 1; + } + std::cout << "Here: " << std::endl; } } @@ -169,6 +178,10 @@ RobotOutputSender::RobotOutputSender( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + model_instance_ = drake::multibody::ModelInstanceIndex(-1); + positions_start_idx_ = 0; + velocities_start_idx_ = 0; + ordered_position_names_ = multibody::ExtractOrderedNamesFromMap(position_index_map_); ordered_velocity_names_ = @@ -199,7 +212,7 @@ RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance, const bool publish_efforts, const bool publish_imu) - : publish_efforts_(publish_efforts), publish_imu_(publish_imu) { + : model_instance_(model_instance), publish_efforts_(publish_efforts), publish_imu_(publish_imu) { num_positions_ = plant.num_positions(model_instance); num_velocities_ = plant.num_velocities(model_instance); num_efforts_ = plant.num_actuators(); @@ -210,10 +223,17 @@ RobotOutputSender::RobotOutputSender( multibody::MakeNameToVelocitiesMap(plant, model_instance); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + positions_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + velocities_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); + ordered_position_names_ = - multibody::ExtractOrderedNamesFromMap(position_index_map_); + multibody::ExtractOrderedNamesFromMap(position_index_map_, positions_start_idx_); ordered_velocity_names_ = - multibody::ExtractOrderedNamesFromMap(velocity_index_map_); + multibody::ExtractOrderedNamesFromMap(velocity_index_map_, velocities_start_idx_); ordered_effort_names_ = multibody::ExtractOrderedNamesFromMap(effort_index_map_); diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index ad5e8bbdd3..2abd106ddd 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -86,6 +86,9 @@ class RobotOutputSender : public drake::systems::LeafSystem { void Output(const drake::systems::Context& context, dairlib::lcmt_robot_output* output) const; + drake::multibody::ModelInstanceIndex model_instance_; + int positions_start_idx_; + int velocities_start_idx_; int num_positions_; int num_velocities_; int num_efforts_; From c039e9064ddc586ec493acbaefa20490951215ea Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Mar 2023 14:41:22 -0400 Subject: [PATCH 413/758] using more realistic parameters --- examples/Cassie/cassie_xbox_remote.py | 3 +-- examples/franka/franka_sim.cc | 2 +- examples/franka/urdf/plate.sdf | 8 ++++---- examples/franka/urdf/table.sdf | 6 +++--- 4 files changed, 9 insertions(+), 10 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index a0bb6dfece..d1d382899d 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -113,8 +113,7 @@ def main(): # Send LCM message radio_msg = dairlib.lcmt_radio_out() radio_msg.channel[0] = -joystick.get_axis(1) - - radio_msg.channel[1] = -joystick.get_axis(0) + radio_msg.channel[1] = -joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(3) radio_msg.channel[3] = joystick.get_axis(2) radio_msg.channel[4] = radio_channel_4_pos diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 0a60131bb9..8660659ef8 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -160,7 +160,7 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; q[plant.num_positions() - 7] = 1; - q[plant.num_positions() - 1] = 1.25; + q[plant.num_positions() - 1] = 1.2; q[plant.num_positions() - 3] = 0.68; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/urdf/plate.sdf b/examples/franka/urdf/plate.sdf index d277378197..65872b9ec4 100644 --- a/examples/franka/urdf/plate.sdf +++ b/examples/franka/urdf/plate.sdf @@ -3,16 +3,16 @@ - 10 + 2 - 1 + 0.015 0 0 - 1 + 0.015 0 - 0.1 + 0.03 diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf index a95df66b3d..5ba471065a 100644 --- a/examples/franka/urdf/table.sdf +++ b/examples/franka/urdf/table.sdf @@ -210,7 +210,7 @@ 0.0 - 0.04 0.12 0.9525 0 0 0 + 0.04 0.12 1.143 0 0 0 @@ -218,7 +218,7 @@ 0.0 - 0.04 -0.12 0.9525 0 0 0 + 0.04 -0.12 1.143 0 0 0 @@ -226,7 +226,7 @@ 0.0 - -0.20 0.12 0.9525 0 0 0 + -0.20 0.12 1.143 0 0 0 0 From 80b1a26904672d0be719535efc1cd65ad3da4435 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 23 Mar 2023 15:01:45 -0400 Subject: [PATCH 414/758] wider tray --- examples/Cassie/cassie_xbox_remote.py | 4 ++-- examples/franka/franka_controller_params.yaml | 6 ++--- examples/franka/urdf/franka_box.urdf | 4 ++-- examples/franka/urdf/plate.sdf | 22 +++++++++++++++---- 4 files changed, 25 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index d1d382899d..e9a95e02fb 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -114,8 +114,8 @@ def main(): radio_msg = dairlib.lcmt_radio_out() radio_msg.channel[0] = -joystick.get_axis(1) radio_msg.channel[1] = -joystick.get_axis(0) - radio_msg.channel[2] = -joystick.get_axis(3) - radio_msg.channel[3] = joystick.get_axis(2) + radio_msg.channel[2] = -joystick.get_axis(4) + radio_msg.channel[3] = joystick.get_axis(3) radio_msg.channel[4] = radio_channel_4_pos radio_msg.channel[5] = radio_channel_5_pos radio_msg.channel[6] = radio_channel_6_pos diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 15590a5059..06a0882544 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -56,6 +56,6 @@ EndEffectorRotKp: 0, 500, 0, 0, 0, 500 ] EndEffectorRotKd: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 10 ] + [ 40, 0, 0, + 0, 40, 0, + 0, 0, 40 ] diff --git a/examples/franka/urdf/franka_box.urdf b/examples/franka/urdf/franka_box.urdf index 4fcde94629..415b6e8176 100644 --- a/examples/franka/urdf/franka_box.urdf +++ b/examples/franka/urdf/franka_box.urdf @@ -513,8 +513,8 @@ - - + + diff --git a/examples/franka/urdf/plate.sdf b/examples/franka/urdf/plate.sdf index 65872b9ec4..ac1ffd8d59 100644 --- a/examples/franka/urdf/plate.sdf +++ b/examples/franka/urdf/plate.sdf @@ -7,27 +7,41 @@ - 0.015 + 0.06 0 0 0.015 0 - 0.03 + 0.075 - 0.3 0.3 0.02 + 0.3 0.6 0.02 - 0.3 0.3 0.02 + 0.3 0.6 0.02 + + + + 100 + + 0.4 + 0.4 + From 172a07c264b9d36b0cb9b29094e1329202265a8f Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 28 Mar 2023 12:00:39 -0400 Subject: [PATCH 415/758] working on adding c3 --- examples/franka/BUILD.bazel | 22 + examples/franka/franka_c3_controller.cc | 96 ++++ examples/franka/franka_c3_controller_params.h | 84 ++++ .../franka/franka_c3_controller_params.yaml | 9 + examples/franka/franka_controller_params.h | 2 + examples/franka/franka_controller_params.yaml | 1 + examples/franka/franka_osc_controller.cc | 60 +-- lcmtypes/lcmt_timestamped_saved_traj.lcm | 10 + solvers/BUILD.bazel | 42 ++ solvers/c3.cc | 358 +++++++++++++++ solvers/c3.h | 137 ++++++ solvers/c3_miqp.cc | 143 ++++++ solvers/c3_miqp.h | 47 ++ solvers/c3_options.h | 10 + solvers/lcs.cc | 43 ++ solvers/lcs.h | 52 +++ solvers/lcs_factory.cc | 409 ++++++++++++++++++ solvers/lcs_factory.h | 51 +++ solvers/osqp_solver_options.h | 73 +++- systems/controllers/BUILD.bazel | 19 +- systems/controllers/c3_controller.cc | 55 +++ systems/controllers/c3_controller.h | 55 +++ systems/trajectory_optimization/BUILD.bazel | 15 + .../lcm_trajectory_systems.cc | 47 ++ .../lcm_trajectory_systems.h | 41 ++ 25 files changed, 1830 insertions(+), 51 deletions(-) create mode 100644 examples/franka/franka_c3_controller.cc create mode 100644 examples/franka/franka_c3_controller_params.h create mode 100644 examples/franka/franka_c3_controller_params.yaml create mode 100644 lcmtypes/lcmt_timestamped_saved_traj.lcm create mode 100644 solvers/c3.cc create mode 100644 solvers/c3.h create mode 100644 solvers/c3_miqp.cc create mode 100644 solvers/c3_miqp.h create mode 100644 solvers/c3_options.h create mode 100644 solvers/lcs.cc create mode 100644 solvers/lcs.h create mode 100644 solvers/lcs_factory.cc create mode 100644 solvers/lcs_factory.h create mode 100644 systems/controllers/c3_controller.cc create mode 100644 systems/controllers/c3_controller.h create mode 100644 systems/trajectory_optimization/lcm_trajectory_systems.cc create mode 100644 systems/trajectory_optimization/lcm_trajectory_systems.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index c59a4dda02..8096917444 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -45,6 +45,28 @@ cc_binary( deps = [ ":franka_controller_params", "//examples/franka/systems:end_effector_trajectory", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_c3_controller", + srcs = ["franka_c3_controller.cc"], + data = [ + ":trifinger_urdf", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_controller_params", + "//examples/franka/systems:end_effector_trajectory", + "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc new file mode 100644 index 0000000000..733d5ced6e --- /dev/null +++ b/examples/franka/franka_c3_controller.cc @@ -0,0 +1,96 @@ + +#include +#include + +#include "examples/franka/franka_controller_params.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "lcm/lcm_trajectory.h" + +#include "drake/common/yaml/yaml_io.h" +#include "drake/common/find_resource.h" +#include "drake/multibody/parsing/parser.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "examples/franka/systems/end_effector_trajectory.h" + +namespace dairlib { + +using drake::math::RigidTransform; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; +using Eigen::VectorXd; +using Eigen::Vector3d; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; + + +DEFINE_string(controller_settings, "", + "Controller settings such as channels. Attempting to minimize " + "number of gflags"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // load parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaControllerParams controller_params = + drake::yaml::LoadYamlFile( + "examples/franka/franka_controller_params.yaml"); + DiagramBuilder builder; + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + + drake::multibody::MultibodyPlant plant_franka(0.0); + Parser parser(&plant_franka, nullptr); + parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + RigidTransform X_WI = RigidTransform::Identity(); + plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), + X_WI); + auto state_receiver = builder.AddSystem(plant_franka); + auto trajectory_sender = + builder.AddSystem(LcmPublisherSystem::Make( + controller_params.c3_channel, + &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + + + + + + +// auto controller = builder.AddSystem( +// plant_franka, plant_f, plant_franka, *context, +// context_f, *context_franka, *plant_ad, +// *plant_ad_f, *context_ad, *context_ad_f, +// scene_graph, *diagram_f, contact_geoms, +// num_friction_directions, mu, Q, R, G, U, +// xdesired, pp); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_c3_controller")); + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, + controller_params.state_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h new file mode 100644 index 0000000000..09fcd50a04 --- /dev/null +++ b/examples/franka/franka_c3_controller_params.h @@ -0,0 +1,84 @@ +#pragma once + +#include "yaml-cpp/yaml.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +using Eigen::MatrixXd; + +struct FrankaControllerParams { + std::string state_channel; + std::string controller_channel; + std::string radio_channel; + std::string osc_debug_channel; + + double end_effector_acceleration; + + std::vector EndEffectorW; + std::vector EndEffectorKp; + std::vector EndEffectorKd; + std::vector MidLinkW; + std::vector MidLinkKp; + std::vector MidLinkKd; + std::vector EndEffectorRotW; + std::vector EndEffectorRotKp; + std::vector EndEffectorRotKd; + + MatrixXd W_end_effector; + MatrixXd K_p_end_effector; + MatrixXd K_d_end_effector; + MatrixXd W_mid_link; + MatrixXd K_p_mid_link; + MatrixXd K_d_mid_link; + MatrixXd W_end_effector_rot; + MatrixXd K_p_end_effector_rot; + MatrixXd K_d_end_effector_rot; + + template + void Serialize(Archive* a) { + OSCGains::Serialize(a); + + a->Visit(DRAKE_NVP(state_channel)); + a->Visit(DRAKE_NVP(controller_channel)); + a->Visit(DRAKE_NVP(radio_channel)); + a->Visit(DRAKE_NVP(osc_debug_channel)); + a->Visit(DRAKE_NVP(end_effector_acceleration)); + a->Visit(DRAKE_NVP(EndEffectorW)); + a->Visit(DRAKE_NVP(EndEffectorKp)); + a->Visit(DRAKE_NVP(EndEffectorKd)); + a->Visit(DRAKE_NVP(MidLinkW)); + a->Visit(DRAKE_NVP(MidLinkKp)); + a->Visit(DRAKE_NVP(MidLinkKd)); + a->Visit(DRAKE_NVP(EndEffectorRotW)); + a->Visit(DRAKE_NVP(EndEffectorRotKp)); + a->Visit(DRAKE_NVP(EndEffectorRotKd)); + + W_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorW.data(), 3, 3); + K_p_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorKp.data(), 3, 3); + K_d_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorKd.data(), 3, 3); + W_mid_link = Eigen::Map< + Eigen::Matrix>( + this->MidLinkW.data(), 3, 3); + K_p_mid_link = Eigen::Map< + Eigen::Matrix>( + this->MidLinkKp.data(), 3, 3); + K_d_mid_link = Eigen::Map< + Eigen::Matrix>( + this->MidLinkKd.data(), 3, 3); + W_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotW.data(), 3, 3); + K_p_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotKp.data(), 3, 3); + K_d_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotKd.data(), 3, 3); + } +}; \ No newline at end of file diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml new file mode 100644 index 0000000000..3b8eea245e --- /dev/null +++ b/examples/franka/franka_c3_controller_params.yaml @@ -0,0 +1,9 @@ + +mu: 1 # changes need to be consistent with urdf +mu_plate: 1 +R: 0.01 # torque cost in xyz +G: 0.01 +U_default: 1 +U_pos_vel: 10 # first 19 diag elements of U +U_u: 1 # last 3 diag elements of U +dt: 0.015 diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index 4534ad48dd..ba016ac43f 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -12,6 +12,7 @@ struct FrankaControllerParams : OSCGains { std::string controller_channel; std::string radio_channel; std::string osc_debug_channel; + std::string c3_channel; double end_effector_acceleration; @@ -43,6 +44,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(radio_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); + a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 06a0882544..8d1230993a 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -3,6 +3,7 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT radio_channel: CASSIE_VIRTUAL_RADIO osc_debug_channel: OSC_DEBUG_FRANKA +c3_channel: C3_TRAJECTORY w_input: 0.00 w_input_reg: 0.0001 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 4614c0a3d2..526e9983bb 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -1,8 +1,10 @@ -#include #include +#include #include "examples/franka/franka_controller_params.h" +#include "examples/franka/systems/end_effector_trajectory.h" +#include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" @@ -13,15 +15,14 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "drake/common/yaml/yaml_io.h" #include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" -#include "examples/franka/systems/end_effector_trajectory.h" namespace dairlib { @@ -33,8 +34,8 @@ using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using Eigen::MatrixXd; -using Eigen::VectorXd; using Eigen::Vector3d; +using Eigen::VectorXd; using multibody::MakeNameToPositionsMap; using multibody::MakeNameToVelocitiesMap; @@ -60,10 +61,12 @@ int DoMain(int argc, char* argv[]) { drake::yaml::LoadYamlFile( "examples/franka/franka_controller_params.yaml"); OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow("examples/franka/franka_controller_params.yaml"), {}, {}, yaml_options); - drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)) - .osqp_options; + FindResourceOrThrow("examples/franka/franka_controller_params.yaml"), {}, + {}, yaml_options); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)) + .osqp_options; DiagramBuilder builder; drake::multibody::MultibodyPlant plant(0.0); @@ -79,9 +82,8 @@ int DoMain(int argc, char* argv[]) { VectorXd gear_ratios(plant.num_actuators()); gear_ratios << 25, 25, 25, 25, 25, 25, 25; std::vector motor_joint_names = { - "panda_motor1", "panda_motor2", "panda_motor3", - "panda_motor4", "panda_motor5", "panda_motor6", - "panda_motor7"}; + "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", + "panda_motor5", "panda_motor6", "panda_motor7"}; for (int i = 0; i < rotor_inertias.size(); ++i) { auto& joint_actuator = plant.get_mutable_joint_actuator( drake::multibody::JointActuatorIndex(i)); @@ -96,6 +98,9 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant); + auto trajectory_receiver = + builder.AddSystem(LcmSubscriberSystem::Make( + controller_params.c3_channel, &lcm)); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( controller_params.controller_channel, &lcm, @@ -111,7 +116,8 @@ int DoMain(int argc, char* argv[]) { plant, plant, plant_context.get(), plant_context.get(), false); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( - controller_params.osc_debug_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); + controller_params.osc_debug_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); osc->SetAccelerationCostWeights(gains.W_acceleration); osc->SetInputCostWeights(gains.W_input_regularization); @@ -123,9 +129,9 @@ int DoMain(int argc, char* argv[]) { controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); end_effector_position_tracking_data->AddPointToTrack("paddle"); - const VectorXd& bound = controller_params.end_effector_acceleration * Vector3d::Ones(); - end_effector_position_tracking_data->SetCmdAccelerationBounds( - -bound, bound); + const VectorXd& bound = + controller_params.end_effector_acceleration * Vector3d::Ones(); + end_effector_position_tracking_data->SetCmdAccelerationBounds(-bound, bound); auto end_effector_position_tracking_data_for_rel = std::make_unique( "end_effector_target", controller_params.K_p_end_effector, @@ -135,29 +141,31 @@ int DoMain(int argc, char* argv[]) { auto mid_link_position_tracking_data_for_rel = std::make_unique( "mid_link", controller_params.K_p_mid_link, - controller_params.K_d_mid_link, controller_params.W_mid_link, - plant, plant); + controller_params.K_d_mid_link, controller_params.W_mid_link, plant, + plant); mid_link_position_tracking_data_for_rel->AddPointToTrack("panda_link4"); auto wrist_relative_tracking_data = std::make_unique( "wrist_down_target", controller_params.K_p_mid_link, - controller_params.K_d_mid_link, controller_params.W_mid_link, - plant, plant, mid_link_position_tracking_data_for_rel.get(), end_effector_position_tracking_data_for_rel.get()); + controller_params.K_d_mid_link, controller_params.W_mid_link, plant, + plant, mid_link_position_tracking_data_for_rel.get(), + end_effector_position_tracking_data_for_rel.get()); Eigen::Vector3d wrist_down_target = Eigen::Vector3d::Zero(); wrist_down_target(1) = 0.0; wrist_down_target(2) = 0.0; auto end_effector_orientation_tracking_data = std::make_unique( - "end_effector_orientation_target", controller_params.K_p_end_effector_rot, - controller_params.K_d_end_effector_rot, controller_params.W_end_effector_rot, - plant, plant); + "end_effector_orientation_target", + controller_params.K_p_end_effector_rot, + controller_params.K_d_end_effector_rot, + controller_params.W_end_effector_rot, plant, plant); end_effector_orientation_tracking_data->AddFrameToTrack("paddle"); Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); orientation_target(0) = 1; -// orientation_target(2) = 1; -// orientation_target(1) = 1; -// orientation_target(3) = 0.707; + // orientation_target(2) = 1; + // orientation_target(1) = 1; + // orientation_target(3) = 0.707; osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), wrist_down_target); @@ -185,7 +193,7 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_controller")); + owned_diagram->set_name(("franka_osc_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), state_receiver, diff --git a/lcmtypes/lcmt_timestamped_saved_traj.lcm b/lcmtypes/lcmt_timestamped_saved_traj.lcm new file mode 100644 index 0000000000..7a49bd7c2b --- /dev/null +++ b/lcmtypes/lcmt_timestamped_saved_traj.lcm @@ -0,0 +1,10 @@ +package dairlib; + +/* lcmtype analog for LcmTrajectory WITH TIMESTAMP to enable using a + LcmSerializer to save/load trajectories +*/ + +struct lcmt_timestamped_saved_traj { + int64_t utime; + lcmt_saved_traj saved_traj; +} diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 6bfb84575b..70af4bdda3 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -19,6 +19,48 @@ cc_library( ], ) +cc_library( + name = "c3", + srcs = [ + "c3.cc", + "c3_miqp.cc", + ], + hdrs = [ + "c3.h", + "c3_miqp.h", + "c3_options.h", + ], + copts = [ + "-fopenmp", + ], + linkopts = [ + "-lgomp", + ], + deps = [ + ":lcs", + "//solvers:fast_osqp_solver", + "@drake//:drake_shared_library", + "@gurobi//:gurobi_cxx", + ], +) + +cc_library( + name = "lcs", + srcs = [ + "lcs.cc", + "lcs_factory.cc", + ], + hdrs = [ + "lcs.h", + "lcs_factory.h", + ], + deps = [ + "//multibody:geom_geom_collider", + "//multibody/kinematic", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "constraint_factory", srcs = [ diff --git a/solvers/c3.cc b/solvers/c3.cc new file mode 100644 index 0000000000..4ef662ceb1 --- /dev/null +++ b/solvers/c3.cc @@ -0,0 +1,358 @@ +#include "solvers/c3.h" + +#include + +#include + +#include "solvers/lcs.h" + +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/moby_lcp_solver.h" +#include "drake/solvers/osqp_solver.h" +#include "drake/solvers/solve.h" + +namespace dairlib { +namespace solvers { + +using Eigen::MatrixXd; +using Eigen::VectorXd; +using std::vector; + +using drake::solvers::MathematicalProgram; +using drake::solvers::MathematicalProgramResult; +using drake::solvers::SolutionResult; +using drake::solvers::SolverOptions; + +using drake::solvers::OsqpSolver; +using drake::solvers::OsqpSolverDetails; +using drake::solvers::Solve; + +C3::C3(const LCS& LCS, const vector& Q, const vector& R, + const vector& G, const vector& U, + const vector& xdesired, const C3Options& options, + const std::vector& warm_start_delta, + const std::vector& warm_start_binary, + const std::vector& warm_start_x, + const std::vector& warm_start_lambda, + const std::vector& warm_start_u, bool warm_start) + : A_(LCS.A_), + B_(LCS.B_), + D_(LCS.D_), + d_(LCS.d_), + E_(LCS.E_), + F_(LCS.F_), + H_(LCS.H_), + c_(LCS.c_), + Q_(Q), + R_(R), + U_(U), + G_(G), + xdesired_(xdesired), + options_(options), + N_((LCS.A_).size()), + n_((LCS.A_)[0].cols()), + m_((LCS.D_)[0].cols()), + k_((LCS.B_)[0].cols()), + hflag_(H_[0].isZero(0)), + prog_(MathematicalProgram()), + OSQPoptions_(SolverOptions()), + osqp_(OsqpSolver()) { + // Deep copy warm start + warm_start_ = warm_start; + if (warm_start_) { + warm_start_delta_.resize(warm_start_delta.size()); + for (size_t i = 0; i < warm_start_delta.size(); i++) { + warm_start_delta_[i] = warm_start_delta[i]; + } + warm_start_binary_.resize(warm_start_binary.size()); + for (size_t i = 0; i < warm_start_binary.size(); i++) { + warm_start_binary_[i] = warm_start_binary[i]; + } + warm_start_x_.resize(warm_start_x.size()); + for (size_t i = 0; i < warm_start_x.size(); i++) { + warm_start_x_[i] = warm_start_x[i]; + } + warm_start_lambda_.resize(warm_start_lambda.size()); + for (size_t i = 0; i < warm_start_lambda.size(); i++) { + warm_start_lambda_[i] = warm_start_lambda[i]; + } + warm_start_u_.resize(warm_start_u.size()); + for (size_t i = 0; i < warm_start_u.size(); i++) { + warm_start_u_[i] = warm_start_u[i]; + } + } + + x_ = vector(); + u_ = vector(); + lambda_ = vector(); + + for (int i = 0; i < N_ + 1; i++) { + x_.push_back(prog_.NewContinuousVariables(n_, "x" + std::to_string(i))); + if (i < N_) { + u_.push_back(prog_.NewContinuousVariables(k_, "k" + std::to_string(i))); + lambda_.push_back( + prog_.NewContinuousVariables(m_, "lambda" + std::to_string(i))); + } + } + + MatrixXd LinEq(n_, 2 * n_ + k_ + m_); + LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); + + for (int i = 0; i < N_; i++) { + LinEq.block(0, 0, n_, n_) = A_.at(i); + LinEq.block(0, n_, n_, k_) = B_.at(i); + LinEq.block(0, n_ + k_, n_, m_) = D_.at(i); + + prog_.AddLinearEqualityConstraint( + LinEq, -d_.at(i), {x_.at(i), u_.at(i), lambda_.at(i), x_.at(i + 1)}); + } + + for (int i = 0; i < N_ + 1; i++) { + prog_.AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * xdesired_.at(i), + x_.at(i), 1); + if (i < N_) { + prog_.AddQuadraticCost(R_.at(i) * 2, VectorXd::Zero(k_), u_.at(i), 1); + } + } + + OSQPoptions_.SetOption(OsqpSolver::id(), "verbose", 0); + // OSQPoptions_.SetOption(OsqpSolver::id(), "ebs_abs", 1e-7); + // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); + // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); + // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-6); + OSQPoptions_.SetOption(OsqpSolver::id(), "max_iter", 30); // 30 + prog_.SetSolverOptions(OSQPoptions_); +} + +VectorXd C3::Solve(const VectorXd& x0, vector& delta, + vector& w) { + vector Gv = G_; + VectorXd z; + + for (int i = 0; i < options_.admm_iter - 1; i++) { + // std::cout << "Iteration" << i << std::endl; + + z = ADMMStep(x0, &delta, &w, &Gv); + // std::cout << "new delta" << i << std::endl; + // std::cout << delta.at(0).segment(n_,m_) << std::endl; + // std::cout << "w" << i << std::endl; + // std::cout << w.at(0) << std::endl; + } + + vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); + for (int i = 0; i < N_; i++) { + WD.at(i) = delta.at(i) - w.at(i); + } + + vector zfin = SolveQP(x0, Gv, WD); + + z = zfin[0]; + + // std::cout << "contact prediction" << std::endl; + // std::cout << zfin[0].segment(n_, m_) << std::endl; + + // std::cout << "violation" << std::endl; + // std::cout << delta.at(0) << std::endl; + + // std::cout << "delta_force" << std::endl; + // std::cout << delta.at(0).segment(n_,m_) << std::endl; + // + // std::cout << "delta_displace" << std::endl; + // std::cout << delta.at(0).segment(0,n_) << std::endl; + + // VectorXd hold = delta.at(0).segment(n_,m_); + // VectorXd hold = z.segment(n_,m_); + + // double count = 0; + // + // for (int i = 3; i < 5; i++) { + // count = count + hold(i); + // } + // + // if ( count >= 0.001){ + // std::cout << "guessing_contact" << std::endl; + // } + + // std::cout << "w" << std::endl; + // std::cout << w.at(0).segment(n_+3,3) << std::endl; + + // std::cout << "input" << std::endl; + // std::cout << z.segment(n_+m_, k_) << std::endl; + + // std::cout << "contact prediction" << std::endl; + // std::cout << z.segment(n_, m_) << std::endl; + + // std::cout << "prediction state" << std::endl; + // std::cout << z.segment(0, n_) << std::endl; + + return z.segment(n_ + m_, k_); +} + +VectorXd C3::ADMMStep(const VectorXd& x0, vector* delta, + vector* w, vector* Gv) { + vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); + + for (int i = 0; i < N_; i++) { + WD.at(i) = delta->at(i) - w->at(i); + } + + vector z = SolveQP(x0, *Gv, WD); + + vector ZW(N_, VectorXd::Zero(n_ + m_ + k_)); + for (int i = 0; i < N_; i++) { + ZW[i] = w->at(i) + z[i]; + } + + if (U_[0].isZero(0) == 0) { + vector Uv = U_; + + *delta = SolveProjection(Uv, ZW); + } else { + *delta = SolveProjection(*Gv, ZW); + } + + for (int i = 0; i < N_; i++) { + w->at(i) = w->at(i) + z[i] - delta->at(i); + w->at(i) = w->at(i) / options_.rho_scale; + + Gv->at(i) = Gv->at(i) * options_.rho_scale; + } + + return z[0]; +} + +vector C3::SolveQP(const VectorXd& x0, vector& G, + vector& WD) { + for (auto& constraint : constraints_) { + prog_.RemoveConstraint(constraint); + } + constraints_.clear(); + + constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); + + if (hflag_ == 1) { + drake::solvers::MobyLCPSolver LCPSolver; + VectorXd lambda0; + LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); + constraints_.push_back(prog_.AddLinearConstraint(lambda_[0] == lambda0)); + } + + for (auto& cost : costs_) { + prog_.RemoveCost(cost); + } + costs_.clear(); + + for (int i = 0; i < N_ + 1; i++) { + if (i < N_) { + costs_.push_back(prog_.AddQuadraticCost( + G.at(i).block(0, 0, n_, n_) * 2, + -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), x_.at(i), + 1)); + costs_.push_back(prog_.AddQuadraticCost( + G.at(i).block(n_, n_, m_, m_) * 2, + -2 * G.at(i).block(n_, n_, m_, m_) * WD.at(i).segment(n_, m_), + lambda_.at(i), 1)); + costs_.push_back( + prog_.AddQuadraticCost(G.at(i).block(n_ + m_, n_ + m_, k_, k_) * 2, + -2 * G.at(i).block(n_ + m_, n_ + m_, k_, k_) * + WD.at(i).segment(n_ + m_, k_), + u_.at(i), 1)); + } + } + + // /// initialize decision variables to warm start + // if (warm_start_){ + // for (int i = 0; i < N_; i++){ + // prog_.SetInitialGuess(x_[i], warm_start_x_[i]); + // prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[i]); + // prog_.SetInitialGuess(u_[i], warm_start_u_[i]); + // } + // prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); + // } + + MathematicalProgramResult result = osqp_.Solve(prog_); + VectorXd xSol = result.GetSolution(x_[0]); + vector zz(N_, VectorXd::Zero(n_ + m_ + k_)); + + for (int i = 0; i < N_; i++) { + zz.at(i).segment(0, n_) = result.GetSolution(x_[i]); + zz.at(i).segment(n_, m_) = result.GetSolution(lambda_[i]); + zz.at(i).segment(n_ + m_, k_) = result.GetSolution(u_[i]); + + if (warm_start_) { + // update warm start parameters + warm_start_x_[i] = result.GetSolution(x_[i]); + warm_start_lambda_[i] = result.GetSolution(lambda_[i]); + warm_start_u_[i] = result.GetSolution(u_[i]); + } + } + if (warm_start_) warm_start_x_[N_] = result.GetSolution(x_[N_]); + + return zz; +} + +void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double& Lowerbound, + double& Upperbound, int& constraint) { + if (constraint == 1) { + for (int i = 1; i < N_; i++) { + userconstraints_.push_back( + prog_.AddLinearConstraint(A, Lowerbound, Upperbound, x_.at(i))); + } + } + + if (constraint == 2) { + for (int i = 0; i < N_; i++) { + userconstraints_.push_back( + prog_.AddLinearConstraint(A, Lowerbound, Upperbound, u_.at(i))); + } + } + + if (constraint == 3) { + for (int i = 0; i < N_; i++) { + userconstraints_.push_back( + prog_.AddLinearConstraint(A, Lowerbound, Upperbound, lambda_.at(i))); + } + } +} + +void C3::RemoveConstraints() { + for (auto& userconstraint : userconstraints_) { + prog_.RemoveConstraint(userconstraint); + } + userconstraints_.clear(); +} + +vector C3::SolveProjection(vector& G, + vector& WZ) { + vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); + int i; + + if (options_.num_threads > 0) { + omp_set_dynamic(0); // Explicitly disable dynamic teams + omp_set_num_threads(options_.num_threads); // Set number of threads + } + +#pragma omp parallel for + for (i = 0; i < N_; i++) { + if (warm_start_) { + deltaProj[i] = + SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], i); + } else { + deltaProj[i] = + SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], -1); + } + } + + return deltaProj; +} + +std::vector C3::GetWarmStartX() const { return warm_start_x_; } + +std::vector C3::GetWarmStartLambda() const { + return warm_start_lambda_; +} + +std::vector C3::GetWarmStartU() const { return warm_start_u_; } + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/c3.h b/solvers/c3.h new file mode 100644 index 0000000000..5ef48f7950 --- /dev/null +++ b/solvers/c3.h @@ -0,0 +1,137 @@ +#pragma once + +#include + +#include + +#include "solvers/c3_options.h" +#include "solvers/fast_osqp_solver.h" +#include "solvers/lcs.h" + +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/osqp_solver.h" +#include "drake/solvers/solve.h" + +namespace dairlib { +namespace solvers { +class C3 { + public: + /// @param LCS LCS parameters + /// @param Q, R, G, U Cost function parameters + C3(const LCS& LCS, const std::vector& Q, + const std::vector& R, + const std::vector& G, + const std::vector& U, + const std::vector& xdesired, + const C3Options& options, + const std::vector& warm_start_delta = {}, + const std::vector& warm_start_binary = {}, + const std::vector& warm_start_x_ = {}, + const std::vector& warm_start_lambda_ = {}, + const std::vector& warm_start_u_ = {}, + bool warm_start = false); + + /// Solve the MPC problem + /// @param x0 The initial state of the system + /// @param delta A pointer to the copy variable solution + /// @param w A pointer to the scaled dual variable solution + /// @return The first control action to take, u[0] + Eigen::VectorXd Solve(const Eigen::VectorXd& x0, + std::vector& delta, + std::vector& w); + + /// Solve a single ADMM step + /// @param x0 The initial state of the system + /// @param delta The copy variables from the previous step + /// @param w The scaled dual variables from the previous step + /// @param G A pointer to the G variables from previous step + Eigen::VectorXd ADMMStep(const Eigen::VectorXd& x0, + std::vector* delta, + std::vector* w, + std::vector* G); + + /// Solve a single QP + /// @param x0 The initial state of the system + /// @param WD A pointer to the (w - delta) variables + /// @param G A pointer to the G variables from previous step + std::vector SolveQP(const Eigen::VectorXd& x0, + std::vector& G, + std::vector& WD); + + /// Solve the projection problem for all timesteps + /// @param WZ A pointer to the (z + w) variables + /// @param G A pointer to the G variables from previous step + std::vector SolveProjection( + std::vector& G, std::vector& WZ); + + /// allow users to add constraints (adds for all timesteps) + /// @param A, Lowerbound, Upperbound Lowerbound <= A^T x <= Upperbound + /// @param constraint inputconstraint, stateconstraint, forceconstraint + void AddLinearConstraint(Eigen::RowVectorXd& A, double& Lowerbound, + double& Upperbound, int& constraint); + + /// allow user to remove all constraints + void RemoveConstraints(); + + /// Get QP warm start + std::vector GetWarmStartX() const; + std::vector GetWarmStartLambda() const; + std::vector GetWarmStartU() const; + + /// Solve a single projection step + /// @param E, F, H, c LCS parameters + /// @param U A pointer to the U variables + /// @param delta_c A pointer to the copy of (z + w) variables + virtual Eigen::VectorXd SolveSingleProjection(const Eigen::MatrixXd& U, + const Eigen::VectorXd& delta_c, + const Eigen::MatrixXd& E, + const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, + const Eigen::VectorXd& c, + const int& warm_start_index) = 0; + + public: + const std::vector A_; + const std::vector B_; + const std::vector D_; + const std::vector d_; + const std::vector E_; + const std::vector F_; + const std::vector H_; + const std::vector c_; + const std::vector Q_; + const std::vector R_; + const std::vector U_; + const std::vector G_; + const std::vector xdesired_; + const C3Options options_; + const int N_; + const int n_; + const int m_; + const int k_; + const bool hflag_; + + protected: + std::vector warm_start_delta_; + std::vector warm_start_binary_; + std::vector warm_start_x_; + std::vector warm_start_lambda_; + std::vector warm_start_u_; + bool warm_start_; + + private: + drake::solvers::MathematicalProgram prog_; + drake::solvers::SolverOptions OSQPoptions_; + drake::solvers::OsqpSolver osqp_; + std::vector x_; + std::vector u_; + std::vector lambda_; + std::vector> costs_; + std::vector> + constraints_; + std::vector> + userconstraints_; +}; + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc new file mode 100644 index 0000000000..2806679faf --- /dev/null +++ b/solvers/c3_miqp.cc @@ -0,0 +1,143 @@ +#include "solvers/c3_miqp.h" + +namespace dairlib { +namespace solvers { + +using Eigen::MatrixXd; +using Eigen::VectorXd; +using std::vector; + +C3MIQP::C3MIQP(const LCS& LCS, const vector& Q, + const vector& R, const vector& G, + const vector& U, const vector& xdesired, + const C3Options& options, + const std::vector& warm_start_delta, + const std::vector& warm_start_binary, + const std::vector& warm_start_x, + const std::vector& warm_start_lambda, + const std::vector& warm_start_u, + bool warm_start) + : C3(LCS, Q, R, G, U, xdesired, options, + warm_start_delta, warm_start_binary, + warm_start_x, warm_start_lambda, + warm_start_u, warm_start), env_(true) { + + // Create an environment + env_.set("LogToConsole", "0"); + env_.set("OutputFlag", "0"); + env_.set("Threads", "2"); + env_.start(); +} + +VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, + const VectorXd& delta_c, + const MatrixXd& E, const MatrixXd& F, + const MatrixXd& H, const VectorXd& c, + const int& warm_start_index) { + // set up linear term in cost + VectorXd cost_lin = -2 * delta_c.transpose() * U; + + // set up for constraints (Ex + F \lambda + Hu + c >= 0) + MatrixXd Mcons1(m_, n_ + m_ + k_); + Mcons1 << E, F, H; + + // set up for constraints (\lambda >= 0) + MatrixXd MM1; + MM1 = MatrixXd::Zero(m_, n_); + MatrixXd MM2; + MM2 = MatrixXd::Identity(m_, m_); + MatrixXd MM3; + MM3 = MatrixXd::Zero(m_, k_); + MatrixXd Mcons2(m_, n_ + m_ + k_); + Mcons2 << MM1, MM2, MM3; + + // Create an empty model + GRBModel model = GRBModel(env_); + //model.set("FeasibilityTol", "0.01"); + //model.set("IterationLimit", "40"); + + GRBVar delta_k[n_ + m_ + k_]; + GRBVar binary[m_]; + + for (int i = 0; i < m_; i++) { + binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); + if (warm_start_index != -1) { + binary[i].set(GRB_DoubleAttr_Start, warm_start_binary_[warm_start_index](i)); + } + } + + for (int i = 0; i < n_ + m_ + k_; i++) { + delta_k[i] = model.addVar(-10000.0, 10000.0, 0.0, GRB_CONTINUOUS); + if (warm_start_index != -1) { + delta_k[i].set(GRB_DoubleAttr_Start, warm_start_delta_[warm_start_index](i)); + } + } + + GRBQuadExpr obj = 0; + + for (int i = 0; i < n_ + m_ + k_; i++) { + obj.addTerm(cost_lin(i), delta_k[i]); + + for (int j = 0; j < n_ + m_ + k_; j++) { + obj.addTerm(U(i, j), delta_k[i], delta_k[j]); + } + } + + model.setObjective(obj, GRB_MINIMIZE); + + int M = 100000; // big M variable + double coeff[n_ + m_ + k_]; + + for (int i = 0; i < m_; i++) { + GRBLinExpr cexpr = 0; + + /// convert VectorXd to double + for (int j = 0; j < n_ + m_ + k_; j++) { + coeff[j] = Mcons2.row(i)(j); + } + + cexpr.addTerms(coeff, delta_k, n_ + m_ + k_); + model.addConstr(cexpr >= 0); + model.addConstr(cexpr <= M * (1 - binary[i])); + + GRBLinExpr cexpr2 = 0; + + /// convert VectorXd to double + for (int j = 0; j < n_ + m_ + k_; j++) { + coeff[j] = Mcons1.row(i)(j); + } + + cexpr2.addTerms(coeff, delta_k, n_ + m_ + k_); + model.addConstr(cexpr2 + c(i) >= 0); + model.addConstr(cexpr2 + c(i) <= M * binary[i]); + } + + model.optimize(); + + VectorXd delta_kc(n_ + m_ + k_); + VectorXd binaryc(m_); + for (int i = 0; i < n_ + m_ + k_; i++) { + delta_kc(i) = delta_k[i].get(GRB_DoubleAttr_X); + } + for (int i = 0; i < m_; i++){ + binaryc(i) = binary[i].get(GRB_DoubleAttr_X); + } + + if (warm_start_index != -1){ + warm_start_delta_[warm_start_index] = delta_kc; + warm_start_binary_[warm_start_index] = binaryc; + } + + return delta_kc; +} + +std::vector C3MIQP::GetWarmStartDelta() const{ + return warm_start_delta_; +} + +std::vector C3MIQP::GetWarmStartBinary() const{ + return warm_start_binary_; +} + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/c3_miqp.h b/solvers/c3_miqp.h new file mode 100644 index 0000000000..9707a105bb --- /dev/null +++ b/solvers/c3_miqp.h @@ -0,0 +1,47 @@ +#pragma once + +#include + +#include + +#include "gurobi_c++.h" +#include "solvers/c3.h" +#include "solvers/lcs.h" + +namespace dairlib { +namespace solvers { + +class C3MIQP : public C3 { + public: + /// Default constructor for time-varying LCS + C3MIQP(const LCS& LCS, const std::vector& Q, + const std::vector& R, + const std::vector& G, + const std::vector& U, + const std::vector& xdesired, + const C3Options& options, + const std::vector& warm_start_delta = {}, + const std::vector& warm_start_binary = {}, + const std::vector& warm_start_x = {}, + const std::vector& warm_start_lambda = {}, + const std::vector& warm_start_u = {}, + bool warm_start = false); + + /// Virtual projection method + Eigen::VectorXd SolveSingleProjection(const Eigen::MatrixXd& U, + const Eigen::VectorXd& delta_c, + const Eigen::MatrixXd& E, + const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, + const Eigen::VectorXd& c, + const int& warm_start_index = -1); + std::vector GetWarmStartDelta() const; + std::vector GetWarmStartBinary() const; + + + private: + GRBEnv env_; +}; + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/c3_options.h b/solvers/c3_options.h new file mode 100644 index 0000000000..8919f78fc1 --- /dev/null +++ b/solvers/c3_options.h @@ -0,0 +1,10 @@ +#pragma once + +struct C3Options { + // Hyperparameters + int admm_iter = 2; // total number of ADMM iterations //2 + float rho = 0.1; // inital value of the rho parameter + float rho_scale = 3; // scaling of rho parameter (/rho = rho_scale * /rho) //3 + int num_threads = 0; // 0 is dynamic, greater than 0 for a fixed count + int delta_option = 1; // different options for delta update +}; \ No newline at end of file diff --git a/solvers/lcs.cc b/solvers/lcs.cc new file mode 100644 index 0000000000..8a0e2851c8 --- /dev/null +++ b/solvers/lcs.cc @@ -0,0 +1,43 @@ +#include "solvers/lcs.h" + +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/moby_lcp_solver.h" +#include "drake/solvers/osqp_solver.h" +#include "drake/solvers/solve.h" + +using Eigen::MatrixXd; +using Eigen::VectorXd; +using std::vector; + +namespace dairlib { +namespace solvers { + +LCS::LCS(const vector& A, const vector& B, + const vector& D, const vector& d, + const vector& E, const vector& F, + const vector& H, const vector& c) + : A_(A), B_(B), D_(D), d_(d), E_(E), F_(F), H_(H), c_(c), N_(A.size()) {} + +LCS::LCS(const MatrixXd& A, const MatrixXd& B, const MatrixXd& D, + const VectorXd& d, const MatrixXd& E, const MatrixXd& F, + const MatrixXd& H, const VectorXd& c, const int& N) + : LCS(vector(N, A), vector(N, B), + vector(N, D), vector(N, d), + vector(N, E), vector(N, F), + vector(N, H), vector(N, c)) {} + +const VectorXd LCS::Simulate(VectorXd& x_init, VectorXd& input) { + VectorXd x_final; + // calculate force + drake::solvers::MobyLCPSolver LCPSolver; + VectorXd force; + + auto flag = LCPSolver.SolveLcpLemke(F_[0], E_[0] * x_init + c_[0] + H_[0] * input, + &force); + // update + x_final = A_[0] * x_init + B_[0] * input + D_[0] * force + d_[0]; + return x_final; +} + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/lcs.h b/solvers/lcs.h new file mode 100644 index 0000000000..2300d4c5b2 --- /dev/null +++ b/solvers/lcs.h @@ -0,0 +1,52 @@ +#pragma once + +#include + +#include + +#include "drake/common/sorted_pair.h" +#include "drake/multibody/plant/multibody_plant.h" + +namespace dairlib { +namespace solvers { +class LCS { + public: + /// Constructor for time-varying LCS + /// @param A, B, D, d Dynamics constraints x_{k+1} = A_k x_k + B_k u_k + D_k + /// \lambda_k + d_k + /// @param E, F, H, c Complementarity constraints 0 <= \lambda_k \perp E_k + /// x_k + F_k \lambda_k + H_k u_k + c_k + LCS(const std::vector& A, + const std::vector& B, + const std::vector& D, + const std::vector& d, + const std::vector& E, + const std::vector& F, + const std::vector& H, + const std::vector& c); + + /// Constructor for time-invariant LCS + LCS(const Eigen::MatrixXd& A, const Eigen::MatrixXd& B, + const Eigen::MatrixXd& D, const Eigen::VectorXd& d, + const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int& N); + + /// Simulate the system for one-step + /// @param x_init Initial x value + /// @param input Input value + const Eigen::VectorXd Simulate(Eigen::VectorXd& x_init, Eigen::VectorXd& input); + + public: + const std::vector A_; + const std::vector B_; + const std::vector D_; + const std::vector d_; + const std::vector E_; + const std::vector F_; + const std::vector H_; + const std::vector c_; + const int N_; +}; + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc new file mode 100644 index 0000000000..ba0b6636e3 --- /dev/null +++ b/solvers/lcs_factory.cc @@ -0,0 +1,409 @@ +#include "solvers/lcs_factory.h" + +#include "multibody/geom_geom_collider.h" +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "drake/solvers/moby_lcp_solver.h" + +#include "drake/math/autodiff_gradient.h" + + + +namespace dairlib { +namespace solvers { + +using std::set; +using std::vector; + +using drake::AutoDiffVecXd; +using drake::AutoDiffXd; +using drake::MatrixX; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::ExtractGradient; +using drake::math::ExtractValue; +using drake::multibody::MultibodyPlant; +using drake::systems::Context; + +using Eigen::MatrixXd; +using Eigen::VectorXd; + +std::pair LCSFactory::LinearizePlantToLCS( + const MultibodyPlant& plant, const Context& context, + const MultibodyPlant& plant_ad, + const Context& context_ad, + const vector>& contact_geoms, +int num_friction_directions, double mu, double dt, int N) { + +/// +/// First, calculate vdot and derivatives from non-contact dynamcs +/// + +int n_contacts = contact_geoms.size(); + +AutoDiffVecXd C(plant.num_velocities()); + +plant_ad.CalcBiasTerm(context_ad, &C); + +AutoDiffVecXd Bu = plant_ad.MakeActuationMatrix() * + plant_ad.get_actuation_input_port().Eval(context_ad); + +AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); + +drake::multibody::MultibodyForces f_app(plant_ad); +plant_ad.CalcForceElementsContribution(context_ad, &f_app); + + +MatrixX M(plant.num_velocities(), plant.num_velocities()); +plant_ad.CalcMassMatrix(context_ad, &M); + +// If this ldlt is slow, there are alternate formulations which avoid it +AutoDiffVecXd vdot_no_contact = + M.ldlt().solve(tau_g + f_app.generalized_forces() + Bu - C); +// Constant term in dynamics, d_vv = d + A x_0 + B u_0 +VectorXd d_vv = ExtractValue(vdot_no_contact); + +// Derivatives w.r.t. x and u, AB +MatrixXd AB_v = ExtractGradient(vdot_no_contact); + +VectorXd inp_dvv = plant.get_actuation_input_port().Eval(context); +VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + plant.num_actuators()); +x_dvv << plant.GetPositions(context), plant.GetVelocities(context), inp_dvv; +VectorXd x_dvvcomp = AB_v * x_dvv; + +VectorXd d_v = d_vv - x_dvvcomp; + + +int n_state = plant_ad.num_positions(); +int n_vel = plant_ad.num_velocities(); +int n_total = plant_ad.num_positions() + plant_ad.num_velocities(); +int n_input = plant_ad.num_actuators(); + +/////////// +AutoDiffVecXd qdot_no_contact(plant.num_positions()); + + +AutoDiffVecXd state = plant_ad.get_state_output_port().Eval(context_ad); + +AutoDiffVecXd vel = state.tail(n_vel); + +plant_ad.MapVelocityToQDot(context_ad, vel, &qdot_no_contact); + +MatrixXd AB_q = ExtractGradient(qdot_no_contact); + +MatrixXd d_q = ExtractValue(qdot_no_contact); + + +MatrixXd Nq = AB_q.block(0, n_state, n_state, n_vel); + +/// +/// Contact-related terms +/// +VectorXd phi(n_contacts); +MatrixXd J_n(n_contacts, plant.num_velocities()); +MatrixXd J_t(2 * n_contacts * num_friction_directions, + plant.num_velocities()); + +for (int i = 0; i < n_contacts; i++) { +multibody::GeomGeomCollider collider( + plant, contact_geoms[i]); // deleted num_fricton_directions (check with +// Michael about changes in geomgeom) +auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); + +phi(i) = phi_i; + +J_n.row(i) = J_i.row(0); +J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, +plant.num_velocities()) = +J_i.block(1, 0, 2 * num_friction_directions, plant.num_velocities()); +} + +auto M_ldlt = ExtractValue(M).ldlt(); +MatrixXd MinvJ_n_T = M_ldlt.solve(J_n.transpose()); +MatrixXd MinvJ_t_T = M_ldlt.solve(J_t.transpose()); + +//float dt = 0.1; +auto n_contact_vars = 2 * n_contacts + + 2 * n_contacts * num_friction_directions; + +MatrixXd A(n_total, n_total); +MatrixXd B(n_total, n_input); +MatrixXd D(n_total, n_contact_vars); +VectorXd d(n_total); +MatrixXd E(n_contact_vars, n_total); +MatrixXd F(n_contact_vars, n_contact_vars); +MatrixXd H(n_contact_vars, n_input); +VectorXd c(n_contact_vars); + +MatrixXd AB_v_q = AB_v.block(0, 0, n_vel, n_state); +MatrixXd AB_v_v = AB_v.block(0, n_state, n_vel, n_vel); +MatrixXd AB_v_u = AB_v.block(0, n_total, n_vel, n_input); + +A.block(0, 0, n_state, n_state) = +MatrixXd::Identity(n_state, n_state) + dt * dt * Nq * AB_v_q; +A.block(0, n_state, n_state, n_vel) = dt * Nq + dt * dt * Nq * AB_v_v; +A.block(n_state, 0, n_vel, n_state) = dt * AB_v_q; +A.block(n_state, n_state, n_vel, n_vel) = +dt * AB_v_v + MatrixXd::Identity(n_vel, n_vel); + +B.block(0, 0, n_state, n_input) = dt * dt * Nq * AB_v_u; +B.block(n_state, 0, n_vel, n_input) = dt * AB_v_u; + +D = MatrixXd::Zero(n_total, n_contact_vars); +D.block(0, 2 * n_contacts, n_state, +2 * n_contacts * num_friction_directions) = +dt * dt * Nq * MinvJ_t_T; +D.block(n_state, 2 * n_contacts, n_vel, +2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; + +D.block(0, n_contacts, n_state, n_contacts ) = dt * dt * Nq * MinvJ_n_T; + +D.block(n_state, n_contacts, n_vel, n_contacts ) = dt * MinvJ_n_T; + +d.head(n_state) = dt * dt * Nq * d_v; +d.tail(n_vel) = dt * d_v; + +E = MatrixXd::Zero(n_contact_vars, n_total); +E.block(n_contacts, 0, n_contacts, n_state) = +dt * dt * J_n * AB_v_q; +E.block(2 * n_contacts, 0, +2 * n_contacts * num_friction_directions, n_state) = +dt * J_t * AB_v_q; +E.block(n_contacts, n_state, n_contacts, n_vel) = +dt * J_n + dt * dt * J_n * AB_v_v; +E.block(2 * n_contacts, n_state, +2 * n_contacts * num_friction_directions, n_vel) = +J_t + dt * J_t * AB_v_v; + +MatrixXd E_t = MatrixXd::Zero( + n_contacts, 2 * n_contacts * num_friction_directions); +for (int i = 0; i < n_contacts; i++) { +E_t.block(i, i * (2 * num_friction_directions), 1, +2 * num_friction_directions) = +MatrixXd::Ones(1, 2 * num_friction_directions); +}; + + +F = MatrixXd::Zero(n_contact_vars, n_contact_vars); +F.block(0, n_contacts, n_contacts, n_contacts) = +mu * MatrixXd::Identity(n_contacts, n_contacts); +F.block(0, 2 * n_contacts, n_contacts, +2 * n_contacts * num_friction_directions) = -E_t; + +F.block(n_contacts, n_contacts, n_contacts, n_contacts ) = +dt * dt * J_n * MinvJ_n_T; +F.block(n_contacts, 2 * n_contacts, n_contacts, +2 * n_contacts * num_friction_directions) = +dt * dt * J_n * MinvJ_t_T; + +F.block(2 * n_contacts, 0, +2 * n_contacts * num_friction_directions, + n_contacts) = E_t.transpose(); + +F.block(2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions, + n_contacts) = dt * J_t * MinvJ_n_T; +F.block(2 * n_contacts, 2 * n_contacts, +2 * n_contacts * num_friction_directions, +2 * n_contacts * num_friction_directions) = +dt * J_t * MinvJ_t_T; +H = MatrixXd::Zero(n_contact_vars, n_input); +H.block(n_contacts, 0, n_contacts, n_input) = +dt * dt * J_n * AB_v_u; +H.block(2 * n_contacts, 0, +2 * n_contacts * num_friction_directions, n_input) = +dt * J_t * AB_v_u; + +c = VectorXd::Zero(n_contact_vars); +c.segment(n_contacts, n_contacts) = +phi + dt * dt * J_n * d_v; + +c.segment(2 * n_contacts, +2 * n_contacts * num_friction_directions) = +J_t * dt * d_v; + +auto Dn = D.squaredNorm(); +auto An = A.squaredNorm(); +auto AnDn = An / Dn; + +D *= AnDn; +E /= AnDn; +c /= AnDn; +H /= AnDn; + +LCS system(A, B, D, d, E, F, H, c, N); + + +//////// +// ///check LCS predictions +// VectorXd inp = plant.get_actuation_input_port().Eval(context); +// +// //std::cout << inp << std::endl; +// +// VectorXd x0(plant.num_positions() + plant.num_velocities()); +// x0 << plant.GetPositions(context), plant.GetVelocities(context); +//// +//// std::cout << "real" << std::endl; +//// std::cout << plant_ad.GetVelocities(context_ad) << std::endl; +//// +// VectorXd asd = system.Simulate(x0 ,inp); +// +// // calculate force +// drake::solvers::MobyLCPSolver LCPSolver; +// VectorXd force; +// +// VectorXd x_init = x0; +// VectorXd input = inp; +// +// +// auto flag = LCPSolver.SolveLcpLemke(F, E * x_init + c + H * input, +// &force); +// +// //VectorXd x_final = A * x_init + B * input + D * force + d; +// +// //if (flag == 1){ +// +// std::cout << "LCS force estimate" << std::endl; +// std::cout << force << std::endl; +// std::cout << "LCS force estimate" << std::endl; +//// +//// +//// std::cout << "Jn * v" << std::endl; +//// std::cout << J_n * x_final.tail(9) << std::endl; +//// std::cout << "Jn * v" << std::endl; +// +//// std::cout << "gap" << std::endl; +//// std::cout << E * x_init + c + H * input + F * force << std::endl; +//// std::cout << "gap" << std::endl; +// +// std::cout << "phi" << std::endl; +// std::cout << phi << std::endl; +// std::cout << "phi" << std::endl; +// +// +// } + +// +// std::cout << "prediction" << std::endl; +// std::cout << asd.tail(15) << std::endl; + +std::pair ret (system, AnDn); + +return ret; + +} + + +LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, + set inactive_lambda_inds) { + + vector remaining_inds; + + // Assumes constant number of contacts per index + int n_lambda = other.F_[0].rows(); + + // Need to solve for lambda_active in terms of remaining elements + // Build temporary [F1, F2] by eliminating rows for inactive + for (int i = 0; i < n_lambda; i++) { + // active/inactive must be exclusive + DRAKE_ASSERT(!active_lambda_inds.count(i) || + !inactive_lambda_inds.count(i)); + + // In C++20, could use contains instead of count + if (!active_lambda_inds.count(i) && + !inactive_lambda_inds.count(i)) { + remaining_inds.push_back(i); + } + } + + int n_remaining = remaining_inds.size(); + int n_active = active_lambda_inds.size(); + + vector A, B, D, E, F, H; + vector d, c; + + // Build selection matrices: + // S_a selects active indices + // S_r selects remaining indices + + MatrixXd S_a = MatrixXd::Zero(n_active, n_lambda); + MatrixXd S_r = MatrixXd::Zero(n_remaining, n_lambda); + + for (int i = 0; i < n_remaining; i++) { + S_r(i, remaining_inds[i]) = 1; + } + { + int i = 0; + for (auto ind_j : active_lambda_inds) { + S_a(i, ind_j) = 1; + i++; + } + } + + + for (int k = 0; k < other.N_; k++) { + Eigen::BDCSVD svd; + svd.setThreshold(1e-5); + svd.compute(S_a * other.F_[k] * S_a.transpose(), + Eigen::ComputeFullU | Eigen::ComputeFullV); + + // F_active likely to be low-rank due to friction, but that should be OK + // MatrixXd res = svd.solve(F_ar); + + // Build new complementarity constraints + // F_a_inv = pinv(S_a * F * S_a^T) + // 0 <= \lambda_k \perp E_k x_k + F_k \lambda_k + H_k u_k + c_k + // 0 = S_a *(E x + F S_a^T \lambda_a + F S_r^T \lambda_r + H_k u_k + c_k) + // \lambda_a = -F_a_inv * (S_a F S_r^T * lambda_r + S_a E x + S_a H u + S_a c) + // + // 0 <= \lambda_r \perp S_r (I - F S_a^T F_a_inv S_a) E x + ... + // S_r (I - F S_a^T F_a_inv S_a) F S_r^T \lambda_r + ... + // S_r (I - F S_a^T F_a_inv S_a) H u + ... + // S_r (I - F S_a^T F_a_inv S_a) c + // + // Calling L = S_r (I - F S_a^T F_a_inv S_a)S_r * other.D_[k] + // E_k = L E + // F_k = L F S_r^t + // H_k = L H + // c_k = L c + // std::cout << S_r << std::endl << std::endl; + // std::cout << other.F_[k] << std::endl << std::endl; + // std::cout << other.F_[k] << std::endl << std::endl; + // auto tmp = S_r * (MatrixXd::Identity(n_lambda, n_lambda) - + // other.F_[k] * S_a.transpose()); + MatrixXd L = S_r * (MatrixXd::Identity(n_lambda, n_lambda) - + other.F_[k] * S_a.transpose() * svd.solve(S_a)); + MatrixXd E_k = L * other.E_[k]; + MatrixXd F_k = L * other.F_[k] * S_r.transpose(); + MatrixXd H_k = L * other.H_[k]; + MatrixXd c_k = L * other.c_[k]; + + // Similarly, + // A_k = A - D * S_a^T * F_a_inv * S_a * E + // B_k = B - D * S_a^T * F_a_inv * S_a * H + // D_k = D * S_r^T - D * S_a^T * F_a_inv * S_a F S_r^T + // d_k = d - D * S_a^T F_a_inv * S_a * c + // + // Calling P = D * S_a^T * F_a_inv * S_a + // + // A_k = A - P E + // B_k = B - P H + // D_k = S_r D - P S_r^T + // d_k = d - P c + MatrixXd P = other.D_[k] * S_a.transpose() * svd.solve(S_a); + MatrixXd A_k = other.A_[k] - P * other.E_[k]; + MatrixXd B_k = other.B_[k] - P * other.H_[k]; + MatrixXd D_k = other.D_[k] * S_r.transpose() - P * S_r.transpose(); + MatrixXd d_k = other.d_[k] - P * other.c_[k]; + E.push_back(E_k); + F.push_back(F_k); + H.push_back(H_k); + c.push_back(c_k); + A.push_back(A_k); + B.push_back(B_k); + D.push_back(D_k); + d.push_back(d_k); + } + return LCS(A, B, D, d, E, F, H, c); +} + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h new file mode 100644 index 0000000000..75b05a1eb1 --- /dev/null +++ b/solvers/lcs_factory.h @@ -0,0 +1,51 @@ +#pragma once + +#include + +#include "solvers/lcs.h" + +namespace dairlib { +namespace solvers { + +class LCSFactory { + public: + /// Build a time-invariant LCS, linearizing a MultibodyPlant + /// Contacts are specified by the pairs in contact_geoms. Each elemnt + /// in the contact_geoms vector defines a collision. + /// This method also uses two copies of the Context, one for double and one + /// for AutoDiff. Given that Contexts can be expensive to create, this is + /// preferred to extracting the double-version from the AutoDiff. + /// + /// TODO: add variant allowing for different frictional properties per + /// contact + /// + /// @param plant The standard MultibodyPlant + /// @param context The context about which to linearize (double) + /// @param plant_ad An AutoDiffXd templated plant for gradient calculation + /// @param context The context about which to linearize (AutoDiffXd) + /// @param contact_geoms + /// @param num_friction faces + /// @param mu + /// @oaram dt The timestep for discretization + /// @param N + static std::pair LinearizePlantToLCS( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const drake::multibody::MultibodyPlant& plant_ad, + const drake::systems::Context& context_ad, + const std::vector>& + contact_geoms, + int num_friction_directions, double mu, double dt, int N); + + /// Create an LCS by fixing some modes from another LCS + /// Ignores generated inequalities that correspond to these modes, but + /// these could be returned via pointer if useful + /// + /// @param active_lambda_inds The indices for lambda thta must be non-zero + /// @param inactive_lambda_inds The indices for lambda that must be 0 + static LCS FixSomeModes(const LCS& other, std::set active_lambda_inds, + std::set inactive_lambda_inds); +}; + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/osqp_solver_options.h b/solvers/osqp_solver_options.h index 0a0f6e6e92..33a4b504fd 100644 --- a/solvers/osqp_solver_options.h +++ b/solvers/osqp_solver_options.h @@ -2,7 +2,7 @@ #include "drake/solvers/solver_options.h" -namespace dairlib::solvers{ +namespace dairlib::solvers { /// Convenience struct for parsing solver options struct DairOsqpSolverOptions { @@ -55,28 +55,53 @@ struct DairOsqpSolverOptions { a->Visit(DRAKE_NVP(adaptive_rho_fraction)); a->Visit(DRAKE_NVP(time_limit)); - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "verbose", verbose); //NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "rho", rho); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "sigma", sigma); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "max_iter", max_iter); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_abs", eps_abs); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_rel", eps_rel); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_prim_inf", eps_prim_inf); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_dual_inf", eps_dual_inf); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "alpha", alpha); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "linsys_solver", linsys_solver); //NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "delta", delta); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "polish", polish); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "polish_refine_iter", polish_refine_iter); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "scaled_termination", scaled_termination); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "check_termination", check_termination); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "warm_start", warm_start); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "scaling", scaling); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "adaptive_rho", adaptive_rho); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "adaptive_rho_interval", adaptive_rho_interval); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "adaptive_rho_tolerance", adaptive_rho_tolerance); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "adaptive_rho_fraction", adaptive_rho_fraction); // NOLINT - osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "time_limit", time_limit); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "verbose", + verbose); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "rho", + rho); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "sigma", + sigma); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "max_iter", + max_iter); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_abs", + eps_abs); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_rel", + eps_rel); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_prim_inf", + eps_prim_inf); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "eps_dual_inf", + eps_dual_inf); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "alpha", + alpha); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "linsys_solver", + linsys_solver); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "delta", + delta); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "polish", + polish); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), + "polish_refine_iter", polish_refine_iter); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), + "scaled_termination", scaled_termination); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), + "check_termination", check_termination); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "warm_start", + warm_start); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "scaling", + scaling); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "adaptive_rho", + adaptive_rho); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), + "adaptive_rho_interval", + adaptive_rho_interval); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), + "adaptive_rho_tolerance", + adaptive_rho_tolerance); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), + "adaptive_rho_fraction", + adaptive_rho_fraction); // NOLINT + osqp_options.SetOption(drake::solvers::OsqpSolver::id(), "time_limit", + time_limit); // NOLINT } }; -} +} // namespace dairlib::solvers diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index bbeb76e64a..a75e8fc081 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -2,7 +2,6 @@ load("@drake//tools/lint:lint.bzl", "add_lint_tests") package(default_visibility = ["//visibility:public"]) - cc_library( name = "controllers_all", srcs = [], @@ -40,6 +39,7 @@ cc_library( "@lcm", ], ) + cc_library( name = "cassie_out_to_radio", srcs = ["cassie_out_to_radio.cc"], @@ -51,6 +51,23 @@ cc_library( ], ) +cc_library( + name = "c3_controller", + srcs = [ + "c3_controller.cc", + ], + hdrs = [ + "c3_controller.h", + ], + deps = [ + "//systems/framework:vector", + "//lcmtypes:lcmt_robot", + "//solvers:c3", + "//lcm:lcm_trajectory_saver", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "linear_controller", srcs = [ diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc new file mode 100644 index 0000000000..7279a76cc0 --- /dev/null +++ b/systems/controllers/c3_controller.cc @@ -0,0 +1,55 @@ +#include "c3_controller.h" + +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" + +namespace dairlib { + +using drake::systems::BasicVector; +using Eigen::VectorXd; +using solvers::LCS; +using solvers::C3MIQP; + +namespace systems { + +C3Controller::C3Controller(LCS& lcs, C3Options c3_options) : lcs_(lcs) { + target_input_port_ = + this->DeclareVectorInputPort("desired_position", + BasicVector(2 + 16)) + .get_index(); + lcs_state_input_port_ = + this->DeclareVectorInputPort( + "x_lcs", BasicVector(10)) + .get_index(); + + std::vector x_desired = {VectorXd::Zero(3)}; + c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options); + + this->set_name("c3_controller"); + trajectory_output_port_ = + this->DeclareAbstractOutputPort("c3_output", + dairlib::lcmt_timestamped_saved_traj(), + &C3Controller::OutputTrajectory) + .get_index(); +} + +void C3Controller::OutputTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const { + const BasicVector& x_des = + *this->template EvalVectorInput(context, target_input_port_); + const BasicVector& x = + *this->template EvalVectorInput(context, lcs_state_input_port_); + // delta + // in order: + // state, forces, inputs + // initialize with zeros or current state + std::vector delta(1, VectorXd::Zero(1)); + std::vector w(1, VectorXd::Zero(1)); + c3_->Solve(x.value(), delta, w); +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h new file mode 100644 index 0000000000..800385ed0a --- /dev/null +++ b/systems/controllers/c3_controller.h @@ -0,0 +1,55 @@ +#pragma once + +#include +#include + +#include "dairlib/lcmt_saved_traj.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "lcm/lcm_trajectory.h" +#include "solvers/c3.h" +#include "solvers/c3_miqp.h" +#include "solvers/c3_options.h" +#include "solvers/lcs.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// Outputs a lcmt_timestamped_saved_traj +class C3Controller : public drake::systems::LeafSystem { + public: + explicit C3Controller(solvers::LCS& lcs, C3Options c3_options); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(target_input_port_); + } + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(lcs_state_input_port_); + } + + const drake::systems::OutputPort& get_output_port_trajectory() const { + return this->get_output_port(trajectory_output_port_); + } + + private: + void OutputTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const; + + drake::systems::InputPortIndex target_input_port_; + drake::systems::InputPortIndex lcs_state_input_port_; + drake::systems::OutputPortIndex trajectory_output_port_; + + std::unique_ptr c3_; + solvers::LCS lcs_; + + std::vector Q_; + std::vector R_; + std::vector G_; + std::vector U_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/trajectory_optimization/BUILD.bazel b/systems/trajectory_optimization/BUILD.bazel index 0926507e40..b342668af5 100644 --- a/systems/trajectory_optimization/BUILD.bazel +++ b/systems/trajectory_optimization/BUILD.bazel @@ -45,6 +45,21 @@ cc_library( ], ) +cc_library( + name = "lcm_trajectory_systems", + srcs = [ + "lcm_trajectory_systems.cc", + ], + hdrs = [ + "lcm_trajectory_systems.h", + ], + deps = [ + "//lcm:lcm_trajectory_saver", + "//common:find_resource", + "@drake//:drake_shared_library", + ], +) + cc_binary( name = "passive_constrained_pendulum_dircon", srcs = ["test/passive_constrained_pendulum_dircon.cc"], diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc new file mode 100644 index 0000000000..d77bfa10b6 --- /dev/null +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -0,0 +1,47 @@ +#include "lcm_trajectory_systems.h" + +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "common/find_resource.h" +#include + +namespace dairlib { +namespace systems { + +using drake::trajectories::PiecewisePolynomial; + +LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) + : trajectory_name_(std::move(trajectory_name)) { + trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj", + drake::Value{}) + .get_index(); + + PiecewisePolynomial traj_inst(Eigen::VectorXd(0)); + this->set_name(trajectory_name_); + trajectory_output_port_ = + this->DeclareAbstractOutputPort(trajectory_name_, traj_inst, + &LcmTrajectoryReceiver::OutputTrajectory) + .get_index(); + lcm_traj_ = LcmTrajectory(dairlib::FindResourceOrThrow(nominal_stand_path_)); + +} + +void LcmTrajectoryReceiver::OutputTrajectory( + const drake::systems::Context& context, + PiecewisePolynomial* output_trajectory) const { + if (this->EvalInputValue( + context, trajectory_input_port_)->utime > 1e-3) { + const auto& lcm_traj = + this->EvalInputValue( + context, trajectory_input_port_); + lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); + } + const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); + + *output_trajectory = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h new file mode 100644 index 0000000000..00e0a7c15f --- /dev/null +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -0,0 +1,41 @@ +#pragma once + +#include +#include + +#include "dairlib/lcmt_saved_traj.hpp" +#include "lcm/lcm_trajectory.h" + +#include "drake/systems/framework/leaf_system.h" +#include "drake/common/trajectories/piecewise_polynomial.h" + +namespace dairlib { +namespace systems { + +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and outputs it as a drake PiecewisePolynomial. +class LcmTrajectoryReceiver : public drake::systems::LeafSystem { + public: + explicit LcmTrajectoryReceiver(std::string trajectory_name); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_input_port_); + } + + const drake::systems::OutputPort& get_output_port_trajectory() const { + return this->get_output_port(trajectory_output_port_); + } + + private: + void OutputTrajectory(const drake::systems::Context& context, + drake::trajectories::PiecewisePolynomial* output_trajectory) const; + drake::systems::InputPortIndex trajectory_input_port_; + drake::systems::OutputPortIndex trajectory_output_port_; + const std::string trajectory_name_; + + mutable LcmTrajectory lcm_traj_; + std::string nominal_stand_path_ = ""; +}; + +} // namespace systems +} // namespace dairlib From edcecf2a75aec187a1dd3a2ac84e5eead29c532e Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 29 Mar 2023 10:29:48 -0400 Subject: [PATCH 416/758] compilation settings --- .bazelrc | 5 + examples/Cassie/cassie_xbox_remote.py | 18 +-- examples/franka/BUILD.bazel | 31 ++--- examples/franka/franka_c3_controller.cc | 113 +++++++++++++----- examples/franka/franka_c3_controller_params.h | 77 +++--------- examples/franka/franka_osc_controller.cc | 2 +- examples/franka/franka_sim.cc | 4 +- examples/franka/franka_visualizer.cc | 4 +- .../urdf/{franka_box.urdf => franka.urdf} | 20 +++- examples/franka/urdf/plate_end_effector.urdf | 46 +++++++ examples/franka/urdf/{plate.sdf => tray.sdf} | 6 +- solvers/c3.cc | 8 +- solvers/c3_options.h | 12 ++ solvers/lcs_factory.h | 2 +- 14 files changed, 210 insertions(+), 138 deletions(-) rename examples/franka/urdf/{franka_box.urdf => franka.urdf} (97%) create mode 100644 examples/franka/urdf/plate_end_effector.urdf rename examples/franka/urdf/{plate.sdf => tray.sdf} (95%) diff --git a/.bazelrc b/.bazelrc index 77f18fabcc..343bde59ae 100644 --- a/.bazelrc +++ b/.bazelrc @@ -53,6 +53,11 @@ build --action_env=LD_LIBRARY_PATH= # build with snopt build --define=WITH_SNOPT=ON +build --define=WITH_GUROBI=ON + +build:omp --copt=-DEIGEN_DONT_PARALLELIZE +build:omp --copt=-fopenmp +build:omp --linkopt=-fopenmp # use python3 by default build --python_path=python3 diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index e9a95e02fb..762e4ac97e 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -39,11 +39,7 @@ def unindent(self): def main(): publisher = lcm.LCM() - pygame.display.set_caption('Cassie Virtual Radio Controller') - pygame.init() - screen_size = 500 - screen = pygame.display.set_mode((screen_size, screen_size)) # Used to manage how fast the screen updates clock = pygame.time.Clock() @@ -76,13 +72,10 @@ def main(): # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands # above this, or they will be erased with this command. - screen.fill(cassie_blue) textPrint.reset() # Get the name from the OS for the controller/joystick name = joystick.get_name() - textPrint.print(screen, "Welcome! remember to make this the active \nwindow when you wish to use the remote") - textPrint.print(screen, "Controller detected: {}".format(name) ) for event in pygame.event.get(): if event.type == pygame.QUIT: # If user clicked close @@ -100,15 +93,6 @@ def main(): # print(i) # print(joystick.get_button(i)) - textPrint.print(screen, "Left Knob position: {:.2f}".format(radio_channel_4_pos)) - textPrint.print(screen, "Right Knob position: {:.2f}".format(radio_channel_5_pos)) - textPrint.print(screen, "Side dial position: {:.2f}".format(radio_channel_6_pos)) - - # ALL CODE TO DRAW SHOULD GO ABOVE THIS COMMENT - - # Go ahead and update the screen with what we've drawn. - pygame.display.flip() - # Send LCM message radio_msg = dairlib.lcmt_radio_out() @@ -120,7 +104,7 @@ def main(): radio_msg.channel[5] = radio_channel_5_pos radio_msg.channel[6] = radio_channel_6_pos - # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) + radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 8096917444..e046f6f7d9 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -4,16 +4,9 @@ package(default_visibility = ["//visibility:public"]) cc_library( - name = "trifinger_urdf", + name = "urdfs", data = glob([ - "robot_properties_fingers/urdf/**", - "robot_properties_fingers/urdf/pro/**", - "robot_properties_fingers/urdf/edu/**", - "robot_properties_fingers/meshes/**", - "robot_properties_fingers/meshes/pro/**", - "robot_properties_fingers/meshes/pro/detailed/**", - "robot_properties_fingers/meshes/edu/**", - "robot_properties_fingers/cube/**", + "urdf/**", ]), ) @@ -21,7 +14,7 @@ cc_binary( name = "franka_sim", srcs = ["franka_sim.cc"], data = [ - ":trifinger_urdf", + ":urdfs", "@drake//manipulation/models/franka_description:models", ], deps = [ @@ -39,7 +32,7 @@ cc_binary( name = "franka_osc_controller", srcs = ["franka_osc_controller.cc"], data = [ - ":trifinger_urdf", + ":urdfs", "@drake//manipulation/models/franka_description:models", ], deps = [ @@ -60,15 +53,16 @@ cc_binary( name = "franka_c3_controller", srcs = ["franka_c3_controller.cc"], data = [ - ":trifinger_urdf", + ":urdfs", "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_controller_params", + ":franka_c3_controller_params", "//examples/franka/systems:end_effector_trajectory", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", + "//systems/controllers:c3_controller", "//systems/controllers", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", @@ -81,7 +75,7 @@ cc_binary( name = "franka_visualizer", srcs = ["franka_visualizer.cc"], data = [ - ":trifinger_urdf", + ":urdfs", "@drake//manipulation/models/franka_description:models", ], deps = [ @@ -111,3 +105,12 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "franka_c3_controller_params", + hdrs = ["franka_c3_controller_params.h"], + deps = [ + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 733d5ced6e..a80fcc5261 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -1,28 +1,34 @@ -#include #include +#include -#include "examples/franka/franka_controller_params.h" +#include "examples/franka/franka_c3_controller_params.h" +#include "examples/franka/systems/end_effector_trajectory.h" +#include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/c3_controller.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "lcm/lcm_trajectory.h" -#include "drake/common/yaml/yaml_io.h" #include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/analysis/simulator.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" -#include "examples/franka/systems/end_effector_trajectory.h" namespace dairlib { +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; using drake::math::RigidTransform; +using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; @@ -30,55 +36,102 @@ using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using Eigen::MatrixXd; -using Eigen::VectorXd; + using Eigen::Vector3d; +using Eigen::VectorXd; using multibody::MakeNameToPositionsMap; using multibody::MakeNameToVelocitiesMap; - DEFINE_string(controller_settings, "", "Controller settings such as channels. Attempting to minimize " "number of gflags"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); // load parameters drake::yaml::LoadYamlOptions yaml_options; yaml_options.allow_yaml_with_no_cpp = true; - FrankaControllerParams controller_params = - drake::yaml::LoadYamlFile( + FrankaC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( "examples/franka/franka_controller_params.yaml"); - DiagramBuilder builder; - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + C3Options c3_options = + drake::yaml::LoadYamlFile(controller_params.c3_options_file); + /// - drake::multibody::MultibodyPlant plant_franka(0.0); - Parser parser(&plant_franka, nullptr); - parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + MultibodyPlant plant_franka(0.0); + Parser parser_franka(&plant_franka, nullptr); + parser_franka.AddModelFromFile("examples/franka/urdf/franka.urdf"); RigidTransform X_WI = RigidTransform::Identity(); - plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), - X_WI); - auto state_receiver = builder.AddSystem(plant_franka); + plant_franka.WeldFrames(plant_franka.world_frame(), + plant_franka.GetFrameByName("panda_link0"), X_WI); + plant_franka.Finalize(); + + /// + MultibodyPlant plant_plate(0.0); + Parser parser_plate(&plant_plate); + parser_plate.package_map().Add("franka_urdfs", "examples/franka/urdf"); + parser_plate.AddModelFromFile("examples/franka/urdf/plate_end_effector.urdf"); + parser_plate.AddModelFromFile("examples/franka/urdf/tray.sdf"); + plant_plate.Finalize(); + + std::unique_ptr> plant_plate_ad = + drake::systems::System::ToAutoDiffXd(plant_plate); + + auto plate_context = plant_plate.CreateDefaultContext(); + auto plate_context_ad = plant_plate_ad->CreateDefaultContext(); + + /// + drake::geometry::GeometryId plate_geoms = + plant_plate.GetCollisionGeometriesForBody( + plant_plate.GetBodyByName("plate"))[0]; + drake::geometry::GeometryId tray_geoms = + plant_plate.GetCollisionGeometriesForBody( + plant_plate.GetBodyByName("tray"))[0]; + // drake::geometry::GeometryId ground_geoms = + // plant_plate.GetCollisionGeometriesForBody(plant_plate.GetBodyByName("box"))[0]; + // drake::geometry::GeometryId sphere_geoms2 = + // plant_plate.GetCollisionGeometriesForBody(plant_plate.GetBodyByName("sphere2"))[0]; + std::vector contact_geoms = {plate_geoms, + tray_geoms}; + std::vector> contact_pairs; + for(int i = 0; i < contact_geoms.size(); ++i){ + for(int j = i+1; j < contact_geoms.size(); ++j){ + + } + } + contact_pairs.push_back(SortedPair(contact_geoms[0], contact_geoms[1])); + contact_pairs.push_back(SortedPair(contact_geoms[1], contact_geoms[2])); + contact_pairs.push_back(SortedPair(contact_geoms[0], contact_geoms[3])); + contact_pairs.push_back(SortedPair(contact_geoms[2], contact_geoms[3])); + contact_pairs.push_back(SortedPair(contact_geoms[1], contact_geoms[3])); + + /// + + DiagramBuilder builder; + + auto state_receiver = + builder.AddSystem(plant_franka); auto trajectory_sender = builder.AddSystem(LcmPublisherSystem::Make( - controller_params.c3_channel, - &lcm, + controller_params.c3_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto lcs = LCSFactory::LinearizePlantToLCS( + plant_plate, *plate_context, *plant_plate_ad, *plate_context_ad, + contact_pairs, controller_params.num_friction_directions, + controller_params.mu, controller_params.dt, 5); + auto controller = builder.AddSystem(lcs.first, c3_options); - - - - -// auto controller = builder.AddSystem( -// plant_franka, plant_f, plant_franka, *context, -// context_f, *context_franka, *plant_ad, -// *plant_ad_f, *context_ad, *context_ad_f, -// scene_graph, *diagram_f, contact_geoms, -// num_friction_directions, mu, Q, R, G, U, -// xdesired, pp); + // plant_franka, plant_f, plant_franka, *context, + // context_f, *context_franka, *plant_ad, + // *plant_ad_f, *context_ad, *context_ad_f, + // scene_graph, *diagram_f, contact_geoms, + // num_friction_directions, mu, Q, R, G, U, + // xdesired, pp); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index 09fcd50a04..a1a3dabf6b 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -3,82 +3,33 @@ #include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" +#include "solvers/c3_options.h" using Eigen::MatrixXd; -struct FrankaControllerParams { +struct FrankaC3ControllerParams { + std::string c3_options_file; + std::string c3_channel; std::string state_channel; - std::string controller_channel; std::string radio_channel; - std::string osc_debug_channel; - double end_effector_acceleration; - std::vector EndEffectorW; - std::vector EndEffectorKp; - std::vector EndEffectorKd; - std::vector MidLinkW; - std::vector MidLinkKp; - std::vector MidLinkKd; - std::vector EndEffectorRotW; - std::vector EndEffectorRotKp; - std::vector EndEffectorRotKd; + double mu; + double dt; + int num_friction_directions; + std::string plant_urdf; - MatrixXd W_end_effector; - MatrixXd K_p_end_effector; - MatrixXd K_d_end_effector; - MatrixXd W_mid_link; - MatrixXd K_p_mid_link; - MatrixXd K_d_mid_link; - MatrixXd W_end_effector_rot; - MatrixXd K_p_end_effector_rot; - MatrixXd K_d_end_effector_rot; template void Serialize(Archive* a) { - OSCGains::Serialize(a); - + a->Visit(DRAKE_NVP(c3_options_file)); + a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(state_channel)); - a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(radio_channel)); - a->Visit(DRAKE_NVP(osc_debug_channel)); - a->Visit(DRAKE_NVP(end_effector_acceleration)); - a->Visit(DRAKE_NVP(EndEffectorW)); - a->Visit(DRAKE_NVP(EndEffectorKp)); - a->Visit(DRAKE_NVP(EndEffectorKd)); - a->Visit(DRAKE_NVP(MidLinkW)); - a->Visit(DRAKE_NVP(MidLinkKp)); - a->Visit(DRAKE_NVP(MidLinkKd)); - a->Visit(DRAKE_NVP(EndEffectorRotW)); - a->Visit(DRAKE_NVP(EndEffectorRotKp)); - a->Visit(DRAKE_NVP(EndEffectorRotKd)); + a->Visit(DRAKE_NVP(mu)); + a->Visit(DRAKE_NVP(dt)); + a->Visit(DRAKE_NVP(num_friction_directions)); + a->Visit(DRAKE_NVP(plant_urdf)); - W_end_effector = Eigen::Map< - Eigen::Matrix>( - this->EndEffectorW.data(), 3, 3); - K_p_end_effector = Eigen::Map< - Eigen::Matrix>( - this->EndEffectorKp.data(), 3, 3); - K_d_end_effector = Eigen::Map< - Eigen::Matrix>( - this->EndEffectorKd.data(), 3, 3); - W_mid_link = Eigen::Map< - Eigen::Matrix>( - this->MidLinkW.data(), 3, 3); - K_p_mid_link = Eigen::Map< - Eigen::Matrix>( - this->MidLinkKp.data(), 3, 3); - K_d_mid_link = Eigen::Map< - Eigen::Matrix>( - this->MidLinkKd.data(), 3, 3); - W_end_effector_rot = Eigen::Map< - Eigen::Matrix>( - this->EndEffectorRotW.data(), 3, 3); - K_p_end_effector_rot = Eigen::Map< - Eigen::Matrix>( - this->EndEffectorRotKp.data(), 3, 3); - K_d_end_effector_rot = Eigen::Map< - Eigen::Matrix>( - this->EndEffectorRotKd.data(), 3, 3); } }; \ No newline at end of file diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 526e9983bb..cee02f8182 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -71,7 +71,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); Parser parser(&plant, nullptr); - parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + parser.AddModelFromFile("examples/franka/urdf/franka.urdf"); RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 8660659ef8..f04ab57525 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -64,7 +64,7 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + parser.AddModelFromFile("examples/franka/urdf/franka.urdf"); drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/table/" @@ -76,7 +76,7 @@ int DoMain(int argc, char* argv[]) { "table1"); drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(FindResourceOrThrow( - "examples/franka/urdf/plate.sdf")); + "examples/franka/urdf/tray.sdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index ecddcf4721..7c063a7af2 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -66,7 +66,7 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModelFromFile("examples/franka/urdf/franka_box.urdf"); + parser.AddModelFromFile("examples/franka/urdf/franka.urdf"); drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/table/" @@ -78,7 +78,7 @@ int do_main(int argc, char* argv[]) { "table1"); drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile(FindResourceOrThrow( - "examples/franka/urdf/plate.sdf")); + "examples/franka/urdf/tray.sdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); diff --git a/examples/franka/urdf/franka_box.urdf b/examples/franka/urdf/franka.urdf similarity index 97% rename from examples/franka/urdf/franka_box.urdf rename to examples/franka/urdf/franka.urdf index 415b6e8176..9f39a1c163 100644 --- a/examples/franka/urdf/franka_box.urdf +++ b/examples/franka/urdf/franka.urdf @@ -518,11 +518,29 @@ - + + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf new file mode 100644 index 0000000000..df800c074f --- /dev/null +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/plate.sdf b/examples/franka/urdf/tray.sdf similarity index 95% rename from examples/franka/urdf/plate.sdf rename to examples/franka/urdf/tray.sdf index ac1ffd8d59..845c3fc0f5 100644 --- a/examples/franka/urdf/plate.sdf +++ b/examples/franka/urdf/tray.sdf @@ -1,7 +1,7 @@ - - + + 2 - - 0.06 - 0 - 0 - 0.015 - 0 - 0.075 - - - - - - 0.3 0.6 0.02 - - - - - - - 0.3 0.6 0.02 - - - - - - 100 - - 0.4 - 0.4 - - - - + + + + 2 + + + 0.06 + 0 + 0 + 0.015 + 0 + 0.075 + + + + + + 0.3 0.6 0.02 + + + + + + + 0.3 0.6 0.02 + + + + + + 100 + + 0.4 + 0.4 + + + + \ No newline at end of file diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index ba0b6636e3..879aebdaa3 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -1,12 +1,11 @@ #include "solvers/lcs_factory.h" +#include #include "multibody/geom_geom_collider.h" #include "multibody/kinematic/kinematic_evaluator_set.h" -#include "drake/solvers/moby_lcp_solver.h" #include "drake/math/autodiff_gradient.h" - - +#include "drake/solvers/moby_lcp_solver.h" namespace dairlib { namespace solvers { @@ -17,6 +16,7 @@ using std::vector; using drake::AutoDiffVecXd; using drake::AutoDiffXd; using drake::MatrixX; +using drake::VectorX; using drake::SortedPair; using drake::geometry::GeometryId; using drake::math::ExtractGradient; @@ -27,274 +27,214 @@ using drake::systems::Context; using Eigen::MatrixXd; using Eigen::VectorXd; -std::pair LCSFactory::LinearizePlantToLCS( +std::pair LCSFactory::LinearizePlantToLCS( const MultibodyPlant& plant, const Context& context, const MultibodyPlant& plant_ad, const Context& context_ad, const vector>& contact_geoms, -int num_friction_directions, double mu, double dt, int N) { - -/// -/// First, calculate vdot and derivatives from non-contact dynamcs -/// - -int n_contacts = contact_geoms.size(); - -AutoDiffVecXd C(plant.num_velocities()); - -plant_ad.CalcBiasTerm(context_ad, &C); - -AutoDiffVecXd Bu = plant_ad.MakeActuationMatrix() * - plant_ad.get_actuation_input_port().Eval(context_ad); - -AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); - -drake::multibody::MultibodyForces f_app(plant_ad); -plant_ad.CalcForceElementsContribution(context_ad, &f_app); - - -MatrixX M(plant.num_velocities(), plant.num_velocities()); -plant_ad.CalcMassMatrix(context_ad, &M); - -// If this ldlt is slow, there are alternate formulations which avoid it -AutoDiffVecXd vdot_no_contact = - M.ldlt().solve(tau_g + f_app.generalized_forces() + Bu - C); -// Constant term in dynamics, d_vv = d + A x_0 + B u_0 -VectorXd d_vv = ExtractValue(vdot_no_contact); - -// Derivatives w.r.t. x and u, AB -MatrixXd AB_v = ExtractGradient(vdot_no_contact); - -VectorXd inp_dvv = plant.get_actuation_input_port().Eval(context); -VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + plant.num_actuators()); -x_dvv << plant.GetPositions(context), plant.GetVelocities(context), inp_dvv; -VectorXd x_dvvcomp = AB_v * x_dvv; - -VectorXd d_v = d_vv - x_dvvcomp; - - -int n_state = plant_ad.num_positions(); -int n_vel = plant_ad.num_velocities(); -int n_total = plant_ad.num_positions() + plant_ad.num_velocities(); -int n_input = plant_ad.num_actuators(); - -/////////// -AutoDiffVecXd qdot_no_contact(plant.num_positions()); - - -AutoDiffVecXd state = plant_ad.get_state_output_port().Eval(context_ad); - -AutoDiffVecXd vel = state.tail(n_vel); - -plant_ad.MapVelocityToQDot(context_ad, vel, &qdot_no_contact); - -MatrixXd AB_q = ExtractGradient(qdot_no_contact); - -MatrixXd d_q = ExtractValue(qdot_no_contact); - - -MatrixXd Nq = AB_q.block(0, n_state, n_state, n_vel); - -/// -/// Contact-related terms -/// -VectorXd phi(n_contacts); -MatrixXd J_n(n_contacts, plant.num_velocities()); -MatrixXd J_t(2 * n_contacts * num_friction_directions, - plant.num_velocities()); - -for (int i = 0; i < n_contacts; i++) { -multibody::GeomGeomCollider collider( - plant, contact_geoms[i]); // deleted num_fricton_directions (check with -// Michael about changes in geomgeom) -auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); - -phi(i) = phi_i; - -J_n.row(i) = J_i.row(0); -J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, -plant.num_velocities()) = -J_i.block(1, 0, 2 * num_friction_directions, plant.num_velocities()); -} - -auto M_ldlt = ExtractValue(M).ldlt(); -MatrixXd MinvJ_n_T = M_ldlt.solve(J_n.transpose()); -MatrixXd MinvJ_t_T = M_ldlt.solve(J_t.transpose()); - -//float dt = 0.1; -auto n_contact_vars = 2 * n_contacts + - 2 * n_contacts * num_friction_directions; - -MatrixXd A(n_total, n_total); -MatrixXd B(n_total, n_input); -MatrixXd D(n_total, n_contact_vars); -VectorXd d(n_total); -MatrixXd E(n_contact_vars, n_total); -MatrixXd F(n_contact_vars, n_contact_vars); -MatrixXd H(n_contact_vars, n_input); -VectorXd c(n_contact_vars); - -MatrixXd AB_v_q = AB_v.block(0, 0, n_vel, n_state); -MatrixXd AB_v_v = AB_v.block(0, n_state, n_vel, n_vel); -MatrixXd AB_v_u = AB_v.block(0, n_total, n_vel, n_input); - -A.block(0, 0, n_state, n_state) = -MatrixXd::Identity(n_state, n_state) + dt * dt * Nq * AB_v_q; -A.block(0, n_state, n_state, n_vel) = dt * Nq + dt * dt * Nq * AB_v_v; -A.block(n_state, 0, n_vel, n_state) = dt * AB_v_q; -A.block(n_state, n_state, n_vel, n_vel) = -dt * AB_v_v + MatrixXd::Identity(n_vel, n_vel); - -B.block(0, 0, n_state, n_input) = dt * dt * Nq * AB_v_u; -B.block(n_state, 0, n_vel, n_input) = dt * AB_v_u; - -D = MatrixXd::Zero(n_total, n_contact_vars); -D.block(0, 2 * n_contacts, n_state, -2 * n_contacts * num_friction_directions) = -dt * dt * Nq * MinvJ_t_T; -D.block(n_state, 2 * n_contacts, n_vel, -2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; - -D.block(0, n_contacts, n_state, n_contacts ) = dt * dt * Nq * MinvJ_n_T; - -D.block(n_state, n_contacts, n_vel, n_contacts ) = dt * MinvJ_n_T; - -d.head(n_state) = dt * dt * Nq * d_v; -d.tail(n_vel) = dt * d_v; - -E = MatrixXd::Zero(n_contact_vars, n_total); -E.block(n_contacts, 0, n_contacts, n_state) = -dt * dt * J_n * AB_v_q; -E.block(2 * n_contacts, 0, -2 * n_contacts * num_friction_directions, n_state) = -dt * J_t * AB_v_q; -E.block(n_contacts, n_state, n_contacts, n_vel) = -dt * J_n + dt * dt * J_n * AB_v_v; -E.block(2 * n_contacts, n_state, -2 * n_contacts * num_friction_directions, n_vel) = -J_t + dt * J_t * AB_v_v; - -MatrixXd E_t = MatrixXd::Zero( - n_contacts, 2 * n_contacts * num_friction_directions); -for (int i = 0; i < n_contacts; i++) { -E_t.block(i, i * (2 * num_friction_directions), 1, -2 * num_friction_directions) = -MatrixXd::Ones(1, 2 * num_friction_directions); -}; - - -F = MatrixXd::Zero(n_contact_vars, n_contact_vars); -F.block(0, n_contacts, n_contacts, n_contacts) = -mu * MatrixXd::Identity(n_contacts, n_contacts); -F.block(0, 2 * n_contacts, n_contacts, -2 * n_contacts * num_friction_directions) = -E_t; - -F.block(n_contacts, n_contacts, n_contacts, n_contacts ) = -dt * dt * J_n * MinvJ_n_T; -F.block(n_contacts, 2 * n_contacts, n_contacts, -2 * n_contacts * num_friction_directions) = -dt * dt * J_n * MinvJ_t_T; - -F.block(2 * n_contacts, 0, -2 * n_contacts * num_friction_directions, - n_contacts) = E_t.transpose(); - -F.block(2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions, - n_contacts) = dt * J_t * MinvJ_n_T; -F.block(2 * n_contacts, 2 * n_contacts, -2 * n_contacts * num_friction_directions, -2 * n_contacts * num_friction_directions) = -dt * J_t * MinvJ_t_T; -H = MatrixXd::Zero(n_contact_vars, n_input); -H.block(n_contacts, 0, n_contacts, n_input) = -dt * dt * J_n * AB_v_u; -H.block(2 * n_contacts, 0, -2 * n_contacts * num_friction_directions, n_input) = -dt * J_t * AB_v_u; - -c = VectorXd::Zero(n_contact_vars); -c.segment(n_contacts, n_contacts) = -phi + dt * dt * J_n * d_v; - -c.segment(2 * n_contacts, -2 * n_contacts * num_friction_directions) = -J_t * dt * d_v; - -auto Dn = D.squaredNorm(); -auto An = A.squaredNorm(); -auto AnDn = An / Dn; - -D *= AnDn; -E /= AnDn; -c /= AnDn; -H /= AnDn; - -LCS system(A, B, D, d, E, F, H, c, N); - - -//////// -// ///check LCS predictions -// VectorXd inp = plant.get_actuation_input_port().Eval(context); -// -// //std::cout << inp << std::endl; -// -// VectorXd x0(plant.num_positions() + plant.num_velocities()); -// x0 << plant.GetPositions(context), plant.GetVelocities(context); -//// -//// std::cout << "real" << std::endl; -//// std::cout << plant_ad.GetVelocities(context_ad) << std::endl; -//// -// VectorXd asd = system.Simulate(x0 ,inp); -// -// // calculate force -// drake::solvers::MobyLCPSolver LCPSolver; -// VectorXd force; -// -// VectorXd x_init = x0; -// VectorXd input = inp; -// -// -// auto flag = LCPSolver.SolveLcpLemke(F, E * x_init + c + H * input, -// &force); -// -// //VectorXd x_final = A * x_init + B * input + D * force + d; -// -// //if (flag == 1){ -// -// std::cout << "LCS force estimate" << std::endl; -// std::cout << force << std::endl; -// std::cout << "LCS force estimate" << std::endl; -//// -//// -//// std::cout << "Jn * v" << std::endl; -//// std::cout << J_n * x_final.tail(9) << std::endl; -//// std::cout << "Jn * v" << std::endl; -// -//// std::cout << "gap" << std::endl; -//// std::cout << E * x_init + c + H * input + F * force << std::endl; -//// std::cout << "gap" << std::endl; -// -// std::cout << "phi" << std::endl; -// std::cout << phi << std::endl; -// std::cout << "phi" << std::endl; -// -// -// } - -// -// std::cout << "prediction" << std::endl; -// std::cout << asd.tail(15) << std::endl; - -std::pair ret (system, AnDn); - -return ret; + int num_friction_directions, double mu, double dt, int N) { + /// + /// First, calculate vdot and derivatives from non-contact dynamcs + /// + + int n_contacts = contact_geoms.size(); + + AutoDiffVecXd C(plant.num_velocities()); + plant_ad.CalcBiasTerm(context_ad, &C); + MatrixXd B_dyn = MatrixXd::Identity(plant.num_velocities(), 6); + VectorXd u_dyn = VectorXd::Zero(6); + AutoDiffVecXd u_dyn_ad = drake::math::InitializeAutoDiff(u_dyn); + AutoDiffVecXd Bu = B_dyn * u_dyn_ad; + + std::cout << ExtractValue(Bu) << std::endl; + std::cout << ExtractGradient(Bu) << std::endl; + AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); + +// drake::multibody::MultibodyForces f_app(plant_ad); +// plant_ad.CalcForceElementsContribution(context_ad, &f_app); + + MatrixX M(plant.num_velocities(), plant.num_velocities()); + plant_ad.CalcMassMatrix(context_ad, &M); + std::cout << "M: " << M << std::endl; + std::cout << "tau_g: " << tau_g << std::endl; + std::cout << "Bu: " << Bu << std::endl; + std::cout << "C: " << C << std::endl; + auto M_test = M.ldlt(); + // If this ldlt is slow, there are alternate formulations which avoid it + //TODO(yangwill): check this line below + AutoDiffVecXd vdot_no_contact = + M.ldlt().solve(tau_g + Bu - C); + // Constant term in dynamics, d_vv = d + A x_0 + B u_0 + VectorXd d_vv = ExtractValue(vdot_no_contact); + std::cout << "computed vdot" << std::endl; + // Derivatives w.r.t. x and u, AB + MatrixXd AB_v = ExtractGradient(vdot_no_contact); + +// VectorXd inp_dvv = plant.get_actuation_input_port().Eval(context); +// VectorXd inp_dvv = u_dyn; + VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + + 6); + x_dvv << plant.GetPositions(context), plant.GetVelocities(context), u_dyn; + VectorXd x_dvvcomp = AB_v * x_dvv; + + VectorXd d_v = d_vv - x_dvvcomp; + + int n_state = plant_ad.num_positions(); + int n_vel = plant_ad.num_velocities(); + int n_total = plant_ad.num_positions() + plant_ad.num_velocities(); +// int n_input = plant_ad.num_actuators(); + int n_input = 6; + + std::cout << "dynamics " << std::endl; + + /////////// + AutoDiffVecXd qdot_no_contact(plant.num_positions()); +// AutoDiffVecXd state = plant_ad.get_state_output_port().Eval(context_ad); + AutoDiffVecXd + vel_ad = drake::math::InitializeAutoDiff(plant.GetVelocities(context)); + + //TODO(yangwill): check this line below + plant_ad.MapVelocityToQDot(context_ad, vel_ad, &qdot_no_contact); + MatrixXd AB_q = ExtractGradient(qdot_no_contact); + MatrixXd d_q = ExtractValue(qdot_no_contact); + MatrixXd Nq = AB_q.block(0, n_state, n_state, n_vel); + + std::cout << "Contact " << std::endl; + /// + /// Contact-related terms + /// + VectorXd phi(n_contacts); + MatrixXd J_n(n_contacts, plant.num_velocities()); + MatrixXd J_t(2 * n_contacts * num_friction_directions, + plant.num_velocities()); + + for (int i = 0; i < n_contacts; i++) { + multibody::GeomGeomCollider collider( + plant, contact_geoms[i]); // deleted num_fricton_directions (check with + // Michael about changes in geomgeom) + auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); + + phi(i) = phi_i; + + J_n.row(i) = J_i.row(0); + J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, + plant.num_velocities()) = + J_i.block(1, 0, 2 * num_friction_directions, plant.num_velocities()); + } + std::cout << "Mass " << std::endl; + + auto M_ldlt = ExtractValue(M).ldlt(); + MatrixXd MinvJ_n_T = M_ldlt.solve(J_n.transpose()); + MatrixXd MinvJ_t_T = M_ldlt.solve(J_t.transpose()); + + // float dt = 0.1; + auto n_contact_vars = + 2 * n_contacts + 2 * n_contacts * num_friction_directions; + + std::cout << "Constructing LCS " << std::endl; + + MatrixXd A(n_total, n_total); + MatrixXd B(n_total, n_input); + MatrixXd D(n_total, n_contact_vars); + VectorXd d(n_total); + MatrixXd E(n_contact_vars, n_total); + MatrixXd F(n_contact_vars, n_contact_vars); + MatrixXd H(n_contact_vars, n_input); + VectorXd c(n_contact_vars); + + MatrixXd AB_v_q = AB_v.block(0, 0, n_vel, n_state); + MatrixXd AB_v_v = AB_v.block(0, n_state, n_vel, n_vel); + MatrixXd AB_v_u = AB_v.block(0, n_total, n_vel, n_input); + + A.block(0, 0, n_state, n_state) = + MatrixXd::Identity(n_state, n_state) + dt * dt * Nq * AB_v_q; + A.block(0, n_state, n_state, n_vel) = dt * Nq + dt * dt * Nq * AB_v_v; + A.block(n_state, 0, n_vel, n_state) = dt * AB_v_q; + A.block(n_state, n_state, n_vel, n_vel) = + dt * AB_v_v + MatrixXd::Identity(n_vel, n_vel); + + B.block(0, 0, n_state, n_input) = dt * dt * Nq * AB_v_u; + B.block(n_state, 0, n_vel, n_input) = dt * AB_v_u; + + D = MatrixXd::Zero(n_total, n_contact_vars); + D.block(0, 2 * n_contacts, n_state, + 2 * n_contacts * num_friction_directions) = dt * dt * Nq * MinvJ_t_T; + D.block(n_state, 2 * n_contacts, n_vel, + 2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; + + D.block(0, n_contacts, n_state, n_contacts) = dt * dt * Nq * MinvJ_n_T; + + D.block(n_state, n_contacts, n_vel, n_contacts) = dt * MinvJ_n_T; + + d.head(n_state) = dt * dt * Nq * d_v; + d.tail(n_vel) = dt * d_v; + + E = MatrixXd::Zero(n_contact_vars, n_total); + E.block(n_contacts, 0, n_contacts, n_state) = dt * dt * J_n * AB_v_q; + E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, + n_state) = dt * J_t * AB_v_q; + E.block(n_contacts, n_state, n_contacts, n_vel) = + dt * J_n + dt * dt * J_n * AB_v_v; + E.block(2 * n_contacts, n_state, 2 * n_contacts * num_friction_directions, + n_vel) = J_t + dt * J_t * AB_v_v; + + MatrixXd E_t = + MatrixXd::Zero(n_contacts, 2 * n_contacts * num_friction_directions); + for (int i = 0; i < n_contacts; i++) { + E_t.block(i, i * (2 * num_friction_directions), 1, + 2 * num_friction_directions) = + MatrixXd::Ones(1, 2 * num_friction_directions); + }; + + F = MatrixXd::Zero(n_contact_vars, n_contact_vars); + F.block(0, n_contacts, n_contacts, n_contacts) = + mu * MatrixXd::Identity(n_contacts, n_contacts); + F.block(0, 2 * n_contacts, n_contacts, + 2 * n_contacts * num_friction_directions) = -E_t; + + F.block(n_contacts, n_contacts, n_contacts, n_contacts) = + dt * dt * J_n * MinvJ_n_T; + F.block(n_contacts, 2 * n_contacts, n_contacts, + 2 * n_contacts * num_friction_directions) = dt * dt * J_n * MinvJ_t_T; + + F.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, + n_contacts) = E_t.transpose(); + + F.block(2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions, + n_contacts) = dt * J_t * MinvJ_n_T; + F.block(2 * n_contacts, 2 * n_contacts, + 2 * n_contacts * num_friction_directions, + 2 * n_contacts * num_friction_directions) = dt * J_t * MinvJ_t_T; + H = MatrixXd::Zero(n_contact_vars, n_input); + H.block(n_contacts, 0, n_contacts, n_input) = dt * dt * J_n * AB_v_u; + H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, + n_input) = dt * J_t * AB_v_u; + + c = VectorXd::Zero(n_contact_vars); + c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; + + c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = + J_t * dt * d_v; + + auto Dn = D.squaredNorm(); + auto An = A.squaredNorm(); + auto AnDn = An / Dn; + + D *= AnDn; + E /= AnDn; + c /= AnDn; + H /= AnDn; + + LCS system(A, B, D, d, E, F, H, c, N); + + std::pair ret(system, AnDn); + + return ret; } - LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, set inactive_lambda_inds) { - vector remaining_inds; // Assumes constant number of contacts per index @@ -305,11 +245,10 @@ LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, for (int i = 0; i < n_lambda; i++) { // active/inactive must be exclusive DRAKE_ASSERT(!active_lambda_inds.count(i) || - !inactive_lambda_inds.count(i)); + !inactive_lambda_inds.count(i)); // In C++20, could use contains instead of count - if (!active_lambda_inds.count(i) && - !inactive_lambda_inds.count(i)) { + if (!active_lambda_inds.count(i) && !inactive_lambda_inds.count(i)) { remaining_inds.push_back(i); } } @@ -338,7 +277,6 @@ LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, } } - for (int k = 0; k < other.N_; k++) { Eigen::BDCSVD svd; svd.setThreshold(1e-5); @@ -352,12 +290,13 @@ LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, // F_a_inv = pinv(S_a * F * S_a^T) // 0 <= \lambda_k \perp E_k x_k + F_k \lambda_k + H_k u_k + c_k // 0 = S_a *(E x + F S_a^T \lambda_a + F S_r^T \lambda_r + H_k u_k + c_k) - // \lambda_a = -F_a_inv * (S_a F S_r^T * lambda_r + S_a E x + S_a H u + S_a c) + // \lambda_a = -F_a_inv * (S_a F S_r^T * lambda_r + S_a E x + S_a H u + S_a + // c) // // 0 <= \lambda_r \perp S_r (I - F S_a^T F_a_inv S_a) E x + ... - // S_r (I - F S_a^T F_a_inv S_a) F S_r^T \lambda_r + ... - // S_r (I - F S_a^T F_a_inv S_a) H u + ... - // S_r (I - F S_a^T F_a_inv S_a) c + // S_r (I - F S_a^T F_a_inv S_a) F S_r^T \lambda_r + + // ... S_r (I - F S_a^T F_a_inv S_a) H u + ... S_r (I - + // F S_a^T F_a_inv S_a) c // // Calling L = S_r (I - F S_a^T F_a_inv S_a)S_r * other.D_[k] // E_k = L E @@ -370,7 +309,7 @@ LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, // auto tmp = S_r * (MatrixXd::Identity(n_lambda, n_lambda) - // other.F_[k] * S_a.transpose()); MatrixXd L = S_r * (MatrixXd::Identity(n_lambda, n_lambda) - - other.F_[k] * S_a.transpose() * svd.solve(S_a)); + other.F_[k] * S_a.transpose() * svd.solve(S_a)); MatrixXd E_k = L * other.E_[k]; MatrixXd F_k = L * other.F_[k] * S_r.transpose(); MatrixXd H_k = L * other.H_[k]; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7279a76cc0..b20e9d56d9 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -9,19 +9,22 @@ namespace dairlib { using drake::systems::BasicVector; using Eigen::VectorXd; -using solvers::LCS; using solvers::C3MIQP; +using solvers::LCS; namespace systems { -C3Controller::C3Controller(LCS& lcs, C3Options c3_options) : lcs_(lcs) { - target_input_port_ = - this->DeclareVectorInputPort("desired_position", - BasicVector(2 + 16)) - .get_index(); +C3Controller::C3Controller(LCS& lcs, C3Options c3_options, + std::vector Q, + std::vector R, + std::vector G, + std::vector U) + : lcs_(lcs), Q_(Q), R_(R), G_(G), U_(U) { + target_input_port_ = this->DeclareVectorInputPort("desired_position", + BasicVector(2 + 16)) + .get_index(); lcs_state_input_port_ = - this->DeclareVectorInputPort( - "x_lcs", BasicVector(10)) + this->DeclareVectorInputPort("x_lcs", BasicVector(10)) .get_index(); std::vector x_desired = {VectorXd::Zero(3)}; @@ -38,10 +41,10 @@ C3Controller::C3Controller(LCS& lcs, C3Options c3_options) : lcs_(lcs) { void C3Controller::OutputTrajectory( const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const { - const BasicVector& x_des = - *this->template EvalVectorInput(context, target_input_port_); - const BasicVector& x = - *this->template EvalVectorInput(context, lcs_state_input_port_); +// const BasicVector& x_des = +// *this->template EvalVectorInput(context, target_input_port_); + const BasicVector& x = *this->template EvalVectorInput( + context, lcs_state_input_port_); // delta // in order: // state, forces, inputs diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 800385ed0a..d4afd34fef 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -19,7 +19,11 @@ namespace systems { /// Outputs a lcmt_timestamped_saved_traj class C3Controller : public drake::systems::LeafSystem { public: - explicit C3Controller(solvers::LCS& lcs, C3Options c3_options); + explicit C3Controller(solvers::LCS& lcs, C3Options c3_options, + std::vector Q, + std::vector R, + std::vector G, + std::vector U); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(target_input_port_); From 6500fdb623791affb4b2714525dbfde780ab427c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 30 Mar 2023 14:56:36 -0400 Subject: [PATCH 418/758] correct autodiff sizes --- examples/franka/franka_c3_controller.cc | 41 +++-- .../franka/franka_c3_controller_params.yaml | 6 +- .../urdf/plate_end_effector_translation.urdf | 62 ++++---- solvers/lcs_factory.cc | 142 ++++++++---------- 4 files changed, 121 insertions(+), 130 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 9581128e1f..08089e3870 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -75,6 +75,9 @@ int DoMain(int argc, char* argv[]) { parser_plate.package_map().Add("franka_urdfs", "examples/franka/urdf"); parser_plate.AddModelFromFile(controller_params.plate_model); parser_plate.AddModelFromFile(controller_params.tray_model); + + plant_plate.WeldFrames(plant_plate.world_frame(), + plant_plate.GetFrameByName("base_link"), X_WI); plant_plate.Finalize(); std::unique_ptr> plant_plate_ad = @@ -116,25 +119,33 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( controller_params.c3_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); - drake::AutoDiffVecXd q_v_ad = drake::math::InitializeAutoDiff(VectorXd::Zero( - plant_plate_ad->num_positions() + plant_plate_ad->num_velocities())); + drake::AutoDiffVecXd q_v_u_ad = + drake::math::InitializeAutoDiff(VectorXd::Zero( + plant_plate_ad->num_positions() + plant_plate_ad->num_velocities() + + plant_plate_ad->num_actuators())); std::cout << "num_positions: " << plant_plate_ad->num_positions() << std::endl; std::cout << "num_velocities: " << plant_plate_ad->num_velocities() << std::endl; - VectorXd q_v = VectorXd::Zero(plant_plate.num_positions() + - plant_plate.num_velocities()); - q_v[0] = 1; - q_v[7] = 1; - q_v_ad[0] = 1; - q_v_ad[7] = 1; - - plant_plate_ad->SetPositionsAndVelocities(plate_context_ad.get(), q_v_ad); - plant_plate.SetPositionsAndVelocities(plate_context.get(), q_v); + std::cout << "num_actuators: " << plant_plate_ad->num_actuators() + << std::endl; + VectorXd q_v_u = VectorXd::Zero(plant_plate.num_positions() + + plant_plate.num_velocities() + + plant_plate.num_actuators()); + q_v_u[0] = 1; + q_v_u[4] = 1; + q_v_u_ad[0] = 1; + q_v_u_ad[4] = 1; + + int n_x = plant_plate_ad->num_positions() + plant_plate_ad->num_velocities(); + int n_u = plant_plate_ad->num_actuators(); + + plant_plate_ad->SetPositionsAndVelocities(plate_context_ad.get(), q_v_u_ad.head(n_x)); + plant_plate.SetPositionsAndVelocities(plate_context.get(), q_v_u.head(n_x)); auto lcs = LCSFactory::LinearizePlantToLCS( plant_plate, *plate_context, *plant_plate_ad, *plate_context_ad, contact_pairs, controller_params.num_friction_directions, - controller_params.mu, controller_params.dt, 5); + controller_params.mu, controller_params.dt, controller_params.N); auto Q = std::vector(controller_params.N, controller_params.Q); auto R = std::vector(controller_params.N, controller_params.R); @@ -143,8 +154,10 @@ int DoMain(int argc, char* argv[]) { auto controller = builder.AddSystem( lcs.first, c3_options, Q, R, G, U); - builder.Connect(state_receiver->get_output_port(), controller->get_input_port_state()); - builder.Connect(controller->get_output_port_trajectory(), trajectory_sender->get_input_port()); + builder.Connect(state_receiver->get_output_port(), + controller->get_input_port_state()); + builder.Connect(controller->get_output_port_trajectory(), + trajectory_sender->get_input_port()); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index a19c697352..5fa1b31bb4 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -23,7 +23,7 @@ w_U: 0.001 g_size: 10 u_size: 10 # State Tracking Error, assuming diagonal -q_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +q_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1, 1, 1, 1] +r_vector: [1, 1, 1] diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 7e00d46507..093f454724 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -69,36 +69,36 @@ - - - - - - - - - - - - - - - - - - - - 1 - - - - - 1 - - - - - 1 - + + + + + + + + + + + + + + + + + + + + 1 + + + + + 1 + + + + + 1 + diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 879aebdaa3..ea2fde752f 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -1,4 +1,5 @@ #include "solvers/lcs_factory.h" + #include #include "multibody/geom_geom_collider.h" @@ -16,8 +17,8 @@ using std::vector; using drake::AutoDiffVecXd; using drake::AutoDiffXd; using drake::MatrixX; -using drake::VectorX; using drake::SortedPair; +using drake::VectorX; using drake::geometry::GeometryId; using drake::math::ExtractGradient; using drake::math::ExtractValue; @@ -33,73 +34,55 @@ std::pair LCSFactory::LinearizePlantToLCS( const Context& context_ad, const vector>& contact_geoms, int num_friction_directions, double mu, double dt, int N) { - /// - /// First, calculate vdot and derivatives from non-contact dynamcs - /// + int n_q = plant_ad.num_positions(); + int n_v = plant_ad.num_velocities(); + int n_x = plant_ad.num_positions() + plant_ad.num_velocities(); + int n_u = plant_ad.num_actuators(); int n_contacts = contact_geoms.size(); AutoDiffVecXd C(plant.num_velocities()); plant_ad.CalcBiasTerm(context_ad, &C); - MatrixXd B_dyn = MatrixXd::Identity(plant.num_velocities(), 6); - VectorXd u_dyn = VectorXd::Zero(6); - AutoDiffVecXd u_dyn_ad = drake::math::InitializeAutoDiff(u_dyn); - AutoDiffVecXd Bu = B_dyn * u_dyn_ad; + auto B_dyn_ad = plant_ad.MakeActuationMatrix(); + VectorXd u_dyn = VectorXd::Zero(n_u); + AutoDiffVecXd u_dyn_ad = drake::math::InitializeAutoDiff(u_dyn, n_q + n_v + n_u); + AutoDiffVecXd Bu = B_dyn_ad * u_dyn_ad; - std::cout << ExtractValue(Bu) << std::endl; - std::cout << ExtractGradient(Bu) << std::endl; AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); -// drake::multibody::MultibodyForces f_app(plant_ad); -// plant_ad.CalcForceElementsContribution(context_ad, &f_app); + drake::multibody::MultibodyForces f_app(plant_ad); + plant_ad.CalcForceElementsContribution(context_ad, &f_app); MatrixX M(plant.num_velocities(), plant.num_velocities()); plant_ad.CalcMassMatrix(context_ad, &M); - std::cout << "M: " << M << std::endl; - std::cout << "tau_g: " << tau_g << std::endl; - std::cout << "Bu: " << Bu << std::endl; - std::cout << "C: " << C << std::endl; - auto M_test = M.ldlt(); + // If this ldlt is slow, there are alternate formulations which avoid it - //TODO(yangwill): check this line below + // TODO(yangwill): check this line below AutoDiffVecXd vdot_no_contact = - M.ldlt().solve(tau_g + Bu - C); + M.ldlt().solve(tau_g + Bu + f_app.generalized_forces() - C); // Constant term in dynamics, d_vv = d + A x_0 + B u_0 VectorXd d_vv = ExtractValue(vdot_no_contact); - std::cout << "computed vdot" << std::endl; // Derivatives w.r.t. x and u, AB MatrixXd AB_v = ExtractGradient(vdot_no_contact); - -// VectorXd inp_dvv = plant.get_actuation_input_port().Eval(context); -// VectorXd inp_dvv = u_dyn; - VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + - 6); + // VectorXd inp_dvv = plant.get_actuation_input_port().Eval(context); + // VectorXd inp_dvv = u_dyn; + VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + n_u); x_dvv << plant.GetPositions(context), plant.GetVelocities(context), u_dyn; VectorXd x_dvvcomp = AB_v * x_dvv; - VectorXd d_v = d_vv - x_dvvcomp; - int n_state = plant_ad.num_positions(); - int n_vel = plant_ad.num_velocities(); - int n_total = plant_ad.num_positions() + plant_ad.num_velocities(); -// int n_input = plant_ad.num_actuators(); - int n_input = 6; - - std::cout << "dynamics " << std::endl; - /////////// + // AutoDiffVecXd state = plant_ad.get_state_output_port().Eval(context_ad); + AutoDiffVecXd x_ad = plant_ad.GetPositionsAndVelocities(context_ad); AutoDiffVecXd qdot_no_contact(plant.num_positions()); -// AutoDiffVecXd state = plant_ad.get_state_output_port().Eval(context_ad); - AutoDiffVecXd - vel_ad = drake::math::InitializeAutoDiff(plant.GetVelocities(context)); + AutoDiffVecXd vel_ad = x_ad.tail(n_v); - //TODO(yangwill): check this line below + // TODO(yangwill): check this line below plant_ad.MapVelocityToQDot(context_ad, vel_ad, &qdot_no_contact); MatrixXd AB_q = ExtractGradient(qdot_no_contact); MatrixXd d_q = ExtractValue(qdot_no_contact); - MatrixXd Nq = AB_q.block(0, n_state, n_state, n_vel); + MatrixXd Nq = AB_q.block(0, n_q, n_q, n_v); - std::cout << "Contact " << std::endl; /// /// Contact-related terms /// @@ -122,8 +105,6 @@ std::pair LCSFactory::LinearizePlantToLCS( J_i.block(1, 0, 2 * num_friction_directions, plant.num_velocities()); } - std::cout << "Mass " << std::endl; - auto M_ldlt = ExtractValue(M).ldlt(); MatrixXd MinvJ_n_T = M_ldlt.solve(J_n.transpose()); MatrixXd MinvJ_t_T = M_ldlt.solve(J_t.transpose()); @@ -132,52 +113,48 @@ std::pair LCSFactory::LinearizePlantToLCS( auto n_contact_vars = 2 * n_contacts + 2 * n_contacts * num_friction_directions; - std::cout << "Constructing LCS " << std::endl; - - MatrixXd A(n_total, n_total); - MatrixXd B(n_total, n_input); - MatrixXd D(n_total, n_contact_vars); - VectorXd d(n_total); - MatrixXd E(n_contact_vars, n_total); + MatrixXd A(n_x, n_x); + MatrixXd B(n_x, n_u); + MatrixXd D(n_x, n_contact_vars); + VectorXd d(n_x); + MatrixXd E(n_contact_vars, n_x); MatrixXd F(n_contact_vars, n_contact_vars); - MatrixXd H(n_contact_vars, n_input); + MatrixXd H(n_contact_vars, n_u); VectorXd c(n_contact_vars); - MatrixXd AB_v_q = AB_v.block(0, 0, n_vel, n_state); - MatrixXd AB_v_v = AB_v.block(0, n_state, n_vel, n_vel); - MatrixXd AB_v_u = AB_v.block(0, n_total, n_vel, n_input); + MatrixXd AB_v_q = AB_v.block(0, 0, n_v, n_q); + MatrixXd AB_v_v = AB_v.block(0, n_q, n_v, n_v); + MatrixXd AB_v_u = AB_v.block(0, n_x, n_v, n_u); - A.block(0, 0, n_state, n_state) = - MatrixXd::Identity(n_state, n_state) + dt * dt * Nq * AB_v_q; - A.block(0, n_state, n_state, n_vel) = dt * Nq + dt * dt * Nq * AB_v_v; - A.block(n_state, 0, n_vel, n_state) = dt * AB_v_q; - A.block(n_state, n_state, n_vel, n_vel) = - dt * AB_v_v + MatrixXd::Identity(n_vel, n_vel); + A.block(0, 0, n_q, n_q) = + MatrixXd::Identity(n_q, n_q) + dt * dt * Nq * AB_v_q; + A.block(0, n_q, n_q, n_v) = dt * Nq + dt * dt * Nq * AB_v_v; + A.block(n_q, 0, n_v, n_q) = dt * AB_v_q; + A.block(n_q, n_q, n_v, n_v) = dt * AB_v_v + MatrixXd::Identity(n_v, n_v); - B.block(0, 0, n_state, n_input) = dt * dt * Nq * AB_v_u; - B.block(n_state, 0, n_vel, n_input) = dt * AB_v_u; + B.block(0, 0, n_q, n_u) = dt * dt * Nq * AB_v_u; + B.block(n_q, 0, n_v, n_u) = dt * AB_v_u; - D = MatrixXd::Zero(n_total, n_contact_vars); - D.block(0, 2 * n_contacts, n_state, - 2 * n_contacts * num_friction_directions) = dt * dt * Nq * MinvJ_t_T; - D.block(n_state, 2 * n_contacts, n_vel, - 2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; + D = MatrixXd::Zero(n_x, n_contact_vars); + D.block(0, 2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions) = + dt * dt * Nq * MinvJ_t_T; + D.block(n_q, 2 * n_contacts, n_v, 2 * n_contacts * num_friction_directions) = + dt * MinvJ_t_T; - D.block(0, n_contacts, n_state, n_contacts) = dt * dt * Nq * MinvJ_n_T; + D.block(0, n_contacts, n_q, n_contacts) = dt * dt * Nq * MinvJ_n_T; - D.block(n_state, n_contacts, n_vel, n_contacts) = dt * MinvJ_n_T; + D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; - d.head(n_state) = dt * dt * Nq * d_v; - d.tail(n_vel) = dt * d_v; + d.head(n_q) = dt * dt * Nq * d_v; + d.tail(n_v) = dt * d_v; - E = MatrixXd::Zero(n_contact_vars, n_total); - E.block(n_contacts, 0, n_contacts, n_state) = dt * dt * J_n * AB_v_q; - E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, - n_state) = dt * J_t * AB_v_q; - E.block(n_contacts, n_state, n_contacts, n_vel) = - dt * J_n + dt * dt * J_n * AB_v_v; - E.block(2 * n_contacts, n_state, 2 * n_contacts * num_friction_directions, - n_vel) = J_t + dt * J_t * AB_v_v; + E = MatrixXd::Zero(n_contact_vars, n_x); + E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q; + E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = + dt * J_t * AB_v_q; + E.block(n_contacts, n_q, n_contacts, n_v) = dt * J_n + dt * dt * J_n * AB_v_v; + E.block(2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions, n_v) = + J_t + dt * J_t * AB_v_v; MatrixXd E_t = MatrixXd::Zero(n_contacts, 2 * n_contacts * num_friction_directions); @@ -185,7 +162,7 @@ std::pair LCSFactory::LinearizePlantToLCS( E_t.block(i, i * (2 * num_friction_directions), 1, 2 * num_friction_directions) = MatrixXd::Ones(1, 2 * num_friction_directions); - }; + } F = MatrixXd::Zero(n_contact_vars, n_contact_vars); F.block(0, n_contacts, n_contacts, n_contacts) = @@ -206,10 +183,11 @@ std::pair LCSFactory::LinearizePlantToLCS( F.block(2 * n_contacts, 2 * n_contacts, 2 * n_contacts * num_friction_directions, 2 * n_contacts * num_friction_directions) = dt * J_t * MinvJ_t_T; - H = MatrixXd::Zero(n_contact_vars, n_input); - H.block(n_contacts, 0, n_contacts, n_input) = dt * dt * J_n * AB_v_u; + + H = MatrixXd::Zero(n_contact_vars, n_u); + H.block(n_contacts, 0, n_contacts, n_u) = dt * dt * J_n * AB_v_u; H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, - n_input) = dt * J_t * AB_v_u; + n_u) = dt * J_t * AB_v_u; c = VectorXd::Zero(n_contact_vars); c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; From d2eea2ca54cecfc4559d8be4dc9d4e64f361ec3b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 30 Mar 2023 23:03:07 -0400 Subject: [PATCH 419/758] working on piecing together the whole system --- examples/franka/BUILD.bazel | 15 +++++ examples/franka/franka_c3_controller.cc | 38 ++++++++--- examples/franka/franka_kinematics.cc | 84 +++++++++++++++++++++++++ examples/franka/franka_kinematics.h | 53 ++++++++++++++++ solvers/c3.cc | 3 +- solvers/lcs_factory.cc | 1 - systems/controllers/c3_controller.cc | 9 ++- systems/controllers/c3_controller.h | 1 + 8 files changed, 191 insertions(+), 13 deletions(-) create mode 100644 examples/franka/franka_kinematics.cc create mode 100644 examples/franka/franka_kinematics.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index e046f6f7d9..8ae587b664 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -58,6 +58,7 @@ cc_binary( ], deps = [ ":franka_c3_controller_params", + ":franka_kinematics", "//examples/franka/systems:end_effector_trajectory", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", @@ -106,6 +107,20 @@ cc_library( ], ) +cc_library( + name = "franka_kinematics", + srcs = ["franka_kinematics.cc"], + hdrs = ["franka_kinematics.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//common", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + + cc_library( name = "franka_c3_controller_params", hdrs = ["franka_c3_controller_params.h"], diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 08089e3870..11a08bcd26 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -3,6 +3,7 @@ #include #include "examples/franka/franka_c3_controller_params.h" +#include "examples/franka/franka_kinematics.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" @@ -68,6 +69,14 @@ int DoMain(int argc, char* argv[]) { plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + + /// + MultibodyPlant plant_tray(0.0); + Parser parser_tray(&plant_tray, nullptr); + parser_tray.AddModelFromFile(controller_params.tray_model); + plant_tray.Finalize(); + auto tray_context = plant_tray.CreateDefaultContext(); /// MultibodyPlant plant_plate(0.0); @@ -113,8 +122,16 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; - auto state_receiver = + auto tray_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + "TRAY_OUTPUT", &lcm)); + auto franka_state_receiver = builder.AddSystem(plant_franka); + auto tray_state_receiver = + builder.AddSystem(plant_tray); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_tray, tray_context.get(), "paddle"); auto trajectory_sender = builder.AddSystem(LcmPublisherSystem::Make( controller_params.c3_channel, &lcm, @@ -130,8 +147,8 @@ int DoMain(int argc, char* argv[]) { std::cout << "num_actuators: " << plant_plate_ad->num_actuators() << std::endl; VectorXd q_v_u = VectorXd::Zero(plant_plate.num_positions() + - plant_plate.num_velocities() + - plant_plate.num_actuators()); + plant_plate.num_velocities() + + plant_plate.num_actuators()); q_v_u[0] = 1; q_v_u[4] = 1; q_v_u_ad[0] = 1; @@ -140,21 +157,28 @@ int DoMain(int argc, char* argv[]) { int n_x = plant_plate_ad->num_positions() + plant_plate_ad->num_velocities(); int n_u = plant_plate_ad->num_actuators(); - plant_plate_ad->SetPositionsAndVelocities(plate_context_ad.get(), q_v_u_ad.head(n_x)); + plant_plate_ad->SetPositionsAndVelocities(plate_context_ad.get(), + q_v_u_ad.head(n_x)); plant_plate.SetPositionsAndVelocities(plate_context.get(), q_v_u.head(n_x)); auto lcs = LCSFactory::LinearizePlantToLCS( plant_plate, *plate_context, *plant_plate_ad, *plate_context_ad, contact_pairs, controller_params.num_friction_directions, controller_params.mu, controller_params.dt, controller_params.N); - auto Q = std::vector(controller_params.N, controller_params.Q); + auto Q = std::vector(controller_params.N + 1, controller_params.Q); auto R = std::vector(controller_params.N, controller_params.R); auto G = std::vector(controller_params.N, controller_params.G); auto U = std::vector(controller_params.N, controller_params.U); auto controller = builder.AddSystem( lcs.first, c3_options, Q, R, G, U); - builder.Connect(state_receiver->get_output_port(), + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(tray_state_sub->get_output_port(), + tray_state_receiver->get_input_port()); + builder.Connect(tray_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_state()); builder.Connect(controller->get_output_port_trajectory(), trajectory_sender->get_input_port()); @@ -163,7 +187,7 @@ int DoMain(int argc, char* argv[]) { owned_diagram->set_name(("franka_c3_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, + &lcm, std::move(owned_diagram), franka_state_receiver, controller_params.state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/franka/franka_kinematics.cc b/examples/franka/franka_kinematics.cc new file mode 100644 index 0000000000..7c6b6b1441 --- /dev/null +++ b/examples/franka/franka_kinematics.cc @@ -0,0 +1,84 @@ +#include "examples/franka/franka_kinematics.h" + +#include + +#include "common/find_resource.h" +#include "multibody/multibody_utils.h" + +namespace dairlib { + +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using Eigen::VectorXd; +using systems::OutputVector; +using systems::TimestampedVector; + +namespace systems { + +FrankaKinematics::FrankaKinematics(const MultibodyPlant& franka_plant, + Context* franka_context, + const MultibodyPlant& object_plant, + Context* object_context, + const std::string& end_effector_name) + : franka_plant_(franka_plant), + franka_context_(franka_context), + object_plant_(object_plant), + object_context_(object_context), + world_(franka_plant_.world_frame()), + end_effector_name_(end_effector_name) { + this->set_name("franka_kinematics"); + franka_state_port_ = + this->DeclareVectorInputPort( + "x_franka", OutputVector(franka_plant.num_positions(), + franka_plant.num_velocities(), + franka_plant.num_actuators())) + .get_index(); + + object_state_port_ = + this->DeclareVectorInputPort( + "x_object", OutputVector(object_plant.num_positions(), + object_plant.num_velocities(), + object_plant.num_actuators())) + .get_index(); + + lcs_state_port_ = + this->DeclareVectorOutputPort("lcs_state", + TimestampedVector(3 + 7 + 3 + 6), + &FrankaKinematics::ComputeLCSState) + .get_index(); +} + +void FrankaKinematics::ComputeLCSState( + const drake::systems::Context& context, + TimestampedVector* lcs_state) const { + const OutputVector* franka_output = + (OutputVector*)this->EvalVectorInput(context, franka_state_port_); + const OutputVector* object_output = + (OutputVector*)this->EvalVectorInput(context, object_state_port_); + + VectorXd q_franka = franka_output->GetPositions(); + VectorXd v_franka = franka_output->GetVelocities(); + VectorXd q_object = object_output->GetPositions(); + VectorXd v_object = object_output->GetVelocities(); + multibody::SetPositionsIfNew(franka_plant_, q_franka, + franka_context_); + multibody::SetVelocitiesIfNew(franka_plant_, v_franka, + franka_context_); + + auto end_effector_pose = franka_plant_.EvalBodyPoseInWorld( + *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); + auto end_effector_spatial_velocity = + franka_plant_.EvalBodySpatialVelocityInWorld( + *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); + + VectorXd lcs_output = VectorXd::Zero(lcs_state->size() - 1); + lcs_output << end_effector_pose.translation(), q_object, + end_effector_spatial_velocity.translational(), v_object; + + lcs_state->set_timestamp(franka_output->get_timestamp()); + lcs_state->SetDataVector(lcs_output); +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/franka_kinematics.h b/examples/franka/franka_kinematics.h new file mode 100644 index 0000000000..e2a361d552 --- /dev/null +++ b/examples/franka/franka_kinematics.h @@ -0,0 +1,53 @@ +#pragma once + +#include +#include +#include + +#include "drake/systems/framework/leaf_system.h" +#include "systems/framework/timestamped_vector.h" +#include "systems/framework/output_vector.h" + +namespace dairlib { +namespace systems { + +/// Outputs a lcmt_timestamped_saved_traj +class FrankaKinematics : public drake::systems::LeafSystem { + public: + explicit FrankaKinematics(const drake::multibody::MultibodyPlant& franka_plant, + drake::systems::Context* franka_context, + const drake::multibody::MultibodyPlant& object_plant, + drake::systems::Context* object_context, + const std::string& end_effector_name); + + const drake::systems::InputPort& get_input_port_object_state() const { + return this->get_input_port(object_state_port_); + } + + const drake::systems::InputPort& get_input_port_franka_state() const { + return this->get_input_port(franka_state_port_); + } + + const drake::systems::OutputPort& get_output_port_lcs_state() const { + return this->get_output_port(lcs_state_port_); + } + + private: + void ComputeLCSState( + const drake::systems::Context& context, + TimestampedVector* output_traj) const; + + drake::systems::InputPortIndex franka_state_port_; + drake::systems::InputPortIndex object_state_port_; + drake::systems::OutputPortIndex lcs_state_port_; + + const drake::multibody::MultibodyPlant& franka_plant_; + drake::systems::Context* franka_context_; + const drake::multibody::MultibodyPlant& object_plant_; + drake::systems::Context* object_context_; + const drake::multibody::Frame& world_; + std::string end_effector_name_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/solvers/c3.cc b/solvers/c3.cc index 73f86d582f..8f3f7d1cad 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -3,6 +3,7 @@ #include #include +#include #include "solvers/lcs.h" @@ -97,7 +98,6 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, MatrixXd LinEq(n_, 2 * n_ + k_ + m_); LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); - for (int i = 0; i < N_; i++) { LinEq.block(0, 0, n_, n_) = A_.at(i); LinEq.block(0, n_, n_, k_) = B_.at(i); @@ -106,7 +106,6 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, prog_.AddLinearEqualityConstraint( LinEq, -d_.at(i), {x_.at(i), u_.at(i), lambda_.at(i), x_.at(i + 1)}); } - for (int i = 0; i < N_ + 1; i++) { prog_.AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * xdesired_.at(i), x_.at(i), 1); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index ea2fde752f..901cdc439a 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -72,7 +72,6 @@ std::pair LCSFactory::LinearizePlantToLCS( VectorXd d_v = d_vv - x_dvvcomp; /////////// - // AutoDiffVecXd state = plant_ad.get_state_output_port().Eval(context_ad); AutoDiffVecXd x_ad = plant_ad.GetPositionsAndVelocities(context_ad); AutoDiffVecXd qdot_no_contact(plant.num_positions()); AutoDiffVecXd vel_ad = x_ad.tail(n_v); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index b20e9d56d9..8049cbe8eb 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -11,6 +11,7 @@ using drake::systems::BasicVector; using Eigen::VectorXd; using solvers::C3MIQP; using solvers::LCS; +using systems::TimestampedVector; namespace systems { @@ -20,14 +21,16 @@ C3Controller::C3Controller(LCS& lcs, C3Options c3_options, std::vector G, std::vector U) : lcs_(lcs), Q_(Q), R_(R), G_(G), U_(U) { + DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); target_input_port_ = this->DeclareVectorInputPort("desired_position", BasicVector(2 + 16)) .get_index(); lcs_state_input_port_ = - this->DeclareVectorInputPort("x_lcs", BasicVector(10)) + this->DeclareVectorInputPort("x_lcs", TimestampedVector(lcs.A_[0].rows())) .get_index(); - std::vector x_desired = {VectorXd::Zero(3)}; + std::vector x_desired = + std::vector(Q_.size() + 1, VectorXd::Zero(lcs.A_[0].rows())); c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options); this->set_name("c3_controller"); @@ -43,7 +46,7 @@ void C3Controller::OutputTrajectory( dairlib::lcmt_timestamped_saved_traj* output_traj) const { // const BasicVector& x_des = // *this->template EvalVectorInput(context, target_input_port_); - const BasicVector& x = *this->template EvalVectorInput( + const BasicVector& x = *this->template EvalVectorInput( context, lcs_state_input_port_); // delta // in order: diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index d4afd34fef..fd300a93f8 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -12,6 +12,7 @@ #include "solvers/lcs.h" #include "drake/systems/framework/leaf_system.h" +#include "systems/framework/timestamped_vector.h" namespace dairlib { namespace systems { From 6ecdae66e8e5e3cb4dc4a3509effd208cfdc05e1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 31 Mar 2023 12:11:03 -0400 Subject: [PATCH 420/758] fixing changes --- examples/franka/franka_c3_controller.cc | 2 +- systems/controllers/c3_controller.cc | 14 +++++++------- systems/controllers/c3_controller.h | 9 +++++---- 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 11a08bcd26..1d94313022 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -133,7 +133,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), "paddle"); auto trajectory_sender = - builder.AddSystem(LcmPublisherSystem::Make( + builder.AddSystem(LcmPublisherSystem::Make( controller_params.c3_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); drake::AutoDiffVecXd q_v_u_ad = diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 8049cbe8eb..6dc640818b 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -16,11 +16,11 @@ using systems::TimestampedVector; namespace systems { C3Controller::C3Controller(LCS& lcs, C3Options c3_options, - std::vector Q, - std::vector R, - std::vector G, - std::vector U) - : lcs_(lcs), Q_(Q), R_(R), G_(G), U_(U) { + std::vector& Q, + std::vector& R, + std::vector& G, + std::vector& U) + : lcs_(lcs), Q_(Q), R_(R), G_(G), U_(U), N_(Q_.size()) { DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); target_input_port_ = this->DeclareVectorInputPort("desired_position", BasicVector(2 + 16)) @@ -52,8 +52,8 @@ void C3Controller::OutputTrajectory( // in order: // state, forces, inputs // initialize with zeros or current state - std::vector delta(1, VectorXd::Zero(1)); - std::vector w(1, VectorXd::Zero(1)); + std::vector delta(N_, VectorXd::Zero(1)); + std::vector w(N_, VectorXd::Zero(1)); c3_->Solve(x.value(), delta, w); } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index fd300a93f8..25b6cfbbb2 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -21,10 +21,10 @@ namespace systems { class C3Controller : public drake::systems::LeafSystem { public: explicit C3Controller(solvers::LCS& lcs, C3Options c3_options, - std::vector Q, - std::vector R, - std::vector G, - std::vector U); + std::vector& Q, + std::vector& R, + std::vector& G, + std::vector& U); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(target_input_port_); @@ -54,6 +54,7 @@ class C3Controller : public drake::systems::LeafSystem { std::vector R_; std::vector G_; std::vector U_; + int N_; }; } // namespace systems From 75d9595932a175471768439cafe39ef77716635e Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 31 Mar 2023 15:01:14 -0400 Subject: [PATCH 421/758] debugging ADMMStep --- examples/franka/franka_c3_controller.cc | 72 ++++++---------- examples/franka/franka_c3_controller_params.h | 45 ---------- .../franka/franka_c3_controller_params.yaml | 20 +---- examples/franka/franka_c3_options.yaml | 22 ++++- .../urdf/plate_end_effector_translation.urdf | 31 ++++--- solvers/c3.cc | 4 +- solvers/c3_options.h | 49 +++++++++++ systems/controllers/c3_controller.cc | 82 ++++++++++++++----- systems/controllers/c3_controller.h | 31 +++++-- systems/system_utils.cc | 4 +- 10 files changed, 203 insertions(+), 157 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 1d94313022..fa327b92a2 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -31,6 +31,7 @@ using drake::geometry::GeometryId; using drake::math::RigidTransform; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::multibody::AddMultibodyPlantSceneGraph; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -60,10 +61,14 @@ int DoMain(int argc, char* argv[]) { C3Options c3_options = drake::yaml::LoadYamlFile(controller_params.c3_options_file); + + DiagramBuilder plant_builder; + /// MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); + parser_franka.package_map().Add("franka_urdfs", "examples/franka/urdf"); parser_franka.AddModelFromFile(controller_params.franka_model); RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), @@ -79,20 +84,21 @@ int DoMain(int argc, char* argv[]) { auto tray_context = plant_tray.CreateDefaultContext(); /// - MultibodyPlant plant_plate(0.0); +// MultibodyPlant plant_plate(0.0); + auto [plant_plate, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); Parser parser_plate(&plant_plate); - parser_plate.package_map().Add("franka_urdfs", "examples/franka/urdf"); parser_plate.AddModelFromFile(controller_params.plate_model); parser_plate.AddModelFromFile(controller_params.tray_model); plant_plate.WeldFrames(plant_plate.world_frame(), plant_plate.GetFrameByName("base_link"), X_WI); plant_plate.Finalize(); - std::unique_ptr> plant_plate_ad = drake::systems::System::ToAutoDiffXd(plant_plate); - auto plate_context = plant_plate.CreateDefaultContext(); + auto plant_diagram = plant_builder.Build(); + std::unique_ptr> diagram_context = plant_diagram->CreateDefaultContext(); + auto& plate_context = plant_diagram->GetMutableSubsystemContext(plant_plate, diagram_context.get()); auto plate_context_ad = plant_plate_ad->CreateDefaultContext(); /// @@ -102,22 +108,21 @@ int DoMain(int argc, char* argv[]) { std::vector tray_geoms = plant_plate.GetCollisionGeometriesForBody( plant_plate.GetBodyByName("tray")); - // drake::geometry::GeometryId ground_geoms = - // plant_plate.GetCollisionGeometriesForBody(plant_plate.GetBodyByName("box"))[0]; - // drake::geometry::GeometryId sphere_geoms2 = - // plant_plate.GetCollisionGeometriesForBody(plant_plate.GetBodyByName("sphere2"))[0]; - // std::vector contact_geoms = {plate_geoms, - // tray_geoms}; std::unordered_map> contact_geoms; contact_geoms["PLATE"] = plate_contact_points; contact_geoms["TRAY"] = tray_geoms; std::vector> contact_pairs; - for (auto geom_id : plate_contact_points) { - contact_pairs.push_back(SortedPair(geom_id, contact_geoms["TRAY"][0])); + for (auto geom_id : contact_geoms["PLATE"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); } - + std::cout << "n_contacts: " << contact_pairs.size() << std::endl; + std::cout << "plate_contacts: " << plate_contact_points.size() << std::endl; + std::cout << "tray_contacts: " << tray_geoms.size() << std::endl; + std::cout << "num_positions: " << plant_plate.num_positions() << std::endl; + std::cout << "num_velocities: " << plant_plate.num_velocities() << std::endl; + std::cout << "num_actuators: " << plant_plate.num_actuators() << std::endl; /// DiagramBuilder builder; @@ -136,41 +141,9 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( controller_params.c3_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); - drake::AutoDiffVecXd q_v_u_ad = - drake::math::InitializeAutoDiff(VectorXd::Zero( - plant_plate_ad->num_positions() + plant_plate_ad->num_velocities() + - plant_plate_ad->num_actuators())); - std::cout << "num_positions: " << plant_plate_ad->num_positions() - << std::endl; - std::cout << "num_velocities: " << plant_plate_ad->num_velocities() - << std::endl; - std::cout << "num_actuators: " << plant_plate_ad->num_actuators() - << std::endl; - VectorXd q_v_u = VectorXd::Zero(plant_plate.num_positions() + - plant_plate.num_velocities() + - plant_plate.num_actuators()); - q_v_u[0] = 1; - q_v_u[4] = 1; - q_v_u_ad[0] = 1; - q_v_u_ad[4] = 1; - - int n_x = plant_plate_ad->num_positions() + plant_plate_ad->num_velocities(); - int n_u = plant_plate_ad->num_actuators(); - - plant_plate_ad->SetPositionsAndVelocities(plate_context_ad.get(), - q_v_u_ad.head(n_x)); - plant_plate.SetPositionsAndVelocities(plate_context.get(), q_v_u.head(n_x)); - auto lcs = LCSFactory::LinearizePlantToLCS( - plant_plate, *plate_context, *plant_plate_ad, *plate_context_ad, - contact_pairs, controller_params.num_friction_directions, - controller_params.mu, controller_params.dt, controller_params.N); - - auto Q = std::vector(controller_params.N + 1, controller_params.Q); - auto R = std::vector(controller_params.N, controller_params.R); - auto G = std::vector(controller_params.N, controller_params.G); - auto U = std::vector(controller_params.N, controller_params.U); + auto controller = builder.AddSystem( - lcs.first, c3_options, Q, R, G, U); + plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); @@ -183,8 +156,13 @@ int DoMain(int argc, char* argv[]) { builder.Connect(controller->get_output_port_trajectory(), trajectory_sender->get_input_port()); +// std::unique_ptr> diagram_context = plant_diagram->CreateDefaultContext(); + auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); + plant_diagram->set_name(("franka_c3_plant")); + DrawAndSaveDiagramGraph(*plant_diagram); + // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), franka_state_receiver, diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index 5be67d71bc..993109b88e 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -13,63 +13,18 @@ struct FrankaC3ControllerParams { std::string c3_channel; std::string state_channel; std::string radio_channel; - - double mu; - double mu_plate; - double dt; - int num_friction_directions; std::string franka_model; std::string plate_model; std::string tray_model; - int N; - double w_Q; - double w_R; - double w_G; - double w_U; - - int g_size; - int u_size; - std::vector q_vector; - - std::vector r_vector; - MatrixXd Q; - MatrixXd R; - MatrixXd G; - MatrixXd U; - template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(c3_options_file)); a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(state_channel)); a->Visit(DRAKE_NVP(radio_channel)); - a->Visit(DRAKE_NVP(mu)); - a->Visit(DRAKE_NVP(mu_plate)); - a->Visit(DRAKE_NVP(dt)); - a->Visit(DRAKE_NVP(num_friction_directions)); a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(plate_model)); a->Visit(DRAKE_NVP(tray_model)); - - a->Visit(DRAKE_NVP(N)); - a->Visit(DRAKE_NVP(w_Q)); - a->Visit(DRAKE_NVP(w_R)); - a->Visit(DRAKE_NVP(w_G)); - a->Visit(DRAKE_NVP(w_U)); - a->Visit(DRAKE_NVP(g_size)); - a->Visit(DRAKE_NVP(u_size)); - a->Visit(DRAKE_NVP(q_vector)); - a->Visit(DRAKE_NVP(r_vector)); - - Eigen::VectorXd q = Eigen::Map( - this->q_vector.data(), this->q_vector.size()); - Eigen::VectorXd r = Eigen::Map( - this->r_vector.data(), this->r_vector.size()); - - Q = q.asDiagonal(); - R = r.asDiagonal(); - G = w_G * MatrixXd::Identity(g_size, g_size); - U = w_U * MatrixXd::Identity(u_size, u_size); } }; \ No newline at end of file diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 5fa1b31bb4..670498f743 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -3,27 +3,11 @@ c3_channel: C3_TRAJECTORY state_channel: FRANKA_OUTPUT radio_channel: CASSIE_VIRTUAL_RADIO -mu: 1 -mu_plate: 1 -dt: 0.015 -num_friction_directions: 4 + franka_model: examples/franka/urdf/franka.urdf #plate_model: examples/franka/urdf/plate_end_effector.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf tray_model: examples/franka/urdf/tray.sdf -N: 5 -w_Q: 0.01 -w_R: 0.01 -# Penalty on all decision variables, assuming scalar -w_G: 0.001 -# Penalty on all decision variables, assuming scalar -w_U: 0.001 -g_size: 10 -u_size: 10 -# State Tracking Error, assuming diagonal -q_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1] -# Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1] + diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index b4b96e558f..297501cb54 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -2,4 +2,24 @@ admm_iter: 2 rho: 0.1 rho_scale: 3 num_threads: 0 -delta_option: 1 \ No newline at end of file +delta_option: 1 + +mu: 1 +mu_plate: 1 +dt: 0.015 +num_friction_directions: 4 +N: 5 +w_Q: 0.01 +w_R: 0.01 +# Penalty on all decision variables, assuming scalar +w_G: 0.001 +# Penalty on all decision variables, assuming scalar +w_U: 0.001 + +g_size: 10 +u_size: 10 +# State Tracking Error, assuming diagonal +q_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1] +# Penalty on efforts, assuming diagonal +r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 093f454724..d67b0fec23 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -15,18 +15,18 @@ iyz="0" izz="0.013"/> - - - - - - - - - - - - + + + + + + + + + + + + @@ -53,24 +53,23 @@ - + - + - + - diff --git a/solvers/c3.cc b/solvers/c3.cc index 8f3f7d1cad..04baab2ad4 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -226,14 +226,16 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, prog_.RemoveConstraint(constraint); } constraints_.clear(); - constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); if (hflag_ == 1) { + std::cout << "hflag true: " << std::endl; drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); + std::cout << "adding constraint: " << std::endl; constraints_.push_back(prog_.AddLinearConstraint(lambda_[0] == lambda0)); + std::cout << "added constraint: " << std::endl; } for (auto& cost : costs_) { diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 585dc8ca0a..9eb3e24eb9 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -3,6 +3,9 @@ #include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" +using Eigen::MatrixXd; +using Eigen::VectorXd; + struct C3Options { // Hyperparameters int admm_iter = 2; // total number of ADMM iterations //2 @@ -10,6 +13,28 @@ struct C3Options { float rho_scale = 3; // scaling of rho parameter (/rho = rho_scale * /rho) //3 int num_threads = 0; // 0 is dynamic, greater than 0 for a fixed count int delta_option = 1; // different options for delta update + + int N; + double w_Q; + double w_R; + double w_G; + double w_U; + + int g_size; + int u_size; + + std::vector q_vector; + std::vector r_vector; + + double mu; + double mu_plate; + double dt; + int num_friction_directions; + MatrixXd Q; + MatrixXd R; + MatrixXd G; + MatrixXd U; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(admm_iter)); @@ -18,5 +43,29 @@ struct C3Options { a->Visit(DRAKE_NVP(num_threads)); a->Visit(DRAKE_NVP(delta_option)); + a->Visit(DRAKE_NVP(mu)); + a->Visit(DRAKE_NVP(mu_plate)); + a->Visit(DRAKE_NVP(dt)); + a->Visit(DRAKE_NVP(num_friction_directions)); + + a->Visit(DRAKE_NVP(N)); + a->Visit(DRAKE_NVP(w_Q)); + a->Visit(DRAKE_NVP(w_R)); + a->Visit(DRAKE_NVP(w_G)); + a->Visit(DRAKE_NVP(w_U)); + a->Visit(DRAKE_NVP(g_size)); + a->Visit(DRAKE_NVP(u_size)); + a->Visit(DRAKE_NVP(q_vector)); + a->Visit(DRAKE_NVP(r_vector)); + + Eigen::VectorXd q = Eigen::Map( + this->q_vector.data(), this->q_vector.size()); + Eigen::VectorXd r = Eigen::Map( + this->r_vector.data(), this->r_vector.size()); + + Q = q.asDiagonal(); + R = r.asDiagonal(); + G = w_G * MatrixXd::Identity(g_size, g_size); + U = w_U * MatrixXd::Identity(u_size, u_size); } }; \ No newline at end of file diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 6dc640818b..348d93483b 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -1,9 +1,11 @@ #include "c3_controller.h" #include +#include #include "common/find_resource.h" #include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "solvers/lcs_factory.h" namespace dairlib { @@ -11,27 +13,42 @@ using drake::systems::BasicVector; using Eigen::VectorXd; using solvers::C3MIQP; using solvers::LCS; +using solvers::LCSFactory; using systems::TimestampedVector; namespace systems { -C3Controller::C3Controller(LCS& lcs, C3Options c3_options, - std::vector& Q, - std::vector& R, - std::vector& G, - std::vector& U) - : lcs_(lcs), Q_(Q), R_(R), G_(G), U_(U), N_(Q_.size()) { - DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); +C3Controller::C3Controller( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector>& + contact_geoms, + C3Options c3_options) + : plant_(plant), + context_(context), + plant_ad_(plant_ad), + context_ad_(context_ad), + contact_pairs_(contact_geoms), + c3_options_(std::move(c3_options)), + Q_(std::vector(c3_options_.N + 1, c3_options_.Q)), + R_(std::vector(c3_options_.N, c3_options_.R)), + G_(std::vector(c3_options_.N, c3_options_.G)), + U_(std::vector(c3_options_.N, c3_options_.U)) { + // DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); + n_q_ = plant_.num_positions(); + n_v_ = plant_.num_velocities(); + n_u_ = plant_.num_actuators(); + target_input_port_ = this->DeclareVectorInputPort("desired_position", BasicVector(2 + 16)) .get_index(); lcs_state_input_port_ = - this->DeclareVectorInputPort("x_lcs", TimestampedVector(lcs.A_[0].rows())) + this->DeclareVectorInputPort("x_lcs", + TimestampedVector(n_q_ + n_v_)) .get_index(); - std::vector x_desired = - std::vector(Q_.size() + 1, VectorXd::Zero(lcs.A_[0].rows())); - c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options); this->set_name("c3_controller"); trajectory_output_port_ = @@ -44,17 +61,42 @@ C3Controller::C3Controller(LCS& lcs, C3Options c3_options, void C3Controller::OutputTrajectory( const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const { -// const BasicVector& x_des = -// *this->template EvalVectorInput(context, target_input_port_); - const BasicVector& x = *this->template EvalVectorInput( - context, lcs_state_input_port_); - // delta - // in order: - // state, forces, inputs - // initialize with zeros or current state + // const BasicVector& x_des = + // *this->template EvalVectorInput(context, + // target_input_port_); + const TimestampedVector& x = + *this->template EvalVectorInput(context, + lcs_state_input_port_); + + VectorXd q_v_u = + VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + + plant_.num_actuators()); + q_v_u << x.get_data(), VectorXd::Zero(n_u_); + drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); + + std::vector x_desired = + std::vector(Q_.size() + 1, VectorXd::Zero(n_q_ + n_v_)); + // q_v_u[0] = 1; + // q_v_u[4] = 1; + // q_v_u_ad[0] = 1; + // q_v_u_ad[4] = 1; + + int n_x = plant_.num_positions() + plant_.num_velocities(); + int n_u = plant_.num_actuators(); + + plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x)); + plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); + auto lcs = LCSFactory::LinearizePlantToLCS( + plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, + c3_options_.N); + c3_ = std::make_unique(lcs.first, Q_, R_, G_, U_, x_desired, + c3_options_); + std::vector delta(N_, VectorXd::Zero(1)); std::vector w(N_, VectorXd::Zero(1)); - c3_->Solve(x.value(), delta, w); + c3_->Solve(x.get_data(), delta, w); + *output_traj = dairlib::lcmt_timestamped_saved_traj(); } } // namespace systems diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 25b6cfbbb2..caca449b7c 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -10,9 +10,9 @@ #include "solvers/c3_miqp.h" #include "solvers/c3_options.h" #include "solvers/lcs.h" +#include "systems/framework/timestamped_vector.h" #include "drake/systems/framework/leaf_system.h" -#include "systems/framework/timestamped_vector.h" namespace dairlib { namespace systems { @@ -20,11 +20,14 @@ namespace systems { /// Outputs a lcmt_timestamped_saved_traj class C3Controller : public drake::systems::LeafSystem { public: - explicit C3Controller(solvers::LCS& lcs, C3Options c3_options, - std::vector& Q, - std::vector& R, - std::vector& G, - std::vector& U); + explicit C3Controller( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector>& + contact_geoms, + C3Options c3_options); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(target_input_port_); @@ -47,8 +50,20 @@ class C3Controller : public drake::systems::LeafSystem { drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::OutputPortIndex trajectory_output_port_; - std::unique_ptr c3_; - solvers::LCS lcs_; + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::MultibodyPlant& plant_ad_; + drake::systems::Context* context_ad_; + const std::vector>& + contact_pairs_; + C3Options c3_options_; + + int n_q_; + int n_v_; + int n_u_; + + mutable std::unique_ptr c3_; + // solvers::LCS lcs_; std::vector Q_; std::vector R_; diff --git a/systems/system_utils.cc b/systems/system_utils.cc index 3ed7c3d19e..478760833b 100644 --- a/systems/system_utils.cc +++ b/systems/system_utils.cc @@ -8,7 +8,9 @@ namespace dairlib { void DrawAndSaveDiagramGraph(const drake::systems::Diagram& diagram, std::string path) { // Default path - if (path.empty()) path = "../" + diagram.get_name(); + if (path.empty()){ + path = "../" + diagram.get_name(); + } // Save Graphviz string to a file std::ofstream out(path); From 83aa3b6a1bf809f6e0835dc4b99ba701b3dd1270 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 31 Mar 2023 15:27:30 -0400 Subject: [PATCH 422/758] osqp prob is nonconvex --- solvers/c3.cc | 58 +++------------------------- systems/controllers/c3_controller.cc | 16 +++++--- 2 files changed, 17 insertions(+), 57 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index 04baab2ad4..8a7e980c37 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -1,9 +1,9 @@ #include "solvers/c3.h" #include +#include #include -#include #include "solvers/lcs.h" @@ -114,7 +114,7 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, } } - OSQPoptions_.SetOption(OsqpSolver::id(), "verbose", 0); + OSQPoptions_.SetOption(OsqpSolver::id(), "verbose", 1); // OSQPoptions_.SetOption(OsqpSolver::id(), "ebs_abs", 1e-7); // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); @@ -129,13 +129,7 @@ VectorXd C3::Solve(const VectorXd& x0, vector& delta, VectorXd z; for (int i = 0; i < options_.admm_iter - 1; i++) { - // std::cout << "Iteration" << i << std::endl; - z = ADMMStep(x0, &delta, &w, &Gv); - // std::cout << "new delta" << i << std::endl; - // std::cout << delta.at(0).segment(n_,m_) << std::endl; - // std::cout << "w" << i << std::endl; - // std::cout << w.at(0) << std::endl; } vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); @@ -147,43 +141,6 @@ VectorXd C3::Solve(const VectorXd& x0, vector& delta, z = zfin[0]; - // std::cout << "contact prediction" << std::endl; - // std::cout << zfin[0].segment(n_, m_) << std::endl; - - // std::cout << "violation" << std::endl; - // std::cout << delta.at(0) << std::endl; - - // std::cout << "delta_force" << std::endl; - // std::cout << delta.at(0).segment(n_,m_) << std::endl; - // - // std::cout << "delta_displace" << std::endl; - // std::cout << delta.at(0).segment(0,n_) << std::endl; - - // VectorXd hold = delta.at(0).segment(n_,m_); - // VectorXd hold = z.segment(n_,m_); - - // double count = 0; - // - // for (int i = 3; i < 5; i++) { - // count = count + hold(i); - // } - // - // if ( count >= 0.001){ - // std::cout << "guessing_contact" << std::endl; - // } - - // std::cout << "w" << std::endl; - // std::cout << w.at(0).segment(n_+3,3) << std::endl; - - // std::cout << "input" << std::endl; - // std::cout << z.segment(n_+m_, k_) << std::endl; - - // std::cout << "contact prediction" << std::endl; - // std::cout << z.segment(n_, m_) << std::endl; - - // std::cout << "prediction state" << std::endl; - // std::cout << z.segment(0, n_) << std::endl; - return z.segment(n_ + m_, k_); } @@ -229,13 +186,10 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); if (hflag_ == 1) { - std::cout << "hflag true: " << std::endl; drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); - std::cout << "adding constraint: " << std::endl; constraints_.push_back(prog_.AddLinearConstraint(lambda_[0] == lambda0)); - std::cout << "added constraint: " << std::endl; } for (auto& cost : costs_) { @@ -328,10 +282,10 @@ vector C3::SolveProjection(vector& G, vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); int i; -// if (options_.num_threads > 0) { -// omp_set_dynamic(0); // Explicitly disable dynamic teams -// omp_set_num_threads(options_.num_threads); // Set number of threads -// } + // if (options_.num_threads > 0) { + // omp_set_dynamic(0); // Explicitly disable dynamic teams + // omp_set_num_threads(options_.num_threads); // Set number of threads + // } #pragma omp parallel for for (i = 0; i < N_; i++) { diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 348d93483b..3a2630953f 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -35,7 +35,8 @@ C3Controller::C3Controller( Q_(std::vector(c3_options_.N + 1, c3_options_.Q)), R_(std::vector(c3_options_.N, c3_options_.R)), G_(std::vector(c3_options_.N, c3_options_.G)), - U_(std::vector(c3_options_.N, c3_options_.U)) { + U_(std::vector(c3_options_.N, c3_options_.U)), + N_(c3_options_.N){ // DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); @@ -86,15 +87,20 @@ void C3Controller::OutputTrajectory( plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x)); plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); - auto lcs = LCSFactory::LinearizePlantToLCS( + auto lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N); - c3_ = std::make_unique(lcs.first, Q_, R_, G_, U_, x_desired, + auto lcs = lcs_pair.first; + c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); - std::vector delta(N_, VectorXd::Zero(1)); - std::vector w(N_, VectorXd::Zero(1)); +// int N = (system_.A_).size(); + int n = ((lcs.A_)[0].cols()); + int m = ((lcs.D_)[0].cols()); + int k = ((lcs.B_)[0].cols()); + std::vector delta(N_, VectorXd::Zero(n + m + k)); + std::vector w(N_, VectorXd::Zero(n + m + k)); c3_->Solve(x.get_data(), delta, w); *output_traj = dairlib::lcmt_timestamped_saved_traj(); } From 74c4405c1eb9368a559bb0c6e58cdc30f1da72fb Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 2 Apr 2023 12:15:10 -0400 Subject: [PATCH 423/758] fixing size of G and U --- examples/franka/franka_c3_options.yaml | 5 +++-- solvers/c3.cc | 7 +++---- solvers/c3_options.h | 2 ++ solvers/lcs.cc | 2 +- solvers/lcs.h | 4 ++++ systems/controllers/c3_controller.cc | 6 ++++++ 6 files changed, 19 insertions(+), 7 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index 297501cb54..d99476c0f9 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -8,6 +8,7 @@ mu: 1 mu_plate: 1 dt: 0.015 num_friction_directions: 4 +num_contacts: 3 N: 5 w_Q: 0.01 w_R: 0.01 @@ -16,8 +17,8 @@ w_G: 0.001 # Penalty on all decision variables, assuming scalar w_U: 0.001 -g_size: 10 -u_size: 10 +g_size: 52 +u_size: 52 # State Tracking Error, assuming diagonal q_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/solvers/c3.cc b/solvers/c3.cc index 8a7e980c37..514e1a2f32 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -201,17 +201,16 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, if (i < N_) { costs_.push_back(prog_.AddQuadraticCost( G.at(i).block(0, 0, n_, n_) * 2, - -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), x_.at(i), - 1)); + -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), x_.at(i))); costs_.push_back(prog_.AddQuadraticCost( G.at(i).block(n_, n_, m_, m_) * 2, -2 * G.at(i).block(n_, n_, m_, m_) * WD.at(i).segment(n_, m_), - lambda_.at(i), 1)); + lambda_.at(i))); costs_.push_back( prog_.AddQuadraticCost(G.at(i).block(n_ + m_, n_ + m_, k_, k_) * 2, -2 * G.at(i).block(n_ + m_, n_ + m_, k_, k_) * WD.at(i).segment(n_ + m_, k_), - u_.at(i), 1)); + u_.at(i))); } } diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 9eb3e24eb9..f89921c4d5 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -30,6 +30,7 @@ struct C3Options { double mu_plate; double dt; int num_friction_directions; + int num_contacts; MatrixXd Q; MatrixXd R; MatrixXd G; @@ -47,6 +48,7 @@ struct C3Options { a->Visit(DRAKE_NVP(mu_plate)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(num_friction_directions)); + a->Visit(DRAKE_NVP(num_contacts)); a->Visit(DRAKE_NVP(N)); a->Visit(DRAKE_NVP(w_Q)); diff --git a/solvers/lcs.cc b/solvers/lcs.cc index 8a0e2851c8..f1f7873336 100644 --- a/solvers/lcs.cc +++ b/solvers/lcs.cc @@ -16,7 +16,7 @@ LCS::LCS(const vector& A, const vector& B, const vector& D, const vector& d, const vector& E, const vector& F, const vector& H, const vector& c) - : A_(A), B_(B), D_(D), d_(d), E_(E), F_(F), H_(H), c_(c), N_(A.size()) {} + : A_(A), B_(B), D_(D), d_(d), E_(E), F_(F), H_(H), c_(c), N_(A.size()), n_(A_[0].rows()), m_(D_[0].cols()), k_(H_[0].cols()) {} LCS::LCS(const MatrixXd& A, const MatrixXd& B, const MatrixXd& D, const VectorXd& d, const MatrixXd& E, const MatrixXd& F, diff --git a/solvers/lcs.h b/solvers/lcs.h index 2300d4c5b2..3b549b88c7 100644 --- a/solvers/lcs.h +++ b/solvers/lcs.h @@ -46,6 +46,10 @@ class LCS { const std::vector H_; const std::vector c_; const int N_; + + const int n_; + const int m_; + const int k_; }; } // namespace solvers diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 3a2630953f..8e8c1f5a0c 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -92,6 +92,12 @@ void C3Controller::OutputTrajectory( c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N); auto lcs = lcs_pair.first; + DRAKE_DEMAND(Q_.front().rows() == lcs.n_); + DRAKE_DEMAND(Q_.front().cols() == lcs.n_); + DRAKE_DEMAND(R_.front().rows() == lcs.k_); + DRAKE_DEMAND(R_.front().cols() == lcs.k_); + DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); + DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); From 7ab9fa2d04cf6c9bf1b68144d582e598ba0ff5e7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 2 Apr 2023 16:59:48 -0400 Subject: [PATCH 424/758] need to construct trajectory --- examples/franka/BUILD.bazel | 1 + examples/franka/franka_osc_controller.cc | 27 +++++++++++++++---- lcm/lcm_trajectory.cc | 2 +- lcm/lcm_trajectory.h | 2 +- .../lcm_trajectory_systems.cc | 21 +++++++++------ .../lcm_trajectory_systems.h | 4 +-- 6 files changed, 40 insertions(+), 17 deletions(-) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 8ae587b664..15dc7f82d8 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -42,6 +42,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", + "//systems/trajectory_optimization:lcm_trajectory_systems", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index cee02f8182..9439d5dca0 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -1,6 +1,7 @@ #include #include +#include #include "examples/franka/franka_controller_params.h" #include "examples/franka/systems/end_effector_trajectory.h" @@ -23,6 +24,8 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" +#include "lcm/lcm_trajectory.h" namespace dairlib { @@ -95,12 +98,23 @@ int DoMain(int argc, char* argv[]) { plant.Finalize(); auto plant_context = plant.CreateDefaultContext(); + +// lcmt_trajectory_block traj_block; +// traj_block.datapoints.push_back({0.65, 0.0, 0.3}); +// traj_block.time_vec.push_back({0.0}); +// auto default_traj = LcmTrajectory::Trajectory("end_effector_traj", traj_block); +// auto default_lcm_traj = LcmTrajectory({default_traj}, {"end_effector_traj"}, "default_franka_trajectory", ""); +// default_lcm_traj.WriteToFile("default_end_effector_pose"); + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant); - auto trajectory_receiver = - builder.AddSystem(LcmSubscriberSystem::Make( + auto trajectory_sub = + builder.AddSystem(LcmSubscriberSystem::Make( controller_params.c3_channel, &lcm)); + auto trajectory_receiver = + builder.AddSystem( + "end_effector_trajectory"); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( controller_params.controller_channel, &lcm, @@ -181,8 +195,7 @@ int DoMain(int argc, char* argv[]) { end_effector_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_trajectory->get_input_port_radio()); - builder.Connect(end_effector_trajectory->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_command(), @@ -191,7 +204,11 @@ int DoMain(int argc, char* argv[]) { osc_debug_pub->get_input_port()); builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); - + builder.Connect(trajectory_sub->get_output_port(), trajectory_receiver->get_input_port_trajectory()); +// builder.Connect(end_effector_trajectory->get_output_port(0), +// osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect(trajectory_receiver->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_target")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); // Run lcm-driven simulation diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index 92c717d2f1..973aabe79c 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -38,7 +38,7 @@ std::string exec(const char* cmd) { return result; } -LcmTrajectory::Trajectory::Trajectory(string traj_name, +LcmTrajectory::Trajectory::Trajectory(const string& traj_name, const lcmt_trajectory_block& traj_block) { int num_points = traj_block.num_points; int num_datatypes = traj_block.num_datatypes; diff --git a/lcm/lcm_trajectory.h b/lcm/lcm_trajectory.h index d2cd1b8167..6a376dd692 100644 --- a/lcm/lcm_trajectory.h +++ b/lcm/lcm_trajectory.h @@ -27,7 +27,7 @@ class LcmTrajectory { /// lcmt_trajectory_block is the lcmtype analog struct Trajectory { Trajectory() = default; - Trajectory(std::string traj_name, const lcmt_trajectory_block& traj_block); + Trajectory(const std::string& traj_name, const lcmt_trajectory_block& traj_block); std::string traj_name; Eigen::VectorXd time_vector; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index d77bfa10b6..c4a45b3a19 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -1,13 +1,15 @@ #include "lcm_trajectory_systems.h" -#include "dairlib/lcmt_timestamped_saved_traj.hpp" -#include "common/find_resource.h" #include +#include "common/find_resource.h" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" + namespace dairlib { namespace systems { using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) : trajectory_name_(std::move(trajectory_name)) { @@ -17,29 +19,32 @@ LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) drake::Value{}) .get_index(); - PiecewisePolynomial traj_inst(Eigen::VectorXd(0)); + PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; this->set_name(trajectory_name_); trajectory_output_port_ = this->DeclareAbstractOutputPort(trajectory_name_, traj_inst, &LcmTrajectoryReceiver::OutputTrajectory) .get_index(); lcm_traj_ = LcmTrajectory(dairlib::FindResourceOrThrow(nominal_stand_path_)); - } void LcmTrajectoryReceiver::OutputTrajectory( const drake::systems::Context& context, - PiecewisePolynomial* output_trajectory) const { + Trajectory* traj) const { if (this->EvalInputValue( - context, trajectory_input_port_)->utime > 1e-3) { + context, trajectory_input_port_) + ->utime > 1e-3) { const auto& lcm_traj = this->EvalInputValue( context, trajectory_input_port_); lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); } const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); - - *output_trajectory = PiecewisePolynomial::FirstOrderHold( + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + *casted_traj = PiecewisePolynomial::FirstOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); } diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 00e0a7c15f..46dd88cb47 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -28,13 +28,13 @@ class LcmTrajectoryReceiver : public drake::systems::LeafSystem { private: void OutputTrajectory(const drake::systems::Context& context, - drake::trajectories::PiecewisePolynomial* output_trajectory) const; + drake::trajectories::Trajectory* traj) const; drake::systems::InputPortIndex trajectory_input_port_; drake::systems::OutputPortIndex trajectory_output_port_; const std::string trajectory_name_; mutable LcmTrajectory lcm_traj_; - std::string nominal_stand_path_ = ""; + std::string nominal_stand_path_ = "examples/franka/saved_trajectories/default_end_effector_pose"; }; } // namespace systems From 6836e404b8c622743a972a363e0ca1d903415014 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 11:49:58 -0400 Subject: [PATCH 425/758] testing different outputs for c3 --- solvers/c3.cc | 3 ++- systems/controllers/c3_controller.cc | 5 ++++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index 514e1a2f32..7a2fae5997 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -141,7 +141,8 @@ VectorXd C3::Solve(const VectorXd& x0, vector& delta, z = zfin[0]; - return z.segment(n_ + m_, k_); +// return z.segment(n_ + m_, k_); + return z; } VectorXd C3::ADMMStep(const VectorXd& x0, vector* delta, diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 8e8c1f5a0c..44d555b741 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -107,7 +107,10 @@ void C3Controller::OutputTrajectory( int k = ((lcs.B_)[0].cols()); std::vector delta(N_, VectorXd::Zero(n + m + k)); std::vector w(N_, VectorXd::Zero(n + m + k)); - c3_->Solve(x.get_data(), delta, w); + auto z_sol = c3_->Solve(x.get_data(), delta, w); + auto x_sol = z_sol.head(lcs.n_); + auto lambda_sol = z_sol.segment(lcs.n_, lcs.m_); + auto u_sol = z_sol.tail(lcs.k_); *output_traj = dairlib::lcmt_timestamped_saved_traj(); } From 1963fe5e50a80e891862870bfd09695bd31b4a7f Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 12:41:14 -0400 Subject: [PATCH 426/758] constructing lcm traj --- solvers/c3.cc | 5 +++-- solvers/lcs.cc | 9 +++++---- solvers/lcs.h | 7 +++++-- solvers/lcs_factory.cc | 2 +- systems/controllers/c3_controller.cc | 18 +++++++++++++++++- 5 files changed, 31 insertions(+), 10 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index 7a2fae5997..5402b65c9a 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -139,10 +139,11 @@ VectorXd C3::Solve(const VectorXd& x0, vector& delta, vector zfin = SolveQP(x0, Gv, WD); - z = zfin[0]; + auto z0 = zfin[0]; // return z.segment(n_ + m_, k_); - return z; + return z0; +// return zfin; } VectorXd C3::ADMMStep(const VectorXd& x0, vector* delta, diff --git a/solvers/lcs.cc b/solvers/lcs.cc index f1f7873336..9c1e63feef 100644 --- a/solvers/lcs.cc +++ b/solvers/lcs.cc @@ -15,16 +15,17 @@ namespace solvers { LCS::LCS(const vector& A, const vector& B, const vector& D, const vector& d, const vector& E, const vector& F, - const vector& H, const vector& c) - : A_(A), B_(B), D_(D), d_(d), E_(E), F_(F), H_(H), c_(c), N_(A.size()), n_(A_[0].rows()), m_(D_[0].cols()), k_(H_[0].cols()) {} + const vector& H, const vector& c, + double dt) + : A_(A), B_(B), D_(D), d_(d), E_(E), F_(F), H_(H), c_(c), N_(A.size()), n_(A_[0].rows()), m_(D_[0].cols()), k_(H_[0].cols()), dt_(dt) {} LCS::LCS(const MatrixXd& A, const MatrixXd& B, const MatrixXd& D, const VectorXd& d, const MatrixXd& E, const MatrixXd& F, - const MatrixXd& H, const VectorXd& c, const int& N) + const MatrixXd& H, const VectorXd& c, const int& N, double dt) : LCS(vector(N, A), vector(N, B), vector(N, D), vector(N, d), vector(N, E), vector(N, F), - vector(N, H), vector(N, c)) {} + vector(N, H), vector(N, c), dt) {} const VectorXd LCS::Simulate(VectorXd& x_init, VectorXd& input) { VectorXd x_final; diff --git a/solvers/lcs.h b/solvers/lcs.h index 3b549b88c7..713c38a64c 100644 --- a/solvers/lcs.h +++ b/solvers/lcs.h @@ -23,13 +23,15 @@ class LCS { const std::vector& E, const std::vector& F, const std::vector& H, - const std::vector& c); + const std::vector& c, + double dt); /// Constructor for time-invariant LCS LCS(const Eigen::MatrixXd& A, const Eigen::MatrixXd& B, const Eigen::MatrixXd& D, const Eigen::VectorXd& d, const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, - const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int& N); + const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int& N, + double dt); /// Simulate the system for one-step /// @param x_init Initial x value @@ -46,6 +48,7 @@ class LCS { const std::vector H_; const std::vector c_; const int N_; + const double dt_; const int n_; const int m_; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 901cdc439a..5e7350ca1b 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -203,7 +203,7 @@ std::pair LCSFactory::LinearizePlantToLCS( c /= AnDn; H /= AnDn; - LCS system(A, B, D, d, E, F, H, c, N); + LCS system(A, B, D, d, E, F, H, c, N, dt); std::pair ret(system, AnDn); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 44d555b741..2495eff107 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -68,7 +68,7 @@ void C3Controller::OutputTrajectory( const TimestampedVector& x = *this->template EvalVectorInput(context, lcs_state_input_port_); - + double t = x.get_timestamp(); VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); @@ -111,7 +111,23 @@ void C3Controller::OutputTrajectory( auto x_sol = z_sol.head(lcs.n_); auto lambda_sol = z_sol.segment(lcs.n_, lcs.m_); auto u_sol = z_sol.tail(lcs.k_); + + MatrixXd knots = x_sol; + VectorXd breaks = VectorXd::Zero(1); +// double T = trajopt_.GetTimingSolution()(0); + for (int n = 0; n < N_; n++) { + breaks(n) = t + lcs.dt_; + } + LcmTrajectory::Trajectory input_traj; + input_traj.traj_name = "input_traj"; + input_traj.datatypes = std::vector(1, "double"); + input_traj.datapoints = knots; + input_traj.time_vector = breaks; + LcmTrajectory lcm_traj( + {input_traj}, {"input_traj"}, "input_traj", "input_traj", false); *output_traj = dairlib::lcmt_timestamped_saved_traj(); + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_traj->utime = ; } } // namespace systems From b8622d7cfe3987907389994497195e5d35307eee Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 12:48:36 -0400 Subject: [PATCH 427/758] testing traj --- solvers/lcs_factory.cc | 2 +- systems/controllers/c3_controller.cc | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 5e7350ca1b..8250fa294f 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -318,7 +318,7 @@ LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, D.push_back(D_k); d.push_back(d_k); } - return LCS(A, B, D, d, E, F, H, c); + return LCS(A, B, D, d, E, F, H, c, other.dt_); } } // namespace solvers diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 2495eff107..cb1ca9ff77 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -127,7 +127,7 @@ void C3Controller::OutputTrajectory( {input_traj}, {"input_traj"}, "input_traj", "input_traj", false); *output_traj = dairlib::lcmt_timestamped_saved_traj(); output_traj->saved_traj = lcm_traj.GenerateLcmObject(); - output_traj->utime = ; + output_traj->utime = t * 1e6; } } // namespace systems From 4afa09fdf7d9535458c5e7626b01be24253eb640 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 13:33:05 -0400 Subject: [PATCH 428/758] tracking is running but not working --- examples/franka/franka_c3_controller.cc | 10 +++++-- examples/franka/franka_osc_controller.cc | 6 ++-- solvers/c3.cc | 26 +++++++++------- solvers/c3.h | 8 +++-- systems/controllers/BUILD.bazel | 2 ++ systems/controllers/c3_controller.cc | 38 +++++++++++++++--------- systems/controllers/c3_controller.h | 11 +++++++ 7 files changed, 69 insertions(+), 32 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index fa327b92a2..6faf2c4093 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -47,6 +47,9 @@ using multibody::MakeNameToVelocitiesMap; DEFINE_string(controller_settings, "", "Controller settings such as channels. Attempting to minimize " "number of gflags"); +DEFINE_string(osqp_settings, + "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "Filepath containing qp settings"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -60,7 +63,10 @@ int DoMain(int argc, char* argv[]) { "examples/franka/franka_c3_controller_params.yaml"); C3Options c3_options = drake::yaml::LoadYamlFile(controller_params.c3_options_file); - + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(FLAGS_osqp_settings)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); DiagramBuilder plant_builder; @@ -144,7 +150,7 @@ int DoMain(int argc, char* argv[]) { auto controller = builder.AddSystem( plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); - + controller->SetOsqpSolverOptions(solver_options); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); builder.Connect(tray_state_sub->get_output_port(), diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 9439d5dca0..fdf1025d65 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -67,9 +67,9 @@ int DoMain(int argc, char* argv[]) { FindResourceOrThrow("examples/franka/franka_controller_params.yaml"), {}, {}, yaml_options); drake::solvers::SolverOptions solver_options = - drake::yaml::LoadYamlFile( + drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_osqp_settings)) - .osqp_options; + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); DiagramBuilder builder; drake::multibody::MultibodyPlant plant(0.0); @@ -114,7 +114,7 @@ int DoMain(int argc, char* argv[]) { controller_params.c3_channel, &lcm)); auto trajectory_receiver = builder.AddSystem( - "end_effector_trajectory"); + "end_effector_traj"); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( controller_params.controller_channel, &lcm, diff --git a/solvers/c3.cc b/solvers/c3.cc index 5402b65c9a..ca96b5a18b 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -56,7 +56,7 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, k_((LCS.B_)[0].cols()), hflag_(H_[0].isZero(0)), prog_(MathematicalProgram()), - OSQPoptions_(SolverOptions()), + solver_options_(SolverOptions()), osqp_(OsqpSolver()) { // Deep copy warm start warm_start_ = warm_start; @@ -114,17 +114,17 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, } } - OSQPoptions_.SetOption(OsqpSolver::id(), "verbose", 1); + // OSQPoptions_.SetOption(OsqpSolver::id(), "verbose", 1); // OSQPoptions_.SetOption(OsqpSolver::id(), "ebs_abs", 1e-7); // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-6); - OSQPoptions_.SetOption(OsqpSolver::id(), "max_iter", 30); // 30 - prog_.SetSolverOptions(OSQPoptions_); + // OSQPoptions_.SetOption(OsqpSolver::id(), "max_iter", 30); // 30 + // prog_.SetSolverOptions(solver_options_); } -VectorXd C3::Solve(const VectorXd& x0, vector& delta, - vector& w) { +vector C3::Solve(const VectorXd& x0, vector& delta, + vector& w) { vector Gv = G_; VectorXd z; @@ -141,9 +141,9 @@ VectorXd C3::Solve(const VectorXd& x0, vector& delta, auto z0 = zfin[0]; -// return z.segment(n_ + m_, k_); - return z0; -// return zfin; + // return z.segment(n_ + m_, k_); + // return z0; + return zfin; } VectorXd C3::ADMMStep(const VectorXd& x0, vector* delta, @@ -203,7 +203,8 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, if (i < N_) { costs_.push_back(prog_.AddQuadraticCost( G.at(i).block(0, 0, n_, n_) * 2, - -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), x_.at(i))); + -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), + x_.at(i))); costs_.push_back(prog_.AddQuadraticCost( G.at(i).block(n_, n_, m_, m_) * 2, -2 * G.at(i).block(n_, n_, m_, m_) * WD.at(i).segment(n_, m_), @@ -226,6 +227,7 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, // prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); // } + prog_.SetSolverOptions(solver_options_); MathematicalProgramResult result = osqp_.Solve(prog_); VectorXd xSol = result.GetSolution(x_[0]); vector zz(N_, VectorXd::Zero(n_ + m_ + k_)); @@ -242,7 +244,9 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, warm_start_u_[i] = result.GetSolution(u_[i]); } } - if (warm_start_) warm_start_x_[N_] = result.GetSolution(x_[N_]); + if (warm_start_) { + warm_start_x_[N_] = result.GetSolution(x_[N_]); + } return zz; } diff --git a/solvers/c3.h b/solvers/c3.h index 5ef48f7950..fceca7ba3a 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -36,7 +36,7 @@ class C3 { /// @param delta A pointer to the copy variable solution /// @param w A pointer to the scaled dual variable solution /// @return The first control action to take, u[0] - Eigen::VectorXd Solve(const Eigen::VectorXd& x0, + std::vector Solve(const Eigen::VectorXd& x0, std::vector& delta, std::vector& w); @@ -90,6 +90,10 @@ class C3 { const Eigen::VectorXd& c, const int& warm_start_index) = 0; + void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { + solver_options_ = options; + } + public: const std::vector A_; const std::vector B_; @@ -121,7 +125,7 @@ class C3 { private: drake::solvers::MathematicalProgram prog_; - drake::solvers::SolverOptions OSQPoptions_; + drake::solvers::SolverOptions solver_options_; drake::solvers::OsqpSolver osqp_; std::vector x_; std::vector u_; diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index a75e8fc081..8a4882774f 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -63,6 +63,8 @@ cc_library( "//systems/framework:vector", "//lcmtypes:lcmt_robot", "//solvers:c3", + "//common:find_resource", + "//solvers:solver_options_io", "//lcm:lcm_trajectory_saver", "@drake//:drake_shared_library", ], diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index cb1ca9ff77..5851d696c0 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -100,6 +100,7 @@ void C3Controller::OutputTrajectory( DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); + c3_->SetOsqpSolverOptions(solver_options_); // int N = (system_.A_).size(); int n = ((lcs.A_)[0].cols()); @@ -108,24 +109,33 @@ void C3Controller::OutputTrajectory( std::vector delta(N_, VectorXd::Zero(n + m + k)); std::vector w(N_, VectorXd::Zero(n + m + k)); auto z_sol = c3_->Solve(x.get_data(), delta, w); - auto x_sol = z_sol.head(lcs.n_); - auto lambda_sol = z_sol.segment(lcs.n_, lcs.m_); - auto u_sol = z_sol.tail(lcs.k_); - MatrixXd knots = x_sol; - VectorXd breaks = VectorXd::Zero(1); -// double T = trajopt_.GetTimingSolution()(0); + MatrixXd x_sol = MatrixXd::Zero(lcs.n_, N_); + MatrixXd lambda_sol = MatrixXd::Zero(lcs.m_, N_); + MatrixXd u_sol = MatrixXd::Zero(lcs.k_, N_); + VectorXd breaks = VectorXd::Zero(N_); + for (int n = 0; n < N_; n++) { - breaks(n) = t + lcs.dt_; + breaks(n) = t + n * lcs.dt_; + x_sol.col(n) = z_sol[n]; + lambda_sol.col(n) = z_sol[n]; + u_sol.col(n) = z_sol[n]; } - LcmTrajectory::Trajectory input_traj; - input_traj.traj_name = "input_traj"; - input_traj.datatypes = std::vector(1, "double"); - input_traj.datapoints = knots; - input_traj.time_vector = breaks; +// auto x_sol = z_sol.head(lcs.n_); +// auto lambda_sol = z_sol.segment(lcs.n_, lcs.m_); +// auto u_sol = z_sol.tail(lcs.k_); +// int dim = 3; +// int dim = 3; + MatrixXd knots = x_sol.topRows(3); +// double T = trajopt_.GetTimingSolution()(0); + LcmTrajectory::Trajectory end_effector_traj; + end_effector_traj.traj_name = "end_effector_traj"; + end_effector_traj.datatypes = std::vector(knots.rows(), "double"); + end_effector_traj.datapoints = knots; + end_effector_traj.time_vector = breaks; LcmTrajectory lcm_traj( - {input_traj}, {"input_traj"}, "input_traj", "input_traj", false); - *output_traj = dairlib::lcmt_timestamped_saved_traj(); + {end_effector_traj}, {"end_effector_traj"}, "end_effector_traj", "end_effector_traj", false); +// *output_traj = dairlib::lcmt_timestamped_saved_traj(); output_traj->saved_traj = lcm_traj.GenerateLcmObject(); output_traj->utime = t * 1e6; } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index caca449b7c..b699cc786f 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -2,6 +2,7 @@ #include #include +#include #include "dairlib/lcmt_saved_traj.hpp" #include "dairlib/lcmt_timestamped_saved_traj.hpp" @@ -13,6 +14,8 @@ #include "systems/framework/timestamped_vector.h" #include "drake/systems/framework/leaf_system.h" +#include "solvers/solver_options_io.h" +#include "common/find_resource.h" namespace dairlib { namespace systems { @@ -41,6 +44,10 @@ class C3Controller : public drake::systems::LeafSystem { return this->get_output_port(trajectory_output_port_); } + void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { + solver_options_ = options; + } + private: void OutputTrajectory( const drake::systems::Context& context, @@ -57,6 +64,10 @@ class C3Controller : public drake::systems::LeafSystem { const std::vector>& contact_pairs_; C3Options c3_options_; + drake::solvers::SolverOptions solver_options_ = + drake::yaml::LoadYamlFile( + FindResourceOrThrow("solvers/osqp_options_default.yaml")) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); int n_q_; int n_v_; From d95739c0d6953b7bf9a8cb7731d5df1b01f215be Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 17:40:33 -0400 Subject: [PATCH 429/758] debugging solution of c3 --- examples/franka/franka_c3_options.yaml | 22 +++--- examples/franka/franka_osc_controller.cc | 27 +++----- examples/franka/franka_sim.cc | 2 +- solvers/c3.cc | 63 +++++++++-------- solvers/c3.h | 9 ++- solvers/c3_options.h | 6 +- solvers/lcs_factory.cc | 33 +++++++-- systems/controllers/c3_controller.cc | 87 +++++++++++++++++------- 8 files changed, 160 insertions(+), 89 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index d99476c0f9..382fc8bd35 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -6,21 +6,23 @@ delta_option: 1 mu: 1 mu_plate: 1 -dt: 0.015 -num_friction_directions: 4 +dt: 0.1 +num_friction_directions: 2 num_contacts: 3 N: 5 -w_Q: 0.01 -w_R: 0.01 +w_Q: 0.00001 +w_R: 0.0 # Penalty on all decision variables, assuming scalar -w_G: 0.001 +w_G: 0.01 # Penalty on all decision variables, assuming scalar -w_U: 0.001 +w_U: 1 -g_size: 52 -u_size: 52 +g_size: 40 +u_size: 40 # State Tracking Error, assuming diagonal -q_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1] +#q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1] +q_vector: [1, 1, 10000000, 0, 0, 0, 0, 0, 0, 0, + 10000000, 10000000, 10000000, 0, 0, 0, 0, 0, 0] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index fdf1025d65..643cf3063d 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -1,7 +1,7 @@ #include -#include #include +#include #include "examples/franka/franka_controller_params.h" #include "examples/franka/systems/end_effector_trajectory.h" @@ -15,6 +15,7 @@ #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" #include "drake/common/find_resource.h" #include "drake/common/yaml/yaml_io.h" @@ -24,8 +25,6 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_publisher_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" -#include "systems/trajectory_optimization/lcm_trajectory_systems.h" -#include "lcm/lcm_trajectory.h" namespace dairlib { @@ -98,23 +97,14 @@ int DoMain(int argc, char* argv[]) { plant.Finalize(); auto plant_context = plant.CreateDefaultContext(); - -// lcmt_trajectory_block traj_block; -// traj_block.datapoints.push_back({0.65, 0.0, 0.3}); -// traj_block.time_vec.push_back({0.0}); -// auto default_traj = LcmTrajectory::Trajectory("end_effector_traj", traj_block); -// auto default_lcm_traj = LcmTrajectory({default_traj}, {"end_effector_traj"}, "default_franka_trajectory", ""); -// default_lcm_traj.WriteToFile("default_end_effector_pose"); - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); auto state_receiver = builder.AddSystem(plant); - auto trajectory_sub = - builder.AddSystem(LcmSubscriberSystem::Make( + auto trajectory_sub = builder.AddSystem( + LcmSubscriberSystem::Make( controller_params.c3_channel, &lcm)); auto trajectory_receiver = - builder.AddSystem( - "end_effector_traj"); + builder.AddSystem("end_effector_traj"); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( controller_params.controller_channel, &lcm, @@ -204,9 +194,10 @@ int DoMain(int argc, char* argv[]) { osc_debug_pub->get_input_port()); builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); - builder.Connect(trajectory_sub->get_output_port(), trajectory_receiver->get_input_port_trajectory()); -// builder.Connect(end_effector_trajectory->get_output_port(0), -// osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect(trajectory_sub->get_output_port(), + trajectory_receiver->get_input_port_trajectory()); + // builder.Connect(end_effector_trajectory->get_output_port(0), + // osc->get_input_port_tracking_data("end_effector_target")); builder.Connect(trajectory_receiver->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); auto owned_diagram = builder.Build(); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index f04ab57525..e14f994dc9 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -160,7 +160,7 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; q[plant.num_positions() - 7] = 1; - q[plant.num_positions() - 1] = 1.2; + q[plant.num_positions() - 1] = 0.8; q[plant.num_positions() - 3] = 0.68; plant.SetPositions(&plant_context, q); diff --git a/solvers/c3.cc b/solvers/c3.cc index ca96b5a18b..c006e88ece 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -87,6 +87,17 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, u_ = vector(); lambda_ = vector(); + z_sol_ = std::make_unique>(); + x_sol_ = std::make_unique>(); + lambda_sol_ = std::make_unique>(); + u_sol_ = std::make_unique>(); + for (int i = 0; i < N_; ++i) { + z_sol_->push_back(Eigen::VectorXd::Zero(n_ + m_ + k_)); + x_sol_->push_back(Eigen::VectorXd::Zero(n_)); + lambda_sol_->push_back(Eigen::VectorXd::Zero(m_)); + u_sol_->push_back(Eigen::VectorXd::Zero(k_)); + } + for (int i = 0; i < N_ + 1; i++) { x_.push_back(prog_.NewContinuousVariables(n_, "x" + std::to_string(i))); if (i < N_) { @@ -113,14 +124,6 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, prog_.AddQuadraticCost(R_.at(i) * 2, VectorXd::Zero(k_), u_.at(i), 1); } } - - // OSQPoptions_.SetOption(OsqpSolver::id(), "verbose", 1); - // OSQPoptions_.SetOption(OsqpSolver::id(), "ebs_abs", 1e-7); - // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_rel", 1e-7); - // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_prim_inf", 1e-6); - // OSQPoptions_.SetOption(OsqpSolver::id(), "eps_dual_inf", 1e-6); - // OSQPoptions_.SetOption(OsqpSolver::id(), "max_iter", 30); // 30 - // prog_.SetSolverOptions(solver_options_); } vector C3::Solve(const VectorXd& x0, vector& delta, @@ -139,7 +142,7 @@ vector C3::Solve(const VectorXd& x0, vector& delta, vector zfin = SolveQP(x0, Gv, WD); - auto z0 = zfin[0]; +// auto z0 = zfin[0]; // return z.segment(n_ + m_, k_); // return z0; @@ -229,57 +232,61 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, prog_.SetSolverOptions(solver_options_); MathematicalProgramResult result = osqp_.Solve(prog_); - VectorXd xSol = result.GetSolution(x_[0]); - vector zz(N_, VectorXd::Zero(n_ + m_ + k_)); - for (int i = 0; i < N_; i++) { - zz.at(i).segment(0, n_) = result.GetSolution(x_[i]); - zz.at(i).segment(n_, m_) = result.GetSolution(lambda_[i]); - zz.at(i).segment(n_ + m_, k_) = result.GetSolution(u_[i]); + if (result.is_success()) { + for (int i = 0; i < N_; i++) { + x_sol_->at(i) = result.GetSolution(x_[i]); + lambda_sol_->at(i) = result.GetSolution(lambda_[i]); + u_sol_->at(i) = result.GetSolution(u_[i]); + z_sol_->at(i).segment(0, n_) = x_sol_->at(i); + z_sol_->at(i).segment(n_, m_) = lambda_sol_->at(i); + z_sol_->at(i).segment(n_ + m_, k_) = u_sol_->at(i); + + if (warm_start_) { + // update warm start parameters + warm_start_x_[i] = result.GetSolution(x_[i]); + warm_start_lambda_[i] = result.GetSolution(lambda_[i]); + warm_start_u_[i] = result.GetSolution(u_[i]); + } + } if (warm_start_) { - // update warm start parameters - warm_start_x_[i] = result.GetSolution(x_[i]); - warm_start_lambda_[i] = result.GetSolution(lambda_[i]); - warm_start_u_[i] = result.GetSolution(u_[i]); + warm_start_x_[N_] = result.GetSolution(x_[N_]); } } - if (warm_start_) { - warm_start_x_[N_] = result.GetSolution(x_[N_]); - } - return zz; + return *z_sol_; } void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double& Lowerbound, double& Upperbound, int& constraint) { if (constraint == 1) { for (int i = 1; i < N_; i++) { - userconstraints_.push_back( + user_constraints_.push_back( prog_.AddLinearConstraint(A, Lowerbound, Upperbound, x_.at(i))); } } if (constraint == 2) { for (int i = 0; i < N_; i++) { - userconstraints_.push_back( + user_constraints_.push_back( prog_.AddLinearConstraint(A, Lowerbound, Upperbound, u_.at(i))); } } if (constraint == 3) { for (int i = 0; i < N_; i++) { - userconstraints_.push_back( + user_constraints_.push_back( prog_.AddLinearConstraint(A, Lowerbound, Upperbound, lambda_.at(i))); } } } void C3::RemoveConstraints() { - for (auto& userconstraint : userconstraints_) { + for (auto& userconstraint : user_constraints_) { prog_.RemoveConstraint(userconstraint); } - userconstraints_.clear(); + user_constraints_.clear(); } vector C3::SolveProjection(vector& G, diff --git a/solvers/c3.h b/solvers/c3.h index fceca7ba3a..119ba189aa 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -134,7 +134,14 @@ class C3 { std::vector> constraints_; std::vector> - userconstraints_; + user_constraints_; + + // Solutions + + std::unique_ptr> z_sol_; + std::unique_ptr> x_sol_; + std::unique_ptr> lambda_sol_; + std::unique_ptr> u_sol_; }; } // namespace solvers diff --git a/solvers/c3_options.h b/solvers/c3_options.h index f89921c4d5..5032103ab6 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -65,9 +65,11 @@ struct C3Options { Eigen::VectorXd r = Eigen::Map( this->r_vector.data(), this->r_vector.size()); - Q = q.asDiagonal(); - R = r.asDiagonal(); + Q = w_Q * q.asDiagonal(); + R = w_R * r.asDiagonal(); G = w_G * MatrixXd::Identity(g_size, g_size); U = w_U * MatrixXd::Identity(u_size, u_size); + + U.block(0, 0, 19, 19) = 100 * MatrixXd::Identity(19, 19); } }; \ No newline at end of file diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 8250fa294f..20b0edcacd 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -45,7 +45,8 @@ std::pair LCSFactory::LinearizePlantToLCS( plant_ad.CalcBiasTerm(context_ad, &C); auto B_dyn_ad = plant_ad.MakeActuationMatrix(); VectorXd u_dyn = VectorXd::Zero(n_u); - AutoDiffVecXd u_dyn_ad = drake::math::InitializeAutoDiff(u_dyn, n_q + n_v + n_u); + AutoDiffVecXd u_dyn_ad = + drake::math::InitializeAutoDiff(u_dyn, n_q + n_v + n_u); AutoDiffVecXd Bu = B_dyn_ad * u_dyn_ad; AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); @@ -121,9 +122,19 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd H(n_contact_vars, n_u); VectorXd c(n_contact_vars); + MatrixXd AB_v_q = AB_v.block(0, 0, n_v, n_q); MatrixXd AB_v_v = AB_v.block(0, n_q, n_v, n_v); - MatrixXd AB_v_u = AB_v.block(0, n_x, n_v, n_u); +// MatrixXd AB_v_u = AB_v.block(0, n_x, n_v, n_u); + MatrixXd M_double = MatrixXd::Zero(n_v, n_v); + plant.CalcMassMatrix(context, &M_double); + // TODO(yangwill): Check why gradient wrt u is not working correctly + MatrixXd AB_v_u = M_double.inverse() * MatrixXd::Identity(n_v, n_u); +// AB_v_u = M.ldlt().solve(); +// std::cout << "AB_v: " << AB_v << std::endl; +// std::cout << "AB_v rows: " << AB_v.rows() << std::endl; +// std::cout << "AB_v cols: " << AB_v.cols() << std::endl; +// std::cout << "AB_v_u: " << AB_v_u << std::endl; A.block(0, 0, n_q, n_q) = MatrixXd::Identity(n_q, n_q) + dt * dt * Nq * AB_v_q; @@ -185,8 +196,8 @@ std::pair LCSFactory::LinearizePlantToLCS( H = MatrixXd::Zero(n_contact_vars, n_u); H.block(n_contacts, 0, n_contacts, n_u) = dt * dt * J_n * AB_v_u; - H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, - n_u) = dt * J_t * AB_v_u; + H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = + dt * J_t * AB_v_u; c = VectorXd::Zero(n_contact_vars); c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; @@ -203,7 +214,19 @@ std::pair LCSFactory::LinearizePlantToLCS( c /= AnDn; H /= AnDn; - LCS system(A, B, D, d, E, F, H, c, N, dt); +// std::cout << B << std::endl; + std::vector A_lcs(N, A); + std::vector B_lcs(N, B); + std::vector D_lcs(N, D); + std::vector d_lcs(N, d); + std::vector E_lcs(N, E); + std::vector F_lcs(N, F); + std::vector c_lcs(N, c); + std::vector H_lcs(N, H); + + LCS system(A_lcs, B_lcs, D_lcs, d_lcs, E_lcs, F_lcs, H_lcs, c_lcs, dt); + + // LCS system(A, B, D, d, E, F, H, c, N, dt); std::pair ret(system, AnDn); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 5851d696c0..664367358d 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -7,6 +7,8 @@ #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "solvers/lcs_factory.h" +#include "drake/solvers/moby_lcp_solver.h" + namespace dairlib { using drake::systems::BasicVector; @@ -36,7 +38,7 @@ C3Controller::C3Controller( R_(std::vector(c3_options_.N, c3_options_.R)), G_(std::vector(c3_options_.N, c3_options_.G)), U_(std::vector(c3_options_.N, c3_options_.U)), - N_(c3_options_.N){ + N_(c3_options_.N) { // DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); @@ -50,7 +52,6 @@ C3Controller::C3Controller( TimestampedVector(n_q_ + n_v_)) .get_index(); - this->set_name("c3_controller"); trajectory_output_port_ = this->DeclareAbstractOutputPort("c3_output", @@ -75,18 +76,25 @@ void C3Controller::OutputTrajectory( q_v_u << x.get_data(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); - std::vector x_desired = - std::vector(Q_.size() + 1, VectorXd::Zero(n_q_ + n_v_)); - // q_v_u[0] = 1; - // q_v_u[4] = 1; - // q_v_u_ad[0] = 1; - // q_v_u_ad[4] = 1; + VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); + x_des[0] = 0.7; + x_des[1] = 0.02; + x_des[2] = 0.4; + x_des[3] = 1; + x_des[4] = 0; + x_des[5] = 0; + x_des[6] = 0; + x_des[7] = 0.7; + x_des[8] = 0.02; + x_des[9] = 0.3; + std::vector x_desired = std::vector(N_ + 1, x_des); int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x)); plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); + // TODO(yangwill): Check why gradient wrt u is not working correctly auto lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, @@ -98,11 +106,10 @@ void C3Controller::OutputTrajectory( DRAKE_DEMAND(R_.front().cols() == lcs.k_); DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); - c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, - c3_options_); + c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); c3_->SetOsqpSolverOptions(solver_options_); -// int N = (system_.A_).size(); + // int N = (system_.A_).size(); int n = ((lcs.A_)[0].cols()); int m = ((lcs.D_)[0].cols()); int k = ((lcs.B_)[0].cols()); @@ -117,25 +124,57 @@ void C3Controller::OutputTrajectory( for (int n = 0; n < N_; n++) { breaks(n) = t + n * lcs.dt_; - x_sol.col(n) = z_sol[n]; - lambda_sol.col(n) = z_sol[n]; - u_sol.col(n) = z_sol[n]; +// x_sol.col(n) = state_next; + x_sol.col(n) = z_sol[n].segment(0, lcs.n_); + lambda_sol.col(n) = z_sol[n].segment(lcs.n_, lcs.m_); + u_sol.col(n) = z_sol[n].segment(lcs.n_ + lcs.m_, lcs.k_); } -// auto x_sol = z_sol.head(lcs.n_); -// auto lambda_sol = z_sol.segment(lcs.n_, lcs.m_); -// auto u_sol = z_sol.tail(lcs.k_); -// int dim = 3; -// int dim = 3; + + double solve_dt = 0.1; + auto second_lcs_pair = LCSFactory::LinearizePlantToLCS( + plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + c3_options_.num_friction_directions, c3_options_.mu, solve_dt, + c3_options_.N); + auto second_lcs = second_lcs_pair.first; + auto second_scale = second_lcs_pair.second; + drake::solvers::MobyLCPSolver LCPSolver; + VectorXd force; +// auto flag = LCPSolver.SolveLcpLemkeRegularized( + auto flag = LCPSolver.SolveLcpLemke( + second_lcs.F_[0], + second_lcs.E_[0] * second_scale * x.get_data() + + second_lcs.c_[0] * second_scale + + second_lcs.H_[0] * second_scale * u_sol.col(0), + &force); + + (void)flag; // suppress compiler unused variable warning + VectorXd state_next = second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + + second_lcs.D_[0] * force / second_scale + + second_lcs.d_[0]; + + +// x_sol.col(0) = state_next; +// x_sol.col(1) = state_next; +// std::cout << "height diff: " << state_next[2] - x.get_data()[2] << std::endl; +// std::cout << "state next: " << state_next.transpose() << std::endl; +// std::cout << "current state: " << x.get_value().transpose() << std::endl; +// std::cout << "force: " << force << std::endl; +// std::cout << "u_sol: " << u_sol.col(0) << std::endl; +// std::cout << "u: " << u_sol.col(0) << std::endl; +// std::cout << "Bu + d: " << second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + second_lcs.d_[0] << std::endl; +// std::cout << "d: " << second_lcs.d_[0] << std::endl; +// x_sol.col(N_ - 1) = z_sol[0].segment(0, lcs.n_); + + MatrixXd knots = x_sol.topRows(3); -// double T = trajopt_.GetTimingSolution()(0); LcmTrajectory::Trajectory end_effector_traj; end_effector_traj.traj_name = "end_effector_traj"; - end_effector_traj.datatypes = std::vector(knots.rows(), "double"); + end_effector_traj.datatypes = + std::vector(knots.rows(), "double"); end_effector_traj.datapoints = knots; end_effector_traj.time_vector = breaks; - LcmTrajectory lcm_traj( - {end_effector_traj}, {"end_effector_traj"}, "end_effector_traj", "end_effector_traj", false); -// *output_traj = dairlib::lcmt_timestamped_saved_traj(); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_traj"}, + "end_effector_traj", "end_effector_traj", false); output_traj->saved_traj = lcm_traj.GenerateLcmObject(); output_traj->utime = t * 1e6; } From 668ce274c4bc5bd5ed682fdac16cc23bd8e69ea9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 17:59:20 -0400 Subject: [PATCH 430/758] need to debug second lcs dynamics --- solvers/lcs_factory.cc | 24 ++++++++++++------------ systems/controllers/c3_controller.cc | 7 ++++--- 2 files changed, 16 insertions(+), 15 deletions(-) diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 20b0edcacd..a842e37e6e 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -215,18 +215,18 @@ std::pair LCSFactory::LinearizePlantToLCS( H /= AnDn; // std::cout << B << std::endl; - std::vector A_lcs(N, A); - std::vector B_lcs(N, B); - std::vector D_lcs(N, D); - std::vector d_lcs(N, d); - std::vector E_lcs(N, E); - std::vector F_lcs(N, F); - std::vector c_lcs(N, c); - std::vector H_lcs(N, H); - - LCS system(A_lcs, B_lcs, D_lcs, d_lcs, E_lcs, F_lcs, H_lcs, c_lcs, dt); - - // LCS system(A, B, D, d, E, F, H, c, N, dt); +// std::vector A_lcs(N, A); +// std::vector B_lcs(N, B); +// std::vector D_lcs(N, D); +// std::vector d_lcs(N, d); +// std::vector E_lcs(N, E); +// std::vector F_lcs(N, F); +// std::vector c_lcs(N, c); +// std::vector H_lcs(N, H); +// +// LCS system(A_lcs, B_lcs, D_lcs, d_lcs, E_lcs, F_lcs, H_lcs, c_lcs, dt); + + LCS system(A, B, D, d, E, F, H, c, N, dt); std::pair ret(system, AnDn); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 664367358d..9ffd7ff862 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -158,9 +158,10 @@ void C3Controller::OutputTrajectory( // std::cout << "height diff: " << state_next[2] - x.get_data()[2] << std::endl; // std::cout << "state next: " << state_next.transpose() << std::endl; // std::cout << "current state: " << x.get_value().transpose() << std::endl; -// std::cout << "force: " << force << std::endl; -// std::cout << "u_sol: " << u_sol.col(0) << std::endl; -// std::cout << "u: " << u_sol.col(0) << std::endl; + std::cout << "second_lcs.A_[0] * x.get_data(): " << second_lcs.A_[0] * x.get_data() << std::endl; + std::cout << "second_lcs.B_[0] * u_sol.col(0): " << second_lcs.B_[0] * u_sol.col(0) << std::endl; + std::cout << "second_lcs.D_[0] * force / second_scale: " << second_lcs.D_[0] * force / second_scale << std::endl; + std::cout << "second_lcs.d_[0]: " << second_lcs.d_[0] << std::endl; // std::cout << "Bu + d: " << second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + second_lcs.d_[0] << std::endl; // std::cout << "d: " << second_lcs.d_[0] << std::endl; // x_sol.col(N_ - 1) = z_sol[0].segment(0, lcs.n_); From b3211d1eaa1b12b72a73031abcd05998ccb75411 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 3 Apr 2023 18:21:28 -0400 Subject: [PATCH 431/758] using right linearization --- examples/franka/franka_c3_options.yaml | 6 +++--- solvers/c3_options.h | 2 +- solvers/lcs_factory.cc | 2 ++ systems/controllers/BUILD.bazel | 1 + systems/controllers/c3_controller.cc | 4 ++++ 5 files changed, 11 insertions(+), 4 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index 382fc8bd35..20c9c6e643 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -13,7 +13,7 @@ N: 5 w_Q: 0.00001 w_R: 0.0 # Penalty on all decision variables, assuming scalar -w_G: 0.01 +w_G: 100 # Penalty on all decision variables, assuming scalar w_U: 1 @@ -22,7 +22,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [1, 1, 10000000, 0, 0, 0, 0, 0, 0, 0, - 10000000, 10000000, 10000000, 0, 0, 0, 0, 0, 0] +q_vector: [1, 1, 1, 0, 0, 0, 0, 0, 0, 0, + 1, 1, 1, 0, 0, 0, 0, 0, 0] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 5032103ab6..062baf26c6 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -70,6 +70,6 @@ struct C3Options { G = w_G * MatrixXd::Identity(g_size, g_size); U = w_U * MatrixXd::Identity(u_size, u_size); - U.block(0, 0, 19, 19) = 100 * MatrixXd::Identity(19, 19); + U.block(0, 0, 19, 19) = 1000 * MatrixXd::Identity(19, 19); } }; \ No newline at end of file diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index a842e37e6e..d4693a7666 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -47,6 +47,8 @@ std::pair LCSFactory::LinearizePlantToLCS( VectorXd u_dyn = VectorXd::Zero(n_u); AutoDiffVecXd u_dyn_ad = drake::math::InitializeAutoDiff(u_dyn, n_q + n_v + n_u); +// AutoDiffVecXd u_dyn_ad = +// plant_ad.; AutoDiffVecXd Bu = B_dyn_ad * u_dyn_ad; AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 8a4882774f..778accfb48 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -64,6 +64,7 @@ cc_library( "//lcmtypes:lcmt_robot", "//solvers:c3", "//common:find_resource", + "//multibody:utils", "//solvers:solver_options_io", "//lcm:lcm_trajectory_saver", "@drake//:drake_shared_library", diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 9ffd7ff862..c4bd5ea0c2 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -4,6 +4,8 @@ #include #include "common/find_resource.h" +#include "multibody/multibody_utils.h" + #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "solvers/lcs_factory.h" @@ -94,6 +96,8 @@ void C3Controller::OutputTrajectory( plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x)); plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); + multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u), context_); + multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u), context_ad_); // TODO(yangwill): Check why gradient wrt u is not working correctly auto lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, From c18e64d412436fa8adf7a9c4e7d5a9dda7fe7532 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 4 Apr 2023 10:10:35 -0400 Subject: [PATCH 432/758] correctly setting number of threads --- examples/franka/franka_c3_options.yaml | 6 +++--- examples/franka/franka_sim.cc | 2 +- solvers/c3.cc | 9 +++++---- systems/controllers/c3_controller.cc | 22 ++++++++++++---------- 4 files changed, 21 insertions(+), 18 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index 20c9c6e643..937b9dbd13 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -1,7 +1,7 @@ admm_iter: 2 rho: 0.1 rho_scale: 3 -num_threads: 0 +num_threads: 4 delta_option: 1 mu: 1 @@ -10,10 +10,10 @@ dt: 0.1 num_friction_directions: 2 num_contacts: 3 N: 5 -w_Q: 0.00001 +w_Q: 10000 w_R: 0.0 # Penalty on all decision variables, assuming scalar -w_G: 100 +w_G: 0.01 # Penalty on all decision variables, assuming scalar w_U: 1 diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index e14f994dc9..f04ab57525 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -160,7 +160,7 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; q[plant.num_positions() - 7] = 1; - q[plant.num_positions() - 1] = 0.8; + q[plant.num_positions() - 1] = 1.2; q[plant.num_positions() - 3] = 0.68; plant.SetPositions(&plant_context, q); diff --git a/solvers/c3.cc b/solvers/c3.cc index c006e88ece..5f9242c65f 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -4,6 +4,7 @@ #include #include +#include #include "solvers/lcs.h" @@ -294,10 +295,10 @@ vector C3::SolveProjection(vector& G, vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); int i; - // if (options_.num_threads > 0) { - // omp_set_dynamic(0); // Explicitly disable dynamic teams - // omp_set_num_threads(options_.num_threads); // Set number of threads - // } + if (options_.num_threads > 0) { + omp_set_dynamic(0); // Explicitly disable dynamic teams + omp_set_num_threads(options_.num_threads); // Set number of threads + } #pragma omp parallel for for (i = 0; i < N_; i++) { diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index c4bd5ea0c2..9f0d024912 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -117,7 +117,9 @@ void C3Controller::OutputTrajectory( int n = ((lcs.A_)[0].cols()); int m = ((lcs.D_)[0].cols()); int k = ((lcs.B_)[0].cols()); - std::vector delta(N_, VectorXd::Zero(n + m + k)); + VectorXd delta_init = VectorXd::Zero(n + m + k); + delta_init.head(n) = x.get_data(); + std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n + m + k)); auto z_sol = c3_->Solve(x.get_data(), delta, w); @@ -157,18 +159,18 @@ void C3Controller::OutputTrajectory( second_lcs.d_[0]; -// x_sol.col(0) = state_next; -// x_sol.col(1) = state_next; // std::cout << "height diff: " << state_next[2] - x.get_data()[2] << std::endl; // std::cout << "state next: " << state_next.transpose() << std::endl; // std::cout << "current state: " << x.get_value().transpose() << std::endl; - std::cout << "second_lcs.A_[0] * x.get_data(): " << second_lcs.A_[0] * x.get_data() << std::endl; - std::cout << "second_lcs.B_[0] * u_sol.col(0): " << second_lcs.B_[0] * u_sol.col(0) << std::endl; - std::cout << "second_lcs.D_[0] * force / second_scale: " << second_lcs.D_[0] * force / second_scale << std::endl; - std::cout << "second_lcs.d_[0]: " << second_lcs.d_[0] << std::endl; -// std::cout << "Bu + d: " << second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + second_lcs.d_[0] << std::endl; -// std::cout << "d: " << second_lcs.d_[0] << std::endl; -// x_sol.col(N_ - 1) = z_sol[0].segment(0, lcs.n_); + +// std::cout << "second_lcs.A_[0] * x.get_data(): " << second_lcs.A_[0] * x.get_data() << std::endl; +// std::cout << "second_lcs.B_[0] * u_sol.col(0): " << second_lcs.B_[0] * u_sol.col(0) << std::endl; +// std::cout << "second_lcs.D_[0] * force / second_scale: " << second_lcs.D_[0] * force / second_scale << std::endl; +// std::cout << "second_lcs.d_[0]: " << second_lcs.d_[0] << std::endl; + +// std::cout << "second_lcs.D_[0] * force / second_scale: " << (second_lcs.D_[0] * force / second_scale).transpose() << std::endl; +// std::cout << "second_lcs.D_[0] * lambda / second_scale: " << (second_lcs.D_[0] * lambda_sol.col(0) / second_scale).transpose() << std::endl; + MatrixXd knots = x_sol.topRows(3); From 8ccc3fca4143e2c5ec3afb7559207b2280d6b63e Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 4 Apr 2023 14:42:13 -0400 Subject: [PATCH 433/758] tuning c3 --- examples/Cassie/cassie_xbox_remote.py | 35 ++------- examples/franka/franka_c3_controller.cc | 2 +- examples/franka/franka_c3_options.yaml | 13 ++-- examples/franka/franka_kinematics.cc | 19 ++++- examples/franka/franka_kinematics.h | 4 +- examples/franka/franka_osc_controller.cc | 4 +- .../franka/systems/end_effector_trajectory.cc | 73 +++++++++---------- .../franka/systems/end_effector_trajectory.h | 6 +- solvers/c3_options.h | 4 +- solvers/lcs_factory.cc | 36 ++------- systems/controllers/c3_controller.cc | 53 ++++++-------- 11 files changed, 105 insertions(+), 144 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 762e4ac97e..e525aeaef0 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -45,15 +45,8 @@ def main(): clock = pygame.time.Clock() textPrint = TextPrint() - # radio spoof variables - radio_channel_6_pos = 0 - radio_channel_6_delta = 0.05 - - radio_channel_4_pos = 0 - radio_channel_4_delta = 0.05 - - radio_channel_5_pos = 0 - radio_channel_5_delta = 0.05 + latching_switch = 0 + # radio_msg.channel[14] = 0 if (pygame.joystick.get_count() != 1): raise RuntimeError("Please connect exactly one controller") @@ -62,11 +55,6 @@ def main(): joystick.init() done = False - max_speed = 1.6 - ramp_up = np.arange(0, max_speed, 0.03) - stay = max_speed * np.ones(125) - ramp_down = np.flip(np.arange(0, max_speed, 0.01)) - speeds = np.hstack((ramp_up, stay, ramp_down)) i = 0 while not done: # DRAWING STEP @@ -81,17 +69,9 @@ def main(): if event.type == pygame.QUIT: # If user clicked close done=True # Flag that we are done so we exit this loop - if event.type == pygame.JOYHATMOTION: - hat_val = joystick.get_hat(0) - radio_channel_6_pos += radio_channel_6_delta * hat_val[1] - # saturate between -1 and 1 - radio_channel_6_pos = min(max(radio_channel_6_pos, -1), 1) if event.type == pygame.JOYBUTTONDOWN: - radio_channel_4_pos += -radio_channel_5_delta * joystick.get_button(2) + radio_channel_5_delta * joystick.get_button(1) - radio_channel_5_pos += -radio_channel_4_delta * joystick.get_button(0) + radio_channel_4_delta * joystick.get_button(3) - # for i in range(joystick.get_numbuttons()): - # print(i) - # print(joystick.get_button(i)) + if event.button == 0: + latching_switch = not latching_switch # Send LCM message @@ -100,10 +80,11 @@ def main(): radio_msg.channel[1] = -joystick.get_axis(0) radio_msg.channel[2] = -joystick.get_axis(4) radio_msg.channel[3] = joystick.get_axis(3) - radio_msg.channel[4] = radio_channel_4_pos - radio_msg.channel[5] = radio_channel_5_pos - radio_msg.channel[6] = radio_channel_6_pos + # radio_msg.channel[4] = radio_channel_4_pos + # radio_msg.channel[5] = radio_channel_5_pos + # radio_msg.channel[6] = radio_channel_6_pos + radio_msg.channel[14] = latching_switch radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 6faf2c4093..7dbfba1dd1 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -142,7 +142,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant_tray); auto reduced_order_model_receiver = builder.AddSystem( - plant_franka, franka_context.get(), plant_tray, tray_context.get(), "paddle"); + plant_franka, franka_context.get(), plant_tray, tray_context.get(), "paddle", "tray"); auto trajectory_sender = builder.AddSystem(LcmPublisherSystem::Make( controller_params.c3_channel, &lcm, diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index 937b9dbd13..ed885c2399 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -1,19 +1,20 @@ -admm_iter: 2 +admm_iter: 3 rho: 0.1 -rho_scale: 3 +rho_scale: 2 num_threads: 4 delta_option: 1 mu: 1 mu_plate: 1 dt: 0.1 +solve_dt: 0.15 num_friction_directions: 2 num_contacts: 3 N: 5 -w_Q: 10000 +w_Q: 1 w_R: 0.0 # Penalty on all decision variables, assuming scalar -w_G: 0.01 +w_G: 0.1 # Penalty on all decision variables, assuming scalar w_U: 1 @@ -22,7 +23,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [1, 1, 1, 0, 0, 0, 0, 0, 0, 0, - 1, 1, 1, 0, 0, 0, 0, 0, 0] +q_vector: [100, 100, 100, 0, 0, 0, 0, 10000, 10000, 10000, + 1, 1, 1, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_kinematics.cc b/examples/franka/franka_kinematics.cc index 7c6b6b1441..4af99c72f4 100644 --- a/examples/franka/franka_kinematics.cc +++ b/examples/franka/franka_kinematics.cc @@ -20,13 +20,15 @@ FrankaKinematics::FrankaKinematics(const MultibodyPlant& franka_plant, Context* franka_context, const MultibodyPlant& object_plant, Context* object_context, - const std::string& end_effector_name) + const std::string& end_effector_name, + const std::string& object_name) : franka_plant_(franka_plant), franka_context_(franka_context), object_plant_(object_plant), object_context_(object_context), world_(franka_plant_.world_frame()), - end_effector_name_(end_effector_name) { + end_effector_name_(end_effector_name), + object_name_(object_name){ this->set_name("franka_kinematics"); franka_state_port_ = this->DeclareVectorInputPort( @@ -65,15 +67,24 @@ void FrankaKinematics::ComputeLCSState( franka_context_); multibody::SetVelocitiesIfNew(franka_plant_, v_franka, franka_context_); + multibody::SetPositionsIfNew(object_plant_, q_object, + object_context_); + multibody::SetVelocitiesIfNew(object_plant_, v_object, + object_context_); auto end_effector_pose = franka_plant_.EvalBodyPoseInWorld( *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); +// auto franka_base_pose = franka_plant_.EvalBodyPoseInWorld( +// *franka_context_, franka_plant_.GetBodyByName("panda_link0")); + auto object_pose = object_plant_.EvalBodyPoseInWorld( + *object_context_, object_plant_.GetBodyByName(object_name_)); + auto relative_translation = object_pose.translation(); + relative_translation(2) -= 0.7645; auto end_effector_spatial_velocity = franka_plant_.EvalBodySpatialVelocityInWorld( *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); - VectorXd lcs_output = VectorXd::Zero(lcs_state->size() - 1); - lcs_output << end_effector_pose.translation(), q_object, + lcs_output << end_effector_pose.translation(), q_object.head(4), relative_translation, end_effector_spatial_velocity.translational(), v_object; lcs_state->set_timestamp(franka_output->get_timestamp()); diff --git a/examples/franka/franka_kinematics.h b/examples/franka/franka_kinematics.h index e2a361d552..d90adb843d 100644 --- a/examples/franka/franka_kinematics.h +++ b/examples/franka/franka_kinematics.h @@ -18,7 +18,8 @@ class FrankaKinematics : public drake::systems::LeafSystem { drake::systems::Context* franka_context, const drake::multibody::MultibodyPlant& object_plant, drake::systems::Context* object_context, - const std::string& end_effector_name); + const std::string& end_effector_name, + const std::string& object_name); const drake::systems::InputPort& get_input_port_object_state() const { return this->get_input_port(object_state_port_); @@ -47,6 +48,7 @@ class FrankaKinematics : public drake::systems::LeafSystem { drake::systems::Context* object_context_; const drake::multibody::Frame& world_; std::string end_effector_name_; + std::string object_name_; }; } // namespace systems diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 643cf3063d..99597ca799 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -196,9 +196,9 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(trajectory_sub->get_output_port(), trajectory_receiver->get_input_port_trajectory()); - // builder.Connect(end_effector_trajectory->get_output_port(0), - // osc->get_input_port_tracking_data("end_effector_target")); builder.Connect(trajectory_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index cc9187cb30..9acf207b80 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -28,23 +28,22 @@ using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator(const MultibodyPlant& plant, - Context* context) - : plant_(plant), - context_(context), - world_(plant.world_frame()) - { - - +EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( + const MultibodyPlant& plant, Context* context) + : plant_(plant), context_(context), world_(plant.world_frame()) { // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); -// target_vel_port_ = this->DeclareVectorInputPort( -// "v_des", BasicVector(VectorXd::Zero(2))) -// .get_index(); + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + PiecewisePolynomial pp = PiecewisePolynomial(); + + trajectory_port_ = + this->DeclareAbstractInputPort( + "trajectory", + drake::Value>(pp)) + .get_index(); radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) @@ -53,15 +52,12 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator(const MultibodyPl Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, &EndEffectorTrajectoryGenerator::CalcTraj); - } PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( const drake::systems::Context& context) const { const auto robot_output = this->template EvalVectorInput(context, state_port_); -// const auto desired_pelvis_vel_xy = -// this->EvalVectorInput(context, target_vel_port_)->get_value(); const auto& radio_out = this->EvalInputValue(context, radio_port_); double t = robot_output->get_timestamp(); @@ -79,16 +75,14 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( ydot0(2) = -radius * frequency * cos(frequency * t); std::vector breaks = {t, t + dt}; std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold(breaks, - samples); + return drake::trajectories::PiecewisePolynomial::FirstOrderHold( + breaks, samples); } PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( const drake::systems::Context& context) const { const auto robot_output = this->template EvalVectorInput(context, state_port_); -// const auto desired_pelvis_vel_xy = -// this->EvalVectorInput(context, target_vel_port_)->get_value(); const auto& radio_out = this->EvalInputValue(context, radio_port_); double t = robot_output->get_timestamp(); @@ -101,18 +95,14 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( VectorXd ydot0 = VectorXd::Zero(3); std::vector breaks = {t, t + dt}; std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold(breaks, - samples); + return drake::trajectories::PiecewisePolynomial::FirstOrderHold( + breaks, samples); } PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateLine( const drake::systems::Context& context) const { const auto robot_output = this->template EvalVectorInput(context, state_port_); -// const auto desired_pelvis_vel_xy = -// this->EvalVectorInput(context, target_vel_port_)->get_value(); -// const auto radio_signal = -// this->EvalVectorInput(context, radio_port_)->get_value(); double t = robot_output->get_timestamp(); double dt = 0.1; VectorXd y0 = VectorXd::Zero(3); @@ -125,21 +115,30 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateLine( ydot0(2) = -0.2 * M_PI * cos(M_PI * t); std::vector breaks = {t, t + dt}; std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold(breaks, - samples); + return drake::trajectories::PiecewisePolynomial::FirstOrderHold( + breaks, samples); } void EndEffectorTrajectoryGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { // // Read in finite state machine - + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); -// *casted_traj = GenerateCircle(context); - *casted_traj = GeneratePose(context); -// *casted_traj = GenerateLine(context); + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (radio_out->channel[14]) { + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } else { + *casted_traj = GeneratePose(context); + // *casted_traj = GenerateCircle(context); + // *casted_traj = GenerateLine(context); + } } -} // namespace dairlib::examples::osc_run +} // namespace dairlib diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index b762c5eccd..8b41ae5d6a 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -17,8 +17,8 @@ class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); } - const drake::systems::InputPort& get_input_port_target_vel() const { - return this->get_input_port(target_vel_port_); + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_port_); } const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); @@ -43,7 +43,7 @@ class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem const drake::multibody::Frame& world_; drake::systems::InputPortIndex state_port_; - drake::systems::InputPortIndex target_vel_port_; + drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; }; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 062baf26c6..eeed3e48aa 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -29,6 +29,7 @@ struct C3Options { double mu; double mu_plate; double dt; + double solve_dt; int num_friction_directions; int num_contacts; MatrixXd Q; @@ -47,6 +48,7 @@ struct C3Options { a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(mu_plate)); a->Visit(DRAKE_NVP(dt)); + a->Visit(DRAKE_NVP(solve_dt)); a->Visit(DRAKE_NVP(num_friction_directions)); a->Visit(DRAKE_NVP(num_contacts)); @@ -70,6 +72,6 @@ struct C3Options { G = w_G * MatrixXd::Identity(g_size, g_size); U = w_U * MatrixXd::Identity(u_size, u_size); - U.block(0, 0, 19, 19) = 1000 * MatrixXd::Identity(19, 19); + U.block(0, 0, 19, 19) = 100 * MatrixXd::Identity(19, 19); } }; \ No newline at end of file diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index d4693a7666..9443afb5ad 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -43,13 +43,11 @@ std::pair LCSFactory::LinearizePlantToLCS( AutoDiffVecXd C(plant.num_velocities()); plant_ad.CalcBiasTerm(context_ad, &C); + VectorXd u_dyn = plant.get_actuation_input_port().Eval(context); + auto B_dyn_ad = plant_ad.MakeActuationMatrix(); - VectorXd u_dyn = VectorXd::Zero(n_u); - AutoDiffVecXd u_dyn_ad = - drake::math::InitializeAutoDiff(u_dyn, n_q + n_v + n_u); -// AutoDiffVecXd u_dyn_ad = -// plant_ad.; - AutoDiffVecXd Bu = B_dyn_ad * u_dyn_ad; + AutoDiffVecXd Bu = + B_dyn_ad * plant_ad.get_actuation_input_port().Eval(context_ad); AutoDiffVecXd tau_g = plant_ad.CalcGravityGeneralizedForces(context_ad); @@ -60,15 +58,12 @@ std::pair LCSFactory::LinearizePlantToLCS( plant_ad.CalcMassMatrix(context_ad, &M); // If this ldlt is slow, there are alternate formulations which avoid it - // TODO(yangwill): check this line below AutoDiffVecXd vdot_no_contact = M.ldlt().solve(tau_g + Bu + f_app.generalized_forces() - C); // Constant term in dynamics, d_vv = d + A x_0 + B u_0 VectorXd d_vv = ExtractValue(vdot_no_contact); // Derivatives w.r.t. x and u, AB MatrixXd AB_v = ExtractGradient(vdot_no_contact); - // VectorXd inp_dvv = plant.get_actuation_input_port().Eval(context); - // VectorXd inp_dvv = u_dyn; VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + n_u); x_dvv << plant.GetPositions(context), plant.GetVelocities(context), u_dyn; VectorXd x_dvvcomp = AB_v * x_dvv; @@ -79,7 +74,6 @@ std::pair LCSFactory::LinearizePlantToLCS( AutoDiffVecXd qdot_no_contact(plant.num_positions()); AutoDiffVecXd vel_ad = x_ad.tail(n_v); - // TODO(yangwill): check this line below plant_ad.MapVelocityToQDot(context_ad, vel_ad, &qdot_no_contact); MatrixXd AB_q = ExtractGradient(qdot_no_contact); MatrixXd d_q = ExtractValue(qdot_no_contact); @@ -124,19 +118,11 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd H(n_contact_vars, n_u); VectorXd c(n_contact_vars); - MatrixXd AB_v_q = AB_v.block(0, 0, n_v, n_q); MatrixXd AB_v_v = AB_v.block(0, n_q, n_v, n_v); -// MatrixXd AB_v_u = AB_v.block(0, n_x, n_v, n_u); + MatrixXd AB_v_u = AB_v.block(0, n_x, n_v, n_u); MatrixXd M_double = MatrixXd::Zero(n_v, n_v); plant.CalcMassMatrix(context, &M_double); - // TODO(yangwill): Check why gradient wrt u is not working correctly - MatrixXd AB_v_u = M_double.inverse() * MatrixXd::Identity(n_v, n_u); -// AB_v_u = M.ldlt().solve(); -// std::cout << "AB_v: " << AB_v << std::endl; -// std::cout << "AB_v rows: " << AB_v.rows() << std::endl; -// std::cout << "AB_v cols: " << AB_v.cols() << std::endl; -// std::cout << "AB_v_u: " << AB_v_u << std::endl; A.block(0, 0, n_q, n_q) = MatrixXd::Identity(n_q, n_q) + dt * dt * Nq * AB_v_q; @@ -216,18 +202,6 @@ std::pair LCSFactory::LinearizePlantToLCS( c /= AnDn; H /= AnDn; -// std::cout << B << std::endl; -// std::vector A_lcs(N, A); -// std::vector B_lcs(N, B); -// std::vector D_lcs(N, D); -// std::vector d_lcs(N, d); -// std::vector E_lcs(N, E); -// std::vector F_lcs(N, F); -// std::vector c_lcs(N, c); -// std::vector H_lcs(N, H); -// -// LCS system(A_lcs, B_lcs, D_lcs, d_lcs, E_lcs, F_lcs, H_lcs, c_lcs, dt); - LCS system(A, B, D, d, E, F, H, c, N, dt); std::pair ret(system, AnDn); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 9f0d024912..8d55bb9c6b 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -41,7 +41,6 @@ C3Controller::C3Controller( G_(std::vector(c3_options_.N, c3_options_.G)), U_(std::vector(c3_options_.N, c3_options_.U)), N_(c3_options_.N) { - // DRAKE_DEMAND(Q_[0].rows() == lcs.A_[0].rows()); n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_u_ = plant_.num_actuators(); @@ -81,15 +80,19 @@ void C3Controller::OutputTrajectory( VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); x_des[0] = 0.7; x_des[1] = 0.02; - x_des[2] = 0.4; + x_des[2] = 0.35; x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; x_des[6] = 0; - x_des[7] = 0.7; - x_des[8] = 0.02; - x_des[9] = 0.3; + x_des[7] = 0.4; + x_des[8] = -0.2; + x_des[9] = 0.45; std::vector x_desired = std::vector(N_ + 1, x_des); +// std::cout << "x value: " << x.get_data() << std::endl; +// std::cout << "x_desired: " << (x_des - x.get_data()).transpose() << std::endl; + std::cout << "plate_error: " << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() << std::endl; + int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -98,7 +101,6 @@ void C3Controller::OutputTrajectory( plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u), context_); multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u), context_ad_); - // TODO(yangwill): Check why gradient wrt u is not working correctly auto lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, @@ -113,7 +115,6 @@ void C3Controller::OutputTrajectory( c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); c3_->SetOsqpSolverOptions(solver_options_); - // int N = (system_.A_).size(); int n = ((lcs.A_)[0].cols()); int m = ((lcs.D_)[0].cols()); int k = ((lcs.B_)[0].cols()); @@ -128,25 +129,23 @@ void C3Controller::OutputTrajectory( MatrixXd u_sol = MatrixXd::Zero(lcs.k_, N_); VectorXd breaks = VectorXd::Zero(N_); - for (int n = 0; n < N_; n++) { - breaks(n) = t + n * lcs.dt_; -// x_sol.col(n) = state_next; - x_sol.col(n) = z_sol[n].segment(0, lcs.n_); - lambda_sol.col(n) = z_sol[n].segment(lcs.n_, lcs.m_); - u_sol.col(n) = z_sol[n].segment(lcs.n_ + lcs.m_, lcs.k_); + for (int i = 0; i < N_; i++) { + breaks(i) = t + i * lcs.dt_; + x_sol.col(i) = z_sol[i].segment(0, lcs.n_); + lambda_sol.col(i) = z_sol[i].segment(lcs.n_, lcs.m_); + u_sol.col(i) = z_sol[i].segment(lcs.n_ + lcs.m_, lcs.k_); } - double solve_dt = 0.1; +// double solve_dt = c3; auto second_lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, - c3_options_.num_friction_directions, c3_options_.mu, solve_dt, + c3_options_.num_friction_directions, c3_options_.mu, c3_options_.solve_dt, c3_options_.N); auto second_lcs = second_lcs_pair.first; auto second_scale = second_lcs_pair.second; drake::solvers::MobyLCPSolver LCPSolver; VectorXd force; -// auto flag = LCPSolver.SolveLcpLemkeRegularized( - auto flag = LCPSolver.SolveLcpLemke( + auto flag = LCPSolver.SolveLcpLemkeRegularized( second_lcs.F_[0], second_lcs.E_[0] * second_scale * x.get_data() + second_lcs.c_[0] * second_scale + @@ -158,20 +157,12 @@ void C3Controller::OutputTrajectory( second_lcs.D_[0] * force / second_scale + second_lcs.d_[0]; - -// std::cout << "height diff: " << state_next[2] - x.get_data()[2] << std::endl; -// std::cout << "state next: " << state_next.transpose() << std::endl; -// std::cout << "current state: " << x.get_value().transpose() << std::endl; - -// std::cout << "second_lcs.A_[0] * x.get_data(): " << second_lcs.A_[0] * x.get_data() << std::endl; -// std::cout << "second_lcs.B_[0] * u_sol.col(0): " << second_lcs.B_[0] * u_sol.col(0) << std::endl; -// std::cout << "second_lcs.D_[0] * force / second_scale: " << second_lcs.D_[0] * force / second_scale << std::endl; -// std::cout << "second_lcs.d_[0]: " << second_lcs.d_[0] << std::endl; - -// std::cout << "second_lcs.D_[0] * force / second_scale: " << (second_lcs.D_[0] * force / second_scale).transpose() << std::endl; -// std::cout << "second_lcs.D_[0] * lambda / second_scale: " << (second_lcs.D_[0] * lambda_sol.col(0) / second_scale).transpose() << std::endl; - - + x_sol.col(0) = state_next; + x_sol.col(1) = state_next; + x_sol.col(2) = state_next; + x_sol.col(3) = state_next; + x_sol.col(4) = state_next; +// x_sol.col(N_ - 1) = x.get_data(); MatrixXd knots = x_sol.topRows(3); LcmTrajectory::Trajectory end_effector_traj; From 476ac269e8f54a41eeb69452466ce4526167d8bd Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 4 Apr 2023 15:25:26 -0400 Subject: [PATCH 434/758] working on gain tuning to try and find sliding --- examples/franka/franka_c3_controller.cc | 14 +++++++------- examples/franka/franka_c3_options.yaml | 4 ++-- examples/franka/franka_osc_controller.cc | 6 ++---- examples/franka/franka_sim_params.yaml | 2 +- systems/controllers/c3_controller.cc | 24 ++++++++++++++++++++---- systems/controllers/c3_controller.h | 10 ++++++++-- 6 files changed, 40 insertions(+), 20 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 7dbfba1dd1..fcf0b3cde0 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -90,7 +90,6 @@ int DoMain(int argc, char* argv[]) { auto tray_context = plant_tray.CreateDefaultContext(); /// -// MultibodyPlant plant_plate(0.0); auto [plant_plate, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); Parser parser_plate(&plant_plate); parser_plate.AddModelFromFile(controller_params.plate_model); @@ -123,12 +122,7 @@ int DoMain(int argc, char* argv[]) { for (auto geom_id : contact_geoms["PLATE"]) { contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); } - std::cout << "n_contacts: " << contact_pairs.size() << std::endl; - std::cout << "plate_contacts: " << plate_contact_points.size() << std::endl; - std::cout << "tray_contacts: " << tray_geoms.size() << std::endl; - std::cout << "num_positions: " << plant_plate.num_positions() << std::endl; - std::cout << "num_velocities: " << plant_plate.num_velocities() << std::endl; - std::cout << "num_actuators: " << plant_plate.num_actuators() << std::endl; + /// DiagramBuilder builder; @@ -147,6 +141,9 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( controller_params.c3_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + controller_params.radio_channel, &lcm)); auto controller = builder.AddSystem( plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); @@ -159,9 +156,12 @@ int DoMain(int argc, char* argv[]) { reduced_order_model_receiver->get_input_port_object_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(), + controller->get_input_port_radio()); builder.Connect(controller->get_output_port_trajectory(), trajectory_sender->get_input_port()); + // std::unique_ptr> diagram_context = plant_diagram->CreateDefaultContext(); auto owned_diagram = builder.Build(); diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index ed885c2399..988753fad8 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 1 +mu: 0.5 mu_plate: 1 dt: 0.1 solve_dt: 0.15 @@ -23,7 +23,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [100, 100, 100, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [1000, 1000, 1000, 0, 0, 0, 0, 100000, 100000, 100000, 1, 1, 1, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 99597ca799..e28e765249 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -167,16 +167,14 @@ int DoMain(int argc, char* argv[]) { end_effector_orientation_tracking_data->AddFrameToTrack("paddle"); Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); orientation_target(0) = 1; - // orientation_target(2) = 1; - // orientation_target(1) = 1; - // orientation_target(3) = 0.707; + osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), wrist_down_target); osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), orientation_target); - osc->SetContactFriction(0.4); + osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); osc->Build(); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 3f5959a2a7..ca4b630352 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -7,4 +7,4 @@ actuator_delay: 0.005 dt: 0.0001 realtime_rate: 1.0 -q_init_franka: [-0.8, 1.6, 1.3, -1.4, 1.6, 1.3, -0.56] +q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 8d55bb9c6b..c31a12691d 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -2,6 +2,7 @@ #include #include +#include #include "common/find_resource.h" #include "multibody/multibody_utils.h" @@ -44,7 +45,7 @@ C3Controller::C3Controller( n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_u_ = plant_.num_actuators(); - + Q_.back() = 100 * c3_options_.Q; target_input_port_ = this->DeclareVectorInputPort("desired_position", BasicVector(2 + 16)) .get_index(); @@ -53,6 +54,11 @@ C3Controller::C3Controller( TimestampedVector(n_q_ + n_v_)) .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + this->set_name("c3_controller"); trajectory_output_port_ = this->DeclareAbstractOutputPort("c3_output", @@ -67,6 +73,8 @@ void C3Controller::OutputTrajectory( // const BasicVector& x_des = // *this->template EvalVectorInput(context, // target_input_port_); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); const TimestampedVector& x = *this->template EvalVectorInput(context, lcs_state_input_port_); @@ -78,20 +86,28 @@ void C3Controller::OutputTrajectory( drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); + /// default position x_des[0] = 0.7; x_des[1] = 0.02; x_des[2] = 0.35; + /// center of plate + x_des.segment(0, 3) = x.get_data().segment(7, 3); x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; x_des[6] = 0; - x_des[7] = 0.4; + /// radio command + x_des[7] = 0.5; x_des[8] = -0.2; x_des[9] = 0.45; + x_des(7) += radio_out->channel[0] * 0.2; + x_des(8) += radio_out->channel[1] * 0.2; + x_des(9) += radio_out->channel[2] * 0.2; + std::vector x_desired = std::vector(N_ + 1, x_des); -// std::cout << "x value: " << x.get_data() << std::endl; -// std::cout << "x_desired: " << (x_des - x.get_data()).transpose() << std::endl; + std::cout << "plate_error: " << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() << std::endl; + std::cout << "end_effector_error: " << (x_des.segment(0, 3) - x.get_data().segment(0, 3)).transpose() << std::endl; int n_x = plant_.num_positions() + plant_.num_velocities(); diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index b699cc786f..b764b1fa88 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -2,8 +2,10 @@ #include #include + #include +#include "common/find_resource.h" #include "dairlib/lcmt_saved_traj.hpp" #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "lcm/lcm_trajectory.h" @@ -11,11 +13,10 @@ #include "solvers/c3_miqp.h" #include "solvers/c3_options.h" #include "solvers/lcs.h" +#include "solvers/solver_options_io.h" #include "systems/framework/timestamped_vector.h" #include "drake/systems/framework/leaf_system.h" -#include "solvers/solver_options_io.h" -#include "common/find_resource.h" namespace dairlib { namespace systems { @@ -44,6 +45,10 @@ class C3Controller : public drake::systems::LeafSystem { return this->get_output_port(trajectory_output_port_); } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { solver_options_ = options; } @@ -55,6 +60,7 @@ class C3Controller : public drake::systems::LeafSystem { drake::systems::InputPortIndex target_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; + drake::systems::InputPortIndex radio_port_; drake::systems::OutputPortIndex trajectory_output_port_; const drake::multibody::MultibodyPlant& plant_; From 1cafc1b8be6fc436074684b7d2df635c69aac1b5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 4 Apr 2023 15:53:52 -0400 Subject: [PATCH 435/758] adding intilaization of plate for sim --- examples/franka/franka_c3_options.yaml | 2 +- examples/franka/franka_sim.cc | 13 ++++++++++--- examples/franka/franka_sim_params.h | 2 ++ examples/franka/franka_sim_params.yaml | 1 + 4 files changed, 14 insertions(+), 4 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index 988753fad8..76649a4e57 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -23,7 +23,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [1000, 1000, 1000, 0, 0, 0, 0, 100000, 100000, 100000, +q_vector: [1000, 1000, 1000, 0, 0, 0, 0, 10000, 10000, 10000, 1, 1, 1, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index f04ab57525..7ab8801bf5 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -150,6 +150,9 @@ int DoMain(int argc, char* argv[]) { VectorXd q = VectorXd::Zero(nq); std::map q_map = MakeNameToPositionsMap(plant); + for (auto pair : q_map){ + std::cout << pair.first << pair.second << std::endl; + } // initialize EE close to {0.5, 0, 0.12}[m] in task space q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; q[q_map["panda_joint2"]] = sim_params.q_init_franka[1]; @@ -159,9 +162,13 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint6"]] = sim_params.q_init_franka[5]; q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; - q[plant.num_positions() - 7] = 1; - q[plant.num_positions() - 1] = 1.2; - q[plant.num_positions() - 3] = 0.68; + q[q_map["base_qw"]] = sim_params.q_init_plate[0]; + q[q_map["base_qx"]] = sim_params.q_init_plate[1]; + q[q_map["base_qy"]] = sim_params.q_init_plate[2]; + q[q_map["base_qz"]] = sim_params.q_init_plate[3]; + q[q_map["base_x"]] = sim_params.q_init_plate[4]; + q[q_map["base_y"]] = sim_params.q_init_plate[5]; + q[q_map["base_z"]] = sim_params.q_init_plate[6]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 2541bfc1cc..387b1e7fe8 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -11,6 +11,7 @@ struct FrankaSimParams { double dt; double realtime_rate; std::vector q_init_franka; + std::vector q_init_plate; std::string state_channel; std::string controller_channel; @@ -30,6 +31,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); a->Visit(DRAKE_NVP(q_init_franka)); + a->Visit(DRAKE_NVP(q_init_plate)); } }; \ No newline at end of file diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index ca4b630352..24df121ccd 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,3 +8,4 @@ actuator_delay: 0.005 dt: 0.0001 realtime_rate: 1.0 q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] +q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] From a8187935abc4921a16d3f300d992a8369aed3ef5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 4 Apr 2023 17:22:37 -0400 Subject: [PATCH 436/758] testing wide plate to enable sliding --- examples/franka/franka_c3_options.yaml | 4 +-- .../urdf/plate_end_effector_translation.urdf | 24 +++++++++++++-- systems/controllers/c3_controller.cc | 30 +++++++++++-------- 3 files changed, 40 insertions(+), 18 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index 76649a4e57..e657acd4a1 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -4,10 +4,10 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.5 +mu: 0.1 mu_plate: 1 dt: 0.1 -solve_dt: 0.15 +solve_dt: 0.1 num_friction_directions: 2 num_contacts: 3 N: 5 diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index d67b0fec23..b409c9d193 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -51,23 +51,41 @@ + + + + + + + + + + + + + + + + + + - + - + - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index c31a12691d..ecb9a03182 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -2,12 +2,12 @@ #include #include + #include #include "common/find_resource.h" -#include "multibody/multibody_utils.h" - #include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "drake/solvers/moby_lcp_solver.h" @@ -89,9 +89,9 @@ void C3Controller::OutputTrajectory( /// default position x_des[0] = 0.7; x_des[1] = 0.02; - x_des[2] = 0.35; + // x_des[2] = 0.35; /// center of plate - x_des.segment(0, 3) = x.get_data().segment(7, 3); + x_des[2] = 0.45 + radio_out->channel[2] * 0.2; x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; @@ -106,9 +106,12 @@ void C3Controller::OutputTrajectory( std::vector x_desired = std::vector(N_ + 1, x_des); - std::cout << "plate_error: " << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() << std::endl; - std::cout << "end_effector_error: " << (x_des.segment(0, 3) - x.get_data().segment(0, 3)).transpose() << std::endl; - + std::cout << "plate_error: " + << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() + << std::endl; + std::cout << "end_effector_error: " + << (x_des.segment(0, 3) - x.get_data().segment(0, 3)).transpose() + << std::endl; int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -116,7 +119,8 @@ void C3Controller::OutputTrajectory( plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x)); plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u), context_); - multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u), context_ad_); + multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u), + context_ad_); auto lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, @@ -152,7 +156,7 @@ void C3Controller::OutputTrajectory( u_sol.col(i) = z_sol[i].segment(lcs.n_ + lcs.m_, lcs.k_); } -// double solve_dt = c3; + // double solve_dt = c3; auto second_lcs_pair = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.solve_dt, @@ -169,16 +173,16 @@ void C3Controller::OutputTrajectory( &force); (void)flag; // suppress compiler unused variable warning - VectorXd state_next = second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + - second_lcs.D_[0] * force / second_scale + - second_lcs.d_[0]; + VectorXd state_next = + second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + + second_lcs.D_[0] * force / second_scale + second_lcs.d_[0]; x_sol.col(0) = state_next; x_sol.col(1) = state_next; x_sol.col(2) = state_next; x_sol.col(3) = state_next; x_sol.col(4) = state_next; -// x_sol.col(N_ - 1) = x.get_data(); + // x_sol.col(N_ - 1) = x.get_data(); MatrixXd knots = x_sol.topRows(3); LcmTrajectory::Trajectory end_effector_traj; From ce437e17554d0623784b096abb2c4ffcf863c2a4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 5 Apr 2023 13:36:16 -0400 Subject: [PATCH 437/758] double chekcing urdfs --- examples/Cassie/cassie_xbox_remote.py | 12 +- examples/franka/franka_c3_options.yaml | 2 +- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/urdf/franka.urdf | 104 ++++++++++-------- .../urdf/plate_end_effector_translation.urdf | 6 +- systems/controllers/c3_controller.cc | 4 +- 6 files changed, 74 insertions(+), 56 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index e525aeaef0..cac97be810 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -78,14 +78,14 @@ def main(): radio_msg = dairlib.lcmt_radio_out() radio_msg.channel[0] = -joystick.get_axis(1) radio_msg.channel[1] = -joystick.get_axis(0) - radio_msg.channel[2] = -joystick.get_axis(4) - radio_msg.channel[3] = joystick.get_axis(3) - # radio_msg.channel[4] = radio_channel_4_pos - # radio_msg.channel[5] = radio_channel_5_pos - # radio_msg.channel[6] = radio_channel_6_pos + # radio_msg.channel[2] = -joystick.get_axis(4) + # radio_msg.channel[3] = joystick.get_axis(3) + radio_msg.channel[2] = -joystick.get_axis(3) + radio_msg.channel[3] = joystick.get_axis(2) + radio_msg.channel[14] = latching_switch - radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) + # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index e657acd4a1..8b74a2a0d6 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -24,6 +24,6 @@ u_size: 40 #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] q_vector: [1000, 1000, 1000, 0, 0, 0, 0, 10000, 10000, 10000, - 1, 1, 1, 0, 0, 0, 1, 1, 1] + 0, 0, 0, 0, 0, 0, 0, 0, 0] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 24df121ccd..c2848e409f 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -6,6 +6,6 @@ publish_efforts: true actuator_delay: 0.005 dt: 0.0001 -realtime_rate: 1.0 +realtime_rate: 0.5 q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index 7a60ff5451..16ff0b838a 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -9,7 +9,8 @@ - + @@ -106,7 +107,8 @@ - + @@ -162,7 +164,8 @@ - + @@ -218,7 +221,8 @@ - + @@ -268,7 +272,8 @@ - + @@ -330,7 +335,8 @@ - + @@ -422,7 +428,8 @@ - + @@ -472,7 +479,8 @@ - + @@ -505,49 +513,49 @@ + ixx="0.0067" + ixy="0" + ixz="0" + iyy="0.0067" + iyz="0" + izz="0.013"/> - - - - - - - - - - - + + + + + + + + + + + - + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - + + + + + @@ -629,5 +637,15 @@ + + + + + + + + + + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index b409c9d193..4ade2174c4 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -36,19 +36,19 @@ - + - + - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index ecb9a03182..090b5c258c 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -91,7 +91,7 @@ void C3Controller::OutputTrajectory( x_des[1] = 0.02; // x_des[2] = 0.35; /// center of plate - x_des[2] = 0.45 + radio_out->channel[2] * 0.2; + x_des[2] = 0.40 - 0.01 + radio_out->channel[2] * 0.2; x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; @@ -99,7 +99,7 @@ void C3Controller::OutputTrajectory( /// radio command x_des[7] = 0.5; x_des[8] = -0.2; - x_des[9] = 0.45; + x_des[9] = 0.40; x_des(7) += radio_out->channel[0] * 0.2; x_des(8) += radio_out->channel[1] * 0.2; x_des(9) += radio_out->channel[2] * 0.2; From 5311a9a8aeaa885b60c9afae961da63962fe2bee Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 5 Apr 2023 16:38:18 -0400 Subject: [PATCH 438/758] visualziation and collision filters work, working on visualization plan for plate --- examples/franka/BUILD.bazel | 1 + examples/franka/franka_sim.cc | 11 ++++- examples/franka/franka_visualizer.cc | 41 +++++++++++-------- examples/franka/urdf/franka.urdf | 2 +- examples/franka/urdf/table.sdf | 10 +---- systems/controllers/c3_controller.cc | 10 ++--- .../lcm_trajectory_systems.cc | 40 ++++++++++++++++++ .../lcm_trajectory_systems.h | 34 ++++++++++++++- 8 files changed, 114 insertions(+), 35 deletions(-) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 15dc7f82d8..d080f626ad 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -85,6 +85,7 @@ cc_binary( "//multibody:utils", "//multibody:visualization_utils", "//systems:robot_lcm_systems", + "//systems/trajectory_optimization:lcm_trajectory_systems", "//systems:system_utils", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 7ab8801bf5..fde83ad2f9 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -32,6 +32,7 @@ namespace dairlib { using dairlib::systems::SubvectorPassThrough; using drake::geometry::SceneGraph; +using drake::geometry::GeometrySet; using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; @@ -90,9 +91,17 @@ int DoMain(int argc, char* argv[]) { plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", table_index), X_WI); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("link", second_table_index), T_X_W); + plant.GetFrameByName("table", second_table_index), T_X_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); + +// drake::geometry::CollisionFilterDeclaration plate_table = drake::geometry::CollisionFilterDeclaration::ExcludeBetween(plant.GetCollisionGeometriesForBody()); + const drake::geometry::GeometrySet &paddle_geom_set = plant.CollectRegisteredGeometries({&plant.GetBodyByName( + "paddle")}); + auto table_support_set = GeometrySet(plant.GetCollisionGeometriesForBody(plant.GetBodyByName("table"))); +// table_support_set); + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair({"paddle", paddle_geom_set}, {"table_support", table_support_set}); + VectorXd rotor_inertias(plant.num_actuators()); rotor_inertias << 61, 61, 61, 61, 61, 61, 61; diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 7c063a7af2..6649658554 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -1,9 +1,11 @@ #include +#include #include #include #include +#include "common/find_resource.h" #include "dairlib/lcmt_robot_output.hpp" #include "multibody/com_pose_system.h" #include "multibody/multibody_utils.h" @@ -11,6 +13,7 @@ #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" #include "drake/common/find_resource.h" #include "drake/common/yaml/yaml_io.h" @@ -22,7 +25,6 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/rendering/multibody_position_to_geometry_pose.h" -#include "common/find_resource.h" DEFINE_string(channel, "FRANKA_OUTPUT", "LCM channel for receiving state. " @@ -76,9 +78,8 @@ int do_main(int argc, char* argv[]) { parser.AddModelFromFile( dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), "table1"); - drake::multibody::ModelInstanceIndex tray_index = - parser.AddModelFromFile(FindResourceOrThrow( - "examples/franka/urdf/tray.sdf")); + drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile( + FindResourceOrThrow("examples/franka/urdf/tray.sdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); @@ -112,32 +113,23 @@ int do_main(int argc, char* argv[]) { auto tray_state_receiver = builder.AddSystem(plant, tray_index); - builder.Connect(*franka_state_sub, *franka_state_receiver); - builder.Connect(*tray_state_sub, *tray_state_receiver); - auto franka_passthrough = builder.AddSystem( franka_state_receiver->get_output_port(0).size(), 0, plant.num_positions(franka_index)); auto tray_passthrough = builder.AddSystem( tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); - builder.Connect(*franka_state_receiver, *franka_passthrough); - builder.Connect(*tray_state_receiver, *tray_passthrough); std::vector input_sizes = {plant.num_positions(franka_index), plant.num_positions(tray_index)}; auto mux = builder.AddSystem>(input_sizes); - builder.Connect(franka_passthrough->get_output_port(), - mux->get_input_port(0)); - builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); + auto trajectory_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + "C3_TRAJECTORY", lcm)); auto to_pose = builder.AddSystem>(plant); - builder.Connect(*mux, *to_pose); - builder.Connect( - to_pose->get_output_port(), - scene_graph.get_source_pose_port(plant.get_source_id().value())); DrakeVisualizer::AddToBuilder(&builder, scene_graph); drake::geometry::MeshcatVisualizerParams params; @@ -145,8 +137,23 @@ int do_main(int argc, char* argv[]) { auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); + auto trajectory_drawer = builder.AddSystem( + meshcat, "end_effector_traj"); - // state_receiver->set_publish_period(1.0/30.0); // framerate + builder.Connect(franka_passthrough->get_output_port(), + mux->get_input_port(0)); + builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); + builder.Connect(trajectory_sub->get_output_port(), + trajectory_drawer->get_input_port_trajectory()); + builder.Connect(*mux, *to_pose); + builder.Connect( + to_pose->get_output_port(), + scene_graph.get_source_pose_port(plant.get_source_id().value())); + builder.Connect(*franka_state_receiver, *franka_passthrough); + builder.Connect(*tray_state_receiver, *tray_passthrough); + + builder.Connect(*franka_state_sub, *franka_state_receiver); + builder.Connect(*tray_state_sub, *tray_state_receiver); auto diagram = builder.Build(); auto context = diagram->CreateDefaultContext(); diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index 16ff0b838a..3e3afb769c 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -642,7 +642,7 @@ - + diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf index 4cec1032bc..8e03995fc2 100644 --- a/examples/franka/urdf/table.sdf +++ b/examples/franka/urdf/table.sdf @@ -9,7 +9,7 @@ involving the table due to a decrease in number of collision checks needed. --> - + 53.5 - 0 0 0.7645 0 0 0 - - 100 + 1 - 0.4 - 0.4 + 1.0 + 1.0 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7e26af9a47..7c07804dcc 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -77,9 +77,9 @@ C3Controller::C3Controller( dairlib::lcmt_timestamped_saved_traj(), &C3Controller::OutputObjectTrajectory) .get_index(); - - //TODO:yangwill check to make sure C3 isn't computing twice here - DeclarePerStepDiscreteUpdateEvent(&C3Controller::ComputePlan); + plan_start_time_index_ = DeclareDiscreteState(1); + // TODO:yangwill check to make sure C3 isn't computing twice here + DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); } drake::systems::EventStatus C3Controller::ComputePlan( @@ -90,6 +90,9 @@ drake::systems::EventStatus C3Controller::ComputePlan( const TimestampedVector& x = *this->template EvalVectorInput(context, lcs_state_input_port_); + discrete_state->get_mutable_value(plan_start_time_index_)[0] = + x.get_timestamp(); + VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); @@ -102,27 +105,27 @@ drake::systems::EventStatus C3Controller::ComputePlan( x_des[1] = 0.02; // x_des[2] = 0.35; /// center of plate - x_des[2] = 0.40 - 0.01 + radio_out->channel[2] * 0.2; + x_des[2] = 0.45 - 0.01 + radio_out->channel[2] * 0.2; x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; x_des[6] = 0; /// radio command - x_des[7] = 0.5; - x_des[8] = -0.2; - x_des[9] = 0.40; + x_des[7] = 0.7; + x_des[8] = 0.02; + x_des[9] = 0.45; x_des(7) += radio_out->channel[0] * 0.2; x_des(8) += radio_out->channel[1] * 0.2; x_des(9) += radio_out->channel[2] * 0.2; std::vector x_desired = std::vector(N_ + 1, x_des); - std::cout << "plate_error: " - << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() - << std::endl; - std::cout << "end_effector_error: " - << (x_des.segment(0, 3) - x.get_data().segment(0, 3)).transpose() - << std::endl; +// std::cout << "plate_error: " +// << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() +// << std::endl; +// std::cout << "end_effector_error: " +// << (x_des.segment(0, 3) - x.get_data().segment(0, 3)).transpose() +// << std::endl; int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -156,12 +159,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( void C3Controller::OutputActorTrajectory( const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const { - - const TimestampedVector& x = - *this->template EvalVectorInput(context, - lcs_state_input_port_); - // TODO:yangwill, check to make sure the time being used here makes sense - double t = x.get_timestamp(); + double t = context.get_discrete_state(plan_start_time_index_)[0]; auto z_sol = c3_->GetFullSolution(); MatrixXd x_sol = MatrixXd::Zero(n_q_ + n_v_, N_); @@ -186,15 +184,22 @@ void C3Controller::OutputActorTrajectory( // VectorXd force; // auto flag = LCPSolver.SolveLcpLemkeRegularized( // second_lcs.F_[0], -// second_lcs.E_[0] * second_scale * x.get_data() + +// second_lcs.E_[0] * second_scale * x_sol.col(0) + // second_lcs.c_[0] * second_scale + // second_lcs.H_[0] * second_scale * u_sol.col(0), // &force); // +// (void)flag; // suppress compiler unused variable warning // VectorXd state_next = -// second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + +// second_lcs.A_[0] * x_sol.col(0) + second_lcs.B_[0] * u_sol.col(0) + // second_lcs.D_[0] * force / second_scale + second_lcs.d_[0]; +// x_sol.col(0) = state_next; +// x_sol.col(1) = state_next; + // x_sol.col(2) = state_next; + // x_sol.col(0) = state_next; + // x_sol.col(0) = state_next; + MatrixXd knots = x_sol.topRows(3); LcmTrajectory::Trajectory end_effector_traj; end_effector_traj.traj_name = "end_effector_traj"; @@ -211,12 +216,8 @@ void C3Controller::OutputActorTrajectory( void C3Controller::OutputObjectTrajectory( const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const { - - const TimestampedVector& x = - *this->template EvalVectorInput(context, - lcs_state_input_port_); // TODO:yangwill, check to make sure the time being used here makes sense - double t = x.get_timestamp(); + double t = context.get_discrete_state(plan_start_time_index_)[0]; auto z_sol = c3_->GetFullSolution(); MatrixXd x_sol = MatrixXd::Zero(n_q_ + n_v_, N_); @@ -231,36 +232,14 @@ void C3Controller::OutputObjectTrajectory( u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); } - // double solve_dt = c3; -// auto second_lcs_pair = LCSFactory::LinearizePlantToLCS( -// plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, -// c3_options_.num_friction_directions, c3_options_.mu, c3_options_.solve_dt, -// c3_options_.N); -// auto second_lcs = second_lcs_pair.first; -// auto second_scale = second_lcs_pair.second; -// drake::solvers::MobyLCPSolver LCPSolver; -// VectorXd force; -// auto flag = LCPSolver.SolveLcpLemkeRegularized( -// second_lcs.F_[0], -// second_lcs.E_[0] * second_scale * x.get_data() + -// second_lcs.c_[0] * second_scale + -// second_lcs.H_[0] * second_scale * u_sol.col(0), -// &force); -// -// (void)flag; // suppress compiler unused variable warning -// VectorXd state_next = -// second_lcs.A_[0] * x.get_data() + second_lcs.B_[0] * u_sol.col(0) + -// second_lcs.D_[0] * force / second_scale + second_lcs.d_[0]; - - MatrixXd knots = x_sol.topRows(n_q_).bottomRows( 3); + MatrixXd knots = x_sol.topRows(n_q_).bottomRows(3); LcmTrajectory::Trajectory object_traj; object_traj.traj_name = "object_traj"; - object_traj.datatypes = - std::vector(knots.rows(), "double"); + object_traj.datatypes = std::vector(knots.rows(), "double"); object_traj.datapoints = knots; object_traj.time_vector = breaks; - LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, - "object_traj", "object_traj", false); + LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, "object_traj", + "object_traj", false); output_traj->saved_traj = lcm_traj.GenerateLcmObject(); output_traj->utime = t * 1e6; } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index b75fa2e88f..b8996e92bc 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -98,7 +98,7 @@ class C3Controller : public drake::systems::LeafSystem { mutable std::unique_ptr c3_; // std::unique_ptr lcs_; - + drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; std::vector R_; std::vector G_; diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index 19d29a2ed0..60a4e89b31 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -261,7 +261,11 @@ class LcmDrivenLoop { simulator_->Initialize(); } simulator_->AdvanceTo(time); - if (is_forced_publish_) { + diagram_ptr_->CalcForcedUnrestrictedUpdate( + diagram_context, &diagram_context.get_mutable_state()); + diagram_ptr_->CalcForcedDiscreteVariableUpdate(diagram_context, + &diagram_context.get_mutable_discrete_state()); + if (is_forced_publish_) { // Force-publish via the diagram diagram_ptr_->ForcedPublish(diagram_context); } From a38347b23717f747dfa3eb65a89623296b53eb70 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 6 Apr 2023 13:51:29 -0400 Subject: [PATCH 443/758] attempting to initiate sliding --- examples/franka/franka_c3_options.yaml | 2 +- examples/franka/franka_sim.cc | 6 +- examples/franka/franka_sim_params.h | 27 +- examples/franka/franka_sim_params.yaml | 4 +- examples/franka/urdf/franka_no_collision.urdf | 309 ++++++++++++++++++ examples/franka/urdf/table.sdf | 6 +- 6 files changed, 338 insertions(+), 16 deletions(-) create mode 100644 examples/franka/urdf/franka_no_collision.urdf diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index eef8d0c0d6..cb2166f9fa 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.1 +mu: 1.0 mu_plate: 1 dt: 0.1 solve_dt: 0.05 diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index eb7d3d173b..f7898b7b5c 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -66,7 +66,7 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModelFromFile("examples/franka/urdf/franka.urdf"); + parser.AddModelFromFile(sim_params.franka_model); drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( drake::FindResourceOrThrow( "drake/examples/kuka_iiwa_arm/models/table/" @@ -149,7 +149,9 @@ int DoMain(int argc, char* argv[]) { int nv = plant.num_velocities(); int nu = plant.num_actuators(); - drake::visualization::AddDefaultVisualization(&builder); + if (sim_params.visualize){ + drake::visualization::AddDefaultVisualization(&builder); + } auto diagram = builder.Build(); diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 387b1e7fe8..7dcd7c5e30 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -8,28 +8,37 @@ using Eigen::MatrixXd; struct FrankaSimParams { - double dt; - double realtime_rate; - std::vector q_init_franka; - std::vector q_init_plate; - std::string state_channel; std::string controller_channel; std::string tray_state_channel; + std::string franka_model; + + double dt; + double realtime_rate; + double actuator_delay; double publish_rate; + + bool visualize; bool publish_efforts; - double actuator_delay; + + std::vector q_init_franka; + std::vector q_init_plate; template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(state_channel)); a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(tray_state_channel)); - a->Visit(DRAKE_NVP(publish_rate)); - a->Visit(DRAKE_NVP(publish_efforts)); - a->Visit(DRAKE_NVP(actuator_delay)); + a->Visit(DRAKE_NVP(franka_model)); + a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); + a->Visit(DRAKE_NVP(actuator_delay)); + a->Visit(DRAKE_NVP(publish_rate)); + + a->Visit(DRAKE_NVP(visualize)); + a->Visit(DRAKE_NVP(publish_efforts)); + a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 24df121ccd..bff3b67173 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -1,11 +1,13 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT tray_state_channel: TRAY_OUTPUT +franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.005 +visualize: false dt: 0.0001 -realtime_rate: 1.0 +realtime_rate: 0.2 q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf new file mode 100644 index 0000000000..077975b7f8 --- /dev/null +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -0,0 +1,309 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + , + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface + + + PositionJointInterface + 1 + + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf index 8e03995fc2..e4c5953210 100644 --- a/examples/franka/urdf/table.sdf +++ b/examples/franka/urdf/table.sdf @@ -207,7 +207,7 @@ - 0.0 + 0.001 0.04 0.12 1.143 0 0 0 @@ -215,7 +215,7 @@ - 0.0 + 0.001 0.04 -0.12 1.143 0 0 0 @@ -223,7 +223,7 @@ - 0.0 + 0.001 -0.20 0.12 1.143 0 0 0 From c0fded2531b25cb78c6b0087c8f2eae157a8941b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 6 Apr 2023 16:54:13 -0400 Subject: [PATCH 444/758] adding feed forward term --- examples/franka/franka_c3_options.yaml | 6 ++-- examples/franka/franka_controller_params.yaml | 4 +-- examples/franka/franka_sim_params.yaml | 6 ++-- examples/franka/urdf/franka_no_collision.urdf | 4 +-- .../urdf/plate_end_effector_translation.urdf | 28 +++++++++---------- examples/franka/urdf/tray.sdf | 11 +++++--- systems/controllers/c3_controller.cc | 11 ++++++-- .../lcm_trajectory_systems.cc | 13 ++++++--- 8 files changed, 48 insertions(+), 35 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index cb2166f9fa..a9207d4deb 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -1,10 +1,10 @@ -admm_iter: 2 +admm_iter: 4 rho: 0.1 rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 1.0 +mu: 0.1 mu_plate: 1 dt: 0.1 solve_dt: 0.05 @@ -23,7 +23,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [500, 500, 1000, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index a8c161362c..9e0c7cc239 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -53,8 +53,8 @@ EndEffectorRotW: 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 500, 0, 0, - 0, 500, 0, + [ 2000, 0, 0, + 0, 2000, 0, 0, 0, 500 ] EndEffectorRotKd: [ 40, 0, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index bff3b67173..c812b13ee6 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -5,9 +5,9 @@ franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.005 -visualize: false +visualize: true dt: 0.0001 -realtime_rate: 0.2 +realtime_rate: 1.0 q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] -q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] +q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.2] diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 077975b7f8..7fe0fd5c73 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -181,7 +181,7 @@ - + @@ -193,7 +193,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 4ade2174c4..d0b5bd68db 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -28,25 +28,25 @@ - + - + - - + + - - + + - - + + @@ -71,21 +71,21 @@ - + - + - + - + - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 165c4fd731..e7683f0419 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -18,18 +18,21 @@ - 0.3 0.6 0.02 + 0.15 0.3 0.02 - 0.3 0.6 0.02 + 0.15 0.3 0.02 + + + - 1.0 - 1.0 + 0.2 + 0.2 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7c07804dcc..06a65f12bd 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -111,8 +111,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( x_des[5] = 0; x_des[6] = 0; /// radio command - x_des[7] = 0.7; - x_des[8] = 0.02; +// x_des[7] = 0.7; +// x_des[8] = 0.02; +// x_des[9] = 0.45; + x_des[7] = 0.5; + x_des[8] = -0.2; x_des[9] = 0.45; x_des(7) += radio_out->channel[0] * 0.2; x_des(8) += radio_out->channel[1] * 0.2; @@ -200,7 +203,9 @@ void C3Controller::OutputActorTrajectory( // x_sol.col(0) = state_next; // x_sol.col(0) = state_next; - MatrixXd knots = x_sol.topRows(3); + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = x_sol.topRows(3); + knots.bottomRows(3) = x_sol.bottomRows(n_v_).topRows(3); LcmTrajectory::Trajectory end_effector_traj; end_effector_traj.traj_name = "end_effector_traj"; end_effector_traj.datatypes = diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index c393d1f348..85bc6d42ae 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -49,8 +49,14 @@ void LcmTrajectoryReceiver::OutputTrajectory( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - *casted_traj = PiecewisePolynomial::FirstOrderHold( - trajectory_block.time_vector, trajectory_block.datapoints); + if (trajectory_block.datapoints.rows() == 3) { + *casted_traj = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); + } else { + *casted_traj = PiecewisePolynomial::CubicHermite( + trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), + trajectory_block.datapoints.bottomRows(3)); + } } LcmTrajectoryDrawer::LcmTrajectoryDrawer( @@ -87,8 +93,7 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( for (int i = 0; i < setpoints.cols(); ++i) { setpoints(2, i) += 0.7645; } - meshcat_->SetLine("/trajectories/" + trajectory_name_, setpoints, 100, - rgba_); + meshcat_->SetLine("/trajectories/" + trajectory_name_, setpoints, 100, rgba_); return drake::systems::EventStatus::Succeeded(); } From cbf843afc953f3ed1ca8b8aff45f1f465a7cd2b6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 7 Apr 2023 11:13:25 -0400 Subject: [PATCH 445/758] small trajectory tweaks --- examples/franka/franka_c3_options.yaml | 2 +- examples/franka/franka_controller_params.yaml | 14 ++++---- examples/franka/franka_visualizer.cc | 4 ++- examples/franka/urdf/franka.urdf | 4 +-- examples/franka/urdf/tray.sdf | 4 +-- systems/controllers/c3_controller.cc | 11 ++++--- .../lcm_trajectory_systems.cc | 33 ++++++++++++++++--- .../lcm_trajectory_systems.h | 6 ++++ 8 files changed, 55 insertions(+), 23 deletions(-) diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index a9207d4deb..e09d61bd62 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.1 +mu: 0.2 mu_plate: 1 dt: 0.1 solve_dt: 0.05 diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 9e0c7cc239..a66e389403 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -25,17 +25,17 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] EndEffectorW: - [1, 0, 0, - 0, 1, 0, + [5, 0, 0, + 0, 5, 0, 0, 0, 1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, 0, 0, 200 ] EndEffectorKd: - [ 30, 0, 0, - 0, 30, 0, - 0, 0, 30 ] + [ 50, 0, 0, + 0, 50, 0, + 0, 0, 50 ] MidLinkW: [0, 0, 0, 0, 0, 0, @@ -57,6 +57,6 @@ EndEffectorRotKp: 0, 2000, 0, 0, 0, 500 ] EndEffectorRotKd: - [ 40, 0, 0, - 0, 40, 0, + [ 100, 0, 0, + 0, 100, 0, 0, 0, 40 ] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index ddaa813aee..bf234798d2 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -138,7 +138,7 @@ int do_main(int argc, char* argv[]) { auto to_pose = builder.AddSystem>(plant); - DrakeVisualizer::AddToBuilder(&builder, scene_graph); +// DrakeVisualizer::AddToBuilder(&builder, scene_graph); drake::geometry::MeshcatVisualizerParams params; params.publish_period = 1.0 / 60.0; auto meshcat = std::make_shared(); @@ -150,6 +150,8 @@ int do_main(int argc, char* argv[]) { meshcat, "object_traj"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); + trajectory_drawer_actor->SetNumSamples(20); + trajectory_drawer_object->SetNumSamples(20); builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index 70b0a64a7d..e69872b9c8 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -523,7 +523,7 @@ - + @@ -535,7 +535,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index e7683f0419..43f99f8067 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -18,14 +18,14 @@ - 0.15 0.3 0.02 + 0.3 0.6 0.02 - 0.15 0.3 0.02 + 0.3 0.6 0.02 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 06a65f12bd..87cface19b 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -105,15 +105,13 @@ drake::systems::EventStatus C3Controller::ComputePlan( x_des[1] = 0.02; // x_des[2] = 0.35; /// center of plate - x_des[2] = 0.45 - 0.01 + radio_out->channel[2] * 0.2; + /// thickness of tray 0.5 * (0.02) + thickness of end effector 0.5 * (0.02) + x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; x_des[6] = 0; /// radio command -// x_des[7] = 0.7; -// x_des[8] = 0.02; -// x_des[9] = 0.45; x_des[7] = 0.5; x_des[8] = -0.2; x_des[9] = 0.45; @@ -237,7 +235,10 @@ void C3Controller::OutputObjectTrajectory( u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); } - MatrixXd knots = x_sol.topRows(n_q_).bottomRows(3); +// MatrixXd knots = x_sol.topRows(n_q_).bottomRows(3); + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = x_sol.topRows(n_q_).bottomRows(3); + knots.bottomRows(3) = x_sol.bottomRows(n_v_).bottomRows(3); LcmTrajectory::Trajectory object_traj; object_traj.traj_name = "object_traj"; object_traj.datatypes = std::vector(knots.rows(), "double"); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 85bc6d42ae..715680db9d 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -15,6 +15,8 @@ using drake::systems::Context; using drake::systems::DiscreteValues; using drake::trajectories::PiecewisePolynomial; using drake::trajectories::Trajectory; +using Eigen::MatrixXd; +using Eigen::VectorXd; LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) : trajectory_name_(std::move(trajectory_name)) { @@ -88,12 +90,33 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( context, trajectory_input_port_); lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); } - Eigen::MatrixXd setpoints = - lcm_traj_.GetTrajectory(trajectory_name_).datapoints; - for (int i = 0; i < setpoints.cols(); ++i) { - setpoints(2, i) += 0.7645; + const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); + MatrixXd line_points = MatrixXd::Zero(3, N_); + VectorXd breaks = + VectorXd::LinSpaced(N_, trajectory_block.time_vector[0], + trajectory_block.time_vector.tail(1)[0]); +// std::cout << "rows: " << trajectory_block.datapoints.rows() << std::endl; +// std::cout << "cols: " << trajectory_block.datapoints.cols() << std::endl; + if (trajectory_block.datapoints.rows() == 3) { + auto trajectory = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); + for (int i = 0; i < line_points.cols(); ++i) { + line_points.col(i) = trajectory.value(breaks(i)); + line_points(2, i) += 0.7645; + } + } else { + auto trajectory = PiecewisePolynomial::CubicHermite( + trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), + trajectory_block.datapoints.bottomRows(3)); + for (int i = 0; i < line_points.cols(); ++i) { + line_points.col(i) = trajectory.value(breaks(i)); + line_points(2, i) += 0.7645; + } } - meshcat_->SetLine("/trajectories/" + trajectory_name_, setpoints, 100, rgba_); + + DRAKE_DEMAND(line_points.rows() == 3); + meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, + rgba_); return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index fa1dd44cf5..6e254fad05 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -58,6 +58,11 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { rgba_ = rgba; } + void SetNumSamples(int N){ + DRAKE_DEMAND(N > 1); + N_ = N; + } + private: void OutputTrajectory(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -72,6 +77,7 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { mutable LcmTrajectory lcm_traj_; std::string default_trajectory_path_; drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + int N_ = 5; }; } // namespace systems From 0a63fa35a915db2dd0f068888fac2fda068ac33f Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 7 Apr 2023 12:28:24 -0400 Subject: [PATCH 446/758] working on controlling orientation as well --- examples/franka/franka_c3_options.yaml | 2 +- examples/franka/franka_controller_params.yaml | 4 +- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/urdf/franka.urdf | 12 +- examples/franka/urdf/franka_no_collision.urdf | 608 +++++++++--------- .../urdf/plate_end_effector_floating.urdf | 109 ++++ .../urdf/plate_end_effector_translation.urdf | 12 - systems/controllers/c3_controller.cc | 37 +- 8 files changed, 439 insertions(+), 347 deletions(-) create mode 100644 examples/franka/urdf/plate_end_effector_floating.urdf diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options.yaml index e09d61bd62..cf241aeffa 100644 --- a/examples/franka/franka_c3_options.yaml +++ b/examples/franka/franka_c3_options.yaml @@ -23,7 +23,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [200, 200, 500, 500, 500, 500, 500, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index a66e389403..9639994557 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -6,8 +6,8 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_channel: C3_TRAJECTORY_ACTOR w_input: 0.00 -w_input_reg: 0.0001 -w_accel: 0.1 +w_input_reg: 1 +w_accel: 1 w_soft_constraint: 10000 w_lambda: 0.1 impact_threshold: 0.000 diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index c812b13ee6..663eda0cf1 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -2,7 +2,7 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT tray_state_channel: TRAY_OUTPUT franka_model: examples/franka/urdf/franka_no_collision.urdf -publish_rate: 1000 +publish_rate: 4000 publish_efforts: true actuator_delay: 0.005 visualize: true diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index e69872b9c8..d355f910ae 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -513,12 +513,12 @@ + ixx="0.01043" + ixy="0" + ixz="0" + iyy="0.01043" + iyz="0" + izz="0.020833"/> diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 7fe0fd5c73..f87d49377a 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -1,309 +1,325 @@ - - - + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + , + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - - - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - - - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - - - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - - - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - - - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - , - - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + transmission_interface/SimpleTransmission + + PositionJointInterface - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - - - - - + + PositionJointInterface + 1 + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf new file mode 100644 index 0000000000..ad2605142e --- /dev/null +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -0,0 +1,109 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + 1 + + + + + 1 + + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index d0b5bd68db..ad2605142e 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -15,18 +15,6 @@ iyz="0" izz="0.013"/> - - - - - - - - - - - - diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 87cface19b..46bd3bce19 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -107,13 +107,18 @@ drake::systems::EventStatus C3Controller::ComputePlan( /// center of plate /// thickness of tray 0.5 * (0.02) + thickness of end effector 0.5 * (0.02) x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; - x_des[3] = 1; +// x_des[3] = 1; +// x_des[4] = 0; +// x_des[5] = 0; +// x_des[6] = 0; + x_des[3] = 0.707; x_des[4] = 0; x_des[5] = 0; - x_des[6] = 0; + x_des[6] = 0.707; /// radio command x_des[7] = 0.5; - x_des[8] = -0.2; +// x_des[8] = -0.2; + x_des[8] = 0.2; x_des[9] = 0.45; x_des(7) += radio_out->channel[0] * 0.2; x_des(8) += radio_out->channel[1] * 0.2; @@ -175,32 +180,6 @@ void C3Controller::OutputActorTrajectory( u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); } -// auto second_lcs_pair = LCSFactory::LinearizePlantToLCS( -// plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, -// c3_options_.num_friction_directions, c3_options_.mu, c3_options_.solve_dt, -// c3_options_.N); -// auto second_lcs = second_lcs_pair.first; -// auto second_scale = second_lcs_pair.second; -// drake::solvers::MobyLCPSolver LCPSolver; -// VectorXd force; -// auto flag = LCPSolver.SolveLcpLemkeRegularized( -// second_lcs.F_[0], -// second_lcs.E_[0] * second_scale * x_sol.col(0) + -// second_lcs.c_[0] * second_scale + -// second_lcs.H_[0] * second_scale * u_sol.col(0), -// &force); -// -// (void)flag; // suppress compiler unused variable warning -// VectorXd state_next = -// second_lcs.A_[0] * x_sol.col(0) + second_lcs.B_[0] * u_sol.col(0) + -// second_lcs.D_[0] * force / second_scale + second_lcs.d_[0]; - -// x_sol.col(0) = state_next; -// x_sol.col(1) = state_next; - // x_sol.col(2) = state_next; - // x_sol.col(0) = state_next; - // x_sol.col(0) = state_next; - MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = x_sol.topRows(3); knots.bottomRows(3) = x_sol.bottomRows(n_v_).topRows(3); From 4eca19b58effe2d1fcb46393720e24eadc14c21e Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 7 Apr 2023 16:30:03 -0400 Subject: [PATCH 447/758] using better organized vector --- examples/franka/BUILD.bazel | 17 +- examples/franka/franka_c3_controller.cc | 29 +-- examples/franka/franka_c3_controller_params.h | 2 + .../franka/franka_c3_controller_params.yaml | 7 +- ...s.yaml => franka_c3_options_floating.yaml} | 0 .../franka/franka_c3_options_translation.yaml | 29 +++ examples/franka/systems/BUILD.bazel | 33 ++++ .../franka/{ => systems}/franka_kinematics.cc | 64 +++++-- .../franka/{ => systems}/franka_kinematics.h | 12 +- .../systems/franka_kinematics_vector.cc | 6 + .../franka/systems/franka_kinematics_vector.h | 175 ++++++++++++++++++ .../urdf/plate_end_effector_floating.urdf | 33 ++++ systems/controllers/BUILD.bazel | 1 + systems/controllers/c3_controller.cc | 53 +++--- systems/framework/timestamped_vector.h | 39 ++-- 15 files changed, 412 insertions(+), 88 deletions(-) rename examples/franka/{franka_c3_options.yaml => franka_c3_options_floating.yaml} (100%) create mode 100644 examples/franka/franka_c3_options_translation.yaml rename examples/franka/{ => systems}/franka_kinematics.cc (59%) rename examples/franka/{ => systems}/franka_kinematics.h (81%) create mode 100644 examples/franka/systems/franka_kinematics_vector.cc create mode 100644 examples/franka/systems/franka_kinematics_vector.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index d080f626ad..97cf700988 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -37,7 +37,7 @@ cc_binary( ], deps = [ ":franka_controller_params", - "//examples/franka/systems:end_effector_trajectory", + "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -59,8 +59,7 @@ cc_binary( ], deps = [ ":franka_c3_controller_params", - ":franka_kinematics", - "//examples/franka/systems:end_effector_trajectory", + "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -109,18 +108,6 @@ cc_library( ], ) -cc_library( - name = "franka_kinematics", - srcs = ["franka_kinematics.cc"], - hdrs = ["franka_kinematics.h"], - deps = [ - "//lcmtypes:lcmt_robot", - "//common", - "//multibody:utils", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) cc_library( diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index bf7795ed3d..8d83fc28dc 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -3,8 +3,8 @@ #include #include "examples/franka/franka_c3_controller_params.h" -#include "examples/franka/franka_kinematics.h" #include "examples/franka/systems/end_effector_trajectory.h" +#include "examples/franka/systems/franka_kinematics.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" @@ -29,9 +29,9 @@ using dairlib::solvers::LCSFactory; using drake::SortedPair; using drake::geometry::GeometryId; using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; -using drake::multibody::AddMultibodyPlantSceneGraph; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -90,7 +90,8 @@ int DoMain(int argc, char* argv[]) { auto tray_context = plant_tray.CreateDefaultContext(); /// - auto [plant_plate, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + auto [plant_plate, scene_graph] = + AddMultibodyPlantSceneGraph(&plant_builder, 0.0); Parser parser_plate(&plant_plate); parser_plate.AddModelFromFile(controller_params.plate_model); parser_plate.AddModelFromFile(controller_params.tray_model); @@ -102,8 +103,10 @@ int DoMain(int argc, char* argv[]) { drake::systems::System::ToAutoDiffXd(plant_plate); auto plant_diagram = plant_builder.Build(); - std::unique_ptr> diagram_context = plant_diagram->CreateDefaultContext(); - auto& plate_context = plant_diagram->GetMutableSubsystemContext(plant_plate, diagram_context.get()); + std::unique_ptr> diagram_context = + plant_diagram->CreateDefaultContext(); + auto& plate_context = plant_diagram->GetMutableSubsystemContext( + plant_plate, diagram_context.get()); auto plate_context_ad = plant_plate_ad->CreateDefaultContext(); /// @@ -136,13 +139,15 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant_tray); auto reduced_order_model_receiver = builder.AddSystem( - plant_franka, franka_context.get(), plant_tray, tray_context.get(), "paddle", "tray"); - auto actor_trajectory_sender = - builder.AddSystem(LcmPublisherSystem::Make( + plant_franka, franka_context.get(), plant_tray, tray_context.get(), + "paddle", "tray", controller_params.include_end_effector_orientation); + + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( controller_params.c3_channel_actor, &lcm, TriggerTypeSet({TriggerType::kForced}))); - auto object_trajectory_sender = - builder.AddSystem(LcmPublisherSystem::Make( + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( controller_params.c3_channel_object, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto radio_sub = @@ -150,7 +155,8 @@ int DoMain(int argc, char* argv[]) { controller_params.radio_channel, &lcm)); auto controller = builder.AddSystem( - plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); + plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), + contact_pairs, c3_options); controller->SetOsqpSolverOptions(solver_options); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); @@ -167,7 +173,6 @@ int DoMain(int argc, char* argv[]) { builder.Connect(controller->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); - auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index 0fc3478634..c8e5102993 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -17,6 +17,7 @@ struct FrankaC3ControllerParams { std::string franka_model; std::string plate_model; std::string tray_model; + bool include_end_effector_orientation; template void Serialize(Archive* a) { @@ -28,5 +29,6 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(plate_model)); a->Visit(DRAKE_NVP(tray_model)); + a->Visit(DRAKE_NVP(include_end_effector_orientation)); } }; \ No newline at end of file diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 9e1e7897f7..72dd4cfa16 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,4 +1,5 @@ -c3_options_file: examples/franka/franka_c3_options.yaml +#c3_options_file: examples/franka/franka_c3_options_translation.yaml +c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,8 +8,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf #plate_model: examples/franka/urdf/plate_end_effector.urdf -plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf +include_end_effector_orientation: true diff --git a/examples/franka/franka_c3_options.yaml b/examples/franka/franka_c3_options_floating.yaml similarity index 100% rename from examples/franka/franka_c3_options.yaml rename to examples/franka/franka_c3_options_floating.yaml diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml new file mode 100644 index 0000000000..cf241aeffa --- /dev/null +++ b/examples/franka/franka_c3_options_translation.yaml @@ -0,0 +1,29 @@ +admm_iter: 4 +rho: 0.1 +rho_scale: 2 +num_threads: 4 +delta_option: 1 + +mu: 0.2 +mu_plate: 1 +dt: 0.1 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 3 +N: 5 +w_Q: 10 +w_R: 0 +# Penalty on all decision variables, assuming scalar +w_G: 0.1 +# Penalty on all decision variables, assuming scalar +w_U: 1 + +g_size: 40 +u_size: 40 +# State Tracking Error, assuming diagonal +#q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1] +q_vector: [200, 200, 500, 500, 500, 500, 500, 10000, 10000, 10000, + 0, 0, 0, 0, 0, 0, 1, 1, 1] +# Penalty on efforts, assuming diagonal +r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index df5a4749ba..36a82bf8f0 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -1,5 +1,12 @@ package(default_visibility = ["//visibility:public"]) +cc_library( + name = "franka_systems", + srcs = [], + deps = [":end_effector_trajectory", + ":franka_kinematics"], +) + cc_library( name = "end_effector_trajectory", srcs = ["end_effector_trajectory.cc"], @@ -12,3 +19,29 @@ cc_library( "@lcm", ], ) + +cc_library( + name = "franka_kinematics", + srcs = ["franka_kinematics.cc"], + hdrs = ["franka_kinematics.h"], + deps = [ + "//lcmtypes:lcmt_robot", + ":franka_kinematics_vector", + "//common", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_kinematics_vector", + srcs = ["franka_kinematics_vector.cc"], + hdrs = ["franka_kinematics_vector.h"], + deps = [ + "//common", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) diff --git a/examples/franka/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc similarity index 59% rename from examples/franka/franka_kinematics.cc rename to examples/franka/systems/franka_kinematics.cc index 4af99c72f4..3f3f0fc2a6 100644 --- a/examples/franka/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -1,4 +1,4 @@ -#include "examples/franka/franka_kinematics.h" +#include "examples/franka/systems/franka_kinematics.h" #include @@ -21,14 +21,16 @@ FrankaKinematics::FrankaKinematics(const MultibodyPlant& franka_plant, const MultibodyPlant& object_plant, Context* object_context, const std::string& end_effector_name, - const std::string& object_name) + const std::string& object_name, + bool include_end_effector_orientation) : franka_plant_(franka_plant), franka_context_(franka_context), object_plant_(object_plant), object_context_(object_context), world_(franka_plant_.world_frame()), end_effector_name_(end_effector_name), - object_name_(object_name){ + object_name_(object_name), + include_end_effector_orientation_(include_end_effector_orientation) { this->set_name("franka_kinematics"); franka_state_port_ = this->DeclareVectorInputPort( @@ -43,17 +45,26 @@ FrankaKinematics::FrankaKinematics(const MultibodyPlant& franka_plant, object_plant.num_velocities(), object_plant.num_actuators())) .get_index(); - + num_end_effector_positions_ = 3 + include_end_effector_orientation_ * 3; + num_object_positions_ = 7; + num_end_effector_velocities_ = 3 + include_end_effector_orientation_ * 3; + num_object_velocities_ = 6; +// int total_state_length = num_end_effector_positions_ + num_object_positions_ + +// num_end_effector_velocities_ + +// num_object_velocities_; lcs_state_port_ = - this->DeclareVectorOutputPort("lcs_state", - TimestampedVector(3 + 7 + 3 + 6), - &FrankaKinematics::ComputeLCSState) + this->DeclareVectorOutputPort( + "lcs_state", + FrankaKinematicsVector( + num_end_effector_positions_, num_object_positions_, + num_end_effector_velocities_, num_object_velocities_), + &FrankaKinematics::ComputeLCSState) .get_index(); } void FrankaKinematics::ComputeLCSState( const drake::systems::Context& context, - TimestampedVector* lcs_state) const { + FrankaKinematicsVector* lcs_state) const { const OutputVector* franka_output = (OutputVector*)this->EvalVectorInput(context, franka_state_port_); const OutputVector* object_output = @@ -74,21 +85,38 @@ void FrankaKinematics::ComputeLCSState( auto end_effector_pose = franka_plant_.EvalBodyPoseInWorld( *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); -// auto franka_base_pose = franka_plant_.EvalBodyPoseInWorld( -// *franka_context_, franka_plant_.GetBodyByName("panda_link0")); - auto object_pose = object_plant_.EvalBodyPoseInWorld( - *object_context_, object_plant_.GetBodyByName(object_name_)); - auto relative_translation = object_pose.translation(); - relative_translation(2) -= 0.7645; +// auto object_pose = object_plant_.EvalBodyPoseInWorld( +// *object_context_, object_plant_.GetBodyByName(object_name_)); auto end_effector_spatial_velocity = franka_plant_.EvalBodySpatialVelocityInWorld( *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); - VectorXd lcs_output = VectorXd::Zero(lcs_state->size() - 1); - lcs_output << end_effector_pose.translation(), q_object.head(4), relative_translation, - end_effector_spatial_velocity.translational(), v_object; + auto end_effector_rotation_rpy = + end_effector_pose.rotation().ToRollPitchYaw().vector(); + VectorXd end_effector_positions = VectorXd::Zero(num_end_effector_positions_); + VectorXd end_effector_velocities = + VectorXd::Zero(num_end_effector_velocities_); + + if (num_end_effector_positions_ > 3) { + end_effector_positions << end_effector_pose.translation(), + end_effector_rotation_rpy; + } else { + end_effector_positions << end_effector_pose.translation(); + } + if (num_end_effector_velocities_ > 3) { + end_effector_velocities << end_effector_spatial_velocity.rotational(), + end_effector_spatial_velocity.translational(); + } else { + end_effector_velocities << end_effector_spatial_velocity.translational(); + } + + VectorXd object_position = q_object; + object_position(2) -= 0.7645; + lcs_state->SetEndEffectorPositions(end_effector_positions); + lcs_state->SetObjectPositions(object_position); + lcs_state->SetEndEffectorVelocities(end_effector_velocities); + lcs_state->SetObjectVelocities(v_object); lcs_state->set_timestamp(franka_output->get_timestamp()); - lcs_state->SetDataVector(lcs_output); } } // namespace systems diff --git a/examples/franka/franka_kinematics.h b/examples/franka/systems/franka_kinematics.h similarity index 81% rename from examples/franka/franka_kinematics.h rename to examples/franka/systems/franka_kinematics.h index d90adb843d..e020e475b6 100644 --- a/examples/franka/franka_kinematics.h +++ b/examples/franka/systems/franka_kinematics.h @@ -3,6 +3,7 @@ #include #include #include +#include "examples/franka/systems/franka_kinematics_vector.h" #include "drake/systems/framework/leaf_system.h" #include "systems/framework/timestamped_vector.h" @@ -19,7 +20,8 @@ class FrankaKinematics : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& object_plant, drake::systems::Context* object_context, const std::string& end_effector_name, - const std::string& object_name); + const std::string& object_name, + bool include_end_effector_orientation); const drake::systems::InputPort& get_input_port_object_state() const { return this->get_input_port(object_state_port_); @@ -36,12 +38,17 @@ class FrankaKinematics : public drake::systems::LeafSystem { private: void ComputeLCSState( const drake::systems::Context& context, - TimestampedVector* output_traj) const; + FrankaKinematicsVector* output_traj) const; drake::systems::InputPortIndex franka_state_port_; drake::systems::InputPortIndex object_state_port_; drake::systems::OutputPortIndex lcs_state_port_; + int num_end_effector_positions_; + int num_object_positions_; + int num_end_effector_velocities_; + int num_object_velocities_; + const drake::multibody::MultibodyPlant& franka_plant_; drake::systems::Context* franka_context_; const drake::multibody::MultibodyPlant& object_plant_; @@ -49,6 +56,7 @@ class FrankaKinematics : public drake::systems::LeafSystem { const drake::multibody::Frame& world_; std::string end_effector_name_; std::string object_name_; + const bool include_end_effector_orientation_; }; } // namespace systems diff --git a/examples/franka/systems/franka_kinematics_vector.cc b/examples/franka/systems/franka_kinematics_vector.cc new file mode 100644 index 0000000000..6dce76fe09 --- /dev/null +++ b/examples/franka/systems/franka_kinematics_vector.cc @@ -0,0 +1,6 @@ +#include "examples/franka/systems/franka_kinematics_vector.h" + +#include "drake/common/default_scalars.h" + +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( + class ::dairlib::systems::FrankaKinematicsVector) diff --git a/examples/franka/systems/franka_kinematics_vector.h b/examples/franka/systems/franka_kinematics_vector.h new file mode 100644 index 0000000000..73a389a62f --- /dev/null +++ b/examples/franka/systems/franka_kinematics_vector.h @@ -0,0 +1,175 @@ +#pragma once + +#include +#include + +#include "systems/framework/timestamped_vector.h" + +namespace dairlib { +namespace systems { + +using drake::VectorX; +using std::string; +using std::vector; + +/// FrankaKinematicsVector stores the robot output as a TimestampedVector +/// * positions +/// * velocities +template +class FrankaKinematicsVector : public TimestampedVector { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(FrankaKinematicsVector) + + FrankaKinematicsVector() = default; + + /// Initializes with the given @p size using the drake::dummy_value, which + /// is NaN when T = double. + explicit FrankaKinematicsVector(int num_end_effector_positions, + int num_object_positions, + int num_end_effector_velocities, + int num_object_velocities) + : TimestampedVector(num_end_effector_positions + num_object_positions + + num_end_effector_velocities + + num_object_velocities), + num_end_effector_positions_(num_end_effector_positions), + num_object_positions_(num_object_positions), + num_end_effector_velocities_(num_end_effector_velocities), + num_object_velocities_(num_object_velocities), + end_effector_positions_start_(0), + object_positions_start_(num_end_effector_positions_), + end_effector_velocities_start_(num_end_effector_positions_ + + num_object_positions_), + object_velocities_start_(num_end_effector_positions_ + + num_object_positions_ + + num_end_effector_velocities_), + num_positions_(num_end_effector_positions_ + num_object_positions_), + num_velocities_(num_end_effector_velocities_ + num_object_velocities_) { + } + + /// Constructs a OutputVector with the specified positions and velocities. + explicit FrankaKinematicsVector(const VectorX& end_effector_positions, + const VectorX& object_positions, + const VectorX& end_effector_velocities, + const VectorX& object_velocities) + : FrankaKinematicsVector( + end_effector_positions.size(), object_positions.size(), + end_effector_velocities.size(), object_velocities.size()) { + this->SetEndEffectorPositions(end_effector_positions); + this->SetObjectPositions(object_positions); + this->SetEndEffectorVelocities(end_effector_velocities); + this->SetObjectVelocities(object_velocities); + } + + void SetEndEffectorPositions(VectorX positions) { + DRAKE_DEMAND(positions.size() == num_end_effector_positions_); + this->get_mutable_data().segment(end_effector_positions_start_, + num_end_effector_positions_) = positions; + } + + void SetObjectPositions(VectorX positions) { + DRAKE_DEMAND(positions.size() == num_object_positions_); + this->get_mutable_data().segment(object_positions_start_, + num_object_positions_) = positions; + } + + void SetEndEffectorVelocities(VectorX velocities) { + DRAKE_DEMAND(velocities.size() == num_end_effector_velocities_); + this->get_mutable_data().segment(end_effector_velocities_start_, + num_end_effector_velocities_) = velocities; + } + + void SetObjectVelocities(VectorX velocities) { + DRAKE_DEMAND(velocities.size() == num_object_velocities_); + this->get_mutable_data().segment(object_velocities_start_, + num_object_velocities_) = velocities; + } + + void SetState(VectorX state) { + DRAKE_DEMAND(state.size() == this->data_size()); + this->get_mutable_data().segment(end_effector_positions_start_, + this->data_size()) = state; + } + + /// Returns a const state vector + const VectorX GetState() const { + return this->get_data().segment(end_effector_positions_start_, + this->data_size()); + } + + /// Returns a const positions vector for the end effector + const VectorX GetEndEffectorPositions() const { + return this->get_data().segment(end_effector_positions_start_, + num_end_effector_positions_); + } + + /// Returns a const positions vector for the object + const VectorX GetObjectPositions() const { + return this->get_data().segment(object_positions_start_, + num_object_positions_); + } + + /// Returns a const positions vector for the end effector + const VectorX GetEndEffectorVelocities() const { + return this->get_data().segment(end_effector_velocities_start_, + num_end_effector_velocities_); + } + + /// Returns a const positions vector for the object + const VectorX GetObjectVelocities() const { + return this->get_data().segment(object_velocities_start_, + num_object_velocities_); + } + + /// Returns a const velocities vector + const VectorX GetVelocities() const { + return this->get_data().segment( + end_effector_velocities_start_, + num_end_effector_velocities_ + num_object_velocities_); + } + + /// Returns a const positions vector + const VectorX GetPositions() const { + return this->get_data().segment( + end_effector_positions_start_, + num_end_effector_positions_ + num_object_positions_); + } + + /// Returns a mutable positions vector + Eigen::Map> GetMutablePositions() { + auto data = this->get_mutable_data().segment( + end_effector_positions_start_, + num_end_effector_positions_ + num_object_positions_); + return Eigen::Map>(&data(0), data.size()); + } + + /// Returns a mutable velocities vector + Eigen::Map> GetMutableVelocities() { + auto data = this->get_mutable_data().segment( + end_effector_velocities_start_, + num_end_effector_velocities_ + num_object_velocities_); + return Eigen::Map>(&data(0), data.size()); + } + + /// Returns a mutable state vector + Eigen::Map> GetMutableState() { + auto data = this->get_mutable_data().segment(end_effector_positions_start_, + this->data_size()); + return Eigen::Map>(&data(0), data.size()); + } + + private: + const int num_end_effector_positions_; + const int num_object_positions_; + const int num_end_effector_velocities_; + const int num_object_velocities_; + const int end_effector_positions_start_; + const int object_positions_start_; + const int end_effector_velocities_start_; + const int object_velocities_start_; + + const int num_positions_; + const int num_velocities_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf index ad2605142e..faedfc224d 100644 --- a/examples/franka/urdf/plate_end_effector_floating.urdf +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -4,6 +4,9 @@ + + + @@ -88,6 +91,21 @@ + + + + + + + + + + + + + + + @@ -106,4 +124,19 @@ 1 + + + + 1 + + + + + 1 + + + + + 1 + diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 778accfb48..ea96a024ed 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -61,6 +61,7 @@ cc_library( ], deps = [ "//systems/framework:vector", + "//examples/franka/systems:franka_systems", "//lcmtypes:lcmt_robot", "//solvers:c3", "//common:find_resource", diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 46bd3bce19..067210b6aa 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -7,6 +7,7 @@ #include "common/find_resource.h" #include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" @@ -14,6 +15,7 @@ namespace dairlib { +using drake::multibody::ModelInstanceIndex; using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteValues; @@ -58,8 +60,12 @@ C3Controller::C3Controller( BasicVector(2 + 16)) .get_index(); lcs_state_input_port_ = - this->DeclareVectorInputPort("x_lcs", - TimestampedVector(n_q_ + n_v_)) + this->DeclareVectorInputPort( + "x_lcs", FrankaKinematicsVector( + plant_.num_positions(ModelInstanceIndex(2)), + plant_.num_positions(ModelInstanceIndex(3)), + plant_.num_velocities(ModelInstanceIndex(2)), + plant_.num_velocities(ModelInstanceIndex(3)))) .get_index(); radio_port_ = @@ -87,16 +93,19 @@ drake::systems::EventStatus C3Controller::ComputePlan( DiscreteValues* discrete_state) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); - const TimestampedVector& x = - *this->template EvalVectorInput(context, - lcs_state_input_port_); + // const TimestampedVector& x = + // *this->template EvalVectorInput(context, + // lcs_state_input_port_); + const FrankaKinematicsVector& lcs_x = + *this->template EvalVectorInput( + context, lcs_state_input_port_); discrete_state->get_mutable_value(plan_start_time_index_)[0] = - x.get_timestamp(); + lcs_x.get_timestamp(); VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); - q_v_u << x.get_data(), VectorXd::Zero(n_u_); + q_v_u << lcs_x.get_data(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); @@ -107,17 +116,17 @@ drake::systems::EventStatus C3Controller::ComputePlan( /// center of plate /// thickness of tray 0.5 * (0.02) + thickness of end effector 0.5 * (0.02) x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; -// x_des[3] = 1; -// x_des[4] = 0; -// x_des[5] = 0; -// x_des[6] = 0; + // x_des[3] = 1; + // x_des[4] = 0; + // x_des[5] = 0; + // x_des[6] = 0; x_des[3] = 0.707; x_des[4] = 0; x_des[5] = 0; x_des[6] = 0.707; /// radio command x_des[7] = 0.5; -// x_des[8] = -0.2; + // x_des[8] = -0.2; x_des[8] = 0.2; x_des[9] = 0.45; x_des(7) += radio_out->channel[0] * 0.2; @@ -126,12 +135,14 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector x_desired = std::vector(N_ + 1, x_des); -// std::cout << "plate_error: " -// << (x_des.segment(7, 3) - x.get_data().segment(7, 3)).transpose() -// << std::endl; -// std::cout << "end_effector_error: " -// << (x_des.segment(0, 3) - x.get_data().segment(0, 3)).transpose() -// << std::endl; + // std::cout << "plate_error: " + // << (x_des.segment(7, 3) - x.get_data().segment(7, + // 3)).transpose() + // << std::endl; + // std::cout << "end_effector_error: " + // << (x_des.segment(0, 3) - x.get_data().segment(0, + // 3)).transpose() + // << std::endl; int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -155,10 +166,10 @@ drake::systems::EventStatus C3Controller::ComputePlan( c3_->SetOsqpSolverOptions(solver_options_); VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); - delta_init.head(n_x_) = x.get_data(); + delta_init.head(n_x_) = lcs_x.get_data(); std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - auto z_sol = c3_->Solve(x.get_data(), delta, w); + auto z_sol = c3_->Solve(lcs_x.get_data(), delta, w); return drake::systems::EventStatus::Succeeded(); } @@ -214,7 +225,7 @@ void C3Controller::OutputObjectTrajectory( u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); } -// MatrixXd knots = x_sol.topRows(n_q_).bottomRows(3); + // MatrixXd knots = x_sol.topRows(n_q_).bottomRows(3); MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = x_sol.topRows(n_q_).bottomRows(3); knots.bottomRows(3) = x_sol.bottomRows(n_v_).bottomRows(3); diff --git a/systems/framework/timestamped_vector.h b/systems/framework/timestamped_vector.h index ef93cec31b..ef755ea909 100644 --- a/systems/framework/timestamped_vector.h +++ b/systems/framework/timestamped_vector.h @@ -5,26 +5,27 @@ namespace dairlib { namespace systems { -using drake::systems::BasicVector; using drake::VectorX; +using drake::systems::BasicVector; /// TimestampedVector wraps a BasicVector along with a timestamp field -/// The primary purpose of this is to pass-through a message (e.g. LCM) timestamp -/// Uses a length N+1 BasicVector to store a vector of length N and a timestamp -/// The timestamp is stored as the final element (Nth) +/// The primary purpose of this is to pass-through a message (e.g. LCM) +/// timestamp Uses a length N+1 BasicVector to store a vector of length N and a +/// timestamp The timestamp is stored as the final element (Nth) template -class TimestampedVector : public drake::systems::BasicVector { -public: +class TimestampedVector : public drake::systems::BasicVector { + public: DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(TimestampedVector) /// Constructs an empty TimestampedVector. TimestampedVector() = default; - /// Initializes with the given @p size using the drake::dummy_value, which /// is NaN when T = double. explicit TimestampedVector(int data_size) - : BasicVector(data_size + 1), timestep_index_(data_size) {} + : BasicVector(data_size + 1), + timestep_index_(data_size), + data_size_(data_size) {} /// Constructs a TimestampedVector with the specified @p data. explicit TimestampedVector(const VectorX& data) @@ -48,10 +49,10 @@ class TimestampedVector : public drake::systems::BasicVector { this->SetAtIndex(timestep_index_, timestamp); } - T get_timestamp() const {return this->GetAtIndex(timestep_index_);} + T get_timestamp() const { return this->GetAtIndex(timestep_index_); } - /// Copies the entire vector to a new TimestampedVector, with the same concrete - /// implementation type. + /// Copies the entire vector to a new TimestampedVector, with the same + /// concrete implementation type. /// /// Uses the Non-Virtual Interface idiom because smart pointers do not have /// type covariance. @@ -77,27 +78,29 @@ class TimestampedVector : public drake::systems::BasicVector { return this->get_value().head(timestep_index_); } - - //sets the data part of the vector (without timestamp) + // sets the data part of the vector (without timestamp) void SetDataVector(const Eigen::Ref>& value) { this->get_mutable_data() = value; } + int data_size() const { return data_size_; } + protected: /// Returns a new TimestampedVector containing a copy of the entire vector. /// Caller must take ownership, and may rely on the NVI wrapper to initialize /// the clone elementwise. /// - /// Subclasses of TimestampedVector must override DoClone to return their covariant - /// type. + /// Subclasses of TimestampedVector must override DoClone to return their + /// covariant type. /// virtual TimestampedVector* DoClone() const { return new TimestampedVector(timestep_index_); } - private: - const int timestep_index_; - }; + private: + const int timestep_index_; + const int data_size_; +}; } // namespace systems } // namespace dairlib From 42ecbc1b9fd78e1839275bde0478d598423741a4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Apr 2023 13:24:13 -0400 Subject: [PATCH 448/758] adding option to add in end effector orientation --- .../franka/franka_c3_controller_params.yaml | 10 ++--- .../franka/franka_c3_options_translation.yaml | 2 +- examples/franka/franka_controller_params.yaml | 14 +++---- examples/franka/franka_sim_params.yaml | 4 +- examples/franka/systems/franka_kinematics.cc | 7 ++-- .../franka/systems/franka_kinematics_vector.h | 7 ++++ systems/controllers/c3_controller.cc | 40 +++++++------------ 7 files changed, 41 insertions(+), 43 deletions(-) diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 72dd4cfa16..3ec4875508 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -#c3_options_file: examples/franka/franka_c3_options_translation.yaml -c3_options_file: examples/franka/franka_c3_options_floating.yaml +c3_options_file: examples/franka/franka_c3_options_translation.yaml +#c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -8,10 +8,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf #plate_model: examples/franka/urdf/plate_end_effector.urdf -#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -include_end_effector_orientation: true +include_end_effector_orientation: false diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index cf241aeffa..e09d61bd62 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -23,7 +23,7 @@ u_size: 40 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 500, 500, 500, 500, 10000, 10000, 10000, +q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 9639994557..985b6433d3 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -6,8 +6,8 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_channel: C3_TRAJECTORY_ACTOR w_input: 0.00 -w_input_reg: 1 -w_accel: 1 +w_input_reg: 0.0001 +w_accel: 0.1 w_soft_constraint: 10000 w_lambda: 0.1 impact_threshold: 0.000 @@ -25,17 +25,17 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] EndEffectorW: - [5, 0, 0, - 0, 5, 0, + [1, 0, 0, + 0, 1, 0, 0, 0, 1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, 0, 0, 200 ] EndEffectorKd: - [ 50, 0, 0, - 0, 50, 0, - 0, 0, 50 ] + [ 30, 0, 0, + 0, 30, 0, + 0, 0, 30 ] MidLinkW: [0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 663eda0cf1..74aeee8dba 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.005 visualize: true dt: 0.0001 -realtime_rate: 1.0 +realtime_rate: 0.5 q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] -q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.2] +q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] diff --git a/examples/franka/systems/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc index 3f3f0fc2a6..d917261812 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -85,8 +85,8 @@ void FrankaKinematics::ComputeLCSState( auto end_effector_pose = franka_plant_.EvalBodyPoseInWorld( *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); -// auto object_pose = object_plant_.EvalBodyPoseInWorld( -// *object_context_, object_plant_.GetBodyByName(object_name_)); + auto object_pose = object_plant_.EvalBodyPoseInWorld( + *object_context_, object_plant_.GetBodyByName(object_name_)); auto end_effector_spatial_velocity = franka_plant_.EvalBodySpatialVelocityInWorld( *franka_context_, franka_plant_.GetBodyByName(end_effector_name_)); @@ -110,7 +110,8 @@ void FrankaKinematics::ComputeLCSState( } VectorXd object_position = q_object; - object_position(2) -= 0.7645; + object_position << q_object.head(4), object_pose.translation(); + object_position.tail(1)(0) -= 0.7645; lcs_state->SetEndEffectorPositions(end_effector_positions); lcs_state->SetObjectPositions(object_position); diff --git a/examples/franka/systems/franka_kinematics_vector.h b/examples/franka/systems/franka_kinematics_vector.h index 73a389a62f..91c8ad325e 100644 --- a/examples/franka/systems/franka_kinematics_vector.h +++ b/examples/franka/systems/franka_kinematics_vector.h @@ -157,6 +157,13 @@ class FrankaKinematicsVector : public TimestampedVector { return Eigen::Map>(&data(0), data.size()); } + protected: + virtual FrankaKinematicsVector* DoClone() const { + return new FrankaKinematicsVector( + num_end_effector_positions_, num_object_positions_, + num_end_effector_velocities_, num_object_velocities_); + } + private: const int num_end_effector_positions_; const int num_object_positions_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 067210b6aa..5b53f4cece 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -84,7 +84,6 @@ C3Controller::C3Controller( &C3Controller::OutputObjectTrajectory) .get_index(); plan_start_time_index_ = DeclareDiscreteState(1); - // TODO:yangwill check to make sure C3 isn't computing twice here DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); } @@ -96,16 +95,16 @@ drake::systems::EventStatus C3Controller::ComputePlan( // const TimestampedVector& x = // *this->template EvalVectorInput(context, // lcs_state_input_port_); - const FrankaKinematicsVector& lcs_x = - *this->template EvalVectorInput( + const FrankaKinematicsVector* lcs_x = + (FrankaKinematicsVector*)this->EvalVectorInput( context, lcs_state_input_port_); discrete_state->get_mutable_value(plan_start_time_index_)[0] = - lcs_x.get_timestamp(); - + lcs_x->get_timestamp(); + std::cout << "lcs_x: " << lcs_x->get_data().transpose() << std::endl; VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); - q_v_u << lcs_x.get_data(), VectorXd::Zero(n_u_); + q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); @@ -116,18 +115,18 @@ drake::systems::EventStatus C3Controller::ComputePlan( /// center of plate /// thickness of tray 0.5 * (0.02) + thickness of end effector 0.5 * (0.02) x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; - // x_des[3] = 1; - // x_des[4] = 0; - // x_des[5] = 0; - // x_des[6] = 0; - x_des[3] = 0.707; + x_des[3] = 1; x_des[4] = 0; x_des[5] = 0; - x_des[6] = 0.707; + x_des[6] = 0; + // x_des[3] = 0.707; + // x_des[4] = 0; + // x_des[5] = 0; + // x_des[6] = 0.707; /// radio command x_des[7] = 0.5; - // x_des[8] = -0.2; - x_des[8] = 0.2; + x_des[8] = -0.2; + // x_des[8] = 0.2; x_des[9] = 0.45; x_des(7) += radio_out->channel[0] * 0.2; x_des(8) += radio_out->channel[1] * 0.2; @@ -135,15 +134,6 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector x_desired = std::vector(N_ + 1, x_des); - // std::cout << "plate_error: " - // << (x_des.segment(7, 3) - x.get_data().segment(7, - // 3)).transpose() - // << std::endl; - // std::cout << "end_effector_error: " - // << (x_des.segment(0, 3) - x.get_data().segment(0, - // 3)).transpose() - // << std::endl; - int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -166,10 +156,10 @@ drake::systems::EventStatus C3Controller::ComputePlan( c3_->SetOsqpSolverOptions(solver_options_); VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); - delta_init.head(n_x_) = lcs_x.get_data(); + delta_init.head(n_x_) = lcs_x->get_data(); std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - auto z_sol = c3_->Solve(lcs_x.get_data(), delta, w); + auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); return drake::systems::EventStatus::Succeeded(); } From 3bb181b608426d56110c2269f3eeb5bd71a233bf Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Apr 2023 15:19:19 -0400 Subject: [PATCH 449/758] trying to find the changes that stopped pure translation to work --- .../franka/franka_c3_options_floating.yaml | 10 ++++---- examples/franka/franka_controller_params.yaml | 8 +++---- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/systems/franka_kinematics.cc | 2 ++ systems/controllers/c3_controller.cc | 23 +++++++++++-------- 5 files changed, 25 insertions(+), 20 deletions(-) diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index cf241aeffa..86f20aa5b5 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -18,12 +18,12 @@ w_G: 0.1 # Penalty on all decision variables, assuming scalar w_U: 1 -g_size: 40 -u_size: 40 +g_size: 49 +u_size: 49 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 500, 500, 500, 500, 10000, 10000, 10000, - 0, 0, 0, 0, 0, 0, 1, 1, 1] +q_vector: [200, 200, 500, 200, 200, 200, 500, 500, 500, 500, 10000, 10000, 10000, + 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1] \ No newline at end of file +r_vector: [1, 1, 1, 1, 1, 1] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 985b6433d3..fbded1c1a6 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -6,7 +6,7 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_channel: C3_TRAJECTORY_ACTOR w_input: 0.00 -w_input_reg: 0.0001 +w_input_reg: 1 w_accel: 0.1 w_soft_constraint: 10000 w_lambda: 0.1 @@ -33,9 +33,9 @@ EndEffectorKp: 0, 200, 0, 0, 0, 200 ] EndEffectorKd: - [ 30, 0, 0, - 0, 30, 0, - 0, 0, 30 ] + [ 50, 0, 0, + 0, 50, 0, + 0, 0, 50 ] MidLinkW: [0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 74aeee8dba..2090056f03 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -2,7 +2,7 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT tray_state_channel: TRAY_OUTPUT franka_model: examples/franka/urdf/franka_no_collision.urdf -publish_rate: 4000 +publish_rate: 1000 publish_efforts: true actuator_delay: 0.005 visualize: true diff --git a/examples/franka/systems/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc index d917261812..3796b63313 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -97,12 +97,14 @@ void FrankaKinematics::ComputeLCSState( VectorXd::Zero(num_end_effector_velocities_); if (num_end_effector_positions_ > 3) { +// std::cout << "here: " << std::endl; end_effector_positions << end_effector_pose.translation(), end_effector_rotation_rpy; } else { end_effector_positions << end_effector_pose.translation(); } if (num_end_effector_velocities_ > 3) { +// std::cout << "here: " << std::endl; end_effector_velocities << end_effector_spatial_velocity.rotational(), end_effector_spatial_velocity.translational(); } else { diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 5b53f4cece..10e3f8f69d 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -104,33 +104,36 @@ drake::systems::EventStatus C3Controller::ComputePlan( VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); - q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); + q_v_u << lcs_x->GetState(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); /// default position - x_des[0] = 0.7; + x_des[0] = 0.5; x_des[1] = 0.02; // x_des[2] = 0.35; /// center of plate /// thickness of tray 0.5 * (0.02) + thickness of end effector 0.5 * (0.02) x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; - x_des[3] = 1; + x_des[3] = 0; x_des[4] = 0; x_des[5] = 0; - x_des[6] = 0; + x_des[6] = 1; + x_des[7] = 0; + x_des[8] = 0; + x_des[9] = 0; // x_des[3] = 0.707; // x_des[4] = 0; // x_des[5] = 0; // x_des[6] = 0.707; /// radio command - x_des[7] = 0.5; - x_des[8] = -0.2; + x_des[10] = 0.5; + x_des[11] = -0.2; // x_des[8] = 0.2; - x_des[9] = 0.45; - x_des(7) += radio_out->channel[0] * 0.2; - x_des(8) += radio_out->channel[1] * 0.2; - x_des(9) += radio_out->channel[2] * 0.2; + x_des[12] = 0.45; + x_des(10) += radio_out->channel[0] * 0.2; + x_des(11) += radio_out->channel[1] * 0.2; + x_des(12) += radio_out->channel[2] * 0.2; std::vector x_desired = std::vector(N_ + 1, x_des); From 6f18bb65040764266ad9adc885b4c622ff56dc25 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Apr 2023 16:43:57 -0400 Subject: [PATCH 450/758] working on orientatino --- examples/franka/franka_c3_controller.cc | 17 ++++++ .../franka/franka_c3_controller_params.yaml | 11 ++-- .../franka/franka_c3_options_floating.yaml | 7 ++- .../franka/franka_c3_options_translation.yaml | 5 +- examples/franka/franka_controller_params.yaml | 8 +-- examples/franka/franka_sim_params.yaml | 2 +- .../urdf/plate_end_effector_floating.urdf | 22 ++++---- solvers/c3_options.h | 12 ++++ solvers/lcs_factory.cc | 2 + systems/controllers/c3_controller.cc | 55 ++++++------------- systems/controllers/c3_controller.h | 2 +- 11 files changed, 80 insertions(+), 63 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 8d83fc28dc..349fb2829c 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -128,6 +128,15 @@ int DoMain(int argc, char* argv[]) { /// + VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + plant_plate.num_velocities()); + x_des << c3_options.q_des, c3_options.v_des; +// x_des + /// default position +// x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; +// x_des(10) += radio_out->channel[0] * 0.2; +// x_des(11) += radio_out->channel[1] * 0.2; +// x_des(12) += radio_out->channel[2] * 0.2; + DiagramBuilder builder; auto tray_state_sub = @@ -173,6 +182,8 @@ int DoMain(int argc, char* argv[]) { builder.Connect(controller->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); + + auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); @@ -183,6 +194,12 @@ int DoMain(int argc, char* argv[]) { &lcm, std::move(owned_diagram), franka_state_receiver, controller_params.state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); + auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( + *controller, + &loop.get_diagram_mutable_context()); +// loop.get_diagram_mutable_context() + controller->get_input_port_target().FixValue(&controller_context, + x_des); loop.Simulate(); return 0; } diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 3ec4875508..8a43576ba2 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -c3_options_file: examples/franka/franka_c3_options_translation.yaml -#c3_options_file: examples/franka/franka_c3_options_floating.yaml +#c3_options_file: examples/franka/franka_c3_options_translation.yaml +c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,11 +7,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -#plate_model: examples/franka/urdf/plate_end_effector.urdf -plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -include_end_effector_orientation: false +include_end_effector_orientation: true diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index 86f20aa5b5..e48705ce49 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -23,7 +23,10 @@ u_size: 49 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 200, 200, 200, 500, 500, 500, 500, 10000, 10000, 10000, +q_vector: [200, 200, 500, 10, 10, 10, 10, 10, 10, 10, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1, 1, 1, 1] \ No newline at end of file +r_vector: [1, 1, 1, 1, 1, 1] + +q_des_vector: [0.5, 0.02, 0.45, 0, 0, 0, 1, 0, 0, 0, 0.3, -0.2, 0.47] +v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index e09d61bd62..8765399419 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -26,4 +26,7 @@ u_size: 40 q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1] \ No newline at end of file +r_vector: [1, 1, 1] + +q_des_vector: [0.5, 0.02, 0.43, 1, 0, 0, 0, 0.3, -0.2, 0.45] +v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index fbded1c1a6..f68c922948 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -53,10 +53,10 @@ EndEffectorRotW: 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 2000, 0, 0, - 0, 2000, 0, + [ 2500, 0, 0, + 0, 2500, 0, 0, 0, 500 ] EndEffectorRotKd: - [ 100, 0, 0, - 0, 100, 0, + [ 150, 0, 0, + 0, 150, 0, 0, 0, 40 ] diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 2090056f03..f20197ddd1 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.005 visualize: true dt: 0.0001 -realtime_rate: 0.5 +realtime_rate: 1.0 q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf index faedfc224d..a6b568d451 100644 --- a/examples/franka/urdf/plate_end_effector_floating.urdf +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -9,19 +9,19 @@ - + + izz="0.020833"/> - + @@ -64,19 +64,19 @@ - + - + - + @@ -126,17 +126,17 @@ - + 1 - + 1 - + 1 diff --git a/solvers/c3_options.h b/solvers/c3_options.h index eeed3e48aa..4f548519a5 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -26,6 +26,9 @@ struct C3Options { std::vector q_vector; std::vector r_vector; + std::vector q_des_vector; + std::vector v_des_vector; + double mu; double mu_plate; double dt; @@ -36,6 +39,8 @@ struct C3Options { MatrixXd R; MatrixXd G; MatrixXd U; + VectorXd q_des; + VectorXd v_des; template void Serialize(Archive* a) { @@ -61,11 +66,17 @@ struct C3Options { a->Visit(DRAKE_NVP(u_size)); a->Visit(DRAKE_NVP(q_vector)); a->Visit(DRAKE_NVP(r_vector)); + a->Visit(DRAKE_NVP(q_des_vector)); + a->Visit(DRAKE_NVP(v_des_vector)); Eigen::VectorXd q = Eigen::Map( this->q_vector.data(), this->q_vector.size()); Eigen::VectorXd r = Eigen::Map( this->r_vector.data(), this->r_vector.size()); + q_des = Eigen::Map( + this->q_des_vector.data(), this->q_des_vector.size()); + v_des = Eigen::Map( + this->v_des_vector.data(), this->v_des_vector.size()); Q = w_Q * q.asDiagonal(); R = w_R * r.asDiagonal(); @@ -73,5 +84,6 @@ struct C3Options { U = w_U * MatrixXd::Identity(u_size, u_size); U.block(0, 0, 19, 19) = 100 * MatrixXd::Identity(19, 19); + } }; \ No newline at end of file diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 9443afb5ad..cc555e4502 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -124,6 +124,8 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd M_double = MatrixXd::Zero(n_v, n_v); plant.CalcMassMatrix(context, &M_double); +// std::cout << "AB_v_u: " << AB_v_u << std::endl; + A.block(0, 0, n_q, n_q) = MatrixXd::Identity(n_q, n_q) + dt * dt * Nq * AB_v_q; A.block(0, n_q, n_q, n_v) = dt * Nq + dt * dt * Nq * AB_v_v; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 10e3f8f69d..40b3e40a17 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -56,9 +56,7 @@ C3Controller::C3Controller( 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; n_u_ = plant_.num_actuators(); Q_.back() = 100 * c3_options_.Q; - target_input_port_ = this->DeclareVectorInputPort("desired_position", - BasicVector(2 + 16)) - .get_index(); + lcs_state_input_port_ = this->DeclareVectorInputPort( "x_lcs", FrankaKinematicsVector( @@ -67,7 +65,12 @@ C3Controller::C3Controller( plant_.num_velocities(ModelInstanceIndex(2)), plant_.num_velocities(ModelInstanceIndex(3)))) .get_index(); - + int x_des_size = plant_.num_positions(ModelInstanceIndex(2)) + + plant_.num_positions(ModelInstanceIndex(3)) + + plant_.num_velocities(ModelInstanceIndex(2)) + + plant_.num_velocities(ModelInstanceIndex(3)); + target_input_port_ = + this->DeclareVectorInputPort("desired_position", x_des_size).get_index(); radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) @@ -92,50 +95,28 @@ drake::systems::EventStatus C3Controller::ComputePlan( DiscreteValues* discrete_state) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); - // const TimestampedVector& x = - // *this->template EvalVectorInput(context, - // lcs_state_input_port_); + const BasicVector& x_des = + *this->template EvalVectorInput(context, target_input_port_); const FrankaKinematicsVector* lcs_x = (FrankaKinematicsVector*)this->EvalVectorInput( context, lcs_state_input_port_); discrete_state->get_mutable_value(plan_start_time_index_)[0] = lcs_x->get_timestamp(); - std::cout << "lcs_x: " << lcs_x->get_data().transpose() << std::endl; VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); q_v_u << lcs_x->GetState(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); - VectorXd x_des = VectorXd::Zero(n_q_ + n_v_); - /// default position - x_des[0] = 0.5; - x_des[1] = 0.02; - // x_des[2] = 0.35; - /// center of plate - /// thickness of tray 0.5 * (0.02) + thickness of end effector 0.5 * (0.02) - x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; - x_des[3] = 0; - x_des[4] = 0; - x_des[5] = 0; - x_des[6] = 1; - x_des[7] = 0; - x_des[8] = 0; - x_des[9] = 0; - // x_des[3] = 0.707; - // x_des[4] = 0; - // x_des[5] = 0; - // x_des[6] = 0.707; - /// radio command - x_des[10] = 0.5; - x_des[11] = -0.2; - // x_des[8] = 0.2; - x_des[12] = 0.45; - x_des(10) += radio_out->channel[0] * 0.2; - x_des(11) += radio_out->channel[1] * 0.2; - x_des(12) += radio_out->channel[2] * 0.2; - - std::vector x_desired = std::vector(N_ + 1, x_des); + VectorXd x_des_adjusted = x_des.value(); + VectorXd current = x_des_adjusted.head(n_q_).tail(3); + current(0) += radio_out->channel[0] * 0.2; + current(1) += radio_out->channel[1] * 0.2; + current(2) += radio_out->channel[2] * 0.2; + x_des_adjusted.head(n_q_).tail(3) = current; +// std::cout << x_des_adjusted.transpose() << std::endl; + + std::vector x_desired = std::vector(N_ + 1, x_des_adjusted); int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index b8996e92bc..669417818a 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -33,7 +33,7 @@ class C3Controller : public drake::systems::LeafSystem { contact_geoms, C3Options c3_options); - const drake::systems::InputPort& get_input_port_trajectory() const { + const drake::systems::InputPort& get_input_port_target() const { return this->get_input_port(target_input_port_); } From 74eec32bd73a3470a54f91a04938f6f18b8a58bc Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 11 Apr 2023 11:59:52 -0400 Subject: [PATCH 451/758] cranking up gains --- .../franka/franka_c3_controller_params.yaml | 10 ++++---- .../franka/franka_c3_options_floating.yaml | 6 ++--- .../franka/franka_c3_options_translation.yaml | 4 ++-- examples/franka/franka_controller_params.yaml | 24 +++++++++---------- examples/franka/franka_sim_params.yaml | 4 ++-- .../urdf/plate_end_effector_floating.urdf | 6 ++--- examples/franka/urdf/tray.sdf | 4 ++-- systems/controllers/c3_controller.cc | 6 ++--- 8 files changed, 32 insertions(+), 32 deletions(-) diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 8a43576ba2..94cf6f8803 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -#c3_options_file: examples/franka/franka_c3_options_translation.yaml -c3_options_file: examples/franka/franka_c3_options_floating.yaml +c3_options_file: examples/franka/franka_c3_options_translation.yaml +#c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,10 +7,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -include_end_effector_orientation: true +include_end_effector_orientation: false diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index e48705ce49..1497c5c568 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.2 +mu: 0.4 mu_plate: 1 dt: 0.1 solve_dt: 0.05 @@ -23,10 +23,10 @@ u_size: 49 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 10, 10, 10, 10, 10, 10, 10, 10000, 10000, 10000, +q_vector: [200, 200, 500, 10, 10, 10, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 1, 1, 1] -q_des_vector: [0.5, 0.02, 0.45, 0, 0, 0, 1, 0, 0, 0, 0.3, -0.2, 0.47] +q_des_vector: [0.5, 0.02, 0.45, 0, 0, 0, 1, 0, 0, 0, 0.3, -0.2, 0.43] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 8765399419..ba6c3dcced 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.2 +mu: 0.4 mu_plate: 1 dt: 0.1 solve_dt: 0.05 @@ -28,5 +28,5 @@ q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.5, 0.02, 0.43, 1, 0, 0, 0, 0.3, -0.2, 0.45] +q_des_vector: [0.5, 0.02, 0.43, 1, 0, 0, 0, 0.5, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index f68c922948..f99db24c2b 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -6,8 +6,8 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_channel: C3_TRAJECTORY_ACTOR w_input: 0.00 -w_input_reg: 1 -w_accel: 0.1 +w_input_reg: 001 +w_accel: 0.001 w_soft_constraint: 10000 w_lambda: 0.1 impact_threshold: 0.000 @@ -29,13 +29,13 @@ EndEffectorW: 0, 1, 0, 0, 0, 1] EndEffectorKp: - [ 200, 0, 0, - 0, 200, 0, - 0, 0, 200 ] + [ 1000, 0, 0, + 0, 1000, 0, + 0, 0, 1000 ] EndEffectorKd: - [ 50, 0, 0, - 0, 50, 0, - 0, 0, 50 ] + [ 300, 0, 0, + 0, 300, 0, + 0, 0, 300 ] MidLinkW: [0, 0, 0, 0, 0, 0, @@ -53,10 +53,10 @@ EndEffectorRotW: 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 2500, 0, 0, - 0, 2500, 0, + [ 4000, 0, 0, + 0, 4000, 0, 0, 0, 500 ] EndEffectorRotKd: - [ 150, 0, 0, - 0, 150, 0, + [ 200, 0, 0, + 0, 200, 0, 0, 0, 40 ] diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index f20197ddd1..9649bbc030 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -9,5 +9,5 @@ visualize: true dt: 0.0001 realtime_rate: 1.0 -q_init_franka: [-0.8, 1.4, 1.2, -1.4, 1.8, 1.2, -0.55] -q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.15] +q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] +q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf index a6b568d451..85a283dfb4 100644 --- a/examples/franka/urdf/plate_end_effector_floating.urdf +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -64,19 +64,19 @@ - + - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 43f99f8067..6afa9a0084 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -42,8 +42,8 @@ - 0.2 - 0.2 + 0.4 + 0.4 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 40b3e40a17..9b0bc27e0d 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -110,9 +110,9 @@ drake::systems::EventStatus C3Controller::ComputePlan( VectorXd x_des_adjusted = x_des.value(); VectorXd current = x_des_adjusted.head(n_q_).tail(3); - current(0) += radio_out->channel[0] * 0.2; - current(1) += radio_out->channel[1] * 0.2; - current(2) += radio_out->channel[2] * 0.2; + current(0) += radio_out->channel[0] * 0.4; + current(1) += radio_out->channel[1] * 0.4; + current(2) += radio_out->channel[2] * 0.4; x_des_adjusted.head(n_q_).tail(3) = current; // std::cout << x_des_adjusted.transpose() << std::endl; From 94e71b30a191c224696033fd326fb9cc2252f96b Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 11 Apr 2023 16:43:34 -0400 Subject: [PATCH 452/758] adding orientation to end effector --- .../franka/franka_c3_controller_params.yaml | 2 +- examples/franka/franka_controller_params.h | 6 +- examples/franka/franka_controller_params.yaml | 5 +- examples/franka/franka_osc_controller.cc | 32 +++++++++-- examples/franka/franka_visualizer.cc | 2 +- solvers/c3.cc | 4 +- solvers/c3.h | 4 +- systems/controllers/c3_controller.cc | 10 +++- systems/trajectory_optimization/BUILD.bazel | 1 + .../lcm_trajectory_systems.cc | 55 ++++++++++++++++++- .../lcm_trajectory_systems.h | 37 +++++++++++-- 11 files changed, 132 insertions(+), 26 deletions(-) diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 94cf6f8803..4ff7970c65 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,6 +1,6 @@ c3_options_file: examples/franka/franka_c3_options_translation.yaml #c3_options_file: examples/franka/franka_c3_options_floating.yaml -c3_channel_actor: C3_TRAJECTORY_ACTOR +c3_channel_actor: C3_TRAJECTORY_ACTOR_POSITION c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT radio_channel: CASSIE_VIRTUAL_RADIO diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index ba016ac43f..6d521a2b3d 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -12,7 +12,8 @@ struct FrankaControllerParams : OSCGains { std::string controller_channel; std::string radio_channel; std::string osc_debug_channel; - std::string c3_channel; + std::string c3_position_channel; + std::string c3_orientation_channel; double end_effector_acceleration; @@ -44,7 +45,8 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(radio_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); - a->Visit(DRAKE_NVP(c3_channel)); + a->Visit(DRAKE_NVP(c3_position_channel)); + a->Visit(DRAKE_NVP(c3_orientation_channel)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index f99db24c2b..bfe06a54de 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -3,10 +3,11 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT radio_channel: CASSIE_VIRTUAL_RADIO osc_debug_channel: OSC_DEBUG_FRANKA -c3_channel: C3_TRAJECTORY_ACTOR +c3_position_channel: C3_TRAJECTORY_ACTOR_POSITION +c3_orientation_channel: C3_TRAJECTORY_ACTOR_ORIENTATION w_input: 0.00 -w_input_reg: 001 +w_input_reg: 0.001 w_accel: 0.001 w_soft_constraint: 10000 w_lambda: 0.1 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index e28e765249..f7241de67f 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -99,12 +99,27 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); +// auto lcm_traj = +// LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); +// auto orientation_traj = LcmTrajectory::Trajectory(); +// orientation_traj.datapoints = MatrixXd::Zero(4, 2); +// orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); +// orientation_traj.traj_name = "end_effector_orientation_target"; +// orientation_traj.datatypes = std::vector(2, "orientation"); +// lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); +// lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); + auto state_receiver = builder.AddSystem(plant); - auto trajectory_sub = builder.AddSystem( + auto end_effector_trajectory_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + controller_params.c3_position_channel, &lcm)); + auto end_effector_orientation_trajectory_sub = builder.AddSystem( LcmSubscriberSystem::Make( - controller_params.c3_channel, &lcm)); - auto trajectory_receiver = + controller_params.c3_orientation_channel, &lcm)); + auto end_effector_receiver = builder.AddSystem("end_effector_traj"); + auto end_effector_orientation_receiver = + builder.AddSystem("end_effector_orientation_target"); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( controller_params.controller_channel, &lcm, @@ -171,6 +186,7 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), wrist_down_target); +// osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), orientation_target); @@ -192,12 +208,16 @@ int DoMain(int argc, char* argv[]) { osc_debug_pub->get_input_port()); builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); - builder.Connect(trajectory_sub->get_output_port(), - trajectory_receiver->get_input_port_trajectory()); - builder.Connect(trajectory_receiver->get_output_port(0), + builder.Connect(end_effector_trajectory_sub->get_output_port(), + end_effector_receiver->get_input_port_trajectory()); + builder.Connect(end_effector_orientation_trajectory_sub->get_output_port(), + end_effector_orientation_receiver->get_input_port_trajectory()); + builder.Connect(end_effector_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); builder.Connect(end_effector_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); +// builder.Connect(end_effector_orientation_receiver->get_output_port(0), +// osc->get_input_port_tracking_data("end_effector_orientation_target")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); // Run lcm-driven simulation diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index bf234798d2..73034ac6d7 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -131,7 +131,7 @@ int do_main(int argc, char* argv[]) { auto trajectory_sub_actor = builder.AddSystem( LcmSubscriberSystem::Make( - "C3_TRAJECTORY_ACTOR", lcm)); + "C3_TRAJECTORY_ACTOR_POSITION", lcm)); auto trajectory_sub_object = builder.AddSystem( LcmSubscriberSystem::Make( "C3_TRAJECTORY_TRAY", lcm)); diff --git a/solvers/c3.cc b/solvers/c3.cc index 5f9242c65f..fed7673d42 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -259,8 +259,8 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, return *z_sol_; } -void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double& Lowerbound, - double& Upperbound, int& constraint) { +void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double Lowerbound, + double Upperbound, int constraint) { if (constraint == 1) { for (int i = 1; i < N_; i++) { user_constraints_.push_back( diff --git a/solvers/c3.h b/solvers/c3.h index 544f1add47..01014df7a3 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -66,8 +66,8 @@ class C3 { /// allow users to add constraints (adds for all timesteps) /// @param A, Lowerbound, Upperbound Lowerbound <= A^T x <= Upperbound /// @param constraint inputconstraint, stateconstraint, forceconstraint - void AddLinearConstraint(Eigen::RowVectorXd& A, double& Lowerbound, - double& Upperbound, int& constraint); + void AddLinearConstraint(Eigen::RowVectorXd& A, double Lowerbound, + double Upperbound, int constraint); /// allow user to remove all constraints void RemoveConstraints(); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 9b0bc27e0d..360e117565 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -114,9 +114,10 @@ drake::systems::EventStatus C3Controller::ComputePlan( current(1) += radio_out->channel[1] * 0.4; current(2) += radio_out->channel[2] * 0.4; x_des_adjusted.head(n_q_).tail(3) = current; -// std::cout << x_des_adjusted.transpose() << std::endl; + // std::cout << x_des_adjusted.transpose() << std::endl; - std::vector x_desired = std::vector(N_ + 1, x_des_adjusted); + std::vector x_desired = + std::vector(N_ + 1, x_des_adjusted); int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -143,6 +144,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( delta_init.head(n_x_) = lcs_x->get_data(); std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); + for (int i : vector({0, 2})){ + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, 0.25, 0.75, 1); + } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/trajectory_optimization/BUILD.bazel b/systems/trajectory_optimization/BUILD.bazel index b342668af5..376590af27 100644 --- a/systems/trajectory_optimization/BUILD.bazel +++ b/systems/trajectory_optimization/BUILD.bazel @@ -56,6 +56,7 @@ cc_library( deps = [ "//lcm:lcm_trajectory_saver", "//common:find_resource", + "//common:eigen_utils", "@drake//:drake_shared_library", ], ) diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 715680db9d..3858648217 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -2,6 +2,7 @@ #include +#include "common/eigen_utils.h" #include "common/find_resource.h" #include "dairlib/lcmt_timestamped_saved_traj.hpp" @@ -14,6 +15,7 @@ using drake::geometry::Rgba; using drake::systems::Context; using drake::systems::DiscreteValues; using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::PiecewiseQuaternionSlerp; using drake::trajectories::Trajectory; using Eigen::MatrixXd; using Eigen::VectorXd; @@ -33,7 +35,8 @@ LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) this->DeclareAbstractOutputPort(trajectory_name_, traj_inst, &LcmTrajectoryReceiver::OutputTrajectory) .get_index(); - lcm_traj_ = LcmTrajectory(dairlib::FindResourceOrThrow(nominal_stand_path_)); + lcm_traj_ = + LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); } void LcmTrajectoryReceiver::OutputTrajectory( @@ -61,6 +64,52 @@ void LcmTrajectoryReceiver::OutputTrajectory( } } +LcmOrientationTrajectoryReceiver::LcmOrientationTrajectoryReceiver( + std::string trajectory_name) + : trajectory_name_(std::move(trajectory_name)) { + trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj", + drake::Value{}) + .get_index(); + + PiecewiseQuaternionSlerp empty_slerp_traj; + Trajectory& traj_inst = empty_slerp_traj; + this->set_name(trajectory_name_); + trajectory_output_port_ = + this->DeclareAbstractOutputPort( + trajectory_name_, traj_inst, + &LcmOrientationTrajectoryReceiver::OutputTrajectory) + .get_index(); + lcm_traj_ = + LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); +} + +void LcmOrientationTrajectoryReceiver::OutputTrajectory( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + if (this->EvalInputValue( + context, trajectory_input_port_) + ->utime > 1e-3) { + const auto& lcm_traj = + this->EvalInputValue( + context, trajectory_input_port_); + lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); + } + const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); + auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< + PiecewiseQuaternionSlerp*>(traj); + std::vector> quaternion_datapoints; + for (int i = 0; i < trajectory_block.datapoints.cols(); ++i) { + quaternion_datapoints.push_back( + drake::math::RollPitchYaw(trajectory_block.datapoints.col(i)) + .ToQuaternion()); + } + *casted_traj = PiecewiseQuaternionSlerp( + CopyVectorXdToStdVector(trajectory_block.time_vector), + quaternion_datapoints); +} + LcmTrajectoryDrawer::LcmTrajectoryDrawer( const std::shared_ptr& meshcat, std::string trajectory_name, const std::string& default_trajectory_path) @@ -95,8 +144,8 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( VectorXd breaks = VectorXd::LinSpaced(N_, trajectory_block.time_vector[0], trajectory_block.time_vector.tail(1)[0]); -// std::cout << "rows: " << trajectory_block.datapoints.rows() << std::endl; -// std::cout << "cols: " << trajectory_block.datapoints.cols() << std::endl; + // std::cout << "rows: " << trajectory_block.datapoints.rows() << std::endl; + // std::cout << "cols: " << trajectory_block.datapoints.cols() << std::endl; if (trajectory_block.datapoints.rows() == 3) { auto trajectory = PiecewisePolynomial::FirstOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 6e254fad05..867ac626f0 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -9,6 +9,7 @@ #include "lcm/lcm_trajectory.h" #include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/common/trajectories/piecewise_quaternion.h" #include "drake/systems/framework/leaf_system.h" namespace dairlib { @@ -31,15 +32,43 @@ class LcmTrajectoryReceiver : public drake::systems::LeafSystem { private: void OutputTrajectory(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; + drake::systems::InputPortIndex trajectory_input_port_; drake::systems::OutputPortIndex trajectory_output_port_; const std::string trajectory_name_; mutable LcmTrajectory lcm_traj_; - std::string nominal_stand_path_ = + std::string default_trajectory_path_ = "examples/franka/saved_trajectories/default_end_effector_pose"; }; +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and outputs it as a drake PiecewisePolynomial. +class LcmOrientationTrajectoryReceiver + : public drake::systems::LeafSystem { + public: + explicit LcmOrientationTrajectoryReceiver(std::string trajectory_name); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_input_port_); + } + + const drake::systems::OutputPort& get_output_port_trajectory() const { + return this->get_output_port(trajectory_output_port_); + } + + private: + void OutputTrajectory(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + drake::systems::InputPortIndex trajectory_input_port_; + drake::systems::OutputPortIndex trajectory_output_port_; + const std::string trajectory_name_; + + mutable LcmTrajectory lcm_traj_; + std::string default_trajectory_path_ = + "examples/franka/saved_trajectories/franka_defaults"; +}; + /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, /// and draws it through meshcat. class LcmTrajectoryDrawer : public drake::systems::LeafSystem { @@ -54,11 +83,9 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { return this->get_input_port(trajectory_input_port_); } - void SetLineColor(drake::geometry::Rgba rgba){ - rgba_ = rgba; - } + void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } - void SetNumSamples(int N){ + void SetNumSamples(int N) { DRAKE_DEMAND(N > 1); N_ = N; } From d286e354f9d6c7384f226982571d85fb55bcc78f Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 13 Apr 2023 12:35:23 -0400 Subject: [PATCH 453/758] adding meshcat visualizer to five link biped --- .../five_link_biped.urdf | 12 ++++++++---- .../five_link_biped_visualizer.cc | 17 +++++++++++++++++ .../joint_space_walking_gains.yaml | 2 +- 3 files changed, 26 insertions(+), 5 deletions(-) diff --git a/examples/impact_invariant_control/five_link_biped.urdf b/examples/impact_invariant_control/five_link_biped.urdf index e3260cc997..2ec29d6a6d 100644 --- a/examples/impact_invariant_control/five_link_biped.urdf +++ b/examples/impact_invariant_control/five_link_biped.urdf @@ -2,7 +2,7 @@ - + @@ -10,13 +10,17 @@ - + + + + + @@ -29,7 +33,7 @@ - + @@ -38,7 +42,7 @@ - + diff --git a/examples/impact_invariant_control/five_link_biped_visualizer.cc b/examples/impact_invariant_control/five_link_biped_visualizer.cc index 805f265706..9e9914005f 100644 --- a/examples/impact_invariant_control/five_link_biped_visualizer.cc +++ b/examples/impact_invariant_control/five_link_biped_visualizer.cc @@ -14,6 +14,8 @@ #include "drake/systems/lcm/lcm_interface_system.h" #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/rendering/multibody_position_to_geometry_pose.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" namespace dairlib { @@ -118,6 +120,21 @@ int do_main(int argc, char* argv[]) { ball_to_pose->get_output_port(), scene_graph->get_source_pose_port(ball_plant->get_source_id().value())); } + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0 / 60.0; + auto meshcat = std::make_shared(); + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, *scene_graph, meshcat, std::move(params)); + + auto ortho_camera = drake::geometry::Meshcat::OrthographicCamera(); + ortho_camera.top = 2; + ortho_camera.bottom = -0.1; + ortho_camera.left = -1; + ortho_camera.right = 4; + ortho_camera.near = 0; + ortho_camera.far = 500; + ortho_camera.zoom = 1; + meshcat->SetCamera(ortho_camera); DrakeVisualizer::AddToBuilder(&builder, *scene_graph); diff --git a/examples/impact_invariant_control/joint_space_walking_gains.yaml b/examples/impact_invariant_control/joint_space_walking_gains.yaml index 2bff46d1f6..eb2fe28632 100644 --- a/examples/impact_invariant_control/joint_space_walking_gains.yaml +++ b/examples/impact_invariant_control/joint_space_walking_gains.yaml @@ -2,7 +2,7 @@ w_input: 0 w_accel: 0.0 w_soft_constraint: 1000000 -impact_threshold: 0.025 +impact_threshold: 0.000 mu: 0.4 From d6ddeb6cae41efa07350536b28e87603e77362c6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 13 Apr 2023 12:48:05 -0400 Subject: [PATCH 454/758] using lcs version of tray instead of end effector per alp suggestion --- .../franka/franka_c3_controller_params.yaml | 2 +- examples/franka/urdf/franka.urdf | 36 ++++---- .../urdf/plate_end_effector_translation.urdf | 82 +++++++++++-------- examples/franka/urdf/tray_lcs.sdf | 51 ++++++++++++ 4 files changed, 117 insertions(+), 54 deletions(-) create mode 100644 examples/franka/urdf/tray_lcs.sdf diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 4ff7970c65..47b2db9d86 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -9,7 +9,7 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf -tray_model: examples/franka/urdf/tray.sdf +tray_model: examples/franka/urdf/tray_lcs.sdf include_end_effector_orientation: false diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index d355f910ae..0601b1c99a 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -538,24 +538,24 @@ - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index ad2605142e..5cff001572 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -18,27 +18,39 @@ - + - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + - + - + + + + + + + @@ -57,24 +69,24 @@ - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/tray_lcs.sdf b/examples/franka/urdf/tray_lcs.sdf new file mode 100644 index 0000000000..4f5e0febd2 --- /dev/null +++ b/examples/franka/urdf/tray_lcs.sdf @@ -0,0 +1,51 @@ + + + + + + 2 + + + 0.06 + 0 + 0 + 0.015 + 0 + 0.075 + + + + + + 0.3 0.6 0.02 + + + + + + + 0.001 + + + -0.15 0 0 0 0 0 + + + + + 0.001 + + + 0.15 -0.3 0 0 0 0 + + + + + 0.001 + + + 0.15 0.3 0 0 0 0 + + + + \ No newline at end of file From 1e50799bff45c671e0300d0631413fd43bf852c7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 13 Apr 2023 13:51:40 -0400 Subject: [PATCH 455/758] added orientation --- examples/franka/franka_c3_controller.cc | 24 ++++++------- .../franka/franka_c3_controller_params.yaml | 12 +++---- examples/franka/franka_controller_params.h | 6 ++-- examples/franka/franka_controller_params.yaml | 3 +- examples/franka/franka_osc_controller.cc | 35 +++++++++---------- examples/franka/urdf/franka.urdf | 4 +-- examples/franka/urdf/franka_no_collision.urdf | 4 +-- .../urdf/plate_end_effector_translation.urdf | 4 +-- systems/controllers/c3_controller.cc | 19 +++++++++- systems/controllers/c3_controller.h | 7 ++++ 10 files changed, 68 insertions(+), 50 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 349fb2829c..4ad21cc81b 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -128,14 +128,15 @@ int DoMain(int argc, char* argv[]) { /// - VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + plant_plate.num_velocities()); + VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + + plant_plate.num_velocities()); x_des << c3_options.q_des, c3_options.v_des; -// x_des + // x_des /// default position -// x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; -// x_des(10) += radio_out->channel[0] * 0.2; -// x_des(11) += radio_out->channel[1] * 0.2; -// x_des(12) += radio_out->channel[2] * 0.2; + // x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; + // x_des(10) += radio_out->channel[0] * 0.2; + // x_des(11) += radio_out->channel[1] * 0.2; + // x_des(12) += radio_out->channel[2] * 0.2; DiagramBuilder builder; @@ -182,7 +183,8 @@ int DoMain(int argc, char* argv[]) { builder.Connect(controller->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); - + controller->SetPublishEndEffectorOrientation( + controller_params.include_end_effector_orientation); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); @@ -195,11 +197,9 @@ int DoMain(int argc, char* argv[]) { controller_params.state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( - *controller, - &loop.get_diagram_mutable_context()); -// loop.get_diagram_mutable_context() - controller->get_input_port_target().FixValue(&controller_context, - x_des); + *controller, &loop.get_diagram_mutable_context()); + // loop.get_diagram_mutable_context() + controller->get_input_port_target().FixValue(&controller_context, x_des); loop.Simulate(); return 0; } diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 47b2db9d86..eb18b7961d 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,16 +1,16 @@ -c3_options_file: examples/franka/franka_c3_options_translation.yaml -#c3_options_file: examples/franka/franka_c3_options_floating.yaml -c3_channel_actor: C3_TRAJECTORY_ACTOR_POSITION +#c3_options_file: examples/franka/franka_c3_options_translation.yaml +c3_options_file: examples/franka/franka_c3_options_floating.yaml +c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray_lcs.sdf -include_end_effector_orientation: false +include_end_effector_orientation: true diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index 6d521a2b3d..ba016ac43f 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -12,8 +12,7 @@ struct FrankaControllerParams : OSCGains { std::string controller_channel; std::string radio_channel; std::string osc_debug_channel; - std::string c3_position_channel; - std::string c3_orientation_channel; + std::string c3_channel; double end_effector_acceleration; @@ -45,8 +44,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(radio_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); - a->Visit(DRAKE_NVP(c3_position_channel)); - a->Visit(DRAKE_NVP(c3_orientation_channel)); + a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index bfe06a54de..8e648fbe45 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -3,8 +3,7 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT radio_channel: CASSIE_VIRTUAL_RADIO osc_debug_channel: OSC_DEBUG_FRANKA -c3_position_channel: C3_TRAJECTORY_ACTOR_POSITION -c3_orientation_channel: C3_TRAJECTORY_ACTOR_ORIENTATION +c3_channel: C3_TRAJECTORY_ACTOR w_input: 0.00 w_input_reg: 0.001 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index f7241de67f..30d57c86b1 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -99,23 +99,20 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); -// auto lcm_traj = -// LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); -// auto orientation_traj = LcmTrajectory::Trajectory(); -// orientation_traj.datapoints = MatrixXd::Zero(4, 2); -// orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); -// orientation_traj.traj_name = "end_effector_orientation_target"; -// orientation_traj.datatypes = std::vector(2, "orientation"); -// lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); -// lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); + auto lcm_traj = + LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); + auto orientation_traj = LcmTrajectory::Trajectory(); + orientation_traj.datapoints = MatrixXd::Zero(4, 2); + orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); + orientation_traj.traj_name = "end_effector_orientation_target"; + orientation_traj.datatypes = std::vector(2, "orientation"); + lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); + lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( LcmSubscriberSystem::Make( - controller_params.c3_position_channel, &lcm)); - auto end_effector_orientation_trajectory_sub = builder.AddSystem( - LcmSubscriberSystem::Make( - controller_params.c3_orientation_channel, &lcm)); + controller_params.c3_channel, &lcm)); auto end_effector_receiver = builder.AddSystem("end_effector_traj"); auto end_effector_orientation_receiver = @@ -186,9 +183,9 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), wrist_down_target); -// osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); - osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), - orientation_target); + osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); +// osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), +// orientation_target); osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); @@ -210,14 +207,14 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(end_effector_trajectory_sub->get_output_port(), end_effector_receiver->get_input_port_trajectory()); - builder.Connect(end_effector_orientation_trajectory_sub->get_output_port(), + builder.Connect(end_effector_trajectory_sub->get_output_port(), end_effector_orientation_receiver->get_input_port_trajectory()); builder.Connect(end_effector_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); builder.Connect(end_effector_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); -// builder.Connect(end_effector_orientation_receiver->get_output_port(0), -// osc->get_input_port_tracking_data("end_effector_orientation_target")); + builder.Connect(end_effector_orientation_receiver->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); // Run lcm-driven simulation diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index 0601b1c99a..b215cfac27 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -523,7 +523,7 @@ - + @@ -535,7 +535,7 @@ - + diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index f87d49377a..1dc88eafb6 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -197,7 +197,7 @@ - + @@ -209,7 +209,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 5cff001572..632933b060 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -18,7 +18,7 @@ - + @@ -42,7 +42,7 @@ - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 360e117565..427be46360 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -144,7 +144,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( delta_init.head(n_x_) = lcs_x->get_data(); std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - for (int i : vector({0, 2})){ + for (int i : vector({0, 2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; c3_->AddLinearConstraint(A, 0.25, 0.75, 1); @@ -182,6 +182,23 @@ void C3Controller::OutputActorTrajectory( end_effector_traj.time_vector = breaks; LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_traj"}, "end_effector_traj", "end_effector_traj", false); + + if (publish_end_effector_orientation_) { + LcmTrajectory::Trajectory end_effector_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(6, N_); + orientation_samples.topRows(3) = x_sol.topRows(6).bottomRows(3); + orientation_samples.bottomRows(3) = + x_sol.bottomRows(n_v_).topRows(6).bottomRows(3); + end_effector_orientation_traj.traj_name = "end_effector_orientation_target"; + end_effector_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + end_effector_orientation_traj.datapoints = orientation_samples; + end_effector_orientation_traj.time_vector = breaks; + lcm_traj.AddTrajectory(end_effector_orientation_traj.traj_name, + std::move(end_effector_orientation_traj)); + } + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); output_traj->utime = t * 1e6; } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 669417818a..fc61778849 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -58,6 +58,10 @@ class C3Controller : public drake::systems::LeafSystem { solver_options_ = options; } + void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { + publish_end_effector_orientation_ = publish_end_effector_orientation; + } + private: void OutputActorTrajectory( const drake::systems::Context& context, @@ -89,6 +93,9 @@ class C3Controller : public drake::systems::LeafSystem { FindResourceOrThrow("solvers/osqp_options_default.yaml")) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + // + bool publish_end_effector_orientation_ = false; + // convenience for variable sizes int n_q_; int n_v_; From 2c54cf1a1d28dae2fba778ef5a1771b83cea19aa Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 13 Apr 2023 16:48:15 -0400 Subject: [PATCH 456/758] need to implement switch for tracking end effector orientation as well --- examples/franka/franka_c3_controller.cc | 4 +-- .../franka/franka_c3_controller_params.yaml | 10 +++---- examples/franka/franka_controller_params.h | 2 ++ examples/franka/franka_controller_params.yaml | 1 + examples/franka/franka_osc_controller.cc | 26 +++++++++++++------ examples/franka/franka_sim_params.yaml | 2 +- examples/franka/franka_visualizer.cc | 2 +- .../urdf/plate_end_effector_translation.urdf | 18 ------------- solvers/lcs_factory.cc | 2 ++ 9 files changed, 32 insertions(+), 35 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 4ad21cc81b..4d0e7581ea 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -122,8 +122,8 @@ int DoMain(int argc, char* argv[]) { contact_geoms["TRAY"] = tray_geoms; std::vector> contact_pairs; - for (auto geom_id : contact_geoms["PLATE"]) { - contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); + for (auto geom_id : contact_geoms["TRAY"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["PLATE"][0]); } /// diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index eb18b7961d..8b75dc5920 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -#c3_options_file: examples/franka/franka_c3_options_translation.yaml -c3_options_file: examples/franka/franka_c3_options_floating.yaml +c3_options_file: examples/franka/franka_c3_options_translation.yaml +#c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,10 +7,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray_lcs.sdf -include_end_effector_orientation: true +include_end_effector_orientation: false diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index ba016ac43f..489288c62d 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -15,6 +15,7 @@ struct FrankaControllerParams : OSCGains { std::string c3_channel; double end_effector_acceleration; + bool track_end_effector_orientation; std::vector EndEffectorW; std::vector EndEffectorKp; @@ -46,6 +47,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(end_effector_acceleration)); + a->Visit(DRAKE_NVP(track_end_effector_orientation)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 8e648fbe45..db0cb3fb8d 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -14,6 +14,7 @@ impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 10.0 +track_end_effector_orientation: true # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 30d57c86b1..e249ebafcd 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -116,7 +116,8 @@ int DoMain(int argc, char* argv[]) { auto end_effector_receiver = builder.AddSystem("end_effector_traj"); auto end_effector_orientation_receiver = - builder.AddSystem("end_effector_orientation_target"); + builder.AddSystem( + "end_effector_orientation_target"); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( controller_params.controller_channel, &lcm, @@ -183,15 +184,24 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), wrist_down_target); - osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); -// osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), -// orientation_target); + if (controller_params.track_end_effector_orientation) { + osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); + } else { + osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), + orientation_target); + } osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); osc->Build(); + if (controller_params.track_end_effector_orientation) { + builder.Connect( + end_effector_orientation_receiver->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); + } + builder.Connect(state_receiver->get_output_port(0), end_effector_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), @@ -207,14 +217,14 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(end_effector_trajectory_sub->get_output_port(), end_effector_receiver->get_input_port_trajectory()); - builder.Connect(end_effector_trajectory_sub->get_output_port(), - end_effector_orientation_receiver->get_input_port_trajectory()); + builder.Connect( + end_effector_trajectory_sub->get_output_port(), + end_effector_orientation_receiver->get_input_port_trajectory()); builder.Connect(end_effector_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); builder.Connect(end_effector_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); - builder.Connect(end_effector_orientation_receiver->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_orientation_target")); + auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); // Run lcm-driven simulation diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 9649bbc030..0965bc1fb7 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.005 visualize: true dt: 0.0001 -realtime_rate: 1.0 +realtime_rate: 0.1 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 73034ac6d7..bf234798d2 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -131,7 +131,7 @@ int do_main(int argc, char* argv[]) { auto trajectory_sub_actor = builder.AddSystem( LcmSubscriberSystem::Make( - "C3_TRAJECTORY_ACTOR_POSITION", lcm)); + "C3_TRAJECTORY_ACTOR", lcm)); auto trajectory_sub_object = builder.AddSystem( LcmSubscriberSystem::Make( "C3_TRAJECTORY_TRAY", lcm)); diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 632933b060..0bb5cc00f3 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -21,24 +21,6 @@ - - - - - - - - - - - - - - - - - - diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index cc555e4502..0f5d3f2e4b 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -190,6 +190,8 @@ std::pair LCSFactory::LinearizePlantToLCS( dt * J_t * AB_v_u; c = VectorXd::Zero(n_contact_vars); + // TODO(yangwill): check gap function to make sure it makes sense. Potential source of uncertainty +// std::cout << "phi: " << phi << std::endl; c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = From b6ed7a4d68239aaf1e25ea8d31179e488c212e9c Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 14 Apr 2023 16:09:35 -0400 Subject: [PATCH 457/758] fully added orientation tracking, though not performing well --- examples/Cassie/cassie_xbox_remote.py | 8 +- examples/franka/franka_controller_params.yaml | 2 +- examples/franka/franka_osc_controller.cc | 47 +++++----- examples/franka/franka_sim.cc | 3 - examples/franka/franka_sim_params.yaml | 2 +- examples/franka/systems/BUILD.bazel | 20 ++++- .../systems/end_effector_orientation.cc | 87 +++++++++++++++++++ .../franka/systems/end_effector_orientation.h | 54 ++++++++++++ .../franka/systems/end_effector_trajectory.cc | 2 +- .../lcm_trajectory_systems.cc | 1 + 10 files changed, 192 insertions(+), 34 deletions(-) create mode 100644 examples/franka/systems/end_effector_orientation.cc create mode 100644 examples/franka/systems/end_effector_orientation.h diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index b0969f59f8..85c732be9e 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -79,10 +79,10 @@ def main(): radio_msg = dairlib.lcmt_radio_out() radio_msg.channel[0] = -joystick.get_axis(1) radio_msg.channel[1] = -joystick.get_axis(0) - radio_msg.channel[2] = -joystick.get_axis(4) - radio_msg.channel[3] = joystick.get_axis(3) - # radio_msg.channel[2] = -joystick.get_axis(3) - # radio_msg.channel[3] = joystick.get_axis(2) + # radio_msg.channel[2] = -joystick.get_axis(4) + # radio_msg.channel[3] = joystick.get_axis(3) + radio_msg.channel[2] = -joystick.get_axis(3) + radio_msg.channel[3] = joystick.get_axis(2) radio_msg.channel[14] = latching_switch diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index db0cb3fb8d..e75d7ba466 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -14,7 +14,7 @@ impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 10.0 -track_end_effector_orientation: true +track_end_effector_orientation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index e249ebafcd..e6f66f1ead 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -4,6 +4,7 @@ #include #include "examples/franka/franka_controller_params.h" +#include "examples/franka/systems/end_effector_orientation.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" @@ -99,15 +100,15 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - auto lcm_traj = - LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); - auto orientation_traj = LcmTrajectory::Trajectory(); - orientation_traj.datapoints = MatrixXd::Zero(4, 2); - orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); - orientation_traj.traj_name = "end_effector_orientation_target"; - orientation_traj.datatypes = std::vector(2, "orientation"); - lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); - lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); +// auto lcm_traj = +// LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); +// auto orientation_traj = LcmTrajectory::Trajectory(); +// orientation_traj.datapoints = MatrixXd::Zero(4, 2); +// orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); +// orientation_traj.traj_name = "end_effector_orientation_target"; +// orientation_traj.datatypes = std::vector(2, "orientation"); +// lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); +// lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( @@ -126,6 +127,10 @@ int DoMain(int argc, char* argv[]) { auto end_effector_trajectory = builder.AddSystem(plant, plant_context.get()); + auto end_effector_orientation_trajectory = + builder.AddSystem(plant, + plant_context.get()); + end_effector_orientation_trajectory->SetTrackOrientation(controller_params.track_end_effector_orientation); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( controller_params.radio_channel, &lcm)); @@ -184,29 +189,21 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), wrist_down_target); - if (controller_params.track_end_effector_orientation) { - osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); - } else { - osc->AddConstTrackingData(std::move(end_effector_orientation_tracking_data), - orientation_target); - } + osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); osc->Build(); - if (controller_params.track_end_effector_orientation) { - builder.Connect( - end_effector_orientation_receiver->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_orientation_target")); - } - builder.Connect(state_receiver->get_output_port(0), end_effector_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_trajectory->get_input_port_radio()); - + builder.Connect(state_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_radio()); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_command(), @@ -222,8 +219,14 @@ int DoMain(int argc, char* argv[]) { end_effector_orientation_receiver->get_input_port_trajectory()); builder.Connect(end_effector_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_orientation_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_trajectory()); builder.Connect(end_effector_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect(end_effector_orientation_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); + + auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index f7898b7b5c..08a8c190a7 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -167,9 +167,6 @@ int DoMain(int argc, char* argv[]) { VectorXd q = VectorXd::Zero(nq); std::map q_map = MakeNameToPositionsMap(plant); - for (auto pair : q_map){ - std::cout << pair.first << pair.second << std::endl; - } // initialize EE close to {0.5, 0, 0.12}[m] in task space q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; q[q_map["panda_joint2"]] = sim_params.q_init_franka[1]; diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 0965bc1fb7..86e74c0c4b 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.005 visualize: true dt: 0.0001 -realtime_rate: 0.1 +realtime_rate: 0.5 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 36a82bf8f0..4c56e7d057 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -3,8 +3,11 @@ package(default_visibility = ["//visibility:public"]) cc_library( name = "franka_systems", srcs = [], - deps = [":end_effector_trajectory", - ":franka_kinematics"], + deps = [ + ":end_effector_trajectory", + ":end_effector_orientation", + ":franka_kinematics" + ], ) cc_library( @@ -20,6 +23,19 @@ cc_library( ], ) +cc_library( + name = "end_effector_orientation", + srcs = ["end_effector_orientation.cc"], + hdrs = ["end_effector_orientation.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + cc_library( name = "franka_kinematics", srcs = ["franka_kinematics.cc"], diff --git a/examples/franka/systems/end_effector_orientation.cc b/examples/franka/systems/end_effector_orientation.cc new file mode 100644 index 0000000000..bd0517ce31 --- /dev/null +++ b/examples/franka/systems/end_effector_orientation.cc @@ -0,0 +1,87 @@ +#include "end_effector_orientation.h" + +#include + +#include "dairlib/lcmt_radio_out.hpp" +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::Vector4d; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::BodyFrame; +using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::PiecewiseQuaternionSlerp; +using drake::trajectories::Trajectory; + +namespace dairlib { + +EndEffectorOrientationGenerator::EndEffectorOrientationGenerator( + const MultibodyPlant& plant, Context* context) + : plant_(plant), context_(context), world_(plant.world_frame()) { + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + PiecewisePolynomial pp = PiecewisePolynomial(); + + trajectory_port_ = + this->DeclareAbstractInputPort( + "trajectory", + drake::Value>(pp)) + .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + PiecewiseQuaternionSlerp empty_slerp_traj; + Trajectory& traj_inst = empty_slerp_traj; + this->DeclareAbstractOutputPort("end_effector_orientation", traj_inst, + &EndEffectorOrientationGenerator::CalcTraj) + .get_index(); +} + +PiecewiseQuaternionSlerp EndEffectorOrientationGenerator::GeneratePose( + const drake::systems::Context& context) const { + Eigen::VectorXd neutral_quaternion = VectorXd::Zero(4); + neutral_quaternion(0) = 1; + return drake::trajectories::PiecewiseQuaternionSlerp( + {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); +} + +void EndEffectorOrientationGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // // Read in finite state machine + + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< + PiecewiseQuaternionSlerp*>(traj); + if (radio_out->channel[14] and track_orientation_) { + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + *casted_traj = *(PiecewiseQuaternionSlerp*)dynamic_cast< + const PiecewiseQuaternionSlerp*>(&trajectory_input); + } else { + *casted_traj = GeneratePose(context); + } +} + +} // namespace dairlib diff --git a/examples/franka/systems/end_effector_orientation.h b/examples/franka/systems/end_effector_orientation.h new file mode 100644 index 0000000000..9629cbd56b --- /dev/null +++ b/examples/franka/systems/end_effector_orientation.h @@ -0,0 +1,54 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_quaternion.h" +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class EndEffectorOrientationGenerator : public drake::systems::LeafSystem { + public: + EndEffectorOrientationGenerator(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + void SetTrackOrientation(bool track_orientation){ + track_orientation_ = track_orientation; + } + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + drake::trajectories::PiecewiseQuaternionSlerp GeneratePose( + const drake::systems::Context& context) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::Frame& world_; + + bool track_orientation_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex trajectory_port_; + drake::systems::InputPortIndex radio_port_; + +}; + +} // namespace dairlib::examples::osc_run diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 9acf207b80..3bf7a7329d 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -50,7 +50,7 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( .get_index(); PiecewisePolynomial empty_pp_traj(VectorXd(0)); Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("right_ft_traj", traj_inst, + this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, &EndEffectorTrajectoryGenerator::CalcTraj); } diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 3858648217..4ea96c7a4b 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -83,6 +83,7 @@ LcmOrientationTrajectoryReceiver::LcmOrientationTrajectoryReceiver( .get_index(); lcm_traj_ = LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); + lcm_traj_.GetTrajectory(trajectory_name_); } void LcmOrientationTrajectoryReceiver::OutputTrajectory( From a4e876eb8d6135782974302d8c3a96d7a5eb60cd Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 17 Apr 2023 12:43:47 -0400 Subject: [PATCH 458/758] need to start creating logging scripts --- bindings/pydairlib/analysis/BUILD.bazel | 20 ++ .../analysis/franka_plotting_utils.py | 74 +++++++ .../pydairlib/analysis/log_plotter_franka.py | 182 ++++++++++++++++++ .../plot_configs/franka_translation.yaml | 21 ++ .../franka/franka_c3_options_translation.yaml | 4 +- examples/franka/franka_controller_params.yaml | 2 +- examples/franka/franka_sim_params.yaml | 2 +- .../lcm_trajectory_systems.cc | 5 + .../lcm_trajectory_systems.h | 2 +- 9 files changed, 306 insertions(+), 6 deletions(-) create mode 100644 bindings/pydairlib/analysis/franka_plotting_utils.py create mode 100644 bindings/pydairlib/analysis/log_plotter_franka.py create mode 100644 bindings/pydairlib/analysis/plot_configs/franka_translation.yaml diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 6aecc3e44b..729149c260 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -106,6 +106,26 @@ py_binary( ], ) +py_binary( + name = "log_plotter_franka", + srcs = ["log_plotter_franka.py"], + data = [ + "@lcm//:lcm-python", + ], + deps = [ + ":cassie_plot_config", + "//bindings/pydairlib/analysis:mbp_plotting_utils", + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", + "//bindings/pydairlib/common:plot_styler", + "//bindings/pydairlib/lcm", + "//bindings/pydairlib/multibody:kinematic_py", + "//bindings/pydairlib/multibody:multibody_py", + "//lcmtypes:lcmtypes_robot_archive_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py new file mode 100644 index 0000000000..700abb3a44 --- /dev/null +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -0,0 +1,74 @@ +# python imports +import lcm +import numpy as np +import matplotlib.pyplot as plt + +# lcmtype imports +import dairlib +import drake + +# dairlib python binding imports +from pydairlib.cassie.cassie_utils import AddCassieMultibody + +# drake imports +from pydrake.multibody.plant import AddMultibodyPlantSceneGraph +from pydrake.systems.framework import DiagramBuilder + +cassie_urdf = "examples/Cassie/urdf/cassie_v2.urdf" +cassie_urdf_no_springs = "examples/Cassie/urdf/cassie_fixed_springs.urdf" +cassie_default_channels = \ + {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, + 'CASSIE_STATE_DISPATCHER': dairlib.lcmt_robot_output, + 'CASSIE_INPUT': dairlib.lcmt_robot_input, + 'OSC_WALKING': dairlib.lcmt_robot_input, + 'OSC_STANDING': dairlib.lcmt_robot_input, + 'OSC_JUMPING': dairlib.lcmt_robot_input, + 'OSC_RUNNING': dairlib.lcmt_robot_input, + 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, + 'OSC_DEBUG_STANDING': dairlib.lcmt_osc_output, + 'OSC_DEBUG_WALKING': dairlib.lcmt_osc_output, + 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output, + 'OSC_DEBUG_RUNNING': dairlib.lcmt_osc_output} + +cassie_default_channels_archive = \ + {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, + 'CASSIE_STATE_DISPATCHER': dairlib.lcmt_robot_output, + 'CASSIE_INPUT': dairlib.lcmt_robot_input, + 'OSC_WALKING': dairlib.lcmt_robot_input, + 'OSC_STANDING': dairlib.lcmt_robot_input, + 'OSC_JUMPING': dairlib.lcmt_robot_input, + 'OSC_RUNNING': dairlib.lcmt_robot_input, + 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out} + +cassie_contact_channels = \ + {'CASSIE_CONTACT_DRAKE': drake.lcmt_contact_results_for_viz, + 'CASSIE_GM_CONTACT_DISPATCHER': drake.lcmt_contact_results_for_viz} + + +def make_plant_and_context(floating_base=True, springs=True): + builder = DiagramBuilder() + plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) + if springs: + AddCassieMultibody(plant, scene_graph, + floating_base, cassie_urdf, True, True, True) + else: + AddCassieMultibody(plant, scene_graph, + floating_base, cassie_urdf_no_springs, False, True, True) + + plant.Finalize() + return plant, plant.CreateDefaultContext() + + +def get_toe_frames_and_points(plant): + front_contact_pt = np.array((-0.0457, 0.112, 0)) + rear_contact_pt = np.array((0.088, 0, 0)) + mid_contact_pt = 0.5 * (front_contact_pt + rear_contact_pt) + + left_frame = plant.GetBodyByName("toe_left") + right_frame = plant.GetBodyByName("toe_right") + + frames = {"left": left_frame, "right": right_frame} + pts = {"rear": rear_contact_pt, "mid": mid_contact_pt, + "front": front_contact_pt} + + return frames, pts diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py new file mode 100644 index 0000000000..63362bc788 --- /dev/null +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -0,0 +1,182 @@ +import sys +import lcm +import matplotlib.pyplot as plt +import numpy as np + +from bindings.pydairlib.lcm.process_lcm_log import get_log_data +from cassie_plot_config import CassiePlotConfig +import cassie_plotting_utils as cassie_plots +import pydairlib.analysis.mbp_plotting_utils as mbp_plots +from pydairlib.common import plot_styler + + +def main(): + config_file = 'bindings/pydairlib/analysis/plot_configs/franka_translation.yaml' + plot_config = CassiePlotConfig(config_file) + + channel_x = plot_config.channel_x + channel_u = plot_config.channel_u + channel_osc = plot_config.channel_osc + + if plot_config.use_default_styling: + plot_styler.PlotStyler.set_default_styling() + + ''' Get the plant ''' + plant, context = cassie_plots.make_plant_and_context( + floating_base=use_floating_base, springs=use_springs) + pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) + pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) + + ''' Read the log ''' + filename = sys.argv[1] + log = lcm.EventLog(filename, "r") + default_channels = cassie_plots.cassie_default_channels + if plot_config.use_archived_lcmtypes: + default_channels = cassie_plots.cassie_default_channels_archive + robot_output, robot_input, osc_debug = \ + get_log_data(log, # log + default_channels, # lcm channels + plot_config.start_time, + plot_config.duration, + mbp_plots.load_default_channels, # processing callback + plant, channel_x, channel_u, channel_osc) # processing callback arguments + + if plot_config.plot_contact_forces: + contact_output = get_log_data(log, # log + cassie_plots.cassie_contact_channels, # lcm channels + plot_config.start_time, + plot_config.duration, + mbp_plots.load_force_channels, # processing callback + 'CASSIE_CONTACT_DRAKE') # processing callback arguments + + print('Finished processing log - making plots') + # Define x time slice + t_x_slice = slice(robot_output['t_x'].size) + t_osc_slice = slice(osc_debug['t_osc'].size) + + print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) + + ''' Plot Positions ''' + # Plot floating base positions if applicable + if use_floating_base and plot_config.plot_floating_base_positions: + plot = mbp_plots.plot_floating_base_positions( + robot_output, pos_names, 7, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + + # Plot joint positions + if plot_config.plot_joint_positions: + plot = mbp_plots.plot_joint_positions(robot_output, pos_names, + 7 if use_floating_base else 0, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + # Plot specific positions + if plot_config.pos_names: + plot = mbp_plots.plot_positions_by_name(robot_output, plot_config.pos_names, + t_x_slice, pos_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + + ''' Plot Velocities ''' + # Plot floating base velocities if applicable + if use_floating_base and plot_config.plot_floating_base_velocities: + plot = mbp_plots.plot_floating_base_velocities( + robot_output, vel_names, 6, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + if plot_config.plot_floating_base_velocity_body_frame: + plot = mbp_plots.plot_floating_base_body_frame_velocities( + robot_output, t_x_slice, plant, context, "pelvis") + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.tight_layout() + # plot.save_fig('running_speed_plot_kd0.png') + + # Plot all joint velocities + if plot_config.plot_joint_velocities: + plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, + 6 if use_floating_base else 0, + t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + # Plot specific velocities + if plot_config.vel_names: + plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, + t_x_slice, vel_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + ''' Plot Efforts ''' + if plot_config.plot_measured_efforts: + plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + if plot_config.plot_commanded_efforts: + plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + if plot_config.act_names: + mbp_plots.plot_measured_efforts_by_name(robot_output, + plot_config.act_names, + t_x_slice, act_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + + ''' Plot OSC ''' + if plot_config.plot_tracking_costs: + plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + # plt.ylim([0, 1e4]) + if plot_config.plot_qp_costs: + plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + if plot_config.plot_qp_solutions: + plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + + if plot_config.tracking_datas_to_plot: + for traj_name, config in plot_config.tracking_datas_to_plot.items(): + for deriv in config['derivs']: + for dim in config['dims']: + plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, + deriv, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + # plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') + tracking_data = osc_debug['osc_debug_tracking_datas'][traj_name] + # print(tracking_data.name + str(dim)) + # print('mean error: ' + str(np.nanmax(np.sqrt(tracking_data.error_y[:, dim].flatten()**2)))) + # print('mean error at end of tracking: ' + str(np.mean(np.sqrt(tracking_data.error_y[:, dim][np.append(np.isnan(tracking_data.error_y[:, dim][1:]), False)]**2)))) + # plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) + # plot.save_fig('swing_foot_target_trajectory.png') + + ''' Plot Foot Positions ''' + if plot_config.foot_positions_to_plot: + _, pts_map = cassie_plots.get_toe_frames_and_points(plant) + foot_frames = [] + dims = {} + pts = {} + plot = None + for pt_on_foot_to_plot in plot_config.pt_on_foot_to_plot: + for pos in plot_config.foot_positions_to_plot: + foot_frames.append('toe_' + pos) + dims['toe_' + pos] = plot_config.foot_xyz_to_plot[pos] + pts['toe_' + pos] = pts_map[pt_on_foot_to_plot] + + plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, + foot_frames, pts, dims, plot) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.save_fig('foot_contact_vertical_position.png') + + if plot_config.plot_qp_solve_time: + plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + + if plot_config.plot_active_tracking_datas: + plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot.save_fig('active_tracking_datas.png') + plt.show() + + +if __name__ == '__main__': + main() diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml new file mode 100644 index 0000000000..b85400ecde --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml @@ -0,0 +1,21 @@ +# LCM channels to read data from +channel_x: "FRANKA_OUTPUT" +channel_u: "FRANKA_INPUT" +channel_osc: "OSC_DEBUG_FRANKA" + +# Plant properties + +# Desired RobotOutput plots +plot_joint_positions: true +plot_joint_velocities: true +plot_measured_efforts: true +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Desired osc plots +plot_qp_costs: true +plot_qp_solve_time: true +plot_tracking_costs: true +tracking_datas_to_plot: + end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index ba6c3dcced..032105e660 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -21,12 +21,10 @@ w_U: 1 g_size: 40 u_size: 40 # State Tracking Error, assuming diagonal -#q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1] q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.5, 0.02, 0.43, 1, 0, 0, 0, 0.5, 0.02, 0.45] +q_des_vector: [0.5, 0.02, 0.41, 1, 0, 0, 0, 0.5, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index db0cb3fb8d..e75d7ba466 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -14,7 +14,7 @@ impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 10.0 -track_end_effector_orientation: true +track_end_effector_orientation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 0965bc1fb7..e4d03586bf 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.005 visualize: true dt: 0.0001 -realtime_rate: 0.1 +realtime_rate: 0.2 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 3858648217..dd2bc9e505 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -95,6 +95,11 @@ void LcmOrientationTrajectoryReceiver::OutputTrajectory( this->EvalInputValue( context, trajectory_input_port_); lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); + try { + lcm_traj_.GetTrajectory(trajectory_name_); + } catch (std::exception& e) { + std::cerr << "Make sure the planner is sending orientation" << std::endl; + } } const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 867ac626f0..e60e616609 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -39,7 +39,7 @@ class LcmTrajectoryReceiver : public drake::systems::LeafSystem { mutable LcmTrajectory lcm_traj_; std::string default_trajectory_path_ = - "examples/franka/saved_trajectories/default_end_effector_pose"; + "examples/franka/saved_trajectories/franka_defaults"; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, From 261550d6e676dbd8fb881d87265dc4f9c19e63ea Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 17 Apr 2023 16:21:31 -0400 Subject: [PATCH 459/758] checking parameters and urdfs --- bindings/pydairlib/analysis/BUILD.bazel | 8 +- .../pydairlib/analysis/franka_plot_config.py | 43 ++++++++++ .../analysis/franka_plotting_utils.py | 79 ++++++------------ .../pydairlib/analysis/log_plotter_franka.py | 80 ++++--------------- .../plot_configs/franka_translation.yaml | 15 +++- .../franka/franka_c3_options_floating.yaml | 6 +- .../franka/franka_c3_options_translation.yaml | 2 +- examples/franka/franka_controller_params.yaml | 10 +-- examples/franka/franka_sim.cc | 2 - examples/franka/franka_sim_params.yaml | 2 +- .../urdf/plate_end_effector_floating.urdf | 10 +-- .../urdf/plate_end_effector_translation.urdf | 2 +- examples/franka/urdf/tray.sdf | 4 +- .../lcm_trajectory_systems.cc | 1 + 14 files changed, 123 insertions(+), 141 deletions(-) create mode 100644 bindings/pydairlib/analysis/franka_plot_config.py diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 729149c260..b09e44c826 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -41,6 +41,12 @@ py_library( deps = [], ) +py_library( + name = "franka_plot_config", + srcs = ["franka_plot_config.py"], + deps = [], +) + py_library( name = "spring_compensation", srcs = ["spring_compensation.py"], @@ -113,7 +119,7 @@ py_binary( "@lcm//:lcm-python", ], deps = [ - ":cassie_plot_config", + ":franka_plot_config", "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py new file mode 100644 index 0000000000..aae1a41727 --- /dev/null +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -0,0 +1,43 @@ +import io +from yaml import load, dump + +try: + from yaml import CLoader as Loader, CDumper as Dumper +except ImportError: + from yaml import Loader, Dumper + + +class FrankaPlotConfig(): + def __init__(self, filename): + data = load(io.open(filename, 'r'), Loader=Loader) + self.channel_x = data['channel_x'] + self.channel_u = data['channel_u'] + self.channel_osc = data['channel_osc'] + self.use_default_styling = data['use_default_styling'] + + self.start_time = data['start_time'] + self.duration = data['duration'] + self.plot_joint_positions = data['plot_joint_positions'] + self.plot_joint_velocities = data['plot_joint_velocities'] + self.plot_measured_efforts = data['plot_measured_efforts'] + self.plot_commanded_efforts = data['plot_commanded_efforts'] + self.plot_contact_forces = data['plot_contact_forces'] + self.pos_names = \ + data['special_positions_to_plot'] if \ + data['special_positions_to_plot'] else [] + self.vel_names = \ + data['special_velocities_to_plot'] if \ + data['special_velocities_to_plot'] else [] + self.act_names = \ + data['special_efforts_to_plot'] if \ + data['special_efforts_to_plot'] else [] + + self.fsm_state_names = data['fsm_state_names'] + + self.plot_qp_costs = data['plot_qp_costs'] + self.plot_qp_solve_time = data['plot_qp_solve_time'] + self.plot_qp_solutions = data['plot_qp_solutions'] + self.plot_tracking_costs = data['plot_tracking_costs'] + self.plot_active_tracking_datas = data['plot_active_tracking_datas'] + self.tracking_datas_to_plot = \ + data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index 700abb3a44..460482d6f1 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -7,68 +7,37 @@ import dairlib import drake -# dairlib python binding imports -from pydairlib.cassie.cassie_utils import AddCassieMultibody - # drake imports from pydrake.multibody.plant import AddMultibodyPlantSceneGraph from pydrake.systems.framework import DiagramBuilder +from pydrake.all import MultibodyPlant, Parser, RigidTransform -cassie_urdf = "examples/Cassie/urdf/cassie_v2.urdf" -cassie_urdf_no_springs = "examples/Cassie/urdf/cassie_fixed_springs.urdf" -cassie_default_channels = \ - {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, - 'CASSIE_STATE_DISPATCHER': dairlib.lcmt_robot_output, - 'CASSIE_INPUT': dairlib.lcmt_robot_input, - 'OSC_WALKING': dairlib.lcmt_robot_input, - 'OSC_STANDING': dairlib.lcmt_robot_input, - 'OSC_JUMPING': dairlib.lcmt_robot_input, - 'OSC_RUNNING': dairlib.lcmt_robot_input, - 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out, - 'OSC_DEBUG_STANDING': dairlib.lcmt_osc_output, - 'OSC_DEBUG_WALKING': dairlib.lcmt_osc_output, - 'OSC_DEBUG_JUMPING': dairlib.lcmt_osc_output, - 'OSC_DEBUG_RUNNING': dairlib.lcmt_osc_output} - -cassie_default_channels_archive = \ - {'CASSIE_STATE_SIMULATION': dairlib.lcmt_robot_output, - 'CASSIE_STATE_DISPATCHER': dairlib.lcmt_robot_output, - 'CASSIE_INPUT': dairlib.lcmt_robot_input, - 'OSC_WALKING': dairlib.lcmt_robot_input, - 'OSC_STANDING': dairlib.lcmt_robot_input, - 'OSC_JUMPING': dairlib.lcmt_robot_input, - 'OSC_RUNNING': dairlib.lcmt_robot_input, - 'CASSIE_OUTPUT': dairlib.lcmt_cassie_out} - -cassie_contact_channels = \ - {'CASSIE_CONTACT_DRAKE': drake.lcmt_contact_results_for_viz, - 'CASSIE_GM_CONTACT_DISPATCHER': drake.lcmt_contact_results_for_viz} - - -def make_plant_and_context(floating_base=True, springs=True): - builder = DiagramBuilder() - plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0) - if springs: - AddCassieMultibody(plant, scene_graph, - floating_base, cassie_urdf, True, True, True) - else: - AddCassieMultibody(plant, scene_graph, - floating_base, cassie_urdf_no_springs, False, True, True) +franka_urdf = "examples/franka/urdf/franka_no_collision.urdf" +tray_model = "examples/franka/urdf/tray.sdf" +franka_default_channels = \ + {'FRANKA_OUTPUT': dairlib.lcmt_robot_output, + 'TRAY_OUTPUT': dairlib.lcmt_robot_output, + 'FRANKA_INPUT': dairlib.lcmt_robot_input, + 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, + 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, + 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, + 'CASSIE_VIRTUAL_RADIO': dairlib.lcmt_radio_out, + 'CONTACT_RESULTS': drake.lcmt_contact_results_for_viz} - plant.Finalize() - return plant, plant.CreateDefaultContext() +def make_plant_and_context(): + builder = DiagramBuilder() -def get_toe_frames_and_points(plant): - front_contact_pt = np.array((-0.0457, 0.112, 0)) - rear_contact_pt = np.array((0.088, 0, 0)) - mid_contact_pt = 0.5 * (front_contact_pt + rear_contact_pt) + franka_plant = MultibodyPlant(0.0) + franka_parser = Parser(franka_plant) + franka_parser.AddModelFromFile(franka_urdf) - left_frame = plant.GetBodyByName("toe_left") - right_frame = plant.GetBodyByName("toe_right") + tray_plant = MultibodyPlant(0.0) + tray_parser = Parser(tray_plant) + tray_parser.AddModelFromFile(tray_model) - frames = {"left": left_frame, "right": right_frame} - pts = {"rear": rear_contact_pt, "mid": mid_contact_pt, - "front": front_contact_pt} + franka_plant.WeldFrames(franka_plant.world_frame(), franka_plant.GetFrameByName("panda_link0"), RigidTransform()) - return frames, pts + franka_plant.Finalize() + tray_plant.Finalize() + return franka_plant, franka_plant.CreateDefaultContext(), tray_plant, tray_plant.CreateDefaultContext() diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 63362bc788..57472e6b00 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -3,16 +3,17 @@ import matplotlib.pyplot as plt import numpy as np +from bindings.pydairlib.analysis.franka_plot_config import FrankaPlotConfig from bindings.pydairlib.lcm.process_lcm_log import get_log_data from cassie_plot_config import CassiePlotConfig -import cassie_plotting_utils as cassie_plots +import franka_plotting_utils as franka_plots import pydairlib.analysis.mbp_plotting_utils as mbp_plots from pydairlib.common import plot_styler def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/franka_translation.yaml' - plot_config = CassiePlotConfig(config_file) + plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x channel_u = plot_config.channel_u @@ -22,32 +23,23 @@ def main(): plot_styler.PlotStyler.set_default_styling() ''' Get the plant ''' - plant, context = cassie_plots.make_plant_and_context( - floating_base=use_floating_base, springs=use_springs) - pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(plant) - pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(plant) + franka_plant, franka_context, tray_plant, tray_context = franka_plots.make_plant_and_context() + + pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(franka_plant) + pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(franka_plant) + ''' Read the log ''' filename = sys.argv[1] log = lcm.EventLog(filename, "r") - default_channels = cassie_plots.cassie_default_channels - if plot_config.use_archived_lcmtypes: - default_channels = cassie_plots.cassie_default_channels_archive + default_channels = franka_plots.franka_default_channels robot_output, robot_input, osc_debug = \ get_log_data(log, # log default_channels, # lcm channels plot_config.start_time, plot_config.duration, mbp_plots.load_default_channels, # processing callback - plant, channel_x, channel_u, channel_osc) # processing callback arguments - - if plot_config.plot_contact_forces: - contact_output = get_log_data(log, # log - cassie_plots.cassie_contact_channels, # lcm channels - plot_config.start_time, - plot_config.duration, - mbp_plots.load_force_channels, # processing callback - 'CASSIE_CONTACT_DRAKE') # processing callback arguments + franka_plant, channel_x, channel_u, channel_osc) # processing callback arguments print('Finished processing log - making plots') # Define x time slice @@ -56,18 +48,10 @@ def main(): print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) - ''' Plot Positions ''' - # Plot floating base positions if applicable - if use_floating_base and plot_config.plot_floating_base_positions: - plot = mbp_plots.plot_floating_base_positions( - robot_output, pos_names, 7, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - - # Plot joint positions if plot_config.plot_joint_positions: plot = mbp_plots.plot_joint_positions(robot_output, pos_names, - 7 if use_floating_base else 0, t_x_slice) + 0, t_x_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) # Plot specific positions @@ -76,25 +60,10 @@ def main(): t_x_slice, pos_map) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - - ''' Plot Velocities ''' - # Plot floating base velocities if applicable - if use_floating_base and plot_config.plot_floating_base_velocities: - plot = mbp_plots.plot_floating_base_velocities( - robot_output, vel_names, 6, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - - if plot_config.plot_floating_base_velocity_body_frame: - plot = mbp_plots.plot_floating_base_body_frame_velocities( - robot_output, t_x_slice, plant, context, "pelvis") - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plot.tight_layout() - # plot.save_fig('running_speed_plot_kd0.png') - # Plot all joint velocities if plot_config.plot_joint_velocities: plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, - 6 if use_floating_base else 0, + 0, t_x_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) @@ -114,7 +83,7 @@ def main(): mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.act_names: - mbp_plots.plot_measured_efforts_by_name(robot_output, + plot = mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, t_x_slice, act_map) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) @@ -124,10 +93,11 @@ def main(): if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - # plt.ylim([0, 1e4]) + plt.ylim([0, 1e3]) if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + if plot_config.plot_qp_solutions: plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) @@ -150,31 +120,13 @@ def main(): # plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) # plot.save_fig('swing_foot_target_trajectory.png') - ''' Plot Foot Positions ''' - if plot_config.foot_positions_to_plot: - _, pts_map = cassie_plots.get_toe_frames_and_points(plant) - foot_frames = [] - dims = {} - pts = {} - plot = None - for pt_on_foot_to_plot in plot_config.pt_on_foot_to_plot: - for pos in plot_config.foot_positions_to_plot: - foot_frames.append('toe_' + pos) - dims['toe_' + pos] = plot_config.foot_xyz_to_plot[pos] - pts['toe_' + pos] = pts_map[pt_on_foot_to_plot] - - plot = mbp_plots.plot_points_positions(robot_output, t_x_slice, plant, context, - foot_frames, pts, dims, plot) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plot.save_fig('foot_contact_vertical_position.png') - if plot_config.plot_qp_solve_time: plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) if plot_config.plot_active_tracking_datas: plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - plot.save_fig('active_tracking_datas.png') + # plot.save_fig('active_tracking_datas.png') plt.show() diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml index b85400ecde..422435e6ec 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml @@ -2,20 +2,33 @@ channel_x: "FRANKA_OUTPUT" channel_u: "FRANKA_INPUT" channel_osc: "OSC_DEBUG_FRANKA" +use_default_styling: false + +start_time: 2 +#duration: 0.47 +duration: 50 # Plant properties # Desired RobotOutput plots plot_joint_positions: true plot_joint_velocities: true -plot_measured_efforts: true +plot_measured_efforts: false +plot_commanded_efforts: true +plot_contact_forces: false + special_positions_to_plot: [] special_velocities_to_plot: [] special_efforts_to_plot: [] +# Finite State Machine Names +fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] + # Desired osc plots plot_qp_costs: true plot_qp_solve_time: true +plot_qp_solutions: false plot_tracking_costs: true +plot_active_tracking_datas: false tracking_datas_to_plot: end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index 1497c5c568..9a73a31ed1 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -10,7 +10,7 @@ dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 -N: 5 +N: 10 w_Q: 10 w_R: 0 # Penalty on all decision variables, assuming scalar @@ -26,7 +26,7 @@ u_size: 49 q_vector: [200, 200, 500, 10, 10, 10, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1, 1, 1, 1] +r_vector: [1, 1, 1, 0.1, 0.1, 0.1] -q_des_vector: [0.5, 0.02, 0.45, 0, 0, 0, 1, 0, 0, 0, 0.3, -0.2, 0.43] +q_des_vector: [0.5, 0.02, 0.41, 0, 0, 0, 1, 0, 0, 0, 0.5, 0.02, 0.3] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 032105e660..5611e1d32f 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.4 +mu: 0.2 mu_plate: 1 dt: 0.1 solve_dt: 0.05 diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index e75d7ba466..12ae4cc3d1 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -13,7 +13,7 @@ w_lambda: 0.1 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 10.0 +end_effector_acceleration: 20.0 track_end_effector_orientation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] @@ -31,12 +31,12 @@ EndEffectorW: 0, 0, 1] EndEffectorKp: [ 1000, 0, 0, - 0, 1000, 0, + 0, 500, 0, 0, 0, 1000 ] EndEffectorKd: - [ 300, 0, 0, - 0, 300, 0, - 0, 0, 300 ] + [ 125, 0, 0, + 0, 70, 0, + 0, 0, 125 ] MidLinkW: [0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 08a8c190a7..e6bf2d6607 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -60,8 +60,6 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; double sim_dt = sim_params.dt; double output_dt = sim_params.dt; - // auto scene_graph = - // builder.AddSystem(std::make_unique>()); auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); Parser parser(&plant); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index e4d03586bf..86e74c0c4b 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.005 visualize: true dt: 0.0001 -realtime_rate: 0.2 +realtime_rate: 0.5 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf index 85a283dfb4..f1807c4a92 100644 --- a/examples/franka/urdf/plate_end_effector_floating.urdf +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -9,19 +9,19 @@ - + + izz="0.013"/> - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 0bb5cc00f3..5b185e05a4 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -6,7 +6,7 @@ - + - 0.4 - 0.4 + 0.2 + 0.2 diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 1500fff4f0..9773e0f7e1 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -100,6 +100,7 @@ void LcmOrientationTrajectoryReceiver::OutputTrajectory( lcm_traj_.GetTrajectory(trajectory_name_); } catch (std::exception& e) { std::cerr << "Make sure the planner is sending orientation" << std::endl; + throw std::out_of_range(""); } } const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); From 0f5c786e9bed2a1709073a960b474fe4f2978f52 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 18 Apr 2023 15:45:33 -0400 Subject: [PATCH 460/758] visualizing end effector pose --- .../franka/franka_c3_controller_params.yaml | 10 +++++----- .../franka/franka_c3_options_floating.yaml | 4 ++-- .../franka/franka_c3_options_translation.yaml | 2 +- examples/franka/franka_osc_controller.cc | 18 +++++++++--------- examples/franka/franka_visualizer.cc | 10 +++------- examples/franka/systems/franka_kinematics.cc | 2 -- lcm/lcm_trajectory.h | 4 ++++ systems/controllers/c3_controller.cc | 1 - .../lcm_trajectory_systems.cc | 19 +++++++++++++++++-- 9 files changed, 41 insertions(+), 29 deletions(-) diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 8b75dc5920..eb18b7961d 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -c3_options_file: examples/franka/franka_c3_options_translation.yaml -#c3_options_file: examples/franka/franka_c3_options_floating.yaml +#c3_options_file: examples/franka/franka_c3_options_translation.yaml +c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,10 +7,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray_lcs.sdf -include_end_effector_orientation: false +include_end_effector_orientation: true diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index 9a73a31ed1..91cda4b7aa 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -10,7 +10,7 @@ dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 -N: 10 +N: 5 w_Q: 10 w_R: 0 # Penalty on all decision variables, assuming scalar @@ -23,7 +23,7 @@ u_size: 49 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 10, 10, 10, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [200, 200, 500, 50, 50, 50, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 0.1, 0.1, 0.1] diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 5611e1d32f..21d610c04d 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -6,7 +6,7 @@ delta_option: 1 mu: 0.2 mu_plate: 1 -dt: 0.1 +dt: 0.08 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index e6f66f1ead..a241923d1a 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -100,15 +100,15 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); -// auto lcm_traj = -// LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); -// auto orientation_traj = LcmTrajectory::Trajectory(); -// orientation_traj.datapoints = MatrixXd::Zero(4, 2); -// orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); -// orientation_traj.traj_name = "end_effector_orientation_target"; -// orientation_traj.datatypes = std::vector(2, "orientation"); -// lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); -// lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); + auto lcm_traj = + LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); + auto orientation_traj = LcmTrajectory::Trajectory(); + orientation_traj.datapoints = MatrixXd::Zero(4, 2); + orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); + orientation_traj.traj_name = "end_effector_orientation_target"; + orientation_traj.datatypes = std::vector(2, "orientation"); + lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); + lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index bf234798d2..f55cd21c08 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -98,11 +98,7 @@ int do_main(int argc, char* argv[]) { R_X_W); plant.Finalize(); - auto lcm_traj = - LcmTrajectory(dairlib::FindResourceOrThrow("examples/franka/saved_trajectories/default_end_effector_pose")); - auto traj = lcm_traj.GetTrajectory("end_effector_traj"); - lcm_traj.AddTrajectory("object_traj", traj); - lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); + auto lcm = builder.AddSystem(); // Create state receiver. @@ -150,8 +146,8 @@ int do_main(int argc, char* argv[]) { meshcat, "object_traj"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); - trajectory_drawer_actor->SetNumSamples(20); - trajectory_drawer_object->SetNumSamples(20); + trajectory_drawer_actor->SetNumSamples(5); + trajectory_drawer_object->SetNumSamples(5); builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); diff --git a/examples/franka/systems/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc index 3796b63313..d917261812 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -97,14 +97,12 @@ void FrankaKinematics::ComputeLCSState( VectorXd::Zero(num_end_effector_velocities_); if (num_end_effector_positions_ > 3) { -// std::cout << "here: " << std::endl; end_effector_positions << end_effector_pose.translation(), end_effector_rotation_rpy; } else { end_effector_positions << end_effector_pose.translation(); } if (num_end_effector_velocities_ > 3) { -// std::cout << "here: " << std::endl; end_effector_velocities << end_effector_spatial_velocity.rotational(), end_effector_spatial_velocity.translational(); } else { diff --git a/lcm/lcm_trajectory.h b/lcm/lcm_trajectory.h index 025648c3a6..89b28e9fad 100644 --- a/lcm/lcm_trajectory.h +++ b/lcm/lcm_trajectory.h @@ -65,6 +65,10 @@ class LcmTrajectory { lcmt_metadata GetMetadata() const { return metadata_; } + bool HasTrajectory(const std::string& trajectory_name) const { + return trajectories_.count(trajectory_name) > 0; + } + const Trajectory& GetTrajectory(const std::string& trajectory_name) const { try { return trajectories_.at(trajectory_name); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 427be46360..7f23b21ede 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -222,7 +222,6 @@ void C3Controller::OutputObjectTrajectory( u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); } - // MatrixXd knots = x_sol.topRows(n_q_).bottomRows(3); MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = x_sol.topRows(n_q_).bottomRows(3); knots.bottomRows(3) = x_sol.bottomRows(n_v_).bottomRows(3); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 9773e0f7e1..ad1240f612 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -18,6 +18,7 @@ using drake::trajectories::PiecewisePolynomial; using drake::trajectories::PiecewiseQuaternionSlerp; using drake::trajectories::Trajectory; using Eigen::MatrixXd; +using Eigen::Quaterniond; using Eigen::VectorXd; LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) @@ -151,8 +152,6 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( VectorXd breaks = VectorXd::LinSpaced(N_, trajectory_block.time_vector[0], trajectory_block.time_vector.tail(1)[0]); - // std::cout << "rows: " << trajectory_block.datapoints.rows() << std::endl; - // std::cout << "cols: " << trajectory_block.datapoints.cols() << std::endl; if (trajectory_block.datapoints.rows() == 3) { auto trajectory = PiecewisePolynomial::FirstOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); @@ -173,6 +172,22 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( DRAKE_DEMAND(line_points.rows() == 3); meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, rgba_); + + if (lcm_traj_.HasTrajectory("end_effector_orientation_target")) { + const auto orientation_block = + lcm_traj_.GetTrajectory("end_effector_orientation_target"); + auto trajectory = PiecewisePolynomial::CubicHermite( + orientation_block.time_vector, orientation_block.datapoints.topRows(3), + orientation_block.datapoints.bottomRows(3)); + for (int i = 0; i < line_points.cols(); ++i) { + auto pose = drake::math::RigidTransform( + drake::math::RollPitchYaw(trajectory.value(breaks(i))), line_points.col(i)); + auto box = drake::geometry::Box(0.1, 0.1, 0.01); + meshcat_->SetObject("box" + std::to_string(i), box, rgba_); + meshcat_->SetTransform("box" + std::to_string(i), pose); + } + } + return drake::systems::EventStatus::Succeeded(); } From 43ec75c993073b06dbac8d0167e663a09dbfef66 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 18 Apr 2023 15:59:40 -0400 Subject: [PATCH 461/758] also publishing object orientation --- systems/controllers/c3_controller.cc | 20 ++++++++++++++++++-- 1 file changed, 18 insertions(+), 2 deletions(-) diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7f23b21ede..f8967c9ec5 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -223,8 +223,8 @@ void C3Controller::OutputObjectTrajectory( } MatrixXd knots = MatrixXd::Zero(6, N_); - knots.topRows(3) = x_sol.topRows(n_q_).bottomRows(3); - knots.bottomRows(3) = x_sol.bottomRows(n_v_).bottomRows(3); + knots.topRows(3) = x_sol.middleRows(n_q_ - 3, 3); + knots.bottomRows(3) = x_sol.middleRows(n_q_ + n_v_ - 3, 3); LcmTrajectory::Trajectory object_traj; object_traj.traj_name = "object_traj"; object_traj.datatypes = std::vector(knots.rows(), "double"); @@ -232,6 +232,22 @@ void C3Controller::OutputObjectTrajectory( object_traj.time_vector = breaks; LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, "object_traj", "object_traj", false); + + if (publish_end_effector_orientation_) { + LcmTrajectory::Trajectory object_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(7, N_); + orientation_samples.topRows(4) = x_sol.middleRows(3 + 3, 4); + orientation_samples.bottomRows(3) = x_sol.middleRows(n_q_ + 3 + 3, 3); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = breaks; + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + std::move(object_orientation_traj)); + } + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); output_traj->utime = t * 1e6; } From 90c68fbc39ec2ea50e95d48835ab267ada3df696 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 18 Apr 2023 17:24:25 -0400 Subject: [PATCH 462/758] tracking works reasonably well --- examples/franka/franka_c3_controller.cc | 8 +-- .../franka/franka_c3_controller_params.yaml | 12 ++-- .../franka/franka_c3_options_translation.yaml | 2 +- .../urdf/plate_end_effector_floating.urdf | 30 ++------ .../urdf/plate_end_effector_translation.urdf | 72 +++++++------------ examples/franka/urdf/tray.sdf | 4 +- .../lcm_trajectory_systems.cc | 28 ++++---- 7 files changed, 60 insertions(+), 96 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 4d0e7581ea..ac3bd33c77 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -122,8 +122,8 @@ int DoMain(int argc, char* argv[]) { contact_geoms["TRAY"] = tray_geoms; std::vector> contact_pairs; - for (auto geom_id : contact_geoms["TRAY"]) { - contact_pairs.emplace_back(geom_id, contact_geoms["PLATE"][0]); + for (auto geom_id : contact_geoms["PLATE"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); } /// @@ -155,11 +155,11 @@ int DoMain(int argc, char* argv[]) { auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( controller_params.c3_channel_actor, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + TriggerTypeSet({TriggerType::kPeriodic}), 0.2)); auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( controller_params.c3_channel_object, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + TriggerTypeSet({TriggerType::kPeriodic}), 0.2)); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( controller_params.radio_channel, &lcm)); diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index eb18b7961d..94cf6f8803 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -#c3_options_file: examples/franka/franka_c3_options_translation.yaml -c3_options_file: examples/franka/franka_c3_options_floating.yaml +c3_options_file: examples/franka/franka_c3_options_translation.yaml +#c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,10 +7,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -plate_model: examples/franka/urdf/plate_end_effector_floating.urdf -tray_model: examples/franka/urdf/tray_lcs.sdf +plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +tray_model: examples/franka/urdf/tray.sdf -include_end_effector_orientation: true +include_end_effector_orientation: false diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 21d610c04d..cb3a1a83bc 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -26,5 +26,5 @@ q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.5, 0.02, 0.41, 1, 0, 0, 0, 0.5, 0.02, 0.45] +q_des_vector: [0.5, 0.02, 0.43, 1, 0, 0, 0, 0.5, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf index f1807c4a92..169119b303 100644 --- a/examples/franka/urdf/plate_end_effector_floating.urdf +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -42,41 +42,23 @@ - - - - - - - - - - - - - - - - - - - + - + - + - + - + - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 5b185e05a4..75d8f4ee0d 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -21,54 +21,36 @@ - - + + + + + + + + + + + + + - + + + + + + + + + + + + + - - - - - - + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 43f99f8067..647583fc90 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -18,14 +18,14 @@ - 0.3 0.6 0.02 + 0.6 0.6 0.02 - 0.3 0.6 0.02 + 0.6 0.6 0.02 diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index ad1240f612..fb25a34f69 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -173,20 +173,20 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, rgba_); - if (lcm_traj_.HasTrajectory("end_effector_orientation_target")) { - const auto orientation_block = - lcm_traj_.GetTrajectory("end_effector_orientation_target"); - auto trajectory = PiecewisePolynomial::CubicHermite( - orientation_block.time_vector, orientation_block.datapoints.topRows(3), - orientation_block.datapoints.bottomRows(3)); - for (int i = 0; i < line_points.cols(); ++i) { - auto pose = drake::math::RigidTransform( - drake::math::RollPitchYaw(trajectory.value(breaks(i))), line_points.col(i)); - auto box = drake::geometry::Box(0.1, 0.1, 0.01); - meshcat_->SetObject("box" + std::to_string(i), box, rgba_); - meshcat_->SetTransform("box" + std::to_string(i), pose); - } - } +// if (lcm_traj_.HasTrajectory("end_effector_orientation_target")) { +// const auto orientation_block = +// lcm_traj_.GetTrajectory("end_effector_orientation_target"); +// auto trajectory = PiecewisePolynomial::CubicHermite( +// orientation_block.time_vector, orientation_block.datapoints.topRows(3), +// orientation_block.datapoints.bottomRows(3)); +// for (int i = 0; i < line_points.cols(); ++i) { +// auto pose = drake::math::RigidTransform( +// drake::math::RollPitchYaw(trajectory.value(breaks(i))), line_points.col(i)); +// auto box = drake::geometry::Box(0.1, 0.1, 0.01); +// meshcat_->SetObject("box" + std::to_string(i), box, rgba_); +// meshcat_->SetTransform("box" + std::to_string(i), pose); +// } +// } return drake::systems::EventStatus::Succeeded(); } From f6e7b5d1ea58047697846ec57b42c31d16054ef8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 19 Apr 2023 10:51:49 -0400 Subject: [PATCH 463/758] updating drake master --- .../state_based_controller_switch.cc | 2 +- examples/Cassie/osc/high_level_command.cc | 1 - examples/Cassie/osc/standing_com_traj.cc | 3 +- examples/Cassie/run_controller_switch.cc | 2 +- multibody/multipose_visualizer.cc | 2 +- systems/controllers/alip_swing_ft_traj_gen.cc | 96 +++++---- systems/controllers/alip_traj_gen.cc | 182 +++++++++--------- systems/controllers/lipm_traj_gen.cc | 10 +- systems/controllers/swing_ft_traj_gen.cc | 3 +- 9 files changed, 142 insertions(+), 159 deletions(-) diff --git a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc index 2873fc7348..3880cd0264 100644 --- a/examples/Cassie/contact_scheduler/state_based_controller_switch.cc +++ b/examples/Cassie/contact_scheduler/state_based_controller_switch.cc @@ -122,7 +122,7 @@ int do_main(int argc, char* argv[]) { // Force-publish via the diagram /// We don't need AdvanceTo(time) because we manually force publish lcm /// message, and there is nothing in the diagram that needs to be updated. - diagram_ptr->Publish(diagram_context); + diagram_ptr->ForcedPublish(diagram_context); pub_count++; } diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index 30c4f3b63d..0852ce0d93 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -8,7 +8,6 @@ #include "multibody/multibody_utils.h" #include "drake/math/quaternion.h" -#include "drake/math/saturate.h" using std::string; diff --git a/examples/Cassie/osc/standing_com_traj.cc b/examples/Cassie/osc/standing_com_traj.cc index 44e5267e85..abce96d008 100644 --- a/examples/Cassie/osc/standing_com_traj.cc +++ b/examples/Cassie/osc/standing_com_traj.cc @@ -3,7 +3,6 @@ #include #include -#include #include "multibody/multibody_utils.h" @@ -87,7 +86,7 @@ void StandingComTraj::CalcDesiredTraj( target_height += kHeightScale * radio_out->channel[0]; // Saturate based on min and max height - target_height = drake::math::saturate(target_height, kMinHeight, kMaxHeight); + target_height = std::clamp(target_height, kMinHeight, kMaxHeight); double x_offset = kCoMXScale * radio_out->channel[4]; double y_offset = kCoMYScale * radio_out->channel[5]; Vector3d target_pos; diff --git a/examples/Cassie/run_controller_switch.cc b/examples/Cassie/run_controller_switch.cc index 68032c1f44..319c422a2e 100644 --- a/examples/Cassie/run_controller_switch.cc +++ b/examples/Cassie/run_controller_switch.cc @@ -137,7 +137,7 @@ int do_main(int argc, char* argv[]) { // Force-publish via the diagram /// We don't need AdvanceTo(time) because we manually force publish lcm /// message, and there is nothing in the diagram that needs to be updated. - diagram_ptr->Publish(diagram_context); + diagram_ptr->ForcedPublish(diagram_context); pub_count++; } diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index 7116b58f2d..37cd2eebc2 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -112,7 +112,7 @@ void MultiposeVisualizer::DrawPoses(MatrixXd poses) { } // Publish diagram - diagram_->Publish(*diagram_context_); + diagram_->ForcedPublish(*diagram_context_); } diff --git a/systems/controllers/alip_swing_ft_traj_gen.cc b/systems/controllers/alip_swing_ft_traj_gen.cc index 5b754d2c9a..45c9472f00 100644 --- a/systems/controllers/alip_swing_ft_traj_gen.cc +++ b/systems/controllers/alip_swing_ft_traj_gen.cc @@ -1,14 +1,14 @@ #include "systems/controllers/alip_swing_ft_traj_gen.h" -#include #include +#include #include #include -#include "drake/math/saturate.h" -#include "drake/math/roll_pitch_yaw.h" -#include "systems/controllers/control_utils.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/control_utils.h" + +#include "drake/math/roll_pitch_yaw.h" using std::string; @@ -18,6 +18,7 @@ using Eigen::Vector3d; using Eigen::Vector4d; using Eigen::VectorXd; +using drake::math::RollPitchYaw; using drake::multibody::Frame; using drake::multibody::JacobianWrtVariable; using drake::systems::BasicVector; @@ -25,7 +26,6 @@ using drake::systems::Context; using drake::systems::DiscreteUpdateEvent; using drake::systems::DiscreteValues; using drake::systems::EventStatus; -using drake::math::RollPitchYaw; using drake::trajectories::ExponentialPlusPiecewisePolynomial; using drake::trajectories::PiecewisePolynomial; @@ -38,7 +38,7 @@ AlipSwingFootTrajGenerator::AlipSwingFootTrajGenerator( std::vector left_right_support_fsm_states, std::vector left_right_support_durations, std::vector&>> - left_right_foot, + left_right_foot, std::string floating_base_body_name, double double_support_duration, double mid_foot_height, double desired_final_foot_height, double desired_final_vertical_foot_velocity, @@ -65,10 +65,10 @@ AlipSwingFootTrajGenerator::AlipSwingFootTrajGenerator( // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector(plant.num_positions(), - plant.num_velocities(), - plant.num_actuators())) - .get_index(); + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); liftoff_time_port_ = @@ -76,14 +76,14 @@ AlipSwingFootTrajGenerator::AlipSwingFootTrajGenerator( .get_index(); PiecewisePolynomial pp(VectorXd::Zero(0)); - alip_state_port_ = this->DeclareAbstractInputPort( - "alip x, y, Lx, Ly", - drake::Value>(pp)) - .get_index(); - vdes_port_ = - this->DeclareVectorInputPort("desired horizontal walking speed", - BasicVector(2)) + alip_state_port_ = + this->DeclareAbstractInputPort( + "alip x, y, Lx, Ly", + drake::Value>(pp)) .get_index(); + vdes_port_ = this->DeclareVectorInputPort("desired horizontal walking speed", + BasicVector(2)) + .get_index(); // Provide an instance to allocate the memory first (for the output) drake::trajectories::Trajectory& traj_instance = pp; this->DeclareAbstractOutputPort("swing_foot_xyz", traj_instance, @@ -124,13 +124,13 @@ EventStatus AlipSwingFootTrajGenerator::DiscreteVariableUpdate( (OutputVector*)this->EvalVectorInput(context, state_port_); auto prev_fsm_state = discrete_state->get_mutable_vector(prev_fsm_state_idx_) - .get_mutable_value(); + .get_mutable_value(); // Find fsm_state in left_right_support_fsm_states - bool is_single_support_phase = (find(left_right_support_fsm_states_.begin(), - left_right_support_fsm_states_.end(), - fsm_state) - != left_right_support_fsm_states_.end()); + bool is_single_support_phase = + (find(left_right_support_fsm_states_.begin(), + left_right_support_fsm_states_.end(), + fsm_state) != left_right_support_fsm_states_.end()); // when entering a new state which is in left_right_support_fsm_states if (fsm_state != prev_fsm_state(0) && is_single_support_phase) { @@ -138,8 +138,9 @@ EventStatus AlipSwingFootTrajGenerator::DiscreteVariableUpdate( VectorXd q = robot_output->GetPositions(); multibody::SetPositionsIfNew(plant_, q, context_); - auto swing_foot_pos_at_liftoff = discrete_state->get_mutable_vector( - liftoff_swing_foot_pos_idx_).get_mutable_value(); + auto swing_foot_pos_at_liftoff = + discrete_state->get_mutable_vector(liftoff_swing_foot_pos_idx_) + .get_mutable_value(); auto swing_foot = swing_foot_map_.at(fsm_state); plant_.CalcPointsPositions(*context_, swing_foot.second, swing_foot.first, @@ -148,7 +149,7 @@ EventStatus AlipSwingFootTrajGenerator::DiscreteVariableUpdate( swing_foot_pos_at_liftoff = multibody::ReExpressWorldVector3InBodyYawFrame( plant_, *context_, "pelvis", swing_foot_pos_at_liftoff - - plant_.CalcCenterOfMassPositionInWorld(*context_)); + plant_.CalcCenterOfMassPositionInWorld(*context_)); } return EventStatus::Succeeded(); @@ -158,9 +159,7 @@ void AlipSwingFootTrajGenerator::CalcFootStepAndStanceFootHeight( const Context& context, const OutputVector* robot_output, const double end_time_of_this_interval, Vector2d* x_fs, double* stance_foot_height) const { - - int fsm_state = - this->EvalVectorInput(context, fsm_port_)->get_value()(0); + int fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value()(0); VectorXd q = robot_output->GetPositions(); multibody::SetPositionsIfNew(plant_, q, context_); @@ -172,17 +171,14 @@ void AlipSwingFootTrajGenerator::CalcFootStepAndStanceFootHeight( world_, &stance_foot_pos); Vector3d pelvis_x = - plant_.EvalBodyPoseInWorld(*context_, pelvis_) - .rotation().col(0); + plant_.EvalBodyPoseInWorld(*context_, pelvis_).rotation().col(0); double approx_pelvis_yaw = atan2(pelvis_x(1), pelvis_x(0)); Vector3d CoM_curr = plant_.CalcCenterOfMassPositionInWorld(*context_); Vector2d vdes_xy = this->EvalVectorInput(context, vdes_port_)->get_value(); - double L_y_des = vdes_xy(0) * - (CoM_curr(2) - stance_foot_pos(2)) * m_; - double L_x_offset = -vdes_xy(1) * - (CoM_curr(2) - stance_foot_pos(2)) * m_; + double L_y_des = vdes_xy(0) * (CoM_curr(2) - stance_foot_pos(2)) * m_; + double L_x_offset = -vdes_xy(1) * (CoM_curr(2) - stance_foot_pos(2)) * m_; // com and angular momentum prediction const drake::AbstractValue* alip_traj_p = @@ -198,25 +194,23 @@ void AlipSwingFootTrajGenerator::CalcFootStepAndStanceFootHeight( double omega = sqrt(9.81 / H); double T = duration_map_.at(fsm_state) + double_support_duration_; double L_x_n = m_ * H * footstep_offset_ * - (omega * sinh(omega * T) / (1 + cosh(omega * T))); - + (omega * sinh(omega * T) / (1 + cosh(omega * T))); Vector2d L_i = multibody::ReExpressWorldVector2InBodyYawFrame( - plant_, *context_,"pelvis", alip_pred.tail<2>()); - Vector2d L_f = is_right_support ? - Vector2d(L_x_offset + L_x_n, L_y_des) : - Vector2d(L_x_offset - L_x_n, L_y_des); - double p_x_ft_to_com = ( L_f(1) - cosh(omega*T) * L_i(1) ) / - (m_ * H * omega * sinh(omega*T)); - double p_y_ft_to_com = -( L_f(0) - cosh(omega*T) * L_i(0) ) / - (m_ * H * omega * sinh(omega*T)); + plant_, *context_, "pelvis", alip_pred.tail<2>()); + Vector2d L_f = is_right_support ? Vector2d(L_x_offset + L_x_n, L_y_des) + : Vector2d(L_x_offset - L_x_n, L_y_des); + double p_x_ft_to_com = + (L_f(1) - cosh(omega * T) * L_i(1)) / (m_ * H * omega * sinh(omega * T)); + double p_y_ft_to_com = + -(L_f(0) - cosh(omega * T) * L_i(0)) / (m_ * H * omega * sinh(omega * T)); *x_fs = Vector2d(-p_x_ft_to_com, -p_y_ft_to_com); /// Imposing guards // Impose half-plane guard Vector2d stance_foot_wrt_com_in_local_frame = multibody::ReExpressWorldVector2InBodyYawFrame( - plant_, *context_,"pelvis", (stance_foot_pos - CoM_curr).head<2>()); + plant_, *context_, "pelvis", (stance_foot_pos - CoM_curr).head<2>()); if (is_right_support) { double line_pos = std::max(center_line_offset_, stance_foot_wrt_com_in_local_frame(1)); @@ -236,7 +230,8 @@ void AlipSwingFootTrajGenerator::CalcFootStepAndStanceFootHeight( *stance_foot_height = stance_foot_pos(2) - CoM_curr(2); } -PiecewisePolynomial AlipSwingFootTrajGenerator::CreateSplineForSwingFoot( +PiecewisePolynomial +AlipSwingFootTrajGenerator::CreateSplineForSwingFoot( const double start_time_of_this_interval, const double end_time_of_this_interval, const double stance_duration, const Vector3d& init_swing_foot_pos, const Vector2d& x_fs, @@ -282,8 +277,8 @@ void AlipSwingFootTrajGenerator::CalcTrajs( drake::trajectories::Trajectory* traj) const { // Cast traj for polymorphism auto* pp_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); + (PiecewisePolynomial*)dynamic_cast*>( + traj); // Get discrete states const auto swing_foot_pos_at_liftoff = @@ -293,8 +288,7 @@ void AlipSwingFootTrajGenerator::CalcTrajs( this->EvalVectorInput(context, liftoff_time_port_)->get_value(); // Read in finite state machine - int fsm_state = - this->EvalVectorInput(context, fsm_port_)->get_value()(0); + int fsm_state = this->EvalVectorInput(context, fsm_port_)->get_value()(0); // Find fsm_state in left_right_support_fsm_states auto it = find(left_right_support_fsm_states_.begin(), @@ -319,7 +313,7 @@ void AlipSwingFootTrajGenerator::CalcTrajs( // creating trajectory. // Ensure "current_time < end_time" to avoid error in // creating trajectory. - start_time_of_this_interval = drake::math::saturate( + start_time_of_this_interval = std::clamp( start_time_of_this_interval, -std::numeric_limits::infinity(), end_time_of_this_interval - 0.001); diff --git a/systems/controllers/alip_traj_gen.cc b/systems/controllers/alip_traj_gen.cc index 88dd7e76db..ab3dcfb2eb 100644 --- a/systems/controllers/alip_traj_gen.cc +++ b/systems/controllers/alip_traj_gen.cc @@ -3,13 +3,11 @@ // #include "alip_traj_gen.h" -#include +#include #include #include -#include - using std::string; using std::vector; @@ -39,8 +37,8 @@ ALIPTrajGenerator::ALIPTrajGenerator( const vector& unordered_state_durations, const vector&>>>& - contact_points_in_each_state, const Eigen::MatrixXd& Q, - const Eigen::MatrixXd& R) + contact_points_in_each_state, + const Eigen::MatrixXd& Q, const Eigen::MatrixXd& R) : plant_(plant), context_(context), desired_com_height_(desired_com_height), @@ -48,18 +46,18 @@ ALIPTrajGenerator::ALIPTrajGenerator( unordered_state_durations_(unordered_state_durations), contact_points_in_each_state_(contact_points_in_each_state), world_(plant_.world_frame()) { - DRAKE_DEMAND(unordered_fsm_states.size() == unordered_state_durations.size()); - DRAKE_DEMAND(unordered_fsm_states.size() == contact_points_in_each_state.size()); + DRAKE_DEMAND(unordered_fsm_states.size() == + contact_points_in_each_state.size()); this->set_name("ALIP_traj"); // Input/Output Setup state_port_ = this->DeclareVectorInputPort( - "x, u, t", OutputVector(plant.num_positions(), - plant.num_velocities(), - plant.num_actuators())) - .get_index(); + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); touchdown_time_port_ = @@ -69,47 +67,45 @@ ALIPTrajGenerator::ALIPTrajGenerator( // Provide an instance to allocate the memory first (for the output) ExponentialPlusPiecewisePolynomial exp; drake::trajectories::Trajectory& traj_inst = exp; - output_port_com_ = - this->DeclareAbstractOutputPort("alip_com_prediction", traj_inst, - &ALIPTrajGenerator::CalcComTrajFromCurrent) - .get_index(); - output_port_alip_state_ = - this->DeclareAbstractOutputPort("alip x, y, Lx, Ly prediction", - traj_inst, - &ALIPTrajGenerator::CalcAlipTrajFromCurrent) - .get_index(); + output_port_com_ = this->DeclareAbstractOutputPort( + "alip_com_prediction", traj_inst, + &ALIPTrajGenerator::CalcComTrajFromCurrent) + .get_index(); + output_port_alip_state_ = this->DeclareAbstractOutputPort( + "alip x, y, Lx, Ly prediction", traj_inst, + &ALIPTrajGenerator::CalcAlipTrajFromCurrent) + .get_index(); m_ = plant_.CalcTotalMass(*context); MatrixXd A = CalcA(desired_com_height); - MatrixXd B = -MatrixXd::Identity(4,2); - MatrixXd C = MatrixXd::Identity(4,4); - MatrixXd G = MatrixXd::Identity(4,4); + MatrixXd B = -MatrixXd::Identity(4, 2); + MatrixXd C = MatrixXd::Identity(4, 4); + MatrixXd G = MatrixXd::Identity(4, 4); S2SKalmanFilterData filter_data = {A, B, C, Q, R, G}; S2SKalmanFilter filter = S2SKalmanFilter(filter_data); - std::pair model_filter = {filter, filter_data}; - alip_filter_idx_ = this->DeclareAbstractState( - drake::Value>(model_filter)); + std::pair model_filter = {filter, + filter_data}; + alip_filter_idx_ = this->DeclareAbstractState( + drake::Value>( + model_filter)); prev_foot_idx_ = this->DeclareDiscreteState(Vector2d::Zero()); prev_fsm_idx_ = this->DeclareDiscreteState(-1 * VectorXd::Ones(1)); - com_z_idx_ = this->DeclareDiscreteState( - desired_com_height * VectorXd::Ones(1)); + com_z_idx_ = + this->DeclareDiscreteState(desired_com_height * VectorXd::Ones(1)); this->DeclarePerStepUnrestrictedUpdateEvent( &ALIPTrajGenerator::UnrestrictedUpdate); } drake::systems::EventStatus ALIPTrajGenerator::UnrestrictedUpdate( - const drake::systems::Context &context, - drake::systems::State *state) const { - + const drake::systems::Context& context, + drake::systems::State* state) const { int prev_fsm = state->get_discrete_state(prev_fsm_idx_).value()(0); - auto& [filter, filter_data] = - state->get_mutable_abstract_state>(alip_filter_idx_); + auto& [filter, filter_data] = state->get_mutable_abstract_state< + std::pair>(alip_filter_idx_); // Read in current state const OutputVector* robot_output = @@ -124,8 +120,8 @@ drake::systems::EventStatus ALIPTrajGenerator::UnrestrictedUpdate( // calculate current estimate of ALIP state Vector3d CoM, L, stance_foot_pos; - CalcAlipState(robot_output->GetState(), mode_index, - &CoM, &L, &stance_foot_pos); + CalcAlipState(robot_output->GetState(), mode_index, &CoM, &L, + &stance_foot_pos); Vector4d x_alip; x_alip.head(2) = CoM.head(2) - stance_foot_pos.head(2); @@ -137,25 +133,30 @@ drake::systems::EventStatus ALIPTrajGenerator::UnrestrictedUpdate( filter.Update(filter_data, Vector2d::Zero(), x_alip, robot_output->get_timestamp()); } else { - Vector2d prev_stance_pos = state->get_discrete_state(prev_foot_idx_).value(); - filter.Update(filter_data, stance_foot_pos.head<2>() - prev_stance_pos, x_alip, - robot_output->get_timestamp()); - state->get_mutable_discrete_state(prev_fsm_idx_).get_mutable_value() << fsm_state; + Vector2d prev_stance_pos = + state->get_discrete_state(prev_foot_idx_).value(); + filter.Update(filter_data, stance_foot_pos.head<2>() - prev_stance_pos, + x_alip, robot_output->get_timestamp()); + state->get_mutable_discrete_state(prev_fsm_idx_).get_mutable_value() + << fsm_state; } - state->get_mutable_discrete_state(com_z_idx_).get_mutable_value() << CoM.tail(1) - stance_foot_pos.tail(1); - state->get_mutable_discrete_state(prev_foot_idx_).get_mutable_value() << stance_foot_pos.head<2>(); + state->get_mutable_discrete_state(com_z_idx_).get_mutable_value() + << CoM.tail(1) - stance_foot_pos.tail(1); + state->get_mutable_discrete_state(prev_foot_idx_).get_mutable_value() + << stance_foot_pos.head<2>(); return EventStatus::Succeeded(); } -ExponentialPlusPiecewisePolynomial ALIPTrajGenerator::ConstructAlipComTraj( - const Vector3d& CoM, const Vector3d& stance_foot_pos, const Vector4d& x_alip, - double start_time, double end_time_of_this_fsm_state) const { - +ExponentialPlusPiecewisePolynomial +ALIPTrajGenerator::ConstructAlipComTraj( + const Vector3d& CoM, const Vector3d& stance_foot_pos, + const Vector4d& x_alip, double start_time, + double end_time_of_this_fsm_state) const { double CoM_wrt_foot_z = (CoM(2) - stance_foot_pos(2)); DRAKE_DEMAND(CoM_wrt_foot_z > 0); // create a 3D one-segment polynomial for ExponentialPlusPiecewisePolynomial - Vector2d T_waypoint_com {start_time, end_time_of_this_fsm_state}; + Vector2d T_waypoint_com{start_time, end_time_of_this_fsm_state}; MatrixXd Y = MatrixXd::Zero(3, 2); Y.col(0).head(2) = stance_foot_pos.head(2); Y.col(1).head(2) = stance_foot_pos.head(2); @@ -163,12 +164,11 @@ ExponentialPlusPiecewisePolynomial ALIPTrajGenerator::ConstructAlipComTr // We add stance_foot_pos(2) to desired COM height to account for state // drifting double max_height_diff_per_step = 0.05; - double final_height = drake::math::saturate( + double final_height = std::clamp( desired_com_height_ + stance_foot_pos(2), - CoM(2) - max_height_diff_per_step, - CoM(2) + max_height_diff_per_step); + CoM(2) - max_height_diff_per_step, CoM(2) + max_height_diff_per_step); // double final_height = desired_com_height_ + stance_foot_pos(2); - Y(2,0) = final_height; + Y(2, 0) = final_height; Y(2, 1) = final_height; Vector3d Y_dot_start = Vector3d::Zero(); @@ -176,18 +176,15 @@ ExponentialPlusPiecewisePolynomial ALIPTrajGenerator::ConstructAlipComTr PiecewisePolynomial pp_part = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - T_waypoint_com, Y, - Y_dot_start, Y_dot_end); + T_waypoint_com, Y, Y_dot_start, Y_dot_end); - MatrixXd K = MatrixXd::Zero(3,4); - K.topLeftCorner(2,2) = MatrixXd::Identity(2,2); + MatrixXd K = MatrixXd::Zero(3, 4); + K.topLeftCorner(2, 2) = MatrixXd::Identity(2, 2); auto A = CalcA(CoM_wrt_foot_z); - return ExponentialPlusPiecewisePolynomial( - K, A, x_alip, pp_part); + return ExponentialPlusPiecewisePolynomial(K, A, x_alip, pp_part); } - Eigen::MatrixXd ALIPTrajGenerator::CalcA(double com_z) const { // Dynamics of ALIP: (eqn 6) https://arxiv.org/pdf/2109.14862.pdf const double g = 9.81; @@ -205,27 +202,25 @@ Eigen::MatrixXd ALIPTrajGenerator::CalcA(double com_z) const { return A; } -ExponentialPlusPiecewisePolynomial ALIPTrajGenerator::ConstructAlipStateTraj( +ExponentialPlusPiecewisePolynomial +ALIPTrajGenerator::ConstructAlipStateTraj( const Eigen::Vector4d& x_alip, double com_z, double start_time, double end_time_of_this_fsm_state) const { - Vector2d breaks = {start_time, end_time_of_this_fsm_state}; PiecewisePolynomial pp_part = PiecewisePolynomial::CubicWithContinuousSecondDerivatives( - breaks, MatrixXd::Zero(4,2), - Vector4d::Zero(), Vector4d::Zero()); - MatrixXd K = MatrixXd::Identity(4,4); + breaks, MatrixXd::Zero(4, 2), Vector4d::Zero(), Vector4d::Zero()); + MatrixXd K = MatrixXd::Identity(4, 4); - return ExponentialPlusPiecewisePolynomial( - K, CalcA(com_z), x_alip, pp_part); + return ExponentialPlusPiecewisePolynomial(K, CalcA(com_z), x_alip, + pp_part); } void ALIPTrajGenerator::CalcAlipState( - const Eigen::VectorXd &x, int mode_index, + const Eigen::VectorXd& x, int mode_index, const drake::EigenPtr& CoM_p, const drake::EigenPtr& L_p, const drake::EigenPtr& stance_pos_p) const { - multibody::SetPositionsAndVelocitiesIfNew(plant_, x, context_); Vector3d CoM = plant_.CalcCenterOfMassPositionInWorld(*context_); @@ -239,17 +234,18 @@ void ALIPTrajGenerator::CalcAlipState( } stance_foot_pos /= contact_points_in_each_state_[mode_index].size(); - Vector3d L = plant_.CalcSpatialMomentumInWorldAboutPoint( - *context_, stance_foot_pos).rotational(); + Vector3d L = + plant_.CalcSpatialMomentumInWorldAboutPoint(*context_, stance_foot_pos) + .rotational(); *CoM_p = CoM; *L_p = L; *stance_pos_p = stance_foot_pos; } -void ALIPTrajGenerator::CalcComTrajFromCurrent(const drake::systems::Context< - double> &context, drake::trajectories::Trajectory *traj) const { - +void ALIPTrajGenerator::CalcComTrajFromCurrent( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { // Read in current state const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); @@ -267,18 +263,18 @@ void ALIPTrajGenerator::CalcComTrajFromCurrent(const drake::systems::Context< double timestamp = robot_output->get_timestamp(); double start_time = timestamp; double end_time = prev_event_time(0) + unordered_state_durations_[mode_index]; - start_time = drake::math::saturate(start_time, - -std::numeric_limits::infinity(), - end_time - 0.001); + start_time = std::clamp( + start_time, -std::numeric_limits::infinity(), end_time - 0.001); Vector3d CoM, L, stance_foot_pos; - CalcAlipState( - robot_output->GetState(), mode_index, - &CoM, &L, &stance_foot_pos); + CalcAlipState(robot_output->GetState(), mode_index, &CoM, &L, + &stance_foot_pos); Vector4d x_alip = - context.get_abstract_state>(alip_filter_idx_).first.x(); + context + .get_abstract_state>( + alip_filter_idx_) + .first.x(); // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< @@ -287,8 +283,9 @@ void ALIPTrajGenerator::CalcComTrajFromCurrent(const drake::systems::Context< ConstructAlipComTraj(CoM, stance_foot_pos, x_alip, start_time, end_time); } -void ALIPTrajGenerator::CalcAlipTrajFromCurrent(const drake::systems::Context< - double> &context, drake::trajectories::Trajectory *traj) const { +void ALIPTrajGenerator::CalcAlipTrajFromCurrent( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { // Read in current state const OutputVector* robot_output = (OutputVector*)this->EvalVectorInput(context, state_port_); @@ -306,27 +303,25 @@ void ALIPTrajGenerator::CalcAlipTrajFromCurrent(const drake::systems::Context< double timestamp = robot_output->get_timestamp(); double start_time = timestamp; double end_time = prev_event_time(0) + unordered_state_durations_[mode_index]; - start_time = drake::math::saturate(start_time, - -std::numeric_limits::infinity(), - end_time - 0.001); + start_time = std::clamp( + start_time, -std::numeric_limits::infinity(), end_time - 0.001); // Assign traj auto exp_pp_traj = (ExponentialPlusPiecewisePolynomial*)dynamic_cast< ExponentialPlusPiecewisePolynomial*>(traj); Vector4d x_alip = - context.get_abstract_state>( - alip_filter_idx_).first.x(); + context + .get_abstract_state>( + alip_filter_idx_) + .first.x(); double com_z = context.get_discrete_state(com_z_idx_).value()(0); - *exp_pp_traj = - ConstructAlipStateTraj(x_alip, com_z, start_time, end_time); + *exp_pp_traj = ConstructAlipStateTraj(x_alip, com_z, start_time, end_time); } int ALIPTrajGenerator::GetModeIdx(int fsm_state) const { - auto it = find(unordered_fsm_states_.begin(), - unordered_fsm_states_.end(), + auto it = find(unordered_fsm_states_.begin(), unordered_fsm_states_.end(), fsm_state); int mode_index = std::distance(unordered_fsm_states_.begin(), it); DRAKE_DEMAND(it != unordered_fsm_states_.end()); @@ -335,4 +330,3 @@ int ALIPTrajGenerator::GetModeIdx(int fsm_state) const { } // namespace systems } // namespace dairlib - diff --git a/systems/controllers/lipm_traj_gen.cc b/systems/controllers/lipm_traj_gen.cc index c986e44255..a3f7163d0f 100644 --- a/systems/controllers/lipm_traj_gen.cc +++ b/systems/controllers/lipm_traj_gen.cc @@ -5,8 +5,6 @@ #include #include -#include - using std::cout; using std::endl; using std::string; @@ -183,10 +181,10 @@ EventStatus LIPMTrajGenerator::DiscreteVariableUpdate( // foot_spread_ub_ meter: ratio 0.9 // Linear interpolate in between - heuristic_ratio_ = drake::math::saturate( + heuristic_ratio_ = std::clamp( 1 + (0.9 - 1) / (foot_spread_ub_ - foot_spread_lb_) * (dist - foot_spread_lb_), - 0.9, 1); + 0.9, 1.0); } discrete_state->get_mutable_vector(prev_fsm_idx_).GetAtIndex(0) = fsm_state; @@ -218,7 +216,7 @@ ExponentialPlusPiecewisePolynomial LIPMTrajGenerator::ConstructLipmTraj( // We add stance_foot_pos(2) to desired COM height to account for state // drifting double max_height_diff_per_step = 0.05; - double final_height = drake::math::saturate( + double final_height = std::clamp( desired_com_height_ + stance_foot_pos(2), CoM(2) - max_height_diff_per_step, CoM(2) + max_height_diff_per_step); // double final_height = desired_com_height_ + stance_foot_pos(2); @@ -301,7 +299,7 @@ void LIPMTrajGenerator::CalcTrajFromCurrent( double end_time = prev_event_time(0) + unordered_state_durations_[mode_index]; // Ensure "current_time < end_time" to avoid error in // creating trajectory. - start_time = drake::math::saturate( + start_time = std::clamp( start_time, -std::numeric_limits::infinity(), end_time - 0.001); VectorXd q = robot_output->GetPositions(); diff --git a/systems/controllers/swing_ft_traj_gen.cc b/systems/controllers/swing_ft_traj_gen.cc index 9020d1288f..1322b801e9 100644 --- a/systems/controllers/swing_ft_traj_gen.cc +++ b/systems/controllers/swing_ft_traj_gen.cc @@ -6,7 +6,6 @@ #include #include -#include #include "systems/controllers/control_utils.h" using std::string; @@ -427,7 +426,7 @@ void SwingFootTrajGenerator::CalcTrajs( // creating trajectory. // Ensure "current_time < end_time" to avoid error in // creating trajectory. - start_time_of_this_interval = drake::math::saturate( + start_time_of_this_interval = std::clamp( start_time_of_this_interval, -std::numeric_limits::infinity(), end_time_of_this_interval - 0.001); From 1acb89f508f11cef8af64f19665b8b201a94eff6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 19 Apr 2023 12:15:52 -0400 Subject: [PATCH 464/758] drake master changes --- .../franka/franka_c3_options_translation.yaml | 2 +- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/franka_visualizer.cc | 1 + examples/franka/urdf/franka.urdf | 16 ++++++++-------- examples/franka/urdf/franka_no_collision.urdf | 16 ++++++++-------- examples/franka/urdf/tray.sdf | 3 +++ 6 files changed, 22 insertions(+), 18 deletions(-) diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index cb3a1a83bc..20456dd24e 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -6,7 +6,7 @@ delta_option: 1 mu: 0.2 mu_plate: 1 -dt: 0.08 +dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 86e74c0c4b..06fb7e961b 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -5,7 +5,7 @@ franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.005 -visualize: true +visualize: false dt: 0.0001 realtime_rate: 0.5 diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index f55cd21c08..ef2607a115 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -137,6 +137,7 @@ int do_main(int argc, char* argv[]) { // DrakeVisualizer::AddToBuilder(&builder, scene_graph); drake::geometry::MeshcatVisualizerParams params; params.publish_period = 1.0 / 60.0; + params.enable_alpha_slider = true; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index b215cfac27..bd5c985787 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -15,7 +15,7 @@ - + @@ -113,7 +113,7 @@ - + @@ -170,7 +170,7 @@ - + @@ -227,7 +227,7 @@ - + @@ -278,7 +278,7 @@ - + @@ -341,7 +341,7 @@ - + @@ -434,7 +434,7 @@ - + @@ -485,7 +485,7 @@ - + diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 1dc88eafb6..0a824c84a6 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -17,7 +17,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link0.obj"/> @@ -33,7 +33,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link1.obj"/> @@ -56,7 +56,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link2.obj"/> @@ -79,7 +79,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link3.obj"/> @@ -102,7 +102,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link4.obj"/> @@ -125,7 +125,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link5.obj"/> @@ -148,7 +148,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link6.obj"/> @@ -171,7 +171,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link7.obj"/> diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 647583fc90..0002dfed07 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -21,6 +21,9 @@ 0.6 0.6 0.02 + + 0.3 0.3 0.3 1 + From 5095497b6e600b030afe730de18899d365301553 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 19 Apr 2023 16:52:17 -0400 Subject: [PATCH 465/758] need to fix jitter --- examples/Cassie/cassie_xbox_remote.py | 18 ++++++---- .../franka/franka_c3_controller_params.yaml | 10 +++--- .../franka/franka_c3_options_floating.yaml | 4 +-- .../franka/franka_c3_options_translation.yaml | 6 ++-- examples/franka/franka_sim_params.yaml | 4 +-- examples/franka/urdf/franka.urdf | 4 +-- examples/franka/urdf/franka_no_collision.urdf | 4 +-- .../urdf/plate_end_effector_translation.urdf | 6 ++-- examples/franka/urdf/tray.sdf | 4 +-- systems/controllers/c3_controller.cc | 9 +++-- .../lcm_trajectory_systems.cc | 34 ++++++++++++++----- 11 files changed, 63 insertions(+), 40 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 85c732be9e..0209e45962 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -56,7 +56,8 @@ def main(): done = False i = 0 - latching_switch = 1 + latching_switch_a = 1 + latching_switch_b = 1 while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands @@ -72,20 +73,23 @@ def main(): if event.type == pygame.JOYBUTTONDOWN: if event.button == 0: - latching_switch = not latching_switch + latching_switch_a = not latching_switch_a + if event.button == 1: + latching_switch_b = not latching_switch_b # Send LCM message radio_msg = dairlib.lcmt_radio_out() radio_msg.channel[0] = -joystick.get_axis(1) radio_msg.channel[1] = -joystick.get_axis(0) - # radio_msg.channel[2] = -joystick.get_axis(4) - # radio_msg.channel[3] = joystick.get_axis(3) - radio_msg.channel[2] = -joystick.get_axis(3) - radio_msg.channel[3] = joystick.get_axis(2) + radio_msg.channel[2] = -joystick.get_axis(4) + radio_msg.channel[3] = joystick.get_axis(3) + # radio_msg.channel[2] = -joystick.get_axis(3) + # radio_msg.channel[3] = joystick.get_axis(2) - radio_msg.channel[14] = latching_switch + radio_msg.channel[13] = latching_switch_b + radio_msg.channel[14] = latching_switch_a # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 94cf6f8803..8a43576ba2 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,5 @@ -c3_options_file: examples/franka/franka_c3_options_translation.yaml -#c3_options_file: examples/franka/franka_c3_options_floating.yaml +#c3_options_file: examples/franka/franka_c3_options_translation.yaml +c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,10 +7,10 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -include_end_effector_orientation: false +include_end_effector_orientation: true diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index 91cda4b7aa..c2ba92e8b0 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -23,10 +23,10 @@ u_size: 49 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 50, 50, 50, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [200, 200, 500, 1, 1, 1, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 0.1, 0.1, 0.1] -q_des_vector: [0.5, 0.02, 0.41, 0, 0, 0, 1, 0, 0, 0, 0.5, 0.02, 0.3] +q_des_vector: [0.55, 0.02, 0.43, 0, 0, 0, 1, 0, 0, 0, 0.55, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 20456dd24e..edc53ef93b 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -1,10 +1,10 @@ -admm_iter: 4 +admm_iter: 3 rho: 0.1 rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.2 +mu: 0.4 mu_plate: 1 dt: 0.1 solve_dt: 0.05 @@ -26,5 +26,5 @@ q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.5, 0.02, 0.43, 1, 0, 0, 0, 0.5, 0.02, 0.45] +q_des_vector: [0.55, 0.02, 0.43, 1, 0, 0, 0, 0.55, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 06fb7e961b..deca91edd0 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -4,10 +4,10 @@ tray_state_channel: TRAY_OUTPUT franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true -actuator_delay: 0.005 +actuator_delay: 0.000 visualize: false dt: 0.0001 -realtime_rate: 0.5 +realtime_rate: 1.0 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index bd5c985787..0735580de0 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -523,7 +523,7 @@ - + @@ -535,7 +535,7 @@ - + diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 0a824c84a6..14ee2543a5 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -197,7 +197,7 @@ - + @@ -209,7 +209,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 75d8f4ee0d..7a1b4cfbcc 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -37,19 +37,19 @@ - + - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 0002dfed07..e86b324b24 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -45,8 +45,8 @@ - 0.2 - 0.2 + 0.4 + 0.4 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index f8967c9ec5..5c0cce8abc 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -110,10 +110,13 @@ drake::systems::EventStatus C3Controller::ComputePlan( VectorXd x_des_adjusted = x_des.value(); VectorXd current = x_des_adjusted.head(n_q_).tail(3); - current(0) += radio_out->channel[0] * 0.4; - current(1) += radio_out->channel[1] * 0.4; - current(2) += radio_out->channel[2] * 0.4; + current(0) += radio_out->channel[0] * 0.2; + current(1) += radio_out->channel[1] * 0.2; + current(2) += radio_out->channel[2] * 0.2; x_des_adjusted.head(n_q_).tail(3) = current; + if (radio_out->channel[13] > 0){ + x_des_adjusted.head(3) = current; + } // std::cout << x_des_adjusted.transpose() << std::endl; std::vector x_desired = diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index fb25a34f69..793aec2fb6 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -173,18 +173,34 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, rgba_); -// if (lcm_traj_.HasTrajectory("end_effector_orientation_target")) { + if (lcm_traj_.HasTrajectory("end_effector_orientation_target")) { + const auto orientation_block = + lcm_traj_.GetTrajectory("end_effector_orientation_target"); + auto trajectory = PiecewisePolynomial::CubicHermite( + orientation_block.time_vector, orientation_block.datapoints.topRows(3), + orientation_block.datapoints.bottomRows(3)); + for (int i = 0; i < line_points.cols(); ++i) { + auto pose = drake::math::RigidTransform( + drake::math::RollPitchYaw(trajectory.value(breaks(i))), + line_points.col(i)); + auto box = drake::geometry::Box(0.1, 0.1, 0.01); + meshcat_->SetObject("end_effector" + std::to_string(i), box, rgba_); + meshcat_->SetTransform("end_effector" + std::to_string(i), pose); + } + } +// if (lcm_traj_.HasTrajectory("object_orientation_target")) { // const auto orientation_block = -// lcm_traj_.GetTrajectory("end_effector_orientation_target"); -// auto trajectory = PiecewisePolynomial::CubicHermite( -// orientation_block.time_vector, orientation_block.datapoints.topRows(3), -// orientation_block.datapoints.bottomRows(3)); -// for (int i = 0; i < line_points.cols(); ++i) { +// lcm_traj_.GetTrajectory("object_orientation_target"); +// for (int i = 0; i < orientation_block.datapoints.cols(); ++i) { // auto pose = drake::math::RigidTransform( -// drake::math::RollPitchYaw(trajectory.value(breaks(i))), line_points.col(i)); +// Quaterniond(orientation_block.datapoints(0, i), +// orientation_block.datapoints(1, i), +// orientation_block.datapoints(2, i), +// orientation_block.datapoints(3, i)), +// line_points.col(i)); // auto box = drake::geometry::Box(0.1, 0.1, 0.01); -// meshcat_->SetObject("box" + std::to_string(i), box, rgba_); -// meshcat_->SetTransform("box" + std::to_string(i), pose); +// meshcat_->SetObject("object" + std::to_string(i), box, rgba_); +// meshcat_->SetTransform("object" + std::to_string(i), pose); // } // } From f4b85c446522004dd1b90ce8cf869eb4933f6531 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 20 Apr 2023 12:58:16 -0400 Subject: [PATCH 466/758] small plotting changes for proposal --- .../plot_five_link_biped.py | 16 +++++++++++++++- bindings/pydairlib/common/plot_styler.py | 6 +++++- 2 files changed, 20 insertions(+), 2 deletions(-) diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 5ac493a237..fa974e92eb 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -151,10 +151,24 @@ def main(): ydot_post = J_r @ v_post # transform = J_r @ M_inv @ J_r.T @ np.linalg.pinv(J_r @ M_inv @ J_r.T) transform = M_inv @ J_r.T @ np.linalg.pinv(J_y @ M_inv @ J_r.T) - + joint_vel_plot = plot_styler.PlotStyler() + start_time = state_traj.start_time() + end_time = state_traj.end_time() + t = np.linspace(start_time, end_time, 1000) + v_samples = [] + for i in t: + v_samples.append(state_traj.value(i)[10:14, 0]) + joint_vel_plot.plot(t, v_samples, xlabel='Time (s)', ylabel='Velocity (rad/s)', grid=False) + joint_vel_plot.add_legend(["Left Hip", "Right Hip", "Left Knee", "Right Knee"]) + joint_vel_plot.tight_layout() + joint_vel_plot.save_fig('rabbit_joint_vel.png') + plt.show() start_time = t_impact - 2 * window_length end_time = t_impact + 2 * window_length + + + start_idx = np.argwhere(np.abs(robot_output['t_x'] - start_time) < 1e-3)[0][0] end_idx = np.argwhere(np.abs(robot_output['t_x'] - end_time) < 1e-3)[0][0] t = np.linspace(start_time, end_time, diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 6dc1c9503b..81a78f1293 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -33,6 +33,10 @@ def __init__(self, figure=None, nrows=1, ncols=1): # self.directory = None self.dpi = 200 self.directory = '/home/yangwill/Pictures/plot_styler/' + plt.rc('legend', fontsize=14) + plt.rc('axes', labelsize=14, titlesize=14) + plt.rc('xtick', labelsize=14) + plt.rc('ytick', labelsize=14) matplotlib.rcParams['figure.figsize'] = 12, 7 matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" @@ -111,5 +115,5 @@ def set_subplot_options(self, sharex=None, sharey=None): plt.setp(self.axes, sharex=sharey) def tight_layout(self): - self.axes[0].autoscale(enable=True, axis='y', tight=True) + # self.axes[0].autoscale(enable=True, axis='y', tight=True) self.axes[0].autoscale(enable=True, axis='x', tight=True) From a2472e1b389dac35ed03ea921c42570196b4dad8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 20 Apr 2023 18:15:35 -0400 Subject: [PATCH 467/758] solve time of c3 does cause jump in desired state, can look into faster solves --- bindings/pydairlib/analysis/log_plotter_franka.py | 2 +- ...ranslation.yaml => franka_translation_plot.yaml} | 4 ++-- examples/franka/franka_c3_controller.cc | 6 ++++-- examples/franka/franka_c3_controller_params.h | 3 +++ examples/franka/franka_c3_controller_params.yaml | 13 ++++++++----- examples/franka/franka_c3_options_translation.yaml | 4 ++-- examples/franka/franka_controller_params.h | 3 +++ examples/franka/franka_controller_params.yaml | 6 ++++-- examples/franka/franka_osc_controller.cc | 2 +- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/urdf/tray.sdf | 8 ++++---- 11 files changed, 33 insertions(+), 20 deletions(-) rename bindings/pydairlib/analysis/plot_configs/{franka_translation.yaml => franka_translation_plot.yaml} (96%) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 57472e6b00..150b0c48b9 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -12,7 +12,7 @@ def main(): - config_file = 'bindings/pydairlib/analysis/plot_configs/franka_translation.yaml' + config_file = 'bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml' plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml similarity index 96% rename from bindings/pydairlib/analysis/plot_configs/franka_translation.yaml rename to bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 422435e6ec..3a6cda6871 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -4,9 +4,9 @@ channel_u: "FRANKA_INPUT" channel_osc: "OSC_DEBUG_FRANKA" use_default_styling: false -start_time: 2 +start_time: 0 #duration: 0.47 -duration: 50 +duration: -1 # Plant properties diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index ac3bd33c77..f90e1859d8 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -155,11 +155,13 @@ int DoMain(int argc, char* argv[]) { auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( controller_params.c3_channel_actor, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 0.2)); + TriggerTypeSet({TriggerType::kPeriodic}), + 1 / controller_params.target_frequency)); auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( controller_params.c3_channel_object, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 0.2)); + TriggerTypeSet({TriggerType::kPeriodic}), + 1 / controller_params.target_frequency)); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( controller_params.radio_channel, &lcm)); diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index c8e5102993..e1573819e7 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -18,9 +18,11 @@ struct FrankaC3ControllerParams { std::string plate_model; std::string tray_model; bool include_end_effector_orientation; + double target_frequency; template void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(c3_options_file)); a->Visit(DRAKE_NVP(c3_channel_actor)); a->Visit(DRAKE_NVP(c3_channel_object)); @@ -30,5 +32,6 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(plate_model)); a->Visit(DRAKE_NVP(tray_model)); a->Visit(DRAKE_NVP(include_end_effector_orientation)); + a->Visit(DRAKE_NVP(target_frequency)); } }; \ No newline at end of file diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 8a43576ba2..ce21cc9a46 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -1,5 +1,6 @@ -#c3_options_file: examples/franka/franka_c3_options_translation.yaml -c3_options_file: examples/franka/franka_c3_options_floating.yaml + +c3_options_file: examples/franka/franka_c3_options_translation.yaml +#c3_options_file: examples/franka/franka_c3_options_floating.yaml c3_channel_actor: C3_TRAJECTORY_ACTOR c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT @@ -7,10 +8,12 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: examples/franka/urdf/franka.urdf -#plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -plate_model: examples/franka/urdf/plate_end_effector_floating.urdf +plate_model: examples/franka/urdf/plate_end_effector_translation.urdf +#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -include_end_effector_orientation: true +include_end_effector_orientation: false +# Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan +target_frequency: 5 diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index edc53ef93b..d888f0877f 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.4 +mu: 0.3 mu_plate: 1 dt: 0.1 solve_dt: 0.05 @@ -26,5 +26,5 @@ q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.55, 0.02, 0.43, 1, 0, 0, 0, 0.55, 0.02, 0.45] +q_des_vector: [0.55, 0.02, 0.41, 1, 0, 0, 0, 0.55, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index 489288c62d..eff0e18c20 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -14,6 +14,8 @@ struct FrankaControllerParams : OSCGains { std::string osc_debug_channel; std::string c3_channel; + std::string franka_model; + double end_effector_acceleration; bool track_end_effector_orientation; @@ -46,6 +48,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(radio_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_channel)); + a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(track_end_effector_orientation)); a->Visit(DRAKE_NVP(EndEffectorW)); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 12ae4cc3d1..2c69c960bb 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -5,15 +5,17 @@ radio_channel: CASSIE_VIRTUAL_RADIO osc_debug_channel: OSC_DEBUG_FRANKA c3_channel: C3_TRAJECTORY_ACTOR +franka_model: examples/franka/urdf/franka.urdf + w_input: 0.00 w_input_reg: 0.001 -w_accel: 0.001 +w_accel: 0.0001 w_soft_constraint: 10000 w_lambda: 0.1 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 20.0 +end_effector_acceleration: 50.0 track_end_effector_orientation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index a241923d1a..e09b0442d2 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -74,7 +74,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); Parser parser(&plant, nullptr); - parser.AddModelFromFile("examples/franka/urdf/franka.urdf"); + parser.AddModelFromFile(controller_params.franka_model); RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index deca91edd0..561881a2de 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.000 visualize: false dt: 0.0001 -realtime_rate: 1.0 +realtime_rate: 0.05 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index e86b324b24..38c037a217 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -3,14 +3,14 @@ - 2 + 2.5 0.06 0 0 - 0.015 + 0.06 0 0.075 @@ -45,8 +45,8 @@ - 0.4 - 0.4 + 0.3 + 0.3 From dccb432d884710f02b6f4165964c3009a99cae34 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 24 Apr 2023 16:39:32 -0400 Subject: [PATCH 468/758] moving to more physical setups --- .../franka/franka_c3_options_translation.yaml | 2 +- examples/franka/franka_controller_params.yaml | 4 ++-- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/urdf/franka.urdf | 4 ++-- examples/franka/urdf/franka_no_collision.urdf | 4 ++-- examples/franka/urdf/tray.sdf | 16 ++++++++-------- .../lcm_trajectory_systems.cc | 8 ++++---- 7 files changed, 20 insertions(+), 20 deletions(-) diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index d888f0877f..2d0af6c969 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.3 +mu: 0.4 mu_plate: 1 dt: 0.1 solve_dt: 0.05 diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 2c69c960bb..e25e3caf1c 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -42,11 +42,11 @@ EndEffectorKd: MidLinkW: [0, 0, 0, 0, 0, 0, - 0, 0, 1] + 0, 0, 2] MidLinkKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 100 ] + 0, 0, 1000 ] MidLinkKd: [ 0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 561881a2de..06e8abe04b 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.000 visualize: false dt: 0.0001 -realtime_rate: 0.05 +realtime_rate: 0.2 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index 0735580de0..bd5c985787 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -523,7 +523,7 @@ - + @@ -535,7 +535,7 @@ - + diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 14ee2543a5..0a824c84a6 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -197,7 +197,7 @@ - + @@ -209,7 +209,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 38c037a217..f32a869569 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -3,22 +3,22 @@ - 2.5 + 0.5 - 0.06 + 0.00668 0 0 - 0.06 + 0.00668 0 - 0.075 + 0.01333 - 0.6 0.6 0.02 + 0.4 0.4 0.02 @@ -28,7 +28,7 @@ - 0.6 0.6 0.02 + 0.4 0.4 0.02 @@ -45,8 +45,8 @@ - 0.3 - 0.3 + 0.4 + 0.4 diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 793aec2fb6..dcb4f7ff68 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -184,8 +184,8 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( drake::math::RollPitchYaw(trajectory.value(breaks(i))), line_points.col(i)); auto box = drake::geometry::Box(0.1, 0.1, 0.01); - meshcat_->SetObject("end_effector" + std::to_string(i), box, rgba_); - meshcat_->SetTransform("end_effector" + std::to_string(i), pose); + meshcat_->SetObject("/trajectories/end_effector" + std::to_string(i), box, rgba_); + meshcat_->SetTransform("/trajectories/end_effector" + std::to_string(i), pose); } } // if (lcm_traj_.HasTrajectory("object_orientation_target")) { @@ -199,8 +199,8 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( // orientation_block.datapoints(3, i)), // line_points.col(i)); // auto box = drake::geometry::Box(0.1, 0.1, 0.01); -// meshcat_->SetObject("object" + std::to_string(i), box, rgba_); -// meshcat_->SetTransform("object" + std::to_string(i), pose); +// meshcat_->SetObject("/trajectories/object" + std::to_string(i), box, rgba_); +// meshcat_->SetTransform("/trajectories/object" + std::to_string(i), pose); // } // } From e065161c5595b09d73392db533f9ca97716ee60d Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 25 Apr 2023 10:44:54 -0400 Subject: [PATCH 469/758] adding transparency to vis --- examples/franka/franka_controller_params.yaml | 2 +- examples/franka/franka_sim_params.yaml | 2 +- .../trajectory_optimization/lcm_trajectory_systems.cc | 10 ++++++++-- 3 files changed, 10 insertions(+), 4 deletions(-) diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index e25e3caf1c..65c4846879 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -46,7 +46,7 @@ MidLinkW: MidLinkKp: [ 0, 0, 0, 0, 0, 0, - 0, 0, 1000 ] + 0, 0, 100 ] MidLinkKd: [ 0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 06e8abe04b..f05e35ed4e 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -8,6 +8,6 @@ actuator_delay: 0.000 visualize: false dt: 0.0001 -realtime_rate: 0.2 +realtime_rate: 0.5 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index dcb4f7ff68..fff1db8fdd 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -184,8 +184,14 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( drake::math::RollPitchYaw(trajectory.value(breaks(i))), line_points.col(i)); auto box = drake::geometry::Box(0.1, 0.1, 0.01); - meshcat_->SetObject("/trajectories/end_effector" + std::to_string(i), box, rgba_); - meshcat_->SetTransform("/trajectories/end_effector" + std::to_string(i), pose); + auto rgba_transparent = rgba_; + rgba_transparent.set(rgba_.r(), + rgba_.g(), + rgba_.b(), + (line_points.cols() - double(i)) / line_points.cols() + * rgba_.a()); + meshcat_->SetObject("/trajectories/end_effector_pose/" + std::to_string(i), box, rgba_transparent); + meshcat_->SetTransform("/trajectories/end_effector_pose/" + std::to_string(i), pose); } } // if (lcm_traj_.HasTrajectory("object_orientation_target")) { From 3c3e7124ae581e7cc9e4d9b82200da63dd2c4c21 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 3 May 2023 22:24:01 -0400 Subject: [PATCH 470/758] working on adding boxes --- .../plot_five_link_biped.py | 6 +- examples/franka/franka_sim.cc | 68 ++++-- examples/franka/franka_sim_params.h | 4 + examples/franka/franka_sim_params.yaml | 2 + examples/franka/franka_visualizer.cc | 21 +- examples/franka/systems/BUILD.bazel | 14 ++ .../franka/systems/franka_sim_controls.cc | 70 ++++++ examples/franka/systems/franka_sim_controls.h | 54 +++++ examples/franka/urdf/default_box.urdf | 34 +++ multibody/multibody_utils.cc | 199 +++++++++++------- 10 files changed, 372 insertions(+), 100 deletions(-) create mode 100644 examples/franka/systems/franka_sim_controls.cc create mode 100644 examples/franka/systems/franka_sim_controls.h create mode 100644 examples/franka/urdf/default_box.urdf diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index fa974e92eb..807cd8bd64 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -157,11 +157,11 @@ def main(): t = np.linspace(start_time, end_time, 1000) v_samples = [] for i in t: - v_samples.append(state_traj.value(i)[10:14, 0]) + v_samples.append(state_traj.value(i)[7:14, 0]) joint_vel_plot.plot(t, v_samples, xlabel='Time (s)', ylabel='Velocity (rad/s)', grid=False) - joint_vel_plot.add_legend(["Left Hip", "Right Hip", "Left Knee", "Right Knee"]) + # joint_vel_plot.add_legend(["Left Hip", "Right Hip", "Left Knee", "Right Knee"]) joint_vel_plot.tight_layout() - joint_vel_plot.save_fig('rabbit_joint_vel.png') + joint_vel_plot.save_fig('rabbit_gen_vel.png') plt.show() start_time = t_impact - 2 * window_length diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index e6bf2d6607..7564ae1b1f 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -32,8 +32,8 @@ namespace dairlib { using dairlib::systems::SubvectorPassThrough; -using drake::geometry::SceneGraph; using drake::geometry::GeometrySet; +using drake::geometry::SceneGraph; using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; @@ -74,9 +74,12 @@ int DoMain(int argc, char* argv[]) { parser.AddModelFromFile( dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), "table1"); - drake::multibody::ModelInstanceIndex tray_index = - parser.AddModelFromFile(FindResourceOrThrow( - "examples/franka/urdf/tray.sdf")); + drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile( + FindResourceOrThrow("examples/franka/urdf/tray.sdf")); + + drake::multibody::ModelInstanceIndex box_index = parser.AddModelFromFile( + FindResourceOrThrow("examples/franka/urdf/default_box.urdf")); + multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); @@ -93,17 +96,19 @@ int DoMain(int argc, char* argv[]) { plant.GetFrameByName("table", second_table_index), T_X_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); - -// drake::geometry::CollisionFilterDeclaration plate_table = drake::geometry::CollisionFilterDeclaration::ExcludeBetween(plant.GetCollisionGeometriesForBody()); - const drake::geometry::GeometrySet &paddle_geom_set = plant.CollectRegisteredGeometries({&plant.GetBodyByName( - "paddle"), &plant.GetBodyByName( - "panda_link4"), &plant.GetBodyByName( - "panda_link5"), &plant.GetBodyByName( - "panda_link6"),&plant.GetBodyByName( - "panda_link7"), }); - auto table_support_set = GeometrySet(plant.GetCollisionGeometriesForBody(plant.GetBodyByName("table"))); - plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair({"paddle", paddle_geom_set}, {"table_support", table_support_set}); - + + const drake::geometry::GeometrySet& paddle_geom_set = + plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("paddle"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link7"), + }); + auto table_support_set = GeometrySet( + plant.GetCollisionGeometriesForBody(plant.GetBodyByName("table"))); + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"paddle", paddle_geom_set}, {"table_support", table_support_set}); VectorXd rotor_inertias(plant.num_actuators()); rotor_inertias << 61, 61, 61, 61, 61, 61, 61; @@ -137,17 +142,26 @@ int DoMain(int argc, char* argv[]) { auto tray_state_pub = builder.AddSystem(LcmPublisherSystem::Make( sim_params.tray_state_channel, lcm, 1.0 / sim_params.publish_rate)); + auto box_state_sender = + builder.AddSystem(plant, box_index); + auto box_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + sim_params.box_state_channel, lcm, 1.0 / sim_params.publish_rate)); builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); + builder.Connect(plant.get_state_output_port(box_index), + box_state_sender->get_input_port_state()); builder.Connect(tray_state_sender->get_output_port(), tray_state_pub->get_input_port()); + builder.Connect(box_state_sender->get_output_port(), + box_state_pub->get_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); int nu = plant.num_actuators(); - if (sim_params.visualize){ + if (sim_params.visualize) { drake::visualization::AddDefaultVisualization(&builder); } @@ -174,13 +188,21 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint6"]] = sim_params.q_init_franka[5]; q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; - q[q_map["base_qw"]] = sim_params.q_init_plate[0]; - q[q_map["base_qx"]] = sim_params.q_init_plate[1]; - q[q_map["base_qy"]] = sim_params.q_init_plate[2]; - q[q_map["base_qz"]] = sim_params.q_init_plate[3]; - q[q_map["base_x"]] = sim_params.q_init_plate[4]; - q[q_map["base_y"]] = sim_params.q_init_plate[5]; - q[q_map["base_z"]] = sim_params.q_init_plate[6]; + q[q_map.at("tray_qw")] = sim_params.q_init_plate[0]; + q[q_map.at("tray_qx")] = sim_params.q_init_plate[1]; + q[q_map.at("tray_qy")] = sim_params.q_init_plate[2]; + q[q_map.at("tray_qz")] = sim_params.q_init_plate[3]; + q[q_map.at("tray_x")] = sim_params.q_init_plate[4]; + q[q_map.at("tray_y")] = sim_params.q_init_plate[5]; + q[q_map.at("tray_z")] = sim_params.q_init_plate[6]; + + q[q_map["box_qw"]] = sim_params.q_init_box[0]; + q[q_map["box_qx"]] = sim_params.q_init_box[1]; + q[q_map["box_qy"]] = sim_params.q_init_box[2]; + q[q_map["box_qz"]] = sim_params.q_init_box[3]; + q[q_map["box_x"]] = sim_params.q_init_box[4]; + q[q_map["box_y"]] = sim_params.q_init_box[5]; + q[q_map["box_z"]] = sim_params.q_init_box[6]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 7dcd7c5e30..8eb57b673f 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -11,6 +11,7 @@ struct FrankaSimParams { std::string state_channel; std::string controller_channel; std::string tray_state_channel; + std::string box_state_channel; std::string franka_model; double dt; @@ -23,12 +24,14 @@ struct FrankaSimParams { std::vector q_init_franka; std::vector q_init_plate; + std::vector q_init_box; template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(state_channel)); a->Visit(DRAKE_NVP(controller_channel)); a->Visit(DRAKE_NVP(tray_state_channel)); + a->Visit(DRAKE_NVP(box_state_channel)); a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(dt)); @@ -41,6 +44,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); + a->Visit(DRAKE_NVP(q_init_box)); } }; \ No newline at end of file diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index f05e35ed4e..e345a87071 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -1,6 +1,7 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT tray_state_channel: TRAY_OUTPUT +box_state_channel: BOX_OUTPUT franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true @@ -11,3 +12,4 @@ dt: 0.0001 realtime_rate: 0.5 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] +q_init_box: [1, 0, 0, 0, 0.8, 0, 0.1] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index ef2607a115..185fdf49b7 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -80,6 +80,9 @@ int do_main(int argc, char* argv[]) { "table1"); drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile( FindResourceOrThrow("examples/franka/urdf/tray.sdf")); + drake::multibody::ModelInstanceIndex box_index = + parser.AddModelFromFile(FindResourceOrThrow( + "examples/franka/urdf/default_box.urdf")); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); @@ -108,10 +111,15 @@ int do_main(int argc, char* argv[]) { auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( "TRAY_OUTPUT", lcm)); + auto box_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + "BOX_OUTPUT", lcm)); auto franka_state_receiver = builder.AddSystem(plant, franka_index); auto tray_state_receiver = builder.AddSystem(plant, tray_index); + auto box_state_receiver = + builder.AddSystem(plant, box_index); auto franka_passthrough = builder.AddSystem( franka_state_receiver->get_output_port(0).size(), 0, @@ -119,9 +127,13 @@ int do_main(int argc, char* argv[]) { auto tray_passthrough = builder.AddSystem( tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); + auto box_passthrough = builder.AddSystem( + tray_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(box_index)); std::vector input_sizes = {plant.num_positions(franka_index), - plant.num_positions(tray_index)}; + plant.num_positions(tray_index), + plant.num_positions(box_index)}; auto mux = builder.AddSystem>(input_sizes); @@ -153,6 +165,7 @@ int do_main(int argc, char* argv[]) { builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); + builder.Connect(box_passthrough->get_output_port(), mux->get_input_port(2)); builder.Connect(trajectory_sub_actor->get_output_port(), trajectory_drawer_actor->get_input_port_trajectory()); builder.Connect(trajectory_sub_object->get_output_port(), @@ -163,9 +176,11 @@ int do_main(int argc, char* argv[]) { scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(*franka_state_receiver, *franka_passthrough); builder.Connect(*tray_state_receiver, *tray_passthrough); + builder.Connect(*box_state_receiver, *box_passthrough); builder.Connect(*franka_state_sub, *franka_state_receiver); builder.Connect(*tray_state_sub, *tray_state_receiver); + builder.Connect(*box_state_sub, *box_state_receiver); auto diagram = builder.Build(); auto context = diagram->CreateDefaultContext(); @@ -174,10 +189,14 @@ int do_main(int argc, char* argv[]) { diagram->GetMutableSubsystemContext(*franka_state_sub, context.get()); auto& tray_state_sub_context = diagram->GetMutableSubsystemContext(*tray_state_sub, context.get()); + auto& box_state_sub_context = + diagram->GetMutableSubsystemContext(*box_state_sub, context.get()); franka_state_receiver->InitializeSubscriberPositions( plant, franka_state_sub_context); tray_state_receiver->InitializeSubscriberPositions(plant, tray_state_sub_context); + box_state_receiver->InitializeSubscriberPositions(plant, + box_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 4c56e7d057..30a9d68c83 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -50,6 +50,20 @@ cc_library( ], ) +cc_library( + name = "franka_sim_controls", + srcs = ["franka_sim_controls.cc"], + hdrs = ["franka_sim_controls.h"], + deps = [ + "//lcmtypes:lcmt_robot", + ":franka_kinematics_vector", + "//common", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "franka_kinematics_vector", srcs = ["franka_kinematics_vector.cc"], diff --git a/examples/franka/systems/franka_sim_controls.cc b/examples/franka/systems/franka_sim_controls.cc new file mode 100644 index 0000000000..6ef3cb2315 --- /dev/null +++ b/examples/franka/systems/franka_sim_controls.cc @@ -0,0 +1,70 @@ +#include + +#include "common/find_resource.h" +#include "examples/franka/systems/franka_sim_controls.h" +#include "multibody/multibody_utils.h" +#include + +namespace dairlib { + +using drake::multibody::ModelInstanceIndex; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteValues; + +using Eigen::VectorXd; +using systems::OutputVector; +using systems::TimestampedVector; + +namespace systems { + +FrankaSimControls::FrankaSimControls(const MultibodyPlant& sim_plant, + Context* sim_context, + ModelInstanceIndex franka_index, + ModelInstanceIndex plate_index, + ModelInstanceIndex box_index, + VectorXd& q_franka_default, + VectorXd& q_plate_default, + VectorXd& q_box_default) + : sim_plant_(sim_plant), + sim_context_(sim_context), + franka_index_(franka_index), + plate_index_(plate_index), + box_index_(box_index), + q_franka_default_(q_franka_default), + q_plate_default_(q_plate_default), + q_box_default_(q_box_default){ + this->set_name("franka_sim_control"); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + DeclareForcedDiscreteUpdateEvent(&FrankaSimControls::UpdateSimState); +} + +drake::systems::EventStatus FrankaSimControls::UpdateSimState( + const Context& context, + DiscreteValues* discrete_state) const { + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + + if (radio_out->channel[15] > 0) { + this->ResetSim(context); + } +} + +void FrankaSimControls::ResetSim( + const drake::systems::Context& context) const { + sim_plant_.SetPositions(sim_context_, franka_index_, q_franka_default_); + sim_plant_.SetPositions(sim_context_, plate_index_, q_plate_default_); + sim_plant_.SetPositions(sim_context_, box_index_, q_box_default_); +} + +//void FrankaSimControls::DropBox( +// const drake::systems::Context& context) const { +// plant.SetPositions(franka_context_, q); +//} + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/systems/franka_sim_controls.h b/examples/franka/systems/franka_sim_controls.h new file mode 100644 index 0000000000..36b70e7599 --- /dev/null +++ b/examples/franka/systems/franka_sim_controls.h @@ -0,0 +1,54 @@ +#pragma once + +#include +#include + +#include + +#include "examples/franka/systems/franka_kinematics_vector.h" +#include "systems/framework/output_vector.h" +#include "systems/framework/timestamped_vector.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// Outputs a lcmt_timestamped_saved_traj +class FrankaSimControls : public drake::systems::LeafSystem { + public: + explicit FrankaSimControls( + const drake::multibody::MultibodyPlant& sim_plant, + drake::systems::Context* sim_context, + drake::multibody::ModelInstanceIndex franka_index, + drake::multibody::ModelInstanceIndex plate_index, + drake::multibody::ModelInstanceIndex box_index, + Eigen::VectorXd& q_franka_default, Eigen::VectorXd& q_plate_default, + Eigen::VectorXd& q_box_default); + + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + private: + void ResetSim(const drake::systems::Context& context) const; + + drake::systems::EventStatus UpdateSimState( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex radio_port_; + + const drake::multibody::MultibodyPlant& sim_plant_; + drake::systems::Context* sim_context_; + drake::multibody::ModelInstanceIndex franka_index_; + drake::multibody::ModelInstanceIndex plate_index_; + drake::multibody::ModelInstanceIndex box_index_; + + Eigen::VectorXd q_franka_default_; + Eigen::VectorXd q_plate_default_; + Eigen::VectorXd q_box_default_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/urdf/default_box.urdf b/examples/franka/urdf/default_box.urdf new file mode 100644 index 0000000000..4a2ff91feb --- /dev/null +++ b/examples/franka/urdf/default_box.urdf @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 7b8b5c6767..65e5bf4725 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -158,7 +158,8 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, } /// Get the ordered names from a NameTo___Map -vector ExtractOrderedNamesFromMap(const map& map, int index_start) { +vector ExtractOrderedNamesFromMap(const map& map, + int index_start) { vector names(map.size()); for (const auto& entry : map) { names[entry.second - index_start] = entry.first; @@ -205,13 +206,13 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant) { // TODO: once RBT fully deprecated, this block can likely be removed, using // default coordinate names from Drake. auto floating_bodies = plant.GetFloatingBaseBodies(); - DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); +// DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); DRAKE_ASSERT(body.has_quaternion_dofs()); int start = body.floating_positions_start(); // should be body.name() once RBT is deprecated - std::string name = "base"; + std::string name = body.name(); name_to_index_map[name + "_qw"] = start; name_to_index_map[name + "_qx"] = start + 1; name_to_index_map[name + "_qy"] = start + 2; @@ -272,31 +273,26 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant, // TODO: once RBT fully deprecated, this block can likely be removed, using // default coordinate names from Drake. - auto floating_bodies = plant.GetFloatingBaseBodies(); - DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); if (plant.HasUniqueFreeBaseBody(model_instance)) { - for (auto body_index : floating_bodies) { - const auto& body = plant.get_body(body_index); - DRAKE_ASSERT(body.has_quaternion_dofs()); - int start = body.floating_positions_start(); - // should be body.name() once RBT is deprecated - std::string name = "base"; - name_to_index_map[name + "_qw"] = start; - name_to_index_map[name + "_qx"] = start + 1; - name_to_index_map[name + "_qy"] = start + 2; - name_to_index_map[name + "_qz"] = start + 3; - name_to_index_map[name + "_x"] = start + 4; - name_to_index_map[name + "_y"] = start + 5; - name_to_index_map[name + "_z"] = start + 6; - for (int i = 0; i < 7; i++) { - index_set.insert(start + i); - } + const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); + DRAKE_ASSERT(body.has_quaternion_dofs()); + int start = body.floating_positions_start(); + // should be body.name() once RBT is deprecated + std::string name = body.name(); + name_to_index_map[name + "_qw"] = start; + name_to_index_map[name + "_qx"] = start + 1; + name_to_index_map[name + "_qy"] = start + 2; + name_to_index_map[name + "_qz"] = start + 3; + name_to_index_map[name + "_x"] = start + 4; + name_to_index_map[name + "_y"] = start + 5; + name_to_index_map[name + "_z"] = start + 6; + for (int i = 0; i < 7; i++) { + index_set.insert(start + i); } } // if index has not already been captured, throw an error DRAKE_THROW_UNLESS(plant.num_positions(model_instance) == index_set.size()); - return name_to_index_map; } @@ -342,11 +338,11 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { auto floating_bodies = plant.GetFloatingBaseBodies(); // Remove throw once RBT deprecated - DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); +// DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); int start = body.floating_velocities_start() - plant.num_positions(); - std::string name = "base"; // should be body.name() once RBT is deprecated + std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; name_to_index_map[name + "_wz"] = start + 2; @@ -411,24 +407,19 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant, } } - auto floating_bodies = plant.GetFloatingBaseBodies(); // Remove throw once RBT deprecated - DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); if (plant.HasUniqueFreeBaseBody(model_instance)) { - for (auto body_index : floating_bodies) { - const auto& body = plant.get_body(body_index); - int start = body.floating_velocities_start() - plant.num_positions(); - std::string name = - "base"; // should be body.name() once RBT is deprecated - name_to_index_map[name + "_wx"] = start; - name_to_index_map[name + "_wy"] = start + 1; - name_to_index_map[name + "_wz"] = start + 2; - name_to_index_map[name + "_vx"] = start + 3; - name_to_index_map[name + "_vy"] = start + 4; - name_to_index_map[name + "_vz"] = start + 5; - for (int i = 0; i < 6; i++) { - index_set.insert(start + i); - } + const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); + int start = body.floating_velocities_start() - plant.num_positions(); + std::string name = body.name(); // should be body.name() once RBT is deprecated + name_to_index_map[name + "_wx"] = start; + name_to_index_map[name + "_wy"] = start + 1; + name_to_index_map[name + "_wz"] = start + 2; + name_to_index_map[name + "_vx"] = start + 3; + name_to_index_map[name + "_vy"] = start + 4; + name_to_index_map[name + "_vz"] = start + 5; + for (int i = 0; i < 6; i++) { + index_set.insert(start + i); } } @@ -663,38 +654,100 @@ template std::vector QuaternionStartIndices( const MultibodyPlant& plant); // NOLINT template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT -template Vector3d ReExpressWorldVector3InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector3d& vec); //NOLINT -template Vector2d ReExpressWorldVector2InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector2d& vec); //NOLINT -template map MakeNameToPositionsMap(const MultibodyPlant& plant); // NOLINT -template map MakeNameToPositionsMap(const MultibodyPlant &plant); // NOLINT -template map MakeNameToPositionsMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToPositionsMap(const MultibodyPlant &plant, drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT -template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT -template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToActuatorsMap(const MultibodyPlant& plant); // NOLINT -template map MakeNameToActuatorsMap(const MultibodyPlant& plant); // NOLINT -template vector CreateStateNameVectorFromMap(const MultibodyPlant& plant); // NOLINT -template vector CreateStateNameVectorFromMap(const MultibodyPlant& plant); // NOLINT -template vector CreateActuatorNameVectorFromMap(const MultibodyPlant& plant); // NOLINT -template vector CreateActuatorNameVectorFromMap(const MultibodyPlant& plant); // NOLINT -template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT -template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT -template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W, double stiffness, double dissipation_rate, bool show_ground); // NOLINT -template VectorX GetInput(const MultibodyPlant& plant, const Context& context); // NOLINT -template VectorX GetInput(const MultibodyPlant& plant, const Context& context); // NOLINT -template std::unique_ptr> CreateContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref& input); // NOLINT -template std::unique_ptr> CreateContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref& input); // NOLINT -template void SetContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref&, Context* context); // NOLINT -template void SetContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref&, Context* context); // NOLINT -template void SetPositionsAndVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetPositionsAndVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetPositionsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetPositionsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetInputsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT -template void SetInputsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template Vector3d ReExpressWorldVector3InBodyYawFrame( + const MultibodyPlant& plant, const Context& context, + const std::string& body_name, const Vector3d& vec); // NOLINT +template Vector2d ReExpressWorldVector2InBodyYawFrame( + const MultibodyPlant& plant, const Context& context, + const std::string& body_name, const Vector2d& vec); // NOLINT +template map MakeNameToPositionsMap( + const MultibodyPlant& plant); // NOLINT +template map MakeNameToPositionsMap( + const MultibodyPlant& plant); // NOLINT +template map MakeNameToPositionsMap( + const MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToPositionsMap( + const MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToVelocitiesMap( + const MultibodyPlant& plant); // NOLINT +template map MakeNameToVelocitiesMap( + const MultibodyPlant& plant); // NOLINT +template map MakeNameToVelocitiesMap( + const MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToVelocitiesMap( + const MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToActuatorsMap( + const MultibodyPlant& plant); // NOLINT +template map MakeNameToActuatorsMap( + const MultibodyPlant& plant); // NOLINT +template vector CreateStateNameVectorFromMap( + const MultibodyPlant& plant); // NOLINT +template vector CreateStateNameVectorFromMap( + const MultibodyPlant& plant); // NOLINT +template vector CreateActuatorNameVectorFromMap( + const MultibodyPlant& plant); // NOLINT +template vector CreateActuatorNameVectorFromMap( + const MultibodyPlant& plant); // NOLINT +template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos( + const drake::multibody::MultibodyPlant& plant_w_spr, + const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT +template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel( + const drake::multibody::MultibodyPlant& plant_w_spr, + const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT +template void AddFlatTerrain(MultibodyPlant* plant, + SceneGraph* scene_graph, + double mu_static, double mu_kinetic, + Eigen::Vector3d normal_W, double stiffness, + double dissipation_rate, + bool show_ground); // NOLINT +template VectorX GetInput(const MultibodyPlant& plant, + const Context& context); // NOLINT +template VectorX GetInput( + const MultibodyPlant& plant, + const Context& context); // NOLINT +template std::unique_ptr> CreateContext( + const MultibodyPlant& plant, + const Eigen::Ref& state, + const Eigen::Ref& input); // NOLINT +template std::unique_ptr> CreateContext( + const MultibodyPlant& plant, + const Eigen::Ref& state, + const Eigen::Ref& input); // NOLINT +template void SetContext(const MultibodyPlant& plant, + const Eigen::Ref& state, + const Eigen::Ref&, + Context* context); // NOLINT +template void SetContext(const MultibodyPlant& plant, + const Eigen::Ref& state, + const Eigen::Ref&, + Context* context); // NOLINT +template void SetPositionsAndVelocitiesIfNew( + const MultibodyPlant&, const Eigen::Ref&, + Context*); // NOLINT +template void SetPositionsAndVelocitiesIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT +template void SetPositionsIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT +template void SetPositionsIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT +template void SetVelocitiesIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT +template void SetVelocitiesIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT +template void SetInputsIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT +template void SetInputsIfNew(const MultibodyPlant&, + const Eigen::Ref&, + Context*); // NOLINT } // namespace multibody } // namespace dairlib From ac88f17a6f9b11538ea8a7d61b53c9a7b1c908a2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 8 May 2023 12:55:23 -0400 Subject: [PATCH 471/758] plotting target position from c3 plan --- .../franka/franka_c3_controller_params.yaml | 2 +- .../franka/franka_c3_options_translation.yaml | 6 +- examples/franka/franka_controller_params.yaml | 14 ++-- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/urdf/franka.urdf | 2 +- examples/franka/urdf/tray.sdf | 4 +- .../lcm_trajectory_systems.cc | 72 ++++++++++++------- 7 files changed, 61 insertions(+), 41 deletions(-) diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index ce21cc9a46..adea73e069 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -14,6 +14,6 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 5 +target_frequency: 2 diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 2d0af6c969..2e946fceff 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -4,7 +4,7 @@ rho_scale: 2 num_threads: 4 delta_option: 1 -mu: 0.4 +mu: 0.2 mu_plate: 1 dt: 0.1 solve_dt: 0.05 @@ -21,10 +21,10 @@ w_U: 1 g_size: 40 u_size: 40 # State Tracking Error, assuming diagonal -q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [100, 100, 1000, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.55, 0.02, 0.41, 1, 0, 0, 0, 0.55, 0.02, 0.45] +q_des_vector: [0.55, 0.02, 0.43, 1, 0, 0, 0, 0.55, 0.02, 0.45] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 65c4846879..46edfc39f3 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -8,14 +8,14 @@ c3_channel: C3_TRAJECTORY_ACTOR franka_model: examples/franka/urdf/franka.urdf w_input: 0.00 -w_input_reg: 0.001 -w_accel: 0.0001 +w_input_reg: 0.0 +w_accel: 0.00001 w_soft_constraint: 10000 w_lambda: 0.1 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 50.0 +end_effector_acceleration: 200.0 track_end_effector_orientation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] @@ -32,9 +32,9 @@ EndEffectorW: 0, 1, 0, 0, 0, 1] EndEffectorKp: - [ 1000, 0, 0, - 0, 500, 0, - 0, 0, 1000 ] + [ 2000, 0, 0, + 0, 1000, 0, + 0, 0, 2000 ] EndEffectorKd: [ 125, 0, 0, 0, 70, 0, @@ -58,7 +58,7 @@ EndEffectorRotW: EndEffectorRotKp: [ 4000, 0, 0, 0, 4000, 0, - 0, 0, 500 ] + 0, 0, 500] EndEffectorRotKd: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index e345a87071..13c5df8ee1 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -9,7 +9,7 @@ actuator_delay: 0.000 visualize: false dt: 0.0001 -realtime_rate: 0.5 +realtime_rate: 1.0 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] q_init_box: [1, 0, 0, 0, 0.8, 0, 0.1] diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index bd5c985787..b4d9be8a01 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -511,7 +511,7 @@ - + - 0.4 - 0.4 + 0.2 + 0.2 diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index fff1db8fdd..abe9f201ad 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -179,36 +179,56 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( auto trajectory = PiecewisePolynomial::CubicHermite( orientation_block.time_vector, orientation_block.datapoints.topRows(3), orientation_block.datapoints.bottomRows(3)); - for (int i = 0; i < line_points.cols(); ++i) { - auto pose = drake::math::RigidTransform( - drake::math::RollPitchYaw(trajectory.value(breaks(i))), - line_points.col(i)); - auto box = drake::geometry::Box(0.1, 0.1, 0.01); - auto rgba_transparent = rgba_; - rgba_transparent.set(rgba_.r(), - rgba_.g(), - rgba_.b(), - (line_points.cols() - double(i)) / line_points.cols() - * rgba_.a()); - meshcat_->SetObject("/trajectories/end_effector_pose/" + std::to_string(i), box, rgba_transparent); - meshcat_->SetTransform("/trajectories/end_effector_pose/" + std::to_string(i), pose); - } - } -// if (lcm_traj_.HasTrajectory("object_orientation_target")) { -// const auto orientation_block = -// lcm_traj_.GetTrajectory("object_orientation_target"); -// for (int i = 0; i < orientation_block.datapoints.cols(); ++i) { +// for (int i = line_points.cols() - 2; i < line_points.cols(); ++i) { // auto pose = drake::math::RigidTransform( -// Quaterniond(orientation_block.datapoints(0, i), -// orientation_block.datapoints(1, i), -// orientation_block.datapoints(2, i), -// orientation_block.datapoints(3, i)), +// drake::math::RollPitchYaw(trajectory.value(breaks(i))), // line_points.col(i)); // auto box = drake::geometry::Box(0.1, 0.1, 0.01); -// meshcat_->SetObject("/trajectories/object" + std::to_string(i), box, rgba_); -// meshcat_->SetTransform("/trajectories/object" + std::to_string(i), pose); +// auto rgba_transparent = rgba_; +// rgba_transparent.set( +// rgba_.r(), rgba_.g(), rgba_.b(), +// (line_points.cols() - double(i)) / line_points.cols() * rgba_.a()); +// meshcat_->SetObject( +// "/trajectories/end_effector_pose/" + std::to_string(i), box, +// rgba_transparent); +// meshcat_->SetTransform( +// "/trajectories/end_effector_pose/" + std::to_string(i), pose); // } -// } + } else { + auto trajectory = PiecewisePolynomial::CubicHermite( + trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), + trajectory_block.datapoints.bottomRows(3)); + auto pose = drake::math::RigidTransform(line_points.col(line_points.cols() - 1)); + double side_length = 0.2; + if (trajectory_name_ == "object_traj"){ + side_length = 0.4; + } + auto box = drake::geometry::Box(side_length, side_length, 0.01); + auto rgba_transparent = rgba_; + rgba_transparent.set( + rgba_.r(), rgba_.g(), rgba_.b(), + 0.3 * rgba_.a()); + meshcat_->SetObject("/trajectories/" + trajectory_name_ + "/end", + box, rgba_transparent); + meshcat_->SetTransform( + "/trajectories/" + trajectory_name_ + "/end", pose); + } + // if (lcm_traj_.HasTrajectory("object_orientation_target")) { + // const auto orientation_block = + // lcm_traj_.GetTrajectory("object_orientation_target"); + // for (int i = 0; i < orientation_block.datapoints.cols(); ++i) { + // auto pose = drake::math::RigidTransform( + // Quaterniond(orientation_block.datapoints(0, i), + // orientation_block.datapoints(1, i), + // orientation_block.datapoints(2, i), + // orientation_block.datapoints(3, i)), + // line_points.col(i)); + // auto box = drake::geometry::Box(0.1, 0.1, 0.01); + // meshcat_->SetObject("/trajectories/object" + std::to_string(i), box, + // rgba_); meshcat_->SetTransform("/trajectories/object" + + // std::to_string(i), pose); + // } + // } return drake::systems::EventStatus::Succeeded(); } From 042d3c6b6dfd541e78a0c4c919683dc5620fcfae Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 8 May 2023 12:59:54 -0400 Subject: [PATCH 472/758] making box smaller and starting on table --- examples/franka/franka_sim_params.yaml | 2 +- examples/franka/urdf/default_box.urdf | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 13c5df8ee1..9a90a71c90 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -12,4 +12,4 @@ dt: 0.0001 realtime_rate: 1.0 q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] -q_init_box: [1, 0, 0, 0, 0.8, 0, 0.1] +q_init_box: [1, 0, 0, 0, 1.0, -0.2, 1.1] diff --git a/examples/franka/urdf/default_box.urdf b/examples/franka/urdf/default_box.urdf index 4a2ff91feb..dbe30519ab 100644 --- a/examples/franka/urdf/default_box.urdf +++ b/examples/franka/urdf/default_box.urdf @@ -15,7 +15,7 @@ - + @@ -27,7 +27,7 @@ - + From fb8e77039868831101931e4f5eb582eedf1395ec Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 11 May 2023 15:33:34 -0400 Subject: [PATCH 473/758] working on ros translation --- examples/franka/BUILD.bazel | 21 ++++ examples/franka/franka_dispatcher_in.cc | 151 +++++++++++++++++++++++ examples/franka/franka_dispatcher_out.cc | 0 systems/ros/robot_lcm_ros_translator.cc | 5 + systems/ros/robot_lcm_ros_translator.h | 26 ++++ 5 files changed, 203 insertions(+) create mode 100644 examples/franka/franka_dispatcher_in.cc create mode 100644 examples/franka/franka_dispatcher_out.cc create mode 100644 systems/ros/robot_lcm_ros_translator.cc create mode 100644 systems/ros/robot_lcm_ros_translator.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 97cf700988..f460f7458d 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -10,6 +10,27 @@ cc_library( ]), ) +cc_library( + name = "franka_hardware", + deps = [], +) + +cc_library( + name = "franka_dispatcher_in", + srcs = ["franka_dispatcher_in.cc"], + deps = [ + "//systems/ros:ros_pubsub_systems" + ], +) + +cc_library( + name = "franka_dispatcher_out", + srcs = ["franka_dispatcher_out.cc"], + deps = [ + "//systems/ros:ros_pubsub_systems" + ], +) + cc_binary( name = "franka_sim", srcs = ["franka_sim.cc"], diff --git a/examples/franka/franka_dispatcher_in.cc b/examples/franka/franka_dispatcher_in.cc new file mode 100644 index 0000000000..07f5183706 --- /dev/null +++ b/examples/franka/franka_dispatcher_in.cc @@ -0,0 +1,151 @@ +#include + +#include "dairlib/lcmt_controller_failure.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/Cassie/networking/cassie_input_translator.h" +#include "examples/Cassie/networking/cassie_udp_publisher.h" +#include "examples/Cassie/systems/input_supervisor.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/linear_controller.h" +#include "systems/controllers/pd_config_lcm.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/lcm/drake_lcm.h" +#include "drake/systems/framework/diagram.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" + +namespace dairlib { +using drake::lcm::Subscriber; +using drake::systems::Context; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::TriggerType; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using systems::RobotCommandSender; +using systems::RobotInputReceiver; + +using std::map; +using std::string; + +DEFINE_double(echo_frequency, 50, "Network LCM pubishing frequency (Hz)."); +DEFINE_double(publish_frequency, 2000, "ROS pubishing period (Hz)."); +DEFINE_double(max_joint_velocity, 20, + "Maximum joint velocity before error is triggered"); +DEFINE_double(input_limit, 300, + "Maximum torque limit. Negative values are inf."); +DEFINE_string(state_channel_name, "CASSIE_STATE_DISPATCHER", + "The name of the lcm channel that sends Cassie's state"); + +int do_main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); + drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); + + DiagramBuilder builder; + + // Create LCM receiver for commands + auto command_receiver = builder.AddSystem(plant); + + // Safety Controller + auto safety_controller = builder.AddSystem( + plant.num_positions(), plant.num_velocities(), plant.num_actuators()); + // Create config receiver. + auto config_receiver = builder.AddSystem(plant); + + // Create state estimate receiver, used for safety checks + auto state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + FLAGS_state_channel_name, &lcm_local)); + auto state_receiver = builder.AddSystem(plant); + + auto input_supervisor_status_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, + FLAGS_pub_rate)); + + auto input_supervisor = builder.AddSystem( + plant, FLAGS_control_channel_name_initial, FLAGS_max_joint_velocity, + input_supervisor_update_period, input_limit, FLAGS_supervisor_N); + auto net_command_sender = builder.AddSystem(plant); + command_pub_network = + builder.AddSystem(LcmPublisherSystem::Make( + "NETWORK_CASSIE_INPUT", &lcm_network, {TriggerType::kPeriodic}, + FLAGS_pub_rate)); + builder.Connect(*net_command_sender, *command_pub_network); + auto command_pub_local = + builder.AddSystem(LcmPublisherSystem::Make( + "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); + + ros::init(argc, argv, "torque_controller"); + ros::NodeHandle node_handle; + signal(SIGINT, SigintHandler); + auto c3_to_ros = builder.AddSystem(7); + // try making this kForced + auto ros_publisher = builder.AddSystem( + systems::RosPublisherSystem::Make( + "/franka_control/torque_in", &node_handle, 1 / publish_frequency)); + + builder.Connect(subvector_passthrough->get_output_port(), + c3_to_ros->get_input_port()); + builder.Connect(c3_to_ros->get_output_port(), + ros_publisher->get_input_port()); + + builder.Connect(input_supervisor->get_output_port_command(), + net_command_sender->get_input_port(0)); + builder.Connect(*net_command_sender, *command_pub_local); + + builder.Connect(state_receiver->get_output_port(0), + input_supervisor->get_input_port_state()); + builder.Connect(command_receiver->get_output_port(0), + input_supervisor->get_input_port_command()); + builder.Connect(controller_switch_sub->get_output_port(), + input_supervisor->get_input_port_controller_switch()); + builder.Connect(controller_error_sub->get_output_port(), + input_supervisor->get_input_port_controller_error()); + builder.Connect(input_supervisor->get_output_port_status(), + input_supervisor_status_pub->get_input_port()); + builder.Connect(cassie_out_receiver->get_output_port(), + input_supervisor->get_input_port_cassie()); + builder.Connect(state_receiver->get_output_port(0), + safety_controller->get_input_port_output()); + builder.Connect(config_receiver->get_output_port(0), + safety_controller->get_input_port_config()); + builder.Connect(safety_controller->get_output_port(0), + input_supervisor->get_input_port_safety_controller()); + builder.Connect(input_supervisor->get_output_port_failure(), + controller_error_pub->get_input_port()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name("franka_dispatcher_in"); + + systems::LcmDrivenLoop loop( + &drake_lcm, std::move(diagram), state_receiver, FLAGS_channel, true); + + auto msg = dairlib::lcmt_pd_config(); + msg.timestamp = 0; + msg.num_joints = 10; + msg.joint_names = {"hip_roll_left_motor", "hip_roll_right_motor", + "hip_yaw_left_motor", "hip_yaw_right_motor", + "hip_pitch_left_motor", "hip_pitch_right_motor", + "knee_left_motor", "knee_right_motor", + "toe_left_motor", "toe_right_motor"}; + msg.desired_position = {-0.01, .01, 0, 0, 0.55, 0.55, -1.7, -1.7, -1.8, -1.8}; + msg.desired_velocity = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; + msg.kp = {50, 50, 50, 50, 50, 50, 50, 50, 20, 20}; + msg.kd = {5, 5, 5, 5, 5, 5, 5, 5, 5, 5}; + config_receiver->get_input_port().FixValue( + &(loop.get_diagram()->GetMutableSubsystemContext( + *config_receiver, &loop.get_diagram_mutable_context())), + msg); + + loop.Simulate(); + + return 0; +} +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/franka/franka_dispatcher_out.cc b/examples/franka/franka_dispatcher_out.cc new file mode 100644 index 0000000000..e69de29bb2 diff --git a/systems/ros/robot_lcm_ros_translator.cc b/systems/ros/robot_lcm_ros_translator.cc new file mode 100644 index 0000000000..b7b4981299 --- /dev/null +++ b/systems/ros/robot_lcm_ros_translator.cc @@ -0,0 +1,5 @@ +// +// Created by yangwill on 5/11/23. +// + +#include "robot_lcm_ros_translator.h" diff --git a/systems/ros/robot_lcm_ros_translator.h b/systems/ros/robot_lcm_ros_translator.h new file mode 100644 index 0000000000..e1da2e8461 --- /dev/null +++ b/systems/ros/robot_lcm_ros_translator.h @@ -0,0 +1,26 @@ +#pragma once + + +#include +#include +#include + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" +#include "drake/systems/lcm/lcm_interface_system.h" + +namespace dairlib { +namespace systems { + +class RobotInputToROS : public drake::systems::LeafSystem { + public: + explicit RobotInputToROS(drake::multibody::MultibodyPlant& plant); + + private: + void ConvertToROS(const drake::systems::Context& context, + std_msgs::Float64MultiArray* output) const; + int num_elements_; +}; + +} +} \ No newline at end of file From 0667f44eb67161bfc8dcd9710cbbec327cb6d2a0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 16 May 2023 16:48:10 -0400 Subject: [PATCH 474/758] adding foce tracking --- examples/franka/BUILD.bazel | 2 + systems/controllers/osc/BUILD.bazel | 13 ++++ .../osc/external_force_tracking_data.cc | 39 +++++++++++ .../osc/external_force_tracking_data.h | 64 +++++++++++++++++++ .../osc/operational_space_control.cc | 39 +++++++++++ .../osc/operational_space_control.h | 10 +++ systems/ros/BUILD.bazel | 16 +++++ systems/ros/robot_lcm_ros_translator.cc | 14 ++-- 8 files changed, 193 insertions(+), 4 deletions(-) create mode 100644 systems/controllers/osc/external_force_tracking_data.cc create mode 100644 systems/controllers/osc/external_force_tracking_data.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index f460f7458d..29b9541868 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -18,6 +18,7 @@ cc_library( cc_library( name = "franka_dispatcher_in", srcs = ["franka_dispatcher_in.cc"], + tags = ["ros"], deps = [ "//systems/ros:ros_pubsub_systems" ], @@ -26,6 +27,7 @@ cc_library( cc_library( name = "franka_dispatcher_out", srcs = ["franka_dispatcher_out.cc"], + tags = ["ros"], deps = [ "//systems/ros:ros_pubsub_systems" ], diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index deb1f3fc9d..ec516567e9 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -33,6 +33,7 @@ cc_library( ":com_tracking_data", ":joint_space_tracking_data", ":osc_tracking_data", + ":external_force_tracking_data", ":relative_transform_tracking_data", ":rot_space_tracking_data", ":trans_space_tracking_data", @@ -125,6 +126,18 @@ cc_library( ], ) +cc_library( + name = "external_force_tracking_data", + srcs = ["external_force_tracking_data.cc"], + hdrs = ["external_force_tracking_data.h"], + deps = [ + ":osc_tracking_data", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "osc_gains", hdrs = ["osc_gains.h"], diff --git a/systems/controllers/osc/external_force_tracking_data.cc b/systems/controllers/osc/external_force_tracking_data.cc new file mode 100644 index 0000000000..b16c59062f --- /dev/null +++ b/systems/controllers/osc/external_force_tracking_data.cc @@ -0,0 +1,39 @@ +#include "external_force_tracking_data.h" +#include "osc_tracking_data.h" + +using Eigen::MatrixXd; +using Eigen::Quaterniond; +using Eigen::Vector3d; +using Eigen::VectorXd; +using std::string; +using std::vector; + +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::Context; + +namespace dairlib::systems::controllers { + +ExternalForceTrackingData::ExternalForceTrackingData( + const string& name, const MatrixXd& W, + const MultibodyPlant& plant_w_spr, + const MultibodyPlant& plant_wo_spr) + : name_(name), + plant_w_spr_(plant_w_spr), + plant_wo_spr_(plant_wo_spr), + world_w_spr_(plant_w_spr_.world_frame()), + world_wo_spr_(plant_wo_spr_.world_frame()), + W_(W) {} + +void ExternalForceTrackingData::UpdateActual( + const Eigen::VectorXd& x_w_spr, + const drake::systems::Context& context_w_spr, + const Eigen::VectorXd& x_wo_spr, + const drake::systems::Context& context_wo_spr, double t) { + J_ = MatrixXd::Zero(kSpaceDim, plant_wo_spr_.num_velocities()); + plant_wo_spr_.CalcJacobianTranslationalVelocity( + context_wo_spr, JacobianWrtVariable::kV, *body_frame_wo_spr_, pt_on_body_, + world_wo_spr_, world_wo_spr_, &J_); +} + +} // namespace dairlib::systems::controllers diff --git a/systems/controllers/osc/external_force_tracking_data.h b/systems/controllers/osc/external_force_tracking_data.h new file mode 100644 index 0000000000..cc6e9bf3cd --- /dev/null +++ b/systems/controllers/osc/external_force_tracking_data.h @@ -0,0 +1,64 @@ +#pragma once + +#include +#include + +namespace dairlib { +namespace systems { +namespace controllers { + + +/// ExternalForceTrackingData +/// Force tracking objective. Used to track desired external forces. Requires +/// contact points on the MultibodyPlant where contact forces enter the dynamics +class ExternalForceTrackingData { + public: + ExternalForceTrackingData( + const std::string& name, const Eigen::MatrixXd& W, + const drake::multibody::MultibodyPlant& plant_w_spr, + const drake::multibody::MultibodyPlant& plant_wo_spr); + + const Eigen::MatrixXd& GetWeight() const { return W_; } + + const Eigen::MatrixXd& GetJ() const { return J_; } + const std::string& GetName() const { return name_; }; + int GetYDim() const { return n_y_; }; + + const drake::multibody::MultibodyPlant& plant_w_spr() const { + return plant_w_spr_; + }; + const drake::multibody::MultibodyPlant& plant_wo_spr() const { + return plant_wo_spr_; + }; + + protected: + private: + std::string name_; + + // This method is called from the parent class (OscTrackingData) due to C++ + // polymorphism. + void UpdateActual(const Eigen::VectorXd& x_w_spr, + const drake::systems::Context& context_w_spr, + const Eigen::VectorXd& x_wo_spr, + const drake::systems::Context& context_wo_spr, + double t); + + const drake::multibody::MultibodyPlant& plant_w_spr_; + const drake::multibody::MultibodyPlant& plant_wo_spr_; + // World frames + const drake::multibody::BodyFrame& world_w_spr_; + const drake::multibody::BodyFrame& world_wo_spr_; + + const drake::multibody::BodyFrame* body_frame_w_spr_; + const drake::multibody::BodyFrame* body_frame_wo_spr_; + Eigen::Vector3d pt_on_body_; + + int n_y_ = 3; + + Eigen::MatrixXd J_; + Eigen::MatrixXd W_; +}; + +} // namespace controllers +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index b25fc23ce7..556bc2f2e9 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -240,6 +240,27 @@ void OperationalSpaceControl::AddTrackingData( traj_name_to_port_index_map_[traj_name] = port_index; } } + +// Tracking data methods +void OperationalSpaceControl::AddForceTrackingData( + std::unique_ptr tracking_data) { + force_tracking_data_vec_->push_back(std::move(tracking_data)); + + // Construct input ports and add element to traj_name_to_port_index_map_ if + // the port for the traj is not created yet + string traj_name = force_tracking_data_vec_->back()->GetName(); + if (traj_name_to_port_index_map_.find(traj_name) == + traj_name_to_port_index_map_.end()) { + PiecewisePolynomial pp = PiecewisePolynomial(); + int port_index = + this->DeclareAbstractInputPort( + traj_name, + drake::Value>(pp)) + .get_index(); + traj_name_to_port_index_map_[traj_name] = port_index; + } +} + void OperationalSpaceControl::AddConstTrackingData( std::unique_ptr tracking_data, const VectorXd& v, double t_lb, double t_ub) { @@ -290,6 +311,12 @@ void OperationalSpaceControl::Build() { ? 0 : kinematic_evaluators_->count_full(); n_c_ = kSpaceDim * all_contacts_.size(); + + n_ee_ = 0; + for (auto& force_tracking_data : *force_tracking_data_vec_){ + n_ee_ += force_tracking_data->GetYDim(); + } + n_c_active_ = 0; for (auto evaluator : all_contacts_) { n_c_active_ += evaluator->num_active(); @@ -312,12 +339,14 @@ void OperationalSpaceControl::Build() { u_sol_ = std::make_unique(n_u_); lambda_c_sol_ = std::make_unique(n_c_); lambda_h_sol_ = std::make_unique(n_h_); + lambda_ee_sol_ = std::make_unique(n_ee_); epsilon_sol_ = std::make_unique(n_c_active_); u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); + lambda_ee_sol_->setZero(); u_prev_->setZero(); // Add decision variables @@ -325,6 +354,7 @@ void OperationalSpaceControl::Build() { u_ = prog_->NewContinuousVariables(n_u_, "u"); lambda_c_ = prog_->NewContinuousVariables(n_c_, "lambda_contact"); lambda_h_ = prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); + lambda_ee_ = prog_->NewContinuousVariables(n_ee_, "lambda_ee"); epsilon_ = prog_->NewContinuousVariables(n_c_active_, "epsilon"); // Add constraints @@ -426,6 +456,15 @@ void OperationalSpaceControl::Build() { .evaluator() .get(); } + // 3. external force cost + for (auto& force_tracking_data: *force_tracking_data_vec_){ + DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); + lambda_ee_cost_ = + prog_ + ->AddQuadraticCost(, VectorXd::Zero(n_h_), lambda_h_) + .evaluator() + .get(); + } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { soft_constraint_cost_ = diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index e407aa1a60..6071db4bac 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -30,6 +30,7 @@ #include "drake/systems/framework/diagram.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/framework/leaf_system.h" +#include "systems/controllers/osc/external_force_tracking_data.h" namespace dairlib::systems::controllers { @@ -239,6 +240,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void AddTrackingData(std::unique_ptr tracking_data, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); + void AddForceTrackingData(std::unique_ptr tracking_data); void AddConstTrackingData( std::unique_ptr tracking_data, const Eigen::VectorXd& v, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); @@ -360,6 +362,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Size of holonomic constraint and total/active contact constraints int n_h_; int n_c_; + int n_ee_; int n_c_active_; // Manually specified holonomic constraints (only valid for plants_wo_springs) @@ -398,6 +401,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::VectorXDecisionVariable u_; drake::solvers::VectorXDecisionVariable lambda_c_; drake::solvers::VectorXDecisionVariable lambda_h_; + drake::solvers::VectorXDecisionVariable lambda_ee_; drake::solvers::VectorXDecisionVariable epsilon_; // Cost and constraints drake::solvers::LinearEqualityConstraint* dynamics_constraint_; @@ -412,6 +416,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::QuadraticCost* input_smoothing_cost_ = nullptr; drake::solvers::QuadraticCost* lambda_c_cost_ = nullptr; drake::solvers::QuadraticCost* lambda_h_cost_ = nullptr; + drake::solvers::QuadraticCost* lambda_ee_cost_ = nullptr; drake::solvers::QuadraticCost* soft_constraint_cost_ = nullptr; // OSC solution @@ -419,6 +424,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::unique_ptr u_sol_; std::unique_ptr lambda_c_sol_; std::unique_ptr lambda_h_sol_; + std::unique_ptr lambda_ee_sol_; std::unique_ptr epsilon_sol_; std::unique_ptr u_prev_; mutable double solve_time_; @@ -459,6 +465,10 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { tracking_data_vec_ = std::make_unique>>(); + std::unique_ptr>> + force_tracking_data_vec_ = + std::make_unique>>(); + // Fixed position of constant trajectories std::vector fixed_position_vec_; diff --git a/systems/ros/BUILD.bazel b/systems/ros/BUILD.bazel index 17dc86e94c..863b62eaae 100644 --- a/systems/ros/BUILD.bazel +++ b/systems/ros/BUILD.bazel @@ -13,6 +13,22 @@ cc_library( ], ) +cc_library( + name = "ros_translator", + hdrs = [ + "robot_lcm_ros_translator.h", + ], + srcs = [ + "robot_lcm_ros_translator.cc", + ], + tags = ["ros"], + deps = [ + "@drake//:drake_shared_library", + "@ros", + ], +) + + cc_binary( name = "test_ros_publisher_system", srcs = ["test/test_ros_publisher_system.cc"], diff --git a/systems/ros/robot_lcm_ros_translator.cc b/systems/ros/robot_lcm_ros_translator.cc index b7b4981299..cc567f945d 100644 --- a/systems/ros/robot_lcm_ros_translator.cc +++ b/systems/ros/robot_lcm_ros_translator.cc @@ -1,5 +1,11 @@ -// -// Created by yangwill on 5/11/23. -// - #include "robot_lcm_ros_translator.h" + + +using drake::multibody::MultibodyPlant; + +namespace dairlib { +namespace systems { + +RobotInputToROS::RobotInputToROS(MultibodyPlant& plant){ + +} From 806193847031af4fd2c4fd9da8418e0b4a75ae71 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 May 2023 15:15:17 -0400 Subject: [PATCH 475/758] trying to set up minimum acceleration needed experiment --- examples/franka/franka_c3_controller.cc | 2 ++ examples/franka/franka_c3_controller_params.yaml | 2 +- examples/franka/franka_c3_options_floating.yaml | 2 +- .../franka/franka_c3_options_translation.yaml | 6 +++--- examples/franka/franka_controller_params.yaml | 8 ++++---- examples/franka/franka_sim_params.yaml | 6 ++++-- examples/franka/urdf/tray.sdf | 2 +- systems/controllers/c3_controller.cc | 5 +++++ .../controllers/osc/operational_space_control.cc | 16 ++++++++-------- 9 files changed, 29 insertions(+), 20 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index f90e1859d8..2d75f29d3b 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -202,6 +202,8 @@ int DoMain(int argc, char* argv[]) { *controller, &loop.get_diagram_mutable_context()); // loop.get_diagram_mutable_context() controller->get_input_port_target().FixValue(&controller_context, x_des); + LcmHandleSubscriptionsUntil(&lcm, [&]() { + return tray_state_sub->GetInternalMessageCount() > 1; }); loop.Simulate(); return 0; } diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index adea73e069..4233b5680f 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -14,6 +14,6 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 2 +target_frequency: 3 diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/franka_c3_options_floating.yaml index c2ba92e8b0..268dd4ed8f 100644 --- a/examples/franka/franka_c3_options_floating.yaml +++ b/examples/franka/franka_c3_options_floating.yaml @@ -23,7 +23,7 @@ u_size: 49 # State Tracking Error, assuming diagonal #q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 1, 1, 1, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [200, 200, 500, 0, 0, 0, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 0.1, 0.1, 0.1] diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 2e946fceff..fadf7fb85b 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -14,17 +14,17 @@ N: 5 w_Q: 10 w_R: 0 # Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.5 # Penalty on all decision variables, assuming scalar w_U: 1 g_size: 40 u_size: 40 # State Tracking Error, assuming diagonal -q_vector: [100, 100, 1000, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [10, 10, 5000, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.55, 0.02, 0.43, 1, 0, 0, 0, 0.55, 0.02, 0.45] +q_des_vector: [0.55, 0.02, 0.4, 1, 0, 0, 0, 0.55, 0.02, 0.42] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_controller_params.yaml index 46edfc39f3..c3ceb06c56 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_controller_params.yaml @@ -15,7 +15,7 @@ w_lambda: 0.1 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 200.0 +end_effector_acceleration: 5.0 track_end_effector_orientation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] @@ -32,9 +32,9 @@ EndEffectorW: 0, 1, 0, 0, 0, 1] EndEffectorKp: - [ 2000, 0, 0, - 0, 1000, 0, - 0, 0, 2000 ] + [ 1000, 0, 0, + 0, 500, 0, + 0, 0, 1000 ] EndEffectorKd: [ 125, 0, 0, 0, 70, 0, diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 9a90a71c90..951d9aff61 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -10,6 +10,8 @@ visualize: false dt: 0.0001 realtime_rate: 1.0 -q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] -q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] +#q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] +q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] +#q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] +q_init_plate: [1, 0, 0, 0, 0.68, 0.00, 1.205] q_init_box: [1, 0, 0, 0, 1.0, -0.2, 1.1] diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 0745e46848..1fdb0b8c11 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -3,7 +3,7 @@ - 0.5 + 0.25 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 5c0cce8abc..5202e8cc77 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -152,6 +152,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, 0.25, 0.75, 1); } + for (int i : vector({1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, -0.25, 0.25, 1); + } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 556bc2f2e9..d17e03bebd 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -457,14 +457,14 @@ void OperationalSpaceControl::Build() { .get(); } // 3. external force cost - for (auto& force_tracking_data: *force_tracking_data_vec_){ - DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); - lambda_ee_cost_ = - prog_ - ->AddQuadraticCost(, VectorXd::Zero(n_h_), lambda_h_) - .evaluator() - .get(); - } +// for (auto& force_tracking_data: *force_tracking_data_vec_){ +// DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); +// lambda_ee_cost_ = +// prog_ +// ->AddQuadraticCost(, VectorXd::Zero(n_h_), lambda_h_) +// .evaluator() +// .get(); +// } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { soft_constraint_cost_ = From 077ed0c2d13b122e400820e33dcacfd7481b67a5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 23 May 2023 13:48:18 -0400 Subject: [PATCH 476/758] adding end effector plotting --- .../pydairlib/analysis/log_plotter_franka.py | 118 ++++++++++---- .../pydairlib/analysis/mbp_plotting_utils.py | 148 ++++++++++++++---- examples/franka/franka_sim_params.yaml | 4 +- 3 files changed, 206 insertions(+), 64 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 150b0c48b9..532f8f1132 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -26,8 +26,8 @@ def main(): franka_plant, franka_context, tray_plant, tray_context = franka_plots.make_plant_and_context() pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(franka_plant) - pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors(franka_plant) - + pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors( + franka_plant) ''' Read the log ''' filename = sys.argv[1] @@ -39,7 +39,8 @@ def main(): plot_config.start_time, plot_config.duration, mbp_plots.load_default_channels, # processing callback - franka_plant, channel_x, channel_u, channel_osc) # processing callback arguments + franka_plant, channel_x, channel_u, + channel_osc) # processing callback arguments print('Finished processing log - making plots') # Define x time slice @@ -52,81 +53,132 @@ def main(): if plot_config.plot_joint_positions: plot = mbp_plots.plot_joint_positions(robot_output, pos_names, 0, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) # Plot specific positions if plot_config.pos_names: - plot = mbp_plots.plot_positions_by_name(robot_output, plot_config.pos_names, + plot = mbp_plots.plot_positions_by_name(robot_output, + plot_config.pos_names, t_x_slice, pos_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) # Plot all joint velocities if plot_config.plot_joint_velocities: plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) # Plot specific velocities if plot_config.vel_names: - plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, + plot = mbp_plots.plot_velocities_by_name(robot_output, + plot_config.vel_names, t_x_slice, vel_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) + + mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, + franka_context, ['paddle'], + {'paddle': np.zeros(3)}, + {'paddle': [0, 1, 2]}) + + mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, + franka_context, ['paddle'], + {'paddle': np.zeros(3)}, + {'paddle': [0, 1, 2]}) + q = np.load( + '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_q.npy') + v = np.load( + '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_v.npy') + t = np.load( + '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_t.npy') + pos = mbp_plots.make_point_positions_from_q(q, + franka_plant, franka_context, + franka_plant.GetBodyByName( + 'paddle').body_frame(), + np.zeros(3)) + vel = mbp_plots.make_point_velocities_from_qv(q, + v, + franka_plant, franka_context, + franka_plant.GetBodyByName( + 'paddle').body_frame(), + np.zeros(3)) + ps = plot_styler.PlotStyler() + ps.plot(t, pos, title='leon_experiment_positions') + ps = plot_styler.PlotStyler() + ps.plot(t, vel, title='leon_experiment_velocities') + ps = plot_styler.PlotStyler() + + ps.plot(t[1:], 1 / np.diff(t) * np.diff(vel, axis=0)[:, 1], + title='leon_experiment_accelerations', ylim=[-10, 10]) ''' Plot Efforts ''' if plot_config.plot_measured_efforts: - plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot = mbp_plots.plot_measured_efforts(robot_output, act_names, + t_x_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) if plot_config.plot_commanded_efforts: - plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, + t_osc_slice) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) if plot_config.act_names: plot = mbp_plots.plot_measured_efforts_by_name(robot_output, - plot_config.act_names, - t_x_slice, act_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - + plot_config.act_names, + t_x_slice, act_map) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) ''' Plot OSC ''' if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) plt.ylim([0, 1e3]) if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) if plot_config.plot_qp_solutions: plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): for deriv in config['derivs']: for dim in config['dims']: - plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, + plot = mbp_plots.plot_osc_tracking_data(osc_debug, + traj_name, dim, deriv, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) - # plot.save_fig(traj_name + '_' + deriv + '_' + str(dim) + '.png') - tracking_data = osc_debug['osc_debug_tracking_datas'][traj_name] - # print(tracking_data.name + str(dim)) - # print('mean error: ' + str(np.nanmax(np.sqrt(tracking_data.error_y[:, dim].flatten()**2)))) - # print('mean error at end of tracking: ' + str(np.mean(np.sqrt(tracking_data.error_y[:, dim][np.append(np.isnan(tracking_data.error_y[:, dim][1:]), False)]**2)))) - # plot = mbp_plots.plot_osc_tracking_data_in_space(osc_debug, traj_name, config['dims'], deriv, t_osc_slice) - # plot.save_fig('swing_foot_target_trajectory.png') + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], + osc_debug['fsm'], + plot_config.fsm_state_names) + tracking_data = osc_debug['osc_debug_tracking_datas'][ + traj_name] if plot_config.plot_qp_solve_time: plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], + plot_config.fsm_state_names) if plot_config.plot_active_tracking_datas: - plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, osc_debug['t_osc'], osc_debug['fsm'], plot_config.fsm_state_names) + plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, + osc_debug['t_osc'], + osc_debug['fsm'], + plot_config.fsm_state_names) # plot.save_fig('active_tracking_datas.png') + plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index db5047cf5b..ade7ac412b 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -2,16 +2,19 @@ import matplotlib.pyplot as plt from matplotlib.patches import Patch +from pydrake.all import JacobianWrtVariable + from bindings.pydairlib.common import plot_styler, plotting_utils -from bindings.pydairlib.analysis.osc_debug import lcmt_osc_tracking_data_t, osc_tracking_cost, osc_regularlization_tracking_cost +from bindings.pydairlib.analysis.osc_debug import lcmt_osc_tracking_data_t, \ + osc_tracking_cost, osc_regularlization_tracking_cost from bindings.pydairlib.multibody import MakeNameToPositionsMap, \ MakeNameToVelocitiesMap, MakeNameToActuatorsMap, \ CreateStateNameVectorFromMap, CreateActuatorNameVectorFromMap +OSC_DERIV_UNITS = {'pos': 'Position $(m)$', + 'vel': 'Velocity $(m/s)$', + 'accel': 'Acceleration $(m/s^2)$'} -OSC_DERIV_UNITS = {'pos' : 'Position $(m)$', - 'vel' : 'Velocity $(m/s)$', - 'accel' : 'Acceleration $(m/s^2)$'} def make_name_to_mbp_maps(plant): return MakeNameToPositionsMap(plant), \ @@ -114,6 +117,27 @@ def make_point_positions_from_q( return pos +def make_point_velocities_from_qv( + q, v, plant, context, frame, pt_on_frame, frame_measured_in=None, + frame_expressed_in=None): + if frame_measured_in is None: + frame_measured_in = plant.world_frame() + if frame_expressed_in is None: + frame_expressed_in = plant.world_frame() + + vel = np.zeros((v.shape[0], 3)) + for i, generalized_pos_vel in enumerate(zip(q, v)): + plant.SetPositions(context, generalized_pos_vel[0]) + J = plant.CalcJacobianTranslationalVelocity(context, + JacobianWrtVariable.kV, + frame, pt_on_frame, + frame_measured_in, + frame_expressed_in) + vel[i] = J @ generalized_pos_vel[1] + + return vel + + def get_floating_base_velocity_in_body_frame( robot_output, plant, context, fb_frame): vel = np.zeros((robot_output['q'].shape[0], 3)) @@ -129,9 +153,11 @@ def get_floating_base_velocity_in_body_frame( def process_osc_channel(data): t_osc = [] if hasattr(data[0], 'regularization_cost_names'): - regularization_costs = osc_regularlization_tracking_cost(data[0].regularization_cost_names) + regularization_costs = osc_regularlization_tracking_cost( + data[0].regularization_cost_names) else: - regularization_costs = osc_regularlization_tracking_cost(['input_cost', 'acceleration_cost', 'soft_constraint_cost']) + regularization_costs = osc_regularlization_tracking_cost( + ['input_cost', 'acceleration_cost', 'soft_constraint_cost']) qp_solve_time = [] u_sol = [] lambda_c_sol = [] @@ -145,11 +171,15 @@ def process_osc_channel(data): for msg in data: t_osc.append(msg.utime / 1e6) if hasattr(msg, 'regularization_cost_names'): - regularization_costs.append(msg.regularization_cost_names, msg.regularization_costs) + regularization_costs.append(msg.regularization_cost_names, + msg.regularization_costs) else: - regularization_cost_names = ['input_cost', 'acceleration_cost', 'soft_constraint_cost'] - regularization_cost_list = [msg.input_cost, msg.acceleration_cost, msg.soft_constraint_cost] - regularization_costs.append(regularization_cost_names, regularization_cost_list) + regularization_cost_names = ['input_cost', 'acceleration_cost', + 'soft_constraint_cost'] + regularization_cost_list = [msg.input_cost, msg.acceleration_cost, + msg.soft_constraint_cost] + regularization_costs.append(regularization_cost_names, + regularization_cost_list) qp_solve_time.append(msg.qp_output.solve_time) u_sol.append(msg.qp_output.u_sol) lambda_c_sol.append(msg.qp_output.lambda_c_sol) @@ -170,9 +200,11 @@ def process_osc_channel(data): tracking_cost_handler = osc_tracking_cost(osc_debug_tracking_datas.keys()) for msg in data: if hasattr(msg, 'tracking_costs'): - tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_costs) + tracking_cost_handler.append(msg.tracking_data_names, + msg.tracking_costs) else: - tracking_cost_handler.append(msg.tracking_data_names, msg.tracking_cost) + tracking_cost_handler.append(msg.tracking_data_names, + msg.tracking_cost) tracking_cost = tracking_cost_handler.convertToNP() for name in osc_debug_tracking_datas: @@ -267,6 +299,7 @@ def load_force_channels(data, contact_force_channel): contact_info = process_contact_channel(data[contact_force_channel]) return contact_info + def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, ylabel=None, title=None): @@ -311,7 +344,8 @@ def plot_u_cmd( return ps -def plot_u_cmd(robot_input, key, x_names, x_slice, time_slice, ylabel=None, title=None): +def plot_u_cmd(robot_input, key, x_names, x_slice, time_slice, ylabel=None, + title=None): ps = plot_styler.PlotStyler() if ylabel is None: ylabel = key @@ -402,7 +436,6 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, plant, context, frame, pt) legend_entries[name] = [name + dim_map[dim] for dim in dims[name]] - plotting_utils.make_plot( data_dict, 't', @@ -417,6 +450,37 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, return ps +def plot_points_velocities(robot_output, time_slice, plant, context, frame_names, + pts, dims, ps=None): + if ps is None: + ps = plot_styler.PlotStyler() + + dim_map = ['_x', '_y', '_z'] + data_dict = {'t': robot_output['t_x']} + legend_entries = {} + for name in frame_names: + frame = plant.GetBodyByName(name).body_frame() + pt = pts[name] + data_dict[name] = make_point_velocities_from_qv(robot_output['q'], + robot_output['v'], + plant, context, + frame, np.zeros(3)) + legend_entries[name] = [name + dim_map[dim] for dim in dims[name]] + + plotting_utils.make_plot( + data_dict, + 't', + time_slice, + frame_names, + dims, + legend_entries, + {'title': 'Point Velocities', + 'xlabel': 'time (s)', + 'ylabel': 'pos (m)'}, ps) + + return ps + + def plot_floating_base_body_frame_velocities(robot_output, time_slice, plant, context, fb_frame_name): data_dict = {'t': robot_output['t_x']} @@ -473,6 +537,7 @@ def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) return ps + def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): ps = plot_styler.PlotStyler() keys = [key for key in data.keys() if key != 't'] @@ -488,6 +553,7 @@ def plot_general_osc_tracking_data(traj_name, deriv, dim, data, time_slice): 'title': f'{traj_name} {deriv} tracking {dim}'}, ps) return ps + def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): tracking_data = osc_debug['osc_debug_tracking_datas'][traj] data = {} @@ -498,7 +564,9 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): elif deriv == 'vel': data['ydot_des'] = tracking_data.ydot_des[:, dim] data['ydot'] = tracking_data.ydot[:, dim] - data['error_ydot'] = tracking_data.ydot_des[:, dim] - tracking_data.ydot[:, dim] + data['error_ydot'] = tracking_data.ydot_des[:, + dim] - tracking_data.ydot[:, + dim] data['projected_error_ydot'] = tracking_data.error_ydot[:, dim] elif deriv == 'accel': data['yddot_des'] = tracking_data.yddot_des[:, dim] @@ -509,6 +577,7 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): return plot_general_osc_tracking_data(traj, deriv, dim, data, time_slice) + def plot_osc_tracking_data_in_space(osc_debug, traj, dims, deriv, time_slice): tracking_data = osc_debug['osc_debug_tracking_datas'][traj] data = {} @@ -520,20 +589,30 @@ def plot_osc_tracking_data_in_space(osc_debug, traj, dims, deriv, time_slice): elif deriv == 'vel': data['ydot_des_' + str(dim)] = tracking_data.ydot_des[:, dim] data['ydot_' + str(dim)] = tracking_data.ydot[:, dim] - data['error_ydot_' + str(dim)] = tracking_data.ydot_des[:, dim] - tracking_data.ydot[:, dim] - data['projected_error_ydot_' + str(dim)] = tracking_data.error_ydot[:, dim] + data['error_ydot_' + str(dim)] = tracking_data.ydot_des[:, + dim] - tracking_data.ydot[:, dim] + data['projected_error_ydot_' + str(dim)] = tracking_data.error_ydot[ + :, + dim] elif deriv == 'accel': data['yddot_des_' + str(dim)] = tracking_data.yddot_des[:, dim] - data['yddot_command_' + str(dim)] = tracking_data.yddot_command[:, dim] - data['yddot_command_sol_' + str(dim)] = tracking_data.yddot_command_sol[:, dim] + data['yddot_command_' + str(dim)] = tracking_data.yddot_command[:, + dim] + data['yddot_command_sol_' + str( + dim)] = tracking_data.yddot_command_sol[:, + dim] data['t'] = tracking_data.t ps = plot_styler.PlotStyler() - ps.plot(data['y_des_' + str(0)], data['y_des_' + str(2)] - data['y_des_' + str(2)][0], xlabel='Forward Position (m)', ylabel='Vertical Position (m)', grid=False) + ps.plot(data['y_des_' + str(0)], + data['y_des_' + str(2)] - data['y_des_' + str(2)][0], + xlabel='Forward Position (m)', ylabel='Vertical Position (m)', + grid=False) # ps.tight_layout() # ps.axes[0].set_ylim([-0.05, 0.5]) return ps + def plot_qp_costs(osc_debug, time_slice): ps = plot_styler.PlotStyler() regularization_cost = osc_debug['regularization_costs'].regularization_costs @@ -639,16 +718,21 @@ def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names): # uses default color map legend_elements = [] for i in np.unique(fsm_signal): - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2 * i), alpha=0.2) + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), + color=ps.cmap(2 * i), alpha=0.2) if fsm_state_names: - legend_elements.append(Patch(facecolor=ps.cmap(2 * i), alpha=0.3, label=fsm_state_names[i])) + legend_elements.append( + Patch(facecolor=ps.cmap(2 * i), alpha=0.3, + label=fsm_state_names[i])) if len(legend_elements) > 0: legend = ax.legend(handles=legend_elements, loc=4) # ax.add_artist(legend) ax.relim() -def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_state_names): + +def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, + fsm_state_names): ps = plot_styler.PlotStyler() ax = ps.fig.axes[0] @@ -673,20 +757,26 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_ # tracking_data_name = tracking_data_names[i] tracking_data = osc_debug['osc_debug_tracking_datas'][ tracking_data_name] - ax.fill_between(fsm_time, ymax - (i+0.25)/n_tracking_datas, ymax - - (i+0.75)/n_tracking_datas, + ax.fill_between(fsm_time, ymax - (i + 0.25) / n_tracking_datas, ymax - + (i + 0.75) / n_tracking_datas, where=tracking_data.is_active.astype(bool)[ :fsm_time.shape[0]], color=ps.cmap(2 * i), alpha=0.7) tracking_data_legend_elements.append(Patch(facecolor=ps.cmap(2 * i), - alpha=0.7, label=tracking_data_name_dict[tracking_data_name])) + alpha=0.7, + label= + tracking_data_name_dict[ + tracking_data_name])) # uses default color map legend_elements = [] for i in np.unique(fsm_signal): - ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), color=ps.cmap(2 * i), alpha=0.2) + ax.fill_between(fsm_time, ymin, ymax, where=(fsm_signal == i), + color=ps.cmap(2 * i), alpha=0.2) if fsm_state_names: - legend_elements.append(Patch(facecolor=ps.cmap(2 * i), alpha=0.3, label=fsm_state_names[i])) + legend_elements.append( + Patch(facecolor=ps.cmap(2 * i), alpha=0.3, + label=fsm_state_names[i])) ps.tight_layout() if len(legend_elements) > 0: @@ -700,4 +790,4 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, fsm_ ax.set_xlabel('Time (s)') ax.set_ylabel('Tracking Objective') - return ps \ No newline at end of file + return ps diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 951d9aff61..bddce88aac 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -9,9 +9,9 @@ actuator_delay: 0.000 visualize: false dt: 0.0001 -realtime_rate: 1.0 +realtime_rate: 0.1 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] -q_init_plate: [1, 0, 0, 0, 0.68, 0.00, 1.205] +q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.205] q_init_box: [1, 0, 0, 0, 1.0, -0.2, 1.1] From 819822fea774129b1baa42e5f69c57218d9d1541 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 23 Oct 2023 13:52:02 -0400 Subject: [PATCH 477/758] updates to 22.04 --- .../franka/franka_c3_options_translation.yaml | 10 +-- examples/franka/franka_sim_params.yaml | 6 +- .../franka/saved_trajectories/franka_defaults | Bin 0 -> 479 bytes examples/franka/urdf/franka.urdf | 59 ++++++++---------- examples/franka/urdf/franka_no_collision.urdf | 20 +++--- .../urdf/plate_end_effector_floating.urdf | 11 +--- .../urdf/plate_end_effector_translation.urdf | 11 +--- examples/franka/urdf/tray.sdf | 17 ++--- examples/franka/urdf/tray_lcs.sdf | 7 ++- solvers/cost_function_utils.cc | 2 +- solvers/lcs_factory.cc | 14 ++++- systems/framework/lcm_driven_loop.h | 1 + .../trajectory_optimization/dircon/dircon.h | 2 + 13 files changed, 77 insertions(+), 83 deletions(-) create mode 100644 examples/franka/saved_trajectories/franka_defaults diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index cb3a1a83bc..e8e9dd6dee 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -1,4 +1,4 @@ -admm_iter: 4 +admm_iter: 3 rho: 0.1 rho_scale: 2 num_threads: 4 @@ -6,11 +6,11 @@ delta_option: 1 mu: 0.2 mu_plate: 1 -dt: 0.08 -solve_dt: 0.05 +dt: 0.05 +solve_dt: 0.00 num_friction_directions: 2 num_contacts: 3 -N: 5 +N: 8 w_Q: 10 w_R: 0 # Penalty on all decision variables, assuming scalar @@ -21,7 +21,7 @@ w_U: 1 g_size: 40 u_size: 40 # State Tracking Error, assuming diagonal -q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [200, 200, 500, 0, 0, 0, 0, 10000, 10000, 1, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 86e74c0c4b..1f6d9d5432 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -4,10 +4,10 @@ tray_state_channel: TRAY_OUTPUT franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true -actuator_delay: 0.005 +actuator_delay: 0.000 visualize: true dt: 0.0001 -realtime_rate: 0.5 -q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] +realtime_rate: 1.0 +q_init_franka: [-1.0, 1.6, 1.3, -1.65, 1.5, 1.3, -0.65] q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults new file mode 100644 index 0000000000000000000000000000000000000000..92e6539977d88ce766f84b7ad237e339cfe8a50e GIT binary patch literal 479 zcma#*(7CMgmLZyrfq{V$h|vjVpb$@fQdVkmNqk9BVirgV6A**M!N7j!Oc0o5|Ktn^ zoQ2Uac^GYf*%%C9G*Fy9CBHN&Cl#auJ5wk%FC{)TEe&XSei8kxS3t2ozbG>`uOzV~ qGe0lBB(W$xwFKmFP*{L47}$S+u?W&UNXCH_WAahM9D7g@bRhs>MR*PX literal 0 HcmV?d00001 diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index b215cfac27..be0c08e862 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -1,21 +1,19 @@ - + + + + - - - - - + - + @@ -107,13 +105,12 @@ - + - + @@ -164,13 +161,12 @@ - + - + @@ -221,13 +217,12 @@ - + - + @@ -272,13 +267,12 @@ - + - + @@ -335,13 +329,12 @@ - + - + @@ -428,13 +421,12 @@ - + - + @@ -475,17 +467,16 @@ - , + - + - + @@ -523,11 +514,11 @@ - + - + @@ -535,7 +526,7 @@ - + @@ -648,4 +639,4 @@ - + \ No newline at end of file diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 1dc88eafb6..80fd2d153c 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -17,7 +17,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link0.obj"/> @@ -33,7 +33,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link1.obj"/> @@ -56,7 +56,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link2.obj"/> @@ -79,7 +79,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link3.obj"/> @@ -102,7 +102,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link4.obj"/> @@ -125,7 +125,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link5.obj"/> @@ -148,7 +148,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link6.obj"/> @@ -171,7 +171,7 @@ + filename="package://drake_models/franka_description/meshes/visual/link7.obj"/> @@ -197,7 +197,7 @@ - + @@ -209,7 +209,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_floating.urdf b/examples/franka/urdf/plate_end_effector_floating.urdf index 169119b303..efaa4bb17f 100644 --- a/examples/franka/urdf/plate_end_effector_floating.urdf +++ b/examples/franka/urdf/plate_end_effector_floating.urdf @@ -9,14 +9,9 @@ - - + + + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 75d8f4ee0d..3080adbe1c 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -6,14 +6,9 @@ - - + + + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 647583fc90..b60121945d 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -3,16 +3,17 @@ + 0 0 0 0 0 0 2 - 0.06 + 0.060067 0 0 - 0.015 + 0.060067 0 - 0.075 + 0.12 @@ -29,16 +30,16 @@ - - - - + + + 3.0e7 + 1.0 - 1 + diff --git a/examples/franka/urdf/tray_lcs.sdf b/examples/franka/urdf/tray_lcs.sdf index 4f5e0febd2..229af25b94 100644 --- a/examples/franka/urdf/tray_lcs.sdf +++ b/examples/franka/urdf/tray_lcs.sdf @@ -3,16 +3,17 @@ + 0.05 0 0 0 0 0 2 - 0.06 + 0.12 0 0 - 0.015 + 0.040001 0 - 0.075 + 0.16 diff --git a/solvers/cost_function_utils.cc b/solvers/cost_function_utils.cc index b696011ba5..7c8e4a41d5 100644 --- a/solvers/cost_function_utils.cc +++ b/solvers/cost_function_utils.cc @@ -22,7 +22,7 @@ void AddPositiveWorkCost( int n_v = plant.num_velocities(); int n_u = plant.num_actuators(); drake::solvers::VectorXDecisionVariable variables(n_vars); - variables(0) = trajopt.timestep(i)(0); + variables(0) = trajopt.time_step(i)(0); variables.segment(1, n_v) = trajopt.state_vars(mode, i - mode_start).tail(n_v); variables.segment(1 + n_v, n_v) = diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 0f5d3f2e4b..2bc4c4a853 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -77,8 +77,16 @@ std::pair LCSFactory::LinearizePlantToLCS( plant_ad.MapVelocityToQDot(context_ad, vel_ad, &qdot_no_contact); MatrixXd AB_q = ExtractGradient(qdot_no_contact); MatrixXd d_q = ExtractValue(qdot_no_contact); - MatrixXd Nq = AB_q.block(0, n_q, n_q, n_v); + Eigen::SparseMatrix Nqt; + Nqt = plant.MakeVelocityToQDotMap(context); + MatrixXd Nq = MatrixXd(Nqt); + //plant_ad.MapQDotToVelocity(context_ad, qdot_no_contact, &vel); + + //std::optional> NqI = std::nullopt; + Eigen::SparseMatrix NqI; + NqI = plant.MakeQDotToVelocityMap(context); + MatrixXd NqInverse = MatrixXd(NqI); /// /// Contact-related terms /// @@ -149,7 +157,7 @@ std::pair LCSFactory::LinearizePlantToLCS( d.tail(n_v) = dt * d_v; E = MatrixXd::Zero(n_contact_vars, n_x); - E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q; + E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q + J_n * NqInverse;; E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = dt * J_t * AB_v_q; E.block(n_contacts, n_q, n_contacts, n_v) = dt * J_n + dt * dt * J_n * AB_v_v; @@ -195,7 +203,7 @@ std::pair LCSFactory::LinearizePlantToLCS( c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = - J_t * dt * d_v; + J_t * dt * d_v - J_n * NqInverse * plant.GetPositions(context); auto Dn = D.squaredNorm(); auto An = A.squaredNorm(); diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index a691e104ff..e1ee3b0889 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -3,6 +3,7 @@ #include #include #include +#include #include "dairlib/lcmt_controller_switch.hpp" #include "dairlib/lcmt_robot_output.hpp" diff --git a/systems/trajectory_optimization/dircon/dircon.h b/systems/trajectory_optimization/dircon/dircon.h index 5b450cf4c0..7b8ccc8280 100644 --- a/systems/trajectory_optimization/dircon/dircon.h +++ b/systems/trajectory_optimization/dircon/dircon.h @@ -203,6 +203,8 @@ class Dircon return mode_sequence_.mode(mode); } + const int get_mode_start(int index) { return mode_start_[index]; } + const drake::systems::Context& get_context(int mode, int knotpoint_index) { return *contexts_.at(mode).at(knotpoint_index); } From 81d7ac0c00dfa4b614baa7c319a9ac88f9896624 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 23 Oct 2023 15:36:45 -0400 Subject: [PATCH 478/758] update from mian --- examples/Cassie/cassie_xbox_remote.py | 2 +- .../diagrams/osc_running_controller_diagram.cc | 2 -- examples/franka/franka_c3_controller_params.h | 1 - examples/franka/franka_controller_params.h | 1 - examples/franka/franka_sim_params.h | 2 -- examples/franka/franka_sim_params.yaml | 6 +++--- .../franka/saved_trajectories/franka_defaults | Bin 479 -> 479 bytes solvers/c3_options.h | 1 - 8 files changed, 4 insertions(+), 11 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 0209e45962..82e0197cbf 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -96,7 +96,7 @@ def main(): publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) # Limit to 20 frames per second - clock.tick(20) + clock.tick(100) i += 1 pygame.quit() diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index b0cf012fb2..15dc9f0c8b 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -2,7 +2,6 @@ #include #include -#include #include "common/find_resource.h" #include "examples/Cassie/cassie_utils.h" @@ -26,7 +25,6 @@ #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" #include "drake/systems/framework/diagram_builder.h" diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index e1573819e7..76589508f2 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -1,7 +1,6 @@ #pragma once #include "solvers/c3_options.h" -#include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_controller_params.h index eff0e18c20..12166fad28 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_controller_params.h @@ -1,7 +1,6 @@ #pragma once #include "systems/controllers/osc/osc_gains.h" -#include "yaml-cpp/yaml.h" #include "drake/common/yaml/yaml_read_archive.h" diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 8eb57b673f..893d93843c 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -1,7 +1,5 @@ #pragma once -#include "yaml-cpp/yaml.h" - #include "drake/common/yaml/yaml_read_archive.h" using Eigen::MatrixXd; diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index bddce88aac..78f231567c 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -6,10 +6,10 @@ franka_model: examples/franka/urdf/franka_no_collision.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 -visualize: false +visualize: true -dt: 0.0001 -realtime_rate: 0.1 +dt: 0.0005 +realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults index 92e6539977d88ce766f84b7ad237e339cfe8a50e..59651e0bf4502ddf28fa1e36475a17b414d7b199 100644 GIT binary patch delta 60 zcmcc5e4lxO%H(~Fij!>_qbJU-pQutfS%y(XStvCxB|bGREj76$zbL+>C^3rx2zc_7 JvVbBGJ^+t{6oUW& delta 39 vcmcc5e4lxO%4B)Q%83i=C(mG1ndlM0!;_zsm6}` Date: Tue, 24 Oct 2023 16:47:48 -0400 Subject: [PATCH 479/758] still need to make models in different controllers consistent, move more parameters to yaml --- examples/franka/BUILD.bazel | 1 + examples/franka/franka_c3_controller.cc | 8 +-- .../franka/franka_c3_controller_params.yaml | 4 +- .../franka/franka_c3_options_translation.yaml | 6 +- examples/franka/franka_osc_controller.cc | 6 +- ...yaml => franka_osc_controller_params.yaml} | 2 +- examples/franka/franka_sim.cc | 62 ++++++++++--------- examples/franka/franka_sim_params.h | 10 +++ examples/franka/franka_sim_params.yaml | 14 +++-- examples/franka/franka_visualizer.cc | 56 ++++++++++------- examples/franka/urdf/franka.urdf | 4 +- examples/franka/urdf/franka_no_collision.urdf | 4 +- examples/franka/urdf/plate_end_effector.urdf | 49 ++------------- examples/franka/urdf/table.sdf | 24 +++---- examples/franka/urdf/tray.sdf | 8 +-- solvers/c3.cc | 3 +- systems/controllers/c3_controller.cc | 6 +- 17 files changed, 129 insertions(+), 138 deletions(-) rename examples/franka/{franka_controller_params.yaml => franka_osc_controller_params.yaml} (99%) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 29b9541868..e37b5cf780 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -103,6 +103,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ + ":franka_sim_params", "//common:find_resource", "//multibody:utils", "//multibody:visualization_utils", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 2d75f29d3b..47fc787196 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -75,7 +75,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.package_map().Add("franka_urdfs", "examples/franka/urdf"); - parser_franka.AddModelFromFile(controller_params.franka_model); + parser_franka.AddModels(controller_params.franka_model); RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); @@ -85,7 +85,7 @@ int DoMain(int argc, char* argv[]) { /// MultibodyPlant plant_tray(0.0); Parser parser_tray(&plant_tray, nullptr); - parser_tray.AddModelFromFile(controller_params.tray_model); + parser_tray.AddModels(controller_params.tray_model); plant_tray.Finalize(); auto tray_context = plant_tray.CreateDefaultContext(); @@ -93,8 +93,8 @@ int DoMain(int argc, char* argv[]) { auto [plant_plate, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); Parser parser_plate(&plant_plate); - parser_plate.AddModelFromFile(controller_params.plate_model); - parser_plate.AddModelFromFile(controller_params.tray_model); + parser_plate.AddModels(controller_params.plate_model); + parser_plate.AddModels(controller_params.tray_model); plant_plate.WeldFrames(plant_plate.world_frame(), plant_plate.GetFrameByName("base_link"), X_WI); diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 4233b5680f..3f08f4a223 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -7,13 +7,13 @@ state_channel: FRANKA_OUTPUT radio_channel: CASSIE_VIRTUAL_RADIO -franka_model: examples/franka/urdf/franka.urdf +franka_model: examples/franka/urdf/franka_no_collision.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 3 +target_frequency: 4 diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index fadf7fb85b..e51b0cd48d 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -1,17 +1,17 @@ admm_iter: 3 rho: 0.1 rho_scale: 2 -num_threads: 4 +num_threads: 6 delta_option: 1 -mu: 0.2 +mu: 0.4 mu_plate: 1 dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 N: 5 -w_Q: 10 +w_Q: 5 w_R: 0 # Penalty on all decision variables, assuming scalar w_G: 0.5 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index e09b0442d2..080b462255 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -62,9 +62,9 @@ int DoMain(int argc, char* argv[]) { yaml_options.allow_yaml_with_no_cpp = true; FrankaControllerParams controller_params = drake::yaml::LoadYamlFile( - "examples/franka/franka_controller_params.yaml"); + "examples/franka/franka_osc_controller_params.yaml"); OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow("examples/franka/franka_controller_params.yaml"), {}, + FindResourceOrThrow("examples/franka/franka_osc_controller_params.yaml"), {}, {}, yaml_options); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( @@ -74,7 +74,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); Parser parser(&plant, nullptr); - parser.AddModelFromFile(controller_params.franka_model); + parser.AddModels(controller_params.franka_model); RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); diff --git a/examples/franka/franka_controller_params.yaml b/examples/franka/franka_osc_controller_params.yaml similarity index 99% rename from examples/franka/franka_controller_params.yaml rename to examples/franka/franka_osc_controller_params.yaml index c3ceb06c56..a54142ea5f 100644 --- a/examples/franka/franka_controller_params.yaml +++ b/examples/franka/franka_osc_controller_params.yaml @@ -42,7 +42,7 @@ EndEffectorKd: MidLinkW: [0, 0, 0, 0, 0, 0, - 0, 0, 2] + 0, 0, 10] MidLinkKp: [ 0, 0, 0, 0, 0, 0, diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 7564ae1b1f..54ea360bc0 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -64,51 +64,55 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModelFromFile(sim_params.franka_model); - drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( - drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"), - "table0"); - drake::multibody::ModelInstanceIndex second_table_index = - parser.AddModelFromFile( - dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), - "table1"); - drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile( - FindResourceOrThrow("examples/franka/urdf/tray.sdf")); - - drake::multibody::ModelInstanceIndex box_index = parser.AddModelFromFile( - FindResourceOrThrow("examples/franka/urdf/default_box.urdf")); + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + drake::multibody::ModelInstanceIndex table_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.table_model))[0]; + drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( + FindResourceOrThrow(sim_params.end_effector_model))[0]; + plant.RenameModelInstance(table_index, "table0"); + drake::multibody::ModelInstanceIndex second_table_index = parser.AddModels( + drake::FindResourceOrThrow(sim_params.table_w_supports_model))[0]; + plant.RenameModelInstance(second_table_index, "table1"); + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + drake::multibody::ModelInstanceIndex box_index = + parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); Vector3d second_table_origin = Eigen::VectorXd::Zero(3); + Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); franka_origin(2) = 0.7645; second_table_origin(0) = 0.75; + tool_attachment_frame(2) = 0.157; RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_X_W = RigidTransform( drake::math::RotationMatrix(), second_table_origin); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), tool_attachment_frame); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", table_index), X_WI); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("table", second_table_index), T_X_W); + plant.GetFrameByName("link", second_table_index), T_X_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); - - const drake::geometry::GeometrySet& paddle_geom_set = - plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("paddle"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link7"), - }); - auto table_support_set = GeometrySet( - plant.GetCollisionGeometriesForBody(plant.GetBodyByName("table"))); - plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"paddle", paddle_geom_set}, {"table_support", table_support_set}); + plant.WeldFrames( plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), + T_EE_W); + + // const drake::geometry::GeometrySet& paddle_geom_set = + // plant.CollectRegisteredGeometries({ + // &plant.GetBodyByName("paddle"), + // &plant.GetBodyByName("panda_link4"), + // &plant.GetBodyByName("panda_link5"), + // &plant.GetBodyByName("panda_link6"), + // &plant.GetBodyByName("panda_link7"), + // }); + // auto table_support_set = GeometrySet( + // plant.GetCollisionGeometriesForBody(plant.GetBodyByName("table"))); + // plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + // {"paddle", paddle_geom_set}, {"table_support", table_support_set}); VectorXd rotor_inertias(plant.num_actuators()); rotor_inertias << 61, 61, 61, 61, 61, 61, 61; diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 893d93843c..9475eba175 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -11,6 +11,11 @@ struct FrankaSimParams { std::string tray_state_channel; std::string box_state_channel; std::string franka_model; + std::string end_effector_model; + std::string table_model; + std::string table_w_supports_model; + std::string tray_model; + std::string box_model; double dt; double realtime_rate; @@ -31,6 +36,11 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(tray_state_channel)); a->Visit(DRAKE_NVP(box_state_channel)); a->Visit(DRAKE_NVP(franka_model)); + a->Visit(DRAKE_NVP(end_effector_model)); + a->Visit(DRAKE_NVP(table_model)); + a->Visit(DRAKE_NVP(table_w_supports_model)); + a->Visit(DRAKE_NVP(tray_model)); + a->Visit(DRAKE_NVP(box_model)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 78f231567c..a3e51b6c17 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -2,16 +2,22 @@ state_channel: FRANKA_OUTPUT controller_channel: FRANKA_INPUT tray_state_channel: TRAY_OUTPUT box_state_channel: BOX_OUTPUT -franka_model: examples/franka/urdf/franka_no_collision.urdf +#franka_model: examples/franka/urdf/franka_no_collision.urdf +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf +table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf +tray_model: examples/franka/urdf/tray.sdf +box_model: examples/franka/urdf/default_box.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 visualize: true dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.5 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] -q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.205] -q_init_box: [1, 0, 0, 0, 1.0, -0.2, 1.1] +q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] +q_init_box: [1, 0, 0, 0, 0.9, -0.2, 1.1] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 185fdf49b7..a93b9713cc 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -7,6 +7,7 @@ #include "common/find_resource.h" #include "dairlib/lcmt_robot_output.hpp" +#include "examples/franka/franka_sim_params.h" #include "multibody/com_pose_system.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" @@ -58,6 +59,8 @@ using drake::systems::DiagramBuilder; int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/franka_sim_params.yaml"); drake::systems::DiagramBuilder builder; @@ -68,37 +71,42 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModelFromFile("examples/franka/urdf/franka.urdf"); - drake::multibody::ModelInstanceIndex table_index = parser.AddModelFromFile( - drake::FindResourceOrThrow( - "drake/examples/kuka_iiwa_arm/models/table/" - "extra_heavy_duty_table_surface_only_collision.sdf"), - "table0"); - drake::multibody::ModelInstanceIndex second_table_index = - parser.AddModelFromFile( - dairlib::FindResourceOrThrow("examples/franka/urdf/table.sdf"), - "table1"); - drake::multibody::ModelInstanceIndex tray_index = parser.AddModelFromFile( - FindResourceOrThrow("examples/franka/urdf/tray.sdf")); + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + drake::multibody::ModelInstanceIndex table_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.table_model))[0]; + drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( + FindResourceOrThrow(sim_params.end_effector_model))[0]; + plant.RenameModelInstance(table_index, "table0"); + drake::multibody::ModelInstanceIndex second_table_index = parser.AddModels( + drake::FindResourceOrThrow(sim_params.table_w_supports_model))[0]; + plant.RenameModelInstance(second_table_index, "table1"); + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; drake::multibody::ModelInstanceIndex box_index = - parser.AddModelFromFile(FindResourceOrThrow( - "examples/franka/urdf/default_box.urdf")); + parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; + multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); Vector3d second_table_origin = Eigen::VectorXd::Zero(3); + Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); franka_origin(2) = 0.7645; second_table_origin(0) = 0.75; + tool_attachment_frame(2) = 0.157; RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_X_W = RigidTransform( drake::math::RotationMatrix(), second_table_origin); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), tool_attachment_frame); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("link", table_index), X_WI); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("table", second_table_index), T_X_W); + plant.GetFrameByName("link", second_table_index), T_X_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); + plant.WeldFrames( plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), + T_EE_W); plant.Finalize(); @@ -111,9 +119,8 @@ int do_main(int argc, char* argv[]) { auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( "TRAY_OUTPUT", lcm)); - auto box_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - "BOX_OUTPUT", lcm)); + auto box_state_sub = builder.AddSystem( + LcmSubscriberSystem::Make("BOX_OUTPUT", lcm)); auto franka_state_receiver = builder.AddSystem(plant, franka_index); auto tray_state_receiver = @@ -146,17 +153,18 @@ int do_main(int argc, char* argv[]) { auto to_pose = builder.AddSystem>(plant); -// DrakeVisualizer::AddToBuilder(&builder, scene_graph); + // DrakeVisualizer::AddToBuilder(&builder, scene_graph); drake::geometry::MeshcatVisualizerParams params; params.publish_period = 1.0 / 60.0; params.enable_alpha_slider = true; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); - auto trajectory_drawer_actor = builder.AddSystem( - meshcat, "end_effector_traj"); - auto trajectory_drawer_object = builder.AddSystem( - meshcat, "object_traj"); + auto trajectory_drawer_actor = + builder.AddSystem(meshcat, + "end_effector_traj"); + auto trajectory_drawer_object = + builder.AddSystem(meshcat, "object_traj"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(5); @@ -196,7 +204,7 @@ int do_main(int argc, char* argv[]) { tray_state_receiver->InitializeSubscriberPositions(plant, tray_state_sub_context); box_state_receiver->InitializeSubscriberPositions(plant, - box_state_sub_context); + box_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf index 8b473c04ee..8fd83719a5 100644 --- a/examples/franka/urdf/franka.urdf +++ b/examples/franka/urdf/franka.urdf @@ -514,7 +514,7 @@ - + @@ -526,7 +526,7 @@ - + diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf index 80fd2d153c..0a824c84a6 100644 --- a/examples/franka/urdf/franka_no_collision.urdf +++ b/examples/franka/urdf/franka_no_collision.urdf @@ -197,7 +197,7 @@ - + @@ -209,7 +209,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 16265ee3f1..be7badad74 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -3,19 +3,14 @@ + - + - + @@ -27,44 +22,8 @@ - - - - - - - - - - - - - - - - - - - + - - - - - - - - - - - - - - - - - - diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf index e4c5953210..1b8236706b 100644 --- a/examples/franka/urdf/table.sdf +++ b/examples/franka/urdf/table.sdf @@ -163,10 +163,10 @@ - 0.04 0.12 0.9525 0 0 0 + 0.04 0.12 0.96 0 0 0 - 0.05 0.05 0.381 + 0.05 0.05 0.5 @@ -177,10 +177,10 @@ - 0.04 -0.12 0.9525 0 0 0 + 0.04 -0.12 0.96 0 0 0 - 0.05 0.05 0.381 + 0.05 0.05 0.5 @@ -191,10 +191,10 @@ - -0.20 0.12 0.9525 0 0 0 + -0.20 0.12 0.96 0 0 0 - 0.05 0.05 0.381 + 0.05 0.05 0.5 @@ -207,26 +207,26 @@ - 0.001 + 0.01 - 0.04 0.12 1.143 0 0 0 + 0.04 0.12 1.2 0 0 0 - 0.001 + 0.01 - 0.04 -0.12 1.143 0 0 0 + 0.04 -0.12 1.2 0 0 0 - 0.001 + 0.01 - -0.20 0.12 1.143 0 0 0 + -0.20 0.12 1.2 0 0 0 0 diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index b08b789bee..612d054e60 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -4,16 +4,16 @@ 0 0 0 0 0 0 - 2 + 0.5 - 0.060067 + 0.0066833 0 0 - 0.060067 + 0.0066833 0 - 0.12 + 0.013333 diff --git a/solvers/c3.cc b/solvers/c3.cc index fed7673d42..aa620570e4 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -298,9 +298,10 @@ vector C3::SolveProjection(vector& G, if (options_.num_threads > 0) { omp_set_dynamic(0); // Explicitly disable dynamic teams omp_set_num_threads(options_.num_threads); // Set number of threads + omp_set_nested(1); } -#pragma omp parallel for +#pragma omp parallel for num_threads(N_) for (i = 0; i < N_; i++) { if (warm_start_) { deltaProj[i] = diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 5202e8cc77..ed4d620592 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -147,15 +147,17 @@ drake::systems::EventStatus C3Controller::ComputePlan( delta_init.head(n_x_) = lcs_x->get_data(); std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); + + // Set actor bounds for (int i : vector({0, 2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.25, 0.75, 1); + c3_->AddLinearConstraint(A, 0.3, 0.7, 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -0.25, 0.25, 1); + c3_->AddLinearConstraint(A, -0.2, 0.2, 1); } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); return drake::systems::EventStatus::Succeeded(); From 6e3c0d7bca84dacd4ae97ad4aa3b536afaede6f3 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 26 Oct 2023 14:52:04 -0400 Subject: [PATCH 480/758] updating controllers to use correct model --- examples/franka/BUILD.bazel | 6 +- examples/franka/franka_c3_controller.cc | 14 ++++- examples/franka/franka_c3_controller_params.h | 4 ++ .../franka/franka_c3_controller_params.yaml | 6 +- .../franka/franka_c3_options_translation.yaml | 4 +- examples/franka/franka_osc_controller.cc | 62 ++++++++++--------- ...arams.h => franka_osc_controller_params.h} | 35 +++++++---- .../franka/franka_osc_controller_params.yaml | 11 +++- examples/franka/franka_sim_params.yaml | 5 +- .../franka/systems/end_effector_trajectory.cc | 58 +++-------------- .../franka/systems/end_effector_trajectory.h | 18 ++++-- examples/franka/urdf/plate_end_effector.urdf | 4 +- systems/controllers/c3_controller.cc | 2 +- 13 files changed, 121 insertions(+), 108 deletions(-) rename examples/franka/{franka_controller_params.h => franka_osc_controller_params.h} (79%) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index e37b5cf780..a502aa5211 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -59,7 +59,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_controller_params", + ":franka_osc_controller_params", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", @@ -125,8 +125,8 @@ cc_library( ) cc_library( - name = "franka_controller_params", - hdrs = ["franka_controller_params.h"], + name = "franka_osc_controller_params", + hdrs = ["franka_osc_controller_params.h"], deps = [ "@drake//:drake_shared_library", ], diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 47fc787196..cb045fce20 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -75,10 +75,20 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.package_map().Add("franka_urdfs", "examples/franka/urdf"); - parser_franka.AddModels(controller_params.franka_model); + parser_franka.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); + Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); + tool_attachment_frame(2) = 0.157; + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), tool_attachment_frame); + plant_franka.WeldFrames(plant_franka.GetFrameByName("panda_link7"), + plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); + plant_franka.Finalize(); auto franka_context = plant_franka.CreateDefaultContext(); @@ -150,7 +160,7 @@ int DoMain(int argc, char* argv[]) { auto reduced_order_model_receiver = builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), - "paddle", "tray", controller_params.include_end_effector_orientation); + controller_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index 76589508f2..654343f7a7 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -14,6 +14,8 @@ struct FrankaC3ControllerParams { std::string state_channel; std::string radio_channel; std::string franka_model; + std::string end_effector_model; + std::string end_effector_name; std::string plate_model; std::string tray_model; bool include_end_effector_orientation; @@ -28,6 +30,8 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(state_channel)); a->Visit(DRAKE_NVP(radio_channel)); a->Visit(DRAKE_NVP(franka_model)); + a->Visit(DRAKE_NVP(end_effector_model)); + a->Visit(DRAKE_NVP(end_effector_name)); a->Visit(DRAKE_NVP(plate_model)); a->Visit(DRAKE_NVP(tray_model)); a->Visit(DRAKE_NVP(include_end_effector_orientation)); diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index 3f08f4a223..b2a6f423b5 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -6,8 +6,10 @@ c3_channel_object: C3_TRAJECTORY_TRAY state_channel: FRANKA_OUTPUT radio_channel: CASSIE_VIRTUAL_RADIO - -franka_model: examples/franka/urdf/franka_no_collision.urdf +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate +#franka_model: examples/franka/urdf/franka_no_collision.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index e51b0cd48d..3809fce387 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -10,7 +10,7 @@ dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 -N: 5 +N: 7 w_Q: 5 w_R: 0 # Penalty on all decision variables, assuming scalar @@ -26,5 +26,5 @@ q_vector: [10, 10, 5000, 0, 0, 0, 0, 10000, 10000, 10000, # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] -q_des_vector: [0.55, 0.02, 0.4, 1, 0, 0, 0, 0.55, 0.02, 0.42] +q_des_vector: [0.55, 0.00, 0.4, 1, 0, 0, 0, 0.55, 0.00, 0.42] v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 080b462255..38b6f055b4 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -3,7 +3,7 @@ #include #include -#include "examples/franka/franka_controller_params.h" +#include "examples/franka/franka_osc_controller_params.h" #include "examples/franka/systems/end_effector_orientation.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" @@ -64,8 +64,8 @@ int DoMain(int argc, char* argv[]) { drake::yaml::LoadYamlFile( "examples/franka/franka_osc_controller_params.yaml"); OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow("examples/franka/franka_osc_controller_params.yaml"), {}, - {}, yaml_options); + FindResourceOrThrow("examples/franka/franka_osc_controller_params.yaml"), + {}, {}, yaml_options); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_osqp_settings)) @@ -74,26 +74,20 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); Parser parser(&plant, nullptr); - parser.AddModels(controller_params.franka_model); + parser.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); + Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); - VectorXd rotor_inertias(plant.num_actuators()); - rotor_inertias << 61, 61, 61, 61, 61, 61, 61; - rotor_inertias *= 1e-6; - VectorXd gear_ratios(plant.num_actuators()); - gear_ratios << 25, 25, 25, 25, 25, 25, 25; - std::vector motor_joint_names = { - "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", - "panda_motor5", "panda_motor6", "panda_motor7"}; - for (int i = 0; i < rotor_inertias.size(); ++i) { - auto& joint_actuator = plant.get_mutable_joint_actuator( - drake::multibody::JointActuatorIndex(i)); - joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); - joint_actuator.set_default_gear_ratio(gear_ratios(i)); - DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); - } + tool_attachment_frame(2) = 0.157; + + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), tool_attachment_frame); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName("plate", end_effector_index), T_EE_W); plant.Finalize(); auto plant_context = plant.CreateDefaultContext(); @@ -127,10 +121,17 @@ int DoMain(int argc, char* argv[]) { auto end_effector_trajectory = builder.AddSystem(plant, plant_context.get()); + VectorXd neutral_position = Eigen::Map( + controller_params.neutral_position.data(), + controller_params.neutral_position.size()); + end_effector_trajectory->SetRemoteControlParameters( + neutral_position, controller_params.x_scale, controller_params.y_scale, + controller_params.z_scale); auto end_effector_orientation_trajectory = builder.AddSystem(plant, plant_context.get()); - end_effector_orientation_trajectory->SetTrackOrientation(controller_params.track_end_effector_orientation); + end_effector_orientation_trajectory->SetTrackOrientation( + controller_params.track_end_effector_orientation); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( controller_params.radio_channel, &lcm)); @@ -150,7 +151,8 @@ int DoMain(int argc, char* argv[]) { "end_effector_target", controller_params.K_p_end_effector, controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); - end_effector_position_tracking_data->AddPointToTrack("paddle"); + end_effector_position_tracking_data->AddPointToTrack( + controller_params.end_effector_name); const VectorXd& bound = controller_params.end_effector_acceleration * Vector3d::Ones(); end_effector_position_tracking_data->SetCmdAccelerationBounds(-bound, bound); @@ -159,7 +161,8 @@ int DoMain(int argc, char* argv[]) { "end_effector_target", controller_params.K_p_end_effector, controller_params.K_d_end_effector, controller_params.W_end_effector, plant, plant); - end_effector_position_tracking_data_for_rel->AddPointToTrack("paddle"); + end_effector_position_tracking_data_for_rel->AddPointToTrack( + controller_params.end_effector_name); auto mid_link_position_tracking_data_for_rel = std::make_unique( "mid_link", controller_params.K_p_mid_link, @@ -182,7 +185,8 @@ int DoMain(int argc, char* argv[]) { controller_params.K_p_end_effector_rot, controller_params.K_d_end_effector_rot, controller_params.W_end_effector_rot, plant, plant); - end_effector_orientation_tracking_data->AddFrameToTrack("paddle"); + end_effector_orientation_tracking_data->AddFrameToTrack( + controller_params.end_effector_name); Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); orientation_target(0) = 1; @@ -219,14 +223,14 @@ int DoMain(int argc, char* argv[]) { end_effector_orientation_receiver->get_input_port_trajectory()); builder.Connect(end_effector_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); - builder.Connect(end_effector_orientation_receiver->get_output_port(0), - end_effector_orientation_trajectory->get_input_port_trajectory()); + builder.Connect( + end_effector_orientation_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_trajectory()); builder.Connect(end_effector_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_target")); - builder.Connect(end_effector_orientation_trajectory->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_orientation_target")); - - + builder.Connect( + end_effector_orientation_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); diff --git a/examples/franka/franka_controller_params.h b/examples/franka/franka_osc_controller_params.h similarity index 79% rename from examples/franka/franka_controller_params.h rename to examples/franka/franka_osc_controller_params.h index 12166fad28..b4efdff1c3 100644 --- a/examples/franka/franka_controller_params.h +++ b/examples/franka/franka_osc_controller_params.h @@ -4,8 +4,6 @@ #include "drake/common/yaml/yaml_read_archive.h" -using Eigen::MatrixXd; - struct FrankaControllerParams : OSCGains { std::string state_channel; std::string controller_channel; @@ -14,10 +12,17 @@ struct FrankaControllerParams : OSCGains { std::string c3_channel; std::string franka_model; + std::string end_effector_model; + std::string end_effector_name; double end_effector_acceleration; bool track_end_effector_orientation; + double x_scale; + double y_scale; + double z_scale; + + std::vector neutral_position; std::vector EndEffectorW; std::vector EndEffectorKp; std::vector EndEffectorKd; @@ -28,15 +33,16 @@ struct FrankaControllerParams : OSCGains { std::vector EndEffectorRotKp; std::vector EndEffectorRotKd; - MatrixXd W_end_effector; - MatrixXd K_p_end_effector; - MatrixXd K_d_end_effector; - MatrixXd W_mid_link; - MatrixXd K_p_mid_link; - MatrixXd K_d_mid_link; - MatrixXd W_end_effector_rot; - MatrixXd K_p_end_effector_rot; - MatrixXd K_d_end_effector_rot; +// Eigen::Vector3d neutral_position; + Eigen::MatrixXd W_end_effector; + Eigen::MatrixXd K_p_end_effector; + Eigen::MatrixXd K_d_end_effector; + Eigen::MatrixXd W_mid_link; + Eigen::MatrixXd K_p_mid_link; + Eigen::MatrixXd K_d_mid_link; + Eigen::MatrixXd W_end_effector_rot; + Eigen::MatrixXd K_p_end_effector_rot; + Eigen::MatrixXd K_d_end_effector_rot; template void Serialize(Archive* a) { @@ -48,6 +54,8 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(franka_model)); + a->Visit(DRAKE_NVP(end_effector_model)); + a->Visit(DRAKE_NVP(end_effector_name)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(track_end_effector_orientation)); a->Visit(DRAKE_NVP(EndEffectorW)); @@ -60,6 +68,11 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(EndEffectorRotKp)); a->Visit(DRAKE_NVP(EndEffectorRotKd)); + a->Visit(DRAKE_NVP(neutral_position)); + a->Visit(DRAKE_NVP(x_scale)); + a->Visit(DRAKE_NVP(y_scale)); + a->Visit(DRAKE_NVP(z_scale)); + W_end_effector = Eigen::Map< Eigen::Matrix>( this->EndEffectorW.data(), 3, 3); diff --git a/examples/franka/franka_osc_controller_params.yaml b/examples/franka/franka_osc_controller_params.yaml index a54142ea5f..8cfb22ddff 100644 --- a/examples/franka/franka_osc_controller_params.yaml +++ b/examples/franka/franka_osc_controller_params.yaml @@ -5,13 +5,20 @@ radio_channel: CASSIE_VIRTUAL_RADIO osc_debug_channel: OSC_DEBUG_FRANKA c3_channel: C3_TRAJECTORY_ACTOR -franka_model: examples/franka/urdf/franka.urdf +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate + +neutral_position: [0.55, 0, 0.4] +x_scale: 0.1 +y_scale: 0.1 +z_scale: 0.1 w_input: 0.00 w_input_reg: 0.0 w_accel: 0.00001 w_soft_constraint: 10000 -w_lambda: 0.1 +w_lambda: 0.0 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index a3e51b6c17..4c61954f51 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -15,9 +15,10 @@ actuator_delay: 0.000 visualize: true dt: 0.0005 -realtime_rate: 0.5 +realtime_rate: 0.1 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] -q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] +#q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] +q_init_plate: [1, 0, 0, 0, 0.68, 0.08, 1.250] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 1.1] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 3bf7a7329d..b672a635bd 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -54,29 +54,12 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( &EndEffectorTrajectoryGenerator::CalcTraj); } -PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateCircle( - const drake::systems::Context& context) const { - const auto robot_output = - this->template EvalVectorInput(context, state_port_); - const auto& radio_out = - this->EvalInputValue(context, radio_port_); - double t = robot_output->get_timestamp(); - double dt = 0.1; - double frequency = 0.5 * (1 + radio_out->channel[2]) * M_PI; - double radius = radio_out->channel[0] * 0.2; - int index = 1 - std::max(0.0, radio_out->channel[15]); - VectorXd y0 = VectorXd::Zero(3); - y0(1 - index) = 0.7; - y0(index) = radius * cos(frequency * t); - y0(2) = radius * sin(frequency * t) + 0.3; - VectorXd ydot0 = VectorXd::Zero(3); - ydot0(1 - index) = 0; - ydot0(index) = -radius * frequency * sin(frequency * t); - ydot0(2) = -radius * frequency * cos(frequency * t); - std::vector breaks = {t, t + dt}; - std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold( - breaks, samples); +void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( + const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale){ + neutral_pose_ = neutral_pose; + x_scale_ = x_scale; + y_scale_ = y_scale; + z_scale_ = z_scale; } PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( @@ -87,32 +70,11 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( this->EvalInputValue(context, radio_port_); double t = robot_output->get_timestamp(); double dt = 0.1; - VectorXd y0 = VectorXd::Zero(3); - y0(0) = 0.65 + radio_out->channel[0] * 0.2; - y0(0) = std::clamp(y0(0), 0.0, 0.75); - y0(1) = radio_out->channel[1] * 0.2; - y0(2) = 0.3 + radio_out->channel[2] * 0.2; - VectorXd ydot0 = VectorXd::Zero(3); - std::vector breaks = {t, t + dt}; - std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold( - breaks, samples); -} - -PiecewisePolynomial EndEffectorTrajectoryGenerator::GenerateLine( - const drake::systems::Context& context) const { - const auto robot_output = - this->template EvalVectorInput(context, state_port_); - double t = robot_output->get_timestamp(); - double dt = 0.1; - VectorXd y0 = VectorXd::Zero(3); - y0(0) = 0; - y0(1) = 0.8; - y0(2) = 0.2 * sin(M_PI * t) + 0.5; + VectorXd y0 = neutral_pose_; + y0(0) += radio_out->channel[0] * x_scale_; + y0(1) += radio_out->channel[1] * y_scale_; + y0(2) += radio_out->channel[2] * z_scale_; VectorXd ydot0 = VectorXd::Zero(3); - ydot0(0) = 0; - ydot0(1) = 0; - ydot0(2) = -0.2 * M_PI * cos(M_PI * t); std::vector breaks = {t, t + dt}; std::vector samples = {y0, y0 + dt * ydot0}; return drake::trajectories::PiecewisePolynomial::FirstOrderHold( diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index 8b41ae5d6a..ab896b8184 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -9,10 +9,12 @@ namespace dairlib { -class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem { +class EndEffectorTrajectoryGenerator + : public drake::systems::LeafSystem { public: - EndEffectorTrajectoryGenerator(const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context); + EndEffectorTrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context); const drake::systems::InputPort& get_input_port_state() const { return this->get_input_port(state_port_); @@ -24,6 +26,9 @@ class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem return this->get_input_port(radio_port_); } + void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, double x_scale, + double y_scale, double z_scale); + private: drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, @@ -46,6 +51,11 @@ class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; + Eigen::Vector3d neutral_pose_; + double x_scale_; + double y_scale_; + double z_scale_; + std::vector half_plane_bounds_; }; -} // namespace dairlib::examples::osc_run +} // namespace dairlib diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index be7badad74..1e74d93114 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -10,7 +10,7 @@ - + @@ -22,7 +22,7 @@ - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index ed4d620592..d89687a17c 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -157,7 +157,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -0.2, 0.2, 1); + c3_->AddLinearConstraint(A, -0.4, 0.4, 1); } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); return drake::systems::EventStatus::Succeeded(); From 957425671472a71438c503adda485b7109e22541 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 26 Oct 2023 16:59:54 -0400 Subject: [PATCH 481/758] moving tool attachment frame to yaml as well --- common/eigen_utils.cc | 15 ++++++++++----- common/eigen_utils.h | 2 ++ examples/franka/BUILD.bazel | 6 ++++-- examples/franka/franka_c3_controller.cc | 5 +++-- examples/franka/franka_c3_controller_params.h | 2 ++ examples/franka/franka_c3_controller_params.yaml | 2 ++ .../franka/franka_c3_options_translation.yaml | 2 +- examples/franka/franka_osc_controller.cc | 5 ++--- examples/franka/franka_osc_controller_params.h | 2 ++ examples/franka/franka_osc_controller_params.yaml | 2 ++ examples/franka/franka_sim.cc | 6 ++++-- examples/franka/franka_sim_params.h | 2 ++ examples/franka/franka_sim_params.yaml | 6 ++++-- examples/franka/franka_visualizer.cc | 4 ++-- 14 files changed, 42 insertions(+), 19 deletions(-) diff --git a/common/eigen_utils.cc b/common/eigen_utils.cc index fdaa6d9d1b..7689634857 100644 --- a/common/eigen_utils.cc +++ b/common/eigen_utils.cc @@ -1,17 +1,22 @@ #include "eigen_utils.h" -std::vector CopyVectorXdToStdVector( - const Eigen::VectorXd& eigen_vec) { +std::vector CopyVectorXdToStdVector(const Eigen::VectorXd& eigen_vec) { return std::vector(eigen_vec.data(), eigen_vec.data() + eigen_vec.size()); } -Eigen::VectorXd eigen_clamp( - const Eigen::VectorXd& value, const Eigen::VectorXd& lb, const Eigen::VectorXd& ub){ +Eigen::VectorXd StdVectorToVectorXd(std::vector std_vec) { + return Eigen::Map(std_vec.data(), + std_vec.size()); +} + +Eigen::VectorXd eigen_clamp(const Eigen::VectorXd& value, + const Eigen::VectorXd& lb, + const Eigen::VectorXd& ub) { DRAKE_DEMAND(value.size() == lb.size()); DRAKE_DEMAND(value.size() == ub.size()); Eigen::VectorXd clamped_value(value.size()); - for (int i = 0; i < value.size(); ++i){ + for (int i = 0; i < value.size(); ++i) { clamped_value[i] = std::clamp(value[i], lb[i], ub[i]); } return clamped_value; diff --git a/common/eigen_utils.h b/common/eigen_utils.h index 17d6cff4c0..e6e3fca3a1 100644 --- a/common/eigen_utils.h +++ b/common/eigen_utils.h @@ -8,6 +8,8 @@ /// from an Eigen::VectorXd. std::vector CopyVectorXdToStdVector(const Eigen::VectorXd& eigen_vec); +Eigen::VectorXd StdVectorToVectorXd(std::vector); + Eigen::VectorXd eigen_clamp(const Eigen::VectorXd& value, const Eigen::VectorXd& lb, const Eigen::VectorXd& ub); diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index a502aa5211..58277e6257 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -45,7 +45,7 @@ cc_binary( "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", - "//common:find_resource", + "//common", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", ], @@ -60,6 +60,7 @@ cc_binary( ], deps = [ ":franka_osc_controller_params", + "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", @@ -82,6 +83,7 @@ cc_binary( ], deps = [ ":franka_c3_controller_params", + "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", @@ -104,7 +106,7 @@ cc_binary( ], deps = [ ":franka_sim_params", - "//common:find_resource", + "//common", "//multibody:utils", "//multibody:visualization_utils", "//systems:robot_lcm_systems", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index cb045fce20..9990767e63 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -2,6 +2,7 @@ #include #include +#include "common/eigen_utils.h" #include "examples/franka/franka_c3_controller_params.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "examples/franka/systems/franka_kinematics.h" @@ -82,8 +83,8 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); - Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); - tool_attachment_frame(2) = 0.157; + Vector3d tool_attachment_frame = StdVectorToVectorXd(controller_params.tool_attachment_frame); + RigidTransform T_EE_W = RigidTransform( drake::math::RotationMatrix(), tool_attachment_frame); plant_franka.WeldFrames(plant_franka.GetFrameByName("panda_link7"), diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/franka_c3_controller_params.h index 654343f7a7..85768e87af 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/franka_c3_controller_params.h @@ -20,6 +20,7 @@ struct FrankaC3ControllerParams { std::string tray_model; bool include_end_effector_orientation; double target_frequency; + std::vector tool_attachment_frame; template void Serialize(Archive* a) { @@ -36,5 +37,6 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(tray_model)); a->Visit(DRAKE_NVP(include_end_effector_orientation)); a->Visit(DRAKE_NVP(target_frequency)); + a->Visit(DRAKE_NVP(tool_attachment_frame)); } }; \ No newline at end of file diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/franka_c3_controller_params.yaml index b2a6f423b5..2bc7289f59 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/franka_c3_controller_params.yaml @@ -9,6 +9,8 @@ radio_channel: CASSIE_VIRTUAL_RADIO franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate + +tool_attachment_frame: [0, 0, 0.15] #franka_model: examples/franka/urdf/franka_no_collision.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/franka_c3_options_translation.yaml index 3809fce387..c1d108d267 100644 --- a/examples/franka/franka_c3_options_translation.yaml +++ b/examples/franka/franka_c3_options_translation.yaml @@ -5,7 +5,7 @@ num_threads: 6 delta_option: 1 mu: 0.4 -mu_plate: 1 +mu_plate: 0.4 dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 38b6f055b4..bd609e6839 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -3,6 +3,7 @@ #include #include +#include "common/eigen_utils.h" #include "examples/franka/franka_osc_controller_params.h" #include "examples/franka/systems/end_effector_orientation.h" #include "examples/franka/systems/end_effector_trajectory.h" @@ -80,9 +81,7 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); - Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); - - tool_attachment_frame(2) = 0.157; + Vector3d tool_attachment_frame = StdVectorToVectorXd(controller_params.tool_attachment_frame); RigidTransform T_EE_W = RigidTransform( drake::math::RotationMatrix(), tool_attachment_frame); diff --git a/examples/franka/franka_osc_controller_params.h b/examples/franka/franka_osc_controller_params.h index b4efdff1c3..c5fc3af6d3 100644 --- a/examples/franka/franka_osc_controller_params.h +++ b/examples/franka/franka_osc_controller_params.h @@ -15,6 +15,7 @@ struct FrankaControllerParams : OSCGains { std::string end_effector_model; std::string end_effector_name; + std::vector tool_attachment_frame; double end_effector_acceleration; bool track_end_effector_orientation; @@ -68,6 +69,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(EndEffectorRotKp)); a->Visit(DRAKE_NVP(EndEffectorRotKd)); + a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(neutral_position)); a->Visit(DRAKE_NVP(x_scale)); a->Visit(DRAKE_NVP(y_scale)); diff --git a/examples/franka/franka_osc_controller_params.yaml b/examples/franka/franka_osc_controller_params.yaml index 8cfb22ddff..70f0442336 100644 --- a/examples/franka/franka_osc_controller_params.yaml +++ b/examples/franka/franka_osc_controller_params.yaml @@ -9,6 +9,8 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate +tool_attachment_frame: [0, 0, 0.15] + neutral_position: [0.55, 0, 0.4] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 54ea360bc0..499d25e7ab 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -12,6 +12,7 @@ #include #include "common/find_resource.h" +#include "common/eigen_utils.h" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "examples/franka/franka_sim_params.h" @@ -82,10 +83,11 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); Vector3d second_table_origin = Eigen::VectorXd::Zero(3); - Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); + Vector3d tool_attachment_frame = + StdVectorToVectorXd(sim_params.tool_attachment_frame); franka_origin(2) = 0.7645; second_table_origin(0) = 0.75; - tool_attachment_frame(2) = 0.157; + RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_X_W = RigidTransform( diff --git a/examples/franka/franka_sim_params.h b/examples/franka/franka_sim_params.h index 9475eba175..74595e375a 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/franka_sim_params.h @@ -28,6 +28,7 @@ struct FrankaSimParams { std::vector q_init_franka; std::vector q_init_plate; std::vector q_init_box; + std::vector tool_attachment_frame; template void Serialize(Archive* a) { @@ -53,6 +54,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); a->Visit(DRAKE_NVP(q_init_box)); + a->Visit(DRAKE_NVP(tool_attachment_frame)); } }; \ No newline at end of file diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/franka_sim_params.yaml index 4c61954f51..bc9861c421 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/franka_sim_params.yaml @@ -14,11 +14,13 @@ publish_efforts: true actuator_delay: 0.000 visualize: true +tool_attachment_frame: [0, 0, 0.15] + dt: 0.0005 -realtime_rate: 0.1 +realtime_rate: 0.5 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] -q_init_plate: [1, 0, 0, 0, 0.68, 0.08, 1.250] +q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 1.1] diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index a93b9713cc..cb9d6334ff 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -6,6 +6,7 @@ #include #include "common/find_resource.h" +#include "common/eigen_utils.h" #include "dairlib/lcmt_robot_output.hpp" #include "examples/franka/franka_sim_params.h" #include "multibody/com_pose_system.h" @@ -89,10 +90,9 @@ int do_main(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); Vector3d second_table_origin = Eigen::VectorXd::Zero(3); - Vector3d tool_attachment_frame = Eigen::VectorXd::Zero(3); + Vector3d tool_attachment_frame = StdVectorToVectorXd(sim_params.tool_attachment_frame); franka_origin(2) = 0.7645; second_table_origin(0) = 0.75; - tool_attachment_frame(2) = 0.157; RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_X_W = RigidTransform( From 4aa8471e83227f2d25c5a41a528d4df974111495 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 30 Oct 2023 14:51:11 -0400 Subject: [PATCH 482/758] adding ros lcm translators --- examples/franka/franka_ros_lcm_bridge.cc | 143 +++++++++ examples/franka/systems/BUILD.bazel | 14 + .../systems/franka_ros_lcm_conversions.cc | 303 ++++++++++++++++++ .../systems/franka_ros_lcm_conversions.h | 161 ++++++++++ lcmtypes/lcmt_estimated_object_state.lcm | 7 + lcmtypes/lcmt_franka_state.lcm | 55 ++++ lcmtypes/lcmt_object_state.lcm | 13 + systems/ros/franka_msgs/Errors.msg | 36 +++ systems/ros/franka_msgs/FrankaState.msg | 54 ++++ 9 files changed, 786 insertions(+) create mode 100644 examples/franka/franka_ros_lcm_bridge.cc create mode 100644 examples/franka/systems/franka_ros_lcm_conversions.cc create mode 100644 examples/franka/systems/franka_ros_lcm_conversions.h create mode 100644 lcmtypes/lcmt_estimated_object_state.lcm create mode 100644 lcmtypes/lcmt_franka_state.lcm create mode 100644 lcmtypes/lcmt_object_state.lcm create mode 100644 systems/ros/franka_msgs/Errors.msg create mode 100644 systems/ros/franka_msgs/FrankaState.msg diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc new file mode 100644 index 0000000000..8e6af42e06 --- /dev/null +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -0,0 +1,143 @@ +#define ROS + +#ifdef ROS + +#include +#include +#include +#include + +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include +#include "ros/ros.h" +#include "sensor_msgs/JointState.h" +#include "std_msgs/Float64MultiArray.h" + +#include "systems/ros/ros_subscriber_system.h" +#include "systems/ros/ros_publisher_system.h" +#include "systems/ros/c3_ros_conversions.h" +#include "systems/system_utils.h" + +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using dairlib::systems::RosSubscriberSystem; +using dairlib::systems::RosPublisherSystem; +using dairlib::systems::ROSToRobotOutputLCM; +using dairlib::systems::ROSToC3LCM; +using dairlib::systems::ROSToBallPositionLCM; + +// Shutdown ROS gracefully and then exit +void SigintHandler(int sig) { + ros::shutdown(); + exit(sig); +} + +DEFINE_string(joint_channel, "/c3/joint_states", + "Rostopic for receiving joint state info from Franka. " + "Use /c3/joint_states for actual experiments (1000hz channel), and " + "use /franka_state_controller/joint_states for debugging (100hz channel)." + "Note that the default rate of the franka_control_interface is 30hz, " + "but this rate has been overridden to be 100hz on the franka computer"); + +namespace dairlib { + +int DoMain(int argc, char* argv[]){ + gflags::ParseCommandLineFlags(&argc, &argv, true); + + ros::init(argc, argv, "run_c3_ros_to_lcm"); + ros::NodeHandle node_handle; + + drake::lcm::DrakeLcm drake_lcm; + DiagramBuilder builder; + + /* -------------------------------------------------------------------------------------------*/ + /// convert franka joint states to lcm + auto franka_subscriber = + builder.AddSystem(RosSubscriberSystem::Make( + FLAGS_joint_channel, &node_handle)); + auto to_robot_output = builder.AddSystem(ROSToRobotOutputLCM::Make(14, 13, 7)); + + // change this to output correctly (i.e. when ros subscriber gets new message) + auto robot_output_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "FRANKA_ROS_OUTPUT", &drake_lcm, + {drake::systems::TriggerType::kPeriodic}, 0.0005)); + /// connections + builder.Connect(franka_subscriber->get_output_port(), to_robot_output->get_input_port()); + builder.Connect(to_robot_output->get_output_port(), robot_output_pub->get_input_port()); + + /* -------------------------------------------------------------------------------------------*/ + /// convert ball position estimate to lcm + auto ball_subscriber = + builder.AddSystem(RosSubscriberSystem::Make( + "/c3/position_estimate", &node_handle)); + auto to_ball_position = builder.AddSystem(ROSToBallPositionLCM::Make()); + + // change this to output correctly (i.e. when ros subscriber gets new message) + auto ball_position_pub = builder.AddSystem( + LcmPublisherSystem::Make( + "VISION_OUTPUT", &drake_lcm, + {drake::systems::TriggerType::kPeriodic}, 0.005)); + /// connections + builder.Connect(ball_subscriber->get_output_port(), to_ball_position->get_input_port()); + builder.Connect(to_ball_position->get_output_port(), ball_position_pub->get_input_port()); + + /* -------------------------------------------------------------------------------------------*/ + /// convert individual camera measurements to lcm for logging + int num_cameras = 3; + std::vector*> + cam_subscribers(num_cameras, nullptr); + std::vector ros_lcm_converters(num_cameras, nullptr); + std::vector cam_publishers(num_cameras, nullptr); + + for (int i = 0; i < num_cameras; i++){ + // Add systems + std::string cam_id = std::to_string(i); + cam_subscribers[i] = + builder.AddSystem(RosSubscriberSystem::Make( + "/c3/cam" + cam_id, &node_handle)); + ros_lcm_converters[i] = + builder.AddSystem(ROSToBallPositionLCM::Make()); + cam_publishers[i] = + builder.AddSystem( + LcmPublisherSystem::Make( + "CAM" + cam_id + "_OUTPUT", &drake_lcm, + {drake::systems::TriggerType::kPeriodic}, 0.005)); + + // Connect systems + builder.Connect(cam_subscribers[i]->get_output_port(), + ros_lcm_converters[i]->get_input_port()); + builder.Connect(ros_lcm_converters[i]->get_output_port(), + cam_publishers[i]->get_input_port()); + } + + /* -------------------------------------------------------------------------------------------*/ + + auto sys = builder.Build(); + // DrawAndSaveDiagramGraph(*sys, "examples/franka_trajectory_following/diagram_run_c3_ros_to_lcm"); + + Simulator simulator(*sys); + simulator.Initialize(); + simulator.set_target_realtime_rate(1.0); + + // figure out what the arguments to this mean + ros::AsyncSpinner spinner(1); + spinner.start(); + signal(SIGINT, SigintHandler); + simulator.AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv);} + +#endif \ No newline at end of file diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 30a9d68c83..dc9209bc4b 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -50,6 +50,20 @@ cc_library( ], ) +cc_library( + name = "franka_ros_lcm_conversions", + srcs = ["franka_ros_lcm_conversions.cc"], + hdrs = ["franka_ros_lcm_conversions.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//common", + "@ros", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "franka_sim_controls", srcs = ["franka_sim_controls.cc"], diff --git a/examples/franka/systems/franka_ros_lcm_conversions.cc b/examples/franka/systems/franka_ros_lcm_conversions.cc new file mode 100644 index 0000000000..d7d7921828 --- /dev/null +++ b/examples/franka/systems/franka_ros_lcm_conversions.cc @@ -0,0 +1,303 @@ +#include "franka_ros_lcm_conversions.h" +//#include "franka_msgs/FrankaState.h" +#include +namespace dairlib { +namespace systems { + +using Eigen::VectorXd; + +// LcmToRosTimestampedVector implementation +LcmToRosTimestampedVector::LcmToRosTimestampedVector(int vector_size) + : vector_size_(vector_size) { + + this->DeclareVectorInputPort("u, t", + TimestampedVector(vector_size_)); + this->DeclareAbstractOutputPort("ROS Float64MultiArray", + &LcmToRosTimestampedVector::ConvertToROS); +}; + +void LcmToRosTimestampedVector::ConvertToROS(const drake::systems::Context& context, + std_msgs::Float64MultiArray* output) const { + + const TimestampedVector* input = + (TimestampedVector*)this->EvalVectorInput(context, 0); + + // note: this function currently appends the timestamp to the end of the output + output->data.clear(); + for (int i = 0; i < vector_size_; i++){ + if (std::isnan(input->GetAtIndex(i))){ + output->data.push_back(0); + } + else{ + output->data.push_back(input->GetAtIndex(i)); + } + } + output->data.push_back(input->get_timestamp()); +} + +/***************************************************************************************/ +// ROSToRobotOuput implementation + +RosToLcmRobotState::RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts) + : num_positions_(num_positions), num_velocities_(num_velocities), num_efforts_(num_efforts) { + + this->DeclareAbstractInputPort("Franka JointState topic", + drake::Value()); + this->DeclareAbstractOutputPort("lcmt_robot_output", + &RosToLcmRobotState::ConvertToLCM); +} + +void RosToLcmRobotState::ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const { + + const drake::AbstractValue* const input = this->EvalAbstractInput(context, 0); + DRAKE_ASSERT(input != nullptr); + const auto& msg = input->get_value(); + + output->num_positions = num_positions_; + output->num_velocities = num_velocities_; + output->num_efforts = num_efforts_; + output->position_names.resize(num_positions_); + output->velocity_names.resize(num_velocities_); + output->effort_names.resize(num_efforts_); + output->position_names = position_names_; + output->velocity_names = velocity_names_; + output->effort_names = effort_names_; + output->position.resize(num_positions_); + output->velocity.resize(num_velocities_); + output->effort.resize(num_efforts_); + + // yet to receive message from rostopic + if (msg.position.empty()){ + for (int i = 0; i < num_positions_; i++){ + output->position[i] = nan(""); + } + for (int i = 0; i < num_velocities_; i++){ + output->velocity[i] = nan(""); + } + for (int i = 0; i < num_efforts_; i++){ + output->effort[i] = nan(""); + } + for (int i = 0; i < 3; i++){ + output->imu_accel[i] = nan(""); + } + } + // input should be order as "positions, velocities, effort, timestamp" + else{ + for (int i = 0; i < num_franka_joints_; i++){ + output->position[i] = msg.position[i]; + } + // hard coded to add 7 zeros to the end of position + for (int i = num_franka_joints_; i < num_positions_; i++){ + output->position[i] = default_ball_position_[i-num_franka_joints_]; + } + + for (int i = 0; i < num_velocities_; i++){ + output->velocity[i] = msg.velocity[i]; + } + // hard coded to add 6 zeros to the end of velocity + for (int i = num_franka_joints_; i < num_velocities_; i++){ + output->velocity[i] = 0; + } + + for (int i = 0; i < num_efforts_; i++){ + output->effort[i] = msg.effort[i]; + } + for (int i = 0; i < 3; i++){ + output->imu_accel[i] = 0; + } + } + output->utime = context.get_time() * 1e6; +} + + +/***************************************************************************************/ +// RosToLcmFrankaState implementation + +RosToLcmFrankaState::RosToLcmFrankaState() { + + this->DeclareAbstractInputPort("ROS Float64MultiArray", + drake::Value()); + this->DeclareAbstractOutputPort("lcmt_franka_state", + &RosToLcmFrankaState::ConvertToLCM); +} + +void RosToLcmFrankaState::ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_franka_state* franka_state) const { + + const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); + const auto& msg = input->get_value(); + + if (msg.O_T_EE.empty()){ + franka_state->valid = false; + } + else{ + for (size_t i = 0; i < msg.O_T_EE.size(); i++){ + franka_state->O_T_EE[i] = msg.O_T_EE[i]; + } + for (size_t i = 0; i < msg.O_T_EE_d.size(); i++){ + franka_state->O_T_EE_d[i] = msg.O_T_EE_d[i]; + } + for (size_t i = 0; i < msg.F_T_EE.size(); i++){ + franka_state->F_T_EE[i] = msg.F_T_EE[i]; + } + for (size_t i = 0; i < msg.F_T_NE.size(); i++){ + franka_state->F_T_NE[i] = msg.F_T_NE[i]; + } + for (size_t i = 0; i < msg.NE_T_EE.size(); i++){ + franka_state->NE_T_EE[i] = msg.NE_T_EE[i]; + } + for (size_t i = 0; i < msg.EE_T_K.size(); i++){ + franka_state->EE_T_K[i] = msg.EE_T_K[i]; + } + franka_state->m_ee = msg.m_ee; + for (size_t i = 0; i < msg.I_ee.size(); i++){ + franka_state->I_ee[i] = msg.I_ee[i]; + } + for (size_t i = 0; i < msg.F_x_Cee.size(); i++){ + franka_state->F_x_Cee[i] = msg.F_x_Cee[i]; + } + franka_state->m_load = msg.m_load; + for (size_t i = 0; i < msg.I_load.size(); i++){ + franka_state->I_load[i] = msg.I_load[i]; + } + for (size_t i = 0; i < msg.F_x_Cload.size(); i++){ + franka_state->F_x_Cload[i] = msg.F_x_Cload[i]; + } + franka_state->m_total = msg.m_total; + for (size_t i = 0; i < msg.I_total.size(); i++){ + franka_state->I_total[i] = msg.I_total[i]; + } + for (size_t i = 0; i < msg.F_x_Ctotal.size(); i++){ + franka_state->F_x_Ctotal[i] = msg.F_x_Ctotal[i]; + } + for (size_t i = 0; i < msg.elbow.size(); i++){ + franka_state->elbow[i] = msg.elbow[i]; + } + for (size_t i = 0; i < msg.elbow_d.size(); i++){ + franka_state->elbow_d[i] = msg.elbow_d[i]; + } + for (size_t i = 0; i < msg.elbow_c.size(); i++){ + franka_state->elbow_c[i] = msg.elbow_c[i]; + } + for (size_t i = 0; i < msg.delbow_c.size(); i++){ + franka_state->delbow_c[i] = msg.delbow_c[i]; + } + for (size_t i = 0; i < msg.ddelbow_c.size(); i++){ + franka_state->ddelbow_c[i] = msg.ddelbow_c[i]; + } + for (size_t i = 0; i < msg.tau_J.size(); i++){ + franka_state->tau_J[i] = msg.tau_J[i]; + } + for (size_t i = 0; i < msg.tau_J_d.size(); i++){ + franka_state->tau_J_d[i] = msg.tau_J_d[i]; + } + for (size_t i = 0; i < msg.dtau_J.size(); i++){ + franka_state->dtau_J[i] = msg.dtau_J[i]; + } + for (size_t i = 0; i < msg.q.size(); i++){ + franka_state->q[i] = msg.q[i]; + } + for (size_t i = 0; i < msg.q_d.size(); i++){ + franka_state->q_d[i] = msg.q_d[i]; + } + for (size_t i = 0; i < msg.dq.size(); i++){ + franka_state->dq[i] = msg.dq[i]; + } + for (size_t i = 0; i < msg.dq_d.size(); i++){ + franka_state->dq_d[i] = msg.dq_d[i]; + } + for (size_t i = 0; i < msg.ddq_d.size(); i++){ + franka_state->ddq_d[i] = msg.ddq_d[i]; + } + for (size_t i = 0; i < msg.joint_contact.size(); i++){ + franka_state->joint_contact[i] = msg.joint_contact[i]; + } + for (size_t i = 0; i < msg.cartesian_contact.size(); i++){ + franka_state->cartesian_contact[i] = msg.cartesian_contact[i]; + } + for (size_t i = 0; i < msg.joint_collision.size(); i++){ + franka_state->joint_collision[i] = msg.joint_collision[i]; + } + for (size_t i = 0; i < msg.cartesian_collision.size(); i++){ + franka_state->cartesian_collision[i] = msg.cartesian_collision[i]; + } + for (size_t i = 0; i < msg.tau_ext_hat_filtered.size(); i++){ + franka_state->tau_ext_hat_filtered[i] = msg.tau_ext_hat_filtered[i]; + } + for (size_t i = 0; i < msg.O_F_ext_hat_K.size(); i++){ + franka_state->O_F_ext_hat_K[i] = msg.O_F_ext_hat_K[i]; + } + for (size_t i = 0; i < msg.K_F_ext_hat_K.size(); i++){ + franka_state->K_F_ext_hat_K[i] = msg.K_F_ext_hat_K[i]; + } + for (size_t i = 0; i < msg.O_dP_EE_d.size(); i++){ + franka_state->O_dP_EE_d[i] = msg.O_dP_EE_d[i]; + } + for (size_t i = 0; i < msg.O_T_EE_c.size(); i++){ + franka_state->O_T_EE_c[i] = msg.O_T_EE_c[i]; + } + for (size_t i = 0; i < msg.O_dP_EE_c.size(); i++){ + franka_state->O_dP_EE_c[i] = msg.O_dP_EE_c[i]; + } + for (size_t i = 0; i < msg.O_ddP_EE_c.size(); i++){ + franka_state->O_ddP_EE_c[i] = msg.O_ddP_EE_c[i]; + } + for (size_t i = 0; i < msg.theta.size(); i++){ + franka_state->theta[i] = msg.theta[i]; + } + for (size_t i = 0; i < msg.dtheta.size(); i++){ + franka_state->dtheta[i] = msg.dtheta[i]; + } + + std::stringstream ss_current_errors; + ss_current_errors << msg.current_errors; + franka_state->current_errors = ss_current_errors.str(); + + std::stringstream ss_last_motion_errors; + ss_last_motion_errors << msg.last_motion_errors; + franka_state->last_motion_errors = ss_last_motion_errors.str(); + + franka_state->control_command_success_rate = msg.control_command_success_rate; + franka_state->robot_mode = msg.robot_mode; + // time from franka robot + franka_state->franka_time = msg.time; + franka_state->valid = true; + } + // time for drake loop + franka_state->utime = context.get_time() * 1e6; +} + +/***************************************************************************************/ +// RosToLcmObjectState implementation + +RosToLcmObjectState::RosToLcmObjectState() { + + this->DeclareAbstractInputPort("ROS Float64MultiArray", + drake::Value()); + this->DeclareAbstractOutputPort("ball_position", + &RosToLcmObjectState::ConvertToLCM); + +} + +void RosToLcmObjectState::ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_object_state* object_state) const { + + const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); + const auto& msg = input->get_value(); + + if (msg.data.empty()){ + for (size_t i = 0; i < object_state->num_positions; i++){ + object_state->position[i] = nan(""); + } + } + else{ + for (size_t i = 0; i < object_state->num_positions; i++){ + object_state->position[i] = msg.data[i]; + } + } + object_state->utime = context.get_time() * 1e6; +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/systems/franka_ros_lcm_conversions.h b/examples/franka/systems/franka_ros_lcm_conversions.h new file mode 100644 index 0000000000..6dc31fbb00 --- /dev/null +++ b/examples/franka/systems/franka_ros_lcm_conversions.h @@ -0,0 +1,161 @@ +#pragma once + +#include +#include +#include + +#include "systems/framework/output_vector.h" +#include "systems/framework/timestamped_vector.h" + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" +#include "drake/systems/lcm/lcm_interface_system.h" + +#include "std_msgs/Float64MultiArray.h" +#include "sensor_msgs/JointState.h" +//#include "dairlib/lcmt_c3.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "dairlib/lcmt_franka_state.hpp" +#include "dairlib/lcmt_estimated_object_state.hpp" + +namespace dairlib { +namespace systems { + +class LcmToRosTimestampedVector : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make(int vector_size) { + return std::make_unique(vector_size); + } + + explicit LcmToRosTimestampedVector(int vector_size); + + private: + void ConvertToROS(const drake::systems::Context& context, + std_msgs::Float64MultiArray* output) const; + int vector_size_; +}; + +// NOTE: this class appends 7 zeros to the position and 6 zeros +// to the velocity fields. This was done since this class was hard +// coded for the C3 Franka experiments. +class RosToLcmRobotState : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make(int num_positions, int num_velocities, int num_efforts) { + return std::make_unique(num_positions, num_velocities, num_efforts); + } + + explicit RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts); + + private: + void ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const; + int num_positions_; + int num_velocities_; + int num_efforts_; + const int num_franka_joints_{7}; + + const std::vector default_ball_position_ {1, 0, 0, 0, 0.5, 0, 0.0315-0.0301}; + + const std::vector position_names_ { + "panda_joint1", + "panda_joint2", + "panda_joint3", + "panda_joint4", + "panda_joint5", + "panda_joint6", + "panda_joint7", + "base_qw", + "base_qx", + "base_qy", + "base_qz", + "base_x", + "base_y", + "base_z"}; + + const std::vector velocity_names_ { + "panda_joint1dot", + "panda_joint2dot", + "panda_joint3dot", + "panda_joint4dot", + "panda_joint5dot", + "panda_joint6dot", + "panda_joint7dot", + "base_wx", + "base_wy", + "base_wz", + "base_vx", + "base_vy", + "base_vz"}; + + const std::vector effort_names_ { + "panda_motor1", + "panda_motor2", + "panda_motor3", + "panda_motor4", + "panda_motor5", + "panda_motor6", + "panda_motor7",}; + +}; + +//class ROSToC3LCM : public drake::systems::LeafSystem { +// public: +// static std::unique_ptr Make(int num_positions, int num_velocities, +// int lambda_size, int misc_size) { +// +// return std::make_unique(num_positions, num_velocities, +// lambda_size, misc_size); +// } +// +// explicit ROSToC3LCM(int num_positions, int num_velocities, +// int lambda_size, int misc_size); +// +// private: +// void ConvertToLCM(const drake::systems::Context& context, +// dairlib::lcmt_c3* output) const; +// int num_positions_; +// int num_velocities_; +// int lambda_size_; +// int misc_size_; +// int data_size_; +//}; + +/// More specific translator from Franka state to LCM. Similar to lcmt_cassie_out.lcm +class RosToLcmFrankaState : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make() { + + return std::make_unique(); + } + + explicit RosToLcmFrankaState(); + + private: + void ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_franka_state* franka_state) const; +}; + +class RosToLcmObjectState : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make() { + + return std::make_unique(); + } + + explicit RosToLcmObjectState(); + + private: + void ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_object_state* franka_state) const; + + std::map enum_map_ = + {{-3.0, "Invalid"}, // invalid ball measurement obtained (i.e. incorrectly identified ball) + {-2.0, "Outlier"}, // outlier ball measurement obtained (i.e. too diff than other measurements) + {-1.0, "Ball not found"}, // no ball measurement obtained + { 0.0, "N/A"}, // See below + { 1.0, "Valid"}}; // valid ball measurement obtained + +}; + +} // namespace systems +} // namespace dairlib diff --git a/lcmtypes/lcmt_estimated_object_state.lcm b/lcmtypes/lcmt_estimated_object_state.lcm new file mode 100644 index 0000000000..3b7c26a90e --- /dev/null +++ b/lcmtypes/lcmt_estimated_object_state.lcm @@ -0,0 +1,7 @@ +package dairlib; + +struct lcmt_estimated_object_state +{ + lcmt_object_state object_state; + string measurement_status; +} diff --git a/lcmtypes/lcmt_franka_state.lcm b/lcmtypes/lcmt_franka_state.lcm new file mode 100644 index 0000000000..2ef1575979 --- /dev/null +++ b/lcmtypes/lcmt_franka_state.lcm @@ -0,0 +1,55 @@ +package dairlib; + +// mimics structure of FrankaState ROS message type +// https://frankaemika.github.io/libfranka/structfranka_1_1RobotState.html +struct lcmt_franka_state +{ + double O_T_EE[16]; + double O_T_EE_d[16]; + double F_T_EE[16]; + double F_T_NE[16]; + double NE_T_EE[16]; + double EE_T_K[16]; + double m_ee; + double I_ee[9]; + double F_x_Cee[3]; + double m_load; + double I_load[9]; + double F_x_Cload[3]; + double m_total; + double I_total[9]; + double F_x_Ctotal[3]; + double elbow[2]; + double elbow_d[2]; + double elbow_c[2]; + double delbow_c[2]; + double ddelbow_c[2]; + double tau_J[7]; + double tau_J_d[7]; + double dtau_J[7]; + double q[7]; + double q_d[7]; + double dq[7]; + double dq_d[7]; + double ddq_d[7]; + double joint_contact[7]; + double cartesian_contact[6]; + double joint_collision[7]; + double cartesian_collision[6]; + double tau_ext_hat_filtered[7]; + double O_F_ext_hat_K[6]; + double K_F_ext_hat_K[6]; + double O_dP_EE_d[16]; + double O_T_EE_c[16]; + double O_dP_EE_c[6]; + double O_ddP_EE_c[6]; + double theta[7]; + double dtheta[7]; + string current_errors; + string last_motion_errors; + double control_command_success_rate; + int16_t robot_mode; + double franka_time; + double utime; + boolean valid; +} \ No newline at end of file diff --git a/lcmtypes/lcmt_object_state.lcm b/lcmtypes/lcmt_object_state.lcm new file mode 100644 index 0000000000..55c7f739f6 --- /dev/null +++ b/lcmtypes/lcmt_object_state.lcm @@ -0,0 +1,13 @@ +package dairlib; + +struct lcmt_object_state +{ + int64_t utime; + string object_name; + + int32_t num_positions; + int32_t num_velocities; + + double position [num_positions]; + double velocity [num_velocities]; +} diff --git a/systems/ros/franka_msgs/Errors.msg b/systems/ros/franka_msgs/Errors.msg new file mode 100644 index 0000000000..a50780fb72 --- /dev/null +++ b/systems/ros/franka_msgs/Errors.msg @@ -0,0 +1,36 @@ +bool joint_position_limits_violation +bool cartesian_position_limits_violation +bool self_collision_avoidance_violation +bool joint_velocity_violation +bool cartesian_velocity_violation +bool force_control_safety_violation +bool joint_reflex +bool cartesian_reflex +bool max_goal_pose_deviation_violation +bool max_path_pose_deviation_violation +bool cartesian_velocity_profile_safety_violation +bool joint_position_motion_generator_start_pose_invalid +bool joint_motion_generator_position_limits_violation +bool joint_motion_generator_velocity_limits_violation +bool joint_motion_generator_velocity_discontinuity +bool joint_motion_generator_acceleration_discontinuity +bool cartesian_position_motion_generator_start_pose_invalid +bool cartesian_motion_generator_elbow_limit_violation +bool cartesian_motion_generator_velocity_limits_violation +bool cartesian_motion_generator_velocity_discontinuity +bool cartesian_motion_generator_acceleration_discontinuity +bool cartesian_motion_generator_elbow_sign_inconsistent +bool cartesian_motion_generator_start_elbow_invalid +bool cartesian_motion_generator_joint_position_limits_violation +bool cartesian_motion_generator_joint_velocity_limits_violation +bool cartesian_motion_generator_joint_velocity_discontinuity +bool cartesian_motion_generator_joint_acceleration_discontinuity +bool cartesian_position_motion_generator_invalid_frame +bool force_controller_desired_force_tolerance_violation +bool controller_torque_discontinuity +bool start_elbow_sign_inconsistent +bool communication_constraints_violation +bool power_limit_violation +bool joint_p2p_insufficient_torque_for_planning +bool tau_j_range_violation +bool instability_detected diff --git a/systems/ros/franka_msgs/FrankaState.msg b/systems/ros/franka_msgs/FrankaState.msg new file mode 100644 index 0000000000..37e6e23c6e --- /dev/null +++ b/systems/ros/franka_msgs/FrankaState.msg @@ -0,0 +1,54 @@ +std_msgs/Header header +float64[6] cartesian_collision +float64[6] cartesian_contact +float64[7] q +float64[7] q_d +float64[7] dq +float64[7] dq_d +float64[7] ddq_d +float64[7] theta +float64[7] dtheta +float64[7] tau_J +float64[7] dtau_J +float64[7] tau_J_d +float64[6] K_F_ext_hat_K +float64[2] elbow +float64[2] elbow_d +float64[2] elbow_c +float64[2] delbow_c +float64[2] ddelbow_c +float64[7] joint_collision +float64[7] joint_contact +float64[6] O_F_ext_hat_K +float64[6] O_dP_EE_d +float64[6] O_dP_EE_c +float64[6] O_ddP_EE_c +float64[7] tau_ext_hat_filtered +float64 m_ee +float64[3] F_x_Cee +float64[9] I_ee +float64 m_load +float64[3] F_x_Cload +float64[9] I_load +float64 m_total +float64[3] F_x_Ctotal +float64[9] I_total +float64[16] O_T_EE +float64[16] O_T_EE_d +float64[16] O_T_EE_c +float64[16] F_T_EE +float64[16] F_T_NE +float64[16] NE_T_EE +float64[16] EE_T_K +float64 time +float64 control_command_success_rate +uint8 ROBOT_MODE_OTHER=0 +uint8 ROBOT_MODE_IDLE=1 +uint8 ROBOT_MODE_MOVE=2 +uint8 ROBOT_MODE_GUIDING=3 +uint8 ROBOT_MODE_REFLEX=4 +uint8 ROBOT_MODE_USER_STOPPED=5 +uint8 ROBOT_MODE_AUTOMATIC_ERROR_RECOVERY=6 +uint8 robot_mode +franka_msgs/Errors current_errors +franka_msgs/Errors last_motion_errors From f3984ebfbae02e18b67db211a5882a6b8655ee85 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 30 Oct 2023 16:23:14 -0400 Subject: [PATCH 483/758] moving lcm channels to separate params file --- examples/franka/BUILD.bazel | 42 ++- examples/franka/franka_c3_controller.cc | 60 ++-- examples/franka/franka_osc_controller.cc | 24 +- examples/franka/franka_ros_lcm_bridge.cc | 26 +- examples/franka/franka_sim.cc | 34 +- examples/franka/franka_visualizer.cc | 26 +- .../franka_c3_controller_params.h | 10 +- .../franka_c3_controller_params.yaml | 7 +- .../franka_c3_options_floating.yaml | 0 .../franka_c3_options_translation.yaml | 0 .../franka/parameters/franka_lcm_channels.h | 27 ++ .../franka_osc_controller_params.h | 11 - .../franka_osc_controller_params.yaml | 5 - .../{ => parameters}/franka_qp_options.yaml | 0 .../{ => parameters}/franka_sim_params.h | 9 - .../{ => parameters}/franka_sim_params.yaml | 4 - .../parameters/lcm_channels_hardware.yaml | 11 + .../parameters/lcm_channels_simulation.yaml | 11 + examples/franka/systems/BUILD.bazel | 13 - .../systems/franka_ros_lcm_conversions.cc | 303 ------------------ .../systems/franka_ros_lcm_conversions.h | 161 ---------- 21 files changed, 187 insertions(+), 597 deletions(-) rename examples/franka/{ => parameters}/franka_c3_controller_params.h (76%) rename examples/franka/{ => parameters}/franka_c3_controller_params.yaml (76%) rename examples/franka/{ => parameters}/franka_c3_options_floating.yaml (100%) rename examples/franka/{ => parameters}/franka_c3_options_translation.yaml (100%) create mode 100644 examples/franka/parameters/franka_lcm_channels.h rename examples/franka/{ => parameters}/franka_osc_controller_params.h (90%) rename examples/franka/{ => parameters}/franka_osc_controller_params.yaml (89%) rename examples/franka/{ => parameters}/franka_qp_options.yaml (100%) rename examples/franka/{ => parameters}/franka_sim_params.h (80%) rename examples/franka/{ => parameters}/franka_sim_params.yaml (88%) create mode 100644 examples/franka/parameters/lcm_channels_hardware.yaml create mode 100644 examples/franka/parameters/lcm_channels_simulation.yaml delete mode 100644 examples/franka/systems/franka_ros_lcm_conversions.cc delete mode 100644 examples/franka/systems/franka_ros_lcm_conversions.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 58277e6257..cdb863efb1 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -42,12 +42,14 @@ cc_binary( ], deps = [ ":franka_sim_params", + ":franka_lcm_channels", "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", "//common", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", + "@gflags", ], ) @@ -60,6 +62,7 @@ cc_binary( ], deps = [ ":franka_osc_controller_params", + ":franka_lcm_channels", "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", @@ -83,6 +86,7 @@ cc_binary( ], deps = [ ":franka_c3_controller_params", + ":franka_lcm_channels", "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", @@ -106,6 +110,7 @@ cc_binary( ], deps = [ ":franka_sim_params", + ":franka_lcm_channels", "//common", "//multibody:utils", "//multibody:visualization_utils", @@ -118,9 +123,38 @@ cc_binary( ], ) +cc_binary( + name = "franka_ros_lcm_bridge", + srcs = ["franka_ros_lcm_bridge.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_sim_params", + ":franka_lcm_channels", + "//common", + "//systems:robot_lcm_systems", + "//systems/ros:franka_ros_lcm_conversions", + "//systems:system_utils", + "//systems/primitives", + "@drake//:drake_shared_library", + "@gflags", + ], + tags = ["ros"], +) + +cc_library( + name = "franka_lcm_channels", + hdrs = ["parameters/franka_lcm_channels.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) + cc_library( name = "franka_sim_params", - hdrs = ["franka_sim_params.h"], + hdrs = ["parameters/franka_sim_params.h"], deps = [ "@drake//:drake_shared_library", ], @@ -128,17 +162,15 @@ cc_library( cc_library( name = "franka_osc_controller_params", - hdrs = ["franka_osc_controller_params.h"], + hdrs = ["parameters/franka_osc_controller_params.h"], deps = [ "@drake//:drake_shared_library", ], ) - - cc_library( name = "franka_c3_controller_params", - hdrs = ["franka_c3_controller_params.h"], + hdrs = ["parameters/franka_c3_controller_params.h"], deps = [ "//solvers:c3", "@drake//:drake_shared_library", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 9990767e63..058d631193 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -3,7 +3,8 @@ #include #include "common/eigen_utils.h" -#include "examples/franka/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "examples/franka/systems/franka_kinematics.h" #include "lcm/lcm_trajectory.h" @@ -45,12 +46,13 @@ using Eigen::VectorXd; using multibody::MakeNameToPositionsMap; using multibody::MakeNameToVelocitiesMap; -DEFINE_string(controller_settings, "", +DEFINE_string(controller_settings, + "examples/franka/parameters/franka_c3_controller_params.yaml", "Controller settings such as channels. Attempting to minimize " "number of gflags"); -DEFINE_string(osqp_settings, - "examples/Cassie/osc_run/osc_running_qp_settings.yaml", - "Filepath containing qp settings"); +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -61,12 +63,14 @@ int DoMain(int argc, char* argv[]) { yaml_options.allow_yaml_with_no_cpp = true; FrankaC3ControllerParams controller_params = drake::yaml::LoadYamlFile( - "examples/franka/franka_c3_controller_params.yaml"); + FLAGS_controller_settings); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); C3Options c3_options = drake::yaml::LoadYamlFile(controller_params.c3_options_file); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osqp_settings)) + FindResourceOrThrow(controller_params.osqp_settings_file)) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); DiagramBuilder plant_builder; @@ -76,19 +80,23 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.package_map().Add("franka_urdfs", "examples/franka/urdf"); - parser_franka.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); - drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; + parser_franka.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = + parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); - Vector3d tool_attachment_frame = StdVectorToVectorXd(controller_params.tool_attachment_frame); + Vector3d tool_attachment_frame = + StdVectorToVectorXd(controller_params.tool_attachment_frame); RigidTransform T_EE_W = RigidTransform( drake::math::RotationMatrix(), tool_attachment_frame); - plant_franka.WeldFrames(plant_franka.GetFrameByName("panda_link7"), - plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); + plant_franka.WeldFrames( + plant_franka.GetFrameByName("panda_link7"), + plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); plant_franka.Finalize(); auto franka_context = plant_franka.CreateDefaultContext(); @@ -137,23 +145,15 @@ int DoMain(int argc, char* argv[]) { contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); } - /// - VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + plant_plate.num_velocities()); x_des << c3_options.q_des, c3_options.v_des; - // x_des - /// default position - // x_des[2] = 0.45 - 0.02 + radio_out->channel[2] * 0.2; - // x_des(10) += radio_out->channel[0] * 0.2; - // x_des(11) += radio_out->channel[1] * 0.2; - // x_des(12) += radio_out->channel[2] * 0.2; DiagramBuilder builder; auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( - "TRAY_OUTPUT", &lcm)); + lcm_channel_params.tray_state_channel, &lcm)); auto franka_state_receiver = builder.AddSystem(plant_franka); auto tray_state_receiver = @@ -161,21 +161,22 @@ int DoMain(int argc, char* argv[]) { auto reduced_order_model_receiver = builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), - controller_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); + controller_params.end_effector_name, "tray", + controller_params.include_end_effector_orientation); auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( - controller_params.c3_channel_actor, &lcm, + lcm_channel_params.c3_actor_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( - controller_params.c3_channel_object, &lcm, + lcm_channel_params.c3_object_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( - controller_params.radio_channel, &lcm)); + lcm_channel_params.radio_channel, &lcm)); auto controller = builder.AddSystem( plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), @@ -207,14 +208,13 @@ int DoMain(int argc, char* argv[]) { // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), franka_state_receiver, - controller_params.state_channel, true); + lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( *controller, &loop.get_diagram_mutable_context()); - // loop.get_diagram_mutable_context() controller->get_input_port_target().FixValue(&controller_context, x_des); - LcmHandleSubscriptionsUntil(&lcm, [&]() { - return tray_state_sub->GetInternalMessageCount() > 1; }); + LcmHandleSubscriptionsUntil( + &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); loop.Simulate(); return 0; } diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index bd609e6839..b788c8bed7 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -4,7 +4,8 @@ #include #include "common/eigen_utils.h" -#include "examples/franka/franka_osc_controller_params.h" +#include "examples/franka/parameters/franka_osc_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/end_effector_orientation.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" @@ -51,9 +52,12 @@ using systems::controllers::TransTaskSpaceTrackingData; DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", "Filepath containing qp settings"); -DEFINE_string(controller_settings, "", +DEFINE_string(controller_parameters, "examples/franka/parameters/franka_osc_controller_params.yaml", "Controller settings such as channels. Attempting to minimize " "number of gflags"); +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); @@ -63,9 +67,11 @@ int DoMain(int argc, char* argv[]) { yaml_options.allow_yaml_with_no_cpp = true; FrankaControllerParams controller_params = drake::yaml::LoadYamlFile( - "examples/franka/franka_osc_controller_params.yaml"); + FLAGS_controller_parameters); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow("examples/franka/franka_osc_controller_params.yaml"), + FindResourceOrThrow(FLAGS_controller_parameters), {}, {}, yaml_options); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( @@ -106,7 +112,7 @@ int DoMain(int argc, char* argv[]) { auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( LcmSubscriberSystem::Make( - controller_params.c3_channel, &lcm)); + lcm_channel_params.c3_actor_channel, &lcm)); auto end_effector_receiver = builder.AddSystem("end_effector_traj"); auto end_effector_orientation_receiver = @@ -114,7 +120,7 @@ int DoMain(int argc, char* argv[]) { "end_effector_orientation_target"); auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( - controller_params.controller_channel, &lcm, + lcm_channel_params.osc_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto end_effector_trajectory = @@ -133,12 +139,12 @@ int DoMain(int argc, char* argv[]) { controller_params.track_end_effector_orientation); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( - controller_params.radio_channel, &lcm)); + lcm_channel_params.radio_channel, &lcm)); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), false); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( - controller_params.osc_debug_channel, &lcm, + lcm_channel_params.osc_debug_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); osc->SetAccelerationCostWeights(gains.W_acceleration); @@ -236,7 +242,7 @@ int DoMain(int argc, char* argv[]) { // Run lcm-driven simulation systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), state_receiver, - controller_params.state_channel, true); + lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); return 0; diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index 8e6af42e06..8bab1af49f 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -57,28 +57,34 @@ int DoMain(int argc, char* argv[]){ drake::lcm::DrakeLcm drake_lcm; DiagramBuilder builder; + MultibodyPlant plant(0.0); + + Parser parser(&plant, &scene_graph); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + /* -------------------------------------------------------------------------------------------*/ /// convert franka joint states to lcm - auto franka_subscriber = + auto franka_joint_state_ros_subscriber = builder.AddSystem(RosSubscriberSystem::Make( FLAGS_joint_channel, &node_handle)); - auto to_robot_output = builder.AddSystem(ROSToRobotOutputLCM::Make(14, 13, 7)); + auto ros_to_lcm_robot_state = builder.AddSystem(RosToLcmRobotState::Make(7, 7, 7)); // change this to output correctly (i.e. when ros subscriber gets new message) auto robot_output_pub = builder.AddSystem( LcmPublisherSystem::Make( - "FRANKA_ROS_OUTPUT", &drake_lcm, - {drake::systems::TriggerType::kPeriodic}, 0.0005)); + "FRANKA_STATE", &drake_lcm, + {drake::systems::TriggerType::kForced})); /// connections - builder.Connect(franka_subscriber->get_output_port(), to_robot_output->get_input_port()); - builder.Connect(to_robot_output->get_output_port(), robot_output_pub->get_input_port()); + builder.Connect(franka_joint_state_ros_subscriber->get_output_port(), ros_to_lcm_robot_state->get_input_port()); + builder.Connect(ros_to_lcm_robot_state->get_output_port(), robot_output_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ /// convert ball position estimate to lcm - auto ball_subscriber = + auto tray_object_state_ros_subscriber = builder.AddSystem(RosSubscriberSystem::Make( "/c3/position_estimate", &node_handle)); - auto to_ball_position = builder.AddSystem(ROSToBallPositionLCM::Make()); + auto ros_to_lcm_object_state = builder.AddSystem(RosToLcmObjectState::Make()); // change this to output correctly (i.e. when ros subscriber gets new message) auto ball_position_pub = builder.AddSystem( @@ -86,8 +92,8 @@ int DoMain(int argc, char* argv[]){ "VISION_OUTPUT", &drake_lcm, {drake::systems::TriggerType::kPeriodic}, 0.005)); /// connections - builder.Connect(ball_subscriber->get_output_port(), to_ball_position->get_input_port()); - builder.Connect(to_ball_position->get_output_port(), ball_position_pub->get_input_port()); + builder.Connect(tray_object_state_ros_subscriber->get_output_port(), ros_to_lcm_object_state->get_input_port()); + builder.Connect(ros_to_lcm_object_state->get_output_port(), ball_position_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ /// convert individual camera measurements to lcm for logging diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 499d25e7ab..60692ca675 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -1,6 +1,7 @@ #include #include +#include #include #include @@ -11,11 +12,12 @@ #include #include -#include "common/find_resource.h" #include "common/eigen_utils.h" +#include "common/find_resource.h" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" -#include "examples/franka/franka_sim_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" #include "multibody/multibody_utils.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" @@ -52,10 +54,16 @@ using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + int DoMain(int argc, char* argv[]) { // load parameters FrankaSimParams sim_params = drake::yaml::LoadYamlFile( - "examples/franka/franka_sim_params.yaml"); + "examples/franka/parameters/franka_sim_params.yaml"); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); // load urdf and sphere DiagramBuilder builder; @@ -68,8 +76,8 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; drake::multibody::ModelInstanceIndex table_index = parser.AddModels(drake::FindResourceOrThrow(sim_params.table_model))[0]; - drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( - FindResourceOrThrow(sim_params.end_effector_model))[0]; + drake::multibody::ModelInstanceIndex end_effector_index = + parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; plant.RenameModelInstance(table_index, "table0"); drake::multibody::ModelInstanceIndex second_table_index = parser.AddModels( drake::FindResourceOrThrow(sim_params.table_w_supports_model))[0]; @@ -100,8 +108,8 @@ int DoMain(int argc, char* argv[]) { plant.GetFrameByName("link", second_table_index), T_X_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); - plant.WeldFrames( plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), - T_EE_W); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName("plate", end_effector_index), T_EE_W); // const drake::geometry::GeometrySet& paddle_geom_set = // plant.CollectRegisteredGeometries({ @@ -140,19 +148,21 @@ int DoMain(int argc, char* argv[]) { auto lcm = builder.AddSystem(&drake_lcm); auto passthrough = AddActuationRecieverAndStateSenderLcm( - &builder, plant, lcm, sim_params.controller_channel, - sim_params.state_channel, sim_params.publish_rate, franka_index, - sim_params.publish_efforts, sim_params.actuator_delay); + &builder, plant, lcm, lcm_channel_params.osc_channel, + lcm_channel_params.franka_state_channel, sim_params.publish_rate, + franka_index, sim_params.publish_efforts, sim_params.actuator_delay); auto tray_state_sender = builder.AddSystem(plant, tray_index); auto tray_state_pub = builder.AddSystem(LcmPublisherSystem::Make( - sim_params.tray_state_channel, lcm, 1.0 / sim_params.publish_rate)); + lcm_channel_params.tray_state_channel, lcm, + 1.0 / sim_params.publish_rate)); auto box_state_sender = builder.AddSystem(plant, box_index); auto box_state_pub = builder.AddSystem(LcmPublisherSystem::Make( - sim_params.box_state_channel, lcm, 1.0 / sim_params.publish_rate)); + lcm_channel_params.box_state_channel, lcm, + 1.0 / sim_params.publish_rate)); builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index cb9d6334ff..62bc32205f 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -8,7 +8,8 @@ #include "common/find_resource.h" #include "common/eigen_utils.h" #include "dairlib/lcmt_robot_output.hpp" -#include "examples/franka/franka_sim_params.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" #include "multibody/com_pose_system.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" @@ -28,11 +29,6 @@ #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/rendering/multibody_position_to_geometry_pose.h" -DEFINE_string(channel, "FRANKA_OUTPUT", - "LCM channel for receiving state. " - "Use FRANKA_OUTPUT to get state from simulator, and " - "use FRANKA_ROS_OUTPUT to get state from state estimator"); - namespace dairlib { using Eigen::MatrixXd; @@ -58,10 +54,16 @@ using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::Parser; using drake::systems::DiagramBuilder; +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + int do_main(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); FrankaSimParams sim_params = drake::yaml::LoadYamlFile( - "examples/franka/franka_sim_params.yaml"); + "examples/franka/parameters/franka_sim_params.yaml"); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); drake::systems::DiagramBuilder builder; @@ -115,12 +117,12 @@ int do_main(int argc, char* argv[]) { // Create state receiver. auto franka_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( - FLAGS_channel, lcm)); + lcm_channel_params.franka_state_channel, lcm)); auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( - "TRAY_OUTPUT", lcm)); + lcm_channel_params.tray_state_channel, lcm)); auto box_state_sub = builder.AddSystem( - LcmSubscriberSystem::Make("BOX_OUTPUT", lcm)); + LcmSubscriberSystem::Make(lcm_channel_params.box_state_channel, lcm)); auto franka_state_receiver = builder.AddSystem(plant, franka_index); auto tray_state_receiver = @@ -146,10 +148,10 @@ int do_main(int argc, char* argv[]) { auto trajectory_sub_actor = builder.AddSystem( LcmSubscriberSystem::Make( - "C3_TRAJECTORY_ACTOR", lcm)); + lcm_channel_params.c3_actor_channel, lcm)); auto trajectory_sub_object = builder.AddSystem( LcmSubscriberSystem::Make( - "C3_TRAJECTORY_TRAY", lcm)); + lcm_channel_params.c3_object_channel, lcm)); auto to_pose = builder.AddSystem>(plant); diff --git a/examples/franka/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h similarity index 76% rename from examples/franka/franka_c3_controller_params.h rename to examples/franka/parameters/franka_c3_controller_params.h index 85768e87af..02c3279583 100644 --- a/examples/franka/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -9,10 +9,7 @@ using Eigen::VectorXd; struct FrankaC3ControllerParams { std::string c3_options_file; - std::string c3_channel_actor; - std::string c3_channel_object; - std::string state_channel; - std::string radio_channel; + std::string osqp_settings_file; std::string franka_model; std::string end_effector_model; std::string end_effector_name; @@ -26,10 +23,7 @@ struct FrankaC3ControllerParams { void Serialize(Archive* a) { a->Visit(DRAKE_NVP(c3_options_file)); - a->Visit(DRAKE_NVP(c3_channel_actor)); - a->Visit(DRAKE_NVP(c3_channel_object)); - a->Visit(DRAKE_NVP(state_channel)); - a->Visit(DRAKE_NVP(radio_channel)); + a->Visit(DRAKE_NVP(osqp_settings_file)); a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_model)); a->Visit(DRAKE_NVP(end_effector_name)); diff --git a/examples/franka/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml similarity index 76% rename from examples/franka/franka_c3_controller_params.yaml rename to examples/franka/parameters/franka_c3_controller_params.yaml index 2bc7289f59..047e445373 100644 --- a/examples/franka/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,10 +1,7 @@ -c3_options_file: examples/franka/franka_c3_options_translation.yaml +c3_options_file: examples/franka/parameters/franka_c3_options_translation.yaml #c3_options_file: examples/franka/franka_c3_options_floating.yaml -c3_channel_actor: C3_TRAJECTORY_ACTOR -c3_channel_object: C3_TRAJECTORY_TRAY -state_channel: FRANKA_OUTPUT -radio_channel: CASSIE_VIRTUAL_RADIO +osqp_settings_file: examples/Cassie/osc_run/osc_running_qp_settings.yaml franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf diff --git a/examples/franka/franka_c3_options_floating.yaml b/examples/franka/parameters/franka_c3_options_floating.yaml similarity index 100% rename from examples/franka/franka_c3_options_floating.yaml rename to examples/franka/parameters/franka_c3_options_floating.yaml diff --git a/examples/franka/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml similarity index 100% rename from examples/franka/franka_c3_options_translation.yaml rename to examples/franka/parameters/franka_c3_options_translation.yaml diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h new file mode 100644 index 0000000000..aaf9aee651 --- /dev/null +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -0,0 +1,27 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + + +struct FrankaLcmChannels { + std::string franka_state_channel; + std::string tray_state_channel; + std::string box_state_channel; + std::string osc_channel; + std::string osc_debug_channel; + std::string c3_actor_channel; + std::string c3_object_channel; + std::string radio_channel; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(franka_state_channel)); + a->Visit(DRAKE_NVP(tray_state_channel)); + a->Visit(DRAKE_NVP(box_state_channel)); + a->Visit(DRAKE_NVP(osc_channel)); + a->Visit(DRAKE_NVP(osc_debug_channel)); + a->Visit(DRAKE_NVP(c3_actor_channel)); + a->Visit(DRAKE_NVP(c3_object_channel)); + a->Visit(DRAKE_NVP(radio_channel)); + } +}; \ No newline at end of file diff --git a/examples/franka/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h similarity index 90% rename from examples/franka/franka_osc_controller_params.h rename to examples/franka/parameters/franka_osc_controller_params.h index c5fc3af6d3..61244da167 100644 --- a/examples/franka/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -5,12 +5,6 @@ #include "drake/common/yaml/yaml_read_archive.h" struct FrankaControllerParams : OSCGains { - std::string state_channel; - std::string controller_channel; - std::string radio_channel; - std::string osc_debug_channel; - std::string c3_channel; - std::string franka_model; std::string end_effector_model; std::string end_effector_name; @@ -49,11 +43,6 @@ struct FrankaControllerParams : OSCGains { void Serialize(Archive* a) { OSCGains::Serialize(a); - a->Visit(DRAKE_NVP(state_channel)); - a->Visit(DRAKE_NVP(controller_channel)); - a->Visit(DRAKE_NVP(radio_channel)); - a->Visit(DRAKE_NVP(osc_debug_channel)); - a->Visit(DRAKE_NVP(c3_channel)); a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_model)); a->Visit(DRAKE_NVP(end_effector_name)); diff --git a/examples/franka/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml similarity index 89% rename from examples/franka/franka_osc_controller_params.yaml rename to examples/franka/parameters/franka_osc_controller_params.yaml index 70f0442336..8c6dee9f55 100644 --- a/examples/franka/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -1,9 +1,4 @@ controller_frequency: 1000 -state_channel: FRANKA_OUTPUT -controller_channel: FRANKA_INPUT -radio_channel: CASSIE_VIRTUAL_RADIO -osc_debug_channel: OSC_DEBUG_FRANKA -c3_channel: C3_TRAJECTORY_ACTOR franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf diff --git a/examples/franka/franka_qp_options.yaml b/examples/franka/parameters/franka_qp_options.yaml similarity index 100% rename from examples/franka/franka_qp_options.yaml rename to examples/franka/parameters/franka_qp_options.yaml diff --git a/examples/franka/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h similarity index 80% rename from examples/franka/franka_sim_params.h rename to examples/franka/parameters/franka_sim_params.h index 74595e375a..e58c79321f 100644 --- a/examples/franka/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -5,11 +5,6 @@ using Eigen::MatrixXd; struct FrankaSimParams { - - std::string state_channel; - std::string controller_channel; - std::string tray_state_channel; - std::string box_state_channel; std::string franka_model; std::string end_effector_model; std::string table_model; @@ -32,10 +27,6 @@ struct FrankaSimParams { template void Serialize(Archive* a) { - a->Visit(DRAKE_NVP(state_channel)); - a->Visit(DRAKE_NVP(controller_channel)); - a->Visit(DRAKE_NVP(tray_state_channel)); - a->Visit(DRAKE_NVP(box_state_channel)); a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_model)); a->Visit(DRAKE_NVP(table_model)); diff --git a/examples/franka/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml similarity index 88% rename from examples/franka/franka_sim_params.yaml rename to examples/franka/parameters/franka_sim_params.yaml index bc9861c421..31a7558369 100644 --- a/examples/franka/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,7 +1,3 @@ -state_channel: FRANKA_OUTPUT -controller_channel: FRANKA_INPUT -tray_state_channel: TRAY_OUTPUT -box_state_channel: BOX_OUTPUT #franka_model: examples/franka/urdf/franka_no_collision.urdf franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml new file mode 100644 index 0000000000..302b4f0c7d --- /dev/null +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -0,0 +1,11 @@ +franka_state_channel: FRANKA_STATE +tray_state_channel: TRAY_STATE +box_state_channel: BOX_STATE + +osc_channel: FRANKA_INPUT +osc_debug_channel: OSC_DEBUG_FRANKA + +c3_actor_channel: C3_TRAJECTORY_ACTOR +c3_object_channel: C3_TRAJECTORY_TRAY + +radio_channel: RADIO diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml new file mode 100644 index 0000000000..e7257b3576 --- /dev/null +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -0,0 +1,11 @@ +franka_state_channel: FRANKA_STATE_SIMULATION +tray_state_channel: TRAY_STATE_SIMULATION +box_state_channel: BOX_STATE_SIMULATION + +osc_channel: FRANKA_INPUT +osc_debug_channel: OSC_DEBUG_FRANKA + +c3_actor_channel: C3_TRAJECTORY_ACTOR +c3_object_channel: C3_TRAJECTORY_TRAY + +radio_channel: RADIO diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index dc9209bc4b..94c889314c 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -50,19 +50,6 @@ cc_library( ], ) -cc_library( - name = "franka_ros_lcm_conversions", - srcs = ["franka_ros_lcm_conversions.cc"], - hdrs = ["franka_ros_lcm_conversions.h"], - deps = [ - "//lcmtypes:lcmt_robot", - "//common", - "@ros", - "//multibody:utils", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) cc_library( name = "franka_sim_controls", diff --git a/examples/franka/systems/franka_ros_lcm_conversions.cc b/examples/franka/systems/franka_ros_lcm_conversions.cc deleted file mode 100644 index d7d7921828..0000000000 --- a/examples/franka/systems/franka_ros_lcm_conversions.cc +++ /dev/null @@ -1,303 +0,0 @@ -#include "franka_ros_lcm_conversions.h" -//#include "franka_msgs/FrankaState.h" -#include -namespace dairlib { -namespace systems { - -using Eigen::VectorXd; - -// LcmToRosTimestampedVector implementation -LcmToRosTimestampedVector::LcmToRosTimestampedVector(int vector_size) - : vector_size_(vector_size) { - - this->DeclareVectorInputPort("u, t", - TimestampedVector(vector_size_)); - this->DeclareAbstractOutputPort("ROS Float64MultiArray", - &LcmToRosTimestampedVector::ConvertToROS); -}; - -void LcmToRosTimestampedVector::ConvertToROS(const drake::systems::Context& context, - std_msgs::Float64MultiArray* output) const { - - const TimestampedVector* input = - (TimestampedVector*)this->EvalVectorInput(context, 0); - - // note: this function currently appends the timestamp to the end of the output - output->data.clear(); - for (int i = 0; i < vector_size_; i++){ - if (std::isnan(input->GetAtIndex(i))){ - output->data.push_back(0); - } - else{ - output->data.push_back(input->GetAtIndex(i)); - } - } - output->data.push_back(input->get_timestamp()); -} - -/***************************************************************************************/ -// ROSToRobotOuput implementation - -RosToLcmRobotState::RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts) - : num_positions_(num_positions), num_velocities_(num_velocities), num_efforts_(num_efforts) { - - this->DeclareAbstractInputPort("Franka JointState topic", - drake::Value()); - this->DeclareAbstractOutputPort("lcmt_robot_output", - &RosToLcmRobotState::ConvertToLCM); -} - -void RosToLcmRobotState::ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_robot_output* output) const { - - const drake::AbstractValue* const input = this->EvalAbstractInput(context, 0); - DRAKE_ASSERT(input != nullptr); - const auto& msg = input->get_value(); - - output->num_positions = num_positions_; - output->num_velocities = num_velocities_; - output->num_efforts = num_efforts_; - output->position_names.resize(num_positions_); - output->velocity_names.resize(num_velocities_); - output->effort_names.resize(num_efforts_); - output->position_names = position_names_; - output->velocity_names = velocity_names_; - output->effort_names = effort_names_; - output->position.resize(num_positions_); - output->velocity.resize(num_velocities_); - output->effort.resize(num_efforts_); - - // yet to receive message from rostopic - if (msg.position.empty()){ - for (int i = 0; i < num_positions_; i++){ - output->position[i] = nan(""); - } - for (int i = 0; i < num_velocities_; i++){ - output->velocity[i] = nan(""); - } - for (int i = 0; i < num_efforts_; i++){ - output->effort[i] = nan(""); - } - for (int i = 0; i < 3; i++){ - output->imu_accel[i] = nan(""); - } - } - // input should be order as "positions, velocities, effort, timestamp" - else{ - for (int i = 0; i < num_franka_joints_; i++){ - output->position[i] = msg.position[i]; - } - // hard coded to add 7 zeros to the end of position - for (int i = num_franka_joints_; i < num_positions_; i++){ - output->position[i] = default_ball_position_[i-num_franka_joints_]; - } - - for (int i = 0; i < num_velocities_; i++){ - output->velocity[i] = msg.velocity[i]; - } - // hard coded to add 6 zeros to the end of velocity - for (int i = num_franka_joints_; i < num_velocities_; i++){ - output->velocity[i] = 0; - } - - for (int i = 0; i < num_efforts_; i++){ - output->effort[i] = msg.effort[i]; - } - for (int i = 0; i < 3; i++){ - output->imu_accel[i] = 0; - } - } - output->utime = context.get_time() * 1e6; -} - - -/***************************************************************************************/ -// RosToLcmFrankaState implementation - -RosToLcmFrankaState::RosToLcmFrankaState() { - - this->DeclareAbstractInputPort("ROS Float64MultiArray", - drake::Value()); - this->DeclareAbstractOutputPort("lcmt_franka_state", - &RosToLcmFrankaState::ConvertToLCM); -} - -void RosToLcmFrankaState::ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_franka_state* franka_state) const { - - const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); - const auto& msg = input->get_value(); - - if (msg.O_T_EE.empty()){ - franka_state->valid = false; - } - else{ - for (size_t i = 0; i < msg.O_T_EE.size(); i++){ - franka_state->O_T_EE[i] = msg.O_T_EE[i]; - } - for (size_t i = 0; i < msg.O_T_EE_d.size(); i++){ - franka_state->O_T_EE_d[i] = msg.O_T_EE_d[i]; - } - for (size_t i = 0; i < msg.F_T_EE.size(); i++){ - franka_state->F_T_EE[i] = msg.F_T_EE[i]; - } - for (size_t i = 0; i < msg.F_T_NE.size(); i++){ - franka_state->F_T_NE[i] = msg.F_T_NE[i]; - } - for (size_t i = 0; i < msg.NE_T_EE.size(); i++){ - franka_state->NE_T_EE[i] = msg.NE_T_EE[i]; - } - for (size_t i = 0; i < msg.EE_T_K.size(); i++){ - franka_state->EE_T_K[i] = msg.EE_T_K[i]; - } - franka_state->m_ee = msg.m_ee; - for (size_t i = 0; i < msg.I_ee.size(); i++){ - franka_state->I_ee[i] = msg.I_ee[i]; - } - for (size_t i = 0; i < msg.F_x_Cee.size(); i++){ - franka_state->F_x_Cee[i] = msg.F_x_Cee[i]; - } - franka_state->m_load = msg.m_load; - for (size_t i = 0; i < msg.I_load.size(); i++){ - franka_state->I_load[i] = msg.I_load[i]; - } - for (size_t i = 0; i < msg.F_x_Cload.size(); i++){ - franka_state->F_x_Cload[i] = msg.F_x_Cload[i]; - } - franka_state->m_total = msg.m_total; - for (size_t i = 0; i < msg.I_total.size(); i++){ - franka_state->I_total[i] = msg.I_total[i]; - } - for (size_t i = 0; i < msg.F_x_Ctotal.size(); i++){ - franka_state->F_x_Ctotal[i] = msg.F_x_Ctotal[i]; - } - for (size_t i = 0; i < msg.elbow.size(); i++){ - franka_state->elbow[i] = msg.elbow[i]; - } - for (size_t i = 0; i < msg.elbow_d.size(); i++){ - franka_state->elbow_d[i] = msg.elbow_d[i]; - } - for (size_t i = 0; i < msg.elbow_c.size(); i++){ - franka_state->elbow_c[i] = msg.elbow_c[i]; - } - for (size_t i = 0; i < msg.delbow_c.size(); i++){ - franka_state->delbow_c[i] = msg.delbow_c[i]; - } - for (size_t i = 0; i < msg.ddelbow_c.size(); i++){ - franka_state->ddelbow_c[i] = msg.ddelbow_c[i]; - } - for (size_t i = 0; i < msg.tau_J.size(); i++){ - franka_state->tau_J[i] = msg.tau_J[i]; - } - for (size_t i = 0; i < msg.tau_J_d.size(); i++){ - franka_state->tau_J_d[i] = msg.tau_J_d[i]; - } - for (size_t i = 0; i < msg.dtau_J.size(); i++){ - franka_state->dtau_J[i] = msg.dtau_J[i]; - } - for (size_t i = 0; i < msg.q.size(); i++){ - franka_state->q[i] = msg.q[i]; - } - for (size_t i = 0; i < msg.q_d.size(); i++){ - franka_state->q_d[i] = msg.q_d[i]; - } - for (size_t i = 0; i < msg.dq.size(); i++){ - franka_state->dq[i] = msg.dq[i]; - } - for (size_t i = 0; i < msg.dq_d.size(); i++){ - franka_state->dq_d[i] = msg.dq_d[i]; - } - for (size_t i = 0; i < msg.ddq_d.size(); i++){ - franka_state->ddq_d[i] = msg.ddq_d[i]; - } - for (size_t i = 0; i < msg.joint_contact.size(); i++){ - franka_state->joint_contact[i] = msg.joint_contact[i]; - } - for (size_t i = 0; i < msg.cartesian_contact.size(); i++){ - franka_state->cartesian_contact[i] = msg.cartesian_contact[i]; - } - for (size_t i = 0; i < msg.joint_collision.size(); i++){ - franka_state->joint_collision[i] = msg.joint_collision[i]; - } - for (size_t i = 0; i < msg.cartesian_collision.size(); i++){ - franka_state->cartesian_collision[i] = msg.cartesian_collision[i]; - } - for (size_t i = 0; i < msg.tau_ext_hat_filtered.size(); i++){ - franka_state->tau_ext_hat_filtered[i] = msg.tau_ext_hat_filtered[i]; - } - for (size_t i = 0; i < msg.O_F_ext_hat_K.size(); i++){ - franka_state->O_F_ext_hat_K[i] = msg.O_F_ext_hat_K[i]; - } - for (size_t i = 0; i < msg.K_F_ext_hat_K.size(); i++){ - franka_state->K_F_ext_hat_K[i] = msg.K_F_ext_hat_K[i]; - } - for (size_t i = 0; i < msg.O_dP_EE_d.size(); i++){ - franka_state->O_dP_EE_d[i] = msg.O_dP_EE_d[i]; - } - for (size_t i = 0; i < msg.O_T_EE_c.size(); i++){ - franka_state->O_T_EE_c[i] = msg.O_T_EE_c[i]; - } - for (size_t i = 0; i < msg.O_dP_EE_c.size(); i++){ - franka_state->O_dP_EE_c[i] = msg.O_dP_EE_c[i]; - } - for (size_t i = 0; i < msg.O_ddP_EE_c.size(); i++){ - franka_state->O_ddP_EE_c[i] = msg.O_ddP_EE_c[i]; - } - for (size_t i = 0; i < msg.theta.size(); i++){ - franka_state->theta[i] = msg.theta[i]; - } - for (size_t i = 0; i < msg.dtheta.size(); i++){ - franka_state->dtheta[i] = msg.dtheta[i]; - } - - std::stringstream ss_current_errors; - ss_current_errors << msg.current_errors; - franka_state->current_errors = ss_current_errors.str(); - - std::stringstream ss_last_motion_errors; - ss_last_motion_errors << msg.last_motion_errors; - franka_state->last_motion_errors = ss_last_motion_errors.str(); - - franka_state->control_command_success_rate = msg.control_command_success_rate; - franka_state->robot_mode = msg.robot_mode; - // time from franka robot - franka_state->franka_time = msg.time; - franka_state->valid = true; - } - // time for drake loop - franka_state->utime = context.get_time() * 1e6; -} - -/***************************************************************************************/ -// RosToLcmObjectState implementation - -RosToLcmObjectState::RosToLcmObjectState() { - - this->DeclareAbstractInputPort("ROS Float64MultiArray", - drake::Value()); - this->DeclareAbstractOutputPort("ball_position", - &RosToLcmObjectState::ConvertToLCM); - -} - -void RosToLcmObjectState::ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_object_state* object_state) const { - - const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); - const auto& msg = input->get_value(); - - if (msg.data.empty()){ - for (size_t i = 0; i < object_state->num_positions; i++){ - object_state->position[i] = nan(""); - } - } - else{ - for (size_t i = 0; i < object_state->num_positions; i++){ - object_state->position[i] = msg.data[i]; - } - } - object_state->utime = context.get_time() * 1e6; -} - -} // namespace systems -} // namespace dairlib diff --git a/examples/franka/systems/franka_ros_lcm_conversions.h b/examples/franka/systems/franka_ros_lcm_conversions.h deleted file mode 100644 index 6dc31fbb00..0000000000 --- a/examples/franka/systems/franka_ros_lcm_conversions.h +++ /dev/null @@ -1,161 +0,0 @@ -#pragma once - -#include -#include -#include - -#include "systems/framework/output_vector.h" -#include "systems/framework/timestamped_vector.h" - -#include "drake/multibody/plant/multibody_plant.h" -#include "drake/systems/framework/leaf_system.h" -#include "drake/systems/lcm/lcm_interface_system.h" - -#include "std_msgs/Float64MultiArray.h" -#include "sensor_msgs/JointState.h" -//#include "dairlib/lcmt_c3.hpp" -#include "dairlib/lcmt_robot_output.hpp" -#include "dairlib/lcmt_franka_state.hpp" -#include "dairlib/lcmt_estimated_object_state.hpp" - -namespace dairlib { -namespace systems { - -class LcmToRosTimestampedVector : public drake::systems::LeafSystem { - public: - static std::unique_ptr Make(int vector_size) { - return std::make_unique(vector_size); - } - - explicit LcmToRosTimestampedVector(int vector_size); - - private: - void ConvertToROS(const drake::systems::Context& context, - std_msgs::Float64MultiArray* output) const; - int vector_size_; -}; - -// NOTE: this class appends 7 zeros to the position and 6 zeros -// to the velocity fields. This was done since this class was hard -// coded for the C3 Franka experiments. -class RosToLcmRobotState : public drake::systems::LeafSystem { - public: - static std::unique_ptr Make(int num_positions, int num_velocities, int num_efforts) { - return std::make_unique(num_positions, num_velocities, num_efforts); - } - - explicit RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts); - - private: - void ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_robot_output* output) const; - int num_positions_; - int num_velocities_; - int num_efforts_; - const int num_franka_joints_{7}; - - const std::vector default_ball_position_ {1, 0, 0, 0, 0.5, 0, 0.0315-0.0301}; - - const std::vector position_names_ { - "panda_joint1", - "panda_joint2", - "panda_joint3", - "panda_joint4", - "panda_joint5", - "panda_joint6", - "panda_joint7", - "base_qw", - "base_qx", - "base_qy", - "base_qz", - "base_x", - "base_y", - "base_z"}; - - const std::vector velocity_names_ { - "panda_joint1dot", - "panda_joint2dot", - "panda_joint3dot", - "panda_joint4dot", - "panda_joint5dot", - "panda_joint6dot", - "panda_joint7dot", - "base_wx", - "base_wy", - "base_wz", - "base_vx", - "base_vy", - "base_vz"}; - - const std::vector effort_names_ { - "panda_motor1", - "panda_motor2", - "panda_motor3", - "panda_motor4", - "panda_motor5", - "panda_motor6", - "panda_motor7",}; - -}; - -//class ROSToC3LCM : public drake::systems::LeafSystem { -// public: -// static std::unique_ptr Make(int num_positions, int num_velocities, -// int lambda_size, int misc_size) { -// -// return std::make_unique(num_positions, num_velocities, -// lambda_size, misc_size); -// } -// -// explicit ROSToC3LCM(int num_positions, int num_velocities, -// int lambda_size, int misc_size); -// -// private: -// void ConvertToLCM(const drake::systems::Context& context, -// dairlib::lcmt_c3* output) const; -// int num_positions_; -// int num_velocities_; -// int lambda_size_; -// int misc_size_; -// int data_size_; -//}; - -/// More specific translator from Franka state to LCM. Similar to lcmt_cassie_out.lcm -class RosToLcmFrankaState : public drake::systems::LeafSystem { - public: - static std::unique_ptr Make() { - - return std::make_unique(); - } - - explicit RosToLcmFrankaState(); - - private: - void ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_franka_state* franka_state) const; -}; - -class RosToLcmObjectState : public drake::systems::LeafSystem { - public: - static std::unique_ptr Make() { - - return std::make_unique(); - } - - explicit RosToLcmObjectState(); - - private: - void ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_object_state* franka_state) const; - - std::map enum_map_ = - {{-3.0, "Invalid"}, // invalid ball measurement obtained (i.e. incorrectly identified ball) - {-2.0, "Outlier"}, // outlier ball measurement obtained (i.e. too diff than other measurements) - {-1.0, "Ball not found"}, // no ball measurement obtained - { 0.0, "N/A"}, // See below - { 1.0, "Valid"}}; // valid ball measurement obtained - -}; - -} // namespace systems -} // namespace dairlib From 07354c977f74030c1c82b4344724be367b12e75a Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 30 Oct 2023 16:55:34 -0400 Subject: [PATCH 484/758] adding ros lcm translator --- examples/franka/franka_ros_lcm_bridge.cc | 132 ++++---- examples/franka/franka_sim.cc | 30 +- .../parameters/franka_osc_controller_params.h | 3 +- systems/ros/BUILD.bazel | 18 +- systems/ros/franka_ros_lcm_conversions.cc | 303 ++++++++++++++++++ systems/ros/franka_ros_lcm_conversions.h | 161 ++++++++++ systems/ros/parameters/franka_ros_channels.h | 19 ++ .../ros/parameters/franka_ros_channels.yaml | 5 + systems/ros/robot_lcm_ros_translator.cc | 11 - systems/ros/robot_lcm_ros_translator.h | 26 -- 10 files changed, 580 insertions(+), 128 deletions(-) create mode 100644 systems/ros/franka_ros_lcm_conversions.cc create mode 100644 systems/ros/franka_ros_lcm_conversions.h create mode 100644 systems/ros/parameters/franka_ros_channels.h create mode 100644 systems/ros/parameters/franka_ros_channels.yaml delete mode 100644 systems/ros/robot_lcm_ros_translator.cc delete mode 100644 systems/ros/robot_lcm_ros_translator.h diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index 8bab1af49f..664de92488 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -2,36 +2,38 @@ #ifdef ROS -#include #include + +#include #include -#include -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" #include +#include + #include "ros/ros.h" #include "sensor_msgs/JointState.h" #include "std_msgs/Float64MultiArray.h" - -#include "systems/ros/ros_subscriber_system.h" -#include "systems/ros/ros_publisher_system.h" #include "systems/ros/c3_ros_conversions.h" +#include "systems/ros/ros_publisher_system.h" +#include "systems/ros/ros_subscriber_system.h" #include "systems/system_utils.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" + using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using dairlib::systems::RosSubscriberSystem; using dairlib::systems::RosPublisherSystem; -using dairlib::systems::ROSToRobotOutputLCM; -using dairlib::systems::ROSToC3LCM; +using dairlib::systems::RosSubscriberSystem; using dairlib::systems::ROSToBallPositionLCM; +using dairlib::systems::ROSToC3LCM; +using dairlib::systems::ROSToRobotOutputLCM; // Shutdown ROS gracefully and then exit void SigintHandler(int sig) { @@ -39,18 +41,23 @@ void SigintHandler(int sig) { exit(sig); } -DEFINE_string(joint_channel, "/c3/joint_states", - "Rostopic for receiving joint state info from Franka. " - "Use /c3/joint_states for actual experiments (1000hz channel), and " - "use /franka_state_controller/joint_states for debugging (100hz channel)." - "Note that the default rate of the franka_control_interface is 30hz, " - "but this rate has been overridden to be 100hz on the franka computer"); +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + +DEFINE_string(ros_channels, "systems/ros/parameters/franka_ros_channels.yaml", + "Filepath containing ROS channels"); namespace dairlib { -int DoMain(int argc, char* argv[]){ +int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + FrankaLcmChannels ros_channel_params = + drake::yaml::LoadYamlFile(FLAGS_ros_channels); + ros::init(argc, argv, "run_c3_ros_to_lcm"); ros::NodeHandle node_handle; @@ -67,67 +74,62 @@ int DoMain(int argc, char* argv[]){ /// convert franka joint states to lcm auto franka_joint_state_ros_subscriber = builder.AddSystem(RosSubscriberSystem::Make( - FLAGS_joint_channel, &node_handle)); - auto ros_to_lcm_robot_state = builder.AddSystem(RosToLcmRobotState::Make(7, 7, 7)); + ros_channel_params.franka_state_channel, &node_handle)); + auto ros_to_lcm_robot_state = builder.AddSystem(RosToLcmRobotState::Make( + plant.num_positions(), plant.num_velocities(), plant.num_actuators())); // change this to output correctly (i.e. when ros subscriber gets new message) - auto robot_output_pub = builder.AddSystem( - LcmPublisherSystem::Make( - "FRANKA_STATE", &drake_lcm, + auto robot_output_lcm_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_state_channel, &drake_lcm, {drake::systems::TriggerType::kForced})); /// connections - builder.Connect(franka_joint_state_ros_subscriber->get_output_port(), ros_to_lcm_robot_state->get_input_port()); - builder.Connect(ros_to_lcm_robot_state->get_output_port(), robot_output_pub->get_input_port()); + builder.Connect(franka_joint_state_ros_subscriber->get_output_port(), + ros_to_lcm_robot_state->get_input_port()); + builder.Connect(ros_to_lcm_robot_state->get_output_port(), + robot_output_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ /// convert ball position estimate to lcm auto tray_object_state_ros_subscriber = builder.AddSystem(RosSubscriberSystem::Make( - "/c3/position_estimate", &node_handle)); + ros_channel_params.tray_state_channel, &node_handle)); auto ros_to_lcm_object_state = builder.AddSystem(RosToLcmObjectState::Make()); // change this to output correctly (i.e. when ros subscriber gets new message) - auto ball_position_pub = builder.AddSystem( - LcmPublisherSystem::Make( - "VISION_OUTPUT", &drake_lcm, + auto tray_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.tray_state_channel, &drake_lcm, {drake::systems::TriggerType::kPeriodic}, 0.005)); /// connections - builder.Connect(tray_object_state_ros_subscriber->get_output_port(), ros_to_lcm_object_state->get_input_port()); - builder.Connect(ros_to_lcm_object_state->get_output_port(), ball_position_pub->get_input_port()); - - /* -------------------------------------------------------------------------------------------*/ - /// convert individual camera measurements to lcm for logging - int num_cameras = 3; - std::vector*> - cam_subscribers(num_cameras, nullptr); - std::vector ros_lcm_converters(num_cameras, nullptr); - std::vector cam_publishers(num_cameras, nullptr); - - for (int i = 0; i < num_cameras; i++){ - // Add systems - std::string cam_id = std::to_string(i); - cam_subscribers[i] = - builder.AddSystem(RosSubscriberSystem::Make( - "/c3/cam" + cam_id, &node_handle)); - ros_lcm_converters[i] = - builder.AddSystem(ROSToBallPositionLCM::Make()); - cam_publishers[i] = - builder.AddSystem( - LcmPublisherSystem::Make( - "CAM" + cam_id + "_OUTPUT", &drake_lcm, - {drake::systems::TriggerType::kPeriodic}, 0.005)); - - // Connect systems - builder.Connect(cam_subscribers[i]->get_output_port(), - ros_lcm_converters[i]->get_input_port()); - builder.Connect(ros_lcm_converters[i]->get_output_port(), - cam_publishers[i]->get_input_port()); - } + builder.Connect(tray_object_state_ros_subscriber->get_output_port(), + ros_to_lcm_object_state->get_input_port()); + builder.Connect(ros_to_lcm_object_state->get_output_port(), + ball_position_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ + auto robot_input_lcm_subscriber = + builder->AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.osc_channel, &drake_lcm)); + auto robot_input_receiver = builder->AddSystem(plant); + auto robot_input_passthrough = builder->AddSystem( + robot_input_receiver->get_output_port(0).size(), 0, + plant.get_actuation_input_port().size()); + auto robot_input_ros_publisher = builder.AddSystem( + systems::RosPublisherSystem::Make( + ros_channel_params.franka_input_channel, &node_handle, .001)); + auto lcm_to_ros_robot_input = + builder.AddSystem(7); + // try making this kForced + + builder.Connect(robot_input_passthrough->get_output_port(), + lcm_to_ros_robot_input->get_input_port()); + builder.Connect(lcm_to_ros_robot_input->get_output_port(), + ros_publisher->get_input_port()); auto sys = builder.Build(); - // DrawAndSaveDiagramGraph(*sys, "examples/franka_trajectory_following/diagram_run_c3_ros_to_lcm"); + // DrawAndSaveDiagramGraph(*sys, + // "examples/franka_trajectory_following/diagram_run_c3_ros_to_lcm"); Simulator simulator(*sys); simulator.Initialize(); @@ -142,8 +144,8 @@ int DoMain(int argc, char* argv[]){ return 0; } -} // namespace dairlib +} // namespace dairlib -int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv);} +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } #endif \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 60692ca675..0e46bf1ad6 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -124,21 +124,21 @@ int DoMain(int argc, char* argv[]) { // plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( // {"paddle", paddle_geom_set}, {"table_support", table_support_set}); - VectorXd rotor_inertias(plant.num_actuators()); - rotor_inertias << 61, 61, 61, 61, 61, 61, 61; - rotor_inertias *= 1e-6; - VectorXd gear_ratios(plant.num_actuators()); - gear_ratios << 25, 25, 25, 25, 25, 25, 25; - std::vector motor_joint_names = { - "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", - "panda_motor5", "panda_motor6", "panda_motor7"}; - for (int i = 0; i < rotor_inertias.size(); ++i) { - auto& joint_actuator = plant.get_mutable_joint_actuator( - drake::multibody::JointActuatorIndex(i)); - joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); - joint_actuator.set_default_gear_ratio(gear_ratios(i)); - DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); - } +// VectorXd rotor_inertias(plant.num_actuators()); +// rotor_inertias << 61, 61, 61, 61, 61, 61, 61; +// rotor_inertias *= 1e-6; +// VectorXd gear_ratios(plant.num_actuators()); +// gear_ratios << 25, 25, 25, 25, 25, 25, 25; +// std::vector motor_joint_names = { +// "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", +// "panda_motor5", "panda_motor6", "panda_motor7"}; +// for (int i = 0; i < rotor_inertias.size(); ++i) { +// auto& joint_actuator = plant.get_mutable_joint_actuator( +// drake::multibody::JointActuatorIndex(i)); +// joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); +// joint_actuator.set_default_gear_ratio(gear_ratios(i)); +// DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); +// } plant.Finalize(); diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index 61244da167..7192121c55 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -13,11 +13,11 @@ struct FrankaControllerParams : OSCGains { double end_effector_acceleration; bool track_end_effector_orientation; + std::vector neutral_position; double x_scale; double y_scale; double z_scale; - std::vector neutral_position; std::vector EndEffectorW; std::vector EndEffectorKp; std::vector EndEffectorKd; @@ -28,7 +28,6 @@ struct FrankaControllerParams : OSCGains { std::vector EndEffectorRotKp; std::vector EndEffectorRotKd; -// Eigen::Vector3d neutral_position; Eigen::MatrixXd W_end_effector; Eigen::MatrixXd K_p_end_effector; Eigen::MatrixXd K_d_end_effector; diff --git a/systems/ros/BUILD.bazel b/systems/ros/BUILD.bazel index 863b62eaae..0b0ee03a7c 100644 --- a/systems/ros/BUILD.bazel +++ b/systems/ros/BUILD.bazel @@ -13,22 +13,22 @@ cc_library( ], ) + cc_library( - name = "ros_translator", - hdrs = [ - "robot_lcm_ros_translator.h", - ], - srcs = [ - "robot_lcm_ros_translator.cc", - ], + name = "franka_ros_lcm_conversions", + srcs = ["franka_ros_lcm_conversions.cc"], + hdrs = ["franka_ros_lcm_conversions.h"], tags = ["ros"], deps = [ - "@drake//:drake_shared_library", + "//lcmtypes:lcmt_robot", + "//common", "@ros", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", ], ) - cc_binary( name = "test_ros_publisher_system", srcs = ["test/test_ros_publisher_system.cc"], diff --git a/systems/ros/franka_ros_lcm_conversions.cc b/systems/ros/franka_ros_lcm_conversions.cc new file mode 100644 index 0000000000..99fd06c629 --- /dev/null +++ b/systems/ros/franka_ros_lcm_conversions.cc @@ -0,0 +1,303 @@ +#include "systems/ros/franka_ros_lcm_conversions.h" +//#include "franka_msgs/FrankaState.h" +#include +namespace dairlib { +namespace systems { + +using Eigen::VectorXd; + +// LcmToRosTimestampedVector implementation +LcmToRosTimestampedVector::LcmToRosTimestampedVector(int vector_size) + : vector_size_(vector_size) { + + this->DeclareVectorInputPort("u, t", + TimestampedVector(vector_size_)); + this->DeclareAbstractOutputPort("ROS Float64MultiArray", + &LcmToRosTimestampedVector::ConvertToROS); +}; + +void LcmToRosTimestampedVector::ConvertToROS(const drake::systems::Context& context, + std_msgs::Float64MultiArray* output) const { + + const TimestampedVector* input = + (TimestampedVector*)this->EvalVectorInput(context, 0); + + // note: this function currently appends the timestamp to the end of the output + output->data.clear(); + for (int i = 0; i < vector_size_; i++){ + if (std::isnan(input->GetAtIndex(i))){ + output->data.push_back(0); + } + else{ + output->data.push_back(input->GetAtIndex(i)); + } + } + output->data.push_back(input->get_timestamp()); +} + +/***************************************************************************************/ +// ROSToRobotOuput implementation + +RosToLcmRobotState::RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts) + : num_positions_(num_positions), num_velocities_(num_velocities), num_efforts_(num_efforts) { + + this->DeclareAbstractInputPort("Franka JointState topic", + drake::Value()); + this->DeclareAbstractOutputPort("lcmt_robot_output", + &RosToLcmRobotState::ConvertToLCM); +} + +void RosToLcmRobotState::ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const { + + const drake::AbstractValue* const input = this->EvalAbstractInput(context, 0); + DRAKE_ASSERT(input != nullptr); + const auto& msg = input->get_value(); + + output->num_positions = num_positions_; + output->num_velocities = num_velocities_; + output->num_efforts = num_efforts_; + output->position_names.resize(num_positions_); + output->velocity_names.resize(num_velocities_); + output->effort_names.resize(num_efforts_); + output->position_names = position_names_; + output->velocity_names = velocity_names_; + output->effort_names = effort_names_; + output->position.resize(num_positions_); + output->velocity.resize(num_velocities_); + output->effort.resize(num_efforts_); + + // yet to receive message from rostopic + if (msg.position.empty()){ + for (int i = 0; i < num_positions_; i++){ + output->position[i] = nan(""); + } + for (int i = 0; i < num_velocities_; i++){ + output->velocity[i] = nan(""); + } + for (int i = 0; i < num_efforts_; i++){ + output->effort[i] = nan(""); + } + for (int i = 0; i < 3; i++){ + output->imu_accel[i] = nan(""); + } + } + // input should be order as "positions, velocities, effort, timestamp" + else{ + for (int i = 0; i < num_franka_joints_; i++){ + output->position[i] = msg.position[i]; + } + // hard coded to add 7 zeros to the end of position + for (int i = num_franka_joints_; i < num_positions_; i++){ + output->position[i] = default_ball_position_[i-num_franka_joints_]; + } + + for (int i = 0; i < num_velocities_; i++){ + output->velocity[i] = msg.velocity[i]; + } + // hard coded to add 6 zeros to the end of velocity + for (int i = num_franka_joints_; i < num_velocities_; i++){ + output->velocity[i] = 0; + } + + for (int i = 0; i < num_efforts_; i++){ + output->effort[i] = msg.effort[i]; + } + for (int i = 0; i < 3; i++){ + output->imu_accel[i] = 0; + } + } + output->utime = context.get_time() * 1e6; +} + + +/***************************************************************************************/ +// RosToLcmFrankaState implementation + +RosToLcmFrankaState::RosToLcmFrankaState() { + + this->DeclareAbstractInputPort("ROS Float64MultiArray", + drake::Value()); + this->DeclareAbstractOutputPort("lcmt_franka_state", + &RosToLcmFrankaState::ConvertToLCM); +} + +void RosToLcmFrankaState::ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_franka_state* franka_state) const { + + const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); + const auto& msg = input->get_value(); + + if (msg.O_T_EE.empty()){ + franka_state->valid = false; + } + else{ + for (size_t i = 0; i < msg.O_T_EE.size(); i++){ + franka_state->O_T_EE[i] = msg.O_T_EE[i]; + } + for (size_t i = 0; i < msg.O_T_EE_d.size(); i++){ + franka_state->O_T_EE_d[i] = msg.O_T_EE_d[i]; + } + for (size_t i = 0; i < msg.F_T_EE.size(); i++){ + franka_state->F_T_EE[i] = msg.F_T_EE[i]; + } + for (size_t i = 0; i < msg.F_T_NE.size(); i++){ + franka_state->F_T_NE[i] = msg.F_T_NE[i]; + } + for (size_t i = 0; i < msg.NE_T_EE.size(); i++){ + franka_state->NE_T_EE[i] = msg.NE_T_EE[i]; + } + for (size_t i = 0; i < msg.EE_T_K.size(); i++){ + franka_state->EE_T_K[i] = msg.EE_T_K[i]; + } + franka_state->m_ee = msg.m_ee; + for (size_t i = 0; i < msg.I_ee.size(); i++){ + franka_state->I_ee[i] = msg.I_ee[i]; + } + for (size_t i = 0; i < msg.F_x_Cee.size(); i++){ + franka_state->F_x_Cee[i] = msg.F_x_Cee[i]; + } + franka_state->m_load = msg.m_load; + for (size_t i = 0; i < msg.I_load.size(); i++){ + franka_state->I_load[i] = msg.I_load[i]; + } + for (size_t i = 0; i < msg.F_x_Cload.size(); i++){ + franka_state->F_x_Cload[i] = msg.F_x_Cload[i]; + } + franka_state->m_total = msg.m_total; + for (size_t i = 0; i < msg.I_total.size(); i++){ + franka_state->I_total[i] = msg.I_total[i]; + } + for (size_t i = 0; i < msg.F_x_Ctotal.size(); i++){ + franka_state->F_x_Ctotal[i] = msg.F_x_Ctotal[i]; + } + for (size_t i = 0; i < msg.elbow.size(); i++){ + franka_state->elbow[i] = msg.elbow[i]; + } + for (size_t i = 0; i < msg.elbow_d.size(); i++){ + franka_state->elbow_d[i] = msg.elbow_d[i]; + } + for (size_t i = 0; i < msg.elbow_c.size(); i++){ + franka_state->elbow_c[i] = msg.elbow_c[i]; + } + for (size_t i = 0; i < msg.delbow_c.size(); i++){ + franka_state->delbow_c[i] = msg.delbow_c[i]; + } + for (size_t i = 0; i < msg.ddelbow_c.size(); i++){ + franka_state->ddelbow_c[i] = msg.ddelbow_c[i]; + } + for (size_t i = 0; i < msg.tau_J.size(); i++){ + franka_state->tau_J[i] = msg.tau_J[i]; + } + for (size_t i = 0; i < msg.tau_J_d.size(); i++){ + franka_state->tau_J_d[i] = msg.tau_J_d[i]; + } + for (size_t i = 0; i < msg.dtau_J.size(); i++){ + franka_state->dtau_J[i] = msg.dtau_J[i]; + } + for (size_t i = 0; i < msg.q.size(); i++){ + franka_state->q[i] = msg.q[i]; + } + for (size_t i = 0; i < msg.q_d.size(); i++){ + franka_state->q_d[i] = msg.q_d[i]; + } + for (size_t i = 0; i < msg.dq.size(); i++){ + franka_state->dq[i] = msg.dq[i]; + } + for (size_t i = 0; i < msg.dq_d.size(); i++){ + franka_state->dq_d[i] = msg.dq_d[i]; + } + for (size_t i = 0; i < msg.ddq_d.size(); i++){ + franka_state->ddq_d[i] = msg.ddq_d[i]; + } + for (size_t i = 0; i < msg.joint_contact.size(); i++){ + franka_state->joint_contact[i] = msg.joint_contact[i]; + } + for (size_t i = 0; i < msg.cartesian_contact.size(); i++){ + franka_state->cartesian_contact[i] = msg.cartesian_contact[i]; + } + for (size_t i = 0; i < msg.joint_collision.size(); i++){ + franka_state->joint_collision[i] = msg.joint_collision[i]; + } + for (size_t i = 0; i < msg.cartesian_collision.size(); i++){ + franka_state->cartesian_collision[i] = msg.cartesian_collision[i]; + } + for (size_t i = 0; i < msg.tau_ext_hat_filtered.size(); i++){ + franka_state->tau_ext_hat_filtered[i] = msg.tau_ext_hat_filtered[i]; + } + for (size_t i = 0; i < msg.O_F_ext_hat_K.size(); i++){ + franka_state->O_F_ext_hat_K[i] = msg.O_F_ext_hat_K[i]; + } + for (size_t i = 0; i < msg.K_F_ext_hat_K.size(); i++){ + franka_state->K_F_ext_hat_K[i] = msg.K_F_ext_hat_K[i]; + } + for (size_t i = 0; i < msg.O_dP_EE_d.size(); i++){ + franka_state->O_dP_EE_d[i] = msg.O_dP_EE_d[i]; + } + for (size_t i = 0; i < msg.O_T_EE_c.size(); i++){ + franka_state->O_T_EE_c[i] = msg.O_T_EE_c[i]; + } + for (size_t i = 0; i < msg.O_dP_EE_c.size(); i++){ + franka_state->O_dP_EE_c[i] = msg.O_dP_EE_c[i]; + } + for (size_t i = 0; i < msg.O_ddP_EE_c.size(); i++){ + franka_state->O_ddP_EE_c[i] = msg.O_ddP_EE_c[i]; + } + for (size_t i = 0; i < msg.theta.size(); i++){ + franka_state->theta[i] = msg.theta[i]; + } + for (size_t i = 0; i < msg.dtheta.size(); i++){ + franka_state->dtheta[i] = msg.dtheta[i]; + } + + std::stringstream ss_current_errors; + ss_current_errors << msg.current_errors; + franka_state->current_errors = ss_current_errors.str(); + + std::stringstream ss_last_motion_errors; + ss_last_motion_errors << msg.last_motion_errors; + franka_state->last_motion_errors = ss_last_motion_errors.str(); + + franka_state->control_command_success_rate = msg.control_command_success_rate; + franka_state->robot_mode = msg.robot_mode; + // time from franka robot + franka_state->franka_time = msg.time; + franka_state->valid = true; + } + // time for drake loop + franka_state->utime = context.get_time() * 1e6; +} + +/***************************************************************************************/ +// RosToLcmObjectState implementation + +RosToLcmObjectState::RosToLcmObjectState() { + + this->DeclareAbstractInputPort("ROS Float64MultiArray", + drake::Value()); + this->DeclareAbstractOutputPort("ball_position", + &RosToLcmObjectState::ConvertToLCM); + +} + +void RosToLcmObjectState::ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_object_state* object_state) const { + + const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); + const auto& msg = input->get_value(); + + if (msg.data.empty()){ + for (size_t i = 0; i < object_state->num_positions; i++){ + object_state->position[i] = nan(""); + } + } + else{ + for (size_t i = 0; i < object_state->num_positions; i++){ + object_state->position[i] = msg.data[i]; + } + } + object_state->utime = context.get_time() * 1e6; +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/ros/franka_ros_lcm_conversions.h b/systems/ros/franka_ros_lcm_conversions.h new file mode 100644 index 0000000000..6dc31fbb00 --- /dev/null +++ b/systems/ros/franka_ros_lcm_conversions.h @@ -0,0 +1,161 @@ +#pragma once + +#include +#include +#include + +#include "systems/framework/output_vector.h" +#include "systems/framework/timestamped_vector.h" + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" +#include "drake/systems/lcm/lcm_interface_system.h" + +#include "std_msgs/Float64MultiArray.h" +#include "sensor_msgs/JointState.h" +//#include "dairlib/lcmt_c3.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "dairlib/lcmt_franka_state.hpp" +#include "dairlib/lcmt_estimated_object_state.hpp" + +namespace dairlib { +namespace systems { + +class LcmToRosTimestampedVector : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make(int vector_size) { + return std::make_unique(vector_size); + } + + explicit LcmToRosTimestampedVector(int vector_size); + + private: + void ConvertToROS(const drake::systems::Context& context, + std_msgs::Float64MultiArray* output) const; + int vector_size_; +}; + +// NOTE: this class appends 7 zeros to the position and 6 zeros +// to the velocity fields. This was done since this class was hard +// coded for the C3 Franka experiments. +class RosToLcmRobotState : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make(int num_positions, int num_velocities, int num_efforts) { + return std::make_unique(num_positions, num_velocities, num_efforts); + } + + explicit RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts); + + private: + void ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const; + int num_positions_; + int num_velocities_; + int num_efforts_; + const int num_franka_joints_{7}; + + const std::vector default_ball_position_ {1, 0, 0, 0, 0.5, 0, 0.0315-0.0301}; + + const std::vector position_names_ { + "panda_joint1", + "panda_joint2", + "panda_joint3", + "panda_joint4", + "panda_joint5", + "panda_joint6", + "panda_joint7", + "base_qw", + "base_qx", + "base_qy", + "base_qz", + "base_x", + "base_y", + "base_z"}; + + const std::vector velocity_names_ { + "panda_joint1dot", + "panda_joint2dot", + "panda_joint3dot", + "panda_joint4dot", + "panda_joint5dot", + "panda_joint6dot", + "panda_joint7dot", + "base_wx", + "base_wy", + "base_wz", + "base_vx", + "base_vy", + "base_vz"}; + + const std::vector effort_names_ { + "panda_motor1", + "panda_motor2", + "panda_motor3", + "panda_motor4", + "panda_motor5", + "panda_motor6", + "panda_motor7",}; + +}; + +//class ROSToC3LCM : public drake::systems::LeafSystem { +// public: +// static std::unique_ptr Make(int num_positions, int num_velocities, +// int lambda_size, int misc_size) { +// +// return std::make_unique(num_positions, num_velocities, +// lambda_size, misc_size); +// } +// +// explicit ROSToC3LCM(int num_positions, int num_velocities, +// int lambda_size, int misc_size); +// +// private: +// void ConvertToLCM(const drake::systems::Context& context, +// dairlib::lcmt_c3* output) const; +// int num_positions_; +// int num_velocities_; +// int lambda_size_; +// int misc_size_; +// int data_size_; +//}; + +/// More specific translator from Franka state to LCM. Similar to lcmt_cassie_out.lcm +class RosToLcmFrankaState : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make() { + + return std::make_unique(); + } + + explicit RosToLcmFrankaState(); + + private: + void ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_franka_state* franka_state) const; +}; + +class RosToLcmObjectState : public drake::systems::LeafSystem { + public: + static std::unique_ptr Make() { + + return std::make_unique(); + } + + explicit RosToLcmObjectState(); + + private: + void ConvertToLCM(const drake::systems::Context& context, + dairlib::lcmt_object_state* franka_state) const; + + std::map enum_map_ = + {{-3.0, "Invalid"}, // invalid ball measurement obtained (i.e. incorrectly identified ball) + {-2.0, "Outlier"}, // outlier ball measurement obtained (i.e. too diff than other measurements) + {-1.0, "Ball not found"}, // no ball measurement obtained + { 0.0, "N/A"}, // See below + { 1.0, "Valid"}}; // valid ball measurement obtained + +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/ros/parameters/franka_ros_channels.h b/systems/ros/parameters/franka_ros_channels.h new file mode 100644 index 0000000000..d295204f92 --- /dev/null +++ b/systems/ros/parameters/franka_ros_channels.h @@ -0,0 +1,19 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + + +struct FrankaRosChannels { + std::string franka_state_channel; + std::string tray_state_channel; + std::string box_state_channel; + std::string franka_input_channel; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(franka_state_channel)); + a->Visit(DRAKE_NVP(tray_state_channel)); + a->Visit(DRAKE_NVP(box_state_channel)); + a->Visit(DRAKE_NVP(franka_input_channel)); + } +}; \ No newline at end of file diff --git a/systems/ros/parameters/franka_ros_channels.yaml b/systems/ros/parameters/franka_ros_channels.yaml new file mode 100644 index 0000000000..ff818f635f --- /dev/null +++ b/systems/ros/parameters/franka_ros_channels.yaml @@ -0,0 +1,5 @@ +franka_state_channel: /franka/franka_robot_state +tray_state_channel: /franka/tray_object_state +box_state_channel: /franka/box_object_state +franka_input_channel: /franka/franka_input + diff --git a/systems/ros/robot_lcm_ros_translator.cc b/systems/ros/robot_lcm_ros_translator.cc deleted file mode 100644 index cc567f945d..0000000000 --- a/systems/ros/robot_lcm_ros_translator.cc +++ /dev/null @@ -1,11 +0,0 @@ -#include "robot_lcm_ros_translator.h" - - -using drake::multibody::MultibodyPlant; - -namespace dairlib { -namespace systems { - -RobotInputToROS::RobotInputToROS(MultibodyPlant& plant){ - -} diff --git a/systems/ros/robot_lcm_ros_translator.h b/systems/ros/robot_lcm_ros_translator.h deleted file mode 100644 index e1da2e8461..0000000000 --- a/systems/ros/robot_lcm_ros_translator.h +++ /dev/null @@ -1,26 +0,0 @@ -#pragma once - - -#include -#include -#include - -#include "drake/multibody/plant/multibody_plant.h" -#include "drake/systems/framework/leaf_system.h" -#include "drake/systems/lcm/lcm_interface_system.h" - -namespace dairlib { -namespace systems { - -class RobotInputToROS : public drake::systems::LeafSystem { - public: - explicit RobotInputToROS(drake::multibody::MultibodyPlant& plant); - - private: - void ConvertToROS(const drake::systems::Context& context, - std_msgs::Float64MultiArray* output) const; - int num_elements_; -}; - -} -} \ No newline at end of file From 143c3172e0c0e7bb430e9c8097a360f417b8fa26 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 31 Oct 2023 12:12:30 -0400 Subject: [PATCH 485/758] compiled ros translator with ros on franka computer --- examples/franka/BUILD.bazel | 21 +-- examples/franka/franka_dispatcher_in.cc | 151 ------------------ examples/franka/franka_dispatcher_out.cc | 0 examples/franka/franka_ros_lcm_bridge.cc | 60 ++++--- examples/franka/franka_sim.cc | 53 +++--- .../franka/parameters/franka_lcm_channels.h | 2 + .../parameters/lcm_channels_hardware.yaml | 1 + .../parameters/lcm_channels_simulation.yaml | 1 + systems/ros/BUILD.bazel | 9 ++ systems/ros/franka_ros_lcm_conversions.h | 3 +- tools/workspace/ros/compile_ros_workspace.sh | 4 +- 11 files changed, 84 insertions(+), 221 deletions(-) delete mode 100644 examples/franka/franka_dispatcher_in.cc delete mode 100644 examples/franka/franka_dispatcher_out.cc diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index cdb863efb1..de1a23cb2f 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -15,24 +15,6 @@ cc_library( deps = [], ) -cc_library( - name = "franka_dispatcher_in", - srcs = ["franka_dispatcher_in.cc"], - tags = ["ros"], - deps = [ - "//systems/ros:ros_pubsub_systems" - ], -) - -cc_library( - name = "franka_dispatcher_out", - srcs = ["franka_dispatcher_out.cc"], - tags = ["ros"], - deps = [ - "//systems/ros:ros_pubsub_systems" - ], -) - cc_binary( name = "franka_sim", srcs = ["franka_sim.cc"], @@ -135,10 +117,13 @@ cc_binary( ":franka_lcm_channels", "//common", "//systems:robot_lcm_systems", + "//systems/ros:ros_pubsub_systems", + "//systems/ros:franka_ros_channels", "//systems/ros:franka_ros_lcm_conversions", "//systems:system_utils", "//systems/primitives", "@drake//:drake_shared_library", + "@ros", "@gflags", ], tags = ["ros"], diff --git a/examples/franka/franka_dispatcher_in.cc b/examples/franka/franka_dispatcher_in.cc deleted file mode 100644 index 07f5183706..0000000000 --- a/examples/franka/franka_dispatcher_in.cc +++ /dev/null @@ -1,151 +0,0 @@ -#include - -#include "dairlib/lcmt_controller_failure.hpp" -#include "dairlib/lcmt_robot_output.hpp" -#include "examples/Cassie/networking/cassie_input_translator.h" -#include "examples/Cassie/networking/cassie_udp_publisher.h" -#include "examples/Cassie/systems/input_supervisor.h" -#include "multibody/multibody_utils.h" -#include "systems/controllers/linear_controller.h" -#include "systems/controllers/pd_config_lcm.h" -#include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" - -#include "drake/lcm/drake_lcm.h" -#include "drake/systems/framework/diagram.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" - -namespace dairlib { -using drake::lcm::Subscriber; -using drake::systems::Context; -using drake::systems::DiagramBuilder; -using drake::systems::Simulator; -using drake::systems::TriggerType; -using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::LcmSubscriberSystem; -using systems::RobotCommandSender; -using systems::RobotInputReceiver; - -using std::map; -using std::string; - -DEFINE_double(echo_frequency, 50, "Network LCM pubishing frequency (Hz)."); -DEFINE_double(publish_frequency, 2000, "ROS pubishing period (Hz)."); -DEFINE_double(max_joint_velocity, 20, - "Maximum joint velocity before error is triggered"); -DEFINE_double(input_limit, 300, - "Maximum torque limit. Negative values are inf."); -DEFINE_string(state_channel_name, "CASSIE_STATE_DISPATCHER", - "The name of the lcm channel that sends Cassie's state"); - -int do_main(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm_local("udpm://239.255.76.67:7667?ttl=0"); - drake::lcm::DrakeLcm lcm_network("udpm://239.255.76.67:7667?ttl=1"); - - DiagramBuilder builder; - - // Create LCM receiver for commands - auto command_receiver = builder.AddSystem(plant); - - // Safety Controller - auto safety_controller = builder.AddSystem( - plant.num_positions(), plant.num_velocities(), plant.num_actuators()); - // Create config receiver. - auto config_receiver = builder.AddSystem(plant); - - // Create state estimate receiver, used for safety checks - auto state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - FLAGS_state_channel_name, &lcm_local)); - auto state_receiver = builder.AddSystem(plant); - - auto input_supervisor_status_pub = builder.AddSystem( - LcmPublisherSystem::Make( - "INPUT_SUPERVISOR_STATUS", &lcm_network, {TriggerType::kPeriodic}, - FLAGS_pub_rate)); - - auto input_supervisor = builder.AddSystem( - plant, FLAGS_control_channel_name_initial, FLAGS_max_joint_velocity, - input_supervisor_update_period, input_limit, FLAGS_supervisor_N); - auto net_command_sender = builder.AddSystem(plant); - command_pub_network = - builder.AddSystem(LcmPublisherSystem::Make( - "NETWORK_CASSIE_INPUT", &lcm_network, {TriggerType::kPeriodic}, - FLAGS_pub_rate)); - builder.Connect(*net_command_sender, *command_pub_network); - auto command_pub_local = - builder.AddSystem(LcmPublisherSystem::Make( - "CASSIE_INPUT", &lcm_local, {TriggerType::kForced})); - - ros::init(argc, argv, "torque_controller"); - ros::NodeHandle node_handle; - signal(SIGINT, SigintHandler); - auto c3_to_ros = builder.AddSystem(7); - // try making this kForced - auto ros_publisher = builder.AddSystem( - systems::RosPublisherSystem::Make( - "/franka_control/torque_in", &node_handle, 1 / publish_frequency)); - - builder.Connect(subvector_passthrough->get_output_port(), - c3_to_ros->get_input_port()); - builder.Connect(c3_to_ros->get_output_port(), - ros_publisher->get_input_port()); - - builder.Connect(input_supervisor->get_output_port_command(), - net_command_sender->get_input_port(0)); - builder.Connect(*net_command_sender, *command_pub_local); - - builder.Connect(state_receiver->get_output_port(0), - input_supervisor->get_input_port_state()); - builder.Connect(command_receiver->get_output_port(0), - input_supervisor->get_input_port_command()); - builder.Connect(controller_switch_sub->get_output_port(), - input_supervisor->get_input_port_controller_switch()); - builder.Connect(controller_error_sub->get_output_port(), - input_supervisor->get_input_port_controller_error()); - builder.Connect(input_supervisor->get_output_port_status(), - input_supervisor_status_pub->get_input_port()); - builder.Connect(cassie_out_receiver->get_output_port(), - input_supervisor->get_input_port_cassie()); - builder.Connect(state_receiver->get_output_port(0), - safety_controller->get_input_port_output()); - builder.Connect(config_receiver->get_output_port(0), - safety_controller->get_input_port_config()); - builder.Connect(safety_controller->get_output_port(0), - input_supervisor->get_input_port_safety_controller()); - builder.Connect(input_supervisor->get_output_port_failure(), - controller_error_pub->get_input_port()); - - auto owned_diagram = builder.Build(); - owned_diagram->set_name("franka_dispatcher_in"); - - systems::LcmDrivenLoop loop( - &drake_lcm, std::move(diagram), state_receiver, FLAGS_channel, true); - - auto msg = dairlib::lcmt_pd_config(); - msg.timestamp = 0; - msg.num_joints = 10; - msg.joint_names = {"hip_roll_left_motor", "hip_roll_right_motor", - "hip_yaw_left_motor", "hip_yaw_right_motor", - "hip_pitch_left_motor", "hip_pitch_right_motor", - "knee_left_motor", "knee_right_motor", - "toe_left_motor", "toe_right_motor"}; - msg.desired_position = {-0.01, .01, 0, 0, 0.55, 0.55, -1.7, -1.7, -1.8, -1.8}; - msg.desired_velocity = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0}; - msg.kp = {50, 50, 50, 50, 50, 50, 50, 50, 20, 20}; - msg.kd = {5, 5, 5, 5, 5, 5, 5, 5, 5, 5}; - config_receiver->get_input_port().FixValue( - &(loop.get_diagram()->GetMutableSubsystemContext( - *config_receiver, &loop.get_diagram_mutable_context())), - msg); - - loop.Simulate(); - - return 0; -} -} // namespace dairlib - -int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/franka/franka_dispatcher_out.cc b/examples/franka/franka_dispatcher_out.cc deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index 664de92488..02df20d3b8 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -7,33 +7,49 @@ #include #include +#include +#include +#include #include +#include +#include +#include +#include +#include +#include +#include #include +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "franka_msgs/FrankaState.h" #include "ros/ros.h" #include "sensor_msgs/JointState.h" #include "std_msgs/Float64MultiArray.h" -#include "systems/ros/c3_ros_conversions.h" +#include "systems/robot_lcm_systems.h" +#include "systems/ros/franka_ros_lcm_conversions.h" +#include "systems/ros/parameters/franka_ros_channels.h" #include "systems/ros/ros_publisher_system.h" #include "systems/ros/ros_subscriber_system.h" #include "systems/system_utils.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" - +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; +using dairlib::systems::LcmToRosTimestampedVector; +using dairlib::systems::RobotInputReceiver; +using dairlib::systems::RobotOutputSender; using dairlib::systems::RosPublisherSystem; using dairlib::systems::RosSubscriberSystem; -using dairlib::systems::ROSToBallPositionLCM; -using dairlib::systems::ROSToC3LCM; -using dairlib::systems::ROSToRobotOutputLCM; +using dairlib::systems::RosToLcmObjectState; +using dairlib::systems::RosToLcmRobotState; +using dairlib::systems::SubvectorPassThrough; +using dairlib::systems::TimestampedVector; +// using dairlib::systems::ROSToRobotOutputLCM; // Shutdown ROS gracefully and then exit void SigintHandler(int sig) { @@ -44,7 +60,6 @@ void SigintHandler(int sig) { DEFINE_string(lcm_channels, "examples/franka/parameters/lcm_channels_simulation.yaml", "Filepath containing lcm channels"); - DEFINE_string(ros_channels, "systems/ros/parameters/franka_ros_channels.yaml", "Filepath containing ROS channels"); @@ -55,8 +70,10 @@ int DoMain(int argc, char* argv[]) { FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); - FrankaLcmChannels ros_channel_params = - drake::yaml::LoadYamlFile(FLAGS_ros_channels); + FrankaRosChannels ros_channel_params = + drake::yaml::LoadYamlFile(FLAGS_ros_channels); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); ros::init(argc, argv, "run_c3_ros_to_lcm"); ros::NodeHandle node_handle; @@ -66,7 +83,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant(0.0); - Parser parser(&plant, &scene_graph); + Parser parser(&plant); drake::multibody::ModelInstanceIndex franka_index = parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; @@ -87,7 +104,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(franka_joint_state_ros_subscriber->get_output_port(), ros_to_lcm_robot_state->get_input_port()); builder.Connect(ros_to_lcm_robot_state->get_output_port(), - robot_output_pub->get_input_port()); + robot_output_lcm_publisher->get_input_port()); /* -------------------------------------------------------------------------------------------*/ /// convert ball position estimate to lcm @@ -105,27 +122,26 @@ int DoMain(int argc, char* argv[]) { builder.Connect(tray_object_state_ros_subscriber->get_output_port(), ros_to_lcm_object_state->get_input_port()); builder.Connect(ros_to_lcm_object_state->get_output_port(), - ball_position_pub->get_input_port()); + tray_state_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ auto robot_input_lcm_subscriber = - builder->AddSystem(LcmSubscriberSystem::Make( + builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.osc_channel, &drake_lcm)); - auto robot_input_receiver = builder->AddSystem(plant); - auto robot_input_passthrough = builder->AddSystem( + auto robot_input_receiver = builder.AddSystem(plant); + auto robot_input_passthrough = builder.AddSystem( robot_input_receiver->get_output_port(0).size(), 0, plant.get_actuation_input_port().size()); auto robot_input_ros_publisher = builder.AddSystem( systems::RosPublisherSystem::Make( ros_channel_params.franka_input_channel, &node_handle, .001)); - auto lcm_to_ros_robot_input = - builder.AddSystem(7); + auto lcm_to_ros_robot_input = builder.AddSystem(7); // try making this kForced builder.Connect(robot_input_passthrough->get_output_port(), lcm_to_ros_robot_input->get_input_port()); builder.Connect(lcm_to_ros_robot_input->get_output_port(), - ros_publisher->get_input_port()); + robot_input_ros_publisher->get_input_port()); auto sys = builder.Build(); // DrawAndSaveDiagramGraph(*sys, diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 0e46bf1ad6..dcc22b9080 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -1,16 +1,24 @@ #include #include -#include #include +#include #include +#include +#include #include #include #include +#include +#include +#include +#include +#include #include #include #include +#include #include "common/eigen_utils.h" #include "common/find_resource.h" @@ -23,15 +31,6 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "drake/common/yaml/yaml_io.h" -#include "drake/geometry/meshcat_visualizer.h" -#include "drake/geometry/meshcat_visualizer_params.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" - namespace dairlib { using dairlib::systems::SubvectorPassThrough; @@ -68,7 +67,7 @@ int DoMain(int argc, char* argv[]) { // load urdf and sphere DiagramBuilder builder; double sim_dt = sim_params.dt; - double output_dt = sim_params.dt; + // double output_dt = sim_params.dt; auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); Parser parser(&plant); @@ -124,21 +123,21 @@ int DoMain(int argc, char* argv[]) { // plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( // {"paddle", paddle_geom_set}, {"table_support", table_support_set}); -// VectorXd rotor_inertias(plant.num_actuators()); -// rotor_inertias << 61, 61, 61, 61, 61, 61, 61; -// rotor_inertias *= 1e-6; -// VectorXd gear_ratios(plant.num_actuators()); -// gear_ratios << 25, 25, 25, 25, 25, 25, 25; -// std::vector motor_joint_names = { -// "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", -// "panda_motor5", "panda_motor6", "panda_motor7"}; -// for (int i = 0; i < rotor_inertias.size(); ++i) { -// auto& joint_actuator = plant.get_mutable_joint_actuator( -// drake::multibody::JointActuatorIndex(i)); -// joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); -// joint_actuator.set_default_gear_ratio(gear_ratios(i)); -// DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); -// } + // VectorXd rotor_inertias(plant.num_actuators()); + // rotor_inertias << 61, 61, 61, 61, 61, 61, 61; + // rotor_inertias *= 1e-6; + // VectorXd gear_ratios(plant.num_actuators()); + // gear_ratios << 25, 25, 25, 25, 25, 25, 25; + // std::vector motor_joint_names = { + // "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", + // "panda_motor5", "panda_motor6", "panda_motor7"}; + // for (int i = 0; i < rotor_inertias.size(); ++i) { + // auto& joint_actuator = plant.get_mutable_joint_actuator( + // drake::multibody::JointActuatorIndex(i)); + // joint_actuator.set_default_rotor_inertia(rotor_inertias(i)); + // joint_actuator.set_default_gear_ratio(gear_ratios(i)); + // DRAKE_DEMAND(motor_joint_names[i] == joint_actuator.name()); + // } plant.Finalize(); @@ -147,7 +146,7 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm drake_lcm; auto lcm = builder.AddSystem(&drake_lcm); - auto passthrough = AddActuationRecieverAndStateSenderLcm( + AddActuationRecieverAndStateSenderLcm( &builder, plant, lcm, lcm_channel_params.osc_channel, lcm_channel_params.franka_state_channel, sim_params.publish_rate, franka_index, sim_params.publish_efforts, sim_params.actuator_delay); diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h index aaf9aee651..38d47fdc1a 100644 --- a/examples/franka/parameters/franka_lcm_channels.h +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -7,6 +7,7 @@ struct FrankaLcmChannels { std::string franka_state_channel; std::string tray_state_channel; std::string box_state_channel; + std::string franka_input_channel; std::string osc_channel; std::string osc_debug_channel; std::string c3_actor_channel; @@ -18,6 +19,7 @@ struct FrankaLcmChannels { a->Visit(DRAKE_NVP(franka_state_channel)); a->Visit(DRAKE_NVP(tray_state_channel)); a->Visit(DRAKE_NVP(box_state_channel)); + a->Visit(DRAKE_NVP(franka_input_channel)); a->Visit(DRAKE_NVP(osc_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_actor_channel)); diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index 302b4f0c7d..2ccbee623d 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -1,6 +1,7 @@ franka_state_channel: FRANKA_STATE tray_state_channel: TRAY_STATE box_state_channel: BOX_STATE +franka_input_channel: FRANKA_INPUT osc_channel: FRANKA_INPUT osc_debug_channel: OSC_DEBUG_FRANKA diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index e7257b3576..4b2e85a8cc 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -1,6 +1,7 @@ franka_state_channel: FRANKA_STATE_SIMULATION tray_state_channel: TRAY_STATE_SIMULATION box_state_channel: BOX_STATE_SIMULATION +franka_input_channel: FRANKA_INPUT osc_channel: FRANKA_INPUT osc_debug_channel: OSC_DEBUG_FRANKA diff --git a/systems/ros/BUILD.bazel b/systems/ros/BUILD.bazel index 0b0ee03a7c..9bb91ed15e 100644 --- a/systems/ros/BUILD.bazel +++ b/systems/ros/BUILD.bazel @@ -1,4 +1,5 @@ # -*- python -*- +package(default_visibility = ["//visibility:public"]) cc_library( name = "ros_pubsub_systems", @@ -29,6 +30,14 @@ cc_library( ], ) +cc_library( + name = "franka_ros_channels", + hdrs = ["parameters/franka_ros_channels.h"], + deps = [ + "@drake//:drake_shared_library", + ], +) + cc_binary( name = "test_ros_publisher_system", srcs = ["test/test_ros_publisher_system.cc"], diff --git a/systems/ros/franka_ros_lcm_conversions.h b/systems/ros/franka_ros_lcm_conversions.h index 6dc31fbb00..9beec239ab 100644 --- a/systems/ros/franka_ros_lcm_conversions.h +++ b/systems/ros/franka_ros_lcm_conversions.h @@ -11,9 +11,10 @@ #include "drake/systems/framework/leaf_system.h" #include "drake/systems/lcm/lcm_interface_system.h" + #include "std_msgs/Float64MultiArray.h" #include "sensor_msgs/JointState.h" -//#include "dairlib/lcmt_c3.hpp" +#include "franka_msgs/FrankaState.h" #include "dairlib/lcmt_robot_output.hpp" #include "dairlib/lcmt_franka_state.hpp" #include "dairlib/lcmt_estimated_object_state.hpp" diff --git a/tools/workspace/ros/compile_ros_workspace.sh b/tools/workspace/ros/compile_ros_workspace.sh index 1bbf8a0b4c..3602b80430 100755 --- a/tools/workspace/ros/compile_ros_workspace.sh +++ b/tools/workspace/ros/compile_ros_workspace.sh @@ -10,7 +10,7 @@ cd $(dirname "$BASH_SOURCE") set -e -PACKAGES="roscpp rospy" +PACKAGES="roscpp rospy franka_msgs sensor_msgs" # You can add any published ros packages you need to this list. # Local ROS packages should be their own bazel local_repository @@ -55,4 +55,4 @@ catkin config \ catkin build -DPYTHON_EXECUTABLE=/usr/bin/python3 -cd $BASE_DIR \ No newline at end of file +cd $BASE_DIR From a63629544956f77597faedd186b8a4b64bdee410 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 31 Oct 2023 17:04:09 -0400 Subject: [PATCH 486/758] cleaning up franka_ros_lcm_bridge, for some reason RobotInputSubscriber isn't working for that system --- examples/franka/franka_ros_lcm_bridge.cc | 87 +++++++++++++----- .../franka/saved_trajectories/franka_defaults | Bin 479 -> 479 bytes systems/robot_lcm_systems.cc | 4 + systems/ros/franka_ros_lcm_conversions.cc | 2 + .../ros/parameters/franka_ros_channels.yaml | 2 +- systems/ros/ros_subscriber_system.h | 14 ++- systems/system_utils.cc | 2 +- 7 files changed, 86 insertions(+), 25 deletions(-) diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index 02df20d3b8..c9de06ebf2 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -33,6 +33,7 @@ #include "systems/ros/ros_subscriber_system.h" #include "systems/system_utils.h" +using drake::math::RigidTransform; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; @@ -58,7 +59,7 @@ void SigintHandler(int sig) { } DEFINE_string(lcm_channels, - "examples/franka/parameters/lcm_channels_simulation.yaml", + "examples/franka/parameters/lcm_channels_hardware.yaml", "Filepath containing lcm channels"); DEFINE_string(ros_channels, "systems/ros/parameters/franka_ros_channels.yaml", "Filepath containing ROS channels"); @@ -78,16 +79,20 @@ int DoMain(int argc, char* argv[]) { ros::init(argc, argv, "run_c3_ros_to_lcm"); ros::NodeHandle node_handle; - drake::lcm::DrakeLcm drake_lcm; + drake::lcm::DrakeLcm drake_lcm("udpm://239.255.76.67:7667?ttl=0"); DiagramBuilder builder; MultibodyPlant plant(0.0); Parser parser(&plant); - drake::multibody::ModelInstanceIndex franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); + plant.Finalize(); - /* -------------------------------------------------------------------------------------------*/ /// convert franka joint states to lcm auto franka_joint_state_ros_subscriber = builder.AddSystem(RosSubscriberSystem::Make( @@ -117,7 +122,7 @@ int DoMain(int argc, char* argv[]) { auto tray_state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, &drake_lcm, - {drake::systems::TriggerType::kPeriodic}, 0.005)); + {drake::systems::TriggerType::kForced})); /// connections builder.Connect(tray_object_state_ros_subscriber->get_output_port(), ros_to_lcm_object_state->get_input_port()); @@ -127,35 +132,75 @@ int DoMain(int argc, char* argv[]) { /* -------------------------------------------------------------------------------------------*/ auto robot_input_lcm_subscriber = builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.osc_channel, &drake_lcm)); + lcm_channel_params.franka_input_channel, &drake_lcm)); auto robot_input_receiver = builder.AddSystem(plant); - auto robot_input_passthrough = builder.AddSystem( - robot_input_receiver->get_output_port(0).size(), 0, - plant.get_actuation_input_port().size()); + auto lcm_to_ros_robot_input = builder.AddSystem(7); auto robot_input_ros_publisher = builder.AddSystem( systems::RosPublisherSystem::Make( - ros_channel_params.franka_input_channel, &node_handle, .001)); - auto lcm_to_ros_robot_input = builder.AddSystem(7); - // try making this kForced + ros_channel_params.franka_input_channel, &node_handle, + {drake::systems::TriggerType::kForced})); - builder.Connect(robot_input_passthrough->get_output_port(), + builder.Connect(robot_input_lcm_subscriber->get_output_port(), + robot_input_receiver->get_input_port()); + builder.Connect(robot_input_receiver->get_output_port(), lcm_to_ros_robot_input->get_input_port()); builder.Connect(lcm_to_ros_robot_input->get_output_port(), robot_input_ros_publisher->get_input_port()); - auto sys = builder.Build(); - // DrawAndSaveDiagramGraph(*sys, - // "examples/franka_trajectory_following/diagram_run_c3_ros_to_lcm"); + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_ros_lcm_bridge")); + const auto& diagram = *owned_diagram; + DrawAndSaveDiagramGraph(diagram); + drake::systems::Simulator simulator(std::move(owned_diagram)); + auto& diagram_context = simulator.get_mutable_context(); +// auto& robot_input_sub_context = robot_input_lcm_subscriber-> - Simulator simulator(*sys); - simulator.Initialize(); - simulator.set_target_realtime_rate(1.0); // figure out what the arguments to this mean ros::AsyncSpinner spinner(1); spinner.start(); signal(SIGINT, SigintHandler); - simulator.AdvanceTo(std::numeric_limits::infinity()); + + // Wait for the first message. + drake::log()->info("Waiting for first ROS message from Franka"); + int old_message_count = 0; + old_message_count = + franka_joint_state_ros_subscriber->WaitForMessage(old_message_count); + + // Initialize the context based on the first message. + const double t0 = franka_joint_state_ros_subscriber->message_time(); + diagram_context.SetTime(t0); + simulator.Initialize(); + + drake::log()->info("dispatcher_robot_out started"); + + while (true) { + old_message_count = + franka_joint_state_ros_subscriber->WaitForMessage(old_message_count); + const double time = franka_joint_state_ros_subscriber->message_time(); + + // Check if we are very far ahead or behind + // (likely due to a restart of the driving clock) + if (time > simulator.get_context().get_time() + 1.0 || + time < simulator.get_context().get_time()) { + std::cout << "Dispatcher time is " << simulator.get_context().get_time() + << ", but stepping to " << time << std::endl; + std::cout << "Difference is too large, resetting dispatcher time." + << std::endl; + simulator.get_mutable_context().SetTime(time); + simulator.Initialize(); + } + + simulator.AdvanceTo(time); + // Force-publish via the diagram + diagram.CalcForcedUnrestrictedUpdate(diagram_context, + &diagram_context.get_mutable_state()); + diagram.CalcForcedDiscreteVariableUpdate(diagram_context, + &diagram_context.get_mutable_discrete_state()); + diagram.ForcedPublish(diagram_context); + } + + // simulator.AdvanceTo(std::numeric_limits::infinity()); return 0; } diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults index 59651e0bf4502ddf28fa1e36475a17b414d7b199..92e6539977d88ce766f84b7ad237e339cfe8a50e 100644 GIT binary patch delta 39 vcmcc5e4lxO%4B)Q%83i=C(mG1ndlM0!;_zsm6}`_qbJU-pQutfS%y(XStvCxB|bGREj76$zbL+>C^3rx2zc_7 JvVbBGJ^+t{6oUW& diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index da54bf60b9..91cbd6e00b 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -326,8 +326,12 @@ void RobotInputReceiver::CopyInputOut(const Context& context, const auto& input_msg = input->get_value(); VectorXd input_vector = VectorXd::Zero(num_actuators_); +// std::cout << "context time: " << context.get_time() << std::endl; +// std::cout << "time: " << input_msg.utime * 1e-6 << std::endl; + std::cout << "num_efforts: " << input_msg.num_efforts << std::endl; for (int i = 0; i < input_msg.num_efforts; i++) { +// std::cout << "effort: " << i << input_msg.efforts[i] << std::endl; int j = actuator_index_map_.at(input_msg.effort_names[i]); input_vector(j) = input_msg.efforts[i]; } diff --git a/systems/ros/franka_ros_lcm_conversions.cc b/systems/ros/franka_ros_lcm_conversions.cc index 99fd06c629..28d1b79e5b 100644 --- a/systems/ros/franka_ros_lcm_conversions.cc +++ b/systems/ros/franka_ros_lcm_conversions.cc @@ -24,7 +24,9 @@ void LcmToRosTimestampedVector::ConvertToROS(const drake::systems::Contextdata.clear(); +// std::cout << "time: " << input->get_timestamp() << std::endl; for (int i = 0; i < vector_size_; i++){ +// std::cout << "value: " << i << " " << input->GetAtIndex(i) << std::endl; if (std::isnan(input->GetAtIndex(i))){ output->data.push_back(0); } diff --git a/systems/ros/parameters/franka_ros_channels.yaml b/systems/ros/parameters/franka_ros_channels.yaml index ff818f635f..0ee6a147c7 100644 --- a/systems/ros/parameters/franka_ros_channels.yaml +++ b/systems/ros/parameters/franka_ros_channels.yaml @@ -1,4 +1,4 @@ -franka_state_channel: /franka/franka_robot_state +franka_state_channel: /franka/joint_states tray_state_channel: /franka/tray_object_state box_state_channel: /franka/box_object_state franka_input_channel: /franka/franka_input diff --git a/systems/ros/ros_subscriber_system.h b/systems/ros/ros_subscriber_system.h index fb05650af1..9e37985919 100644 --- a/systems/ros/ros_subscriber_system.h +++ b/systems/ros/ros_subscriber_system.h @@ -1,15 +1,16 @@ #pragma once +#include #include #include #include #include +#include "ros/ros.h" + #include "drake/common/drake_copyable.h" #include "drake/systems/framework/leaf_system.h" -#include "ros/ros.h" - namespace dairlib { namespace systems { @@ -82,12 +83,16 @@ class RosSubscriberSystem : public drake::systems::LeafSystem { message_state_index); set_name(make_name(topic_)); + start_ = std::chrono::steady_clock::now(); + time_ = 0; } ~RosSubscriberSystem() override{}; const std::string& get_topic_name() const { return topic_; } + double message_time() const { return time_; } + /// Returns the default name for a system that publishes @p topic. static std::string make_name(const std::string& topic) { return "RosSubscriberSystem(" + topic + ")"; @@ -187,6 +192,8 @@ class RosSubscriberSystem : public drake::systems::LeafSystem { received_message_ = message; received_message_count_++; received_message_condition_variable_.notify_all(); + time_ = + (duration_cast(std::chrono::steady_clock::now() - start_)).count()/1.0e6; } // The topic on which to receive ROS messages. @@ -198,6 +205,9 @@ class RosSubscriberSystem : public drake::systems::LeafSystem { // A condition variable that's signaled every time the handler is called. mutable std::condition_variable received_message_condition_variable_; + mutable double time_; + mutable std::chrono::time_point start_; + // The most recently received ROS message. RosMessage received_message_{}; diff --git a/systems/system_utils.cc b/systems/system_utils.cc index 478760833b..675bb53e13 100644 --- a/systems/system_utils.cc +++ b/systems/system_utils.cc @@ -21,7 +21,7 @@ void DrawAndSaveDiagramGraph(const drake::systems::Diagram& diagram, // The command is `dot -Tps input_file -o output_file` std::regex r(" "); path = std::regex_replace(path, r, "\\ "); - std::string cmd = "dot -Tps " + path + " -o " + path + ".ps"; + std::string cmd = "dot -Tsvg " + path + " -o " + path + ".svg"; (void) std::system(cmd.c_str()); // Remove Graphviz string file From de151f9fc46385d97508c192f79e8c333e1aebad Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Nov 2023 15:01:23 -0400 Subject: [PATCH 487/758] adding option to disable gravity compensation in osc as it may be added by Franka anyway --- examples/franka/franka_osc_controller.cc | 15 ++++++++----- .../parameters/franka_osc_controller_params.h | 2 ++ .../franka_osc_controller_params.yaml | 1 + .../osc/operational_space_control.cc | 22 ++++++++++--------- .../osc/operational_space_control.h | 10 +++++++++ 5 files changed, 35 insertions(+), 15 deletions(-) diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index b788c8bed7..c324a6c17d 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -4,8 +4,8 @@ #include #include "common/eigen_utils.h" -#include "examples/franka/parameters/franka_osc_controller_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_osc_controller_params.h" #include "examples/franka/systems/end_effector_orientation.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" @@ -52,7 +52,8 @@ using systems::controllers::TransTaskSpaceTrackingData; DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", "Filepath containing qp settings"); -DEFINE_string(controller_parameters, "examples/franka/parameters/franka_osc_controller_params.yaml", +DEFINE_string(controller_parameters, + "examples/franka/parameters/franka_osc_controller_params.yaml", "Controller settings such as channels. Attempting to minimize " "number of gflags"); DEFINE_string(lcm_channels, @@ -71,8 +72,7 @@ int DoMain(int argc, char* argv[]) { FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_controller_parameters), - {}, {}, yaml_options); + FindResourceOrThrow(FLAGS_controller_parameters), {}, {}, yaml_options); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(FLAGS_osqp_settings)) @@ -87,7 +87,8 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); - Vector3d tool_attachment_frame = StdVectorToVectorXd(controller_params.tool_attachment_frame); + Vector3d tool_attachment_frame = + StdVectorToVectorXd(controller_params.tool_attachment_frame); RigidTransform T_EE_W = RigidTransform( drake::math::RotationMatrix(), tool_attachment_frame); @@ -151,6 +152,10 @@ int DoMain(int argc, char* argv[]) { osc->SetInputCostWeights(gains.W_input_regularization); osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); + if (!controller_params.include_gravity_compensation) { + osc->DisableGravityCompensation(); + } + auto end_effector_position_tracking_data = std::make_unique( "end_effector_target", controller_params.K_p_end_effector, diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index 7192121c55..b4983330a4 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -12,6 +12,7 @@ struct FrankaControllerParams : OSCGains { std::vector tool_attachment_frame; double end_effector_acceleration; bool track_end_effector_orientation; + bool include_gravity_compensation; std::vector neutral_position; double x_scale; @@ -47,6 +48,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(end_effector_name)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(track_end_effector_orientation)); + a->Visit(DRAKE_NVP(include_gravity_compensation)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 8c6dee9f55..61112cc201 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,6 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 5.0 track_end_effector_orientation: false +include_gravity_compensation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index d17e03bebd..82374ac927 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -313,7 +313,7 @@ void OperationalSpaceControl::Build() { n_c_ = kSpaceDim * all_contacts_.size(); n_ee_ = 0; - for (auto& force_tracking_data : *force_tracking_data_vec_){ + for (auto& force_tracking_data : *force_tracking_data_vec_) { n_ee_ += force_tracking_data->GetYDim(); } @@ -457,14 +457,14 @@ void OperationalSpaceControl::Build() { .get(); } // 3. external force cost -// for (auto& force_tracking_data: *force_tracking_data_vec_){ -// DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); -// lambda_ee_cost_ = -// prog_ -// ->AddQuadraticCost(, VectorXd::Zero(n_h_), lambda_h_) -// .evaluator() -// .get(); -// } + // for (auto& force_tracking_data: *force_tracking_data_vec_){ + // DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); + // lambda_ee_cost_ = + // prog_ + // ->AddQuadraticCost(, VectorXd::Zero(n_h_), lambda_h_) + // .evaluator() + // .get(); + // } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { soft_constraint_cost_ = @@ -590,7 +590,9 @@ VectorXd OperationalSpaceControl::SolveQp( drake::multibody::MultibodyForces f_app(plant_wo_spr_); plant_wo_spr_.CalcForceElementsContribution(*context_wo_spr_, &f_app); VectorXd grav = plant_wo_spr_.CalcGravityGeneralizedForces(*context_wo_spr_); - bias = bias - grav; + if (with_gravity_compensation_) { + bias = bias - grav; + } // TODO (yangwill): Characterize damping in cassie model // std::cout << f_app.generalized_forces().transpose() << std::endl; // bias = bias - f_app.generalized_forces(); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 6071db4bac..0632ca605e 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -224,6 +224,14 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { */ void SetJointLimitWeight(const double w) { w_joint_limit_ = w; } + void DisableGravityCompensation() { + with_gravity_compensation_ = false; + } + + bool HasGravityCompensation(){ + return with_gravity_compensation_; + } + // Constraint methods void DisableAcutationConstraint() { with_input_constraints_ = false; } void SetContactFriction(double mu) { mu_ = mu; } @@ -386,6 +394,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // floating base model flag bool is_quaternion_; + bool with_gravity_compensation_ = true; + // Solver std::unique_ptr solver_; drake::solvers::SolverOptions solver_options_ = From 1834f794f699008e59c711cfce0cafac3563a4bf Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 1 Nov 2023 15:29:33 -0400 Subject: [PATCH 488/758] adding system that cancels out gravity compensation --- examples/franka/franka_osc_controller.cc | 36 +++++++++---- examples/franka/franka_sim.cc | 2 +- .../parameters/franka_osc_controller_params.h | 4 +- .../franka_osc_controller_params.yaml | 2 +- .../parameters/lcm_channels_hardware.yaml | 2 +- .../parameters/lcm_channels_simulation.yaml | 2 +- .../franka/saved_trajectories/franka_defaults | Bin 479 -> 479 bytes systems/controllers/BUILD.bazel | 15 ++++++ systems/controllers/gravity_compensator.cc | 45 ++++++++++++++++ systems/controllers/gravity_compensator.h | 49 ++++++++++++++++++ 10 files changed, 142 insertions(+), 15 deletions(-) create mode 100644 systems/controllers/gravity_compensator.cc create mode 100644 systems/controllers/gravity_compensator.h diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index c324a6c17d..6d855579e7 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -18,6 +18,7 @@ #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" +#include "systems/controllers/gravity_compensator.h" #include "systems/trajectory_optimization/lcm_trajectory_systems.h" #include "drake/common/find_resource.h" @@ -119,11 +120,18 @@ int DoMain(int argc, char* argv[]) { auto end_effector_orientation_receiver = builder.AddSystem( "end_effector_orientation_target"); - auto command_pub = + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_input_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto osc_command_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.osc_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); - auto command_sender = builder.AddSystem(plant); + auto franka_command_sender = + builder.AddSystem(plant); + auto osc_command_sender = + builder.AddSystem(plant); auto end_effector_trajectory = builder.AddSystem(plant, plant_context.get()); @@ -152,10 +160,6 @@ int DoMain(int argc, char* argv[]) { osc->SetInputCostWeights(gains.W_input_regularization); osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); - if (!controller_params.include_gravity_compensation) { - osc->DisableGravityCompensation(); - } - auto end_effector_position_tracking_data = std::make_unique( "end_effector_target", controller_params.K_p_end_effector, @@ -210,6 +214,18 @@ int DoMain(int argc, char* argv[]) { osc->Build(); + if (controller_params.cancel_gravity_compensation) { + auto gravity_compensator = + builder.AddSystem(plant, *plant_context); + builder.Connect(osc->get_output_port_osc_command(), + gravity_compensator->get_input_port()); + builder.Connect(gravity_compensator->get_output_port(), + franka_command_sender->get_input_port()); + } else { + builder.Connect(osc->get_output_port_osc_command(), + franka_command_sender->get_input_port(0)); + } + builder.Connect(state_receiver->get_output_port(0), end_effector_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), @@ -218,10 +234,12 @@ int DoMain(int argc, char* argv[]) { end_effector_orientation_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_orientation_trajectory->get_input_port_radio()); - builder.Connect(command_sender->get_output_port(0), - command_pub->get_input_port()); + builder.Connect(franka_command_sender->get_output_port(), + franka_command_pub->get_input_port()); + builder.Connect(osc_command_sender->get_output_port(), + osc_command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_command(), - command_sender->get_input_port(0)); + osc_command_sender->get_input_port(0)); builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index dcc22b9080..05c63ebb13 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -147,7 +147,7 @@ int DoMain(int argc, char* argv[]) { auto lcm = builder.AddSystem(&drake_lcm); AddActuationRecieverAndStateSenderLcm( - &builder, plant, lcm, lcm_channel_params.osc_channel, + &builder, plant, lcm, lcm_channel_params.franka_input_channel, lcm_channel_params.franka_state_channel, sim_params.publish_rate, franka_index, sim_params.publish_efforts, sim_params.actuator_delay); auto tray_state_sender = diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index b4983330a4..eafbfa434b 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -12,7 +12,7 @@ struct FrankaControllerParams : OSCGains { std::vector tool_attachment_frame; double end_effector_acceleration; bool track_end_effector_orientation; - bool include_gravity_compensation; + bool cancel_gravity_compensation; std::vector neutral_position; double x_scale; @@ -48,7 +48,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(end_effector_name)); a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(track_end_effector_orientation)); - a->Visit(DRAKE_NVP(include_gravity_compensation)); + a->Visit(DRAKE_NVP(cancel_gravity_compensation)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 61112cc201..2ad6160877 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 5.0 track_end_effector_orientation: false -include_gravity_compensation: false +cancel_gravity_compensation: true # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index 2ccbee623d..f8c3c78756 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -3,7 +3,7 @@ tray_state_channel: TRAY_STATE box_state_channel: BOX_STATE franka_input_channel: FRANKA_INPUT -osc_channel: FRANKA_INPUT +osc_channel: OSC_FRANKA osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index 4b2e85a8cc..19554c767b 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -3,7 +3,7 @@ tray_state_channel: TRAY_STATE_SIMULATION box_state_channel: BOX_STATE_SIMULATION franka_input_channel: FRANKA_INPUT -osc_channel: FRANKA_INPUT +osc_channel: OSC_FRANKA osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults index 92e6539977d88ce766f84b7ad237e339cfe8a50e..59651e0bf4502ddf28fa1e36475a17b414d7b199 100644 GIT binary patch delta 60 zcmcc5e4lxO%H(~Fij!>_qbJU-pQutfS%y(XStvCxB|bGREj76$zbL+>C^3rx2zc_7 JvVbBGJ^+t{6oUW& delta 39 vcmcc5e4lxO%4B)Q%83i=C(mG1ndlM0!;_zsm6}`& plant, + drake::systems::Context& context) + : plant_(plant), context_(context){ + + num_actuators_ = plant_.num_actuators(); + this->DeclareVectorInputPort("u, t", + TimestampedVector(num_actuators_)); + this->DeclareVectorOutputPort("u, t", + TimestampedVector(num_actuators_), + &GravityCompensationRemover::CancelGravityCompensation); +} + +void GravityCompensationRemover::CancelGravityCompensation(const drake::systems::Context& context, + TimestampedVector* output) const { + const TimestampedVector* tau = + (TimestampedVector*)this->EvalVectorInput(context, 0); + VectorXd tau_g = plant_.CalcGravityGeneralizedForces(context_); + + VectorXd compensated_tau = VectorXd::Zero(num_actuators_); + for (int i = 0; i < num_actuators_; i++){ + compensated_tau(i) = tau->GetAtIndex(i) + tau_g(i); + } + + output->SetDataVector(compensated_tau); + output->set_timestamp(tau->get_timestamp()); +} + +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/controllers/gravity_compensator.h b/systems/controllers/gravity_compensator.h new file mode 100644 index 0000000000..9d7bcb8cf1 --- /dev/null +++ b/systems/controllers/gravity_compensator.h @@ -0,0 +1,49 @@ +#pragma once + +#include +#include +#include + + +#include +#include + +#include "systems/framework/output_vector.h" +#include "drake/systems/framework/leaf_system.h" + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/context.h" + +#include +#include +#include + +using drake::multibody::MultibodyPlant; +using drake::systems::Context; +using drake::systems::LeafSystem; + +using Eigen::MatrixXd; +using Eigen::VectorXd; + +namespace dairlib { +namespace systems { + +class GravityCompensationRemover : public LeafSystem { + public: + GravityCompensationRemover( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context& context); + + private: + // adds gravity compensation to output + void CancelGravityCompensation(const drake::systems::Context& context, + TimestampedVector* output) const; + + // constructor variables + const MultibodyPlant& plant_; + drake::systems::Context& context_; + int num_actuators_; +}; + +} // namespace systems +} // namespace dairlib \ No newline at end of file From f7d9bf1185443badff16fb17e8e878f30652ed5a Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 2 Nov 2023 10:13:25 -0400 Subject: [PATCH 489/758] changes to successfully run experiments on franka --- .../analysis/franka_plotting_utils.py | 6 +- .../pydairlib/analysis/log_plotter_franka.py | 50 +++--- .../plot_configs/franka_translation_plot.yaml | 2 +- examples/Cassie/cassie_xbox_remote.py | 4 +- examples/franka/BUILD.bazel | 24 +++ examples/franka/franka_lcm_ros_bridge.cc | 146 ++++++++++++++++++ examples/franka/franka_osc_controller.cc | 19 +-- examples/franka/franka_ros_lcm_bridge.cc | 46 +++--- .../franka/parameters/franka_lcm_channels.h | 2 + .../parameters/franka_osc_controller_params.h | 26 ++-- .../franka_osc_controller_params.yaml | 43 +++--- .../franka/parameters/franka_sim_params.yaml | 4 +- .../parameters/lcm_channels_hardware.yaml | 1 + .../parameters/lcm_channels_simulation.yaml | 1 + .../franka/systems/end_effector_trajectory.cc | 4 +- systems/robot_lcm_systems.cc | 5 +- 16 files changed, 271 insertions(+), 112 deletions(-) create mode 100644 examples/franka/franka_lcm_ros_bridge.cc diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index 460482d6f1..64b56b353b 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -15,13 +15,13 @@ franka_urdf = "examples/franka/urdf/franka_no_collision.urdf" tray_model = "examples/franka/urdf/tray.sdf" franka_default_channels = \ - {'FRANKA_OUTPUT': dairlib.lcmt_robot_output, - 'TRAY_OUTPUT': dairlib.lcmt_robot_output, + {'FRANKA_STATE': dairlib.lcmt_robot_output, + # 'TRAY_STATE': dairlib.lcmt_robot_output, 'FRANKA_INPUT': dairlib.lcmt_robot_input, 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, - 'CASSIE_VIRTUAL_RADIO': dairlib.lcmt_radio_out, + 'RADIO': dairlib.lcmt_radio_out, 'CONTACT_RESULTS': drake.lcmt_contact_results_for_viz} diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 532f8f1132..868f838761 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -89,31 +89,31 @@ def main(): franka_context, ['paddle'], {'paddle': np.zeros(3)}, {'paddle': [0, 1, 2]}) - q = np.load( - '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_q.npy') - v = np.load( - '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_v.npy') - t = np.load( - '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_t.npy') - pos = mbp_plots.make_point_positions_from_q(q, - franka_plant, franka_context, - franka_plant.GetBodyByName( - 'paddle').body_frame(), - np.zeros(3)) - vel = mbp_plots.make_point_velocities_from_qv(q, - v, - franka_plant, franka_context, - franka_plant.GetBodyByName( - 'paddle').body_frame(), - np.zeros(3)) - ps = plot_styler.PlotStyler() - ps.plot(t, pos, title='leon_experiment_positions') - ps = plot_styler.PlotStyler() - ps.plot(t, vel, title='leon_experiment_velocities') - ps = plot_styler.PlotStyler() - - ps.plot(t[1:], 1 / np.diff(t) * np.diff(vel, axis=0)[:, 1], - title='leon_experiment_accelerations', ylim=[-10, 10]) + # q = np.load( + # '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_q.npy') + # v = np.load( + # '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_v.npy') + # t = np.load( + # '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_t.npy') + # pos = mbp_plots.make_point_positions_from_q(q, + # franka_plant, franka_context, + # franka_plant.GetBodyByName( + # 'paddle').body_frame(), + # np.zeros(3)) + # vel = mbp_plots.make_point_velocities_from_qv(q, + # v, + # franka_plant, franka_context, + # franka_plant.GetBodyByName( + # 'paddle').body_frame(), + # np.zeros(3)) + # ps = plot_styler.PlotStyler() + # ps.plot(t, pos, title='leon_experiment_positions') + # ps = plot_styler.PlotStyler() + # ps.plot(t, vel, title='leon_experiment_velocities') + # ps = plot_styler.PlotStyler() + + # ps.plot(t[1:], 1 / np.diff(t) * np.diff(vel, axis=0)[:, 1], + # title='leon_experiment_accelerations', ylim=[-10, 10]) ''' Plot Efforts ''' if plot_config.plot_measured_efforts: diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 3a6cda6871..8152ebf266 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -1,5 +1,5 @@ # LCM channels to read data from -channel_x: "FRANKA_OUTPUT" +channel_x: "FRANKA_STATE" channel_u: "FRANKA_INPUT" channel_osc: "OSC_DEBUG_FRANKA" use_default_styling: false diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 82e0197cbf..cabf275888 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -58,6 +58,7 @@ def main(): i = 0 latching_switch_a = 1 latching_switch_b = 1 + print("Teleop Status: " + str(latching_switch_a)) while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands @@ -74,6 +75,7 @@ def main(): if event.type == pygame.JOYBUTTONDOWN: if event.button == 0: latching_switch_a = not latching_switch_a + print("Teleop Status: " + str(latching_switch_a)) if event.button == 1: latching_switch_b = not latching_switch_b @@ -93,7 +95,7 @@ def main(): # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) - publisher.publish("CASSIE_VIRTUAL_RADIO", radio_msg.encode()) + publisher.publish("RADIO", radio_msg.encode()) # Limit to 20 frames per second clock.tick(100) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index de1a23cb2f..bc88a4bf1d 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -129,6 +129,30 @@ cc_binary( tags = ["ros"], ) +cc_binary( + name = "franka_lcm_ros_bridge", + srcs = ["franka_lcm_ros_bridge.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_sim_params", + ":franka_lcm_channels", + "//common", + "//systems:robot_lcm_systems", + "//systems/ros:ros_pubsub_systems", + "//systems/ros:franka_ros_channels", + "//systems/ros:franka_ros_lcm_conversions", + "//systems/framework:lcm_driven_loop", + "//systems:system_utils", + "@drake//:drake_shared_library", + "@ros", + "@gflags", + ], + tags = ["ros"], +) + cc_library( name = "franka_lcm_channels", hdrs = ["parameters/franka_lcm_channels.h"], diff --git a/examples/franka/franka_lcm_ros_bridge.cc b/examples/franka/franka_lcm_ros_bridge.cc new file mode 100644 index 0000000000..48778239b5 --- /dev/null +++ b/examples/franka/franka_lcm_ros_bridge.cc @@ -0,0 +1,146 @@ +#define ROS + +#ifdef ROS + +#include + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "franka_msgs/FrankaState.h" +#include "ros/ros.h" +#include "sensor_msgs/JointState.h" +#include "std_msgs/Float64MultiArray.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/ros/franka_ros_lcm_conversions.h" +#include "systems/ros/parameters/franka_ros_channels.h" +#include "systems/ros/ros_publisher_system.h" +#include "systems/ros/ros_subscriber_system.h" +#include "systems/system_utils.h" + +using drake::math::RigidTransform; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using dairlib::systems::LcmToRosTimestampedVector; +using dairlib::systems::RobotInputReceiver; +using dairlib::systems::RobotOutputSender; +using dairlib::systems::RosPublisherSystem; +using dairlib::systems::RosSubscriberSystem; +using dairlib::systems::RosToLcmObjectState; +using dairlib::systems::RosToLcmRobotState; +using dairlib::systems::SubvectorPassThrough; +using dairlib::systems::TimestampedVector; +// using dairlib::systems::ROSToRobotOutputLCM; + +// Shutdown ROS gracefully and then exit +void SigintHandler(int sig) { + ros::shutdown(); + exit(sig); +} + +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_hardware.yaml", + "Filepath containing lcm channels"); +DEFINE_string(ros_channels, "systems/ros/parameters/franka_ros_channels.yaml", + "Filepath containing ROS channels"); + +namespace dairlib { + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + FrankaRosChannels ros_channel_params = + drake::yaml::LoadYamlFile(FLAGS_ros_channels); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + + ros::init(argc, argv, "run_lcm_to_ros"); + ros::NodeHandle node_handle; + + drake::lcm::DrakeLcm drake_lcm("udpm://239.255.76.67:7667?ttl=0"); + DiagramBuilder builder; + + MultibodyPlant plant(0.0); + + Parser parser(&plant); + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); + plant.Finalize(); + + /* -------------------------------------------------------------------------------------------*/ +// auto robot_input_lcm_subscriber = +// builder.AddSystem(LcmSubscriberSystem::Make( +// lcm_channel_params.franka_input_channel, &drake_lcm)); +// auto robot_input_lcm_echo = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.franka_input_echo, &drake_lcm, +// {drake::systems::TriggerType::kForced})); + auto robot_input_receiver = builder.AddSystem(plant); + auto lcm_to_ros_robot_input = builder.AddSystem(7); + auto robot_input_ros_publisher = builder.AddSystem( + systems::RosPublisherSystem::Make( + ros_channel_params.franka_input_channel, &node_handle, + {drake::systems::TriggerType::kForced})); + +// builder.Connect(robot_input_lcm_subscriber->get_output_port(), +// robot_input_receiver->get_input_port()); +// builder.Connect(robot_input_lcm_subscriber->get_output_port(), +// robot_input_lcm_echo->get_input_port()); + builder.Connect(robot_input_receiver->get_output_port(), + lcm_to_ros_robot_input->get_input_port()); + builder.Connect(lcm_to_ros_robot_input->get_output_port(), + robot_input_ros_publisher->get_input_port()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_lcm_ros_bridge")); + const auto& diagram = *owned_diagram; + DrawAndSaveDiagramGraph(diagram); +// drake::systems::Simulator simulator(std::move(owned_diagram)); +// auto& diagram_context = simulator.get_mutable_context(); + + // figure out what the arguments to this mean + ros::AsyncSpinner spinner(1); + spinner.start(); + signal(SIGINT, SigintHandler); + + systems::LcmDrivenLoop loop( + &drake_lcm, std::move(owned_diagram), robot_input_receiver, + lcm_channel_params.franka_input_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } + +#endif \ No newline at end of file diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 6d855579e7..09f2ddedad 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -178,20 +178,11 @@ int DoMain(int argc, char* argv[]) { end_effector_position_tracking_data_for_rel->AddPointToTrack( controller_params.end_effector_name); auto mid_link_position_tracking_data_for_rel = - std::make_unique( - "mid_link", controller_params.K_p_mid_link, + std::make_unique( + "panda_joint3_target", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant); - mid_link_position_tracking_data_for_rel->AddPointToTrack("panda_link4"); - auto wrist_relative_tracking_data = - std::make_unique( - "wrist_down_target", controller_params.K_p_mid_link, - controller_params.K_d_mid_link, controller_params.W_mid_link, plant, - plant, mid_link_position_tracking_data_for_rel.get(), - end_effector_position_tracking_data_for_rel.get()); - Eigen::Vector3d wrist_down_target = Eigen::Vector3d::Zero(); - wrist_down_target(1) = 0.0; - wrist_down_target(2) = 0.0; + mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint3", "panda_joint3dot"); auto end_effector_orientation_tracking_data = std::make_unique( @@ -205,8 +196,8 @@ int DoMain(int argc, char* argv[]) { orientation_target(0) = 1; osc->AddTrackingData(std::move(end_effector_position_tracking_data)); - osc->AddConstTrackingData(std::move(wrist_relative_tracking_data), - wrist_down_target); + osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), + 1.4 * VectorXd::Ones(1)); osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); osc->SetContactFriction(controller_params.mu); diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index c9de06ebf2..be5e1a73b4 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -76,7 +76,7 @@ int DoMain(int argc, char* argv[]) { FrankaSimParams sim_params = drake::yaml::LoadYamlFile( "examples/franka/parameters/franka_sim_params.yaml"); - ros::init(argc, argv, "run_c3_ros_to_lcm"); + ros::init(argc, argv, "run_ros_to_lcm"); ros::NodeHandle node_handle; drake::lcm::DrakeLcm drake_lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -130,22 +130,28 @@ int DoMain(int argc, char* argv[]) { tray_state_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ - auto robot_input_lcm_subscriber = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.franka_input_channel, &drake_lcm)); - auto robot_input_receiver = builder.AddSystem(plant); - auto lcm_to_ros_robot_input = builder.AddSystem(7); - auto robot_input_ros_publisher = builder.AddSystem( - systems::RosPublisherSystem::Make( - ros_channel_params.franka_input_channel, &node_handle, - {drake::systems::TriggerType::kForced})); - - builder.Connect(robot_input_lcm_subscriber->get_output_port(), - robot_input_receiver->get_input_port()); - builder.Connect(robot_input_receiver->get_output_port(), - lcm_to_ros_robot_input->get_input_port()); - builder.Connect(lcm_to_ros_robot_input->get_output_port(), - robot_input_ros_publisher->get_input_port()); +// auto robot_input_lcm_subscriber = +// builder.AddSystem(LcmSubscriberSystem::Make( +// lcm_channel_params.franka_input_channel, &drake_lcm)); +// auto robot_input_lcm_echo = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.franka_input_echo, &drake_lcm, +// {drake::systems::TriggerType::kForced})); +// auto robot_input_receiver = builder.AddSystem(plant); +// auto lcm_to_ros_robot_input = builder.AddSystem(7); +// auto robot_input_ros_publisher = builder.AddSystem( +// systems::RosPublisherSystem::Make( +// ros_channel_params.franka_input_channel, &node_handle, +// {drake::systems::TriggerType::kForced})); +// +// builder.Connect(robot_input_lcm_subscriber->get_output_port(), +// robot_input_receiver->get_input_port()); +// builder.Connect(robot_input_lcm_subscriber->get_output_port(), +// robot_input_lcm_echo->get_input_port()); +// builder.Connect(robot_input_receiver->get_output_port(), +// lcm_to_ros_robot_input->get_input_port()); +// builder.Connect(lcm_to_ros_robot_input->get_output_port(), +// robot_input_ros_publisher->get_input_port()); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_ros_lcm_bridge")); @@ -153,8 +159,6 @@ int DoMain(int argc, char* argv[]) { DrawAndSaveDiagramGraph(diagram); drake::systems::Simulator simulator(std::move(owned_diagram)); auto& diagram_context = simulator.get_mutable_context(); -// auto& robot_input_sub_context = robot_input_lcm_subscriber-> - // figure out what the arguments to this mean ros::AsyncSpinner spinner(1); @@ -172,13 +176,14 @@ int DoMain(int argc, char* argv[]) { diagram_context.SetTime(t0); simulator.Initialize(); - drake::log()->info("dispatcher_robot_out started"); + drake::log()->info("franka ros-lcm bridge started"); while (true) { old_message_count = franka_joint_state_ros_subscriber->WaitForMessage(old_message_count); const double time = franka_joint_state_ros_subscriber->message_time(); + // Check if we are very far ahead or behind // (likely due to a restart of the driving clock) if (time > simulator.get_context().get_time() + 1.0 || @@ -192,6 +197,7 @@ int DoMain(int argc, char* argv[]) { } simulator.AdvanceTo(time); + // Force-publish via the diagram diagram.CalcForcedUnrestrictedUpdate(diagram_context, &diagram_context.get_mutable_state()); diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h index 38d47fdc1a..c9c591c2a3 100644 --- a/examples/franka/parameters/franka_lcm_channels.h +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -8,6 +8,7 @@ struct FrankaLcmChannels { std::string tray_state_channel; std::string box_state_channel; std::string franka_input_channel; + std::string franka_input_echo; std::string osc_channel; std::string osc_debug_channel; std::string c3_actor_channel; @@ -20,6 +21,7 @@ struct FrankaLcmChannels { a->Visit(DRAKE_NVP(tray_state_channel)); a->Visit(DRAKE_NVP(box_state_channel)); a->Visit(DRAKE_NVP(franka_input_channel)); + a->Visit(DRAKE_NVP(franka_input_echo)); a->Visit(DRAKE_NVP(osc_channel)); a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_actor_channel)); diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index eafbfa434b..932fea7053 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -19,12 +19,13 @@ struct FrankaControllerParams : OSCGains { double y_scale; double z_scale; + double w_elbow; + double elbow_kp; + double elbow_kd; + std::vector EndEffectorW; std::vector EndEffectorKp; std::vector EndEffectorKd; - std::vector MidLinkW; - std::vector MidLinkKp; - std::vector MidLinkKd; std::vector EndEffectorRotW; std::vector EndEffectorRotKp; std::vector EndEffectorRotKd; @@ -52,13 +53,12 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); - a->Visit(DRAKE_NVP(MidLinkW)); - a->Visit(DRAKE_NVP(MidLinkKp)); - a->Visit(DRAKE_NVP(MidLinkKd)); a->Visit(DRAKE_NVP(EndEffectorRotW)); a->Visit(DRAKE_NVP(EndEffectorRotKp)); a->Visit(DRAKE_NVP(EndEffectorRotKd)); - + a->Visit(DRAKE_NVP(w_elbow)); + a->Visit(DRAKE_NVP(elbow_kp)); + a->Visit(DRAKE_NVP(elbow_kd)); a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(neutral_position)); a->Visit(DRAKE_NVP(x_scale)); @@ -74,15 +74,9 @@ struct FrankaControllerParams : OSCGains { K_d_end_effector = Eigen::Map< Eigen::Matrix>( this->EndEffectorKd.data(), 3, 3); - W_mid_link = Eigen::Map< - Eigen::Matrix>( - this->MidLinkW.data(), 3, 3); - K_p_mid_link = Eigen::Map< - Eigen::Matrix>( - this->MidLinkKp.data(), 3, 3); - K_d_mid_link = Eigen::Map< - Eigen::Matrix>( - this->MidLinkKd.data(), 3, 3); + W_mid_link = this->w_elbow * MatrixXd::Identity(1, 1); + K_p_mid_link = this->elbow_kp * MatrixXd::Identity(1, 1); + K_d_mid_link = this->elbow_kd * MatrixXd::Identity(1, 1); W_end_effector_rot = Eigen::Map< Eigen::Matrix>( this->EndEffectorRotW.data(), 3, 3); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2ad6160877..b05c362059 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -19,7 +19,7 @@ w_lambda: 0.0 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 5.0 +end_effector_acceleration: 1.0 track_end_effector_orientation: false cancel_gravity_compensation: true # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe @@ -32,39 +32,32 @@ W_lambda_c_reg: [ 0.001, 0.001, 0.01, W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] + +w_elbow: 1 +elbow_kp: 100 +elbow_kd: 5 + EndEffectorW: [1, 0, 0, 0, 1, 0, 0, 0, 1] EndEffectorKp: - [ 1000, 0, 0, - 0, 500, 0, - 0, 0, 1000 ] -EndEffectorKd: - [ 125, 0, 0, - 0, 70, 0, - 0, 0, 125 ] -MidLinkW: - [0, 0, 0, - 0, 0, 0, - 0, 0, 10] -MidLinkKp: - [ 0, 0, 0, - 0, 0, 0, + [ 100, 0, 0, + 0, 100, 0, 0, 0, 100 ] -MidLinkKd: - [ 0, 0, 0, - 0, 0, 0, - 0, 0, 20 ] +EndEffectorKd: + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 5 ] EndEffectorRotW: [ 10, 0, 0, 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 4000, 0, 0, - 0, 4000, 0, - 0, 0, 500] + [ 100, 0, 0, + 0, 100, 0, + 0, 0, 100] EndEffectorRotKd: - [ 200, 0, 0, - 0, 200, 0, - 0, 0, 40 ] + [ 5, 0, 0, + 0, 5, 0, + 0, 0, 5 ] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 31a7558369..286319ffdf 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,14 +8,14 @@ box_model: examples/franka/urdf/default_box.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 -visualize: true +visualize: false tool_attachment_frame: [0, 0, 0.15] dt: 0.0005 realtime_rate: 0.5 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] -q_init_franka: [-1.0, 1.25, 1.25, -1.7, 1.85, 1.23, -0.67] +q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index f8c3c78756..0257f707ca 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -2,6 +2,7 @@ franka_state_channel: FRANKA_STATE tray_state_channel: TRAY_STATE box_state_channel: BOX_STATE franka_input_channel: FRANKA_INPUT +franka_input_echo: FRANKA_INPUT_ECHO osc_channel: OSC_FRANKA osc_debug_channel: OSC_DEBUG_FRANKA diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index 19554c767b..6ccfedf62f 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -2,6 +2,7 @@ franka_state_channel: FRANKA_STATE_SIMULATION tray_state_channel: TRAY_STATE_SIMULATION box_state_channel: BOX_STATE_SIMULATION franka_input_channel: FRANKA_INPUT +franka_input_echo: FRANKA_INPUT_ECHO osc_channel: OSC_FRANKA osc_debug_channel: OSC_DEBUG_FRANKA diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index b672a635bd..64899bd2f1 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -94,10 +94,10 @@ void EndEffectorTrajectoryGenerator::CalcTraj( (PiecewisePolynomial*)dynamic_cast*>( traj); if (radio_out->channel[14]) { + *casted_traj = GeneratePose(context); + } else { *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); - } else { - *casted_traj = GeneratePose(context); // *casted_traj = GenerateCircle(context); // *casted_traj = GenerateLine(context); } diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 91cbd6e00b..d9fcf95081 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -316,7 +316,7 @@ RobotInputReceiver::RobotInputReceiver( drake::Value{}); this->DeclareVectorOutputPort("u, t", TimestampedVector(num_actuators_), - &RobotInputReceiver::CopyInputOut); + &RobotInputReceiver::CopyInputOut, {all_sources_ticket()}); } void RobotInputReceiver::CopyInputOut(const Context& context, @@ -328,10 +328,9 @@ void RobotInputReceiver::CopyInputOut(const Context& context, VectorXd input_vector = VectorXd::Zero(num_actuators_); // std::cout << "context time: " << context.get_time() << std::endl; // std::cout << "time: " << input_msg.utime * 1e-6 << std::endl; - std::cout << "num_efforts: " << input_msg.num_efforts << std::endl; +// std::cout << "num_efforts: " << input_msg.num_efforts << std::endl; for (int i = 0; i < input_msg.num_efforts; i++) { -// std::cout << "effort: " << i << input_msg.efforts[i] << std::endl; int j = actuator_index_map_.at(input_msg.effort_names[i]); input_vector(j) = input_msg.efforts[i]; } From 4319dc53645623eba3cf0bd8a890a34fb08c2a31 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Nov 2023 10:15:53 -0400 Subject: [PATCH 490/758] plotting updates for better formatting --- .../pydairlib/analysis/franka_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_franka.py | 63 +++++++++---------- .../pydairlib/analysis/mbp_plotting_utils.py | 1 + .../plot_configs/franka_translation_plot.yaml | 12 ++-- bindings/pydairlib/common/plot_styler.py | 12 ++-- 5 files changed, 48 insertions(+), 41 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py index aae1a41727..93c94d58b8 100644 --- a/bindings/pydairlib/analysis/franka_plot_config.py +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -22,6 +22,7 @@ def __init__(self, filename): self.plot_measured_efforts = data['plot_measured_efforts'] self.plot_commanded_efforts = data['plot_commanded_efforts'] self.plot_contact_forces = data['plot_contact_forces'] + self.plot_end_effector = data['plot_end_effector'] self.pos_names = \ data['special_positions_to_plot'] if \ data['special_positions_to_plot'] else [] diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 868f838761..779c6fd849 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -10,6 +10,7 @@ import pydairlib.analysis.mbp_plotting_utils as mbp_plots from pydairlib.common import plot_styler +from pydrake.all import JointIndex, JointActuatorIndex def main(): config_file = 'bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml' @@ -49,41 +50,54 @@ def main(): print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) + franka_joint_limits_lower = np.zeros(franka_plant.num_positions()) + franka_joint_limits_upper = np.zeros(franka_plant.num_positions()) + franka_joint_velocity_limits_lower = np.zeros(franka_plant.num_positions()) + franka_joint_velocity_limits_upper = np.zeros(franka_plant.num_positions()) + franka_joint_actuator_limits_lower = np.zeros(franka_plant.num_positions()) + franka_joint_actuator_limits_upper = np.zeros(franka_plant.num_positions()) + for i in range(franka_plant.num_positions()): + franka_joint_limits_upper[i] = franka_plant.get_joint(JointIndex(i)).position_upper_limits()[0] + franka_joint_limits_lower[i] = franka_plant.get_joint(JointIndex(i)).position_lower_limits()[0] + franka_joint_velocity_limits_lower[i] = franka_plant.get_joint(JointIndex(i)).velocity_upper_limits()[0] + franka_joint_velocity_limits_upper[i] = franka_plant.get_joint(JointIndex(i)).velocity_lower_limits()[0] + franka_joint_actuator_limits_lower[i] = -franka_plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() + franka_joint_actuator_limits_upper[i] = franka_plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() + franka_joint_limit_range = [np.min(franka_joint_limits_lower), np.max(franka_joint_limits_upper)] + franka_joint_velocity_limit_range = [np.min(franka_joint_velocity_limits_lower), np.max(franka_joint_velocity_limits_upper)] + franka_joint_actuator_limit_range = [np.min(franka_joint_actuator_limits_lower), np.max(franka_joint_actuator_limits_upper)] + # Plot joint positions if plot_config.plot_joint_positions: plot = mbp_plots.plot_joint_positions(robot_output, pos_names, 0, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) + plt.ylim(franka_joint_limit_range) # Plot specific positions if plot_config.pos_names: plot = mbp_plots.plot_positions_by_name(robot_output, plot_config.pos_names, t_x_slice, pos_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) # Plot all joint velocities if plot_config.plot_joint_velocities: plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) + plt.ylim(franka_joint_velocity_limit_range) + - # Plot specific velocities +# Plot specific velocities if plot_config.vel_names: plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, t_x_slice, vel_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) - mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, - franka_context, ['paddle'], - {'paddle': np.zeros(3)}, - {'paddle': [0, 1, 2]}) + if plot_config.plot_end_effector: + mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, + franka_context, ['paddle'], + {'paddle': np.zeros(3)}, + {'paddle': [0, 1, 2]}) mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, franka_context, ['paddle'], @@ -119,40 +133,30 @@ def main(): if plot_config.plot_measured_efforts: plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) + plt.ylim(franka_joint_actuator_limit_range) if plot_config.plot_commanded_efforts: plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) + plt.ylim(franka_joint_actuator_limit_range) if plot_config.act_names: plot = mbp_plots.plot_measured_efforts_by_name(robot_output, plot_config.act_names, t_x_slice, act_map) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) ''' Plot OSC ''' if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) + plt.ylim([0, 1e3]) if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) + if plot_config.plot_qp_solutions: plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): @@ -161,16 +165,11 @@ def main(): plot = mbp_plots.plot_osc_tracking_data(osc_debug, traj_name, dim, deriv, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], - osc_debug['fsm'], - plot_config.fsm_state_names) tracking_data = osc_debug['osc_debug_tracking_datas'][ traj_name] if plot_config.plot_qp_solve_time: plot = mbp_plots.plot_qp_solve_time(osc_debug, t_osc_slice) - mbp_plots.add_fsm_to_plot(plot, osc_debug['t_osc'], osc_debug['fsm'], - plot_config.fsm_state_names) if plot_config.plot_active_tracking_datas: plot = mbp_plots.plot_active_tracking_datas(osc_debug, t_osc_slice, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index ade7ac412b..1df80d502b 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -729,6 +729,7 @@ def add_fsm_to_plot(ps, fsm_time, fsm_signal, fsm_state_names): legend = ax.legend(handles=legend_elements, loc=4) # ax.add_artist(legend) ax.relim() + ax.relim() def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 8152ebf266..8ca1ad571c 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -6,16 +6,17 @@ use_default_styling: false start_time: 0 #duration: 0.47 -duration: -1 +duration: 2 # Plant properties # Desired RobotOutput plots plot_joint_positions: true plot_joint_velocities: true -plot_measured_efforts: false +plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false +plot_end_effector: false special_positions_to_plot: [] special_velocities_to_plot: [] @@ -25,10 +26,11 @@ special_efforts_to_plot: [] fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] # Desired osc plots -plot_qp_costs: true +plot_qp_costs: false plot_qp_solve_time: true plot_qp_solutions: false -plot_tracking_costs: true +plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +# end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +# end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 81a78f1293..f9ebbafa68 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -31,13 +31,19 @@ def __init__(self, figure=None, nrows=1, ncols=1): self.grey = '#909090' self.orange = '#FE7F0E' # self.directory = None - self.dpi = 200 + self.dpi = 150 self.directory = '/home/yangwill/Pictures/plot_styler/' plt.rc('legend', fontsize=14) plt.rc('axes', labelsize=14, titlesize=14) plt.rc('xtick', labelsize=14) plt.rc('ytick', labelsize=14) matplotlib.rcParams['figure.figsize'] = 12, 7 + print(matplotlib.rcParams.keys()) + matplotlib.rcParams['figure.autolayout'] = True + matplotlib.rcParams['axes.xmargin'] = 0 + matplotlib.rcParams['axes.ymargin'] = 0 + # matplotlib.rcParams['toolbar'] = 'None' + matplotlib.rcParams['figure.constrained_layout.use'] = True matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" if figure is None: @@ -48,7 +54,6 @@ def __init__(self, figure=None, nrows=1, ncols=1): self.axes = figure.get_axes() if not isinstance(self.axes, np.ndarray): self.axes = [self.axes] - # self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] self.fig_id = self.fig.number return @@ -56,7 +61,6 @@ def __init__(self, figure=None, nrows=1, ncols=1): def attach(self): plt.figure(self.fig_id) - def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, linestyle=None, grid=True, xlabel=None, ylabel=None, title=None, legend=None, @@ -75,8 +79,8 @@ def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, self.axes[subplot_index].set_title(title) if legend: self.axes[subplot_index].legend(legend) - self.axes[subplot_index].grid(grid, which='major') + self.axes[subplot_index].autoscale() def plot_bands(self, x_low, x_high, y_low, y_high, color='C0', subplot_index=0): From 7444772e3c4d1b5e7bedcd7b8382ed20cf5fe6a1 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 2 Nov 2023 11:03:43 -0400 Subject: [PATCH 491/758] franka osc teleop works --- examples/franka/franka_osc_controller.cc | 6 ++-- .../franka_osc_controller_params.yaml | 30 +++++++++---------- .../franka/parameters/franka_sim_params.yaml | 2 +- .../parameters/lcm_channels_hardware.yaml | 2 +- 4 files changed, 20 insertions(+), 20 deletions(-) diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 09f2ddedad..34f2c3b02f 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -179,10 +179,10 @@ int DoMain(int argc, char* argv[]) { controller_params.end_effector_name); auto mid_link_position_tracking_data_for_rel = std::make_unique( - "panda_joint3_target", controller_params.K_p_mid_link, + "panda_joint2_target", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant); - mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint3", "panda_joint3dot"); + mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", "panda_joint2dot"); auto end_effector_orientation_tracking_data = std::make_unique( @@ -197,7 +197,7 @@ int DoMain(int argc, char* argv[]) { osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), - 1.4 * VectorXd::Ones(1)); + 1.6 * VectorXd::Ones(1)); osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); osc->SetContactFriction(controller_params.mu); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index b05c362059..b99c9f2b82 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -19,7 +19,7 @@ w_lambda: 0.0 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 1.0 +end_effector_acceleration: 4.0 track_end_effector_orientation: false cancel_gravity_compensation: true # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe @@ -34,30 +34,30 @@ W_lambda_h_reg: [ 0.001, 0.001, 0.001, w_elbow: 1 -elbow_kp: 100 -elbow_kd: 5 +elbow_kp: 200 +elbow_kd: 10 EndEffectorW: [1, 0, 0, 0, 1, 0, 0, 0, 1] EndEffectorKp: - [ 100, 0, 0, - 0, 100, 0, - 0, 0, 100 ] + [ 200, 0, 0, + 0, 200, 0, + 0, 0, 200 ] EndEffectorKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 5 ] + [ 20, 0, 0, + 0, 20, 0, + 0, 0, 20 ] EndEffectorRotW: [ 10, 0, 0, 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 100, 0, 0, - 0, 100, 0, - 0, 0, 100] + [ 200, 0, 0, + 0, 200, 0, + 0, 0, 200] EndEffectorRotKd: - [ 5, 0, 0, - 0, 5, 0, - 0, 0, 5 ] + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 286319ffdf..996b30cdc4 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -13,7 +13,7 @@ visualize: false tool_attachment_frame: [0, 0, 0.15] dt: 0.0005 -realtime_rate: 0.5 +realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index 0257f707ca..1a65b34798 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -1,5 +1,5 @@ franka_state_channel: FRANKA_STATE -tray_state_channel: TRAY_STATE +tray_state_channel: TRAY_STATE_SIMULATION box_state_channel: BOX_STATE franka_input_channel: FRANKA_INPUT franka_input_echo: FRANKA_INPUT_ECHO From 08bbd3b821b84f6b1b4cf9487d9d00b7424a7c6d Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 2 Nov 2023 11:40:56 -0400 Subject: [PATCH 492/758] updating controller and plotting after experimnets --- .../analysis/franka_plotting_utils.py | 2 ++ .../plot_configs/franka_translation_plot.yaml | 6 ++--- bindings/pydairlib/common/plot_styler.py | 2 -- examples/franka/franka_osc_controller.cc | 27 ++++++++++++------- .../franka_osc_controller_params.yaml | 2 +- 5 files changed, 24 insertions(+), 15 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index 64b56b353b..fcee19cceb 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -18,6 +18,8 @@ {'FRANKA_STATE': dairlib.lcmt_robot_output, # 'TRAY_STATE': dairlib.lcmt_robot_output, 'FRANKA_INPUT': dairlib.lcmt_robot_input, + 'OSC_FRANKA': dairlib.lcmt_robot_input, + 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 8ca1ad571c..9de2bc5fc8 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -1,12 +1,12 @@ # LCM channels to read data from channel_x: "FRANKA_STATE" -channel_u: "FRANKA_INPUT" +channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" use_default_styling: false start_time: 0 #duration: 0.47 -duration: 2 +duration: -1 # Plant properties @@ -32,5 +32,5 @@ plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: -# end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} + end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index f9ebbafa68..78923e8874 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -38,12 +38,10 @@ def __init__(self, figure=None, nrows=1, ncols=1): plt.rc('xtick', labelsize=14) plt.rc('ytick', labelsize=14) matplotlib.rcParams['figure.figsize'] = 12, 7 - print(matplotlib.rcParams.keys()) matplotlib.rcParams['figure.autolayout'] = True matplotlib.rcParams['axes.xmargin'] = 0 matplotlib.rcParams['axes.ymargin'] = 0 # matplotlib.rcParams['toolbar'] = 'None' - matplotlib.rcParams['figure.constrained_layout.use'] = True matplotlib.rcParams['text.latex.preamble'] = r"\usepackage{amsmath}" if figure is None: diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 34f2c3b02f..7019185e1d 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -10,6 +10,7 @@ #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" +#include "systems/controllers/gravity_compensator.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/relative_translation_tracking_data.h" @@ -18,7 +19,6 @@ #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "systems/controllers/gravity_compensator.h" #include "systems/trajectory_optimization/lcm_trajectory_systems.h" #include "drake/common/find_resource.h" @@ -83,18 +83,25 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); Parser parser(&plant, nullptr); parser.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); - drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; + RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); Vector3d tool_attachment_frame = StdVectorToVectorXd(controller_params.tool_attachment_frame); - RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), tool_attachment_frame); - plant.WeldFrames(plant.GetFrameByName("panda_link7"), - plant.GetFrameByName("plate", end_effector_index), T_EE_W); + if (!controller_params.end_effector_name.empty()) { + drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), tool_attachment_frame); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName(controller_params.end_effector_name, + end_effector_index), + T_EE_W); + } else { + std::cout << "OSC plant has been constructed with no end effector." << std::endl; + } plant.Finalize(); auto plant_context = plant.CreateDefaultContext(); @@ -182,7 +189,8 @@ int DoMain(int argc, char* argv[]) { "panda_joint2_target", controller_params.K_p_mid_link, controller_params.K_d_mid_link, controller_params.W_mid_link, plant, plant); - mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", "panda_joint2dot"); + mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", + "panda_joint2dot"); auto end_effector_orientation_tracking_data = std::make_unique( @@ -207,7 +215,8 @@ int DoMain(int argc, char* argv[]) { if (controller_params.cancel_gravity_compensation) { auto gravity_compensator = - builder.AddSystem(plant, *plant_context); + builder.AddSystem(plant, + *plant_context); builder.Connect(osc->get_output_port_osc_command(), gravity_compensator->get_input_port()); builder.Connect(gravity_compensator->get_output_port(), diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index b99c9f2b82..e356680fc8 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -19,7 +19,7 @@ w_lambda: 0.0 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 4.0 +end_effector_acceleration: 4.5 track_end_effector_orientation: false cancel_gravity_compensation: true # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe From c685512e34790fee2611ca6359dc32cad0b91d59 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 2 Nov 2023 13:51:06 -0400 Subject: [PATCH 493/758] switching to cylindrical ee and object --- .../franka_osc_controller_params.yaml | 4 ++-- .../franka/parameters/franka_sim_params.yaml | 6 +++--- examples/franka/urdf/plate_end_effector.urdf | 4 ++-- examples/franka/urdf/tray.sdf | 18 ++++++++++-------- 4 files changed, 17 insertions(+), 15 deletions(-) diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index e356680fc8..7df7e53fac 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -4,7 +4,7 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate -tool_attachment_frame: [0, 0, 0.15] +tool_attachment_frame: [0, 0, 0.107] neutral_position: [0.55, 0, 0.4] x_scale: 0.1 @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 996b30cdc4..aa1cd579d9 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,9 +8,9 @@ box_model: examples/franka/urdf/default_box.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 -visualize: false +visualize: true -tool_attachment_frame: [0, 0, 0.15] +tool_attachment_frame: [0, 0, 0.107] dt: 0.0005 realtime_rate: 1.0 @@ -18,5 +18,5 @@ realtime_rate: 1.0 q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] -q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] +q_init_plate: [1, 0, 0, 0, 0.56, 0.00, 1.250] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 1.1] diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 1e74d93114..9b33fddb69 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -10,7 +10,7 @@ - + @@ -22,7 +22,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 612d054e60..3870fbeaca 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -18,9 +18,10 @@ - - 0.4 0.4 0.02 - + + 0.2286 + 0.01778 + 0.3 0.3 0.3 1 @@ -28,15 +29,16 @@ - - 0.4 0.4 0.02 - + + 0.2286 + 0.01778 + - 3.0e7 - 1.0 + 3.0e8 + 0.05 @@ -30,21 +30,21 @@ - + - + - + - + - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 3870fbeaca..aab632d0a2 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -8,12 +8,12 @@ - 0.0066833 + 0.0065454 0 0 - 0.0066833 + 0.0065454 0 - 0.013333 + 0.013064 @@ -27,7 +27,7 @@ 0.3 0.3 0.3 1 - + 0.2286 @@ -37,19 +37,11 @@ - 3.0e8 - 0.05 - - - - 0.2 - 0.2 + 3.0e7 + 0.5 + 10 + 0.4 + 0.4 diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index abe9f201ad..28fce7cfef 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -157,7 +157,6 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( trajectory_block.time_vector, trajectory_block.datapoints); for (int i = 0; i < line_points.cols(); ++i) { line_points.col(i) = trajectory.value(breaks(i)); - line_points(2, i) += 0.7645; } } else { auto trajectory = PiecewisePolynomial::CubicHermite( @@ -165,7 +164,6 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( trajectory_block.datapoints.bottomRows(3)); for (int i = 0; i < line_points.cols(); ++i) { line_points.col(i) = trajectory.value(breaks(i)); - line_points(2, i) += 0.7645; } } From 56989e1ee25e8b734a72660bd0d4dc9f589cacb9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 Nov 2023 17:59:59 -0400 Subject: [PATCH 495/758] adding c3 visualization traces --- examples/franka/franka_visualizer.cc | 26 ++-- multibody/multipose_visualizer.cc | 26 ++-- multibody/multipose_visualizer.h | 3 +- systems/trajectory_optimization/BUILD.bazel | 1 + .../lcm_trajectory_systems.cc | 130 ++++++++++-------- .../lcm_trajectory_systems.h | 40 ++++++ 6 files changed, 152 insertions(+), 74 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 462b885222..632f696dbf 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -5,11 +5,11 @@ #include #include -#include "common/find_resource.h" #include "common/eigen_utils.h" +#include "common/find_resource.h" #include "dairlib/lcmt_robot_output.hpp" -#include "examples/franka/parameters/franka_sim_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" #include "multibody/com_pose_system.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" @@ -76,8 +76,8 @@ int do_main(int argc, char* argv[]) { drake::multibody::ModelInstanceIndex franka_index = parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; - drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( - FindResourceOrThrow(sim_params.end_effector_model))[0]; + drake::multibody::ModelInstanceIndex end_effector_index = + parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; drake::multibody::ModelInstanceIndex box_index = @@ -86,7 +86,8 @@ int do_main(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); - Vector3d tool_attachment_frame = StdVectorToVectorXd(sim_params.tool_attachment_frame); + Vector3d tool_attachment_frame = + StdVectorToVectorXd(sim_params.tool_attachment_frame); RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); @@ -94,8 +95,8 @@ int do_main(int argc, char* argv[]) { drake::math::RotationMatrix(), tool_attachment_frame); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); - plant.WeldFrames( plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), - T_EE_W); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName("plate", end_effector_index), T_EE_W); plant.Finalize(); @@ -108,8 +109,9 @@ int do_main(int argc, char* argv[]) { auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.tray_state_channel, lcm)); - auto box_state_sub = builder.AddSystem( - LcmSubscriberSystem::Make(lcm_channel_params.box_state_channel, lcm)); + auto box_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.box_state_channel, lcm)); auto franka_state_receiver = builder.AddSystem(plant, franka_index); auto tray_state_receiver = @@ -154,6 +156,10 @@ int do_main(int argc, char* argv[]) { "end_effector_traj"); auto trajectory_drawer_object = builder.AddSystem(meshcat, "object_traj"); + auto object_trajectory_drawer_object = + builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.tray_model), "object_traj", + "object_orientation_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(5); @@ -167,6 +173,8 @@ int do_main(int argc, char* argv[]) { trajectory_drawer_actor->get_input_port_trajectory()); builder.Connect(trajectory_sub_object->get_output_port(), trajectory_drawer_object->get_input_port_trajectory()); + builder.Connect(trajectory_sub_object->get_output_port(), + object_trajectory_drawer_object->get_input_port_trajectory()); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index 37cd2eebc2..1348629e59 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -1,12 +1,15 @@ #include "multibody/multipose_visualizer.h" +#include + #include "drake/geometry/drake_visualizer.h" -#include "drake/geometry/scene_graph.h" #include "drake/geometry/meshcat_visualizer_params.h" +#include "drake/geometry/scene_graph.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" using drake::geometry::DrakeVisualizer; +using drake::geometry::Meshcat; using drake::geometry::SceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; @@ -30,7 +33,8 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, - string weld_frame_to_world) + string weld_frame_to_world, + std::shared_ptr meshcat) : num_poses_(num_poses) { DRAKE_DEMAND(num_poses == alpha_scale.size()); DiagramBuilder builder; @@ -89,16 +93,19 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, } } - drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0/60.0; - meshcat_ = std::make_shared(); - meshcat_visualizer_ = &drake::geometry::MeshcatVisualizer::AddToBuilder( - &builder, *scene_graph, meshcat_, std::move(params)); + if (meshcat == nullptr) { + meshcat_ = std::make_shared(); + } else { + meshcat_ = meshcat; + } + meshcat_visualizer_ = + &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, *scene_graph, meshcat_); - DrakeVisualizer::AddToBuilder(&builder, *scene_graph, lcm); + // DrakeVisualizer::AddToBuilder(&builder, *scene_graph, lcm); + // DrakeVisualizer::DispatchLoadMessage(*scene_graph, lcm); diagram_ = builder.Build(); diagram_context_ = diagram_->CreateDefaultContext(); - DrakeVisualizer::DispatchLoadMessage(*scene_graph, lcm); } void MultiposeVisualizer::DrawPoses(MatrixXd poses) { @@ -113,7 +120,6 @@ void MultiposeVisualizer::DrawPoses(MatrixXd poses) { // Publish diagram diagram_->ForcedPublish(*diagram_context_); - } } // namespace multibody diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index f7d2690a11..cfbf078826 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -47,7 +47,8 @@ class MultiposeVisualizer { /// @param weld_frame_to_world Welds the frame of the given name to the world MultiposeVisualizer(std::string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, - std::string weld_frame_to_world = ""); + std::string weld_frame_to_world = "", + std::shared_ptr = nullptr); /// Draws the poses in the given (num_positions x num_poses) matrix /// Note: the matrix can have extra rows (e.g. velocities), which will be diff --git a/systems/trajectory_optimization/BUILD.bazel b/systems/trajectory_optimization/BUILD.bazel index 376590af27..dca8994e5e 100644 --- a/systems/trajectory_optimization/BUILD.bazel +++ b/systems/trajectory_optimization/BUILD.bazel @@ -55,6 +55,7 @@ cc_library( ], deps = [ "//lcm:lcm_trajectory_saver", + "//multibody:multipose_visualizer", "//common:find_resource", "//common:eigen_utils", "@drake//:drake_shared_library", diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 28fce7cfef..ab4f586b9d 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -171,62 +171,84 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, rgba_); - if (lcm_traj_.HasTrajectory("end_effector_orientation_target")) { - const auto orientation_block = - lcm_traj_.GetTrajectory("end_effector_orientation_target"); - auto trajectory = PiecewisePolynomial::CubicHermite( - orientation_block.time_vector, orientation_block.datapoints.topRows(3), - orientation_block.datapoints.bottomRows(3)); -// for (int i = line_points.cols() - 2; i < line_points.cols(); ++i) { -// auto pose = drake::math::RigidTransform( -// drake::math::RollPitchYaw(trajectory.value(breaks(i))), -// line_points.col(i)); -// auto box = drake::geometry::Box(0.1, 0.1, 0.01); -// auto rgba_transparent = rgba_; -// rgba_transparent.set( -// rgba_.r(), rgba_.g(), rgba_.b(), -// (line_points.cols() - double(i)) / line_points.cols() * rgba_.a()); -// meshcat_->SetObject( -// "/trajectories/end_effector_pose/" + std::to_string(i), box, -// rgba_transparent); -// meshcat_->SetTransform( -// "/trajectories/end_effector_pose/" + std::to_string(i), pose); -// } - } else { - auto trajectory = PiecewisePolynomial::CubicHermite( - trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), - trajectory_block.datapoints.bottomRows(3)); - auto pose = drake::math::RigidTransform(line_points.col(line_points.cols() - 1)); - double side_length = 0.2; - if (trajectory_name_ == "object_traj"){ - side_length = 0.4; + return drake::systems::EventStatus::Succeeded(); +} + +LcmObjectTrajectoryDrawer::LcmObjectTrajectoryDrawer( + const std::shared_ptr& meshcat, + const std::string& model_file, + const std::string& translation_trajectory_name, + const std::string& orientation_trajectory_name, + const std::string& default_trajectory_path) + : meshcat_(meshcat), + translation_trajectory_name_(std::move(translation_trajectory_name)), + orientation_trajectory_name_(std::move(orientation_trajectory_name)), + default_trajectory_path_(default_trajectory_path) { + this->set_name(model_file); + + multipose_visualizer_ = std::make_unique( + model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.5), "", meshcat); + trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj", + drake::Value{}) + .get_index(); + + lcm_traj_ = + LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); + DeclarePerStepDiscreteUpdateEvent(&LcmObjectTrajectoryDrawer::DrawTrajectory); +} + +drake::systems::EventStatus LcmObjectTrajectoryDrawer::DrawTrajectory( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, trajectory_input_port_) + ->utime > 1e-3) { + const auto& lcm_traj = + this->EvalInputValue( + context, trajectory_input_port_); + lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); + } + MatrixXd object_poses = MatrixXd::Zero(7, N_); + + if (!lcm_traj_.HasTrajectory(translation_trajectory_name_)) { + return drake::systems::EventStatus::Succeeded(); + } + + const auto lcm_translation_traj = + lcm_traj_.GetTrajectory(translation_trajectory_name_); + auto translation_trajectory = PiecewisePolynomial::FirstOrderHold( + lcm_translation_traj.time_vector, lcm_translation_traj.datapoints); + auto orientation_trajectory = PiecewiseQuaternionSlerp( + {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); + + if (lcm_traj_.HasTrajectory(orientation_trajectory_name_)) { + const auto lcm_orientation_traj = + lcm_traj_.GetTrajectory(orientation_trajectory_name_); + std::vector> quaternion_datapoints; + for (int i = 0; i < lcm_orientation_traj.datapoints.cols(); ++i) { + quaternion_datapoints.push_back( + drake::math::RollPitchYaw( + lcm_orientation_traj.datapoints.col(i)) + .ToQuaternion()); } - auto box = drake::geometry::Box(side_length, side_length, 0.01); - auto rgba_transparent = rgba_; - rgba_transparent.set( - rgba_.r(), rgba_.g(), rgba_.b(), - 0.3 * rgba_.a()); - meshcat_->SetObject("/trajectories/" + trajectory_name_ + "/end", - box, rgba_transparent); - meshcat_->SetTransform( - "/trajectories/" + trajectory_name_ + "/end", pose); + orientation_trajectory = PiecewiseQuaternionSlerp( + CopyVectorXdToStdVector(lcm_orientation_traj.time_vector), + quaternion_datapoints); } - // if (lcm_traj_.HasTrajectory("object_orientation_target")) { - // const auto orientation_block = - // lcm_traj_.GetTrajectory("object_orientation_target"); - // for (int i = 0; i < orientation_block.datapoints.cols(); ++i) { - // auto pose = drake::math::RigidTransform( - // Quaterniond(orientation_block.datapoints(0, i), - // orientation_block.datapoints(1, i), - // orientation_block.datapoints(2, i), - // orientation_block.datapoints(3, i)), - // line_points.col(i)); - // auto box = drake::geometry::Box(0.1, 0.1, 0.01); - // meshcat_->SetObject("/trajectories/object" + std::to_string(i), box, - // rgba_); meshcat_->SetTransform("/trajectories/object" + - // std::to_string(i), pose); - // } - // } + + // ASSUMING orientation and translation trajectories have the same breaks + VectorXd translation_breaks = + VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], + lcm_translation_traj.time_vector.tail(1)[0]); + + for (int i = 0; i < object_poses.cols(); ++i) { + object_poses.col(i) << orientation_trajectory.value(translation_breaks(i)), + translation_trajectory.value(translation_breaks(i)); + } + + multipose_visualizer_->DrawPoses(object_poses); return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index e60e616609..5dc15d56ea 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -6,6 +6,7 @@ #include #include "dairlib/lcmt_saved_traj.hpp" +#include "multibody/multipose_visualizer.h" #include "lcm/lcm_trajectory.h" #include "drake/common/trajectories/piecewise_polynomial.h" @@ -107,5 +108,44 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { int N_ = 5; }; +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws the object pose through meshcat. +class LcmObjectTrajectoryDrawer : public drake::systems::LeafSystem { + public: + explicit LcmObjectTrajectoryDrawer( + const std::shared_ptr&, + const std::string& model_file, + const std::string& translation_trajectory_name, + const std::string& orientation_trajectory_name, + const std::string& default_trajectory_path = + "examples/franka/saved_trajectories/franka_defaults"); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_input_port_); + } + + void SetNumSamples(int N) { + DRAKE_DEMAND(N > 1); + N_ = N; + } + + private: + void OutputTrajectory(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + drake::systems::EventStatus DrawTrajectory( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex trajectory_input_port_; + std::shared_ptr meshcat_; + const std::string translation_trajectory_name_; + const std::string orientation_trajectory_name_; + mutable LcmTrajectory lcm_traj_; + std::unique_ptr multipose_visualizer_; + std::string default_trajectory_path_; + int N_ = 5; +}; + } // namespace systems } // namespace dairlib From 6f083ee119fc5acf905a8e93ab132e558361e101 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 10:35:56 -0400 Subject: [PATCH 496/758] fixing bazel settings and cleaning up pose visualizer --- examples/franka/BUILD.bazel | 16 ++++++++++++++++ examples/franka/franka_visualizer.cc | 2 +- .../franka_c3_options_translation.yaml | 8 ++++++++ .../franka/parameters/franka_sim_params.yaml | 4 ++-- solvers/c3_options.h | 15 ++++++++++----- .../lcm_trajectory_systems.cc | 8 +++++--- .../lcm_trajectory_systems.h | 15 +++++---------- 7 files changed, 47 insertions(+), 21 deletions(-) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index bc88a4bf1d..03a0c3aac2 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -159,6 +159,10 @@ cc_library( deps = [ "@drake//:drake_shared_library", ], + data = [ + "parameters/lcm_channels_hardware.yaml", + "parameters/lcm_channels_simulation.yaml", + ] ) cc_library( @@ -167,6 +171,9 @@ cc_library( deps = [ "@drake//:drake_shared_library", ], + data = [ + "parameters/franka_sim_params.yaml", + ] ) cc_library( @@ -175,6 +182,9 @@ cc_library( deps = [ "@drake//:drake_shared_library", ], + data = [ + "parameters/franka_osc_controller_params.yaml", + ] ) cc_library( @@ -184,4 +194,10 @@ cc_library( "//solvers:c3", "@drake//:drake_shared_library", ], + data = [ + "parameters/franka_c3_controller_params.yaml", + "parameters/franka_c3_options_floating.yaml", + "parameters/franka_c3_options_translation.yaml", + "parameters/franka_qp_options.yaml", + ] ) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 632f696dbf..fc7b6afd2c 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -157,7 +157,7 @@ int do_main(int argc, char* argv[]) { auto trajectory_drawer_object = builder.AddSystem(meshcat, "object_traj"); auto object_trajectory_drawer_object = - builder.AddSystem( + builder.AddSystem( meshcat, FindResourceOrThrow(sim_params.tray_model), "object_traj", "object_orientation_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index c1d108d267..0a3dbea683 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -11,6 +11,8 @@ solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 N: 7 + +# matrix scaling w_Q: 5 w_R: 0 # Penalty on all decision variables, assuming scalar @@ -23,6 +25,12 @@ u_size: 40 # State Tracking Error, assuming diagonal q_vector: [10, 10, 5000, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] +# Penalty on all decision variables +g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +# Penalty on all decision variables +u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index aa1cd579d9..9125e92864 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -18,5 +18,5 @@ realtime_rate: 1.0 q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] -q_init_plate: [1, 0, 0, 0, 0.56, 0.00, 1.250] -q_init_box: [1, 0, 0, 0, 0.9, -0.2, 1.1] +q_init_plate: [1, 0, 0, 0, 0.56, 0.00, 0.550] +q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 74f70c92c2..82ece81042 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -24,6 +24,8 @@ struct C3Options { std::vector q_vector; std::vector r_vector; + std::vector g_vector; + std::vector u_vector; std::vector q_des_vector; std::vector v_des_vector; @@ -64,6 +66,8 @@ struct C3Options { a->Visit(DRAKE_NVP(g_size)); a->Visit(DRAKE_NVP(u_size)); a->Visit(DRAKE_NVP(q_vector)); + a->Visit(DRAKE_NVP(g_vector)); + a->Visit(DRAKE_NVP(u_vector)); a->Visit(DRAKE_NVP(r_vector)); a->Visit(DRAKE_NVP(q_des_vector)); a->Visit(DRAKE_NVP(v_des_vector)); @@ -72,6 +76,10 @@ struct C3Options { this->q_vector.data(), this->q_vector.size()); Eigen::VectorXd r = Eigen::Map( this->r_vector.data(), this->r_vector.size()); + Eigen::VectorXd g = Eigen::Map( + this->g_vector.data(), this->g_vector.size()); + Eigen::VectorXd u = Eigen::Map( + this->u_vector.data(), this->u_vector.size()); q_des = Eigen::Map( this->q_des_vector.data(), this->q_des_vector.size()); v_des = Eigen::Map( @@ -79,10 +87,7 @@ struct C3Options { Q = w_Q * q.asDiagonal(); R = w_R * r.asDiagonal(); - G = w_G * MatrixXd::Identity(g_size, g_size); - U = w_U * MatrixXd::Identity(u_size, u_size); - - U.block(0, 0, 19, 19) = 100 * MatrixXd::Identity(19, 19); - + G = w_G * g.asDiagonal(); + U = w_U * u.asDiagonal(); } }; \ No newline at end of file diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index ab4f586b9d..bbf7346eb8 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -174,15 +174,17 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( return drake::systems::EventStatus::Succeeded(); } -LcmObjectTrajectoryDrawer::LcmObjectTrajectoryDrawer( +LcmPoseDrawer::LcmPoseDrawer( const std::shared_ptr& meshcat, const std::string& model_file, const std::string& translation_trajectory_name, const std::string& orientation_trajectory_name, + int num_poses, const std::string& default_trajectory_path) : meshcat_(meshcat), translation_trajectory_name_(std::move(translation_trajectory_name)), orientation_trajectory_name_(std::move(orientation_trajectory_name)), + N_(num_poses), default_trajectory_path_(default_trajectory_path) { this->set_name(model_file); @@ -196,10 +198,10 @@ LcmObjectTrajectoryDrawer::LcmObjectTrajectoryDrawer( lcm_traj_ = LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); - DeclarePerStepDiscreteUpdateEvent(&LcmObjectTrajectoryDrawer::DrawTrajectory); + DeclarePerStepDiscreteUpdateEvent(&LcmPoseDrawer::DrawTrajectory); } -drake::systems::EventStatus LcmObjectTrajectoryDrawer::DrawTrajectory( +drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( const Context& context, DiscreteValues* discrete_state) const { if (this->EvalInputValue( diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 5dc15d56ea..ac579c0152 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -6,8 +6,8 @@ #include #include "dairlib/lcmt_saved_traj.hpp" -#include "multibody/multipose_visualizer.h" #include "lcm/lcm_trajectory.h" +#include "multibody/multipose_visualizer.h" #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/common/trajectories/piecewise_quaternion.h" @@ -110,13 +110,13 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, /// and draws the object pose through meshcat. -class LcmObjectTrajectoryDrawer : public drake::systems::LeafSystem { +class LcmPoseDrawer : public drake::systems::LeafSystem { public: - explicit LcmObjectTrajectoryDrawer( + explicit LcmPoseDrawer( const std::shared_ptr&, const std::string& model_file, const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, + const std::string& orientation_trajectory_name, int num_poses = 5, const std::string& default_trajectory_path = "examples/franka/saved_trajectories/franka_defaults"); @@ -124,11 +124,6 @@ class LcmObjectTrajectoryDrawer : public drake::systems::LeafSystem { return this->get_input_port(trajectory_input_port_); } - void SetNumSamples(int N) { - DRAKE_DEMAND(N > 1); - N_ = N; - } - private: void OutputTrajectory(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -144,7 +139,7 @@ class LcmObjectTrajectoryDrawer : public drake::systems::LeafSystem { mutable LcmTrajectory lcm_traj_; std::unique_ptr multipose_visualizer_; std::string default_trajectory_path_; - int N_ = 5; + const int N_; }; } // namespace systems From d75e7510238cb00cf7dd066f1cfe880cecc39b9e Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 10:53:04 -0400 Subject: [PATCH 497/758] removed hardcoded model naming for multipose visualizer --- examples/franka/franka_visualizer.cc | 10 ++++++++-- .../parameters/franka_c3_controller_params.yaml | 2 +- .../franka/saved_trajectories/franka_defaults | Bin 479 -> 479 bytes multibody/multipose_visualizer.cc | 5 ++--- .../lcm_trajectory_systems.cc | 4 ++-- 5 files changed, 13 insertions(+), 8 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index fc7b6afd2c..b66f5c8d8d 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -156,10 +156,14 @@ int do_main(int argc, char* argv[]) { "end_effector_traj"); auto trajectory_drawer_object = builder.AddSystem(meshcat, "object_traj"); - auto object_trajectory_drawer_object = + auto object_pose_drawer = builder.AddSystem( meshcat, FindResourceOrThrow(sim_params.tray_model), "object_traj", "object_orientation_target"); + auto end_effector_pose_drawer = + builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.end_effector_model), "end_effector_traj", + "end_effector_orientation_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(5); @@ -174,7 +178,9 @@ int do_main(int argc, char* argv[]) { builder.Connect(trajectory_sub_object->get_output_port(), trajectory_drawer_object->get_input_port_trajectory()); builder.Connect(trajectory_sub_object->get_output_port(), - object_trajectory_drawer_object->get_input_port_trajectory()); + object_pose_drawer->get_input_port_trajectory()); + builder.Connect(trajectory_sub_actor->get_output_port(), + end_effector_pose_drawer->get_input_port_trajectory()); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 047e445373..bfb3182d04 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -15,6 +15,6 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 4 +target_frequency: 10 diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults index 92e6539977d88ce766f84b7ad237e339cfe8a50e..59651e0bf4502ddf28fa1e36475a17b414d7b199 100644 GIT binary patch delta 60 zcmcc5e4lxO%H(~Fij!>_qbJU-pQutfS%y(XStvCxB|bGREj76$zbL+>C^3rx2zc_7 JvVbBGJ^+t{6oUW& delta 39 vcmcc5e4lxO%4B)Q%83i=C(mG1ndlM0!;_zsm6}`(); Parser parser(plant_, scene_graph); - + parser.SetAutoRenaming(true); // Add num_poses copies of the plant, giving each a unique name for (int i = 0; i < num_poses_; i++) { - auto index = - parser.AddModelFromFile(model_file, "model[" + std::to_string(i) + "]"); + auto index = parser.AddModels(model_file)[0]; model_indices_.push_back(index); if (!weld_frame_to_world.empty()) { plant_->WeldFrames( diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index bbf7346eb8..23b88d52ea 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -186,10 +186,10 @@ LcmPoseDrawer::LcmPoseDrawer( orientation_trajectory_name_(std::move(orientation_trajectory_name)), N_(num_poses), default_trajectory_path_(default_trajectory_path) { - this->set_name(model_file); + this->set_name("/poses/" + model_file); multipose_visualizer_ = std::make_unique( - model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.5), "", meshcat); + model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.4), "", meshcat); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", From ba14eb1fadcfceba37eb0561660b1e2f8cd29a26 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 13:56:18 -0400 Subject: [PATCH 498/758] pulling trajectory generation out of c3 controller, adding c3 output structs for debugging --- examples/franka/BUILD.bazel | 69 ++++++------ examples/franka/franka_c3_controller.cc | 9 +- .../franka/saved_trajectories/franka_defaults | Bin 479 -> 479 bytes examples/franka/systems/BUILD.bazel | 24 +++- .../franka/systems/plate_balancing_target.cc | 106 ++++++++++++++++++ .../franka/systems/plate_balancing_target.h | 61 ++++++++++ lcmtypes/lcmt_c3_intermediates.lcm | 11 ++ lcmtypes/lcmt_c3_output.lcm | 9 ++ lcmtypes/lcmt_c3_solution.lcm | 14 +++ solvers/BUILD.bazel | 14 +++ solvers/c3_output.cc | 5 + solvers/c3_output.h | 56 +++++++++ 12 files changed, 336 insertions(+), 42 deletions(-) create mode 100644 examples/franka/systems/plate_balancing_target.cc create mode 100644 examples/franka/systems/plate_balancing_target.h create mode 100644 lcmtypes/lcmt_c3_intermediates.lcm create mode 100644 lcmtypes/lcmt_c3_output.lcm create mode 100644 lcmtypes/lcmt_c3_solution.lcm create mode 100644 solvers/c3_output.cc create mode 100644 solvers/c3_output.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 03a0c3aac2..17fef4186e 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -23,12 +23,12 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_sim_params", ":franka_lcm_channels", + ":franka_sim_params", + "//common", "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", - "//common", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", "@gflags", @@ -43,17 +43,17 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_osc_controller_params", ":franka_lcm_channels", + ":franka_osc_controller_params", "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", - "//systems/trajectory_optimization:lcm_trajectory_systems", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", + "//systems/trajectory_optimization:lcm_trajectory_systems", "@drake//:drake_shared_library", "@gflags", ], @@ -74,8 +74,9 @@ cc_binary( "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", - "//systems/controllers:c3_controller", "//systems/controllers", + "//systems/controllers:c3_controller", + "//systems/controllers:c3_trajectory_generator", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", @@ -91,15 +92,15 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_sim_params", ":franka_lcm_channels", + ":franka_sim_params", "//common", "//multibody:utils", "//multibody:visualization_utils", "//systems:robot_lcm_systems", - "//systems/trajectory_optimization:lcm_trajectory_systems", "//systems:system_utils", "//systems/primitives", + "//systems/trajectory_optimization:lcm_trajectory_systems", "@drake//:drake_shared_library", "@gflags", ], @@ -112,21 +113,21 @@ cc_binary( ":urdfs", "@drake//manipulation/models/franka_description:models", ], + tags = ["ros"], deps = [ - ":franka_sim_params", ":franka_lcm_channels", + ":franka_sim_params", "//common", "//systems:robot_lcm_systems", - "//systems/ros:ros_pubsub_systems", - "//systems/ros:franka_ros_channels", - "//systems/ros:franka_ros_lcm_conversions", "//systems:system_utils", "//systems/primitives", + "//systems/ros:franka_ros_channels", + "//systems/ros:franka_ros_lcm_conversions", + "//systems/ros:ros_pubsub_systems", "@drake//:drake_shared_library", - "@ros", "@gflags", + "@ros", ], - tags = ["ros"], ) cc_binary( @@ -136,68 +137,68 @@ cc_binary( ":urdfs", "@drake//manipulation/models/franka_description:models", ], + tags = ["ros"], deps = [ - ":franka_sim_params", ":franka_lcm_channels", + ":franka_sim_params", "//common", "//systems:robot_lcm_systems", - "//systems/ros:ros_pubsub_systems", + "//systems:system_utils", + "//systems/framework:lcm_driven_loop", "//systems/ros:franka_ros_channels", "//systems/ros:franka_ros_lcm_conversions", - "//systems/framework:lcm_driven_loop", - "//systems:system_utils", + "//systems/ros:ros_pubsub_systems", "@drake//:drake_shared_library", - "@ros", "@gflags", + "@ros", ], - tags = ["ros"], ) cc_library( name = "franka_lcm_channels", hdrs = ["parameters/franka_lcm_channels.h"], - deps = [ - "@drake//:drake_shared_library", - ], data = [ "parameters/lcm_channels_hardware.yaml", "parameters/lcm_channels_simulation.yaml", - ] + ], + deps = [ + "@drake//:drake_shared_library", + ], ) cc_library( name = "franka_sim_params", hdrs = ["parameters/franka_sim_params.h"], + data = [ + "parameters/franka_sim_params.yaml", + ], deps = [ "@drake//:drake_shared_library", ], - data = [ - "parameters/franka_sim_params.yaml", - ] ) cc_library( name = "franka_osc_controller_params", hdrs = ["parameters/franka_osc_controller_params.h"], + data = [ + "parameters/franka_osc_controller_params.yaml", + ], deps = [ "@drake//:drake_shared_library", ], - data = [ - "parameters/franka_osc_controller_params.yaml", - ] ) cc_library( name = "franka_c3_controller_params", hdrs = ["parameters/franka_c3_controller_params.h"], - deps = [ - "//solvers:c3", - "@drake//:drake_shared_library", - ], data = [ "parameters/franka_c3_controller_params.yaml", "parameters/franka_c3_options_floating.yaml", "parameters/franka_c3_options_translation.yaml", "parameters/franka_qp_options.yaml", - ] + ], + deps = [ + "//solvers:c3", + "@drake//:drake_shared_library", + ], ) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 058d631193..2d4bf9fadd 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -11,6 +11,7 @@ #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3_controller.h" +#include "systems/controllers/c3_trajectory_generator.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" @@ -181,6 +182,8 @@ int DoMain(int argc, char* argv[]) { auto controller = builder.AddSystem( plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); + auto c3_trajectory_generator = builder.AddSystem( + plant_plate, &plate_context, c3_options); controller->SetOsqpSolverOptions(solver_options); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); @@ -192,9 +195,11 @@ int DoMain(int argc, char* argv[]) { controller->get_input_port_state()); builder.Connect(radio_sub->get_output_port(), controller->get_input_port_radio()); - builder.Connect(controller->get_output_port_actor_trajectory(), + builder.Connect(controller->get_output_port_c3_solution(), + c3_trajectory_generator->get_input_port_c3_solution()); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), actor_trajectory_sender->get_input_port()); - builder.Connect(controller->get_output_port_object_trajectory(), + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); controller->SetPublishEndEffectorOrientation( diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults index 59651e0bf4502ddf28fa1e36475a17b414d7b199..92e6539977d88ce766f84b7ad237e339cfe8a50e 100644 GIT binary patch delta 39 vcmcc5e4lxO%4B)Q%83i=C(mG1ndlM0!;_zsm6}`_qbJU-pQutfS%y(XStvCxB|bGREj76$zbL+>C^3rx2zc_7 JvVbBGJ^+t{6oUW& diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 94c889314c..bfac7e7341 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -4,10 +4,10 @@ cc_library( name = "franka_systems", srcs = [], deps = [ - ":end_effector_trajectory", ":end_effector_orientation", - ":franka_kinematics" - ], + ":end_effector_trajectory", + ":franka_kinematics", + ], ) cc_library( @@ -36,29 +36,41 @@ cc_library( ], ) +cc_library( + name = "plate_balancing_target", + srcs = ["plate_balancing_target.cc"], + hdrs = ["plate_balancing_target.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + cc_library( name = "franka_kinematics", srcs = ["franka_kinematics.cc"], hdrs = ["franka_kinematics.h"], deps = [ - "//lcmtypes:lcmt_robot", ":franka_kinematics_vector", "//common", + "//lcmtypes:lcmt_robot", "//multibody:utils", "//systems/primitives", "@drake//:drake_shared_library", ], ) - cc_library( name = "franka_sim_controls", srcs = ["franka_sim_controls.cc"], hdrs = ["franka_sim_controls.h"], deps = [ - "//lcmtypes:lcmt_robot", ":franka_kinematics_vector", "//common", + "//lcmtypes:lcmt_robot", "//multibody:utils", "//systems/primitives", "@drake//:drake_shared_library", diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc new file mode 100644 index 0000000000..228eb3e3a5 --- /dev/null +++ b/examples/franka/systems/plate_balancing_target.cc @@ -0,0 +1,106 @@ +#include "plate_balancing_target.h" + +#include + +#include "dairlib/lcmt_radio_out.hpp" +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::Vector4d; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::BodyFrame; +using drake::multibody::Frame; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib { + +PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( + const MultibodyPlant& plant, Context* context) + : plant_(plant), context_(context), world_(plant.world_frame()) { + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + PiecewisePolynomial pp = PiecewisePolynomial(); + + trajectory_port_ = + this->DeclareAbstractInputPort( + "trajectory", + drake::Value>(pp)) + .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + PiecewisePolynomial empty_pp_traj(VectorXd(0)); + Trajectory& traj_inst = empty_pp_traj; + this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, + &PlateBalancingTargetGenerator::CalcTraj); +} + +void PlateBalancingTargetGenerator::SetRemoteControlParameters( + const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale){ + neutral_pose_ = neutral_pose; + x_scale_ = x_scale; + y_scale_ = y_scale; + z_scale_ = z_scale; +} + +PiecewisePolynomial PlateBalancingTargetGenerator::GeneratePose( + const drake::systems::Context& context) const { + const auto robot_output = + this->template EvalVectorInput(context, state_port_); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + double t = robot_output->get_timestamp(); + double dt = 0.1; + VectorXd y0 = neutral_pose_; + y0(0) += radio_out->channel[0] * x_scale_; + y0(1) += radio_out->channel[1] * y_scale_; + y0(2) += radio_out->channel[2] * z_scale_; + VectorXd ydot0 = VectorXd::Zero(3); + std::vector breaks = {t, t + dt}; + std::vector samples = {y0, y0 + dt * ydot0}; + return drake::trajectories::PiecewisePolynomial::FirstOrderHold( + breaks, samples); +} + +void PlateBalancingTargetGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // // Read in finite state machine + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (radio_out->channel[14]) { + *casted_traj = GeneratePose(context); + } else { + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + // *casted_traj = GenerateCircle(context); + // *casted_traj = GenerateLine(context); + } +} + +} // namespace dairlib diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h new file mode 100644 index 0000000000..f0fe03d3a2 --- /dev/null +++ b/examples/franka/systems/plate_balancing_target.h @@ -0,0 +1,61 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class PlateBalancingTargetGenerator + : public drake::systems::LeafSystem { + public: + PlateBalancingTargetGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, double x_scale, + double y_scale, double z_scale); + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + drake::trajectories::PiecewisePolynomial GenerateCircle( + const drake::systems::Context& context) const; + drake::trajectories::PiecewisePolynomial GeneratePose( + const drake::systems::Context& context) const; + drake::trajectories::PiecewisePolynomial GenerateLine( + const drake::systems::Context& context) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::Frame& world_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex trajectory_port_; + drake::systems::InputPortIndex radio_port_; + + Eigen::Vector3d neutral_pose_; + double x_scale_; + double y_scale_; + double z_scale_; + std::vector half_plane_bounds_; +}; + +} // namespace dairlib diff --git a/lcmtypes/lcmt_c3_intermediates.lcm b/lcmtypes/lcmt_c3_intermediates.lcm new file mode 100644 index 0000000000..684e2e10e7 --- /dev/null +++ b/lcmtypes/lcmt_c3_intermediates.lcm @@ -0,0 +1,11 @@ +package dairlib; + +struct lcmt_c3_intermediates +{ + int32_t num_points; + int32_t num_total_variables; + + float time_vec[num_points]; + float delta_sol[num_total_variables][num_points]; + float w_sol[num_total_variables][num_points]; +} \ No newline at end of file diff --git a/lcmtypes/lcmt_c3_output.lcm b/lcmtypes/lcmt_c3_output.lcm new file mode 100644 index 0000000000..b82b674801 --- /dev/null +++ b/lcmtypes/lcmt_c3_output.lcm @@ -0,0 +1,9 @@ +package dairlib; + +struct lcmt_c3_output +{ + int64_t utime; + + lcmt_c3_solution c3_solution; + lcmt_c3_intermediates c3_intermediates; +} diff --git a/lcmtypes/lcmt_c3_solution.lcm b/lcmtypes/lcmt_c3_solution.lcm new file mode 100644 index 0000000000..9648477032 --- /dev/null +++ b/lcmtypes/lcmt_c3_solution.lcm @@ -0,0 +1,14 @@ +package dairlib; + +struct lcmt_c3_solution +{ + int32_t num_points; + int32_t num_state_variables; + int32_t num_contact_variables; + int32_t num_input_variables; + + float time_vec[num_points]; + float x_sol[num_state_variables][num_points]; + float lambda_sol[num_contact_variables][num_points]; + float u_sol[num_input_variables][num_points]; +} diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index ebc3d18b4d..398ee6f58f 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -44,6 +44,20 @@ cc_library( ], ) +cc_library( + name = "c3_output", + srcs = [ + "c3_output.cc", + ], + hdrs = [ + "c3_output.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "lcs", srcs = [ diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc new file mode 100644 index 0000000000..710a14208b --- /dev/null +++ b/solvers/c3_output.cc @@ -0,0 +1,5 @@ +// +// Created by yangwill on 11/3/23. +// + +#include "c3_output.h" diff --git a/solvers/c3_output.h b/solvers/c3_output.h new file mode 100644 index 0000000000..9996c2026a --- /dev/null +++ b/solvers/c3_output.h @@ -0,0 +1,56 @@ +#pragma once + +#include +#include +#include +#include + +#include + +#include "dairlib/lcmt_c3_output.hpp" + +#include "drake/systems/lcm/serializer.h" + +namespace dairlib { + +/// Used for outputting c3 solutions and intermediate variables for debugging purposes + +class C3Output { + public: + struct C3Solution { + C3Solution() = default; +// C3Solution(Eigen::VectorXd time_vector_, Eigen::MatrixXd x_sol_, +// Eigen::MatrixXd lambda_sol_, Eigen::MatrixXd u_sol_); + + Eigen::VectorXd time_vector_; + Eigen::MatrixXd x_sol_; + Eigen::MatrixXd lambda_sol_; + Eigen::MatrixXd u_sol_; + }; + + struct C3Intermediates { + C3Intermediates() = default; +// C3Intermediates(Eigen::VectorXd time_vector_, Eigen::MatrixXd delta_, +// Eigen::MatrixXd w_); + + Eigen::VectorXd time_vector_; + Eigen::MatrixXd delta_; + Eigen::MatrixXd w_; + }; + + C3Output() = default; + C3Output(C3Solution c3_sol, C3Intermediates c3_intermediates); + + explicit C3Output(const lcmt_c3_output& traj); + + virtual ~C3Output() = default; + + lcmt_c3_output GenerateLcmObject() const; + + protected: + private: + C3Solution c3_solution_; + C3Intermediates c3_intermediates_; +}; + +} // namespace dairlib From 7ab1739ec2b0d9f05f6ef26170b0d1c62c87fedf Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 13:56:34 -0400 Subject: [PATCH 499/758] forgot to commit c3 systems in previous commit --- systems/controllers/BUILD.bazel | 33 ++++- systems/controllers/c3_controller.cc | 126 ++++------------ systems/controllers/c3_controller.h | 30 ++-- .../controllers/c3_trajectory_generator.cc | 134 ++++++++++++++++++ systems/controllers/c3_trajectory_generator.h | 78 ++++++++++ 5 files changed, 283 insertions(+), 118 deletions(-) create mode 100644 systems/controllers/c3_trajectory_generator.cc create mode 100644 systems/controllers/c3_trajectory_generator.h diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 6f0a33fa37..ce8c2c827f 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -53,21 +53,40 @@ cc_library( cc_library( name = "c3_controller", + srcs = ["c3_controller.cc"], + hdrs = ["c3_controller.h"], + deps = [ + "//common:find_resource", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//solvers:c3", + "//solvers:c3_output", + "//solvers:solver_options_io", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "c3_trajectory_generator", srcs = [ - "c3_controller.cc", + "c3_trajectory_generator.cc", ], hdrs = [ - "c3_controller.h", + "c3_trajectory_generator.h", ], deps = [ - "//systems/framework:vector", + "//common:find_resource", "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", - "//solvers:c3", - "//common:find_resource", "//multibody:utils", + "//solvers:c3", + "//solvers:c3_output", "//solvers:solver_options_io", - "//lcm:lcm_trajectory_saver", + "//systems/framework:vector", "@drake//:drake_shared_library", ], ) @@ -135,8 +154,8 @@ cc_library( deps = [ ":affine_controller", ":constrained_lqr_controller", - ":linear_controller", ":gravity_compensator", + ":linear_controller", ], ) diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index d89687a17c..7c5dc5a5b7 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -6,7 +6,6 @@ #include #include "common/find_resource.h" -#include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" @@ -75,17 +74,24 @@ C3Controller::C3Controller( this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); - - actor_trajectory_port_ = - this->DeclareAbstractOutputPort("c3_actor_trajectory_output", - dairlib::lcmt_timestamped_saved_traj(), - &C3Controller::OutputActorTrajectory) + auto c3_solution = C3Output::C3Solution(); + c3_solution.x_sol_ = MatrixXd::Zero(n_q_ + n_v_, N_); + c3_solution.lambda_sol_ = MatrixXd::Zero(n_lambda_, N_); + c3_solution.u_sol_ = MatrixXd::Zero(n_u_, N_); + c3_solution.time_vector_ = VectorXd::Zero(N_); + auto c3_intermediates = C3Output::C3Intermediates(); + c3_intermediates.w_ = MatrixXd::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.delta_ = MatrixXd::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.time_vector_ = VectorXd::Zero(N_); + c3_solution_port_ = + this->DeclareAbstractOutputPort("c3_solution", c3_solution, + &C3Controller::OutputC3Solution) .get_index(); - object_trajectory_port_ = - this->DeclareAbstractOutputPort("c3_object_trajectory_output", - dairlib::lcmt_timestamped_saved_traj(), - &C3Controller::OutputObjectTrajectory) + c3_intermediates_port_ = + this->DeclareAbstractOutputPort("c3_intermediates", c3_intermediates, + &C3Controller::OutputC3Intermediates) .get_index(); + plan_start_time_index_ = DeclareDiscreteState(1); DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); } @@ -114,10 +120,9 @@ drake::systems::EventStatus C3Controller::ComputePlan( current(1) += radio_out->channel[1] * 0.2; current(2) += radio_out->channel[2] * 0.2; x_des_adjusted.head(n_q_).tail(3) = current; - if (radio_out->channel[13] > 0){ + if (radio_out->channel[13] > 0) { x_des_adjusted.head(3) = current; } - // std::cout << x_des_adjusted.transpose() << std::endl; std::vector x_desired = std::vector(N_ + 1, x_des_adjusted); @@ -160,106 +165,35 @@ drake::systems::EventStatus C3Controller::ComputePlan( c3_->AddLinearConstraint(A, -0.4, 0.4, 1); } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); + delta_ = delta; + w_ = w; return drake::systems::EventStatus::Succeeded(); } -void C3Controller::OutputActorTrajectory( +void C3Controller::OutputC3Solution( const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const { + C3Output::C3Solution* c3_solution) const { double t = context.get_discrete_state(plan_start_time_index_)[0]; auto z_sol = c3_->GetFullSolution(); - MatrixXd x_sol = MatrixXd::Zero(n_q_ + n_v_, N_); - MatrixXd lambda_sol = MatrixXd::Zero(n_lambda_, N_); - MatrixXd u_sol = MatrixXd::Zero(n_u_, N_); - VectorXd breaks = VectorXd::Zero(N_); - for (int i = 0; i < N_; i++) { - breaks(i) = t + i * c3_options_.dt; - x_sol.col(i) = z_sol[i].segment(0, n_x_); - lambda_sol.col(i) = z_sol[i].segment(n_x_, n_lambda_); - u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); + c3_solution->time_vector_(i) = t + i * c3_options_.dt; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_); + c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_); + c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); } - - MatrixXd knots = MatrixXd::Zero(6, N_); - knots.topRows(3) = x_sol.topRows(3); - knots.bottomRows(3) = x_sol.bottomRows(n_v_).topRows(3); - LcmTrajectory::Trajectory end_effector_traj; - end_effector_traj.traj_name = "end_effector_traj"; - end_effector_traj.datatypes = - std::vector(knots.rows(), "double"); - end_effector_traj.datapoints = knots; - end_effector_traj.time_vector = breaks; - LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_traj"}, - "end_effector_traj", "end_effector_traj", false); - - if (publish_end_effector_orientation_) { - LcmTrajectory::Trajectory end_effector_orientation_traj; - // first 3 rows are rpy, last 3 rows are angular velocity - MatrixXd orientation_samples = MatrixXd::Zero(6, N_); - orientation_samples.topRows(3) = x_sol.topRows(6).bottomRows(3); - orientation_samples.bottomRows(3) = - x_sol.bottomRows(n_v_).topRows(6).bottomRows(3); - end_effector_orientation_traj.traj_name = "end_effector_orientation_target"; - end_effector_orientation_traj.datatypes = - std::vector(orientation_samples.rows(), "double"); - end_effector_orientation_traj.datapoints = orientation_samples; - end_effector_orientation_traj.time_vector = breaks; - lcm_traj.AddTrajectory(end_effector_orientation_traj.traj_name, - std::move(end_effector_orientation_traj)); - } - - output_traj->saved_traj = lcm_traj.GenerateLcmObject(); - output_traj->utime = t * 1e6; } -void C3Controller::OutputObjectTrajectory( +void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const { - // TODO:yangwill, check to make sure the time being used here makes sense + C3Output::C3Intermediates* c3_intermediates) const { double t = context.get_discrete_state(plan_start_time_index_)[0]; - auto z_sol = c3_->GetFullSolution(); - MatrixXd x_sol = MatrixXd::Zero(n_q_ + n_v_, N_); - MatrixXd lambda_sol = MatrixXd::Zero(n_lambda_, N_); - MatrixXd u_sol = MatrixXd::Zero(n_u_, N_); - VectorXd breaks = VectorXd::Zero(N_); - for (int i = 0; i < N_; i++) { - breaks(i) = t + i * c3_options_.dt; - x_sol.col(i) = z_sol[i].segment(0, n_x_); - lambda_sol.col(i) = z_sol[i].segment(n_x_, n_lambda_); - u_sol.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); - } - - MatrixXd knots = MatrixXd::Zero(6, N_); - knots.topRows(3) = x_sol.middleRows(n_q_ - 3, 3); - knots.bottomRows(3) = x_sol.middleRows(n_q_ + n_v_ - 3, 3); - LcmTrajectory::Trajectory object_traj; - object_traj.traj_name = "object_traj"; - object_traj.datatypes = std::vector(knots.rows(), "double"); - object_traj.datapoints = knots; - object_traj.time_vector = breaks; - LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, "object_traj", - "object_traj", false); - - if (publish_end_effector_orientation_) { - LcmTrajectory::Trajectory object_orientation_traj; - // first 3 rows are rpy, last 3 rows are angular velocity - MatrixXd orientation_samples = MatrixXd::Zero(7, N_); - orientation_samples.topRows(4) = x_sol.middleRows(3 + 3, 4); - orientation_samples.bottomRows(3) = x_sol.middleRows(n_q_ + 3 + 3, 3); - object_orientation_traj.traj_name = "object_orientation_target"; - object_orientation_traj.datatypes = - std::vector(orientation_samples.rows(), "double"); - object_orientation_traj.datapoints = orientation_samples; - object_orientation_traj.time_vector = breaks; - lcm_traj.AddTrajectory(object_orientation_traj.traj_name, - std::move(object_orientation_traj)); + c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; + c3_intermediates->w_.col(i) = w_[i]; + c3_intermediates->delta_.col(i) = delta_[i]; } - - output_traj->saved_traj = lcm_traj.GenerateLcmObject(); - output_traj->utime = t * 1e6; } } // namespace systems diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index fc61778849..ea59bf413b 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -12,6 +12,7 @@ #include "solvers/c3.h" #include "solvers/c3_miqp.h" #include "solvers/c3_options.h" +#include "solvers/c3_output.h" #include "solvers/lcs.h" #include "solvers/solver_options_io.h" #include "systems/framework/timestamped_vector.h" @@ -41,13 +42,13 @@ class C3Controller : public drake::systems::LeafSystem { return this->get_input_port(lcs_state_input_port_); } - const drake::systems::OutputPort& get_output_port_actor_trajectory() + const drake::systems::OutputPort& get_output_port_c3_solution() const { - return this->get_output_port(actor_trajectory_port_); + return this->get_output_port(c3_solution_port_); } - const drake::systems::OutputPort& get_output_port_object_trajectory() + const drake::systems::OutputPort& get_output_port_c3_intermediates() const { - return this->get_output_port(object_trajectory_port_); + return this->get_output_port(c3_intermediates_port_); } const drake::systems::InputPort& get_input_port_radio() const { @@ -63,23 +64,21 @@ class C3Controller : public drake::systems::LeafSystem { } private: - void OutputActorTrajectory( - const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const; - - void OutputObjectTrajectory( - const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const; - drake::systems::EventStatus ComputePlan( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; + void OutputC3Solution(const drake::systems::Context& context, + C3Output::C3Solution* c3_solution) const; + + void OutputC3Intermediates(const drake::systems::Context& context, + C3Output::C3Intermediates* c3_intermediates) const; + drake::systems::InputPortIndex target_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::InputPortIndex radio_port_; - drake::systems::OutputPortIndex actor_trajectory_port_; - drake::systems::OutputPortIndex object_trajectory_port_; + drake::systems::OutputPortIndex c3_solution_port_; + drake::systems::OutputPortIndex c3_intermediates_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; @@ -93,7 +92,6 @@ class C3Controller : public drake::systems::LeafSystem { FindResourceOrThrow("solvers/osqp_options_default.yaml")) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - // bool publish_end_effector_orientation_ = false; // convenience for variable sizes @@ -104,6 +102,8 @@ class C3Controller : public drake::systems::LeafSystem { int n_u_; mutable std::unique_ptr c3_; + mutable std::vector delta_; + mutable std::vector w_; // std::unique_ptr lcs_; drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; diff --git a/systems/controllers/c3_trajectory_generator.cc b/systems/controllers/c3_trajectory_generator.cc new file mode 100644 index 0000000000..f3918643d2 --- /dev/null +++ b/systems/controllers/c3_trajectory_generator.cc @@ -0,0 +1,134 @@ +#include "c3_trajectory_generator.h" + +#include +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "examples/franka/systems/franka_kinematics_vector.h" +#include "multibody/multibody_utils.h" + +#include "solvers/c3_output.h" + +namespace dairlib { + +using drake::multibody::ModelInstanceIndex; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteValues; +using Eigen::VectorXd; +using systems::TimestampedVector; + +namespace systems { + +C3TrajectoryGenerator::C3TrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, C3Options c3_options) + : plant_(plant), + context_(context), + c3_options_(std::move(c3_options)), + N_(c3_options_.N) { + this->set_name("c3_trajectory_generator"); + + n_q_ = plant_.num_positions(); + n_v_ = plant_.num_velocities(); + n_x_ = n_q_ + n_v_; + n_lambda_ = + 2 * c3_options_.num_contacts + + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + n_u_ = plant_.num_actuators(); + + c3_solution_port_ = + this->DeclareAbstractInputPort("c3_solution", drake::Value()) + .get_index(); + + actor_trajectory_port_ = + this->DeclareAbstractOutputPort( + "c3_actor_trajectory_output", + dairlib::lcmt_timestamped_saved_traj(), + &C3TrajectoryGenerator::OutputActorTrajectory) + .get_index(); + object_trajectory_port_ = + this->DeclareAbstractOutputPort( + "c3_object_trajectory_output", + dairlib::lcmt_timestamped_saved_traj(), + &C3TrajectoryGenerator::OutputObjectTrajectory) + .get_index(); +} + +void C3TrajectoryGenerator::OutputActorTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const { + const auto& c3_solution = + this->EvalInputValue(context, c3_solution_port_); + + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = c3_solution->x_sol_.topRows(3); + knots.bottomRows(3) = c3_solution->x_sol_.bottomRows(n_v_).topRows(3); + LcmTrajectory::Trajectory end_effector_traj; + end_effector_traj.traj_name = "end_effector_traj"; + end_effector_traj.datatypes = + std::vector(knots.rows(), "double"); + end_effector_traj.datapoints = knots; + end_effector_traj.time_vector = c3_solution->time_vector_; + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_traj"}, + "end_effector_traj", "end_effector_traj", false); + + if (publish_end_effector_orientation_) { + LcmTrajectory::Trajectory end_effector_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(6, N_); + orientation_samples.topRows(3) = c3_solution->x_sol_.topRows(6).bottomRows(3); + orientation_samples.bottomRows(3) = + c3_solution->x_sol_.bottomRows(n_v_).topRows(6).bottomRows(3); + end_effector_orientation_traj.traj_name = "end_effector_orientation_target"; + end_effector_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + end_effector_orientation_traj.datapoints = orientation_samples; + end_effector_orientation_traj.time_vector = c3_solution->time_vector_; + lcm_traj.AddTrajectory(end_effector_orientation_traj.traj_name, + std::move(end_effector_orientation_traj)); + } + + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_traj->utime = context.get_time() * 1e6; +} + +void C3TrajectoryGenerator::OutputObjectTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const { + const auto& c3_solution = + this->EvalInputValue(context, c3_solution_port_); + + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3); + knots.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3); + LcmTrajectory::Trajectory object_traj; + object_traj.traj_name = "object_traj"; + object_traj.datatypes = std::vector(knots.rows(), "double"); + object_traj.datapoints = knots; + object_traj.time_vector = c3_solution->time_vector_; + LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, "object_traj", + "object_traj", false); + + if (publish_end_effector_orientation_) { + LcmTrajectory::Trajectory object_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(7, N_); + orientation_samples.topRows(4) = c3_solution->x_sol_.middleRows(3 + 3, 4); + orientation_samples.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + 3 + 3, 3); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = c3_solution->time_vector_; + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + std::move(object_orientation_traj)); + } + + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_traj->utime = context.get_time() * 1e6; +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/c3_trajectory_generator.h b/systems/controllers/c3_trajectory_generator.h new file mode 100644 index 0000000000..1fb38b633e --- /dev/null +++ b/systems/controllers/c3_trajectory_generator.h @@ -0,0 +1,78 @@ +#pragma once + +#include +#include + +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_saved_traj.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "lcm/lcm_trajectory.h" +#include "solvers/c3_options.h" +#include "solvers/lcs.h" +#include "solvers/solver_options_io.h" +#include "systems/framework/timestamped_vector.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// Outputs a lcmt_timestamped_saved_traj +class C3TrajectoryGenerator : public drake::systems::LeafSystem { + public: + explicit C3TrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, C3Options c3_options); + + const drake::systems::InputPort& get_input_port_c3_solution() const { + return this->get_input_port(c3_solution_port_); + } + + const drake::systems::OutputPort& get_output_port_actor_trajectory() + const { + return this->get_output_port(actor_trajectory_port_); + } + const drake::systems::OutputPort& get_output_port_object_trajectory() + const { + return this->get_output_port(object_trajectory_port_); + } + + void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { + publish_end_effector_orientation_ = publish_end_effector_orientation; + } + + private: + void OutputActorTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const; + + void OutputObjectTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const; + + drake::systems::InputPortIndex c3_solution_port_; + drake::systems::OutputPortIndex actor_trajectory_port_; + drake::systems::OutputPortIndex object_trajectory_port_; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + C3Options c3_options_; + + bool publish_end_effector_orientation_ = false; + + // convenience for variable sizes + int n_q_; + int n_v_; + int n_x_; + int n_lambda_; + int n_u_; + + // std::unique_ptr lcs_; + drake::systems::DiscreteStateIndex plan_start_time_index_; + int N_; +}; + +} // namespace systems +} // namespace dairlib From 03bff15381c4df00da423d4eb543a23580df0137 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 14:01:54 -0400 Subject: [PATCH 500/758] moving franka traj generator to appropriate place --- examples/franka/BUILD.bazel | 2 +- examples/franka/franka_c3_controller.cc | 2 +- examples/franka/franka_osc_controller.cc | 2 +- examples/franka/systems/BUILD.bazel | 22 +++++++++++++++++++ .../systems}/c3_trajectory_generator.cc | 2 +- .../franka/systems}/c3_trajectory_generator.h | 0 systems/controllers/BUILD.bazel | 22 ------------------- 7 files changed, 26 insertions(+), 26 deletions(-) rename {systems/controllers => examples/franka/systems}/c3_trajectory_generator.cc (98%) rename {systems/controllers => examples/franka/systems}/c3_trajectory_generator.h (100%) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 17fef4186e..00738c8c3c 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -70,13 +70,13 @@ cc_binary( ":franka_c3_controller_params", ":franka_lcm_channels", "//common", + "//examples/franka/systems:c3_trajectory_generator", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", "//systems/controllers:c3_controller", - "//systems/controllers:c3_trajectory_generator", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", "@drake//:drake_shared_library", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 2d4bf9fadd..606f99a1ef 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -11,7 +11,7 @@ #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3_controller.h" -#include "systems/controllers/c3_trajectory_generator.h" +#include "examples/franka/systems/c3_trajectory_generator.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 7019185e1d..d068dd791a 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -116,7 +116,7 @@ int DoMain(int argc, char* argv[]) { orientation_traj.traj_name = "end_effector_orientation_target"; orientation_traj.datatypes = std::vector(2, "orientation"); lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); - lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); +// lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index bfac7e7341..365b39b326 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -49,6 +49,28 @@ cc_library( ], ) +cc_library( + name = "c3_trajectory_generator", + srcs = [ + "c3_trajectory_generator.cc", + ], + hdrs = [ + "c3_trajectory_generator.h", + ], + deps = [ + "//common:find_resource", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//solvers:c3", + "//solvers:c3_output", + "//solvers:solver_options_io", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "franka_kinematics", srcs = ["franka_kinematics.cc"], diff --git a/systems/controllers/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc similarity index 98% rename from systems/controllers/c3_trajectory_generator.cc rename to examples/franka/systems/c3_trajectory_generator.cc index f3918643d2..f5184c0c8c 100644 --- a/systems/controllers/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -1,4 +1,4 @@ -#include "c3_trajectory_generator.h" +#include "examples/franka/systems/c3_trajectory_generator.h" #include #include diff --git a/systems/controllers/c3_trajectory_generator.h b/examples/franka/systems/c3_trajectory_generator.h similarity index 100% rename from systems/controllers/c3_trajectory_generator.h rename to examples/franka/systems/c3_trajectory_generator.h diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index ce8c2c827f..25b469728a 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -69,28 +69,6 @@ cc_library( ], ) -cc_library( - name = "c3_trajectory_generator", - srcs = [ - "c3_trajectory_generator.cc", - ], - hdrs = [ - "c3_trajectory_generator.h", - ], - deps = [ - "//common:find_resource", - "//examples/franka/systems:franka_systems", - "//lcm:lcm_trajectory_saver", - "//lcmtypes:lcmt_robot", - "//multibody:utils", - "//solvers:c3", - "//solvers:c3_output", - "//solvers:solver_options_io", - "//systems/framework:vector", - "@drake//:drake_shared_library", - ], -) - cc_library( name = "gravity_compensator", srcs = [ From 0555e65a516781be90d18f043329935261ed1621 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 14:07:45 -0400 Subject: [PATCH 501/758] running buildifier to clean up BUILD files --- bindings/pydairlib/analysis/BUILD.bazel | 3 +- .../impact_invariant_control/BUILD.bazel | 15 ++++----- bindings/pydairlib/cassie/BUILD.bazel | 14 ++++---- .../pydairlib/cassie/gym_envs/BUILD.bazel | 30 ++++++++--------- bindings/pydairlib/cassie/mujoco/BUILD.bazel | 6 ++-- bindings/pydairlib/lcm/BUILD.bazel | 5 ++- .../pydairlib/lcm/visualization/BUILD.bazel | 12 +++---- bindings/pydairlib/multibody/BUILD.bazel | 4 +-- director/BUILD.bazel | 2 +- examples/Cassie/BUILD.bazel | 32 +++++++++---------- examples/Cassie/contact_scheduler/BUILD.bazel | 10 +++--- examples/Cassie/diagrams/BUILD.bazel | 24 +++++++------- examples/Cassie/osc/BUILD.bazel | 6 ++-- examples/Cassie/osc_run/BUILD.bazel | 7 ++-- signalscope/BUILD.bazel | 4 +-- systems/controllers/osc/BUILD.bazel | 2 +- systems/primitives/BUILD.bazel | 2 +- systems/ros/BUILD.bazel | 5 ++- systems/trajectory_optimization/BUILD.bazel | 4 +-- 19 files changed, 90 insertions(+), 97 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index b09e44c826..f17a75ceb6 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -82,7 +82,7 @@ py_library( "@lcm//:lcm-python", ], deps = [ - "//bindings/pydairlib/cassie:cassie", + "//bindings/pydairlib/cassie", "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", @@ -132,7 +132,6 @@ py_binary( ], ) - # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") diff --git a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel index 58a2a15599..f6e3b5bddc 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel +++ b/bindings/pydairlib/analysis/impact_invariant_control/BUILD.bazel @@ -18,19 +18,18 @@ py_binary( "@lcm//:lcm-python", ], deps = [ - "//bindings/pydairlib/cassie:cassie_utils_py", - "//bindings/pydairlib/common", - "//bindings/pydairlib/lcm:process_lcm_log", "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/analysis:osc_debug_py", + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", "//bindings/pydairlib/lcm", + "//bindings/pydairlib/lcm:process_lcm_log", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", "//lcmtypes:lcmtypes_robot_py", ], ) - py_binary( name = "jumping_parameter_study", srcs = ["jumping_parameter_study.py"], @@ -38,13 +37,13 @@ py_binary( "@lcm//:lcm-python", ], deps = [ - "//bindings/pydairlib/cassie:cassie_utils_py", - "//bindings/pydairlib/common", - "//bindings/pydairlib/lcm:process_lcm_log", - "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/analysis:cassie_plotting_utils", + "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/analysis:osc_debug_py", + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", "//bindings/pydairlib/lcm", + "//bindings/pydairlib/lcm:process_lcm_log", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", "//lcmtypes:lcmtypes_robot_py", diff --git a/bindings/pydairlib/cassie/BUILD.bazel b/bindings/pydairlib/cassie/BUILD.bazel index bccab2efd8..5a0b396612 100644 --- a/bindings/pydairlib/cassie/BUILD.bazel +++ b/bindings/pydairlib/cassie/BUILD.bazel @@ -11,7 +11,6 @@ load( "pybind_py_library", ) - pybind_py_library( name = "cassie_utils_py", cc_deps = [ @@ -46,9 +45,9 @@ pybind_py_library( pybind_py_library( name = "controllers_py", cc_deps = [ - "@drake//:drake_shared_library", "//examples/Cassie/diagrams:osc_running_controller_diagram", "//examples/Cassie/diagrams:osc_walking_controller_diagram", + "@drake//:drake_shared_library", ], cc_so_name = "controllers", cc_srcs = ["controllers_py.cc"], @@ -62,13 +61,14 @@ pybind_py_library( pybind_py_library( name = "simulators_py", cc_deps = [ + "//examples/Cassie/diagrams:cassie_sim_diagram", "@drake//:drake_shared_library", "@drake//bindings/pydrake/common:value_pybind", - "//examples/Cassie/diagrams:cassie_sim_diagram", ], cc_so_name = "simulators", - cc_srcs = ["simulators_py.cc", - ], + cc_srcs = [ + "simulators_py.cc", + ], py_deps = [ "@drake//bindings/pydrake", "//bindings/pydairlib/lcm:lcm", @@ -81,8 +81,8 @@ py_binary( name = "learn_osc_gains", srcs = ["learn_osc_gains.py"], deps = [ + "//bindings/pydairlib/cassie", "//bindings/pydairlib/cassie/gym_envs:cassie_gym_all", - "//bindings/pydairlib/cassie:cassie", "@drake//bindings/pydrake", ], ) @@ -113,4 +113,4 @@ py_library( name = "cassie", imports = PACKAGE_INFO.py_imports, deps = PY_LIBRARIES, -) \ No newline at end of file +) diff --git a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel index bcb457bc78..889ddffedd 100644 --- a/bindings/pydairlib/cassie/gym_envs/BUILD.bazel +++ b/bindings/pydairlib/cassie/gym_envs/BUILD.bazel @@ -15,23 +15,22 @@ py_library( name = "cassie_gym_all", srcs = [], deps = [ + ":cassie_env_rewards", ":drake_cassie_gym", ":mujoco_cassie_gym", - ":cassie_env_rewards", ], ) - py_library( name = "drake_cassie_gym", srcs = ["drake_cassie_gym.py"], deps = [ - "//bindings/pydairlib/cassie:cassie", + ":cassie_env_state", "//bindings/pydairlib", - "//bindings/pydairlib/systems:systems", + "//bindings/pydairlib/cassie", "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems", "//bindings/pydairlib/systems:primitives_py", - ":cassie_env_state", ], ) @@ -39,9 +38,9 @@ py_binary( name = "cassie_gym_test", srcs = ["cassie_gym_test.py"], deps = [ - ":cassie_gym_all", ":cassie_env_rewards", - "//bindings/pydairlib/cassie:cassie", + ":cassie_gym_all", + "//bindings/pydairlib/cassie", "@drake//bindings/pydrake", ], ) @@ -62,24 +61,25 @@ py_library( py_library( name = "cassie_env_rewards", - srcs = ["reward_base.py", - "reward_osudrl.py"], + srcs = [ + "reward_base.py", + "reward_osudrl.py", + ], deps = [ - ":cassie_env_state" + ":cassie_env_state", ], ) - py_library( name = "mujoco_cassie_gym", srcs = ["mujoco_cassie_gym.py"], deps = [ - "//bindings/pydairlib/cassie:cassie", - "//bindings/pydairlib/cassie/mujoco:cassie_mujoco_all", + ":cassie_env_state", "//bindings/pydairlib", - "//bindings/pydairlib/systems:systems", + "//bindings/pydairlib/cassie", + "//bindings/pydairlib/cassie/mujoco:cassie_mujoco_all", "//bindings/pydairlib/multibody", + "//bindings/pydairlib/systems", "//bindings/pydairlib/systems:primitives_py", - ":cassie_env_state", ], ) diff --git a/bindings/pydairlib/cassie/mujoco/BUILD.bazel b/bindings/pydairlib/cassie/mujoco/BUILD.bazel index e74c661ec5..53d6928895 100644 --- a/bindings/pydairlib/cassie/mujoco/BUILD.bazel +++ b/bindings/pydairlib/cassie/mujoco/BUILD.bazel @@ -11,18 +11,16 @@ load( "pybind_py_library", ) - py_library( name = "cassie_mujoco_all", srcs = [], deps = [ - ":mujoco_lcm_utils", - ":drake_to_mujoco_converter", ":cassie_mujoco_py", + ":drake_to_mujoco_converter", + ":mujoco_lcm_utils", ], ) - py_library( name = "mujoco_lcm_utils", srcs = ["mujoco_lcm_utils.py"], diff --git a/bindings/pydairlib/lcm/BUILD.bazel b/bindings/pydairlib/lcm/BUILD.bazel index b1fd003b9f..425661d6e4 100644 --- a/bindings/pydairlib/lcm/BUILD.bazel +++ b/bindings/pydairlib/lcm/BUILD.bazel @@ -1,4 +1,4 @@ - # -*- python -*- +# -*- python -*- load("@drake//tools/install:install.bzl", "install") package(default_visibility = ["//visibility:public"]) @@ -11,13 +11,12 @@ load( "pybind_py_library", ) - pybind_py_library( name = "lcm_py", cc_deps = [ "//lcmtypes:lcmt_robot", - "@drake//bindings/pydrake/systems:lcm_pybind", "@drake//bindings/pydrake/common:value_pybind", + "@drake//bindings/pydrake/systems:lcm_pybind", ], cc_srcs = [ "lcm_py.cc", diff --git a/bindings/pydairlib/lcm/visualization/BUILD.bazel b/bindings/pydairlib/lcm/visualization/BUILD.bazel index e5de1218c0..8e7de61057 100644 --- a/bindings/pydairlib/lcm/visualization/BUILD.bazel +++ b/bindings/pydairlib/lcm/visualization/BUILD.bazel @@ -1,4 +1,4 @@ - # -*- python -*- +# -*- python -*- load("@drake//tools/install:install.bzl", "install") package(default_visibility = ["//visibility:public"]) @@ -31,11 +31,11 @@ py_binary( srcs = ["visualize_trajectory.py"], deps = [ ":visualize_params", + "//bindings/pydairlib/cassie:cassie_utils_py", + "//bindings/pydairlib/common", "//bindings/pydairlib/lcm", - "//lcmtypes:lcmtypes_robot_py", "//bindings/pydairlib/multibody", - "//bindings/pydairlib/common", - "//bindings/pydairlib/cassie:cassie_utils_py", + "//lcmtypes:lcmtypes_robot_py", ], ) @@ -43,10 +43,10 @@ py_binary( name = "dircon_trajectory_plotter", srcs = ["dircon_trajectory_plotter.py"], deps = [ - "//bindings/pydairlib/lcm", + "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", + "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:multibody_py", - "//bindings/pydairlib/cassie:cassie_utils_py", "//lcmtypes:lcmtypes_robot_py", ], ) diff --git a/bindings/pydairlib/multibody/BUILD.bazel b/bindings/pydairlib/multibody/BUILD.bazel index 0995b385bf..b586433253 100644 --- a/bindings/pydairlib/multibody/BUILD.bazel +++ b/bindings/pydairlib/multibody/BUILD.bazel @@ -15,14 +15,14 @@ pybind_py_library( name = "multibody_py", cc_deps = [ "//multibody:multipose_visualizer", - "//multibody:visualization_utils", "//multibody:utils", + "//multibody:visualization_utils", "@drake//:drake_shared_library", ], cc_so_name = "multibody", cc_srcs = ["multibody_py.cc"], py_deps = [ -# "@drake//bindings/pydrake", + # "@drake//bindings/pydrake", ":module_py", ], py_imports = ["."], diff --git a/director/BUILD.bazel b/director/BUILD.bazel index 689d1bc680..1d76f15ba9 100644 --- a/director/BUILD.bazel +++ b/director/BUILD.bazel @@ -8,7 +8,7 @@ py_binary( deps = [ "//lcmtypes:lcmtypes_robot_py", "@drake//tools:drake_visualizer_py", -# "//bindings/pydairlib/multibody:multibody_py", + # "//bindings/pydairlib/multibody:multibody_py", "@pydrake_pegged", ], ) diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index 0132877122..a32c0ff340 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -66,7 +66,7 @@ cc_library( hdrs = ["cassie_state_estimator_settings.h"], deps = [ "@drake//:drake_shared_library", - ] + ], ) cc_library( @@ -75,9 +75,9 @@ cc_library( hdrs = ["cassie_state_estimator.h"], deps = [ ":cassie_utils", + "//examples/Cassie:cassie_state_estimator_settings", "//examples/Cassie/datatypes:cassie_names", "//examples/Cassie/datatypes:cassie_out_t", - "//examples/Cassie:cassie_state_estimator_settings", "//multibody:utils", "//multibody/kinematic", "//systems/framework:vector", @@ -185,9 +185,9 @@ cc_binary( "//examples/Cassie/systems:cassie_encoder", "//solvers:optimization_utils", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/framework:geared_motor", "//systems/primitives", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -249,9 +249,9 @@ cc_binary( "//lcmtypes:lcmt_robot", "//multibody:multibody_solvers", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/framework:lcm_driven_loop", "//systems/primitives", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -269,9 +269,9 @@ cc_binary( "//examples/Cassie/systems:input_supervisor", "//lcmtypes:lcmt_robot", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/controllers:linear_controller", "//systems/controllers:pd_config_lcm", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -296,8 +296,8 @@ cc_binary( deps = [ "//lcmtypes:lcmt_robot", "@drake//lcm", - "@lcm", "@gflags", + "@lcm", ], ) @@ -307,8 +307,8 @@ cc_binary( deps = [ "//lcmtypes:lcmt_robot", "@drake//lcm", - "@lcm", "@gflags", + "@lcm", ], ) @@ -350,18 +350,18 @@ cc_binary( deps = [ ":cassie_urdf", ":cassie_utils", - "//examples/Cassie/osc", "//examples/Cassie/contact_scheduler:all", - "//examples/Cassie/systems:cassie_out_to_radio", + "//examples/Cassie/osc", "//examples/Cassie/osc_jump", "//examples/Cassie/osc_run", + "//examples/Cassie/systems:cassie_out_to_radio", "//lcm:trajectory_saver", "//multibody:utils", "//systems:robot_lcm_systems", "//systems:system_utils", - "//systems/filters:floating_base_velocity_filter", - "//systems/controllers/osc:osc_tracking_datas", "//systems/controllers:controllers_all", + "//systems/controllers/osc:osc_tracking_datas", + "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", @@ -382,11 +382,11 @@ cc_binary( "//multibody:view_frame", "//multibody/kinematic", "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers:controllers_all", "//systems/controllers:fsm_event_time", "//systems/framework:lcm_driven_loop", "//systems/primitives", - "//systems/controllers:controllers_all", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], @@ -399,17 +399,17 @@ cc_binary( ":cassie_urdf", ":cassie_utils", "//examples/Cassie/osc", - "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//examples/Cassie/systems:cassie_out_to_radio", "//examples/Cassie/systems:simulator_drift", + "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//multibody:utils", "//multibody:view_frame", "//multibody/kinematic", "//solvers:solver_options_io", "//systems:robot_lcm_systems", "//systems:system_utils", - "//systems/controllers:fsm_event_time", "//systems/controllers:controllers_all", + "//systems/controllers:fsm_event_time", "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", @@ -429,11 +429,11 @@ cc_binary( "//multibody:utils", "//multibody/kinematic", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/controllers/osc:operational_space_control", "//systems/controllers/osc:osc_gains", "//systems/framework:lcm_driven_loop", "//systems/primitives", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/contact_scheduler/BUILD.bazel b/examples/Cassie/contact_scheduler/BUILD.bazel index 9f029cba6d..6c704f3854 100644 --- a/examples/Cassie/contact_scheduler/BUILD.bazel +++ b/examples/Cassie/contact_scheduler/BUILD.bazel @@ -4,10 +4,10 @@ package(default_visibility = ["//visibility:public"]) cc_library( - name="all", + name = "all", deps = [ ":contact_scheduler", - ] + ], ) cc_library( @@ -15,10 +15,10 @@ cc_library( srcs = ["contact_scheduler.cc"], hdrs = ["contact_scheduler.h"], deps = [ - "//lcmtypes:lcmt_robot", "//common", - "//multibody:utils", "//examples/Cassie:cassie_utils", + "//lcmtypes:lcmt_robot", + "//multibody:utils", "//systems/primitives", "@drake//:drake_shared_library", ], @@ -28,8 +28,8 @@ cc_binary( name = "state_based_controller_switch", srcs = ["state_based_controller_switch.cc"], deps = [ - "@drake//:drake_shared_library", "//lcmtypes:lcmt_robot", + "@drake//:drake_shared_library", "@gflags", ], ) diff --git a/examples/Cassie/diagrams/BUILD.bazel b/examples/Cassie/diagrams/BUILD.bazel index 66e42dc00c..70a0917fca 100644 --- a/examples/Cassie/diagrams/BUILD.bazel +++ b/examples/Cassie/diagrams/BUILD.bazel @@ -25,9 +25,9 @@ load( cc_library( name = "diagrams", deps = [ + ":cassie_sim_diagram", ":osc_running_controller_diagram", ":osc_walking_controller_diagram", - ":cassie_sim_diagram", ], ) @@ -36,18 +36,18 @@ cc_library( srcs = ["osc_running_controller_diagram.cc"], hdrs = ["osc_running_controller_diagram.h"], deps = [ - "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//examples/Cassie:cassie_urdf", "//examples/Cassie:cassie_utils", - "//examples/Cassie/osc_run:osc_run", "//examples/Cassie/contact_scheduler:all", - "//examples/Cassie/osc:osc", + "//examples/Cassie/osc", + "//examples/Cassie/osc_run", + "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//lcm:trajectory_saver", "//multibody:utils", "//systems:robot_lcm_systems", "//systems:system_utils", - "//systems/filters:floating_base_velocity_filter", "//systems/controllers/osc:osc_tracking_datas", + "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", "//systems/primitives:radio_parser", @@ -60,18 +60,18 @@ cc_library( srcs = ["osc_walking_controller_diagram.cc"], hdrs = ["osc_walking_controller_diagram.h"], deps = [ - "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//examples/Cassie:cassie_urdf", "//examples/Cassie:cassie_utils", - "//examples/Cassie/osc:osc", + "//examples/Cassie/osc", + "//examples/impact_invariant_control:impact_aware_time_based_fsm", "//lcm:trajectory_saver", "//multibody:utils", "//systems:robot_lcm_systems", "//systems:system_utils", - "//systems/filters:floating_base_velocity_filter", - "//systems/controllers/osc:osc_tracking_datas", - "//systems/controllers/osc:osc_gains", "//systems/controllers:fsm_event_time", + "//systems/controllers/osc:osc_gains", + "//systems/controllers/osc:osc_tracking_datas", + "//systems/filters:floating_base_velocity_filter", "//systems/framework:lcm_driven_loop", "//systems/primitives", "//systems/primitives:radio_parser", @@ -84,15 +84,15 @@ cc_library( srcs = ["cassie_sim_diagram.cc"], hdrs = ["cassie_sim_diagram.h"], deps = [ - "//examples/Cassie/systems:cassie_encoder", "//examples/Cassie:cassie_fixed_point_solver", "//examples/Cassie:cassie_urdf", "//examples/Cassie:cassie_utils", + "//examples/Cassie/systems:cassie_encoder", "//systems:robot_lcm_systems", + "//systems:system_utils", "//systems/framework:geared_motor", "//systems/primitives", "//systems/primitives:radio_parser", - "//systems:system_utils", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/Cassie/osc/BUILD.bazel b/examples/Cassie/osc/BUILD.bazel index a57a3d6c78..e7adc3a496 100644 --- a/examples/Cassie/osc/BUILD.bazel +++ b/examples/Cassie/osc/BUILD.bazel @@ -8,9 +8,9 @@ cc_library( "//examples/Cassie/osc:heading_traj_generator", "//examples/Cassie/osc:high_level_command", "//examples/Cassie/osc:hip_yaw_traj_gen", + "//examples/Cassie/osc:osc_standing_gains", "//examples/Cassie/osc:osc_walking_gains", "//examples/Cassie/osc:osc_walking_gains_alip", - "//examples/Cassie/osc:osc_standing_gains", "//examples/Cassie/osc:standing_com_traj", "//examples/Cassie/osc:standing_pelvis_orientation_traj", "//examples/Cassie/osc:swing_toe_traj", @@ -76,9 +76,9 @@ cc_library( srcs = ["standing_com_traj.cc"], hdrs = ["standing_com_traj.h"], deps = [ + "//common", "//lcmtypes:lcmt_robot", "//multibody:utils", - "//common:common", "//systems/controllers:control_utils", "//systems/framework:vector", "@drake//:drake_shared_library", @@ -90,10 +90,10 @@ cc_library( srcs = ["standing_pelvis_orientation_traj.cc"], hdrs = ["standing_pelvis_orientation_traj.h"], deps = [ + "//common", "//lcmtypes:lcmt_robot", "//systems/controllers:control_utils", "//systems/framework:vector", - "//common:common", "@drake//:drake_shared_library", ], ) diff --git a/examples/Cassie/osc_run/BUILD.bazel b/examples/Cassie/osc_run/BUILD.bazel index 53ffab7875..3535f79fe1 100644 --- a/examples/Cassie/osc_run/BUILD.bazel +++ b/examples/Cassie/osc_run/BUILD.bazel @@ -45,24 +45,23 @@ cc_library( srcs = ["pelvis_trans_traj_generator.cc"], hdrs = ["pelvis_trans_traj_generator.h"], deps = [ + "//examples/Cassie/contact_scheduler:all", "//multibody:utils", "//systems/controllers/osc:osc_gains", - "//examples/Cassie/contact_scheduler:all", "//systems/primitives", "@drake//:drake_shared_library", ], ) - cc_library( name = "foot_traj_generator", srcs = ["foot_traj_generator.cc"], hdrs = ["foot_traj_generator.h"], deps = [ - "//multibody:utils", + "//examples/Cassie/contact_scheduler:all", "//lcmtypes:lcmt_robot", + "//multibody:utils", "//systems/controllers/osc:osc_gains", - "//examples/Cassie/contact_scheduler:all", "//systems/primitives", "@drake//:drake_shared_library", ], diff --git a/signalscope/BUILD.bazel b/signalscope/BUILD.bazel index a1fbac7032..8f66a1aea2 100644 --- a/signalscope/BUILD.bazel +++ b/signalscope/BUILD.bazel @@ -12,14 +12,14 @@ py_binary( srcs = ["signal-scope.py"], data = ["@signal_scope"], main = "signal-scope.py", + tags = ["manual"], deps = ["//lcmtypes:lcmtypes_robot_py"], - tags=["manual"] ) load("@drake//tools/skylark:drake_runfiles_binary.bzl", "drake_runfiles_binary") drake_runfiles_binary( name = "signal-scope", + tags = ["manual"], target = ":signal-scope-py", - tags = ["manual"] ) diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index ec516567e9..dd675d3851 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -31,9 +31,9 @@ cc_library( name = "osc_tracking_datas", deps = [ ":com_tracking_data", + ":external_force_tracking_data", ":joint_space_tracking_data", ":osc_tracking_data", - ":external_force_tracking_data", ":relative_transform_tracking_data", ":rot_space_tracking_data", ":trans_space_tracking_data", diff --git a/systems/primitives/BUILD.bazel b/systems/primitives/BUILD.bazel index d07aa4ceee..6a1eb747b7 100644 --- a/systems/primitives/BUILD.bazel +++ b/systems/primitives/BUILD.bazel @@ -46,8 +46,8 @@ cc_library( "radio_parser.h", ], deps = [ - "//systems/framework:vector", "//lcmtypes:lcmt_robot", + "//systems/framework:vector", "@drake//:drake_shared_library", ], ) diff --git a/systems/ros/BUILD.bazel b/systems/ros/BUILD.bazel index 9bb91ed15e..2785cd834f 100644 --- a/systems/ros/BUILD.bazel +++ b/systems/ros/BUILD.bazel @@ -14,19 +14,18 @@ cc_library( ], ) - cc_library( name = "franka_ros_lcm_conversions", srcs = ["franka_ros_lcm_conversions.cc"], hdrs = ["franka_ros_lcm_conversions.h"], tags = ["ros"], deps = [ - "//lcmtypes:lcmt_robot", "//common", - "@ros", + "//lcmtypes:lcmt_robot", "//multibody:utils", "//systems/primitives", "@drake//:drake_shared_library", + "@ros", ], ) diff --git a/systems/trajectory_optimization/BUILD.bazel b/systems/trajectory_optimization/BUILD.bazel index dca8994e5e..ca82ba7214 100644 --- a/systems/trajectory_optimization/BUILD.bazel +++ b/systems/trajectory_optimization/BUILD.bazel @@ -54,10 +54,10 @@ cc_library( "lcm_trajectory_systems.h", ], deps = [ + "//common:eigen_utils", + "//common:find_resource", "//lcm:lcm_trajectory_saver", "//multibody:multipose_visualizer", - "//common:find_resource", - "//common:eigen_utils", "@drake//:drake_shared_library", ], ) From 434dfade7c0ac2e342c34200e9bb0bb9752b15f2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 3 Nov 2023 16:24:09 -0400 Subject: [PATCH 502/758] publishing c3 debug struct, make sure float isn't an issue --- examples/franka/BUILD.bazel | 1 + examples/franka/franka_c3_controller.cc | 30 ++++-- .../franka/parameters/franka_lcm_channels.h | 2 + .../parameters/lcm_channels_simulation.yaml | 1 + .../franka/systems/c3_trajectory_generator.cc | 4 +- solvers/c3_output.cc | 101 +++++++++++++++++- solvers/c3_output.h | 7 +- systems/controllers/c3_controller.cc | 2 +- systems/trajectory_optimization/BUILD.bazel | 16 +++ .../c3_output_systems.cc | 46 ++++++++ .../c3_output_systems.h | 42 ++++++++ .../lcm_trajectory_systems.cc | 9 +- 12 files changed, 237 insertions(+), 24 deletions(-) create mode 100644 systems/trajectory_optimization/c3_output_systems.cc create mode 100644 systems/trajectory_optimization/c3_output_systems.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 00738c8c3c..fd642da489 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -79,6 +79,7 @@ cc_binary( "//systems/controllers:c3_controller", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", + "//systems/trajectory_optimization:c3_output_systems", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 606f99a1ef..12a9be0efb 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -5,17 +5,18 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/systems/c3_trajectory_generator.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "examples/franka/systems/franka_kinematics.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3_controller.h" -#include "examples/franka/systems/c3_trajectory_generator.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" #include "drake/common/find_resource.h" #include "drake/common/yaml/yaml_io.h" @@ -168,13 +169,17 @@ int DoMain(int argc, char* argv[]) { auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_actor_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), - 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kForced}))); + auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), - 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kForced}))); + + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); @@ -182,8 +187,10 @@ int DoMain(int argc, char* argv[]) { auto controller = builder.AddSystem( plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); - auto c3_trajectory_generator = builder.AddSystem( - plant_plate, &plate_context, c3_options); + auto c3_trajectory_generator = + builder.AddSystem( + plant_plate, &plate_context, c3_options); + auto c3_output_sender = builder.AddSystem(); controller->SetOsqpSolverOptions(solver_options); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); @@ -196,12 +203,19 @@ int DoMain(int argc, char* argv[]) { builder.Connect(radio_sub->get_output_port(), controller->get_input_port_radio()); builder.Connect(controller->get_output_port_c3_solution(), - c3_trajectory_generator->get_input_port_c3_solution()); + c3_trajectory_generator->get_input_port_c3_solution()); builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_output_sender->get_input_port_c3_solution()); + builder.Connect(controller->get_output_port_c3_intermediates(), + c3_output_sender->get_input_port_c3_intermediates()); + builder.Connect(c3_output_sender->get_output_port_c3_debug(), + c3_output_publisher->get_input_port()); + controller->SetPublishEndEffectorOrientation( controller_params.include_end_effector_orientation); diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h index c9c591c2a3..a39dc0623f 100644 --- a/examples/franka/parameters/franka_lcm_channels.h +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -13,6 +13,7 @@ struct FrankaLcmChannels { std::string osc_debug_channel; std::string c3_actor_channel; std::string c3_object_channel; + std::string c3_debug_output_channel; std::string radio_channel; template @@ -26,6 +27,7 @@ struct FrankaLcmChannels { a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_actor_channel)); a->Visit(DRAKE_NVP(c3_object_channel)); + a->Visit(DRAKE_NVP(c3_debug_output_channel)); a->Visit(DRAKE_NVP(radio_channel)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index 6ccfedf62f..b3c36b1cb9 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -9,5 +9,6 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY +c3_debug_output_channel: C3_DEBUG radio_channel: RADIO diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index f5184c0c8c..d270b22dab 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -87,7 +87,7 @@ void C3TrajectoryGenerator::OutputActorTrajectory( end_effector_orientation_traj.datapoints = orientation_samples; end_effector_orientation_traj.time_vector = c3_solution->time_vector_; lcm_traj.AddTrajectory(end_effector_orientation_traj.traj_name, - std::move(end_effector_orientation_traj)); + end_effector_orientation_traj); } output_traj->saved_traj = lcm_traj.GenerateLcmObject(); @@ -123,7 +123,7 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( object_orientation_traj.datapoints = orientation_samples; object_orientation_traj.time_vector = c3_solution->time_vector_; lcm_traj.AddTrajectory(object_orientation_traj.traj_name, - std::move(object_orientation_traj)); + object_orientation_traj); } output_traj->saved_traj = lcm_traj.GenerateLcmObject(); diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc index 710a14208b..a452defede 100644 --- a/solvers/c3_output.cc +++ b/solvers/c3_output.cc @@ -1,5 +1,98 @@ -// -// Created by yangwill on 11/3/23. -// - #include "c3_output.h" + +using Eigen::VectorXd; +using std::vector; + +namespace dairlib { + +C3Output::C3Output(C3Solution c3_sol, C3Intermediates c3_intermediates) + : c3_solution_(c3_sol), c3_intermediates_(c3_intermediates) {} + +lcmt_c3_output C3Output::GenerateLcmObject(double time) const { + lcmt_c3_output c3_output; + lcmt_c3_solution c3_solution; + lcmt_c3_intermediates c3_intermediates; + c3_output.utime = static_cast(1e6 * time); + + std::cout << c3_solution_.time_vector_.size() << std::endl; + std::cout << c3_solution_.x_sol_.rows() << std::endl; + c3_solution.num_points = c3_solution_.time_vector_.size(); + int knot_points = c3_solution.num_points; + c3_solution.num_state_variables = c3_solution_.x_sol_.rows(); + c3_solution.num_contact_variables = c3_solution_.lambda_sol_.rows(); + c3_solution.num_input_variables = c3_solution_.u_sol_.rows(); + c3_solution.time_vec.reserve(knot_points); + c3_solution.x_sol = vector>(c3_solution.num_state_variables, + vector(knot_points)); + c3_solution.lambda_sol = vector>( + c3_solution.num_contact_variables, vector(knot_points)); + c3_solution.u_sol = vector>(c3_solution.num_input_variables, + vector(knot_points)); + + c3_solution.time_vec = vector( + c3_solution_.time_vector_.data(), + c3_solution_.time_vector_.data() + c3_solution_.time_vector_.size()); + + c3_intermediates.num_total_variables = c3_intermediates_.delta_.rows(); + c3_intermediates.num_points = c3_solution.num_points; + c3_intermediates.time_vec.reserve(c3_intermediates.num_points); + c3_intermediates.delta_sol = vector>( + c3_intermediates.num_total_variables, vector(knot_points)); + c3_intermediates.w_sol = vector>( + c3_intermediates.num_total_variables, vector(knot_points)); + c3_intermediates.time_vec = c3_solution.time_vec; + + std::cout << "c3_solution.num_points" << c3_solution.num_points << std::endl; + std::cout << "c3_solution.num_state_variables" << c3_solution.num_state_variables << std::endl; + std::cout << "c3_solution.num_contact_variables" << c3_solution.num_contact_variables << std::endl; + std::cout << "c3_solution.num_input_variables" << c3_solution.num_input_variables << std::endl; + std::cout << "c3_solution.time_vec" << c3_solution.time_vec.size() << std::endl; + std::cout << "c3_solution.x_sol" << c3_solution.x_sol.size() << std::endl; + std::cout << "c3_solution.lambda_sol" << c3_solution.lambda_sol.size() << std::endl; + std::cout << "c3_solution.u_sol" << c3_solution.u_sol.size() << std::endl; + std::cout << "c3_intermediates.time_vec" << c3_intermediates.time_vec.size() << std::endl; + std::cout << "c3_intermediates.delta_sol" << c3_intermediates.delta_sol.size() << std::endl; + std::cout << "c3_intermediates.w_sol" << c3_intermediates.w_sol.size() << std::endl; + + for (int i = 0; i < c3_solution.num_state_variables; ++i) { + // Temporary copy due to underlying data of Eigen::Matrix + // being column major + VectorXd temp_row = c3_solution_.x_sol_.row(i); + memcpy(c3_solution.x_sol[i].data(), temp_row.data(), + sizeof(float) * knot_points); + } + for (int i = 0; i < c3_solution.num_contact_variables; ++i) { + // Temporary copy due to underlying data of Eigen::Matrix + // being column major + VectorXd temp_row = c3_solution_.lambda_sol_.row(i); + memcpy(c3_solution.lambda_sol[i].data(), temp_row.data(), + sizeof(float) * knot_points); + } + for (int i = 0; i < c3_solution.num_input_variables; ++i) { + // Temporary copy due to underlying data of Eigen::Matrix + // being column major + VectorXd temp_row = c3_solution_.u_sol_.row(i); + memcpy(c3_solution.u_sol[i].data(), temp_row.data(), + sizeof(float) * knot_points); + } + for (int i = 0; i < c3_intermediates.num_total_variables; ++i) { + // Temporary copy due to underlying data of Eigen::Matrix + // being column major + VectorXd temp_delta_row = c3_intermediates_.delta_.row(i); + VectorXd temp_w_row = c3_intermediates_.w_.row(i); + memcpy(c3_intermediates.delta_sol[i].data(), temp_delta_row.data(), + sizeof(float) * knot_points); + memcpy(c3_intermediates.w_sol[i].data(), temp_w_row.data(), + sizeof(float) * knot_points); + } + + + // + c3_output.c3_solution = c3_solution; + c3_output.c3_intermediates = lcmt_c3_intermediates(); + std::cout << "constructed c3 output" << std::endl; + + return c3_output; +} + +} // namespace dairlib diff --git a/solvers/c3_output.h b/solvers/c3_output.h index 9996c2026a..6e7ccf03fd 100644 --- a/solvers/c3_output.h +++ b/solvers/c3_output.h @@ -9,7 +9,7 @@ #include "dairlib/lcmt_c3_output.hpp" -#include "drake/systems/lcm/serializer.h" +//#include "drake/systems/lcm/serializer.h" namespace dairlib { @@ -22,6 +22,7 @@ class C3Output { // C3Solution(Eigen::VectorXd time_vector_, Eigen::MatrixXd x_sol_, // Eigen::MatrixXd lambda_sol_, Eigen::MatrixXd u_sol_); + // Shape is (variable_vector_size, knot_points) Eigen::VectorXd time_vector_; Eigen::MatrixXd x_sol_; Eigen::MatrixXd lambda_sol_; @@ -33,6 +34,7 @@ class C3Output { // C3Intermediates(Eigen::VectorXd time_vector_, Eigen::MatrixXd delta_, // Eigen::MatrixXd w_); + // Shape is (variable_vector_size, knot_points) Eigen::VectorXd time_vector_; Eigen::MatrixXd delta_; Eigen::MatrixXd w_; @@ -45,9 +47,8 @@ class C3Output { virtual ~C3Output() = default; - lcmt_c3_output GenerateLcmObject() const; + lcmt_c3_output GenerateLcmObject(double time) const; - protected: private: C3Solution c3_solution_; C3Intermediates c3_intermediates_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7c5dc5a5b7..4e8dc26a98 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -188,7 +188,7 @@ void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { double t = context.get_discrete_state(plan_start_time_index_)[0]; - auto z_sol = c3_->GetFullSolution(); +// auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; c3_intermediates->w_.col(i) = w_[i]; diff --git a/systems/trajectory_optimization/BUILD.bazel b/systems/trajectory_optimization/BUILD.bazel index ca82ba7214..a8bcc809ff 100644 --- a/systems/trajectory_optimization/BUILD.bazel +++ b/systems/trajectory_optimization/BUILD.bazel @@ -62,6 +62,22 @@ cc_library( ], ) +cc_library( + name = "c3_output_systems", + srcs = [ + "c3_output_systems.cc", + ], + hdrs = [ + "c3_output_systems.h", + ], + deps = [ + "//common:eigen_utils", + "//lcmtypes:lcmt_robot", + "//solvers:c3_output", + "@drake//:drake_shared_library", + ], +) + cc_binary( name = "passive_constrained_pendulum_dircon", srcs = ["test/passive_constrained_pendulum_dircon.cc"], diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc new file mode 100644 index 0000000000..48f23f100e --- /dev/null +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -0,0 +1,46 @@ +#include "c3_output_systems.h" + + +#include "common/eigen_utils.h" +#include "solvers/c3_output.h" + +namespace dairlib { +namespace systems { + +using drake::systems::Context; +using drake::systems::DiscreteValues; +using Eigen::MatrixXd; +using Eigen::Quaterniond; +using Eigen::VectorXd; + +C3OutputSender::C3OutputSender() { + c3_solution_port_ = + this->DeclareAbstractInputPort("c3_solution", + drake::Value{}) + .get_index(); + c3_intermediates_port_ = + this->DeclareAbstractInputPort("c3_intermediates", + drake::Value{}) + .get_index(); + + this->set_name("c3_output_sender"); + lcm_c3_output_port_ = this->DeclareAbstractOutputPort( + "lcmt_c3_output", dairlib::lcmt_c3_output(), + &C3OutputSender::OutputC3Lcm) + .get_index(); +} + +void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, + dairlib::lcmt_c3_output* output) const { + const auto& c3_solution = + this->EvalInputValue(context, c3_solution_port_); + const auto& c3_intermediates = + this->EvalInputValue(context, + c3_intermediates_port_); + + C3Output c3_output = C3Output(*c3_solution, *c3_intermediates); + *output = c3_output.GenerateLcmObject(context.get_time()); +} + +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/trajectory_optimization/c3_output_systems.h b/systems/trajectory_optimization/c3_output_systems.h new file mode 100644 index 0000000000..10ad89f248 --- /dev/null +++ b/systems/trajectory_optimization/c3_output_systems.h @@ -0,0 +1,42 @@ +#pragma once + +#include +#include + +#include "dairlib/lcmt_c3_output.hpp" + +#include "drake/systems/framework/leaf_system.h" +#include "drake/systems/lcm/lcm_interface_system.h" + +namespace dairlib { +namespace systems { + +/// Converts a OutputVector object to LCM type lcmt_robot_output +class C3OutputSender : public drake::systems::LeafSystem { + public: + C3OutputSender(); + + const drake::systems::InputPort& get_input_port_c3_solution() const { + return this->get_input_port(c3_solution_port_); + } + + const drake::systems::InputPort& get_input_port_c3_intermediates() + const { + return this->get_input_port(c3_intermediates_port_); + } + + const drake::systems::OutputPort& get_output_port_c3_debug() const { + return this->get_output_port(lcm_c3_output_port_); + } + + private: + void OutputC3Lcm(const drake::systems::Context& context, + dairlib::lcmt_c3_output* output) const; + + drake::systems::InputPortIndex c3_solution_port_; + drake::systems::InputPortIndex c3_intermediates_port_; + drake::systems::OutputPortIndex lcm_c3_output_port_; +}; + +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 23b88d52ea..615a192bf2 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -178,8 +178,7 @@ LcmPoseDrawer::LcmPoseDrawer( const std::shared_ptr& meshcat, const std::string& model_file, const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, - int num_poses, + const std::string& orientation_trajectory_name, int num_poses, const std::string& default_trajectory_path) : meshcat_(meshcat), translation_trajectory_name_(std::move(translation_trajectory_name)), @@ -211,12 +210,10 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( this->EvalInputValue( context, trajectory_input_port_); lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); - } - MatrixXd object_poses = MatrixXd::Zero(7, N_); - - if (!lcm_traj_.HasTrajectory(translation_trajectory_name_)) { + } else { return drake::systems::EventStatus::Succeeded(); } + MatrixXd object_poses = MatrixXd::Zero(7, N_); const auto lcm_translation_traj = lcm_traj_.GetTrajectory(translation_trajectory_name_); From a7e5d7b8ab8040f0e67fd238a1fd3843b6e7838c Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 6 Nov 2023 10:51:07 -0500 Subject: [PATCH 503/758] allowing default plot styling options --- .../pydairlib/analysis/cassie_plot_config.py | 2 +- .../pydairlib/analysis/franka_plot_config.py | 2 +- .../pydairlib/analysis/log_plotter_cassie.py | 4 +++- .../pydairlib/analysis/log_plotter_franka.py | 4 +++- .../plot_configs/franka_translation_plot.yaml | 5 +++-- bindings/pydairlib/common/plot_styler.py | 19 +++++++++++++++++-- .../franka_osc_controller_params.yaml | 2 +- .../parameters/lcm_channels_hardware.yaml | 3 ++- 8 files changed, 31 insertions(+), 10 deletions(-) diff --git a/bindings/pydairlib/analysis/cassie_plot_config.py b/bindings/pydairlib/analysis/cassie_plot_config.py index ef034215b7..c91ed33627 100644 --- a/bindings/pydairlib/analysis/cassie_plot_config.py +++ b/bindings/pydairlib/analysis/cassie_plot_config.py @@ -14,7 +14,7 @@ def __init__(self, filename): self.channel_u = data['channel_u'] self.channel_osc = data['channel_osc'] self.use_archived_lcmtypes = data['use_archived_lcmtypes'] - self.use_default_styling = data['use_default_styling'] + self.plot_style = data['plot_style'] self.use_floating_base = data['use_floating_base'] self.use_springs = data['use_springs'] self.start_time = data['start_time'] diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py index 93c94d58b8..9e17be98ab 100644 --- a/bindings/pydairlib/analysis/franka_plot_config.py +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -13,7 +13,7 @@ def __init__(self, filename): self.channel_x = data['channel_x'] self.channel_u = data['channel_u'] self.channel_osc = data['channel_osc'] - self.use_default_styling = data['use_default_styling'] + self.plot_style = data['plot_style'] self.start_time = data['start_time'] self.duration = data['duration'] diff --git a/bindings/pydairlib/analysis/log_plotter_cassie.py b/bindings/pydairlib/analysis/log_plotter_cassie.py index f7bb75e3a2..8d0081b310 100644 --- a/bindings/pydairlib/analysis/log_plotter_cassie.py +++ b/bindings/pydairlib/analysis/log_plotter_cassie.py @@ -25,8 +25,10 @@ def main(): channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc - if plot_config.use_default_styling: + if plot_config.plot_style == "paper": plot_styler.PlotStyler.set_default_styling() + elif plot_config.plot_style == "compact": + plot_styler.PlotStyler.set_compact_styling() ''' Get the plant ''' plant, context = cassie_plots.make_plant_and_context( diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 779c6fd849..510f85dbd0 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -20,8 +20,10 @@ def main(): channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc - if plot_config.use_default_styling: + if plot_config.plot_style == "paper": plot_styler.PlotStyler.set_default_styling() + elif plot_config.plot_style == "compact": + plot_styler.PlotStyler.set_compact_styling() ''' Get the plant ''' franka_plant, franka_context, tray_plant, tray_context = franka_plots.make_plant_and_context() diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 9de2bc5fc8..ccd5c7bc80 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -2,7 +2,7 @@ channel_x: "FRANKA_STATE" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" -use_default_styling: false +plot_style: 'compact' # compact, paper, default start_time: 0 #duration: 0.47 @@ -32,5 +32,6 @@ plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} + end_effector_target: {'dims': [0, 1, 2], 'derivs': ['vel']} +# end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index 78923e8874..bd60329c7b 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -9,15 +9,30 @@ class PlotStyler(): @staticmethod - def set_default_styling(): + def set_paper_styling(): # matplotlib.rcParams['figure.figsize'] = 20, 12 # matplotlib.rcParams['figure.figsize'] = 20, 6 matplotlib.rcParams['figure.figsize'] = 8, 6 + plt.rcParams['figure.dpi'] = 200 matplotlib.rcParams['figure.autolayout'] = True font = {'size': 20} matplotlib.rc('font', **font) matplotlib.rcParams['lines.linewidth'] = 2 plt.set_cmap('tab20') + @staticmethod + def set_compact_styling(): + matplotlib.rcParams['figure.figsize'] = 20, 12 + font_size = 6 + plt.rc('legend', fontsize=font_size) + plt.rc('axes', labelsize=font_size, titlesize=font_size) + plt.rc('xtick', labelsize=font_size) + plt.rc('ytick', labelsize=font_size) + plt.rcParams['figure.dpi'] = 75 + matplotlib.rcParams['figure.autolayout'] = False + font = {'size': font_size} + matplotlib.rc('font', **font) + matplotlib.rcParams['lines.linewidth'] = 2 + plt.set_cmap('tab20') def __init__(self, figure=None, nrows=1, ncols=1): @@ -31,7 +46,7 @@ def __init__(self, figure=None, nrows=1, ncols=1): self.grey = '#909090' self.orange = '#FE7F0E' # self.directory = None - self.dpi = 150 + self.dpi = plt.rcParams['figure.dpi'] self.directory = '/home/yangwill/Pictures/plot_styler/' plt.rc('legend', fontsize=14) plt.rc('axes', labelsize=14, titlesize=14) diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 7df7e53fac..2c0bb0340c 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index 1a65b34798..5d138589d2 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -1,5 +1,5 @@ franka_state_channel: FRANKA_STATE -tray_state_channel: TRAY_STATE_SIMULATION +tray_state_channel: TRAY_STATE box_state_channel: BOX_STATE franka_input_channel: FRANKA_INPUT franka_input_echo: FRANKA_INPUT_ECHO @@ -9,5 +9,6 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY +c3_debug_output_channel: C3_DEBUG radio_channel: RADIO From bacc22d42970e1bf8f5e899669664354ffa5766d Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Nov 2023 13:20:45 -0500 Subject: [PATCH 504/758] cleaning up urdf and small systems --- bindings/pydairlib/multibody/BUILD.bazel | 1 - examples/franka/urdf/default_box.urdf | 2 +- examples/franka/urdf/plate_end_effector.urdf | 2 +- examples/franka/urdf/tray.sdf | 2 +- multibody/multibody_utils.cc | 140 +++++-------------- solvers/c3_output.cc | 12 -- systems/robot_lcm_systems.cc | 4 - 7 files changed, 40 insertions(+), 123 deletions(-) diff --git a/bindings/pydairlib/multibody/BUILD.bazel b/bindings/pydairlib/multibody/BUILD.bazel index b586433253..3f5fe996aa 100644 --- a/bindings/pydairlib/multibody/BUILD.bazel +++ b/bindings/pydairlib/multibody/BUILD.bazel @@ -22,7 +22,6 @@ pybind_py_library( cc_so_name = "multibody", cc_srcs = ["multibody_py.cc"], py_deps = [ - # "@drake//bindings/pydrake", ":module_py", ], py_imports = ["."], diff --git a/examples/franka/urdf/default_box.urdf b/examples/franka/urdf/default_box.urdf index dbe30519ab..f2b1f70a1d 100644 --- a/examples/franka/urdf/default_box.urdf +++ b/examples/franka/urdf/default_box.urdf @@ -25,7 +25,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 04fabce326..7f9e79af3f 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -14,7 +14,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index aab632d0a2..db71b92681 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -38,7 +38,7 @@ 3.0e7 - 0.5 + 0.1 10 0.4 0.4 diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 65e5bf4725..74938a9e0e 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -644,110 +644,44 @@ Eigen::MatrixXd JwrtqdotToJwrtv(const Eigen::VectorXd& q, return ret; } -template int QuaternionStartIndex( - const MultibodyPlant& plant); // NOLINT -template int QuaternionStartIndex( - const MultibodyPlant& plant); // NOLINT -template std::vector QuaternionStartIndices( - const MultibodyPlant& plant); // NOLINT -template std::vector QuaternionStartIndices( - const MultibodyPlant& plant); // NOLINT +template int QuaternionStartIndex(const MultibodyPlant& plant); // NOLINT +template int QuaternionStartIndex(const MultibodyPlant& plant); // NOLINT +template std::vector QuaternionStartIndices(const MultibodyPlant& plant); // NOLINT +template std::vector QuaternionStartIndices(const MultibodyPlant& plant); // NOLINT template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT template bool HasQuaternion(const MultibodyPlant& plant); // NOLINT -template Vector3d ReExpressWorldVector3InBodyYawFrame( - const MultibodyPlant& plant, const Context& context, - const std::string& body_name, const Vector3d& vec); // NOLINT -template Vector2d ReExpressWorldVector2InBodyYawFrame( - const MultibodyPlant& plant, const Context& context, - const std::string& body_name, const Vector2d& vec); // NOLINT -template map MakeNameToPositionsMap( - const MultibodyPlant& plant); // NOLINT -template map MakeNameToPositionsMap( - const MultibodyPlant& plant); // NOLINT -template map MakeNameToPositionsMap( - const MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToPositionsMap( - const MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToVelocitiesMap( - const MultibodyPlant& plant); // NOLINT -template map MakeNameToVelocitiesMap( - const MultibodyPlant& plant); // NOLINT -template map MakeNameToVelocitiesMap( - const MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToVelocitiesMap( - const MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex); // NOLINT -template map MakeNameToActuatorsMap( - const MultibodyPlant& plant); // NOLINT -template map MakeNameToActuatorsMap( - const MultibodyPlant& plant); // NOLINT -template vector CreateStateNameVectorFromMap( - const MultibodyPlant& plant); // NOLINT -template vector CreateStateNameVectorFromMap( - const MultibodyPlant& plant); // NOLINT -template vector CreateActuatorNameVectorFromMap( - const MultibodyPlant& plant); // NOLINT -template vector CreateActuatorNameVectorFromMap( - const MultibodyPlant& plant); // NOLINT -template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos( - const drake::multibody::MultibodyPlant& plant_w_spr, - const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT -template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel( - const drake::multibody::MultibodyPlant& plant_w_spr, - const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT -template void AddFlatTerrain(MultibodyPlant* plant, - SceneGraph* scene_graph, - double mu_static, double mu_kinetic, - Eigen::Vector3d normal_W, double stiffness, - double dissipation_rate, - bool show_ground); // NOLINT -template VectorX GetInput(const MultibodyPlant& plant, - const Context& context); // NOLINT -template VectorX GetInput( - const MultibodyPlant& plant, - const Context& context); // NOLINT -template std::unique_ptr> CreateContext( - const MultibodyPlant& plant, - const Eigen::Ref& state, - const Eigen::Ref& input); // NOLINT -template std::unique_ptr> CreateContext( - const MultibodyPlant& plant, - const Eigen::Ref& state, - const Eigen::Ref& input); // NOLINT -template void SetContext(const MultibodyPlant& plant, - const Eigen::Ref& state, - const Eigen::Ref&, - Context* context); // NOLINT -template void SetContext(const MultibodyPlant& plant, - const Eigen::Ref& state, - const Eigen::Ref&, - Context* context); // NOLINT -template void SetPositionsAndVelocitiesIfNew( - const MultibodyPlant&, const Eigen::Ref&, - Context*); // NOLINT -template void SetPositionsAndVelocitiesIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT -template void SetPositionsIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT -template void SetPositionsIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT -template void SetVelocitiesIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT -template void SetVelocitiesIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT -template void SetInputsIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT -template void SetInputsIfNew(const MultibodyPlant&, - const Eigen::Ref&, - Context*); // NOLINT +template Vector3d ReExpressWorldVector3InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector3d& vec); // NOLINT +template Vector2d ReExpressWorldVector2InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector2d& vec); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToActuatorsMap( const MultibodyPlant& plant); // NOLINT +template map MakeNameToActuatorsMap( const MultibodyPlant& plant); // NOLINT +template vector CreateStateNameVectorFromMap( const MultibodyPlant& plant); // NOLINT +template vector CreateStateNameVectorFromMap( const MultibodyPlant& plant); // NOLINT +template vector CreateActuatorNameVectorFromMap( const MultibodyPlant& plant); // NOLINT +template vector CreateActuatorNameVectorFromMap( const MultibodyPlant& plant); // NOLINT +template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT +template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT +template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W, double stiffness, double dissipation_rate, bool show_ground); // NOLINT +template VectorX GetInput(const MultibodyPlant& plant, const Context& context); // NOLINT +template VectorX GetInput(const MultibodyPlant& plant, const Context& context); // NOLINT +template std::unique_ptr> CreateContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref& input); // NOLINT +template std::unique_ptr> CreateContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref& input); // NOLINT +template void SetContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref&, Context* context); // NOLINT +template void SetContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref&, Context* context); // NOLINT +template void SetPositionsAndVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetPositionsAndVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetPositionsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetPositionsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetVelocitiesIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetInputsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT +template void SetInputsIfNew(const MultibodyPlant&, const Eigen::Ref&, Context*); // NOLINT } // namespace multibody } // namespace dairlib diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc index a452defede..0630937aea 100644 --- a/solvers/c3_output.cc +++ b/solvers/c3_output.cc @@ -42,18 +42,6 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { c3_intermediates.num_total_variables, vector(knot_points)); c3_intermediates.time_vec = c3_solution.time_vec; - std::cout << "c3_solution.num_points" << c3_solution.num_points << std::endl; - std::cout << "c3_solution.num_state_variables" << c3_solution.num_state_variables << std::endl; - std::cout << "c3_solution.num_contact_variables" << c3_solution.num_contact_variables << std::endl; - std::cout << "c3_solution.num_input_variables" << c3_solution.num_input_variables << std::endl; - std::cout << "c3_solution.time_vec" << c3_solution.time_vec.size() << std::endl; - std::cout << "c3_solution.x_sol" << c3_solution.x_sol.size() << std::endl; - std::cout << "c3_solution.lambda_sol" << c3_solution.lambda_sol.size() << std::endl; - std::cout << "c3_solution.u_sol" << c3_solution.u_sol.size() << std::endl; - std::cout << "c3_intermediates.time_vec" << c3_intermediates.time_vec.size() << std::endl; - std::cout << "c3_intermediates.delta_sol" << c3_intermediates.delta_sol.size() << std::endl; - std::cout << "c3_intermediates.w_sol" << c3_intermediates.w_sol.size() << std::endl; - for (int i = 0; i < c3_solution.num_state_variables; ++i) { // Temporary copy due to underlying data of Eigen::Matrix // being column major diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index d9fcf95081..4e65eb8c7c 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -154,7 +154,6 @@ void RobotOutputReceiver::InitializeSubscriberPositions( if (body.has_quaternion_dofs()) { state_msg.position.at(body.floating_positions_start()) = 1; } - std::cout << "Here: " << std::endl; } } @@ -326,9 +325,6 @@ void RobotInputReceiver::CopyInputOut(const Context& context, const auto& input_msg = input->get_value(); VectorXd input_vector = VectorXd::Zero(num_actuators_); -// std::cout << "context time: " << context.get_time() << std::endl; -// std::cout << "time: " << input_msg.utime * 1e-6 << std::endl; -// std::cout << "num_efforts: " << input_msg.num_efforts << std::endl; for (int i = 0; i < input_msg.num_efforts; i++) { int j = actuator_index_map_.at(input_msg.effort_names[i]); From 8dcb549706b49306e2e2db6bf586bf994f4ec4e6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Nov 2023 13:53:36 -0500 Subject: [PATCH 505/758] adding support for model instances in our common utils functions --- bindings/pydairlib/multibody/BUILD.bazel | 1 + bindings/pydairlib/multibody/multibody_py.cc | 20 +- .../pydairlib/systems/robot_lcm_systems_py.cc | 35 ++- multibody/multibody_utils.cc | 199 +++++++++++++++--- multibody/multibody_utils.h | 16 +- multibody/multipose_visualizer.cc | 23 +- multibody/multipose_visualizer.h | 11 +- multibody/visualization_utils.cc | 9 +- multibody/visualization_utils.h | 2 +- systems/robot_lcm_systems.cc | 177 ++++++++++++---- systems/robot_lcm_systems.h | 33 ++- 11 files changed, 423 insertions(+), 103 deletions(-) diff --git a/bindings/pydairlib/multibody/BUILD.bazel b/bindings/pydairlib/multibody/BUILD.bazel index 9de8f1de70..eb6c8266c5 100644 --- a/bindings/pydairlib/multibody/BUILD.bazel +++ b/bindings/pydairlib/multibody/BUILD.bazel @@ -16,6 +16,7 @@ pybind_py_library( cc_deps = [ "//multibody:multipose_visualizer", "//multibody:utils", + "//multibody:visualization_utils", "@drake//:drake_shared_library", ], cc_so_name = "multibody", diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index 896d7e4789..2a993d785e 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -5,6 +5,7 @@ #include "multibody/multibody_utils.h" #include "multibody/multipose_visualizer.h" +#include "multibody/visualization_utils.h" namespace py = pybind11; @@ -22,12 +23,18 @@ PYBIND11_MODULE(multibody, m) { .def(py::init()) .def(py::init()) .def(py::init()) - .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses")); + .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses")) + .def("GetMeshcat", &MultiposeVisualizer::GetMeshcat); + + m.def("ConnectTrajectoryVisualizer", + &dairlib::multibody::ConnectTrajectoryVisualizer, py::arg("plant"), + py::arg("builder"), py::arg("scene_graph"), py::arg("trajectory")); m.def("MakeNameToPositionsMap", - &dairlib::multibody::MakeNameToPositionsMap, py::arg("plant")) + py::overload_cast&>(&dairlib::multibody::MakeNameToPositionsMap), + py::arg("plant")) .def("MakeNameToVelocitiesMap", - &dairlib::multibody::MakeNameToVelocitiesMap, + py::overload_cast&>(&dairlib::multibody::MakeNameToVelocitiesMap), py::arg("plant")) .def("MakeNameToActuatorsMap", &dairlib::multibody::MakeNameToActuatorsMap, @@ -38,10 +45,17 @@ PYBIND11_MODULE(multibody, m) { .def("CreateActuatorNameVectorFromMap", &dairlib::multibody::CreateActuatorNameVectorFromMap, py::arg("plant")) + .def("CreateWithSpringsToWithoutSpringsMapPos", + &dairlib::multibody::CreateWithSpringsToWithoutSpringsMapPos, + py::arg("plant_w_spr"), py::arg("plant_wo_spr")) + .def("CreateWithSpringsToWithoutSpringsMapVel", + &dairlib::multibody::CreateWithSpringsToWithoutSpringsMapVel, + py::arg("plant_w_spr"), py::arg("plant_wo_spr")) .def("AddFlatTerrain", &dairlib::multibody::AddFlatTerrain, py::arg("plant"), py::arg("scene_graph"), py::arg("mu_static"), py::arg("mu_kinetic"), py::arg("normal_W") = Eigen::Vector3d(0, 0, 1), + py::arg("stiffness") = 0, py::arg("dissipation_rate") = 0, py::arg("show_ground") = 1); } diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 8117020da2..696769516f 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -8,7 +8,6 @@ #include "drake/multibody/plant/multibody_plant.h" namespace py = pybind11; -using py_rvp = py::return_value_policy; namespace dairlib { namespace pydairlib { @@ -18,32 +17,52 @@ PYBIND11_MODULE(robot_lcm_systems, m) { using drake::multibody::MultibodyPlant; using systems::RobotOutputSender; + using py_rvp = py::return_value_policy; py::class_>( m, "RobotOutputReceiver") - .def(py::init&>()); + .def(py::init&>()) + .def(py::init&, + drake::multibody::ModelInstanceIndex>()); py::class_>( m, "RobotInputReceiver") .def(py::init&>()); py::class_>( m, "RobotOutputSender") - .def(py::init&, bool>()) + .def(py::init&, bool, bool>()) + .def(py::init&, + drake::multibody::ModelInstanceIndex, + bool, bool>()) .def("get_input_port_state", &RobotOutputSender::get_input_port_state, - py_rvp::reference_internal) + py_rvp::reference_internal) .def("get_input_port_effort", &RobotOutputSender::get_input_port_effort, - py_rvp::reference_internal) + py_rvp::reference_internal) .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu, - py_rvp::reference_internal); + py_rvp::reference_internal); py::class_>( m, "RobotCommandSender") .def(py::init&>()); m.def("AddActuationRecieverAndStateSenderLcm", - &dairlib::systems::AddActuationRecieverAndStateSenderLcm, + py::overload_cast*, + const MultibodyPlant&, + drake::systems::lcm::LcmInterfaceSystem*, std::string, + std::string, double, + drake::multibody::ModelInstanceIndex, bool, double>( + &dairlib::systems::AddActuationRecieverAndStateSenderLcm), + py::arg("builder"), py::arg("plant"), py::arg("lcm"), + py::arg("actuator_channel"), py::arg("state_channel"), + py::arg("publish_rate"), py::arg("model_instance"), + py::arg("publish_efforts"), py::arg("actuator_delay")); + m.def("AddActuationRecieverAndStateSenderLcm", + py::overload_cast*, + const MultibodyPlant&, + drake::systems::lcm::LcmInterfaceSystem*, std::string, + std::string, double, bool, double>( + &dairlib::systems::AddActuationRecieverAndStateSenderLcm), py::arg("builder"), py::arg("plant"), py::arg("lcm"), py::arg("actuator_channel"), py::arg("state_channel"), py::arg("publish_rate"), py::arg("publish_efforts"), py::arg("actuator_delay")); - } } // namespace pydairlib diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index 4c1156778f..d4ae2469d0 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -4,6 +4,7 @@ #include #include "drake/common/drake_assert.h" +#include "drake/geometry/proximity_properties.h" #include "drake/math/autodiff_gradient.h" namespace dairlib { @@ -22,9 +23,9 @@ using drake::multibody::JointIndex; using drake::multibody::ModelInstanceIndex; using drake::multibody::MultibodyPlant; using drake::systems::Context; -using Eigen::VectorXd; -using Eigen::Vector3d; using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; using std::map; using std::string; using std::vector; @@ -121,7 +122,8 @@ void SetInputsIfNew(const MultibodyPlant& plant, template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, - Eigen::Vector3d normal_W, bool show_ground) { + Eigen::Vector3d normal_W, double stiffness, + double dissipation_rate, bool show_ground) { if (!plant->geometry_source_is_registered()) { plant->RegisterAsSourceForSceneGraph(scene_graph); } @@ -133,21 +135,33 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, const drake::math::RigidTransformd X_WG( HalfSpace::MakePose(normal_W, point_W)); - plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), - "collision", friction); + if (stiffness != 0) { + drake::geometry::ProximityProperties props; + props.AddProperty("material", "point_contact_stiffness", stiffness); + props.AddProperty("material", "hunt_crossley_dissipation", + dissipation_rate); + props.AddProperty(drake::geometry::internal::kMaterialGroup, + drake::geometry::internal::kFriction, friction); + plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), + "collision", props); + } else { + plant->RegisterCollisionGeometry(plant->world_body(), X_WG, HalfSpace(), + "collision", friction); + } // Add visual for the ground. if (show_ground) { - plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), - "visual"); + // plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), + // "visual"); } } /// Get the ordered names from a NameTo___Map -vector ExtractOrderedNamesFromMap(const map& map) { +vector ExtractOrderedNamesFromMap(const map& map, + int index_start) { vector names(map.size()); for (const auto& entry : map) { - names[entry.second] = entry.first; + names[entry.second - index_start] = entry.first; } return names; } @@ -191,13 +205,13 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant) { // TODO: once RBT fully deprecated, this block can likely be removed, using // default coordinate names from Drake. auto floating_bodies = plant.GetFloatingBaseBodies(); - DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); + // DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); DRAKE_ASSERT(body.has_quaternion_dofs()); int start = body.floating_positions_start(); // should be body.name() once RBT is deprecated - std::string name = "base"; + std::string name = body.name(); name_to_index_map[name + "_qw"] = start; name_to_index_map[name + "_qx"] = start + 1; name_to_index_map[name + "_qy"] = start + 2; @@ -219,6 +233,67 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant) { return name_to_index_map; } +/// Construct a map between joint names and position indices +/// such that q(index) has the given name +/// -Only accurately includes joints with a single position and single velocity +/// -Others are included as "position[ind]"" +/// -Index mapping can also be used as a state mapping (assumes x = [q;v]) +template +map MakeNameToPositionsMap(const MultibodyPlant& plant, + ModelInstanceIndex model_instance) { + map name_to_index_map; + std::set index_set; + for (auto i : plant.GetJointIndices(model_instance)) { + const drake::multibody::Joint& joint = plant.get_joint(i); + auto name = joint.name(); + + if (joint.num_velocities() == 1 && joint.num_positions() == 1) { + std::vector index_vector{i}; + auto selectorMatrix = plant.MakeStateSelectorMatrix(index_vector); + // find index and add + int selector_index = -1; + for (int j = 0; j < selectorMatrix.cols(); ++j) { + if (selectorMatrix(0, j) == 1) { + if (selector_index == -1) { + selector_index = j; + } else { + throw std::logic_error("Unable to create selector map."); + } + } + } + if (selector_index == -1) { + std::logic_error("Unable to create selector map."); + } + + name_to_index_map[name] = selector_index; + index_set.insert(selector_index); + } + } + + // TODO: once RBT fully deprecated, this block can likely be removed, using + // default coordinate names from Drake. + if (plant.HasUniqueFreeBaseBody(model_instance)) { + const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); + DRAKE_ASSERT(body.has_quaternion_dofs()); + int start = body.floating_positions_start(); + // should be body.name() once RBT is deprecated + std::string name = body.name(); + name_to_index_map[name + "_qw"] = start; + name_to_index_map[name + "_qx"] = start + 1; + name_to_index_map[name + "_qy"] = start + 2; + name_to_index_map[name + "_qz"] = start + 3; + name_to_index_map[name + "_x"] = start + 4; + name_to_index_map[name + "_y"] = start + 5; + name_to_index_map[name + "_z"] = start + 6; + for (int i = 0; i < 7; i++) { + index_set.insert(start + i); + } + } + // if index has not already been captured, throw an error + DRAKE_THROW_UNLESS(plant.num_positions(model_instance) == index_set.size()); + + return name_to_index_map; +} /// Construct a map between joint names and velocity indices /// such that v(index) has the given name @@ -262,11 +337,11 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { auto floating_bodies = plant.GetFloatingBaseBodies(); // Remove throw once RBT deprecated - DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); + // DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); int start = body.floating_velocities_start() - plant.num_positions(); - std::string name = "base"; // should be body.name() once RBT is deprecated + std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; name_to_index_map[name + "_wz"] = start + 2; @@ -285,6 +360,71 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { } } + // if index has not already been captured, throw an error + DRAKE_THROW_UNLESS(plant.num_velocities() == index_set.size()); + return name_to_index_map; +} + +/// Construct a map between joint names and velocity indices +/// such that v(index) has the given name +/// -Only accurately includes joints with a single position and single velocity +/// -Others are included as "state[ind]" +/// -Index mapping can also be used as a state mapping, AFTER +/// an offset of num_positions is applied (assumes x = [q;v]) +template +map MakeNameToVelocitiesMap(const MultibodyPlant& plant, + ModelInstanceIndex model_instance) { + map name_to_index_map; + std::set index_set; + + for (auto i : plant.GetJointIndices(model_instance)) { + const drake::multibody::Joint& joint = plant.get_joint(i); + // TODO(posa): this "dot" should be removed, it's an anachronism from + // RBT + auto name = joint.name() + "dot"; + + if (joint.num_velocities() == 1 && joint.num_positions() == 1) { + std::vector index_vector{i}; + auto selectorMatrix = plant.MakeStateSelectorMatrix(index_vector); + // find index and add + int selector_index = -1; + for (int j = 0; j < selectorMatrix.cols(); ++j) { + if (selectorMatrix(1, j) == 1) { + if (selector_index == -1) { + selector_index = j; + } else { + throw std::logic_error("Unable to create selector map."); + } + } + } + if (selector_index == -1) { + throw std::logic_error("Unable to create selector map."); + } + + name_to_index_map[name] = selector_index - plant.num_positions(); + index_set.insert(selector_index - plant.num_positions()); + } + } + + // Remove throw once RBT deprecated + if (plant.HasUniqueFreeBaseBody(model_instance)) { + const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); + int start = body.floating_velocities_start() - plant.num_positions(); + std::string name = + body.name(); // should be body.name() once RBT is deprecated + name_to_index_map[name + "_wx"] = start; + name_to_index_map[name + "_wy"] = start + 1; + name_to_index_map[name + "_wz"] = start + 2; + name_to_index_map[name + "_vx"] = start + 3; + name_to_index_map[name + "_vy"] = start + 4; + name_to_index_map[name + "_vz"] = start + 5; + for (int i = 0; i < 6; i++) { + index_set.insert(start + i); + } + } + + // if index has not already been captured, throw an error + DRAKE_THROW_UNLESS(plant.num_velocities(model_instance) == index_set.size()); return name_to_index_map; } @@ -323,8 +463,7 @@ map MakeNameToActuatorsMap(const MultibodyPlant& plant) { } template -vector CreateStateNameVectorFromMap( - const MultibodyPlant& plant) { +vector CreateStateNameVectorFromMap(const MultibodyPlant& plant) { map pos_map = MakeNameToPositionsMap(plant); map vel_map = MakeNameToVelocitiesMap(plant); vector state_names(pos_map.size() + vel_map.size()); @@ -340,8 +479,7 @@ vector CreateStateNameVectorFromMap( } template -vector CreateActuatorNameVectorFromMap( - const MultibodyPlant& plant) { +vector CreateActuatorNameVectorFromMap(const MultibodyPlant& plant) { map act_map = MakeNameToActuatorsMap(plant); return ExtractOrderedNamesFromMap(act_map); } @@ -453,10 +591,9 @@ Vector3d ReExpressWorldVector3InBodyYawFrame(const MultibodyPlant& plant, const Vector3d& vec) { Vector3d pelvis_x = plant.GetBodyByName(body_name).EvalPoseInWorld(context).rotation().col(0); - double yaw = atan2(pelvis_x(1), pelvis_x(0)); - return Vector3d(cos(yaw) * vec(0) + sin(yaw)*vec(1), - -sin(yaw) * vec(0) + cos(yaw)*vec(1), - vec(2)); + double yaw = atan2(pelvis_x(1), pelvis_x(0)); + return Vector3d(cos(yaw) * vec(0) + sin(yaw) * vec(1), + -sin(yaw) * vec(0) + cos(yaw) * vec(1), vec(2)); } template @@ -466,9 +603,9 @@ Vector2d ReExpressWorldVector2InBodyYawFrame(const MultibodyPlant& plant, const Vector2d& vec) { Vector3d pelvis_x = plant.GetBodyByName(body_name).EvalPoseInWorld(context).rotation().col(0); - double yaw = atan2(pelvis_x(1), pelvis_x(0)); - return Vector2d(cos(yaw) * vec(0) + sin(yaw)*vec(1), - -sin(yaw) * vec(0) + cos(yaw)*vec(1)); + double yaw = atan2(pelvis_x(1), pelvis_x(0)); + return Vector2d(cos(yaw) * vec(0) + sin(yaw) * vec(1), + -sin(yaw) * vec(0) + cos(yaw) * vec(1)); } VectorXd MakeJointPositionOffsetFromMap( @@ -487,21 +624,21 @@ Eigen::MatrixXd WToQuatDotMap(const Eigen::Vector4d& q) { // clang-format off Eigen::MatrixXd ret(4,3); ret << -q(1), -q(2), -q(3), - q(0), q(3), -q(2), - -q(3), q(0), q(1), - q(2), -q(1), q(0); + q(0), q(3), -q(2), + -q(3), q(0), q(1), + q(2), -q(1), q(0); ret *= 0.5; // clang-format on return ret; } -Eigen::MatrixXd JwrtqdotToJwrtv( - const Eigen::VectorXd& q, const Eigen::MatrixXd& Jwrtqdot) { +Eigen::MatrixXd JwrtqdotToJwrtv(const Eigen::VectorXd& q, + const Eigen::MatrixXd& Jwrtqdot) { //[J_1:4, J_5:end] * [WToQuatDotMap, 0] = [J_1:4 * WToQuatDotMap, J_5:end] // [ 0 , I] DRAKE_DEMAND(Jwrtqdot.cols() == q.size()); - Eigen::MatrixXd ret(Jwrtqdot.rows(), q.size() -1); + Eigen::MatrixXd ret(Jwrtqdot.rows(), q.size() - 1); ret << Jwrtqdot.leftCols<4>() * WToQuatDotMap(q.head<4>()), Jwrtqdot.rightCols(q.size() - 4); return ret; @@ -527,7 +664,7 @@ template vector CreateActuatorNameVectorFromMap(const MultibodyPlant CreateActuatorNameVectorFromMap(const MultibodyPlant& plant); // NOLINT template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapPos(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT template Eigen::MatrixXd CreateWithSpringsToWithoutSpringsMapVel(const drake::multibody::MultibodyPlant& plant_w_spr, const drake::multibody::MultibodyPlant& plant_wo_spr); // NOLINT -template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W, bool show_ground); // NOLINT +template void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W, double stiffness, double dissipation_rate, bool show_ground); // NOLINT template VectorX GetInput(const MultibodyPlant& plant, const Context& context); // NOLINT template VectorX GetInput(const MultibodyPlant& plant, const Context& context); // NOLINT template std::unique_ptr> CreateContext(const MultibodyPlant& plant, const Eigen::Ref& state, const Eigen::Ref& input); // NOLINT diff --git a/multibody/multibody_utils.h b/multibody/multibody_utils.h index 03ad94022a..aa335dd85a 100644 --- a/multibody/multibody_utils.h +++ b/multibody/multibody_utils.h @@ -68,22 +68,36 @@ void AddFlatTerrain(drake::multibody::MultibodyPlant* plant, drake::geometry::SceneGraph* scene_graph, double mu_static, double mu_kinetic, Eigen::Vector3d normal_W = Eigen::Vector3d(0, 0, 1), + double stiffness = 0, double dissipation_rate = 0, bool show_ground = true); /// Get the ordered names from a NameTo___Map std::vector ExtractOrderedNamesFromMap( - const std::map& map); + const std::map& map, int index_start = 0); /// Given a MultibodyPlant, builds a map from position name to position index template std::map MakeNameToPositionsMap( const drake::multibody::MultibodyPlant& plant); +/// Given a MultibodyPlant, builds a map from position name to position index +template +std::map MakeNameToPositionsMap( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index); + /// Given a MultiBodyTree, builds a map from velocity name to velocity index template std::map MakeNameToVelocitiesMap( const drake::multibody::MultibodyPlant& plant); + +/// Given a MultiBodyTree, builds a map from velocity name to velocity index +template +std::map MakeNameToVelocitiesMap( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index); + /// Given a MultiBodyTree, builds a map from actuator name to actuator index template std::map MakeNameToActuatorsMap( diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index e11da4ef05..fd23289204 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -1,11 +1,15 @@ #include "multibody/multipose_visualizer.h" +#include + #include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/geometry/scene_graph.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" using drake::geometry::DrakeVisualizer; +using drake::geometry::Meshcat; using drake::geometry::SceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; @@ -29,7 +33,8 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, - string weld_frame_to_world) + string weld_frame_to_world, + std::shared_ptr meshcat) : num_poses_(num_poses) { DRAKE_DEMAND(num_poses == alpha_scale.size()); DiagramBuilder builder; @@ -40,11 +45,10 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, auto lcm = builder.AddSystem(); Parser parser(plant_, scene_graph); - + parser.SetAutoRenaming(true); // Add num_poses copies of the plant, giving each a unique name for (int i = 0; i < num_poses_; i++) { - auto index = - parser.AddModelFromFile(model_file, "model[" + std::to_string(i) + "]"); + auto index = parser.AddModels(model_file)[0]; model_indices_.push_back(index); if (!weld_frame_to_world.empty()) { plant_->WeldFrames( @@ -88,10 +92,19 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, } } + if (meshcat == nullptr) { + meshcat_ = std::make_shared(); + } else { + meshcat_ = meshcat; + } + meshcat_visualizer_ = + &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, *scene_graph, meshcat_); + DrakeVisualizer::AddToBuilder(&builder, *scene_graph, lcm); + DrakeVisualizer::DispatchLoadMessage(*scene_graph, lcm); diagram_ = builder.Build(); diagram_context_ = diagram_->CreateDefaultContext(); - DrakeVisualizer::DispatchLoadMessage(*scene_graph, lcm); } void MultiposeVisualizer::DrawPoses(MatrixXd poses) { diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index 3d4f28b0d7..5ae9feb9ac 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -4,6 +4,7 @@ #include #include "drake/geometry/scene_graph.h" +#include "drake/geometry/meshcat_visualizer.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/diagram.h" @@ -44,19 +45,27 @@ class MultiposeVisualizer { /// @param alpha_scale Vector, of same length as num_poses. Provideas variable /// scaling of the transparency alpha field of all bodies, indexed by pose /// @param weld_frame_to_world Welds the frame of the given name to the world + /// @param meshcat Pointer to meshcat visualizer for option to attach to an existing meshcat instance MultiposeVisualizer(std::string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, - std::string weld_frame_to_world = ""); + std::string weld_frame_to_world = "", + std::shared_ptr meshcat = nullptr); /// Draws the poses in the given (num_positions x num_poses) matrix /// Note: the matrix can have extra rows (e.g. velocities), which will be /// ignored. void DrawPoses(Eigen::MatrixXd poses); + const std::shared_ptr GetMeshcat(){ + return meshcat_; + } + private: int num_poses_; drake::multibody::MultibodyPlant* plant_; std::unique_ptr> diagram_; + std::shared_ptr meshcat_; + drake::geometry::MeshcatVisualizer* meshcat_visualizer_; std::unique_ptr> diagram_context_; std::vector model_indices_; }; diff --git a/multibody/visualization_utils.cc b/multibody/visualization_utils.cc index b5d819fc0c..4e2922ab35 100644 --- a/multibody/visualization_utils.cc +++ b/multibody/visualization_utils.cc @@ -4,6 +4,8 @@ #include "multibody/com_pose_system.h" #include "systems/primitives/subvector_pass_through.h" #include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/primitives/trajectory_source.h" @@ -37,11 +39,11 @@ void ConnectTrajectoryVisualizer( drake::geometry::SceneGraph* scene_graph, const Trajectory& trajectory) { auto empty_plant = std::make_unique>(0.0); - ConnectTrajectoryVisualizer(plant, builder, scene_graph, trajectory, - *empty_plant); + ConnectTrajectoryVisualizerWithCoM(plant, builder, scene_graph, trajectory, + *empty_plant); } -void ConnectTrajectoryVisualizer( +void ConnectTrajectoryVisualizerWithCoM( const MultibodyPlant* plant, drake::systems::DiagramBuilder* builder, drake::geometry::SceneGraph* scene_graph, @@ -82,6 +84,7 @@ void ConnectTrajectoryVisualizer( } DrakeVisualizer::AddToBuilder(builder, *scene_graph); + } } // namespace multibody diff --git a/multibody/visualization_utils.h b/multibody/visualization_utils.h index 31de4481c2..fba3f5f21a 100644 --- a/multibody/visualization_utils.h +++ b/multibody/visualization_utils.h @@ -27,7 +27,7 @@ void ConnectTrajectoryVisualizer( drake::systems::DiagramBuilder* builder, drake::geometry::SceneGraph* scene_graph, const drake::trajectories::Trajectory& trajectory); -void ConnectTrajectoryVisualizer( +void ConnectTrajectoryVisualizerWithCoM( const drake::multibody::MultibodyPlant* plant, drake::systems::DiagramBuilder* builder, drake::geometry::SceneGraph* scene_graph, diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index b812225a48..fbdc08002d 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -1,7 +1,7 @@ -#include - #include "robot_lcm_systems.h" +#include "dairlib/lcmt_robot_input.hpp" +#include "dairlib/lcmt_robot_output.hpp" #include "multibody/multibody_utils.h" #include "drake/multibody/plant/multibody_plant.h" @@ -9,9 +9,6 @@ #include "drake/systems/lcm/lcm_subscriber_system.h" #include "drake/systems/primitives/discrete_time_delay.h" -#include "dairlib/lcmt_robot_input.hpp" -#include "dairlib/lcmt_robot_output.hpp" - namespace dairlib { namespace systems { @@ -19,9 +16,9 @@ using drake::multibody::JointActuatorIndex; using drake::multibody::JointIndex; using drake::multibody::MultibodyPlant; using drake::systems::Context; +using drake::systems::LeafSystem; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::LeafSystem; using Eigen::VectorXd; using std::string; using systems::OutputVector; @@ -36,6 +33,10 @@ RobotOutputReceiver::RobotOutputReceiver( num_efforts_ = plant.num_actuators(); position_index_map_ = multibody::MakeNameToPositionsMap(plant); velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); + model_instance_ = drake::multibody::ModelInstanceIndex(-1); + + positions_start_idx_ = 0; + velocities_start_idx_ = 0; effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); this->DeclareAbstractInputPort("lcmt_robot_output", drake::Value{}); @@ -46,6 +47,35 @@ RobotOutputReceiver::RobotOutputReceiver( &RobotOutputReceiver::CopyOutput); } +RobotOutputReceiver::RobotOutputReceiver( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance) { + model_instance_ = model_instance; + num_positions_ = plant.num_positions(model_instance); + num_velocities_ = plant.num_velocities(model_instance); + num_efforts_ = plant.num_actuators(); + position_index_map_ = + multibody::MakeNameToPositionsMap(plant, model_instance); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant, model_instance); + + positions_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + velocities_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); + effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + this->DeclareAbstractInputPort("lcmt_robot_output", + drake::Value{}); + this->DeclareVectorOutputPort( + "x, u, t", + OutputVector(plant.num_positions(model_instance), + plant.num_velocities(model_instance), + plant.num_actuators()), + &RobotOutputReceiver::CopyOutput); +} + void RobotOutputReceiver::CopyOutput(const Context& context, OutputVector* output) const { const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); @@ -55,12 +85,12 @@ void RobotOutputReceiver::CopyOutput(const Context& context, VectorXd positions = VectorXd::Zero(num_positions_); for (int i = 0; i < state_msg.num_positions; i++) { int j = position_index_map_.at(state_msg.position_names[i]); - positions(j) = state_msg.position[i]; + positions(j - positions_start_idx_) = state_msg.position[i]; } VectorXd velocities = VectorXd::Zero(num_velocities_); for (int i = 0; i < state_msg.num_velocities; i++) { int j = velocity_index_map_.at(state_msg.velocity_names[i]); - velocities(j) = state_msg.velocity[i]; + velocities(j - velocities_start_idx_) = state_msg.velocity[i]; } VectorXd efforts = VectorXd::Zero(num_efforts_); for (int i = 0; i < state_msg.num_efforts; i++) { @@ -84,16 +114,18 @@ void RobotOutputReceiver::CopyOutput(const Context& context, void RobotOutputReceiver::InitializeSubscriberPositions( const MultibodyPlant& plant, - drake::systems::Context &context) const { + drake::systems::Context& context) const { auto& state_msg = context.get_mutable_abstract_state(0); // using the time from the context state_msg.utime = context.get_time() * 1e6; std::vector ordered_position_names = - multibody::ExtractOrderedNamesFromMap(position_index_map_); + multibody::ExtractOrderedNamesFromMap(position_index_map_, + positions_start_idx_); std::vector ordered_velocity_names = - multibody::ExtractOrderedNamesFromMap(velocity_index_map_); + multibody::ExtractOrderedNamesFromMap(velocity_index_map_, + velocities_start_idx_); std::vector ordered_effort_names = multibody::ExtractOrderedNamesFromMap(effort_index_map_); @@ -110,10 +142,16 @@ void RobotOutputReceiver::InitializeSubscriberPositions( } // Set quaternion w = 1, assumes drake quaternion ordering of wxyz - for (const auto& body_idx : plant.GetFloatingBaseBodies()) { - const auto& body = plant.get_body(body_idx); - if (body.has_quaternion_dofs()) { - state_msg.position[body.floating_positions_start()] = 1; + if (model_instance_ != drake::multibody::ModelInstanceIndex(-1)) { + if (plant.HasUniqueFreeBaseBody(model_instance_)) { + state_msg.position.at(0) = 1; + } + } else { + for (const auto& body_idx : plant.GetFloatingBaseBodies()) { + const auto& body = plant.get_body(body_idx); + if (body.has_quaternion_dofs()) { + state_msg.position.at(body.floating_positions_start()) = 1; + } } } @@ -125,7 +163,6 @@ void RobotOutputReceiver::InitializeSubscriberPositions( /*--------------------------------------------------------------------------*/ // methods implementation for RobotOutputSender. - RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, const bool publish_efforts, const bool publish_imu) @@ -138,6 +175,10 @@ RobotOutputSender::RobotOutputSender( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + model_instance_ = drake::multibody::ModelInstanceIndex(-1); + positions_start_idx_ = 0; + velocities_start_idx_ = 0; + ordered_position_names_ = multibody::ExtractOrderedNamesFromMap(position_index_map_); ordered_velocity_names_ = @@ -164,6 +205,56 @@ RobotOutputSender::RobotOutputSender( &RobotOutputSender::Output); } +RobotOutputSender::RobotOutputSender( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance, + const bool publish_efforts, const bool publish_imu) + : model_instance_(model_instance), + publish_efforts_(publish_efforts), + publish_imu_(publish_imu) { + num_positions_ = plant.num_positions(model_instance); + num_velocities_ = plant.num_velocities(model_instance); + num_efforts_ = plant.num_actuators(); + + position_index_map_ = + multibody::MakeNameToPositionsMap(plant, model_instance); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant, model_instance); + effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); + + positions_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + velocities_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); + + ordered_position_names_ = multibody::ExtractOrderedNamesFromMap( + position_index_map_, positions_start_idx_); + ordered_velocity_names_ = multibody::ExtractOrderedNamesFromMap( + velocity_index_map_, velocities_start_idx_); + ordered_effort_names_ = + multibody::ExtractOrderedNamesFromMap(effort_index_map_); + + state_input_port_ = + this->DeclareVectorInputPort( + "x", BasicVector(num_positions_ + num_velocities_)) + .get_index(); + if (publish_efforts_) { + effort_input_port_ = + this->DeclareVectorInputPort("u", BasicVector(num_efforts_)) + .get_index(); + } + if (publish_imu_) { + imu_input_port_ = + this->DeclareVectorInputPort("imu_acceleration", BasicVector(3)) + .get_index(); + } + + this->DeclareAbstractOutputPort("lcmt_robot_output", + &RobotOutputSender::Output); +} + /// Populate a state message with all states void RobotOutputSender::Output(const Context& context, dairlib::lcmt_robot_output* state_msg) const { @@ -222,9 +313,9 @@ RobotInputReceiver::RobotInputReceiver( actuator_index_map_ = multibody::MakeNameToActuatorsMap(plant); this->DeclareAbstractInputPort("lcmt_robot_input", drake::Value{}); - this->DeclareVectorOutputPort("u, t", - TimestampedVector(num_actuators_), - &RobotInputReceiver::CopyInputOut); + this->DeclareVectorOutputPort( + "u, t", TimestampedVector(num_actuators_), + &RobotInputReceiver::CopyInputOut, {all_sources_ticket()}); } void RobotInputReceiver::CopyInputOut(const Context& context, @@ -284,13 +375,10 @@ void RobotCommandSender::OutputCommand( SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const MultibodyPlant& plant, - drake::systems::lcm::LcmInterfaceSystem* lcm, - std::string actuator_channel, - std::string state_channel, - double publish_rate, - bool publish_efforts, - double actuator_delay) { - + drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, + std::string state_channel, double publish_rate, + drake::multibody::ModelInstanceIndex model_instance_index, + bool publish_efforts, double actuator_delay) { // Create LCM input for actuators auto input_sub = builder->AddSystem(LcmSubscriberSystem::Make( @@ -307,31 +395,32 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( builder->AddSystem(LcmPublisherSystem::Make( state_channel, lcm, 1.0 / publish_rate)); auto state_sender = builder->AddSystem( - plant, publish_efforts); - builder->Connect(plant.get_state_output_port(), + plant, model_instance_index, publish_efforts); + + builder->Connect(plant.get_state_output_port(model_instance_index), state_sender->get_input_port_state()); // Add delay, if used, and associated connections if (actuator_delay > 0) { - auto discrete_time_delay = - builder->AddSystem( - 1.0 / publish_rate, actuator_delay * publish_rate, - plant.num_actuators()); - builder->Connect(*passthrough, *discrete_time_delay); + auto discrete_time_delay = + builder->AddSystem( + 1.0 / publish_rate, actuator_delay * publish_rate, + plant.num_actuators()); + builder->Connect(*passthrough, *discrete_time_delay); + builder->Connect(discrete_time_delay->get_output_port(), + plant.get_actuation_input_port()); + + if (publish_efforts) { builder->Connect(discrete_time_delay->get_output_port(), - plant.get_actuation_input_port()); - - if (publish_efforts) { - builder->Connect(discrete_time_delay->get_output_port(), - state_sender->get_input_port_effort()); - } + state_sender->get_input_port_effort()); + } } else { + builder->Connect(passthrough->get_output_port(), + plant.get_actuation_input_port()); + if (publish_efforts) { builder->Connect(passthrough->get_output_port(), - plant.get_actuation_input_port()); - if (publish_efforts) { - builder->Connect(passthrough->get_output_port(), - state_sender->get_input_port_effort()); - } + state_sender->get_input_port_effort()); + } } builder->Connect(*state_sender, *state_pub); diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 3e1a88c0f6..7ca76144e2 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -29,6 +29,10 @@ class RobotOutputReceiver : public drake::systems::LeafSystem { explicit RobotOutputReceiver( const drake::multibody::MultibodyPlant& plant); + explicit RobotOutputReceiver( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance); + /// Convenience function to initialize an lcmt_robot_output subscriber with /// positions and velocities which are all zero except for the quaternion /// positions, which are all 1, 0, 0, 0 @@ -41,6 +45,9 @@ class RobotOutputReceiver : public drake::systems::LeafSystem { private: void CopyOutput(const drake::systems::Context& context, OutputVector* output) const; + drake::multibody::ModelInstanceIndex model_instance_; + int positions_start_idx_; + int velocities_start_idx_; int num_positions_; int num_velocities_; int num_efforts_; @@ -52,6 +59,12 @@ class RobotOutputReceiver : public drake::systems::LeafSystem { /// Converts a OutputVector object to LCM type lcmt_robot_output class RobotOutputSender : public drake::systems::LeafSystem { public: + explicit RobotOutputSender( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index = + drake::multibody::default_model_instance(), + const bool publish_efforts = false, const bool publish_imu = false); + explicit RobotOutputSender( const drake::multibody::MultibodyPlant& plant, const bool publish_efforts = false, const bool publish_imu = false); @@ -73,6 +86,9 @@ class RobotOutputSender : public drake::systems::LeafSystem { void Output(const drake::systems::Context& context, dairlib::lcmt_robot_output* output) const; + drake::multibody::ModelInstanceIndex model_instance_; + int positions_start_idx_; + int velocities_start_idx_; int num_positions_; int num_velocities_; int num_efforts_; @@ -122,7 +138,6 @@ class RobotCommandSender : public drake::systems::LeafSystem { std::map actuator_index_map_; }; - /// /// Convenience method to add and connect leaf systems for controlling /// a MultibodyPlant via LCM. Makes two primary connections: @@ -148,11 +163,17 @@ class RobotCommandSender : public drake::systems::LeafSystem { SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::systems::DiagramBuilder* builder, const drake::multibody::MultibodyPlant& plant, - drake::systems::lcm::LcmInterfaceSystem* lcm, - std::string actuator_channel, - std::string state_channel, - double publish_rate, - bool publish_efforts = true, + drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, + std::string state_channel, double publish_rate, + drake::multibody::ModelInstanceIndex model_instance_index, + bool publish_efforts = true, double actuator_delay = 0); + +SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( + drake::systems::DiagramBuilder* builder, + const drake::multibody::MultibodyPlant& plant, + drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, + std::string state_channel, double publish_rate, bool publish_efforts = true, double actuator_delay = 0); + } // namespace systems } // namespace dairlib From f83c97a94b3c60e593566f9660db1bdbb3d0b75b Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 6 Nov 2023 15:39:56 -0500 Subject: [PATCH 506/758] adding new object state message to simplify translation between ros and lcm --- examples/Cassie/cassie_xbox_remote.py | 7 +- examples/franka/franka_c3_controller.cc | 4 +- examples/franka/franka_lcm_ros_bridge.cc | 9 +- examples/franka/franka_ros_lcm_bridge.cc | 50 ++--- examples/franka/franka_sim.cc | 8 +- examples/franka/franka_visualizer.cc | 9 +- .../franka_c3_options_translation.yaml | 2 +- examples/franka/systems/franka_kinematics.cc | 10 +- examples/franka/systems/franka_kinematics.h | 1 + lcmtypes/lcmt_object_state.lcm | 3 + solvers/c3_output.cc | 5 - systems/framework/BUILD.bazel | 2 + systems/framework/state_vector.cc | 6 + systems/framework/state_vector.h | 131 +++++++++++ systems/robot_lcm_systems.cc | 204 ++++++++++++++++++ systems/robot_lcm_systems.h | 77 ++++++- systems/ros/franka_ros_lcm_conversions.cc | 192 +++++++++-------- systems/ros/franka_ros_lcm_conversions.h | 127 ++++------- 18 files changed, 588 insertions(+), 259 deletions(-) create mode 100644 systems/framework/state_vector.cc create mode 100644 systems/framework/state_vector.h diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index cabf275888..c19c710a6d 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -63,15 +63,12 @@ def main(): # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands # above this, or they will be erased with this command. - textPrint.reset() + # textPrint.reset() # Get the name from the OS for the controller/joystick name = joystick.get_name() for event in pygame.event.get(): - if event.type == pygame.QUIT: # If user clicked close - done=True # Flag that we are done so we exit this loop - if event.type == pygame.JOYBUTTONDOWN: if event.button == 0: latching_switch_a = not latching_switch_a @@ -98,7 +95,7 @@ def main(): publisher.publish("RADIO", radio_msg.encode()) # Limit to 20 frames per second - clock.tick(100) + clock.tick(60) i += 1 pygame.quit() diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 12a9be0efb..7289e855f0 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -154,12 +154,12 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; auto tray_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( + builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.tray_state_channel, &lcm)); auto franka_state_receiver = builder.AddSystem(plant_franka); auto tray_state_receiver = - builder.AddSystem(plant_tray); + builder.AddSystem(plant_tray); auto reduced_order_model_receiver = builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), diff --git a/examples/franka/franka_lcm_ros_bridge.cc b/examples/franka/franka_lcm_ros_bridge.cc index 48778239b5..685cf6f1a9 100644 --- a/examples/franka/franka_lcm_ros_bridge.cc +++ b/examples/franka/franka_lcm_ros_bridge.cc @@ -1,7 +1,3 @@ -#define ROS - -#ifdef ROS - #include #include @@ -51,7 +47,6 @@ using dairlib::systems::RosToLcmObjectState; using dairlib::systems::RosToLcmRobotState; using dairlib::systems::SubvectorPassThrough; using dairlib::systems::TimestampedVector; -// using dairlib::systems::ROSToRobotOutputLCM; // Shutdown ROS gracefully and then exit void SigintHandler(int sig) { @@ -141,6 +136,4 @@ int DoMain(int argc, char* argv[]) { } // namespace dairlib -int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } - -#endif \ No newline at end of file +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index be5e1a73b4..806ce9e7a8 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -1,7 +1,3 @@ -#define ROS - -#ifdef ROS - #include #include @@ -20,6 +16,7 @@ #include #include +#include "common/find_resource.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "franka_msgs/FrankaState.h" @@ -85,7 +82,10 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant); - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + auto franka_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + auto tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); @@ -98,7 +98,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(RosSubscriberSystem::Make( ros_channel_params.franka_state_channel, &node_handle)); auto ros_to_lcm_robot_state = builder.AddSystem(RosToLcmRobotState::Make( - plant.num_positions(), plant.num_velocities(), plant.num_actuators())); + plant.num_positions(franka_index), plant.num_velocities(franka_index), + plant.num_actuators(franka_index))); // change this to output correctly (i.e. when ros subscriber gets new message) auto robot_output_lcm_publisher = @@ -112,11 +113,12 @@ int DoMain(int argc, char* argv[]) { robot_output_lcm_publisher->get_input_port()); /* -------------------------------------------------------------------------------------------*/ - /// convert ball position estimate to lcm auto tray_object_state_ros_subscriber = builder.AddSystem(RosSubscriberSystem::Make( ros_channel_params.tray_state_channel, &node_handle)); - auto ros_to_lcm_object_state = builder.AddSystem(RosToLcmObjectState::Make()); + auto ros_to_lcm_object_state = builder.AddSystem( + RosToLcmObjectState::Make("tray", plant.num_positions(tray_index), + plant.num_velocities(tray_index))); // change this to output correctly (i.e. when ros subscriber gets new message) auto tray_state_pub = @@ -130,28 +132,6 @@ int DoMain(int argc, char* argv[]) { tray_state_pub->get_input_port()); /* -------------------------------------------------------------------------------------------*/ -// auto robot_input_lcm_subscriber = -// builder.AddSystem(LcmSubscriberSystem::Make( -// lcm_channel_params.franka_input_channel, &drake_lcm)); -// auto robot_input_lcm_echo = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.franka_input_echo, &drake_lcm, -// {drake::systems::TriggerType::kForced})); -// auto robot_input_receiver = builder.AddSystem(plant); -// auto lcm_to_ros_robot_input = builder.AddSystem(7); -// auto robot_input_ros_publisher = builder.AddSystem( -// systems::RosPublisherSystem::Make( -// ros_channel_params.franka_input_channel, &node_handle, -// {drake::systems::TriggerType::kForced})); -// -// builder.Connect(robot_input_lcm_subscriber->get_output_port(), -// robot_input_receiver->get_input_port()); -// builder.Connect(robot_input_lcm_subscriber->get_output_port(), -// robot_input_lcm_echo->get_input_port()); -// builder.Connect(robot_input_receiver->get_output_port(), -// lcm_to_ros_robot_input->get_input_port()); -// builder.Connect(lcm_to_ros_robot_input->get_output_port(), -// robot_input_ros_publisher->get_input_port()); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_ros_lcm_bridge")); @@ -183,7 +163,6 @@ int DoMain(int argc, char* argv[]) { franka_joint_state_ros_subscriber->WaitForMessage(old_message_count); const double time = franka_joint_state_ros_subscriber->message_time(); - // Check if we are very far ahead or behind // (likely due to a restart of the driving clock) if (time > simulator.get_context().get_time() + 1.0 || @@ -201,18 +180,13 @@ int DoMain(int argc, char* argv[]) { // Force-publish via the diagram diagram.CalcForcedUnrestrictedUpdate(diagram_context, &diagram_context.get_mutable_state()); - diagram.CalcForcedDiscreteVariableUpdate(diagram_context, - &diagram_context.get_mutable_discrete_state()); + diagram.CalcForcedDiscreteVariableUpdate( + diagram_context, &diagram_context.get_mutable_discrete_state()); diagram.ForcedPublish(diagram_context); } - - // simulator.AdvanceTo(std::numeric_limits::infinity()); - return 0; } } // namespace dairlib int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } - -#endif \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index dc55e43f6f..a28638a6a5 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -129,15 +129,15 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.franka_state_channel, sim_params.publish_rate, franka_index, sim_params.publish_efforts, sim_params.actuator_delay); auto tray_state_sender = - builder.AddSystem(plant, tray_index); + builder.AddSystem(plant, tray_index); auto tray_state_pub = - builder.AddSystem(LcmPublisherSystem::Make( + builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, lcm, 1.0 / sim_params.publish_rate)); auto box_state_sender = - builder.AddSystem(plant, box_index); + builder.AddSystem(plant, box_index); auto box_state_pub = - builder.AddSystem(LcmPublisherSystem::Make( + builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.box_state_channel, lcm, 1.0 / sim_params.publish_rate)); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index b66f5c8d8d..6132fd017b 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -36,6 +36,7 @@ using Eigen::Vector3d; using Eigen::VectorXd; using dairlib::systems::RobotOutputReceiver; +using dairlib::systems::ObjectStateReceiver; using dairlib::systems::SubvectorPassThrough; using drake::geometry::DrakeVisualizer; using drake::geometry::SceneGraph; @@ -107,17 +108,17 @@ int do_main(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.franka_state_channel, lcm)); auto tray_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( + builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.tray_state_channel, lcm)); auto box_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( + builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.box_state_channel, lcm)); auto franka_state_receiver = builder.AddSystem(plant, franka_index); auto tray_state_receiver = - builder.AddSystem(plant, tray_index); + builder.AddSystem(plant, tray_index); auto box_state_receiver = - builder.AddSystem(plant, box_index); + builder.AddSystem(plant, box_index); auto franka_passthrough = builder.AddSystem( franka_state_receiver->get_output_port(0).size(), 0, diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 0a3dbea683..91e14b219e 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -10,7 +10,7 @@ dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 -N: 7 +N: 5 # matrix scaling w_Q: 5 diff --git a/examples/franka/systems/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc index 66f43e938d..ae4fade422 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -12,6 +12,7 @@ using drake::systems::BasicVector; using drake::systems::Context; using Eigen::VectorXd; using systems::OutputVector; +using systems::StateVector; using systems::TimestampedVector; namespace systems { @@ -41,9 +42,8 @@ FrankaKinematics::FrankaKinematics(const MultibodyPlant& franka_plant, object_state_port_ = this->DeclareVectorInputPort( - "x_object", OutputVector(object_plant.num_positions(), - object_plant.num_velocities(), - object_plant.num_actuators())) + "x_object", StateVector(object_plant.num_positions(), + object_plant.num_velocities())) .get_index(); num_end_effector_positions_ = 3 + include_end_effector_orientation_ * 3; num_object_positions_ = 7; @@ -64,8 +64,8 @@ void FrankaKinematics::ComputeLCSState( FrankaKinematicsVector* lcs_state) const { const OutputVector* franka_output = (OutputVector*)this->EvalVectorInput(context, franka_state_port_); - const OutputVector* object_output = - (OutputVector*)this->EvalVectorInput(context, object_state_port_); + const StateVector* object_output = + (StateVector*)this->EvalVectorInput(context, object_state_port_); VectorXd q_franka = franka_output->GetPositions(); VectorXd v_franka = franka_output->GetVelocities(); diff --git a/examples/franka/systems/franka_kinematics.h b/examples/franka/systems/franka_kinematics.h index e020e475b6..cc57c8dee7 100644 --- a/examples/franka/systems/franka_kinematics.h +++ b/examples/franka/systems/franka_kinematics.h @@ -8,6 +8,7 @@ #include "drake/systems/framework/leaf_system.h" #include "systems/framework/timestamped_vector.h" #include "systems/framework/output_vector.h" +#include "systems/framework/state_vector.h" namespace dairlib { namespace systems { diff --git a/lcmtypes/lcmt_object_state.lcm b/lcmtypes/lcmt_object_state.lcm index 55c7f739f6..aa5d1cffa2 100644 --- a/lcmtypes/lcmt_object_state.lcm +++ b/lcmtypes/lcmt_object_state.lcm @@ -8,6 +8,9 @@ struct lcmt_object_state int32_t num_positions; int32_t num_velocities; + string position_names [num_positions]; double position [num_positions]; + + string velocity_names [num_velocities]; double velocity [num_velocities]; } diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc index 0630937aea..fd5629d1b6 100644 --- a/solvers/c3_output.cc +++ b/solvers/c3_output.cc @@ -14,8 +14,6 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { lcmt_c3_intermediates c3_intermediates; c3_output.utime = static_cast(1e6 * time); - std::cout << c3_solution_.time_vector_.size() << std::endl; - std::cout << c3_solution_.x_sol_.rows() << std::endl; c3_solution.num_points = c3_solution_.time_vector_.size(); int knot_points = c3_solution.num_points; c3_solution.num_state_variables = c3_solution_.x_sol_.rows(); @@ -74,11 +72,8 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { sizeof(float) * knot_points); } - - // c3_output.c3_solution = c3_solution; c3_output.c3_intermediates = lcmt_c3_intermediates(); - std::cout << "constructed c3 output" << std::endl; return c3_output; } diff --git a/systems/framework/BUILD.bazel b/systems/framework/BUILD.bazel index a762800015..2b9b27766a 100644 --- a/systems/framework/BUILD.bazel +++ b/systems/framework/BUILD.bazel @@ -9,11 +9,13 @@ cc_library( srcs = [ "impact_info_vector.cc", "output_vector.cc", + "state_vector.cc", "timestamped_vector.cc", ], hdrs = [ "impact_info_vector.h", "output_vector.h", + "state_vector.h", "timestamped_vector.h", ], deps = [ diff --git a/systems/framework/state_vector.cc b/systems/framework/state_vector.cc new file mode 100644 index 0000000000..60ae8e4de5 --- /dev/null +++ b/systems/framework/state_vector.cc @@ -0,0 +1,6 @@ +#include "systems/framework/state_vector.h" + +#include "drake/common/default_scalars.h" + +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( + class ::dairlib::systems::StateVector) diff --git a/systems/framework/state_vector.h b/systems/framework/state_vector.h new file mode 100644 index 0000000000..506933dd12 --- /dev/null +++ b/systems/framework/state_vector.h @@ -0,0 +1,131 @@ +#pragma once + +#include "systems/framework/timestamped_vector.h" +#include +#include + + +namespace dairlib { +namespace systems { + +using drake::VectorX; +using std::string; +using std::vector; + +/// StateVector stores the object state as a TimestampedVector +/// * positions +/// * velocities +/// Similar to OutputVector but only the state variables +template +class StateVector : public TimestampedVector { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(StateVector) + + StateVector() = default; + + /// Initializes with the given @p size using the drake::dummy_value, which + /// is NaN when T = double. + explicit StateVector(int num_positions, int num_velocities) + : TimestampedVector(num_positions + num_velocities), + num_positions_(num_positions), + num_velocities_(num_velocities), + position_start_(0){} + + /// Constructs a StateVector with the specified positions and velocities. + explicit StateVector(const VectorX& positions, + const VectorX& velocities) + : StateVector(positions.size(), velocities.size()) { + this->SetPositions(positions); + this->SetVelocities(velocities); + } + + void SetPositions(VectorX positions) { + this->get_mutable_data().segment(position_start_, + num_positions_) = positions; + } + + void SetVelocities(VectorX velocities) { + this->get_mutable_data().segment(position_start_ + num_positions_, + num_velocities_) = velocities; + } + + void SetPositionAtIndex(int index, T value) { + this->SetAtIndex(position_start_ + index, value); + } + + void SetVelocityAtIndex(int index, T value) { + this->SetAtIndex(position_start_ + num_positions_ + index, value); + } + + void SetState(VectorX state) { + this->get_mutable_data().segment(position_start_, + num_positions_ + num_velocities_) = state; + } + + /// Returns a const state vector + const VectorX GetState() const { + return this->get_data().segment(position_start_, + num_positions_ + num_velocities_); + } + + /// Returns a const positions vector + const VectorX GetPositions() const { + return this->get_data().segment(position_start_, num_positions_); + } + + /// Returns a const velocities vector + const VectorX GetVelocities() const { + return this->get_data().segment(position_start_ + num_positions_, + num_velocities_); + } + + /// Returns a mutable state vector + Eigen::Map> GetMutableState() { + auto data = this->get_mutable_data().segment(position_start_, + num_positions_ + num_velocities_); + return Eigen::Map>(&data(0), data.size()); + } + + /// Returns a mutable positions vector + Eigen::Map> GetMutablePositions() { + auto data = this->get_mutable_data().segment(position_start_, num_positions_); + return Eigen::Map>(&data(0), data.size()); + } + + /// Returns a mutable velocities vector + Eigen::Map> GetMutableVelocities() { + auto data = this->get_mutable_data().segment( + position_start_ + num_positions_, num_velocities_); + return Eigen::Map>(&data(0), data.size()); + } + + T GetPositionAtIndex(int index) const { + return this->GetAtIndex(position_start_ + index); + } + + T GetVelocityAtIndex(int index) const { + return this->GetAtIndex(position_start_ + num_positions_ + index); + } + + void SetName(int index, string name) { + position_names_[index] = name; + } + + string GetName(int index) { + return position_names_[index]; + } + + protected: + virtual StateVector* DoClone() const { + return new StateVector(num_positions_, num_velocities_); + } + + private: + const int num_positions_; + const int num_velocities_; + const int position_start_; + vector position_names_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 4e65eb8c7c..84de91dc39 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -304,6 +304,210 @@ void RobotOutputSender::Output(const Context& context, } } +ObjectStateReceiver::ObjectStateReceiver( + const drake::multibody::MultibodyPlant& plant) { + num_positions_ = plant.num_positions(); + num_velocities_ = plant.num_velocities(); + position_index_map_ = multibody::MakeNameToPositionsMap(plant); + velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); + model_instance_ = drake::multibody::ModelInstanceIndex(-1); + + positions_start_idx_ = 0; + velocities_start_idx_ = 0; + this->DeclareAbstractInputPort("lcmt_object_state", + drake::Value{}); + this->DeclareVectorOutputPort( + "x, t", + StateVector(plant.num_positions(), plant.num_velocities()), + &ObjectStateReceiver::CopyOutput); +} + +ObjectStateReceiver::ObjectStateReceiver( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance) { + model_instance_ = model_instance; + num_positions_ = plant.num_positions(model_instance); + num_velocities_ = plant.num_velocities(model_instance); + position_index_map_ = + multibody::MakeNameToPositionsMap(plant, model_instance); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant, model_instance); + + positions_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + velocities_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); + this->DeclareAbstractInputPort("lcmt_object_state", + drake::Value{}); + this->DeclareVectorOutputPort( + "x, t", + StateVector(plant.num_positions(model_instance), + plant.num_velocities(model_instance)), + &ObjectStateReceiver::CopyOutput); +} + +void ObjectStateReceiver::CopyOutput(const Context& context, + StateVector* output) const { + const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); + DRAKE_ASSERT(input != nullptr); + const auto& state_msg = input->get_value(); + + VectorXd positions = VectorXd::Zero(num_positions_); + for (int i = 0; i < state_msg.num_positions; i++) { + int j = position_index_map_.at(state_msg.position_names[i]); + positions(j - positions_start_idx_) = state_msg.position[i]; + } + VectorXd velocities = VectorXd::Zero(num_velocities_); + for (int i = 0; i < state_msg.num_velocities; i++) { + int j = velocity_index_map_.at(state_msg.velocity_names[i]); + velocities(j - velocities_start_idx_) = state_msg.velocity[i]; + } + + output->SetPositions(positions); + output->SetVelocities(velocities); + output->set_timestamp(state_msg.utime * 1.0e-6); +} + +void ObjectStateReceiver::InitializeSubscriberPositions( + const MultibodyPlant& plant, + drake::systems::Context& context) const { + auto& state_msg = context.get_mutable_abstract_state(0); + + // using the time from the context + state_msg.utime = context.get_time() * 1e6; + + std::vector ordered_position_names = + multibody::ExtractOrderedNamesFromMap(position_index_map_, + positions_start_idx_); + std::vector ordered_velocity_names = + multibody::ExtractOrderedNamesFromMap(velocity_index_map_, + velocities_start_idx_); + + state_msg.num_positions = num_positions_; + state_msg.num_velocities = num_velocities_; + state_msg.position_names.resize(num_positions_); + state_msg.velocity_names.resize(num_velocities_); + state_msg.position.resize(num_positions_); + state_msg.velocity.resize(num_positions_); + + for (int i = 0; i < num_positions_; i++) { + state_msg.position_names[i] = ordered_position_names[i]; + state_msg.position[i] = 0; + } + + // Set quaternion w = 1, assumes drake quaternion ordering of wxyz + if (model_instance_ != drake::multibody::ModelInstanceIndex(-1)) { + if (plant.HasUniqueFreeBaseBody(model_instance_)) { + state_msg.position.at(0) = 1; + } + } else { + for (const auto& body_idx : plant.GetFloatingBaseBodies()) { + const auto& body = plant.get_body(body_idx); + if (body.has_quaternion_dofs()) { + state_msg.position.at(body.floating_positions_start()) = 1; + } + } + } + + for (int i = 0; i < num_velocities_; i++) { + state_msg.velocity[i] = 0; + state_msg.velocity_names[i] = ordered_velocity_names[i]; + } +} + +/*--------------------------------------------------------------------------*/ +// methods implementation for RobotOutputSender. +ObjectStateSender::ObjectStateSender( + const drake::multibody::MultibodyPlant& plant){ + num_positions_ = plant.num_positions(); + num_velocities_ = plant.num_velocities(); + + position_index_map_ = multibody::MakeNameToPositionsMap(plant); + velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); + + model_instance_ = drake::multibody::ModelInstanceIndex(-1); + positions_start_idx_ = 0; + velocities_start_idx_ = 0; + + ordered_position_names_ = + multibody::ExtractOrderedNamesFromMap(position_index_map_); + ordered_velocity_names_ = + multibody::ExtractOrderedNamesFromMap(velocity_index_map_); + + state_input_port_ = + this->DeclareVectorInputPort( + "x", BasicVector(num_positions_ + num_velocities_)) + .get_index(); + + this->DeclareAbstractOutputPort("lcmt_object_state", + &ObjectStateSender::Output); +} + +ObjectStateSender::ObjectStateSender( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance) + : model_instance_(model_instance){ + num_positions_ = plant.num_positions(model_instance); + num_velocities_ = plant.num_velocities(model_instance); + + position_index_map_ = + multibody::MakeNameToPositionsMap(plant, model_instance); + velocity_index_map_ = + multibody::MakeNameToVelocitiesMap(plant, model_instance); + + positions_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + velocities_start_idx_ = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); + + ordered_position_names_ = + multibody::ExtractOrderedNamesFromMap(position_index_map_, positions_start_idx_); + ordered_velocity_names_ = + multibody::ExtractOrderedNamesFromMap(velocity_index_map_, velocities_start_idx_); + + + state_input_port_ = + this->DeclareVectorInputPort( + "x", BasicVector(num_positions_ + num_velocities_)) + .get_index(); + + this->DeclareAbstractOutputPort("lcmt_object_state", + &ObjectStateSender::Output); +} + +/// Populate a state message with all states +void ObjectStateSender::Output(const Context& context, + dairlib::lcmt_object_state* state_msg) const { + const auto state = this->EvalVectorInput(context, state_input_port_); + + // using the time from the context + state_msg->utime = context.get_time() * 1e6; + + state_msg->num_positions = num_positions_; + state_msg->num_velocities = num_velocities_; + state_msg->position_names.resize(num_positions_); + state_msg->velocity_names.resize(num_velocities_); + state_msg->position.resize(num_positions_); + state_msg->velocity.resize(num_velocities_); + + for (int i = 0; i < num_positions_; i++) { + state_msg->position_names[i] = ordered_position_names_[i]; + if (std::isnan(state->GetAtIndex(i))) { + state_msg->position[i] = 0; + } else { + state_msg->position[i] = state->GetAtIndex(i); + } + } + for (int i = 0; i < num_velocities_; i++) { + state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); + state_msg->velocity_names[i] = ordered_velocity_names_[i]; + } +} + /*--------------------------------------------------------------------------*/ // methods implementation for RobotInputReceiver. diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 2abd106ddd..6694dcbd87 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -4,9 +4,12 @@ #include #include +#include + #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_robot_output.hpp" #include "systems/framework/output_vector.h" +#include "systems/framework/state_vector.h" #include "systems/framework/timestamped_vector.h" #include "systems/primitives/subvector_pass_through.h" @@ -18,10 +21,9 @@ namespace dairlib { namespace systems { /// @file This file contains classes dealing with sending/receiving -/// LCM messages related to a robot. The classes in this file are based on -/// acrobot_lcm.h +/// LCM messages related to a robot. -/// Receives the output of an LcmSubsriberSystem that subsribes to the +/// Receives the output of an LcmSubscriberSystem that subscribes to the /// Robot output channel with LCM type lcmt_robot_output, and outputs the /// robot states as a OutputVector. class RobotOutputReceiver : public drake::systems::LeafSystem { @@ -105,7 +107,74 @@ class RobotOutputSender : public drake::systems::LeafSystem { bool publish_imu_; }; -/// Receives the output of an LcmSubsriberSystem that subsribes to the +/// @file This file contains classes dealing with sending/receiving +/// LCM messages related to a object. + +/// Receives the output of an LcmSubscriberSystem that subscribes to the +/// object state channel with LCM type lcmt_object_state, and outputs the +/// object state as a StateVector. +class ObjectStateReceiver : public drake::systems::LeafSystem { + public: + explicit ObjectStateReceiver( + const drake::multibody::MultibodyPlant& plant); + + explicit ObjectStateReceiver( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance); + + /// Convenience function to initialize an lcmt_object_state subscriber with + /// positions and velocities which are all zero except for the quaternion + /// positions, which are all 1, 0, 0, 0 + /// @param context The context of a + /// drake::LcmSubscriberSystem + void InitializeSubscriberPositions( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context& context) const; + + private: + void CopyOutput(const drake::systems::Context& context, + StateVector* output) const; + drake::multibody::ModelInstanceIndex model_instance_; + int positions_start_idx_; + int velocities_start_idx_; + int num_positions_; + int num_velocities_; + std::map position_index_map_; + std::map velocity_index_map_; +}; + +/// Converts a StateVector object to LCM type lcmt_robot_output +class ObjectStateSender : public drake::systems::LeafSystem { + public: + explicit ObjectStateSender( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance_index = + drake::multibody::default_model_instance()); + + explicit ObjectStateSender( + const drake::multibody::MultibodyPlant& plant); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_input_port_); + } + + private: + void Output(const drake::systems::Context& context, + dairlib::lcmt_object_state* output) const; + + drake::multibody::ModelInstanceIndex model_instance_; + int positions_start_idx_; + int velocities_start_idx_; + int num_positions_; + int num_velocities_; + std::vector ordered_position_names_; + std::vector ordered_velocity_names_; + std::map position_index_map_; + std::map velocity_index_map_; + int state_input_port_ = -1; +}; + +/// Receives the output of an LcmSubscriberSystem that subscribes to the /// robot input channel with LCM type lcmt_robot_input and outputs the /// robot inputs as a TimestampedVector. class RobotInputReceiver : public drake::systems::LeafSystem { diff --git a/systems/ros/franka_ros_lcm_conversions.cc b/systems/ros/franka_ros_lcm_conversions.cc index 28d1b79e5b..f153cdaa3e 100644 --- a/systems/ros/franka_ros_lcm_conversions.cc +++ b/systems/ros/franka_ros_lcm_conversions.cc @@ -9,28 +9,27 @@ using Eigen::VectorXd; // LcmToRosTimestampedVector implementation LcmToRosTimestampedVector::LcmToRosTimestampedVector(int vector_size) : vector_size_(vector_size) { - - this->DeclareVectorInputPort("u, t", - TimestampedVector(vector_size_)); + this->DeclareVectorInputPort("u, t", TimestampedVector(vector_size_)); this->DeclareAbstractOutputPort("ROS Float64MultiArray", &LcmToRosTimestampedVector::ConvertToROS); }; -void LcmToRosTimestampedVector::ConvertToROS(const drake::systems::Context& context, - std_msgs::Float64MultiArray* output) const { - +void LcmToRosTimestampedVector::ConvertToROS( + const drake::systems::Context& context, + std_msgs::Float64MultiArray* output) const { const TimestampedVector* input = - (TimestampedVector*)this->EvalVectorInput(context, 0); + (TimestampedVector*)this->EvalVectorInput(context, 0); - // note: this function currently appends the timestamp to the end of the output + // note: this function currently appends the timestamp to the end of the + // output output->data.clear(); -// std::cout << "time: " << input->get_timestamp() << std::endl; - for (int i = 0; i < vector_size_; i++){ -// std::cout << "value: " << i << " " << input->GetAtIndex(i) << std::endl; - if (std::isnan(input->GetAtIndex(i))){ + // std::cout << "time: " << input->get_timestamp() << std::endl; + for (int i = 0; i < vector_size_; i++) { + // std::cout << "value: " << i << " " << input->GetAtIndex(i) << + // std::endl; + if (std::isnan(input->GetAtIndex(i))) { output->data.push_back(0); - } - else{ + } else { output->data.push_back(input->GetAtIndex(i)); } } @@ -40,18 +39,20 @@ void LcmToRosTimestampedVector::ConvertToROS(const drake::systems::ContextDeclareAbstractInputPort("Franka JointState topic", drake::Value()); this->DeclareAbstractOutputPort("lcmt_robot_output", &RosToLcmRobotState::ConvertToLCM); } -void RosToLcmRobotState::ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_robot_output* output) const { - +void RosToLcmRobotState::ConvertToLCM( + const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const { const drake::AbstractValue* const input = this->EvalAbstractInput(context, 0); DRAKE_ASSERT(input != nullptr); const auto& msg = input->get_value(); @@ -70,185 +71,182 @@ void RosToLcmRobotState::ConvertToLCM(const drake::systems::Context& con output->effort.resize(num_efforts_); // yet to receive message from rostopic - if (msg.position.empty()){ - for (int i = 0; i < num_positions_; i++){ + if (msg.position.empty()) { + for (int i = 0; i < num_positions_; i++) { output->position[i] = nan(""); } - for (int i = 0; i < num_velocities_; i++){ + for (int i = 0; i < num_velocities_; i++) { output->velocity[i] = nan(""); } - for (int i = 0; i < num_efforts_; i++){ + for (int i = 0; i < num_efforts_; i++) { output->effort[i] = nan(""); } - for (int i = 0; i < 3; i++){ + for (int i = 0; i < 3; i++) { output->imu_accel[i] = nan(""); } } - // input should be order as "positions, velocities, effort, timestamp" - else{ - for (int i = 0; i < num_franka_joints_; i++){ + // input should be order as "positions, velocities, effort, timestamp" + else { + for (int i = 0; i < num_franka_joints_; i++) { output->position[i] = msg.position[i]; } // hard coded to add 7 zeros to the end of position - for (int i = num_franka_joints_; i < num_positions_; i++){ - output->position[i] = default_ball_position_[i-num_franka_joints_]; + for (int i = num_franka_joints_; i < num_positions_; i++) { + output->position[i] = default_ball_position_[i - num_franka_joints_]; } - for (int i = 0; i < num_velocities_; i++){ + for (int i = 0; i < num_velocities_; i++) { output->velocity[i] = msg.velocity[i]; } // hard coded to add 6 zeros to the end of velocity - for (int i = num_franka_joints_; i < num_velocities_; i++){ + for (int i = num_franka_joints_; i < num_velocities_; i++) { output->velocity[i] = 0; } - for (int i = 0; i < num_efforts_; i++){ + for (int i = 0; i < num_efforts_; i++) { output->effort[i] = msg.effort[i]; } - for (int i = 0; i < 3; i++){ + for (int i = 0; i < 3; i++) { output->imu_accel[i] = 0; } } output->utime = context.get_time() * 1e6; } - /***************************************************************************************/ // RosToLcmFrankaState implementation RosToLcmFrankaState::RosToLcmFrankaState() { - this->DeclareAbstractInputPort("ROS Float64MultiArray", drake::Value()); this->DeclareAbstractOutputPort("lcmt_franka_state", &RosToLcmFrankaState::ConvertToLCM); } -void RosToLcmFrankaState::ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_franka_state* franka_state) const { - +void RosToLcmFrankaState::ConvertToLCM( + const drake::systems::Context& context, + dairlib::lcmt_franka_state* franka_state) const { const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); const auto& msg = input->get_value(); - if (msg.O_T_EE.empty()){ + if (msg.O_T_EE.empty()) { franka_state->valid = false; - } - else{ - for (size_t i = 0; i < msg.O_T_EE.size(); i++){ + } else { + for (size_t i = 0; i < msg.O_T_EE.size(); i++) { franka_state->O_T_EE[i] = msg.O_T_EE[i]; } - for (size_t i = 0; i < msg.O_T_EE_d.size(); i++){ + for (size_t i = 0; i < msg.O_T_EE_d.size(); i++) { franka_state->O_T_EE_d[i] = msg.O_T_EE_d[i]; } - for (size_t i = 0; i < msg.F_T_EE.size(); i++){ + for (size_t i = 0; i < msg.F_T_EE.size(); i++) { franka_state->F_T_EE[i] = msg.F_T_EE[i]; } - for (size_t i = 0; i < msg.F_T_NE.size(); i++){ + for (size_t i = 0; i < msg.F_T_NE.size(); i++) { franka_state->F_T_NE[i] = msg.F_T_NE[i]; } - for (size_t i = 0; i < msg.NE_T_EE.size(); i++){ + for (size_t i = 0; i < msg.NE_T_EE.size(); i++) { franka_state->NE_T_EE[i] = msg.NE_T_EE[i]; } - for (size_t i = 0; i < msg.EE_T_K.size(); i++){ + for (size_t i = 0; i < msg.EE_T_K.size(); i++) { franka_state->EE_T_K[i] = msg.EE_T_K[i]; } franka_state->m_ee = msg.m_ee; - for (size_t i = 0; i < msg.I_ee.size(); i++){ + for (size_t i = 0; i < msg.I_ee.size(); i++) { franka_state->I_ee[i] = msg.I_ee[i]; } - for (size_t i = 0; i < msg.F_x_Cee.size(); i++){ + for (size_t i = 0; i < msg.F_x_Cee.size(); i++) { franka_state->F_x_Cee[i] = msg.F_x_Cee[i]; } franka_state->m_load = msg.m_load; - for (size_t i = 0; i < msg.I_load.size(); i++){ + for (size_t i = 0; i < msg.I_load.size(); i++) { franka_state->I_load[i] = msg.I_load[i]; } - for (size_t i = 0; i < msg.F_x_Cload.size(); i++){ + for (size_t i = 0; i < msg.F_x_Cload.size(); i++) { franka_state->F_x_Cload[i] = msg.F_x_Cload[i]; } franka_state->m_total = msg.m_total; - for (size_t i = 0; i < msg.I_total.size(); i++){ + for (size_t i = 0; i < msg.I_total.size(); i++) { franka_state->I_total[i] = msg.I_total[i]; } - for (size_t i = 0; i < msg.F_x_Ctotal.size(); i++){ + for (size_t i = 0; i < msg.F_x_Ctotal.size(); i++) { franka_state->F_x_Ctotal[i] = msg.F_x_Ctotal[i]; } - for (size_t i = 0; i < msg.elbow.size(); i++){ + for (size_t i = 0; i < msg.elbow.size(); i++) { franka_state->elbow[i] = msg.elbow[i]; } - for (size_t i = 0; i < msg.elbow_d.size(); i++){ + for (size_t i = 0; i < msg.elbow_d.size(); i++) { franka_state->elbow_d[i] = msg.elbow_d[i]; } - for (size_t i = 0; i < msg.elbow_c.size(); i++){ + for (size_t i = 0; i < msg.elbow_c.size(); i++) { franka_state->elbow_c[i] = msg.elbow_c[i]; } - for (size_t i = 0; i < msg.delbow_c.size(); i++){ + for (size_t i = 0; i < msg.delbow_c.size(); i++) { franka_state->delbow_c[i] = msg.delbow_c[i]; } - for (size_t i = 0; i < msg.ddelbow_c.size(); i++){ + for (size_t i = 0; i < msg.ddelbow_c.size(); i++) { franka_state->ddelbow_c[i] = msg.ddelbow_c[i]; } - for (size_t i = 0; i < msg.tau_J.size(); i++){ + for (size_t i = 0; i < msg.tau_J.size(); i++) { franka_state->tau_J[i] = msg.tau_J[i]; } - for (size_t i = 0; i < msg.tau_J_d.size(); i++){ + for (size_t i = 0; i < msg.tau_J_d.size(); i++) { franka_state->tau_J_d[i] = msg.tau_J_d[i]; } - for (size_t i = 0; i < msg.dtau_J.size(); i++){ + for (size_t i = 0; i < msg.dtau_J.size(); i++) { franka_state->dtau_J[i] = msg.dtau_J[i]; } - for (size_t i = 0; i < msg.q.size(); i++){ + for (size_t i = 0; i < msg.q.size(); i++) { franka_state->q[i] = msg.q[i]; } - for (size_t i = 0; i < msg.q_d.size(); i++){ + for (size_t i = 0; i < msg.q_d.size(); i++) { franka_state->q_d[i] = msg.q_d[i]; } - for (size_t i = 0; i < msg.dq.size(); i++){ + for (size_t i = 0; i < msg.dq.size(); i++) { franka_state->dq[i] = msg.dq[i]; } - for (size_t i = 0; i < msg.dq_d.size(); i++){ + for (size_t i = 0; i < msg.dq_d.size(); i++) { franka_state->dq_d[i] = msg.dq_d[i]; } - for (size_t i = 0; i < msg.ddq_d.size(); i++){ + for (size_t i = 0; i < msg.ddq_d.size(); i++) { franka_state->ddq_d[i] = msg.ddq_d[i]; } - for (size_t i = 0; i < msg.joint_contact.size(); i++){ + for (size_t i = 0; i < msg.joint_contact.size(); i++) { franka_state->joint_contact[i] = msg.joint_contact[i]; } - for (size_t i = 0; i < msg.cartesian_contact.size(); i++){ + for (size_t i = 0; i < msg.cartesian_contact.size(); i++) { franka_state->cartesian_contact[i] = msg.cartesian_contact[i]; } - for (size_t i = 0; i < msg.joint_collision.size(); i++){ + for (size_t i = 0; i < msg.joint_collision.size(); i++) { franka_state->joint_collision[i] = msg.joint_collision[i]; } - for (size_t i = 0; i < msg.cartesian_collision.size(); i++){ + for (size_t i = 0; i < msg.cartesian_collision.size(); i++) { franka_state->cartesian_collision[i] = msg.cartesian_collision[i]; } - for (size_t i = 0; i < msg.tau_ext_hat_filtered.size(); i++){ + for (size_t i = 0; i < msg.tau_ext_hat_filtered.size(); i++) { franka_state->tau_ext_hat_filtered[i] = msg.tau_ext_hat_filtered[i]; } - for (size_t i = 0; i < msg.O_F_ext_hat_K.size(); i++){ + for (size_t i = 0; i < msg.O_F_ext_hat_K.size(); i++) { franka_state->O_F_ext_hat_K[i] = msg.O_F_ext_hat_K[i]; } - for (size_t i = 0; i < msg.K_F_ext_hat_K.size(); i++){ + for (size_t i = 0; i < msg.K_F_ext_hat_K.size(); i++) { franka_state->K_F_ext_hat_K[i] = msg.K_F_ext_hat_K[i]; } - for (size_t i = 0; i < msg.O_dP_EE_d.size(); i++){ + for (size_t i = 0; i < msg.O_dP_EE_d.size(); i++) { franka_state->O_dP_EE_d[i] = msg.O_dP_EE_d[i]; } - for (size_t i = 0; i < msg.O_T_EE_c.size(); i++){ + for (size_t i = 0; i < msg.O_T_EE_c.size(); i++) { franka_state->O_T_EE_c[i] = msg.O_T_EE_c[i]; } - for (size_t i = 0; i < msg.O_dP_EE_c.size(); i++){ + for (size_t i = 0; i < msg.O_dP_EE_c.size(); i++) { franka_state->O_dP_EE_c[i] = msg.O_dP_EE_c[i]; } - for (size_t i = 0; i < msg.O_ddP_EE_c.size(); i++){ + for (size_t i = 0; i < msg.O_ddP_EE_c.size(); i++) { franka_state->O_ddP_EE_c[i] = msg.O_ddP_EE_c[i]; } - for (size_t i = 0; i < msg.theta.size(); i++){ + for (size_t i = 0; i < msg.theta.size(); i++) { franka_state->theta[i] = msg.theta[i]; } - for (size_t i = 0; i < msg.dtheta.size(); i++){ + for (size_t i = 0; i < msg.dtheta.size(); i++) { franka_state->dtheta[i] = msg.dtheta[i]; } @@ -260,7 +258,8 @@ void RosToLcmFrankaState::ConvertToLCM(const drake::systems::Context& co ss_last_motion_errors << msg.last_motion_errors; franka_state->last_motion_errors = ss_last_motion_errors.str(); - franka_state->control_command_success_rate = msg.control_command_success_rate; + franka_state->control_command_success_rate = + msg.control_command_success_rate; franka_state->robot_mode = msg.robot_mode; // time from franka robot franka_state->franka_time = msg.time; @@ -271,30 +270,33 @@ void RosToLcmFrankaState::ConvertToLCM(const drake::systems::Context& co } /***************************************************************************************/ -// RosToLcmObjectState implementation - -RosToLcmObjectState::RosToLcmObjectState() { - +RosToLcmObjectState::RosToLcmObjectState(const std::string& object_name, + int num_positions, + int num_velocities) { this->DeclareAbstractInputPort("ROS Float64MultiArray", drake::Value()); - this->DeclareAbstractOutputPort("ball_position", + dairlib::lcmt_object_state object_state = dairlib::lcmt_object_state(); + object_state.num_positions = num_positions; + object_state.num_velocities = num_velocities; + object_state.object_name = object_name; + object_state.position = std::vector(num_positions); + object_state.velocity = std::vector(num_velocities); + this->DeclareAbstractOutputPort(object_name + "_state", object_state, &RosToLcmObjectState::ConvertToLCM); - } -void RosToLcmObjectState::ConvertToLCM(const drake::systems::Context& context, - dairlib::lcmt_object_state* object_state) const { - +void RosToLcmObjectState::ConvertToLCM( + const drake::systems::Context& context, + dairlib::lcmt_object_state* object_state) const { const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); const auto& msg = input->get_value(); - if (msg.data.empty()){ - for (size_t i = 0; i < object_state->num_positions; i++){ + if (msg.data.empty()) { + for (size_t i = 0; i < object_state->num_positions; i++) { object_state->position[i] = nan(""); } - } - else{ - for (size_t i = 0; i < object_state->num_positions; i++){ + } else { + for (size_t i = 0; i < object_state->num_positions; i++) { object_state->position[i] = msg.data[i]; } } diff --git a/systems/ros/franka_ros_lcm_conversions.h b/systems/ros/franka_ros_lcm_conversions.h index 9beec239ab..9d3d4644cf 100644 --- a/systems/ros/franka_ros_lcm_conversions.h +++ b/systems/ros/franka_ros_lcm_conversions.h @@ -4,6 +4,12 @@ #include #include +#include "dairlib/lcmt_estimated_object_state.hpp" +#include "dairlib/lcmt_franka_state.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "franka_msgs/FrankaState.h" +#include "sensor_msgs/JointState.h" +#include "std_msgs/Float64MultiArray.h" #include "systems/framework/output_vector.h" #include "systems/framework/timestamped_vector.h" @@ -11,14 +17,6 @@ #include "drake/systems/framework/leaf_system.h" #include "drake/systems/lcm/lcm_interface_system.h" - -#include "std_msgs/Float64MultiArray.h" -#include "sensor_msgs/JointState.h" -#include "franka_msgs/FrankaState.h" -#include "dairlib/lcmt_robot_output.hpp" -#include "dairlib/lcmt_franka_state.hpp" -#include "dairlib/lcmt_estimated_object_state.hpp" - namespace dairlib { namespace systems { @@ -41,11 +39,15 @@ class LcmToRosTimestampedVector : public drake::systems::LeafSystem { // coded for the C3 Franka experiments. class RosToLcmRobotState : public drake::systems::LeafSystem { public: - static std::unique_ptr Make(int num_positions, int num_velocities, int num_efforts) { - return std::make_unique(num_positions, num_velocities, num_efforts); + static std::unique_ptr Make(int num_positions, + int num_velocities, + int num_efforts) { + return std::make_unique(num_positions, num_velocities, + num_efforts); } - explicit RosToLcmRobotState(int num_positions, int num_velocities, int num_efforts); + explicit RosToLcmRobotState(int num_positions, int num_velocities, + int num_efforts); private: void ConvertToLCM(const drake::systems::Context& context, @@ -55,77 +57,33 @@ class RosToLcmRobotState : public drake::systems::LeafSystem { int num_efforts_; const int num_franka_joints_{7}; - const std::vector default_ball_position_ {1, 0, 0, 0, 0.5, 0, 0.0315-0.0301}; - - const std::vector position_names_ { - "panda_joint1", - "panda_joint2", - "panda_joint3", - "panda_joint4", - "panda_joint5", - "panda_joint6", - "panda_joint7", - "base_qw", - "base_qx", - "base_qy", - "base_qz", - "base_x", - "base_y", - "base_z"}; - - const std::vector velocity_names_ { - "panda_joint1dot", - "panda_joint2dot", - "panda_joint3dot", - "panda_joint4dot", - "panda_joint5dot", - "panda_joint6dot", - "panda_joint7dot", - "base_wx", - "base_wy", - "base_wz", - "base_vx", - "base_vy", - "base_vz"}; + const std::vector default_ball_position_{ + 1, 0, 0, 0, 0.5, 0, 0.0315 - 0.0301}; + + const std::vector position_names_{ + "panda_joint1", "panda_joint2", "panda_joint3", "panda_joint4", + "panda_joint5", "panda_joint6", "panda_joint7", "base_qw", + "base_qx", "base_qy", "base_qz", "base_x", + "base_y", "base_z"}; - const std::vector effort_names_ { - "panda_motor1", - "panda_motor2", - "panda_motor3", - "panda_motor4", - "panda_motor5", - "panda_motor6", - "panda_motor7",}; + const std::vector velocity_names_{ + "panda_joint1dot", "panda_joint2dot", "panda_joint3dot", + "panda_joint4dot", "panda_joint5dot", "panda_joint6dot", + "panda_joint7dot", "base_wx", "base_wy", + "base_wz", "base_vx", "base_vy", + "base_vz"}; + const std::vector effort_names_{ + "panda_motor1", "panda_motor2", "panda_motor3", "panda_motor4", + "panda_motor5", "panda_motor6", "panda_motor7", + }; }; -//class ROSToC3LCM : public drake::systems::LeafSystem { -// public: -// static std::unique_ptr Make(int num_positions, int num_velocities, -// int lambda_size, int misc_size) { -// -// return std::make_unique(num_positions, num_velocities, -// lambda_size, misc_size); -// } -// -// explicit ROSToC3LCM(int num_positions, int num_velocities, -// int lambda_size, int misc_size); -// -// private: -// void ConvertToLCM(const drake::systems::Context& context, -// dairlib::lcmt_c3* output) const; -// int num_positions_; -// int num_velocities_; -// int lambda_size_; -// int misc_size_; -// int data_size_; -//}; - -/// More specific translator from Franka state to LCM. Similar to lcmt_cassie_out.lcm +/// More specific translator from Franka state to LCM. Similar to +/// lcmt_cassie_out.lcm class RosToLcmFrankaState : public drake::systems::LeafSystem { public: static std::unique_ptr Make() { - return std::make_unique(); } @@ -138,25 +96,18 @@ class RosToLcmFrankaState : public drake::systems::LeafSystem { class RosToLcmObjectState : public drake::systems::LeafSystem { public: - static std::unique_ptr Make() { - - return std::make_unique(); + static std::unique_ptr Make( + const std::string& object_name, int num_positions, int num_velocities) { + return std::make_unique(object_name, num_positions, + num_velocities); } - explicit RosToLcmObjectState(); + explicit RosToLcmObjectState(const std::string& object_name, + int num_positions, int num_velocities); private: void ConvertToLCM(const drake::systems::Context& context, dairlib::lcmt_object_state* franka_state) const; - - std::map enum_map_ = - {{-3.0, "Invalid"}, // invalid ball measurement obtained (i.e. incorrectly identified ball) - {-2.0, "Outlier"}, // outlier ball measurement obtained (i.e. too diff than other measurements) - {-1.0, "Ball not found"}, // no ball measurement obtained - { 0.0, "N/A"}, // See below - { 1.0, "Valid"}}; // valid ball measurement obtained - }; - } // namespace systems } // namespace dairlib From 264144f6f209d85a2a07a62faad5a51f20e64015 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 6 Nov 2023 16:39:45 -0500 Subject: [PATCH 507/758] fixing ros lcm bridge for new object type --- examples/franka/franka_ros_lcm_bridge.cc | 3 +- examples/franka/franka_sim.cc | 1 + systems/ros/franka_ros_lcm_conversions.cc | 41 ++++++++++++++++------- systems/ros/franka_ros_lcm_conversions.h | 14 +++++--- 4 files changed, 40 insertions(+), 19 deletions(-) diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index 806ce9e7a8..ac049c3c94 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -117,8 +117,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(RosSubscriberSystem::Make( ros_channel_params.tray_state_channel, &node_handle)); auto ros_to_lcm_object_state = builder.AddSystem( - RosToLcmObjectState::Make("tray", plant.num_positions(tray_index), - plant.num_velocities(tray_index))); + RosToLcmObjectState::Make(plant, tray_index, "tray")); // change this to output correctly (i.e. when ros subscriber gets new message) auto tray_state_pub = diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index a28638a6a5..66ba14e56f 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -58,6 +58,7 @@ DEFINE_string(lcm_channels, "Filepath containing lcm channels"); int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); // load parameters FrankaSimParams sim_params = drake::yaml::LoadYamlFile( "examples/franka/parameters/franka_sim_params.yaml"); diff --git a/systems/ros/franka_ros_lcm_conversions.cc b/systems/ros/franka_ros_lcm_conversions.cc index f153cdaa3e..e28ab8c194 100644 --- a/systems/ros/franka_ros_lcm_conversions.cc +++ b/systems/ros/franka_ros_lcm_conversions.cc @@ -1,6 +1,8 @@ #include "systems/ros/franka_ros_lcm_conversions.h" //#include "franka_msgs/FrankaState.h" #include + +#include "multibody/multibody_utils.h" namespace dairlib { namespace systems { @@ -270,19 +272,34 @@ void RosToLcmFrankaState::ConvertToLCM( } /***************************************************************************************/ -RosToLcmObjectState::RosToLcmObjectState(const std::string& object_name, - int num_positions, - int num_velocities) { - this->DeclareAbstractInputPort("ROS Float64MultiArray", - drake::Value()); +RosToLcmObjectState::RosToLcmObjectState( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance, + const std::string& object_name) { + auto positions_start_idx = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .position_start(); + auto velocities_start_idx = + plant.get_joint(plant.GetJointIndices(model_instance).front()) + .velocity_start(); + dairlib::lcmt_object_state object_state = dairlib::lcmt_object_state(); - object_state.num_positions = num_positions; - object_state.num_velocities = num_velocities; + object_state.num_positions = plant.num_positions(model_instance); + object_state.num_velocities = plant.num_velocities(model_instance); object_state.object_name = object_name; - object_state.position = std::vector(num_positions); - object_state.velocity = std::vector(num_velocities); + object_state.position = std::vector(object_state.num_positions); + object_state.position_names = multibody::ExtractOrderedNamesFromMap( + multibody::MakeNameToPositionsMap(plant, model_instance), + positions_start_idx); + object_state.velocity = std::vector(object_state.num_velocities); + object_state.velocity_names = multibody::ExtractOrderedNamesFromMap( + multibody::MakeNameToVelocitiesMap(plant, model_instance), + velocities_start_idx); + object_state.position[0] = 1; this->DeclareAbstractOutputPort(object_name + "_state", object_state, &RosToLcmObjectState::ConvertToLCM); + this->DeclareAbstractInputPort("ROS Float64MultiArray", + drake::Value()); } void RosToLcmObjectState::ConvertToLCM( @@ -292,9 +309,9 @@ void RosToLcmObjectState::ConvertToLCM( const auto& msg = input->get_value(); if (msg.data.empty()) { - for (size_t i = 0; i < object_state->num_positions; i++) { - object_state->position[i] = nan(""); - } +// for (size_t i = 0; i < object_state->num_positions; i++) { +// object_state->position[i] = nan(""); +// } } else { for (size_t i = 0; i < object_state->num_positions; i++) { object_state->position[i] = msg.data[i]; diff --git a/systems/ros/franka_ros_lcm_conversions.h b/systems/ros/franka_ros_lcm_conversions.h index 9d3d4644cf..95aace780b 100644 --- a/systems/ros/franka_ros_lcm_conversions.h +++ b/systems/ros/franka_ros_lcm_conversions.h @@ -97,13 +97,17 @@ class RosToLcmFrankaState : public drake::systems::LeafSystem { class RosToLcmObjectState : public drake::systems::LeafSystem { public: static std::unique_ptr Make( - const std::string& object_name, int num_positions, int num_velocities) { - return std::make_unique(object_name, num_positions, - num_velocities); + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance, + const std::string& object_name) { + return std::make_unique(plant, model_instance, + object_name); } - explicit RosToLcmObjectState(const std::string& object_name, - int num_positions, int num_velocities); + explicit RosToLcmObjectState( + const drake::multibody::MultibodyPlant& plant, + drake::multibody::ModelInstanceIndex model_instance, + const std::string& object_name); private: void ConvertToLCM(const drake::systems::Context& context, From 7fe302537ae31791aa0b11306745d280fbd15ab5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 Nov 2023 17:15:40 -0500 Subject: [PATCH 508/758] cleaning up c3 with orientation parameters --- examples/franka/franka_c3_controller.cc | 5 +++-- examples/franka/parameters/franka_c3_controller_params.yaml | 4 ++-- examples/franka/parameters/franka_c3_options_floating.yaml | 6 ++++++ .../franka/parameters/franka_osc_controller_params.yaml | 2 +- multibody/multipose_visualizer.cc | 3 ++- 5 files changed, 14 insertions(+), 6 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 7289e855f0..a2cb2a8535 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -169,12 +169,12 @@ int DoMain(int argc, char* argv[]) { auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_actor_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( @@ -190,6 +190,7 @@ int DoMain(int argc, char* argv[]) { auto c3_trajectory_generator = builder.AddSystem( plant_plate, &plate_context, c3_options); + c3_trajectory_generator->SetPublishEndEffectorOrientation(controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); controller->SetOsqpSolverOptions(solver_options); builder.Connect(franka_state_receiver->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index bfb3182d04..a84ae8a867 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,6 +1,6 @@ c3_options_file: examples/franka/parameters/franka_c3_options_translation.yaml -#c3_options_file: examples/franka/franka_c3_options_floating.yaml +#c3_options_file: examples/franka/parameters/franka_c3_options_floating.yaml osqp_settings_file: examples/Cassie/osc_run/osc_running_qp_settings.yaml franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf @@ -15,6 +15,6 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 10 +target_frequency: 5 diff --git a/examples/franka/parameters/franka_c3_options_floating.yaml b/examples/franka/parameters/franka_c3_options_floating.yaml index 268dd4ed8f..bfd93fc90e 100644 --- a/examples/franka/parameters/franka_c3_options_floating.yaml +++ b/examples/franka/parameters/franka_c3_options_floating.yaml @@ -25,6 +25,12 @@ u_size: 49 # 1, 1, 1, 1, 1, 1, 1, 1, 1] q_vector: [200, 200, 500, 0, 0, 0, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] +# Penalty on all decision variables +g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +# Penalty on all decision variables +u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2c0bb0340c..7df7e53fac 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index 998c22158d..fd7c9575a8 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -44,11 +44,12 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, drake::multibody::AddMultibodyPlantSceneGraph(&builder, 0.0); auto lcm = builder.AddSystem(); - Parser parser(plant_, scene_graph); + Parser parser(plant_, scene_graph, "pose_trace"); parser.SetAutoRenaming(true); // Add num_poses copies of the plant, giving each a unique name for (int i = 0; i < num_poses_; i++) { auto index = parser.AddModels(model_file)[0]; +// plant_->RenameModelInstance(index, plant_->get_name() + "_" + std::to_string(i)); model_indices_.push_back(index); if (!weld_frame_to_world.empty()) { plant_->WeldFrames( From 54660103fe93bb2559a3208c5b52b57f1aa5142a Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 7 Nov 2023 16:14:16 -0500 Subject: [PATCH 509/758] enabling loading of c3 debug logs --- .../pydairlib/analysis/franka_plot_config.py | 1 + .../analysis/franka_plotting_utils.py | 1 + .../pydairlib/analysis/log_plotter_franka.py | 58 +++++++++---------- .../pydairlib/analysis/mbp_plotting_utils.py | 45 +++++++++++++- .../plot_configs/franka_translation_plot.yaml | 3 +- bindings/pydairlib/lcm/process_lcm_log.py | 2 - 6 files changed, 75 insertions(+), 35 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py index 9e17be98ab..670beeaf7e 100644 --- a/bindings/pydairlib/analysis/franka_plot_config.py +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -13,6 +13,7 @@ def __init__(self, filename): self.channel_x = data['channel_x'] self.channel_u = data['channel_u'] self.channel_osc = data['channel_osc'] + self.channel_c3 = data['channel_c3'] self.plot_style = data['plot_style'] self.start_time = data['start_time'] diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index fcee19cceb..d346251004 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -22,6 +22,7 @@ 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, + 'C3_DEBUG': dairlib.lcmt_c3_output, 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, 'RADIO': dairlib.lcmt_radio_out, 'CONTACT_RESULTS': drake.lcmt_contact_results_for_viz} diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 510f85dbd0..2a2c2c1190 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -12,13 +12,16 @@ from pydrake.all import JointIndex, JointActuatorIndex + def main(): - config_file = 'bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml' + config_file = ('bindings/pydairlib/analysis/plot_configs' + '/franka_translation_plot.yaml') plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc + channel_c3 = plot_config.channel_c3 if plot_config.plot_style == "paper": plot_styler.PlotStyler.set_default_styling() @@ -26,7 +29,8 @@ def main(): plot_styler.PlotStyler.set_compact_styling() ''' Get the plant ''' - franka_plant, franka_context, tray_plant, tray_context = franka_plots.make_plant_and_context() + franka_plant, franka_context, tray_plant, tray_context = ( + franka_plots.make_plant_and_context()) pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(franka_plant) pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors( @@ -45,6 +49,11 @@ def main(): franka_plant, channel_x, channel_u, channel_osc) # processing callback arguments + # processing callback arguments + c3_output = get_log_data(log, default_channels, plot_config.start_time, + plot_config.duration, mbp_plots.load_c3_debug, + channel_c3) + print('Finished processing log - making plots') # Define x time slice t_x_slice = slice(robot_output['t_x'].size) @@ -52,29 +61,15 @@ def main(): print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) - franka_joint_limits_lower = np.zeros(franka_plant.num_positions()) - franka_joint_limits_upper = np.zeros(franka_plant.num_positions()) - franka_joint_velocity_limits_lower = np.zeros(franka_plant.num_positions()) - franka_joint_velocity_limits_upper = np.zeros(franka_plant.num_positions()) - franka_joint_actuator_limits_lower = np.zeros(franka_plant.num_positions()) - franka_joint_actuator_limits_upper = np.zeros(franka_plant.num_positions()) - for i in range(franka_plant.num_positions()): - franka_joint_limits_upper[i] = franka_plant.get_joint(JointIndex(i)).position_upper_limits()[0] - franka_joint_limits_lower[i] = franka_plant.get_joint(JointIndex(i)).position_lower_limits()[0] - franka_joint_velocity_limits_lower[i] = franka_plant.get_joint(JointIndex(i)).velocity_upper_limits()[0] - franka_joint_velocity_limits_upper[i] = franka_plant.get_joint(JointIndex(i)).velocity_lower_limits()[0] - franka_joint_actuator_limits_lower[i] = -franka_plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() - franka_joint_actuator_limits_upper[i] = franka_plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() - franka_joint_limit_range = [np.min(franka_joint_limits_lower), np.max(franka_joint_limits_upper)] - franka_joint_velocity_limit_range = [np.min(franka_joint_velocity_limits_lower), np.max(franka_joint_velocity_limits_upper)] - franka_joint_actuator_limit_range = [np.min(franka_joint_actuator_limits_lower), np.max(franka_joint_actuator_limits_upper)] + (franka_joint_position_limit_range, franka_joint_velocity_limit_range, + franka_joint_actuator_limit_range) = mbp_plots.generate_joint_limits( + franka_plant) # Plot joint positions if plot_config.plot_joint_positions: - plot = mbp_plots.plot_joint_positions(robot_output, pos_names, - 0, t_x_slice) - plt.ylim(franka_joint_limit_range) - + plot = mbp_plots.plot_joint_positions(robot_output, pos_names, 0, + t_x_slice) + plt.ylim(franka_joint_position_limit_range) # Plot specific positions if plot_config.pos_names: plot = mbp_plots.plot_positions_by_name(robot_output, @@ -83,13 +78,11 @@ def main(): # Plot all joint velocities if plot_config.plot_joint_velocities: - plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, - 0, + plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, t_x_slice) plt.ylim(franka_joint_velocity_limit_range) - -# Plot specific velocities + # Plot specific velocities if plot_config.vel_names: plot = mbp_plots.plot_velocities_by_name(robot_output, plot_config.vel_names, @@ -106,11 +99,14 @@ def main(): {'paddle': np.zeros(3)}, {'paddle': [0, 1, 2]}) # q = np.load( - # '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_q.npy') + # '/home/yangwill/Documents/research/projects/franka/leon_data + # /test_2023-05-19-14-10-43_q.npy') # v = np.load( - # '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_v.npy') + # '/home/yangwill/Documents/research/projects/franka/leon_data + # /test_2023-05-19-14-10-43_v.npy') # t = np.load( - # '/home/yangwill/Documents/research/projects/franka/leon_data/test_2023-05-19-14-10-43_t.npy') + # '/home/yangwill/Documents/research/projects/franka/leon_data + # /test_2023-05-19-14-10-43_t.npy') # pos = mbp_plots.make_point_positions_from_q(q, # franka_plant, franka_context, # franka_plant.GetBodyByName( @@ -118,7 +114,8 @@ def main(): # np.zeros(3)) # vel = mbp_plots.make_point_velocities_from_qv(q, # v, - # franka_plant, franka_context, + # franka_plant, + # franka_context, # franka_plant.GetBodyByName( # 'paddle').body_frame(), # np.zeros(3)) @@ -155,7 +152,6 @@ def main(): if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) - if plot_config.plot_qp_solutions: plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 1df80d502b..bbf0649832 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -2,7 +2,7 @@ import matplotlib.pyplot as plt from matplotlib.patches import Patch -from pydrake.all import JacobianWrtVariable +from pydrake.all import JacobianWrtVariable, JointActuatorIndex, JointIndex from bindings.pydairlib.common import plot_styler, plotting_utils from bindings.pydairlib.analysis.osc_debug import lcmt_osc_tracking_data_t, \ @@ -276,6 +276,26 @@ def process_contact_channel(data): 'lambda_c': contact_forces, 'p_lambda_c': contact_info_locs} +def process_c3_channel(data): + t = [] + states = [] # Allocate space for all 4 point contacts + contact_forces = [] + inputs = [] + for msg in data: + t.append(msg.timestamp / 1e6) + states.append(msg.c3_solution.x_sol) + contact_forces.append(msg.c3_solution.lambda_sol) + inputs.append(msg.u_sol.lambda_sol) + + t_contact_info = np.array(states) + contact_forces = np.array(contact_forces) + contact_info_locs = np.array(inputs) + + return {'t_c3': t, + 'x_c3': states, + 'lambda_c3': contact_forces, + 'u_c3': inputs,} + def permute_osc_joint_ordering(osc_data, robot_output_msg, plant): _, vperm, uperm = make_joint_order_permutations(robot_output_msg, plant) @@ -299,6 +319,9 @@ def load_force_channels(data, contact_force_channel): contact_info = process_contact_channel(data[contact_force_channel]) return contact_info +def load_c3_debug(data, c3_debug_channel): + c3_debug = process_c3_channel(data[c3_debug_channel]) + return c3_debug def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, @@ -570,6 +593,7 @@ def plot_osc_tracking_data(osc_debug, traj, dim, deriv, time_slice): data['projected_error_ydot'] = tracking_data.error_ydot[:, dim] elif deriv == 'accel': data['yddot_des'] = tracking_data.yddot_des[:, dim] + data['yddot_actual'] = 1000 * np.diff(tracking_data.ydot[:, dim], prepend=[0]) data['yddot_command'] = tracking_data.yddot_command[:, dim] data['yddot_command_sol'] = tracking_data.yddot_command_sol[:, dim] @@ -792,3 +816,22 @@ def plot_active_tracking_datas(osc_debug, time_slice, fsm_time, fsm_signal, ax.set_ylabel('Tracking Objective') return ps + +def generate_joint_limits(plant): + joint_position_limits_lower = np.zeros(plant.num_positions()) + joint_position_limits_upper = np.zeros(plant.num_positions()) + joint_velocity_limits_lower = np.zeros(plant.num_positions()) + joint_velocity_limits_upper = np.zeros(plant.num_positions()) + joint_actuator_limits_lower = np.zeros(plant.num_positions()) + joint_actuator_limits_upper = np.zeros(plant.num_positions()) + for i in range(plant.num_positions()): + joint_position_limits_lower[i] = plant.get_joint(JointIndex(i)).position_upper_limits()[0] + joint_position_limits_upper[i] = plant.get_joint(JointIndex(i)).position_lower_limits()[0] + joint_velocity_limits_lower[i] = plant.get_joint(JointIndex(i)).velocity_upper_limits()[0] + joint_velocity_limits_upper[i] = plant.get_joint(JointIndex(i)).velocity_lower_limits()[0] + joint_actuator_limits_lower[i] = -plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() + joint_actuator_limits_upper[i] = plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() + franka_joint_position_limit_range = [np.min(joint_position_limits_lower), np.max(joint_position_limits_upper)] + franka_joint_velocity_limit_range = [np.min(joint_velocity_limits_lower), np.max(joint_velocity_limits_upper)] + franka_joint_actuator_limit_range = [np.min(joint_actuator_limits_lower), np.max(joint_actuator_limits_upper)] + return franka_joint_position_limit_range, franka_joint_velocity_limit_range, franka_joint_actuator_limit_range diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index ccd5c7bc80..1a89080ae8 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -2,6 +2,7 @@ channel_x: "FRANKA_STATE" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" +channel_c3: "C3_DEBUG" plot_style: 'compact' # compact, paper, default start_time: 0 @@ -32,6 +33,6 @@ plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0, 1, 2], 'derivs': ['vel']} + end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index 65e1fe28fd..c09ca6f8c6 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -44,10 +44,8 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca event = lcm_log.read_next_event() return data_processing_callback(data_to_process, *args, *kwargs) - def get_log_summary(lcm_log): channel_names_and_msg_counts = {} - import pdb; pdb.set_trace() for event in lcm_log: if event.channel not in channel_names_and_msg_counts: channel_names_and_msg_counts[event.channel] = 1 From 762c3d4ba4951361a28e01442c9994c282f3795c Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Nov 2023 17:28:40 -0500 Subject: [PATCH 510/758] removed some usings in .h files, fixed files downstream accordingly --- examples/Cassie/systems/cassie_encoder.cc | 11 ++++---- examples/Cassie/systems/cassie_encoder.h | 2 +- .../systems/sim_cassie_sensor_aggregator.cc | 1 + .../kuka_iiwa_arm/iiwa_controller_demo.cc | 3 +++ .../endeffector_position_controller.cc | 13 ++++++++++ .../endeffector_position_controller.h | 25 ++++++------------- .../endeffector_velocity_controller.cc | 8 ++++++ .../endeffector_velocity_controller.h | 18 +++++-------- .../controllers/safe_velocity_controller.cc | 4 +++ .../controllers/safe_velocity_controller.h | 12 +++------ systems/framework/geared_motor.cc | 1 + systems/framework/geared_motor.h | 2 +- systems/framework/timestamped_vector.h | 23 ++++++++--------- 13 files changed, 65 insertions(+), 58 deletions(-) diff --git a/examples/Cassie/systems/cassie_encoder.cc b/examples/Cassie/systems/cassie_encoder.cc index eee194243e..2cec041487 100644 --- a/examples/Cassie/systems/cassie_encoder.cc +++ b/examples/Cassie/systems/cassie_encoder.cc @@ -7,6 +7,7 @@ namespace dairlib { using Eigen::VectorXd; +using drake::systems::BasicVector; CassieEncoder::CassieEncoder( const drake::multibody::MultibodyPlant& plant) @@ -37,17 +38,17 @@ CassieEncoder::CassieEncoder( } this->DeclareVectorInputPort( "robot_state", - systems::BasicVector(num_positions_ + num_velocities_)); + BasicVector(num_positions_ + num_velocities_)); this->DeclareVectorOutputPort( "filtered_state", - systems::BasicVector(num_positions_ + num_velocities_), + BasicVector(num_positions_ + num_velocities_), &CassieEncoder::UpdateFilter); } void CassieEncoder::UpdateFilter(const drake::systems::Context& context, - systems::BasicVector* output) const { - const systems::BasicVector& x = - *this->template EvalVectorInput(context, 0); + BasicVector* output) const { + const BasicVector& x = + *this->template EvalVectorInput(context, 0); VectorXd q = x.value().head(num_positions_); VectorXd v = x.value().tail(num_velocities_); diff --git a/examples/Cassie/systems/cassie_encoder.h b/examples/Cassie/systems/cassie_encoder.h index a2e5a011ca..66749179e9 100644 --- a/examples/Cassie/systems/cassie_encoder.h +++ b/examples/Cassie/systems/cassie_encoder.h @@ -70,7 +70,7 @@ class CassieEncoder final : public drake::systems::LeafSystem { protected: void UpdateFilter(const drake::systems::Context& context, - systems::BasicVector* output) const; + drake::systems::BasicVector* output) const; private: struct DriveFilter { diff --git a/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc b/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc index 84de52e132..9cb578a982 100644 --- a/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc +++ b/examples/Cassie/systems/sim_cassie_sensor_aggregator.cc @@ -7,6 +7,7 @@ namespace systems { using std::string; using drake::systems::Context; +using drake::systems::BasicVector; using drake::AbstractValue; using dairlib::systems::TimestampedVector; using Eigen::VectorXd; diff --git a/examples/kuka_iiwa_arm/iiwa_controller_demo.cc b/examples/kuka_iiwa_arm/iiwa_controller_demo.cc index d9253b016a..ebf8717b0e 100644 --- a/examples/kuka_iiwa_arm/iiwa_controller_demo.cc +++ b/examples/kuka_iiwa_arm/iiwa_controller_demo.cc @@ -26,6 +26,9 @@ #include "systems/controllers/endeffector_velocity_controller.h" #include "systems/controllers/endeffector_position_controller.h" +using Eigen::VectorXd; +using drake::multibody::MultibodyPlant; + namespace dairlib { // This function creates a controller for a Kuka LBR Iiwa arm by connecting an diff --git a/systems/controllers/endeffector_position_controller.cc b/systems/controllers/endeffector_position_controller.cc index 9b15a51528..1ec1c8f5da 100644 --- a/systems/controllers/endeffector_position_controller.cc +++ b/systems/controllers/endeffector_position_controller.cc @@ -4,6 +4,19 @@ namespace dairlib{ namespace systems{ +using Eigen::VectorXd; +using Eigen::MatrixXd; +using Eigen::Quaternion; +using Eigen::Quaterniond; +using Eigen::AngleAxis; +using Eigen::AngleAxisd; +using drake::systems::LeafSystem; +using drake::systems::Context; +using drake::multibody::MultibodyPlant; +using drake::multibody::Frame; +using drake::systems::BasicVector; +using drake::VectorX; + EndEffectorPositionController::EndEffectorPositionController( const MultibodyPlant& plant, std::string ee_frame_name, Eigen::Vector3d ee_contact_frame, double k_p, double k_omega) diff --git a/systems/controllers/endeffector_position_controller.h b/systems/controllers/endeffector_position_controller.h index b17297567b..2fa4855d16 100644 --- a/systems/controllers/endeffector_position_controller.h +++ b/systems/controllers/endeffector_position_controller.h @@ -10,17 +10,6 @@ #include #include -using Eigen::VectorXd; -using Eigen::MatrixXd; -using Eigen::Quaternion; -using Eigen::Quaterniond; -using Eigen::AngleAxis; -using Eigen::AngleAxisd; -using drake::systems::LeafSystem; -using drake::systems::Context; -using drake::multibody::MultibodyPlant; -using drake::multibody::Frame; - namespace dairlib{ namespace systems{ @@ -30,10 +19,10 @@ namespace systems{ // outputs appropriate velocity (twist) as 6-vector: first three indices // are desired angular velocity, next three are desired linear velocity. -class EndEffectorPositionController : public LeafSystem { + class EndEffectorPositionController : public drake::systems::LeafSystem { public: // Constructor - EndEffectorPositionController(const MultibodyPlant& plant, + EndEffectorPositionController(const drake::multibody::MultibodyPlant& plant, std::string ee_frame_name, Eigen::Vector3d ee_contact_frame, double k_p, double k_omega); @@ -55,13 +44,13 @@ class EndEffectorPositionController : public LeafSystem { private: // Callback method called when declaring output port of the system. // Twist combines linear and angular velocities. - void CalcOutputTwist(const Context &context, - BasicVector* output) const; + void CalcOutputTwist(const drake::systems::Context &context, + drake::systems::BasicVector* output) const; - const MultibodyPlant& plant_; - const Frame& plant_world_frame_; + const drake::multibody::MultibodyPlant& plant_; + const drake::multibody::Frame& plant_world_frame_; Eigen::Vector3d ee_contact_frame_; - const Frame& ee_joint_frame_; + const drake::multibody::Frame& ee_joint_frame_; double k_p_; double k_omega_; int joint_position_measured_port_; diff --git a/systems/controllers/endeffector_velocity_controller.cc b/systems/controllers/endeffector_velocity_controller.cc index 188c55d867..3a3d9b81ba 100644 --- a/systems/controllers/endeffector_velocity_controller.cc +++ b/systems/controllers/endeffector_velocity_controller.cc @@ -1,6 +1,14 @@ #include "systems/controllers/endeffector_velocity_controller.h" #include +using Eigen::VectorXd; +using Eigen::MatrixXd; +using drake::systems::LeafSystem; +using drake::systems::Context; +using drake::systems::BasicVector; +using drake::multibody::MultibodyPlant; +using drake::multibody::Frame; + namespace dairlib{ namespace systems{ diff --git a/systems/controllers/endeffector_velocity_controller.h b/systems/controllers/endeffector_velocity_controller.h index 7a68cad445..7b49f30a7a 100644 --- a/systems/controllers/endeffector_velocity_controller.h +++ b/systems/controllers/endeffector_velocity_controller.h @@ -8,12 +8,6 @@ #include -using Eigen::VectorXd; -using Eigen::MatrixXd; -using drake::systems::LeafSystem; -using drake::systems::Context; -using drake::multibody::MultibodyPlant; -using drake::multibody::Frame; namespace dairlib{ namespace systems{ @@ -23,10 +17,10 @@ namespace systems{ // In this case, KukaIiwaVelocityController will take in desired velocities, // q, q_dot, and output an appropriate torque // \Tau = jacobian.transpose x K x desired_accelerations -class EndEffectorVelocityController : public LeafSystem { + class EndEffectorVelocityController : public drake::systems::LeafSystem { public: // Constructor - EndEffectorVelocityController(const MultibodyPlant& plant, + EndEffectorVelocityController(const drake::multibody::MultibodyPlant& plant, std::string ee_frame_name, Eigen::Vector3d ee_contact_frame, double k_d, double k_r); @@ -49,12 +43,12 @@ class EndEffectorVelocityController : public LeafSystem { // The callback called when declaring the output port of the system. // The 'output' vector is set in place and then passed out. // Think a simulink system. - void CalcOutputTorques(const Context& context, - BasicVector* output) const; + void CalcOutputTorques(const drake::systems::Context& context, + drake::systems::BasicVector* output) const; - const MultibodyPlant& plant_; + const drake::multibody::MultibodyPlant& plant_; int num_joints_; - const Frame& ee_joint_frame_; + const drake::multibody::Frame& ee_joint_frame_; Eigen::Vector3d ee_contact_frame_; int joint_position_measured_port_; int joint_velocity_measured_port_; diff --git a/systems/controllers/safe_velocity_controller.cc b/systems/controllers/safe_velocity_controller.cc index 3c4ab58b46..6e2d1558b9 100644 --- a/systems/controllers/safe_velocity_controller.cc +++ b/systems/controllers/safe_velocity_controller.cc @@ -1,5 +1,9 @@ #include "systems/controllers/safe_velocity_controller.h" +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::VectorX; + namespace dairlib{ namespace systems{ diff --git a/systems/controllers/safe_velocity_controller.h b/systems/controllers/safe_velocity_controller.h index 28d4d18853..b35e1d8093 100644 --- a/systems/controllers/safe_velocity_controller.h +++ b/systems/controllers/safe_velocity_controller.h @@ -7,14 +7,10 @@ #include "drake/systems/framework/event_status.h" #include "drake/systems/framework/discrete_values.h" -using Eigen::VectorXd; -using drake::systems::LeafSystem; -using drake::systems::Context; - namespace dairlib{ namespace systems{ -class SafeVelocityController : public LeafSystem { + class SafeVelocityController : public drake::systems::LeafSystem { public: SafeVelocityController(double max_velocity, int num_joints); @@ -29,11 +25,11 @@ class SafeVelocityController : public LeafSystem { } private: - void CalcOutputTorques(const Context &context, - BasicVector* output) const; + void CalcOutputTorques(const drake::systems::Context &context, + drake::systems::BasicVector* output) const; drake::systems::EventStatus CheckTerminate( - const Context &context, + const drake::systems::Context &context, drake::systems::DiscreteValues* next_state) const; diff --git a/systems/framework/geared_motor.cc b/systems/framework/geared_motor.cc index bfc0e3fcfe..ddba8e082e 100644 --- a/systems/framework/geared_motor.cc +++ b/systems/framework/geared_motor.cc @@ -8,6 +8,7 @@ namespace systems { using drake::multibody::JointActuator; using drake::multibody::MultibodyPlant; using drake::systems::kUseDefaultName; +using drake::systems::BasicVector; GearedMotor::GearedMotor(const MultibodyPlant& plant, const std::unordered_map& max_motor_speeds) diff --git a/systems/framework/geared_motor.h b/systems/framework/geared_motor.h index 5f765482c3..dc03255a7b 100644 --- a/systems/framework/geared_motor.h +++ b/systems/framework/geared_motor.h @@ -39,7 +39,7 @@ class GearedMotor final : public drake::systems::LeafSystem { protected: void CalcTorqueOutput(const drake::systems::Context& context, - systems::BasicVector* output) const; + drake::systems::BasicVector* output) const; private: bool is_abstract() const { return false; } diff --git a/systems/framework/timestamped_vector.h b/systems/framework/timestamped_vector.h index ef755ea909..471a9dde22 100644 --- a/systems/framework/timestamped_vector.h +++ b/systems/framework/timestamped_vector.h @@ -5,12 +5,9 @@ namespace dairlib { namespace systems { -using drake::VectorX; -using drake::systems::BasicVector; - -/// TimestampedVector wraps a BasicVector along with a timestamp field +/// TimestampedVector wraps a drake::systems::BasicVector along with a timestamp field /// The primary purpose of this is to pass-through a message (e.g. LCM) -/// timestamp Uses a length N+1 BasicVector to store a vector of length N and a +/// timestamp Uses a length N+1 drake::systems::BasicVector to store a vector of length N and a /// timestamp The timestamp is stored as the final element (Nth) template class TimestampedVector : public drake::systems::BasicVector { @@ -23,14 +20,14 @@ class TimestampedVector : public drake::systems::BasicVector { /// Initializes with the given @p size using the drake::dummy_value, which /// is NaN when T = double. explicit TimestampedVector(int data_size) - : BasicVector(data_size + 1), + : drake::systems::BasicVector(data_size + 1), timestep_index_(data_size), data_size_(data_size) {} /// Constructs a TimestampedVector with the specified @p data. - explicit TimestampedVector(const VectorX& data) + explicit TimestampedVector(const drake::VectorX& data) : TimestampedVector(data.size()) { - VectorX data_timestamped = VectorX(data.size() + 1); + drake::VectorX data_timestamped = drake::VectorX(data.size() + 1); data_timestamped.head(data.size()) = data; data_timestamped(data.size()) = 0; this->SetFromVector(data_timestamped); @@ -63,23 +60,23 @@ class TimestampedVector : public drake::systems::BasicVector { } /// Returns the vector without the timestamp - VectorX CopyVectorNoTimestamp() const { + drake::VectorX CopyVectorNoTimestamp() const { return this->CopyToVector().head(timestep_index_); } /// Returns a mutable vector of the data values (without timestamp) - Eigen::Map> get_mutable_data() { + Eigen::Map> get_mutable_data() { auto data = this->get_mutable_value().head(timestep_index_); - return Eigen::Map>(&data(0), data.size()); + return Eigen::Map>(&data(0), data.size()); } /// Returns the entire vector as a const Eigen::VectorBlock. - const VectorX get_data() const { + const drake::VectorX get_data() const { return this->get_value().head(timestep_index_); } // sets the data part of the vector (without timestamp) - void SetDataVector(const Eigen::Ref>& value) { + void SetDataVector(const Eigen::Ref>& value) { this->get_mutable_data() = value; } From 7bbcad9d13222ae82ead6f5c7550e9e3c17b83b6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Nov 2023 17:29:19 -0500 Subject: [PATCH 511/758] csupport c3 output messages to be float and fixing the conversions --- .../franka/systems/c3_trajectory_generator.cc | 26 +++++----- .../franka/systems/franka_kinematics_vector.h | 48 +++++++++---------- examples/franka/urdf/plate_end_effector.urdf | 2 +- examples/franka/urdf/tray.sdf | 2 +- solvers/c3_options.h | 15 +++--- solvers/c3_output.cc | 11 +++-- solvers/c3_output.h | 18 +++---- systems/controllers/c3_controller.cc | 28 ++++++----- systems/controllers/c3_controller.h | 4 +- systems/robot_lcm_systems.cc | 1 + 10 files changed, 76 insertions(+), 79 deletions(-) diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index d270b22dab..220308334b 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -17,6 +17,8 @@ using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteValues; using Eigen::VectorXd; +using Eigen::MatrixXd; +using Eigen::MatrixXf; using systems::TimestampedVector; namespace systems { @@ -63,14 +65,14 @@ void C3TrajectoryGenerator::OutputActorTrajectory( this->EvalInputValue(context, c3_solution_port_); MatrixXd knots = MatrixXd::Zero(6, N_); - knots.topRows(3) = c3_solution->x_sol_.topRows(3); - knots.bottomRows(3) = c3_solution->x_sol_.bottomRows(n_v_).topRows(3); + knots.topRows(3) = c3_solution->x_sol_.topRows(3).cast(); + knots.bottomRows(3) = c3_solution->x_sol_.bottomRows(n_v_).topRows(3).cast(); LcmTrajectory::Trajectory end_effector_traj; end_effector_traj.traj_name = "end_effector_traj"; end_effector_traj.datatypes = std::vector(knots.rows(), "double"); end_effector_traj.datapoints = knots; - end_effector_traj.time_vector = c3_solution->time_vector_; + end_effector_traj.time_vector = c3_solution->time_vector_.cast(); LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_traj"}, "end_effector_traj", "end_effector_traj", false); @@ -78,14 +80,14 @@ void C3TrajectoryGenerator::OutputActorTrajectory( LcmTrajectory::Trajectory end_effector_orientation_traj; // first 3 rows are rpy, last 3 rows are angular velocity MatrixXd orientation_samples = MatrixXd::Zero(6, N_); - orientation_samples.topRows(3) = c3_solution->x_sol_.topRows(6).bottomRows(3); + orientation_samples.topRows(3) = c3_solution->x_sol_.topRows(6).bottomRows(3).cast(); orientation_samples.bottomRows(3) = - c3_solution->x_sol_.bottomRows(n_v_).topRows(6).bottomRows(3); + c3_solution->x_sol_.bottomRows(n_v_).topRows(6).bottomRows(3).cast(); end_effector_orientation_traj.traj_name = "end_effector_orientation_target"; end_effector_orientation_traj.datatypes = std::vector(orientation_samples.rows(), "double"); end_effector_orientation_traj.datapoints = orientation_samples; - end_effector_orientation_traj.time_vector = c3_solution->time_vector_; + end_effector_orientation_traj.time_vector = c3_solution->time_vector_.cast(); lcm_traj.AddTrajectory(end_effector_orientation_traj.traj_name, end_effector_orientation_traj); } @@ -101,13 +103,13 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( this->EvalInputValue(context, c3_solution_port_); MatrixXd knots = MatrixXd::Zero(6, N_); - knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3); - knots.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3); + knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3).cast(); + knots.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); LcmTrajectory::Trajectory object_traj; object_traj.traj_name = "object_traj"; object_traj.datatypes = std::vector(knots.rows(), "double"); object_traj.datapoints = knots; - object_traj.time_vector = c3_solution->time_vector_; + object_traj.time_vector = c3_solution->time_vector_.cast(); LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, "object_traj", "object_traj", false); @@ -115,13 +117,13 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( LcmTrajectory::Trajectory object_orientation_traj; // first 3 rows are rpy, last 3 rows are angular velocity MatrixXd orientation_samples = MatrixXd::Zero(7, N_); - orientation_samples.topRows(4) = c3_solution->x_sol_.middleRows(3 + 3, 4); - orientation_samples.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + 3 + 3, 3); + orientation_samples.topRows(4) = c3_solution->x_sol_.middleRows(3 + 3, 4).cast(); + orientation_samples.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + 3 + 3, 3).cast(); object_orientation_traj.traj_name = "object_orientation_target"; object_orientation_traj.datatypes = std::vector(orientation_samples.rows(), "double"); object_orientation_traj.datapoints = orientation_samples; - object_orientation_traj.time_vector = c3_solution->time_vector_; + object_orientation_traj.time_vector = c3_solution->time_vector_.cast(); lcm_traj.AddTrajectory(object_orientation_traj.traj_name, object_orientation_traj); } diff --git a/examples/franka/systems/franka_kinematics_vector.h b/examples/franka/systems/franka_kinematics_vector.h index 91c8ad325e..4454c70cd2 100644 --- a/examples/franka/systems/franka_kinematics_vector.h +++ b/examples/franka/systems/franka_kinematics_vector.h @@ -8,10 +8,6 @@ namespace dairlib { namespace systems { -using drake::VectorX; -using std::string; -using std::vector; - /// FrankaKinematicsVector stores the robot output as a TimestampedVector /// * positions /// * velocities @@ -47,10 +43,10 @@ class FrankaKinematicsVector : public TimestampedVector { } /// Constructs a OutputVector with the specified positions and velocities. - explicit FrankaKinematicsVector(const VectorX& end_effector_positions, - const VectorX& object_positions, - const VectorX& end_effector_velocities, - const VectorX& object_velocities) + explicit FrankaKinematicsVector(const drake::VectorX& end_effector_positions, + const drake::VectorX& object_positions, + const drake::VectorX& end_effector_velocities, + const drake::VectorX& object_velocities) : FrankaKinematicsVector( end_effector_positions.size(), object_positions.size(), end_effector_velocities.size(), object_velocities.size()) { @@ -60,101 +56,101 @@ class FrankaKinematicsVector : public TimestampedVector { this->SetObjectVelocities(object_velocities); } - void SetEndEffectorPositions(VectorX positions) { + void SetEndEffectorPositions(drake::VectorX positions) { DRAKE_DEMAND(positions.size() == num_end_effector_positions_); this->get_mutable_data().segment(end_effector_positions_start_, num_end_effector_positions_) = positions; } - void SetObjectPositions(VectorX positions) { + void SetObjectPositions(drake::VectorX positions) { DRAKE_DEMAND(positions.size() == num_object_positions_); this->get_mutable_data().segment(object_positions_start_, num_object_positions_) = positions; } - void SetEndEffectorVelocities(VectorX velocities) { + void SetEndEffectorVelocities(drake::VectorX velocities) { DRAKE_DEMAND(velocities.size() == num_end_effector_velocities_); this->get_mutable_data().segment(end_effector_velocities_start_, num_end_effector_velocities_) = velocities; } - void SetObjectVelocities(VectorX velocities) { + void SetObjectVelocities(drake::VectorX velocities) { DRAKE_DEMAND(velocities.size() == num_object_velocities_); this->get_mutable_data().segment(object_velocities_start_, num_object_velocities_) = velocities; } - void SetState(VectorX state) { + void SetState(drake::VectorX state) { DRAKE_DEMAND(state.size() == this->data_size()); this->get_mutable_data().segment(end_effector_positions_start_, this->data_size()) = state; } /// Returns a const state vector - const VectorX GetState() const { + const drake::VectorX GetState() const { return this->get_data().segment(end_effector_positions_start_, this->data_size()); } /// Returns a const positions vector for the end effector - const VectorX GetEndEffectorPositions() const { + const drake::VectorX GetEndEffectorPositions() const { return this->get_data().segment(end_effector_positions_start_, num_end_effector_positions_); } /// Returns a const positions vector for the object - const VectorX GetObjectPositions() const { + const drake::VectorX GetObjectPositions() const { return this->get_data().segment(object_positions_start_, num_object_positions_); } /// Returns a const positions vector for the end effector - const VectorX GetEndEffectorVelocities() const { + const drake::VectorX GetEndEffectorVelocities() const { return this->get_data().segment(end_effector_velocities_start_, num_end_effector_velocities_); } /// Returns a const positions vector for the object - const VectorX GetObjectVelocities() const { + const drake::VectorX GetObjectVelocities() const { return this->get_data().segment(object_velocities_start_, num_object_velocities_); } /// Returns a const velocities vector - const VectorX GetVelocities() const { + const drake::VectorX GetVelocities() const { return this->get_data().segment( end_effector_velocities_start_, num_end_effector_velocities_ + num_object_velocities_); } /// Returns a const positions vector - const VectorX GetPositions() const { + const drake::VectorX GetPositions() const { return this->get_data().segment( end_effector_positions_start_, num_end_effector_positions_ + num_object_positions_); } /// Returns a mutable positions vector - Eigen::Map> GetMutablePositions() { + Eigen::Map> GetMutablePositions() { auto data = this->get_mutable_data().segment( end_effector_positions_start_, num_end_effector_positions_ + num_object_positions_); - return Eigen::Map>(&data(0), data.size()); + return Eigen::Map>(&data(0), data.size()); } /// Returns a mutable velocities vector - Eigen::Map> GetMutableVelocities() { + Eigen::Map> GetMutableVelocities() { auto data = this->get_mutable_data().segment( end_effector_velocities_start_, num_end_effector_velocities_ + num_object_velocities_); - return Eigen::Map>(&data(0), data.size()); + return Eigen::Map>(&data(0), data.size()); } /// Returns a mutable state vector - Eigen::Map> GetMutableState() { + Eigen::Map> GetMutableState() { auto data = this->get_mutable_data().segment(end_effector_positions_start_, this->data_size()); - return Eigen::Map>(&data(0), data.size()); + return Eigen::Map>(&data(0), data.size()); } protected: diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 7f9e79af3f..dcc3cee42b 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -14,7 +14,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index db71b92681..0dd2a418bb 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -38,7 +38,7 @@ 3.0e7 - 0.1 + 0.18 10 0.4 0.4 diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 82ece81042..27ffe706d0 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -2,9 +2,6 @@ #include "drake/common/yaml/yaml_read_archive.h" -using Eigen::MatrixXd; -using Eigen::VectorXd; - struct C3Options { // Hyperparameters int admm_iter = 2; // total number of ADMM iterations //2 @@ -36,12 +33,12 @@ struct C3Options { double solve_dt; int num_friction_directions; int num_contacts; - MatrixXd Q; - MatrixXd R; - MatrixXd G; - MatrixXd U; - VectorXd q_des; - VectorXd v_des; + Eigen::MatrixXd Q; + Eigen::MatrixXd R; + Eigen::MatrixXd G; + Eigen::MatrixXd U; + Eigen::VectorXd q_des; + Eigen::VectorXd v_des; template void Serialize(Archive* a) { diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc index fd5629d1b6..06ef761f50 100644 --- a/solvers/c3_output.cc +++ b/solvers/c3_output.cc @@ -1,6 +1,7 @@ #include "c3_output.h" using Eigen::VectorXd; +using Eigen::VectorXf; using std::vector; namespace dairlib { @@ -43,29 +44,29 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { for (int i = 0; i < c3_solution.num_state_variables; ++i) { // Temporary copy due to underlying data of Eigen::Matrix // being column major - VectorXd temp_row = c3_solution_.x_sol_.row(i); + VectorXf temp_row = c3_solution_.x_sol_.row(i); memcpy(c3_solution.x_sol[i].data(), temp_row.data(), sizeof(float) * knot_points); } for (int i = 0; i < c3_solution.num_contact_variables; ++i) { // Temporary copy due to underlying data of Eigen::Matrix // being column major - VectorXd temp_row = c3_solution_.lambda_sol_.row(i); + VectorXf temp_row = c3_solution_.lambda_sol_.row(i); memcpy(c3_solution.lambda_sol[i].data(), temp_row.data(), sizeof(float) * knot_points); } for (int i = 0; i < c3_solution.num_input_variables; ++i) { // Temporary copy due to underlying data of Eigen::Matrix // being column major - VectorXd temp_row = c3_solution_.u_sol_.row(i); + VectorXf temp_row = c3_solution_.u_sol_.row(i); memcpy(c3_solution.u_sol[i].data(), temp_row.data(), sizeof(float) * knot_points); } for (int i = 0; i < c3_intermediates.num_total_variables; ++i) { // Temporary copy due to underlying data of Eigen::Matrix // being column major - VectorXd temp_delta_row = c3_intermediates_.delta_.row(i); - VectorXd temp_w_row = c3_intermediates_.w_.row(i); + VectorXf temp_delta_row = c3_intermediates_.delta_.row(i); + VectorXf temp_w_row = c3_intermediates_.w_.row(i); memcpy(c3_intermediates.delta_sol[i].data(), temp_delta_row.data(), sizeof(float) * knot_points); memcpy(c3_intermediates.w_sol[i].data(), temp_w_row.data(), diff --git a/solvers/c3_output.h b/solvers/c3_output.h index 6e7ccf03fd..1325ef458e 100644 --- a/solvers/c3_output.h +++ b/solvers/c3_output.h @@ -9,8 +9,6 @@ #include "dairlib/lcmt_c3_output.hpp" -//#include "drake/systems/lcm/serializer.h" - namespace dairlib { /// Used for outputting c3 solutions and intermediate variables for debugging purposes @@ -19,14 +17,12 @@ class C3Output { public: struct C3Solution { C3Solution() = default; -// C3Solution(Eigen::VectorXd time_vector_, Eigen::MatrixXd x_sol_, -// Eigen::MatrixXd lambda_sol_, Eigen::MatrixXd u_sol_); // Shape is (variable_vector_size, knot_points) - Eigen::VectorXd time_vector_; - Eigen::MatrixXd x_sol_; - Eigen::MatrixXd lambda_sol_; - Eigen::MatrixXd u_sol_; + Eigen::VectorXf time_vector_; + Eigen::MatrixXf x_sol_; + Eigen::MatrixXf lambda_sol_; + Eigen::MatrixXf u_sol_; }; struct C3Intermediates { @@ -35,9 +31,9 @@ class C3Output { // Eigen::MatrixXd w_); // Shape is (variable_vector_size, knot_points) - Eigen::VectorXd time_vector_; - Eigen::MatrixXd delta_; - Eigen::MatrixXd w_; + Eigen::VectorXf time_vector_; + Eigen::MatrixXf delta_; + Eigen::MatrixXf w_; }; C3Output() = default; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 4e8dc26a98..3b3849432c 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -18,7 +18,11 @@ using drake::multibody::ModelInstanceIndex; using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteValues; +using Eigen::MatrixXd; using Eigen::VectorXd; +using Eigen::MatrixXf; +using Eigen::VectorXf; +using std::vector; using solvers::C3MIQP; using solvers::LCS; using solvers::LCSFactory; @@ -75,14 +79,14 @@ C3Controller::C3Controller( drake::Value{}) .get_index(); auto c3_solution = C3Output::C3Solution(); - c3_solution.x_sol_ = MatrixXd::Zero(n_q_ + n_v_, N_); - c3_solution.lambda_sol_ = MatrixXd::Zero(n_lambda_, N_); - c3_solution.u_sol_ = MatrixXd::Zero(n_u_, N_); - c3_solution.time_vector_ = VectorXd::Zero(N_); + c3_solution.x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); + c3_solution.lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); + c3_solution.u_sol_ = MatrixXf::Zero(n_u_, N_); + c3_solution.time_vector_ = VectorXf::Zero(N_); auto c3_intermediates = C3Output::C3Intermediates(); - c3_intermediates.w_ = MatrixXd::Zero(n_x_ + n_lambda_ + n_u_, N_); - c3_intermediates.delta_ = MatrixXd::Zero(n_x_ + n_lambda_ + n_u_, N_); - c3_intermediates.time_vector_ = VectorXd::Zero(N_); + c3_intermediates.w_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.delta_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.time_vector_ = VectorXf::Zero(N_); c3_solution_port_ = this->DeclareAbstractOutputPort("c3_solution", c3_solution, &C3Controller::OutputC3Solution) @@ -178,9 +182,9 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { c3_solution->time_vector_(i) = t + i * c3_options_.dt; - c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_); - c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_); - c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_); + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } } @@ -191,8 +195,8 @@ void C3Controller::OutputC3Intermediates( // auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; - c3_intermediates->w_.col(i) = w_[i]; - c3_intermediates->delta_.col(i) = delta_[i]; + c3_intermediates->w_.col(i) = w_[i].cast(); + c3_intermediates->delta_.col(i) = delta_[i].cast(); } } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index ea59bf413b..df99c587fb 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -102,8 +102,8 @@ class C3Controller : public drake::systems::LeafSystem { int n_u_; mutable std::unique_ptr c3_; - mutable std::vector delta_; - mutable std::vector w_; + mutable std::vector delta_; + mutable std::vector w_; // std::unique_ptr lcs_; drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 84de91dc39..dfc60ebf76 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -19,6 +19,7 @@ using drake::multibody::JointIndex; using drake::multibody::MultibodyPlant; using drake::systems::Context; using drake::systems::LeafSystem; +using drake::systems::BasicVector; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using Eigen::VectorXd; From 1beb9613d161f9b7471932dcc2ff8edf40946286 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 Nov 2023 17:29:35 -0500 Subject: [PATCH 512/758] small plotting changes for visualizing c3 output --- .../analysis/franka_plotting_utils.py | 1 + .../pydairlib/analysis/log_plotter_franka.py | 44 +++++-------------- .../pydairlib/analysis/mbp_plotting_utils.py | 35 +++++++++++---- .../plot_configs/franka_translation_plot.yaml | 2 +- 4 files changed, 39 insertions(+), 43 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index d346251004..6d3c5257e3 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -16,6 +16,7 @@ tray_model = "examples/franka/urdf/tray.sdf" franka_default_channels = \ {'FRANKA_STATE': dairlib.lcmt_robot_output, + 'FRANKA_STATE_SIMULATION': dairlib.lcmt_robot_output, # 'TRAY_STATE': dairlib.lcmt_robot_output, 'FRANKA_INPUT': dairlib.lcmt_robot_input, 'OSC_FRANKA': dairlib.lcmt_robot_input, diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 2a2c2c1190..3216a94c63 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -58,6 +58,7 @@ def main(): # Define x time slice t_x_slice = slice(robot_output['t_x'].size) t_osc_slice = slice(osc_debug['t_osc'].size) + t_c3_slice = slice(c3_output['t'].size) print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) @@ -76,6 +77,10 @@ def main(): plot_config.pos_names, t_x_slice, pos_map) + # import pdb; pdb.set_trace() + mbp_plots.plot_c3_inputs(c3_output, t_c3_slice) + # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) + # Plot all joint velocities if plot_config.plot_joint_velocities: plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, @@ -94,39 +99,10 @@ def main(): {'paddle': np.zeros(3)}, {'paddle': [0, 1, 2]}) - mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, - franka_context, ['paddle'], - {'paddle': np.zeros(3)}, - {'paddle': [0, 1, 2]}) - # q = np.load( - # '/home/yangwill/Documents/research/projects/franka/leon_data - # /test_2023-05-19-14-10-43_q.npy') - # v = np.load( - # '/home/yangwill/Documents/research/projects/franka/leon_data - # /test_2023-05-19-14-10-43_v.npy') - # t = np.load( - # '/home/yangwill/Documents/research/projects/franka/leon_data - # /test_2023-05-19-14-10-43_t.npy') - # pos = mbp_plots.make_point_positions_from_q(q, - # franka_plant, franka_context, - # franka_plant.GetBodyByName( - # 'paddle').body_frame(), - # np.zeros(3)) - # vel = mbp_plots.make_point_velocities_from_qv(q, - # v, - # franka_plant, - # franka_context, - # franka_plant.GetBodyByName( - # 'paddle').body_frame(), - # np.zeros(3)) - # ps = plot_styler.PlotStyler() - # ps.plot(t, pos, title='leon_experiment_positions') - # ps = plot_styler.PlotStyler() - # ps.plot(t, vel, title='leon_experiment_velocities') - # ps = plot_styler.PlotStyler() - - # ps.plot(t[1:], 1 / np.diff(t) * np.diff(vel, axis=0)[:, 1], - # title='leon_experiment_accelerations', ylim=[-10, 10]) + mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, + franka_context, ['paddle'], + {'paddle': np.zeros(3)}, + {'paddle': [0, 1, 2]}) ''' Plot Efforts ''' if plot_config.plot_measured_efforts: @@ -147,8 +123,8 @@ def main(): ''' Plot OSC ''' if plot_config.plot_tracking_costs: plot = mbp_plots.plot_tracking_costs(osc_debug, t_osc_slice) - plt.ylim([0, 1e3]) + if plot_config.plot_qp_costs: plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index bbf0649832..3786c2c49a 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -279,22 +279,27 @@ def process_contact_channel(data): def process_c3_channel(data): t = [] states = [] # Allocate space for all 4 point contacts + breaks = [] # Allocate space for all 4 point contacts contact_forces = [] inputs = [] for msg in data: - t.append(msg.timestamp / 1e6) + t.append(msg.utime / 1e6) states.append(msg.c3_solution.x_sol) + breaks.append(msg.c3_solution.time_vec) contact_forces.append(msg.c3_solution.lambda_sol) - inputs.append(msg.u_sol.lambda_sol) + inputs.append(msg.c3_solution.u_sol) - t_contact_info = np.array(states) + t = np.array(t) + states = np.array(states) + breaks = np.array(breaks) contact_forces = np.array(contact_forces) - contact_info_locs = np.array(inputs) + inputs = np.array(inputs) - return {'t_c3': t, - 'x_c3': states, - 'lambda_c3': contact_forces, - 'u_c3': inputs,} + return {'t': t, + 'time_vector': breaks, + 'x': states, + 'lambda': contact_forces, + 'u': inputs,} def permute_osc_joint_ordering(osc_data, robot_output_msg, plant): @@ -835,3 +840,17 @@ def generate_joint_limits(plant): franka_joint_velocity_limit_range = [np.min(joint_velocity_limits_lower), np.max(joint_velocity_limits_upper)] franka_joint_actuator_limit_range = [np.min(joint_actuator_limits_lower), np.max(joint_actuator_limits_upper)] return franka_joint_position_limit_range, franka_joint_velocity_limit_range, franka_joint_actuator_limit_range + +def plot_c3_inputs(c3_output, time_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + c3_output, + 't', + time_slice, + ['u'], + {'u': 0}, + {}, + {'xlabel': 'Timestamp', + 'ylabel': 'C3 Actor Inputs ', + 'title': 'C3 Actor Solution'}, ps) + return ps \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 1a89080ae8..fccfc11b7c 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -1,5 +1,5 @@ # LCM channels to read data from -channel_x: "FRANKA_STATE" +channel_x: "FRANKA_STATE_SIMULATION" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" channel_c3: "C3_DEBUG" From 5ee07cc0384e2793cbe7b95184383781c687da8b Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Nov 2023 13:51:22 -0500 Subject: [PATCH 513/758] fixing visualizer --- systems/trajectory_optimization/lcm_trajectory_systems.cc | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 615a192bf2..19fee85d89 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -217,8 +217,10 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( const auto lcm_translation_traj = lcm_traj_.GetTrajectory(translation_trajectory_name_); - auto translation_trajectory = PiecewisePolynomial::FirstOrderHold( - lcm_translation_traj.time_vector, lcm_translation_traj.datapoints); + auto translation_trajectory = PiecewisePolynomial::CubicHermite( + lcm_translation_traj.time_vector, + lcm_translation_traj.datapoints.topRows(3), + lcm_translation_traj.datapoints.bottomRows(3)); auto orientation_trajectory = PiecewiseQuaternionSlerp( {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); @@ -241,7 +243,6 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( VectorXd translation_breaks = VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], lcm_translation_traj.time_vector.tail(1)[0]); - for (int i = 0; i < object_poses.cols(); ++i) { object_poses.col(i) << orientation_trajectory.value(translation_breaks(i)), translation_trajectory.value(translation_breaks(i)); From 397690590e276a3a6758c10ac5eda1aeb3b28dda Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Nov 2023 13:51:50 -0500 Subject: [PATCH 514/758] cleaning up c3 solvers --- solvers/c3.cc | 10 +++++----- solvers/c3.h | 6 +++--- solvers/c3_miqp.h | 5 ++++- solvers/c3_options.h | 10 ++++++++++ 4 files changed, 22 insertions(+), 9 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index aa620570e4..a1aec5aeb7 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -259,26 +259,26 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, return *z_sol_; } -void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double Lowerbound, - double Upperbound, int constraint) { +void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double lower_bound, + double upper_bound, int constraint) { if (constraint == 1) { for (int i = 1; i < N_; i++) { user_constraints_.push_back( - prog_.AddLinearConstraint(A, Lowerbound, Upperbound, x_.at(i))); + prog_.AddLinearConstraint(A, lower_bound, upper_bound, x_.at(i))); } } if (constraint == 2) { for (int i = 0; i < N_; i++) { user_constraints_.push_back( - prog_.AddLinearConstraint(A, Lowerbound, Upperbound, u_.at(i))); + prog_.AddLinearConstraint(A, lower_bound, upper_bound, u_.at(i))); } } if (constraint == 3) { for (int i = 0; i < N_; i++) { user_constraints_.push_back( - prog_.AddLinearConstraint(A, Lowerbound, Upperbound, lambda_.at(i))); + prog_.AddLinearConstraint(A, lower_bound, upper_bound, lambda_.at(i))); } } } diff --git a/solvers/c3.h b/solvers/c3.h index 01014df7a3..079a58f46a 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -64,10 +64,10 @@ class C3 { std::vector& G, std::vector& WZ); /// allow users to add constraints (adds for all timesteps) - /// @param A, Lowerbound, Upperbound Lowerbound <= A^T x <= Upperbound + /// @param A, lower_bound, upper_bound lower_bound <= A^T x <= upper_bound /// @param constraint inputconstraint, stateconstraint, forceconstraint - void AddLinearConstraint(Eigen::RowVectorXd& A, double Lowerbound, - double Upperbound, int constraint); + void AddLinearConstraint(Eigen::RowVectorXd& A, double lower_bound, + double upper_bound, int constraint); /// allow user to remove all constraints void RemoveConstraints(); diff --git a/solvers/c3_miqp.h b/solvers/c3_miqp.h index 9707a105bb..ffd24261b9 100644 --- a/solvers/c3_miqp.h +++ b/solvers/c3_miqp.h @@ -11,7 +11,7 @@ namespace dairlib { namespace solvers { -class C3MIQP : public C3 { +class C3MIQP final : public C3 { public: /// Default constructor for time-varying LCS C3MIQP(const LCS& LCS, const std::vector& Q, @@ -27,6 +27,9 @@ class C3MIQP : public C3 { const std::vector& warm_start_u = {}, bool warm_start = false); + ~C3MIQP(){ + } + /// Virtual projection method Eigen::VectorXd SolveSingleProjection(const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 27ffe706d0..bc4afc7c51 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -40,6 +40,11 @@ struct C3Options { Eigen::VectorXd q_des; Eigen::VectorXd v_des; + std::vector neutral_position; + double x_scale; + double y_scale; + double z_scale; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(admm_iter)); @@ -69,6 +74,11 @@ struct C3Options { a->Visit(DRAKE_NVP(q_des_vector)); a->Visit(DRAKE_NVP(v_des_vector)); + a->Visit(DRAKE_NVP(neutral_position)); + a->Visit(DRAKE_NVP(x_scale)); + a->Visit(DRAKE_NVP(y_scale)); + a->Visit(DRAKE_NVP(z_scale)); + Eigen::VectorXd q = Eigen::Map( this->q_vector.data(), this->q_vector.size()); Eigen::VectorXd r = Eigen::Map( From 032ccae6ec04de371ba0fda22acde08ec4189a66 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Nov 2023 13:52:32 -0500 Subject: [PATCH 515/758] moving c3 target state out of c3 controller --- examples/franka/franka_c3_controller.cc | 65 ++++++++--- examples/franka/franka_sim.cc | 8 -- examples/franka/franka_visualizer.cc | 1 - .../franka_c3_options_floating.yaml | 2 +- .../franka_c3_options_translation.yaml | 7 +- .../franka/parameters/franka_sim_params.yaml | 5 +- examples/franka/systems/BUILD.bazel | 1 + .../franka/systems/end_effector_trajectory.h | 4 - .../franka/systems/plate_balancing_target.cc | 109 ++++++------------ .../franka/systems/plate_balancing_target.h | 62 ++++------ examples/franka/urdf/tray.sdf | 1 - systems/controllers/c3_controller.cc | 42 ++++--- systems/controllers/c3_controller.h | 8 +- 13 files changed, 148 insertions(+), 167 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index a2cb2a8535..1c0d8bcda8 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -1,5 +1,15 @@ #include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include #include #include "common/eigen_utils.h" @@ -8,6 +18,7 @@ #include "examples/franka/systems/c3_trajectory_generator.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "examples/franka/systems/franka_kinematics.h" +#include "examples/franka/systems/plate_balancing_target.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" @@ -18,15 +29,6 @@ #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" -#include "drake/common/find_resource.h" -#include "drake/common/yaml/yaml_io.h" -#include "drake/multibody/parsing/parser.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" - namespace dairlib { using dairlib::solvers::LCSFactory; @@ -77,8 +79,6 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder plant_builder; - /// - MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.package_map().Add("franka_urdfs", "examples/franka/urdf"); @@ -169,12 +169,14 @@ int DoMain(int argc, char* argv[]) { auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_actor_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kPeriodic}), + 1 / controller_params.target_frequency)); auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kPeriodic}), + 1 / controller_params.target_frequency)); auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( @@ -184,17 +186,44 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); + auto plate_balancing_target = + builder.AddSystem(); + VectorXd neutral_position = Eigen::Map( + c3_options.neutral_position.data(), c3_options.neutral_position.size()); + plate_balancing_target->SetRemoteControlParameters( + neutral_position, c3_options.x_scale, c3_options.y_scale, + c3_options.z_scale); + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto tray_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(plate_balancing_target->get_output_port_tray_target(), + target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(tray_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(3)); auto controller = builder.AddSystem( plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); auto c3_trajectory_generator = builder.AddSystem( plant_plate, &plate_context, c3_options); - c3_trajectory_generator->SetPublishEndEffectorOrientation(controller_params.include_end_effector_orientation); + c3_trajectory_generator->SetPublishEndEffectorOrientation( + controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); controller->SetOsqpSolverOptions(solver_options); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(target_state_mux->get_output_port(), + controller->get_input_port_target()); builder.Connect(tray_state_sub->get_output_port(), tray_state_receiver->get_input_port()); builder.Connect(tray_state_receiver->get_output_port(), @@ -202,7 +231,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_state()); builder.Connect(radio_sub->get_output_port(), - controller->get_input_port_radio()); + plate_balancing_target->get_input_port_radio()); builder.Connect(controller->get_output_port_c3_solution(), c3_trajectory_generator->get_input_port_c3_solution()); builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), @@ -230,9 +259,9 @@ int DoMain(int argc, char* argv[]) { &lcm, std::move(owned_diagram), franka_state_receiver, lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); - auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( - *controller, &loop.get_diagram_mutable_context()); - controller->get_input_port_target().FixValue(&controller_context, x_des); + // auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( + // *controller, &loop.get_diagram_mutable_context()); + // controller->get_input_port_target().FixValue(&controller_context, x_des); LcmHandleSubscriptionsUntil( &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); loop.Simulate(); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 66ba14e56f..77dca45dea 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -112,14 +112,6 @@ int DoMain(int argc, char* argv[]) { plant.Finalize(); - for (auto joint_actuator_index : - plant.GetJointActuatorIndices(franka_index)) { - std::cout << "Joint: " << joint_actuator_index << " reflected inertia: " - << plant.get_joint_actuator(joint_actuator_index) - .default_reflected_inertia() - << std::endl; - } - /* -------------------------------------------------------------------------------------------*/ drake::lcm::DrakeLcm drake_lcm; diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 6132fd017b..019eec3882 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -145,7 +145,6 @@ int do_main(int argc, char* argv[]) { auto to_pose = builder.AddSystem>(plant); - // DrakeVisualizer::AddToBuilder(&builder, scene_graph); drake::geometry::MeshcatVisualizerParams params; params.publish_period = 1.0 / 60.0; params.enable_alpha_slider = true; diff --git a/examples/franka/parameters/franka_c3_options_floating.yaml b/examples/franka/parameters/franka_c3_options_floating.yaml index bfd93fc90e..9cd4abed03 100644 --- a/examples/franka/parameters/franka_c3_options_floating.yaml +++ b/examples/franka/parameters/franka_c3_options_floating.yaml @@ -6,7 +6,7 @@ delta_option: 1 mu: 0.4 mu_plate: 1 -dt: 0.1 +dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 91e14b219e..3fcc9ce80c 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -35,4 +35,9 @@ u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, r_vector: [1, 1, 1] q_des_vector: [0.55, 0.00, 0.4, 1, 0, 0, 0, 0.55, 0.00, 0.42] -v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file +v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] + +neutral_position: [0.55, 0, 0.40] +x_scale: 0.1 +y_scale: 0.1 +z_scale: 0.1 \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 9125e92864..66238569b3 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 -visualize: true +visualize: false tool_attachment_frame: [0, 0, 0.107] @@ -18,5 +18,6 @@ realtime_rate: 1.0 q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] -q_init_plate: [1, 0, 0, 0, 0.56, 0.00, 0.550] +#q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] +q_init_plate: [1, 0, 0, 0, 0.56, 0.05, 0.430] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 365b39b326..396f28eee2 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -7,6 +7,7 @@ cc_library( ":end_effector_orientation", ":end_effector_trajectory", ":franka_kinematics", + ":plate_balancing_target", ], ) diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index ab896b8184..f35dce87d0 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -33,12 +33,8 @@ class EndEffectorTrajectoryGenerator drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; - drake::trajectories::PiecewisePolynomial GenerateCircle( - const drake::systems::Context& context) const; drake::trajectories::PiecewisePolynomial GeneratePose( const drake::systems::Context& context) const; - drake::trajectories::PiecewisePolynomial GenerateLine( - const drake::systems::Context& context) const; void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 228eb3e3a5..7715be6c64 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -1,106 +1,67 @@ #include "plate_balancing_target.h" -#include - #include "dairlib/lcmt_radio_out.hpp" -#include "multibody/multibody_utils.h" - -using Eigen::Map; -using Eigen::MatrixXd; -using Eigen::Vector2d; -using Eigen::Vector3d; -using Eigen::Vector4d; -using Eigen::VectorXd; -using std::string; -using dairlib::systems::OutputVector; -using drake::multibody::BodyFrame; -using drake::multibody::Frame; -using drake::multibody::JacobianWrtVariable; -using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; -using drake::systems::Context; -using drake::systems::DiscreteUpdateEvent; -using drake::systems::DiscreteValues; -using drake::systems::EventStatus; -using drake::trajectories::PiecewisePolynomial; -using drake::trajectories::Trajectory; +using Eigen::VectorXd; namespace dairlib { +namespace systems { -PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( - const MultibodyPlant& plant, Context* context) - : plant_(plant), context_(context), world_(plant.world_frame()) { +PlateBalancingTargetGenerator::PlateBalancingTargetGenerator() { // Input/Output Setup - state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); - PiecewisePolynomial pp = PiecewisePolynomial(); - - trajectory_port_ = - this->DeclareAbstractInputPort( - "trajectory", - drake::Value>(pp)) - .get_index(); radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); - PiecewisePolynomial empty_pp_traj(VectorXd(0)); - Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, - &PlateBalancingTargetGenerator::CalcTraj); + end_effector_target_port_ = + this->DeclareVectorOutputPort( + "end_effector_target", BasicVector(3), + &PlateBalancingTargetGenerator::CalcEndEffectorTarget) + .get_index(); + tray_target_port_ = this->DeclareVectorOutputPort( + "tray_target", BasicVector(7), + &PlateBalancingTargetGenerator::CalcTrayTarget) + .get_index(); } void PlateBalancingTargetGenerator::SetRemoteControlParameters( - const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale){ + const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, + double z_scale) { neutral_pose_ = neutral_pose; x_scale_ = x_scale; y_scale_ = y_scale; z_scale_ = z_scale; } -PiecewisePolynomial PlateBalancingTargetGenerator::GeneratePose( - const drake::systems::Context& context) const { - const auto robot_output = - this->template EvalVectorInput(context, state_port_); +void PlateBalancingTargetGenerator::CalcEndEffectorTarget( + const drake::systems::Context& context, + drake::systems::BasicVector* target) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); - double t = robot_output->get_timestamp(); - double dt = 0.1; VectorXd y0 = neutral_pose_; - y0(0) += radio_out->channel[0] * x_scale_; - y0(1) += radio_out->channel[1] * y_scale_; - y0(2) += radio_out->channel[2] * z_scale_; - VectorXd ydot0 = VectorXd::Zero(3); - std::vector breaks = {t, t + dt}; - std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold( - breaks, samples); + // Update target if remote trigger is active + if (radio_out->channel[13] > 0) { + y0(0) += radio_out->channel[0] * x_scale_; + y0(1) += radio_out->channel[1] * y_scale_; + y0(2) += radio_out->channel[2] * z_scale_; + } + target->SetFromVector(y0); } -void PlateBalancingTargetGenerator::CalcTraj( +void PlateBalancingTargetGenerator::CalcTrayTarget( const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const { - // // Read in finite state machine - const auto& trajectory_input = - this->EvalAbstractInput(context, trajectory_port_) - ->get_value>(); + BasicVector* target) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); - auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - if (radio_out->channel[14]) { - *casted_traj = GeneratePose(context); - } else { - *casted_traj = *(PiecewisePolynomial*)dynamic_cast< - const PiecewisePolynomial*>(&trajectory_input); - // *casted_traj = GenerateCircle(context); - // *casted_traj = GenerateLine(context); - } + VectorXd target_tray_state = VectorXd::Zero(7); + VectorXd tray_position = neutral_pose_; + tray_position(0) += radio_out->channel[0] * x_scale_; + tray_position(1) += radio_out->channel[1] * y_scale_; + tray_position(2) += radio_out->channel[2] * z_scale_; + target_tray_state << 1, 0, 0, 0, tray_position; + target->SetFromVector(target_tray_state); } -} // namespace dairlib +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index f0fe03d3a2..60b3ebb1e6 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -1,61 +1,49 @@ #pragma once -#include - -#include "systems/framework/output_vector.h" - -#include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" namespace dairlib { +namespace systems { class PlateBalancingTargetGenerator : public drake::systems::LeafSystem { public: - PlateBalancingTargetGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context); + PlateBalancingTargetGenerator(); - const drake::systems::InputPort& get_input_port_state() const { - return this->get_input_port(state_port_); - } - const drake::systems::InputPort& get_input_port_trajectory() const { - return this->get_input_port(trajectory_port_); - } const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); } - void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, double x_scale, - double y_scale, double z_scale); + const drake::systems::OutputPort& + get_output_port_end_effector_target() const { + return this->get_output_port(end_effector_target_port_); + } + + const drake::systems::OutputPort& get_output_port_tray_target() + const { + return this->get_output_port(tray_target_port_); + } + + void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, + double x_scale, double y_scale, + double z_scale); private: - drake::systems::EventStatus DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - drake::trajectories::PiecewisePolynomial GenerateCircle( - const drake::systems::Context& context) const; - drake::trajectories::PiecewisePolynomial GeneratePose( - const drake::systems::Context& context) const; - drake::trajectories::PiecewisePolynomial GenerateLine( - const drake::systems::Context& context) const; - - void CalcTraj(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; - const drake::multibody::Frame& world_; - - drake::systems::InputPortIndex state_port_; - drake::systems::InputPortIndex trajectory_port_; + void CalcEndEffectorTarget(const drake::systems::Context& context, + drake::systems::BasicVector* target) const; + void CalcTrayTarget(const drake::systems::Context& context, + drake::systems::BasicVector* target) const; + drake::systems::InputPortIndex radio_port_; + drake::systems::OutputPortIndex end_effector_target_port_; + drake::systems::OutputPortIndex tray_target_port_; Eigen::Vector3d neutral_pose_; double x_scale_; double y_scale_; double z_scale_; - std::vector half_plane_bounds_; + // std::vector half_plane_bounds_; }; -} // namespace dairlib +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 0dd2a418bb..d89a58d2c6 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -35,7 +35,6 @@ - 3.0e7 0.18 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 3b3849432c..77700a71f2 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -74,10 +74,10 @@ C3Controller::C3Controller( plant_.num_velocities(ModelInstanceIndex(3)); target_input_port_ = this->DeclareVectorInputPort("desired_position", x_des_size).get_index(); - radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) - .get_index(); +// radio_port_ = +// this->DeclareAbstractInputPort("lcmt_radio_out", +// drake::Value{}) +// .get_index(); auto c3_solution = C3Output::C3Solution(); c3_solution.x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); c3_solution.lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); @@ -103,8 +103,8 @@ C3Controller::C3Controller( drake::systems::EventStatus C3Controller::ComputePlan( const Context& context, DiscreteValues* discrete_state) const { - const auto& radio_out = - this->EvalInputValue(context, radio_port_); +// const auto& radio_out = +// this->EvalInputValue(context, radio_port_); const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const FrankaKinematicsVector* lcs_x = @@ -118,18 +118,18 @@ drake::systems::EventStatus C3Controller::ComputePlan( q_v_u << lcs_x->GetState(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); - VectorXd x_des_adjusted = x_des.value(); - VectorXd current = x_des_adjusted.head(n_q_).tail(3); - current(0) += radio_out->channel[0] * 0.2; - current(1) += radio_out->channel[1] * 0.2; - current(2) += radio_out->channel[2] * 0.2; - x_des_adjusted.head(n_q_).tail(3) = current; - if (radio_out->channel[13] > 0) { - x_des_adjusted.head(3) = current; - } +// VectorXd x_des_adjusted = x_des.value(); +// VectorXd current = x_des_adjusted.head(n_q_).tail(3); +// current(0) += radio_out->channel[0] * 0.2; +// current(1) += radio_out->channel[1] * 0.2; +// current(2) += radio_out->channel[2] * 0.2; +// x_des_adjusted.head(n_q_).tail(3) = current; +// if (radio_out->channel[13] > 0) { +// x_des_adjusted.head(3) = current; +// } std::vector x_desired = - std::vector(N_ + 1, x_des_adjusted); + std::vector(N_ + 1, x_des.value()); int n_x = plant_.num_positions() + plant_.num_velocities(); int n_u = plant_.num_actuators(); @@ -168,6 +168,16 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, -0.4, 0.4, 1); } + for (int i : vector({0, 1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, -5, 5, 2); + } + for (int i : vector({2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, 10, 20, 2); + } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); delta_ = delta; w_ = w; diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index df99c587fb..1a95da413a 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -51,9 +51,9 @@ class C3Controller : public drake::systems::LeafSystem { return this->get_output_port(c3_intermediates_port_); } - const drake::systems::InputPort& get_input_port_radio() const { - return this->get_input_port(radio_port_); - } +// const drake::systems::InputPort& get_input_port_radio() const { +// return this->get_input_port(radio_port_); +// } void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { solver_options_ = options; @@ -76,7 +76,7 @@ class C3Controller : public drake::systems::LeafSystem { drake::systems::InputPortIndex target_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; - drake::systems::InputPortIndex radio_port_; +// drake::systems::InputPortIndex radio_port_; drake::systems::OutputPortIndex c3_solution_port_; drake::systems::OutputPortIndex c3_intermediates_port_; From 5c0bcba1b689dcfb22d089fae2081d75f5a4d679 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Nov 2023 13:53:10 -0500 Subject: [PATCH 516/758] making metadata struct construction false by default for lcm trajectories --- lcm/lcm_trajectory.cc | 1 + lcm/lcm_trajectory.h | 12 ++++++------ 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index e698c29458..7508bbafe3 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -64,6 +64,7 @@ LcmTrajectory::LcmTrajectory(const vector& trajectories, for (const string& traj_name : trajectory_names_) { trajectories_[traj_name] = trajectories[index++]; } + metadata_.git_dirty_flag = false; if (get_metadata) { std::cout << "NOTE: Using subprocesses to get LcmTrajectory metadata\n"; ConstructMetadataObject(name, description); diff --git a/lcm/lcm_trajectory.h b/lcm/lcm_trajectory.h index 89b28e9fad..0eccb7de14 100644 --- a/lcm/lcm_trajectory.h +++ b/lcm/lcm_trajectory.h @@ -1,9 +1,9 @@ #pragma once +#include #include #include #include -#include #include @@ -27,7 +27,8 @@ class LcmTrajectory { /// lcmt_trajectory_block is the lcmtype analog struct Trajectory { Trajectory() = default; - Trajectory(const std::string& traj_name, const lcmt_trajectory_block& traj_block); + Trajectory(const std::string& traj_name, + const lcmt_trajectory_block& traj_block); std::string traj_name; Eigen::VectorXd time_vector; @@ -40,9 +41,8 @@ class LcmTrajectory { LcmTrajectory() = default; LcmTrajectory(const std::vector& trajectories, const std::vector& trajectory_names, - const std::string& name, - const std::string& description, - bool get_metadata=true); + const std::string& name, const std::string& description, + bool get_metadata = false); explicit LcmTrajectory(const lcmt_saved_traj& traj); @@ -88,6 +88,7 @@ class LcmTrajectory { return trajectory_names_; } lcmt_saved_traj GenerateLcmObject() const; + protected: /// Constructs a lcmt_metadata object with a specified name and description /// Other relevant metadata details such as datatime and git status are @@ -95,7 +96,6 @@ class LcmTrajectory { void ConstructMetadataObject(std::string name, std::string description); private: - lcmt_metadata metadata_; std::unordered_map trajectories_; std::vector trajectory_names_; From 3b3dc4dce4b17484f10831231d87eaf342e3079f Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 Nov 2023 13:53:57 -0500 Subject: [PATCH 517/758] allowing subplots in log_plotter_franka --- bindings/pydairlib/analysis/BUILD.bazel | 15 +++++ .../analysis/cassie_plotting_utils.py | 1 - .../pydairlib/analysis/franka_plot_config.py | 1 + .../pydairlib/analysis/log_plotter_franka.py | 19 ++++-- .../pydairlib/analysis/mbp_plotting_utils.py | 66 +++++++------------ .../plot_configs/franka_translation_plot.yaml | 3 +- bindings/pydairlib/common/plotting_utils.py | 6 +- 7 files changed, 56 insertions(+), 55 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index f17a75ceb6..da891628fc 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -91,6 +91,20 @@ py_library( ], ) +py_library( + name = "franka_plotting_utils", + srcs = ["franka_plotting_utils.py"], + data = [ + "//examples/Cassie:cassie_urdf", + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/lcm", + "//lcmtypes:lcmtypes_robot_archive_py", + "//lcmtypes:lcmtypes_robot_py", + ], +) + py_binary( name = "log_plotter_cassie", srcs = ["log_plotter_cassie.py"], @@ -149,6 +163,7 @@ py_library( PY_LIBRARIES = [ ":cassie_plotting_utils", + ":franka_plotting_utils", ":mbp_plotting_utils", ":spring_compensation", ":osc_debug_py", diff --git a/bindings/pydairlib/analysis/cassie_plotting_utils.py b/bindings/pydairlib/analysis/cassie_plotting_utils.py index 700abb3a44..0f7a564d15 100644 --- a/bindings/pydairlib/analysis/cassie_plotting_utils.py +++ b/bindings/pydairlib/analysis/cassie_plotting_utils.py @@ -1,7 +1,6 @@ # python imports import lcm import numpy as np -import matplotlib.pyplot as plt # lcmtype imports import dairlib diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py index 670beeaf7e..abc9c15026 100644 --- a/bindings/pydairlib/analysis/franka_plot_config.py +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -43,3 +43,4 @@ def __init__(self, filename): self.plot_active_tracking_datas = data['plot_active_tracking_datas'] self.tracking_datas_to_plot = \ data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] + self.plot_c3_debug = data['plot_c3_debug'] diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 3216a94c63..e4dde9cb8a 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -78,7 +78,8 @@ def main(): t_x_slice, pos_map) # import pdb; pdb.set_trace() - mbp_plots.plot_c3_inputs(c3_output, t_c3_slice) + if plot_config.plot_c3_debug: + mbp_plots.plot_c3_inputs(c3_output, t_c3_slice) # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) # Plot all joint velocities @@ -94,26 +95,30 @@ def main(): t_x_slice, vel_map) if plot_config.plot_end_effector: + end_effector_plotter = plot_styler.PlotStyler(nrows=2) mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, franka_context, ['paddle'], {'paddle': np.zeros(3)}, - {'paddle': [0, 1, 2]}) + {'paddle': [0, 1, 2]}, ps=end_effector_plotter, + subplot_index=0) mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, franka_context, ['paddle'], {'paddle': np.zeros(3)}, - {'paddle': [0, 1, 2]}) + {'paddle': [0, 1, 2]}, ps=end_effector_plotter, + subplot_index=1) ''' Plot Efforts ''' + effort_plotter = plot_styler.PlotStyler(nrows=2) if plot_config.plot_measured_efforts: plot = mbp_plots.plot_measured_efforts(robot_output, act_names, - t_x_slice) - plt.ylim(franka_joint_actuator_limit_range) + t_x_slice, effort_plotter, subplot_index=0) + plot.fig.axes[0].set_ylim(franka_joint_actuator_limit_range) if plot_config.plot_commanded_efforts: plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, - t_osc_slice) - plt.ylim(franka_joint_actuator_limit_range) + t_osc_slice, effort_plotter, subplot_index=1) + plot.fig.axes[1].set_ylim(franka_joint_actuator_limit_range) if plot_config.act_names: plot = mbp_plots.plot_measured_efforts_by_name(robot_output, diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 3786c2c49a..10130d5169 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -330,8 +330,9 @@ def load_c3_debug(data, c3_debug_channel): def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, - ylabel=None, title=None): - ps = plot_styler.PlotStyler() + ylabel=None, title=None, ps=None, subplot_index=0): + if ps is None: + ps = plot_styler.PlotStyler() if ylabel is None: ylabel = key if title is None: @@ -346,35 +347,15 @@ def plot_q_or_v_or_u( {key: x_names}, # legend entries {'xlabel': 'Time', 'ylabel': ylabel, - 'title': title}, ps) + 'title': title}, ps, subplot_index=subplot_index) return ps def plot_u_cmd( robot_input, key, x_names, x_slice, time_slice, - ylabel=None, title=None): - ps = plot_styler.PlotStyler() - if ylabel is None: - ylabel = key - if title is None: - title = key - - plotting_utils.make_plot( - robot_input, # data dict - 't_u', # time channel - time_slice, - [key], # key to plot - {key: x_slice}, # slice of key to plot - {key: x_names}, # legend entries - {'xlabel': 'Time', - 'ylabel': ylabel, - 'title': title}, ps) - return ps - - -def plot_u_cmd(robot_input, key, x_names, x_slice, time_slice, ylabel=None, - title=None): - ps = plot_styler.PlotStyler() + ylabel=None, title=None, ps=None, subplot_index=0): + if ps is None: + ps = plot_styler.PlotStyler() if ylabel is None: ylabel = key if title is None: @@ -389,21 +370,20 @@ def plot_u_cmd(robot_input, key, x_names, x_slice, time_slice, ylabel=None, {key: x_names}, # legend entries {'xlabel': 'Time', 'ylabel': ylabel, - 'title': title}, ps) + 'title': title}, ps, subplot_index=subplot_index) return ps - def plot_floating_base_positions(robot_output, q_names, fb_dim, time_slice): return plot_q_or_v_or_u(robot_output, 'q', q_names[:fb_dim], slice(fb_dim), time_slice, ylabel='Position', title='Floating Base Positions') -def plot_joint_positions(robot_output, q_names, fb_dim, time_slice): +def plot_joint_positions(robot_output, q_names, fb_dim, time_slice, subplot_index=0): q_slice = slice(fb_dim, len(q_names)) return plot_q_or_v_or_u(robot_output, 'q', q_names[q_slice], q_slice, time_slice, ylabel='Joint Angle (rad)', - title='Joint Positions') + title='Joint Positions', subplot_index=subplot_index) def plot_positions_by_name(robot_output, q_names, time_slice, pos_map): @@ -418,11 +398,11 @@ def plot_floating_base_velocities(robot_output, v_names, fb_dim, time_slice): title='Floating Base Velocities') -def plot_joint_velocities(robot_output, v_names, fb_dim, time_slice): +def plot_joint_velocities(robot_output, v_names, fb_dim, time_slice, subplot_index=0): q_slice = slice(fb_dim, len(v_names)) return plot_q_or_v_or_u(robot_output, 'v', v_names[q_slice], q_slice, time_slice, ylabel='Joint Vel (rad/s)', - title='Joint Velocities') + title='Joint Velocities', subplot_index=subplot_index) def plot_velocities_by_name(robot_output, v_names, time_slice, vel_map): @@ -431,26 +411,26 @@ def plot_velocities_by_name(robot_output, v_names, time_slice, vel_map): ylabel='Velocity', title='Select Velocities') -def plot_measured_efforts(robot_output, u_names, time_slice): +def plot_measured_efforts(robot_output, u_names, time_slice, ps=None, subplot_index=0): return plot_q_or_v_or_u(robot_output, 'u', u_names, slice(len(u_names)), time_slice, ylabel='Efforts (Nm)', - title='Measured Joint Efforts') + title='Measured Joint Efforts', ps=ps, subplot_index=subplot_index) -def plot_commanded_efforts(robot_input, u_names, time_slice): +def plot_commanded_efforts(robot_input, u_names, time_slice, ps=None, subplot_index=0): return plot_u_cmd(robot_input, 'u', u_names, slice(len(u_names)), time_slice, ylabel='Efforts (Nm)', - title='Commanded Joint Efforts') + title='Commanded Joint Efforts', ps=ps, subplot_index=subplot_index) -def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map): +def plot_measured_efforts_by_name(robot_output, u_names, time_slice, u_map, ps=None, subplot_index=0): u_slice = [u_map[name] for name in u_names] return plot_q_or_v_or_u(robot_output, 'u', u_names, u_slice, time_slice, - ylabel='Efforts (Nm)', title='Select Joint Efforts') + ylabel='Efforts (Nm)', title='Select Joint Efforts', ps=ps, subplot_index=subplot_index) def plot_points_positions(robot_output, time_slice, plant, context, frame_names, - pts, dims, ps=None): + pts, dims, ps=None, subplot_index=0): if ps is None: ps = plot_styler.PlotStyler() @@ -473,13 +453,13 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, legend_entries, {'title': 'Point Positions', 'xlabel': 'time (s)', - 'ylabel': 'pos (m)'}, ps) + 'ylabel': 'pos (m)'}, ps, subplot_index=subplot_index) return ps def plot_points_velocities(robot_output, time_slice, plant, context, frame_names, - pts, dims, ps=None): + pts, dims, ps=None, subplot_index=0): if ps is None: ps = plot_styler.PlotStyler() @@ -504,7 +484,7 @@ def plot_points_velocities(robot_output, time_slice, plant, context, frame_names legend_entries, {'title': 'Point Velocities', 'xlabel': 'time (s)', - 'ylabel': 'pos (m)'}, ps) + 'ylabel': 'pos (m)'}, ps, subplot_index=subplot_index) return ps @@ -848,7 +828,7 @@ def plot_c3_inputs(c3_output, time_slice): 't', time_slice, ['u'], - {'u': 0}, + {'u': 2}, {}, {'xlabel': 'Timestamp', 'ylabel': 'C3 Actor Inputs ', diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index fccfc11b7c..1a2d937d5a 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -17,7 +17,7 @@ plot_joint_velocities: true plot_measured_efforts: true plot_commanded_efforts: true plot_contact_forces: false -plot_end_effector: false +plot_end_effector: true special_positions_to_plot: [] special_velocities_to_plot: [] @@ -36,3 +36,4 @@ tracking_datas_to_plot: end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +plot_c3_debug: true \ No newline at end of file diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index aca420b5e3..ae8e7facd4 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -19,18 +19,18 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, slices_to_plot, legend_entries, plot_labels, - ps): + ps, subplot_index=0): legend = [] for key in keys_to_plot: if key not in slices_to_plot: ps.plot(data_dictionary[time_key][time_slice], data_dictionary[key][time_slice], xlabel=plot_labels['xlabel'], - ylabel=plot_labels['ylabel'], title=plot_labels['title']) + ylabel=plot_labels['ylabel'], title=plot_labels['title'], subplot_index=subplot_index) else: ps.plot(data_dictionary[time_key][time_slice], data_dictionary[key][time_slice, slices_to_plot[key]], xlabel=plot_labels['xlabel'], ylabel=plot_labels['ylabel'], - title=plot_labels['title']) + title=plot_labels['title'], subplot_index=subplot_index) if key in legend_entries: legend.extend(legend_entries[key]) From f9bc470771a1c441c70a6be069d192f4725a3f5f Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 8 Nov 2023 15:34:56 -0500 Subject: [PATCH 518/758] improving plotting script --- bindings/pydairlib/analysis/BUILD.bazel | 3 +- .../analysis/franka_plotting_utils.py | 73 +++++++++++-------- .../pydairlib/analysis/log_plotter_franka.py | 28 ++++--- .../pydairlib/analysis/mbp_plotting_utils.py | 23 +++++- .../plot_configs/franka_translation_plot.yaml | 6 +- 5 files changed, 84 insertions(+), 49 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index da891628fc..d0792adbea 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -95,8 +95,8 @@ py_library( name = "franka_plotting_utils", srcs = ["franka_plotting_utils.py"], data = [ - "//examples/Cassie:cassie_urdf", "@lcm//:lcm-python", + "@drake//manipulation/models/franka_description:models", ], deps = [ "//bindings/pydairlib/lcm", @@ -135,6 +135,7 @@ py_binary( deps = [ ":franka_plot_config", "//bindings/pydairlib/analysis:mbp_plotting_utils", + "//bindings/pydairlib/analysis:franka_plotting_utils", "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", "//bindings/pydairlib/common:plot_styler", diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index 6d3c5257e3..bcbf504e04 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -10,38 +10,53 @@ # drake imports from pydrake.multibody.plant import AddMultibodyPlantSceneGraph from pydrake.systems.framework import DiagramBuilder -from pydrake.all import MultibodyPlant, Parser, RigidTransform +from pydrake.all import MultibodyPlant, Parser, RigidTransform, \ + FindResourceOrThrow -franka_urdf = "examples/franka/urdf/franka_no_collision.urdf" +franka_urdf = FindResourceOrThrow( + "drake/manipulation/models/franka_description/urdf/panda_arm.urdf") +end_effector_model = "examples/franka/urdf/plate_end_effector.urdf" tray_model = "examples/franka/urdf/tray.sdf" +tool_attachment_frame = np.array([0, 0, 0.107]) + franka_default_channels = \ - {'FRANKA_STATE': dairlib.lcmt_robot_output, - 'FRANKA_STATE_SIMULATION': dairlib.lcmt_robot_output, - # 'TRAY_STATE': dairlib.lcmt_robot_output, - 'FRANKA_INPUT': dairlib.lcmt_robot_input, - 'OSC_FRANKA': dairlib.lcmt_robot_input, - 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, - 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, - 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, - 'C3_DEBUG': dairlib.lcmt_c3_output, - 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, - 'RADIO': dairlib.lcmt_radio_out, - 'CONTACT_RESULTS': drake.lcmt_contact_results_for_viz} + {'FRANKA_STATE': dairlib.lcmt_robot_output, + 'FRANKA_STATE_SIMULATION': dairlib.lcmt_robot_output, + # 'TRAY_STATE': dairlib.lcmt_robot_output, + 'FRANKA_INPUT': dairlib.lcmt_robot_input, + 'OSC_FRANKA': dairlib.lcmt_robot_input, + 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, + 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, + 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, + 'C3_DEBUG': dairlib.lcmt_c3_output, + 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, + 'RADIO': dairlib.lcmt_radio_out, + 'CONTACT_RESULTS': drake.lcmt_contact_results_for_viz} def make_plant_and_context(): - builder = DiagramBuilder() - - franka_plant = MultibodyPlant(0.0) - franka_parser = Parser(franka_plant) - franka_parser.AddModelFromFile(franka_urdf) - - tray_plant = MultibodyPlant(0.0) - tray_parser = Parser(tray_plant) - tray_parser.AddModelFromFile(tray_model) - - franka_plant.WeldFrames(franka_plant.world_frame(), franka_plant.GetFrameByName("panda_link0"), RigidTransform()) - - franka_plant.Finalize() - tray_plant.Finalize() - return franka_plant, franka_plant.CreateDefaultContext(), tray_plant, tray_plant.CreateDefaultContext() + builder = DiagramBuilder() + + franka_plant = MultibodyPlant(0.0) + franka_parser = Parser(franka_plant) + franka_parser.AddModelFromFile(franka_urdf) + end_effector_index = \ + franka_parser.AddModels(end_effector_model)[0] + T_EE_W = RigidTransform(tool_attachment_frame) + + franka_plant.WeldFrames(franka_plant.world_frame(), + franka_plant.GetFrameByName("panda_link0"), + RigidTransform()) + franka_plant.WeldFrames(franka_plant.GetFrameByName("panda_link7"), + franka_plant.GetFrameByName("plate", + end_effector_index), + T_EE_W) + + tray_plant = MultibodyPlant(0.0) + tray_parser = Parser(tray_plant) + tray_parser.AddModelFromFile(tray_model) + + franka_plant.Finalize() + tray_plant.Finalize() + return (franka_plant, franka_plant.CreateDefaultContext(), tray_plant, + tray_plant.CreateDefaultContext()) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index e4dde9cb8a..5d5f6b2e25 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -50,15 +50,15 @@ def main(): channel_osc) # processing callback arguments # processing callback arguments - c3_output = get_log_data(log, default_channels, plot_config.start_time, - plot_config.duration, mbp_plots.load_c3_debug, - channel_c3) + if plot_config.plot_c3_debug: + c3_output = get_log_data(log, default_channels, plot_config.start_time, + plot_config.duration, mbp_plots.load_c3_debug, + channel_c3) print('Finished processing log - making plots') # Define x time slice t_x_slice = slice(robot_output['t_x'].size) t_osc_slice = slice(osc_debug['t_osc'].size) - t_c3_slice = slice(c3_output['t'].size) print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) @@ -79,6 +79,7 @@ def main(): # import pdb; pdb.set_trace() if plot_config.plot_c3_debug: + t_c3_slice = slice(c3_output['t'].size) mbp_plots.plot_c3_inputs(c3_output, t_c3_slice) # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) @@ -87,6 +88,8 @@ def main(): plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, t_x_slice) plt.ylim(franka_joint_velocity_limit_range) + plt.axhline(franka_joint_velocity_limit_range[0], linestyle='--') + plt.axhline(franka_joint_velocity_limit_range[1], linestyle='--') # Plot specific velocities if plot_config.vel_names: @@ -97,15 +100,15 @@ def main(): if plot_config.plot_end_effector: end_effector_plotter = plot_styler.PlotStyler(nrows=2) mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, - franka_context, ['paddle'], - {'paddle': np.zeros(3)}, - {'paddle': [0, 1, 2]}, ps=end_effector_plotter, + franka_context, ['plate'], + {'plate': np.zeros(3)}, + {'plate': [0, 1, 2]}, ps=end_effector_plotter, subplot_index=0) mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, - franka_context, ['paddle'], - {'paddle': np.zeros(3)}, - {'paddle': [0, 1, 2]}, ps=end_effector_plotter, + franka_context, ['plate'], + {'plate': np.zeros(3)}, + {'plate': [0, 1, 2]}, ps=end_effector_plotter, subplot_index=1) ''' Plot Efforts ''' @@ -134,8 +137,9 @@ def main(): plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) if plot_config.plot_qp_solutions: - plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) - plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) + plot = mbp_plots.plot_ddq_sol(osc_debug, t_osc_slice, pos_names, slice(0, 7)) + # plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) + # plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 10130d5169..82a4441b4a 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -672,6 +672,20 @@ def plot_qp_solve_time(osc_debug, time_slice): return ps +def plot_ddq_sol(osc_debug, time_slice, joint_names, ddq_slice): + ps = plot_styler.PlotStyler() + plotting_utils.make_plot( + osc_debug, + 't_osc', + time_slice, + ['dv_sol'], + {'dv_sol': ddq_slice}, + {'dv_sol': joint_names[ddq_slice]}, + {'xlabel': 'time', + 'ylabel': 'joint accelerations (rad/s^2)', + 'title': 'OSC joint acceleration'}, ps) + return ps + def plot_lambda_c_sol(osc_debug, time_slice, lambda_slice): ps = plot_styler.PlotStyler() plotting_utils.make_plot( @@ -810,10 +824,11 @@ def generate_joint_limits(plant): joint_actuator_limits_lower = np.zeros(plant.num_positions()) joint_actuator_limits_upper = np.zeros(plant.num_positions()) for i in range(plant.num_positions()): - joint_position_limits_lower[i] = plant.get_joint(JointIndex(i)).position_upper_limits()[0] - joint_position_limits_upper[i] = plant.get_joint(JointIndex(i)).position_lower_limits()[0] - joint_velocity_limits_lower[i] = plant.get_joint(JointIndex(i)).velocity_upper_limits()[0] - joint_velocity_limits_upper[i] = plant.get_joint(JointIndex(i)).velocity_lower_limits()[0] + + joint_position_limits_lower[i] = plant.get_joint(JointIndex(i)).position_lower_limits()[0] + joint_position_limits_upper[i] = plant.get_joint(JointIndex(i)).position_upper_limits()[0] + joint_velocity_limits_lower[i] = plant.get_joint(JointIndex(i)).velocity_lower_limits()[0] + joint_velocity_limits_upper[i] = plant.get_joint(JointIndex(i)).velocity_upper_limits()[0] joint_actuator_limits_lower[i] = -plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() joint_actuator_limits_upper[i] = plant.get_joint_actuator(JointActuatorIndex(i)).effort_limit() franka_joint_position_limit_range = [np.min(joint_position_limits_lower), np.max(joint_position_limits_upper)] diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 1a2d937d5a..81b5269017 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -1,5 +1,5 @@ # LCM channels to read data from -channel_x: "FRANKA_STATE_SIMULATION" +channel_x: "FRANKA_STATE" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" channel_c3: "C3_DEBUG" @@ -29,11 +29,11 @@ fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', # Desired osc plots plot_qp_costs: false plot_qp_solve_time: true -plot_qp_solutions: false +plot_qp_solutions: true plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} -plot_c3_debug: true \ No newline at end of file +plot_c3_debug: false \ No newline at end of file From efe03cc88af317007349975f22d4d827f5dcbd2e Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 8 Nov 2023 15:35:48 -0500 Subject: [PATCH 519/758] enabling joint acceleration constraints as an option in OSC --- examples/franka/franka_osc_controller.cc | 1 + .../parameters/franka_osc_controller_params.h | 2 + .../franka_osc_controller_params.yaml | 3 +- .../osc/operational_space_control.cc | 14 +++++++ .../osc/operational_space_control.h | 37 +++++++++++-------- 5 files changed, 41 insertions(+), 16 deletions(-) diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index d068dd791a..4709a1da2d 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -166,6 +166,7 @@ int DoMain(int argc, char* argv[]) { osc->SetAccelerationCostWeights(gains.W_acceleration); osc->SetInputCostWeights(gains.W_input_regularization); osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); + osc->SetAccelerationConstraints(controller_params.enforce_acceleration_constraints); auto end_effector_position_tracking_data = std::make_unique( diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index 932fea7053..133ef584f4 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -13,6 +13,7 @@ struct FrankaControllerParams : OSCGains { double end_effector_acceleration; bool track_end_effector_orientation; bool cancel_gravity_compensation; + bool enforce_acceleration_constraints; std::vector neutral_position; double x_scale; @@ -50,6 +51,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(end_effector_acceleration)); a->Visit(DRAKE_NVP(track_end_effector_orientation)); a->Visit(DRAKE_NVP(cancel_gravity_compensation)); + a->Visit(DRAKE_NVP(enforce_acceleration_constraints)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 7df7e53fac..efc829c3fb 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,8 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true +enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 82374ac927..1d9f86c3e4 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -125,6 +125,15 @@ OperationalSpaceControl::OperationalSpaceControl( u_min_ = u_min; u_max_ = u_max; + VectorXd ddq_min(n_q_); + VectorXd ddq_max(n_q_); + for (JointIndex i(0); i < n_q_; ++i) { + ddq_min[i] = plant_wo_spr_.get_joint(i).acceleration_lower_limits()[0]; + ddq_max[i] = plant_wo_spr_.get_joint(i).acceleration_upper_limits()[0]; + } + ddq_min_ = ddq_min; + ddq_max_ = ddq_max; + n_revolute_joints_ = 0; for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); @@ -415,6 +424,11 @@ void OperationalSpaceControl::Build() { prog_->AddLinearConstraint(MatrixXd::Identity(n_u_, n_u_), u_min_, u_max_, u_); } + + if (with_acceleration_constraints_) { + prog_->AddLinearConstraint(MatrixXd::Identity(n_q_, n_q_), ddq_min_, ddq_max_, + dv_); + } // No joint position constraint in this implementation // Add costs diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 0632ca605e..f755a28f77 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -17,6 +17,7 @@ #include "solvers/fast_osqp_solver.h" #include "solvers/solver_options_io.h" #include "systems/controllers/control_utils.h" +#include "systems/controllers/osc/external_force_tracking_data.h" #include "systems/controllers/osc/osc_tracking_data.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" @@ -30,7 +31,6 @@ #include "drake/systems/framework/diagram.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/framework/leaf_system.h" -#include "systems/controllers/osc/external_force_tracking_data.h" namespace dairlib::systems::controllers { @@ -224,16 +224,17 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { */ void SetJointLimitWeight(const double w) { w_joint_limit_ = w; } - void DisableGravityCompensation() { - with_gravity_compensation_ = false; - } + void DisableGravityCompensation() { with_gravity_compensation_ = false; } - bool HasGravityCompensation(){ - return with_gravity_compensation_; - } + bool HasGravityCompensation() { return with_gravity_compensation_; } // Constraint methods - void DisableAcutationConstraint() { with_input_constraints_ = false; } + void SetActuationConstraints(bool constraint_status) { + with_input_constraints_ = constraint_status; + } + void SetAccelerationConstraints(bool constraint_status) { + with_acceleration_constraints_ = constraint_status; + } void SetContactFriction(double mu) { mu_ = mu; } void AddContactPoint(const multibody::WorldPointEvaluator* evaluator); @@ -248,7 +249,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { void AddTrackingData(std::unique_ptr tracking_data, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); - void AddForceTrackingData(std::unique_ptr tracking_data); + void AddForceTrackingData( + std::unique_ptr tracking_data); void AddConstTrackingData( std::unique_ptr tracking_data, const Eigen::VectorXd& v, double t_lb = 0, double t_ub = std::numeric_limits::infinity()); @@ -271,8 +273,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { SetOsqpSolverOptions( drake::yaml::LoadYamlFile( FindResourceOrThrow(yaml_string)) - .GetAsSolverOptions(drake::solvers::OsqpSolver::id()) - ); + .GetAsSolverOptions(drake::solvers::OsqpSolver::id())); }; // OSC LeafSystem builder void Build(); @@ -374,7 +375,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int n_c_active_; // Manually specified holonomic constraints (only valid for plants_wo_springs) - const multibody::KinematicEvaluatorSet* kinematic_evaluators_ = nullptr; + const multibody::KinematicEvaluatorSet* kinematic_evaluators_ = + nullptr; // robot input limits Eigen::VectorXd u_min_; @@ -384,10 +386,14 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::VectorXd q_min_; Eigen::VectorXd q_max_; - // robot joint limits + // robot joint limits gains Eigen::MatrixXd K_joint_pos_; Eigen::MatrixXd K_joint_vel_; + // robot joint acceleration limits + Eigen::VectorXd ddq_min_; + Eigen::VectorXd ddq_max_; + // flag indicating whether using osc with finite state machine or not bool used_with_finite_state_machine_; @@ -459,6 +465,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // OSC constraint members bool with_input_constraints_ = true; + bool with_acceleration_constraints_ = false; // Soft contact penalty coefficient and friction cone coefficient double mu_ = -1; // Friction coefficients double w_soft_constraint_ = -1; @@ -476,8 +483,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::make_unique>>(); std::unique_ptr>> - force_tracking_data_vec_ = - std::make_unique>>(); + force_tracking_data_vec_ = std::make_unique< + std::vector>>(); // Fixed position of constant trajectories std::vector fixed_position_vec_; From 095391c4e5bc0d3c64480798c592326ed7bbe7f2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Nov 2023 10:49:33 -0500 Subject: [PATCH 520/758] outputting force trajectory from c3 --- examples/franka/franka_c3_controller.cc | 8 ++++++ .../franka/parameters/franka_lcm_channels.h | 2 ++ .../parameters/lcm_channels_hardware.yaml | 1 + .../parameters/lcm_channels_simulation.yaml | 1 + .../franka/systems/c3_trajectory_generator.cc | 28 ++++++++++++++++++- .../franka/systems/c3_trajectory_generator.h | 10 ++++++- systems/controllers/c3_controller.cc | 24 ++-------------- 7 files changed, 51 insertions(+), 23 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 1c0d8bcda8..3ac08f7a1f 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -178,6 +178,12 @@ int DoMain(int argc, char* argv[]) { TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); + auto force_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, &lcm, + TriggerTypeSet({TriggerType::kPeriodic}), + 1 / controller_params.target_frequency)); + auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_debug_output_channel, &lcm, @@ -238,6 +244,8 @@ int DoMain(int argc, char* argv[]) { actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_force_trajectory(), + force_trajectory_sender->get_input_port()); builder.Connect(controller->get_output_port_c3_solution(), c3_output_sender->get_input_port_c3_solution()); diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h index a39dc0623f..91147a37e2 100644 --- a/examples/franka/parameters/franka_lcm_channels.h +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -13,6 +13,7 @@ struct FrankaLcmChannels { std::string osc_debug_channel; std::string c3_actor_channel; std::string c3_object_channel; + std::string c3_force_channel; std::string c3_debug_output_channel; std::string radio_channel; @@ -27,6 +28,7 @@ struct FrankaLcmChannels { a->Visit(DRAKE_NVP(osc_debug_channel)); a->Visit(DRAKE_NVP(c3_actor_channel)); a->Visit(DRAKE_NVP(c3_object_channel)); + a->Visit(DRAKE_NVP(c3_force_channel)); a->Visit(DRAKE_NVP(c3_debug_output_channel)); a->Visit(DRAKE_NVP(radio_channel)); } diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index 5d138589d2..71788307c3 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -9,6 +9,7 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY +c3_force_channel: C3_TRAJECTORY_FORCE c3_debug_output_channel: C3_DEBUG radio_channel: RADIO diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index b3c36b1cb9..016662c7e0 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -9,6 +9,7 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY +c3_force_channel: C3_TRAJECTORY_FORCE c3_debug_output_channel: C3_DEBUG radio_channel: RADIO diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 220308334b..5ad2b6c4a3 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -56,6 +56,12 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( dairlib::lcmt_timestamped_saved_traj(), &C3TrajectoryGenerator::OutputObjectTrajectory) .get_index(); + force_trajectory_port_ = + this->DeclareAbstractOutputPort( + "c3_force_trajectory_output", + dairlib::lcmt_timestamped_saved_traj(), + &C3TrajectoryGenerator::OutputForceTrajectory) + .get_index(); } void C3TrajectoryGenerator::OutputActorTrajectory( @@ -63,6 +69,7 @@ void C3TrajectoryGenerator::OutputActorTrajectory( dairlib::lcmt_timestamped_saved_traj* output_traj) const { const auto& c3_solution = this->EvalInputValue(context, c3_solution_port_); + DRAKE_DEMAND(c3_solution->x_sol_.rows() == n_q_ + n_v_); MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = c3_solution->x_sol_.topRows(3).cast(); @@ -101,7 +108,7 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( dairlib::lcmt_timestamped_saved_traj* output_traj) const { const auto& c3_solution = this->EvalInputValue(context, c3_solution_port_); - + DRAKE_DEMAND(c3_solution->x_sol_.rows() == n_q_ + n_v_); MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3).cast(); knots.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); @@ -132,5 +139,24 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( output_traj->utime = context.get_time() * 1e6; } +void C3TrajectoryGenerator::OutputForceTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const { + const auto& c3_solution = + this->EvalInputValue(context, c3_solution_port_); + DRAKE_DEMAND(c3_solution->u_sol_.rows() == n_u_); + MatrixXd knots = c3_solution->u_sol_.cast(); + LcmTrajectory::Trajectory force_traj; + force_traj.traj_name = "force_traj"; + force_traj.datatypes = std::vector(knots.rows(), "double"); + force_traj.datapoints = knots; + force_traj.time_vector = c3_solution->time_vector_.cast(); + LcmTrajectory lcm_traj({force_traj}, {"force_traj"}, "force_traj", + "force_traj", false); + + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_traj->utime = context.get_time() * 1e6; +} + } // namespace systems } // namespace dairlib diff --git a/examples/franka/systems/c3_trajectory_generator.h b/examples/franka/systems/c3_trajectory_generator.h index 1fb38b633e..086ac40ff5 100644 --- a/examples/franka/systems/c3_trajectory_generator.h +++ b/examples/franka/systems/c3_trajectory_generator.h @@ -38,6 +38,10 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const { return this->get_output_port(object_trajectory_port_); } + const drake::systems::OutputPort& get_output_port_force_trajectory() + const { + return this->get_output_port(force_trajectory_port_); + } void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { publish_end_effector_orientation_ = publish_end_effector_orientation; @@ -52,9 +56,14 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const; + void OutputForceTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const; + drake::systems::InputPortIndex c3_solution_port_; drake::systems::OutputPortIndex actor_trajectory_port_; drake::systems::OutputPortIndex object_trajectory_port_; + drake::systems::OutputPortIndex force_trajectory_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; @@ -69,7 +78,6 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { int n_lambda_; int n_u_; - // std::unique_ptr lcs_; drake::systems::DiscreteStateIndex plan_start_time_index_; int N_; }; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 77700a71f2..acbfcf593a 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -1,10 +1,7 @@ #include "c3_controller.h" -#include #include -#include - #include "common/find_resource.h" #include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" @@ -58,7 +55,7 @@ C3Controller::C3Controller( 2 * c3_options_.num_contacts + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; n_u_ = plant_.num_actuators(); - Q_.back() = 100 * c3_options_.Q; +// Q_.back() = 100 * c3_options_.Q; lcs_state_input_port_ = this->DeclareVectorInputPort( @@ -74,10 +71,7 @@ C3Controller::C3Controller( plant_.num_velocities(ModelInstanceIndex(3)); target_input_port_ = this->DeclareVectorInputPort("desired_position", x_des_size).get_index(); -// radio_port_ = -// this->DeclareAbstractInputPort("lcmt_radio_out", -// drake::Value{}) -// .get_index(); + auto c3_solution = C3Output::C3Solution(); c3_solution.x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); c3_solution.lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); @@ -103,8 +97,6 @@ C3Controller::C3Controller( drake::systems::EventStatus C3Controller::ComputePlan( const Context& context, DiscreteValues* discrete_state) const { -// const auto& radio_out = -// this->EvalInputValue(context, radio_port_); const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const FrankaKinematicsVector* lcs_x = @@ -118,16 +110,6 @@ drake::systems::EventStatus C3Controller::ComputePlan( q_v_u << lcs_x->GetState(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); -// VectorXd x_des_adjusted = x_des.value(); -// VectorXd current = x_des_adjusted.head(n_q_).tail(3); -// current(0) += radio_out->channel[0] * 0.2; -// current(1) += radio_out->channel[1] * 0.2; -// current(2) += radio_out->channel[2] * 0.2; -// x_des_adjusted.head(n_q_).tail(3) = current; -// if (radio_out->channel[13] > 0) { -// x_des_adjusted.head(3) = current; -// } - std::vector x_desired = std::vector(N_ + 1, x_des.value()); @@ -202,7 +184,7 @@ void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { double t = context.get_discrete_state(plan_start_time_index_)[0]; -// auto z_sol = c3_->GetFullSolution(); + for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; c3_intermediates->w_.col(i) = w_[i].cast(); From 1732adf3f5fb43113f3d2d99beaf571934d71d6c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Nov 2023 14:41:32 -0500 Subject: [PATCH 521/758] adding qp projection option --- examples/franka/franka_c3_controller.cc | 13 +- examples/franka/franka_osc_controller.cc | 16 +-- .../franka_c3_options_translation.yaml | 1 + .../franka_osc_controller_params.yaml | 2 +- solvers/BUILD.bazel | 2 + solvers/c3.cc | 9 +- solvers/c3_options.h | 2 + solvers/c3_qp.cc | 115 ++++++++++++++++++ solvers/c3_qp.h | 62 ++++++++++ systems/controllers/c3_controller.cc | 31 +++-- systems/controllers/c3_controller.h | 4 +- 11 files changed, 225 insertions(+), 32 deletions(-) create mode 100644 solvers/c3_qp.cc create mode 100644 solvers/c3_qp.h diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 3ac08f7a1f..32d6619c78 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -147,9 +147,9 @@ int DoMain(int argc, char* argv[]) { contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); } - VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + - plant_plate.num_velocities()); - x_des << c3_options.q_des, c3_options.v_des; +// VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + +// plant_plate.num_velocities()); +// x_des << c3_options.q_des, c3_options.v_des; DiagramBuilder builder; @@ -165,29 +165,26 @@ int DoMain(int argc, char* argv[]) { plant_franka, franka_context.get(), plant_tray, tray_context.get(), controller_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); - auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_actor_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); - auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); - auto force_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_force_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); - auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_debug_output_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + TriggerTypeSet({TriggerType::kPeriodic}), + 1 / controller_params.target_frequency)); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 4709a1da2d..9cc806a1f1 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -100,7 +100,8 @@ int DoMain(int argc, char* argv[]) { end_effector_index), T_EE_W); } else { - std::cout << "OSC plant has been constructed with no end effector." << std::endl; + std::cout << "OSC plant has been constructed with no end effector." + << std::endl; } plant.Finalize(); @@ -116,7 +117,7 @@ int DoMain(int argc, char* argv[]) { orientation_traj.traj_name = "end_effector_orientation_target"; orientation_traj.datatypes = std::vector(2, "orientation"); lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); -// lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); + // lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( @@ -163,11 +164,6 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.osc_debug_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); - osc->SetAccelerationCostWeights(gains.W_acceleration); - osc->SetInputCostWeights(gains.W_input_regularization); - osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); - osc->SetAccelerationConstraints(controller_params.enforce_acceleration_constraints); - auto end_effector_position_tracking_data = std::make_unique( "end_effector_target", controller_params.K_p_end_effector, @@ -203,11 +199,15 @@ int DoMain(int argc, char* argv[]) { controller_params.end_effector_name); Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); orientation_target(0) = 1; - osc->AddTrackingData(std::move(end_effector_position_tracking_data)); osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), 1.6 * VectorXd::Ones(1)); osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); + osc->SetAccelerationCostWeights(gains.W_acceleration); + osc->SetInputCostWeights(gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); + osc->SetAccelerationConstraints( + controller_params.enforce_acceleration_constraints); osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 3fcc9ce80c..d32a36a151 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -3,6 +3,7 @@ rho: 0.1 rho_scale: 2 num_threads: 6 delta_option: 1 +projection_type: "MIQP" mu: 0.4 mu_plate: 0.4 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index efc829c3fb..aa8fc904df 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 398ee6f58f..7a8fe3fc44 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -24,11 +24,13 @@ cc_library( srcs = [ "c3.cc", "c3_miqp.cc", + "c3_qp.cc", ], hdrs = [ "c3.h", "c3_miqp.h", "c3_options.h", + "c3_qp.h", ], copts = [ "-fopenmp", diff --git a/solvers/c3.cc b/solvers/c3.cc index a1aec5aeb7..87c3817593 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -3,8 +3,8 @@ #include #include -#include #include +#include #include "solvers/lcs.h" @@ -143,7 +143,7 @@ vector C3::Solve(const VectorXd& x0, vector& delta, vector zfin = SolveQP(x0, Gv, WD); -// auto z0 = zfin[0]; + // auto z0 = zfin[0]; // return z.segment(n_ + m_, k_); // return z0; @@ -235,7 +235,6 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, MathematicalProgramResult result = osqp_.Solve(prog_); if (result.is_success()) { - for (int i = 0; i < N_; i++) { x_sol_->at(i) = result.GetSolution(x_[i]); lambda_sol_->at(i) = result.GetSolution(lambda_[i]); @@ -277,8 +276,8 @@ void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double lower_bound, if (constraint == 3) { for (int i = 0; i < N_; i++) { - user_constraints_.push_back( - prog_.AddLinearConstraint(A, lower_bound, upper_bound, lambda_.at(i))); + user_constraints_.push_back(prog_.AddLinearConstraint( + A, lower_bound, upper_bound, lambda_.at(i))); } } } diff --git a/solvers/c3_options.h b/solvers/c3_options.h index bc4afc7c51..b4022adbf5 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -9,6 +9,7 @@ struct C3Options { float rho_scale = 3; // scaling of rho parameter (/rho = rho_scale * /rho) //3 int num_threads = 0; // 0 is dynamic, greater than 0 for a fixed count int delta_option = 1; // different options for delta update + std::string projection_type; int N; double w_Q; @@ -52,6 +53,7 @@ struct C3Options { a->Visit(DRAKE_NVP(rho_scale)); a->Visit(DRAKE_NVP(num_threads)); a->Visit(DRAKE_NVP(delta_option)); + a->Visit(DRAKE_NVP(projection_type)); a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(mu_plate)); diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc new file mode 100644 index 0000000000..0c00a2e9de --- /dev/null +++ b/solvers/c3_qp.cc @@ -0,0 +1,115 @@ +#include "solvers/c3_qp.h" + +#include + +#include + +#include "solvers/c3_options.h" +#include "solvers/lcs.h" + +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/osqp_solver.h" +#include "drake/solvers/solve.h" + +namespace dairlib { +namespace solvers { + +using Eigen::MatrixXd; +using Eigen::VectorXd; +using std::vector; + +using drake::solvers::MathematicalProgram; +using drake::solvers::MathematicalProgramResult; +using drake::solvers::SolutionResult; +using drake::solvers::SolverOptions; + +using drake::solvers::OsqpSolver; +using drake::solvers::OsqpSolverDetails; +using drake::solvers::Solve; + +C3QP::C3QP(const LCS& LCS, const vector& Q, const vector& R, + const vector& G, const vector& U, + const vector& xdesired, const C3Options& options, + const std::vector& warm_start_delta, + const std::vector& warm_start_binary, + const std::vector& warm_start_x, + const std::vector& warm_start_lambda, + const std::vector& warm_start_u, bool warm_start) + : C3(LCS, Q, R, G, U, xdesired, options, warm_start_delta, + warm_start_binary, warm_start_x, warm_start_lambda, warm_start_u, + warm_start) {} + +VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, + const MatrixXd& E, const MatrixXd& F, + const MatrixXd& H, const VectorXd& c, + const int& warm_start_index) { + drake::solvers::MathematicalProgram prog; + drake::solvers::SolverOptions solver_options; + drake::solvers::OsqpSolver osqp_; + + auto xn_ = prog.NewContinuousVariables(n_, "x"); + auto ln_ = prog.NewContinuousVariables(m_, "lambda"); + auto un_ = prog.NewContinuousVariables(k_, "u"); + + double alpha = 0.3; + double scaling = 1000; + + MatrixXd EFH(m_, n_ + m_ + k_); + EFH.block(0, 0, m_, n_) = E / scaling; + EFH.block(0, n_, m_, m_) = F / scaling; + EFH.block(0, n_ + m_, m_, k_) = H / scaling; + + prog.AddLinearConstraint( + EFH, -c / scaling, + Eigen::VectorXd::Constant(m_, std::numeric_limits::infinity()), + {xn_, ln_, un_}); + + prog.AddLinearConstraint( + MatrixXd::Identity(m_, m_), VectorXd::Zero(m_), + Eigen::VectorXd::Constant(m_, std::numeric_limits::infinity()), + ln_); + + MatrixXd New_U = U; + New_U.block(n_, n_, m_, m_) = alpha * F; + + VectorXd cost_linear = -delta_c.transpose() * New_U; + +// prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}, 1); + prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}); + +// prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); + prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_); + + solver_options.SetOption(OsqpSolver::id(), "max_iter", 250); + solver_options.SetOption(OsqpSolver::id(), "verbose", 0); + solver_options.SetOption(OsqpSolver::id(), "polish", 1); + solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 3); + solver_options.SetOption(OsqpSolver::id(), "rho", 1e-4); + solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); + solver_options.SetOption(OsqpSolver::id(), "linsys_solver", 0); + prog.SetSolverOptions(solver_options); + + MathematicalProgramResult result = osqp_.Solve(prog); + + VectorXd xSol = result.GetSolution(xn_); + VectorXd lamSol = result.GetSolution(ln_); + VectorXd uSol = result.GetSolution(un_); + + VectorXd delta_kc = VectorXd::Zero(n_ + m_ + k_); + delta_kc.segment(0, n_) = xSol; + delta_kc.segment(n_, m_) = lamSol; + delta_kc.segment(n_ + m_, k_) = uSol; + + return delta_kc; +} + +std::vector C3QP::GetWarmStartDelta() const { + return warm_start_delta_; +} + +std::vector C3QP::GetWarmStartBinary() const { + return warm_start_binary_; +} + +} // namespace solvers +} // namespace dairlib diff --git a/solvers/c3_qp.h b/solvers/c3_qp.h new file mode 100644 index 0000000000..46c88b338b --- /dev/null +++ b/solvers/c3_qp.h @@ -0,0 +1,62 @@ +#pragma once + +#include + +#include + +#include "gurobi_c++.h" +#include "solvers/c3.h" +#include "solvers/lcs.h" + +#include "drake/solvers/mathematical_program.h" +#include "drake/solvers/moby_lcp_solver.h" +#include "drake/solvers/osqp_solver.h" +#include "drake/solvers/solve.h" + +#include "solvers/c3_options.h" +#include "solvers/fast_osqp_solver.h" + + +namespace dairlib { +namespace solvers { + +class C3QP : public C3 { + public: + /// Default constructor for time-varying LCS + C3QP(const LCS& LCS, const std::vector& Q, + const std::vector& R, + const std::vector& G, + const std::vector& U, + const std::vector& xdesired, + const C3Options& options, + const std::vector& warm_start_delta = {}, + const std::vector& warm_start_binary = {}, + const std::vector& warm_start_x = {}, + const std::vector& warm_start_lambda = {}, + const std::vector& warm_start_u = {}, + bool warm_start = false); + + /// Virtual projection method + Eigen::VectorXd SolveSingleProjection(const Eigen::MatrixXd& U, + const Eigen::VectorXd& delta_c, + const Eigen::MatrixXd& E, + const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, + const Eigen::VectorXd& c, + const int& warm_start_index = -1); + std::vector GetWarmStartDelta() const; + std::vector GetWarmStartBinary() const; + + +// private: +// GRBEnv env_; + //drake::solvers::MathematicalProgram projprog_; + //drake::solvers::SolverOptions OSQPoptions_; + //drake::solvers::OsqpSolver osqp_; +// drake::solvers::VectorXDecisionVariable xn_; +// drake::solvers::VectorXDecisionVariable un_; +// drake::solvers::VectorXDecisionVariable ln_; +}; + +} // namespace solvers +} // namespace dairlib diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index acbfcf593a..d648579036 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -2,13 +2,15 @@ #include +#include + #include "common/find_resource.h" #include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" +#include "solvers/c3_miqp.h" +#include "solvers/c3_qp.h" #include "solvers/lcs_factory.h" -#include "drake/solvers/moby_lcp_solver.h" - namespace dairlib { using drake::multibody::ModelInstanceIndex; @@ -16,13 +18,14 @@ using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteValues; using Eigen::MatrixXd; -using Eigen::VectorXd; using Eigen::MatrixXf; +using Eigen::VectorXd; using Eigen::VectorXf; -using std::vector; using solvers::C3MIQP; +using solvers::C3QP; using solvers::LCS; using solvers::LCSFactory; +using std::vector; using systems::TimestampedVector; namespace systems { @@ -55,7 +58,7 @@ C3Controller::C3Controller( 2 * c3_options_.num_contacts + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; n_u_ = plant_.num_actuators(); -// Q_.back() = 100 * c3_options_.Q; + // Q_.back() = 100 * c3_options_.Q; lcs_state_input_port_ = this->DeclareVectorInputPort( @@ -131,7 +134,17 @@ drake::systems::EventStatus C3Controller::ComputePlan( DRAKE_DEMAND(R_.front().cols() == lcs.k_); DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); - c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); + + if (c3_options_.projection_type == "MIQP") { + c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); + + } else if (c3_options_.projection_type == "QP") { + c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); + + } else { + std::cerr << ("Unknown projection type") << std::endl; + DRAKE_THROW_UNLESS(false); + } c3_->SetOsqpSolverOptions(solver_options_); VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); @@ -175,8 +188,10 @@ void C3Controller::OutputC3Solution( for (int i = 0; i < N_; i++) { c3_solution->time_vector_(i) = t + i * c3_options_.dt; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); - c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); - c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 1a95da413a..6efae29fe0 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -10,7 +10,7 @@ #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "lcm/lcm_trajectory.h" #include "solvers/c3.h" -#include "solvers/c3_miqp.h" + #include "solvers/c3_options.h" #include "solvers/c3_output.h" #include "solvers/lcs.h" @@ -101,7 +101,7 @@ class C3Controller : public drake::systems::LeafSystem { int n_lambda_; int n_u_; - mutable std::unique_ptr c3_; + mutable std::unique_ptr c3_; mutable std::vector delta_; mutable std::vector w_; // std::unique_ptr lcs_; From 4158d9e790bf3ce12da039011621b7bb4143fef7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 9 Nov 2023 17:01:14 -0500 Subject: [PATCH 522/758] implemented very hacky way of adding external force tracking --- examples/franka/franka_c3_controller.cc | 4 -- examples/franka/franka_osc_controller.cc | 21 ++++---- .../parameters/franka_osc_controller_params.h | 6 +++ .../franka_osc_controller_params.yaml | 4 ++ .../osc/external_force_tracking_data.cc | 16 ++++-- .../osc/external_force_tracking_data.h | 25 +++++----- .../osc/operational_space_control.cc | 50 ++++++++++++------- 7 files changed, 79 insertions(+), 47 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 32d6619c78..c98c282e73 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -147,10 +147,6 @@ int DoMain(int argc, char* argv[]) { contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); } -// VectorXd x_des = VectorXd::Zero(plant_plate.num_positions() + -// plant_plate.num_velocities()); -// x_des << c3_options.q_des, c3_options.v_des; - DiagramBuilder builder; auto tray_state_sub = diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 9cc806a1f1..dce3efbe4f 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -16,6 +16,7 @@ #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/controllers/osc/external_force_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -49,6 +50,7 @@ using systems::controllers::JointSpaceTrackingData; using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::ExternalForceTrackingData; DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", @@ -171,16 +173,10 @@ int DoMain(int argc, char* argv[]) { plant, plant); end_effector_position_tracking_data->AddPointToTrack( controller_params.end_effector_name); - const VectorXd& bound = + const VectorXd& end_effector_acceleration_limits = controller_params.end_effector_acceleration * Vector3d::Ones(); - end_effector_position_tracking_data->SetCmdAccelerationBounds(-bound, bound); - auto end_effector_position_tracking_data_for_rel = - std::make_unique( - "end_effector_target", controller_params.K_p_end_effector, - controller_params.K_d_end_effector, controller_params.W_end_effector, - plant, plant); - end_effector_position_tracking_data_for_rel->AddPointToTrack( - controller_params.end_effector_name); + end_effector_position_tracking_data->SetCmdAccelerationBounds( + -end_effector_acceleration_limits, end_effector_acceleration_limits); auto mid_link_position_tracking_data_for_rel = std::make_unique( "panda_joint2_target", controller_params.K_p_mid_link, @@ -189,6 +185,12 @@ int DoMain(int argc, char* argv[]) { mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", "panda_joint2dot"); + auto end_effector_force_tracking_data = + std::make_unique( + "end_effector_force", controller_params.W_ee_lambda, plant, plant, + controller_params.end_effector_name, Vector3d::Zero() + ); + auto end_effector_orientation_tracking_data = std::make_unique( "end_effector_orientation_target", @@ -203,6 +205,7 @@ int DoMain(int argc, char* argv[]) { osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), 1.6 * VectorXd::Ones(1)); osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); + osc->AddForceTrackingData(std::move(end_effector_force_tracking_data)); osc->SetAccelerationCostWeights(gains.W_acceleration); osc->SetInputCostWeights(gains.W_input_regularization); osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index 133ef584f4..a5fc7cf633 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -30,6 +30,7 @@ struct FrankaControllerParams : OSCGains { std::vector EndEffectorRotW; std::vector EndEffectorRotKp; std::vector EndEffectorRotKd; + std::vector LambdaEndEffectorW; Eigen::MatrixXd W_end_effector; Eigen::MatrixXd K_p_end_effector; @@ -40,6 +41,7 @@ struct FrankaControllerParams : OSCGains { Eigen::MatrixXd W_end_effector_rot; Eigen::MatrixXd K_p_end_effector_rot; Eigen::MatrixXd K_d_end_effector_rot; + Eigen::MatrixXd W_ee_lambda; template void Serialize(Archive* a) { @@ -58,6 +60,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(EndEffectorRotW)); a->Visit(DRAKE_NVP(EndEffectorRotKp)); a->Visit(DRAKE_NVP(EndEffectorRotKd)); + a->Visit(DRAKE_NVP(LambdaEndEffectorW)); a->Visit(DRAKE_NVP(w_elbow)); a->Visit(DRAKE_NVP(elbow_kp)); a->Visit(DRAKE_NVP(elbow_kd)); @@ -88,5 +91,8 @@ struct FrankaControllerParams : OSCGains { K_d_end_effector_rot = Eigen::Map< Eigen::Matrix>( this->EndEffectorRotKd.data(), 3, 3); + W_ee_lambda = Eigen::Map< + Eigen::Matrix>( + this->LambdaEndEffectorW.data(), 3, 3); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index aa8fc904df..1abef96206 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -62,3 +62,7 @@ EndEffectorRotKd: [ 10, 0, 0, 0, 10, 0, 0, 0, 10 ] +LambdaEndEffectorW: + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1 ] diff --git a/systems/controllers/osc/external_force_tracking_data.cc b/systems/controllers/osc/external_force_tracking_data.cc index b16c59062f..34bd93f6cd 100644 --- a/systems/controllers/osc/external_force_tracking_data.cc +++ b/systems/controllers/osc/external_force_tracking_data.cc @@ -1,5 +1,4 @@ #include "external_force_tracking_data.h" -#include "osc_tracking_data.h" using Eigen::MatrixXd; using Eigen::Quaterniond; @@ -17,20 +16,27 @@ namespace dairlib::systems::controllers { ExternalForceTrackingData::ExternalForceTrackingData( const string& name, const MatrixXd& W, const MultibodyPlant& plant_w_spr, - const MultibodyPlant& plant_wo_spr) + const MultibodyPlant& plant_wo_spr, + const std::string& body_name, const Vector3d& pt_on_body) : name_(name), plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), world_w_spr_(plant_w_spr_.world_frame()), world_wo_spr_(plant_wo_spr_.world_frame()), - W_(W) {} + body_frame_w_spr_(&plant_w_spr_.GetBodyByName(body_name).body_frame()), + body_frame_wo_spr_(&plant_wo_spr_.GetBodyByName(body_name).body_frame()), + pt_on_body_(pt_on_body), + W_(W) { + J_ = MatrixXd::Zero(3, plant_wo_spr_.num_velocities()); + lambda_des_ = Vector3d::Zero(); +} -void ExternalForceTrackingData::UpdateActual( +void ExternalForceTrackingData::Update( const Eigen::VectorXd& x_w_spr, const drake::systems::Context& context_w_spr, const Eigen::VectorXd& x_wo_spr, const drake::systems::Context& context_wo_spr, double t) { - J_ = MatrixXd::Zero(kSpaceDim, plant_wo_spr_.num_velocities()); + J_ = MatrixXd::Zero(3, plant_wo_spr_.num_velocities()); plant_wo_spr_.CalcJacobianTranslationalVelocity( context_wo_spr, JacobianWrtVariable::kV, *body_frame_wo_spr_, pt_on_body_, world_wo_spr_, world_wo_spr_, &J_); diff --git a/systems/controllers/osc/external_force_tracking_data.h b/systems/controllers/osc/external_force_tracking_data.h index cc6e9bf3cd..623d4deb4e 100644 --- a/systems/controllers/osc/external_force_tracking_data.h +++ b/systems/controllers/osc/external_force_tracking_data.h @@ -16,13 +16,15 @@ class ExternalForceTrackingData { ExternalForceTrackingData( const std::string& name, const Eigen::MatrixXd& W, const drake::multibody::MultibodyPlant& plant_w_spr, - const drake::multibody::MultibodyPlant& plant_wo_spr); + const drake::multibody::MultibodyPlant& plant_wo_spr, + const std::string& body_name, const Eigen::Vector3d& pt_on_body); const Eigen::MatrixXd& GetWeight() const { return W_; } const Eigen::MatrixXd& GetJ() const { return J_; } + const Eigen::VectorXd& GetLambdaDes() const { return lambda_des_; } const std::string& GetName() const { return name_; }; - int GetYDim() const { return n_y_; }; + int GetLambdaDim() const { return n_lambda_; }; const drake::multibody::MultibodyPlant& plant_w_spr() const { return plant_w_spr_; @@ -30,18 +32,16 @@ class ExternalForceTrackingData { const drake::multibody::MultibodyPlant& plant_wo_spr() const { return plant_wo_spr_; }; - - protected: - private: - std::string name_; - - // This method is called from the parent class (OscTrackingData) due to C++ - // polymorphism. - void UpdateActual(const Eigen::VectorXd& x_w_spr, + void Update(const Eigen::VectorXd& x_w_spr, const drake::systems::Context& context_w_spr, const Eigen::VectorXd& x_wo_spr, const drake::systems::Context& context_wo_spr, double t); + protected: + private: + std::string name_; + + const drake::multibody::MultibodyPlant& plant_w_spr_; const drake::multibody::MultibodyPlant& plant_wo_spr_; @@ -51,10 +51,11 @@ class ExternalForceTrackingData { const drake::multibody::BodyFrame* body_frame_w_spr_; const drake::multibody::BodyFrame* body_frame_wo_spr_; - Eigen::Vector3d pt_on_body_; + const Eigen::Vector3d pt_on_body_; - int n_y_ = 3; + int n_lambda_ = 3; + Eigen::VectorXd lambda_des_; Eigen::MatrixXd J_; Eigen::MatrixXd W_; }; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 1d9f86c3e4..3790a1fd26 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -323,9 +323,11 @@ void OperationalSpaceControl::Build() { n_ee_ = 0; for (auto& force_tracking_data : *force_tracking_data_vec_) { - n_ee_ += force_tracking_data->GetYDim(); + n_ee_ += force_tracking_data->GetLambdaDim(); } + std::cout << "num contact forces" << n_ee_ << std::endl; + n_c_active_ = 0; for (auto evaluator : all_contacts_) { n_c_active_ += evaluator->num_active(); @@ -371,8 +373,8 @@ void OperationalSpaceControl::Build() { dynamics_constraint_ = prog_ ->AddLinearEqualityConstraint( - MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_), - VectorXd::Zero(n_v_), {dv_, lambda_c_, lambda_h_, u_}) + MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_ee_), + VectorXd::Zero(n_v_), {dv_, lambda_c_, lambda_h_, u_, lambda_ee_}) .evaluator() .get(); // 2. Holonomic constraint @@ -426,8 +428,8 @@ void OperationalSpaceControl::Build() { } if (with_acceleration_constraints_) { - prog_->AddLinearConstraint(MatrixXd::Identity(n_q_, n_q_), ddq_min_, ddq_max_, - dv_); + prog_->AddLinearConstraint(MatrixXd::Identity(n_q_, n_q_), ddq_min_, + ddq_max_, dv_); } // No joint position constraint in this implementation @@ -470,15 +472,14 @@ void OperationalSpaceControl::Build() { .evaluator() .get(); } - // 3. external force cost - // for (auto& force_tracking_data: *force_tracking_data_vec_){ - // DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); - // lambda_ee_cost_ = - // prog_ - // ->AddQuadraticCost(, VectorXd::Zero(n_h_), lambda_h_) - // .evaluator() - // .get(); - // } + // 3. external force cost + for (auto& force_tracking_data : *force_tracking_data_vec_) { + lambda_ee_cost_ = prog_ + ->AddQuadraticCost(MatrixXd::Zero(n_ee_, n_ee_), + VectorXd::Zero(n_ee_), lambda_ee_) + .evaluator() + .get(); + } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { soft_constraint_cost_ = @@ -665,11 +666,13 @@ VectorXd OperationalSpaceControl::SolveQp( /// M*dv + bias == J_c^T*lambda_c + J_h^T*lambda_h + B*u /// -> M*dv - J_c^T*lambda_c - J_h^T*lambda_h - B*u == - bias /// -> [M, -J_c^T, -J_h^T, -B]*[dv, lambda_c, lambda_h, u]^T = - bias - MatrixXd A_dyn = MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_); + MatrixXd A_dyn = MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_ee_); A_dyn.block(0, 0, n_v_, n_v_) = M; A_dyn.block(0, n_v_, n_v_, n_c_) = -J_c.transpose(); A_dyn.block(0, n_v_ + n_c_, n_v_, n_h_) = -J_h.transpose(); A_dyn.block(0, n_v_ + n_c_ + n_h_, n_v_, n_u_) = -B; + MatrixXd J_ee = force_tracking_data_vec_->at(0)->GetJ(); + A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_ee_) = -J_ee.transpose(); dynamics_constraint_->UpdateCoefficients(A_dyn, -bias); // 2. Holonomic constraint /// JdotV_h + J_h*dv == 0 @@ -766,6 +769,16 @@ VectorXd OperationalSpaceControl::SolveQp( } } + for (auto& force_tracking_data : *force_tracking_data_vec_){ + force_tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, + *context_wo_spr_, t); + const MatrixXd W = force_tracking_data->GetWeight(); + const VectorXd lambda_des = force_tracking_data->GetLambdaDes(); + lambda_ee_cost_->UpdateCoefficients(2 * W, + -2 * W * lambda_des, + lambda_des.transpose() * W * lambda_des); + } + // Add joint limit constraints if (w_joint_limit_ > 0) { VectorXd w_joint_limit = @@ -853,6 +866,7 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); + *lambda_ee_sol_ = result.GetSolution(lambda_ee_); } else { *u_prev_ = 0.99 * *u_sol_ + VectorXd::Random(n_u_); } @@ -1046,12 +1060,14 @@ void OperationalSpaceControl::AssignOscLcmOutput( lcmt_osc_qp_output qp_output; qp_output.solve_time = solve_time_; qp_output.u_dim = n_u_; - qp_output.lambda_c_dim = n_c_; +// qp_output.lambda_c_dim = n_c_; + qp_output.lambda_c_dim = n_ee_; qp_output.lambda_h_dim = n_h_; qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); +// qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ee_sol_); qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); From 88cd52550fe376648e7d4c1440b4a7e80b2f7151 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 10 Nov 2023 12:54:50 -0500 Subject: [PATCH 523/758] adding option for different contact model and linearization, but they don't seem to work yet --- examples/franka/franka_c3_controller.cc | 2 +- .../franka_c3_options_translation.yaml | 10 +- .../franka/systems/c3_trajectory_generator.cc | 42 ++-- .../franka/systems/c3_trajectory_generator.h | 7 +- solvers/c3.h | 2 + solvers/c3_miqp.h | 7 +- solvers/c3_options.h | 5 + solvers/c3_qp.h | 4 +- solvers/lcs_factory.cc | 182 ++++++++++-------- solvers/lcs_factory.h | 7 +- systems/controllers/c3_controller.cc | 10 +- 11 files changed, 168 insertions(+), 110 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index c98c282e73..9874755dae 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -214,7 +214,7 @@ int DoMain(int argc, char* argv[]) { contact_pairs, c3_options); auto c3_trajectory_generator = builder.AddSystem( - plant_plate, &plate_context, c3_options); + plant_plate, c3_options); c3_trajectory_generator->SetPublishEndEffectorOrientation( controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index d32a36a151..68a6376ae9 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -3,7 +3,10 @@ rho: 0.1 rho_scale: 2 num_threads: 6 delta_option: 1 -projection_type: "MIQP" +# options are 'MIQP' or 'QP' +projection_type: 'MIQP' +# options are 'stewart_and_trinkle' or 'anitescu +contact_model: 'stewart_and_trinkle' mu: 0.4 mu_plate: 0.4 @@ -21,8 +24,13 @@ w_G: 0.5 # Penalty on all decision variables, assuming scalar w_U: 1 +# n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions +# size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle +# size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu g_size: 40 u_size: 40 +#g_size: 34 +#u_size: 34 # State Tracking Error, assuming diagonal q_vector: [10, 10, 5000, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 5ad2b6c4a3..4c2445fa83 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -1,13 +1,11 @@ #include "examples/franka/systems/c3_trajectory_generator.h" -#include #include #include "common/find_resource.h" #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" - #include "solvers/c3_output.h" namespace dairlib { @@ -16,20 +14,16 @@ using drake::multibody::ModelInstanceIndex; using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteValues; -using Eigen::VectorXd; using Eigen::MatrixXd; using Eigen::MatrixXf; +using Eigen::VectorXd; using systems::TimestampedVector; namespace systems { C3TrajectoryGenerator::C3TrajectoryGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, C3Options c3_options) - : plant_(plant), - context_(context), - c3_options_(std::move(c3_options)), - N_(c3_options_.N) { + const drake::multibody::MultibodyPlant& plant, C3Options c3_options) + : plant_(plant), c3_options_(std::move(c3_options)), N_(c3_options_.N) { this->set_name("c3_trajectory_generator"); n_q_ = plant_.num_positions(); @@ -41,7 +35,8 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( n_u_ = plant_.num_actuators(); c3_solution_port_ = - this->DeclareAbstractInputPort("c3_solution", drake::Value()) + this->DeclareAbstractInputPort("c3_solution", + drake::Value()) .get_index(); actor_trajectory_port_ = @@ -73,7 +68,8 @@ void C3TrajectoryGenerator::OutputActorTrajectory( MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = c3_solution->x_sol_.topRows(3).cast(); - knots.bottomRows(3) = c3_solution->x_sol_.bottomRows(n_v_).topRows(3).cast(); + knots.bottomRows(3) = + c3_solution->x_sol_.bottomRows(n_v_).topRows(3).cast(); LcmTrajectory::Trajectory end_effector_traj; end_effector_traj.traj_name = "end_effector_traj"; end_effector_traj.datatypes = @@ -87,14 +83,18 @@ void C3TrajectoryGenerator::OutputActorTrajectory( LcmTrajectory::Trajectory end_effector_orientation_traj; // first 3 rows are rpy, last 3 rows are angular velocity MatrixXd orientation_samples = MatrixXd::Zero(6, N_); - orientation_samples.topRows(3) = c3_solution->x_sol_.topRows(6).bottomRows(3).cast(); - orientation_samples.bottomRows(3) = - c3_solution->x_sol_.bottomRows(n_v_).topRows(6).bottomRows(3).cast(); + orientation_samples.topRows(3) = + c3_solution->x_sol_.topRows(6).bottomRows(3).cast(); + orientation_samples.bottomRows(3) = c3_solution->x_sol_.bottomRows(n_v_) + .topRows(6) + .bottomRows(3) + .cast(); end_effector_orientation_traj.traj_name = "end_effector_orientation_target"; end_effector_orientation_traj.datatypes = std::vector(orientation_samples.rows(), "double"); end_effector_orientation_traj.datapoints = orientation_samples; - end_effector_orientation_traj.time_vector = c3_solution->time_vector_.cast(); + end_effector_orientation_traj.time_vector = + c3_solution->time_vector_.cast(); lcm_traj.AddTrajectory(end_effector_orientation_traj.traj_name, end_effector_orientation_traj); } @@ -111,7 +111,8 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( DRAKE_DEMAND(c3_solution->x_sol_.rows() == n_q_ + n_v_); MatrixXd knots = MatrixXd::Zero(6, N_); knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3).cast(); - knots.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); + knots.bottomRows(3) = + c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); LcmTrajectory::Trajectory object_traj; object_traj.traj_name = "object_traj"; object_traj.datatypes = std::vector(knots.rows(), "double"); @@ -124,13 +125,16 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( LcmTrajectory::Trajectory object_orientation_traj; // first 3 rows are rpy, last 3 rows are angular velocity MatrixXd orientation_samples = MatrixXd::Zero(7, N_); - orientation_samples.topRows(4) = c3_solution->x_sol_.middleRows(3 + 3, 4).cast(); - orientation_samples.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + 3 + 3, 3).cast(); + orientation_samples.topRows(4) = + c3_solution->x_sol_.middleRows(3 + 3, 4).cast(); + orientation_samples.bottomRows(3) = + c3_solution->x_sol_.middleRows(n_q_ + 3 + 3, 3).cast(); object_orientation_traj.traj_name = "object_orientation_target"; object_orientation_traj.datatypes = std::vector(orientation_samples.rows(), "double"); object_orientation_traj.datapoints = orientation_samples; - object_orientation_traj.time_vector = c3_solution->time_vector_.cast(); + object_orientation_traj.time_vector = + c3_solution->time_vector_.cast(); lcm_traj.AddTrajectory(object_orientation_traj.traj_name, object_orientation_traj); } diff --git a/examples/franka/systems/c3_trajectory_generator.h b/examples/franka/systems/c3_trajectory_generator.h index 086ac40ff5..589a9bcb6c 100644 --- a/examples/franka/systems/c3_trajectory_generator.h +++ b/examples/franka/systems/c3_trajectory_generator.h @@ -3,16 +3,13 @@ #include #include -#include +#include #include "common/find_resource.h" #include "dairlib/lcmt_saved_traj.hpp" #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "lcm/lcm_trajectory.h" #include "solvers/c3_options.h" -#include "solvers/lcs.h" -#include "solvers/solver_options_io.h" -#include "systems/framework/timestamped_vector.h" #include "drake/systems/framework/leaf_system.h" @@ -24,7 +21,7 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { public: explicit C3TrajectoryGenerator( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, C3Options c3_options); + C3Options c3_options); const drake::systems::InputPort& get_input_port_c3_solution() const { return this->get_input_port(c3_solution_port_); diff --git a/solvers/c3.h b/solvers/c3.h index 079a58f46a..067e28b9e5 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -30,6 +30,8 @@ class C3 { const std::vector& warm_start_u_ = {}, bool warm_start = false); + virtual ~C3() = default; + /// Solve the MPC problem /// @param x0 The initial state of the system /// @param delta A pointer to the copy variable solution diff --git a/solvers/c3_miqp.h b/solvers/c3_miqp.h index ffd24261b9..2457daf19b 100644 --- a/solvers/c3_miqp.h +++ b/solvers/c3_miqp.h @@ -18,8 +18,7 @@ class C3MIQP final : public C3 { const std::vector& R, const std::vector& G, const std::vector& U, - const std::vector& xdesired, - const C3Options& options, + const std::vector& xdesired, const C3Options& options, const std::vector& warm_start_delta = {}, const std::vector& warm_start_binary = {}, const std::vector& warm_start_x = {}, @@ -27,8 +26,7 @@ class C3MIQP final : public C3 { const std::vector& warm_start_u = {}, bool warm_start = false); - ~C3MIQP(){ - } + ~C3MIQP() override = default; /// Virtual projection method Eigen::VectorXd SolveSingleProjection(const Eigen::MatrixXd& U, @@ -41,7 +39,6 @@ class C3MIQP final : public C3 { std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; - private: GRBEnv env_; }; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index b4022adbf5..4035a8aa05 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -10,6 +10,7 @@ struct C3Options { int num_threads = 0; // 0 is dynamic, greater than 0 for a fixed count int delta_option = 1; // different options for delta update std::string projection_type; + std::string contact_model; int N; double w_Q; @@ -53,7 +54,11 @@ struct C3Options { a->Visit(DRAKE_NVP(rho_scale)); a->Visit(DRAKE_NVP(num_threads)); a->Visit(DRAKE_NVP(delta_option)); + a->Visit(DRAKE_NVP(contact_model)); a->Visit(DRAKE_NVP(projection_type)); + if (projection_type == "QP"){ + DRAKE_DEMAND(contact_model == "anitescu"); + } a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(mu_plate)); diff --git a/solvers/c3_qp.h b/solvers/c3_qp.h index 46c88b338b..02d6797f80 100644 --- a/solvers/c3_qp.h +++ b/solvers/c3_qp.h @@ -20,7 +20,7 @@ namespace dairlib { namespace solvers { -class C3QP : public C3 { +class C3QP final : public C3 { public: /// Default constructor for time-varying LCS C3QP(const LCS& LCS, const std::vector& Q, @@ -36,6 +36,8 @@ class C3QP : public C3 { const std::vector& warm_start_u = {}, bool warm_start = false); + ~C3QP() override = default; + /// Virtual projection method Eigen::VectorXd SolveSingleProjection(const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 2bc4c4a853..83ffeb2d67 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -33,15 +33,21 @@ std::pair LCSFactory::LinearizePlantToLCS( const MultibodyPlant& plant_ad, const Context& context_ad, const vector>& contact_geoms, - int num_friction_directions, double mu, double dt, int N) { - int n_q = plant_ad.num_positions(); - int n_v = plant_ad.num_velocities(); + int num_friction_directions, double mu, double dt, int N, + ContactModel contact_model) { + // int n_q = plant_ad.num_positions(); + // int n_v = plant_ad.num_velocities(); int n_x = plant_ad.num_positions() + plant_ad.num_velocities(); int n_u = plant_ad.num_actuators(); int n_contacts = contact_geoms.size(); - AutoDiffVecXd C(plant.num_velocities()); + DRAKE_DEMAND(plant_ad.num_velocities() == plant.num_velocities()); + DRAKE_DEMAND(plant_ad.num_positions() == plant.num_positions()); + int n_v = plant.num_velocities(); + int n_q = plant.num_positions(); + + AutoDiffVecXd C(n_v); plant_ad.CalcBiasTerm(context_ad, &C); VectorXd u_dyn = plant.get_actuation_input_port().Eval(context); @@ -54,7 +60,7 @@ std::pair LCSFactory::LinearizePlantToLCS( drake::multibody::MultibodyForces f_app(plant_ad); plant_ad.CalcForceElementsContribution(context_ad, &f_app); - MatrixX M(plant.num_velocities(), plant.num_velocities()); + MatrixX M(n_v, n_v); plant_ad.CalcMassMatrix(context_ad, &M); // If this ldlt is slow, there are alternate formulations which avoid it @@ -64,14 +70,14 @@ std::pair LCSFactory::LinearizePlantToLCS( VectorXd d_vv = ExtractValue(vdot_no_contact); // Derivatives w.r.t. x and u, AB MatrixXd AB_v = ExtractGradient(vdot_no_contact); - VectorXd x_dvv(plant.num_positions() + plant.num_velocities() + n_u); + VectorXd x_dvv(n_q + n_v + n_u); x_dvv << plant.GetPositions(context), plant.GetVelocities(context), u_dyn; VectorXd x_dvvcomp = AB_v * x_dvv; VectorXd d_v = d_vv - x_dvvcomp; /////////// AutoDiffVecXd x_ad = plant_ad.GetPositionsAndVelocities(context_ad); - AutoDiffVecXd qdot_no_contact(plant.num_positions()); + AutoDiffVecXd qdot_no_contact(n_q); AutoDiffVecXd vel_ad = x_ad.tail(n_v); plant_ad.MapVelocityToQDot(context_ad, vel_ad, &qdot_no_contact); @@ -81,9 +87,9 @@ std::pair LCSFactory::LinearizePlantToLCS( Nqt = plant.MakeVelocityToQDotMap(context); MatrixXd Nq = MatrixXd(Nqt); - //plant_ad.MapQDotToVelocity(context_ad, qdot_no_contact, &vel); + // plant_ad.MapQDotToVelocity(context_ad, qdot_no_contact, &vel); - //std::optional> NqI = std::nullopt; + // std::optional> NqI = std::nullopt; Eigen::SparseMatrix NqI; NqI = plant.MakeQDotToVelocityMap(context); MatrixXd NqInverse = MatrixXd(NqI); @@ -91,13 +97,13 @@ std::pair LCSFactory::LinearizePlantToLCS( /// Contact-related terms /// VectorXd phi(n_contacts); - MatrixXd J_n(n_contacts, plant.num_velocities()); - MatrixXd J_t(2 * n_contacts * num_friction_directions, - plant.num_velocities()); + MatrixXd J_n(n_contacts, n_v); + MatrixXd J_t(2 * n_contacts * num_friction_directions, n_v); for (int i = 0; i < n_contacts; i++) { multibody::GeomGeomCollider collider( - plant, contact_geoms[i]); // deleted num_fricton_directions (check with + plant, + contact_geoms[i]); // deleted num_friction_directions (check with // Michael about changes in geomgeom) auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); @@ -105,26 +111,16 @@ std::pair LCSFactory::LinearizePlantToLCS( J_n.row(i) = J_i.row(0); J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, - plant.num_velocities()) = - J_i.block(1, 0, 2 * num_friction_directions, plant.num_velocities()); + n_v) = J_i.block(1, 0, 2 * num_friction_directions, n_v); } auto M_ldlt = ExtractValue(M).ldlt(); MatrixXd MinvJ_n_T = M_ldlt.solve(J_n.transpose()); MatrixXd MinvJ_t_T = M_ldlt.solve(J_t.transpose()); - // float dt = 0.1; - auto n_contact_vars = - 2 * n_contacts + 2 * n_contacts * num_friction_directions; - MatrixXd A(n_x, n_x); MatrixXd B(n_x, n_u); - MatrixXd D(n_x, n_contact_vars); VectorXd d(n_x); - MatrixXd E(n_contact_vars, n_x); - MatrixXd F(n_contact_vars, n_contact_vars); - MatrixXd H(n_contact_vars, n_u); - VectorXd c(n_contact_vars); MatrixXd AB_v_q = AB_v.block(0, 0, n_v, n_q); MatrixXd AB_v_v = AB_v.block(0, n_q, n_v, n_v); @@ -132,8 +128,6 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd M_double = MatrixXd::Zero(n_v, n_v); plant.CalcMassMatrix(context, &M_double); -// std::cout << "AB_v_u: " << AB_v_u << std::endl; - A.block(0, 0, n_q, n_q) = MatrixXd::Identity(n_q, n_q) + dt * dt * Nq * AB_v_q; A.block(0, n_q, n_q, n_v) = dt * Nq + dt * dt * Nq * AB_v_v; @@ -143,27 +137,9 @@ std::pair LCSFactory::LinearizePlantToLCS( B.block(0, 0, n_q, n_u) = dt * dt * Nq * AB_v_u; B.block(n_q, 0, n_v, n_u) = dt * AB_v_u; - D = MatrixXd::Zero(n_x, n_contact_vars); - D.block(0, 2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions) = - dt * dt * Nq * MinvJ_t_T; - D.block(n_q, 2 * n_contacts, n_v, 2 * n_contacts * num_friction_directions) = - dt * MinvJ_t_T; - - D.block(0, n_contacts, n_q, n_contacts) = dt * dt * Nq * MinvJ_n_T; - - D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; - d.head(n_q) = dt * dt * Nq * d_v; d.tail(n_v) = dt * d_v; - E = MatrixXd::Zero(n_contact_vars, n_x); - E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q + J_n * NqInverse;; - E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = - dt * J_t * AB_v_q; - E.block(n_contacts, n_q, n_contacts, n_v) = dt * J_n + dt * dt * J_n * AB_v_v; - E.block(2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions, n_v) = - J_t + dt * J_t * AB_v_v; - MatrixXd E_t = MatrixXd::Zero(n_contacts, 2 * n_contacts * num_friction_directions); for (int i = 0; i < n_contacts; i++) { @@ -172,38 +148,92 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd::Ones(1, 2 * num_friction_directions); } - F = MatrixXd::Zero(n_contact_vars, n_contact_vars); - F.block(0, n_contacts, n_contacts, n_contacts) = - mu * MatrixXd::Identity(n_contacts, n_contacts); - F.block(0, 2 * n_contacts, n_contacts, - 2 * n_contacts * num_friction_directions) = -E_t; - - F.block(n_contacts, n_contacts, n_contacts, n_contacts) = - dt * dt * J_n * MinvJ_n_T; - F.block(n_contacts, 2 * n_contacts, n_contacts, - 2 * n_contacts * num_friction_directions) = dt * dt * J_n * MinvJ_t_T; - - F.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, - n_contacts) = E_t.transpose(); - - F.block(2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions, - n_contacts) = dt * J_t * MinvJ_n_T; - F.block(2 * n_contacts, 2 * n_contacts, - 2 * n_contacts * num_friction_directions, - 2 * n_contacts * num_friction_directions) = dt * J_t * MinvJ_t_T; - - H = MatrixXd::Zero(n_contact_vars, n_u); - H.block(n_contacts, 0, n_contacts, n_u) = dt * dt * J_n * AB_v_u; - H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = - dt * J_t * AB_v_u; - - c = VectorXd::Zero(n_contact_vars); - // TODO(yangwill): check gap function to make sure it makes sense. Potential source of uncertainty -// std::cout << "phi: " << phi << std::endl; - c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; - - c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = - J_t * dt * d_v - J_n * NqInverse * plant.GetPositions(context); + // MatrixXd D(n_x, n_contact_vars); + // MatrixXd E(n_contact_vars, n_x); + // MatrixXd F(n_contact_vars, n_contact_vars); + // MatrixXd H(n_contact_vars, n_u); + // VectorXd c(n_contact_vars); + int n_contact_vars = 0; + if (contact_model == ContactModel::kStewartAndTrinkle) { + n_contact_vars = 2 * n_contacts + 2 * n_contacts * num_friction_directions; + } else { + n_contact_vars = 2 * n_contacts * num_friction_directions; + } + + MatrixXd D = MatrixXd::Zero(n_x, n_contact_vars); + MatrixXd E = MatrixXd::Zero(n_contact_vars, n_x); + MatrixXd F = MatrixXd::Zero(n_contact_vars, n_contact_vars); + MatrixXd H = MatrixXd::Zero(n_contact_vars, n_u); + VectorXd c = VectorXd::Zero(n_contact_vars); + + if (contact_model == ContactModel::kStewartAndTrinkle) { + D.block(0, 2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions) = + dt * dt * Nq * MinvJ_t_T; + D.block(n_q, 2 * n_contacts, n_v, + 2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; + + D.block(0, n_contacts, n_q, n_contacts) = dt * dt * Nq * MinvJ_n_T; + + D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; + + E.block(n_contacts, 0, n_contacts, n_q) = + dt * dt * J_n * AB_v_q + J_n * NqInverse; + ; + E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = + dt * J_t * AB_v_q; + E.block(n_contacts, n_q, n_contacts, n_v) = + dt * J_n + dt * dt * J_n * AB_v_v; + E.block(2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions, + n_v) = J_t + dt * J_t * AB_v_v; + + F.block(0, n_contacts, n_contacts, n_contacts) = + mu * MatrixXd::Identity(n_contacts, n_contacts); + F.block(0, 2 * n_contacts, n_contacts, + 2 * n_contacts * num_friction_directions) = -E_t; + + F.block(n_contacts, n_contacts, n_contacts, n_contacts) = + dt * dt * J_n * MinvJ_n_T; + F.block(n_contacts, 2 * n_contacts, n_contacts, + 2 * n_contacts * num_friction_directions) = + dt * dt * J_n * MinvJ_t_T; + + F.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, + n_contacts) = E_t.transpose(); + + F.block(2 * n_contacts, n_contacts, + 2 * n_contacts * num_friction_directions, n_contacts) = + dt * J_t * MinvJ_n_T; + F.block(2 * n_contacts, 2 * n_contacts, + 2 * n_contacts * num_friction_directions, + 2 * n_contacts * num_friction_directions) = dt * J_t * MinvJ_t_T; + + H.block(n_contacts, 0, n_contacts, n_u) = dt * dt * J_n * AB_v_u; + H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = + dt * J_t * AB_v_u; + + // TODO(yangwill): check gap function to make sure it makes sense. Potential + // source of uncertainty + // std::cout << "phi: " << phi << std::endl; + c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; + c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = + J_t * dt * d_v - J_n * NqInverse * plant.GetPositions(context); + } else if (contact_model == ContactModel::kAnitescu) { + MatrixXd Nqinv = Nq.completeOrthogonalDecomposition().pseudoInverse(); + // auto M_ldlt = ExtractValue(M).ldlt(); + MatrixXd J_c = E_t.transpose() * J_n + mu * J_t; + + MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); + + E.block(0, 0, n_contacts, n_q) = + dt * J_c * AB_v_q + E_t.transpose() * J_n * Nqinv / dt; + E.block(0, n_q, n_contacts, n_v) = J_c + dt * J_c * AB_v_v; + + F = J_c * MinvJ_c_T; + + H = dt * J_c * AB_v_u; + c = E_t.transpose() * phi / dt + dt * J_c * d_v - + E_t.transpose() * J_n * Nqinv * plant.GetPositions(context) / dt; + } auto Dn = D.squaredNorm(); auto An = A.squaredNorm(); diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index 3afa9b2eaa..c1290ec873 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -7,6 +7,11 @@ namespace dairlib { namespace solvers { +enum class ContactModel { + kStewartAndTrinkle, /// Stewart and Trinkle timestepping contact + kAnitescu /// Anitescu convex contact +}; + class LCSFactory { public: /// Build a time-invariant LCS, linearizing a MultibodyPlant @@ -35,7 +40,7 @@ class LCSFactory { const drake::systems::Context& context_ad, const std::vector>& contact_geoms, - int num_friction_directions, double mu, double dt, int N); + int num_friction_directions, double mu, double dt, int N, ContactModel=ContactModel::kStewartAndTrinkle); /// Create an LCS by fixing some modes from another LCS /// Ignores generated inequalities that correspond to these modes, but diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index d648579036..58f2c93eb7 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -124,10 +124,18 @@ drake::systems::EventStatus C3Controller::ComputePlan( multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u), context_); multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u), context_ad_); + solvers::ContactModel contact_model; + if (c3_options_.contact_model == "stewart_and_trinkle") { + contact_model = solvers::ContactModel::kStewartAndTrinkle; + } else if (c3_options_.contact_model == "anitescu") { + contact_model = solvers::ContactModel::kAnitescu; + } else { + throw std::runtime_error("unknown or unsupported contact model"); + } auto [lcs, scale] = LCSFactory::LinearizePlantToLCS( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, - c3_options_.N); + c3_options_.N, contact_model); DRAKE_DEMAND(Q_.front().rows() == lcs.n_); DRAKE_DEMAND(Q_.front().cols() == lcs.n_); DRAKE_DEMAND(R_.front().rows() == lcs.k_); From 080af9a82522a0bdc76943b72b6b31894ce6fdf1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 Nov 2023 15:54:23 -0500 Subject: [PATCH 524/758] fixing qp and anitescu linearization --- solvers/c3_qp.cc | 8 ++++---- solvers/lcs_factory.cc | 3 ++- systems/controllers/c3_controller.cc | 12 +++++++++--- 3 files changed, 15 insertions(+), 8 deletions(-) diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc index 0c00a2e9de..0e780d00e2 100644 --- a/solvers/c3_qp.cc +++ b/solvers/c3_qp.cc @@ -74,11 +74,11 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, VectorXd cost_linear = -delta_c.transpose() * New_U; -// prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}, 1); - prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}); + // prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}, 1); + prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}, 1); -// prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); - prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_); + // prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); + prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); solver_options.SetOption(OsqpSolver::id(), "max_iter", 250); solver_options.SetOption(OsqpSolver::id(), "verbose", 0); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 83ffeb2d67..4781921a55 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -223,7 +223,8 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd J_c = E_t.transpose() * J_n + mu * J_t; MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); - + D.block(0, 0, n_q, n_contacts) = dt * Nq * MinvJ_c_T; + D.block(n_q, 0, n_v, n_contacts) = MinvJ_c_T; E.block(0, 0, n_contacts, n_q) = dt * J_c * AB_v_q + E_t.transpose() * J_n * Nqinv / dt; E.block(0, n_q, n_contacts, n_v) = J_c + dt * J_c * AB_v_v; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 58f2c93eb7..53036282aa 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -54,9 +54,15 @@ C3Controller::C3Controller( n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_x_ = n_q_ + n_v_; - n_lambda_ = - 2 * c3_options_.num_contacts + - 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + if (c3_options_.contact_model == "stewart_and_trinkle") { + n_lambda_ = + 2 * c3_options_.num_contacts + + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + } else if (c3_options_.contact_model == "anitescu") { + n_lambda_ = + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + } + n_u_ = plant_.num_actuators(); // Q_.back() = 100 * c3_options_.Q; From fc2f6ab610fd1c44c82a35ea0f8adf2dd813816f Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 10 Nov 2023 15:56:35 -0500 Subject: [PATCH 525/758] resetting target to neutral position if c3 finds totally infeasible --- examples/franka/franka_c3_controller.cc | 11 +++++++--- .../franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../franka/systems/end_effector_trajectory.cc | 21 +++++++++++-------- .../franka/systems/plate_balancing_target.cc | 1 + 5 files changed, 23 insertions(+), 14 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 9874755dae..bd44ec0452 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -176,11 +176,15 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.c3_force_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); + // auto c3_output_publisher = + // builder.AddSystem(LcmPublisherSystem::Make( + // lcm_channel_params.c3_debug_output_channel, &lcm, + // TriggerTypeSet({TriggerType::kPeriodic}), + // 1 / controller_params.target_frequency)); auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_debug_output_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), - 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kForced}))); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); @@ -264,7 +268,8 @@ int DoMain(int argc, char* argv[]) { // *controller, &loop.get_diagram_mutable_context()); // controller->get_input_port_target().FixValue(&controller_context, x_des); LcmHandleSubscriptionsUntil( - &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); + &lcm, [&]() { + return tray_state_sub->GetInternalMessageCount() > 1; }); loop.Simulate(); return 0; } diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index a84ae8a867..b67fea7764 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -7,7 +7,7 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate -tool_attachment_frame: [0, 0, 0.15] +tool_attachment_frame: [0, 0, 0.107] #franka_model: examples/franka/urdf/franka_no_collision.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 66238569b3..36c9eaa36a 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -19,5 +19,5 @@ q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, 0.05, 0.430] +q_init_plate: [1, 0, 0, 0, 0.56, -0.05, 0.430] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 64899bd2f1..2a63d7c479 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -55,11 +55,12 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( } void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( - const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale){ - neutral_pose_ = neutral_pose; - x_scale_ = x_scale; - y_scale_ = y_scale; - z_scale_ = z_scale; + const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, + double z_scale) { + neutral_pose_ = neutral_pose; + x_scale_ = x_scale; + y_scale_ = y_scale; + z_scale_ = z_scale; } PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( @@ -96,10 +97,12 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (radio_out->channel[14]) { *casted_traj = GeneratePose(context); } else { - *casted_traj = *(PiecewisePolynomial*)dynamic_cast< - const PiecewisePolynomial*>(&trajectory_input); - // *casted_traj = GenerateCircle(context); - // *casted_traj = GenerateLine(context); + if (trajectory_input.value(0).isZero()) { + *casted_traj = GeneratePose(context); + } else { + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } } } diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 7715be6c64..7780f87886 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -56,6 +56,7 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( this->EvalInputValue(context, radio_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = neutral_pose_; + tray_position[2] += 0.02; tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; From c202236b999b8b893101b086d6fcc805011d78c9 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 13 Nov 2023 11:03:41 -0500 Subject: [PATCH 526/758] updating end effector urdf from physical model --- examples/franka/urdf/plate_end_effector.urdf | 10 +++---- .../urdf/plate_end_effector_translation.urdf | 28 ++++++------------- 2 files changed, 13 insertions(+), 25 deletions(-) diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index dcc3cee42b..517a98f274 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -3,14 +3,14 @@ - - - + + + - + - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index bb1fcdbce4..a72c12ebdc 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -6,45 +6,33 @@ - - - + + + - + - + - - - - - - - - - - - - - + - + - + From 12b7aff35fac701156f9f8e4aee3e46b7e2358b7 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 13 Nov 2023 12:57:53 -0500 Subject: [PATCH 527/758] tracking forces, updating urdfs, removing dependence on lcmtraj files --- examples/franka/franka_c3_controller.cc | 17 +-- examples/franka/franka_osc_controller.cc | 25 ++-- examples/franka/franka_visualizer.cc | 4 +- .../franka_c3_controller_params.yaml | 2 +- .../franka_c3_options_translation.yaml | 22 +-- .../franka_osc_controller_params.yaml | 6 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../franka/saved_trajectories/franka_defaults | Bin 479 -> 615 bytes .../franka/systems/c3_trajectory_generator.cc | 41 ++---- .../franka/systems/c3_trajectory_generator.h | 9 -- .../franka/systems/end_effector_trajectory.cc | 4 +- .../franka/systems/end_effector_trajectory.h | 2 +- examples/franka/urdf/plate_end_effector.urdf | 6 +- .../urdf/plate_end_effector_translation.urdf | 8 +- examples/franka/urdf/tray.sdf | 8 +- systems/controllers/c3_controller.cc | 10 +- .../osc/external_force_tracking_data.cc | 6 +- .../osc/external_force_tracking_data.h | 13 +- .../osc/operational_space_control.cc | 22 +-- .../lcm_trajectory_systems.cc | 129 +++++++++--------- .../lcm_trajectory_systems.h | 31 +---- 21 files changed, 163 insertions(+), 204 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index bd44ec0452..153d4169a5 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -171,16 +171,11 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.c3_object_channel, &lcm, TriggerTypeSet({TriggerType::kPeriodic}), 1 / controller_params.target_frequency)); - auto force_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_force_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), - 1 / controller_params.target_frequency)); - // auto c3_output_publisher = - // builder.AddSystem(LcmPublisherSystem::Make( - // lcm_channel_params.c3_debug_output_channel, &lcm, - // TriggerTypeSet({TriggerType::kPeriodic}), - // 1 / controller_params.target_frequency)); +// auto force_trajectory_sender = builder.AddSystem( +// LcmPublisherSystem::Make( +// lcm_channel_params.c3_force_channel, &lcm, +// TriggerTypeSet({TriggerType::kPeriodic}), +// 1 / controller_params.target_frequency)); auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_debug_output_channel, &lcm, @@ -241,8 +236,6 @@ int DoMain(int argc, char* argv[]) { actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_force_trajectory(), - force_trajectory_sender->get_input_port()); builder.Connect(controller->get_output_port_c3_solution(), c3_output_sender->get_input_port_c3_solution()); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index dce3efbe4f..e67d8aae1c 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -111,22 +111,14 @@ int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - auto lcm_traj = - LcmTrajectory("examples/franka/saved_trajectories/franka_defaults"); - auto orientation_traj = LcmTrajectory::Trajectory(); - orientation_traj.datapoints = MatrixXd::Zero(4, 2); - orientation_traj.time_vector = Eigen::Vector2d(0.0, 1.0); - orientation_traj.traj_name = "end_effector_orientation_target"; - orientation_traj.datatypes = std::vector(2, "orientation"); - lcm_traj.AddTrajectory(orientation_traj.traj_name, orientation_traj); - // lcm_traj.WriteToFile("examples/franka/saved_trajectories/franka_defaults"); - auto state_receiver = builder.AddSystem(plant); auto end_effector_trajectory_sub = builder.AddSystem( LcmSubscriberSystem::Make( lcm_channel_params.c3_actor_channel, &lcm)); - auto end_effector_receiver = - builder.AddSystem("end_effector_traj"); + auto end_effector_position_receiver = + builder.AddSystem("end_effector_position_target"); + auto end_effector_force_receiver = + builder.AddSystem("end_effector_force_target"); auto end_effector_orientation_receiver = builder.AddSystem( "end_effector_orientation_target"); @@ -249,11 +241,13 @@ int DoMain(int argc, char* argv[]) { builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); builder.Connect(end_effector_trajectory_sub->get_output_port(), - end_effector_receiver->get_input_port_trajectory()); + end_effector_position_receiver->get_input_port_trajectory()); + builder.Connect(end_effector_trajectory_sub->get_output_port(), + end_effector_force_receiver->get_input_port_trajectory()); builder.Connect( end_effector_trajectory_sub->get_output_port(), end_effector_orientation_receiver->get_input_port_trajectory()); - builder.Connect(end_effector_receiver->get_output_port(0), + builder.Connect(end_effector_position_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); builder.Connect( end_effector_orientation_receiver->get_output_port(0), @@ -263,6 +257,9 @@ int DoMain(int argc, char* argv[]) { builder.Connect( end_effector_orientation_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_orientation_target")); + builder.Connect( + end_effector_force_receiver->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_force")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 019eec3882..d8cde9bd04 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -153,7 +153,7 @@ int do_main(int argc, char* argv[]) { &builder, scene_graph, meshcat, std::move(params)); auto trajectory_drawer_actor = builder.AddSystem(meshcat, - "end_effector_traj"); + "end_effector_position_target"); auto trajectory_drawer_object = builder.AddSystem(meshcat, "object_traj"); auto object_pose_drawer = @@ -162,7 +162,7 @@ int do_main(int argc, char* argv[]) { "object_orientation_target"); auto end_effector_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.end_effector_model), "end_effector_traj", + meshcat, FindResourceOrThrow(sim_params.end_effector_model), "end_effector_position_target", "end_effector_orientation_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index b67fea7764..2970b36c97 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -15,6 +15,6 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 5 +target_frequency: 10 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 68a6376ae9..bc37cbba8a 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -4,13 +4,13 @@ rho_scale: 2 num_threads: 6 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'MIQP' +projection_type: 'QP' # options are 'stewart_and_trinkle' or 'anitescu -contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' mu: 0.4 mu_plate: 0.4 -dt: 0.1 +dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 @@ -27,19 +27,23 @@ w_U: 1 # n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions # size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle # size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu -g_size: 40 -u_size: 40 -#g_size: 34 -#u_size: 34 +#g_size: 40 +#u_size: 40 +g_size: 34 +u_size: 34 # State Tracking Error, assuming diagonal q_vector: [10, 10, 5000, 0, 0, 0, 0, 10000, 10000, 10000, 0, 0, 0, 0, 0, 0, 1, 1, 1] # Penalty on all decision variables +#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables +#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 1abef96206..80d5762481 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -55,9 +55,9 @@ EndEffectorRotW: 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 200, 0, 0, - 0, 200, 0, - 0, 0, 200] + [ 400, 0, 0, + 0, 400, 0, + 0, 0, 400] EndEffectorRotKd: [ 10, 0, 0, 0, 10, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 36c9eaa36a..796d96a4c7 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -19,5 +19,5 @@ q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, -0.05, 0.430] +q_init_plate: [1, 0, 0, 0, 0.56, -0.00, 0.430] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults index 92e6539977d88ce766f84b7ad237e339cfe8a50e..cbd50d77127b80a7170228019eea72c136f4ead5 100644 GIT binary patch delta 92 zcmcc5{G4Ti0wc>t#d1brsnoob_|&wt)Z~)5I|WI6@@3S UU^JHlieS+bUy@jqo?5~H06-iaI{*Lx delta 19 acmaFPa-VsE0weQA#d5}pDgu**n9Kn`*adF@ diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 4c2445fa83..2d3ba2f140 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -51,12 +51,6 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( dairlib::lcmt_timestamped_saved_traj(), &C3TrajectoryGenerator::OutputObjectTrajectory) .get_index(); - force_trajectory_port_ = - this->DeclareAbstractOutputPort( - "c3_force_trajectory_output", - dairlib::lcmt_timestamped_saved_traj(), - &C3TrajectoryGenerator::OutputForceTrajectory) - .get_index(); } void C3TrajectoryGenerator::OutputActorTrajectory( @@ -71,13 +65,23 @@ void C3TrajectoryGenerator::OutputActorTrajectory( knots.bottomRows(3) = c3_solution->x_sol_.bottomRows(n_v_).topRows(3).cast(); LcmTrajectory::Trajectory end_effector_traj; - end_effector_traj.traj_name = "end_effector_traj"; + end_effector_traj.traj_name = "end_effector_position_target"; end_effector_traj.datatypes = std::vector(knots.rows(), "double"); end_effector_traj.datapoints = knots; end_effector_traj.time_vector = c3_solution->time_vector_.cast(); - LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_traj"}, - "end_effector_traj", "end_effector_traj", false); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_position_target"}, + "end_effector_position_target", + "end_effector_position_target", false); + + MatrixXd force_samples = c3_solution->u_sol_.cast(); + LcmTrajectory::Trajectory force_traj; + force_traj.traj_name = "end_effector_force_target"; + force_traj.datatypes = + std::vector(force_samples.rows(), "double"); + force_traj.datapoints = force_samples; + force_traj.time_vector = c3_solution->time_vector_.cast(); + lcm_traj.AddTrajectory(force_traj.traj_name, force_traj); if (publish_end_effector_orientation_) { LcmTrajectory::Trajectory end_effector_orientation_traj; @@ -143,24 +147,5 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( output_traj->utime = context.get_time() * 1e6; } -void C3TrajectoryGenerator::OutputForceTrajectory( - const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const { - const auto& c3_solution = - this->EvalInputValue(context, c3_solution_port_); - DRAKE_DEMAND(c3_solution->u_sol_.rows() == n_u_); - MatrixXd knots = c3_solution->u_sol_.cast(); - LcmTrajectory::Trajectory force_traj; - force_traj.traj_name = "force_traj"; - force_traj.datatypes = std::vector(knots.rows(), "double"); - force_traj.datapoints = knots; - force_traj.time_vector = c3_solution->time_vector_.cast(); - LcmTrajectory lcm_traj({force_traj}, {"force_traj"}, "force_traj", - "force_traj", false); - - output_traj->saved_traj = lcm_traj.GenerateLcmObject(); - output_traj->utime = context.get_time() * 1e6; -} - } // namespace systems } // namespace dairlib diff --git a/examples/franka/systems/c3_trajectory_generator.h b/examples/franka/systems/c3_trajectory_generator.h index 589a9bcb6c..560f68bb25 100644 --- a/examples/franka/systems/c3_trajectory_generator.h +++ b/examples/franka/systems/c3_trajectory_generator.h @@ -35,10 +35,6 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const { return this->get_output_port(object_trajectory_port_); } - const drake::systems::OutputPort& get_output_port_force_trajectory() - const { - return this->get_output_port(force_trajectory_port_); - } void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { publish_end_effector_orientation_ = publish_end_effector_orientation; @@ -53,14 +49,9 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const; - void OutputForceTrajectory( - const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const; - drake::systems::InputPortIndex c3_solution_port_; drake::systems::OutputPortIndex actor_trajectory_port_; drake::systems::OutputPortIndex object_trajectory_port_; - drake::systems::OutputPortIndex force_trajectory_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 2a63d7c479..02b1de74cf 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -48,7 +48,7 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); - PiecewisePolynomial empty_pp_traj(VectorXd(0)); + PiecewisePolynomial empty_pp_traj(neutral_pose_); Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, &EndEffectorTrajectoryGenerator::CalcTraj); @@ -98,7 +98,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( *casted_traj = GeneratePose(context); } else { if (trajectory_input.value(0).isZero()) { - *casted_traj = GeneratePose(context); +// *casted_traj = GeneratePose(context); } else { *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index f35dce87d0..3c55ddafca 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -47,7 +47,7 @@ class EndEffectorTrajectoryGenerator drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; - Eigen::Vector3d neutral_pose_; + Eigen::Vector3d neutral_pose_ = {0.55, 0, 0.40}; double x_scale_; double y_scale_; double z_scale_; diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 517a98f274..1bb32b3105 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -14,15 +14,15 @@ - + - + - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index a72c12ebdc..29a1b227eb 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -6,9 +6,9 @@ - + - + @@ -26,13 +26,13 @@ - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index d89a58d2c6..908c8a8e21 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -4,16 +4,16 @@ 0 0 0 0 0 0 - 0.5 + 0.97 - 0.0065454 + 0.012698 0 0 - 0.0065454 + 0.012698 0 - 0.013064 + 0.025345 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 53036282aa..a9891fa3ec 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -182,11 +182,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, -5, 5, 2); } - for (int i : vector({2})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_u_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, 10, 20, 2); - } +// for (int i : vector({2})) { +// Eigen::RowVectorXd A = VectorXd::Zero(n_u_); +// A(i) = 1.0; +// c3_->AddLinearConstraint(A, 10, 20, 2); +// } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); delta_ = delta; w_ = w; diff --git a/systems/controllers/osc/external_force_tracking_data.cc b/systems/controllers/osc/external_force_tracking_data.cc index 34bd93f6cd..51eae3b09e 100644 --- a/systems/controllers/osc/external_force_tracking_data.cc +++ b/systems/controllers/osc/external_force_tracking_data.cc @@ -35,7 +35,11 @@ void ExternalForceTrackingData::Update( const Eigen::VectorXd& x_w_spr, const drake::systems::Context& context_w_spr, const Eigen::VectorXd& x_wo_spr, - const drake::systems::Context& context_wo_spr, double t) { + const drake::systems::Context& context_wo_spr, + const drake::trajectories::Trajectory& traj, + double t) { + DRAKE_DEMAND(traj.rows() == 3); + lambda_des_ = -traj.value(t); J_ = MatrixXd::Zero(3, plant_wo_spr_.num_velocities()); plant_wo_spr_.CalcJacobianTranslationalVelocity( context_wo_spr, JacobianWrtVariable::kV, *body_frame_wo_spr_, pt_on_body_, diff --git a/systems/controllers/osc/external_force_tracking_data.h b/systems/controllers/osc/external_force_tracking_data.h index 623d4deb4e..196943457c 100644 --- a/systems/controllers/osc/external_force_tracking_data.h +++ b/systems/controllers/osc/external_force_tracking_data.h @@ -7,7 +7,6 @@ namespace dairlib { namespace systems { namespace controllers { - /// ExternalForceTrackingData /// Force tracking objective. Used to track desired external forces. Requires /// contact points on the MultibodyPlant where contact forces enter the dynamics @@ -33,16 +32,16 @@ class ExternalForceTrackingData { return plant_wo_spr_; }; void Update(const Eigen::VectorXd& x_w_spr, - const drake::systems::Context& context_w_spr, - const Eigen::VectorXd& x_wo_spr, - const drake::systems::Context& context_wo_spr, - double t); + const drake::systems::Context& context_w_spr, + const Eigen::VectorXd& x_wo_spr, + const drake::systems::Context& context_wo_spr, + const drake::trajectories::Trajectory& traj, + double t); + protected: private: std::string name_; - - const drake::multibody::MultibodyPlant& plant_w_spr_; const drake::multibody::MultibodyPlant& plant_wo_spr_; // World frames diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 3790a1fd26..80b70a22cd 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -769,14 +769,20 @@ VectorXd OperationalSpaceControl::SolveQp( } } - for (auto& force_tracking_data : *force_tracking_data_vec_){ + for (auto& force_tracking_data : *force_tracking_data_vec_) { + int port_index = + traj_name_to_port_index_map_.at(force_tracking_data->GetName()); + const drake::AbstractValue* input_traj = + this->EvalAbstractInput(context, port_index); + DRAKE_DEMAND(input_traj != nullptr); + const auto& traj = + input_traj->get_value>(); force_tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, - *context_wo_spr_, t); + *context_wo_spr_, traj, t); const MatrixXd W = force_tracking_data->GetWeight(); - const VectorXd lambda_des = force_tracking_data->GetLambdaDes(); - lambda_ee_cost_->UpdateCoefficients(2 * W, - -2 * W * lambda_des, - lambda_des.transpose() * W * lambda_des); + const VectorXd lambda_des = force_tracking_data->GetLambdaDes(); + lambda_ee_cost_->UpdateCoefficients( + 2 * W, -2 * W * lambda_des, lambda_des.transpose() * W * lambda_des); } // Add joint limit constraints @@ -1060,13 +1066,13 @@ void OperationalSpaceControl::AssignOscLcmOutput( lcmt_osc_qp_output qp_output; qp_output.solve_time = solve_time_; qp_output.u_dim = n_u_; -// qp_output.lambda_c_dim = n_c_; + // qp_output.lambda_c_dim = n_c_; qp_output.lambda_c_dim = n_ee_; qp_output.lambda_h_dim = n_h_; qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); -// qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); + // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ee_sol_); qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 19fee85d89..4d239e11fb 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -19,6 +19,7 @@ using drake::trajectories::PiecewiseQuaternionSlerp; using drake::trajectories::Trajectory; using Eigen::MatrixXd; using Eigen::Quaterniond; +using Eigen::Vector3d; using Eigen::VectorXd; LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) @@ -36,32 +37,33 @@ LcmTrajectoryReceiver::LcmTrajectoryReceiver(std::string trajectory_name) this->DeclareAbstractOutputPort(trajectory_name_, traj_inst, &LcmTrajectoryReceiver::OutputTrajectory) .get_index(); - lcm_traj_ = - LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); } void LcmTrajectoryReceiver::OutputTrajectory( const drake::systems::Context& context, Trajectory* traj) const { + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); if (this->EvalInputValue( context, trajectory_input_port_) ->utime > 1e-3) { - const auto& lcm_traj = + const auto& lcmt_traj = this->EvalInputValue( context, trajectory_input_port_); - lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); - } - const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); - auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - if (trajectory_block.datapoints.rows() == 3) { - *casted_traj = PiecewisePolynomial::FirstOrderHold( - trajectory_block.time_vector, trajectory_block.datapoints); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); + + if (trajectory_block.datapoints.rows() == 3) { + *casted_traj = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); + } else { + *casted_traj = PiecewisePolynomial::CubicHermite( + trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), + trajectory_block.datapoints.bottomRows(3)); + } } else { - *casted_traj = PiecewisePolynomial::CubicHermite( - trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), - trajectory_block.datapoints.bottomRows(3)); + *casted_traj = PiecewisePolynomial(Vector3d::Zero()); } } @@ -82,57 +84,57 @@ LcmOrientationTrajectoryReceiver::LcmOrientationTrajectoryReceiver( trajectory_name_, traj_inst, &LcmOrientationTrajectoryReceiver::OutputTrajectory) .get_index(); - lcm_traj_ = - LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); - lcm_traj_.GetTrajectory(trajectory_name_); } void LcmOrientationTrajectoryReceiver::OutputTrajectory( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { + auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< + PiecewiseQuaternionSlerp*>(traj); if (this->EvalInputValue( context, trajectory_input_port_) ->utime > 1e-3) { - const auto& lcm_traj = + const auto& lcmt_traj = this->EvalInputValue( context, trajectory_input_port_); - lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); try { - lcm_traj_.GetTrajectory(trajectory_name_); + lcm_traj.GetTrajectory(trajectory_name_); } catch (std::exception& e) { std::cerr << "Make sure the planner is sending orientation" << std::endl; throw std::out_of_range(""); } + const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); + + std::vector> quaternion_datapoints; + for (int i = 0; i < trajectory_block.datapoints.cols(); ++i) { + quaternion_datapoints.push_back( + drake::math::RollPitchYaw(trajectory_block.datapoints.col(i)) + .ToQuaternion()); + } + *casted_traj = PiecewiseQuaternionSlerp( + CopyVectorXdToStdVector(trajectory_block.time_vector), + quaternion_datapoints); + } else { + *casted_traj = drake::trajectories::PiecewiseQuaternionSlerp( + {0, 1}, + {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); } - const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); - auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< - PiecewiseQuaternionSlerp*>(traj); - std::vector> quaternion_datapoints; - for (int i = 0; i < trajectory_block.datapoints.cols(); ++i) { - quaternion_datapoints.push_back( - drake::math::RollPitchYaw(trajectory_block.datapoints.col(i)) - .ToQuaternion()); - } - *casted_traj = PiecewiseQuaternionSlerp( - CopyVectorXdToStdVector(trajectory_block.time_vector), - quaternion_datapoints); } LcmTrajectoryDrawer::LcmTrajectoryDrawer( const std::shared_ptr& meshcat, - std::string trajectory_name, const std::string& default_trajectory_path) - : meshcat_(meshcat), - trajectory_name_(std::move(trajectory_name)), - default_trajectory_path_(default_trajectory_path) { - this->set_name(trajectory_name); + std::string trajectory_name) + : meshcat_(meshcat), trajectory_name_(std::move(trajectory_name)) { + this->set_name(trajectory_name_); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", drake::Value{}) .get_index(); - lcm_traj_ = - LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); + // lcm_traj_ = + // LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); DeclarePerStepDiscreteUpdateEvent(&LcmTrajectoryDrawer::DrawTrajectory); } @@ -141,13 +143,14 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( DiscreteValues* discrete_state) const { if (this->EvalInputValue( context, trajectory_input_port_) - ->utime > 1e-3) { - const auto& lcm_traj = - this->EvalInputValue( - context, trajectory_input_port_); - lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); } - const auto trajectory_block = lcm_traj_.GetTrajectory(trajectory_name_); + const auto& lcmt_traj = + this->EvalInputValue( + context, trajectory_input_port_); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); MatrixXd line_points = MatrixXd::Zero(3, N_); VectorXd breaks = VectorXd::LinSpaced(N_, trajectory_block.time_vector[0], @@ -170,7 +173,6 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( DRAKE_DEMAND(line_points.rows() == 3); meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, rgba_); - return drake::systems::EventStatus::Succeeded(); } @@ -178,13 +180,11 @@ LcmPoseDrawer::LcmPoseDrawer( const std::shared_ptr& meshcat, const std::string& model_file, const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, int num_poses, - const std::string& default_trajectory_path) + const std::string& orientation_trajectory_name, int num_poses) : meshcat_(meshcat), - translation_trajectory_name_(std::move(translation_trajectory_name)), - orientation_trajectory_name_(std::move(orientation_trajectory_name)), - N_(num_poses), - default_trajectory_path_(default_trajectory_path) { + translation_trajectory_name_(translation_trajectory_name), + orientation_trajectory_name_(orientation_trajectory_name), + N_(num_poses) { this->set_name("/poses/" + model_file); multipose_visualizer_ = std::make_unique( @@ -195,8 +195,6 @@ LcmPoseDrawer::LcmPoseDrawer( drake::Value{}) .get_index(); - lcm_traj_ = - LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); DeclarePerStepDiscreteUpdateEvent(&LcmPoseDrawer::DrawTrajectory); } @@ -205,18 +203,17 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( DiscreteValues* discrete_state) const { if (this->EvalInputValue( context, trajectory_input_port_) - ->utime > 1e-3) { - const auto& lcm_traj = - this->EvalInputValue( - context, trajectory_input_port_); - lcm_traj_ = LcmTrajectory(lcm_traj->saved_traj); - } else { + ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } + const auto& lcmt_traj = + this->EvalInputValue( + context, trajectory_input_port_); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); MatrixXd object_poses = MatrixXd::Zero(7, N_); - const auto lcm_translation_traj = - lcm_traj_.GetTrajectory(translation_trajectory_name_); + const auto& lcm_translation_traj = + lcm_traj.GetTrajectory(translation_trajectory_name_); auto translation_trajectory = PiecewisePolynomial::CubicHermite( lcm_translation_traj.time_vector, lcm_translation_traj.datapoints.topRows(3), @@ -224,9 +221,9 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( auto orientation_trajectory = PiecewiseQuaternionSlerp( {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); - if (lcm_traj_.HasTrajectory(orientation_trajectory_name_)) { - const auto lcm_orientation_traj = - lcm_traj_.GetTrajectory(orientation_trajectory_name_); + if (lcm_traj.HasTrajectory(orientation_trajectory_name_)) { + const auto& lcm_orientation_traj = + lcm_traj.GetTrajectory(orientation_trajectory_name_); std::vector> quaternion_datapoints; for (int i = 0; i < lcm_orientation_traj.datapoints.cols(); ++i) { quaternion_datapoints.push_back( diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index ac579c0152..c050f22e16 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -37,10 +37,6 @@ class LcmTrajectoryReceiver : public drake::systems::LeafSystem { drake::systems::InputPortIndex trajectory_input_port_; drake::systems::OutputPortIndex trajectory_output_port_; const std::string trajectory_name_; - - mutable LcmTrajectory lcm_traj_; - std::string default_trajectory_path_ = - "examples/franka/saved_trajectories/franka_defaults"; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, @@ -64,21 +60,14 @@ class LcmOrientationTrajectoryReceiver drake::systems::InputPortIndex trajectory_input_port_; drake::systems::OutputPortIndex trajectory_output_port_; const std::string trajectory_name_; - - mutable LcmTrajectory lcm_traj_; - std::string default_trajectory_path_ = - "examples/franka/saved_trajectories/franka_defaults"; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, /// and draws it through meshcat. class LcmTrajectoryDrawer : public drake::systems::LeafSystem { public: - explicit LcmTrajectoryDrawer( - const std::shared_ptr&, - std::string trajectory_name, - const std::string& default_trajectory_path = - "examples/franka/saved_trajectories/franka_defaults"); + explicit LcmTrajectoryDrawer(const std::shared_ptr&, + std::string trajectory_name); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_input_port_); @@ -102,8 +91,6 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { drake::systems::InputPortIndex trajectory_input_port_; std::shared_ptr meshcat_; const std::string trajectory_name_; - mutable LcmTrajectory lcm_traj_; - std::string default_trajectory_path_; drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); int N_ = 5; }; @@ -112,13 +99,11 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { /// and draws the object pose through meshcat. class LcmPoseDrawer : public drake::systems::LeafSystem { public: - explicit LcmPoseDrawer( - const std::shared_ptr&, - const std::string& model_file, - const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, int num_poses = 5, - const std::string& default_trajectory_path = - "examples/franka/saved_trajectories/franka_defaults"); + explicit LcmPoseDrawer(const std::shared_ptr&, + const std::string& model_file, + const std::string& translation_trajectory_name, + const std::string& orientation_trajectory_name, + int num_poses = 5); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_input_port_); @@ -136,9 +121,7 @@ class LcmPoseDrawer : public drake::systems::LeafSystem { std::shared_ptr meshcat_; const std::string translation_trajectory_name_; const std::string orientation_trajectory_name_; - mutable LcmTrajectory lcm_traj_; std::unique_ptr multipose_visualizer_; - std::string default_trajectory_path_; const int N_; }; From d4e09432e5961f4d8980dff7a4b0b6008ffc9999 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 Nov 2023 14:33:05 -0500 Subject: [PATCH 528/758] finalizing end effector force tracking and visualizing object orientation --- examples/franka/franka_osc_controller.cc | 28 +++++--- examples/franka/franka_visualizer.cc | 4 +- .../franka_c3_controller_params.yaml | 2 +- .../franka_c3_options_translation.yaml | 28 ++++---- .../franka_osc_controller_params.yaml | 6 +- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/systems/BUILD.bazel | 14 ++++ .../franka/systems/c3_trajectory_generator.cc | 38 +++++----- .../systems/end_effector_force_trajectory.cc | 72 +++++++++++++++++++ .../systems/end_effector_force_trajectory.h | 47 ++++++++++++ .../franka/systems/end_effector_trajectory.cc | 3 - .../franka/systems/plate_balancing_target.cc | 2 +- systems/controllers/c3_controller.cc | 10 +-- .../lcm_trajectory_systems.cc | 6 +- 14 files changed, 199 insertions(+), 63 deletions(-) create mode 100644 examples/franka/systems/end_effector_force_trajectory.cc create mode 100644 examples/franka/systems/end_effector_force_trajectory.h diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index e67d8aae1c..73b7bf2b2c 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -6,17 +6,18 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_osc_controller_params.h" +#include "examples/franka/systems/end_effector_force_trajectory.h" #include "examples/franka/systems/end_effector_orientation.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" +#include "systems/controllers/osc/external_force_tracking_data.h" #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" -#include "systems/controllers/osc/external_force_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -46,11 +47,11 @@ using Eigen::VectorXd; using multibody::MakeNameToPositionsMap; using multibody::MakeNameToVelocitiesMap; +using systems::controllers::ExternalForceTrackingData; using systems::controllers::JointSpaceTrackingData; using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -using systems::controllers::ExternalForceTrackingData; DEFINE_string(osqp_settings, "examples/Cassie/osc_run/osc_running_qp_settings.yaml", @@ -116,9 +117,11 @@ int DoMain(int argc, char* argv[]) { LcmSubscriberSystem::Make( lcm_channel_params.c3_actor_channel, &lcm)); auto end_effector_position_receiver = - builder.AddSystem("end_effector_position_target"); + builder.AddSystem( + "end_effector_position_target"); auto end_effector_force_receiver = - builder.AddSystem("end_effector_force_target"); + builder.AddSystem( + "end_effector_force_target"); auto end_effector_orientation_receiver = builder.AddSystem( "end_effector_orientation_target"); @@ -148,6 +151,9 @@ int DoMain(int argc, char* argv[]) { plant_context.get()); end_effector_orientation_trajectory->SetTrackOrientation( controller_params.track_end_effector_orientation); + auto end_effector_force_trajectory = + builder.AddSystem( + plant, plant_context.get()); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); @@ -180,8 +186,7 @@ int DoMain(int argc, char* argv[]) { auto end_effector_force_tracking_data = std::make_unique( "end_effector_force", controller_params.W_ee_lambda, plant, plant, - controller_params.end_effector_name, Vector3d::Zero() - ); + controller_params.end_effector_name, Vector3d::Zero()); auto end_effector_orientation_tracking_data = std::make_unique( @@ -230,6 +235,10 @@ int DoMain(int argc, char* argv[]) { end_effector_orientation_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_orientation_trajectory->get_input_port_radio()); + builder.Connect(state_receiver->get_output_port(0), + end_effector_force_trajectory->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_force_trajectory->get_input_port_radio()); builder.Connect(franka_command_sender->get_output_port(), franka_command_pub->get_input_port()); builder.Connect(osc_command_sender->get_output_port(), @@ -257,9 +266,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect( end_effector_orientation_trajectory->get_output_port(0), osc->get_input_port_tracking_data("end_effector_orientation_target")); - builder.Connect( - end_effector_force_receiver->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_force")); + builder.Connect(end_effector_force_receiver->get_output_port(0), + end_effector_force_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_force_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_force")); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_osc_controller")); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index d8cde9bd04..c8550474c3 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -155,10 +155,10 @@ int do_main(int argc, char* argv[]) { builder.AddSystem(meshcat, "end_effector_position_target"); auto trajectory_drawer_object = - builder.AddSystem(meshcat, "object_traj"); + builder.AddSystem(meshcat, "object_position_target"); auto object_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.tray_model), "object_traj", + meshcat, FindResourceOrThrow(sim_params.tray_model), "object_position_target", "object_orientation_target"); auto end_effector_pose_drawer = builder.AddSystem( diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 2970b36c97..6d5b7eb44c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -15,6 +15,6 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 10 +target_frequency: 80 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index bc37cbba8a..eaaad502cf 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -4,9 +4,9 @@ rho_scale: 2 num_threads: 6 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'QP' +projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu -contact_model: 'anitescu' +contact_model: 'stewart_and_trinkle' mu: 0.4 mu_plate: 0.4 @@ -27,23 +27,23 @@ w_U: 1 # n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions # size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle # size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu -#g_size: 40 -#u_size: 40 -g_size: 34 -u_size: 34 +g_size: 40 +u_size: 40 +#g_size: 34 +#u_size: 34 # State Tracking Error, assuming diagonal -q_vector: [10, 10, 5000, 0, 0, 0, 0, 10000, 10000, 10000, - 0, 0, 0, 0, 0, 0, 1, 1, 1] +q_vector: [10, 10, 5000, 1000, 1000, 1000, 1000, 10000, 10000, 10000, + 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables -#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables -#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 80d5762481..3ee360c9f2 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] + [0.00001, 0, 0, + 0, 0.00001, 0, + 0, 0, 0.00001] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 796d96a4c7..513e97bdab 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 -visualize: false +visualize: true tool_attachment_frame: [0, 0, 0.107] diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 396f28eee2..d2ad44618a 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -4,6 +4,7 @@ cc_library( name = "franka_systems", srcs = [], deps = [ + ":end_effector_force_trajectory", ":end_effector_orientation", ":end_effector_trajectory", ":franka_kinematics", @@ -24,6 +25,19 @@ cc_library( ], ) +cc_library( + name = "end_effector_force_trajectory", + srcs = ["end_effector_force_trajectory.cc"], + hdrs = ["end_effector_force_trajectory.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + cc_library( name = "end_effector_orientation", srcs = ["end_effector_orientation.cc"], diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 2d3ba2f140..4f2f31d0cb 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -118,30 +118,26 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( knots.bottomRows(3) = c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); LcmTrajectory::Trajectory object_traj; - object_traj.traj_name = "object_traj"; + object_traj.traj_name = "object_position_target"; object_traj.datatypes = std::vector(knots.rows(), "double"); object_traj.datapoints = knots; object_traj.time_vector = c3_solution->time_vector_.cast(); - LcmTrajectory lcm_traj({object_traj}, {"object_traj"}, "object_traj", - "object_traj", false); - - if (publish_end_effector_orientation_) { - LcmTrajectory::Trajectory object_orientation_traj; - // first 3 rows are rpy, last 3 rows are angular velocity - MatrixXd orientation_samples = MatrixXd::Zero(7, N_); - orientation_samples.topRows(4) = - c3_solution->x_sol_.middleRows(3 + 3, 4).cast(); - orientation_samples.bottomRows(3) = - c3_solution->x_sol_.middleRows(n_q_ + 3 + 3, 3).cast(); - object_orientation_traj.traj_name = "object_orientation_target"; - object_orientation_traj.datatypes = - std::vector(orientation_samples.rows(), "double"); - object_orientation_traj.datapoints = orientation_samples; - object_orientation_traj.time_vector = - c3_solution->time_vector_.cast(); - lcm_traj.AddTrajectory(object_orientation_traj.traj_name, - object_orientation_traj); - } + LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, "object_target", + "object_target", false); + + LcmTrajectory::Trajectory object_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(4, N_); + orientation_samples = + c3_solution->x_sol_.middleRows(n_q_ - 7, 4).cast(); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = + c3_solution->time_vector_.cast(); + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + object_orientation_traj); output_traj->saved_traj = lcm_traj.GenerateLcmObject(); output_traj->utime = context.get_time() * 1e6; diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc new file mode 100644 index 0000000000..40576224a4 --- /dev/null +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -0,0 +1,72 @@ +#include "end_effector_force_trajectory.h" + +#include "dairlib/lcmt_radio_out.hpp" +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::Vector2d; +using Eigen::Vector3d; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::BodyFrame; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib { + +EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator( + const MultibodyPlant& plant, Context* context) + : plant_(plant), context_(context), world_(plant.world_frame()) { + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + PiecewisePolynomial pp = PiecewisePolynomial(); + + trajectory_port_ = + this->DeclareAbstractInputPort( + "trajectory", + drake::Value>(pp)) + .get_index(); + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + PiecewisePolynomial empty_pp_traj(Vector3d::Zero()); + Trajectory& traj_inst = empty_pp_traj; + this->DeclareAbstractOutputPort( + "end_effector_force_trajectory", traj_inst, + &EndEffectorForceTrajectoryGenerator::CalcTraj); +} + +void EndEffectorForceTrajectoryGenerator::CalcTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + // // Read in finite state machine + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (radio_out->channel[14] || trajectory_input.value(0).isZero()) { + *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); + } else { + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } +} + +} // namespace dairlib diff --git a/examples/franka/systems/end_effector_force_trajectory.h b/examples/franka/systems/end_effector_force_trajectory.h new file mode 100644 index 0000000000..0e35d01049 --- /dev/null +++ b/examples/franka/systems/end_effector_force_trajectory.h @@ -0,0 +1,47 @@ +#pragma once + +#include + +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class EndEffectorForceTrajectoryGenerator + : public drake::systems::LeafSystem { + public: + EndEffectorForceTrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcTraj(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::Frame& world_; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex trajectory_port_; + drake::systems::InputPortIndex radio_port_; + +}; + +} // namespace dairlib diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 02b1de74cf..9557a71f43 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -1,7 +1,5 @@ #include "end_effector_trajectory.h" -#include - #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" @@ -16,7 +14,6 @@ using std::string; using dairlib::systems::OutputVector; using drake::multibody::BodyFrame; using drake::multibody::Frame; -using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; using drake::systems::Context; diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 7780f87886..eda7e4b3b8 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -56,7 +56,7 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( this->EvalInputValue(context, radio_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = neutral_pose_; - tray_position[2] += 0.02; + tray_position[2] += 0.012065; // thickness of end effector and tray tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index a9891fa3ec..7a71727664 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -177,11 +177,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, -0.4, 0.4, 1); } - for (int i : vector({0, 1})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_u_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, -5, 5, 2); - } +// for (int i : vector({0, 1})) { +// Eigen::RowVectorXd A = VectorXd::Zero(n_u_); +// A(i) = 1.0; +// c3_->AddLinearConstraint(A, -5, 5, 2); +// } // for (int i : vector({2})) { // Eigen::RowVectorXd A = VectorXd::Zero(n_u_); // A(i) = 1.0; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 4d239e11fb..cdd4a2e5ad 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -226,10 +226,10 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( lcm_traj.GetTrajectory(orientation_trajectory_name_); std::vector> quaternion_datapoints; for (int i = 0; i < lcm_orientation_traj.datapoints.cols(); ++i) { + VectorXd orientation_sample = lcm_orientation_traj.datapoints.col(i); quaternion_datapoints.push_back( - drake::math::RollPitchYaw( - lcm_orientation_traj.datapoints.col(i)) - .ToQuaternion()); + Quaterniond(orientation_sample[0], orientation_sample[1], + orientation_sample[2], orientation_sample[3])); } orientation_trajectory = PiecewiseQuaternionSlerp( CopyVectorXdToStdVector(lcm_orientation_traj.time_vector), From 4eb156bdda2473fee1d5354513a5362eeaa7aeee Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 13 Nov 2023 17:01:58 -0500 Subject: [PATCH 529/758] minor changes, playing with differnet c3 parameters --- .../osc_run/osc_running_qp_settings.yaml | 2 +- examples/franka/franka_c3_controller.cc | 27 +++++++---------- examples/franka/franka_osc_controller.cc | 4 +++ .../parameters/franka_c3_controller_params.h | 11 ++++++- .../franka_c3_controller_params.yaml | 5 +++- .../franka_c3_options_translation.yaml | 19 ++++-------- .../franka_osc_controller_params.yaml | 14 ++++----- .../franka/parameters/franka_sim_params.yaml | 2 +- solvers/c3_miqp.h | 2 +- solvers/c3_options.h | 30 ++++--------------- solvers/c3_qp.h | 2 +- systems/controllers/c3_controller.cc | 10 +++---- .../lcm_trajectory_systems.cc | 10 +++++-- 13 files changed, 63 insertions(+), 75 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 5cf72f59b4..9dd7eaf13a 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 250 + max_iter: 500 linsys_solver: 0 verbose: 0 warm_start: 1 diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 153d4169a5..f7fd2b613a 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -164,18 +164,13 @@ int DoMain(int argc, char* argv[]) { auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_actor_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), - 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kForced}))); + auto object_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, - TriggerTypeSet({TriggerType::kPeriodic}), - 1 / controller_params.target_frequency)); -// auto force_trajectory_sender = builder.AddSystem( -// LcmPublisherSystem::Make( -// lcm_channel_params.c3_force_channel, &lcm, -// TriggerTypeSet({TriggerType::kPeriodic}), -// 1 / controller_params.target_frequency)); + TriggerTypeSet({TriggerType::kForced}))); + auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_debug_output_channel, &lcm, @@ -187,10 +182,11 @@ int DoMain(int argc, char* argv[]) { auto plate_balancing_target = builder.AddSystem(); VectorXd neutral_position = Eigen::Map( - c3_options.neutral_position.data(), c3_options.neutral_position.size()); + controller_params.neutral_position.data(), + controller_params.neutral_position.size()); plate_balancing_target->SetRemoteControlParameters( - neutral_position, c3_options.x_scale, c3_options.y_scale, - c3_options.z_scale); + neutral_position, controller_params.x_scale, controller_params.y_scale, + controller_params.z_scale); std::vector input_sizes = {3, 7, 3, 6}; auto target_state_mux = builder.AddSystem(input_sizes); @@ -212,8 +208,8 @@ int DoMain(int argc, char* argv[]) { plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), contact_pairs, c3_options); auto c3_trajectory_generator = - builder.AddSystem( - plant_plate, c3_options); + builder.AddSystem(plant_plate, + c3_options); c3_trajectory_generator->SetPublishEndEffectorOrientation( controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); @@ -261,8 +257,7 @@ int DoMain(int argc, char* argv[]) { // *controller, &loop.get_diagram_mutable_context()); // controller->get_input_port_target().FixValue(&controller_context, x_des); LcmHandleSubscriptionsUntil( - &lcm, [&]() { - return tray_state_sub->GetInternalMessageCount() > 1; }); + &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); loop.Simulate(); return 0; } diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 73b7bf2b2c..14fbba3d84 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -223,6 +223,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(gravity_compensator->get_output_port(), franka_command_sender->get_input_port()); } else { + if (FLAGS_lcm_channels == "examples/franka/parameters/lcm_channels_hardware.yaml"){ + std::cerr << "Using hardware lcm channels but not cancelling gravity compensation. Please check the OSC settings" << std::endl; + return -1; + } builder.Connect(osc->get_output_port_osc_command(), franka_command_sender->get_input_port(0)); } diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 02c3279583..10276b94bb 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -19,9 +19,13 @@ struct FrankaC3ControllerParams { double target_frequency; std::vector tool_attachment_frame; + std::vector neutral_position; + double x_scale; + double y_scale; + double z_scale; + template void Serialize(Archive* a) { - a->Visit(DRAKE_NVP(c3_options_file)); a->Visit(DRAKE_NVP(osqp_settings_file)); a->Visit(DRAKE_NVP(franka_model)); @@ -32,5 +36,10 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(include_end_effector_orientation)); a->Visit(DRAKE_NVP(target_frequency)); a->Visit(DRAKE_NVP(tool_attachment_frame)); + + a->Visit(DRAKE_NVP(neutral_position)); + a->Visit(DRAKE_NVP(x_scale)); + a->Visit(DRAKE_NVP(y_scale)); + a->Visit(DRAKE_NVP(z_scale)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 6d5b7eb44c..c1c5eadec1 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -17,4 +17,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 80 - +neutral_position: [0.55, 0, 0.45] +x_scale: 0.1 +y_scale: 0.1 +z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index eaaad502cf..12a82c221b 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -10,17 +10,17 @@ contact_model: 'stewart_and_trinkle' mu: 0.4 mu_plate: 0.4 -dt: 0.05 +dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 N: 5 # matrix scaling -w_Q: 5 -w_R: 0 +w_Q: 50 +w_R: 0.0001 # Penalty on all decision variables, assuming scalar -w_G: 0.5 +w_G: 1 # Penalty on all decision variables, assuming scalar w_U: 1 @@ -32,7 +32,7 @@ u_size: 40 #g_size: 34 #u_size: 34 # State Tracking Error, assuming diagonal -q_vector: [10, 10, 5000, 1000, 1000, 1000, 1000, 10000, 10000, 10000, +q_vector: [100, 100, 5000, 100, 100, 100, 100, 10000, 10000, 10000, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, @@ -45,12 +45,5 @@ u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, #u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal -r_vector: [1, 1, 1] +r_vector: [0.1, 0.1, 1] -q_des_vector: [0.55, 0.00, 0.4, 1, 0, 0, 0, 0.55, 0.00, 0.42] -v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0] - -neutral_position: [0.55, 0, 0.40] -x_scale: 0.1 -y_scale: 0.1 -z_scale: 0.1 \ No newline at end of file diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 3ee360c9f2..7badb37904 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -6,7 +6,7 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.55, 0, 0.4] +neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [0.00001, 0, 0, - 0, 0.00001, 0, - 0, 0, 0.00001] + [0.001, 0, 0, + 0, 0.001, 0, + 0, 0, 0.001] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, @@ -63,6 +63,6 @@ EndEffectorRotKd: 0, 10, 0, 0, 0, 10 ] LambdaEndEffectorW: - [ 1, 0, 0, - 0, 1, 0, - 0, 0, 1 ] + [ 100000, 0, 0, + 0, 100000, 0, + 0, 0, 100000 ] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 513e97bdab..a52ac2471d 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -19,5 +19,5 @@ q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, -0.00, 0.430] +q_init_plate: [1, 0, 0, 0, 0.56, -0.03, 0.430] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/solvers/c3_miqp.h b/solvers/c3_miqp.h index 2457daf19b..9b6cd34a06 100644 --- a/solvers/c3_miqp.h +++ b/solvers/c3_miqp.h @@ -35,7 +35,7 @@ class C3MIQP final : public C3 { const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, - const int& warm_start_index = -1); + const int& warm_start_index = -1) override; std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 4035a8aa05..26863100cd 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -4,9 +4,10 @@ struct C3Options { // Hyperparameters - int admm_iter = 2; // total number of ADMM iterations //2 - float rho = 0.1; // inital value of the rho parameter - float rho_scale = 3; // scaling of rho parameter (/rho = rho_scale * /rho) //3 + int admm_iter = 2; // total number of ADMM iterations //2 + float rho = 0.1; // inital value of the rho parameter + float rho_scale = + 3; // scaling of rho parameter (/rho = rho_scale * /rho) //3 int num_threads = 0; // 0 is dynamic, greater than 0 for a fixed count int delta_option = 1; // different options for delta update std::string projection_type; @@ -26,9 +27,6 @@ struct C3Options { std::vector g_vector; std::vector u_vector; - std::vector q_des_vector; - std::vector v_des_vector; - double mu; double mu_plate; double dt; @@ -39,13 +37,6 @@ struct C3Options { Eigen::MatrixXd R; Eigen::MatrixXd G; Eigen::MatrixXd U; - Eigen::VectorXd q_des; - Eigen::VectorXd v_des; - - std::vector neutral_position; - double x_scale; - double y_scale; - double z_scale; template void Serialize(Archive* a) { @@ -56,7 +47,7 @@ struct C3Options { a->Visit(DRAKE_NVP(delta_option)); a->Visit(DRAKE_NVP(contact_model)); a->Visit(DRAKE_NVP(projection_type)); - if (projection_type == "QP"){ + if (projection_type == "QP") { DRAKE_DEMAND(contact_model == "anitescu"); } @@ -78,13 +69,6 @@ struct C3Options { a->Visit(DRAKE_NVP(g_vector)); a->Visit(DRAKE_NVP(u_vector)); a->Visit(DRAKE_NVP(r_vector)); - a->Visit(DRAKE_NVP(q_des_vector)); - a->Visit(DRAKE_NVP(v_des_vector)); - - a->Visit(DRAKE_NVP(neutral_position)); - a->Visit(DRAKE_NVP(x_scale)); - a->Visit(DRAKE_NVP(y_scale)); - a->Visit(DRAKE_NVP(z_scale)); Eigen::VectorXd q = Eigen::Map( this->q_vector.data(), this->q_vector.size()); @@ -94,10 +78,6 @@ struct C3Options { this->g_vector.data(), this->g_vector.size()); Eigen::VectorXd u = Eigen::Map( this->u_vector.data(), this->u_vector.size()); - q_des = Eigen::Map( - this->q_des_vector.data(), this->q_des_vector.size()); - v_des = Eigen::Map( - this->v_des_vector.data(), this->v_des_vector.size()); Q = w_Q * q.asDiagonal(); R = w_R * r.asDiagonal(); diff --git a/solvers/c3_qp.h b/solvers/c3_qp.h index 02d6797f80..189f864a94 100644 --- a/solvers/c3_qp.h +++ b/solvers/c3_qp.h @@ -45,7 +45,7 @@ class C3QP final : public C3 { const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, - const int& warm_start_index = -1); + const int& warm_start_index = -1) override; std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7a71727664..a9891fa3ec 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -177,11 +177,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, -0.4, 0.4, 1); } -// for (int i : vector({0, 1})) { -// Eigen::RowVectorXd A = VectorXd::Zero(n_u_); -// A(i) = 1.0; -// c3_->AddLinearConstraint(A, -5, 5, 2); -// } + for (int i : vector({0, 1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, -5, 5, 2); + } // for (int i : vector({2})) { // Eigen::RowVectorXd A = VectorXd::Zero(n_u_); // A(i) = 1.0; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index cdd4a2e5ad..f0b87c0c88 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -227,9 +227,13 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( std::vector> quaternion_datapoints; for (int i = 0; i < lcm_orientation_traj.datapoints.cols(); ++i) { VectorXd orientation_sample = lcm_orientation_traj.datapoints.col(i); - quaternion_datapoints.push_back( - Quaterniond(orientation_sample[0], orientation_sample[1], - orientation_sample[2], orientation_sample[3])); + if (orientation_sample.isZero()) { + quaternion_datapoints.push_back(Quaterniond(1, 0, 0, 0)); + } else { + quaternion_datapoints.push_back( + Quaterniond(orientation_sample[0], orientation_sample[1], + orientation_sample[2], orientation_sample[3])); + } } orientation_trajectory = PiecewiseQuaternionSlerp( CopyVectorXdToStdVector(lcm_orientation_traj.time_vector), From 19981a8b5fc0b06ce993877eda599c3c4ec95083 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 13 Nov 2023 17:17:30 -0500 Subject: [PATCH 530/758] issue with force tracking is time delay for solve --- .../franka/parameters/franka_osc_controller_params.yaml | 6 +++--- systems/controllers/osc/external_force_tracking_data.cc | 2 +- systems/controllers/osc/operational_space_control.cc | 9 ++++++++- 3 files changed, 12 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 7badb37904..77ceeea5e9 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -63,6 +63,6 @@ EndEffectorRotKd: 0, 10, 0, 0, 0, 10 ] LambdaEndEffectorW: - [ 100000, 0, 0, - 0, 100000, 0, - 0, 0, 100000 ] + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1 ] diff --git a/systems/controllers/osc/external_force_tracking_data.cc b/systems/controllers/osc/external_force_tracking_data.cc index 51eae3b09e..9433b1b7b1 100644 --- a/systems/controllers/osc/external_force_tracking_data.cc +++ b/systems/controllers/osc/external_force_tracking_data.cc @@ -39,7 +39,7 @@ void ExternalForceTrackingData::Update( const drake::trajectories::Trajectory& traj, double t) { DRAKE_DEMAND(traj.rows() == 3); - lambda_des_ = -traj.value(t); + lambda_des_ = traj.value(t); J_ = MatrixXd::Zero(3, plant_wo_spr_.num_velocities()); plant_wo_spr_.CalcJacobianTranslationalVelocity( context_wo_spr, JacobianWrtVariable::kV, *body_frame_wo_spr_, pt_on_body_, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 80b70a22cd..e82fff0fed 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -672,7 +672,7 @@ VectorXd OperationalSpaceControl::SolveQp( A_dyn.block(0, n_v_ + n_c_, n_v_, n_h_) = -J_h.transpose(); A_dyn.block(0, n_v_ + n_c_ + n_h_, n_v_, n_u_) = -B; MatrixXd J_ee = force_tracking_data_vec_->at(0)->GetJ(); - A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_ee_) = -J_ee.transpose(); + A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_ee_) = J_ee.transpose(); dynamics_constraint_->UpdateCoefficients(A_dyn, -bias); // 2. Holonomic constraint /// JdotV_h + J_h*dv == 0 @@ -1007,6 +1007,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( VectorXd y_input_smoothing_cost = VectorXd::Zero(1); VectorXd y_lambda_c_cost = VectorXd::Zero(1); VectorXd y_lambda_h_cost = VectorXd::Zero(1); + VectorXd y_lambda_ee_cost = VectorXd::Zero(1); VectorXd y_soft_constraint_cost = VectorXd::Zero(1); VectorXd y_joint_limit_cost = VectorXd::Zero(1); if (accel_cost_) { @@ -1021,6 +1022,9 @@ void OperationalSpaceControl::AssignOscLcmOutput( if (lambda_c_cost_) { lambda_c_cost_->Eval(*lambda_c_sol_, &y_lambda_c_cost); } + if (lambda_ee_cost_) { + lambda_ee_cost_->Eval(*lambda_ee_sol_, &y_lambda_ee_cost); + } if (lambda_h_cost_) { lambda_h_cost_->Eval(*lambda_h_sol_, &y_lambda_h_cost); } @@ -1038,6 +1042,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( (soft_constraint_cost_ != nullptr) ? y_soft_constraint_cost[0] : 0; double lambda_c_cost = (lambda_c_cost_ != nullptr) ? y_lambda_c_cost[0] : 0; double lambda_h_cost = (lambda_h_cost_ != nullptr) ? y_lambda_h_cost[0] : 0; + double lambda_ee_cost = (lambda_ee_cost_ != nullptr) ? y_lambda_ee_cost[0] : 0; // double joint_limit_cost = // (joint_limit_cost_ != nullptr) ? y_joint_limit_cost[0] : 0; @@ -1058,6 +1063,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( output->regularization_cost_names.emplace_back("lambda_c_cost"); output->regularization_costs.push_back(lambda_h_cost); output->regularization_cost_names.emplace_back("lambda_h_cost"); + output->regularization_costs.push_back(lambda_ee_cost); + output->regularization_cost_names.emplace_back("lambda_ee_cost"); output->tracking_data_names.clear(); output->tracking_data.clear(); From 132cc814b439d9674ee6998e21511dd578635d55 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Nov 2023 10:37:33 -0500 Subject: [PATCH 531/758] cleaning up code as per comments --- multibody/multibody_utils.cc | 25 +++++++------------------ multibody/multibody_utils.h | 6 +++--- multibody/multipose_visualizer.cc | 3 --- multibody/visualization_utils.cc | 5 ----- systems/robot_lcm_systems.h | 7 ------- 5 files changed, 10 insertions(+), 36 deletions(-) diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index d4ae2469d0..b603f1861c 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -151,8 +151,8 @@ void AddFlatTerrain(MultibodyPlant* plant, SceneGraph* scene_graph, // Add visual for the ground. if (show_ground) { - // plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), - // "visual"); + plant->RegisterVisualGeometry(plant->world_body(), X_WG, HalfSpace(), + "visual"); } } @@ -202,15 +202,11 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant) { } } - // TODO: once RBT fully deprecated, this block can likely be removed, using - // default coordinate names from Drake. auto floating_bodies = plant.GetFloatingBaseBodies(); - // DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); DRAKE_ASSERT(body.has_quaternion_dofs()); int start = body.floating_positions_start(); - // should be body.name() once RBT is deprecated std::string name = body.name(); name_to_index_map[name + "_qw"] = start; name_to_index_map[name + "_qx"] = start + 1; @@ -270,13 +266,10 @@ map MakeNameToPositionsMap(const MultibodyPlant& plant, } } - // TODO: once RBT fully deprecated, this block can likely be removed, using - // default coordinate names from Drake. if (plant.HasUniqueFreeBaseBody(model_instance)) { const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); DRAKE_ASSERT(body.has_quaternion_dofs()); int start = body.floating_positions_start(); - // should be body.name() once RBT is deprecated std::string name = body.name(); name_to_index_map[name + "_qw"] = start; name_to_index_map[name + "_qx"] = start + 1; @@ -308,8 +301,6 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { for (JointIndex i(0); i < plant.num_joints(); ++i) { const drake::multibody::Joint& joint = plant.get_joint(i); - // TODO(posa): this "dot" should be removed, it's an anachronism from - // RBT auto name = joint.name() + "dot"; if (joint.num_velocities() == 1 && joint.num_positions() == 1) { @@ -336,8 +327,6 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { } auto floating_bodies = plant.GetFloatingBaseBodies(); - // Remove throw once RBT deprecated - // DRAKE_THROW_UNLESS(floating_bodies.size() <= 1); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); int start = body.floating_velocities_start() - plant.num_positions(); @@ -379,8 +368,6 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant, for (auto i : plant.GetJointIndices(model_instance)) { const drake::multibody::Joint& joint = plant.get_joint(i); - // TODO(posa): this "dot" should be removed, it's an anachronism from - // RBT auto name = joint.name() + "dot"; if (joint.num_velocities() == 1 && joint.num_positions() == 1) { @@ -406,12 +393,10 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant, } } - // Remove throw once RBT deprecated if (plant.HasUniqueFreeBaseBody(model_instance)) { const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); int start = body.floating_velocities_start() - plant.num_positions(); - std::string name = - body.name(); // should be body.name() once RBT is deprecated + std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; name_to_index_map[name + "_wz"] = start + 2; @@ -654,8 +639,12 @@ template Vector3d ReExpressWorldVector3InBodyYawFrame(const MultibodyPlant& plant, const Context& context, const std::string& body_name, const Vector2d& vec); //NOLINT template map MakeNameToPositionsMap(const MultibodyPlant& plant); // NOLINT template map MakeNameToPositionsMap(const MultibodyPlant &plant); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToPositionsMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT template map MakeNameToVelocitiesMap(const MultibodyPlant& plant); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT +template map MakeNameToVelocitiesMap(const MultibodyPlant& plant, drake::multibody::ModelInstanceIndex); // NOLINT template map MakeNameToActuatorsMap(const MultibodyPlant& plant); // NOLINT template map MakeNameToActuatorsMap(const MultibodyPlant& plant); // NOLINT template vector CreateStateNameVectorFromMap(const MultibodyPlant& plant); // NOLINT diff --git a/multibody/multibody_utils.h b/multibody/multibody_utils.h index aa335dd85a..4d829fe985 100644 --- a/multibody/multibody_utils.h +++ b/multibody/multibody_utils.h @@ -86,19 +86,19 @@ std::map MakeNameToPositionsMap( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance_index); -/// Given a MultiBodyTree, builds a map from velocity name to velocity index +/// Given a MultiBodyPlant, builds a map from velocity name to velocity index template std::map MakeNameToVelocitiesMap( const drake::multibody::MultibodyPlant& plant); -/// Given a MultiBodyTree, builds a map from velocity name to velocity index +/// Given a MultiBodyPlant, builds a map from velocity name to velocity index template std::map MakeNameToVelocitiesMap( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance_index); -/// Given a MultiBodyTree, builds a map from actuator name to actuator index +/// Given a MultiBodyPlant, builds a map from actuator name to actuator index template std::map MakeNameToActuatorsMap( const drake::multibody::MultibodyPlant& plant); diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index fd23289204..e8e3aa9aa8 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -1,9 +1,6 @@ #include "multibody/multipose_visualizer.h" -#include - #include "drake/geometry/drake_visualizer.h" -#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/geometry/scene_graph.h" #include "drake/systems/framework/diagram_builder.h" #include "drake/systems/lcm/lcm_interface_system.h" diff --git a/multibody/visualization_utils.cc b/multibody/visualization_utils.cc index 4e2922ab35..2c53e7c15f 100644 --- a/multibody/visualization_utils.cc +++ b/multibody/visualization_utils.cc @@ -3,9 +3,6 @@ #include "common/find_resource.h" #include "multibody/com_pose_system.h" #include "systems/primitives/subvector_pass_through.h" -#include "drake/geometry/drake_visualizer.h" -#include "drake/geometry/meshcat_visualizer.h" -#include "drake/geometry/meshcat_visualizer_params.h" #include "drake/multibody/parsing/parser.h" #include "drake/systems/primitives/trajectory_source.h" @@ -83,8 +80,6 @@ void ConnectTrajectoryVisualizerWithCoM( scene_graph->get_source_pose_port(ball_plant.get_source_id().value())); } - DrakeVisualizer::AddToBuilder(builder, *scene_graph); - } } // namespace multibody diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 7ca76144e2..2218d68b41 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -168,12 +168,5 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( drake::multibody::ModelInstanceIndex model_instance_index, bool publish_efforts = true, double actuator_delay = 0); -SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( - drake::systems::DiagramBuilder* builder, - const drake::multibody::MultibodyPlant& plant, - drake::systems::lcm::LcmInterfaceSystem* lcm, std::string actuator_channel, - std::string state_channel, double publish_rate, bool publish_efforts = true, - double actuator_delay = 0); - } // namespace systems } // namespace dairlib From 35d9c458280545fb3d3f8a247904238a295498f8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Nov 2023 11:12:04 -0500 Subject: [PATCH 532/758] fixing compile issues, renaming base to pelvis for cassie examples --- .../pydairlib/systems/robot_lcm_systems_py.cc | 10 ----- examples/Cassie/cassie_fixed_point_solver.cc | 42 +++++++++---------- systems/robot_lcm_systems.cc | 4 +- systems/robot_lcm_systems.h | 4 +- 4 files changed, 23 insertions(+), 37 deletions(-) diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 696769516f..606197e509 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -53,16 +53,6 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::arg("actuator_channel"), py::arg("state_channel"), py::arg("publish_rate"), py::arg("model_instance"), py::arg("publish_efforts"), py::arg("actuator_delay")); - m.def("AddActuationRecieverAndStateSenderLcm", - py::overload_cast*, - const MultibodyPlant&, - drake::systems::lcm::LcmInterfaceSystem*, std::string, - std::string, double, bool, double>( - &dairlib::systems::AddActuationRecieverAndStateSenderLcm), - py::arg("builder"), py::arg("plant"), py::arg("lcm"), - py::arg("actuator_channel"), py::arg("state_channel"), - py::arg("publish_rate"), py::arg("publish_efforts"), - py::arg("actuator_delay")); } } // namespace pydairlib diff --git a/examples/Cassie/cassie_fixed_point_solver.cc b/examples/Cassie/cassie_fixed_point_solver.cc index e4b6d394f2..fdd5f9f00e 100644 --- a/examples/Cassie/cassie_fixed_point_solver.cc +++ b/examples/Cassie/cassie_fixed_point_solver.cc @@ -88,14 +88,14 @@ void CassieFixedPointSolver( program.AddJointLimitConstraints(q); // Fix floating base - program.AddConstraint(q(positions_map.at("base_qw")) == 1); - program.AddConstraint(q(positions_map.at("base_qx")) == 0); - program.AddConstraint(q(positions_map.at("base_qy")) == 0); - program.AddConstraint(q(positions_map.at("base_qz")) == 0); + program.AddConstraint(q(positions_map.at("pelvis_qw")) == 1); + program.AddConstraint(q(positions_map.at("pelvis_qx")) == 0); + program.AddConstraint(q(positions_map.at("pelvis_qy")) == 0); + program.AddConstraint(q(positions_map.at("pelvis_qz")) == 0); - program.AddConstraint(q(positions_map.at("base_x")) == 0); - program.AddConstraint(q(positions_map.at("base_y")) == 0); - program.AddConstraint(q(positions_map.at("base_z")) == height); + program.AddConstraint(q(positions_map.at("pelvis_x")) == 0); + program.AddConstraint(q(positions_map.at("pelvis_y")) == 0); + program.AddConstraint(q(positions_map.at("pelvis_z")) == height); // Add symmetry constraints, and zero roll/pitch on the hip program.AddConstraint(q(positions_map.at("knee_left")) == @@ -143,7 +143,7 @@ void CassieFixedPointSolver( // Set initial guess/cost for q using a vaguely neutral position Eigen::VectorXd q_guess = Eigen::VectorXd::Zero(plant.num_positions()); q_guess(0) = 1; // quaternion - q_guess(positions_map.at("base_z")) = height; + q_guess(positions_map.at("pelvis_z")) = height; q_guess(positions_map.at("hip_pitch_left")) = 1; q_guess(positions_map.at("knee_left")) = -2; q_guess(positions_map.at("ankle_joint_left")) = 2; @@ -334,27 +334,27 @@ void CassieInitStateSolver( int n_v = plant.num_velocities(); // Fix floating base - program.AddBoundingBoxConstraint(1, 1, q(positions_map.at("base_qw"))); - program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("base_qx"))); - program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("base_qy"))); - program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("base_qz"))); + program.AddBoundingBoxConstraint(1, 1, q(positions_map.at("pelvis_qw"))); + program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("pelvis_qx"))); + program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("pelvis_qy"))); + program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("pelvis_qz"))); - program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("base_x"))); - program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("base_y"))); + program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("pelvis_x"))); + program.AddBoundingBoxConstraint(0, 0, q(positions_map.at("pelvis_y"))); program.AddBoundingBoxConstraint(height, height, - q(positions_map.at("base_z"))); + q(positions_map.at("pelvis_z"))); program.AddBoundingBoxConstraint(-10, 10, v); - program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("base_wx"))); - program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("base_wy"))); - program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("base_wz"))); + program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("pelvis_wx"))); + program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("pelvis_wy"))); + program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("pelvis_wz"))); program.AddBoundingBoxConstraint(pelvis_xy_vel(0), pelvis_xy_vel(0), - v(vel_map.at("base_vx"))); + v(vel_map.at("pelvis_vx"))); program.AddBoundingBoxConstraint(pelvis_xy_vel(1), pelvis_xy_vel(1), - v(vel_map.at("base_vy"))); - program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("base_vz"))); + v(vel_map.at("pelvis_vy"))); + program.AddBoundingBoxConstraint(0, 0, v(vel_map.at("pelvis_vz"))); // Add symmetry constraints, and zero roll/pitch on the hip program.AddConstraint(q(positions_map.at("knee_left")) == diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index fbdc08002d..d8611caa09 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -175,7 +175,6 @@ RobotOutputSender::RobotOutputSender( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); effort_index_map_ = multibody::MakeNameToActuatorsMap(plant); - model_instance_ = drake::multibody::ModelInstanceIndex(-1); positions_start_idx_ = 0; velocities_start_idx_ = 0; @@ -209,8 +208,7 @@ RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance, const bool publish_efforts, const bool publish_imu) - : model_instance_(model_instance), - publish_efforts_(publish_efforts), + : publish_efforts_(publish_efforts), publish_imu_(publish_imu) { num_positions_ = plant.num_positions(model_instance); num_velocities_ = plant.num_velocities(model_instance); diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 2218d68b41..b280c24c7d 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -61,8 +61,7 @@ class RobotOutputSender : public drake::systems::LeafSystem { public: explicit RobotOutputSender( const drake::multibody::MultibodyPlant& plant, - drake::multibody::ModelInstanceIndex model_instance_index = - drake::multibody::default_model_instance(), + drake::multibody::ModelInstanceIndex model_instance_index, const bool publish_efforts = false, const bool publish_imu = false); explicit RobotOutputSender( @@ -86,7 +85,6 @@ class RobotOutputSender : public drake::systems::LeafSystem { void Output(const drake::systems::Context& context, dairlib::lcmt_robot_output* output) const; - drake::multibody::ModelInstanceIndex model_instance_; int positions_start_idx_; int velocities_start_idx_; int num_positions_; From 36c292c5029c020e1ec6027ec51e4b2aa69914ce Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Nov 2023 11:34:51 -0500 Subject: [PATCH 533/758] renaming hardcoded base link for cassie examples --- examples/Cassie/cassie_state_estimator.cc | 30 ++-- examples/Cassie/run_dircon_jumping.cc | 12 +- examples/Cassie/run_dircon_squatting.cc | 68 ++++---- examples/Cassie/run_dircon_walking.cc | 162 +++++++++--------- examples/Cassie/visualize_trajectory.cc | 12 +- multibody/test/geom_geom_collider_test.cc | 12 +- .../dircon_opt_constraints.cc | 11 +- 7 files changed, 155 insertions(+), 152 deletions(-) diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 376d5838d1..6fe105077c 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -435,20 +435,20 @@ void CassieStateEstimator::AssignNonFloatingBaseStateToOutputVector( void CassieStateEstimator::AssignFloatingBaseStateToOutputVector( const VectorXd& est_fb_state, OutputVector* output) const { - output->SetPositionAtIndex(position_idx_map_.at("base_qw"), est_fb_state(0)); - output->SetPositionAtIndex(position_idx_map_.at("base_qx"), est_fb_state(1)); - output->SetPositionAtIndex(position_idx_map_.at("base_qy"), est_fb_state(2)); - output->SetPositionAtIndex(position_idx_map_.at("base_qz"), est_fb_state(3)); - output->SetPositionAtIndex(position_idx_map_.at("base_x"), est_fb_state(4)); - output->SetPositionAtIndex(position_idx_map_.at("base_y"), est_fb_state(5)); - output->SetPositionAtIndex(position_idx_map_.at("base_z"), est_fb_state(6)); - - output->SetVelocityAtIndex(velocity_idx_map_.at("base_wx"), est_fb_state(7)); - output->SetVelocityAtIndex(velocity_idx_map_.at("base_wy"), est_fb_state(8)); - output->SetVelocityAtIndex(velocity_idx_map_.at("base_wz"), est_fb_state(9)); - output->SetVelocityAtIndex(velocity_idx_map_.at("base_vx"), est_fb_state(10)); - output->SetVelocityAtIndex(velocity_idx_map_.at("base_vy"), est_fb_state(11)); - output->SetVelocityAtIndex(velocity_idx_map_.at("base_vz"), est_fb_state(12)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qw"), est_fb_state(0)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qx"), est_fb_state(1)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qy"), est_fb_state(2)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qz"), est_fb_state(3)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_x"), est_fb_state(4)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_y"), est_fb_state(5)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_z"), est_fb_state(6)); + + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wx"), est_fb_state(7)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wy"), est_fb_state(8)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wz"), est_fb_state(9)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vx"), est_fb_state(10)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vy"), est_fb_state(11)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vz"), est_fb_state(12)); } /// EstimateContactFromSprings(). Conservative estimation. @@ -628,7 +628,7 @@ EventStatus CassieStateEstimator::Update( // is not triggered by CASSIE_STATE_SIMULATION message. // This wouldn't be an issue when you don't use ground truth state. if (output_gt.GetPositions().head(7).norm() == 0) { - output_gt.SetPositionAtIndex(position_idx_map_.at("base_qw"), 1); + output_gt.SetPositionAtIndex(position_idx_map_.at("pelvis_qw"), 1); } // Get kinematics cache for ground truth diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index a6c75a7df2..8521caf236 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -442,9 +442,9 @@ void SetKinematicConstraints(Dircon* trajopt, auto& prog = trajopt->prog(); // position constraints prog.AddBoundingBoxConstraint(0 - midpoint, 0 - midpoint, - x_0(pos_map.at("base_x"))); - prog.AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("base_y"))); - prog.AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("base_y"))); + x_0(pos_map.at("pelvis_x"))); + prog.AddBoundingBoxConstraint(0, 0, x_0(pos_map.at("pelvis_y"))); + prog.AddBoundingBoxConstraint(0, 0, x_f(pos_map.at("pelvis_y"))); // initial fb orientation constraint VectorXd quat_identity(4); @@ -472,13 +472,13 @@ void SetKinematicConstraints(Dircon* trajopt, // Jumping height constraints prog.AddBoundingBoxConstraint(rest_height - eps, rest_height + eps, - x_0(pos_map.at("base_z"))); + x_0(pos_map.at("pelvis_z"))); prog.AddBoundingBoxConstraint(0.5 * FLAGS_height + rest_height - eps, FLAGS_height + rest_height + eps, - x_top(pos_map.at("base_z"))); + x_top(pos_map.at("pelvis_z"))); prog.AddBoundingBoxConstraint(0.8 * FLAGS_height + rest_height - eps, 0.8 * FLAGS_height + rest_height + eps, - x_f(pos_map.at("base_z"))); + x_f(pos_map.at("pelvis_z"))); // Zero starting and final velocities prog.AddLinearConstraint(VectorXd::Zero(n_v) == x_0.tail(n_v)); diff --git a/examples/Cassie/run_dircon_squatting.cc b/examples/Cassie/run_dircon_squatting.cc index f5d5e2a36b..8385e7e385 100644 --- a/examples/Cassie/run_dircon_squatting.cc +++ b/examples/Cassie/run_dircon_squatting.cc @@ -114,13 +114,13 @@ void DoMain(double duration, int max_iter, const string& data_directory, map velocities_map = multibody::MakeNameToVelocitiesMap(plant); map actuators_map = multibody::MakeNameToActuatorsMap(plant); - int base_qw_idx = positions_map.at("base_qw"); - int base_qx_idx = positions_map.at("base_qx"); - int base_qy_idx = positions_map.at("base_qy"); - int base_qz_idx = positions_map.at("base_qz"); - int base_x_idx = positions_map.at("base_x"); - int base_y_idx = positions_map.at("base_y"); - int base_z_idx = positions_map.at("base_z"); + int pelvis_qw_idx = positions_map.at("pelvis_qw"); + int pelvis_qx_idx = positions_map.at("pelvis_qx"); + int pelvis_qy_idx = positions_map.at("pelvis_qy"); + int pelvis_qz_idx = positions_map.at("pelvis_qz"); + int pelvis_x_idx = positions_map.at("pelvis_x"); + int pelvis_y_idx = positions_map.at("pelvis_y"); + int pelvis_z_idx = positions_map.at("pelvis_z"); int hip_roll_left_idx = positions_map.at("hip_roll_left"); int hip_roll_right_idx = positions_map.at("hip_roll_right"); int hip_yaw_left_idx = positions_map.at("hip_yaw_left"); @@ -134,12 +134,12 @@ void DoMain(double duration, int max_iter, const string& data_directory, int toe_left_idx = positions_map.at("toe_left"); int toe_right_idx = positions_map.at("toe_right"); - int base_wx_idx = velocities_map.at("base_wx"); - int base_wy_idx = velocities_map.at("base_wy"); - int base_wz_idx = velocities_map.at("base_wz"); - int base_vx_idx = velocities_map.at("base_vx"); - int base_vy_idx = velocities_map.at("base_vy"); - int base_vz_idx = velocities_map.at("base_vz"); + int pelvis_wx_idx = velocities_map.at("pelvis_wx"); + int pelvis_wy_idx = velocities_map.at("pelvis_wy"); + int pelvis_wz_idx = velocities_map.at("pelvis_wz"); + int pelvis_vx_idx = velocities_map.at("pelvis_vx"); + int pelvis_vy_idx = velocities_map.at("pelvis_vy"); + int pelvis_vz_idx = velocities_map.at("pelvis_vz"); int hip_roll_leftdot_idx = velocities_map.at("hip_roll_leftdot"); int hip_roll_rightdot_idx = velocities_map.at("hip_roll_rightdot"); int hip_yaw_leftdot_idx = velocities_map.at("hip_yaw_leftdot"); @@ -238,8 +238,8 @@ void DoMain(double duration, int max_iter, const string& data_directory, double s_dyn_2 = (FLAGS_scale_variable) ? 6.0 : 1.0; double s_dyn_3 = (FLAGS_scale_variable) ? 85.0 : 1.0; double_support.SetDynamicsScale( - {base_qw_idx, base_qx_idx, base_qy_idx, base_qz_idx, base_x_idx, - base_y_idx, base_z_idx, hip_roll_left_idx, hip_roll_right_idx, + {pelvis_qw_idx, pelvis_qx_idx, pelvis_qy_idx, pelvis_qz_idx, pelvis_x_idx, + pelvis_y_idx, pelvis_z_idx, hip_roll_left_idx, hip_roll_right_idx, hip_yaw_left_idx, hip_yaw_right_idx, hip_pitch_left_idx, hip_pitch_right_idx, knee_left_idx, knee_right_idx}, 1.0 / 150.0); @@ -248,8 +248,8 @@ void DoMain(double duration, int max_iter, const string& data_directory, 1.0 / 150.0 / 3.33 / s_dyn_1); double_support.SetDynamicsScale({toe_left_idx, toe_right_idx}, 1.0 / 150.0); double_support.SetDynamicsScale( - {base_wx_idx, base_wy_idx, base_wz_idx, base_vx_idx, base_vy_idx, - base_vz_idx, hip_roll_leftdot_idx, hip_roll_rightdot_idx}, + {pelvis_wx_idx, pelvis_wy_idx, pelvis_wz_idx, pelvis_vx_idx, pelvis_vy_idx, + pelvis_vz_idx, hip_roll_leftdot_idx, hip_roll_rightdot_idx}, 1.0 / 150.0 / s_dyn_1); double_support.SetDynamicsScale({hip_yaw_leftdot_idx, hip_yaw_rightdot_idx}, 1.0 / 150.0 / s_dyn_2); @@ -338,20 +338,20 @@ void DoMain(double duration, int max_iter, const string& data_directory, auto xmid = trajopt.state_vars(0, (num_knotpoints - 1) / 2); // height constraint - prog.AddBoundingBoxConstraint(1, 1, x0(positions_map.at("base_z"))); - prog.AddBoundingBoxConstraint(1.1, 1.1, xf(positions_map.at("base_z"))); + prog.AddBoundingBoxConstraint(1, 1, x0(positions_map.at("pelvis_z"))); + prog.AddBoundingBoxConstraint(1.1, 1.1, xf(positions_map.at("pelvis_z"))); // initial pelvis position - prog.AddBoundingBoxConstraint(0, 0, x0(positions_map.at("base_x"))); - prog.AddBoundingBoxConstraint(0, 0, x0(positions_map.at("base_y"))); + prog.AddBoundingBoxConstraint(0, 0, x0(positions_map.at("pelvis_x"))); + prog.AddBoundingBoxConstraint(0, 0, x0(positions_map.at("pelvis_y"))); // pelvis pose constraints for (int i = 0; i < num_knotpoints; i++) { auto xi = trajopt.state(i); - prog.AddBoundingBoxConstraint(1, 1, xi(positions_map.at("base_qw"))); - prog.AddBoundingBoxConstraint(0, 0, xi(positions_map.at("base_qx"))); - prog.AddBoundingBoxConstraint(0, 0, xi(positions_map.at("base_qy"))); - prog.AddBoundingBoxConstraint(0, 0, xi(positions_map.at("base_qz"))); + prog.AddBoundingBoxConstraint(1, 1, xi(positions_map.at("pelvis_qw"))); + prog.AddBoundingBoxConstraint(0, 0, xi(positions_map.at("pelvis_qx"))); + prog.AddBoundingBoxConstraint(0, 0, xi(positions_map.at("pelvis_qy"))); + prog.AddBoundingBoxConstraint(0, 0, xi(positions_map.at("pelvis_qz"))); } // start/end velocity constraints @@ -449,9 +449,9 @@ void DoMain(double duration, int max_iter, const string& data_directory, trajopt.ScaleTimeVariables(0.015); // state std::vector idx_list = { - n_q + base_wx_idx, n_q + base_wy_idx, - n_q + base_wz_idx, n_q + base_vx_idx, - n_q + base_vy_idx, n_q + base_vz_idx, + n_q + pelvis_wx_idx, n_q + pelvis_wy_idx, + n_q + pelvis_wz_idx, n_q + pelvis_vx_idx, + n_q + pelvis_vy_idx, n_q + pelvis_vz_idx, n_q + hip_roll_leftdot_idx, n_q + hip_roll_rightdot_idx, n_q + hip_yaw_leftdot_idx, n_q + hip_yaw_rightdot_idx}; trajopt.ScaleStateVariables(idx_list, 6); @@ -546,13 +546,13 @@ void DoMain(double duration, int max_iter, const string& data_directory, // produces NAN value in some calculation. for (int i = 0; i < num_knotpoints; i++) { auto xi = trajopt.state(i); - if ((prog.GetInitialGuess(xi.segment<4>(base_qw_idx)).norm() == 0) || + if ((prog.GetInitialGuess(xi.segment<4>(pelvis_qw_idx)).norm() == 0) || std::isnan( - prog.GetInitialGuess(xi.segment<4>(base_qw_idx)).norm())) { - prog.SetInitialGuess(xi(base_qw_idx), 1); - prog.SetInitialGuess(xi(base_qx_idx), 0); - prog.SetInitialGuess(xi(base_qy_idx), 0); - prog.SetInitialGuess(xi(base_qz_idx), 0); + prog.GetInitialGuess(xi.segment<4>(pelvis_qw_idx)).norm())) { + prog.SetInitialGuess(xi(pelvis_qw_idx), 1); + prog.SetInitialGuess(xi(pelvis_qx_idx), 0); + prog.SetInitialGuess(xi(pelvis_qy_idx), 0); + prog.SetInitialGuess(xi(pelvis_qz_idx), 0); } } diff --git a/examples/Cassie/run_dircon_walking.cc b/examples/Cassie/run_dircon_walking.cc index ba3b2b4450..357f1c0165 100644 --- a/examples/Cassie/run_dircon_walking.cc +++ b/examples/Cassie/run_dircon_walking.cc @@ -119,13 +119,13 @@ vector GetInitGuessForQ(int N, double stride_length, map pos_value_map; Eigen::Vector4d quat(2000.06, -0.339462, -0.609533, -0.760854); quat.normalize(); - pos_value_map["base_qw"] = quat(0); - pos_value_map["base_qx"] = quat(1); - pos_value_map["base_qy"] = quat(2); - pos_value_map["base_qz"] = quat(3); - pos_value_map["base_x"] = 0.000889849; - pos_value_map["base_y"] = 0.000626865; - pos_value_map["base_z"] = 1.0009; + pos_value_map["pelvis_qw"] = quat(0); + pos_value_map["pelvis_qx"] = quat(1); + pos_value_map["pelvis_qy"] = quat(2); + pos_value_map["pelvis_qz"] = quat(3); + pos_value_map["pelvis_x"] = 0.000889849; + pos_value_map["pelvis_y"] = 0.000626865; + pos_value_map["pelvis_z"] = 1.0009; pos_value_map["hip_roll_left"] = -0.0112109; pos_value_map["hip_roll_right"] = 0.00927845; pos_value_map["hip_yaw_left"] = -0.000600725; @@ -411,13 +411,13 @@ void DoMain(double duration, double stride_length, double ground_incline, options_list[i].setConstraintRelative(3, true); } - int base_qw_idx = pos_map.at("base_qw"); - int base_qx_idx = pos_map.at("base_qx"); - int base_qy_idx = pos_map.at("base_qy"); - int base_qz_idx = pos_map.at("base_qz"); - int base_x_idx = pos_map.at("base_x"); - int base_y_idx = pos_map.at("base_y"); - int base_z_idx = pos_map.at("base_z"); + int pelvis_qw_idx = pos_map.at("pelvis_qw"); + int pelvis_qx_idx = pos_map.at("pelvis_qx"); + int pelvis_qy_idx = pos_map.at("pelvis_qy"); + int pelvis_qz_idx = pos_map.at("pelvis_qz"); + int pelvis_x_idx = pos_map.at("pelvis_x"); + int pelvis_y_idx = pos_map.at("pelvis_y"); + int pelvis_z_idx = pos_map.at("pelvis_z"); int hip_roll_left_idx = pos_map.at("hip_roll_left"); int hip_roll_right_idx = pos_map.at("hip_roll_right"); int hip_yaw_left_idx = pos_map.at("hip_yaw_left"); @@ -431,12 +431,12 @@ void DoMain(double duration, double stride_length, double ground_incline, int toe_left_idx = pos_map.at("toe_left"); int toe_right_idx = pos_map.at("toe_right"); - int base_wx_idx = vel_map.at("base_wx"); - int base_wy_idx = vel_map.at("base_wy"); - int base_wz_idx = vel_map.at("base_wz"); - int base_vx_idx = vel_map.at("base_vx"); - int base_vy_idx = vel_map.at("base_vy"); - int base_vz_idx = vel_map.at("base_vz"); + int pelvis_wx_idx = vel_map.at("pelvis_wx"); + int pelvis_wy_idx = vel_map.at("pelvis_wy"); + int pelvis_wz_idx = vel_map.at("pelvis_wz"); + int pelvis_vx_idx = vel_map.at("pelvis_vx"); + int pelvis_vy_idx = vel_map.at("pelvis_vy"); + int pelvis_vz_idx = vel_map.at("pelvis_vz"); int hip_roll_leftdot_idx = vel_map.at("hip_roll_leftdot"); int hip_roll_rightdot_idx = vel_map.at("hip_roll_rightdot"); int hip_yaw_leftdot_idx = vel_map.at("hip_yaw_leftdot"); @@ -467,9 +467,9 @@ void DoMain(double duration, double stride_length, double ground_incline, double s = 1; // scale everything together // Dynamic constraints options_list[i].setDynConstraintScaling( - {base_qw_idx, base_qx_idx, base_qy_idx, base_qz_idx}, s * 1.0 / 30.0); + {pelvis_qw_idx, pelvis_qx_idx, pelvis_qy_idx, pelvis_qz_idx}, s * 1.0 / 30.0); options_list[i].setDynConstraintScaling( - {base_x_idx, base_y_idx, base_z_idx, hip_roll_left_idx, + {pelvis_x_idx, pelvis_y_idx, pelvis_z_idx, hip_roll_left_idx, hip_roll_right_idx, hip_yaw_left_idx, hip_yaw_right_idx, hip_pitch_left_idx, hip_pitch_right_idx, knee_left_idx, knee_right_idx, ankle_joint_left_idx, ankle_joint_right_idx}, @@ -477,8 +477,8 @@ void DoMain(double duration, double stride_length, double ground_incline, options_list[i].setDynConstraintScaling({toe_left_idx, toe_right_idx}, s * 1.0 / 300.0); options_list[i].setDynConstraintScaling( - {n_q + base_wx_idx, n_q + base_wy_idx, n_q + base_wz_idx, - n_q + base_vx_idx, n_q + base_vy_idx, n_q + base_vz_idx, + {n_q + pelvis_wx_idx, n_q + pelvis_wy_idx, n_q + pelvis_wz_idx, + n_q + pelvis_vx_idx, n_q + pelvis_vy_idx, n_q + pelvis_vz_idx, n_q + hip_roll_leftdot_idx, n_q + hip_roll_rightdot_idx, n_q + hip_yaw_leftdot_idx, n_q + hip_yaw_rightdot_idx}, s * 1.0 / 600.0); @@ -503,9 +503,9 @@ void DoMain(double duration, double stride_length, double ground_incline, s * 20); // Impact constraints options_list[i].setImpConstraintScaling( - {base_wx_idx, base_wy_idx, base_wz_idx}, s / 50.0); + {pelvis_wx_idx, pelvis_wy_idx, pelvis_wz_idx}, s / 50.0); options_list[i].setImpConstraintScaling( - {base_vx_idx, base_vy_idx, base_vz_idx}, s / 300.0); + {pelvis_vx_idx, pelvis_vy_idx, pelvis_vz_idx}, s / 300.0); options_list[i].setImpConstraintScaling( {hip_roll_leftdot_idx, hip_roll_rightdot_idx}, s / 24.0); options_list[i].setImpConstraintScaling( @@ -577,23 +577,23 @@ void DoMain(double duration, double stride_length, double ground_incline, } // x position constraint - prog.AddBoundingBoxConstraint(0, 0, x0(pos_map.at("base_x"))); + prog.AddBoundingBoxConstraint(0, 0, x0(pos_map.at("pelvis_x"))); prog.AddBoundingBoxConstraint(stride_length, stride_length, - xf(pos_map.at("base_x"))); + xf(pos_map.at("pelvis_x"))); // height constraint - // prog.AddLinearConstraint(x0(pos_map.at("base_z")) == 1); - // prog.AddLinearConstraint(xf(pos_map.at("base_z")) == 1.1); + // prog.AddLinearConstraint(x0(pos_map.at("pelvis_z")) == 1); + // prog.AddLinearConstraint(xf(pos_map.at("pelvis_z")) == 1.1); // initial pelvis position - // prog.AddLinearConstraint(x0(pos_map.at("base_y")) == 0); + // prog.AddLinearConstraint(x0(pos_map.at("pelvis_y")) == 0); // pelvis pose constraints - // prog.AddConstraintToAllKnotPoints(x(pos_map.at("base_qw")) == - // 1); prog.AddConstraintToAllKnotPoints(x(pos_map.at("base_qx")) + // prog.AddConstraintToAllKnotPoints(x(pos_map.at("pelvis_qw")) == + // 1); prog.AddConstraintToAllKnotPoints(x(pos_map.at("pelvis_qx")) // == 0); - // prog.AddConstraintToAllKnotPoints(x(pos_map.at("base_qy")) == - // 0); prog.AddConstraintToAllKnotPoints(x(pos_map.at("base_qz")) + // prog.AddConstraintToAllKnotPoints(x(pos_map.at("pelvis_qy")) == + // 0); prog.AddConstraintToAllKnotPoints(x(pos_map.at("pelvis_qz")) // == 0); // start/end velocity constraints @@ -601,32 +601,32 @@ void DoMain(double duration, double stride_length, double ground_incline, // prog.AddLinearConstraint(xf.tail(n_v) == VectorXd::Zero(n_v)); // Floating base periodicity - prog.AddLinearConstraint(x0(pos_map.at("base_qw")) == - xf(pos_map.at("base_qw"))); - prog.AddLinearConstraint(x0(pos_map.at("base_qx")) == - -xf(pos_map.at("base_qx"))); - prog.AddLinearConstraint(x0(pos_map.at("base_qy")) == - xf(pos_map.at("base_qy"))); - prog.AddLinearConstraint(x0(pos_map.at("base_qz")) == - -xf(pos_map.at("base_qz"))); - prog.AddLinearConstraint(x0(pos_map.at("base_y")) == - -xf(pos_map.at("base_y"))); + prog.AddLinearConstraint(x0(pos_map.at("pelvis_qw")) == + xf(pos_map.at("pelvis_qw"))); + prog.AddLinearConstraint(x0(pos_map.at("pelvis_qx")) == + -xf(pos_map.at("pelvis_qx"))); + prog.AddLinearConstraint(x0(pos_map.at("pelvis_qy")) == + xf(pos_map.at("pelvis_qy"))); + prog.AddLinearConstraint(x0(pos_map.at("pelvis_qz")) == + -xf(pos_map.at("pelvis_qz"))); + prog.AddLinearConstraint(x0(pos_map.at("pelvis_y")) == + -xf(pos_map.at("pelvis_y"))); if (ground_incline == 0) { - prog.AddLinearConstraint(x0(pos_map.at("base_z")) == - xf(pos_map.at("base_z"))); + prog.AddLinearConstraint(x0(pos_map.at("pelvis_z")) == + xf(pos_map.at("pelvis_z"))); } - prog.AddLinearConstraint(x0(n_q + vel_map.at("base_wx")) == - xf(n_q + vel_map.at("base_wx"))); - prog.AddLinearConstraint(x0(n_q + vel_map.at("base_wy")) == - -xf(n_q + vel_map.at("base_wy"))); - prog.AddLinearConstraint(x0(n_q + vel_map.at("base_wz")) == - xf(n_q + vel_map.at("base_wz"))); - prog.AddLinearConstraint(x0(n_q + vel_map.at("base_vx")) == - xf(n_q + vel_map.at("base_vx"))); - prog.AddLinearConstraint(x0(n_q + vel_map.at("base_vy")) == - -xf(n_q + vel_map.at("base_vy"))); - prog.AddLinearConstraint(x0(n_q + vel_map.at("base_vz")) == - xf(n_q + vel_map.at("base_vz"))); + prog.AddLinearConstraint(x0(n_q + vel_map.at("pelvis_wx")) == + xf(n_q + vel_map.at("pelvis_wx"))); + prog.AddLinearConstraint(x0(n_q + vel_map.at("pelvis_wy")) == + -xf(n_q + vel_map.at("pelvis_wy"))); + prog.AddLinearConstraint(x0(n_q + vel_map.at("pelvis_wz")) == + xf(n_q + vel_map.at("pelvis_wz"))); + prog.AddLinearConstraint(x0(n_q + vel_map.at("pelvis_vx")) == + xf(n_q + vel_map.at("pelvis_vx"))); + prog.AddLinearConstraint(x0(n_q + vel_map.at("pelvis_vy")) == + -xf(n_q + vel_map.at("pelvis_vy"))); + prog.AddLinearConstraint(x0(n_q + vel_map.at("pelvis_vz")) == + xf(n_q + vel_map.at("pelvis_vz"))); // The legs joint positions/velocities/torque should be mirrored between legs // (notice that hip yaw and roll should be asymmetric instead of symmetric.) @@ -719,7 +719,7 @@ void DoMain(double duration, double stride_length, double ground_incline, prog.AddConstraint(right_foot_constraint_z, x_mid.head(n_q)); // Optional -- constraint on initial floating base - prog.AddConstraint(x0(pos_map.at("base_qw")) == 1); + prog.AddConstraint(x0(pos_map.at("pelvis_qw")) == 1); // Optional -- constraint on the forces magnitude /*for (unsigned int mode = 0; mode < num_time_samples.size(); mode++) { for (int index = 0; index < num_time_samples[mode]; index++) { @@ -774,7 +774,7 @@ void DoMain(double duration, double stride_length, double ground_incline, trajopt->ScaleTimeVariables(0.008); // state trajopt->ScaleStateVariables( - {base_qw_idx, base_qx_idx, base_qy_idx, base_qz_idx}, 0.5); + {pelvis_qw_idx, pelvis_qx_idx, pelvis_qy_idx, pelvis_qz_idx}, 0.5); if (s_q_toe > 1) { trajopt->ScaleStateVariables({toe_left_idx, toe_right_idx}, s_q_toe); } @@ -882,7 +882,7 @@ void DoMain(double duration, double stride_length, double ground_incline, } if (w_q_quat_xyz) { for (int i = 0; i < N; i++) { - auto q = trajopt->state(i).segment(base_qx_idx, 3); + auto q = trajopt->state(i).segment(pelvis_qx_idx, 3); prog.AddCost(w_q_quat_xyz * q.transpose() * q); } } @@ -953,23 +953,23 @@ void DoMain(double duration, double stride_length, double ground_incline, // initial condition for post impact velocity auto vp_var = trajopt->v_post_impact_vars_by_mode(0); prog.SetInitialGuess( - vp_var(vel_map.at("base_wx")), - prog.GetInitialGuess(x0(n_q + vel_map.at("base_wx")))); + vp_var(vel_map.at("pelvis_wx")), + prog.GetInitialGuess(x0(n_q + vel_map.at("pelvis_wx")))); prog.SetInitialGuess( - vp_var(vel_map.at("base_wy")), - -prog.GetInitialGuess(x0(n_q + vel_map.at("base_wy")))); + vp_var(vel_map.at("pelvis_wy")), + -prog.GetInitialGuess(x0(n_q + vel_map.at("pelvis_wy")))); prog.SetInitialGuess( - vp_var(vel_map.at("base_wz")), - prog.GetInitialGuess(x0(n_q + vel_map.at("base_wz")))); + vp_var(vel_map.at("pelvis_wz")), + prog.GetInitialGuess(x0(n_q + vel_map.at("pelvis_wz")))); prog.SetInitialGuess( - vp_var(vel_map.at("base_vx")), - prog.GetInitialGuess(x0(n_q + vel_map.at("base_vx")))); + vp_var(vel_map.at("pelvis_vx")), + prog.GetInitialGuess(x0(n_q + vel_map.at("pelvis_vx")))); prog.SetInitialGuess( - vp_var(vel_map.at("base_vy")), - -prog.GetInitialGuess(x0(n_q + vel_map.at("base_vy")))); + vp_var(vel_map.at("pelvis_vy")), + -prog.GetInitialGuess(x0(n_q + vel_map.at("pelvis_vy")))); prog.SetInitialGuess( - vp_var(vel_map.at("base_vz")), - prog.GetInitialGuess(x0(n_q + vel_map.at("base_vz")))); + vp_var(vel_map.at("pelvis_vz")), + prog.GetInitialGuess(x0(n_q + vel_map.at("pelvis_vz")))); for (auto l_r_pair : l_r_pairs) { for (unsigned int i = 0; i < asy_joint_names.size(); i++) { // velocities @@ -994,13 +994,13 @@ void DoMain(double duration, double stride_length, double ground_incline, // produces NAN value in some calculation. for (int i = 0; i < N; i++) { auto xi = trajopt->state(i); - if ((prog.GetInitialGuess(xi.segment<4>(base_qw_idx)).norm() == + if ((prog.GetInitialGuess(xi.segment<4>(pelvis_qw_idx)).norm() == 0) || std::isnan(prog.GetInitialGuess( - xi.segment<4>(base_qw_idx)).norm())) { - prog.SetInitialGuess(xi(pos_map.at("base_qw")), 1); - prog.SetInitialGuess(xi(pos_map.at("base_qx")), 0); - prog.SetInitialGuess(xi(pos_map.at("base_qy")), 0); - prog.SetInitialGuess(xi(pos_map.at("base_qz")), 0); + xi.segment<4>(pelvis_qw_idx)).norm())) { + prog.SetInitialGuess(xi(pos_map.at("pelvis_qw")), 1); + prog.SetInitialGuess(xi(pos_map.at("pelvis_qx")), 0); + prog.SetInitialGuess(xi(pos_map.at("pelvis_qy")), 0); + prog.SetInitialGuess(xi(pos_map.at("pelvis_qz")), 0); } } @@ -1200,7 +1200,7 @@ void DoMain(double duration, double stride_length, double ground_incline, // add cost on quaternion double cost_q_quat_xyz = 0; for (int i = 0; i < N; i++) { - auto q = result.GetSolution(trajopt->state(i).segment(base_qx_idx, 3)); + auto q = result.GetSolution(trajopt->state(i).segment(pelvis_qx_idx, 3)); cost_q_quat_xyz += w_q_quat_xyz * q.transpose() * q; } total_cost += cost_q_quat_xyz; diff --git a/examples/Cassie/visualize_trajectory.cc b/examples/Cassie/visualize_trajectory.cc index ca9e4293f3..83a5f60d2f 100644 --- a/examples/Cassie/visualize_trajectory.cc +++ b/examples/Cassie/visualize_trajectory.cc @@ -72,9 +72,9 @@ int DoMain() { auto mirrored_traj = saved_traj.ReconstructMirrorStateTrajectory(optimal_traj.end_time()); VectorXd x_offset = VectorXd::Zero(nx); - x_offset(pos_map["base_x"]) = - optimal_traj.value(optimal_traj.end_time())(pos_map["base_x"]) - - optimal_traj.value(optimal_traj.start_time())(pos_map["base_x"]); + x_offset(pos_map["pelvis_x"]) = + optimal_traj.value(optimal_traj.end_time())(pos_map["pelvis_x"]) - + optimal_traj.value(optimal_traj.start_time())(pos_map["pelvis_x"]); std::vector x_offset_rep(mirrored_traj.get_segment_times().size(), x_offset); PiecewisePolynomial x_offset_traj = @@ -82,9 +82,9 @@ int DoMain() { mirrored_traj.get_segment_times(), x_offset_rep); optimal_traj.ConcatenateInTime(mirrored_traj + x_offset_traj); - x_offset(pos_map["base_x"]) = - optimal_traj.value(optimal_traj.end_time())(pos_map["base_x"]) - - optimal_traj.value(optimal_traj.start_time())(pos_map["base_x"]); + x_offset(pos_map["pelvis_x"]) = + optimal_traj.value(optimal_traj.end_time())(pos_map["pelvis_x"]) - + optimal_traj.value(optimal_traj.start_time())(pos_map["pelvis_x"]); x_offset_rep = std::vector( optimal_traj.get_segment_times().size(), x_offset); diff --git a/multibody/test/geom_geom_collider_test.cc b/multibody/test/geom_geom_collider_test.cc index bcee569344..09050b0af5 100644 --- a/multibody/test/geom_geom_collider_test.cc +++ b/multibody/test/geom_geom_collider_test.cc @@ -74,12 +74,12 @@ void GeomGeomColliderTest() { q(q_map.at("finger_base_to_upper_joint_240")) = 0; q(q_map.at("finger_upper_to_middle_joint_240")) = -1; q(q_map.at("finger_middle_to_lower_joint_240")) = -1.5; - q(q_map.at("base_qw")) = 1; - q(q_map.at("base_qx")) = 0; - q(q_map.at("base_qz")) = 0; - q(q_map.at("base_x")) = 0; - q(q_map.at("base_y")) = 0; - q(q_map.at("base_z")) = .05; + q(q_map.at("cube_qw")) = 1; + q(q_map.at("cube_qx")) = 0; + q(q_map.at("cube_qz")) = 0; + q(q_map.at("cube_x")) = 0; + q(q_map.at("cube_y")) = 0; + q(q_map.at("cube_z")) = .05; plant.SetPositions(&context, q); diff --git a/systems/trajectory_optimization/dircon_opt_constraints.cc b/systems/trajectory_optimization/dircon_opt_constraints.cc index 4d0f6866df..f382e347f7 100644 --- a/systems/trajectory_optimization/dircon_opt_constraints.cc +++ b/systems/trajectory_optimization/dircon_opt_constraints.cc @@ -53,10 +53,13 @@ DirconDynamicConstraint::DirconDynamicConstraint( // is located at the first four element of the generalized position if (is_quaternion) { map positions_map = multibody::MakeNameToPositionsMap(plant); - DRAKE_DEMAND(positions_map.at("base_qw") == 0); - DRAKE_DEMAND(positions_map.at("base_qx") == 1); - DRAKE_DEMAND(positions_map.at("base_qy") == 2); - DRAKE_DEMAND(positions_map.at("base_qz") == 3); + auto floating_bodies = plant.GetFloatingBaseBodies(); + const auto& body = plant.get_body(*floating_bodies.begin()); + std::string name = body.name(); + DRAKE_DEMAND(positions_map.at(name + "_qw") == 0); + DRAKE_DEMAND(positions_map.at(name + "_qx") == 1); + DRAKE_DEMAND(positions_map.at(name + "_qy") == 2); + DRAKE_DEMAND(positions_map.at(name + "_qz") == 3); } } From 02037e224ded91fd99a6120f0c9cf2eec0db79b7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Nov 2023 13:12:39 -0500 Subject: [PATCH 534/758] more changes --- .../osc_run/osc_running_qp_settings.yaml | 2 +- multibody/multipose_visualizer.cc | 3 - .../osc/operational_space_control.cc | 65 +++++++++++-------- .../osc/operational_space_control.h | 13 ++-- systems/robot_lcm_systems.cc | 1 + 5 files changed, 48 insertions(+), 36 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 9dd7eaf13a..5cf72f59b4 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 500 + max_iter: 250 linsys_solver: 0 verbose: 0 warm_start: 1 diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index 1298ec060d..d921100430 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -2,9 +2,7 @@ #include "drake/geometry/scene_graph.h" #include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -using drake::geometry::DrakeVisualizer; using drake::geometry::Meshcat; using drake::geometry::SceneGraph; using drake::multibody::MultibodyPlant; @@ -39,7 +37,6 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, std::tie(plant_, scene_graph) = drake::multibody::AddMultibodyPlantSceneGraph(&builder, 0.0); - auto lcm = builder.AddSystem(); Parser parser(plant_, scene_graph, "pose_trace"); parser.SetAutoRenaming(true); // Add num_poses copies of the plant, giving each a unique name diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index e82fff0fed..41080cfa4e 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -125,11 +125,13 @@ OperationalSpaceControl::OperationalSpaceControl( u_min_ = u_min; u_max_ = u_max; - VectorXd ddq_min(n_q_); - VectorXd ddq_max(n_q_); + VectorXd ddq_min = VectorXd::Zero(n_q_); + VectorXd ddq_max = VectorXd::Zero(n_q_); for (JointIndex i(0); i < n_q_; ++i) { - ddq_min[i] = plant_wo_spr_.get_joint(i).acceleration_lower_limits()[0]; - ddq_max[i] = plant_wo_spr_.get_joint(i).acceleration_upper_limits()[0]; + if (plant_wo_spr_.get_joint(i).acceleration_lower_limits().size() != 0) { + ddq_min[i] = plant_wo_spr_.get_joint(i).acceleration_lower_limits()[0]; + ddq_max[i] = plant_wo_spr_.get_joint(i).acceleration_upper_limits()[0]; + } } ddq_min_ = ddq_min; ddq_max_ = ddq_max; @@ -321,12 +323,12 @@ void OperationalSpaceControl::Build() { : kinematic_evaluators_->count_full(); n_c_ = kSpaceDim * all_contacts_.size(); - n_ee_ = 0; + n_lambda_ext_ = 0; for (auto& force_tracking_data : *force_tracking_data_vec_) { - n_ee_ += force_tracking_data->GetLambdaDim(); + n_lambda_ext_ += force_tracking_data->GetLambdaDim(); } - std::cout << "num contact forces" << n_ee_ << std::endl; + std::cout << "num contact forces" << n_lambda_ext_ << std::endl; n_c_active_ = 0; for (auto evaluator : all_contacts_) { @@ -350,14 +352,14 @@ void OperationalSpaceControl::Build() { u_sol_ = std::make_unique(n_u_); lambda_c_sol_ = std::make_unique(n_c_); lambda_h_sol_ = std::make_unique(n_h_); - lambda_ee_sol_ = std::make_unique(n_ee_); + lambda_ext_sol_ = std::make_unique(n_lambda_ext_); epsilon_sol_ = std::make_unique(n_c_active_); u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); - lambda_ee_sol_->setZero(); + lambda_ext_sol_->setZero(); u_prev_->setZero(); // Add decision variables @@ -365,7 +367,7 @@ void OperationalSpaceControl::Build() { u_ = prog_->NewContinuousVariables(n_u_, "u"); lambda_c_ = prog_->NewContinuousVariables(n_c_, "lambda_contact"); lambda_h_ = prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); - lambda_ee_ = prog_->NewContinuousVariables(n_ee_, "lambda_ee"); + lambda_ext_ = prog_->NewContinuousVariables(n_lambda_ext_, "lambda_ee"); epsilon_ = prog_->NewContinuousVariables(n_c_active_, "epsilon"); // Add constraints @@ -373,8 +375,9 @@ void OperationalSpaceControl::Build() { dynamics_constraint_ = prog_ ->AddLinearEqualityConstraint( - MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_ee_), - VectorXd::Zero(n_v_), {dv_, lambda_c_, lambda_h_, u_, lambda_ee_}) + MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_lambda_ext_), + VectorXd::Zero(n_v_), + {dv_, lambda_c_, lambda_h_, u_, lambda_ext_}) .evaluator() .get(); // 2. Holonomic constraint @@ -474,11 +477,12 @@ void OperationalSpaceControl::Build() { } // 3. external force cost for (auto& force_tracking_data : *force_tracking_data_vec_) { - lambda_ee_cost_ = prog_ - ->AddQuadraticCost(MatrixXd::Zero(n_ee_, n_ee_), - VectorXd::Zero(n_ee_), lambda_ee_) - .evaluator() - .get(); + lambda_ext_cost_ = + prog_ + ->AddQuadraticCost(MatrixXd::Zero(n_lambda_ext_, n_lambda_ext_), + VectorXd::Zero(n_lambda_ext_), lambda_ext_) + .evaluator() + .get(); } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { @@ -666,13 +670,17 @@ VectorXd OperationalSpaceControl::SolveQp( /// M*dv + bias == J_c^T*lambda_c + J_h^T*lambda_h + B*u /// -> M*dv - J_c^T*lambda_c - J_h^T*lambda_h - B*u == - bias /// -> [M, -J_c^T, -J_h^T, -B]*[dv, lambda_c, lambda_h, u]^T = - bias - MatrixXd A_dyn = MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_ee_); + MatrixXd A_dyn = + MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_lambda_ext_); A_dyn.block(0, 0, n_v_, n_v_) = M; A_dyn.block(0, n_v_, n_v_, n_c_) = -J_c.transpose(); A_dyn.block(0, n_v_ + n_c_, n_v_, n_h_) = -J_h.transpose(); A_dyn.block(0, n_v_ + n_c_ + n_h_, n_v_, n_u_) = -B; - MatrixXd J_ee = force_tracking_data_vec_->at(0)->GetJ(); - A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_ee_) = J_ee.transpose(); + for (auto& force_tracking_data : *force_tracking_data_vec_) { + MatrixXd J_ee = force_tracking_data->GetJ(); + A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_lambda_ext_) = + J_ee.transpose(); + } dynamics_constraint_->UpdateCoefficients(A_dyn, -bias); // 2. Holonomic constraint /// JdotV_h + J_h*dv == 0 @@ -781,7 +789,7 @@ VectorXd OperationalSpaceControl::SolveQp( *context_wo_spr_, traj, t); const MatrixXd W = force_tracking_data->GetWeight(); const VectorXd lambda_des = force_tracking_data->GetLambdaDes(); - lambda_ee_cost_->UpdateCoefficients( + lambda_ext_cost_->UpdateCoefficients( 2 * W, -2 * W * lambda_des, lambda_des.transpose() * W * lambda_des); } @@ -872,7 +880,7 @@ VectorXd OperationalSpaceControl::SolveQp( *lambda_c_sol_ = result.GetSolution(lambda_c_); *lambda_h_sol_ = result.GetSolution(lambda_h_); *epsilon_sol_ = result.GetSolution(epsilon_); - *lambda_ee_sol_ = result.GetSolution(lambda_ee_); + *lambda_ext_sol_ = result.GetSolution(lambda_ext_); } else { *u_prev_ = 0.99 * *u_sol_ + VectorXd::Random(n_u_); } @@ -1022,8 +1030,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( if (lambda_c_cost_) { lambda_c_cost_->Eval(*lambda_c_sol_, &y_lambda_c_cost); } - if (lambda_ee_cost_) { - lambda_ee_cost_->Eval(*lambda_ee_sol_, &y_lambda_ee_cost); + if (lambda_ext_cost_) { + lambda_ext_cost_->Eval(*lambda_ext_sol_, &y_lambda_ee_cost); } if (lambda_h_cost_) { lambda_h_cost_->Eval(*lambda_h_sol_, &y_lambda_h_cost); @@ -1042,7 +1050,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( (soft_constraint_cost_ != nullptr) ? y_soft_constraint_cost[0] : 0; double lambda_c_cost = (lambda_c_cost_ != nullptr) ? y_lambda_c_cost[0] : 0; double lambda_h_cost = (lambda_h_cost_ != nullptr) ? y_lambda_h_cost[0] : 0; - double lambda_ee_cost = (lambda_ee_cost_ != nullptr) ? y_lambda_ee_cost[0] : 0; + double lambda_ee_cost = + (lambda_ext_cost_ != nullptr) ? y_lambda_ee_cost[0] : 0; // double joint_limit_cost = // (joint_limit_cost_ != nullptr) ? y_joint_limit_cost[0] : 0; @@ -1074,13 +1083,13 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.solve_time = solve_time_; qp_output.u_dim = n_u_; // qp_output.lambda_c_dim = n_c_; - qp_output.lambda_c_dim = n_ee_; + qp_output.lambda_c_dim = n_lambda_ext_; qp_output.lambda_h_dim = n_h_; qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); - // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ee_sol_); + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); + // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index f755a28f77..03d122d397 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -233,6 +233,11 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { with_input_constraints_ = constraint_status; } void SetAccelerationConstraints(bool constraint_status) { + if (ddq_max_.isZero() and constraint_status) { + throw std::runtime_error( + "Attempting to set acceleration limits when acceleration limits have " + "not been defined for the plant."); + } with_acceleration_constraints_ = constraint_status; } void SetContactFriction(double mu) { mu_ = mu; } @@ -371,7 +376,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Size of holonomic constraint and total/active contact constraints int n_h_; int n_c_; - int n_ee_; + int n_lambda_ext_; int n_c_active_; // Manually specified holonomic constraints (only valid for plants_wo_springs) @@ -417,7 +422,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::VectorXDecisionVariable u_; drake::solvers::VectorXDecisionVariable lambda_c_; drake::solvers::VectorXDecisionVariable lambda_h_; - drake::solvers::VectorXDecisionVariable lambda_ee_; + drake::solvers::VectorXDecisionVariable lambda_ext_; drake::solvers::VectorXDecisionVariable epsilon_; // Cost and constraints drake::solvers::LinearEqualityConstraint* dynamics_constraint_; @@ -432,7 +437,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::solvers::QuadraticCost* input_smoothing_cost_ = nullptr; drake::solvers::QuadraticCost* lambda_c_cost_ = nullptr; drake::solvers::QuadraticCost* lambda_h_cost_ = nullptr; - drake::solvers::QuadraticCost* lambda_ee_cost_ = nullptr; + drake::solvers::QuadraticCost* lambda_ext_cost_ = nullptr; drake::solvers::QuadraticCost* soft_constraint_cost_ = nullptr; // OSC solution @@ -440,7 +445,7 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::unique_ptr u_sol_; std::unique_ptr lambda_c_sol_; std::unique_ptr lambda_h_sol_; - std::unique_ptr lambda_ee_sol_; + std::unique_ptr lambda_ext_sol_; std::unique_ptr epsilon_sol_; std::unique_ptr u_prev_; mutable double solve_time_; diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index addf14479a..7aa12a9d12 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -16,6 +16,7 @@ using drake::multibody::JointActuatorIndex; using drake::multibody::JointIndex; using drake::multibody::MultibodyPlant; using drake::systems::Context; +using drake::systems::BasicVector; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using Eigen::VectorXd; From c4d938ec2a9922da646a6a0e7ed46ce9531c9f32 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 14 Nov 2023 15:00:19 -0500 Subject: [PATCH 535/758] tuning c3 controller --- .../osc_run/osc_running_qp_settings.yaml | 2 +- .../franka_c3_controller_params.yaml | 2 +- .../franka_c3_options_translation.yaml | 16 +++++++------- .../franka_osc_controller_params.yaml | 6 +++--- .../franka/parameters/franka_sim_params.yaml | 4 ++-- solvers/c3.cc | 21 +++++++------------ systems/controllers/c3_controller.cc | 19 +++++++++++------ systems/controllers/c3_controller.h | 1 + .../osc/operational_space_control.cc | 4 ++-- .../lcm_trajectory_systems.cc | 6 +++--- 10 files changed, 42 insertions(+), 39 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 5cf72f59b4..639eca37a0 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 250 + max_iter: 1000 linsys_solver: 0 verbose: 0 warm_start: 1 diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index c1c5eadec1..9744504a33 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -15,7 +15,7 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 80 +target_frequency: 100 neutral_position: [0.55, 0, 0.45] x_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 12a82c221b..40e85a01fb 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -1,6 +1,6 @@ -admm_iter: 3 +admm_iter: 4 rho: 0.1 -rho_scale: 2 +rho_scale: 1 num_threads: 6 delta_option: 1 # options are 'MIQP' or 'QP' @@ -10,19 +10,19 @@ contact_model: 'stewart_and_trinkle' mu: 0.4 mu_plate: 0.4 -dt: 0.1 +dt: 0.03 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 N: 5 # matrix scaling -w_Q: 50 -w_R: 0.0001 +w_Q: 20 +w_R: 0 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar -w_U: 1 +w_U: 0.5 # n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions # size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle @@ -32,8 +32,8 @@ u_size: 40 #g_size: 34 #u_size: 34 # State Tracking Error, assuming diagonal -q_vector: [100, 100, 5000, 100, 100, 100, 100, 10000, 10000, 10000, - 1, 1, 1, 1, 1, 1, 1, 1, 1] +q_vector: [100, 100, 500, 100, 100, 100, 100, 10000, 10000, 10000, + 5, 5, 5, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 77ceeea5e9..b1fb5adb52 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [0.001, 0, 0, - 0, 0.001, 0, - 0, 0, 0.001] + [0.1, 0, 0, + 0, 0.1, 0, + 0, 0, 0.1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index a52ac2471d..b3b4cc7cc5 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf publish_rate: 1000 publish_efforts: true actuator_delay: 0.000 -visualize: true +visualize: false tool_attachment_frame: [0, 0, 0.107] @@ -19,5 +19,5 @@ q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, -0.03, 0.430] +q_init_plate: [1, 0, 0, 0, 0.56, 0.03, 0.430] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/solvers/c3.cc b/solvers/c3.cc index 87c3817593..b576659f98 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -142,11 +142,6 @@ vector C3::Solve(const VectorXd& x0, vector& delta, } vector zfin = SolveQP(x0, Gv, WD); - - // auto z0 = zfin[0]; - - // return z.segment(n_ + m_, k_); - // return z0; return zfin; } @@ -222,14 +217,14 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, } // /// initialize decision variables to warm start - // if (warm_start_){ - // for (int i = 0; i < N_; i++){ - // prog_.SetInitialGuess(x_[i], warm_start_x_[i]); - // prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[i]); - // prog_.SetInitialGuess(u_[i], warm_start_u_[i]); - // } - // prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); - // } +// if (warm_start_) { +// for (int i = 0; i < N_; i++) { +// prog_.SetInitialGuess(x_[i], warm_start_x_[i]); +// prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[i]); +// prog_.SetInitialGuess(u_[i], warm_start_u_[i]); +// } +// prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); +// } prog_.SetSolverOptions(solver_options_); MathematicalProgramResult result = osqp_.Solve(prog_); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index a9891fa3ec..621e2977eb 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -106,6 +106,8 @@ C3Controller::C3Controller( drake::systems::EventStatus C3Controller::ComputePlan( const Context& context, DiscreteValues* discrete_state) const { + auto start = std::chrono::high_resolution_clock::now(); + const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const FrankaKinematicsVector* lcs_x = @@ -170,7 +172,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( for (int i : vector({0, 2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.3, 0.7, 1); + c3_->AddLinearConstraint(A, 0.2, 0.7, 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); @@ -182,14 +184,19 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, -5, 5, 2); } -// for (int i : vector({2})) { -// Eigen::RowVectorXd A = VectorXd::Zero(n_u_); -// A(i) = 1.0; -// c3_->AddLinearConstraint(A, 10, 20, 2); -// } + for (int i : vector({2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, 5, 20, 2); + } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); + auto finish = std::chrono::high_resolution_clock::now(); delta_ = delta; w_ = w; + auto elapsed = finish - start; + solve_time_ = + std::chrono::duration_cast(elapsed).count() / + 1e6; return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 6efae29fe0..84e137aafd 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -104,6 +104,7 @@ class C3Controller : public drake::systems::LeafSystem { mutable std::unique_ptr c3_; mutable std::vector delta_; mutable std::vector w_; + mutable double solve_time_; // std::unique_ptr lcs_; drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 41080cfa4e..f43c55625c 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1088,8 +1088,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); - // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); + // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index f0b87c0c88..c6addb787f 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -55,7 +55,9 @@ void LcmTrajectoryReceiver::OutputTrajectory( const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); if (trajectory_block.datapoints.rows() == 3) { - *casted_traj = PiecewisePolynomial::FirstOrderHold( +// *casted_traj = PiecewisePolynomial::FirstOrderHold( +// trajectory_block.time_vector, trajectory_block.datapoints); + *casted_traj = PiecewisePolynomial::ZeroOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); } else { *casted_traj = PiecewisePolynomial::CubicHermite( @@ -133,8 +135,6 @@ LcmTrajectoryDrawer::LcmTrajectoryDrawer( drake::Value{}) .get_index(); - // lcm_traj_ = - // LcmTrajectory(dairlib::FindResourceOrThrow(default_trajectory_path_)); DeclarePerStepDiscreteUpdateEvent(&LcmTrajectoryDrawer::DrawTrajectory); } From 1cd6ff8507506902353b6b27c0cafc9693012e29 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 15 Nov 2023 10:56:45 -0500 Subject: [PATCH 536/758] adding nav_msgs as ROS message type --- tools/workspace/ros/compile_ros_workspace.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/tools/workspace/ros/compile_ros_workspace.sh b/tools/workspace/ros/compile_ros_workspace.sh index 3602b80430..e95b6bc464 100755 --- a/tools/workspace/ros/compile_ros_workspace.sh +++ b/tools/workspace/ros/compile_ros_workspace.sh @@ -10,7 +10,7 @@ cd $(dirname "$BASH_SOURCE") set -e -PACKAGES="roscpp rospy franka_msgs sensor_msgs" +PACKAGES="roscpp rospy franka_msgs sensor_msgs nav_msgs" # You can add any published ros packages you need to this list. # Local ROS packages should be their own bazel local_repository From dde03a0f033a2b7688556a82fa6b21886392f3cc Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 15 Nov 2023 10:57:06 -0500 Subject: [PATCH 537/758] updating ros lcm bridge to include tray state --- examples/franka/franka_ros_lcm_bridge.cc | 4 +-- .../franka_osc_controller_params.yaml | 2 +- systems/ros/franka_ros_lcm_conversions.cc | 29 ++++++++++++------- systems/ros/franka_ros_lcm_conversions.h | 2 -- .../ros/parameters/franka_ros_channels.yaml | 2 +- 5 files changed, 22 insertions(+), 17 deletions(-) diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index ac049c3c94..259b57f4ac 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -22,7 +22,7 @@ #include "franka_msgs/FrankaState.h" #include "ros/ros.h" #include "sensor_msgs/JointState.h" -#include "std_msgs/Float64MultiArray.h" +#include "nav_msgs/Odometry.h" #include "systems/robot_lcm_systems.h" #include "systems/ros/franka_ros_lcm_conversions.h" #include "systems/ros/parameters/franka_ros_channels.h" @@ -114,7 +114,7 @@ int DoMain(int argc, char* argv[]) { /* -------------------------------------------------------------------------------------------*/ auto tray_object_state_ros_subscriber = - builder.AddSystem(RosSubscriberSystem::Make( + builder.AddSystem(RosSubscriberSystem::Make( ros_channel_params.tray_state_channel, &node_handle)); auto ros_to_lcm_object_state = builder.AddSystem( RosToLcmObjectState::Make(plant, tray_index, "tray")); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index b1fb5adb52..c8535f796c 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/systems/ros/franka_ros_lcm_conversions.cc b/systems/ros/franka_ros_lcm_conversions.cc index e28ab8c194..6aa78bf36e 100644 --- a/systems/ros/franka_ros_lcm_conversions.cc +++ b/systems/ros/franka_ros_lcm_conversions.cc @@ -1,8 +1,13 @@ #include "systems/ros/franka_ros_lcm_conversions.h" -//#include "franka_msgs/FrankaState.h" + #include +#include "franka_msgs/FrankaState.h" #include "multibody/multibody_utils.h" +#include "nav_msgs/Path.h" +#include "nav_msgs/Odometry.h" +#include "sensor_msgs/JointState.h" + namespace dairlib { namespace systems { @@ -298,24 +303,26 @@ RosToLcmObjectState::RosToLcmObjectState( object_state.position[0] = 1; this->DeclareAbstractOutputPort(object_name + "_state", object_state, &RosToLcmObjectState::ConvertToLCM); - this->DeclareAbstractInputPort("ROS Float64MultiArray", - drake::Value()); + this->DeclareAbstractInputPort("ROS PoseWithCovariance", + drake::Value()); } void RosToLcmObjectState::ConvertToLCM( const drake::systems::Context& context, dairlib::lcmt_object_state* object_state) const { const drake::AbstractValue* input = this->EvalAbstractInput(context, 0); - const auto& msg = input->get_value(); + const auto& msg = input->get_value(); - if (msg.data.empty()) { -// for (size_t i = 0; i < object_state->num_positions; i++) { -// object_state->position[i] = nan(""); -// } + if (msg.pose.pose.position.x == 0) { + // do nothing when there is no message, just keep the most recent message1 } else { - for (size_t i = 0; i < object_state->num_positions; i++) { - object_state->position[i] = msg.data[i]; - } + object_state->position[0] = msg.pose.pose.orientation.w; + object_state->position[1] = msg.pose.pose.orientation.x; + object_state->position[2] = msg.pose.pose.orientation.y; + object_state->position[3] = msg.pose.pose.orientation.z; + object_state->position[4] = msg.pose.pose.orientation.x; + object_state->position[5] = msg.pose.pose.orientation.y; + object_state->position[6] = msg.pose.pose.orientation.z; } object_state->utime = context.get_time() * 1e6; } diff --git a/systems/ros/franka_ros_lcm_conversions.h b/systems/ros/franka_ros_lcm_conversions.h index 95aace780b..791960ebb7 100644 --- a/systems/ros/franka_ros_lcm_conversions.h +++ b/systems/ros/franka_ros_lcm_conversions.h @@ -7,8 +7,6 @@ #include "dairlib/lcmt_estimated_object_state.hpp" #include "dairlib/lcmt_franka_state.hpp" #include "dairlib/lcmt_robot_output.hpp" -#include "franka_msgs/FrankaState.h" -#include "sensor_msgs/JointState.h" #include "std_msgs/Float64MultiArray.h" #include "systems/framework/output_vector.h" #include "systems/framework/timestamped_vector.h" diff --git a/systems/ros/parameters/franka_ros_channels.yaml b/systems/ros/parameters/franka_ros_channels.yaml index 0ee6a147c7..b60e08b698 100644 --- a/systems/ros/parameters/franka_ros_channels.yaml +++ b/systems/ros/parameters/franka_ros_channels.yaml @@ -1,5 +1,5 @@ franka_state_channel: /franka/joint_states -tray_state_channel: /franka/tray_object_state +tray_state_channel: /tagslam/odom/body_tray box_state_channel: /franka/box_object_state franka_input_channel: /franka/franka_input From eb31dd9c5ff25f9755d6e09026879f6ac6895b0d Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 15 Nov 2023 16:34:45 -0500 Subject: [PATCH 538/758] updating tray estimation slightly --- examples/franka/parameters/franka_sim_params.yaml | 2 +- systems/ros/franka_ros_lcm_conversions.cc | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b3b4cc7cc5..d11ebd59d7 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -15,7 +15,7 @@ tool_attachment_frame: [0, 0, 0.107] dt: 0.0005 realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] -q_init_franka: [-1.285, 1.6, 1.4, -2.08, 1.464, 1.43, -0.804] +q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] diff --git a/systems/ros/franka_ros_lcm_conversions.cc b/systems/ros/franka_ros_lcm_conversions.cc index 6aa78bf36e..67f1c96646 100644 --- a/systems/ros/franka_ros_lcm_conversions.cc +++ b/systems/ros/franka_ros_lcm_conversions.cc @@ -320,9 +320,9 @@ void RosToLcmObjectState::ConvertToLCM( object_state->position[1] = msg.pose.pose.orientation.x; object_state->position[2] = msg.pose.pose.orientation.y; object_state->position[3] = msg.pose.pose.orientation.z; - object_state->position[4] = msg.pose.pose.orientation.x; - object_state->position[5] = msg.pose.pose.orientation.y; - object_state->position[6] = msg.pose.pose.orientation.z; + object_state->position[4] = msg.pose.pose.position.x; + object_state->position[5] = msg.pose.pose.position.y; + object_state->position[6] = msg.pose.pose.position.z; } object_state->utime = context.get_time() * 1e6; } From b0f42787d9187895f716643857e7011b6d8c2748 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 16 Nov 2023 11:50:03 -0500 Subject: [PATCH 539/758] using lossy encoding scheme to record videos to greatly reduce file size --- record_video.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/record_video.py b/record_video.py index 2bd474b67f..71a04be89a 100644 --- a/record_video.py +++ b/record_video.py @@ -20,7 +20,7 @@ def main(): # determine log number curr_date = date.today().strftime("%m_%d_%y") year = date.today().strftime("%Y") - logdir = f"{os.getenv('HOME')}/Videos/cassie_experiments/{year}/{curr_date}/" + logdir = f"{os.getenv('HOME')}/Videos/franka_experiments/{year}/{curr_date}/" os.makedirs(logdir, exist_ok=True) current_logs = sorted(glob.glob(logdir + '*log_*')) if current_logs: @@ -33,7 +33,7 @@ def main(): for i, name in enumerate(dev_names): experiment_name = logdir + 'log_' + log_num + '_cam' + str(i) + '.mp4' # print(experiment_name) - cmd = ('ffmpeg -y -f alsa -i default -i ' + name + ' -vcodec libx264 -acodec aac -qp 0').split(' ') + cmd = ('ffmpeg -y -f v4l2 -r 30 -i ' + name).split(' ') cmd.append(experiment_name) print(' '.join(cmd)) cmds.append(cmd) From f26b2d170ba6bc9ed14f0a89ae7bbced22a167d3 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 16 Nov 2023 11:50:14 -0500 Subject: [PATCH 540/758] plotting updates for franka --- bindings/pydairlib/analysis/BUILD.bazel | 4 +- .../pydairlib/analysis/franka_plot_config.py | 2 + .../analysis/franka_plotting_utils.py | 2 +- .../pydairlib/analysis/log_plotter_franka.py | 49 ++++++++++++++++--- .../pydairlib/analysis/mbp_plotting_utils.py | 42 +++++++++++----- .../plot_configs/franka_translation_plot.yaml | 8 +-- 6 files changed, 82 insertions(+), 25 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index d0792adbea..04f0034f08 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -95,8 +95,8 @@ py_library( name = "franka_plotting_utils", srcs = ["franka_plotting_utils.py"], data = [ - "@lcm//:lcm-python", "@drake//manipulation/models/franka_description:models", + "@lcm//:lcm-python", ], deps = [ "//bindings/pydairlib/lcm", @@ -134,8 +134,8 @@ py_binary( ], deps = [ ":franka_plot_config", - "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/analysis:franka_plotting_utils", + "//bindings/pydairlib/analysis:mbp_plotting_utils", "//bindings/pydairlib/cassie:cassie_utils_py", "//bindings/pydairlib/common", "//bindings/pydairlib/common:plot_styler", diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py index abc9c15026..d566c87c70 100644 --- a/bindings/pydairlib/analysis/franka_plot_config.py +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -14,6 +14,7 @@ def __init__(self, filename): self.channel_u = data['channel_u'] self.channel_osc = data['channel_osc'] self.channel_c3 = data['channel_c3'] + self.channel_tray = data['channel_tray'] self.plot_style = data['plot_style'] self.start_time = data['start_time'] @@ -44,3 +45,4 @@ def __init__(self, filename): self.tracking_datas_to_plot = \ data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] self.plot_c3_debug = data['plot_c3_debug'] + self.plot_object_state = data['plot_object_state'] diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index bcbf504e04..de9f4e3a9f 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -22,7 +22,7 @@ franka_default_channels = \ {'FRANKA_STATE': dairlib.lcmt_robot_output, 'FRANKA_STATE_SIMULATION': dairlib.lcmt_robot_output, - # 'TRAY_STATE': dairlib.lcmt_robot_output, + 'TRAY_STATE': dairlib.lcmt_object_state, 'FRANKA_INPUT': dairlib.lcmt_robot_input, 'OSC_FRANKA': dairlib.lcmt_robot_input, 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 5d5f6b2e25..7ed7d6d69d 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -22,6 +22,7 @@ def main(): channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc channel_c3 = plot_config.channel_c3 + channel_tray = plot_config.channel_tray if plot_config.plot_style == "paper": plot_styler.PlotStyler.set_default_styling() @@ -35,6 +36,10 @@ def main(): pos_map, vel_map, act_map = mbp_plots.make_name_to_mbp_maps(franka_plant) pos_names, vel_names, act_names = mbp_plots.make_mbp_name_vectors( franka_plant) + tray_pos_map, tray_vel_map, _ = mbp_plots.make_name_to_mbp_maps(tray_plant) + + tray_pos_names, tray_vel_names, _ = mbp_plots.make_mbp_name_vectors( + tray_plant) ''' Read the log ''' filename = sys.argv[1] @@ -55,9 +60,18 @@ def main(): plot_config.duration, mbp_plots.load_c3_debug, channel_c3) + # processing callback arguments + if plot_config.plot_object_state: + object_state = get_log_data(log, default_channels, + plot_config.start_time, + plot_config.duration, + mbp_plots.load_object_state, + channel_tray) + t_object_slice = slice(object_state['t'].size) + print('Finished processing log - making plots') # Define x time slice - t_x_slice = slice(robot_output['t_x'].size) + t_x_slice = slice(robot_output['t'].size) t_osc_slice = slice(osc_debug['t_osc'].size) print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) @@ -102,25 +116,29 @@ def main(): mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, franka_context, ['plate'], {'plate': np.zeros(3)}, - {'plate': [0, 1, 2]}, ps=end_effector_plotter, + {'plate': [0, 1, 2]}, + ps=end_effector_plotter, subplot_index=0) mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, franka_context, ['plate'], {'plate': np.zeros(3)}, - {'plate': [0, 1, 2]}, ps=end_effector_plotter, + {'plate': [0, 1, 2]}, + ps=end_effector_plotter, subplot_index=1) ''' Plot Efforts ''' effort_plotter = plot_styler.PlotStyler(nrows=2) if plot_config.plot_measured_efforts: plot = mbp_plots.plot_measured_efforts(robot_output, act_names, - t_x_slice, effort_plotter, subplot_index=0) + t_x_slice, effort_plotter, + subplot_index=0) plot.fig.axes[0].set_ylim(franka_joint_actuator_limit_range) if plot_config.plot_commanded_efforts: plot = mbp_plots.plot_commanded_efforts(robot_input, act_names, - t_osc_slice, effort_plotter, subplot_index=1) + t_osc_slice, effort_plotter, + subplot_index=1) plot.fig.axes[1].set_ylim(franka_joint_actuator_limit_range) if plot_config.act_names: @@ -137,9 +155,14 @@ def main(): plot = mbp_plots.plot_qp_costs(osc_debug, t_osc_slice) if plot_config.plot_qp_solutions: - plot = mbp_plots.plot_ddq_sol(osc_debug, t_osc_slice, pos_names, slice(0, 7)) - # plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 12)) - # plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, 6)) + plot = mbp_plots.plot_ddq_sol(osc_debug, t_osc_slice, pos_names, + slice(0, 7)) + plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, + t_x_slice) + # plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, + # 12)) + # plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, + # 6)) if plot_config.tracking_datas_to_plot: for traj_name, config in plot_config.tracking_datas_to_plot.items(): @@ -161,6 +184,16 @@ def main(): plot_config.fsm_state_names) # plot.save_fig('active_tracking_datas.png') + if plot_config.plot_object_state: + plot = mbp_plots.plot_positions_by_name(object_state, + tray_pos_names[4:], + t_object_slice, tray_pos_map) + # plot.save_fig(('/').join(filename.split('/')[-2:]) + '/object_position') + if plot_config.plot_object_state: + plot = mbp_plots.plot_positions_by_name(object_state, + tray_pos_names[:4], + t_object_slice, tray_pos_map) + plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 82a4441b4a..5c7791f3db 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -58,7 +58,7 @@ def make_joint_order_permutations(robot_output_message, plant): def process_state_channel(state_data, plant): - t_x = [] + t = [] q = [] u = [] v = [] @@ -80,9 +80,9 @@ def process_state_channel(state_data, plant): q.append(q_temp) v.append(v_temp) u.append(u_temp) - t_x.append(msg.utime / 1e6) + t.append(msg.utime / 1e6) - return {'t_x': np.array(t_x), + return {'t': np.array(t), 'q': np.array(q), 'v': np.array(v), 'u': np.array(u)} @@ -100,7 +100,7 @@ def process_effort_channel(data, plant): t.append(msg.utime / 1e6) u.append(u_temp) - return {'t_u': np.array(t), 'u': np.array(u)} + return {'t': np.array(t), 'u': np.array(u)} def make_point_positions_from_q( @@ -278,8 +278,8 @@ def process_contact_channel(data): def process_c3_channel(data): t = [] - states = [] # Allocate space for all 4 point contacts - breaks = [] # Allocate space for all 4 point contacts + states = [] + breaks = [] contact_forces = [] inputs = [] for msg in data: @@ -300,6 +300,22 @@ def process_c3_channel(data): 'x': states, 'lambda': contact_forces, 'u': inputs,} +def process_object_state_channel(data): + t = [] + positions = [] + velocities = [] + for msg in data: + t.append(msg.utime / 1e6) + positions.append(msg.position) + velocities.append(msg.velocity) + + t = np.array(t) + positions = np.array(positions) + velocities = np.array(velocities) + + return {'t': t, + 'q': positions, + 'v': velocities,} def permute_osc_joint_ordering(osc_data, robot_output_msg, plant): @@ -328,6 +344,10 @@ def load_c3_debug(data, c3_debug_channel): c3_debug = process_c3_channel(data[c3_debug_channel]) return c3_debug +def load_object_state(data, object_state_channel): + object_state = process_object_state_channel(data[object_state_channel]) + return object_state + def plot_q_or_v_or_u( robot_output, key, x_names, x_slice, time_slice, ylabel=None, title=None, ps=None, subplot_index=0): @@ -340,7 +360,7 @@ def plot_q_or_v_or_u( plotting_utils.make_plot( robot_output, # data dict - 't_x', # time channel + 't', # time channel time_slice, [key], # key to plot {key: x_slice}, # slice of key to plot @@ -363,7 +383,7 @@ def plot_u_cmd( plotting_utils.make_plot( robot_input, # data dict - 't_u', # time channel + 't', # time channel time_slice, [key], # key to plot {key: x_slice}, # slice of key to plot @@ -435,7 +455,7 @@ def plot_points_positions(robot_output, time_slice, plant, context, frame_names, ps = plot_styler.PlotStyler() dim_map = ['_x', '_y', '_z'] - data_dict = {'t': robot_output['t_x']} + data_dict = {'t': robot_output['t']} legend_entries = {} for name in frame_names: frame = plant.GetBodyByName(name).body_frame() @@ -464,7 +484,7 @@ def plot_points_velocities(robot_output, time_slice, plant, context, frame_names ps = plot_styler.PlotStyler() dim_map = ['_x', '_y', '_z'] - data_dict = {'t': robot_output['t_x']} + data_dict = {'t': robot_output['t']} legend_entries = {} for name in frame_names: frame = plant.GetBodyByName(name).body_frame() @@ -491,7 +511,7 @@ def plot_points_velocities(robot_output, time_slice, plant, context, frame_names def plot_floating_base_body_frame_velocities(robot_output, time_slice, plant, context, fb_frame_name): - data_dict = {'t': robot_output['t_x']} + data_dict = {'t': robot_output['t']} data_dict['base_vel'] = get_floating_base_velocity_in_body_frame( robot_output, plant, context, plant.GetBodyByName(fb_frame_name).body_frame())[:, 0] diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 81b5269017..97df060eae 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -3,11 +3,12 @@ channel_x: "FRANKA_STATE" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" channel_c3: "C3_DEBUG" +channel_tray: "TRAY_STATE" plot_style: 'compact' # compact, paper, default -start_time: 0 +start_time: 10 #duration: 0.47 -duration: -1 +duration: 6 # Plant properties @@ -36,4 +37,5 @@ tracking_datas_to_plot: end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} -plot_c3_debug: false \ No newline at end of file +plot_c3_debug: false +plot_object_state: true \ No newline at end of file From f9a08cb431308ef8c3d6d2c089500aa234ec576a Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 16 Nov 2023 11:50:27 -0500 Subject: [PATCH 541/758] updating tray sdf origin --- examples/franka/urdf/tray.sdf | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 908c8a8e21..8a4c5c5b6f 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -17,6 +17,7 @@ + 0 0 0.009 0 0 0 0.2286 @@ -24,10 +25,11 @@ - 0.3 0.3 0.3 1 + 0.1 0.1 0.1 1 + 0 0 0.009 0 0 0 0.2286 From 53cc8fdbed4647bdecb4c5e7f8b4ec6cd1347162 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 17 Nov 2023 10:29:08 -0500 Subject: [PATCH 542/758] tuning c3 params --- .../franka/parameters/franka_c3_options_translation.yaml | 6 +++--- .../franka/parameters/franka_osc_controller_params.yaml | 8 ++++---- examples/franka/parameters/franka_sim_params.yaml | 2 +- systems/controllers/c3_controller.cc | 4 ++-- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 40e85a01fb..f3ac592d0d 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -10,7 +10,7 @@ contact_model: 'stewart_and_trinkle' mu: 0.4 mu_plate: 0.4 -dt: 0.03 +dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 @@ -32,8 +32,8 @@ u_size: 40 #g_size: 34 #u_size: 34 # State Tracking Error, assuming diagonal -q_vector: [100, 100, 500, 100, 100, 100, 100, 10000, 10000, 10000, - 5, 5, 5, 1, 1, 1, 1, 1, 1] +q_vector: [100, 100, 100, 0, 0, 0, 0, 10000, 10000, 10000, + 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on all decision variables g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index c8535f796c..51655ed336 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 4.5 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] @@ -59,9 +59,9 @@ EndEffectorRotKp: 0, 400, 0, 0, 0, 400] EndEffectorRotKd: - [ 10, 0, 0, - 0, 10, 0, - 0, 0, 10 ] + [ 20, 0, 0, + 0, 20, 0, + 0, 0, 20 ] LambdaEndEffectorW: [ 1, 0, 0, 0, 1, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index d11ebd59d7..c250a83b99 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -19,5 +19,5 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, 0.03, 0.430] +q_init_plate: [1, 0, 0, 0, 0.56, 0.06, 0.450] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 621e2977eb..7b503dbf31 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -182,12 +182,12 @@ drake::systems::EventStatus C3Controller::ComputePlan( for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -5, 5, 2); + c3_->AddLinearConstraint(A, -10, 10, 2); } for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 5, 20, 2); + c3_->AddLinearConstraint(A, 0, 20, 2); } auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); auto finish = std::chrono::high_resolution_clock::now(); From 5511ffab7754c988b199969fca9a514fe0fff916 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 17 Nov 2023 14:27:53 -0500 Subject: [PATCH 543/758] reasonble closed loop solutions in sim --- .../osc_run/osc_running_qp_settings.yaml | 4 +- .../franka_c3_options_floating.yaml | 41 ++++++++++++------- .../franka_c3_options_translation.yaml | 8 ++-- .../franka_osc_controller_params.yaml | 4 +- 4 files changed, 34 insertions(+), 23 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 639eca37a0..c4b2641c43 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 1000 + max_iter: 500 linsys_solver: 0 verbose: 0 warm_start: 1 @@ -12,7 +12,7 @@ int_options: scaled_termination: 1 check_termination: 25 double_options: - rho: 0.001 + rho: 0.01 sigma: 1e-6 eps_abs: 1e-5 eps_rel: 1e-5 diff --git a/examples/franka/parameters/franka_c3_options_floating.yaml b/examples/franka/parameters/franka_c3_options_floating.yaml index 9cd4abed03..118a6b0ce9 100644 --- a/examples/franka/parameters/franka_c3_options_floating.yaml +++ b/examples/franka/parameters/franka_c3_options_floating.yaml @@ -1,38 +1,49 @@ admm_iter: 4 rho: 0.1 -rho_scale: 2 -num_threads: 4 +rho_scale: 1 +num_threads: 6 delta_option: 1 +# options are 'MIQP' or 'QP' +projection_type: 'MIQP' +# options are 'stewart_and_trinkle' or 'anitescu +contact_model: 'stewart_and_trinkle' mu: 0.4 -mu_plate: 1 +mu_plate: 0.4 dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 N: 5 -w_Q: 10 + +# matrix scaling +w_Q: 20 w_R: 0 # Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 1 # Penalty on all decision variables, assuming scalar -w_U: 1 +w_U: 0.5 +# n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions +# size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle +# size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu g_size: 49 u_size: 49 +#g_size: 34 +#u_size: 34 # State Tracking Error, assuming diagonal -#q_vector: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1] -q_vector: [200, 200, 500, 0, 0, 0, 0, 0, 0, 0, 10000, 10000, 10000, - 0, 0, 0, 0, 0, 0, 0, 0, 0, 1, 1, 1] +q_vector: [100, 100, 500, 0, 0, 0, 0, 0, 0, 0, 10000, 10000, 10000, + 0, 0, 0, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on all decision variables -g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 0.1, 0.1, 0.1] -q_des_vector: [0.55, 0.02, 0.43, 0, 0, 0, 1, 0, 0, 0, 0.55, 0.02, 0.45] -v_des_vector: [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index f3ac592d0d..41e8612f29 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -8,8 +8,8 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu contact_model: 'stewart_and_trinkle' -mu: 0.4 -mu_plate: 0.4 +mu: 0.2 +mu_plate: 0.2 dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 @@ -17,7 +17,7 @@ num_contacts: 3 N: 5 # matrix scaling -w_Q: 20 +w_Q: 30 w_R: 0 # Penalty on all decision variables, assuming scalar w_G: 1 @@ -32,7 +32,7 @@ u_size: 40 #g_size: 34 #u_size: 34 # State Tracking Error, assuming diagonal -q_vector: [100, 100, 100, 0, 0, 0, 0, 10000, 10000, 10000, +q_vector: [175, 175, 175, 0, 0, 0, 0, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on all decision variables g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 51655ed336..9bd9799fa5 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -14,12 +14,12 @@ z_scale: 0.1 w_input: 0.00 w_input_reg: 0.0 w_accel: 0.00001 -w_soft_constraint: 10000 +w_soft_constraint: 0.0 w_lambda: 0.0 impact_threshold: 0.000 impact_tau: 0.000 mu: 0.6 -end_effector_acceleration: 4.5 +end_effector_acceleration: 10 track_end_effector_orientation: false cancel_gravity_compensation: false enforce_acceleration_constraints: false From 4f2c06fa6d42030a106acdfc9adc1c8096d8b385 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 20 Nov 2023 15:40:41 -0500 Subject: [PATCH 544/758] updating sim params to reflect slower tray publish rate --- examples/franka/franka_sim.cc | 42 +++++++++---------- .../franka_c3_controller_params.yaml | 4 +- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 6 ++- .../franka/parameters/franka_sim_params.yaml | 5 ++- examples/franka/urdf/tray.sdf | 4 +- systems/controllers/c3_controller.cc | 1 - systems/robot_lcm_systems.cc | 3 +- 8 files changed, 35 insertions(+), 32 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 77dca45dea..5f3706f3e7 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -78,8 +78,8 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; - drake::multibody::ModelInstanceIndex box_index = - parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; +// drake::multibody::ModelInstanceIndex box_index = +// parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); @@ -119,29 +119,29 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(&drake_lcm); AddActuationRecieverAndStateSenderLcm( &builder, plant, lcm, lcm_channel_params.franka_input_channel, - lcm_channel_params.franka_state_channel, sim_params.publish_rate, + lcm_channel_params.franka_state_channel, sim_params.franka_publish_rate, franka_index, sim_params.publish_efforts, sim_params.actuator_delay); auto tray_state_sender = builder.AddSystem(plant, tray_index); auto tray_state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, lcm, - 1.0 / sim_params.publish_rate)); - auto box_state_sender = - builder.AddSystem(plant, box_index); - auto box_state_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.box_state_channel, lcm, - 1.0 / sim_params.publish_rate)); + 1.0 / sim_params.tray_publish_rate)); +// auto box_state_sender = +// builder.AddSystem(plant, box_index); +// auto box_state_pub = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.box_state_channel, lcm, +// 1.0 / sim_params.publish_rate)); builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); - builder.Connect(plant.get_state_output_port(box_index), - box_state_sender->get_input_port_state()); +// builder.Connect(plant.get_state_output_port(box_index), +// box_state_sender->get_input_port_state()); builder.Connect(tray_state_sender->get_output_port(), tray_state_pub->get_input_port()); - builder.Connect(box_state_sender->get_output_port(), - box_state_pub->get_input_port()); +// builder.Connect(box_state_sender->get_output_port(), +// box_state_pub->get_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); @@ -182,13 +182,13 @@ int DoMain(int argc, char* argv[]) { q[q_map.at("tray_y")] = sim_params.q_init_plate[5]; q[q_map.at("tray_z")] = sim_params.q_init_plate[6]; - q[q_map["box_qw"]] = sim_params.q_init_box[0]; - q[q_map["box_qx"]] = sim_params.q_init_box[1]; - q[q_map["box_qy"]] = sim_params.q_init_box[2]; - q[q_map["box_qz"]] = sim_params.q_init_box[3]; - q[q_map["box_x"]] = sim_params.q_init_box[4]; - q[q_map["box_y"]] = sim_params.q_init_box[5]; - q[q_map["box_z"]] = sim_params.q_init_box[6]; +// q[q_map["box_qw"]] = sim_params.q_init_box[0]; +// q[q_map["box_qx"]] = sim_params.q_init_box[1]; +// q[q_map["box_qy"]] = sim_params.q_init_box[2]; +// q[q_map["box_qz"]] = sim_params.q_init_box[3]; +// q[q_map["box_x"]] = sim_params.q_init_box[4]; +// q[q_map["box_y"]] = sim_params.q_init_box[5]; +// q[q_map["box_z"]] = sim_params.q_init_box[6]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 9744504a33..6ba87279c0 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -15,9 +15,9 @@ tray_model: examples/franka/urdf/tray.sdf include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 100 +target_frequency: 50 -neutral_position: [0.55, 0, 0.45] +neutral_position: [0.55, 0, 0.47] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 9bd9799fa5..1e9a5c2ef3 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index e58c79321f..0a1d79a140 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -15,7 +15,8 @@ struct FrankaSimParams { double dt; double realtime_rate; double actuator_delay; - double publish_rate; + double franka_publish_rate; + double tray_publish_rate; bool visualize; bool publish_efforts; @@ -37,7 +38,8 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); a->Visit(DRAKE_NVP(actuator_delay)); - a->Visit(DRAKE_NVP(publish_rate)); + a->Visit(DRAKE_NVP(franka_publish_rate)); + a->Visit(DRAKE_NVP(tray_publish_rate)); a->Visit(DRAKE_NVP(visualize)); a->Visit(DRAKE_NVP(publish_efforts)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index c250a83b99..c7133400db 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -5,10 +5,11 @@ table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_su table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf tray_model: examples/franka/urdf/tray.sdf box_model: examples/franka/urdf/default_box.urdf -publish_rate: 1000 +franka_publish_rate: 1000 +tray_publish_rate: 10 publish_efforts: true actuator_delay: 0.000 -visualize: false +visualize: true tool_attachment_frame: [0, 0, 0.107] diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 8a4c5c5b6f..427bf59d6c 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -17,7 +17,7 @@ - 0 0 0.009 0 0 0 + 0 0 0.0 0 0 0 0.2286 @@ -29,7 +29,7 @@ - 0 0 0.009 0 0 0 + 0 0 0.0 0 0 0 0.2286 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7b503dbf31..1e8e7ef47a 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -64,7 +64,6 @@ C3Controller::C3Controller( } n_u_ = plant_.num_actuators(); - // Q_.back() = 100 * c3_options_.Q; lcs_state_input_port_ = this->DeclareVectorInputPort( diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index 7aa12a9d12..b0ea900ed8 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -501,7 +501,8 @@ void ObjectStateSender::Output(const Context& context, } } for (int i = 0; i < num_velocities_; i++) { - state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); +// state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); + state_msg->velocity[i] = 0; state_msg->velocity_names[i] = ordered_velocity_names_[i]; } } From 72a0876f1ed2ae4dab24de89bec22f319d12dbe2 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 21 Nov 2023 14:11:40 -0500 Subject: [PATCH 545/758] small cleanup --- examples/Cassie/cassie_xbox_remote.py | 3 ++- systems/controllers/c3_controller.h | 11 ----------- 2 files changed, 2 insertions(+), 12 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index c19c710a6d..203233d8ed 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -59,6 +59,7 @@ def main(): latching_switch_a = 1 latching_switch_b = 1 print("Teleop Status: " + str(latching_switch_a)) + print("End Effector Follow Status: " + str(latching_switch_b)) while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands @@ -75,7 +76,7 @@ def main(): print("Teleop Status: " + str(latching_switch_a)) if event.button == 1: latching_switch_b = not latching_switch_b - + print("End Effector Follow Status: " + str(latching_switch_b)) # Send LCM message radio_msg = dairlib.lcmt_radio_out() diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 84e137aafd..a79566b977 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -51,18 +51,10 @@ class C3Controller : public drake::systems::LeafSystem { return this->get_output_port(c3_intermediates_port_); } -// const drake::systems::InputPort& get_input_port_radio() const { -// return this->get_input_port(radio_port_); -// } - void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { solver_options_ = options; } - void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { - publish_end_effector_orientation_ = publish_end_effector_orientation; - } - private: drake::systems::EventStatus ComputePlan( const drake::systems::Context& context, @@ -76,7 +68,6 @@ class C3Controller : public drake::systems::LeafSystem { drake::systems::InputPortIndex target_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; -// drake::systems::InputPortIndex radio_port_; drake::systems::OutputPortIndex c3_solution_port_; drake::systems::OutputPortIndex c3_intermediates_port_; @@ -92,8 +83,6 @@ class C3Controller : public drake::systems::LeafSystem { FindResourceOrThrow("solvers/osqp_options_default.yaml")) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - bool publish_end_effector_orientation_ = false; - // convenience for variable sizes int n_q_; int n_v_; From 0084160dd3abaa8e03b0adf8ec377567ced9556e Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 21 Nov 2023 16:36:19 -0500 Subject: [PATCH 546/758] publishing c3 target and actual state --- examples/franka/BUILD.bazel | 1 - examples/franka/franka_c3_controller.cc | 30 +++++++-- .../franka/parameters/franka_lcm_channels.h | 4 ++ .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../parameters/lcm_channels_hardware.yaml | 2 + .../parameters/lcm_channels_simulation.yaml | 2 + examples/franka/systems/BUILD.bazel | 19 +++++- examples/franka/systems/c3_state_sender.cc | 61 +++++++++++++++++++ examples/franka/systems/c3_state_sender.h | 52 ++++++++++++++++ .../franka/systems/franka_kinematics_vector.h | 2 - .../franka/systems/plate_balancing_target.cc | 2 +- examples/franka/urdf/tray.sdf | 8 +-- lcmtypes/lcmt_c3_state.lcm | 10 +++ systems/controllers/c3_controller.cc | 19 +++--- 15 files changed, 190 insertions(+), 26 deletions(-) create mode 100644 examples/franka/systems/c3_state_sender.cc create mode 100644 examples/franka/systems/c3_state_sender.h create mode 100644 lcmtypes/lcmt_c3_state.lcm diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index fd642da489..c435a2067c 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -70,7 +70,6 @@ cc_binary( ":franka_c3_controller_params", ":franka_lcm_channels", "//common", - "//examples/franka/systems:c3_trajectory_generator", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index f7fd2b613a..00f4fb8b2f 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -15,6 +15,7 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" #include "examples/franka/systems/end_effector_trajectory.h" #include "examples/franka/systems/franka_kinematics.h" @@ -175,6 +176,14 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_debug_output_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); @@ -210,6 +219,15 @@ int DoMain(int argc, char* argv[]) { auto c3_trajectory_generator = builder.AddSystem(plant_plate, c3_options); + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", + "tray_qx", "tray_qy", "tray_qz", "tray_x", + "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", + "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", + "tray_vz", "tray_vz", "tray_vz", + }; + auto c3_state_sender = + builder.AddSystem(3 + 7 + 3 + 6, state_names); c3_trajectory_generator->SetPublishEndEffectorOrientation( controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); @@ -232,7 +250,14 @@ int DoMain(int argc, char* argv[]) { actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); - + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); builder.Connect(controller->get_output_port_c3_solution(), c3_output_sender->get_input_port_c3_solution()); builder.Connect(controller->get_output_port_c3_intermediates(), @@ -240,9 +265,6 @@ int DoMain(int argc, char* argv[]) { builder.Connect(c3_output_sender->get_output_port_c3_debug(), c3_output_publisher->get_input_port()); - controller->SetPublishEndEffectorOrientation( - controller_params.include_end_effector_orientation); - auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h index 91147a37e2..c30a661208 100644 --- a/examples/franka/parameters/franka_lcm_channels.h +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -15,6 +15,8 @@ struct FrankaLcmChannels { std::string c3_object_channel; std::string c3_force_channel; std::string c3_debug_output_channel; + std::string c3_target_state_channel; + std::string c3_actual_state_channel; std::string radio_channel; template @@ -30,6 +32,8 @@ struct FrankaLcmChannels { a->Visit(DRAKE_NVP(c3_object_channel)); a->Visit(DRAKE_NVP(c3_force_channel)); a->Visit(DRAKE_NVP(c3_debug_output_channel)); + a->Visit(DRAKE_NVP(c3_target_state_channel)); + a->Visit(DRAKE_NVP(c3_actual_state_channel)); a->Visit(DRAKE_NVP(radio_channel)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 1e9a5c2ef3..9bd9799fa5 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index c7133400db..4ed2bd77a0 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -20,5 +20,5 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] #q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] #q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] #q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, 0.06, 0.450] +q_init_plate: [1, 0, 0, 0, 0.56, 0.04, 0.450] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index 71788307c3..fbe4c699bc 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -11,5 +11,7 @@ c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY c3_force_channel: C3_TRAJECTORY_FORCE c3_debug_output_channel: C3_DEBUG +c3_target_state_channel: C3_TARGET +c3_actual_state_channel: C3_ACTUAL radio_channel: RADIO diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index 016662c7e0..4e04c90e18 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -11,5 +11,7 @@ c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY c3_force_channel: C3_TRAJECTORY_FORCE c3_debug_output_channel: C3_DEBUG +c3_target_state_channel: C3_TARGET +c3_actual_state_channel: C3_ACTUAL radio_channel: RADIO diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index d2ad44618a..41451dc6cd 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -9,6 +9,8 @@ cc_library( ":end_effector_trajectory", ":franka_kinematics", ":plate_balancing_target", + ":c3_state_sender", + ":c3_trajectory_generator", ], ) @@ -73,8 +75,8 @@ cc_library( "c3_trajectory_generator.h", ], deps = [ + ":franka_kinematics", "//common:find_resource", - "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", "//multibody:utils", @@ -86,6 +88,21 @@ cc_library( ], ) +cc_library( + name = "c3_state_sender", + srcs = [ + "c3_state_sender.cc", + ], + hdrs = [ + "c3_state_sender.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "franka_kinematics", srcs = ["franka_kinematics.cc"], diff --git a/examples/franka/systems/c3_state_sender.cc b/examples/franka/systems/c3_state_sender.cc new file mode 100644 index 0000000000..94a72d6f5c --- /dev/null +++ b/examples/franka/systems/c3_state_sender.cc @@ -0,0 +1,61 @@ +#include "examples/franka/systems/c3_state_sender.h" +#include "systems/framework/timestamped_vector.h" + +namespace dairlib { + +using drake::systems::BasicVector; +using systems::TimestampedVector; +using drake::systems::Context; + +namespace systems { + +C3StateSender::C3StateSender(int state_size, + std::vector state_names) { + this->set_name("c3_state_sender"); + + n_x_ = state_size; + target_state_ = this->DeclareVectorInputPort("target_state", + BasicVector(state_size)) + .get_index(); + actual_state_ = this->DeclareVectorInputPort("c3_solution", + TimestampedVector(state_size)) + .get_index(); + + lcmt_c3_state default_c3_state = dairlib::lcmt_c3_state(); + default_c3_state.num_states = n_x_; + default_c3_state.utime = 0; + default_c3_state.state = std::vector(n_x_); + default_c3_state.state_names = state_names; + target_c3_state_ = this->DeclareAbstractOutputPort( + "c3_actor_trajectory_output", default_c3_state, + &C3StateSender::OutputTargetState) + .get_index(); + actual_c3_state_ = this->DeclareAbstractOutputPort( + "c3_object_trajectory_output", default_c3_state, + &C3StateSender::OutputActualState) + .get_index(); +} + +void C3StateSender::OutputTargetState( + const drake::systems::Context& context, + dairlib::lcmt_c3_state* output) const { + const auto target_state = this->EvalVectorInput(context, target_state_); + DRAKE_DEMAND(target_state->size() == n_x_); + output->utime = context.get_time() * 1e6; + for (int i = 0; i < n_x_; ++i) { + output->state[i] = static_cast(target_state->GetAtIndex(i)); + } +} + +void C3StateSender::OutputActualState( + const drake::systems::Context& context, + dairlib::lcmt_c3_state* output) const { + const auto actual_state = (TimestampedVector*)this->EvalVectorInput(context, actual_state_); + DRAKE_DEMAND(actual_state->get_data().size() == n_x_); + output->utime = context.get_time() * 1e6; + for (int i = 0; i < n_x_; ++i) { + output->state[i] = static_cast(actual_state->GetAtIndex(i)); + } +} +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/systems/c3_state_sender.h b/examples/franka/systems/c3_state_sender.h new file mode 100644 index 0000000000..5d43a1ea35 --- /dev/null +++ b/examples/franka/systems/c3_state_sender.h @@ -0,0 +1,52 @@ +#pragma once + +#include +#include + +#include "common/find_resource.h" +#include "dairlib/lcmt_c3_state.hpp" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// Outputs a lcmt_timestamped_saved_traj +class C3StateSender : public drake::systems::LeafSystem { + public: + explicit C3StateSender(int state_size, std::vector state_names); + + const drake::systems::InputPort& get_input_port_target_state() const { + return this->get_input_port(target_state_); + } + + const drake::systems::InputPort& get_input_port_actual_state() const { + return this->get_input_port(actual_state_); + } + + const drake::systems::OutputPort& get_output_port_target_c3_state() + const { + return this->get_output_port(target_c3_state_); + } + const drake::systems::OutputPort& get_output_port_actual_c3_state() + const { + return this->get_output_port(actual_c3_state_); + } + + private: + void OutputTargetState(const drake::systems::Context& context, + dairlib::lcmt_c3_state* output) const; + + void OutputActualState(const drake::systems::Context& context, + dairlib::lcmt_c3_state* output) const; + + drake::systems::InputPortIndex target_state_; + drake::systems::InputPortIndex actual_state_; + drake::systems::OutputPortIndex target_c3_state_; + drake::systems::OutputPortIndex actual_c3_state_; + + int n_x_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/systems/franka_kinematics_vector.h b/examples/franka/systems/franka_kinematics_vector.h index 4454c70cd2..7b773f7f14 100644 --- a/examples/franka/systems/franka_kinematics_vector.h +++ b/examples/franka/systems/franka_kinematics_vector.h @@ -18,8 +18,6 @@ class FrankaKinematicsVector : public TimestampedVector { FrankaKinematicsVector() = default; - /// Initializes with the given @p size using the drake::dummy_value, which - /// is NaN when T = double. explicit FrankaKinematicsVector(int num_end_effector_positions, int num_object_positions, int num_end_effector_velocities, diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index eda7e4b3b8..15a7523b35 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -56,7 +56,7 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( this->EvalInputValue(context, radio_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = neutral_pose_; - tray_position[2] += 0.012065; // thickness of end effector and tray + tray_position[2] += 0.015; // thickness of end effector and tray tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 427bf59d6c..f908a0b5ae 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -8,10 +8,10 @@ - 0.012698 + 0.012712 0 0 - 0.012698 + 0.012712 0 0.025345 @@ -21,7 +21,7 @@ 0.2286 - 0.01778 + 0.022 @@ -33,7 +33,7 @@ 0.2286 - 0.01778 + 0.022 diff --git a/lcmtypes/lcmt_c3_state.lcm b/lcmtypes/lcmt_c3_state.lcm new file mode 100644 index 0000000000..1d1f4a2101 --- /dev/null +++ b/lcmtypes/lcmt_c3_state.lcm @@ -0,0 +1,10 @@ +package dairlib; + +struct lcmt_c3_state +{ + int64_t utime; + int32_t num_states; + + float state [num_states]; + string state_names [num_states]; +} \ No newline at end of file diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 1e8e7ef47a..4f351f3179 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -65,18 +65,15 @@ C3Controller::C3Controller( n_u_ = plant_.num_actuators(); - lcs_state_input_port_ = - this->DeclareVectorInputPort( - "x_lcs", FrankaKinematicsVector( - plant_.num_positions(ModelInstanceIndex(2)), - plant_.num_positions(ModelInstanceIndex(3)), - plant_.num_velocities(ModelInstanceIndex(2)), - plant_.num_velocities(ModelInstanceIndex(3)))) - .get_index(); int x_des_size = plant_.num_positions(ModelInstanceIndex(2)) + plant_.num_positions(ModelInstanceIndex(3)) + plant_.num_velocities(ModelInstanceIndex(2)) + plant_.num_velocities(ModelInstanceIndex(3)); + lcs_state_input_port_ = + this->DeclareVectorInputPort( + "x_lcs", TimestampedVector( + x_des_size)) + .get_index(); target_input_port_ = this->DeclareVectorInputPort("desired_position", x_des_size).get_index(); @@ -109,15 +106,15 @@ drake::systems::EventStatus C3Controller::ComputePlan( const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); - const FrankaKinematicsVector* lcs_x = - (FrankaKinematicsVector*)this->EvalVectorInput( + const TimestampedVector* lcs_x = + (TimestampedVector*)this->EvalVectorInput( context, lcs_state_input_port_); discrete_state->get_mutable_value(plan_start_time_index_)[0] = lcs_x->get_timestamp(); VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); - q_v_u << lcs_x->GetState(), VectorXd::Zero(n_u_); + q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); std::vector x_desired = From d6b2538e568d5cf385ad45e61b650bc30b7907c1 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 29 Nov 2023 13:51:42 -0500 Subject: [PATCH 547/758] small plotting changes for franka experiments --- bindings/pydairlib/analysis/log_plotter_franka.py | 7 ++++++- bindings/pydairlib/analysis/mbp_plotting_utils.py | 5 +++-- .../analysis/plot_configs/franka_translation_plot.yaml | 6 +++--- 3 files changed, 12 insertions(+), 6 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 7ed7d6d69d..c7c342aa75 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -59,6 +59,7 @@ def main(): c3_output = get_log_data(log, default_channels, plot_config.start_time, plot_config.duration, mbp_plots.load_c3_debug, channel_c3) + print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_output['t']))) # processing callback arguments if plot_config.plot_object_state: @@ -76,6 +77,7 @@ def main(): print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) + (franka_joint_position_limit_range, franka_joint_velocity_limit_range, franka_joint_actuator_limit_range) = mbp_plots.generate_joint_limits( franka_plant) @@ -94,7 +96,10 @@ def main(): # import pdb; pdb.set_trace() if plot_config.plot_c3_debug: t_c3_slice = slice(c3_output['t'].size) - mbp_plots.plot_c3_inputs(c3_output, t_c3_slice) + mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 0) + + t_c3_slice = slice(c3_output['t'].size) + mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) # Plot all joint velocities diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 5c7791f3db..2e6b6f4dca 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -856,14 +856,15 @@ def generate_joint_limits(plant): franka_joint_actuator_limit_range = [np.min(joint_actuator_limits_lower), np.max(joint_actuator_limits_upper)] return franka_joint_position_limit_range, franka_joint_velocity_limit_range, franka_joint_actuator_limit_range -def plot_c3_inputs(c3_output, time_slice): +# Cannot plot multiple indices of the solution because the solution is already multi-dimensional (time) +def plot_c3_inputs(c3_output, time_slice, input_index): ps = plot_styler.PlotStyler() plotting_utils.make_plot( c3_output, 't', time_slice, ['u'], - {'u': 2}, + {'u': input_index}, {}, {'xlabel': 'Timestamp', 'ylabel': 'C3 Actor Inputs ', diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 97df060eae..d96358e3ed 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -6,9 +6,9 @@ channel_c3: "C3_DEBUG" channel_tray: "TRAY_STATE" plot_style: 'compact' # compact, paper, default -start_time: 10 +start_time: 4 #duration: 0.47 -duration: 6 +duration: 5 # Plant properties @@ -37,5 +37,5 @@ tracking_datas_to_plot: end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} -plot_c3_debug: false +plot_c3_debug: true plot_object_state: true \ No newline at end of file From dba73f4057cef0cb7b8cff987a5de75d571e21d0 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 30 Nov 2023 13:41:50 -0500 Subject: [PATCH 548/758] plotting changes and adding debug info to osc --- .../analysis/franka_plotting_utils.py | 1 + .../pydairlib/analysis/log_plotter_franka.py | 3 +-- .../plot_configs/franka_translation_plot.yaml | 4 ++-- .../franka_c3_options_translation.yaml | 21 +++++++++++++------ solvers/c3_options.h | 2 ++ .../osc/operational_space_control.cc | 4 ++-- 6 files changed, 23 insertions(+), 12 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index de9f4e3a9f..becdb8e03a 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -23,6 +23,7 @@ {'FRANKA_STATE': dairlib.lcmt_robot_output, 'FRANKA_STATE_SIMULATION': dairlib.lcmt_robot_output, 'TRAY_STATE': dairlib.lcmt_object_state, + 'TRAY_STATE_SIMULATION': dairlib.lcmt_object_state, 'FRANKA_INPUT': dairlib.lcmt_robot_input, 'OSC_FRANKA': dairlib.lcmt_robot_input, 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index c7c342aa75..511fa46c99 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -164,8 +164,7 @@ def main(): slice(0, 7)) plot = mbp_plots.plot_joint_velocities(robot_output, vel_names, 0, t_x_slice) - # plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, - # 12)) + plot = mbp_plots.plot_lambda_c_sol(osc_debug, t_osc_slice, slice(0, 3)) # plot = mbp_plots.plot_lambda_h_sol(osc_debug, t_osc_slice, slice(0, # 6)) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index d96358e3ed..35308c7d44 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -1,9 +1,9 @@ # LCM channels to read data from -channel_x: "FRANKA_STATE" +channel_x: "FRANKA_STATE_SIMULATION" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" channel_c3: "C3_DEBUG" -channel_tray: "TRAY_STATE" +channel_tray: "TRAY_STATE_SIMULATION" plot_style: 'compact' # compact, paper, default start_time: 4 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 41e8612f29..4fc995813f 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -5,11 +5,13 @@ num_threads: 6 delta_option: 1 # options are 'MIQP' or 'QP' projection_type: 'MIQP' -# options are 'stewart_and_trinkle' or 'anitescu +# options are 'stewart_and_trinkle' or 'anitescu' +#contact_model: 'stewart_and_trinkle' contact_model: 'stewart_and_trinkle' +warm_start: true mu: 0.2 -mu_plate: 0.2 +mu_plate: 0.0 dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 @@ -25,8 +27,8 @@ w_G: 1 w_U: 0.5 # n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions -# size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle -# size = n_x ( 7 + 3 + 6 + 3 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu +# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle +# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu g_size: 40 u_size: 40 #g_size: 34 @@ -39,11 +41,18 @@ g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] #g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + + + # Penalty on all decision variables -u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, + 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] #u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 1] +#g_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#u_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 26863100cd..d3fb7d51f8 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -12,6 +12,7 @@ struct C3Options { int delta_option = 1; // different options for delta update std::string projection_type; std::string contact_model; + bool warm_start; int N; double w_Q; @@ -50,6 +51,7 @@ struct C3Options { if (projection_type == "QP") { DRAKE_DEMAND(contact_model == "anitescu"); } + a->Visit(DRAKE_NVP(warm_start)); a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(mu_plate)); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index f43c55625c..603960635e 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1084,13 +1084,13 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.u_dim = n_u_; // qp_output.lambda_c_dim = n_c_; qp_output.lambda_c_dim = n_lambda_ext_; - qp_output.lambda_h_dim = n_h_; + qp_output.lambda_h_dim = n_lambda_ext_; qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); - qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); + qp_output.lambda_h_sol = CopyVectorXdToStdVector(force_tracking_data_vec_->at(0)->GetLambdaDes()); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; From a32397d2121059263bb1ba8814ec58c3c0db98de Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 30 Nov 2023 14:37:44 -0500 Subject: [PATCH 549/758] plotting updates --- .../pydairlib/analysis/franka_plot_config.py | 3 +++ .../analysis/franka_plotting_utils.py | 2 ++ .../pydairlib/analysis/log_plotter_franka.py | 15 ++++++++++-- .../pydairlib/analysis/mbp_plotting_utils.py | 24 +++++++++++++++---- .../plot_configs/franka_translation_plot.yaml | 13 ++++++---- 5 files changed, 46 insertions(+), 11 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plot_config.py b/bindings/pydairlib/analysis/franka_plot_config.py index d566c87c70..cae37dc58f 100644 --- a/bindings/pydairlib/analysis/franka_plot_config.py +++ b/bindings/pydairlib/analysis/franka_plot_config.py @@ -15,6 +15,8 @@ def __init__(self, filename): self.channel_osc = data['channel_osc'] self.channel_c3 = data['channel_c3'] self.channel_tray = data['channel_tray'] + self.channel_c3_target = data['channel_c3_target'] + self.channel_c3_actual = data['channel_c3_actual'] self.plot_style = data['plot_style'] self.start_time = data['start_time'] @@ -45,4 +47,5 @@ def __init__(self, filename): self.tracking_datas_to_plot = \ data['tracking_datas_to_plot'] if data['tracking_datas_to_plot'] else [] self.plot_c3_debug = data['plot_c3_debug'] + self.plot_c3_tracking = data['plot_c3_tracking'] self.plot_object_state = data['plot_object_state'] diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index becdb8e03a..842e6984ee 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -30,6 +30,8 @@ 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, 'C3_DEBUG': dairlib.lcmt_c3_output, + 'C3_ACTUAL': dairlib.lcmt_c3_state, + 'C3_TARGET': dairlib.lcmt_c3_state, 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, 'RADIO': dairlib.lcmt_radio_out, 'CONTACT_RESULTS': drake.lcmt_contact_results_for_viz} diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 511fa46c99..bb398d0a34 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -22,6 +22,8 @@ def main(): channel_u = plot_config.channel_u channel_osc = plot_config.channel_osc channel_c3 = plot_config.channel_c3 + channel_c3_target = plot_config.channel_c3_target + channel_c3_actual = plot_config.channel_c3_actual channel_tray = plot_config.channel_tray if plot_config.plot_style == "paper": @@ -56,9 +58,9 @@ def main(): # processing callback arguments if plot_config.plot_c3_debug: - c3_output = get_log_data(log, default_channels, plot_config.start_time, + c3_output, c3_tracking_target, c3_tracking_actual = get_log_data(log, default_channels, plot_config.start_time, plot_config.duration, mbp_plots.load_c3_debug, - channel_c3) + channel_c3, channel_c3_target, channel_c3_actual) print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_output['t']))) # processing callback arguments @@ -100,6 +102,15 @@ def main(): t_c3_slice = slice(c3_output['t'].size) mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) + + if plot_config.plot_c3_tracking: + plot = plot_styler.PlotStyler(nrows=2) + plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:3], subplot_index = 0) + plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0) + plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) + plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:10], subplot_index = 1) + plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 1) + plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) # Plot all joint velocities diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2e6b6f4dca..92640a298f 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -276,7 +276,7 @@ def process_contact_channel(data): 'lambda_c': contact_forces, 'p_lambda_c': contact_info_locs} -def process_c3_channel(data): +def process_c3_debug(data): t = [] states = [] breaks = [] @@ -300,6 +300,20 @@ def process_c3_channel(data): 'x': states, 'lambda': contact_forces, 'u': inputs,} + +def process_c3_tracking(data): + t = [] + states = [] + for msg in data: + t.append(msg.utime / 1e6) + states.append(msg.state) + + t = np.array(t) + states = np.array(states) + + return {'t': t, + 'x': states, + } def process_object_state_channel(data): t = [] positions = [] @@ -340,9 +354,11 @@ def load_force_channels(data, contact_force_channel): contact_info = process_contact_channel(data[contact_force_channel]) return contact_info -def load_c3_debug(data, c3_debug_channel): - c3_debug = process_c3_channel(data[c3_debug_channel]) - return c3_debug +def load_c3_debug(data, c3_debug_channel, c3_target_channel, c3_actual_channel): + c3_debug = process_c3_debug(data[c3_debug_channel]) + c3_tracking_target = process_c3_tracking(data[c3_target_channel]) + c3_tracking_actual = process_c3_tracking(data[c3_actual_channel]) + return c3_debug, c3_tracking_target, c3_tracking_actual def load_object_state(data, object_state_channel): object_state = process_object_state_channel(data[object_state_channel]) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 35308c7d44..7e7f36911a 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -1,14 +1,16 @@ # LCM channels to read data from -channel_x: "FRANKA_STATE_SIMULATION" +channel_x: "FRANKA_STATE" channel_u: "OSC_FRANKA" channel_osc: "OSC_DEBUG_FRANKA" channel_c3: "C3_DEBUG" -channel_tray: "TRAY_STATE_SIMULATION" +channel_tray: "TRAY_STATE" +channel_c3_target: "C3_TARGET" +channel_c3_actual: "C3_ACTUAL" plot_style: 'compact' # compact, paper, default -start_time: 4 +start_time: 15 #duration: 0.47 -duration: 5 +duration: 10 # Plant properties @@ -34,8 +36,9 @@ plot_qp_solutions: true plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0, 1, 2], 'derivs': ['accel']} + end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} plot_c3_debug: true +plot_c3_tracking: true plot_object_state: true \ No newline at end of file From 59a6c44c513ebc1e8921072d9107846480aa12e8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 4 Dec 2023 14:26:27 -0500 Subject: [PATCH 550/758] cleaning up system naming and adding supports again --- examples/franka/franka_sim.cc | 76 +++++++++++-------- examples/franka/franka_visualizer.cc | 22 ++++++ .../franka_c3_controller_params.yaml | 1 - .../franka/parameters/franka_sim_params.h | 11 ++- .../franka/parameters/franka_sim_params.yaml | 14 ++-- examples/franka/systems/c3_state_sender.cc | 2 +- examples/franka/systems/franka_kinematics.cc | 2 +- examples/franka/urdf/left_support.urdf | 34 +++++++++ examples/franka/urdf/right_support.urdf | 34 +++++++++ systems/controllers/c3_controller.cc | 4 +- 10 files changed, 159 insertions(+), 41 deletions(-) create mode 100644 examples/franka/urdf/left_support.urdf create mode 100644 examples/franka/urdf/right_support.urdf diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 5f3706f3e7..33fd27f37d 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -6,7 +6,6 @@ #include #include #include -#include #include #include #include @@ -16,20 +15,15 @@ #include #include #include -#include #include #include #include "common/eigen_utils.h" #include "common/find_resource.h" -#include "dairlib/lcmt_robot_input.hpp" -#include "dairlib/lcmt_robot_output.hpp" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "multibody/multibody_utils.h" -#include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" namespace dairlib { @@ -68,18 +62,18 @@ int DoMain(int argc, char* argv[]) { // load urdf and sphere DiagramBuilder builder; double sim_dt = sim_params.dt; - // double output_dt = sim_params.dt; auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); Parser parser(&plant); + parser.SetAutoRenaming(true); drake::multibody::ModelInstanceIndex franka_index = parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; -// drake::multibody::ModelInstanceIndex box_index = -// parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; + // drake::multibody::ModelInstanceIndex box_index = + // parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); @@ -87,23 +81,45 @@ int DoMain(int argc, char* argv[]) { Vector3d tool_attachment_frame = StdVectorToVectorXd(sim_params.tool_attachment_frame); - - RigidTransform R_X_W = RigidTransform( + RigidTransform T_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_EE_W = RigidTransform( drake::math::RotationMatrix(), tool_attachment_frame); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), - R_X_W); + T_X_W); plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); + if (sim_params.scene_index == 1){ + drake::multibody::ModelInstanceIndex left_support_index = + parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; + drake::multibody::ModelInstanceIndex right_support_index = + parser.AddModels(FindResourceOrThrow(sim_params.right_support_model))[0]; + Vector3d first_support_position = + StdVectorToVectorXd(sim_params.left_support_position); + Vector3d second_support_position = + StdVectorToVectorXd(sim_params.right_support_position); + RigidTransform T_S1_W = RigidTransform( + drake::math::RotationMatrix(), first_support_position); + RigidTransform T_S2_W = RigidTransform( + drake::math::RotationMatrix(), second_support_position); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", left_support_index), + T_S1_W); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", right_support_index), + T_S2_W); + } + const drake::geometry::GeometrySet& paddle_geom_set = plant.CollectRegisteredGeometries({ &plant.GetBodyByName("panda_link4"), &plant.GetBodyByName("panda_link5"), &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link7"), +// &plant.GetBodyByName("panda_link7"), &plant.GetBodyByName("panda_link8"), +// &plant.GetBodyByName("plate"), }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); @@ -127,21 +143,21 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, lcm, 1.0 / sim_params.tray_publish_rate)); -// auto box_state_sender = -// builder.AddSystem(plant, box_index); -// auto box_state_pub = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.box_state_channel, lcm, -// 1.0 / sim_params.publish_rate)); + // auto box_state_sender = + // builder.AddSystem(plant, box_index); + // auto box_state_pub = + // builder.AddSystem(LcmPublisherSystem::Make( + // lcm_channel_params.box_state_channel, lcm, + // 1.0 / sim_params.publish_rate)); builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); -// builder.Connect(plant.get_state_output_port(box_index), -// box_state_sender->get_input_port_state()); + // builder.Connect(plant.get_state_output_port(box_index), + // box_state_sender->get_input_port_state()); builder.Connect(tray_state_sender->get_output_port(), tray_state_pub->get_input_port()); -// builder.Connect(box_state_sender->get_output_port(), -// box_state_pub->get_input_port()); + // builder.Connect(box_state_sender->get_output_port(), + // box_state_pub->get_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); @@ -182,13 +198,13 @@ int DoMain(int argc, char* argv[]) { q[q_map.at("tray_y")] = sim_params.q_init_plate[5]; q[q_map.at("tray_z")] = sim_params.q_init_plate[6]; -// q[q_map["box_qw"]] = sim_params.q_init_box[0]; -// q[q_map["box_qx"]] = sim_params.q_init_box[1]; -// q[q_map["box_qy"]] = sim_params.q_init_box[2]; -// q[q_map["box_qz"]] = sim_params.q_init_box[3]; -// q[q_map["box_x"]] = sim_params.q_init_box[4]; -// q[q_map["box_y"]] = sim_params.q_init_box[5]; -// q[q_map["box_z"]] = sim_params.q_init_box[6]; + // q[q_map["box_qw"]] = sim_params.q_init_box[0]; + // q[q_map["box_qx"]] = sim_params.q_init_box[1]; + // q[q_map["box_qy"]] = sim_params.q_init_box[2]; + // q[q_map["box_qz"]] = sim_params.q_init_box[3]; + // q[q_map["box_x"]] = sim_params.q_init_box[4]; + // q[q_map["box_y"]] = sim_params.q_init_box[5]; + // q[q_map["box_z"]] = sim_params.q_init_box[6]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index c8550474c3..c0340b63da 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -74,6 +74,7 @@ int do_main(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant, &scene_graph); + parser.SetAutoRenaming(true); drake::multibody::ModelInstanceIndex franka_index = parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; @@ -99,6 +100,27 @@ int do_main(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); + if (sim_params.scene_index == 1){ + drake::multibody::ModelInstanceIndex left_support_index = + parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; + drake::multibody::ModelInstanceIndex right_support_index = + parser.AddModels(FindResourceOrThrow(sim_params.right_support_model))[0]; + Vector3d first_support_position = + StdVectorToVectorXd(sim_params.left_support_position); + Vector3d second_support_position = + StdVectorToVectorXd(sim_params.right_support_position); + RigidTransform T_S1_W = RigidTransform( + drake::math::RotationMatrix(), first_support_position); + RigidTransform T_S2_W = RigidTransform( + drake::math::RotationMatrix(), second_support_position); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", left_support_index), + T_S1_W); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", right_support_index), + T_S2_W); + } + plant.Finalize(); auto lcm = builder.AddSystem(); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 6ba87279c0..0512ada758 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -8,7 +8,6 @@ end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -#franka_model: examples/franka/urdf/franka_no_collision.urdf plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 0a1d79a140..0fe5cae49a 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -11,6 +11,8 @@ struct FrankaSimParams { std::string table_w_supports_model; std::string tray_model; std::string box_model; + std::string left_support_model; + std::string right_support_model; double dt; double realtime_rate; @@ -18,6 +20,7 @@ struct FrankaSimParams { double franka_publish_rate; double tray_publish_rate; + int scene_index; bool visualize; bool publish_efforts; @@ -25,6 +28,8 @@ struct FrankaSimParams { std::vector q_init_plate; std::vector q_init_box; std::vector tool_attachment_frame; + std::vector left_support_position; + std::vector right_support_position; template void Serialize(Archive* a) { @@ -34,6 +39,8 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(table_w_supports_model)); a->Visit(DRAKE_NVP(tray_model)); a->Visit(DRAKE_NVP(box_model)); + a->Visit(DRAKE_NVP(left_support_model)); + a->Visit(DRAKE_NVP(right_support_model)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); @@ -41,6 +48,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(franka_publish_rate)); a->Visit(DRAKE_NVP(tray_publish_rate)); + a->Visit(DRAKE_NVP(scene_index)); a->Visit(DRAKE_NVP(visualize)); a->Visit(DRAKE_NVP(publish_efforts)); @@ -48,6 +56,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(q_init_plate)); a->Visit(DRAKE_NVP(q_init_box)); a->Visit(DRAKE_NVP(tool_attachment_frame)); - + a->Visit(DRAKE_NVP(left_support_position)); + a->Visit(DRAKE_NVP(right_support_position)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 4ed2bd77a0..b94ef1877f 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -5,20 +5,24 @@ table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_su table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf tray_model: examples/franka/urdf/tray.sdf box_model: examples/franka/urdf/default_box.urdf +left_support_model: examples/franka/urdf/left_support.urdf +right_support_model: examples/franka/urdf/right_support.urdf franka_publish_rate: 1000 tray_publish_rate: 10 -publish_efforts: true actuator_delay: 0.000 + +scene_index: 0 visualize: true +publish_efforts: true tool_attachment_frame: [0, 0, 0.107] +left_support_position: [0.55, 0.15, 0.225] +right_support_position: [0.8, -0.15, 0.225] dt: 0.0005 realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -#q_init_plate: [1, 0, 0, 0, 0.68, 0, 1.16] -#q_init_plate: [1, 0, 0, 0, 0.68, 0.07, 1.250] -#q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.430] -q_init_plate: [1, 0, 0, 0, 0.56, 0.04, 0.450] +q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.450] +#q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/systems/c3_state_sender.cc b/examples/franka/systems/c3_state_sender.cc index 94a72d6f5c..61a8b0f6bc 100644 --- a/examples/franka/systems/c3_state_sender.cc +++ b/examples/franka/systems/c3_state_sender.cc @@ -17,7 +17,7 @@ C3StateSender::C3StateSender(int state_size, target_state_ = this->DeclareVectorInputPort("target_state", BasicVector(state_size)) .get_index(); - actual_state_ = this->DeclareVectorInputPort("c3_solution", + actual_state_ = this->DeclareVectorInputPort("actual_state", TimestampedVector(state_size)) .get_index(); diff --git a/examples/franka/systems/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc index ae4fade422..61ba418180 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -51,7 +51,7 @@ FrankaKinematics::FrankaKinematics(const MultibodyPlant& franka_plant, num_object_velocities_ = 6; lcs_state_port_ = this->DeclareVectorOutputPort( - "lcs_state", + "x_lcs", FrankaKinematicsVector( num_end_effector_positions_, num_object_positions_, num_end_effector_velocities_, num_object_velocities_), diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf new file mode 100644 index 0000000000..7b77c3b0ed --- /dev/null +++ b/examples/franka/urdf/left_support.urdf @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/right_support.urdf b/examples/franka/urdf/right_support.urdf new file mode 100644 index 0000000000..b4826f0205 --- /dev/null +++ b/examples/franka/urdf/right_support.urdf @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 4f351f3179..7b134f426a 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -75,7 +75,7 @@ C3Controller::C3Controller( x_des_size)) .get_index(); target_input_port_ = - this->DeclareVectorInputPort("desired_position", x_des_size).get_index(); + this->DeclareVectorInputPort("x_lcs_des", x_des_size).get_index(); auto c3_solution = C3Output::C3Solution(); c3_solution.x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); @@ -168,7 +168,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( for (int i : vector({0, 2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.2, 0.7, 1); + c3_->AddLinearConstraint(A, 0.2, 0.8, 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); From 3edd6d6c1c018e587e2b87a16073654acb38442f Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 4 Dec 2023 17:19:22 -0500 Subject: [PATCH 551/758] adding supports demo --- examples/franka/franka_c3_controller.cc | 73 +++++++++++++------ examples/franka/franka_sim.cc | 3 +- .../parameters/franka_c3_controller_params.h | 13 ++++ .../franka_c3_controller_params.yaml | 11 ++- .../franka_c3_options_w_supports.yaml | 60 +++++++++++++++ .../franka/parameters/franka_sim_params.yaml | 10 +-- examples/franka/urdf/left_support.urdf | 6 +- .../urdf/left_support_point_contact.urdf | 34 +++++++++ examples/franka/urdf/right_support.urdf | 2 +- .../urdf/right_support_point_contact.urdf | 28 +++++++ systems/controllers/c3_controller.cc | 3 + systems/controllers/c3_controller.h | 1 + 12 files changed, 212 insertions(+), 32 deletions(-) create mode 100644 examples/franka/parameters/franka_c3_options_w_supports.yaml create mode 100644 examples/franka/urdf/left_support_point_contact.urdf create mode 100644 examples/franka/urdf/right_support_point_contact.urdf diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 00f4fb8b2f..9a643b41e5 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -3,9 +3,7 @@ #include #include #include -#include #include -#include #include #include #include @@ -17,14 +15,11 @@ #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/end_effector_trajectory.h" #include "examples/franka/systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" -#include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3_controller.h" -#include "systems/controllers/osc/operational_space_control.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" @@ -82,7 +77,6 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); - parser_franka.package_map().Add("franka_urdfs", "examples/franka/urdf"); parser_franka.AddModels( drake::FindResourceOrThrow(controller_params.franka_model)); drake::multibody::ModelInstanceIndex end_effector_index = @@ -112,32 +106,69 @@ int DoMain(int argc, char* argv[]) { auto tray_context = plant_tray.CreateDefaultContext(); /// - auto [plant_plate, scene_graph] = + auto [plant_for_lcs, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); - Parser parser_plate(&plant_plate); + Parser parser_plate(&plant_for_lcs); parser_plate.AddModels(controller_params.plate_model); parser_plate.AddModels(controller_params.tray_model); - plant_plate.WeldFrames(plant_plate.world_frame(), - plant_plate.GetFrameByName("base_link"), X_WI); - plant_plate.Finalize(); - std::unique_ptr> plant_plate_ad = - drake::systems::System::ToAutoDiffXd(plant_plate); + drake::multibody::ModelInstanceIndex left_support_index; + drake::multibody::ModelInstanceIndex right_support_index; + if (controller_params.scene_index == 1){ + left_support_index = + parser_plate.AddModels(FindResourceOrThrow(controller_params.left_support_model))[0]; + right_support_index = + parser_plate.AddModels(FindResourceOrThrow(controller_params.right_support_model))[0]; + Vector3d first_support_position = + StdVectorToVectorXd(controller_params.left_support_position); + Vector3d second_support_position = + StdVectorToVectorXd(controller_params.right_support_position); + RigidTransform T_S1_W = RigidTransform( + drake::math::RotationMatrix(), first_support_position); + RigidTransform T_S2_W = RigidTransform( + drake::math::RotationMatrix(), second_support_position); + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", left_support_index), + T_S1_W); + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", right_support_index), + T_S2_W); + } + + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("base_link"), X_WI); + plant_for_lcs.Finalize(); + std::unique_ptr> plant_for_lcs_autodiff = + drake::systems::System::ToAutoDiffXd(plant_for_lcs); auto plant_diagram = plant_builder.Build(); std::unique_ptr> diagram_context = plant_diagram->CreateDefaultContext(); auto& plate_context = plant_diagram->GetMutableSubsystemContext( - plant_plate, diagram_context.get()); - auto plate_context_ad = plant_plate_ad->CreateDefaultContext(); + plant_for_lcs, diagram_context.get()); + auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); /// std::vector plate_contact_points = - plant_plate.GetCollisionGeometriesForBody( - plant_plate.GetBodyByName("plate")); + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("plate")); + if (controller_params.scene_index == 1) { + std::vector left_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", left_support_index)); + std::vector right_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", right_support_index)); + plate_contact_points.insert(plate_contact_points.end(), + left_support_contact_points.begin(), + left_support_contact_points.end()); + plate_contact_points.insert(plate_contact_points.end(), + right_support_contact_points.begin(), + right_support_contact_points.end()); + } std::vector tray_geoms = - plant_plate.GetCollisionGeometriesForBody( - plant_plate.GetBodyByName("tray")); + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("tray")); std::unordered_map> contact_geoms; contact_geoms["PLATE"] = plate_contact_points; @@ -214,10 +245,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(tray_zero_velocity_source->get_output_port(), target_state_mux->get_input_port(3)); auto controller = builder.AddSystem( - plant_plate, &plate_context, *plant_plate_ad, plate_context_ad.get(), + plant_for_lcs, &plate_context, *plant_for_lcs_autodiff, plate_context_ad.get(), contact_pairs, c3_options); auto c3_trajectory_generator = - builder.AddSystem(plant_plate, + builder.AddSystem(plant_for_lcs, c3_options); std::vector state_names = { "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 33fd27f37d..5fc0cc9809 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -114,10 +114,11 @@ int DoMain(int argc, char* argv[]) { const drake::geometry::GeometrySet& paddle_geom_set = plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), &plant.GetBodyByName("panda_link4"), &plant.GetBodyByName("panda_link5"), &plant.GetBodyByName("panda_link6"), -// &plant.GetBodyByName("panda_link7"), &plant.GetBodyByName("panda_link8"), // &plant.GetBodyByName("plate"), }); diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 10276b94bb..9b8c44a594 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -15,15 +15,22 @@ struct FrankaC3ControllerParams { std::string end_effector_name; std::string plate_model; std::string tray_model; + std::string left_support_model; + std::string right_support_model; bool include_end_effector_orientation; double target_frequency; std::vector tool_attachment_frame; + int scene_index; + std::vector neutral_position; double x_scale; double y_scale; double z_scale; + std::vector left_support_position; + std::vector right_support_position; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(c3_options_file)); @@ -33,13 +40,19 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(end_effector_name)); a->Visit(DRAKE_NVP(plate_model)); a->Visit(DRAKE_NVP(tray_model)); + a->Visit(DRAKE_NVP(left_support_model)); + a->Visit(DRAKE_NVP(right_support_model)); a->Visit(DRAKE_NVP(include_end_effector_orientation)); a->Visit(DRAKE_NVP(target_frequency)); a->Visit(DRAKE_NVP(tool_attachment_frame)); + a->Visit(DRAKE_NVP(scene_index)); a->Visit(DRAKE_NVP(neutral_position)); a->Visit(DRAKE_NVP(x_scale)); a->Visit(DRAKE_NVP(y_scale)); a->Visit(DRAKE_NVP(z_scale)); + + a->Visit(DRAKE_NVP(left_support_position)); + a->Visit(DRAKE_NVP(right_support_position)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 0512ada758..5a468d28ab 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,5 +1,6 @@ -c3_options_file: examples/franka/parameters/franka_c3_options_translation.yaml +c3_options_file: examples/franka/parameters/franka_c3_options_w_supports.yaml +#c3_options_file: examples/franka/parameters/franka_c3_options_translation.yaml #c3_options_file: examples/franka/parameters/franka_c3_options_floating.yaml osqp_settings_file: examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -12,6 +13,14 @@ plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf +scene_index: 1 + +left_support_model: examples/franka/urdf/left_support_point_contact.urdf +right_support_model: examples/franka/urdf/right_support_point_contact.urdf +left_support_position: [0.55, 0.15, 0.225] +right_support_position: [0.8, -0.15, 0.225] + + include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 50 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml new file mode 100644 index 0000000000..774838de0c --- /dev/null +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -0,0 +1,60 @@ +admm_iter: 4 +rho: 0.1 +rho_scale: 1 +num_threads: 6 +delta_option: 1 +# options are 'MIQP' or 'QP' +projection_type: 'MIQP' +# options are 'stewart_and_trinkle' or 'anitescu' +#contact_model: 'stewart_and_trinkle' +contact_model: 'stewart_and_trinkle' +warm_start: true + +mu: 0.2 +mu_plate: 0.0 +dt: 0.05 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 6 +N: 5 + +# matrix scaling +w_Q: 30 +w_R: 0 +# Penalty on all decision variables, assuming scalar +w_G: 1 +# Penalty on all decision variables, assuming scalar +w_U: 0.5 + +# n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions +# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 6 + 2 * 6 * 2) + n_u (3) = 58 for stewart and trinkle +# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu +g_size: 58 +u_size: 58 +#g_size: 34 +#u_size: 34 +# State Tracking Error, assuming diagonal +q_vector: [175, 175, 175, 0, 0, 0, 0, 15000, 15000, 15000, + 5, 5, 10, 1, 1, 1, 5, 5, 5] +# Penalty on all decision variables +g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, + 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] + + + +# Penalty on all decision variables +u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, + 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, + 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] +#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +# Penalty on efforts, assuming diagonal +r_vector: [0.1, 0.1, 1] + +#g_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#u_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b94ef1877f..ff087a9cd4 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -11,18 +11,18 @@ franka_publish_rate: 1000 tray_publish_rate: 10 actuator_delay: 0.000 -scene_index: 0 +scene_index: 1 visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.55, 0.15, 0.225] -right_support_position: [0.8, -0.15, 0.225] +left_support_position: [0.65, 0.15, 0.225] +right_support_position: [0.7875, -0.15, 0.225] dt: 0.0005 realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [1, 0, 0, 0, 0.56, 0.0, 0.450] -#q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] +#q_init_plate: [1, 0, 0, 0, 0.56, 0.04, 0.450] +q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index 7b77c3b0ed..3a380e520a 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -1,6 +1,6 @@ - + @@ -15,7 +15,7 @@ - + @@ -27,7 +27,7 @@ - + diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf new file mode 100644 index 0000000000..7f4091e575 --- /dev/null +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -0,0 +1,34 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/right_support.urdf b/examples/franka/urdf/right_support.urdf index b4826f0205..92c363edbb 100644 --- a/examples/franka/urdf/right_support.urdf +++ b/examples/franka/urdf/right_support.urdf @@ -1,6 +1,6 @@ - + diff --git a/examples/franka/urdf/right_support_point_contact.urdf b/examples/franka/urdf/right_support_point_contact.urdf new file mode 100644 index 0000000000..773d7fb57a --- /dev/null +++ b/examples/franka/urdf/right_support_point_contact.urdf @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7b134f426a..3d5d86e0a8 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -74,6 +74,9 @@ C3Controller::C3Controller( "x_lcs", TimestampedVector( x_des_size)) .get_index(); +// lcs_input_port_ = +// this->DeclareAbstractInputPort("lcs", LCS()); + target_input_port_ = this->DeclareVectorInputPort("x_lcs_des", x_des_size).get_index(); diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index a79566b977..6448965bde 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -67,6 +67,7 @@ class C3Controller : public drake::systems::LeafSystem { C3Output::C3Intermediates* c3_intermediates) const; drake::systems::InputPortIndex target_input_port_; + drake::systems::InputPortIndex lcs_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::OutputPortIndex c3_solution_port_; drake::systems::OutputPortIndex c3_intermediates_port_; From 8d5f0dabb2ab73f1bd5712711b4e5cb80ff996e6 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 5 Dec 2023 12:02:24 -0500 Subject: [PATCH 552/758] organizing c3 gains --- .../franka_c3_options_w_supports.yaml | 40 +++++++++++------ .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 4 +- .../urdf/left_support_point_contact.urdf | 4 +- examples/franka/urdf/plate_end_effector.urdf | 3 ++ solvers/c3_options.h | 45 +++++++++++++++++-- 6 files changed, 76 insertions(+), 22 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 774838de0c..0db4b16b8c 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -8,15 +8,15 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'stewart_and_trinkle' -warm_start: true +warm_start: false -mu: 0.2 +mu: 0.1 mu_plate: 0.0 dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 6 -N: 5 +N: 7 # matrix scaling w_Q: 30 @@ -34,25 +34,37 @@ u_size: 58 #g_size: 34 #u_size: 34 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 0, 0, 0, 0, 15000, 15000, 15000, +q_vector: [175, 175, 125, 0, 0, 0, 0, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] +# Penalty on efforts, assuming diagonal +r_vector: [0.1, 0.1, 1] + # Penalty on all decision variables -g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, +# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # 19 +g_gamma: [1, 1, 1, 1, 1, 1] # 6 +g_lambda_n: [1, 1, 1, 1, 1, 1] # 6 +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # 24 +g_u: [1, 1, 1] # 3 + #g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables -u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, - 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, - 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] -#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -# Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 1] +#u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, +# 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, +# 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] +u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10] +u_gamma: [1, 1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_u: [10, 10, 10] + + #g_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 9bd9799fa5..1d1f5bbf10 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -6,7 +6,7 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.55, 0, 0.45] +neutral_position: [0.55, 0, 0.43] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index ff087a9cd4..49ecbca1ab 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/right_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 10 +tray_publish_rate: 100 actuator_delay: 0.000 scene_index: 1 @@ -20,7 +20,7 @@ left_support_position: [0.65, 0.15, 0.225] right_support_position: [0.7875, -0.15, 0.225] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.1 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] #q_init_plate: [1, 0, 0, 0, 0.56, 0.04, 0.450] diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index 7f4091e575..cbc9cfb74d 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,13 +13,13 @@ izz="0.013"/> - + - + diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 1bb32b3105..564e616c2e 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -21,6 +21,9 @@ + + + diff --git a/solvers/c3_options.h b/solvers/c3_options.h index d3fb7d51f8..1e75f575ac 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -1,5 +1,5 @@ #pragma once - +#include #include "drake/common/yaml/yaml_read_archive.h" struct C3Options { @@ -26,7 +26,17 @@ struct C3Options { std::vector q_vector; std::vector r_vector; std::vector g_vector; + std::vector g_x; + std::vector g_gamma; + std::vector g_lambda_n; + std::vector g_lambda_t; + std::vector g_u; std::vector u_vector; + std::vector u_x; + std::vector u_gamma; + std::vector u_lambda_n; + std::vector u_lambda_t; + std::vector u_u; double mu; double mu_plate; @@ -68,9 +78,38 @@ struct C3Options { a->Visit(DRAKE_NVP(g_size)); a->Visit(DRAKE_NVP(u_size)); a->Visit(DRAKE_NVP(q_vector)); - a->Visit(DRAKE_NVP(g_vector)); - a->Visit(DRAKE_NVP(u_vector)); a->Visit(DRAKE_NVP(r_vector)); +// a->Visit(DRAKE_NVP(g_vector)); + a->Visit(DRAKE_NVP(g_x)); + a->Visit(DRAKE_NVP(g_gamma)); + a->Visit(DRAKE_NVP(g_lambda_n)); + a->Visit(DRAKE_NVP(g_lambda_t)); + a->Visit(DRAKE_NVP(g_u)); +// a->Visit(DRAKE_NVP(u_vector)); + a->Visit(DRAKE_NVP(u_x)); + a->Visit(DRAKE_NVP(u_gamma)); + a->Visit(DRAKE_NVP(u_lambda_n)); + a->Visit(DRAKE_NVP(u_lambda_t)); + a->Visit(DRAKE_NVP(u_u)); + + g_vector = std::vector(); + g_vector.insert(g_vector.end(), g_x.begin(), g_x.end()); + g_vector.insert(g_vector.end(), g_gamma.begin(), g_gamma.end()); + g_vector.insert(g_vector.end(), g_lambda_n.begin(), g_lambda_n.end()); + g_vector.insert(g_vector.end(), g_lambda_t.begin(), g_lambda_t.end()); + g_vector.insert(g_vector.end(), g_u.begin(), g_u.end()); + u_vector = std::vector(); + u_vector.insert(u_vector.end(), u_x.begin(), u_x.end()); + u_vector.insert(u_vector.end(), u_gamma.begin(), u_gamma.end()); + u_vector.insert(u_vector.end(), u_lambda_n.begin(), u_lambda_n.end()); + u_vector.insert(u_vector.end(), u_lambda_t.begin(), u_lambda_t.end()); + u_vector.insert(u_vector.end(), u_u.begin(), u_u.end()); + + for (auto value : u_vector){ + std::cout << value << std::endl; + } + DRAKE_DEMAND(u_size == u_vector.size()); + DRAKE_DEMAND(g_size == g_vector.size()); Eigen::VectorXd q = Eigen::Map( this->q_vector.data(), this->q_vector.size()); From 5ba8aedee21ca65ea575bafcaf84b47d3aca8f22 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Dec 2023 13:58:14 -0500 Subject: [PATCH 553/758] cleaner way to change scenes --- examples/franka/franka_c3_controller.cc | 2 +- examples/franka/franka_sim.cc | 16 +++++----- .../parameters/franka_c3_controller_params.h | 2 +- .../franka_c3_controller_params.yaml | 5 ++-- .../franka_c3_options_translation.yaml | 25 +++++++++++----- .../franka_c3_options_w_supports.yaml | 29 ++++--------------- .../franka/parameters/franka_sim_params.h | 2 +- .../franka/parameters/franka_sim_params.yaml | 6 ++-- 8 files changed, 40 insertions(+), 47 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 9a643b41e5..3d2dd5d52a 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -67,7 +67,7 @@ int DoMain(int argc, char* argv[]) { FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); C3Options c3_options = - drake::yaml::LoadYamlFile(controller_params.c3_options_file); + drake::yaml::LoadYamlFile(controller_params.c3_options_file[controller_params.scene_index]); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(controller_params.osqp_settings_file)) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 5fc0cc9809..74732fffe9 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -191,13 +191,15 @@ int DoMain(int argc, char* argv[]) { q[q_map["panda_joint6"]] = sim_params.q_init_franka[5]; q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; - q[q_map.at("tray_qw")] = sim_params.q_init_plate[0]; - q[q_map.at("tray_qx")] = sim_params.q_init_plate[1]; - q[q_map.at("tray_qy")] = sim_params.q_init_plate[2]; - q[q_map.at("tray_qz")] = sim_params.q_init_plate[3]; - q[q_map.at("tray_x")] = sim_params.q_init_plate[4]; - q[q_map.at("tray_y")] = sim_params.q_init_plate[5]; - q[q_map.at("tray_z")] = sim_params.q_init_plate[6]; + auto q_init_plate = sim_params.q_init_plate[sim_params.scene_index]; + + q[q_map.at("tray_qw")] = q_init_plate[0]; + q[q_map.at("tray_qx")] = q_init_plate[1]; + q[q_map.at("tray_qy")] = q_init_plate[2]; + q[q_map.at("tray_qz")] = q_init_plate[3]; + q[q_map.at("tray_x")] = q_init_plate[4]; + q[q_map.at("tray_y")] = q_init_plate[5]; + q[q_map.at("tray_z")] = q_init_plate[6]; // q[q_map["box_qw"]] = sim_params.q_init_box[0]; // q[q_map["box_qx"]] = sim_params.q_init_box[1]; diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 9b8c44a594..c5d617382a 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -8,7 +8,7 @@ using Eigen::MatrixXd; using Eigen::VectorXd; struct FrankaC3ControllerParams { - std::string c3_options_file; + std::vector c3_options_file; std::string osqp_settings_file; std::string franka_model; std::string end_effector_model; diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 5a468d28ab..01d0b5d6b8 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,7 +1,6 @@ -c3_options_file: examples/franka/parameters/franka_c3_options_w_supports.yaml -#c3_options_file: examples/franka/parameters/franka_c3_options_translation.yaml -#c3_options_file: examples/franka/parameters/franka_c3_options_floating.yaml +c3_options_file: [examples/franka/parameters/franka_c3_options_translation.yaml, + examples/franka/parameters/franka_c3_options_w_supports.yaml] osqp_settings_file: examples/Cassie/osc_run/osc_running_qp_settings.yaml franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 4fc995813f..aad9fa339a 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -36,21 +36,30 @@ u_size: 40 # State Tracking Error, assuming diagonal q_vector: [175, 175, 175, 0, 0, 0, 0, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] + +# Penalty on efforts, assuming diagonal +r_vector: [0.1, 0.1, 1] + # Penalty on all decision variables -g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, - 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_gamma: [1, 1, 1] +g_lambda_n: [1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_u: [1, 1, 1] #g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # Penalty on all decision variables -u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, - 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] -#u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -# Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 1] +#u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, +# 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] +u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10] +u_gamma: [1, 1, 1] +u_lambda_n: [1, 1, 1] +u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_u: [10, 10, 10] + #g_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, # 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 0db4b16b8c..d2acf319cf 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -40,33 +40,14 @@ q_vector: [175, 175, 125, 0, 0, 0, 0, 15000, 15000, 15000, r_vector: [0.1, 0.1, 1] # Penalty on all decision variables -#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # 19 -g_gamma: [1, 1, 1, 1, 1, 1] # 6 -g_lambda_n: [1, 1, 1, 1, 1, 1] # 6 -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] # 24 -g_u: [1, 1, 1] # 3 +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_gamma: [1, 1, 1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_u: [1, 1, 1] -#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] - - - -# Penalty on all decision variables -#u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, -# 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, -# 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10] u_gamma: [1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_u: [10, 10, 10] - - - -#g_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -#u_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 0fe5cae49a..43088485ea 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -25,7 +25,7 @@ struct FrankaSimParams { bool publish_efforts; std::vector q_init_franka; - std::vector q_init_plate; + std::vector> q_init_plate; std::vector q_init_box; std::vector tool_attachment_frame; std::vector left_support_position; diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 49ecbca1ab..eb4da76742 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -23,6 +23,8 @@ dt: 0.0005 realtime_rate: 0.1 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -#q_init_plate: [1, 0, 0, 0, 0.56, 0.04, 0.450] -q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] + +q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.470], + [1, 0, 0, 0, 0.7, 0.00, 0.50]] +#q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] From 8f16e8d76ebed9725aef547c10e5ae0375e41383 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Dec 2023 14:47:03 -0500 Subject: [PATCH 554/758] changing mu to be a diagonal matrix --- .../parameters/franka_c3_options_translation.yaml | 3 +-- .../parameters/franka_c3_options_w_supports.yaml | 3 +-- solvers/c3_options.h | 15 ++++++--------- solvers/lcs_factory.cc | 9 +++++---- solvers/lcs_factory.h | 2 +- 5 files changed, 14 insertions(+), 18 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index aad9fa339a..97d842de09 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -10,8 +10,7 @@ projection_type: 'MIQP' contact_model: 'stewart_and_trinkle' warm_start: true -mu: 0.2 -mu_plate: 0.0 +mu: [0.2, 0.2, 0.2] dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index d2acf319cf..ab9d3534b0 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -10,8 +10,7 @@ projection_type: 'MIQP' contact_model: 'stewart_and_trinkle' warm_start: false -mu: 0.1 -mu_plate: 0.0 +mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05] dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 1e75f575ac..5c680bba90 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -4,12 +4,11 @@ struct C3Options { // Hyperparameters - int admm_iter = 2; // total number of ADMM iterations //2 - float rho = 0.1; // inital value of the rho parameter - float rho_scale = - 3; // scaling of rho parameter (/rho = rho_scale * /rho) //3 - int num_threads = 0; // 0 is dynamic, greater than 0 for a fixed count - int delta_option = 1; // different options for delta update + int admm_iter; // total number of ADMM iterations //2 + float rho; // inital value of the rho parameter + float rho_scale; // scaling of rho parameter (/rho = rho_scale * /rho) //3 + int num_threads; // 0 is dynamic, greater than 0 for a fixed count + int delta_option; // different options for delta update std::string projection_type; std::string contact_model; bool warm_start; @@ -38,8 +37,7 @@ struct C3Options { std::vector u_lambda_t; std::vector u_u; - double mu; - double mu_plate; + std::vector mu; double dt; double solve_dt; int num_friction_directions; @@ -64,7 +62,6 @@ struct C3Options { a->Visit(DRAKE_NVP(warm_start)); a->Visit(DRAKE_NVP(mu)); - a->Visit(DRAKE_NVP(mu_plate)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(solve_dt)); a->Visit(DRAKE_NVP(num_friction_directions)); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 4781921a55..389d5d3616 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -33,7 +33,7 @@ std::pair LCSFactory::LinearizePlantToLCS( const MultibodyPlant& plant_ad, const Context& context_ad, const vector>& contact_geoms, - int num_friction_directions, double mu, double dt, int N, + int num_friction_directions, const std::vector& mu, double dt, int N, ContactModel contact_model) { // int n_q = plant_ad.num_positions(); // int n_v = plant_ad.num_velocities(); @@ -178,7 +178,6 @@ std::pair LCSFactory::LinearizePlantToLCS( E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q + J_n * NqInverse; - ; E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = dt * J_t * AB_v_q; E.block(n_contacts, n_q, n_contacts, n_v) = @@ -187,7 +186,9 @@ std::pair LCSFactory::LinearizePlantToLCS( n_v) = J_t + dt * J_t * AB_v_v; F.block(0, n_contacts, n_contacts, n_contacts) = - mu * MatrixXd::Identity(n_contacts, n_contacts); + Eigen::Map( + mu.data(), mu.size()).asDiagonal(); + F.block(0, 2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions) = -E_t; @@ -220,7 +221,7 @@ std::pair LCSFactory::LinearizePlantToLCS( } else if (contact_model == ContactModel::kAnitescu) { MatrixXd Nqinv = Nq.completeOrthogonalDecomposition().pseudoInverse(); // auto M_ldlt = ExtractValue(M).ldlt(); - MatrixXd J_c = E_t.transpose() * J_n + mu * J_t; + MatrixXd J_c = E_t.transpose() * J_n + mu[0] * J_t; MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); D.block(0, 0, n_q, n_contacts) = dt * Nq * MinvJ_c_T; diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index c1290ec873..b50a1fe209 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -40,7 +40,7 @@ class LCSFactory { const drake::systems::Context& context_ad, const std::vector>& contact_geoms, - int num_friction_directions, double mu, double dt, int N, ContactModel=ContactModel::kStewartAndTrinkle); + int num_friction_directions, const std::vector& mu, double dt, int N, ContactModel=ContactModel::kStewartAndTrinkle); /// Create an LCS by fixing some modes from another LCS /// Ignores generated inequalities that correspond to these modes, but From b216bed2836ed232fc93cea0664a0ff724b18d5b Mon Sep 17 00:00:00 2001 From: AlpAydinoglu Date: Tue, 5 Dec 2023 15:06:32 -0500 Subject: [PATCH 555/758] option to use anitescu model --- .../franka_c3_options_w_supports.yaml | 10 +++--- .../franka/parameters/franka_sim_params.yaml | 4 +-- solvers/c3_options.h | 36 ++++++++++++------- 3 files changed, 31 insertions(+), 19 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index ab9d3534b0..a127f5047d 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -6,8 +6,8 @@ delta_option: 1 # options are 'MIQP' or 'QP' projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'stewart_and_trinkle' contact_model: 'stewart_and_trinkle' +# contact_model: 'anitescu' warm_start: false mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05] @@ -27,9 +27,9 @@ w_U: 0.5 # n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions # size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 6 + 2 * 6 * 2) + n_u (3) = 58 for stewart and trinkle -# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu -g_size: 58 -u_size: 58 +# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 6 * 2) + n_u (3) = 34 for anitescu +# g_size: 58 +# u_size: 58 #g_size: 34 #u_size: 34 # State Tracking Error, assuming diagonal @@ -43,10 +43,12 @@ g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_gamma: [1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_u: [1, 1, 1] u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10] u_gamma: [1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_u: [10, 10, 10] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index eb4da76742..b813a5356a 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/right_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 100 +tray_publish_rate: 1000 actuator_delay: 0.000 scene_index: 1 @@ -25,6 +25,6 @@ realtime_rate: 0.1 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.470], - [1, 0, 0, 0, 0.7, 0.00, 0.50]] + [1, 0, 0, 0, 0.7, 0.00, 0.47]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 5c680bba90..6b0860a3b8 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -29,12 +29,14 @@ struct C3Options { std::vector g_gamma; std::vector g_lambda_n; std::vector g_lambda_t; + std::vector g_lambda; std::vector g_u; std::vector u_vector; std::vector u_x; std::vector u_gamma; std::vector u_lambda_n; std::vector u_lambda_t; + std::vector u_lambda; std::vector u_u; std::vector mu; @@ -72,8 +74,8 @@ struct C3Options { a->Visit(DRAKE_NVP(w_R)); a->Visit(DRAKE_NVP(w_G)); a->Visit(DRAKE_NVP(w_U)); - a->Visit(DRAKE_NVP(g_size)); - a->Visit(DRAKE_NVP(u_size)); + // a->Visit(DRAKE_NVP(g_size)); + // a->Visit(DRAKE_NVP(u_size)); a->Visit(DRAKE_NVP(q_vector)); a->Visit(DRAKE_NVP(r_vector)); // a->Visit(DRAKE_NVP(g_vector)); @@ -81,32 +83,40 @@ struct C3Options { a->Visit(DRAKE_NVP(g_gamma)); a->Visit(DRAKE_NVP(g_lambda_n)); a->Visit(DRAKE_NVP(g_lambda_t)); + a->Visit(DRAKE_NVP(g_lambda)); a->Visit(DRAKE_NVP(g_u)); // a->Visit(DRAKE_NVP(u_vector)); a->Visit(DRAKE_NVP(u_x)); a->Visit(DRAKE_NVP(u_gamma)); a->Visit(DRAKE_NVP(u_lambda_n)); a->Visit(DRAKE_NVP(u_lambda_t)); + a->Visit(DRAKE_NVP(u_lambda)); a->Visit(DRAKE_NVP(u_u)); g_vector = std::vector(); g_vector.insert(g_vector.end(), g_x.begin(), g_x.end()); - g_vector.insert(g_vector.end(), g_gamma.begin(), g_gamma.end()); - g_vector.insert(g_vector.end(), g_lambda_n.begin(), g_lambda_n.end()); - g_vector.insert(g_vector.end(), g_lambda_t.begin(), g_lambda_t.end()); + if (contact_model == "stewart_and_trinkle"){ + g_vector.insert(g_vector.end(), g_gamma.begin(), g_gamma.end()); + g_vector.insert(g_vector.end(), g_lambda_n.begin(), g_lambda_n.end()); + g_vector.insert(g_vector.end(), g_lambda_t.begin(), g_lambda_t.end()); + }else{ + g_vector.insert(g_vector.end(), g_lambda.begin(), g_lambda.end()); + } + g_vector.insert(g_vector.end(), g_u.begin(), g_u.end()); u_vector = std::vector(); u_vector.insert(u_vector.end(), u_x.begin(), u_x.end()); - u_vector.insert(u_vector.end(), u_gamma.begin(), u_gamma.end()); - u_vector.insert(u_vector.end(), u_lambda_n.begin(), u_lambda_n.end()); - u_vector.insert(u_vector.end(), u_lambda_t.begin(), u_lambda_t.end()); + if (contact_model == "stewart_and_trinkle"){ + u_vector.insert(u_vector.end(), u_gamma.begin(), u_gamma.end()); + u_vector.insert(u_vector.end(), u_lambda_n.begin(), u_lambda_n.end()); + u_vector.insert(u_vector.end(), u_lambda_t.begin(), u_lambda_t.end()); + }else{ + u_vector.insert(u_vector.end(), u_lambda.begin(), u_lambda.end()); + } u_vector.insert(u_vector.end(), u_u.begin(), u_u.end()); - for (auto value : u_vector){ - std::cout << value << std::endl; - } - DRAKE_DEMAND(u_size == u_vector.size()); - DRAKE_DEMAND(g_size == g_vector.size()); + // DRAKE_DEMAND(u_size == u_vector.size()); + // DRAKE_DEMAND(g_size == g_vector.size()); Eigen::VectorXd q = Eigen::Map( this->q_vector.data(), this->q_vector.size()); From ff4d2cfd2dc7ac083da213693235e3824fc6ace5 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 5 Dec 2023 16:02:18 -0500 Subject: [PATCH 556/758] making sure im parallelizing correctly --- .../franka_c3_options_translation.yaml | 23 +++------------ .../franka_c3_options_w_supports.yaml | 15 +++------- solvers/c3.cc | 29 +++++++++---------- 3 files changed, 22 insertions(+), 45 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 97d842de09..607783dd51 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -1,12 +1,12 @@ admm_iter: 4 rho: 0.1 rho_scale: 1 -num_threads: 6 +num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'stewart_and_trinkle' +#contact_model: 'anitescu' contact_model: 'stewart_and_trinkle' warm_start: true @@ -25,13 +25,6 @@ w_G: 1 # Penalty on all decision variables, assuming scalar w_U: 0.5 -# n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions -# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 3 + 2 * 3 * 2) + n_u (3) = 40 for stewart and trinkle -# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 3 * 2) + n_u (3) = 34 for anitescu -g_size: 40 -u_size: 40 -#g_size: 34 -#u_size: 34 # State Tracking Error, assuming diagonal q_vector: [175, 175, 175, 0, 0, 0, 0, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] @@ -44,11 +37,8 @@ g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_gamma: [1, 1, 1] g_lambda_n: [1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_u: [1, 1, 1] -#g_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] - - # Penalty on all decision variables #u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, @@ -57,10 +47,5 @@ u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 1 u_gamma: [1, 1, 1] u_lambda_n: [1, 1, 1] u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_lambda: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_u: [10, 10, 10] - - -#g_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -#u_vector: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, -# 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index a127f5047d..d947620e7f 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,13 +1,13 @@ admm_iter: 4 rho: 0.1 rho_scale: 1 -num_threads: 6 +num_threads: 7 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'MIQP' +projection_type: 'QP' # options are 'stewart_and_trinkle' or 'anitescu' -contact_model: 'stewart_and_trinkle' -# contact_model: 'anitescu' +#contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' warm_start: false mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05] @@ -25,13 +25,6 @@ w_G: 1 # Penalty on all decision variables, assuming scalar w_U: 0.5 -# n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions -# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 6 + 2 * 6 * 2) + n_u (3) = 58 for stewart and trinkle -# size = n_x ( 3 + 7 + 3 + 6 ) + n_lambda (2 * 6 * 2) + n_u (3) = 34 for anitescu -# g_size: 58 -# u_size: 58 -#g_size: 34 -#u_size: 34 # State Tracking Error, assuming diagonal q_vector: [175, 175, 125, 0, 0, 0, 0, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] diff --git a/solvers/c3.cc b/solvers/c3.cc index b576659f98..cb46996193 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -217,14 +217,14 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, } // /// initialize decision variables to warm start -// if (warm_start_) { -// for (int i = 0; i < N_; i++) { -// prog_.SetInitialGuess(x_[i], warm_start_x_[i]); -// prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[i]); -// prog_.SetInitialGuess(u_[i], warm_start_u_[i]); -// } -// prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); -// } + // if (warm_start_) { + // for (int i = 0; i < N_; i++) { + // prog_.SetInitialGuess(x_[i], warm_start_x_[i]); + // prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[i]); + // prog_.SetInitialGuess(u_[i], warm_start_u_[i]); + // } + // prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); + // } prog_.SetSolverOptions(solver_options_); MathematicalProgramResult result = osqp_.Solve(prog_); @@ -287,16 +287,15 @@ void C3::RemoveConstraints() { vector C3::SolveProjection(vector& G, vector& WZ) { vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); - int i; - if (options_.num_threads > 0) { - omp_set_dynamic(0); // Explicitly disable dynamic teams - omp_set_num_threads(options_.num_threads); // Set number of threads - omp_set_nested(1); - } +// if (options_.num_threads > 0) { +// omp_set_num_threads(options_.num_threads); // Set number of threads +// omp_set_nested(1); +// } + omp_set_dynamic(0); // Explicitly disable dynamic teams #pragma omp parallel for num_threads(N_) - for (i = 0; i < N_; i++) { + for (int i = 0; i < N_; ++i) { if (warm_start_) { deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], i); From 4b34373774ee7d1a6b55e17af9be8b6f3a53c316 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 6 Dec 2023 17:26:15 -0500 Subject: [PATCH 557/758] debugging scene 2 --- examples/franka/franka_sim.cc | 27 +++++++-- .../franka_c3_controller_params.yaml | 6 +- .../franka_c3_options_w_supports.yaml | 30 +++++----- .../franka_osc_controller_params.yaml | 6 +- .../franka/parameters/franka_sim_params.yaml | 6 +- examples/franka/urdf/left_support.urdf | 4 +- solvers/c3.cc | 13 +++-- solvers/c3_options.h | 7 +-- solvers/lcs_factory.cc | 56 ++++++++++--------- systems/controllers/c3_controller.cc | 6 +- .../osc/operational_space_control.cc | 2 - 11 files changed, 92 insertions(+), 71 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 74732fffe9..df8ccb7fac 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -91,11 +91,11 @@ int DoMain(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); - if (sim_params.scene_index == 1){ + if (sim_params.scene_index == 1) { drake::multibody::ModelInstanceIndex left_support_index = parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; - drake::multibody::ModelInstanceIndex right_support_index = - parser.AddModels(FindResourceOrThrow(sim_params.right_support_model))[0]; + drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( + FindResourceOrThrow(sim_params.right_support_model))[0]; Vector3d first_support_position = StdVectorToVectorXd(sim_params.left_support_position); Vector3d second_support_position = @@ -110,6 +110,24 @@ int DoMain(int argc, char* argv[]) { plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", right_support_index), T_S2_W); + const drake::geometry::GeometrySet& support_geom_set = + plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("support", left_support_index), + &plant.GetBodyByName("support", right_support_index), + }); + const drake::geometry::GeometrySet& paddle_geom_set = + plant.CollectRegisteredGeometries( + {&plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link7"), + &plant.GetBodyByName("plate"), + &plant.GetBodyByName("panda_link8")}); + + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"paddle", support_geom_set}, {"tray", paddle_geom_set}); } const drake::geometry::GeometrySet& paddle_geom_set = @@ -120,7 +138,8 @@ int DoMain(int argc, char* argv[]) { &plant.GetBodyByName("panda_link5"), &plant.GetBodyByName("panda_link6"), &plant.GetBodyByName("panda_link8"), -// &plant.GetBodyByName("plate"), + + // &plant.GetBodyByName("plate"), }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 01d0b5d6b8..4d4607629c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -14,8 +14,8 @@ tray_model: examples/franka/urdf/tray.sdf scene_index: 1 -left_support_model: examples/franka/urdf/left_support_point_contact.urdf -right_support_model: examples/franka/urdf/right_support_point_contact.urdf +left_support_model: examples/franka/urdf/left_support.urdf +right_support_model: examples/franka/urdf/right_support.urdf left_support_position: [0.55, 0.15, 0.225] right_support_position: [0.8, -0.15, 0.225] @@ -24,7 +24,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 50 -neutral_position: [0.55, 0, 0.47] +neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index d947620e7f..f2308dfea5 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,6 +1,6 @@ admm_iter: 4 rho: 0.1 -rho_scale: 1 +rho_scale: 2 num_threads: 7 delta_option: 1 # options are 'MIQP' or 'QP' @@ -10,38 +10,38 @@ projection_type: 'QP' contact_model: 'anitescu' warm_start: false -mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05] +mu: [0.4, 0.4, 0.4, 0.01, 0.01] dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 -num_contacts: 6 +num_contacts: 5 N: 7 # matrix scaling -w_Q: 30 -w_R: 0 +w_Q: 50 +w_R: 0.01 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar w_U: 0.5 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 125, 0, 0, 0, 0, 15000, 15000, 15000, +q_vector: [175, 175, 125, 1, 1, 1, 1, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 1] # Penalty on all decision variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_gamma: [1, 1, 1, 1, 1, 1] -g_lambda_n: [1, 1, 1, 1, 1, 1] -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_gamma: [1, 1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] g_u: [1, 1, 1] -u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10] -u_gamma: [1, 1, 1, 1, 1, 1] -u_lambda_n: [1, 1, 1, 1, 1, 1] -u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1] +u_gamma: [1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] u_u: [10, 10, 10] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 1d1f5bbf10..e7f2a107a1 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [0.1, 0, 0, - 0, 0.1, 0, - 0, 0, 0.1] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b813a5356a..17225b4a4b 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -6,7 +6,7 @@ table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_du tray_model: examples/franka/urdf/tray.sdf box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf -right_support_model: examples/franka/urdf/right_support.urdf +right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 actuator_delay: 0.000 @@ -17,10 +17,10 @@ publish_efforts: true tool_attachment_frame: [0, 0, 0.107] left_support_position: [0.65, 0.15, 0.225] -right_support_position: [0.7875, -0.15, 0.225] +right_support_position: [0.65, -0.15, 0.225] dt: 0.0005 -realtime_rate: 0.1 +realtime_rate: 0.5 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index 3a380e520a..ba1719f487 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -20,8 +20,8 @@ - - + + diff --git a/solvers/c3.cc b/solvers/c3.cc index cb46996193..cd776ed188 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -287,15 +287,16 @@ void C3::RemoveConstraints() { vector C3::SolveProjection(vector& G, vector& WZ) { vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); + int i; -// if (options_.num_threads > 0) { -// omp_set_num_threads(options_.num_threads); // Set number of threads -// omp_set_nested(1); -// } - omp_set_dynamic(0); // Explicitly disable dynamic teams + if (options_.num_threads > 0) { + omp_set_dynamic(0); // Explicitly disable dynamic teams + omp_set_num_threads(options_.num_threads); // Set number of threads + omp_set_nested(1); + } #pragma omp parallel for num_threads(N_) - for (int i = 0; i < N_; ++i) { + for (i = 0; i < N_; i++) { if (warm_start_) { deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], i); diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 6b0860a3b8..e8638e676e 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -19,9 +19,6 @@ struct C3Options { double w_G; double w_U; - int g_size; - int u_size; - std::vector q_vector; std::vector r_vector; std::vector g_vector; @@ -30,6 +27,7 @@ struct C3Options { std::vector g_lambda_n; std::vector g_lambda_t; std::vector g_lambda; + std::vector g_u; std::vector u_vector; std::vector u_x; @@ -115,9 +113,6 @@ struct C3Options { } u_vector.insert(u_vector.end(), u_u.begin(), u_u.end()); - // DRAKE_DEMAND(u_size == u_vector.size()); - // DRAKE_DEMAND(g_size == g_vector.size()); - Eigen::VectorXd q = Eigen::Map( this->q_vector.data(), this->q_vector.size()); Eigen::VectorXd r = Eigen::Map( diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 389d5d3616..a604e2dc88 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -33,8 +33,8 @@ std::pair LCSFactory::LinearizePlantToLCS( const MultibodyPlant& plant_ad, const Context& context_ad, const vector>& contact_geoms, - int num_friction_directions, const std::vector& mu, double dt, int N, - ContactModel contact_model) { + int num_friction_directions, const std::vector& mu, double dt, + int N, ContactModel contact_model) { // int n_q = plant_ad.num_positions(); // int n_v = plant_ad.num_velocities(); int n_x = plant_ad.num_positions() + plant_ad.num_velocities(); @@ -85,14 +85,14 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd d_q = ExtractValue(qdot_no_contact); Eigen::SparseMatrix Nqt; Nqt = plant.MakeVelocityToQDotMap(context); - MatrixXd Nq = MatrixXd(Nqt); + MatrixXd qdotNv = MatrixXd(Nqt); // plant_ad.MapQDotToVelocity(context_ad, qdot_no_contact, &vel); // std::optional> NqI = std::nullopt; Eigen::SparseMatrix NqI; NqI = plant.MakeQDotToVelocityMap(context); - MatrixXd NqInverse = MatrixXd(NqI); + MatrixXd vNqdot = MatrixXd(NqI); /// /// Contact-related terms /// @@ -129,15 +129,15 @@ std::pair LCSFactory::LinearizePlantToLCS( plant.CalcMassMatrix(context, &M_double); A.block(0, 0, n_q, n_q) = - MatrixXd::Identity(n_q, n_q) + dt * dt * Nq * AB_v_q; - A.block(0, n_q, n_q, n_v) = dt * Nq + dt * dt * Nq * AB_v_v; + MatrixXd::Identity(n_q, n_q) + dt * dt * qdotNv * AB_v_q; + A.block(0, n_q, n_q, n_v) = dt * qdotNv + dt * dt * qdotNv * AB_v_v; A.block(n_q, 0, n_v, n_q) = dt * AB_v_q; A.block(n_q, n_q, n_v, n_v) = dt * AB_v_v + MatrixXd::Identity(n_v, n_v); - B.block(0, 0, n_q, n_u) = dt * dt * Nq * AB_v_u; + B.block(0, 0, n_q, n_u) = dt * dt * qdotNv * AB_v_u; B.block(n_q, 0, n_v, n_u) = dt * AB_v_u; - d.head(n_q) = dt * dt * Nq * d_v; + d.head(n_q) = dt * dt * qdotNv * d_v; d.tail(n_v) = dt * d_v; MatrixXd E_t = @@ -148,11 +148,6 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd::Ones(1, 2 * num_friction_directions); } - // MatrixXd D(n_x, n_contact_vars); - // MatrixXd E(n_contact_vars, n_x); - // MatrixXd F(n_contact_vars, n_contact_vars); - // MatrixXd H(n_contact_vars, n_u); - // VectorXd c(n_contact_vars); int n_contact_vars = 0; if (contact_model == ContactModel::kStewartAndTrinkle) { n_contact_vars = 2 * n_contacts + 2 * n_contacts * num_friction_directions; @@ -168,16 +163,16 @@ std::pair LCSFactory::LinearizePlantToLCS( if (contact_model == ContactModel::kStewartAndTrinkle) { D.block(0, 2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions) = - dt * dt * Nq * MinvJ_t_T; + dt * dt * qdotNv * MinvJ_t_T; D.block(n_q, 2 * n_contacts, n_v, 2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; - D.block(0, n_contacts, n_q, n_contacts) = dt * dt * Nq * MinvJ_n_T; + D.block(0, n_contacts, n_q, n_contacts) = dt * dt * qdotNv * MinvJ_n_T; D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; E.block(n_contacts, 0, n_contacts, n_q) = - dt * dt * J_n * AB_v_q + J_n * NqInverse; + dt * dt * J_n * AB_v_q + J_n * vNqdot; E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = dt * J_t * AB_v_q; E.block(n_contacts, n_q, n_contacts, n_v) = @@ -186,8 +181,9 @@ std::pair LCSFactory::LinearizePlantToLCS( n_v) = J_t + dt * J_t * AB_v_v; F.block(0, n_contacts, n_contacts, n_contacts) = - Eigen::Map( - mu.data(), mu.size()).asDiagonal(); + Eigen::Map(mu.data(), + mu.size()) + .asDiagonal(); F.block(0, 2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions) = -E_t; @@ -217,24 +213,34 @@ std::pair LCSFactory::LinearizePlantToLCS( // std::cout << "phi: " << phi << std::endl; c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = - J_t * dt * d_v - J_n * NqInverse * plant.GetPositions(context); + J_t * dt * d_v - J_n * vNqdot * plant.GetPositions(context); } else if (contact_model == ContactModel::kAnitescu) { - MatrixXd Nqinv = Nq.completeOrthogonalDecomposition().pseudoInverse(); - // auto M_ldlt = ExtractValue(M).ldlt(); - MatrixXd J_c = E_t.transpose() * J_n + mu[0] * J_t; + VectorXd mu_vec = Eigen::Map(mu.data(), + mu.size()); + VectorXd anitescu_mu_vec = VectorXd::Zero(n_contact_vars); + for (int i = 0; i < mu_vec.rows(); i++) { + double cur = mu_vec(i); + anitescu_mu_vec(4 * i) = cur; + anitescu_mu_vec(4 * i + 1) = cur; + anitescu_mu_vec(4 * i + 2) = cur; + anitescu_mu_vec(4 * i + 3) = cur; + } + MatrixXd anitescu_mu_matrix = anitescu_mu_vec.asDiagonal(); + MatrixXd J_c = E_t.transpose() * J_n + anitescu_mu_matrix * J_t; MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); - D.block(0, 0, n_q, n_contacts) = dt * Nq * MinvJ_c_T; + + D.block(0, 0, n_q, n_contacts) = dt * qdotNv * MinvJ_c_T; D.block(n_q, 0, n_v, n_contacts) = MinvJ_c_T; E.block(0, 0, n_contacts, n_q) = - dt * J_c * AB_v_q + E_t.transpose() * J_n * Nqinv / dt; + dt * J_c * AB_v_q + E_t.transpose() * J_n * vNqdot / dt; E.block(0, n_q, n_contacts, n_v) = J_c + dt * J_c * AB_v_v; F = J_c * MinvJ_c_T; H = dt * J_c * AB_v_u; c = E_t.transpose() * phi / dt + dt * J_c * d_v - - E_t.transpose() * J_n * Nqinv * plant.GetPositions(context) / dt; + E_t.transpose() * J_n * vNqdot * plant.GetPositions(context) / dt; } auto Dn = D.squaredNorm(); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 3d5d86e0a8..c9dc096cd7 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -149,6 +149,8 @@ drake::systems::EventStatus C3Controller::ComputePlan( DRAKE_DEMAND(R_.front().cols() == lcs.k_); DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); + DRAKE_DEMAND(U_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); + DRAKE_DEMAND(U_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); if (c3_options_.projection_type == "MIQP") { c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); @@ -171,12 +173,12 @@ drake::systems::EventStatus C3Controller::ComputePlan( for (int i : vector({0, 2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.2, 0.8, 1); + c3_->AddLinearConstraint(A, 0.35, 0.6, 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -0.4, 0.4, 1); + c3_->AddLinearConstraint(A, -0.2, 0.2, 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 603960635e..24b59a6bdf 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -328,8 +328,6 @@ void OperationalSpaceControl::Build() { n_lambda_ext_ += force_tracking_data->GetLambdaDim(); } - std::cout << "num contact forces" << n_lambda_ext_ << std::endl; - n_c_active_ = 0; for (auto evaluator : all_contacts_) { n_c_active_ += evaluator->num_active(); From 7efe7de05d957934a55cbbc7081fad135832ef34 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 7 Dec 2023 14:04:08 -0500 Subject: [PATCH 558/758] cleaning up yamls and adding visualizing force feature --- examples/franka/franka_c3_controller.cc | 12 +- examples/franka/franka_sim.cc | 35 ++---- examples/franka/franka_visualizer.cc | 18 +-- .../parameters/franka_c3_controller_params.h | 11 +- .../franka/parameters/franka_sim_params.h | 13 +-- .../lcm_trajectory_systems.cc | 109 +++++++++++++++++- .../lcm_trajectory_systems.h | 37 ++++++ 7 files changed, 171 insertions(+), 64 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 3d2dd5d52a..9162d69d41 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -86,11 +86,9 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); - Vector3d tool_attachment_frame = - StdVectorToVectorXd(controller_params.tool_attachment_frame); RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), tool_attachment_frame); + drake::math::RotationMatrix(), controller_params.tool_attachment_frame); plant_franka.WeldFrames( plant_franka.GetFrameByName("panda_link7"), plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); @@ -119,14 +117,10 @@ int DoMain(int argc, char* argv[]) { parser_plate.AddModels(FindResourceOrThrow(controller_params.left_support_model))[0]; right_support_index = parser_plate.AddModels(FindResourceOrThrow(controller_params.right_support_model))[0]; - Vector3d first_support_position = - StdVectorToVectorXd(controller_params.left_support_position); - Vector3d second_support_position = - StdVectorToVectorXd(controller_params.right_support_position); RigidTransform T_S1_W = RigidTransform( - drake::math::RotationMatrix(), first_support_position); + drake::math::RotationMatrix(), controller_params.left_support_position); RigidTransform T_S2_W = RigidTransform( - drake::math::RotationMatrix(), second_support_position); + drake::math::RotationMatrix(), controller_params.right_support_position); plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index df8ccb7fac..20dc17255f 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -78,13 +78,11 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); - Vector3d tool_attachment_frame = - StdVectorToVectorXd(sim_params.tool_attachment_frame); RigidTransform T_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), tool_attachment_frame); + drake::math::RotationMatrix(), sim_params.tool_attachment_frame); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), T_X_W); @@ -96,14 +94,10 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( FindResourceOrThrow(sim_params.right_support_model))[0]; - Vector3d first_support_position = - StdVectorToVectorXd(sim_params.left_support_position); - Vector3d second_support_position = - StdVectorToVectorXd(sim_params.right_support_position); RigidTransform T_S1_W = RigidTransform( - drake::math::RotationMatrix(), first_support_position); + drake::math::RotationMatrix(), sim_params.left_support_position); RigidTransform T_S2_W = RigidTransform( - drake::math::RotationMatrix(), second_support_position); + drake::math::RotationMatrix(), sim_params.right_support_position); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_S1_W); @@ -181,7 +175,6 @@ int DoMain(int argc, char* argv[]) { int nq = plant.num_positions(); int nv = plant.num_velocities(); - int nu = plant.num_actuators(); if (sim_params.visualize) { drake::visualization::AddDefaultVisualization(&builder); @@ -201,24 +194,10 @@ int DoMain(int argc, char* argv[]) { VectorXd q = VectorXd::Zero(nq); std::map q_map = MakeNameToPositionsMap(plant); - // initialize EE close to {0.5, 0, 0.12}[m] in task space - q[q_map["panda_joint1"]] = sim_params.q_init_franka[0]; - q[q_map["panda_joint2"]] = sim_params.q_init_franka[1]; - q[q_map["panda_joint3"]] = sim_params.q_init_franka[2]; - q[q_map["panda_joint4"]] = sim_params.q_init_franka[3]; - q[q_map["panda_joint5"]] = sim_params.q_init_franka[4]; - q[q_map["panda_joint6"]] = sim_params.q_init_franka[5]; - q[q_map["panda_joint7"]] = sim_params.q_init_franka[6]; - - auto q_init_plate = sim_params.q_init_plate[sim_params.scene_index]; - - q[q_map.at("tray_qw")] = q_init_plate[0]; - q[q_map.at("tray_qx")] = q_init_plate[1]; - q[q_map.at("tray_qy")] = q_init_plate[2]; - q[q_map.at("tray_qz")] = q_init_plate[3]; - q[q_map.at("tray_x")] = q_init_plate[4]; - q[q_map.at("tray_y")] = q_init_plate[5]; - q[q_map.at("tray_z")] = q_init_plate[6]; + q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; + + q.tail(plant.num_positions(tray_index)) = sim_params.q_init_plate[sim_params.scene_index]; + // q[q_map["box_qw"]] = sim_params.q_init_box[0]; // q[q_map["box_qx"]] = sim_params.q_init_box[1]; diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index c0340b63da..f620497186 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -88,13 +88,11 @@ int do_main(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); Vector3d franka_origin = Eigen::VectorXd::Zero(3); - Vector3d tool_attachment_frame = - StdVectorToVectorXd(sim_params.tool_attachment_frame); RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), tool_attachment_frame); + drake::math::RotationMatrix(), sim_params.tool_attachment_frame); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), R_X_W); plant.WeldFrames(plant.GetFrameByName("panda_link7"), @@ -105,14 +103,10 @@ int do_main(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels(FindResourceOrThrow(sim_params.right_support_model))[0]; - Vector3d first_support_position = - StdVectorToVectorXd(sim_params.left_support_position); - Vector3d second_support_position = - StdVectorToVectorXd(sim_params.right_support_position); RigidTransform T_S1_W = RigidTransform( - drake::math::RotationMatrix(), first_support_position); + drake::math::RotationMatrix(), sim_params.left_support_position); RigidTransform T_S2_W = RigidTransform( - drake::math::RotationMatrix(), second_support_position); + drake::math::RotationMatrix(), sim_params.right_support_position); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_S1_W); @@ -186,6 +180,10 @@ int do_main(int argc, char* argv[]) { builder.AddSystem( meshcat, FindResourceOrThrow(sim_params.end_effector_model), "end_effector_position_target", "end_effector_orientation_target"); + auto end_effector_force_drawer = + builder.AddSystem( + meshcat, "end_effector_position_target", + "end_effector_force_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(5); @@ -203,6 +201,8 @@ int do_main(int argc, char* argv[]) { object_pose_drawer->get_input_port_trajectory()); builder.Connect(trajectory_sub_actor->get_output_port(), end_effector_pose_drawer->get_input_port_trajectory()); + builder.Connect(trajectory_sub_actor->get_output_port(), + end_effector_force_drawer->get_input_port_trajectory()); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index c5d617382a..84a24498f7 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -4,9 +4,6 @@ #include "drake/common/yaml/yaml_read_archive.h" -using Eigen::MatrixXd; -using Eigen::VectorXd; - struct FrankaC3ControllerParams { std::vector c3_options_file; std::string osqp_settings_file; @@ -19,17 +16,17 @@ struct FrankaC3ControllerParams { std::string right_support_model; bool include_end_effector_orientation; double target_frequency; - std::vector tool_attachment_frame; + Eigen::Vector3d tool_attachment_frame; int scene_index; - std::vector neutral_position; + Eigen::Vector3d neutral_position; double x_scale; double y_scale; double z_scale; - std::vector left_support_position; - std::vector right_support_position; + Eigen::Vector3d left_support_position; + Eigen::Vector3d right_support_position; template void Serialize(Archive* a) { diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 43088485ea..ae47e94a9d 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -2,7 +2,6 @@ #include "drake/common/yaml/yaml_read_archive.h" -using Eigen::MatrixXd; struct FrankaSimParams { std::string franka_model; @@ -24,12 +23,12 @@ struct FrankaSimParams { bool visualize; bool publish_efforts; - std::vector q_init_franka; - std::vector> q_init_plate; - std::vector q_init_box; - std::vector tool_attachment_frame; - std::vector left_support_position; - std::vector right_support_position; + Eigen::VectorXd q_init_franka; + std::vector q_init_plate; + Eigen::VectorXd q_init_box; + Eigen::VectorXd tool_attachment_frame; + Eigen::VectorXd left_support_position; + Eigen::VectorXd right_support_position; template void Serialize(Archive* a) { diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index c6addb787f..36bbaf60d6 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -12,6 +12,8 @@ namespace dairlib { namespace systems { using drake::geometry::Rgba; +using drake::math::RigidTransformd; +using drake::math::RotationMatrixd; using drake::systems::Context; using drake::systems::DiscreteValues; using drake::trajectories::PiecewisePolynomial; @@ -55,8 +57,8 @@ void LcmTrajectoryReceiver::OutputTrajectory( const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); if (trajectory_block.datapoints.rows() == 3) { -// *casted_traj = PiecewisePolynomial::FirstOrderHold( -// trajectory_block.time_vector, trajectory_block.datapoints); + // *casted_traj = PiecewisePolynomial::FirstOrderHold( + // trajectory_block.time_vector, trajectory_block.datapoints); *casted_traj = PiecewisePolynomial::ZeroOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); } else { @@ -128,7 +130,7 @@ LcmTrajectoryDrawer::LcmTrajectoryDrawer( const std::shared_ptr& meshcat, std::string trajectory_name) : meshcat_(meshcat), trajectory_name_(std::move(trajectory_name)) { - this->set_name(trajectory_name_); + this->set_name("LcmTrajectoryDrawer: " + trajectory_name_); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", @@ -185,7 +187,7 @@ LcmPoseDrawer::LcmPoseDrawer( translation_trajectory_name_(translation_trajectory_name), orientation_trajectory_name_(orientation_trajectory_name), N_(num_poses) { - this->set_name("/poses/" + model_file); + this->set_name("LcmPoseDrawer: " + translation_trajectory_name); multipose_visualizer_ = std::make_unique( model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.4), "", meshcat); @@ -254,5 +256,104 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( return drake::systems::EventStatus::Succeeded(); } +LcmForceDrawer::LcmForceDrawer( + const std::shared_ptr& meshcat, + std::string actor_trajectory_name, std::string force_trajectory_name) + : meshcat_(meshcat), + actor_trajectory_name_(std::move(actor_trajectory_name)), + force_trajectory_name_(std::move(force_trajectory_name)) { + this->set_name("LcmForceDrawer: " + force_trajectory_name_); + trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj", + drake::Value{}) + .get_index(); + + meshcat_->SetProperty(force_path_, "visible", false, 0); + + // Add the geometry to meshcat. + // Set radius 1.0 so that it can be scaled later by the force/moment norm in + // the path transform. + const drake::geometry::Cylinder cylinder(radius_, 1.0); + const double arrowhead_height = radius_ * 2.0; + const double arrowhead_width = radius_ * 2.0; + const drake::geometry::MeshcatCone arrowhead(arrowhead_height, arrowhead_width, + arrowhead_width); + + meshcat_->SetObject(force_path_ + "/force_C_W/cylinder", cylinder, + {1, 0, 0, 1}); + meshcat_->SetObject(force_path_ + "/force_C_W/head", arrowhead, + {1, 0, 0, 1}); +// meshcat_->SetObject(force_path_ + "/moment_C_W/cylinder", cylinder, +// {0, 0, 1, 1}); +// meshcat_->SetObject(force_path_ + "/moment_C_W/head", arrowhead, +// {0, 0, 1, 1}); + + DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawTrajectory); +} + +drake::systems::EventStatus LcmForceDrawer::DrawTrajectory( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, trajectory_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + const auto& lcmt_traj = + this->EvalInputValue( + context, trajectory_input_port_); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + const auto& force_trajectory_block = + lcm_traj.GetTrajectory(force_trajectory_name_); + const auto& actor_trajectory_block = + lcm_traj.GetTrajectory(actor_trajectory_name_); + auto force_trajectory = PiecewisePolynomial::FirstOrderHold( + force_trajectory_block.time_vector, force_trajectory_block.datapoints); + VectorXd pose; + if (actor_trajectory_block.datapoints.rows() == 3) { + auto trajectory = PiecewisePolynomial::FirstOrderHold( + actor_trajectory_block.time_vector, actor_trajectory_block.datapoints); + pose = trajectory.value(actor_trajectory_block.time_vector[0]); + } else { + auto trajectory = PiecewisePolynomial::CubicHermite( + actor_trajectory_block.time_vector, + actor_trajectory_block.datapoints.topRows(3), + actor_trajectory_block.datapoints.bottomRows(3)); + pose = trajectory.value(actor_trajectory_block.time_vector[0]); + } + + auto force = force_trajectory.value(force_trajectory_block.time_vector[0]); + + meshcat_->SetTransform(force_path_, RigidTransformd(pose)); + + auto force_norm = force.norm(); + // Stretch the cylinder in z. + if (force_norm >= 0.01) { + meshcat_->SetTransform(force_path_ + "/force_C_W", + RigidTransformd(RotationMatrixd::MakeFromOneVector( + force, 2))); + const double height = force_norm / 10; + meshcat_->SetProperty(force_path_ + "/force_C_W/cylinder", "position", + {0, 0, 0.5 * height}); + // Note: Meshcat does not fully support non-uniform scaling (see #18095). + // We get away with it here since there is no rotation on this frame and + // no children in the kinematic tree. + meshcat_->SetProperty(force_path_ + "/force_C_W/cylinder", "scale", + {1, 1, height}); + // Translate the arrowheads. + const double arrowhead_height = radius_ * 2.0; + meshcat_->SetTransform( + force_path_ + "/force_C_W/head", + RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), + Vector3d{0, 0, height + arrowhead_height})); + meshcat_->SetProperty(force_path_, "visible", true); + } else { +// meshcat_->SetProperty(force_path_ + "/force_C_W", "visible", false); + meshcat_->SetProperty(force_path_, "visible", false); + } + return drake::systems::EventStatus::Succeeded(); +} + } // namespace systems } // namespace dairlib diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index c050f22e16..2f4914903b 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -125,5 +125,42 @@ class LcmPoseDrawer : public drake::systems::LeafSystem { const int N_; }; +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws it through meshcat. +class LcmForceDrawer : public drake::systems::LeafSystem { + public: + explicit LcmForceDrawer(const std::shared_ptr&, + std::string force_trajectory_name, + std::string actor_trajectory_name); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_input_port_); + } + + void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } + + void SetNumSamples(int N) { + DRAKE_DEMAND(N > 1); + N_ = N; + } + + private: + void OutputTrajectory(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + drake::systems::EventStatus DrawTrajectory( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex trajectory_input_port_; + std::shared_ptr meshcat_; + const std::string force_path_ = "c3_forces"; + const std::string actor_trajectory_name_; + const std::string force_trajectory_name_; + drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + int N_ = 5; + const double radius_ = 0.002; +}; + } // namespace systems } // namespace dairlib From 0bf6ab9b6c68942b8872abde0329a532c7322fa6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 8 Dec 2023 16:58:29 -0500 Subject: [PATCH 559/758] extracted lcs factory to be outsdie of c3 controller, working on visualizing forces --- examples/franka/BUILD.bazel | 1 + examples/franka/franka_c3_controller.cc | 21 ++- examples/franka/franka_visualizer.cc | 10 +- .../franka/systems/c3_trajectory_generator.cc | 57 +++++++- .../franka/systems/c3_trajectory_generator.h | 12 +- solvers/lcs.cc | 74 ++++++++-- solvers/lcs.h | 34 +++-- solvers/lcs_factory.cc | 2 - systems/controllers/BUILD.bazel | 14 +- systems/controllers/c3/lcs_factory_system.cc | 102 ++++++++++++++ systems/controllers/c3/lcs_factory_system.h | 63 +++++++++ systems/controllers/c3_controller.cc | 56 +++----- systems/controllers/c3_controller.h | 23 ++- .../lcm_trajectory_systems.cc | 131 ++++++++++++++---- .../lcm_trajectory_systems.h | 32 +++-- 15 files changed, 506 insertions(+), 126 deletions(-) create mode 100644 systems/controllers/c3/lcs_factory_system.cc create mode 100644 systems/controllers/c3/lcs_factory_system.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index c435a2067c..b4b0c2170d 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -76,6 +76,7 @@ cc_binary( "//systems:system_utils", "//systems/controllers", "//systems/controllers:c3_controller", + "//systems/controllers:lcs_factory_system", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", "//systems/trajectory_optimization:c3_output_systems", diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 9162d69d41..c147c3a463 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -24,6 +24,7 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/controllers/c3/lcs_factory_system.h" namespace dairlib { @@ -138,7 +139,7 @@ int DoMain(int argc, char* argv[]) { auto plant_diagram = plant_builder.Build(); std::unique_ptr> diagram_context = plant_diagram->CreateDefaultContext(); - auto& plate_context = plant_diagram->GetMutableSubsystemContext( + auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( plant_for_lcs, diagram_context.get()); auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); @@ -196,6 +197,10 @@ int DoMain(int argc, char* argv[]) { LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto force_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( @@ -238,9 +243,11 @@ int DoMain(int argc, char* argv[]) { target_state_mux->get_input_port(2)); builder.Connect(tray_zero_velocity_source->get_output_port(), target_state_mux->get_input_port(3)); - auto controller = builder.AddSystem( - plant_for_lcs, &plate_context, *plant_for_lcs_autodiff, plate_context_ad.get(), + auto lcs_factory = builder.AddSystem( + plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, plate_context_ad.get(), contact_pairs, c3_options); + auto controller = builder.AddSystem( + plant_for_lcs, &plant_for_lcs_context, c3_options); auto c3_trajectory_generator = builder.AddSystem(plant_for_lcs, c3_options); @@ -261,12 +268,16 @@ int DoMain(int argc, char* argv[]) { reduced_order_model_receiver->get_input_port_franka_state()); builder.Connect(target_state_mux->get_output_port(), controller->get_input_port_target()); + builder.Connect(lcs_factory->get_output_port_lcs(), + controller->get_input_port_lcs()); builder.Connect(tray_state_sub->get_output_port(), tray_state_receiver->get_input_port()); builder.Connect(tray_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_object_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), - controller->get_input_port_state()); + controller->get_input_port_lcs_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + lcs_factory->get_input_port_lcs_state()); builder.Connect(radio_sub->get_output_port(), plate_balancing_target->get_input_port_radio()); builder.Connect(controller->get_output_port_c3_solution(), @@ -275,6 +286,8 @@ int DoMain(int argc, char* argv[]) { actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_force_trajectory(), + force_trajectory_sender->get_input_port()); builder.Connect(target_state_mux->get_output_port(), c3_state_sender->get_input_port_target_state()); builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index f620497186..86f5a32628 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -158,6 +158,9 @@ int do_main(int argc, char* argv[]) { auto trajectory_sub_object = builder.AddSystem( LcmSubscriberSystem::Make( lcm_channel_params.c3_object_channel, lcm)); + auto trajectory_sub_force = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_force_channel, lcm)); auto to_pose = builder.AddSystem>(plant); @@ -183,7 +186,8 @@ int do_main(int argc, char* argv[]) { auto end_effector_force_drawer = builder.AddSystem( meshcat, "end_effector_position_target", - "end_effector_force_target"); + "end_effector_force_target", + "lcs_force_trajectory"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(5); @@ -202,7 +206,9 @@ int do_main(int argc, char* argv[]) { builder.Connect(trajectory_sub_actor->get_output_port(), end_effector_pose_drawer->get_input_port_trajectory()); builder.Connect(trajectory_sub_actor->get_output_port(), - end_effector_force_drawer->get_input_port_trajectory()); + end_effector_force_drawer->get_input_port_actor_trajectory()); + builder.Connect(trajectory_sub_force->get_output_port(), + end_effector_force_drawer->get_input_port_force_trajectory()); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 4f2f31d0cb..3d2002240a 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -7,6 +7,7 @@ #include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" #include "solvers/c3_output.h" +#include "solvers/lcs.h" namespace dairlib { @@ -17,6 +18,7 @@ using drake::systems::DiscreteValues; using Eigen::MatrixXd; using Eigen::MatrixXf; using Eigen::VectorXd; +using solvers::LCS; using systems::TimestampedVector; namespace systems { @@ -29,9 +31,14 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_x_ = n_q_ + n_v_; - n_lambda_ = - 2 * c3_options_.num_contacts + - 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + if (c3_options_.contact_model == "stewart_and_trinkle") { + n_lambda_ = + 2 * c3_options_.num_contacts + + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + } else if (c3_options_.contact_model == "anitescu") { + n_lambda_ = + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + } n_u_ = plant_.num_actuators(); c3_solution_port_ = @@ -39,6 +46,18 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( drake::Value()) .get_index(); + MatrixXd A = MatrixXd::Zero(n_x_, n_x_); + MatrixXd B = MatrixXd::Zero(n_x_, n_u_); + VectorXd d = VectorXd::Zero(n_x_); + MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); + MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); + MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); + MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); + VectorXd c = VectorXd::Zero(n_lambda_); + auto lcs = LCS(A, B, D, d, E, F, H, c, N_, c3_options_.dt); + lcs_port_ = + this->DeclareAbstractInputPort("lcs", drake::Value(lcs)).get_index(); + actor_trajectory_port_ = this->DeclareAbstractOutputPort( "c3_actor_trajectory_output", @@ -51,6 +70,12 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( dairlib::lcmt_timestamped_saved_traj(), &C3TrajectoryGenerator::OutputObjectTrajectory) .get_index(); + force_trajectory_port_ = + this->DeclareAbstractOutputPort( + "c3_force_trajectory_output", + dairlib::lcmt_timestamped_saved_traj(), + &C3TrajectoryGenerator::OutputLCSForceTrajectory) + .get_index(); } void C3TrajectoryGenerator::OutputActorTrajectory( @@ -122,8 +147,8 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( object_traj.datatypes = std::vector(knots.rows(), "double"); object_traj.datapoints = knots; object_traj.time_vector = c3_solution->time_vector_.cast(); - LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, "object_target", - "object_target", false); + LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, + "object_target", "object_target", false); LcmTrajectory::Trajectory object_orientation_traj; // first 3 rows are rpy, last 3 rows are angular velocity @@ -143,5 +168,27 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( output_traj->utime = context.get_time() * 1e6; } +void C3TrajectoryGenerator::OutputLCSForceTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const { + const auto& c3_solution = + this->EvalInputValue(context, c3_solution_port_); + // auto& lcs = this->EvalAbstractInput(context, lcs_port_)->get_value(); + + DRAKE_DEMAND(c3_solution->lambda_sol_.rows() == n_lambda_); + MatrixXd knots = c3_solution->lambda_sol_.cast(); + LcmTrajectory::Trajectory lcs_force_trajectory; + lcs_force_trajectory.traj_name = "lcs_force_trajectory"; + lcs_force_trajectory.datatypes = + std::vector(knots.rows(), "double"); + lcs_force_trajectory.datapoints = knots; + lcs_force_trajectory.time_vector = c3_solution->time_vector_.cast(); + LcmTrajectory lcm_traj({lcs_force_trajectory}, {"lcs_force_trajectory"}, + "lcs_force_trajectory", "lcs_force_trajectory", false); + + output_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_traj->utime = context.get_time() * 1e6; +} + } // namespace systems } // namespace dairlib diff --git a/examples/franka/systems/c3_trajectory_generator.h b/examples/franka/systems/c3_trajectory_generator.h index 560f68bb25..a41e111893 100644 --- a/examples/franka/systems/c3_trajectory_generator.h +++ b/examples/franka/systems/c3_trajectory_generator.h @@ -35,6 +35,11 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const { return this->get_output_port(object_trajectory_port_); } + // LCS contact force, not actor input forces + const drake::systems::OutputPort& get_output_port_force_trajectory() + const { + return this->get_output_port(force_trajectory_port_); + } void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { publish_end_effector_orientation_ = publish_end_effector_orientation; @@ -49,12 +54,17 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const; + void OutputLCSForceTrajectory( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_traj) const; + drake::systems::InputPortIndex c3_solution_port_; + drake::systems::InputPortIndex lcs_port_; drake::systems::OutputPortIndex actor_trajectory_port_; drake::systems::OutputPortIndex object_trajectory_port_; + drake::systems::OutputPortIndex force_trajectory_port_; const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; C3Options c3_options_; bool publish_end_effector_orientation_ = false; diff --git a/solvers/lcs.cc b/solvers/lcs.cc index 9c1e63feef..75906d275d 100644 --- a/solvers/lcs.cc +++ b/solvers/lcs.cc @@ -1,10 +1,9 @@ #include "solvers/lcs.h" +#include + #include "drake/solvers/mathematical_program.h" #include "drake/solvers/moby_lcp_solver.h" -#include "drake/solvers/osqp_solver.h" -#include "drake/solvers/solve.h" - using Eigen::MatrixXd; using Eigen::VectorXd; using std::vector; @@ -15,9 +14,20 @@ namespace solvers { LCS::LCS(const vector& A, const vector& B, const vector& D, const vector& d, const vector& E, const vector& F, - const vector& H, const vector& c, - double dt) - : A_(A), B_(B), D_(D), d_(d), E_(E), F_(F), H_(H), c_(c), N_(A.size()), n_(A_[0].rows()), m_(D_[0].cols()), k_(H_[0].cols()), dt_(dt) {} + const vector& H, const vector& c, double dt) + : A_(A), + B_(B), + D_(D), + d_(d), + E_(E), + F_(F), + H_(H), + c_(c), + N_(A_.size()), + dt_(dt), + n_(A_[0].rows()), + m_(D_[0].cols()), + k_(H_[0].cols()) {} LCS::LCS(const MatrixXd& A, const MatrixXd& B, const MatrixXd& D, const VectorXd& d, const MatrixXd& E, const MatrixXd& F, @@ -27,14 +37,62 @@ LCS::LCS(const MatrixXd& A, const MatrixXd& B, const MatrixXd& D, vector(N, E), vector(N, F), vector(N, H), vector(N, c), dt) {} +LCS::LCS(const LCS& lcs) + : N_(lcs.N_), dt_(lcs.dt_), n_(lcs.n_), m_(lcs.m_), k_(lcs.k_) { + A_.resize(N_); + B_.resize(N_); + D_.resize(N_); + d_.resize(N_); + E_.resize(N_); + F_.resize(N_); + H_.resize(N_); + c_.resize(N_); + for (int i = 0; i < lcs.N_; ++i) { + A_.at(i) = lcs.A_.at(i); + B_.at(i) = lcs.B_.at(i); + D_.at(i) = lcs.D_.at(i); + d_.at(i) = lcs.d_.at(i); + E_.at(i) = lcs.E_.at(i); + F_.at(i) = lcs.F_.at(i); + H_.at(i) = lcs.H_.at(i); + c_.at(i) = lcs.c_.at(i); + } +} + +LCS& LCS::operator=(const LCS& lcs) { + N_ = lcs.N_; + dt_ = lcs.dt_; + n_ = lcs.n_; + m_ = lcs.m_; + k_ = lcs.k_; + A_.resize(N_); + B_.resize(N_); + D_.resize(N_); + d_.resize(N_); + E_.resize(N_); + F_.resize(N_); + H_.resize(N_); + c_.resize(N_); + for (int i = 0; i < lcs.N_; ++i) { + A_.at(i) = lcs.A_.at(i); + B_.at(i) = lcs.B_.at(i); + D_.at(i) = lcs.D_.at(i); + d_.at(i) = lcs.d_.at(i); + E_.at(i) = lcs.E_.at(i); + F_.at(i) = lcs.F_.at(i); + H_.at(i) = lcs.H_.at(i); + c_.at(i) = lcs.c_.at(i); + } +} + const VectorXd LCS::Simulate(VectorXd& x_init, VectorXd& input) { VectorXd x_final; // calculate force drake::solvers::MobyLCPSolver LCPSolver; VectorXd force; - auto flag = LCPSolver.SolveLcpLemke(F_[0], E_[0] * x_init + c_[0] + H_[0] * input, - &force); + auto flag = LCPSolver.SolveLcpLemke( + F_[0], E_[0] * x_init + c_[0] + H_[0] * input, &force); // update x_final = A_[0] * x_init + B_[0] * input + D_[0] * force + d_[0]; return x_final; diff --git a/solvers/lcs.h b/solvers/lcs.h index 713c38a64c..27056cd65d 100644 --- a/solvers/lcs.h +++ b/solvers/lcs.h @@ -33,26 +33,32 @@ class LCS { const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int& N, double dt); + LCS(const LCS& other); + LCS& operator=(const LCS&); + LCS(LCS&&) = default; + LCS& operator=(LCS&&) = default; + /// Simulate the system for one-step /// @param x_init Initial x value /// @param input Input value const Eigen::VectorXd Simulate(Eigen::VectorXd& x_init, Eigen::VectorXd& input); public: - const std::vector A_; - const std::vector B_; - const std::vector D_; - const std::vector d_; - const std::vector E_; - const std::vector F_; - const std::vector H_; - const std::vector c_; - const int N_; - const double dt_; - - const int n_; - const int m_; - const int k_; + std::vector A_; + std::vector B_; + std::vector D_; + std::vector d_; + std::vector E_; + std::vector F_; + std::vector H_; + std::vector c_; + Eigen::MatrixXd J_c_; + int N_; + double dt_; + + int n_; + int m_; + int k_; }; } // namespace solvers diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index a604e2dc88..65f45f49b3 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -108,7 +108,6 @@ std::pair LCSFactory::LinearizePlantToLCS( auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); phi(i) = phi_i; - J_n.row(i) = J_i.row(0); J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, n_v) = J_i.block(1, 0, 2 * num_friction_directions, n_v); @@ -255,7 +254,6 @@ std::pair LCSFactory::LinearizePlantToLCS( LCS system(A, B, D, d, E, F, H, c, N, dt); std::pair ret(system, AnDn); - return ret; } diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 25b469728a..07e96212c7 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -51,13 +51,23 @@ cc_library( ], ) +cc_library( + name = "lcs_factory_system", + srcs = ["c3/lcs_factory_system.cc"], + hdrs = ["c3/lcs_factory_system.h"], + deps = [ + "//multibody:utils", + "//solvers:c3", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "c3_controller", srcs = ["c3_controller.cc"], hdrs = ["c3_controller.h"], deps = [ - "//common:find_resource", - "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", "//multibody:utils", diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc new file mode 100644 index 0000000000..8709a3888d --- /dev/null +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -0,0 +1,102 @@ +#include "lcs_factory_system.h" + +#include + +#include "multibody/multibody_utils.h" +#include "solvers/lcs.h" +#include "solvers/lcs_factory.h" +#include "systems/framework/timestamped_vector.h" + +namespace dairlib { + +using drake::multibody::ModelInstanceIndex; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteValues; +using Eigen::MatrixXd; +using Eigen::MatrixXf; +using Eigen::VectorXd; +using solvers::LCS; +using solvers::LCSFactory; +using systems::TimestampedVector; + +namespace systems { + +LCSFactorySystem::LCSFactorySystem( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector>& + contact_geoms, + C3Options c3_options) + : plant_(plant), + context_(context), + plant_ad_(plant_ad), + context_ad_(context_ad), + contact_pairs_(contact_geoms), + c3_options_(std::move(c3_options)), + N_(c3_options_.N) { + this->set_name("lcs_factory_system"); + + n_q_ = plant_.num_positions(); + n_v_ = plant_.num_velocities(); + n_x_ = n_q_ + n_v_; + dt_ = c3_options_.dt; + n_lambda_ = + 2 * c3_options_.num_contacts + + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + n_u_ = plant_.num_actuators(); + + lcs_state_input_port_ = + this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) + .get_index(); + + MatrixXd A = MatrixXd::Zero(n_x_, n_x_); + MatrixXd B = MatrixXd::Zero(n_x_, n_u_); + VectorXd d = VectorXd::Zero(n_x_); + MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); + MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); + MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); + MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); + VectorXd c = VectorXd::Zero(n_lambda_); + lcs_port_ = this->DeclareAbstractOutputPort( + "lcs", LCS(A, B, D, d, E, F, H, c, N_, dt_), + &LCSFactorySystem::OutputLCS) + .get_index(); +} + +void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, + LCS* output_lcs) const { + const TimestampedVector* lcs_x = + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + + VectorXd q_v_u = + VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + + plant_.num_actuators()); + q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); + drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); + + plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); + multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); + multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u_), + context_ad_); + solvers::ContactModel contact_model; + if (c3_options_.contact_model == "stewart_and_trinkle") { + contact_model = solvers::ContactModel::kStewartAndTrinkle; + } else if (c3_options_.contact_model == "anitescu") { + contact_model = solvers::ContactModel::kAnitescu; + } else { + throw std::runtime_error("unknown or unsupported contact model"); + } + + double scale; + std::tie(*output_lcs, scale) = LCSFactory::LinearizePlantToLCS( + plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, + c3_options_.N, contact_model); +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h new file mode 100644 index 0000000000..695294fa17 --- /dev/null +++ b/systems/controllers/c3/lcs_factory_system.h @@ -0,0 +1,63 @@ +#pragma once + +#include +#include + +#include + +#include "solvers/c3_options.h" +#include "solvers/lcs.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// Outputs a lcmt_timestamped_saved_traj +class LCSFactorySystem : public drake::systems::LeafSystem { + public: + explicit LCSFactorySystem( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector>& contact_geoms, + C3Options c3_options); + + const drake::systems::InputPort& get_input_port_lcs_state() const { + return this->get_input_port(lcs_state_input_port_); + } + + const drake::systems::OutputPort& get_output_port_lcs() const { + return this->get_output_port(lcs_port_); + } + + private: + void OutputLCS(const drake::systems::Context& context, + solvers::LCS* output_traj) const; + + drake::systems::InputPortIndex lcs_state_input_port_; + drake::systems::OutputPortIndex actor_trajectory_port_; + drake::systems::OutputPortIndex lcs_port_; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + const drake::multibody::MultibodyPlant& plant_ad_; + drake::systems::Context* context_ad_; + const std::vector>& + contact_pairs_; + + C3Options c3_options_; + + // convenience for variable sizes + int n_q_; + int n_v_; + int n_x_; + int n_lambda_; + int n_u_; + int N_; + double dt_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index c9dc096cd7..e49089d7f0 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -2,10 +2,6 @@ #include -#include - -#include "common/find_resource.h" -#include "examples/franka/systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" #include "solvers/c3_miqp.h" #include "solvers/c3_qp.h" @@ -33,16 +29,9 @@ namespace systems { C3Controller::C3Controller( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - const drake::multibody::MultibodyPlant& plant_ad, - drake::systems::Context* context_ad, - const std::vector>& - contact_geoms, C3Options c3_options) : plant_(plant), context_(context), - plant_ad_(plant_ad), - context_ad_(context_ad), - contact_pairs_(contact_geoms), c3_options_(std::move(c3_options)), Q_(std::vector(c3_options_.N + 1, c3_options_.Q)), R_(std::vector(c3_options_.N, c3_options_.R)), @@ -54,6 +43,7 @@ C3Controller::C3Controller( n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_x_ = n_q_ + n_v_; + dt_ = c3_options_.dt; if (c3_options_.contact_model == "stewart_and_trinkle") { n_lambda_ = 2 * c3_options_.num_contacts + @@ -64,6 +54,7 @@ C3Controller::C3Controller( } n_u_ = plant_.num_actuators(); + u_prev_ = VectorXd::Zero(n_u_); int x_des_size = plant_.num_positions(ModelInstanceIndex(2)) + plant_.num_positions(ModelInstanceIndex(3)) + @@ -74,8 +65,19 @@ C3Controller::C3Controller( "x_lcs", TimestampedVector( x_des_size)) .get_index(); -// lcs_input_port_ = -// this->DeclareAbstractInputPort("lcs", LCS()); + + MatrixXd A = MatrixXd::Zero(n_x_, n_x_); + MatrixXd B = MatrixXd::Zero(n_x_, n_u_); + VectorXd d = VectorXd::Zero(n_x_); + MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); + MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); + MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); + MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); + VectorXd c = VectorXd::Zero(n_lambda_); + auto lcs = LCS(A, B, D, d, E, F, H, c, N_, dt_); + + lcs_input_port_ = + this->DeclareAbstractInputPort("lcs", drake::Value(lcs)).get_index(); target_input_port_ = this->DeclareVectorInputPort("x_lcs_des", x_des_size).get_index(); @@ -112,37 +114,16 @@ drake::systems::EventStatus C3Controller::ComputePlan( const TimestampedVector* lcs_x = (TimestampedVector*)this->EvalVectorInput( context, lcs_state_input_port_); + auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); + discrete_state->get_mutable_value(plan_start_time_index_)[0] = lcs_x->get_timestamp(); - VectorXd q_v_u = - VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + - plant_.num_actuators()); - q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); - drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); + std::vector x_desired = std::vector(N_ + 1, x_des.value()); - int n_x = plant_.num_positions() + plant_.num_velocities(); - int n_u = plant_.num_actuators(); - plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x)); - plant_ad_.SetPositionsAndVelocities(context_ad_, q_v_u_ad.head(n_x)); - multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u), context_); - multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u), - context_ad_); - solvers::ContactModel contact_model; - if (c3_options_.contact_model == "stewart_and_trinkle") { - contact_model = solvers::ContactModel::kStewartAndTrinkle; - } else if (c3_options_.contact_model == "anitescu") { - contact_model = solvers::ContactModel::kAnitescu; - } else { - throw std::runtime_error("unknown or unsupported contact model"); - } - auto [lcs, scale] = LCSFactory::LinearizePlantToLCS( - plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, - c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, - c3_options_.N, contact_model); DRAKE_DEMAND(Q_.front().rows() == lcs.n_); DRAKE_DEMAND(Q_.front().cols() == lcs.n_); DRAKE_DEMAND(R_.front().rows() == lcs.k_); @@ -215,6 +196,7 @@ void C3Controller::OutputC3Solution( c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } + u_prev_ = z_sol[0].segment(n_x_ + n_lambda_, n_u_); } void C3Controller::OutputC3Intermediates( diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 6448965bde..f0db2cb263 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -28,20 +28,20 @@ class C3Controller : public drake::systems::LeafSystem { explicit C3Controller( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, - const drake::multibody::MultibodyPlant& plant_ad, - drake::systems::Context* context_ad, - const std::vector>& - contact_geoms, C3Options c3_options); const drake::systems::InputPort& get_input_port_target() const { return this->get_input_port(target_input_port_); } - const drake::systems::InputPort& get_input_port_state() const { + const drake::systems::InputPort& get_input_port_lcs_state() const { return this->get_input_port(lcs_state_input_port_); } + const drake::systems::InputPort& get_input_port_lcs() const { + return this->get_input_port(lcs_input_port_); + } + const drake::systems::OutputPort& get_output_port_c3_solution() const { return this->get_output_port(c3_solution_port_); @@ -67,21 +67,18 @@ class C3Controller : public drake::systems::LeafSystem { C3Output::C3Intermediates* c3_intermediates) const; drake::systems::InputPortIndex target_input_port_; - drake::systems::InputPortIndex lcs_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; + drake::systems::InputPortIndex lcs_input_port_; drake::systems::OutputPortIndex c3_solution_port_; drake::systems::OutputPortIndex c3_intermediates_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::MultibodyPlant& plant_ad_; - drake::systems::Context* context_ad_; - const std::vector>& - contact_pairs_; + C3Options c3_options_; drake::solvers::SolverOptions solver_options_ = drake::yaml::LoadYamlFile( - FindResourceOrThrow("solvers/osqp_options_default.yaml")) + "solvers/osqp_options_default.yaml") .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); // convenience for variable sizes @@ -90,12 +87,14 @@ class C3Controller : public drake::systems::LeafSystem { int n_x_; int n_lambda_; int n_u_; + double dt_; mutable std::unique_ptr c3_; mutable std::vector delta_; mutable std::vector w_; + mutable Eigen::VectorXd u_prev_; mutable double solve_time_; - // std::unique_ptr lcs_; + drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; std::vector R_; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 36bbaf60d6..3a98aa30eb 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -258,14 +258,22 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( LcmForceDrawer::LcmForceDrawer( const std::shared_ptr& meshcat, - std::string actor_trajectory_name, std::string force_trajectory_name) + std::string actor_trajectory_name, std::string force_trajectory_name, + std::string lcs_force_trajectory_name) : meshcat_(meshcat), actor_trajectory_name_(std::move(actor_trajectory_name)), - force_trajectory_name_(std::move(force_trajectory_name)) { + force_trajectory_name_(std::move(force_trajectory_name)), + lcs_force_trajectory_name_(std::move(lcs_force_trajectory_name)) { this->set_name("LcmForceDrawer: " + force_trajectory_name_); - trajectory_input_port_ = + actor_trajectory_input_port_ = this->DeclareAbstractInputPort( - "lcmt_timestamped_saved_traj", + "lcmt_timestamped_saved_traj: actor", + drake::Value{}) + .get_index(); + + force_trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj: force", drake::Value{}) .get_index(); @@ -277,32 +285,39 @@ LcmForceDrawer::LcmForceDrawer( const drake::geometry::Cylinder cylinder(radius_, 1.0); const double arrowhead_height = radius_ * 2.0; const double arrowhead_width = radius_ * 2.0; - const drake::geometry::MeshcatCone arrowhead(arrowhead_height, arrowhead_width, - arrowhead_width); + const drake::geometry::MeshcatCone arrowhead( + arrowhead_height, arrowhead_width, arrowhead_width); - meshcat_->SetObject(force_path_ + "/force_C_W/cylinder", cylinder, + meshcat_->SetObject(force_path_ + "/u_lcs/cylinder", cylinder, {1, 0, 0, 1}); - meshcat_->SetObject(force_path_ + "/force_C_W/head", arrowhead, - {1, 0, 0, 1}); -// meshcat_->SetObject(force_path_ + "/moment_C_W/cylinder", cylinder, -// {0, 0, 1, 1}); -// meshcat_->SetObject(force_path_ + "/moment_C_W/head", arrowhead, -// {0, 0, 1, 1}); + meshcat_->SetObject(force_path_ + "/u_lcs/head", arrowhead, {1, 0, 0, 1}); + for (int i = 0; i < 5; ++i) { + for (int force_component = 0; force_component < 4; ++force_component) { + const std::string lcs_force_path = force_path_ + "/lcs_force_" + std::to_string(i) + + "/" + std::to_string(force_component); + meshcat_->SetObject(lcs_force_path + + "/cylinder", + cylinder, {1, 0, 0, 1}); + meshcat_->SetObject(lcs_force_path + "/head", + arrowhead, {1, 0, 0, 1}); + } + } - DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawTrajectory); + DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); + DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); } -drake::systems::EventStatus LcmForceDrawer::DrawTrajectory( +drake::systems::EventStatus LcmForceDrawer::DrawForce( const Context& context, DiscreteValues* discrete_state) const { if (this->EvalInputValue( - context, trajectory_input_port_) + context, actor_trajectory_input_port_) ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } const auto& lcmt_traj = this->EvalInputValue( - context, trajectory_input_port_); + context, actor_trajectory_input_port_); auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); const auto& force_trajectory_block = lcm_traj.GetTrajectory(force_trajectory_name_); @@ -325,32 +340,92 @@ drake::systems::EventStatus LcmForceDrawer::DrawTrajectory( auto force = force_trajectory.value(force_trajectory_block.time_vector[0]); - meshcat_->SetTransform(force_path_, RigidTransformd(pose)); + meshcat_->SetTransform(force_path_ + "/u_lcs", RigidTransformd(pose)); auto force_norm = force.norm(); // Stretch the cylinder in z. if (force_norm >= 0.01) { - meshcat_->SetTransform(force_path_ + "/force_C_W", - RigidTransformd(RotationMatrixd::MakeFromOneVector( - force, 2))); - const double height = force_norm / 10; - meshcat_->SetProperty(force_path_ + "/force_C_W/cylinder", "position", + meshcat_->SetTransform( + force_path_ + "/u_lcs", + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + const double height = force_norm / newtons_per_meter_; + meshcat_->SetProperty(force_path_ + "/u_lcs/cylinder", "position", {0, 0, 0.5 * height}); // Note: Meshcat does not fully support non-uniform scaling (see #18095). // We get away with it here since there is no rotation on this frame and // no children in the kinematic tree. - meshcat_->SetProperty(force_path_ + "/force_C_W/cylinder", "scale", + meshcat_->SetProperty(force_path_ + "/u_lcs/cylinder", "scale", {1, 1, height}); // Translate the arrowheads. const double arrowhead_height = radius_ * 2.0; meshcat_->SetTransform( - force_path_ + "/force_C_W/head", + force_path_ + "/u_lcs/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_, "visible", true); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); } else { -// meshcat_->SetProperty(force_path_ + "/force_C_W", "visible", false); - meshcat_->SetProperty(force_path_, "visible", false); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); + } + return drake::systems::EventStatus::Succeeded(); +} + +drake::systems::EventStatus LcmForceDrawer::DrawForces( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, force_trajectory_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + const auto& lcmt_traj = + this->EvalInputValue( + context, force_trajectory_input_port_); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + const auto& force_trajectory_block = + lcm_traj.GetTrajectory(lcs_force_trajectory_name_); + auto force_trajectory = PiecewisePolynomial::FirstOrderHold( + force_trajectory_block.time_vector, force_trajectory_block.datapoints); + auto all_forces = force_trajectory.value(force_trajectory_block.time_vector[0]).col(0); + for (int i = 0; i < 5; ++i) { + VectorXd pose = VectorXd::Zero(3); //TODO(yangwill) fix this + const std::string& force_path_root = + force_path_ + "/lcs_force_" + std::to_string(i) + "/"; + meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + VectorXd force = all_forces.segment(4 * i, 4); + std::vector bases_vectors = {{0, -0.4, 1}, + {0, 0.4, 1}, + {-0.4, 0.0, 1}, + {0.4, 0.0, 1}}; + for (int j = 0; j < 4; ++j) { + auto force_norm = force(j); + // Stretch the cylinder in z. + const std::string& force_arrow_path = + force_path_root + std::to_string(j); + if (force_norm >= 0.01) { + meshcat_->SetTransform( + force_arrow_path, + RigidTransformd(RotationMatrixd::MakeFromOneVector(bases_vectors[j], 2))); + const double height = force_norm / newtons_per_meter_; + meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", + {0, 0, 0.5 * height}); + // Note: Meshcat does not fully support non-uniform scaling (see + // #18095). We get away with it here since there is no rotation on this + // frame and no children in the kinematic tree. + meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", + {1, 1, height}); + // Translate the arrowheads. + const double arrowhead_height = radius_ * 2.0; + meshcat_->SetTransform( + force_arrow_path + "/head", + RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), + Vector3d{0, 0, height + arrowhead_height})); + meshcat_->SetProperty(force_arrow_path, "visible", true); + } else { + // meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", + // false); + meshcat_->SetProperty(force_arrow_path, "visible", false); + } + } } return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 2f4914903b..fc0a88e326 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -4,6 +4,8 @@ #include #include +#include +#include #include "dairlib/lcmt_saved_traj.hpp" #include "lcm/lcm_trajectory.h" @@ -131,10 +133,15 @@ class LcmForceDrawer : public drake::systems::LeafSystem { public: explicit LcmForceDrawer(const std::shared_ptr&, std::string force_trajectory_name, - std::string actor_trajectory_name); + std::string actor_trajectory_name, + std::string lcs_force_trajectory_name); - const drake::systems::InputPort& get_input_port_trajectory() const { - return this->get_input_port(trajectory_input_port_); + const drake::systems::InputPort& get_input_port_actor_trajectory() const { + return this->get_input_port(actor_trajectory_input_port_); + } + + const drake::systems::InputPort& get_input_port_force_trajectory() const { + return this->get_input_port(force_trajectory_input_port_); } void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } @@ -145,21 +152,24 @@ class LcmForceDrawer : public drake::systems::LeafSystem { } private: - void OutputTrajectory(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - drake::systems::EventStatus DrawTrajectory( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - - drake::systems::InputPortIndex trajectory_input_port_; + drake::systems::EventStatus DrawForce( + const drake::systems::Context &context, + drake::systems::DiscreteValues *discrete_state) const; + drake::systems::EventStatus DrawForces( + const drake::systems::Context &context, + drake::systems::DiscreteValues *discrete_state) const; + + drake::systems::InputPortIndex actor_trajectory_input_port_; + drake::systems::InputPortIndex force_trajectory_input_port_; std::shared_ptr meshcat_; const std::string force_path_ = "c3_forces"; const std::string actor_trajectory_name_; const std::string force_trajectory_name_; + const std::string lcs_force_trajectory_name_; drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); int N_ = 5; const double radius_ = 0.002; + const double newtons_per_meter_ = 40; }; } // namespace systems From 2b2578ff7a482365312f7cd18712a9c4ed760ee1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 10 Dec 2023 19:50:14 -0500 Subject: [PATCH 560/758] trying to visualize all lcs forces --- examples/franka/franka_c3_controller.cc | 16 ++- examples/franka/franka_visualizer.cc | 3 +- .../parameters/lcm_channels_simulation.yaml | 2 +- .../franka/systems/c3_trajectory_generator.cc | 40 ------- .../franka/systems/c3_trajectory_generator.h | 12 -- lcmtypes/lcmt_c3_forces.lcm | 11 ++ lcmtypes/lcmt_force.lcm | 12 ++ multibody/geom_geom_collider.cc | 2 +- solvers/lcs_factory.cc | 81 +++++++++++-- solvers/lcs_factory.h | 19 ++- systems/controllers/c3/lcs_factory_system.cc | 46 ++++++- systems/controllers/c3/lcs_factory_system.h | 7 ++ .../c3_output_systems.cc | 36 +++++- .../c3_output_systems.h | 17 +++ .../lcm_trajectory_systems.cc | 113 ++++++++---------- 15 files changed, 275 insertions(+), 142 deletions(-) create mode 100644 lcmtypes/lcmt_c3_forces.lcm create mode 100644 lcmtypes/lcmt_force.lcm diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index c147c3a463..858192e026 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -197,10 +197,6 @@ int DoMain(int argc, char* argv[]) { LcmPublisherSystem::Make( lcm_channel_params.c3_object_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); - auto force_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_force_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); auto c3_output_publisher = builder.AddSystem(LcmPublisherSystem::Make( @@ -214,6 +210,10 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.c3_actual_state_channel, &lcm, TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); @@ -282,12 +282,14 @@ int DoMain(int argc, char* argv[]) { plate_balancing_target->get_input_port_radio()); builder.Connect(controller->get_output_port_c3_solution(), c3_trajectory_generator->get_input_port_c3_solution()); + builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), + c3_output_sender->get_input_port_lcs_contact_jacobian()); builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_force_trajectory(), - force_trajectory_sender->get_input_port()); +// builder.Connect(c3_trajectory_generator->get_output_port_force_trajectory(), +// force_trajectory_sender->get_input_port()); builder.Connect(target_state_mux->get_output_port(), c3_state_sender->get_input_port_target_state()); builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), @@ -302,6 +304,8 @@ int DoMain(int argc, char* argv[]) { c3_output_sender->get_input_port_c3_intermediates()); builder.Connect(c3_output_sender->get_output_port_c3_debug(), c3_output_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_force(), + c3_forces_publisher->get_input_port()); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 86f5a32628..f37292b331 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -1,6 +1,7 @@ #include #include +#include #include #include #include @@ -159,7 +160,7 @@ int do_main(int argc, char* argv[]) { LcmSubscriberSystem::Make( lcm_channel_params.c3_object_channel, lcm)); auto trajectory_sub_force = builder.AddSystem( - LcmSubscriberSystem::Make( + LcmSubscriberSystem::Make( lcm_channel_params.c3_force_channel, lcm)); auto to_pose = builder.AddSystem>(plant); diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index 4e04c90e18..003e20c5dc 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -9,7 +9,7 @@ osc_debug_channel: OSC_DEBUG_FRANKA c3_actor_channel: C3_TRAJECTORY_ACTOR c3_object_channel: C3_TRAJECTORY_TRAY -c3_force_channel: C3_TRAJECTORY_FORCE +c3_force_channel: C3_FORCES c3_debug_output_channel: C3_DEBUG c3_target_state_channel: C3_TARGET c3_actual_state_channel: C3_ACTUAL diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 3d2002240a..9af7656509 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -46,18 +46,6 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( drake::Value()) .get_index(); - MatrixXd A = MatrixXd::Zero(n_x_, n_x_); - MatrixXd B = MatrixXd::Zero(n_x_, n_u_); - VectorXd d = VectorXd::Zero(n_x_); - MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); - MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); - MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); - MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); - VectorXd c = VectorXd::Zero(n_lambda_); - auto lcs = LCS(A, B, D, d, E, F, H, c, N_, c3_options_.dt); - lcs_port_ = - this->DeclareAbstractInputPort("lcs", drake::Value(lcs)).get_index(); - actor_trajectory_port_ = this->DeclareAbstractOutputPort( "c3_actor_trajectory_output", @@ -70,12 +58,6 @@ C3TrajectoryGenerator::C3TrajectoryGenerator( dairlib::lcmt_timestamped_saved_traj(), &C3TrajectoryGenerator::OutputObjectTrajectory) .get_index(); - force_trajectory_port_ = - this->DeclareAbstractOutputPort( - "c3_force_trajectory_output", - dairlib::lcmt_timestamped_saved_traj(), - &C3TrajectoryGenerator::OutputLCSForceTrajectory) - .get_index(); } void C3TrajectoryGenerator::OutputActorTrajectory( @@ -168,27 +150,5 @@ void C3TrajectoryGenerator::OutputObjectTrajectory( output_traj->utime = context.get_time() * 1e6; } -void C3TrajectoryGenerator::OutputLCSForceTrajectory( - const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const { - const auto& c3_solution = - this->EvalInputValue(context, c3_solution_port_); - // auto& lcs = this->EvalAbstractInput(context, lcs_port_)->get_value(); - - DRAKE_DEMAND(c3_solution->lambda_sol_.rows() == n_lambda_); - MatrixXd knots = c3_solution->lambda_sol_.cast(); - LcmTrajectory::Trajectory lcs_force_trajectory; - lcs_force_trajectory.traj_name = "lcs_force_trajectory"; - lcs_force_trajectory.datatypes = - std::vector(knots.rows(), "double"); - lcs_force_trajectory.datapoints = knots; - lcs_force_trajectory.time_vector = c3_solution->time_vector_.cast(); - LcmTrajectory lcm_traj({lcs_force_trajectory}, {"lcs_force_trajectory"}, - "lcs_force_trajectory", "lcs_force_trajectory", false); - - output_traj->saved_traj = lcm_traj.GenerateLcmObject(); - output_traj->utime = context.get_time() * 1e6; -} - } // namespace systems } // namespace dairlib diff --git a/examples/franka/systems/c3_trajectory_generator.h b/examples/franka/systems/c3_trajectory_generator.h index a41e111893..5ae42e5b8a 100644 --- a/examples/franka/systems/c3_trajectory_generator.h +++ b/examples/franka/systems/c3_trajectory_generator.h @@ -35,11 +35,6 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const { return this->get_output_port(object_trajectory_port_); } - // LCS contact force, not actor input forces - const drake::systems::OutputPort& get_output_port_force_trajectory() - const { - return this->get_output_port(force_trajectory_port_); - } void SetPublishEndEffectorOrientation(bool publish_end_effector_orientation) { publish_end_effector_orientation_ = publish_end_effector_orientation; @@ -54,15 +49,9 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { const drake::systems::Context& context, dairlib::lcmt_timestamped_saved_traj* output_traj) const; - void OutputLCSForceTrajectory( - const drake::systems::Context& context, - dairlib::lcmt_timestamped_saved_traj* output_traj) const; - drake::systems::InputPortIndex c3_solution_port_; - drake::systems::InputPortIndex lcs_port_; drake::systems::OutputPortIndex actor_trajectory_port_; drake::systems::OutputPortIndex object_trajectory_port_; - drake::systems::OutputPortIndex force_trajectory_port_; const drake::multibody::MultibodyPlant& plant_; C3Options c3_options_; @@ -76,7 +65,6 @@ class C3TrajectoryGenerator : public drake::systems::LeafSystem { int n_lambda_; int n_u_; - drake::systems::DiscreteStateIndex plan_start_time_index_; int N_; }; diff --git a/lcmtypes/lcmt_c3_forces.lcm b/lcmtypes/lcmt_c3_forces.lcm new file mode 100644 index 0000000000..f9122bd72a --- /dev/null +++ b/lcmtypes/lcmt_c3_forces.lcm @@ -0,0 +1,11 @@ +package dairlib; + +/* lcmtype containing information to visualize forces in meshcat +*/ +struct lcmt_c3_forces +{ + int64_t utime; + + int32_t num_forces; + lcmt_force forces[num_forces]; +} \ No newline at end of file diff --git a/lcmtypes/lcmt_force.lcm b/lcmtypes/lcmt_force.lcm new file mode 100644 index 0000000000..935c9635aa --- /dev/null +++ b/lcmtypes/lcmt_force.lcm @@ -0,0 +1,12 @@ +package dairlib; + +/* lcmtype containing information to visualize forces in meshcat +*/ +struct lcmt_force +{ + int64_t utime; + + // These are all expressed in the world frame. + double contact_point[3]; + double contact_force[3]; +} \ No newline at end of file diff --git a/multibody/geom_geom_collider.cc b/multibody/geom_geom_collider.cc index 60d79fe659..5af2e4872f 100644 --- a/multibody/geom_geom_collider.cc +++ b/multibody/geom_geom_collider.cc @@ -38,7 +38,7 @@ std::pair> GeomGeomCollider::EvalPolytope( if (num_friction_directions == 1) { throw std::runtime_error( - "GeomGeomCollider cannot specificy 1 friction direction unless " + "GeomGeomCollider cannot specify 1 friction direction unless " "using EvalPlanar."); } diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 65f45f49b3..5d317d441d 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -35,8 +35,6 @@ std::pair LCSFactory::LinearizePlantToLCS( const vector>& contact_geoms, int num_friction_directions, const std::vector& mu, double dt, int N, ContactModel contact_model) { - // int n_q = plant_ad.num_positions(); - // int n_v = plant_ad.num_velocities(); int n_x = plant_ad.num_positions() + plant_ad.num_velocities(); int n_u = plant_ad.num_actuators(); @@ -87,15 +85,10 @@ std::pair LCSFactory::LinearizePlantToLCS( Nqt = plant.MakeVelocityToQDotMap(context); MatrixXd qdotNv = MatrixXd(Nqt); - // plant_ad.MapQDotToVelocity(context_ad, qdot_no_contact, &vel); - - // std::optional> NqI = std::nullopt; Eigen::SparseMatrix NqI; NqI = plant.MakeQDotToVelocityMap(context); MatrixXd vNqdot = MatrixXd(NqI); - /// - /// Contact-related terms - /// + VectorXd phi(n_contacts); MatrixXd J_n(n_contacts, n_v); MatrixXd J_t(2 * n_contacts * num_friction_directions, n_v); @@ -154,6 +147,7 @@ std::pair LCSFactory::LinearizePlantToLCS( n_contact_vars = 2 * n_contacts * num_friction_directions; } + // Matrices with contact variables MatrixXd D = MatrixXd::Zero(n_x, n_contact_vars); MatrixXd E = MatrixXd::Zero(n_contact_vars, n_x); MatrixXd F = MatrixXd::Zero(n_contact_vars, n_contact_vars); @@ -214,8 +208,8 @@ std::pair LCSFactory::LinearizePlantToLCS( c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = J_t * dt * d_v - J_n * vNqdot * plant.GetPositions(context); } else if (contact_model == ContactModel::kAnitescu) { - VectorXd mu_vec = Eigen::Map(mu.data(), - mu.size()); + VectorXd mu_vec = Eigen::Map( + mu.data(), mu.size()); VectorXd anitescu_mu_vec = VectorXd::Zero(n_contact_vars); for (int i = 0; i < mu_vec.rows(); i++) { double cur = mu_vec(i); @@ -257,6 +251,73 @@ std::pair LCSFactory::LinearizePlantToLCS( return ret; } +Eigen::MatrixXd LCSFactory::ComputeContactJacobian( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const drake::multibody::MultibodyPlant& plant_ad, + const drake::systems::Context& context_ad, + const std::vector>& + contact_geoms, + int num_friction_directions, const std::vector& mu, double dt, + int N, dairlib::solvers::ContactModel contact_model) { +// int n_x = plant_ad.num_positions() + plant_ad.num_velocities(); + int n_u = plant_ad.num_actuators(); + + int n_contacts = contact_geoms.size(); + + DRAKE_DEMAND(plant_ad.num_velocities() == plant.num_velocities()); + DRAKE_DEMAND(plant_ad.num_positions() == plant.num_positions()); + int n_v = plant.num_velocities(); + int n_q = plant.num_positions(); + + VectorXd phi(n_contacts); + MatrixXd J_n(n_contacts, n_v); + MatrixXd J_t(2 * n_contacts * num_friction_directions, n_v); + + for (int i = 0; i < n_contacts; i++) { + multibody::GeomGeomCollider collider( + plant, + contact_geoms[i]); // deleted num_friction_directions (check with + // Michael about changes in geomgeom) + auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); + + phi(i) = phi_i; + J_n.row(i) = J_i.row(0); + J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, + n_v) = J_i.block(1, 0, 2 * num_friction_directions, n_v); + } + + if (contact_model == ContactModel::kStewartAndTrinkle) { + MatrixXd J_c = MatrixXd::Zero( + n_contacts + 2 * n_contacts * num_friction_directions, n_v); + J_c << J_n, J_t; + return J_c; + } else if (contact_model == ContactModel::kAnitescu) { + MatrixXd E_t = + MatrixXd::Zero(n_contacts, 2 * n_contacts * num_friction_directions); + for (int i = 0; i < n_contacts; i++) { + E_t.block(i, i * (2 * num_friction_directions), 1, + 2 * num_friction_directions) = + MatrixXd::Ones(1, 2 * num_friction_directions); + } + int n_contact_vars = 2 * n_contacts * num_friction_directions; + + VectorXd mu_vec = Eigen::Map( + mu.data(), mu.size()); + VectorXd anitescu_mu_vec = VectorXd::Zero(n_contact_vars); + for (int i = 0; i < mu_vec.rows(); i++) { + double cur = mu_vec(i); + anitescu_mu_vec(4 * i) = cur; + anitescu_mu_vec(4 * i + 1) = cur; + anitescu_mu_vec(4 * i + 2) = cur; + anitescu_mu_vec(4 * i + 3) = cur; + } + MatrixXd anitescu_mu_matrix = anitescu_mu_vec.asDiagonal(); + MatrixXd J_c = E_t.transpose() * J_n + anitescu_mu_matrix * J_t; + return J_c; + } +} + LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, set inactive_lambda_inds) { vector remaining_inds; diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index b50a1fe209..1bcd8c4cbf 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -9,7 +9,7 @@ namespace solvers { enum class ContactModel { kStewartAndTrinkle, /// Stewart and Trinkle timestepping contact - kAnitescu /// Anitescu convex contact + kAnitescu /// Anitescu convex contact }; class LCSFactory { @@ -33,14 +33,25 @@ class LCSFactory { /// @param mu /// @oaram dt The timestep for discretization /// @param N - static std::pair LinearizePlantToLCS( + static std::pair LinearizePlantToLCS( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, const drake::systems::Context& context_ad, const std::vector>& - contact_geoms, - int num_friction_directions, const std::vector& mu, double dt, int N, ContactModel=ContactModel::kStewartAndTrinkle); + contact_geoms, + int num_friction_directions, const std::vector& mu, double dt, + int N, ContactModel = ContactModel::kStewartAndTrinkle); + + static Eigen::MatrixXd ComputeContactJacobian( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const drake::multibody::MultibodyPlant& plant_ad, + const drake::systems::Context& context_ad, + const std::vector>& + contact_geoms, + int num_friction_directions, const std::vector& mu, double dt, + int N, ContactModel = ContactModel::kStewartAndTrinkle); /// Create an LCS by fixing some modes from another LCS /// Ignores generated inequalities that correspond to these modes, but diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 8709a3888d..0289f1727e 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -43,9 +43,14 @@ LCSFactorySystem::LCSFactorySystem( n_v_ = plant_.num_velocities(); n_x_ = n_q_ + n_v_; dt_ = c3_options_.dt; - n_lambda_ = - 2 * c3_options_.num_contacts + - 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + if (c3_options_.contact_model == "stewart_and_trinkle") { + n_lambda_ = + 2 * c3_options_.num_contacts + + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + } else if (c3_options_.contact_model == "anitescu") { + n_lambda_ = + 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; + } n_u_ = plant_.num_actuators(); lcs_state_input_port_ = @@ -64,6 +69,10 @@ LCSFactorySystem::LCSFactorySystem( "lcs", LCS(A, B, D, d, E, F, H, c, N_, dt_), &LCSFactorySystem::OutputLCS) .get_index(); + lcs_contact_jacobian_port_ = this->DeclareAbstractOutputPort( + "J_lcs", Eigen::MatrixXd(n_x_, n_lambda_), + &LCSFactorySystem::OutputLCSContactJacobian) + .get_index(); } void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, @@ -98,5 +107,36 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, c3_options_.N, contact_model); } +void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context& context, + Eigen::MatrixXd* output_jacobian) const { + const TimestampedVector* lcs_x = + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + + VectorXd q_v_u = + VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + + plant_.num_actuators()); + q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); +// drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); + + plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); + multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); +// multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u_), +// context_ad_); + solvers::ContactModel contact_model; + if (c3_options_.contact_model == "stewart_and_trinkle") { + contact_model = solvers::ContactModel::kStewartAndTrinkle; + } else if (c3_options_.contact_model == "anitescu") { + contact_model = solvers::ContactModel::kAnitescu; + } else { + throw std::runtime_error("unknown or unsupported contact model"); + } + + *output_jacobian = LCSFactory::ComputeContactJacobian( + plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, + c3_options_.N, contact_model); +} + } // namespace systems } // namespace dairlib diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h index 695294fa17..56038a6014 100644 --- a/systems/controllers/c3/lcs_factory_system.h +++ b/systems/controllers/c3/lcs_factory_system.h @@ -32,13 +32,20 @@ class LCSFactorySystem : public drake::systems::LeafSystem { return this->get_output_port(lcs_port_); } + const drake::systems::OutputPort& get_output_port_lcs_contact_jacobian() const { + return this->get_output_port(lcs_contact_jacobian_port_); + } + private: void OutputLCS(const drake::systems::Context& context, solvers::LCS* output_traj) const; + void OutputLCSContactJacobian(const drake::systems::Context& context, + Eigen::MatrixXd* output_jacobian) const; drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::OutputPortIndex actor_trajectory_port_; drake::systems::OutputPortIndex lcs_port_; + drake::systems::OutputPortIndex lcs_contact_jacobian_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index 48f23f100e..ab6cec60f7 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -1,9 +1,11 @@ #include "c3_output_systems.h" - #include "common/eigen_utils.h" #include "solvers/c3_output.h" +#include "dairlib/lcmt_force.hpp" + + namespace dairlib { namespace systems { @@ -22,12 +24,18 @@ C3OutputSender::C3OutputSender() { this->DeclareAbstractInputPort("c3_intermediates", drake::Value{}) .get_index(); + lcs_contact_jacobian_port_ = + this->DeclareAbstractInputPort("J_lcs", drake::Value()).get_index(); this->set_name("c3_output_sender"); lcm_c3_output_port_ = this->DeclareAbstractOutputPort( "lcmt_c3_output", dairlib::lcmt_c3_output(), &C3OutputSender::OutputC3Lcm) .get_index(); + lcs_forces_output_port_ = this->DeclareAbstractOutputPort( + "lcmt_c3_force", dairlib::lcmt_c3_forces(), + &C3OutputSender::OutputC3Forces) + .get_index(); } void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, @@ -42,5 +50,31 @@ void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, *output = c3_output.GenerateLcmObject(context.get_time()); } + +void C3OutputSender::OutputC3Forces( + const drake::systems::Context& context, + dairlib::lcmt_c3_forces* output_traj) const { + const auto& c3_solution = + this->EvalInputValue(context, c3_solution_port_); + const auto& J_c = + this->EvalInputValue(context, lcs_contact_jacobian_port_); + output_traj->num_forces = c3_solution->lambda_sol_.rows(); + output_traj->forces.resize(output_traj->num_forces); + for (int i = 0; i < c3_solution->lambda_sol_.rows(); ++i){ + auto force = lcmt_force(); + force.contact_point[0] = 0; + force.contact_point[1] = 0; + force.contact_point[2] = 0; + // 6, 7, 8 are the indices for the x,y,z components of the tray + // TODO(yangwill): find a cleaner way to figure out the equivalent forces expressed in the world frame + force.contact_force[0] = c3_solution->lambda_sol_(i, 0) * J_c->row(i)(6); + force.contact_force[1] = c3_solution->lambda_sol_(i, 0) * J_c->row(i)(7); + force.contact_force[2] = c3_solution->lambda_sol_(i, 0) * J_c->row(i)(8); + output_traj->forces[i] = force; + } + output_traj->utime = context.get_time() * 1e6; +} + + } // namespace systems } // namespace dairlib \ No newline at end of file diff --git a/systems/trajectory_optimization/c3_output_systems.h b/systems/trajectory_optimization/c3_output_systems.h index 10ad89f248..42ac385970 100644 --- a/systems/trajectory_optimization/c3_output_systems.h +++ b/systems/trajectory_optimization/c3_output_systems.h @@ -4,6 +4,7 @@ #include #include "dairlib/lcmt_c3_output.hpp" +#include "dairlib/lcmt_c3_forces.hpp" #include "drake/systems/framework/leaf_system.h" #include "drake/systems/lcm/lcm_interface_system.h" @@ -25,17 +26,33 @@ class C3OutputSender : public drake::systems::LeafSystem { return this->get_input_port(c3_intermediates_port_); } + const drake::systems::InputPort& get_input_port_lcs_contact_jacobian() const { + return this->get_input_port(lcs_contact_jacobian_port_); + } + const drake::systems::OutputPort& get_output_port_c3_debug() const { return this->get_output_port(lcm_c3_output_port_); } + // LCS contact force, not actor input forces + const drake::systems::OutputPort& get_output_port_c3_force() + const { + return this->get_output_port(lcs_forces_output_port_); + } + private: void OutputC3Lcm(const drake::systems::Context& context, dairlib::lcmt_c3_output* output) const; + void OutputC3Forces( + const drake::systems::Context& context, + dairlib::lcmt_c3_forces* output_traj) const; + drake::systems::InputPortIndex c3_solution_port_; drake::systems::InputPortIndex c3_intermediates_port_; + drake::systems::InputPortIndex lcs_contact_jacobian_port_; drake::systems::OutputPortIndex lcm_c3_output_port_; + drake::systems::OutputPortIndex lcs_forces_output_port_; }; } // namespace systems diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 3a98aa30eb..db279098df 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -4,6 +4,7 @@ #include "common/eigen_utils.h" #include "common/find_resource.h" +#include "dairlib/lcmt_c3_forces.hpp" #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "drake/geometry/rgba.h" @@ -272,12 +273,11 @@ LcmForceDrawer::LcmForceDrawer( .get_index(); force_trajectory_input_port_ = - this->DeclareAbstractInputPort( - "lcmt_timestamped_saved_traj: force", - drake::Value{}) + this->DeclareAbstractInputPort("lcmt_c3_forces", + drake::Value{}) .get_index(); - meshcat_->SetProperty(force_path_, "visible", false, 0); + meshcat_->SetProperty(force_path_, "visible", true, 0); // Add the geometry to meshcat. // Set radius 1.0 so that it can be scaled later by the force/moment norm in @@ -288,19 +288,13 @@ LcmForceDrawer::LcmForceDrawer( const drake::geometry::MeshcatCone arrowhead( arrowhead_height, arrowhead_width, arrowhead_width); - meshcat_->SetObject(force_path_ + "/u_lcs/cylinder", cylinder, - {1, 0, 0, 1}); + meshcat_->SetObject(force_path_ + "/u_lcs/cylinder", cylinder, {1, 0, 0, 1}); meshcat_->SetObject(force_path_ + "/u_lcs/head", arrowhead, {1, 0, 0, 1}); - for (int i = 0; i < 5; ++i) { - for (int force_component = 0; force_component < 4; ++force_component) { - const std::string lcs_force_path = force_path_ + "/lcs_force_" + std::to_string(i) + - "/" + std::to_string(force_component); - meshcat_->SetObject(lcs_force_path + - "/cylinder", - cylinder, {1, 0, 0, 1}); - meshcat_->SetObject(lcs_force_path + "/head", - arrowhead, {1, 0, 0, 1}); - } + for (int i = 0; i < 20; ++i) { + const std::string lcs_force_path = force_path_ + "/lcs_force_" + + std::to_string(i); + meshcat_->SetObject(lcs_force_path + "/cylinder", cylinder, {1, 0, 0, 1}); + meshcat_->SetObject(lcs_force_path + "/head", arrowhead, {1, 0, 0, 1}); } DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); @@ -372,59 +366,52 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( drake::systems::EventStatus LcmForceDrawer::DrawForces( const Context& context, DiscreteValues* discrete_state) const { - if (this->EvalInputValue( + if (this->EvalInputValue( context, force_trajectory_input_port_) ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } - const auto& lcmt_traj = - this->EvalInputValue( - context, force_trajectory_input_port_); - auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); - const auto& force_trajectory_block = - lcm_traj.GetTrajectory(lcs_force_trajectory_name_); - auto force_trajectory = PiecewisePolynomial::FirstOrderHold( - force_trajectory_block.time_vector, force_trajectory_block.datapoints); - auto all_forces = force_trajectory.value(force_trajectory_block.time_vector[0]).col(0); - for (int i = 0; i < 5; ++i) { - VectorXd pose = VectorXd::Zero(3); //TODO(yangwill) fix this + const auto& c3_forces = this->EvalInputValue( + context, force_trajectory_input_port_); + for (int i = 0; i < c3_forces->num_forces; ++i) { + + const VectorXd pose = Eigen::Map( + c3_forces->forces[i].contact_point, 3); + const std::string& force_path_root = - force_path_ + "/lcs_force_" + std::to_string(i) + "/"; + force_path_ + "/lcs_force_" + std::to_string(i); meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); - VectorXd force = all_forces.segment(4 * i, 4); - std::vector bases_vectors = {{0, -0.4, 1}, - {0, 0.4, 1}, - {-0.4, 0.0, 1}, - {0.4, 0.0, 1}}; - for (int j = 0; j < 4; ++j) { - auto force_norm = force(j); - // Stretch the cylinder in z. - const std::string& force_arrow_path = - force_path_root + std::to_string(j); - if (force_norm >= 0.01) { - meshcat_->SetTransform( - force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(bases_vectors[j], 2))); - const double height = force_norm / newtons_per_meter_; - meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", - {0, 0, 0.5 * height}); - // Note: Meshcat does not fully support non-uniform scaling (see - // #18095). We get away with it here since there is no rotation on this - // frame and no children in the kinematic tree. - meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", - {1, 1, height}); - // Translate the arrowheads. - const double arrowhead_height = radius_ * 2.0; - meshcat_->SetTransform( - force_arrow_path + "/head", - RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), - Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_arrow_path, "visible", true); - } else { - // meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", - // false); - meshcat_->SetProperty(force_arrow_path, "visible", false); - } + if (i > 11){ + meshcat_->SetTransform(force_path_root, RigidTransformd(Vector3d(-1, 0, 0))); + } + const VectorXd force = Eigen::Map( + c3_forces->forces[i].contact_force, 3); + auto force_norm = force.norm(); + // Stretch the cylinder in z. + const std::string& force_arrow_path = force_path_root; + if (force_norm >= 0.01) { + meshcat_->SetTransform( + force_arrow_path, + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + const double height = force_norm / newtons_per_meter_; + meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", + {0, 0, 0.5 * height}); + // Note: Meshcat does not fully support non-uniform scaling (see + // #18095). We get away with it here since there is no rotation on this + // frame and no children in the kinematic tree. + meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", + {1, 1, height}); + // Translate the arrowheads. + const double arrowhead_height = radius_ * 2.0; + meshcat_->SetTransform( + force_arrow_path + "/head", + RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), + Vector3d{0, 0, height + arrowhead_height})); + meshcat_->SetProperty(force_arrow_path, "visible", true); + } else { + // meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", + // false); + meshcat_->SetProperty(force_arrow_path, "visible", false); } } return drake::systems::EventStatus::Succeeded(); From b71a4cc1b685bba49d1cbe28875c560b5d183e0f Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 10 Dec 2023 22:29:49 -0500 Subject: [PATCH 561/758] force visualization works --- examples/franka/franka_c3_controller.cc | 2 + multibody/geom_geom_collider.cc | 87 ++++++++++++------- multibody/geom_geom_collider.h | 8 +- solvers/lcs_factory.cc | 12 +-- solvers/lcs_factory.h | 2 +- systems/controllers/c3/lcs_factory_system.cc | 59 +++++++++++-- systems/controllers/c3/lcs_factory_system.h | 13 +++ .../c3_output_systems.cc | 31 ++++--- .../c3_output_systems.h | 5 ++ .../lcm_trajectory_systems.cc | 27 +++--- 10 files changed, 175 insertions(+), 71 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 858192e026..4bbd9fa458 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -284,6 +284,8 @@ int DoMain(int argc, char* argv[]) { c3_trajectory_generator->get_input_port_c3_solution()); builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), c3_output_sender->get_input_port_lcs_contact_jacobian()); + builder.Connect(lcs_factory->get_output_port_lcs_contact_points(), + c3_output_sender->get_input_port_lcs_contact_points()); builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), diff --git a/multibody/geom_geom_collider.cc b/multibody/geom_geom_collider.cc index 5af2e4872f..cfb33bb81b 100644 --- a/multibody/geom_geom_collider.cc +++ b/multibody/geom_geom_collider.cc @@ -1,17 +1,17 @@ #include "multibody/geom_geom_collider.h" -#include "multibody/geom_geom_collider.h" #include "drake/math/rotation_matrix.h" -using Eigen::Vector3d; -using Eigen::Matrix; using drake::EigenPtr; using drake::MatrixX; +using drake::VectorX; using drake::geometry::GeometryId; using drake::geometry::SignedDistancePair; using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; using drake::systems::Context; +using Eigen::Matrix; +using Eigen::Vector3d; namespace dairlib { namespace multibody { @@ -22,8 +22,7 @@ GeomGeomCollider::GeomGeomCollider( const drake::SortedPair geometry_pair) : plant_(plant), geometry_id_A_(geometry_pair.first()), - geometry_id_B_(geometry_pair.second()) { -} + geometry_id_B_(geometry_pair.second()) {} template std::pair> GeomGeomCollider::Eval(const Context& context, @@ -35,22 +34,21 @@ template std::pair> GeomGeomCollider::EvalPolytope( const Context& context, int num_friction_directions, JacobianWrtVariable wrt) { - if (num_friction_directions == 1) { throw std::runtime_error( - "GeomGeomCollider cannot specify 1 friction direction unless " - "using EvalPlanar."); + "GeomGeomCollider cannot specify 1 friction direction unless " + "using EvalPlanar."); } // Build friction basis - Matrix force_basis( - 2 * num_friction_directions + 1, 3); + Matrix force_basis(2 * num_friction_directions + 1, + 3); force_basis.row(0) << 1, 0, 0; for (int i = 0; i < num_friction_directions; i++) { double theta = (M_PI * i) / num_friction_directions; - force_basis.row(2*i + 1) = Vector3d(0, cos(theta), sin(theta)); - force_basis.row(2*i + 2) = -force_basis.row(2*i + 1); + force_basis.row(2 * i + 1) = Vector3d(0, cos(theta), sin(theta)); + force_basis.row(2 * i + 2) = -force_basis.row(2 * i + 1); } return DoEval(context, force_basis, wrt); } @@ -62,12 +60,41 @@ std::pair> GeomGeomCollider::EvalPlanar( return DoEval(context, planar_normal.transpose(), wrt, true); } - // } +template +std::pair, VectorX> +GeomGeomCollider::CalcWitnessPoints(const Context& context) { + const auto& query_port = plant_.get_geometry_query_input_port(); + const auto& query_object = + query_port.template Eval>(context); + + const SignedDistancePair signed_distance_pair = + query_object.ComputeSignedDistancePairClosestPoints(geometry_id_A_, + geometry_id_B_); + const auto& inspector = query_object.inspector(); + const auto frame_A_id = inspector.GetFrameId(geometry_id_A_); + const auto frame_B_id = inspector.GetFrameId(geometry_id_B_); + const auto& frameA = plant_.GetBodyFromFrameId(frame_A_id)->body_frame(); + const auto& frameB = plant_.GetBodyFromFrameId(frame_B_id)->body_frame(); + + const Vector3d& p_ACa = + inspector.GetPoseInFrame(geometry_id_A_).template cast() * + signed_distance_pair.p_ACa; + const Vector3d& p_BCb = + inspector.GetPoseInFrame(geometry_id_B_).template cast() * + signed_distance_pair.p_BCb; + Vector3d p_WCa = Vector3d::Zero(); + Vector3d p_WCb = Vector3d::Zero(); + plant_.CalcPointsPositions(context, frameA, p_ACa, plant_.world_frame(), + &p_WCa); + plant_.CalcPointsPositions(context, frameB, p_BCb, + plant_.world_frame(), &p_WCb); + return std::pair, VectorX>(p_WCa, p_WCb); +} + template std::pair> GeomGeomCollider::DoEval( const Context& context, Matrix force_basis, JacobianWrtVariable wrt, bool planar) { - const auto& query_port = plant_.get_geometry_query_input_port(); const auto& query_object = query_port.template Eval>(context); @@ -84,27 +111,25 @@ std::pair> GeomGeomCollider::DoEval( const Vector3d& p_ACa = inspector.GetPoseInFrame(geometry_id_A_).template cast() * - signed_distance_pair.p_ACa; + signed_distance_pair.p_ACa; const Vector3d& p_BCb = inspector.GetPoseInFrame(geometry_id_B_).template cast() * - signed_distance_pair.p_BCb; - + signed_distance_pair.p_BCb; - int n_cols = (wrt == JacobianWrtVariable::kV) ? plant_.num_velocities() : - plant_.num_positions(); + int n_cols = (wrt == JacobianWrtVariable::kV) ? plant_.num_velocities() + : plant_.num_positions(); Matrix Jv_WCa(3, n_cols); Matrix Jv_WCb(3, n_cols); - plant_.CalcJacobianTranslationalVelocity(context, wrt, - frameA, p_ACa, plant_.world_frame(), - plant_.world_frame(), &Jv_WCa); - plant_.CalcJacobianTranslationalVelocity(context, wrt, - frameB, p_BCb, plant_.world_frame(), - plant_.world_frame(), &Jv_WCb); + plant_.CalcJacobianTranslationalVelocity(context, wrt, frameA, p_ACa, + plant_.world_frame(), + plant_.world_frame(), &Jv_WCa); + plant_.CalcJacobianTranslationalVelocity(context, wrt, frameB, p_BCb, + plant_.world_frame(), + plant_.world_frame(), &Jv_WCb); - const auto& R_WC = - drake::math::RotationMatrix::MakeFromOneVector( - signed_distance_pair.nhat_BA_W, 0); + const auto& R_WC = drake::math::RotationMatrix::MakeFromOneVector( + signed_distance_pair.nhat_BA_W, 0); // if this is a planar problem, then the basis has one row and encodes // the planar normal direction. @@ -116,7 +141,8 @@ std::pair> GeomGeomCollider::DoEval( force_basis.resize(3, 3); // First row is the contact normal, projected to the plane - force_basis.row(0) = signed_distance_pair.nhat_BA_W - + force_basis.row(0) = + signed_distance_pair.nhat_BA_W - planar_normal * planar_normal.dot(signed_distance_pair.nhat_BA_W); force_basis.row(0).normalize(); @@ -125,7 +151,7 @@ std::pair> GeomGeomCollider::DoEval( force_basis.row(1).normalize(); force_basis.row(2) = -force_basis.row(1); } - // Standard case + // Standard case auto J = force_basis * R_WC.matrix().transpose() * (Jv_WCa - Jv_WCb); return std::pair>(signed_distance_pair.distance, J); } @@ -133,5 +159,4 @@ std::pair> GeomGeomCollider::DoEval( } // namespace multibody } // namespace dairlib - template class dairlib::multibody::GeomGeomCollider; \ No newline at end of file diff --git a/multibody/geom_geom_collider.h b/multibody/geom_geom_collider.h index 5e32b95290..9d3b107f5a 100644 --- a/multibody/geom_geom_collider.h +++ b/multibody/geom_geom_collider.h @@ -31,7 +31,6 @@ class GeomGeomCollider { drake::multibody::JacobianWrtVariable wrt = drake::multibody::JacobianWrtVariable::kV); - /// Calculates the distance and contact frame Jacobian. /// Jacobian is ordered [J_n; J_t], and has shape //// (2*num_friction_directions + 1) x (nq or nv), depending @@ -48,12 +47,10 @@ class GeomGeomCollider { /// @param num_friction_directions /// @return A pair with std::pair> EvalPolytope( - const drake::systems::Context& context, - int num_friction_directions, + const drake::systems::Context& context, int num_friction_directions, drake::multibody::JacobianWrtVariable wrt = drake::multibody::JacobianWrtVariable::kV); - /// Calculates the distance and contact frame Jacobian for a 2D planar problem /// Jacobian is ordered [J_n; +J_t; -J_t], and has shape 3 x (nq). /// J_t refers to the (contact_normal x planar_normal) direction @@ -66,6 +63,9 @@ class GeomGeomCollider { drake::multibody::JacobianWrtVariable wrt = drake::multibody::JacobianWrtVariable::kV); + std::pair, drake::VectorX> CalcWitnessPoints( + const drake::systems::Context& context); + private: std::pair> DoEval( const drake::systems::Context& context, diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 5d317d441d..ed07ac3653 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -251,7 +251,7 @@ std::pair LCSFactory::LinearizePlantToLCS( return ret; } -Eigen::MatrixXd LCSFactory::ComputeContactJacobian( +std::pair> LCSFactory::ComputeContactJacobian( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, @@ -273,14 +273,16 @@ Eigen::MatrixXd LCSFactory::ComputeContactJacobian( VectorXd phi(n_contacts); MatrixXd J_n(n_contacts, n_v); MatrixXd J_t(2 * n_contacts * num_friction_directions, n_v); - + std::vector contact_points; for (int i = 0; i < n_contacts; i++) { multibody::GeomGeomCollider collider( plant, contact_geoms[i]); // deleted num_friction_directions (check with // Michael about changes in geomgeom) auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); - + auto [p_WCa, p_WCb] = collider.CalcWitnessPoints(context); + // TODO(yangwill): think about if we want to push back both witness points + contact_points.push_back(p_WCa); phi(i) = phi_i; J_n.row(i) = J_i.row(0); J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, @@ -291,7 +293,7 @@ Eigen::MatrixXd LCSFactory::ComputeContactJacobian( MatrixXd J_c = MatrixXd::Zero( n_contacts + 2 * n_contacts * num_friction_directions, n_v); J_c << J_n, J_t; - return J_c; + return std::make_pair(J_c, contact_points); } else if (contact_model == ContactModel::kAnitescu) { MatrixXd E_t = MatrixXd::Zero(n_contacts, 2 * n_contacts * num_friction_directions); @@ -314,7 +316,7 @@ Eigen::MatrixXd LCSFactory::ComputeContactJacobian( } MatrixXd anitescu_mu_matrix = anitescu_mu_vec.asDiagonal(); MatrixXd J_c = E_t.transpose() * J_n + anitescu_mu_matrix * J_t; - return J_c; + return std::make_pair(J_c, contact_points); } } diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index 1bcd8c4cbf..2258b69451 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -43,7 +43,7 @@ class LCSFactory { int num_friction_directions, const std::vector& mu, double dt, int N, ContactModel = ContactModel::kStewartAndTrinkle); - static Eigen::MatrixXd ComputeContactJacobian( + static std::pair> ComputeContactJacobian( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 0289f1727e..7e1376bed5 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -69,12 +69,27 @@ LCSFactorySystem::LCSFactorySystem( "lcs", LCS(A, B, D, d, E, F, H, c, N_, dt_), &LCSFactorySystem::OutputLCS) .get_index(); +// DeclareForcedDiscreteUpdateEvent(&LCSFactorySystem::UpdateLCS); + +// contact_jacobian_ = MatrixXd::Zero(n_lambda_, n_v_); + lcs_contact_jacobian_port_ = this->DeclareAbstractOutputPort( "J_lcs", Eigen::MatrixXd(n_x_, n_lambda_), &LCSFactorySystem::OutputLCSContactJacobian) .get_index(); + + lcs_contact_points_port_ = this->DeclareAbstractOutputPort( + "p_contact", std::vector(), + &LCSFactorySystem::OutputLCSContactPoints) + .get_index(); } +//drake::systems::EventStatus LCSFactorySystem::UpdateLCS( +// const drake::systems::Context& context, +// drake::systems::DiscreteValues* discrete_state) const{ +// +//} + void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, LCS* output_lcs) const { const TimestampedVector* lcs_x = @@ -115,14 +130,11 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Contextget_data(), VectorXd::Zero(n_u_); -// drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); -// multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u_), -// context_ad_); solvers::ContactModel contact_model; if (c3_options_.contact_model == "stewart_and_trinkle") { contact_model = solvers::ContactModel::kStewartAndTrinkle; @@ -132,11 +144,48 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context contact_points; + std::tie(*output_jacobian, contact_points) = LCSFactory::ComputeContactJacobian( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); } +void LCSFactorySystem::OutputLCSContactPoints(const drake::systems::Context& context, + std::vector* contact_points) const { + const TimestampedVector* lcs_x = + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + + VectorXd q_v_u = + VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + + plant_.num_actuators()); + q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); + + plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); + multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); + solvers::ContactModel contact_model; + if (c3_options_.contact_model == "stewart_and_trinkle") { + contact_model = solvers::ContactModel::kStewartAndTrinkle; + } else if (c3_options_.contact_model == "anitescu") { + contact_model = solvers::ContactModel::kAnitescu; + } else { + throw std::runtime_error("unknown or unsupported contact model"); + } + + MatrixXd contact_jacobian; + contact_points->clear(); + std::tie(contact_jacobian, *contact_points) = LCSFactory::ComputeContactJacobian( + plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, + c3_options_.N, contact_model); + +// for (auto& contact_point : witness_points_){ +// contact_points->push_back(contact_point); +// } +} + + + } // namespace systems } // namespace dairlib diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h index 56038a6014..a78a800789 100644 --- a/systems/controllers/c3/lcs_factory_system.h +++ b/systems/controllers/c3/lcs_factory_system.h @@ -36,16 +36,26 @@ class LCSFactorySystem : public drake::systems::LeafSystem { return this->get_output_port(lcs_contact_jacobian_port_); } + const drake::systems::OutputPort& get_output_port_lcs_contact_points() const { + return this->get_output_port(lcs_contact_points_port_); + } + private: + drake::systems::EventStatus UpdateLCS( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; void OutputLCS(const drake::systems::Context& context, solvers::LCS* output_traj) const; void OutputLCSContactJacobian(const drake::systems::Context& context, Eigen::MatrixXd* output_jacobian) const; + void OutputLCSContactPoints(const drake::systems::Context& context, + std::vector* contact_points) const; drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::OutputPortIndex actor_trajectory_port_; drake::systems::OutputPortIndex lcs_port_; drake::systems::OutputPortIndex lcs_contact_jacobian_port_; + drake::systems::OutputPortIndex lcs_contact_points_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; @@ -56,6 +66,9 @@ class LCSFactorySystem : public drake::systems::LeafSystem { C3Options c3_options_; +// mutable std::vector witness_points_; +// mutable Eigen::MatrixXd contact_jacobian_; + // convenience for variable sizes int n_q_; int n_v_; diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index ab6cec60f7..4ce7ed009f 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -26,6 +26,8 @@ C3OutputSender::C3OutputSender() { .get_index(); lcs_contact_jacobian_port_ = this->DeclareAbstractInputPort("J_lcs", drake::Value()).get_index(); + lcs_contact_points_port_ = + this->DeclareAbstractInputPort("p_lcs", drake::Value>()).get_index(); this->set_name("c3_output_sender"); lcm_c3_output_port_ = this->DeclareAbstractOutputPort( @@ -58,19 +60,26 @@ void C3OutputSender::OutputC3Forces( this->EvalInputValue(context, c3_solution_port_); const auto& J_c = this->EvalInputValue(context, lcs_contact_jacobian_port_); + const auto& contact_points = + this->EvalInputValue>(context, lcs_contact_points_port_); output_traj->num_forces = c3_solution->lambda_sol_.rows(); output_traj->forces.resize(output_traj->num_forces); - for (int i = 0; i < c3_solution->lambda_sol_.rows(); ++i){ - auto force = lcmt_force(); - force.contact_point[0] = 0; - force.contact_point[1] = 0; - force.contact_point[2] = 0; - // 6, 7, 8 are the indices for the x,y,z components of the tray - // TODO(yangwill): find a cleaner way to figure out the equivalent forces expressed in the world frame - force.contact_force[0] = c3_solution->lambda_sol_(i, 0) * J_c->row(i)(6); - force.contact_force[1] = c3_solution->lambda_sol_(i, 0) * J_c->row(i)(7); - force.contact_force[2] = c3_solution->lambda_sol_(i, 0) * J_c->row(i)(8); - output_traj->forces[i] = force; + int forces_per_contact = J_c->rows() / contact_points->size(); + int contact_var_start; + for (int contact_index = 0; contact_index < contact_points->size(); ++contact_index){ + contact_var_start = forces_per_contact * contact_index; + for (int i = 0; i < forces_per_contact; ++i){ + auto force = lcmt_force(); + force.contact_point[0] = contact_points->at(contact_index)[0]; + force.contact_point[1] = contact_points->at(contact_index)[1]; + force.contact_point[2] = contact_points->at(contact_index)[2]; + // 6, 7, 8 are the indices for the x,y,z components of the tray + // TODO(yangwill): find a cleaner way to figure out the equivalent forces expressed in the world frame + force.contact_force[0] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(6); + force.contact_force[1] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(7); + force.contact_force[2] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(8); + output_traj->forces[contact_var_start + i] = force; + } } output_traj->utime = context.get_time() * 1e6; } diff --git a/systems/trajectory_optimization/c3_output_systems.h b/systems/trajectory_optimization/c3_output_systems.h index 42ac385970..6bce22c4e1 100644 --- a/systems/trajectory_optimization/c3_output_systems.h +++ b/systems/trajectory_optimization/c3_output_systems.h @@ -30,6 +30,10 @@ class C3OutputSender : public drake::systems::LeafSystem { return this->get_input_port(lcs_contact_jacobian_port_); } + const drake::systems::InputPort& get_input_port_lcs_contact_points() const { + return this->get_input_port(lcs_contact_points_port_); + } + const drake::systems::OutputPort& get_output_port_c3_debug() const { return this->get_output_port(lcm_c3_output_port_); } @@ -51,6 +55,7 @@ class C3OutputSender : public drake::systems::LeafSystem { drake::systems::InputPortIndex c3_solution_port_; drake::systems::InputPortIndex c3_intermediates_port_; drake::systems::InputPortIndex lcs_contact_jacobian_port_; + drake::systems::InputPortIndex lcs_contact_points_port_; drake::systems::OutputPortIndex lcm_c3_output_port_; drake::systems::OutputPortIndex lcs_forces_output_port_; }; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index db279098df..ac8dffdb4d 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -288,11 +288,11 @@ LcmForceDrawer::LcmForceDrawer( const drake::geometry::MeshcatCone arrowhead( arrowhead_height, arrowhead_width, arrowhead_width); - meshcat_->SetObject(force_path_ + "/u_lcs/cylinder", cylinder, {1, 0, 0, 1}); - meshcat_->SetObject(force_path_ + "/u_lcs/head", arrowhead, {1, 0, 0, 1}); + meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder, {0, 0, 1, 1}); + meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead, {0, 0, 1, 1}); for (int i = 0; i < 20; ++i) { const std::string lcs_force_path = force_path_ + "/lcs_force_" + - std::to_string(i); + std::to_string(i) + "/arrow"; meshcat_->SetObject(lcs_force_path + "/cylinder", cylinder, {1, 0, 0, 1}); meshcat_->SetObject(lcs_force_path + "/head", arrowhead, {1, 0, 0, 1}); } @@ -333,27 +333,29 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( } auto force = force_trajectory.value(force_trajectory_block.time_vector[0]); - - meshcat_->SetTransform(force_path_ + "/u_lcs", RigidTransformd(pose)); + const std::string& force_path_root = + force_path_ + "/u_lcs/"; + meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + const std::string& force_arrow_path = force_path_root + "arrow"; auto force_norm = force.norm(); // Stretch the cylinder in z. if (force_norm >= 0.01) { meshcat_->SetTransform( - force_path_ + "/u_lcs", + force_arrow_path, RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); const double height = force_norm / newtons_per_meter_; - meshcat_->SetProperty(force_path_ + "/u_lcs/cylinder", "position", + meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); // Note: Meshcat does not fully support non-uniform scaling (see #18095). // We get away with it here since there is no rotation on this frame and // no children in the kinematic tree. - meshcat_->SetProperty(force_path_ + "/u_lcs/cylinder", "scale", + meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", {1, 1, height}); // Translate the arrowheads. const double arrowhead_height = radius_ * 2.0; meshcat_->SetTransform( - force_path_ + "/u_lcs/head", + force_arrow_path + "/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), Vector3d{0, 0, height + arrowhead_height})); meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); @@ -379,16 +381,13 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( c3_forces->forces[i].contact_point, 3); const std::string& force_path_root = - force_path_ + "/lcs_force_" + std::to_string(i); + force_path_ + "/lcs_force_" + std::to_string(i) + "/"; meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); - if (i > 11){ - meshcat_->SetTransform(force_path_root, RigidTransformd(Vector3d(-1, 0, 0))); - } const VectorXd force = Eigen::Map( c3_forces->forces[i].contact_force, 3); auto force_norm = force.norm(); // Stretch the cylinder in z. - const std::string& force_arrow_path = force_path_root; + const std::string& force_arrow_path = force_path_root + "arrow"; if (force_norm >= 0.01) { meshcat_->SetTransform( force_arrow_path, From 64a118714f8a5aff7ff4bbe98f3e8152c0f09872 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 11 Dec 2023 17:14:32 -0500 Subject: [PATCH 562/758] small naming improvements --- examples/franka/franka_c3_controller.cc | 4 +- examples/franka/urdf/left_support.urdf | 8 +-- solvers/c3.cc | 2 + solvers/c3_miqp.cc | 16 +++--- systems/controllers/c3/lcs_factory_system.cc | 24 +++++---- systems/controllers/c3/lcs_factory_system.h | 6 ++- systems/controllers/c3_controller.cc | 2 - systems/controllers/c3_controller.h | 1 - .../c3_output_systems.cc | 54 +++++++++++++------ .../c3_output_systems.h | 25 ++++++--- .../lcm_trajectory_systems.cc | 3 +- 11 files changed, 88 insertions(+), 57 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 4bbd9fa458..54da088571 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -290,8 +290,6 @@ int DoMain(int argc, char* argv[]) { actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), object_trajectory_sender->get_input_port()); -// builder.Connect(c3_trajectory_generator->get_output_port_force_trajectory(), -// force_trajectory_sender->get_input_port()); builder.Connect(target_state_mux->get_output_port(), c3_state_sender->get_input_port_target_state()); builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), @@ -308,6 +306,8 @@ int DoMain(int argc, char* argv[]) { c3_output_publisher->get_input_port()); builder.Connect(c3_output_sender->get_output_port_c3_force(), c3_forces_publisher->get_input_port()); +// builder.Connect(c3_output_sender->get_output_port_next_c3_input(), +// lcs_factory->get_input_port_lcs_input()); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index ba1719f487..2f8c5f4c5a 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -15,19 +15,19 @@ - + - - + + - + diff --git a/solvers/c3.cc b/solvers/c3.cc index cd776ed188..e0395e0d5e 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -142,6 +142,7 @@ vector C3::Solve(const VectorXd& x0, vector& delta, } vector zfin = SolveQP(x0, Gv, WD); + std::cout << "lambda_sol " << z_sol_->at(0).segment(n_, m_) << std::endl; return zfin; } @@ -187,6 +188,7 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); if (hflag_ == 1) { + std::cout << "solving lcp: " << std::endl; drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 2806679faf..da5af3a22e 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -42,12 +42,9 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, Mcons1 << E, F, H; // set up for constraints (\lambda >= 0) - MatrixXd MM1; - MM1 = MatrixXd::Zero(m_, n_); - MatrixXd MM2; - MM2 = MatrixXd::Identity(m_, m_); - MatrixXd MM3; - MM3 = MatrixXd::Zero(m_, k_); + MatrixXd MM1 = MatrixXd::Zero(m_, n_); + MatrixXd MM2 = MatrixXd::Identity(m_, m_); + MatrixXd MM3 = MatrixXd::Zero(m_, k_); MatrixXd Mcons2(m_, n_ + m_ + k_); Mcons2 << MM1, MM2, MM3; @@ -85,8 +82,9 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.setObjective(obj, GRB_MINIMIZE); - int M = 100000; // big M variable + int M = std::numeric_limits::max(); // big M variable double coeff[n_ + m_ + k_]; + double coeff2[n_ + m_ + k_]; for (int i = 0; i < m_; i++) { GRBLinExpr cexpr = 0; @@ -104,10 +102,10 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, /// convert VectorXd to double for (int j = 0; j < n_ + m_ + k_; j++) { - coeff[j] = Mcons1.row(i)(j); + coeff2[j] = Mcons1.row(i)(j); } - cexpr2.addTerms(coeff, delta_k, n_ + m_ + k_); + cexpr2.addTerms(coeff2, delta_k, n_ + m_ + k_); model.addConstr(cexpr2 + c(i) >= 0); model.addConstr(cexpr2 + c(i) <= M * binary[i]); } diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 7e1376bed5..3f77e76bac 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -57,6 +57,10 @@ LCSFactorySystem::LCSFactorySystem( this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) .get_index(); +// lcs_inputs_input_port_ = +// this->DeclareVectorInputPort("u_lcs", BasicVector(n_u_)) +// .get_index(); + MatrixXd A = MatrixXd::Zero(n_x_, n_x_); MatrixXd B = MatrixXd::Zero(n_x_, n_u_); VectorXd d = VectorXd::Zero(n_x_); @@ -69,9 +73,6 @@ LCSFactorySystem::LCSFactorySystem( "lcs", LCS(A, B, D, d, E, F, H, c, N_, dt_), &LCSFactorySystem::OutputLCS) .get_index(); -// DeclareForcedDiscreteUpdateEvent(&LCSFactorySystem::UpdateLCS); - -// contact_jacobian_ = MatrixXd::Zero(n_lambda_, n_v_); lcs_contact_jacobian_port_ = this->DeclareAbstractOutputPort( "J_lcs", Eigen::MatrixXd(n_x_, n_lambda_), @@ -79,26 +80,25 @@ LCSFactorySystem::LCSFactorySystem( .get_index(); lcs_contact_points_port_ = this->DeclareAbstractOutputPort( - "p_contact", std::vector(), + "p_lcs", std::vector(), &LCSFactorySystem::OutputLCSContactPoints) .get_index(); } -//drake::systems::EventStatus LCSFactorySystem::UpdateLCS( -// const drake::systems::Context& context, -// drake::systems::DiscreteValues* discrete_state) const{ -// -//} - void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, LCS* output_lcs) const { const TimestampedVector* lcs_x = (TimestampedVector*)this->EvalVectorInput(context, lcs_state_input_port_); - +// const auto lcs_u = +// (BasicVector*)this->EvalVectorInput(context, +// lcs_inputs_input_port_); + DRAKE_DEMAND(lcs_x->get_data().size() == n_x_); +// DRAKE_DEMAND(lcs_u->get_value().size() == n_u_); VectorXd q_v_u = VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + plant_.num_actuators()); +// q_v_u << lcs_x->get_data(), lcs_u->get_value(); q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); @@ -131,6 +131,7 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Contextget_data(), VectorXd::Zero(n_u_); plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); @@ -160,6 +161,7 @@ void LCSFactorySystem::OutputLCSContactPoints(const drake::systems::Contextget_data(), VectorXd::Zero(n_u_); plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h index a78a800789..dd7f077880 100644 --- a/systems/controllers/c3/lcs_factory_system.h +++ b/systems/controllers/c3/lcs_factory_system.h @@ -28,6 +28,10 @@ class LCSFactorySystem : public drake::systems::LeafSystem { return this->get_input_port(lcs_state_input_port_); } +// const drake::systems::InputPort& get_input_port_lcs_input() const { +// return this->get_input_port(lcs_inputs_input_port_); +// } + const drake::systems::OutputPort& get_output_port_lcs() const { return this->get_output_port(lcs_port_); } @@ -52,7 +56,7 @@ class LCSFactorySystem : public drake::systems::LeafSystem { std::vector* contact_points) const; drake::systems::InputPortIndex lcs_state_input_port_; - drake::systems::OutputPortIndex actor_trajectory_port_; +// drake::systems::InputPortIndex lcs_inputs_input_port_; drake::systems::OutputPortIndex lcs_port_; drake::systems::OutputPortIndex lcs_contact_jacobian_port_; drake::systems::OutputPortIndex lcs_contact_points_port_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index e49089d7f0..a6822c637e 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -54,7 +54,6 @@ C3Controller::C3Controller( } n_u_ = plant_.num_actuators(); - u_prev_ = VectorXd::Zero(n_u_); int x_des_size = plant_.num_positions(ModelInstanceIndex(2)) + plant_.num_positions(ModelInstanceIndex(3)) + @@ -196,7 +195,6 @@ void C3Controller::OutputC3Solution( c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } - u_prev_ = z_sol[0].segment(n_x_ + n_lambda_, n_u_); } void C3Controller::OutputC3Intermediates( diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index f0db2cb263..58a02c52ba 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -92,7 +92,6 @@ class C3Controller : public drake::systems::LeafSystem { mutable std::unique_ptr c3_; mutable std::vector delta_; mutable std::vector w_; - mutable Eigen::VectorXd u_prev_; mutable double solve_time_; drake::systems::DiscreteStateIndex plan_start_time_index_; diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index 4ce7ed009f..e522c29d1a 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -1,10 +1,8 @@ #include "c3_output_systems.h" #include "common/eigen_utils.h" -#include "solvers/c3_output.h" - #include "dairlib/lcmt_force.hpp" - +#include "solvers/c3_output.h" namespace dairlib { namespace systems { @@ -25,9 +23,12 @@ C3OutputSender::C3OutputSender() { drake::Value{}) .get_index(); lcs_contact_jacobian_port_ = - this->DeclareAbstractInputPort("J_lcs", drake::Value()).get_index(); + this->DeclareAbstractInputPort("J_lcs", drake::Value()) + .get_index(); lcs_contact_points_port_ = - this->DeclareAbstractInputPort("p_lcs", drake::Value>()).get_index(); + this->DeclareAbstractInputPort("p_lcs", + drake::Value>()) + .get_index(); this->set_name("c3_output_sender"); lcm_c3_output_port_ = this->DeclareAbstractOutputPort( @@ -35,9 +36,14 @@ C3OutputSender::C3OutputSender() { &C3OutputSender::OutputC3Lcm) .get_index(); lcs_forces_output_port_ = this->DeclareAbstractOutputPort( - "lcmt_c3_force", dairlib::lcmt_c3_forces(), - &C3OutputSender::OutputC3Forces) - .get_index(); + "lcmt_c3_force", dairlib::lcmt_c3_forces(), + &C3OutputSender::OutputC3Forces) + .get_index(); +// lcs_inputs_output_port_ = +// this->DeclareVectorOutputPort("u_lcs", +// drake::systems::BasicVector(3), +// &C3OutputSender::OutputNextC3Input) +// .get_index(); } void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, @@ -52,7 +58,6 @@ void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, *output = c3_output.GenerateLcmObject(context.get_time()); } - void C3OutputSender::OutputC3Forces( const drake::systems::Context& context, dairlib::lcmt_c3_forces* output_traj) const { @@ -60,30 +65,45 @@ void C3OutputSender::OutputC3Forces( this->EvalInputValue(context, c3_solution_port_); const auto& J_c = this->EvalInputValue(context, lcs_contact_jacobian_port_); - const auto& contact_points = - this->EvalInputValue>(context, lcs_contact_points_port_); + const auto& contact_points = this->EvalInputValue>( + context, lcs_contact_points_port_); output_traj->num_forces = c3_solution->lambda_sol_.rows(); output_traj->forces.resize(output_traj->num_forces); int forces_per_contact = J_c->rows() / contact_points->size(); int contact_var_start; - for (int contact_index = 0; contact_index < contact_points->size(); ++contact_index){ + for (int contact_index = 0; contact_index < contact_points->size(); + ++contact_index) { contact_var_start = forces_per_contact * contact_index; - for (int i = 0; i < forces_per_contact; ++i){ + for (int i = 0; i < forces_per_contact; ++i) { auto force = lcmt_force(); force.contact_point[0] = contact_points->at(contact_index)[0]; force.contact_point[1] = contact_points->at(contact_index)[1]; force.contact_point[2] = contact_points->at(contact_index)[2]; // 6, 7, 8 are the indices for the x,y,z components of the tray - // TODO(yangwill): find a cleaner way to figure out the equivalent forces expressed in the world frame - force.contact_force[0] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(6); - force.contact_force[1] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(7); - force.contact_force[2] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(8); + // TODO(yangwill): find a cleaner way to figure out the equivalent forces + // expressed in the world frame + force.contact_force[0] = + c3_solution->lambda_sol_(contact_var_start + i, 0) * + J_c->row(contact_var_start + i)(6); + force.contact_force[1] = + c3_solution->lambda_sol_(contact_var_start + i, 0) * + J_c->row(contact_var_start + i)(7); + force.contact_force[2] = + c3_solution->lambda_sol_(contact_var_start + i, 0) * + J_c->row(contact_var_start + i)(8); output_traj->forces[contact_var_start + i] = force; } } output_traj->utime = context.get_time() * 1e6; } +// void C3OutputSender::OutputNextC3Input(const drake::systems::Context& +// context, +// drake::systems::BasicVector* u_next) const { +// const auto& c3_solution = +// this->EvalInputValue(context, c3_solution_port_); +// u_next->SetFromVector(c3_solution->u_sol_.col(0).cast()); +//} } // namespace systems } // namespace dairlib \ No newline at end of file diff --git a/systems/trajectory_optimization/c3_output_systems.h b/systems/trajectory_optimization/c3_output_systems.h index 6bce22c4e1..3a926a69d4 100644 --- a/systems/trajectory_optimization/c3_output_systems.h +++ b/systems/trajectory_optimization/c3_output_systems.h @@ -3,8 +3,8 @@ #include #include -#include "dairlib/lcmt_c3_output.hpp" #include "dairlib/lcmt_c3_forces.hpp" +#include "dairlib/lcmt_c3_output.hpp" #include "drake/systems/framework/leaf_system.h" #include "drake/systems/lcm/lcm_interface_system.h" @@ -26,11 +26,13 @@ class C3OutputSender : public drake::systems::LeafSystem { return this->get_input_port(c3_intermediates_port_); } - const drake::systems::InputPort& get_input_port_lcs_contact_jacobian() const { + const drake::systems::InputPort& get_input_port_lcs_contact_jacobian() + const { return this->get_input_port(lcs_contact_jacobian_port_); } - const drake::systems::InputPort& get_input_port_lcs_contact_points() const { + const drake::systems::InputPort& get_input_port_lcs_contact_points() + const { return this->get_input_port(lcs_contact_points_port_); } @@ -39,18 +41,24 @@ class C3OutputSender : public drake::systems::LeafSystem { } // LCS contact force, not actor input forces - const drake::systems::OutputPort& get_output_port_c3_force() - const { + const drake::systems::OutputPort& get_output_port_c3_force() const { return this->get_output_port(lcs_forces_output_port_); } +// // LCS actor input force +// const drake::systems::OutputPort& get_output_port_next_c3_input() const { +// return this->get_output_port(lcs_inputs_output_port_); +// } + private: void OutputC3Lcm(const drake::systems::Context& context, dairlib::lcmt_c3_output* output) const; - void OutputC3Forces( - const drake::systems::Context& context, - dairlib::lcmt_c3_forces* output_traj) const; + void OutputC3Forces(const drake::systems::Context& context, + dairlib::lcmt_c3_forces* output_traj) const; + + void OutputNextC3Input(const drake::systems::Context& context, + drake::systems::BasicVector* u_next) const; drake::systems::InputPortIndex c3_solution_port_; drake::systems::InputPortIndex c3_intermediates_port_; @@ -58,6 +66,7 @@ class C3OutputSender : public drake::systems::LeafSystem { drake::systems::InputPortIndex lcs_contact_points_port_; drake::systems::OutputPortIndex lcm_c3_output_port_; drake::systems::OutputPortIndex lcs_forces_output_port_; +// drake::systems::OutputPortIndex lcs_inputs_output_port_; }; } // namespace systems diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index ac8dffdb4d..34945d802b 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -368,6 +368,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( drake::systems::EventStatus LcmForceDrawer::DrawForces( const Context& context, DiscreteValues* discrete_state) const { + std::cout << context.get_time() << std::endl; if (this->EvalInputValue( context, force_trajectory_input_port_) ->utime < 1e-3) { @@ -408,8 +409,6 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( Vector3d{0, 0, height + arrowhead_height})); meshcat_->SetProperty(force_arrow_path, "visible", true); } else { - // meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", - // false); meshcat_->SetProperty(force_arrow_path, "visible", false); } } From ab9621353b728d69dff854e1d932072a530b6527 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Dec 2023 14:52:13 -0500 Subject: [PATCH 563/758] selectively adding and drawing forces --- solvers/c3.cc | 28 +++---- .../lcm_trajectory_systems.cc | 81 ++++++++++++------- .../lcm_trajectory_systems.h | 7 +- 3 files changed, 70 insertions(+), 46 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index e0395e0d5e..c2df37790f 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -108,15 +108,15 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, } } - MatrixXd LinEq(n_, 2 * n_ + k_ + m_); - LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); + MatrixXd LinEq(n_, 2 * n_ + m_ + k_); + LinEq.block(0, n_ + m_ + k_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); for (int i = 0; i < N_; i++) { LinEq.block(0, 0, n_, n_) = A_.at(i); - LinEq.block(0, n_, n_, k_) = B_.at(i); - LinEq.block(0, n_ + k_, n_, m_) = D_.at(i); + LinEq.block(0, n_, n_, m_) = D_.at(i); + LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); prog_.AddLinearEqualityConstraint( - LinEq, -d_.at(i), {x_.at(i), u_.at(i), lambda_.at(i), x_.at(i + 1)}); + LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}); } for (int i = 0; i < N_ + 1; i++) { prog_.AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * xdesired_.at(i), @@ -140,9 +140,7 @@ vector C3::Solve(const VectorXd& x0, vector& delta, for (int i = 0; i < N_; i++) { WD.at(i) = delta.at(i) - w.at(i); } - vector zfin = SolveQP(x0, Gv, WD); - std::cout << "lambda_sol " << z_sol_->at(0).segment(n_, m_) << std::endl; return zfin; } @@ -203,18 +201,18 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, for (int i = 0; i < N_ + 1; i++) { if (i < N_) { costs_.push_back(prog_.AddQuadraticCost( - G.at(i).block(0, 0, n_, n_) * 2, - -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), - x_.at(i))); + 2 * G.at(i).block(0, 0, n_, n_), + -2 * G.at(i).block(0, 0, n_, n_) * WD.at(i).segment(0, n_), x_.at(i), + 1)); costs_.push_back(prog_.AddQuadraticCost( - G.at(i).block(n_, n_, m_, m_) * 2, + 2 * G.at(i).block(n_, n_, m_, m_), -2 * G.at(i).block(n_, n_, m_, m_) * WD.at(i).segment(n_, m_), - lambda_.at(i))); + lambda_.at(i), 1)); costs_.push_back( - prog_.AddQuadraticCost(G.at(i).block(n_ + m_, n_ + m_, k_, k_) * 2, + prog_.AddQuadraticCost(2 * G.at(i).block(n_ + m_, n_ + m_, k_, k_), -2 * G.at(i).block(n_ + m_, n_ + m_, k_, k_) * WD.at(i).segment(n_ + m_, k_), - u_.at(i))); + u_.at(i), 1)); } } @@ -297,7 +295,7 @@ vector C3::SolveProjection(vector& G, omp_set_nested(1); } -#pragma omp parallel for num_threads(N_) +#pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { if (warm_start_) { deltaProj[i] = diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 34945d802b..d02eef77c3 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -279,23 +279,28 @@ LcmForceDrawer::LcmForceDrawer( meshcat_->SetProperty(force_path_, "visible", true, 0); + actor_last_update_time_index_ = this->DeclareDiscreteState(1); + forces_last_update_time_index_ = this->DeclareDiscreteState(1); // Add the geometry to meshcat. // Set radius 1.0 so that it can be scaled later by the force/moment norm in // the path transform. - const drake::geometry::Cylinder cylinder(radius_, 1.0); - const double arrowhead_height = radius_ * 2.0; - const double arrowhead_width = radius_ * 2.0; - const drake::geometry::MeshcatCone arrowhead( - arrowhead_height, arrowhead_width, arrowhead_width); - - meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder, {0, 0, 1, 1}); - meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead, {0, 0, 1, 1}); - for (int i = 0; i < 20; ++i) { - const std::string lcs_force_path = force_path_ + "/lcs_force_" + - std::to_string(i) + "/arrow"; - meshcat_->SetObject(lcs_force_path + "/cylinder", cylinder, {1, 0, 0, 1}); - meshcat_->SetObject(lcs_force_path + "/head", arrowhead, {1, 0, 0, 1}); - } + // const drake::geometry::Cylinder cylinder(radius_, 1.0); + // const double arrowhead_height = radius_ * 2.0; + // const double arrowhead_width = radius_ * 2.0; + // const drake::geometry::MeshcatCone arrowhead( + // arrowhead_height, arrowhead_width, arrowhead_width); + + meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, + {0, 0, 1, 1}); + meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, + {0, 0, 1, 1}); + // for (int i = 0; i < 18; ++i) { + // const std::string lcs_force_path = force_path_ + "/lcs_force_" + + // std::to_string(i) + "/arrow"; + // meshcat_->SetObject(lcs_force_path + "/cylinder", cylinder, {1, 0, 0, + // 1}); meshcat_->SetObject(lcs_force_path + "/head", arrowhead, {1, 0, 0, + // 1}); + // } DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); @@ -309,6 +314,12 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } + if (discrete_state->get_value(actor_last_update_time_index_)[0] >= + context.get_time()) { + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(actor_last_update_time_index_)[0] = + context.get_time(); const auto& lcmt_traj = this->EvalInputValue( context, actor_trajectory_input_port_); @@ -333,8 +344,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( } auto force = force_trajectory.value(force_trajectory_block.time_vector[0]); - const std::string& force_path_root = - force_path_ + "/u_lcs/"; + const std::string& force_path_root = force_path_ + "/u_lcs/"; meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); const std::string& force_arrow_path = force_path_root + "arrow"; @@ -344,7 +354,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( meshcat_->SetTransform( force_arrow_path, RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); - const double height = force_norm / newtons_per_meter_; + const double height = force_norm / newtons_per_meter_ / 10; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); // Note: Meshcat does not fully support non-uniform scaling (see #18095). @@ -368,31 +378,42 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( drake::systems::EventStatus LcmForceDrawer::DrawForces( const Context& context, DiscreteValues* discrete_state) const { - std::cout << context.get_time() << std::endl; if (this->EvalInputValue( context, force_trajectory_input_port_) ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } + if (discrete_state->get_value(forces_last_update_time_index_)[0] >= + context.get_time()) { + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(forces_last_update_time_index_)[0] = + context.get_time(); + const auto& c3_forces = this->EvalInputValue( context, force_trajectory_input_port_); for (int i = 0; i < c3_forces->num_forces; ++i) { - - const VectorXd pose = Eigen::Map( - c3_forces->forces[i].contact_point, 3); - - const std::string& force_path_root = - force_path_ + "/lcs_force_" + std::to_string(i) + "/"; - meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); const VectorXd force = Eigen::Map( c3_forces->forces[i].contact_force, 3); auto force_norm = force.norm(); - // Stretch the cylinder in z. - const std::string& force_arrow_path = force_path_root + "arrow"; + const std::string& force_path_root = + force_path_ + "/lcs_force_" + std::to_string(i) + "/"; if (force_norm >= 0.01) { + if (!meshcat_->HasPath(force_path_root)) { + meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, + {1, 0, 0, 1}); + meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, {1, 0, 0, 1}); + } + + const VectorXd pose = Eigen::Map( + c3_forces->forces[i].contact_point, 3); + + meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + // Stretch the cylinder in z. + const std::string& force_arrow_path = force_path_root + "arrow"; meshcat_->SetTransform( force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 0))); const double height = force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); @@ -407,9 +428,9 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( force_arrow_path + "/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_arrow_path, "visible", true); + meshcat_->SetProperty(force_path_root, "visible", true); } else { - meshcat_->SetProperty(force_arrow_path, "visible", false); + meshcat_->SetProperty(force_path_root, "visible", false); } } return drake::systems::EventStatus::Succeeded(); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index fc0a88e326..b2575bbd77 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -161,7 +161,12 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::systems::InputPortIndex actor_trajectory_input_port_; drake::systems::InputPortIndex force_trajectory_input_port_; + + drake::systems::DiscreteStateIndex actor_last_update_time_index_; + drake::systems::DiscreteStateIndex forces_last_update_time_index_; std::shared_ptr meshcat_; + const drake::geometry::Cylinder cylinder_ = drake::geometry::Cylinder(0.002, 1.0); + const drake::geometry::MeshcatCone arrowhead_ = drake::geometry::MeshcatCone(0.004, 0.004, 0.004); const std::string force_path_ = "c3_forces"; const std::string actor_trajectory_name_; const std::string force_trajectory_name_; @@ -169,7 +174,7 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); int N_ = 5; const double radius_ = 0.002; - const double newtons_per_meter_ = 40; + const double newtons_per_meter_ = 10; }; } // namespace systems From 6acd51dcb5923bd83208c9bfe03980c0bed19ddc Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Dec 2023 15:48:52 -0500 Subject: [PATCH 564/758] still investigating contact model --- examples/Cassie/osc_run/osc_running_qp_settings.yaml | 2 +- examples/franka/franka_c3_controller.cc | 1 + .../franka/parameters/franka_c3_controller_params.yaml | 4 ++-- examples/franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/left_support_point_contact.urdf | 6 +++--- solvers/c3.cc | 1 + systems/trajectory_optimization/c3_output_systems.cc | 10 +++++----- systems/trajectory_optimization/c3_output_systems.h | 2 +- .../trajectory_optimization/lcm_trajectory_systems.cc | 4 ++-- 9 files changed, 17 insertions(+), 15 deletions(-) diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index c4b2641c43..8ab02da43d 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 500 + max_iter: 2000 linsys_solver: 0 verbose: 0 warm_start: 1 diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 54da088571..6d4693fde1 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -108,6 +108,7 @@ int DoMain(int argc, char* argv[]) { auto [plant_for_lcs, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); Parser parser_plate(&plant_for_lcs); + parser_plate.SetAutoRenaming(true); parser_plate.AddModels(controller_params.plate_model); parser_plate.AddModels(controller_params.tray_model); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 4d4607629c..8c83795893 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -14,8 +14,8 @@ tray_model: examples/franka/urdf/tray.sdf scene_index: 1 -left_support_model: examples/franka/urdf/left_support.urdf -right_support_model: examples/franka/urdf/right_support.urdf +left_support_model: examples/franka/urdf/left_support_point_contact.urdf +right_support_model: examples/franka/urdf/left_support_point_contact.urdf left_support_position: [0.55, 0.15, 0.225] right_support_position: [0.8, -0.15, 0.225] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 17225b4a4b..2fa59111a2 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -20,7 +20,7 @@ left_support_position: [0.65, 0.15, 0.225] right_support_position: [0.65, -0.15, 0.225] dt: 0.0005 -realtime_rate: 0.5 +realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index cbc9cfb74d..a2fad0a4c6 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,13 +13,13 @@ izz="0.013"/> - + - + @@ -27,7 +27,7 @@ - + diff --git a/solvers/c3.cc b/solvers/c3.cc index c2df37790f..6b85786484 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -117,6 +117,7 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, prog_.AddLinearEqualityConstraint( LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}); +// prog_.AddLinearConstraint(lambda_.at(i) >= VectorXd::Zero(m_)); } for (int i = 0; i < N_ + 1; i++) { prog_.AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * xdesired_.at(i), diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index e522c29d1a..bf5689c3ee 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -60,15 +60,15 @@ void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, void C3OutputSender::OutputC3Forces( const drake::systems::Context& context, - dairlib::lcmt_c3_forces* output_traj) const { + dairlib::lcmt_c3_forces* c3_forces_output) const { const auto& c3_solution = this->EvalInputValue(context, c3_solution_port_); const auto& J_c = this->EvalInputValue(context, lcs_contact_jacobian_port_); const auto& contact_points = this->EvalInputValue>( context, lcs_contact_points_port_); - output_traj->num_forces = c3_solution->lambda_sol_.rows(); - output_traj->forces.resize(output_traj->num_forces); + c3_forces_output->num_forces = c3_solution->lambda_sol_.rows(); + c3_forces_output->forces.resize(c3_forces_output->num_forces); int forces_per_contact = J_c->rows() / contact_points->size(); int contact_var_start; for (int contact_index = 0; contact_index < contact_points->size(); @@ -91,10 +91,10 @@ void C3OutputSender::OutputC3Forces( force.contact_force[2] = c3_solution->lambda_sol_(contact_var_start + i, 0) * J_c->row(contact_var_start + i)(8); - output_traj->forces[contact_var_start + i] = force; + c3_forces_output->forces[contact_var_start + i] = force; } } - output_traj->utime = context.get_time() * 1e6; + c3_forces_output->utime = context.get_time() * 1e6; } // void C3OutputSender::OutputNextC3Input(const drake::systems::Context& diff --git a/systems/trajectory_optimization/c3_output_systems.h b/systems/trajectory_optimization/c3_output_systems.h index 3a926a69d4..904db68736 100644 --- a/systems/trajectory_optimization/c3_output_systems.h +++ b/systems/trajectory_optimization/c3_output_systems.h @@ -55,7 +55,7 @@ class C3OutputSender : public drake::systems::LeafSystem { dairlib::lcmt_c3_output* output) const; void OutputC3Forces(const drake::systems::Context& context, - dairlib::lcmt_c3_forces* output_traj) const; + dairlib::lcmt_c3_forces* c3_forces_output) const; void OutputNextC3Input(const drake::systems::Context& context, drake::systems::BasicVector* u_next) const; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index d02eef77c3..c89e0a3653 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -399,7 +399,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( const std::string& force_path_root = force_path_ + "/lcs_force_" + std::to_string(i) + "/"; if (force_norm >= 0.01) { - if (!meshcat_->HasPath(force_path_root)) { + if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, {1, 0, 0, 1}); meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, {1, 0, 0, 1}); @@ -413,7 +413,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( const std::string& force_arrow_path = force_path_root + "arrow"; meshcat_->SetTransform( force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 0))); + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); const double height = force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); From 495fcfa38e2cb604850a269d4a3c92c6d54f1e56 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Dec 2023 16:11:35 -0500 Subject: [PATCH 565/758] fixing big bug in my lcs factory --- solvers/lcs_factory.cc | 41 ++++++++++++++++++++--------------------- 1 file changed, 20 insertions(+), 21 deletions(-) diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index ed07ac3653..dfb0be14fe 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -140,19 +140,19 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd::Ones(1, 2 * num_friction_directions); } - int n_contact_vars = 0; + int n_lambda = 0; if (contact_model == ContactModel::kStewartAndTrinkle) { - n_contact_vars = 2 * n_contacts + 2 * n_contacts * num_friction_directions; + n_lambda = 2 * n_contacts + 2 * n_contacts * num_friction_directions; } else { - n_contact_vars = 2 * n_contacts * num_friction_directions; + n_lambda = 2 * n_contacts * num_friction_directions; } // Matrices with contact variables - MatrixXd D = MatrixXd::Zero(n_x, n_contact_vars); - MatrixXd E = MatrixXd::Zero(n_contact_vars, n_x); - MatrixXd F = MatrixXd::Zero(n_contact_vars, n_contact_vars); - MatrixXd H = MatrixXd::Zero(n_contact_vars, n_u); - VectorXd c = VectorXd::Zero(n_contact_vars); + MatrixXd D = MatrixXd::Zero(n_x, n_lambda); + MatrixXd E = MatrixXd::Zero(n_lambda, n_x); + MatrixXd F = MatrixXd::Zero(n_lambda, n_lambda); + MatrixXd H = MatrixXd::Zero(n_lambda, n_u); + VectorXd c = VectorXd::Zero(n_lambda); if (contact_model == ContactModel::kStewartAndTrinkle) { D.block(0, 2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions) = @@ -163,7 +163,7 @@ std::pair LCSFactory::LinearizePlantToLCS( D.block(0, n_contacts, n_q, n_contacts) = dt * dt * qdotNv * MinvJ_n_T; D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; - + std::cout << "D: " << D << std::endl; E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q + J_n * vNqdot; E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = @@ -210,7 +210,7 @@ std::pair LCSFactory::LinearizePlantToLCS( } else if (contact_model == ContactModel::kAnitescu) { VectorXd mu_vec = Eigen::Map( mu.data(), mu.size()); - VectorXd anitescu_mu_vec = VectorXd::Zero(n_contact_vars); + VectorXd anitescu_mu_vec = VectorXd::Zero(n_lambda); for (int i = 0; i < mu_vec.rows(); i++) { double cur = mu_vec(i); anitescu_mu_vec(4 * i) = cur; @@ -223,11 +223,12 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); - D.block(0, 0, n_q, n_contacts) = dt * qdotNv * MinvJ_c_T; - D.block(n_q, 0, n_v, n_contacts) = MinvJ_c_T; - E.block(0, 0, n_contacts, n_q) = + D.block(0, 0, n_q, n_lambda) = dt * qdotNv * MinvJ_c_T; + D.block(n_q, 0, n_v, n_lambda) = MinvJ_c_T; + + E.block(0, 0, n_lambda, n_q) = dt * J_c * AB_v_q + E_t.transpose() * J_n * vNqdot / dt; - E.block(0, n_q, n_contacts, n_v) = J_c + dt * J_c * AB_v_v; + E.block(0, n_q, n_lambda, n_v) = J_c + dt * J_c * AB_v_v; F = J_c * MinvJ_c_T; @@ -251,7 +252,8 @@ std::pair LCSFactory::LinearizePlantToLCS( return ret; } -std::pair> LCSFactory::ComputeContactJacobian( +std::pair> +LCSFactory::ComputeContactJacobian( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, @@ -260,15 +262,9 @@ std::pair> LCSFactory::ComputeContactJaco contact_geoms, int num_friction_directions, const std::vector& mu, double dt, int N, dairlib::solvers::ContactModel contact_model) { -// int n_x = plant_ad.num_positions() + plant_ad.num_velocities(); - int n_u = plant_ad.num_actuators(); - int n_contacts = contact_geoms.size(); - DRAKE_DEMAND(plant_ad.num_velocities() == plant.num_velocities()); - DRAKE_DEMAND(plant_ad.num_positions() == plant.num_positions()); int n_v = plant.num_velocities(); - int n_q = plant.num_positions(); VectorXd phi(n_contacts); MatrixXd J_n(n_contacts, n_v); @@ -317,6 +313,9 @@ std::pair> LCSFactory::ComputeContactJaco MatrixXd anitescu_mu_matrix = anitescu_mu_vec.asDiagonal(); MatrixXd J_c = E_t.transpose() * J_n + anitescu_mu_matrix * J_t; return std::make_pair(J_c, contact_points); + } else { + std::cerr << ("Unknown projection type") << std::endl; + DRAKE_THROW_UNLESS(false); } } From 168a7dc39729ec6b710e65aadac368b406e424ec Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 12 Dec 2023 16:43:35 -0500 Subject: [PATCH 566/758] still needs tuning, solution looks much better --- .../franka_c3_controller_params.yaml | 4 +-- .../franka_c3_options_w_supports.yaml | 28 +++++++++---------- .../franka_osc_controller_params.yaml | 6 ++-- .../franka/parameters/franka_sim_params.yaml | 2 +- .../urdf/left_support_point_contact.urdf | 4 +-- systems/controllers/c3_controller.cc | 27 ++++++++++-------- 6 files changed, 37 insertions(+), 34 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 8c83795893..97412976c8 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -16,8 +16,8 @@ scene_index: 1 left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.55, 0.15, 0.225] -right_support_position: [0.8, -0.15, 0.225] +left_support_position: [0.65, 0.15, 0.225] +right_support_position: [0.65, -0.15, 0.225] include_end_effector_orientation: false diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index f2308dfea5..941929a084 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,4 +1,4 @@ -admm_iter: 4 +admm_iter: 6 rho: 0.1 rho_scale: 2 num_threads: 7 @@ -10,16 +10,16 @@ projection_type: 'QP' contact_model: 'anitescu' warm_start: false -mu: [0.4, 0.4, 0.4, 0.01, 0.01] +mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05, 0.05] dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 -num_contacts: 5 +num_contacts: 7 N: 7 # matrix scaling w_Q: 50 -w_R: 0.01 +w_R: 0.1 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar @@ -31,17 +31,17 @@ q_vector: [175, 175, 125, 1, 1, 1, 1, 15000, 15000, 15000, # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 1] -# Penalty on all decision variables -g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_gamma: [1, 1, 1, 1, 1] -g_lambda_n: [1, 1, 1, 1, 1] -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] +# Penalty on matching projected variables +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [1, 1, 1, 1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] g_u: [1, 1, 1] u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1] -u_gamma: [1, 1, 1, 1, 1] -u_lambda_n: [1, 1, 1, 1, 1] -u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] +u_gamma: [1, 1, 1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] u_u: [10, 10, 10] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index e7f2a107a1..1d1f5bbf10 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] + [0.1, 0, 0, + 0, 0.1, 0, + 0, 0, 0.1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 2fa59111a2..066bab1a94 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -20,7 +20,7 @@ left_support_position: [0.65, 0.15, 0.225] right_support_position: [0.65, -0.15, 0.225] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.1 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index a2fad0a4c6..65da54dc3a 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,13 +13,13 @@ izz="0.013"/> - + - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index a6822c637e..2835b5234a 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -28,8 +28,7 @@ namespace systems { C3Controller::C3Controller( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, - C3Options c3_options) + drake::systems::Context* context, C3Options c3_options) : plant_(plant), context_(context), c3_options_(std::move(c3_options)), @@ -60,9 +59,8 @@ C3Controller::C3Controller( plant_.num_velocities(ModelInstanceIndex(2)) + plant_.num_velocities(ModelInstanceIndex(3)); lcs_state_input_port_ = - this->DeclareVectorInputPort( - "x_lcs", TimestampedVector( - x_des_size)) + this->DeclareVectorInputPort("x_lcs", + TimestampedVector(x_des_size)) .get_index(); MatrixXd A = MatrixXd::Zero(n_x_, n_x_); @@ -111,18 +109,17 @@ drake::systems::EventStatus C3Controller::ComputePlan( const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const TimestampedVector* lcs_x = - (TimestampedVector*)this->EvalVectorInput( - context, lcs_state_input_port_); - auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + auto& lcs = + this->EvalAbstractInput(context, lcs_input_port_)->get_value(); discrete_state->get_mutable_value(plan_start_time_index_)[0] = lcs_x->get_timestamp(); - std::vector x_desired = std::vector(N_ + 1, x_des.value()); - DRAKE_DEMAND(Q_.front().rows() == lcs.n_); DRAKE_DEMAND(Q_.front().cols() == lcs.n_); DRAKE_DEMAND(R_.front().rows() == lcs.k_); @@ -190,8 +187,14 @@ void C3Controller::OutputC3Solution( for (int i = 0; i < N_; i++) { c3_solution->time_vector_(i) = t + i * c3_options_.dt; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); - c3_solution->lambda_sol_.col(i) = - z_sol[i].segment(n_x_, n_lambda_).cast(); + if (c3_options_.contact_model == "anitescu") { + c3_solution->lambda_sol_.col(i) = + c3_options_.dt * z_sol[i].segment(n_x_, n_lambda_).cast(); + } else { + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + } + c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } From 8f50387c4b06c96cb7bca5c0c492d96c64cf8bff Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 13 Dec 2023 10:00:39 -0500 Subject: [PATCH 567/758] changing parameters for c3 --- .../osc_run/osc_running_qp_settings.yaml | 4 +-- examples/franka/franka_osc_controller.cc | 2 +- .../franka_c3_controller_params.yaml | 2 +- .../parameters/franka_c3_qp_settings.yaml | 27 +++++++++++++++++++ .../parameters/franka_osc_qp_settings.yaml | 27 +++++++++++++++++++ .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/left_support.urdf | 3 +++ examples/franka/urdf/tray.sdf | 2 +- .../osc/rot_space_tracking_data.cc | 4 ++- 9 files changed, 66 insertions(+), 7 deletions(-) create mode 100644 examples/franka/parameters/franka_c3_qp_settings.yaml create mode 100644 examples/franka/parameters/franka_osc_qp_settings.yaml diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 8ab02da43d..5cf72f59b4 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 2000 + max_iter: 250 linsys_solver: 0 verbose: 0 warm_start: 1 @@ -12,7 +12,7 @@ int_options: scaled_termination: 1 check_termination: 25 double_options: - rho: 0.01 + rho: 0.001 sigma: 1e-6 eps_abs: 1e-5 eps_rel: 1e-5 diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 14fbba3d84..d1b0f7ec14 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -54,7 +54,7 @@ using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; DEFINE_string(osqp_settings, - "examples/Cassie/osc_run/osc_running_qp_settings.yaml", + "examples/franka/parameters/franka_osc_qp_settings.yaml", "Filepath containing qp settings"); DEFINE_string(controller_parameters, "examples/franka/parameters/franka_osc_controller_params.yaml", diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 97412976c8..bd5b4117c5 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,7 +1,7 @@ c3_options_file: [examples/franka/parameters/franka_c3_options_translation.yaml, examples/franka/parameters/franka_c3_options_w_supports.yaml] -osqp_settings_file: examples/Cassie/osc_run/osc_running_qp_settings.yaml +osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf diff --git a/examples/franka/parameters/franka_c3_qp_settings.yaml b/examples/franka/parameters/franka_c3_qp_settings.yaml new file mode 100644 index 0000000000..64903da49b --- /dev/null +++ b/examples/franka/parameters/franka_c3_qp_settings.yaml @@ -0,0 +1,27 @@ +print_to_console: 0 +log_file_name: "" +int_options: + max_iter: 5000 + linsys_solver: 0 + verbose: 0 + warm_start: 1 + scaling: 1 + adaptive_rho: 1 + polish: 1 + polish_refine_iter: 1 + scaled_termination: 1 + check_termination: 200 +double_options: + rho: 0.001 + sigma: 1e-6 + eps_abs: 1e-5 + eps_rel: 1e-5 + eps_prim_inf: 1e-5 + eps_dual_inf: 1e-5 + alpha: 1.6 + delta: 1e-6 + adaptive_rho_interval: 0 + adaptive_rho_tolerance: 5 + adaptive_rho_fraction: 0.4 + time_limit: 0 +string_options: {} \ No newline at end of file diff --git a/examples/franka/parameters/franka_osc_qp_settings.yaml b/examples/franka/parameters/franka_osc_qp_settings.yaml new file mode 100644 index 0000000000..639eca37a0 --- /dev/null +++ b/examples/franka/parameters/franka_osc_qp_settings.yaml @@ -0,0 +1,27 @@ +print_to_console: 0 +log_file_name: "" +int_options: + max_iter: 1000 + linsys_solver: 0 + verbose: 0 + warm_start: 1 + scaling: 1 + adaptive_rho: 1 + polish: 1 + polish_refine_iter: 1 + scaled_termination: 1 + check_termination: 25 +double_options: + rho: 0.001 + sigma: 1e-6 + eps_abs: 1e-5 + eps_rel: 1e-5 + eps_prim_inf: 1e-5 + eps_dual_inf: 1e-5 + alpha: 1.6 + delta: 1e-6 + adaptive_rho_interval: 0 + adaptive_rho_tolerance: 5 + adaptive_rho_fraction: 0.4 + time_limit: 0 +string_options: {} \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 066bab1a94..2fa59111a2 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -20,7 +20,7 @@ left_support_position: [0.65, 0.15, 0.225] right_support_position: [0.65, -0.15, 0.225] dt: 0.0005 -realtime_rate: 0.1 +realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index 2f8c5f4c5a..97502a0cd2 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -29,6 +29,9 @@ + + + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index f908a0b5ae..4ddd39833e 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -25,7 +25,7 @@ - 0.1 0.1 0.1 1 + 0.1 0.1 0.1 0.8 diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index 60e0174287..b10b18be5b 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -84,7 +84,9 @@ void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { Quaterniond y_quat_des(y_des_(0), y_des_(1), y_des_(2), y_des_(3)); Quaterniond dy_quat_des(ydot_des_(0), ydot_des_(1), ydot_des_(2), ydot_des_(3)); - Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); +// Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); + DRAKE_DEMAND(ydot_des_.size() == 3); + Vector3d w_des_ = ydot_des_; // Because we transform the error here rather than in the parent // options_tracking_data, and because J_y is already transformed in the view // frame, we need to undo the transformation on J_y From e5f4f11aaa222de19577d85a3152bfa1b3572187 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 13 Dec 2023 14:03:58 -0500 Subject: [PATCH 568/758] fixing cassie stuff with rot space changes --- examples/Cassie/osc/heading_traj_generator.cc | 38 ++++--------------- .../osc/standing_pelvis_orientation_traj.cc | 13 ++++--- .../osc/operational_space_control.cc | 7 ++-- 3 files changed, 20 insertions(+), 38 deletions(-) diff --git a/examples/Cassie/osc/heading_traj_generator.cc b/examples/Cassie/osc/heading_traj_generator.cc index 30bd5af970..cb0be9afd1 100644 --- a/examples/Cassie/osc/heading_traj_generator.cc +++ b/examples/Cassie/osc/heading_traj_generator.cc @@ -3,6 +3,7 @@ #include #include +#include #include "multibody/multibody_utils.h" @@ -21,6 +22,7 @@ using drake::systems::Context; using drake::systems::LeafSystem; using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::PiecewiseQuaternionSlerp; namespace dairlib { namespace cassie { @@ -43,8 +45,8 @@ HeadingTrajGenerator::HeadingTrajGenerator( this->DeclareVectorInputPort("pelvis_yaw", BasicVector(1)) .get_index(); // Provide an instance to allocate the memory first (for the output) - PiecewisePolynomial pp(VectorXd(0)); - drake::trajectories::Trajectory& traj_inst = pp; + PiecewiseQuaternionSlerp empty_slerp_traj; + drake::trajectories::Trajectory& traj_inst = empty_slerp_traj; this->DeclareAbstractOutputPort("pelvis_quat", traj_inst, &HeadingTrajGenerator::CalcHeadingTraj); } @@ -64,33 +66,13 @@ void HeadingTrajGenerator::CalcHeadingTraj( multibody::SetPositionsIfNew(plant_, q, context_); - // Get approximated heading angle of pelvis - Vector3d pelvis_heading_vec = - plant_.EvalBodyPoseInWorld(*context_, pelvis_).rotation().col(0); - double approx_pelvis_yaw_i = - atan2(pelvis_heading_vec(1), pelvis_heading_vec(0)); - - // Get quaternion from body rotation matrix instead of state directly, becasue - // this is how osc tracking data get the quaternion. Quaterniond quat( plant_.EvalBodyPoseInWorld(*context_, pelvis_).rotation().matrix()); quat.normalize(); - // Construct the PiecewisePolynomial. - /// Given yaw position p_i and velocity v_i, we want to generate affine - /// functions, p_i + v_i*t, for the desired trajectory. We use - /// FirstOrderHold() to approximately generate the function, so we need to - /// have the endpoint of the trajectory. We generate the endpoint by - /// looking ahead what the position is in dt second with fixed velocity v_i. - /// Note that we construct trajectories in R^4 (quaternion space), so we need - /// to transform the yaw trajectory into quaternion representation. - /// The value of dt changes the trajectory time horizon. As long as it's - /// larger than the recompute time, the value doesn't affect the control - /// outcome. + double dt = 0.1; double des_delta_yaw = des_yaw_vel(0) * dt; - // We set pitch and roll = 0, because we also use this traj for balance in - // some controller Eigen::Vector4d pelvis_rotation_i; pelvis_rotation_i << quat.w(), 0, 0, quat.z(); pelvis_rotation_i.normalize(); @@ -100,19 +82,15 @@ void HeadingTrajGenerator::CalcHeadingTraj( Quaterniond relative_quat(cos(des_delta_yaw / 2), 0, 0, sin(des_delta_yaw / 2)); Quaterniond final_quat = relative_quat * init_quat; - Eigen::Vector4d pelvis_rotation_f; - pelvis_rotation_f << final_quat.w(), final_quat.vec(); const std::vector breaks = {context.get_time(), context.get_time() + dt}; - std::vector knots(breaks.size(), MatrixXd::Zero(4, 1)); - knots[0] = pelvis_rotation_i; - knots[1] = pelvis_rotation_f; - const auto pp = PiecewisePolynomial::FirstOrderHold(breaks, knots); + const auto pp = drake::trajectories::PiecewiseQuaternionSlerp( + breaks, {quat, final_quat}); // Assign traj auto* pp_traj = - (PiecewisePolynomial*)dynamic_cast*>( + (PiecewiseQuaternionSlerp*)dynamic_cast*>( traj); *pp_traj = pp; } diff --git a/examples/Cassie/osc/standing_pelvis_orientation_traj.cc b/examples/Cassie/osc/standing_pelvis_orientation_traj.cc index a9004e3308..77cf8fc498 100644 --- a/examples/Cassie/osc/standing_pelvis_orientation_traj.cc +++ b/examples/Cassie/osc/standing_pelvis_orientation_traj.cc @@ -3,12 +3,14 @@ #include #include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/common/trajectories/piecewise_quaternion.h" #include "drake/common/trajectories/trajectory.h" #include "drake/math/wrap_to.h" using dairlib::systems::OutputVector; using drake::systems::BasicVector; using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::PiecewiseQuaternionSlerp; using drake::trajectories::Trajectory; using Eigen::MatrixXd; using Eigen::Vector3d; @@ -40,8 +42,8 @@ StandingPelvisOrientationTraj::StandingPelvisOrientationTraj( radio_port_ = this->DeclareAbstractInputPort( "radio_out", drake::Value{}) .get_index(); - PiecewisePolynomial empty_pp_traj(Eigen::VectorXd(0)); - Trajectory& traj_inst = empty_pp_traj; + PiecewiseQuaternionSlerp empty_slerp_traj; + Trajectory& traj_inst = empty_slerp_traj; this->set_name(traj_name); this->DeclareAbstractOutputPort(traj_name, traj_inst, &StandingPelvisOrientationTraj::CalcTraj); @@ -58,7 +60,7 @@ void StandingPelvisOrientationTraj::CalcTraj( VectorXd q = robot_output->GetPositions(); plant_.SetPositions(context_, q); auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( + (PiecewiseQuaternionSlerp*)dynamic_cast*>( traj); Vector3d pt_0; Vector3d pt_1; @@ -87,8 +89,9 @@ void StandingPelvisOrientationTraj::CalcTraj( target_orientation_filter_->Update(rpy); auto rot_mat = drake::math::RotationMatrix(drake::math::RollPitchYaw( static_cast(target_orientation_filter_->Value()))); - - *casted_traj = PiecewisePolynomial(rot_mat.ToQuaternionAsVector4()); + const std::vector breaks = {0, 1}; + *casted_traj = drake::trajectories::PiecewiseQuaternionSlerp( + breaks, {rot_mat.ToQuaternion(), rot_mat.ToQuaternion()}); } } // namespace dairlib::cassie::osc diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 24b59a6bdf..6fbbfbd735 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1086,9 +1086,10 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); - // qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); - qp_output.lambda_h_sol = CopyVectorXdToStdVector(force_tracking_data_vec_->at(0)->GetLambdaDes()); + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); + qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); +// qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); +// qp_output.lambda_h_sol = CopyVectorXdToStdVector(force_tracking_data_vec_->at(0)->GetLambdaDes()); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; From f8d2371956583d8053e6012e3407163be83388c4 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 13 Dec 2023 17:24:49 -0500 Subject: [PATCH 569/758] need to spend some time tuning c3 parameters, bugs seem mostly fixed, check impulse/force --- .../franka_c3_controller_params.yaml | 2 +- .../franka_c3_options_translation.yaml | 18 +++++----- .../franka_c3_options_w_supports.yaml | 20 +++++------ .../parameters/franka_c3_qp_settings.yaml | 4 +-- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/plate_end_effector.urdf | 4 +-- solvers/c3.cc | 2 +- solvers/c3_miqp.cc | 11 ++++-- solvers/c3_options.h | 35 ++++++++++--------- solvers/lcs_factory.cc | 7 ++-- systems/controllers/c3_controller.cc | 17 +++++---- .../osc/operational_space_control.cc | 16 +++++---- 12 files changed, 73 insertions(+), 65 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index bd5b4117c5..b5f08739d1 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -22,7 +22,7 @@ right_support_position: [0.65, -0.15, 0.225] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan -target_frequency: 50 +target_frequency: 0 #unused neutral_position: [0.55, 0, 0.45] x_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 607783dd51..2836a945fb 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -4,10 +4,10 @@ rho_scale: 1 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'MIQP' +projection_type: 'QP' # options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'anitescu' -contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' +#contact_model: 'stewart_and_trinkle' warm_start: true mu: [0.2, 0.2, 0.2] @@ -26,26 +26,24 @@ w_G: 1 w_U: 0.5 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 0, 0, 0, 0, 15000, 15000, 15000, +q_vector: [175, 175, 175, 10, 10, 10, 10, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 1] # Penalty on all decision variables -g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1] g_lambda_n: [1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [.05, .05, .05, .05, .05, .05, .05, .05, .05, .05, .05, .05] g_u: [1, 1, 1] # Penalty on all decision variables -#u_vector: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10, -# 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 10, 10, 10] -u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 10, 10, 10] +u_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 1, 1, 1, 10, 10, 10, 10, 10, 10] u_gamma: [1, 1, 1] u_lambda_n: [1, 1, 1] u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_lambda: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_lambda: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05] u_u: [10, 10, 10] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 941929a084..9599419ae0 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,7 +1,7 @@ -admm_iter: 6 +admm_iter: 3 rho: 0.1 rho_scale: 2 -num_threads: 7 +num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' projection_type: 'QP' @@ -15,7 +15,7 @@ dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 -N: 7 +N: 5 # matrix scaling w_Q: 50 @@ -26,22 +26,22 @@ w_G: 1 w_U: 0.5 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 125, 1, 1, 1, 1, 15000, 15000, 15000, +q_vector: [175, 175, 125, 1000, 1000, 1000, 1000, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 1] # Penalty on matching projected variables -g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_x: [1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] -g_u: [1, 1, 1] +g_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_u: [5, 5, 10] -u_x: [1, 1, 1, 100, 100, 100, 100, 100, 100, 100, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1] +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001] -u_u: [10, 10, 10] +u_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_u: [5, 5, 5] diff --git a/examples/franka/parameters/franka_c3_qp_settings.yaml b/examples/franka/parameters/franka_c3_qp_settings.yaml index 64903da49b..8dc5e369ea 100644 --- a/examples/franka/parameters/franka_c3_qp_settings.yaml +++ b/examples/franka/parameters/franka_c3_qp_settings.yaml @@ -1,7 +1,7 @@ print_to_console: 0 log_file_name: "" int_options: - max_iter: 5000 + max_iter: 1000 linsys_solver: 0 verbose: 0 warm_start: 1 @@ -10,7 +10,7 @@ int_options: polish: 1 polish_refine_iter: 1 scaled_termination: 1 - check_termination: 200 + check_termination: 100 double_options: rho: 0.001 sigma: 1e-6 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 2fa59111a2..7ee6f51728 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,7 +12,7 @@ tray_publish_rate: 1000 actuator_delay: 0.000 scene_index: 1 -visualize: true +visualize: false publish_efforts: true tool_attachment_frame: [0, 0, 0.107] diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 564e616c2e..37a37f570a 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,8 +15,8 @@ - - + + diff --git a/solvers/c3.cc b/solvers/c3.cc index 6b85786484..721a3ead28 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -117,7 +117,7 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, prog_.AddLinearEqualityConstraint( LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}); -// prog_.AddLinearConstraint(lambda_.at(i) >= VectorXd::Zero(m_)); + // prog_.AddLinearConstraint(lambda_.at(i) >= VectorXd::Zero(m_)); } for (int i = 0; i < N_ + 1; i++) { prog_.AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * xdesired_.at(i), diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index da5af3a22e..deca99c0c4 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -23,7 +23,7 @@ C3MIQP::C3MIQP(const LCS& LCS, const vector& Q, warm_start_u, warm_start), env_(true) { // Create an environment - env_.set("LogToConsole", "0"); +// env_.set("LogToConsole", "0"); env_.set("OutputFlag", "0"); env_.set("Threads", "2"); env_.start(); @@ -49,7 +49,13 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, Mcons2 << MM1, MM2, MM3; // Create an empty model +// GRBEnv env = GRBEnv(); +// env.start(); +// env_.start(); + GRBModel model = GRBModel(env_); +// model.set(GRB_IntParam_LogToConsole, 1); +// model.set(GRB_StringParam_LogFile, "grb_debug"); //model.set("FeasibilityTol", "0.01"); //model.set("IterationLimit", "40"); @@ -82,7 +88,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.setObjective(obj, GRB_MINIMIZE); - int M = std::numeric_limits::max(); // big M variable + int M = 1000; // big M variable double coeff[n_ + m_ + k_]; double coeff2[n_ + m_ + k_]; @@ -125,7 +131,6 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, warm_start_delta_[warm_start_index] = delta_kc; warm_start_binary_[warm_start_index] = binaryc; } - return delta_kc; } diff --git a/solvers/c3_options.h b/solvers/c3_options.h index e8638e676e..bcdb4ed9b2 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -1,12 +1,13 @@ #pragma once #include + #include "drake/common/yaml/yaml_read_archive.h" struct C3Options { // Hyperparameters - int admm_iter; // total number of ADMM iterations //2 - float rho; // inital value of the rho parameter - float rho_scale; // scaling of rho parameter (/rho = rho_scale * /rho) //3 + int admm_iter; // total number of ADMM iterations //2 + float rho; // inital value of the rho parameter + float rho_scale; // scaling of rho parameter (/rho = rho_scale * /rho) //3 int num_threads; // 0 is dynamic, greater than 0 for a fixed count int delta_option; // different options for delta update std::string projection_type; @@ -76,14 +77,14 @@ struct C3Options { // a->Visit(DRAKE_NVP(u_size)); a->Visit(DRAKE_NVP(q_vector)); a->Visit(DRAKE_NVP(r_vector)); -// a->Visit(DRAKE_NVP(g_vector)); + // a->Visit(DRAKE_NVP(g_vector)); a->Visit(DRAKE_NVP(g_x)); a->Visit(DRAKE_NVP(g_gamma)); a->Visit(DRAKE_NVP(g_lambda_n)); a->Visit(DRAKE_NVP(g_lambda_t)); a->Visit(DRAKE_NVP(g_lambda)); a->Visit(DRAKE_NVP(g_u)); -// a->Visit(DRAKE_NVP(u_vector)); + // a->Visit(DRAKE_NVP(u_vector)); a->Visit(DRAKE_NVP(u_x)); a->Visit(DRAKE_NVP(u_gamma)); a->Visit(DRAKE_NVP(u_lambda_n)); @@ -93,23 +94,23 @@ struct C3Options { g_vector = std::vector(); g_vector.insert(g_vector.end(), g_x.begin(), g_x.end()); - if (contact_model == "stewart_and_trinkle"){ - g_vector.insert(g_vector.end(), g_gamma.begin(), g_gamma.end()); - g_vector.insert(g_vector.end(), g_lambda_n.begin(), g_lambda_n.end()); - g_vector.insert(g_vector.end(), g_lambda_t.begin(), g_lambda_t.end()); - }else{ - g_vector.insert(g_vector.end(), g_lambda.begin(), g_lambda.end()); + if (contact_model == "stewart_and_trinkle") { + g_vector.insert(g_vector.end(), g_gamma.begin(), g_gamma.end()); + g_vector.insert(g_vector.end(), g_lambda_n.begin(), g_lambda_n.end()); + g_vector.insert(g_vector.end(), g_lambda_t.begin(), g_lambda_t.end()); + } else { + g_vector.insert(g_vector.end(), g_lambda.begin(), g_lambda.end()); } g_vector.insert(g_vector.end(), g_u.begin(), g_u.end()); u_vector = std::vector(); u_vector.insert(u_vector.end(), u_x.begin(), u_x.end()); - if (contact_model == "stewart_and_trinkle"){ - u_vector.insert(u_vector.end(), u_gamma.begin(), u_gamma.end()); - u_vector.insert(u_vector.end(), u_lambda_n.begin(), u_lambda_n.end()); - u_vector.insert(u_vector.end(), u_lambda_t.begin(), u_lambda_t.end()); - }else{ - u_vector.insert(u_vector.end(), u_lambda.begin(), u_lambda.end()); + if (contact_model == "stewart_and_trinkle") { + u_vector.insert(u_vector.end(), u_gamma.begin(), u_gamma.end()); + u_vector.insert(u_vector.end(), u_lambda_n.begin(), u_lambda_n.end()); + u_vector.insert(u_vector.end(), u_lambda_t.begin(), u_lambda_t.end()); + } else { + u_vector.insert(u_vector.end(), u_lambda.begin(), u_lambda.end()); } u_vector.insert(u_vector.end(), u_u.begin(), u_u.end()); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index dfb0be14fe..70eb269933 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -163,7 +163,6 @@ std::pair LCSFactory::LinearizePlantToLCS( D.block(0, n_contacts, n_q, n_contacts) = dt * dt * qdotNv * MinvJ_n_T; D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; - std::cout << "D: " << D << std::endl; E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q + J_n * vNqdot; E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = @@ -223,14 +222,14 @@ std::pair LCSFactory::LinearizePlantToLCS( MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); - D.block(0, 0, n_q, n_lambda) = dt * qdotNv * MinvJ_c_T; - D.block(n_q, 0, n_v, n_lambda) = MinvJ_c_T; + D.block(0, 0, n_q, n_lambda) = dt * dt * qdotNv * MinvJ_c_T; + D.block(n_q, 0, n_v, n_lambda) = dt * MinvJ_c_T; E.block(0, 0, n_lambda, n_q) = dt * J_c * AB_v_q + E_t.transpose() * J_n * vNqdot / dt; E.block(0, n_q, n_lambda, n_v) = J_c + dt * J_c * AB_v_v; - F = J_c * MinvJ_c_T; + F = dt * J_c * MinvJ_c_T; H = dt * J_c * AB_v_u; c = E_t.transpose() * phi / dt + dt * J_c * d_v - diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 2835b5234a..8446602aaa 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -187,13 +187,16 @@ void C3Controller::OutputC3Solution( for (int i = 0; i < N_; i++) { c3_solution->time_vector_(i) = t + i * c3_options_.dt; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); - if (c3_options_.contact_model == "anitescu") { - c3_solution->lambda_sol_.col(i) = - c3_options_.dt * z_sol[i].segment(n_x_, n_lambda_).cast(); - } else { - c3_solution->lambda_sol_.col(i) = - z_sol[i].segment(n_x_, n_lambda_).cast(); - } + // if (c3_options_.contact_model == "anitescu") { + // c3_solution->lambda_sol_.col(i) = + // c3_options_.dt * z_sol[i].segment(n_x_, + // n_lambda_).cast(); + // } else { + // c3_solution->lambda_sol_.col(i) = + // z_sol[i].segment(n_x_, n_lambda_).cast(); + // } + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 6fbbfbd735..688ea568ed 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -675,9 +675,11 @@ VectorXd OperationalSpaceControl::SolveQp( A_dyn.block(0, n_v_ + n_c_, n_v_, n_h_) = -J_h.transpose(); A_dyn.block(0, n_v_ + n_c_ + n_h_, n_v_, n_u_) = -B; for (auto& force_tracking_data : *force_tracking_data_vec_) { - MatrixXd J_ee = force_tracking_data->GetJ(); - A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_lambda_ext_) = - J_ee.transpose(); + if (!force_tracking_data->GetWeight().isZero()){ + MatrixXd J_ee = force_tracking_data->GetJ(); + A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_lambda_ext_) = + J_ee.transpose(); + } } dynamics_constraint_->UpdateCoefficients(A_dyn, -bias); // 2. Holonomic constraint @@ -1086,10 +1088,10 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); - qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); -// qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); -// qp_output.lambda_h_sol = CopyVectorXdToStdVector(force_tracking_data_vec_->at(0)->GetLambdaDes()); +// qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); +// qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); + qp_output.lambda_h_sol = CopyVectorXdToStdVector(force_tracking_data_vec_->at(0)->GetLambdaDes()); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; From 65788b420888f369fc44f3eaa783293b3f2fc992 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 14 Dec 2023 11:23:27 -0500 Subject: [PATCH 570/758] reordering geometry additions so sortedpair has the right visualizatin --- examples/franka/franka_c3_controller.cc | 3 ++- .../parameters/franka_c3_options_w_supports.yaml | 16 ++++++++-------- examples/franka/urdf/plate_end_effector.urdf | 2 +- .../urdf/plate_end_effector_translation.urdf | 6 +++--- multibody/geom_geom_collider.cc | 4 ++-- solvers/c3_qp.cc | 6 +++--- systems/controllers/c3_controller.cc | 9 ++------- 7 files changed, 21 insertions(+), 25 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 6d4693fde1..24a3bff054 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -110,7 +110,6 @@ int DoMain(int argc, char* argv[]) { Parser parser_plate(&plant_for_lcs); parser_plate.SetAutoRenaming(true); parser_plate.AddModels(controller_params.plate_model); - parser_plate.AddModels(controller_params.tray_model); drake::multibody::ModelInstanceIndex left_support_index; drake::multibody::ModelInstanceIndex right_support_index; @@ -130,6 +129,8 @@ int DoMain(int argc, char* argv[]) { plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); } + parser_plate.AddModels(controller_params.tray_model); + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), plant_for_lcs.GetFrameByName("base_link"), X_WI); diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 9599419ae0..c1c412eb15 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,4 +1,4 @@ -admm_iter: 3 +admm_iter: 4 rho: 0.1 rho_scale: 2 num_threads: 5 @@ -11,7 +11,7 @@ contact_model: 'anitescu' warm_start: false mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05, 0.05] -dt: 0.05 +dt: 0.1 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 @@ -19,29 +19,29 @@ N: 5 # matrix scaling w_Q: 50 -w_R: 0.1 +w_R: 0.01 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar w_U: 0.5 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 125, 1000, 1000, 1000, 1000, 15000, 15000, 15000, +q_vector: [175, 175, 175, 1000, 1000, 1000, 1000, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 1] +r_vector: [0.1, 0.1, 0.1] # Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_u: [5, 5, 10] +g_lambda: [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_u: [10, 10, 10] u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10] u_u: [5, 5, 5] diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 37a37f570a..8e5b77e75b 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -22,7 +22,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 29a1b227eb..3a9b301937 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -20,19 +20,19 @@ - + - + - + diff --git a/multibody/geom_geom_collider.cc b/multibody/geom_geom_collider.cc index cfb33bb81b..c8c023a068 100644 --- a/multibody/geom_geom_collider.cc +++ b/multibody/geom_geom_collider.cc @@ -86,8 +86,8 @@ GeomGeomCollider::CalcWitnessPoints(const Context& context) { Vector3d p_WCb = Vector3d::Zero(); plant_.CalcPointsPositions(context, frameA, p_ACa, plant_.world_frame(), &p_WCa); - plant_.CalcPointsPositions(context, frameB, p_BCb, - plant_.world_frame(), &p_WCb); + plant_.CalcPointsPositions(context, frameB, p_BCb, plant_.world_frame(), + &p_WCb); return std::pair, VectorX>(p_WCa, p_WCb); } diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc index 0e780d00e2..f846f6c40f 100644 --- a/solvers/c3_qp.cc +++ b/solvers/c3_qp.cc @@ -51,7 +51,7 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, auto ln_ = prog.NewContinuousVariables(m_, "lambda"); auto un_ = prog.NewContinuousVariables(k_, "u"); - double alpha = 0.3; + double alpha = 0.01; double scaling = 1000; MatrixXd EFH(m_, n_ + m_ + k_); @@ -80,10 +80,10 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, // prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); - solver_options.SetOption(OsqpSolver::id(), "max_iter", 250); + solver_options.SetOption(OsqpSolver::id(), "max_iter", 500); solver_options.SetOption(OsqpSolver::id(), "verbose", 0); solver_options.SetOption(OsqpSolver::id(), "polish", 1); - solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 3); + solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 1); solver_options.SetOption(OsqpSolver::id(), "rho", 1e-4); solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); solver_options.SetOption(OsqpSolver::id(), "linsys_solver", 0); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 8446602aaa..4ff450136f 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -54,13 +54,8 @@ C3Controller::C3Controller( n_u_ = plant_.num_actuators(); - int x_des_size = plant_.num_positions(ModelInstanceIndex(2)) + - plant_.num_positions(ModelInstanceIndex(3)) + - plant_.num_velocities(ModelInstanceIndex(2)) + - plant_.num_velocities(ModelInstanceIndex(3)); lcs_state_input_port_ = - this->DeclareVectorInputPort("x_lcs", - TimestampedVector(x_des_size)) + this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) .get_index(); MatrixXd A = MatrixXd::Zero(n_x_, n_x_); @@ -77,7 +72,7 @@ C3Controller::C3Controller( this->DeclareAbstractInputPort("lcs", drake::Value(lcs)).get_index(); target_input_port_ = - this->DeclareVectorInputPort("x_lcs_des", x_des_size).get_index(); + this->DeclareVectorInputPort("x_lcs_des", n_x_).get_index(); auto c3_solution = C3Output::C3Solution(); c3_solution.x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); From 9cab04fccfef70f9017760ba9bc323399e7c6c05 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 15 Dec 2023 11:53:46 -0500 Subject: [PATCH 571/758] cleaning up code --- examples/franka/franka_visualizer.cc | 59 ++++++++++--------- .../franka_c3_options_translation.yaml | 2 +- .../franka_c3_options_w_supports.yaml | 22 +++---- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/plate_end_effector.urdf | 4 +- .../urdf/plate_end_effector_translation.urdf | 4 +- examples/franka/urdf/tray.sdf | 4 +- solvers/c3.cc | 28 +++++---- solvers/c3.h | 4 +- systems/controllers/c3_controller.cc | 12 +--- .../lcm_trajectory_systems.cc | 30 ++++------ .../lcm_trajectory_systems.h | 5 ++ 12 files changed, 90 insertions(+), 86 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index f37292b331..24ad5aa623 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -1,7 +1,7 @@ #include -#include #include +#include #include #include #include @@ -36,8 +36,8 @@ using Eigen::MatrixXd; using Eigen::Vector3d; using Eigen::VectorXd; -using dairlib::systems::RobotOutputReceiver; using dairlib::systems::ObjectStateReceiver; +using dairlib::systems::RobotOutputReceiver; using dairlib::systems::SubvectorPassThrough; using drake::geometry::DrakeVisualizer; using drake::geometry::SceneGraph; @@ -99,15 +99,17 @@ int do_main(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); - if (sim_params.scene_index == 1){ + if (sim_params.scene_index == 1) { drake::multibody::ModelInstanceIndex left_support_index = parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; - drake::multibody::ModelInstanceIndex right_support_index = - parser.AddModels(FindResourceOrThrow(sim_params.right_support_model))[0]; - RigidTransform T_S1_W = RigidTransform( - drake::math::RotationMatrix(), sim_params.left_support_position); - RigidTransform T_S2_W = RigidTransform( - drake::math::RotationMatrix(), sim_params.right_support_position); + drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( + FindResourceOrThrow(sim_params.right_support_model))[0]; + RigidTransform T_S1_W = + RigidTransform(drake::math::RotationMatrix(), + sim_params.left_support_position); + RigidTransform T_S2_W = + RigidTransform(drake::math::RotationMatrix(), + sim_params.right_support_position); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_S1_W); @@ -140,6 +142,9 @@ int do_main(int argc, char* argv[]) { auto franka_passthrough = builder.AddSystem( franka_state_receiver->get_output_port(0).size(), 0, plant.num_positions(franka_index)); + auto robot_time_passthrough = builder.AddSystem( + franka_state_receiver->get_output_port(0).size(), + franka_state_receiver->get_output_port(0).size() - 1, 1); auto tray_passthrough = builder.AddSystem( tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); @@ -159,8 +164,8 @@ int do_main(int argc, char* argv[]) { auto trajectory_sub_object = builder.AddSystem( LcmSubscriberSystem::Make( lcm_channel_params.c3_object_channel, lcm)); - auto trajectory_sub_force = builder.AddSystem( - LcmSubscriberSystem::Make( + auto trajectory_sub_force = + builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.c3_force_channel, lcm)); auto to_pose = builder.AddSystem>(plant); @@ -172,23 +177,20 @@ int do_main(int argc, char* argv[]) { auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); auto trajectory_drawer_actor = - builder.AddSystem(meshcat, - "end_effector_position_target"); + builder.AddSystem( + meshcat, "end_effector_position_target"); auto trajectory_drawer_object = - builder.AddSystem(meshcat, "object_position_target"); - auto object_pose_drawer = - builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.tray_model), "object_position_target", - "object_orientation_target"); - auto end_effector_pose_drawer = - builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.end_effector_model), "end_effector_position_target", - "end_effector_orientation_target"); - auto end_effector_force_drawer = - builder.AddSystem( - meshcat, "end_effector_position_target", - "end_effector_force_target", - "lcs_force_trajectory"); + builder.AddSystem(meshcat, + "object_position_target"); + auto object_pose_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.tray_model), + "object_position_target", "object_orientation_target"); + auto end_effector_pose_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.end_effector_model), + "end_effector_position_target", "end_effector_orientation_target"); + auto end_effector_force_drawer = builder.AddSystem( + meshcat, "end_effector_position_target", "end_effector_force_target", + "lcs_force_trajectory"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(5); @@ -215,6 +217,9 @@ int do_main(int argc, char* argv[]) { to_pose->get_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(*franka_state_receiver, *franka_passthrough); + builder.Connect(*franka_state_receiver, *robot_time_passthrough); + builder.Connect(robot_time_passthrough->get_output_port(), + end_effector_force_drawer->get_input_port_robot_time()); builder.Connect(*tray_state_receiver, *tray_passthrough); builder.Connect(*box_state_receiver, *box_passthrough); diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 2836a945fb..229c6c6cef 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -37,7 +37,7 @@ g_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0 g_gamma: [1, 1, 1] g_lambda_n: [1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [.05, .05, .05, .05, .05, .05, .05, .05, .05, .05, .05, .05] +g_lambda: [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10] g_u: [1, 1, 1] # Penalty on all decision variables diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index c1c412eb15..bf157fa435 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,17 +1,17 @@ admm_iter: 4 rho: 0.1 -rho_scale: 2 +rho_scale: 3 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'QP' +projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' warm_start: false -mu: [0.4, 0.4, 0.4, 0.05, 0.05, 0.05, 0.05] -dt: 0.1 +mu: [0.8, 0.8, 0.8, 0.05, 0.05, 0.05, 0.05] +dt: 0.08 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 @@ -19,7 +19,7 @@ N: 5 # matrix scaling w_Q: 50 -w_R: 0.01 +w_R: 10 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar @@ -32,16 +32,16 @@ q_vector: [175, 175, 175, 1000, 1000, 1000, 1000, 15000, 15000, 15000, r_vector: [0.1, 0.1, 0.1] # Penalty on matching projected variables -g_x: [1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_x: [1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 2, 2, 2, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [10, 10, 10] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_u: [20, 20, 20] -u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1] +u_x: [10, 10, 10, 1, 1, 1, 1, 5, 5, 5, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10] -u_u: [5, 5, 5] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_u: [30, 30, 30] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 7ee6f51728..2fa59111a2 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,7 +12,7 @@ tray_publish_rate: 1000 actuator_delay: 0.000 scene_index: 1 -visualize: false +visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 8e5b77e75b..3987d2d8ba 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,8 +15,8 @@ - - + + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 3a9b301937..b1e4be49f9 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -6,9 +6,9 @@ - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 4ddd39833e..8efe27d385 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -41,8 +41,8 @@ 3.0e7 0.18 10 - 0.4 - 0.4 + 0.8 + 0.8 diff --git a/solvers/c3.cc b/solvers/c3.cc index 721a3ead28..003d0129f6 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -119,11 +119,12 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}); // prog_.AddLinearConstraint(lambda_.at(i) >= VectorXd::Zero(m_)); } + input_costs_.resize(N_); for (int i = 0; i < N_ + 1; i++) { - prog_.AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * xdesired_.at(i), + prog_.AddQuadraticCost(2 * Q_.at(i), -2 * Q_.at(i) * xdesired_.at(i), x_.at(i), 1); if (i < N_) { - prog_.AddQuadraticCost(R_.at(i) * 2, VectorXd::Zero(k_), u_.at(i), 1); + input_costs_[i] = prog_.AddQuadraticCost(2 * R_.at(i), VectorXd::Zero(k_), u_.at(i), 1).evaluator(); } } } @@ -133,6 +134,11 @@ vector C3::Solve(const VectorXd& x0, vector& delta, vector Gv = G_; VectorXd z; + for (int i = 0; i < N_; ++i){ + input_costs_[i]->UpdateCoefficients(2 * R_.at(i), -2 * R_.at(i) * u_sol_->at(i)); + } +// input_costs_[0]->UpdateCoefficients(2 * R_.at(0), -2 * R_.at(0) * u_sol_->at(0)); + for (int i = 0; i < options_.admm_iter - 1; i++) { z = ADMMStep(x0, &delta, &w, &Gv); } @@ -141,7 +147,7 @@ vector C3::Solve(const VectorXd& x0, vector& delta, for (int i = 0; i < N_; i++) { WD.at(i) = delta.at(i) - w.at(i); } - vector zfin = SolveQP(x0, Gv, WD); + vector zfin = SolveQP(x0, Gv, WD, true); return zfin; } @@ -179,7 +185,7 @@ VectorXd C3::ADMMStep(const VectorXd& x0, vector* delta, } vector C3::SolveQP(const VectorXd& x0, vector& G, - vector& WD) { + vector& WD, bool is_final_solve) { for (auto& constraint : constraints_) { prog_.RemoveConstraint(constraint); } @@ -232,12 +238,14 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, if (result.is_success()) { for (int i = 0; i < N_; i++) { - x_sol_->at(i) = result.GetSolution(x_[i]); - lambda_sol_->at(i) = result.GetSolution(lambda_[i]); - u_sol_->at(i) = result.GetSolution(u_[i]); - z_sol_->at(i).segment(0, n_) = x_sol_->at(i); - z_sol_->at(i).segment(n_, m_) = lambda_sol_->at(i); - z_sol_->at(i).segment(n_ + m_, k_) = u_sol_->at(i); + if (is_final_solve){ + x_sol_->at(i) = result.GetSolution(x_[i]); + lambda_sol_->at(i) = result.GetSolution(lambda_[i]); + u_sol_->at(i) = result.GetSolution(u_[i]); + } + z_sol_->at(i).segment(0, n_) = result.GetSolution(x_[i]); + z_sol_->at(i).segment(n_, m_) = result.GetSolution(lambda_[i]); + z_sol_->at(i).segment(n_ + m_, k_) = result.GetSolution(u_[i]); if (warm_start_) { // update warm start parameters diff --git a/solvers/c3.h b/solvers/c3.h index 067e28b9e5..fe26ff93e1 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -57,7 +57,8 @@ class C3 { /// @param G A pointer to the G variables from previous step std::vector SolveQP(const Eigen::VectorXd& x0, std::vector& G, - std::vector& WD); + std::vector& WD, + bool is_final_solve = false); /// Solve the projection problem for all timesteps /// @param WZ A pointer to the (z + w) variables @@ -135,6 +136,7 @@ class C3 { std::vector u_; std::vector lambda_; std::vector> costs_; + std::vector> input_costs_; std::vector> constraints_; std::vector> diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 4ff450136f..80e774c62a 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -162,7 +162,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( A(i) = 1.0; c3_->AddLinearConstraint(A, 0, 20, 2); } - auto z_sol = c3_->Solve(lcs_x->get_data(), delta, w); + c3_->Solve(lcs_x->get_data(), delta, w); auto finish = std::chrono::high_resolution_clock::now(); delta_ = delta; w_ = w; @@ -182,14 +182,6 @@ void C3Controller::OutputC3Solution( for (int i = 0; i < N_; i++) { c3_solution->time_vector_(i) = t + i * c3_options_.dt; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); - // if (c3_options_.contact_model == "anitescu") { - // c3_solution->lambda_sol_.col(i) = - // c3_options_.dt * z_sol[i].segment(n_x_, - // n_lambda_).cast(); - // } else { - // c3_solution->lambda_sol_.col(i) = - // z_sol[i].segment(n_x_, n_lambda_).cast(); - // } c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); @@ -201,7 +193,7 @@ void C3Controller::OutputC3Solution( void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { - double t = context.get_discrete_state(plan_start_time_index_)[0]; + double t = context.get_discrete_state(plan_start_time_index_)[0] + solve_time_; for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index c89e0a3653..3fd206a33e 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -272,6 +272,9 @@ LcmForceDrawer::LcmForceDrawer( drake::Value{}) .get_index(); + robot_time_input_port_ = + this->DeclareVectorInputPort("t_robot", 1).get_index(); + force_trajectory_input_port_ = this->DeclareAbstractInputPort("lcmt_c3_forces", drake::Value{}) @@ -281,26 +284,10 @@ LcmForceDrawer::LcmForceDrawer( actor_last_update_time_index_ = this->DeclareDiscreteState(1); forces_last_update_time_index_ = this->DeclareDiscreteState(1); - // Add the geometry to meshcat. - // Set radius 1.0 so that it can be scaled later by the force/moment norm in - // the path transform. - // const drake::geometry::Cylinder cylinder(radius_, 1.0); - // const double arrowhead_height = radius_ * 2.0; - // const double arrowhead_width = radius_ * 2.0; - // const drake::geometry::MeshcatCone arrowhead( - // arrowhead_height, arrowhead_width, arrowhead_width); - meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, {0, 0, 1, 1}); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, {0, 0, 1, 1}); - // for (int i = 0; i < 18; ++i) { - // const std::string lcs_force_path = force_path_ + "/lcs_force_" + - // std::to_string(i) + "/arrow"; - // meshcat_->SetObject(lcs_force_path + "/cylinder", cylinder, {1, 0, 0, - // 1}); meshcat_->SetObject(lcs_force_path + "/head", arrowhead, {1, 0, 0, - // 1}); - // } DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); @@ -323,12 +310,16 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( const auto& lcmt_traj = this->EvalInputValue( context, actor_trajectory_input_port_); + const auto& robot_time_vec = + this->EvalVectorInput( + context, robot_time_input_port_); + double robot_time = robot_time_vec->GetAtIndex(0); auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); const auto& force_trajectory_block = lcm_traj.GetTrajectory(force_trajectory_name_); const auto& actor_trajectory_block = lcm_traj.GetTrajectory(actor_trajectory_name_); - auto force_trajectory = PiecewisePolynomial::FirstOrderHold( + auto force_trajectory = PiecewisePolynomial::ZeroOrderHold( force_trajectory_block.time_vector, force_trajectory_block.datapoints); VectorXd pose; if (actor_trajectory_block.datapoints.rows() == 3) { @@ -343,7 +334,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( pose = trajectory.value(actor_trajectory_block.time_vector[0]); } - auto force = force_trajectory.value(force_trajectory_block.time_vector[0]); + auto force = force_trajectory.value(robot_time); const std::string& force_path_root = force_path_ + "/u_lcs/"; meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); const std::string& force_arrow_path = force_path_root + "arrow"; @@ -402,7 +393,8 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, {1, 0, 0, 1}); - meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, {1, 0, 0, 1}); + meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, + {1, 0, 0, 1}); } const VectorXd pose = Eigen::Map( diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index b2575bbd77..8c3c561a7e 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -140,6 +140,10 @@ class LcmForceDrawer : public drake::systems::LeafSystem { return this->get_input_port(actor_trajectory_input_port_); } + const drake::systems::InputPort& get_input_port_robot_time() const { + return this->get_input_port(robot_time_input_port_); + } + const drake::systems::InputPort& get_input_port_force_trajectory() const { return this->get_input_port(force_trajectory_input_port_); } @@ -160,6 +164,7 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::systems::DiscreteValues *discrete_state) const; drake::systems::InputPortIndex actor_trajectory_input_port_; + drake::systems::InputPortIndex robot_time_input_port_; drake::systems::InputPortIndex force_trajectory_input_port_; drake::systems::DiscreteStateIndex actor_last_update_time_index_; From 861aba8446d33e5c98412e8ddcbed5d4e34b3c48 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 18 Dec 2023 16:45:42 -0500 Subject: [PATCH 572/758] attempted basic hydroelastic lcs, most likely turning into better point contact formulation --- .../franka_c3_controller_params.yaml | 4 +- .../franka_c3_options_translation.yaml | 12 +- .../franka_c3_options_w_supports.yaml | 10 +- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/plate_end_effector.urdf | 4 +- .../plate_end_effector_translation_he.urdf | 62 +++++ examples/franka/urdf/tray.sdf | 4 +- multibody/BUILD.bazel | 13 + multibody/hydroelastic_geom_collider.cc | 246 ++++++++++++++++++ multibody/hydroelastic_geom_collider.h | 85 ++++++ .../lcm_trajectory_systems.cc | 9 +- 11 files changed, 429 insertions(+), 22 deletions(-) create mode 100644 examples/franka/urdf/plate_end_effector_translation_he.urdf create mode 100644 multibody/hydroelastic_geom_collider.cc create mode 100644 multibody/hydroelastic_geom_collider.h diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index b5f08739d1..9aa97d0a08 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -12,8 +12,10 @@ plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -scene_index: 1 +scene_index: 0 +#left_support_model: examples/franka/urdf/left_support.urdf +#right_support_model: examples/franka/urdf/left_support.urdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf left_support_position: [0.65, 0.15, 0.225] diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 229c6c6cef..c723e31f91 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -1,13 +1,13 @@ admm_iter: 4 rho: 0.1 -rho_scale: 1 +rho_scale: 2 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'QP' +projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' -contact_model: 'anitescu' -#contact_model: 'stewart_and_trinkle' +#contact_model: 'anitescu' +contact_model: 'stewart_and_trinkle' warm_start: true mu: [0.2, 0.2, 0.2] @@ -37,7 +37,7 @@ g_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0 g_gamma: [1, 1, 1] g_lambda_n: [1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] # Penalty on all decision variables @@ -45,5 +45,5 @@ u_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 1, 1, 1, 10, 10, 10, 10, 10, 10] u_gamma: [1, 1, 1] u_lambda_n: [1, 1, 1] u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_lambda: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05, 0.05] +u_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_u: [10, 10, 10] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index bf157fa435..50a2869aaf 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,5 +1,5 @@ admm_iter: 4 -rho: 0.1 +rho: 0 # does not do anything rho_scale: 3 num_threads: 5 delta_option: 1 @@ -19,7 +19,7 @@ N: 5 # matrix scaling w_Q: 50 -w_R: 10 +w_R: 5 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar @@ -32,14 +32,14 @@ q_vector: [175, 175, 175, 1000, 1000, 1000, 1000, 15000, 15000, 15000, r_vector: [0.1, 0.1, 0.1] # Penalty on matching projected variables -g_x: [1, 1, 1, 1, 1, 1, 1, 5, 5, 5, 2, 2, 2, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_x: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [20, 20, 20] +g_u: [20, 20, 5] -u_x: [10, 10, 10, 1, 1, 1, 1, 5, 5, 5, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [10, 10, 10, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 2fa59111a2..b04e2392e9 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -11,7 +11,7 @@ franka_publish_rate: 1000 tray_publish_rate: 1000 actuator_delay: 0.000 -scene_index: 1 +scene_index: 0 visualize: true publish_efforts: true diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 3987d2d8ba..8e5b77e75b 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,8 +15,8 @@ - - + + diff --git a/examples/franka/urdf/plate_end_effector_translation_he.urdf b/examples/franka/urdf/plate_end_effector_translation_he.urdf new file mode 100644 index 0000000000..01d1b5a3d9 --- /dev/null +++ b/examples/franka/urdf/plate_end_effector_translation_he.urdf @@ -0,0 +1,62 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + 1 + + + + + 1 + + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 8efe27d385..4ddd39833e 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -41,8 +41,8 @@ 3.0e7 0.18 10 - 0.8 - 0.8 + 0.4 + 0.4 diff --git a/multibody/BUILD.bazel b/multibody/BUILD.bazel index 0d76a6d617..a9ea3eede2 100644 --- a/multibody/BUILD.bazel +++ b/multibody/BUILD.bazel @@ -123,3 +123,16 @@ cc_binary( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "hydroelastic_geom_collider", + srcs = ["hydroelastic_geom_collider.cc"], + hdrs = [ + "hydroelastic_geom_collider.h", + ], + deps = [ + ":utils", + "//common", + "@drake//:drake_shared_library", + ], +) diff --git a/multibody/hydroelastic_geom_collider.cc b/multibody/hydroelastic_geom_collider.cc new file mode 100644 index 0000000000..62b6e8360e --- /dev/null +++ b/multibody/hydroelastic_geom_collider.cc @@ -0,0 +1,246 @@ +#include "multibody/hydroelastic_geom_collider.h" + +#include + +#include "drake/math/rotation_matrix.h" + +using drake::EigenPtr; +using drake::MatrixX; +using drake::VectorX; +using drake::geometry::GeometryId; +using drake::geometry::HydroelasticContactRepresentation; +using drake::geometry::SignedDistancePair; +using drake::multibody::JacobianWrtVariable; +using drake::multibody::MultibodyPlant; +using drake::systems::Context; +using Eigen::Matrix; +using Eigen::Vector3d; +using Eigen::VectorXd; + +namespace dairlib { +namespace multibody { + +template +HydroelasticGeomCollider::HydroelasticGeomCollider( + const drake::multibody::MultibodyPlant& plant, + const std::vector>& + contact_geoms) + : plant_(plant), contact_pairs_(contact_geoms) {} + +template +std::vector>> HydroelasticGeomCollider::Eval( + const Context& context, JacobianWrtVariable wrt) { + return DoEval(context, Eigen::Matrix3d::Identity(), wrt); +} + +template +std::vector>> HydroelasticGeomCollider::EvalPolytope( + const Context& context, int num_friction_directions, + JacobianWrtVariable wrt) { + if (num_friction_directions == 1) { + throw std::runtime_error( + "HydroelasticGeomCollider cannot specify 1 friction direction unless " + "using EvalPlanar."); + } + + // Build friction basis + Matrix force_basis(2 * num_friction_directions + 1, + 3); + force_basis.row(0) << 1, 0, 0; + + for (int i = 0; i < num_friction_directions; i++) { + double theta = (M_PI * i) / num_friction_directions; + force_basis.row(2 * i + 1) = Vector3d(0, cos(theta), sin(theta)); + force_basis.row(2 * i + 2) = -force_basis.row(2 * i + 1); + } + return DoEval(context, force_basis, wrt); +} + +template +std::vector>> HydroelasticGeomCollider::EvalPlanar( + const Context& context, const Vector3d& planar_normal, + JacobianWrtVariable wrt) { + return DoEval(context, planar_normal.transpose(), wrt, true); +} + +template +std::vector> HydroelasticGeomCollider::CalcWitnessPoints( + const Context& context) { + const auto& query_port = plant_.get_geometry_query_input_port(); + const auto& query_object = + query_port.template Eval>(context); + + auto geom_ids = contact_pairs_.front(); + auto geometry_id_A_ = geom_ids.first(); + auto geometry_id_B_ = geom_ids.second(); + + const SignedDistancePair signed_distance_pair = + query_object.ComputeSignedDistancePairClosestPoints(geometry_id_A_, + geometry_id_B_); + const auto& inspector = query_object.inspector(); + const auto frame_A_id = inspector.GetFrameId(geometry_id_A_); + const auto frame_B_id = inspector.GetFrameId(geometry_id_B_); + const auto& frameA = plant_.GetBodyFromFrameId(frame_A_id)->body_frame(); + const auto& frameB = plant_.GetBodyFromFrameId(frame_B_id)->body_frame(); + + const Vector3d& p_ACa = + inspector.GetPoseInFrame(geometry_id_A_).template cast() * + signed_distance_pair.p_ACa; + const Vector3d& p_BCb = + inspector.GetPoseInFrame(geometry_id_B_).template cast() * + signed_distance_pair.p_BCb; + Vector3d p_WCa = Vector3d::Zero(); + Vector3d p_WCb = Vector3d::Zero(); + plant_.CalcPointsPositions(context, frameA, p_ACa, plant_.world_frame(), + &p_WCa); + plant_.CalcPointsPositions(context, frameB, p_BCb, plant_.world_frame(), + &p_WCb); + std::vector> witness_points; + witness_points.push_back(p_WCa); + return witness_points; +} + +template +std::vector>> HydroelasticGeomCollider::DoEval( + const Context& context, Matrix force_basis, + JacobianWrtVariable wrt, bool planar) { + const auto& query_port = plant_.get_geometry_query_input_port(); + const auto& query_object = + query_port.template Eval>(context); + const auto& inspector = query_object.inspector(); + + const auto& contact_surfaces = query_object.ComputeContactSurfaces( + HydroelasticContactRepresentation::kPolygon); +// auto contact_info = drake::multibody::internal::HydroelasticContactInfoAndBodySpatialForces( +// plant_.num_bodies()); +// plant_.CalcHydroelasticContactForces(context, &contact_info); + std::vector>> contact_data; + std::set> + geom_pairs_with_data; + for (auto& contact_surface : contact_surfaces) { + std::cout << "body M name: " + << plant_ + .GetBodyFromFrameId( + inspector.GetFrameId(contact_surface.id_M())) + ->name() + << std::endl; + std::cout << "body N name: " + << plant_ + .GetBodyFromFrameId( + inspector.GetFrameId(contact_surface.id_N())) + ->name() + << std::endl; + std::cout << "Has M gradient" << contact_surface.HasGradE_M() << std::endl; + std::cout << "Has N gradient" << contact_surface.HasGradE_N() << std::endl; + + std::cout << "Total area: " << contact_surface.total_area() << std::endl; + std::cout << "contact_surface.num_faces()" << contact_surface.num_faces() + << std::endl; + const SignedDistancePair contact_surface_signed_distance_pair = + query_object.ComputeSignedDistancePairClosestPoints( + contact_surface.id_M(), contact_surface.id_N()); + + // const auto frame_B_id = inspector.GetFrameId(geometry_id_B_); + const auto& frameM = + plant_.GetBodyFromFrameId(inspector.GetFrameId(contact_surface.id_M())) + ->body_frame(); + const auto& frameN = + plant_.GetBodyFromFrameId(inspector.GetFrameId(contact_surface.id_N())) + ->body_frame(); + + const Vector3d& p_ACM = + inspector.GetPoseInFrame(contact_surface.id_M()).template cast() * + contact_surface_signed_distance_pair.p_ACa; + const Vector3d& p_BCN = + inspector.GetPoseInFrame(contact_surface.id_N()).template cast() * + contact_surface_signed_distance_pair.p_BCb; + + Vector3d p_WCa = Vector3d::Zero(); + Vector3d p_WCb = Vector3d::Zero(); + plant_.CalcPointsPositions(context, frameM, p_ACM, plant_.world_frame(), + &p_WCa); + plant_.CalcPointsPositions(context, frameN, p_BCN, plant_.world_frame(), + &p_WCb); + int face_with_area = 0; + VectorXd wrench_basis = VectorXd::Zero(6); + + for (int i = 0; i < contact_surface.num_faces(); ++i) { + if (contact_surface.area(i) > .0001) { + std::cout << "face centroid: " << contact_surface.centroid(i) + << std::endl; + if (contact_surface.HasGradE_N()) { + std::cout << "Grad N" << contact_surface.EvaluateGradE_N_W(i) + << std::endl; + } + face_with_area += 1; + VectorXd wrench = VectorXd::Zero(6); + wrench << contact_surface.face_normal(i), + (contact_surface.centroid(i) - p_WCb) + .cross(contact_surface.face_normal(i)); + wrench_basis += contact_surface.area(i) * wrench; + } + } + std::cout << "wrench basis: " << wrench_basis << std::endl; + std::cout << "faces with non-negligible area: " << face_with_area + << std::endl; + int n_cols = (wrt == JacobianWrtVariable::kV) ? plant_.num_velocities() + : plant_.num_positions(); +// Matrix Jv_WCa(3, n_cols); + Matrix Js_V_ABp_E(6, n_cols); + plant_.CalcJacobianSpatialVelocity(context, wrt, frameM, contact_surface_signed_distance_pair.p_ACa, + plant_.world_frame(), + plant_.world_frame(), &Js_V_ABp_E); + plant_.CalcJacobianSpatialVelocity(context, wrt, frameM, contact_surface_signed_distance_pair.p_ACa, + plant_.world_frame(), + plant_.world_frame(), &Js_V_ABp_E); + contact_data.push_back(std::pair>(contact_surface_signed_distance_pair.distance, Js_V_ABp_E)); + geom_pairs_with_data.insert( + drake::SortedPair(contact_surface.id_M(), + contact_surface.id_N())); + } + + for (auto &contact_pair : contact_pairs_){ + if (geom_pairs_with_data.find(contact_pair) == geom_pairs_with_data.end()){ + auto geometry_id_M = contact_pair.first(); + auto geometry_id_N = contact_pair.second(); + const SignedDistancePair signed_distance_pair = + query_object.ComputeSignedDistancePairClosestPoints(geometry_id_M, + geometry_id_N); + const auto frame_A_id = inspector.GetFrameId(geometry_id_M); + const auto frame_B_id = inspector.GetFrameId(geometry_id_N); + const auto& frameA = plant_.GetBodyFromFrameId(frame_A_id)->body_frame(); + const auto& frameB = plant_.GetBodyFromFrameId(frame_B_id)->body_frame(); + + const Vector3d& p_ACa = + inspector.GetPoseInFrame(geometry_id_M).template cast() * + signed_distance_pair.p_ACa; + const Vector3d& p_BCb = + inspector.GetPoseInFrame(geometry_id_N).template cast() * + signed_distance_pair.p_BCb; + + int n_cols = (wrt == JacobianWrtVariable::kV) ? plant_.num_velocities() + : plant_.num_positions(); + Matrix Jv_WCa(3, n_cols); + Matrix Jv_WCb(3, n_cols); + + plant_.CalcJacobianTranslationalVelocity(context, wrt, frameA, p_ACa, + plant_.world_frame(), + plant_.world_frame(), &Jv_WCa); + plant_.CalcJacobianTranslationalVelocity(context, wrt, frameB, p_BCb, + plant_.world_frame(), + plant_.world_frame(), &Jv_WCb); + + const auto& R_WC = drake::math::RotationMatrix::MakeFromOneVector( + signed_distance_pair.nhat_BA_W, 0); + + // Standard case + auto J = force_basis * R_WC.matrix().transpose() * (Jv_WCa - Jv_WCb); + contact_data.push_back(std::pair>(signed_distance_pair.distance, J)); + } + } +} + +} // namespace multibody +} // namespace dairlib + +template class dairlib::multibody::HydroelasticGeomCollider; \ No newline at end of file diff --git a/multibody/hydroelastic_geom_collider.h b/multibody/hydroelastic_geom_collider.h new file mode 100644 index 0000000000..4606fad155 --- /dev/null +++ b/multibody/hydroelastic_geom_collider.h @@ -0,0 +1,85 @@ +#pragma once + +#include "drake/common/sorted_pair.h" +#include "drake/multibody/plant/multibody_plant.h" + +namespace dairlib { +namespace multibody { + +/// A class for computing collider properties as hydroelastic contact patches +/// This class attempts to compute hydroelastic contact data when available and +/// defaults to a single point contact per geometry pair if hydroelastic is not +/// available +template +class HydroelasticGeomCollider { + public: + /// Default constructor + /// Specifies the MultibodyPlant object, as well as the two geometries + /// + /// @param plant + /// @param geometry_id_A + /// @param geometry_id_B + HydroelasticGeomCollider( + const drake::multibody::MultibodyPlant& plant, + const std::vector>& contact_geoms); + + /// Calculates the distance and contact frame Jacobian. + /// Jacobian is ordered [J_n; J_t], and has shape 3 x (nq or nv), depending + /// on the choice of JacobianWrtVariable. + /// @param context The context for the MultibodyPlant + /// @return A pair with + std::vector>> Eval( + const drake::systems::Context& context, + drake::multibody::JacobianWrtVariable wrt = + drake::multibody::JacobianWrtVariable::kV); + + /// Calculates the distance and contact frame Jacobian. + /// Jacobian is ordered [J_n; J_t], and has shape + //// (2*num_friction_directions + 1) x (nq or nv), depending + /// on the choice of JacobianWrtVariable. + /// + /// Specifies the number of friction directions, used to + /// construct a polytope representation of friction with + /// (2 * num_friction_directions) faces. + /// Setting this to 0 is acceptable for frictionless contact + /// num_friction_directions != 1, as this would not be + /// well-defined in 3D. + /// + /// @param context The context for the MultibodyPlant + /// @param num_friction_directions + /// @return A pair with + std::vector>> EvalPolytope( + const drake::systems::Context& context, int num_friction_directions, + drake::multibody::JacobianWrtVariable wrt = + drake::multibody::JacobianWrtVariable::kV); + + /// Calculates the distance and contact frame Jacobian for a 2D planar problem + /// Jacobian is ordered [J_n; +J_t; -J_t], and has shape 3 x (nq). + /// J_t refers to the (contact_normal x planar_normal) direction + /// @param context The context for the MultibodyPlant + /// @param planar_normal The normal vector to the planar system + /// @return A pair with + std::vector>> EvalPlanar( + const drake::systems::Context& context, + const Eigen::Vector3d& planar_normal, + drake::multibody::JacobianWrtVariable wrt = + drake::multibody::JacobianWrtVariable::kV); + + std::vector> CalcWitnessPoints( + const drake::systems::Context& context); + + private: + std::vector>> DoEval( + const drake::systems::Context& context, + Eigen::Matrix force_basis, + drake::multibody::JacobianWrtVariable wrt, bool planar = false); + + const drake::multibody::MultibodyPlant& plant_; + const std::vector>& + contact_pairs_; +}; + +} // namespace multibody +} // namespace dairlib + +extern template class dairlib::multibody::HydroelasticGeomCollider; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 3fd206a33e..367b79492d 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -58,10 +58,10 @@ void LcmTrajectoryReceiver::OutputTrajectory( const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); if (trajectory_block.datapoints.rows() == 3) { - // *casted_traj = PiecewisePolynomial::FirstOrderHold( - // trajectory_block.time_vector, trajectory_block.datapoints); - *casted_traj = PiecewisePolynomial::ZeroOrderHold( + *casted_traj = PiecewisePolynomial::FirstOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); + // *casted_traj = PiecewisePolynomial::ZeroOrderHold( + // trajectory_block.time_vector, trajectory_block.datapoints); } else { *casted_traj = PiecewisePolynomial::CubicHermite( trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), @@ -311,8 +311,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( this->EvalInputValue( context, actor_trajectory_input_port_); const auto& robot_time_vec = - this->EvalVectorInput( - context, robot_time_input_port_); + this->EvalVectorInput(context, robot_time_input_port_); double robot_time = robot_time_vec->GetAtIndex(0); auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); const auto& force_trajectory_block = From 45f087fe566c10b6ab3d4f5ce7647686d0e7ede9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 1 Jan 2024 13:53:48 -0500 Subject: [PATCH 573/758] sliding almost working properly, sensitive to gap --- examples/franka/franka_visualizer.cc | 2 +- .../franka_c3_controller_params.yaml | 4 +- .../franka_c3_options_w_supports.yaml | 14 ++--- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../urdf/left_support_point_contact.urdf | 4 +- examples/franka/urdf/plate_end_effector.urdf | 2 +- .../urdf/plate_end_effector_massless.urdf | 32 +++++++++++ solvers/c3.cc | 55 ++++++++++--------- solvers/c3.h | 20 +++---- systems/controllers/c3_controller.cc | 3 +- .../lcm_trajectory_systems.cc | 2 +- 12 files changed, 89 insertions(+), 53 deletions(-) create mode 100644 examples/franka/urdf/plate_end_effector_massless.urdf diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 24ad5aa623..e3e19f3410 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -171,7 +171,7 @@ int do_main(int argc, char* argv[]) { builder.AddSystem>(plant); drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0 / 60.0; + params.publish_period = 1.0 / 30.0; params.enable_alpha_slider = true; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 9aa97d0a08..3ff4af80d0 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -12,7 +12,7 @@ plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf -scene_index: 0 +scene_index: 1 #left_support_model: examples/franka/urdf/left_support.urdf #right_support_model: examples/franka/urdf/left_support.urdf @@ -26,7 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.55, 0, 0.45] +neutral_position: [0.53, 0, 0.442] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 50a2869aaf..d786c7216d 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,6 +1,6 @@ admm_iter: 4 rho: 0 # does not do anything -rho_scale: 3 +rho_scale: 2.1 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -10,7 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: false -mu: [0.8, 0.8, 0.8, 0.05, 0.05, 0.05, 0.05] +mu: [0.8, 0.8, 0.8, 0.1, 0.1, 0.1, 0.1] dt: 0.08 solve_dt: 0.05 num_friction_directions: 2 @@ -21,23 +21,23 @@ N: 5 w_Q: 50 w_R: 5 # Penalty on all decision variables, assuming scalar -w_G: 1 +w_G: 0.1 # Penalty on all decision variables, assuming scalar -w_U: 0.5 +w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 1000, 1000, 1000, 1000, 15000, 15000, 15000, +q_vector: [175, 175, 175, 400, 400, 400, 400, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] # Penalty on matching projected variables -g_x: [100, 100, 100, 1, 1, 1, 1, 1, 1, 1, 2, 2, 2, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [20, 20, 5] +g_u: [1, 1, 1] u_x: [10, 10, 10, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 1d1f5bbf10..2246c514ff 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -1,7 +1,7 @@ controller_frequency: 1000 franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf -end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_model: examples/franka/urdf/plate_end_effector_massless.urdf end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b04e2392e9..2fa59111a2 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -11,7 +11,7 @@ franka_publish_rate: 1000 tray_publish_rate: 1000 actuator_delay: 0.000 -scene_index: 0 +scene_index: 1 visualize: true publish_efforts: true diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index 65da54dc3a..daf9ff9e5b 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,13 +13,13 @@ izz="0.013"/> - + - + diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 8e5b77e75b..b81d96de63 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -22,7 +22,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_massless.urdf b/examples/franka/urdf/plate_end_effector_massless.urdf new file mode 100644 index 0000000000..6985b79727 --- /dev/null +++ b/examples/franka/urdf/plate_end_effector_massless.urdf @@ -0,0 +1,32 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/solvers/c3.cc b/solvers/c3.cc index 003d0129f6..c1b8ebfe43 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -55,7 +55,7 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, n_((LCS.A_)[0].cols()), m_((LCS.D_)[0].cols()), k_((LCS.B_)[0].cols()), - hflag_(H_[0].isZero(0)), + h_is_zero_(H_[0].isZero(0)), prog_(MathematicalProgram()), solver_options_(SolverOptions()), osqp_(OsqpSolver()) { @@ -124,75 +124,80 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, prog_.AddQuadraticCost(2 * Q_.at(i), -2 * Q_.at(i) * xdesired_.at(i), x_.at(i), 1); if (i < N_) { - input_costs_[i] = prog_.AddQuadraticCost(2 * R_.at(i), VectorXd::Zero(k_), u_.at(i), 1).evaluator(); + input_costs_[i] = + prog_.AddQuadraticCost(2 * R_.at(i), VectorXd::Zero(k_), u_.at(i), 1) + .evaluator(); } } } -vector C3::Solve(const VectorXd& x0, vector& delta, - vector& w) { +void C3::Solve(const VectorXd& x0, vector& delta, + vector& w) { vector Gv = G_; VectorXd z; - for (int i = 0; i < N_; ++i){ - input_costs_[i]->UpdateCoefficients(2 * R_.at(i), -2 * R_.at(i) * u_sol_->at(i)); + for (int i = 0; i < N_; ++i) { + input_costs_[i]->UpdateCoefficients(2 * R_.at(i), + -2 * R_.at(i) * u_sol_->at(i)); } -// input_costs_[0]->UpdateCoefficients(2 * R_.at(0), -2 * R_.at(0) * u_sol_->at(0)); for (int i = 0; i < options_.admm_iter - 1; i++) { - z = ADMMStep(x0, &delta, &w, &Gv); + ADMMStep(x0, &delta, &w, &Gv); } vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { WD.at(i) = delta.at(i) - w.at(i); } - vector zfin = SolveQP(x0, Gv, WD, true); - return zfin; + + *z_sol_ = delta; + z_sol_->at(0).segment(0, n_) = x0; + for (int i = 1; i < N_; ++i) { + z_sol_->at(i).segment(0, n_) = + A_.at(i) * x_sol_->at(i - 1) + B_.at(i) * u_sol_->at(i - 1) + + D_.at(i) * lambda_sol_->at(i - 1) + d_.at(i - 1); + } } -VectorXd C3::ADMMStep(const VectorXd& x0, vector* delta, - vector* w, vector* Gv) { +void C3::ADMMStep(const VectorXd& x0, vector* delta, + vector* w, vector* Gv) { vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { WD.at(i) = delta->at(i) - w->at(i); } - vector z = SolveQP(x0, *Gv, WD); + vector z = SolveQP(x0, *Gv, WD, true); vector ZW(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { ZW[i] = w->at(i) + z[i]; } - if (U_[0].isZero(0) == 0) { - vector Uv = U_; + if (U_[0].isZero(0)) { + *delta = SolveProjection(*Gv, ZW); - *delta = SolveProjection(Uv, ZW); } else { - *delta = SolveProjection(*Gv, ZW); + *delta = SolveProjection(U_, ZW); } +// *z_sol_ = *delta; for (int i = 0; i < N_; i++) { w->at(i) = w->at(i) + z[i] - delta->at(i); w->at(i) = w->at(i) / options_.rho_scale; - Gv->at(i) = Gv->at(i) * options_.rho_scale; } - - return z[0]; } -vector C3::SolveQP(const VectorXd& x0, vector& G, - vector& WD, bool is_final_solve) { +vector C3::SolveQP(const VectorXd& x0, const vector& G, + const vector& WD, bool is_final_solve) { for (auto& constraint : constraints_) { prog_.RemoveConstraint(constraint); } constraints_.clear(); constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); - if (hflag_ == 1) { + if (h_is_zero_ == 1) { std::cout << "solving lcp: " << std::endl; drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; @@ -238,7 +243,7 @@ vector C3::SolveQP(const VectorXd& x0, vector& G, if (result.is_success()) { for (int i = 0; i < N_; i++) { - if (is_final_solve){ + if (is_final_solve) { x_sol_->at(i) = result.GetSolution(x_[i]); lambda_sol_->at(i) = result.GetSolution(lambda_[i]); u_sol_->at(i) = result.GetSolution(u_[i]); @@ -293,7 +298,7 @@ void C3::RemoveConstraints() { user_constraints_.clear(); } -vector C3::SolveProjection(vector& G, +vector C3::SolveProjection(const vector& G, vector& WZ) { vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); int i; diff --git a/solvers/c3.h b/solvers/c3.h index fe26ff93e1..516c027424 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -37,34 +37,32 @@ class C3 { /// @param delta A pointer to the copy variable solution /// @param w A pointer to the scaled dual variable solution /// @return The first control action to take, u[0] - std::vector Solve(const Eigen::VectorXd& x0, - std::vector& delta, - std::vector& w); + void Solve(const Eigen::VectorXd& x0, std::vector& delta, + std::vector& w); /// Solve a single ADMM step /// @param x0 The initial state of the system /// @param delta The copy variables from the previous step /// @param w The scaled dual variables from the previous step /// @param G A pointer to the G variables from previous step - Eigen::VectorXd ADMMStep(const Eigen::VectorXd& x0, - std::vector* delta, - std::vector* w, - std::vector* G); + void ADMMStep(const Eigen::VectorXd& x0, std::vector* delta, + std::vector* w, + std::vector* G); /// Solve a single QP /// @param x0 The initial state of the system /// @param WD A pointer to the (w - delta) variables /// @param G A pointer to the G variables from previous step std::vector SolveQP(const Eigen::VectorXd& x0, - std::vector& G, - std::vector& WD, + const std::vector& G, + const std::vector& WD, bool is_final_solve = false); /// Solve the projection problem for all timesteps /// @param WZ A pointer to the (z + w) variables /// @param G A pointer to the G variables from previous step std::vector SolveProjection( - std::vector& G, std::vector& WZ); + const std::vector& G, std::vector& WZ); /// allow users to add constraints (adds for all timesteps) /// @param A, lower_bound, upper_bound lower_bound <= A^T x <= upper_bound @@ -118,7 +116,7 @@ class C3 { const int n_; const int m_; const int k_; - const bool hflag_; + const bool h_is_zero_; protected: std::vector warm_start_delta_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 80e774c62a..761b192665 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -193,7 +193,8 @@ void C3Controller::OutputC3Solution( void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { - double t = context.get_discrete_state(plan_start_time_index_)[0] + solve_time_; + double t = + context.get_discrete_state(plan_start_time_index_)[0] + solve_time_; for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 367b79492d..35f8606080 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -318,7 +318,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( lcm_traj.GetTrajectory(force_trajectory_name_); const auto& actor_trajectory_block = lcm_traj.GetTrajectory(actor_trajectory_name_); - auto force_trajectory = PiecewisePolynomial::ZeroOrderHold( + auto force_trajectory = PiecewisePolynomial::FirstOrderHold( force_trajectory_block.time_vector, force_trajectory_block.datapoints); VectorXd pose; if (actor_trajectory_block.datapoints.rows() == 3) { From 8167d26aa985accca758c8f1320d1adc28264aff Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 2 Jan 2024 15:25:16 -0500 Subject: [PATCH 574/758] some more tuning --- .../franka/parameters/franka_c3_options_w_supports.yaml | 6 +++--- examples/franka/parameters/franka_c3_qp_settings.yaml | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index d786c7216d..ebab286d98 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,6 +1,6 @@ -admm_iter: 4 +admm_iter: 2 rho: 0 # does not do anything -rho_scale: 2.1 +rho_scale: 8 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -8,7 +8,7 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' -warm_start: false +warm_start: true mu: [0.8, 0.8, 0.8, 0.1, 0.1, 0.1, 0.1] dt: 0.08 diff --git a/examples/franka/parameters/franka_c3_qp_settings.yaml b/examples/franka/parameters/franka_c3_qp_settings.yaml index 8dc5e369ea..b136c938f3 100644 --- a/examples/franka/parameters/franka_c3_qp_settings.yaml +++ b/examples/franka/parameters/franka_c3_qp_settings.yaml @@ -12,7 +12,7 @@ int_options: scaled_termination: 1 check_termination: 100 double_options: - rho: 0.001 + rho: 0.1 sigma: 1e-6 eps_abs: 1e-5 eps_rel: 1e-5 From 3cd7810eeebfcaadd8300737e3b8cda80a569c7b Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 2 Jan 2024 15:25:27 -0500 Subject: [PATCH 575/758] warm starting c3, not clear if it helps --- solvers/c3.cc | 205 +++++++++++++++++---------- solvers/c3.h | 83 ++++++----- solvers/c3_miqp.cc | 45 +++--- solvers/c3_miqp.h | 14 +- solvers/c3_options.h | 10 +- solvers/c3_qp.cc | 19 +-- solvers/c3_qp.h | 23 +-- systems/controllers/c3_controller.cc | 128 ++++++++++------- systems/controllers/c3_controller.h | 2 + 9 files changed, 289 insertions(+), 240 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index c1b8ebfe43..920696ef67 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -29,15 +29,24 @@ using drake::solvers::OsqpSolver; using drake::solvers::OsqpSolverDetails; using drake::solvers::Solve; -C3::C3(const LCS& LCS, const vector& Q, const vector& R, - const vector& G, const vector& U, - const vector& xdesired, const C3Options& options, - const std::vector& warm_start_delta, - const std::vector& warm_start_binary, - const std::vector& warm_start_x, - const std::vector& warm_start_lambda, - const std::vector& warm_start_u, bool warm_start) - : A_(LCS.A_), +C3::CostMatrices::CostMatrices(const std::vector& Q, + const std::vector& R, + const std::vector& G, + const std::vector& U) { + this->Q = Q; + this->R = R; + this->G = G; + this->U = U; +} + +C3::C3(const LCS& LCS, const C3::CostMatrices& costs, + const vector& x_desired, const C3Options& options) + : warm_start_(options.warm_start), + N_((LCS.A_).size()), + n_((LCS.A_)[0].cols()), + m_((LCS.D_)[0].cols()), + k_((LCS.B_)[0].cols()), + A_(LCS.A_), B_(LCS.B_), D_(LCS.D_), d_(LCS.d_), @@ -45,42 +54,43 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, F_(LCS.F_), H_(LCS.H_), c_(LCS.c_), - Q_(Q), - R_(R), - U_(U), - G_(G), - xdesired_(xdesired), + Q_(costs.Q), + R_(costs.R), + U_(costs.U), + G_(costs.G), + x_desired_(x_desired), options_(options), - N_((LCS.A_).size()), - n_((LCS.A_)[0].cols()), - m_((LCS.D_)[0].cols()), - k_((LCS.B_)[0].cols()), h_is_zero_(H_[0].isZero(0)), prog_(MathematicalProgram()), solver_options_(SolverOptions()), osqp_(OsqpSolver()) { - // Deep copy warm start - warm_start_ = warm_start; if (warm_start_) { - warm_start_delta_.resize(warm_start_delta.size()); - for (size_t i = 0; i < warm_start_delta.size(); i++) { - warm_start_delta_[i] = warm_start_delta[i]; - } - warm_start_binary_.resize(warm_start_binary.size()); - for (size_t i = 0; i < warm_start_binary.size(); i++) { - warm_start_binary_[i] = warm_start_binary[i]; - } - warm_start_x_.resize(warm_start_x.size()); - for (size_t i = 0; i < warm_start_x.size(); i++) { - warm_start_x_[i] = warm_start_x[i]; - } - warm_start_lambda_.resize(warm_start_lambda.size()); - for (size_t i = 0; i < warm_start_lambda.size(); i++) { - warm_start_lambda_[i] = warm_start_lambda[i]; - } - warm_start_u_.resize(warm_start_u.size()); - for (size_t i = 0; i < warm_start_u.size(); i++) { - warm_start_u_[i] = warm_start_u[i]; + warm_start_delta_.resize(options_.admm_iter); + warm_start_binary_.resize(options_.admm_iter); + warm_start_x_.resize(options_.admm_iter); + warm_start_lambda_.resize(options_.admm_iter); + warm_start_u_.resize(options_.admm_iter); + for (size_t iter = 0; iter < options_.admm_iter; ++iter) { + warm_start_delta_[iter].resize(N_); + for (size_t i = 0; i < N_; i++) { + warm_start_delta_[iter][i] = VectorXd::Zero(n_ + m_ + k_); + } + warm_start_binary_[iter].resize(N_); + for (size_t i = 0; i < N_; i++) { + warm_start_binary_[iter][i] = VectorXd::Zero(m_); + } + warm_start_x_[iter].resize(N_ + 1); + for (size_t i = 0; i < N_ + 1; i++) { + warm_start_x_[iter][i] = VectorXd::Zero(n_); + } + warm_start_lambda_[iter].resize(N_); + for (size_t i = 0; i < N_; i++) { + warm_start_lambda_[iter][i] = VectorXd::Zero(m_); + } + warm_start_u_[iter].resize(N_); + for (size_t i = 0; i < N_; i++) { + warm_start_u_[iter][i] = VectorXd::Zero(k_); + } } } @@ -110,19 +120,33 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, MatrixXd LinEq(n_, 2 * n_ + m_ + k_); LinEq.block(0, n_ + m_ + k_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); + dynamics_constraints_.resize(N_); + target_cost_.resize(N_ + 1); for (int i = 0; i < N_; i++) { LinEq.block(0, 0, n_, n_) = A_.at(i); LinEq.block(0, n_, n_, m_) = D_.at(i); LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); - prog_.AddLinearEqualityConstraint( - LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}); + // prog_.AddLinearEqualityConstraint( + // LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + + // 1)}); + dynamics_constraints_[i] = + prog_ + .AddLinearEqualityConstraint( + LinEq, -d_.at(i), + {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}) + .evaluator() + .get(); // prog_.AddLinearConstraint(lambda_.at(i) >= VectorXd::Zero(m_)); } input_costs_.resize(N_); for (int i = 0; i < N_ + 1; i++) { - prog_.AddQuadraticCost(2 * Q_.at(i), -2 * Q_.at(i) * xdesired_.at(i), - x_.at(i), 1); + target_cost_[i] = + prog_ + .AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * x_desired_.at(i), + x_.at(i), 1) + .evaluator() + .get(); if (i < N_) { input_costs_[i] = prog_.AddQuadraticCost(2 * R_.at(i), VectorXd::Zero(k_), u_.at(i), 1) @@ -131,18 +155,49 @@ C3::C3(const LCS& LCS, const vector& Q, const vector& R, } } +void C3::UpdateLCS(const LCS& lcs) { + // first 4 lines are unnecessary + A_ = lcs.A_; + B_ = lcs.B_; + D_ = lcs.D_; + d_ = lcs.d_; + E_ = lcs.E_; + F_ = lcs.F_; + H_ = lcs.H_; + c_ = lcs.c_; + h_is_zero_ = H_[0].isZero(0); + + MatrixXd LinEq = MatrixXd::Zero(n_, 2 * n_ + m_ + k_); + LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); + + for (int i = 0; i < N_; i++) { + LinEq.block(0, 0, n_, n_) = A_.at(i); + LinEq.block(0, n_, n_, m_) = D_.at(i); + LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); + + dynamics_constraints_[i]->UpdateCoefficients(LinEq, -lcs.d_.at(i)); + } +} + +void C3::UpdateTarget(const std::vector& x_des) { + x_desired_ = x_des; + for (int i = 0; i < N_ + 1; i++) { + target_cost_[i]->UpdateCoefficients(Q_.at(i) * 2, + -2 * Q_.at(i) * x_desired_.at(i)); + } +} + void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; - VectorXd z; for (int i = 0; i < N_; ++i) { input_costs_[i]->UpdateCoefficients(2 * R_.at(i), -2 * R_.at(i) * u_sol_->at(i)); } - for (int i = 0; i < options_.admm_iter - 1; i++) { - ADMMStep(x0, &delta, &w, &Gv); + for (int iter = 0; iter < options_.admm_iter; iter++) { + ADMMStep(x0, &delta, &w, &Gv, iter); } vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); @@ -160,14 +215,15 @@ void C3::Solve(const VectorXd& x0, vector& delta, } void C3::ADMMStep(const VectorXd& x0, vector* delta, - vector* w, vector* Gv) { + vector* w, vector* Gv, + int admm_iteration) { vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { WD.at(i) = delta->at(i) - w->at(i); } - vector z = SolveQP(x0, *Gv, WD, true); + vector z = SolveQP(x0, *Gv, WD, admm_iteration, true); vector ZW(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { @@ -175,12 +231,11 @@ void C3::ADMMStep(const VectorXd& x0, vector* delta, } if (U_[0].isZero(0)) { - *delta = SolveProjection(*Gv, ZW); + *delta = SolveProjection(*Gv, ZW, admm_iteration); } else { - *delta = SolveProjection(U_, ZW); + *delta = SolveProjection(U_, ZW, admm_iteration); } -// *z_sol_ = *delta; for (int i = 0; i < N_; i++) { w->at(i) = w->at(i) + z[i] - delta->at(i); @@ -190,7 +245,8 @@ void C3::ADMMStep(const VectorXd& x0, vector* delta, } vector C3::SolveQP(const VectorXd& x0, const vector& G, - const vector& WD, bool is_final_solve) { + const vector& WD, int admm_iteration, + bool is_final_solve) { for (auto& constraint : constraints_) { prog_.RemoveConstraint(constraint); } @@ -198,7 +254,6 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); if (h_is_zero_ == 1) { - std::cout << "solving lcp: " << std::endl; drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); @@ -229,14 +284,14 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, } // /// initialize decision variables to warm start - // if (warm_start_) { - // for (int i = 0; i < N_; i++) { - // prog_.SetInitialGuess(x_[i], warm_start_x_[i]); - // prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[i]); - // prog_.SetInitialGuess(u_[i], warm_start_u_[i]); - // } - // prog_.SetInitialGuess(x_[N_], warm_start_x_[N_]); - // } + if (warm_start_) { + for (int i = 0; i < N_; i++) { + prog_.SetInitialGuess(x_[i], warm_start_x_[admm_iteration][i]); + prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[admm_iteration][i]); + prog_.SetInitialGuess(u_[i], warm_start_u_[admm_iteration][i]); + } + prog_.SetInitialGuess(x_[N_], warm_start_x_[admm_iteration][N_]); + } prog_.SetSolverOptions(solver_options_); MathematicalProgramResult result = osqp_.Solve(prog_); @@ -254,13 +309,13 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, if (warm_start_) { // update warm start parameters - warm_start_x_[i] = result.GetSolution(x_[i]); - warm_start_lambda_[i] = result.GetSolution(lambda_[i]); - warm_start_u_[i] = result.GetSolution(u_[i]); + warm_start_x_[admm_iteration][i] = result.GetSolution(x_[i]); + warm_start_lambda_[admm_iteration][i] = result.GetSolution(lambda_[i]); + warm_start_u_[admm_iteration][i] = result.GetSolution(u_[i]); } } if (warm_start_) { - warm_start_x_[N_] = result.GetSolution(x_[N_]); + warm_start_x_[admm_iteration][N_] = result.GetSolution(x_[N_]); } } @@ -299,7 +354,7 @@ void C3::RemoveConstraints() { } vector C3::SolveProjection(const vector& G, - vector& WZ) { + vector& WZ, int admm_iteration) { vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); int i; @@ -312,24 +367,28 @@ vector C3::SolveProjection(const vector& G, #pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { if (warm_start_) { - deltaProj[i] = - SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], i); + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, i); } else { - deltaProj[i] = - SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], -1); + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, -1); } } return deltaProj; } -std::vector C3::GetWarmStartX() const { return warm_start_x_; } +std::vector C3::GetWarmStartX() const { + return warm_start_x_[0]; +} std::vector C3::GetWarmStartLambda() const { - return warm_start_lambda_; + return warm_start_lambda_[0]; } -std::vector C3::GetWarmStartU() const { return warm_start_u_; } +std::vector C3::GetWarmStartU() const { + return warm_start_u_[0]; +} } // namespace solvers } // namespace dairlib diff --git a/solvers/c3.h b/solvers/c3.h index 516c027424..a6a709ddee 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -14,21 +14,24 @@ namespace dairlib { namespace solvers { + class C3 { public: + struct CostMatrices { + CostMatrices() = default; + CostMatrices(const std::vector& Q, + const std::vector& R, + const std::vector& G, + const std::vector& U); + std::vector Q; + std::vector R; + std::vector G; + std::vector U; + }; /// @param LCS LCS parameters /// @param Q, R, G, U Cost function parameters - C3(const LCS& LCS, const std::vector& Q, - const std::vector& R, - const std::vector& G, - const std::vector& U, - const std::vector& xdesired, const C3Options& options, - const std::vector& warm_start_delta = {}, - const std::vector& warm_start_binary = {}, - const std::vector& warm_start_x_ = {}, - const std::vector& warm_start_lambda_ = {}, - const std::vector& warm_start_u_ = {}, - bool warm_start = false); + C3(const LCS& LCS, const CostMatrices& costs, + const std::vector& x_desired, const C3Options& options); virtual ~C3() = default; @@ -47,7 +50,8 @@ class C3 { /// @param G A pointer to the G variables from previous step void ADMMStep(const Eigen::VectorXd& x0, std::vector* delta, std::vector* w, - std::vector* G); + std::vector* G, + int admm_iteration); /// Solve a single QP /// @param x0 The initial state of the system @@ -56,13 +60,15 @@ class C3 { std::vector SolveQP(const Eigen::VectorXd& x0, const std::vector& G, const std::vector& WD, + int admm_iteration, bool is_final_solve = false); /// Solve the projection problem for all timesteps /// @param WZ A pointer to the (z + w) variables /// @param G A pointer to the G variables from previous step std::vector SolveProjection( - const std::vector& G, std::vector& WZ); + const std::vector& G, std::vector& WZ, + int admm_iteration); /// allow users to add constraints (adds for all timesteps) /// @param A, lower_bound, upper_bound lower_bound <= A^T x <= upper_bound @@ -86,6 +92,7 @@ class C3 { const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, + const int admm_iteration, const int& warm_start_index) = 0; void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { @@ -98,41 +105,47 @@ class C3 { std::vector GetInputSolution() { return *u_sol_; } public: - const std::vector A_; - const std::vector B_; - const std::vector D_; - const std::vector d_; - const std::vector E_; - const std::vector F_; - const std::vector H_; - const std::vector c_; + void UpdateLCS(const LCS& lcs); + void UpdateTarget(const std::vector& x_des); + + protected: + std::vector> warm_start_delta_; + std::vector> warm_start_binary_; + std::vector> warm_start_x_; + std::vector> warm_start_lambda_; + std::vector> warm_start_u_; + bool warm_start_; + const int N_; + const int n_; + const int m_; + const int k_; + + private: + std::vector A_; + std::vector B_; + std::vector D_; + std::vector d_; + std::vector E_; + std::vector F_; + std::vector H_; + std::vector c_; const std::vector Q_; const std::vector R_; const std::vector U_; const std::vector G_; - const std::vector xdesired_; + std::vector x_desired_; const C3Options options_; - const int N_; - const int n_; - const int m_; - const int k_; - const bool h_is_zero_; - protected: - std::vector warm_start_delta_; - std::vector warm_start_binary_; - std::vector warm_start_x_; - std::vector warm_start_lambda_; - std::vector warm_start_u_; - bool warm_start_; + bool h_is_zero_; - private: drake::solvers::MathematicalProgram prog_; drake::solvers::SolverOptions solver_options_; drake::solvers::OsqpSolver osqp_; std::vector x_; std::vector u_; std::vector lambda_; + std::vector dynamics_constraints_; + std::vector target_cost_; std::vector> costs_; std::vector> input_costs_; std::vector> diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index deca99c0c4..5767ad5007 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -7,21 +7,9 @@ using Eigen::MatrixXd; using Eigen::VectorXd; using std::vector; -C3MIQP::C3MIQP(const LCS& LCS, const vector& Q, - const vector& R, const vector& G, - const vector& U, const vector& xdesired, - const C3Options& options, - const std::vector& warm_start_delta, - const std::vector& warm_start_binary, - const std::vector& warm_start_x, - const std::vector& warm_start_lambda, - const std::vector& warm_start_u, - bool warm_start) - : C3(LCS, Q, R, G, U, xdesired, options, - warm_start_delta, warm_start_binary, - warm_start_x, warm_start_lambda, - warm_start_u, warm_start), env_(true) { - +C3MIQP::C3MIQP(const LCS& LCS, const CostMatrices& costs, + const vector& xdesired, const C3Options& options) + : C3(LCS, costs, xdesired, options), env_(true) { // Create an environment // env_.set("LogToConsole", "0"); env_.set("OutputFlag", "0"); @@ -33,6 +21,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, const MatrixXd& E, const MatrixXd& F, const MatrixXd& H, const VectorXd& c, + const int admm_iteration, const int& warm_start_index) { // set up linear term in cost VectorXd cost_lin = -2 * delta_c.transpose() * U; @@ -56,8 +45,8 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, GRBModel model = GRBModel(env_); // model.set(GRB_IntParam_LogToConsole, 1); // model.set(GRB_StringParam_LogFile, "grb_debug"); - //model.set("FeasibilityTol", "0.01"); - //model.set("IterationLimit", "40"); + // model.set("FeasibilityTol", "0.01"); + // model.set("IterationLimit", "40"); GRBVar delta_k[n_ + m_ + k_]; GRBVar binary[m_]; @@ -65,14 +54,16 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, for (int i = 0; i < m_; i++) { binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); if (warm_start_index != -1) { - binary[i].set(GRB_DoubleAttr_Start, warm_start_binary_[warm_start_index](i)); + binary[i].set(GRB_DoubleAttr_Start, + warm_start_binary_[admm_iteration][warm_start_index](i)); } } for (int i = 0; i < n_ + m_ + k_; i++) { delta_k[i] = model.addVar(-10000.0, 10000.0, 0.0, GRB_CONTINUOUS); if (warm_start_index != -1) { - delta_k[i].set(GRB_DoubleAttr_Start, warm_start_delta_[warm_start_index](i)); + delta_k[i].set(GRB_DoubleAttr_Start, + warm_start_delta_[admm_iteration][warm_start_index](i)); } } @@ -123,23 +114,23 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, for (int i = 0; i < n_ + m_ + k_; i++) { delta_kc(i) = delta_k[i].get(GRB_DoubleAttr_X); } - for (int i = 0; i < m_; i++){ + for (int i = 0; i < m_; i++) { binaryc(i) = binary[i].get(GRB_DoubleAttr_X); } - if (warm_start_index != -1){ - warm_start_delta_[warm_start_index] = delta_kc; - warm_start_binary_[warm_start_index] = binaryc; + if (warm_start_index != -1) { + warm_start_delta_[admm_iteration][warm_start_index] = delta_kc; + warm_start_binary_[admm_iteration][warm_start_index] = binaryc; } return delta_kc; } -std::vector C3MIQP::GetWarmStartDelta() const{ - return warm_start_delta_; +std::vector C3MIQP::GetWarmStartDelta() const { + return warm_start_delta_[0]; } -std::vector C3MIQP::GetWarmStartBinary() const{ - return warm_start_binary_; +std::vector C3MIQP::GetWarmStartBinary() const { + return warm_start_binary_[0]; } } // namespace solvers diff --git a/solvers/c3_miqp.h b/solvers/c3_miqp.h index 9b6cd34a06..96db21f011 100644 --- a/solvers/c3_miqp.h +++ b/solvers/c3_miqp.h @@ -14,17 +14,8 @@ namespace solvers { class C3MIQP final : public C3 { public: /// Default constructor for time-varying LCS - C3MIQP(const LCS& LCS, const std::vector& Q, - const std::vector& R, - const std::vector& G, - const std::vector& U, - const std::vector& xdesired, const C3Options& options, - const std::vector& warm_start_delta = {}, - const std::vector& warm_start_binary = {}, - const std::vector& warm_start_x = {}, - const std::vector& warm_start_lambda = {}, - const std::vector& warm_start_u = {}, - bool warm_start = false); + C3MIQP(const LCS& LCS, const CostMatrices& costs, + const std::vector& xdesired, const C3Options& options); ~C3MIQP() override = default; @@ -35,6 +26,7 @@ class C3MIQP final : public C3 { const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, + const int admm_iteration, const int& warm_start_index = -1) override; std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index bcdb4ed9b2..a6ba41bbaa 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -5,9 +5,9 @@ struct C3Options { // Hyperparameters - int admm_iter; // total number of ADMM iterations //2 - float rho; // inital value of the rho parameter - float rho_scale; // scaling of rho parameter (/rho = rho_scale * /rho) //3 + int admm_iter; // total number of ADMM iterations + float rho; // initial value of the rho parameter + float rho_scale; // scaling of rho parameter (/rho = rho_scale * /rho) int num_threads; // 0 is dynamic, greater than 0 for a fixed count int delta_option; // different options for delta update std::string projection_type; @@ -73,18 +73,14 @@ struct C3Options { a->Visit(DRAKE_NVP(w_R)); a->Visit(DRAKE_NVP(w_G)); a->Visit(DRAKE_NVP(w_U)); - // a->Visit(DRAKE_NVP(g_size)); - // a->Visit(DRAKE_NVP(u_size)); a->Visit(DRAKE_NVP(q_vector)); a->Visit(DRAKE_NVP(r_vector)); - // a->Visit(DRAKE_NVP(g_vector)); a->Visit(DRAKE_NVP(g_x)); a->Visit(DRAKE_NVP(g_gamma)); a->Visit(DRAKE_NVP(g_lambda_n)); a->Visit(DRAKE_NVP(g_lambda_t)); a->Visit(DRAKE_NVP(g_lambda)); a->Visit(DRAKE_NVP(g_u)); - // a->Visit(DRAKE_NVP(u_vector)); a->Visit(DRAKE_NVP(u_x)); a->Visit(DRAKE_NVP(u_gamma)); a->Visit(DRAKE_NVP(u_lambda_n)); diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc index f846f6c40f..0c0112502a 100644 --- a/solvers/c3_qp.cc +++ b/solvers/c3_qp.cc @@ -27,21 +27,14 @@ using drake::solvers::OsqpSolver; using drake::solvers::OsqpSolverDetails; using drake::solvers::Solve; -C3QP::C3QP(const LCS& LCS, const vector& Q, const vector& R, - const vector& G, const vector& U, - const vector& xdesired, const C3Options& options, - const std::vector& warm_start_delta, - const std::vector& warm_start_binary, - const std::vector& warm_start_x, - const std::vector& warm_start_lambda, - const std::vector& warm_start_u, bool warm_start) - : C3(LCS, Q, R, G, U, xdesired, options, warm_start_delta, - warm_start_binary, warm_start_x, warm_start_lambda, warm_start_u, - warm_start) {} +C3QP::C3QP(const LCS& LCS, const CostMatrices& costs, + const vector& xdesired, const C3Options& options) + : C3(LCS, costs, xdesired, options) {} VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, const MatrixXd& E, const MatrixXd& F, const MatrixXd& H, const VectorXd& c, + const int admm_iteration, const int& warm_start_index) { drake::solvers::MathematicalProgram prog; drake::solvers::SolverOptions solver_options; @@ -104,11 +97,11 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, } std::vector C3QP::GetWarmStartDelta() const { - return warm_start_delta_; + return warm_start_delta_[0]; } std::vector C3QP::GetWarmStartBinary() const { - return warm_start_binary_; + return warm_start_binary_[0]; } } // namespace solvers diff --git a/solvers/c3_qp.h b/solvers/c3_qp.h index 189f864a94..c308baaf26 100644 --- a/solvers/c3_qp.h +++ b/solvers/c3_qp.h @@ -23,18 +23,9 @@ namespace solvers { class C3QP final : public C3 { public: /// Default constructor for time-varying LCS - C3QP(const LCS& LCS, const std::vector& Q, - const std::vector& R, - const std::vector& G, - const std::vector& U, + C3QP(const LCS& LCS, const CostMatrices& costs, const std::vector& xdesired, - const C3Options& options, - const std::vector& warm_start_delta = {}, - const std::vector& warm_start_binary = {}, - const std::vector& warm_start_x = {}, - const std::vector& warm_start_lambda = {}, - const std::vector& warm_start_u = {}, - bool warm_start = false); + const C3Options& options); ~C3QP() override = default; @@ -45,19 +36,11 @@ class C3QP final : public C3 { const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, + const int admm_iteration, const int& warm_start_index = -1) override; std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; - -// private: -// GRBEnv env_; - //drake::solvers::MathematicalProgram projprog_; - //drake::solvers::SolverOptions OSQPoptions_; - //drake::solvers::OsqpSolver osqp_; -// drake::solvers::VectorXDecisionVariable xn_; -// drake::solvers::VectorXDecisionVariable un_; -// drake::solvers::VectorXDecisionVariable ln_; }; } // namespace solvers diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 761b192665..d738a8d989 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -17,6 +17,7 @@ using Eigen::MatrixXd; using Eigen::MatrixXf; using Eigen::VectorXd; using Eigen::VectorXf; +using solvers::C3; using solvers::C3MIQP; using solvers::C3QP; using solvers::LCS; @@ -41,6 +42,7 @@ C3Controller::C3Controller( n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); + n_u_ = plant_.num_actuators(); n_x_ = n_q_ + n_v_; dt_ = c3_options_.dt; if (c3_options_.contact_model == "stewart_and_trinkle") { @@ -54,22 +56,56 @@ C3Controller::C3Controller( n_u_ = plant_.num_actuators(); + // Creates placeholder lcs to construct base C3 problem + // Placeholder LCS will have correct size as it's already determined by the + // contact model + auto lcs_placeholder = CreatePlaceholderLCS(); + auto x_desired_placeholder = + std::vector(N_ + 1, VectorXd::Zero(n_x_)); + if (c3_options_.projection_type == "MIQP") { + c3_ = std::make_unique(lcs_placeholder, + C3::CostMatrices(Q_, R_, G_, U_), + x_desired_placeholder, c3_options_); + + } else if (c3_options_.projection_type == "QP") { + c3_ = std::make_unique(lcs_placeholder, + C3::CostMatrices(Q_, R_, G_, U_), + x_desired_placeholder, c3_options_); + + } else { + std::cerr << ("Unknown projection type") << std::endl; + DRAKE_THROW_UNLESS(false); + } + + c3_->SetOsqpSolverOptions(solver_options_); + + // Set actor bounds + for (int i : vector({0, 2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, 0.35, 0.6, 1); + } + for (int i : vector({1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, -0.2, 0.2, 1); + } + for (int i : vector({0, 1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, -10, 10, 2); + } + for (int i : vector({2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, 0, 20, 2); + } + lcs_state_input_port_ = this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) .get_index(); - - MatrixXd A = MatrixXd::Zero(n_x_, n_x_); - MatrixXd B = MatrixXd::Zero(n_x_, n_u_); - VectorXd d = VectorXd::Zero(n_x_); - MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); - MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); - MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); - MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); - VectorXd c = VectorXd::Zero(n_lambda_); - auto lcs = LCS(A, B, D, d, E, F, H, c, N_, dt_); - lcs_input_port_ = - this->DeclareAbstractInputPort("lcs", drake::Value(lcs)).get_index(); + this->DeclareAbstractInputPort("lcs", drake::Value(lcs_placeholder)).get_index(); target_input_port_ = this->DeclareVectorInputPort("x_lcs_des", n_x_).get_index(); @@ -96,6 +132,18 @@ C3Controller::C3Controller( DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); } +LCS C3Controller::CreatePlaceholderLCS() const { + MatrixXd A = MatrixXd::Zero(n_x_, n_x_); + MatrixXd B = MatrixXd::Zero(n_x_, n_u_); + VectorXd d = VectorXd::Zero(n_x_); + MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); + MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); + MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); + MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); + VectorXd c = VectorXd::Zero(n_lambda_); + return LCS(A, B, D, d, E, F, H, c, c3_options_.N, c3_options_.dt); +} + drake::systems::EventStatus C3Controller::ComputePlan( const Context& context, DiscreteValues* discrete_state) const { @@ -108,6 +156,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( lcs_state_input_port_); auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); + const drake::VectorX& x_lcs = lcs_x->get_data(); discrete_state->get_mutable_value(plan_start_time_index_)[0] = lcs_x->get_timestamp(); @@ -115,54 +164,25 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector x_desired = std::vector(N_ + 1, x_des.value()); - DRAKE_DEMAND(Q_.front().rows() == lcs.n_); - DRAKE_DEMAND(Q_.front().cols() == lcs.n_); - DRAKE_DEMAND(R_.front().rows() == lcs.k_); - DRAKE_DEMAND(R_.front().cols() == lcs.k_); - DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); - DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); - DRAKE_DEMAND(U_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); - DRAKE_DEMAND(U_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); - - if (c3_options_.projection_type == "MIQP") { - c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); - - } else if (c3_options_.projection_type == "QP") { - c3_ = std::make_unique(lcs, Q_, R_, G_, U_, x_desired, c3_options_); +// DRAKE_DEMAND(Q_.front().rows() == lcs.n_); +// DRAKE_DEMAND(Q_.front().cols() == lcs.n_); +// DRAKE_DEMAND(R_.front().rows() == lcs.k_); +// DRAKE_DEMAND(R_.front().cols() == lcs.k_); +// DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); +// DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); +// DRAKE_DEMAND(U_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); +// DRAKE_DEMAND(U_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); - } else { - std::cerr << ("Unknown projection type") << std::endl; - DRAKE_THROW_UNLESS(false); - } c3_->SetOsqpSolverOptions(solver_options_); + c3_->UpdateLCS(lcs); + c3_->UpdateTarget(x_desired); VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); - delta_init.head(n_x_) = lcs_x->get_data(); + delta_init.head(n_x_) = x_lcs; std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - - // Set actor bounds - for (int i : vector({0, 2})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_x_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.35, 0.6, 1); - } - for (int i : vector({1})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_x_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, -0.2, 0.2, 1); - } - for (int i : vector({0, 1})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_u_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, -10, 10, 2); - } - for (int i : vector({2})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_u_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, 0, 20, 2); - } - c3_->Solve(lcs_x->get_data(), delta, w); + + c3_->Solve(x_lcs, delta, w); auto finish = std::chrono::high_resolution_clock::now(); delta_ = delta; w_ = w; diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 58a02c52ba..bca44dcb8a 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -56,6 +56,8 @@ class C3Controller : public drake::systems::LeafSystem { } private: + solvers::LCS CreatePlaceholderLCS() const; + drake::systems::EventStatus ComputePlan( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; From 2b187d4477ee12a0f9e02e724a21ca271e1f2bef Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 2 Jan 2024 16:30:15 -0500 Subject: [PATCH 576/758] adding option to disable ff force in osc --- examples/Cassie/cassie_xbox_remote.py | 11 +++++++++++ .../parameters/franka_c3_controller_params.yaml | 2 +- .../parameters/franka_c3_options_w_supports.yaml | 2 +- .../franka/systems/end_effector_force_trajectory.cc | 2 +- 4 files changed, 14 insertions(+), 3 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 203233d8ed..d36be8cdf3 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -58,6 +58,8 @@ def main(): i = 0 latching_switch_a = 1 latching_switch_b = 1 + latching_switch_x = 0 + latching_switch_y = 0 print("Teleop Status: " + str(latching_switch_a)) print("End Effector Follow Status: " + str(latching_switch_b)) while not done: @@ -77,6 +79,13 @@ def main(): if event.button == 1: latching_switch_b = not latching_switch_b print("End Effector Follow Status: " + str(latching_switch_b)) + if event.button == 2: + latching_switch_x = not latching_switch_x + print("End Effector Follow Status: " + str(latching_switch_b)) + if event.button == 3: + latching_switch_y = not latching_switch_y + print("End Effector Follow Status: " + str(latching_switch_b)) + # Send LCM message radio_msg = dairlib.lcmt_radio_out() @@ -90,6 +99,8 @@ def main(): radio_msg.channel[13] = latching_switch_b radio_msg.channel[14] = latching_switch_a + radio_msg.channel[11] = latching_switch_x + radio_msg.channel[12] = latching_switch_y # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 3ff4af80d0..d48ed23940 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -26,7 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.53, 0, 0.442] +neutral_position: [0.5, -0.02, 0.442] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index ebab286d98..5994bd4dbc 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -11,7 +11,7 @@ contact_model: 'anitescu' warm_start: true mu: [0.8, 0.8, 0.8, 0.1, 0.1, 0.1, 0.1] -dt: 0.08 +dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index 40576224a4..f6c9a5371e 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -61,7 +61,7 @@ void EndEffectorForceTrajectoryGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (radio_out->channel[14] || trajectory_input.value(0).isZero()) { + if (radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); } else { *casted_traj = *(PiecewisePolynomial*)dynamic_cast< From b7aad2a6a23fc288032e96bed2747ed365e03ed1 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 3 Jan 2024 14:35:52 -0500 Subject: [PATCH 577/758] adjusting sim set up for clearance --- examples/franka/franka_sim.cc | 1 - examples/franka/parameters/franka_c3_controller_params.yaml | 4 ++-- examples/franka/parameters/franka_c3_options_w_supports.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 4 ++-- examples/franka/urdf/left_support_point_contact.urdf | 4 ++-- solvers/c3.cc | 4 ++-- 6 files changed, 9 insertions(+), 10 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 20dc17255f..6da4dab8c0 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -141,7 +141,6 @@ int DoMain(int argc, char* argv[]) { {"paddle", paddle_geom_set}, {"tray", tray_collision_set}); plant.Finalize(); - /* -------------------------------------------------------------------------------------------*/ drake::lcm::DrakeLcm drake_lcm; diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index d48ed23940..64106c7c19 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -18,8 +18,8 @@ scene_index: 1 #right_support_model: examples/franka/urdf/left_support.urdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.65, 0.15, 0.225] -right_support_position: [0.65, -0.15, 0.225] +left_support_position: [0.7, 0.15, 0.225] +right_support_position: [0.7, -0.15, 0.225] include_end_effector_orientation: false diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 5994bd4dbc..a84af81722 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -39,7 +39,7 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -u_x: [10, 10, 10, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [1, 1, 1, 10, 10, 10, 10, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 2fa59111a2..eaa458921b 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -16,8 +16,8 @@ visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.65, 0.15, 0.225] -right_support_position: [0.65, -0.15, 0.225] +left_support_position: [0.8, 0.15, 0.225] +right_support_position: [0.8, -0.15, 0.225] dt: 0.0005 realtime_rate: 1.0 diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index daf9ff9e5b..5f8121385c 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,13 +13,13 @@ izz="0.013"/> - + - + diff --git a/solvers/c3.cc b/solvers/c3.cc index 920696ef67..e16b0593cb 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -209,8 +209,8 @@ void C3::Solve(const VectorXd& x0, vector& delta, z_sol_->at(0).segment(0, n_) = x0; for (int i = 1; i < N_; ++i) { z_sol_->at(i).segment(0, n_) = - A_.at(i) * x_sol_->at(i - 1) + B_.at(i) * u_sol_->at(i - 1) + - D_.at(i) * lambda_sol_->at(i - 1) + d_.at(i - 1); + A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + + D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); } } From 61d7a60ebd14aca298c79c888c9b697d867757a2 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 3 Jan 2024 14:54:05 -0500 Subject: [PATCH 578/758] playing with different gains --- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_c3_options_w_supports.yaml | 6 +++--- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 2 +- 4 files changed, 6 insertions(+), 6 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 64106c7c19..f55a23c2b9 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -26,7 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.5, -0.02, 0.442] +neutral_position: [0.5, 0, 0.443] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index a84af81722..24baee6950 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -10,8 +10,8 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true -mu: [0.8, 0.8, 0.8, 0.1, 0.1, 0.1, 0.1] -dt: 0.075 +mu: [0.9, 0.9, 0.9, 0.1, 0.1, 0.1, 0.1] +dt: 0.08 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 @@ -26,7 +26,7 @@ w_G: 0.1 w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 400, 400, 400, 400, 15000, 15000, 15000, +q_vector: [175, 175, 175, 50, 50, 50, 50, 20000, 20000, 20000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2246c514ff..8db0ba4b5c 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -7,7 +7,7 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] neutral_position: [0.55, 0, 0.43] -x_scale: 0.1 +x_scale: 0.05 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index eaa458921b..6449f7ebc5 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -25,6 +25,6 @@ realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.470], - [1, 0, 0, 0, 0.7, 0.00, 0.47]] + [1, 0, 0, 0, 0.72, 0.00, 0.47]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] From 440a64b6cda5684cfff0398da5389185d135e6cc Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 3 Jan 2024 16:22:12 -0500 Subject: [PATCH 579/758] minor visualization changes for franka example --- examples/franka/franka_visualizer.cc | 15 +-------------- .../lcm_trajectory_systems.cc | 6 ++++-- 2 files changed, 5 insertions(+), 16 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index e3e19f3410..87b22f209e 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -83,8 +83,6 @@ int do_main(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; - drake::multibody::ModelInstanceIndex box_index = - parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); @@ -136,8 +134,6 @@ int do_main(int argc, char* argv[]) { builder.AddSystem(plant, franka_index); auto tray_state_receiver = builder.AddSystem(plant, tray_index); - auto box_state_receiver = - builder.AddSystem(plant, box_index); auto franka_passthrough = builder.AddSystem( franka_state_receiver->get_output_port(0).size(), 0, @@ -148,13 +144,9 @@ int do_main(int argc, char* argv[]) { auto tray_passthrough = builder.AddSystem( tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); - auto box_passthrough = builder.AddSystem( - tray_state_receiver->get_output_port(0).size(), 0, - plant.num_positions(box_index)); std::vector input_sizes = {plant.num_positions(franka_index), - plant.num_positions(tray_index), - plant.num_positions(box_index)}; + plant.num_positions(tray_index)}; auto mux = builder.AddSystem>(input_sizes); @@ -199,7 +191,6 @@ int do_main(int argc, char* argv[]) { builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); - builder.Connect(box_passthrough->get_output_port(), mux->get_input_port(2)); builder.Connect(trajectory_sub_actor->get_output_port(), trajectory_drawer_actor->get_input_port_trajectory()); builder.Connect(trajectory_sub_object->get_output_port(), @@ -221,11 +212,9 @@ int do_main(int argc, char* argv[]) { builder.Connect(robot_time_passthrough->get_output_port(), end_effector_force_drawer->get_input_port_robot_time()); builder.Connect(*tray_state_receiver, *tray_passthrough); - builder.Connect(*box_state_receiver, *box_passthrough); builder.Connect(*franka_state_sub, *franka_state_receiver); builder.Connect(*tray_state_sub, *tray_state_receiver); - builder.Connect(*box_state_sub, *box_state_receiver); auto diagram = builder.Build(); auto context = diagram->CreateDefaultContext(); @@ -240,8 +229,6 @@ int do_main(int argc, char* argv[]) { plant, franka_state_sub_context); tray_state_receiver->InitializeSubscriberPositions(plant, tray_state_sub_context); - box_state_receiver->InitializeSubscriberPositions(plant, - box_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 35f8606080..17f8b149b6 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -285,9 +285,11 @@ LcmForceDrawer::LcmForceDrawer( actor_last_update_time_index_ = this->DeclareDiscreteState(1); forces_last_update_time_index_ = this->DeclareDiscreteState(1); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, - {0, 0, 1, 1}); + {0, 1, 0, 1}); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, - {0, 0, 1, 1}); + {0, 1, 0, 1}); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); + DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); From f86243429894ef3e7cdcf5dadceb122916d9b47d Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 4 Jan 2024 14:23:23 -0500 Subject: [PATCH 580/758] adjusting sim params to reflect hardware setup --- .../franka/parameters/franka_c3_controller_params.yaml | 8 ++++---- examples/franka/parameters/franka_sim_params.yaml | 10 +++++----- examples/franka/urdf/left_support.urdf | 6 +++--- examples/franka/urdf/left_support_point_contact.urdf | 6 +++--- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index f55a23c2b9..0d2b7e1984 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -7,7 +7,7 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate -tool_attachment_frame: [0, 0, 0.107] +tool_attachment_frame: [0, 0, 0.1324] plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf @@ -18,15 +18,15 @@ scene_index: 1 #right_support_model: examples/franka/urdf/left_support.urdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.7, 0.15, 0.225] -right_support_position: [0.7, -0.15, 0.225] +left_support_position: [0.7, 0.15, 0.4808] +right_support_position: [0.7, -0.15, 0.4808] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.5, 0, 0.443] +neutral_position: [0.45, 0, 0.5] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 6449f7ebc5..810f926286 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -15,16 +15,16 @@ scene_index: 1 visualize: true publish_efforts: true -tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.225] -right_support_position: [0.8, -0.15, 0.225] +tool_attachment_frame: [0, 0, 0.1324] # original tool attachment frame + 1in for the spacer +left_support_position: [0.8, 0.15, 0.4808] +right_support_position: [0.8, -0.15, 0.4808] dt: 0.0005 realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.470], - [1, 0, 0, 0, 0.72, 0.00, 0.47]] +q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.515], + [1, 0, 0, 0, 0.72, 0.00, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index 97502a0cd2..81350d956f 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -15,7 +15,7 @@ - + @@ -27,10 +27,10 @@ - + - + diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index 5f8121385c..100720f92d 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,13 +13,13 @@ izz="0.013"/> - + - + @@ -27,7 +27,7 @@ - + From d4ccbfd004b6f5dd879c1fd1791465990b5f610a Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 4 Jan 2024 16:26:48 -0500 Subject: [PATCH 581/758] updating osc with new offset as well --- .../franka_osc_controller_params.yaml | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 8db0ba4b5c..addef623ce 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -4,10 +4,10 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector_massless.urdf end_effector_name: plate -tool_attachment_frame: [0, 0, 0.107] +tool_attachment_frame: [0, 0, 0.1324] -neutral_position: [0.55, 0, 0.43] -x_scale: 0.05 +neutral_position: [0.55, 0, 0.48] +x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 @@ -55,13 +55,13 @@ EndEffectorRotW: 0, 10, 0, 0, 0, 10 ] EndEffectorRotKp: - [ 400, 0, 0, - 0, 400, 0, - 0, 0, 400] + [ 800, 0, 0, + 0, 800, 0, + 0, 0, 800] EndEffectorRotKd: - [ 20, 0, 0, - 0, 20, 0, - 0, 0, 20 ] + [ 40, 0, 0, + 0, 40, 0, + 0, 0, 40] LambdaEndEffectorW: [ 1, 0, 0, 0, 1, 0, From 181f04ec42c994575f89982f66ee5cae6bde3600 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 4 Jan 2024 17:35:55 -0500 Subject: [PATCH 582/758] using point contact and box model now --- examples/franka/parameters/franka_c3_controller_params.yaml | 4 ++-- examples/franka/urdf/left_support_point_contact.urdf | 6 +++--- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 0d2b7e1984..eaff9b794e 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -18,8 +18,8 @@ scene_index: 1 #right_support_model: examples/franka/urdf/left_support.urdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.7, 0.15, 0.4808] -right_support_position: [0.7, -0.15, 0.4808] +left_support_position: [0.8, 0.15, 0.4808] +right_support_position: [0.8, -0.15, 0.4808] include_end_effector_orientation: false diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index 100720f92d..bb27099a8c 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -13,15 +13,15 @@ izz="0.013"/> - + - + - + From 20e51b15f031a5072da85b903713b42bf35de59e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 4 Jan 2024 17:36:24 -0500 Subject: [PATCH 583/758] removing box from franka sim --- examples/franka/franka_sim.cc | 23 ----------------------- 1 file changed, 23 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 6da4dab8c0..60a7a1f517 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -72,8 +72,6 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; - // drake::multibody::ModelInstanceIndex box_index = - // parser.AddModels(FindResourceOrThrow(sim_params.box_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); @@ -132,8 +130,6 @@ int DoMain(int argc, char* argv[]) { &plant.GetBodyByName("panda_link5"), &plant.GetBodyByName("panda_link6"), &plant.GetBodyByName("panda_link8"), - - // &plant.GetBodyByName("plate"), }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); @@ -156,21 +152,11 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, lcm, 1.0 / sim_params.tray_publish_rate)); - // auto box_state_sender = - // builder.AddSystem(plant, box_index); - // auto box_state_pub = - // builder.AddSystem(LcmPublisherSystem::Make( - // lcm_channel_params.box_state_channel, lcm, - // 1.0 / sim_params.publish_rate)); builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); - // builder.Connect(plant.get_state_output_port(box_index), - // box_state_sender->get_input_port_state()); builder.Connect(tray_state_sender->get_output_port(), tray_state_pub->get_input_port()); - // builder.Connect(box_state_sender->get_output_port(), - // box_state_pub->get_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); @@ -197,15 +183,6 @@ int DoMain(int argc, char* argv[]) { q.tail(plant.num_positions(tray_index)) = sim_params.q_init_plate[sim_params.scene_index]; - - // q[q_map["box_qw"]] = sim_params.q_init_box[0]; - // q[q_map["box_qx"]] = sim_params.q_init_box[1]; - // q[q_map["box_qy"]] = sim_params.q_init_box[2]; - // q[q_map["box_qz"]] = sim_params.q_init_box[3]; - // q[q_map["box_x"]] = sim_params.q_init_box[4]; - // q[q_map["box_y"]] = sim_params.q_init_box[5]; - // q[q_map["box_z"]] = sim_params.q_init_box[6]; - plant.SetPositions(&plant_context, q); VectorXd v = VectorXd::Zero(nv); From 7acd90553ff7840aed352a9b5128b65ff4c00e1b Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 5 Jan 2024 14:45:41 -0500 Subject: [PATCH 584/758] attempting these gains on hardware --- .../franka_c3_controller_params.yaml | 8 ++++---- .../franka_c3_options_w_supports.yaml | 6 +++--- .../franka_osc_controller_params.yaml | 4 ++-- .../franka/parameters/franka_sim_params.yaml | 8 ++++---- .../urdf/left_support_point_contact.urdf | 4 ++-- .../urdf/plate_end_effector_massless.urdf | 2 +- systems/controllers/c3_controller.cc | 18 +++++++++++++++--- 7 files changed, 31 insertions(+), 19 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index eaff9b794e..7ea651cc4c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -7,7 +7,7 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate -tool_attachment_frame: [0, 0, 0.1324] +tool_attachment_frame: [0, 0, 0.107] plate_model: examples/franka/urdf/plate_end_effector_translation.urdf #plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf @@ -18,15 +18,15 @@ scene_index: 1 #right_support_model: examples/franka/urdf/left_support.urdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.8, 0.15, 0.4808] -right_support_position: [0.8, -0.15, 0.4808] +left_support_position: [0.8, 0.15, 0.45] +right_support_position: [0.8, -0.15, 0.45] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.45, 0, 0.5] +neutral_position: [0.45, 0, 0.475] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 24baee6950..22ad12ddc2 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,6 +1,6 @@ admm_iter: 2 rho: 0 # does not do anything -rho_scale: 8 +rho_scale: 10 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -21,12 +21,12 @@ N: 5 w_Q: 50 w_R: 5 # Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.2 # Penalty on all decision variables, assuming scalar w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 50, 50, 50, 50, 20000, 20000, 20000, +q_vector: [150, 100, 100, 500, 500, 500, 500, 20000, 20000, 20000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index addef623ce..32ca425eb7 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -4,9 +4,9 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector_massless.urdf end_effector_name: plate -tool_attachment_frame: [0, 0, 0.1324] +tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.55, 0, 0.48] +neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 810f926286..328156b7d9 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -15,9 +15,9 @@ scene_index: 1 visualize: true publish_efforts: true -tool_attachment_frame: [0, 0, 0.1324] # original tool attachment frame + 1in for the spacer -left_support_position: [0.8, 0.15, 0.4808] -right_support_position: [0.8, -0.15, 0.4808] +tool_attachment_frame: [0, 0, 0.107] +left_support_position: [0.8, 0.15, 0.45] +right_support_position: [0.8, -0.15, 0.45] dt: 0.0005 realtime_rate: 1.0 @@ -25,6 +25,6 @@ realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.515], - [1, 0, 0, 0, 0.72, 0.00, 0.515]] + [1, 0, 0, 0, 0.7, 0.00, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index bb27099a8c..4c69a58889 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -19,9 +19,9 @@ - + - + diff --git a/examples/franka/urdf/plate_end_effector_massless.urdf b/examples/franka/urdf/plate_end_effector_massless.urdf index 6985b79727..b81d96de63 100644 --- a/examples/franka/urdf/plate_end_effector_massless.urdf +++ b/examples/franka/urdf/plate_end_effector_massless.urdf @@ -4,7 +4,7 @@ - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index d738a8d989..0dc10792ac 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -80,15 +80,20 @@ C3Controller::C3Controller( c3_->SetOsqpSolverOptions(solver_options_); // Set actor bounds - for (int i : vector({0, 2})) { + for (int i : vector({0})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.35, 0.6, 1); + c3_->AddLinearConstraint(A, 0.4, 0.6, 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -0.2, 0.2, 1); + c3_->AddLinearConstraint(A, -0.1, 0.1, 1); + } + for (int i : vector({2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A(i) = 1.0; + c3_->AddLinearConstraint(A, 0.35, 0.55, 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); @@ -164,6 +169,13 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector x_desired = std::vector(N_ + 1, x_des.value()); + DRAKE_DEMAND(lcs_x->get_data()[0] > 0.35 ); + DRAKE_DEMAND(lcs_x->get_data()[0] < 0.65); + DRAKE_DEMAND(lcs_x->get_data()[1] > -0.1); + DRAKE_DEMAND(lcs_x->get_data()[1] < 0.1); + DRAKE_DEMAND(lcs_x->get_data()[2] > 0.35); + DRAKE_DEMAND(lcs_x->get_data()[2] < 0.55); + // DRAKE_DEMAND(Q_.front().rows() == lcs.n_); // DRAKE_DEMAND(Q_.front().cols() == lcs.n_); // DRAKE_DEMAND(R_.front().rows() == lcs.k_); From ec6f2c0fdb9c81111f70bb5bf1e51c64b898f28a Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 5 Jan 2024 16:49:33 -0500 Subject: [PATCH 585/758] printing xbox settings --- examples/Cassie/cassie_xbox_remote.py | 6 +++--- examples/franka/systems/end_effector_force_trajectory.cc | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index d36be8cdf3..df092c1c92 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -58,8 +58,8 @@ def main(): i = 0 latching_switch_a = 1 latching_switch_b = 1 - latching_switch_x = 0 - latching_switch_y = 0 + latching_switch_x = 1 + latching_switch_y = 1 print("Teleop Status: " + str(latching_switch_a)) print("End Effector Follow Status: " + str(latching_switch_b)) while not done: @@ -81,7 +81,7 @@ def main(): print("End Effector Follow Status: " + str(latching_switch_b)) if event.button == 2: latching_switch_x = not latching_switch_x - print("End Effector Follow Status: " + str(latching_switch_b)) + print("Force Tracking Status: " + str(latching_switch_x)) if event.button == 3: latching_switch_y = not latching_switch_y print("End Effector Follow Status: " + str(latching_switch_b)) diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index f6c9a5371e..7639454b52 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -61,7 +61,7 @@ void EndEffectorForceTrajectoryGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { + if (!radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); } else { *casted_traj = *(PiecewisePolynomial*)dynamic_cast< From 902371a270e71888c6cc5fb92c8150e75490a6c6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 7 Jan 2024 19:26:33 -0500 Subject: [PATCH 586/758] features implemented, need to tune with plots' --- examples/Cassie/cassie_xbox_remote.py | 5 +- examples/franka/franka_c3_controller.cc | 4 +- examples/franka/franka_visualizer.cc | 2 +- .../franka_c3_controller_params.yaml | 2 +- .../franka_c3_options_translation.yaml | 1 + .../franka_c3_options_w_supports.yaml | 8 +-- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/systems/franka_kinematics.cc | 2 - .../franka/systems/plate_balancing_target.cc | 16 +++++- .../franka/systems/plate_balancing_target.h | 10 +++- .../urdf/left_support_point_contact.urdf | 6 +-- solvers/c3.cc | 4 +- solvers/c3_miqp.cc | 16 +++--- solvers/c3_options.h | 4 ++ systems/controllers/c3_controller.cc | 54 ++++++++++++------- systems/controllers/c3_controller.h | 5 +- 16 files changed, 92 insertions(+), 49 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index df092c1c92..682894c719 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -56,12 +56,13 @@ def main(): done = False i = 0 - latching_switch_a = 1 + latching_switch_a = 0 latching_switch_b = 1 - latching_switch_x = 1 + latching_switch_x = 0 latching_switch_y = 1 print("Teleop Status: " + str(latching_switch_a)) print("End Effector Follow Status: " + str(latching_switch_b)) + print("Force Tracking Status: " + str(latching_switch_x)) while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 24a3bff054..ca4e3bbbc3 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -221,7 +221,7 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.radio_channel, &lcm)); auto plate_balancing_target = - builder.AddSystem(); + builder.AddSystem(plant_tray); VectorXd neutral_position = Eigen::Map( controller_params.neutral_position.data(), controller_params.neutral_position.size()); @@ -276,6 +276,8 @@ int DoMain(int argc, char* argv[]) { tray_state_receiver->get_input_port()); builder.Connect(tray_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(tray_state_receiver->get_output_port(), + plate_balancing_target->get_input_port_tray_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_lcs_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 87b22f209e..0af9035003 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -163,7 +163,7 @@ int do_main(int argc, char* argv[]) { builder.AddSystem>(plant); drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0 / 30.0; + params.publish_period = 1.0 / 15.0; params.enable_alpha_slider = true; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 7ea651cc4c..f3ff948069 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -26,7 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.45, 0, 0.475] +neutral_position: [0.45, 0, 0.48] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index c723e31f91..932ac25463 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -16,6 +16,7 @@ solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 N: 5 +gamma: 1 # matrix scaling w_Q: 30 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 22ad12ddc2..d295d7103e 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -9,24 +9,26 @@ projection_type: 'MIQP' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' warm_start: true +use_predicted_x0: true mu: [0.9, 0.9, 0.9, 0.1, 0.1, 0.1, 0.1] -dt: 0.08 +dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 N: 5 +gamma: 0.9 # matrix scaling w_Q: 50 w_R: 5 # Penalty on all decision variables, assuming scalar -w_G: 0.2 +w_G: 0.1 # Penalty on all decision variables, assuming scalar w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 100, 100, 500, 500, 500, 500, 20000, 20000, 20000, +q_vector: [150, 100, 100, 500, 500, 500, 500, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 328156b7d9..8f99a562ab 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 1000 +tray_publish_rate: 20 actuator_delay: 0.000 scene_index: 1 diff --git a/examples/franka/systems/franka_kinematics.cc b/examples/franka/systems/franka_kinematics.cc index 61ba418180..4119c93c27 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/examples/franka/systems/franka_kinematics.cc @@ -1,7 +1,5 @@ #include "examples/franka/systems/franka_kinematics.h" -#include - #include "common/find_resource.h" #include "multibody/multibody_utils.h" diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 15a7523b35..d7a587c291 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -1,19 +1,26 @@ #include "plate_balancing_target.h" - +#include #include "dairlib/lcmt_radio_out.hpp" +using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; +using dairlib::systems::StateVector; using Eigen::VectorXd; namespace dairlib { namespace systems { -PlateBalancingTargetGenerator::PlateBalancingTargetGenerator() { +PlateBalancingTargetGenerator::PlateBalancingTargetGenerator(const MultibodyPlant& object_plant) { // Input/Output Setup radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); + tray_state_port_ = + this->DeclareVectorInputPort( + "x_object", StateVector(object_plant.num_positions(), + object_plant.num_velocities())) + .get_index(); end_effector_target_port_ = this->DeclareVectorOutputPort( "end_effector_target", BasicVector(3), @@ -54,12 +61,17 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( BasicVector* target) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); + const StateVector* tray_state = + (StateVector*)this->EvalVectorInput(context, tray_state_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = neutral_pose_; tray_position[2] += 0.015; // thickness of end effector and tray tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; + if ((tray_state->GetPositions().tail(3) - tray_position).norm() < 0.1){ + tray_position[2] += 0.1; // raise the tray once it is close + } target_tray_state << 1, 0, 0, 0, tray_position; target->SetFromVector(target_tray_state); } diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 60b3ebb1e6..c503830ebb 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -1,6 +1,8 @@ #pragma once #include "drake/systems/framework/leaf_system.h" +#include +#include "systems/framework/state_vector.h" namespace dairlib { namespace systems { @@ -8,12 +10,16 @@ namespace systems { class PlateBalancingTargetGenerator : public drake::systems::LeafSystem { public: - PlateBalancingTargetGenerator(); + PlateBalancingTargetGenerator(const drake::multibody::MultibodyPlant& object_plant); const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); } + const drake::systems::InputPort& get_input_port_tray_state() const { + return this->get_input_port(tray_state_port_); + } + const drake::systems::OutputPort& get_output_port_end_effector_target() const { return this->get_output_port(end_effector_target_port_); @@ -35,6 +41,7 @@ class PlateBalancingTargetGenerator drake::systems::BasicVector* target) const; drake::systems::InputPortIndex radio_port_; + drake::systems::InputPortIndex tray_state_port_; drake::systems::OutputPortIndex end_effector_target_port_; drake::systems::OutputPortIndex tray_target_port_; @@ -42,7 +49,6 @@ class PlateBalancingTargetGenerator double x_scale_; double y_scale_; double z_scale_; - // std::vector half_plane_bounds_; }; } // namespace systems diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index 4c69a58889..f6f3b8d5bb 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -19,15 +19,15 @@ - + - + - + diff --git a/solvers/c3.cc b/solvers/c3.cc index e16b0593cb..eb19555cde 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -191,9 +191,9 @@ void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; - for (int i = 0; i < N_; ++i) { + for (int i = 0; i < N_ - 1; ++i) { input_costs_[i]->UpdateCoefficients(2 * R_.at(i), - -2 * R_.at(i) * u_sol_->at(i)); + -2 * R_.at(i) * u_sol_->at(i + 1)); } for (int iter = 0; iter < options_.admm_iter; iter++) { diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 5767ad5007..1702d4f1a4 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -53,18 +53,18 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, for (int i = 0; i < m_; i++) { binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); - if (warm_start_index != -1) { - binary[i].set(GRB_DoubleAttr_Start, - warm_start_binary_[admm_iteration][warm_start_index](i)); - } +// if (warm_start_index != -1) { +// binary[i].set(GRB_DoubleAttr_Start, +// warm_start_binary_[admm_iteration][warm_start_index](i)); +// } } for (int i = 0; i < n_ + m_ + k_; i++) { delta_k[i] = model.addVar(-10000.0, 10000.0, 0.0, GRB_CONTINUOUS); - if (warm_start_index != -1) { - delta_k[i].set(GRB_DoubleAttr_Start, - warm_start_delta_[admm_iteration][warm_start_index](i)); - } +// if (warm_start_index != -1) { +// delta_k[i].set(GRB_DoubleAttr_Start, +// warm_start_delta_[admm_iteration][warm_start_index](i)); +// } } GRBQuadExpr obj = 0; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index a6ba41bbaa..fb0724e509 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -13,8 +13,10 @@ struct C3Options { std::string projection_type; std::string contact_model; bool warm_start; + bool use_predicted_x0; int N; + double gamma; double w_Q; double w_R; double w_G; @@ -61,6 +63,7 @@ struct C3Options { DRAKE_DEMAND(contact_model == "anitescu"); } a->Visit(DRAKE_NVP(warm_start)); + a->Visit(DRAKE_NVP(use_predicted_x0)); a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(dt)); @@ -69,6 +72,7 @@ struct C3Options { a->Visit(DRAKE_NVP(num_contacts)); a->Visit(DRAKE_NVP(N)); + a->Visit(DRAKE_NVP(gamma)); a->Visit(DRAKE_NVP(w_Q)); a->Visit(DRAKE_NVP(w_R)); a->Visit(DRAKE_NVP(w_G)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 0dc10792ac..52a2e909c4 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -33,13 +33,21 @@ C3Controller::C3Controller( : plant_(plant), context_(context), c3_options_(std::move(c3_options)), - Q_(std::vector(c3_options_.N + 1, c3_options_.Q)), - R_(std::vector(c3_options_.N, c3_options_.R)), G_(std::vector(c3_options_.N, c3_options_.G)), U_(std::vector(c3_options_.N, c3_options_.U)), N_(c3_options_.N) { this->set_name("c3_controller"); + double discount_factor = 1; + for (int i = 0; i < N_; ++i) { + Q_.push_back(discount_factor * c3_options_.Q); + R_.push_back(discount_factor * c3_options_.R); + discount_factor *= c3_options_.gamma; + } + Q_.push_back(discount_factor * c3_options_.Q); + DRAKE_DEMAND(Q_.size() == N_ + 1); + DRAKE_DEMAND(R_.size() == N_); + n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_u_ = plant_.num_actuators(); @@ -110,7 +118,8 @@ C3Controller::C3Controller( this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) .get_index(); lcs_input_port_ = - this->DeclareAbstractInputPort("lcs", drake::Value(lcs_placeholder)).get_index(); + this->DeclareAbstractInputPort("lcs", drake::Value(lcs_placeholder)) + .get_index(); target_input_port_ = this->DeclareVectorInputPort("x_lcs_des", n_x_).get_index(); @@ -134,6 +143,7 @@ C3Controller::C3Controller( .get_index(); plan_start_time_index_ = DeclareDiscreteState(1); + x_pred_ = VectorXd::Zero(n_x_); DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); } @@ -161,7 +171,11 @@ drake::systems::EventStatus C3Controller::ComputePlan( lcs_state_input_port_); auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); - const drake::VectorX& x_lcs = lcs_x->get_data(); + drake::VectorX x_lcs = lcs_x->get_data(); + if (c3_options_.use_predicted_x0 && !x_pred_.isZero()) { + x_lcs.head(3) = x_pred_.head(3); + x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); + } discrete_state->get_mutable_value(plan_start_time_index_)[0] = lcs_x->get_timestamp(); @@ -169,22 +183,13 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector x_desired = std::vector(N_ + 1, x_des.value()); - DRAKE_DEMAND(lcs_x->get_data()[0] > 0.35 ); + DRAKE_DEMAND(lcs_x->get_data()[0] > 0.35); DRAKE_DEMAND(lcs_x->get_data()[0] < 0.65); DRAKE_DEMAND(lcs_x->get_data()[1] > -0.1); DRAKE_DEMAND(lcs_x->get_data()[1] < 0.1); DRAKE_DEMAND(lcs_x->get_data()[2] > 0.35); DRAKE_DEMAND(lcs_x->get_data()[2] < 0.55); -// DRAKE_DEMAND(Q_.front().rows() == lcs.n_); -// DRAKE_DEMAND(Q_.front().cols() == lcs.n_); -// DRAKE_DEMAND(R_.front().rows() == lcs.k_); -// DRAKE_DEMAND(R_.front().cols() == lcs.k_); -// DRAKE_DEMAND(G_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); -// DRAKE_DEMAND(G_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); -// DRAKE_DEMAND(U_.front().rows() == lcs.n_ + lcs.m_ + lcs.k_); -// DRAKE_DEMAND(U_.front().cols() == lcs.n_ + lcs.m_ + lcs.k_); - c3_->SetOsqpSolverOptions(solver_options_); c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); @@ -193,15 +198,17 @@ drake::systems::EventStatus C3Controller::ComputePlan( delta_init.head(n_x_) = x_lcs; std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - + c3_->Solve(x_lcs, delta, w); auto finish = std::chrono::high_resolution_clock::now(); delta_ = delta; w_ = w; auto elapsed = finish - start; - solve_time_ = + double solve_time = std::chrono::duration_cast(elapsed).count() / 1e6; + filtered_solve_time_ = (1 - solve_time_filter_constant_) * solve_time + + (solve_time_filter_constant_)*filtered_solve_time_; return drake::systems::EventStatus::Succeeded(); } @@ -212,21 +219,28 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = t + i * c3_options_.dt; + c3_solution->time_vector_(i) = t + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); - c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } + + if (filtered_solve_time_ < dt_) { + double weight = (dt_ - filtered_solve_time_) / dt_; + x_pred_ = weight * z_sol[0].segment(0, n_x_) + + (1 - weight) * z_sol[1].segment(0, n_x_); + } else { + x_pred_ = z_sol[1].segment(0, n_x_); + } } void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { - double t = - context.get_discrete_state(plan_start_time_index_)[0] + solve_time_; + double t = context.get_discrete_state(plan_start_time_index_)[0] + + filtered_solve_time_; for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index bca44dcb8a..13794e444a 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -94,7 +94,10 @@ class C3Controller : public drake::systems::LeafSystem { mutable std::unique_ptr c3_; mutable std::vector delta_; mutable std::vector w_; - mutable double solve_time_; + mutable double filtered_solve_time_; + mutable Eigen::VectorXd x_pred_; + + const double solve_time_filter_constant_ = 0.9; drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; From 83a6431c6ce05360729de0bffe6ffacd765e2b13 Mon Sep 17 00:00:00 2001 From: AlpAydinoglu Date: Mon, 8 Jan 2024 10:13:49 -0500 Subject: [PATCH 587/758] some parameter tuning --- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- examples/franka/parameters/franka_c3_options_w_supports.yaml | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index f3ff948069..bdb3d55228 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -26,7 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -neutral_position: [0.45, 0, 0.48] +neutral_position: [0.45, 0, 0.47] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index d295d7103e..259cad5064 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -11,13 +11,13 @@ contact_model: 'anitescu' warm_start: true use_predicted_x0: true -mu: [0.9, 0.9, 0.9, 0.1, 0.1, 0.1, 0.1] +mu: [0.5, 0.5, 0.5, 0.1, 0.1, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 N: 5 -gamma: 0.9 +gamma: 1 # matrix scaling w_Q: 50 From 3835b470dda7083434f67bb9dfbe3fc08ae1c66f Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 8 Jan 2024 11:52:16 -0500 Subject: [PATCH 588/758] tuning and adjusting warm startg --- examples/franka/franka_visualizer.cc | 2 +- .../franka_c3_options_w_supports.yaml | 10 +++--- .../franka/parameters/franka_sim_params.h | 2 ++ .../franka/parameters/franka_sim_params.yaml | 3 +- .../franka/systems/plate_balancing_target.cc | 34 +++++++++++++++---- .../franka/systems/plate_balancing_target.h | 11 ++++-- solvers/c3.cc | 27 +++++++++------ solvers/c3_miqp.cc | 16 ++++----- systems/controllers/c3_controller.cc | 4 +-- 9 files changed, 73 insertions(+), 36 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 0af9035003..21be9df069 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -163,7 +163,7 @@ int do_main(int argc, char* argv[]) { builder.AddSystem>(plant); drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0 / 15.0; + params.publish_period = 1.0 / sim_params.visualizer_publish_rate; params.enable_alpha_slider = true; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 259cad5064..2e755ea1e9 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -11,7 +11,7 @@ contact_model: 'anitescu' warm_start: true use_predicted_x0: true -mu: [0.5, 0.5, 0.5, 0.1, 0.1, 0.1, 0.1] +mu: [0.55, 0.55, 0.55, 0.1, 0.1, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 @@ -28,20 +28,20 @@ w_G: 0.1 w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 100, 100, 500, 500, 500, 500, 15000, 15000, 15000, - 5, 5, 10, 1, 1, 1, 5, 5, 5] +q_vector: [150, 100, 100, 1, 1, 1, 1, 15000, 15000, 15000, + 5, 5, 10, 1, 100, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] # Penalty on matching projected variables -g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -u_x: [1, 1, 1, 10, 10, 10, 10, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [0.1, 0.1, 0.1, 10, 10, 10, 10, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index ae47e94a9d..86cea76367 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -18,6 +18,7 @@ struct FrankaSimParams { double actuator_delay; double franka_publish_rate; double tray_publish_rate; + double visualizer_publish_rate; int scene_index; bool visualize; @@ -46,6 +47,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(actuator_delay)); a->Visit(DRAKE_NVP(franka_publish_rate)); a->Visit(DRAKE_NVP(tray_publish_rate)); + a->Visit(DRAKE_NVP(visualizer_publish_rate)); a->Visit(DRAKE_NVP(scene_index)); a->Visit(DRAKE_NVP(visualize)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 8f99a562ab..8d3f90ef5b 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,8 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 20 +tray_publish_rate: 10 +visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 1 diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index d7a587c291..f951d985d4 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -1,16 +1,20 @@ #include "plate_balancing_target.h" + #include + #include "dairlib/lcmt_radio_out.hpp" +using dairlib::systems::StateVector; using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; -using dairlib::systems::StateVector; +using drake::systems::EventStatus; using Eigen::VectorXd; namespace dairlib { namespace systems { -PlateBalancingTargetGenerator::PlateBalancingTargetGenerator(const MultibodyPlant& object_plant) { +PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( + const MultibodyPlant& object_plant) { // Input/Output Setup radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", @@ -30,6 +34,20 @@ PlateBalancingTargetGenerator::PlateBalancingTargetGenerator(const MultibodyPlan "tray_target", BasicVector(7), &PlateBalancingTargetGenerator::CalcTrayTarget) .get_index(); + reached_first_target_idx_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + DeclareForcedDiscreteUpdateEvent( + &PlateBalancingTargetGenerator::DiscreteVariableUpdate); +} + +EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { + const StateVector* tray_state = + (StateVector*)this->EvalVectorInput(context, tray_state_port_); + if ((tray_state->GetPositions().tail(3) - neutral_pose_).norm() < 0.05) { + discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 1; + } + return EventStatus::Succeeded(); } void PlateBalancingTargetGenerator::SetRemoteControlParameters( @@ -46,6 +64,7 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( drake::systems::BasicVector* target) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); + VectorXd y0 = neutral_pose_; // Update target if remote trigger is active if (radio_out->channel[13] > 0) { @@ -53,6 +72,9 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( y0(1) += radio_out->channel[1] * y_scale_; y0(2) += radio_out->channel[2] * z_scale_; } + if (context.get_discrete_state(reached_first_target_idx_)[0]) { + y0[2] += 0.1; // raise the tray once it is close + } target->SetFromVector(y0); } @@ -61,16 +83,14 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( BasicVector* target) const { const auto& radio_out = this->EvalInputValue(context, radio_port_); - const StateVector* tray_state = - (StateVector*)this->EvalVectorInput(context, tray_state_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = neutral_pose_; - tray_position[2] += 0.015; // thickness of end effector and tray + tray_position[2] += 0.015; // thickness of end effector and tray tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; - if ((tray_state->GetPositions().tail(3) - tray_position).norm() < 0.1){ - tray_position[2] += 0.1; // raise the tray once it is close + if (context.get_discrete_state(reached_first_target_idx_)[0]) { + tray_position[2] += 0.1; // raise the tray once it is close } target_tray_state << 1, 0, 0, 0, tray_position; target->SetFromVector(target_tray_state); diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index c503830ebb..7cf71caab4 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -1,16 +1,19 @@ #pragma once -#include "drake/systems/framework/leaf_system.h" #include + #include "systems/framework/state_vector.h" +#include "drake/systems/framework/leaf_system.h" + namespace dairlib { namespace systems { class PlateBalancingTargetGenerator : public drake::systems::LeafSystem { public: - PlateBalancingTargetGenerator(const drake::multibody::MultibodyPlant& object_plant); + PlateBalancingTargetGenerator( + const drake::multibody::MultibodyPlant& object_plant); const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); @@ -39,12 +42,16 @@ class PlateBalancingTargetGenerator drake::systems::BasicVector* target) const; void CalcTrayTarget(const drake::systems::Context& context, drake::systems::BasicVector* target) const; + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; drake::systems::InputPortIndex radio_port_; drake::systems::InputPortIndex tray_state_port_; drake::systems::OutputPortIndex end_effector_target_port_; drake::systems::OutputPortIndex tray_target_port_; + drake::systems::DiscreteStateIndex reached_first_target_idx_; Eigen::Vector3d neutral_pose_; double x_scale_; double y_scale_; diff --git a/solvers/c3.cc b/solvers/c3.cc index eb19555cde..e015d436ec 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -191,10 +191,10 @@ void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; - for (int i = 0; i < N_ - 1; ++i) { - input_costs_[i]->UpdateCoefficients(2 * R_.at(i), - -2 * R_.at(i) * u_sol_->at(i + 1)); - } + // for (int i = 0; i < N_ - 1; ++i) { + // input_costs_[i]->UpdateCoefficients(2 * R_.at(i), + // -2 * R_.at(i) * u_sol_->at(i)); + // } for (int iter = 0; iter < options_.admm_iter; iter++) { ADMMStep(x0, &delta, &w, &Gv, iter); @@ -285,10 +285,12 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, // /// initialize decision variables to warm start if (warm_start_) { - for (int i = 0; i < N_; i++) { - prog_.SetInitialGuess(x_[i], warm_start_x_[admm_iteration][i]); - prog_.SetInitialGuess(lambda_[i], warm_start_lambda_[admm_iteration][i]); - prog_.SetInitialGuess(u_[i], warm_start_u_[admm_iteration][i]); + prog_.SetInitialGuess(x_[0], x0); + for (int i = 0; i < N_ - 1; i++) { + prog_.SetInitialGuess(x_[i], warm_start_x_[admm_iteration][i + 1]); + prog_.SetInitialGuess(lambda_[i], + warm_start_lambda_[admm_iteration][i + 1]); + prog_.SetInitialGuess(u_[i], warm_start_u_[admm_iteration][i + 1]); } prog_.SetInitialGuess(x_[N_], warm_start_x_[admm_iteration][N_]); } @@ -367,8 +369,13 @@ vector C3::SolveProjection(const vector& G, #pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { if (warm_start_) { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], - c_[i], admm_iteration, i); + if (i == N_ - 1) { + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, -1); + } else { + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, i + 1); + } } else { deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], admm_iteration, -1); diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 1702d4f1a4..5767ad5007 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -53,18 +53,18 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, for (int i = 0; i < m_; i++) { binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); -// if (warm_start_index != -1) { -// binary[i].set(GRB_DoubleAttr_Start, -// warm_start_binary_[admm_iteration][warm_start_index](i)); -// } + if (warm_start_index != -1) { + binary[i].set(GRB_DoubleAttr_Start, + warm_start_binary_[admm_iteration][warm_start_index](i)); + } } for (int i = 0; i < n_ + m_ + k_; i++) { delta_k[i] = model.addVar(-10000.0, 10000.0, 0.0, GRB_CONTINUOUS); -// if (warm_start_index != -1) { -// delta_k[i].set(GRB_DoubleAttr_Start, -// warm_start_delta_[admm_iteration][warm_start_index](i)); -// } + if (warm_start_index != -1) { + delta_k[i].set(GRB_DoubleAttr_Start, + warm_start_delta_[admm_iteration][warm_start_index](i)); + } } GRBQuadExpr obj = 0; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 52a2e909c4..f28c4a1aec 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -101,7 +101,7 @@ C3Controller::C3Controller( for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.35, 0.55, 1); + c3_->AddLinearConstraint(A, 0.35, 0.6, 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); @@ -188,7 +188,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( DRAKE_DEMAND(lcs_x->get_data()[1] > -0.1); DRAKE_DEMAND(lcs_x->get_data()[1] < 0.1); DRAKE_DEMAND(lcs_x->get_data()[2] > 0.35); - DRAKE_DEMAND(lcs_x->get_data()[2] < 0.55); + DRAKE_DEMAND(lcs_x->get_data()[2] < 0.6); c3_->SetOsqpSolverOptions(solver_options_); c3_->UpdateLCS(lcs); From 5ac5c52ad3a78a3cc3a8a394fd63cf01b2660ddb Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 8 Jan 2024 13:24:06 -0500 Subject: [PATCH 589/758] works on lab desktop, sensitive to solve time --- examples/Cassie/cassie_xbox_remote.py | 4 ++-- examples/franka/parameters/franka_c3_controller_params.h | 2 ++ .../franka/parameters/franka_c3_controller_params.yaml | 1 + .../franka/parameters/franka_c3_options_w_supports.yaml | 4 ++-- examples/franka/systems/plate_balancing_target.cc | 6 ++++-- examples/franka/systems/plate_balancing_target.h | 3 ++- solvers/c3.cc | 8 ++++---- systems/trajectory_optimization/lcm_trajectory_systems.cc | 1 - 8 files changed, 17 insertions(+), 12 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 682894c719..c72354af4b 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -56,9 +56,9 @@ def main(): done = False i = 0 - latching_switch_a = 0 + latching_switch_a = 1 latching_switch_b = 1 - latching_switch_x = 0 + latching_switch_x = 1 latching_switch_y = 1 print("Teleop Status: " + str(latching_switch_a)) print("End Effector Follow Status: " + str(latching_switch_b)) diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 84a24498f7..4c4d9c3915 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -24,6 +24,7 @@ struct FrankaC3ControllerParams { double x_scale; double y_scale; double z_scale; + double near_target_threshold; Eigen::Vector3d left_support_position; Eigen::Vector3d right_support_position; @@ -48,6 +49,7 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(x_scale)); a->Visit(DRAKE_NVP(y_scale)); a->Visit(DRAKE_NVP(z_scale)); + a->Visit(DRAKE_NVP(near_target_threshold)); a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index bdb3d55228..beff6b4a1e 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -26,6 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused +near_target_threshold: 0.07g neutral_position: [0.45, 0, 0.47] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 2e755ea1e9..d6cb763f5b 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -17,7 +17,7 @@ solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 N: 5 -gamma: 1 +gamma: 1.0 # matrix scaling w_Q: 50 @@ -45,5 +45,5 @@ u_x: [0.1, 0.1, 0.1, 10, 10, 10, 10, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_lambda: [75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75] u_u: [30, 30, 30] diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index f951d985d4..538973f40c 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -14,7 +14,8 @@ namespace dairlib { namespace systems { PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( - const MultibodyPlant& object_plant) { + const MultibodyPlant& object_plant, double first_target_range) + : first_target_range_(first_target_range) { // Input/Output Setup radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", @@ -44,7 +45,8 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( drake::systems::DiscreteValues* discrete_state) const { const StateVector* tray_state = (StateVector*)this->EvalVectorInput(context, tray_state_port_); - if ((tray_state->GetPositions().tail(3) - neutral_pose_).norm() < 0.05) { + if ((tray_state->GetPositions().tail(3) - neutral_pose_).norm() < + first_target_range_) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 1; } return EventStatus::Succeeded(); diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 7cf71caab4..a109028d68 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -13,7 +13,7 @@ class PlateBalancingTargetGenerator : public drake::systems::LeafSystem { public: PlateBalancingTargetGenerator( - const drake::multibody::MultibodyPlant& object_plant); + const drake::multibody::MultibodyPlant& object_plant, double first_target_range = 0.075); const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); @@ -53,6 +53,7 @@ class PlateBalancingTargetGenerator drake::systems::DiscreteStateIndex reached_first_target_idx_; Eigen::Vector3d neutral_pose_; + double first_target_range_; double x_scale_; double y_scale_; double z_scale_; diff --git a/solvers/c3.cc b/solvers/c3.cc index e015d436ec..86896934fd 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -191,10 +191,10 @@ void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; - // for (int i = 0; i < N_ - 1; ++i) { - // input_costs_[i]->UpdateCoefficients(2 * R_.at(i), - // -2 * R_.at(i) * u_sol_->at(i)); - // } + for (int i = 0; i < N_ - 1; ++i) { + input_costs_[i]->UpdateCoefficients(2 * R_.at(i), + -2 * R_.at(i) * u_sol_->at(i)); + } for (int iter = 0; iter < options_.admm_iter; iter++) { ADMMStep(x0, &delta, &w, &Gv, iter); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 17f8b149b6..91f13362fa 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -290,7 +290,6 @@ LcmForceDrawer::LcmForceDrawer( {0, 1, 0, 1}); meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); - DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); } From 766b75f2eab14a058d6f4c23beccb6c7e8bd8053 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 8 Jan 2024 13:29:12 -0500 Subject: [PATCH 590/758] fixing small typo in gains --- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index beff6b4a1e..b8743d3172 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -26,7 +26,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -near_target_threshold: 0.07g +near_target_threshold: 0.07 neutral_position: [0.45, 0, 0.47] x_scale: 0.1 y_scale: 0.1 From 267d621261129638030142ccde7e94454530d2fd Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 8 Jan 2024 14:47:13 -0500 Subject: [PATCH 591/758] updating support position to reflect hardware --- examples/franka/parameters/franka_c3_controller_params.yaml | 6 +++--- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 4 ++-- examples/franka/urdf/left_support_point_contact.urdf | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index b8743d3172..9d39fde5ba 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -19,15 +19,15 @@ scene_index: 1 left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.8, 0.15, 0.45] -right_support_position: [0.8, -0.15, 0.45] +left_support_position: [0.8, 0.15, 0.46] +right_support_position: [0.8, -0.15, 0.46] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused near_target_threshold: 0.07 -neutral_position: [0.45, 0, 0.47] +neutral_position: [0.45, 0, 0.485] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 32ca425eb7..512a6a88da 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 0.6 end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false # roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 8d3f90ef5b..9dc3ceb2a4 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -17,8 +17,8 @@ visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.45] -right_support_position: [0.8, -0.15, 0.45] +left_support_position: [0.8, 0.15, 0.465] +right_support_position: [0.8, -0.15, 0.465] dt: 0.0005 realtime_rate: 1.0 diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index f6f3b8d5bb..3efa82100e 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -19,9 +19,9 @@ - + - + From 1c82ac24ed0c886c9409c9b580a0f7b75c698221 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 10 Jan 2024 16:44:24 -0500 Subject: [PATCH 592/758] adding feature for c3 to place plate back --- examples/franka/franka_c3_controller.cc | 60 +++++++++---------- .../parameters/franka_c3_controller_params.h | 8 ++- .../franka_c3_controller_params.yaml | 4 +- .../franka/systems/plate_balancing_target.cc | 43 ++++++++----- .../franka/systems/plate_balancing_target.h | 12 ++-- 5 files changed, 76 insertions(+), 51 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index ca4e3bbbc3..ae550fcc4e 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -19,12 +19,12 @@ #include "examples/franka/systems/plate_balancing_target.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" +#include "systems/controllers/c3/lcs_factory_system.h" #include "systems/controllers/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/controllers/c3/lcs_factory_system.h" namespace dairlib { @@ -67,8 +67,8 @@ int DoMain(int argc, char* argv[]) { FLAGS_controller_settings); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); - C3Options c3_options = - drake::yaml::LoadYamlFile(controller_params.c3_options_file[controller_params.scene_index]); + C3Options c3_options = drake::yaml::LoadYamlFile( + controller_params.c3_options_file[controller_params.scene_index]); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(controller_params.osqp_settings_file)) @@ -88,8 +88,9 @@ int DoMain(int argc, char* argv[]) { plant_franka.WeldFrames(plant_franka.world_frame(), plant_franka.GetFrameByName("panda_link0"), X_WI); - RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), controller_params.tool_attachment_frame); + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); plant_franka.WeldFrames( plant_franka.GetFrameByName("panda_link7"), plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); @@ -113,25 +114,26 @@ int DoMain(int argc, char* argv[]) { drake::multibody::ModelInstanceIndex left_support_index; drake::multibody::ModelInstanceIndex right_support_index; - if (controller_params.scene_index == 1){ - left_support_index = - parser_plate.AddModels(FindResourceOrThrow(controller_params.left_support_model))[0]; - right_support_index = - parser_plate.AddModels(FindResourceOrThrow(controller_params.right_support_model))[0]; - RigidTransform T_S1_W = RigidTransform( - drake::math::RotationMatrix(), controller_params.left_support_position); - RigidTransform T_S2_W = RigidTransform( - drake::math::RotationMatrix(), controller_params.right_support_position); - plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", left_support_index), - T_S1_W); - plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", right_support_index), - T_S2_W); + if (controller_params.scene_index == 1) { + left_support_index = parser_plate.AddModels( + FindResourceOrThrow(controller_params.left_support_model))[0]; + right_support_index = parser_plate.AddModels( + FindResourceOrThrow(controller_params.right_support_model))[0]; + RigidTransform T_S1_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.left_support_position); + RigidTransform T_S2_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.right_support_position); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); } parser_plate.AddModels(controller_params.tray_model); - plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), plant_for_lcs.GetFrameByName("base_link"), X_WI); plant_for_lcs.Finalize(); @@ -222,12 +224,10 @@ int DoMain(int argc, char* argv[]) { auto plate_balancing_target = builder.AddSystem(plant_tray); - VectorXd neutral_position = Eigen::Map( - controller_params.neutral_position.data(), - controller_params.neutral_position.size()); plate_balancing_target->SetRemoteControlParameters( - neutral_position, controller_params.x_scale, controller_params.y_scale, - controller_params.z_scale); + controller_params.initial_pose, controller_params.first_target, + controller_params.second_target, controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); std::vector input_sizes = {3, 7, 3, 6}; auto target_state_mux = builder.AddSystem(input_sizes); @@ -246,8 +246,8 @@ int DoMain(int argc, char* argv[]) { builder.Connect(tray_zero_velocity_source->get_output_port(), target_state_mux->get_input_port(3)); auto lcs_factory = builder.AddSystem( - plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, plate_context_ad.get(), - contact_pairs, c3_options); + plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, + plate_context_ad.get(), contact_pairs, c3_options); auto controller = builder.AddSystem( plant_for_lcs, &plant_for_lcs_context, c3_options); auto c3_trajectory_generator = @@ -310,8 +310,8 @@ int DoMain(int argc, char* argv[]) { c3_output_publisher->get_input_port()); builder.Connect(c3_output_sender->get_output_port_c3_force(), c3_forces_publisher->get_input_port()); -// builder.Connect(c3_output_sender->get_output_port_next_c3_input(), -// lcs_factory->get_input_port_lcs_input()); + // builder.Connect(c3_output_sender->get_output_port_next_c3_input(), + // lcs_factory->get_input_port_lcs_input()); auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 4c4d9c3915..3f927bc6d7 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -20,7 +20,9 @@ struct FrankaC3ControllerParams { int scene_index; - Eigen::Vector3d neutral_position; + Eigen::Vector3d initial_pose; + Eigen::Vector3d first_target; + Eigen::Vector3d second_target; double x_scale; double y_scale; double z_scale; @@ -45,7 +47,9 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(scene_index)); - a->Visit(DRAKE_NVP(neutral_position)); + a->Visit(DRAKE_NVP(initial_pose)); + a->Visit(DRAKE_NVP(first_target)); + a->Visit(DRAKE_NVP(second_target)); a->Visit(DRAKE_NVP(x_scale)); a->Visit(DRAKE_NVP(y_scale)); a->Visit(DRAKE_NVP(z_scale)); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 9d39fde5ba..6853ddc19f 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -27,7 +27,9 @@ include_end_effector_orientation: false target_frequency: 0 #unused near_target_threshold: 0.07 -neutral_position: [0.45, 0, 0.485] +initial_pose: [0.65, 0.00, 0.485] +first_target: [0.45, 0, 0.47] +second_target: [0.45, 0, 0.57] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 538973f40c..38bb3bc866 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -14,8 +14,8 @@ namespace dairlib { namespace systems { PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( - const MultibodyPlant& object_plant, double first_target_range) - : first_target_range_(first_target_range) { + const MultibodyPlant& object_plant, double target_threshold) + : target_threshold_(target_threshold) { // Input/Output Setup radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", @@ -45,17 +45,24 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( drake::systems::DiscreteValues* discrete_state) const { const StateVector* tray_state = (StateVector*)this->EvalVectorInput(context, tray_state_port_); - if ((tray_state->GetPositions().tail(3) - neutral_pose_).norm() < - first_target_range_) { + if (context.get_discrete_state(reached_first_target_idx_)[0] == 0 && + (tray_state->GetPositions().tail(3) - first_target_).norm() < + target_threshold_) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 1; } + if ((tray_state->GetPositions().tail(3) - second_target_).norm() < 0.02) { + discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 2; + } return EventStatus::Succeeded(); } void PlateBalancingTargetGenerator::SetRemoteControlParameters( - const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, + const Eigen::Vector3d& initial_pose, const Eigen::Vector3d& first_target, + const Eigen::Vector3d& second_target, double x_scale, double y_scale, double z_scale) { - neutral_pose_ = neutral_pose; + initial_pose_ = initial_pose; + first_target_ = first_target; + second_target_ = second_target; x_scale_ = x_scale; y_scale_ = y_scale; z_scale_ = z_scale; @@ -67,16 +74,21 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( const auto& radio_out = this->EvalInputValue(context, radio_port_); - VectorXd y0 = neutral_pose_; + VectorXd y0 = first_target_; // Update target if remote trigger is active + if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { + y0 = second_target_; // raise the tray once it is close + y0[2] -= 0.015; + } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2) { + y0 = initial_pose_; // raise the tray once it is close + y0[2] -= 0.015; + y0[0] -= 0.1; + } if (radio_out->channel[13] > 0) { y0(0) += radio_out->channel[0] * x_scale_; y0(1) += radio_out->channel[1] * y_scale_; y0(2) += radio_out->channel[2] * z_scale_; } - if (context.get_discrete_state(reached_first_target_idx_)[0]) { - y0[2] += 0.1; // raise the tray once it is close - } target->SetFromVector(y0); } @@ -86,14 +98,17 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( const auto& radio_out = this->EvalInputValue(context, radio_port_); VectorXd target_tray_state = VectorXd::Zero(7); - VectorXd tray_position = neutral_pose_; + VectorXd tray_position = first_target_; tray_position[2] += 0.015; // thickness of end effector and tray + + if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { + tray_position = second_target_; // raise the tray once it is close + } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2) { + tray_position = initial_pose_; // raise the tray once it is close + } tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; - if (context.get_discrete_state(reached_first_target_idx_)[0]) { - tray_position[2] += 0.1; // raise the tray once it is close - } target_tray_state << 1, 0, 0, 0, tray_position; target->SetFromVector(target_tray_state); } diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index a109028d68..f17fc1a88b 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -13,7 +13,7 @@ class PlateBalancingTargetGenerator : public drake::systems::LeafSystem { public: PlateBalancingTargetGenerator( - const drake::multibody::MultibodyPlant& object_plant, double first_target_range = 0.075); + const drake::multibody::MultibodyPlant& object_plant, double target_threshold = 0.075); const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); @@ -33,7 +33,9 @@ class PlateBalancingTargetGenerator return this->get_output_port(tray_target_port_); } - void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, + void SetRemoteControlParameters(const Eigen::Vector3d& initial_pose, + const Eigen::Vector3d& first_target, + const Eigen::Vector3d& second_target, double x_scale, double y_scale, double z_scale); @@ -52,8 +54,10 @@ class PlateBalancingTargetGenerator drake::systems::OutputPortIndex tray_target_port_; drake::systems::DiscreteStateIndex reached_first_target_idx_; - Eigen::Vector3d neutral_pose_; - double first_target_range_; + Eigen::Vector3d initial_pose_; + Eigen::Vector3d first_target_; + Eigen::Vector3d second_target_; + double target_threshold_; double x_scale_; double y_scale_; double z_scale_; From f2f8e0f0af08d7a5dd9d88bb230b8a7f6c7064e2 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 11 Jan 2024 11:16:16 -0500 Subject: [PATCH 593/758] adding feature to easily repeat motion --- examples/Cassie/cassie_xbox_remote.py | 2 +- .../franka_c3_controller_params.yaml | 10 ++++---- .../franka_c3_options_translation.yaml | 2 ++ .../franka_c3_options_w_supports.yaml | 1 + .../franka_osc_controller_params.yaml | 5 ++-- .../franka/parameters/franka_sim_params.yaml | 4 ++-- .../franka/systems/plate_balancing_target.cc | 24 +++++++++++++++---- .../urdf/left_support_point_contact.urdf | 4 ++-- examples/franka/urdf/plate_end_effector.urdf | 4 ++-- solvers/c3_options.h | 2 ++ systems/controllers/c3_controller.cc | 3 ++- systems/controllers/c3_controller.h | 3 +-- 12 files changed, 42 insertions(+), 22 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index c72354af4b..998f6a642d 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -85,7 +85,7 @@ def main(): print("Force Tracking Status: " + str(latching_switch_x)) if event.button == 3: latching_switch_y = not latching_switch_y - print("End Effector Follow Status: " + str(latching_switch_b)) + print("Ready to Reset Status: " + str(latching_switch_y)) # Send LCM message diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 6853ddc19f..daed984de1 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -19,17 +19,17 @@ scene_index: 1 left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.8, 0.15, 0.46] -right_support_position: [0.8, -0.15, 0.46] +left_support_position: [0.8, 0.15, 0.45] +right_support_position: [0.8, -0.15, 0.45] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -near_target_threshold: 0.07 -initial_pose: [0.65, 0.00, 0.485] +near_target_threshold: 0.03 +initial_pose: [0.7, 0.00, 0.485] first_target: [0.45, 0, 0.47] -second_target: [0.45, 0, 0.57] +second_target: [0.45, 0, 0.6] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 932ac25463..f8b8de191e 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -9,6 +9,8 @@ projection_type: 'MIQP' #contact_model: 'anitescu' contact_model: 'stewart_and_trinkle' warm_start: true +use_predicted_x0: true +solve_time_filter_alpha: 0.9 mu: [0.2, 0.2, 0.2] dt: 0.05 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index d6cb763f5b..3abaa7436d 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -10,6 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true +solve_time_filter_alpha: 0.9 mu: [0.55, 0.55, 0.55, 0.1, 0.1, 0.1, 0.1] dt: 0.075 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 512a6a88da..2140bf9708 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -18,12 +18,11 @@ w_soft_constraint: 0.0 w_lambda: 0.0 impact_threshold: 0.000 impact_tau: 0.000 -mu: 0.6 +mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false -# roll, yaw, pitch, knee, knee_spring, ankle_joint, ankle_spring, toe W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] W_lambda_c_reg: [ 0.001, 0.001, 0.01, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 9dc3ceb2a4..8d3f90ef5b 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -17,8 +17,8 @@ visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.465] -right_support_position: [0.8, -0.15, 0.465] +left_support_position: [0.8, 0.15, 0.45] +right_support_position: [0.8, -0.15, 0.45] dt: 0.0005 realtime_rate: 1.0 diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 38bb3bc866..a9e0818b93 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -45,14 +45,28 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( drake::systems::DiscreteValues* discrete_state) const { const StateVector* tray_state = (StateVector*)this->EvalVectorInput(context, tray_state_port_); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + + // Ugly FSM if (context.get_discrete_state(reached_first_target_idx_)[0] == 0 && (tray_state->GetPositions().tail(3) - first_target_).norm() < target_threshold_) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 1; } - if ((tray_state->GetPositions().tail(3) - second_target_).norm() < 0.02) { + if ((tray_state->GetPositions().tail(3) - second_target_).norm() < + 0.75 * target_threshold_) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 2; } + if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 && + (tray_state->GetPositions().tail(3) - initial_pose_).norm() < + target_threshold_) { + discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 3; + } + if (radio_out->channel[12] > 0 && + context.get_discrete_state(reached_first_target_idx_)[0] == 3) { + discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 0; + } return EventStatus::Succeeded(); } @@ -79,8 +93,9 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { y0 = second_target_; // raise the tray once it is close y0[2] -= 0.015; - } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2) { - y0 = initial_pose_; // raise the tray once it is close + } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 || + context.get_discrete_state(reached_first_target_idx_)[0] == 3) { + y0 = initial_pose_; // put the tray back y0[2] -= 0.015; y0[0] -= 0.1; } @@ -103,7 +118,8 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { tray_position = second_target_; // raise the tray once it is close - } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2) { + } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 || + context.get_discrete_state(reached_first_target_idx_)[0] == 3) { tray_position = initial_pose_; // raise the tray once it is close } tray_position(0) += radio_out->channel[0] * x_scale_; diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index 3efa82100e..f6f3b8d5bb 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -19,9 +19,9 @@ - + - + diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index b81d96de63..5b6d6dfdc2 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,8 +15,8 @@ - - + + diff --git a/solvers/c3_options.h b/solvers/c3_options.h index fb0724e509..567d0eda0f 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -14,6 +14,7 @@ struct C3Options { std::string contact_model; bool warm_start; bool use_predicted_x0; + double solve_time_filter_alpha; int N; double gamma; @@ -64,6 +65,7 @@ struct C3Options { } a->Visit(DRAKE_NVP(warm_start)); a->Visit(DRAKE_NVP(use_predicted_x0)); + a->Visit(DRAKE_NVP(solve_time_filter_alpha)); a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(dt)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index f28c4a1aec..2c4dda8dbb 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -53,6 +53,7 @@ C3Controller::C3Controller( n_u_ = plant_.num_actuators(); n_x_ = n_q_ + n_v_; dt_ = c3_options_.dt; + solve_time_filter_constant_ = c3_options_.solve_time_filter_alpha; if (c3_options_.contact_model == "stewart_and_trinkle") { n_lambda_ = 2 * c3_options_.num_contacts + @@ -230,7 +231,7 @@ void C3Controller::OutputC3Solution( if (filtered_solve_time_ < dt_) { double weight = (dt_ - filtered_solve_time_) / dt_; x_pred_ = weight * z_sol[0].segment(0, n_x_) + - (1 - weight) * z_sol[1].segment(0, n_x_); + (1 - weight) * z_sol[1].segment(0, n_x_); } else { x_pred_ = z_sol[1].segment(0, n_x_); } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 13794e444a..d9005df655 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -97,8 +97,7 @@ class C3Controller : public drake::systems::LeafSystem { mutable double filtered_solve_time_; mutable Eigen::VectorXd x_pred_; - const double solve_time_filter_constant_ = 0.9; - + double solve_time_filter_constant_; drake::systems::DiscreteStateIndex plan_start_time_index_; std::vector Q_; std::vector R_; From 333b5ef0699cb47a9b3bae6d0cf6e3584eca6226 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 11 Jan 2024 11:42:04 -0500 Subject: [PATCH 594/758] small changes to make the plate sliding demo more consistent --- examples/Cassie/cassie_xbox_remote.py | 2 +- .../parameters/franka_c3_controller_params.yaml | 8 ++++---- .../franka/parameters/franka_sim_params.yaml | 4 ++-- .../franka/systems/end_effector_trajectory.cc | 16 ++++++---------- .../franka/systems/plate_balancing_target.cc | 2 +- 5 files changed, 14 insertions(+), 18 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 998f6a642d..a15ad202d4 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -102,7 +102,7 @@ def main(): radio_msg.channel[14] = latching_switch_a radio_msg.channel[11] = latching_switch_x radio_msg.channel[12] = latching_switch_y - # radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) + radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) publisher.publish("RADIO", radio_msg.encode()) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index daed984de1..78030b26e6 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -19,16 +19,16 @@ scene_index: 1 left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.8, 0.15, 0.45] -right_support_position: [0.8, -0.15, 0.45] +left_support_position: [0.8, 0.15, 0.46] +right_support_position: [0.8, -0.15, 0.46] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused near_target_threshold: 0.03 -initial_pose: [0.7, 0.00, 0.485] -first_target: [0.45, 0, 0.47] +initial_pose: [0.7, 0.00, 0.495] +first_target: [0.45, 0, 0.48] second_target: [0.45, 0, 0.6] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 8d3f90ef5b..13cbf428bc 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -17,8 +17,8 @@ visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.45] -right_support_position: [0.8, -0.15, 0.45] +left_support_position: [0.8, 0.15, 0.46] +right_support_position: [0.8, -0.15, 0.46] dt: 0.0005 realtime_rate: 1.0 diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 9557a71f43..8659a17919 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -1,5 +1,5 @@ #include "end_effector_trajectory.h" - +#include #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" @@ -66,17 +66,11 @@ PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( this->template EvalVectorInput(context, state_port_); const auto& radio_out = this->EvalInputValue(context, radio_port_); - double t = robot_output->get_timestamp(); - double dt = 0.1; VectorXd y0 = neutral_pose_; y0(0) += radio_out->channel[0] * x_scale_; y0(1) += radio_out->channel[1] * y_scale_; y0(2) += radio_out->channel[2] * z_scale_; - VectorXd ydot0 = VectorXd::Zero(3); - std::vector breaks = {t, t + dt}; - std::vector samples = {y0, y0 + dt * ydot0}; - return drake::trajectories::PiecewisePolynomial::FirstOrderHold( - breaks, samples); + return drake::trajectories::PiecewisePolynomial(y0); } void EndEffectorTrajectoryGenerator::CalcTraj( @@ -97,8 +91,10 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { - *casted_traj = *(PiecewisePolynomial*)dynamic_cast< - const PiecewisePolynomial*>(&trajectory_input); + if ((context.get_time() - trajectory_input.start_time()) < 0.13){ + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } } } } diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index a9e0818b93..550622e2de 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -63,7 +63,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( target_threshold_) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 3; } - if (radio_out->channel[12] > 0 && + if (radio_out->channel[15] < 0 && context.get_discrete_state(reached_first_target_idx_)[0] == 3) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 0; } From 21ee642e02f8c6e6c9f054765144bed34d2df873 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 11 Jan 2024 13:24:10 -0500 Subject: [PATCH 595/758] gains for hardware experiments --- .../franka/parameters/franka_c3_controller_params.yaml | 8 ++++---- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 6 +++--- examples/franka/systems/end_effector_trajectory.cc | 2 +- examples/franka/urdf/left_support_point_contact.urdf | 4 ++-- 5 files changed, 11 insertions(+), 11 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 78030b26e6..546de8408a 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -19,16 +19,16 @@ scene_index: 1 left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.8, 0.15, 0.46] -right_support_position: [0.8, -0.15, 0.46] +left_support_position: [0.8, 0.15, 0.453] +right_support_position: [0.8, -0.15, 0.453] include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused near_target_threshold: 0.03 -initial_pose: [0.7, 0.00, 0.495] -first_target: [0.45, 0, 0.48] +initial_pose: [0.7, 0.00, 0.488] +first_target: [0.45, 0, 0.471] second_target: [0.45, 0, 0.6] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2140bf9708..fcd7090eab 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 13cbf428bc..f6753f7e8e 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -9,7 +9,7 @@ left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 tray_publish_rate: 10 -visualizer_publish_rate: 30 +visualizer_publish_rate: 15 actuator_delay: 0.000 scene_index: 1 @@ -17,8 +17,8 @@ visualize: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.46] -right_support_position: [0.8, -0.15, 0.46] +left_support_position: [0.8, 0.15, 0.453] +right_support_position: [0.8, -0.15, 0.453] dt: 0.0005 realtime_rate: 1.0 diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 8659a17919..79ee442aed 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -91,7 +91,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { - if ((context.get_time() - trajectory_input.start_time()) < 0.13){ + if ((context.get_time() - trajectory_input.start_time()) < 0.15){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/left_support_point_contact.urdf index f6f3b8d5bb..3efa82100e 100644 --- a/examples/franka/urdf/left_support_point_contact.urdf +++ b/examples/franka/urdf/left_support_point_contact.urdf @@ -19,9 +19,9 @@ - + - + From 9e06e62c01f1dd96ccdd9eabe35b4e3829ce0e84 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 11 Jan 2024 17:07:04 -0500 Subject: [PATCH 596/758] removing unnecessary setting of solver options every iteration --- solvers/c3.cc | 2 -- solvers/c3.h | 3 +-- systems/controllers/c3_controller.cc | 2 -- systems/controllers/c3_controller.h | 1 + 4 files changed, 2 insertions(+), 6 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index 86896934fd..796bfbe5a5 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -62,7 +62,6 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, options_(options), h_is_zero_(H_[0].isZero(0)), prog_(MathematicalProgram()), - solver_options_(SolverOptions()), osqp_(OsqpSolver()) { if (warm_start_) { warm_start_delta_.resize(options_.admm_iter); @@ -295,7 +294,6 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, prog_.SetInitialGuess(x_[N_], warm_start_x_[admm_iteration][N_]); } - prog_.SetSolverOptions(solver_options_); MathematicalProgramResult result = osqp_.Solve(prog_); if (result.is_success()) { diff --git a/solvers/c3.h b/solvers/c3.h index a6a709ddee..03a2120200 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -96,7 +96,7 @@ class C3 { const int& warm_start_index) = 0; void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { - solver_options_ = options; + prog_.SetSolverOptions(options); } std::vector GetFullSolution() { return *z_sol_; } @@ -139,7 +139,6 @@ class C3 { bool h_is_zero_; drake::solvers::MathematicalProgram prog_; - drake::solvers::SolverOptions solver_options_; drake::solvers::OsqpSolver osqp_; std::vector x_; std::vector u_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 2c4dda8dbb..9d01acd3f9 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -142,7 +142,6 @@ C3Controller::C3Controller( this->DeclareAbstractOutputPort("c3_intermediates", c3_intermediates, &C3Controller::OutputC3Intermediates) .get_index(); - plan_start_time_index_ = DeclareDiscreteState(1); x_pred_ = VectorXd::Zero(n_x_); DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); @@ -191,7 +190,6 @@ drake::systems::EventStatus C3Controller::ComputePlan( DRAKE_DEMAND(lcs_x->get_data()[2] > 0.35); DRAKE_DEMAND(lcs_x->get_data()[2] < 0.6); - c3_->SetOsqpSolverOptions(solver_options_); c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index d9005df655..bde37c008e 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -53,6 +53,7 @@ class C3Controller : public drake::systems::LeafSystem { void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { solver_options_ = options; + c3_->SetOsqpSolverOptions(solver_options_); } private: From 942b98904e4c134974653d34fa49b0fc0dbbb708 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 12 Jan 2024 10:59:29 -0500 Subject: [PATCH 597/758] more intelligent setting of next target --- examples/franka/franka_c3_controller.cc | 6 +-- .../parameters/franka_c3_controller_params.h | 10 +++-- .../franka_c3_controller_params.yaml | 10 +++-- .../franka_c3_options_w_supports.yaml | 2 +- .../franka_osc_controller_params.yaml | 2 +- .../franka/systems/plate_balancing_target.cc | 40 ++++++++++--------- .../franka/systems/plate_balancing_target.h | 10 +++-- 7 files changed, 45 insertions(+), 35 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index ae550fcc4e..4de1a2b08c 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -223,10 +223,10 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.radio_channel, &lcm)); auto plate_balancing_target = - builder.AddSystem(plant_tray); + builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); plate_balancing_target->SetRemoteControlParameters( - controller_params.initial_pose, controller_params.first_target, - controller_params.second_target, controller_params.x_scale, + controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], controller_params.x_scale, controller_params.y_scale, controller_params.z_scale); std::vector input_sizes = {3, 7, 3, 6}; auto target_state_mux = diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 3f927bc6d7..fb320cf326 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -20,9 +20,9 @@ struct FrankaC3ControllerParams { int scene_index; - Eigen::Vector3d initial_pose; - Eigen::Vector3d first_target; - Eigen::Vector3d second_target; + std::vector first_target; + std::vector second_target; + std::vector third_target; double x_scale; double y_scale; double z_scale; @@ -30,6 +30,7 @@ struct FrankaC3ControllerParams { Eigen::Vector3d left_support_position; Eigen::Vector3d right_support_position; + double end_effector_thickness; template void Serialize(Archive* a) { @@ -47,9 +48,9 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(scene_index)); - a->Visit(DRAKE_NVP(initial_pose)); a->Visit(DRAKE_NVP(first_target)); a->Visit(DRAKE_NVP(second_target)); + a->Visit(DRAKE_NVP(third_target)); a->Visit(DRAKE_NVP(x_scale)); a->Visit(DRAKE_NVP(y_scale)); a->Visit(DRAKE_NVP(z_scale)); @@ -57,5 +58,6 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); + a->Visit(DRAKE_NVP(end_effector_thickness)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 546de8408a..a2b6adb59d 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -21,15 +21,19 @@ right_support_model: examples/franka/urdf/left_support_point_contact.urdf left_support_position: [0.8, 0.15, 0.453] right_support_position: [0.8, -0.15, 0.453] +end_effector_thickness: 0.015 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused near_target_threshold: 0.03 -initial_pose: [0.7, 0.00, 0.488] -first_target: [0.45, 0, 0.471] -second_target: [0.45, 0, 0.6] +first_target: [[0.45, 0.0, 0.45], + [0.45, 0, 0.486]] +second_target: [[0.45, 0.0, 0.45], + [0.45, 0, 0.6]] +third_target: [[0.45, 0.0, 0.45], + [0.7, 0.00, 0.488]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 3abaa7436d..6209692d5e 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -29,7 +29,7 @@ w_G: 0.1 w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 100, 100, 1, 1, 1, 1, 15000, 15000, 15000, +q_vector: [150, 100, 100, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 10, 1, 100, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index fcd7090eab..2140bf9708 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 550622e2de..c0118d31bf 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -14,8 +14,10 @@ namespace dairlib { namespace systems { PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( - const MultibodyPlant& object_plant, double target_threshold) - : target_threshold_(target_threshold) { + const MultibodyPlant& object_plant, double end_effector_thickness, + double target_threshold) + : end_effector_thickness_(end_effector_thickness), + target_threshold_(target_threshold) { // Input/Output Setup radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", @@ -59,7 +61,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 2; } if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 && - (tray_state->GetPositions().tail(3) - initial_pose_).norm() < + (tray_state->GetPositions().tail(3) - third_target_).norm() < target_threshold_) { discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 3; } @@ -71,12 +73,12 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( } void PlateBalancingTargetGenerator::SetRemoteControlParameters( - const Eigen::Vector3d& initial_pose, const Eigen::Vector3d& first_target, - const Eigen::Vector3d& second_target, double x_scale, double y_scale, + const Eigen::Vector3d& first_target, const Eigen::Vector3d& second_target, + const Eigen::Vector3d& third_target, double x_scale, double y_scale, double z_scale) { - initial_pose_ = initial_pose; first_target_ = first_target; second_target_ = second_target; + third_target_ = third_target; x_scale_ = x_scale; y_scale_ = y_scale; z_scale_ = z_scale; @@ -88,23 +90,24 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( const auto& radio_out = this->EvalInputValue(context, radio_port_); - VectorXd y0 = first_target_; + VectorXd end_effector_position = first_target_; // Update target if remote trigger is active if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { - y0 = second_target_; // raise the tray once it is close - y0[2] -= 0.015; + end_effector_position = second_target_; // raise the tray once it is close } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 || context.get_discrete_state(reached_first_target_idx_)[0] == 3) { - y0 = initial_pose_; // put the tray back - y0[2] -= 0.015; - y0[0] -= 0.1; + end_effector_position = third_target_; // put the tray back + } + end_effector_position[2] -= end_effector_thickness_; // place end effector below tray + if (end_effector_position[0] > 0.6) { + end_effector_position[0] = 0.6; // keep it within the workspace } if (radio_out->channel[13] > 0) { - y0(0) += radio_out->channel[0] * x_scale_; - y0(1) += radio_out->channel[1] * y_scale_; - y0(2) += radio_out->channel[2] * z_scale_; + end_effector_position(0) += radio_out->channel[0] * x_scale_; + end_effector_position(1) += radio_out->channel[1] * y_scale_; + end_effector_position(2) += radio_out->channel[2] * z_scale_; } - target->SetFromVector(y0); + target->SetFromVector(end_effector_position); } void PlateBalancingTargetGenerator::CalcTrayTarget( @@ -114,18 +117,17 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( this->EvalInputValue(context, radio_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = first_target_; - tray_position[2] += 0.015; // thickness of end effector and tray if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { tray_position = second_target_; // raise the tray once it is close } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 || context.get_discrete_state(reached_first_target_idx_)[0] == 3) { - tray_position = initial_pose_; // raise the tray once it is close + tray_position = third_target_; // raise the tray once it is close } tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; - target_tray_state << 1, 0, 0, 0, tray_position; + target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat target->SetFromVector(target_tray_state); } diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index f17fc1a88b..00771dfaf3 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -13,7 +13,8 @@ class PlateBalancingTargetGenerator : public drake::systems::LeafSystem { public: PlateBalancingTargetGenerator( - const drake::multibody::MultibodyPlant& object_plant, double target_threshold = 0.075); + const drake::multibody::MultibodyPlant& object_plant, + double end_effector_thickness, double target_threshold = 0.075); const drake::systems::InputPort& get_input_port_radio() const { return this->get_input_port(radio_port_); @@ -33,9 +34,9 @@ class PlateBalancingTargetGenerator return this->get_output_port(tray_target_port_); } - void SetRemoteControlParameters(const Eigen::Vector3d& initial_pose, - const Eigen::Vector3d& first_target, + void SetRemoteControlParameters(const Eigen::Vector3d& first_target, const Eigen::Vector3d& second_target, + const Eigen::Vector3d& third_target, double x_scale, double y_scale, double z_scale); @@ -54,9 +55,10 @@ class PlateBalancingTargetGenerator drake::systems::OutputPortIndex tray_target_port_; drake::systems::DiscreteStateIndex reached_first_target_idx_; - Eigen::Vector3d initial_pose_; + double end_effector_thickness_; Eigen::Vector3d first_target_; Eigen::Vector3d second_target_; + Eigen::Vector3d third_target_; double target_threshold_; double x_scale_; double y_scale_; From 11f7803367bb68b8c7a3127c65dbae950990ffaf Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 12 Jan 2024 11:09:59 -0500 Subject: [PATCH 598/758] minor updates --- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- systems/controllers/c3_controller.cc | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index a2b6adb59d..e6bf7aecb4 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -27,7 +27,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -near_target_threshold: 0.03 +near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.45], [0.45, 0, 0.486]] second_target: [[0.45, 0.0, 0.45], diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 9d01acd3f9..d7fd3c76f9 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -183,6 +183,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector x_desired = std::vector(N_ + 1, x_des.value()); + // Force Checking of Workspace Limits DRAKE_DEMAND(lcs_x->get_data()[0] > 0.35); DRAKE_DEMAND(lcs_x->get_data()[0] < 0.65); DRAKE_DEMAND(lcs_x->get_data()[1] > -0.1); From 83a4da4050d6930c877ad8d770df831fae31bedd Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 12 Jan 2024 13:19:40 -0500 Subject: [PATCH 599/758] changing w support demo --- .../franka_c3_controller_params.yaml | 2 +- .../franka/systems/plate_balancing_target.cc | 78 +++++++++++++------ .../franka/systems/plate_balancing_target.h | 5 +- examples/franka/urdf/plate_end_effector.urdf | 2 +- .../urdf/plate_end_effector_translation.urdf | 2 +- systems/controllers/c3_controller.cc | 6 +- 6 files changed, 63 insertions(+), 32 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index e6bf7aecb4..c5112bad2c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -31,7 +31,7 @@ near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.45], [0.45, 0, 0.486]] second_target: [[0.45, 0.0, 0.45], - [0.45, 0, 0.6]] + [0.45, 0, 0.65]] third_target: [[0.45, 0.0, 0.45], [0.7, 0.00, 0.488]] x_scale: 0.1 diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index c0118d31bf..f9ae9d7248 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -37,7 +37,9 @@ PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( "tray_target", BasicVector(7), &PlateBalancingTargetGenerator::CalcTrayTarget) .get_index(); - reached_first_target_idx_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + sequence_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + within_target_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + time_entered_target_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); DeclareForcedDiscreteUpdateEvent( &PlateBalancingTargetGenerator::DiscreteVariableUpdate); } @@ -51,23 +53,48 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( this->EvalInputValue(context, radio_port_); // Ugly FSM - if (context.get_discrete_state(reached_first_target_idx_)[0] == 0 && - (tray_state->GetPositions().tail(3) - first_target_).norm() < - target_threshold_) { - discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 1; + int current_sequence = context.get_discrete_state(sequence_index_)[0]; + int within_target = context.get_discrete_state(within_target_index_)[0]; + int time_entered_target = + context.get_discrete_state(time_entered_target_index_)[0]; + if (current_sequence == 0) { + if ((tray_state->GetPositions().tail(3) - first_target_).norm() < + target_threshold_) { + if (within_target == + 0) { // set the time of when the tray first hits the target + discrete_state->get_mutable_value(time_entered_target_index_)[0] = + context.get_time(); + } + discrete_state->get_mutable_value(within_target_index_)[0] = 1; + } + if (within_target == 1 && + (context.get_time() - time_entered_target) > 1.0) { + discrete_state->get_mutable_value(within_target_index_)[0] = 0; + discrete_state->get_mutable_value(sequence_index_)[0] = 1; + } + } else if (current_sequence == 1) { + if ((tray_state->GetPositions().tail(3) - second_target_).norm() < + target_threshold_) { + if (within_target == + 0) { // set the time of when the tray first hits the target + discrete_state->get_mutable_value(time_entered_target_index_)[0] = + context.get_time(); + } + discrete_state->get_mutable_value(within_target_index_)[0] = 1; + } + if (within_target == 1 && + (context.get_time() - time_entered_target) > delay_at_top_) { + discrete_state->get_mutable_value(within_target_index_)[0] = 0; + discrete_state->get_mutable_value(sequence_index_)[0] = 2; + } + } else if (current_sequence == 2) { + if ((tray_state->GetPositions().tail(3) - third_target_).norm() < + target_threshold_) { + discrete_state->get_mutable_value(sequence_index_)[0] = 3; + } } - if ((tray_state->GetPositions().tail(3) - second_target_).norm() < - 0.75 * target_threshold_) { - discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 2; - } - if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 && - (tray_state->GetPositions().tail(3) - third_target_).norm() < - target_threshold_) { - discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 3; - } - if (radio_out->channel[15] < 0 && - context.get_discrete_state(reached_first_target_idx_)[0] == 3) { - discrete_state->get_mutable_value(reached_first_target_idx_)[0] = 0; + if (current_sequence == 3 && radio_out->channel[15] < 0) { + discrete_state->get_mutable_value(sequence_index_)[0] = 0; } return EventStatus::Succeeded(); } @@ -92,13 +119,14 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( VectorXd end_effector_position = first_target_; // Update target if remote trigger is active - if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { + if (context.get_discrete_state(sequence_index_)[0] == 1) { end_effector_position = second_target_; // raise the tray once it is close - } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 || - context.get_discrete_state(reached_first_target_idx_)[0] == 3) { + } else if (context.get_discrete_state(sequence_index_)[0] == 2 || + context.get_discrete_state(sequence_index_)[0] == 3) { end_effector_position = third_target_; // put the tray back } - end_effector_position[2] -= end_effector_thickness_; // place end effector below tray + end_effector_position[2] -= + end_effector_thickness_; // place end effector below tray if (end_effector_position[0] > 0.6) { end_effector_position[0] = 0.6; // keep it within the workspace } @@ -118,16 +146,16 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = first_target_; - if (context.get_discrete_state(reached_first_target_idx_)[0] == 1) { + if (context.get_discrete_state(sequence_index_)[0] == 1) { tray_position = second_target_; // raise the tray once it is close - } else if (context.get_discrete_state(reached_first_target_idx_)[0] == 2 || - context.get_discrete_state(reached_first_target_idx_)[0] == 3) { + } else if (context.get_discrete_state(sequence_index_)[0] == 2 || + context.get_discrete_state(sequence_index_)[0] == 3) { tray_position = third_target_; // raise the tray once it is close } tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; - target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat + target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat target->SetFromVector(target_tray_state); } diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 00771dfaf3..4a992c1593 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -54,11 +54,14 @@ class PlateBalancingTargetGenerator drake::systems::OutputPortIndex end_effector_target_port_; drake::systems::OutputPortIndex tray_target_port_; - drake::systems::DiscreteStateIndex reached_first_target_idx_; + drake::systems::DiscreteStateIndex sequence_index_; + drake::systems::DiscreteStateIndex within_target_index_; + drake::systems::DiscreteStateIndex time_entered_target_index_; double end_effector_thickness_; Eigen::Vector3d first_target_; Eigen::Vector3d second_target_; Eigen::Vector3d third_target_; + const double delay_at_top_ = 5.0; double target_threshold_; double x_scale_; double y_scale_; diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 5b6d6dfdc2..4a4d9c1963 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -10,7 +10,7 @@ - + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index b1e4be49f9..c39762f21c 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -13,7 +13,7 @@ - + diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index d7fd3c76f9..2172af8a6a 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -102,7 +102,7 @@ C3Controller::C3Controller( for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.35, 0.6, 1); + c3_->AddLinearConstraint(A, 0.35, 0.7, 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); @@ -112,7 +112,7 @@ C3Controller::C3Controller( for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0, 20, 2); + c3_->AddLinearConstraint(A, 0, 30, 2); } lcs_state_input_port_ = @@ -189,7 +189,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( DRAKE_DEMAND(lcs_x->get_data()[1] > -0.1); DRAKE_DEMAND(lcs_x->get_data()[1] < 0.1); DRAKE_DEMAND(lcs_x->get_data()[2] > 0.35); - DRAKE_DEMAND(lcs_x->get_data()[2] < 0.6); + DRAKE_DEMAND(lcs_x->get_data()[2] < 0.7); c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); From 98942dc2962d0ada057bfaa90abb3a13bbcf3794 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Fri, 12 Jan 2024 15:19:43 -0500 Subject: [PATCH 600/758] minor changes from hardware --- examples/franka/parameters/franka_c3_controller_params.yaml | 6 +++--- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/systems/plate_balancing_target.h | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index c5112bad2c..326d60edf7 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -19,8 +19,8 @@ scene_index: 1 left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf -left_support_position: [0.8, 0.15, 0.453] -right_support_position: [0.8, -0.15, 0.453] +left_support_position: [0.8, 0.15, 0.455] +right_support_position: [0.8, -0.15, 0.455] end_effector_thickness: 0.015 include_end_effector_orientation: false @@ -29,7 +29,7 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.45], - [0.45, 0, 0.486]] + [0.45, 0, 0.488]] second_target: [[0.45, 0.0, 0.45], [0.45, 0, 0.65]] third_target: [[0.45, 0.0, 0.45], diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2140bf9708..fcd7090eab 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 4a992c1593..6906c587bd 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -61,7 +61,7 @@ class PlateBalancingTargetGenerator Eigen::Vector3d first_target_; Eigen::Vector3d second_target_; Eigen::Vector3d third_target_; - const double delay_at_top_ = 5.0; + const double delay_at_top_ = 3.0; double target_threshold_; double x_scale_; double y_scale_; From 23a6e211d222ee5f8e35e29373e0f5447f4d0e13 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 12 Jan 2024 17:31:14 -0500 Subject: [PATCH 601/758] updating drake version --- .bazelrc | 1 + WORKSPACE | 4 - .../analysis/franka_plotting_utils.py | 4 +- .../plot_five_link_biped.py | 2 +- .../mujoco/drake_to_mujoco_converter.py | 6 +- .../test/multipose_visualizer_test.py | 2 +- director/BUILD.bazel | 38 +-- director/scripts/VisualizationGUI.py | 2 +- examples/Cassie/cassie_state_estimator.cc | 17 +- examples/Cassie/cassie_utils.cc | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 2 +- .../Cassie/networking/cassie_udp_publisher.cc | 13 +- .../osc_jump/convert_traj_for_controller.cc | 2 +- .../osc_run/convert_traj_for_controller.cc | 2 +- examples/Cassie/run_dircon_jumping.cc | 4 +- examples/Cassie/run_dircon_running.cc | 4 +- examples/Cassie/run_dircon_squatting.cc | 4 +- examples/Cassie/run_dircon_walking.cc | 4 +- examples/Cassie/test/benchmark_dynamics.cc | 2 +- examples/Cassie/test/min_deps_mbt_sim.cc | 2 +- examples/Cassie/visualize_trajectory.cc | 4 +- examples/PlanarWalker/run_gait_dircon.cc | 4 +- examples/acrobot/swingup.cc | 4 +- .../five_link_biped_sim.cc | 2 +- .../five_link_biped_visualizer.cc | 2 +- .../run_dircon_walking.cc | 2 +- .../run_joint_space_walking_controller.cc | 2 +- examples/kuka_iiwa_arm/BUILD.bazel | 75 ------ .../kuka_iiwa_arm/iiwa_controller_demo.cc | 208 ---------------- examples/kuka_iiwa_arm/iiwa_oscillate.cc | 134 ----------- examples/kuka_iiwa_arm/iiwa_visualizer.cc | 87 ------- examples/kuka_iiwa_arm/kuka_simulation.cc | 224 ------------------ examples/kuka_iiwa_arm/kuka_test.pmd | 44 ---- .../kuka_iiwa_arm/kuka_torque_controller.cc | 175 -------------- .../kuka_iiwa_arm/kuka_torque_controller.h | 68 ------ examples/kuka_iiwa_arm/signal_scope_panel.py | 8 - examples/trifinger/lcm_control_demo.py | 4 +- examples/trifinger/simulate_trifinger.py | 4 +- examples/trifinger/simulate_trifinger_lcm.py | 4 +- lcmtypes/BUILD.bazel | 1 - .../test/kinematic_evaluator_caching_test.cc | 2 +- .../test/kinematic_evaluator_test.cc | 2 +- multibody/test/geom_geom_collider_test.cc | 4 +- multibody/test/multibody_utils_test.cc | 2 +- multibody/visualization_utils.cc | 2 +- solvers/fast_osqp_solver_common.cc | 9 +- .../passive_constrained_pendulum_dircon.cc | 4 +- .../passive_constrained_pendulum_dircon.cc | 2 +- tools/workspace/pydrake/repository.bzl | 58 ++--- 49 files changed, 117 insertions(+), 1141 deletions(-) delete mode 100644 examples/kuka_iiwa_arm/BUILD.bazel delete mode 100644 examples/kuka_iiwa_arm/iiwa_controller_demo.cc delete mode 100644 examples/kuka_iiwa_arm/iiwa_oscillate.cc delete mode 100644 examples/kuka_iiwa_arm/iiwa_visualizer.cc delete mode 100644 examples/kuka_iiwa_arm/kuka_simulation.cc delete mode 100644 examples/kuka_iiwa_arm/kuka_test.pmd delete mode 100644 examples/kuka_iiwa_arm/kuka_torque_controller.cc delete mode 100644 examples/kuka_iiwa_arm/kuka_torque_controller.h delete mode 100644 examples/kuka_iiwa_arm/signal_scope_panel.py diff --git a/.bazelrc b/.bazelrc index 84cc5fb460..486f79fb7e 100644 --- a/.bazelrc +++ b/.bazelrc @@ -54,6 +54,7 @@ build --action_env=LD_LIBRARY_PATH= # build with snopt build --define=WITH_SNOPT=ON build --define=WITH_GUROBI=ON +build --define=NO_CLARABEL=ON build:omp --copt=-DEIGEN_DONT_PARALLELIZE build:omp --copt=-fopenmp diff --git a/WORKSPACE b/WORKSPACE index 0b48c9f153..fbb7b4aab0 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -71,10 +71,6 @@ load("@dairlib//tools/workspace/signal_scope:repository.bzl", "signal_scope_repo signal_scope_repository(name = "signal_scope") -load("@dairlib//tools/workspace/pydrake:repository.bzl", "pydrake_repository") - -pydrake_repository(name = "pydrake_pegged") - # Prebuilt ROS workspace new_local_repository( name = "ros", diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index 842e6984ee..bfc83ffee2 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -42,7 +42,7 @@ def make_plant_and_context(): franka_plant = MultibodyPlant(0.0) franka_parser = Parser(franka_plant) - franka_parser.AddModelFromFile(franka_urdf) + franka_parser.AddModels(franka_urdf) end_effector_index = \ franka_parser.AddModels(end_effector_model)[0] T_EE_W = RigidTransform(tool_attachment_frame) @@ -57,7 +57,7 @@ def make_plant_and_context(): tray_plant = MultibodyPlant(0.0) tray_parser = Parser(tray_plant) - tray_parser.AddModelFromFile(tray_model) + tray_parser.AddModels(tray_model) franka_plant.Finalize() tray_plant.Finalize() diff --git a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py index 807cd8bd64..93fad485c6 100644 --- a/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py +++ b/bindings/pydairlib/analysis/impact_invariant_control/plot_five_link_biped.py @@ -70,7 +70,7 @@ def load_logs(plant, t_impact, window): def main(): builder = DiagramBuilder() plant, _ = AddMultibodyPlantSceneGraph(builder, 0.0) - Parser(plant).AddModelFromFile( + Parser(plant).AddModels( "examples/impact_invariant_control/five_link_biped.urdf") plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base")) plant.Finalize() diff --git a/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py index 8b8c95df1e..1e16c58b61 100644 --- a/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py +++ b/bindings/pydairlib/cassie/mujoco/drake_to_mujoco_converter.py @@ -31,7 +31,7 @@ def __init__(self, drake_sim_dt=5e-5): self.foot_crank_plant, self.foot_crank_scene_graph = AddMultibodyPlantSceneGraph(self.foot_crank_builder, drake_sim_dt) - Parser(self.foot_crank_plant).AddModelFromFile( + Parser(self.foot_crank_plant).AddModels( self.foot_crank_urdf) self.foot_crank_plant.Finalize() @@ -39,7 +39,7 @@ def __init__(self, drake_sim_dt=5e-5): self.knee_linkage_plant, self.knee_linkage_scene_graph = AddMultibodyPlantSceneGraph(self.knee_linkage_builder, drake_sim_dt) - Parser(self.knee_linkage_plant).AddModelFromFile(self.knee_linkage_urdf) + Parser(self.knee_linkage_plant).AddModels(self.knee_linkage_urdf) self.knee_linkage_plant.Finalize() self.diagram = self.builder.Build() @@ -137,7 +137,7 @@ def visualize_entire_leg(self, x): plant = MultibodyPlant(self.drake_sim_dt) scene_graph = builder.AddSystem(SceneGraph()) - Parser(plant).AddModelFromFile(self.left_leg_urdf) + Parser(plant).AddModels(self.left_leg_urdf) plant.Finalize() self.print_pos_indices(plant) diff --git a/bindings/pydairlib/multibody/test/multipose_visualizer_test.py b/bindings/pydairlib/multibody/test/multipose_visualizer_test.py index 0be0f8b706..4330f9c3ee 100644 --- a/bindings/pydairlib/multibody/test/multipose_visualizer_test.py +++ b/bindings/pydairlib/multibody/test/multipose_visualizer_test.py @@ -15,7 +15,7 @@ def main(): builder = pydrake.systems.framework.DiagramBuilder() plant, scene_graph = pydrake.multibody.plant.AddMultibodyPlantSceneGraph( builder, 0) - pydrake.multibody.parsing.Parser(plant).AddModelFromFile( + pydrake.multibody.parsing.Parser(plant).AddModels( FindResourceOrThrow("examples/Cassie/urdf/cassie_v2.urdf")) plant.Finalize() visualizer.DrawPoses(np.random.rand(plant.num_positions(), diff --git a/director/BUILD.bazel b/director/BUILD.bazel index 1d76f15ba9..3c02eb9bbe 100644 --- a/director/BUILD.bazel +++ b/director/BUILD.bazel @@ -1,21 +1,21 @@ # -*- python -*- -py_binary( - name = "drake_director_py", - srcs = ["drake_director.py"], - main = "drake_director.py", - # Python libraries to import. - deps = [ - "//lcmtypes:lcmtypes_robot_py", - "@drake//tools:drake_visualizer_py", - # "//bindings/pydairlib/multibody:multibody_py", - "@pydrake_pegged", - ], -) - -load("@drake//tools/skylark:drake_runfiles_binary.bzl", "drake_runfiles_binary") - -drake_runfiles_binary( - name = "drake-director", - target = ":drake_director_py", -) +#py_binary( +# name = "drake_director_py", +# srcs = ["drake_director.py"], +# main = "drake_director.py", +# # Python libraries to import. +# deps = [ +# "//lcmtypes:lcmtypes_robot_py", +# "@drake//tools:drake_visualizer_py", +# # "//bindings/pydairlib/multibody:multibody_py", +# "@pydrake_pegged", +# ], +#) +# +#load("@drake//tools/skylark:drake_runfiles_binary.bzl", "drake_runfiles_binary") +# +#drake_runfiles_binary( +# name = "drake-director", +# target = ":drake_director_py", +#) diff --git a/director/scripts/VisualizationGUI.py b/director/scripts/VisualizationGUI.py index 8024642947..cbc85cbf9d 100644 --- a/director/scripts/VisualizationGUI.py +++ b/director/scripts/VisualizationGUI.py @@ -147,7 +147,7 @@ def readJSONFile(self): pydrake.multibody.plant.AddMultibodyPlantSceneGraph(builder, 0) file = os.getcwd() + '/' + self.modelFile - pydrake.multibody.parsing.Parser(self.plant).AddModelFromFile(file) + pydrake.multibody.parsing.Parser(self.plant).AddModels(file) # determine if there is a need to use the weld a body part if (self.weldBody != None): diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 6fe105077c..50b0ee3ebf 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -1087,14 +1087,15 @@ void CassieStateEstimator::DoCalcNextUpdateTime( *time = next_message_time_ - eps_; if (is_floating_base_) { - UnrestrictedUpdateEvent::UnrestrictedUpdateCallback callback = - [this](const Context& c, - const UnrestrictedUpdateEvent&, - drake::systems::State* s) { this->Update(c, s); }; - - auto& uu_events = events->get_mutable_unrestricted_update_events(); - uu_events.AddEvent(UnrestrictedUpdateEvent( - drake::systems::TriggerType::kTimed, callback)); + //TODO(yangwill) fix this using new Drake +// UnrestrictedUpdateEvent::UnrestrictedUpdateCallback callback = +// [this](const Context& c, +// const UnrestrictedUpdateEvent&, +// drake::systems::State* s) { this->Update(c, s); }; +// +// auto& uu_events = events->get_mutable_unrestricted_update_events(); +// uu_events.AddEvent(UnrestrictedUpdateEvent( +// drake::systems::TriggerType::kTimed, callback)); } else { *time = INFINITY; } diff --git a/examples/Cassie/cassie_utils.cc b/examples/Cassie/cassie_utils.cc index 662c5df09f..3e1127f0ac 100644 --- a/examples/Cassie/cassie_utils.cc +++ b/examples/Cassie/cassie_utils.cc @@ -110,7 +110,7 @@ void AddCassieMultibody(MultibodyPlant* plant, bool add_loop_closure, bool add_reflected_inertia) { std::string full_name = FindResourceOrThrow(filename); Parser parser(plant, scene_graph); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); if (!floating_base) { plant->WeldFrames(plant->world_frame(), plant->GetFrameByName("pelvis"), diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index fb102758c8..33d3dbfbcb 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -110,7 +110,7 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); std::string terrain_name = FindResourceOrThrow("examples/impact_invariant_control/platform.urdf"); - parser.AddModelFromFile(terrain_name); + parser.AddModels(terrain_name); Eigen::Vector3d offset; offset << FLAGS_platform_x, 0, 0.25 + FLAGS_platform_height; plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), diff --git a/examples/Cassie/networking/cassie_udp_publisher.cc b/examples/Cassie/networking/cassie_udp_publisher.cc index 1b787250ef..02c6d18245 100644 --- a/examples/Cassie/networking/cassie_udp_publisher.cc +++ b/examples/Cassie/networking/cassie_udp_publisher.cc @@ -64,12 +64,13 @@ CassieUDPPublisher::CassieUDPPublisher(const std::string& address, DRAKE_DEMAND(publish_period == 0); } if (publish_triggers.find(TriggerType::kPerStep) != publish_triggers.end()) { - this->DeclarePerStepEvent( - drake::systems::PublishEvent([this]( - const drake::systems::Context& context, - const drake::systems::PublishEvent&) { - this->PublishInputAsUDPMessage(context); - })); + //TODO(yangwill): fix this later for new drake +// this->DeclarePerStepEvent( +// drake::systems::PublishEvent([this]( +// const drake::systems::Context& context, +// const drake::systems::PublishEvent&) { +// this->PublishInputAsUDPMessage(context); +// })); } } diff --git a/examples/Cassie/osc_jump/convert_traj_for_controller.cc b/examples/Cassie/osc_jump/convert_traj_for_controller.cc index 45d7851fd0..30b9f5829f 100644 --- a/examples/Cassie/osc_jump/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_jump/convert_traj_for_controller.cc @@ -47,7 +47,7 @@ int DoMain() { MultibodyPlant plant(1e-5); // non-zero timestep to avoid continuous // model warnings Parser parser(&plant, &scene_graph); - parser.AddModelFromFile( + parser.AddModels( FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); plant.mutable_gravity_field().set_gravity_vector(-9.81 * Eigen::Vector3d::UnitZ()); diff --git a/examples/Cassie/osc_run/convert_traj_for_controller.cc b/examples/Cassie/osc_run/convert_traj_for_controller.cc index c501eee35b..0e65ff54e9 100644 --- a/examples/Cassie/osc_run/convert_traj_for_controller.cc +++ b/examples/Cassie/osc_run/convert_traj_for_controller.cc @@ -40,7 +40,7 @@ int DoMain() { MultibodyPlant plant(1e-5); // non-zero timestep to avoid continuous // model warnings Parser parser(&plant, &scene_graph); - parser.AddModelFromFile( + parser.AddModels( FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf")); plant.mutable_gravity_field().set_gravity_vector(-9.81 * Eigen::Vector3d::UnitZ()); diff --git a/examples/Cassie/run_dircon_jumping.cc b/examples/Cassie/run_dircon_jumping.cc index 8521caf236..30af30f689 100644 --- a/examples/Cassie/run_dircon_jumping.cc +++ b/examples/Cassie/run_dircon_jumping.cc @@ -176,7 +176,7 @@ void DoMain() { false); Parser parser_vis(&plant_vis, &scene_graph); - parser_vis.AddModelFromFile(file_name); + parser_vis.AddModels(file_name); plant.Finalize(); plant_vis.Finalize(); @@ -189,7 +189,7 @@ void DoMain() { if (FLAGS_use_springs && FLAGS_convert_to_springs) { MultibodyPlant plant_wo_spr(0.0); Parser parser(&plant_wo_spr); - parser.AddModelFromFile( + parser.AddModels( "examples/Cassie/urdf/cassie_fixed_springs_conservative.urdf"); plant_wo_spr.Finalize(); spr_map = CreateWithSpringsToWithoutSpringsMapPos(plant, plant_wo_spr); diff --git a/examples/Cassie/run_dircon_running.cc b/examples/Cassie/run_dircon_running.cc index 1a67cc9888..044accf0e8 100644 --- a/examples/Cassie/run_dircon_running.cc +++ b/examples/Cassie/run_dircon_running.cc @@ -101,8 +101,8 @@ void DoMain() { Parser parser(&plant); Parser parser_vis(&plant_vis, &scene_graph); - parser.AddModelFromFile(file_name); - parser_vis.AddModelFromFile(file_name); + parser.AddModels(file_name); + parser_vis.AddModels(file_name); plant.Finalize(); plant_vis.Finalize(); diff --git a/examples/Cassie/run_dircon_squatting.cc b/examples/Cassie/run_dircon_squatting.cc index 8385e7e385..d3b88bd889 100644 --- a/examples/Cassie/run_dircon_squatting.cc +++ b/examples/Cassie/run_dircon_squatting.cc @@ -104,8 +104,8 @@ void DoMain(double duration, int max_iter, const string& data_directory, string full_name = FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); - parser_vis.AddModelFromFile(full_name); + parser.AddModels(full_name); + parser_vis.AddModels(full_name); plant.Finalize(); plant_vis.Finalize(); diff --git a/examples/Cassie/run_dircon_walking.cc b/examples/Cassie/run_dircon_walking.cc index 357f1c0165..2c0c6ee77b 100644 --- a/examples/Cassie/run_dircon_walking.cc +++ b/examples/Cassie/run_dircon_walking.cc @@ -206,7 +206,7 @@ vector GetInitGuessForQ(int N, double stride_length, Parser parser(&plant_ik, &scene_graph_ik); string full_name = FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant_ik.Finalize(); // Visualize @@ -298,7 +298,7 @@ void DoMain(double duration, double stride_length, double ground_incline, string full_name = FindResourceOrThrow("examples/Cassie/urdf/cassie_fixed_springs.urdf"); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.Finalize(); // Create maps for joints diff --git a/examples/Cassie/test/benchmark_dynamics.cc b/examples/Cassie/test/benchmark_dynamics.cc index b8f8a31c8b..380812205f 100644 --- a/examples/Cassie/test/benchmark_dynamics.cc +++ b/examples/Cassie/test/benchmark_dynamics.cc @@ -80,7 +80,7 @@ int do_main() { scene_graph.set_name("scene_graph"); multibody::Parser parser(&multibody_plant, &scene_graph); - parser.AddModelFromFile(dairlib::FindResourceOrThrow( + parser.AddModels(dairlib::FindResourceOrThrow( "examples/Cassie/urdf/cassie_v2.urdf")); multibody_plant.WeldFrames( diff --git a/examples/Cassie/test/min_deps_mbt_sim.cc b/examples/Cassie/test/min_deps_mbt_sim.cc index 9c24a6cceb..5ae25c3f2b 100644 --- a/examples/Cassie/test/min_deps_mbt_sim.cc +++ b/examples/Cassie/test/min_deps_mbt_sim.cc @@ -49,7 +49,7 @@ int do_main(int argc, char* argv[]) { // NOTE: will need to change path as appropriate std::string full_name = "/home/posa/workspace/dairlib/examples/Cassie/urdf/cassie_v2.urdf"; Parser parser(&plant, &scene_graph); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.WeldFrames( plant.world_frame(), plant.GetFrameByName("pelvis"), diff --git a/examples/Cassie/visualize_trajectory.cc b/examples/Cassie/visualize_trajectory.cc index d06d01d12b..9efcbf549b 100644 --- a/examples/Cassie/visualize_trajectory.cc +++ b/examples/Cassie/visualize_trajectory.cc @@ -51,14 +51,14 @@ int DoMain() { Parser parser(&plant, &scene_graph); const std::string& fixed_spring_urdf = "examples/Cassie/urdf/cassie_fixed_springs.urdf"; - parser.AddModelFromFile(fixed_spring_urdf); + parser.AddModels(fixed_spring_urdf); plant.Finalize(); MultibodyPlant plant_w_spr(1e-3); const std::string& spring_urdf = "examples/Cassie/urdf/cassie_v2_shells.urdf"; Parser parser_w_spr(&plant_w_spr, &scene_graph_w_spr); - parser_w_spr.AddModelFromFile(spring_urdf); + parser_w_spr.AddModels(spring_urdf); plant_w_spr.Finalize(); auto pos_spr_map = multibody::CreateWithSpringsToWithoutSpringsMapPos(plant_w_spr, plant); diff --git a/examples/PlanarWalker/run_gait_dircon.cc b/examples/PlanarWalker/run_gait_dircon.cc index 6c7213d78b..2655915fb3 100644 --- a/examples/PlanarWalker/run_gait_dircon.cc +++ b/examples/PlanarWalker/run_gait_dircon.cc @@ -230,8 +230,8 @@ int main(int argc, char* argv[]) { std::string full_name = dairlib::FindResourceOrThrow("examples/PlanarWalker/PlanarWalker.urdf"); - parser.AddModelFromFile(full_name); - parser_vis.AddModelFromFile(full_name); + parser.AddModels(full_name); + parser_vis.AddModels(full_name); plant->WeldFrames( plant->world_frame(), plant->GetFrameByName("base"), diff --git a/examples/acrobot/swingup.cc b/examples/acrobot/swingup.cc index d8c9bd34dc..055c062cd8 100644 --- a/examples/acrobot/swingup.cc +++ b/examples/acrobot/swingup.cc @@ -150,8 +150,8 @@ int main(int argc, char* argv[]) { std::string full_name = dairlib::FindResourceOrThrow("examples/acrobot/Acrobot.urdf"); - parser.AddModelFromFile(full_name); - parser_vis.AddModelFromFile(full_name); + parser.AddModels(full_name); + parser_vis.AddModels(full_name); plant->Finalize(); plant_vis->Finalize(); diff --git a/examples/impact_invariant_control/five_link_biped_sim.cc b/examples/impact_invariant_control/five_link_biped_sim.cc index c9525e709e..e91ddb5c49 100644 --- a/examples/impact_invariant_control/five_link_biped_sim.cc +++ b/examples/impact_invariant_control/five_link_biped_sim.cc @@ -80,7 +80,7 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); std::string full_name = FindResourceOrThrow( "examples/impact_invariant_control/five_link_biped.urdf"); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform()); multibody::AddFlatTerrain(&plant, &scene_graph, .8, .8); // Add ground diff --git a/examples/impact_invariant_control/five_link_biped_visualizer.cc b/examples/impact_invariant_control/five_link_biped_visualizer.cc index 9e9914005f..29f425fe27 100644 --- a/examples/impact_invariant_control/five_link_biped_visualizer.cc +++ b/examples/impact_invariant_control/five_link_biped_visualizer.cc @@ -55,7 +55,7 @@ int do_main(int argc, char* argv[]) { SceneGraph* scene_graph = builder.AddSystem(); scene_graph->set_name("scene_graph"); Parser parser(&plant, scene_graph); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform()); plant.mutable_gravity_field().set_gravity_vector(-9.81 * diff --git a/examples/impact_invariant_control/run_dircon_walking.cc b/examples/impact_invariant_control/run_dircon_walking.cc index 22c434cfb5..63f5016183 100644 --- a/examples/impact_invariant_control/run_dircon_walking.cc +++ b/examples/impact_invariant_control/run_dircon_walking.cc @@ -278,7 +278,7 @@ int doMain(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); std::string full_name = FindResourceOrThrow( "examples/impact_invariant_control/five_link_biped.urdf"); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.mutable_gravity_field().set_gravity_vector(-FLAGS_gravity * Eigen::Vector3d::UnitZ()); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 9832f2e2f5..5953d4bb38 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -75,7 +75,7 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); std::string full_name = FindResourceOrThrow( "examples/impact_invariant_control/five_link_biped.urdf"); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), drake::math::RigidTransform()); plant.Finalize(); diff --git a/examples/kuka_iiwa_arm/BUILD.bazel b/examples/kuka_iiwa_arm/BUILD.bazel deleted file mode 100644 index ace8be3a78..0000000000 --- a/examples/kuka_iiwa_arm/BUILD.bazel +++ /dev/null @@ -1,75 +0,0 @@ -load("@drake//tools/lint:lint.bzl", "add_lint_tests") - -package(default_visibility = ["//visibility:public"]) - -load( - "@drake//tools/skylark:drake_lcm.bzl", - "drake_lcm_cc_library", - "drake_lcm_java_library", - "drake_lcm_py_library", -) -load( - "@drake//tools/skylark:drake_py.bzl", - "drake_py_binary", - "drake_py_library", - "drake_py_unittest", -) - -cc_binary( - name = "kuka_simulation", - srcs = ["kuka_simulation.cc"], - data = [ - "@drake//manipulation/models/iiwa_description:models", - ], - deps = [ - ":kuka_torque_controller", - "//common", - "@drake//:drake_shared_library", - ], -) - -cc_binary( - name = "iiwa_oscillate", - srcs = ["iiwa_oscillate.cc"], - deps = [ - "//systems/controllers:endeffector_position_controller", - "//systems/controllers:endeffector_velocity_controller", - "//systems/controllers:safe_velocity_controller", - "@drake//:drake_shared_library", - ], -) - -cc_binary( - name = "iiwa_visualizer", - srcs = ["iiwa_visualizer.cc"], - data = [ - "@drake//examples/kuka_iiwa_arm:models", - "@drake//manipulation/models/iiwa_description:models", - ], - deprecation = "Attic/RigidBodyTree is deprecated.", - tags = ["manual"], - deps = [ - "//common", - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "kuka_torque_controller", - srcs = ["kuka_torque_controller.cc"], - hdrs = ["kuka_torque_controller.h"], - visibility = ["//visibility:public"], - deps = [ - "@drake//:drake_shared_library", - ], -) - -cc_binary( - name = "iiwa_controller_demo", - srcs = ["iiwa_controller_demo.cc"], - deps = [ - "//systems/controllers:endeffector_position_controller", - "//systems/controllers:endeffector_velocity_controller", - "@drake//:drake_shared_library", - ], -) diff --git a/examples/kuka_iiwa_arm/iiwa_controller_demo.cc b/examples/kuka_iiwa_arm/iiwa_controller_demo.cc deleted file mode 100644 index ebf8717b0e..0000000000 --- a/examples/kuka_iiwa_arm/iiwa_controller_demo.cc +++ /dev/null @@ -1,208 +0,0 @@ -// Kp and 'Rotational' Kp -#define K_P 1 -#define K_OMEGA 0.7 - -// Kd and 'Rotational' Kd -#define K_D 1 -#define K_R 0.3 - -#include "drake/common/trajectories/piecewise_polynomial.h" -#include "drake/manipulation/kuka_iiwa/iiwa_status_receiver.h" -#include "drake/manipulation/kuka_iiwa/iiwa_command_sender.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/primitives/trajectory_source.h" -#include "drake/systems/primitives/constant_vector_source.h" -#include "drake/lcm/drake_lcm.h" -#include "drake/lcmt_iiwa_command.hpp" -#include "drake/lcmt_iiwa_status.hpp" -#include "drake/multibody/plant/multibody_plant.h" -#include "drake/multibody/parsing/parser.h" - -#include "systems/controllers/endeffector_velocity_controller.h" -#include "systems/controllers/endeffector_position_controller.h" - -using Eigen::VectorXd; -using drake::multibody::MultibodyPlant; - -namespace dairlib { - -// This function creates a controller for a Kuka LBR Iiwa arm by connecting an -// EndEffectorPositionController to an EndEffectorVelocityController to control -// the individual joint torques as to move the endeffector -// to a desired position. -int do_main(int argc, char* argv[]) { - // Creating end effector trajectory - // TODO make this modular - const std::vector times {0.0, 25.0, 35.0, 45.0, 55.0, 65.0, - 75.0, 85.0, 95.0, 105.0, 115}; - - std::vector points(times.size()); - - Eigen::Vector3d AS, A0, A1, A2, A3, A4, A5, A6, A7, A8, A9; - - AS << -0.23, -0.2, 0.25; - A0 << -0.23, -0.2, 0.25; - - A1 << -0.23, -0.6, 0.25; - A2 << 0.23, -0.6, 0.25; - - A3 << 0.23, -0.2, 0.25; - - A4 << 0.23, -0.2, 0.25; - - A5 << 0.23, -0.6, 0.25; - - A6 << -0.23, -0.6, 0.25; - - A7 << -0.23, -0.2, 0.25; - - A8 << -0.23, -0.2, 0.25; - A9 << -0.23, -0.2, 0.25; - - points[0] = AS; - points[1] = A0; - points[2] = A1; - points[3] = A2; - points[4] = A3; - points[5] = A4; - points[6] = A5; - points[7] = A6; - points[8] = A7; - points[9] = A8; - points[10] = A9; - - auto ee_trajectory = drake::trajectories::PiecewisePolynomial< - double>::FirstOrderHold(times, points); - - // Creating end effector orientation trajectory - const std::vector orient_times {0, 115}; - std::vector orient_points(orient_times.size()); - Eigen::Vector4d start_o, end_o; - start_o << 0, 0, 1, 0; - end_o << 0, 0, 1, 0; - - orient_points[0] = start_o; - orient_points[1] = end_o; - - auto orientation_trajectory = drake::trajectories::PiecewisePolynomial< - double>::FirstOrderHold(orient_times, orient_points); - - // Initialize Kuka model URDF-- from Drake kuka simulation files - std::string kModelPath = "../drake/manipulation/models/iiwa_description" - "/iiwa7/iiwa7_no_collision.sdf"; - const std::string urdf_string = FindResourceOrThrow(kModelPath); - - // MultibodyPlants are created here, then passed by reference - // to the controller blocks for internal modelling. - const auto X_WI = drake::math::RigidTransform::Identity(); - std::unique_ptr> owned_plant = - std::make_unique>(0.0); - - drake::multibody::Parser plant_parser(owned_plant.get()); - plant_parser.AddModelFromFile(urdf_string, "iiwa"); - owned_plant->WeldFrames(owned_plant->world_frame(), - owned_plant->GetFrameByName("iiwa_link_0"), X_WI); - owned_plant->Finalize(); - - drake::systems::DiagramBuilder builder; - - auto lcm = builder.AddSystem(); - - // Adding status subscriber and receiver blocks - auto status_subscriber = builder.AddSystem( - drake::systems::lcm::LcmSubscriberSystem::Make( - "IIWA_STATUS", lcm)); - auto status_receiver = builder.AddSystem< - drake::manipulation::kuka_iiwa::IiwaStatusReceiver>(); - - // The coordinates for the end effector with respect to the last joint, - // used to determine location of end effector - Eigen::Vector3d eeContactFrame; - eeContactFrame << 0.0, 0, 0.09; - - const std::string link_7 = "iiwa_link_7"; - - // Adding position controller block - auto position_controller = builder.AddSystem< - systems::EndEffectorPositionController>( - *owned_plant, link_7, eeContactFrame, K_P, K_OMEGA); - - // Adding Velocity Controller block - auto velocity_controller = builder.AddSystem< - systems::EndEffectorVelocityController>( - *owned_plant, link_7, eeContactFrame, K_D, K_R); - - - // Adding linear position Trajectory Source - auto input_trajectory = builder.AddSystem( - ee_trajectory); - // Adding orientation Trajectory Source - auto input_orientation = builder.AddSystem( - orientation_trajectory); - - - // Adding command publisher and broadcaster blocks - auto command_sender = builder.AddSystem< - drake::manipulation::kuka_iiwa::IiwaCommandSender>(); - auto command_publisher = builder.AddSystem( - drake::systems::lcm::LcmPublisherSystem::Make( - "IIWA_COMMAND", lcm, 1.0/200.0)); - - // Torque Controller-- includes virtual springs and damping. - VectorXd ConstPositionCommand; - - // The virtual spring stiffness in Nm/rad. - ConstPositionCommand.resize(7); - ConstPositionCommand << 0, 0, 0, 0, 0, 0, 0; - - auto positionCommand = builder.AddSystem< - drake::systems::ConstantVectorSource>(ConstPositionCommand); - - builder.Connect(status_subscriber->get_output_port(), - status_receiver->get_input_port()); - builder.Connect(status_receiver->get_position_measured_output_port(), - velocity_controller->get_joint_pos_input_port()); - builder.Connect(status_receiver->get_velocity_estimated_output_port(), - velocity_controller->get_joint_vel_input_port()); - //Connecting q input from status receiver to position controller - builder.Connect(status_receiver->get_position_measured_output_port(), - position_controller->get_joint_pos_input_port()); - //Connecting x_desired input from trajectory to position controller - builder.Connect(input_trajectory->get_output_port(), - position_controller->get_endpoint_pos_input_port()); - //Connecting desired orientation to position controller - builder.Connect(input_orientation->get_output_port(), - position_controller->get_endpoint_orient_input_port()); - //Connecting position (twist) controller to trajectory/velocity controller; - builder.Connect(position_controller->get_endpoint_cmd_output_port(), - velocity_controller->get_endpoint_twist_input_port()); - - builder.Connect(velocity_controller->get_endpoint_torque_output_port(), - command_sender->get_torque_input_port()); - - builder.Connect(positionCommand->get_output_port(), - command_sender->get_position_input_port()); - builder.Connect(command_sender->get_output_port(), - command_publisher->get_input_port()); - - auto diagram = builder.Build(); - - drake::systems::Simulator simulator(*diagram); - - simulator.set_publish_every_time_step(false); - simulator.set_target_realtime_rate(1.0); - simulator.Initialize(); - simulator.AdvanceTo(ee_trajectory.end_time()); - return 0; -} - -} // Namespace dairlib - -int main(int argc, char* argv[]) { - return dairlib::do_main(argc, argv); -} diff --git a/examples/kuka_iiwa_arm/iiwa_oscillate.cc b/examples/kuka_iiwa_arm/iiwa_oscillate.cc deleted file mode 100644 index 9827cb2b64..0000000000 --- a/examples/kuka_iiwa_arm/iiwa_oscillate.cc +++ /dev/null @@ -1,134 +0,0 @@ -#define AMPLITUDE 1 -#define FREQUENCY 3 -#define MAX_VELOCITY 5 - -#include -#include -#include -#include - -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" -#include "drake/systems/primitives/multiplexer.h" -#include "drake/systems/primitives/constant_vector_source.h" -#include "drake/systems/primitives/sine.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/lcmt_iiwa_command.hpp" -#include "drake/lcmt_iiwa_status.hpp" -#include "drake/manipulation/kuka_iiwa/iiwa_status_receiver.h" -#include "drake/manipulation/kuka_iiwa/iiwa_command_sender.h" -#include "drake/common/find_resource.h" -#include "drake/common/text_logging.h" - -#include "spdlog/spdlog.h" -#include "spdlog/sinks/stdout_color_sinks.h" -#include "spdlog/sinks/basic_file_sink.h" - -#include "systems/controllers/safe_velocity_controller.h" - -namespace dairlib { - -void setup_log(); - -int do_main(int argc, char* argv[]) { - drake::systems::DiagramBuilder builder; - auto lcm = builder.AddSystem(); - - // Adding status subscriber and receiver blocks - auto status_subscriber = builder.AddSystem( - drake::systems::lcm::LcmSubscriberSystem::Make( - "IIWA_STATUS", lcm)); - auto status_receiver = builder.AddSystem(); - - // Adding command publisher and broadcaster blocks - auto command_sender = builder.AddSystem(); - auto command_publisher = builder.AddSystem( - drake::systems::lcm::LcmPublisherSystem::Make( - "IIWA_COMMAND", lcm, 1.0/200.0)); - - Eigen::VectorXd zeros_low = Eigen::VectorXd::Zero(4); - auto zeros_low_source = builder.AddSystem(zeros_low); - - Eigen::VectorXd zeros_high = Eigen::VectorXd::Zero(2); - auto zeros_high_source = builder.AddSystem(zeros_high); - - auto sine_source = builder.AddSystem(AMPLITUDE, FREQUENCY, 0, 1, true); - //setup_log(); - - std::vector input_sizes = {4, 1, 2}; - auto mux = builder.AddSystem(input_sizes); - - const int num_iiwa_joints = 7; - auto velocity_controller = builder.AddSystem( - MAX_VELOCITY, num_iiwa_joints); - - Eigen::VectorXd zeros_seven = Eigen::VectorXd::Zero(7); - auto constant_position_src = builder.AddSystem(zeros_seven); - - builder.Connect(zeros_low_source->get_output_port(), - mux->get_input_port(0)); - builder.Connect(sine_source->get_output_port(0), - mux->get_input_port(1)); - builder.Connect(zeros_high_source->get_output_port(), - mux->get_input_port(2)); - - builder.Connect(status_subscriber->get_output_port(), - status_receiver->get_input_port()); - - builder.Connect(mux->get_output_port(0), - velocity_controller->get_joint_torques_input_port()); - - builder.Connect(status_receiver->get_velocity_estimated_output_port(), - velocity_controller->get_joint_velocities_input_port()); - - builder.Connect(velocity_controller->get_joint_torques_output_port(), - command_sender->get_torque_input_port()); - - // builder.Connect(status_receiver->get_position_measured_output_port(), - // command_sender->get_position_input_port()); - - builder.Connect(constant_position_src->get_output_port(), - command_sender->get_position_input_port()); - - builder.Connect(command_sender->get_output_port(), - command_publisher->get_input_port()); - - auto diagram = builder.Build(); - drake::systems::Simulator simulator(*diagram); - - simulator.set_publish_every_time_step(false); - simulator.set_publish_at_initialization(false); - simulator.set_target_realtime_rate(1.0); - simulator.Initialize(); - - simulator.AdvanceTo(20); - return 0; -} - -void setup_log() { - auto t = std::time(nullptr); - auto tm = *std::localtime(&t); - - std::ostringstream oss; - oss << std::put_time(&tm, "%d_%m_%Y-%H_%M_%S"); - auto time_str = oss.str(); - - auto file_str = "logs/test_config_" + time_str + ".txt"; - - auto file_sink = std::make_shared(file_str, true); - drake::log()->sinks().push_back(file_sink); - - drake::log()->info("Testing with amplitude {} and frequency {}", AMPLITUDE, FREQUENCY); - drake::log()->info("Max velocity {}", MAX_VELOCITY); - drake::log()->info("Has spdlog: {}", drake::logging::kHaveSpdlog); - -} - -} // Namespace dairlib - -int main(int argc, char* argv[]) { - return dairlib::do_main(argc, argv); -} diff --git a/examples/kuka_iiwa_arm/iiwa_visualizer.cc b/examples/kuka_iiwa_arm/iiwa_visualizer.cc deleted file mode 100644 index 083de5f4f4..0000000000 --- a/examples/kuka_iiwa_arm/iiwa_visualizer.cc +++ /dev/null @@ -1,87 +0,0 @@ -#include "drake/common/find_resource.h" -#include "drake/manipulation/kuka_iiwa/iiwa_status_receiver.h" -#include "drake/lcmt_iiwa_status.hpp" -#include "drake/multibody/rigid_body_plant/rigid_body_plant.h" -#include "drake/multibody/rigid_body_tree_construction.h" -#include "drake/multibody/parsers/urdf_parser.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" -#include "drake/systems/primitives/discrete_derivative.h" -#include "drake/multibody/rigid_body_plant/drake_visualizer.h" - -namespace dairlib { -using drake::systems::RigidBodyPlant; -using drake::systems::Simulator; -using drake::manipulation::kuka_iiwa::IiwaStatusReceiver; - -int doMain(int argc, char* argv[]) { - - drake::systems::DiagramBuilder builder; - // Adds a plant. - const char* kModelPath = - "drake/manipulation/models/iiwa_description/" - "urdf/iiwa14_polytope_collision.urdf"; - const std::string urdf = drake::FindResourceOrThrow(kModelPath); - int num_joints; - - - RigidBodyTree tree; - { - drake::parsers::urdf::AddModelInstanceFromUrdfFileToWorld( - urdf, drake::multibody::joints::kFixed, &tree); - drake::multibody::AddFlatTerrainToWorld(&tree, 100., 10.); - //plant = builder.AddPlant(std::move(tree)); - num_joints = tree.get_num_positions(); - } - - auto lcm = builder.AddSystem(); - const std::string channel_x = "IIWA_STATUS"; - - // Create state subscriber and state receiver. - auto state_sub = builder.AddSystem( - drake::systems::lcm::LcmSubscriberSystem::Make < - drake::lcmt_iiwa_status > (channel_x, lcm)); - auto state_receiver = builder.AddSystem(num_joints); - - // Create visualizer - auto visualizer = builder.AddSystem(tree, lcm); - visualizer->set_publish_period(1.0/30.0); - - // Get the state from the LCM message and add it to the Visualizer - auto desired_state_from_position = builder.AddSystem< - drake::systems::StateInterpolatorWithDiscreteDerivative>( - num_joints, 0.005); - desired_state_from_position->set_name("desired_state_from_position"); - - builder.Connect(state_sub->get_output_port(), - state_receiver->get_input_port()); - builder.Connect(state_receiver->get_position_measured_output_port(), - desired_state_from_position->get_input_port()); - builder.Connect(desired_state_from_position->get_output_port(), - visualizer->get_input_port(0)); - - auto diagram = builder.Build(); - auto context = diagram->CreateDefaultContext(); - - auto stepper = std::make_unique>(*diagram, - std::move(context)); - - stepper->set_publish_every_time_step(false); - stepper->set_publish_at_initialization(false); - stepper->set_target_realtime_rate(1.0); - stepper->Initialize(); - - drake::log()->info("visualizer started"); - - stepper->AdvanceTo(std::numeric_limits::infinity()); - - return 0; -} - -} // namespace dairlib - -int main(int argc, char* argv[]) { - return dairlib::doMain(argc, argv); -} diff --git a/examples/kuka_iiwa_arm/kuka_simulation.cc b/examples/kuka_iiwa_arm/kuka_simulation.cc deleted file mode 100644 index 39c31a5323..0000000000 --- a/examples/kuka_iiwa_arm/kuka_simulation.cc +++ /dev/null @@ -1,224 +0,0 @@ -/// @file -/// -/// Implements a simulation of the KUKA iiwa arm. Like the driver for the -/// physical arm, this simulation communicates over LCM using lcmt_iiwa_status -/// and lcmt_iiwa_command messages. It is intended to be a be a direct -/// replacement for the KUKA iiwa driver and the actual robot hardware. - -#include -#include -#include -#include - -#include "drake/common/find_resource.h" -#include "drake/geometry/drake_visualizer.h" -#include "drake/geometry/scene_graph.h" -#include "drake/manipulation/kuka_iiwa/iiwa_command_receiver.h" -#include "drake/manipulation/kuka_iiwa/iiwa_status_sender.h" -#include "drake/math/rigid_transform.h" -#include "drake/multibody/parsing/parser.h" -#include "drake/multibody/tree/revolute_joint.h" -#include "drake/multibody/tree/multibody_tree.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/primitives/demultiplexer.h" -#include "drake/systems/primitives/discrete_derivative.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_publisher_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" -#include "drake/multibody/plant/multibody_plant.h" -#include "drake/lcmt_iiwa_command.hpp" -#include "drake/lcmt_iiwa_status.hpp" -#include "examples/kuka_iiwa_arm/kuka_torque_controller.h" - -namespace dairlib { -namespace examples { -namespace kuka_iiwa_arm { - - using Eigen::Vector3d; - using Eigen::VectorXd; - - using drake::geometry::DrakeVisualizer; - using drake::geometry::SceneGraph; - using drake::manipulation::kuka_iiwa::IiwaCommandReceiver; - using drake::manipulation::kuka_iiwa::IiwaStatusSender; - using drake::math::RigidTransform; - using drake::math::RollPitchYaw; - using drake::multibody::Joint; - using drake::multibody::ModelInstanceIndex; - using drake::multibody::MultibodyPlant; - using drake::multibody::RevoluteJoint; - using drake::multibody::SpatialInertia; - using drake::systems::StateInterpolatorWithDiscreteDerivative; - -int DoMain() { - - std::unique_ptr> owned_world_plant = - std::make_unique>(0.0001); - std::unique_ptr> owned_controller_plant = - std::make_unique>(0.0); - std::unique_ptr> owned_scene_graph = - std::make_unique>(); - - MultibodyPlant* world_plant = - owned_world_plant.get(); - MultibodyPlant* controller_plant = - owned_controller_plant.get(); - drake::geometry::SceneGraph* scene_graph = - owned_scene_graph.get(); - world_plant->RegisterAsSourceForSceneGraph(scene_graph); - - // Get the Iiwa model. TODO: grab this from pegged drake libraries - const char* kModelPath = - "drake/manipulation/models/iiwa_description/iiwa7/iiwa7_no_collision.sdf"; - const std::string kuka_urdf = drake::FindResourceOrThrow(kModelPath); - const auto X_WI = RigidTransform::Identity(); - - // Add the Iiwa model to the world model - drake::multibody::Parser world_plant_parser(world_plant); - const drake::multibody::ModelInstanceIndex iiwa_model = - world_plant_parser.AddModelFromFile(kuka_urdf, "iiwa"); - world_plant->WeldFrames( - owned_world_plant->world_frame(), - owned_world_plant->GetFrameByName("iiwa_link_0", iiwa_model), X_WI); - - // Create and add a plant to the controller-specific model - drake::multibody::Parser controller_plant_parser(controller_plant); - const auto controller_iiwa_model = controller_plant_parser.AddModelFromFile( - kuka_urdf, "iiwa"); - owned_controller_plant->WeldFrames(owned_controller_plant->world_frame(), - owned_controller_plant->GetFrameByName("iiwa_link_0", controller_iiwa_model), - X_WI); - - // Finalize the plants to begin adding them to a system - owned_controller_plant->Finalize(); - world_plant->Finalize(); - - const int num_iiwa_positions = world_plant->num_positions(); - const int num_iiwa_velocities = world_plant->num_velocities(); - - drake::systems::DiagramBuilder builder; - builder.AddSystem(std::move(owned_world_plant)); - builder.AddSystem(std::move(owned_scene_graph)); - - auto lcm = builder.AddSystem(); - - // Create the command subscriber and status publisher. - auto command_sub = builder.AddSystem( - drake::systems::lcm::LcmSubscriberSystem::Make( - "IIWA_COMMAND", lcm)); - command_sub->set_name("command_subscriber"); - auto command_receiver = - builder.AddSystem(num_iiwa_positions); - command_receiver->set_name("command_receiver"); - - // LCM publisher system - const double kIiwaLcmStatusPeriod = 0.005; - auto iiwa_status_publisher = builder.AddSystem( - drake::systems::lcm::LcmPublisherSystem::Make( - "IIWA_STATUS", lcm, kIiwaLcmStatusPeriod /* publish period */)); - - // Torque Controller-- includes virtual springs and damping. - VectorXd stiffness, damping_ratio; - - // The virtual spring stiffness in Nm/rad. - stiffness.resize(num_iiwa_positions); - stiffness << 2, 2, 2, 2, 2, 2, 2; - - // A dimensionless damping ratio. See KukaTorqueController for details. - damping_ratio.resize(num_iiwa_positions); - damping_ratio.setConstant(1.0); - auto iiwa_controller = builder.AddSystem< - dairlib::systems::KukaTorqueController>( - std::move(owned_controller_plant), stiffness, damping_ratio); - - // Creating status sender - auto iiwa_status = builder.AddSystem(num_iiwa_positions); - - // Creating system to approximate desired state command from a discrete - // derivative of the position command input port. - auto desired_state_from_position = builder.AddSystem< - drake::systems::StateInterpolatorWithDiscreteDerivative>( - num_iiwa_positions, world_plant->time_step()); - - // Demuxing system state for status publisher - auto demux = builder.AddSystem>( - 2 * num_iiwa_positions, num_iiwa_positions); - - builder.Connect(command_sub->get_output_port(), - command_receiver->get_message_input_port()); - - // Connecting iiwa input ports - builder.Connect(iiwa_controller->get_output_port_control(), - world_plant->get_actuation_input_port(iiwa_model)); - - // Interpolating desired positions into desired velocities for controller. - builder.Connect(command_receiver->get_commanded_position_output_port(), - desired_state_from_position->get_input_port()); - - // Connecting iiwa controller input ports - builder.Connect(world_plant->get_state_output_port(iiwa_model), - iiwa_controller->get_input_port_estimated_state()); - builder.Connect(desired_state_from_position->get_output_port(), - iiwa_controller->get_input_port_desired_state()); - builder.Connect(command_receiver->get_commanded_torque_output_port(), - iiwa_controller->get_input_port_commanded_torque()); - - // Demux is for separating q and v from state output port. - builder.Connect(world_plant->get_state_output_port(iiwa_model), - demux->get_input_port(0)); - - // Connecting outputs to iiwa state broadcaster - builder.Connect(demux->get_output_port(0), - iiwa_status->get_position_measured_input_port()); - builder.Connect(demux->get_output_port(1), - iiwa_status->get_velocity_estimated_input_port()); - builder.Connect(command_receiver->get_output_port(0), - iiwa_status->get_position_commanded_input_port()); - builder.Connect(iiwa_controller->get_output_port_control(), - iiwa_status->get_torque_commanded_input_port()); - builder.Connect(iiwa_controller->get_output_port_control(), - iiwa_status->get_torque_measured_input_port()); - builder.Connect(world_plant->get_generalized_contact_forces_output_port(iiwa_model), - iiwa_status->get_torque_external_input_port()); - builder.Connect(iiwa_status->get_output_port(), - iiwa_status_publisher->get_input_port()); - - // Connecting world to scene graph components for visualization - builder.Connect( - world_plant->get_geometry_poses_output_port(), - scene_graph->get_source_pose_port(world_plant->get_source_id().value())); - builder.Connect(scene_graph->get_query_output_port(), - world_plant->get_geometry_query_input_port()); - - DrakeVisualizer::AddToBuilder(&builder, *scene_graph); - - auto diagram = builder.Build(); - drake::systems::Simulator simulator(*diagram); - - // Set the iiwa default joint configuration. - drake::VectorX q0_iiwa(num_iiwa_positions + num_iiwa_velocities); - q0_iiwa << 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0; - - drake::systems::Context& context = - diagram->GetMutableSubsystemContext(*world_plant, - &simulator.get_mutable_context()); - - drake::systems::BasicVector& state = - context.get_mutable_discrete_state(0); - state.SetFromVector(q0_iiwa); - - simulator.set_publish_every_time_step(false); - simulator.set_target_realtime_rate(1.0); - simulator.AdvanceTo(std::numeric_limits::infinity()); - return 0; - -} - -} // namespace kuka_iiwa_arm -} // namespace examples -} // namespace drake - -int main(int argc, char* argv[]) { - return dairlib::examples::kuka_iiwa_arm::DoMain(); -} diff --git a/examples/kuka_iiwa_arm/kuka_test.pmd b/examples/kuka_iiwa_arm/kuka_test.pmd deleted file mode 100644 index 9f18384e2a..0000000000 --- a/examples/kuka_iiwa_arm/kuka_test.pmd +++ /dev/null @@ -1,44 +0,0 @@ -group "0.operator" { - cmd "1.drake-director" { - exec = "bazel-bin/director/drake-director --script examples/kuka_iiwa_arm/signal_scope_panel.py"; - host = "localhost"; - } -} - -group "1.simulated-robot" { - cmd "1.simulator" { - exec = "bazel-bin/examples/kuka_iiwa_arm/kuka_simulation"; - host = "localhost"; - } - - cmd "1a. rbp simulator" { - exec = "../drake/bazel-bin/examples/kuka_iiwa_arm/kuka_simulation"; - host = "localhost"; - } - - cmd "2.position_broadcaster" { - exec = "bazel-bin/examples/kuka_iiwa_arm/iiwa_controller_demo"; - host = "localhost"; - } - - cmd "3.iiwa_oscillate" { - exec = "bazel-bin/examples/kuka_iiwa_arm/iiwa_oscillate"; - host = "localhost"; - } - - cmd "4.Visualizer" { - exec = "bazel-bin/examples/kuka_iiwa_arm/iiwa_visualizer"; - host = "localhost"; - } -} - -group "2.lcm-tools" { - cmd "0.lcm-spy" { - exec = "bazel-bin/lcmtypes/dair-lcm-spy"; - host = "localhost"; - } - cmd "1.signal-scope" { - exec = "bazel-bin/director/signal-scope"; - host = "localhost"; - } -} diff --git a/examples/kuka_iiwa_arm/kuka_torque_controller.cc b/examples/kuka_iiwa_arm/kuka_torque_controller.cc deleted file mode 100644 index a9b7687d40..0000000000 --- a/examples/kuka_iiwa_arm/kuka_torque_controller.cc +++ /dev/null @@ -1,175 +0,0 @@ -// A rewrite of Drake's kuka_torque_controller updated with a MultiBodyPlant. -#include - -#include -#include "drake/systems/controllers/inverse_dynamics.h" -#include "drake/systems/controllers/pid_controller.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/framework/leaf_system.h" -#include "drake/systems/primitives/adder.h" -#include "drake/systems/primitives/constant_vector_source.h" -#include "drake/systems/primitives/pass_through.h" -#include "drake/multibody/plant/multibody_plant.h" - -#include "examples/kuka_iiwa_arm/kuka_torque_controller.h" - -namespace dairlib { -namespace systems { - - using drake::systems::kVectorValued; - using drake::systems::Adder; - using drake::systems::BasicVector; - using drake::systems::Context; - using drake::systems::DiagramBuilder; - using drake::systems::LeafSystem; - using drake::systems::PassThrough; - using drake::systems::controllers::InverseDynamics; - using drake::systems::controllers::PidController; - using drake::multibody::MultibodyPlant; - using drake::VectorX; - -template -class StateDependentDamper : public LeafSystem { - public: - StateDependentDamper(const MultibodyPlant& plant, - const VectorX& stiffness, - const VectorX& damping_ratio) - : plant_(plant), stiffness_(stiffness), damping_ratio_(damping_ratio) { - const int num_q = plant_.num_positions(); - const int num_v = plant_.num_velocities(); - const int num_x = num_q + num_v; - - DRAKE_DEMAND(stiffness.size() == num_v); - DRAKE_DEMAND(damping_ratio.size() == num_v); - - this->DeclareInputPort("x", kVectorValued, num_x); - this->DeclareVectorOutputPort("u", BasicVector(num_v), - &StateDependentDamper::CalcTorque); - } - - private: - const MultibodyPlant& plant_; - const VectorX stiffness_; - const VectorX damping_ratio_; - - /** - * Computes joint level damping forces by computing the damping ratio for each - * joint independently as if all other joints were fixed. Note that the - * effective inertia of a joint, when all of the other joints are fixed, is - * given by the corresponding diagonal entry of the mass matrix. The critical - * damping gain for the i-th joint is given by 2*sqrt(M(i,i)*stiffness(i)). - */ - void CalcTorque(const Context& context, BasicVector* torque) const { - Eigen::VectorXd x = this->EvalVectorInput(context, 0)->get_value(); - Eigen::VectorXd q = x.head(plant_.num_positions()); - Eigen::VectorXd v = x.tail(plant_.num_velocities()); - - // Compute critical damping gains and scale by damping ratio. Use Eigen - // arrays (rather than matrices) for elementwise multiplication. - Eigen::MatrixXd H(plant_.num_positions(), plant_.num_positions()); - std::unique_ptr> plant_context = plant_.CreateDefaultContext(); - - plant_.CalcMassMatrix(*plant_context.get(), &H); - Eigen::ArrayXd temp = H.diagonal().array() * stiffness_.array(); - Eigen::ArrayXd damping_gains = 2 * temp.sqrt(); - damping_gains *= damping_ratio_.array(); - - // Compute damping torque. - torque->get_mutable_value() = -(damping_gains * v.array()).matrix(); - } -}; - - -template -void KukaTorqueController::SetUp(const VectorX& stiffness, - const VectorX& damping_ratio) { - DiagramBuilder builder; - const MultibodyPlant& plant = *robot_for_control_; - DRAKE_DEMAND(plant.num_positions() == stiffness.size()); - DRAKE_DEMAND(plant.num_positions() == damping_ratio.size()); - - const int dim = plant.num_positions(); - - /* - torque_in ---------------------------- - | - (q, v) ------>|Gravity Comp|------+---> torque_out - | /| - --->|Damping|---------- | - | | - --->| Virtual Spring |--- - (q*, v*) ------>|PID with kd=ki=0| - */ - - // Redirects estimated state input into PID and gravity compensation. - auto pass_through = builder.template AddSystem>(2 * dim); - - - // Add gravity compensator. - auto gravity_comp = builder.template AddSystem>( - &plant, InverseDynamics::kGravityCompensation); - - // Adds virtual springs. - Eigen::VectorXd kd(dim); - Eigen::VectorXd ki(dim); - Eigen::VectorXd kp(dim); - kd.setZero(); - ki.setZero(); - kp.setZero(); - auto spring = builder.template AddSystem>(kp, kd, ki); - - // Adds virtual damper. - auto damper = builder.template AddSystem>( - plant, stiffness, damping_ratio); - - // Adds an adder to sum the gravity compensation, spring, damper, and - // feedforward torque. - auto adder = builder.template AddSystem>(4, dim); - - // Connects the estimated state to the gravity compensator. - builder.Connect(pass_through->get_output_port(), - gravity_comp->get_input_port_estimated_state()); - - // Connects the estimated state to the spring. - builder.Connect(pass_through->get_output_port(), - spring->get_input_port_estimated_state()); - - // Connects the estimated state to the damper. - builder.Connect(pass_through->get_output_port(), - damper->get_input_port(0)); - - // Connects the gravity compensation, spring, and damper torques to the adder. - builder.Connect(gravity_comp->get_output_port_force(), adder->get_input_port(1)); - builder.Connect(spring->get_output_port(0), adder->get_input_port(2)); - builder.Connect(damper->get_output_port(0), adder->get_input_port(3)); - - // Exposes the estimated state port. - input_port_index_estimated_state_ = - builder.ExportInput(pass_through->get_input_port()); - - // Exposes the desired state port. - input_port_index_desired_state_ = - builder.ExportInput(spring->get_input_port_desired_state()); - - // Exposes the commanded torque port. - input_port_index_commanded_torque_ = - builder.ExportInput(adder->get_input_port(0)); - - // Exposes controller output. - output_port_index_control_ = builder.ExportOutput(adder->get_output_port()); - builder.BuildInto(this); -} - -template -KukaTorqueController::KukaTorqueController( - std::unique_ptr> plant, const VectorX& stiffness, - const VectorX& damping) { - robot_for_control_ = std::move(plant); - SetUp(stiffness, damping); -} - - -template class dairlib::systems::KukaTorqueController; - -} // namespace systems -} // namespace dairlib diff --git a/examples/kuka_iiwa_arm/kuka_torque_controller.h b/examples/kuka_iiwa_arm/kuka_torque_controller.h deleted file mode 100644 index d762465521..0000000000 --- a/examples/kuka_iiwa_arm/kuka_torque_controller.h +++ /dev/null @@ -1,68 +0,0 @@ -#pragma once - -#include -#include - -#include "drake/common/drake_copyable.h" -#include "drake/multibody/plant/multibody_plant.h" -#include "drake/systems/controllers/state_feedback_controller_interface.h" -#include "drake/systems/framework/diagram.h" - -namespace dairlib { -namespace systems { - -/** - * Controller that take emulates the kuka_iiwa_arm when operated in torque - * control mode. The controller specifies a stiffness and damping ratio at each - * of the joints. Because the critical damping constant is a function of the - * configuration the damping is non-linear. See - * https://github.com/RobotLocomotion/drake-iiwa-driver/blob/master/kuka-driver/sunrise_1.11/DrakeFRITorqueDriver.java - * - * for details on the low-level controller. Note that the - * input_port_desired_state() method takes a full state for convenient wiring - * with other Systems, but ignores the velocity component. - */ - -using drake::VectorX; -using drake::multibody::MultibodyPlant; - -template -class KukaTorqueController - : public drake::systems::Diagram, - public drake::systems::controllers::StateFeedbackControllerInterface { - public: - DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(KukaTorqueController) - KukaTorqueController(std::unique_ptr> plant, - const VectorX& stiffness, - const VectorX& damping); - - const drake::systems::InputPort& get_input_port_commanded_torque() const { - return drake::systems::Diagram::get_input_port( - input_port_index_commanded_torque_); - } - - const drake::systems::InputPort& get_input_port_estimated_state() const override { - return drake::systems::Diagram::get_input_port( - input_port_index_estimated_state_); - } - - const drake::systems::InputPort& get_input_port_desired_state() const override { - return drake::systems::Diagram::get_input_port(input_port_index_desired_state_); - } - - const drake::systems::OutputPort& get_output_port_control() const override { - return drake::systems::Diagram::get_output_port(output_port_index_control_); - } - - private: - void SetUp(const VectorX& stiffness, - const VectorX& damping_ratio); - std::unique_ptr> robot_for_control_{nullptr}; - int input_port_index_estimated_state_{-1}; - int input_port_index_desired_state_{-1}; - int input_port_index_commanded_torque_{-1}; - int output_port_index_control_{-1}; -}; - -} // namespace systems -} // namespace dair diff --git a/examples/kuka_iiwa_arm/signal_scope_panel.py b/examples/kuka_iiwa_arm/signal_scope_panel.py deleted file mode 100644 index c0508908c4..0000000000 --- a/examples/kuka_iiwa_arm/signal_scope_panel.py +++ /dev/null @@ -1,8 +0,0 @@ -import dairlib.lcmt_iiwa_command -import dairlib.lcmt_iiwa_status - -import director.openscope as scope -import subprocess - -view = applogic.getMainWindow() -applogic.addShortcut(view, 'Ctrl+I', scope.startSignalScope) diff --git a/examples/trifinger/lcm_control_demo.py b/examples/trifinger/lcm_control_demo.py index 6564c38c9f..817c31799f 100644 --- a/examples/trifinger/lcm_control_demo.py +++ b/examples/trifinger/lcm_control_demo.py @@ -47,9 +47,9 @@ def CalcControl(self, context, output): parser = Parser(plant) parser.package_map().Add("robot_properties_fingers", "examples/trifinger/robot_properties_fingers") -parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( +parser.AddModels(pydairlib.common.FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/urdf/trifinger_minimal_collision.urdf")) -parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( +parser.AddModels(pydairlib.common.FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/cube/cube_v2.urdf")) # Fix the base of the finger to the world diff --git a/examples/trifinger/simulate_trifinger.py b/examples/trifinger/simulate_trifinger.py index 1c91adc7ff..0a08c51563 100644 --- a/examples/trifinger/simulate_trifinger.py +++ b/examples/trifinger/simulate_trifinger.py @@ -43,9 +43,9 @@ def CalcControl(self, context, output): parser = Parser(plant) parser.package_map().Add("robot_properties_fingers", "examples/trifinger/robot_properties_fingers") -parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( +parser.AddModels(pydairlib.common.FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/urdf/trifinger_minimal_collision.urdf")) -parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( +parser.AddModels(pydairlib.common.FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/cube/cube_v2.urdf")) # Fix the base of the finger to the world diff --git a/examples/trifinger/simulate_trifinger_lcm.py b/examples/trifinger/simulate_trifinger_lcm.py index e3f6f7329d..faf1e5970c 100644 --- a/examples/trifinger/simulate_trifinger_lcm.py +++ b/examples/trifinger/simulate_trifinger_lcm.py @@ -17,9 +17,9 @@ parser = Parser(plant) parser.package_map().Add("robot_properties_fingers", "examples/trifinger/robot_properties_fingers") -parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( +parser.AddModels(pydairlib.common.FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/urdf/trifinger_minimal_collision.urdf")) -parser.AddModelFromFile(pydairlib.common.FindResourceOrThrow( +parser.AddModels(pydairlib.common.FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/cube/cube_v2.urdf")) # Fix the base of the finger to the world diff --git a/lcmtypes/BUILD.bazel b/lcmtypes/BUILD.bazel index 3297db6fc0..bf07523c9b 100644 --- a/lcmtypes/BUILD.bazel +++ b/lcmtypes/BUILD.bazel @@ -63,6 +63,5 @@ drake_java_binary( runtime_deps = [ ":lcmtypes_robot_java", "@drake//lcmtypes:lcmtypes_drake_java", - "@optitrack_driver//lcmtypes:lcmtypes_optitrack", ], ) diff --git a/multibody/kinematic/test/kinematic_evaluator_caching_test.cc b/multibody/kinematic/test/kinematic_evaluator_caching_test.cc index 43cd3e62fe..333dec4bc5 100644 --- a/multibody/kinematic/test/kinematic_evaluator_caching_test.cc +++ b/multibody/kinematic/test/kinematic_evaluator_caching_test.cc @@ -309,7 +309,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0); drake::multibody::Parser parser(&plant); std::string full_name = FindResourceOrThrow(filename); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant.Finalize(); multibody::KinematicEvaluatorSet evaluators(plant); diff --git a/multibody/kinematic/test/kinematic_evaluator_test.cc b/multibody/kinematic/test/kinematic_evaluator_test.cc index 904993cd22..14ca6846da 100644 --- a/multibody/kinematic/test/kinematic_evaluator_test.cc +++ b/multibody/kinematic/test/kinematic_evaluator_test.cc @@ -36,7 +36,7 @@ class KinematicEvaluatorTest : public ::testing::Test { std::string full_name = dairlib::FindResourceOrThrow("examples/PlanarWalker/PlanarWalker.urdf"); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("base"), drake::math::RigidTransform()); diff --git a/multibody/test/geom_geom_collider_test.cc b/multibody/test/geom_geom_collider_test.cc index 09050b0af5..dbb1d33f08 100644 --- a/multibody/test/geom_geom_collider_test.cc +++ b/multibody/test/geom_geom_collider_test.cc @@ -28,9 +28,9 @@ void GeomGeomColliderTest() { parser.package_map().Add("robot_properties_fingers", "examples/trifinger/robot_properties_fingers"); - parser.AddModelFromFile(FindResourceOrThrow("examples/trifinger/" + parser.AddModels(FindResourceOrThrow("examples/trifinger/" "robot_properties_fingers/urdf/trifinger_minimal_collision.urdf")); - parser.AddModelFromFile(FindResourceOrThrow( + parser.AddModels(FindResourceOrThrow( "examples/trifinger/robot_properties_fingers/cube/cube_v2.urdf")); auto X_WI = drake::math::RigidTransform::Identity(); diff --git a/multibody/test/multibody_utils_test.cc b/multibody/test/multibody_utils_test.cc index 8c9f4df502..021411465a 100644 --- a/multibody/test/multibody_utils_test.cc +++ b/multibody/test/multibody_utils_test.cc @@ -23,7 +23,7 @@ class MultibodyUtilsTest : public ::testing::Test { std::string full_name = FindResourceOrThrow( "examples/Cassie/urdf/cassie_v2.urdf"); Parser parser(&plant_, &scene_graph); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); plant_.Finalize(); } diff --git a/multibody/visualization_utils.cc b/multibody/visualization_utils.cc index 2c53e7c15f..ab2b7d70c8 100644 --- a/multibody/visualization_utils.cc +++ b/multibody/visualization_utils.cc @@ -25,7 +25,7 @@ std::unique_ptr> ConstructBallPlant( auto ball_plant = std::make_unique>(0.0); std::string full_name = FindResourceOrThrow("multibody/ball.urdf"); Parser parser(ball_plant.get(), scene_graph); - parser.AddModelFromFile(full_name); + parser.AddModels(full_name); ball_plant->Finalize(); return ball_plant; } diff --git a/solvers/fast_osqp_solver_common.cc b/solvers/fast_osqp_solver_common.cc index 40e688d7bd..70c06cad9a 100644 --- a/solvers/fast_osqp_solver_common.cc +++ b/solvers/fast_osqp_solver_common.cc @@ -18,8 +18,8 @@ namespace dairlib { namespace solvers { FastOsqpSolver::FastOsqpSolver() - : SolverBase(id(), &is_available, &is_enabled, &ProgramAttributesSatisfied) { -} + : SolverBase(id(), &is_available, &is_enabled, + &ProgramAttributesSatisfied) {} FastOsqpSolver::~FastOsqpSolver() = default; @@ -32,7 +32,7 @@ bool FastOsqpSolver::is_enabled() { return true; } namespace { bool CheckAttributes(const MathematicalProgram& prog, - std::string* explanation) { + std::string* explanation) { static const drake::never_destroyed solver_capabilities( std::initializer_list{ ProgramAttribute::kLinearCost, ProgramAttribute::kQuadraticCost, @@ -61,7 +61,8 @@ bool CheckAttributes(const MathematicalProgram& prog, } const drake::solvers::Binding* nonconvex_quadratic_cost = - FindNonconvexQuadraticCost(prog.quadratic_costs()); + drake::solvers::internal::FindNonconvexQuadraticCost( + prog.quadratic_costs()); if (nonconvex_quadratic_cost != nullptr) { if (explanation) { *explanation = diff --git a/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc index e7f519360b..a6c6349469 100644 --- a/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/dircon/test/passive_constrained_pendulum_dircon.cc @@ -66,10 +66,10 @@ void runDircon() { Parser parser(&plant_double); Parser parser_vis(&plant_vis, &scene_graph); - parser.AddModelFromFile(urdf_path); + parser.AddModels(urdf_path); plant_double.Finalize(); - parser_vis.AddModelFromFile(urdf_path); + parser_vis.AddModels(urdf_path); plant_vis.Finalize(); std::unique_ptr> plant_pointer; diff --git a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc index e5d3dcebc0..b5df5cfa93 100644 --- a/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc +++ b/systems/trajectory_optimization/test/passive_constrained_pendulum_dircon.cc @@ -56,7 +56,7 @@ void runDircon() { SceneGraph& scene_graph = *builder.AddSystem(); Parser parser(&plant, &scene_graph); - parser.AddModelFromFile(sdf_path); + parser.AddModels(sdf_path); plant.WeldFrames( plant.world_frame(), plant.GetFrameByName("base_link"), diff --git a/tools/workspace/pydrake/repository.bzl b/tools/workspace/pydrake/repository.bzl index 78c121a0f3..4866b0d5f6 100644 --- a/tools/workspace/pydrake/repository.bzl +++ b/tools/workspace/pydrake/repository.bzl @@ -1,29 +1,29 @@ -load("@drake//tools/workspace:pypi_wheel.bzl", "setup_pypi_wheel") - -def _impl(repository_ctx): - mirrors = { - "pypi_wheel": [ - "https://www.seas.upenn.edu/~posa/files/{package}-{version}-{tag}.whl", # noqa - ], - } - - result = setup_pypi_wheel( - repository_ctx, - package = "drake", - version = "0.0.2022.2.2", - pypi_tag = "cp38-cp38-manylinux_2_27_x86_64", - blake2_256 = "0", # noqa - sha256 = "6ffd53c9889eaa3a2ce27784ee9a21f65f849bcfab47d1958c234bd218c2d163", # noqa - mirrors = mirrors, - data = "glob([\"pydrake/share/drake/**\"])", - ) - if result.error != None: - fail("Unable to complete setup for @{} repository: {}".format( - # (forced line break) - repository_ctx.name, - result.error, - )) - -pydrake_repository = repository_rule( - implementation = _impl, -) +#load("@drake//tools/workspace:pypi_wheel.bzl", "setup_pypi_wheel") +# +#def _impl(repository_ctx): +# mirrors = { +# "pypi_wheel": [ +# "https://www.seas.upenn.edu/~posa/files/{package}-{version}-{tag}.whl", # noqa +# ], +# } +# +# result = setup_pypi_wheel( +# repository_ctx, +# package = "drake", +# version = "0.0.2022.2.2", +# pypi_tag = "cp38-cp38-manylinux_2_27_x86_64", +# blake2_256 = "0", # noqa +# sha256 = "6ffd53c9889eaa3a2ce27784ee9a21f65f849bcfab47d1958c234bd218c2d163", # noqa +# mirrors = mirrors, +# data = "glob([\"pydrake/share/drake/**\"])", +# ) +# if result.error != None: +# fail("Unable to complete setup for @{} repository: {}".format( +# # (forced line break) +# repository_ctx.name, +# result.error, +# )) +# +#pydrake_repository = repository_rule( +# implementation = _impl, +#) From 4db2e1ab6ab0b59b0acac3a9750ec907c9f43fa7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 12 Jan 2024 17:43:42 -0500 Subject: [PATCH 602/758] slight tuning and updating sim params to allow modifying camera pose --- examples/franka/franka_visualizer.cc | 1 + .../franka/parameters/franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_c3_options_w_supports.yaml | 2 +- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.h | 6 ++++++ examples/franka/parameters/franka_sim_params.yaml | 7 +++++-- 6 files changed, 15 insertions(+), 5 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 21be9df069..5201a431ee 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -168,6 +168,7 @@ int do_main(int argc, char* argv[]) { auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); + meshcat->SetCameraPose(sim_params.camera_pose, sim_params.camera_target); auto trajectory_drawer_actor = builder.AddSystem( meshcat, "end_effector_position_target"); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 326d60edf7..3f00cfb72c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -31,7 +31,7 @@ near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.45], [0.45, 0, 0.488]] second_target: [[0.45, 0.0, 0.45], - [0.45, 0, 0.65]] + [0.45, 0, 0.6]] third_target: [[0.45, 0.0, 0.45], [0.7, 0.00, 0.488]] x_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 6209692d5e..9e0b844c00 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -12,7 +12,7 @@ warm_start: true use_predicted_x0: true solve_time_filter_alpha: 0.9 -mu: [0.55, 0.55, 0.55, 0.1, 0.1, 0.1, 0.1] +mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index fcd7090eab..2140bf9708 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 86cea76367..51e9360916 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -24,6 +24,9 @@ struct FrankaSimParams { bool visualize; bool publish_efforts; + Eigen::VectorXd camera_pose; + Eigen::VectorXd camera_target; + Eigen::VectorXd q_init_franka; std::vector q_init_plate; Eigen::VectorXd q_init_box; @@ -53,6 +56,9 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(visualize)); a->Visit(DRAKE_NVP(publish_efforts)); + a->Visit(DRAKE_NVP(camera_pose)); + a->Visit(DRAKE_NVP(camera_target)); + a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); a->Visit(DRAKE_NVP(q_init_box)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index f6753f7e8e..04d970313e 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -16,9 +16,12 @@ scene_index: 1 visualize: true publish_efforts: true +camera_pose: [0.5, -1.5, 0.7] +camera_target: [0.5, 0, 0.5] + tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.453] -right_support_position: [0.8, -0.15, 0.453] +left_support_position: [0.8, 0.15, 0.455] +right_support_position: [0.8, -0.15, 0.455] dt: 0.0005 realtime_rate: 1.0 From fff0d31a6269d33fb69ac1064cfd518f8cce6a3b Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 15 Jan 2024 13:39:21 -0500 Subject: [PATCH 603/758] minor changes to work with drake v1.24.0 --- examples/Cassie/cassie_state_estimator.cc | 54 ++++++++++--------- .../Cassie/networking/cassie_udp_publisher.cc | 10 ++-- systems/ros/ros_publisher_system.h | 7 +-- 3 files changed, 34 insertions(+), 37 deletions(-) diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index 50b0ee3ebf..ee73c24cd1 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -67,7 +67,7 @@ CassieStateEstimator::CassieStateEstimator( print_info_to_terminal_(print_info_to_terminal), hardware_test_mode_(hardware_test_mode), contact_force_threshold_(contact_force_threshold), - joint_offsets_(MakeJointPositionOffsetFromMap(plant, joint_offset_map)){ + joint_offsets_(MakeJointPositionOffsetFromMap(plant, joint_offset_map)) { DRAKE_DEMAND(&fourbar_evaluator->plant() == &plant); DRAKE_DEMAND(&left_contact_evaluator->plant() == &plant); DRAKE_DEMAND(&right_contact_evaluator->plant() == &plant); @@ -416,7 +416,7 @@ void CassieStateEstimator::AssignNonFloatingBaseStateToOutputVector( double right_heel_spring = 0; VectorXd q = output->GetPositions() + joint_offsets_; output->SetPositions(q); - + if (is_floating_base_) { // Floating-base state doesn't affect the spring values // We assign the floating base of q in case output's floating base is @@ -435,20 +435,30 @@ void CassieStateEstimator::AssignNonFloatingBaseStateToOutputVector( void CassieStateEstimator::AssignFloatingBaseStateToOutputVector( const VectorXd& est_fb_state, OutputVector* output) const { - output->SetPositionAtIndex(position_idx_map_.at("pelvis_qw"), est_fb_state(0)); - output->SetPositionAtIndex(position_idx_map_.at("pelvis_qx"), est_fb_state(1)); - output->SetPositionAtIndex(position_idx_map_.at("pelvis_qy"), est_fb_state(2)); - output->SetPositionAtIndex(position_idx_map_.at("pelvis_qz"), est_fb_state(3)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qw"), + est_fb_state(0)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qx"), + est_fb_state(1)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qy"), + est_fb_state(2)); + output->SetPositionAtIndex(position_idx_map_.at("pelvis_qz"), + est_fb_state(3)); output->SetPositionAtIndex(position_idx_map_.at("pelvis_x"), est_fb_state(4)); output->SetPositionAtIndex(position_idx_map_.at("pelvis_y"), est_fb_state(5)); output->SetPositionAtIndex(position_idx_map_.at("pelvis_z"), est_fb_state(6)); - output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wx"), est_fb_state(7)); - output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wy"), est_fb_state(8)); - output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wz"), est_fb_state(9)); - output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vx"), est_fb_state(10)); - output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vy"), est_fb_state(11)); - output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vz"), est_fb_state(12)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wx"), + est_fb_state(7)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wy"), + est_fb_state(8)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_wz"), + est_fb_state(9)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vx"), + est_fb_state(10)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vy"), + est_fb_state(11)); + output->SetVelocityAtIndex(velocity_idx_map_.at("pelvis_vz"), + est_fb_state(12)); } /// EstimateContactFromSprings(). Conservative estimation. @@ -780,9 +790,9 @@ EventStatus CassieStateEstimator::Update( // TODO(yangwill): Decide whether to use both contacts per foot or just one. // Possibly leave it as an option to the state estimator contacts.push_back(std::pair(0, left_contact)); -// contacts.push_back(std::pair(1, left_contact)); + // contacts.push_back(std::pair(1, left_contact)); contacts.push_back(std::pair(2, right_contact)); -// contacts.push_back(std::pair(3, right_contact)); + // contacts.push_back(std::pair(3, right_contact)); ekf.setContacts(contacts); // Step 4 - EKF (measurement step) @@ -1020,7 +1030,6 @@ void CassieStateEstimator::setPreviousImuMeasurement( void CassieStateEstimator::EstimateContactForces( const Context& context, const systems::OutputVector& output, VectorXd& lambda, int& left_contact, int& right_contact) const { - // TODO(yangwill) add a discrete time filter to the force estimate VectorXd v_prev = context.get_discrete_state(previous_velocity_idx_).get_value(); @@ -1087,15 +1096,12 @@ void CassieStateEstimator::DoCalcNextUpdateTime( *time = next_message_time_ - eps_; if (is_floating_base_) { - //TODO(yangwill) fix this using new Drake -// UnrestrictedUpdateEvent::UnrestrictedUpdateCallback callback = -// [this](const Context& c, -// const UnrestrictedUpdateEvent&, -// drake::systems::State* s) { this->Update(c, s); }; -// -// auto& uu_events = events->get_mutable_unrestricted_update_events(); -// uu_events.AddEvent(UnrestrictedUpdateEvent( -// drake::systems::TriggerType::kTimed, callback)); + auto callback = [](const System& system, const Context& c, + const UnrestrictedUpdateEvent&, + drake::systems::State* s) { + const auto& self = dynamic_cast(system); + return self.Update(c, s); + }; } else { *time = INFINITY; } diff --git a/examples/Cassie/networking/cassie_udp_publisher.cc b/examples/Cassie/networking/cassie_udp_publisher.cc index 02c6d18245..9c5e3eee82 100644 --- a/examples/Cassie/networking/cassie_udp_publisher.cc +++ b/examples/Cassie/networking/cassie_udp_publisher.cc @@ -64,13 +64,9 @@ CassieUDPPublisher::CassieUDPPublisher(const std::string& address, DRAKE_DEMAND(publish_period == 0); } if (publish_triggers.find(TriggerType::kPerStep) != publish_triggers.end()) { - //TODO(yangwill): fix this later for new drake -// this->DeclarePerStepEvent( -// drake::systems::PublishEvent([this]( -// const drake::systems::Context& context, -// const drake::systems::PublishEvent&) { -// this->PublishInputAsUDPMessage(context); -// })); + this->DeclarePerStepPublishEvent( + &CassieUDPPublisher::PublishInputAsUDPMessage + ); } } diff --git a/systems/ros/ros_publisher_system.h b/systems/ros/ros_publisher_system.h index b49f3aa9a4..f3b21ee6fc 100644 --- a/systems/ros/ros_publisher_system.h +++ b/systems/ros/ros_publisher_system.h @@ -129,12 +129,7 @@ class RosPublisherSystem : public drake::systems::LeafSystem { if (publish_triggers.find(TriggerType::kPerStep) != publish_triggers.end()) { - this->DeclarePerStepEvent( - drake::systems::PublishEvent([this]( - const drake::systems::Context& context, - const drake::systems::PublishEvent&) { - this->PublishToRosTopic(context); - })); + this->DeclarePerStepPublishEvent(&RosPublisherSystem::PublishToRosTopic); } } From 71980c357d29a2da8f1c854a302f18cde589759d Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 16 Jan 2024 11:11:18 -0500 Subject: [PATCH 604/758] reordering parameter file, tuning plate balancing for anitescu model --- .../parameters/franka_c3_controller_params.h | 16 +++++++----- .../franka_c3_controller_params.yaml | 19 +++++--------- .../franka_c3_options_translation.yaml | 26 ++++++++++++------- .../franka_c3_options_w_supports.yaml | 14 +++++++--- .../franka/parameters/franka_sim_params.yaml | 6 ++--- solvers/c3_options.h | 12 +++++++++ systems/controllers/c3_controller.cc | 10 +++---- 7 files changed, 65 insertions(+), 38 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index fb320cf326..685d04a32e 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -14,12 +14,19 @@ struct FrankaC3ControllerParams { std::string tray_model; std::string left_support_model; std::string right_support_model; - bool include_end_effector_orientation; - double target_frequency; + Eigen::Vector3d tool_attachment_frame; + Eigen::Vector3d left_support_position; + Eigen::Vector3d right_support_position; + double end_effector_thickness; int scene_index; + + + bool include_end_effector_orientation; + double target_frequency; + std::vector first_target; std::vector second_target; std::vector third_target; @@ -28,10 +35,6 @@ struct FrankaC3ControllerParams { double z_scale; double near_target_threshold; - Eigen::Vector3d left_support_position; - Eigen::Vector3d right_support_position; - double end_effector_thickness; - template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(c3_options_file)); @@ -48,6 +51,7 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(scene_index)); + a->Visit(DRAKE_NVP(first_target)); a->Visit(DRAKE_NVP(second_target)); a->Visit(DRAKE_NVP(third_target)); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 3f00cfb72c..803e5307f5 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -6,33 +6,28 @@ osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate - -tool_attachment_frame: [0, 0, 0.107] plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -#plate_model: examples/franka/urdf/plate_end_effector_floating.urdf tray_model: examples/franka/urdf/tray.sdf - -scene_index: 1 - -#left_support_model: examples/franka/urdf/left_support.urdf -#right_support_model: examples/franka/urdf/left_support.urdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf +tool_attachment_frame: [0, 0, 0.107] left_support_position: [0.8, 0.15, 0.455] right_support_position: [0.8, -0.15, 0.455] -end_effector_thickness: 0.015 +end_effector_thickness: 0.016 + +scene_index: 0 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused near_target_threshold: 0.05 -first_target: [[0.45, 0.0, 0.45], +first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.488]] -second_target: [[0.45, 0.0, 0.45], +second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6]] -third_target: [[0.45, 0.0, 0.45], +third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.488]] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index f8b8de191e..0904e574a5 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -1,18 +1,26 @@ admm_iter: 4 -rho: 0.1 +rho: 0.0 rho_scale: 2 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'anitescu' -contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' +#contact_model: 'stewart_and_trinkle' warm_start: true -use_predicted_x0: true +use_predicted_x0: false solve_time_filter_alpha: 0.9 -mu: [0.2, 0.2, 0.2] +# Workspace Limits +world_x_limits: [0.4, 0.6] +world_y_limits: [-0.1, 0.1] +world_z_limits: [0.35, 0.7] + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] + +mu: [0.6, 0.6, 0.6] dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 @@ -21,8 +29,8 @@ N: 5 gamma: 1 # matrix scaling -w_Q: 30 -w_R: 0 +w_Q: 50 +w_R: 1 # Penalty on all decision variables, assuming scalar w_G: 1 # Penalty on all decision variables, assuming scalar @@ -33,7 +41,7 @@ q_vector: [175, 175, 175, 10, 10, 10, 10, 15000, 15000, 15000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 1] +r_vector: [0.1, 0.1, 0.1] # Penalty on all decision variables g_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] @@ -48,5 +56,5 @@ u_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 1, 1, 1, 10, 10, 10, 10, 10, 10] u_gamma: [1, 1, 1] u_lambda_n: [1, 1, 1] u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_lambda: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] u_u: [10, 10, 10] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 9e0b844c00..8c4a047354 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -10,7 +10,15 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true -solve_time_filter_alpha: 0.9 +solve_time_filter_alpha: 0.9 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} + +# Workspace Limits +world_x_limits: [0.4, 0.6] +world_y_limits: [-0.1, 0.1] +world_z_limits: [0.35, 0.7] + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] dt: 0.075 @@ -18,7 +26,7 @@ solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 N: 5 -gamma: 1.0 +gamma: 1.0 # discount factor on MPC costs # matrix scaling w_Q: 50 @@ -29,7 +37,7 @@ w_G: 0.1 w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 100, 100, 0, 1, 1, 0, 15000, 15000, 15000, +q_vector: [150, 150, 100, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 10, 1, 100, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 04d970313e..d5485c22dd 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,11 +8,11 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 10 +tray_publish_rate: 1000 visualizer_publish_rate: 15 actuator_delay: 0.000 -scene_index: 1 +scene_index: 0 visualize: true publish_efforts: true @@ -28,7 +28,7 @@ realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.56, 0.04, 0.515], +q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.7, 0.00, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 567d0eda0f..e41130e65b 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -16,6 +16,12 @@ struct C3Options { bool use_predicted_x0; double solve_time_filter_alpha; + std::vector world_x_limits; + std::vector world_y_limits; + std::vector world_z_limits; + std::vector u_horizontal_limits; + std::vector u_vertical_limits; + int N; double gamma; double w_Q; @@ -67,6 +73,12 @@ struct C3Options { a->Visit(DRAKE_NVP(use_predicted_x0)); a->Visit(DRAKE_NVP(solve_time_filter_alpha)); + a->Visit(DRAKE_NVP(world_x_limits)); + a->Visit(DRAKE_NVP(world_y_limits)); + a->Visit(DRAKE_NVP(world_z_limits)); + a->Visit(DRAKE_NVP(u_horizontal_limits)); + a->Visit(DRAKE_NVP(u_vertical_limits)); + a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(solve_dt)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 2172af8a6a..ba5ef9bc28 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -92,27 +92,27 @@ C3Controller::C3Controller( for (int i : vector({0})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.4, 0.6, 1); + c3_->AddLinearConstraint(A, c3_options_.world_x_limits[0], c3_options_.world_x_limits[1], 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -0.1, 0.1, 1); + c3_->AddLinearConstraint(A, c3_options_.world_y_limits[0], c3_options_.world_y_limits[1], 1); } for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0.35, 0.7, 1); + c3_->AddLinearConstraint(A, c3_options_.world_z_limits[0], c3_options_.world_z_limits[1], 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, -10, 10, 2); + c3_->AddLinearConstraint(A, c3_options_.u_horizontal_limits[0], c3_options_.u_horizontal_limits[1], 2); } for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, 0, 30, 2); + c3_->AddLinearConstraint(A, c3_options_.u_vertical_limits[0], c3_options_.u_vertical_limits[1], 2); } lcs_state_input_port_ = From 00e7df04347c29add9e36ff74bb398b5f7f1f444 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 16 Jan 2024 13:41:10 -0500 Subject: [PATCH 605/758] improving visualization settings --- examples/franka/franka_sim.cc | 2 +- examples/franka/franka_visualizer.cc | 95 ++++++---- .../franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 14 +- .../franka/parameters/franka_sim_params.yaml | 13 +- .../lcm_trajectory_systems.cc | 162 ++++++++++++++++-- .../lcm_trajectory_systems.h | 45 +++++ 7 files changed, 279 insertions(+), 54 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 60a7a1f517..2aad133d4b 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -161,7 +161,7 @@ int DoMain(int argc, char* argv[]) { int nq = plant.num_positions(); int nv = plant.num_velocities(); - if (sim_params.visualize) { + if (sim_params.visualize_drake_sim) { drake::visualization::AddDefaultVisualization(&builder); } diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 5201a431ee..f835f19131 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -1,6 +1,7 @@ #include #include +#include #include #include #include @@ -159,61 +160,85 @@ int do_main(int argc, char* argv[]) { auto trajectory_sub_force = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.c3_force_channel, lcm)); + + auto c3_state_actual_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm)); + auto c3_state_target_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm)); auto to_pose = builder.AddSystem>(plant); drake::geometry::MeshcatVisualizerParams params; params.publish_period = 1.0 / sim_params.visualizer_publish_rate; - params.enable_alpha_slider = true; auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); meshcat->SetCameraPose(sim_params.camera_pose, sim_params.camera_target); - auto trajectory_drawer_actor = - builder.AddSystem( - meshcat, "end_effector_position_target"); - auto trajectory_drawer_object = - builder.AddSystem(meshcat, - "object_position_target"); - auto object_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.tray_model), - "object_position_target", "object_orientation_target"); - auto end_effector_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.end_effector_model), - "end_effector_position_target", "end_effector_orientation_target"); - auto end_effector_force_drawer = builder.AddSystem( - meshcat, "end_effector_position_target", "end_effector_force_target", - "lcs_force_trajectory"); - trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); - trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); - trajectory_drawer_actor->SetNumSamples(5); - trajectory_drawer_object->SetNumSamples(5); + + if (sim_params.visualize_center_of_mass_plan){ + auto trajectory_drawer_actor = + builder.AddSystem( + meshcat, "end_effector_position_target"); + auto trajectory_drawer_object = + builder.AddSystem(meshcat, + "object_position_target"); + trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); + trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); + trajectory_drawer_actor->SetNumSamples(5); + trajectory_drawer_object->SetNumSamples(5); + builder.Connect(trajectory_sub_actor->get_output_port(), + trajectory_drawer_actor->get_input_port_trajectory()); + builder.Connect(trajectory_sub_object->get_output_port(), + trajectory_drawer_object->get_input_port_trajectory()); + } + + if (sim_params.visualize_pose_trace){ + auto object_pose_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.tray_model), + "object_position_target", "object_orientation_target"); + auto end_effector_pose_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.end_effector_model), + "end_effector_position_target", "end_effector_orientation_target"); + + builder.Connect(trajectory_sub_object->get_output_port(), + object_pose_drawer->get_input_port_trajectory()); + builder.Connect(trajectory_sub_actor->get_output_port(), + end_effector_pose_drawer->get_input_port_trajectory()); + } + + if (sim_params.visualize_c3_state){ + auto c3_target_drawer = + builder.AddSystem(meshcat, true, true); + builder.Connect(c3_state_actual_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_actual()); + builder.Connect(c3_state_target_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_target()); + } + + if (sim_params.visualize_c3_forces){ + auto end_effector_force_drawer = builder.AddSystem( + meshcat, "end_effector_position_target", "end_effector_force_target", + "lcs_force_trajectory"); + builder.Connect(trajectory_sub_actor->get_output_port(), + end_effector_force_drawer->get_input_port_actor_trajectory()); + builder.Connect(trajectory_sub_force->get_output_port(), + end_effector_force_drawer->get_input_port_force_trajectory()); + builder.Connect(robot_time_passthrough->get_output_port(), + end_effector_force_drawer->get_input_port_robot_time()); + } builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); - builder.Connect(trajectory_sub_actor->get_output_port(), - trajectory_drawer_actor->get_input_port_trajectory()); - builder.Connect(trajectory_sub_object->get_output_port(), - trajectory_drawer_object->get_input_port_trajectory()); - builder.Connect(trajectory_sub_object->get_output_port(), - object_pose_drawer->get_input_port_trajectory()); - builder.Connect(trajectory_sub_actor->get_output_port(), - end_effector_pose_drawer->get_input_port_trajectory()); - builder.Connect(trajectory_sub_actor->get_output_port(), - end_effector_force_drawer->get_input_port_actor_trajectory()); - builder.Connect(trajectory_sub_force->get_output_port(), - end_effector_force_drawer->get_input_port_force_trajectory()); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(*franka_state_receiver, *franka_passthrough); builder.Connect(*franka_state_receiver, *robot_time_passthrough); - builder.Connect(robot_time_passthrough->get_output_port(), - end_effector_force_drawer->get_input_port_robot_time()); builder.Connect(*tray_state_receiver, *tray_passthrough); - builder.Connect(*franka_state_sub, *franka_state_receiver); builder.Connect(*tray_state_sub, *tray_state_receiver); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 803e5307f5..0d29498dff 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -16,7 +16,7 @@ left_support_position: [0.8, 0.15, 0.455] right_support_position: [0.8, -0.15, 0.455] end_effector_thickness: 0.016 -scene_index: 0 +scene_index: 1 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 51e9360916..1509e09648 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -21,7 +21,7 @@ struct FrankaSimParams { double visualizer_publish_rate; int scene_index; - bool visualize; + bool visualize_drake_sim; bool publish_efforts; Eigen::VectorXd camera_pose; @@ -34,6 +34,11 @@ struct FrankaSimParams { Eigen::VectorXd left_support_position; Eigen::VectorXd right_support_position; + bool visualize_pose_trace; + bool visualize_center_of_mass_plan; + bool visualize_c3_forces; + bool visualize_c3_state; + template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(franka_model)); @@ -53,7 +58,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(visualizer_publish_rate)); a->Visit(DRAKE_NVP(scene_index)); - a->Visit(DRAKE_NVP(visualize)); + a->Visit(DRAKE_NVP(visualize_drake_sim)); a->Visit(DRAKE_NVP(publish_efforts)); a->Visit(DRAKE_NVP(camera_pose)); @@ -65,5 +70,10 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); + + a->Visit(DRAKE_NVP(visualize_pose_trace)); + a->Visit(DRAKE_NVP(visualize_center_of_mass_plan)); + a->Visit(DRAKE_NVP(visualize_c3_forces)); + a->Visit(DRAKE_NVP(visualize_c3_state)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index d5485c22dd..e9ef7e9664 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,12 +8,12 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 1000 -visualizer_publish_rate: 15 +tray_publish_rate: 10 +visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 0 -visualize: true +scene_index: 1 +visualize_drake_sim: true publish_efforts: true camera_pose: [0.5, -1.5, 0.7] @@ -32,3 +32,8 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.7, 0.00, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] + +visualize_pose_trace: true +visualize_center_of_mass_plan: false +visualize_c3_forces: true +visualize_c3_state: true diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 91f13362fa..eb9edc2d72 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -2,11 +2,14 @@ #include +#include + #include "common/eigen_utils.h" #include "common/find_resource.h" #include "dairlib/lcmt_c3_forces.hpp" #include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "drake/common/schema/rotation.h" #include "drake/geometry/rgba.h" namespace dairlib { @@ -302,18 +305,21 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } - if (discrete_state->get_value(actor_last_update_time_index_)[0] >= - context.get_time()) { - return drake::systems::EventStatus::Succeeded(); - } - discrete_state->get_mutable_value(actor_last_update_time_index_)[0] = - context.get_time(); const auto& lcmt_traj = this->EvalInputValue( context, actor_trajectory_input_port_); + + // Don't needlessly update + if (discrete_state->get_value(actor_last_update_time_index_)[0] == + lcmt_traj->utime * 1e-6) { + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(actor_last_update_time_index_)[0] = + lcmt_traj->utime * 1e-6; const auto& robot_time_vec = this->EvalVectorInput(context, robot_time_input_port_); double robot_time = robot_time_vec->GetAtIndex(0); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); const auto& force_trajectory_block = lcm_traj.GetTrajectory(force_trajectory_name_); @@ -374,15 +380,17 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( ->utime < 1e-3) { return drake::systems::EventStatus::Succeeded(); } - if (discrete_state->get_value(forces_last_update_time_index_)[0] >= - context.get_time()) { + const auto& c3_forces = this->EvalInputValue( + context, force_trajectory_input_port_); + + // Don't needlessly update + if (discrete_state->get_value(forces_last_update_time_index_)[0] == + c3_forces->utime * 1e-6) { return drake::systems::EventStatus::Succeeded(); } discrete_state->get_mutable_value(forces_last_update_time_index_)[0] = - context.get_time(); + c3_forces->utime * 1e-6; - const auto& c3_forces = this->EvalInputValue( - context, force_trajectory_input_port_); for (int i = 0; i < c3_forces->num_forces; ++i) { const VectorXd force = Eigen::Map( c3_forces->forces[i].contact_force, 3); @@ -428,5 +436,137 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( return drake::systems::EventStatus::Succeeded(); } +LcmC3TargetDrawer::LcmC3TargetDrawer( + const std::shared_ptr& meshcat, bool draw_tray, + bool draw_ee) + : meshcat_(meshcat), draw_tray_(draw_tray), draw_ee_(draw_ee) { + this->set_name("LcmC3TargetDrawer"); + c3_state_target_input_port_ = + this->DeclareAbstractInputPort("lcmt_c3_state: target", + drake::Value{}) + .get_index(); + + c3_state_actual_input_port_ = + this->DeclareAbstractInputPort("lcmt_c3_state: actual", + drake::Value{}) + .get_index(); + last_update_time_index_ = this->DeclareDiscreteState(1); + + meshcat_->SetProperty(c3_state_path_, "visible", true, 0); + + // TODO(yangwill): Clean up all this visualization, move to separate + // visualization directory1 + meshcat_->SetObject(c3_target_tray_path_ + "/x-axis", cylinder_for_tray_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_target_tray_path_ + "/y-axis", cylinder_for_tray_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_target_tray_path_ + "/z-axis", cylinder_for_tray_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_actual_tray_path_ + "/x-axis", cylinder_for_tray_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_actual_tray_path_ + "/y-axis", cylinder_for_tray_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_actual_tray_path_ + "/z-axis", cylinder_for_tray_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, + {0, 0, 1, 1}); + auto x_axis_transform = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), + Vector3d{0.075, 0.0, 0.0}); + auto y_axis_transform = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), + Vector3d{0.0, 0.075, 0.0}); + auto z_axis_transform = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), + Vector3d{0.0, 0.0, 0.075}); + auto x_axis_transform_ee = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), + 0.5 * Vector3d{0.075, 0.0, 0.0}); + auto y_axis_transform_ee = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), + 0.5 * Vector3d{0.0, 0.075, 0.0}); + auto z_axis_transform_ee = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), + 0.5 * Vector3d{0.0, 0.0, 0.075}); + meshcat_->SetTransform(c3_target_tray_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_target_tray_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_target_tray_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_actual_tray_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_actual_tray_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_actual_tray_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); + + DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); +} + +drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue(context, + c3_state_target_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + if (this->EvalInputValue(context, + c3_state_actual_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + if (discrete_state->get_value(last_update_time_index_)[0] >= + context.get_time()) { + // no need to update if simulation has not advanced + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(last_update_time_index_)[0] = + context.get_time(); + const auto& c3_target = this->EvalInputValue( + context, c3_state_target_input_port_); + const auto& c3_actual = this->EvalInputValue( + context, c3_state_actual_input_port_); + if (draw_tray_) { + meshcat_->SetTransform( + c3_target_tray_path_, + RigidTransformd( + Eigen::Quaterniond(c3_target->state[3], c3_target->state[4], + c3_target->state[5], c3_target->state[6]), + Vector3d{c3_target->state[7], c3_target->state[8], + c3_target->state[9]})); + meshcat_->SetTransform( + c3_actual_tray_path_, + RigidTransformd( + Eigen::Quaterniond(c3_actual->state[3], c3_actual->state[4], + c3_actual->state[5], c3_actual->state[6]), + Vector3d{c3_actual->state[7], c3_actual->state[8], + c3_actual->state[9]})); + } + if (draw_ee_) { + meshcat_->SetTransform( + c3_target_ee_path_, + RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], + c3_target->state[2]})); + + meshcat_->SetTransform( + c3_actual_ee_path_, + RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], + c3_actual->state[2]})); + } + return drake::systems::EventStatus::Succeeded(); +} + } // namespace systems } // namespace dairlib diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 8c3c561a7e..a3dd94b2ba 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -182,5 +182,50 @@ class LcmForceDrawer : public drake::systems::LeafSystem { const double newtons_per_meter_ = 10; }; +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws it through meshcat. +class LcmC3TargetDrawer : public drake::systems::LeafSystem { + public: + explicit LcmC3TargetDrawer(const std::shared_ptr&, + bool draw_tray = true, + bool draw_ee = false); + + const drake::systems::InputPort& get_input_port_c3_state_target() const { + return this->get_input_port(c3_state_target_input_port_); + } + + const drake::systems::InputPort& get_input_port_c3_state_actual() const { + return this->get_input_port(c3_state_actual_input_port_); + } + + private: + drake::systems::EventStatus DrawC3State( + const drake::systems::Context &context, + drake::systems::DiscreteValues *discrete_state) const; + + std::shared_ptr meshcat_; + + drake::systems::InputPortIndex c3_state_target_input_port_; + drake::systems::InputPortIndex c3_state_actual_input_port_; + + bool draw_tray_; + bool draw_ee_; + + drake::systems::DiscreteStateIndex last_update_time_index_; + + const drake::geometry::Cylinder cylinder_for_tray_ = drake::geometry::Cylinder(0.005, 0.15); + const drake::geometry::Cylinder cylinder_for_ee_ = drake::geometry::Cylinder(0.0025, 0.075); + drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + const std::string c3_state_path_ = "c3_state"; + const std::string c3_target_tray_path_ = "c3_state/c3_target_tray"; + const std::string c3_actual_tray_path_ = "c3_state/c3_actual_tray"; + const std::string c3_target_ee_path_ = "c3_state/c3_target_ee"; + const std::string c3_actual_ee_path_ = "c3_state/c3_actual_ee"; + +// const double radius_ = 0.002; +// const double newtons_per_meter_ = 10; +}; + + } // namespace systems } // namespace dairlib From 6d18c3f420c8c3f3909707580c95fa9b14ff2082 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 16 Jan 2024 13:50:59 -0500 Subject: [PATCH 606/758] minor adjustments --- examples/franka/parameters/franka_sim_params.yaml | 4 ++-- examples/franka/systems/end_effector_trajectory.cc | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index e9ef7e9664..b4e0002788 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -16,7 +16,7 @@ scene_index: 1 visualize_drake_sim: true publish_efforts: true -camera_pose: [0.5, -1.5, 0.7] +camera_pose: [0.5, -1.2, 0.7] camera_target: [0.5, 0, 0.5] tool_attachment_frame: [0, 0, 0.107] @@ -33,7 +33,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] -visualize_pose_trace: true +visualize_pose_trace: false visualize_center_of_mass_plan: false visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 79ee442aed..6aca6eb75b 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -91,7 +91,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { - if ((context.get_time() - trajectory_input.start_time()) < 0.15){ + if ((context.get_time() - trajectory_input.start_time()) < 0.14){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } From 806f067a1c73d6d14e3e6d6789a03993130c60a1 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 16 Jan 2024 16:40:35 -0500 Subject: [PATCH 607/758] parameters to reflect new support position --- examples/franka/parameters/franka_c3_controller_params.yaml | 4 ++-- examples/franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 4 ++-- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 0d29498dff..c6b15ccdfd 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -12,8 +12,8 @@ left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.455] -right_support_position: [0.8, -0.15, 0.455] +left_support_position: [0.8, 0.15, 0.453] +right_support_position: [0.8, -0.15, 0.453] end_effector_thickness: 0.016 scene_index: 1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2140bf9708..fcd7090eab 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b4e0002788..ab95d060d1 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -20,8 +20,8 @@ camera_pose: [0.5, -1.2, 0.7] camera_target: [0.5, 0, 0.5] tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.455] -right_support_position: [0.8, -0.15, 0.455] +left_support_position: [0.8, 0.15, 0.453] +right_support_position: [0.8, -0.15, 0.453] dt: 0.0005 realtime_rate: 1.0 From dccb1d317bcb93779364a163e8ac1916c6a9c15e Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 17 Jan 2024 13:07:16 -0500 Subject: [PATCH 608/758] visualization changes --- examples/franka/franka_sim.cc | 3 +- examples/franka/franka_visualizer.cc | 14 +++++- .../franka_c3_controller_params.yaml | 4 +- .../franka_c3_options_translation.yaml | 4 +- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 10 ++++ .../franka/parameters/franka_sim_params.yaml | 14 ++++++ examples/franka/urdf/tray_lcs.sdf | 47 ++++++++----------- .../lcm_trajectory_systems.cc | 10 ++-- .../lcm_trajectory_systems.h | 2 +- 10 files changed, 69 insertions(+), 41 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 2aad133d4b..317f7278f5 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -107,12 +107,13 @@ int DoMain(int argc, char* argv[]) { &plant.GetBodyByName("support", left_support_index), &plant.GetBodyByName("support", right_support_index), }); + // we WANT to model collisions between link5 and the supports const drake::geometry::GeometrySet& paddle_geom_set = plant.CollectRegisteredGeometries( {&plant.GetBodyByName("panda_link2"), &plant.GetBodyByName("panda_link3"), &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), +// &plant.GetBodyByName("panda_link5"), &plant.GetBodyByName("panda_link6"), &plant.GetBodyByName("panda_link7"), &plant.GetBodyByName("plate"), diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index f835f19131..242feabab9 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -177,6 +177,18 @@ int do_main(int argc, char* argv[]) { &builder, scene_graph, meshcat, std::move(params)); meshcat->SetCameraPose(sim_params.camera_pose, sim_params.camera_target); + + if (sim_params.visualize_workspace){ + double width = sim_params.world_x_limits[1] - sim_params.world_x_limits[0]; + double depth = sim_params.world_y_limits[1] - sim_params.world_y_limits[0]; + double height = sim_params.world_z_limits[1] - sim_params.world_z_limits[0]; + Vector3d workspace_center = {0.5 * (sim_params.world_x_limits[1] + sim_params.world_x_limits[0]), + 0.5 * (sim_params.world_y_limits[1] + sim_params.world_y_limits[0]), + 0.5 * (sim_params.world_z_limits[1] + sim_params.world_z_limits[0])}; + meshcat->SetObject("c3_state/workspace", drake::geometry::Box(width, depth, height), + {1, 0, 0, 0.2}); + meshcat->SetTransform("c3_state/workspace", RigidTransformd(workspace_center)); + } if (sim_params.visualize_center_of_mass_plan){ auto trajectory_drawer_actor = builder.AddSystem( @@ -210,7 +222,7 @@ int do_main(int argc, char* argv[]) { if (sim_params.visualize_c3_state){ auto c3_target_drawer = - builder.AddSystem(meshcat, true, true); + builder.AddSystem(meshcat, true, false); builder.Connect(c3_state_actual_sub->get_output_port(), c3_target_drawer->get_input_port_c3_state_actual()); builder.Connect(c3_state_target_sub->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index c6b15ccdfd..9501307c88 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -24,11 +24,11 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], - [0.45, 0, 0.488]] + [0.45, 0, 0.485]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.7, 0.00, 0.488]] + [0.7, 0.00, 0.49]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 0904e574a5..370ca7bd1b 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -14,8 +14,8 @@ solve_time_filter_alpha: 0.9 # Workspace Limits world_x_limits: [0.4, 0.6] -world_y_limits: [-0.1, 0.1] -world_z_limits: [0.35, 0.7] +world_y_limits: [-0.15, 0.15] +world_z_limits: [0.3, 0.6] u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index fcd7090eab..2140bf9708 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 1509e09648..b5cdb5cf15 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -34,10 +34,15 @@ struct FrankaSimParams { Eigen::VectorXd left_support_position; Eigen::VectorXd right_support_position; + std::vector world_x_limits; + std::vector world_y_limits; + std::vector world_z_limits; + bool visualize_pose_trace; bool visualize_center_of_mass_plan; bool visualize_c3_forces; bool visualize_c3_state; + bool visualize_workspace; template void Serialize(Archive* a) { @@ -71,9 +76,14 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); + a->Visit(DRAKE_NVP(world_x_limits)); + a->Visit(DRAKE_NVP(world_y_limits)); + a->Visit(DRAKE_NVP(world_z_limits)); + a->Visit(DRAKE_NVP(visualize_pose_trace)); a->Visit(DRAKE_NVP(visualize_center_of_mass_plan)); a->Visit(DRAKE_NVP(visualize_c3_forces)); a->Visit(DRAKE_NVP(visualize_c3_state)); + a->Visit(DRAKE_NVP(visualize_workspace)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index ab95d060d1..11d43ef365 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -19,10 +19,23 @@ publish_efforts: true camera_pose: [0.5, -1.2, 0.7] camera_target: [0.5, 0, 0.5] +#camera_pose: [0.5, -0.8, 0.6] +#camera_target: [0.5, 0, 0.5] + tool_attachment_frame: [0, 0, 0.107] left_support_position: [0.8, 0.15, 0.453] right_support_position: [0.8, -0.15, 0.453] +# Workspace Limits +#world_x_limits: [0.4, 0.6] +#world_y_limits: [-0.15, 0.15] +#world_z_limits: [0.3, 0.6] + +# Workspace Limits +world_x_limits: [0.4, 0.6] +world_y_limits: [-0.1, 0.1] +world_z_limits: [0.35, 0.7] + dt: 0.0005 realtime_rate: 1.0 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] @@ -33,6 +46,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] +visualize_workspace: true visualize_pose_trace: false visualize_center_of_mass_plan: false visualize_c3_forces: true diff --git a/examples/franka/urdf/tray_lcs.sdf b/examples/franka/urdf/tray_lcs.sdf index 229af25b94..511cbf0a36 100644 --- a/examples/franka/urdf/tray_lcs.sdf +++ b/examples/franka/urdf/tray_lcs.sdf @@ -3,47 +3,38 @@ - 0.05 0 0 0 0 0 - 2 + 0 0 0 0 0 0 + 0.97 - 0.12 + 0.012712 0 0 - 0.040001 + 0.012712 0 - 0.16 + 0.025345 + 0 0 0.0 0 0 0 - - 0.3 0.6 0.02 - + + 0.2286 + 0.022 + + + 0.1 0.1 0.1 0.8 + - + + 0 0 0.0 0 0 0 - - 0.001 - - - -0.15 0 0 0 0 0 - - - - - 0.001 - - - 0.15 -0.3 0 0 0 0 - - - - - 0.001 - + + 0.2286 + 0.022 + 0.15 0.3 0 0 0 0 diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index eb9edc2d72..9ccb33e2b1 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -351,7 +351,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( meshcat_->SetTransform( force_arrow_path, RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); - const double height = force_norm / newtons_per_meter_ / 10; + const double height = force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); // Note: Meshcat does not fully support non-uniform scaling (see #18095). @@ -560,10 +560,10 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], c3_target->state[2]})); - meshcat_->SetTransform( - c3_actual_ee_path_, - RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], - c3_actual->state[2]})); +// meshcat_->SetTransform( +// c3_actual_ee_path_, +// RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], +// c3_actual->state[2]})); } return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index a3dd94b2ba..80d26c477c 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -179,7 +179,7 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); int N_ = 5; const double radius_ = 0.002; - const double newtons_per_meter_ = 10; + const double newtons_per_meter_ = 20; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, From 6ec0a55b1b732fa9820b8e4c1c11ff32c06d9890 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 17 Jan 2024 18:00:10 -0500 Subject: [PATCH 609/758] adding options to use different support orientation/placement --- examples/franka/franka_c3_controller.cc | 6 +++--- examples/franka/franka_sim.cc | 4 ++-- examples/franka/franka_visualizer.cc | 6 +++--- .../parameters/franka_c3_controller_params.h | 7 +++++-- .../parameters/franka_c3_controller_params.yaml | 15 ++++++++++++--- .../parameters/franka_c3_options_translation.yaml | 1 + .../parameters/franka_c3_options_w_supports.yaml | 7 +++++-- examples/franka/parameters/franka_sim_params.h | 4 ++++ examples/franka/parameters/franka_sim_params.yaml | 13 +++++++++++++ .../franka/systems/end_effector_trajectory.cc | 2 +- examples/franka/systems/plate_balancing_target.cc | 3 +++ solvers/c3_options.h | 2 ++ systems/controllers/c3_controller.cc | 12 ++++++------ 13 files changed, 60 insertions(+), 22 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 4de1a2b08c..df4a6de0a2 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -114,16 +114,16 @@ int DoMain(int argc, char* argv[]) { drake::multibody::ModelInstanceIndex left_support_index; drake::multibody::ModelInstanceIndex right_support_index; - if (controller_params.scene_index == 1) { + if (controller_params.scene_index > 0) { left_support_index = parser_plate.AddModels( FindResourceOrThrow(controller_params.left_support_model))[0]; right_support_index = parser_plate.AddModels( FindResourceOrThrow(controller_params.right_support_model))[0]; RigidTransform T_S1_W = - RigidTransform(drake::math::RotationMatrix(), + RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), controller_params.left_support_position); RigidTransform T_S2_W = - RigidTransform(drake::math::RotationMatrix(), + RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), controller_params.right_support_position); plant_for_lcs.WeldFrames( plant_for_lcs.world_frame(), diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 317f7278f5..92aaa04476 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -93,9 +93,9 @@ int DoMain(int argc, char* argv[]) { drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( FindResourceOrThrow(sim_params.right_support_model))[0]; RigidTransform T_S1_W = RigidTransform( - drake::math::RotationMatrix(), sim_params.left_support_position); + drake::math::RollPitchYaw(sim_params.left_support_orientation), sim_params.left_support_position); RigidTransform T_S2_W = RigidTransform( - drake::math::RotationMatrix(), sim_params.right_support_position); + drake::math::RollPitchYaw(sim_params.right_support_orientation), sim_params.right_support_position); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_S1_W); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 242feabab9..e1d20b6248 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -104,10 +104,10 @@ int do_main(int argc, char* argv[]) { drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( FindResourceOrThrow(sim_params.right_support_model))[0]; RigidTransform T_S1_W = - RigidTransform(drake::math::RotationMatrix(), + RigidTransform(drake::math::RollPitchYaw(sim_params.left_support_orientation), sim_params.left_support_position); RigidTransform T_S2_W = - RigidTransform(drake::math::RotationMatrix(), + RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), sim_params.right_support_position); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), @@ -222,7 +222,7 @@ int do_main(int argc, char* argv[]) { if (sim_params.visualize_c3_state){ auto c3_target_drawer = - builder.AddSystem(meshcat, true, false); + builder.AddSystem(meshcat, true, true); builder.Connect(c3_state_actual_sub->get_output_port(), c3_target_drawer->get_input_port_c3_state_actual()); builder.Connect(c3_state_target_sub->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 685d04a32e..74f3292740 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -18,12 +18,13 @@ struct FrankaC3ControllerParams { Eigen::Vector3d tool_attachment_frame; Eigen::Vector3d left_support_position; Eigen::Vector3d right_support_position; + Eigen::Vector3d left_support_orientation; + Eigen::Vector3d right_support_orientation; + double workspace_margin; double end_effector_thickness; int scene_index; - - bool include_end_effector_orientation; double target_frequency; @@ -62,6 +63,8 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); + a->Visit(DRAKE_NVP(left_support_orientation)); + a->Visit(DRAKE_NVP(right_support_orientation)); a->Visit(DRAKE_NVP(end_effector_thickness)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 9501307c88..21aed55e7f 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -14,6 +14,12 @@ right_support_model: examples/franka/urdf/left_support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] left_support_position: [0.8, 0.15, 0.453] right_support_position: [0.8, -0.15, 0.453] +left_support_orientation: [0.0, 0.0, 0.0] +right_support_orientation: [0.0, 0.0, 0.0] +#left_support_position: [0.4, 0.275, 0.453] +#right_support_position: [0.7, 0.275, 0.453] +#left_support_orientation: [0.0, 0.0, 1.57] +#right_support_orientation: [0.0, 0.0, 1.57] end_effector_thickness: 0.016 scene_index: 1 @@ -24,11 +30,14 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], - [0.45, 0, 0.485]] + [0.45, 0, 0.485], + [0.55, -0.15, 0.485]] second_target: [[0.45, 0.0, 0.5], - [0.45, 0, 0.6]] + [0.45, 0, 0.6], + [0.55, -0.15, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.7, 0.00, 0.49]] + [0.7, 0.00, 0.49], + [0.55, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 370ca7bd1b..8532da9892 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -16,6 +16,7 @@ solve_time_filter_alpha: 0.9 world_x_limits: [0.4, 0.6] world_y_limits: [-0.15, 0.15] world_z_limits: [0.3, 0.6] +workspace_margins: 0.05 u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 8c4a047354..414cf70156 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -15,7 +15,10 @@ solve_time_filter_alpha: 0.9 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} # Workspace Limits world_x_limits: [0.4, 0.6] world_y_limits: [-0.1, 0.1] +#world_x_limits: [0.45, 0.65] +#world_y_limits: [-0.2, 0.05] world_z_limits: [0.35, 0.7] +workspace_margins: 0.05 u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] @@ -38,7 +41,7 @@ w_U: 0.1 # State Tracking Error, assuming diagonal q_vector: [150, 150, 100, 0, 1, 1, 0, 15000, 15000, 15000, - 5, 5, 10, 1, 100, 1, 5, 5, 5] + 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] @@ -50,7 +53,7 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -u_x: [0.1, 0.1, 0.1, 10, 10, 10, 10, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [0.1, 0.1, 0.1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index b5cdb5cf15..f254203813 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -33,6 +33,8 @@ struct FrankaSimParams { Eigen::VectorXd tool_attachment_frame; Eigen::VectorXd left_support_position; Eigen::VectorXd right_support_position; + Eigen::VectorXd left_support_orientation; + Eigen::VectorXd right_support_orientation; std::vector world_x_limits; std::vector world_y_limits; @@ -75,6 +77,8 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); + a->Visit(DRAKE_NVP(left_support_orientation)); + a->Visit(DRAKE_NVP(right_support_orientation)); a->Visit(DRAKE_NVP(world_x_limits)); a->Visit(DRAKE_NVP(world_y_limits)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 11d43ef365..8c5abbd140 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -16,6 +16,9 @@ scene_index: 1 visualize_drake_sim: true publish_efforts: true +#camera_pose: [1.5, 0, 0.5] +#camera_target: [0.5, 0, 0.45] + camera_pose: [0.5, -1.2, 0.7] camera_target: [0.5, 0, 0.5] @@ -25,6 +28,13 @@ camera_target: [0.5, 0, 0.5] tool_attachment_frame: [0, 0, 0.107] left_support_position: [0.8, 0.15, 0.453] right_support_position: [0.8, -0.15, 0.453] +left_support_orientation: [0.0, 0.0, 0.0] +right_support_orientation: [0.0, 0.0, 0.0] + +#left_support_position: [0.4, 0.275, 0.453] +#right_support_position: [0.7, 0.275, 0.453] +#left_support_orientation: [0.0, 0.0, 1.57] +#right_support_orientation: [0.0, 0.0, 1.57] # Workspace Limits #world_x_limits: [0.4, 0.6] @@ -34,6 +44,8 @@ right_support_position: [0.8, -0.15, 0.453] # Workspace Limits world_x_limits: [0.4, 0.6] world_y_limits: [-0.1, 0.1] +#world_x_limits: [0.45, 0.65] +#world_y_limits: [-0.15, 0.05] world_z_limits: [0.35, 0.7] dt: 0.0005 @@ -43,6 +55,7 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.7, 0.00, 0.515]] +# [1, 0, 0, 0, 0.55, 0.15, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 6aca6eb75b..8659a17919 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -91,7 +91,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { - if ((context.get_time() - trajectory_input.start_time()) < 0.14){ + if ((context.get_time() - trajectory_input.start_time()) < 0.13){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index f9ae9d7248..48d9e3e774 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -130,6 +130,9 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( if (end_effector_position[0] > 0.6) { end_effector_position[0] = 0.6; // keep it within the workspace } + if (end_effector_position[1] > 0.05) { + end_effector_position[1] = 0.05; // keep it within the workspace + } if (radio_out->channel[13] > 0) { end_effector_position(0) += radio_out->channel[0] * x_scale_; end_effector_position(1) += radio_out->channel[1] * y_scale_; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index e41130e65b..71c895421f 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -21,6 +21,7 @@ struct C3Options { std::vector world_z_limits; std::vector u_horizontal_limits; std::vector u_vertical_limits; + double workspace_margins; int N; double gamma; @@ -78,6 +79,7 @@ struct C3Options { a->Visit(DRAKE_NVP(world_z_limits)); a->Visit(DRAKE_NVP(u_horizontal_limits)); a->Visit(DRAKE_NVP(u_vertical_limits)); + a->Visit(DRAKE_NVP(workspace_margins)); a->Visit(DRAKE_NVP(mu)); a->Visit(DRAKE_NVP(dt)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index ba5ef9bc28..ae944c4cdd 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -184,12 +184,12 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector(N_ + 1, x_des.value()); // Force Checking of Workspace Limits - DRAKE_DEMAND(lcs_x->get_data()[0] > 0.35); - DRAKE_DEMAND(lcs_x->get_data()[0] < 0.65); - DRAKE_DEMAND(lcs_x->get_data()[1] > -0.1); - DRAKE_DEMAND(lcs_x->get_data()[1] < 0.1); - DRAKE_DEMAND(lcs_x->get_data()[2] > 0.35); - DRAKE_DEMAND(lcs_x->get_data()[2] < 0.7); + DRAKE_DEMAND(lcs_x->get_data()[0] > c3_options_.world_x_limits[0] - c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[0] < c3_options_.world_x_limits[1] + c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[1] > c3_options_.world_y_limits[0] - c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[1] < c3_options_.world_y_limits[1] + c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[2] > c3_options_.world_z_limits[0] - c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[2] < c3_options_.world_z_limits[1] + c3_options_.workspace_margins); c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); From 11ad8b3bd06989749829b75b9cf3a7fd9ac2cbf6 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 17 Jan 2024 19:35:16 -0500 Subject: [PATCH 610/758] updating plot configs --- .../pydairlib/analysis/log_plotter_franka.py | 7 ++- .../plot_configs/franka_sim_plot_config.yaml | 43 +++++++++++++++++++ .../plot_configs/franka_translation_plot.yaml | 15 +++---- 3 files changed, 56 insertions(+), 9 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index bb398d0a34..80ce734c2e 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -14,8 +14,10 @@ def main(): + # config_file = ('bindings/pydairlib/analysis/plot_configs' + # '/franka_translation_plot.yaml') config_file = ('bindings/pydairlib/analysis/plot_configs' - '/franka_translation_plot.yaml') + '/franka_sim_plot_config.yaml') plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x @@ -100,6 +102,9 @@ def main(): t_c3_slice = slice(c3_output['t'].size) mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 0) + t_c3_slice = slice(c3_output['t'].size) + mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1) + t_c3_slice = slice(c3_output['t'].size) mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml new file mode 100644 index 0000000000..1310921dff --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml @@ -0,0 +1,43 @@ +# LCM channels to read data from +channel_x: "FRANKA_STATE_SIMULATION" +channel_u: "OSC_FRANKA" +channel_osc: "OSC_DEBUG_FRANKA" +channel_c3: "C3_DEBUG" +channel_tray: "TRAY_STATE_SIMULATION" +channel_c3_target: "C3_TARGET" +channel_c3_actual: "C3_ACTUAL" +plot_style: 'compact' # compact, paper, default + +start_time: 0 +#duration: 0.47 +duration: -1 +# Plant properties + +# Desired RobotOutput plots +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +plot_commanded_efforts: false +plot_contact_forces: false +plot_end_effector: true + +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Finite State Machine Names +fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] + +# Desired osc plots +plot_qp_costs: false +plot_qp_solve_time: true +plot_qp_solutions: true +plot_tracking_costs: false +plot_active_tracking_datas: false +tracking_datas_to_plot: + end_effector_target: {'dims': [0], 'derivs': ['accel']} +# end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} +# end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +plot_c3_debug: true +plot_c3_tracking: true +plot_object_state: true \ No newline at end of file diff --git a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml index 7e7f36911a..14ac9156b6 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_translation_plot.yaml @@ -8,17 +8,16 @@ channel_c3_target: "C3_TARGET" channel_c3_actual: "C3_ACTUAL" plot_style: 'compact' # compact, paper, default -start_time: 15 +start_time: 0 #duration: 0.47 -duration: 10 - +duration: -1 # Plant properties # Desired RobotOutput plots -plot_joint_positions: true -plot_joint_velocities: true -plot_measured_efforts: true -plot_commanded_efforts: true +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +plot_commanded_efforts: false plot_contact_forces: false plot_end_effector: true @@ -36,7 +35,7 @@ plot_qp_solutions: true plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos']} + end_effector_target: {'dims': [0], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} plot_c3_debug: true From 319a5d46584d6ab8dce656dcc21135b717d50033 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 18 Jan 2024 12:06:42 -0500 Subject: [PATCH 611/758] tuned side supports scenario in sim --- examples/franka/franka_c3_controller.cc | 2 +- examples/franka/franka_sim.cc | 2 +- examples/franka/franka_visualizer.cc | 3 +- .../franka_c3_controller_params.yaml | 27 +++++---- .../franka_c3_options_side_supports.yaml | 59 +++++++++++++++++++ .../franka_c3_options_translation.yaml | 4 +- .../franka_c3_options_w_supports.yaml | 2 - .../franka/parameters/franka_sim_params.yaml | 48 +++++++-------- .../franka/systems/end_effector_trajectory.cc | 2 +- .../franka/systems/plate_balancing_target.cc | 12 +++- 10 files changed, 112 insertions(+), 49 deletions(-) create mode 100644 examples/franka/parameters/franka_c3_options_side_supports.yaml diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index df4a6de0a2..4860547be3 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -151,7 +151,7 @@ int DoMain(int argc, char* argv[]) { std::vector plate_contact_points = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("plate")); - if (controller_params.scene_index == 1) { + if (controller_params.scene_index > 0) { std::vector left_support_contact_points = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("support", left_support_index)); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 92aaa04476..cb9c7f0e33 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -87,7 +87,7 @@ int DoMain(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); - if (sim_params.scene_index == 1) { + if (sim_params.scene_index > 0) { drake::multibody::ModelInstanceIndex left_support_index = parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index e1d20b6248..9a5ac02bb9 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -98,7 +98,7 @@ int do_main(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); - if (sim_params.scene_index == 1) { + if (sim_params.scene_index > 0) { drake::multibody::ModelInstanceIndex left_support_index = parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( @@ -177,7 +177,6 @@ int do_main(int argc, char* argv[]) { &builder, scene_graph, meshcat, std::move(params)); meshcat->SetCameraPose(sim_params.camera_pose, sim_params.camera_target); - if (sim_params.visualize_workspace){ double width = sim_params.world_x_limits[1] - sim_params.world_x_limits[0]; double depth = sim_params.world_y_limits[1] - sim_params.world_y_limits[0]; diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 21aed55e7f..b63382bed4 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,6 +1,7 @@ c3_options_file: [examples/franka/parameters/franka_c3_options_translation.yaml, - examples/franka/parameters/franka_c3_options_w_supports.yaml] + examples/franka/parameters/franka_c3_options_w_supports.yaml, + examples/franka/parameters/franka_c3_options_side_supports.yaml] osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf @@ -12,17 +13,17 @@ left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.453] -right_support_position: [0.8, -0.15, 0.453] -left_support_orientation: [0.0, 0.0, 0.0] -right_support_orientation: [0.0, 0.0, 0.0] -#left_support_position: [0.4, 0.275, 0.453] -#right_support_position: [0.7, 0.275, 0.453] -#left_support_orientation: [0.0, 0.0, 1.57] -#right_support_orientation: [0.0, 0.0, 1.57] +#left_support_position: [0.8, 0.15, 0.453] +#right_support_position: [0.8, -0.15, 0.453] +#left_support_orientation: [0.0, 0.0, 0.0] +#right_support_orientation: [0.0, 0.0, 0.0] +left_support_position: [0.4, 0.25, 0.452] +right_support_position: [0.7, 0.25, 0.452] +left_support_orientation: [0.0, 0.0, 1.57] +right_support_orientation: [0.0, 0.0, 1.57] end_effector_thickness: 0.016 -scene_index: 1 +scene_index: 2 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan @@ -31,12 +32,12 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.15, 0.485]] + [0.55, -0.1, 0.485]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], - [0.55, -0.15, 0.6]] + [0.55, -0.1, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.7, 0.00, 0.49], + [0.7, 0.00, 0.485], [0.55, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml new file mode 100644 index 0000000000..9fc27b909c --- /dev/null +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -0,0 +1,59 @@ +admm_iter: 2 +rho: 0 # does not do anything +rho_scale: 10 +num_threads: 5 +delta_option: 1 +# options are 'MIQP' or 'QP' +projection_type: 'MIQP' +# options are 'stewart_and_trinkle' or 'anitescu' +#contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' +warm_start: true +use_predicted_x0: true +solve_time_filter_alpha: 0.9 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} + +# Workspace Limits +world_x_limits: [0.45, 0.65] +world_y_limits: [-0.15, 0.05] +world_z_limits: [0.4, 0.7] +workspace_margins: 0.05 + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] + +mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] +dt: 0.075 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 7 +N: 5 +gamma: 1.0 # discount factor on MPC costs + +# matrix scaling +w_Q: 50 +w_R: 5 +# Penalty on all decision variables, assuming scalar +w_G: 0.1 +# Penalty on all decision variables, assuming scalar +w_U: 0.1 + +# State Tracking Error, assuming diagonal +q_vector: [150, 150, 100, 0, 1, 1, 0, 17500, 15000, 15000, + 5, 5, 10, 100, 1, 1, 5, 5, 5] +# Penalty on efforts, assuming diagonal +r_vector: [0.1, 0.1, 0.1] + +# Penalty on matching projected variables +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [1, 1, 1, 1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_u: [1, 1, 1] + +u_x: [0.1, 0.1, 0.1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_gamma: [1, 1, 1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75] +u_u: [30, 30, 30] diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 8532da9892..dcc877e3ba 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -6,8 +6,8 @@ delta_option: 1 # options are 'MIQP' or 'QP' projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' -contact_model: 'anitescu' -#contact_model: 'stewart_and_trinkle' +#contact_model: 'anitescu' +contact_model: 'stewart_and_trinkle' warm_start: true use_predicted_x0: false solve_time_filter_alpha: 0.9 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 414cf70156..db41d82c7d 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -15,8 +15,6 @@ solve_time_filter_alpha: 0.9 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} # Workspace Limits world_x_limits: [0.4, 0.6] world_y_limits: [-0.1, 0.1] -#world_x_limits: [0.45, 0.65] -#world_y_limits: [-0.2, 0.05] world_z_limits: [0.35, 0.7] workspace_margins: 0.05 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 8c5abbd140..b3ee989bdb 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,29 +12,29 @@ tray_publish_rate: 10 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 1 +scene_index: 2 visualize_drake_sim: true publish_efforts: true -#camera_pose: [1.5, 0, 0.5] -#camera_target: [0.5, 0, 0.45] - -camera_pose: [0.5, -1.2, 0.7] -camera_target: [0.5, 0, 0.5] +#camera_pose: [0.5, -1.2, 0.7] +#camera_target: [0.5, 0, 0.5] #camera_pose: [0.5, -0.8, 0.6] #camera_target: [0.5, 0, 0.5] +camera_pose: [1.5, 0, 0.6] +camera_target: [0.5, 0, 0.55] + tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.453] -right_support_position: [0.8, -0.15, 0.453] -left_support_orientation: [0.0, 0.0, 0.0] -right_support_orientation: [0.0, 0.0, 0.0] +#left_support_position: [0.8, 0.15, 0.453] +#right_support_position: [0.8, -0.15, 0.453] +#left_support_orientation: [0.0, 0.0, 0.0] +#right_support_orientation: [0.0, 0.0, 0.0] -#left_support_position: [0.4, 0.275, 0.453] -#right_support_position: [0.7, 0.275, 0.453] -#left_support_orientation: [0.0, 0.0, 1.57] -#right_support_orientation: [0.0, 0.0, 1.57] +left_support_position: [0.4, 0.25, 0.452] +right_support_position: [0.7, 0.25, 0.452] +left_support_orientation: [0.0, 0.0, 1.57] +right_support_orientation: [0.0, 0.0, 1.57] # Workspace Limits #world_x_limits: [0.4, 0.6] @@ -42,11 +42,11 @@ right_support_orientation: [0.0, 0.0, 0.0] #world_z_limits: [0.3, 0.6] # Workspace Limits -world_x_limits: [0.4, 0.6] -world_y_limits: [-0.1, 0.1] -#world_x_limits: [0.45, 0.65] -#world_y_limits: [-0.15, 0.05] -world_z_limits: [0.35, 0.7] +#world_x_limits: [0.4, 0.6] +#world_y_limits: [-0.1, 0.1] +world_x_limits: [0.45, 0.65] +world_y_limits: [-0.15, 0.05] +world_z_limits: [0.4, 0.7] dt: 0.0005 realtime_rate: 1.0 @@ -54,13 +54,13 @@ realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], - [1, 0, 0, 0, 0.7, 0.00, 0.515]] -# [1, 0, 0, 0, 0.55, 0.15, 0.515]] + [1, 0, 0, 0, 0.7, 0.00, 0.515], + [1, 0, 0, 0, 0.55, 0.125, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] visualize_workspace: true -visualize_pose_trace: false -visualize_center_of_mass_plan: false -visualize_c3_forces: true +visualize_pose_trace: true +visualize_center_of_mass_plan: true +visualize_c3_forces: false visualize_c3_state: true diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 8659a17919..b63dc83b01 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -91,7 +91,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { - if ((context.get_time() - trajectory_input.start_time()) < 0.13){ + if ((context.get_time() - trajectory_input.start_time()) < 0.075){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 48d9e3e774..29aa971d72 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -68,7 +68,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( discrete_state->get_mutable_value(within_target_index_)[0] = 1; } if (within_target == 1 && - (context.get_time() - time_entered_target) > 1.0) { + (context.get_time() - time_entered_target) > 0.5) { discrete_state->get_mutable_value(within_target_index_)[0] = 0; discrete_state->get_mutable_value(sequence_index_)[0] = 1; } @@ -138,6 +138,9 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( end_effector_position(1) += radio_out->channel[1] * y_scale_; end_effector_position(2) += radio_out->channel[2] * z_scale_; } +// end_effector_position(0) = 0.55; +// end_effector_position(1) = 0.1 * sin(3 * context.get_time()); +// end_effector_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()) - end_effector_thickness_; target->SetFromVector(end_effector_position); } @@ -150,14 +153,17 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( VectorXd tray_position = first_target_; if (context.get_discrete_state(sequence_index_)[0] == 1) { - tray_position = second_target_; // raise the tray once it is close + tray_position = second_target_; } else if (context.get_discrete_state(sequence_index_)[0] == 2 || context.get_discrete_state(sequence_index_)[0] == 3) { - tray_position = third_target_; // raise the tray once it is close + tray_position = third_target_; } tray_position(0) += radio_out->channel[0] * x_scale_; tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; +// tray_position(0) = 0.55; +// tray_position(1) = 0.1 * sin(3 * context.get_time()); +// tray_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()); target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat target->SetFromVector(target_tray_state); } From 378a4540007a4e59505062ccd487b239c1412224 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 18 Jan 2024 12:43:13 -0500 Subject: [PATCH 612/758] updating contact spheres to reflect end effector thickness --- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/urdf/plate_end_effector_translation.urdf | 6 +++--- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index b63382bed4..f5d6f7aa1f 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -32,7 +32,7 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.1, 0.485]] + [0.55, -0.1, 0.486]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.55, -0.1, 0.6]] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2140bf9708..fcd7090eab 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index c39762f21c..8f6f93e6e2 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -20,19 +20,19 @@ - + - + - + From a32f1242095f481d4d47683fb034ca694d00d153 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Jan 2024 14:29:07 -0500 Subject: [PATCH 613/758] limiting distance between predicted and measured initial state --- systems/controllers/c3_controller.cc | 13 +++++++++++-- 1 file changed, 11 insertions(+), 2 deletions(-) diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index ae944c4cdd..c5de8768b3 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -172,9 +172,18 @@ drake::systems::EventStatus C3Controller::ComputePlan( auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); drake::VectorX x_lcs = lcs_x->get_data(); + + // TODO(yangwill): clean this up if (c3_options_.use_predicted_x0 && !x_pred_.isZero()) { - x_lcs.head(3) = x_pred_.head(3); - x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); + x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, x_lcs[0] + 10 * dt_ * dt_); + x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, x_lcs[1] + 10 * dt_ * dt_); + x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 10 * dt_ * dt_, x_lcs[2] + 10 * dt_ * dt_); +// x_lcs.head(3) = x_pred_.head(3); + x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, x_lcs[n_q_ + 0] + 10 * dt_); + x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, x_lcs[n_q_ + 1] + 10 * dt_); + x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, x_lcs[n_q_ + 2] + 10 * dt_); +// x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); + } discrete_state->get_mutable_value(plan_start_time_index_)[0] = From b6e140e8f7efa0fd40a7e7d433cc1f13b2b31d9c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Jan 2024 14:48:12 -0500 Subject: [PATCH 614/758] refactoring lcm visualization systems --- examples/franka/BUILD.bazel | 1 + examples/franka/franka_visualizer.cc | 1 + .../lcm_trajectory_systems.cc | 440 ----------------- .../lcm_trajectory_systems.h | 162 ------ systems/visualization/BUILD.bazel | 21 + .../lcm_visualization_systems.cc | 466 ++++++++++++++++++ .../visualization/lcm_visualization_systems.h | 187 +++++++ 7 files changed, 676 insertions(+), 602 deletions(-) create mode 100644 systems/visualization/BUILD.bazel create mode 100644 systems/visualization/lcm_visualization_systems.cc create mode 100644 systems/visualization/lcm_visualization_systems.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index b4b0c2170d..2a7b99a3c9 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -102,6 +102,7 @@ cc_binary( "//systems:system_utils", "//systems/primitives", "//systems/trajectory_optimization:lcm_trajectory_systems", + "//systems/visualization:lcm_visualization_systems", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 9a5ac02bb9..e02ce8c1f7 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -19,6 +19,7 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/lcm_trajectory_systems.h" +#include "systems/visualization/lcm_visualization_systems.h" #include "drake/common/find_resource.h" #include "drake/common/yaml/yaml_io.h" diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 9ccb33e2b1..bc8e833308 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -2,11 +2,9 @@ #include -#include #include "common/eigen_utils.h" #include "common/find_resource.h" -#include "dairlib/lcmt_c3_forces.hpp" #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "drake/common/schema/rotation.h" @@ -130,443 +128,5 @@ void LcmOrientationTrajectoryReceiver::OutputTrajectory( } } -LcmTrajectoryDrawer::LcmTrajectoryDrawer( - const std::shared_ptr& meshcat, - std::string trajectory_name) - : meshcat_(meshcat), trajectory_name_(std::move(trajectory_name)) { - this->set_name("LcmTrajectoryDrawer: " + trajectory_name_); - trajectory_input_port_ = - this->DeclareAbstractInputPort( - "lcmt_timestamped_saved_traj", - drake::Value{}) - .get_index(); - - DeclarePerStepDiscreteUpdateEvent(&LcmTrajectoryDrawer::DrawTrajectory); -} - -drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( - const Context& context, - DiscreteValues* discrete_state) const { - if (this->EvalInputValue( - context, trajectory_input_port_) - ->utime < 1e-3) { - return drake::systems::EventStatus::Succeeded(); - } - const auto& lcmt_traj = - this->EvalInputValue( - context, trajectory_input_port_); - auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); - const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); - MatrixXd line_points = MatrixXd::Zero(3, N_); - VectorXd breaks = - VectorXd::LinSpaced(N_, trajectory_block.time_vector[0], - trajectory_block.time_vector.tail(1)[0]); - if (trajectory_block.datapoints.rows() == 3) { - auto trajectory = PiecewisePolynomial::FirstOrderHold( - trajectory_block.time_vector, trajectory_block.datapoints); - for (int i = 0; i < line_points.cols(); ++i) { - line_points.col(i) = trajectory.value(breaks(i)); - } - } else { - auto trajectory = PiecewisePolynomial::CubicHermite( - trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), - trajectory_block.datapoints.bottomRows(3)); - for (int i = 0; i < line_points.cols(); ++i) { - line_points.col(i) = trajectory.value(breaks(i)); - } - } - - DRAKE_DEMAND(line_points.rows() == 3); - meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, - rgba_); - return drake::systems::EventStatus::Succeeded(); -} - -LcmPoseDrawer::LcmPoseDrawer( - const std::shared_ptr& meshcat, - const std::string& model_file, - const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, int num_poses) - : meshcat_(meshcat), - translation_trajectory_name_(translation_trajectory_name), - orientation_trajectory_name_(orientation_trajectory_name), - N_(num_poses) { - this->set_name("LcmPoseDrawer: " + translation_trajectory_name); - - multipose_visualizer_ = std::make_unique( - model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.4), "", meshcat); - trajectory_input_port_ = - this->DeclareAbstractInputPort( - "lcmt_timestamped_saved_traj", - drake::Value{}) - .get_index(); - - DeclarePerStepDiscreteUpdateEvent(&LcmPoseDrawer::DrawTrajectory); -} - -drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( - const Context& context, - DiscreteValues* discrete_state) const { - if (this->EvalInputValue( - context, trajectory_input_port_) - ->utime < 1e-3) { - return drake::systems::EventStatus::Succeeded(); - } - const auto& lcmt_traj = - this->EvalInputValue( - context, trajectory_input_port_); - auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); - MatrixXd object_poses = MatrixXd::Zero(7, N_); - - const auto& lcm_translation_traj = - lcm_traj.GetTrajectory(translation_trajectory_name_); - auto translation_trajectory = PiecewisePolynomial::CubicHermite( - lcm_translation_traj.time_vector, - lcm_translation_traj.datapoints.topRows(3), - lcm_translation_traj.datapoints.bottomRows(3)); - auto orientation_trajectory = PiecewiseQuaternionSlerp( - {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); - - if (lcm_traj.HasTrajectory(orientation_trajectory_name_)) { - const auto& lcm_orientation_traj = - lcm_traj.GetTrajectory(orientation_trajectory_name_); - std::vector> quaternion_datapoints; - for (int i = 0; i < lcm_orientation_traj.datapoints.cols(); ++i) { - VectorXd orientation_sample = lcm_orientation_traj.datapoints.col(i); - if (orientation_sample.isZero()) { - quaternion_datapoints.push_back(Quaterniond(1, 0, 0, 0)); - } else { - quaternion_datapoints.push_back( - Quaterniond(orientation_sample[0], orientation_sample[1], - orientation_sample[2], orientation_sample[3])); - } - } - orientation_trajectory = PiecewiseQuaternionSlerp( - CopyVectorXdToStdVector(lcm_orientation_traj.time_vector), - quaternion_datapoints); - } - - // ASSUMING orientation and translation trajectories have the same breaks - VectorXd translation_breaks = - VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], - lcm_translation_traj.time_vector.tail(1)[0]); - for (int i = 0; i < object_poses.cols(); ++i) { - object_poses.col(i) << orientation_trajectory.value(translation_breaks(i)), - translation_trajectory.value(translation_breaks(i)); - } - - multipose_visualizer_->DrawPoses(object_poses); - - return drake::systems::EventStatus::Succeeded(); -} - -LcmForceDrawer::LcmForceDrawer( - const std::shared_ptr& meshcat, - std::string actor_trajectory_name, std::string force_trajectory_name, - std::string lcs_force_trajectory_name) - : meshcat_(meshcat), - actor_trajectory_name_(std::move(actor_trajectory_name)), - force_trajectory_name_(std::move(force_trajectory_name)), - lcs_force_trajectory_name_(std::move(lcs_force_trajectory_name)) { - this->set_name("LcmForceDrawer: " + force_trajectory_name_); - actor_trajectory_input_port_ = - this->DeclareAbstractInputPort( - "lcmt_timestamped_saved_traj: actor", - drake::Value{}) - .get_index(); - - robot_time_input_port_ = - this->DeclareVectorInputPort("t_robot", 1).get_index(); - - force_trajectory_input_port_ = - this->DeclareAbstractInputPort("lcmt_c3_forces", - drake::Value{}) - .get_index(); - - meshcat_->SetProperty(force_path_, "visible", true, 0); - - actor_last_update_time_index_ = this->DeclareDiscreteState(1); - forces_last_update_time_index_ = this->DeclareDiscreteState(1); - meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, - {0, 1, 0, 1}); - meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, - {0, 1, 0, 1}); - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); - - DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); - DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); -} - -drake::systems::EventStatus LcmForceDrawer::DrawForce( - const Context& context, - DiscreteValues* discrete_state) const { - if (this->EvalInputValue( - context, actor_trajectory_input_port_) - ->utime < 1e-3) { - return drake::systems::EventStatus::Succeeded(); - } - const auto& lcmt_traj = - this->EvalInputValue( - context, actor_trajectory_input_port_); - - // Don't needlessly update - if (discrete_state->get_value(actor_last_update_time_index_)[0] == - lcmt_traj->utime * 1e-6) { - return drake::systems::EventStatus::Succeeded(); - } - discrete_state->get_mutable_value(actor_last_update_time_index_)[0] = - lcmt_traj->utime * 1e-6; - const auto& robot_time_vec = - this->EvalVectorInput(context, robot_time_input_port_); - double robot_time = robot_time_vec->GetAtIndex(0); - - auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); - const auto& force_trajectory_block = - lcm_traj.GetTrajectory(force_trajectory_name_); - const auto& actor_trajectory_block = - lcm_traj.GetTrajectory(actor_trajectory_name_); - auto force_trajectory = PiecewisePolynomial::FirstOrderHold( - force_trajectory_block.time_vector, force_trajectory_block.datapoints); - VectorXd pose; - if (actor_trajectory_block.datapoints.rows() == 3) { - auto trajectory = PiecewisePolynomial::FirstOrderHold( - actor_trajectory_block.time_vector, actor_trajectory_block.datapoints); - pose = trajectory.value(actor_trajectory_block.time_vector[0]); - } else { - auto trajectory = PiecewisePolynomial::CubicHermite( - actor_trajectory_block.time_vector, - actor_trajectory_block.datapoints.topRows(3), - actor_trajectory_block.datapoints.bottomRows(3)); - pose = trajectory.value(actor_trajectory_block.time_vector[0]); - } - - auto force = force_trajectory.value(robot_time); - const std::string& force_path_root = force_path_ + "/u_lcs/"; - meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); - const std::string& force_arrow_path = force_path_root + "arrow"; - - auto force_norm = force.norm(); - // Stretch the cylinder in z. - if (force_norm >= 0.01) { - meshcat_->SetTransform( - force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); - const double height = force_norm / newtons_per_meter_; - meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", - {0, 0, 0.5 * height}); - // Note: Meshcat does not fully support non-uniform scaling (see #18095). - // We get away with it here since there is no rotation on this frame and - // no children in the kinematic tree. - meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", - {1, 1, height}); - // Translate the arrowheads. - const double arrowhead_height = radius_ * 2.0; - meshcat_->SetTransform( - force_arrow_path + "/head", - RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), - Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); - } else { - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); - } - return drake::systems::EventStatus::Succeeded(); -} - -drake::systems::EventStatus LcmForceDrawer::DrawForces( - const Context& context, - DiscreteValues* discrete_state) const { - if (this->EvalInputValue( - context, force_trajectory_input_port_) - ->utime < 1e-3) { - return drake::systems::EventStatus::Succeeded(); - } - const auto& c3_forces = this->EvalInputValue( - context, force_trajectory_input_port_); - - // Don't needlessly update - if (discrete_state->get_value(forces_last_update_time_index_)[0] == - c3_forces->utime * 1e-6) { - return drake::systems::EventStatus::Succeeded(); - } - discrete_state->get_mutable_value(forces_last_update_time_index_)[0] = - c3_forces->utime * 1e-6; - - for (int i = 0; i < c3_forces->num_forces; ++i) { - const VectorXd force = Eigen::Map( - c3_forces->forces[i].contact_force, 3); - auto force_norm = force.norm(); - const std::string& force_path_root = - force_path_ + "/lcs_force_" + std::to_string(i) + "/"; - if (force_norm >= 0.01) { - if (!meshcat_->HasPath(force_path_root + "arrow/")) { - meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, - {1, 0, 0, 1}); - meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, - {1, 0, 0, 1}); - } - - const VectorXd pose = Eigen::Map( - c3_forces->forces[i].contact_point, 3); - - meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); - // Stretch the cylinder in z. - const std::string& force_arrow_path = force_path_root + "arrow"; - meshcat_->SetTransform( - force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); - const double height = force_norm / newtons_per_meter_; - meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", - {0, 0, 0.5 * height}); - // Note: Meshcat does not fully support non-uniform scaling (see - // #18095). We get away with it here since there is no rotation on this - // frame and no children in the kinematic tree. - meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", - {1, 1, height}); - // Translate the arrowheads. - const double arrowhead_height = radius_ * 2.0; - meshcat_->SetTransform( - force_arrow_path + "/head", - RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), - Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_root, "visible", true); - } else { - meshcat_->SetProperty(force_path_root, "visible", false); - } - } - return drake::systems::EventStatus::Succeeded(); -} - -LcmC3TargetDrawer::LcmC3TargetDrawer( - const std::shared_ptr& meshcat, bool draw_tray, - bool draw_ee) - : meshcat_(meshcat), draw_tray_(draw_tray), draw_ee_(draw_ee) { - this->set_name("LcmC3TargetDrawer"); - c3_state_target_input_port_ = - this->DeclareAbstractInputPort("lcmt_c3_state: target", - drake::Value{}) - .get_index(); - - c3_state_actual_input_port_ = - this->DeclareAbstractInputPort("lcmt_c3_state: actual", - drake::Value{}) - .get_index(); - last_update_time_index_ = this->DeclareDiscreteState(1); - - meshcat_->SetProperty(c3_state_path_, "visible", true, 0); - - // TODO(yangwill): Clean up all this visualization, move to separate - // visualization directory1 - meshcat_->SetObject(c3_target_tray_path_ + "/x-axis", cylinder_for_tray_, - {1, 0, 0, 1}); - meshcat_->SetObject(c3_target_tray_path_ + "/y-axis", cylinder_for_tray_, - {0, 1, 0, 1}); - meshcat_->SetObject(c3_target_tray_path_ + "/z-axis", cylinder_for_tray_, - {0, 0, 1, 1}); - meshcat_->SetObject(c3_actual_tray_path_ + "/x-axis", cylinder_for_tray_, - {1, 0, 0, 1}); - meshcat_->SetObject(c3_actual_tray_path_ + "/y-axis", cylinder_for_tray_, - {0, 1, 0, 1}); - meshcat_->SetObject(c3_actual_tray_path_ + "/z-axis", cylinder_for_tray_, - {0, 0, 1, 1}); - meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, - {1, 0, 0, 1}); - meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, - {0, 1, 0, 1}); - meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, - {0, 0, 1, 1}); - meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, - {1, 0, 0, 1}); - meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, - {0, 1, 0, 1}); - meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, - {0, 0, 1, 1}); - auto x_axis_transform = - RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), - Vector3d{0.075, 0.0, 0.0}); - auto y_axis_transform = - RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), - Vector3d{0.0, 0.075, 0.0}); - auto z_axis_transform = - RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), - Vector3d{0.0, 0.0, 0.075}); - auto x_axis_transform_ee = - RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), - 0.5 * Vector3d{0.075, 0.0, 0.0}); - auto y_axis_transform_ee = - RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), - 0.5 * Vector3d{0.0, 0.075, 0.0}); - auto z_axis_transform_ee = - RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), - 0.5 * Vector3d{0.0, 0.0, 0.075}); - meshcat_->SetTransform(c3_target_tray_path_ + "/x-axis", x_axis_transform); - meshcat_->SetTransform(c3_target_tray_path_ + "/y-axis", y_axis_transform); - meshcat_->SetTransform(c3_target_tray_path_ + "/z-axis", z_axis_transform); - meshcat_->SetTransform(c3_actual_tray_path_ + "/x-axis", x_axis_transform); - meshcat_->SetTransform(c3_actual_tray_path_ + "/y-axis", y_axis_transform); - meshcat_->SetTransform(c3_actual_tray_path_ + "/z-axis", z_axis_transform); - meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); - meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); - meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); - - DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); -} - -drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( - const Context& context, - DiscreteValues* discrete_state) const { - if (this->EvalInputValue(context, - c3_state_target_input_port_) - ->utime < 1e-3) { - return drake::systems::EventStatus::Succeeded(); - } - if (this->EvalInputValue(context, - c3_state_actual_input_port_) - ->utime < 1e-3) { - return drake::systems::EventStatus::Succeeded(); - } - if (discrete_state->get_value(last_update_time_index_)[0] >= - context.get_time()) { - // no need to update if simulation has not advanced - return drake::systems::EventStatus::Succeeded(); - } - discrete_state->get_mutable_value(last_update_time_index_)[0] = - context.get_time(); - const auto& c3_target = this->EvalInputValue( - context, c3_state_target_input_port_); - const auto& c3_actual = this->EvalInputValue( - context, c3_state_actual_input_port_); - if (draw_tray_) { - meshcat_->SetTransform( - c3_target_tray_path_, - RigidTransformd( - Eigen::Quaterniond(c3_target->state[3], c3_target->state[4], - c3_target->state[5], c3_target->state[6]), - Vector3d{c3_target->state[7], c3_target->state[8], - c3_target->state[9]})); - meshcat_->SetTransform( - c3_actual_tray_path_, - RigidTransformd( - Eigen::Quaterniond(c3_actual->state[3], c3_actual->state[4], - c3_actual->state[5], c3_actual->state[6]), - Vector3d{c3_actual->state[7], c3_actual->state[8], - c3_actual->state[9]})); - } - if (draw_ee_) { - meshcat_->SetTransform( - c3_target_ee_path_, - RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], - c3_target->state[2]})); - -// meshcat_->SetTransform( -// c3_actual_ee_path_, -// RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], -// c3_actual->state[2]})); - } - return drake::systems::EventStatus::Succeeded(); -} - } // namespace systems } // namespace dairlib diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.h b/systems/trajectory_optimization/lcm_trajectory_systems.h index 80d26c477c..bc46dc988e 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.h +++ b/systems/trajectory_optimization/lcm_trajectory_systems.h @@ -64,168 +64,6 @@ class LcmOrientationTrajectoryReceiver const std::string trajectory_name_; }; -/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, -/// and draws it through meshcat. -class LcmTrajectoryDrawer : public drake::systems::LeafSystem { - public: - explicit LcmTrajectoryDrawer(const std::shared_ptr&, - std::string trajectory_name); - - const drake::systems::InputPort& get_input_port_trajectory() const { - return this->get_input_port(trajectory_input_port_); - } - - void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } - - void SetNumSamples(int N) { - DRAKE_DEMAND(N > 1); - N_ = N; - } - - private: - void OutputTrajectory(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - drake::systems::EventStatus DrawTrajectory( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - - drake::systems::InputPortIndex trajectory_input_port_; - std::shared_ptr meshcat_; - const std::string trajectory_name_; - drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); - int N_ = 5; -}; - -/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, -/// and draws the object pose through meshcat. -class LcmPoseDrawer : public drake::systems::LeafSystem { - public: - explicit LcmPoseDrawer(const std::shared_ptr&, - const std::string& model_file, - const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, - int num_poses = 5); - - const drake::systems::InputPort& get_input_port_trajectory() const { - return this->get_input_port(trajectory_input_port_); - } - - private: - void OutputTrajectory(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - drake::systems::EventStatus DrawTrajectory( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - - drake::systems::InputPortIndex trajectory_input_port_; - std::shared_ptr meshcat_; - const std::string translation_trajectory_name_; - const std::string orientation_trajectory_name_; - std::unique_ptr multipose_visualizer_; - const int N_; -}; - -/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, -/// and draws it through meshcat. -class LcmForceDrawer : public drake::systems::LeafSystem { - public: - explicit LcmForceDrawer(const std::shared_ptr&, - std::string force_trajectory_name, - std::string actor_trajectory_name, - std::string lcs_force_trajectory_name); - - const drake::systems::InputPort& get_input_port_actor_trajectory() const { - return this->get_input_port(actor_trajectory_input_port_); - } - - const drake::systems::InputPort& get_input_port_robot_time() const { - return this->get_input_port(robot_time_input_port_); - } - - const drake::systems::InputPort& get_input_port_force_trajectory() const { - return this->get_input_port(force_trajectory_input_port_); - } - - void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } - - void SetNumSamples(int N) { - DRAKE_DEMAND(N > 1); - N_ = N; - } - - private: - drake::systems::EventStatus DrawForce( - const drake::systems::Context &context, - drake::systems::DiscreteValues *discrete_state) const; - drake::systems::EventStatus DrawForces( - const drake::systems::Context &context, - drake::systems::DiscreteValues *discrete_state) const; - - drake::systems::InputPortIndex actor_trajectory_input_port_; - drake::systems::InputPortIndex robot_time_input_port_; - drake::systems::InputPortIndex force_trajectory_input_port_; - - drake::systems::DiscreteStateIndex actor_last_update_time_index_; - drake::systems::DiscreteStateIndex forces_last_update_time_index_; - std::shared_ptr meshcat_; - const drake::geometry::Cylinder cylinder_ = drake::geometry::Cylinder(0.002, 1.0); - const drake::geometry::MeshcatCone arrowhead_ = drake::geometry::MeshcatCone(0.004, 0.004, 0.004); - const std::string force_path_ = "c3_forces"; - const std::string actor_trajectory_name_; - const std::string force_trajectory_name_; - const std::string lcs_force_trajectory_name_; - drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); - int N_ = 5; - const double radius_ = 0.002; - const double newtons_per_meter_ = 20; -}; - -/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, -/// and draws it through meshcat. -class LcmC3TargetDrawer : public drake::systems::LeafSystem { - public: - explicit LcmC3TargetDrawer(const std::shared_ptr&, - bool draw_tray = true, - bool draw_ee = false); - - const drake::systems::InputPort& get_input_port_c3_state_target() const { - return this->get_input_port(c3_state_target_input_port_); - } - - const drake::systems::InputPort& get_input_port_c3_state_actual() const { - return this->get_input_port(c3_state_actual_input_port_); - } - - private: - drake::systems::EventStatus DrawC3State( - const drake::systems::Context &context, - drake::systems::DiscreteValues *discrete_state) const; - - std::shared_ptr meshcat_; - - drake::systems::InputPortIndex c3_state_target_input_port_; - drake::systems::InputPortIndex c3_state_actual_input_port_; - - bool draw_tray_; - bool draw_ee_; - - drake::systems::DiscreteStateIndex last_update_time_index_; - - const drake::geometry::Cylinder cylinder_for_tray_ = drake::geometry::Cylinder(0.005, 0.15); - const drake::geometry::Cylinder cylinder_for_ee_ = drake::geometry::Cylinder(0.0025, 0.075); - drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); - const std::string c3_state_path_ = "c3_state"; - const std::string c3_target_tray_path_ = "c3_state/c3_target_tray"; - const std::string c3_actual_tray_path_ = "c3_state/c3_actual_tray"; - const std::string c3_target_ee_path_ = "c3_state/c3_target_ee"; - const std::string c3_actual_ee_path_ = "c3_state/c3_actual_ee"; - -// const double radius_ = 0.002; -// const double newtons_per_meter_ = 10; -}; - } // namespace systems } // namespace dairlib diff --git a/systems/visualization/BUILD.bazel b/systems/visualization/BUILD.bazel new file mode 100644 index 0000000000..9efc58dce4 --- /dev/null +++ b/systems/visualization/BUILD.bazel @@ -0,0 +1,21 @@ +# -*- mode: python -*- +# vi: set ft=python : + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "lcm_visualization_systems", + srcs = [ + "lcm_visualization_systems.cc", + ], + hdrs = [ + "lcm_visualization_systems.h", + ], + deps = [ + "//common:eigen_utils", + "//common:find_resource", + "//lcm:lcm_trajectory_saver", + "//multibody:multipose_visualizer", + "@drake//:drake_shared_library", + ], +) diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc new file mode 100644 index 0000000000..c79e70dba0 --- /dev/null +++ b/systems/visualization/lcm_visualization_systems.cc @@ -0,0 +1,466 @@ +#include "lcm_visualization_systems.h" + +#include +#include +#include + +#include "common/eigen_utils.h" + +#include "drake/common/schema/rotation.h" +#include "drake/geometry/rgba.h" + +namespace dairlib { +namespace systems { + +using drake::geometry::Rgba; +using drake::math::RigidTransformd; +using drake::math::RotationMatrixd; +using drake::systems::Context; +using drake::systems::DiscreteValues; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::PiecewiseQuaternionSlerp; +using drake::trajectories::Trajectory; +using Eigen::MatrixXd; +using Eigen::Quaterniond; +using Eigen::Vector3d; +using Eigen::VectorXd; + +LcmTrajectoryDrawer::LcmTrajectoryDrawer( + const std::shared_ptr& meshcat, + std::string trajectory_name) + : meshcat_(meshcat), trajectory_name_(std::move(trajectory_name)) { + this->set_name("LcmTrajectoryDrawer: " + trajectory_name_); + trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj", + drake::Value{}) + .get_index(); + + DeclarePerStepDiscreteUpdateEvent(&LcmTrajectoryDrawer::DrawTrajectory); +} + +drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, trajectory_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + const auto& lcmt_traj = + this->EvalInputValue( + context, trajectory_input_port_); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); + MatrixXd line_points = MatrixXd::Zero(3, N_); + VectorXd breaks = + VectorXd::LinSpaced(N_, trajectory_block.time_vector[0], + trajectory_block.time_vector.tail(1)[0]); + if (trajectory_block.datapoints.rows() == 3) { + auto trajectory = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); + for (int i = 0; i < line_points.cols(); ++i) { + line_points.col(i) = trajectory.value(breaks(i)); + } + } else { + auto trajectory = PiecewisePolynomial::CubicHermite( + trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), + trajectory_block.datapoints.bottomRows(3)); + for (int i = 0; i < line_points.cols(); ++i) { + line_points.col(i) = trajectory.value(breaks(i)); + } + } + + DRAKE_DEMAND(line_points.rows() == 3); + meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, + rgba_); + return drake::systems::EventStatus::Succeeded(); +} + +LcmPoseDrawer::LcmPoseDrawer( + const std::shared_ptr& meshcat, + const std::string& model_file, + const std::string& translation_trajectory_name, + const std::string& orientation_trajectory_name, int num_poses) + : meshcat_(meshcat), + translation_trajectory_name_(translation_trajectory_name), + orientation_trajectory_name_(orientation_trajectory_name), + N_(num_poses) { + this->set_name("LcmPoseDrawer: " + translation_trajectory_name); + + multipose_visualizer_ = std::make_unique( + model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.4), "", meshcat); + trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj", + drake::Value{}) + .get_index(); + + DeclarePerStepDiscreteUpdateEvent(&LcmPoseDrawer::DrawTrajectory); +} + +drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, trajectory_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + const auto& lcmt_traj = + this->EvalInputValue( + context, trajectory_input_port_); + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + MatrixXd object_poses = MatrixXd::Zero(7, N_); + + const auto& lcm_translation_traj = + lcm_traj.GetTrajectory(translation_trajectory_name_); + auto translation_trajectory = PiecewisePolynomial::CubicHermite( + lcm_translation_traj.time_vector, + lcm_translation_traj.datapoints.topRows(3), + lcm_translation_traj.datapoints.bottomRows(3)); + auto orientation_trajectory = PiecewiseQuaternionSlerp( + {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); + + if (lcm_traj.HasTrajectory(orientation_trajectory_name_)) { + const auto& lcm_orientation_traj = + lcm_traj.GetTrajectory(orientation_trajectory_name_); + std::vector> quaternion_datapoints; + for (int i = 0; i < lcm_orientation_traj.datapoints.cols(); ++i) { + VectorXd orientation_sample = lcm_orientation_traj.datapoints.col(i); + if (orientation_sample.isZero()) { + quaternion_datapoints.push_back(Quaterniond(1, 0, 0, 0)); + } else { + quaternion_datapoints.push_back( + Quaterniond(orientation_sample[0], orientation_sample[1], + orientation_sample[2], orientation_sample[3])); + } + } + orientation_trajectory = PiecewiseQuaternionSlerp( + CopyVectorXdToStdVector(lcm_orientation_traj.time_vector), + quaternion_datapoints); + } + + // ASSUMING orientation and translation trajectories have the same breaks + VectorXd translation_breaks = + VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], + lcm_translation_traj.time_vector.tail(1)[0]); + for (int i = 0; i < object_poses.cols(); ++i) { + object_poses.col(i) << orientation_trajectory.value(translation_breaks(i)), + translation_trajectory.value(translation_breaks(i)); + } + + multipose_visualizer_->DrawPoses(object_poses); + + return drake::systems::EventStatus::Succeeded(); +} + +LcmForceDrawer::LcmForceDrawer( + const std::shared_ptr& meshcat, + std::string actor_trajectory_name, std::string force_trajectory_name, + std::string lcs_force_trajectory_name) + : meshcat_(meshcat), + actor_trajectory_name_(std::move(actor_trajectory_name)), + force_trajectory_name_(std::move(force_trajectory_name)), + lcs_force_trajectory_name_(std::move(lcs_force_trajectory_name)) { + this->set_name("LcmForceDrawer: " + force_trajectory_name_); + actor_trajectory_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj: actor", + drake::Value{}) + .get_index(); + + robot_time_input_port_ = + this->DeclareVectorInputPort("t_robot", 1).get_index(); + + force_trajectory_input_port_ = + this->DeclareAbstractInputPort("lcmt_c3_forces", + drake::Value{}) + .get_index(); + + meshcat_->SetProperty(force_path_, "visible", true, 0); + + actor_last_update_time_index_ = this->DeclareDiscreteState(1); + forces_last_update_time_index_ = this->DeclareDiscreteState(1); + meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, + {0, 1, 0, 1}); + meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, + {0, 1, 0, 1}); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); + + DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); + DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForces); +} + +drake::systems::EventStatus LcmForceDrawer::DrawForce( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, actor_trajectory_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + const auto& lcmt_traj = + this->EvalInputValue( + context, actor_trajectory_input_port_); + + // Don't needlessly update + if (discrete_state->get_value(actor_last_update_time_index_)[0] == + lcmt_traj->utime * 1e-6) { + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(actor_last_update_time_index_)[0] = + lcmt_traj->utime * 1e-6; + const auto& robot_time_vec = + this->EvalVectorInput(context, robot_time_input_port_); + double robot_time = robot_time_vec->GetAtIndex(0); + + auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); + const auto& force_trajectory_block = + lcm_traj.GetTrajectory(force_trajectory_name_); + const auto& actor_trajectory_block = + lcm_traj.GetTrajectory(actor_trajectory_name_); + auto force_trajectory = PiecewisePolynomial::FirstOrderHold( + force_trajectory_block.time_vector, force_trajectory_block.datapoints); + VectorXd pose; + if (actor_trajectory_block.datapoints.rows() == 3) { + auto trajectory = PiecewisePolynomial::FirstOrderHold( + actor_trajectory_block.time_vector, actor_trajectory_block.datapoints); + pose = trajectory.value(actor_trajectory_block.time_vector[0]); + } else { + auto trajectory = PiecewisePolynomial::CubicHermite( + actor_trajectory_block.time_vector, + actor_trajectory_block.datapoints.topRows(3), + actor_trajectory_block.datapoints.bottomRows(3)); + pose = trajectory.value(actor_trajectory_block.time_vector[0]); + } + + auto force = force_trajectory.value(robot_time); + const std::string& force_path_root = force_path_ + "/u_lcs/"; + meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + const std::string& force_arrow_path = force_path_root + "arrow"; + + auto force_norm = force.norm(); + // Stretch the cylinder in z. + if (force_norm >= 0.01) { + meshcat_->SetTransform( + force_arrow_path, + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + const double height = force_norm / newtons_per_meter_; + meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", + {0, 0, 0.5 * height}); + // Note: Meshcat does not fully support non-uniform scaling (see #18095). + // We get away with it here since there is no rotation on this frame and + // no children in the kinematic tree. + meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", + {1, 1, height}); + // Translate the arrowheads. + const double arrowhead_height = radius_ * 2.0; + meshcat_->SetTransform( + force_arrow_path + "/head", + RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), + Vector3d{0, 0, height + arrowhead_height})); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); + } else { + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); + } + return drake::systems::EventStatus::Succeeded(); +} + +drake::systems::EventStatus LcmForceDrawer::DrawForces( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue( + context, force_trajectory_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + const auto& c3_forces = this->EvalInputValue( + context, force_trajectory_input_port_); + + // Don't needlessly update + if (discrete_state->get_value(forces_last_update_time_index_)[0] == + c3_forces->utime * 1e-6) { + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(forces_last_update_time_index_)[0] = + c3_forces->utime * 1e-6; + + for (int i = 0; i < c3_forces->num_forces; ++i) { + const VectorXd force = Eigen::Map( + c3_forces->forces[i].contact_force, 3); + auto force_norm = force.norm(); + const std::string& force_path_root = + force_path_ + "/lcs_force_" + std::to_string(i) + "/"; + if (force_norm >= 0.01) { + if (!meshcat_->HasPath(force_path_root + "arrow/")) { + meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, + {1, 0, 0, 1}); + meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, + {1, 0, 0, 1}); + } + + const VectorXd pose = Eigen::Map( + c3_forces->forces[i].contact_point, 3); + + meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + // Stretch the cylinder in z. + const std::string& force_arrow_path = force_path_root + "arrow"; + meshcat_->SetTransform( + force_arrow_path, + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + const double height = force_norm / newtons_per_meter_; + meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", + {0, 0, 0.5 * height}); + // Note: Meshcat does not fully support non-uniform scaling (see + // #18095). We get away with it here since there is no rotation on this + // frame and no children in the kinematic tree. + meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", + {1, 1, height}); + // Translate the arrowheads. + const double arrowhead_height = radius_ * 2.0; + meshcat_->SetTransform( + force_arrow_path + "/head", + RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), + Vector3d{0, 0, height + arrowhead_height})); + meshcat_->SetProperty(force_path_root, "visible", true); + } else { + meshcat_->SetProperty(force_path_root, "visible", false); + } + } + return drake::systems::EventStatus::Succeeded(); +} + +LcmC3TargetDrawer::LcmC3TargetDrawer( + const std::shared_ptr& meshcat, bool draw_tray, + bool draw_ee) + : meshcat_(meshcat), draw_tray_(draw_tray), draw_ee_(draw_ee) { + this->set_name("LcmC3TargetDrawer"); + c3_state_target_input_port_ = + this->DeclareAbstractInputPort("lcmt_c3_state: target", + drake::Value{}) + .get_index(); + + c3_state_actual_input_port_ = + this->DeclareAbstractInputPort("lcmt_c3_state: actual", + drake::Value{}) + .get_index(); + last_update_time_index_ = this->DeclareDiscreteState(1); + + meshcat_->SetProperty(c3_state_path_, "visible", true, 0); + + // TODO(yangwill): Clean up all this visualization, move to separate + // visualization directory1 + meshcat_->SetObject(c3_target_tray_path_ + "/x-axis", cylinder_for_tray_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_target_tray_path_ + "/y-axis", cylinder_for_tray_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_target_tray_path_ + "/z-axis", cylinder_for_tray_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_actual_tray_path_ + "/x-axis", cylinder_for_tray_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_actual_tray_path_ + "/y-axis", cylinder_for_tray_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_actual_tray_path_ + "/z-axis", cylinder_for_tray_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, + {0, 0, 1, 1}); + auto x_axis_transform = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), + Vector3d{0.075, 0.0, 0.0}); + auto y_axis_transform = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), + Vector3d{0.0, 0.075, 0.0}); + auto z_axis_transform = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), + Vector3d{0.0, 0.0, 0.075}); + auto x_axis_transform_ee = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), + 0.5 * Vector3d{0.075, 0.0, 0.0}); + auto y_axis_transform_ee = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), + 0.5 * Vector3d{0.0, 0.075, 0.0}); + auto z_axis_transform_ee = + RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), + 0.5 * Vector3d{0.0, 0.0, 0.075}); + meshcat_->SetTransform(c3_target_tray_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_target_tray_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_target_tray_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_actual_tray_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_actual_tray_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_actual_tray_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); + + DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); +} + +drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( + const Context& context, + DiscreteValues* discrete_state) const { + if (this->EvalInputValue(context, + c3_state_target_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + if (this->EvalInputValue(context, + c3_state_actual_input_port_) + ->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } + if (discrete_state->get_value(last_update_time_index_)[0] >= + context.get_time()) { + // no need to update if simulation has not advanced + return drake::systems::EventStatus::Succeeded(); + } + discrete_state->get_mutable_value(last_update_time_index_)[0] = + context.get_time(); + const auto& c3_target = this->EvalInputValue( + context, c3_state_target_input_port_); + const auto& c3_actual = this->EvalInputValue( + context, c3_state_actual_input_port_); + if (draw_tray_) { + meshcat_->SetTransform( + c3_target_tray_path_, + RigidTransformd( + Eigen::Quaterniond(c3_target->state[3], c3_target->state[4], + c3_target->state[5], c3_target->state[6]), + Vector3d{c3_target->state[7], c3_target->state[8], + c3_target->state[9]})); + meshcat_->SetTransform( + c3_actual_tray_path_, + RigidTransformd( + Eigen::Quaterniond(c3_actual->state[3], c3_actual->state[4], + c3_actual->state[5], c3_actual->state[6]), + Vector3d{c3_actual->state[7], c3_actual->state[8], + c3_actual->state[9]})); + } + if (draw_ee_) { + meshcat_->SetTransform( + c3_target_ee_path_, + RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], + c3_target->state[2]})); + // meshcat_->SetTransform( + // c3_actual_ee_path_, + // RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], + // c3_actual->state[2]})); + } + return drake::systems::EventStatus::Succeeded(); +} + +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h new file mode 100644 index 0000000000..d5397652f2 --- /dev/null +++ b/systems/visualization/lcm_visualization_systems.h @@ -0,0 +1,187 @@ +#pragma once + +#include +#include + +#include +#include +#include + +#include "dairlib/lcmt_saved_traj.hpp" +#include "lcm/lcm_trajectory.h" +#include "multibody/multipose_visualizer.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/common/trajectories/piecewise_quaternion.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws it through meshcat. +class LcmTrajectoryDrawer : public drake::systems::LeafSystem { + public: + explicit LcmTrajectoryDrawer(const std::shared_ptr&, + std::string trajectory_name); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_input_port_); + } + + void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } + + void SetNumSamples(int N) { + DRAKE_DEMAND(N > 1); + N_ = N; + } + + private: + void OutputTrajectory(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + drake::systems::EventStatus DrawTrajectory( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex trajectory_input_port_; + std::shared_ptr meshcat_; + const std::string trajectory_name_; + drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + int N_ = 5; +}; + +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws the object pose through meshcat. +class LcmPoseDrawer : public drake::systems::LeafSystem { + public: + explicit LcmPoseDrawer(const std::shared_ptr&, + const std::string& model_file, + const std::string& translation_trajectory_name, + const std::string& orientation_trajectory_name, + int num_poses = 5); + + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_input_port_); + } + + private: + void OutputTrajectory(const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + drake::systems::EventStatus DrawTrajectory( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex trajectory_input_port_; + std::shared_ptr meshcat_; + const std::string translation_trajectory_name_; + const std::string orientation_trajectory_name_; + std::unique_ptr multipose_visualizer_; + const int N_; +}; + +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws it through meshcat. +class LcmForceDrawer : public drake::systems::LeafSystem { + public: + explicit LcmForceDrawer(const std::shared_ptr&, + std::string force_trajectory_name, + std::string actor_trajectory_name, + std::string lcs_force_trajectory_name); + + const drake::systems::InputPort& get_input_port_actor_trajectory() + const { + return this->get_input_port(actor_trajectory_input_port_); + } + + const drake::systems::InputPort& get_input_port_robot_time() const { + return this->get_input_port(robot_time_input_port_); + } + + const drake::systems::InputPort& get_input_port_force_trajectory() + const { + return this->get_input_port(force_trajectory_input_port_); + } + + void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } + + void SetNumSamples(int N) { + DRAKE_DEMAND(N > 1); + N_ = N; + } + + private: + drake::systems::EventStatus DrawForce( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + drake::systems::EventStatus DrawForces( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex actor_trajectory_input_port_; + drake::systems::InputPortIndex robot_time_input_port_; + drake::systems::InputPortIndex force_trajectory_input_port_; + + drake::systems::DiscreteStateIndex actor_last_update_time_index_; + drake::systems::DiscreteStateIndex forces_last_update_time_index_; + std::shared_ptr meshcat_; + const drake::geometry::Cylinder cylinder_ = + drake::geometry::Cylinder(0.002, 1.0); + const drake::geometry::MeshcatCone arrowhead_ = + drake::geometry::MeshcatCone(0.004, 0.004, 0.004); + const std::string force_path_ = "c3_forces"; + const std::string actor_trajectory_name_; + const std::string force_trajectory_name_; + const std::string lcs_force_trajectory_name_; + drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + int N_ = 5; + const double radius_ = 0.002; + const double newtons_per_meter_ = 20; +}; + +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws it through meshcat. +class LcmC3TargetDrawer : public drake::systems::LeafSystem { + public: + explicit LcmC3TargetDrawer(const std::shared_ptr&, + bool draw_tray = true, bool draw_ee = false); + + const drake::systems::InputPort& get_input_port_c3_state_target() + const { + return this->get_input_port(c3_state_target_input_port_); + } + + const drake::systems::InputPort& get_input_port_c3_state_actual() + const { + return this->get_input_port(c3_state_actual_input_port_); + } + + private: + drake::systems::EventStatus DrawC3State( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + std::shared_ptr meshcat_; + + drake::systems::InputPortIndex c3_state_target_input_port_; + drake::systems::InputPortIndex c3_state_actual_input_port_; + + bool draw_tray_; + bool draw_ee_; + + drake::systems::DiscreteStateIndex last_update_time_index_; + + const drake::geometry::Cylinder cylinder_for_tray_ = + drake::geometry::Cylinder(0.005, 0.15); + const drake::geometry::Cylinder cylinder_for_ee_ = + drake::geometry::Cylinder(0.0025, 0.075); + drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + const std::string c3_state_path_ = "c3_state"; + const std::string c3_target_tray_path_ = "c3_state/c3_target_tray"; + const std::string c3_actual_tray_path_ = "c3_state/c3_actual_tray"; + const std::string c3_target_ee_path_ = "c3_state/c3_target_ee"; + const std::string c3_actual_ee_path_ = "c3_state/c3_actual_ee"; +}; +} // namespace systems +} // namespace dairlib From 03712c3d9623cf3cfa85c9fc95064f803c801ee1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Jan 2024 17:09:11 -0500 Subject: [PATCH 615/758] adding plot to try and analyze friction boundary --- bindings/pydairlib/analysis/log_plotter_franka.py | 15 ++++++++++----- .../plot_configs/franka_sim_plot_config.yaml | 4 ++-- 2 files changed, 12 insertions(+), 7 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 80ce734c2e..5b2f877cae 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -99,14 +99,19 @@ def main(): # import pdb; pdb.set_trace() if plot_config.plot_c3_debug: - t_c3_slice = slice(c3_output['t'].size) - mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 0) + # t_c3_slice = slice(c3_output['t'].size) + # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 0) t_c3_slice = slice(c3_output['t'].size) - mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1) + plot = mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1) + plot.axes[0].axhline(y=8.06, color='r', linestyle='-') + plot.axes[0].axhline(y=-8.06, color='r', linestyle='-') - t_c3_slice = slice(c3_output['t'].size) - mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) + + + + # t_c3_slice = slice(c3_output['t'].size) + # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) if plot_config.plot_c3_tracking: plot = plot_styler.PlotStyler(nrows=2) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml index 1310921dff..e154b4ea47 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_sim_plot_config.yaml @@ -16,7 +16,7 @@ duration: -1 # Desired RobotOutput plots plot_joint_positions: false plot_joint_velocities: false -plot_measured_efforts: false +plot_measured_efforts: true plot_commanded_efforts: false plot_contact_forces: false plot_end_effector: true @@ -35,7 +35,7 @@ plot_qp_solutions: true plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0], 'derivs': ['accel']} + end_effector_target: {'dims': [1], 'derivs': ['pos', 'vel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} plot_c3_debug: true From c9241b79c3973e2bec68225a73b0df3148c3bb1d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 18 Jan 2024 17:11:48 -0500 Subject: [PATCH 616/758] updating sim params to better reflect friction coeffs in real, qol changes --- examples/franka/franka_visualizer.cc | 2 +- examples/franka/parameters/franka_sim_params.h | 4 ++-- .../franka/parameters/franka_sim_params.yaml | 16 +++++++--------- examples/franka/urdf/left_support.urdf | 4 ++-- .../urdf/plate_end_effector_translation.urdf | 6 +++--- 5 files changed, 15 insertions(+), 17 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index e02ce8c1f7..c32c58667a 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -176,7 +176,7 @@ int do_main(int argc, char* argv[]) { auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); - meshcat->SetCameraPose(sim_params.camera_pose, sim_params.camera_target); + meshcat->SetCameraPose(sim_params.camera_pose[sim_params.scene_index], sim_params.camera_target[sim_params.scene_index]); if (sim_params.visualize_workspace){ double width = sim_params.world_x_limits[1] - sim_params.world_x_limits[0]; diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index f254203813..0fcd372b1a 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -24,8 +24,8 @@ struct FrankaSimParams { bool visualize_drake_sim; bool publish_efforts; - Eigen::VectorXd camera_pose; - Eigen::VectorXd camera_target; + std::vector camera_pose; + std::vector camera_target; Eigen::VectorXd q_init_franka; std::vector q_init_plate; diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b3ee989bdb..08b679aa3a 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -16,14 +16,12 @@ scene_index: 2 visualize_drake_sim: true publish_efforts: true -#camera_pose: [0.5, -1.2, 0.7] -#camera_target: [0.5, 0, 0.5] - -#camera_pose: [0.5, -0.8, 0.6] -#camera_target: [0.5, 0, 0.5] - -camera_pose: [1.5, 0, 0.6] -camera_target: [0.5, 0, 0.55] +camera_pose: [[0.5, -1.2, 0.7], + [0.5, -0.8, 0.6], + [1.5, 0, 0.6]] +camera_target: [[0.5, 0, 0.5], + [0.5, 0, 0.5], + [0.5, 0, 0.55]] tool_attachment_frame: [0, 0, 0.107] #left_support_position: [0.8, 0.15, 0.453] @@ -59,7 +57,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] -visualize_workspace: true +visualize_workspace: false visualize_pose_trace: true visualize_center_of_mass_plan: true visualize_c3_forces: false diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index 81350d956f..803553eee7 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -20,8 +20,8 @@ - - + + diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 8f6f93e6e2..89ee71bac9 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -20,19 +20,19 @@ - + - + - + From c40d3a6023146a2c4988b1e8e7dcc31894f43dac Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 20 Jan 2024 17:17:26 -0500 Subject: [PATCH 617/758] minor plotting changes --- bindings/pydairlib/analysis/log_plotter_franka.py | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 5b2f877cae..1962005c71 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -63,8 +63,10 @@ def main(): c3_output, c3_tracking_target, c3_tracking_actual = get_log_data(log, default_channels, plot_config.start_time, plot_config.duration, mbp_plots.load_c3_debug, channel_c3, channel_c3_target, channel_c3_actual) + solve_times = np.diff(c3_output['t'], prepend=[0]) print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_output['t']))) + # processing callback arguments if plot_config.plot_object_state: object_state = get_log_data(log, default_channels, @@ -106,6 +108,7 @@ def main(): plot = mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1) plot.axes[0].axhline(y=8.06, color='r', linestyle='-') plot.axes[0].axhline(y=-8.06, color='r', linestyle='-') + plot.save_fig('c3_inputs_' + filename.split('/')[-1]) @@ -121,6 +124,7 @@ def main(): plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:10], subplot_index = 1) plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 1) plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) + plot.plot(c3_tracking_target['t'], solve_times) # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) # Plot all joint velocities From 302f01180ecbdf18d0544215e0016d816c3409fc Mon Sep 17 00:00:00 2001 From: Will Yang Date: Sat, 20 Jan 2024 18:09:21 -0500 Subject: [PATCH 618/758] plotting updates --- .../pydairlib/analysis/log_plotter_franka.py | 35 ++++++++++++++----- 1 file changed, 26 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 1962005c71..fed4947317 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -14,10 +14,10 @@ def main(): - # config_file = ('bindings/pydairlib/analysis/plot_configs' - # '/franka_translation_plot.yaml') config_file = ('bindings/pydairlib/analysis/plot_configs' - '/franka_sim_plot_config.yaml') + '/franka_translation_plot.yaml') + # config_file = ('bindings/pydairlib/analysis/plot_configs' + # '/franka_sim_plot_config.yaml') plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x @@ -63,7 +63,7 @@ def main(): c3_output, c3_tracking_target, c3_tracking_actual = get_log_data(log, default_channels, plot_config.start_time, plot_config.duration, mbp_plots.load_c3_debug, channel_c3, channel_c3_target, channel_c3_actual) - solve_times = np.diff(c3_output['t'], prepend=[0]) + solve_times = np.diff(c3_output['t'], prepend=[c3_output['t'][0]]) print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_output['t']))) @@ -118,13 +118,30 @@ def main(): if plot_config.plot_c3_tracking: plot = plot_styler.PlotStyler(nrows=2) - plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:3], subplot_index = 0) - plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0) + # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:3], subplot_index = 0) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0) + # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) + # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:10], subplot_index = 1) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 1) + # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) + + plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) + plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0) plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) - plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:10], subplot_index = 1) - plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 1) + plot.axes[0].set_ylim([0.4, 0.7]) + plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) + plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) + plot.axes[0].set_ylim([0.4, 0.7]) plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) - plot.plot(c3_tracking_target['t'], solve_times) + + plot = plot_styler.PlotStyler(nrows=2) + plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 0) + plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0) + plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 0) + plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 1) + plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 1) + plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 9:10], subplot_index = 1) + # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8] - c3_tracking_actual['x'][:, 7:8], subplot_index = 1) # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) # Plot all joint velocities From fb00120f4a8b0e58752eef8dadda9506fce30498 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 20 Jan 2024 18:22:03 -0500 Subject: [PATCH 619/758] updating gains, reducing end effector friction for tuning --- .../franka/parameters/franka_c3_options_translation.yaml | 4 ++-- .../franka/parameters/franka_c3_options_w_supports.yaml | 2 +- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/systems/plate_balancing_target.cc | 8 ++++++-- examples/franka/urdf/plate_end_effector.urdf | 4 ++-- 5 files changed, 12 insertions(+), 8 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index dcc877e3ba..ce05799966 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -14,7 +14,7 @@ solve_time_filter_alpha: 0.9 # Workspace Limits world_x_limits: [0.4, 0.6] -world_y_limits: [-0.15, 0.15] +world_y_limits: [-0.2, 0.2] world_z_limits: [0.3, 0.6] workspace_margins: 0.05 @@ -38,7 +38,7 @@ w_G: 1 w_U: 0.5 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 10, 10, 10, 10, 15000, 15000, 15000, +q_vector: [175, 175, 175, 10, 10, 10, 10, 5000, 5000, 5000, 5, 5, 10, 1, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index db41d82c7d..3b037d92cc 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -21,7 +21,7 @@ workspace_margins: 0.05 u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] -mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] +mu: [0.4, 0.4, 0.4, 0.1, 0.1, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index fcd7090eab..2140bf9708 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 29aa971d72..2ed21f5e64 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -140,7 +140,9 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( } // end_effector_position(0) = 0.55; // end_effector_position(1) = 0.1 * sin(3 * context.get_time()); -// end_effector_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()) - end_effector_thickness_; +// end_effector_position(1) = 0.1 * (int) (2 * sin(context.get_time())); + // end_effector_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()) - end_effector_thickness_; +// end_effector_position(2) = 0.45 - end_effector_thickness_; target->SetFromVector(end_effector_position); } @@ -163,7 +165,9 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( tray_position(2) += radio_out->channel[2] * z_scale_; // tray_position(0) = 0.55; // tray_position(1) = 0.1 * sin(3 * context.get_time()); -// tray_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()); +// tray_position(1) = 0.1 * (int) (2 * sin(context.get_time())); + // tray_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()); +// tray_position(2) = 0.45; target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat target->SetFromVector(target_tray_state); } diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 4a4d9c1963..abb81fc352 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,8 +15,8 @@ - - + + From 42f31f12a4fe64e772c09da19434684ea0ba0ce7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 20 Jan 2024 19:26:03 -0500 Subject: [PATCH 620/758] using better predicted state --- systems/controllers/c3_controller.cc | 65 ++++++++++++++++++---------- 1 file changed, 41 insertions(+), 24 deletions(-) diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index c5de8768b3..6710700bc7 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -92,27 +92,32 @@ C3Controller::C3Controller( for (int i : vector({0})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.world_x_limits[0], c3_options_.world_x_limits[1], 1); + c3_->AddLinearConstraint(A, c3_options_.world_x_limits[0], + c3_options_.world_x_limits[1], 1); } for (int i : vector({1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.world_y_limits[0], c3_options_.world_y_limits[1], 1); + c3_->AddLinearConstraint(A, c3_options_.world_y_limits[0], + c3_options_.world_y_limits[1], 1); } for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.world_z_limits[0], c3_options_.world_z_limits[1], 1); + c3_->AddLinearConstraint(A, c3_options_.world_z_limits[0], + c3_options_.world_z_limits[1], 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.u_horizontal_limits[0], c3_options_.u_horizontal_limits[1], 2); + c3_->AddLinearConstraint(A, c3_options_.u_horizontal_limits[0], + c3_options_.u_horizontal_limits[1], 2); } for (int i : vector({2})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.u_vertical_limits[0], c3_options_.u_vertical_limits[1], 2); + c3_->AddLinearConstraint(A, c3_options_.u_vertical_limits[0], + c3_options_.u_vertical_limits[1], 2); } lcs_state_input_port_ = @@ -175,15 +180,20 @@ drake::systems::EventStatus C3Controller::ComputePlan( // TODO(yangwill): clean this up if (c3_options_.use_predicted_x0 && !x_pred_.isZero()) { - x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, x_lcs[0] + 10 * dt_ * dt_); - x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, x_lcs[1] + 10 * dt_ * dt_); - x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 10 * dt_ * dt_, x_lcs[2] + 10 * dt_ * dt_); -// x_lcs.head(3) = x_pred_.head(3); - x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, x_lcs[n_q_ + 0] + 10 * dt_); - x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, x_lcs[n_q_ + 1] + 10 * dt_); - x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, x_lcs[n_q_ + 2] + 10 * dt_); -// x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); - + x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, + x_lcs[0] + 10 * dt_ * dt_); + x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, + x_lcs[1] + 10 * dt_ * dt_); + x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 10 * dt_ * dt_, + x_lcs[2] + 10 * dt_ * dt_); + // x_lcs.head(3) = x_pred_.head(3); + x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, + x_lcs[n_q_ + 0] + 10 * dt_); + x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, + x_lcs[n_q_ + 1] + 10 * dt_); + x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, + x_lcs[n_q_ + 2] + 10 * dt_); + // x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); } discrete_state->get_mutable_value(plan_start_time_index_)[0] = @@ -193,12 +203,18 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector(N_ + 1, x_des.value()); // Force Checking of Workspace Limits - DRAKE_DEMAND(lcs_x->get_data()[0] > c3_options_.world_x_limits[0] - c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[0] < c3_options_.world_x_limits[1] + c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[1] > c3_options_.world_y_limits[0] - c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[1] < c3_options_.world_y_limits[1] + c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[2] > c3_options_.world_z_limits[0] - c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[2] < c3_options_.world_z_limits[1] + c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[0] > + c3_options_.world_x_limits[0] - c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[0] < + c3_options_.world_x_limits[1] + c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[1] > + c3_options_.world_y_limits[0] - c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[1] < + c3_options_.world_y_limits[1] + c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[2] > + c3_options_.world_z_limits[0] - c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data()[2] < + c3_options_.world_z_limits[1] + c3_options_.workspace_margins); c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); @@ -236,10 +252,11 @@ void C3Controller::OutputC3Solution( z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } - if (filtered_solve_time_ < dt_) { - double weight = (dt_ - filtered_solve_time_) / dt_; - x_pred_ = weight * z_sol[0].segment(0, n_x_) + - (1 - weight) * z_sol[1].segment(0, n_x_); + if (filtered_solve_time_ < N_ * dt_) { + int index = filtered_solve_time_ / dt_; + double weight = ((index + 1) * dt_ - filtered_solve_time_) / dt_; + x_pred_ = weight * z_sol[index].segment(0, n_x_) + + (1 - weight) * z_sol[index + 1].segment(0, n_x_); } else { x_pred_ = z_sol[1].segment(0, n_x_); } From e2bae3171cd0e15475d6635ba73b9d39473525fc Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 12:55:25 -0500 Subject: [PATCH 621/758] more consistent transition between teleop and mpc --- .../systems/end_effector_force_trajectory.cc | 28 +++++++++++++++++-- .../systems/end_effector_force_trajectory.h | 2 ++ .../franka/systems/end_effector_trajectory.cc | 26 ++++++++++++++++- .../franka/systems/end_effector_trajectory.h | 2 ++ 4 files changed, 55 insertions(+), 3 deletions(-) diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index 7639454b52..6af1c79834 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -42,6 +42,9 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator( this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); + controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + DeclareForcedDiscreteUpdateEvent( + &EndEffectorForceTrajectoryGenerator::DiscreteVariableUpdate); PiecewisePolynomial empty_pp_traj(Vector3d::Zero()); Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort( @@ -49,6 +52,25 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator( &EndEffectorForceTrajectoryGenerator::CalcTraj); } + +EventStatus EndEffectorForceTrajectoryGenerator::DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { + + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + bool using_c3 = context.get_discrete_state(controller_switch_index_)[0]; + if (!using_c3 && radio_out->channel[14] == 0) { + if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.04) { + discrete_state->get_mutable_value(controller_switch_index_)[0] = 1; + } + } + return EventStatus::Succeeded(); +} + void EndEffectorForceTrajectoryGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { @@ -64,8 +86,10 @@ void EndEffectorForceTrajectoryGenerator::CalcTraj( if (!radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); } else { - *casted_traj = *(PiecewisePolynomial*)dynamic_cast< - const PiecewisePolynomial*>(&trajectory_input); + if (context.get_discrete_state(controller_switch_index_)[0]){ + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } } } diff --git a/examples/franka/systems/end_effector_force_trajectory.h b/examples/franka/systems/end_effector_force_trajectory.h index 0e35d01049..5eb48cfb7f 100644 --- a/examples/franka/systems/end_effector_force_trajectory.h +++ b/examples/franka/systems/end_effector_force_trajectory.h @@ -34,6 +34,8 @@ class EndEffectorForceTrajectoryGenerator void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; + drake::systems::DiscreteStateIndex controller_switch_index_; + const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; const drake::multibody::Frame& world_; diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index b63dc83b01..3675751bcd 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -45,12 +45,35 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); + controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + DeclareForcedDiscreteUpdateEvent( + &EndEffectorTrajectoryGenerator::DiscreteVariableUpdate); PiecewisePolynomial empty_pp_traj(neutral_pose_); Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, &EndEffectorTrajectoryGenerator::CalcTraj); } + +EventStatus EndEffectorTrajectoryGenerator::DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { + + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + bool using_c3 = context.get_discrete_state(controller_switch_index_)[0]; + if (!using_c3 && radio_out->channel[14] == 0) { + if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.04) { + discrete_state->get_mutable_value(controller_switch_index_)[0] = 1; + } + } + return EventStatus::Succeeded(); +} + + void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale) { @@ -85,13 +108,14 @@ void EndEffectorTrajectoryGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); + if (radio_out->channel[14]) { *casted_traj = GeneratePose(context); } else { if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { - if ((context.get_time() - trajectory_input.start_time()) < 0.075){ + if (context.get_discrete_state(controller_switch_index_)[0]){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index 3c55ddafca..af93ff0dc4 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -43,6 +43,8 @@ class EndEffectorTrajectoryGenerator drake::systems::Context* context_; const drake::multibody::Frame& world_; + drake::systems::DiscreteStateIndex controller_switch_index_; + drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; From cc3f4b46dc11a83c8f23acd2b8353298b9ae844e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 12:55:41 -0500 Subject: [PATCH 622/758] varying tray mass --- .../franka/parameters/franka_c3_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/tray.sdf | 8 ++++---- examples/franka/urdf/tray_lcs.sdf | 8 ++++---- 4 files changed, 10 insertions(+), 10 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index f5d6f7aa1f..a38629a78b 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -8,7 +8,7 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -tray_model: examples/franka/urdf/tray.sdf +tray_model: examples/franka/urdf/tray_lcs.sdf left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 08b679aa3a..667ebbb168 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -60,5 +60,5 @@ q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] visualize_workspace: false visualize_pose_trace: true visualize_center_of_mass_plan: true -visualize_c3_forces: false +visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 4ddd39833e..0f794fed60 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -4,16 +4,16 @@ 0 0 0 0 0 0 - 0.97 + 1.25 - 0.012712 + 0.016381 0 0 - 0.012712 + 0.016381 0 - 0.025345 + 0.032661 diff --git a/examples/franka/urdf/tray_lcs.sdf b/examples/franka/urdf/tray_lcs.sdf index 511cbf0a36..0f5862fe11 100644 --- a/examples/franka/urdf/tray_lcs.sdf +++ b/examples/franka/urdf/tray_lcs.sdf @@ -4,16 +4,16 @@ 0 0 0 0 0 0 - 0.97 + 1 - 0.012712 + 0.013105 0 0 - 0.012712 + 0.013105 0 - 0.025345 + 0.026129 From f270914cf4539d9dee09e8d6a7ecf1ef3ec9a9eb Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 12:55:53 -0500 Subject: [PATCH 623/758] plot and vis updates --- .../pydairlib/analysis/log_plotter_franka.py | 18 ++++---- .../franka_hardware_plot_config.yaml | 43 +++++++++++++++++++ .../visualization/lcm_visualization_systems.h | 2 +- 3 files changed, 53 insertions(+), 10 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index fed4947317..b8d9a33779 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -14,10 +14,10 @@ def main(): - config_file = ('bindings/pydairlib/analysis/plot_configs' - '/franka_translation_plot.yaml') # config_file = ('bindings/pydairlib/analysis/plot_configs' - # '/franka_sim_plot_config.yaml') + # '/franka_hardware_plot_config.yaml') + config_file = ('bindings/pydairlib/analysis/plot_configs' + '/franka_sim_plot_config.yaml') plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x @@ -161,16 +161,16 @@ def main(): if plot_config.plot_end_effector: end_effector_plotter = plot_styler.PlotStyler(nrows=2) mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, - franka_context, ['plate'], - {'plate': np.zeros(3)}, - {'plate': [0, 1, 2]}, + franka_context, ['end_effector'], + {'end_effector': np.zeros(3)}, + {'end_effector': [0, 1, 2]}, ps=end_effector_plotter, subplot_index=0) mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, - franka_context, ['plate'], - {'plate': np.zeros(3)}, - {'plate': [0, 1, 2]}, + franka_context, ['end_effector'], + {'end_effector': np.zeros(3)}, + {'end_effector': [0, 1, 2]}, ps=end_effector_plotter, subplot_index=1) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml new file mode 100644 index 0000000000..14ac9156b6 --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -0,0 +1,43 @@ +# LCM channels to read data from +channel_x: "FRANKA_STATE" +channel_u: "OSC_FRANKA" +channel_osc: "OSC_DEBUG_FRANKA" +channel_c3: "C3_DEBUG" +channel_tray: "TRAY_STATE" +channel_c3_target: "C3_TARGET" +channel_c3_actual: "C3_ACTUAL" +plot_style: 'compact' # compact, paper, default + +start_time: 0 +#duration: 0.47 +duration: -1 +# Plant properties + +# Desired RobotOutput plots +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +plot_commanded_efforts: false +plot_contact_forces: false +plot_end_effector: true + +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Finite State Machine Names +fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] + +# Desired osc plots +plot_qp_costs: false +plot_qp_solve_time: true +plot_qp_solutions: true +plot_tracking_costs: false +plot_active_tracking_datas: false +tracking_datas_to_plot: + end_effector_target: {'dims': [0], 'derivs': ['accel']} +# end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} +# end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +plot_c3_debug: true +plot_c3_tracking: true +plot_object_state: true \ No newline at end of file diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index d5397652f2..b2179fa1b3 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -137,7 +137,7 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); int N_ = 5; const double radius_ = 0.002; - const double newtons_per_meter_ = 20; + const double newtons_per_meter_ = 40; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, From ceb6b00aaa64e63f86de8956fe22d3ae590d5ad9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 14:06:17 -0500 Subject: [PATCH 624/758] eliminating extra geom geom call --- examples/franka/franka_c3_controller.cc | 4 +- systems/controllers/c3/lcs_factory_system.cc | 48 ++----------------- systems/controllers/c3/lcs_factory_system.h | 12 +---- .../c3_output_systems.cc | 37 ++++++-------- .../c3_output_systems.h | 16 ++----- 5 files changed, 24 insertions(+), 93 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 4860547be3..5cb965c184 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -287,9 +287,7 @@ int DoMain(int argc, char* argv[]) { builder.Connect(controller->get_output_port_c3_solution(), c3_trajectory_generator->get_input_port_c3_solution()); builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), - c3_output_sender->get_input_port_lcs_contact_jacobian()); - builder.Connect(lcs_factory->get_output_port_lcs_contact_points(), - c3_output_sender->get_input_port_lcs_contact_points()); + c3_output_sender->get_input_port_lcs_contact_info()); builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), actor_trajectory_sender->get_input_port()); builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 3f77e76bac..21b0f1deb7 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -75,14 +75,9 @@ LCSFactorySystem::LCSFactorySystem( .get_index(); lcs_contact_jacobian_port_ = this->DeclareAbstractOutputPort( - "J_lcs", Eigen::MatrixXd(n_x_, n_lambda_), + "J_lcs, p_lcs", std::pair(Eigen::MatrixXd(n_x_, n_lambda_), std::vector()), &LCSFactorySystem::OutputLCSContactJacobian) .get_index(); - - lcs_contact_points_port_ = this->DeclareAbstractOutputPort( - "p_lcs", std::vector(), - &LCSFactorySystem::OutputLCSContactPoints) - .get_index(); } void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, @@ -123,7 +118,7 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, } void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context& context, - Eigen::MatrixXd* output_jacobian) const { + std::pair>* output) const { const TimestampedVector* lcs_x = (TimestampedVector*)this->EvalVectorInput(context, lcs_state_input_port_); @@ -146,48 +141,11 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context contact_points; - std::tie(*output_jacobian, contact_points) = LCSFactory::ComputeContactJacobian( + *output = LCSFactory::ComputeContactJacobian( plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); } -void LCSFactorySystem::OutputLCSContactPoints(const drake::systems::Context& context, - std::vector* contact_points) const { - const TimestampedVector* lcs_x = - (TimestampedVector*)this->EvalVectorInput(context, - lcs_state_input_port_); - - VectorXd q_v_u = - VectorXd::Zero(plant_.num_positions() + plant_.num_velocities() + - plant_.num_actuators()); - // u is irrelevant in pure geometric/kinematic calculation - q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); - - plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); - multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); - solvers::ContactModel contact_model; - if (c3_options_.contact_model == "stewart_and_trinkle") { - contact_model = solvers::ContactModel::kStewartAndTrinkle; - } else if (c3_options_.contact_model == "anitescu") { - contact_model = solvers::ContactModel::kAnitescu; - } else { - throw std::runtime_error("unknown or unsupported contact model"); - } - - MatrixXd contact_jacobian; - contact_points->clear(); - std::tie(contact_jacobian, *contact_points) = LCSFactory::ComputeContactJacobian( - plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, - c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, - c3_options_.N, contact_model); - -// for (auto& contact_point : witness_points_){ -// contact_points->push_back(contact_point); -// } -} - - - } // namespace systems } // namespace dairlib diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h index dd7f077880..50030e8c01 100644 --- a/systems/controllers/c3/lcs_factory_system.h +++ b/systems/controllers/c3/lcs_factory_system.h @@ -40,10 +40,6 @@ class LCSFactorySystem : public drake::systems::LeafSystem { return this->get_output_port(lcs_contact_jacobian_port_); } - const drake::systems::OutputPort& get_output_port_lcs_contact_points() const { - return this->get_output_port(lcs_contact_points_port_); - } - private: drake::systems::EventStatus UpdateLCS( const drake::systems::Context& context, @@ -51,15 +47,12 @@ class LCSFactorySystem : public drake::systems::LeafSystem { void OutputLCS(const drake::systems::Context& context, solvers::LCS* output_traj) const; void OutputLCSContactJacobian(const drake::systems::Context& context, - Eigen::MatrixXd* output_jacobian) const; - void OutputLCSContactPoints(const drake::systems::Context& context, - std::vector* contact_points) const; + std::pair>*) const; drake::systems::InputPortIndex lcs_state_input_port_; // drake::systems::InputPortIndex lcs_inputs_input_port_; drake::systems::OutputPortIndex lcs_port_; drake::systems::OutputPortIndex lcs_contact_jacobian_port_; - drake::systems::OutputPortIndex lcs_contact_points_port_; const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; @@ -70,9 +63,6 @@ class LCSFactorySystem : public drake::systems::LeafSystem { C3Options c3_options_; -// mutable std::vector witness_points_; -// mutable Eigen::MatrixXd contact_jacobian_; - // convenience for variable sizes int n_q_; int n_v_; diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index bf5689c3ee..40025496f2 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -22,12 +22,8 @@ C3OutputSender::C3OutputSender() { this->DeclareAbstractInputPort("c3_intermediates", drake::Value{}) .get_index(); - lcs_contact_jacobian_port_ = - this->DeclareAbstractInputPort("J_lcs", drake::Value()) - .get_index(); - lcs_contact_points_port_ = - this->DeclareAbstractInputPort("p_lcs", - drake::Value>()) + lcs_contact_info_port_ = + this->DeclareAbstractInputPort("J_lcs, p_lcs", drake::Value>>()) .get_index(); this->set_name("c3_output_sender"); @@ -39,11 +35,6 @@ C3OutputSender::C3OutputSender() { "lcmt_c3_force", dairlib::lcmt_c3_forces(), &C3OutputSender::OutputC3Forces) .get_index(); -// lcs_inputs_output_port_ = -// this->DeclareVectorOutputPort("u_lcs", -// drake::systems::BasicVector(3), -// &C3OutputSender::OutputNextC3Input) -// .get_index(); } void C3OutputSender::OutputC3Lcm(const drake::systems::Context& context, @@ -63,34 +54,34 @@ void C3OutputSender::OutputC3Forces( dairlib::lcmt_c3_forces* c3_forces_output) const { const auto& c3_solution = this->EvalInputValue(context, c3_solution_port_); - const auto& J_c = - this->EvalInputValue(context, lcs_contact_jacobian_port_); - const auto& contact_points = this->EvalInputValue>( - context, lcs_contact_points_port_); + const auto& contact_info = + this->EvalInputValue>>(context, lcs_contact_info_port_); + MatrixXd J_c = contact_info->first; + auto contact_points = contact_info->second; c3_forces_output->num_forces = c3_solution->lambda_sol_.rows(); c3_forces_output->forces.resize(c3_forces_output->num_forces); - int forces_per_contact = J_c->rows() / contact_points->size(); + int forces_per_contact = contact_info->first.rows() / contact_points.size(); int contact_var_start; - for (int contact_index = 0; contact_index < contact_points->size(); + for (int contact_index = 0; contact_index < contact_points.size(); ++contact_index) { contact_var_start = forces_per_contact * contact_index; for (int i = 0; i < forces_per_contact; ++i) { auto force = lcmt_force(); - force.contact_point[0] = contact_points->at(contact_index)[0]; - force.contact_point[1] = contact_points->at(contact_index)[1]; - force.contact_point[2] = contact_points->at(contact_index)[2]; + force.contact_point[0] = contact_points.at(contact_index)[0]; + force.contact_point[1] = contact_points.at(contact_index)[1]; + force.contact_point[2] = contact_points.at(contact_index)[2]; // 6, 7, 8 are the indices for the x,y,z components of the tray // TODO(yangwill): find a cleaner way to figure out the equivalent forces // expressed in the world frame force.contact_force[0] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c->row(contact_var_start + i)(6); + J_c.row(contact_var_start + i)(6); force.contact_force[1] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c->row(contact_var_start + i)(7); + J_c.row(contact_var_start + i)(7); force.contact_force[2] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c->row(contact_var_start + i)(8); + J_c.row(contact_var_start + i)(8); c3_forces_output->forces[contact_var_start + i] = force; } } diff --git a/systems/trajectory_optimization/c3_output_systems.h b/systems/trajectory_optimization/c3_output_systems.h index 904db68736..1975721240 100644 --- a/systems/trajectory_optimization/c3_output_systems.h +++ b/systems/trajectory_optimization/c3_output_systems.h @@ -26,14 +26,9 @@ class C3OutputSender : public drake::systems::LeafSystem { return this->get_input_port(c3_intermediates_port_); } - const drake::systems::InputPort& get_input_port_lcs_contact_jacobian() + const drake::systems::InputPort& get_input_port_lcs_contact_info() const { - return this->get_input_port(lcs_contact_jacobian_port_); - } - - const drake::systems::InputPort& get_input_port_lcs_contact_points() - const { - return this->get_input_port(lcs_contact_points_port_); + return this->get_input_port(lcs_contact_info_port_); } const drake::systems::OutputPort& get_output_port_c3_debug() const { @@ -57,13 +52,12 @@ class C3OutputSender : public drake::systems::LeafSystem { void OutputC3Forces(const drake::systems::Context& context, dairlib::lcmt_c3_forces* c3_forces_output) const; - void OutputNextC3Input(const drake::systems::Context& context, - drake::systems::BasicVector* u_next) const; +// void OutputNextC3Input(const drake::systems::Context& context, +// drake::systems::BasicVector* u_next) const; drake::systems::InputPortIndex c3_solution_port_; drake::systems::InputPortIndex c3_intermediates_port_; - drake::systems::InputPortIndex lcs_contact_jacobian_port_; - drake::systems::InputPortIndex lcs_contact_points_port_; + drake::systems::InputPortIndex lcs_contact_info_port_; drake::systems::OutputPortIndex lcm_c3_output_port_; drake::systems::OutputPortIndex lcs_forces_output_port_; // drake::systems::OutputPortIndex lcs_inputs_output_port_; From a52a3424b6003992addb7e20131348624c56b29b Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 15:19:09 -0500 Subject: [PATCH 625/758] tweaking parameters for more consistent task completion --- .../franka_c3_options_side_supports.yaml | 2 +- .../franka/systems/end_effector_trajectory.cc | 2 +- examples/franka/urdf/tray.sdf | 8 ++++---- systems/controllers/c3_controller.cc | 2 +- .../lcm_visualization_systems.cc | 20 +++++++++---------- 5 files changed, 17 insertions(+), 17 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 9fc27b909c..0920f26667 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -10,7 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true -solve_time_filter_alpha: 0.9 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} +solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} # Workspace Limits world_x_limits: [0.45, 0.65] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 3675751bcd..c1356a5aa4 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -66,7 +66,7 @@ EventStatus EndEffectorTrajectoryGenerator::DiscreteVariableUpdate( ->get_value>(); bool using_c3 = context.get_discrete_state(controller_switch_index_)[0]; if (!using_c3 && radio_out->channel[14] == 0) { - if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.04) { + if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.05) { discrete_state->get_mutable_value(controller_switch_index_)[0] = 1; } } diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 0f794fed60..a874f8097b 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -4,16 +4,16 @@ 0 0 0 0 0 0 - 1.25 + 1 - 0.016381 + 0.013105 0 0 - 0.016381 + 0.013105 0 - 0.032661 + 0.026129 diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 6710700bc7..957acaf9a0 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -244,7 +244,7 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = t + i * dt_; + c3_solution->time_vector_(i) = t + 0.25 * filtered_solve_time_ + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index c79e70dba0..b3125d00f9 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -292,7 +292,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( auto force_norm = force.norm(); const std::string& force_path_root = force_path_ + "/lcs_force_" + std::to_string(i) + "/"; - if (force_norm >= 0.01) { + if (force_norm >= 0.5) { if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, {1, 0, 0, 1}); @@ -369,12 +369,12 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( {0, 1, 0, 1}); meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, {0, 0, 1, 1}); - meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, - {1, 0, 0, 1}); - meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, - {0, 1, 0, 1}); - meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, - {0, 0, 1, 1}); +// meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, +// {1, 0, 0, 1}); +// meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, +// {0, 1, 0, 1}); +// meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, +// {0, 0, 1, 1}); auto x_axis_transform = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), Vector3d{0.075, 0.0, 0.0}); @@ -402,9 +402,9 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); +// meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); +// meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); +// meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); } From 0b441b7d700ab3fd3b670ba41e1c834d10870965 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 15:46:54 -0500 Subject: [PATCH 626/758] c3 gains for parameter study --- examples/franka/parameters/franka_c3_options_side_supports.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 0920f26667..364f63c63d 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -38,7 +38,7 @@ w_G: 0.1 w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 150, 100, 0, 1, 1, 0, 17500, 15000, 15000, +q_vector: [150, 150, 100, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 10, 100, 1, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal r_vector: [0.1, 0.1, 0.1] From eb8bfc1aa6fcf3fc5b2125ec2ff6c79b80fb555e Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 22 Jan 2024 17:34:15 -0500 Subject: [PATCH 627/758] adding code for parameter sweeps --- bindings/pydairlib/analysis/BUILD.bazel | 1 - .../analysis/tray_balance_study/BUILD.bazel | 25 +++++ .../tray_parameter_study.py | 100 ++++++++++++++++++ examples/franka/franka_osc_controller.cc | 15 +-- .../parameters/franka_osc_controller_params.h | 2 + .../franka_osc_controller_params.yaml | 3 +- .../franka/parameters/franka_sim_params.yaml | 8 +- 7 files changed, 142 insertions(+), 12 deletions(-) create mode 100644 bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel create mode 100644 bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 04f0034f08..0b685a6721 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -142,7 +142,6 @@ py_binary( "//bindings/pydairlib/lcm", "//bindings/pydairlib/multibody:kinematic_py", "//bindings/pydairlib/multibody:multibody_py", - "//lcmtypes:lcmtypes_robot_archive_py", "//lcmtypes:lcmtypes_robot_py", ], ) diff --git a/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel b/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel new file mode 100644 index 0000000000..a267a628ec --- /dev/null +++ b/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel @@ -0,0 +1,25 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +py_binary( + name = "tray_parameter_study", + srcs = ["tray_parameter_study.py"], + data = [ + "@drake//manipulation/models/franka_description:models", + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/common", + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py new file mode 100644 index 0000000000..5818902eb0 --- /dev/null +++ b/bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py @@ -0,0 +1,100 @@ +import subprocess +import time +from tqdm import * +import lcm +import dairlib.lcmt_radio_out + +import numpy as np +def main(): + trajectory_path = "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/" + gains_path = 'examples/franka/parameters/' + model_path = 'examples/franka/urdf/' + results_folder = '/media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_22_24/parameter_study' + sim_time = 10.0 + cooldown_time = 10.0 + start_time = 0 + realtime_rate = 1.0 + num_trials = 10 + + sim_cmd = 'bazel-bin/examples/franka/franka_sim' + osc_cmd = 'bazel-bin/examples/franka/franka_osc_controller' + c3_cmd = 'bazel-bin/examples/franka/franka_c3_controller' + fix_inertia_cmd = 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' + + # Add an extra second to the runtime of the simulator process to account for start up and stopping time + sim_run_time = sim_time / realtime_rate + 1.0 + c3_start_up_time = 4.0 + controller_startup_time = 0.1 + lcm_logger_cmd = '' + publisher = lcm.LCM() + + + gain_filename = 'franka_c3_options_side_supports.yaml' + model_filename = 'tray.sdf' + # parameter = 'mu_c3' + parameter = 'mass_real' + + nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' + nominal_tray_mass = '1' + + initial_radio_msg = dairlib.lcmt_radio_out() + start_c3_radio_msg = dairlib.lcmt_radio_out() + initial_radio_msg.channel[13] = 1 + initial_radio_msg.channel[11] = 1 + initial_radio_msg.channel[14] = 1 + start_c3_radio_msg.channel[13] = 1 + start_c3_radio_msg.channel[11] = 1 + start_c3_radio_msg.channel[14] = 0 + + mu_range = np.arange(0.3, 0.8, 0.01) + mass_range = np.arange(0.5, 2.0, 0.05) + + # for i in range(0, disturbances.shape[0]): + for i in trange(mu_range.shape[0]): + for j in trange(num_trials): + log_path = results_folder + '/' + parameter + '/simlog-' + '%02d_%1d' % (i, j) + + modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) + modified_mass_value = ' %.1f ' % (mass_range[i]) + + # f = open(gains_path + gain_filename, 'r') + f = open(model_path + model_filename, 'r') + + filedata = f.read() + f.close() + # newdata = filedata.replace(nominal_mu_value, modified_mu_value) + newdata = filedata.replace(nominal_tray_mass, modified_mass_value) + + # f = open(gains_path + 'franka_c3_options_parameter_sweep.yaml', 'w') + f = open(model_path + 'tray_parameter_sweep.sdf', 'w') + f.write(newdata) + f.close() + fix_inertia_process = subprocess.Popen(fix_inertia_cmd.split(' ')) + time.sleep(1.0) + + lcm_logger_cmd = ['lcm-logger', + '-f', + '%s' % log_path, + ] + + osc_process = subprocess.Popen(osc_cmd) + c3_process = subprocess.Popen(c3_cmd) + sim_process = subprocess.Popen(sim_cmd) + time.sleep(controller_startup_time) + publisher.publish("RADIO", initial_radio_msg.encode()) + logger_process = subprocess.Popen(lcm_logger_cmd) + time.sleep(c3_start_up_time) + publisher.publish("RADIO", start_c3_radio_msg.encode()) + time.sleep(sim_run_time) + osc_process.kill() + c3_process.kill() + sim_process.kill() + logger_process.kill() + time.sleep(cooldown_time) + +if __name__ == "__main__": + main() + # construct_success_plot() + # convert_logs_to_costs() + # plot_success() + # plot_costs() diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index d1b0f7ec14..0545fdfeea 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -159,10 +159,14 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.radio_channel, &lcm)); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), false); - auto osc_debug_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.osc_debug_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + if (controller_params.publish_debug_info){ + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_debug_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); + } auto end_effector_position_tracking_data = std::make_unique( @@ -249,8 +253,7 @@ int DoMain(int argc, char* argv[]) { osc_command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_command(), osc_command_sender->get_input_port(0)); - builder.Connect(osc->get_output_port_osc_debug(), - osc_debug_pub->get_input_port()); + builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); builder.Connect(end_effector_trajectory_sub->get_output_port(), diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index a5fc7cf633..2138d28b64 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -14,6 +14,7 @@ struct FrankaControllerParams : OSCGains { bool track_end_effector_orientation; bool cancel_gravity_compensation; bool enforce_acceleration_constraints; + bool publish_debug_info; std::vector neutral_position; double x_scale; @@ -54,6 +55,7 @@ struct FrankaControllerParams : OSCGains { a->Visit(DRAKE_NVP(track_end_effector_orientation)); a->Visit(DRAKE_NVP(cancel_gravity_compensation)); a->Visit(DRAKE_NVP(enforce_acceleration_constraints)); + a->Visit(DRAKE_NVP(publish_debug_info)); a->Visit(DRAKE_NVP(EndEffectorW)); a->Visit(DRAKE_NVP(EndEffectorKp)); a->Visit(DRAKE_NVP(EndEffectorKd)); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 2140bf9708..1b419dd3a1 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -23,6 +23,8 @@ end_effector_acceleration: 10 track_end_effector_orientation: false cancel_gravity_compensation: false enforce_acceleration_constraints: false +publish_debug_info: false + W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] W_lambda_c_reg: [ 0.001, 0.001, 0.01, @@ -32,7 +34,6 @@ W_lambda_c_reg: [ 0.001, 0.001, 0.01, W_lambda_h_reg: [ 0.001, 0.001, 0.001, 0.001, 0.001, 0.001 ] - w_elbow: 1 elbow_kp: 200 elbow_kd: 10 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 667ebbb168..9f21ab7d66 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -3,7 +3,7 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf -tray_model: examples/franka/urdf/tray.sdf +tray_model: examples/franka/urdf/tray_parameter_sweep.sdf box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf @@ -13,7 +13,7 @@ visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 2 -visualize_drake_sim: true +visualize_drake_sim: false publish_efforts: true camera_pose: [[0.5, -1.2, 0.7], @@ -58,7 +58,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] visualize_workspace: false -visualize_pose_trace: true +visualize_pose_trace: false visualize_center_of_mass_plan: true -visualize_c3_forces: true +visualize_c3_forces: false visualize_c3_state: true From 6b65264df6da4b1de29e78fa5b1e4ed5c4c2532a Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 23 Jan 2024 13:02:36 -0500 Subject: [PATCH 628/758] updating plotting scripts --- .../pydairlib/analysis/mbp_plotting_utils.py | 5 +- .../analysis/tray_balance_study/BUILD.bazel | 21 ++++- .../parameter_study_analysis.py | 88 +++++++++++++++++++ .../parameter_study_config.yaml | 18 ++++ ...r_study.py => run_tray_parameter_study.py} | 55 ++++++------ bindings/pydairlib/common/plot_styler.py | 2 +- bindings/pydairlib/lcm/process_lcm_log.py | 4 +- 7 files changed, 158 insertions(+), 35 deletions(-) create mode 100644 bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py create mode 100644 bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml rename bindings/pydairlib/analysis/tray_balance_study/{tray_parameter_study.py => run_tray_parameter_study.py} (57%) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 92640a298f..d4984c1ce1 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -873,8 +873,9 @@ def generate_joint_limits(plant): return franka_joint_position_limit_range, franka_joint_velocity_limit_range, franka_joint_actuator_limit_range # Cannot plot multiple indices of the solution because the solution is already multi-dimensional (time) -def plot_c3_inputs(c3_output, time_slice, input_index): - ps = plot_styler.PlotStyler() +def plot_c3_inputs(c3_output, time_slice, input_index, ps=None): + if ps == None: + ps = plot_styler.PlotStyler() plotting_utils.make_plot( c3_output, 't', diff --git a/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel b/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel index a267a628ec..0ad3234d92 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel +++ b/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel @@ -12,8 +12,8 @@ load( ) py_binary( - name = "tray_parameter_study", - srcs = ["tray_parameter_study.py"], + name = "run_tray_parameter_study", + srcs = ["run_tray_parameter_study.py"], data = [ "@drake//manipulation/models/franka_description:models", "@lcm//:lcm-python", @@ -23,3 +23,20 @@ py_binary( "//lcmtypes:lcmtypes_robot_py", ], ) + +py_binary( + name = "parameter_study_analysis", + srcs = ["parameter_study_analysis.py"], + data = [ + ":parameter_study_config.yaml", + "//examples/franka:parameters", + "@drake//manipulation/models/franka_description:models", + "@lcm//:lcm-python", + ], + deps = [ + "//bindings/pydairlib/analysis:mbp_plotting_utils", + "//bindings/pydairlib/common", + "//bindings/pydairlib/lcm:process_lcm_log", + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py new file mode 100644 index 0000000000..5ed653eaa5 --- /dev/null +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -0,0 +1,88 @@ +import subprocess +import time +from tqdm import * +import lcm +from bindings.pydairlib.common import plot_styler, plotting_utils +import pydairlib.analysis.mbp_plotting_utils as mbp_plots +from bindings.pydairlib.lcm.process_lcm_log import get_log_data +import matplotlib.pyplot as plt +import numpy as np +import yaml +import dairlib + + +def process_c3_channel(data): + t = [] + x = [] + for msg in data: + t.append(msg.utime / 1e6) + x.append(msg.state) + t = np.array(t) + x = np.array(x) + + return {'t': t, + 'x': x} + +def load_c3_channels(data, c3_target_state_channel, c3_actual_state_channel, c3_debug_output_channel): + c3_target = process_c3_channel(data[c3_target_state_channel]) + c3_actual = process_c3_channel(data[c3_actual_state_channel]) + c3_output = mbp_plots.process_c3_debug(data[c3_debug_output_channel]) + return c3_target, c3_actual, c3_output + +def load_lcm_logs(): + config_file = 'parameter_study_config.yaml' + parameters_directory = 'examples/franka/parameters/' + lcm_channels_sim = 'lcm_channels_simulation.yaml' + + with open(parameters_directory + lcm_channels_sim) as f: + filedata = f.read() + lcm_channels = yaml.load(filedata) + + with open('bindings/pydairlib/analysis/tray_balance_study/' + config_file) as f: + filedata = f.read() + param_study = yaml.load(filedata) + + start_time = 0 + duration = -1 + + + c3_channels = {lcm_channels['c3_target_state_channel']: dairlib.lcmt_c3_state, + lcm_channels['c3_actual_state_channel']: dairlib.lcmt_c3_state, + lcm_channels['c3_debug_output_channel']: dairlib.lcmt_c3_output} + callback = load_c3_channels + mass_range = np.arange(0.5, 2.0, 0.05) + mu_range = np.arange(0.3, 0.8, 0.01) + + for i in range(mass_range.shape[0]): + print(mass_range[i]) + for j in range(10): + ps = plot_styler.PlotStyler(nrows=2) + log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%1d' % (i, j) + log = lcm.EventLog(log_filename, "r") + c3_target, c3_actual, c3_output = \ + get_log_data(log, c3_channels, start_time, duration, callback, + lcm_channels['c3_target_state_channel'], lcm_channels['c3_actual_state_channel'], + lcm_channels['c3_debug_output_channel']) + ps.plot(c3_target['t'], c3_target['x'][:, 7:10], subplot_index=1) + ps.plot(c3_actual['t'], c3_actual['x'][:, 7:10], subplot_index=1) + t_c3_slice = slice(c3_output['t'].size) + mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1, ps) + plt.show() + +def main(): + load_lcm_logs() + + + + + + + + + + + + + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml new file mode 100644 index 0000000000..dc071bd96c --- /dev/null +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -0,0 +1,18 @@ +trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ +gains_path: examples/franka/parameters/ +model_path: examples/franka/urdf/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_22_24/parameter_study/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_22_24/parameter_study/data/ +sim_cmd: bazel-bin/examples/franka/franka_sim +osc_cmd: bazel-bin/examples/franka/franka_osc_controller +c3_cmd: bazel-bin/examples/franka/franka_c3_controller +fix_inertia_cmd: 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' + +nominal_c3_gain_filename: franka_c3_options_side_supports.yaml +nominal_model_filename: tray.sdf + +modified_c3_gain_filename: franka_c3_options_parameter_sweep.yaml +modified_model_filename: tray_parameter_sweep.sdf + +parameter: ['mu_c3', 'mass_real', 'mu_real'] + diff --git a/bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py similarity index 57% rename from bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py rename to bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index 5818902eb0..e3bfa0297a 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -5,36 +5,33 @@ import dairlib.lcmt_radio_out import numpy as np +import yaml def main(): - trajectory_path = "/home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/" - gains_path = 'examples/franka/parameters/' - model_path = 'examples/franka/urdf/' - results_folder = '/media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_22_24/parameter_study' + config_file = 'parameter_study_config.yaml' sim_time = 10.0 cooldown_time = 10.0 start_time = 0 realtime_rate = 1.0 num_trials = 10 - - sim_cmd = 'bazel-bin/examples/franka/franka_sim' - osc_cmd = 'bazel-bin/examples/franka/franka_osc_controller' - c3_cmd = 'bazel-bin/examples/franka/franka_c3_controller' - fix_inertia_cmd = 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' - - # Add an extra second to the runtime of the simulator process to account for start up and stopping time sim_run_time = sim_time / realtime_rate + 1.0 c3_start_up_time = 4.0 controller_startup_time = 0.1 + + with open('bindings/pydairlib/analysis/tray_balance_study/' + config_file) as f: + filedata = f.read() + config = yaml.load(filedata) + + # Add an extra second to the runtime of the simulator process to account for start up and stopping time + lcm_logger_cmd = '' publisher = lcm.LCM() - - gain_filename = 'franka_c3_options_side_supports.yaml' - model_filename = 'tray.sdf' # parameter = 'mu_c3' - parameter = 'mass_real' + # parameter = 'mass_real' + parameter = 'mu_real' nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' + nominal_real_mu_value = '0.4' nominal_tray_mass = '1' initial_radio_msg = dairlib.lcmt_radio_out() @@ -49,37 +46,39 @@ def main(): mu_range = np.arange(0.3, 0.8, 0.01) mass_range = np.arange(0.5, 2.0, 0.05) - # for i in range(0, disturbances.shape[0]): for i in trange(mu_range.shape[0]): for j in trange(num_trials): - log_path = results_folder + '/' + parameter + '/simlog-' + '%02d_%1d' % (i, j) + log_path = config['results_folder'] + '/' + parameter + '/simlog-' + '%02d_%1d' % (i, j) - modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) - modified_mass_value = ' %.1f ' % (mass_range[i]) + # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) + # modified_mass_value = ' %.1f ' % (mass_range[i]) + modified_real_mu_value = '%.2f' % (mu_range[i]) # f = open(gains_path + gain_filename, 'r') - f = open(model_path + model_filename, 'r') + f = open(config['model_path'] + config['nominal_model_filename'], 'r') filedata = f.read() f.close() # newdata = filedata.replace(nominal_mu_value, modified_mu_value) - newdata = filedata.replace(nominal_tray_mass, modified_mass_value) + newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) + # newdata = filedata.replace(nominal_tray_mass, modified_mass_value) - # f = open(gains_path + 'franka_c3_options_parameter_sweep.yaml', 'w') - f = open(model_path + 'tray_parameter_sweep.sdf', 'w') + f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') + f = open(config['model_path'] + config['modified_model_filename'], 'w') f.write(newdata) f.close() - fix_inertia_process = subprocess.Popen(fix_inertia_cmd.split(' ')) - time.sleep(1.0) + if parameter == 'mass_real': + fix_inertia_process = subprocess.Popen(config['fix_inertia_cmd'].split(' ')) + time.sleep(1.0) lcm_logger_cmd = ['lcm-logger', '-f', '%s' % log_path, ] - osc_process = subprocess.Popen(osc_cmd) - c3_process = subprocess.Popen(c3_cmd) - sim_process = subprocess.Popen(sim_cmd) + osc_process = subprocess.Popen(config['osc_cmd']) + c3_process = subprocess.Popen(config['c3_cmd']) + sim_process = subprocess.Popen(config['sim_cmd']) time.sleep(controller_startup_time) publisher.publish("RADIO", initial_radio_msg.encode()) logger_process = subprocess.Popen(lcm_logger_cmd) diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index bd60329c7b..ea9f5b0224 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -36,7 +36,6 @@ def set_compact_styling(): def __init__(self, figure=None, nrows=1, ncols=1): - plt.subplots_adjust(left=0.1, right=0.85, bottom=0.15, top=0.75) # List is [left, bottom, width, height] # plt.subplots_adjust(left=0.0, right=1.0, bottom=0.0, top=1.0) # List is [left, bottom, width, height] # self.cmap = plt.get_cmap('tab10') self.cmap = plt.get_cmap('tab20') @@ -69,6 +68,7 @@ def __init__(self, figure=None, nrows=1, ncols=1): self.axes = [self.axes] # self.fig.add_axes([0.1, 0.15, 0.85, 0.75]) # List is [left, bottom, width, height] self.fig_id = self.fig.number + plt.subplots_adjust(left=0.1, right=0.85, bottom=0.15, top=0.75) # List is [left, bottom, width, height] return def attach(self): diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index c09ca6f8c6..2d54a947eb 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -22,8 +22,8 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca pass first_timestamp = lcm_log.read_next_event().timestamp start_timestamp = int(first_timestamp + start_time * 1e6) - print('Start time: ' + str(start_time)) - print('Duration: ' + str(duration)) + # print('Start time: ' + str(start_time)) + # print('Duration: ' + str(duration)) lcm_log.seek_to_timestamp(start_timestamp) t = lcm_log.read_next_event().timestamp lcm_log.seek_to_timestamp(start_timestamp) From b25079e7a82c16d4e168fd6bd13e05974c5e044e Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 23 Jan 2024 13:51:40 -0500 Subject: [PATCH 629/758] updating changes --- .../parameter_study_config.yaml | 10 +++--- .../run_tray_parameter_study.py | 14 +++++---- examples/franka/BUILD.bazel | 7 +++++ .../franka/parameters/franka_sim_params.yaml | 4 +-- .../parameters/lcm_channels_simulation.yaml | 16 +++++----- examples/franka/urdf/plate_end_effector.urdf | 1 - .../plate_end_effector_parameter_sweep.urdf | 31 +++++++++++++++++++ examples/franka/urdf/tray.sdf | 1 - solvers/c3_miqp.cc | 29 ++++++++--------- systems/controllers/c3_controller.cc | 2 +- 10 files changed, 76 insertions(+), 39 deletions(-) create mode 100644 examples/franka/urdf/plate_end_effector_parameter_sweep.urdf diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index dc071bd96c..63d457a6a0 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,18 +1,20 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_22_24/parameter_study/ -processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_22_24/parameter_study/data/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_23_24/parameter_study/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_23_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller fix_inertia_cmd: 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' nominal_c3_gain_filename: franka_c3_options_side_supports.yaml -nominal_model_filename: tray.sdf +#nominal_model_filename: tray.sdf +nominal_model_filename: plate_end_effector.urdf modified_c3_gain_filename: franka_c3_options_parameter_sweep.yaml -modified_model_filename: tray_parameter_sweep.sdf +#modified_model_filename: tray_parameter_sweep.sdf +modified_model_filename: plate_end_effector_parameter_sweep.sdf parameter: ['mu_c3', 'mass_real', 'mu_real'] diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index e3bfa0297a..661aeb4c09 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -28,10 +28,11 @@ def main(): # parameter = 'mu_c3' # parameter = 'mass_real' - parameter = 'mu_real' + parameter = config['parameter'][2] nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' - nominal_real_mu_value = '0.4' + # nominal_real_mu_value = '0.4' + nominal_real_mu_value = '' nominal_tray_mass = '1' initial_radio_msg = dairlib.lcmt_radio_out() @@ -43,16 +44,17 @@ def main(): start_c3_radio_msg.channel[11] = 1 start_c3_radio_msg.channel[14] = 0 - mu_range = np.arange(0.3, 0.8, 0.01) + mu_range = np.arange(0.3, 0.8, 0.05) mass_range = np.arange(0.5, 2.0, 0.05) for i in trange(mu_range.shape[0]): for j in trange(num_trials): - log_path = config['results_folder'] + '/' + parameter + '/simlog-' + '%02d_%1d' % (i, j) + log_path = config['results_folder'] + parameter + '/simlog-' + '%02d_%1d' % (i, j) # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) # modified_mass_value = ' %.1f ' % (mass_range[i]) - modified_real_mu_value = '%.2f' % (mu_range[i]) + # modified_real_mu_value = '%.2f' % (mu_range[i]) + modified_real_mu_value = '' % (mu_range[i]) # f = open(gains_path + gain_filename, 'r') f = open(config['model_path'] + config['nominal_model_filename'], 'r') @@ -63,7 +65,7 @@ def main(): newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) # newdata = filedata.replace(nominal_tray_mass, modified_mass_value) - f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') + # f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') f = open(config['model_path'] + config['modified_model_filename'], 'w') f.write(newdata) f.close() diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 2a7b99a3c9..28acd29322 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -10,6 +10,13 @@ cc_library( ]), ) +cc_library( + name = "parameters", + data = glob([ + "*yaml", + ]), +) + cc_library( name = "franka_hardware", deps = [], diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 9f21ab7d66..74123e0549 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,9 +1,9 @@ #franka_model: examples/franka/urdf/franka_no_collision.urdf franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf -end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_model: examples/franka/urdf/plate_end_effector_parameter_sweep.urdf table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf -tray_model: examples/franka/urdf/tray_parameter_sweep.sdf +tray_model: examples/franka/urdf/tray.sdf box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index 003e20c5dc..c053fa5f24 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -1,17 +1,17 @@ -franka_state_channel: FRANKA_STATE_SIMULATION -tray_state_channel: TRAY_STATE_SIMULATION -box_state_channel: BOX_STATE_SIMULATION -franka_input_channel: FRANKA_INPUT +franka_state_channel: FRANKA_STATE_SIMULATION # lcmt_robot_output +tray_state_channel: TRAY_STATE_SIMULATION # lcmt_object_state +box_state_channel: BOX_STATE_SIMULATION # lcmt_object_state +franka_input_channel: FRANKA_INPUT # lcmt_robot_input franka_input_echo: FRANKA_INPUT_ECHO osc_channel: OSC_FRANKA osc_debug_channel: OSC_DEBUG_FRANKA -c3_actor_channel: C3_TRAJECTORY_ACTOR -c3_object_channel: C3_TRAJECTORY_TRAY +c3_actor_channel: C3_TRAJECTORY_ACTOR # lcmt_timestamped_saved_traj +c3_object_channel: C3_TRAJECTORY_TRAY # lcmt_timestamped_saved_traj c3_force_channel: C3_FORCES c3_debug_output_channel: C3_DEBUG -c3_target_state_channel: C3_TARGET -c3_actual_state_channel: C3_ACTUAL +c3_target_state_channel: C3_TARGET # lcmt_c3_state +c3_actual_state_channel: C3_ACTUAL # lcmt_c3_state radio_channel: RADIO diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index abb81fc352..9d55c0ef85 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -16,7 +16,6 @@ - diff --git a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf new file mode 100644 index 0000000000..9d55c0ef85 --- /dev/null +++ b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf @@ -0,0 +1,31 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index a874f8097b..b1984f4656 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -42,7 +42,6 @@ 0.18 10 0.4 - 0.4 diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 5767ad5007..650fa130a6 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -7,22 +7,22 @@ using Eigen::MatrixXd; using Eigen::VectorXd; using std::vector; -C3MIQP::C3MIQP(const LCS& LCS, const CostMatrices& costs, - const vector& xdesired, const C3Options& options) +C3MIQP::C3MIQP(const LCS &LCS, const CostMatrices &costs, + const vector &xdesired, const C3Options &options) : C3(LCS, costs, xdesired, options), env_(true) { // Create an environment // env_.set("LogToConsole", "0"); env_.set("OutputFlag", "0"); - env_.set("Threads", "2"); + env_.set("Threads", "0"); env_.start(); } -VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, - const VectorXd& delta_c, - const MatrixXd& E, const MatrixXd& F, - const MatrixXd& H, const VectorXd& c, +VectorXd C3MIQP::SolveSingleProjection(const MatrixXd &U, + const VectorXd &delta_c, + const MatrixXd &E, const MatrixXd &F, + const MatrixXd &H, const VectorXd &c, const int admm_iteration, - const int& warm_start_index) { + const int &warm_start_index) { // set up linear term in cost VectorXd cost_lin = -2 * delta_c.transpose() * U; @@ -37,16 +37,13 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, MatrixXd Mcons2(m_, n_ + m_ + k_); Mcons2 << MM1, MM2, MM3; - // Create an empty model -// GRBEnv env = GRBEnv(); -// env.start(); -// env_.start(); - GRBModel model = GRBModel(env_); // model.set(GRB_IntParam_LogToConsole, 1); // model.set(GRB_StringParam_LogFile, "grb_debug"); - // model.set("FeasibilityTol", "0.01"); - // model.set("IterationLimit", "40"); +// model.set("Cutoff", "0.001"); +// model.set("FeasibilityTol", "0.00001"); +// model.set("FeasibilityTol", "0.01"); +// model.set("IterationLimit", "40"); GRBVar delta_k[n_ + m_ + k_]; GRBVar binary[m_]; @@ -60,7 +57,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, } for (int i = 0; i < n_ + m_ + k_; i++) { - delta_k[i] = model.addVar(-10000.0, 10000.0, 0.0, GRB_CONTINUOUS); + delta_k[i] = model.addVar(-100.0, 100.0, 0.0, GRB_CONTINUOUS); if (warm_start_index != -1) { delta_k[i].set(GRB_DoubleAttr_Start, warm_start_delta_[admm_iteration][warm_start_index](i)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 957acaf9a0..efb2b30c4b 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -244,7 +244,7 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = t + 0.25 * filtered_solve_time_ + i * dt_; + c3_solution->time_vector_(i) = t + 0.2 * filtered_solve_time_ + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); From 7c81808b3f26cc57ca7aeda3a6b1ddf35cc621cb Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 23 Jan 2024 14:20:43 -0500 Subject: [PATCH 630/758] parameters to identify support friction --- .../pydairlib/analysis/log_plotter_franka.py | 50 +++++++++---------- .../pydairlib/analysis/mbp_plotting_utils.py | 11 ++-- .../franka_hardware_friction_plot_config.yaml | 43 ++++++++++++++++ bindings/pydairlib/common/plotting_utils.py | 2 +- .../franka_osc_controller_params.yaml | 4 +- 5 files changed, 76 insertions(+), 34 deletions(-) create mode 100644 bindings/pydairlib/analysis/plot_configs/franka_hardware_friction_plot_config.yaml diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index b8d9a33779..bf57cd8539 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -14,10 +14,10 @@ def main(): - # config_file = ('bindings/pydairlib/analysis/plot_configs' - # '/franka_hardware_plot_config.yaml') config_file = ('bindings/pydairlib/analysis/plot_configs' - '/franka_sim_plot_config.yaml') + '/franka_hardware_plot_config.yaml') + # config_file = ('bindings/pydairlib/analysis/plot_configs' + # '/franka_sim_plot_config.yaml') plot_config = FrankaPlotConfig(config_file) channel_x = plot_config.channel_x @@ -79,9 +79,9 @@ def main(): print('Finished processing log - making plots') # Define x time slice t_x_slice = slice(robot_output['t'].size) - t_osc_slice = slice(osc_debug['t_osc'].size) + # t_osc_slice = slice(osc_debug['t_osc'].size) - print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) + # print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) (franka_joint_position_limit_range, franka_joint_velocity_limit_range, @@ -134,15 +134,13 @@ def main(): plot.axes[0].set_ylim([0.4, 0.7]) plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) - plot = plot_styler.PlotStyler(nrows=2) - plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 0) - plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0) - plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 0) - plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 1) - plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 1) - plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 9:10], subplot_index = 1) - # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8] - c3_tracking_actual['x'][:, 7:8], subplot_index = 1) - # plt.plot(c3_output['t'], c3_output['x'][:, 0, :]) + # plot = plot_styler.PlotStyler(nrows=2) + # plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 0) + # plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0) + # plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 0) + # plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 1) + # plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 1) + # plot.plot(c3_tracking_target['t'], c3_tracking_actual['x'][:, 9:10], subplot_index = 1) # Plot all joint velocities if plot_config.plot_joint_velocities: @@ -161,16 +159,16 @@ def main(): if plot_config.plot_end_effector: end_effector_plotter = plot_styler.PlotStyler(nrows=2) mbp_plots.plot_points_positions(robot_output, t_x_slice, franka_plant, - franka_context, ['end_effector'], - {'end_effector': np.zeros(3)}, - {'end_effector': [0, 1, 2]}, + franka_context, ['plate'], + {'plate': np.zeros(3)}, + {'plate': [0, 1, 2]}, ps=end_effector_plotter, subplot_index=0) mbp_plots.plot_points_velocities(robot_output, t_x_slice, franka_plant, - franka_context, ['end_effector'], - {'end_effector': np.zeros(3)}, - {'end_effector': [0, 1, 2]}, + franka_context, ['plate'], + {'plate': np.zeros(3)}, + {'plate': [0, 1, 2]}, ps=end_effector_plotter, subplot_index=1) @@ -231,14 +229,14 @@ def main(): # plot.save_fig('active_tracking_datas.png') if plot_config.plot_object_state: - plot = mbp_plots.plot_positions_by_name(object_state, + ps = plot_styler.PlotStyler(nrows=2) + mbp_plots.plot_positions_by_name(object_state, tray_pos_names[4:], - t_object_slice, tray_pos_map) - # plot.save_fig(('/').join(filename.split('/')[-2:]) + '/object_position') - if plot_config.plot_object_state: - plot = mbp_plots.plot_positions_by_name(object_state, + t_object_slice, tray_pos_map, ps = ps, subplot_index = 0) + mbp_plots.plot_positions_by_name(object_state, tray_pos_names[:4], - t_object_slice, tray_pos_map) + t_object_slice, tray_pos_map, ps = ps, subplot_index = 1) + # plot.save_fig(('/').join(filenme.split('/')[-2:]) + '/object_position') plt.show() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index d4984c1ce1..b644275774 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -343,9 +343,10 @@ def load_default_channels(data, plant, state_channel, input_channel, osc_debug_channel): robot_output = process_state_channel(data[state_channel], plant) robot_input = process_effort_channel(data[input_channel], plant) - osc_debug = process_osc_channel(data[osc_debug_channel]) - osc_debug = permute_osc_joint_ordering( - osc_debug, data[state_channel][0], plant) + # osc_debug = process_osc_channel(data[osc_debug_channel]) + # osc_debug = permute_osc_joint_ordering( + # osc_debug, data[state_channel][0], plant) + osc_debug = None return robot_output, robot_input, osc_debug @@ -422,10 +423,10 @@ def plot_joint_positions(robot_output, q_names, fb_dim, time_slice, subplot_inde title='Joint Positions', subplot_index=subplot_index) -def plot_positions_by_name(robot_output, q_names, time_slice, pos_map): +def plot_positions_by_name(robot_output, q_names, time_slice, pos_map, ps = None, subplot_index = 0): q_slice = [pos_map[name] for name in q_names] return plot_q_or_v_or_u(robot_output, 'q', q_names, q_slice, time_slice, - ylabel='Position', title='Select Positions') + ylabel='Position', title='Select Positions', ps=ps, subplot_index=subplot_index) def plot_floating_base_velocities(robot_output, v_names, fb_dim, time_slice): diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_friction_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_friction_plot_config.yaml new file mode 100644 index 0000000000..1d02070c7b --- /dev/null +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_friction_plot_config.yaml @@ -0,0 +1,43 @@ +# LCM channels to read data from +channel_x: "FRANKA_STATE" +channel_u: "OSC_FRANKA" +channel_osc: "OSC_DEBUG_FRANKA" +channel_c3: "C3_DEBUG" +channel_tray: "TRAY_STATE" +channel_c3_target: "C3_TARGET" +channel_c3_actual: "C3_ACTUAL" +plot_style: 'compact' # compact, paper, default + +start_time: 0 +#duration: 0.47 +duration: -1 +# Plant properties + +# Desired RobotOutput plots +plot_joint_positions: false +plot_joint_velocities: false +plot_measured_efforts: false +plot_commanded_efforts: false +plot_contact_forces: false +plot_end_effector: false + +special_positions_to_plot: [] +special_velocities_to_plot: [] +special_efforts_to_plot: [] + +# Finite State Machine Names +fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] + +# Desired osc plots +plot_qp_costs: false +plot_qp_solve_time: false +plot_qp_solutions: false +plot_tracking_costs: false +plot_active_tracking_datas: false +tracking_datas_to_plot: +# end_effector_target: {'dims': [0], 'derivs': ['accel']} +# end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} +# end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} +plot_c3_debug: false +plot_c3_tracking: false +plot_object_state: true \ No newline at end of file diff --git a/bindings/pydairlib/common/plotting_utils.py b/bindings/pydairlib/common/plotting_utils.py index ae8e7facd4..3023093578 100644 --- a/bindings/pydairlib/common/plotting_utils.py +++ b/bindings/pydairlib/common/plotting_utils.py @@ -34,7 +34,7 @@ def make_plot(data_dictionary, time_key, time_slice, keys_to_plot, if key in legend_entries: legend.extend(legend_entries[key]) - ps.add_legend(legend, loc='upper right') + ps.add_legend(legend, loc='upper right', subplot_index=subplot_index) def make_mixed_data_plot(data_dictionaries, time_keys, time_slices, diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 1b419dd3a1..a966a8959d 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,9 +21,9 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false -publish_debug_info: false +publish_debug_info: true W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] From 5d721dd3ce6c3fbbc6c957f47b0942c1bc8c7663 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 23 Jan 2024 20:08:04 -0500 Subject: [PATCH 631/758] tuning low friction gains --- .../franka_c3_controller_params.yaml | 8 +-- .../franka_c3_options_side_supports.yaml | 8 +-- ...c3_options_side_supports_low_friction.yaml | 59 +++++++++++++++++++ .../franka/parameters/franka_sim_params.yaml | 6 +- .../franka/systems/end_effector_trajectory.cc | 34 ++--------- .../franka/systems/end_effector_trajectory.h | 4 +- .../urdf/plate_end_effector_translation.urdf | 6 +- examples/franka/urdf/tray.sdf | 2 +- solvers/c3.cc | 8 +-- systems/controllers/c3_controller.cc | 28 ++++----- 10 files changed, 98 insertions(+), 65 deletions(-) create mode 100644 examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index a38629a78b..4a13006282 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -17,8 +17,8 @@ tool_attachment_frame: [0, 0, 0.107] #right_support_position: [0.8, -0.15, 0.453] #left_support_orientation: [0.0, 0.0, 0.0] #right_support_orientation: [0.0, 0.0, 0.0] -left_support_position: [0.4, 0.25, 0.452] -right_support_position: [0.7, 0.25, 0.452] +left_support_position: [0.4, 0.25, 0.45] +right_support_position: [0.7, 0.25, 0.45] left_support_orientation: [0.0, 0.0, 1.57] right_support_orientation: [0.0, 0.0, 1.57] end_effector_thickness: 0.016 @@ -32,13 +32,13 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.1, 0.486]] + [0.55, -0.1, 0.48]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.55, -0.1, 0.6]] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], - [0.55, 0.15, 0.49]] + [0.55, 0.15, 0.482]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 364f63c63d..2f9da002e3 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -30,12 +30,12 @@ N: 5 gamma: 1.0 # discount factor on MPC costs # matrix scaling -w_Q: 50 -w_R: 5 +w_Q: 5 +w_R: 0.5 # Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.01 # Penalty on all decision variables, assuming scalar -w_U: 0.1 +w_U: 0.01 # State Tracking Error, assuming diagonal q_vector: [150, 150, 100, 0, 1, 1, 0, 15000, 15000, 15000, diff --git a/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml b/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml new file mode 100644 index 0000000000..b949c18763 --- /dev/null +++ b/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml @@ -0,0 +1,59 @@ +admm_iter: 2 +rho: 0 # does not do anything +rho_scale: 10 +num_threads: 5 +delta_option: 1 +# options are 'MIQP' or 'QP' +projection_type: 'MIQP' +# options are 'stewart_and_trinkle' or 'anitescu' +#contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' +warm_start: true +use_predicted_x0: true +solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} + +# Workspace Limits +world_x_limits: [0.45, 0.65] +world_y_limits: [-0.15, 0.05] +world_z_limits: [0.4, 0.7] +workspace_margins: 0.05 + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] + +mu: [0.3, 0.3, 0.3, 0.2, 0.2, 0.2, 0.2] +dt: 0.075 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 7 +N: 5 +gamma: 1.0 # discount factor on MPC costs + +# matrix scaling +w_Q: 0.005 +w_R: 0.0005 +# Penalty on all decision variables, assuming scalar +w_G: 0.0000025 +# Penalty on all decision variables, assuming scalar +w_U: 0.000005 + +# State Tracking Error, assuming diagonal +q_vector: [150, 150, 100, 0, 1, 1, 0, 10000, 10000, 10000, + 7.5, 7.5, 15, 1, 1, 1, 1, 1, 1] +# Penalty on efforts, assuming diagonal +r_vector: [0.1, 0.1, 0.1] + +# Penalty on matching projected variables +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [1, 1, 1, 1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_u: [1, 1, 1] + +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_gamma: [1, 1, 1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75] +u_u: [30, 30, 100] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 74123e0549..8241e57cf7 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,6 +1,6 @@ #franka_model: examples/franka/urdf/franka_no_collision.urdf franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf -end_effector_model: examples/franka/urdf/plate_end_effector_parameter_sweep.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf tray_model: examples/franka/urdf/tray.sdf @@ -29,8 +29,8 @@ tool_attachment_frame: [0, 0, 0.107] #left_support_orientation: [0.0, 0.0, 0.0] #right_support_orientation: [0.0, 0.0, 0.0] -left_support_position: [0.4, 0.25, 0.452] -right_support_position: [0.7, 0.25, 0.452] +left_support_position: [0.4, 0.25, 0.45] +right_support_position: [0.7, 0.25, 0.45] left_support_orientation: [0.0, 0.0, 1.57] right_support_orientation: [0.0, 0.0, 1.57] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index c1356a5aa4..eccbe91401 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -45,35 +45,12 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( this->DeclareAbstractInputPort("lcmt_radio_out", drake::Value{}) .get_index(); - controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); - DeclareForcedDiscreteUpdateEvent( - &EndEffectorTrajectoryGenerator::DiscreteVariableUpdate); PiecewisePolynomial empty_pp_traj(neutral_pose_); Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, &EndEffectorTrajectoryGenerator::CalcTraj); } - -EventStatus EndEffectorTrajectoryGenerator::DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const { - - const auto& radio_out = - this->EvalInputValue(context, radio_port_); - const auto& trajectory_input = - this->EvalAbstractInput(context, trajectory_port_) - ->get_value>(); - bool using_c3 = context.get_discrete_state(controller_switch_index_)[0]; - if (!using_c3 && radio_out->channel[14] == 0) { - if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.05) { - discrete_state->get_mutable_value(controller_switch_index_)[0] = 1; - } - } - return EventStatus::Succeeded(); -} - - void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale) { @@ -108,17 +85,16 @@ void EndEffectorTrajectoryGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (radio_out->channel[14]) { *casted_traj = GeneratePose(context); } else { if (trajectory_input.value(0).isZero()) { -// *casted_traj = GeneratePose(context); + // *casted_traj = GeneratePose(context); } else { - if (context.get_discrete_state(controller_switch_index_)[0]){ - *casted_traj = *(PiecewisePolynomial*)dynamic_cast< - const PiecewisePolynomial*>(&trajectory_input); - } +// if ((context.get_time() - trajectory_input.start_time()) < 0.075){ + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); +// } } } } diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index af93ff0dc4..5b3d0960e9 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -27,7 +27,7 @@ class EndEffectorTrajectoryGenerator } void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, double x_scale, - double y_scale, double z_scale); + double y_scale, double z_scale); private: drake::systems::EventStatus DiscreteVariableUpdate( @@ -43,8 +43,6 @@ class EndEffectorTrajectoryGenerator drake::systems::Context* context_; const drake::multibody::Frame& world_; - drake::systems::DiscreteStateIndex controller_switch_index_; - drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 89ee71bac9..0df22bc08f 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -20,19 +20,19 @@ - + - + - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index b1984f4656..0959121122 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -41,7 +41,7 @@ 3.0e7 0.18 10 - 0.4 + 0.2 diff --git a/solvers/c3.cc b/solvers/c3.cc index 796bfbe5a5..b371fb2d21 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -190,10 +190,10 @@ void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; - for (int i = 0; i < N_ - 1; ++i) { - input_costs_[i]->UpdateCoefficients(2 * R_.at(i), - -2 * R_.at(i) * u_sol_->at(i)); - } +// for (int i = 0; i < N_ - 1; ++i) { +// input_costs_[i]->UpdateCoefficients(2 * R_.at(i), +// -2 * R_.at(i) * u_sol_->at(i)); +// } for (int iter = 0; iter < options_.admm_iter; iter++) { ADMMStep(x0, &delta, &w, &Gv, iter); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index efb2b30c4b..7158297840 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -179,20 +179,20 @@ drake::systems::EventStatus C3Controller::ComputePlan( drake::VectorX x_lcs = lcs_x->get_data(); // TODO(yangwill): clean this up - if (c3_options_.use_predicted_x0 && !x_pred_.isZero()) { - x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, - x_lcs[0] + 10 * dt_ * dt_); - x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, - x_lcs[1] + 10 * dt_ * dt_); - x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 10 * dt_ * dt_, - x_lcs[2] + 10 * dt_ * dt_); + if (x_lcs.segment(n_q_, 3).norm() > 0.05 && c3_options_.use_predicted_x0 && !x_pred_.isZero()) { + x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 20 * dt_ * dt_, + x_lcs[0] + 20 * dt_ * dt_); + x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 20 * dt_ * dt_, + x_lcs[1] + 20 * dt_ * dt_); + x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 5 * dt_ * dt_, + x_lcs[2] + 5 * dt_ * dt_); // x_lcs.head(3) = x_pred_.head(3); - x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, - x_lcs[n_q_ + 0] + 10 * dt_); - x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, - x_lcs[n_q_ + 1] + 10 * dt_); - x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, - x_lcs[n_q_ + 2] + 10 * dt_); + x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 20 * dt_, + x_lcs[n_q_ + 0] + 20 * dt_); + x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 20 * dt_, + x_lcs[n_q_ + 1] + 20 * dt_); + x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 5 * dt_, + x_lcs[n_q_ + 2] + 5 * dt_); // x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); } @@ -244,7 +244,7 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = t + 0.2 * filtered_solve_time_ + i * dt_; + c3_solution->time_vector_(i) = t + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); From a8a3a7c39fd0d8d6fed10c1c519639dcbac4cab1 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 24 Jan 2024 15:09:44 -0500 Subject: [PATCH 632/758] tuning parameters, still not perfect --- examples/franka/franka_c3_controller.cc | 2 + .../franka_c3_controller_params.yaml | 4 +- .../franka_c3_options_side_supports.yaml | 14 +++---- .../franka_osc_controller_params.yaml | 8 ++-- .../franka/parameters/franka_sim_params.yaml | 4 +- .../franka/systems/end_effector_trajectory.cc | 3 ++ examples/franka/urdf/plate_end_effector.urdf | 2 +- solvers/c3.cc | 8 ++-- systems/controllers/c3_controller.cc | 41 +++++++++++-------- systems/controllers/c3_controller.h | 5 +++ .../lcm_trajectory_systems.cc | 24 ++++++----- 11 files changed, 67 insertions(+), 48 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 5cb965c184..1052bcad4c 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -280,6 +280,8 @@ int DoMain(int argc, char* argv[]) { plate_balancing_target->get_input_port_tray_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_lcs_state()); + builder.Connect(radio_sub->get_output_port(), + controller->get_input_port_radio()); builder.Connect(reduced_order_model_receiver->get_output_port(), lcs_factory->get_input_port_lcs_state()); builder.Connect(radio_sub->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 4a13006282..94e8ceb556 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -32,13 +32,13 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.1, 0.48]] + [0.55, -0.1, 0.49]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.55, -0.1, 0.6]] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], - [0.55, 0.15, 0.482]] + [0.55, 0.125, 0.485]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 2f9da002e3..f1358d1211 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -30,18 +30,18 @@ N: 5 gamma: 1.0 # discount factor on MPC costs # matrix scaling -w_Q: 5 -w_R: 0.5 +w_Q: 50 +w_R: 50 # Penalty on all decision variables, assuming scalar -w_G: 0.01 +w_G: 0.1 # Penalty on all decision variables, assuming scalar -w_U: 0.01 +w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 150, 100, 0, 1, 1, 0, 15000, 15000, 15000, - 5, 5, 10, 100, 1, 1, 5, 5, 5] +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, + 5, 5, 15, 10, 10, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 0.1] +r_vector: [0.15, 0.15, 0.1] # Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index a966a8959d..92db6e9c4d 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false publish_debug_info: true @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [0.1, 0, 0, - 0, 0.1, 0, - 0, 0, 0.1] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 8241e57cf7..2f85560773 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -47,7 +47,7 @@ world_y_limits: [-0.15, 0.05] world_z_limits: [0.4, 0.7] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 1 #q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] @@ -57,7 +57,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] -visualize_workspace: false +visualize_workspace: true visualize_pose_trace: false visualize_center_of_mass_plan: true visualize_c3_forces: false diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index eccbe91401..d76d55d22e 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -94,6 +94,9 @@ void EndEffectorTrajectoryGenerator::CalcTraj( // if ((context.get_time() - trajectory_input.start_time()) < 0.075){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); + if (context.get_time() > casted_traj->get_segment_times()[1]){ + std::cout << "using second segment" << std::endl; + } // } } } diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index 9d55c0ef85..c5109a1276 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,7 +15,7 @@ - + diff --git a/solvers/c3.cc b/solvers/c3.cc index b371fb2d21..796bfbe5a5 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -190,10 +190,10 @@ void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; -// for (int i = 0; i < N_ - 1; ++i) { -// input_costs_[i]->UpdateCoefficients(2 * R_.at(i), -// -2 * R_.at(i) * u_sol_->at(i)); -// } + for (int i = 0; i < N_ - 1; ++i) { + input_costs_[i]->UpdateCoefficients(2 * R_.at(i), + -2 * R_.at(i) * u_sol_->at(i)); + } for (int iter = 0; iter < options_.admm_iter; iter++) { ADMMStep(x0, &delta, &w, &Gv, iter); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 7158297840..4274b75ba9 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -1,7 +1,7 @@ #include "c3_controller.h" #include - +#include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" #include "solvers/c3_miqp.h" #include "solvers/c3_qp.h" @@ -120,6 +120,10 @@ C3Controller::C3Controller( c3_options_.u_vertical_limits[1], 2); } + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); lcs_state_input_port_ = this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) .get_index(); @@ -169,6 +173,8 @@ drake::systems::EventStatus C3Controller::ComputePlan( DiscreteValues* discrete_state) const { auto start = std::chrono::high_resolution_clock::now(); + const auto& radio_out = + this->EvalInputValue(context, radio_port_); const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const TimestampedVector* lcs_x = @@ -179,21 +185,21 @@ drake::systems::EventStatus C3Controller::ComputePlan( drake::VectorX x_lcs = lcs_x->get_data(); // TODO(yangwill): clean this up - if (x_lcs.segment(n_q_, 3).norm() > 0.05 && c3_options_.use_predicted_x0 && !x_pred_.isZero()) { - x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 20 * dt_ * dt_, - x_lcs[0] + 20 * dt_ * dt_); - x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 20 * dt_ * dt_, - x_lcs[1] + 20 * dt_ * dt_); - x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 5 * dt_ * dt_, - x_lcs[2] + 5 * dt_ * dt_); - // x_lcs.head(3) = x_pred_.head(3); - x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 20 * dt_, - x_lcs[n_q_ + 0] + 20 * dt_); - x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 20 * dt_, - x_lcs[n_q_ + 1] + 20 * dt_); - x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 5 * dt_, - x_lcs[n_q_ + 2] + 5 * dt_); - // x_lcs.segment(n_q_, 3) = x_pred_.segment(n_q_, 3); + // if (x_lcs.segment(n_q_, 3).norm() > 0.05 && c3_options_.use_predicted_x0 + // && !x_pred_.isZero()) { + if (!radio_out->channel[14] && c3_options_.use_predicted_x0 && !x_pred_.isZero()) { + x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, + x_lcs[0] + 10 * dt_ * dt_); + x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, + x_lcs[1] + 10 * dt_ * dt_); + x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 10 * dt_ * dt_, + x_lcs[2] + 10 * dt_ * dt_); + x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, + x_lcs[n_q_ + 0] + 10 * dt_); + x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, + x_lcs[n_q_ + 1] + 10 * dt_); + x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, + x_lcs[n_q_ + 2] + 10 * dt_); } discrete_state->get_mutable_value(plan_start_time_index_)[0] = @@ -244,7 +250,8 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = t + i * dt_; +// c3_solution->time_vector_(i) = 0.01 + filtered_solve_time_ + t + i * dt_; + c3_solution->time_vector_(i) = 0.01 + filtered_solve_time_ + t + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index bde37c008e..9493488a6b 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -34,6 +34,10 @@ class C3Controller : public drake::systems::LeafSystem { return this->get_input_port(target_input_port_); } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + const drake::systems::InputPort& get_input_port_lcs_state() const { return this->get_input_port(lcs_state_input_port_); } @@ -69,6 +73,7 @@ class C3Controller : public drake::systems::LeafSystem { void OutputC3Intermediates(const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const; + drake::systems::InputPortIndex radio_port_; drake::systems::InputPortIndex target_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::InputPortIndex lcs_input_port_; diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index bc8e833308..92b4aed274 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -57,17 +57,19 @@ void LcmTrajectoryReceiver::OutputTrajectory( context, trajectory_input_port_); auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); - - if (trajectory_block.datapoints.rows() == 3) { - *casted_traj = PiecewisePolynomial::FirstOrderHold( - trajectory_block.time_vector, trajectory_block.datapoints); - // *casted_traj = PiecewisePolynomial::ZeroOrderHold( - // trajectory_block.time_vector, trajectory_block.datapoints); - } else { - *casted_traj = PiecewisePolynomial::CubicHermite( - trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), - trajectory_block.datapoints.bottomRows(3)); - } + *casted_traj = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); +// if (trajectory_block.datapoints.rows() == 3) { +// *casted_traj = PiecewisePolynomial::FirstOrderHold( +// trajectory_block.time_vector, trajectory_block.datapoints); +// // *casted_traj = PiecewisePolynomial::ZeroOrderHold( +// // trajectory_block.time_vector, trajectory_block.datapoints); +// } else { +// +//// *casted_traj = PiecewisePolynomial::CubicHermite( +//// trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), +//// trajectory_block.datapoints.bottomRows(3)); +// } } else { *casted_traj = PiecewisePolynomial(Vector3d::Zero()); } From 275826100b9c1fd1cc1da0af2254881a5ebc43b8 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 24 Jan 2024 17:20:12 -0500 Subject: [PATCH 633/758] working on wgetting stuck near workspace --- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- examples/franka/parameters/franka_osc_controller_params.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 94e8ceb556..9ec6ff7254 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -38,7 +38,7 @@ second_target: [[0.45, 0.0, 0.5], [0.55, -0.1, 0.6]] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], - [0.55, 0.125, 0.485]] + [0.55, 0.15, 0.485]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 92db6e9c4d..5f1b285c10 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false publish_debug_info: true From 6f6bbc6e82c72e99b985189552a8c22ef5c28cf4 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 25 Jan 2024 11:18:31 -0500 Subject: [PATCH 634/758] small updates --- .../franka/parameters/franka_c3_options_side_supports.yaml | 6 +++--- .../franka/parameters/franka_osc_controller_params.yaml | 2 +- examples/franka/systems/end_effector_trajectory.cc | 5 ----- examples/franka/urdf/plate_end_effector_translation.urdf | 6 +++--- solvers/lcs_factory.cc | 2 +- 5 files changed, 8 insertions(+), 13 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index f1358d1211..eb3fbb0a2a 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -15,7 +15,7 @@ solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} # Workspace Limits world_x_limits: [0.45, 0.65] world_y_limits: [-0.15, 0.05] -world_z_limits: [0.4, 0.7] +world_z_limits: [0.35, 0.65] workspace_margins: 0.05 u_horizontal_limits: [-10, 10] @@ -51,9 +51,9 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -u_x: [0.1, 0.1, 0.1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_u: [30, 30, 30] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 5f1b285c10..92db6e9c4d 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false publish_debug_info: true diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index d76d55d22e..e0919fdaf6 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -91,13 +91,8 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (trajectory_input.value(0).isZero()) { // *casted_traj = GeneratePose(context); } else { -// if ((context.get_time() - trajectory_input.start_time()) < 0.075){ *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); - if (context.get_time() > casted_traj->get_segment_times()[1]){ - std::cout << "using second segment" << std::endl; - } -// } } } } diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index 0df22bc08f..affe7932a9 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -20,19 +20,19 @@ - + - + - + diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 70eb269933..59d2e15e9e 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -277,7 +277,7 @@ LCSFactory::ComputeContactJacobian( auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); auto [p_WCa, p_WCb] = collider.CalcWitnessPoints(context); // TODO(yangwill): think about if we want to push back both witness points - contact_points.push_back(p_WCa); + contact_points.push_back(p_WCb); phi(i) = phi_i; J_n.row(i) = J_i.row(0); J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, From f3ef800599312757dd010d32fbd3a963948f311e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 25 Jan 2024 11:19:30 -0500 Subject: [PATCH 635/758] fixing bug in rot tracking data --- .../osc/rot_space_tracking_data.cc | 22 +++---------------- 1 file changed, 3 insertions(+), 19 deletions(-) diff --git a/systems/controllers/osc/rot_space_tracking_data.cc b/systems/controllers/osc/rot_space_tracking_data.cc index b10b18be5b..efb353ea72 100644 --- a/systems/controllers/osc/rot_space_tracking_data.cc +++ b/systems/controllers/osc/rot_space_tracking_data.cc @@ -80,24 +80,12 @@ void RotTaskSpaceTrackingData::UpdateYdot( } void RotTaskSpaceTrackingData::UpdateYdotError(const Eigen::VectorXd& v_proj) { - // Transform qdot to w - Quaterniond y_quat_des(y_des_(0), y_des_(1), y_des_(2), y_des_(3)); - Quaterniond dy_quat_des(ydot_des_(0), ydot_des_(1), ydot_des_(2), - ydot_des_(3)); -// Vector3d w_des_ = 2 * (dy_quat_des * y_quat_des.conjugate()).vec(); DRAKE_DEMAND(ydot_des_.size() == 3); - Vector3d w_des_ = ydot_des_; - // Because we transform the error here rather than in the parent - // options_tracking_data, and because J_y is already transformed in the view - // frame, we need to undo the transformation on J_y error_ydot_ = - w_des_ - ydot_ - view_frame_rot_T_.transpose() * GetJ() * v_proj; + ydot_des_ - ydot_; if (with_view_frame_) { error_ydot_ = view_frame_rot_T_ * error_ydot_; } - - ydot_des_ = - w_des_; // Overwrite 4d quat_dot with 3d omega. Need this for osc logging } void RotTaskSpaceTrackingData::UpdateJ(const VectorXd& x_wo_spr, @@ -122,12 +110,8 @@ void RotTaskSpaceTrackingData::UpdateJdotV( } void RotTaskSpaceTrackingData::UpdateYddotDes(double, double) { - // Convert ddq into angular acceleration - // See https://physics.stackexchange.com/q/460311 - Quaterniond y_quat_des(y_des_(0), y_des_(1), y_des_(2), y_des_(3)); - Quaterniond yddot_quat_des(yddot_des_(0), yddot_des_(1), yddot_des_(2), - yddot_des_(3)); - yddot_des_converted_ = 2 * (yddot_quat_des * y_quat_des.conjugate()).vec(); + DRAKE_DEMAND(yddot_des_.size() == 3); + yddot_des_converted_ = yddot_des_; if (!idx_zero_feedforward_accel_.empty()) { std::cerr << "RotTaskSpaceTrackingData does not support zero feedforward " "acceleration"; From 402ec3606e56c6b7682154b746cb69a5f944155d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 25 Jan 2024 12:26:17 -0500 Subject: [PATCH 636/758] very minor channges to try to get c3 more consistent --- .../franka_c3_options_side_supports.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- solvers/c3.cc | 2 +- solvers/c3_miqp.cc | 39 +++++++++---------- systems/controllers/c3_controller.cc | 1 - 5 files changed, 21 insertions(+), 25 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index eb3fbb0a2a..3eb11d6272 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -8,7 +8,7 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' -warm_start: true +warm_start: false use_predicted_x0: true solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 2f85560773..729f71f61b 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 10 +tray_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 diff --git a/solvers/c3.cc b/solvers/c3.cc index 796bfbe5a5..e254c64b00 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -190,7 +190,7 @@ void C3::Solve(const VectorXd& x0, vector& delta, vector& w) { vector Gv = G_; - for (int i = 0; i < N_ - 1; ++i) { + for (int i = 0; i < N_; ++i) { input_costs_[i]->UpdateCoefficients(2 * R_.at(i), -2 * R_.at(i) * u_sol_->at(i)); } diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 650fa130a6..4e83b0b8db 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -7,22 +7,22 @@ using Eigen::MatrixXd; using Eigen::VectorXd; using std::vector; -C3MIQP::C3MIQP(const LCS &LCS, const CostMatrices &costs, - const vector &xdesired, const C3Options &options) +C3MIQP::C3MIQP(const LCS& LCS, const CostMatrices& costs, + const vector& xdesired, const C3Options& options) : C3(LCS, costs, xdesired, options), env_(true) { // Create an environment -// env_.set("LogToConsole", "0"); + // env_.set("LogToConsole", "0"); env_.set("OutputFlag", "0"); env_.set("Threads", "0"); env_.start(); } -VectorXd C3MIQP::SolveSingleProjection(const MatrixXd &U, - const VectorXd &delta_c, - const MatrixXd &E, const MatrixXd &F, - const MatrixXd &H, const VectorXd &c, +VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, + const VectorXd& delta_c, + const MatrixXd& E, const MatrixXd& F, + const MatrixXd& H, const VectorXd& c, const int admm_iteration, - const int &warm_start_index) { + const int& warm_start_index) { // set up linear term in cost VectorXd cost_lin = -2 * delta_c.transpose() * U; @@ -38,12 +38,12 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd &U, Mcons2 << MM1, MM2, MM3; GRBModel model = GRBModel(env_); -// model.set(GRB_IntParam_LogToConsole, 1); -// model.set(GRB_StringParam_LogFile, "grb_debug"); -// model.set("Cutoff", "0.001"); -// model.set("FeasibilityTol", "0.00001"); -// model.set("FeasibilityTol", "0.01"); -// model.set("IterationLimit", "40"); + // model.set(GRB_IntParam_LogToConsole, 1); + // model.set(GRB_StringParam_LogFile, "grb_debug"); + // model.set("Cutoff", "0.001"); + // model.set("FeasibilityTol", "0.00001"); + // model.set("FeasibilityTol", "0.01"); + // model.set("IterationLimit", "40"); GRBVar delta_k[n_ + m_ + k_]; GRBVar binary[m_]; @@ -68,15 +68,12 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd &U, for (int i = 0; i < n_ + m_ + k_; i++) { obj.addTerm(cost_lin(i), delta_k[i]); - - for (int j = 0; j < n_ + m_ + k_; j++) { - obj.addTerm(U(i, j), delta_k[i], delta_k[j]); - } + obj.addTerm(U(i, i), delta_k[i], delta_k[i]); } model.setObjective(obj, GRB_MINIMIZE); - int M = 1000; // big M variable + int M = 100000; // big M variable double coeff[n_ + m_ + k_]; double coeff2[n_ + m_ + k_]; @@ -85,7 +82,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd &U, /// convert VectorXd to double for (int j = 0; j < n_ + m_ + k_; j++) { - coeff[j] = Mcons2.row(i)(j); + coeff[j] = Mcons2(i, j); } cexpr.addTerms(coeff, delta_k, n_ + m_ + k_); @@ -96,7 +93,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd &U, /// convert VectorXd to double for (int j = 0; j < n_ + m_ + k_; j++) { - coeff2[j] = Mcons1.row(i)(j); + coeff2[j] = Mcons1(i, j); } cexpr2.addTerms(coeff2, delta_k, n_ + m_ + k_); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 4274b75ba9..9cd043f559 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -250,7 +250,6 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { -// c3_solution->time_vector_(i) = 0.01 + filtered_solve_time_ + t + i * dt_; c3_solution->time_vector_(i) = 0.01 + filtered_solve_time_ + t + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = From 6ab192945fe7f547d3a39da277c42b3518515b97 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 25 Jan 2024 17:07:26 -0500 Subject: [PATCH 637/758] minor changes for parameter study --- .../parameter_study_config.yaml | 12 +++---- .../run_tray_parameter_study.py | 34 ++++++------------- examples/Cassie/cassie_xbox_remote.py | 6 ++-- .../franka_c3_options_translation.yaml | 6 ++-- .../franka/parameters/franka_sim_params.yaml | 12 ++++--- .../systems/end_effector_force_trajectory.cc | 2 +- .../plate_end_effector_parameter_sweep.urdf | 2 +- 7 files changed, 32 insertions(+), 42 deletions(-) diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index 63d457a6a0..aa076cce01 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,20 +1,20 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_23_24/parameter_study/ -processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_23_24/parameter_study/data/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_25_24/parameter_study/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_25_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller fix_inertia_cmd: 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' nominal_c3_gain_filename: franka_c3_options_side_supports.yaml -#nominal_model_filename: tray.sdf -nominal_model_filename: plate_end_effector.urdf +nominal_model_filename: tray.sdf +#nominal_model_filename: plate_end_effector.urdf modified_c3_gain_filename: franka_c3_options_parameter_sweep.yaml -#modified_model_filename: tray_parameter_sweep.sdf -modified_model_filename: plate_end_effector_parameter_sweep.sdf +modified_model_filename: tray_parameter_sweep.sdf +#modified_model_filename: plate_end_effector_parameter_sweep.urdf parameter: ['mu_c3', 'mass_real', 'mu_real'] diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index 661aeb4c09..bbb2784a25 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -13,9 +13,8 @@ def main(): start_time = 0 realtime_rate = 1.0 num_trials = 10 - sim_run_time = sim_time / realtime_rate + 1.0 - c3_start_up_time = 4.0 - controller_startup_time = 0.1 + sim_run_time = sim_time / realtime_rate + controller_startup_time = 1.0 with open('bindings/pydairlib/analysis/tray_balance_study/' + config_file) as f: filedata = f.read() @@ -28,33 +27,25 @@ def main(): # parameter = 'mu_c3' # parameter = 'mass_real' - parameter = config['parameter'][2] + parameter = config['parameter'][1] nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' # nominal_real_mu_value = '0.4' nominal_real_mu_value = '' nominal_tray_mass = '1' - initial_radio_msg = dairlib.lcmt_radio_out() - start_c3_radio_msg = dairlib.lcmt_radio_out() - initial_radio_msg.channel[13] = 1 - initial_radio_msg.channel[11] = 1 - initial_radio_msg.channel[14] = 1 - start_c3_radio_msg.channel[13] = 1 - start_c3_radio_msg.channel[11] = 1 - start_c3_radio_msg.channel[14] = 0 - mu_range = np.arange(0.3, 0.8, 0.05) mass_range = np.arange(0.5, 2.0, 0.05) - for i in trange(mu_range.shape[0]): + # for i in trange(mu_range.shape[0]): + for i in trange(mass_range.shape[0]): for j in trange(num_trials): log_path = config['results_folder'] + parameter + '/simlog-' + '%02d_%1d' % (i, j) # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) - # modified_mass_value = ' %.1f ' % (mass_range[i]) + modified_mass_value = ' %.1f ' % (mass_range[i]) # modified_real_mu_value = '%.2f' % (mu_range[i]) - modified_real_mu_value = '' % (mu_range[i]) + # modified_real_mu_value = '' % (mu_range[i]) # f = open(gains_path + gain_filename, 'r') f = open(config['model_path'] + config['nominal_model_filename'], 'r') @@ -62,8 +53,8 @@ def main(): filedata = f.read() f.close() # newdata = filedata.replace(nominal_mu_value, modified_mu_value) - newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) - # newdata = filedata.replace(nominal_tray_mass, modified_mass_value) + # newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) + newdata = filedata.replace(nominal_tray_mass, modified_mass_value) # f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') f = open(config['model_path'] + config['modified_model_filename'], 'w') @@ -78,14 +69,11 @@ def main(): '%s' % log_path, ] + logger_process = subprocess.Popen(lcm_logger_cmd) osc_process = subprocess.Popen(config['osc_cmd']) - c3_process = subprocess.Popen(config['c3_cmd']) sim_process = subprocess.Popen(config['sim_cmd']) time.sleep(controller_startup_time) - publisher.publish("RADIO", initial_radio_msg.encode()) - logger_process = subprocess.Popen(lcm_logger_cmd) - time.sleep(c3_start_up_time) - publisher.publish("RADIO", start_c3_radio_msg.encode()) + c3_process = subprocess.Popen(config['c3_cmd']) time.sleep(sim_run_time) osc_process.kill() c3_process.kill() diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index a15ad202d4..3a777519e3 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -58,11 +58,11 @@ def main(): i = 0 latching_switch_a = 1 latching_switch_b = 1 - latching_switch_x = 1 + latching_switch_x = 0 latching_switch_y = 1 print("Teleop Status: " + str(latching_switch_a)) print("End Effector Follow Status: " + str(latching_switch_b)) - print("Force Tracking Status: " + str(latching_switch_x)) + print("Force Tracking Status: " + str(not latching_switch_x)) while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands @@ -82,7 +82,7 @@ def main(): print("End Effector Follow Status: " + str(latching_switch_b)) if event.button == 2: latching_switch_x = not latching_switch_x - print("Force Tracking Status: " + str(latching_switch_x)) + print("Force Tracking Status: " + str(not latching_switch_x)) if event.button == 3: latching_switch_y = not latching_switch_y print("Ready to Reset Status: " + str(latching_switch_y)) diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index ce05799966..35344c13ac 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -4,10 +4,10 @@ rho_scale: 2 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'MIQP' +projection_type: 'QP' # options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'anitescu' -contact_model: 'stewart_and_trinkle' +contact_model: 'anitescu' +#contact_model: 'stewart_and_trinkle' warm_start: true use_predicted_x0: false solve_time_filter_alpha: 0.9 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 729f71f61b..d34b2b0177 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,14 +12,16 @@ tray_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 2 +scene_index: 0 visualize_drake_sim: false publish_efforts: true -camera_pose: [[0.5, -1.2, 0.7], +camera_pose: [[1.5, 0, 0.6], + [0.5, -1.2, 0.7], [0.5, -0.8, 0.6], [1.5, 0, 0.6]] -camera_target: [[0.5, 0, 0.5], +camera_target: [[0.5, 0, 0.55], + [0.5, 0, 0.5], [0.5, 0, 0.5], [0.5, 0, 0.55]] @@ -57,8 +59,8 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] -visualize_workspace: true +visualize_workspace: false visualize_pose_trace: false -visualize_center_of_mass_plan: true +visualize_center_of_mass_plan: false visualize_c3_forces: false visualize_c3_state: true diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index 6af1c79834..9ff439e0fe 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -83,7 +83,7 @@ void EndEffectorForceTrajectoryGenerator::CalcTraj( auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (!radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { + if (radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); } else { if (context.get_discrete_state(controller_switch_index_)[0]){ diff --git a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf index 9d55c0ef85..c5109a1276 100644 --- a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf +++ b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf @@ -15,7 +15,7 @@ - + From 38d37c49053b9693daa1f7a4ab1d5a25e2e18424 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 26 Jan 2024 17:46:27 -0500 Subject: [PATCH 638/758] reliable parameters --- .../parameters/franka_c3_controller_params.yaml | 2 +- .../franka_c3_options_side_supports.yaml | 3 ++- examples/franka/parameters/franka_sim_params.yaml | 14 ++++++-------- examples/franka/systems/end_effector_trajectory.cc | 3 --- examples/franka/urdf/left_support.urdf | 1 - examples/franka/urdf/tray.sdf | 2 +- solvers/c3.cc | 14 ++++++++------ systems/controllers/c3_controller.cc | 2 +- 8 files changed, 19 insertions(+), 22 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 9ec6ff7254..fa5049e6c7 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -32,7 +32,7 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.1, 0.49]] + [0.55, -0.1, 0.485]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.55, -0.1, 0.6]] diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 3eb11d6272..1f119f2a3c 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -1,6 +1,6 @@ admm_iter: 2 rho: 0 # does not do anything -rho_scale: 10 +rho_scale: 4 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -51,6 +51,7 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] +# Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index d34b2b0177..2f85560773 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,20 +8,18 @@ box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 -tray_publish_rate: 1000 +tray_publish_rate: 10 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 0 +scene_index: 2 visualize_drake_sim: false publish_efforts: true -camera_pose: [[1.5, 0, 0.6], - [0.5, -1.2, 0.7], +camera_pose: [[0.5, -1.2, 0.7], [0.5, -0.8, 0.6], [1.5, 0, 0.6]] -camera_target: [[0.5, 0, 0.55], - [0.5, 0, 0.5], +camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.5], [0.5, 0, 0.55]] @@ -59,8 +57,8 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] -visualize_workspace: false +visualize_workspace: true visualize_pose_trace: false -visualize_center_of_mass_plan: false +visualize_center_of_mass_plan: true visualize_c3_forces: false visualize_c3_state: true diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index e0919fdaf6..c443b37b3d 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -62,8 +62,6 @@ void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( const drake::systems::Context& context) const { - const auto robot_output = - this->template EvalVectorInput(context, state_port_); const auto& radio_out = this->EvalInputValue(context, radio_port_); VectorXd y0 = neutral_pose_; @@ -89,7 +87,6 @@ void EndEffectorTrajectoryGenerator::CalcTraj( *casted_traj = GeneratePose(context); } else { if (trajectory_input.value(0).isZero()) { - // *casted_traj = GeneratePose(context); } else { *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/left_support.urdf index 803553eee7..14447ba3a6 100644 --- a/examples/franka/urdf/left_support.urdf +++ b/examples/franka/urdf/left_support.urdf @@ -21,7 +21,6 @@ - diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 0959121122..b1984f4656 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -41,7 +41,7 @@ 3.0e7 0.18 10 - 0.2 + 0.4 diff --git a/solvers/c3.cc b/solvers/c3.cc index e254c64b00..832591db61 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -64,12 +64,12 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, prog_(MathematicalProgram()), osqp_(OsqpSolver()) { if (warm_start_) { - warm_start_delta_.resize(options_.admm_iter); - warm_start_binary_.resize(options_.admm_iter); - warm_start_x_.resize(options_.admm_iter); - warm_start_lambda_.resize(options_.admm_iter); - warm_start_u_.resize(options_.admm_iter); - for (size_t iter = 0; iter < options_.admm_iter; ++iter) { + warm_start_delta_.resize(options_.admm_iter + 1); + warm_start_binary_.resize(options_.admm_iter + 1); + warm_start_x_.resize(options_.admm_iter + 1); + warm_start_lambda_.resize(options_.admm_iter + 1); + warm_start_u_.resize(options_.admm_iter + 1); + for (size_t iter = 0; iter < options_.admm_iter + 1; ++iter) { warm_start_delta_[iter].resize(N_); for (size_t i = 0; i < N_; i++) { warm_start_delta_[iter][i] = VectorXd::Zero(n_ + m_ + k_); @@ -204,6 +204,8 @@ void C3::Solve(const VectorXd& x0, vector& delta, WD.at(i) = delta.at(i) - w.at(i); } + vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); + *z_sol_ = delta; z_sol_->at(0).segment(0, n_) = x0; for (int i = 1; i < N_; ++i) { diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 9cd043f559..bf6944e7f6 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -250,7 +250,7 @@ void C3Controller::OutputC3Solution( auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = 0.01 + filtered_solve_time_ + t + i * dt_; + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); From d4afacccc7598bbefa9f7fdfda82058361f45af7 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Sat, 27 Jan 2024 17:33:57 -0500 Subject: [PATCH 639/758] somewhat reliable gains --- examples/franka/franka_visualizer.cc | 12 +++---- .../franka_c3_controller_params.yaml | 16 +++++----- ...c3_options_side_supports_low_friction.yaml | 2 +- .../franka_c3_options_w_supports.yaml | 22 ++++++------- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 6 ++-- .../franka/parameters/franka_sim_params.yaml | 31 +++++++++---------- .../franka/systems/plate_balancing_target.cc | 14 ++++----- solvers/lcs_factory.cc | 2 +- 9 files changed, 53 insertions(+), 54 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index c32c58667a..fc321c487e 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -179,12 +179,12 @@ int do_main(int argc, char* argv[]) { meshcat->SetCameraPose(sim_params.camera_pose[sim_params.scene_index], sim_params.camera_target[sim_params.scene_index]); if (sim_params.visualize_workspace){ - double width = sim_params.world_x_limits[1] - sim_params.world_x_limits[0]; - double depth = sim_params.world_y_limits[1] - sim_params.world_y_limits[0]; - double height = sim_params.world_z_limits[1] - sim_params.world_z_limits[0]; - Vector3d workspace_center = {0.5 * (sim_params.world_x_limits[1] + sim_params.world_x_limits[0]), - 0.5 * (sim_params.world_y_limits[1] + sim_params.world_y_limits[0]), - 0.5 * (sim_params.world_z_limits[1] + sim_params.world_z_limits[0])}; + double width = sim_params.world_x_limits[sim_params.scene_index][1] - sim_params.world_x_limits[sim_params.scene_index][0]; + double depth = sim_params.world_y_limits[sim_params.scene_index][1] - sim_params.world_y_limits[sim_params.scene_index][0]; + double height = sim_params.world_z_limits[sim_params.scene_index][1] - sim_params.world_z_limits[sim_params.scene_index][0]; + Vector3d workspace_center = {0.5 * (sim_params.world_x_limits[sim_params.scene_index][1] + sim_params.world_x_limits[sim_params.scene_index][0]), + 0.5 * (sim_params.world_y_limits[sim_params.scene_index][1] + sim_params.world_y_limits[sim_params.scene_index][0]), + 0.5 * (sim_params.world_z_limits[sim_params.scene_index][1] + sim_params.world_z_limits[sim_params.scene_index][0])}; meshcat->SetObject("c3_state/workspace", drake::geometry::Box(width, depth, height), {1, 0, 0, 0.2}); meshcat->SetTransform("c3_state/workspace", RigidTransformd(workspace_center)); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index fa5049e6c7..a79b1f8325 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -13,12 +13,12 @@ left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] -#left_support_position: [0.8, 0.15, 0.453] -#right_support_position: [0.8, -0.15, 0.453] +#left_support_position: [0.8, 0.15, 0.455] +#right_support_position: [0.8, -0.15, 0.455] #left_support_orientation: [0.0, 0.0, 0.0] #right_support_orientation: [0.0, 0.0, 0.0] -left_support_position: [0.4, 0.25, 0.45] -right_support_position: [0.7, 0.25, 0.45] +left_support_position: [0.4, 0.25, 0.450] +right_support_position: [0.7, 0.25, 0.450] left_support_orientation: [0.0, 0.0, 1.57] right_support_orientation: [0.0, 0.0, 1.57] end_effector_thickness: 0.016 @@ -29,16 +29,16 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -near_target_threshold: 0.05 +near_target_threshold: 0.075 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.1, 0.485]] + [0.55, -0.1, 0.49]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.55, -0.1, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.7, 0.00, 0.485], - [0.55, 0.15, 0.485]] + [0.7, 0.00, 0.49], + [0.55, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml b/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml index b949c18763..0aa173ca4c 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml @@ -14,7 +14,7 @@ solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} # Workspace Limits world_x_limits: [0.45, 0.65] -world_y_limits: [-0.15, 0.05] +world_y_limits: [-0.2, 0.05] world_z_limits: [0.4, 0.7] workspace_margins: 0.05 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 3b037d92cc..4c1f46b82e 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -1,6 +1,6 @@ admm_iter: 2 rho: 0 # does not do anything -rho_scale: 10 +rho_scale: 4 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -8,9 +8,9 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' -warm_start: true +warm_start: false use_predicted_x0: true -solve_time_filter_alpha: 0.9 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} +solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} # Workspace Limits world_x_limits: [0.4, 0.6] @@ -21,7 +21,7 @@ workspace_margins: 0.05 u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] -mu: [0.4, 0.4, 0.4, 0.1, 0.1, 0.1, 0.1] +mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 @@ -31,17 +31,17 @@ gamma: 1.0 # discount factor on MPC costs # matrix scaling w_Q: 50 -w_R: 5 +w_R: 50 # Penalty on all decision variables, assuming scalar w_G: 0.1 # Penalty on all decision variables, assuming scalar w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [150, 150, 100, 0, 1, 1, 0, 15000, 15000, 15000, - 5, 5, 10, 1, 1, 1, 5, 5, 5] +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, + 5, 5, 15, 10, 10, 1, 5, 5, 5] # Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 0.1] +r_vector: [0.15, 0.15, 0.1] # Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] @@ -51,9 +51,9 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -u_x: [0.1, 0.1, 0.1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75] -u_u: [30, 30, 30] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_u: [15, 15, 15] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 92db6e9c4d..5f1b285c10 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false publish_debug_info: true diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 0fcd372b1a..42f796cbab 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -36,9 +36,9 @@ struct FrankaSimParams { Eigen::VectorXd left_support_orientation; Eigen::VectorXd right_support_orientation; - std::vector world_x_limits; - std::vector world_y_limits; - std::vector world_z_limits; + std::vector world_x_limits; + std::vector world_y_limits; + std::vector world_z_limits; bool visualize_pose_trace; bool visualize_center_of_mass_plan; diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 2f85560773..566170686f 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -9,14 +9,14 @@ left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 tray_publish_rate: 10 -visualizer_publish_rate: 30 +visualizer_publish_rate: 10 actuator_delay: 0.000 scene_index: 2 visualize_drake_sim: false publish_efforts: true -camera_pose: [[0.5, -1.2, 0.7], +camera_pose: [[1.5, 0, 0.6], [0.5, -0.8, 0.6], [1.5, 0, 0.6]] camera_target: [[0.5, 0, 0.5], @@ -24,8 +24,8 @@ camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.55]] tool_attachment_frame: [0, 0, 0.107] -#left_support_position: [0.8, 0.15, 0.453] -#right_support_position: [0.8, -0.15, 0.453] +#left_support_position: [0.8, 0.15, 0.455] +#right_support_position: [0.8, -0.15, 0.455] #left_support_orientation: [0.0, 0.0, 0.0] #right_support_orientation: [0.0, 0.0, 0.0] @@ -35,16 +35,15 @@ left_support_orientation: [0.0, 0.0, 1.57] right_support_orientation: [0.0, 0.0, 1.57] # Workspace Limits -#world_x_limits: [0.4, 0.6] -#world_y_limits: [-0.15, 0.15] -#world_z_limits: [0.3, 0.6] - -# Workspace Limits -#world_x_limits: [0.4, 0.6] -#world_y_limits: [-0.1, 0.1] -world_x_limits: [0.45, 0.65] -world_y_limits: [-0.15, 0.05] -world_z_limits: [0.4, 0.7] +world_x_limits: [[0.4, 0.6], + [0.4, 0.6], + [0.45, 0.65]] +world_y_limits: [[-0.15, 0.15], + [-0.1, 0.1], + [-0.15, 0.05]] +world_z_limits: [[0.35, 0.7], + [0.35, 0.7], + [0.35, 0.7]] dt: 0.0005 realtime_rate: 1 @@ -53,11 +52,11 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.7, 0.00, 0.515], - [1, 0, 0, 0, 0.55, 0.125, 0.515]] + [1, 0, 0, 0, 0.55, 0.15, 0.515]] #q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] -visualize_workspace: true +visualize_workspace: false visualize_pose_trace: false visualize_center_of_mass_plan: true visualize_c3_forces: false diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 2ed21f5e64..b33309673c 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -68,7 +68,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( discrete_state->get_mutable_value(within_target_index_)[0] = 1; } if (within_target == 1 && - (context.get_time() - time_entered_target) > 0.5) { + (context.get_time() - time_entered_target) > 0.1) { discrete_state->get_mutable_value(within_target_index_)[0] = 0; discrete_state->get_mutable_value(sequence_index_)[0] = 1; } @@ -139,9 +139,9 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( end_effector_position(2) += radio_out->channel[2] * z_scale_; } // end_effector_position(0) = 0.55; -// end_effector_position(1) = 0.1 * sin(3 * context.get_time()); -// end_effector_position(1) = 0.1 * (int) (2 * sin(context.get_time())); - // end_effector_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()) - end_effector_thickness_; +// end_effector_position(1) = 0.1 * sin(4 * context.get_time()); +// end_effector_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()) - end_effector_thickness_; +// end_effector_position(1) = 0.1 * (int) (2 * sin(0.5 * context.get_time())); // end_effector_position(2) = 0.45 - end_effector_thickness_; target->SetFromVector(end_effector_position); } @@ -164,9 +164,9 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( tray_position(1) += radio_out->channel[1] * y_scale_; tray_position(2) += radio_out->channel[2] * z_scale_; // tray_position(0) = 0.55; -// tray_position(1) = 0.1 * sin(3 * context.get_time()); -// tray_position(1) = 0.1 * (int) (2 * sin(context.get_time())); - // tray_position(2) = 0.45 + 0.1 * cos(1.5 *context.get_time()); +// tray_position(1) = 0.1 * sin(4 * context.get_time()); +// tray_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()); +// tray_position(1) = 0.1 * (int) (2 * sin(0.5 * context.get_time())); // tray_position(2) = 0.45; target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat target->SetFromVector(target_tray_state); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 59d2e15e9e..70eb269933 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -277,7 +277,7 @@ LCSFactory::ComputeContactJacobian( auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); auto [p_WCa, p_WCb] = collider.CalcWitnessPoints(context); // TODO(yangwill): think about if we want to push back both witness points - contact_points.push_back(p_WCb); + contact_points.push_back(p_WCa); phi(i) = phi_i; J_n.row(i) = J_i.row(0); J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, From 540ac8f646fe1fdf545e76ff222265e5bc77871a Mon Sep 17 00:00:00 2001 From: Will Yang Date: Sun, 28 Jan 2024 19:50:52 -0500 Subject: [PATCH 640/758] changing visualization colors --- .../lcm_visualization_systems.cc | 50 +++++++++---------- .../visualization/lcm_visualization_systems.h | 4 +- 2 files changed, 27 insertions(+), 27 deletions(-) diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index b3125d00f9..d976cedd3f 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -183,9 +183,9 @@ LcmForceDrawer::LcmForceDrawer( actor_last_update_time_index_ = this->DeclareDiscreteState(1); forces_last_update_time_index_ = this->DeclareDiscreteState(1); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, - {0, 1, 0, 1}); + {0.6, 0.0, 0, 1}); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, - {0, 1, 0, 1}); + {0.6, 0.0, 0, 1}); meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); @@ -226,13 +226,13 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( if (actor_trajectory_block.datapoints.rows() == 3) { auto trajectory = PiecewisePolynomial::FirstOrderHold( actor_trajectory_block.time_vector, actor_trajectory_block.datapoints); - pose = trajectory.value(actor_trajectory_block.time_vector[0]); + pose = trajectory.value(robot_time); } else { auto trajectory = PiecewisePolynomial::CubicHermite( actor_trajectory_block.time_vector, actor_trajectory_block.datapoints.topRows(3), actor_trajectory_block.datapoints.bottomRows(3)); - pose = trajectory.value(actor_trajectory_block.time_vector[0]); + pose = trajectory.value(robot_time); } auto force = force_trajectory.value(robot_time); @@ -295,9 +295,9 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( if (force_norm >= 0.5) { if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, - {1, 0, 0, 1}); + {0.004, 0.122, 0.357, 1}); meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, - {1, 0, 0, 1}); + {0.004, 0.122, 0.357, 1}); } const VectorXd pose = Eigen::Map( @@ -363,12 +363,12 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( {0, 1, 0, 1}); meshcat_->SetObject(c3_actual_tray_path_ + "/z-axis", cylinder_for_tray_, {0, 0, 1, 1}); - meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, - {1, 0, 0, 1}); - meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, - {0, 1, 0, 1}); - meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, - {0, 0, 1, 1}); +// meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, +// {1, 0, 0, 1}); +// meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, +// {0, 1, 0, 1}); +// meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, +// {0, 0, 1, 1}); // meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, // {1, 0, 0, 1}); // meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, @@ -377,31 +377,31 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( // {0, 0, 1, 1}); auto x_axis_transform = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), - Vector3d{0.075, 0.0, 0.0}); + Vector3d{0.05, 0.0, 0.0}); auto y_axis_transform = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), - Vector3d{0.0, 0.075, 0.0}); + Vector3d{0.0, 0.05, 0.0}); auto z_axis_transform = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), - Vector3d{0.0, 0.0, 0.075}); + Vector3d{0.0, 0.0, 0.05}); auto x_axis_transform_ee = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), - 0.5 * Vector3d{0.075, 0.0, 0.0}); + 0.5 * Vector3d{0.05, 0.0, 0.0}); auto y_axis_transform_ee = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitX()), - 0.5 * Vector3d{0.0, 0.075, 0.0}); + 0.5 * Vector3d{0.0, 0.05, 0.0}); auto z_axis_transform_ee = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), - 0.5 * Vector3d{0.0, 0.0, 0.075}); + 0.5 * Vector3d{0.0, 0.0, 0.05}); meshcat_->SetTransform(c3_target_tray_path_ + "/x-axis", x_axis_transform); meshcat_->SetTransform(c3_target_tray_path_ + "/y-axis", y_axis_transform); meshcat_->SetTransform(c3_target_tray_path_ + "/z-axis", z_axis_transform); meshcat_->SetTransform(c3_actual_tray_path_ + "/x-axis", x_axis_transform); meshcat_->SetTransform(c3_actual_tray_path_ + "/y-axis", y_axis_transform); meshcat_->SetTransform(c3_actual_tray_path_ + "/z-axis", z_axis_transform); - meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); - meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); - meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); +// meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); +// meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); +// meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); // meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); // meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); // meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); @@ -450,10 +450,10 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( c3_actual->state[9]})); } if (draw_ee_) { - meshcat_->SetTransform( - c3_target_ee_path_, - RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], - c3_target->state[2]})); +// meshcat_->SetTransform( +// c3_target_ee_path_, +// RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], +// c3_target->state[2]})); // meshcat_->SetTransform( // c3_actual_ee_path_, // RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index b2179fa1b3..c0388ebbf4 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -173,9 +173,9 @@ class LcmC3TargetDrawer : public drake::systems::LeafSystem { drake::systems::DiscreteStateIndex last_update_time_index_; const drake::geometry::Cylinder cylinder_for_tray_ = - drake::geometry::Cylinder(0.005, 0.15); + drake::geometry::Cylinder(0.005, 0.1); const drake::geometry::Cylinder cylinder_for_ee_ = - drake::geometry::Cylinder(0.0025, 0.075); + drake::geometry::Cylinder(0.0025, 0.05); drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); const std::string c3_state_path_ = "c3_state"; const std::string c3_target_tray_path_ = "c3_state/c3_target_tray"; From 73f653c2fd9320b7e9a5d7154f86b9b03dbf9b73 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 29 Jan 2024 13:44:50 -0500 Subject: [PATCH 641/758] commit used for ablation for force tracking --- .../franka_c3_controller_params.yaml | 22 +++++++++---------- .../franka_c3_options_w_supports.yaml | 7 +++--- .../franka/parameters/franka_sim_params.yaml | 20 ++++++++--------- .../franka/systems/plate_balancing_target.cc | 2 +- .../urdf/plate_end_effector_translation.urdf | 6 ++--- 5 files changed, 29 insertions(+), 28 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index a79b1f8325..2d92ec0060 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -13,23 +13,23 @@ left_support_model: examples/franka/urdf/left_support_point_contact.urdf right_support_model: examples/franka/urdf/left_support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] -#left_support_position: [0.8, 0.15, 0.455] -#right_support_position: [0.8, -0.15, 0.455] -#left_support_orientation: [0.0, 0.0, 0.0] -#right_support_orientation: [0.0, 0.0, 0.0] -left_support_position: [0.4, 0.25, 0.450] -right_support_position: [0.7, 0.25, 0.450] -left_support_orientation: [0.0, 0.0, 1.57] -right_support_orientation: [0.0, 0.0, 1.57] +left_support_position: [0.8, 0.15, 0.447] +right_support_position: [0.8, -0.15, 0.447] +left_support_orientation: [0.0, 0.0, 0.0] +right_support_orientation: [0.0, 0.0, 0.0] +#left_support_position: [0.4, 0.25, 0.450] +#right_support_position: [0.7, 0.25, 0.450] +#left_support_orientation: [0.0, 0.0, 1.57] +#right_support_orientation: [0.0, 0.0, 1.57] end_effector_thickness: 0.016 -scene_index: 2 +scene_index: 1 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -near_target_threshold: 0.075 +near_target_threshold: 0.06 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], [0.55, -0.1, 0.49]] @@ -37,7 +37,7 @@ second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.55, -0.1, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.7, 0.00, 0.49], + [0.7, 0.00, 0.485], [0.55, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 4c1f46b82e..90e2080279 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -8,9 +8,9 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' -warm_start: false +warm_start: true use_predicted_x0: true -solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} +solve_time_filter_alpha: 0.95 # Workspace Limits world_x_limits: [0.4, 0.6] @@ -51,9 +51,10 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] +# Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -u_u: [15, 15, 15] +u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 566170686f..37b632aa4d 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,7 +12,7 @@ tray_publish_rate: 10 visualizer_publish_rate: 10 actuator_delay: 0.000 -scene_index: 2 +scene_index: 1 visualize_drake_sim: false publish_efforts: true @@ -24,15 +24,15 @@ camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.55]] tool_attachment_frame: [0, 0, 0.107] -#left_support_position: [0.8, 0.15, 0.455] -#right_support_position: [0.8, -0.15, 0.455] -#left_support_orientation: [0.0, 0.0, 0.0] -#right_support_orientation: [0.0, 0.0, 0.0] - -left_support_position: [0.4, 0.25, 0.45] -right_support_position: [0.7, 0.25, 0.45] -left_support_orientation: [0.0, 0.0, 1.57] -right_support_orientation: [0.0, 0.0, 1.57] +left_support_position: [0.8, 0.15, 0.447] +right_support_position: [0.8, -0.15, 0.447] +left_support_orientation: [0.0, 0.0, 0.0] +right_support_orientation: [0.0, 0.0, 0.0] + +#left_support_position: [0.4, 0.25, 0.45] +#right_support_position: [0.7, 0.25, 0.45] +#left_support_orientation: [0.0, 0.0, 1.57] +#right_support_orientation: [0.0, 0.0, 1.57] # Workspace Limits world_x_limits: [[0.4, 0.6], diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index b33309673c..98a60bc128 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -68,7 +68,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( discrete_state->get_mutable_value(within_target_index_)[0] = 1; } if (within_target == 1 && - (context.get_time() - time_entered_target) > 0.1) { + (context.get_time() - time_entered_target) > 0.5) { discrete_state->get_mutable_value(within_target_index_)[0] = 0; discrete_state->get_mutable_value(sequence_index_)[0] = 1; } diff --git a/examples/franka/urdf/plate_end_effector_translation.urdf b/examples/franka/urdf/plate_end_effector_translation.urdf index affe7932a9..bb2ca2f4f8 100644 --- a/examples/franka/urdf/plate_end_effector_translation.urdf +++ b/examples/franka/urdf/plate_end_effector_translation.urdf @@ -20,19 +20,19 @@ - + - + - + From 0223f4cd73447273c064d163b299698a6ea34df2 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Mon, 29 Jan 2024 18:25:42 -0500 Subject: [PATCH 642/758] visualization changes --- .../parameters/franka_c3_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 6 +++--- examples/franka/urdf/plate_end_effector.urdf | 2 +- examples/franka/urdf/tray.sdf | 2 +- systems/visualization/lcm_visualization_systems.cc | 8 ++++---- systems/visualization/lcm_visualization_systems.h | 12 ++---------- 6 files changed, 12 insertions(+), 20 deletions(-) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 2d92ec0060..8b725cc94f 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -29,7 +29,7 @@ include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused -near_target_threshold: 0.06 +near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], [0.55, -0.1, 0.49]] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 37b632aa4d..174e05d7b1 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -17,7 +17,7 @@ visualize_drake_sim: false publish_efforts: true camera_pose: [[1.5, 0, 0.6], - [0.5, -0.8, 0.6], + [0.5, -0.6, 0.65], [1.5, 0, 0.6]] camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.5], @@ -58,6 +58,6 @@ q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] visualize_workspace: false visualize_pose_trace: false -visualize_center_of_mass_plan: true -visualize_c3_forces: false +visualize_center_of_mass_plan: false +visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index c5109a1276..a0efe0cef0 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -21,7 +21,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index b1984f4656..d2766b6bd3 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -25,7 +25,7 @@ - 0.1 0.1 0.1 0.8 + 0.1 0.1 0.1 0.6 diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index d976cedd3f..b03ee3412a 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -183,9 +183,9 @@ LcmForceDrawer::LcmForceDrawer( actor_last_update_time_index_ = this->DeclareDiscreteState(1); forces_last_update_time_index_ = this->DeclareDiscreteState(1); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/cylinder", cylinder_, - {0.6, 0.0, 0, 1}); + actor_force_color_); meshcat_->SetObject(force_path_ + "/u_lcs/arrow/head", arrowhead_, - {0.6, 0.0, 0, 1}); + actor_force_color_); meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); DeclarePerStepDiscreteUpdateEvent(&LcmForceDrawer::DrawForce); @@ -295,9 +295,9 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( if (force_norm >= 0.5) { if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, - {0.004, 0.122, 0.357, 1}); + contact_force_color_); meshcat_->SetObject(force_path_root + "arrow/head", arrowhead_, - {0.004, 0.122, 0.357, 1}); + contact_force_color_); } const VectorXd pose = Eigen::Map( diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index c0388ebbf4..4525ff78f4 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -104,13 +104,6 @@ class LcmForceDrawer : public drake::systems::LeafSystem { return this->get_input_port(force_trajectory_input_port_); } - void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } - - void SetNumSamples(int N) { - DRAKE_DEMAND(N > 1); - N_ = N; - } - private: drake::systems::EventStatus DrawForce( const drake::systems::Context& context, @@ -134,8 +127,8 @@ class LcmForceDrawer : public drake::systems::LeafSystem { const std::string actor_trajectory_name_; const std::string force_trajectory_name_; const std::string lcs_force_trajectory_name_; - drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); - int N_ = 5; + drake::geometry::Rgba actor_force_color_ = drake::geometry::Rgba(1, 0, 1, 1.0); + drake::geometry::Rgba contact_force_color_ = drake::geometry::Rgba(0.949, 0.757, 0.0, 1.0); const double radius_ = 0.002; const double newtons_per_meter_ = 40; }; @@ -176,7 +169,6 @@ class LcmC3TargetDrawer : public drake::systems::LeafSystem { drake::geometry::Cylinder(0.005, 0.1); const drake::geometry::Cylinder cylinder_for_ee_ = drake::geometry::Cylinder(0.0025, 0.05); - drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); const std::string c3_state_path_ = "c3_state"; const std::string c3_target_tray_path_ = "c3_state/c3_target_tray"; const std::string c3_actual_tray_path_ = "c3_state/c3_actual_tray"; From b3050cf0a43c947e0359411eb83ade5e5f8abff0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 30 Jan 2024 20:44:08 -0500 Subject: [PATCH 643/758] updating analysis scripts --- .../pydairlib/analysis/log_plotter_franka.py | 44 +++++++++++---- .../pydairlib/analysis/mbp_plotting_utils.py | 8 +-- .../franka_hardware_plot_config.yaml | 4 +- .../parameter_study_analysis.py | 53 +++++++++++++++---- .../parameter_study_config.yaml | 4 +- .../run_tray_parameter_study.py | 2 +- 6 files changed, 85 insertions(+), 30 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index bf57cd8539..579f24e066 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -29,7 +29,7 @@ def main(): channel_tray = plot_config.channel_tray if plot_config.plot_style == "paper": - plot_styler.PlotStyler.set_default_styling() + plot_styler.PlotStyler.set_paper_styling() elif plot_config.plot_style == "compact": plot_styler.PlotStyler.set_compact_styling() @@ -79,7 +79,7 @@ def main(): print('Finished processing log - making plots') # Define x time slice t_x_slice = slice(robot_output['t'].size) - # t_osc_slice = slice(osc_debug['t_osc'].size) + t_osc_slice = slice(osc_debug['t_osc'].size) # print('Average OSC frequency: ', 1 / np.mean(np.diff(osc_debug['t_osc']))) @@ -117,7 +117,9 @@ def main(): # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) if plot_config.plot_c3_tracking: - plot = plot_styler.PlotStyler(nrows=2) + # plot = plot_styler.PlotStyler(nrows=2) + plot = plot_styler.PlotStyler() + # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:3], subplot_index = 0) # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0) # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) @@ -125,14 +127,34 @@ def main(): # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 1) # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) - plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) - plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0) - plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) - plot.axes[0].set_ylim([0.4, 0.7]) - plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) - plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) - plot.axes[0].set_ylim([0.4, 0.7]) - plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) + # plots between end effector y and tray y + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 1:2], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) + + # plots y - z trajectories + plot.plot(c3_tracking_target['x'][:, 8:9], c3_tracking_target['x'][:, 9:10], subplot_index = 0) + plot.plot(c3_tracking_actual['x'][:, 8:9], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + + # plot.plot(c3_tracking_actual['t'], c3_tracking_target['x'][:, 8:9] - c3_tracking_target['x'][:, 1:2], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + # plot.plot(c3_tracking_target['x'][:, 1:2], c3_tracking_target['x'][:, 2:3], subplot_index = 0) + # plot.plot(c3_tracking_actual['x'][:, 1:2], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) + # plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) + # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) + plot.axes[0].set_ylim([0.3, 0.6]) + plot.axes[0].set_xlim([-0.15, 0.15]) + plot.add_legend(['tray target', 'tray actual', 'end effector target', 'end effector actual']) + # plot.add_legend(['tray', 'end effector']) + + + # plot.save_fig('figure_8_tracking_over_time') + plot.save_fig('figure_8_tracking') + + # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) + # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) + # plot.axes[0].set_ylim([0.4, 0.7]) + # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) # plot = plot_styler.PlotStyler(nrows=2) # plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 0) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index b644275774..ccc01ba899 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -343,10 +343,10 @@ def load_default_channels(data, plant, state_channel, input_channel, osc_debug_channel): robot_output = process_state_channel(data[state_channel], plant) robot_input = process_effort_channel(data[input_channel], plant) - # osc_debug = process_osc_channel(data[osc_debug_channel]) - # osc_debug = permute_osc_joint_ordering( - # osc_debug, data[state_channel][0], plant) - osc_debug = None + osc_debug = process_osc_channel(data[osc_debug_channel]) + osc_debug = permute_osc_joint_ordering( + osc_debug, data[state_channel][0], plant) + # osc_debug = None return robot_output, robot_input, osc_debug diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml index 14ac9156b6..9fac62f8af 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -6,11 +6,11 @@ channel_c3: "C3_DEBUG" channel_tray: "TRAY_STATE" channel_c3_target: "C3_TARGET" channel_c3_actual: "C3_ACTUAL" -plot_style: 'compact' # compact, paper, default +plot_style: 'paper' # compact, paper, default start_time: 0 #duration: 0.47 -duration: -1 +duration: 20 # Plant properties # Desired RobotOutput plots diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py index 5ed653eaa5..b99e787f43 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -51,27 +51,60 @@ def load_lcm_logs(): lcm_channels['c3_debug_output_channel']: dairlib.lcmt_c3_output} callback = load_c3_channels mass_range = np.arange(0.5, 2.0, 0.05) - mu_range = np.arange(0.3, 0.8, 0.01) + # mu_range = np.arange(0.3, 0.8, 0.01) + mu_range = np.arange(0.3, 0.8, 0.05) + print(mu_range.shape[0]) + all_successes = np.zeros((mu_range.shape[0], 3)) + for i in range(mu_range.shape[0]): + print(mu_range[i]) + # print(mass_range[i]) + # ps = plot_styler.PlotStyler(nrows=2) + # ps = plot_styler.PlotStyler() + successes = np.zeros(3) - for i in range(mass_range.shape[0]): - print(mass_range[i]) for j in range(10): - ps = plot_styler.PlotStyler(nrows=2) - log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%1d' % (i, j) + log_filename = param_study['results_folder'] + param_study['parameter'][2] + '/simlog-' + '%02d_%1d' % (i, j) log = lcm.EventLog(log_filename, "r") c3_target, c3_actual, c3_output = \ get_log_data(log, c3_channels, start_time, duration, callback, lcm_channels['c3_target_state_channel'], lcm_channels['c3_actual_state_channel'], lcm_channels['c3_debug_output_channel']) - ps.plot(c3_target['t'], c3_target['x'][:, 7:10], subplot_index=1) - ps.plot(c3_actual['t'], c3_actual['x'][:, 7:10], subplot_index=1) + length = min(c3_target['t'].shape[0], c3_actual['t'].shape[0]) + # ps.plot(c3_target['x'][:, 8:9], c3_target['x'][:, 9:10], subplot_index=1) + # ps.plot(c3_actual['x'][:, 8:9], c3_actual['x'][:, 9:10], subplot_index=1) + # ps.plot(c3_actual['t'], c3_actual['x'][:, 7:10], subplot_index=1) + first_target = np.array([0.55, -0.1, 0.485]) + second_target = np.array([0.55, -0.1, 0.6]) + third_target = np.array([0.55, 0.15, 0.485]) + reached_first_target = np.any(np.all(np.isclose(c3_target['x'][:, 7:10], second_target, atol=1e-3), axis=1)) + reached_second_target = np.any(np.all(np.isclose(c3_target['x'][:, 7:10], third_target, atol=1e-3), axis=1)) + reached_third_target = reached_second_target and np.linalg.norm(c3_target['x'][:length, 7:10] - c3_actual['x'][:length, 7:10], axis=1)[-1] < 0.1 + task_success = np.array([reached_first_target, reached_second_target, reached_third_target]) + print('reached_targets: ', task_success) + successes += task_success + # print('reached_second_target: ', reached_second_target) + # print('reached_third_target: ', reached_third_target) t_c3_slice = slice(c3_output['t'].size) - mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1, ps) - plt.show() + # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1, ps) + print(successes) + all_successes[i] = successes + np.save('all_successes', all_successes ) + +def plot_logs(): + all_successes = np.load('all_successes.npy') + bar_width = 0.2 + bar_positions = np.arange(all_successes.shape[0]) + n = all_successes.shape[0] + + # Plotting bars for each task + for i in range(3): + plt.bar(bar_positions + i * (n + 1), all_successes[:, i], label=f'Task {i + 1}') + + plt.show() def main(): load_lcm_logs() - + # plot_logs() diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index aa076cce01..d817bd94fd 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,8 +1,8 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_25_24/parameter_study/ -processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_25_24/parameter_study/data/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_30_24/parameter_study/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_30_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index bbb2784a25..93d808a9a6 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -12,7 +12,7 @@ def main(): cooldown_time = 10.0 start_time = 0 realtime_rate = 1.0 - num_trials = 10 + num_trials = 20 sim_run_time = sim_time / realtime_rate controller_startup_time = 1.0 From b2139ff6b0065905f172da0ed1d8a0b04a6a78be Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 30 Jan 2024 22:47:44 -0500 Subject: [PATCH 644/758] plotting changes --- bindings/pydairlib/analysis/log_plotter_franka.py | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 579f24e066..15ae248356 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -108,7 +108,7 @@ def main(): plot = mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1) plot.axes[0].axhline(y=8.06, color='r', linestyle='-') plot.axes[0].axhline(y=-8.06, color='r', linestyle='-') - plot.save_fig('c3_inputs_' + filename.split('/')[-1]) + # plot.save_fig('c3_inputs_' + filename.split('/')[-1]) @@ -132,8 +132,10 @@ def main(): # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 1:2], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) # plots y - z trajectories - plot.plot(c3_tracking_target['x'][:, 8:9], c3_tracking_target['x'][:, 9:10], subplot_index = 0) - plot.plot(c3_tracking_actual['x'][:, 8:9], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + plot.plot(c3_tracking_target['x'][:, 7:8], c3_tracking_target['x'][:, 9:10], subplot_index = 0) + plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + plot.plot(c3_tracking_target['x'][:, 0:1], c3_tracking_target['x'][:, 2:3], subplot_index = 0) + plot.plot(c3_tracking_actual['x'][:, 0:1], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) # plot.plot(c3_tracking_actual['t'], c3_tracking_target['x'][:, 8:9] - c3_tracking_target['x'][:, 1:2], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) # plot.plot(c3_tracking_target['x'][:, 1:2], c3_tracking_target['x'][:, 2:3], subplot_index = 0) @@ -142,14 +144,15 @@ def main(): # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) # plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) - plot.axes[0].set_ylim([0.3, 0.6]) - plot.axes[0].set_xlim([-0.15, 0.15]) + plot.axes[0].set_ylim([0.4, 0.6]) + plot.axes[0].set_xlim([0.4, 0.7]) plot.add_legend(['tray target', 'tray actual', 'end effector target', 'end effector actual']) # plot.add_legend(['tray', 'end effector']) # plot.save_fig('figure_8_tracking_over_time') - plot.save_fig('figure_8_tracking') + # plot.save_fig('figure_8_tracking') + plot.save_fig('c3_actual_trajectory') # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) From 8c3ec1ae9bc5b86b9fc88a5e99f0b280b90f6c1b Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 31 Jan 2024 22:04:26 -0500 Subject: [PATCH 645/758] plotting changes --- .../pydairlib/analysis/log_plotter_franka.py | 68 ++++++++++++++++--- .../franka_hardware_plot_config.yaml | 4 +- bindings/pydairlib/common/plot_styler.py | 2 +- 3 files changed, 61 insertions(+), 13 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 15ae248356..acd87c92b5 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -12,6 +12,7 @@ from pydrake.all import JointIndex, JointActuatorIndex +from matplotlib.patches import Patch def main(): config_file = ('bindings/pydairlib/analysis/plot_configs' @@ -128,36 +129,83 @@ def main(): # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) # plots between end effector y and tray y - # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) - # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 1:2], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) + plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) + plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 1:2], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) # plots y - z trajectories - plot.plot(c3_tracking_target['x'][:, 7:8], c3_tracking_target['x'][:, 9:10], subplot_index = 0) - plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) - plot.plot(c3_tracking_target['x'][:, 0:1], c3_tracking_target['x'][:, 2:3], subplot_index = 0) - plot.plot(c3_tracking_actual['x'][:, 0:1], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + # plot.axes[0].scatter(c3_tracking_target['x'][0, 7], c3_tracking_target['x'][0, 9], marker='s') + # plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + # plot.plot(c3_tracking_actual['x'][:, 0:1], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) - # plot.plot(c3_tracking_actual['t'], c3_tracking_target['x'][:, 8:9] - c3_tracking_target['x'][:, 1:2], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) # plot.plot(c3_tracking_target['x'][:, 1:2], c3_tracking_target['x'][:, 2:3], subplot_index = 0) # plot.plot(c3_tracking_actual['x'][:, 1:2], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) # plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 7:8], subplot_index = 1) + # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) - plot.axes[0].set_ylim([0.4, 0.6]) + plot.axes[0].set_xlim([0.4, 0.7]) - plot.add_legend(['tray target', 'tray actual', 'end effector target', 'end effector actual']) + plot.axes[0].set_ylim([0.35, 0.65]) + plot.add_legend(['tray actual', 'end effector actual']) # plot.add_legend(['tray', 'end effector']) + plot.save_fig('c3_actual_xz_plot') # plot.save_fig('figure_8_tracking_over_time') # plot.save_fig('figure_8_tracking') - plot.save_fig('c3_actual_trajectory') + plot.save_fig('c3_actual_trajectory_time') # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) # plot.axes[0].set_ylim([0.4, 0.7]) # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) + plotter = plot_styler.PlotStyler() + if True: + # zero_vel_threshold = 0.00001 + # tray_x_vel = np.diff(c3_tracking_actual['x'][:, 7]) + # end_effector_x_vel = np.diff(c3_tracking_actual['x'][:, 0]) + # tray_x_vel[np.abs(tray_x_vel) < zero_vel_threshold] = 0 + # end_effector_x_vel[np.abs(end_effector_x_vel) < zero_vel_threshold] = 0 + # tray_x_vel_dir = np.sign(tray_x_vel) + # end_effector_x_vel_dir = np.sign(end_effector_x_vel) + sticking_contacts = [slice(12, 18), slice(24, 27), slice(34, 53), slice(59, 210), slice(216, 221), slice(232, 235), slice(247, 290)] + sliding_contacts = [slice(17, 25), slice(26, 35), slice(52, 60), slice(209, 217), slice(220, 233), slice(234, 248)] + no_contacts = [slice(0, 13)] + # import pdb; pdb.set_trace() + # sticking = np.sign(tray_x_vel) == np.sign(end_effector_x_vel) + plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 7:10], subplot_index = 0, xlabel='time (s)', ylabel='position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0, xlabel='time (s)', ylabel='position (m)', grid=False) + ax = plotter.fig.axes[0] + ymin, ymax = ax.get_ylim() + for i in no_contacts: + ax.fill_between(c3_tracking_actual['t'][i], ymin, ymax, + color=plotter.cmap(0), alpha=0.2) + for i in sticking_contacts: + ax.fill_between(c3_tracking_actual['t'][i], ymin, ymax, + color=plotter.cmap(2), alpha=0.2) + for i in sliding_contacts: + ax.fill_between(c3_tracking_actual['t'][i], ymin, ymax, + color=plotter.cmap(4), alpha=0.2) + legend_elements = [] + labels = ['No Contact', 'Sticking Contact', 'Sliding Contact'] + for i in range(3): + legend_elements.append( + Patch(facecolor=plotter.cmap(2 * i), alpha=0.3, + label=labels[i])) + # legend = ax.legend(handles=['Tray x', 'Tray y', 'Tray z', 'End Effector x', 'End Effector y', 'End Effector z'], loc=1) + # ax.add_artist(legend) + legend = ax.legend(handles=legend_elements, loc=4) + ax.add_artist(legend) + plotter.add_legend(['Tray x', 'Tray y', 'Tray z', 'End Effector x', 'End Effector y', 'End Effector z'], subplot_index = 0) + plotter.axes[0].set_xlim([7.4, 15.5]) + + plotter.save_fig('c3_actual_trajectory_time') + # plot.plot(c3_tracking_actual['t'][1:], tray_x_vel) + # plot.plot(c3_tracking_actual['t'][1:], end_effector_x_vel) + # plot.plot(c3_tracking_actual['t'][1:], 0.1 * tray_x_vel_dir + 0.5) + # plot.plot(c3_tracking_actual['t'][1:], 0.1 * end_effector_x_vel_dir + 0.5) # plot = plot_styler.PlotStyler(nrows=2) # plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 0) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml index 9fac62f8af..5b21692449 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -8,9 +8,9 @@ channel_c3_target: "C3_TARGET" channel_c3_actual: "C3_ACTUAL" plot_style: 'paper' # compact, paper, default -start_time: 0 +start_time: 7.4 #duration: 0.47 -duration: 20 +duration: 8.5 # Plant properties # Desired RobotOutput plots diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index ea9f5b0224..bdaa694790 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -76,7 +76,7 @@ def attach(self): def plot(self, xdata, ydata, xlim=None, ylim=None, color=None, linestyle=None, - grid=True, xlabel=None, ylabel=None, title=None, legend=None, + grid=False, xlabel=None, ylabel=None, title=None, legend=None, data_label=None, subplot_index=0): self.axes[subplot_index].plot(xdata, ydata, color=color, linestyle=linestyle, label=data_label) From 7e9d6ec629877308dcce1ca5f66e664f92c157bb Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Feb 2024 18:29:55 -0500 Subject: [PATCH 646/758] updating plotting script --- .../pydairlib/analysis/log_plotter_franka.py | 65 +++++++++++++------ .../franka_hardware_plot_config.yaml | 10 +-- .../parameter_study_analysis.py | 12 ++-- .../parameter_study_config.yaml | 4 +- 4 files changed, 57 insertions(+), 34 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index acd87c92b5..c68f90984f 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -128,9 +128,14 @@ def main(): # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 1) # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) + # plot target + # plot.plot(c3_tracking_actual['t'], c3_tracking_target['x'][:, 7:10], subplot_index = 0, ylabel='target position (m)', xlabel='time (s)', grid=False) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 0, ylabel='target position (m)', xlabel='time (s)', grid=False) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0, ylabel='target position (m)', xlabel='time (s)', grid=False) + # plots between end effector y and tray y - plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) - plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 1:2], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) + # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 1:2], subplot_index = 0, ylabel='y position (m)', xlabel='time (s)', grid=False) # plots y - z trajectories # plot.axes[0].scatter(c3_tracking_target['x'][0, 7], c3_tracking_target['x'][0, 9], marker='s') @@ -146,23 +151,25 @@ def main(): # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) - plot.axes[0].set_xlim([0.4, 0.7]) - plot.axes[0].set_ylim([0.35, 0.65]) - plot.add_legend(['tray actual', 'end effector actual']) + # plot.axes[0].set_xlim([0.4, 0.7]) + # plot.axes[0].set_ylim([0.35, 0.65]) + + # plot.add_legend(['tray actual', 'end effector actual']) + plot.add_legend(['tray target x', 'tray target y', 'tray target z']) # plot.add_legend(['tray', 'end effector']) - plot.save_fig('c3_actual_xz_plot') + # plot.save_fig('c3_actual_xz_plot') # plot.save_fig('figure_8_tracking_over_time') # plot.save_fig('figure_8_tracking') - plot.save_fig('c3_actual_trajectory_time') + # plot.save_fig('c3_actual_trajectory_time') # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) # plot.axes[0].set_ylim([0.4, 0.7]) # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) - plotter = plot_styler.PlotStyler() if True: + plotter = plot_styler.PlotStyler() # zero_vel_threshold = 0.00001 # tray_x_vel = np.diff(c3_tracking_actual['x'][:, 7]) # end_effector_x_vel = np.diff(c3_tracking_actual['x'][:, 0]) @@ -173,23 +180,40 @@ def main(): sticking_contacts = [slice(12, 18), slice(24, 27), slice(34, 53), slice(59, 210), slice(216, 221), slice(232, 235), slice(247, 290)] sliding_contacts = [slice(17, 25), slice(26, 35), slice(52, 60), slice(209, 217), slice(220, 233), slice(234, 248)] no_contacts = [slice(0, 13)] - # import pdb; pdb.set_trace() - # sticking = np.sign(tray_x_vel) == np.sign(end_effector_x_vel) - plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 7:10], subplot_index = 0, xlabel='time (s)', ylabel='position (m)', grid=False) - plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0, xlabel='time (s)', ylabel='position (m)', grid=False) + + support_sticking_contacts = [slice(0, 13), slice(18, 27), slice(35, 40), slice(259, 290)] + support_sliding_contacts = [slice(12, 19), slice(26, 36), slice(39, 68), slice(218, 260)] + support_no_contacts = [slice(67, 219)] + + plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 7:8], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) ax = plotter.fig.axes[0] ymin, ymax = ax.get_ylim() + halfway = ymin + 0.5 * (ymax - ymin) + # colors = plt.get_cmap('tab20c') for i in no_contacts: - ax.fill_between(c3_tracking_actual['t'][i], ymin, ymax, + ax.fill_between(c3_tracking_actual['t'][i], halfway, ymax, color=plotter.cmap(0), alpha=0.2) for i in sticking_contacts: - ax.fill_between(c3_tracking_actual['t'][i], ymin, ymax, + ax.fill_between(c3_tracking_actual['t'][i], halfway, ymax, color=plotter.cmap(2), alpha=0.2) for i in sliding_contacts: - ax.fill_between(c3_tracking_actual['t'][i], ymin, ymax, + ax.fill_between(c3_tracking_actual['t'][i], halfway, ymax, + color=plotter.cmap(4), alpha=0.2) + for i in support_no_contacts: + ax.fill_between(c3_tracking_actual['t'][i], ymin, halfway, + color=plotter.cmap(0), alpha=0.2) + for i in support_sticking_contacts: + ax.fill_between(c3_tracking_actual['t'][i], ymin, halfway, + color=plotter.cmap(2), alpha=0.2) + for i in support_sliding_contacts: + ax.fill_between(c3_tracking_actual['t'][i], ymin, halfway, color=plotter.cmap(4), alpha=0.2) legend_elements = [] labels = ['No Contact', 'Sticking Contact', 'Sliding Contact'] + # legend_elements.append(Patch(color='none', label=labels[0])) for i in range(3): legend_elements.append( Patch(facecolor=plotter.cmap(2 * i), alpha=0.3, @@ -198,14 +222,11 @@ def main(): # ax.add_artist(legend) legend = ax.legend(handles=legend_elements, loc=4) ax.add_artist(legend) - plotter.add_legend(['Tray x', 'Tray y', 'Tray z', 'End Effector x', 'End Effector y', 'End Effector z'], subplot_index = 0) + plotter.add_legend(['Tray x', 'Tray z', 'End Effector x', 'End Effector z'], subplot_index = 0, loc=1) plotter.axes[0].set_xlim([7.4, 15.5]) plotter.save_fig('c3_actual_trajectory_time') - # plot.plot(c3_tracking_actual['t'][1:], tray_x_vel) - # plot.plot(c3_tracking_actual['t'][1:], end_effector_x_vel) - # plot.plot(c3_tracking_actual['t'][1:], 0.1 * tray_x_vel_dir + 0.5) - # plot.plot(c3_tracking_actual['t'][1:], 0.1 * end_effector_x_vel_dir + 0.5) + # plot = plot_styler.PlotStyler(nrows=2) # plot.plot(c3_tracking_target['t'], solve_times, subplot_index = 0) @@ -246,7 +267,9 @@ def main(): subplot_index=1) ''' Plot Efforts ''' - effort_plotter = plot_styler.PlotStyler(nrows=2) + if plot_config.plot_measured_efforts or plot_config.plot_commanded_efforts: + effort_plotter = plot_styler.PlotStyler(nrows=2) + if plot_config.plot_measured_efforts: plot = mbp_plots.plot_measured_efforts(robot_output, act_names, t_x_slice, effort_plotter, diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml index 5b21692449..81f29b59de 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -19,7 +19,7 @@ plot_joint_velocities: false plot_measured_efforts: false plot_commanded_efforts: false plot_contact_forces: false -plot_end_effector: true +plot_end_effector: false special_positions_to_plot: [] special_velocities_to_plot: [] @@ -30,14 +30,14 @@ fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', # Desired osc plots plot_qp_costs: false -plot_qp_solve_time: true -plot_qp_solutions: true +plot_qp_solve_time: false +plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: false tracking_datas_to_plot: - end_effector_target: {'dims': [0], 'derivs': ['accel']} +# end_effector_target: {'dims': [0], 'derivs': ['accel']} # end_effector_orientation_target: {'dims': [0, 1, 2], 'derivs': ['pos']} # end_effector_target: {'dims': [0, 1, 2], 'derivs': ['pos', 'vel', 'accel']} plot_c3_debug: true plot_c3_tracking: true -plot_object_state: true \ No newline at end of file +plot_object_state: false \ No newline at end of file diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py index b99e787f43..b9eab2c4be 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -45,14 +45,13 @@ def load_lcm_logs(): start_time = 0 duration = -1 - c3_channels = {lcm_channels['c3_target_state_channel']: dairlib.lcmt_c3_state, lcm_channels['c3_actual_state_channel']: dairlib.lcmt_c3_state, lcm_channels['c3_debug_output_channel']: dairlib.lcmt_c3_output} callback = load_c3_channels mass_range = np.arange(0.5, 2.0, 0.05) # mu_range = np.arange(0.3, 0.8, 0.01) - mu_range = np.arange(0.3, 0.8, 0.05) + mu_range = np.arange(0.3, 0.74, 0.05) print(mu_range.shape[0]) all_successes = np.zeros((mu_range.shape[0], 3)) for i in range(mu_range.shape[0]): @@ -62,8 +61,9 @@ def load_lcm_logs(): # ps = plot_styler.PlotStyler() successes = np.zeros(3) - for j in range(10): - log_filename = param_study['results_folder'] + param_study['parameter'][2] + '/simlog-' + '%02d_%1d' % (i, j) + for j in range(30): + log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%02d' % (i, j) + print(log_filename) log = lcm.EventLog(log_filename, "r") c3_target, c3_actual, c3_output = \ get_log_data(log, c3_channels, start_time, duration, callback, @@ -103,8 +103,8 @@ def plot_logs(): plt.show() def main(): - load_lcm_logs() - # plot_logs() + # load_lcm_logs() + plot_logs() diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index d817bd94fd..0c780d53a4 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,8 +1,8 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_30_24/parameter_study/ -processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_30_24/parameter_study/data/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller From e24c6cce10be3247cadb2d3cd66b5c511667e74d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Feb 2024 19:24:03 -0500 Subject: [PATCH 647/758] debugging all controller + sim in loop --- examples/franka/BUILD.bazel | 29 + examples/franka/franka_c3_controller.cc | 2 +- examples/franka/franka_osc_controller.cc | 4 +- examples/franka/full_diagram.cc | 645 ++++++++++++++++++ .../parameters/franka_osc_controller_params.h | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- 6 files changed, 678 insertions(+), 6 deletions(-) create mode 100644 examples/franka/full_diagram.cc diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 28acd29322..444a1ceb7a 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -22,6 +22,35 @@ cc_library( deps = [], ) +cc_binary( + name = "full_diagram", + srcs = ["full_diagram.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_c3_controller_params", + ":franka_lcm_channels", + ":franka_osc_controller_params", + ":franka_sim_params", + "//common", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers:c3_controller", + "//systems/controllers:lcs_factory_system", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/trajectory_optimization:c3_output_systems", + "//systems/trajectory_optimization:lcm_trajectory_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "franka_sim", srcs = ["franka_sim.cc"], diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 1052bcad4c..4dc0f40ac1 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -316,7 +316,7 @@ int DoMain(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); - DrawAndSaveDiagramGraph(*plant_diagram); +// DrawAndSaveDiagramGraph(*plant_diagram); // Run lcm-driven simulation systems::LcmDrivenLoop loop( diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 0545fdfeea..762eeadc22 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -90,14 +90,12 @@ int DoMain(int argc, char* argv[]) { RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), X_WI); - Vector3d tool_attachment_frame = - StdVectorToVectorXd(controller_params.tool_attachment_frame); if (!controller_params.end_effector_name.empty()) { drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( FindResourceOrThrow(controller_params.end_effector_model))[0]; RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), tool_attachment_frame); + drake::math::RotationMatrix(), controller_params.tool_attachment_frame); plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName(controller_params.end_effector_name, end_effector_index), diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc new file mode 100644 index 0000000000..8b46c258bb --- /dev/null +++ b/examples/franka/full_diagram.cc @@ -0,0 +1,645 @@ +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "common/find_resource.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_osc_controller_params.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/systems/c3_state_sender.h" +#include "examples/franka/systems/c3_trajectory_generator.h" +#include "examples/franka/systems/end_effector_force_trajectory.h" +#include "examples/franka/systems/end_effector_orientation.h" +#include "examples/franka/systems/end_effector_trajectory.h" +#include "examples/franka/systems/franka_kinematics.h" +#include "examples/franka/systems/plate_balancing_target.h" +#include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/c3/lcs_factory_system.h" +#include "systems/controllers/c3_controller.h" +#include "systems/controllers/osc/external_force_tracking_data.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" + + +namespace dairlib { + +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::GeometrySet; +using drake::geometry::SceneGraph; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::Context; +using drake::systems::DiagramBuilder; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using systems::AddActuationRecieverAndStateSenderLcm; +using systems::RobotInputReceiver; +using systems::RobotOutputSender; + +using drake::math::RigidTransform; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using systems::controllers::ExternalForceTrackingData; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; + +DEFINE_string(controller_settings, + "examples/franka/parameters/franka_c3_controller_params.yaml", + "Controller settings such as channels. Attempting to minimize " + "number of gflags"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile( + "examples/franka/parameters/lcm_channels_simulation.yaml"); + // load parameters + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + FrankaC3ControllerParams c3_controller_params = + drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_c3_controller_params.yaml"); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(c3_controller_params.osqp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + C3Options c3_options = drake::yaml::LoadYamlFile( + c3_controller_params.c3_options_file[c3_controller_params.scene_index]); + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow( + "examples/franka/parameters/franka_osc_controller_params.yaml"), + {}, {}, yaml_options); + FrankaControllerParams controller_params = + drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_osc_controller_params.yaml"); + + DiagramBuilder builder; + + /// OSC + drake::multibody::MultibodyPlant osc_plant(0.0); + Parser osc_parser(&osc_plant, nullptr); + osc_parser.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + + RigidTransform X_WI = RigidTransform::Identity(); + osc_plant.WeldFrames(osc_plant.world_frame(), + osc_plant.GetFrameByName("panda_link0"), X_WI); + + if (!controller_params.end_effector_name.empty()) { + drake::multibody::ModelInstanceIndex end_effector_index = + osc_parser.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + osc_plant.WeldFrames( + osc_plant.GetFrameByName("panda_link7"), + osc_plant.GetFrameByName(controller_params.end_effector_name, + end_effector_index), + T_EE_W); + } else { + std::cout << "OSC osc_plant has been constructed with no end effector." + << std::endl; + } + osc_plant.Finalize(); + auto osc_plant_context = osc_plant.CreateDefaultContext(); + + auto end_effector_position_receiver = + builder.AddSystem( + "end_effector_position_target"); + auto end_effector_force_receiver = + builder.AddSystem( + "end_effector_force_target"); + auto end_effector_orientation_receiver = + builder.AddSystem( + "end_effector_orientation_target"); + auto osc_command_sender = + builder.AddSystem(osc_plant); + auto end_effector_trajectory = + builder.AddSystem( + osc_plant, osc_plant_context.get()); + auto end_effector_orientation_trajectory = + builder.AddSystem( + osc_plant, osc_plant_context.get()); + end_effector_orientation_trajectory->SetTrackOrientation( + controller_params.track_end_effector_orientation); + auto end_effector_force_trajectory = + builder.AddSystem( + osc_plant, osc_plant_context.get()); + auto osc = builder.AddSystem( + osc_plant, osc_plant, osc_plant_context.get(), osc_plant_context.get(), + false); + auto end_effector_position_tracking_data = + std::make_unique( + "end_effector_target", controller_params.K_p_end_effector, + controller_params.K_d_end_effector, controller_params.W_end_effector, + osc_plant, osc_plant); + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_input_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + end_effector_position_tracking_data->AddPointToTrack( + controller_params.end_effector_name); + const VectorXd& end_effector_acceleration_limits = + controller_params.end_effector_acceleration * Vector3d::Ones(); + end_effector_position_tracking_data->SetCmdAccelerationBounds( + -end_effector_acceleration_limits, end_effector_acceleration_limits); + auto mid_link_position_tracking_data_for_rel = + std::make_unique( + "panda_joint2_target", controller_params.K_p_mid_link, + controller_params.K_d_mid_link, controller_params.W_mid_link, + osc_plant, osc_plant); + mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", + "panda_joint2dot"); + + auto end_effector_force_tracking_data = + std::make_unique( + "end_effector_force", controller_params.W_ee_lambda, osc_plant, + osc_plant, controller_params.end_effector_name, Vector3d::Zero()); + + auto end_effector_orientation_tracking_data = + std::make_unique( + "end_effector_orientation_target", + controller_params.K_p_end_effector_rot, + controller_params.K_d_end_effector_rot, + controller_params.W_end_effector_rot, osc_plant, osc_plant); + end_effector_orientation_tracking_data->AddFrameToTrack( + controller_params.end_effector_name); + Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); + orientation_target(0) = 1; + osc->AddTrackingData(std::move(end_effector_position_tracking_data)); + osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), + 1.6 * VectorXd::Ones(1)); + osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); + osc->AddForceTrackingData(std::move(end_effector_force_tracking_data)); + osc->SetAccelerationCostWeights(gains.W_acceleration); + osc->SetInputCostWeights(gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); + osc->SetAccelerationConstraints( + controller_params.enforce_acceleration_constraints); + + osc->SetContactFriction(controller_params.mu); + drake::solvers::SolverOptions osc_solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow( + "examples/franka/parameters/franka_osc_qp_settings.yaml")) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + osc->SetOsqpSolverOptions(osc_solver_options); + + osc->Build(); + /// end of OSC + + /// C3 plant + DiagramBuilder plant_builder; + + MultibodyPlant plant_franka(0.0); + Parser parser_franka(&plant_franka, nullptr); + parser_franka.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = + parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + + plant_franka.WeldFrames(plant_franka.world_frame(), + plant_franka.GetFrameByName("panda_link0"), X_WI); + + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + plant_franka.WeldFrames( + plant_franka.GetFrameByName("panda_link7"), + plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); + + plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + MultibodyPlant plant_tray(0.0); + Parser parser_tray(&plant_tray, nullptr); + parser_tray.AddModels(c3_controller_params.tray_model); + plant_tray.Finalize(); + auto tray_context = plant_tray.CreateDefaultContext(); + + auto [plant_for_lcs, lcs_scene_graph] = + AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + Parser parser_plate(&plant_for_lcs); + parser_plate.SetAutoRenaming(true); + parser_plate.AddModels(c3_controller_params.plate_model); + + drake::multibody::ModelInstanceIndex left_support_index; + drake::multibody::ModelInstanceIndex right_support_index; + if (c3_controller_params.scene_index > 0) { + left_support_index = parser_plate.AddModels( + FindResourceOrThrow(c3_controller_params.left_support_model))[0]; + right_support_index = parser_plate.AddModels( + FindResourceOrThrow(c3_controller_params.right_support_model))[0]; + RigidTransform T_S1_W = RigidTransform( + drake::math::RollPitchYaw( + c3_controller_params.left_support_orientation), + c3_controller_params.left_support_position); + RigidTransform T_S2_W = RigidTransform( + drake::math::RollPitchYaw( + c3_controller_params.right_support_orientation), + c3_controller_params.right_support_position); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); + } + parser_plate.AddModels(c3_controller_params.tray_model); + + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("base_link"), X_WI); + plant_for_lcs.Finalize(); + std::unique_ptr> plant_for_lcs_autodiff = + drake::systems::System::ToAutoDiffXd(plant_for_lcs); + + auto plant_diagram = plant_builder.Build(); + std::unique_ptr> diagram_context = + plant_diagram->CreateDefaultContext(); + auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( + plant_for_lcs, diagram_context.get()); + auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); + std::vector plate_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("plate")); + if (c3_controller_params.scene_index > 0) { + std::vector left_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", left_support_index)); + std::vector right_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", right_support_index)); + plate_contact_points.insert(plate_contact_points.end(), + left_support_contact_points.begin(), + left_support_contact_points.end()); + plate_contact_points.insert(plate_contact_points.end(), + right_support_contact_points.begin(), + right_support_contact_points.end()); + } + std::vector tray_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("tray")); + std::unordered_map> + contact_geoms; + contact_geoms["PLATE"] = plate_contact_points; + contact_geoms["TRAY"] = tray_geoms; + + std::vector> contact_pairs; + for (auto geom_id : contact_geoms["PLATE"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); + } + + auto franka_state_receiver = + builder.AddSystem(plant_franka); + auto tray_state_receiver = + builder.AddSystem(plant_tray); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_tray, tray_context.get(), + controller_params.end_effector_name, "tray", + c3_controller_params.include_end_effector_orientation); + + auto plate_balancing_target = + builder.AddSystem( + plant_tray, c3_controller_params.end_effector_thickness, + c3_controller_params.near_target_threshold); + plate_balancing_target->SetRemoteControlParameters( + c3_controller_params.first_target[c3_controller_params.scene_index], + c3_controller_params.second_target[c3_controller_params.scene_index], + c3_controller_params.third_target[c3_controller_params.scene_index], + c3_controller_params.x_scale, c3_controller_params.y_scale, + c3_controller_params.z_scale); + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto tray_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(plate_balancing_target->get_output_port_tray_target(), + target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(tray_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(3)); + auto lcs_factory = builder.AddSystem( + plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, + plate_context_ad.get(), contact_pairs, c3_options); + auto c3_controller = builder.AddSystem( + plant_for_lcs, &plant_for_lcs_context, c3_options); + auto c3_trajectory_generator = + builder.AddSystem(plant_for_lcs, + c3_options); + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", + "tray_qx", "tray_qy", "tray_qz", "tray_x", + "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", + "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", + "tray_vz", "tray_vz", "tray_vz", + }; + auto c3_state_sender = + builder.AddSystem(3 + 7 + 3 + 6, state_names); + c3_trajectory_generator->SetPublishEndEffectorOrientation( + c3_controller_params.include_end_effector_orientation); + auto c3_output_sender = builder.AddSystem(); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); +// auto c3_output_publisher = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.c3_debug_output_channel, &lcm, +// TriggerTypeSet({TriggerType::kForced}))); + /// C3 + + /// Sim Start + double sim_dt = sim_params.dt; + auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); + + Parser parser(&plant); + parser.SetAutoRenaming(true); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + drake::multibody::ModelInstanceIndex c3_end_effector_index = + parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); + + Vector3d franka_origin = Eigen::VectorXd::Zero(3); + + RigidTransform T_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + T_X_W); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName("plate", c3_end_effector_index), + T_EE_W); + + if (sim_params.scene_index > 0) { + drake::multibody::ModelInstanceIndex left_support_index = + parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; + drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( + FindResourceOrThrow(sim_params.right_support_model))[0]; + RigidTransform T_S1_W = RigidTransform( + drake::math::RollPitchYaw(sim_params.left_support_orientation), + sim_params.left_support_position); + RigidTransform T_S2_W = RigidTransform( + drake::math::RollPitchYaw(sim_params.right_support_orientation), + sim_params.right_support_position); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", left_support_index), + T_S1_W); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", right_support_index), + T_S2_W); + const drake::geometry::GeometrySet& support_geom_set = + plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("support", left_support_index), + &plant.GetBodyByName("support", right_support_index), + }); + // we WANT to model collisions between link5 and the supports + const drake::geometry::GeometrySet& paddle_geom_set = + plant.CollectRegisteredGeometries( + {&plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link7"), &plant.GetBodyByName("plate"), + &plant.GetBodyByName("panda_link8")}); + + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"paddle", support_geom_set}, {"tray", paddle_geom_set}); + } + + const drake::geometry::GeometrySet& paddle_geom_set = + plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link8"), + }); + auto tray_collision_set = GeometrySet( + plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"paddle", paddle_geom_set}, {"tray", tray_collision_set}); + + plant.Finalize(); + /* -------------------------------------------------------------------------------------------*/ + auto input_receiver = builder.AddSystem(plant); + auto passthrough = builder.AddSystem( + input_receiver->get_output_port(0).size(), 0, + plant.get_actuation_input_port().size()); + builder.Connect(*input_receiver, *passthrough); + auto tray_state_sender = + builder.AddSystem(plant, tray_index); + auto franka_state_sender = + builder.AddSystem(plant, franka_index, false); + auto state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_state_channel, &lcm, 1.0 / sim_params.franka_publish_rate)); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + std::cout << lcm_channel_params.radio_channel << std::endl; + auto osc_state_receiver = + builder.AddSystem(osc_plant); + + //// OSC connections + builder.Connect(osc_state_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_trajectory->get_input_port_radio()); + builder.Connect(osc_state_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_radio()); + builder.Connect(osc_state_receiver->get_output_port(0), + end_effector_force_trajectory->get_input_port_state()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_force_trajectory->get_input_port_radio()); + builder.Connect(osc->get_output_port_osc_command(), + osc_command_sender->get_input_port(0)); + + builder.Connect(osc_state_receiver->get_output_port(0), + osc->get_input_port_robot_output()); + builder.Connect(end_effector_position_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_trajectory()); + builder.Connect( + end_effector_orientation_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect( + end_effector_orientation_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); + builder.Connect(end_effector_force_receiver->get_output_port(0), + end_effector_force_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_force_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_force")); + builder.Connect(osc_command_sender->get_output_port(), + franka_command_pub->get_input_port()); + builder.Connect(plant.get_state_output_port(tray_index), + tray_state_sender->get_input_port_state()); + c3_controller->SetOsqpSolverOptions(solver_options); + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(target_state_mux->get_output_port(), + c3_controller->get_input_port_target()); + builder.Connect(lcs_factory->get_output_port_lcs(), + c3_controller->get_input_port_lcs()); + builder.Connect(tray_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(tray_state_receiver->get_output_port(), + plate_balancing_target->get_input_port_tray_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + c3_controller->get_input_port_lcs_state()); + builder.Connect(radio_sub->get_output_port(), + c3_controller->get_input_port_radio()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + lcs_factory->get_input_port_lcs_state()); + builder.Connect(radio_sub->get_output_port(), + plate_balancing_target->get_input_port_radio()); + builder.Connect(c3_controller->get_output_port_c3_solution(), + c3_trajectory_generator->get_input_port_c3_solution()); + builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), + c3_output_sender->get_input_port_lcs_contact_info()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); +// builder.Connect(c3_output_sender->get_output_port_c3_debug(), +// c3_output_publisher->get_input_port()); + builder.Connect(c3_controller->get_output_port_c3_solution(), + c3_output_sender->get_input_port_c3_solution()); + builder.Connect(c3_controller->get_output_port_c3_intermediates(), + c3_output_sender->get_input_port_c3_intermediates()); + + // Diagram Connections + builder.Connect(*tray_state_sender, *tray_state_receiver); + builder.Connect(*osc_command_sender, *input_receiver); + builder.Connect(passthrough->get_output_port(), + plant.get_actuation_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + end_effector_force_receiver->get_input_port_trajectory()); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + end_effector_position_receiver->get_input_port_trajectory()); + builder.Connect( + c3_trajectory_generator->get_output_port_actor_trajectory(), + end_effector_orientation_receiver->get_input_port_trajectory()); + builder.Connect(*franka_state_sender, *franka_state_receiver); + builder.Connect(*franka_state_sender, *osc_state_receiver); + builder.Connect(*franka_state_sender, *state_pub); + builder.Connect(plant.get_state_output_port(franka_index), + franka_state_sender->get_input_port_state()); + + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + + if (sim_params.visualize_drake_sim) { + drake::visualization::AddDefaultVisualization(&builder); + } + + auto diagram = builder.Build(); + diagram->set_name("plate_balancing_full_diagram"); + DrawAndSaveDiagramGraph(*diagram); + + drake::systems::Simulator simulator(*diagram); + + simulator.set_publish_every_time_step(true); + simulator.set_publish_at_initialization(true); + simulator.set_target_realtime_rate(sim_params.realtime_rate); + + auto& plant_context = diagram->GetMutableSubsystemContext( + plant, &simulator.get_mutable_context()); + + VectorXd q = VectorXd::Zero(nq); + std::map q_map = MakeNameToPositionsMap(plant); + + q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; + + q.tail(plant.num_positions(tray_index)) = + sim_params.q_init_plate[sim_params.scene_index]; + + plant.SetPositions(&plant_context, q); + + VectorXd v = VectorXd::Zero(nv); + plant.SetVelocities(&plant_context, v); + + simulator.Initialize(); + simulator.AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index 2138d28b64..9b429d47f4 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -9,7 +9,7 @@ struct FrankaControllerParams : OSCGains { std::string end_effector_model; std::string end_effector_name; - std::vector tool_attachment_frame; + Eigen::VectorXd tool_attachment_frame; double end_effector_acceleration; bool track_end_effector_orientation; bool cancel_gravity_compensation; diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 174e05d7b1..812ba3ef43 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -13,7 +13,7 @@ visualizer_publish_rate: 10 actuator_delay: 0.000 scene_index: 1 -visualize_drake_sim: false +visualize_drake_sim: true publish_efforts: true camera_pose: [[1.5, 0, 0.6], From 7c08c321218ac4cdfa2ca815e2fcec273077645b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 1 Feb 2024 20:40:56 -0500 Subject: [PATCH 648/758] changes for c3_tracking figure --- bindings/pydairlib/analysis/log_plotter_franka.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index c68f90984f..296a07fb88 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -212,7 +212,7 @@ def main(): ax.fill_between(c3_tracking_actual['t'][i], ymin, halfway, color=plotter.cmap(4), alpha=0.2) legend_elements = [] - labels = ['No Contact', 'Sticking Contact', 'Sliding Contact'] + labels = ['No Contact', 'Sticking', 'Sliding'] # legend_elements.append(Patch(color='none', label=labels[0])) for i in range(3): legend_elements.append( From 8f5f7bbc9c87359bad7a09d311e8c57ff6ee37ab Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 2 Feb 2024 13:47:34 -0500 Subject: [PATCH 649/758] parameter study changes --- .../pydairlib/analysis/log_plotter_franka.py | 27 +++---- .../franka_hardware_plot_config.yaml | 2 +- .../parameter_study_analysis.py | 46 ++++++++---- .../parameter_study_config.yaml | 10 +-- .../run_tray_parameter_study.py | 74 ++++++++++++------- bindings/pydairlib/common/plot_styler.py | 14 ++-- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../plate_end_effector_parameter_sweep.urdf | 4 +- 9 files changed, 110 insertions(+), 71 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 296a07fb88..a3d1a9ee4a 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -139,8 +139,8 @@ def main(): # plots y - z trajectories # plot.axes[0].scatter(c3_tracking_target['x'][0, 7], c3_tracking_target['x'][0, 9], marker='s') - # plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) - # plot.plot(c3_tracking_actual['x'][:, 0:1], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) + plot.plot(c3_tracking_actual['x'][:, 7:8], c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='X Position (m)', ylabel='Z Position (m)', grid=False) + plot.plot(c3_tracking_actual['x'][:, 0:1], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='X Position (m)', ylabel='Z Position (m)', grid=False) # plot.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 8:9], subplot_index = 0, xlabel='y position (m)', ylabel='z position (m)', grid=False) # plot.plot(c3_tracking_target['x'][:, 1:2], c3_tracking_target['x'][:, 2:3], subplot_index = 0) @@ -151,17 +151,18 @@ def main(): # plot.add_legend(['robot_des_x', 'robot_des_y', 'robot_des_z', 'robot_x', 'robot_y', 'robot_z'], subplot_index = 0) - # plot.axes[0].set_xlim([0.4, 0.7]) - # plot.axes[0].set_ylim([0.35, 0.65]) + plot.axes[0].set_xlim([0.4, 0.8]) + plot.axes[0].set_ylim([0.35, 0.65]) - # plot.add_legend(['tray actual', 'end effector actual']) - plot.add_legend(['tray target x', 'tray target y', 'tray target z']) + plot.add_legend(['Tray Path', 'End Effector Path']) + # plot.add_legend(['tray target x', 'tray target y', 'tray target z']) # plot.add_legend(['tray', 'end effector']) # plot.save_fig('c3_actual_xz_plot') # plot.save_fig('figure_8_tracking_over_time') # plot.save_fig('figure_8_tracking') + plot.save_fig('c3_gaiting') # plot.save_fig('c3_actual_trajectory_time') # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 0:1], subplot_index = 0) @@ -177,17 +178,17 @@ def main(): # end_effector_x_vel[np.abs(end_effector_x_vel) < zero_vel_threshold] = 0 # tray_x_vel_dir = np.sign(tray_x_vel) # end_effector_x_vel_dir = np.sign(end_effector_x_vel) - sticking_contacts = [slice(12, 18), slice(24, 27), slice(34, 53), slice(59, 210), slice(216, 221), slice(232, 235), slice(247, 290)] - sliding_contacts = [slice(17, 25), slice(26, 35), slice(52, 60), slice(209, 217), slice(220, 233), slice(234, 248)] - no_contacts = [slice(0, 13)] + sticking_contacts = [slice(12, 18), slice(25, 28), slice(34, 53), slice(59, 210), slice(216, 221), slice(232, 235), slice(247, 290)] + sliding_contacts = [slice(17, 20), slice(22, 26), slice(27, 35), slice(52, 60), slice(209, 217), slice(220, 233), slice(234, 248)] + no_contacts = [slice(0, 13), slice(19, 23)] support_sticking_contacts = [slice(0, 13), slice(18, 27), slice(35, 40), slice(259, 290)] support_sliding_contacts = [slice(12, 19), slice(26, 36), slice(39, 68), slice(218, 260)] support_no_contacts = [slice(67, 219)] plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 7:8], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) - plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) ax = plotter.fig.axes[0] ymin, ymax = ax.get_ylim() @@ -220,12 +221,12 @@ def main(): label=labels[i])) # legend = ax.legend(handles=['Tray x', 'Tray y', 'Tray z', 'End Effector x', 'End Effector y', 'End Effector z'], loc=1) # ax.add_artist(legend) - legend = ax.legend(handles=legend_elements, loc=4) + legend = ax.legend(handles=legend_elements, loc=(0.55, 0.765)) ax.add_artist(legend) - plotter.add_legend(['Tray x', 'Tray z', 'End Effector x', 'End Effector z'], subplot_index = 0, loc=1) + plotter.add_legend(['Tray x', 'End Effector x', 'Tray z', 'End Effector z'], subplot_index = 0, loc=(0.27, 0.7)) plotter.axes[0].set_xlim([7.4, 15.5]) - plotter.save_fig('c3_actual_trajectory_time') + # plotter.save_fig('c3_actual_trajectory_time') # plot = plot_styler.PlotStyler(nrows=2) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml index 81f29b59de..5e94a9f970 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -10,7 +10,7 @@ plot_style: 'paper' # compact, paper, default start_time: 7.4 #duration: 0.47 -duration: 8.5 +duration: 1.5 # Plant properties # Desired RobotOutput plots diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py index b9eab2c4be..a85e9c763c 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -51,17 +51,19 @@ def load_lcm_logs(): callback = load_c3_channels mass_range = np.arange(0.5, 2.0, 0.05) # mu_range = np.arange(0.3, 0.8, 0.01) - mu_range = np.arange(0.3, 0.74, 0.05) - print(mu_range.shape[0]) - all_successes = np.zeros((mu_range.shape[0], 3)) - for i in range(mu_range.shape[0]): - print(mu_range[i]) + effective_mu_range = np.arange(0.2, 0.61, 0.05) + + print(effective_mu_range.shape[0]) + all_successes = np.zeros((effective_mu_range.shape[0], 3)) + for i in range(effective_mu_range.shape[0]): + print('%02d', effective_mu_range[i]) # print(mass_range[i]) # ps = plot_styler.PlotStyler(nrows=2) - # ps = plot_styler.PlotStyler() + successes = np.zeros(3) for j in range(30): + # ps = plot_styler.PlotStyler() log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%02d' % (i, j) print(log_filename) log = lcm.EventLog(log_filename, "r") @@ -70,9 +72,10 @@ def load_lcm_logs(): lcm_channels['c3_target_state_channel'], lcm_channels['c3_actual_state_channel'], lcm_channels['c3_debug_output_channel']) length = min(c3_target['t'].shape[0], c3_actual['t'].shape[0]) - # ps.plot(c3_target['x'][:, 8:9], c3_target['x'][:, 9:10], subplot_index=1) - # ps.plot(c3_actual['x'][:, 8:9], c3_actual['x'][:, 9:10], subplot_index=1) - # ps.plot(c3_actual['t'], c3_actual['x'][:, 7:10], subplot_index=1) + # ps.plot(c3_actual['t'], c3_actual['x'][:, 8:9], subplot_index=0) + # ps.plot(c3_actual['t'], c3_actual['x'][:, 9:10], subplot_index=0) + # ps.plot(c3_actual['t'], c3_actual['x'][:, 1:2], subplot_index=0) + # ps.plot(c3_actual['t'], c3_actual['x'][:, 2:3], subplot_index=0) first_target = np.array([0.55, -0.1, 0.485]) second_target = np.array([0.55, -0.1, 0.6]) third_target = np.array([0.55, 0.15, 0.485]) @@ -86,19 +89,36 @@ def load_lcm_logs(): # print('reached_third_target: ', reached_third_target) t_c3_slice = slice(c3_output['t'].size) # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1, ps) + # plt.show() print(successes) all_successes[i] = successes - np.save('all_successes', all_successes ) + np.save('target_successes', all_successes ) def plot_logs(): all_successes = np.load('all_successes.npy') - bar_width = 0.2 + bar_width = 0.025 bar_positions = np.arange(all_successes.shape[0]) n = all_successes.shape[0] + # mu_range = np.arange(0.3, 0.74, 0.05) + effective_mu_range = np.arange(0.2, 0.61, 0.05) + plt.rc('legend', fontsize=36) + plt.rc('axes', labelsize=36, titlesize=36) + plt.rc('xtick', labelsize=36) + plt.rc('ytick', labelsize=36) # Plotting bars for each task - for i in range(3): - plt.bar(bar_positions + i * (n + 1), all_successes[:, i], label=f'Task {i + 1}') + for i in range(n): + # for j in range(3): + # plt.bar(bar_positions[i], all_successes[i, 2] / 30, width=bar_width) + # plt.bar(mu_range[i], all_successes[i, 2] / all_successes[i, 0], width=bar_width, color='grey') + plt.bar(effective_mu_range[i], all_successes[i, 0] / 30, width=bar_width, color='grey') + plt.ylabel('Target Success Rate') + plt.xlabel('Tray/End Effector Friction Coefficient') + + plt.savefig('/home/yangwill/Pictures/plot_styler/' + 'target_1_success') + # plt.legend() + # for i in range(3): + # plt.bar(bar_positions + i * (n + 1), all_successes[:, i], label=f'Task {i + 1}') plt.show() diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index 0c780d53a4..69088c438d 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,7 +1,7 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/02_02_24/parameter_study/ processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller @@ -9,12 +9,12 @@ c3_cmd: bazel-bin/examples/franka/franka_c3_controller fix_inertia_cmd: 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' nominal_c3_gain_filename: franka_c3_options_side_supports.yaml -nominal_model_filename: tray.sdf -#nominal_model_filename: plate_end_effector.urdf +#nominal_model_filename: tray.sdf +nominal_model_filename: plate_end_effector.urdf modified_c3_gain_filename: franka_c3_options_parameter_sweep.yaml -modified_model_filename: tray_parameter_sweep.sdf -#modified_model_filename: plate_end_effector_parameter_sweep.urdf +#modified_model_filename: tray_parameter_sweep.sdf +modified_model_filename: plate_end_effector_parameter_sweep.urdf parameter: ['mu_c3', 'mass_real', 'mu_real'] diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index 93d808a9a6..106aee1f1e 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -12,9 +12,10 @@ def main(): cooldown_time = 10.0 start_time = 0 realtime_rate = 1.0 - num_trials = 20 + num_trials = 10 + c3_start_up_time = 4.0 sim_run_time = sim_time / realtime_rate - controller_startup_time = 1.0 + controller_startup_time = 0.1 with open('bindings/pydairlib/analysis/tray_balance_study/' + config_file) as f: filedata = f.read() @@ -31,49 +32,66 @@ def main(): nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' # nominal_real_mu_value = '0.4' - nominal_real_mu_value = '' + nominal_real_mu_value = '' nominal_tray_mass = '1' - mu_range = np.arange(0.3, 0.8, 0.05) - mass_range = np.arange(0.5, 2.0, 0.05) + # mu_range = np.arange(0.3, 0.8, 0.05) + # mass_range = np.arange(0.5, 2.0, 0.05) + effective_mu_range = np.arange(0.2, 0.71, 0.05) + tray_mu = 0.4 + + initial_radio_msg = dairlib.lcmt_radio_out() + start_c3_radio_msg = dairlib.lcmt_radio_out() + initial_radio_msg.channel[13] = 1 + initial_radio_msg.channel[11] = 0 + initial_radio_msg.channel[14] = 1 + start_c3_radio_msg.channel[13] = 1 + start_c3_radio_msg.channel[11] = 0 + start_c3_radio_msg.channel[14] = 0 # for i in trange(mu_range.shape[0]): - for i in trange(mass_range.shape[0]): - for j in trange(num_trials): - log_path = config['results_folder'] + parameter + '/simlog-' + '%02d_%1d' % (i, j) + for i in trange(effective_mu_range.shape[0]): + plate_mu = 0.5 * effective_mu_range[i] / (1 - effective_mu_range[i]/(2 * tray_mu)) - # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) - modified_mass_value = ' %.1f ' % (mass_range[i]) - # modified_real_mu_value = '%.2f' % (mu_range[i]) - # modified_real_mu_value = '' % (mu_range[i]) + # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) + # modified_mass_value = ' %.1f ' % (mass_range[i]) + # modified_real_mu_value = '%.2f' % (mu_range[i]) + modified_real_mu_value = '' % (plate_mu) - # f = open(gains_path + gain_filename, 'r') - f = open(config['model_path'] + config['nominal_model_filename'], 'r') + # f = open(gains_path + gain_filename, 'r') + f = open(config['model_path'] + config['nominal_model_filename'], 'r') - filedata = f.read() - f.close() - # newdata = filedata.replace(nominal_mu_value, modified_mu_value) - # newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) - newdata = filedata.replace(nominal_tray_mass, modified_mass_value) + filedata = f.read() + f.close() + # newdata = filedata.replace(nominal_mu_value, modified_mu_value) + newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) + # newdata = filedata.replace(nominal_tray_mass, modified_mass_value) + + # f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') + f = open(config['model_path'] + config['modified_model_filename'], 'w') + print(config['model_path'] + config['modified_model_filename']) + f.write(newdata) + f.close() + if parameter == 'mass_real': + fix_inertia_process = subprocess.Popen(config['fix_inertia_cmd'].split(' ')) + time.sleep(1.0) - # f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') - f = open(config['model_path'] + config['modified_model_filename'], 'w') - f.write(newdata) - f.close() - if parameter == 'mass_real': - fix_inertia_process = subprocess.Popen(config['fix_inertia_cmd'].split(' ')) - time.sleep(1.0) + for j in trange(num_trials): + log_path = config['results_folder'] + parameter + '/simlog-' + '%02d_%1d' % (i, j) lcm_logger_cmd = ['lcm-logger', '-f', '%s' % log_path, ] - logger_process = subprocess.Popen(lcm_logger_cmd) osc_process = subprocess.Popen(config['osc_cmd']) + c3_process = subprocess.Popen(config['c3_cmd']) sim_process = subprocess.Popen(config['sim_cmd']) time.sleep(controller_startup_time) - c3_process = subprocess.Popen(config['c3_cmd']) + publisher.publish("RADIO", initial_radio_msg.encode()) + logger_process = subprocess.Popen(lcm_logger_cmd) + time.sleep(c3_start_up_time) + publisher.publish("RADIO", start_c3_radio_msg.encode()) time.sleep(sim_run_time) osc_process.kill() c3_process.kill() diff --git a/bindings/pydairlib/common/plot_styler.py b/bindings/pydairlib/common/plot_styler.py index bdaa694790..963ad1a9ae 100644 --- a/bindings/pydairlib/common/plot_styler.py +++ b/bindings/pydairlib/common/plot_styler.py @@ -12,12 +12,12 @@ class PlotStyler(): def set_paper_styling(): # matplotlib.rcParams['figure.figsize'] = 20, 12 # matplotlib.rcParams['figure.figsize'] = 20, 6 - matplotlib.rcParams['figure.figsize'] = 8, 6 + matplotlib.rcParams['figure.figsize'] = 16, 12 plt.rcParams['figure.dpi'] = 200 matplotlib.rcParams['figure.autolayout'] = True font = {'size': 20} matplotlib.rc('font', **font) - matplotlib.rcParams['lines.linewidth'] = 2 + matplotlib.rcParams['lines.linewidth'] = 4 plt.set_cmap('tab20') @staticmethod def set_compact_styling(): @@ -47,10 +47,10 @@ def __init__(self, figure=None, nrows=1, ncols=1): # self.directory = None self.dpi = plt.rcParams['figure.dpi'] self.directory = '/home/yangwill/Pictures/plot_styler/' - plt.rc('legend', fontsize=14) - plt.rc('axes', labelsize=14, titlesize=14) - plt.rc('xtick', labelsize=14) - plt.rc('ytick', labelsize=14) + plt.rc('legend', fontsize=24) + plt.rc('axes', labelsize=24, titlesize=24) + plt.rc('xtick', labelsize=24) + plt.rc('ytick', labelsize=24) matplotlib.rcParams['figure.figsize'] = 12, 7 matplotlib.rcParams['figure.autolayout'] = True matplotlib.rcParams['axes.xmargin'] = 0 @@ -111,7 +111,7 @@ def show_fig(self): return def save_fig(self, filename): - self.fig.savefig(self.directory + filename, dpi=self.dpi, bbox_inches='tight') + self.fig.savefig(self.directory + filename, dpi=400, bbox_inches='tight') return def add_legend(self, labels, loc=0, subplot_index=0): diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 5f1b285c10..92db6e9c4d 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false publish_debug_info: true diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 812ba3ef43..711ede7887 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,6 +1,6 @@ #franka_model: examples/franka/urdf/franka_no_collision.urdf franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf -end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_model: examples/franka/urdf/plate_end_effector_parameter_sweep.urdf table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf tray_model: examples/franka/urdf/tray.sdf diff --git a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf index c5109a1276..47c45e4458 100644 --- a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf +++ b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf @@ -15,13 +15,13 @@ - + - + From 03121cfba5b83920bfeb2965f77929b414a51777 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 6 Feb 2024 14:20:23 -0500 Subject: [PATCH 650/758] cleaning up code --- .../parameter_study_analysis.py | 24 +++++++++---------- .../parameter_study_config.yaml | 3 ++- .../run_tray_parameter_study.py | 4 ++-- .../franka/parameters/franka_sim_params.h | 8 ------- .../franka/parameters/franka_sim_params.yaml | 14 ++++------- examples/franka/urdf/tray.sdf | 2 +- .../lcm_visualization_systems.cc | 2 +- 7 files changed, 22 insertions(+), 35 deletions(-) diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py index a85e9c763c..15150ebac1 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -51,7 +51,7 @@ def load_lcm_logs(): callback = load_c3_channels mass_range = np.arange(0.5, 2.0, 0.05) # mu_range = np.arange(0.3, 0.8, 0.01) - effective_mu_range = np.arange(0.2, 0.61, 0.05) + effective_mu_range = np.arange(0.1, 0.71, 0.1) print(effective_mu_range.shape[0]) all_successes = np.zeros((effective_mu_range.shape[0], 3)) @@ -62,9 +62,9 @@ def load_lcm_logs(): successes = np.zeros(3) - for j in range(30): + for j in range(5): # ps = plot_styler.PlotStyler() - log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%02d' % (i, j) + log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%1d' % (i, j) print(log_filename) log = lcm.EventLog(log_filename, "r") c3_target, c3_actual, c3_output = \ @@ -76,14 +76,14 @@ def load_lcm_logs(): # ps.plot(c3_actual['t'], c3_actual['x'][:, 9:10], subplot_index=0) # ps.plot(c3_actual['t'], c3_actual['x'][:, 1:2], subplot_index=0) # ps.plot(c3_actual['t'], c3_actual['x'][:, 2:3], subplot_index=0) - first_target = np.array([0.55, -0.1, 0.485]) - second_target = np.array([0.55, -0.1, 0.6]) - third_target = np.array([0.55, 0.15, 0.485]) + first_target = np.array([0.45, 0, 0.485]) + second_target = np.array([0.45, 0, 0.6]) + third_target = np.array([0.7, 0.0, 0.485]) reached_first_target = np.any(np.all(np.isclose(c3_target['x'][:, 7:10], second_target, atol=1e-3), axis=1)) reached_second_target = np.any(np.all(np.isclose(c3_target['x'][:, 7:10], third_target, atol=1e-3), axis=1)) reached_third_target = reached_second_target and np.linalg.norm(c3_target['x'][:length, 7:10] - c3_actual['x'][:length, 7:10], axis=1)[-1] < 0.1 task_success = np.array([reached_first_target, reached_second_target, reached_third_target]) - print('reached_targets: ', task_success) + # print('reached_targets: ', task_success) successes += task_success # print('reached_second_target: ', reached_second_target) # print('reached_third_target: ', reached_third_target) @@ -92,7 +92,7 @@ def load_lcm_logs(): # plt.show() print(successes) all_successes[i] = successes - np.save('target_successes', all_successes ) + np.save('target_successes_23', all_successes ) def plot_logs(): all_successes = np.load('all_successes.npy') @@ -110,12 +110,12 @@ def plot_logs(): for i in range(n): # for j in range(3): # plt.bar(bar_positions[i], all_successes[i, 2] / 30, width=bar_width) - # plt.bar(mu_range[i], all_successes[i, 2] / all_successes[i, 0], width=bar_width, color='grey') + # plt.bar(effective_mu_range[i], all_successes[i, 2] / all_successes[i, 0], width=bar_width, color='grey') plt.bar(effective_mu_range[i], all_successes[i, 0] / 30, width=bar_width, color='grey') plt.ylabel('Target Success Rate') plt.xlabel('Tray/End Effector Friction Coefficient') - plt.savefig('/home/yangwill/Pictures/plot_styler/' + 'target_1_success') + # plt.savefig('/home/yangwill/Pictures/plot_styler/' + 'target_1_success') # plt.legend() # for i in range(3): # plt.bar(bar_positions + i * (n + 1), all_successes[:, i], label=f'Task {i + 1}') @@ -123,8 +123,8 @@ def plot_logs(): plt.show() def main(): - # load_lcm_logs() - plot_logs() + load_lcm_logs() + # plot_logs() diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index 69088c438d..0a8a0cb00d 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,7 +1,8 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/02_02_24/parameter_study/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/02_04_24/parameter_study/ +#results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/ processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index 106aee1f1e..788c761821 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -12,7 +12,7 @@ def main(): cooldown_time = 10.0 start_time = 0 realtime_rate = 1.0 - num_trials = 10 + num_trials = 5 c3_start_up_time = 4.0 sim_run_time = sim_time / realtime_rate controller_startup_time = 0.1 @@ -37,7 +37,7 @@ def main(): # mu_range = np.arange(0.3, 0.8, 0.05) # mass_range = np.arange(0.5, 2.0, 0.05) - effective_mu_range = np.arange(0.2, 0.71, 0.05) + effective_mu_range = np.arange(0.1, 0.71, 0.1) tray_mu = 0.4 initial_radio_msg = dairlib.lcmt_radio_out() diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 42f796cbab..ff8edd3eb0 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -6,10 +6,7 @@ struct FrankaSimParams { std::string franka_model; std::string end_effector_model; - std::string table_model; - std::string table_w_supports_model; std::string tray_model; - std::string box_model; std::string left_support_model; std::string right_support_model; @@ -29,7 +26,6 @@ struct FrankaSimParams { Eigen::VectorXd q_init_franka; std::vector q_init_plate; - Eigen::VectorXd q_init_box; Eigen::VectorXd tool_attachment_frame; Eigen::VectorXd left_support_position; Eigen::VectorXd right_support_position; @@ -50,10 +46,7 @@ struct FrankaSimParams { void Serialize(Archive* a) { a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_model)); - a->Visit(DRAKE_NVP(table_model)); - a->Visit(DRAKE_NVP(table_w_supports_model)); a->Visit(DRAKE_NVP(tray_model)); - a->Visit(DRAKE_NVP(box_model)); a->Visit(DRAKE_NVP(left_support_model)); a->Visit(DRAKE_NVP(right_support_model)); @@ -73,7 +66,6 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); - a->Visit(DRAKE_NVP(q_init_box)); a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 711ede7887..79b6a1cfb9 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,23 +1,20 @@ #franka_model: examples/franka/urdf/franka_no_collision.urdf franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector_parameter_sweep.urdf -table_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf -table_w_supports_model: drake/examples/kuka_iiwa_arm/models/table/extra_heavy_duty_table_surface_only_collision.sdf tray_model: examples/franka/urdf/tray.sdf -box_model: examples/franka/urdf/default_box.urdf left_support_model: examples/franka/urdf/left_support.urdf right_support_model: examples/franka/urdf/left_support.urdf franka_publish_rate: 1000 tray_publish_rate: 10 -visualizer_publish_rate: 10 +visualizer_publish_rate: 60 actuator_delay: 0.000 scene_index: 1 -visualize_drake_sim: true +visualize_drake_sim: false publish_efforts: true camera_pose: [[1.5, 0, 0.6], - [0.5, -0.6, 0.65], + [0.5, -0.9, 0.75], [1.5, 0, 0.6]] camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.5], @@ -47,17 +44,14 @@ world_z_limits: [[0.35, 0.7], dt: 0.0005 realtime_rate: 1 -#q_init_franka: [-0.85, 1.45, 1.25, -1.5, 1.70, 1.2, -0.6] q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.7, 0.00, 0.515], [1, 0, 0, 0, 0.55, 0.15, 0.515]] -#q_init_plate: [1, 0, 0, 0, 0.7, 0.00, 0.50] -q_init_box: [1, 0, 0, 0, 0.9, -0.2, 0.5] visualize_workspace: false -visualize_pose_trace: false +visualize_pose_trace: true visualize_center_of_mass_plan: false visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index d2766b6bd3..b1984f4656 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -25,7 +25,7 @@ - 0.1 0.1 0.1 0.6 + 0.1 0.1 0.1 0.8 diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index b03ee3412a..b57ba079b5 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -260,7 +260,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( force_arrow_path + "/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); } else { meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); } From fdf1680d675c44214cbb2093058a1482db78fb0b Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 6 Feb 2024 14:54:54 -0500 Subject: [PATCH 651/758] cleaning up code --- examples/franka/franka_lcm_ros_bridge.cc | 14 - examples/franka/franka_osc_controller.cc | 10 +- examples/franka/full_diagram.cc | 10 +- .../franka_c3_controller_params.yaml | 4 +- .../franka/parameters/franka_sim_params.yaml | 5 +- examples/franka/systems/BUILD.bazel | 18 +- .../systems/end_effector_orientation.cc | 29 +- .../franka/systems/end_effector_orientation.h | 16 +- .../franka/systems/end_effector_trajectory.cc | 18 +- .../franka/systems/end_effector_trajectory.h | 22 +- .../franka/systems/franka_sim_controls.cc | 70 -- examples/franka/systems/franka_sim_controls.h | 54 -- examples/franka/urdf/franka.urdf | 642 ------------------ examples/franka/urdf/franka_no_collision.urdf | 325 --------- examples/franka/urdf/right_support.urdf | 34 - .../urdf/right_support_point_contact.urdf | 28 - .../urdf/{left_support.urdf => support.urdf} | 0 ...ontact.urdf => support_point_contact.urdf} | 0 examples/franka/urdf/table.sdf | 293 -------- 19 files changed, 19 insertions(+), 1573 deletions(-) delete mode 100644 examples/franka/systems/franka_sim_controls.cc delete mode 100644 examples/franka/systems/franka_sim_controls.h delete mode 100644 examples/franka/urdf/franka.urdf delete mode 100644 examples/franka/urdf/franka_no_collision.urdf delete mode 100644 examples/franka/urdf/right_support.urdf delete mode 100644 examples/franka/urdf/right_support_point_contact.urdf rename examples/franka/urdf/{left_support.urdf => support.urdf} (100%) rename examples/franka/urdf/{left_support_point_contact.urdf => support_point_contact.urdf} (100%) delete mode 100644 examples/franka/urdf/table.sdf diff --git a/examples/franka/franka_lcm_ros_bridge.cc b/examples/franka/franka_lcm_ros_bridge.cc index 685cf6f1a9..d0b82b7b88 100644 --- a/examples/franka/franka_lcm_ros_bridge.cc +++ b/examples/franka/franka_lcm_ros_bridge.cc @@ -90,13 +90,6 @@ int DoMain(int argc, char* argv[]) { plant.Finalize(); /* -------------------------------------------------------------------------------------------*/ -// auto robot_input_lcm_subscriber = -// builder.AddSystem(LcmSubscriberSystem::Make( -// lcm_channel_params.franka_input_channel, &drake_lcm)); -// auto robot_input_lcm_echo = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.franka_input_echo, &drake_lcm, -// {drake::systems::TriggerType::kForced})); auto robot_input_receiver = builder.AddSystem(plant); auto lcm_to_ros_robot_input = builder.AddSystem(7); auto robot_input_ros_publisher = builder.AddSystem( @@ -104,10 +97,6 @@ int DoMain(int argc, char* argv[]) { ros_channel_params.franka_input_channel, &node_handle, {drake::systems::TriggerType::kForced})); -// builder.Connect(robot_input_lcm_subscriber->get_output_port(), -// robot_input_receiver->get_input_port()); -// builder.Connect(robot_input_lcm_subscriber->get_output_port(), -// robot_input_lcm_echo->get_input_port()); builder.Connect(robot_input_receiver->get_output_port(), lcm_to_ros_robot_input->get_input_port()); builder.Connect(lcm_to_ros_robot_input->get_output_port(), @@ -116,9 +105,6 @@ int DoMain(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_lcm_ros_bridge")); const auto& diagram = *owned_diagram; - DrawAndSaveDiagramGraph(diagram); -// drake::systems::Simulator simulator(std::move(owned_diagram)); -// auto& diagram_context = simulator.get_mutable_context(); // figure out what the arguments to this mean ros::AsyncSpinner spinner(1); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 762eeadc22..5fec0e8ed1 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -136,8 +136,7 @@ int DoMain(int argc, char* argv[]) { auto osc_command_sender = builder.AddSystem(plant); auto end_effector_trajectory = - builder.AddSystem(plant, - plant_context.get()); + builder.AddSystem(); VectorXd neutral_position = Eigen::Map( controller_params.neutral_position.data(), controller_params.neutral_position.size()); @@ -145,8 +144,7 @@ int DoMain(int argc, char* argv[]) { neutral_position, controller_params.x_scale, controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = - builder.AddSystem(plant, - plant_context.get()); + builder.AddSystem(); end_effector_orientation_trajectory->SetTrackOrientation( controller_params.track_end_effector_orientation); auto end_effector_force_trajectory = @@ -233,12 +231,8 @@ int DoMain(int argc, char* argv[]) { franka_command_sender->get_input_port(0)); } - builder.Connect(state_receiver->get_output_port(0), - end_effector_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_trajectory->get_input_port_radio()); - builder.Connect(state_receiver->get_output_port(0), - end_effector_orientation_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_orientation_trajectory->get_input_port_radio()); builder.Connect(state_receiver->get_output_port(0), diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 8b46c258bb..8d361b7d5e 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -168,11 +168,9 @@ int DoMain(int argc, char* argv[]) { auto osc_command_sender = builder.AddSystem(osc_plant); auto end_effector_trajectory = - builder.AddSystem( - osc_plant, osc_plant_context.get()); + builder.AddSystem(); auto end_effector_orientation_trajectory = - builder.AddSystem( - osc_plant, osc_plant_context.get()); + builder.AddSystem(); end_effector_orientation_trajectory->SetTrackOrientation( controller_params.track_end_effector_orientation); auto end_effector_force_trajectory = @@ -510,12 +508,8 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(osc_plant); //// OSC connections - builder.Connect(osc_state_receiver->get_output_port(0), - end_effector_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_trajectory->get_input_port_radio()); - builder.Connect(osc_state_receiver->get_output_port(0), - end_effector_orientation_trajectory->get_input_port_state()); builder.Connect(radio_sub->get_output_port(0), end_effector_orientation_trajectory->get_input_port_radio()); builder.Connect(osc_state_receiver->get_output_port(0), diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 8b725cc94f..6b362beed5 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -9,8 +9,8 @@ end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate plate_model: examples/franka/urdf/plate_end_effector_translation.urdf tray_model: examples/franka/urdf/tray_lcs.sdf -left_support_model: examples/franka/urdf/left_support_point_contact.urdf -right_support_model: examples/franka/urdf/left_support_point_contact.urdf +left_support_model: examples/franka/urdf/support_point_contact.urdf +right_support_model: examples/franka/urdf/support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] left_support_position: [0.8, 0.15, 0.447] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 79b6a1cfb9..5302861fe0 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,9 +1,8 @@ -#franka_model: examples/franka/urdf/franka_no_collision.urdf franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector_parameter_sweep.urdf tray_model: examples/franka/urdf/tray.sdf -left_support_model: examples/franka/urdf/left_support.urdf -right_support_model: examples/franka/urdf/left_support.urdf +left_support_model: examples/franka/urdf/support.urdf +right_support_model: examples/franka/urdf/support.urdf franka_publish_rate: 1000 tray_publish_rate: 10 visualizer_publish_rate: 60 diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 41451dc6cd..1098f3ebee 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -4,13 +4,13 @@ cc_library( name = "franka_systems", srcs = [], deps = [ + ":c3_state_sender", + ":c3_trajectory_generator", ":end_effector_force_trajectory", ":end_effector_orientation", ":end_effector_trajectory", ":franka_kinematics", ":plate_balancing_target", - ":c3_state_sender", - ":c3_trajectory_generator", ], ) @@ -117,20 +117,6 @@ cc_library( ], ) -cc_library( - name = "franka_sim_controls", - srcs = ["franka_sim_controls.cc"], - hdrs = ["franka_sim_controls.h"], - deps = [ - ":franka_kinematics_vector", - "//common", - "//lcmtypes:lcmt_robot", - "//multibody:utils", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) - cc_library( name = "franka_kinematics_vector", srcs = ["franka_kinematics_vector.cc"], diff --git a/examples/franka/systems/end_effector_orientation.cc b/examples/franka/systems/end_effector_orientation.cc index bd0517ce31..ac961678e6 100644 --- a/examples/franka/systems/end_effector_orientation.cc +++ b/examples/franka/systems/end_effector_orientation.cc @@ -1,44 +1,19 @@ #include "end_effector_orientation.h" -#include - #include "dairlib/lcmt_radio_out.hpp" -#include "multibody/multibody_utils.h" -using Eigen::Map; using Eigen::MatrixXd; -using Eigen::Vector2d; -using Eigen::Vector3d; -using Eigen::Vector4d; using Eigen::VectorXd; using std::string; -using dairlib::systems::OutputVector; -using drake::multibody::BodyFrame; -using drake::multibody::Frame; -using drake::multibody::JacobianWrtVariable; -using drake::multibody::MultibodyPlant; -using drake::systems::BasicVector; using drake::systems::Context; -using drake::systems::DiscreteUpdateEvent; -using drake::systems::DiscreteValues; -using drake::systems::EventStatus; -using drake::trajectories::PiecewisePolynomial; using drake::trajectories::PiecewiseQuaternionSlerp; using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorOrientationGenerator::EndEffectorOrientationGenerator( - const MultibodyPlant& plant, Context* context) - : plant_(plant), context_(context), world_(plant.world_frame()) { - // Input/Output Setup - state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); - PiecewisePolynomial pp = PiecewisePolynomial(); +EndEffectorOrientationGenerator::EndEffectorOrientationGenerator() { + auto pp = drake::trajectories::PiecewiseQuaternionSlerp(); trajectory_port_ = this->DeclareAbstractInputPort( diff --git a/examples/franka/systems/end_effector_orientation.h b/examples/franka/systems/end_effector_orientation.h index 9629cbd56b..db134e65d1 100644 --- a/examples/franka/systems/end_effector_orientation.h +++ b/examples/franka/systems/end_effector_orientation.h @@ -1,23 +1,14 @@ #pragma once -#include - -#include "systems/framework/output_vector.h" - #include "drake/common/trajectories/piecewise_quaternion.h" -#include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" namespace dairlib { class EndEffectorOrientationGenerator : public drake::systems::LeafSystem { public: - EndEffectorOrientationGenerator(const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context); + EndEffectorOrientationGenerator(); - const drake::systems::InputPort& get_input_port_state() const { - return this->get_input_port(state_port_); - } const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_port_); } @@ -39,13 +30,8 @@ class EndEffectorOrientationGenerator : public drake::systems::LeafSystem& context, drake::trajectories::Trajectory* traj) const; - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; - const drake::multibody::Frame& world_; - bool track_orientation_; - drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index c443b37b3d..5b61c915e1 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -1,20 +1,13 @@ #include "end_effector_trajectory.h" -#include + #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" using Eigen::Map; using Eigen::MatrixXd; -using Eigen::Vector2d; -using Eigen::Vector3d; -using Eigen::Vector4d; using Eigen::VectorXd; using std::string; -using dairlib::systems::OutputVector; -using drake::multibody::BodyFrame; -using drake::multibody::Frame; -using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; using drake::systems::Context; using drake::systems::DiscreteUpdateEvent; @@ -25,15 +18,8 @@ using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( - const MultibodyPlant& plant, Context* context) - : plant_(plant), context_(context), world_(plant.world_frame()) { +EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator() { // Input/Output Setup - state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); PiecewisePolynomial pp = PiecewisePolynomial(); trajectory_port_ = diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index 5b3d0960e9..f0489d1455 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -1,9 +1,5 @@ #pragma once -#include - -#include "systems/framework/output_vector.h" - #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/systems/framework/leaf_system.h" @@ -12,13 +8,8 @@ namespace dairlib { class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem { public: - EndEffectorTrajectoryGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context); + EndEffectorTrajectoryGenerator(); - const drake::systems::InputPort& get_input_port_state() const { - return this->get_input_port(state_port_); - } const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_port_); } @@ -26,8 +17,9 @@ class EndEffectorTrajectoryGenerator return this->get_input_port(radio_port_); } - void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, double x_scale, - double y_scale, double z_scale); + void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, + double x_scale, double y_scale, + double z_scale); private: drake::systems::EventStatus DiscreteVariableUpdate( @@ -39,11 +31,6 @@ class EndEffectorTrajectoryGenerator void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; - const drake::multibody::Frame& world_; - - drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; @@ -51,7 +38,6 @@ class EndEffectorTrajectoryGenerator double x_scale_; double y_scale_; double z_scale_; - std::vector half_plane_bounds_; }; } // namespace dairlib diff --git a/examples/franka/systems/franka_sim_controls.cc b/examples/franka/systems/franka_sim_controls.cc deleted file mode 100644 index 6ef3cb2315..0000000000 --- a/examples/franka/systems/franka_sim_controls.cc +++ /dev/null @@ -1,70 +0,0 @@ -#include - -#include "common/find_resource.h" -#include "examples/franka/systems/franka_sim_controls.h" -#include "multibody/multibody_utils.h" -#include - -namespace dairlib { - -using drake::multibody::ModelInstanceIndex; -using drake::multibody::MultibodyPlant; -using drake::systems::BasicVector; -using drake::systems::Context; -using drake::systems::DiscreteValues; - -using Eigen::VectorXd; -using systems::OutputVector; -using systems::TimestampedVector; - -namespace systems { - -FrankaSimControls::FrankaSimControls(const MultibodyPlant& sim_plant, - Context* sim_context, - ModelInstanceIndex franka_index, - ModelInstanceIndex plate_index, - ModelInstanceIndex box_index, - VectorXd& q_franka_default, - VectorXd& q_plate_default, - VectorXd& q_box_default) - : sim_plant_(sim_plant), - sim_context_(sim_context), - franka_index_(franka_index), - plate_index_(plate_index), - box_index_(box_index), - q_franka_default_(q_franka_default), - q_plate_default_(q_plate_default), - q_box_default_(q_box_default){ - this->set_name("franka_sim_control"); - radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) - .get_index(); - DeclareForcedDiscreteUpdateEvent(&FrankaSimControls::UpdateSimState); -} - -drake::systems::EventStatus FrankaSimControls::UpdateSimState( - const Context& context, - DiscreteValues* discrete_state) const { - const auto& radio_out = - this->EvalInputValue(context, radio_port_); - - if (radio_out->channel[15] > 0) { - this->ResetSim(context); - } -} - -void FrankaSimControls::ResetSim( - const drake::systems::Context& context) const { - sim_plant_.SetPositions(sim_context_, franka_index_, q_franka_default_); - sim_plant_.SetPositions(sim_context_, plate_index_, q_plate_default_); - sim_plant_.SetPositions(sim_context_, box_index_, q_box_default_); -} - -//void FrankaSimControls::DropBox( -// const drake::systems::Context& context) const { -// plant.SetPositions(franka_context_, q); -//} - -} // namespace systems -} // namespace dairlib diff --git a/examples/franka/systems/franka_sim_controls.h b/examples/franka/systems/franka_sim_controls.h deleted file mode 100644 index 36b70e7599..0000000000 --- a/examples/franka/systems/franka_sim_controls.h +++ /dev/null @@ -1,54 +0,0 @@ -#pragma once - -#include -#include - -#include - -#include "examples/franka/systems/franka_kinematics_vector.h" -#include "systems/framework/output_vector.h" -#include "systems/framework/timestamped_vector.h" - -#include "drake/systems/framework/leaf_system.h" - -namespace dairlib { -namespace systems { - -/// Outputs a lcmt_timestamped_saved_traj -class FrankaSimControls : public drake::systems::LeafSystem { - public: - explicit FrankaSimControls( - const drake::multibody::MultibodyPlant& sim_plant, - drake::systems::Context* sim_context, - drake::multibody::ModelInstanceIndex franka_index, - drake::multibody::ModelInstanceIndex plate_index, - drake::multibody::ModelInstanceIndex box_index, - Eigen::VectorXd& q_franka_default, Eigen::VectorXd& q_plate_default, - Eigen::VectorXd& q_box_default); - - const drake::systems::InputPort& get_input_port_radio() const { - return this->get_input_port(radio_port_); - } - - private: - void ResetSim(const drake::systems::Context& context) const; - - drake::systems::EventStatus UpdateSimState( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - - drake::systems::InputPortIndex radio_port_; - - const drake::multibody::MultibodyPlant& sim_plant_; - drake::systems::Context* sim_context_; - drake::multibody::ModelInstanceIndex franka_index_; - drake::multibody::ModelInstanceIndex plate_index_; - drake::multibody::ModelInstanceIndex box_index_; - - Eigen::VectorXd q_franka_default_; - Eigen::VectorXd q_plate_default_; - Eigen::VectorXd q_box_default_; -}; - -} // namespace systems -} // namespace dairlib diff --git a/examples/franka/urdf/franka.urdf b/examples/franka/urdf/franka.urdf deleted file mode 100644 index 8fd83719a5..0000000000 --- a/examples/franka/urdf/franka.urdf +++ /dev/null @@ -1,642 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/examples/franka/urdf/franka_no_collision.urdf b/examples/franka/urdf/franka_no_collision.urdf deleted file mode 100644 index 0a824c84a6..0000000000 --- a/examples/franka/urdf/franka_no_collision.urdf +++ /dev/null @@ -1,325 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - , - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - transmission_interface/SimpleTransmission - - PositionJointInterface - - - PositionJointInterface - 1 - - - - - - - - - - - - - - - - - - - diff --git a/examples/franka/urdf/right_support.urdf b/examples/franka/urdf/right_support.urdf deleted file mode 100644 index 92c363edbb..0000000000 --- a/examples/franka/urdf/right_support.urdf +++ /dev/null @@ -1,34 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/examples/franka/urdf/right_support_point_contact.urdf b/examples/franka/urdf/right_support_point_contact.urdf deleted file mode 100644 index 773d7fb57a..0000000000 --- a/examples/franka/urdf/right_support_point_contact.urdf +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/examples/franka/urdf/left_support.urdf b/examples/franka/urdf/support.urdf similarity index 100% rename from examples/franka/urdf/left_support.urdf rename to examples/franka/urdf/support.urdf diff --git a/examples/franka/urdf/left_support_point_contact.urdf b/examples/franka/urdf/support_point_contact.urdf similarity index 100% rename from examples/franka/urdf/left_support_point_contact.urdf rename to examples/franka/urdf/support_point_contact.urdf diff --git a/examples/franka/urdf/table.sdf b/examples/franka/urdf/table.sdf deleted file mode 100644 index 1b8236706b..0000000000 --- a/examples/franka/urdf/table.sdf +++ /dev/null @@ -1,293 +0,0 @@ - - - - - - - 53.5 - - - 5.177409 - 0 - 0 - 4.843753753 - 0 - 4.843753753 - - - 0 - - -0.33 -0.35 0.381 0 0 0 - - - 0.05 0.05 0.762 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0.33 0.35 0.381 0 0 0 - - - 0.05 0.05 0.762 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0.33 0 0.13335 0 0 0 - - - 0.05 0.662 0.05 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - -0.33 0 0.13335 0 0 0 - - - 0.05 0.662 0.05 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - -0.33 0.35 0.381 0 0 0 - - - 0.05 0.05 0.762 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0.33 -0.35 0.381 0 0 0 - - - 0.05 0.05 0.762 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0 0.35 0.13335 0 0 0 - - - 0.6112 0.05 0.05 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0 -0.35 0.13335 0 0 0 - - - 0.6112 0.05 0.05 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0 0 0.736 0 0 0 - - - 0.7112 0.762 0.057 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0.04 0.12 0.96 0 0 0 - - - 0.05 0.05 0.5 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - 0.04 -0.12 0.96 0 0 0 - - - 0.05 0.05 0.5 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - -0.20 0.12 0.96 0 0 0 - - - 0.05 0.05 0.5 - - - - 0.3 0.3 0.3 1 - 0.7 0.7 0.7 1 - 0.01 0.01 0.01 1 - 0 0 0 1 - - - - - - 0.01 - - - 0.04 0.12 1.2 0 0 0 - - - - - 0.01 - - - 0.04 -0.12 1.2 0 0 0 - - - - - 0.01 - - - -0.20 0.12 1.2 0 0 0 - - - 0 - 0 0 0.736 0 0 0 - - - 0.7112 0.762 0.057 - - - - - - 0.6 - 0.6 - 0 0 0 - 0 - 0 - - - 1 - 0 - 0 - 1 - - 0 - - - - - 0 - 1e+06 - - - 0 - 1 - 1 - - 0 - 0.2 - 1e+13 - 1 - 0.01 - 0 - - - 1 - -0.01 - - 0 - 0.2 - 1e+13 - 1 - - - - - - - - From 5be8fb711c8c883a9cdfd60e60c8e7342a074a65 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 8 Feb 2024 09:47:50 -0500 Subject: [PATCH 652/758] visualization changes to reduce flickering --- examples/franka/franka_visualizer.cc | 2 +- examples/franka/urdf/tray.sdf | 2 +- examples/franka/urdf/tray_transparent.sdf | 49 +++++++++++++++++++ .../lcm_visualization_systems.cc | 10 ++-- 4 files changed, 56 insertions(+), 7 deletions(-) create mode 100644 examples/franka/urdf/tray_transparent.sdf diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index fc321c487e..c143738611 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -208,7 +208,7 @@ int do_main(int argc, char* argv[]) { if (sim_params.visualize_pose_trace){ auto object_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.tray_model), + meshcat, FindResourceOrThrow("examples/franka/urdf/tray_transparent.sdf"), "object_position_target", "object_orientation_target"); auto end_effector_pose_drawer = builder.AddSystem( meshcat, FindResourceOrThrow(sim_params.end_effector_model), diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index b1984f4656..d21382eea2 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -25,7 +25,7 @@ - 0.1 0.1 0.1 0.8 + 0.1 0.1 0.1 0.7 diff --git a/examples/franka/urdf/tray_transparent.sdf b/examples/franka/urdf/tray_transparent.sdf new file mode 100644 index 0000000000..c0947bf6fb --- /dev/null +++ b/examples/franka/urdf/tray_transparent.sdf @@ -0,0 +1,49 @@ + + + + + + 0 0 0 0 0 0 + 1 + + + 0.013105 + 0 + 0 + 0.013105 + 0 + 0.026129 + + + + 0 0 0.0 0 0 0 + + + 0.2276 + 0.022 + + + + 0.1 0.1 0.1 0.9 + + + + 0 0 0.0 0 0 0 + + + 0.2286 + 0.022 + + + + + 3.0e7 + 0.18 + 10 + 0.4 + + + + + \ No newline at end of file diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index b57ba079b5..af79c70683 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -89,7 +89,7 @@ LcmPoseDrawer::LcmPoseDrawer( this->set_name("LcmPoseDrawer: " + translation_trajectory_name); multipose_visualizer_ = std::make_unique( - model_file, N_, 1.0 * VectorXd::LinSpaced(N_, 0, 0.4), "", meshcat); + model_file, N_ - 1, 1.0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4), "", meshcat); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", @@ -111,7 +111,7 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( this->EvalInputValue( context, trajectory_input_port_); auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); - MatrixXd object_poses = MatrixXd::Zero(7, N_); + MatrixXd object_poses = MatrixXd::Zero(7, N_ - 1); const auto& lcm_translation_traj = lcm_traj.GetTrajectory(translation_trajectory_name_); @@ -146,8 +146,8 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], lcm_translation_traj.time_vector.tail(1)[0]); for (int i = 0; i < object_poses.cols(); ++i) { - object_poses.col(i) << orientation_trajectory.value(translation_breaks(i)), - translation_trajectory.value(translation_breaks(i)); + object_poses.col(i) << orientation_trajectory.value(translation_breaks(i + 1)), + translation_trajectory.value(translation_breaks(i + 1)); } multipose_visualizer_->DrawPoses(object_poses); @@ -260,7 +260,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( force_arrow_path + "/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); } else { meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); } From cbd009a57cc81339cd9d33af6d1d559105737c17 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 16 Feb 2024 17:15:59 -0500 Subject: [PATCH 653/758] minor renaming --- examples/franka/franka_c3_controller.cc | 16 +++++------ examples/franka/franka_sim.cc | 36 +++++++++---------------- 2 files changed, 21 insertions(+), 31 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 4dc0f40ac1..8a3f3c19b1 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -148,7 +148,7 @@ int DoMain(int argc, char* argv[]) { auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); /// - std::vector plate_contact_points = + std::vector end_effector_contact_points = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("plate")); if (controller_params.scene_index > 0) { @@ -158,19 +158,19 @@ int DoMain(int argc, char* argv[]) { std::vector right_support_contact_points = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("support", right_support_index)); - plate_contact_points.insert(plate_contact_points.end(), - left_support_contact_points.begin(), - left_support_contact_points.end()); - plate_contact_points.insert(plate_contact_points.end(), - right_support_contact_points.begin(), - right_support_contact_points.end()); + end_effector_contact_points.insert(end_effector_contact_points.end(), + left_support_contact_points.begin(), + left_support_contact_points.end()); + end_effector_contact_points.insert(end_effector_contact_points.end(), + right_support_contact_points.begin(), + right_support_contact_points.end()); } std::vector tray_geoms = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("tray")); std::unordered_map> contact_geoms; - contact_geoms["PLATE"] = plate_contact_points; + contact_geoms["PLATE"] = end_effector_contact_points; contact_geoms["TRAY"] = tray_geoms; std::vector> contact_pairs; diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index cb9c7f0e33..cfe4a686d2 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -87,6 +87,17 @@ int DoMain(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); + // we WANT to model collisions between link5 and the supports + const drake::geometry::GeometrySet& franka_geom_set = + plant.CollectRegisteredGeometries( + {&plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), +// &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link7"), + &plant.GetBodyByName("plate"), + &plant.GetBodyByName("panda_link8")}); if (sim_params.scene_index > 0) { drake::multibody::ModelInstanceIndex left_support_index = parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; @@ -107,35 +118,14 @@ int DoMain(int argc, char* argv[]) { &plant.GetBodyByName("support", left_support_index), &plant.GetBodyByName("support", right_support_index), }); - // we WANT to model collisions between link5 and the supports - const drake::geometry::GeometrySet& paddle_geom_set = - plant.CollectRegisteredGeometries( - {&plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), -// &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link7"), - &plant.GetBodyByName("plate"), - &plant.GetBodyByName("panda_link8")}); - plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"paddle", support_geom_set}, {"tray", paddle_geom_set}); + {"supports", support_geom_set}, {"franka", franka_geom_set}); } - const drake::geometry::GeometrySet& paddle_geom_set = - plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link8"), - }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"paddle", paddle_geom_set}, {"tray", tray_collision_set}); + {"franka", franka_geom_set}, {"tray", tray_collision_set}); plant.Finalize(); /* -------------------------------------------------------------------------------------------*/ From 3f3851765a867375d30661e412f2b769db38aff3 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 20 Feb 2024 11:41:58 -0500 Subject: [PATCH 654/758] working on full diagram --- examples/franka/BUILD.bazel | 15 +- examples/franka/diagrams/BUILD.bazel | 47 ++ .../diagrams/franka_c3_controller_diagram.cc | 325 ++++++++++++ .../diagrams/franka_c3_controller_diagram.h | 85 +++ .../diagrams/franka_osc_controller_diagram.cc | 278 ++++++++++ .../diagrams/franka_osc_controller_diagram.h | 81 +++ examples/franka/franka_c3_controller.cc | 13 +- examples/franka/franka_osc_controller.cc | 28 +- examples/franka/franka_sim.cc | 11 +- examples/franka/full_diagram.cc | 485 ++---------------- .../franka/parameters/franka_sim_params.yaml | 6 +- .../systems/end_effector_force_trajectory.cc | 34 +- .../systems/end_effector_force_trajectory.h | 13 +- .../systems/end_effector_orientation.cc | 27 +- .../franka/systems/end_effector_orientation.h | 10 +- .../franka/systems/end_effector_trajectory.cc | 29 +- .../franka/systems/end_effector_trajectory.h | 2 - .../franka/systems/plate_balancing_target.cc | 49 +- systems/controllers/c3/lcs_factory_system.cc | 16 +- systems/controllers/c3/lcs_factory_system.h | 11 +- systems/controllers/c3_controller.cc | 16 +- systems/controllers/c3_controller.h | 7 - systems/primitives/radio_parser.cc | 23 +- systems/primitives/radio_parser.h | 21 + 24 files changed, 1016 insertions(+), 616 deletions(-) create mode 100644 examples/franka/diagrams/BUILD.bazel create mode 100644 examples/franka/diagrams/franka_c3_controller_diagram.cc create mode 100644 examples/franka/diagrams/franka_c3_controller_diagram.h create mode 100644 examples/franka/diagrams/franka_osc_controller_diagram.cc create mode 100644 examples/franka/diagrams/franka_osc_controller_diagram.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 444a1ceb7a..0303809528 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -34,20 +34,11 @@ cc_binary( ":franka_lcm_channels", ":franka_osc_controller_params", ":franka_sim_params", - "//common", - "//examples/franka/systems:franka_systems", - "//lcm:lcm_trajectory_saver", + "//examples/franka/diagrams:franka_c3_controller_diagram", + "//examples/franka/diagrams:franka_osc_controller_diagram", "//systems:robot_lcm_systems", "//systems:system_utils", - "//systems/controllers", - "//systems/controllers:c3_controller", - "//systems/controllers:lcs_factory_system", - "//systems/controllers/osc:operational_space_control", - "//systems/framework:lcm_driven_loop", - "//systems/trajectory_optimization:c3_output_systems", - "//systems/trajectory_optimization:lcm_trajectory_systems", "@drake//:drake_shared_library", - "@gflags", ], ) @@ -89,6 +80,7 @@ cc_binary( "//systems/controllers", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", "//systems/trajectory_optimization:lcm_trajectory_systems", "@drake//:drake_shared_library", "@gflags", @@ -115,6 +107,7 @@ cc_binary( "//systems/controllers:lcs_factory_system", "//systems/controllers/osc:operational_space_control", "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", "//systems/trajectory_optimization:c3_output_systems", "@drake//:drake_shared_library", "@gflags", diff --git a/examples/franka/diagrams/BUILD.bazel b/examples/franka/diagrams/BUILD.bazel new file mode 100644 index 0000000000..6590ea82c3 --- /dev/null +++ b/examples/franka/diagrams/BUILD.bazel @@ -0,0 +1,47 @@ +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "franka_c3_controller_diagram", + srcs = ["franka_c3_controller_diagram.cc"], + hdrs = ["franka_c3_controller_diagram.h"], + deps = [ + "//common", + "//examples/franka:franka_c3_controller_params", + "//examples/franka:franka_lcm_channels", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers:c3_controller", + "//systems/controllers:lcs_factory_system", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", + "//systems/trajectory_optimization:c3_output_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_library( + name = "franka_osc_controller_diagram", + srcs = ["franka_osc_controller_diagram.cc"], + hdrs = ["franka_osc_controller_diagram.h"], + deps = [ + "//common", + "//examples/franka:franka_lcm_channels", + "//examples/franka:franka_osc_controller_params", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", + "//systems/trajectory_optimization:lcm_trajectory_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc new file mode 100644 index 0000000000..f1a9f74963 --- /dev/null +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -0,0 +1,325 @@ +// +// Created by yangwill on 2/19/24. +// + +#include "examples/franka/diagrams/franka_c3_controller_diagram.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/systems/c3_state_sender.h" +#include "examples/franka/systems/c3_trajectory_generator.h" +#include "examples/franka/systems/franka_kinematics.h" +#include "examples/franka/systems/plate_balancing_target.h" +#include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/c3/lcs_factory_system.h" +#include "systems/controllers/c3_controller.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/primitives/radio_parser.h" + +namespace dairlib { + +namespace examples { +namespace controllers { + +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; + +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using std::string; + +FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( + const string& controller_settings, + const string& lcm_channels, + drake::lcm::DrakeLcm* lcm){ + this->set_name("FrankaC3Controller"); + DiagramBuilder builder; + + FrankaC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_settings); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels); + C3Options c3_options = drake::yaml::LoadYamlFile( + controller_params.c3_options_file[controller_params.scene_index]); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_params.osqp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + plant_franka_ = new drake::multibody::MultibodyPlant (0.0); + Parser parser_franka(plant_franka_, nullptr); + parser_franka.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = + parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + + RigidTransform X_WI = RigidTransform::Identity(); + plant_franka_->WeldFrames(plant_franka_->world_frame(), + plant_franka_->GetFrameByName("panda_link0"), X_WI); + + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + plant_franka_->WeldFrames( + plant_franka_->GetFrameByName("panda_link7"), + plant_franka_->GetFrameByName("plate", end_effector_index), T_EE_W); + + plant_franka_->Finalize(); + plant_franka_context_ = plant_franka_->CreateDefaultContext(); + + /// + plant_tray_ = new drake::multibody::MultibodyPlant (0.0); + Parser parser_tray(plant_tray_, nullptr); + parser_tray.AddModels(controller_params.tray_model); + plant_tray_->Finalize(); + plant_tray_context_ = plant_tray_->CreateDefaultContext(); + + /// +// plant_for_lcs_ = std::make_unique>(0.0); +// AddMultibodyPlantSceneGraph(&plant_builder, std::make_unique>(0.0), scene_graph_lcs_); +// plant_for_lcs_, scene_graph_lcs_ = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + drake::planning::RobotDiagramBuilder lcs_diagram_builder; +// lcs_diagram_builder.plant() + lcs_diagram_builder.parser().SetAutoRenaming(true); + lcs_diagram_builder.parser().AddModels(controller_params.plate_model); + + drake::multibody::ModelInstanceIndex left_support_index; + drake::multibody::ModelInstanceIndex right_support_index; + if (controller_params.scene_index > 0) { + left_support_index = lcs_diagram_builder.parser().AddModels( + FindResourceOrThrow(controller_params.left_support_model))[0]; + right_support_index = lcs_diagram_builder.parser().AddModels( + FindResourceOrThrow(controller_params.right_support_model))[0]; + RigidTransform T_S1_W = + RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), + controller_params.left_support_position); + RigidTransform T_S2_W = + RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), + controller_params.right_support_position); + lcs_diagram_builder.plant().WeldFrames( + lcs_diagram_builder.plant().world_frame(), + lcs_diagram_builder.plant().GetFrameByName("support", left_support_index), T_S1_W); + lcs_diagram_builder.plant().WeldFrames( + lcs_diagram_builder.plant().world_frame(), + lcs_diagram_builder.plant().GetFrameByName("support", right_support_index), T_S2_W); + } + lcs_diagram_builder.parser().AddModels(controller_params.tray_model); + + lcs_diagram_builder.plant().WeldFrames(lcs_diagram_builder.plant().world_frame(), + lcs_diagram_builder.plant().GetFrameByName("base_link"), X_WI); + lcs_diagram_builder.plant().Finalize(); + robot_diagram_for_lcs_ = lcs_diagram_builder.Build(); + plant_for_lcs_autodiff_ = + drake::systems::System::ToAutoDiffXd(robot_diagram_for_lcs_->plant()); + +// auto plant_diagram = plant_builder.Build(); +// auto plant_diagram = plant_lcs_builder_->Build(); +// plant_for_lcs_diagram_context_ = +// plant_diagram->CreateDefaultContext(); +// plant_for_lcs_context_ = std::move(plant_diagram->GetMutableSubsystemContext( +// plant_for_lcs_, plant_for_lcs_diagram_context_.get())); + robot_diagram_root_context_ = robot_diagram_for_lcs_->CreateDefaultContext(); + plant_for_lcs_autodiff_context_ = plant_for_lcs_autodiff_->CreateDefaultContext(); + + /// + std::vector end_effector_contact_points = + robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( + robot_diagram_for_lcs_->plant().GetBodyByName("plate")); + if (controller_params.scene_index > 0) { + std::vector left_support_contact_points = + robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( + robot_diagram_for_lcs_->plant().GetBodyByName("support", left_support_index)); + std::vector right_support_contact_points = + robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( + robot_diagram_for_lcs_->plant().GetBodyByName("support", right_support_index)); + end_effector_contact_points.insert(end_effector_contact_points.end(), + left_support_contact_points.begin(), + left_support_contact_points.end()); + end_effector_contact_points.insert(end_effector_contact_points.end(), + right_support_contact_points.begin(), + right_support_contact_points.end()); + } + std::vector tray_geoms = + robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( + robot_diagram_for_lcs_->plant().GetBodyByName("tray")); + std::unordered_map> + contact_geoms; + contact_geoms["PLATE"] = end_effector_contact_points; + contact_geoms["TRAY"] = tray_geoms; + + std::vector> contact_pairs; + for (auto geom_id : contact_geoms["PLATE"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); + } + + auto franka_state_receiver = + builder.AddSystem(*plant_franka_); + auto tray_state_receiver = + builder.AddSystem(*plant_tray_); + auto reduced_order_model_receiver = + builder.AddSystem( + *plant_franka_, plant_franka_context_.get(), *plant_tray_, plant_tray_context_.get(), + controller_params.end_effector_name, "tray", + controller_params.include_end_effector_orientation); + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto plate_balancing_target = + builder.AddSystem(*plant_tray_, controller_params.end_effector_thickness, controller_params.near_target_threshold); + plate_balancing_target->SetRemoteControlParameters( + controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto tray_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(plate_balancing_target->get_output_port_tray_target(), + target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(tray_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(3)); + auto lcs_factory = builder.AddSystem( + robot_diagram_for_lcs_->plant(), robot_diagram_for_lcs_->mutable_plant_context(robot_diagram_root_context_.get()), *plant_for_lcs_autodiff_, + plant_for_lcs_autodiff_context_.get(), contact_pairs, c3_options); + auto controller = builder.AddSystem( + robot_diagram_for_lcs_->plant(), c3_options); + auto c3_trajectory_generator = + builder.AddSystem(robot_diagram_for_lcs_->plant(), + c3_options); + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", + "tray_qx", "tray_qy", "tray_qz", "tray_x", + "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", + "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", + "tray_vz", "tray_vz", "tray_vz", + }; + auto c3_state_sender = + builder.AddSystem(3 + 7 + 3 + 6, state_names); + c3_trajectory_generator->SetPublishEndEffectorOrientation( + controller_params.include_end_effector_orientation); + auto c3_output_sender = builder.AddSystem(); + auto radio_to_vector = builder.AddSystem(); + controller->SetOsqpSolverOptions(solver_options); + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(target_state_mux->get_output_port(), + controller->get_input_port_target()); + builder.Connect(lcs_factory->get_output_port_lcs(), + controller->get_input_port_lcs()); + builder.Connect(tray_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(tray_state_receiver->get_output_port(), + plate_balancing_target->get_input_port_tray_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + controller->get_input_port_lcs_state()); +// builder.Connect(radio_sub->get_output_port(), +// controller->get_input_port_radio()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + lcs_factory->get_input_port_lcs_state()); + builder.Connect(radio_to_vector->get_output_port(), + plate_balancing_target->get_input_port_radio()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_trajectory_generator->get_input_port_c3_solution()); + builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), + c3_output_sender->get_input_port_lcs_contact_info()); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + actor_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), + object_trajectory_sender->get_input_port()); + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_output_sender->get_input_port_c3_solution()); + builder.Connect(controller->get_output_port_c3_intermediates(), + c3_output_sender->get_input_port_c3_intermediates()); + builder.Connect(c3_output_sender->get_output_port_c3_debug(), + c3_output_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_force(), + c3_forces_publisher->get_input_port()); + + // Publisher connections + builder.ExportInput(franka_state_receiver->get_input_port(), "franka_state: lcmt_robot_output"); + builder.ExportInput(tray_state_receiver->get_input_port(), "tray_state: lcmt_object_state"); + builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); + builder.ExportOutput(c3_trajectory_generator->get_output_port_actor_trajectory(), "actor_trajectory"); +// builder.ExportOutput(c3_trajectory_generator->get_output_port_object_trajectory(), "object_trajectory"); +// builder.ExportOutput(c3_output_sender->get_output_port_c3_force(), "c3_forces"); + + builder.BuildInto(this); + this->set_name("FrankaC3Controller"); + DrawAndSaveDiagramGraph(*this); +} + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.h b/examples/franka/diagrams/franka_c3_controller_diagram.h new file mode 100644 index 0000000000..215f612a83 --- /dev/null +++ b/examples/franka/diagrams/franka_c3_controller_diagram.h @@ -0,0 +1,85 @@ +#pragma once + +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +namespace dairlib { +namespace examples { +namespace controllers { + +class FrankaC3ControllerDiagram : public drake::systems::Diagram { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(FrankaC3ControllerDiagram) + + /// @param[in] osc_gains_filename filepath containing the osc_running_gains. + /// @param[in] osqp_settings filepath containing the osqp settings. + FrankaC3ControllerDiagram(const std::string& controller_settings, + const std::string& lcm_channels, + drake::lcm::DrakeLcm* lcm); + + /// @return the input port for the plant state. + const drake::systems::InputPort& get_input_port_robot_state() const { + return this->get_input_port(franka_state_port_); + } + + /// @return the input port for the plant state. + const drake::systems::InputPort& get_input_port_object_state() const { + return this->get_input_port(tray_state_port_); + } + + /// @return the input port for the cassie_out struct (containing radio + /// commands). + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + /// @return the output port for the lcmt_robot_input message. + const drake::systems::OutputPort& get_output_port_mpc_plan() const { + return this->get_output_port(mpc_plan_port_); + } + + private: + drake::multibody::MultibodyPlant* plant_franka_; + drake::multibody::MultibodyPlant* plant_tray_; +// std::unique_ptr> plant_for_lcs_; +// std::unique_ptr> scene_graph_lcs_; + + // Storage for the diagram and its plant and scene graph. + // After Build(), the `builder_` is set to nullptr. + std::unique_ptr> robot_diagram_for_lcs_; + std::unique_ptr> robot_diagram_root_context_; +// std::unique_ptr> plant_lcs_builder_; +// drake::multibody::AddMultibodyPlantSceneGraphResult pair_; +// drake::multibody::MultibodyPlant& plant_for_lcs_; +// drake::geometry::SceneGraph& scene_graph_lcs_; + std::unique_ptr> plant_for_lcs_diagram_context_; +// drake::multibody::MultibodyPlant& plant_for_lcs_; +// drake::geometry::SceneGraph& scene_graph_lcs_; + std::unique_ptr> plant_for_lcs_autodiff_; + std::unique_ptr> plant_franka_context_; + std::unique_ptr> plant_tray_context_; +// drake::systems::Context& plant_for_lcs_context_; + std::unique_ptr> plant_for_lcs_autodiff_context_; + + const drake::systems::InputPortIndex franka_state_port_ = + drake::systems::InputPortIndex(0); + const drake::systems::InputPortIndex tray_state_port_ = + drake::systems::InputPortIndex(1); + const drake::systems::InputPortIndex radio_port_ = + drake::systems::InputPortIndex(2); + const drake::systems::OutputPortIndex mpc_plan_port_ = + drake::systems::OutputPortIndex(0); +}; + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc new file mode 100644 index 0000000000..fb1b00f7f8 --- /dev/null +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -0,0 +1,278 @@ +// +// Created by yangwill on 2/19/24. +// + +#include "examples/franka/diagrams/franka_osc_controller_diagram.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_osc_controller_params.h" +#include "examples/franka/systems/end_effector_force_trajectory.h" +#include "examples/franka/systems/end_effector_orientation.h" +#include "examples/franka/systems/end_effector_trajectory.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/gravity_compensator.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/primitives/radio_parser.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" + +namespace dairlib { + +namespace examples { +namespace controllers { + +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; + +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using std::string; + +FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( + const string& controller_settings, const string& lcm_channels, + drake::lcm::DrakeLcm* lcm) { + DiagramBuilder builder; + + // load parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaControllerParams controller_params = + drake::yaml::LoadYamlFile(controller_settings); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels); + OSCGains gains = drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_settings), {}, {}, yaml_options); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow( + "examples/franka/parameters/franka_osc_qp_settings.yaml")) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + plant_ = new drake::multibody::MultibodyPlant (0.0); + Parser parser(plant_, nullptr); + parser.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); + + RigidTransform X_WI = RigidTransform::Identity(); + plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("panda_link0"), + X_WI); + + if (!controller_params.end_effector_name.empty()) { + drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + plant_->WeldFrames(plant_->GetFrameByName("panda_link7"), + plant_->GetFrameByName(controller_params.end_effector_name, + end_effector_index), + T_EE_W); + } else { + std::cout << "OSC plant has been constructed with no end effector." + << std::endl; + } + + plant_->Finalize(); + plant_context_ = plant_->CreateDefaultContext(); + + auto state_receiver = builder.AddSystem(*plant_); +// auto end_effector_trajectory_receiver = +// builder.AddSystem( +// drake::systems::PassThrough(drake::Value{})); + auto end_effector_position_receiver = + builder.AddSystem( + "end_effector_position_target"); + auto end_effector_force_receiver = + builder.AddSystem( + "end_effector_force_target"); + auto end_effector_orientation_receiver = + builder.AddSystem( + "end_effector_orientation_target"); + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_input_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto osc_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto franka_command_sender = + builder.AddSystem(*plant_); + auto osc_command_sender = + builder.AddSystem(*plant_); + auto end_effector_trajectory = + builder.AddSystem(); + auto radio_to_vector = builder.AddSystem(); + VectorXd neutral_position = Eigen::Map( + controller_params.neutral_position.data(), + controller_params.neutral_position.size()); + end_effector_trajectory->SetRemoteControlParameters( + neutral_position, controller_params.x_scale, controller_params.y_scale, + controller_params.z_scale); + auto end_effector_orientation_trajectory = + builder.AddSystem(); + end_effector_orientation_trajectory->SetTrackOrientation( + controller_params.track_end_effector_orientation); + auto end_effector_force_trajectory = + builder.AddSystem(); + auto osc = builder.AddSystem( + *plant_, *plant_, plant_context_.get(), plant_context_.get(), false); + if (controller_params.publish_debug_info) { + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_debug_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); + } + + auto end_effector_position_tracking_data = + std::make_unique( + "end_effector_target", controller_params.K_p_end_effector, + controller_params.K_d_end_effector, controller_params.W_end_effector, + *plant_, *plant_); + end_effector_position_tracking_data->AddPointToTrack( + controller_params.end_effector_name); + const VectorXd& end_effector_acceleration_limits = + controller_params.end_effector_acceleration * Vector3d::Ones(); + end_effector_position_tracking_data->SetCmdAccelerationBounds( + -end_effector_acceleration_limits, end_effector_acceleration_limits); + auto mid_link_position_tracking_data_for_rel = + std::make_unique( + "panda_joint2_target", controller_params.K_p_mid_link, + controller_params.K_d_mid_link, controller_params.W_mid_link, *plant_, + *plant_); + mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", + "panda_joint2dot"); + + auto end_effector_force_tracking_data = + std::make_unique( + "end_effector_force", controller_params.W_ee_lambda, *plant_, *plant_, + controller_params.end_effector_name, Vector3d::Zero()); + + auto end_effector_orientation_tracking_data = + std::make_unique( + "end_effector_orientation_target", + controller_params.K_p_end_effector_rot, + controller_params.K_d_end_effector_rot, + controller_params.W_end_effector_rot, *plant_, *plant_); + end_effector_orientation_tracking_data->AddFrameToTrack( + controller_params.end_effector_name); + Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); + orientation_target(0) = 1; + osc->AddTrackingData(std::move(end_effector_position_tracking_data)); + osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), + 1.6 * VectorXd::Ones(1)); + osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); + osc->AddForceTrackingData(std::move(end_effector_force_tracking_data)); + osc->SetAccelerationCostWeights(gains.W_acceleration); + osc->SetInputCostWeights(gains.W_input_regularization); + osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); + osc->SetAccelerationConstraints( + controller_params.enforce_acceleration_constraints); + + osc->SetContactFriction(controller_params.mu); + osc->SetOsqpSolverOptions(solver_options); + + osc->Build(); + + if (controller_params.cancel_gravity_compensation) { + auto gravity_compensator = + builder.AddSystem(*plant_, + *plant_context_); + builder.Connect(osc->get_output_port_osc_command(), + gravity_compensator->get_input_port()); + builder.Connect(gravity_compensator->get_output_port(), + franka_command_sender->get_input_port()); + } else { + DRAKE_DEMAND(lcm_channels == + "examples/franka/parameters/lcm_channels_simulation.yaml"); + builder.Connect(osc->get_output_port_osc_command(), + franka_command_sender->get_input_port(0)); + } + + builder.Connect(radio_to_vector->get_output_port(), + end_effector_trajectory->get_input_port_radio()); + builder.Connect(radio_to_vector->get_output_port(), + end_effector_orientation_trajectory->get_input_port_radio()); + builder.Connect(radio_to_vector->get_output_port(), + end_effector_force_trajectory->get_input_port_radio()); + builder.Connect(franka_command_sender->get_output_port(), + franka_command_pub->get_input_port()); + builder.Connect(osc_command_sender->get_output_port(), + osc_command_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_command(), + osc_command_sender->get_input_port(0)); + + builder.Connect(state_receiver->get_output_port(0), + osc->get_input_port_robot_output()); +// builder.Connect(end_effector_trajectory_receiver->get_output_port(), +// end_effector_position_receiver->get_input_port_trajectory()); +// builder.Connect(end_effector_trajectory_receiver->get_output_port(), +// end_effector_force_receiver->get_input_port_trajectory()); +// builder.Connect( +// end_effector_trajectory_receiver->get_output_port(), +// end_effector_orientation_receiver->get_input_port_trajectory()); + builder.Connect(end_effector_position_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_trajectory()); + builder.Connect( + end_effector_orientation_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect( + end_effector_orientation_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); + builder.Connect(end_effector_force_receiver->get_output_port(0), + end_effector_force_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_force_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_force")); + + // Publisher connections + builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); + builder.ExportInput(end_effector_position_receiver->get_input_port(), + "end_effector_position: lcmt_timestamped_trajectory"); + builder.ExportInput(end_effector_orientation_receiver->get_input_port(), + "end_effector_orientation: lcmt_timestamped_trajectory"); + builder.ExportInput(end_effector_force_receiver->get_input_port(), + "end_effector_force: lcmt_timestamped_trajectory"); + builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); + builder.ExportOutput(osc->get_output_port_osc_command(), "robot_input"); + // builder.ExportOutput(c3_trajectory_generator->get_output_port_object_trajectory(), + // "object_trajectory"); + // builder.ExportOutput(c3_output_sender->get_output_port_c3_force(), + // "c3_forces"); + + builder.BuildInto(this); + this->set_name("FrankaOSCController"); + DrawAndSaveDiagramGraph(*this); +} + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.h b/examples/franka/diagrams/franka_osc_controller_diagram.h new file mode 100644 index 0000000000..19c8cadaf6 --- /dev/null +++ b/examples/franka/diagrams/franka_osc_controller_diagram.h @@ -0,0 +1,81 @@ +#pragma once + +#include +#include +#include +#include +#include +#include + +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/external_force_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" + +namespace dairlib { +namespace examples { +namespace controllers { + +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; +using systems::controllers::ExternalForceTrackingData; + +class FrankaOSCControllerDiagram : public drake::systems::Diagram { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(FrankaOSCControllerDiagram) + + /// @param[in] osc_gains_filename filepath containing the osc_running_gains. + /// @param[in] osqp_settings filepath containing the osqp settings. + FrankaOSCControllerDiagram(const std::string& controller_settings, + const std::string& lcm_channels, + drake::lcm::DrakeLcm* lcm); + + /// @return the input port for the plant state. + const drake::systems::InputPort& get_input_port_robot_state() const { + return this->get_input_port(franka_state_port_); + } + + const drake::systems::InputPort& get_input_port_end_effector_position() const { + return this->get_input_port(end_effector_position_port_); + } + + const drake::systems::InputPort& get_input_port_end_effector_orientation() const { + return this->get_input_port(end_effector_orientation_port_); + } + + const drake::systems::InputPort& get_input_port_end_effector_force() const { + return this->get_input_port(end_effector_force_port_); + } + + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + /// @return the output port for the lcmt_robot_input message. + const drake::systems::OutputPort& get_output_port_robot_input() const { + return this->get_output_port(robot_input_port_); + } + + private: + drake::multibody::MultibodyPlant* plant_; + std::unique_ptr> plant_context_; + + const drake::systems::InputPortIndex franka_state_port_ = + drake::systems::InputPortIndex(0); + const drake::systems::InputPortIndex end_effector_position_port_ = + drake::systems::InputPortIndex(1); + const drake::systems::InputPortIndex end_effector_orientation_port_ = + drake::systems::InputPortIndex(2); + const drake::systems::InputPortIndex end_effector_force_port_ = + drake::systems::InputPortIndex(3); + const drake::systems::InputPortIndex radio_port_ = + drake::systems::InputPortIndex(4); + const drake::systems::OutputPortIndex robot_input_port_ = + drake::systems::OutputPortIndex(0); +}; + +} // namespace controllers +} // namespace examples +} // namespace dairlib diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 8a3f3c19b1..ae2716da8f 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -25,6 +25,7 @@ #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/primitives/radio_parser.h" namespace dairlib { @@ -221,6 +222,8 @@ int DoMain(int argc, char* argv[]) { auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); + auto radio_to_vector = builder.AddSystem(); + auto plate_balancing_target = builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); @@ -246,10 +249,10 @@ int DoMain(int argc, char* argv[]) { builder.Connect(tray_zero_velocity_source->get_output_port(), target_state_mux->get_input_port(3)); auto lcs_factory = builder.AddSystem( - plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, + plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, plate_context_ad.get(), contact_pairs, c3_options); auto controller = builder.AddSystem( - plant_for_lcs, &plant_for_lcs_context, c3_options); + plant_for_lcs, c3_options); auto c3_trajectory_generator = builder.AddSystem(plant_for_lcs, c3_options); @@ -266,6 +269,8 @@ int DoMain(int argc, char* argv[]) { controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); controller->SetOsqpSolverOptions(solver_options); + + builder.Connect(*radio_sub, *radio_to_vector); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); builder.Connect(target_state_mux->get_output_port(), @@ -280,11 +285,9 @@ int DoMain(int argc, char* argv[]) { plate_balancing_target->get_input_port_tray_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_lcs_state()); - builder.Connect(radio_sub->get_output_port(), - controller->get_input_port_radio()); builder.Connect(reduced_order_model_receiver->get_output_port(), lcs_factory->get_input_port_lcs_state()); - builder.Connect(radio_sub->get_output_port(), + builder.Connect(radio_to_vector->get_output_port(), plate_balancing_target->get_input_port_radio()); builder.Connect(controller->get_output_port_c3_solution(), c3_trajectory_generator->get_input_port_c3_solution()); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 5fec0e8ed1..8f4c550442 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -19,6 +19,7 @@ #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/lcm_trajectory_systems.h" @@ -94,8 +95,9 @@ int DoMain(int argc, char* argv[]) { if (!controller_params.end_effector_name.empty()) { drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( FindResourceOrThrow(controller_params.end_effector_model))[0]; - RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), controller_params.tool_attachment_frame); + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName(controller_params.end_effector_name, end_effector_index), @@ -148,14 +150,14 @@ int DoMain(int argc, char* argv[]) { end_effector_orientation_trajectory->SetTrackOrientation( controller_params.track_end_effector_orientation); auto end_effector_force_trajectory = - builder.AddSystem( - plant, plant_context.get()); + builder.AddSystem(); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); + auto radio_to_vector = builder.AddSystem(); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), false); - if (controller_params.publish_debug_info){ + if (controller_params.publish_debug_info) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.osc_debug_channel, &lcm, @@ -223,21 +225,23 @@ int DoMain(int argc, char* argv[]) { builder.Connect(gravity_compensator->get_output_port(), franka_command_sender->get_input_port()); } else { - if (FLAGS_lcm_channels == "examples/franka/parameters/lcm_channels_hardware.yaml"){ - std::cerr << "Using hardware lcm channels but not cancelling gravity compensation. Please check the OSC settings" << std::endl; + if (FLAGS_lcm_channels == + "examples/franka/parameters/lcm_channels_hardware.yaml") { + std::cerr << "Using hardware lcm channels but not cancelling gravity " + "compensation. Please check the OSC settings" + << std::endl; return -1; } builder.Connect(osc->get_output_port_osc_command(), franka_command_sender->get_input_port(0)); } - builder.Connect(radio_sub->get_output_port(0), + builder.Connect(*radio_sub, *radio_to_vector); + builder.Connect(radio_to_vector->get_output_port(), end_effector_trajectory->get_input_port_radio()); - builder.Connect(radio_sub->get_output_port(0), + builder.Connect(radio_to_vector->get_output_port(), end_effector_orientation_trajectory->get_input_port_radio()); - builder.Connect(state_receiver->get_output_port(0), - end_effector_force_trajectory->get_input_port_state()); - builder.Connect(radio_sub->get_output_port(0), + builder.Connect(radio_to_vector->get_output_port(), end_effector_force_trajectory->get_input_port_radio()); builder.Connect(franka_command_sender->get_output_port(), franka_command_pub->get_input_port()); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index cfe4a686d2..b4a5f6602f 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -122,10 +122,19 @@ int DoMain(int argc, char* argv[]) { {"supports", support_geom_set}, {"franka", franka_geom_set}); } + const drake::geometry::GeometrySet& franka_only_geom_set = + plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link8"), + }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"franka", franka_geom_set}, {"tray", tray_collision_set}); + {"franka", franka_only_geom_set}, {"tray", tray_collision_set}); plant.Finalize(); /* -------------------------------------------------------------------------------------------*/ diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 8d361b7d5e..f220bccafb 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -1,9 +1,10 @@ -#include #include +#include + +#include "examples/franka/diagrams/franka_c3_controller_diagram.h" +#include "examples/franka/diagrams/franka_osc_controller_diagram.h" -#include -#include #include #include #include @@ -13,91 +14,41 @@ #include #include #include +#include #include #include -#include #include #include #include +#include #include "common/eigen_utils.h" #include "common/find_resource.h" -#include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/parameters/franka_osc_controller_params.h" #include "examples/franka/parameters/franka_sim_params.h" -#include "examples/franka/systems/c3_state_sender.h" -#include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/end_effector_force_trajectory.h" -#include "examples/franka/systems/end_effector_orientation.h" -#include "examples/franka/systems/end_effector_trajectory.h" -#include "examples/franka/systems/franka_kinematics.h" -#include "examples/franka/systems/plate_balancing_target.h" #include "multibody/multibody_utils.h" -#include "solvers/lcs_factory.h" -#include "systems/controllers/c3/lcs_factory_system.h" -#include "systems/controllers/c3_controller.h" -#include "systems/controllers/osc/external_force_tracking_data.h" -#include "systems/controllers/osc/joint_space_tracking_data.h" -#include "systems/controllers/osc/operational_space_control.h" -#include "systems/controllers/osc/relative_translation_tracking_data.h" -#include "systems/controllers/osc/rot_space_tracking_data.h" -#include "systems/controllers/osc/trans_space_tracking_data.h" -#include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" +#include "systems/primitives/subvector_pass_through.h" #include "systems/system_utils.h" -#include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/trajectory_optimization/lcm_trajectory_systems.h" - namespace dairlib { -using dairlib::systems::SubvectorPassThrough; -using drake::geometry::GeometrySet; -using drake::geometry::SceneGraph; -using drake::math::RigidTransform; +using examples::controllers::FrankaOSCControllerDiagram; +using examples::controllers::FrankaC3ControllerDiagram; +using drake::systems::DiagramBuilder; using drake::multibody::AddMultibodyPlantSceneGraph; -using drake::multibody::MultibodyPlant; using drake::multibody::Parser; -using drake::systems::Context; -using drake::systems::DiagramBuilder; +using drake::math::RigidTransform; +using drake::geometry::GeometrySet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using drake::trajectories::PiecewisePolynomial; -using multibody::MakeNameToPositionsMap; -using multibody::MakeNameToVelocitiesMap; -using systems::AddActuationRecieverAndStateSenderLcm; using systems::RobotInputReceiver; +using systems::SubvectorPassThrough; using systems::RobotOutputSender; - -using drake::math::RigidTransform; -using drake::multibody::Parser; -using drake::systems::DiagramBuilder; -using drake::systems::TriggerType; -using drake::systems::TriggerTypeSet; -using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::LcmSubscriberSystem; -using Eigen::MatrixXd; -using Eigen::Vector3d; using Eigen::VectorXd; -using systems::controllers::ExternalForceTrackingData; -using systems::controllers::JointSpaceTrackingData; -using systems::controllers::RelativeTranslationTrackingData; -using systems::controllers::RotTaskSpaceTrackingData; -using systems::controllers::TransTaskSpaceTrackingData; - -using dairlib::solvers::LCSFactory; -using drake::SortedPair; -using drake::geometry::GeometryId; - -DEFINE_string(controller_settings, - "examples/franka/parameters/franka_c3_controller_params.yaml", - "Controller settings such as channels. Attempting to minimize " - "number of gflags"); int DoMain(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); drake::yaml::LoadYamlOptions yaml_options; @@ -108,308 +59,18 @@ int DoMain(int argc, char* argv[]) { // load parameters FrankaSimParams sim_params = drake::yaml::LoadYamlFile( "examples/franka/parameters/franka_sim_params.yaml"); - FrankaC3ControllerParams c3_controller_params = - drake::yaml::LoadYamlFile( - "examples/franka/parameters/franka_c3_controller_params.yaml"); - drake::solvers::SolverOptions solver_options = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(c3_controller_params.osqp_settings_file)) - .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - C3Options c3_options = drake::yaml::LoadYamlFile( - c3_controller_params.c3_options_file[c3_controller_params.scene_index]); - OSCGains gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow( - "examples/franka/parameters/franka_osc_controller_params.yaml"), - {}, {}, yaml_options); - FrankaControllerParams controller_params = - drake::yaml::LoadYamlFile( - "examples/franka/parameters/franka_osc_controller_params.yaml"); DiagramBuilder builder; /// OSC - drake::multibody::MultibodyPlant osc_plant(0.0); - Parser osc_parser(&osc_plant, nullptr); - osc_parser.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); - - RigidTransform X_WI = RigidTransform::Identity(); - osc_plant.WeldFrames(osc_plant.world_frame(), - osc_plant.GetFrameByName("panda_link0"), X_WI); - - if (!controller_params.end_effector_name.empty()) { - drake::multibody::ModelInstanceIndex end_effector_index = - osc_parser.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; - RigidTransform T_EE_W = - RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); - osc_plant.WeldFrames( - osc_plant.GetFrameByName("panda_link7"), - osc_plant.GetFrameByName(controller_params.end_effector_name, - end_effector_index), - T_EE_W); - } else { - std::cout << "OSC osc_plant has been constructed with no end effector." - << std::endl; - } - osc_plant.Finalize(); - auto osc_plant_context = osc_plant.CreateDefaultContext(); - - auto end_effector_position_receiver = - builder.AddSystem( - "end_effector_position_target"); - auto end_effector_force_receiver = - builder.AddSystem( - "end_effector_force_target"); - auto end_effector_orientation_receiver = - builder.AddSystem( - "end_effector_orientation_target"); - auto osc_command_sender = - builder.AddSystem(osc_plant); - auto end_effector_trajectory = - builder.AddSystem(); - auto end_effector_orientation_trajectory = - builder.AddSystem(); - end_effector_orientation_trajectory->SetTrackOrientation( - controller_params.track_end_effector_orientation); - auto end_effector_force_trajectory = - builder.AddSystem( - osc_plant, osc_plant_context.get()); - auto osc = builder.AddSystem( - osc_plant, osc_plant, osc_plant_context.get(), osc_plant_context.get(), - false); - auto end_effector_position_tracking_data = - std::make_unique( - "end_effector_target", controller_params.K_p_end_effector, - controller_params.K_d_end_effector, controller_params.W_end_effector, - osc_plant, osc_plant); - auto franka_command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.franka_input_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - end_effector_position_tracking_data->AddPointToTrack( - controller_params.end_effector_name); - const VectorXd& end_effector_acceleration_limits = - controller_params.end_effector_acceleration * Vector3d::Ones(); - end_effector_position_tracking_data->SetCmdAccelerationBounds( - -end_effector_acceleration_limits, end_effector_acceleration_limits); - auto mid_link_position_tracking_data_for_rel = - std::make_unique( - "panda_joint2_target", controller_params.K_p_mid_link, - controller_params.K_d_mid_link, controller_params.W_mid_link, - osc_plant, osc_plant); - mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", - "panda_joint2dot"); - - auto end_effector_force_tracking_data = - std::make_unique( - "end_effector_force", controller_params.W_ee_lambda, osc_plant, - osc_plant, controller_params.end_effector_name, Vector3d::Zero()); - - auto end_effector_orientation_tracking_data = - std::make_unique( - "end_effector_orientation_target", - controller_params.K_p_end_effector_rot, - controller_params.K_d_end_effector_rot, - controller_params.W_end_effector_rot, osc_plant, osc_plant); - end_effector_orientation_tracking_data->AddFrameToTrack( - controller_params.end_effector_name); - Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); - orientation_target(0) = 1; - osc->AddTrackingData(std::move(end_effector_position_tracking_data)); - osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), - 1.6 * VectorXd::Ones(1)); - osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); - osc->AddForceTrackingData(std::move(end_effector_force_tracking_data)); - osc->SetAccelerationCostWeights(gains.W_acceleration); - osc->SetInputCostWeights(gains.W_input_regularization); - osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); - osc->SetAccelerationConstraints( - controller_params.enforce_acceleration_constraints); - - osc->SetContactFriction(controller_params.mu); - drake::solvers::SolverOptions osc_solver_options = - drake::yaml::LoadYamlFile( - FindResourceOrThrow( - "examples/franka/parameters/franka_osc_qp_settings.yaml")) - .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - osc->SetOsqpSolverOptions(osc_solver_options); - - osc->Build(); - /// end of OSC + auto osc_controller = builder.AddSystem("examples/franka/parameters/franka_osc_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", + &lcm); /// C3 plant - DiagramBuilder plant_builder; - - MultibodyPlant plant_franka(0.0); - Parser parser_franka(&plant_franka, nullptr); - parser_franka.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); - drake::multibody::ModelInstanceIndex end_effector_index = - parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; - - plant_franka.WeldFrames(plant_franka.world_frame(), - plant_franka.GetFrameByName("panda_link0"), X_WI); - - RigidTransform T_EE_W = - RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); - plant_franka.WeldFrames( - plant_franka.GetFrameByName("panda_link7"), - plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); - - plant_franka.Finalize(); - auto franka_context = plant_franka.CreateDefaultContext(); - MultibodyPlant plant_tray(0.0); - Parser parser_tray(&plant_tray, nullptr); - parser_tray.AddModels(c3_controller_params.tray_model); - plant_tray.Finalize(); - auto tray_context = plant_tray.CreateDefaultContext(); - - auto [plant_for_lcs, lcs_scene_graph] = - AddMultibodyPlantSceneGraph(&plant_builder, 0.0); - Parser parser_plate(&plant_for_lcs); - parser_plate.SetAutoRenaming(true); - parser_plate.AddModels(c3_controller_params.plate_model); - - drake::multibody::ModelInstanceIndex left_support_index; - drake::multibody::ModelInstanceIndex right_support_index; - if (c3_controller_params.scene_index > 0) { - left_support_index = parser_plate.AddModels( - FindResourceOrThrow(c3_controller_params.left_support_model))[0]; - right_support_index = parser_plate.AddModels( - FindResourceOrThrow(c3_controller_params.right_support_model))[0]; - RigidTransform T_S1_W = RigidTransform( - drake::math::RollPitchYaw( - c3_controller_params.left_support_orientation), - c3_controller_params.left_support_position); - RigidTransform T_S2_W = RigidTransform( - drake::math::RollPitchYaw( - c3_controller_params.right_support_orientation), - c3_controller_params.right_support_position); - plant_for_lcs.WeldFrames( - plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); - plant_for_lcs.WeldFrames( - plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); - } - parser_plate.AddModels(c3_controller_params.tray_model); - - plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("base_link"), X_WI); - plant_for_lcs.Finalize(); - std::unique_ptr> plant_for_lcs_autodiff = - drake::systems::System::ToAutoDiffXd(plant_for_lcs); - - auto plant_diagram = plant_builder.Build(); - std::unique_ptr> diagram_context = - plant_diagram->CreateDefaultContext(); - auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( - plant_for_lcs, diagram_context.get()); - auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); - std::vector plate_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("plate")); - if (c3_controller_params.scene_index > 0) { - std::vector left_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", left_support_index)); - std::vector right_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", right_support_index)); - plate_contact_points.insert(plate_contact_points.end(), - left_support_contact_points.begin(), - left_support_contact_points.end()); - plate_contact_points.insert(plate_contact_points.end(), - right_support_contact_points.begin(), - right_support_contact_points.end()); - } - std::vector tray_geoms = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("tray")); - std::unordered_map> - contact_geoms; - contact_geoms["PLATE"] = plate_contact_points; - contact_geoms["TRAY"] = tray_geoms; - - std::vector> contact_pairs; - for (auto geom_id : contact_geoms["PLATE"]) { - contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); - } - - auto franka_state_receiver = - builder.AddSystem(plant_franka); - auto tray_state_receiver = - builder.AddSystem(plant_tray); - auto reduced_order_model_receiver = - builder.AddSystem( - plant_franka, franka_context.get(), plant_tray, tray_context.get(), - controller_params.end_effector_name, "tray", - c3_controller_params.include_end_effector_orientation); - - auto plate_balancing_target = - builder.AddSystem( - plant_tray, c3_controller_params.end_effector_thickness, - c3_controller_params.near_target_threshold); - plate_balancing_target->SetRemoteControlParameters( - c3_controller_params.first_target[c3_controller_params.scene_index], - c3_controller_params.second_target[c3_controller_params.scene_index], - c3_controller_params.third_target[c3_controller_params.scene_index], - c3_controller_params.x_scale, c3_controller_params.y_scale, - c3_controller_params.z_scale); - std::vector input_sizes = {3, 7, 3, 6}; - auto target_state_mux = - builder.AddSystem(input_sizes); - auto end_effector_zero_velocity_source = - builder.AddSystem( - VectorXd::Zero(3)); - auto tray_zero_velocity_source = - builder.AddSystem( - VectorXd::Zero(6)); - builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), - target_state_mux->get_input_port(0)); - builder.Connect(plate_balancing_target->get_output_port_tray_target(), - target_state_mux->get_input_port(1)); - builder.Connect(end_effector_zero_velocity_source->get_output_port(), - target_state_mux->get_input_port(2)); - builder.Connect(tray_zero_velocity_source->get_output_port(), - target_state_mux->get_input_port(3)); - auto lcs_factory = builder.AddSystem( - plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, - plate_context_ad.get(), contact_pairs, c3_options); - auto c3_controller = builder.AddSystem( - plant_for_lcs, &plant_for_lcs_context, c3_options); - auto c3_trajectory_generator = - builder.AddSystem(plant_for_lcs, - c3_options); - std::vector state_names = { - "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", - "tray_qx", "tray_qy", "tray_qz", "tray_x", - "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", - "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", - "tray_vz", "tray_vz", "tray_vz", - }; - auto c3_state_sender = - builder.AddSystem(3 + 7 + 3 + 6, state_names); - c3_trajectory_generator->SetPublishEndEffectorOrientation( - c3_controller_params.include_end_effector_orientation); - auto c3_output_sender = builder.AddSystem(); - auto c3_target_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_target_state_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_actual_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_actual_state_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); -// auto c3_output_publisher = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.c3_debug_output_channel, &lcm, -// TriggerTypeSet({TriggerType::kForced}))); - /// C3 + auto c3_controller = builder.AddSystem("examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", + &lcm); /// Sim Start double sim_dt = sim_params.dt; @@ -425,11 +86,10 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); - Vector3d franka_origin = Eigen::VectorXd::Zero(3); - RigidTransform T_X_W = RigidTransform( - drake::math::RotationMatrix(), franka_origin); - + drake::math::RotationMatrix(), Eigen::VectorXd::Zero(3)); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), sim_params.tool_attachment_frame); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), T_X_W); plant.WeldFrames(plant.GetFrameByName("panda_link7"), @@ -488,11 +148,9 @@ int DoMain(int argc, char* argv[]) { plant.Finalize(); /* -------------------------------------------------------------------------------------------*/ - auto input_receiver = builder.AddSystem(plant); auto passthrough = builder.AddSystem( - input_receiver->get_output_port(0).size(), 0, + osc_controller->get_output_port_robot_input().size(), 0, plant.get_actuation_input_port().size()); - builder.Connect(*input_receiver, *passthrough); auto tray_state_sender = builder.AddSystem(plant, tray_index); auto franka_state_sender = @@ -503,94 +161,25 @@ int DoMain(int argc, char* argv[]) { auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); - std::cout << lcm_channel_params.radio_channel << std::endl; - auto osc_state_receiver = - builder.AddSystem(osc_plant); //// OSC connections - builder.Connect(radio_sub->get_output_port(0), - end_effector_trajectory->get_input_port_radio()); - builder.Connect(radio_sub->get_output_port(0), - end_effector_orientation_trajectory->get_input_port_radio()); - builder.Connect(osc_state_receiver->get_output_port(0), - end_effector_force_trajectory->get_input_port_state()); - builder.Connect(radio_sub->get_output_port(0), - end_effector_force_trajectory->get_input_port_radio()); - builder.Connect(osc->get_output_port_osc_command(), - osc_command_sender->get_input_port(0)); - - builder.Connect(osc_state_receiver->get_output_port(0), - osc->get_input_port_robot_output()); - builder.Connect(end_effector_position_receiver->get_output_port(0), - end_effector_trajectory->get_input_port_trajectory()); - builder.Connect( - end_effector_orientation_receiver->get_output_port(0), - end_effector_orientation_trajectory->get_input_port_trajectory()); - builder.Connect(end_effector_trajectory->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_target")); - builder.Connect( - end_effector_orientation_trajectory->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_orientation_target")); - builder.Connect(end_effector_force_receiver->get_output_port(0), - end_effector_force_trajectory->get_input_port_trajectory()); - builder.Connect(end_effector_force_trajectory->get_output_port(0), - osc->get_input_port_tracking_data("end_effector_force")); - builder.Connect(osc_command_sender->get_output_port(), - franka_command_pub->get_input_port()); + builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); - c3_controller->SetOsqpSolverOptions(solver_options); - builder.Connect(franka_state_receiver->get_output_port(), - reduced_order_model_receiver->get_input_port_franka_state()); - builder.Connect(target_state_mux->get_output_port(), - c3_controller->get_input_port_target()); - builder.Connect(lcs_factory->get_output_port_lcs(), - c3_controller->get_input_port_lcs()); - builder.Connect(tray_state_receiver->get_output_port(), - reduced_order_model_receiver->get_input_port_object_state()); - builder.Connect(tray_state_receiver->get_output_port(), - plate_balancing_target->get_input_port_tray_state()); - builder.Connect(reduced_order_model_receiver->get_output_port(), - c3_controller->get_input_port_lcs_state()); - builder.Connect(radio_sub->get_output_port(), - c3_controller->get_input_port_radio()); - builder.Connect(reduced_order_model_receiver->get_output_port(), - lcs_factory->get_input_port_lcs_state()); - builder.Connect(radio_sub->get_output_port(), - plate_balancing_target->get_input_port_radio()); - builder.Connect(c3_controller->get_output_port_c3_solution(), - c3_trajectory_generator->get_input_port_c3_solution()); - builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), - c3_output_sender->get_input_port_lcs_contact_info()); - builder.Connect(c3_state_sender->get_output_port_target_c3_state(), - c3_target_state_publisher->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), - c3_actual_state_publisher->get_input_port()); - builder.Connect(target_state_mux->get_output_port(), - c3_state_sender->get_input_port_target_state()); - builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), - c3_state_sender->get_input_port_actual_state()); -// builder.Connect(c3_output_sender->get_output_port_c3_debug(), -// c3_output_publisher->get_input_port()); - builder.Connect(c3_controller->get_output_port_c3_solution(), - c3_output_sender->get_input_port_c3_solution()); - builder.Connect(c3_controller->get_output_port_c3_intermediates(), - c3_output_sender->get_input_port_c3_intermediates()); // Diagram Connections - builder.Connect(*tray_state_sender, *tray_state_receiver); - builder.Connect(*osc_command_sender, *input_receiver); - builder.Connect(passthrough->get_output_port(), - plant.get_actuation_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), - end_effector_force_receiver->get_input_port_trajectory()); - builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), - end_effector_position_receiver->get_input_port_trajectory()); - builder.Connect( - c3_trajectory_generator->get_output_port_actor_trajectory(), - end_effector_orientation_receiver->get_input_port_trajectory()); - builder.Connect(*franka_state_sender, *franka_state_receiver); - builder.Connect(*franka_state_sender, *osc_state_receiver); + builder.Connect(osc_controller->get_output_port_robot_input(), passthrough->get_input_port()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), osc_controller->get_input_port_end_effector_position()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), osc_controller->get_input_port_end_effector_orientation()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), osc_controller->get_input_port_end_effector_force()); + + + builder.Connect(franka_state_sender->get_output_port(), osc_controller->get_input_port_robot_state()); + builder.Connect(franka_state_sender->get_output_port(), c3_controller->get_input_port_robot_state()); + builder.Connect(tray_state_sender->get_output_port(), c3_controller->get_input_port_object_state()); + builder.Connect(radio_sub->get_output_port(), c3_controller->get_input_port_radio()); + builder.Connect(radio_sub->get_output_port(), osc_controller->get_input_port_radio()); + builder.Connect(*franka_state_sender, *state_pub); builder.Connect(plant.get_state_output_port(franka_index), franka_state_sender->get_input_port_state()); @@ -616,8 +205,6 @@ int DoMain(int argc, char* argv[]) { plant, &simulator.get_mutable_context()); VectorXd q = VectorXd::Zero(nq); - std::map q_map = MakeNameToPositionsMap(plant); - q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; q.tail(plant.num_positions(tray_index)) = diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 5302861fe0..50485f81ad 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,11 +1,11 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf -end_effector_model: examples/franka/urdf/plate_end_effector_parameter_sweep.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray.sdf left_support_model: examples/franka/urdf/support.urdf right_support_model: examples/franka/urdf/support.urdf franka_publish_rate: 1000 -tray_publish_rate: 10 -visualizer_publish_rate: 60 +tray_publish_rate: 1000 +visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 1 diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index 9ff439e0fe..f8dcf18605 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -22,15 +22,7 @@ using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator( - const MultibodyPlant& plant, Context* context) - : plant_(plant), context_(context), world_(plant.world_frame()) { - // Input/Output Setup - state_port_ = this->DeclareVectorInputPort( - "x", OutputVector(plant_.num_positions(), - plant_.num_velocities(), - plant_.num_actuators())) - .get_index(); +EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator() { PiecewisePolynomial pp = PiecewisePolynomial(); trajectory_port_ = @@ -39,8 +31,7 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator( drake::Value>(pp)) .get_index(); radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) + this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) .get_index(); controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); DeclareForcedDiscreteUpdateEvent( @@ -52,19 +43,17 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator( &EndEffectorForceTrajectoryGenerator::CalcTraj); } - EventStatus EndEffectorForceTrajectoryGenerator::DiscreteVariableUpdate( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const { - - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); bool using_c3 = context.get_discrete_state(controller_switch_index_)[0]; - if (!using_c3 && radio_out->channel[14] == 0) { - if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.04) { + if (!using_c3 && radio_out->value()[14] == 0) { + if (!trajectory_input.value(0).isZero() && + (context.get_time() - trajectory_input.start_time()) < 0.04) { discrete_state->get_mutable_value(controller_switch_index_)[0] = 1; } } @@ -78,15 +67,16 @@ void EndEffectorForceTrajectoryGenerator::CalcTraj( const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { - *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); + if (radio_out->value()[11] || radio_out->value()[14] || + trajectory_input.value(0).isZero()) { + *casted_traj = + drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); } else { - if (context.get_discrete_state(controller_switch_index_)[0]){ + if (context.get_discrete_state(controller_switch_index_)[0]) { *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/examples/franka/systems/end_effector_force_trajectory.h b/examples/franka/systems/end_effector_force_trajectory.h index 5eb48cfb7f..0c4468d228 100644 --- a/examples/franka/systems/end_effector_force_trajectory.h +++ b/examples/franka/systems/end_effector_force_trajectory.h @@ -12,13 +12,8 @@ namespace dairlib { class EndEffectorForceTrajectoryGenerator : public drake::systems::LeafSystem { public: - EndEffectorForceTrajectoryGenerator( - const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context); + EndEffectorForceTrajectoryGenerator(); - const drake::systems::InputPort& get_input_port_state() const { - return this->get_input_port(state_port_); - } const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_port_); } @@ -36,14 +31,8 @@ class EndEffectorForceTrajectoryGenerator drake::systems::DiscreteStateIndex controller_switch_index_; - const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; - const drake::multibody::Frame& world_; - - drake::systems::InputPortIndex state_port_; drake::systems::InputPortIndex trajectory_port_; drake::systems::InputPortIndex radio_port_; - }; } // namespace dairlib diff --git a/examples/franka/systems/end_effector_orientation.cc b/examples/franka/systems/end_effector_orientation.cc index ac961678e6..ac42221bcd 100644 --- a/examples/franka/systems/end_effector_orientation.cc +++ b/examples/franka/systems/end_effector_orientation.cc @@ -2,6 +2,7 @@ #include "dairlib/lcmt_radio_out.hpp" +using drake::systems::BasicVector; using Eigen::MatrixXd; using Eigen::VectorXd; using std::string; @@ -21,8 +22,7 @@ EndEffectorOrientationGenerator::EndEffectorOrientationGenerator() { drake::Value>(pp)) .get_index(); radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) + this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) .get_index(); PiecewiseQuaternionSlerp empty_slerp_traj; Trajectory& traj_inst = empty_slerp_traj; @@ -31,31 +31,26 @@ EndEffectorOrientationGenerator::EndEffectorOrientationGenerator() { .get_index(); } -PiecewiseQuaternionSlerp EndEffectorOrientationGenerator::GeneratePose( - const drake::systems::Context& context) const { - Eigen::VectorXd neutral_quaternion = VectorXd::Zero(4); - neutral_quaternion(0) = 1; - return drake::trajectories::PiecewiseQuaternionSlerp( - {0, 1}, {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); -} - void EndEffectorOrientationGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { - // // Read in finite state machine - - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< PiecewiseQuaternionSlerp*>(traj); - if (radio_out->channel[14] and track_orientation_) { + if (radio_out->value()[14] and track_orientation_) { const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); *casted_traj = *(PiecewiseQuaternionSlerp*)dynamic_cast< const PiecewiseQuaternionSlerp*>(&trajectory_input); } else { - *casted_traj = GeneratePose(context); + PiecewiseQuaternionSlerp result; + Eigen::VectorXd neutral_quaternion = VectorXd::Zero(4); + neutral_quaternion(0) = 1; + result = drake::trajectories::PiecewiseQuaternionSlerp( + {0, 1}, + {Eigen::Quaterniond(1, 0, 0, 0), Eigen::Quaterniond(1, 0, 0, 0)}); + *casted_traj = result; } } diff --git a/examples/franka/systems/end_effector_orientation.h b/examples/franka/systems/end_effector_orientation.h index db134e65d1..4799bc0752 100644 --- a/examples/franka/systems/end_effector_orientation.h +++ b/examples/franka/systems/end_effector_orientation.h @@ -5,7 +5,8 @@ namespace dairlib { -class EndEffectorOrientationGenerator : public drake::systems::LeafSystem { +class EndEffectorOrientationGenerator + : public drake::systems::LeafSystem { public: EndEffectorOrientationGenerator(); @@ -16,7 +17,7 @@ class EndEffectorOrientationGenerator : public drake::systems::LeafSystemget_input_port(radio_port_); } - void SetTrackOrientation(bool track_orientation){ + void SetTrackOrientation(bool track_orientation) { track_orientation_ = track_orientation; } @@ -24,8 +25,6 @@ class EndEffectorOrientationGenerator : public drake::systems::LeafSystem& context, drake::systems::DiscreteValues* discrete_state) const; - drake::trajectories::PiecewiseQuaternionSlerp GeneratePose( - const drake::systems::Context& context) const; void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; @@ -34,7 +33,6 @@ class EndEffectorOrientationGenerator : public drake::systems::LeafSystem>(pp)) .get_index(); radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) + this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) .get_index(); + PiecewisePolynomial empty_pp_traj(neutral_pose_); Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, @@ -46,31 +46,24 @@ void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( z_scale_ = z_scale; } -PiecewisePolynomial EndEffectorTrajectoryGenerator::GeneratePose( - const drake::systems::Context& context) const { - const auto& radio_out = - this->EvalInputValue(context, radio_port_); - VectorXd y0 = neutral_pose_; - y0(0) += radio_out->channel[0] * x_scale_; - y0(1) += radio_out->channel[1] * y_scale_; - y0(2) += radio_out->channel[2] * z_scale_; - return drake::trajectories::PiecewisePolynomial(y0); -} - void EndEffectorTrajectoryGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { - // // Read in finite state machine const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (radio_out->channel[14]) { - *casted_traj = GeneratePose(context); + if (radio_out->value()[14]) { + PiecewisePolynomial result; + VectorXd y_0 = neutral_pose_; + y_0(0) += radio_out->value()[0] * x_scale_; + y_0(1) += radio_out->value()[1] * y_scale_; + y_0(2) += radio_out->value()[2] * z_scale_; + result = drake::trajectories::PiecewisePolynomial(y_0); + *casted_traj = result; } else { if (trajectory_input.value(0).isZero()) { } else { diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index f0489d1455..85b8b0d81e 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -25,8 +25,6 @@ class EndEffectorTrajectoryGenerator drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; - drake::trajectories::PiecewisePolynomial GeneratePose( - const drake::systems::Context& context) const; void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 98a60bc128..1cadcdde40 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -20,8 +20,7 @@ PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( target_threshold_(target_threshold) { // Input/Output Setup radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) + this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) .get_index(); tray_state_port_ = this->DeclareVectorInputPort( @@ -49,8 +48,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( drake::systems::DiscreteValues* discrete_state) const { const StateVector* tray_state = (StateVector*)this->EvalVectorInput(context, tray_state_port_); - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); // Ugly FSM int current_sequence = context.get_discrete_state(sequence_index_)[0]; @@ -93,7 +91,7 @@ EventStatus PlateBalancingTargetGenerator::DiscreteVariableUpdate( discrete_state->get_mutable_value(sequence_index_)[0] = 3; } } - if (current_sequence == 3 && radio_out->channel[15] < 0) { + if (current_sequence == 3 && radio_out->value()[15] < 0) { discrete_state->get_mutable_value(sequence_index_)[0] = 0; } return EventStatus::Succeeded(); @@ -114,8 +112,7 @@ void PlateBalancingTargetGenerator::SetRemoteControlParameters( void PlateBalancingTargetGenerator::CalcEndEffectorTarget( const drake::systems::Context& context, drake::systems::BasicVector* target) const { - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); VectorXd end_effector_position = first_target_; // Update target if remote trigger is active @@ -133,24 +130,24 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( if (end_effector_position[1] > 0.05) { end_effector_position[1] = 0.05; // keep it within the workspace } - if (radio_out->channel[13] > 0) { - end_effector_position(0) += radio_out->channel[0] * x_scale_; - end_effector_position(1) += radio_out->channel[1] * y_scale_; - end_effector_position(2) += radio_out->channel[2] * z_scale_; + if (radio_out->value()[13] > 0) { + end_effector_position(0) += radio_out->value()[0] * x_scale_; + end_effector_position(1) += radio_out->value()[1] * y_scale_; + end_effector_position(2) += radio_out->value()[2] * z_scale_; } -// end_effector_position(0) = 0.55; -// end_effector_position(1) = 0.1 * sin(4 * context.get_time()); -// end_effector_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()) - end_effector_thickness_; -// end_effector_position(1) = 0.1 * (int) (2 * sin(0.5 * context.get_time())); -// end_effector_position(2) = 0.45 - end_effector_thickness_; + // end_effector_position(0) = 0.55; + // end_effector_position(1) = 0.1 * sin(4 * context.get_time()); + // end_effector_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()) - + // end_effector_thickness_; end_effector_position(1) = 0.1 * (int) (2 * + // sin(0.5 * context.get_time())); end_effector_position(2) = 0.45 - + // end_effector_thickness_; target->SetFromVector(end_effector_position); } void PlateBalancingTargetGenerator::CalcTrayTarget( const drake::systems::Context& context, BasicVector* target) const { - const auto& radio_out = - this->EvalInputValue(context, radio_port_); + const auto& radio_out = this->EvalVectorInput(context, radio_port_); VectorXd target_tray_state = VectorXd::Zero(7); VectorXd tray_position = first_target_; @@ -160,14 +157,14 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( context.get_discrete_state(sequence_index_)[0] == 3) { tray_position = third_target_; } - tray_position(0) += radio_out->channel[0] * x_scale_; - tray_position(1) += radio_out->channel[1] * y_scale_; - tray_position(2) += radio_out->channel[2] * z_scale_; -// tray_position(0) = 0.55; -// tray_position(1) = 0.1 * sin(4 * context.get_time()); -// tray_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()); -// tray_position(1) = 0.1 * (int) (2 * sin(0.5 * context.get_time())); -// tray_position(2) = 0.45; + tray_position(0) += radio_out->value()[0] * x_scale_; + tray_position(1) += radio_out->value()[1] * y_scale_; + tray_position(2) += radio_out->value()[2] * z_scale_; + // tray_position(0) = 0.55; + // tray_position(1) = 0.1 * sin(4 * context.get_time()); + // tray_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()); + // tray_position(1) = 0.1 * (int) (2 * sin(0.5 * context.get_time())); + // tray_position(2) = 0.45; target_tray_state << 1, 0, 0, 0, tray_position; // tray orientation is flat target->SetFromVector(target_tray_state); } diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 21b0f1deb7..4e2e59c35b 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -24,10 +24,10 @@ namespace systems { LCSFactorySystem::LCSFactorySystem( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, + drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, drake::systems::Context* context_ad, - const std::vector>& + const std::vector> contact_geoms, C3Options c3_options) : plant_(plant), @@ -97,8 +97,8 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, q_v_u << lcs_x->get_data(), VectorXd::Zero(n_u_); drake::AutoDiffVecXd q_v_u_ad = drake::math::InitializeAutoDiff(q_v_u); - plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); - multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); + plant_.SetPositionsAndVelocities(&context_, q_v_u.head(n_x_)); + multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), &context_); multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u_), context_ad_); solvers::ContactModel contact_model; @@ -112,7 +112,7 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, double scale; std::tie(*output_lcs, scale) = LCSFactory::LinearizePlantToLCS( - plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + plant_, context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); } @@ -129,8 +129,8 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Contextget_data(), VectorXd::Zero(n_u_); - plant_.SetPositionsAndVelocities(context_, q_v_u.head(n_x_)); - multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), context_); + plant_.SetPositionsAndVelocities(&context_, q_v_u.head(n_x_)); + multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), &context_); solvers::ContactModel contact_model; if (c3_options_.contact_model == "stewart_and_trinkle") { contact_model = solvers::ContactModel::kStewartAndTrinkle; @@ -142,7 +142,7 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context contact_points; *output = LCSFactory::ComputeContactJacobian( - plant_, *context_, plant_ad_, *context_ad_, contact_pairs_, + plant_, context_, plant_ad_, *context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); } diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h index 50030e8c01..36ca372ff2 100644 --- a/systems/controllers/c3/lcs_factory_system.h +++ b/systems/controllers/c3/lcs_factory_system.h @@ -18,10 +18,10 @@ class LCSFactorySystem : public drake::systems::LeafSystem { public: explicit LCSFactorySystem( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, + drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, drake::systems::Context* context_ad, - const std::vector>& contact_geoms, + const std::vector> contact_geoms, C3Options c3_options); const drake::systems::InputPort& get_input_port_lcs_state() const { @@ -41,9 +41,6 @@ class LCSFactorySystem : public drake::systems::LeafSystem { } private: - drake::systems::EventStatus UpdateLCS( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; void OutputLCS(const drake::systems::Context& context, solvers::LCS* output_traj) const; void OutputLCSContactJacobian(const drake::systems::Context& context, @@ -55,10 +52,10 @@ class LCSFactorySystem : public drake::systems::LeafSystem { drake::systems::OutputPortIndex lcs_contact_jacobian_port_; const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; + drake::systems::Context& context_; const drake::multibody::MultibodyPlant& plant_ad_; drake::systems::Context* context_ad_; - const std::vector>& + const std::vector> contact_pairs_; C3Options c3_options_; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index bf6944e7f6..675b1b2191 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -1,6 +1,7 @@ #include "c3_controller.h" #include + #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" #include "solvers/c3_miqp.h" @@ -29,9 +30,8 @@ namespace systems { C3Controller::C3Controller( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, C3Options c3_options) + C3Options c3_options) : plant_(plant), - context_(context), c3_options_(std::move(c3_options)), G_(std::vector(c3_options_.N, c3_options_.G)), U_(std::vector(c3_options_.N, c3_options_.U)), @@ -48,6 +48,7 @@ C3Controller::C3Controller( DRAKE_DEMAND(Q_.size() == N_ + 1); DRAKE_DEMAND(R_.size() == N_); + filtered_solve_time_ = 0.0; n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_u_ = plant_.num_actuators(); @@ -62,6 +63,9 @@ C3Controller::C3Controller( n_lambda_ = 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; } + VectorXd zeros = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); + w_ = std::vector(N_, zeros); + delta_ = std::vector(N_, zeros); n_u_ = plant_.num_actuators(); @@ -120,10 +124,6 @@ C3Controller::C3Controller( c3_options_.u_vertical_limits[1], 2); } - radio_port_ = - this->DeclareAbstractInputPort("lcmt_radio_out", - drake::Value{}) - .get_index(); lcs_state_input_port_ = this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) .get_index(); @@ -173,8 +173,6 @@ drake::systems::EventStatus C3Controller::ComputePlan( DiscreteValues* discrete_state) const { auto start = std::chrono::high_resolution_clock::now(); - const auto& radio_out = - this->EvalInputValue(context, radio_port_); const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const TimestampedVector* lcs_x = @@ -187,7 +185,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( // TODO(yangwill): clean this up // if (x_lcs.segment(n_q_, 3).norm() > 0.05 && c3_options_.use_predicted_x0 // && !x_pred_.isZero()) { - if (!radio_out->channel[14] && c3_options_.use_predicted_x0 && !x_pred_.isZero()) { + if (x_lcs.segment(n_q_, 3).norm() > 0.01 && c3_options_.use_predicted_x0 && !x_pred_.isZero()) { x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, x_lcs[0] + 10 * dt_ * dt_); x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 9493488a6b..125ad37f25 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -27,17 +27,12 @@ class C3Controller : public drake::systems::LeafSystem { public: explicit C3Controller( const drake::multibody::MultibodyPlant& plant, - drake::systems::Context* context, C3Options c3_options); const drake::systems::InputPort& get_input_port_target() const { return this->get_input_port(target_input_port_); } - const drake::systems::InputPort& get_input_port_radio() const { - return this->get_input_port(radio_port_); - } - const drake::systems::InputPort& get_input_port_lcs_state() const { return this->get_input_port(lcs_state_input_port_); } @@ -73,7 +68,6 @@ class C3Controller : public drake::systems::LeafSystem { void OutputC3Intermediates(const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const; - drake::systems::InputPortIndex radio_port_; drake::systems::InputPortIndex target_input_port_; drake::systems::InputPortIndex lcs_state_input_port_; drake::systems::InputPortIndex lcs_input_port_; @@ -81,7 +75,6 @@ class C3Controller : public drake::systems::LeafSystem { drake::systems::OutputPortIndex c3_intermediates_port_; const drake::multibody::MultibodyPlant& plant_; - drake::systems::Context* context_; C3Options c3_options_; drake::solvers::SolverOptions solver_options_ = diff --git a/systems/primitives/radio_parser.cc b/systems/primitives/radio_parser.cc index 8cad3488b6..9f26acc05e 100644 --- a/systems/primitives/radio_parser.cc +++ b/systems/primitives/radio_parser.cc @@ -1,7 +1,5 @@ #include "systems/primitives/radio_parser.h" -#include - namespace dairlib { namespace systems { @@ -26,5 +24,26 @@ void RadioParser::CalcRadioOutput( } } +RadioToVector::RadioToVector() { + radio_port_ = this->DeclareAbstractInputPort( + "radio_in", drake::Value()) + .get_index(); + this->DeclareVectorOutputPort("raw_radio", BasicVector(2 + 16), + &RadioToVector::ConvertToVector); +} + +void RadioToVector::ConvertToVector( + const drake::systems::Context& context, + drake::systems::BasicVector* output) const { + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + output->SetZero(); + for (int i = 0; i < 16; ++i) { + output->get_mutable_value()[i] = radio_out->channel[i]; + } + output->get_mutable_value()[16 + 0] = radio_out->radioReceiverSignalGood; + output->get_mutable_value()[16 + 1] = radio_out->receiverMedullaSignalGood; +} + } // namespace systems } // namespace dairlib diff --git a/systems/primitives/radio_parser.h b/systems/primitives/radio_parser.h index 754054ed7e..f6886d00aa 100644 --- a/systems/primitives/radio_parser.h +++ b/systems/primitives/radio_parser.h @@ -28,5 +28,26 @@ class RadioParser : public drake::systems::LeafSystem { int data_input_port_; }; +class RadioToVector : public drake::systems::LeafSystem { + public: + RadioToVector(); + + const drake::systems::InputPort& get_input_port() const { + return drake::systems::LeafSystem::get_input_port(0); + } + + const drake::systems::OutputPort& get_output_port() const { + return drake::systems::LeafSystem::get_output_port(0); + } + + protected: + void ConvertToVector(const drake::systems::Context& context, + drake::systems::BasicVector* output) const; + + private: + bool is_abstract() const { return false; } + int radio_port_; +}; + } // namespace systems } // namespace dairlib From 07f46d6449aa2f57f388dc20aab6272b8266aa2e Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 20 Feb 2024 14:44:35 -0500 Subject: [PATCH 655/758] deterministic sim is running but not quite fully working --- .../diagrams/franka_c3_controller_diagram.cc | 193 ++++++++++-------- examples/franka/full_diagram.cc | 81 +++++--- .../franka_c3_options_w_supports.yaml | 2 + .../franka/parameters/franka_sim_params.yaml | 4 +- solvers/c3_options.h | 2 + systems/controllers/c3_controller.cc | 18 +- 6 files changed, 174 insertions(+), 126 deletions(-) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index f1a9f74963..26a3d34edb 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -27,10 +27,10 @@ #include "systems/controllers/c3/lcs_factory_system.h" #include "systems/controllers/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/primitives/radio_parser.h" namespace dairlib { @@ -58,15 +58,13 @@ using multibody::MakeNameToVelocitiesMap; using std::string; FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( - const string& controller_settings, - const string& lcm_channels, - drake::lcm::DrakeLcm* lcm){ + const string& controller_settings, const string& lcm_channels, + drake::lcm::DrakeLcm* lcm) { this->set_name("FrankaC3Controller"); DiagramBuilder builder; FrankaC3ControllerParams controller_params = - drake::yaml::LoadYamlFile( - controller_settings); + drake::yaml::LoadYamlFile(controller_settings); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(lcm_channels); C3Options c3_options = drake::yaml::LoadYamlFile( @@ -76,7 +74,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( FindResourceOrThrow(controller_params.osqp_settings_file)) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - plant_franka_ = new drake::multibody::MultibodyPlant (0.0); + plant_franka_ = new drake::multibody::MultibodyPlant(0.0); Parser parser_franka(plant_franka_, nullptr); parser_franka.AddModels( drake::FindResourceOrThrow(controller_params.franka_model)); @@ -86,7 +84,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( RigidTransform X_WI = RigidTransform::Identity(); plant_franka_->WeldFrames(plant_franka_->world_frame(), - plant_franka_->GetFrameByName("panda_link0"), X_WI); + plant_franka_->GetFrameByName("panda_link0"), X_WI); RigidTransform T_EE_W = RigidTransform(drake::math::RotationMatrix(), @@ -99,18 +97,21 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plant_franka_context_ = plant_franka_->CreateDefaultContext(); /// - plant_tray_ = new drake::multibody::MultibodyPlant (0.0); + plant_tray_ = new drake::multibody::MultibodyPlant(0.0); Parser parser_tray(plant_tray_, nullptr); parser_tray.AddModels(controller_params.tray_model); plant_tray_->Finalize(); plant_tray_context_ = plant_tray_->CreateDefaultContext(); /// -// plant_for_lcs_ = std::make_unique>(0.0); -// AddMultibodyPlantSceneGraph(&plant_builder, std::make_unique>(0.0), scene_graph_lcs_); -// plant_for_lcs_, scene_graph_lcs_ = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + // plant_for_lcs_ = + // std::make_unique>(0.0); + // AddMultibodyPlantSceneGraph(&plant_builder, + // std::make_unique>(0.0), + // scene_graph_lcs_); plant_for_lcs_, scene_graph_lcs_ = + // AddMultibodyPlantSceneGraph(&plant_builder, 0.0); drake::planning::RobotDiagramBuilder lcs_diagram_builder; -// lcs_diagram_builder.plant() + // lcs_diagram_builder.plant() lcs_diagram_builder.parser().SetAutoRenaming(true); lcs_diagram_builder.parser().AddModels(controller_params.plate_model); @@ -122,35 +123,44 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( right_support_index = lcs_diagram_builder.parser().AddModels( FindResourceOrThrow(controller_params.right_support_model))[0]; RigidTransform T_S1_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), + RigidTransform(drake::math::RollPitchYaw( + controller_params.left_support_orientation), controller_params.left_support_position); RigidTransform T_S2_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), + RigidTransform(drake::math::RollPitchYaw( + controller_params.right_support_orientation), controller_params.right_support_position); lcs_diagram_builder.plant().WeldFrames( lcs_diagram_builder.plant().world_frame(), - lcs_diagram_builder.plant().GetFrameByName("support", left_support_index), T_S1_W); + lcs_diagram_builder.plant().GetFrameByName("support", + left_support_index), + T_S1_W); lcs_diagram_builder.plant().WeldFrames( lcs_diagram_builder.plant().world_frame(), - lcs_diagram_builder.plant().GetFrameByName("support", right_support_index), T_S2_W); + lcs_diagram_builder.plant().GetFrameByName("support", + right_support_index), + T_S2_W); } lcs_diagram_builder.parser().AddModels(controller_params.tray_model); - lcs_diagram_builder.plant().WeldFrames(lcs_diagram_builder.plant().world_frame(), - lcs_diagram_builder.plant().GetFrameByName("base_link"), X_WI); + lcs_diagram_builder.plant().WeldFrames( + lcs_diagram_builder.plant().world_frame(), + lcs_diagram_builder.plant().GetFrameByName("base_link"), X_WI); lcs_diagram_builder.plant().Finalize(); robot_diagram_for_lcs_ = lcs_diagram_builder.Build(); - plant_for_lcs_autodiff_ = - drake::systems::System::ToAutoDiffXd(robot_diagram_for_lcs_->plant()); + plant_for_lcs_autodiff_ = drake::systems::System::ToAutoDiffXd( + robot_diagram_for_lcs_->plant()); -// auto plant_diagram = plant_builder.Build(); -// auto plant_diagram = plant_lcs_builder_->Build(); -// plant_for_lcs_diagram_context_ = -// plant_diagram->CreateDefaultContext(); -// plant_for_lcs_context_ = std::move(plant_diagram->GetMutableSubsystemContext( -// plant_for_lcs_, plant_for_lcs_diagram_context_.get())); + // auto plant_diagram = plant_builder.Build(); + // auto plant_diagram = plant_lcs_builder_->Build(); + // plant_for_lcs_diagram_context_ = + // plant_diagram->CreateDefaultContext(); + // plant_for_lcs_context_ = + // std::move(plant_diagram->GetMutableSubsystemContext( + // plant_for_lcs_, plant_for_lcs_diagram_context_.get())); robot_diagram_root_context_ = robot_diagram_for_lcs_->CreateDefaultContext(); - plant_for_lcs_autodiff_context_ = plant_for_lcs_autodiff_->CreateDefaultContext(); + plant_for_lcs_autodiff_context_ = + plant_for_lcs_autodiff_->CreateDefaultContext(); /// std::vector end_effector_contact_points = @@ -159,10 +169,12 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( if (controller_params.scene_index > 0) { std::vector left_support_contact_points = robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( - robot_diagram_for_lcs_->plant().GetBodyByName("support", left_support_index)); + robot_diagram_for_lcs_->plant().GetBodyByName("support", + left_support_index)); std::vector right_support_contact_points = robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( - robot_diagram_for_lcs_->plant().GetBodyByName("support", right_support_index)); + robot_diagram_for_lcs_->plant().GetBodyByName("support", + right_support_index)); end_effector_contact_points.insert(end_effector_contact_points.end(), left_support_contact_points.begin(), left_support_contact_points.end()); @@ -189,42 +201,20 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( builder.AddSystem(*plant_tray_); auto reduced_order_model_receiver = builder.AddSystem( - *plant_franka_, plant_franka_context_.get(), *plant_tray_, plant_tray_context_.get(), - controller_params.end_effector_name, "tray", - controller_params.include_end_effector_orientation); - auto actor_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_actor_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - - auto object_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_object_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - - auto c3_output_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_debug_output_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_target_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_target_state_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_actual_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_actual_state_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_forces_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_force_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); + *plant_franka_, plant_franka_context_.get(), *plant_tray_, + plant_tray_context_.get(), controller_params.end_effector_name, + "tray", controller_params.include_end_effector_orientation); auto plate_balancing_target = - builder.AddSystem(*plant_tray_, controller_params.end_effector_thickness, controller_params.near_target_threshold); + builder.AddSystem( + *plant_tray_, controller_params.end_effector_thickness, + controller_params.near_target_threshold); plate_balancing_target->SetRemoteControlParameters( - controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], - controller_params.third_target[controller_params.scene_index], controller_params.x_scale, - controller_params.y_scale, controller_params.z_scale); + controller_params.first_target[controller_params.scene_index], + controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], + controller_params.x_scale, controller_params.y_scale, + controller_params.z_scale); std::vector input_sizes = {3, 7, 3, 6}; auto target_state_mux = builder.AddSystem(input_sizes); @@ -243,13 +233,16 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( builder.Connect(tray_zero_velocity_source->get_output_port(), target_state_mux->get_input_port(3)); auto lcs_factory = builder.AddSystem( - robot_diagram_for_lcs_->plant(), robot_diagram_for_lcs_->mutable_plant_context(robot_diagram_root_context_.get()), *plant_for_lcs_autodiff_, - plant_for_lcs_autodiff_context_.get(), contact_pairs, c3_options); + robot_diagram_for_lcs_->plant(), + robot_diagram_for_lcs_->mutable_plant_context( + robot_diagram_root_context_.get()), + *plant_for_lcs_autodiff_, plant_for_lcs_autodiff_context_.get(), + contact_pairs, c3_options); auto controller = builder.AddSystem( robot_diagram_for_lcs_->plant(), c3_options); auto c3_trajectory_generator = - builder.AddSystem(robot_diagram_for_lcs_->plant(), - c3_options); + builder.AddSystem( + robot_diagram_for_lcs_->plant(), c3_options); std::vector state_names = { "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", "tray_qx", "tray_qy", "tray_qz", "tray_x", @@ -276,8 +269,8 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plate_balancing_target->get_input_port_tray_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_lcs_state()); -// builder.Connect(radio_sub->get_output_port(), -// controller->get_input_port_radio()); + // builder.Connect(radio_sub->get_output_port(), + // controller->get_input_port_radio()); builder.Connect(reduced_order_model_receiver->get_output_port(), lcs_factory->get_input_port_lcs_state()); builder.Connect(radio_to_vector->get_output_port(), @@ -286,34 +279,70 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( c3_trajectory_generator->get_input_port_c3_solution()); builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), c3_output_sender->get_input_port_lcs_contact_info()); - builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), - actor_trajectory_sender->get_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), - object_trajectory_sender->get_input_port()); + builder.Connect(target_state_mux->get_output_port(), c3_state_sender->get_input_port_target_state()); builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), c3_state_sender->get_input_port_actual_state()); - builder.Connect(c3_state_sender->get_output_port_target_c3_state(), - c3_target_state_publisher->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), - c3_actual_state_publisher->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution(), c3_output_sender->get_input_port_c3_solution()); builder.Connect(controller->get_output_port_c3_intermediates(), c3_output_sender->get_input_port_c3_intermediates()); + + // publisher connections + DRAKE_DEMAND(c3_options.publish_frequency > 0); + + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_channel, lcm, + TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_channel, lcm, + TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, lcm, + TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm, + TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm, + TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, lcm, + TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + actor_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), + object_trajectory_sender->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); builder.Connect(c3_output_sender->get_output_port_c3_debug(), c3_output_publisher->get_input_port()); builder.Connect(c3_output_sender->get_output_port_c3_force(), c3_forces_publisher->get_input_port()); // Publisher connections - builder.ExportInput(franka_state_receiver->get_input_port(), "franka_state: lcmt_robot_output"); - builder.ExportInput(tray_state_receiver->get_input_port(), "tray_state: lcmt_object_state"); + builder.ExportInput(franka_state_receiver->get_input_port(), + "franka_state: lcmt_robot_output"); + builder.ExportInput(tray_state_receiver->get_input_port(), + "tray_state: lcmt_object_state"); builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); - builder.ExportOutput(c3_trajectory_generator->get_output_port_actor_trajectory(), "actor_trajectory"); -// builder.ExportOutput(c3_trajectory_generator->get_output_port_object_trajectory(), "object_trajectory"); -// builder.ExportOutput(c3_output_sender->get_output_port_c3_force(), "c3_forces"); + builder.ExportOutput( + c3_trajectory_generator->get_output_port_actor_trajectory(), + "actor_trajectory"); + // builder.ExportOutput(c3_trajectory_generator->get_output_port_object_trajectory(), + // "object_trajectory"); + // builder.ExportOutput(c3_output_sender->get_output_port_c3_force(), + // "c3_forces"); builder.BuildInto(this); this->set_name("FrankaC3Controller"); diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index f220bccafb..5889ec7215 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -1,10 +1,8 @@ #include -#include - -#include "examples/franka/diagrams/franka_c3_controller_diagram.h" -#include "examples/franka/diagrams/franka_osc_controller_diagram.h" +#include +#include #include #include #include @@ -20,33 +18,33 @@ #include #include #include -#include #include "common/eigen_utils.h" #include "common/find_resource.h" +#include "examples/franka/diagrams/franka_c3_controller_diagram.h" +#include "examples/franka/diagrams/franka_osc_controller_diagram.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "multibody/multibody_utils.h" -#include "systems/robot_lcm_systems.h" #include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" namespace dairlib { -using examples::controllers::FrankaOSCControllerDiagram; -using examples::controllers::FrankaC3ControllerDiagram; -using drake::systems::DiagramBuilder; +using drake::geometry::GeometrySet; +using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::Parser; -using drake::math::RigidTransform; -using drake::geometry::GeometrySet; +using drake::systems::DiagramBuilder; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::VectorXd; +using examples::controllers::FrankaC3ControllerDiagram; +using examples::controllers::FrankaOSCControllerDiagram; using systems::RobotInputReceiver; -using systems::SubvectorPassThrough; using systems::RobotOutputSender; -using Eigen::VectorXd; - +using systems::SubvectorPassThrough; int DoMain(int argc, char* argv[]) { drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); @@ -63,14 +61,14 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; /// OSC - auto osc_controller = builder.AddSystem("examples/franka/parameters/franka_osc_controller_params.yaml", - "examples/franka/parameters/lcm_channels_simulation.yaml", - &lcm); + auto osc_controller = builder.AddSystem( + "examples/franka/parameters/franka_osc_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); /// C3 plant - auto c3_controller = builder.AddSystem("examples/franka/parameters/franka_c3_controller_params.yaml", - "examples/franka/parameters/lcm_channels_simulation.yaml", - &lcm); + auto c3_controller = builder.AddSystem( + "examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); /// Sim Start double sim_dt = sim_params.dt; @@ -157,7 +155,12 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(plant, franka_index, false); auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.franka_state_channel, &lcm, 1.0 / sim_params.franka_publish_rate)); + lcm_channel_params.franka_state_channel, &lcm, + 1.0 / sim_params.franka_publish_rate)); + auto tray_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.tray_state_channel, &lcm, + 1.0 / sim_params.tray_publish_rate)); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); @@ -168,21 +171,33 @@ int DoMain(int argc, char* argv[]) { tray_state_sender->get_input_port_state()); // Diagram Connections - builder.Connect(osc_controller->get_output_port_robot_input(), passthrough->get_input_port()); - builder.Connect(c3_controller->get_output_port_mpc_plan(), osc_controller->get_input_port_end_effector_position()); - builder.Connect(c3_controller->get_output_port_mpc_plan(), osc_controller->get_input_port_end_effector_orientation()); - builder.Connect(c3_controller->get_output_port_mpc_plan(), osc_controller->get_input_port_end_effector_force()); - - - builder.Connect(franka_state_sender->get_output_port(), osc_controller->get_input_port_robot_state()); - builder.Connect(franka_state_sender->get_output_port(), c3_controller->get_input_port_robot_state()); - builder.Connect(tray_state_sender->get_output_port(), c3_controller->get_input_port_object_state()); - builder.Connect(radio_sub->get_output_port(), c3_controller->get_input_port_radio()); - builder.Connect(radio_sub->get_output_port(), osc_controller->get_input_port_radio()); + builder.Connect(osc_controller->get_output_port_robot_input(), + passthrough->get_input_port()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), + osc_controller->get_input_port_end_effector_position()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), + osc_controller->get_input_port_end_effector_orientation()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), + osc_controller->get_input_port_end_effector_force()); + + builder.Connect(franka_state_sender->get_output_port(), + osc_controller->get_input_port_robot_state()); + builder.Connect(franka_state_sender->get_output_port(), + c3_controller->get_input_port_robot_state()); + builder.Connect(tray_state_sender->get_output_port(), + c3_controller->get_input_port_object_state()); + builder.Connect(radio_sub->get_output_port(), + c3_controller->get_input_port_radio()); + builder.Connect(radio_sub->get_output_port(), + osc_controller->get_input_port_radio()); builder.Connect(*franka_state_sender, *state_pub); + builder.Connect(tray_state_sender->get_output_port(), + tray_state_pub->get_input_port()); builder.Connect(plant.get_state_output_port(franka_index), - franka_state_sender->get_input_port_state()); + franka_state_sender->get_input_port_state()); + builder.Connect(passthrough->get_output_port(), + plant.get_actuation_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 90e2080279..e53030e1cc 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -11,6 +11,8 @@ contact_model: 'anitescu' warm_start: true use_predicted_x0: true solve_time_filter_alpha: 0.95 +# set to 0 to publish as fast as possible +publish_frequency: 30 # Workspace Limits world_x_limits: [0.4, 0.6] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 50485f81ad..60c0177aea 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -9,7 +9,7 @@ visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 1 -visualize_drake_sim: false +visualize_drake_sim: true publish_efforts: true camera_pose: [[1.5, 0, 0.6], @@ -42,7 +42,7 @@ world_z_limits: [[0.35, 0.7], [0.35, 0.7]] dt: 0.0005 -realtime_rate: 1 +realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 71c895421f..c584e45e05 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -15,6 +15,7 @@ struct C3Options { bool warm_start; bool use_predicted_x0; double solve_time_filter_alpha; + double publish_frequency; std::vector world_x_limits; std::vector world_y_limits; @@ -73,6 +74,7 @@ struct C3Options { a->Visit(DRAKE_NVP(warm_start)); a->Visit(DRAKE_NVP(use_predicted_x0)); a->Visit(DRAKE_NVP(solve_time_filter_alpha)); + a->Visit(DRAKE_NVP(publish_frequency)); a->Visit(DRAKE_NVP(world_x_limits)); a->Visit(DRAKE_NVP(world_y_limits)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 675b1b2191..e31be5b7c3 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -2,7 +2,6 @@ #include -#include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" #include "solvers/c3_miqp.h" #include "solvers/c3_qp.h" @@ -29,8 +28,7 @@ using systems::TimestampedVector; namespace systems { C3Controller::C3Controller( - const drake::multibody::MultibodyPlant& plant, - C3Options c3_options) + const drake::multibody::MultibodyPlant& plant, C3Options c3_options) : plant_(plant), c3_options_(std::move(c3_options)), G_(std::vector(c3_options_.N, c3_options_.G)), @@ -153,7 +151,12 @@ C3Controller::C3Controller( .get_index(); plan_start_time_index_ = DeclareDiscreteState(1); x_pred_ = VectorXd::Zero(n_x_); - DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); + if (c3_options_.publish_frequency > 0) { + DeclarePeriodicDiscreteUpdateEvent(1 / c3_options_.publish_frequency, 0.0, + &C3Controller::ComputePlan); + } else { + DeclareForcedDiscreteUpdateEvent(&C3Controller::ComputePlan); + } } LCS C3Controller::CreatePlaceholderLCS() const { @@ -182,10 +185,8 @@ drake::systems::EventStatus C3Controller::ComputePlan( this->EvalAbstractInput(context, lcs_input_port_)->get_value(); drake::VectorX x_lcs = lcs_x->get_data(); - // TODO(yangwill): clean this up - // if (x_lcs.segment(n_q_, 3).norm() > 0.05 && c3_options_.use_predicted_x0 - // && !x_pred_.isZero()) { - if (x_lcs.segment(n_q_, 3).norm() > 0.01 && c3_options_.use_predicted_x0 && !x_pred_.isZero()) { + if (x_lcs.segment(n_q_, 3).norm() > 0.01 && c3_options_.use_predicted_x0 && + !x_pred_.isZero()) { x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, x_lcs[0] + 10 * dt_ * dt_); x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, @@ -245,7 +246,6 @@ void C3Controller::OutputC3Solution( const drake::systems::Context& context, C3Output::C3Solution* c3_solution) const { double t = context.get_discrete_state(plan_start_time_index_)[0]; - auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; From 1297fbf98e7fa24067de3f38039ebb38061a9e87 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 20 Feb 2024 14:57:20 -0500 Subject: [PATCH 656/758] making contexts consistent in lcs factory: --- examples/franka/diagrams/franka_c3_controller_diagram.cc | 2 +- examples/franka/franka_c3_controller.cc | 2 +- systems/controllers/c3/lcs_factory_system.cc | 8 ++++---- systems/controllers/c3/lcs_factory_system.h | 4 ++-- 4 files changed, 8 insertions(+), 8 deletions(-) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 26a3d34edb..e04c196a73 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -236,7 +236,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( robot_diagram_for_lcs_->plant(), robot_diagram_for_lcs_->mutable_plant_context( robot_diagram_root_context_.get()), - *plant_for_lcs_autodiff_, plant_for_lcs_autodiff_context_.get(), + *plant_for_lcs_autodiff_, *plant_for_lcs_autodiff_context_, contact_pairs, c3_options); auto controller = builder.AddSystem( robot_diagram_for_lcs_->plant(), c3_options); diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index ae2716da8f..08a188ba6d 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -250,7 +250,7 @@ int DoMain(int argc, char* argv[]) { target_state_mux->get_input_port(3)); auto lcs_factory = builder.AddSystem( plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, - plate_context_ad.get(), contact_pairs, c3_options); + *plate_context_ad, contact_pairs, c3_options); auto controller = builder.AddSystem( plant_for_lcs, c3_options); auto c3_trajectory_generator = diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 4e2e59c35b..b29f087597 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -26,7 +26,7 @@ LCSFactorySystem::LCSFactorySystem( const drake::multibody::MultibodyPlant& plant, drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, - drake::systems::Context* context_ad, + drake::systems::Context& context_ad, const std::vector> contact_geoms, C3Options c3_options) @@ -100,7 +100,7 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, plant_.SetPositionsAndVelocities(&context_, q_v_u.head(n_x_)); multibody::SetInputsIfNew(plant_, q_v_u.tail(n_u_), &context_); multibody::SetInputsIfNew(plant_ad_, q_v_u_ad.tail(n_u_), - context_ad_); + &context_ad_); solvers::ContactModel contact_model; if (c3_options_.contact_model == "stewart_and_trinkle") { contact_model = solvers::ContactModel::kStewartAndTrinkle; @@ -112,7 +112,7 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, double scale; std::tie(*output_lcs, scale) = LCSFactory::LinearizePlantToLCS( - plant_, context_, plant_ad_, *context_ad_, contact_pairs_, + plant_, context_, plant_ad_, context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); } @@ -142,7 +142,7 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context contact_points; *output = LCSFactory::ComputeContactJacobian( - plant_, context_, plant_ad_, *context_ad_, contact_pairs_, + plant_, context_, plant_ad_, context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); } diff --git a/systems/controllers/c3/lcs_factory_system.h b/systems/controllers/c3/lcs_factory_system.h index 36ca372ff2..a267d308e0 100644 --- a/systems/controllers/c3/lcs_factory_system.h +++ b/systems/controllers/c3/lcs_factory_system.h @@ -20,7 +20,7 @@ class LCSFactorySystem : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant, drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, - drake::systems::Context* context_ad, + drake::systems::Context& context_ad, const std::vector> contact_geoms, C3Options c3_options); @@ -54,7 +54,7 @@ class LCSFactorySystem : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context& context_; const drake::multibody::MultibodyPlant& plant_ad_; - drake::systems::Context* context_ad_; + drake::systems::Context& context_ad_; const std::vector> contact_pairs_; From 58d0a20b5cf76b1429c1e15d987482b0407b9201 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 29 Feb 2024 14:02:50 -0500 Subject: [PATCH 657/758] adding foward kinematics systems to work with mujoco mpc --- examples/franka/BUILD.bazel | 27 +++ examples/franka/forward_kinematics_for_lcs.cc | 162 ++++++++++++++++++ .../franka/parameters/franka_sim_params.yaml | 6 +- .../franka/systems/franka_kinematics_vector.h | 9 +- 4 files changed, 197 insertions(+), 7 deletions(-) create mode 100644 examples/franka/forward_kinematics_for_lcs.cc diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 0303809528..dbf09caab1 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -114,6 +114,33 @@ cc_binary( ], ) +cc_binary( + name = "forward_kinematics_for_lcs", + srcs = ["forward_kinematics_for_lcs.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_c3_controller_params", + ":franka_lcm_channels", + "//common", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers:c3_controller", + "//systems/controllers:lcs_factory_system", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", + "//systems/trajectory_optimization:c3_output_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "franka_visualizer", srcs = ["franka_visualizer.cc"], diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc new file mode 100644 index 0000000000..1521a18a5f --- /dev/null +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -0,0 +1,162 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/systems/c3_state_sender.h" +#include "examples/franka/systems/c3_trajectory_generator.h" +#include "examples/franka/systems/franka_kinematics.h" +#include "examples/franka/systems/plate_balancing_target.h" +#include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/c3/lcs_factory_system.h" +#include "systems/controllers/c3_controller.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/primitives/radio_parser.h" + +namespace dairlib { + +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; + +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; + +DEFINE_string(controller_settings, + "examples/franka/parameters/franka_c3_controller_params.yaml", + "Controller settings such as channels. Attempting to minimize " + "number of gflags"); +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + // load parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + FLAGS_controller_settings); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_params.osqp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + DiagramBuilder plant_builder; + + MultibodyPlant plant_franka(0.0); + Parser parser_franka(&plant_franka, nullptr); + parser_franka.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = + parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + + RigidTransform X_WI = RigidTransform::Identity(); + plant_franka.WeldFrames(plant_franka.world_frame(), + plant_franka.GetFrameByName("panda_link0"), X_WI); + + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + plant_franka.WeldFrames( + plant_franka.GetFrameByName("panda_link7"), + plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); + + plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + + /// + MultibodyPlant plant_tray(0.0); + Parser parser_tray(&plant_tray, nullptr); + parser_tray.AddModels(controller_params.tray_model); + plant_tray.Finalize(); + auto tray_context = plant_tray.CreateDefaultContext(); + + DiagramBuilder builder; + + auto tray_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.tray_state_channel, &lcm)); + auto franka_state_receiver = + builder.AddSystem(plant_franka); + auto tray_state_receiver = + builder.AddSystem(plant_tray); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_tray, tray_context.get(), + controller_params.end_effector_name, "tray", + controller_params.include_end_effector_orientation); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", + "tray_qx", "tray_qy", "tray_qz", "tray_x", + "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", + "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", + "tray_vz", "tray_vz", "tray_vz", + }; + auto c3_state_sender = + builder.AddSystem(3 + 7 + 3 + 6, state_names); + + builder.Connect(tray_state_sub->get_output_port(), + tray_state_receiver->get_input_port()); + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(tray_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_c3_controller")); + + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_state_receiver, + lcm_channel_params.franka_state_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + + LcmHandleSubscriptionsUntil( + &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 60c0177aea..b501fd5a16 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -51,6 +51,6 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], visualize_workspace: false visualize_pose_trace: true -visualize_center_of_mass_plan: false -visualize_c3_forces: true -visualize_c3_state: true +visualize_center_of_mass_plan: true +visualize_c3_forces: false +visualize_c3_state: false diff --git a/examples/franka/systems/franka_kinematics_vector.h b/examples/franka/systems/franka_kinematics_vector.h index 7b773f7f14..a3288c7d8e 100644 --- a/examples/franka/systems/franka_kinematics_vector.h +++ b/examples/franka/systems/franka_kinematics_vector.h @@ -41,10 +41,11 @@ class FrankaKinematicsVector : public TimestampedVector { } /// Constructs a OutputVector with the specified positions and velocities. - explicit FrankaKinematicsVector(const drake::VectorX& end_effector_positions, - const drake::VectorX& object_positions, - const drake::VectorX& end_effector_velocities, - const drake::VectorX& object_velocities) + explicit FrankaKinematicsVector( + const drake::VectorX& end_effector_positions, + const drake::VectorX& object_positions, + const drake::VectorX& end_effector_velocities, + const drake::VectorX& object_velocities) : FrankaKinematicsVector( end_effector_positions.size(), object_positions.size(), end_effector_velocities.size(), object_velocities.size()) { From ede8c977cf4dd893b52cf607e73d28272889d755 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 29 Feb 2024 17:01:42 -0500 Subject: [PATCH 658/758] removing mutables in c3 controller --- .../franka_c3_options_w_supports.yaml | 2 +- .../franka_osc_controller_params.yaml | 6 +- .../franka/parameters/franka_sim_params.yaml | 2 +- solvers/c3.cc | 13 +++- solvers/c3.h | 7 +- solvers/c3_output.cc | 9 +-- systems/controllers/c3_controller.cc | 76 ++++++++++--------- systems/controllers/c3_controller.h | 6 +- 8 files changed, 66 insertions(+), 55 deletions(-) diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index e53030e1cc..c6e6ac5b14 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -12,7 +12,7 @@ warm_start: true use_predicted_x0: true solve_time_filter_alpha: 0.95 # set to 0 to publish as fast as possible -publish_frequency: 30 +publish_frequency: 0 # Workspace Limits world_x_limits: [0.4, 0.6] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 92db6e9c4d..8db84b5236 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [1, 0, 0, - 0, 1, 0, - 0, 0, 1] + [0.01, 0, 0, + 0, 0.01, 0, + 0, 0, 0.01] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b501fd5a16..87d9affbdd 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -50,7 +50,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.55, 0.15, 0.515]] visualize_workspace: false -visualize_pose_trace: true +visualize_pose_trace: false visualize_center_of_mass_plan: true visualize_c3_forces: false visualize_c3_state: false diff --git a/solvers/c3.cc b/solvers/c3.cc index 832591db61..e984b572f2 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -101,11 +101,15 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, x_sol_ = std::make_unique>(); lambda_sol_ = std::make_unique>(); u_sol_ = std::make_unique>(); + w_sol_ = std::make_unique>(); + delta_sol_ = std::make_unique>(); for (int i = 0; i < N_; ++i) { z_sol_->push_back(Eigen::VectorXd::Zero(n_ + m_ + k_)); x_sol_->push_back(Eigen::VectorXd::Zero(n_)); lambda_sol_->push_back(Eigen::VectorXd::Zero(m_)); u_sol_->push_back(Eigen::VectorXd::Zero(k_)); + w_sol_->push_back(Eigen::VectorXd::Zero(n_ + m_ + k_)); + delta_sol_->push_back(Eigen::VectorXd::Zero(n_ + m_ + k_)); } for (int i = 0; i < N_ + 1; i++) { @@ -186,8 +190,11 @@ void C3::UpdateTarget(const std::vector& x_des) { } } -void C3::Solve(const VectorXd& x0, vector& delta, - vector& w) { +void C3::Solve(const VectorXd& x0) { + VectorXd delta_init = VectorXd::Zero(n_ + m_ + k_); + delta_init.head(n_) = x0; + std::vector delta(N_, delta_init); + std::vector w(N_, VectorXd::Zero(n_ + m_ + k_)); vector Gv = G_; for (int i = 0; i < N_; ++i) { @@ -213,6 +220,8 @@ void C3::Solve(const VectorXd& x0, vector& delta, A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); } + *w_sol_ = w; + *delta_sol_ = delta; } void C3::ADMMStep(const VectorXd& x0, vector* delta, diff --git a/solvers/c3.h b/solvers/c3.h index 03a2120200..bf1f7f0d84 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -40,8 +40,7 @@ class C3 { /// @param delta A pointer to the copy variable solution /// @param w A pointer to the scaled dual variable solution /// @return The first control action to take, u[0] - void Solve(const Eigen::VectorXd& x0, std::vector& delta, - std::vector& w); + void Solve(const Eigen::VectorXd& x0); /// Solve a single ADMM step /// @param x0 The initial state of the system @@ -103,6 +102,8 @@ class C3 { std::vector GetStateSolution() { return *x_sol_; } std::vector GetForceSolution() { return *lambda_sol_; } std::vector GetInputSolution() { return *u_sol_; } + std::vector GetDualDeltaSolution() { return *delta_sol_; } + std::vector GetDualWSolution() { return *w_sol_; } public: void UpdateLCS(const LCS& lcs); @@ -158,6 +159,8 @@ class C3 { std::unique_ptr> x_sol_; std::unique_ptr> lambda_sol_; std::unique_ptr> u_sol_; + std::unique_ptr> w_sol_; + std::unique_ptr> delta_sol_; }; } // namespace solvers diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc index 06ef761f50..d7b71f2027 100644 --- a/solvers/c3_output.cc +++ b/solvers/c3_output.cc @@ -42,29 +42,21 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { c3_intermediates.time_vec = c3_solution.time_vec; for (int i = 0; i < c3_solution.num_state_variables; ++i) { - // Temporary copy due to underlying data of Eigen::Matrix - // being column major VectorXf temp_row = c3_solution_.x_sol_.row(i); memcpy(c3_solution.x_sol[i].data(), temp_row.data(), sizeof(float) * knot_points); } for (int i = 0; i < c3_solution.num_contact_variables; ++i) { - // Temporary copy due to underlying data of Eigen::Matrix - // being column major VectorXf temp_row = c3_solution_.lambda_sol_.row(i); memcpy(c3_solution.lambda_sol[i].data(), temp_row.data(), sizeof(float) * knot_points); } for (int i = 0; i < c3_solution.num_input_variables; ++i) { - // Temporary copy due to underlying data of Eigen::Matrix - // being column major VectorXf temp_row = c3_solution_.u_sol_.row(i); memcpy(c3_solution.u_sol[i].data(), temp_row.data(), sizeof(float) * knot_points); } for (int i = 0; i < c3_intermediates.num_total_variables; ++i) { - // Temporary copy due to underlying data of Eigen::Matrix - // being column major VectorXf temp_delta_row = c3_intermediates_.delta_.row(i); VectorXf temp_w_row = c3_intermediates_.w_.row(i); memcpy(c3_intermediates.delta_sol[i].data(), temp_delta_row.data(), @@ -74,6 +66,7 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { } c3_output.c3_solution = c3_solution; + // Not assigning to reduce space c3_output.c3_intermediates = lcmt_c3_intermediates(); return c3_output; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index e31be5b7c3..784c8947cb 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -46,7 +46,6 @@ C3Controller::C3Controller( DRAKE_DEMAND(Q_.size() == N_ + 1); DRAKE_DEMAND(R_.size() == N_); - filtered_solve_time_ = 0.0; n_q_ = plant_.num_positions(); n_v_ = plant_.num_velocities(); n_u_ = plant_.num_actuators(); @@ -62,8 +61,6 @@ C3Controller::C3Controller( 2 * c3_options_.num_friction_directions * c3_options_.num_contacts; } VectorXd zeros = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); - w_ = std::vector(N_, zeros); - delta_ = std::vector(N_, zeros); n_u_ = plant_.num_actuators(); @@ -149,8 +146,11 @@ C3Controller::C3Controller( this->DeclareAbstractOutputPort("c3_intermediates", c3_intermediates, &C3Controller::OutputC3Intermediates) .get_index(); + plan_start_time_index_ = DeclareDiscreteState(1); - x_pred_ = VectorXd::Zero(n_x_); + x_pred_index_ = DeclareDiscreteState(n_x_); + filtered_solve_time_index_ = DeclareDiscreteState(1); + if (c3_options_.publish_frequency > 0) { DeclarePeriodicDiscreteUpdateEvent(1 / c3_options_.publish_frequency, 0.0, &C3Controller::ComputePlan); @@ -184,20 +184,23 @@ drake::systems::EventStatus C3Controller::ComputePlan( auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); drake::VectorX x_lcs = lcs_x->get_data(); + auto& x_pred = context.get_discrete_state(x_pred_index_).value(); + auto mutable_x_pred = discrete_state->get_mutable_value(x_pred_index_); + auto mutable_solve_time = discrete_state->get_mutable_value(filtered_solve_time_index_); if (x_lcs.segment(n_q_, 3).norm() > 0.01 && c3_options_.use_predicted_x0 && - !x_pred_.isZero()) { - x_lcs[0] = std::clamp(x_pred_[0], x_lcs[0] - 10 * dt_ * dt_, + !x_pred.isZero()) { + x_lcs[0] = std::clamp(x_pred[0], x_lcs[0] - 10 * dt_ * dt_, x_lcs[0] + 10 * dt_ * dt_); - x_lcs[1] = std::clamp(x_pred_[1], x_lcs[1] - 10 * dt_ * dt_, + x_lcs[1] = std::clamp(x_pred[1], x_lcs[1] - 10 * dt_ * dt_, x_lcs[1] + 10 * dt_ * dt_); - x_lcs[2] = std::clamp(x_pred_[2], x_lcs[2] - 10 * dt_ * dt_, + x_lcs[2] = std::clamp(x_pred[2], x_lcs[2] - 10 * dt_ * dt_, x_lcs[2] + 10 * dt_ * dt_); - x_lcs[n_q_ + 0] = std::clamp(x_pred_[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, + x_lcs[n_q_ + 0] = std::clamp(x_pred[n_q_ + 0], x_lcs[n_q_ + 0] - 10 * dt_, x_lcs[n_q_ + 0] + 10 * dt_); - x_lcs[n_q_ + 1] = std::clamp(x_pred_[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, + x_lcs[n_q_ + 1] = std::clamp(x_pred[n_q_ + 1], x_lcs[n_q_ + 1] - 10 * dt_, x_lcs[n_q_ + 1] + 10 * dt_); - x_lcs[n_q_ + 2] = std::clamp(x_pred_[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, + x_lcs[n_q_ + 2] = std::clamp(x_pred[n_q_ + 2], x_lcs[n_q_ + 2] - 10 * dt_, x_lcs[n_q_ + 2] + 10 * dt_); } @@ -224,21 +227,30 @@ drake::systems::EventStatus C3Controller::ComputePlan( c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); - VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); - delta_init.head(n_x_) = x_lcs; - std::vector delta(N_, delta_init); - std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); +// VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); +// delta_init.head(n_x_) = x_lcs; +// std::vector delta(N_, delta_init); +// std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - c3_->Solve(x_lcs, delta, w); + c3_->Solve(x_lcs); auto finish = std::chrono::high_resolution_clock::now(); - delta_ = delta; - w_ = w; auto elapsed = finish - start; double solve_time = std::chrono::duration_cast(elapsed).count() / 1e6; - filtered_solve_time_ = (1 - solve_time_filter_constant_) * solve_time + - (solve_time_filter_constant_)*filtered_solve_time_; + mutable_solve_time[0] = (1 - solve_time_filter_constant_) * solve_time + + solve_time_filter_constant_ * mutable_solve_time[0]; + + auto z_sol = c3_->GetFullSolution(); + if (mutable_solve_time[0] < N_ * dt_) { + int index = mutable_solve_time[0] / dt_; + double weight = ((index + 1) * dt_ - mutable_solve_time[0]) / dt_; + mutable_x_pred = weight * z_sol[index].segment(0, n_x_) + + (1 - weight) * z_sol[index + 1].segment(0, n_x_); + } else { + mutable_x_pred = z_sol[1].segment(0, n_x_); + } + return drake::systems::EventStatus::Succeeded(); } @@ -246,36 +258,32 @@ void C3Controller::OutputC3Solution( const drake::systems::Context& context, C3Output::C3Solution* c3_solution) const { double t = context.get_discrete_state(plan_start_time_index_)[0]; + double solve_time = context.get_discrete_state(filtered_solve_time_index_)[0]; + auto z_sol = c3_->GetFullSolution(); for (int i = 0; i < N_; i++) { - c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->time_vector_(i) = solve_time + t + i * dt_; c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); c3_solution->lambda_sol_.col(i) = z_sol[i].segment(n_x_, n_lambda_).cast(); c3_solution->u_sol_.col(i) = z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); } - - if (filtered_solve_time_ < N_ * dt_) { - int index = filtered_solve_time_ / dt_; - double weight = ((index + 1) * dt_ - filtered_solve_time_) / dt_; - x_pred_ = weight * z_sol[index].segment(0, n_x_) + - (1 - weight) * z_sol[index + 1].segment(0, n_x_); - } else { - x_pred_ = z_sol[1].segment(0, n_x_); - } } void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { + double solve_time = context.get_discrete_state(filtered_solve_time_index_)[0]; double t = context.get_discrete_state(plan_start_time_index_)[0] + - filtered_solve_time_; + solve_time; + auto delta = c3_->GetDualDeltaSolution(); + auto w = c3_->GetDualWSolution(); for (int i = 0; i < N_; i++) { - c3_intermediates->time_vector_(i) = t + i * c3_options_.dt; - c3_intermediates->w_.col(i) = w_[i].cast(); - c3_intermediates->delta_.col(i) = delta_[i].cast(); + c3_intermediates->time_vector_(i) = solve_time + t + i * dt_; + c3_intermediates->w_.col(i) = delta[i].cast(); + c3_intermediates->delta_.col(i) = w[i].cast(); } } diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 125ad37f25..681c7293f0 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -91,13 +91,11 @@ class C3Controller : public drake::systems::LeafSystem { double dt_; mutable std::unique_ptr c3_; - mutable std::vector delta_; - mutable std::vector w_; - mutable double filtered_solve_time_; - mutable Eigen::VectorXd x_pred_; double solve_time_filter_constant_; drake::systems::DiscreteStateIndex plan_start_time_index_; + drake::systems::DiscreteStateIndex x_pred_index_; + drake::systems::DiscreteStateIndex filtered_solve_time_index_; std::vector Q_; std::vector R_; std::vector G_; From dac266ed489209969cacba0b8c292ac726615c61 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 29 Feb 2024 17:07:30 -0500 Subject: [PATCH 659/758] small cleanup of c3_controller --- systems/controllers/c3_controller.cc | 9 ++------- systems/controllers/c3_controller.h | 1 - 2 files changed, 2 insertions(+), 8 deletions(-) diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 784c8947cb..0092781c21 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -87,7 +87,7 @@ C3Controller::C3Controller( c3_->SetOsqpSolverOptions(solver_options_); - // Set actor bounds + // Set actor bounds, TODO(yangwill): move this out of here because it is task specific for (int i : vector({0})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; @@ -226,13 +226,8 @@ drake::systems::EventStatus C3Controller::ComputePlan( c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); - -// VectorXd delta_init = VectorXd::Zero(n_x_ + n_lambda_ + n_u_); -// delta_init.head(n_x_) = x_lcs; -// std::vector delta(N_, delta_init); -// std::vector w(N_, VectorXd::Zero(n_x_ + n_lambda_ + n_u_)); - c3_->Solve(x_lcs); + auto finish = std::chrono::high_resolution_clock::now(); auto elapsed = finish - start; double solve_time = diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index 681c7293f0..f9b17bb08d 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -22,7 +22,6 @@ namespace dairlib { namespace systems { -/// Outputs a lcmt_timestamped_saved_traj class C3Controller : public drake::systems::LeafSystem { public: explicit C3Controller( From 555b374d27c5bcf5075cbfcb4084ecd1e2f43fbe Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 11 Mar 2024 14:44:20 -0400 Subject: [PATCH 660/758] attempting to get full diagram to succeed, radio parser doesn't seem to work --- .../diagrams/franka_c3_controller_diagram.cc | 22 -------------- .../diagrams/franka_c3_controller_diagram.h | 10 +------ .../diagrams/franka_osc_controller_diagram.cc | 26 ++++------------- .../diagrams/franka_osc_controller_diagram.h | 15 ++++------ examples/franka/franka_visualizer.cc | 1 - examples/franka/full_diagram.cc | 29 ++++++++++--------- .../franka_osc_controller_params.yaml | 6 ++-- .../systems/end_effector_force_trajectory.cc | 2 +- .../lcm_trajectory_systems.cc | 21 +++++++------- .../lcm_visualization_systems.cc | 12 ++++++-- .../visualization/lcm_visualization_systems.h | 3 +- 11 files changed, 53 insertions(+), 94 deletions(-) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index e04c196a73..2e7ecfab5f 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -103,15 +103,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plant_tray_->Finalize(); plant_tray_context_ = plant_tray_->CreateDefaultContext(); - /// - // plant_for_lcs_ = - // std::make_unique>(0.0); - // AddMultibodyPlantSceneGraph(&plant_builder, - // std::make_unique>(0.0), - // scene_graph_lcs_); plant_for_lcs_, scene_graph_lcs_ = - // AddMultibodyPlantSceneGraph(&plant_builder, 0.0); drake::planning::RobotDiagramBuilder lcs_diagram_builder; - // lcs_diagram_builder.plant() lcs_diagram_builder.parser().SetAutoRenaming(true); lcs_diagram_builder.parser().AddModels(controller_params.plate_model); @@ -151,13 +143,6 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plant_for_lcs_autodiff_ = drake::systems::System::ToAutoDiffXd( robot_diagram_for_lcs_->plant()); - // auto plant_diagram = plant_builder.Build(); - // auto plant_diagram = plant_lcs_builder_->Build(); - // plant_for_lcs_diagram_context_ = - // plant_diagram->CreateDefaultContext(); - // plant_for_lcs_context_ = - // std::move(plant_diagram->GetMutableSubsystemContext( - // plant_for_lcs_, plant_for_lcs_diagram_context_.get())); robot_diagram_root_context_ = robot_diagram_for_lcs_->CreateDefaultContext(); plant_for_lcs_autodiff_context_ = plant_for_lcs_autodiff_->CreateDefaultContext(); @@ -269,8 +254,6 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plate_balancing_target->get_input_port_tray_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), controller->get_input_port_lcs_state()); - // builder.Connect(radio_sub->get_output_port(), - // controller->get_input_port_radio()); builder.Connect(reduced_order_model_receiver->get_output_port(), lcs_factory->get_input_port_lcs_state()); builder.Connect(radio_to_vector->get_output_port(), @@ -339,14 +322,9 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( builder.ExportOutput( c3_trajectory_generator->get_output_port_actor_trajectory(), "actor_trajectory"); - // builder.ExportOutput(c3_trajectory_generator->get_output_port_object_trajectory(), - // "object_trajectory"); - // builder.ExportOutput(c3_output_sender->get_output_port_c3_force(), - // "c3_forces"); builder.BuildInto(this); this->set_name("FrankaC3Controller"); - DrawAndSaveDiagramGraph(*this); } } // namespace controllers diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.h b/examples/franka/diagrams/franka_c3_controller_diagram.h index 215f612a83..09259d5127 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.h +++ b/examples/franka/diagrams/franka_c3_controller_diagram.h @@ -50,24 +50,16 @@ class FrankaC3ControllerDiagram : public drake::systems::Diagram { private: drake::multibody::MultibodyPlant* plant_franka_; drake::multibody::MultibodyPlant* plant_tray_; -// std::unique_ptr> plant_for_lcs_; -// std::unique_ptr> scene_graph_lcs_; // Storage for the diagram and its plant and scene graph. // After Build(), the `builder_` is set to nullptr. std::unique_ptr> robot_diagram_for_lcs_; + std::unique_ptr> robot_diagram_root_context_; -// std::unique_ptr> plant_lcs_builder_; -// drake::multibody::AddMultibodyPlantSceneGraphResult pair_; -// drake::multibody::MultibodyPlant& plant_for_lcs_; -// drake::geometry::SceneGraph& scene_graph_lcs_; std::unique_ptr> plant_for_lcs_diagram_context_; -// drake::multibody::MultibodyPlant& plant_for_lcs_; -// drake::geometry::SceneGraph& scene_graph_lcs_; std::unique_ptr> plant_for_lcs_autodiff_; std::unique_ptr> plant_franka_context_; std::unique_ptr> plant_tray_context_; -// drake::systems::Context& plant_for_lcs_context_; std::unique_ptr> plant_for_lcs_autodiff_context_; const drake::systems::InputPortIndex franka_state_port_ = diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index fb1b00f7f8..df567e2162 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -101,9 +101,6 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( plant_context_ = plant_->CreateDefaultContext(); auto state_receiver = builder.AddSystem(*plant_); -// auto end_effector_trajectory_receiver = -// builder.AddSystem( -// drake::systems::PassThrough(drake::Value{})); auto end_effector_position_receiver = builder.AddSystem( "end_effector_position_target"); @@ -228,16 +225,8 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( osc_command_pub->get_input_port()); builder.Connect(osc->get_output_port_osc_command(), osc_command_sender->get_input_port(0)); - builder.Connect(state_receiver->get_output_port(0), osc->get_input_port_robot_output()); -// builder.Connect(end_effector_trajectory_receiver->get_output_port(), -// end_effector_position_receiver->get_input_port_trajectory()); -// builder.Connect(end_effector_trajectory_receiver->get_output_port(), -// end_effector_force_receiver->get_input_port_trajectory()); -// builder.Connect( -// end_effector_trajectory_receiver->get_output_port(), -// end_effector_orientation_receiver->get_input_port_trajectory()); builder.Connect(end_effector_position_receiver->get_output_port(0), end_effector_trajectory->get_input_port_trajectory()); builder.Connect( @@ -254,23 +243,18 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( osc->get_input_port_tracking_data("end_effector_force")); // Publisher connections - builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); - builder.ExportInput(end_effector_position_receiver->get_input_port(), + franka_state_port_ = builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); + end_effector_position_port_ = builder.ExportInput(end_effector_position_receiver->get_input_port(), "end_effector_position: lcmt_timestamped_trajectory"); - builder.ExportInput(end_effector_orientation_receiver->get_input_port(), + end_effector_orientation_port_ = builder.ExportInput(end_effector_orientation_receiver->get_input_port(), "end_effector_orientation: lcmt_timestamped_trajectory"); - builder.ExportInput(end_effector_force_receiver->get_input_port(), + end_effector_force_port_ = builder.ExportInput(end_effector_force_receiver->get_input_port(), "end_effector_force: lcmt_timestamped_trajectory"); - builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); + radio_port_ = builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); builder.ExportOutput(osc->get_output_port_osc_command(), "robot_input"); - // builder.ExportOutput(c3_trajectory_generator->get_output_port_object_trajectory(), - // "object_trajectory"); - // builder.ExportOutput(c3_output_sender->get_output_port_c3_force(), - // "c3_forces"); builder.BuildInto(this); this->set_name("FrankaOSCController"); - DrawAndSaveDiagramGraph(*this); } } // namespace controllers diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.h b/examples/franka/diagrams/franka_osc_controller_diagram.h index 19c8cadaf6..4c5a48e058 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.h +++ b/examples/franka/diagrams/franka_osc_controller_diagram.h @@ -62,16 +62,11 @@ class FrankaOSCControllerDiagram : public drake::systems::Diagram { drake::multibody::MultibodyPlant* plant_; std::unique_ptr> plant_context_; - const drake::systems::InputPortIndex franka_state_port_ = - drake::systems::InputPortIndex(0); - const drake::systems::InputPortIndex end_effector_position_port_ = - drake::systems::InputPortIndex(1); - const drake::systems::InputPortIndex end_effector_orientation_port_ = - drake::systems::InputPortIndex(2); - const drake::systems::InputPortIndex end_effector_force_port_ = - drake::systems::InputPortIndex(3); - const drake::systems::InputPortIndex radio_port_ = - drake::systems::InputPortIndex(4); + drake::systems::InputPortIndex franka_state_port_; + drake::systems::InputPortIndex end_effector_position_port_; + drake::systems::InputPortIndex end_effector_orientation_port_; + drake::systems::InputPortIndex end_effector_force_port_; + drake::systems::InputPortIndex radio_port_; const drake::systems::OutputPortIndex robot_input_port_ = drake::systems::OutputPortIndex(0); }; diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index c143738611..6f2f883cc7 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -80,7 +80,6 @@ int do_main(int argc, char* argv[]) { parser.SetAutoRenaming(true); drake::multibody::ModelInstanceIndex franka_index = parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; - drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 5889ec7215..9f6b665c7d 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -1,4 +1,5 @@ +#include #include #include @@ -29,7 +30,6 @@ #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" - namespace dairlib { using drake::geometry::GeometrySet; @@ -60,16 +60,6 @@ int DoMain(int argc, char* argv[]) { DiagramBuilder builder; - /// OSC - auto osc_controller = builder.AddSystem( - "examples/franka/parameters/franka_osc_controller_params.yaml", - "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); - - /// C3 plant - auto c3_controller = builder.AddSystem( - "examples/franka/parameters/franka_c3_controller_params.yaml", - "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); - /// Sim Start double sim_dt = sim_params.dt; auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); @@ -145,6 +135,17 @@ int DoMain(int argc, char* argv[]) { {"paddle", paddle_geom_set}, {"tray", tray_collision_set}); plant.Finalize(); + + /// OSC + auto osc_controller = builder.AddSystem( + "examples/franka/parameters/franka_osc_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); + + /// C3 plant + auto c3_controller = builder.AddSystem( + "examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); + /* -------------------------------------------------------------------------------------------*/ auto passthrough = builder.AddSystem( osc_controller->get_output_port_robot_input().size(), 0, @@ -156,11 +157,13 @@ int DoMain(int argc, char* argv[]) { auto state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.franka_state_channel, &lcm, - 1.0 / sim_params.franka_publish_rate)); + drake::systems::TriggerTypeSet( + {drake::systems::TriggerType::kForced}))); auto tray_state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, &lcm, - 1.0 / sim_params.tray_publish_rate)); + drake::systems::TriggerTypeSet( + {drake::systems::TriggerType::kForced}))); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 8db84b5236..92db6e9c4d 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -39,9 +39,9 @@ elbow_kp: 200 elbow_kd: 10 EndEffectorW: - [0.01, 0, 0, - 0, 0.01, 0, - 0, 0, 0.01] + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] EndEffectorKp: [ 200, 0, 0, 0, 200, 0, diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index f8dcf18605..0c6d337683 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -33,7 +33,7 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator() { radio_port_ = this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) .get_index(); - controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Ones(1)); DeclareForcedDiscreteUpdateEvent( &EndEffectorForceTrajectoryGenerator::DiscreteVariableUpdate); PiecewisePolynomial empty_pp_traj(Vector3d::Zero()); diff --git a/systems/trajectory_optimization/lcm_trajectory_systems.cc b/systems/trajectory_optimization/lcm_trajectory_systems.cc index 92b4aed274..6b097023dd 100644 --- a/systems/trajectory_optimization/lcm_trajectory_systems.cc +++ b/systems/trajectory_optimization/lcm_trajectory_systems.cc @@ -59,17 +59,16 @@ void LcmTrajectoryReceiver::OutputTrajectory( const auto& trajectory_block = lcm_traj.GetTrajectory(trajectory_name_); *casted_traj = PiecewisePolynomial::FirstOrderHold( trajectory_block.time_vector, trajectory_block.datapoints); -// if (trajectory_block.datapoints.rows() == 3) { -// *casted_traj = PiecewisePolynomial::FirstOrderHold( -// trajectory_block.time_vector, trajectory_block.datapoints); -// // *casted_traj = PiecewisePolynomial::ZeroOrderHold( -// // trajectory_block.time_vector, trajectory_block.datapoints); -// } else { -// -//// *casted_traj = PiecewisePolynomial::CubicHermite( -//// trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), -//// trajectory_block.datapoints.bottomRows(3)); -// } + if (trajectory_block.datapoints.rows() == 3) { + *casted_traj = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints); + } else { + *casted_traj = PiecewisePolynomial::FirstOrderHold( + trajectory_block.time_vector, trajectory_block.datapoints.topRows(trajectory_block.datapoints.rows() / 2)); +// *casted_traj = PiecewisePolynomial::CubicHermite( +// trajectory_block.time_vector, trajectory_block.datapoints.topRows(3), +// trajectory_block.datapoints.bottomRows(3)); + } } else { *casted_traj = PiecewisePolynomial(Vector3d::Zero()); } diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index af79c70683..326416fecf 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -81,15 +81,23 @@ LcmPoseDrawer::LcmPoseDrawer( const std::shared_ptr& meshcat, const std::string& model_file, const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, int num_poses) + const std::string& orientation_trajectory_name, int num_poses, + bool add_transparency) : meshcat_(meshcat), translation_trajectory_name_(translation_trajectory_name), orientation_trajectory_name_(orientation_trajectory_name), N_(num_poses) { this->set_name("LcmPoseDrawer: " + translation_trajectory_name); + Eigen::VectorXd alpha_scale; + if (add_transparency){ + alpha_scale = .0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4); + }else{ + alpha_scale = 1.0 * VectorXd::Ones(N_ - 1); + } + multipose_visualizer_ = std::make_unique( - model_file, N_ - 1, 1.0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4), "", meshcat); + model_file, N_ - 1, alpha_scale, "", meshcat); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index 4525ff78f4..7d9a7854e9 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -59,7 +59,8 @@ class LcmPoseDrawer : public drake::systems::LeafSystem { const std::string& model_file, const std::string& translation_trajectory_name, const std::string& orientation_trajectory_name, - int num_poses = 5); + int num_poses = 5, + bool add_transparency = true); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_input_port_); From 1986fdfa0ef28d1cc96550aef9c1470cf8607753 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 13 Mar 2024 15:23:47 -0400 Subject: [PATCH 661/758] small tweaks --- examples/franka/franka_sim.cc | 37 +++++++++---------- examples/franka/franka_visualizer.cc | 4 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../lcm_visualization_systems.cc | 2 +- 4 files changed, 22 insertions(+), 23 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index b4a5f6602f..1989d62578 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -89,24 +89,22 @@ int DoMain(int argc, char* argv[]) { // we WANT to model collisions between link5 and the supports const drake::geometry::GeometrySet& franka_geom_set = - plant.CollectRegisteredGeometries( - {&plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), -// &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link7"), - &plant.GetBodyByName("plate"), - &plant.GetBodyByName("panda_link8")}); + plant.CollectRegisteredGeometries({&plant.GetBodyByName("panda_link0"), + &plant.GetBodyByName("panda_link1"), + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4")}); if (sim_params.scene_index > 0) { drake::multibody::ModelInstanceIndex left_support_index = parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( FindResourceOrThrow(sim_params.right_support_model))[0]; RigidTransform T_S1_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.left_support_orientation), sim_params.left_support_position); + drake::math::RollPitchYaw(sim_params.left_support_orientation), + sim_params.left_support_position); RigidTransform T_S2_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.right_support_orientation), sim_params.right_support_position); + drake::math::RollPitchYaw(sim_params.right_support_orientation), + sim_params.right_support_position); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_S1_W); @@ -124,13 +122,13 @@ int DoMain(int argc, char* argv[]) { const drake::geometry::GeometrySet& franka_only_geom_set = plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link8"), - }); + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link8"), + }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( @@ -181,7 +179,8 @@ int DoMain(int argc, char* argv[]) { q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; - q.tail(plant.num_positions(tray_index)) = sim_params.q_init_plate[sim_params.scene_index]; + q.tail(plant.num_positions(tray_index)) = + sim_params.q_init_plate[sim_params.scene_index]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 6f2f883cc7..9a60a75cc2 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -197,8 +197,8 @@ int do_main(int argc, char* argv[]) { "object_position_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); - trajectory_drawer_actor->SetNumSamples(5); - trajectory_drawer_object->SetNumSamples(5); + trajectory_drawer_actor->SetNumSamples(40); + trajectory_drawer_object->SetNumSamples(40); builder.Connect(trajectory_sub_actor->get_output_port(), trajectory_drawer_actor->get_input_port_trajectory()); builder.Connect(trajectory_sub_object->get_output_port(), diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 87d9affbdd..04b23698fa 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -46,7 +46,7 @@ realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], - [1, 0, 0, 0, 0.7, 0.00, 0.515], + [1, 0, 0, 0, 0.7, 0.00, 0.485], [1, 0, 0, 0, 0.55, 0.15, 0.515]] visualize_workspace: false diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index 326416fecf..37d6c4c86a 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -91,7 +91,7 @@ LcmPoseDrawer::LcmPoseDrawer( Eigen::VectorXd alpha_scale; if (add_transparency){ - alpha_scale = .0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4); + alpha_scale = 1.0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4); }else{ alpha_scale = 1.0 * VectorXd::Ones(N_ - 1); } From f40059d2b653c43069463c85e8b6c5dbe00741dc Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 14 Mar 2024 11:37:38 -0400 Subject: [PATCH 662/758] giving fk for mpc state responsibility for also publishing target state --- examples/franka/forward_kinematics_for_lcs.cc | 57 +++++++++++++++++-- 1 file changed, 51 insertions(+), 6 deletions(-) diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index 1521a18a5f..1e878634a4 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -22,10 +22,10 @@ #include "systems/controllers/c3/lcs_factory_system.h" #include "systems/controllers/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/primitives/radio_parser.h" namespace dairlib { @@ -118,10 +118,11 @@ int DoMain(int argc, char* argv[]) { plant_franka, franka_context.get(), plant_tray, tray_context.get(), controller_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); - auto c3_actual_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_actual_state_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + auto radio_to_vector = builder.AddSystem(); + std::vector state_names = { "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", "tray_qx", "tray_qy", "tray_qz", "tray_x", @@ -131,19 +132,63 @@ int DoMain(int argc, char* argv[]) { }; auto c3_state_sender = builder.AddSystem(3 + 7 + 3 + 6, state_names); + auto plate_balancing_target = + builder.AddSystem( + plant_tray, controller_params.end_effector_thickness, + controller_params.near_target_threshold); + plate_balancing_target->SetRemoteControlParameters( + controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto tray_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(tray_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(3)); + + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + builder.Connect(*radio_sub, *radio_to_vector); + builder.Connect(tray_state_receiver->get_output_port(), + plate_balancing_target->get_input_port_tray_state()); + builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(plate_balancing_target->get_output_port_tray_target(), + target_state_mux->get_input_port(1)); builder.Connect(tray_state_sub->get_output_port(), tray_state_receiver->get_input_port()); + builder.Connect(radio_to_vector->get_output_port(), + plate_balancing_target->get_input_port_radio()); builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); builder.Connect(tray_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_object_state()); builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), c3_state_sender->get_input_port_actual_state()); + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), c3_actual_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_c3_controller")); + owned_diagram->set_name(("franka_forward_kinematics")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( From bb42f3998f17059d23692d95c77e6697ecdf4b34 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 20 Mar 2024 13:41:05 -0400 Subject: [PATCH 663/758] working on closed loop sim --- .../tray_balance_study/generate_dataset.py | 41 +++++ bindings/pydairlib/franka/BUILD.bazel | 54 +++++++ bindings/pydairlib/franka/__init__.py | 2 + bindings/pydairlib/franka/controllers_py.cc | 65 ++++++++ examples/franka/diagrams/BUILD.bazel | 16 +- .../diagrams/franka_c3_controller_diagram.cc | 77 +++++---- .../diagrams/franka_osc_controller_diagram.cc | 1 - .../franka/diagrams/franka_sim_diagram.cc | 146 ++++++++++++++++++ examples/franka/diagrams/franka_sim_diagram.h | 55 +++++++ examples/franka/diagrams/full_diagram.cc | 146 ++++++++++++++++++ examples/franka/franka_sim.cc | 1 - .../franka_c3_options_w_supports.yaml | 2 +- 12 files changed, 563 insertions(+), 43 deletions(-) create mode 100644 bindings/pydairlib/analysis/tray_balance_study/generate_dataset.py create mode 100644 bindings/pydairlib/franka/BUILD.bazel create mode 100644 bindings/pydairlib/franka/__init__.py create mode 100644 bindings/pydairlib/franka/controllers_py.cc create mode 100644 examples/franka/diagrams/franka_sim_diagram.cc create mode 100644 examples/franka/diagrams/franka_sim_diagram.h create mode 100644 examples/franka/diagrams/full_diagram.cc diff --git a/bindings/pydairlib/analysis/tray_balance_study/generate_dataset.py b/bindings/pydairlib/analysis/tray_balance_study/generate_dataset.py new file mode 100644 index 0000000000..0ea6b5dd01 --- /dev/null +++ b/bindings/pydairlib/analysis/tray_balance_study/generate_dataset.py @@ -0,0 +1,41 @@ +import numpy as np +import os +import datetime +def gather_theta_batched_branin_data(n_datapoints, + batch_size, + gains_to_randomize, + thetas_to_randomize, + high_level_folder, + params_t=BraninFnParamsTrain): + + assert n_datapoints == int(n_datapoints / batch_size) * batch_size + + num_batches = int(n_datapoints / (batch_size)) + # Each batch is associated with a single set of system intrinsic parameters + intrinsics = np.zeros((num_batches, len(thetas_to_randomize))) + # for each parameter vector, generate $batch_size random gains to evaluate + gains_to_test = np.zeros((num_batches, batch_size, len(gains_to_randomize))) + + subfolder = "branin_data_" + datetime.now().strftime("%b_%d_%Y_%H%M") + "/" + if not os.path.exists(os.path.join(high_level_folder, subfolder)): + os.makedirs(os.path.join(high_level_folder, subfolder), exist_ok=True) + + with h5py.File(os.path.join(high_level_folder, subfolder, "dataset.hdf5"), 'w') as f: + # intrinsic vectors don't actually get used anywhere, but good to save for bookkeeping + f.create_dataset("intrinsics", shape=intrinsics.shape) + f.create_dataset("gains", shape=gains_to_test.shape) + # this system only has 1 performance metric, but in principle this could be any number + f.create_dataset("metrics", shape=(num_batches, batch_size, 1)) + for batch in range(num_batches): + # Generate a random intrinsic vector for this batch + batch_intrinsic_obj = params_t.generate_random(thetas_to_randomize) + f["intrinsics"][batch,...] = batch_intrinsic_obj.get_list() + robot = Branin(batch_intrinsic_obj, gains_to_randomize) + for point in range(batch_size): + # generate a random gain vector + gain = BraninInputs.generate_random(gains_to_randomize).get_list()[gains_to_randomize] + # run the simulation and obtain the performance metrics + metric = robot.evaluate_x(gain) + f["metrics"][batch,point] = metric + f["gains"][batch,point] = gain + print(f"finished batch {batch}") \ No newline at end of file diff --git a/bindings/pydairlib/franka/BUILD.bazel b/bindings/pydairlib/franka/BUILD.bazel new file mode 100644 index 0000000000..7cac5cb5fa --- /dev/null +++ b/bindings/pydairlib/franka/BUILD.bazel @@ -0,0 +1,54 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") + +package(default_visibility = ["//visibility:public"]) + +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) + +pybind_py_library( + name = "controllers_py", + cc_deps = [ + "//examples/franka/diagrams:franka_c3_controller_diagram", + "//examples/franka/diagrams:franka_osc_controller_diagram", + "@drake//:drake_shared_library", + ], + cc_so_name = "controllers", + cc_srcs = ["controllers_py.cc"], + py_deps = [ + "@drake//bindings/pydrake", + ":module_py", + ], + py_imports = ["."], +) + +# This determines how `PYTHONPATH` is configured, and how to install the +# bindings. +PACKAGE_INFO = get_pybind_package_info("//bindings") + +py_library( + name = "module_py", + srcs = [ + "__init__.py", + ], + imports = PACKAGE_INFO.py_imports, + deps = [ + "//bindings/pydairlib:module_py", + ], +) + +PY_LIBRARIES = [ + ":controllers_py", +] + +# Package roll-up (for Bazel dependencies). +py_library( + name = "franka", + imports = PACKAGE_INFO.py_imports, + deps = PY_LIBRARIES, +) diff --git a/bindings/pydairlib/franka/__init__.py b/bindings/pydairlib/franka/__init__.py new file mode 100644 index 0000000000..b889fc0649 --- /dev/null +++ b/bindings/pydairlib/franka/__init__.py @@ -0,0 +1,2 @@ +# Importing everything in this directory to this package +from .franka import * \ No newline at end of file diff --git a/bindings/pydairlib/franka/controllers_py.cc b/bindings/pydairlib/franka/controllers_py.cc new file mode 100644 index 0000000000..dda6871c74 --- /dev/null +++ b/bindings/pydairlib/franka/controllers_py.cc @@ -0,0 +1,65 @@ +#include +#include + +#include "examples/franka/diagrams/franka_c3_controller_diagram.h" +#include "examples/franka/diagrams/franka_osc_controller_diagram.h" + +namespace py = pybind11; + +namespace dairlib { +namespace pydairlib { + +using examples::controllers::FrankaC3ControllerDiagram; +using examples::controllers::FrankaOSCControllerDiagram; + +PYBIND11_MODULE(controllers, m) { + m.doc() = "Binding controller factories for plate balancing demo"; + + using py_rvp = py::return_value_policy; + + py::class_>( + m, "FrankaOSCControllerDiagram") + .def(py::init(), + py::arg("controller_settings"), py::arg("lcm_channels"), + py::arg("lcm")) + .def("FrankaOSCControllerDiagram", + &FrankaOSCControllerDiagram::get_input_port_robot_state, + py_rvp::reference_internal) + .def("get_input_port_end_effector_position", + &FrankaOSCControllerDiagram::get_input_port_end_effector_position, + py_rvp::reference_internal) + .def("get_input_port_end_effector_orientation", + &FrankaOSCControllerDiagram::get_input_port_end_effector_orientation, + py_rvp::reference_internal) + .def("get_input_port_end_effector_force", + &FrankaOSCControllerDiagram::get_input_port_end_effector_force, + py_rvp::reference_internal) + .def("get_input_port_radio", + &FrankaOSCControllerDiagram::get_input_port_radio, + py_rvp::reference_internal) + .def("get_output_port_robot_input", + &FrankaOSCControllerDiagram::get_output_port_robot_input, + py_rvp::reference_internal); + + py::class_>( + m, "FrankaC3ControllerDiagram") + .def(py::init(), + py::arg("controller_settings"), py::arg("lcm_channels"), + py::arg("lcm")) + .def("get_input_port_robot_state", + &FrankaC3ControllerDiagram::get_input_port_robot_state, + py_rvp::reference_internal) + .def("get_input_port_object_state", + &FrankaC3ControllerDiagram::get_input_port_object_state, + py_rvp::reference_internal) + .def("get_input_port_radio", + &FrankaC3ControllerDiagram::get_input_port_radio, + py_rvp::reference_internal) + .def("get_output_port_mpc_plan", + &FrankaC3ControllerDiagram::get_output_port_mpc_plan, + py_rvp::reference_internal); +} +} // namespace pydairlib +} // namespace dairlib \ No newline at end of file diff --git a/examples/franka/diagrams/BUILD.bazel b/examples/franka/diagrams/BUILD.bazel index 6590ea82c3..4a59891304 100644 --- a/examples/franka/diagrams/BUILD.bazel +++ b/examples/franka/diagrams/BUILD.bazel @@ -38,10 +38,24 @@ cc_library( "//systems:system_utils", "//systems/controllers", "//systems/controllers/osc:operational_space_control", - "//systems/framework:lcm_driven_loop", "//systems/primitives:radio_parser", "//systems/trajectory_optimization:lcm_trajectory_systems", "@drake//:drake_shared_library", "@gflags", ], ) + +cc_library( + name = "franka_sim_diagram", + srcs = ["franka_sim_diagram.cc"], + hdrs = ["franka_sim_diagram.h"], + deps = [ + "//common", + "//examples/franka:franka_lcm_channels", + "//examples/franka:franka_sim_params", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "@drake//:drake_shared_library", + "@gflags", + ], +) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 2e7ecfab5f..4e853a4f3f 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -41,7 +41,6 @@ using dairlib::solvers::LCSFactory; using drake::SortedPair; using drake::geometry::GeometryId; using drake::math::RigidTransform; -using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; using drake::systems::DiagramBuilder; @@ -221,8 +220,8 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( robot_diagram_for_lcs_->plant(), robot_diagram_for_lcs_->mutable_plant_context( robot_diagram_root_context_.get()), - *plant_for_lcs_autodiff_, *plant_for_lcs_autodiff_context_, - contact_pairs, c3_options); + *plant_for_lcs_autodiff_, *plant_for_lcs_autodiff_context_, contact_pairs, + c3_options); auto controller = builder.AddSystem( robot_diagram_for_lcs_->plant(), c3_options); auto c3_trajectory_generator = @@ -276,42 +275,42 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( // publisher connections DRAKE_DEMAND(c3_options.publish_frequency > 0); - auto actor_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_actor_channel, lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); - auto object_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_object_channel, lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); - auto c3_output_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_debug_output_channel, lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); - auto c3_target_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_target_state_channel, lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); - auto c3_actual_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_actual_state_channel, lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); - auto c3_forces_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_force_channel, lcm, - TriggerTypeSet({TriggerType::kPeriodic}), 1 / c3_options.publish_frequency)); - builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), - actor_trajectory_sender->get_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), - object_trajectory_sender->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_target_c3_state(), - c3_target_state_publisher->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), - c3_actual_state_publisher->get_input_port()); - builder.Connect(c3_output_sender->get_output_port_c3_debug(), - c3_output_publisher->get_input_port()); - builder.Connect(c3_output_sender->get_output_port_c3_force(), - c3_forces_publisher->get_input_port()); +// auto actor_trajectory_sender = builder.AddSystem( +// LcmPublisherSystem::Make( +// lcm_channel_params.c3_actor_channel, lcm, +// TriggerTypeSet({TriggerType::kForced}))); +// auto object_trajectory_sender = builder.AddSystem( +// LcmPublisherSystem::Make( +// lcm_channel_params.c3_object_channel, lcm, +// TriggerTypeSet({TriggerType::kForced}))); +// auto c3_output_publisher = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.c3_debug_output_channel, lcm, +// TriggerTypeSet({TriggerType::kForced}))); +// auto c3_target_state_publisher = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.c3_target_state_channel, lcm, +// TriggerTypeSet({TriggerType::kForced}))); +// auto c3_actual_state_publisher = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.c3_actual_state_channel, lcm, +// TriggerTypeSet({TriggerType::kForced}))); +// auto c3_forces_publisher = +// builder.AddSystem(LcmPublisherSystem::Make( +// lcm_channel_params.c3_force_channel, lcm, +// TriggerTypeSet({TriggerType::kForced}))); +// builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), +// actor_trajectory_sender->get_input_port()); +// builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), +// object_trajectory_sender->get_input_port()); +// builder.Connect(c3_state_sender->get_output_port_target_c3_state(), +// c3_target_state_publisher->get_input_port()); +// builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), +// c3_actual_state_publisher->get_input_port()); +// builder.Connect(c3_output_sender->get_output_port_c3_debug(), +// c3_output_publisher->get_input_port()); +// builder.Connect(c3_output_sender->get_output_port_c3_force(), +// c3_forces_publisher->get_input_port()); // Publisher connections builder.ExportInput(franka_state_receiver->get_input_port(), diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index df567e2162..5b91c5bf48 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -24,7 +24,6 @@ #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" #include "systems/controllers/osc/operational_space_control.h" -#include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/primitives/radio_parser.h" diff --git a/examples/franka/diagrams/franka_sim_diagram.cc b/examples/franka/diagrams/franka_sim_diagram.cc new file mode 100644 index 0000000000..87a69808bf --- /dev/null +++ b/examples/franka/diagrams/franka_sim_diagram.cc @@ -0,0 +1,146 @@ + +#include "franka_sim_diagram.h" + +#include +#include +#include +#include +#include +#include +#include + +#include "common/find_resource.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "systems/robot_lcm_systems.h" + +namespace dairlib { +namespace examples { +using drake::systems::lcm::LcmPublisherSystem; + +using drake::geometry::GeometrySet; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::systems::DiagramBuilder; + +FrankaSimDiagram::FrankaSimDiagram(std::unique_ptr> plant, + drake::lcm::DrakeLcm* lcm) { + // load parameters + DiagramBuilder builder; + scene_graph_ = builder.AddSystem(); + scene_graph_->set_name("scene_graph"); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile("examples/franka/parameters/lcm_channels_simulation.yaml"); + /// Sim Start + plant_ = builder.AddSystem(std::move(plant)); + + auto parser = drake::multibody::Parser(plant_, scene_graph_); +// lcs_diagram_builder.parser() lcs_diagram_builder.parser()(&plant); + parser.SetAutoRenaming(true); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + drake::multibody::ModelInstanceIndex c3_end_effector_index = + parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + + RigidTransform T_X_W = RigidTransform( + drake::math::RotationMatrix(), Eigen::VectorXd::Zero(3)); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), sim_params.tool_attachment_frame); + plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("panda_link0"), + T_X_W); + plant_->WeldFrames(plant_->GetFrameByName("panda_link7"), + plant_->GetFrameByName("plate", c3_end_effector_index), + T_EE_W); + + if (sim_params.scene_index > 0) { + drake::multibody::ModelInstanceIndex left_support_index = + parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; + drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( + FindResourceOrThrow(sim_params.right_support_model))[0]; + RigidTransform T_S1_W = RigidTransform( + drake::math::RollPitchYaw(sim_params.left_support_orientation), + sim_params.left_support_position); + RigidTransform T_S2_W = RigidTransform( + drake::math::RollPitchYaw(sim_params.right_support_orientation), + sim_params.right_support_position); + plant_->WeldFrames(plant_->world_frame(), + plant_->GetFrameByName("support", left_support_index), + T_S1_W); + plant_->WeldFrames(plant_->world_frame(), + plant_->GetFrameByName("support", right_support_index), + T_S2_W); + const drake::geometry::GeometrySet& support_geom_set = + plant_->CollectRegisteredGeometries({ + &plant_->GetBodyByName("support", left_support_index), + &plant_->GetBodyByName("support", right_support_index), + }); + // we WANT to model collisions between link5 and the supports + const drake::geometry::GeometrySet& paddle_geom_set = + plant_->CollectRegisteredGeometries( + {&plant_->GetBodyByName("panda_link2"), + &plant_->GetBodyByName("panda_link3"), + &plant_->GetBodyByName("panda_link4"), + &plant_->GetBodyByName("panda_link6"), + &plant_->GetBodyByName("panda_link7"), &plant_->GetBodyByName("plate"), + &plant_->GetBodyByName("panda_link8")}); + + plant_->ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"paddle", support_geom_set}, {"tray", paddle_geom_set}); + } + + const drake::geometry::GeometrySet& paddle_geom_set = + plant_->CollectRegisteredGeometries({ + &plant_->GetBodyByName("panda_link2"), + &plant_->GetBodyByName("panda_link3"), + &plant_->GetBodyByName("panda_link4"), + &plant_->GetBodyByName("panda_link5"), + &plant_->GetBodyByName("panda_link6"), + &plant_->GetBodyByName("panda_link8"), + }); + auto tray_collision_set = GeometrySet( + plant_->GetCollisionGeometriesForBody(plant_->GetBodyByName("tray"))); + plant_->ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"paddle", paddle_geom_set}, {"tray", tray_collision_set}); + + plant_->Finalize(); + auto tray_state_sender = + builder.AddSystem(*plant_, tray_index); + auto franka_state_sender = + builder.AddSystem(*plant_, franka_index, false); + + // for lcm debugging + auto state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_state_channel, lcm, + drake::systems::TriggerTypeSet( + {drake::systems::TriggerType::kForced}))); + auto tray_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.tray_state_channel, lcm, + drake::systems::TriggerTypeSet( + {drake::systems::TriggerType::kForced}))); + builder.Connect(plant_->get_state_output_port(tray_index), + tray_state_sender->get_input_port_state()); + builder.Connect(plant_->get_state_output_port(franka_index), + franka_state_sender->get_input_port_state()); + builder.Connect(*franka_state_sender, *state_pub); + builder.Connect(*tray_state_sender, *tray_state_pub); + // end lcm debugging + + actuation_port_ = builder.ExportInput(plant_->get_actuation_input_port(), + "franka_sim: robot_efforts"); + tray_state_port_ = builder.ExportOutput(tray_state_sender->get_output_port(), + "franka_sim: tray_state"); + franka_state_port_ = builder.ExportOutput(franka_state_sender->get_output_port(), + "franka_sim: franka_state"); + + builder.BuildInto(this); + this->set_name("FrankaSim"); + +} +} // namespace examples +} // namespace dairlib \ No newline at end of file diff --git a/examples/franka/diagrams/franka_sim_diagram.h b/examples/franka/diagrams/franka_sim_diagram.h new file mode 100644 index 0000000000..daf0d8f235 --- /dev/null +++ b/examples/franka/diagrams/franka_sim_diagram.h @@ -0,0 +1,55 @@ +#pragma once + +#include +#include + +#include +#include +#include + +#include "drake/common/drake_copyable.h" +#include "drake/systems/framework/diagram.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/framework/system.h" + +namespace dairlib { +namespace examples { + +class FrankaSimDiagram : public drake::systems::Diagram { + public: + DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(FrankaSimDiagram) + + /// @param[in] urdf filepath containing the osc_running_gains. + FrankaSimDiagram( + std::unique_ptr> plant, + drake::lcm::DrakeLcm* lcm); + + /// @return the input port for the actuation command. + const drake::systems::InputPort& get_input_port_actuation() const { + return this->get_input_port(actuation_port_); + } + + /// @return the output port for the plant state as an OutputVector. + const drake::systems::OutputPort& get_output_port_tray_state() const { + return this->get_output_port(tray_state_port_); + } + + /// @return the output port for the plant state as an OutputVector. + const drake::systems::OutputPort& get_output_port_franka_state() + const { + return this->get_output_port(franka_state_port_); + } + + const drake::multibody::MultibodyPlant& get_plant() { return *plant_; } + + private: + drake::multibody::MultibodyPlant* plant_; + drake::geometry::SceneGraph* scene_graph_; + + drake::systems::InputPortIndex actuation_port_; + drake::systems::OutputPortIndex tray_state_port_; + drake::systems::OutputPortIndex franka_state_port_; +}; + +} // namespace examples +} // namespace dairlib diff --git a/examples/franka/diagrams/full_diagram.cc b/examples/franka/diagrams/full_diagram.cc new file mode 100644 index 0000000000..5cdc53c396 --- /dev/null +++ b/examples/franka/diagrams/full_diagram.cc @@ -0,0 +1,146 @@ + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "common/find_resource.h" +#include "examples/franka/diagrams/franka_c3_controller_diagram.h" +#include "examples/franka/diagrams/franka_osc_controller_diagram.h" +#include "examples/franka/diagrams/franka_sim_diagram.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "multibody/multibody_utils.h" +#include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +namespace dairlib { + +using drake::geometry::GeometrySet; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::VectorXd; +using examples::controllers::FrankaC3ControllerDiagram; +using examples::controllers::FrankaOSCControllerDiagram; +using systems::RobotInputReceiver; +using systems::RobotOutputSender; +using systems::SubvectorPassThrough; + +int DoMain(int argc, char* argv[]) { + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile( + "examples/franka/parameters/lcm_channels_simulation.yaml"); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + + DiagramBuilder builder; + std::unique_ptr> sim_plant = + std::make_unique>(sim_params.dt); + + auto franka_sim = + builder.AddSystem(std::move(sim_plant), &lcm); + + /// OSC + auto osc_controller = builder.AddSystem( + "examples/franka/parameters/franka_osc_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); + + /// C3 plant + auto c3_controller = builder.AddSystem( + "examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); + + /* -------------------------------------------------------------------------------------------*/ + auto passthrough = builder.AddSystem( + osc_controller->get_output_port_robot_input().size(), 0, + franka_sim->get_input_port_actuation().size()); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + + //// OSC connections + + // Diagram Connections + builder.Connect(osc_controller->get_output_port_robot_input(), + passthrough->get_input_port()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), + osc_controller->get_input_port_end_effector_position()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), + osc_controller->get_input_port_end_effector_orientation()); + builder.Connect(c3_controller->get_output_port_mpc_plan(), + osc_controller->get_input_port_end_effector_force()); + + builder.Connect(franka_sim->get_output_port_franka_state(), + osc_controller->get_input_port_robot_state()); + builder.Connect(franka_sim->get_output_port_franka_state(), + c3_controller->get_input_port_robot_state()); + builder.Connect(franka_sim->get_output_port_tray_state(), + c3_controller->get_input_port_object_state()); + + builder.Connect(radio_sub->get_output_port(), + c3_controller->get_input_port_radio()); + builder.Connect(radio_sub->get_output_port(), + osc_controller->get_input_port_radio()); + + builder.Connect(passthrough->get_output_port(), + franka_sim->get_input_port_actuation()); + + auto diagram = builder.Build(); + diagram->set_name("plate_balancing_full_diagram"); + DrawAndSaveDiagramGraph(*diagram); + + drake::systems::Simulator simulator(*diagram); + + simulator.set_publish_every_time_step(true); + simulator.set_publish_at_initialization(true); + simulator.set_target_realtime_rate(sim_params.realtime_rate); + + + auto diagram_context = diagram->CreateDefaultContext(); + auto& plant = franka_sim->get_plant(); + auto& plant_context = + diagram->GetMutableSubsystemContext(plant, diagram_context.get()); + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + VectorXd q = VectorXd::Zero(nq); + q.head(7) = sim_params.q_init_franka; + + q.tail(7) = sim_params.q_init_plate[sim_params.scene_index]; + + plant.SetPositions(&plant_context, q); + + VectorXd v = VectorXd::Zero(nv); + plant.SetVelocities(&plant_context, v); + + simulator.Initialize(); + simulator.AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 1989d62578..295b02c5d8 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -4,7 +4,6 @@ #include #include -#include #include #include #include diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index c6e6ac5b14..e53030e1cc 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -12,7 +12,7 @@ warm_start: true use_predicted_x0: true solve_time_filter_alpha: 0.95 # set to 0 to publish as fast as possible -publish_frequency: 0 +publish_frequency: 30 # Workspace Limits world_x_limits: [0.4, 0.6] From 71990312851975d75a79c3756d9d69df4e93fa47 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 21 Mar 2024 13:39:40 -0400 Subject: [PATCH 664/758] working on deterministic sim --- bindings/pydairlib/franka/BUILD.bazel | 18 +++ bindings/pydairlib/franka/__init__.py | 1 - bindings/pydairlib/franka/controllers_py.cc | 2 +- bindings/pydairlib/franka/franka_env.py | 137 ++++++++++++++++++ .../lcm/lcm_py_bind_cpp_serializers.cc | 4 + .../pydairlib/systems/robot_lcm_systems_py.cc | 13 ++ .../diagrams/franka_c3_controller_diagram.cc | 112 ++++++++------ .../diagrams/franka_c3_controller_diagram.h | 12 +- .../diagrams/franka_osc_controller_diagram.cc | 12 +- examples/franka/full_diagram.cc | 13 +- .../franka_c3_options_w_supports.yaml | 3 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../franka/systems/end_effector_trajectory.cc | 3 +- systems/controllers/c3_controller.cc | 15 +- 14 files changed, 272 insertions(+), 75 deletions(-) create mode 100644 bindings/pydairlib/franka/franka_env.py diff --git a/bindings/pydairlib/franka/BUILD.bazel b/bindings/pydairlib/franka/BUILD.bazel index 7cac5cb5fa..39b0f12f2c 100644 --- a/bindings/pydairlib/franka/BUILD.bazel +++ b/bindings/pydairlib/franka/BUILD.bazel @@ -27,6 +27,24 @@ pybind_py_library( py_imports = ["."], ) +py_binary( + name = "franka_env", + srcs = ["franka_env.py"], + data = [ + "//examples/franka:urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + "//bindings/pydairlib/franka", + "//bindings/pydairlib/lcm:lcm_trajectory_py", + "//bindings/pydairlib/systems:framework_py", + "//bindings/pydairlib/systems:primitives_py", + "//bindings/pydairlib/systems:robot_lcm_systems_py", + "//lcmtypes:lcmtypes_robot_py", + "@drake//bindings/pydrake", + ], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") diff --git a/bindings/pydairlib/franka/__init__.py b/bindings/pydairlib/franka/__init__.py index b889fc0649..fa9c628350 100644 --- a/bindings/pydairlib/franka/__init__.py +++ b/bindings/pydairlib/franka/__init__.py @@ -1,2 +1 @@ # Importing everything in this directory to this package -from .franka import * \ No newline at end of file diff --git a/bindings/pydairlib/franka/controllers_py.cc b/bindings/pydairlib/franka/controllers_py.cc index dda6871c74..e60f69a475 100644 --- a/bindings/pydairlib/franka/controllers_py.cc +++ b/bindings/pydairlib/franka/controllers_py.cc @@ -23,7 +23,7 @@ PYBIND11_MODULE(controllers, m) { drake::lcm::DrakeLcm*>(), py::arg("controller_settings"), py::arg("lcm_channels"), py::arg("lcm")) - .def("FrankaOSCControllerDiagram", + .def("get_input_port_robot_state", &FrankaOSCControllerDiagram::get_input_port_robot_state, py_rvp::reference_internal) .def("get_input_port_end_effector_position", diff --git a/bindings/pydairlib/franka/franka_env.py b/bindings/pydairlib/franka/franka_env.py new file mode 100644 index 0000000000..8c53181560 --- /dev/null +++ b/bindings/pydairlib/franka/franka_env.py @@ -0,0 +1,137 @@ +from pydrake.all import * +from pydairlib.franka.controllers import FrankaOSCControllerDiagram +from pydairlib.franka.controllers import FrankaC3ControllerDiagram + +from pydrake.common.yaml import yaml_load +from pydairlib.systems.primitives import * +from pydairlib.systems.robot_lcm_systems import * +from pydairlib.lcm.lcm_trajectory import * +import pydrake.systems.lcm as mut + +import dairlib + + +def main(): + osc_params_file = "examples/franka/parameters/franka_osc_controller_params.yaml" + c3_params_file = "examples/franka/parameters/franka_c3_controller_params.yaml" + lcm_params_file = "examples/franka/parameters/lcm_channels_simulation.yaml" + sim_params_file = "examples/franka/parameters/franka_sim_params.yaml" + + sim_params = yaml_load(filename=sim_params_file) + lcm_params = yaml_load(filename=lcm_params_file) + c3_params = yaml_load(filename=c3_params_file) + c3_options_file = c3_params['c3_options_file'][c3_params['scene_index']] + c3_options = yaml_load(filename=c3_options_file) + lcm = DrakeLcm() + builder = DiagramBuilder() + plant, scene_graph = AddMultibodyPlantSceneGraph(builder, sim_params['dt']) + + parser = Parser(plant) + parser.SetAutoRenaming(True) + + franka_index, = parser.AddModels(FindResourceOrThrow(sim_params['franka_model'])) + end_effector_index, = parser.AddModels(sim_params['end_effector_model']) + tray_index, = parser.AddModels(sim_params['tray_model']) + + T_X_W = RigidTransform(RotationMatrix(), np.zeros(3)) + T_EE_W = RigidTransform(RotationMatrix(), sim_params['tool_attachment_frame']) + + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName('panda_link0'), T_X_W) + frame = plant.GetFrameByName(name='plate', model_instance=end_effector_index) + plant.WeldFrames(plant.GetFrameByName('panda_link7'), + frame, + T_EE_W) + left_support_index, = parser.AddModels(sim_params['left_support_model']) + right_support_index, = parser.AddModels(sim_params['right_support_model']) + T_S1_W = RigidTransform(RollPitchYaw(sim_params['left_support_orientation']), + sim_params['left_support_position']) + T_S2_W = RigidTransform(RollPitchYaw(sim_params['right_support_orientation']), + sim_params['right_support_position']) + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", left_support_index), + T_S1_W) + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", right_support_index), + T_S2_W) + plant.Finalize() + + osc_controller = builder.AddSystem(FrankaOSCControllerDiagram( + "examples/franka/parameters/franka_osc_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) + + c3_controller = builder.AddSystem(FrankaC3ControllerDiagram( + "examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) + c3_publish_frequency = c3_options['publish_frequency'] + # placeholder_trajectory = dairlib.lcmt_timestamped_saved_traj() + # a = Value(placeholder_trajectory) + # discrete_time_delay = builder.AddSystem( + # DiscreteTimeDelay(1.0 / c3_publish_frequency, 1, Value(placeholder_trajectory))) + + passthrough = builder.AddSystem(SubvectorPassThrough(8, 0, 7)) + tray_state_sender = builder.AddSystem(ObjectStateSender(plant, tray_index)) + franka_state_sender = builder.AddSystem(RobotOutputSender(plant, franka_index, False, False)) + + # radio_sub = builder.AddSystem(LcmSubscriberSystem.Make(channel=lcm_params['radio_channel'], lcm_type=dairlib.lcmt_radio_out, lcm=lcm, use_cpp_serializer=True)) + sim_state_logger = builder.AddSystem( + VectorLogSink(plant.num_positions() + plant.num_velocities(), 2 * sim_params['dt'])) + + builder.Connect(c3_controller.get_output_port_mpc_plan(), + discrete_time_delay.get_input_port()) + builder.Connect(c3_controller.get_output_port_mpc_plan(), + osc_controller.get_input_port_end_effector_position()) + builder.Connect(c3_controller.get_output_port_mpc_plan(), + osc_controller.get_input_port_end_effector_orientation()) + builder.Connect(c3_controller.get_output_port_mpc_plan(), + osc_controller.get_input_port_end_effector_force()) + + builder.Connect(osc_controller.get_output_port_robot_input(), + passthrough.get_input_port()) + + builder.Connect(franka_state_sender.get_output_port(), + osc_controller.get_input_port_robot_state()) + builder.Connect(franka_state_sender.get_output_port(), + c3_controller.get_input_port_robot_state()) + builder.Connect(tray_state_sender.get_output_port(), + c3_controller.get_input_port_object_state()) + + builder.Connect(plant.get_state_output_port(franka_index), + franka_state_sender.get_input_port_state()) + builder.Connect(plant.get_state_output_port(tray_index), + tray_state_sender.get_input_port_state()) + builder.Connect(plant.get_state_output_port(), + sim_state_logger.get_input_port()) + builder.Connect(passthrough.get_output_port(), + plant.get_actuation_input_port()) + + if sim_params['visualize_drake_sim']: + AddDefaultVisualization(builder) + + diagram = builder.Build() + simulator = Simulator(diagram) + + simulator.set_publish_every_time_step(False) + simulator.set_publish_at_initialization(False) + simulator.set_target_realtime_rate(sim_params['realtime_rate']) + + plant_context = diagram.GetMutableSubsystemContext(plant, simulator.get_mutable_context()) + osc_controller_context = diagram.GetMutableSubsystemContext(osc_controller, simulator.get_mutable_context()) + c3_controller_context = diagram.GetMutableSubsystemContext(c3_controller, simulator.get_mutable_context()) + osc_controller.get_input_port_radio().FixValue(osc_controller_context, np.zeros(18)) + c3_controller.get_input_port_radio().FixValue(c3_controller_context, np.zeros(18)) + logger_context = diagram.GetSubsystemContext(sim_state_logger, simulator.get_context()) + + q = np.hstack((sim_params['q_init_franka'], sim_params['q_init_plate'][sim_params['scene_index']])) + v = np.zeros(plant.num_velocities()) + plant.SetPositions(plant_context, q) + + simulator.Initialize() + simulator.AdvanceTo(5.0) + + sim_states = sim_state_logger.GetLog(logger_context) + # print(sim_states.data().shape) + # print(sim_states.sample_times().shape) + + +if __name__ == '__main__': + main() diff --git a/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc index f41936d54b..dd08d27678 100644 --- a/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc +++ b/bindings/pydairlib/lcm/lcm_py_bind_cpp_serializers.cc @@ -8,6 +8,8 @@ #include "dairlib/lcmt_osc_tracking_data.hpp" #include "dairlib/lcmt_robot_input.hpp" #include "dairlib/lcmt_saved_traj.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "dairlib/lcmt_radio_out.hpp" #include "drake/bindings/pydrake/systems/lcm_pybind.h" @@ -25,6 +27,8 @@ void BindCppSerializers() { drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); + drake::pydrake::pysystems::pylcm::BindCppSerializer("dairlib"); } } // namespace pydairlib diff --git a/bindings/pydairlib/systems/robot_lcm_systems_py.cc b/bindings/pydairlib/systems/robot_lcm_systems_py.cc index 606197e509..eab647bfaf 100644 --- a/bindings/pydairlib/systems/robot_lcm_systems_py.cc +++ b/bindings/pydairlib/systems/robot_lcm_systems_py.cc @@ -39,6 +39,18 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py_rvp::reference_internal) .def("get_input_port_imu", &RobotOutputSender::get_input_port_imu, py_rvp::reference_internal); + py::class_>( + m, "ObjectStateSender") + .def(py::init&, + drake::multibody::ModelInstanceIndex>()) + .def("get_input_port_state", &systems::ObjectStateSender::get_input_port_state, + py_rvp::reference_internal); + py::class_>( + m, "ObjectStateReceiver") + .def(py::init&>()) + .def(py::init&, + drake::multibody::ModelInstanceIndex>()); + py::class_>( m, "RobotCommandSender") .def(py::init&>()); @@ -53,6 +65,7 @@ PYBIND11_MODULE(robot_lcm_systems, m) { py::arg("actuator_channel"), py::arg("state_channel"), py::arg("publish_rate"), py::arg("model_instance"), py::arg("publish_efforts"), py::arg("actuator_delay")); + } } // namespace pydairlib diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 4e853a4f3f..f9df9c0c7c 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -14,6 +14,8 @@ #include #include #include +#include +#include #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" @@ -227,6 +229,15 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( auto c3_trajectory_generator = builder.AddSystem( robot_diagram_for_lcs_->plant(), c3_options); +// auto placeholder_trajectory = lcmt_timestamped_saved_traj(); + auto placeholder_solution = C3Output::C3Solution(); + placeholder_solution.x_sol_ = Eigen::MatrixXf::Zero(c3_options.g_x.size(), c3_options.N); + placeholder_solution.lambda_sol_ = Eigen::MatrixXf::Zero(c3_options.g_lambda.size(), c3_options.N); + placeholder_solution.u_sol_ = Eigen::MatrixXf::Zero(c3_options.g_u.size(), c3_options.N); + placeholder_solution.time_vector_ = Eigen::VectorXf::LinSpaced(c3_options.N, 0, 1); + auto discrete_time_delay = builder.AddSystem(1 / c3_options.publish_frequency, + 1, + drake::Value(placeholder_solution)); std::vector state_names = { "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", "tray_qx", "tray_qy", "tray_qz", "tray_x", @@ -239,8 +250,16 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( c3_trajectory_generator->SetPublishEndEffectorOrientation( controller_params.include_end_effector_orientation); auto c3_output_sender = builder.AddSystem(); - auto radio_to_vector = builder.AddSystem(); + auto passthrough = builder.AddSystem>(18); + controller->SetOsqpSolverOptions(solver_options); + + // publisher connections + DRAKE_DEMAND(c3_options.publish_frequency > 0); + builder.Connect(controller->get_output_port_c3_solution(), + discrete_time_delay->get_input_port()); + + builder.Connect(franka_state_receiver->get_output_port(), reduced_order_model_receiver->get_input_port_franka_state()); builder.Connect(target_state_mux->get_output_port(), @@ -255,9 +274,9 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( controller->get_input_port_lcs_state()); builder.Connect(reduced_order_model_receiver->get_output_port(), lcs_factory->get_input_port_lcs_state()); - builder.Connect(radio_to_vector->get_output_port(), + builder.Connect(passthrough->get_output_port(), plate_balancing_target->get_input_port_radio()); - builder.Connect(controller->get_output_port_c3_solution(), + builder.Connect(discrete_time_delay->get_output_port(), c3_trajectory_generator->get_input_port_c3_solution()); builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), c3_output_sender->get_input_port_lcs_contact_info()); @@ -267,58 +286,59 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), c3_state_sender->get_input_port_actual_state()); - builder.Connect(controller->get_output_port_c3_solution(), + builder.Connect(discrete_time_delay->get_output_port(), c3_output_sender->get_input_port_c3_solution()); builder.Connect(controller->get_output_port_c3_intermediates(), c3_output_sender->get_input_port_c3_intermediates()); - // publisher connections - DRAKE_DEMAND(c3_options.publish_frequency > 0); -// auto actor_trajectory_sender = builder.AddSystem( -// LcmPublisherSystem::Make( -// lcm_channel_params.c3_actor_channel, lcm, -// TriggerTypeSet({TriggerType::kForced}))); -// auto object_trajectory_sender = builder.AddSystem( -// LcmPublisherSystem::Make( -// lcm_channel_params.c3_object_channel, lcm, -// TriggerTypeSet({TriggerType::kForced}))); -// auto c3_output_publisher = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.c3_debug_output_channel, lcm, -// TriggerTypeSet({TriggerType::kForced}))); -// auto c3_target_state_publisher = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.c3_target_state_channel, lcm, -// TriggerTypeSet({TriggerType::kForced}))); -// auto c3_actual_state_publisher = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.c3_actual_state_channel, lcm, -// TriggerTypeSet({TriggerType::kForced}))); -// auto c3_forces_publisher = -// builder.AddSystem(LcmPublisherSystem::Make( -// lcm_channel_params.c3_force_channel, lcm, -// TriggerTypeSet({TriggerType::kForced}))); -// builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), -// actor_trajectory_sender->get_input_port()); -// builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), -// object_trajectory_sender->get_input_port()); -// builder.Connect(c3_state_sender->get_output_port_target_c3_state(), -// c3_target_state_publisher->get_input_port()); -// builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), -// c3_actual_state_publisher->get_input_port()); -// builder.Connect(c3_output_sender->get_output_port_c3_debug(), -// c3_output_publisher->get_input_port()); -// builder.Connect(c3_output_sender->get_output_port_c3_force(), -// c3_forces_publisher->get_input_port()); + + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + actor_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), + object_trajectory_sender->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_debug(), + c3_output_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_force(), + c3_forces_publisher->get_input_port()); + + // Publisher connections - builder.ExportInput(franka_state_receiver->get_input_port(), + franka_state_port_ = builder.ExportInput(franka_state_receiver->get_input_port(), "franka_state: lcmt_robot_output"); - builder.ExportInput(tray_state_receiver->get_input_port(), + tray_state_port_ = builder.ExportInput(tray_state_receiver->get_input_port(), "tray_state: lcmt_object_state"); - builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); - builder.ExportOutput( + radio_port_ = builder.ExportInput(passthrough->get_input_port(), "raw_radio"); + mpc_plan_port_ = builder.ExportOutput( c3_trajectory_generator->get_output_port_actor_trajectory(), "actor_trajectory"); diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.h b/examples/franka/diagrams/franka_c3_controller_diagram.h index 09259d5127..8a4b6b68b9 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.h +++ b/examples/franka/diagrams/franka_c3_controller_diagram.h @@ -62,14 +62,10 @@ class FrankaC3ControllerDiagram : public drake::systems::Diagram { std::unique_ptr> plant_tray_context_; std::unique_ptr> plant_for_lcs_autodiff_context_; - const drake::systems::InputPortIndex franka_state_port_ = - drake::systems::InputPortIndex(0); - const drake::systems::InputPortIndex tray_state_port_ = - drake::systems::InputPortIndex(1); - const drake::systems::InputPortIndex radio_port_ = - drake::systems::InputPortIndex(2); - const drake::systems::OutputPortIndex mpc_plan_port_ = - drake::systems::OutputPortIndex(0); + drake::systems::InputPortIndex franka_state_port_; + drake::systems::InputPortIndex tray_state_port_; + drake::systems::InputPortIndex radio_port_; + drake::systems::OutputPortIndex mpc_plan_port_; }; } // namespace controllers diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index 5b91c5bf48..0fea6bd739 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -123,7 +123,7 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( builder.AddSystem(*plant_); auto end_effector_trajectory = builder.AddSystem(); - auto radio_to_vector = builder.AddSystem(); + auto passthrough = builder.AddSystem>(18); VectorXd neutral_position = Eigen::Map( controller_params.neutral_position.data(), controller_params.neutral_position.size()); @@ -212,11 +212,13 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( franka_command_sender->get_input_port(0)); } - builder.Connect(radio_to_vector->get_output_port(), +// builder.Connect(radio_to_vector->get_output_port(), +// passthrough->get_input_port()); + builder.Connect(passthrough->get_output_port(), end_effector_trajectory->get_input_port_radio()); - builder.Connect(radio_to_vector->get_output_port(), + builder.Connect(passthrough->get_output_port(), end_effector_orientation_trajectory->get_input_port_radio()); - builder.Connect(radio_to_vector->get_output_port(), + builder.Connect(passthrough->get_output_port(), end_effector_force_trajectory->get_input_port_radio()); builder.Connect(franka_command_sender->get_output_port(), franka_command_pub->get_input_port()); @@ -249,7 +251,7 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( "end_effector_orientation: lcmt_timestamped_trajectory"); end_effector_force_port_ = builder.ExportInput(end_effector_force_receiver->get_input_port(), "end_effector_force: lcmt_timestamped_trajectory"); - radio_port_ = builder.ExportInput(radio_to_vector->get_input_port(), "raw_radio"); + radio_port_ = builder.ExportInput(passthrough->get_input_port(), "raw_radio"); builder.ExportOutput(osc->get_output_port_osc_command(), "robot_input"); builder.BuildInto(this); diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 9f6b665c7d..917e4d8578 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -30,6 +30,7 @@ #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" +#include "systems/primitives/radio_parser.h" namespace dairlib { using drake::geometry::GeometrySet; @@ -170,9 +171,9 @@ int DoMain(int argc, char* argv[]) { //// OSC connections - builder.Connect(plant.get_state_output_port(tray_index), - tray_state_sender->get_input_port_state()); - + auto radio_to_vector = builder.AddSystem(); + builder.Connect(radio_sub->get_output_port(), + radio_to_vector->get_input_port()); // Diagram Connections builder.Connect(osc_controller->get_output_port_robot_input(), passthrough->get_input_port()); @@ -189,9 +190,9 @@ int DoMain(int argc, char* argv[]) { c3_controller->get_input_port_robot_state()); builder.Connect(tray_state_sender->get_output_port(), c3_controller->get_input_port_object_state()); - builder.Connect(radio_sub->get_output_port(), + builder.Connect(radio_to_vector->get_output_port(), c3_controller->get_input_port_radio()); - builder.Connect(radio_sub->get_output_port(), + builder.Connect(radio_to_vector->get_output_port(), osc_controller->get_input_port_radio()); builder.Connect(*franka_state_sender, *state_pub); @@ -199,6 +200,8 @@ int DoMain(int argc, char* argv[]) { tray_state_pub->get_input_port()); builder.Connect(plant.get_state_output_port(franka_index), franka_state_sender->get_input_port_state()); + builder.Connect(plant.get_state_output_port(tray_index), + tray_state_sender->get_input_port_state()); builder.Connect(passthrough->get_output_port(), plant.get_actuation_input_port()); diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index e53030e1cc..1264840761 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -12,6 +12,7 @@ warm_start: true use_predicted_x0: true solve_time_filter_alpha: 0.95 # set to 0 to publish as fast as possible +#publish_frequency: 0 publish_frequency: 30 # Workspace Limits @@ -35,7 +36,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 # Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.2 # Penalty on all decision variables, assuming scalar w_U: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 04b23698fa..de32033225 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -53,4 +53,4 @@ visualize_workspace: false visualize_pose_trace: false visualize_center_of_mass_plan: true visualize_c3_forces: false -visualize_c3_state: false +visualize_c3_state: true diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index 7128864dcc..ce96a9354d 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -1,5 +1,5 @@ #include "end_effector_trajectory.h" - +#include #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" @@ -67,6 +67,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( } else { if (trajectory_input.value(0).isZero()) { } else { + std::cout << "time difference: " << context.get_time() - trajectory_input.start_time() << std::endl; *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 0092781c21..1f4a33764b 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -87,7 +87,8 @@ C3Controller::C3Controller( c3_->SetOsqpSolverOptions(solver_options_); - // Set actor bounds, TODO(yangwill): move this out of here because it is task specific + // Set actor bounds, TODO(yangwill): move this out of here because it is task + // specific for (int i : vector({0})) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); A(i) = 1.0; @@ -175,7 +176,6 @@ drake::systems::EventStatus C3Controller::ComputePlan( const Context& context, DiscreteValues* discrete_state) const { auto start = std::chrono::high_resolution_clock::now(); - const BasicVector& x_des = *this->template EvalVectorInput(context, target_input_port_); const TimestampedVector* lcs_x = @@ -186,7 +186,8 @@ drake::systems::EventStatus C3Controller::ComputePlan( drake::VectorX x_lcs = lcs_x->get_data(); auto& x_pred = context.get_discrete_state(x_pred_index_).value(); auto mutable_x_pred = discrete_state->get_mutable_value(x_pred_index_); - auto mutable_solve_time = discrete_state->get_mutable_value(filtered_solve_time_index_); + auto mutable_solve_time = + discrete_state->get_mutable_value(filtered_solve_time_index_); if (x_lcs.segment(n_q_, 3).norm() > 0.01 && c3_options_.use_predicted_x0 && !x_pred.isZero()) { @@ -234,7 +235,10 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::chrono::duration_cast(elapsed).count() / 1e6; mutable_solve_time[0] = (1 - solve_time_filter_constant_) * solve_time + - solve_time_filter_constant_ * mutable_solve_time[0]; + solve_time_filter_constant_ * mutable_solve_time[0]; + +// solve_time = 1.0 / c3_options_.publish_frequency; +// mutable_solve_time[0] = solve_time; auto z_sol = c3_->GetFullSolution(); if (mutable_solve_time[0] < N_ * dt_) { @@ -270,8 +274,7 @@ void C3Controller::OutputC3Intermediates( const drake::systems::Context& context, C3Output::C3Intermediates* c3_intermediates) const { double solve_time = context.get_discrete_state(filtered_solve_time_index_)[0]; - double t = context.get_discrete_state(plan_start_time_index_)[0] + - solve_time; + double t = context.get_discrete_state(plan_start_time_index_)[0] + solve_time; auto delta = c3_->GetDualDeltaSolution(); auto w = c3_->GetDualWSolution(); From 4952fa992f7abf2f18a07f18341cc4951ac87948 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 21 Mar 2024 15:25:45 -0400 Subject: [PATCH 665/758] fixing bug in gap function taylor expansion --- solvers/lcs_factory.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 70eb269933..a7eaf27e8f 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -203,9 +203,9 @@ std::pair LCSFactory::LinearizePlantToLCS( // TODO(yangwill): check gap function to make sure it makes sense. Potential // source of uncertainty // std::cout << "phi: " << phi << std::endl; - c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v; + c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v - J_n * vNqdot * plant.GetPositions(context); c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = - J_t * dt * d_v - J_n * vNqdot * plant.GetPositions(context); + J_t * dt * d_v; } else if (contact_model == ContactModel::kAnitescu) { VectorXd mu_vec = Eigen::Map( mu.data(), mu.size()); From 05397206993a5fd1a1c0b6352d32852b888ece66 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 25 Mar 2024 14:21:54 -0400 Subject: [PATCH 666/758] deterministic sim still not quite working --- bindings/pydairlib/franka/controllers_py.cc | 56 +++++++++++++- bindings/pydairlib/franka/franka_env.py | 76 ++++++++++++++++--- .../diagrams/franka_c3_controller_diagram.cc | 8 +- .../diagrams/franka_c3_controller_diagram.h | 3 +- examples/franka/full_diagram.cc | 10 ++- .../franka_c3_options_w_supports.yaml | 30 ++++---- .../franka/systems/end_effector_trajectory.cc | 2 +- solvers/c3.cc | 2 +- solvers/c3_options.h | 4 +- systems/controllers/c3_controller.cc | 16 ++-- 10 files changed, 162 insertions(+), 45 deletions(-) diff --git a/bindings/pydairlib/franka/controllers_py.cc b/bindings/pydairlib/franka/controllers_py.cc index e60f69a475..d59e42872e 100644 --- a/bindings/pydairlib/franka/controllers_py.cc +++ b/bindings/pydairlib/franka/controllers_py.cc @@ -1,8 +1,10 @@ #include #include +#include #include "examples/franka/diagrams/franka_c3_controller_diagram.h" #include "examples/franka/diagrams/franka_osc_controller_diagram.h" +#include "solvers/c3_options.h" namespace py = pybind11; @@ -16,6 +18,7 @@ PYBIND11_MODULE(controllers, m) { m.doc() = "Binding controller factories for plate balancing demo"; using py_rvp = py::return_value_policy; + py::module::import("pydrake.math"); py::class_>( m, "FrankaOSCControllerDiagram") @@ -44,10 +47,10 @@ PYBIND11_MODULE(controllers, m) { py::class_>( m, "FrankaC3ControllerDiagram") - .def(py::init(), - py::arg("controller_settings"), py::arg("lcm_channels"), - py::arg("lcm")) + py::arg("controller_settings"), py::arg("c3_options"), + py::arg("lcm_channels"), py::arg("lcm")) .def("get_input_port_robot_state", &FrankaC3ControllerDiagram::get_input_port_robot_state, py_rvp::reference_internal) @@ -60,6 +63,53 @@ PYBIND11_MODULE(controllers, m) { .def("get_output_port_mpc_plan", &FrankaC3ControllerDiagram::get_output_port_mpc_plan, py_rvp::reference_internal); + + py::class_(m, "C3Options") + .def(py::init<>()) + .def_readwrite("admm_iter", &C3Options::admm_iter) + .def_readwrite("rho", &C3Options::rho) + .def_readwrite("rho_scale", &C3Options::rho_scale) + .def_readwrite("num_threads", &C3Options::num_threads) + .def_readwrite("delta_option", &C3Options::delta_option) + .def_readwrite("projection_type", &C3Options::projection_type) + .def_readwrite("contact_model", &C3Options::contact_model) + .def_readwrite("warm_start", &C3Options::warm_start) + .def_readwrite("use_predicted_x0", &C3Options::use_predicted_x0) + .def_readwrite("solve_time_filter_alpha", &C3Options::solve_time_filter_alpha) + .def_readwrite("publish_frequency", &C3Options::publish_frequency) + .def_readwrite("world_x_limits", &C3Options::world_x_limits) + .def_readwrite("world_y_limits", &C3Options::world_y_limits) + .def_readwrite("world_z_limits", &C3Options::world_z_limits) + .def_readwrite("u_horizontal_limits", &C3Options::u_horizontal_limits) + .def_readwrite("u_vertical_limits", &C3Options::u_vertical_limits) + .def_readwrite("workspace_margins", &C3Options::workspace_margins) + .def_readwrite("N", &C3Options::N) + .def_readwrite("gamma", &C3Options::gamma) + .def_readwrite("q_vector", &C3Options::q_vector) + .def_readwrite("r_vector", &C3Options::r_vector) + .def_readwrite("g_vector", &C3Options::g_vector) + .def_readwrite("g_x", &C3Options::g_x) + .def_readwrite("g_gamma", &C3Options::g_gamma) + .def_readwrite("g_lambda_n", &C3Options::g_lambda_n) + .def_readwrite("g_lambda_t", &C3Options::g_lambda_t) + .def_readwrite("g_lambda", &C3Options::g_lambda) + .def_readwrite("g_u", &C3Options::g_u) + .def_readwrite("u_vector", &C3Options::u_vector) + .def_readwrite("u_x", &C3Options::u_x) + .def_readwrite("u_gamma", &C3Options::u_gamma) + .def_readwrite("u_lambda_n", &C3Options::u_lambda_n) + .def_readwrite("u_lambda_t", &C3Options::u_lambda_t) + .def_readwrite("u_lambda", &C3Options::u_lambda) + .def_readwrite("u_u", &C3Options::u_u) + .def_readwrite("mu", &C3Options::mu) + .def_readwrite("dt", &C3Options::dt) + .def_readwrite("solve_dt", &C3Options::solve_dt) + .def_readwrite("num_friction_directions", &C3Options::num_friction_directions) + .def_readwrite("num_contacts", &C3Options::num_contacts) + .def_readwrite("Q", &C3Options::Q) + .def_readwrite("R", &C3Options::R) + .def_readwrite("G", &C3Options::G) + .def_readwrite("U", &C3Options::U); } } // namespace pydairlib } // namespace dairlib \ No newline at end of file diff --git a/bindings/pydairlib/franka/franka_env.py b/bindings/pydairlib/franka/franka_env.py index 8c53181560..fae4dac59c 100644 --- a/bindings/pydairlib/franka/franka_env.py +++ b/bindings/pydairlib/franka/franka_env.py @@ -1,6 +1,5 @@ from pydrake.all import * -from pydairlib.franka.controllers import FrankaOSCControllerDiagram -from pydairlib.franka.controllers import FrankaC3ControllerDiagram +from pydairlib.franka.controllers import FrankaOSCControllerDiagram, FrankaC3ControllerDiagram, C3Options from pydrake.common.yaml import yaml_load from pydairlib.systems.primitives import * @@ -21,8 +20,56 @@ def main(): lcm_params = yaml_load(filename=lcm_params_file) c3_params = yaml_load(filename=c3_params_file) c3_options_file = c3_params['c3_options_file'][c3_params['scene_index']] - c3_options = yaml_load(filename=c3_options_file) - lcm = DrakeLcm() + c3_options_dict = yaml_load(filename=c3_options_file) + c3_options = C3Options() + c3_options.admm_iter = c3_options_dict['admm_iter'] + c3_options.rho = c3_options_dict['rho'] + c3_options.rho_scale = c3_options_dict['rho_scale'] + c3_options.num_threads = c3_options_dict['num_threads'] + c3_options.delta_option = c3_options_dict['delta_option'] + c3_options.projection_type = c3_options_dict['projection_type'] + c3_options.contact_model = c3_options_dict['contact_model'] + c3_options.warm_start = c3_options_dict['warm_start'] + c3_options.use_predicted_x0 = c3_options_dict['use_predicted_x0'] + c3_options.solve_time_filter_alpha = c3_options_dict['solve_time_filter_alpha'] + c3_options.publish_frequency = c3_options_dict['publish_frequency'] + c3_options.world_x_limits = c3_options_dict['world_x_limits'] + c3_options.world_y_limits = c3_options_dict['world_y_limits'] + c3_options.world_z_limits = c3_options_dict['world_z_limits'] + c3_options.u_horizontal_limits = c3_options_dict['u_horizontal_limits'] + c3_options.u_vertical_limits = c3_options_dict['u_vertical_limits'] + c3_options.workspace_margins = c3_options_dict['workspace_margins'] + c3_options.N = c3_options_dict['N'] + c3_options.gamma = c3_options_dict['gamma'] + c3_options.gamma = c3_options_dict['gamma'] + c3_options.q_vector = c3_options_dict['q_vector'] + c3_options.r_vector = c3_options_dict['r_vector'] + c3_options.g_x = c3_options_dict['g_x'] + c3_options.g_gamma = c3_options_dict['g_gamma'] + c3_options.g_lambda_n = c3_options_dict['g_lambda_n'] + c3_options.g_lambda_t = c3_options_dict['g_lambda_t'] + c3_options.g_lambda = c3_options_dict['g_lambda'] + c3_options.g_u = c3_options_dict['g_u'] + c3_options.u_x = c3_options_dict['u_x'] + c3_options.u_gamma = c3_options_dict['u_gamma'] + c3_options.u_lambda_n = c3_options_dict['u_lambda_n'] + c3_options.u_lambda_t = c3_options_dict['u_lambda_t'] + c3_options.u_lambda = c3_options_dict['u_lambda'] + c3_options.u_u = c3_options_dict['u_u'] + c3_options.gamma = c3_options_dict['gamma'] + c3_options.mu = c3_options_dict['mu'] + c3_options.dt = c3_options_dict['dt'] + c3_options.solve_dt = c3_options_dict['solve_dt'] + c3_options.num_friction_directions = c3_options_dict['num_friction_directions'] + c3_options.num_contacts = c3_options_dict['num_contacts'] + c3_options.Q = c3_options_dict['w_Q'] * np.diag(np.array(c3_options_dict['q_vector'])) + c3_options.R = c3_options_dict['w_R'] * np.diag(np.array(c3_options_dict['r_vector'])) + g_vec = np.hstack((c3_options_dict['g_x'], c3_options_dict['g_lambda'], c3_options_dict['g_u'])) + u_vec = np.hstack((c3_options_dict['u_x'], c3_options_dict['u_lambda'], c3_options_dict['u_u'])) + c3_options.G = c3_options_dict['w_G'] * np.diag(g_vec) + c3_options.U = c3_options_dict['w_U'] * np.diag(u_vec) + + lcm = DrakeLcm("udpm://239.255.76.67:7667?ttl=0") builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, sim_params['dt']) @@ -55,19 +102,30 @@ def main(): T_S2_W) plant.Finalize() + + osc_controller = builder.AddSystem(FrankaOSCControllerDiagram( "examples/franka/parameters/franka_osc_controller_params.yaml", "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) c3_controller = builder.AddSystem(FrankaC3ControllerDiagram( - "examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/franka_c3_controller_params.yaml", c3_options, "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) - c3_publish_frequency = c3_options['publish_frequency'] + + # c3_publish_frequency = c3_options.publish_frequency # placeholder_trajectory = dairlib.lcmt_timestamped_saved_traj() # a = Value(placeholder_trajectory) # discrete_time_delay = builder.AddSystem( # DiscreteTimeDelay(1.0 / c3_publish_frequency, 1, Value(placeholder_trajectory))) + # state_pub =builder.AddSystem(LcmPublisherSystem.Make(lcm_params['franka_state_channel'], lcm_type=dairlib.lcmt_robot_output, + # lcm=lcm, publish_triggers=TriggerType.kForced, use_cpp_serializer=True)) + # tray_state_pub = + # builder.AddSystem(LcmPublisherSystem::Make( + # lcm_channel_params.tray_state_channel, &lcm, + # drake::systems::TriggerTypeSet( + # {drake::systems::TriggerType::kForced}))); + passthrough = builder.AddSystem(SubvectorPassThrough(8, 0, 7)) tray_state_sender = builder.AddSystem(ObjectStateSender(plant, tray_index)) franka_state_sender = builder.AddSystem(RobotOutputSender(plant, franka_index, False, False)) @@ -76,8 +134,6 @@ def main(): sim_state_logger = builder.AddSystem( VectorLogSink(plant.num_positions() + plant.num_velocities(), 2 * sim_params['dt'])) - builder.Connect(c3_controller.get_output_port_mpc_plan(), - discrete_time_delay.get_input_port()) builder.Connect(c3_controller.get_output_port_mpc_plan(), osc_controller.get_input_port_end_effector_position()) builder.Connect(c3_controller.get_output_port_mpc_plan(), @@ -110,8 +166,8 @@ def main(): diagram = builder.Build() simulator = Simulator(diagram) - simulator.set_publish_every_time_step(False) - simulator.set_publish_at_initialization(False) + simulator.set_publish_every_time_step(True) + simulator.set_publish_at_initialization(True) simulator.set_target_realtime_rate(sim_params['realtime_rate']) plant_context = diagram.GetMutableSubsystemContext(plant, simulator.get_mutable_context()) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index f9df9c0c7c..b75fda39f3 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -59,7 +59,7 @@ using multibody::MakeNameToVelocitiesMap; using std::string; FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( - const string& controller_settings, const string& lcm_channels, + const string& controller_settings, const C3Options c3_options, const string& lcm_channels, drake::lcm::DrakeLcm* lcm) { this->set_name("FrankaC3Controller"); DiagramBuilder builder; @@ -68,8 +68,8 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( drake::yaml::LoadYamlFile(controller_settings); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(lcm_channels); - C3Options c3_options = drake::yaml::LoadYamlFile( - controller_params.c3_options_file[controller_params.scene_index]); +// C3Options c3_options = drake::yaml::LoadYamlFile( +// controller_params.c3_options_file[controller_params.scene_index]); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(controller_params.osqp_settings_file)) @@ -236,7 +236,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( placeholder_solution.u_sol_ = Eigen::MatrixXf::Zero(c3_options.g_u.size(), c3_options.N); placeholder_solution.time_vector_ = Eigen::VectorXf::LinSpaced(c3_options.N, 0, 1); auto discrete_time_delay = builder.AddSystem(1 / c3_options.publish_frequency, - 1, + 2, drake::Value(placeholder_solution)); std::vector state_names = { "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.h b/examples/franka/diagrams/franka_c3_controller_diagram.h index 8a4b6b68b9..160a0eb6c6 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.h +++ b/examples/franka/diagrams/franka_c3_controller_diagram.h @@ -11,6 +11,7 @@ #include #include #include +#include "solvers/c3_options.h" namespace dairlib { namespace examples { @@ -22,7 +23,7 @@ class FrankaC3ControllerDiagram : public drake::systems::Diagram { /// @param[in] osc_gains_filename filepath containing the osc_running_gains. /// @param[in] osqp_settings filepath containing the osqp settings. - FrankaC3ControllerDiagram(const std::string& controller_settings, + FrankaC3ControllerDiagram(const std::string& controller_settings, const C3Options c3_options, const std::string& lcm_channels, drake::lcm::DrakeLcm* lcm); diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 917e4d8578..7f80d0979f 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -24,13 +24,14 @@ #include "common/find_resource.h" #include "examples/franka/diagrams/franka_c3_controller_diagram.h" #include "examples/franka/diagrams/franka_osc_controller_diagram.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "multibody/multibody_utils.h" +#include "systems/primitives/radio_parser.h" #include "systems/primitives/subvector_pass_through.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "systems/primitives/radio_parser.h" namespace dairlib { using drake::geometry::GeometrySet; @@ -58,6 +59,11 @@ int DoMain(int argc, char* argv[]) { // load parameters FrankaSimParams sim_params = drake::yaml::LoadYamlFile( "examples/franka/parameters/franka_sim_params.yaml"); + FrankaC3ControllerParams c3_params = + drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_c3_controller_params.yaml"); + C3Options c3_options = drake::yaml::LoadYamlFile( + c3_params.c3_options_file[c3_params.scene_index]); DiagramBuilder builder; @@ -144,7 +150,7 @@ int DoMain(int argc, char* argv[]) { /// C3 plant auto c3_controller = builder.AddSystem( - "examples/franka/parameters/franka_c3_controller_params.yaml", + "examples/franka/parameters/franka_c3_controller_params.yaml", c3_options, "examples/franka/parameters/lcm_channels_simulation.yaml", &lcm); /* -------------------------------------------------------------------------------------------*/ diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index 1264840761..c8b4a3fc46 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -3,19 +3,19 @@ rho: 0 # does not do anything rho_scale: 4 num_threads: 5 delta_option: 1 -# options are 'MIQP' or 'QP' +#options are 'MIQP' or 'QP' projection_type: 'MIQP' -# options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'stewart_and_trinkle' +#options are 'stewart_and_trinkle' or 'anitescu' +#contact_model : 'stewart_and_trinkle' contact_model: 'anitescu' warm_start: true use_predicted_x0: true solve_time_filter_alpha: 0.95 -# set to 0 to publish as fast as possible -#publish_frequency: 0 -publish_frequency: 30 +#set to 0 to publish as fast as possible +#publish_frequency : 0 +publish_frequency: 25 -# Workspace Limits +#Workspace Limits world_x_limits: [0.4, 0.6] world_y_limits: [-0.1, 0.1] world_z_limits: [0.35, 0.7] @@ -32,21 +32,21 @@ num_contacts: 7 N: 5 gamma: 1.0 # discount factor on MPC costs -# matrix scaling +#matrix scaling w_Q: 50 w_R: 50 -# Penalty on all decision variables, assuming scalar -w_G: 0.2 -# Penalty on all decision variables, assuming scalar +#Penalty on all decision variables, assuming scalar +w_G: 0.3 +#Penalty on all decision variables, assuming scalar w_U: 0.1 -# State Tracking Error, assuming diagonal +#State Tracking Error, assuming diagonal q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 15, 10, 10, 1, 5, 5, 5] -# Penalty on efforts, assuming diagonal +#Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] -# Penalty on matching projected variables +#Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] @@ -54,7 +54,7 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -# Penalty on matching the QP variables +#Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index ce96a9354d..db6de776bb 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -67,7 +67,7 @@ void EndEffectorTrajectoryGenerator::CalcTraj( } else { if (trajectory_input.value(0).isZero()) { } else { - std::cout << "time difference: " << context.get_time() - trajectory_input.start_time() << std::endl; +// std::cout << "time difference: " << context.get_time() - trajectory_input.start_time() << std::endl; *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/solvers/c3.cc b/solvers/c3.cc index e984b572f2..c0c4776d71 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -146,7 +146,7 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, for (int i = 0; i < N_ + 1; i++) { target_cost_[i] = prog_ - .AddQuadraticCost(Q_.at(i) * 2, -2 * Q_.at(i) * x_desired_.at(i), + .AddQuadraticCost(2 * Q_.at(i), -2 * Q_.at(i) * x_desired_.at(i), x_.at(i), 1) .evaluator() .get(); diff --git a/solvers/c3_options.h b/solvers/c3_options.h index c584e45e05..9a4f386536 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -26,6 +26,7 @@ struct C3Options { int N; double gamma; + double w_Q; double w_R; double w_G; @@ -33,14 +34,15 @@ struct C3Options { std::vector q_vector; std::vector r_vector; + std::vector g_vector; std::vector g_x; std::vector g_gamma; std::vector g_lambda_n; std::vector g_lambda_t; std::vector g_lambda; - std::vector g_u; + std::vector u_vector; std::vector u_x; std::vector u_gamma; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 1f4a33764b..bb6d65b11c 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -237,17 +237,19 @@ drake::systems::EventStatus C3Controller::ComputePlan( mutable_solve_time[0] = (1 - solve_time_filter_constant_) * solve_time + solve_time_filter_constant_ * mutable_solve_time[0]; -// solve_time = 1.0 / c3_options_.publish_frequency; -// mutable_solve_time[0] = solve_time; + if (c3_options_.publish_frequency > 0){ + solve_time = 1.0 / c3_options_.publish_frequency; + mutable_solve_time[0] = solve_time; + } auto z_sol = c3_->GetFullSolution(); - if (mutable_solve_time[0] < N_ * dt_) { + if (mutable_solve_time[0] < (N_ - 1) * dt_) { int index = mutable_solve_time[0] / dt_; - double weight = ((index + 1) * dt_ - mutable_solve_time[0]) / dt_; - mutable_x_pred = weight * z_sol[index].segment(0, n_x_) + - (1 - weight) * z_sol[index + 1].segment(0, n_x_); + double weight = (mutable_solve_time[0] - index * dt_) / dt_; + mutable_x_pred = (1 - weight) * z_sol[index].segment(0, n_x_) + + weight * z_sol[index + 1].segment(0, n_x_); } else { - mutable_x_pred = z_sol[1].segment(0, n_x_); + mutable_x_pred = z_sol[-1].segment(0, n_x_); } return drake::systems::EventStatus::Succeeded(); From 09b4a3deee795b437591222e59fd3fc2007ff0a6 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 25 Mar 2024 16:23:10 -0400 Subject: [PATCH 667/758] rerunning parameter sweep after tuning c3 parameters to be more robust --- .../pydairlib/analysis/log_plotter_franka.py | 2 +- .../parameter_study_analysis.py | 18 ++--- .../parameter_study_config.yaml | 4 +- .../run_tray_parameter_study.py | 7 +- bindings/pydairlib/franka/franka_env.py | 69 +++++-------------- bindings/pydairlib/franka/load_c3_options.py | 57 +++++++++++++++ bindings/pydairlib/lcm/process_lcm_log.py | 4 +- 7 files changed, 90 insertions(+), 71 deletions(-) create mode 100644 bindings/pydairlib/franka/load_c3_options.py diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index a3d1a9ee4a..1f149d5c16 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -56,7 +56,7 @@ def main(): plot_config.start_time, plot_config.duration, mbp_plots.load_default_channels, # processing callback - franka_plant, channel_x, channel_u, + franka_plant, True, channel_x, channel_u, channel_osc) # processing callback arguments # processing callback arguments diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py index 15150ebac1..e4d9f7054b 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -64,11 +64,10 @@ def load_lcm_logs(): for j in range(5): # ps = plot_styler.PlotStyler() - log_filename = param_study['results_folder'] + param_study['parameter'][1] + '/simlog-' + '%02d_%1d' % (i, j) - print(log_filename) + log_filename = param_study['results_folder'] + param_study['parameter'][2] + '/simlog-' + '%02d_%1d' % (i, j) log = lcm.EventLog(log_filename, "r") c3_target, c3_actual, c3_output = \ - get_log_data(log, c3_channels, start_time, duration, callback, + get_log_data(log, c3_channels, start_time, duration, callback, False, lcm_channels['c3_target_state_channel'], lcm_channels['c3_actual_state_channel'], lcm_channels['c3_debug_output_channel']) length = min(c3_target['t'].shape[0], c3_actual['t'].shape[0]) @@ -92,15 +91,16 @@ def load_lcm_logs(): # plt.show() print(successes) all_successes[i] = successes - np.save('target_successes_23', all_successes ) + # np.save('target_successes_23', all_successes ) + np.save('target_successes_03_25', all_successes ) def plot_logs(): - all_successes = np.load('all_successes.npy') + all_successes = np.load('target_successes_03_25.npy') bar_width = 0.025 bar_positions = np.arange(all_successes.shape[0]) n = all_successes.shape[0] # mu_range = np.arange(0.3, 0.74, 0.05) - effective_mu_range = np.arange(0.2, 0.61, 0.05) + effective_mu_range = np.arange(0.1, 0.71, 0.1) plt.rc('legend', fontsize=36) plt.rc('axes', labelsize=36, titlesize=36) @@ -111,7 +111,7 @@ def plot_logs(): # for j in range(3): # plt.bar(bar_positions[i], all_successes[i, 2] / 30, width=bar_width) # plt.bar(effective_mu_range[i], all_successes[i, 2] / all_successes[i, 0], width=bar_width, color='grey') - plt.bar(effective_mu_range[i], all_successes[i, 0] / 30, width=bar_width, color='grey') + plt.bar(effective_mu_range[i], all_successes[i, 0] / 5, width=bar_width, color='grey') plt.ylabel('Target Success Rate') plt.xlabel('Tray/End Effector Friction Coefficient') @@ -123,8 +123,8 @@ def plot_logs(): plt.show() def main(): - load_lcm_logs() - # plot_logs() + # load_lcm_logs() + plot_logs() diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index 0a8a0cb00d..57d9868ef2 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,9 +1,9 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/02_04_24/parameter_study/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/03_25_24/parameter_study/ #results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/ -processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/data/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/03_25_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index 788c761821..e103582c06 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -8,12 +8,12 @@ import yaml def main(): config_file = 'parameter_study_config.yaml' - sim_time = 10.0 + sim_time = 20.0 cooldown_time = 10.0 start_time = 0 realtime_rate = 1.0 num_trials = 5 - c3_start_up_time = 4.0 + c3_start_up_time = 1.0 sim_run_time = sim_time / realtime_rate controller_startup_time = 0.1 @@ -28,7 +28,7 @@ def main(): # parameter = 'mu_c3' # parameter = 'mass_real' - parameter = config['parameter'][1] + parameter = config['parameter'][2] nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' # nominal_real_mu_value = '0.4' @@ -52,7 +52,6 @@ def main(): # for i in trange(mu_range.shape[0]): for i in trange(effective_mu_range.shape[0]): plate_mu = 0.5 * effective_mu_range[i] / (1 - effective_mu_range[i]/(2 * tray_mu)) - # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) # modified_mass_value = ' %.1f ' % (mass_range[i]) # modified_real_mu_value = '%.2f' % (mu_range[i]) diff --git a/bindings/pydairlib/franka/franka_env.py b/bindings/pydairlib/franka/franka_env.py index fae4dac59c..bc8bad0b32 100644 --- a/bindings/pydairlib/franka/franka_env.py +++ b/bindings/pydairlib/franka/franka_env.py @@ -6,7 +6,7 @@ from pydairlib.systems.robot_lcm_systems import * from pydairlib.lcm.lcm_trajectory import * import pydrake.systems.lcm as mut - +from load_c3_options import load_c3_options import dairlib @@ -18,56 +18,7 @@ def main(): sim_params = yaml_load(filename=sim_params_file) lcm_params = yaml_load(filename=lcm_params_file) - c3_params = yaml_load(filename=c3_params_file) - c3_options_file = c3_params['c3_options_file'][c3_params['scene_index']] - c3_options_dict = yaml_load(filename=c3_options_file) - c3_options = C3Options() - c3_options.admm_iter = c3_options_dict['admm_iter'] - c3_options.rho = c3_options_dict['rho'] - c3_options.rho_scale = c3_options_dict['rho_scale'] - c3_options.num_threads = c3_options_dict['num_threads'] - c3_options.delta_option = c3_options_dict['delta_option'] - c3_options.projection_type = c3_options_dict['projection_type'] - c3_options.contact_model = c3_options_dict['contact_model'] - c3_options.warm_start = c3_options_dict['warm_start'] - c3_options.use_predicted_x0 = c3_options_dict['use_predicted_x0'] - c3_options.solve_time_filter_alpha = c3_options_dict['solve_time_filter_alpha'] - c3_options.publish_frequency = c3_options_dict['publish_frequency'] - c3_options.world_x_limits = c3_options_dict['world_x_limits'] - c3_options.world_y_limits = c3_options_dict['world_y_limits'] - c3_options.world_z_limits = c3_options_dict['world_z_limits'] - c3_options.u_horizontal_limits = c3_options_dict['u_horizontal_limits'] - c3_options.u_vertical_limits = c3_options_dict['u_vertical_limits'] - c3_options.workspace_margins = c3_options_dict['workspace_margins'] - c3_options.N = c3_options_dict['N'] - c3_options.gamma = c3_options_dict['gamma'] - c3_options.gamma = c3_options_dict['gamma'] - c3_options.q_vector = c3_options_dict['q_vector'] - c3_options.r_vector = c3_options_dict['r_vector'] - c3_options.g_x = c3_options_dict['g_x'] - c3_options.g_gamma = c3_options_dict['g_gamma'] - c3_options.g_lambda_n = c3_options_dict['g_lambda_n'] - c3_options.g_lambda_t = c3_options_dict['g_lambda_t'] - c3_options.g_lambda = c3_options_dict['g_lambda'] - c3_options.g_u = c3_options_dict['g_u'] - c3_options.u_x = c3_options_dict['u_x'] - c3_options.u_gamma = c3_options_dict['u_gamma'] - c3_options.u_lambda_n = c3_options_dict['u_lambda_n'] - c3_options.u_lambda_t = c3_options_dict['u_lambda_t'] - c3_options.u_lambda = c3_options_dict['u_lambda'] - c3_options.u_u = c3_options_dict['u_u'] - c3_options.gamma = c3_options_dict['gamma'] - c3_options.mu = c3_options_dict['mu'] - c3_options.dt = c3_options_dict['dt'] - c3_options.solve_dt = c3_options_dict['solve_dt'] - c3_options.num_friction_directions = c3_options_dict['num_friction_directions'] - c3_options.num_contacts = c3_options_dict['num_contacts'] - c3_options.Q = c3_options_dict['w_Q'] * np.diag(np.array(c3_options_dict['q_vector'])) - c3_options.R = c3_options_dict['w_R'] * np.diag(np.array(c3_options_dict['r_vector'])) - g_vec = np.hstack((c3_options_dict['g_x'], c3_options_dict['g_lambda'], c3_options_dict['g_u'])) - u_vec = np.hstack((c3_options_dict['u_x'], c3_options_dict['u_lambda'], c3_options_dict['u_u'])) - c3_options.G = c3_options_dict['w_G'] * np.diag(g_vec) - c3_options.U = c3_options_dict['w_U'] * np.diag(u_vec) + c3_options = load_c3_options(c3_params_file) lcm = DrakeLcm("udpm://239.255.76.67:7667?ttl=0") builder = DiagramBuilder() @@ -102,8 +53,6 @@ def main(): T_S2_W) plant.Finalize() - - osc_controller = builder.AddSystem(FrankaOSCControllerDiagram( "examples/franka/parameters/franka_osc_controller_params.yaml", "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) @@ -126,6 +75,20 @@ def main(): # drake::systems::TriggerTypeSet( # {drake::systems::TriggerType::kForced}))); + parameters = 2 * np.random.random(5) - 1 # center around 0. [-1, 1] + print(parameters) + c3_options.publish_frequency = (parameters[0] * 5) + 25 + c3_options.Q = (1 + 0.5 * parameters[1]) * c3_options.Q + c3_options.R = (1 + 0.5 * parameters[2]) * c3_options.R + c3_options.G = (1 + 0.5 * parameters[3]) * c3_options.G + c3_options.U = (1 + 0.5 * parameters[4]) * c3_options.U + scales = np.array([(parameters[0] * 5), + (1 + 0.5 * parameters[1]), + (1 + 0.5 * parameters[2]), + (1 + 0.5 * parameters[3]), + (1 + 0.5 * parameters[4])]) + print(scales) + passthrough = builder.AddSystem(SubvectorPassThrough(8, 0, 7)) tray_state_sender = builder.AddSystem(ObjectStateSender(plant, tray_index)) franka_state_sender = builder.AddSystem(RobotOutputSender(plant, franka_index, False, False)) diff --git a/bindings/pydairlib/franka/load_c3_options.py b/bindings/pydairlib/franka/load_c3_options.py new file mode 100644 index 0000000000..706e2d163e --- /dev/null +++ b/bindings/pydairlib/franka/load_c3_options.py @@ -0,0 +1,57 @@ +from pydairlib.franka.controllers import C3Options +import numpy as np +from pydrake.common.yaml import yaml_load + + +def load_c3_options(c3_params_file): + c3_params = yaml_load(filename=c3_params_file) + c3_options_file = c3_params['c3_options_file'][c3_params['scene_index']] + c3_options_dict = yaml_load(filename=c3_options_file) + c3_options = C3Options() + c3_options.admm_iter = c3_options_dict['admm_iter'] + c3_options.rho = c3_options_dict['rho'] + c3_options.rho_scale = c3_options_dict['rho_scale'] + c3_options.num_threads = c3_options_dict['num_threads'] + c3_options.delta_option = c3_options_dict['delta_option'] + c3_options.projection_type = c3_options_dict['projection_type'] + c3_options.contact_model = c3_options_dict['contact_model'] + c3_options.warm_start = c3_options_dict['warm_start'] + c3_options.use_predicted_x0 = c3_options_dict['use_predicted_x0'] + c3_options.solve_time_filter_alpha = c3_options_dict['solve_time_filter_alpha'] + c3_options.publish_frequency = c3_options_dict['publish_frequency'] + c3_options.world_x_limits = c3_options_dict['world_x_limits'] + c3_options.world_y_limits = c3_options_dict['world_y_limits'] + c3_options.world_z_limits = c3_options_dict['world_z_limits'] + c3_options.u_horizontal_limits = c3_options_dict['u_horizontal_limits'] + c3_options.u_vertical_limits = c3_options_dict['u_vertical_limits'] + c3_options.workspace_margins = c3_options_dict['workspace_margins'] + c3_options.N = c3_options_dict['N'] + c3_options.gamma = c3_options_dict['gamma'] + c3_options.gamma = c3_options_dict['gamma'] + c3_options.q_vector = c3_options_dict['q_vector'] + c3_options.r_vector = c3_options_dict['r_vector'] + c3_options.g_x = c3_options_dict['g_x'] + c3_options.g_gamma = c3_options_dict['g_gamma'] + c3_options.g_lambda_n = c3_options_dict['g_lambda_n'] + c3_options.g_lambda_t = c3_options_dict['g_lambda_t'] + c3_options.g_lambda = c3_options_dict['g_lambda'] + c3_options.g_u = c3_options_dict['g_u'] + c3_options.u_x = c3_options_dict['u_x'] + c3_options.u_gamma = c3_options_dict['u_gamma'] + c3_options.u_lambda_n = c3_options_dict['u_lambda_n'] + c3_options.u_lambda_t = c3_options_dict['u_lambda_t'] + c3_options.u_lambda = c3_options_dict['u_lambda'] + c3_options.u_u = c3_options_dict['u_u'] + c3_options.gamma = c3_options_dict['gamma'] + c3_options.mu = c3_options_dict['mu'] + c3_options.dt = c3_options_dict['dt'] + c3_options.solve_dt = c3_options_dict['solve_dt'] + c3_options.num_friction_directions = c3_options_dict['num_friction_directions'] + c3_options.num_contacts = c3_options_dict['num_contacts'] + c3_options.Q = c3_options_dict['w_Q'] * np.diag(np.array(c3_options_dict['q_vector'])) + c3_options.R = c3_options_dict['w_R'] * np.diag(np.array(c3_options_dict['r_vector'])) + g_vec = np.hstack((c3_options_dict['g_x'], c3_options_dict['g_lambda'], c3_options_dict['g_u'])) + u_vec = np.hstack((c3_options_dict['u_x'], c3_options_dict['u_lambda'], c3_options_dict['u_u'])) + c3_options.G = c3_options_dict['w_G'] * np.diag(g_vec) + c3_options.U = c3_options_dict['w_U'] * np.diag(u_vec) + return c3_options diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index 2d54a947eb..844bc3eddf 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -1,6 +1,6 @@ import lcm -def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_callback, *args, +def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_callback, print, *args, **kwargs): """ Parses an LCM log and returns data as specified by a callback function @@ -36,7 +36,7 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca else: data_to_process[event.channel] = \ [lcm_channels[event.channel].decode(event.data)] - if event.eventnum % 50000 == 0: + if print and event.eventnum % 50000 == 0: print(f'processed {(event.timestamp - t) * 1e-6:.1f}' f' seconds of log data') if 0 < duration <= (event.timestamp - t) * 1e-6: From 067ff4856888d68ba4e10ad192bed162bb8fbbe9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 26 Mar 2024 14:13:40 -0400 Subject: [PATCH 668/758] minor changes --- .../parameter_study_analysis.py | 6 +- .../parameter_study_config.yaml | 4 +- .../run_tray_parameter_study.py | 195 +++++++++--------- bindings/pydairlib/franka/BUILD.bazel | 12 ++ bindings/pydairlib/franka/franka_env.py | 56 +++-- ...ions.py => franka_env_helper_functions.py} | 26 +++ bindings/pydairlib/franka/generate_dataset.py | 53 +++++ .../franka/parameters/dataset_params.yaml | 1 + .../diagrams/franka_osc_controller_diagram.cc | 7 +- examples/franka/franka_osc_controller.cc | 7 +- .../parameters/franka_osc_controller_params.h | 2 +- .../franka/parameters/franka_sim_params.yaml | 4 +- .../franka/systems/end_effector_trajectory.cc | 5 +- .../franka/systems/end_effector_trajectory.h | 2 +- .../plate_end_effector_parameter_sweep.urdf | 2 +- solvers/c3.cc | 4 +- .../osc/operational_space_control.cc | 13 +- 17 files changed, 243 insertions(+), 156 deletions(-) rename bindings/pydairlib/franka/{load_c3_options.py => franka_env_helper_functions.py} (68%) create mode 100644 bindings/pydairlib/franka/generate_dataset.py create mode 100644 bindings/pydairlib/franka/parameters/dataset_params.yaml diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py index e4d9f7054b..0e5aab7237 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_analysis.py @@ -92,7 +92,7 @@ def load_lcm_logs(): print(successes) all_successes[i] = successes # np.save('target_successes_23', all_successes ) - np.save('target_successes_03_25', all_successes ) + np.save('target_successes_03_26', all_successes ) def plot_logs(): all_successes = np.load('target_successes_03_25.npy') @@ -123,8 +123,8 @@ def plot_logs(): plt.show() def main(): - # load_lcm_logs() - plot_logs() + load_lcm_logs() + # plot_logs() diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index 57d9868ef2..7a58d2e60c 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -1,9 +1,9 @@ trajectory_path: /home/yangwill/workspace/dairlib/examples/Cassie/saved_trajectories/ gains_path: examples/franka/parameters/ model_path: examples/franka/urdf/ -results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/03_25_24/parameter_study/ +results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/03_26_24/parameter_study/ #results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/01_31_24/parameter_study/ -processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/03_25_24/parameter_study/data/ +processed_results_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/logs/2024/03_26_24/parameter_study/data/ sim_cmd: bazel-bin/examples/franka/franka_sim osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller diff --git a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py index e103582c06..141ba33efe 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py +++ b/bindings/pydairlib/analysis/tray_balance_study/run_tray_parameter_study.py @@ -6,101 +6,106 @@ import numpy as np import yaml + + def main(): - config_file = 'parameter_study_config.yaml' - sim_time = 20.0 - cooldown_time = 10.0 - start_time = 0 - realtime_rate = 1.0 - num_trials = 5 - c3_start_up_time = 1.0 - sim_run_time = sim_time / realtime_rate - controller_startup_time = 0.1 - - with open('bindings/pydairlib/analysis/tray_balance_study/' + config_file) as f: - filedata = f.read() - config = yaml.load(filedata) - - # Add an extra second to the runtime of the simulator process to account for start up and stopping time - - lcm_logger_cmd = '' - publisher = lcm.LCM() - - # parameter = 'mu_c3' - # parameter = 'mass_real' - parameter = config['parameter'][2] - - nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' - # nominal_real_mu_value = '0.4' - nominal_real_mu_value = '' - nominal_tray_mass = '1' - - # mu_range = np.arange(0.3, 0.8, 0.05) - # mass_range = np.arange(0.5, 2.0, 0.05) - effective_mu_range = np.arange(0.1, 0.71, 0.1) - tray_mu = 0.4 - - initial_radio_msg = dairlib.lcmt_radio_out() - start_c3_radio_msg = dairlib.lcmt_radio_out() - initial_radio_msg.channel[13] = 1 - initial_radio_msg.channel[11] = 0 - initial_radio_msg.channel[14] = 1 - start_c3_radio_msg.channel[13] = 1 - start_c3_radio_msg.channel[11] = 0 - start_c3_radio_msg.channel[14] = 0 - - # for i in trange(mu_range.shape[0]): - for i in trange(effective_mu_range.shape[0]): - plate_mu = 0.5 * effective_mu_range[i] / (1 - effective_mu_range[i]/(2 * tray_mu)) - # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) - # modified_mass_value = ' %.1f ' % (mass_range[i]) - # modified_real_mu_value = '%.2f' % (mu_range[i]) - modified_real_mu_value = '' % (plate_mu) - - # f = open(gains_path + gain_filename, 'r') - f = open(config['model_path'] + config['nominal_model_filename'], 'r') - - filedata = f.read() - f.close() - # newdata = filedata.replace(nominal_mu_value, modified_mu_value) - newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) - # newdata = filedata.replace(nominal_tray_mass, modified_mass_value) - - # f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') - f = open(config['model_path'] + config['modified_model_filename'], 'w') - print(config['model_path'] + config['modified_model_filename']) - f.write(newdata) - f.close() - if parameter == 'mass_real': - fix_inertia_process = subprocess.Popen(config['fix_inertia_cmd'].split(' ')) - time.sleep(1.0) - - - for j in trange(num_trials): - log_path = config['results_folder'] + parameter + '/simlog-' + '%02d_%1d' % (i, j) - lcm_logger_cmd = ['lcm-logger', - '-f', - '%s' % log_path, - ] - - osc_process = subprocess.Popen(config['osc_cmd']) - c3_process = subprocess.Popen(config['c3_cmd']) - sim_process = subprocess.Popen(config['sim_cmd']) - time.sleep(controller_startup_time) - publisher.publish("RADIO", initial_radio_msg.encode()) - logger_process = subprocess.Popen(lcm_logger_cmd) - time.sleep(c3_start_up_time) - publisher.publish("RADIO", start_c3_radio_msg.encode()) - time.sleep(sim_run_time) - osc_process.kill() - c3_process.kill() - sim_process.kill() - logger_process.kill() - time.sleep(cooldown_time) + config_file = 'parameter_study_config.yaml' + sim_time = 20.0 + cooldown_time = 10.0 + start_time = 0 + realtime_rate = 1.0 + num_trials = 10 + c3_start_up_time = 1.0 + sim_run_time = sim_time / realtime_rate + controller_startup_time = 0.1 + + with open('bindings/pydairlib/analysis/tray_balance_study/' + config_file) as f: + filedata = f.read() + config = yaml.load(filedata) + + # Add an extra second to the runtime of the simulator process to account for start up and stopping time + + lcm_logger_cmd = '' + publisher = lcm.LCM() + + # parameter = 'mu_c3' + # parameter = 'mass_real' + parameter = config['parameter'][2] + + nominal_mu_value = 'mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1]' + # nominal_real_mu_value = '0.4' + nominal_real_mu_value = '' + nominal_tray_mass = '1' + + # mu_range = np.arange(0.3, 0.8, 0.05) + # mass_range = np.arange(0.5, 2.0, 0.05) + effective_mu_range = np.arange(0.1, 0.71, 0.1) + tray_mu = 0.4 + + initial_radio_msg = dairlib.lcmt_radio_out() + start_c3_radio_msg = dairlib.lcmt_radio_out() + initial_radio_msg.channel[13] = 1 + initial_radio_msg.channel[11] = 0 + initial_radio_msg.channel[14] = 1 + start_c3_radio_msg.channel[13] = 1 + start_c3_radio_msg.channel[11] = 0 + start_c3_radio_msg.channel[14] = 0 + + # for i in trange(mu_range.shape[0]): + for i in trange(effective_mu_range.shape[0]): + plate_mu = 0.5 * effective_mu_range[i] / (1 - effective_mu_range[i] / (2 * tray_mu)) + # modified_mu_value = 'mu: [%.2f, %.2f, %.2f, 0.1, 0.1, 0.1, 0.1]' % (mu_range[i], mu_range[i], mu_range[i]) + # modified_mass_value = ' %.1f ' % (mass_range[i]) + # modified_real_mu_value = '%.2f' % (mu_range[i]) + modified_real_mu_value = '' % (plate_mu) + + # f = open(gains_path + gain_filename, 'r') + f = open(config['model_path'] + config['nominal_model_filename'], 'r') + + filedata = f.read() + f.close() + # newdata = filedata.replace(nominal_mu_value, modified_mu_value) + newdata = filedata.replace(nominal_real_mu_value, modified_real_mu_value) + # newdata = filedata.replace(nominal_tray_mass, modified_mass_value) + + # f = open(config['gains_path'] + config['modified_c3_gain_filename.yaml'], 'w') + f = open(config['model_path'] + config['modified_model_filename'], 'w') + f.write(newdata) + f.close() + if parameter == 'mass_real': + fix_inertia_process = subprocess.Popen(config['fix_inertia_cmd'].split(' ')) + time.sleep(1.0) + + for j in trange(num_trials): + log_path = config['results_folder'] + parameter + '/simlog-' + '%02d_%1d' % (i, j) + lcm_logger_cmd = ['lcm-logger', + '-f', + '%s' % log_path, + ] + + osc_process = subprocess.Popen(config['osc_cmd'], stdout=subprocess.DEVNULL, + stderr=subprocess.STDOUT) + c3_process = subprocess.Popen(config['c3_cmd'], stdout=subprocess.DEVNULL, + stderr=subprocess.STDOUT) + sim_process = subprocess.Popen(config['sim_cmd'], stdout=subprocess.DEVNULL, + stderr=subprocess.STDOUT) + time.sleep(controller_startup_time) + publisher.publish("RADIO", initial_radio_msg.encode()) + logger_process = subprocess.Popen(lcm_logger_cmd, stdout=subprocess.DEVNULL, + stderr=subprocess.STDOUT) + time.sleep(c3_start_up_time) + publisher.publish("RADIO", start_c3_radio_msg.encode()) + time.sleep(sim_run_time) + osc_process.kill() + c3_process.kill() + sim_process.kill() + logger_process.kill() + time.sleep(cooldown_time) + if __name__ == "__main__": - main() - # construct_success_plot() - # convert_logs_to_costs() - # plot_success() - # plot_costs() + main() + # construct_success_plot() + # convert_logs_to_costs() + # plot_success() + # plot_costs() diff --git a/bindings/pydairlib/franka/BUILD.bazel b/bindings/pydairlib/franka/BUILD.bazel index 39b0f12f2c..90a7620fcf 100644 --- a/bindings/pydairlib/franka/BUILD.bazel +++ b/bindings/pydairlib/franka/BUILD.bazel @@ -45,6 +45,18 @@ py_binary( ], ) +py_binary( + name = "generate_dataset", + srcs = ["generate_dataset.py"], + data = [ + ":parameters/dataset_params.yaml", + ], + deps = [ + ":franka_env", + "@drake//bindings/pydrake", + ], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") diff --git a/bindings/pydairlib/franka/franka_env.py b/bindings/pydairlib/franka/franka_env.py index bc8bad0b32..28c2a879c1 100644 --- a/bindings/pydairlib/franka/franka_env.py +++ b/bindings/pydairlib/franka/franka_env.py @@ -6,11 +6,11 @@ from pydairlib.systems.robot_lcm_systems import * from pydairlib.lcm.lcm_trajectory import * import pydrake.systems.lcm as mut -from load_c3_options import load_c3_options +from franka_env_helper_functions import * import dairlib -def main(): +def run_sim(intrinsics, gains): osc_params_file = "examples/franka/parameters/franka_osc_controller_params.yaml" c3_params_file = "examples/franka/parameters/franka_c3_controller_params.yaml" lcm_params_file = "examples/franka/parameters/lcm_channels_simulation.yaml" @@ -61,33 +61,19 @@ def main(): "examples/franka/parameters/franka_c3_controller_params.yaml", c3_options, "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) - # c3_publish_frequency = c3_options.publish_frequency - # placeholder_trajectory = dairlib.lcmt_timestamped_saved_traj() - # a = Value(placeholder_trajectory) - # discrete_time_delay = builder.AddSystem( - # DiscreteTimeDelay(1.0 / c3_publish_frequency, 1, Value(placeholder_trajectory))) - - # state_pub =builder.AddSystem(LcmPublisherSystem.Make(lcm_params['franka_state_channel'], lcm_type=dairlib.lcmt_robot_output, - # lcm=lcm, publish_triggers=TriggerType.kForced, use_cpp_serializer=True)) - # tray_state_pub = - # builder.AddSystem(LcmPublisherSystem::Make( - # lcm_channel_params.tray_state_channel, &lcm, - # drake::systems::TriggerTypeSet( - # {drake::systems::TriggerType::kForced}))); - - parameters = 2 * np.random.random(5) - 1 # center around 0. [-1, 1] - print(parameters) - c3_options.publish_frequency = (parameters[0] * 5) + 25 - c3_options.Q = (1 + 0.5 * parameters[1]) * c3_options.Q - c3_options.R = (1 + 0.5 * parameters[2]) * c3_options.R - c3_options.G = (1 + 0.5 * parameters[3]) * c3_options.G - c3_options.U = (1 + 0.5 * parameters[4]) * c3_options.U - scales = np.array([(parameters[0] * 5), - (1 + 0.5 * parameters[1]), - (1 + 0.5 * parameters[2]), - (1 + 0.5 * parameters[3]), - (1 + 0.5 * parameters[4])]) - print(scales) + # parameters = 2 * np.random.random(5) - 1 # center around 0. [-1, 1] + # print(parameters) + c3_options.publish_frequency = (gains[0] * 5) + 25 + c3_options.Q = (1 + 0.5 * gains[1]) * c3_options.Q + c3_options.R = (1 + 0.5 * gains[2]) * c3_options.R + c3_options.G = (1 + 0.5 * gains[3]) * c3_options.G + c3_options.U = (1 + 0.5 * gains[4]) * c3_options.U + scales = np.array([(gains[0] * 5), + (1 + 0.5 * gains[1]), + (1 + 0.5 * gains[2]), + (1 + 0.5 * gains[3]), + (1 + 0.5 * gains[4])]) + # print(scales) passthrough = builder.AddSystem(SubvectorPassThrough(8, 0, 7)) tray_state_sender = builder.AddSystem(ObjectStateSender(plant, tray_index)) @@ -147,10 +133,18 @@ def main(): simulator.Initialize() simulator.AdvanceTo(5.0) - sim_states = sim_state_logger.GetLog(logger_context) + sim_data = sim_state_logger.GetLog(logger_context) + sim_states = sim_data.data() + sim_times = sim_data.sample_times() + + # reward = compute_reward_sparse(sim_times, sim_states) + reward = compute_reward_mpc(sim_times, sim_states) + # print(reward) # print(sim_states.data().shape) # print(sim_states.sample_times().shape) + return reward, sim_states if __name__ == '__main__': - main() + reward, sim_states = run_sim(np.zeros(5), np.zeros(5)) + print(reward) diff --git a/bindings/pydairlib/franka/load_c3_options.py b/bindings/pydairlib/franka/franka_env_helper_functions.py similarity index 68% rename from bindings/pydairlib/franka/load_c3_options.py rename to bindings/pydairlib/franka/franka_env_helper_functions.py index 706e2d163e..04fcedfc90 100644 --- a/bindings/pydairlib/franka/load_c3_options.py +++ b/bindings/pydairlib/franka/franka_env_helper_functions.py @@ -1,7 +1,33 @@ from pydairlib.franka.controllers import C3Options import numpy as np from pydrake.common.yaml import yaml_load +from pydrake.all import * +def compute_reward_sparse(times, sim_states): + first_target = np.array([0.45, 0, 0.485]) + second_target = np.array([0.45, 0, 0.6]) + third_target = np.array([0.7, 0.0, 0.485]) + length = min(times.shape[0], times.shape[0]) + reached_first_target = np.any(np.all(np.isclose(sim_states[:, 7:10], second_target, atol=1e-3), axis=1)) + reached_second_target = np.any(np.all(np.isclose(sim_states[:, 7:10], third_target, atol=1e-3), axis=1)) + reached_third_target = reached_second_target and np.linalg.norm(sim_states[:length, 7:10] - sim_states[:length, 7:10], axis=1)[-1] < 0.1 + # return reached_first_target + reached_second_target + reached_third_target + return reached_first_target + reached_second_target + reached_third_target + +def compute_reward_mpc(times, sim_states): + first_target = np.array([0.45, 0, 0.485]) + second_target = np.array([0.45, 0, 0.6]) + third_target = np.array([0.7, 0.0, 0.485]) + neutral_orientation = Quaternion() + cumulative_cost = 0 + for i in range(times.shape[0]): + tray_pos = sim_states[11:14, i] + tray_orientation = sim_states[7:11, i] + cumulative_cost += np.linalg.norm(tray_pos - first_target) + angle_difference = Quaternion.multiply(neutral_orientation.conjugate(), Quaternion(tray_orientation)) + cumulative_cost += RotationMatrix(angle_difference).ToAngleAxis().angle() + cumulative_cost /= times.shape[0] + return cumulative_cost def load_c3_options(c3_params_file): c3_params = yaml_load(filename=c3_params_file) diff --git a/bindings/pydairlib/franka/generate_dataset.py b/bindings/pydairlib/franka/generate_dataset.py new file mode 100644 index 0000000000..d6f09ca0b9 --- /dev/null +++ b/bindings/pydairlib/franka/generate_dataset.py @@ -0,0 +1,53 @@ +from franka_env import * +from yaml import * +from datetime import datetime +import h5py + +# gains are controller params +# thetas/intrinsics are environment params +def generate_dataset(n_datapoints, + batch_size, + gains_to_randomize, + thetas_to_randomize, + high_level_folder): + assert n_datapoints == int(n_datapoints / batch_size) * batch_size + + num_batches = int(n_datapoints / (batch_size)) + # Each batch is associated with a single set of system intrinsic parameters + intrinsics = np.zeros((num_batches, len(thetas_to_randomize))) + # for each parameter vector, generate $batch_size random gains to evaluate + gains_to_test = np.zeros((num_batches, batch_size, len(gains_to_randomize))) + + subfolder = "occam_data" + datetime.now().strftime("%b_%d_%Y_%H%M") + "/" + if not os.path.exists(os.path.join(high_level_folder, subfolder)): + os.makedirs(os.path.join(high_level_folder, subfolder), exist_ok=True) + + with h5py.File(os.path.join(high_level_folder, subfolder, "dataset.hdf5"), 'w') as f: + # intrinsic vectors don't actually get used anywhere, but good to save for bookkeeping + f.create_dataset("intrinsics", shape=intrinsics.shape) + f.create_dataset("gains", shape=gains_to_test.shape) + # this system only has 1 performance metric, but in principle this could be any number + f.create_dataset("metrics", shape=(num_batches, batch_size, 1)) + # f.create_dataset("states", shape=(num_batches, batch_size, 1)) + for batch in range(num_batches): + # Generate a random intrinsic vector for this batch + # batch_intrinsic_obj = params_t.generate_random(thetas_to_randomize) + f["intrinsics"][batch, ...] = thetas_to_randomize + # robot = Branin(batch_intrinsic_obj, gains_to_randomize) + for point in range(batch_size): + # generate a random gain vector + # gain = BraninInputs.generate_random(gains_to_randomize).get_list()[gains_to_randomize] + gain = 2 * np.random.random(gains_to_randomize.shape[0]) - 1 # center around 0. [-1, 1] + # run the simulation and obtain the performance metrics + # metric = robot.evaluate_x(gain) + metric, states = run_sim(thetas_to_randomize, gain) + f["metrics"][batch, point] = metric + f["gains"][batch, point] = gain + # f["states"][batch, point] = states + print(f"finished batch {batch}") + + +if __name__ == '__main__': + hersh_dataset_params_file = 'bindings/pydairlib/franka/parameters/dataset_params.yaml' + params = yaml_load(filename=hersh_dataset_params_file) + generate_dataset(20, 5, np.ones(5), np.zeros(5), params['high_level_folder']) diff --git a/bindings/pydairlib/franka/parameters/dataset_params.yaml b/bindings/pydairlib/franka/parameters/dataset_params.yaml new file mode 100644 index 0000000000..77293d3cb3 --- /dev/null +++ b/bindings/pydairlib/franka/parameters/dataset_params.yaml @@ -0,0 +1 @@ +high_level_folder: /media/yangwill/backups/home/yangwill/Documents/research/projects/franka/occam/ diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index 0fea6bd739..93b2b7e89b 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -122,13 +122,10 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( auto osc_command_sender = builder.AddSystem(*plant_); auto end_effector_trajectory = - builder.AddSystem(); + builder.AddSystem(controller_params.neutral_position); auto passthrough = builder.AddSystem>(18); - VectorXd neutral_position = Eigen::Map( - controller_params.neutral_position.data(), - controller_params.neutral_position.size()); end_effector_trajectory->SetRemoteControlParameters( - neutral_position, controller_params.x_scale, controller_params.y_scale, + controller_params.neutral_position, controller_params.x_scale, controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = builder.AddSystem(); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 8f4c550442..d9a205575c 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -138,12 +138,9 @@ int DoMain(int argc, char* argv[]) { auto osc_command_sender = builder.AddSystem(plant); auto end_effector_trajectory = - builder.AddSystem(); - VectorXd neutral_position = Eigen::Map( - controller_params.neutral_position.data(), - controller_params.neutral_position.size()); + builder.AddSystem(controller_params.neutral_position); end_effector_trajectory->SetRemoteControlParameters( - neutral_position, controller_params.x_scale, controller_params.y_scale, + controller_params.neutral_position, controller_params.x_scale, controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = builder.AddSystem(); diff --git a/examples/franka/parameters/franka_osc_controller_params.h b/examples/franka/parameters/franka_osc_controller_params.h index 9b429d47f4..2c1b6215f4 100644 --- a/examples/franka/parameters/franka_osc_controller_params.h +++ b/examples/franka/parameters/franka_osc_controller_params.h @@ -16,7 +16,7 @@ struct FrankaControllerParams : OSCGains { bool enforce_acceleration_constraints; bool publish_debug_info; - std::vector neutral_position; + Eigen::VectorXd neutral_position; double x_scale; double y_scale; double z_scale; diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index de32033225..b920c7870a 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -9,7 +9,7 @@ visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 1 -visualize_drake_sim: true +visualize_drake_sim: false publish_efforts: true camera_pose: [[1.5, 0, 0.6], @@ -52,5 +52,5 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], visualize_workspace: false visualize_pose_trace: false visualize_center_of_mass_plan: true -visualize_c3_forces: false +visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index db6de776bb..d5b484304b 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -18,7 +18,7 @@ using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator() { +EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator(const Eigen::Vector3d& neutral_pose) { // Input/Output Setup PiecewisePolynomial pp = PiecewisePolynomial(); @@ -31,7 +31,7 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator() { this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) .get_index(); - PiecewisePolynomial empty_pp_traj(neutral_pose_); + PiecewisePolynomial empty_pp_traj(neutral_pose); Trajectory& traj_inst = empty_pp_traj; this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, &EndEffectorTrajectoryGenerator::CalcTraj); @@ -67,7 +67,6 @@ void EndEffectorTrajectoryGenerator::CalcTraj( } else { if (trajectory_input.value(0).isZero()) { } else { -// std::cout << "time difference: " << context.get_time() - trajectory_input.start_time() << std::endl; *casted_traj = *(PiecewisePolynomial*)dynamic_cast< const PiecewisePolynomial*>(&trajectory_input); } diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index 85b8b0d81e..550e850d5b 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -8,7 +8,7 @@ namespace dairlib { class EndEffectorTrajectoryGenerator : public drake::systems::LeafSystem { public: - EndEffectorTrajectoryGenerator(); + EndEffectorTrajectoryGenerator(const Eigen::Vector3d& neutral_pose); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_port_); diff --git a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf index 47c45e4458..18c5c1a817 100644 --- a/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf +++ b/examples/franka/urdf/plate_end_effector_parameter_sweep.urdf @@ -15,7 +15,7 @@ - + diff --git a/solvers/c3.cc b/solvers/c3.cc index c0c4776d71..31ec27eb58 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -192,7 +192,9 @@ void C3::UpdateTarget(const std::vector& x_des) { void C3::Solve(const VectorXd& x0) { VectorXd delta_init = VectorXd::Zero(n_ + m_ + k_); - delta_init.head(n_) = x0; + if (options_.delta_option == 1){ + delta_init.head(n_) = x0; + } std::vector delta(N_, delta_init); std::vector w(N_, VectorXd::Zero(n_ + m_ + k_)); vector Gv = G_; diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 688ea568ed..4392564e12 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -576,13 +576,14 @@ VectorXd OperationalSpaceControl::SolveQp( auto map_iterator = contact_indices_map_.find(fsm_state); if (map_iterator != contact_indices_map_.end()) { active_contact_set = map_iterator->second; - } else { - static const drake::logging::Warn log_once(const_cast( - (std::to_string(fsm_state) + - " is not a valid finite state machine state in OSC. This can happen " - "if there are modes with no active contacts.") - .c_str())); } +// else { +// static const drake::logging::Warn log_once(const_cast( +// (std::to_string(fsm_state) + +// " is not a valid finite state machine state in OSC. This can happen " +// "if there are modes with no active contacts.") +// .c_str())); +// } } // Update context From ddc05a12c1f55efc05de0a5cbf6e228dde499f1d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 28 Mar 2024 13:11:13 -0400 Subject: [PATCH 669/758] deterministic sim --- bindings/pydairlib/franka/franka_env.py | 24 +++--- .../franka/franka_env_helper_functions.py | 4 +- bindings/pydairlib/franka/generate_dataset.py | 2 +- .../diagrams/franka_c3_controller_diagram.cc | 77 ++++++++++--------- .../diagrams/franka_c3_controller_diagram.h | 2 +- 5 files changed, 53 insertions(+), 56 deletions(-) diff --git a/bindings/pydairlib/franka/franka_env.py b/bindings/pydairlib/franka/franka_env.py index 28c2a879c1..ea7223b290 100644 --- a/bindings/pydairlib/franka/franka_env.py +++ b/bindings/pydairlib/franka/franka_env.py @@ -53,6 +53,12 @@ def run_sim(intrinsics, gains): T_S2_W) plant.Finalize() + c3_options.publish_frequency = (gains[0] * 5) + 25 + c3_options.Q = (1 + 0.5 * gains[1]) * c3_options.Q + c3_options.R = (1 + 0.5 * gains[2]) * c3_options.R + c3_options.G = (1 + 0.5 * gains[3]) * c3_options.G + c3_options.U = (1 + 0.5 * gains[4]) * c3_options.U + osc_controller = builder.AddSystem(FrankaOSCControllerDiagram( "examples/franka/parameters/franka_osc_controller_params.yaml", "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) @@ -61,20 +67,6 @@ def run_sim(intrinsics, gains): "examples/franka/parameters/franka_c3_controller_params.yaml", c3_options, "examples/franka/parameters/lcm_channels_simulation.yaml", lcm)) - # parameters = 2 * np.random.random(5) - 1 # center around 0. [-1, 1] - # print(parameters) - c3_options.publish_frequency = (gains[0] * 5) + 25 - c3_options.Q = (1 + 0.5 * gains[1]) * c3_options.Q - c3_options.R = (1 + 0.5 * gains[2]) * c3_options.R - c3_options.G = (1 + 0.5 * gains[3]) * c3_options.G - c3_options.U = (1 + 0.5 * gains[4]) * c3_options.U - scales = np.array([(gains[0] * 5), - (1 + 0.5 * gains[1]), - (1 + 0.5 * gains[2]), - (1 + 0.5 * gains[3]), - (1 + 0.5 * gains[4])]) - # print(scales) - passthrough = builder.AddSystem(SubvectorPassThrough(8, 0, 7)) tray_state_sender = builder.AddSystem(ObjectStateSender(plant, tray_index)) franka_state_sender = builder.AddSystem(RobotOutputSender(plant, franka_index, False, False)) @@ -146,5 +138,7 @@ def run_sim(intrinsics, gains): if __name__ == '__main__': - reward, sim_states = run_sim(np.zeros(5), np.zeros(5)) + parameters = 2 * np.random.random(5) - 1 # center around 0. [-1, 1] + # reward, sim_states = run_sim(np.zeros(5), np.ones(5)) + reward, sim_states = run_sim(np.zeros(5), parameters) print(reward) diff --git a/bindings/pydairlib/franka/franka_env_helper_functions.py b/bindings/pydairlib/franka/franka_env_helper_functions.py index 04fcedfc90..ce01e8fff3 100644 --- a/bindings/pydairlib/franka/franka_env_helper_functions.py +++ b/bindings/pydairlib/franka/franka_env_helper_functions.py @@ -23,8 +23,10 @@ def compute_reward_mpc(times, sim_states): for i in range(times.shape[0]): tray_pos = sim_states[11:14, i] tray_orientation = sim_states[7:11, i] + tray_quat = Quaternion(tray_orientation / np.linalg.norm(tray_orientation)) cumulative_cost += np.linalg.norm(tray_pos - first_target) - angle_difference = Quaternion.multiply(neutral_orientation.conjugate(), Quaternion(tray_orientation)) + # tray_quat /= np.linalg.norm(tray_quat.wxyz()) + angle_difference = Quaternion.multiply(neutral_orientation.conjugate(), tray_quat) cumulative_cost += RotationMatrix(angle_difference).ToAngleAxis().angle() cumulative_cost /= times.shape[0] return cumulative_cost diff --git a/bindings/pydairlib/franka/generate_dataset.py b/bindings/pydairlib/franka/generate_dataset.py index d6f09ca0b9..1450d29d98 100644 --- a/bindings/pydairlib/franka/generate_dataset.py +++ b/bindings/pydairlib/franka/generate_dataset.py @@ -50,4 +50,4 @@ def generate_dataset(n_datapoints, if __name__ == '__main__': hersh_dataset_params_file = 'bindings/pydairlib/franka/parameters/dataset_params.yaml' params = yaml_load(filename=hersh_dataset_params_file) - generate_dataset(20, 5, np.ones(5), np.zeros(5), params['high_level_folder']) + generate_dataset(500 * 64, 64, np.ones(5), np.zeros(5), params['high_level_folder']) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index b75fda39f3..606b886163 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -60,7 +60,7 @@ using std::string; FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( const string& controller_settings, const C3Options c3_options, const string& lcm_channels, - drake::lcm::DrakeLcm* lcm) { + drake::lcm::DrakeLcm* lcm, bool publish_c3_debug) { this->set_name("FrankaC3Controller"); DiagramBuilder builder; @@ -292,43 +292,44 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( c3_output_sender->get_input_port_c3_intermediates()); - - auto actor_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_actor_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto object_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_object_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_output_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_debug_output_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_target_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_target_state_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_actual_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_actual_state_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_forces_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_force_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), - actor_trajectory_sender->get_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), - object_trajectory_sender->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_target_c3_state(), - c3_target_state_publisher->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), - c3_actual_state_publisher->get_input_port()); - builder.Connect(c3_output_sender->get_output_port_c3_debug(), - c3_output_publisher->get_input_port()); - builder.Connect(c3_output_sender->get_output_port_c3_force(), - c3_forces_publisher->get_input_port()); + if (publish_c3_debug){ + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + actor_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), + object_trajectory_sender->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_debug(), + c3_output_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_force(), + c3_forces_publisher->get_input_port()); + } diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.h b/examples/franka/diagrams/franka_c3_controller_diagram.h index 160a0eb6c6..4e0abb92c4 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.h +++ b/examples/franka/diagrams/franka_c3_controller_diagram.h @@ -25,7 +25,7 @@ class FrankaC3ControllerDiagram : public drake::systems::Diagram { /// @param[in] osqp_settings filepath containing the osqp settings. FrankaC3ControllerDiagram(const std::string& controller_settings, const C3Options c3_options, const std::string& lcm_channels, - drake::lcm::DrakeLcm* lcm); + drake::lcm::DrakeLcm* lcm, bool publish_c3_debug = false); /// @return the input port for the plant state. const drake::systems::InputPort& get_input_port_robot_state() const { From d68062bb26619d5d087ee99326638326b01634af Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 29 Mar 2024 13:38:39 -0400 Subject: [PATCH 670/758] setting option to allow ending on qp step --- bindings/pydairlib/franka/generate_dataset.py | 2 +- .../diagrams/franka_osc_controller_diagram.cc | 76 ++++++++++--------- .../franka_c3_options_side_supports.yaml | 5 +- .../franka_c3_options_translation.yaml | 3 + .../franka_c3_options_w_supports.yaml | 1 + .../franka_osc_controller_params.yaml | 2 +- solvers/c3.cc | 19 +++-- solvers/c3_options.h | 1 + 8 files changed, 63 insertions(+), 46 deletions(-) diff --git a/bindings/pydairlib/franka/generate_dataset.py b/bindings/pydairlib/franka/generate_dataset.py index 1450d29d98..f892686be0 100644 --- a/bindings/pydairlib/franka/generate_dataset.py +++ b/bindings/pydairlib/franka/generate_dataset.py @@ -50,4 +50,4 @@ def generate_dataset(n_datapoints, if __name__ == '__main__': hersh_dataset_params_file = 'bindings/pydairlib/franka/parameters/dataset_params.yaml' params = yaml_load(filename=hersh_dataset_params_file) - generate_dataset(500 * 64, 64, np.ones(5), np.zeros(5), params['high_level_folder']) + generate_dataset(50 * 64, 64, np.ones(5), np.zeros(5), params['high_level_folder']) diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index 93b2b7e89b..09904db905 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -24,9 +24,9 @@ #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" #include "systems/controllers/osc/operational_space_control.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "systems/primitives/radio_parser.h" #include "systems/trajectory_optimization/lcm_trajectory_systems.h" namespace dairlib { @@ -73,13 +73,13 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( "examples/franka/parameters/franka_osc_qp_settings.yaml")) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - plant_ = new drake::multibody::MultibodyPlant (0.0); + plant_ = new drake::multibody::MultibodyPlant(0.0); Parser parser(plant_, nullptr); parser.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); RigidTransform X_WI = RigidTransform::Identity(); - plant_->WeldFrames(plant_->world_frame(), plant_->GetFrameByName("panda_link0"), - X_WI); + plant_->WeldFrames(plant_->world_frame(), + plant_->GetFrameByName("panda_link0"), X_WI); if (!controller_params.end_effector_name.empty()) { drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels( @@ -87,10 +87,11 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( RigidTransform T_EE_W = RigidTransform(drake::math::RotationMatrix(), controller_params.tool_attachment_frame); - plant_->WeldFrames(plant_->GetFrameByName("panda_link7"), - plant_->GetFrameByName(controller_params.end_effector_name, - end_effector_index), - T_EE_W); + plant_->WeldFrames( + plant_->GetFrameByName("panda_link7"), + plant_->GetFrameByName(controller_params.end_effector_name, + end_effector_index), + T_EE_W); } else { std::cout << "OSC plant has been constructed with no end effector." << std::endl; @@ -99,34 +100,28 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( plant_->Finalize(); plant_context_ = plant_->CreateDefaultContext(); - auto state_receiver = builder.AddSystem(*plant_); + auto state_receiver = + builder.AddSystem(*plant_); auto end_effector_position_receiver = - builder.AddSystem( - "end_effector_position_target"); + builder.AddSystem( + "end_effector_position_target"); auto end_effector_force_receiver = builder.AddSystem( "end_effector_force_target"); auto end_effector_orientation_receiver = builder.AddSystem( "end_effector_orientation_target"); - auto franka_command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.franka_input_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto osc_command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.osc_channel, lcm, - TriggerTypeSet({TriggerType::kForced}))); auto franka_command_sender = builder.AddSystem(*plant_); auto osc_command_sender = builder.AddSystem(*plant_); auto end_effector_trajectory = - builder.AddSystem(controller_params.neutral_position); + builder.AddSystem( + controller_params.neutral_position); auto passthrough = builder.AddSystem>(18); end_effector_trajectory->SetRemoteControlParameters( - controller_params.neutral_position, controller_params.x_scale, controller_params.y_scale, - controller_params.z_scale); + controller_params.neutral_position, controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = builder.AddSystem(); end_effector_orientation_trajectory->SetTrackOrientation( @@ -136,12 +131,24 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( auto osc = builder.AddSystem( *plant_, *plant_, plant_context_.get(), plant_context_.get(), false); if (controller_params.publish_debug_info) { + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_input_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto osc_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_channel, lcm, + TriggerTypeSet({TriggerType::kForced}))); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.osc_debug_channel, lcm, TriggerTypeSet({TriggerType::kForced}))); builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(franka_command_sender->get_output_port(), + franka_command_pub->get_input_port()); + builder.Connect(osc_command_sender->get_output_port(), + osc_command_pub->get_input_port()); } auto end_effector_position_tracking_data = @@ -209,18 +216,13 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( franka_command_sender->get_input_port(0)); } -// builder.Connect(radio_to_vector->get_output_port(), -// passthrough->get_input_port()); builder.Connect(passthrough->get_output_port(), end_effector_trajectory->get_input_port_radio()); builder.Connect(passthrough->get_output_port(), end_effector_orientation_trajectory->get_input_port_radio()); builder.Connect(passthrough->get_output_port(), end_effector_force_trajectory->get_input_port_radio()); - builder.Connect(franka_command_sender->get_output_port(), - franka_command_pub->get_input_port()); - builder.Connect(osc_command_sender->get_output_port(), - osc_command_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_command(), osc_command_sender->get_input_port(0)); builder.Connect(state_receiver->get_output_port(0), @@ -241,13 +243,17 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( osc->get_input_port_tracking_data("end_effector_force")); // Publisher connections - franka_state_port_ = builder.ExportInput(state_receiver->get_input_port(), "lcmt_robot_output"); - end_effector_position_port_ = builder.ExportInput(end_effector_position_receiver->get_input_port(), - "end_effector_position: lcmt_timestamped_trajectory"); - end_effector_orientation_port_ = builder.ExportInput(end_effector_orientation_receiver->get_input_port(), - "end_effector_orientation: lcmt_timestamped_trajectory"); - end_effector_force_port_ = builder.ExportInput(end_effector_force_receiver->get_input_port(), - "end_effector_force: lcmt_timestamped_trajectory"); + franka_state_port_ = builder.ExportInput(state_receiver->get_input_port(), + "lcmt_robot_output"); + end_effector_position_port_ = + builder.ExportInput(end_effector_position_receiver->get_input_port(), + "end_effector_position: lcmt_timestamped_trajectory"); + end_effector_orientation_port_ = builder.ExportInput( + end_effector_orientation_receiver->get_input_port(), + "end_effector_orientation: lcmt_timestamped_trajectory"); + end_effector_force_port_ = + builder.ExportInput(end_effector_force_receiver->get_input_port(), + "end_effector_force: lcmt_timestamped_trajectory"); radio_port_ = builder.ExportInput(passthrough->get_input_port(), "raw_radio"); builder.ExportOutput(osc->get_output_port_osc_command(), "robot_input"); diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 1f119f2a3c..6ce2220ee1 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -8,9 +8,12 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'stewart_and_trinkle' contact_model: 'anitescu' -warm_start: false +warm_start: true use_predicted_x0: true +end_on_qp_step: false solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} +#publish_frequency : 0 +publish_frequency: 25 # Workspace Limits world_x_limits: [0.45, 0.65] diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/franka_c3_options_translation.yaml index 35344c13ac..56d1882767 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/franka_c3_options_translation.yaml @@ -10,7 +10,10 @@ contact_model: 'anitescu' #contact_model: 'stewart_and_trinkle' warm_start: true use_predicted_x0: false +end_on_qp_step: false solve_time_filter_alpha: 0.9 +#publish_frequency : 0 +publish_frequency: 25 # Workspace Limits world_x_limits: [0.4, 0.6] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index c8b4a3fc46..b20ba699fb 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -10,6 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true +end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible #publish_frequency : 0 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 92db6e9c4d..b0ffc4bfe3 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -23,7 +23,7 @@ end_effector_acceleration: 10 track_end_effector_orientation: false cancel_gravity_compensation: false enforce_acceleration_constraints: false -publish_debug_info: true +publish_debug_info: false W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/solvers/c3.cc b/solvers/c3.cc index 31ec27eb58..af0b02b53d 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -215,15 +215,18 @@ void C3::Solve(const VectorXd& x0) { vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); - *z_sol_ = delta; - z_sol_->at(0).segment(0, n_) = x0; - for (int i = 1; i < N_; ++i) { - z_sol_->at(i).segment(0, n_) = - A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + - D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); + if (!options_.end_with_qp_step){ + *z_sol_ = delta; + z_sol_->at(0).segment(0, n_) = x0; + for (int i = 1; i < N_; ++i) { + z_sol_->at(i).segment(0, n_) = + A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + + D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); + } + *w_sol_ = w; + *delta_sol_ = delta; } - *w_sol_ = w; - *delta_sol_ = delta; + } void C3::ADMMStep(const VectorXd& x0, vector* delta, diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 9a4f386536..0695cae492 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -14,6 +14,7 @@ struct C3Options { std::string contact_model; bool warm_start; bool use_predicted_x0; + bool end_with_qp_step; double solve_time_filter_alpha; double publish_frequency; From 62704e4b053a44c08cda10746a8b81b1f98c573a Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 30 Mar 2024 17:31:52 -0400 Subject: [PATCH 671/758] working on very slightly more expressive workspace constraints --- bindings/pydairlib/franka/controllers_py.cc | 4 +- examples/franka/franka_sim.cc | 25 ++++++---- examples/franka/franka_visualizer.cc | 16 +++++-- .../franka_c3_controller_params.yaml | 24 +++++----- .../franka_c3_options_side_supports.yaml | 10 ++-- .../franka_c3_options_w_supports.yaml | 16 ++++--- .../franka_osc_controller_params.yaml | 3 +- .../franka/parameters/franka_sim_params.h | 2 + .../franka/parameters/franka_sim_params.yaml | 24 ++++++---- examples/franka/urdf/center_support.urdf | 36 ++++++++++++++ solvers/c3.cc | 2 +- solvers/c3_options.h | 16 ++++--- systems/controllers/c3_controller.cc | 48 +++++++------------ 13 files changed, 137 insertions(+), 89 deletions(-) create mode 100644 examples/franka/urdf/center_support.urdf diff --git a/bindings/pydairlib/franka/controllers_py.cc b/bindings/pydairlib/franka/controllers_py.cc index d59e42872e..074a2fd55f 100644 --- a/bindings/pydairlib/franka/controllers_py.cc +++ b/bindings/pydairlib/franka/controllers_py.cc @@ -77,9 +77,7 @@ PYBIND11_MODULE(controllers, m) { .def_readwrite("use_predicted_x0", &C3Options::use_predicted_x0) .def_readwrite("solve_time_filter_alpha", &C3Options::solve_time_filter_alpha) .def_readwrite("publish_frequency", &C3Options::publish_frequency) - .def_readwrite("world_x_limits", &C3Options::world_x_limits) - .def_readwrite("world_y_limits", &C3Options::world_y_limits) - .def_readwrite("world_z_limits", &C3Options::world_z_limits) + .def_readwrite("world_x_limits", &C3Options::workspace_limits) .def_readwrite("u_horizontal_limits", &C3Options::u_horizontal_limits) .def_readwrite("u_vertical_limits", &C3Options::u_vertical_limits) .def_readwrite("workspace_margins", &C3Options::workspace_margins) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 295b02c5d8..ee1a1f2faa 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -98,22 +98,31 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( FindResourceOrThrow(sim_params.right_support_model))[0]; - RigidTransform T_S1_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.left_support_orientation), - sim_params.left_support_position); - RigidTransform T_S2_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.right_support_orientation), - sim_params.right_support_position); + drake::multibody::ModelInstanceIndex center_support_index = parser.AddModels( + FindResourceOrThrow(sim_params.center_support_model))[0]; + RigidTransform T_LS_W = + RigidTransform(drake::math::RollPitchYaw(sim_params.left_support_orientation), + sim_params.left_support_position); + RigidTransform T_RS_W = + RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), + sim_params.right_support_position); + RigidTransform T_CS_W = + RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), + 0.5 * (sim_params.left_support_position + sim_params.right_support_position)); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), - T_S1_W); + T_LS_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", right_support_index), - T_S2_W); + T_RS_W); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", center_support_index), + T_CS_W); const drake::geometry::GeometrySet& support_geom_set = plant.CollectRegisteredGeometries({ &plant.GetBodyByName("support", left_support_index), &plant.GetBodyByName("support", right_support_index), + &plant.GetBodyByName("support", center_support_index), }); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( {"supports", support_geom_set}, {"franka", franka_geom_set}); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 9a60a75cc2..87b3899258 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -103,18 +103,26 @@ int do_main(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( FindResourceOrThrow(sim_params.right_support_model))[0]; - RigidTransform T_S1_W = + drake::multibody::ModelInstanceIndex center_support_index = parser.AddModels( + FindResourceOrThrow(sim_params.center_support_model))[0]; + RigidTransform T_LS_W = RigidTransform(drake::math::RollPitchYaw(sim_params.left_support_orientation), sim_params.left_support_position); - RigidTransform T_S2_W = + RigidTransform T_RS_W = RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), sim_params.right_support_position); + RigidTransform T_CS_W = + RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), + 0.5 * (sim_params.left_support_position + sim_params.right_support_position)); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), - T_S1_W); + T_LS_W); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", right_support_index), - T_S2_W); + T_RS_W); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("support", center_support_index), + T_CS_W); } plant.Finalize(); diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 6b362beed5..86ac868c1f 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -13,17 +13,17 @@ left_support_model: examples/franka/urdf/support_point_contact.urdf right_support_model: examples/franka/urdf/support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.447] -right_support_position: [0.8, -0.15, 0.447] -left_support_orientation: [0.0, 0.0, 0.0] -right_support_orientation: [0.0, 0.0, 0.0] -#left_support_position: [0.4, 0.25, 0.450] -#right_support_position: [0.7, 0.25, 0.450] -#left_support_orientation: [0.0, 0.0, 1.57] -#right_support_orientation: [0.0, 0.0, 1.57] +#left_support_position: [0.8, 0.15, 0.447] +#right_support_position: [0.8, -0.15, 0.447] +#left_support_orientation: [0.0, 0.0, 0.0] +#right_support_orientation: [0.0, 0.0, 0.0] +left_support_position: [0.6178, 0.3299, 0.45 ] +right_support_position: [0.7678, 0.0701, 0.45 ] +left_support_orientation: [0. , 0. , 0.5236] +right_support_orientation: [0. , 0. , 0.5236] end_effector_thickness: 0.016 -scene_index: 1 +scene_index: 2 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan @@ -32,13 +32,13 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.55, -0.1, 0.49]] + [0.3897, 0.125, 0.49]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], - [0.55, -0.1, 0.6]] + [0.3897, 0.125, 0.6]] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], - [0.55, 0.15, 0.49]] + [0.6062, 0.25 , 0.49]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index 6ce2220ee1..fdf2c987e5 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -13,12 +13,12 @@ use_predicted_x0: true end_on_qp_step: false solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} #publish_frequency : 0 -publish_frequency: 25 +publish_frequency: 0 # Workspace Limits -world_x_limits: [0.45, 0.65] -world_y_limits: [-0.15, 0.05] -world_z_limits: [0.35, 0.65] +workspace_limits: [[0.866, 0.5, 0.0, 0.4, 0.6], + [-0.5, 0.866, 0.0, -0.1, 0.1], + [0.0, 0.0, 1.0, 0.35, 0.7]] workspace_margins: 0.05 u_horizontal_limits: [-10, 10] @@ -36,7 +36,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 # Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.15 # Penalty on all decision variables, assuming scalar w_U: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/franka_c3_options_w_supports.yaml index b20ba699fb..e1b5b760ea 100644 --- a/examples/franka/parameters/franka_c3_options_w_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_w_supports.yaml @@ -13,13 +13,15 @@ use_predicted_x0: true end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible -#publish_frequency : 0 -publish_frequency: 25 +publish_frequency : 0 +#publish_frequency: 25 -#Workspace Limits -world_x_limits: [0.4, 0.6] -world_y_limits: [-0.1, 0.1] -world_z_limits: [0.35, 0.7] +# End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], + [0.0, 1.0, 0.0, -0.1, 0.1], + [0.0, 0.0, 1.0, 0.35, 0.7]] +#world_y_limits: [-0.1, 0.1] +#world_z_limits: [0.35, 0.7] workspace_margins: 0.05 u_horizontal_limits: [-10, 10] @@ -37,7 +39,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 #Penalty on all decision variables, assuming scalar -w_G: 0.3 +w_G: 0.15 #Penalty on all decision variables, assuming scalar w_U: 0.1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index b0ffc4bfe3..7ea424283a 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -6,7 +6,8 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.55, 0, 0.45] +neutral_position: [0.5196, 0.1 , 0.45] +#neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index ff8edd3eb0..c49f727c4c 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -9,6 +9,7 @@ struct FrankaSimParams { std::string tray_model; std::string left_support_model; std::string right_support_model; + std::string center_support_model; double dt; double realtime_rate; @@ -49,6 +50,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(tray_model)); a->Visit(DRAKE_NVP(left_support_model)); a->Visit(DRAKE_NVP(right_support_model)); + a->Visit(DRAKE_NVP(center_support_model)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b920c7870a..b745e1f2c4 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -3,13 +3,14 @@ end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray.sdf left_support_model: examples/franka/urdf/support.urdf right_support_model: examples/franka/urdf/support.urdf +center_support_model: examples/franka/urdf/center_support.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 1 -visualize_drake_sim: false +scene_index: 2 +visualize_drake_sim: true publish_efforts: true camera_pose: [[1.5, 0, 0.6], @@ -20,13 +21,16 @@ camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.55]] tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.447] -right_support_position: [0.8, -0.15, 0.447] -left_support_orientation: [0.0, 0.0, 0.0] -right_support_orientation: [0.0, 0.0, 0.0] +#left_support_position: [0.8, 0.15, 0.447] +#right_support_position: [0.8, -0.15, 0.447] +#left_support_orientation: [0.0, 0.0, 0.0] +#right_support_orientation: [0.0, 0.0, 0.0] + +left_support_position: [0.6178, 0.3299, 0.45 ] +right_support_position: [0.7678, 0.0701, 0.45 ] +left_support_orientation: [0. , 0. , 0.5236] +right_support_orientation: [0. , 0. , 0.5236] -#left_support_position: [0.4, 0.25, 0.45] -#right_support_position: [0.7, 0.25, 0.45] #left_support_orientation: [0.0, 0.0, 1.57] #right_support_orientation: [0.0, 0.0, 1.57] @@ -36,7 +40,7 @@ world_x_limits: [[0.4, 0.6], [0.45, 0.65]] world_y_limits: [[-0.15, 0.15], [-0.1, 0.1], - [-0.15, 0.05]] + [-0.05, 0.3]] world_z_limits: [[0.35, 0.7], [0.35, 0.7], [0.35, 0.7]] @@ -47,7 +51,7 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], [1, 0, 0, 0, 0.7, 0.00, 0.485], - [1, 0, 0, 0, 0.55, 0.15, 0.515]] + [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ]] visualize_workspace: false visualize_pose_trace: false diff --git a/examples/franka/urdf/center_support.urdf b/examples/franka/urdf/center_support.urdf new file mode 100644 index 0000000000..42008679b7 --- /dev/null +++ b/examples/franka/urdf/center_support.urdf @@ -0,0 +1,36 @@ + + + + + + + + + + + + cod + + + + + + + + + + + cod + + + + + + + diff --git a/solvers/c3.cc b/solvers/c3.cc index af0b02b53d..5091769605 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -215,7 +215,7 @@ void C3::Solve(const VectorXd& x0) { vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); - if (!options_.end_with_qp_step){ + if (!options_.end_on_qp_step){ *z_sol_ = delta; z_sol_->at(0).segment(0, n_) = x0; for (int i = 1; i < N_; ++i) { diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 0695cae492..d9c208eb97 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -14,15 +14,16 @@ struct C3Options { std::string contact_model; bool warm_start; bool use_predicted_x0; - bool end_with_qp_step; + bool end_on_qp_step; double solve_time_filter_alpha; double publish_frequency; - std::vector world_x_limits; - std::vector world_y_limits; - std::vector world_z_limits; +// std::vector world_x_limits; +// std::vector world_y_limits; +// std::vector world_z_limits; std::vector u_horizontal_limits; std::vector u_vertical_limits; + std::vector workspace_limits; double workspace_margins; int N; @@ -76,12 +77,13 @@ struct C3Options { } a->Visit(DRAKE_NVP(warm_start)); a->Visit(DRAKE_NVP(use_predicted_x0)); + a->Visit(DRAKE_NVP(end_on_qp_step)); a->Visit(DRAKE_NVP(solve_time_filter_alpha)); a->Visit(DRAKE_NVP(publish_frequency)); - a->Visit(DRAKE_NVP(world_x_limits)); - a->Visit(DRAKE_NVP(world_y_limits)); - a->Visit(DRAKE_NVP(world_z_limits)); + a->Visit(DRAKE_NVP(workspace_limits)); +// a->Visit(DRAKE_NVP(world_y_limits)); +// a->Visit(DRAKE_NVP(world_z_limits)); a->Visit(DRAKE_NVP(u_horizontal_limits)); a->Visit(DRAKE_NVP(u_vertical_limits)); a->Visit(DRAKE_NVP(workspace_margins)); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index bb6d65b11c..e4a9f8cf96 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -87,25 +87,13 @@ C3Controller::C3Controller( c3_->SetOsqpSolverOptions(solver_options_); - // Set actor bounds, TODO(yangwill): move this out of here because it is task - // specific - for (int i : vector({0})) { + // Set actor bounds, + // TODO(yangwill): move this out of here because it is task specific + for (int i = 0; i < c3_options_.workspace_limits.size(); ++i) { Eigen::RowVectorXd A = VectorXd::Zero(n_x_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.world_x_limits[0], - c3_options_.world_x_limits[1], 1); - } - for (int i : vector({1})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_x_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.world_y_limits[0], - c3_options_.world_y_limits[1], 1); - } - for (int i : vector({2})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_x_); - A(i) = 1.0; - c3_->AddLinearConstraint(A, c3_options_.world_z_limits[0], - c3_options_.world_z_limits[1], 1); + A.segment(0, 3) = c3_options_.workspace_limits[i].segment(0, 3); + c3_->AddLinearConstraint(A, c3_options_.workspace_limits[i][3], + c3_options_.workspace_limits[i][4], 1); } for (int i : vector({0, 1})) { Eigen::RowVectorXd A = VectorXd::Zero(n_u_); @@ -212,18 +200,16 @@ drake::systems::EventStatus C3Controller::ComputePlan( std::vector(N_ + 1, x_des.value()); // Force Checking of Workspace Limits - DRAKE_DEMAND(lcs_x->get_data()[0] > - c3_options_.world_x_limits[0] - c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[0] < - c3_options_.world_x_limits[1] + c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[1] > - c3_options_.world_y_limits[0] - c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[1] < - c3_options_.world_y_limits[1] + c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[2] > - c3_options_.world_z_limits[0] - c3_options_.workspace_margins); - DRAKE_DEMAND(lcs_x->get_data()[2] < - c3_options_.world_z_limits[1] + c3_options_.workspace_margins); + for (int i = 0; i < c3_options_.workspace_limits.size(); ++i) { + DRAKE_DEMAND(lcs_x->get_data().segment(0, 3).transpose() * + c3_options_.workspace_limits[i].segment(0, 3) > + c3_options_.workspace_limits[i][3] - + c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x->get_data().segment(0, 3).transpose() * + c3_options_.workspace_limits[i].segment(0, 3) < + c3_options_.workspace_limits[i][4] + + c3_options_.workspace_margins); + } c3_->UpdateLCS(lcs); c3_->UpdateTarget(x_desired); @@ -237,7 +223,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( mutable_solve_time[0] = (1 - solve_time_filter_constant_) * solve_time + solve_time_filter_constant_ * mutable_solve_time[0]; - if (c3_options_.publish_frequency > 0){ + if (c3_options_.publish_frequency > 0) { solve_time = 1.0 / c3_options_.publish_frequency; mutable_solve_time[0] = solve_time; } From 70cae27ecdc98607f1dfa5382a4245cedcd226e0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 31 Mar 2024 15:06:52 -0400 Subject: [PATCH 672/758] task at different angle mostly works, workspace limits seem off still --- examples/franka/franka_visualizer.cc | 2 +- .../franka_c3_controller_params.yaml | 6 +- .../franka_c3_options_side_supports.yaml | 16 ++--- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 + .../franka/systems/plate_balancing_target.cc | 12 ++-- .../lcm_visualization_systems.cc | 63 ++++++++++--------- 7 files changed, 55 insertions(+), 48 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 87b3899258..20fe3fd642 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -229,7 +229,7 @@ int do_main(int argc, char* argv[]) { if (sim_params.visualize_c3_state){ auto c3_target_drawer = - builder.AddSystem(meshcat, true, true); + builder.AddSystem(meshcat, true, false); builder.Connect(c3_state_actual_sub->get_output_port(), c3_target_drawer->get_input_port_c3_state_actual()); builder.Connect(c3_state_target_sub->get_output_port(), diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 86ac868c1f..96be125f07 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -32,13 +32,13 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.3897, 0.125, 0.49]] + [0.3897, 0.025, 0.49]] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], - [0.3897, 0.125, 0.6]] + [0.3897, 0.025, 0.6]] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], - [0.6062, 0.25 , 0.49]] + [0.6062, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index fdf2c987e5..e9f8678c05 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -17,7 +17,7 @@ publish_frequency: 0 # Workspace Limits workspace_limits: [[0.866, 0.5, 0.0, 0.4, 0.6], - [-0.5, 0.866, 0.0, -0.1, 0.1], + [-0.5 , 0.866, 0.0, -0.2, -0.0], [0.0, 0.0, 1.0, 0.35, 0.7]] workspace_margins: 0.05 @@ -32,21 +32,21 @@ num_contacts: 7 N: 5 gamma: 1.0 # discount factor on MPC costs -# matrix scaling +#matrix scaling w_Q: 50 w_R: 50 -# Penalty on all decision variables, assuming scalar +#Penalty on all decision variables, assuming scalar w_G: 0.15 -# Penalty on all decision variables, assuming scalar +#Penalty on all decision variables, assuming scalar w_U: 0.1 -# State Tracking Error, assuming diagonal +#State Tracking Error, assuming diagonal q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 15, 10, 10, 1, 5, 5, 5] -# Penalty on efforts, assuming diagonal +#Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] -# Penalty on matching projected variables +#Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] @@ -54,7 +54,7 @@ g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] -# Penalty on matching the QP variables +#Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 7ea424283a..22a57769dc 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -6,7 +6,7 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.5196, 0.1 , 0.45] +neutral_position: [0.4763, 0.075 , 0.45] #neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b745e1f2c4..27dfc22ac5 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -21,6 +21,8 @@ camera_target: [[0.5, 0, 0.5], [0.5, 0, 0.55]] tool_attachment_frame: [0, 0, 0.107] + + #left_support_position: [0.8, 0.15, 0.447] #right_support_position: [0.8, -0.15, 0.447] #left_support_orientation: [0.0, 0.0, 0.0] diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 1cadcdde40..7fa0469b43 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -124,12 +124,12 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( } end_effector_position[2] -= end_effector_thickness_; // place end effector below tray - if (end_effector_position[0] > 0.6) { - end_effector_position[0] = 0.6; // keep it within the workspace - } - if (end_effector_position[1] > 0.05) { - end_effector_position[1] = 0.05; // keep it within the workspace - } +// if (end_effector_position[0] > 0.6) { +// end_effector_position[0] = 0.6; // keep it within the workspace +// } +// if (end_effector_position[1] > 0.05) { +// end_effector_position[1] = 0.05; // keep it within the workspace +// } if (radio_out->value()[13] > 0) { end_effector_position(0) += radio_out->value()[0] * x_scale_; end_effector_position(1) += radio_out->value()[1] * y_scale_; diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index 37d6c4c86a..14e43a1293 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -90,9 +90,9 @@ LcmPoseDrawer::LcmPoseDrawer( this->set_name("LcmPoseDrawer: " + translation_trajectory_name); Eigen::VectorXd alpha_scale; - if (add_transparency){ + if (add_transparency) { alpha_scale = 1.0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4); - }else{ + } else { alpha_scale = 1.0 * VectorXd::Ones(N_ - 1); } @@ -154,7 +154,8 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], lcm_translation_traj.time_vector.tail(1)[0]); for (int i = 0; i < object_poses.cols(); ++i) { - object_poses.col(i) << orientation_trajectory.value(translation_breaks(i + 1)), + object_poses.col(i) << orientation_trajectory.value( + translation_breaks(i + 1)), translation_trajectory.value(translation_breaks(i + 1)); } @@ -371,18 +372,20 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( {0, 1, 0, 1}); meshcat_->SetObject(c3_actual_tray_path_ + "/z-axis", cylinder_for_tray_, {0, 0, 1, 1}); -// meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, -// {1, 0, 0, 1}); -// meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, -// {0, 1, 0, 1}); -// meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, -// {0, 0, 1, 1}); -// meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, -// {1, 0, 0, 1}); -// meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, -// {0, 1, 0, 1}); -// meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, -// {0, 0, 1, 1}); + if (draw_ee_){ + meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/y-axis", cylinder_for_ee_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_target_ee_path_ + "/z-axis", cylinder_for_ee_, + {0, 0, 1, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/x-axis", cylinder_for_ee_, + {1, 0, 0, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/y-axis", cylinder_for_ee_, + {0, 1, 0, 1}); + meshcat_->SetObject(c3_actual_ee_path_ + "/z-axis", cylinder_for_ee_, + {0, 0, 1, 1}); + } auto x_axis_transform = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitY()), Vector3d{0.05, 0.0, 0.0}); @@ -407,12 +410,14 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( meshcat_->SetTransform(c3_actual_tray_path_ + "/x-axis", x_axis_transform); meshcat_->SetTransform(c3_actual_tray_path_ + "/y-axis", y_axis_transform); meshcat_->SetTransform(c3_actual_tray_path_ + "/z-axis", z_axis_transform); -// meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); -// meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); -// meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); -// meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); -// meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); -// meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); + if (draw_ee_){ + meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); + } DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); } @@ -458,14 +463,14 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( c3_actual->state[9]})); } if (draw_ee_) { -// meshcat_->SetTransform( -// c3_target_ee_path_, -// RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], -// c3_target->state[2]})); - // meshcat_->SetTransform( - // c3_actual_ee_path_, - // RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], - // c3_actual->state[2]})); + meshcat_->SetTransform( + c3_target_ee_path_, + RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], + c3_target->state[2]})); + meshcat_->SetTransform( + c3_actual_ee_path_, + RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], + c3_actual->state[2]})); } return drake::systems::EventStatus::Succeeded(); } From 5c2cbc55792272cf0cf8e427db360da173d60463 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 31 Mar 2024 16:07:48 -0400 Subject: [PATCH 673/758] options to add another object to franka examples --- examples/franka/BUILD.bazel | 27 ++ .../franka_c3_controller_with_object.cc | 340 ++++++++++++++++++ examples/franka/franka_sim.cc | 41 ++- examples/franka/franka_visualizer.cc | 31 +- .../franka_c3_controller_params.yaml | 18 +- .../franka/parameters/franka_lcm_channels.h | 4 +- .../franka_osc_controller_params.yaml | 4 +- .../franka/parameters/franka_sim_params.h | 8 + .../franka/parameters/franka_sim_params.yaml | 28 +- .../parameters/lcm_channels_simulation.yaml | 2 +- examples/franka/urdf/center_support.urdf | 4 +- ...{default_box.urdf => cylinder_object.urdf} | 17 +- 12 files changed, 464 insertions(+), 60 deletions(-) create mode 100644 examples/franka/franka_c3_controller_with_object.cc rename examples/franka/urdf/{default_box.urdf => cylinder_object.urdf} (63%) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index dbf09caab1..979e28ab0e 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -114,6 +114,33 @@ cc_binary( ], ) +cc_binary( + name = "franka_c3_controller_with_object", + srcs = ["franka_c3_controller_with_object.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_c3_controller_params", + ":franka_lcm_channels", + "//common", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers:c3_controller", + "//systems/controllers:lcs_factory_system", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", + "//systems/trajectory_optimization:c3_output_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "forward_kinematics_for_lcs", srcs = ["forward_kinematics_for_lcs.cc"], diff --git a/examples/franka/franka_c3_controller_with_object.cc b/examples/franka/franka_c3_controller_with_object.cc new file mode 100644 index 0000000000..08a188ba6d --- /dev/null +++ b/examples/franka/franka_c3_controller_with_object.cc @@ -0,0 +1,340 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/systems/c3_state_sender.h" +#include "examples/franka/systems/c3_trajectory_generator.h" +#include "examples/franka/systems/franka_kinematics.h" +#include "examples/franka/systems/plate_balancing_target.h" +#include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/c3/lcs_factory_system.h" +#include "systems/controllers/c3_controller.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/primitives/radio_parser.h" + +namespace dairlib { + +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; + +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; + +DEFINE_string(controller_settings, + "examples/franka/parameters/franka_c3_controller_params.yaml", + "Controller settings such as channels. Attempting to minimize " + "number of gflags"); +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + // load parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + FLAGS_controller_settings); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + C3Options c3_options = drake::yaml::LoadYamlFile( + controller_params.c3_options_file[controller_params.scene_index]); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_params.osqp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + DiagramBuilder plant_builder; + + MultibodyPlant plant_franka(0.0); + Parser parser_franka(&plant_franka, nullptr); + parser_franka.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = + parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + + RigidTransform X_WI = RigidTransform::Identity(); + plant_franka.WeldFrames(plant_franka.world_frame(), + plant_franka.GetFrameByName("panda_link0"), X_WI); + + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + plant_franka.WeldFrames( + plant_franka.GetFrameByName("panda_link7"), + plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); + + plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + + /// + MultibodyPlant plant_tray(0.0); + Parser parser_tray(&plant_tray, nullptr); + parser_tray.AddModels(controller_params.tray_model); + plant_tray.Finalize(); + auto tray_context = plant_tray.CreateDefaultContext(); + + /// + auto [plant_for_lcs, scene_graph] = + AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + Parser parser_plate(&plant_for_lcs); + parser_plate.SetAutoRenaming(true); + parser_plate.AddModels(controller_params.plate_model); + + drake::multibody::ModelInstanceIndex left_support_index; + drake::multibody::ModelInstanceIndex right_support_index; + if (controller_params.scene_index > 0) { + left_support_index = parser_plate.AddModels( + FindResourceOrThrow(controller_params.left_support_model))[0]; + right_support_index = parser_plate.AddModels( + FindResourceOrThrow(controller_params.right_support_model))[0]; + RigidTransform T_S1_W = + RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), + controller_params.left_support_position); + RigidTransform T_S2_W = + RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), + controller_params.right_support_position); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); + } + parser_plate.AddModels(controller_params.tray_model); + + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("base_link"), X_WI); + plant_for_lcs.Finalize(); + std::unique_ptr> plant_for_lcs_autodiff = + drake::systems::System::ToAutoDiffXd(plant_for_lcs); + + auto plant_diagram = plant_builder.Build(); + std::unique_ptr> diagram_context = + plant_diagram->CreateDefaultContext(); + auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( + plant_for_lcs, diagram_context.get()); + auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); + + /// + std::vector end_effector_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("plate")); + if (controller_params.scene_index > 0) { + std::vector left_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", left_support_index)); + std::vector right_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", right_support_index)); + end_effector_contact_points.insert(end_effector_contact_points.end(), + left_support_contact_points.begin(), + left_support_contact_points.end()); + end_effector_contact_points.insert(end_effector_contact_points.end(), + right_support_contact_points.begin(), + right_support_contact_points.end()); + } + std::vector tray_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("tray")); + std::unordered_map> + contact_geoms; + contact_geoms["PLATE"] = end_effector_contact_points; + contact_geoms["TRAY"] = tray_geoms; + + std::vector> contact_pairs; + for (auto geom_id : contact_geoms["PLATE"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); + } + + DiagramBuilder builder; + + auto tray_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.tray_state_channel, &lcm)); + auto franka_state_receiver = + builder.AddSystem(plant_franka); + auto tray_state_receiver = + builder.AddSystem(plant_tray); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_tray, tray_context.get(), + controller_params.end_effector_name, "tray", + controller_params.include_end_effector_orientation); + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + auto radio_to_vector = builder.AddSystem(); + + + auto plate_balancing_target = + builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); + plate_balancing_target->SetRemoteControlParameters( + controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto tray_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(plate_balancing_target->get_output_port_tray_target(), + target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(tray_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(3)); + auto lcs_factory = builder.AddSystem( + plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, + *plate_context_ad, contact_pairs, c3_options); + auto controller = builder.AddSystem( + plant_for_lcs, c3_options); + auto c3_trajectory_generator = + builder.AddSystem(plant_for_lcs, + c3_options); + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", + "tray_qx", "tray_qy", "tray_qz", "tray_x", + "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", + "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", + "tray_vz", "tray_vz", "tray_vz", + }; + auto c3_state_sender = + builder.AddSystem(3 + 7 + 3 + 6, state_names); + c3_trajectory_generator->SetPublishEndEffectorOrientation( + controller_params.include_end_effector_orientation); + auto c3_output_sender = builder.AddSystem(); + controller->SetOsqpSolverOptions(solver_options); + + builder.Connect(*radio_sub, *radio_to_vector); + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(target_state_mux->get_output_port(), + controller->get_input_port_target()); + builder.Connect(lcs_factory->get_output_port_lcs(), + controller->get_input_port_lcs()); + builder.Connect(tray_state_sub->get_output_port(), + tray_state_receiver->get_input_port()); + builder.Connect(tray_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(tray_state_receiver->get_output_port(), + plate_balancing_target->get_input_port_tray_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + controller->get_input_port_lcs_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + lcs_factory->get_input_port_lcs_state()); + builder.Connect(radio_to_vector->get_output_port(), + plate_balancing_target->get_input_port_radio()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_trajectory_generator->get_input_port_c3_solution()); + builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), + c3_output_sender->get_input_port_lcs_contact_info()); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + actor_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), + object_trajectory_sender->get_input_port()); + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_output_sender->get_input_port_c3_solution()); + builder.Connect(controller->get_output_port_c3_intermediates(), + c3_output_sender->get_input_port_c3_intermediates()); + builder.Connect(c3_output_sender->get_output_port_c3_debug(), + c3_output_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_force(), + c3_forces_publisher->get_input_port()); + // builder.Connect(c3_output_sender->get_output_port_next_c3_input(), + // lcs_factory->get_input_port_lcs_input()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_c3_controller")); + plant_diagram->set_name(("franka_c3_plant")); +// DrawAndSaveDiagramGraph(*plant_diagram); + + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_state_receiver, + lcm_channel_params.franka_state_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + // auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( + // *controller, &loop.get_diagram_mutable_context()); + // controller->get_input_port_target().FixValue(&controller_context, x_des); + LcmHandleSubscriptionsUntil( + &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index ee1a1f2faa..4cf4095538 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -71,6 +71,8 @@ int DoMain(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + drake::multibody::ModelInstanceIndex object_index = + parser.AddModels(FindResourceOrThrow(sim_params.object_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); @@ -108,7 +110,7 @@ int DoMain(int argc, char* argv[]) { sim_params.right_support_position); RigidTransform T_CS_W = RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - 0.5 * (sim_params.left_support_position + sim_params.right_support_position)); + 0.5 * (sim_params.left_support_position + sim_params.right_support_position) + sim_params.center_support_offset); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_LS_W); @@ -120,23 +122,23 @@ int DoMain(int argc, char* argv[]) { T_CS_W); const drake::geometry::GeometrySet& support_geom_set = plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("support", left_support_index), - &plant.GetBodyByName("support", right_support_index), - &plant.GetBodyByName("support", center_support_index), - }); + &plant.GetBodyByName("support", left_support_index), + &plant.GetBodyByName("support", right_support_index), + &plant.GetBodyByName("support", center_support_index), + }); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( {"supports", support_geom_set}, {"franka", franka_geom_set}); } const drake::geometry::GeometrySet& franka_only_geom_set = plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link8"), - }); + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link8"), + }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( @@ -158,11 +160,21 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, lcm, 1.0 / sim_params.tray_publish_rate)); + auto object_state_sender = + builder.AddSystem(plant, object_index); + auto object_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.object_state_channel, lcm, + 1.0 / sim_params.object_publish_rate)); builder.Connect(plant.get_state_output_port(tray_index), tray_state_sender->get_input_port_state()); builder.Connect(tray_state_sender->get_output_port(), tray_state_pub->get_input_port()); + builder.Connect(plant.get_state_output_port(object_index), + object_state_sender->get_input_port_state()); + builder.Connect(object_state_sender->get_output_port(), + object_state_pub->get_input_port()); int nq = plant.num_positions(); int nv = plant.num_velocities(); @@ -183,12 +195,13 @@ int DoMain(int argc, char* argv[]) { plant, &simulator.get_mutable_context()); VectorXd q = VectorXd::Zero(nq); - std::map q_map = MakeNameToPositionsMap(plant); q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; - q.tail(plant.num_positions(tray_index)) = + q.segment(plant.num_positions(franka_index), plant.num_positions(tray_index)) = sim_params.q_init_plate[sim_params.scene_index]; + q.tail(plant.num_positions(object_index)) = + sim_params.q_init_object[sim_params.scene_index]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 20fe3fd642..2f290586ea 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -84,6 +84,8 @@ int do_main(int argc, char* argv[]) { parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + drake::multibody::ModelInstanceIndex object_index = + parser.AddModels(FindResourceOrThrow(sim_params.object_model))[0]; multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); RigidTransform X_WI = RigidTransform::Identity(); @@ -113,7 +115,7 @@ int do_main(int argc, char* argv[]) { sim_params.right_support_position); RigidTransform T_CS_W = RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - 0.5 * (sim_params.left_support_position + sim_params.right_support_position)); + 0.5 * (sim_params.left_support_position + sim_params.right_support_position) + sim_params.center_support_offset); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("support", left_support_index), T_LS_W); @@ -136,13 +138,15 @@ int do_main(int argc, char* argv[]) { auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.tray_state_channel, lcm)); - auto box_state_sub = + auto object_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.box_state_channel, lcm)); + lcm_channel_params.object_state_channel, lcm)); auto franka_state_receiver = builder.AddSystem(plant, franka_index); auto tray_state_receiver = builder.AddSystem(plant, tray_index); + auto object_state_receiver = + builder.AddSystem(plant, object_index); auto franka_passthrough = builder.AddSystem( franka_state_receiver->get_output_port(0).size(), 0, @@ -153,16 +157,20 @@ int do_main(int argc, char* argv[]) { auto tray_passthrough = builder.AddSystem( tray_state_receiver->get_output_port(0).size(), 0, plant.num_positions(tray_index)); + auto object_passthrough = builder.AddSystem( + tray_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(object_index)); std::vector input_sizes = {plant.num_positions(franka_index), - plant.num_positions(tray_index)}; + plant.num_positions(tray_index), + plant.num_positions(object_index)}; auto mux = builder.AddSystem>(input_sizes); auto trajectory_sub_actor = builder.AddSystem( LcmSubscriberSystem::Make( lcm_channel_params.c3_actor_channel, lcm)); - auto trajectory_sub_object = builder.AddSystem( + auto trajectory_sub_tray = builder.AddSystem( LcmSubscriberSystem::Make( lcm_channel_params.c3_object_channel, lcm)); auto trajectory_sub_force = @@ -209,7 +217,7 @@ int do_main(int argc, char* argv[]) { trajectory_drawer_object->SetNumSamples(40); builder.Connect(trajectory_sub_actor->get_output_port(), trajectory_drawer_actor->get_input_port_trajectory()); - builder.Connect(trajectory_sub_object->get_output_port(), + builder.Connect(trajectory_sub_tray->get_output_port(), trajectory_drawer_object->get_input_port_trajectory()); } @@ -221,7 +229,7 @@ int do_main(int argc, char* argv[]) { meshcat, FindResourceOrThrow(sim_params.end_effector_model), "end_effector_position_target", "end_effector_orientation_target"); - builder.Connect(trajectory_sub_object->get_output_port(), + builder.Connect(trajectory_sub_tray->get_output_port(), object_pose_drawer->get_input_port_trajectory()); builder.Connect(trajectory_sub_actor->get_output_port(), end_effector_pose_drawer->get_input_port_trajectory()); @@ -251,6 +259,7 @@ int do_main(int argc, char* argv[]) { builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); + builder.Connect(object_passthrough->get_output_port(), mux->get_input_port(2)); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), @@ -258,8 +267,10 @@ int do_main(int argc, char* argv[]) { builder.Connect(*franka_state_receiver, *franka_passthrough); builder.Connect(*franka_state_receiver, *robot_time_passthrough); builder.Connect(*tray_state_receiver, *tray_passthrough); + builder.Connect(*object_state_receiver, *object_passthrough); builder.Connect(*franka_state_sub, *franka_state_receiver); builder.Connect(*tray_state_sub, *tray_state_receiver); + builder.Connect(*object_state_sub, *object_state_receiver); auto diagram = builder.Build(); auto context = diagram->CreateDefaultContext(); @@ -268,12 +279,14 @@ int do_main(int argc, char* argv[]) { diagram->GetMutableSubsystemContext(*franka_state_sub, context.get()); auto& tray_state_sub_context = diagram->GetMutableSubsystemContext(*tray_state_sub, context.get()); - auto& box_state_sub_context = - diagram->GetMutableSubsystemContext(*box_state_sub, context.get()); + auto& object_state_sub_context = + diagram->GetMutableSubsystemContext(*object_state_sub, context.get()); franka_state_receiver->InitializeSubscriberPositions( plant, franka_state_sub_context); tray_state_receiver->InitializeSubscriberPositions(plant, tray_state_sub_context); + object_state_receiver->InitializeSubscriberPositions(plant, + object_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 96be125f07..7f4f925cec 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -13,17 +13,17 @@ left_support_model: examples/franka/urdf/support_point_contact.urdf right_support_model: examples/franka/urdf/support_point_contact.urdf tool_attachment_frame: [0, 0, 0.107] -#left_support_position: [0.8, 0.15, 0.447] -#right_support_position: [0.8, -0.15, 0.447] -#left_support_orientation: [0.0, 0.0, 0.0] -#right_support_orientation: [0.0, 0.0, 0.0] -left_support_position: [0.6178, 0.3299, 0.45 ] -right_support_position: [0.7678, 0.0701, 0.45 ] -left_support_orientation: [0. , 0. , 0.5236] -right_support_orientation: [0. , 0. , 0.5236] +left_support_position: [0.8, 0.15, 0.447] +right_support_position: [0.8, -0.15, 0.447] +left_support_orientation: [0.0, 0.0, 0.0] +right_support_orientation: [0.0, 0.0, 0.0] +#left_support_position: [0.6178, 0.3299, 0.45 ] +#right_support_position: [0.7678, 0.0701, 0.45 ] +#left_support_orientation: [0. , 0. , 0.5236] +#right_support_orientation: [0. , 0. , 0.5236] end_effector_thickness: 0.016 -scene_index: 2 +scene_index: 1 include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan diff --git a/examples/franka/parameters/franka_lcm_channels.h b/examples/franka/parameters/franka_lcm_channels.h index c30a661208..adb84c4e2b 100644 --- a/examples/franka/parameters/franka_lcm_channels.h +++ b/examples/franka/parameters/franka_lcm_channels.h @@ -6,7 +6,7 @@ struct FrankaLcmChannels { std::string franka_state_channel; std::string tray_state_channel; - std::string box_state_channel; + std::string object_state_channel; std::string franka_input_channel; std::string franka_input_echo; std::string osc_channel; @@ -23,7 +23,7 @@ struct FrankaLcmChannels { void Serialize(Archive* a) { a->Visit(DRAKE_NVP(franka_state_channel)); a->Visit(DRAKE_NVP(tray_state_channel)); - a->Visit(DRAKE_NVP(box_state_channel)); + a->Visit(DRAKE_NVP(object_state_channel)); a->Visit(DRAKE_NVP(franka_input_channel)); a->Visit(DRAKE_NVP(franka_input_echo)); a->Visit(DRAKE_NVP(osc_channel)); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 22a57769dc..e6277dd88e 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -6,8 +6,8 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.4763, 0.075 , 0.45] -#neutral_position: [0.55, 0, 0.45] +#neutral_position: [0.4763, 0.075 , 0.45] +neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index c49f727c4c..67ec2705fb 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -7,6 +7,7 @@ struct FrankaSimParams { std::string franka_model; std::string end_effector_model; std::string tray_model; + std::string object_model; std::string left_support_model; std::string right_support_model; std::string center_support_model; @@ -16,6 +17,7 @@ struct FrankaSimParams { double actuator_delay; double franka_publish_rate; double tray_publish_rate; + double object_publish_rate; double visualizer_publish_rate; int scene_index; @@ -27,11 +29,13 @@ struct FrankaSimParams { Eigen::VectorXd q_init_franka; std::vector q_init_plate; + std::vector q_init_object; Eigen::VectorXd tool_attachment_frame; Eigen::VectorXd left_support_position; Eigen::VectorXd right_support_position; Eigen::VectorXd left_support_orientation; Eigen::VectorXd right_support_orientation; + Eigen::VectorXd center_support_offset; std::vector world_x_limits; std::vector world_y_limits; @@ -48,6 +52,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_model)); a->Visit(DRAKE_NVP(tray_model)); + a->Visit(DRAKE_NVP(object_model)); a->Visit(DRAKE_NVP(left_support_model)); a->Visit(DRAKE_NVP(right_support_model)); a->Visit(DRAKE_NVP(center_support_model)); @@ -57,6 +62,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(actuator_delay)); a->Visit(DRAKE_NVP(franka_publish_rate)); a->Visit(DRAKE_NVP(tray_publish_rate)); + a->Visit(DRAKE_NVP(object_publish_rate)); a->Visit(DRAKE_NVP(visualizer_publish_rate)); a->Visit(DRAKE_NVP(scene_index)); @@ -68,11 +74,13 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); + a->Visit(DRAKE_NVP(q_init_object)); a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(left_support_position)); a->Visit(DRAKE_NVP(right_support_position)); a->Visit(DRAKE_NVP(left_support_orientation)); a->Visit(DRAKE_NVP(right_support_orientation)); + a->Visit(DRAKE_NVP(center_support_offset)); a->Visit(DRAKE_NVP(world_x_limits)); a->Visit(DRAKE_NVP(world_y_limits)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 27dfc22ac5..86fb55c5ff 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,15 +1,17 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray.sdf +object_model: examples/franka/urdf/cylinder_object.urdf left_support_model: examples/franka/urdf/support.urdf right_support_model: examples/franka/urdf/support.urdf center_support_model: examples/franka/urdf/center_support.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 +object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 2 +scene_index: 1 visualize_drake_sim: true publish_efforts: true @@ -23,15 +25,16 @@ camera_target: [[0.5, 0, 0.5], tool_attachment_frame: [0, 0, 0.107] -#left_support_position: [0.8, 0.15, 0.447] -#right_support_position: [0.8, -0.15, 0.447] -#left_support_orientation: [0.0, 0.0, 0.0] -#right_support_orientation: [0.0, 0.0, 0.0] +left_support_position: [0.8, 0.15, 0.447] +right_support_position: [0.8, -0.15, 0.447] +left_support_orientation: [0.0, 0.0, 0.0] +right_support_orientation: [0.0, 0.0, 0.0] +center_support_offset: [-0.1, 0.0, 0.0] -left_support_position: [0.6178, 0.3299, 0.45 ] -right_support_position: [0.7678, 0.0701, 0.45 ] -left_support_orientation: [0. , 0. , 0.5236] -right_support_orientation: [0. , 0. , 0.5236] +#left_support_position: [0.6178, 0.3299, 0.45 ] +#right_support_position: [0.7678, 0.0701, 0.45 ] +#left_support_orientation: [0. , 0. , 0.5236] +#right_support_orientation: [0. , 0. , 0.5236] #left_support_orientation: [0.0, 0.0, 1.57] #right_support_orientation: [0.0, 0.0, 1.57] @@ -51,10 +54,15 @@ dt: 0.0005 realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.515], +q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.485], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ]] +q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.515], + [1, 0, 0, 0, 0.7, 0.00, 0.0], + [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.5 ], + [1. , 0. , 0. , 0. , 0.55, 0.0 , 0.5 ]] + visualize_workspace: false visualize_pose_trace: false visualize_center_of_mass_plan: true diff --git a/examples/franka/parameters/lcm_channels_simulation.yaml b/examples/franka/parameters/lcm_channels_simulation.yaml index c053fa5f24..97596064bf 100644 --- a/examples/franka/parameters/lcm_channels_simulation.yaml +++ b/examples/franka/parameters/lcm_channels_simulation.yaml @@ -1,6 +1,6 @@ franka_state_channel: FRANKA_STATE_SIMULATION # lcmt_robot_output tray_state_channel: TRAY_STATE_SIMULATION # lcmt_object_state -box_state_channel: BOX_STATE_SIMULATION # lcmt_object_state +object_state_channel: OBJECT_STATE_SIMULATION # lcmt_object_state franka_input_channel: FRANKA_INPUT # lcmt_robot_input franka_input_echo: FRANKA_INPUT_ECHO diff --git a/examples/franka/urdf/center_support.urdf b/examples/franka/urdf/center_support.urdf index 42008679b7..7da594902d 100644 --- a/examples/franka/urdf/center_support.urdf +++ b/examples/franka/urdf/center_support.urdf @@ -15,7 +15,7 @@ - cod + cod @@ -26,7 +26,7 @@ - cod + cod diff --git a/examples/franka/urdf/default_box.urdf b/examples/franka/urdf/cylinder_object.urdf similarity index 63% rename from examples/franka/urdf/default_box.urdf rename to examples/franka/urdf/cylinder_object.urdf index f2b1f70a1d..cdfcc40000 100644 --- a/examples/franka/urdf/default_box.urdf +++ b/examples/franka/urdf/cylinder_object.urdf @@ -3,23 +3,18 @@ - - + + + - + - + @@ -27,7 +22,7 @@ - + From 8a1fa88f32585d7debc0f97209b88a8d535d487d Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 31 Mar 2024 17:45:29 -0400 Subject: [PATCH 674/758] working on a more flexible scene specification --- examples/franka/BUILD.bazel | 43 +++ .../franka/franka_c3_controller_with_wall.cc | 340 ++++++++++++++++++ examples/franka/franka_sim_with_wall.cc | 186 ++++++++++ .../franka/franka_visualizer_with_wall.cc | 293 +++++++++++++++ .../franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 6 + .../franka/parameters/franka_sim_params.yaml | 9 +- .../franka/systems/plate_balancing_target.cc | 12 +- examples/franka/urdf/side_wall.urdf | 36 ++ 9 files changed, 917 insertions(+), 10 deletions(-) create mode 100644 examples/franka/franka_c3_controller_with_wall.cc create mode 100644 examples/franka/franka_sim_with_wall.cc create mode 100644 examples/franka/franka_visualizer_with_wall.cc create mode 100644 examples/franka/urdf/side_wall.urdf diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 979e28ab0e..ca3739788c 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -62,6 +62,26 @@ cc_binary( ], ) +cc_binary( + name = "franka_sim_with_wall", + srcs = ["franka_sim_with_wall.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_lcm_channels", + ":franka_sim_params", + "//common", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/framework:lcm_driven_loop", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "franka_osc_controller", srcs = ["franka_osc_controller.cc"], @@ -191,6 +211,29 @@ cc_binary( ], ) +cc_binary( + name = "franka_visualizer_with_wall", + srcs = ["franka_visualizer_with_wall.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":franka_lcm_channels", + ":franka_sim_params", + "//common", + "//multibody:utils", + "//multibody:visualization_utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/primitives", + "//systems/trajectory_optimization:lcm_trajectory_systems", + "//systems/visualization:lcm_visualization_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "franka_ros_lcm_bridge", srcs = ["franka_ros_lcm_bridge.cc"], diff --git a/examples/franka/franka_c3_controller_with_wall.cc b/examples/franka/franka_c3_controller_with_wall.cc new file mode 100644 index 0000000000..08a188ba6d --- /dev/null +++ b/examples/franka/franka_c3_controller_with_wall.cc @@ -0,0 +1,340 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/systems/c3_state_sender.h" +#include "examples/franka/systems/c3_trajectory_generator.h" +#include "examples/franka/systems/franka_kinematics.h" +#include "examples/franka/systems/plate_balancing_target.h" +#include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/c3/lcs_factory_system.h" +#include "systems/controllers/c3_controller.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" +#include "systems/primitives/radio_parser.h" + +namespace dairlib { + +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; + +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; + +DEFINE_string(controller_settings, + "examples/franka/parameters/franka_c3_controller_params.yaml", + "Controller settings such as channels. Attempting to minimize " + "number of gflags"); +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + // load parameters + drake::yaml::LoadYamlOptions yaml_options; + yaml_options.allow_yaml_with_no_cpp = true; + FrankaC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + FLAGS_controller_settings); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + C3Options c3_options = drake::yaml::LoadYamlFile( + controller_params.c3_options_file[controller_params.scene_index]); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_params.osqp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + DiagramBuilder plant_builder; + + MultibodyPlant plant_franka(0.0); + Parser parser_franka(&plant_franka, nullptr); + parser_franka.AddModels( + drake::FindResourceOrThrow(controller_params.franka_model)); + drake::multibody::ModelInstanceIndex end_effector_index = + parser_franka.AddModels( + FindResourceOrThrow(controller_params.end_effector_model))[0]; + + RigidTransform X_WI = RigidTransform::Identity(); + plant_franka.WeldFrames(plant_franka.world_frame(), + plant_franka.GetFrameByName("panda_link0"), X_WI); + + RigidTransform T_EE_W = + RigidTransform(drake::math::RotationMatrix(), + controller_params.tool_attachment_frame); + plant_franka.WeldFrames( + plant_franka.GetFrameByName("panda_link7"), + plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); + + plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + + /// + MultibodyPlant plant_tray(0.0); + Parser parser_tray(&plant_tray, nullptr); + parser_tray.AddModels(controller_params.tray_model); + plant_tray.Finalize(); + auto tray_context = plant_tray.CreateDefaultContext(); + + /// + auto [plant_for_lcs, scene_graph] = + AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + Parser parser_plate(&plant_for_lcs); + parser_plate.SetAutoRenaming(true); + parser_plate.AddModels(controller_params.plate_model); + + drake::multibody::ModelInstanceIndex left_support_index; + drake::multibody::ModelInstanceIndex right_support_index; + if (controller_params.scene_index > 0) { + left_support_index = parser_plate.AddModels( + FindResourceOrThrow(controller_params.left_support_model))[0]; + right_support_index = parser_plate.AddModels( + FindResourceOrThrow(controller_params.right_support_model))[0]; + RigidTransform T_S1_W = + RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), + controller_params.left_support_position); + RigidTransform T_S2_W = + RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), + controller_params.right_support_position); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); + plant_for_lcs.WeldFrames( + plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); + } + parser_plate.AddModels(controller_params.tray_model); + + plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), + plant_for_lcs.GetFrameByName("base_link"), X_WI); + plant_for_lcs.Finalize(); + std::unique_ptr> plant_for_lcs_autodiff = + drake::systems::System::ToAutoDiffXd(plant_for_lcs); + + auto plant_diagram = plant_builder.Build(); + std::unique_ptr> diagram_context = + plant_diagram->CreateDefaultContext(); + auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( + plant_for_lcs, diagram_context.get()); + auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); + + /// + std::vector end_effector_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("plate")); + if (controller_params.scene_index > 0) { + std::vector left_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", left_support_index)); + std::vector right_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("support", right_support_index)); + end_effector_contact_points.insert(end_effector_contact_points.end(), + left_support_contact_points.begin(), + left_support_contact_points.end()); + end_effector_contact_points.insert(end_effector_contact_points.end(), + right_support_contact_points.begin(), + right_support_contact_points.end()); + } + std::vector tray_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("tray")); + std::unordered_map> + contact_geoms; + contact_geoms["PLATE"] = end_effector_contact_points; + contact_geoms["TRAY"] = tray_geoms; + + std::vector> contact_pairs; + for (auto geom_id : contact_geoms["PLATE"]) { + contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); + } + + DiagramBuilder builder; + + auto tray_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.tray_state_channel, &lcm)); + auto franka_state_receiver = + builder.AddSystem(plant_franka); + auto tray_state_receiver = + builder.AddSystem(plant_tray); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_tray, tray_context.get(), + controller_params.end_effector_name, "tray", + controller_params.include_end_effector_orientation); + auto actor_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto object_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto c3_output_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + auto radio_to_vector = builder.AddSystem(); + + + auto plate_balancing_target = + builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); + plate_balancing_target->SetRemoteControlParameters( + controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto tray_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(plate_balancing_target->get_output_port_tray_target(), + target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(tray_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(3)); + auto lcs_factory = builder.AddSystem( + plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, + *plate_context_ad, contact_pairs, c3_options); + auto controller = builder.AddSystem( + plant_for_lcs, c3_options); + auto c3_trajectory_generator = + builder.AddSystem(plant_for_lcs, + c3_options); + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", + "tray_qx", "tray_qy", "tray_qz", "tray_x", + "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", + "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", + "tray_vz", "tray_vz", "tray_vz", + }; + auto c3_state_sender = + builder.AddSystem(3 + 7 + 3 + 6, state_names); + c3_trajectory_generator->SetPublishEndEffectorOrientation( + controller_params.include_end_effector_orientation); + auto c3_output_sender = builder.AddSystem(); + controller->SetOsqpSolverOptions(solver_options); + + builder.Connect(*radio_sub, *radio_to_vector); + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(target_state_mux->get_output_port(), + controller->get_input_port_target()); + builder.Connect(lcs_factory->get_output_port_lcs(), + controller->get_input_port_lcs()); + builder.Connect(tray_state_sub->get_output_port(), + tray_state_receiver->get_input_port()); + builder.Connect(tray_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(tray_state_receiver->get_output_port(), + plate_balancing_target->get_input_port_tray_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + controller->get_input_port_lcs_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + lcs_factory->get_input_port_lcs_state()); + builder.Connect(radio_to_vector->get_output_port(), + plate_balancing_target->get_input_port_radio()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_trajectory_generator->get_input_port_c3_solution()); + builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), + c3_output_sender->get_input_port_lcs_contact_info()); + builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), + actor_trajectory_sender->get_input_port()); + builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), + object_trajectory_sender->get_input_port()); + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution(), + c3_output_sender->get_input_port_c3_solution()); + builder.Connect(controller->get_output_port_c3_intermediates(), + c3_output_sender->get_input_port_c3_intermediates()); + builder.Connect(c3_output_sender->get_output_port_c3_debug(), + c3_output_publisher->get_input_port()); + builder.Connect(c3_output_sender->get_output_port_c3_force(), + c3_forces_publisher->get_input_port()); + // builder.Connect(c3_output_sender->get_output_port_next_c3_input(), + // lcs_factory->get_input_port_lcs_input()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_c3_controller")); + plant_diagram->set_name(("franka_c3_plant")); +// DrawAndSaveDiagramGraph(*plant_diagram); + + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_state_receiver, + lcm_channel_params.franka_state_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + // auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( + // *controller, &loop.get_diagram_mutable_context()); + // controller->get_input_port_target().FixValue(&controller_context, x_des); + LcmHandleSubscriptionsUntil( + &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_sim_with_wall.cc b/examples/franka/franka_sim_with_wall.cc new file mode 100644 index 0000000000..730f471854 --- /dev/null +++ b/examples/franka/franka_sim_with_wall.cc @@ -0,0 +1,186 @@ +#include + +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "common/find_resource.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "multibody/multibody_utils.h" +#include "systems/robot_lcm_systems.h" + +namespace dairlib { + +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::GeometrySet; +using drake::geometry::SceneGraph; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::Context; +using drake::systems::DiagramBuilder; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using systems::AddActuationRecieverAndStateSenderLcm; + +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + // load parameters + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + + // load urdf and sphere + DiagramBuilder builder; + double sim_dt = sim_params.dt; + auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); + + Parser parser(&plant); + parser.SetAutoRenaming(true); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + drake::multibody::ModelInstanceIndex end_effector_index = + parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + drake::multibody::ModelInstanceIndex object_index = + parser.AddModels(FindResourceOrThrow(sim_params.object_model))[0]; + multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); + + RigidTransform X_WI = RigidTransform::Identity(); + Vector3d franka_origin = Eigen::VectorXd::Zero(3); + + RigidTransform T_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), sim_params.tool_attachment_frame); + + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + T_X_W); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName("plate", end_effector_index), T_EE_W); + + drake::multibody::ModelInstanceIndex wall_index = + parser.AddModels(FindResourceOrThrow(sim_params.wall_model))[0]; + RigidTransform T_Wall_W = RigidTransform( + drake::math::RollPitchYaw(sim_params.wall_orientation), + sim_params.wall_position); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("wall", wall_index), T_Wall_W); + + const drake::geometry::GeometrySet& franka_only_geom_set = + plant.CollectRegisteredGeometries({ + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link8"), + }); + auto tray_collision_set = GeometrySet( + plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"franka", franka_only_geom_set}, {"tray", tray_collision_set}); + + plant.Finalize(); + /* -------------------------------------------------------------------------------------------*/ + + drake::lcm::DrakeLcm drake_lcm; + auto lcm = + builder.AddSystem(&drake_lcm); + AddActuationRecieverAndStateSenderLcm( + &builder, plant, lcm, lcm_channel_params.franka_input_channel, + lcm_channel_params.franka_state_channel, sim_params.franka_publish_rate, + franka_index, sim_params.publish_efforts, sim_params.actuator_delay); + auto tray_state_sender = + builder.AddSystem(plant, tray_index); + auto tray_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.tray_state_channel, lcm, + 1.0 / sim_params.tray_publish_rate)); + auto object_state_sender = + builder.AddSystem(plant, object_index); + auto object_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.object_state_channel, lcm, + 1.0 / sim_params.object_publish_rate)); + + builder.Connect(plant.get_state_output_port(tray_index), + tray_state_sender->get_input_port_state()); + builder.Connect(tray_state_sender->get_output_port(), + tray_state_pub->get_input_port()); + builder.Connect(plant.get_state_output_port(object_index), + object_state_sender->get_input_port_state()); + builder.Connect(object_state_sender->get_output_port(), + object_state_pub->get_input_port()); + + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + + if (sim_params.visualize_drake_sim) { + drake::visualization::AddDefaultVisualization(&builder); + } + + auto diagram = builder.Build(); + + drake::systems::Simulator simulator(*diagram); + + simulator.set_publish_every_time_step(false); + simulator.set_publish_at_initialization(false); + simulator.set_target_realtime_rate(sim_params.realtime_rate); + + auto& plant_context = diagram->GetMutableSubsystemContext( + plant, &simulator.get_mutable_context()); + + VectorXd q = VectorXd::Zero(nq); + + q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; + + q.segment(plant.num_positions(franka_index), + plant.num_positions(tray_index)) = + sim_params.q_init_plate[sim_params.scene_index]; + q.tail(plant.num_positions(object_index)) = + sim_params.q_init_object[sim_params.scene_index]; + + plant.SetPositions(&plant_context, q); + + VectorXd v = VectorXd::Zero(nv); + plant.SetVelocities(&plant_context, v); + + simulator.Initialize(); + simulator.AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/franka/franka_visualizer_with_wall.cc b/examples/franka/franka_visualizer_with_wall.cc new file mode 100644 index 0000000000..a4c1934e22 --- /dev/null +++ b/examples/franka/franka_visualizer_with_wall.cc @@ -0,0 +1,293 @@ +#include + +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "common/find_resource.h" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "multibody/com_pose_system.h" +#include "multibody/multibody_utils.h" +#include "multibody/visualization_utils.h" +#include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" +#include "systems/visualization/lcm_visualization_systems.h" + +#include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" +#include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "drake/systems/rendering/multibody_position_to_geometry_pose.h" + +namespace dairlib { + +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::systems::ObjectStateReceiver; +using dairlib::systems::RobotOutputReceiver; +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::DrakeVisualizer; +using drake::geometry::SceneGraph; +using drake::geometry::Sphere; +using drake::math::RigidTransformd; +using drake::multibody::MultibodyPlant; +using drake::multibody::RigidBody; +using drake::multibody::SpatialInertia; +using drake::multibody::UnitInertia; +using drake::systems::Simulator; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::systems::rendering::MultibodyPositionToGeometryPose; + +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; + +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_simulation.yaml", + "Filepath containing lcm channels"); + +int do_main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + + drake::systems::DiagramBuilder builder; + + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + + MultibodyPlant plant(0.0); + + Parser parser(&plant, &scene_graph); + parser.SetAutoRenaming(true); + drake::multibody::ModelInstanceIndex franka_index = + parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + drake::multibody::ModelInstanceIndex end_effector_index = + parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; + drake::multibody::ModelInstanceIndex tray_index = + parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; + drake::multibody::ModelInstanceIndex object_index = + parser.AddModels(FindResourceOrThrow(sim_params.object_model))[0]; + multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); + + RigidTransform X_WI = RigidTransform::Identity(); + Vector3d franka_origin = Eigen::VectorXd::Zero(3); + + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix(), sim_params.tool_attachment_frame); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); + plant.WeldFrames(plant.GetFrameByName("panda_link7"), + plant.GetFrameByName("plate", end_effector_index), T_EE_W); + + drake::multibody::ModelInstanceIndex wall_index = + parser.AddModels(FindResourceOrThrow(sim_params.wall_model))[0]; + RigidTransform T_Wall_W = RigidTransform( + drake::math::RollPitchYaw(sim_params.wall_orientation), + sim_params.wall_position); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("wall", wall_index), T_Wall_W); + + + plant.Finalize(); + + auto lcm = builder.AddSystem(); + + // Create state receiver. + auto franka_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.franka_state_channel, lcm)); + auto tray_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.tray_state_channel, lcm)); + auto object_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.object_state_channel, lcm)); + auto franka_state_receiver = + builder.AddSystem(plant, franka_index); + auto tray_state_receiver = + builder.AddSystem(plant, tray_index); + auto object_state_receiver = + builder.AddSystem(plant, object_index); + + auto franka_passthrough = builder.AddSystem( + franka_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(franka_index)); + auto robot_time_passthrough = builder.AddSystem( + franka_state_receiver->get_output_port(0).size(), + franka_state_receiver->get_output_port(0).size() - 1, 1); + auto tray_passthrough = builder.AddSystem( + tray_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(tray_index)); + auto object_passthrough = builder.AddSystem( + tray_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(object_index)); + + std::vector input_sizes = {plant.num_positions(franka_index), + plant.num_positions(tray_index), + plant.num_positions(object_index)}; + auto mux = + builder.AddSystem>(input_sizes); + + auto trajectory_sub_actor = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_actor_channel, lcm)); + auto trajectory_sub_tray = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_object_channel, lcm)); + auto trajectory_sub_force = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.c3_force_channel, lcm)); + + auto c3_state_actual_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm)); + auto c3_state_target_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm)); + auto to_pose = + builder.AddSystem>(plant); + + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0 / sim_params.visualizer_publish_rate; + auto meshcat = std::make_shared(); + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, scene_graph, meshcat, std::move(params)); + meshcat->SetCameraPose(sim_params.camera_pose[sim_params.scene_index], sim_params.camera_target[sim_params.scene_index]); + + if (sim_params.visualize_workspace){ + double width = sim_params.world_x_limits[sim_params.scene_index][1] - sim_params.world_x_limits[sim_params.scene_index][0]; + double depth = sim_params.world_y_limits[sim_params.scene_index][1] - sim_params.world_y_limits[sim_params.scene_index][0]; + double height = sim_params.world_z_limits[sim_params.scene_index][1] - sim_params.world_z_limits[sim_params.scene_index][0]; + Vector3d workspace_center = {0.5 * (sim_params.world_x_limits[sim_params.scene_index][1] + sim_params.world_x_limits[sim_params.scene_index][0]), + 0.5 * (sim_params.world_y_limits[sim_params.scene_index][1] + sim_params.world_y_limits[sim_params.scene_index][0]), + 0.5 * (sim_params.world_z_limits[sim_params.scene_index][1] + sim_params.world_z_limits[sim_params.scene_index][0])}; + meshcat->SetObject("c3_state/workspace", drake::geometry::Box(width, depth, height), + {1, 0, 0, 0.2}); + meshcat->SetTransform("c3_state/workspace", RigidTransformd(workspace_center)); + } + if (sim_params.visualize_center_of_mass_plan){ + auto trajectory_drawer_actor = + builder.AddSystem( + meshcat, "end_effector_position_target"); + auto trajectory_drawer_object = + builder.AddSystem(meshcat, + "object_position_target"); + trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); + trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); + trajectory_drawer_actor->SetNumSamples(40); + trajectory_drawer_object->SetNumSamples(40); + builder.Connect(trajectory_sub_actor->get_output_port(), + trajectory_drawer_actor->get_input_port_trajectory()); + builder.Connect(trajectory_sub_tray->get_output_port(), + trajectory_drawer_object->get_input_port_trajectory()); + } + + if (sim_params.visualize_pose_trace){ + auto object_pose_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow("examples/franka/urdf/tray_transparent.sdf"), + "object_position_target", "object_orientation_target"); + auto end_effector_pose_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow(sim_params.end_effector_model), + "end_effector_position_target", "end_effector_orientation_target"); + + builder.Connect(trajectory_sub_tray->get_output_port(), + object_pose_drawer->get_input_port_trajectory()); + builder.Connect(trajectory_sub_actor->get_output_port(), + end_effector_pose_drawer->get_input_port_trajectory()); + } + + if (sim_params.visualize_c3_state){ + auto c3_target_drawer = + builder.AddSystem(meshcat, true, false); + builder.Connect(c3_state_actual_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_actual()); + builder.Connect(c3_state_target_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_target()); + } + + if (sim_params.visualize_c3_forces){ + auto end_effector_force_drawer = builder.AddSystem( + meshcat, "end_effector_position_target", "end_effector_force_target", + "lcs_force_trajectory"); + builder.Connect(trajectory_sub_actor->get_output_port(), + end_effector_force_drawer->get_input_port_actor_trajectory()); + builder.Connect(trajectory_sub_force->get_output_port(), + end_effector_force_drawer->get_input_port_force_trajectory()); + builder.Connect(robot_time_passthrough->get_output_port(), + end_effector_force_drawer->get_input_port_robot_time()); + } + + builder.Connect(franka_passthrough->get_output_port(), + mux->get_input_port(0)); + builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); + builder.Connect(object_passthrough->get_output_port(), mux->get_input_port(2)); + builder.Connect(*mux, *to_pose); + builder.Connect( + to_pose->get_output_port(), + scene_graph.get_source_pose_port(plant.get_source_id().value())); + builder.Connect(*franka_state_receiver, *franka_passthrough); + builder.Connect(*franka_state_receiver, *robot_time_passthrough); + builder.Connect(*tray_state_receiver, *tray_passthrough); + builder.Connect(*object_state_receiver, *object_passthrough); + builder.Connect(*franka_state_sub, *franka_state_receiver); + builder.Connect(*tray_state_sub, *tray_state_receiver); + builder.Connect(*object_state_sub, *object_state_receiver); + + auto diagram = builder.Build(); + auto context = diagram->CreateDefaultContext(); + + auto& franka_state_sub_context = + diagram->GetMutableSubsystemContext(*franka_state_sub, context.get()); + auto& tray_state_sub_context = + diagram->GetMutableSubsystemContext(*tray_state_sub, context.get()); + auto& object_state_sub_context = + diagram->GetMutableSubsystemContext(*object_state_sub, context.get()); + franka_state_receiver->InitializeSubscriberPositions( + plant, franka_state_sub_context); + tray_state_receiver->InitializeSubscriberPositions(plant, + tray_state_sub_context); + object_state_receiver->InitializeSubscriberPositions(plant, + object_state_sub_context); + + /// Use the simulator to drive at a fixed rate + /// If set_publish_every_time_step is true, this publishes twice + /// Set realtime rate. Otherwise, runs as fast as possible + auto stepper = + std::make_unique>(*diagram, std::move(context)); + stepper->set_publish_every_time_step(false); + stepper->set_publish_at_initialization(false); + stepper->set_target_realtime_rate( + 1.0); // may need to change this to param.real_time_rate? + stepper->Initialize(); + + drake::log()->info("visualizer started"); + + stepper->AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 7f4f925cec..4ccc2e68f8 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -37,7 +37,7 @@ second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.3897, 0.025, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.7, 0.00, 0.485], + [0.9, 0.00, 0.485], [0.6062, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 67ec2705fb..6f6587bccb 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -11,6 +11,7 @@ struct FrankaSimParams { std::string left_support_model; std::string right_support_model; std::string center_support_model; + std::string wall_model; double dt; double realtime_rate; @@ -35,6 +36,8 @@ struct FrankaSimParams { Eigen::VectorXd right_support_position; Eigen::VectorXd left_support_orientation; Eigen::VectorXd right_support_orientation; + Eigen::VectorXd wall_position; + Eigen::VectorXd wall_orientation; Eigen::VectorXd center_support_offset; std::vector world_x_limits; @@ -56,6 +59,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(left_support_model)); a->Visit(DRAKE_NVP(right_support_model)); a->Visit(DRAKE_NVP(center_support_model)); + a->Visit(DRAKE_NVP(wall_model)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); @@ -80,6 +84,8 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(right_support_position)); a->Visit(DRAKE_NVP(left_support_orientation)); a->Visit(DRAKE_NVP(right_support_orientation)); + a->Visit(DRAKE_NVP(wall_position)); + a->Visit(DRAKE_NVP(wall_orientation)); a->Visit(DRAKE_NVP(center_support_offset)); a->Visit(DRAKE_NVP(world_x_limits)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 86fb55c5ff..72496b7229 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -5,13 +5,14 @@ object_model: examples/franka/urdf/cylinder_object.urdf left_support_model: examples/franka/urdf/support.urdf right_support_model: examples/franka/urdf/support.urdf center_support_model: examples/franka/urdf/center_support.urdf +wall_model: examples/franka/urdf/side_wall.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 1 +scene_index: 0 visualize_drake_sim: true publish_efforts: true @@ -29,6 +30,8 @@ left_support_position: [0.8, 0.15, 0.447] right_support_position: [0.8, -0.15, 0.447] left_support_orientation: [0.0, 0.0, 0.0] right_support_orientation: [0.0, 0.0, 0.0] +wall_position: [0.6, 0.35, 0.25] +wall_orientation: [0.0, 0.0, 0.0] center_support_offset: [-0.1, 0.0, 0.0] #left_support_position: [0.6178, 0.3299, 0.45 ] @@ -54,11 +57,11 @@ dt: 0.0005 realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.485], +q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.5], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ]] -q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.515], +q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1, 0, 0, 0, 0.7, 0.00, 0.0], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.5 ], [1. , 0. , 0. , 0. , 0.55, 0.0 , 0.5 ]] diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 7fa0469b43..1cadcdde40 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -124,12 +124,12 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( } end_effector_position[2] -= end_effector_thickness_; // place end effector below tray -// if (end_effector_position[0] > 0.6) { -// end_effector_position[0] = 0.6; // keep it within the workspace -// } -// if (end_effector_position[1] > 0.05) { -// end_effector_position[1] = 0.05; // keep it within the workspace -// } + if (end_effector_position[0] > 0.6) { + end_effector_position[0] = 0.6; // keep it within the workspace + } + if (end_effector_position[1] > 0.05) { + end_effector_position[1] = 0.05; // keep it within the workspace + } if (radio_out->value()[13] > 0) { end_effector_position(0) += radio_out->value()[0] * x_scale_; end_effector_position(1) += radio_out->value()[1] * y_scale_; diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf new file mode 100644 index 0000000000..5d4d90cf61 --- /dev/null +++ b/examples/franka/urdf/side_wall.urdf @@ -0,0 +1,36 @@ + + + + + + + + + + + + cod + + + + + + + + + + + cod + + + + + + + From 6b333ba775a294fd2c1928a278993622289f9b65 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 31 Mar 2024 18:35:15 -0400 Subject: [PATCH 675/758] separating scene to separate yaml --- examples/franka/BUILD.bazel | 42 +-- examples/franka/diagrams/BUILD.bazel | 1 + .../diagrams/franka_c3_controller_diagram.cc | 80 ++--- examples/franka/forward_kinematics_for_lcs.cc | 16 +- examples/franka/franka_c3_controller.cc | 96 ++--- .../franka_c3_controller_with_object.cc | 340 ------------------ examples/franka/franka_sim.cc | 12 +- examples/franka/franka_visualizer.cc | 9 +- .../c3_scenes/supports_rotated_scene.yaml | 14 + .../parameters/c3_scenes/supports_scene.yaml | 14 + .../parameters/c3_scenes/tray_scene.yaml | 11 + .../c3_scenes/two_object_scene.yaml | 14 + .../parameters/c3_scenes/wall_scene.yaml | 14 + .../parameters/franka_c3_controller_params.h | 38 +- .../franka_c3_controller_params.yaml | 30 +- .../franka_c3_options_side_supports.yaml | 3 +- .../parameters/franka_c3_scene_params.h | 30 ++ .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/center_support.urdf | 4 +- examples/franka/urdf/support.urdf | 4 +- .../franka/urdf/support_point_contact.urdf | 4 +- 21 files changed, 237 insertions(+), 541 deletions(-) delete mode 100644 examples/franka/franka_c3_controller_with_object.cc create mode 100644 examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml create mode 100644 examples/franka/parameters/c3_scenes/supports_scene.yaml create mode 100644 examples/franka/parameters/c3_scenes/tray_scene.yaml create mode 100644 examples/franka/parameters/c3_scenes/two_object_scene.yaml create mode 100644 examples/franka/parameters/c3_scenes/wall_scene.yaml create mode 100644 examples/franka/parameters/franka_c3_scene_params.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index ca3739788c..4714bb894f 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -116,33 +116,7 @@ cc_binary( ], deps = [ ":franka_c3_controller_params", - ":franka_lcm_channels", - "//common", - "//examples/franka/systems:franka_systems", - "//lcm:lcm_trajectory_saver", - "//systems:robot_lcm_systems", - "//systems:system_utils", - "//systems/controllers", - "//systems/controllers:c3_controller", - "//systems/controllers:lcs_factory_system", - "//systems/controllers/osc:operational_space_control", - "//systems/framework:lcm_driven_loop", - "//systems/primitives:radio_parser", - "//systems/trajectory_optimization:c3_output_systems", - "@drake//:drake_shared_library", - "@gflags", - ], -) - -cc_binary( - name = "franka_c3_controller_with_object", - srcs = ["franka_c3_controller_with_object.cc"], - data = [ - ":urdfs", - "@drake//manipulation/models/franka_description:models", - ], - deps = [ - ":franka_c3_controller_params", + ":franka_c3_scene_params", ":franka_lcm_channels", "//common", "//examples/franka/systems:franka_systems", @@ -170,6 +144,7 @@ cc_binary( ], deps = [ ":franka_c3_controller_params", + ":franka_c3_scene_params", ":franka_lcm_channels", "//common", "//examples/franka/systems:franka_systems", @@ -330,3 +305,16 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "franka_c3_scene_params", + hdrs = ["parameters/franka_c3_scene_params.h"], + data = [ + "parameters/c3_scenes/supports_scene.yaml", + "parameters/c3_scenes/two_object_scene.yaml", + "parameters/c3_scenes/wall_scene.yaml", + ], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/examples/franka/diagrams/BUILD.bazel b/examples/franka/diagrams/BUILD.bazel index 4a59891304..61d06d5a54 100644 --- a/examples/franka/diagrams/BUILD.bazel +++ b/examples/franka/diagrams/BUILD.bazel @@ -7,6 +7,7 @@ cc_library( deps = [ "//common", "//examples/franka:franka_c3_controller_params", + "//examples/franka:franka_c3_scene_params", "//examples/franka:franka_lcm_channels", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 606b886163..944c17b312 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -19,6 +19,7 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" @@ -68,6 +69,9 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( drake::yaml::LoadYamlFile(controller_settings); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(lcm_channels); + FrankaC3SceneParams scene_params = + drake::yaml::LoadYamlFile( + controller_params.c3_scene_file[controller_params.scene_index]); // C3Options c3_options = drake::yaml::LoadYamlFile( // controller_params.c3_options_file[controller_params.scene_index]); drake::solvers::SolverOptions solver_options = @@ -78,10 +82,10 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plant_franka_ = new drake::multibody::MultibodyPlant(0.0); Parser parser_franka(plant_franka_, nullptr); parser_franka.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); + drake::FindResourceOrThrow(scene_params.franka_model)); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; + FindResourceOrThrow(scene_params.end_effector_model))[0]; RigidTransform X_WI = RigidTransform::Identity(); plant_franka_->WeldFrames(plant_franka_->world_frame(), @@ -89,7 +93,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( RigidTransform T_EE_W = RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); + scene_params.tool_attachment_frame); plant_franka_->WeldFrames( plant_franka_->GetFrameByName("panda_link7"), plant_franka_->GetFrameByName("plate", end_effector_index), T_EE_W); @@ -100,42 +104,31 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( /// plant_tray_ = new drake::multibody::MultibodyPlant(0.0); Parser parser_tray(plant_tray_, nullptr); - parser_tray.AddModels(controller_params.tray_model); + parser_tray.AddModels(scene_params.object_models[0]); plant_tray_->Finalize(); plant_tray_context_ = plant_tray_->CreateDefaultContext(); drake::planning::RobotDiagramBuilder lcs_diagram_builder; lcs_diagram_builder.parser().SetAutoRenaming(true); - lcs_diagram_builder.parser().AddModels(controller_params.plate_model); - - drake::multibody::ModelInstanceIndex left_support_index; - drake::multibody::ModelInstanceIndex right_support_index; - if (controller_params.scene_index > 0) { - left_support_index = lcs_diagram_builder.parser().AddModels( - FindResourceOrThrow(controller_params.left_support_model))[0]; - right_support_index = lcs_diagram_builder.parser().AddModels( - FindResourceOrThrow(controller_params.right_support_model))[0]; - RigidTransform T_S1_W = + lcs_diagram_builder.parser().AddModels(scene_params.end_effector_lcs_model); + + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = lcs_diagram_builder.parser().AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = RigidTransform(drake::math::RollPitchYaw( - controller_params.left_support_orientation), - controller_params.left_support_position); - RigidTransform T_S2_W = - RigidTransform(drake::math::RollPitchYaw( - controller_params.right_support_orientation), - controller_params.right_support_position); - lcs_diagram_builder.plant().WeldFrames( - lcs_diagram_builder.plant().world_frame(), - lcs_diagram_builder.plant().GetFrameByName("support", - left_support_index), - T_S1_W); + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); lcs_diagram_builder.plant().WeldFrames( lcs_diagram_builder.plant().world_frame(), - lcs_diagram_builder.plant().GetFrameByName("support", - right_support_index), - T_S2_W); + lcs_diagram_builder.plant().GetFrameByName("base", environment_model_indices[i]), + T_E_W); + } + for (int i = 0; i < scene_params.object_models.size(); ++i) { + lcs_diagram_builder.parser().AddModels(scene_params.object_models[i]); } - lcs_diagram_builder.parser().AddModels(controller_params.tray_model); - lcs_diagram_builder.plant().WeldFrames( lcs_diagram_builder.plant().world_frame(), lcs_diagram_builder.plant().GetFrameByName("base_link"), X_WI); @@ -152,21 +145,16 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( std::vector end_effector_contact_points = robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( robot_diagram_for_lcs_->plant().GetBodyByName("plate")); - if (controller_params.scene_index > 0) { - std::vector left_support_contact_points = - robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( - robot_diagram_for_lcs_->plant().GetBodyByName("support", - left_support_index)); - std::vector right_support_contact_points = + for (int i = 0; i < environment_model_indices.size(); ++i) { + std::vector + environment_support_contact_points = robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( - robot_diagram_for_lcs_->plant().GetBodyByName("support", - right_support_index)); - end_effector_contact_points.insert(end_effector_contact_points.end(), - left_support_contact_points.begin(), - left_support_contact_points.end()); - end_effector_contact_points.insert(end_effector_contact_points.end(), - right_support_contact_points.begin(), - right_support_contact_points.end()); + robot_diagram_for_lcs_->plant().GetBodyByName("base", + environment_model_indices[i])); + end_effector_contact_points.insert( + end_effector_contact_points.end(), + environment_support_contact_points.begin(), + environment_support_contact_points.end()); } std::vector tray_geoms = robot_diagram_for_lcs_->plant().GetCollisionGeometriesForBody( @@ -188,12 +176,12 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( auto reduced_order_model_receiver = builder.AddSystem( *plant_franka_, plant_franka_context_.get(), *plant_tray_, - plant_tray_context_.get(), controller_params.end_effector_name, + plant_tray_context_.get(), scene_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); auto plate_balancing_target = builder.AddSystem( - *plant_tray_, controller_params.end_effector_thickness, + *plant_tray_, scene_params.end_effector_thickness, controller_params.near_target_threshold); plate_balancing_target->SetRemoteControlParameters( controller_params.first_target[controller_params.scene_index], diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index 1e878634a4..13e724c79c 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -12,6 +12,7 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" @@ -66,6 +67,9 @@ int DoMain(int argc, char* argv[]) { FrankaC3ControllerParams controller_params = drake::yaml::LoadYamlFile( FLAGS_controller_settings); + FrankaC3SceneParams scene_params = + drake::yaml::LoadYamlFile( + controller_params.c3_scene_file[controller_params.scene_index]); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); drake::solvers::SolverOptions solver_options = @@ -78,10 +82,10 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); + drake::FindResourceOrThrow(scene_params.franka_model)); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; + FindResourceOrThrow(scene_params.end_effector_model))[0]; RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), @@ -89,7 +93,7 @@ int DoMain(int argc, char* argv[]) { RigidTransform T_EE_W = RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); + scene_params.tool_attachment_frame); plant_franka.WeldFrames( plant_franka.GetFrameByName("panda_link7"), plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); @@ -100,7 +104,7 @@ int DoMain(int argc, char* argv[]) { /// MultibodyPlant plant_tray(0.0); Parser parser_tray(&plant_tray, nullptr); - parser_tray.AddModels(controller_params.tray_model); + parser_tray.AddModels(scene_params.object_models[0]); plant_tray.Finalize(); auto tray_context = plant_tray.CreateDefaultContext(); @@ -116,7 +120,7 @@ int DoMain(int argc, char* argv[]) { auto reduced_order_model_receiver = builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), - controller_params.end_effector_name, "tray", + scene_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( @@ -134,7 +138,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(3 + 7 + 3 + 6, state_names); auto plate_balancing_target = builder.AddSystem( - plant_tray, controller_params.end_effector_thickness, + plant_tray, scene_params.end_effector_thickness, controller_params.near_target_threshold); plate_balancing_target->SetRemoteControlParameters( controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 08a188ba6d..fbf3f4e8be 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -12,6 +12,7 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" @@ -22,10 +23,10 @@ #include "systems/controllers/c3/lcs_factory_system.h" #include "systems/controllers/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/primitives/radio_parser.h" namespace dairlib { @@ -70,6 +71,9 @@ int DoMain(int argc, char* argv[]) { drake::yaml::LoadYamlFile(FLAGS_lcm_channels); C3Options c3_options = drake::yaml::LoadYamlFile( controller_params.c3_options_file[controller_params.scene_index]); + FrankaC3SceneParams scene_params = + drake::yaml::LoadYamlFile( + controller_params.c3_scene_file[controller_params.scene_index]); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(controller_params.osqp_settings_file)) @@ -80,10 +84,10 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); + drake::FindResourceOrThrow(scene_params.franka_model)); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; + FindResourceOrThrow(scene_params.end_effector_model))[0]; RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), @@ -91,7 +95,7 @@ int DoMain(int argc, char* argv[]) { RigidTransform T_EE_W = RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); + scene_params.tool_attachment_frame); plant_franka.WeldFrames( plant_franka.GetFrameByName("panda_link7"), plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); @@ -102,38 +106,34 @@ int DoMain(int argc, char* argv[]) { /// MultibodyPlant plant_tray(0.0); Parser parser_tray(&plant_tray, nullptr); - parser_tray.AddModels(controller_params.tray_model); + parser_tray.AddModels(scene_params.object_models[0]); plant_tray.Finalize(); auto tray_context = plant_tray.CreateDefaultContext(); /// auto [plant_for_lcs, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); - Parser parser_plate(&plant_for_lcs); - parser_plate.SetAutoRenaming(true); - parser_plate.AddModels(controller_params.plate_model); + Parser lcs_parser(&plant_for_lcs); + lcs_parser.SetAutoRenaming(true); + lcs_parser.AddModels(scene_params.end_effector_lcs_model); - drake::multibody::ModelInstanceIndex left_support_index; - drake::multibody::ModelInstanceIndex right_support_index; - if (controller_params.scene_index > 0) { - left_support_index = parser_plate.AddModels( - FindResourceOrThrow(controller_params.left_support_model))[0]; - right_support_index = parser_plate.AddModels( - FindResourceOrThrow(controller_params.right_support_model))[0]; - RigidTransform T_S1_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), - controller_params.left_support_position); - RigidTransform T_S2_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), - controller_params.right_support_position); - plant_for_lcs.WeldFrames( - plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = lcs_parser.AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = + RigidTransform(drake::math::RollPitchYaw( + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); plant_for_lcs.WeldFrames( plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); + plant_for_lcs.GetFrameByName("base", environment_model_indices[i]), + T_E_W); + } + for (int i = 0; i < scene_params.object_models.size(); ++i) { + lcs_parser.AddModels(scene_params.object_models[i]); } - parser_plate.AddModels(controller_params.tray_model); plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), plant_for_lcs.GetFrameByName("base_link"), X_WI); @@ -152,19 +152,16 @@ int DoMain(int argc, char* argv[]) { std::vector end_effector_contact_points = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("plate")); - if (controller_params.scene_index > 0) { - std::vector left_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", left_support_index)); - std::vector right_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", right_support_index)); - end_effector_contact_points.insert(end_effector_contact_points.end(), - left_support_contact_points.begin(), - left_support_contact_points.end()); - end_effector_contact_points.insert(end_effector_contact_points.end(), - right_support_contact_points.begin(), - right_support_contact_points.end()); + for (int i = 0; i < environment_model_indices.size(); ++i) { + std::vector + environment_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("base", + environment_model_indices[i])); + end_effector_contact_points.insert( + end_effector_contact_points.end(), + environment_support_contact_points.begin(), + environment_support_contact_points.end()); } std::vector tray_geoms = plant_for_lcs.GetCollisionGeometriesForBody( @@ -191,7 +188,7 @@ int DoMain(int argc, char* argv[]) { auto reduced_order_model_receiver = builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), - controller_params.end_effector_name, "tray", + scene_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( @@ -224,13 +221,16 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.radio_channel, &lcm)); auto radio_to_vector = builder.AddSystem(); - auto plate_balancing_target = - builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); + builder.AddSystem( + plant_tray, scene_params.end_effector_thickness, + controller_params.near_target_threshold); plate_balancing_target->SetRemoteControlParameters( - controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], - controller_params.third_target[controller_params.scene_index], controller_params.x_scale, - controller_params.y_scale, controller_params.z_scale); + controller_params.first_target[controller_params.scene_index], + controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], + controller_params.x_scale, controller_params.y_scale, + controller_params.z_scale); std::vector input_sizes = {3, 7, 3, 6}; auto target_state_mux = builder.AddSystem(input_sizes); @@ -251,8 +251,8 @@ int DoMain(int argc, char* argv[]) { auto lcs_factory = builder.AddSystem( plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, *plate_context_ad, contact_pairs, c3_options); - auto controller = builder.AddSystem( - plant_for_lcs, c3_options); + auto controller = + builder.AddSystem(plant_for_lcs, c3_options); auto c3_trajectory_generator = builder.AddSystem(plant_for_lcs, c3_options); @@ -319,7 +319,7 @@ int DoMain(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); -// DrawAndSaveDiagramGraph(*plant_diagram); + // DrawAndSaveDiagramGraph(*plant_diagram); // Run lcm-driven simulation systems::LcmDrivenLoop loop( diff --git a/examples/franka/franka_c3_controller_with_object.cc b/examples/franka/franka_c3_controller_with_object.cc deleted file mode 100644 index 08a188ba6d..0000000000 --- a/examples/franka/franka_c3_controller_with_object.cc +++ /dev/null @@ -1,340 +0,0 @@ - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "common/eigen_utils.h" -#include "examples/franka/parameters/franka_c3_controller_params.h" -#include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/systems/c3_state_sender.h" -#include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/franka_kinematics.h" -#include "examples/franka/systems/plate_balancing_target.h" -#include "multibody/multibody_utils.h" -#include "solvers/lcs_factory.h" -#include "systems/controllers/c3/lcs_factory_system.h" -#include "systems/controllers/c3_controller.h" -#include "systems/framework/lcm_driven_loop.h" -#include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" -#include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/primitives/radio_parser.h" - -namespace dairlib { - -using dairlib::solvers::LCSFactory; -using drake::SortedPair; -using drake::geometry::GeometryId; -using drake::math::RigidTransform; -using drake::multibody::AddMultibodyPlantSceneGraph; -using drake::multibody::MultibodyPlant; -using drake::multibody::Parser; -using drake::systems::DiagramBuilder; -using drake::systems::TriggerType; -using drake::systems::TriggerTypeSet; -using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::LcmSubscriberSystem; -using Eigen::MatrixXd; - -using Eigen::Vector3d; -using Eigen::VectorXd; -using multibody::MakeNameToPositionsMap; -using multibody::MakeNameToVelocitiesMap; - -DEFINE_string(controller_settings, - "examples/franka/parameters/franka_c3_controller_params.yaml", - "Controller settings such as channels. Attempting to minimize " - "number of gflags"); -DEFINE_string(lcm_channels, - "examples/franka/parameters/lcm_channels_simulation.yaml", - "Filepath containing lcm channels"); - -int DoMain(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - - // load parameters - drake::yaml::LoadYamlOptions yaml_options; - yaml_options.allow_yaml_with_no_cpp = true; - FrankaC3ControllerParams controller_params = - drake::yaml::LoadYamlFile( - FLAGS_controller_settings); - FrankaLcmChannels lcm_channel_params = - drake::yaml::LoadYamlFile(FLAGS_lcm_channels); - C3Options c3_options = drake::yaml::LoadYamlFile( - controller_params.c3_options_file[controller_params.scene_index]); - drake::solvers::SolverOptions solver_options = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(controller_params.osqp_settings_file)) - .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - - DiagramBuilder plant_builder; - - MultibodyPlant plant_franka(0.0); - Parser parser_franka(&plant_franka, nullptr); - parser_franka.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); - drake::multibody::ModelInstanceIndex end_effector_index = - parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; - - RigidTransform X_WI = RigidTransform::Identity(); - plant_franka.WeldFrames(plant_franka.world_frame(), - plant_franka.GetFrameByName("panda_link0"), X_WI); - - RigidTransform T_EE_W = - RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); - plant_franka.WeldFrames( - plant_franka.GetFrameByName("panda_link7"), - plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); - - plant_franka.Finalize(); - auto franka_context = plant_franka.CreateDefaultContext(); - - /// - MultibodyPlant plant_tray(0.0); - Parser parser_tray(&plant_tray, nullptr); - parser_tray.AddModels(controller_params.tray_model); - plant_tray.Finalize(); - auto tray_context = plant_tray.CreateDefaultContext(); - - /// - auto [plant_for_lcs, scene_graph] = - AddMultibodyPlantSceneGraph(&plant_builder, 0.0); - Parser parser_plate(&plant_for_lcs); - parser_plate.SetAutoRenaming(true); - parser_plate.AddModels(controller_params.plate_model); - - drake::multibody::ModelInstanceIndex left_support_index; - drake::multibody::ModelInstanceIndex right_support_index; - if (controller_params.scene_index > 0) { - left_support_index = parser_plate.AddModels( - FindResourceOrThrow(controller_params.left_support_model))[0]; - right_support_index = parser_plate.AddModels( - FindResourceOrThrow(controller_params.right_support_model))[0]; - RigidTransform T_S1_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), - controller_params.left_support_position); - RigidTransform T_S2_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), - controller_params.right_support_position); - plant_for_lcs.WeldFrames( - plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); - plant_for_lcs.WeldFrames( - plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); - } - parser_plate.AddModels(controller_params.tray_model); - - plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("base_link"), X_WI); - plant_for_lcs.Finalize(); - std::unique_ptr> plant_for_lcs_autodiff = - drake::systems::System::ToAutoDiffXd(plant_for_lcs); - - auto plant_diagram = plant_builder.Build(); - std::unique_ptr> diagram_context = - plant_diagram->CreateDefaultContext(); - auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( - plant_for_lcs, diagram_context.get()); - auto plate_context_ad = plant_for_lcs_autodiff->CreateDefaultContext(); - - /// - std::vector end_effector_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("plate")); - if (controller_params.scene_index > 0) { - std::vector left_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", left_support_index)); - std::vector right_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", right_support_index)); - end_effector_contact_points.insert(end_effector_contact_points.end(), - left_support_contact_points.begin(), - left_support_contact_points.end()); - end_effector_contact_points.insert(end_effector_contact_points.end(), - right_support_contact_points.begin(), - right_support_contact_points.end()); - } - std::vector tray_geoms = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("tray")); - std::unordered_map> - contact_geoms; - contact_geoms["PLATE"] = end_effector_contact_points; - contact_geoms["TRAY"] = tray_geoms; - - std::vector> contact_pairs; - for (auto geom_id : contact_geoms["PLATE"]) { - contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); - } - - DiagramBuilder builder; - - auto tray_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.tray_state_channel, &lcm)); - auto franka_state_receiver = - builder.AddSystem(plant_franka); - auto tray_state_receiver = - builder.AddSystem(plant_tray); - auto reduced_order_model_receiver = - builder.AddSystem( - plant_franka, franka_context.get(), plant_tray, tray_context.get(), - controller_params.end_effector_name, "tray", - controller_params.include_end_effector_orientation); - auto actor_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_actor_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - - auto object_trajectory_sender = builder.AddSystem( - LcmPublisherSystem::Make( - lcm_channel_params.c3_object_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - - auto c3_output_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_debug_output_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_target_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_target_state_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_actual_state_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_actual_state_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto c3_forces_publisher = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.c3_force_channel, &lcm, - TriggerTypeSet({TriggerType::kForced}))); - auto radio_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.radio_channel, &lcm)); - auto radio_to_vector = builder.AddSystem(); - - - auto plate_balancing_target = - builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); - plate_balancing_target->SetRemoteControlParameters( - controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], - controller_params.third_target[controller_params.scene_index], controller_params.x_scale, - controller_params.y_scale, controller_params.z_scale); - std::vector input_sizes = {3, 7, 3, 6}; - auto target_state_mux = - builder.AddSystem(input_sizes); - auto end_effector_zero_velocity_source = - builder.AddSystem( - VectorXd::Zero(3)); - auto tray_zero_velocity_source = - builder.AddSystem( - VectorXd::Zero(6)); - builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), - target_state_mux->get_input_port(0)); - builder.Connect(plate_balancing_target->get_output_port_tray_target(), - target_state_mux->get_input_port(1)); - builder.Connect(end_effector_zero_velocity_source->get_output_port(), - target_state_mux->get_input_port(2)); - builder.Connect(tray_zero_velocity_source->get_output_port(), - target_state_mux->get_input_port(3)); - auto lcs_factory = builder.AddSystem( - plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, - *plate_context_ad, contact_pairs, c3_options); - auto controller = builder.AddSystem( - plant_for_lcs, c3_options); - auto c3_trajectory_generator = - builder.AddSystem(plant_for_lcs, - c3_options); - std::vector state_names = { - "end_effector_x", "end_effector_y", "end_effector_z", "tray_qw", - "tray_qx", "tray_qy", "tray_qz", "tray_x", - "tray_y", "tray_z", "end_effector_vx", "end_effector_vy", - "end_effector_vz", "tray_wx", "tray_wy", "tray_wz", - "tray_vz", "tray_vz", "tray_vz", - }; - auto c3_state_sender = - builder.AddSystem(3 + 7 + 3 + 6, state_names); - c3_trajectory_generator->SetPublishEndEffectorOrientation( - controller_params.include_end_effector_orientation); - auto c3_output_sender = builder.AddSystem(); - controller->SetOsqpSolverOptions(solver_options); - - builder.Connect(*radio_sub, *radio_to_vector); - builder.Connect(franka_state_receiver->get_output_port(), - reduced_order_model_receiver->get_input_port_franka_state()); - builder.Connect(target_state_mux->get_output_port(), - controller->get_input_port_target()); - builder.Connect(lcs_factory->get_output_port_lcs(), - controller->get_input_port_lcs()); - builder.Connect(tray_state_sub->get_output_port(), - tray_state_receiver->get_input_port()); - builder.Connect(tray_state_receiver->get_output_port(), - reduced_order_model_receiver->get_input_port_object_state()); - builder.Connect(tray_state_receiver->get_output_port(), - plate_balancing_target->get_input_port_tray_state()); - builder.Connect(reduced_order_model_receiver->get_output_port(), - controller->get_input_port_lcs_state()); - builder.Connect(reduced_order_model_receiver->get_output_port(), - lcs_factory->get_input_port_lcs_state()); - builder.Connect(radio_to_vector->get_output_port(), - plate_balancing_target->get_input_port_radio()); - builder.Connect(controller->get_output_port_c3_solution(), - c3_trajectory_generator->get_input_port_c3_solution()); - builder.Connect(lcs_factory->get_output_port_lcs_contact_jacobian(), - c3_output_sender->get_input_port_lcs_contact_info()); - builder.Connect(c3_trajectory_generator->get_output_port_actor_trajectory(), - actor_trajectory_sender->get_input_port()); - builder.Connect(c3_trajectory_generator->get_output_port_object_trajectory(), - object_trajectory_sender->get_input_port()); - builder.Connect(target_state_mux->get_output_port(), - c3_state_sender->get_input_port_target_state()); - builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), - c3_state_sender->get_input_port_actual_state()); - builder.Connect(c3_state_sender->get_output_port_target_c3_state(), - c3_target_state_publisher->get_input_port()); - builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), - c3_actual_state_publisher->get_input_port()); - builder.Connect(controller->get_output_port_c3_solution(), - c3_output_sender->get_input_port_c3_solution()); - builder.Connect(controller->get_output_port_c3_intermediates(), - c3_output_sender->get_input_port_c3_intermediates()); - builder.Connect(c3_output_sender->get_output_port_c3_debug(), - c3_output_publisher->get_input_port()); - builder.Connect(c3_output_sender->get_output_port_c3_force(), - c3_forces_publisher->get_input_port()); - // builder.Connect(c3_output_sender->get_output_port_next_c3_input(), - // lcs_factory->get_input_port_lcs_input()); - - auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_c3_controller")); - plant_diagram->set_name(("franka_c3_plant")); -// DrawAndSaveDiagramGraph(*plant_diagram); - - // Run lcm-driven simulation - systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_state_receiver, - lcm_channel_params.franka_state_channel, true); - DrawAndSaveDiagramGraph(*loop.get_diagram()); - // auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( - // *controller, &loop.get_diagram_mutable_context()); - // controller->get_input_port_target().FixValue(&controller_context, x_des); - LcmHandleSubscriptionsUntil( - &lcm, [&]() { return tray_state_sub->GetInternalMessageCount() > 1; }); - loop.Simulate(); - return 0; -} - -} // namespace dairlib - -int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 4cf4095538..1e164424b7 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -112,19 +112,19 @@ int DoMain(int argc, char* argv[]) { RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), 0.5 * (sim_params.left_support_position + sim_params.right_support_position) + sim_params.center_support_offset); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", left_support_index), + plant.GetFrameByName("base", left_support_index), T_LS_W); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", right_support_index), + plant.GetFrameByName("base", right_support_index), T_RS_W); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", center_support_index), + plant.GetFrameByName("base", center_support_index), T_CS_W); const drake::geometry::GeometrySet& support_geom_set = plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("support", left_support_index), - &plant.GetBodyByName("support", right_support_index), - &plant.GetBodyByName("support", center_support_index), + &plant.GetBodyByName("base", left_support_index), + &plant.GetBodyByName("base", right_support_index), + &plant.GetBodyByName("base", center_support_index), }); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( {"supports", support_geom_set}, {"franka", franka_geom_set}); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 2f290586ea..240d8bd37c 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -115,15 +115,16 @@ int do_main(int argc, char* argv[]) { sim_params.right_support_position); RigidTransform T_CS_W = RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - 0.5 * (sim_params.left_support_position + sim_params.right_support_position) + sim_params.center_support_offset); + 0.5 * (sim_params.left_support_position + sim_params.right_support_position) + + sim_params.center_support_offset); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", left_support_index), + plant.GetFrameByName("base", left_support_index), T_LS_W); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", right_support_index), + plant.GetFrameByName("base", right_support_index), T_RS_W); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", center_support_index), + plant.GetFrameByName("base", center_support_index), T_CS_W); } diff --git a/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml b/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml new file mode 100644 index 0000000000..2a4d319dac --- /dev/null +++ b/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml @@ -0,0 +1,14 @@ +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate +end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf +tool_attachment_frame: [0, 0, 0.107] +end_effector_thickness: 0.016 +object_models: [examples/franka/urdf/tray_lcs.sdf] +environment_models: [examples/franka/urdf/support_point_contact.urdf, + examples/franka/urdf/support_point_contact.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0. , 0. , 0.5236], + [0. , 0. , 0.5236]] +environment_positions: [[0.6178, 0.3299, 0.45 ], + [0.7678, 0.0701, 0.45 ]] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/supports_scene.yaml b/examples/franka/parameters/c3_scenes/supports_scene.yaml new file mode 100644 index 0000000000..3007a9bfee --- /dev/null +++ b/examples/franka/parameters/c3_scenes/supports_scene.yaml @@ -0,0 +1,14 @@ +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate +end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf +tool_attachment_frame: [0, 0, 0.107] +end_effector_thickness: 0.016 +object_models: [examples/franka/urdf/tray_lcs.sdf] +environment_models: [examples/franka/urdf/support_point_contact.urdf, + examples/franka/urdf/support_point_contact.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0]] +environment_positions: [[0.8, 0.15, 0.447], + [0.8, -0.15, 0.447]] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/tray_scene.yaml b/examples/franka/parameters/c3_scenes/tray_scene.yaml new file mode 100644 index 0000000000..a22ff7fd9e --- /dev/null +++ b/examples/franka/parameters/c3_scenes/tray_scene.yaml @@ -0,0 +1,11 @@ +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate +end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf +tool_attachment_frame: [0, 0, 0.107] +end_effector_thickness: 0.016 +object_models: [examples/franka/urdf/tray_lcs.sdf] +environment_models: [] +# orientation in RPY then position in XYZ +environment_orientations: [] +environment_positions: [] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/two_object_scene.yaml b/examples/franka/parameters/c3_scenes/two_object_scene.yaml new file mode 100644 index 0000000000..3007a9bfee --- /dev/null +++ b/examples/franka/parameters/c3_scenes/two_object_scene.yaml @@ -0,0 +1,14 @@ +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate +end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf +tool_attachment_frame: [0, 0, 0.107] +end_effector_thickness: 0.016 +object_models: [examples/franka/urdf/tray_lcs.sdf] +environment_models: [examples/franka/urdf/support_point_contact.urdf, + examples/franka/urdf/support_point_contact.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0]] +environment_positions: [[0.8, 0.15, 0.447], + [0.8, -0.15, 0.447]] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml new file mode 100644 index 0000000000..3007a9bfee --- /dev/null +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -0,0 +1,14 @@ +franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +end_effector_model: examples/franka/urdf/plate_end_effector.urdf +end_effector_name: plate +end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf +tool_attachment_frame: [0, 0, 0.107] +end_effector_thickness: 0.016 +object_models: [examples/franka/urdf/tray_lcs.sdf] +environment_models: [examples/franka/urdf/support_point_contact.urdf, + examples/franka/urdf/support_point_contact.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0]] +environment_positions: [[0.8, 0.15, 0.447], + [0.8, -0.15, 0.447]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.h b/examples/franka/parameters/franka_c3_controller_params.h index 74f3292740..4b09b48ca6 100644 --- a/examples/franka/parameters/franka_c3_controller_params.h +++ b/examples/franka/parameters/franka_c3_controller_params.h @@ -5,54 +5,32 @@ #include "drake/common/yaml/yaml_read_archive.h" struct FrankaC3ControllerParams { + int scene_index; std::vector c3_options_file; + std::vector c3_scene_file; std::string osqp_settings_file; - std::string franka_model; - std::string end_effector_model; - std::string end_effector_name; - std::string plate_model; - std::string tray_model; - std::string left_support_model; - std::string right_support_model; - - Eigen::Vector3d tool_attachment_frame; - Eigen::Vector3d left_support_position; - Eigen::Vector3d right_support_position; - Eigen::Vector3d left_support_orientation; - Eigen::Vector3d right_support_orientation; - double workspace_margin; - double end_effector_thickness; - - int scene_index; bool include_end_effector_orientation; double target_frequency; + double near_target_threshold; std::vector first_target; std::vector second_target; std::vector third_target; double x_scale; double y_scale; double z_scale; - double near_target_threshold; template void Serialize(Archive* a) { a->Visit(DRAKE_NVP(c3_options_file)); + a->Visit(DRAKE_NVP(c3_scene_file)); a->Visit(DRAKE_NVP(osqp_settings_file)); - a->Visit(DRAKE_NVP(franka_model)); - a->Visit(DRAKE_NVP(end_effector_model)); - a->Visit(DRAKE_NVP(end_effector_name)); - a->Visit(DRAKE_NVP(plate_model)); - a->Visit(DRAKE_NVP(tray_model)); - a->Visit(DRAKE_NVP(left_support_model)); - a->Visit(DRAKE_NVP(right_support_model)); + a->Visit(DRAKE_NVP(include_end_effector_orientation)); a->Visit(DRAKE_NVP(target_frequency)); - a->Visit(DRAKE_NVP(tool_attachment_frame)); a->Visit(DRAKE_NVP(scene_index)); - a->Visit(DRAKE_NVP(first_target)); a->Visit(DRAKE_NVP(second_target)); a->Visit(DRAKE_NVP(third_target)); @@ -60,11 +38,5 @@ struct FrankaC3ControllerParams { a->Visit(DRAKE_NVP(y_scale)); a->Visit(DRAKE_NVP(z_scale)); a->Visit(DRAKE_NVP(near_target_threshold)); - - a->Visit(DRAKE_NVP(left_support_position)); - a->Visit(DRAKE_NVP(right_support_position)); - a->Visit(DRAKE_NVP(left_support_orientation)); - a->Visit(DRAKE_NVP(right_support_orientation)); - a->Visit(DRAKE_NVP(end_effector_thickness)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 4ccc2e68f8..bb1925cb99 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,30 +1,14 @@ - +scene_index: 1 c3_options_file: [examples/franka/parameters/franka_c3_options_translation.yaml, examples/franka/parameters/franka_c3_options_w_supports.yaml, examples/franka/parameters/franka_c3_options_side_supports.yaml] +c3_scene_file: [examples/franka/parameters/c3_scenes/tray_scene.yaml, + examples/franka/parameters/c3_scenes/supports_scene.yaml, + examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml, + examples/franka/parameters/c3_scenes/two_object_scene.yaml, + examples/franka/parameters/c3_scenes/wall_scene.yaml,] osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf -end_effector_model: examples/franka/urdf/plate_end_effector.urdf -end_effector_name: plate -plate_model: examples/franka/urdf/plate_end_effector_translation.urdf -tray_model: examples/franka/urdf/tray_lcs.sdf -left_support_model: examples/franka/urdf/support_point_contact.urdf -right_support_model: examples/franka/urdf/support_point_contact.urdf - -tool_attachment_frame: [0, 0, 0.107] -left_support_position: [0.8, 0.15, 0.447] -right_support_position: [0.8, -0.15, 0.447] -left_support_orientation: [0.0, 0.0, 0.0] -right_support_orientation: [0.0, 0.0, 0.0] -#left_support_position: [0.6178, 0.3299, 0.45 ] -#right_support_position: [0.7678, 0.0701, 0.45 ] -#left_support_orientation: [0. , 0. , 0.5236] -#right_support_orientation: [0. , 0. , 0.5236] -end_effector_thickness: 0.016 - -scene_index: 1 - include_end_effector_orientation: false # Note: C3 is set to update much faster than this number. This is just to reduce preempting of the current plan target_frequency: 0 #unused @@ -37,7 +21,7 @@ second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.3897, 0.025, 0.6]] third_target: [[0.45, 0.0, 0.5], - [0.9, 0.00, 0.485], + [0.7, 0.00, 0.485], [0.6062, 0.15, 0.49]] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/franka_c3_options_side_supports.yaml index e9f8678c05..14dba977c8 100644 --- a/examples/franka/parameters/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/franka_c3_options_side_supports.yaml @@ -15,7 +15,7 @@ solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} #publish_frequency : 0 publish_frequency: 0 -# Workspace Limits +# Workspace Limits (specified as Linear Constraints on the end effector position) workspace_limits: [[0.866, 0.5, 0.0, 0.4, 0.6], [-0.5 , 0.866, 0.0, -0.2, -0.0], [0.0, 0.0, 1.0, 0.35, 0.7]] @@ -24,6 +24,7 @@ workspace_margins: 0.05 u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] +# LCS generation parameters mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 diff --git a/examples/franka/parameters/franka_c3_scene_params.h b/examples/franka/parameters/franka_c3_scene_params.h new file mode 100644 index 0000000000..7d4034db74 --- /dev/null +++ b/examples/franka/parameters/franka_c3_scene_params.h @@ -0,0 +1,30 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + +struct FrankaC3SceneParams { + std::string franka_model; + std::string end_effector_model; + std::string end_effector_name; + Eigen::Vector3d tool_attachment_frame; + double end_effector_thickness; + std::string end_effector_lcs_model; + std::vector object_models; + std::vector environment_models; + std::vector environment_orientations; + std::vector environment_positions; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(franka_model)); + a->Visit(DRAKE_NVP(end_effector_model)); + a->Visit(DRAKE_NVP(end_effector_name)); + a->Visit(DRAKE_NVP(tool_attachment_frame)); + a->Visit(DRAKE_NVP(end_effector_thickness)); + a->Visit(DRAKE_NVP(end_effector_lcs_model)); + a->Visit(DRAKE_NVP(object_models)); + a->Visit(DRAKE_NVP(environment_models)); + a->Visit(DRAKE_NVP(environment_orientations)); + a->Visit(DRAKE_NVP(environment_positions)); + } +}; \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 72496b7229..e2d6016641 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,7 +12,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 0 +scene_index: 1 visualize_drake_sim: true publish_efforts: true diff --git a/examples/franka/urdf/center_support.urdf b/examples/franka/urdf/center_support.urdf index 7da594902d..90ace69be8 100644 --- a/examples/franka/urdf/center_support.urdf +++ b/examples/franka/urdf/center_support.urdf @@ -1,7 +1,7 @@ - - + + - - + + - - + + Date: Sun, 31 Mar 2024 18:57:16 -0400 Subject: [PATCH 676/758] specifying wall example --- examples/franka/BUILD.bazel | 4 +- examples/franka/franka_sim_with_wall.cc | 2 +- .../franka/franka_visualizer_with_wall.cc | 2 +- .../franka_c3_options_floating.yaml | 0 .../franka_c3_options_side_supports.yaml | 0 ...c3_options_side_supports_low_friction.yaml | 0 .../franka_c3_options_translation.yaml | 6 +- .../franka_c3_options_w_supports.yaml | 0 .../c3_options/franka_c3_options_wall.yaml | 64 +++++++++++++++++++ .../parameters/c3_scenes/wall_scene.yaml | 9 +-- .../franka_c3_controller_params.yaml | 24 ++++--- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/side_wall.urdf | 2 +- 13 files changed, 92 insertions(+), 23 deletions(-) rename examples/franka/parameters/{ => c3_options}/franka_c3_options_floating.yaml (100%) rename examples/franka/parameters/{ => c3_options}/franka_c3_options_side_supports.yaml (100%) rename examples/franka/parameters/{ => c3_options}/franka_c3_options_side_supports_low_friction.yaml (100%) rename examples/franka/parameters/{ => c3_options}/franka_c3_options_translation.yaml (91%) rename examples/franka/parameters/{ => c3_options}/franka_c3_options_w_supports.yaml (100%) create mode 100644 examples/franka/parameters/c3_options/franka_c3_options_wall.yaml diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 4714bb894f..1122f5d016 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -295,9 +295,9 @@ cc_library( name = "franka_c3_controller_params", hdrs = ["parameters/franka_c3_controller_params.h"], data = [ + "parameters/c3_options/franka_c3_options_floating.yaml", + "parameters/c3_options/franka_c3_options_translation.yaml", "parameters/franka_c3_controller_params.yaml", - "parameters/franka_c3_options_floating.yaml", - "parameters/franka_c3_options_translation.yaml", "parameters/franka_qp_options.yaml", ], deps = [ diff --git a/examples/franka/franka_sim_with_wall.cc b/examples/franka/franka_sim_with_wall.cc index 730f471854..d34e736ee9 100644 --- a/examples/franka/franka_sim_with_wall.cc +++ b/examples/franka/franka_sim_with_wall.cc @@ -94,7 +94,7 @@ int DoMain(int argc, char* argv[]) { drake::math::RollPitchYaw(sim_params.wall_orientation), sim_params.wall_position); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("wall", wall_index), T_Wall_W); + plant.GetFrameByName("base", wall_index), T_Wall_W); const drake::geometry::GeometrySet& franka_only_geom_set = plant.CollectRegisteredGeometries({ diff --git a/examples/franka/franka_visualizer_with_wall.cc b/examples/franka/franka_visualizer_with_wall.cc index a4c1934e22..83e9a3de30 100644 --- a/examples/franka/franka_visualizer_with_wall.cc +++ b/examples/franka/franka_visualizer_with_wall.cc @@ -106,7 +106,7 @@ int do_main(int argc, char* argv[]) { drake::math::RollPitchYaw(sim_params.wall_orientation), sim_params.wall_position); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("wall", wall_index), T_Wall_W); + plant.GetFrameByName("base", wall_index), T_Wall_W); plant.Finalize(); diff --git a/examples/franka/parameters/franka_c3_options_floating.yaml b/examples/franka/parameters/c3_options/franka_c3_options_floating.yaml similarity index 100% rename from examples/franka/parameters/franka_c3_options_floating.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_floating.yaml diff --git a/examples/franka/parameters/franka_c3_options_side_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml similarity index 100% rename from examples/franka/parameters/franka_c3_options_side_supports.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml diff --git a/examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml b/examples/franka/parameters/c3_options/franka_c3_options_side_supports_low_friction.yaml similarity index 100% rename from examples/franka/parameters/franka_c3_options_side_supports_low_friction.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_side_supports_low_friction.yaml diff --git a/examples/franka/parameters/franka_c3_options_translation.yaml b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml similarity index 91% rename from examples/franka/parameters/franka_c3_options_translation.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_translation.yaml index 56d1882767..b955e17899 100644 --- a/examples/franka/parameters/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml @@ -16,9 +16,9 @@ solve_time_filter_alpha: 0.9 publish_frequency: 25 # Workspace Limits -world_x_limits: [0.4, 0.6] -world_y_limits: [-0.2, 0.2] -world_z_limits: [0.3, 0.6] +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], + [0.0, 1.0, 0.0, -0.2, 0.2], + [0.0, 0.0, 1.0, 0.3, 0.6]] workspace_margins: 0.05 u_horizontal_limits: [-10, 10] diff --git a/examples/franka/parameters/franka_c3_options_w_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml similarity index 100% rename from examples/franka/parameters/franka_c3_options_w_supports.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml new file mode 100644 index 0000000000..ed6c2180b3 --- /dev/null +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -0,0 +1,64 @@ +admm_iter: 2 +rho: 0 # does not do anything +rho_scale: 4 +num_threads: 5 +delta_option: 1 +#options are 'MIQP' or 'QP' +projection_type: 'MIQP' +#options are 'stewart_and_trinkle' or 'anitescu' +#contact_model : 'stewart_and_trinkle' +contact_model: 'anitescu' +warm_start: true +use_predicted_x0: true +end_on_qp_step: false +solve_time_filter_alpha: 0.95 +#set to 0 to publish as fast as possible +publish_frequency : 0 +#publish_frequency: 25 + +# End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] +workspace_limits: [] +#world_y_limits: [-0.1, 0.1] +#world_z_limits: [0.35, 0.7] +workspace_margins: 0.05 + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] + +mu: [0.6, 0.6, 0.6, 0.1] +dt: 0.075 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 4 +N: 5 +gamma: 1.0 # discount factor on MPC costs + +#matrix scaling +w_Q: 50 +w_R: 50 +#Penalty on all decision variables, assuming scalar +w_G: 0.15 +#Penalty on all decision variables, assuming scalar +w_U: 0.1 + +#State Tracking Error, assuming diagonal +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, + 5, 5, 15, 10, 10, 1, 5, 5, 5] +#Penalty on efforts, assuming diagonal +r_vector: [0.15, 0.15, 0.1] + +#Penalty on matching projected variables +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [1, 1, 1, 1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_u: [1, 1, 1] + +#Penalty on matching the QP variables +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_gamma: [1, 1, 1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index 3007a9bfee..95f5f12f8e 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -5,10 +5,7 @@ end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf tool_attachment_frame: [0, 0, 0.107] end_effector_thickness: 0.016 object_models: [examples/franka/urdf/tray_lcs.sdf] -environment_models: [examples/franka/urdf/support_point_contact.urdf, - examples/franka/urdf/support_point_contact.urdf] +environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ -environment_orientations: [[0.0, 0.0, 0.0], - [0.0, 0.0, 0.0]] -environment_positions: [[0.8, 0.15, 0.447], - [0.8, -0.15, 0.447]] \ No newline at end of file +environment_orientations: [[0.0, 0.0, 0.0]] +environment_positions: [[0.6, 0.35, 0.25]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index bb1925cb99..78c3ddfc8b 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,12 +1,14 @@ -scene_index: 1 -c3_options_file: [examples/franka/parameters/franka_c3_options_translation.yaml, - examples/franka/parameters/franka_c3_options_w_supports.yaml, - examples/franka/parameters/franka_c3_options_side_supports.yaml] +scene_index: 4 +c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, + examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml, + examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml, + examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, + examples/franka/parameters/c3_options/franka_c3_options_wall.yaml,] c3_scene_file: [examples/franka/parameters/c3_scenes/tray_scene.yaml, examples/franka/parameters/c3_scenes/supports_scene.yaml, examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml, examples/franka/parameters/c3_scenes/two_object_scene.yaml, - examples/franka/parameters/c3_scenes/wall_scene.yaml,] + examples/franka/parameters/c3_scenes/wall_scene.yaml] osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml include_end_effector_orientation: false @@ -16,13 +18,19 @@ target_frequency: 0 #unused near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], - [0.3897, 0.025, 0.49]] + [0.3897, 0.025, 0.49], + [0.45, 0.0, 0.5], + [0.45, 0.0, 0.5],] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], - [0.3897, 0.025, 0.6]] + [0.3897, 0.025, 0.6], + [0.45, 0.0, 0.5], + [0.45, 0.0, 0.5],] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], - [0.6062, 0.15, 0.49]] + [0.6062, 0.15, 0.49], + [0.45, 0.0, 0.5], + [0.45, 0.0, 0.5],] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index e2d6016641..72496b7229 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -12,7 +12,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 1 +scene_index: 0 visualize_drake_sim: true publish_efforts: true diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf index 5d4d90cf61..f7eea4e8bc 100644 --- a/examples/franka/urdf/side_wall.urdf +++ b/examples/franka/urdf/side_wall.urdf @@ -1,7 +1,7 @@ - + Date: Sun, 31 Mar 2024 19:04:47 -0400 Subject: [PATCH 677/758] wall scene wroks --- .../franka/parameters/c3_options/franka_c3_options_wall.yaml | 4 ++-- examples/franka/parameters/c3_scenes/wall_scene.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/side_wall.urdf | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index ed6c2180b3..2b6ce2ef94 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -34,7 +34,7 @@ N: 5 gamma: 1.0 # discount factor on MPC costs #matrix scaling -w_Q: 50 +w_Q: 100 w_R: 50 #Penalty on all decision variables, assuming scalar w_G: 0.15 @@ -42,7 +42,7 @@ w_G: 0.15 w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, +q_vector: [150, 150, 150, 0, 1, 1, 0, 5000, 5000, 5000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index 95f5f12f8e..c44d83cc11 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -8,4 +8,4 @@ object_models: [examples/franka/urdf/tray_lcs.sdf] environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.35, 0.25]] \ No newline at end of file +environment_positions: [[0.6, 0.3, 0.25]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 72496b7229..bf662432d4 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -30,7 +30,7 @@ left_support_position: [0.8, 0.15, 0.447] right_support_position: [0.8, -0.15, 0.447] left_support_orientation: [0.0, 0.0, 0.0] right_support_orientation: [0.0, 0.0, 0.0] -wall_position: [0.6, 0.35, 0.25] +wall_position: [0.6, 0.3, 0.25] wall_orientation: [0.0, 0.0, 0.0] center_support_offset: [-0.1, 0.0, 0.0] diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf index f7eea4e8bc..ab8535e918 100644 --- a/examples/franka/urdf/side_wall.urdf +++ b/examples/franka/urdf/side_wall.urdf @@ -15,7 +15,7 @@ - cod + cod From 288e94e7c647d3a301418fe33a7264c83d5d6f8f Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 1 Apr 2024 11:56:38 -0400 Subject: [PATCH 678/758] allowing sim to be specified with a scene file as well --- examples/franka/BUILD.bazel | 149 ++------- examples/franka/diagrams/BUILD.bazel | 10 +- .../franka/diagrams/franka_sim_diagram.cc | 63 ++-- examples/franka/franka_sim.cc | 56 ++-- examples/franka/franka_sim_with_wall.cc | 186 ----------- examples/franka/franka_visualizer.cc | 104 ++++--- .../franka/franka_visualizer_with_wall.cc | 293 ------------------ .../c3_options/franka_c3_options_wall.yaml | 19 +- .../parameters/c3_scenes/wall_scene.yaml | 9 +- .../franka_c3_controller_params.yaml | 12 +- .../franka/parameters/franka_sim_params.h | 31 +- .../franka/parameters/franka_sim_params.yaml | 20 +- .../parameters/franka_sim_scene_params.h | 23 ++ .../parameters/sim_scenes/empty_scene.yaml | 4 + .../sim_scenes/supports_rotated_scene.yaml | 7 + .../parameters/sim_scenes/supports_scene.yaml | 9 + .../parameters/sim_scenes/wall_scene.yaml | 7 + examples/franka/urdf/side_wall.urdf | 4 +- 18 files changed, 210 insertions(+), 796 deletions(-) delete mode 100644 examples/franka/franka_sim_with_wall.cc delete mode 100644 examples/franka/franka_visualizer_with_wall.cc create mode 100644 examples/franka/parameters/franka_sim_scene_params.h create mode 100644 examples/franka/parameters/sim_scenes/empty_scene.yaml create mode 100644 examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml create mode 100644 examples/franka/parameters/sim_scenes/supports_scene.yaml create mode 100644 examples/franka/parameters/sim_scenes/wall_scene.yaml diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 1122f5d016..e41d5ddcfa 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -10,18 +10,6 @@ cc_library( ]), ) -cc_library( - name = "parameters", - data = glob([ - "*yaml", - ]), -) - -cc_library( - name = "franka_hardware", - deps = [], -) - cc_binary( name = "full_diagram", srcs = ["full_diagram.cc"], @@ -30,10 +18,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_c3_controller_params", - ":franka_lcm_channels", - ":franka_osc_controller_params", - ":franka_sim_params", + ":parameters", "//examples/franka/diagrams:franka_c3_controller_diagram", "//examples/franka/diagrams:franka_osc_controller_diagram", "//systems:robot_lcm_systems", @@ -50,28 +35,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_lcm_channels", - ":franka_sim_params", - "//common", - "//systems:robot_lcm_systems", - "//systems:system_utils", - "//systems/controllers", - "//systems/framework:lcm_driven_loop", - "@drake//:drake_shared_library", - "@gflags", - ], -) - -cc_binary( - name = "franka_sim_with_wall", - srcs = ["franka_sim_with_wall.cc"], - data = [ - ":urdfs", - "@drake//manipulation/models/franka_description:models", - ], - deps = [ - ":franka_lcm_channels", - ":franka_sim_params", + ":parameters", "//common", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -90,8 +54,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_lcm_channels", - ":franka_osc_controller_params", + ":parameters", "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", @@ -115,9 +78,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_c3_controller_params", - ":franka_c3_scene_params", - ":franka_lcm_channels", + ":parameters", "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", @@ -143,9 +104,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_c3_controller_params", - ":franka_c3_scene_params", - ":franka_lcm_channels", + ":parameters", "//common", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", @@ -171,31 +130,7 @@ cc_binary( "@drake//manipulation/models/franka_description:models", ], deps = [ - ":franka_lcm_channels", - ":franka_sim_params", - "//common", - "//multibody:utils", - "//multibody:visualization_utils", - "//systems:robot_lcm_systems", - "//systems:system_utils", - "//systems/primitives", - "//systems/trajectory_optimization:lcm_trajectory_systems", - "//systems/visualization:lcm_visualization_systems", - "@drake//:drake_shared_library", - "@gflags", - ], -) - -cc_binary( - name = "franka_visualizer_with_wall", - srcs = ["franka_visualizer_with_wall.cc"], - data = [ - ":urdfs", - "@drake//manipulation/models/franka_description:models", - ], - deps = [ - ":franka_lcm_channels", - ":franka_sim_params", + ":parameters", "//common", "//multibody:utils", "//multibody:visualization_utils", @@ -218,8 +153,7 @@ cc_binary( ], tags = ["ros"], deps = [ - ":franka_lcm_channels", - ":franka_sim_params", + ":parameters", "//common", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -242,8 +176,7 @@ cc_binary( ], tags = ["ros"], deps = [ - ":franka_lcm_channels", - ":franka_sim_params", + ":parameters", "//common", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -258,62 +191,18 @@ cc_binary( ) cc_library( - name = "franka_lcm_channels", - hdrs = ["parameters/franka_lcm_channels.h"], - data = [ - "parameters/lcm_channels_hardware.yaml", - "parameters/lcm_channels_simulation.yaml", - ], - deps = [ - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_sim_params", - hdrs = ["parameters/franka_sim_params.h"], - data = [ - "parameters/franka_sim_params.yaml", - ], - deps = [ - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_osc_controller_params", - hdrs = ["parameters/franka_osc_controller_params.h"], - data = [ - "parameters/franka_osc_controller_params.yaml", - ], - deps = [ - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_c3_controller_params", - hdrs = ["parameters/franka_c3_controller_params.h"], - data = [ - "parameters/c3_options/franka_c3_options_floating.yaml", - "parameters/c3_options/franka_c3_options_translation.yaml", - "parameters/franka_c3_controller_params.yaml", - "parameters/franka_qp_options.yaml", - ], - deps = [ - "//solvers:c3", - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_c3_scene_params", - hdrs = ["parameters/franka_c3_scene_params.h"], - data = [ - "parameters/c3_scenes/supports_scene.yaml", - "parameters/c3_scenes/two_object_scene.yaml", - "parameters/c3_scenes/wall_scene.yaml", + name = "parameters", + hdrs = [ + "parameters/franka_c3_controller_params.h", + "parameters/franka_c3_scene_params.h", + "parameters/franka_lcm_channels.h", + "parameters/franka_osc_controller_params.h", + "parameters/franka_sim_params.h", + "parameters/franka_sim_scene_params.h", ], + data = glob([ + "*yaml", + ]), deps = [ "@drake//:drake_shared_library", ], diff --git a/examples/franka/diagrams/BUILD.bazel b/examples/franka/diagrams/BUILD.bazel index 61d06d5a54..db1f2cd374 100644 --- a/examples/franka/diagrams/BUILD.bazel +++ b/examples/franka/diagrams/BUILD.bazel @@ -6,9 +6,7 @@ cc_library( hdrs = ["franka_c3_controller_diagram.h"], deps = [ "//common", - "//examples/franka:franka_c3_controller_params", - "//examples/franka:franka_c3_scene_params", - "//examples/franka:franka_lcm_channels", + "//examples/franka:parameters", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", @@ -31,8 +29,7 @@ cc_library( hdrs = ["franka_osc_controller_diagram.h"], deps = [ "//common", - "//examples/franka:franka_lcm_channels", - "//examples/franka:franka_osc_controller_params", + "//examples/franka:parameters", "//examples/franka/systems:franka_systems", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", @@ -52,8 +49,7 @@ cc_library( hdrs = ["franka_sim_diagram.h"], deps = [ "//common", - "//examples/franka:franka_lcm_channels", - "//examples/franka:franka_sim_params", + "//examples/franka:parameters", "//systems:robot_lcm_systems", "//systems:system_utils", "@drake//:drake_shared_library", diff --git a/examples/franka/diagrams/franka_sim_diagram.cc b/examples/franka/diagrams/franka_sim_diagram.cc index 87a69808bf..f17b9cf31e 100644 --- a/examples/franka/diagrams/franka_sim_diagram.cc +++ b/examples/franka/diagrams/franka_sim_diagram.cc @@ -12,6 +12,7 @@ #include "common/find_resource.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/parameters/franka_sim_scene_params.h" #include "systems/robot_lcm_systems.h" namespace dairlib { @@ -33,6 +34,9 @@ FrankaSimDiagram::FrankaSimDiagram(std::unique_ptr("examples/franka/parameters/lcm_channels_simulation.yaml"); + FrankaSimSceneParams scene_params = + drake::yaml::LoadYamlFile( + sim_params.sim_scene_file[sim_params.scene_index]); /// Sim Start plant_ = builder.AddSystem(std::move(plant)); @@ -56,41 +60,32 @@ FrankaSimDiagram::FrankaSimDiagram(std::unique_ptrGetFrameByName("plate", c3_end_effector_index), T_EE_W); - if (sim_params.scene_index > 0) { - drake::multibody::ModelInstanceIndex left_support_index = - parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; - drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( - FindResourceOrThrow(sim_params.right_support_model))[0]; - RigidTransform T_S1_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.left_support_orientation), - sim_params.left_support_position); - RigidTransform T_S2_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.right_support_orientation), - sim_params.right_support_position); - plant_->WeldFrames(plant_->world_frame(), - plant_->GetFrameByName("support", left_support_index), - T_S1_W); - plant_->WeldFrames(plant_->world_frame(), - plant_->GetFrameByName("support", right_support_index), - T_S2_W); - const drake::geometry::GeometrySet& support_geom_set = - plant_->CollectRegisteredGeometries({ - &plant_->GetBodyByName("support", left_support_index), - &plant_->GetBodyByName("support", right_support_index), - }); - // we WANT to model collisions between link5 and the supports - const drake::geometry::GeometrySet& paddle_geom_set = - plant_->CollectRegisteredGeometries( - {&plant_->GetBodyByName("panda_link2"), - &plant_->GetBodyByName("panda_link3"), - &plant_->GetBodyByName("panda_link4"), - &plant_->GetBodyByName("panda_link6"), - &plant_->GetBodyByName("panda_link7"), &plant_->GetBodyByName("plate"), - &plant_->GetBodyByName("panda_link8")}); - - plant_->ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"paddle", support_geom_set}, {"tray", paddle_geom_set}); + // we WANT to model collisions between link5 and the supports + const drake::geometry::GeometrySet& franka_geom_set = + plant->CollectRegisteredGeometries({&plant->GetBodyByName("panda_link0"), + &plant->GetBodyByName("panda_link1"), + &plant->GetBodyByName("panda_link2"), + &plant->GetBodyByName("panda_link3"), + &plant->GetBodyByName("panda_link4")}); + drake::geometry::GeometrySet support_geom_set; + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = parser.AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = + RigidTransform(drake::math::RollPitchYaw( + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); + plant->WeldFrames( + plant->world_frame(), + plant->GetFrameByName("base", environment_model_indices[i]), + T_E_W); + support_geom_set.Add(plant->GetCollisionGeometriesForBody(plant->GetBodyByName("base", + environment_model_indices[i]))); } + plant->ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"supports", support_geom_set}, {"franka", franka_geom_set}); const drake::geometry::GeometrySet& paddle_geom_set = plant_->CollectRegisteredGeometries({ diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 1e164424b7..1108ef738c 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -21,6 +21,7 @@ #include "common/find_resource.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/parameters/franka_sim_scene_params.h" #include "multibody/multibody_utils.h" #include "systems/robot_lcm_systems.h" @@ -57,6 +58,9 @@ int DoMain(int argc, char* argv[]) { "examples/franka/parameters/franka_sim_params.yaml"); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + FrankaSimSceneParams scene_params = + drake::yaml::LoadYamlFile( + sim_params.sim_scene_file[sim_params.scene_index]); // load urdf and sphere DiagramBuilder builder; @@ -95,40 +99,26 @@ int DoMain(int argc, char* argv[]) { &plant.GetBodyByName("panda_link2"), &plant.GetBodyByName("panda_link3"), &plant.GetBodyByName("panda_link4")}); - if (sim_params.scene_index > 0) { - drake::multibody::ModelInstanceIndex left_support_index = - parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; - drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( - FindResourceOrThrow(sim_params.right_support_model))[0]; - drake::multibody::ModelInstanceIndex center_support_index = parser.AddModels( - FindResourceOrThrow(sim_params.center_support_model))[0]; - RigidTransform T_LS_W = - RigidTransform(drake::math::RollPitchYaw(sim_params.left_support_orientation), - sim_params.left_support_position); - RigidTransform T_RS_W = - RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - sim_params.right_support_position); - RigidTransform T_CS_W = - RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - 0.5 * (sim_params.left_support_position + sim_params.right_support_position) + sim_params.center_support_offset); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", left_support_index), - T_LS_W); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", right_support_index), - T_RS_W); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", center_support_index), - T_CS_W); - const drake::geometry::GeometrySet& support_geom_set = - plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("base", left_support_index), - &plant.GetBodyByName("base", right_support_index), - &plant.GetBodyByName("base", center_support_index), - }); - plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"supports", support_geom_set}, {"franka", franka_geom_set}); + + drake::geometry::GeometrySet support_geom_set; + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = parser.AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = + RigidTransform(drake::math::RollPitchYaw( + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); + plant.WeldFrames( + plant.world_frame(), + plant.GetFrameByName("base", environment_model_indices[i]), + T_E_W); + support_geom_set.Add(plant.GetCollisionGeometriesForBody(plant.GetBodyByName("base", + environment_model_indices[i]))); } + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"supports", support_geom_set}, {"franka", franka_geom_set}); const drake::geometry::GeometrySet& franka_only_geom_set = plant.CollectRegisteredGeometries({ diff --git a/examples/franka/franka_sim_with_wall.cc b/examples/franka/franka_sim_with_wall.cc deleted file mode 100644 index d34e736ee9..0000000000 --- a/examples/franka/franka_sim_with_wall.cc +++ /dev/null @@ -1,186 +0,0 @@ -#include - -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include - -#include "common/eigen_utils.h" -#include "common/find_resource.h" -#include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/parameters/franka_sim_params.h" -#include "multibody/multibody_utils.h" -#include "systems/robot_lcm_systems.h" - -namespace dairlib { - -using dairlib::systems::SubvectorPassThrough; -using drake::geometry::GeometrySet; -using drake::geometry::SceneGraph; -using drake::math::RigidTransform; -using drake::multibody::AddMultibodyPlantSceneGraph; -using drake::multibody::MultibodyPlant; -using drake::multibody::Parser; -using drake::systems::Context; -using drake::systems::DiagramBuilder; -using drake::systems::lcm::LcmPublisherSystem; -using drake::systems::lcm::LcmSubscriberSystem; -using drake::trajectories::PiecewisePolynomial; -using multibody::MakeNameToPositionsMap; -using multibody::MakeNameToVelocitiesMap; -using systems::AddActuationRecieverAndStateSenderLcm; - -using Eigen::MatrixXd; -using Eigen::Vector3d; -using Eigen::VectorXd; - -DEFINE_string(lcm_channels, - "examples/franka/parameters/lcm_channels_simulation.yaml", - "Filepath containing lcm channels"); - -int DoMain(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - // load parameters - FrankaSimParams sim_params = drake::yaml::LoadYamlFile( - "examples/franka/parameters/franka_sim_params.yaml"); - FrankaLcmChannels lcm_channel_params = - drake::yaml::LoadYamlFile(FLAGS_lcm_channels); - - // load urdf and sphere - DiagramBuilder builder; - double sim_dt = sim_params.dt; - auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); - - Parser parser(&plant); - parser.SetAutoRenaming(true); - drake::multibody::ModelInstanceIndex franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; - drake::multibody::ModelInstanceIndex end_effector_index = - parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; - drake::multibody::ModelInstanceIndex tray_index = - parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; - drake::multibody::ModelInstanceIndex object_index = - parser.AddModels(FindResourceOrThrow(sim_params.object_model))[0]; - multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); - - RigidTransform X_WI = RigidTransform::Identity(); - Vector3d franka_origin = Eigen::VectorXd::Zero(3); - - RigidTransform T_X_W = RigidTransform( - drake::math::RotationMatrix(), franka_origin); - RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), sim_params.tool_attachment_frame); - - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), - T_X_W); - plant.WeldFrames(plant.GetFrameByName("panda_link7"), - plant.GetFrameByName("plate", end_effector_index), T_EE_W); - - drake::multibody::ModelInstanceIndex wall_index = - parser.AddModels(FindResourceOrThrow(sim_params.wall_model))[0]; - RigidTransform T_Wall_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.wall_orientation), - sim_params.wall_position); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", wall_index), T_Wall_W); - - const drake::geometry::GeometrySet& franka_only_geom_set = - plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link8"), - }); - auto tray_collision_set = GeometrySet( - plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); - plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"franka", franka_only_geom_set}, {"tray", tray_collision_set}); - - plant.Finalize(); - /* -------------------------------------------------------------------------------------------*/ - - drake::lcm::DrakeLcm drake_lcm; - auto lcm = - builder.AddSystem(&drake_lcm); - AddActuationRecieverAndStateSenderLcm( - &builder, plant, lcm, lcm_channel_params.franka_input_channel, - lcm_channel_params.franka_state_channel, sim_params.franka_publish_rate, - franka_index, sim_params.publish_efforts, sim_params.actuator_delay); - auto tray_state_sender = - builder.AddSystem(plant, tray_index); - auto tray_state_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.tray_state_channel, lcm, - 1.0 / sim_params.tray_publish_rate)); - auto object_state_sender = - builder.AddSystem(plant, object_index); - auto object_state_pub = - builder.AddSystem(LcmPublisherSystem::Make( - lcm_channel_params.object_state_channel, lcm, - 1.0 / sim_params.object_publish_rate)); - - builder.Connect(plant.get_state_output_port(tray_index), - tray_state_sender->get_input_port_state()); - builder.Connect(tray_state_sender->get_output_port(), - tray_state_pub->get_input_port()); - builder.Connect(plant.get_state_output_port(object_index), - object_state_sender->get_input_port_state()); - builder.Connect(object_state_sender->get_output_port(), - object_state_pub->get_input_port()); - - int nq = plant.num_positions(); - int nv = plant.num_velocities(); - - if (sim_params.visualize_drake_sim) { - drake::visualization::AddDefaultVisualization(&builder); - } - - auto diagram = builder.Build(); - - drake::systems::Simulator simulator(*diagram); - - simulator.set_publish_every_time_step(false); - simulator.set_publish_at_initialization(false); - simulator.set_target_realtime_rate(sim_params.realtime_rate); - - auto& plant_context = diagram->GetMutableSubsystemContext( - plant, &simulator.get_mutable_context()); - - VectorXd q = VectorXd::Zero(nq); - - q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; - - q.segment(plant.num_positions(franka_index), - plant.num_positions(tray_index)) = - sim_params.q_init_plate[sim_params.scene_index]; - q.tail(plant.num_positions(object_index)) = - sim_params.q_init_object[sim_params.scene_index]; - - plant.SetPositions(&plant_context, q); - - VectorXd v = VectorXd::Zero(nv); - plant.SetVelocities(&plant_context, v); - - simulator.Initialize(); - simulator.AdvanceTo(std::numeric_limits::infinity()); - - return 0; -} - -} // namespace dairlib - -int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 240d8bd37c..12ef32ff4e 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -12,6 +12,7 @@ #include "dairlib/lcmt_robot_output.hpp" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/parameters/franka_sim_scene_params.h" #include "multibody/com_pose_system.h" #include "multibody/multibody_utils.h" #include "multibody/visualization_utils.h" @@ -68,6 +69,9 @@ int do_main(int argc, char* argv[]) { "examples/franka/parameters/franka_sim_params.yaml"); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + FrankaSimSceneParams scene_params = + drake::yaml::LoadYamlFile( + sim_params.sim_scene_file[sim_params.scene_index]); drake::systems::DiagramBuilder builder; @@ -100,32 +104,18 @@ int do_main(int argc, char* argv[]) { plant.WeldFrames(plant.GetFrameByName("panda_link7"), plant.GetFrameByName("plate", end_effector_index), T_EE_W); - if (sim_params.scene_index > 0) { - drake::multibody::ModelInstanceIndex left_support_index = - parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; - drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( - FindResourceOrThrow(sim_params.right_support_model))[0]; - drake::multibody::ModelInstanceIndex center_support_index = parser.AddModels( - FindResourceOrThrow(sim_params.center_support_model))[0]; - RigidTransform T_LS_W = - RigidTransform(drake::math::RollPitchYaw(sim_params.left_support_orientation), - sim_params.left_support_position); - RigidTransform T_RS_W = - RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - sim_params.right_support_position); - RigidTransform T_CS_W = - RigidTransform(drake::math::RollPitchYaw(sim_params.right_support_orientation), - 0.5 * (sim_params.left_support_position + sim_params.right_support_position) - + sim_params.center_support_offset); + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = parser.AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = + RigidTransform(drake::math::RollPitchYaw( + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", left_support_index), - T_LS_W); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", right_support_index), - T_RS_W); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", center_support_index), - T_CS_W); + plant.GetFrameByName("base", environment_model_indices[i]), + T_E_W); } plant.Finalize(); @@ -192,26 +182,36 @@ int do_main(int argc, char* argv[]) { auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); - meshcat->SetCameraPose(sim_params.camera_pose[sim_params.scene_index], sim_params.camera_target[sim_params.scene_index]); - - if (sim_params.visualize_workspace){ - double width = sim_params.world_x_limits[sim_params.scene_index][1] - sim_params.world_x_limits[sim_params.scene_index][0]; - double depth = sim_params.world_y_limits[sim_params.scene_index][1] - sim_params.world_y_limits[sim_params.scene_index][0]; - double height = sim_params.world_z_limits[sim_params.scene_index][1] - sim_params.world_z_limits[sim_params.scene_index][0]; - Vector3d workspace_center = {0.5 * (sim_params.world_x_limits[sim_params.scene_index][1] + sim_params.world_x_limits[sim_params.scene_index][0]), - 0.5 * (sim_params.world_y_limits[sim_params.scene_index][1] + sim_params.world_y_limits[sim_params.scene_index][0]), - 0.5 * (sim_params.world_z_limits[sim_params.scene_index][1] + sim_params.world_z_limits[sim_params.scene_index][0])}; - meshcat->SetObject("c3_state/workspace", drake::geometry::Box(width, depth, height), + meshcat->SetCameraPose(scene_params.camera_pose[sim_params.scene_index], + scene_params.camera_target[sim_params.scene_index]); + + if (sim_params.visualize_workspace) { + double width = sim_params.world_x_limits[sim_params.scene_index][1] - + sim_params.world_x_limits[sim_params.scene_index][0]; + double depth = sim_params.world_y_limits[sim_params.scene_index][1] - + sim_params.world_y_limits[sim_params.scene_index][0]; + double height = sim_params.world_z_limits[sim_params.scene_index][1] - + sim_params.world_z_limits[sim_params.scene_index][0]; + Vector3d workspace_center = { + 0.5 * (sim_params.world_x_limits[sim_params.scene_index][1] + + sim_params.world_x_limits[sim_params.scene_index][0]), + 0.5 * (sim_params.world_y_limits[sim_params.scene_index][1] + + sim_params.world_y_limits[sim_params.scene_index][0]), + 0.5 * (sim_params.world_z_limits[sim_params.scene_index][1] + + sim_params.world_z_limits[sim_params.scene_index][0])}; + meshcat->SetObject("c3_state/workspace", + drake::geometry::Box(width, depth, height), {1, 0, 0, 0.2}); - meshcat->SetTransform("c3_state/workspace", RigidTransformd(workspace_center)); + meshcat->SetTransform("c3_state/workspace", + RigidTransformd(workspace_center)); } - if (sim_params.visualize_center_of_mass_plan){ + if (sim_params.visualize_center_of_mass_plan) { auto trajectory_drawer_actor = builder.AddSystem( meshcat, "end_effector_position_target"); auto trajectory_drawer_object = - builder.AddSystem(meshcat, - "object_position_target"); + builder.AddSystem( + meshcat, "object_position_target"); trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); trajectory_drawer_actor->SetNumSamples(40); @@ -222,9 +222,10 @@ int do_main(int argc, char* argv[]) { trajectory_drawer_object->get_input_port_trajectory()); } - if (sim_params.visualize_pose_trace){ + if (sim_params.visualize_pose_trace) { auto object_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow("examples/franka/urdf/tray_transparent.sdf"), + meshcat, + FindResourceOrThrow("examples/franka/urdf/tray_transparent.sdf"), "object_position_target", "object_orientation_target"); auto end_effector_pose_drawer = builder.AddSystem( meshcat, FindResourceOrThrow(sim_params.end_effector_model), @@ -236,7 +237,7 @@ int do_main(int argc, char* argv[]) { end_effector_pose_drawer->get_input_port_trajectory()); } - if (sim_params.visualize_c3_state){ + if (sim_params.visualize_c3_state) { auto c3_target_drawer = builder.AddSystem(meshcat, true, false); builder.Connect(c3_state_actual_sub->get_output_port(), @@ -245,14 +246,16 @@ int do_main(int argc, char* argv[]) { c3_target_drawer->get_input_port_c3_state_target()); } - if (sim_params.visualize_c3_forces){ + if (sim_params.visualize_c3_forces) { auto end_effector_force_drawer = builder.AddSystem( meshcat, "end_effector_position_target", "end_effector_force_target", "lcs_force_trajectory"); - builder.Connect(trajectory_sub_actor->get_output_port(), - end_effector_force_drawer->get_input_port_actor_trajectory()); - builder.Connect(trajectory_sub_force->get_output_port(), - end_effector_force_drawer->get_input_port_force_trajectory()); + builder.Connect( + trajectory_sub_actor->get_output_port(), + end_effector_force_drawer->get_input_port_actor_trajectory()); + builder.Connect( + trajectory_sub_force->get_output_port(), + end_effector_force_drawer->get_input_port_force_trajectory()); builder.Connect(robot_time_passthrough->get_output_port(), end_effector_force_drawer->get_input_port_robot_time()); } @@ -260,7 +263,8 @@ int do_main(int argc, char* argv[]) { builder.Connect(franka_passthrough->get_output_port(), mux->get_input_port(0)); builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); - builder.Connect(object_passthrough->get_output_port(), mux->get_input_port(2)); + builder.Connect(object_passthrough->get_output_port(), + mux->get_input_port(2)); builder.Connect(*mux, *to_pose); builder.Connect( to_pose->get_output_port(), @@ -286,8 +290,8 @@ int do_main(int argc, char* argv[]) { plant, franka_state_sub_context); tray_state_receiver->InitializeSubscriberPositions(plant, tray_state_sub_context); - object_state_receiver->InitializeSubscriberPositions(plant, - object_state_sub_context); + object_state_receiver->InitializeSubscriberPositions( + plant, object_state_sub_context); /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice diff --git a/examples/franka/franka_visualizer_with_wall.cc b/examples/franka/franka_visualizer_with_wall.cc deleted file mode 100644 index 83e9a3de30..0000000000 --- a/examples/franka/franka_visualizer_with_wall.cc +++ /dev/null @@ -1,293 +0,0 @@ -#include - -#include -#include -#include -#include -#include -#include - -#include "common/eigen_utils.h" -#include "common/find_resource.h" -#include "dairlib/lcmt_robot_output.hpp" -#include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/parameters/franka_sim_params.h" -#include "multibody/com_pose_system.h" -#include "multibody/multibody_utils.h" -#include "multibody/visualization_utils.h" -#include "systems/primitives/subvector_pass_through.h" -#include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" -#include "systems/trajectory_optimization/lcm_trajectory_systems.h" -#include "systems/visualization/lcm_visualization_systems.h" - -#include "drake/common/find_resource.h" -#include "drake/common/yaml/yaml_io.h" -#include "drake/geometry/drake_visualizer.h" -#include "drake/geometry/meshcat_visualizer.h" -#include "drake/geometry/meshcat_visualizer_params.h" -#include "drake/systems/analysis/simulator.h" -#include "drake/systems/framework/diagram_builder.h" -#include "drake/systems/lcm/lcm_interface_system.h" -#include "drake/systems/lcm/lcm_subscriber_system.h" -#include "drake/systems/rendering/multibody_position_to_geometry_pose.h" - -namespace dairlib { - -using Eigen::MatrixXd; -using Eigen::Vector3d; -using Eigen::VectorXd; - -using dairlib::systems::ObjectStateReceiver; -using dairlib::systems::RobotOutputReceiver; -using dairlib::systems::SubvectorPassThrough; -using drake::geometry::DrakeVisualizer; -using drake::geometry::SceneGraph; -using drake::geometry::Sphere; -using drake::math::RigidTransformd; -using drake::multibody::MultibodyPlant; -using drake::multibody::RigidBody; -using drake::multibody::SpatialInertia; -using drake::multibody::UnitInertia; -using drake::systems::Simulator; -using drake::systems::lcm::LcmSubscriberSystem; -using drake::systems::rendering::MultibodyPositionToGeometryPose; - -using drake::math::RigidTransform; -using drake::multibody::AddMultibodyPlantSceneGraph; -using drake::multibody::Parser; -using drake::systems::DiagramBuilder; - -DEFINE_string(lcm_channels, - "examples/franka/parameters/lcm_channels_simulation.yaml", - "Filepath containing lcm channels"); - -int do_main(int argc, char* argv[]) { - gflags::ParseCommandLineFlags(&argc, &argv, true); - FrankaSimParams sim_params = drake::yaml::LoadYamlFile( - "examples/franka/parameters/franka_sim_params.yaml"); - FrankaLcmChannels lcm_channel_params = - drake::yaml::LoadYamlFile(FLAGS_lcm_channels); - - drake::systems::DiagramBuilder builder; - - SceneGraph& scene_graph = *builder.AddSystem(); - scene_graph.set_name("scene_graph"); - - MultibodyPlant plant(0.0); - - Parser parser(&plant, &scene_graph); - parser.SetAutoRenaming(true); - drake::multibody::ModelInstanceIndex franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; - drake::multibody::ModelInstanceIndex end_effector_index = - parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; - drake::multibody::ModelInstanceIndex tray_index = - parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; - drake::multibody::ModelInstanceIndex object_index = - parser.AddModels(FindResourceOrThrow(sim_params.object_model))[0]; - multibody::AddFlatTerrain(&plant, &scene_graph, 1.0, 1.0); - - RigidTransform X_WI = RigidTransform::Identity(); - Vector3d franka_origin = Eigen::VectorXd::Zero(3); - - RigidTransform R_X_W = RigidTransform( - drake::math::RotationMatrix(), franka_origin); - RigidTransform T_EE_W = RigidTransform( - drake::math::RotationMatrix(), sim_params.tool_attachment_frame); - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), - R_X_W); - plant.WeldFrames(plant.GetFrameByName("panda_link7"), - plant.GetFrameByName("plate", end_effector_index), T_EE_W); - - drake::multibody::ModelInstanceIndex wall_index = - parser.AddModels(FindResourceOrThrow(sim_params.wall_model))[0]; - RigidTransform T_Wall_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.wall_orientation), - sim_params.wall_position); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("base", wall_index), T_Wall_W); - - - plant.Finalize(); - - auto lcm = builder.AddSystem(); - - // Create state receiver. - auto franka_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.franka_state_channel, lcm)); - auto tray_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.tray_state_channel, lcm)); - auto object_state_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.object_state_channel, lcm)); - auto franka_state_receiver = - builder.AddSystem(plant, franka_index); - auto tray_state_receiver = - builder.AddSystem(plant, tray_index); - auto object_state_receiver = - builder.AddSystem(plant, object_index); - - auto franka_passthrough = builder.AddSystem( - franka_state_receiver->get_output_port(0).size(), 0, - plant.num_positions(franka_index)); - auto robot_time_passthrough = builder.AddSystem( - franka_state_receiver->get_output_port(0).size(), - franka_state_receiver->get_output_port(0).size() - 1, 1); - auto tray_passthrough = builder.AddSystem( - tray_state_receiver->get_output_port(0).size(), 0, - plant.num_positions(tray_index)); - auto object_passthrough = builder.AddSystem( - tray_state_receiver->get_output_port(0).size(), 0, - plant.num_positions(object_index)); - - std::vector input_sizes = {plant.num_positions(franka_index), - plant.num_positions(tray_index), - plant.num_positions(object_index)}; - auto mux = - builder.AddSystem>(input_sizes); - - auto trajectory_sub_actor = builder.AddSystem( - LcmSubscriberSystem::Make( - lcm_channel_params.c3_actor_channel, lcm)); - auto trajectory_sub_tray = builder.AddSystem( - LcmSubscriberSystem::Make( - lcm_channel_params.c3_object_channel, lcm)); - auto trajectory_sub_force = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.c3_force_channel, lcm)); - - auto c3_state_actual_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.c3_actual_state_channel, lcm)); - auto c3_state_target_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.c3_target_state_channel, lcm)); - auto to_pose = - builder.AddSystem>(plant); - - drake::geometry::MeshcatVisualizerParams params; - params.publish_period = 1.0 / sim_params.visualizer_publish_rate; - auto meshcat = std::make_shared(); - auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( - &builder, scene_graph, meshcat, std::move(params)); - meshcat->SetCameraPose(sim_params.camera_pose[sim_params.scene_index], sim_params.camera_target[sim_params.scene_index]); - - if (sim_params.visualize_workspace){ - double width = sim_params.world_x_limits[sim_params.scene_index][1] - sim_params.world_x_limits[sim_params.scene_index][0]; - double depth = sim_params.world_y_limits[sim_params.scene_index][1] - sim_params.world_y_limits[sim_params.scene_index][0]; - double height = sim_params.world_z_limits[sim_params.scene_index][1] - sim_params.world_z_limits[sim_params.scene_index][0]; - Vector3d workspace_center = {0.5 * (sim_params.world_x_limits[sim_params.scene_index][1] + sim_params.world_x_limits[sim_params.scene_index][0]), - 0.5 * (sim_params.world_y_limits[sim_params.scene_index][1] + sim_params.world_y_limits[sim_params.scene_index][0]), - 0.5 * (sim_params.world_z_limits[sim_params.scene_index][1] + sim_params.world_z_limits[sim_params.scene_index][0])}; - meshcat->SetObject("c3_state/workspace", drake::geometry::Box(width, depth, height), - {1, 0, 0, 0.2}); - meshcat->SetTransform("c3_state/workspace", RigidTransformd(workspace_center)); - } - if (sim_params.visualize_center_of_mass_plan){ - auto trajectory_drawer_actor = - builder.AddSystem( - meshcat, "end_effector_position_target"); - auto trajectory_drawer_object = - builder.AddSystem(meshcat, - "object_position_target"); - trajectory_drawer_actor->SetLineColor(drake::geometry::Rgba({1, 0, 0, 1})); - trajectory_drawer_object->SetLineColor(drake::geometry::Rgba({0, 0, 1, 1})); - trajectory_drawer_actor->SetNumSamples(40); - trajectory_drawer_object->SetNumSamples(40); - builder.Connect(trajectory_sub_actor->get_output_port(), - trajectory_drawer_actor->get_input_port_trajectory()); - builder.Connect(trajectory_sub_tray->get_output_port(), - trajectory_drawer_object->get_input_port_trajectory()); - } - - if (sim_params.visualize_pose_trace){ - auto object_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow("examples/franka/urdf/tray_transparent.sdf"), - "object_position_target", "object_orientation_target"); - auto end_effector_pose_drawer = builder.AddSystem( - meshcat, FindResourceOrThrow(sim_params.end_effector_model), - "end_effector_position_target", "end_effector_orientation_target"); - - builder.Connect(trajectory_sub_tray->get_output_port(), - object_pose_drawer->get_input_port_trajectory()); - builder.Connect(trajectory_sub_actor->get_output_port(), - end_effector_pose_drawer->get_input_port_trajectory()); - } - - if (sim_params.visualize_c3_state){ - auto c3_target_drawer = - builder.AddSystem(meshcat, true, false); - builder.Connect(c3_state_actual_sub->get_output_port(), - c3_target_drawer->get_input_port_c3_state_actual()); - builder.Connect(c3_state_target_sub->get_output_port(), - c3_target_drawer->get_input_port_c3_state_target()); - } - - if (sim_params.visualize_c3_forces){ - auto end_effector_force_drawer = builder.AddSystem( - meshcat, "end_effector_position_target", "end_effector_force_target", - "lcs_force_trajectory"); - builder.Connect(trajectory_sub_actor->get_output_port(), - end_effector_force_drawer->get_input_port_actor_trajectory()); - builder.Connect(trajectory_sub_force->get_output_port(), - end_effector_force_drawer->get_input_port_force_trajectory()); - builder.Connect(robot_time_passthrough->get_output_port(), - end_effector_force_drawer->get_input_port_robot_time()); - } - - builder.Connect(franka_passthrough->get_output_port(), - mux->get_input_port(0)); - builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); - builder.Connect(object_passthrough->get_output_port(), mux->get_input_port(2)); - builder.Connect(*mux, *to_pose); - builder.Connect( - to_pose->get_output_port(), - scene_graph.get_source_pose_port(plant.get_source_id().value())); - builder.Connect(*franka_state_receiver, *franka_passthrough); - builder.Connect(*franka_state_receiver, *robot_time_passthrough); - builder.Connect(*tray_state_receiver, *tray_passthrough); - builder.Connect(*object_state_receiver, *object_passthrough); - builder.Connect(*franka_state_sub, *franka_state_receiver); - builder.Connect(*tray_state_sub, *tray_state_receiver); - builder.Connect(*object_state_sub, *object_state_receiver); - - auto diagram = builder.Build(); - auto context = diagram->CreateDefaultContext(); - - auto& franka_state_sub_context = - diagram->GetMutableSubsystemContext(*franka_state_sub, context.get()); - auto& tray_state_sub_context = - diagram->GetMutableSubsystemContext(*tray_state_sub, context.get()); - auto& object_state_sub_context = - diagram->GetMutableSubsystemContext(*object_state_sub, context.get()); - franka_state_receiver->InitializeSubscriberPositions( - plant, franka_state_sub_context); - tray_state_receiver->InitializeSubscriberPositions(plant, - tray_state_sub_context); - object_state_receiver->InitializeSubscriberPositions(plant, - object_state_sub_context); - - /// Use the simulator to drive at a fixed rate - /// If set_publish_every_time_step is true, this publishes twice - /// Set realtime rate. Otherwise, runs as fast as possible - auto stepper = - std::make_unique>(*diagram, std::move(context)); - stepper->set_publish_every_time_step(false); - stepper->set_publish_at_initialization(false); - stepper->set_target_realtime_rate( - 1.0); // may need to change this to param.real_time_rate? - stepper->Initialize(); - - drake::log()->info("visualizer started"); - - stepper->AdvanceTo(std::numeric_limits::infinity()); - - return 0; -} - -} // namespace dairlib - -int main(int argc, char* argv[]) { return dairlib::do_main(argc, argv); } diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 2b6ce2ef94..f435cd8a7e 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -17,27 +17,28 @@ publish_frequency : 0 #publish_frequency: 25 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] -workspace_limits: [] +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], + [0.0, 1.0, 0.0, -0.15, 0.15]] #world_y_limits: [-0.1, 0.1] #world_z_limits: [0.35, 0.7] workspace_margins: 0.05 -u_horizontal_limits: [-10, 10] +u_horizontal_limits: [-20, 20] u_vertical_limits: [0, 30] -mu: [0.6, 0.6, 0.6, 0.1] +mu: [0.6, 0.6, 0.6, 0.1, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 -num_contacts: 4 +num_contacts: 5 N: 5 gamma: 1.0 # discount factor on MPC costs #matrix scaling -w_Q: 100 -w_R: 50 +w_Q: 50 +w_R: 5 #Penalty on all decision variables, assuming scalar -w_G: 0.15 +w_G: 0.5 #Penalty on all decision variables, assuming scalar w_U: 0.1 @@ -52,7 +53,7 @@ g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] #Penalty on matching the QP variables @@ -60,5 +61,5 @@ u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index c44d83cc11..41f7b6fe2e 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -5,7 +5,10 @@ end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf tool_attachment_frame: [0, 0, 0.107] end_effector_thickness: 0.016 object_models: [examples/franka/urdf/tray_lcs.sdf] -environment_models: [examples/franka/urdf/side_wall.urdf] +environment_models: [examples/franka/urdf/side_wall.urdf, + examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ -environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.3, 0.25]] \ No newline at end of file +environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0]] +environment_positions: [[0.6, 0.35, 0.25], + [0.6, -0.35, 0.25]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 78c3ddfc8b..5aaaa8bba8 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -19,18 +19,18 @@ near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], [0.3897, 0.025, 0.49], - [0.45, 0.0, 0.5], - [0.45, 0.0, 0.5],] + [0.45, 0.0, 0.485], + [0.55, 0.0, 0.485],] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.3897, 0.025, 0.6], - [0.45, 0.0, 0.5], - [0.45, 0.0, 0.5],] + [0.45, 0.0, 0.485], + [0.45, 0.0, 0.485],] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], [0.6062, 0.15, 0.49], - [0.45, 0.0, 0.5], - [0.45, 0.0, 0.5],] + [0.45, 0.0, 0.485], + [0.55, 0.0, 0.485],] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 6f6587bccb..f00b966951 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -2,16 +2,12 @@ #include "drake/common/yaml/yaml_read_archive.h" - struct FrankaSimParams { + std::vector sim_scene_file; std::string franka_model; std::string end_effector_model; std::string tray_model; std::string object_model; - std::string left_support_model; - std::string right_support_model; - std::string center_support_model; - std::string wall_model; double dt; double realtime_rate; @@ -25,20 +21,10 @@ struct FrankaSimParams { bool visualize_drake_sim; bool publish_efforts; - std::vector camera_pose; - std::vector camera_target; - Eigen::VectorXd q_init_franka; std::vector q_init_plate; std::vector q_init_object; Eigen::VectorXd tool_attachment_frame; - Eigen::VectorXd left_support_position; - Eigen::VectorXd right_support_position; - Eigen::VectorXd left_support_orientation; - Eigen::VectorXd right_support_orientation; - Eigen::VectorXd wall_position; - Eigen::VectorXd wall_orientation; - Eigen::VectorXd center_support_offset; std::vector world_x_limits; std::vector world_y_limits; @@ -52,14 +38,11 @@ struct FrankaSimParams { template void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(sim_scene_file)); a->Visit(DRAKE_NVP(franka_model)); a->Visit(DRAKE_NVP(end_effector_model)); a->Visit(DRAKE_NVP(tray_model)); a->Visit(DRAKE_NVP(object_model)); - a->Visit(DRAKE_NVP(left_support_model)); - a->Visit(DRAKE_NVP(right_support_model)); - a->Visit(DRAKE_NVP(center_support_model)); - a->Visit(DRAKE_NVP(wall_model)); a->Visit(DRAKE_NVP(dt)); a->Visit(DRAKE_NVP(realtime_rate)); @@ -73,20 +56,10 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(visualize_drake_sim)); a->Visit(DRAKE_NVP(publish_efforts)); - a->Visit(DRAKE_NVP(camera_pose)); - a->Visit(DRAKE_NVP(camera_target)); - a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); a->Visit(DRAKE_NVP(q_init_object)); a->Visit(DRAKE_NVP(tool_attachment_frame)); - a->Visit(DRAKE_NVP(left_support_position)); - a->Visit(DRAKE_NVP(right_support_position)); - a->Visit(DRAKE_NVP(left_support_orientation)); - a->Visit(DRAKE_NVP(right_support_orientation)); - a->Visit(DRAKE_NVP(wall_position)); - a->Visit(DRAKE_NVP(wall_orientation)); - a->Visit(DRAKE_NVP(center_support_offset)); a->Visit(DRAKE_NVP(world_x_limits)); a->Visit(DRAKE_NVP(world_y_limits)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index bf662432d4..63ee5cc16a 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -2,10 +2,6 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray.sdf object_model: examples/franka/urdf/cylinder_object.urdf -left_support_model: examples/franka/urdf/support.urdf -right_support_model: examples/franka/urdf/support.urdf -center_support_model: examples/franka/urdf/center_support.urdf -wall_model: examples/franka/urdf/side_wall.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 object_publish_rate: 1000 @@ -25,14 +21,10 @@ camera_target: [[0.5, 0, 0.5], tool_attachment_frame: [0, 0, 0.107] - -left_support_position: [0.8, 0.15, 0.447] -right_support_position: [0.8, -0.15, 0.447] -left_support_orientation: [0.0, 0.0, 0.0] -right_support_orientation: [0.0, 0.0, 0.0] -wall_position: [0.6, 0.3, 0.25] -wall_orientation: [0.0, 0.0, 0.0] -center_support_offset: [-0.1, 0.0, 0.0] +sim_scene_file: [examples/franka/parameters/sim_scenes/tray_scene.yaml, + examples/franka/parameters/sim_scenes/supports_scene.yaml, + examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml, + examples/franka/parameters/sim_scenes/wall_scene.yaml] #left_support_position: [0.6178, 0.3299, 0.45 ] #right_support_position: [0.7678, 0.0701, 0.45 ] @@ -54,10 +46,10 @@ world_z_limits: [[0.35, 0.7], [0.35, 0.7]] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.1 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.5], +q_init_plate: [[1, 0, 0, 0, 0.55, -0.075, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ]] diff --git a/examples/franka/parameters/franka_sim_scene_params.h b/examples/franka/parameters/franka_sim_scene_params.h new file mode 100644 index 0000000000..eb5ab5a31b --- /dev/null +++ b/examples/franka/parameters/franka_sim_scene_params.h @@ -0,0 +1,23 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + +// Currently this scene only defines static environment obstacles +struct FrankaSimSceneParams { + std::vector environment_models; + std::vector environment_orientations; + std::vector environment_positions; + + std::vector camera_pose; + std::vector camera_target; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(environment_models)); + a->Visit(DRAKE_NVP(environment_orientations)); + a->Visit(DRAKE_NVP(environment_positions)); + + a->Visit(DRAKE_NVP(camera_pose)); + a->Visit(DRAKE_NVP(camera_target)); + } +}; \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/empty_scene.yaml b/examples/franka/parameters/sim_scenes/empty_scene.yaml new file mode 100644 index 0000000000..2629e2f9d2 --- /dev/null +++ b/examples/franka/parameters/sim_scenes/empty_scene.yaml @@ -0,0 +1,4 @@ +environment_models: [] +# orientation in RPY then position in XYZ +environment_orientations: [] +environment_positions: [] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml b/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml new file mode 100644 index 0000000000..62a81eaca8 --- /dev/null +++ b/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml @@ -0,0 +1,7 @@ +environment_models: [examples/franka/urdf/support.urdf, + examples/franka/urdf/support.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0. , 0. , 0.5236], + [0. , 0. , 0.5236]] +environment_positions: [[0.6178, 0.3299, 0.45 ], + [0.7678, 0.0701, 0.45 ]] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/supports_scene.yaml b/examples/franka/parameters/sim_scenes/supports_scene.yaml new file mode 100644 index 0000000000..82b324fb29 --- /dev/null +++ b/examples/franka/parameters/sim_scenes/supports_scene.yaml @@ -0,0 +1,9 @@ +environment_models: [examples/franka/urdf/support.urdf, + examples/franka/urdf/support.urdf, + examples/franka/urdf/center_support.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0]] +environment_positions: [[0.8, 0.15, 0.447], + [0.8, -0.15, 0.447], + [0.7, 0.0, 0.447]] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml new file mode 100644 index 0000000000..79d2e8a1d4 --- /dev/null +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -0,0 +1,7 @@ +environment_models: [examples/franka/urdf/side_wall.urdf, + examples/franka/urdf/side_wall.urdf] +# orientation in RPY then position in XYZ +environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0]] +environment_positions: [[0.6, 0.35, 0.25], + [0.6, -0.35, 0.25]] \ No newline at end of file diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf index ab8535e918..8ff34c5381 100644 --- a/examples/franka/urdf/side_wall.urdf +++ b/examples/franka/urdf/side_wall.urdf @@ -15,7 +15,7 @@ - cod + cod @@ -26,7 +26,7 @@ - cod + cod From 5277f65e76fc73f5af123c3513cc20d88ac020b8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 1 Apr 2024 13:08:46 -0400 Subject: [PATCH 679/758] working on tuning wall scene --- examples/franka/franka_visualizer.cc | 4 +- examples/franka/full_diagram.cc | 64 +++++++++---------- .../franka_c3_options_side_supports.yaml | 2 +- .../c3_options/franka_c3_options_wall.yaml | 10 +-- .../franka_c3_controller_params.yaml | 9 +-- .../franka/parameters/franka_sim_params.yaml | 29 ++++----- .../parameters/franka_sim_scene_params.h | 4 +- .../parameters/sim_scenes/empty_scene.yaml | 5 +- .../sim_scenes/supports_rotated_scene.yaml | 5 +- .../parameters/sim_scenes/supports_scene.yaml | 6 +- .../parameters/sim_scenes/wall_scene.yaml | 5 +- examples/franka/urdf/side_wall.urdf | 2 +- 12 files changed, 73 insertions(+), 72 deletions(-) diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 12ef32ff4e..2fba74329c 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -182,8 +182,8 @@ int do_main(int argc, char* argv[]) { auto meshcat = std::make_shared(); auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( &builder, scene_graph, meshcat, std::move(params)); - meshcat->SetCameraPose(scene_params.camera_pose[sim_params.scene_index], - scene_params.camera_target[sim_params.scene_index]); + meshcat->SetCameraPose(scene_params.camera_pose, + scene_params.camera_target); if (sim_params.visualize_workspace) { double width = sim_params.world_x_limits[sim_params.scene_index][1] - diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 7f80d0979f..54b1bb3129 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -27,6 +27,7 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/parameters/franka_sim_scene_params.h" #include "multibody/multibody_utils.h" #include "systems/primitives/radio_parser.h" #include "systems/primitives/subvector_pass_through.h" @@ -59,6 +60,9 @@ int DoMain(int argc, char* argv[]) { // load parameters FrankaSimParams sim_params = drake::yaml::LoadYamlFile( "examples/franka/parameters/franka_sim_params.yaml"); + FrankaSimSceneParams scene_params = + drake::yaml::LoadYamlFile( + sim_params.sim_scene_file[sim_params.scene_index]); FrankaC3ControllerParams c3_params = drake::yaml::LoadYamlFile( "examples/franka/parameters/franka_c3_controller_params.yaml"); @@ -91,41 +95,33 @@ int DoMain(int argc, char* argv[]) { plant.GetFrameByName("plate", c3_end_effector_index), T_EE_W); - if (sim_params.scene_index > 0) { - drake::multibody::ModelInstanceIndex left_support_index = - parser.AddModels(FindResourceOrThrow(sim_params.left_support_model))[0]; - drake::multibody::ModelInstanceIndex right_support_index = parser.AddModels( - FindResourceOrThrow(sim_params.right_support_model))[0]; - RigidTransform T_S1_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.left_support_orientation), - sim_params.left_support_position); - RigidTransform T_S2_W = RigidTransform( - drake::math::RollPitchYaw(sim_params.right_support_orientation), - sim_params.right_support_position); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", left_support_index), - T_S1_W); - plant.WeldFrames(plant.world_frame(), - plant.GetFrameByName("support", right_support_index), - T_S2_W); - const drake::geometry::GeometrySet& support_geom_set = - plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("support", left_support_index), - &plant.GetBodyByName("support", right_support_index), - }); - // we WANT to model collisions between link5 and the supports - const drake::geometry::GeometrySet& paddle_geom_set = - plant.CollectRegisteredGeometries( - {&plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link7"), &plant.GetBodyByName("plate"), - &plant.GetBodyByName("panda_link8")}); - - plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( - {"paddle", support_geom_set}, {"tray", paddle_geom_set}); + const drake::geometry::GeometrySet& franka_geom_set = + plant.CollectRegisteredGeometries({&plant.GetBodyByName("panda_link0"), + &plant.GetBodyByName("panda_link1"), + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4")}); + + drake::geometry::GeometrySet support_geom_set; + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = parser.AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = + RigidTransform(drake::math::RollPitchYaw( + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); + plant.WeldFrames( + plant.world_frame(), + plant.GetFrameByName("base", environment_model_indices[i]), + T_E_W); + support_geom_set.Add(plant.GetCollisionGeometriesForBody(plant.GetBodyByName("base", + environment_model_indices[i]))); } + plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( + {"supports", support_geom_set}, {"franka", franka_geom_set}); + const drake::geometry::GeometrySet& paddle_geom_set = plant.CollectRegisteredGeometries({ diff --git a/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml index 14dba977c8..56a8be697d 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml @@ -17,7 +17,7 @@ publish_frequency: 0 # Workspace Limits (specified as Linear Constraints on the end effector position) workspace_limits: [[0.866, 0.5, 0.0, 0.4, 0.6], - [-0.5 , 0.866, 0.0, -0.2, -0.0], + [-0.5 , 0.866, 0.0, -0.1, -0.1], [0.0, 0.0, 1.0, 0.35, 0.7]] workspace_margins: 0.05 diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index f435cd8a7e..311cc49828 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -10,7 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true -end_on_qp_step: false +end_on_qp_step: true solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible publish_frequency : 0 @@ -18,7 +18,7 @@ publish_frequency : 0 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], - [0.0, 1.0, 0.0, -0.15, 0.15]] + [0.0, 1.0, 0.0, -0.1, 0.1]] #world_y_limits: [-0.1, 0.1] #world_z_limits: [0.35, 0.7] workspace_margins: 0.05 @@ -36,14 +36,14 @@ gamma: 1.0 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 5 +w_R: 50 #Penalty on all decision variables, assuming scalar w_G: 0.5 #Penalty on all decision variables, assuming scalar w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 1, 1, 0, 5000, 5000, 5000, +q_vector: [150, 150, 150, 0, 1, 1, 0, 5000, 50000, 10000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] @@ -54,7 +54,7 @@ g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [1, 1, 1] +g_u: [1, 50, 1] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 5aaaa8bba8..7b6945b932 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,13 +1,11 @@ -scene_index: 4 +scene_index: 3 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml, - examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_wall.yaml,] c3_scene_file: [examples/franka/parameters/c3_scenes/tray_scene.yaml, examples/franka/parameters/c3_scenes/supports_scene.yaml, examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml, - examples/franka/parameters/c3_scenes/two_object_scene.yaml, examples/franka/parameters/c3_scenes/wall_scene.yaml] osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml @@ -19,17 +17,14 @@ near_target_threshold: 0.05 first_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.485], [0.3897, 0.025, 0.49], - [0.45, 0.0, 0.485], [0.55, 0.0, 0.485],] second_target: [[0.45, 0.0, 0.5], [0.45, 0, 0.6], [0.3897, 0.025, 0.6], - [0.45, 0.0, 0.485], - [0.45, 0.0, 0.485],] + [0.55, 0.0, 0.485],] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], [0.6062, 0.15, 0.49], - [0.45, 0.0, 0.485], [0.55, 0.0, 0.485],] x_scale: 0.1 y_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 63ee5cc16a..f995cfa350 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,20 +8,13 @@ object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 0 +scene_index: 3 visualize_drake_sim: true publish_efforts: true -camera_pose: [[1.5, 0, 0.6], - [0.5, -0.9, 0.75], - [1.5, 0, 0.6]] -camera_target: [[0.5, 0, 0.5], - [0.5, 0, 0.5], - [0.5, 0, 0.55]] - tool_attachment_frame: [0, 0, 0.107] -sim_scene_file: [examples/franka/parameters/sim_scenes/tray_scene.yaml, +sim_scene_file: [examples/franka/parameters/sim_scenes/empty_scene.yaml, examples/franka/parameters/sim_scenes/supports_scene.yaml, examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml, examples/franka/parameters/sim_scenes/wall_scene.yaml] @@ -37,29 +30,33 @@ sim_scene_file: [examples/franka/parameters/sim_scenes/tray_scene.yaml, # Workspace Limits world_x_limits: [[0.4, 0.6], [0.4, 0.6], + [0.45, 0.65], [0.45, 0.65]] world_y_limits: [[-0.15, 0.15], [-0.1, 0.1], - [-0.05, 0.3]] + [-0.05, 0.3], + [0.45, 0.65]] world_z_limits: [[0.35, 0.7], [0.35, 0.7], - [0.35, 0.7]] + [0.35, 0.7], + [0.45, 0.65]] dt: 0.0005 -realtime_rate: 0.1 +realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.55, -0.075, 0.465], +q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], - [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ]] + [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], + [1, 0, 0, 0, 0.55, 0.06, 0.465]] q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1, 0, 0, 0, 0.7, 0.00, 0.0], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.5 ], - [1. , 0. , 0. , 0. , 0.55, 0.0 , 0.5 ]] + [1. , 0. , 0. , 0. , 0.55, 0.0 , 0.0 ]] visualize_workspace: false -visualize_pose_trace: false +visualize_pose_trace: true visualize_center_of_mass_plan: true visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/parameters/franka_sim_scene_params.h b/examples/franka/parameters/franka_sim_scene_params.h index eb5ab5a31b..dc141151d4 100644 --- a/examples/franka/parameters/franka_sim_scene_params.h +++ b/examples/franka/parameters/franka_sim_scene_params.h @@ -8,8 +8,8 @@ struct FrankaSimSceneParams { std::vector environment_orientations; std::vector environment_positions; - std::vector camera_pose; - std::vector camera_target; + Eigen::VectorXd camera_pose; + Eigen::VectorXd camera_target; template void Serialize(Archive* a) { diff --git a/examples/franka/parameters/sim_scenes/empty_scene.yaml b/examples/franka/parameters/sim_scenes/empty_scene.yaml index 2629e2f9d2..b813f26d31 100644 --- a/examples/franka/parameters/sim_scenes/empty_scene.yaml +++ b/examples/franka/parameters/sim_scenes/empty_scene.yaml @@ -1,4 +1,7 @@ environment_models: [] # orientation in RPY then position in XYZ environment_orientations: [] -environment_positions: [] \ No newline at end of file +environment_positions: [] + +camera_pose: [1.5, 0, 0.6] +camera_target: [0.5, 0, 0.5] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml b/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml index 62a81eaca8..412a5ae72a 100644 --- a/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml +++ b/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml @@ -4,4 +4,7 @@ environment_models: [examples/franka/urdf/support.urdf, environment_orientations: [[0. , 0. , 0.5236], [0. , 0. , 0.5236]] environment_positions: [[0.6178, 0.3299, 0.45 ], - [0.7678, 0.0701, 0.45 ]] \ No newline at end of file + [0.7678, 0.0701, 0.45 ]] + +camera_pose: [ 0.5, -0.9, 0.75 ] +camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/supports_scene.yaml b/examples/franka/parameters/sim_scenes/supports_scene.yaml index 82b324fb29..1f9c99e12a 100644 --- a/examples/franka/parameters/sim_scenes/supports_scene.yaml +++ b/examples/franka/parameters/sim_scenes/supports_scene.yaml @@ -3,7 +3,11 @@ environment_models: [examples/franka/urdf/support.urdf, examples/franka/urdf/center_support.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0], + [0.0, 0.0, 0.0], [0.0, 0.0, 0.0]] environment_positions: [[0.8, 0.15, 0.447], [0.8, -0.15, 0.447], - [0.7, 0.0, 0.447]] \ No newline at end of file + [0.7, 0.0, 0.447]] + +camera_pose: [0.5, -0.9, 0.75] +camera_target: [0.5, 0, 0.5] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index 79d2e8a1d4..e7d6b6cc2b 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -4,4 +4,7 @@ environment_models: [examples/franka/urdf/side_wall.urdf, environment_orientations: [[0.0, 0.0, 0.0], [0.0, 0.0, 0.0]] environment_positions: [[0.6, 0.35, 0.25], - [0.6, -0.35, 0.25]] \ No newline at end of file + [0.6, -0.35, 0.25]] + +camera_pose: [ 0.5, -0.9, 0.75 ] +camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf index 8ff34c5381..1dc7cb8ff0 100644 --- a/examples/franka/urdf/side_wall.urdf +++ b/examples/franka/urdf/side_wall.urdf @@ -20,7 +20,7 @@ - + From b21634a0fa0089af758c438fc2815903883d6f2d Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 1 Apr 2024 14:57:08 -0400 Subject: [PATCH 680/758] still tuning wall example --- .../c3_options/franka_c3_options_wall.yaml | 36 +++++++++---------- .../parameters/c3_scenes/wall_scene.yaml | 9 ++--- .../franka/parameters/franka_sim_params.yaml | 14 ++------ .../parameters/franka_sim_scene_params.h | 2 ++ .../parameters/sim_scenes/wall_scene.yaml | 9 ++--- examples/franka/urdf/cylinder_object.urdf | 2 +- examples/franka/urdf/side_wall.urdf | 2 +- examples/franka/urdf/tray.sdf | 2 +- solvers/c3_options.h | 7 ++-- 9 files changed, 36 insertions(+), 47 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 311cc49828..a0f152b977 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -10,56 +10,54 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true -end_on_qp_step: true +end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible publish_frequency : 0 #publish_frequency: 25 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] -workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], - [0.0, 1.0, 0.0, -0.1, 0.1]] -#world_y_limits: [-0.1, 0.1] -#world_z_limits: [0.35, 0.7] +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.7], + [0.0, 1.0, 0.0, -0.15, 0.15]] workspace_margins: 0.05 -u_horizontal_limits: [-20, 20] +u_horizontal_limits: [-30, 30] u_vertical_limits: [0, 30] -mu: [0.6, 0.6, 0.6, 0.1, 0.1] +mu: [0.6, 0.6, 0.6, 0.1] dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 -num_contacts: 5 +num_contacts: 4 N: 5 gamma: 1.0 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 50 +w_R: 25 #Penalty on all decision variables, assuming scalar w_G: 0.5 #Penalty on all decision variables, assuming scalar w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 1, 1, 0, 5000, 50000, 10000, +q_vector: [100, 100, 100, 0, 1, 1, 0, 15000, 20000, 15000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -g_gamma: [1, 1, 1, 1, 1, 1, 1] -g_lambda_n: [1, 1, 1, 1, 1, 1, 1] -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [1, 50, 1] +g_gamma: [1, 1, 1, 1] +g_lambda_n: [1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 250, 250, 250, 250] +g_u: [1, 1, 1] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_gamma: [1, 1, 1, 1, 1, 1, 1] -u_lambda_n: [1, 1, 1, 1, 1, 1, 1] -u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_gamma: [1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 250, 250, 250, 250] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index 41f7b6fe2e..993502d4d4 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -5,10 +5,7 @@ end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf tool_attachment_frame: [0, 0, 0.107] end_effector_thickness: 0.016 object_models: [examples/franka/urdf/tray_lcs.sdf] -environment_models: [examples/franka/urdf/side_wall.urdf, - examples/franka/urdf/side_wall.urdf] +environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ -environment_orientations: [[0.0, 0.0, 0.0], - [0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.35, 0.25], - [0.6, -0.35, 0.25]] \ No newline at end of file +environment_orientations: [[0.0, 0.0, 0.0]] +environment_positions: [[0.6, 0.35, 0.35]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index f995cfa350..abfd580e05 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,6 +1,6 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf -tray_model: examples/franka/urdf/tray.sdf +tray_model: examples/franka/urdf/tray_lcs.sdf object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 @@ -19,14 +19,6 @@ sim_scene_file: [examples/franka/parameters/sim_scenes/empty_scene.yaml, examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml, examples/franka/parameters/sim_scenes/wall_scene.yaml] -#left_support_position: [0.6178, 0.3299, 0.45 ] -#right_support_position: [0.7678, 0.0701, 0.45 ] -#left_support_orientation: [0. , 0. , 0.5236] -#right_support_orientation: [0. , 0. , 0.5236] - -#left_support_orientation: [0.0, 0.0, 1.57] -#right_support_orientation: [0.0, 0.0, 1.57] - # Workspace Limits world_x_limits: [[0.4, 0.6], [0.4, 0.6], @@ -48,7 +40,7 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], - [1, 0, 0, 0, 0.55, 0.06, 0.465]] + [1, 0, 0, 0, 0.55, 0.0, 0.465]] q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1, 0, 0, 0, 0.7, 0.00, 0.0], @@ -56,7 +48,7 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1. , 0. , 0. , 0. , 0.55, 0.0 , 0.0 ]] visualize_workspace: false -visualize_pose_trace: true +visualize_pose_trace: false visualize_center_of_mass_plan: true visualize_c3_forces: true visualize_c3_state: true diff --git a/examples/franka/parameters/franka_sim_scene_params.h b/examples/franka/parameters/franka_sim_scene_params.h index dc141151d4..cc546c6b30 100644 --- a/examples/franka/parameters/franka_sim_scene_params.h +++ b/examples/franka/parameters/franka_sim_scene_params.h @@ -16,6 +16,8 @@ struct FrankaSimSceneParams { a->Visit(DRAKE_NVP(environment_models)); a->Visit(DRAKE_NVP(environment_orientations)); a->Visit(DRAKE_NVP(environment_positions)); + DRAKE_DEMAND(environment_models.size() == environment_orientations.size()); + DRAKE_DEMAND(environment_models.size() == environment_positions.size()); a->Visit(DRAKE_NVP(camera_pose)); a->Visit(DRAKE_NVP(camera_target)); diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index e7d6b6cc2b..fae6b25da4 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -1,10 +1,7 @@ -environment_models: [examples/franka/urdf/side_wall.urdf, - examples/franka/urdf/side_wall.urdf] +environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ -environment_orientations: [[0.0, 0.0, 0.0], - [0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.35, 0.25], - [0.6, -0.35, 0.25]] +environment_orientations: [[0.0, 0.0, 0.0]] +environment_positions: [[0.6, 0.35, 0.35]] camera_pose: [ 0.5, -0.9, 0.75 ] camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/urdf/cylinder_object.urdf b/examples/franka/urdf/cylinder_object.urdf index cdfcc40000..dc5bb57b9c 100644 --- a/examples/franka/urdf/cylinder_object.urdf +++ b/examples/franka/urdf/cylinder_object.urdf @@ -14,7 +14,7 @@ - + diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf index 1dc7cb8ff0..157f56699c 100644 --- a/examples/franka/urdf/side_wall.urdf +++ b/examples/franka/urdf/side_wall.urdf @@ -20,7 +20,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index d21382eea2..28f0afa776 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -39,7 +39,7 @@ 3.0e7 - 0.18 + 0.15 10 0.4 diff --git a/solvers/c3_options.h b/solvers/c3_options.h index d9c208eb97..d18069b7ce 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -82,8 +82,6 @@ struct C3Options { a->Visit(DRAKE_NVP(publish_frequency)); a->Visit(DRAKE_NVP(workspace_limits)); -// a->Visit(DRAKE_NVP(world_y_limits)); -// a->Visit(DRAKE_NVP(world_z_limits)); a->Visit(DRAKE_NVP(u_horizontal_limits)); a->Visit(DRAKE_NVP(u_vertical_limits)); a->Visit(DRAKE_NVP(workspace_margins)); @@ -146,6 +144,11 @@ struct C3Options { Eigen::VectorXd u = Eigen::Map( this->u_vector.data(), this->u_vector.size()); + DRAKE_DEMAND(g_lambda.size() == num_contacts * num_friction_directions*2); + DRAKE_DEMAND(u_lambda.size() == num_contacts * num_friction_directions*2); + DRAKE_DEMAND(mu.size() == num_contacts); + DRAKE_DEMAND(g.size() == u.size()); + Q = w_Q * q.asDiagonal(); R = w_R * r.asDiagonal(); G = w_G * g.asDiagonal(); From b87ee502a00b8c446a9b59b895e17365c532c5a9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 1 Apr 2024 16:33:44 -0400 Subject: [PATCH 681/758] gains that somewhat work for wall example --- .../c3_options/franka_c3_options_wall.yaml | 27 ++++++++++--------- .../franka/parameters/franka_sim_params.yaml | 8 +++--- .../parameters/sim_scenes/wall_scene.yaml | 2 +- .../lcm_visualization_systems.cc | 4 +-- .../visualization/lcm_visualization_systems.h | 2 +- 5 files changed, 22 insertions(+), 21 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index a0f152b977..6a399392a7 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -1,7 +1,7 @@ admm_iter: 2 rho: 0 # does not do anything rho_scale: 4 -num_threads: 5 +num_threads: 6 delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' @@ -18,40 +18,41 @@ publish_frequency : 0 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.7], - [0.0, 1.0, 0.0, -0.15, 0.15]] + [0.0, 1.0, 0.0, -0.15, 0.15], + [0.0, 0.0, 1.0, 0.35, 0.6]] workspace_margins: 0.05 -u_horizontal_limits: [-30, 30] -u_vertical_limits: [0, 30] +u_horizontal_limits: [-20, 20] +u_vertical_limits: [-20, 30] mu: [0.6, 0.6, 0.6, 0.1] -dt: 0.075 +dt: 0.06 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 4 -N: 5 +N: 6 gamma: 1.0 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 25 +w_R: 20 #Penalty on all decision variables, assuming scalar -w_G: 0.5 +w_G: 0.1 #Penalty on all decision variables, assuming scalar w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [100, 100, 100, 0, 1, 1, 0, 15000, 20000, 15000, - 5, 5, 15, 10, 10, 1, 5, 5, 5] +q_vector: [50, 50, 50, 0, 1, 1, 0, 75000, 75000, 75000, + 5, 5, 5, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal -r_vector: [0.15, 0.15, 0.1] +r_vector: [0.1, 0.1, 0.01] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 250, 250, 250, 250] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 2000, 2000, 2000, 2000] g_u: [1, 1, 1] #Penalty on matching the QP variables @@ -59,5 +60,5 @@ u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 250, 250, 250, 250] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index abfd580e05..82cd153571 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -3,13 +3,13 @@ end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray_lcs.sdf object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 -tray_publish_rate: 1000 +tray_publish_rate: 10 object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 3 -visualize_drake_sim: true +visualize_drake_sim: false publish_efforts: true tool_attachment_frame: [0, 0, 0.107] @@ -40,12 +40,12 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], - [1, 0, 0, 0, 0.55, 0.0, 0.465]] + [1, 0, 0, 0, 0.55, 0.06, 0.46]] q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1, 0, 0, 0, 0.7, 0.00, 0.0], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.5 ], - [1. , 0. , 0. , 0. , 0.55, 0.0 , 0.0 ]] + [1. , 0. , 0. , 0. , -0.55, 0.0 , 0.0 ]] visualize_workspace: false visualize_pose_trace: false diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index fae6b25da4..d8a332048e 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -3,5 +3,5 @@ environment_models: [examples/franka/urdf/side_wall.urdf] environment_orientations: [[0.0, 0.0, 0.0]] environment_positions: [[0.6, 0.35, 0.35]] -camera_pose: [ 0.5, -0.9, 0.75 ] +camera_pose: [ 1.5, 0, 0.75 ] camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index 14e43a1293..88c651a083 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -301,7 +301,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( auto force_norm = force.norm(); const std::string& force_path_root = force_path_ + "/lcs_force_" + std::to_string(i) + "/"; - if (force_norm >= 0.5) { + if (force_norm >= 0.1) { if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, contact_force_color_); @@ -318,7 +318,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( meshcat_->SetTransform( force_arrow_path, RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); - const double height = force_norm / newtons_per_meter_; + const double height = 2 * force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); // Note: Meshcat does not fully support non-uniform scaling (see diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index 7d9a7854e9..495de7bc1b 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -131,7 +131,7 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::geometry::Rgba actor_force_color_ = drake::geometry::Rgba(1, 0, 1, 1.0); drake::geometry::Rgba contact_force_color_ = drake::geometry::Rgba(0.949, 0.757, 0.0, 1.0); const double radius_ = 0.002; - const double newtons_per_meter_ = 40; + const double newtons_per_meter_ = 30; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, From 401cfe3c873d2b4f98e9874d14ed364f44d351ed Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 1 Apr 2024 21:18:40 -0400 Subject: [PATCH 682/758] reverting visualization scaling and small tweaks to fix rotated supports scene --- .../franka_c3_options_side_supports.yaml | 2 +- ...c3_options_side_supports_low_friction.yaml | 59 ------------------- .../franka/parameters/franka_sim_params.yaml | 6 +- .../lcm_visualization_systems.cc | 2 +- .../visualization/lcm_visualization_systems.h | 2 +- 5 files changed, 6 insertions(+), 65 deletions(-) delete mode 100644 examples/franka/parameters/c3_options/franka_c3_options_side_supports_low_friction.yaml diff --git a/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml index 56a8be697d..b16d2ed6f6 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml @@ -17,7 +17,7 @@ publish_frequency: 0 # Workspace Limits (specified as Linear Constraints on the end effector position) workspace_limits: [[0.866, 0.5, 0.0, 0.4, 0.6], - [-0.5 , 0.866, 0.0, -0.1, -0.1], + [-0.5, 0.866, 0.0, -0.2, 0.0], [0.0, 0.0, 1.0, 0.35, 0.7]] workspace_margins: 0.05 diff --git a/examples/franka/parameters/c3_options/franka_c3_options_side_supports_low_friction.yaml b/examples/franka/parameters/c3_options/franka_c3_options_side_supports_low_friction.yaml deleted file mode 100644 index 0aa173ca4c..0000000000 --- a/examples/franka/parameters/c3_options/franka_c3_options_side_supports_low_friction.yaml +++ /dev/null @@ -1,59 +0,0 @@ -admm_iter: 2 -rho: 0 # does not do anything -rho_scale: 10 -num_threads: 5 -delta_option: 1 -# options are 'MIQP' or 'QP' -projection_type: 'MIQP' -# options are 'stewart_and_trinkle' or 'anitescu' -#contact_model: 'stewart_and_trinkle' -contact_model: 'anitescu' -warm_start: true -use_predicted_x0: true -solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} - -# Workspace Limits -world_x_limits: [0.45, 0.65] -world_y_limits: [-0.2, 0.05] -world_z_limits: [0.4, 0.7] -workspace_margins: 0.05 - -u_horizontal_limits: [-10, 10] -u_vertical_limits: [0, 30] - -mu: [0.3, 0.3, 0.3, 0.2, 0.2, 0.2, 0.2] -dt: 0.075 -solve_dt: 0.05 -num_friction_directions: 2 -num_contacts: 7 -N: 5 -gamma: 1.0 # discount factor on MPC costs - -# matrix scaling -w_Q: 0.005 -w_R: 0.0005 -# Penalty on all decision variables, assuming scalar -w_G: 0.0000025 -# Penalty on all decision variables, assuming scalar -w_U: 0.000005 - -# State Tracking Error, assuming diagonal -q_vector: [150, 150, 100, 0, 1, 1, 0, 10000, 10000, 10000, - 7.5, 7.5, 15, 1, 1, 1, 1, 1, 1] -# Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 0.1] - -# Penalty on matching projected variables -g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -g_gamma: [1, 1, 1, 1, 1, 1, 1] -g_lambda_n: [1, 1, 1, 1, 1, 1, 1] -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [1, 1, 1] - -u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_gamma: [1, 1, 1, 1, 1, 1, 1] -u_lambda_n: [1, 1, 1, 1, 1, 1, 1] -u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75, 75] -u_u: [30, 30, 100] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 82cd153571..5f1e9fbaef 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,6 +1,6 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf -tray_model: examples/franka/urdf/tray_lcs.sdf +tray_model: examples/franka/urdf/tray.sdf # rigid contact model does not do sticking well object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 tray_publish_rate: 10 @@ -44,8 +44,8 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1, 0, 0, 0, 0.7, 0.00, 0.0], - [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.5 ], - [1. , 0. , 0. , 0. , -0.55, 0.0 , 0.0 ]] + [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ], + [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ]] visualize_workspace: false visualize_pose_trace: false diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index 88c651a083..2cc7cb520b 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -318,7 +318,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( meshcat_->SetTransform( force_arrow_path, RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); - const double height = 2 * force_norm / newtons_per_meter_; + const double height = force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", {0, 0, 0.5 * height}); // Note: Meshcat does not fully support non-uniform scaling (see diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index 495de7bc1b..7d9a7854e9 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -131,7 +131,7 @@ class LcmForceDrawer : public drake::systems::LeafSystem { drake::geometry::Rgba actor_force_color_ = drake::geometry::Rgba(1, 0, 1, 1.0); drake::geometry::Rgba contact_force_color_ = drake::geometry::Rgba(0.949, 0.757, 0.0, 1.0); const double radius_ = 0.002; - const double newtons_per_meter_ = 30; + const double newtons_per_meter_ = 40; }; /// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, From 33f2ca55d9638392c6ee9d9f72a94c6a8d737950 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 2 Apr 2024 15:02:38 -0400 Subject: [PATCH 683/758] working on other scenes --- .../parameter_study_config.yaml | 2 +- examples/franka/BUILD.bazel | 26 ++++ ...cc => franka_c3_controller_two_objects.cc} | 119 ++++++++++-------- examples/franka/franka_visualizer.cc | 4 +- ...> franka_c3_options_rotated_supports.yaml} | 6 +- ...s.yaml => franka_c3_options_supports.yaml} | 0 .../franka_c3_options_translation.yaml | 2 +- .../franka_c3_options_two_objects.yaml | 64 ++++++++++ .../c3_options/franka_c3_options_wall.yaml | 2 +- .../c3_scenes/two_object_scene.yaml | 11 +- .../franka_c3_controller_params.yaml | 23 ++-- .../franka_osc_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 6 +- .../franka/parameters/franka_sim_params.yaml | 15 +-- .../franka/systems/plate_balancing_target.cc | 3 - examples/franka/urdf/cylinder_lcs.urdf | 41 ++++++ solvers/c3.cc | 6 +- 17 files changed, 235 insertions(+), 97 deletions(-) rename examples/franka/{franka_c3_controller_with_wall.cc => franka_c3_controller_two_objects.cc} (81%) rename examples/franka/parameters/c3_options/{franka_c3_options_side_supports.yaml => franka_c3_options_rotated_supports.yaml} (94%) rename examples/franka/parameters/c3_options/{franka_c3_options_w_supports.yaml => franka_c3_options_supports.yaml} (100%) create mode 100644 examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml create mode 100644 examples/franka/urdf/cylinder_lcs.urdf diff --git a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml index 7a58d2e60c..32819883bb 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml +++ b/bindings/pydairlib/analysis/tray_balance_study/parameter_study_config.yaml @@ -9,7 +9,7 @@ osc_cmd: bazel-bin/examples/franka/franka_osc_controller c3_cmd: bazel-bin/examples/franka/franka_c3_controller fix_inertia_cmd: 'python3 -m pydrake.multibody.fix_inertia --in_place examples/franka/urdf/tray_parameter_sweep.sdf' -nominal_c3_gain_filename: franka_c3_options_side_supports.yaml +nominal_c3_gain_filename: franka_c3_options_rotated_supports.yaml #nominal_model_filename: tray.sdf nominal_model_filename: plate_end_effector.urdf diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index e41d5ddcfa..6dcfc7e17b 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -96,6 +96,32 @@ cc_binary( ], ) +cc_binary( + name = "franka_c3_controller_two_objects", + srcs = ["franka_c3_controller_two_objects.cc"], + data = [ + ":urdfs", + "@drake//manipulation/models/franka_description:models", + ], + deps = [ + ":parameters", + "//common", + "//examples/franka/systems:franka_systems", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers", + "//systems/controllers:c3_controller", + "//systems/controllers:lcs_factory_system", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", + "//systems/trajectory_optimization:c3_output_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "forward_kinematics_for_lcs", srcs = ["forward_kinematics_for_lcs.cc"], diff --git a/examples/franka/franka_c3_controller_with_wall.cc b/examples/franka/franka_c3_controller_two_objects.cc similarity index 81% rename from examples/franka/franka_c3_controller_with_wall.cc rename to examples/franka/franka_c3_controller_two_objects.cc index 08a188ba6d..0fdc454b5a 100644 --- a/examples/franka/franka_c3_controller_with_wall.cc +++ b/examples/franka/franka_c3_controller_two_objects.cc @@ -12,6 +12,7 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" +#include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" @@ -22,10 +23,10 @@ #include "systems/controllers/c3/lcs_factory_system.h" #include "systems/controllers/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" #include "systems/trajectory_optimization/c3_output_systems.h" -#include "systems/primitives/radio_parser.h" namespace dairlib { @@ -70,6 +71,9 @@ int DoMain(int argc, char* argv[]) { drake::yaml::LoadYamlFile(FLAGS_lcm_channels); C3Options c3_options = drake::yaml::LoadYamlFile( controller_params.c3_options_file[controller_params.scene_index]); + FrankaC3SceneParams scene_params = + drake::yaml::LoadYamlFile( + controller_params.c3_scene_file[controller_params.scene_index]); drake::solvers::SolverOptions solver_options = drake::yaml::LoadYamlFile( FindResourceOrThrow(controller_params.osqp_settings_file)) @@ -80,10 +84,10 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); parser_franka.AddModels( - drake::FindResourceOrThrow(controller_params.franka_model)); + drake::FindResourceOrThrow(scene_params.franka_model)); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( - FindResourceOrThrow(controller_params.end_effector_model))[0]; + FindResourceOrThrow(scene_params.end_effector_model))[0]; RigidTransform X_WI = RigidTransform::Identity(); plant_franka.WeldFrames(plant_franka.world_frame(), @@ -91,7 +95,7 @@ int DoMain(int argc, char* argv[]) { RigidTransform T_EE_W = RigidTransform(drake::math::RotationMatrix(), - controller_params.tool_attachment_frame); + scene_params.tool_attachment_frame); plant_franka.WeldFrames( plant_franka.GetFrameByName("panda_link7"), plant_franka.GetFrameByName("plate", end_effector_index), T_EE_W); @@ -102,38 +106,36 @@ int DoMain(int argc, char* argv[]) { /// MultibodyPlant plant_tray(0.0); Parser parser_tray(&plant_tray, nullptr); - parser_tray.AddModels(controller_params.tray_model); + + auto tray_index = parser_tray.AddModels(scene_params.object_models[0])[0]; + auto object_index = parser_tray.AddModels(scene_params.object_models[1])[0]; plant_tray.Finalize(); auto tray_context = plant_tray.CreateDefaultContext(); /// auto [plant_for_lcs, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); - Parser parser_plate(&plant_for_lcs); - parser_plate.SetAutoRenaming(true); - parser_plate.AddModels(controller_params.plate_model); + Parser lcs_parser(&plant_for_lcs); + lcs_parser.SetAutoRenaming(true); + lcs_parser.AddModels(scene_params.end_effector_lcs_model); - drake::multibody::ModelInstanceIndex left_support_index; - drake::multibody::ModelInstanceIndex right_support_index; - if (controller_params.scene_index > 0) { - left_support_index = parser_plate.AddModels( - FindResourceOrThrow(controller_params.left_support_model))[0]; - right_support_index = parser_plate.AddModels( - FindResourceOrThrow(controller_params.right_support_model))[0]; - RigidTransform T_S1_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.left_support_orientation), - controller_params.left_support_position); - RigidTransform T_S2_W = - RigidTransform(drake::math::RollPitchYaw(controller_params.right_support_orientation), - controller_params.right_support_position); - plant_for_lcs.WeldFrames( - plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", left_support_index), T_S1_W); + std::vector environment_model_indices; + environment_model_indices.resize(scene_params.environment_models.size()); + for (int i = 0; i < scene_params.environment_models.size(); ++i) { + environment_model_indices[i] = lcs_parser.AddModels( + FindResourceOrThrow(scene_params.environment_models[i]))[0]; + RigidTransform T_E_W = + RigidTransform(drake::math::RollPitchYaw( + scene_params.environment_orientations[i]), + scene_params.environment_positions[i]); plant_for_lcs.WeldFrames( plant_for_lcs.world_frame(), - plant_for_lcs.GetFrameByName("support", right_support_index), T_S2_W); + plant_for_lcs.GetFrameByName("base", environment_model_indices[i]), + T_E_W); + } + for (int i = 0; i < scene_params.object_models.size(); ++i) { + lcs_parser.AddModels(scene_params.object_models[i]); } - parser_plate.AddModels(controller_params.tray_model); plant_for_lcs.WeldFrames(plant_for_lcs.world_frame(), plant_for_lcs.GetFrameByName("base_link"), X_WI); @@ -152,31 +154,30 @@ int DoMain(int argc, char* argv[]) { std::vector end_effector_contact_points = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("plate")); - if (controller_params.scene_index > 0) { - std::vector left_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", left_support_index)); - std::vector right_support_contact_points = - plant_for_lcs.GetCollisionGeometriesForBody( - plant_for_lcs.GetBodyByName("support", right_support_index)); - end_effector_contact_points.insert(end_effector_contact_points.end(), - left_support_contact_points.begin(), - left_support_contact_points.end()); - end_effector_contact_points.insert(end_effector_contact_points.end(), - right_support_contact_points.begin(), - right_support_contact_points.end()); + for (int i = 0; i < environment_model_indices.size(); ++i) { + std::vector + environment_support_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("base", + environment_model_indices[i])); + end_effector_contact_points.insert( + end_effector_contact_points.end(), + environment_support_contact_points.begin(), + environment_support_contact_points.end()); } std::vector tray_geoms = plant_for_lcs.GetCollisionGeometriesForBody( plant_for_lcs.GetBodyByName("tray")); - std::unordered_map> - contact_geoms; - contact_geoms["PLATE"] = end_effector_contact_points; - contact_geoms["TRAY"] = tray_geoms; + std::vector object_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("base")); std::vector> contact_pairs; - for (auto geom_id : contact_geoms["PLATE"]) { - contact_pairs.emplace_back(geom_id, contact_geoms["TRAY"][0]); + for (auto geom_id : end_effector_contact_points) { + contact_pairs.emplace_back(geom_id, tray_geoms[0]); + } + for (auto geom_id : object_geoms) { + contact_pairs.emplace_back(tray_geoms[0], geom_id); } DiagramBuilder builder; @@ -184,14 +185,19 @@ int DoMain(int argc, char* argv[]) { auto tray_state_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.tray_state_channel, &lcm)); + auto object_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.object_state_channel, &lcm)); auto franka_state_receiver = builder.AddSystem(plant_franka); auto tray_state_receiver = - builder.AddSystem(plant_tray); + builder.AddSystem(plant_tray, tray_index); + auto object_state_receiver = + builder.AddSystem(plant_tray, object_index); auto reduced_order_model_receiver = builder.AddSystem( plant_franka, franka_context.get(), plant_tray, tray_context.get(), - controller_params.end_effector_name, "tray", + scene_params.end_effector_name, "tray", controller_params.include_end_effector_orientation); auto actor_trajectory_sender = builder.AddSystem( LcmPublisherSystem::Make( @@ -224,13 +230,16 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.radio_channel, &lcm)); auto radio_to_vector = builder.AddSystem(); - auto plate_balancing_target = - builder.AddSystem(plant_tray, controller_params.end_effector_thickness, controller_params.near_target_threshold); + builder.AddSystem( + plant_tray, scene_params.end_effector_thickness, + controller_params.near_target_threshold); plate_balancing_target->SetRemoteControlParameters( - controller_params.first_target[controller_params.scene_index], controller_params.second_target[controller_params.scene_index], - controller_params.third_target[controller_params.scene_index], controller_params.x_scale, - controller_params.y_scale, controller_params.z_scale); + controller_params.first_target[controller_params.scene_index], + controller_params.second_target[controller_params.scene_index], + controller_params.third_target[controller_params.scene_index], + controller_params.x_scale, controller_params.y_scale, + controller_params.z_scale); std::vector input_sizes = {3, 7, 3, 6}; auto target_state_mux = builder.AddSystem(input_sizes); @@ -251,8 +260,8 @@ int DoMain(int argc, char* argv[]) { auto lcs_factory = builder.AddSystem( plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, *plate_context_ad, contact_pairs, c3_options); - auto controller = builder.AddSystem( - plant_for_lcs, c3_options); + auto controller = + builder.AddSystem(plant_for_lcs, c3_options); auto c3_trajectory_generator = builder.AddSystem(plant_for_lcs, c3_options); @@ -319,7 +328,7 @@ int DoMain(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); -// DrawAndSaveDiagramGraph(*plant_diagram); + // DrawAndSaveDiagramGraph(*plant_diagram); // Run lcm-driven simulation systems::LcmDrivenLoop loop( diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 2fba74329c..3f52360859 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -237,9 +237,9 @@ int do_main(int argc, char* argv[]) { end_effector_pose_drawer->get_input_port_trajectory()); } - if (sim_params.visualize_c3_state) { + if (sim_params.visualize_c3_object_state || sim_params.visualize_c3_end_effector_state) { auto c3_target_drawer = - builder.AddSystem(meshcat, true, false); + builder.AddSystem(meshcat, sim_params.visualize_c3_object_state, sim_params.visualize_c3_end_effector_state); builder.Connect(c3_state_actual_sub->get_output_port(), c3_target_drawer->get_input_port_c3_state_actual()); builder.Connect(c3_state_target_sub->get_output_port(), diff --git a/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml similarity index 94% rename from examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml index b16d2ed6f6..18b5b3bbc0 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml @@ -16,8 +16,8 @@ solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} publish_frequency: 0 # Workspace Limits (specified as Linear Constraints on the end effector position) -workspace_limits: [[0.866, 0.5, 0.0, 0.4, 0.6], - [-0.5, 0.866, 0.0, -0.2, 0.0], +workspace_limits: [[0.866, 0.5, 0.0, 0.3, 0.5], + [-0.5, 0.866, 0.0, -0.1932, -0.1532], [0.0, 0.0, 1.0, 0.35, 0.7]] workspace_margins: 0.05 @@ -37,7 +37,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 #Penalty on all decision variables, assuming scalar -w_G: 0.15 +w_G: 0.1 #Penalty on all decision variables, assuming scalar w_U: 0.1 diff --git a/examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml similarity index 100% rename from examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml rename to examples/franka/parameters/c3_options/franka_c3_options_supports.yaml diff --git a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml index b955e17899..a71a11b694 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml @@ -9,7 +9,7 @@ projection_type: 'QP' contact_model: 'anitescu' #contact_model: 'stewart_and_trinkle' warm_start: true -use_predicted_x0: false +use_predicted_x0: true end_on_qp_step: false solve_time_filter_alpha: 0.9 #publish_frequency : 0 diff --git a/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml b/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml new file mode 100644 index 0000000000..d1f7ca1c59 --- /dev/null +++ b/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml @@ -0,0 +1,64 @@ +admm_iter: 2 +rho: 0.0 +rho_scale: 4 +num_threads: 5 +delta_option: 1 +# options are 'MIQP' or 'QP' +projection_type: 'MIQP' +# options are 'stewart_and_trinkle' or 'anitescu' +contact_model: 'anitescu' +#contact_model: 'stewart_and_trinkle' +warm_start: true +use_predicted_x0: false +end_on_qp_step: false +solve_time_filter_alpha: 0.9 +#publish_frequency : 0 +publish_frequency: 25 + +# Workspace Limits +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], + [0.0, 1.0, 0.0, -0.2, 0.2], + [0.0, 0.0, 1.0, 0.3, 0.6]] +workspace_margins: 0.05 + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] + +mu: [0.6, 0.6, 0.6, 0.6, 0.6, 0.6] +dt: 0.05 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 6 +N: 5 +gamma: 1 + +# matrix scaling +w_Q: 50 +w_R: 1 +# Penalty on all decision variables, assuming scalar +w_G: 1 +# Penalty on all decision variables, assuming scalar +w_U: 0.5 + +# State Tracking Error, assuming diagonal +q_vector: [175, 175, 175, 10, 10, 10, 10, 5000, 5000, 5000, + 5, 5, 10, 1, 1, 1, 5, 5, 5] + +# Penalty on efforts, assuming diagonal +r_vector: [0.1, 0.1, 0.1] + +# Penalty on all decision variables +g_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [1, 1, 1] +g_lambda_n: [1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_u: [1, 1, 1] + +# Penalty on all decision variables +u_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 1, 1, 1, 10, 10, 10, 10, 10, 10] +u_gamma: [1, 1, 1] +u_lambda_n: [1, 1, 1] +u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_lambda: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] +u_u: [10, 10, 10] diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 6a399392a7..26ed75e516 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -45,7 +45,7 @@ w_U: 0.1 q_vector: [50, 50, 50, 0, 1, 1, 0, 75000, 75000, 75000, 5, 5, 5, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 0.01] +r_vector: [0.1, 0.1, 0.1] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/c3_scenes/two_object_scene.yaml b/examples/franka/parameters/c3_scenes/two_object_scene.yaml index 3007a9bfee..05a6da5bb7 100644 --- a/examples/franka/parameters/c3_scenes/two_object_scene.yaml +++ b/examples/franka/parameters/c3_scenes/two_object_scene.yaml @@ -4,11 +4,8 @@ end_effector_name: plate end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf tool_attachment_frame: [0, 0, 0.107] end_effector_thickness: 0.016 -object_models: [examples/franka/urdf/tray_lcs.sdf] -environment_models: [examples/franka/urdf/support_point_contact.urdf, - examples/franka/urdf/support_point_contact.urdf] +object_models: [examples/franka/urdf/tray_lcs.sdf, examples/franka/urdf/cylinder_lcs.sdf] +environment_models: [] # orientation in RPY then position in XYZ -environment_orientations: [[0.0, 0.0, 0.0], - [0.0, 0.0, 0.0]] -environment_positions: [[0.8, 0.15, 0.447], - [0.8, -0.15, 0.447]] \ No newline at end of file +environment_orientations: [] +environment_positions: [] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 7b6945b932..8de991f879 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,12 +1,14 @@ scene_index: 3 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, - examples/franka/parameters/c3_options/franka_c3_options_w_supports.yaml, - examples/franka/parameters/c3_options/franka_c3_options_side_supports.yaml, - examples/franka/parameters/c3_options/franka_c3_options_wall.yaml,] + examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, + examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, + examples/franka/parameters/c3_options/franka_c3_options_wall.yaml, + examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml] c3_scene_file: [examples/franka/parameters/c3_scenes/tray_scene.yaml, examples/franka/parameters/c3_scenes/supports_scene.yaml, examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml, - examples/franka/parameters/c3_scenes/wall_scene.yaml] + examples/franka/parameters/c3_scenes/wall_scene.yaml, + examples/franka/parameters/c3_scenes/tray_scene.yaml] osqp_settings_file: examples/franka/parameters/franka_c3_qp_settings.yaml include_end_effector_orientation: false @@ -14,18 +16,21 @@ include_end_effector_orientation: false target_frequency: 0 #unused near_target_threshold: 0.05 -first_target: [[0.45, 0.0, 0.5], +first_target: [[0.55, 0.0, 0.485], [0.45, 0, 0.485], [0.3897, 0.025, 0.49], - [0.55, 0.0, 0.485],] -second_target: [[0.45, 0.0, 0.5], + [0.55, 0.0, 0.485], + [0.45, 0.0, 0.5],] +second_target: [[0.55, 0.0, 0.485], [0.45, 0, 0.6], [0.3897, 0.025, 0.6], - [0.55, 0.0, 0.485],] + [0.55, 0.0, 0.485], + [0.45, 0.0, 0.5],] third_target: [[0.45, 0.0, 0.5], [0.7, 0.00, 0.485], [0.6062, 0.15, 0.49], - [0.55, 0.0, 0.485],] + [0.55, 0.0, 0.485], + [0.45, 0.0, 0.5],] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index e6277dd88e..89ea5b9eb2 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -24,7 +24,7 @@ end_effector_acceleration: 10 track_end_effector_orientation: false cancel_gravity_compensation: false enforce_acceleration_constraints: false -publish_debug_info: false +publish_debug_info: true W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index f00b966951..2bac60d208 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -33,7 +33,8 @@ struct FrankaSimParams { bool visualize_pose_trace; bool visualize_center_of_mass_plan; bool visualize_c3_forces; - bool visualize_c3_state; + bool visualize_c3_object_state; + bool visualize_c3_end_effector_state; bool visualize_workspace; template @@ -68,7 +69,8 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(visualize_pose_trace)); a->Visit(DRAKE_NVP(visualize_center_of_mass_plan)); a->Visit(DRAKE_NVP(visualize_c3_forces)); - a->Visit(DRAKE_NVP(visualize_c3_state)); + a->Visit(DRAKE_NVP(visualize_c3_object_state)); + a->Visit(DRAKE_NVP(visualize_c3_end_effector_state)); a->Visit(DRAKE_NVP(visualize_workspace)); } }; \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 5f1e9fbaef..e4aaeb3aca 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,9 +1,9 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf -tray_model: examples/franka/urdf/tray.sdf # rigid contact model does not do sticking well +tray_model: examples/franka/urdf/tray_lcs.sdf # rigid contact model does not do sticking well object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 -tray_publish_rate: 10 +tray_publish_rate: 1000 object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 @@ -40,15 +40,16 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], - [1, 0, 0, 0, 0.55, 0.06, 0.46]] + [1, 0, 0, 0, 0.55, -0.06, 0.46]] -q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], +q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], [1, 0, 0, 0, 0.7, 0.00, 0.0], [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ], [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ]] visualize_workspace: false -visualize_pose_trace: false -visualize_center_of_mass_plan: true +visualize_pose_trace: true +visualize_center_of_mass_plan: false visualize_c3_forces: true -visualize_c3_state: true +visualize_c3_object_state: true +visualize_c3_end_effector_state: false diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 1cadcdde40..768e1a9537 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -127,9 +127,6 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( if (end_effector_position[0] > 0.6) { end_effector_position[0] = 0.6; // keep it within the workspace } - if (end_effector_position[1] > 0.05) { - end_effector_position[1] = 0.05; // keep it within the workspace - } if (radio_out->value()[13] > 0) { end_effector_position(0) += radio_out->value()[0] * x_scale_; end_effector_position(1) += radio_out->value()[1] * y_scale_; diff --git a/examples/franka/urdf/cylinder_lcs.urdf b/examples/franka/urdf/cylinder_lcs.urdf new file mode 100644 index 0000000000..31a4718b6c --- /dev/null +++ b/examples/franka/urdf/cylinder_lcs.urdf @@ -0,0 +1,41 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/solvers/c3.cc b/solvers/c3.cc index 5091769605..2b97837955 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -130,9 +130,6 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, LinEq.block(0, n_, n_, m_) = D_.at(i); LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); - // prog_.AddLinearEqualityConstraint( - // LinEq, -d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + - // 1)}); dynamics_constraints_[i] = prog_ .AddLinearEqualityConstraint( @@ -140,7 +137,6 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}) .evaluator() .get(); - // prog_.AddLinearConstraint(lambda_.at(i) >= VectorXd::Zero(m_)); } input_costs_.resize(N_); for (int i = 0; i < N_ + 1; i++) { @@ -185,7 +181,7 @@ void C3::UpdateLCS(const LCS& lcs) { void C3::UpdateTarget(const std::vector& x_des) { x_desired_ = x_des; for (int i = 0; i < N_ + 1; i++) { - target_cost_[i]->UpdateCoefficients(Q_.at(i) * 2, + target_cost_[i]->UpdateCoefficients(2 * Q_.at(i), -2 * Q_.at(i) * x_desired_.at(i)); } } From 26dd238886b5196a13b42bc4aee74e02e24bd9b7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 3 Apr 2024 14:07:04 -0400 Subject: [PATCH 684/758] adding external force --- examples/Cassie/cassie_xbox_remote.py | 4 +- examples/franka/BUILD.bazel | 2 + examples/franka/franka_sim.cc | 48 +++++++++----- .../parameters/c3_scenes/wall_scene.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 3 + .../franka/parameters/franka_sim_params.yaml | 6 +- .../parameters/sim_scenes/wall_scene.yaml | 2 +- examples/franka/systems/BUILD.bazel | 14 +++++ .../systems/external_force_generator.cc | 62 +++++++++++++++++++ .../franka/systems/external_force_generator.h | 38 ++++++++++++ .../franka/systems/plate_balancing_target.cc | 8 ++- 11 files changed, 166 insertions(+), 23 deletions(-) create mode 100644 examples/franka/systems/external_force_generator.cc create mode 100644 examples/franka/systems/external_force_generator.h diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index 3a777519e3..f9285f2693 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -61,7 +61,7 @@ def main(): latching_switch_x = 0 latching_switch_y = 1 print("Teleop Status: " + str(latching_switch_a)) - print("End Effector Follow Status: " + str(latching_switch_b)) + print("Move Target with Remote: " + str(latching_switch_b)) print("Force Tracking Status: " + str(not latching_switch_x)) while not done: # DRAWING STEP @@ -79,7 +79,7 @@ def main(): print("Teleop Status: " + str(latching_switch_a)) if event.button == 1: latching_switch_b = not latching_switch_b - print("End Effector Follow Status: " + str(latching_switch_b)) + print("Move Target with Remote: " + str(latching_switch_b)) if event.button == 2: latching_switch_x = not latching_switch_x print("Force Tracking Status: " + str(not latching_switch_x)) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 6dcfc7e17b..aafa1758ef 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -37,10 +37,12 @@ cc_binary( deps = [ ":parameters", "//common", + "//examples/franka/systems:franka_systems", "//systems:robot_lcm_systems", "//systems:system_utils", "//systems/controllers", "//systems/framework:lcm_driven_loop", + "//systems/primitives:radio_parser", "@drake//:drake_shared_library", "@gflags", ], diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 1108ef738c..39a3d0eac1 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -2,12 +2,14 @@ #include +#include #include #include #include #include #include #include +#include #include #include #include @@ -22,7 +24,9 @@ #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "examples/franka/parameters/franka_sim_scene_params.h" +#include "examples/franka/systems/external_force_generator.h" #include "multibody/multibody_utils.h" +#include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" namespace dairlib { @@ -110,25 +114,24 @@ int DoMain(int argc, char* argv[]) { RigidTransform(drake::math::RollPitchYaw( scene_params.environment_orientations[i]), scene_params.environment_positions[i]); - plant.WeldFrames( - plant.world_frame(), - plant.GetFrameByName("base", environment_model_indices[i]), - T_E_W); - support_geom_set.Add(plant.GetCollisionGeometriesForBody(plant.GetBodyByName("base", - environment_model_indices[i]))); + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("base", environment_model_indices[i]), + T_E_W); + support_geom_set.Add(plant.GetCollisionGeometriesForBody( + plant.GetBodyByName("base", environment_model_indices[i]))); } plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( {"supports", support_geom_set}, {"franka", franka_geom_set}); const drake::geometry::GeometrySet& franka_only_geom_set = plant.CollectRegisteredGeometries({ - &plant.GetBodyByName("panda_link2"), - &plant.GetBodyByName("panda_link3"), - &plant.GetBodyByName("panda_link4"), - &plant.GetBodyByName("panda_link5"), - &plant.GetBodyByName("panda_link6"), - &plant.GetBodyByName("panda_link8"), - }); + &plant.GetBodyByName("panda_link2"), + &plant.GetBodyByName("panda_link3"), + &plant.GetBodyByName("panda_link4"), + &plant.GetBodyByName("panda_link5"), + &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link8"), + }); auto tray_collision_set = GeometrySet( plant.GetCollisionGeometriesForBody(plant.GetBodyByName("tray"))); plant.ExcludeCollisionGeometriesWithCollisionFilterGroupPair( @@ -166,6 +169,22 @@ int DoMain(int argc, char* argv[]) { builder.Connect(object_state_sender->get_output_port(), object_state_pub->get_input_port()); + auto external_force_generator = builder.AddSystem( + plant.GetBodyByName("tray").index()); + external_force_generator->SetRemoteControlParameters( + sim_params.external_force_scaling[0], + sim_params.external_force_scaling[1], + sim_params.external_force_scaling[2]); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &drake_lcm)); + auto radio_to_vector = builder.AddSystem(); + builder.Connect(*radio_sub, *radio_to_vector); + builder.Connect(radio_to_vector->get_output_port(), + external_force_generator->get_input_port_radio()); + builder.Connect(external_force_generator->get_output_port_spatial_force(), + plant.get_applied_spatial_force_input_port()); + int nq = plant.num_positions(); int nv = plant.num_velocities(); @@ -188,7 +207,8 @@ int DoMain(int argc, char* argv[]) { q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; - q.segment(plant.num_positions(franka_index), plant.num_positions(tray_index)) = + q.segment(plant.num_positions(franka_index), + plant.num_positions(tray_index)) = sim_params.q_init_plate[sim_params.scene_index]; q.tail(plant.num_positions(object_index)) = sim_params.q_init_object[sim_params.scene_index]; diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index 993502d4d4..b0eabbfed3 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -8,4 +8,4 @@ object_models: [examples/franka/urdf/tray_lcs.sdf] environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.35, 0.35]] \ No newline at end of file +environment_positions: [[0.6, 0.4, 0.35]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 2bac60d208..653ff7b5c5 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -30,6 +30,8 @@ struct FrankaSimParams { std::vector world_y_limits; std::vector world_z_limits; + std::vector external_force_scaling; + bool visualize_pose_trace; bool visualize_center_of_mass_plan; bool visualize_c3_forces; @@ -65,6 +67,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(world_x_limits)); a->Visit(DRAKE_NVP(world_y_limits)); a->Visit(DRAKE_NVP(world_z_limits)); + a->Visit(DRAKE_NVP(external_force_scaling)); a->Visit(DRAKE_NVP(visualize_pose_trace)); a->Visit(DRAKE_NVP(visualize_center_of_mass_plan)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index e4aaeb3aca..7900dbd33d 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -3,7 +3,7 @@ end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray_lcs.sdf # rigid contact model does not do sticking well object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 -tray_publish_rate: 1000 +tray_publish_rate: 100 object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 @@ -33,6 +33,8 @@ world_z_limits: [[0.35, 0.7], [0.35, 0.7], [0.45, 0.65]] +external_force_scaling: [10.0, 10.0, 10.0] + dt: 0.0005 realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] @@ -40,7 +42,7 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], - [1, 0, 0, 0, 0.55, -0.06, 0.46]] + [1, 0, 0, 0, 0.55, 0.0, 0.46]] q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], [1, 0, 0, 0, 0.7, 0.00, 0.0], diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index d8a332048e..8caa5d1db2 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -1,7 +1,7 @@ environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.35, 0.35]] +environment_positions: [[0.6, 0.4, 0.35]] camera_pose: [ 1.5, 0, 0.75 ] camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 1098f3ebee..6ffa7b38f8 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -9,11 +9,25 @@ cc_library( ":end_effector_force_trajectory", ":end_effector_orientation", ":end_effector_trajectory", + ":external_force_generator", ":franka_kinematics", ":plate_balancing_target", ], ) +cc_library( + name = "external_force_generator", + srcs = ["external_force_generator.cc"], + hdrs = ["external_force_generator.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + cc_library( name = "end_effector_trajectory", srcs = ["end_effector_trajectory.cc"], diff --git a/examples/franka/systems/external_force_generator.cc b/examples/franka/systems/external_force_generator.cc new file mode 100644 index 0000000000..f3168085e6 --- /dev/null +++ b/examples/franka/systems/external_force_generator.cc @@ -0,0 +1,62 @@ +#include "external_force_generator.h" + +using Eigen::Vector3d; +using Eigen::VectorXd; + +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::EventStatus; + +namespace dairlib { + +ExternalForceGenerator::ExternalForceGenerator( + drake::multibody::BodyIndex body_index) + : body_index_(body_index) { + // Input/Output Setup + radio_port_ = + this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) + .get_index(); + + spatial_force_port_ = + this->DeclareAbstractOutputPort( + "object_spatial_force", + std::vector< + drake::multibody::ExternallyAppliedSpatialForce>(), + &ExternalForceGenerator::CalcSpatialForce) + .get_index(); +} + +void ExternalForceGenerator::SetRemoteControlParameters(double x_scale, + double y_scale, + double z_scale) { + x_scale_ = x_scale; + y_scale_ = y_scale; + z_scale_ = z_scale; +} + +void ExternalForceGenerator::CalcSpatialForce( + const drake::systems::Context& context, + std::vector>* + spatial_forces) const { + const auto& radio_out = this->EvalVectorInput(context, radio_port_); + Vector3d force = VectorXd::Zero(3); + if (radio_out->value()[12]) { + force(0) = radio_out->value()[0] * x_scale_; + force(1) = radio_out->value()[1] * y_scale_; + force(2) = radio_out->value()[2] * z_scale_; + } + if (spatial_forces->empty()) { + auto spatial_force = + drake::multibody::ExternallyAppliedSpatialForce(); + spatial_force.body_index = body_index_; + spatial_force.F_Bq_W = + drake::multibody::SpatialForce(Vector3d::Zero(), force); + spatial_forces->push_back(spatial_force); + } else { + spatial_forces->at(0).F_Bq_W = + drake::multibody::SpatialForce(Vector3d::Zero(), force); + spatial_forces->at(0).body_index = body_index_; + } +} + +} // namespace dairlib diff --git a/examples/franka/systems/external_force_generator.h b/examples/franka/systems/external_force_generator.h new file mode 100644 index 0000000000..a94f023f4b --- /dev/null +++ b/examples/franka/systems/external_force_generator.h @@ -0,0 +1,38 @@ +#pragma once + +#include +#include + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class ExternalForceGenerator : public drake::systems::LeafSystem { + public: + ExternalForceGenerator(drake::multibody::BodyIndex body_index); + + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + const drake::systems::OutputPort& get_output_port_spatial_force() + const { + return this->get_output_port(spatial_force_port_); + } + + void SetRemoteControlParameters(double x_scale, double y_scale, + double z_scale); + + private: + void CalcSpatialForce(const drake::systems::Context& context, + std::vector>* spatial_forces) const; + + drake::systems::InputPortIndex radio_port_; + drake::systems::OutputPortIndex spatial_force_port_; + drake::multibody::BodyIndex body_index_; + double x_scale_ = 0; + double y_scale_ = 0; + double z_scale_ = 0; +}; + +} // namespace dairlib diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 768e1a9537..9e65e31556 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -154,9 +154,11 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( context.get_discrete_state(sequence_index_)[0] == 3) { tray_position = third_target_; } - tray_position(0) += radio_out->value()[0] * x_scale_; - tray_position(1) += radio_out->value()[1] * y_scale_; - tray_position(2) += radio_out->value()[2] * z_scale_; + if (radio_out->value()[13] > 0) { + tray_position(0) += radio_out->value()[0] * x_scale_; + tray_position(1) += radio_out->value()[1] * y_scale_; + tray_position(2) += radio_out->value()[2] * z_scale_; + } // tray_position(0) = 0.55; // tray_position(1) = 0.1 * sin(4 * context.get_time()); // tray_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()); From 6f7530eccfe437e78b74e06ce5e1483dd2de8eba Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 3 Apr 2024 15:13:09 -0400 Subject: [PATCH 685/758] fixing conflict on channel 11 --- examples/Cassie/cassie_xbox_remote.py | 15 +++++++++++---- .../parameters/franka_c3_controller_params.yaml | 4 ++-- examples/franka/parameters/franka_sim_params.yaml | 2 +- .../franka/systems/end_effector_trajectory.cc | 8 +++++--- 4 files changed, 19 insertions(+), 10 deletions(-) diff --git a/examples/Cassie/cassie_xbox_remote.py b/examples/Cassie/cassie_xbox_remote.py index f9285f2693..21e3ac3a0f 100644 --- a/examples/Cassie/cassie_xbox_remote.py +++ b/examples/Cassie/cassie_xbox_remote.py @@ -59,10 +59,13 @@ def main(): latching_switch_a = 1 latching_switch_b = 1 latching_switch_x = 0 - latching_switch_y = 1 + latching_switch_y = 0 + latching_switch_rt = 1 # right trigger print("Teleop Status: " + str(latching_switch_a)) - print("Move Target with Remote: " + str(latching_switch_b)) + print("Move C3 Target with Remote Status: " + str(latching_switch_b)) print("Force Tracking Status: " + str(not latching_switch_x)) + print("Spatial Force on Object Status: " + str(not latching_switch_y)) + print("Set OSC Target with Remote Status: " + str(not latching_switch_rt)) while not done: # DRAWING STEP # First, clear the screen to blue. Don't put other drawing commands @@ -79,13 +82,16 @@ def main(): print("Teleop Status: " + str(latching_switch_a)) if event.button == 1: latching_switch_b = not latching_switch_b - print("Move Target with Remote: " + str(latching_switch_b)) + print("Move C3 Target with Remote Status: " + str(latching_switch_b)) if event.button == 2: latching_switch_x = not latching_switch_x print("Force Tracking Status: " + str(not latching_switch_x)) if event.button == 3: latching_switch_y = not latching_switch_y - print("Ready to Reset Status: " + str(latching_switch_y)) + print("Spatial Force on Object Status: " + str(latching_switch_y)) + if event.button == 5: + latching_switch_rt = not latching_switch_rt + print("Set OSC Target with Remote Status: " + str(latching_switch_rt)) # Send LCM message @@ -102,6 +108,7 @@ def main(): radio_msg.channel[14] = latching_switch_a radio_msg.channel[11] = latching_switch_x radio_msg.channel[12] = latching_switch_y + radio_msg.channel[10] = latching_switch_rt radio_msg.channel[15] = -1 * np.rint(joystick.get_axis(5)) diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 8de991f879..720762fd30 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,4 +1,4 @@ -scene_index: 3 +scene_index: 0 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, @@ -26,7 +26,7 @@ second_target: [[0.55, 0.0, 0.485], [0.3897, 0.025, 0.6], [0.55, 0.0, 0.485], [0.45, 0.0, 0.5],] -third_target: [[0.45, 0.0, 0.5], +third_target: [[0.55, 0.0, 0.485], [0.7, 0.00, 0.485], [0.6062, 0.15, 0.49], [0.55, 0.0, 0.485], diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 7900dbd33d..9613e1a5be 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -3,7 +3,7 @@ end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray_lcs.sdf # rigid contact model does not do sticking well object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 -tray_publish_rate: 100 +tray_publish_rate: 1000 object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_trajectory.cc index d5b484304b..a7b491667b 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_trajectory.cc @@ -59,9 +59,11 @@ void EndEffectorTrajectoryGenerator::CalcTraj( if (radio_out->value()[14]) { PiecewisePolynomial result; VectorXd y_0 = neutral_pose_; - y_0(0) += radio_out->value()[0] * x_scale_; - y_0(1) += radio_out->value()[1] * y_scale_; - y_0(2) += radio_out->value()[2] * z_scale_; + if (radio_out->value()[10]){ + y_0(0) += radio_out->value()[0] * x_scale_; + y_0(1) += radio_out->value()[1] * y_scale_; + y_0(2) += radio_out->value()[2] * z_scale_; + } result = drake::trajectories::PiecewisePolynomial(y_0); *casted_traj = result; } else { From 8048e5401f498d6c6b27cc1d123b5d4dfa91e471 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 3 Apr 2024 16:58:19 -0400 Subject: [PATCH 686/758] working on rotating with wall --- .../c3_options/franka_c3_options_wall.yaml | 32 +++++++++---------- .../parameters/c3_scenes/wall_scene.yaml | 2 +- .../franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 7 ++-- .../parameters/sim_scenes/wall_scene.yaml | 2 +- examples/franka/urdf/side_wall.urdf | 2 +- 6 files changed, 24 insertions(+), 23 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 26ed75e516..ed7d66d9a9 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -1,7 +1,7 @@ -admm_iter: 2 +admm_iter: 3 rho: 0 # does not do anything -rho_scale: 4 -num_threads: 6 +rho_scale: 7 +num_threads: 5 delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' @@ -18,41 +18,41 @@ publish_frequency : 0 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.7], - [0.0, 1.0, 0.0, -0.15, 0.15], + [0.0, 1.0, 0.0, -0.2, 0.2], [0.0, 0.0, 1.0, 0.35, 0.6]] workspace_margins: 0.05 u_horizontal_limits: [-20, 20] u_vertical_limits: [-20, 30] -mu: [0.6, 0.6, 0.6, 0.1] -dt: 0.06 +mu: [1.0, 1.0, 1.0, 1.0] +dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 4 -N: 6 -gamma: 1.0 # discount factor on MPC costs +N: 5 +gamma: 0.75 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 20 +w_R: 25 #Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.5 #Penalty on all decision variables, assuming scalar -w_U: 0.1 +w_U: 0.5 #State Tracking Error, assuming diagonal -q_vector: [50, 50, 50, 0, 1, 1, 0, 75000, 75000, 75000, - 5, 5, 5, 10, 10, 1, 5, 5, 5] +q_vector: [25, 25, 500, 1000, 1000, 5000, 5000, 1000, 1000, 5000, + 1, 1, 1, 1, 1, 1, 1, 1, 1] #Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 0.1] +r_vector: [0.15, 0.15, 0.5] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 2000, 2000, 2000, 2000] +g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] #Penalty on matching the QP variables @@ -60,5 +60,5 @@ u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 2000, 2000, 2000, 2000] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index b0eabbfed3..c179f13ac6 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -8,4 +8,4 @@ object_models: [examples/franka/urdf/tray_lcs.sdf] environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.4, 0.35]] \ No newline at end of file +environment_positions: [[0.6, 0.3, 0.35]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 720762fd30..e6eb866c6c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,4 +1,4 @@ -scene_index: 0 +scene_index: 3 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 9613e1a5be..caea08bed2 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -42,7 +42,8 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], - [1, 0, 0, 0, 0.55, 0.0, 0.46]] + [0.7068252, 0, 0, 0.7073883, 0.55, 0.01, 0.46]] +# [1, 0, 0, 0, 0.55, 0.0, 0.46]] q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], [1, 0, 0, 0, 0.7, 0.00, 0.0], @@ -50,8 +51,8 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ]] visualize_workspace: false -visualize_pose_trace: true +visualize_pose_trace: false visualize_center_of_mass_plan: false visualize_c3_forces: true visualize_c3_object_state: true -visualize_c3_end_effector_state: false +visualize_c3_end_effector_state: true diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index 8caa5d1db2..64c28608aa 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -1,7 +1,7 @@ environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.4, 0.35]] +environment_positions: [[0.6, 0.3, 0.35]] camera_pose: [ 1.5, 0, 0.75 ] camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/urdf/side_wall.urdf b/examples/franka/urdf/side_wall.urdf index 157f56699c..4cb74faec7 100644 --- a/examples/franka/urdf/side_wall.urdf +++ b/examples/franka/urdf/side_wall.urdf @@ -20,7 +20,7 @@ - + From 5f37ad697b8d81a467f067c0e702a9826c3d0b07 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 4 Apr 2024 14:08:21 -0400 Subject: [PATCH 687/758] still working on rotating with wall --- examples/franka/franka_c3_controller.cc | 5 +--- .../c3_options/franka_c3_options_wall.yaml | 30 +++++++++---------- .../franka/parameters/franka_sim_params.yaml | 6 ++-- .../parameters/sim_scenes/wall_scene.yaml | 7 +++-- .../franka/systems/plate_balancing_target.cc | 27 +++++++++++++++++ .../franka/systems/plate_balancing_target.h | 8 +++++ 6 files changed, 58 insertions(+), 25 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index fbf3f4e8be..82f3ddb7ec 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -237,16 +237,13 @@ int DoMain(int argc, char* argv[]) { auto end_effector_zero_velocity_source = builder.AddSystem( VectorXd::Zero(3)); - auto tray_zero_velocity_source = - builder.AddSystem( - VectorXd::Zero(6)); builder.Connect(plate_balancing_target->get_output_port_end_effector_target(), target_state_mux->get_input_port(0)); builder.Connect(plate_balancing_target->get_output_port_tray_target(), target_state_mux->get_input_port(1)); builder.Connect(end_effector_zero_velocity_source->get_output_port(), target_state_mux->get_input_port(2)); - builder.Connect(tray_zero_velocity_source->get_output_port(), + builder.Connect(plate_balancing_target->get_output_port_tray_velocity_target(), target_state_mux->get_input_port(3)); auto lcs_factory = builder.AddSystem( plant_for_lcs, plant_for_lcs_context, *plant_for_lcs_autodiff, diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index ed7d66d9a9..8040c84e62 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -1,7 +1,7 @@ admm_iter: 3 rho: 0 # does not do anything -rho_scale: 7 -num_threads: 5 +rho_scale: 5 +num_threads: 4 delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' @@ -22,43 +22,43 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.7], [0.0, 0.0, 1.0, 0.35, 0.6]] workspace_margins: 0.05 -u_horizontal_limits: [-20, 20] -u_vertical_limits: [-20, 30] +u_horizontal_limits: [-10, 10] +u_vertical_limits: [-0, 30] -mu: [1.0, 1.0, 1.0, 1.0] -dt: 0.075 +mu: [0.8, 0.8, 0.8, 1.0] +dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 4 -N: 5 -gamma: 0.75 # discount factor on MPC costs +N: 4 +gamma: 1.0 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 25 +w_R: 75 #Penalty on all decision variables, assuming scalar w_G: 0.5 #Penalty on all decision variables, assuming scalar w_U: 0.5 #State Tracking Error, assuming diagonal -q_vector: [25, 25, 500, 1000, 1000, 5000, 5000, 1000, 1000, 5000, - 1, 1, 1, 1, 1, 1, 1, 1, 1] +q_vector: [5, 10, 150, 1000, 1000, 1000, 1000, 5, 10, 15000, + 5, 5, 5, 1, 1, 500, 5, 5, 5] #Penalty on efforts, assuming diagonal -r_vector: [0.15, 0.15, 0.5] +r_vector: [1.9, 0.5, 0.05] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -g_u: [1, 1, 1] +g_lambda: [150, 150, 150, 150, 150, 150, 150, 150, 150, 150, 150, 150, 150, 150, 150, 150] +g_u: [2.5, 2.5, 2.5] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 2000, 2000, 2000, 2000] +u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index caea08bed2..832249b332 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -42,7 +42,7 @@ q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], - [0.7068252, 0, 0, 0.7073883, 0.55, 0.01, 0.46]] + [0.8775826, 0, 0, 0.4794255, 0.55, 0.02, 0.46]] # [1, 0, 0, 0, 0.55, 0.0, 0.46]] q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], @@ -51,8 +51,8 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ]] visualize_workspace: false -visualize_pose_trace: false -visualize_center_of_mass_plan: false +visualize_pose_trace: true +visualize_center_of_mass_plan: true visualize_c3_forces: true visualize_c3_object_state: true visualize_c3_end_effector_state: true diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index 64c28608aa..1f21a113bc 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -1,7 +1,8 @@ +camera_pose: [ 1.5, 0, 0.75 ] +camera_target: [ 0.5, 0, 0.5 ] + environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.3, 0.35]] +environment_positions: [[0.6, 0.285, 0.35]] -camera_pose: [ 1.5, 0, 0.75 ] -camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index 9e65e31556..fd74c19e4e 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -1,6 +1,7 @@ #include "plate_balancing_target.h" #include +#include #include "dairlib/lcmt_radio_out.hpp" @@ -36,6 +37,10 @@ PlateBalancingTargetGenerator::PlateBalancingTargetGenerator( "tray_target", BasicVector(7), &PlateBalancingTargetGenerator::CalcTrayTarget) .get_index(); + tray_velocity_target_port_ = this->DeclareVectorOutputPort( + "tray_velocity_target", BasicVector(6), + &PlateBalancingTargetGenerator::CalcTrayVelocityTarget) + .get_index(); sequence_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); within_target_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); time_entered_target_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); @@ -168,5 +173,27 @@ void PlateBalancingTargetGenerator::CalcTrayTarget( target->SetFromVector(target_tray_state); } +void PlateBalancingTargetGenerator::CalcTrayVelocityTarget( + const drake::systems::Context& context, + BasicVector* target) const { + const StateVector* tray_state = + (StateVector*)this->EvalVectorInput(context, tray_state_port_); + Eigen::Quaterniond y_quat_des(1, 0, 0, 0); + const VectorX &q = tray_state->GetPositions(); + Eigen::Quaterniond y_quat(q(0), q(1), q(2), q(3)); + Eigen::AngleAxis angle_axis_diff(y_quat_des * y_quat.inverse()); + VectorXd angle_error = angle_axis_diff.angle() * angle_axis_diff.axis(); + + VectorXd target_tray_state = VectorXd::Zero(6); + + // tray_position(0) = 0.55; + // tray_position(1) = 0.1 * sin(4 * context.get_time()); + // tray_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()); + // tray_position(1) = 0.1 * (int) (2 * sin(0.5 * context.get_time())); + // tray_position(2) = 0.45; + target_tray_state << angle_error, VectorXd::Zero(3); // tray orientation is flat + target->SetFromVector(target_tray_state); +} + } // namespace systems } // namespace dairlib \ No newline at end of file diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 6906c587bd..0acec769ca 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -34,6 +34,11 @@ class PlateBalancingTargetGenerator return this->get_output_port(tray_target_port_); } + const drake::systems::OutputPort& get_output_port_tray_velocity_target() + const { + return this->get_output_port(tray_velocity_target_port_); + } + void SetRemoteControlParameters(const Eigen::Vector3d& first_target, const Eigen::Vector3d& second_target, const Eigen::Vector3d& third_target, @@ -45,6 +50,8 @@ class PlateBalancingTargetGenerator drake::systems::BasicVector* target) const; void CalcTrayTarget(const drake::systems::Context& context, drake::systems::BasicVector* target) const; + void CalcTrayVelocityTarget(const drake::systems::Context& context, + drake::systems::BasicVector* target) const; drake::systems::EventStatus DiscreteVariableUpdate( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const; @@ -53,6 +60,7 @@ class PlateBalancingTargetGenerator drake::systems::InputPortIndex tray_state_port_; drake::systems::OutputPortIndex end_effector_target_port_; drake::systems::OutputPortIndex tray_target_port_; + drake::systems::OutputPortIndex tray_velocity_target_port_; drake::systems::DiscreteStateIndex sequence_index_; drake::systems::DiscreteStateIndex within_target_index_; From 70453a27416b273b81908661792a9d2ae806620d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 4 Apr 2024 17:02:06 -0400 Subject: [PATCH 688/758] working wall task --- .../parameters/c3_options/franka_c3_options_wall.yaml | 6 +++--- examples/franka/parameters/franka_sim_params.yaml | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 8040c84e62..356ae6981a 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -17,9 +17,9 @@ publish_frequency : 0 #publish_frequency: 25 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] -workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.7], +workspace_limits: [[1.0, 0.0, 0.0, 0.45, 0.7], [0.0, 1.0, 0.0, -0.2, 0.2], - [0.0, 0.0, 1.0, 0.35, 0.6]] + [0.0, 0.0, 1.0, 0.4, 0.5]] workspace_margins: 0.05 u_horizontal_limits: [-10, 10] @@ -42,7 +42,7 @@ w_G: 0.5 w_U: 0.5 #State Tracking Error, assuming diagonal -q_vector: [5, 10, 150, 1000, 1000, 1000, 1000, 5, 10, 15000, +q_vector: [10, 25, 150, 1000, 1000, 1000, 1000, 25, 25, 15000, 5, 5, 5, 1, 1, 500, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [1.9, 0.5, 0.05] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 832249b332..6cefc79973 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -48,7 +48,7 @@ q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], [1, 0, 0, 0, 0.7, 0.00, 0.0], [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ], - [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ]] + [1. , 0. , 0. , 0. , -1.55, 0.0, 0.0 ]] visualize_workspace: false visualize_pose_trace: true From 715f5dbf0139eabd938872c978ef2c955fb9e9ed Mon Sep 17 00:00:00 2001 From: Will Yang Date: Sun, 7 Apr 2024 14:29:21 -0400 Subject: [PATCH 689/758] commiting gains that kind of work on april7 --- .../pydairlib/analysis/log_plotter_franka.py | 16 +++++++++------- .../pydairlib/analysis/mbp_plotting_utils.py | 1 - .../franka_hardware_plot_config.yaml | 6 +++--- bindings/pydairlib/lcm/process_lcm_log.py | 4 ++-- .../c3_options/franka_c3_options_wall.yaml | 2 +- .../franka/parameters/c3_scenes/wall_scene.yaml | 2 +- .../parameters/franka_osc_controller_params.yaml | 2 +- .../franka/parameters/lcm_channels_hardware.yaml | 2 +- 8 files changed, 18 insertions(+), 17 deletions(-) diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 1f149d5c16..8d16268804 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -56,14 +56,14 @@ def main(): plot_config.start_time, plot_config.duration, mbp_plots.load_default_channels, # processing callback - franka_plant, True, channel_x, channel_u, + True, franka_plant, channel_x, channel_u, channel_osc) # processing callback arguments # processing callback arguments if plot_config.plot_c3_debug: c3_output, c3_tracking_target, c3_tracking_actual = get_log_data(log, default_channels, plot_config.start_time, - plot_config.duration, mbp_plots.load_c3_debug, - channel_c3, channel_c3_target, channel_c3_actual) + plot_config.duration, mbp_plots.load_c3_debug, True, + channel_c3, channel_c3_target, channel_c3_actual) solve_times = np.diff(c3_output['t'], prepend=[c3_output['t'][0]]) print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_output['t']))) @@ -186,10 +186,12 @@ def main(): support_sliding_contacts = [slice(12, 19), slice(26, 36), slice(39, 68), slice(218, 260)] support_no_contacts = [slice(67, 219)] - plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 7:8], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) - plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) - plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) - plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + # plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 7:8], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + # plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:1], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + # plotter.plot(c3_tracking_actual['t'] - 0.15, c3_tracking_actual['x'][:, 9:10], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + # plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 2:3], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 0:3], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) + plotter.plot(c3_tracking_actual['t'], c3_tracking_actual['x'][:, 7:10], subplot_index = 0, xlabel='Time (s)', ylabel='Position (m)', grid=False) ax = plotter.fig.axes[0] ymin, ymax = ax.get_ylim() halfway = ymin + 0.5 * (ymax - ymin) diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index ccc01ba899..2efc871712 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -62,7 +62,6 @@ def process_state_channel(state_data, plant): q = [] u = [] v = [] - pos_map = MakeNameToPositionsMap(plant) vel_map = MakeNameToVelocitiesMap(plant) act_map = MakeNameToActuatorsMap(plant) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml index 5e94a9f970..7c68e348a0 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -6,11 +6,11 @@ channel_c3: "C3_DEBUG" channel_tray: "TRAY_STATE" channel_c3_target: "C3_TARGET" channel_c3_actual: "C3_ACTUAL" -plot_style: 'paper' # compact, paper, default +plot_style: 'compact' # compact, paper, default -start_time: 7.4 +start_time: 0 #duration: 0.47 -duration: 1.5 +duration: -1 # Plant properties # Desired RobotOutput plots diff --git a/bindings/pydairlib/lcm/process_lcm_log.py b/bindings/pydairlib/lcm/process_lcm_log.py index 844bc3eddf..0e913b29a0 100644 --- a/bindings/pydairlib/lcm/process_lcm_log.py +++ b/bindings/pydairlib/lcm/process_lcm_log.py @@ -1,6 +1,6 @@ import lcm -def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_callback, print, *args, +def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_callback, print_info, *args, **kwargs): """ Parses an LCM log and returns data as specified by a callback function @@ -36,7 +36,7 @@ def get_log_data(lcm_log, lcm_channels, start_time, duration, data_processing_ca else: data_to_process[event.channel] = \ [lcm_channels[event.channel].decode(event.data)] - if print and event.eventnum % 50000 == 0: + if print_info and event.eventnum % 50000 == 0: print(f'processed {(event.timestamp - t) * 1e-6:.1f}' f' seconds of log data') if 0 < duration <= (event.timestamp - t) * 1e-6: diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 356ae6981a..55779e2f50 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -45,7 +45,7 @@ w_U: 0.5 q_vector: [10, 25, 150, 1000, 1000, 1000, 1000, 25, 25, 15000, 5, 5, 5, 1, 1, 500, 5, 5, 5] #Penalty on efforts, assuming diagonal -r_vector: [1.9, 0.5, 0.05] +r_vector: [2.0, 0.75, 0.05] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index c179f13ac6..207555065d 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -8,4 +8,4 @@ object_models: [examples/franka/urdf/tray_lcs.sdf] environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.3, 0.35]] \ No newline at end of file +environment_positions: [[0.6, 0.285, 0.35]] \ No newline at end of file diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 89ea5b9eb2..cba0b5f92d 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -22,7 +22,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false publish_debug_info: true diff --git a/examples/franka/parameters/lcm_channels_hardware.yaml b/examples/franka/parameters/lcm_channels_hardware.yaml index fbe4c699bc..a1c12f8099 100644 --- a/examples/franka/parameters/lcm_channels_hardware.yaml +++ b/examples/franka/parameters/lcm_channels_hardware.yaml @@ -1,6 +1,6 @@ franka_state_channel: FRANKA_STATE tray_state_channel: TRAY_STATE -box_state_channel: BOX_STATE +object_state_channel: BOX_STATE franka_input_channel: FRANKA_INPUT franka_input_echo: FRANKA_INPUT_ECHO From 20204791b7a89d3f958de3f86e583b635c43001c Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 9 Apr 2024 15:09:34 -0400 Subject: [PATCH 690/758] minor gain changes for perturbation rejection --- .../parameters/c3_options/franka_c3_options_supports.yaml | 2 +- examples/franka/systems/plate_balancing_target.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index e1b5b760ea..b4b2fcceb2 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -44,7 +44,7 @@ w_G: 0.15 w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 3000000, 15000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 0acec769ca..892983d486 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -69,7 +69,7 @@ class PlateBalancingTargetGenerator Eigen::Vector3d first_target_; Eigen::Vector3d second_target_; Eigen::Vector3d third_target_; - const double delay_at_top_ = 3.0; + const double delay_at_top_ = 10.0; double target_threshold_; double x_scale_; double y_scale_; From 3d0e7ab5bbdb50d7c36690d9b3ae9c9526043931 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 10 Apr 2024 13:07:39 -0400 Subject: [PATCH 691/758] final working gains --- .../franka/parameters/c3_options/franka_c3_options_wall.yaml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 55779e2f50..3e45937f6c 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -17,7 +17,7 @@ publish_frequency : 0 #publish_frequency: 25 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] -workspace_limits: [[1.0, 0.0, 0.0, 0.45, 0.7], +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.7], [0.0, 1.0, 0.0, -0.2, 0.2], [0.0, 0.0, 1.0, 0.4, 0.5]] workspace_margins: 0.05 @@ -43,7 +43,7 @@ w_U: 0.5 #State Tracking Error, assuming diagonal q_vector: [10, 25, 150, 1000, 1000, 1000, 1000, 25, 25, 15000, - 5, 5, 5, 1, 1, 500, 5, 5, 5] + 2.5, 5, 5, 1, 1, 500, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [2.0, 0.75, 0.05] From 9b843c632144b6973ca77c33f39d7300c9128741 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 11 Apr 2024 15:58:28 -0400 Subject: [PATCH 692/758] visualization changes --- examples/franka/parameters/sim_scenes/wall_scene.yaml | 4 +++- examples/franka/systems/plate_balancing_target.h | 3 ++- systems/visualization/lcm_visualization_systems.cc | 2 +- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/examples/franka/parameters/sim_scenes/wall_scene.yaml b/examples/franka/parameters/sim_scenes/wall_scene.yaml index 1f21a113bc..336dae7191 100644 --- a/examples/franka/parameters/sim_scenes/wall_scene.yaml +++ b/examples/franka/parameters/sim_scenes/wall_scene.yaml @@ -1,8 +1,10 @@ camera_pose: [ 1.5, 0, 0.75 ] camera_target: [ 0.5, 0, 0.5 ] +#camera_pose: [ 0.55, 0, 1.2 ] +#camera_target: [ 0.55, 0, 0.5 ] environment_models: [examples/franka/urdf/side_wall.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0.0, 0.0, 0.0]] -environment_positions: [[0.6, 0.285, 0.35]] +environment_positions: [[0.6, 0.3, 0.35]] diff --git a/examples/franka/systems/plate_balancing_target.h b/examples/franka/systems/plate_balancing_target.h index 892983d486..be73d052b1 100644 --- a/examples/franka/systems/plate_balancing_target.h +++ b/examples/franka/systems/plate_balancing_target.h @@ -69,7 +69,8 @@ class PlateBalancingTargetGenerator Eigen::Vector3d first_target_; Eigen::Vector3d second_target_; Eigen::Vector3d third_target_; - const double delay_at_top_ = 10.0; +// const double delay_at_top_ = 10.0; + const double delay_at_top_ = 3.0; double target_threshold_; double x_scale_; double y_scale_; diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index 2cc7cb520b..14e43a1293 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -301,7 +301,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( auto force_norm = force.norm(); const std::string& force_path_root = force_path_ + "/lcs_force_" + std::to_string(i) + "/"; - if (force_norm >= 0.1) { + if (force_norm >= 0.5) { if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, contact_force_color_); From 45287a14076c480857c82da7d265ee769507c591 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 10:15:23 -0400 Subject: [PATCH 693/758] last changes from rebuttal --- .../plot_configs/franka_hardware_plot_config.yaml | 4 ++-- .../franka_c3_options_rotated_supports.yaml | 8 ++++---- .../c3_options/franka_c3_options_translation.yaml | 6 +++--- .../parameters/franka_c3_controller_params.yaml | 2 +- .../parameters/franka_osc_controller_params.yaml | 6 +++--- examples/franka/parameters/franka_sim_params.yaml | 14 +++++++------- .../sim_scenes/supports_rotated_scene.yaml | 12 +++++++++--- .../parameters/sim_scenes/supports_scene.yaml | 2 +- examples/franka/urdf/cylinder_object.urdf | 4 ++-- examples/franka/urdf/tray.sdf | 2 +- 10 files changed, 33 insertions(+), 27 deletions(-) diff --git a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml index 7c68e348a0..e2958a34cd 100644 --- a/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml +++ b/bindings/pydairlib/analysis/plot_configs/franka_hardware_plot_config.yaml @@ -29,8 +29,8 @@ special_efforts_to_plot: [] fsm_state_names: [ 'Left Stance (LS)', 'Right Stance (RS)', 'Left Flight (LF)', 'Right Flight (RF)' ] # Desired osc plots -plot_qp_costs: false -plot_qp_solve_time: false +plot_qp_costs: true +plot_qp_solve_time: true plot_qp_solutions: false plot_tracking_costs: false plot_active_tracking_datas: false diff --git a/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml index 18b5b3bbc0..f4a537a0e3 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml @@ -1,6 +1,6 @@ admm_iter: 2 rho: 0 # does not do anything -rho_scale: 4 +rho_scale: 3.9 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -16,8 +16,8 @@ solve_time_filter_alpha: 0.95 # \bar{dt} = (1 - alpha) dt + (alpha) * \bar{dt} publish_frequency: 0 # Workspace Limits (specified as Linear Constraints on the end effector position) -workspace_limits: [[0.866, 0.5, 0.0, 0.3, 0.5], - [-0.5, 0.866, 0.0, -0.1932, -0.1532], +workspace_limits: [[0.866, 0.5, 0.0, 0.3, 0.49], + [-0.5, 0.866, 0.0, -0.1782, -0.1682], [0.0, 0.0, 1.0, 0.35, 0.7]] workspace_margins: 0.05 @@ -37,7 +37,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 #Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.15 #Penalty on all decision variables, assuming scalar w_U: 0.1 diff --git a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml index a71a11b694..3246562d33 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml @@ -4,10 +4,10 @@ rho_scale: 2 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' -projection_type: 'QP' +projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' -contact_model: 'anitescu' -#contact_model: 'stewart_and_trinkle' +#contact_model: 'anitescu' +contact_model: 'stewart_and_trinkle' warm_start: true use_predicted_x0: true end_on_qp_step: false diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index e6eb866c6c..40a59b106a 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,4 +1,4 @@ -scene_index: 3 +scene_index: 1 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index cba0b5f92d..0ee6adfb3a 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -6,8 +6,8 @@ end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -#neutral_position: [0.4763, 0.075 , 0.45] -neutral_position: [0.55, 0, 0.45] +neutral_position: [0.4763, 0.075 , 0.47] +#neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 @@ -22,7 +22,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: true +cancel_gravity_compensation: false enforce_acceleration_constraints: false publish_debug_info: true diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 6cefc79973..61d8db0553 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,6 +1,6 @@ franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf -tray_model: examples/franka/urdf/tray_lcs.sdf # rigid contact model does not do sticking well +tray_model: examples/franka/urdf/tray.sdf # rigid contact model does not do sticking well object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 @@ -8,7 +8,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 30 actuator_delay: 0.000 -scene_index: 3 +scene_index: 1 visualize_drake_sim: false publish_efforts: true @@ -36,23 +36,23 @@ world_z_limits: [[0.35, 0.7], external_force_scaling: [10.0, 10.0, 10.0] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.9 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], - [1. , 0. , 0. , 0. , 0.6062, 0.15 , 0.485 ], + [1. , 0. , 0. , 0. , 0.5889, 0.14 , 0.485], [0.8775826, 0, 0, 0.4794255, 0.55, 0.02, 0.46]] # [1, 0, 0, 0, 0.55, 0.0, 0.46]] -q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.48], +q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1, 0, 0, 0, 0.7, 0.00, 0.0], [1. , 0. , 0. , 0. , -0.55, 0.0, 0.0 ], [1. , 0. , 0. , 0. , -1.55, 0.0, 0.0 ]] visualize_workspace: false visualize_pose_trace: true -visualize_center_of_mass_plan: true +visualize_center_of_mass_plan: false visualize_c3_forces: true visualize_c3_object_state: true -visualize_c3_end_effector_state: true +visualize_c3_end_effector_state: false diff --git a/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml b/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml index 412a5ae72a..6f16b5b21b 100644 --- a/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml +++ b/examples/franka/parameters/sim_scenes/supports_rotated_scene.yaml @@ -1,10 +1,16 @@ environment_models: [examples/franka/urdf/support.urdf, - examples/franka/urdf/support.urdf] + examples/franka/urdf/support.urdf, + examples/franka/urdf/center_support.urdf] # orientation in RPY then position in XYZ environment_orientations: [[0. , 0. , 0.5236], + [0. , 0. , 0.5236], [0. , 0. , 0.5236]] environment_positions: [[0.6178, 0.3299, 0.45 ], - [0.7678, 0.0701, 0.45 ]] + [0.7678, 0.0701, 0.45 ], + [0.5889, 0.14 , 0.45 ]] -camera_pose: [ 0.5, -0.9, 0.75 ] +#camera_pose: [ 0.5, -0.9, 0.75 ] +#camera_target: [ 0.5, 0, 0.5 ] + +camera_pose: [ 0.5, 0.0, 1.5 ] camera_target: [ 0.5, 0, 0.5 ] \ No newline at end of file diff --git a/examples/franka/parameters/sim_scenes/supports_scene.yaml b/examples/franka/parameters/sim_scenes/supports_scene.yaml index 1f9c99e12a..c76b033f8e 100644 --- a/examples/franka/parameters/sim_scenes/supports_scene.yaml +++ b/examples/franka/parameters/sim_scenes/supports_scene.yaml @@ -7,7 +7,7 @@ environment_orientations: [[0.0, 0.0, 0.0], [0.0, 0.0, 0.0]] environment_positions: [[0.8, 0.15, 0.447], [0.8, -0.15, 0.447], - [0.7, 0.0, 0.447]] + [0.68, 0.0, 0.447]] camera_pose: [0.5, -0.9, 0.75] camera_target: [0.5, 0, 0.5] \ No newline at end of file diff --git a/examples/franka/urdf/cylinder_object.urdf b/examples/franka/urdf/cylinder_object.urdf index dc5bb57b9c..245967ebe5 100644 --- a/examples/franka/urdf/cylinder_object.urdf +++ b/examples/franka/urdf/cylinder_object.urdf @@ -10,7 +10,7 @@ - + @@ -22,7 +22,7 @@ - + diff --git a/examples/franka/urdf/tray.sdf b/examples/franka/urdf/tray.sdf index 28f0afa776..b774f23a7b 100644 --- a/examples/franka/urdf/tray.sdf +++ b/examples/franka/urdf/tray.sdf @@ -25,7 +25,7 @@ - 0.1 0.1 0.1 0.7 + 0.1 0.1 0.1 0.6 From 9fd76d3c9dbcc6da1321da1ec460ddf362449d26 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 12:59:27 -0400 Subject: [PATCH 694/758] bazel settings for new version of drake --- .bazelrc | 4 +- WORKSPACE | 25 +++----- environ.bzl | 50 ++++++++++------ tools/workspace/drake_models/BUILD.bazel | 10 ++++ .../drake_models/package.BUILD.bazel | 57 +++++++++++++++++++ tools/workspace/drake_models/repository.bzl | 16 ++++++ tools/workspace/signal_scope/BUILD.bazel | 2 - tools/workspace/signal_scope/README | 2 - tools/workspace/signal_scope/repository.bzl | 53 ----------------- 9 files changed, 126 insertions(+), 93 deletions(-) create mode 100644 tools/workspace/drake_models/BUILD.bazel create mode 100644 tools/workspace/drake_models/package.BUILD.bazel create mode 100644 tools/workspace/drake_models/repository.bzl delete mode 100644 tools/workspace/signal_scope/BUILD.bazel delete mode 100644 tools/workspace/signal_scope/README delete mode 100644 tools/workspace/signal_scope/repository.bzl diff --git a/.bazelrc b/.bazelrc index 486f79fb7e..2f75e98746 100644 --- a/.bazelrc +++ b/.bazelrc @@ -39,8 +39,8 @@ test --test_output=errors test --test_summary=terse # Use C++14. -build --cxxopt=-std=c++17 -build --host_cxxopt=-std=c++17 +build --cxxopt=-std=c++20 +build --host_cxxopt=-std=c++20 # https://github.com/bazelbuild/bazel/issues/1164 build --action_env=CCACHE_DISABLE=1 diff --git a/WORKSPACE b/WORKSPACE index fbb7b4aab0..f280d1a894 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -19,14 +19,13 @@ DRAKE_CHECKSUM = "78cf62c177c41f8415ade172c1e6eb270db619f07c4b043d5148e1f35be8da #DRAKE_CHECKSUM = "0" * 64 # Load an environment variable. -load("//:environ.bzl", "environ_repository") +load("//:environ.bzl", "drake_repository") +load("//:environ.bzl", "inekf_repository") -environ_repository( - name = "environ", - vars = ["DAIRLIB_LOCAL_DRAKE_PATH"], -) - -load("@environ//:environ.bzl", "DAIRLIB_LOCAL_DRAKE_PATH") +drake_repository(name="drake_path") +inekf_repository(name="inekf_path") +load("@drake_path//:environ.bzl", "DAIRLIB_LOCAL_DRAKE_PATH") +load("@inekf_path//:environ.bzl", "DAIRLIB_LOCAL_INEKF_PATH") # The WORKSPACE file does not permit `if` statements, so we handle the local # option by toying with the repository names. The selected repository is named @@ -67,9 +66,9 @@ load("@dairlib//tools/workspace/osqp:repository.bzl", "osqp_repository") osqp_repository(name = "osqp") -load("@dairlib//tools/workspace/signal_scope:repository.bzl", "signal_scope_repository") +load("@dairlib//tools/workspace/drake_models:repository.bzl", "drake_models_repository") -signal_scope_repository(name = "signal_scope") +drake_models_repository(name = "drake_models") # Prebuilt ROS workspace new_local_repository( @@ -113,14 +112,6 @@ INEKF_CHECKSUM = "f87e3262b0c9c9237881fcd539acd1c60000f97dfdfa47b0ae53cb7a0f3256 # displays the suggested new value for the CHECKSUM. # INEKF_CHECKSUM = "0" * 64 -# Load an environment variable. -environ_repository( - name = "environ_inekf", - vars = ["DAIRLIB_LOCAL_INEKF_PATH"], -) - -load("@environ_inekf//:environ.bzl", "DAIRLIB_LOCAL_INEKF_PATH") - # The WORKSPACE file does not permit `if` statements, so we handle the local # option by toying with the repository names. The selected repository is named # "@inekf", the other is named "@inekf_ignored". diff --git a/environ.bzl b/environ.bzl index 13eebd0625..62d1d3f06f 100644 --- a/environ.bzl +++ b/environ.bzl @@ -50,21 +50,37 @@ def _impl(repository_ctx): executable = False, ) -def environ_repository(name = None, vars = []): - """Provide specific environment variables for use in a WORKSPACE file. - The `vars` are the environment variables to provide. +#def environ_repository(name = None, vars = []): +# """Provide specific environment variables for use in a WORKSPACE file. +# The `vars` are the environment variables to provide. +# +# Example: +# environ_repository(name = "foo", vars = ["BAR", "BAZ"]) +# load("@foo//:environ.bzl", "BAR", "BAZ") +# print(BAR) +# """ +# rule = repository_rule( +# implementation = _impl, +# attrs = { +# "_vars": attr.string_list(default = vars), +# }, +# local = True, +# environ = vars, +# ) +# rule(name = name) + +#def +#def drake_repository(): +drake_repository = repository_rule( + implementation = _impl, + environ = ["DAIRLIB_LOCAL_DRAKE_PATH"], + local = True, + attrs = {"_vars": attr.string_list(default=["DAIRLIB_LOCAL_DRAKE_PATH"])}, +) +inekf_repository = repository_rule( + implementation = _impl, + environ = ["DAIRLIB_LOCAL_INEKF_PATH"], + local = True, + attrs = {"_vars": attr.string_list(default=["DAIRLIB_LOCAL_INEKF_PATH"])}, +) - Example: - environ_repository(name = "foo", vars = ["BAR", "BAZ"]) - load("@foo//:environ.bzl", "BAR", "BAZ") - print(BAR) - """ - rule = repository_rule( - implementation = _impl, - attrs = { - "_vars": attr.string_list(default = vars), - }, - local = True, - environ = vars, - ) - rule(name = name) diff --git a/tools/workspace/drake_models/BUILD.bazel b/tools/workspace/drake_models/BUILD.bazel new file mode 100644 index 0000000000..400f0f04f3 --- /dev/null +++ b/tools/workspace/drake_models/BUILD.bazel @@ -0,0 +1,10 @@ +load("@drake//doc:defs.bzl", "enumerate_filegroup") +load("@drake//tools/lint:lint.bzl", "add_lint_tests") +#load("//tools/skylark:drake_py.bzl", "drake_py_unittest") + +enumerate_filegroup( + name = "inventory.txt", + data = ["@drake_models"], +) + +add_lint_tests() diff --git a/tools/workspace/drake_models/package.BUILD.bazel b/tools/workspace/drake_models/package.BUILD.bazel new file mode 100644 index 0000000000..245f642e99 --- /dev/null +++ b/tools/workspace/drake_models/package.BUILD.bazel @@ -0,0 +1,57 @@ +# -*- bazel -*- + +package(default_visibility = ["//visibility:public"]) + +# Glob for all files in this package. We do one big glob (instead of several +# smaller ones) so Bazel's loading is as efficient as possible. +_SRCS = glob(["**/*"]) + +# All files in this repository are public. Since everything here is excluded +# from Stable API policy, there's no point in trying to set visibility for the +# stable parts vs internal-use-only parts. +exports_files(_SRCS) + +# Provide a filegroup with all files. +filegroup( + name = "drake_models", + srcs = _SRCS, +) + +# Provide one filegroup per subdirectory (so Bazel users can depend on a +# smaller set of runfiles, for efficiency). +[ + filegroup( + name = top_dir, + srcs = [ + src + for src in _SRCS + if src.startswith(top_dir + "/") + ], + ) + for top_dir in depset([ + src.split("/", 1)[0] + for src in _SRCS + if "/" in src + ]).to_list() +] + +# Nominally, the `@drake_models` external is fetched via `github_archive()`, +# which creates a json metadata files to explain what it downloaded. Drake's +# install rules use that file to pin the lazy-download version of the models. +# +# However, in case a developer is using a local checkout of `@drake_models`, +# the json file will not exist. In that case, we need to generate a stub file +# to take its place, so that our Bazel install rules can still find it. We'll +# fill it with dummy data. To guard against shipping a Drake release with the +# dummy data, the package_map_remote_test checks the content of the json file. +glob(["drake_repository_metadata.json"], allow_empty = True) or genrule( + name = "_gen_dummy_metadata", + outs = ["drake_repository_metadata.json"], + cmd = "echo '{}' > $@".format( + json.encode(dict( + urls = [], + sha256 = "", + strip_prefix = "", + )), + ), +) diff --git a/tools/workspace/drake_models/repository.bzl b/tools/workspace/drake_models/repository.bzl new file mode 100644 index 0000000000..f74b5299a8 --- /dev/null +++ b/tools/workspace/drake_models/repository.bzl @@ -0,0 +1,16 @@ +load("@drake//tools/workspace:github.bzl", "github_archive") + +def drake_models_repository( + name, + mirrors = {"github": [ + "https://github.com/{repository}/archive/refs/tags/{tag_name}.tar.gz", # noqa + "https://github.com/{repository}/archive/{commit_sha}.tar.gz", + ]}): + github_archive( + name = name, + repository = "RobotLocomotion/models", + commit = "c81f2458cf6d19a20a27e1495e7f07202536e845", + sha256 = "1107e8314e49102a247f2e87666cba8bd1e76527112ce01d849e299cf8010d94", # noqa + build_file = ":package.BUILD.bazel", + mirrors = mirrors, + ) \ No newline at end of file diff --git a/tools/workspace/signal_scope/BUILD.bazel b/tools/workspace/signal_scope/BUILD.bazel deleted file mode 100644 index eb9fa5a75d..0000000000 --- a/tools/workspace/signal_scope/BUILD.bazel +++ /dev/null @@ -1,2 +0,0 @@ -# -*- mode: python -*- -# vi: set ft=python : diff --git a/tools/workspace/signal_scope/README b/tools/workspace/signal_scope/README deleted file mode 100644 index dbdda24f04..0000000000 --- a/tools/workspace/signal_scope/README +++ /dev/null @@ -1,2 +0,0 @@ -This directory and it's files are modified and pared down from those in -Drake's //tools/workspace/drake_visualizer as of b909617dd0156d61b3dd7943bc86a00f7effaa3a \ No newline at end of file diff --git a/tools/workspace/signal_scope/repository.bzl b/tools/workspace/signal_scope/repository.bzl deleted file mode 100644 index 127a43c03f..0000000000 --- a/tools/workspace/signal_scope/repository.bzl +++ /dev/null @@ -1,53 +0,0 @@ -# -*- mode: python -*- -# vi: set ft=python : - -load("@drake//tools/workspace:os.bzl", "determine_os") - -def _impl(repository_ctx): - os_result = determine_os(repository_ctx) - if os_result.error != None: - fail(os_result.error) - - if os_result.is_macos: - urls = ["https://www.seas.upenn.edu/~posa/files/signal-scope/signal-scope-mac.zip"] - prefix = "signal-scope-mac" - sha256 = "c34b4dd4d85f9575b51cc2e03236420d8517f5fdb232bffacc09bf35ee0bd473" - elif os_result.ubuntu_release == "16.04": - urls = ["https://www.seas.upenn.edu/~posa/files/signal-scope/signal-scope-16.04.zip"] - sha256 = "d51cc26c5130cdf51ee10602d2a32032219bfdf25f96bfaa1f7dbd9d9623e1cf" - prefix = "signal-scope-16.04" - elif os_result.ubuntu_release == "18.04": - urls = ["https://www.seas.upenn.edu/~posa/files/signal-scope/signal-scope-18.04.zip"] - sha256 = "b9dd567bde8f4a1043ae9f13194b7a2cf9c8c716f8e7373f11a98a770c404d54" - prefix = "signal-scope-18.04" - elif os_result.ubuntu_release == "20.04": - urls = ["https://www.seas.upenn.edu/~posa/files/signal-scope/signal-scope-20.04.zip"] - sha256 = "6bb42fdec9767984d21cd07ab0eb13e11189c3a1b5931a5fabef4c23de247fa6" - prefix = "signal-scope-20.04" - else: - fail("Operating system is NOT supported", attr = os_result) - - root_path = repository_ctx.path("") - - repository_ctx.download_and_extract(urls, "", sha256 = sha256, stripPrefix = prefix) - - file_content = """# -*- python -*- - -# DO NOT EDIT: generated signal_scope_repository() - -filegroup( - name = "signal_scope", - srcs = glob(["**"]), - visibility = ["//visibility:public"], -) -""" - - repository_ctx.file( - "BUILD.bazel", - content = file_content, - executable = False, - ) - -signal_scope_repository = repository_rule( - implementation = _impl, -) From 507b2f6eb771170b57ca5fe41ab4e4ccf34ea3ca Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 15:36:45 -0400 Subject: [PATCH 695/758] changes for updating to drake, still need to resolve drake model paths --- bindings/pydairlib/analysis/BUILD.bazel | 2 +- .../analysis/tray_balance_study/BUILD.bazel | 4 ++-- bindings/pydairlib/franka/BUILD.bazel | 2 +- examples/Cassie/cassie_state_estimator.h | 2 +- .../contact_scheduler/kinodynamic_planner.cc | 2 +- examples/Cassie/osc/heading_traj_generator.h | 2 +- examples/Cassie/osc/high_level_command.h | 2 +- examples/Cassie/osc/standing_com_traj.h | 2 +- .../osc/standing_pelvis_orientation_traj.h | 2 +- examples/Cassie/osc/swing_toe_traj_generator.h | 2 +- examples/Cassie/osc/walking_speed_control.h | 2 +- .../osc_jump/flight_foot_traj_generator.cc | 2 +- .../osc_jump/pelvis_trans_traj_generator.h | 2 +- .../Cassie/osc_jump/toe_angle_traj_generator.h | 2 +- examples/Cassie/osc_run/foot_traj_generator.cc | 2 +- .../osc_run/pelvis_trans_traj_generator.h | 2 +- examples/franka/BUILD.bazel | 18 +++++++++--------- examples/franka/franka_sim.cc | 2 +- examples/franka/franka_visualizer.cc | 2 +- .../franka/parameters/franka_sim_params.yaml | 2 +- .../systems/end_effector_force_trajectory.cc | 2 +- multibody/multibody_utils.cc | 4 ++-- solvers/lcs_factory.cc | 6 ++---- solvers/lcs_factory.h | 6 ++---- systems/controllers/alip_swing_ft_traj_gen.h | 2 +- systems/controllers/alip_traj_gen.h | 2 +- systems/controllers/c3/lcs_factory_system.cc | 5 ++--- systems/controllers/lipm_traj_gen.h | 2 +- .../osc/external_force_tracking_data.h | 8 ++++---- .../osc/operational_space_control.h | 4 ++-- systems/controllers/osc/osc_tracking_data.h | 4 ++-- .../controllers/osc/rot_space_tracking_data.h | 4 ++-- .../osc/trans_space_tracking_data.h | 4 ++-- systems/controllers/swing_ft_traj_gen.h | 2 +- systems/primitives/vector_aggregator.h | 2 +- 35 files changed, 55 insertions(+), 60 deletions(-) diff --git a/bindings/pydairlib/analysis/BUILD.bazel b/bindings/pydairlib/analysis/BUILD.bazel index 0b685a6721..996b39a0b7 100644 --- a/bindings/pydairlib/analysis/BUILD.bazel +++ b/bindings/pydairlib/analysis/BUILD.bazel @@ -95,7 +95,7 @@ py_library( name = "franka_plotting_utils", srcs = ["franka_plotting_utils.py"], data = [ - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", "@lcm//:lcm-python", ], deps = [ diff --git a/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel b/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel index 0ad3234d92..10aa865f41 100644 --- a/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel +++ b/bindings/pydairlib/analysis/tray_balance_study/BUILD.bazel @@ -15,7 +15,7 @@ py_binary( name = "run_tray_parameter_study", srcs = ["run_tray_parameter_study.py"], data = [ - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", "@lcm//:lcm-python", ], deps = [ @@ -30,7 +30,7 @@ py_binary( data = [ ":parameter_study_config.yaml", "//examples/franka:parameters", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", "@lcm//:lcm-python", ], deps = [ diff --git a/bindings/pydairlib/franka/BUILD.bazel b/bindings/pydairlib/franka/BUILD.bazel index 90a7620fcf..ae7aee9651 100644 --- a/bindings/pydairlib/franka/BUILD.bazel +++ b/bindings/pydairlib/franka/BUILD.bazel @@ -32,7 +32,7 @@ py_binary( srcs = ["franka_env.py"], data = [ "//examples/franka:urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ "//bindings/pydairlib/franka", diff --git a/examples/Cassie/cassie_state_estimator.h b/examples/Cassie/cassie_state_estimator.h index 1aa90f5c99..fef0379d24 100644 --- a/examples/Cassie/cassie_state_estimator.h +++ b/examples/Cassie/cassie_state_estimator.h @@ -162,7 +162,7 @@ class CassieStateEstimator : public drake::systems::LeafSystem { const multibody::KinematicEvaluatorSet* fourbar_evaluator_; const multibody::KinematicEvaluatorSet* left_contact_evaluator_; const multibody::KinematicEvaluatorSet* right_contact_evaluator_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const bool is_floating_base_; std::unique_ptr> context_; diff --git a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc index d372908232..f5fca87f4c 100644 --- a/examples/Cassie/contact_scheduler/kinodynamic_planner.cc +++ b/examples/Cassie/contact_scheduler/kinodynamic_planner.cc @@ -1,7 +1,7 @@ #include "kinodynamic_planner.h" using drake::AbstractValue; -using drake::multibody::BodyFrame; +using drake::multibody::RigidBodyFrame; using drake::multibody::JacobianWrtVariable; using drake::systems::BasicVector; using drake::systems::Context; diff --git a/examples/Cassie/osc/heading_traj_generator.h b/examples/Cassie/osc/heading_traj_generator.h index b51ce32b78..9ddd4be152 100644 --- a/examples/Cassie/osc/heading_traj_generator.h +++ b/examples/Cassie/osc/heading_traj_generator.h @@ -41,7 +41,7 @@ class HeadingTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const drake::multibody::Body& pelvis_; int state_port_; diff --git a/examples/Cassie/osc/high_level_command.h b/examples/Cassie/osc/high_level_command.h index 5912d5c25d..9bc3c2346a 100644 --- a/examples/Cassie/osc/high_level_command.h +++ b/examples/Cassie/osc/high_level_command.h @@ -102,7 +102,7 @@ class HighLevelCommand : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const drake::multibody::Body& pelvis_; bool use_radio_command_; diff --git a/examples/Cassie/osc/standing_com_traj.h b/examples/Cassie/osc/standing_com_traj.h index 438dc8e0e5..f49e50c5a5 100644 --- a/examples/Cassie/osc/standing_com_traj.h +++ b/examples/Cassie/osc/standing_com_traj.h @@ -58,7 +58,7 @@ class StandingComTraj : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; int state_port_; int target_height_port_; diff --git a/examples/Cassie/osc/standing_pelvis_orientation_traj.h b/examples/Cassie/osc/standing_pelvis_orientation_traj.h index c0ab3e1c2b..d52470406d 100644 --- a/examples/Cassie/osc/standing_pelvis_orientation_traj.h +++ b/examples/Cassie/osc/standing_pelvis_orientation_traj.h @@ -37,7 +37,7 @@ class StandingPelvisOrientationTraj const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; // A list of pairs of contact body frame and contact point const std::vector< diff --git a/examples/Cassie/osc/swing_toe_traj_generator.h b/examples/Cassie/osc/swing_toe_traj_generator.h index 245ac574fe..d23fb1efdb 100644 --- a/examples/Cassie/osc/swing_toe_traj_generator.h +++ b/examples/Cassie/osc/swing_toe_traj_generator.h @@ -31,7 +31,7 @@ class SwingToeTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; int swing_toe_idx_; // A list of pairs of contact body frame and contact point diff --git a/examples/Cassie/osc/walking_speed_control.h b/examples/Cassie/osc/walking_speed_control.h index 55802195a3..afd2e88849 100644 --- a/examples/Cassie/osc/walking_speed_control.h +++ b/examples/Cassie/osc/walking_speed_control.h @@ -71,7 +71,7 @@ class WalkingSpeedControl : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const drake::multibody::Body& pelvis_; double swing_phase_duration_; diff --git a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc index 62ee294b3c..980d36a625 100644 --- a/examples/Cassie/osc_jump/flight_foot_traj_generator.cc +++ b/examples/Cassie/osc_jump/flight_foot_traj_generator.cc @@ -10,7 +10,7 @@ using Eigen::VectorXd; using std::string; using dairlib::systems::OutputVector; -using drake::multibody::BodyFrame; +using drake::multibody::RigidBodyFrame; using drake::multibody::Frame; using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; diff --git a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h index ddbf25ce8b..4508ff6a12 100644 --- a/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_jump/pelvis_trans_traj_generator.h @@ -51,7 +51,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; drake::systems::DiscreteStateIndex prev_fsm_idx_; drake::systems::DiscreteStateIndex pelvis_x_offset_idx_; diff --git a/examples/Cassie/osc_jump/toe_angle_traj_generator.h b/examples/Cassie/osc_jump/toe_angle_traj_generator.h index ab769aa420..ffa390a2e1 100644 --- a/examples/Cassie/osc_jump/toe_angle_traj_generator.h +++ b/examples/Cassie/osc_jump/toe_angle_traj_generator.h @@ -39,7 +39,7 @@ class FlightToeAngleTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; drake::trajectories::PiecewisePolynomial toe_traj_; bool use_traj_; diff --git a/examples/Cassie/osc_run/foot_traj_generator.cc b/examples/Cassie/osc_run/foot_traj_generator.cc index 0f55d4ae9b..9e2fd6e75b 100644 --- a/examples/Cassie/osc_run/foot_traj_generator.cc +++ b/examples/Cassie/osc_run/foot_traj_generator.cc @@ -15,7 +15,7 @@ using Eigen::VectorXd; using std::string; using dairlib::systems::OutputVector; -using drake::multibody::BodyFrame; +using drake::multibody::RigidBodyFrame; using drake::multibody::Frame; using drake::multibody::JacobianWrtVariable; using drake::multibody::MultibodyPlant; diff --git a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h index a6193b549a..2337662ef4 100644 --- a/examples/Cassie/osc_run/pelvis_trans_traj_generator.h +++ b/examples/Cassie/osc_run/pelvis_trans_traj_generator.h @@ -51,7 +51,7 @@ class PelvisTransTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const drake::multibody::Body& pelvis_; // A list of pairs of contact body frame and contact point diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index aafa1758ef..bda08c180f 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -15,7 +15,7 @@ cc_binary( srcs = ["full_diagram.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -32,7 +32,7 @@ cc_binary( srcs = ["franka_sim.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -53,7 +53,7 @@ cc_binary( srcs = ["franka_osc_controller.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -77,7 +77,7 @@ cc_binary( srcs = ["franka_c3_controller.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -103,7 +103,7 @@ cc_binary( srcs = ["franka_c3_controller_two_objects.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -129,7 +129,7 @@ cc_binary( srcs = ["forward_kinematics_for_lcs.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -155,7 +155,7 @@ cc_binary( srcs = ["franka_visualizer.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], deps = [ ":parameters", @@ -177,7 +177,7 @@ cc_binary( srcs = ["franka_ros_lcm_bridge.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], tags = ["ros"], deps = [ @@ -200,7 +200,7 @@ cc_binary( srcs = ["franka_lcm_ros_bridge.cc"], data = [ ":urdfs", - "@drake//manipulation/models/franka_description:models", + "@drake_models//:franka_description", ], tags = ["ros"], deps = [ diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 39a3d0eac1..a0ecebe0fd 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -74,7 +74,7 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant); parser.SetAutoRenaming(true); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + parser.AddModelsFromUrl(sim_params.franka_model)[0]; drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 3f52360859..10fffa12d9 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -83,7 +83,7 @@ int do_main(int argc, char* argv[]) { Parser parser(&plant, &scene_graph); parser.SetAutoRenaming(true); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + parser.AddModelsFromUrl(sim_params.franka_model)[0]; drake::multibody::ModelInstanceIndex end_effector_index = parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 61d8db0553..5b1731af14 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -1,4 +1,4 @@ -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf tray_model: examples/franka/urdf/tray.sdf # rigid contact model does not do sticking well object_model: examples/franka/urdf/cylinder_object.urdf diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force_trajectory.cc index 0c6d337683..5daabaee6e 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force_trajectory.cc @@ -10,7 +10,7 @@ using Eigen::VectorXd; using std::string; using dairlib::systems::OutputVector; -using drake::multibody::BodyFrame; +using drake::multibody::RigidBodyFrame; using drake::multibody::MultibodyPlant; using drake::systems::BasicVector; using drake::systems::Context; diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index b603f1861c..d2487a61d4 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -329,7 +329,7 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { auto floating_bodies = plant.GetFloatingBaseBodies(); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); - int start = body.floating_velocities_start() - plant.num_positions(); + int start = body.floating_velocities_start_in_v() - plant.num_positions(); std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; @@ -395,7 +395,7 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant, if (plant.HasUniqueFreeBaseBody(model_instance)) { const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); - int start = body.floating_velocities_start() - plant.num_positions(); + int start = body.floating_velocities_start_in_v() - plant.num_positions(); std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index a7eaf27e8f..ff22accc4a 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -255,12 +255,10 @@ std::pair> LCSFactory::ComputeContactJacobian( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, - const drake::multibody::MultibodyPlant& plant_ad, - const drake::systems::Context& context_ad, const std::vector>& contact_geoms, - int num_friction_directions, const std::vector& mu, double dt, - int N, dairlib::solvers::ContactModel contact_model) { + int num_friction_directions, const std::vector& mu, + dairlib::solvers::ContactModel contact_model) { int n_contacts = contact_geoms.size(); int n_v = plant.num_velocities(); diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index 2258b69451..e7eff1b51a 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -46,12 +46,10 @@ class LCSFactory { static std::pair> ComputeContactJacobian( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, - const drake::multibody::MultibodyPlant& plant_ad, - const drake::systems::Context& context_ad, const std::vector>& contact_geoms, - int num_friction_directions, const std::vector& mu, double dt, - int N, ContactModel = ContactModel::kStewartAndTrinkle); + int num_friction_directions, const std::vector& mu, + ContactModel = ContactModel::kStewartAndTrinkle); /// Create an LCS by fixing some modes from another LCS /// Ignores generated inequalities that correspond to these modes, but diff --git a/systems/controllers/alip_swing_ft_traj_gen.h b/systems/controllers/alip_swing_ft_traj_gen.h index d154f9d702..6c04b9b763 100644 --- a/systems/controllers/alip_swing_ft_traj_gen.h +++ b/systems/controllers/alip_swing_ft_traj_gen.h @@ -107,7 +107,7 @@ class AlipSwingFootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const drake::multibody::Body& pelvis_; std::vector left_right_support_fsm_states_; diff --git a/systems/controllers/alip_traj_gen.h b/systems/controllers/alip_traj_gen.h index 5a4c76ae88..49a8edb0a0 100644 --- a/systems/controllers/alip_traj_gen.h +++ b/systems/controllers/alip_traj_gen.h @@ -119,7 +119,7 @@ class ALIPTrajGenerator : public drake::systems::LeafSystem { const std::vector&>>>& contact_points_in_each_state_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; double m_; diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index b29f087597..9f79719792 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -142,9 +142,8 @@ void LCSFactorySystem::OutputLCSContactJacobian(const drake::systems::Context contact_points; *output = LCSFactory::ComputeContactJacobian( - plant_, context_, plant_ad_, context_ad_, contact_pairs_, - c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, - c3_options_.N, contact_model); + plant_, context_, contact_pairs_, + c3_options_.num_friction_directions, c3_options_.mu, contact_model); } } // namespace systems diff --git a/systems/controllers/lipm_traj_gen.h b/systems/controllers/lipm_traj_gen.h index 43638019d2..20785f2eb5 100644 --- a/systems/controllers/lipm_traj_gen.h +++ b/systems/controllers/lipm_traj_gen.h @@ -105,7 +105,7 @@ class LIPMTrajGenerator : public drake::systems::LeafSystem { const std::vector&>>>& contact_points_in_each_state_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; bool use_com_; diff --git a/systems/controllers/osc/external_force_tracking_data.h b/systems/controllers/osc/external_force_tracking_data.h index 196943457c..b97a0aa7d6 100644 --- a/systems/controllers/osc/external_force_tracking_data.h +++ b/systems/controllers/osc/external_force_tracking_data.h @@ -45,11 +45,11 @@ class ExternalForceTrackingData { const drake::multibody::MultibodyPlant& plant_w_spr_; const drake::multibody::MultibodyPlant& plant_wo_spr_; // World frames - const drake::multibody::BodyFrame& world_w_spr_; - const drake::multibody::BodyFrame& world_wo_spr_; + const drake::multibody::RigidBodyFrame& world_w_spr_; + const drake::multibody::RigidBodyFrame& world_wo_spr_; - const drake::multibody::BodyFrame* body_frame_w_spr_; - const drake::multibody::BodyFrame* body_frame_wo_spr_; + const drake::multibody::RigidBodyFrame* body_frame_w_spr_; + const drake::multibody::RigidBodyFrame* body_frame_wo_spr_; const Eigen::Vector3d pt_on_body_; int n_lambda_ = 3; diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index 03d122d397..f3694f06cd 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -364,8 +364,8 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { drake::systems::Context* context_wo_spr_; // World frames - const drake::multibody::BodyFrame& world_w_spr_; - const drake::multibody::BodyFrame& world_wo_spr_; + const drake::multibody::RigidBodyFrame& world_w_spr_; + const drake::multibody::RigidBodyFrame& world_wo_spr_; // Size of position, velocity and input of the MBP without spring int n_q_; diff --git a/systems/controllers/osc/osc_tracking_data.h b/systems/controllers/osc/osc_tracking_data.h index 94bcb81883..cf7e42d9f2 100644 --- a/systems/controllers/osc/osc_tracking_data.h +++ b/systems/controllers/osc/osc_tracking_data.h @@ -169,8 +169,8 @@ class OscTrackingData { const drake::multibody::MultibodyPlant& plant_wo_spr_; // World frames - const drake::multibody::BodyFrame& world_w_spr_; - const drake::multibody::BodyFrame& world_wo_spr_; + const drake::multibody::RigidBodyFrame& world_w_spr_; + const drake::multibody::RigidBodyFrame& world_wo_spr_; private: void UpdateDesired(const drake::trajectories::Trajectory& traj, diff --git a/systems/controllers/osc/rot_space_tracking_data.h b/systems/controllers/osc/rot_space_tracking_data.h index 713ea5c6c0..6b8b9aebb4 100644 --- a/systems/controllers/osc/rot_space_tracking_data.h +++ b/systems/controllers/osc/rot_space_tracking_data.h @@ -36,9 +36,9 @@ class RotTaskSpaceTrackingData final : public OptionsTrackingData { const Eigen::Isometry3d& frame_pose = Eigen::Isometry3d::Identity()); protected: - std::unordered_map*> + std::unordered_map*> body_frames_w_spr_; - std::unordered_map*> + std::unordered_map*> body_frames_wo_spr_; private: diff --git a/systems/controllers/osc/trans_space_tracking_data.h b/systems/controllers/osc/trans_space_tracking_data.h index f4067686f5..909f150803 100644 --- a/systems/controllers/osc/trans_space_tracking_data.h +++ b/systems/controllers/osc/trans_space_tracking_data.h @@ -33,9 +33,9 @@ class TransTaskSpaceTrackingData final : public OptionsTrackingData { const Eigen::Vector3d& pt_on_body = Eigen::Vector3d::Zero()); protected: - std::unordered_map*> + std::unordered_map*> body_frames_w_spr_; - std::unordered_map*> + std::unordered_map*> body_frames_wo_spr_; private: diff --git a/systems/controllers/swing_ft_traj_gen.h b/systems/controllers/swing_ft_traj_gen.h index 80bf1e7a45..3c4b9e4a9f 100644 --- a/systems/controllers/swing_ft_traj_gen.h +++ b/systems/controllers/swing_ft_traj_gen.h @@ -110,7 +110,7 @@ class SwingFootTrajGenerator : public drake::systems::LeafSystem { const drake::multibody::MultibodyPlant& plant_; drake::systems::Context* context_; - const drake::multibody::BodyFrame& world_; + const drake::multibody::RigidBodyFrame& world_; const drake::multibody::Body& pelvis_; std::vector left_right_support_fsm_states_; diff --git a/systems/primitives/vector_aggregator.h b/systems/primitives/vector_aggregator.h index 279094e79d..78819e10d9 100644 --- a/systems/primitives/vector_aggregator.h +++ b/systems/primitives/vector_aggregator.h @@ -65,7 +65,7 @@ class VectorAggregator : public drake::systems::LeafSystem { private: void DoPublish(const drake::systems::Context& context, const std::vector*>& - events) const override { + events) const { const TimestampedVector* input = dynamic_cast*>( EvalVectorInput(context, 0)); From bb0dfe4a154305715cc6a9f3c578dfcec95dfd92 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 16:06:45 -0400 Subject: [PATCH 696/758] using new franka model path --- examples/franka/diagrams/franka_osc_controller_diagram.cc | 2 +- examples/franka/diagrams/franka_sim_diagram.cc | 2 +- examples/franka/franka_c3_controller.cc | 3 +-- examples/franka/franka_lcm_ros_bridge.cc | 2 +- examples/franka/franka_osc_controller.cc | 2 +- examples/franka/franka_ros_lcm_bridge.cc | 2 +- examples/franka/full_diagram.cc | 2 +- .../parameters/c3_options/franka_c3_options_supports.yaml | 4 ++-- .../franka/parameters/c3_scenes/supports_rotated_scene.yaml | 2 +- examples/franka/parameters/c3_scenes/supports_scene.yaml | 2 +- examples/franka/parameters/c3_scenes/tray_scene.yaml | 2 +- examples/franka/parameters/c3_scenes/two_object_scene.yaml | 2 +- examples/franka/parameters/c3_scenes/wall_scene.yaml | 2 +- examples/franka/parameters/franka_osc_controller_params.yaml | 5 ++--- examples/franka/parameters/franka_sim_params.yaml | 4 ++-- examples/franka/parameters/sim_scenes/supports_scene.yaml | 2 +- multibody/multibody_utils.cc | 4 ++-- 17 files changed, 21 insertions(+), 23 deletions(-) diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index 09904db905..d71f0939ac 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -75,7 +75,7 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( plant_ = new drake::multibody::MultibodyPlant(0.0); Parser parser(plant_, nullptr); - parser.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); + parser.AddModelsFromUrl(controller_params.franka_model); RigidTransform X_WI = RigidTransform::Identity(); plant_->WeldFrames(plant_->world_frame(), diff --git a/examples/franka/diagrams/franka_sim_diagram.cc b/examples/franka/diagrams/franka_sim_diagram.cc index f17b9cf31e..584acef837 100644 --- a/examples/franka/diagrams/franka_sim_diagram.cc +++ b/examples/franka/diagrams/franka_sim_diagram.cc @@ -44,7 +44,7 @@ FrankaSimDiagram::FrankaSimDiagram(std::unique_ptr plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); - parser_franka.AddModels( - drake::FindResourceOrThrow(scene_params.franka_model)); + parser_franka.AddModelsFromUrl(scene_params.franka_model); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( FindResourceOrThrow(scene_params.end_effector_model))[0]; diff --git a/examples/franka/franka_lcm_ros_bridge.cc b/examples/franka/franka_lcm_ros_bridge.cc index d0b82b7b88..7c0252e06c 100644 --- a/examples/franka/franka_lcm_ros_bridge.cc +++ b/examples/franka/franka_lcm_ros_bridge.cc @@ -81,7 +81,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant); - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + parser.AddModelsFromUrl(sim_params.franka_model)[0]; Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index d9a205575c..3b0c71a6fd 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -86,7 +86,7 @@ int DoMain(int argc, char* argv[]) { drake::multibody::MultibodyPlant plant(0.0); Parser parser(&plant, nullptr); - parser.AddModels(drake::FindResourceOrThrow(controller_params.franka_model)); + parser.AddModelsFromUrl(controller_params.franka_model); RigidTransform X_WI = RigidTransform::Identity(); plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index 259b57f4ac..f61ae024ba 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -83,7 +83,7 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant); auto franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + parser.AddModelsFromUrl(sim_params.franka_model)[0]; auto tray_index = parser.AddModels(FindResourceOrThrow(sim_params.tray_model))[0]; Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 54b1bb3129..3e3ea219f0 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -78,7 +78,7 @@ int DoMain(int argc, char* argv[]) { Parser parser(&plant); parser.SetAutoRenaming(true); drake::multibody::ModelInstanceIndex franka_index = - parser.AddModels(drake::FindResourceOrThrow(sim_params.franka_model))[0]; + parser.AddModelsFromUrl(sim_params.franka_model)[0]; drake::multibody::ModelInstanceIndex c3_end_effector_index = parser.AddModels(FindResourceOrThrow(sim_params.end_effector_model))[0]; drake::multibody::ModelInstanceIndex tray_index = diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index b4b2fcceb2..2278dfe9fd 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -39,12 +39,12 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 #Penalty on all decision variables, assuming scalar -w_G: 0.15 +w_G: 0.2 #Penalty on all decision variables, assuming scalar w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 3000000, 15000, +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal r_vector: [0.15, 0.15, 0.1] diff --git a/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml b/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml index 2a4d319dac..069fb2bf64 100644 --- a/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml +++ b/examples/franka/parameters/c3_scenes/supports_rotated_scene.yaml @@ -1,4 +1,4 @@ -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf diff --git a/examples/franka/parameters/c3_scenes/supports_scene.yaml b/examples/franka/parameters/c3_scenes/supports_scene.yaml index 3007a9bfee..a0aaecdb2f 100644 --- a/examples/franka/parameters/c3_scenes/supports_scene.yaml +++ b/examples/franka/parameters/c3_scenes/supports_scene.yaml @@ -1,4 +1,4 @@ -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf diff --git a/examples/franka/parameters/c3_scenes/tray_scene.yaml b/examples/franka/parameters/c3_scenes/tray_scene.yaml index a22ff7fd9e..4d8fae92ac 100644 --- a/examples/franka/parameters/c3_scenes/tray_scene.yaml +++ b/examples/franka/parameters/c3_scenes/tray_scene.yaml @@ -1,4 +1,4 @@ -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf diff --git a/examples/franka/parameters/c3_scenes/two_object_scene.yaml b/examples/franka/parameters/c3_scenes/two_object_scene.yaml index 05a6da5bb7..9a394e55c8 100644 --- a/examples/franka/parameters/c3_scenes/two_object_scene.yaml +++ b/examples/franka/parameters/c3_scenes/two_object_scene.yaml @@ -1,4 +1,4 @@ -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf diff --git a/examples/franka/parameters/c3_scenes/wall_scene.yaml b/examples/franka/parameters/c3_scenes/wall_scene.yaml index 207555065d..39e02111a1 100644 --- a/examples/franka/parameters/c3_scenes/wall_scene.yaml +++ b/examples/franka/parameters/c3_scenes/wall_scene.yaml @@ -1,4 +1,4 @@ -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector.urdf end_effector_name: plate end_effector_lcs_model: examples/franka/urdf/plate_end_effector_translation.urdf diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 0ee6adfb3a..8fa4ae1673 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -1,13 +1,12 @@ controller_frequency: 1000 -franka_model: drake/manipulation/models/franka_description/urdf/panda_arm.urdf +franka_model: package://drake_models/franka_description/urdf/panda_arm.urdf end_effector_model: examples/franka/urdf/plate_end_effector_massless.urdf end_effector_name: plate tool_attachment_frame: [0, 0, 0.107] -neutral_position: [0.4763, 0.075 , 0.47] -#neutral_position: [0.55, 0, 0.45] +neutral_position: [0.55, 0, 0.45] x_scale: 0.1 y_scale: 0.1 z_scale: 0.1 diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 5b1731af14..bd6ea15fd7 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -9,7 +9,7 @@ visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 1 -visualize_drake_sim: false +visualize_drake_sim: true publish_efforts: true tool_attachment_frame: [0, 0, 0.107] @@ -36,7 +36,7 @@ world_z_limits: [[0.35, 0.7], external_force_scaling: [10.0, 10.0, 10.0] dt: 0.0005 -realtime_rate: 0.9 +realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], diff --git a/examples/franka/parameters/sim_scenes/supports_scene.yaml b/examples/franka/parameters/sim_scenes/supports_scene.yaml index c76b033f8e..00172ea599 100644 --- a/examples/franka/parameters/sim_scenes/supports_scene.yaml +++ b/examples/franka/parameters/sim_scenes/supports_scene.yaml @@ -7,7 +7,7 @@ environment_orientations: [[0.0, 0.0, 0.0], [0.0, 0.0, 0.0]] environment_positions: [[0.8, 0.15, 0.447], [0.8, -0.15, 0.447], - [0.68, 0.0, 0.447]] + [0.75, 0.0, 0.447]] camera_pose: [0.5, -0.9, 0.75] camera_target: [0.5, 0, 0.5] \ No newline at end of file diff --git a/multibody/multibody_utils.cc b/multibody/multibody_utils.cc index d2487a61d4..8bd7d0a66d 100644 --- a/multibody/multibody_utils.cc +++ b/multibody/multibody_utils.cc @@ -329,7 +329,7 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant) { auto floating_bodies = plant.GetFloatingBaseBodies(); for (auto body_index : floating_bodies) { const auto& body = plant.get_body(body_index); - int start = body.floating_velocities_start_in_v() - plant.num_positions(); + int start = body.floating_velocities_start_in_v(); std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; @@ -395,7 +395,7 @@ map MakeNameToVelocitiesMap(const MultibodyPlant& plant, if (plant.HasUniqueFreeBaseBody(model_instance)) { const auto& body = plant.GetUniqueFreeBaseBodyOrThrow(model_instance); - int start = body.floating_velocities_start_in_v() - plant.num_positions(); + int start = body.floating_velocities_start_in_v(); std::string name = body.name(); name_to_index_map[name + "_wx"] = start; name_to_index_map[name + "_wy"] = start + 1; From a505c42c9049a3f17e3fd3f23a164da727d7b769 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 16:13:01 -0400 Subject: [PATCH 697/758] filtering out collision geometry that i previously removed in my previous version of drake --- examples/franka/franka_sim.cc | 1 + .../parameters/c3_options/franka_c3_options_supports.yaml | 2 +- examples/franka/parameters/sim_scenes/supports_scene.yaml | 2 +- 3 files changed, 3 insertions(+), 2 deletions(-) diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index a0ecebe0fd..0598a7c022 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -130,6 +130,7 @@ int DoMain(int argc, char* argv[]) { &plant.GetBodyByName("panda_link4"), &plant.GetBodyByName("panda_link5"), &plant.GetBodyByName("panda_link6"), + &plant.GetBodyByName("panda_link7"), &plant.GetBodyByName("panda_link8"), }); auto tray_collision_set = GeometrySet( diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 2278dfe9fd..40b26fc13d 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -39,7 +39,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 #Penalty on all decision variables, assuming scalar -w_G: 0.2 +w_G: 0.1 #Penalty on all decision variables, assuming scalar w_U: 0.1 diff --git a/examples/franka/parameters/sim_scenes/supports_scene.yaml b/examples/franka/parameters/sim_scenes/supports_scene.yaml index 00172ea599..1f9c99e12a 100644 --- a/examples/franka/parameters/sim_scenes/supports_scene.yaml +++ b/examples/franka/parameters/sim_scenes/supports_scene.yaml @@ -7,7 +7,7 @@ environment_orientations: [[0.0, 0.0, 0.0], [0.0, 0.0, 0.0]] environment_positions: [[0.8, 0.15, 0.447], [0.8, -0.15, 0.447], - [0.75, 0.0, 0.447]] + [0.7, 0.0, 0.447]] camera_pose: [0.5, -0.9, 0.75] camera_target: [0.5, 0, 0.5] \ No newline at end of file From 30608ef69e4201b152ddd0d3e1a654adeffa0803 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 16:17:38 -0400 Subject: [PATCH 698/758] fixing some more model paths --- bindings/pydairlib/analysis/franka_plotting_utils.py | 5 ++--- examples/franka/diagrams/franka_c3_controller_diagram.cc | 3 +-- examples/franka/forward_kinematics_for_lcs.cc | 3 +-- examples/franka/franka_c3_controller_two_objects.cc | 3 +-- 4 files changed, 5 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index bfc83ffee2..cd154c9b82 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -13,8 +13,7 @@ from pydrake.all import MultibodyPlant, Parser, RigidTransform, \ FindResourceOrThrow -franka_urdf = FindResourceOrThrow( - "drake/manipulation/models/franka_description/urdf/panda_arm.urdf") +franka_urdf = "package://drake_models/franka_description/urdf/panda_arm.urdf" end_effector_model = "examples/franka/urdf/plate_end_effector.urdf" tray_model = "examples/franka/urdf/tray.sdf" tool_attachment_frame = np.array([0, 0, 0.107]) @@ -42,7 +41,7 @@ def make_plant_and_context(): franka_plant = MultibodyPlant(0.0) franka_parser = Parser(franka_plant) - franka_parser.AddModels(franka_urdf) + franka_parser.AddModelsFromUrl(franka_urdf) end_effector_index = \ franka_parser.AddModels(end_effector_model)[0] T_EE_W = RigidTransform(tool_attachment_frame) diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 944c17b312..e057092567 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -81,8 +81,7 @@ FrankaC3ControllerDiagram::FrankaC3ControllerDiagram( plant_franka_ = new drake::multibody::MultibodyPlant(0.0); Parser parser_franka(plant_franka_, nullptr); - parser_franka.AddModels( - drake::FindResourceOrThrow(scene_params.franka_model)); + parser_franka.AddModelsFromUrl(scene_params.franka_model); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( FindResourceOrThrow(scene_params.end_effector_model))[0]; diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index 13e724c79c..5e943dc5f9 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -81,8 +81,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); - parser_franka.AddModels( - drake::FindResourceOrThrow(scene_params.franka_model)); + parser_franka.AddModelsFromUrl(scene_params.franka_model); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( FindResourceOrThrow(scene_params.end_effector_model))[0]; diff --git a/examples/franka/franka_c3_controller_two_objects.cc b/examples/franka/franka_c3_controller_two_objects.cc index 0fdc454b5a..34d980ea88 100644 --- a/examples/franka/franka_c3_controller_two_objects.cc +++ b/examples/franka/franka_c3_controller_two_objects.cc @@ -83,8 +83,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); - parser_franka.AddModels( - drake::FindResourceOrThrow(scene_params.franka_model)); + parser_franka.AddModelsFromUrl(scene_params.franka_model); drake::multibody::ModelInstanceIndex end_effector_index = parser_franka.AddModels( FindResourceOrThrow(scene_params.end_effector_model))[0]; From 42b96ad83f7d4abd89efcb885ad374cf8624a107 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 17:20:44 -0400 Subject: [PATCH 699/758] scaling lambda only within c3 instead of in lcs factory --- solvers/c3.cc | 26 +++++++++++++++++++- solvers/c3.h | 1 + solvers/lcs_factory.cc | 14 ++--------- solvers/lcs_factory.h | 2 +- systems/controllers/c3/lcs_factory_system.cc | 3 +-- systems/controllers/c3_controller.cc | 4 +-- 6 files changed, 32 insertions(+), 18 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index 2b97837955..2ed47815e0 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -93,6 +93,17 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, } } + auto Dn = D_.at(0).squaredNorm(); + auto An = A_.at(0).squaredNorm(); + double AnDn_ = An / Dn; + + for (int i = 0 ; i < N_; ++i){ + D_.at(i) *= AnDn_; + E_.at(i) /= AnDn_; + c_.at(i) /= AnDn_; + H_.at(i) /= AnDn_; + } + x_ = vector(); u_ = vector(); lambda_ = vector(); @@ -169,6 +180,17 @@ void C3::UpdateLCS(const LCS& lcs) { MatrixXd LinEq = MatrixXd::Zero(n_, 2 * n_ + m_ + k_); LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); + auto Dn = D_[0].squaredNorm(); + auto An = A_[0].squaredNorm(); + double AnDn_ = An / Dn; + + for (int i = 0 ; i < N_; ++i){ + D_.at(i) *= AnDn_; + E_.at(i) /= AnDn_; + c_.at(i) /= AnDn_; + H_.at(i) /= AnDn_; + } + for (int i = 0; i < N_; i++) { LinEq.block(0, 0, n_, n_) = A_.at(i); LinEq.block(0, n_, n_, m_) = D_.at(i); @@ -222,7 +244,9 @@ void C3::Solve(const VectorXd& x0) { *w_sol_ = w; *delta_sol_ = delta; } - + for (int i = 0; i < N_; ++i){ + lambda_sol_->at(i) *= AnDn_; + } } void C3::ADMMStep(const VectorXd& x0, vector* delta, diff --git a/solvers/c3.h b/solvers/c3.h index bf1f7f0d84..42b54641fa 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -130,6 +130,7 @@ class C3 { std::vector F_; std::vector H_; std::vector c_; + double AnDn_; const std::vector Q_; const std::vector R_; const std::vector U_; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index ff22accc4a..a4eb5cd227 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -28,7 +28,7 @@ using drake::systems::Context; using Eigen::MatrixXd; using Eigen::VectorXd; -std::pair LCSFactory::LinearizePlantToLCS( +LCS LCSFactory::LinearizePlantToLCS( const MultibodyPlant& plant, const Context& context, const MultibodyPlant& plant_ad, const Context& context_ad, @@ -236,19 +236,9 @@ std::pair LCSFactory::LinearizePlantToLCS( E_t.transpose() * J_n * vNqdot * plant.GetPositions(context) / dt; } - auto Dn = D.squaredNorm(); - auto An = A.squaredNorm(); - auto AnDn = An / Dn; - - D *= AnDn; - E /= AnDn; - c /= AnDn; - H /= AnDn; - LCS system(A, B, D, d, E, F, H, c, N, dt); - std::pair ret(system, AnDn); - return ret; + return system; } std::pair> diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index e7eff1b51a..e86d94d439 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -33,7 +33,7 @@ class LCSFactory { /// @param mu /// @oaram dt The timestep for discretization /// @param N - static std::pair LinearizePlantToLCS( + static LCS LinearizePlantToLCS( const drake::multibody::MultibodyPlant& plant, const drake::systems::Context& context, const drake::multibody::MultibodyPlant& plant_ad, diff --git a/systems/controllers/c3/lcs_factory_system.cc b/systems/controllers/c3/lcs_factory_system.cc index 9f79719792..fc4cc16a70 100644 --- a/systems/controllers/c3/lcs_factory_system.cc +++ b/systems/controllers/c3/lcs_factory_system.cc @@ -110,8 +110,7 @@ void LCSFactorySystem::OutputLCS(const drake::systems::Context& context, throw std::runtime_error("unknown or unsupported contact model"); } - double scale; - std::tie(*output_lcs, scale) = LCSFactory::LinearizePlantToLCS( + *output_lcs = LCSFactory::LinearizePlantToLCS( plant_, context_, plant_ad_, context_ad_, contact_pairs_, c3_options_.num_friction_directions, c3_options_.mu, c3_options_.dt, c3_options_.N, contact_model); diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index e4a9f8cf96..b13a899f06 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -149,10 +149,10 @@ C3Controller::C3Controller( } LCS C3Controller::CreatePlaceholderLCS() const { - MatrixXd A = MatrixXd::Zero(n_x_, n_x_); + MatrixXd A = MatrixXd::Ones(n_x_, n_x_); MatrixXd B = MatrixXd::Zero(n_x_, n_u_); VectorXd d = VectorXd::Zero(n_x_); - MatrixXd D = MatrixXd::Zero(n_x_, n_lambda_); + MatrixXd D = MatrixXd::Ones(n_x_, n_lambda_); MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); From 1f650eeb4cb49ac578b9d44070f308e8ebdb2d34 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 29 Apr 2024 17:34:26 -0400 Subject: [PATCH 700/758] fixing bug in scaling visualization --- solvers/c3.cc | 6 ++++-- solvers/c3.h | 2 +- 2 files changed, 5 insertions(+), 3 deletions(-) diff --git a/solvers/c3.cc b/solvers/c3.cc index 2ed47815e0..2e6150f730 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -95,7 +95,7 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, auto Dn = D_.at(0).squaredNorm(); auto An = A_.at(0).squaredNorm(); - double AnDn_ = An / Dn; + AnDn_ = An / Dn; for (int i = 0 ; i < N_; ++i){ D_.at(i) *= AnDn_; @@ -182,7 +182,7 @@ void C3::UpdateLCS(const LCS& lcs) { auto Dn = D_[0].squaredNorm(); auto An = A_[0].squaredNorm(); - double AnDn_ = An / Dn; + AnDn_ = An / Dn; for (int i = 0 ; i < N_; ++i){ D_.at(i) *= AnDn_; @@ -244,8 +244,10 @@ void C3::Solve(const VectorXd& x0) { *w_sol_ = w; *delta_sol_ = delta; } + for (int i = 0; i < N_; ++i){ lambda_sol_->at(i) *= AnDn_; + z_sol_->at(i).segment(n_, m_) *= AnDn_; } } diff --git a/solvers/c3.h b/solvers/c3.h index 42b54641fa..576d3059c4 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -130,7 +130,7 @@ class C3 { std::vector F_; std::vector H_; std::vector c_; - double AnDn_; + double AnDn_ = 1.0; const std::vector Q_; const std::vector R_; const std::vector U_; From 2fdb93dc1f71e1d3eba35e0ec3772d8027dbee6d Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 30 Apr 2024 11:30:28 -0400 Subject: [PATCH 701/758] minor chagnes to scaling --- .../franka_c3_options_supports.yaml | 8 ++--- solvers/c3.cc | 32 +++++++++++++------ solvers/c3.h | 3 +- 3 files changed, 29 insertions(+), 14 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 40b26fc13d..037ab2bcde 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -14,7 +14,7 @@ end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible publish_frequency : 0 -#publish_frequency: 25 +#publish_frequency: 15 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], @@ -39,7 +39,7 @@ gamma: 1.0 # discount factor on MPC costs w_Q: 50 w_R: 50 #Penalty on all decision variables, assuming scalar -w_G: 0.1 +w_G: 0.15 #Penalty on all decision variables, assuming scalar w_U: 0.1 @@ -54,7 +54,7 @@ g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] g_lambda_n: [1, 1, 1, 1, 1, 1, 1] g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +g_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] g_u: [1, 1, 1] #Penalty on matching the QP variables @@ -62,5 +62,5 @@ u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] -u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] +u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] u_u: [30, 30, 30] \ No newline at end of file diff --git a/solvers/c3.cc b/solvers/c3.cc index 2e6150f730..7a3d650470 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -93,8 +93,8 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, } } - auto Dn = D_.at(0).squaredNorm(); - auto An = A_.at(0).squaredNorm(); + auto Dn = D_.at(0).norm(); + auto An = A_.at(0).norm(); AnDn_ = An / Dn; for (int i = 0 ; i < N_; ++i){ @@ -175,13 +175,14 @@ void C3::UpdateLCS(const LCS& lcs) { F_ = lcs.F_; H_ = lcs.H_; c_ = lcs.c_; + dt_ = lcs.dt_; h_is_zero_ = H_[0].isZero(0); MatrixXd LinEq = MatrixXd::Zero(n_, 2 * n_ + m_ + k_); LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); - auto Dn = D_[0].squaredNorm(); - auto An = A_[0].squaredNorm(); + auto Dn = D_[0].norm(); + auto An = A_[0].norm(); AnDn_ = An / Dn; for (int i = 0 ; i < N_; ++i){ @@ -209,6 +210,9 @@ void C3::UpdateTarget(const std::vector& x_des) { } void C3::Solve(const VectorXd& x0) { + auto start = std::chrono::high_resolution_clock::now(); + + VectorXd delta_init = VectorXd::Zero(n_ + m_ + k_); if (options_.delta_option == 1){ delta_init.head(n_) = x0; @@ -249,6 +253,12 @@ void C3::Solve(const VectorXd& x0) { lambda_sol_->at(i) *= AnDn_; z_sol_->at(i).segment(n_, m_) *= AnDn_; } + + auto finish = std::chrono::high_resolution_clock::now(); + auto elapsed = finish - start; + solve_time_ = + std::chrono::duration_cast(elapsed).count() / + 1e6; } void C3::ADMMStep(const VectorXd& x0, vector* delta, @@ -322,13 +332,17 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, // /// initialize decision variables to warm start if (warm_start_) { - prog_.SetInitialGuess(x_[0], x0); + int index = solve_time_ / dt_; + double weight = (solve_time_ - index * dt_) / dt_; for (int i = 0; i < N_ - 1; i++) { - prog_.SetInitialGuess(x_[i], warm_start_x_[admm_iteration][i + 1]); - prog_.SetInitialGuess(lambda_[i], - warm_start_lambda_[admm_iteration][i + 1]); - prog_.SetInitialGuess(u_[i], warm_start_u_[admm_iteration][i + 1]); + prog_.SetInitialGuess(x_[i], (1 - weight) * warm_start_x_[admm_iteration][i] + weight * warm_start_x_[admm_iteration][i + 1]); + prog_.SetInitialGuess(lambda_[i], (1 - weight) * warm_start_lambda_[admm_iteration][i] + weight * warm_start_lambda_[admm_iteration][i + 1]); + prog_.SetInitialGuess(u_[i], (1 - weight) * warm_start_u_[admm_iteration][i] + weight * warm_start_u_[admm_iteration][i + 1]); +// prog_.SetInitialGuess(lambda_[i], +// warm_start_lambda_[admm_iteration][i + 1]); +// prog_.SetInitialGuess(u_[i], warm_start_u_[admm_iteration][i + 1]); } + prog_.SetInitialGuess(x_[0], x0); prog_.SetInitialGuess(x_[N_], warm_start_x_[admm_iteration][N_]); } diff --git a/solvers/c3.h b/solvers/c3.h index 576d3059c4..ddbed73bee 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -137,7 +137,8 @@ class C3 { const std::vector G_; std::vector x_desired_; const C3Options options_; - + double dt_ = 0; + double solve_time_ = 0; bool h_is_zero_; drake::solvers::MathematicalProgram prog_; From 7697f9fdc936737c58c2f95cbadf050e1068d161 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 May 2024 13:05:08 -0400 Subject: [PATCH 702/758] outputting c3 debug information --- .../analysis/franka_plotting_utils.py | 1 - .../pydairlib/analysis/log_plotter_franka.py | 21 ++-------------- .../pydairlib/analysis/mbp_plotting_utils.py | 3 ++- lcmtypes/lcmt_c3_intermediates.lcm | 1 + solvers/c3.cc | 4 +-- solvers/c3.h | 5 ++-- solvers/c3_output.cc | 8 +++++- solvers/c3_output.h | 3 +-- solvers/lcs_factory.cc | 3 --- systems/controllers/c3_controller.cc | 13 +++++----- systems/robot_lcm_systems.cc | 25 ++++++++++--------- systems/robot_lcm_systems.h | 5 ++-- 12 files changed, 41 insertions(+), 51 deletions(-) diff --git a/bindings/pydairlib/analysis/franka_plotting_utils.py b/bindings/pydairlib/analysis/franka_plotting_utils.py index cd154c9b82..e9c6cb8b86 100644 --- a/bindings/pydairlib/analysis/franka_plotting_utils.py +++ b/bindings/pydairlib/analysis/franka_plotting_utils.py @@ -28,7 +28,6 @@ 'FRANKA_INPUT_ECHO': dairlib.lcmt_robot_input, 'C3_TRAJECTORY_ACTOR': dairlib.lcmt_timestamped_saved_traj, 'C3_TRAJECTORY_TRAY': dairlib.lcmt_timestamped_saved_traj, - 'C3_DEBUG': dairlib.lcmt_c3_output, 'C3_ACTUAL': dairlib.lcmt_c3_state, 'C3_TARGET': dairlib.lcmt_c3_state, 'OSC_DEBUG_FRANKA': dairlib.lcmt_osc_output, diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 8d16268804..8652f38a78 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -64,8 +64,8 @@ def main(): c3_output, c3_tracking_target, c3_tracking_actual = get_log_data(log, default_channels, plot_config.start_time, plot_config.duration, mbp_plots.load_c3_debug, True, channel_c3, channel_c3_target, channel_c3_actual) - solve_times = np.diff(c3_output['t'], prepend=[c3_output['t'][0]]) - print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_output['t']))) + solve_times = np.diff(c3_tracking_target['t'], prepend=[c3_tracking_target['t'][0]]) + print('Average C3 frequency: ', 1 / np.mean(np.diff(c3_tracking_target['t']))) # processing callback arguments @@ -100,23 +100,6 @@ def main(): plot_config.pos_names, t_x_slice, pos_map) - # import pdb; pdb.set_trace() - if plot_config.plot_c3_debug: - # t_c3_slice = slice(c3_output['t'].size) - # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 0) - - t_c3_slice = slice(c3_output['t'].size) - plot = mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 1) - plot.axes[0].axhline(y=8.06, color='r', linestyle='-') - plot.axes[0].axhline(y=-8.06, color='r', linestyle='-') - # plot.save_fig('c3_inputs_' + filename.split('/')[-1]) - - - - - # t_c3_slice = slice(c3_output['t'].size) - # mbp_plots.plot_c3_inputs(c3_output, t_c3_slice, 2) - if plot_config.plot_c3_tracking: # plot = plot_styler.PlotStyler(nrows=2) plot = plot_styler.PlotStyler() diff --git a/bindings/pydairlib/analysis/mbp_plotting_utils.py b/bindings/pydairlib/analysis/mbp_plotting_utils.py index 2efc871712..718ec8707b 100644 --- a/bindings/pydairlib/analysis/mbp_plotting_utils.py +++ b/bindings/pydairlib/analysis/mbp_plotting_utils.py @@ -355,7 +355,8 @@ def load_force_channels(data, contact_force_channel): return contact_info def load_c3_debug(data, c3_debug_channel, c3_target_channel, c3_actual_channel): - c3_debug = process_c3_debug(data[c3_debug_channel]) + # c3_debug = process_c3_debug(data[c3_debug_channel]) + c3_debug = None c3_tracking_target = process_c3_tracking(data[c3_target_channel]) c3_tracking_actual = process_c3_tracking(data[c3_actual_channel]) return c3_debug, c3_tracking_target, c3_tracking_actual diff --git a/lcmtypes/lcmt_c3_intermediates.lcm b/lcmtypes/lcmt_c3_intermediates.lcm index 684e2e10e7..c709decfb9 100644 --- a/lcmtypes/lcmt_c3_intermediates.lcm +++ b/lcmtypes/lcmt_c3_intermediates.lcm @@ -6,6 +6,7 @@ struct lcmt_c3_intermediates int32_t num_total_variables; float time_vec[num_points]; + float z_sol[num_total_variables][num_points]; float delta_sol[num_total_variables][num_points]; float w_sol[num_total_variables][num_points]; } \ No newline at end of file diff --git a/solvers/c3.cc b/solvers/c3.cc index 7a3d650470..5800b35a5e 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -245,9 +245,9 @@ void C3::Solve(const VectorXd& x0) { A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); } - *w_sol_ = w; - *delta_sol_ = delta; } + *w_sol_ = w; + *delta_sol_ = delta; for (int i = 0; i < N_; ++i){ lambda_sol_->at(i) *= AnDn_; diff --git a/solvers/c3.h b/solvers/c3.h index ddbed73bee..593980b041 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -157,12 +157,13 @@ class C3 { // Solutions - std::unique_ptr> z_sol_; std::unique_ptr> x_sol_; std::unique_ptr> lambda_sol_; std::unique_ptr> u_sol_; - std::unique_ptr> w_sol_; + + std::unique_ptr> z_sol_; std::unique_ptr> delta_sol_; + std::unique_ptr> w_sol_; }; } // namespace solvers diff --git a/solvers/c3_output.cc b/solvers/c3_output.cc index d7b71f2027..2f68be4b3d 100644 --- a/solvers/c3_output.cc +++ b/solvers/c3_output.cc @@ -35,6 +35,8 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { c3_intermediates.num_total_variables = c3_intermediates_.delta_.rows(); c3_intermediates.num_points = c3_solution.num_points; c3_intermediates.time_vec.reserve(c3_intermediates.num_points); + c3_intermediates.z_sol = vector>( + c3_intermediates.num_total_variables, vector(knot_points)); c3_intermediates.delta_sol = vector>( c3_intermediates.num_total_variables, vector(knot_points)); c3_intermediates.w_sol = vector>( @@ -57,8 +59,11 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { sizeof(float) * knot_points); } for (int i = 0; i < c3_intermediates.num_total_variables; ++i) { + VectorXf temp_z_row = c3_intermediates_.z_.row(i); VectorXf temp_delta_row = c3_intermediates_.delta_.row(i); VectorXf temp_w_row = c3_intermediates_.w_.row(i); + memcpy(c3_intermediates.z_sol[i].data(), temp_z_row.data(), + sizeof(float) * knot_points); memcpy(c3_intermediates.delta_sol[i].data(), temp_delta_row.data(), sizeof(float) * knot_points); memcpy(c3_intermediates.w_sol[i].data(), temp_w_row.data(), @@ -67,7 +72,8 @@ lcmt_c3_output C3Output::GenerateLcmObject(double time) const { c3_output.c3_solution = c3_solution; // Not assigning to reduce space - c3_output.c3_intermediates = lcmt_c3_intermediates(); +// c3_output.c3_intermediates = lcmt_c3_intermediates(); + c3_output.c3_intermediates = c3_intermediates; return c3_output; } diff --git a/solvers/c3_output.h b/solvers/c3_output.h index 1325ef458e..6e4f574211 100644 --- a/solvers/c3_output.h +++ b/solvers/c3_output.h @@ -27,11 +27,10 @@ class C3Output { struct C3Intermediates { C3Intermediates() = default; -// C3Intermediates(Eigen::VectorXd time_vector_, Eigen::MatrixXd delta_, -// Eigen::MatrixXd w_); // Shape is (variable_vector_size, knot_points) Eigen::VectorXf time_vector_; + Eigen::MatrixXf z_; Eigen::MatrixXf delta_; Eigen::MatrixXf w_; }; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index a4eb5cd227..273af3ccc0 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -200,9 +200,6 @@ LCS LCSFactory::LinearizePlantToLCS( H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = dt * J_t * AB_v_u; - // TODO(yangwill): check gap function to make sure it makes sense. Potential - // source of uncertainty - // std::cout << "phi: " << phi << std::endl; c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v - J_n * vNqdot * plant.GetPositions(context); c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = J_t * dt * d_v; diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index b13a899f06..066527089e 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -1,8 +1,6 @@ #include "c3_controller.h" +#include -#include - -#include "multibody/multibody_utils.h" #include "solvers/c3_miqp.h" #include "solvers/c3_qp.h" #include "solvers/lcs_factory.h" @@ -124,8 +122,9 @@ C3Controller::C3Controller( c3_solution.u_sol_ = MatrixXf::Zero(n_u_, N_); c3_solution.time_vector_ = VectorXf::Zero(N_); auto c3_intermediates = C3Output::C3Intermediates(); - c3_intermediates.w_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.z_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); c3_intermediates.delta_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.w_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); c3_intermediates.time_vector_ = VectorXf::Zero(N_); c3_solution_port_ = this->DeclareAbstractOutputPort("c3_solution", c3_solution, @@ -263,13 +262,15 @@ void C3Controller::OutputC3Intermediates( C3Output::C3Intermediates* c3_intermediates) const { double solve_time = context.get_discrete_state(filtered_solve_time_index_)[0]; double t = context.get_discrete_state(plan_start_time_index_)[0] + solve_time; + auto z = c3_->GetFullSolution(); auto delta = c3_->GetDualDeltaSolution(); auto w = c3_->GetDualWSolution(); for (int i = 0; i < N_; i++) { c3_intermediates->time_vector_(i) = solve_time + t + i * dt_; - c3_intermediates->w_.col(i) = delta[i].cast(); - c3_intermediates->delta_.col(i) = w[i].cast(); + c3_intermediates->z_.col(i) = z[i].cast(); + c3_intermediates->delta_.col(i) = delta[i].cast(); + c3_intermediates->w_.col(i) = w[i].cast(); } } diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index b0ea900ed8..b9371c0072 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -15,8 +15,8 @@ namespace systems { using drake::multibody::JointActuatorIndex; using drake::multibody::JointIndex; using drake::multibody::MultibodyPlant; -using drake::systems::Context; using drake::systems::BasicVector; +using drake::systems::Context; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; using Eigen::VectorXd; @@ -208,8 +208,7 @@ RobotOutputSender::RobotOutputSender( const drake::multibody::MultibodyPlant& plant, drake::multibody::ModelInstanceIndex model_instance, const bool publish_efforts, const bool publish_imu) - : publish_efforts_(publish_efforts), - publish_imu_(publish_imu) { + : publish_efforts_(publish_efforts), publish_imu_(publish_imu) { num_positions_ = plant.num_positions(model_instance); num_velocities_ = plant.num_velocities(model_instance); num_efforts_ = plant.num_actuators(); @@ -342,7 +341,7 @@ ObjectStateReceiver::ObjectStateReceiver( this->DeclareVectorOutputPort( "x, t", StateVector(plant.num_positions(model_instance), - plant.num_velocities(model_instance)), + plant.num_velocities(model_instance)), &ObjectStateReceiver::CopyOutput); } @@ -418,7 +417,7 @@ void ObjectStateReceiver::InitializeSubscriberPositions( /*--------------------------------------------------------------------------*/ // methods implementation for RobotOutputSender. ObjectStateSender::ObjectStateSender( - const drake::multibody::MultibodyPlant& plant){ + const drake::multibody::MultibodyPlant& plant) { num_positions_ = plant.num_positions(); num_velocities_ = plant.num_velocities(); @@ -445,8 +444,9 @@ ObjectStateSender::ObjectStateSender( ObjectStateSender::ObjectStateSender( const drake::multibody::MultibodyPlant& plant, + bool publish_velocities, drake::multibody::ModelInstanceIndex model_instance) - : model_instance_(model_instance){ + : publish_velocities_(publish_velocities), model_instance_(model_instance) { num_positions_ = plant.num_positions(model_instance); num_velocities_ = plant.num_velocities(model_instance); @@ -462,11 +462,10 @@ ObjectStateSender::ObjectStateSender( plant.get_joint(plant.GetJointIndices(model_instance).front()) .velocity_start(); - ordered_position_names_ = - multibody::ExtractOrderedNamesFromMap(position_index_map_, positions_start_idx_); - ordered_velocity_names_ = - multibody::ExtractOrderedNamesFromMap(velocity_index_map_, velocities_start_idx_); - + ordered_position_names_ = multibody::ExtractOrderedNamesFromMap( + position_index_map_, positions_start_idx_); + ordered_velocity_names_ = multibody::ExtractOrderedNamesFromMap( + velocity_index_map_, velocities_start_idx_); state_input_port_ = this->DeclareVectorInputPort( @@ -501,8 +500,10 @@ void ObjectStateSender::Output(const Context& context, } } for (int i = 0; i < num_velocities_; i++) { -// state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); state_msg->velocity[i] = 0; + if (publish_velocities_) { + state_msg->velocity[i] = state->GetAtIndex(num_positions_ + i); + } state_msg->velocity_names[i] = ordered_velocity_names_[i]; } } diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 244633a89c..7938d08d84 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -145,7 +145,7 @@ class ObjectStateReceiver : public drake::systems::LeafSystem { class ObjectStateSender : public drake::systems::LeafSystem { public: explicit ObjectStateSender( - const drake::multibody::MultibodyPlant& plant, + const drake::multibody::MultibodyPlant& plant, bool publish_velocities = true, drake::multibody::ModelInstanceIndex model_instance_index = drake::multibody::default_model_instance()); @@ -169,7 +169,8 @@ class ObjectStateSender : public drake::systems::LeafSystem { std::vector ordered_velocity_names_; std::map position_index_map_; std::map velocity_index_map_; - int state_input_port_ = -1; + drake::systems::InputPortIndex state_input_port_; + bool publish_velocities_; }; /// Receives the output of an LcmSubscriberSystem that subscribes to the From e6bfc360454dcf8a6682437de2d36e91b889c58d Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 2 May 2024 13:05:22 -0400 Subject: [PATCH 703/758] adding flag to publish object velocities --- examples/franka/franka_c3_controller.cc | 2 -- examples/franka/franka_sim.cc | 5 +++-- examples/franka/parameters/franka_sim_params.h | 2 ++ examples/franka/parameters/franka_sim_params.yaml | 1 + 4 files changed, 6 insertions(+), 4 deletions(-) diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 1949c196ae..0e09e936ca 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -3,14 +3,12 @@ #include #include #include -#include #include #include #include #include #include -#include "common/eigen_utils.h" #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index 0598a7c022..aed024062e 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -28,6 +28,7 @@ #include "multibody/multibody_utils.h" #include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" namespace dairlib { @@ -149,13 +150,13 @@ int DoMain(int argc, char* argv[]) { lcm_channel_params.franka_state_channel, sim_params.franka_publish_rate, franka_index, sim_params.publish_efforts, sim_params.actuator_delay); auto tray_state_sender = - builder.AddSystem(plant, tray_index); + builder.AddSystem(plant, sim_params.publish_object_velocities, tray_index); auto tray_state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.tray_state_channel, lcm, 1.0 / sim_params.tray_publish_rate)); auto object_state_sender = - builder.AddSystem(plant, object_index); + builder.AddSystem(plant, sim_params.publish_object_velocities, object_index); auto object_state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.object_state_channel, lcm, diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 653ff7b5c5..2441c5ce70 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -20,6 +20,7 @@ struct FrankaSimParams { int scene_index; bool visualize_drake_sim; bool publish_efforts; + bool publish_object_velocities; Eigen::VectorXd q_init_franka; std::vector q_init_plate; @@ -58,6 +59,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(scene_index)); a->Visit(DRAKE_NVP(visualize_drake_sim)); a->Visit(DRAKE_NVP(publish_efforts)); + a->Visit(DRAKE_NVP(publish_object_velocities)); a->Visit(DRAKE_NVP(q_init_franka)); a->Visit(DRAKE_NVP(q_init_plate)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index bd6ea15fd7..4e56b6294c 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -11,6 +11,7 @@ actuator_delay: 0.000 scene_index: 1 visualize_drake_sim: true publish_efforts: true +publish_object_velocities: true tool_attachment_frame: [0, 0, 0.107] From 6dcc3c4af33c1599b95c2cc45a5556df548c9804 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Thu, 2 May 2024 22:27:23 -0400 Subject: [PATCH 704/758] adding bridge to use drake lcm driver --- examples/franka/BUILD.bazel | 22 ++++ examples/franka/franka_driver_bridge.cc | 117 ++++++++++++++++++ .../franka_drake_lcm_driver_channels.h | 15 +++ .../franka_drake_lcm_driver_channels.yaml | 2 + examples/franka/systems/BUILD.bazel | 16 +++ .../franka/systems/franka_state_translator.cc | 78 ++++++++++++ .../franka/systems/franka_state_translator.h | 60 +++++++++ 7 files changed, 310 insertions(+) create mode 100644 examples/franka/franka_driver_bridge.cc create mode 100644 examples/franka/parameters/franka_drake_lcm_driver_channels.h create mode 100644 examples/franka/parameters/franka_drake_lcm_driver_channels.yaml create mode 100644 examples/franka/systems/franka_state_translator.cc create mode 100644 examples/franka/systems/franka_state_translator.h diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index bda08c180f..8352dbf5b2 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -172,6 +172,27 @@ cc_binary( ], ) +cc_binary( + name = "franka_driver_bridge", + srcs = ["franka_driver_bridge.cc"], + data = [ + ":urdfs", + "@drake_models//:franka_description", + ], + deps = [ + ":parameters", + "//common", + "//multibody:utils", + "//examples/franka/systems:franka_state_translator", + "//systems:robot_lcm_systems", + "//systems/framework:lcm_driven_loop", + "//systems:system_utils", + "//systems/primitives", + "@drake//:drake_shared_library", + "@gflags", + ], +) + cc_binary( name = "franka_ros_lcm_bridge", srcs = ["franka_ros_lcm_bridge.cc"], @@ -226,6 +247,7 @@ cc_library( "parameters/franka_lcm_channels.h", "parameters/franka_osc_controller_params.h", "parameters/franka_sim_params.h", + "parameters/franka_drake_lcm_driver_channels.h", "parameters/franka_sim_scene_params.h", ], data = glob([ diff --git a/examples/franka/franka_driver_bridge.cc b/examples/franka/franka_driver_bridge.cc new file mode 100644 index 0000000000..74a996cb1b --- /dev/null +++ b/examples/franka/franka_driver_bridge.cc @@ -0,0 +1,117 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "examples/franka/parameters/franka_drake_lcm_driver_channels.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/systems/franka_state_translator.h" +#include "multibody/multibody_utils.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +using drake::math::RigidTransform; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using dairlib::systems::RobotInputReceiver; +using dairlib::systems::RobotOutputSender; +using dairlib::systems::SubvectorPassThrough; +using dairlib::systems::TimestampedVector; + +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_hardware.yaml", + "Filepath containing lcm channels"); +DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_driver_channels.yaml", + "Filepath containing ROS channels"); + +namespace dairlib { + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + FrankaDrakeLcmDriverChannels franka_driver_channel_params = + drake::yaml::LoadYamlFile(FLAGS_franka_driver_channels); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + + DiagramBuilder builder; + + MultibodyPlant plant(0.0); + + Parser parser(&plant); + parser.AddModelsFromUrl(sim_params.franka_model)[0]; + Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); + plant.Finalize(); + + auto pos_map = multibody::MakeNameToPositionsMap(plant); + auto vel_map = multibody::MakeNameToVelocitiesMap(plant); + auto act_map = multibody::MakeNameToActuatorsMap(plant); + + auto pos_names = multibody::ExtractOrderedNamesFromMap(pos_map); + auto vel_names = multibody::ExtractOrderedNamesFromMap(vel_map); + auto act_names = multibody::ExtractOrderedNamesFromMap(act_map); + + /* -------------------------------------------------------------------------------------------*/ + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto franka_status_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + franka_driver_channel_params.franka_status_channel, &lcm)); + auto franka_command_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.franka_input_channel, &lcm)); + auto franka_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_state_channel, &lcm, + 1.0 / 1000.0)); + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + franka_driver_channel_params.franka_command_channel, &lcm, + 1.0 / 1000.0)); + auto franka_state_translator = builder.AddSystem( + pos_names, vel_names, act_names); +auto franka_command_translator = builder.AddSystem(); + + builder.Connect(*franka_status_sub, *franka_state_translator); + builder.Connect(*franka_state_translator, *franka_state_pub); + builder.Connect(*franka_command_sub, *franka_command_translator); + builder.Connect(*franka_command_translator, *franka_command_pub); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_lcm_ros_bridge")); + const auto& diagram = *owned_diagram; + + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_status_sub, + franka_driver_channel_params.franka_status_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/parameters/franka_drake_lcm_driver_channels.h b/examples/franka/parameters/franka_drake_lcm_driver_channels.h new file mode 100644 index 0000000000..eaa7d3ee08 --- /dev/null +++ b/examples/franka/parameters/franka_drake_lcm_driver_channels.h @@ -0,0 +1,15 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + + +struct FrankaDrakeLcmDriverChannels { + std::string franka_status_channel; + std::string franka_command_channel; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(franka_status_channel)); + a->Visit(DRAKE_NVP(franka_command_channel)); + } +}; \ No newline at end of file diff --git a/examples/franka/parameters/franka_drake_lcm_driver_channels.yaml b/examples/franka/parameters/franka_drake_lcm_driver_channels.yaml new file mode 100644 index 0000000000..55cc785c3b --- /dev/null +++ b/examples/franka/parameters/franka_drake_lcm_driver_channels.yaml @@ -0,0 +1,2 @@ +franka_status_channel: PANDA_STATUS # lcmt_panda_status +franka_command_channel: PANDA_COMMAND # lcmt_panda_command diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 6ffa7b38f8..77cef8a42f 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -11,6 +11,7 @@ cc_library( ":end_effector_trajectory", ":external_force_generator", ":franka_kinematics", + ":franka_state_translator", ":plate_balancing_target", ], ) @@ -117,6 +118,21 @@ cc_library( ], ) +cc_library( + name = "franka_state_translator", + srcs = [ + "franka_state_translator.cc", + ], + hdrs = [ + "franka_state_translator.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "franka_kinematics", srcs = ["franka_kinematics.cc"], diff --git a/examples/franka/systems/franka_state_translator.cc b/examples/franka/systems/franka_state_translator.cc new file mode 100644 index 0000000000..7698de6c44 --- /dev/null +++ b/examples/franka/systems/franka_state_translator.cc @@ -0,0 +1,78 @@ +#include "examples/franka/systems/franka_state_translator.h" + +#include + +#include "lcmtypes/drake/lcmt_panda_status.hpp" +#include "systems/framework/output_vector.h" + +namespace dairlib { + +using drake::systems::BasicVector; +using drake::systems::Context; +using systems::TimestampedVector; + +namespace systems { + +FrankaStateOutTranslator::FrankaStateOutTranslator( + std::vector joint_position_names, + std::vector joint_velocity_names, + std::vector joint_actuator_names) { + this->set_name("franka_state_translator"); + + panda_status_ = + this->DeclareAbstractInputPort("franka_state", + drake::Value()) + .get_index(); + DRAKE_DEMAND(joint_position_names.size() == kNumFrankaJoints); + DRAKE_DEMAND(joint_velocity_names.size() == kNumFrankaJoints); + DRAKE_DEMAND(joint_actuator_names.size() == kNumFrankaJoints); + auto default_robot_output_msg = dairlib::lcmt_robot_output(); + default_robot_output_msg.position_names = joint_position_names; + default_robot_output_msg.velocity_names = joint_velocity_names; + default_robot_output_msg.effort_names = joint_actuator_names; + state_output_ = this->DeclareAbstractOutputPort( + "lcmt_robot_output", default_robot_output_msg, + &FrankaStateOutTranslator::OutputFrankaState) + .get_index(); +} + +void FrankaStateOutTranslator::OutputFrankaState( + const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const { + const auto& panda_status = + this->EvalInputValue(context, panda_status_); + output->utime = panda_status->utime; + output->position = panda_status->joint_position; + output->velocity = panda_status->joint_velocity; + output->effort = panda_status->joint_torque; +} + +FrankaEffortsInTranslator::FrankaEffortsInTranslator() { + this->set_name("franka_state_translator"); + + robot_input_ = + this->DeclareAbstractInputPort("franka_state", + drake::Value()) + .get_index(); + + franka_command_output_ = + this->DeclareAbstractOutputPort( + "lcmt_robot_output", + &FrankaEffortsInTranslator::OutputFrankaCommand) + .get_index(); +} + +void FrankaEffortsInTranslator::OutputFrankaCommand( + const drake::systems::Context& context, + drake::lcmt_panda_command* output) const { + const auto& robot_input = + this->EvalInputValue(context, robot_input_); + DRAKE_DEMAND(robot_input->efforts.size() == kNumFrankaJoints); + output->utime = robot_input->utime; + output->num_joint_torque = robot_input->efforts.size(); + output->joint_torque = robot_input->efforts; + output->control_mode_expected = drake::lcmt_panda_status::CONTROL_MODE_TORQUE; +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/franka/systems/franka_state_translator.h b/examples/franka/systems/franka_state_translator.h new file mode 100644 index 0000000000..f1a3bc8c39 --- /dev/null +++ b/examples/franka/systems/franka_state_translator.h @@ -0,0 +1,60 @@ +#pragma once + +#include +#include +#include +#include + +#include "common/find_resource.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +const static int kNumFrankaJoints = 7; + +class FrankaStateOutTranslator : public drake::systems::LeafSystem { + public: + explicit FrankaStateOutTranslator(std::vector joint_position_names, + std::vector joint_velocity_names, + std::vector joint_actuator_names); + + const drake::systems::InputPort& get_input_port_panda_status() const { + return this->get_input_port(panda_status_); + } + const drake::systems::OutputPort& get_output_port_robot_state() + const { + return this->get_output_port(state_output_); + } + + private: + void OutputFrankaState(const drake::systems::Context& context, + dairlib::lcmt_robot_output* output) const; + + drake::systems::InputPortIndex panda_status_; + drake::systems::OutputPortIndex state_output_; +}; + +class FrankaEffortsInTranslator : public drake::systems::LeafSystem { + public: + explicit FrankaEffortsInTranslator(); + + const drake::systems::InputPort& get_input_port_efforts() const { + return this->get_input_port(robot_input_); + } + const drake::systems::OutputPort& get_output_port_panda_command() + const { + return this->get_output_port(franka_command_output_); + } + + private: + void OutputFrankaCommand(const drake::systems::Context& context, + drake::lcmt_panda_command* output) const; + + drake::systems::InputPortIndex robot_input_; + drake::systems::OutputPortIndex franka_command_output_; +}; + +} // namespace systems +} // namespace dairlib From f2bb7ae727db7c732f8bd6cfb2f9e4faf4b22fdd Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 6 May 2024 14:38:23 -0400 Subject: [PATCH 705/758] minor cleanup --- examples/franka/BUILD.bazel | 6 ++--- .../franka/systems/end_effector_trajectory.h | 4 ---- solvers/c3.cc | 15 ------------ solvers/c3.h | 24 +++++++++---------- .../c3_output_systems.cc | 8 ------- tools/workspace/drake_models/repository.bzl | 8 +++---- tools/workspace/osqp/package.BUILD.bazel | 8 +++---- 7 files changed, 22 insertions(+), 51 deletions(-) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 8352dbf5b2..6fcf9b3461 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -182,11 +182,11 @@ cc_binary( deps = [ ":parameters", "//common", - "//multibody:utils", "//examples/franka/systems:franka_state_translator", + "//multibody:utils", "//systems:robot_lcm_systems", - "//systems/framework:lcm_driven_loop", "//systems:system_utils", + "//systems/framework:lcm_driven_loop", "//systems/primitives", "@drake//:drake_shared_library", "@gflags", @@ -244,10 +244,10 @@ cc_library( hdrs = [ "parameters/franka_c3_controller_params.h", "parameters/franka_c3_scene_params.h", + "parameters/franka_drake_lcm_driver_channels.h", "parameters/franka_lcm_channels.h", "parameters/franka_osc_controller_params.h", "parameters/franka_sim_params.h", - "parameters/franka_drake_lcm_driver_channels.h", "parameters/franka_sim_scene_params.h", ], data = glob([ diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_trajectory.h index 550e850d5b..f98c443cb8 100644 --- a/examples/franka/systems/end_effector_trajectory.h +++ b/examples/franka/systems/end_effector_trajectory.h @@ -22,10 +22,6 @@ class EndEffectorTrajectoryGenerator double z_scale); private: - drake::systems::EventStatus DiscreteVariableUpdate( - const drake::systems::Context& context, - drake::systems::DiscreteValues* discrete_state) const; - void CalcTraj(const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const; diff --git a/solvers/c3.cc b/solvers/c3.cc index 5800b35a5e..6f7e644877 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -338,9 +338,6 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, prog_.SetInitialGuess(x_[i], (1 - weight) * warm_start_x_[admm_iteration][i] + weight * warm_start_x_[admm_iteration][i + 1]); prog_.SetInitialGuess(lambda_[i], (1 - weight) * warm_start_lambda_[admm_iteration][i] + weight * warm_start_lambda_[admm_iteration][i + 1]); prog_.SetInitialGuess(u_[i], (1 - weight) * warm_start_u_[admm_iteration][i] + weight * warm_start_u_[admm_iteration][i + 1]); -// prog_.SetInitialGuess(lambda_[i], -// warm_start_lambda_[admm_iteration][i + 1]); -// prog_.SetInitialGuess(u_[i], warm_start_u_[admm_iteration][i + 1]); } prog_.SetInitialGuess(x_[0], x0); prog_.SetInitialGuess(x_[N_], warm_start_x_[admm_iteration][N_]); @@ -435,17 +432,5 @@ vector C3::SolveProjection(const vector& G, return deltaProj; } -std::vector C3::GetWarmStartX() const { - return warm_start_x_[0]; -} - -std::vector C3::GetWarmStartLambda() const { - return warm_start_lambda_[0]; -} - -std::vector C3::GetWarmStartU() const { - return warm_start_u_[0]; -} - } // namespace solvers } // namespace dairlib diff --git a/solvers/c3.h b/solvers/c3.h index 593980b041..4543b63339 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -49,8 +49,7 @@ class C3 { /// @param G A pointer to the G variables from previous step void ADMMStep(const Eigen::VectorXd& x0, std::vector* delta, std::vector* w, - std::vector* G, - int admm_iteration); + std::vector* G, int admm_iteration); /// Solve a single QP /// @param x0 The initial state of the system @@ -78,11 +77,6 @@ class C3 { /// allow user to remove all constraints void RemoveConstraints(); - /// Get QP warm start - std::vector GetWarmStartX() const; - std::vector GetWarmStartLambda() const; - std::vector GetWarmStartU() const; - /// Solve a single projection step /// @param E, F, H, c LCS parameters /// @param U A pointer to the U variables @@ -91,8 +85,7 @@ class C3 { const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, - const int admm_iteration, - const int& warm_start_index) = 0; + const int admm_iteration, const int& warm_start_index) = 0; void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { prog_.SetSolverOptions(options); @@ -142,21 +135,26 @@ class C3 { bool h_is_zero_; drake::solvers::MathematicalProgram prog_; + // QP step variables drake::solvers::OsqpSolver osqp_; std::vector x_; std::vector u_; std::vector lambda_; + // QP step constraints std::vector dynamics_constraints_; - std::vector target_cost_; - std::vector> costs_; - std::vector> input_costs_; std::vector> constraints_; std::vector> user_constraints_; - // Solutions + /// Projection step variables are defined outside of the MathematicalProgram + /// interface + std::vector target_cost_; + std::vector> costs_; + std::vector> input_costs_; + + // Solutions std::unique_ptr> x_sol_; std::unique_ptr> lambda_sol_; std::unique_ptr> u_sol_; diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index 40025496f2..d1807eb6ce 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -88,13 +88,5 @@ void C3OutputSender::OutputC3Forces( c3_forces_output->utime = context.get_time() * 1e6; } -// void C3OutputSender::OutputNextC3Input(const drake::systems::Context& -// context, -// drake::systems::BasicVector* u_next) const { -// const auto& c3_solution = -// this->EvalInputValue(context, c3_solution_port_); -// u_next->SetFromVector(c3_solution->u_sol_.col(0).cast()); -//} - } // namespace systems } // namespace dairlib \ No newline at end of file diff --git a/tools/workspace/drake_models/repository.bzl b/tools/workspace/drake_models/repository.bzl index f74b5299a8..1a991b5c2a 100644 --- a/tools/workspace/drake_models/repository.bzl +++ b/tools/workspace/drake_models/repository.bzl @@ -3,9 +3,9 @@ load("@drake//tools/workspace:github.bzl", "github_archive") def drake_models_repository( name, mirrors = {"github": [ - "https://github.com/{repository}/archive/refs/tags/{tag_name}.tar.gz", # noqa - "https://github.com/{repository}/archive/{commit_sha}.tar.gz", - ]}): + "https://github.com/{repository}/archive/refs/tags/{tag_name}.tar.gz", # noqa + "https://github.com/{repository}/archive/{commit_sha}.tar.gz", + ]}): github_archive( name = name, repository = "RobotLocomotion/models", @@ -13,4 +13,4 @@ def drake_models_repository( sha256 = "1107e8314e49102a247f2e87666cba8bd1e76527112ce01d849e299cf8010d94", # noqa build_file = ":package.BUILD.bazel", mirrors = mirrors, - ) \ No newline at end of file + ) diff --git a/tools/workspace/osqp/package.BUILD.bazel b/tools/workspace/osqp/package.BUILD.bazel index 9d40ac32b7..782deb213d 100644 --- a/tools/workspace/osqp/package.BUILD.bazel +++ b/tools/workspace/osqp/package.BUILD.bazel @@ -1,13 +1,13 @@ # -*- bazel -*- -load( - "@drake//tools/workspace:cmake_configure_file.bzl", - "cmake_configure_file", -) load( "@drake//tools/install:install.bzl", "install", ) +load( + "@drake//tools/workspace:cmake_configure_file.bzl", + "cmake_configure_file", +) licenses(["notice"]) # Apache-2.0 From 47b1d85bdd87efbe30745de970bacebaa7e8088a Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 7 May 2024 15:17:06 -0400 Subject: [PATCH 706/758] minor formatting and clean up along with dynamic camera tracking --- multibody/multipose_visualizer.h | 15 ++++--- solvers/c3_miqp.cc | 8 +--- solvers/lcs_factory.cc | 11 +++-- systems/controllers/c3_controller.h | 6 +-- systems/visualization/BUILD.bazel | 11 +++++ .../lcm_visualization_systems.cc | 28 ++++++------ .../visualization/lcm_visualization_systems.h | 4 +- .../visualization/meshcat_dynamic_camera.cc | 45 +++++++++++++++++++ .../visualization/meshcat_dynamic_camera.h | 38 ++++++++++++++++ 9 files changed, 126 insertions(+), 40 deletions(-) create mode 100644 systems/visualization/meshcat_dynamic_camera.cc create mode 100644 systems/visualization/meshcat_dynamic_camera.h diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index 5ae9feb9ac..a88fbb3ecd 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -3,8 +3,8 @@ #include #include -#include "drake/geometry/scene_graph.h" #include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/scene_graph.h" #include "drake/multibody/parsing/parser.h" #include "drake/multibody/plant/multibody_plant.h" #include "drake/systems/framework/diagram.h" @@ -45,18 +45,19 @@ class MultiposeVisualizer { /// @param alpha_scale Vector, of same length as num_poses. Provideas variable /// scaling of the transparency alpha field of all bodies, indexed by pose /// @param weld_frame_to_world Welds the frame of the given name to the world - /// @param meshcat Pointer to meshcat visualizer for option to attach to an existing meshcat instance - MultiposeVisualizer(std::string model_file, int num_poses, - const Eigen::VectorXd& alpha_scale, - std::string weld_frame_to_world = "", - std::shared_ptr meshcat = nullptr); + /// @param meshcat Pointer to meshcat visualizer for option to attach to an + /// existing meshcat instance + MultiposeVisualizer( + std::string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, + std::string weld_frame_to_world = "", + std::shared_ptr meshcat = nullptr); /// Draws the poses in the given (num_positions x num_poses) matrix /// Note: the matrix can have extra rows (e.g. velocities), which will be /// ignored. void DrawPoses(Eigen::MatrixXd poses); - const std::shared_ptr GetMeshcat(){ + const std::shared_ptr GetMeshcat() { return meshcat_; } diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 4e83b0b8db..1027c47f8d 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -38,12 +38,6 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, Mcons2 << MM1, MM2, MM3; GRBModel model = GRBModel(env_); - // model.set(GRB_IntParam_LogToConsole, 1); - // model.set(GRB_StringParam_LogFile, "grb_debug"); - // model.set("Cutoff", "0.001"); - // model.set("FeasibilityTol", "0.00001"); - // model.set("FeasibilityTol", "0.01"); - // model.set("IterationLimit", "40"); GRBVar delta_k[n_ + m_ + k_]; GRBVar binary[m_]; @@ -73,7 +67,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.setObjective(obj, GRB_MINIMIZE); - int M = 100000; // big M variable + int M = 1000; // big M variable double coeff[n_ + m_ + k_]; double coeff2[n_ + m_ + k_]; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 273af3ccc0..b85750a443 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -200,7 +200,8 @@ LCS LCSFactory::LinearizePlantToLCS( H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = dt * J_t * AB_v_u; - c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v - J_n * vNqdot * plant.GetPositions(context); + c.segment(n_contacts, n_contacts) = + phi + dt * dt * J_n * d_v - J_n * vNqdot * plant.GetPositions(context); c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = J_t * dt * d_v; } else if (contact_model == ContactModel::kAnitescu) { @@ -208,11 +209,9 @@ LCS LCSFactory::LinearizePlantToLCS( mu.data(), mu.size()); VectorXd anitescu_mu_vec = VectorXd::Zero(n_lambda); for (int i = 0; i < mu_vec.rows(); i++) { - double cur = mu_vec(i); - anitescu_mu_vec(4 * i) = cur; - anitescu_mu_vec(4 * i + 1) = cur; - anitescu_mu_vec(4 * i + 2) = cur; - anitescu_mu_vec(4 * i + 3) = cur; + anitescu_mu_vec.segment((2 * num_friction_directions) * i, + 2 * num_friction_directions) = + mu_vec(i) * VectorXd::Ones(2 * num_friction_directions); } MatrixXd anitescu_mu_matrix = anitescu_mu_vec.asDiagonal(); MatrixXd J_c = E_t.transpose() * J_n + anitescu_mu_matrix * J_t; diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3_controller.h index f9b17bb08d..e8131583eb 100644 --- a/systems/controllers/c3_controller.h +++ b/systems/controllers/c3_controller.h @@ -10,7 +10,6 @@ #include "dairlib/lcmt_timestamped_saved_traj.hpp" #include "lcm/lcm_trajectory.h" #include "solvers/c3.h" - #include "solvers/c3_options.h" #include "solvers/c3_output.h" #include "solvers/lcs.h" @@ -24,9 +23,8 @@ namespace systems { class C3Controller : public drake::systems::LeafSystem { public: - explicit C3Controller( - const drake::multibody::MultibodyPlant& plant, - C3Options c3_options); + explicit C3Controller(const drake::multibody::MultibodyPlant& plant, + C3Options c3_options); const drake::systems::InputPort& get_input_port_target() const { return this->get_input_port(target_input_port_); diff --git a/systems/visualization/BUILD.bazel b/systems/visualization/BUILD.bazel index 9efc58dce4..34d0ffcff7 100644 --- a/systems/visualization/BUILD.bazel +++ b/systems/visualization/BUILD.bazel @@ -19,3 +19,14 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "meshcat_dynamic_camera", + srcs = ["meshcat_dynamic_camera.cc"], + hdrs = ["meshcat_dynamic_camera.h"], + deps = [ + "//common", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index 14e43a1293..ba76ab6de8 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -360,17 +360,17 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( // TODO(yangwill): Clean up all this visualization, move to separate // visualization directory1 - meshcat_->SetObject(c3_target_tray_path_ + "/x-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_target_object_path_ + "/x-axis", cylinder_for_tray_, {1, 0, 0, 1}); - meshcat_->SetObject(c3_target_tray_path_ + "/y-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_target_object_path_ + "/y-axis", cylinder_for_tray_, {0, 1, 0, 1}); - meshcat_->SetObject(c3_target_tray_path_ + "/z-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_target_object_path_ + "/z-axis", cylinder_for_tray_, {0, 0, 1, 1}); - meshcat_->SetObject(c3_actual_tray_path_ + "/x-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_actual_object_path_ + "/x-axis", cylinder_for_tray_, {1, 0, 0, 1}); - meshcat_->SetObject(c3_actual_tray_path_ + "/y-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_actual_object_path_ + "/y-axis", cylinder_for_tray_, {0, 1, 0, 1}); - meshcat_->SetObject(c3_actual_tray_path_ + "/z-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_actual_object_path_ + "/z-axis", cylinder_for_tray_, {0, 0, 1, 1}); if (draw_ee_){ meshcat_->SetObject(c3_target_ee_path_ + "/x-axis", cylinder_for_ee_, @@ -404,12 +404,12 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( auto z_axis_transform_ee = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), 0.5 * Vector3d{0.0, 0.0, 0.05}); - meshcat_->SetTransform(c3_target_tray_path_ + "/x-axis", x_axis_transform); - meshcat_->SetTransform(c3_target_tray_path_ + "/y-axis", y_axis_transform); - meshcat_->SetTransform(c3_target_tray_path_ + "/z-axis", z_axis_transform); - meshcat_->SetTransform(c3_actual_tray_path_ + "/x-axis", x_axis_transform); - meshcat_->SetTransform(c3_actual_tray_path_ + "/y-axis", y_axis_transform); - meshcat_->SetTransform(c3_actual_tray_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_actual_object_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_actual_object_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_actual_object_path_ + "/z-axis", z_axis_transform); if (draw_ee_){ meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); @@ -448,14 +448,14 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( context, c3_state_actual_input_port_); if (draw_tray_) { meshcat_->SetTransform( - c3_target_tray_path_, + c3_target_object_path_, RigidTransformd( Eigen::Quaterniond(c3_target->state[3], c3_target->state[4], c3_target->state[5], c3_target->state[6]), Vector3d{c3_target->state[7], c3_target->state[8], c3_target->state[9]})); meshcat_->SetTransform( - c3_actual_tray_path_, + c3_actual_object_path_, RigidTransformd( Eigen::Quaterniond(c3_actual->state[3], c3_actual->state[4], c3_actual->state[5], c3_actual->state[6]), diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index 7d9a7854e9..aca1c8642e 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -171,8 +171,8 @@ class LcmC3TargetDrawer : public drake::systems::LeafSystem { const drake::geometry::Cylinder cylinder_for_ee_ = drake::geometry::Cylinder(0.0025, 0.05); const std::string c3_state_path_ = "c3_state"; - const std::string c3_target_tray_path_ = "c3_state/c3_target_tray"; - const std::string c3_actual_tray_path_ = "c3_state/c3_actual_tray"; + const std::string c3_target_object_path_ = "c3_state/c3_target_object"; + const std::string c3_actual_object_path_ = "c3_state/c3_actual_object"; const std::string c3_target_ee_path_ = "c3_state/c3_target_ee"; const std::string c3_actual_ee_path_ = "c3_state/c3_actual_ee"; }; diff --git a/systems/visualization/meshcat_dynamic_camera.cc b/systems/visualization/meshcat_dynamic_camera.cc new file mode 100644 index 0000000000..12570f6d18 --- /dev/null +++ b/systems/visualization/meshcat_dynamic_camera.cc @@ -0,0 +1,45 @@ +#include "systems/visualization/meshcat_dynamic_camera.h" + +#include + +#include "systems/framework/output_vector.h" + +namespace dairlib { +using systems::OutputVector; + +MeshcatDynamicCamera::MeshcatDynamicCamera( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* plant_context, + const std::shared_ptr& meshcat, + const drake::multibody::RigidBodyFrame& body_frame_to_track) + : plant_(plant), + plant_context_(plant_context), + body_frame_to_track_(body_frame_to_track), + meshcat_(meshcat) { + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(plant.num_positions(), + plant.num_velocities(), + plant.num_actuators())) + .get_index(); + DeclarePerStepDiscreteUpdateEvent(&MeshcatDynamicCamera::UpdateMeshcat); +} + +drake::systems::EventStatus MeshcatDynamicCamera::UpdateMeshcat( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const { + const OutputVector* robot_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + plant_.SetPositions(plant_context_, robot_output->GetPositions()); + Eigen::VectorXd q = robot_output->GetPositions(); + Eigen::VectorXd body_pos_in_world = Eigen::VectorXd::Zero(3); + plant_.CalcPointsPositions(*plant_context_, body_frame_to_track_, + Eigen::VectorXd::Zero(3), plant_.world_frame(), + &body_pos_in_world); + body_pos_in_world[2] = 0.8; + Eigen::VectorXd camera_pos_offset = Eigen::VectorXd::Zero(3); + camera_pos_offset << 0.1, 3.0, 0.5; + meshcat_->SetCameraPose(body_pos_in_world + camera_pos_offset, body_pos_in_world); + return drake::systems::EventStatus::Succeeded(); +} + +} // namespace dairlib \ No newline at end of file diff --git a/systems/visualization/meshcat_dynamic_camera.h b/systems/visualization/meshcat_dynamic_camera.h new file mode 100644 index 0000000000..8daeef7db5 --- /dev/null +++ b/systems/visualization/meshcat_dynamic_camera.h @@ -0,0 +1,38 @@ +#pragma once + +#include +#include + +#include "drake/multibody/plant/multibody_plant.h" + +namespace dairlib { + +/// Receives the output of an MPC planner as a lcmt_timestamped_saved_traj, +/// and draws it through meshcat. +class MeshcatDynamicCamera : public drake::systems::LeafSystem { + public: + explicit MeshcatDynamicCamera( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* plant_context, + const std::shared_ptr&, + const drake::multibody::RigidBodyFrame& body_frame_to_track); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + + private: + drake::systems::EventStatus UpdateMeshcat( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + drake::systems::InputPortIndex state_port_; + // Kinematic calculations + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* plant_context_; + const drake::multibody::RigidBodyFrame& body_frame_to_track_; + + std::shared_ptr meshcat_; +}; + +} // namespace dairlib \ No newline at end of file From d015b51d8a61f10df642db418c737bc47f103527 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 May 2024 12:01:55 -0400 Subject: [PATCH 707/758] adding example procman script and README for franka examples --- examples/franka/README.md | 60 +++++++++++++++++++++++++++++ examples/franka/franka_sim.pmd | 69 ++++++++++++++++++++++++++++++++++ 2 files changed, 129 insertions(+) create mode 100644 examples/franka/README.md create mode 100644 examples/franka/franka_sim.pmd diff --git a/examples/franka/README.md b/examples/franka/README.md new file mode 100644 index 0000000000..387dea710e --- /dev/null +++ b/examples/franka/README.md @@ -0,0 +1,60 @@ +## Experiment Instructions + + +## Simulated Robot + +1. Start the procman script containing a list of relevant processes +``` +bot-procman-sheriff -l franka_sim.pmd +``` + +2. In the procman window, start the operator processes (meshcat visualizer) using the script `script:start_operator_commands`. Scripts are located in the top bar of the procman window. + +3. The meshcat visualizer can be viewed by opening a browser and navigating to `localhost:7000` + +4. The examples with the C3 controller can be run using the script `script:c3_mpc`. Note, the task can be changed by changing the `scene_index` in the parameters. More details in [changing the scene](#changing-the-scene). This script spawns three processes: + - `bazel-bin/examples/franka/franka_sim`: Simulated environment which takes in torques commands from `franka_osc` and publishes the state of the system via LCM on various channels. + - `bazel-bin/examples/franka/franka_osc_controller`: Low-level task-space controller that tracks task-space trajectories it receives from the MPC + - `bazel-bin/examples/franka/franka_c3_controller`: Contact Implicit MPC controller that takes in the state of the system and publishes end effector trajectories to be tracked by the OSC. + +5. The simulator and controller can be stopped using the script `script:stop_controllers_and_simulators`. +6. A comparison using the sampling based MPC controllers from the [MJMPC controllers](https://github.com/google-deepmind/mujoco_mpc) can be run using `script:mjmpc_with_drake_sim`. This extracts out just the controller portion of the MJMPC code base and runs in on the identical task (scene 1) in the Drake simulator. Instructions to build and configure the standalone MJMPC controllers are a WIP. + +## Physical Robot + +Hardware experiment instructions are still listed for ROS and Ubuntu 20.04. Instructions for Ubuntu 22.04 are being worked on. + +1. Start the procman script containing a list of relevant processes. The primary differences from`franka_sim.pmd` script are the lcm_channels and the addition of a bridge linking ROS and LCM. +``` +bot-procman-sheriff -l franka_hardware.pmd +``` + +2. In the procman window, start the operator processes (meshcat visualizer and xbox controller) using the script `script:start_operator_commands`. Scripts are located in the top bar of the procman window. + +3. The meshcat visualizer can be viewed by opening a browser and navigating to `localhost:7000` + +4. The processes, except the C3 controller, can be run using the script `script:start_experiment`. This spawns the following processes: + - ROS/LCM bridge: communicates with FrankaRos to receive/publish franka state information and torque commands + - `bazel-bin/examples/franka/franka_osc_controller`: Low-level task-space controller that tracks task-space trajectories it receives from the MPC + - `start_logging.py`: Starts a lcm-logger with an automatic naming convention for the log number. + - `record_video.py`: Streams all available webcams to a .mp4 file corresponding to the log number. + +5. For safety, start the C3 controller separately after verifying the rest of the processes have started successfully, by manually starting the `franka_c3` process. +6. Using the xbox controller, switch from tracking the teleop commands to the MPC plan by pressing "A". +7. Stop the experiment using `script:stop_experiment` + + +## Changing the scene + +We currently have environment descriptions and gains for the following scenes: + +The scene can be changed by updating the `scene_index` parameter in BOTH `franka_sim_params.yaml` and `franka_c3_controller_params.yaml`. +The visualizer process must be restarted if changing the scene. + +| Scene Index | Description | +|-------------|-----------------------------------------------------------------------------------------------------------------------------------------------| +| 0 | No fixed environment features. For testing controlled sliding purely between the end effector and tray + optional objects. Gains still a WIP. | +| 1 | Primary RSS paper example with supports | +| 2 | Variation on RSS paper example with rotated supports | +| 3 | Additional rotating with wall task for RSS paper | + diff --git a/examples/franka/franka_sim.pmd b/examples/franka/franka_sim.pmd new file mode 100644 index 0000000000..f12f036d8d --- /dev/null +++ b/examples/franka/franka_sim.pmd @@ -0,0 +1,69 @@ +group "simulations" { + cmd "franka_sim" { + exec = "bazel-bin/examples/franka/franka_sim"; + host = "localhost"; + } + cmd "franka_kinematics" { + exec = "bazel-bin/examples/franka/forward_kinematics_for_lcs"; + host = "localhost"; + } +} + +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/franka/franka_visualizer"; + host = "localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/Cassie/cassie_xbox_remote"; + host = "localhost"; + } + cmd "start_logging" { + exec = "python3 start_logging.py sim"; + host = "localhost"; + } +} + +group "controllers" { + cmd "franka_osc" { + exec = "bazel-bin/examples/franka/franka_osc_controller"; + host = "localhost"; + } + cmd "franka_c3" { + exec = "bazel-bin/examples/franka/franka_c3_controller"; + host = "localhost"; + } + cmd "mujoco_mpc" { + exec = "../mujoco_mpc/build/bin/standalone_controller"; + host = "localhost"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "localhost"; + } +} + +script "c3_mpc" { + start cmd "franka_sim"; + start cmd "franka_osc"; + start cmd "franka_c3"; +} + +script "mjmpc_with_drake_sim" { + start cmd "franka_sim"; + start cmd "franka_osc"; + start cmd "mujoco_mpc"; + start cmd "franka_kinematics"; +} + +script "start_operator_commands" { + start cmd "visualizer"; +} + +script "stop_controllers_and_simulators" { + stop group "simulations"; + stop group "controllers"; +} From 1592909a36bf64b15931ebc491158a0c7eecc39d Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 8 May 2024 17:13:11 -0400 Subject: [PATCH 708/758] working on robust formulation anitescu, need to verify activation --- solvers/c3_miqp.cc | 46 ++++++++++++++++++++++++++++++++++-------- solvers/lcs_factory.cc | 3 +++ 2 files changed, 41 insertions(+), 8 deletions(-) diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 1027c47f8d..ed4eadcfbd 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -41,6 +41,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, GRBVar delta_k[n_ + m_ + k_]; GRBVar binary[m_]; + GRBVar reduced_friction_cone_binary[m_ / 2]; for (int i = 0; i < m_; i++) { binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); @@ -72,29 +73,58 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, double coeff2[n_ + m_ + k_]; for (int i = 0; i < m_; i++) { - GRBLinExpr cexpr = 0; + GRBLinExpr lambda_expr = 0; /// convert VectorXd to double for (int j = 0; j < n_ + m_ + k_; j++) { coeff[j] = Mcons2(i, j); } - cexpr.addTerms(coeff, delta_k, n_ + m_ + k_); - model.addConstr(cexpr >= 0); - model.addConstr(cexpr <= M * (1 - binary[i])); + lambda_expr.addTerms(coeff, delta_k, n_ + m_ + k_); + model.addConstr(lambda_expr >= 0); + model.addConstr(lambda_expr <= M * (1 - binary[i])); - GRBLinExpr cexpr2 = 0; + GRBLinExpr activation_expr = 0; /// convert VectorXd to double for (int j = 0; j < n_ + m_ + k_; j++) { coeff2[j] = Mcons1(i, j); } - cexpr2.addTerms(coeff2, delta_k, n_ + m_ + k_); - model.addConstr(cexpr2 + c(i) >= 0); - model.addConstr(cexpr2 + c(i) <= M * binary[i]); + activation_expr.addTerms(coeff2, delta_k, n_ + m_ + k_); + model.addConstr(activation_expr + c(i) >= 0); + model.addConstr(activation_expr + c(i) <= M * binary[i]); } + DRAKE_DEMAND(m_ % 2 == 0); // only works for Anitescu Model + double subtraction_coeffs[n_ + m_ + k_]; + double addition_coeffs[n_ + m_ + k_]; + MatrixXd addition_of_aligned_forces = MatrixXd::Zero(m_ / 2, n_ + m_ + k_); + MatrixXd subtraction_of_aligned_forces = MatrixXd::Zero(m_ / 2, n_ + m_ + k_); + for (int i = 0; i < m_ / 2; ++i){ + addition_of_aligned_forces(i, n_ + 2 * i + 0) = 1; + addition_of_aligned_forces(i, n_ + 2 * i + 1) = 1; + subtraction_of_aligned_forces(i, n_ + 2 * i + 0) = 1; + subtraction_of_aligned_forces(i, n_ + 2 * i + 1) = -1; + } + + for (int i = 0; i < m_ / 2; ++i){ + GRBLinExpr subtraction_constraint_expr = 0; + GRBLinExpr addition_constraint_expr = 0; + + /// convert VectorXd to double + for (int j = 0; j < n_ + m_ + k_; j++) { + addition_coeffs[j] = addition_of_aligned_forces(i, j); + subtraction_coeffs[j] = subtraction_of_aligned_forces(i, j); + } + + subtraction_constraint_expr.addTerms(subtraction_coeffs, delta_k, n_ + m_ + k_); + addition_constraint_expr.addTerms(addition_coeffs, delta_k, n_ + m_ + k_); + model.addConstr(subtraction_constraint_expr <= 0.75 * (addition_constraint_expr) + M * (1 - binary[2 * i])); + } + + + model.optimize(); VectorXd delta_kc(n_ + m_ + k_); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index b85750a443..7fa8efbd2a 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -99,6 +99,9 @@ LCS LCSFactory::LinearizePlantToLCS( contact_geoms[i]); // deleted num_friction_directions (check with // Michael about changes in geomgeom) auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); + // J_i is 3 x n_v + // row (0) is contact normal + // rows (1-num_friction directions) are the contact tangents phi(i) = phi_i; J_n.row(i) = J_i.row(0); From f9e6ae1da058e72b4a2607848dd99ed006bf57cf Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 10 May 2024 11:49:58 -0400 Subject: [PATCH 709/758] robust formulation runs but doesn't work --- .bazeliskrc | 6 + .../franka_c3_options_supports.yaml | 1 + solvers/c3.cc | 115 ++++++------- solvers/c3.h | 21 ++- solvers/c3_miqp.cc | 160 ++++++++++++++++-- solvers/c3_miqp.h | 8 + solvers/c3_options.h | 2 + solvers/c3_qp.cc | 8 + solvers/c3_qp.h | 8 + solvers/lcs.cc | 6 + solvers/lcs.h | 24 ++- solvers/lcs_factory.cc | 12 +- 12 files changed, 287 insertions(+), 84 deletions(-) create mode 100644 .bazeliskrc diff --git a/.bazeliskrc b/.bazeliskrc new file mode 100644 index 0000000000..dbaa31a83e --- /dev/null +++ b/.bazeliskrc @@ -0,0 +1,6 @@ +# Keep this version number in sync with the Ubuntu deb installed by +# drake/setup/ubuntu/source_distribution/install_bazel.sh. +# +# These files should also be updated: +# drake/tools/workspace/drake_visualizer/image/provision.sh +USE_BAZEL_VERSION=7.1.1 \ No newline at end of file diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 037ab2bcde..82eafd1b3e 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -10,6 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true +use_robust_formulation: true end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible diff --git a/solvers/c3.cc b/solvers/c3.cc index 6f7e644877..45e8a1feab 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -39,28 +39,21 @@ C3::CostMatrices::CostMatrices(const std::vector& Q, this->U = U; } -C3::C3(const LCS& LCS, const C3::CostMatrices& costs, +C3::C3(const LCS& lcs, const C3::CostMatrices& costs, const vector& x_desired, const C3Options& options) : warm_start_(options.warm_start), - N_((LCS.A_).size()), - n_((LCS.A_)[0].cols()), - m_((LCS.D_)[0].cols()), - k_((LCS.B_)[0].cols()), - A_(LCS.A_), - B_(LCS.B_), - D_(LCS.D_), - d_(LCS.d_), - E_(LCS.E_), - F_(LCS.F_), - H_(LCS.H_), - c_(LCS.c_), + lcs_(lcs), + N_((lcs.A_).size()), + n_((lcs.A_)[0].cols()), + m_((lcs.D_)[0].cols()), + k_((lcs.B_)[0].cols()), Q_(costs.Q), R_(costs.R), U_(costs.U), G_(costs.G), x_desired_(x_desired), options_(options), - h_is_zero_(H_[0].isZero(0)), + h_is_zero_(lcs.H_[0].isZero(0)), prog_(MathematicalProgram()), osqp_(OsqpSolver()) { if (warm_start_) { @@ -93,15 +86,15 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, } } - auto Dn = D_.at(0).norm(); - auto An = A_.at(0).norm(); + auto Dn = lcs.D_.at(0).norm(); + auto An = lcs.A_.at(0).norm(); AnDn_ = An / Dn; for (int i = 0 ; i < N_; ++i){ - D_.at(i) *= AnDn_; - E_.at(i) /= AnDn_; - c_.at(i) /= AnDn_; - H_.at(i) /= AnDn_; + lcs_.D_.at(i) *= AnDn_; + lcs_.E_.at(i) /= AnDn_; + lcs_.c_.at(i) /= AnDn_; + lcs_.H_.at(i) /= AnDn_; } x_ = vector(); @@ -137,14 +130,14 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, dynamics_constraints_.resize(N_); target_cost_.resize(N_ + 1); for (int i = 0; i < N_; i++) { - LinEq.block(0, 0, n_, n_) = A_.at(i); - LinEq.block(0, n_, n_, m_) = D_.at(i); - LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); + LinEq.block(0, 0, n_, n_) = lcs.A_.at(i); + LinEq.block(0, n_, n_, m_) = lcs.D_.at(i); + LinEq.block(0, n_ + m_, n_, k_) = lcs.B_.at(i); dynamics_constraints_[i] = prog_ .AddLinearEqualityConstraint( - LinEq, -d_.at(i), + LinEq, -lcs.d_.at(i), {x_.at(i), lambda_.at(i), u_.at(i), x_.at(i + 1)}) .evaluator() .get(); @@ -167,35 +160,26 @@ C3::C3(const LCS& LCS, const C3::CostMatrices& costs, void C3::UpdateLCS(const LCS& lcs) { // first 4 lines are unnecessary - A_ = lcs.A_; - B_ = lcs.B_; - D_ = lcs.D_; - d_ = lcs.d_; - E_ = lcs.E_; - F_ = lcs.F_; - H_ = lcs.H_; - c_ = lcs.c_; - dt_ = lcs.dt_; - h_is_zero_ = H_[0].isZero(0); + lcs_ = lcs; + h_is_zero_ = lcs_.H_[0].isZero(0); MatrixXd LinEq = MatrixXd::Zero(n_, 2 * n_ + m_ + k_); LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); - - auto Dn = D_[0].norm(); - auto An = A_[0].norm(); + auto Dn = lcs_.D_[0].norm(); + auto An = lcs_.A_[0].norm(); AnDn_ = An / Dn; for (int i = 0 ; i < N_; ++i){ - D_.at(i) *= AnDn_; - E_.at(i) /= AnDn_; - c_.at(i) /= AnDn_; - H_.at(i) /= AnDn_; + lcs_.D_.at(i) *= AnDn_; + lcs_.E_.at(i) /= AnDn_; + lcs_.c_.at(i) /= AnDn_; + lcs_.H_.at(i) /= AnDn_; } for (int i = 0; i < N_; i++) { - LinEq.block(0, 0, n_, n_) = A_.at(i); - LinEq.block(0, n_, n_, m_) = D_.at(i); - LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); + LinEq.block(0, 0, n_, n_) = lcs_.A_.at(i); + LinEq.block(0, n_, n_, m_) = lcs_.D_.at(i); + LinEq.block(0, n_ + m_, n_, k_) = lcs_.B_.at(i); dynamics_constraints_[i]->UpdateCoefficients(LinEq, -lcs.d_.at(i)); } @@ -242,8 +226,8 @@ void C3::Solve(const VectorXd& x0) { z_sol_->at(0).segment(0, n_) = x0; for (int i = 1; i < N_; ++i) { z_sol_->at(i).segment(0, n_) = - A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + - D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); + lcs_.A_.at(i - 1) * x_sol_->at(i - 1) + lcs_.B_.at(i - 1) * u_sol_->at(i - 1) + + lcs_.D_.at(i - 1) * lambda_sol_->at(i - 1) + lcs_.d_.at(i - 1); } } *w_sol_ = w; @@ -300,10 +284,10 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, constraints_.clear(); constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); - if (h_is_zero_ == 1) { + if (h_is_zero_ == 1) { // No dependence on u, so just simulate passive system drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; - LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); + LCPSolver.SolveLcpLemke(lcs_.F_[0], lcs_.E_[0] * x0 + lcs_.c_[0], &lambda0); constraints_.push_back(prog_.AddLinearConstraint(lambda_[0] == lambda0)); } @@ -415,17 +399,34 @@ vector C3::SolveProjection(const vector& G, #pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { - if (warm_start_) { - if (i == N_ - 1) { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], - c_[i], admm_iteration, -1); + if (options_.use_robust_formulation){ + DRAKE_DEMAND(lcs_.has_tangent_linearization_); + if (warm_start_) { + if (i == N_ - 1) { + deltaProj[i] = SolveRobustSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], + lcs_.c_[i], lcs_.W_x_,lcs_.W_l_,lcs_.W_u_, lcs_.w_, admm_iteration, -1); + } else { + deltaProj[i] = SolveRobustSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], + lcs_.c_[i], lcs_.W_x_,lcs_.W_l_,lcs_.W_u_, lcs_.w_, admm_iteration, i + 1); + } + } else { + deltaProj[i] = SolveRobustSingleProjection( + G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], lcs_.c_[i], + lcs_.W_x_, lcs_.W_l_, lcs_.W_u_, lcs_.w_, admm_iteration, -1); + } + }else{ + if (warm_start_) { + if (i == N_ - 1) { + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], + lcs_.c_[i], admm_iteration, -1); + } else { + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], + lcs_.c_[i], admm_iteration, i + 1); + } } else { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], - c_[i], admm_iteration, i + 1); + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], + lcs_.c_[i], admm_iteration, -1); } - } else { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], - c_[i], admm_iteration, -1); } } diff --git a/solvers/c3.h b/solvers/c3.h index 4543b63339..30ad7dd082 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -87,6 +87,18 @@ class C3 { const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int admm_iteration, const int& warm_start_index) = 0; + /// Solve a robust single projection step + /// @param E, F, H, c LCS parameters + /// @param U A pointer to the U variables + /// @param delta_c A pointer to the copy of (z + w) variables + virtual Eigen::VectorXd SolveRobustSingleProjection( + const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, + const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, const Eigen::VectorXd& c, + const Eigen::MatrixXd& W_x, const Eigen::MatrixXd& W_l, + const Eigen::MatrixXd& W_u, const Eigen::VectorXd& w, + const int admm_iteration, const int& warm_start_index) = 0; + void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { prog_.SetSolverOptions(options); } @@ -115,14 +127,7 @@ class C3 { const int k_; private: - std::vector A_; - std::vector B_; - std::vector D_; - std::vector d_; - std::vector E_; - std::vector F_; - std::vector H_; - std::vector c_; + LCS lcs_; double AnDn_ = 1.0; const std::vector Q_; const std::vector R_; diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index ed4eadcfbd..198bf6f0d3 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -41,7 +41,6 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, GRBVar delta_k[n_ + m_ + k_]; GRBVar binary[m_]; - GRBVar reduced_friction_cone_binary[m_ / 2]; for (int i = 0; i < m_; i++) { binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); @@ -96,34 +95,167 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.addConstr(activation_expr + c(i) <= M * binary[i]); } - DRAKE_DEMAND(m_ % 2 == 0); // only works for Anitescu Model + model.optimize(); + + VectorXd delta_kc(n_ + m_ + k_); + VectorXd binaryc(m_); + for (int i = 0; i < n_ + m_ + k_; i++) { + delta_kc(i) = delta_k[i].get(GRB_DoubleAttr_X); + } + for (int i = 0; i < m_; i++) { + binaryc(i) = binary[i].get(GRB_DoubleAttr_X); + } + + if (warm_start_index != -1) { + warm_start_delta_[admm_iteration][warm_start_index] = delta_kc; + warm_start_binary_[admm_iteration][warm_start_index] = binaryc; + } + return delta_kc; +} + +VectorXd C3MIQP::SolveRobustSingleProjection( + const MatrixXd& U, const VectorXd& delta_c, const MatrixXd& E, + const MatrixXd& F, const MatrixXd& H, const VectorXd& c, + const Eigen::MatrixXd& W_x, const Eigen::MatrixXd& W_l, + const Eigen::MatrixXd& W_u, const Eigen::VectorXd& w, + const int admm_iteration, const int& warm_start_index) { + // set up linear term in cost + VectorXd cost_lin = -2 * delta_c.transpose() * U; + + // set up for constraints (Ex + F \lambda + Hu + c >= 0) + MatrixXd Mcons1(m_, n_ + m_ + k_); + Mcons1 << E, F, H; + + // set up for constraints (\lambda >= 0) + MatrixXd MM1 = MatrixXd::Zero(m_, n_); + MatrixXd MM2 = MatrixXd::Identity(m_, m_); + MatrixXd MM3 = MatrixXd::Zero(m_, k_); + MatrixXd Mcons2(m_, n_ + m_ + k_); + Mcons2 << MM1, MM2, MM3; + + GRBModel model = GRBModel(env_); + + GRBVar delta_k[n_ + m_ + k_]; + GRBVar binary[m_]; + GRBVar reduced_friction_cone_binary[m_]; + + for (int i = 0; i < m_; i++) { + binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); + if (warm_start_index != -1) { + binary[i].set(GRB_DoubleAttr_Start, + warm_start_binary_[admm_iteration][warm_start_index](i)); + } + } + + for (int i = 0; i < n_ + m_ + k_; i++) { + delta_k[i] = model.addVar(-100.0, 100.0, 0.0, GRB_CONTINUOUS); + if (warm_start_index != -1) { + delta_k[i].set(GRB_DoubleAttr_Start, + warm_start_delta_[admm_iteration][warm_start_index](i)); + } + } + + GRBQuadExpr obj = 0; + + for (int i = 0; i < n_ + m_ + k_; i++) { + obj.addTerm(cost_lin(i), delta_k[i]); + obj.addTerm(U(i, i), delta_k[i], delta_k[i]); + } + + model.setObjective(obj, GRB_MINIMIZE); + + int M = 1000; // big M variable + double coeff[n_ + m_ + k_]; + double coeff2[n_ + m_ + k_]; + + for (int i = 0; i < m_; i++) { + GRBLinExpr lambda_expr = 0; + + /// convert VectorXd to double + for (int j = 0; j < n_ + m_ + k_; j++) { + coeff[j] = Mcons2(i, j); + } + + lambda_expr.addTerms(coeff, delta_k, n_ + m_ + k_); + model.addConstr(lambda_expr >= 0); + model.addConstr(lambda_expr <= M * (1 - binary[i])); + + GRBLinExpr activation_expr = 0; + + /// convert VectorXd to double + for (int j = 0; j < n_ + m_ + k_; j++) { + coeff2[j] = Mcons1(i, j); + } + + activation_expr.addTerms(coeff2, delta_k, n_ + m_ + k_); + model.addConstr(activation_expr + c(i) >= 0); + model.addConstr(activation_expr + c(i) <= M * binary[i]); + } + + // DRAKE_DEMAND(m_ % 2 == 0); // only works for Anitescu Model double subtraction_coeffs[n_ + m_ + k_]; + double flipped_subtraction_coeffs[n_ + m_ + k_]; double addition_coeffs[n_ + m_ + k_]; - MatrixXd addition_of_aligned_forces = MatrixXd::Zero(m_ / 2, n_ + m_ + k_); - MatrixXd subtraction_of_aligned_forces = MatrixXd::Zero(m_ / 2, n_ + m_ + k_); - for (int i = 0; i < m_ / 2; ++i){ - addition_of_aligned_forces(i, n_ + 2 * i + 0) = 1; - addition_of_aligned_forces(i, n_ + 2 * i + 1) = 1; - subtraction_of_aligned_forces(i, n_ + 2 * i + 0) = 1; - subtraction_of_aligned_forces(i, n_ + 2 * i + 1) = -1; + double tangential_velocity_coeffs[n_ + m_ + k_]; + double single_lambda_coeffs[n_ + m_ + k_]; + MatrixXd addition_of_aligned_forces = MatrixXd::Zero(m_, n_ + m_ + k_); + MatrixXd subtraction_of_aligned_forces = MatrixXd::Zero(m_, n_ + m_ + k_); + + MatrixXd P_t(m_, n_ + m_ + k_); + P_t << W_x, W_l, W_u; + for (int i = 0; i < m_; ++i) { + addition_of_aligned_forces(i, n_ + 2 * (i % 2) + 0) = 1; + addition_of_aligned_forces(i, n_ + 2 * (i % 2) + 1) = 1; + if (i % 2 == 0){ + subtraction_of_aligned_forces(i, n_ + i + 0) = 1; + subtraction_of_aligned_forces(i, n_ + i + 1) = -1; + } else { + subtraction_of_aligned_forces(i, n_ + i + 0) = 1; + subtraction_of_aligned_forces(i, n_ + i - 1) = -1; + } } - for (int i = 0; i < m_ / 2; ++i){ + for (int i = 0; i < m_; ++i) { + reduced_friction_cone_binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); GRBLinExpr subtraction_constraint_expr = 0; GRBLinExpr addition_constraint_expr = 0; + GRBLinExpr tangential_velocity_expr = 0; + GRBLinExpr single_lambda_expr = 0; /// convert VectorXd to double for (int j = 0; j < n_ + m_ + k_; j++) { addition_coeffs[j] = addition_of_aligned_forces(i, j); subtraction_coeffs[j] = subtraction_of_aligned_forces(i, j); + tangential_velocity_coeffs[j] = P_t(i, j); + single_lambda_coeffs[j] = Mcons2(i, j); } - subtraction_constraint_expr.addTerms(subtraction_coeffs, delta_k, n_ + m_ + k_); + subtraction_constraint_expr.addTerms(subtraction_coeffs, delta_k, + n_ + m_ + k_); addition_constraint_expr.addTerms(addition_coeffs, delta_k, n_ + m_ + k_); - model.addConstr(subtraction_constraint_expr <= 0.75 * (addition_constraint_expr) + M * (1 - binary[2 * i])); - } - + tangential_velocity_expr.addTerms(tangential_velocity_coeffs, delta_k, + n_ + m_ + k_); + single_lambda_expr.addTerms(single_lambda_coeffs, delta_k, + n_ + m_ + k_); + + if (m_ % 2 == 0){ + model.addConstr(subtraction_constraint_expr <= + (0.4 / 0.6) * (addition_constraint_expr) + + M * (reduced_friction_cone_binary[i])); + model.addConstr(tangential_velocity_expr <= + M * (reduced_friction_cone_binary[i])); + } + else if (m_ % 2 == 1){ + model.addConstr(subtraction_constraint_expr <= + (0.4 / 0.6) * (addition_constraint_expr) + + M * (reduced_friction_cone_binary[i])); + model.addConstr(tangential_velocity_expr <= + M * (reduced_friction_cone_binary[i])); + } + model.addConstr(single_lambda_expr <= + M * (1 - reduced_friction_cone_binary[i])); + } model.optimize(); diff --git a/solvers/c3_miqp.h b/solvers/c3_miqp.h index 96db21f011..0a80f70148 100644 --- a/solvers/c3_miqp.h +++ b/solvers/c3_miqp.h @@ -28,6 +28,14 @@ class C3MIQP final : public C3 { const Eigen::VectorXd& c, const int admm_iteration, const int& warm_start_index = -1) override; + /// Robust projection method + Eigen::VectorXd SolveRobustSingleProjection( + const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, + const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, const Eigen::VectorXd& c, + const Eigen::MatrixXd& W_x, const Eigen::MatrixXd& W_l, + const Eigen::MatrixXd& W_u, const Eigen::VectorXd& w, + const int admm_iteration, const int& warm_start_index = -1) override; std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index d18069b7ce..6b201063fb 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -15,6 +15,7 @@ struct C3Options { bool warm_start; bool use_predicted_x0; bool end_on_qp_step; + bool use_robust_formulation; double solve_time_filter_alpha; double publish_frequency; @@ -78,6 +79,7 @@ struct C3Options { a->Visit(DRAKE_NVP(warm_start)); a->Visit(DRAKE_NVP(use_predicted_x0)); a->Visit(DRAKE_NVP(end_on_qp_step)); + a->Visit(DRAKE_NVP(use_robust_formulation)); a->Visit(DRAKE_NVP(solve_time_filter_alpha)); a->Visit(DRAKE_NVP(publish_frequency)); diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc index 0c0112502a..1fbfa9af95 100644 --- a/solvers/c3_qp.cc +++ b/solvers/c3_qp.cc @@ -96,6 +96,14 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, return delta_kc; } +VectorXd C3QP::SolveRobustSingleProjection(const MatrixXd& U, const VectorXd& delta_c, const MatrixXd& E, + const MatrixXd& F, const MatrixXd& H, const VectorXd& c, + const Eigen::MatrixXd& W_x, const Eigen::MatrixXd& W_l, + const Eigen::MatrixXd& W_u, const Eigen::VectorXd& w, + const int admm_iteration, const int& warm_start_index) { + return delta_c; +} + std::vector C3QP::GetWarmStartDelta() const { return warm_start_delta_[0]; } diff --git a/solvers/c3_qp.h b/solvers/c3_qp.h index c308baaf26..dee6c58c2c 100644 --- a/solvers/c3_qp.h +++ b/solvers/c3_qp.h @@ -38,6 +38,14 @@ class C3QP final : public C3 { const Eigen::VectorXd& c, const int admm_iteration, const int& warm_start_index = -1) override; + /// Robust projection method + Eigen::VectorXd SolveRobustSingleProjection( + const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, + const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, + const Eigen::MatrixXd& H, const Eigen::VectorXd& c, + const Eigen::MatrixXd& W_x, const Eigen::MatrixXd& W_l, + const Eigen::MatrixXd& W_u, const Eigen::VectorXd& w, + const int admm_iteration, const int& warm_start_index = -1) override; std::vector GetWarmStartDelta() const; std::vector GetWarmStartBinary() const; diff --git a/solvers/lcs.cc b/solvers/lcs.cc index 75906d275d..24d27aa14a 100644 --- a/solvers/lcs.cc +++ b/solvers/lcs.cc @@ -83,6 +83,12 @@ LCS& LCS::operator=(const LCS& lcs) { H_.at(i) = lcs.H_.at(i); c_.at(i) = lcs.c_.at(i); } + W_x_ = lcs.W_x_; + W_l_ = lcs.W_l_; + W_u_ = lcs.W_u_; + w_ = lcs.w_; + has_tangent_linearization_ = lcs.has_tangent_linearization_; + return *this; } const VectorXd LCS::Simulate(VectorXd& x_init, VectorXd& input) { diff --git a/solvers/lcs.h b/solvers/lcs.h index 27056cd65d..9cfe7b85ce 100644 --- a/solvers/lcs.h +++ b/solvers/lcs.h @@ -1,5 +1,5 @@ #pragma once - +#include #include #include @@ -23,8 +23,7 @@ class LCS { const std::vector& E, const std::vector& F, const std::vector& H, - const std::vector& c, - double dt); + const std::vector& c, double dt); /// Constructor for time-invariant LCS LCS(const Eigen::MatrixXd& A, const Eigen::MatrixXd& B, @@ -38,10 +37,22 @@ class LCS { LCS(LCS&&) = default; LCS& operator=(LCS&&) = default; + void SetTangentGapLinearization(const Eigen::MatrixXd& W_x, + const Eigen::MatrixXd& W_l, + const Eigen::MatrixXd& W_u, + const Eigen::VectorXd& w) { + W_x_ = W_x; + W_l_ = W_l; + W_u_ = W_u; + w_ = w; + has_tangent_linearization_ = true; + } + /// Simulate the system for one-step /// @param x_init Initial x value /// @param input Input value - const Eigen::VectorXd Simulate(Eigen::VectorXd& x_init, Eigen::VectorXd& input); + const Eigen::VectorXd Simulate(Eigen::VectorXd& x_init, + Eigen::VectorXd& input); public: std::vector A_; @@ -52,6 +63,11 @@ class LCS { std::vector F_; std::vector H_; std::vector c_; + Eigen::MatrixXd W_x_; + Eigen::MatrixXd W_l_; + Eigen::MatrixXd W_u_; + Eigen::VectorXd w_; + bool has_tangent_linearization_ = false; Eigen::MatrixXd J_c_; int N_; double dt_; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 7fa8efbd2a..f281d93227 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -157,6 +157,11 @@ LCS LCSFactory::LinearizePlantToLCS( MatrixXd H = MatrixXd::Zero(n_lambda, n_u); VectorXd c = VectorXd::Zero(n_lambda); + MatrixXd W_x = MatrixXd::Zero(n_lambda, n_x); + MatrixXd W_l = MatrixXd::Zero(n_lambda, n_lambda); + MatrixXd W_u = MatrixXd::Zero(n_lambda, n_u); + MatrixXd w = VectorXd::Zero(n_lambda); + if (contact_model == ContactModel::kStewartAndTrinkle) { D.block(0, 2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions) = dt * dt * qdotNv * MinvJ_t_T; @@ -233,10 +238,15 @@ LCS LCSFactory::LinearizePlantToLCS( H = dt * J_c * AB_v_u; c = E_t.transpose() * phi / dt + dt * J_c * d_v - E_t.transpose() * J_n * vNqdot * plant.GetPositions(context) / dt; + W_x.block(0, 0, n_lambda, n_q) = J_t * AB_v_q; + W_x.block(0, n_q, n_lambda, n_v) = J_t + J_t * AB_v_v; + W_l = J_t * (MinvJ_c_T); + W_u = J_t * (AB_v_u); + w = J_t * (d_v); } LCS system(A, B, D, d, E, F, H, c, N, dt); - + system.SetTangentGapLinearization(W_x, W_l, W_u, w); return system; } From 7a3ee466620c11f936d6a3573e9cad55ae3eaf03 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 13 May 2024 14:49:23 -0400 Subject: [PATCH 710/758] trying to tune for stewart and trinkle --- .../franka_c3_options_supports.yaml | 12 +- .../franka/parameters/franka_sim_params.yaml | 4 +- solvers/c3.cc | 116 +++++++++++------- solvers/c3.h | 13 +- solvers/c3_miqp.cc | 52 ++++---- solvers/lcs.cc | 5 + solvers/lcs_factory.cc | 31 ++++- 7 files changed, 148 insertions(+), 85 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 82eafd1b3e..5a5c4d4f6e 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -6,8 +6,8 @@ delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' #options are 'stewart_and_trinkle' or 'anitescu' -#contact_model : 'stewart_and_trinkle' -contact_model: 'anitescu' +contact_model : 'stewart_and_trinkle' +#contact_model: 'anitescu' warm_start: true use_predicted_x0: true use_robust_formulation: true @@ -53,15 +53,15 @@ r_vector: [0.15, 0.15, 0.1] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] -g_lambda_n: [1, 1, 1, 1, 1, 1, 1] -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_lambda_n: [50, 50, 50, 50, 50, 50, 50] +g_lambda_t: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] g_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] g_u: [1, 1, 1] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [1, 1, 1, 1, 1, 1, 1] -u_lambda_n: [1, 1, 1, 1, 1, 1, 1] -u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +u_lambda_n: [250, 250, 250, 250, 250, 250, 250] +u_lambda_t: [250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250] u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 4e56b6294c..b9dd9a553c 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -9,7 +9,7 @@ visualizer_publish_rate: 30 actuator_delay: 0.000 scene_index: 1 -visualize_drake_sim: true +visualize_drake_sim: false publish_efforts: true publish_object_velocities: true @@ -54,6 +54,6 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], visualize_workspace: false visualize_pose_trace: true visualize_center_of_mass_plan: false -visualize_c3_forces: true +visualize_c3_forces: false visualize_c3_object_state: true visualize_c3_end_effector_state: false diff --git a/solvers/c3.cc b/solvers/c3.cc index 45e8a1feab..92d30b3b38 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -42,11 +42,18 @@ C3::CostMatrices::CostMatrices(const std::vector& Q, C3::C3(const LCS& lcs, const C3::CostMatrices& costs, const vector& x_desired, const C3Options& options) : warm_start_(options.warm_start), - lcs_(lcs), N_((lcs.A_).size()), n_((lcs.A_)[0].cols()), m_((lcs.D_)[0].cols()), k_((lcs.B_)[0].cols()), + A_(lcs.A_), + B_(lcs.B_), + D_(lcs.D_), + d_(lcs.d_), + E_(lcs.E_), + F_(lcs.F_), + H_(lcs.H_), + c_(lcs.c_), Q_(costs.Q), R_(costs.R), U_(costs.U), @@ -90,11 +97,11 @@ C3::C3(const LCS& lcs, const C3::CostMatrices& costs, auto An = lcs.A_.at(0).norm(); AnDn_ = An / Dn; - for (int i = 0 ; i < N_; ++i){ - lcs_.D_.at(i) *= AnDn_; - lcs_.E_.at(i) /= AnDn_; - lcs_.c_.at(i) /= AnDn_; - lcs_.H_.at(i) /= AnDn_; + for (int i = 0; i < N_; ++i) { + D_.at(i) *= AnDn_; + E_.at(i) /= AnDn_; + c_.at(i) /= AnDn_; + H_.at(i) /= AnDn_; } x_ = vector(); @@ -159,27 +166,38 @@ C3::C3(const LCS& lcs, const C3::CostMatrices& costs, } void C3::UpdateLCS(const LCS& lcs) { - // first 4 lines are unnecessary - lcs_ = lcs; - h_is_zero_ = lcs_.H_[0].isZero(0); + A_ = lcs.A_; + B_ = lcs.B_; + D_ = lcs.D_; + d_ = lcs.d_; + E_ = lcs.E_; + F_ = lcs.F_; + H_ = lcs.H_; + c_ = lcs.c_; + dt_ = lcs.dt_; + W_x_ = lcs.W_x_; + W_l_ = lcs.W_l_; + W_u_ = lcs.W_u_; + w_ = lcs.w_; + h_is_zero_ = H_[0].isZero(0); MatrixXd LinEq = MatrixXd::Zero(n_, 2 * n_ + m_ + k_); LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); - auto Dn = lcs_.D_[0].norm(); - auto An = lcs_.A_[0].norm(); + auto Dn = D_[0].norm(); + auto An = A_[0].norm(); AnDn_ = An / Dn; - for (int i = 0 ; i < N_; ++i){ - lcs_.D_.at(i) *= AnDn_; - lcs_.E_.at(i) /= AnDn_; - lcs_.c_.at(i) /= AnDn_; - lcs_.H_.at(i) /= AnDn_; + for (int i = 0; i < N_; ++i) { + D_.at(i) *= AnDn_; + E_.at(i) /= AnDn_; + c_.at(i) /= AnDn_; + H_.at(i) /= AnDn_; } for (int i = 0; i < N_; i++) { - LinEq.block(0, 0, n_, n_) = lcs_.A_.at(i); - LinEq.block(0, n_, n_, m_) = lcs_.D_.at(i); - LinEq.block(0, n_ + m_, n_, k_) = lcs_.B_.at(i); + LinEq.block(0, 0, n_, n_) = A_.at(i); + LinEq.block(0, n_, n_, m_) = D_.at(i); + LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); dynamics_constraints_[i]->UpdateCoefficients(LinEq, -lcs.d_.at(i)); } @@ -196,9 +214,8 @@ void C3::UpdateTarget(const std::vector& x_des) { void C3::Solve(const VectorXd& x0) { auto start = std::chrono::high_resolution_clock::now(); - VectorXd delta_init = VectorXd::Zero(n_ + m_ + k_); - if (options_.delta_option == 1){ + if (options_.delta_option == 1) { delta_init.head(n_) = x0; } std::vector delta(N_, delta_init); @@ -221,19 +238,19 @@ void C3::Solve(const VectorXd& x0) { vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); - if (!options_.end_on_qp_step){ + if (!options_.end_on_qp_step) { *z_sol_ = delta; z_sol_->at(0).segment(0, n_) = x0; for (int i = 1; i < N_; ++i) { z_sol_->at(i).segment(0, n_) = - lcs_.A_.at(i - 1) * x_sol_->at(i - 1) + lcs_.B_.at(i - 1) * u_sol_->at(i - 1) + - lcs_.D_.at(i - 1) * lambda_sol_->at(i - 1) + lcs_.d_.at(i - 1); + A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + + D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); } } *w_sol_ = w; *delta_sol_ = delta; - for (int i = 0; i < N_; ++i){ + for (int i = 0; i < N_; ++i) { lambda_sol_->at(i) *= AnDn_; z_sol_->at(i).segment(n_, m_) *= AnDn_; } @@ -242,7 +259,7 @@ void C3::Solve(const VectorXd& x0) { auto elapsed = finish - start; solve_time_ = std::chrono::duration_cast(elapsed).count() / - 1e6; + 1e6; } void C3::ADMMStep(const VectorXd& x0, vector* delta, @@ -284,10 +301,10 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, constraints_.clear(); constraints_.push_back(prog_.AddLinearConstraint(x_[0] == x0)); - if (h_is_zero_ == 1) { // No dependence on u, so just simulate passive system + if (h_is_zero_ == 1) { // No dependence on u, so just simulate passive system drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; - LCPSolver.SolveLcpLemke(lcs_.F_[0], lcs_.E_[0] * x0 + lcs_.c_[0], &lambda0); + LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); constraints_.push_back(prog_.AddLinearConstraint(lambda_[0] == lambda0)); } @@ -319,9 +336,15 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, int index = solve_time_ / dt_; double weight = (solve_time_ - index * dt_) / dt_; for (int i = 0; i < N_ - 1; i++) { - prog_.SetInitialGuess(x_[i], (1 - weight) * warm_start_x_[admm_iteration][i] + weight * warm_start_x_[admm_iteration][i + 1]); - prog_.SetInitialGuess(lambda_[i], (1 - weight) * warm_start_lambda_[admm_iteration][i] + weight * warm_start_lambda_[admm_iteration][i + 1]); - prog_.SetInitialGuess(u_[i], (1 - weight) * warm_start_u_[admm_iteration][i] + weight * warm_start_u_[admm_iteration][i + 1]); + prog_.SetInitialGuess(x_[i], + (1 - weight) * warm_start_x_[admm_iteration][i] + + weight * warm_start_x_[admm_iteration][i + 1]); + prog_.SetInitialGuess( + lambda_[i], (1 - weight) * warm_start_lambda_[admm_iteration][i] + + weight * warm_start_lambda_[admm_iteration][i + 1]); + prog_.SetInitialGuess(u_[i], + (1 - weight) * warm_start_u_[admm_iteration][i] + + weight * warm_start_u_[admm_iteration][i + 1]); } prog_.SetInitialGuess(x_[0], x0); prog_.SetInitialGuess(x_[N_], warm_start_x_[admm_iteration][N_]); @@ -399,33 +422,34 @@ vector C3::SolveProjection(const vector& G, #pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { - if (options_.use_robust_formulation){ - DRAKE_DEMAND(lcs_.has_tangent_linearization_); + if (options_.use_robust_formulation) { if (warm_start_) { if (i == N_ - 1) { - deltaProj[i] = SolveRobustSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], - lcs_.c_[i], lcs_.W_x_,lcs_.W_l_,lcs_.W_u_, lcs_.w_, admm_iteration, -1); + deltaProj[i] = SolveRobustSingleProjection( + G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, + admm_iteration, -1); } else { - deltaProj[i] = SolveRobustSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], - lcs_.c_[i], lcs_.W_x_,lcs_.W_l_,lcs_.W_u_, lcs_.w_, admm_iteration, i + 1); + deltaProj[i] = SolveRobustSingleProjection( + G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, + admm_iteration, i + 1); } } else { deltaProj[i] = SolveRobustSingleProjection( - G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], lcs_.c_[i], - lcs_.W_x_, lcs_.W_l_, lcs_.W_u_, lcs_.w_, admm_iteration, -1); + G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, + admm_iteration, -1); } - }else{ + } else { if (warm_start_) { if (i == N_ - 1) { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], - lcs_.c_[i], admm_iteration, -1); + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, -1); } else { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], - lcs_.c_[i], admm_iteration, i + 1); + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, i + 1); } } else { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], lcs_.E_[i], lcs_.F_[i], lcs_.H_[i], - lcs_.c_[i], admm_iteration, -1); + deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + c_[i], admm_iteration, -1); } } } diff --git a/solvers/c3.h b/solvers/c3.h index 30ad7dd082..e90c3d5505 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -127,7 +127,18 @@ class C3 { const int k_; private: - LCS lcs_; + std::vector A_; + std::vector B_; + std::vector D_; + std::vector d_; + std::vector E_; + std::vector F_; + std::vector H_; + std::vector c_; + Eigen::MatrixXd W_x_; + Eigen::MatrixXd W_l_; + Eigen::MatrixXd W_u_; + Eigen::VectorXd w_; double AnDn_ = 1.0; const std::vector Q_; const std::vector R_; diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 198bf6f0d3..c15763d0da 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -192,30 +192,36 @@ VectorXd C3MIQP::SolveRobustSingleProjection( model.addConstr(activation_expr + c(i) <= M * binary[i]); } - // DRAKE_DEMAND(m_ % 2 == 0); // only works for Anitescu Model double subtraction_coeffs[n_ + m_ + k_]; - double flipped_subtraction_coeffs[n_ + m_ + k_]; double addition_coeffs[n_ + m_ + k_]; double tangential_velocity_coeffs[n_ + m_ + k_]; double single_lambda_coeffs[n_ + m_ + k_]; MatrixXd addition_of_aligned_forces = MatrixXd::Zero(m_, n_ + m_ + k_); MatrixXd subtraction_of_aligned_forces = MatrixXd::Zero(m_, n_ + m_ + k_); + MatrixXd P_t(m_, n_ + m_ + k_); - P_t << W_x, W_l, W_u; - for (int i = 0; i < m_; ++i) { - addition_of_aligned_forces(i, n_ + 2 * (i % 2) + 0) = 1; - addition_of_aligned_forces(i, n_ + 2 * (i % 2) + 1) = 1; - if (i % 2 == 0){ - subtraction_of_aligned_forces(i, n_ + i + 0) = 1; - subtraction_of_aligned_forces(i, n_ + i + 1) = -1; + int constraint_rows = m_; +// P_t << W_x, W_l, W_u; + + // stewart and trinkle + P_t << E, F, H; + MatrixXd P_t2 = P_t.bottomRows(((m_ / 6) * 4) / 7 * 3); + P_t = P_t2; + constraint_rows = P_t2.rows(); + for (int i = 0; i < constraint_rows; ++i) { + addition_of_aligned_forces(i, n_ + 2 * (i / 2) + 0) = 1; + addition_of_aligned_forces(i, n_ + 2 * (i / 2) + 1) = 1; + if (i % 2 == 0) { + subtraction_of_aligned_forces(i, n_ + i + 0) = -1; + subtraction_of_aligned_forces(i, n_ + i + 1) = 1; } else { - subtraction_of_aligned_forces(i, n_ + i + 0) = 1; - subtraction_of_aligned_forces(i, n_ + i - 1) = -1; + subtraction_of_aligned_forces(i, n_ + i + 0) = -1; + subtraction_of_aligned_forces(i, n_ + i - 1) = 1; } } - for (int i = 0; i < m_; ++i) { + for (int i = 0; i < constraint_rows; ++i) { reduced_friction_cone_binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); GRBLinExpr subtraction_constraint_expr = 0; GRBLinExpr addition_constraint_expr = 0; @@ -235,23 +241,20 @@ VectorXd C3MIQP::SolveRobustSingleProjection( addition_constraint_expr.addTerms(addition_coeffs, delta_k, n_ + m_ + k_); tangential_velocity_expr.addTerms(tangential_velocity_coeffs, delta_k, n_ + m_ + k_); - single_lambda_expr.addTerms(single_lambda_coeffs, delta_k, - n_ + m_ + k_); + single_lambda_expr.addTerms(single_lambda_coeffs, delta_k, n_ + m_ + k_); - if (m_ % 2 == 0){ + if (constraint_rows % 2 == 1) { model.addConstr(subtraction_constraint_expr <= - (0.4 / 0.6) * (addition_constraint_expr) + - M * (reduced_friction_cone_binary[i])); + (0.4 / 0.6) * (addition_constraint_expr) + + M * (reduced_friction_cone_binary[i])); model.addConstr(tangential_velocity_expr <= - M * (reduced_friction_cone_binary[i])); - - } - else if (m_ % 2 == 1){ + M * (reduced_friction_cone_binary[i])); + } else { model.addConstr(subtraction_constraint_expr <= - (0.4 / 0.6) * (addition_constraint_expr) + - M * (reduced_friction_cone_binary[i])); + (0.4 / 0.6) * (addition_constraint_expr) + + M * (reduced_friction_cone_binary[i])); model.addConstr(tangential_velocity_expr <= - M * (reduced_friction_cone_binary[i])); + M * (reduced_friction_cone_binary[i])); } model.addConstr(single_lambda_expr <= M * (1 - reduced_friction_cone_binary[i])); @@ -272,6 +275,7 @@ VectorXd C3MIQP::SolveRobustSingleProjection( warm_start_delta_[admm_iteration][warm_start_index] = delta_kc; warm_start_binary_[admm_iteration][warm_start_index] = binaryc; } + return delta_kc; } diff --git a/solvers/lcs.cc b/solvers/lcs.cc index 24d27aa14a..7433279a38 100644 --- a/solvers/lcs.cc +++ b/solvers/lcs.cc @@ -57,6 +57,11 @@ LCS::LCS(const LCS& lcs) H_.at(i) = lcs.H_.at(i); c_.at(i) = lcs.c_.at(i); } + W_x_ = lcs.W_x_; + W_l_ = lcs.W_l_; + W_u_ = lcs.W_u_; + w_ = lcs.w_; + has_tangent_linearization_ = lcs.has_tangent_linearization_; } LCS& LCS::operator=(const LCS& lcs) { diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index f281d93227..6c4726fdf5 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -171,6 +171,7 @@ LCS LCSFactory::LinearizePlantToLCS( D.block(0, n_contacts, n_q, n_contacts) = dt * dt * qdotNv * MinvJ_n_T; D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; + // Complementarity condition for gamma: mu lambda^n E.block(n_contacts, 0, n_contacts, n_q) = dt * dt * J_n * AB_v_q + J_n * vNqdot; E.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_q) = @@ -180,26 +181,35 @@ LCS LCSFactory::LinearizePlantToLCS( E.block(2 * n_contacts, n_q, 2 * n_contacts * num_friction_directions, n_v) = J_t + dt * J_t * AB_v_v; - F.block(0, n_contacts, n_contacts, n_contacts) = - Eigen::Map(mu.data(), - mu.size()) - .asDiagonal(); + VectorXd mu_vec = Eigen::Map( + mu.data(), mu.size()); + // Complementarity condition for gamma: mu lambda^n + F.block(0, n_contacts, n_contacts, n_contacts) = mu_vec.asDiagonal(); + // Complementarity condition for gamma: lambda^t F.block(0, 2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions) = -E_t; + // Complementarity condition for lambda_n: dt J_n (lambda^n component of + // v_{k+1}) F.block(n_contacts, n_contacts, n_contacts, n_contacts) = dt * dt * J_n * MinvJ_n_T; + // Complementarity condition for lambda_n: dt J_n (lambda^t component of + // v_{k+1}) F.block(n_contacts, 2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions) = dt * dt * J_n * MinvJ_t_T; - + // Complementarity condition for lambda_t: dt J_t (gamma component of + // v_{k+1}) F.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_contacts) = E_t.transpose(); - + // Complementarity condition for lambda_t: dt J_t (lambda^n component of + // v_{k+1}) F.block(2 * n_contacts, n_contacts, 2 * n_contacts * num_friction_directions, n_contacts) = dt * J_t * MinvJ_n_T; + // Complementarity condition for lambda_t: dt J_t (lambda^t component of + // v_{k+1}) F.block(2 * n_contacts, 2 * n_contacts, 2 * n_contacts * num_friction_directions, 2 * n_contacts * num_friction_directions) = dt * J_t * MinvJ_t_T; @@ -208,6 +218,15 @@ LCS LCSFactory::LinearizePlantToLCS( H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = dt * J_t * AB_v_u; +// W_x.block(0, 0, n_lambda, n_q) = J_t * AB_v_q; +// W_x.block(0, n_q, n_lambda, n_v) = J_t + J_t * AB_v_v; +// W_l.block(0, n_contacts, n_contacts, n_contacts) = J_t * (MinvJ_c_T); +// W_l.block(0, n_contacts + n_contacts, n_contacts, 2 * n_contacts * num_friction_directions) = J_t * (MinvJ_c_T); +// W_l.block(0, 0, n_lambda, ) = J_t * (MinvJ_c_T); +// W_l.block(0, 0, n_lambda, ) = J_t * (MinvJ_c_T); +// W_u = J_t * (AB_v_u); +// w = J_t * (d_v); + c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v - J_n * vNqdot * plant.GetPositions(context); c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = From fe0e0187eea65d66eb5744577276ed9d7c72c4c5 Mon Sep 17 00:00:00 2001 From: Will Yang Date: Tue, 14 May 2024 14:12:26 -0400 Subject: [PATCH 711/758] updating procman script --- examples/franka/franka_hardware.pmd | 104 ++++++++++++++++++++++++++++ 1 file changed, 104 insertions(+) create mode 100644 examples/franka/franka_hardware.pmd diff --git a/examples/franka/franka_hardware.pmd b/examples/franka/franka_hardware.pmd new file mode 100644 index 0000000000..496a270d39 --- /dev/null +++ b/examples/franka/franka_hardware.pmd @@ -0,0 +1,104 @@ +group "simulations" { + cmd "franka_sim" { + exec = "bazel-bin/examples/franka/franka_sim"; + host = "localhost"; + } +} + +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/franka/franka_visualizer --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; + host = "localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/Cassie/cassie_xbox_remote"; + host = "localhost"; + } + cmd "logger" { + exec = "python3 start_logging.py hw"; + host = "localhost"; + } + cmd "record_video" { + exec = "python3 record_video.py"; + host = "localhost"; + } +} + +group "controllers (hardware)" { + cmd "franka_osc" { + exec = "bazel-bin/examples/franka/franka_osc_controller --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; + host = "localhost"; + } + cmd "franka_c3" { + exec = "bazel-bin/examples/franka/franka_c3_controller --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; + host = "localhost"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "localhost"; + } +} + +group "dispatchers" { + cmd "ros_lcm_bridge" { + exec = "bazel-bin/examples/franka/franka_ros_lcm_bridge"; + host = "localhost"; + } + cmd "lcm_ros_bridge" { + exec = "bazel-bin/examples/franka/franka_lcm_ros_bridge"; + host = "localhost"; + } +} + +group "drivers" { + cmd "move_to_start" { + exec = "roslaunch franka_example_controllers move_to_start.launch robot_ip:=172.16.0.2 load_gripper:=false"; + host = "franka_control"; + } + cmd "torque_passthrough_controller" { + exec = "roslaunch franka_example_controllers torque_passthrough_controller.launch robot_ip:=172.16.0.2 load_gripper:=false"; + host = "franka_control"; + } + cmd "move_to_osc_pose" { + exec = "roslaunch franka_example_controllers move_to_start_osc.launch robot_ip:=172.16.0.2 load_gripper:=false"; + host = "franka_control"; + } + cmd "position_driver" { + exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=position"; + host = "franka_control"; + } + cmd "torque_driver" { + exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=torque"; + host = "franka_control"; + } + cmd "cam_sync" { + exec = "roslaunch kuka_vision kuka_online_cam_sync.launch"; + host = "tagslam"; + } +} + + +script "start_franka_osc" { + stop cmd "lcm_ros_bridge"; + stop cmd "ros_lcm_bridge"; + stop cmd "franka_osc"; + stop cmd "torque_passthrough_controller"; + start cmd "record_video"; + start cmd "logger"; + start cmd "lcm_ros_bridge"; + start cmd "ros_lcm_bridge"; + start cmd "franka_osc"; + wait ms 1000; + start cmd "torque_passthrough_controller"; +} + +script "stop_experiment" { + stop cmd "torque_passthrough_controller" wait "stopped"; + stop group "controllers (hardware)"; + stop group "dispatchers"; + stop cmd "record_video"; + stop cmd "logger"; +} From 63cc66ad063acb08f95b4471a8340f30f512ef57 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 15 May 2024 14:02:43 -0400 Subject: [PATCH 712/758] fixing bug in visualizing stewart and trinkle forces --- .bazelrc | 1 - .../franka_c3_options_supports.yaml | 6 ++--- .../franka/parameters/franka_sim_params.yaml | 4 +-- systems/controllers/c3_controller.cc | 3 ++- .../c3_output_systems.cc | 26 ++++++++++++++----- 5 files changed, 26 insertions(+), 14 deletions(-) diff --git a/.bazelrc b/.bazelrc index 2f75e98746..25fb2159dd 100644 --- a/.bazelrc +++ b/.bazelrc @@ -52,7 +52,6 @@ build --action_env=LD_LIBRARY_PATH= # customizations somehow. # build with snopt -build --define=WITH_SNOPT=ON build --define=WITH_GUROBI=ON build --define=NO_CLARABEL=ON diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 5a5c4d4f6e..f8961955b4 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -10,7 +10,7 @@ contact_model : 'stewart_and_trinkle' #contact_model: 'anitescu' warm_start: true use_predicted_x0: true -use_robust_formulation: true +use_robust_formulation: false end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible @@ -26,7 +26,7 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], workspace_margins: 0.05 u_horizontal_limits: [-10, 10] -u_vertical_limits: [0, 30] +u_vertical_limits: [-200, 200] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] dt: 0.075 @@ -60,7 +60,7 @@ g_u: [1, 1, 1] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_gamma: [1, 1, 1, 1, 1, 1, 1] +u_gamma: [10, 10, 10, 10, 10, 10, 10] u_lambda_n: [250, 250, 250, 250, 250, 250, 250] u_lambda_t: [250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250] u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index b9dd9a553c..9845ad9e2d 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -5,7 +5,7 @@ object_model: examples/franka/urdf/cylinder_object.urdf franka_publish_rate: 1000 tray_publish_rate: 1000 object_publish_rate: 1000 -visualizer_publish_rate: 30 +visualizer_publish_rate: 32 actuator_delay: 0.000 scene_index: 1 @@ -54,6 +54,6 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], visualize_workspace: false visualize_pose_trace: true visualize_center_of_mass_plan: false -visualize_c3_forces: false +visualize_c3_forces: true visualize_c3_object_state: true visualize_c3_end_effector_state: false diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3_controller.cc index 066527089e..8585005e73 100644 --- a/systems/controllers/c3_controller.cc +++ b/systems/controllers/c3_controller.cc @@ -168,6 +168,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( const TimestampedVector* lcs_x = (TimestampedVector*)this->EvalVectorInput(context, lcs_state_input_port_); + auto& lcs = this->EvalAbstractInput(context, lcs_input_port_)->get_value(); drake::VectorX x_lcs = lcs_x->get_data(); @@ -234,7 +235,7 @@ drake::systems::EventStatus C3Controller::ComputePlan( mutable_x_pred = (1 - weight) * z_sol[index].segment(0, n_x_) + weight * z_sol[index + 1].segment(0, n_x_); } else { - mutable_x_pred = z_sol[-1].segment(0, n_x_); + mutable_x_pred = z_sol[N_ - 1].segment(0, n_x_); } return drake::systems::EventStatus::Succeeded(); diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index d1807eb6ce..6c5af1b5a9 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -57,15 +57,27 @@ void C3OutputSender::OutputC3Forces( const auto& contact_info = this->EvalInputValue>>(context, lcs_contact_info_port_); MatrixXd J_c = contact_info->first; + int contact_force_start = c3_solution->lambda_sol_.rows() - J_c.rows(); auto contact_points = contact_info->second; - c3_forces_output->num_forces = c3_solution->lambda_sol_.rows(); - c3_forces_output->forces.resize(c3_forces_output->num_forces); int forces_per_contact = contact_info->first.rows() / contact_points.size(); + c3_forces_output->num_forces = forces_per_contact * contact_points.size(); + c3_forces_output->forces.resize(c3_forces_output->num_forces); + int contact_var_start; + int contact_jacobian_row_start; for (int contact_index = 0; contact_index < contact_points.size(); ++contact_index) { - contact_var_start = forces_per_contact * contact_index; + contact_var_start = contact_force_start + forces_per_contact * contact_index; + contact_jacobian_row_start = forces_per_contact * contact_index; for (int i = 0; i < forces_per_contact; ++i) { + int force_row = contact_jacobian_row_start + i; + if (contact_force_start > 0){ + if (i == 0){ + force_row = contact_index; + }else{ + force_row = contact_points.size() + (forces_per_contact - 1) * contact_index + i; + } + } auto force = lcmt_force(); force.contact_point[0] = contact_points.at(contact_index)[0]; force.contact_point[1] = contact_points.at(contact_index)[1]; @@ -75,14 +87,14 @@ void C3OutputSender::OutputC3Forces( // expressed in the world frame force.contact_force[0] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c.row(contact_var_start + i)(6); + J_c.row(force_row)(6); force.contact_force[1] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c.row(contact_var_start + i)(7); + J_c.row(force_row)(7); force.contact_force[2] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c.row(contact_var_start + i)(8); - c3_forces_output->forces[contact_var_start + i] = force; + J_c.row(force_row)(8); + c3_forces_output->forces[contact_jacobian_row_start + i] = force; } } c3_forces_output->utime = context.get_time() * 1e6; From cd5ea5b9ad37376d358be0a017488f22ce4361ba Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 15 May 2024 14:15:49 -0400 Subject: [PATCH 713/758] minor renaming for visualizing force code --- .../c3_output_systems.cc | 42 ++++++++++--------- 1 file changed, 23 insertions(+), 19 deletions(-) diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index 6c5af1b5a9..02e1c81fb1 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -58,43 +58,47 @@ void C3OutputSender::OutputC3Forces( this->EvalInputValue>>(context, lcs_contact_info_port_); MatrixXd J_c = contact_info->first; int contact_force_start = c3_solution->lambda_sol_.rows() - J_c.rows(); - auto contact_points = contact_info->second; - int forces_per_contact = contact_info->first.rows() / contact_points.size(); - c3_forces_output->num_forces = forces_per_contact * contact_points.size(); + bool using_stewart_and_trinkle_model = contact_force_start > 0; + + auto num_contact_points = contact_info->second; + int forces_per_contact = contact_info->first.rows() / num_contact_points.size(); + + c3_forces_output->num_forces = forces_per_contact * num_contact_points.size(); c3_forces_output->forces.resize(c3_forces_output->num_forces); int contact_var_start; - int contact_jacobian_row_start; - for (int contact_index = 0; contact_index < contact_points.size(); + int force_index; + for (int contact_index = 0; contact_index < num_contact_points.size(); ++contact_index) { contact_var_start = contact_force_start + forces_per_contact * contact_index; - contact_jacobian_row_start = forces_per_contact * contact_index; + force_index = forces_per_contact * contact_index; for (int i = 0; i < forces_per_contact; ++i) { - int force_row = contact_jacobian_row_start + i; - if (contact_force_start > 0){ + int contact_jacobian_row = force_index + i; // index for anitescu model + if (using_stewart_and_trinkle_model){ // index for stweart and trinkle model if (i == 0){ - force_row = contact_index; - }else{ - force_row = contact_points.size() + (forces_per_contact - 1) * contact_index + i; + contact_jacobian_row = contact_index; + } else { + contact_jacobian_row = num_contact_points.size() + (forces_per_contact - 1) * contact_index + i; } } auto force = lcmt_force(); - force.contact_point[0] = contact_points.at(contact_index)[0]; - force.contact_point[1] = contact_points.at(contact_index)[1]; - force.contact_point[2] = contact_points.at(contact_index)[2]; - // 6, 7, 8 are the indices for the x,y,z components of the tray + force.contact_point[0] = num_contact_points.at(contact_index)[0]; + force.contact_point[1] = num_contact_points.at(contact_index)[1]; + force.contact_point[2] = num_contact_points.at(contact_index)[2]; // TODO(yangwill): find a cleaner way to figure out the equivalent forces + // VISUALIZING FORCES FOR THE FIRST KNOT POINT + // 6, 7, 8 are the indices for the x,y,z components of the tray // expressed in the world frame force.contact_force[0] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c.row(force_row)(6); + J_c.row(contact_jacobian_row)(6); force.contact_force[1] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c.row(force_row)(7); + J_c.row(contact_jacobian_row)(7); force.contact_force[2] = c3_solution->lambda_sol_(contact_var_start + i, 0) * - J_c.row(force_row)(8); - c3_forces_output->forces[contact_jacobian_row_start + i] = force; + J_c.row(contact_jacobian_row)(8); + c3_forces_output->forces[force_index + i] = force; } } c3_forces_output->utime = context.get_time() * 1e6; From 9196ed8816a2a30cc914a5fdf66cbab56fcda8b7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 15 May 2024 14:52:45 -0400 Subject: [PATCH 714/758] updating readme --- examples/franka/README.md | 4 ++++ .../parameters/c3_options/franka_c3_options_supports.yaml | 6 +++--- 2 files changed, 7 insertions(+), 3 deletions(-) diff --git a/examples/franka/README.md b/examples/franka/README.md index 387dea710e..4f29b104fd 100644 --- a/examples/franka/README.md +++ b/examples/franka/README.md @@ -1,5 +1,9 @@ ## Experiment Instructions +Central repo for C3 and its examples, including: +- https://arxiv.org/abs/2405.08731 + +This branch/repo is being constantly updated so examples may be unstable. ## Simulated Robot diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index f8961955b4..c4fd059c42 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -6,8 +6,8 @@ delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' #options are 'stewart_and_trinkle' or 'anitescu' -contact_model : 'stewart_and_trinkle' -#contact_model: 'anitescu' +#contact_model : 'stewart_and_trinkle' +contact_model: 'anitescu' warm_start: true use_predicted_x0: true use_robust_formulation: false @@ -26,7 +26,7 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], workspace_margins: 0.05 u_horizontal_limits: [-10, 10] -u_vertical_limits: [-200, 200] +u_vertical_limits: [0, 30] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] dt: 0.075 From be5fec7b495a201cee1113cdfd2c4cfc66a00a51 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 16 May 2024 10:33:17 -0400 Subject: [PATCH 715/758] only using robust projection on the last admm iteration --- .../franka_c3_options_supports_st.yaml | 67 +++++++++++++++++++ .../franka_c3_controller_params.yaml | 2 +- solvers/c3.cc | 65 +++++++++--------- 3 files changed, 101 insertions(+), 33 deletions(-) create mode 100644 examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml new file mode 100644 index 0000000000..81b80cf8c3 --- /dev/null +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml @@ -0,0 +1,67 @@ +admm_iter: 3 +rho: 0 # does not do anything +rho_scale: 3 +num_threads: 5 +delta_option: 1 +#options are 'MIQP' or 'QP' +projection_type: 'MIQP' +#options are 'stewart_and_trinkle' or 'anitescu' +contact_model : 'stewart_and_trinkle' +#contact_model: 'anitescu' +warm_start: true +use_predicted_x0: true +use_robust_formulation: true +end_on_qp_step: false +solve_time_filter_alpha: 0.95 +#set to 0 to publish as fast as possible +publish_frequency : 0 +#publish_frequency: 15 + +# End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] +workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], + [0.0, 1.0, 0.0, -0.1, 0.1], + [0.0, 0.0, 1.0, 0.35, 0.7]] +#world_y_limits: [-0.1, 0.1] +#world_z_limits: [0.35, 0.7] +workspace_margins: 0.05 + +u_horizontal_limits: [-10, 10] +u_vertical_limits: [0, 30] + +mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] +dt: 0.05 +solve_dt: 0.05 +num_friction_directions: 2 +num_contacts: 7 +N: 5 +gamma: 1.0 # discount factor on MPC costs + +#matrix scaling +w_Q: 50 +w_R: 50 +#Penalty on all decision variables, assuming scalar +w_G: 0.15 +#Penalty on all decision variables, assuming scalar +w_U: 0.1 + +#State Tracking Error, assuming diagonal +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, + 5, 5, 15, 10, 10, 1, 5, 5, 5] +#Penalty on efforts, assuming diagonal +r_vector: [0.15, 0.15, 0.1] + +#Penalty on matching projected variables +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [1, 1, 1, 1, 1, 1, 1] +g_lambda_n: [50, 50, 50, 50, 50, 50, 50] +g_lambda_t: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] +g_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] +g_u: [1, 1, 1] + +#Penalty on matching the QP variables +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_gamma: [10, 10, 10, 10, 10, 10, 10] +u_lambda_n: [250, 250, 250, 250, 250, 250, 250] +u_lambda_t: [250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250] +u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] +u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 40a59b106a..89efab600c 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,6 +1,6 @@ scene_index: 1 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, - examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, + examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_wall.yaml, examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml] diff --git a/solvers/c3.cc b/solvers/c3.cc index 92d30b3b38..842abd49ac 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -378,37 +378,6 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, return *z_sol_; } -void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double lower_bound, - double upper_bound, int constraint) { - if (constraint == 1) { - for (int i = 1; i < N_; i++) { - user_constraints_.push_back( - prog_.AddLinearConstraint(A, lower_bound, upper_bound, x_.at(i))); - } - } - - if (constraint == 2) { - for (int i = 0; i < N_; i++) { - user_constraints_.push_back( - prog_.AddLinearConstraint(A, lower_bound, upper_bound, u_.at(i))); - } - } - - if (constraint == 3) { - for (int i = 0; i < N_; i++) { - user_constraints_.push_back(prog_.AddLinearConstraint( - A, lower_bound, upper_bound, lambda_.at(i))); - } - } -} - -void C3::RemoveConstraints() { - for (auto& userconstraint : user_constraints_) { - prog_.RemoveConstraint(userconstraint); - } - user_constraints_.clear(); -} - vector C3::SolveProjection(const vector& G, vector& WZ, int admm_iteration) { vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); @@ -422,7 +391,7 @@ vector C3::SolveProjection(const vector& G, #pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { - if (options_.use_robust_formulation) { + if (options_.use_robust_formulation && admm_iteration == (options_.admm_iter - 1)) { // only on the last iteration if (warm_start_) { if (i == N_ - 1) { deltaProj[i] = SolveRobustSingleProjection( @@ -457,5 +426,37 @@ vector C3::SolveProjection(const vector& G, return deltaProj; } +void C3::AddLinearConstraint(Eigen::RowVectorXd& A, double lower_bound, + double upper_bound, int constraint) { + if (constraint == 1) { + for (int i = 1; i < N_; i++) { + user_constraints_.push_back( + prog_.AddLinearConstraint(A, lower_bound, upper_bound, x_.at(i))); + } + } + + if (constraint == 2) { + for (int i = 0; i < N_; i++) { + user_constraints_.push_back( + prog_.AddLinearConstraint(A, lower_bound, upper_bound, u_.at(i))); + } + } + + if (constraint == 3) { + for (int i = 0; i < N_; i++) { + user_constraints_.push_back(prog_.AddLinearConstraint( + A, lower_bound, upper_bound, lambda_.at(i))); + } + } +} + +void C3::RemoveConstraints() { + for (auto& userconstraint : user_constraints_) { + prog_.RemoveConstraint(userconstraint); + } + user_constraints_.clear(); +} + + } // namespace solvers } // namespace dairlib From 52496c52ae61418584386ce272e25883d22e421f Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 16 May 2024 11:25:56 -0400 Subject: [PATCH 716/758] reasonably working params on fast computer --- .../franka_c3_options_supports.yaml | 14 ++++++------ .../franka_c3_options_supports_st.yaml | 12 +++++----- .../franka/parameters/franka_sim_params.yaml | 4 ++-- .../c3_output_systems.cc | 22 +++++++++---------- 4 files changed, 26 insertions(+), 26 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index c4fd059c42..06420f1fba 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -1,13 +1,13 @@ -admm_iter: 2 +admm_iter: 3 rho: 0 # does not do anything -rho_scale: 4 +rho_scale: 3 num_threads: 5 delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' #options are 'stewart_and_trinkle' or 'anitescu' -#contact_model : 'stewart_and_trinkle' -contact_model: 'anitescu' +contact_model : 'stewart_and_trinkle' +#contact_model: 'anitescu' warm_start: true use_predicted_x0: true use_robust_formulation: false @@ -26,10 +26,10 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], workspace_margins: 0.05 u_horizontal_limits: [-10, 10] -u_vertical_limits: [0, 30] +u_vertical_limits: [-100, 100] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] -dt: 0.075 +dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 @@ -38,7 +38,7 @@ gamma: 1.0 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 50 +w_R: 25 #Penalty on all decision variables, assuming scalar w_G: 0.15 #Penalty on all decision variables, assuming scalar diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml index 81b80cf8c3..b6832d1f21 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml @@ -1,6 +1,6 @@ -admm_iter: 3 +admm_iter: 5 rho: 0 # does not do anything -rho_scale: 3 +rho_scale: 2 num_threads: 5 delta_option: 1 #options are 'MIQP' or 'QP' @@ -45,10 +45,10 @@ w_G: 0.15 w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, +q_vector: [150, 150, 150, 0, 100, 100, 0, 15000, 15000, 25000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal -r_vector: [0.15, 0.15, 0.1] +r_vector: [0.15, 0.15, 0.05] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] @@ -61,7 +61,7 @@ g_u: [1, 1, 1] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_gamma: [10, 10, 10, 10, 10, 10, 10] -u_lambda_n: [250, 250, 250, 250, 250, 250, 250] -u_lambda_t: [250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250] +u_lambda_n: [300, 300, 300, 300, 300, 300, 300] +u_lambda_t: [300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300] u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] u_u: [30, 30, 30] \ No newline at end of file diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 9845ad9e2d..e9d72e3da7 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -37,7 +37,7 @@ world_z_limits: [[0.35, 0.7], external_force_scaling: [10.0, 10.0, 10.0] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.7 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], @@ -53,7 +53,7 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], visualize_workspace: false visualize_pose_trace: true -visualize_center_of_mass_plan: false +visualize_center_of_mass_plan: true visualize_c3_forces: true visualize_c3_object_state: true visualize_c3_end_effector_state: false diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index 02e1c81fb1..5d529541ca 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -60,15 +60,15 @@ void C3OutputSender::OutputC3Forces( int contact_force_start = c3_solution->lambda_sol_.rows() - J_c.rows(); bool using_stewart_and_trinkle_model = contact_force_start > 0; - auto num_contact_points = contact_info->second; - int forces_per_contact = contact_info->first.rows() / num_contact_points.size(); + auto contact_points = contact_info->second; + int forces_per_contact = contact_info->first.rows() / contact_points.size(); - c3_forces_output->num_forces = forces_per_contact * num_contact_points.size(); + c3_forces_output->num_forces = forces_per_contact * contact_points.size(); c3_forces_output->forces.resize(c3_forces_output->num_forces); int contact_var_start; int force_index; - for (int contact_index = 0; contact_index < num_contact_points.size(); + for (int contact_index = 0; contact_index < contact_points.size(); ++contact_index) { contact_var_start = contact_force_start + forces_per_contact * contact_index; force_index = forces_per_contact * contact_index; @@ -78,25 +78,25 @@ void C3OutputSender::OutputC3Forces( if (i == 0){ contact_jacobian_row = contact_index; } else { - contact_jacobian_row = num_contact_points.size() + (forces_per_contact - 1) * contact_index + i; + contact_jacobian_row = contact_points.size() + (forces_per_contact - 1) * contact_index + i - 1; } } auto force = lcmt_force(); - force.contact_point[0] = num_contact_points.at(contact_index)[0]; - force.contact_point[1] = num_contact_points.at(contact_index)[1]; - force.contact_point[2] = num_contact_points.at(contact_index)[2]; + force.contact_point[0] = contact_points.at(contact_index)[0]; + force.contact_point[1] = contact_points.at(contact_index)[1]; + force.contact_point[2] = contact_points.at(contact_index)[2]; // TODO(yangwill): find a cleaner way to figure out the equivalent forces // VISUALIZING FORCES FOR THE FIRST KNOT POINT // 6, 7, 8 are the indices for the x,y,z components of the tray // expressed in the world frame force.contact_force[0] = - c3_solution->lambda_sol_(contact_var_start + i, 0) * + c3_solution->lambda_sol_(contact_var_start + i, 1) * J_c.row(contact_jacobian_row)(6); force.contact_force[1] = - c3_solution->lambda_sol_(contact_var_start + i, 0) * + c3_solution->lambda_sol_(contact_var_start + i, 1) * J_c.row(contact_jacobian_row)(7); force.contact_force[2] = - c3_solution->lambda_sol_(contact_var_start + i, 0) * + c3_solution->lambda_sol_(contact_var_start + i, 1) * J_c.row(contact_jacobian_row)(8); c3_forces_output->forces[force_index + i] = force; } From 2205b12bc4baf19ce8b94844de22d3640d2d1633 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 16 May 2024 14:39:19 -0400 Subject: [PATCH 717/758] fixing constraint construction --- solvers/c3_miqp.cc | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index c15763d0da..57fa9f24f8 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -243,7 +243,12 @@ VectorXd C3MIQP::SolveRobustSingleProjection( n_ + m_ + k_); single_lambda_expr.addTerms(single_lambda_coeffs, delta_k, n_ + m_ + k_); - if (constraint_rows % 2 == 1) { + /// Constraint explanation + /// if i % 2 == 0: + /// lambda_1 - lambda_2 <= mu_l / mu * (lambda_1 + lambda_2) + /// else: + /// lambda_2 - lambda_1 <= mu_l / mu * (lambda_1 + lambda_2) + if (i % 2 == 1) { model.addConstr(subtraction_constraint_expr <= (0.4 / 0.6) * (addition_constraint_expr) + M * (reduced_friction_cone_binary[i])); @@ -256,6 +261,10 @@ VectorXd C3MIQP::SolveRobustSingleProjection( model.addConstr(tangential_velocity_expr <= M * (reduced_friction_cone_binary[i])); } + /// if i % 2 == 0: + /// lambda_1 = 0 + /// else: + /// lambda_2 = 0 model.addConstr(single_lambda_expr <= M * (1 - reduced_friction_cone_binary[i])); } From 2a1e45b4e2381ecb2648f0e5321292a3c0293809 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 16 May 2024 14:57:01 -0400 Subject: [PATCH 718/758] finally propering visualizing stewart and trinkle forces --- systems/trajectory_optimization/c3_output_systems.cc | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index 5d529541ca..efbba1eff0 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -74,11 +74,14 @@ void C3OutputSender::OutputC3Forces( force_index = forces_per_contact * contact_index; for (int i = 0; i < forces_per_contact; ++i) { int contact_jacobian_row = force_index + i; // index for anitescu model + int contact_var_index = contact_var_start + i; if (using_stewart_and_trinkle_model){ // index for stweart and trinkle model if (i == 0){ contact_jacobian_row = contact_index; + contact_var_index = contact_force_start + contact_index; } else { contact_jacobian_row = contact_points.size() + (forces_per_contact - 1) * contact_index + i - 1; + contact_var_index = contact_force_start + contact_points.size() + (forces_per_contact - 1) * contact_index + i - 1; } } auto force = lcmt_force(); @@ -90,13 +93,13 @@ void C3OutputSender::OutputC3Forces( // 6, 7, 8 are the indices for the x,y,z components of the tray // expressed in the world frame force.contact_force[0] = - c3_solution->lambda_sol_(contact_var_start + i, 1) * + c3_solution->lambda_sol_(contact_var_index, 1) * J_c.row(contact_jacobian_row)(6); force.contact_force[1] = - c3_solution->lambda_sol_(contact_var_start + i, 1) * + c3_solution->lambda_sol_(contact_var_index, 1) * J_c.row(contact_jacobian_row)(7); force.contact_force[2] = - c3_solution->lambda_sol_(contact_var_start + i, 1) * + c3_solution->lambda_sol_(contact_var_index, 1) * J_c.row(contact_jacobian_row)(8); c3_forces_output->forces[force_index + i] = force; } From 2f70695419467385cf49da1746f45f5170808839 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 16 May 2024 15:00:53 -0400 Subject: [PATCH 719/758] minor fixes --- .../franka_c3_options_supports.yaml | 24 +++++++++---------- .../c3_output_systems.cc | 6 ++--- 2 files changed, 15 insertions(+), 15 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 06420f1fba..462a1d9927 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -1,13 +1,13 @@ -admm_iter: 3 +admm_iter: 2 rho: 0 # does not do anything -rho_scale: 3 +rho_scale: 4 num_threads: 5 delta_option: 1 #options are 'MIQP' or 'QP' projection_type: 'MIQP' #options are 'stewart_and_trinkle' or 'anitescu' -contact_model : 'stewart_and_trinkle' -#contact_model: 'anitescu' +#contact_model : 'stewart_and_trinkle' +contact_model: 'anitescu' warm_start: true use_predicted_x0: true use_robust_formulation: false @@ -26,10 +26,10 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], workspace_margins: 0.05 u_horizontal_limits: [-10, 10] -u_vertical_limits: [-100, 100] +u_vertical_limits: [0, 30] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] -dt: 0.05 +dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 @@ -38,7 +38,7 @@ gamma: 1.0 # discount factor on MPC costs #matrix scaling w_Q: 50 -w_R: 25 +w_R: 50 #Penalty on all decision variables, assuming scalar w_G: 0.15 #Penalty on all decision variables, assuming scalar @@ -53,15 +53,15 @@ r_vector: [0.15, 0.15, 0.1] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma: [1, 1, 1, 1, 1, 1, 1] -g_lambda_n: [50, 50, 50, 50, 50, 50, 50] -g_lambda_t: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] +g_lambda_n: [1, 1, 1, 1, 1, 1, 1] +g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] g_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] g_u: [1, 1, 1] #Penalty on matching the QP variables u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -u_gamma: [10, 10, 10, 10, 10, 10, 10] -u_lambda_n: [250, 250, 250, 250, 250, 250, 250] -u_lambda_t: [250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250, 250] +u_gamma: [1, 1, 1, 1, 1, 1, 1] +u_lambda_n: [1, 1, 1, 1, 1, 1, 1] +u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] u_u: [30, 30, 30] \ No newline at end of file diff --git a/systems/trajectory_optimization/c3_output_systems.cc b/systems/trajectory_optimization/c3_output_systems.cc index efbba1eff0..61691633e3 100644 --- a/systems/trajectory_optimization/c3_output_systems.cc +++ b/systems/trajectory_optimization/c3_output_systems.cc @@ -93,13 +93,13 @@ void C3OutputSender::OutputC3Forces( // 6, 7, 8 are the indices for the x,y,z components of the tray // expressed in the world frame force.contact_force[0] = - c3_solution->lambda_sol_(contact_var_index, 1) * + c3_solution->lambda_sol_(contact_var_index, 0) * J_c.row(contact_jacobian_row)(6); force.contact_force[1] = - c3_solution->lambda_sol_(contact_var_index, 1) * + c3_solution->lambda_sol_(contact_var_index, 0) * J_c.row(contact_jacobian_row)(7); force.contact_force[2] = - c3_solution->lambda_sol_(contact_var_index, 1) * + c3_solution->lambda_sol_(contact_var_index, 0) * J_c.row(contact_jacobian_row)(8); c3_forces_output->forces[force_index + i] = force; } From 62b4b56f050f1145c4608c065cddc0a28ee1ddcb Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 22 May 2024 15:41:46 -0400 Subject: [PATCH 720/758] still working on getting framework to be more reliable --- .../franka_c3_options_supports.yaml | 2 +- .../franka_c3_options_supports_st.yaml | 2 +- .../franka_c3_options_translation.yaml | 45 ++++++++++--------- .../franka_c3_controller_params.yaml | 2 +- .../franka/parameters/franka_sim_params.yaml | 8 ++-- .../franka/systems/plate_balancing_target.cc | 6 +-- 6 files changed, 33 insertions(+), 32 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 462a1d9927..9ff0b05c60 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -14,7 +14,7 @@ use_robust_formulation: false end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible -publish_frequency : 0 +publish_frequency: 0 #publish_frequency: 15 # End Effector Workspace Limits Specified as Linear Constraints [x, y, z, lb, ub] diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml index b6832d1f21..b310284759 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml @@ -29,7 +29,7 @@ u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] -dt: 0.05 +dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 7 diff --git a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml index 3246562d33..7edcd83299 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml @@ -1,6 +1,6 @@ -admm_iter: 4 +admm_iter: 3 rho: 0.0 -rho_scale: 2 +rho_scale: 4 num_threads: 5 delta_option: 1 # options are 'MIQP' or 'QP' @@ -10,10 +10,11 @@ projection_type: 'MIQP' contact_model: 'stewart_and_trinkle' warm_start: true use_predicted_x0: true +use_robust_formulation: false end_on_qp_step: false -solve_time_filter_alpha: 0.9 +solve_time_filter_alpha: 0.95 #publish_frequency : 0 -publish_frequency: 25 +publish_frequency: 0 # Workspace Limits workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], @@ -21,11 +22,11 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], [0.0, 0.0, 1.0, 0.3, 0.6]] workspace_margins: 0.05 -u_horizontal_limits: [-10, 10] -u_vertical_limits: [0, 30] +u_horizontal_limits: [-50, 50] +u_vertical_limits: [-50, 50] mu: [0.6, 0.6, 0.6] -dt: 0.05 +dt: 0.075 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 @@ -34,31 +35,31 @@ gamma: 1 # matrix scaling w_Q: 50 -w_R: 1 +w_R: 50 # Penalty on all decision variables, assuming scalar -w_G: 1 +w_G: 0.1 # Penalty on all decision variables, assuming scalar -w_U: 0.5 +w_U: 0.1 # State Tracking Error, assuming diagonal -q_vector: [175, 175, 175, 10, 10, 10, 10, 5000, 5000, 5000, - 5, 5, 10, 1, 1, 1, 5, 5, 5] +q_vector: [175, 175, 175, 1, 1, 1, 1, 15000, 15000, 15000, + 5, 5, 5, 10, 10, 10, 5, 5, 5] # Penalty on efforts, assuming diagonal -r_vector: [0.1, 0.1, 0.1] +r_vector: [0.15, 0.15, 0.1] # Penalty on all decision variables -g_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] -g_gamma: [1, 1, 1] -g_lambda_n: [1, 1, 1] -g_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] +g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma: [50, 50, 50] +g_lambda_n: [50, 50, 50] +g_lambda_t: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] g_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] g_u: [1, 1, 1] # Penalty on all decision variables -u_x: [1, 1, 1, 1, 1, 1, 1, 10, 10, 10, 1, 1, 1, 10, 10, 10, 10, 10, 10] -u_gamma: [1, 1, 1] -u_lambda_n: [1, 1, 1] -u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +u_gamma: [100, 100, 100] +u_lambda_n: [100, 100, 100] +u_lambda_t: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_lambda: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] -u_u: [10, 10, 10] +u_u: [30, 30, 30] diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 89efab600c..e9e6d50a8a 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,4 +1,4 @@ -scene_index: 1 +scene_index: 0 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index e9d72e3da7..1962394621 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 32 actuator_delay: 0.000 -scene_index: 1 +scene_index: 0 visualize_drake_sim: false publish_efforts: true publish_object_velocities: true @@ -37,7 +37,7 @@ world_z_limits: [[0.35, 0.7], external_force_scaling: [10.0, 10.0, 10.0] dt: 0.0005 -realtime_rate: 0.7 +realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], @@ -52,8 +52,8 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1. , 0. , 0. , 0. , -1.55, 0.0, 0.0 ]] visualize_workspace: false -visualize_pose_trace: true +visualize_pose_trace: false visualize_center_of_mass_plan: true visualize_c3_forces: true visualize_c3_object_state: true -visualize_c3_end_effector_state: false +visualize_c3_end_effector_state: true diff --git a/examples/franka/systems/plate_balancing_target.cc b/examples/franka/systems/plate_balancing_target.cc index fd74c19e4e..a503d18af1 100644 --- a/examples/franka/systems/plate_balancing_target.cc +++ b/examples/franka/systems/plate_balancing_target.cc @@ -129,14 +129,14 @@ void PlateBalancingTargetGenerator::CalcEndEffectorTarget( } end_effector_position[2] -= end_effector_thickness_; // place end effector below tray - if (end_effector_position[0] > 0.6) { - end_effector_position[0] = 0.6; // keep it within the workspace - } if (radio_out->value()[13] > 0) { end_effector_position(0) += radio_out->value()[0] * x_scale_; end_effector_position(1) += radio_out->value()[1] * y_scale_; end_effector_position(2) += radio_out->value()[2] * z_scale_; } + if (end_effector_position[0] > 0.6) { + end_effector_position[0] = 0.6; // keep it within the workspace + } // end_effector_position(0) = 0.55; // end_effector_position(1) = 0.1 * sin(4 * context.get_time()); // end_effector_position(2) = 0.45 + 0.1 * cos(2 *context.get_time()) - From 8850d56f5ef8f1a138f37ca4d7710be21d45467b Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 27 May 2024 12:08:14 -0400 Subject: [PATCH 721/758] cleaning up code and debugging anitescu --- .../franka_c3_options_supports_st.yaml | 6 ++-- .../franka_c3_controller_params.yaml | 4 +-- .../franka/parameters/franka_sim_params.yaml | 8 ++--- examples/franka/urdf/cylinder_object.urdf | 6 ---- solvers/c3.cc | 30 +++++++++++-------- solvers/c3.h | 6 ++-- solvers/lcs_factory.cc | 18 +++++------ 7 files changed, 38 insertions(+), 40 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml index b310284759..e7dd3a7715 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml @@ -25,7 +25,7 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], #world_z_limits: [0.35, 0.7] workspace_margins: 0.05 -u_horizontal_limits: [-10, 10] +u_horizontal_limits: [-10, 20] u_vertical_limits: [0, 30] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] @@ -45,10 +45,10 @@ w_G: 0.15 w_U: 0.1 #State Tracking Error, assuming diagonal -q_vector: [150, 150, 150, 0, 100, 100, 0, 15000, 15000, 25000, +q_vector: [150, 150, 150, 0, 1, 1, 0, 15000, 15000, 15000, 5, 5, 15, 10, 10, 1, 5, 5, 5] #Penalty on efforts, assuming diagonal -r_vector: [0.15, 0.15, 0.05] +r_vector: [0.15, 0.15, 0.1] #Penalty on matching projected variables g_x: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index e9e6d50a8a..40a59b106a 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,6 +1,6 @@ -scene_index: 0 +scene_index: 1 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, - examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml, + examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_wall.yaml, examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml] diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 1962394621..9845ad9e2d 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 32 actuator_delay: 0.000 -scene_index: 0 +scene_index: 1 visualize_drake_sim: false publish_efforts: true publish_object_velocities: true @@ -52,8 +52,8 @@ q_init_object: [[1, 0, 0, 0, 0.55, 0.0, 0.0], [1. , 0. , 0. , 0. , -1.55, 0.0, 0.0 ]] visualize_workspace: false -visualize_pose_trace: false -visualize_center_of_mass_plan: true +visualize_pose_trace: true +visualize_center_of_mass_plan: false visualize_c3_forces: true visualize_c3_object_state: true -visualize_c3_end_effector_state: true +visualize_c3_end_effector_state: false diff --git a/examples/franka/urdf/cylinder_object.urdf b/examples/franka/urdf/cylinder_object.urdf index 245967ebe5..5832f2b11b 100644 --- a/examples/franka/urdf/cylinder_object.urdf +++ b/examples/franka/urdf/cylinder_object.urdf @@ -19,11 +19,5 @@ - - - - - - diff --git a/solvers/c3.cc b/solvers/c3.cc index 842abd49ac..d76baf0550 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -236,19 +236,22 @@ void C3::Solve(const VectorXd& x0) { WD.at(i) = delta.at(i) - w.at(i); } - vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); - - if (!options_.end_on_qp_step) { - *z_sol_ = delta; - z_sol_->at(0).segment(0, n_) = x0; - for (int i = 1; i < N_; ++i) { - z_sol_->at(i).segment(0, n_) = - A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + - D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); - } - } +// vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); + *w_sol_ = w; *delta_sol_ = delta; + *z_sol_ = delta; + +// if (!options_.end_on_qp_step) { +// *z_sol_ = delta; +// z_sol_->at(0).segment(0, n_) = x0; +// x_sol_->at(0) = x0; +// for (int i = 1; i < N_; ++i) { +// z_sol_->at(i).segment(0, n_) = +// A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + +// D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); +// } +// } for (int i = 0; i < N_; ++i) { lambda_sol_->at(i) *= AnDn_; @@ -391,7 +394,9 @@ vector C3::SolveProjection(const vector& G, #pragma omp parallel for num_threads(options_.num_threads) for (i = 0; i < N_; i++) { - if (options_.use_robust_formulation && admm_iteration == (options_.admm_iter - 1)) { // only on the last iteration + if (options_.use_robust_formulation && + admm_iteration == + (options_.admm_iter - 1)) { // only on the last iteration if (warm_start_) { if (i == N_ - 1) { deltaProj[i] = SolveRobustSingleProjection( @@ -457,6 +462,5 @@ void C3::RemoveConstraints() { user_constraints_.clear(); } - } // namespace solvers } // namespace dairlib diff --git a/solvers/c3.h b/solvers/c3.h index e90c3d5505..e68c606c9e 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -122,9 +122,9 @@ class C3 { std::vector> warm_start_u_; bool warm_start_; const int N_; - const int n_; - const int m_; - const int k_; + const int n_; // n_x + const int m_; // n_lambda + const int k_; // n_u private: std::vector A_; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 6c4726fdf5..d979afb2d8 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -218,15 +218,6 @@ LCS LCSFactory::LinearizePlantToLCS( H.block(2 * n_contacts, 0, 2 * n_contacts * num_friction_directions, n_u) = dt * J_t * AB_v_u; -// W_x.block(0, 0, n_lambda, n_q) = J_t * AB_v_q; -// W_x.block(0, n_q, n_lambda, n_v) = J_t + J_t * AB_v_v; -// W_l.block(0, n_contacts, n_contacts, n_contacts) = J_t * (MinvJ_c_T); -// W_l.block(0, n_contacts + n_contacts, n_contacts, 2 * n_contacts * num_friction_directions) = J_t * (MinvJ_c_T); -// W_l.block(0, 0, n_lambda, ) = J_t * (MinvJ_c_T); -// W_l.block(0, 0, n_lambda, ) = J_t * (MinvJ_c_T); -// W_u = J_t * (AB_v_u); -// w = J_t * (d_v); - c.segment(n_contacts, n_contacts) = phi + dt * dt * J_n * d_v - J_n * vNqdot * plant.GetPositions(context); c.segment(2 * n_contacts, 2 * n_contacts * num_friction_directions) = @@ -241,6 +232,7 @@ LCS LCSFactory::LinearizePlantToLCS( mu_vec(i) * VectorXd::Ones(2 * num_friction_directions); } MatrixXd anitescu_mu_matrix = anitescu_mu_vec.asDiagonal(); + // Constructing friction bases MatrixXd J_c = E_t.transpose() * J_n + anitescu_mu_matrix * J_t; MatrixXd MinvJ_c_T = M_ldlt.solve(J_c.transpose()); @@ -248,15 +240,23 @@ LCS LCSFactory::LinearizePlantToLCS( D.block(0, 0, n_q, n_lambda) = dt * dt * qdotNv * MinvJ_c_T; D.block(n_q, 0, n_v, n_lambda) = dt * MinvJ_c_T; + // q component of complementarity constraint E.block(0, 0, n_lambda, n_q) = dt * J_c * AB_v_q + E_t.transpose() * J_n * vNqdot / dt; E.block(0, n_q, n_lambda, n_v) = J_c + dt * J_c * AB_v_v; + // lambda component of complementarity constraint F = dt * J_c * MinvJ_c_T; + // u component of complementarity constraint H = dt * J_c * AB_v_u; + // constant component of complementarity constraint c = E_t.transpose() * phi / dt + dt * J_c * d_v - E_t.transpose() * J_n * vNqdot * plant.GetPositions(context) / dt; + + // Anitescu model needs an explicit formulation for the tangential + // components in order to appropriately activate the robust constraint + // (TODO): yangwill do another pass to verify this formulation W_x.block(0, 0, n_lambda, n_q) = J_t * AB_v_q; W_x.block(0, n_q, n_lambda, n_v) = J_t + J_t * AB_v_v; W_l = J_t * (MinvJ_c_T); From 66e3a764c3ed11398d19186ebfe912f0f81b457c Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 27 May 2024 12:08:31 -0400 Subject: [PATCH 722/758] trying init state constraint in projection step --- solvers/c3_miqp.cc | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 57fa9f24f8..dd8d79ed6e 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -67,6 +67,15 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.setObjective(obj, GRB_MINIMIZE); +// for (int i = 0; i < n_; ++i){ +// VectorXd identity = VectorXd::Zero(n_ + m_ + k_); +// double* init_state_coeff = identity.data(); +// init_state_coeff[i] = 1; +// GRBLinExpr init_state_expr = 0; +// init_state_expr.addTerms(init_state_coeff, delta_k, n_ + m_ + k_); +// model.addConstr(init_state_expr == delta_c[i]); +// } + int M = 1000; // big M variable double coeff[n_ + m_ + k_]; double coeff2[n_ + m_ + k_]; @@ -162,6 +171,16 @@ VectorXd C3MIQP::SolveRobustSingleProjection( obj.addTerm(U(i, i), delta_k[i], delta_k[i]); } +// for (int i = 0; i < n_; ++i){ +// VectorXd identity = VectorXd::Zero(n_ + m_ + k_); +// double* init_state_coeff = identity.data(); +// init_state_coeff[i] = 1; +// GRBLinExpr init_state_expr = 0; +// init_state_expr.addTerms(init_state_coeff, delta_k, n_ + m_ + k_); +// model.addConstr(init_state_expr == delta_c[i]); +// } + + model.setObjective(obj, GRB_MINIMIZE); int M = 1000; // big M variable From 2e92c6cbd14d1df01f8cc393f2aac577ce28375c Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 28 May 2024 13:16:03 -0400 Subject: [PATCH 723/758] cleaning up initial state constraint in projection, and robust constraint --- .../franka_c3_options_supports_st.yaml | 2 +- solvers/c3.cc | 25 +++--- solvers/c3_miqp.cc | 86 ++++++------------- 3 files changed, 38 insertions(+), 75 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml index e7dd3a7715..46deca02d4 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml @@ -25,7 +25,7 @@ workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], #world_z_limits: [0.35, 0.7] workspace_margins: 0.05 -u_horizontal_limits: [-10, 20] +u_horizontal_limits: [-10, 10] u_vertical_limits: [0, 30] mu: [0.6, 0.6, 0.6, 0.1, 0.1, 0.1, 0.1] diff --git a/solvers/c3.cc b/solvers/c3.cc index d76baf0550..2e2aeb2615 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -236,22 +236,21 @@ void C3::Solve(const VectorXd& x0) { WD.at(i) = delta.at(i) - w.at(i); } -// vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); + vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); *w_sol_ = w; *delta_sol_ = delta; - *z_sol_ = delta; - -// if (!options_.end_on_qp_step) { -// *z_sol_ = delta; -// z_sol_->at(0).segment(0, n_) = x0; -// x_sol_->at(0) = x0; -// for (int i = 1; i < N_; ++i) { -// z_sol_->at(i).segment(0, n_) = -// A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + -// D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); -// } -// } + + if (!options_.end_on_qp_step) { + *z_sol_ = delta; + z_sol_->at(0).segment(0, n_) = x0; + x_sol_->at(0) = x0; + for (int i = 1; i < N_; ++i) { + z_sol_->at(i).segment(0, n_) = + A_.at(i - 1) * x_sol_->at(i - 1) + B_.at(i - 1) * u_sol_->at(i - 1) + + D_.at(i - 1) * lambda_sol_->at(i - 1) + d_.at(i - 1); + } + } for (int i = 0; i < N_; ++i) { lambda_sol_->at(i) *= AnDn_; diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index dd8d79ed6e..c53d71b89e 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -67,14 +67,12 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.setObjective(obj, GRB_MINIMIZE); -// for (int i = 0; i < n_; ++i){ -// VectorXd identity = VectorXd::Zero(n_ + m_ + k_); -// double* init_state_coeff = identity.data(); -// init_state_coeff[i] = 1; -// GRBLinExpr init_state_expr = 0; -// init_state_expr.addTerms(init_state_coeff, delta_k, n_ + m_ + k_); -// model.addConstr(init_state_expr == delta_c[i]); -// } + // initial state constraint + if (warm_start_index == 0){ + for (int i = 0; i < n_; ++i){ + model.addConstr(delta_k[i] == delta_c[i]); + } + } int M = 1000; // big M variable double coeff[n_ + m_ + k_]; @@ -171,14 +169,12 @@ VectorXd C3MIQP::SolveRobustSingleProjection( obj.addTerm(U(i, i), delta_k[i], delta_k[i]); } -// for (int i = 0; i < n_; ++i){ -// VectorXd identity = VectorXd::Zero(n_ + m_ + k_); -// double* init_state_coeff = identity.data(); -// init_state_coeff[i] = 1; -// GRBLinExpr init_state_expr = 0; -// init_state_expr.addTerms(init_state_coeff, delta_k, n_ + m_ + k_); -// model.addConstr(init_state_expr == delta_c[i]); -// } + // initial state constraint + if (warm_start_index == 0){ + for (int i = 0; i < n_; ++i){ + model.addConstr(delta_k[i] == delta_c[i]); + } + } model.setObjective(obj, GRB_MINIMIZE); @@ -211,71 +207,39 @@ VectorXd C3MIQP::SolveRobustSingleProjection( model.addConstr(activation_expr + c(i) <= M * binary[i]); } - double subtraction_coeffs[n_ + m_ + k_]; - double addition_coeffs[n_ + m_ + k_]; - double tangential_velocity_coeffs[n_ + m_ + k_]; - double single_lambda_coeffs[n_ + m_ + k_]; - MatrixXd addition_of_aligned_forces = MatrixXd::Zero(m_, n_ + m_ + k_); - MatrixXd subtraction_of_aligned_forces = MatrixXd::Zero(m_, n_ + m_ + k_); - - + double* tangential_velocity_coeffs; MatrixXd P_t(m_, n_ + m_ + k_); int constraint_rows = m_; -// P_t << W_x, W_l, W_u; + P_t << W_x, W_l, W_u; // stewart and trinkle - P_t << E, F, H; - MatrixXd P_t2 = P_t.bottomRows(((m_ / 6) * 4) / 7 * 3); - P_t = P_t2; - constraint_rows = P_t2.rows(); - for (int i = 0; i < constraint_rows; ++i) { - addition_of_aligned_forces(i, n_ + 2 * (i / 2) + 0) = 1; - addition_of_aligned_forces(i, n_ + 2 * (i / 2) + 1) = 1; - if (i % 2 == 0) { - subtraction_of_aligned_forces(i, n_ + i + 0) = -1; - subtraction_of_aligned_forces(i, n_ + i + 1) = 1; - } else { - subtraction_of_aligned_forces(i, n_ + i + 0) = -1; - subtraction_of_aligned_forces(i, n_ + i - 1) = 1; - } - } +// P_t << E, F, H; +// MatrixXd P_t2 = P_t.bottomRows(((m_ / 6) * 4) / 7 * 3); +// P_t = P_t2; +// constraint_rows = P_t2.rows(); for (int i = 0; i < constraint_rows; ++i) { reduced_friction_cone_binary[i] = model.addVar(0.0, 1.0, 0.0, GRB_BINARY); - GRBLinExpr subtraction_constraint_expr = 0; - GRBLinExpr addition_constraint_expr = 0; GRBLinExpr tangential_velocity_expr = 0; - GRBLinExpr single_lambda_expr = 0; - - /// convert VectorXd to double - for (int j = 0; j < n_ + m_ + k_; j++) { - addition_coeffs[j] = addition_of_aligned_forces(i, j); - subtraction_coeffs[j] = subtraction_of_aligned_forces(i, j); - tangential_velocity_coeffs[j] = P_t(i, j); - single_lambda_coeffs[j] = Mcons2(i, j); - } - - subtraction_constraint_expr.addTerms(subtraction_coeffs, delta_k, - n_ + m_ + k_); - addition_constraint_expr.addTerms(addition_coeffs, delta_k, n_ + m_ + k_); + tangential_velocity_coeffs = P_t.row(i).data(); tangential_velocity_expr.addTerms(tangential_velocity_coeffs, delta_k, n_ + m_ + k_); - single_lambda_expr.addTerms(single_lambda_coeffs, delta_k, n_ + m_ + k_); /// Constraint explanation /// if i % 2 == 0: /// lambda_1 - lambda_2 <= mu_l / mu * (lambda_1 + lambda_2) /// else: /// lambda_2 - lambda_1 <= mu_l / mu * (lambda_1 + lambda_2) + /// tangential velocity expr is the tangential velocity in the SAME direction as the friction force if (i % 2 == 1) { - model.addConstr(subtraction_constraint_expr <= - (0.4 / 0.6) * (addition_constraint_expr) + + model.addConstr(delta_k[n_ + i + 1] - delta_k[n_ + i + 0] <= + (0.5 / 0.6) * (delta_k[n_ + i + 1] + delta_k[n_ + i + 0]) + M * (reduced_friction_cone_binary[i])); model.addConstr(tangential_velocity_expr <= M * (reduced_friction_cone_binary[i])); } else { - model.addConstr(subtraction_constraint_expr <= - (0.4 / 0.6) * (addition_constraint_expr) + + model.addConstr(delta_k[n_ + i + 0] - delta_k[n_ + i + 1] <= + (0.5 / 0.6) * (delta_k[n_ + i + 1] + delta_k[n_ + i + 0]) + M * (reduced_friction_cone_binary[i])); model.addConstr(tangential_velocity_expr <= M * (reduced_friction_cone_binary[i])); @@ -284,7 +248,7 @@ VectorXd C3MIQP::SolveRobustSingleProjection( /// lambda_1 = 0 /// else: /// lambda_2 = 0 - model.addConstr(single_lambda_expr <= + model.addConstr(delta_k[n_ + i] <= M * (1 - reduced_friction_cone_binary[i])); } From d3908a4d35302e6cebe9394950b01855509bd2e8 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 28 May 2024 18:09:10 -0400 Subject: [PATCH 724/758] working on robust formulation --- bindings/pydairlib/franka/franka_env.py | 2 +- examples/franka/diagrams/full_diagram.cc | 2 +- examples/franka/franka_sim.cc | 2 +- examples/franka/franka_visualizer.cc | 2 +- examples/franka/full_diagram.cc | 2 +- .../franka_c3_options_supports.yaml | 2 +- .../franka/parameters/franka_sim_params.h | 4 +-- .../franka/parameters/franka_sim_params.yaml | 4 +-- solvers/c3_miqp.cc | 34 +++++++++++++------ 9 files changed, 33 insertions(+), 21 deletions(-) diff --git a/bindings/pydairlib/franka/franka_env.py b/bindings/pydairlib/franka/franka_env.py index ea7223b290..da50f5e476 100644 --- a/bindings/pydairlib/franka/franka_env.py +++ b/bindings/pydairlib/franka/franka_env.py @@ -118,7 +118,7 @@ def run_sim(intrinsics, gains): c3_controller.get_input_port_radio().FixValue(c3_controller_context, np.zeros(18)) logger_context = diagram.GetSubsystemContext(sim_state_logger, simulator.get_context()) - q = np.hstack((sim_params['q_init_franka'], sim_params['q_init_plate'][sim_params['scene_index']])) + q = np.hstack((sim_params['q_init_franka'], sim_params['q_init_tray'][sim_params['scene_index']])) v = np.zeros(plant.num_velocities()) plant.SetPositions(plant_context, q) diff --git a/examples/franka/diagrams/full_diagram.cc b/examples/franka/diagrams/full_diagram.cc index 5cdc53c396..a988919a05 100644 --- a/examples/franka/diagrams/full_diagram.cc +++ b/examples/franka/diagrams/full_diagram.cc @@ -128,7 +128,7 @@ int DoMain(int argc, char* argv[]) { VectorXd q = VectorXd::Zero(nq); q.head(7) = sim_params.q_init_franka; - q.tail(7) = sim_params.q_init_plate[sim_params.scene_index]; + q.tail(7) = sim_params.q_init_tray[sim_params.scene_index]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/franka_sim.cc b/examples/franka/franka_sim.cc index aed024062e..f047338d8d 100644 --- a/examples/franka/franka_sim.cc +++ b/examples/franka/franka_sim.cc @@ -211,7 +211,7 @@ int DoMain(int argc, char* argv[]) { q.segment(plant.num_positions(franka_index), plant.num_positions(tray_index)) = - sim_params.q_init_plate[sim_params.scene_index]; + sim_params.q_init_tray[sim_params.scene_index]; q.tail(plant.num_positions(object_index)) = sim_params.q_init_object[sim_params.scene_index]; diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index 10fffa12d9..bfda9ba177 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -225,7 +225,7 @@ int do_main(int argc, char* argv[]) { if (sim_params.visualize_pose_trace) { auto object_pose_drawer = builder.AddSystem( meshcat, - FindResourceOrThrow("examples/franka/urdf/tray_transparent.sdf"), + FindResourceOrThrow("examples/franka/urdf/tray.sdf"), "object_position_target", "object_orientation_target"); auto end_effector_pose_drawer = builder.AddSystem( meshcat, FindResourceOrThrow(sim_params.end_effector_model), diff --git a/examples/franka/full_diagram.cc b/examples/franka/full_diagram.cc index 3e3ea219f0..34365d0b8b 100644 --- a/examples/franka/full_diagram.cc +++ b/examples/franka/full_diagram.cc @@ -231,7 +231,7 @@ int DoMain(int argc, char* argv[]) { q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; q.tail(plant.num_positions(tray_index)) = - sim_params.q_init_plate[sim_params.scene_index]; + sim_params.q_init_tray[sim_params.scene_index]; plant.SetPositions(&plant_context, q); diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 9ff0b05c60..2e693a3bf3 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -10,7 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true -use_robust_formulation: false +use_robust_formulation: true end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible diff --git a/examples/franka/parameters/franka_sim_params.h b/examples/franka/parameters/franka_sim_params.h index 2441c5ce70..0835d92e10 100644 --- a/examples/franka/parameters/franka_sim_params.h +++ b/examples/franka/parameters/franka_sim_params.h @@ -23,7 +23,7 @@ struct FrankaSimParams { bool publish_object_velocities; Eigen::VectorXd q_init_franka; - std::vector q_init_plate; + std::vector q_init_tray; std::vector q_init_object; Eigen::VectorXd tool_attachment_frame; @@ -62,7 +62,7 @@ struct FrankaSimParams { a->Visit(DRAKE_NVP(publish_object_velocities)); a->Visit(DRAKE_NVP(q_init_franka)); - a->Visit(DRAKE_NVP(q_init_plate)); + a->Visit(DRAKE_NVP(q_init_tray)); a->Visit(DRAKE_NVP(q_init_object)); a->Visit(DRAKE_NVP(tool_attachment_frame)); diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 9845ad9e2d..26de64dc62 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -37,10 +37,10 @@ world_z_limits: [[0.35, 0.7], external_force_scaling: [10.0, 10.0, 10.0] dt: 0.0005 -realtime_rate: 1.0 +realtime_rate: 0.75 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] -q_init_plate: [[1, 0, 0, 0, 0.55, 0.0, 0.465], +q_init_tray: [[1, 0, 0, 0, 0.55, 0.0, 0.465], [1, 0, 0, 0, 0.7, 0.00, 0.485], [1. , 0. , 0. , 0. , 0.5889, 0.14 , 0.485], [0.8775826, 0, 0, 0.4794255, 0.55, 0.02, 0.46]] diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index c53d71b89e..9173435ec7 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -225,31 +225,43 @@ VectorXd C3MIQP::SolveRobustSingleProjection( tangential_velocity_expr.addTerms(tangential_velocity_coeffs, delta_k, n_ + m_ + k_); - /// Constraint explanation - /// if i % 2 == 0: - /// lambda_1 - lambda_2 <= mu_l / mu * (lambda_1 + lambda_2) - /// else: - /// lambda_2 - lambda_1 <= mu_l / mu * (lambda_1 + lambda_2) + /// Constraint explanation: + /// Adding a binary decision to either be: + /// - inside a conservative (mu_l) friction cone (stick) + /// or + /// - on the boundary of the original friction cone (mu) (slip) + /// where mu_l < mu + + /// The active constraint for the sticking condition is: + /// lambda_1 - lambda_2 <= mu_l / mu * (lambda_1 + lambda_2) + + /// The active constraint for the friction cone boundary is: + /// lambda_2 == 0 + /// where lambda_2 is the friction force in the sliding direction /// tangential velocity expr is the tangential velocity in the SAME direction as the friction force if (i % 2 == 1) { - model.addConstr(delta_k[n_ + i + 1] - delta_k[n_ + i + 0] <= - (0.5 / 0.6) * (delta_k[n_ + i + 1] + delta_k[n_ + i + 0]) + + model.addConstr(delta_k[n_ + i - 1] - delta_k[n_ + i] <= + (0.5 / 0.6) * (delta_k[n_ + i] + delta_k[n_ + i - 1]) + M * (reduced_friction_cone_binary[i])); model.addConstr(tangential_velocity_expr <= M * (reduced_friction_cone_binary[i])); + model.addConstr(delta_k[n_ + i] <= + M * (1 - reduced_friction_cone_binary[i])); } else { - model.addConstr(delta_k[n_ + i + 0] - delta_k[n_ + i + 1] <= - (0.5 / 0.6) * (delta_k[n_ + i + 1] + delta_k[n_ + i + 0]) + + model.addConstr(delta_k[n_ + i + 1] - delta_k[n_ + i] <= + (0.5 / 0.6) * (delta_k[n_ + i] + delta_k[n_ + i + 1]) + M * (reduced_friction_cone_binary[i])); model.addConstr(tangential_velocity_expr <= M * (reduced_friction_cone_binary[i])); + model.addConstr(delta_k[n_ + i] <= + M * (1 - reduced_friction_cone_binary[i])); } /// if i % 2 == 0: /// lambda_1 = 0 /// else: /// lambda_2 = 0 - model.addConstr(delta_k[n_ + i] <= - M * (1 - reduced_friction_cone_binary[i])); +// model.addConstr(delta_k[n_ + i] <= +// M * (1 - reduced_friction_cone_binary[i])); } model.optimize(); From f2ff8ed3bb02b1cad6532b982c824eb2933eb92f Mon Sep 17 00:00:00 2001 From: Will Yang Date: Wed, 5 Jun 2024 12:26:51 -0400 Subject: [PATCH 725/758] updating to work with drake lcm driver --- examples/franka/BUILD.bazel | 25 ++++- examples/franka/franka_bridge_driver_in.cc | 102 ++++++++++++++++++ ..._bridge.cc => franka_bridge_driver_out.cc} | 23 +--- .../franka_osc_controller_params.yaml | 2 +- .../franka/systems/franka_state_translator.cc | 8 +- franka_hardware.pmd | 77 +++++++++++++ 6 files changed, 214 insertions(+), 23 deletions(-) create mode 100644 examples/franka/franka_bridge_driver_in.cc rename examples/franka/{franka_driver_bridge.cc => franka_bridge_driver_out.cc} (79%) create mode 100644 franka_hardware.pmd diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 6fcf9b3461..0a0ca93294 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -173,8 +173,29 @@ cc_binary( ) cc_binary( - name = "franka_driver_bridge", - srcs = ["franka_driver_bridge.cc"], + name = "franka_bridge_driver_out", + srcs = ["franka_bridge_driver_out.cc"], + data = [ + ":urdfs", + "@drake_models//:franka_description", + ], + deps = [ + ":parameters", + "//common", + "//examples/franka/systems:franka_state_translator", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_bridge_driver_in", + srcs = ["franka_bridge_driver_in.cc"], data = [ ":urdfs", "@drake_models//:franka_description", diff --git a/examples/franka/franka_bridge_driver_in.cc b/examples/franka/franka_bridge_driver_in.cc new file mode 100644 index 0000000000..3c696de18c --- /dev/null +++ b/examples/franka/franka_bridge_driver_in.cc @@ -0,0 +1,102 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "examples/franka/parameters/franka_drake_lcm_driver_channels.h" +#include "examples/franka/parameters/franka_lcm_channels.h" +#include "examples/franka/parameters/franka_sim_params.h" +#include "examples/franka/systems/franka_state_translator.h" +#include "multibody/multibody_utils.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +using drake::math::RigidTransform; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using dairlib::systems::RobotInputReceiver; +using dairlib::systems::RobotOutputSender; +using dairlib::systems::SubvectorPassThrough; +using dairlib::systems::TimestampedVector; + +DEFINE_string(lcm_channels, + "examples/franka/parameters/lcm_channels_hardware.yaml", + "Filepath containing lcm channels"); +DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_drake_lcm_driver_channels.yaml", + "Filepath containing ROS channels"); + +namespace dairlib { + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + FrankaLcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(FLAGS_lcm_channels); + FrankaDrakeLcmDriverChannels franka_driver_channel_params = + drake::yaml::LoadYamlFile(FLAGS_franka_driver_channels); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + "examples/franka/parameters/franka_sim_params.yaml"); + + DiagramBuilder builder; + + MultibodyPlant plant(0.0); + + Parser parser(&plant); + parser.AddModelsFromUrl(sim_params.franka_model)[0]; + Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); + RigidTransform R_X_W = RigidTransform( + drake::math::RotationMatrix(), franka_origin); + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("panda_link0"), + R_X_W); + plant.Finalize(); + + auto pos_map = multibody::MakeNameToPositionsMap(plant); + auto vel_map = multibody::MakeNameToVelocitiesMap(plant); + auto act_map = multibody::MakeNameToActuatorsMap(plant); + + auto pos_names = multibody::ExtractOrderedNamesFromMap(pos_map); + auto vel_names = multibody::ExtractOrderedNamesFromMap(vel_map); + auto act_names = multibody::ExtractOrderedNamesFromMap(act_map); + + /* -------------------------------------------------------------------------------------------*/ + drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); + + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + franka_driver_channel_params.franka_command_channel, &lcm, + 1.0 / 1000.0)); + auto franka_command_translator = builder.AddSystem(); + + builder.Connect(*franka_command_translator, *franka_command_pub); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("franka_bridge_driver_in")); + const auto& diagram = *owned_diagram; + + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_command_translator, + lcm_channel_params.franka_input_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/franka_driver_bridge.cc b/examples/franka/franka_bridge_driver_out.cc similarity index 79% rename from examples/franka/franka_driver_bridge.cc rename to examples/franka/franka_bridge_driver_out.cc index 74a996cb1b..304feb8031 100644 --- a/examples/franka/franka_driver_bridge.cc +++ b/examples/franka/franka_bridge_driver_out.cc @@ -37,7 +37,7 @@ using dairlib::systems::TimestampedVector; DEFINE_string(lcm_channels, "examples/franka/parameters/lcm_channels_hardware.yaml", "Filepath containing lcm channels"); -DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_driver_channels.yaml", +DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_drake_lcm_driver_channels.yaml", "Filepath containing ROS channels"); namespace dairlib { @@ -76,35 +76,22 @@ int DoMain(int argc, char* argv[]) { /* -------------------------------------------------------------------------------------------*/ drake::lcm::DrakeLcm lcm("udpm://239.255.76.67:7667?ttl=0"); - auto franka_status_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - franka_driver_channel_params.franka_status_channel, &lcm)); - auto franka_command_sub = - builder.AddSystem(LcmSubscriberSystem::Make( - lcm_channel_params.franka_input_channel, &lcm)); + auto franka_state_pub = builder.AddSystem(LcmPublisherSystem::Make( lcm_channel_params.franka_state_channel, &lcm, 1.0 / 1000.0)); - auto franka_command_pub = - builder.AddSystem(LcmPublisherSystem::Make( - franka_driver_channel_params.franka_command_channel, &lcm, - 1.0 / 1000.0)); auto franka_state_translator = builder.AddSystem( pos_names, vel_names, act_names); -auto franka_command_translator = builder.AddSystem(); - builder.Connect(*franka_status_sub, *franka_state_translator); builder.Connect(*franka_state_translator, *franka_state_pub); - builder.Connect(*franka_command_sub, *franka_command_translator); - builder.Connect(*franka_command_translator, *franka_command_pub); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_lcm_ros_bridge")); + owned_diagram->set_name(("franka_bridge_driver_out")); const auto& diagram = *owned_diagram; - systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_status_sub, + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_state_translator, franka_driver_channel_params.franka_status_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/franka/parameters/franka_osc_controller_params.yaml b/examples/franka/parameters/franka_osc_controller_params.yaml index 8fa4ae1673..8b98e49dcc 100644 --- a/examples/franka/parameters/franka_osc_controller_params.yaml +++ b/examples/franka/parameters/franka_osc_controller_params.yaml @@ -21,7 +21,7 @@ impact_tau: 0.000 mu: 1.0 # unused end_effector_acceleration: 10 track_end_effector_orientation: false -cancel_gravity_compensation: false +cancel_gravity_compensation: true enforce_acceleration_constraints: false publish_debug_info: true diff --git a/examples/franka/systems/franka_state_translator.cc b/examples/franka/systems/franka_state_translator.cc index 7698de6c44..46277ddb52 100644 --- a/examples/franka/systems/franka_state_translator.cc +++ b/examples/franka/systems/franka_state_translator.cc @@ -43,12 +43,16 @@ void FrankaStateOutTranslator::OutputFrankaState( this->EvalInputValue(context, panda_status_); output->utime = panda_status->utime; output->position = panda_status->joint_position; + output->num_positions = panda_status->num_joints; + output->num_velocities = panda_status->num_joints; + output->num_efforts = panda_status->num_joints; +// output->position_names = std::vector(output->num_positions, "double"); output->velocity = panda_status->joint_velocity; output->effort = panda_status->joint_torque; } FrankaEffortsInTranslator::FrankaEffortsInTranslator() { - this->set_name("franka_state_translator"); + this->set_name("franka_command_translator"); robot_input_ = this->DeclareAbstractInputPort("franka_state", @@ -57,7 +61,7 @@ FrankaEffortsInTranslator::FrankaEffortsInTranslator() { franka_command_output_ = this->DeclareAbstractOutputPort( - "lcmt_robot_output", + "lcmt_panda_command", &FrankaEffortsInTranslator::OutputFrankaCommand) .get_index(); } diff --git a/franka_hardware.pmd b/franka_hardware.pmd new file mode 100644 index 0000000000..ca24114a18 --- /dev/null +++ b/franka_hardware.pmd @@ -0,0 +1,77 @@ +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/franka/franka_visualizer --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; + host = "localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/Cassie/cassie_xbox_remote"; + host = "localhost"; + } + cmd "logger" { + exec = "python3 start_logging.py hw"; + host = "localhost"; + } + cmd "record_video" { + exec = "python3 record_video.py"; + host = "localhost"; + } +} + +group "controllers (hardware)" { + cmd "franka_osc" { + exec = "bazel-bin/examples/franka/franka_osc_controller --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; + host = "localhost"; + } + cmd "franka_c3" { + exec = "bazel-bin/examples/franka/franka_c3_controller --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; + host = "localhost"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "localhost"; + } +} + +group "drivers" { + cmd "franka_driver_out" { + exec = "bazel-bin/examples/franka/franka_bridge_driver_out"; + host = "localhost"; + } + cmd "franka_driver_in" { + exec = "bazel-bin/examples/franka/franka_bridge_driver_in"; + host = "localhost"; + } + cmd "position_driver" { + exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=position"; + host = "franka_control"; + } + cmd "torque_driver" { + exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=torque"; + host = "franka_control"; + } +} + + +script "start_franka_osc" { + stop cmd "franka_driver_out"; + stop cmd "franka_driver_in"; + stop cmd "franka_osc"; + stop cmd "torque_driver"; + start cmd "record_video"; + start cmd "logger"; + wait ms 1000; + start cmd "franka_driver_out"; + start cmd "franka_driver_in"; + start cmd "franka_osc"; + start cmd "torque_driver"; +} + +script "stop_experiment" { + stop group "drivers"; + stop group "controllers (hardware)"; + stop cmd "record_video"; + stop cmd "logger"; +} From 7cf1cdaf9ae3062cb32ca77abf7bc0aaf6e4c85b Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 5 Jun 2024 14:00:15 -0400 Subject: [PATCH 726/758] updaing visualization --- WORKSPACE | 22 ++----- .../pydairlib/analysis/log_plotter_franka.py | 1 + bindings/pydairlib/multibody/multibody_py.cc | 2 +- examples/Cassie/osc/high_level_command.cc | 2 +- examples/franka/franka_visualizer.cc | 28 ++++++--- .../franka/parameters/franka_sim_params.yaml | 2 +- examples/franka/urdf/plate_end_effector.urdf | 2 +- multibody/multipose_visualizer.cc | 6 +- multibody/multipose_visualizer.h | 2 +- solvers/c3_miqp.cc | 10 ++-- .../lcm_visualization_systems.cc | 60 +++++++++---------- 11 files changed, 71 insertions(+), 66 deletions(-) diff --git a/WORKSPACE b/WORKSPACE index f280d1a894..2d5e35a75e 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -19,11 +19,12 @@ DRAKE_CHECKSUM = "78cf62c177c41f8415ade172c1e6eb270db619f07c4b043d5148e1f35be8da #DRAKE_CHECKSUM = "0" * 64 # Load an environment variable. -load("//:environ.bzl", "drake_repository") -load("//:environ.bzl", "inekf_repository") +load("//:environ.bzl", "drake_repository", "inekf_repository") + +drake_repository(name = "drake_path") + +inekf_repository(name = "inekf_path") -drake_repository(name="drake_path") -inekf_repository(name="inekf_path") load("@drake_path//:environ.bzl", "DAIRLIB_LOCAL_DRAKE_PATH") load("@inekf_path//:environ.bzl", "DAIRLIB_LOCAL_INEKF_PATH") @@ -66,10 +67,6 @@ load("@dairlib//tools/workspace/osqp:repository.bzl", "osqp_repository") osqp_repository(name = "osqp") -load("@dairlib//tools/workspace/drake_models:repository.bzl", "drake_models_repository") - -drake_models_repository(name = "drake_models") - # Prebuilt ROS workspace new_local_repository( name = "ros", @@ -120,9 +117,6 @@ INEKF_CHECKSUM = "f87e3262b0c9c9237881fcd539acd1c60000f97dfdfa47b0ae53cb7a0f3256 "inekf" if DAIRLIB_LOCAL_INEKF_PATH else "inekf_ignored", ) -# Maybe download InEKF. -load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive") - http_archive( name = _http_inekf_repo_name, sha256 = INEKF_CHECKSUM, @@ -140,8 +134,6 @@ local_repository( path = DAIRLIB_LOCAL_INEKF_PATH, ) -load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive") - # buildifier is written in Go and hence needs rules_go to be built. # See https://github.com/bazelbuild/rules_go for the up to date setup instructions. http_archive( @@ -153,12 +145,10 @@ http_archive( ], ) -load("@io_bazel_rules_go//go:deps.bzl", "go_rules_dependencies") +load("@io_bazel_rules_go//go:deps.bzl", "go_register_toolchains", "go_rules_dependencies") go_rules_dependencies() -load("@io_bazel_rules_go//go:deps.bzl", "go_register_toolchains") - go_register_toolchains(version = "1.17.2") http_archive( diff --git a/bindings/pydairlib/analysis/log_plotter_franka.py b/bindings/pydairlib/analysis/log_plotter_franka.py index 8652f38a78..45a1ffcc54 100644 --- a/bindings/pydairlib/analysis/log_plotter_franka.py +++ b/bindings/pydairlib/analysis/log_plotter_franka.py @@ -152,6 +152,7 @@ def main(): # plot.plot(c3_tracking_target['t'], c3_tracking_target['x'][:, 7:8], subplot_index = 1) # plot.axes[0].set_ylim([0.4, 0.7]) # plot.add_legend(['tray_des_x', 'tray_des_y', 'tray_des_z', 'tray_x', 'tray_y', 'tray_z'], subplot_index = 1) + if True: plotter = plot_styler.PlotStyler() # zero_vel_threshold = 0.00001 diff --git a/bindings/pydairlib/multibody/multibody_py.cc b/bindings/pydairlib/multibody/multibody_py.cc index 2a993d785e..3e08e2e505 100644 --- a/bindings/pydairlib/multibody/multibody_py.cc +++ b/bindings/pydairlib/multibody/multibody_py.cc @@ -23,7 +23,7 @@ PYBIND11_MODULE(multibody, m) { .def(py::init()) .def(py::init()) .def(py::init()) - .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses")) + .def("DrawPoses", &MultiposeVisualizer::DrawPoses, py::arg("poses"), py::arg("poses")) .def("GetMeshcat", &MultiposeVisualizer::GetMeshcat); m.def("ConnectTrajectoryVisualizer", diff --git a/examples/Cassie/osc/high_level_command.cc b/examples/Cassie/osc/high_level_command.cc index 0852ce0d93..ff85634953 100644 --- a/examples/Cassie/osc/high_level_command.cc +++ b/examples/Cassie/osc/high_level_command.cc @@ -99,7 +99,7 @@ HighLevelCommand::HighLevelCommand( &HighLevelCommand::CopyDesiredHorizontalVel) .get_index(); // Declare update event - DeclareForcedDiscreteUpdateEvent(&HighLevelCommand::DiscreteVariableUpdate); + DeclarePerStepDiscreteUpdateEvent(&HighLevelCommand::DiscreteVariableUpdate); // Discrete state which stores the desired yaw velocity des_vel_idx_ = DeclareDiscreteState(VectorXd::Zero(3)); diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index bfda9ba177..d60c7c45a0 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -6,6 +6,7 @@ #include #include #include +#include #include "common/eigen_utils.h" #include "common/find_resource.h" @@ -180,8 +181,7 @@ int do_main(int argc, char* argv[]) { drake::geometry::MeshcatVisualizerParams params; params.publish_period = 1.0 / sim_params.visualizer_publish_rate; auto meshcat = std::make_shared(); - auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( - &builder, scene_graph, meshcat, std::move(params)); + meshcat->SetCameraPose(scene_params.camera_pose, scene_params.camera_target); @@ -277,6 +277,9 @@ int do_main(int argc, char* argv[]) { builder.Connect(*tray_state_sub, *tray_state_receiver); builder.Connect(*object_state_sub, *object_state_receiver); + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, scene_graph, meshcat, std::move(params)); + auto diagram = builder.Build(); auto context = diagram->CreateDefaultContext(); @@ -296,17 +299,24 @@ int do_main(int argc, char* argv[]) { /// Use the simulator to drive at a fixed rate /// If set_publish_every_time_step is true, this publishes twice /// Set realtime rate. Otherwise, runs as fast as possible - auto stepper = + auto simulator = std::make_unique>(*diagram, std::move(context)); - stepper->set_publish_every_time_step(false); - stepper->set_publish_at_initialization(false); - stepper->set_target_realtime_rate( + simulator->set_publish_every_time_step(false); + simulator->set_publish_at_initialization(false); + simulator->set_target_realtime_rate( 1.0); // may need to change this to param.real_time_rate? - stepper->Initialize(); + simulator->Initialize(); drake::log()->info("visualizer started"); - - stepper->AdvanceTo(std::numeric_limits::infinity()); + meshcat->get_mutable_recording().set_loop_mode(drake::geometry::MeshcatAnimation::LoopMode::kLoopRepeat); + meshcat->StartRecording(); +// simulator->AdvanceTo(std::numeric_limits::infinity()); + simulator->AdvanceTo(20.0); + meshcat->StopRecording(); + meshcat->PublishRecording(); + std::ofstream outfile("visualization.html"); + outfile << meshcat->StaticHtml() < - + diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index d921100430..beb9e1c282 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -98,15 +98,19 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, diagram_context_ = diagram_->CreateDefaultContext(); } -void MultiposeVisualizer::DrawPoses(MatrixXd poses) { +void MultiposeVisualizer::DrawPoses(MatrixXd poses, std::optional time_in_recording) { // Set positions for individual instances auto& plant_context = diagram_->GetMutableSubsystemContext(*plant_, diagram_context_.get()); + for (int i = 0; i < num_poses_; i++) { plant_->SetPositions( &plant_context, model_indices_.at(i), poses.block(0, i, plant_->num_positions(model_indices_.at(i)), 1)); } + if (time_in_recording){ + diagram_context_->SetTime(time_in_recording.value()); + } // Publish diagram diagram_->ForcedPublish(*diagram_context_); diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index a88fbb3ecd..0c8a1b1a23 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -55,7 +55,7 @@ class MultiposeVisualizer { /// Draws the poses in the given (num_positions x num_poses) matrix /// Note: the matrix can have extra rows (e.g. velocities), which will be /// ignored. - void DrawPoses(Eigen::MatrixXd poses); + void DrawPoses(Eigen::MatrixXd poses, std::optional time_in_recording = std::nullopt); const std::shared_ptr GetMeshcat() { return meshcat_; diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 9173435ec7..1d1e4d3a37 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -68,11 +68,11 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, model.setObjective(obj, GRB_MINIMIZE); // initial state constraint - if (warm_start_index == 0){ - for (int i = 0; i < n_; ++i){ - model.addConstr(delta_k[i] == delta_c[i]); - } - } +// if (warm_start_index == 0){ +// for (int i = 0; i < n_; ++i){ +// model.addConstr(delta_k[i] == delta_c[i]); +// } +// } int M = 1000; // big M variable double coeff[n_ + m_ + k_]; diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index ba76ab6de8..e879ad3249 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -246,7 +246,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( auto force = force_trajectory.value(robot_time); const std::string& force_path_root = force_path_ + "/u_lcs/"; - meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + meshcat_->SetTransform(force_path_root, RigidTransformd(pose), context.get_time()); const std::string& force_arrow_path = force_path_root + "arrow"; auto force_norm = force.norm(); @@ -254,24 +254,24 @@ drake::systems::EventStatus LcmForceDrawer::DrawForce( if (force_norm >= 0.01) { meshcat_->SetTransform( force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2)), context.get_time()); const double height = force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", - {0, 0, 0.5 * height}); + {0, 0, 0.5 * height}, context.get_time()); // Note: Meshcat does not fully support non-uniform scaling (see #18095). // We get away with it here since there is no rotation on this frame and // no children in the kinematic tree. meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", - {1, 1, height}); + {1, 1, height}, context.get_time()); // Translate the arrowheads. const double arrowhead_height = radius_ * 2.0; meshcat_->SetTransform( force_arrow_path + "/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), - Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true); + Vector3d{0, 0, height + arrowhead_height}), context.get_time()); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", true, context.get_time()); } else { - meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false); + meshcat_->SetProperty(force_path_ + "/u_lcs", "visible", false, context.get_time()); } return drake::systems::EventStatus::Succeeded(); } @@ -312,29 +312,29 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( const VectorXd pose = Eigen::Map( c3_forces->forces[i].contact_point, 3); - meshcat_->SetTransform(force_path_root, RigidTransformd(pose)); + meshcat_->SetTransform(force_path_root, RigidTransformd(pose), context.get_time()); // Stretch the cylinder in z. const std::string& force_arrow_path = force_path_root + "arrow"; meshcat_->SetTransform( force_arrow_path, - RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2))); + RigidTransformd(RotationMatrixd::MakeFromOneVector(force, 2)), context.get_time()); const double height = force_norm / newtons_per_meter_; meshcat_->SetProperty(force_arrow_path + "/cylinder", "position", - {0, 0, 0.5 * height}); + {0, 0, 0.5 * height}, context.get_time()); // Note: Meshcat does not fully support non-uniform scaling (see // #18095). We get away with it here since there is no rotation on this // frame and no children in the kinematic tree. meshcat_->SetProperty(force_arrow_path + "/cylinder", "scale", - {1, 1, height}); + {1, 1, height}, context.get_time()); // Translate the arrowheads. const double arrowhead_height = radius_ * 2.0; meshcat_->SetTransform( force_arrow_path + "/head", RigidTransformd(RotationMatrixd::MakeXRotation(M_PI), - Vector3d{0, 0, height + arrowhead_height})); - meshcat_->SetProperty(force_path_root, "visible", true); + Vector3d{0, 0, height + arrowhead_height}), context.get_time()); + meshcat_->SetProperty(force_path_root, "visible", true, context.get_time()); } else { - meshcat_->SetProperty(force_path_root, "visible", false); + meshcat_->SetProperty(force_path_root, "visible", false, context.get_time()); } } return drake::systems::EventStatus::Succeeded(); @@ -404,19 +404,19 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( auto z_axis_transform_ee = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), 0.5 * Vector3d{0.0, 0.0, 0.05}); - meshcat_->SetTransform(c3_target_object_path_ + "/x-axis", x_axis_transform); - meshcat_->SetTransform(c3_target_object_path_ + "/y-axis", y_axis_transform); - meshcat_->SetTransform(c3_target_object_path_ + "/z-axis", z_axis_transform); - meshcat_->SetTransform(c3_actual_object_path_ + "/x-axis", x_axis_transform); - meshcat_->SetTransform(c3_actual_object_path_ + "/y-axis", y_axis_transform); - meshcat_->SetTransform(c3_actual_object_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/x-axis", x_axis_transform, 0.0); + meshcat_->SetTransform(c3_target_object_path_ + "/y-axis", y_axis_transform, 0.0); + meshcat_->SetTransform(c3_target_object_path_ + "/z-axis", z_axis_transform, 0.0); + meshcat_->SetTransform(c3_actual_object_path_ + "/x-axis", x_axis_transform, 0.0); + meshcat_->SetTransform(c3_actual_object_path_ + "/y-axis", y_axis_transform, 0.0); + meshcat_->SetTransform(c3_actual_object_path_ + "/z-axis", z_axis_transform, 0.0); if (draw_ee_){ - meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); - meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); - meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); - meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee, 0.0); + meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee, 0.0); + meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee, 0.0); + meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee, 0.0); + meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee, 0.0); + meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee, 0.0); } DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); @@ -453,24 +453,24 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( Eigen::Quaterniond(c3_target->state[3], c3_target->state[4], c3_target->state[5], c3_target->state[6]), Vector3d{c3_target->state[7], c3_target->state[8], - c3_target->state[9]})); + c3_target->state[9]}), context.get_time()); meshcat_->SetTransform( c3_actual_object_path_, RigidTransformd( Eigen::Quaterniond(c3_actual->state[3], c3_actual->state[4], c3_actual->state[5], c3_actual->state[6]), Vector3d{c3_actual->state[7], c3_actual->state[8], - c3_actual->state[9]})); + c3_actual->state[9]}), context.get_time()); } if (draw_ee_) { meshcat_->SetTransform( c3_target_ee_path_, RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], - c3_target->state[2]})); + c3_target->state[2]}), context.get_time()); meshcat_->SetTransform( c3_actual_ee_path_, RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], - c3_actual->state[2]})); + c3_actual->state[2]}), context.get_time()); } return drake::systems::EventStatus::Succeeded(); } From 938a8159aa816ca688e12f74312ff3adb72c4b36 Mon Sep 17 00:00:00 2001 From: William Yang Date: Wed, 5 Jun 2024 17:27:25 -0400 Subject: [PATCH 727/758] cleaning up code --- examples/franka/franka_bridge_driver_in.cc | 5 +-- examples/franka/franka_bridge_driver_out.cc | 5 +-- examples/franka/franka_visualizer.cc | 20 +++++----- .../franka_osc_controller_params.yaml | 2 +- examples/franka/start_logging.py | 39 +++++++++++++++++++ 5 files changed, 54 insertions(+), 17 deletions(-) create mode 100644 examples/franka/start_logging.py diff --git a/examples/franka/franka_bridge_driver_in.cc b/examples/franka/franka_bridge_driver_in.cc index 3c696de18c..c08ba518d4 100644 --- a/examples/franka/franka_bridge_driver_in.cc +++ b/examples/franka/franka_bridge_driver_in.cc @@ -38,7 +38,7 @@ DEFINE_string(lcm_channels, "examples/franka/parameters/lcm_channels_hardware.yaml", "Filepath containing lcm channels"); DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_drake_lcm_driver_channels.yaml", - "Filepath containing ROS channels"); + "Filepath containing drake franka driver channels"); namespace dairlib { @@ -57,7 +57,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant); - parser.AddModelsFromUrl(sim_params.franka_model)[0]; + parser.AddModelsFromUrl(sim_params.franka_model); Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); @@ -86,7 +86,6 @@ int DoMain(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_bridge_driver_in")); - const auto& diagram = *owned_diagram; systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), franka_command_translator, diff --git a/examples/franka/franka_bridge_driver_out.cc b/examples/franka/franka_bridge_driver_out.cc index 304feb8031..ce0e80f25f 100644 --- a/examples/franka/franka_bridge_driver_out.cc +++ b/examples/franka/franka_bridge_driver_out.cc @@ -38,7 +38,7 @@ DEFINE_string(lcm_channels, "examples/franka/parameters/lcm_channels_hardware.yaml", "Filepath containing lcm channels"); DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_drake_lcm_driver_channels.yaml", - "Filepath containing ROS channels"); + "Filepath containing drake franka driver channels"); namespace dairlib { @@ -57,7 +57,7 @@ int DoMain(int argc, char* argv[]) { MultibodyPlant plant(0.0); Parser parser(&plant); - parser.AddModelsFromUrl(sim_params.franka_model)[0]; + parser.AddModelsFromUrl(sim_params.franka_model); Eigen::Vector3d franka_origin = Eigen::VectorXd::Zero(3); RigidTransform R_X_W = RigidTransform( drake::math::RotationMatrix(), franka_origin); @@ -88,7 +88,6 @@ int DoMain(int argc, char* argv[]) { auto owned_diagram = builder.Build(); owned_diagram->set_name(("franka_bridge_driver_out")); - const auto& diagram = *owned_diagram; systems::LcmDrivenLoop loop( &lcm, std::move(owned_diagram), franka_state_translator, diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index d60c7c45a0..d370bd6d71 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -307,16 +307,16 @@ int do_main(int argc, char* argv[]) { 1.0); // may need to change this to param.real_time_rate? simulator->Initialize(); - drake::log()->info("visualizer started"); - meshcat->get_mutable_recording().set_loop_mode(drake::geometry::MeshcatAnimation::LoopMode::kLoopRepeat); - meshcat->StartRecording(); -// simulator->AdvanceTo(std::numeric_limits::infinity()); - simulator->AdvanceTo(20.0); - meshcat->StopRecording(); - meshcat->PublishRecording(); - std::ofstream outfile("visualization.html"); - outfile << meshcat->StaticHtml() <AdvanceTo(std::numeric_limits::infinity()); + // meshcat->get_mutable_recording().set_loop_mode(drake::geometry::MeshcatAnimation::LoopMode::kLoopRepeat); + // meshcat->StartRecording(); + + // simulator->AdvanceTo(18.0); + // meshcat->StopRecording(); + // meshcat->PublishRecording(); + // std::ofstream outfile("visualization.html"); + // outfile << meshcat->StaticHtml() < Date: Thu, 6 Jun 2024 12:43:25 -0400 Subject: [PATCH 728/758] updating franka hardware procman --- examples/franka/franka_hardware.pmd | 53 +++++--------------- franka_hardware.pmd | 77 ----------------------------- 2 files changed, 13 insertions(+), 117 deletions(-) delete mode 100644 franka_hardware.pmd diff --git a/examples/franka/franka_hardware.pmd b/examples/franka/franka_hardware.pmd index 496a270d39..ca24114a18 100644 --- a/examples/franka/franka_hardware.pmd +++ b/examples/franka/franka_hardware.pmd @@ -1,10 +1,3 @@ -group "simulations" { - cmd "franka_sim" { - exec = "bazel-bin/examples/franka/franka_sim"; - host = "localhost"; - } -} - group "operator" { cmd "visualizer" { exec = "bazel-bin/examples/franka/franka_visualizer --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; @@ -42,30 +35,15 @@ group "debug" { } } -group "dispatchers" { - cmd "ros_lcm_bridge" { - exec = "bazel-bin/examples/franka/franka_ros_lcm_bridge"; +group "drivers" { + cmd "franka_driver_out" { + exec = "bazel-bin/examples/franka/franka_bridge_driver_out"; host = "localhost"; } - cmd "lcm_ros_bridge" { - exec = "bazel-bin/examples/franka/franka_lcm_ros_bridge"; + cmd "franka_driver_in" { + exec = "bazel-bin/examples/franka/franka_bridge_driver_in"; host = "localhost"; } -} - -group "drivers" { - cmd "move_to_start" { - exec = "roslaunch franka_example_controllers move_to_start.launch robot_ip:=172.16.0.2 load_gripper:=false"; - host = "franka_control"; - } - cmd "torque_passthrough_controller" { - exec = "roslaunch franka_example_controllers torque_passthrough_controller.launch robot_ip:=172.16.0.2 load_gripper:=false"; - host = "franka_control"; - } - cmd "move_to_osc_pose" { - exec = "roslaunch franka_example_controllers move_to_start_osc.launch robot_ip:=172.16.0.2 load_gripper:=false"; - host = "franka_control"; - } cmd "position_driver" { exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=position"; host = "franka_control"; @@ -74,31 +52,26 @@ group "drivers" { exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=torque"; host = "franka_control"; } - cmd "cam_sync" { - exec = "roslaunch kuka_vision kuka_online_cam_sync.launch"; - host = "tagslam"; - } } script "start_franka_osc" { - stop cmd "lcm_ros_bridge"; - stop cmd "ros_lcm_bridge"; + stop cmd "franka_driver_out"; + stop cmd "franka_driver_in"; stop cmd "franka_osc"; - stop cmd "torque_passthrough_controller"; + stop cmd "torque_driver"; start cmd "record_video"; start cmd "logger"; - start cmd "lcm_ros_bridge"; - start cmd "ros_lcm_bridge"; - start cmd "franka_osc"; wait ms 1000; - start cmd "torque_passthrough_controller"; + start cmd "franka_driver_out"; + start cmd "franka_driver_in"; + start cmd "franka_osc"; + start cmd "torque_driver"; } script "stop_experiment" { - stop cmd "torque_passthrough_controller" wait "stopped"; + stop group "drivers"; stop group "controllers (hardware)"; - stop group "dispatchers"; stop cmd "record_video"; stop cmd "logger"; } diff --git a/franka_hardware.pmd b/franka_hardware.pmd deleted file mode 100644 index ca24114a18..0000000000 --- a/franka_hardware.pmd +++ /dev/null @@ -1,77 +0,0 @@ -group "operator" { - cmd "visualizer" { - exec = "bazel-bin/examples/franka/franka_visualizer --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; - host = "localhost"; - } - cmd "xbox" { - exec = "bazel-bin/examples/Cassie/cassie_xbox_remote"; - host = "localhost"; - } - cmd "logger" { - exec = "python3 start_logging.py hw"; - host = "localhost"; - } - cmd "record_video" { - exec = "python3 record_video.py"; - host = "localhost"; - } -} - -group "controllers (hardware)" { - cmd "franka_osc" { - exec = "bazel-bin/examples/franka/franka_osc_controller --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; - host = "localhost"; - } - cmd "franka_c3" { - exec = "bazel-bin/examples/franka/franka_c3_controller --lcm_channels=examples/franka/parameters/lcm_channels_hardware.yaml"; - host = "localhost"; - } -} - -group "debug" { - cmd "lcm-spy" { - exec = "bazel-bin/lcmtypes/dair-lcm-spy"; - host = "localhost"; - } -} - -group "drivers" { - cmd "franka_driver_out" { - exec = "bazel-bin/examples/franka/franka_bridge_driver_out"; - host = "localhost"; - } - cmd "franka_driver_in" { - exec = "bazel-bin/examples/franka/franka_bridge_driver_in"; - host = "localhost"; - } - cmd "position_driver" { - exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=position"; - host = "franka_control"; - } - cmd "torque_driver" { - exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=torque"; - host = "franka_control"; - } -} - - -script "start_franka_osc" { - stop cmd "franka_driver_out"; - stop cmd "franka_driver_in"; - stop cmd "franka_osc"; - stop cmd "torque_driver"; - start cmd "record_video"; - start cmd "logger"; - wait ms 1000; - start cmd "franka_driver_out"; - start cmd "franka_driver_in"; - start cmd "franka_osc"; - start cmd "torque_driver"; -} - -script "stop_experiment" { - stop group "drivers"; - stop group "controllers (hardware)"; - stop cmd "record_video"; - stop cmd "logger"; -} From 2a76134c34aff658dfd3abd628a6fae9b6dc79f7 Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 6 Jun 2024 12:56:53 -0400 Subject: [PATCH 729/758] updating franka readme with new hardware instructions for 22.04 --- examples/franka/README.md | 25 +++++++++++++++++++------ examples/franka/franka_hardware.pmd | 8 ++++++-- 2 files changed, 25 insertions(+), 8 deletions(-) diff --git a/examples/franka/README.md b/examples/franka/README.md index 4f29b104fd..989a8dc943 100644 --- a/examples/franka/README.md +++ b/examples/franka/README.md @@ -26,26 +26,39 @@ bot-procman-sheriff -l franka_sim.pmd ## Physical Robot -Hardware experiment instructions are still listed for ROS and Ubuntu 20.04. Instructions for Ubuntu 22.04 are being worked on. +Hardware instructions updated for Ubuntu 22.04. We are no longer using ROS or ROS2 and instead relying on [drake-franka-driver](https://github.com/RobotLocomotion/drake-franka-driver), which works via LCM. Much thanks to the Drake developers who provided this! + +### Installing `drake-franka-driver` -1. Start the procman script containing a list of relevant processes. The primary differences from`franka_sim.pmd` script are the lcm_channels and the addition of a bridge linking ROS and LCM. ``` -bot-procman-sheriff -l franka_hardware.pmd +git clone https://github.com/RobotLocomotion/drake-franka-driver +cd drake-franka-driver +bazel build ... ``` + +### Running Experiments + +1. Start the procman script containing a list of relevant processes. The primary differences from`franka_sim.pmd` script are the lcm_channels and the drake-franka-driver and corresponding translators to communicate with the Franka via LCM. + + - In the root of dairlib: ``` bot-procman-sheriff -l examples/franka/franka_hardware.pmd ``` + - In the root of drake-franka-driver: ```bot-procman-deputy franka_control``` + 2. In the procman window, start the operator processes (meshcat visualizer and xbox controller) using the script `script:start_operator_commands`. Scripts are located in the top bar of the procman window. 3. The meshcat visualizer can be viewed by opening a browser and navigating to `localhost:7000` 4. The processes, except the C3 controller, can be run using the script `script:start_experiment`. This spawns the following processes: - - ROS/LCM bridge: communicates with FrankaRos to receive/publish franka state information and torque commands - - `bazel-bin/examples/franka/franka_osc_controller`: Low-level task-space controller that tracks task-space trajectories it receives from the MPC - `start_logging.py`: Starts a lcm-logger with an automatic naming convention for the log number. - `record_video.py`: Streams all available webcams to a .mp4 file corresponding to the log number. + - `torque_driver`: `drake-franka-driver` in torque control mode. + - `franka_driver_`(in/out): communicates with `drake-franka-driver` to receive/publish franka state information and torque commands. This is just a translator between Drake's Franka Panda specific lcm messages and the standardized robot commands that we use. + - `bazel-bin/examples/franka/franka_osc_controller`: Low-level task-space controller that tracks task-space trajectories it receives from the MPC + 5. For safety, start the C3 controller separately after verifying the rest of the processes have started successfully, by manually starting the `franka_c3` process. 6. Using the xbox controller, switch from tracking the teleop commands to the MPC plan by pressing "A". -7. Stop the experiment using `script:stop_experiment` +7. Stop the experiment using `script:stop_experiment`. This also stops logging and recording. ## Changing the scene diff --git a/examples/franka/franka_hardware.pmd b/examples/franka/franka_hardware.pmd index ca24114a18..b20047cf2c 100644 --- a/examples/franka/franka_hardware.pmd +++ b/examples/franka/franka_hardware.pmd @@ -54,8 +54,12 @@ group "drivers" { } } +script "start_operator_commands" { + restart cmd "visualizer"; + restart cmd "xbox"; +} -script "start_franka_osc" { +script "start_experiment" { stop cmd "franka_driver_out"; stop cmd "franka_driver_in"; stop cmd "franka_osc"; @@ -65,8 +69,8 @@ script "start_franka_osc" { wait ms 1000; start cmd "franka_driver_out"; start cmd "franka_driver_in"; - start cmd "franka_osc"; start cmd "torque_driver"; + start cmd "franka_osc"; } script "stop_experiment" { From 7f31546d519ec24e3ca47cd3b491a686ef25a9a0 Mon Sep 17 00:00:00 2001 From: William Yang Date: Mon, 10 Jun 2024 16:22:06 -0400 Subject: [PATCH 730/758] working on simple example --- bindings/pydairlib/franka/BUILD.bazel | 15 +++- .../pydairlib/franka/planar_box_example.py | 64 ++++++++++++++++ .../pydairlib/franka/urdf/active_block.sdf | 62 +++++++++++++++ .../pydairlib/franka/urdf/passive_block.sdf | 76 +++++++++++++++++++ 4 files changed, 214 insertions(+), 3 deletions(-) create mode 100644 bindings/pydairlib/franka/planar_box_example.py create mode 100644 bindings/pydairlib/franka/urdf/active_block.sdf create mode 100644 bindings/pydairlib/franka/urdf/passive_block.sdf diff --git a/bindings/pydairlib/franka/BUILD.bazel b/bindings/pydairlib/franka/BUILD.bazel index ae7aee9651..1767837afe 100644 --- a/bindings/pydairlib/franka/BUILD.bazel +++ b/bindings/pydairlib/franka/BUILD.bazel @@ -1,8 +1,5 @@ # -*- python -*- load("@drake//tools/install:install.bzl", "install") - -package(default_visibility = ["//visibility:public"]) - load( "@drake//tools/skylark:pybind.bzl", "drake_pybind_library", @@ -11,6 +8,8 @@ load( "pybind_py_library", ) +package(default_visibility = ["//visibility:public"]) + pybind_py_library( name = "controllers_py", cc_deps = [ @@ -57,6 +56,16 @@ py_binary( ], ) +py_binary( + name = "planar_box_example", + srcs = ["planar_box_example.py"], + data = [ + ], + deps = [ + "@drake//bindings/pydrake", + ], +) + # This determines how `PYTHONPATH` is configured, and how to install the # bindings. PACKAGE_INFO = get_pybind_package_info("//bindings") diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py new file mode 100644 index 0000000000..4a8dbf2baa --- /dev/null +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -0,0 +1,64 @@ +import numpy as np +from pydrake.all import ( + AddMultibodyPlantSceneGraph, + ContactVisualizer, + DiagramBuilder, + ExternallyAppliedSpatialForce, + LeafSystem, + List, + MeshcatVisualizer, + ModelVisualizer, + Parser, + Simulator, + SpatialForce, + StartMeshcat, + RigidTransform, + Value, +) + +class CubePusher(LeafSystem): + def __init__(self, plant): + LeafSystem.__init__(self) + forces_cls = Value[List[ExternallyAppliedSpatialForce]] + self.DeclareAbstractOutputPort( + "applied_force", lambda: forces_cls(), self.CalcOutput + ) + self.plant = plant + + def CalcOutput(self, context, output): + forces = [] + force = ExternallyAppliedSpatialForce() + force.body_index = self.plant.GetBodyByName("active_block").index() + force.F_Bq_W = SpatialForce( + tau=np.array([0, 0, 0]), + f=[4 * np.sin(1.0 * context.get_time()), 0, 0], + ) + forces.append(force) + output.set_value(forces) +def main(): + + + builder = DiagramBuilder() + + plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0005) + parser = Parser(plant) + parser.AddModels("bindings/pydairlib/franka/urdf/passive_block.sdf") + parser.AddModels("bindings/pydairlib/franka/urdf/active_block.sdf") + offset = RigidTransform(np.array([0.0, 0.0, 0.25])) + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("center")) + plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), offset) + plant.Finalize() + meshcat = StartMeshcat() + visualizer = MeshcatVisualizer.AddToBuilder(builder, scene_graph, meshcat) + ContactVisualizer.AddToBuilder(builder, plant, meshcat) + pusher = builder.AddSystem(CubePusher(plant)) + builder.Connect(pusher.get_output_port(), plant.get_applied_spatial_force_input_port()) + diagram = builder.Build() + meshcat.SetCameraPose(np.array([0, -3.0, 0.5]), np.array([0, 0.0, 0.0])) + simulator = Simulator(diagram) + context = simulator.get_context() + simulator.set_target_realtime_rate(1.0) + simulator.AdvanceTo(60.0) + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/bindings/pydairlib/franka/urdf/active_block.sdf b/bindings/pydairlib/franka/urdf/active_block.sdf new file mode 100644 index 0000000000..f799b89755 --- /dev/null +++ b/bindings/pydairlib/franka/urdf/active_block.sdf @@ -0,0 +1,62 @@ + + + + + + + + 0 0 0 0 0 0 + 1 + + 0.014167 + 0 + 0 + 0.33417 + 0 + 0.34667 + + + + 0 0 0 0 0 0 + + 0.5 0.2 0.2 0.6 + + + + 2.0 0.4 0.1 + + + + + 0 0 0 0 0 0 + + + 2.0 0.4 0.1 + + + + + 3.0e7 + 0.15 + 10 + 0.4 + + + + + center + active_block + + + 1 0 0 + + + -1.0 + 1.0 + 5.0 + + + + + + \ No newline at end of file diff --git a/bindings/pydairlib/franka/urdf/passive_block.sdf b/bindings/pydairlib/franka/urdf/passive_block.sdf new file mode 100644 index 0000000000..62d7ed122b --- /dev/null +++ b/bindings/pydairlib/franka/urdf/passive_block.sdf @@ -0,0 +1,76 @@ + + + + + + + + + + 0 0 0 0 0 0 + 0.2 + + 0.0028333 + 0 + 0 + 0.0028333 + 0 + 0.0053333 + + + + 0 0 0 0 0 0 + + 0.1 0.1 0.1 0.6 + + + + 0.4 0.4 0.1 + + + + + 0 0 0 0 0 0 + + + 0.4 0.4 0.1 + + + + + 3.0e7 + 0.15 + 10 + 0.4 + + + + + base + base_x + + + 1 0 0 + + + + + base_x + base_xz + + + 0 0 1 + + + + base_xz + passive_block + + + 0 1 0 + + + + + + \ No newline at end of file From 2330539fa5a4ea14c89534f68e2577a79cc34c89 Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 11 Jun 2024 11:36:08 -0400 Subject: [PATCH 731/758] minor refactoring --- .../franka/diagrams/franka_c3_controller_diagram.cc | 2 +- examples/franka/forward_kinematics_for_lcs.cc | 6 ------ examples/franka/franka_c3_controller.cc | 2 +- examples/franka/franka_c3_controller_two_objects.cc | 2 +- .../c3_options/franka_c3_options_translation.yaml | 12 ++++++------ .../parameters/franka_c3_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 4 ++-- examples/franka/urdf/plate_end_effector.urdf | 2 +- lcmtypes/lcmt_estimated_object_state.lcm | 7 ------- solvers/BUILD.bazel | 2 +- 10 files changed, 14 insertions(+), 27 deletions(-) delete mode 100644 lcmtypes/lcmt_estimated_object_state.lcm diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index e057092567..09f3fc87b2 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -28,7 +28,7 @@ #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3/lcs_factory_system.h" -#include "systems/controllers/c3_controller.h" +#include "systems/controllers/c3/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index 5e943dc5f9..937927c80e 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -21,12 +21,10 @@ #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3/lcs_factory_system.h" -#include "systems/controllers/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" #include "systems/system_utils.h" -#include "systems/trajectory_optimization/c3_output_systems.h" namespace dairlib { @@ -72,10 +70,6 @@ int DoMain(int argc, char* argv[]) { controller_params.c3_scene_file[controller_params.scene_index]); FrankaLcmChannels lcm_channel_params = drake::yaml::LoadYamlFile(FLAGS_lcm_channels); - drake::solvers::SolverOptions solver_options = - drake::yaml::LoadYamlFile( - FindResourceOrThrow(controller_params.osqp_settings_file)) - .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); DiagramBuilder plant_builder; diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index 0e09e936ca..a3ccbaafc2 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -19,7 +19,7 @@ #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3/lcs_factory_system.h" -#include "systems/controllers/c3_controller.h" +#include "systems/controllers/c3/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/franka/franka_c3_controller_two_objects.cc b/examples/franka/franka_c3_controller_two_objects.cc index 34d980ea88..dfba0d63cc 100644 --- a/examples/franka/franka_c3_controller_two_objects.cc +++ b/examples/franka/franka_c3_controller_two_objects.cc @@ -21,7 +21,7 @@ #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" #include "systems/controllers/c3/lcs_factory_system.h" -#include "systems/controllers/c3_controller.h" +#include "systems/controllers/c3/c3_controller.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/primitives/radio_parser.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml index 7edcd83299..9dc916382a 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml @@ -1,4 +1,4 @@ -admm_iter: 3 +admm_iter: 2 rho: 0.0 rho_scale: 4 num_threads: 5 @@ -8,8 +8,8 @@ projection_type: 'MIQP' # options are 'stewart_and_trinkle' or 'anitescu' #contact_model: 'anitescu' contact_model: 'stewart_and_trinkle' -warm_start: true -use_predicted_x0: true +warm_start: false +use_predicted_x0: false use_robust_formulation: false end_on_qp_step: false solve_time_filter_alpha: 0.95 @@ -26,7 +26,7 @@ u_horizontal_limits: [-50, 50] u_vertical_limits: [-50, 50] mu: [0.6, 0.6, 0.6] -dt: 0.075 +dt: 0.05 solve_dt: 0.05 num_friction_directions: 2 num_contacts: 3 @@ -35,11 +35,11 @@ gamma: 1 # matrix scaling w_Q: 50 -w_R: 50 +w_R: 25 # Penalty on all decision variables, assuming scalar w_G: 0.1 # Penalty on all decision variables, assuming scalar -w_U: 0.1 +w_U: 0.5 # State Tracking Error, assuming diagonal q_vector: [175, 175, 175, 1, 1, 1, 1, 15000, 15000, 15000, diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 40a59b106a..720762fd30 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,4 +1,4 @@ -scene_index: 1 +scene_index: 0 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 3bfafbd72c..73fdfee3f0 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 32 actuator_delay: 0.000 -scene_index: 1 +scene_index: 0 visualize_drake_sim: false publish_efforts: true publish_object_velocities: true @@ -37,7 +37,7 @@ world_z_limits: [[0.35, 0.7], external_force_scaling: [10.0, 10.0, 10.0] dt: 0.0005 -realtime_rate: 0.8 +realtime_rate: 1.0 q_init_franka: [-1.3, 1.6, 1.6, -2.1, 1.57, 1.62, -0.81] q_init_tray: [[1, 0, 0, 0, 0.55, 0.0, 0.465], diff --git a/examples/franka/urdf/plate_end_effector.urdf b/examples/franka/urdf/plate_end_effector.urdf index e1203ecd38..a0efe0cef0 100644 --- a/examples/franka/urdf/plate_end_effector.urdf +++ b/examples/franka/urdf/plate_end_effector.urdf @@ -15,7 +15,7 @@ - + diff --git a/lcmtypes/lcmt_estimated_object_state.lcm b/lcmtypes/lcmt_estimated_object_state.lcm deleted file mode 100644 index 3b7c26a90e..0000000000 --- a/lcmtypes/lcmt_estimated_object_state.lcm +++ /dev/null @@ -1,7 +0,0 @@ -package dairlib; - -struct lcmt_estimated_object_state -{ - lcmt_object_state object_state; - string measurement_status; -} diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 7a8fe3fc44..21bfb3fcf1 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -36,7 +36,7 @@ cc_library( "-fopenmp", ], linkopts = [ - "-lgomp", + "-fopenmp", ], deps = [ ":lcs", From 570e392beadb86b11868dff9a0c492ba65947d9e Mon Sep 17 00:00:00 2001 From: William Yang Date: Tue, 11 Jun 2024 11:36:36 -0400 Subject: [PATCH 732/758] moving c3 controller to separate folder --- systems/controllers/BUILD.bazel | 12 ++++++++++-- systems/controllers/{ => c3}/c3_controller.cc | 0 systems/controllers/{ => c3}/c3_controller.h | 0 3 files changed, 10 insertions(+), 2 deletions(-) rename systems/controllers/{ => c3}/c3_controller.cc (100%) rename systems/controllers/{ => c3}/c3_controller.h (100%) diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index 07e96212c7..d542343eba 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -13,6 +13,14 @@ cc_library( ], ) +cc_library( + name = "c3_systems", + deps = [ + ":c3_controller", + ":lcs_factory_system", + ], +) + cc_library( name = "control_utils", srcs = [ @@ -65,8 +73,8 @@ cc_library( cc_library( name = "c3_controller", - srcs = ["c3_controller.cc"], - hdrs = ["c3_controller.h"], + srcs = ["c3/c3_controller.cc"], + hdrs = ["c3/c3_controller.h"], deps = [ "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", diff --git a/systems/controllers/c3_controller.cc b/systems/controllers/c3/c3_controller.cc similarity index 100% rename from systems/controllers/c3_controller.cc rename to systems/controllers/c3/c3_controller.cc diff --git a/systems/controllers/c3_controller.h b/systems/controllers/c3/c3_controller.h similarity index 100% rename from systems/controllers/c3_controller.h rename to systems/controllers/c3/c3_controller.h From f6c84b9609ff2e05ac3ec8bd74da12130426d9dd Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 14 Jun 2024 11:06:45 -0400 Subject: [PATCH 733/758] playing with visualization --- .../parameters/c3_options/franka_c3_options_supports.yaml | 2 +- examples/franka/parameters/franka_c3_controller_params.yaml | 2 +- examples/franka/parameters/franka_sim_params.yaml | 2 +- solvers/c3.cc | 2 +- systems/visualization/lcm_visualization_systems.cc | 3 ++- 5 files changed, 6 insertions(+), 5 deletions(-) diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 2e693a3bf3..9ff0b05c60 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -10,7 +10,7 @@ projection_type: 'MIQP' contact_model: 'anitescu' warm_start: true use_predicted_x0: true -use_robust_formulation: true +use_robust_formulation: false end_on_qp_step: false solve_time_filter_alpha: 0.95 #set to 0 to publish as fast as possible diff --git a/examples/franka/parameters/franka_c3_controller_params.yaml b/examples/franka/parameters/franka_c3_controller_params.yaml index 720762fd30..40a59b106a 100644 --- a/examples/franka/parameters/franka_c3_controller_params.yaml +++ b/examples/franka/parameters/franka_c3_controller_params.yaml @@ -1,4 +1,4 @@ -scene_index: 0 +scene_index: 1 c3_options_file: [examples/franka/parameters/c3_options/franka_c3_options_translation.yaml, examples/franka/parameters/c3_options/franka_c3_options_supports.yaml, examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml, diff --git a/examples/franka/parameters/franka_sim_params.yaml b/examples/franka/parameters/franka_sim_params.yaml index 73fdfee3f0..b95a39c5b4 100644 --- a/examples/franka/parameters/franka_sim_params.yaml +++ b/examples/franka/parameters/franka_sim_params.yaml @@ -8,7 +8,7 @@ object_publish_rate: 1000 visualizer_publish_rate: 32 actuator_delay: 0.000 -scene_index: 0 +scene_index: 1 visualize_drake_sim: false publish_efforts: true publish_object_velocities: true diff --git a/solvers/c3.cc b/solvers/c3.cc index 2e2aeb2615..5df5a28a9f 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -388,7 +388,7 @@ vector C3::SolveProjection(const vector& G, if (options_.num_threads > 0) { omp_set_dynamic(0); // Explicitly disable dynamic teams omp_set_num_threads(options_.num_threads); // Set number of threads - omp_set_nested(1); + omp_set_max_active_levels(1); } #pragma omp parallel for num_threads(options_.num_threads) diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index e879ad3249..c7eb1643b6 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -91,10 +91,11 @@ LcmPoseDrawer::LcmPoseDrawer( Eigen::VectorXd alpha_scale; if (add_transparency) { - alpha_scale = 1.0 * VectorXd::LinSpaced(N_ - 1, 0.1, 0.4); + alpha_scale = 1.0 * VectorXd::LinSpaced(N_ - 1, 0.2, 0.5); } else { alpha_scale = 1.0 * VectorXd::Ones(N_ - 1); } + alpha_scale.reverseInPlace(); multipose_visualizer_ = std::make_unique( model_file, N_ - 1, alpha_scale, "", meshcat); From 4bebe5b1d28f596467ef370b8470d5e418ad6371 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 14 Jun 2024 14:25:04 -0400 Subject: [PATCH 734/758] renaming and adding comments --- .../diagrams/franka_osc_controller_diagram.cc | 6 +- examples/franka/franka_osc_controller.cc | 6 +- .../franka_c3_options_supports.yaml | 3 +- .../franka/saved_trajectories/franka_defaults | Bin 615 -> 0 bytes examples/franka/systems/BUILD.bazel | 16 ++--- ...ce_trajectory.cc => end_effector_force.cc} | 2 +- ...orce_trajectory.h => end_effector_force.h} | 0 .../systems/end_effector_orientation.cc | 6 +- .../franka/systems/end_effector_orientation.h | 4 +- ...trajectory.cc => end_effector_position.cc} | 2 +- ...r_trajectory.h => end_effector_position.h} | 0 solvers/c3.cc | 14 ++--- solvers/c3.h | 58 +++++++++++------- 13 files changed, 65 insertions(+), 52 deletions(-) delete mode 100644 examples/franka/saved_trajectories/franka_defaults rename examples/franka/systems/{end_effector_force_trajectory.cc => end_effector_force.cc} (98%) rename examples/franka/systems/{end_effector_force_trajectory.h => end_effector_force.h} (100%) rename examples/franka/systems/{end_effector_trajectory.cc => end_effector_position.cc} (98%) rename examples/franka/systems/{end_effector_trajectory.h => end_effector_position.h} (100%) diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index d71f0939ac..b59ebf1720 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -17,9 +17,9 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_osc_controller_params.h" -#include "examples/franka/systems/end_effector_force_trajectory.h" +#include "examples/franka/systems/end_effector_force.h" #include "examples/franka/systems/end_effector_orientation.h" -#include "examples/franka/systems/end_effector_trajectory.h" +#include "examples/franka/systems/end_effector_position.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" @@ -123,7 +123,7 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( controller_params.neutral_position, controller_params.x_scale, controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = - builder.AddSystem(); + builder.AddSystem(); end_effector_orientation_trajectory->SetTrackOrientation( controller_params.track_end_effector_orientation); auto end_effector_force_trajectory = diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 3b0c71a6fd..ebd362bd98 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -6,9 +6,9 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_osc_controller_params.h" -#include "examples/franka/systems/end_effector_force_trajectory.h" +#include "examples/franka/systems/end_effector_force.h" #include "examples/franka/systems/end_effector_orientation.h" -#include "examples/franka/systems/end_effector_trajectory.h" +#include "examples/franka/systems/end_effector_position.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" @@ -143,7 +143,7 @@ int DoMain(int argc, char* argv[]) { controller_params.neutral_position, controller_params.x_scale, controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = - builder.AddSystem(); + builder.AddSystem(); end_effector_orientation_trajectory->SetTrackOrientation( controller_params.track_end_effector_orientation); auto end_effector_force_trajectory = diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 9ff0b05c60..3775d510f3 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -21,8 +21,7 @@ publish_frequency: 0 workspace_limits: [[1.0, 0.0, 0.0, 0.4, 0.6], [0.0, 1.0, 0.0, -0.1, 0.1], [0.0, 0.0, 1.0, 0.35, 0.7]] -#world_y_limits: [-0.1, 0.1] -#world_z_limits: [0.35, 0.7] + workspace_margins: 0.05 u_horizontal_limits: [-10, 10] diff --git a/examples/franka/saved_trajectories/franka_defaults b/examples/franka/saved_trajectories/franka_defaults deleted file mode 100644 index cbd50d77127b80a7170228019eea72c136f4ead5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 615 zcma#*(7CMgmLZyrfq{V$h|viapb$@fQdVkmNqk9BVirgV6A&|l7$9K3b0!GPvVU?0 z1kS=}h%AD%zibQ!Fd8Vso|0dhl#>clgPkdqnwJuvnwAE%Jimzk)+?Y`pI?-jnpcuo zl9`_uUy@jqo>~HOI4CSY7!2$`z*q!n9wg&HiqZK}D0Zji7bT}s!B#e~K_L4OEcDpL M9_Yk`1s*p8006a;5C8xG diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 77cef8a42f..6551f6f3b9 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -7,8 +7,8 @@ cc_library( ":c3_state_sender", ":c3_trajectory_generator", ":end_effector_force_trajectory", - ":end_effector_orientation", - ":end_effector_trajectory", + ":end_effector_orientation_trajectory", + ":end_effector_position_trajectory", ":external_force_generator", ":franka_kinematics", ":franka_state_translator", @@ -30,9 +30,9 @@ cc_library( ) cc_library( - name = "end_effector_trajectory", - srcs = ["end_effector_trajectory.cc"], - hdrs = ["end_effector_trajectory.h"], + name = "end_effector_position_trajectory", + srcs = ["end_effector_position.cc"], + hdrs = ["end_effector_position.h"], deps = [ "//lcmtypes:lcmt_robot", "//multibody:utils", @@ -44,8 +44,8 @@ cc_library( cc_library( name = "end_effector_force_trajectory", - srcs = ["end_effector_force_trajectory.cc"], - hdrs = ["end_effector_force_trajectory.h"], + srcs = ["end_effector_force.cc"], + hdrs = ["end_effector_force.h"], deps = [ "//lcmtypes:lcmt_robot", "//multibody:utils", @@ -56,7 +56,7 @@ cc_library( ) cc_library( - name = "end_effector_orientation", + name = "end_effector_orientation_trajectory", srcs = ["end_effector_orientation.cc"], hdrs = ["end_effector_orientation.h"], deps = [ diff --git a/examples/franka/systems/end_effector_force_trajectory.cc b/examples/franka/systems/end_effector_force.cc similarity index 98% rename from examples/franka/systems/end_effector_force_trajectory.cc rename to examples/franka/systems/end_effector_force.cc index 5daabaee6e..62fcb4a474 100644 --- a/examples/franka/systems/end_effector_force_trajectory.cc +++ b/examples/franka/systems/end_effector_force.cc @@ -1,4 +1,4 @@ -#include "end_effector_force_trajectory.h" +#include "end_effector_force.h" #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" diff --git a/examples/franka/systems/end_effector_force_trajectory.h b/examples/franka/systems/end_effector_force.h similarity index 100% rename from examples/franka/systems/end_effector_force_trajectory.h rename to examples/franka/systems/end_effector_force.h diff --git a/examples/franka/systems/end_effector_orientation.cc b/examples/franka/systems/end_effector_orientation.cc index ac42221bcd..f49b5ef86e 100644 --- a/examples/franka/systems/end_effector_orientation.cc +++ b/examples/franka/systems/end_effector_orientation.cc @@ -13,7 +13,7 @@ using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorOrientationGenerator::EndEffectorOrientationGenerator() { +EndEffectorOrientationTrajectoryGenerator::EndEffectorOrientationTrajectoryGenerator() { auto pp = drake::trajectories::PiecewiseQuaternionSlerp(); trajectory_port_ = @@ -27,11 +27,11 @@ EndEffectorOrientationGenerator::EndEffectorOrientationGenerator() { PiecewiseQuaternionSlerp empty_slerp_traj; Trajectory& traj_inst = empty_slerp_traj; this->DeclareAbstractOutputPort("end_effector_orientation", traj_inst, - &EndEffectorOrientationGenerator::CalcTraj) + &EndEffectorOrientationTrajectoryGenerator::CalcTraj) .get_index(); } -void EndEffectorOrientationGenerator::CalcTraj( +void EndEffectorOrientationTrajectoryGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { const auto& radio_out = this->EvalVectorInput(context, radio_port_); diff --git a/examples/franka/systems/end_effector_orientation.h b/examples/franka/systems/end_effector_orientation.h index 4799bc0752..16c06d1378 100644 --- a/examples/franka/systems/end_effector_orientation.h +++ b/examples/franka/systems/end_effector_orientation.h @@ -5,10 +5,10 @@ namespace dairlib { -class EndEffectorOrientationGenerator +class EndEffectorOrientationTrajectoryGenerator : public drake::systems::LeafSystem { public: - EndEffectorOrientationGenerator(); + EndEffectorOrientationTrajectoryGenerator(); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_port_); diff --git a/examples/franka/systems/end_effector_trajectory.cc b/examples/franka/systems/end_effector_position.cc similarity index 98% rename from examples/franka/systems/end_effector_trajectory.cc rename to examples/franka/systems/end_effector_position.cc index a7b491667b..5d76601224 100644 --- a/examples/franka/systems/end_effector_trajectory.cc +++ b/examples/franka/systems/end_effector_position.cc @@ -1,4 +1,4 @@ -#include "end_effector_trajectory.h" +#include "end_effector_position.h" #include #include "dairlib/lcmt_radio_out.hpp" #include "multibody/multibody_utils.h" diff --git a/examples/franka/systems/end_effector_trajectory.h b/examples/franka/systems/end_effector_position.h similarity index 100% rename from examples/franka/systems/end_effector_trajectory.h rename to examples/franka/systems/end_effector_position.h diff --git a/solvers/c3.cc b/solvers/c3.cc index 5df5a28a9f..570518f463 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -380,7 +380,7 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, return *z_sol_; } -vector C3::SolveProjection(const vector& G, +vector C3::SolveProjection(const vector& U, vector& WZ, int admm_iteration) { vector deltaProj(N_, VectorXd::Zero(n_ + m_ + k_)); int i; @@ -399,29 +399,29 @@ vector C3::SolveProjection(const vector& G, if (warm_start_) { if (i == N_ - 1) { deltaProj[i] = SolveRobustSingleProjection( - G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, + U[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, admm_iteration, -1); } else { deltaProj[i] = SolveRobustSingleProjection( - G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, + U[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, admm_iteration, i + 1); } } else { deltaProj[i] = SolveRobustSingleProjection( - G[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, + U[i], WZ[i], E_[i], F_[i], H_[i], c_[i], W_x_, W_l_, W_u_, w_, admm_iteration, -1); } } else { if (warm_start_) { if (i == N_ - 1) { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + deltaProj[i] = SolveSingleProjection(U[i], WZ[i], E_[i], F_[i], H_[i], c_[i], admm_iteration, -1); } else { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + deltaProj[i] = SolveSingleProjection(U[i], WZ[i], E_[i], F_[i], H_[i], c_[i], admm_iteration, i + 1); } } else { - deltaProj[i] = SolveSingleProjection(G[i], WZ[i], E_[i], F_[i], H_[i], + deltaProj[i] = SolveSingleProjection(U[i], WZ[i], E_[i], F_[i], H_[i], c_[i], admm_iteration, -1); } } diff --git a/solvers/c3.h b/solvers/c3.h index e68c606c9e..d10fe282a9 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -29,7 +29,7 @@ class C3 { std::vector U; }; /// @param LCS LCS parameters - /// @param Q, R, G, U Cost function parameters + /// @param Q, R, G, U Cost Matrices C3(const LCS& LCS, const CostMatrices& costs, const std::vector& x_desired, const C3Options& options); @@ -37,9 +37,7 @@ class C3 { /// Solve the MPC problem /// @param x0 The initial state of the system - /// @param delta A pointer to the copy variable solution - /// @param w A pointer to the scaled dual variable solution - /// @return The first control action to take, u[0] + /// @return void void Solve(const Eigen::VectorXd& x0); /// Solve a single ADMM step @@ -47,14 +45,20 @@ class C3 { /// @param delta The copy variables from the previous step /// @param w The scaled dual variables from the previous step /// @param G A pointer to the G variables from previous step + /// @param admm_iteration ADMM iteration for accurate warm starting + /// @return solution is saved in C3 object void ADMMStep(const Eigen::VectorXd& x0, std::vector* delta, std::vector* w, std::vector* G, int admm_iteration); /// Solve a single QP /// @param x0 The initial state of the system - /// @param WD A pointer to the (w - delta) variables /// @param G A pointer to the G variables from previous step + /// @param WD A pointer to the (w - delta) variables + /// @param admm_iteration ADMM iteration for accurate warm starting + /// @param is_final_solve Indicating final admm iteration in case of any + /// polishing steps + /// @return z MPC solution std::vector SolveQP(const Eigen::VectorXd& x0, const std::vector& G, const std::vector& WD, @@ -62,10 +66,11 @@ class C3 { bool is_final_solve = false); /// Solve the projection problem for all timesteps - /// @param WZ A pointer to the (z + w) variables - /// @param G A pointer to the G variables from previous step + /// @param U Matrix for consensus cost + /// @param WZ (z + w) variables + /// @param admm_iteration ADMM iteration for accurate warm starting std::vector SolveProjection( - const std::vector& G, std::vector& WZ, + const std::vector& U, std::vector& WZ, int admm_iteration); /// allow users to add constraints (adds for all timesteps) @@ -74,23 +79,31 @@ class C3 { void AddLinearConstraint(Eigen::RowVectorXd& A, double lower_bound, double upper_bound, int constraint); - /// allow user to remove all constraints + /// remove all constraints void RemoveConstraints(); - /// Solve a single projection step - /// @param E, F, H, c LCS parameters - /// @param U A pointer to the U variables + /// Solve a projection step for a single knot point k + /// @param U Matrix for consensus cost /// @param delta_c A pointer to the copy of (z + w) variables + /// @param E, F, H, c LCS contact parameters + /// @param admm_iteration ADMM iteration for accurate warm starting + /// @param warm_start_index knot point index for warm starting + /// @return delta_k virtual Eigen::VectorXd SolveSingleProjection( const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int admm_iteration, const int& warm_start_index) = 0; - /// Solve a robust single projection step - /// @param E, F, H, c LCS parameters - /// @param U A pointer to the U variables + /// Solve a robust (friction cone) projection step for a single knot point k + /// @param U Matrix for consensus cost /// @param delta_c A pointer to the copy of (z + w) variables + /// @param E, F, H, c LCS contact parameters + /// @param W_x, W_l, W_u, w Linearization of J_t v_{k+1} wrt x_k, lambda_k, + /// u_k + /// @param admm_iteration ADMM iteration for accurate warm starting + /// @param warm_start_index knot point index for warm starting + /// @return delta_k virtual Eigen::VectorXd SolveRobustSingleProjection( const Eigen::MatrixXd& U, const Eigen::VectorXd& delta_c, const Eigen::MatrixXd& E, const Eigen::MatrixXd& F, @@ -99,6 +112,7 @@ class C3 { const Eigen::MatrixXd& W_u, const Eigen::VectorXd& w, const int admm_iteration, const int& warm_start_index) = 0; + /// Solve a robust (friction cone) projection step for a single knot point void SetOsqpSolverOptions(const drake::solvers::SolverOptions& options) { prog_.SetSolverOptions(options); } @@ -150,22 +164,22 @@ class C3 { double solve_time_ = 0; bool h_is_zero_; - drake::solvers::MathematicalProgram prog_; - // QP step variables + /// MathematicalProgram for QP step drake::solvers::OsqpSolver osqp_; + drake::solvers::MathematicalProgram prog_; + /// Decision variables for QP step std::vector x_; std::vector u_; std::vector lambda_; - // QP step constraints + /// QP step constraints std::vector dynamics_constraints_; + // initial state constraint std::vector> constraints_; + // workspace and input limit constraints std::vector> user_constraints_; - - /// Projection step variables are defined outside of the MathematicalProgram - /// interface - + /// QP step costs std::vector target_cost_; std::vector> costs_; std::vector> input_costs_; From 2fe13d786c6154a537cc33533029fc7fff2f78be Mon Sep 17 00:00:00 2001 From: William Yang Date: Sat, 15 Jun 2024 18:10:04 -0400 Subject: [PATCH 735/758] successfully bound lcs factory, need to update simple model --- bindings/pydairlib/franka/BUILD.bazel | 1 + .../pydairlib/franka/planar_box_example.py | 110 +++++++++++++---- .../pydairlib/franka/urdf/active_block.sdf | 24 ++-- .../pydairlib/franka/urdf/passive_block.sdf | 12 +- bindings/pydairlib/solvers/BUILD.bazel | 54 ++++++++ bindings/pydairlib/solvers/__init__.py | 3 + bindings/pydairlib/solvers/c3_py.cc | 116 ++++++++++++++++++ examples/franka/franka_c3_controller.cc | 2 +- solvers/c3.cc | 8 +- solvers/c3.h | 2 +- 10 files changed, 292 insertions(+), 40 deletions(-) create mode 100644 bindings/pydairlib/solvers/BUILD.bazel create mode 100644 bindings/pydairlib/solvers/__init__.py create mode 100644 bindings/pydairlib/solvers/c3_py.cc diff --git a/bindings/pydairlib/franka/BUILD.bazel b/bindings/pydairlib/franka/BUILD.bazel index 1767837afe..503916512b 100644 --- a/bindings/pydairlib/franka/BUILD.bazel +++ b/bindings/pydairlib/franka/BUILD.bazel @@ -62,6 +62,7 @@ py_binary( data = [ ], deps = [ + "//bindings/pydairlib/solvers:c3_py", "@drake//bindings/pydrake", ], ) diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index 4a8dbf2baa..1c6f1e20e1 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -14,51 +14,117 @@ StartMeshcat, RigidTransform, Value, + InitializeAutoDiff, + ModelInstanceIndex ) -class CubePusher(LeafSystem): - def __init__(self, plant): +from c3 import * + + +class Controller(LeafSystem): + def __init__(self, plant, plant_context): LeafSystem.__init__(self) forces_cls = Value[List[ExternallyAppliedSpatialForce]] - self.DeclareAbstractOutputPort( - "applied_force", lambda: forces_cls(), self.CalcOutput + self.DeclareVectorOutputPort( + "controller_output", 1, self.CalcOutput ) + self.DeclareVectorInputPort("system_state", plant.num_positions() + plant.num_velocities()) self.plant = plant + self.plant_context = plant_context + + lcs_builer = DiagramBuilder() + self.plant_for_lcs, self.scene_graph_for_lcs = AddMultibodyPlantSceneGraph( + lcs_builer, 0.0) + lcs_parser = Parser(self.plant_for_lcs) + self.passive_block_index = lcs_parser.AddModels( + "bindings/pydairlib/franka/urdf/passive_block.sdf")[0] + self.active_block_index = \ + lcs_parser.AddModels("bindings/pydairlib/franka/urdf/active_block.sdf")[ + 0] + self.plant_for_lcs.WeldFrames(self.plant_for_lcs.world_frame(), + self.plant_for_lcs.GetFrameByName("base", + self.passive_block_index)) + self.plant_for_lcs.Finalize() + lcs_diagram = lcs_builer.Build() + + diagram_context = lcs_diagram.CreateDefaultContext() + self.context_for_lcs = lcs_diagram.GetMutableSubsystemContext( + self.plant_for_lcs, diagram_context) + self.plant_ad = self.plant_for_lcs.ToAutoDiffXd() + self.context_ad = self.plant_ad.CreateDefaultContext() + + passive_block_contact_points = self.plant_for_lcs.GetCollisionGeometriesForBody( + self.plant_for_lcs.GetBodyByName("passive_block", + self.passive_block_index)) + active_block_contact_points = self.plant_for_lcs.GetCollisionGeometriesForBody( + self.plant_for_lcs.GetBodyByName("active_block", + self.active_block_index)) + self.contact_geoms = list() + for geom_id in active_block_contact_points: + # contact_geoms.append([geom_id, passive_block_contact_points[0]]) + self.contact_geoms.append((geom_id, passive_block_contact_points[0])) + self.num_friction_directions = 2 + self.mu = [0.4] + self.dt = 0.1 + self.N = 5 + self.contact_model = ContactModel.kAnitescu + + def CalcOutput(self, context, output): - forces = [] - force = ExternallyAppliedSpatialForce() - force.body_index = self.plant.GetBodyByName("active_block").index() - force.F_Bq_W = SpatialForce( - tau=np.array([0, 0, 0]), - f=[4 * np.sin(1.0 * context.get_time()), 0, 0], - ) - forces.append(force) - output.set_value(forces) -def main(): + x = self.EvalVectorInput(context, 0) + x_u = np.hstack((x.value(), np.array([0]))) + x_u_ad = InitializeAutoDiff(x_u) + self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) + self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, np.array([0])) + self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) + lcs = LinearizePlantToLCS(self.plant_for_lcs, self.context_for_lcs, + self.plant_ad, self.context_ad, self.contact_geoms, + self.num_friction_directions, self.mu, self.dt, self.N, + self.contact_model) + # import pdb; pdb.set_trace() + # print(lcs.A_[0]) + print(lcs.D_[0].shape) + # import pdb; pdb.set_trace() + output.set_value(np.array([5 * np.sin(1.0 * context.get_time())])) +def main(): builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0005) parser = Parser(plant) - parser.AddModels("bindings/pydairlib/franka/urdf/passive_block.sdf") - parser.AddModels("bindings/pydairlib/franka/urdf/active_block.sdf") - offset = RigidTransform(np.array([0.0, 0.0, 0.25])) - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("center")) - plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base"), offset) + passive_block_index = \ + parser.AddModels("bindings/pydairlib/franka/urdf/passive_block.sdf")[0] + active_block_index = \ + parser.AddModels("bindings/pydairlib/franka/urdf/active_block.sdf")[0] + offset = RigidTransform(np.array([0.0, 0.0, 0.0])) + plant.WeldFrames(plant.world_frame(), + plant.GetFrameByName("base", passive_block_index), offset) + # plant.WeldFrames(plant.world_frame(), + # plant.GetFrameByName("base", active_block_index)) plant.Finalize() + plant_context = plant.CreateDefaultContext() meshcat = StartMeshcat() visualizer = MeshcatVisualizer.AddToBuilder(builder, scene_graph, meshcat) ContactVisualizer.AddToBuilder(builder, plant, meshcat) - pusher = builder.AddSystem(CubePusher(plant)) - builder.Connect(pusher.get_output_port(), plant.get_applied_spatial_force_input_port()) + controller = builder.AddSystem(Controller(plant, plant_context)) + builder.Connect(controller.get_output_port(), + plant.get_actuation_input_port()) + builder.Connect(plant.get_state_output_port(), + controller.get_input_port()) diagram = builder.Build() + meshcat.SetCameraPose(np.array([0, -3.0, 0.5]), np.array([0, 0.0, 0.0])) simulator = Simulator(diagram) context = simulator.get_context() + plant.SetPositions(diagram.GetMutableSubsystemContext(plant, + simulator.get_mutable_context()), + np.array([0, 0.25, 0.0, 0])) # x, z, theta + simulator.Initialize() simulator.set_target_realtime_rate(1.0) simulator.AdvanceTo(60.0) + if __name__ == '__main__': - main() \ No newline at end of file + main() diff --git a/bindings/pydairlib/franka/urdf/active_block.sdf b/bindings/pydairlib/franka/urdf/active_block.sdf index f799b89755..9090630fc3 100644 --- a/bindings/pydairlib/franka/urdf/active_block.sdf +++ b/bindings/pydairlib/franka/urdf/active_block.sdf @@ -2,19 +2,18 @@ - 0 0 0 0 0 0 1 - - 0.014167 - 0 - 0 - 0.33417 - 0 - 0.34667 - + + 0.014167 + 0 + 0 + 0.33417 + 0 + 0.34667 + 0 0 0 0 0 0 @@ -44,7 +43,7 @@ - center + world active_block @@ -53,8 +52,11 @@ -1.0 1.0 - 5.0 + 10.0 + + 0.0 + diff --git a/bindings/pydairlib/franka/urdf/passive_block.sdf b/bindings/pydairlib/franka/urdf/passive_block.sdf index 62d7ed122b..1ba1efca6d 100644 --- a/bindings/pydairlib/franka/urdf/passive_block.sdf +++ b/bindings/pydairlib/franka/urdf/passive_block.sdf @@ -52,6 +52,9 @@ 1 0 0 + + 0.0 + @@ -61,7 +64,11 @@ 0 0 1 - + + 0.0 + + + base_xz passive_block @@ -69,6 +76,9 @@ 0 1 0 + + 0.0 + diff --git a/bindings/pydairlib/solvers/BUILD.bazel b/bindings/pydairlib/solvers/BUILD.bazel new file mode 100644 index 0000000000..5fe19d4692 --- /dev/null +++ b/bindings/pydairlib/solvers/BUILD.bazel @@ -0,0 +1,54 @@ +# -*- python -*- +load("@drake//tools/install:install.bzl", "install") +load( + "@drake//tools/skylark:pybind.bzl", + "drake_pybind_library", + "get_drake_py_installs", + "get_pybind_package_info", + "pybind_py_library", +) +#load("@rules_python//python:packaging.bzl", "py_package", "py_wheel") + +package(default_visibility = ["//visibility:public"]) + +pybind_py_library( + name = "c3_py", + cc_deps = [ + "//solvers:c3", + "@drake//bindings/pydrake/common:default_scalars_pybind", + "@drake//bindings/pydrake/common:deprecation_pybind", + "@drake//bindings/pydrake/common:sorted_pair_pybind", + ], + cc_so_name = "c3", + cc_srcs = ["c3_py.cc"], + py_deps = [ + ":module_py", + ], + py_imports = ["."], +) + +# This determines how `PYTHONPATH` is configured, and how to install the +# bindings. +PACKAGE_INFO = get_pybind_package_info("//bindings") + +py_library( + name = "module_py", + srcs = [ + "__init__.py", + ], + imports = PACKAGE_INFO.py_imports, + deps = [ + ], +) + +PY_LIBRARIES = [ + ":module_py", + ":c3_py", +] + +# Package roll-up (for Bazel dependencies). +py_library( + name = "pyc3", + imports = PACKAGE_INFO.py_imports, + deps = PY_LIBRARIES, +) diff --git a/bindings/pydairlib/solvers/__init__.py b/bindings/pydairlib/solvers/__init__.py new file mode 100644 index 0000000000..6faf2149f8 --- /dev/null +++ b/bindings/pydairlib/solvers/__init__.py @@ -0,0 +1,3 @@ +# Importing everything in this directory to this package +from . import * +from .c3 import * diff --git a/bindings/pydairlib/solvers/c3_py.cc b/bindings/pydairlib/solvers/c3_py.cc new file mode 100644 index 0000000000..7e36a6fcda --- /dev/null +++ b/bindings/pydairlib/solvers/c3_py.cc @@ -0,0 +1,116 @@ +#include +#include +#include +#include + +#include "solvers/c3_miqp.h" +#include "solvers/lcs.h" +#include "solvers/lcs_factory.h" + +namespace py = pybind11; + +using Eigen::MatrixXd; +using Eigen::VectorXd; +using py::arg; +using std::vector; + +using dairlib::solvers::C3MIQP; +using dairlib::solvers::LCS; + +namespace c3 { +namespace pyc3 { + +PYBIND11_MODULE(c3, m) { + py::class_(m, "LCS") + .def(py::init&, const vector&, + const vector&, const vector&, + const vector&, const vector&, + const vector&, const vector&, double>(), + arg("A"), arg("B"), arg("D"), arg("d"), arg("E"), arg("F"), arg("H"), + arg("c"), arg("dt")) + .def(py::init(), + arg("A"), arg("B"), arg("D"), arg("d"), arg("E"), arg("F"), arg("H"), + arg("c"), arg("N"), arg("dt")) + .def_readwrite("A_", &LCS::A_) + .def_readwrite("B_", &LCS::B_) + .def_readwrite("D_", &LCS::D_) + .def_readwrite("d_", &LCS::d_) + .def_readwrite("E_", &LCS::E_) + .def_readwrite("F_", &LCS::F_) + .def_readwrite("H_", &LCS::H_) + .def_readwrite("c_", &LCS::c_) + .def("Simulate", &LCS::Simulate); + + m.def("LinearizePlantToLCS", + &dairlib::solvers::LCSFactory::LinearizePlantToLCS, + py::arg("plant"), + py::arg("context"), + py::arg("plant_ad"), + py::arg("context_ad"), + py::arg("contact_geoms"), + py::arg("num_friction_directions"), + py::arg("mu"), + py::arg("dt"), + py::arg("N"), + py::arg("contact_model")); + + { + using Enum = dairlib::solvers::ContactModel; + py::enum_ enum_py(m, "ContactModel"); + enum_py // BR + .value("kStewartAndTrinkle", Enum::kStewartAndTrinkle) + .value("kAnitescu", Enum::kAnitescu); + } + + py::class_(m, "C3MIQP") + .def(py::init&, const C3Options&>(), + arg("LCS"), arg("costs"), arg("x_des"), arg("c3_options")) + .def("Solve", &C3MIQP::Solve, arg("x0")) + .def("ADMMStep", &C3MIQP::ADMMStep, arg("x0"), arg("delta"), arg("w"), + arg("G"), arg("admm_iteration")) + .def("SolveQP", &C3MIQP::SolveQP, arg("x0"), arg("G"), arg("WD"), + arg("admm_iteration"), arg("is_final_solve")) + .def("SolveProjection", &C3MIQP::SolveProjection, arg("U"), arg("WZ"), arg("admm_iteration")) + .def("AddLinearConstraint", &C3MIQP::AddLinearConstraint, arg("A"), + arg("lower_bound"), arg("upper_bound"), arg("constraint")) + .def("RemoveConstraints", &C3MIQP::RemoveConstraints); + + py::class_ options(m, "C3Options"); + options.def(py::init<>()) + .def_readwrite("admm_iter", &C3Options::admm_iter) + .def_readwrite("rho", &C3Options::rho) + .def_readwrite("rho_scale", &C3Options::rho_scale) + .def_readwrite("num_threads", &C3Options::num_threads) + .def_readwrite("delta_option", &C3Options::delta_option) + .def_readwrite("contact_model", &C3Options::contact_model) + .def_readwrite("warm_start", &C3Options::warm_start) + .def_readwrite("use_predicted_x0", &C3Options::use_predicted_x0) + .def_readwrite("end_on_qp_step", &C3Options::end_on_qp_step) + .def_readwrite("use_robust_formulation", + &C3Options::use_robust_formulation) + .def_readwrite("solve_time_filter_alpha", + &C3Options::solve_time_filter_alpha) + .def_readwrite("publish_frequency", &C3Options::publish_frequency) + .def_readwrite("u_horizontal_limits", &C3Options::u_horizontal_limits) + .def_readwrite("u_vertical_limits", &C3Options::u_vertical_limits) + .def_readwrite("workspace_limits", &C3Options::workspace_limits) + .def_readwrite("workspace_margins", &C3Options::workspace_margins) + .def_readwrite("N", &C3Options::N) + .def_readwrite("gamma", &C3Options::gamma) + .def_readwrite("mu", &C3Options::mu) + .def_readwrite("dt", &C3Options::dt) + .def_readwrite("solve_dt", &C3Options::solve_dt) + .def_readwrite("num_friction_directions", + &C3Options::num_friction_directions) + .def_readwrite("num_contacts", &C3Options::num_contacts) + .def_readwrite("Q", &C3Options::Q) + .def_readwrite("R", &C3Options::R) + .def_readwrite("G", &C3Options::G) + .def_readwrite("U", &C3Options::U); +} + +} // namespace pyc3 +} // namespace c3 diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index a3ccbaafc2..b18e5f750b 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -77,7 +77,6 @@ int DoMain(int argc, char* argv[]) { FindResourceOrThrow(controller_params.osqp_settings_file)) .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); - DiagramBuilder plant_builder; MultibodyPlant plant_franka(0.0); Parser parser_franka(&plant_franka, nullptr); @@ -108,6 +107,7 @@ int DoMain(int argc, char* argv[]) { auto tray_context = plant_tray.CreateDefaultContext(); /// + DiagramBuilder plant_builder; auto [plant_for_lcs, scene_graph] = AddMultibodyPlantSceneGraph(&plant_builder, 0.0); Parser lcs_parser(&plant_for_lcs); diff --git a/solvers/c3.cc b/solvers/c3.cc index 570518f463..8b82850257 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -40,7 +40,7 @@ C3::CostMatrices::CostMatrices(const std::vector& Q, } C3::C3(const LCS& lcs, const C3::CostMatrices& costs, - const vector& x_desired, const C3Options& options) + const vector& x_des, const C3Options& options) : warm_start_(options.warm_start), N_((lcs.A_).size()), n_((lcs.A_)[0].cols()), @@ -58,11 +58,11 @@ C3::C3(const LCS& lcs, const C3::CostMatrices& costs, R_(costs.R), U_(costs.U), G_(costs.G), - x_desired_(x_desired), + x_desired_(x_des), options_(options), h_is_zero_(lcs.H_[0].isZero(0)), - prog_(MathematicalProgram()), - osqp_(OsqpSolver()) { + osqp_(OsqpSolver()), + prog_(MathematicalProgram()) { if (warm_start_) { warm_start_delta_.resize(options_.admm_iter + 1); warm_start_binary_.resize(options_.admm_iter + 1); diff --git a/solvers/c3.h b/solvers/c3.h index d10fe282a9..824c6410e4 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -31,7 +31,7 @@ class C3 { /// @param LCS LCS parameters /// @param Q, R, G, U Cost Matrices C3(const LCS& LCS, const CostMatrices& costs, - const std::vector& x_desired, const C3Options& options); + const std::vector& x_des, const C3Options& options); virtual ~C3() = default; From 148bc2e18b9f776d42653541230c2777f2757da9 Mon Sep 17 00:00:00 2001 From: William Yang Date: Sun, 16 Jun 2024 15:37:03 -0400 Subject: [PATCH 736/758] simple python example is running but doesn't work --- .../pydairlib/franka/planar_box_example.py | 95 +++++++++++++++---- .../pydairlib/franka/urdf/active_block.sdf | 6 +- .../franka/urdf/passive_block_lcs.sdf | 87 +++++++++++++++++ bindings/pydairlib/solvers/c3_py.cc | 14 ++- solvers/c3_miqp.cc | 4 +- 5 files changed, 182 insertions(+), 24 deletions(-) create mode 100644 bindings/pydairlib/franka/urdf/passive_block_lcs.sdf diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index 1c6f1e20e1..3193fe77b4 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -15,7 +15,8 @@ RigidTransform, Value, InitializeAutoDiff, - ModelInstanceIndex + ModelInstanceIndex, + PiecewisePolynomial, ) from c3 import * @@ -31,13 +32,14 @@ def __init__(self, plant, plant_context): self.DeclareVectorInputPort("system_state", plant.num_positions() + plant.num_velocities()) self.plant = plant self.plant_context = plant_context + self.c3_options = C3Options() lcs_builer = DiagramBuilder() self.plant_for_lcs, self.scene_graph_for_lcs = AddMultibodyPlantSceneGraph( lcs_builer, 0.0) lcs_parser = Parser(self.plant_for_lcs) self.passive_block_index = lcs_parser.AddModels( - "bindings/pydairlib/franka/urdf/passive_block.sdf")[0] + "bindings/pydairlib/franka/urdf/passive_block_lcs.sdf")[0] self.active_block_index = \ lcs_parser.AddModels("bindings/pydairlib/franka/urdf/active_block.sdf")[ 0] @@ -60,15 +62,52 @@ def __init__(self, plant, plant_context): self.plant_for_lcs.GetBodyByName("active_block", self.active_block_index)) self.contact_geoms = list() - for geom_id in active_block_contact_points: + for geom_id in passive_block_contact_points: # contact_geoms.append([geom_id, passive_block_contact_points[0]]) - self.contact_geoms.append((geom_id, passive_block_contact_points[0])) + self.contact_geoms.append((active_block_contact_points[0], geom_id)) self.num_friction_directions = 2 - self.mu = [0.4] - self.dt = 0.1 + self.mu = [0.4, 0.4] + self.dt = 0.5 self.N = 5 self.contact_model = ContactModel.kAnitescu - + # self.contact_model = ContactModel.kStewartAndTrinkle + self.Q = np.diag(np.array([100, 100, 1, 1, 1, 1, 1, 1])) + self.R = 10 * np.eye(1) + self.G = 0.5 * np.eye(8 + 8 + 1) + self.U = 0.5 * np.eye(8 + 8 + 1) + # self.G = np.eye(8 + 12 + 1) + # self.U = np.eye(8 + 12 + 1) + self.c3_options.admm_iter = 8 + self.c3_options.rho = 2 + self.c3_options.rho_scale = 2 + self.c3_options.num_threads = 4 + self.c3_options.delta_option = 1 + self.c3_options.contact_model = "anitescu" + self.c3_options.warm_start = 0 + self.c3_options.use_predicted_x0 = 0 + self.c3_options.end_on_qp_step = 0 + self.c3_options.use_robust_formulation = 0 + self.c3_options.solve_time_filter_alpha = 0.95 + self.c3_options.publish_frequency = 0 + self.c3_options.u_horizontal_limits = np.array([-10, 10]) + self.c3_options.u_vertical_limits = np.array([0, 0]) + self.c3_options.workspace_limits = [np.array([1, 1, 1, -1000, 1000])] + self.c3_options.workspace_margins = 0.05 + self.c3_options.N = self.N + self.c3_options.gamma = 1.0 + self.c3_options.mu = self.mu + self.c3_options.dt = self.dt + self.c3_options.solve_dt = 0.0 + self.c3_options.num_friction_directions = self.num_friction_directions + self.c3_options.num_contacts = len(self.mu) + self.c3_options.Q = self.Q + self.c3_options.R = self.R + self.c3_options.G = self.G + self.c3_options.U = self.U + self.u = PiecewisePolynomial(np.array([0])) + self.last_update_time = -1 + self.c3_solver = None + self.x_des = np.array([0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) def CalcOutput(self, context, output): @@ -78,21 +117,41 @@ def CalcOutput(self, context, output): self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, np.array([0])) self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) - lcs = LinearizePlantToLCS(self.plant_for_lcs, self.context_for_lcs, - self.plant_ad, self.context_ad, self.contact_geoms, - self.num_friction_directions, self.mu, self.dt, self.N, - self.contact_model) - # import pdb; pdb.set_trace() - # print(lcs.A_[0]) - print(lcs.D_[0].shape) - # import pdb; pdb.set_trace() - output.set_value(np.array([5 * np.sin(1.0 * context.get_time())])) + # if context.get_time() > self.last_update_time + (self.N * self.dt): + if context.get_time() > self.last_update_time + (self.dt): + print("cost: ", (x.value() - self.x_des).T @ self.Q @ (x.value() - self.x_des)) + print((x.value() - self.x_des)[:2]) + print("time: ", context.get_time()) + # import pdb; pdb.set_trace() + lcs = LinearizePlantToLCS(self.plant_for_lcs, self.context_for_lcs, + self.plant_ad, self.context_ad, self.contact_geoms, + self.num_friction_directions, self.mu, self.dt, self.N, + self.contact_model) + Qs = [] + for i in range(self.N + 1): + Qs.append(1.0 ** i * self.Q) + # costs = CostMatrices((self.N + 1) * [self.Q], self.N * [self.R], self.N * [self.G], self.N * [self.U]) + costs = CostMatrices(Qs, self.N * [self.R], self.N * [self.G], self.N * [self.U]) + if self.c3_solver == None: + self.c3_solver = C3MIQP(lcs, costs, (self.N + 1) * [self.x_des], self.c3_options) + else: + print("updating target") + self.c3_solver.UpdateTarget((self.N + 1) * [self.x_des]) + self.c3_solver.Solve(x.value()) + u_sol = self.c3_solver.GetInputSolution() + x_sol = self.c3_solver.GetStateSolution() + print(np.array(x_sol)[:, 0]) + print(np.array(x_sol)[:, 1]) + timestamps = context.get_time() + self.dt * np.arange(self.N) + self.u = PiecewisePolynomial.ZeroOrderHold(timestamps, np.array(u_sol).T) + self.last_update_time = context.get_time() + output.set_value(1 * self.u.value(context.get_time())) def main(): builder = DiagramBuilder() - plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.0005) + plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.001) parser = Parser(plant) passive_block_index = \ parser.AddModels("bindings/pydairlib/franka/urdf/passive_block.sdf")[0] @@ -120,7 +179,7 @@ def main(): context = simulator.get_context() plant.SetPositions(diagram.GetMutableSubsystemContext(plant, simulator.get_mutable_context()), - np.array([0, 0.25, 0.0, 0])) # x, z, theta + np.array([0.0, 0.3, 0.1, 0])) # active x, passive: x, z, theta simulator.Initialize() simulator.set_target_realtime_rate(1.0) simulator.AdvanceTo(60.0) diff --git a/bindings/pydairlib/franka/urdf/active_block.sdf b/bindings/pydairlib/franka/urdf/active_block.sdf index 9090630fc3..673ac81500 100644 --- a/bindings/pydairlib/franka/urdf/active_block.sdf +++ b/bindings/pydairlib/franka/urdf/active_block.sdf @@ -50,9 +50,9 @@ 1 0 0 - -1.0 - 1.0 - 10.0 + -2.0 + 2.0 + 50.0 0.0 diff --git a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf new file mode 100644 index 0000000000..932c83ea7e --- /dev/null +++ b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf @@ -0,0 +1,87 @@ + + + + + + + + + + 0 0 0 0 0 0 + 0.2 + + 0.0028333 + 0 + 0 + 0.0028333 + 0 + 0.0053333 + + + + 0 0 0 0 0 0 + + 0.1 0.1 0.1 0.6 + + + + 0.4 0.4 0.1 + + + + + -0.2 0.0 -0.05 0 0 0 + + + 0.001" + + + + + 0.2 0.0 -0.05 0 0 0 + + + 0.001" + + + + + + base + base_x + + + 1 0 0 + + + 0.0 + + + + + base_x + base_xz + + + 0 0 1 + + + 0.0 + + + + + base_xz + passive_block + + + 0 1 0 + + + 0.0 + + + + + + \ No newline at end of file diff --git a/bindings/pydairlib/solvers/c3_py.cc b/bindings/pydairlib/solvers/c3_py.cc index 7e36a6fcda..ef9bbe5a5f 100644 --- a/bindings/pydairlib/solvers/c3_py.cc +++ b/bindings/pydairlib/solvers/c3_py.cc @@ -64,11 +64,17 @@ PYBIND11_MODULE(c3, m) { .value("kAnitescu", Enum::kAnitescu); } + py::class_(m, "CostMatrices") + .def(py::init&, const std::vector&, + const std::vector&, const std::vector&>(), + arg("Q"), arg("R"), arg("G"), arg("U")); + py::class_(m, "C3MIQP") .def(py::init&, const C3Options&>(), arg("LCS"), arg("costs"), arg("x_des"), arg("c3_options")) .def("Solve", &C3MIQP::Solve, arg("x0")) + .def("UpdateTarget", &C3MIQP::UpdateTarget, arg("x0")) .def("ADMMStep", &C3MIQP::ADMMStep, arg("x0"), arg("delta"), arg("w"), arg("G"), arg("admm_iteration")) .def("SolveQP", &C3MIQP::SolveQP, arg("x0"), arg("G"), arg("WD"), @@ -76,7 +82,13 @@ PYBIND11_MODULE(c3, m) { .def("SolveProjection", &C3MIQP::SolveProjection, arg("U"), arg("WZ"), arg("admm_iteration")) .def("AddLinearConstraint", &C3MIQP::AddLinearConstraint, arg("A"), arg("lower_bound"), arg("upper_bound"), arg("constraint")) - .def("RemoveConstraints", &C3MIQP::RemoveConstraints); + .def("RemoveConstraints", &C3MIQP::RemoveConstraints) + .def("GetFullSolution", &C3MIQP::GetFullSolution) + .def("GetStateSolution", &C3MIQP::GetStateSolution) + .def("GetForceSolution", &C3MIQP::GetForceSolution) + .def("GetInputSolution", &C3MIQP::GetInputSolution) + .def("GetDualDeltaSolution", &C3MIQP::GetDualDeltaSolution) + .def("GetDualWSolution", &C3MIQP::GetDualWSolution); py::class_ options(m, "C3Options"); options.def(py::init<>()) diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 1d1e4d3a37..941c99e182 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -11,8 +11,8 @@ C3MIQP::C3MIQP(const LCS& LCS, const CostMatrices& costs, const vector& xdesired, const C3Options& options) : C3(LCS, costs, xdesired, options), env_(true) { // Create an environment - // env_.set("LogToConsole", "0"); - env_.set("OutputFlag", "0"); +// env_.set("LogToConsole", "1"); + env_.set("OutputFlag", "1"); env_.set("Threads", "0"); env_.start(); } From 2ea7227fe9188a88754c64f385b0dfd74eddea4c Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 20 Jun 2024 14:52:41 -0400 Subject: [PATCH 737/758] fixing planar lcs, gains work but are not convincing --- .../pydairlib/franka/planar_box_example.py | 63 +++++++++++-------- .../pydairlib/franka/urdf/active_block.sdf | 12 ++-- .../pydairlib/franka/urdf/passive_block.sdf | 8 +-- .../franka/urdf/passive_block_lcs.sdf | 14 ++--- bindings/pydairlib/solvers/c3_py.cc | 1 + multibody/geom_geom_collider.cc | 7 ++- solvers/c3_miqp.cc | 6 +- solvers/lcs_factory.cc | 26 +++++--- 8 files changed, 82 insertions(+), 55 deletions(-) diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index 3193fe77b4..0b259ed182 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -63,35 +63,33 @@ def __init__(self, plant, plant_context): self.active_block_index)) self.contact_geoms = list() for geom_id in passive_block_contact_points: - # contact_geoms.append([geom_id, passive_block_contact_points[0]]) self.contact_geoms.append((active_block_contact_points[0], geom_id)) - self.num_friction_directions = 2 + self.num_friction_directions = 1 self.mu = [0.4, 0.4] - self.dt = 0.5 - self.N = 5 + self.dt = 0.05 + self.N = 10 self.contact_model = ContactModel.kAnitescu # self.contact_model = ContactModel.kStewartAndTrinkle - self.Q = np.diag(np.array([100, 100, 1, 1, 1, 1, 1, 1])) - self.R = 10 * np.eye(1) - self.G = 0.5 * np.eye(8 + 8 + 1) - self.U = 0.5 * np.eye(8 + 8 + 1) - # self.G = np.eye(8 + 12 + 1) - # self.U = np.eye(8 + 12 + 1) - self.c3_options.admm_iter = 8 - self.c3_options.rho = 2 - self.c3_options.rho_scale = 2 + self.Q = 50 * np.diag(np.array([1000, 5000, 10, 10, 5, 10, 5, 5])) + self.R = 5 * np.eye(1) + # self.G = 0.5 * np.eye(8 + 8 + 1) + self.G = 0.1 * np.diag(np.hstack((np.ones(4), 0.1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) + self.U = 0.1 * np.diag(np.hstack((np.ones(4), 0.1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) + self.c3_options.admm_iter = 4 + self.c3_options.rho = 0 + self.c3_options.rho_scale = 4 self.c3_options.num_threads = 4 self.c3_options.delta_option = 1 self.c3_options.contact_model = "anitescu" - self.c3_options.warm_start = 0 - self.c3_options.use_predicted_x0 = 0 + self.c3_options.warm_start = 1 + self.c3_options.use_predicted_x0 = 1 self.c3_options.end_on_qp_step = 0 - self.c3_options.use_robust_formulation = 0 + self.c3_options.use_robust_formulation = 1 self.c3_options.solve_time_filter_alpha = 0.95 self.c3_options.publish_frequency = 0 - self.c3_options.u_horizontal_limits = np.array([-10, 10]) + self.c3_options.u_horizontal_limits = np.array([-5, 5]) self.c3_options.u_vertical_limits = np.array([0, 0]) - self.c3_options.workspace_limits = [np.array([1, 1, 1, -1000, 1000])] + self.c3_options.workspace_limits = [np.array([1, 0, 0, -0.5, 0.5])] # unused self.c3_options.workspace_margins = 0.05 self.c3_options.N = self.N self.c3_options.gamma = 1.0 @@ -108,6 +106,7 @@ def __init__(self, plant, plant_context): self.last_update_time = -1 self.c3_solver = None self.x_des = np.array([0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) + self.predicted_x1 = self.x_des def CalcOutput(self, context, output): @@ -117,16 +116,24 @@ def CalcOutput(self, context, output): self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, np.array([0])) self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) - # if context.get_time() > self.last_update_time + (self.N * self.dt): - if context.get_time() > self.last_update_time + (self.dt): - print("cost: ", (x.value() - self.x_des).T @ self.Q @ (x.value() - self.x_des)) - print((x.value() - self.x_des)[:2]) + # if context.get_time() > self.last_update_time + (5 * self.dt): + if context.get_time() > self.last_update_time + (self.dt): # execute first knot point of the plan + if context.get_time() // 10 % 2 == 0: + self.x_des = np.array([0.0, -0.3, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) + else: + self.x_des = np.array([0.0, 0.3, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) print("time: ", context.get_time()) + print("current cost: ", (x.value() - self.x_des).T @ self.Q @ (x.value() - self.x_des)) + print("desired x: ", self.x_des) + print("predicted x1: ", self.predicted_x1) + print("actual x1: ", x.value()) # import pdb; pdb.set_trace() lcs = LinearizePlantToLCS(self.plant_for_lcs, self.context_for_lcs, self.plant_ad, self.context_ad, self.contact_geoms, self.num_friction_directions, self.mu, self.dt, self.N, self.contact_model) + # print(lcs.D_[0]) + # import pdb; pdb.set_trace() Qs = [] for i in range(self.N + 1): Qs.append(1.0 ** i * self.Q) @@ -136,19 +143,25 @@ def CalcOutput(self, context, output): self.c3_solver = C3MIQP(lcs, costs, (self.N + 1) * [self.x_des], self.c3_options) else: print("updating target") + self.c3_solver.UpdateLCS(lcs) self.c3_solver.UpdateTarget((self.N + 1) * [self.x_des]) self.c3_solver.Solve(x.value()) u_sol = self.c3_solver.GetInputSolution() x_sol = self.c3_solver.GetStateSolution() - print(np.array(x_sol)[:, 0]) - print(np.array(x_sol)[:, 1]) + + # print((x.value() - self.x_des)[:2]) + # print(np.array(x_sol)[:, 0]) + # print(np.array(x_sol)[:, 1]) + self.predicted_x1 = np.array(x_sol)[1, :] timestamps = context.get_time() + self.dt * np.arange(self.N) self.u = PiecewisePolynomial.ZeroOrderHold(timestamps, np.array(u_sol).T) + # self.u = PiecewisePolynomial.FirstOrderHold(timestamps, np.array(u_sol).T) self.last_update_time = context.get_time() - output.set_value(1 * self.u.value(context.get_time())) + output.set_value(self.u.value(context.get_time())) def main(): + np.set_printoptions(3, threshold=3, suppress=True) builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.001) diff --git a/bindings/pydairlib/franka/urdf/active_block.sdf b/bindings/pydairlib/franka/urdf/active_block.sdf index 673ac81500..0cf5c974ec 100644 --- a/bindings/pydairlib/franka/urdf/active_block.sdf +++ b/bindings/pydairlib/franka/urdf/active_block.sdf @@ -7,12 +7,12 @@ 0 0 0 0 0 0 1 - 0.014167 - 0 - 0 - 0.33417 - 0 - 0.34667 + 0.014167 + 0 + 0 + 0.33417 + 0 + 0.34667 diff --git a/bindings/pydairlib/franka/urdf/passive_block.sdf b/bindings/pydairlib/franka/urdf/passive_block.sdf index 1ba1efca6d..b606dcf264 100644 --- a/bindings/pydairlib/franka/urdf/passive_block.sdf +++ b/bindings/pydairlib/franka/urdf/passive_block.sdf @@ -8,14 +8,14 @@ 0 0 0 0 0 0 - 0.2 + 1 - 0.0028333 + 0.014167 0 0 - 0.0028333 + 0.014167 0 - 0.0053333 + 0.026667 diff --git a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf index 932c83ea7e..1129749025 100644 --- a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf +++ b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf @@ -7,15 +7,15 @@ - 0 0 0 0 0 0 - 0.2 + 0 0 -0.05 0 0 0 + 1 - 0.0028333 + 4e-07 0 0 - 0.0028333 + 0.04 0 - 0.0053333 + 0.04 @@ -30,7 +30,7 @@ - -0.2 0.0 -0.05 0 0 0 + -0.2 0.0 -0.049 0 0 0 0.001" @@ -38,7 +38,7 @@ - 0.2 0.0 -0.05 0 0 0 + 0.2 0.0 -0.049 0 0 0 0.001" diff --git a/bindings/pydairlib/solvers/c3_py.cc b/bindings/pydairlib/solvers/c3_py.cc index ef9bbe5a5f..daa6c3aceb 100644 --- a/bindings/pydairlib/solvers/c3_py.cc +++ b/bindings/pydairlib/solvers/c3_py.cc @@ -75,6 +75,7 @@ PYBIND11_MODULE(c3, m) { arg("LCS"), arg("costs"), arg("x_des"), arg("c3_options")) .def("Solve", &C3MIQP::Solve, arg("x0")) .def("UpdateTarget", &C3MIQP::UpdateTarget, arg("x0")) + .def("UpdateLCS", &C3MIQP::UpdateLCS, arg("lcs")) .def("ADMMStep", &C3MIQP::ADMMStep, arg("x0"), arg("delta"), arg("w"), arg("G"), arg("admm_iteration")) .def("SolveQP", &C3MIQP::SolveQP, arg("x0"), arg("G"), arg("WD"), diff --git a/multibody/geom_geom_collider.cc b/multibody/geom_geom_collider.cc index c8c023a068..e34bdfbed6 100644 --- a/multibody/geom_geom_collider.cc +++ b/multibody/geom_geom_collider.cc @@ -1,7 +1,7 @@ #include "multibody/geom_geom_collider.h" #include "drake/math/rotation_matrix.h" - +#include using drake::EigenPtr; using drake::MatrixX; using drake::VectorX; @@ -128,7 +128,7 @@ std::pair> GeomGeomCollider::DoEval( plant_.world_frame(), plant_.world_frame(), &Jv_WCb); - const auto& R_WC = drake::math::RotationMatrix::MakeFromOneVector( + auto R_WC = drake::math::RotationMatrix::MakeFromOneVector( signed_distance_pair.nhat_BA_W, 0); // if this is a planar problem, then the basis has one row and encodes @@ -138,8 +138,8 @@ std::pair> GeomGeomCollider::DoEval( // thus the somewhat awkward calculations here. if (planar) { Vector3d planar_normal = force_basis.row(0); + force_basis = Eigen::MatrixXd::Zero(3, 3); force_basis.resize(3, 3); - // First row is the contact normal, projected to the plane force_basis.row(0) = signed_distance_pair.nhat_BA_W - @@ -150,6 +150,7 @@ std::pair> GeomGeomCollider::DoEval( force_basis.row(1) = signed_distance_pair.nhat_BA_W.cross(planar_normal); force_basis.row(1).normalize(); force_basis.row(2) = -force_basis.row(1); + R_WC = drake::math::RotationMatrix::Identity(); } // Standard case auto J = force_basis * R_WC.matrix().transpose() * (Jv_WCa - Jv_WCb); diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 941c99e182..1895514c9a 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -11,7 +11,7 @@ C3MIQP::C3MIQP(const LCS& LCS, const CostMatrices& costs, const vector& xdesired, const C3Options& options) : C3(LCS, costs, xdesired, options), env_(true) { // Create an environment -// env_.set("LogToConsole", "1"); + env_.set("LogToConsole", "0"); env_.set("OutputFlag", "1"); env_.set("Threads", "0"); env_.start(); @@ -211,7 +211,9 @@ VectorXd C3MIQP::SolveRobustSingleProjection( MatrixXd P_t(m_, n_ + m_ + k_); int constraint_rows = m_; P_t << W_x, W_l, W_u; - +// std::cout << "W_x: " << W_x << std::endl; +// std::cout << "W_l: " << W_l << std::endl; +// std::cout << "W_u: " << W_u << std::endl; // stewart and trinkle // P_t << E, F, H; // MatrixXd P_t2 = P_t.bottomRows(((m_ / 6) * 4) / 7 * 3); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index d979afb2d8..18483ab941 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -96,17 +96,27 @@ LCS LCSFactory::LinearizePlantToLCS( for (int i = 0; i < n_contacts; i++) { multibody::GeomGeomCollider collider( plant, - contact_geoms[i]); // deleted num_friction_directions (check with - // Michael about changes in geomgeom) - auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); + contact_geoms[i]); + if (num_friction_directions == 1) { + Eigen::Vector3d planar_normal; + planar_normal << 0, -1, 0; + auto [phi_i, J_i] = collider.EvalPlanar(context, planar_normal); + phi(i) = phi_i; + J_n.row(i) = J_i.row(0); + J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, + n_v) = J_i.block(1, 0, 2 * num_friction_directions, n_v); + } else { + auto [phi_i, J_i] = + collider.EvalPolytope(context, num_friction_directions); + phi(i) = phi_i; + J_n.row(i) = J_i.row(0); + J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, + n_v) = J_i.block(1, 0, 2 * num_friction_directions, n_v); + } + // J_i is 3 x n_v // row (0) is contact normal // rows (1-num_friction directions) are the contact tangents - - phi(i) = phi_i; - J_n.row(i) = J_i.row(0); - J_t.block(2 * i * num_friction_directions, 0, 2 * num_friction_directions, - n_v) = J_i.block(1, 0, 2 * num_friction_directions, n_v); } auto M_ldlt = ExtractValue(M).ldlt(); From bda5d64e7ea0ab3b2072ef20684d137ea106256b Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 20 Jun 2024 15:00:49 -0400 Subject: [PATCH 738/758] working but not great example --- bindings/pydairlib/franka/planar_box_example.py | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index 0b259ed182..4c655c5aa8 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -84,7 +84,7 @@ def __init__(self, plant, plant_context): self.c3_options.warm_start = 1 self.c3_options.use_predicted_x0 = 1 self.c3_options.end_on_qp_step = 0 - self.c3_options.use_robust_formulation = 1 + self.c3_options.use_robust_formulation = 0 self.c3_options.solve_time_filter_alpha = 0.95 self.c3_options.publish_frequency = 0 self.c3_options.u_horizontal_limits = np.array([-5, 5]) @@ -116,8 +116,9 @@ def CalcOutput(self, context, output): self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, np.array([0])) self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) - # if context.get_time() > self.last_update_time + (5 * self.dt): - if context.get_time() > self.last_update_time + (self.dt): # execute first knot point of the plan + if context.get_time() > self.last_update_time + (5 * self.dt): + # if context.get_time() > self.last_update_time + (self.dt): # execute first knot point of the plan + # self.x_des = np.array([0.5 * np.sin(context.get_time()), 0.5 * np.sin(context.get_time()), 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) if context.get_time() // 10 % 2 == 0: self.x_des = np.array([0.0, -0.3, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) else: @@ -143,7 +144,7 @@ def CalcOutput(self, context, output): self.c3_solver = C3MIQP(lcs, costs, (self.N + 1) * [self.x_des], self.c3_options) else: print("updating target") - self.c3_solver.UpdateLCS(lcs) + # self.c3_solver.UpdateLCS(lcs) self.c3_solver.UpdateTarget((self.N + 1) * [self.x_des]) self.c3_solver.Solve(x.value()) u_sol = self.c3_solver.GetInputSolution() @@ -192,7 +193,7 @@ def main(): context = simulator.get_context() plant.SetPositions(diagram.GetMutableSubsystemContext(plant, simulator.get_mutable_context()), - np.array([0.0, 0.3, 0.1, 0])) # active x, passive: x, z, theta + np.array([0.0, 0.0, 0.1, 0])) # active x, passive: x, z, theta simulator.Initialize() simulator.set_target_realtime_rate(1.0) simulator.AdvanceTo(60.0) From 44f28eee30f00d630cdd7bd7896198984bec631e Mon Sep 17 00:00:00 2001 From: William Yang Date: Thu, 20 Jun 2024 17:46:08 -0400 Subject: [PATCH 739/758] debugging consensus const --- .../pydairlib/franka/planar_box_example.py | 21 ++++++++++++------- .../franka/urdf/passive_block_lcs.sdf | 4 ++-- 2 files changed, 16 insertions(+), 9 deletions(-) diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index 4c655c5aa8..ecc50e0224 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -73,16 +73,16 @@ def __init__(self, plant, plant_context): self.Q = 50 * np.diag(np.array([1000, 5000, 10, 10, 5, 10, 5, 5])) self.R = 5 * np.eye(1) # self.G = 0.5 * np.eye(8 + 8 + 1) - self.G = 0.1 * np.diag(np.hstack((np.ones(4), 0.1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) - self.U = 0.1 * np.diag(np.hstack((np.ones(4), 0.1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) - self.c3_options.admm_iter = 4 + self.G = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) + self.U = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) + self.c3_options.admm_iter = 10 self.c3_options.rho = 0 - self.c3_options.rho_scale = 4 + self.c3_options.rho_scale = 2 self.c3_options.num_threads = 4 self.c3_options.delta_option = 1 self.c3_options.contact_model = "anitescu" self.c3_options.warm_start = 1 - self.c3_options.use_predicted_x0 = 1 + self.c3_options.use_predicted_x0 = 0 self.c3_options.end_on_qp_step = 0 self.c3_options.use_robust_formulation = 0 self.c3_options.solve_time_filter_alpha = 0.95 @@ -116,7 +116,7 @@ def CalcOutput(self, context, output): self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, np.array([0])) self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) - if context.get_time() > self.last_update_time + (5 * self.dt): + if context.get_time() > self.last_update_time + (1 * self.dt): # if context.get_time() > self.last_update_time + (self.dt): # execute first knot point of the plan # self.x_des = np.array([0.5 * np.sin(context.get_time()), 0.5 * np.sin(context.get_time()), 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) if context.get_time() // 10 % 2 == 0: @@ -149,6 +149,13 @@ def CalcOutput(self, context, output): self.c3_solver.Solve(x.value()) u_sol = self.c3_solver.GetInputSolution() x_sol = self.c3_solver.GetStateSolution() + w_sol = self.c3_solver.GetDualWSolution() + delta_sol = self.c3_solver.GetDualDeltaSolution() + z_sol = self.c3_solver.GetFullSolution() + # print(w_sol) + print(delta_sol) + print(z_sol) + import pdb; pdb.set_trace() # print((x.value() - self.x_des)[:2]) # print(np.array(x_sol)[:, 0]) @@ -162,7 +169,7 @@ def CalcOutput(self, context, output): def main(): - np.set_printoptions(3, threshold=3, suppress=True) + # np.set_printoptions(3, threshold=3, suppress=True) builder = DiagramBuilder() plant, scene_graph = AddMultibodyPlantSceneGraph(builder, 0.001) diff --git a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf index 1129749025..92a01b8656 100644 --- a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf +++ b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf @@ -30,7 +30,7 @@ - -0.2 0.0 -0.049 0 0 0 + -0.2 0.0 -0.048 0 0 0 0.001" @@ -38,7 +38,7 @@ - 0.2 0.0 -0.049 0 0 0 + 0.2 0.0 -0.048 0 0 0 0.001" From 831cdbfb28a1e15fd25b061373dca1ba7575927d Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 21 Jun 2024 14:18:24 -0400 Subject: [PATCH 740/758] reexamining planar box example because sdf links have default mass of 1 --- .../pydairlib/franka/planar_box_example.py | 57 +++++++++++-------- solvers/lcs_factory.cc | 3 +- 2 files changed, 33 insertions(+), 27 deletions(-) diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index ecc50e0224..e1d27fa352 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -47,6 +47,7 @@ def __init__(self, plant, plant_context): self.plant_for_lcs.GetFrameByName("base", self.passive_block_index)) self.plant_for_lcs.Finalize() + lcs_diagram = lcs_builer.Build() diagram_context = lcs_diagram.CreateDefaultContext() @@ -72,15 +73,18 @@ def __init__(self, plant, plant_context): # self.contact_model = ContactModel.kStewartAndTrinkle self.Q = 50 * np.diag(np.array([1000, 5000, 10, 10, 5, 10, 5, 5])) self.R = 5 * np.eye(1) - # self.G = 0.5 * np.eye(8 + 8 + 1) self.G = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) self.U = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) + + # self.U = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 1 * np.ones(8), 5 * np.ones(1)))) + # self.G = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 1 * np.ones(8), 5 * np.ones(1)))) self.c3_options.admm_iter = 10 self.c3_options.rho = 0 self.c3_options.rho_scale = 2 self.c3_options.num_threads = 4 self.c3_options.delta_option = 1 self.c3_options.contact_model = "anitescu" + # self.c3_options.contact_model = "stewart_and_trinkle" self.c3_options.warm_start = 1 self.c3_options.use_predicted_x0 = 0 self.c3_options.end_on_qp_step = 0 @@ -110,15 +114,12 @@ def __init__(self, plant, plant_context): def CalcOutput(self, context, output): - x = self.EvalVectorInput(context, 0) - x_u = np.hstack((x.value(), np.array([0]))) - x_u_ad = InitializeAutoDiff(x_u) - self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) - self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, np.array([0])) - self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) - if context.get_time() > self.last_update_time + (1 * self.dt): - # if context.get_time() > self.last_update_time + (self.dt): # execute first knot point of the plan - # self.x_des = np.array([0.5 * np.sin(context.get_time()), 0.5 * np.sin(context.get_time()), 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) + + + if context.get_time() > self.last_update_time + (3 * self.dt): + x = self.EvalVectorInput(context, 0) + x_u = np.hstack((x.value(), self.u.value(context.get_time())[0])) + x_u_ad = InitializeAutoDiff(x_u) if context.get_time() // 10 % 2 == 0: self.x_des = np.array([0.0, -0.3, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) else: @@ -129,12 +130,13 @@ def CalcOutput(self, context, output): print("predicted x1: ", self.predicted_x1) print("actual x1: ", x.value()) # import pdb; pdb.set_trace() + self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) + self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, self.u.value(context.get_time())) + self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) lcs = LinearizePlantToLCS(self.plant_for_lcs, self.context_for_lcs, self.plant_ad, self.context_ad, self.contact_geoms, self.num_friction_directions, self.mu, self.dt, self.N, self.contact_model) - # print(lcs.D_[0]) - # import pdb; pdb.set_trace() Qs = [] for i in range(self.N + 1): Qs.append(1.0 ** i * self.Q) @@ -143,8 +145,7 @@ def CalcOutput(self, context, output): if self.c3_solver == None: self.c3_solver = C3MIQP(lcs, costs, (self.N + 1) * [self.x_des], self.c3_options) else: - print("updating target") - # self.c3_solver.UpdateLCS(lcs) + self.c3_solver.UpdateLCS(lcs) self.c3_solver.UpdateTarget((self.N + 1) * [self.x_des]) self.c3_solver.Solve(x.value()) u_sol = self.c3_solver.GetInputSolution() @@ -152,17 +153,17 @@ def CalcOutput(self, context, output): w_sol = self.c3_solver.GetDualWSolution() delta_sol = self.c3_solver.GetDualDeltaSolution() z_sol = self.c3_solver.GetFullSolution() - # print(w_sol) - print(delta_sol) - print(z_sol) - import pdb; pdb.set_trace() - - # print((x.value() - self.x_des)[:2]) - # print(np.array(x_sol)[:, 0]) - # print(np.array(x_sol)[:, 1]) - self.predicted_x1 = np.array(x_sol)[1, :] + + u_sol = np.array(u_sol) + x_sol = np.array(x_sol) + w_sol = np.array(w_sol) + delta_sol = np.array(delta_sol) + z_sol = np.array(z_sol) + + + self.predicted_x1 = x_sol[1, :] timestamps = context.get_time() + self.dt * np.arange(self.N) - self.u = PiecewisePolynomial.ZeroOrderHold(timestamps, np.array(u_sol).T) + self.u = PiecewisePolynomial.ZeroOrderHold(timestamps, u_sol.T) # self.u = PiecewisePolynomial.FirstOrderHold(timestamps, np.array(u_sol).T) self.last_update_time = context.get_time() output.set_value(self.u.value(context.get_time())) @@ -203,7 +204,13 @@ def main(): np.array([0.0, 0.0, 0.1, 0])) # active x, passive: x, z, theta simulator.Initialize() simulator.set_target_realtime_rate(1.0) - simulator.AdvanceTo(60.0) + meshcat.StartRecording() + simulator.AdvanceTo(20.0) + meshcat.StopRecording() + meshcat.PublishRecording() + with open("planar_box_visualization.html", "r+") as f: + f.write(meshcat.StaticHtml()) + print("done simulating") if __name__ == '__main__': diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 18483ab941..404807c61b 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -99,7 +99,7 @@ LCS LCSFactory::LinearizePlantToLCS( contact_geoms[i]); if (num_friction_directions == 1) { Eigen::Vector3d planar_normal; - planar_normal << 0, -1, 0; + planar_normal << 0, 1, 0; auto [phi_i, J_i] = collider.EvalPlanar(context, planar_normal); phi(i) = phi_i; J_n.row(i) = J_i.row(0); @@ -177,7 +177,6 @@ LCS LCSFactory::LinearizePlantToLCS( dt * dt * qdotNv * MinvJ_t_T; D.block(n_q, 2 * n_contacts, n_v, 2 * n_contacts * num_friction_directions) = dt * MinvJ_t_T; - D.block(0, n_contacts, n_q, n_contacts) = dt * dt * qdotNv * MinvJ_n_T; D.block(n_q, n_contacts, n_v, n_contacts) = dt * MinvJ_n_T; From 3dbad2d9d5ed3aa65c6b8750c61437ac3824a1c1 Mon Sep 17 00:00:00 2001 From: William Yang Date: Fri, 21 Jun 2024 16:42:18 -0400 Subject: [PATCH 741/758] planar box results still don't make sense --- .../pydairlib/franka/planar_box_example.py | 50 ++++++++------ .../pydairlib/franka/urdf/passive_block.sdf | 67 +++++++++++++++---- .../franka/urdf/passive_block_lcs.sdf | 53 +++++++++++++-- 3 files changed, 130 insertions(+), 40 deletions(-) diff --git a/bindings/pydairlib/franka/planar_box_example.py b/bindings/pydairlib/franka/planar_box_example.py index e1d27fa352..e3036ee1ef 100644 --- a/bindings/pydairlib/franka/planar_box_example.py +++ b/bindings/pydairlib/franka/planar_box_example.py @@ -75,10 +75,12 @@ def __init__(self, plant, plant_context): self.R = 5 * np.eye(1) self.G = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) self.U = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 100 * np.ones(4), 5 * np.ones(1)))) + # self.G = 0.1 * np.diag(np.ones(13)) + # self.U = 0.1 * np.diag(np.ones(13)) - # self.U = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 1 * np.ones(8), 5 * np.ones(1)))) - # self.G = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 1 * np.ones(8), 5 * np.ones(1)))) - self.c3_options.admm_iter = 10 + # self.U = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 0.01 * np.ones(8), 5 * np.ones(1)))) + # self.G = 0.1 * np.diag(np.hstack((np.ones(4), 1 * np.ones(4), 0.01 * np.ones(8), 5 * np.ones(1)))) + self.c3_options.admm_iter = 2 self.c3_options.rho = 0 self.c3_options.rho_scale = 2 self.c3_options.num_threads = 4 @@ -111,43 +113,49 @@ def __init__(self, plant, plant_context): self.c3_solver = None self.x_des = np.array([0.0, 0.0, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) self.predicted_x1 = self.x_des - + self.lcs_pred = self.x_des + Qs = [] + for i in range(self.N + 1): + Qs.append(1.0 ** i * self.Q) + # costs = CostMatrices((self.N + 1) * [self.Q], self.N * [self.R], self.N * [self.G], self.N * [self.U]) + self.costs = CostMatrices(Qs, self.N * [self.R], self.N * [self.G], self.N * [self.U]) def CalcOutput(self, context, output): - if context.get_time() > self.last_update_time + (3 * self.dt): + if context.get_time() > self.last_update_time + (0.1 * self.dt): x = self.EvalVectorInput(context, 0) - x_u = np.hstack((x.value(), self.u.value(context.get_time())[0])) + x0 = x.value() + # u0 = np.zeros(1) + u0 = self.u.value(context.get_time())[0] + x_u = np.hstack((x.value(), u0)) x_u_ad = InitializeAutoDiff(x_u) + if context.get_time() // 10 % 2 == 0: self.x_des = np.array([0.0, -0.3, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) else: self.x_des = np.array([0.0, 0.3, 0.1, 0.0, 0.0, 0.0, 0.0, 0.0]) print("time: ", context.get_time()) - print("current cost: ", (x.value() - self.x_des).T @ self.Q @ (x.value() - self.x_des)) + print("current cost: ", (x.value() - self.x_des).T @ (x.value() - self.x_des)) print("desired x: ", self.x_des) - print("predicted x1: ", self.predicted_x1) + print("planned x1: ", self.predicted_x1) + print("lcs pred x1: ", self.lcs_pred) print("actual x1: ", x.value()) # import pdb; pdb.set_trace() - self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x.value()) - self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, self.u.value(context.get_time())) + self.plant_for_lcs.SetPositionsAndVelocities(self.context_for_lcs, x0) + self.plant_for_lcs.get_actuation_input_port().FixValue(self.context_for_lcs, u0) self.plant_ad.get_actuation_input_port().FixValue(self.context_ad, x_u_ad[-1]) lcs = LinearizePlantToLCS(self.plant_for_lcs, self.context_for_lcs, self.plant_ad, self.context_ad, self.contact_geoms, self.num_friction_directions, self.mu, self.dt, self.N, self.contact_model) - Qs = [] - for i in range(self.N + 1): - Qs.append(1.0 ** i * self.Q) - # costs = CostMatrices((self.N + 1) * [self.Q], self.N * [self.R], self.N * [self.G], self.N * [self.U]) - costs = CostMatrices(Qs, self.N * [self.R], self.N * [self.G], self.N * [self.U]) + if self.c3_solver == None: - self.c3_solver = C3MIQP(lcs, costs, (self.N + 1) * [self.x_des], self.c3_options) + self.c3_solver = C3MIQP(lcs, self.costs, (self.N + 1) * [self.x_des], self.c3_options) else: self.c3_solver.UpdateLCS(lcs) self.c3_solver.UpdateTarget((self.N + 1) * [self.x_des]) - self.c3_solver.Solve(x.value()) + self.c3_solver.Solve(x0) u_sol = self.c3_solver.GetInputSolution() x_sol = self.c3_solver.GetStateSolution() w_sol = self.c3_solver.GetDualWSolution() @@ -160,8 +168,12 @@ def CalcOutput(self, context, output): delta_sol = np.array(delta_sol) z_sol = np.array(z_sol) - self.predicted_x1 = x_sol[1, :] + self.lcs_pred = lcs.Simulate(x0, u_sol[0]) + # print(next_pred) + # next_pred = lcs.Simulate(next_pred, u_sol[0]) + # print(next_pred) + # import pdb; pdb.set_trace() timestamps = context.get_time() + self.dt * np.arange(self.N) self.u = PiecewisePolynomial.ZeroOrderHold(timestamps, u_sol.T) # self.u = PiecewisePolynomial.FirstOrderHold(timestamps, np.array(u_sol).T) @@ -205,7 +217,7 @@ def main(): simulator.Initialize() simulator.set_target_realtime_rate(1.0) meshcat.StartRecording() - simulator.AdvanceTo(20.0) + simulator.AdvanceTo(40.0) meshcat.StopRecording() meshcat.PublishRecording() with open("planar_box_visualization.html", "r+") as f: diff --git a/bindings/pydairlib/franka/urdf/passive_block.sdf b/bindings/pydairlib/franka/urdf/passive_block.sdf index b606dcf264..a9b43873f8 100644 --- a/bindings/pydairlib/franka/urdf/passive_block.sdf +++ b/bindings/pydairlib/franka/urdf/passive_block.sdf @@ -2,9 +2,48 @@ - - - + + + 0 0 0 0 0 0 + 0 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0 0 0 0 0 0 + 0 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0 0 0 0 0 0 + 0 + + 0 + 0 + 0 + 0 + 0 + 0 + + + 0 0 0 0 0 0 @@ -18,17 +57,17 @@ 0.026667 - - 0 0 0 0 0 0 - - 0.1 0.1 0.1 0.6 - - - - 0.4 0.4 0.1 - - - + + 0 0 0 0 0 0 + + 0.1 0.1 0.1 0.6 + + + + 0.4 0.4 0.1 + + + 0 0 0 0 0 0 diff --git a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf index 92a01b8656..e218edb31e 100644 --- a/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf +++ b/bindings/pydairlib/franka/urdf/passive_block_lcs.sdf @@ -2,20 +2,59 @@ - - - + + + 0 0 0 0 0 0 + 0 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0 0 0 0 0 0 + 0 + + 0 + 0 + 0 + 0 + 0 + 0 + + + + + + 0 0 0 0 0 0 + 0 + + 0 + 0 + 0 + 0 + 0 + 0 + + + - 0 0 -0.05 0 0 0 + 0 0 0 0 0 0 1 - 4e-07 + 0.014167 0 0 - 0.04 + 0.014167 0 - 0.04 + 0.026667 From 5d86320ca001e9596fb548b113c48a6eac0d46f5 Mon Sep 17 00:00:00 2001 From: sharanyashastry <113148765+sharanyashastry@users.noreply.github.com> Date: Mon, 19 May 2025 20:15:36 -0400 Subject: [PATCH 742/758] Update Drake version to enable building of branch (#369) * Upgraded drake to newest version that required no other changes to build the branch. * Removing white space change. * Adding install prereqs changes to this PR. * Added noenable_bzlmod flag in bazelrc. --- .bazelrc | 2 ++ WORKSPACE | 4 ++-- install/install_prereqs_jammy.sh | 4 +++- 3 files changed, 7 insertions(+), 3 deletions(-) diff --git a/.bazelrc b/.bazelrc index 25fb2159dd..667f4b0694 100644 --- a/.bazelrc +++ b/.bazelrc @@ -61,3 +61,5 @@ build:omp --linkopt=-fopenmp # use python3 by default build --python_path=python3 + +common --noenable_bzlmod \ No newline at end of file diff --git a/WORKSPACE b/WORKSPACE index 2d5e35a75e..8af20fdf7a 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -11,9 +11,9 @@ workspace(name = "dairlib") # export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake # Choose a revision of Drake to use. -DRAKE_COMMIT = "v1.22.0" +DRAKE_COMMIT = "v1.33.0" -DRAKE_CHECKSUM = "78cf62c177c41f8415ade172c1e6eb270db619f07c4b043d5148e1f35be8da09" +DRAKE_CHECKSUM = "2713ad1ea53ed7b9cfe1ba751eeeab7dc173408753ead21b7bafb0436b92dcf3" # Before changing the COMMIT, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. #DRAKE_CHECKSUM = "0" * 64 diff --git a/install/install_prereqs_jammy.sh b/install/install_prereqs_jammy.sh index 987fe41795..c6ef759e7e 100755 --- a/install/install_prereqs_jammy.sh +++ b/install/install_prereqs_jammy.sh @@ -23,6 +23,8 @@ touch install_prereqs_user_environment.sh wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}.txt" wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-clang.txt" wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-test-only.txt" +wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_bazelisk.sh" +wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_bazel.sh" cd .. mkdir binary_distribution cd binary_distribution @@ -30,7 +32,7 @@ wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/se wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/packages-${ubuntu_codename}.txt" cd .. chmod +x install_prereqs.sh -./install_prereqs.sh +./install_prereqs.sh --with-bazel cd .. rm -rf tmp/ # In addition to drake, install lcm and libbot2 From df15fe62f077ca8ac2ac38ce41d839e05e767562 Mon Sep 17 00:00:00 2001 From: sharanyashastry <113148765+sharanyashastry@users.noreply.github.com> Date: Wed, 21 May 2025 17:02:13 -0400 Subject: [PATCH 743/758] Expose Franka systems for use in other examples, e.g. future sampling_c3 implementation (#371) --------- Co-authored-by: Bibit Bianchini Co-authored-by: Brian-Acosta --- examples/franka/BUILD.bazel | 10 +- examples/franka/diagrams/BUILD.bazel | 1 + .../diagrams/franka_c3_controller_diagram.cc | 4 +- .../diagrams/franka_osc_controller_diagram.cc | 11 +- examples/franka/forward_kinematics_for_lcs.cc | 4 +- examples/franka/franka_bridge_driver_in.cc | 2 +- examples/franka/franka_bridge_driver_out.cc | 2 +- examples/franka/franka_c3_controller.cc | 4 +- .../franka_c3_controller_two_objects.cc | 4 +- examples/franka/franka_osc_controller.cc | 22 +-- examples/franka/systems/BUILD.bazel | 105 +----------- .../franka/systems/c3_trajectory_generator.cc | 2 +- .../franka/systems/end_effector_position.cc | 78 --------- .../franka/systems/end_effector_position.h | 37 ----- systems/BUILD.bazel | 41 +++++ systems/controllers/osc/BUILD.bazel | 42 +++++ .../controllers/osc}/end_effector_force.cc | 15 +- .../controllers/osc}/end_effector_force.h | 0 .../osc}/end_effector_orientation.cc | 10 +- .../osc}/end_effector_orientation.h | 0 .../controllers/osc/end_effector_position.cc | 157 ++++++++++++++++++ .../controllers/osc/end_effector_position.h | 67 ++++++++ .../systems => systems}/franka_kinematics.cc | 2 +- .../systems => systems}/franka_kinematics.h | 2 +- .../franka_kinematics_vector.cc | 2 +- .../franka_kinematics_vector.h | 8 +- .../franka_state_translator.cc | 2 +- .../franka_state_translator.h | 0 systems/robot_lcm_systems.cc | 31 ++-- systems/sender_systems/BUILD.bazel | 25 +++ .../sender_systems}/c3_state_sender.cc | 43 ++++- .../sender_systems}/c3_state_sender.h | 14 ++ 32 files changed, 458 insertions(+), 289 deletions(-) delete mode 100644 examples/franka/systems/end_effector_position.cc delete mode 100644 examples/franka/systems/end_effector_position.h rename {examples/franka/systems => systems/controllers/osc}/end_effector_force.cc (87%) rename {examples/franka/systems => systems/controllers/osc}/end_effector_force.h (100%) rename {examples/franka/systems => systems/controllers/osc}/end_effector_orientation.cc (87%) rename {examples/franka/systems => systems/controllers/osc}/end_effector_orientation.h (100%) create mode 100644 systems/controllers/osc/end_effector_position.cc create mode 100644 systems/controllers/osc/end_effector_position.h rename {examples/franka/systems => systems}/franka_kinematics.cc (98%) rename {examples/franka/systems => systems}/franka_kinematics.h (97%) rename {examples/franka/systems => systems}/franka_kinematics_vector.cc (72%) rename {examples/franka/systems => systems}/franka_kinematics_vector.h (97%) rename {examples/franka/systems => systems}/franka_state_translator.cc (98%) rename {examples/franka/systems => systems}/franka_state_translator.h (100%) create mode 100644 systems/sender_systems/BUILD.bazel rename {examples/franka/systems => systems/sender_systems}/c3_state_sender.cc (51%) rename {examples/franka/systems => systems/sender_systems}/c3_state_sender.h (73%) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 0a0ca93294..62216931cb 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -83,6 +83,8 @@ cc_binary( ":parameters", "//common", "//examples/franka/systems:franka_systems", + "//systems:franka_kinematics", + "//systems/sender_systems:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -109,6 +111,8 @@ cc_binary( ":parameters", "//common", "//examples/franka/systems:franka_systems", + "//systems:franka_kinematics", + "//systems/sender_systems:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -135,6 +139,8 @@ cc_binary( ":parameters", "//common", "//examples/franka/systems:franka_systems", + "//systems:franka_kinematics", + "//systems/sender_systems:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -182,7 +188,7 @@ cc_binary( deps = [ ":parameters", "//common", - "//examples/franka/systems:franka_state_translator", + "//systems:franka_state_translator", "//multibody:utils", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -203,7 +209,7 @@ cc_binary( deps = [ ":parameters", "//common", - "//examples/franka/systems:franka_state_translator", + "//systems:franka_state_translator", "//multibody:utils", "//systems:robot_lcm_systems", "//systems:system_utils", diff --git a/examples/franka/diagrams/BUILD.bazel b/examples/franka/diagrams/BUILD.bazel index db1f2cd374..35085d5fcb 100644 --- a/examples/franka/diagrams/BUILD.bazel +++ b/examples/franka/diagrams/BUILD.bazel @@ -8,6 +8,7 @@ cc_library( "//common", "//examples/franka:parameters", "//examples/franka/systems:franka_systems", + "//systems/sender_systems:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 09f3fc87b2..23062da2a7 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -21,9 +21,9 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/systems/c3_state_sender.h" +#include "systems/sender_systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/franka_kinematics.h" +#include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index b59ebf1720..f62460d438 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -17,9 +17,9 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_osc_controller_params.h" -#include "examples/franka/systems/end_effector_force.h" -#include "examples/franka/systems/end_effector_orientation.h" -#include "examples/franka/systems/end_effector_position.h" +#include "systems/controllers/osc/end_effector_force.h" +#include "systems/controllers/osc/end_effector_orientation.h" +#include "systems/controllers/osc/end_effector_position.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" @@ -116,8 +116,9 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( auto osc_command_sender = builder.AddSystem(*plant_); auto end_effector_trajectory = - builder.AddSystem( - controller_params.neutral_position); + builder.AddSystem(*plant_, + plant_context_.get(), controller_params.neutral_position, false, + controller_params.end_effector_name); auto passthrough = builder.AddSystem>(18); end_effector_trajectory->SetRemoteControlParameters( controller_params.neutral_position, controller_params.x_scale, diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index 937927c80e..711e22ab06 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -14,9 +14,9 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/systems/c3_state_sender.h" +#include "systems/sender_systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/franka_kinematics.h" +#include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" diff --git a/examples/franka/franka_bridge_driver_in.cc b/examples/franka/franka_bridge_driver_in.cc index c08ba518d4..473d566e9e 100644 --- a/examples/franka/franka_bridge_driver_in.cc +++ b/examples/franka/franka_bridge_driver_in.cc @@ -15,7 +15,7 @@ #include "examples/franka/parameters/franka_drake_lcm_driver_channels.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" -#include "examples/franka/systems/franka_state_translator.h" +#include "systems/franka_state_translator.h" #include "multibody/multibody_utils.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/franka/franka_bridge_driver_out.cc b/examples/franka/franka_bridge_driver_out.cc index ce0e80f25f..f9e7286ef8 100644 --- a/examples/franka/franka_bridge_driver_out.cc +++ b/examples/franka/franka_bridge_driver_out.cc @@ -15,7 +15,7 @@ #include "examples/franka/parameters/franka_drake_lcm_driver_channels.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" -#include "examples/franka/systems/franka_state_translator.h" +#include "systems/franka_state_translator.h" #include "multibody/multibody_utils.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index b18e5f750b..da028effa1 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -12,9 +12,9 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/systems/c3_state_sender.h" +#include "systems/sender_systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/franka_kinematics.h" +#include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" diff --git a/examples/franka/franka_c3_controller_two_objects.cc b/examples/franka/franka_c3_controller_two_objects.cc index dfba0d63cc..ff12d61aac 100644 --- a/examples/franka/franka_c3_controller_two_objects.cc +++ b/examples/franka/franka_c3_controller_two_objects.cc @@ -14,9 +14,9 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "examples/franka/systems/c3_state_sender.h" +#include "systems/sender_systems/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" -#include "examples/franka/systems/franka_kinematics.h" +#include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" #include "multibody/multibody_utils.h" #include "solvers/lcs_factory.h" diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index ebd362bd98..61bef2cda2 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -6,9 +6,9 @@ #include "common/eigen_utils.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_osc_controller_params.h" -#include "examples/franka/systems/end_effector_force.h" -#include "examples/franka/systems/end_effector_orientation.h" -#include "examples/franka/systems/end_effector_position.h" +#include "systems/controllers/osc/end_effector_force.h" +#include "systems/controllers/osc/end_effector_orientation.h" +#include "systems/controllers/osc/end_effector_position.h" #include "lcm/lcm_trajectory.h" #include "multibody/multibody_utils.h" #include "systems/controllers/gravity_compensator.h" @@ -138,10 +138,12 @@ int DoMain(int argc, char* argv[]) { auto osc_command_sender = builder.AddSystem(plant); auto end_effector_trajectory = - builder.AddSystem(controller_params.neutral_position); + builder.AddSystem(plant, + plant_context.get(), controller_params.neutral_position, false, + controller_params.end_effector_name); end_effector_trajectory->SetRemoteControlParameters( - controller_params.neutral_position, controller_params.x_scale, controller_params.y_scale, - controller_params.z_scale); + controller_params.neutral_position, controller_params.x_scale, + controller_params.y_scale, controller_params.z_scale); auto end_effector_orientation_trajectory = builder.AddSystem(); end_effector_orientation_trajectory->SetTrackOrientation( @@ -151,7 +153,6 @@ int DoMain(int argc, char* argv[]) { auto radio_sub = builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); - auto radio_to_vector = builder.AddSystem(); auto osc = builder.AddSystem( plant, plant, plant_context.get(), plant_context.get(), false); if (controller_params.publish_debug_info) { @@ -233,12 +234,11 @@ int DoMain(int argc, char* argv[]) { franka_command_sender->get_input_port(0)); } - builder.Connect(*radio_sub, *radio_to_vector); - builder.Connect(radio_to_vector->get_output_port(), + builder.Connect(radio_sub->get_output_port(), end_effector_trajectory->get_input_port_radio()); - builder.Connect(radio_to_vector->get_output_port(), + builder.Connect(radio_sub->get_output_port(), end_effector_orientation_trajectory->get_input_port_radio()); - builder.Connect(radio_to_vector->get_output_port(), + builder.Connect(radio_sub->get_output_port(), end_effector_force_trajectory->get_input_port_radio()); builder.Connect(franka_command_sender->get_output_port(), franka_command_pub->get_input_port()); diff --git a/examples/franka/systems/BUILD.bazel b/examples/franka/systems/BUILD.bazel index 6551f6f3b9..2f2e1e7fc1 100644 --- a/examples/franka/systems/BUILD.bazel +++ b/examples/franka/systems/BUILD.bazel @@ -4,14 +4,8 @@ cc_library( name = "franka_systems", srcs = [], deps = [ - ":c3_state_sender", ":c3_trajectory_generator", - ":end_effector_force_trajectory", - ":end_effector_orientation_trajectory", - ":end_effector_position_trajectory", ":external_force_generator", - ":franka_kinematics", - ":franka_state_translator", ":plate_balancing_target", ], ) @@ -29,45 +23,6 @@ cc_library( ], ) -cc_library( - name = "end_effector_position_trajectory", - srcs = ["end_effector_position.cc"], - hdrs = ["end_effector_position.h"], - deps = [ - "//lcmtypes:lcmt_robot", - "//multibody:utils", - "//systems/framework:vector", - "@drake//:drake_shared_library", - "@lcm", - ], -) - -cc_library( - name = "end_effector_force_trajectory", - srcs = ["end_effector_force.cc"], - hdrs = ["end_effector_force.h"], - deps = [ - "//lcmtypes:lcmt_robot", - "//multibody:utils", - "//systems/framework:vector", - "@drake//:drake_shared_library", - "@lcm", - ], -) - -cc_library( - name = "end_effector_orientation_trajectory", - srcs = ["end_effector_orientation.cc"], - hdrs = ["end_effector_orientation.h"], - deps = [ - "//lcmtypes:lcmt_robot", - "//multibody:utils", - "//systems/framework:vector", - "@drake//:drake_shared_library", - "@lcm", - ], -) - cc_library( name = "plate_balancing_target", srcs = ["plate_balancing_target.cc"], @@ -90,7 +45,7 @@ cc_library( "c3_trajectory_generator.h", ], deps = [ - ":franka_kinematics", + "//systems:franka_kinematics", "//common:find_resource", "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", @@ -101,60 +56,4 @@ cc_library( "//systems/framework:vector", "@drake//:drake_shared_library", ], -) - -cc_library( - name = "c3_state_sender", - srcs = [ - "c3_state_sender.cc", - ], - hdrs = [ - "c3_state_sender.h", - ], - deps = [ - "//lcmtypes:lcmt_robot", - "//systems/framework:vector", - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_state_translator", - srcs = [ - "franka_state_translator.cc", - ], - hdrs = [ - "franka_state_translator.h", - ], - deps = [ - "//lcmtypes:lcmt_robot", - "//systems/framework:vector", - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_kinematics", - srcs = ["franka_kinematics.cc"], - hdrs = ["franka_kinematics.h"], - deps = [ - ":franka_kinematics_vector", - "//common", - "//lcmtypes:lcmt_robot", - "//multibody:utils", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) - -cc_library( - name = "franka_kinematics_vector", - srcs = ["franka_kinematics_vector.cc"], - hdrs = ["franka_kinematics_vector.h"], - deps = [ - "//common", - "//multibody:utils", - "//systems/primitives", - "@drake//:drake_shared_library", - ], -) +) \ No newline at end of file diff --git a/examples/franka/systems/c3_trajectory_generator.cc b/examples/franka/systems/c3_trajectory_generator.cc index 9af7656509..024223162b 100644 --- a/examples/franka/systems/c3_trajectory_generator.cc +++ b/examples/franka/systems/c3_trajectory_generator.cc @@ -4,7 +4,7 @@ #include "common/find_resource.h" #include "dairlib/lcmt_timestamped_saved_traj.hpp" -#include "examples/franka/systems/franka_kinematics_vector.h" +#include "systems/franka_kinematics_vector.h" #include "multibody/multibody_utils.h" #include "solvers/c3_output.h" #include "solvers/lcs.h" diff --git a/examples/franka/systems/end_effector_position.cc b/examples/franka/systems/end_effector_position.cc deleted file mode 100644 index 5d76601224..0000000000 --- a/examples/franka/systems/end_effector_position.cc +++ /dev/null @@ -1,78 +0,0 @@ -#include "end_effector_position.h" -#include -#include "dairlib/lcmt_radio_out.hpp" -#include "multibody/multibody_utils.h" - -using Eigen::Map; -using Eigen::MatrixXd; -using Eigen::VectorXd; -using std::string; - -using drake::systems::BasicVector; -using drake::systems::Context; -using drake::systems::DiscreteUpdateEvent; -using drake::systems::DiscreteValues; -using drake::systems::EventStatus; -using drake::trajectories::PiecewisePolynomial; -using drake::trajectories::Trajectory; - -namespace dairlib { - -EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator(const Eigen::Vector3d& neutral_pose) { - // Input/Output Setup - PiecewisePolynomial pp = PiecewisePolynomial(); - - trajectory_port_ = - this->DeclareAbstractInputPort( - "trajectory", - drake::Value>(pp)) - .get_index(); - radio_port_ = - this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) - .get_index(); - - PiecewisePolynomial empty_pp_traj(neutral_pose); - Trajectory& traj_inst = empty_pp_traj; - this->DeclareAbstractOutputPort("end_effector_trajectory", traj_inst, - &EndEffectorTrajectoryGenerator::CalcTraj); -} - -void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( - const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, - double z_scale) { - neutral_pose_ = neutral_pose; - x_scale_ = x_scale; - y_scale_ = y_scale; - z_scale_ = z_scale; -} - -void EndEffectorTrajectoryGenerator::CalcTraj( - const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const { - const auto& trajectory_input = - this->EvalAbstractInput(context, trajectory_port_) - ->get_value>(); - const auto& radio_out = this->EvalVectorInput(context, radio_port_); - auto* casted_traj = - (PiecewisePolynomial*)dynamic_cast*>( - traj); - if (radio_out->value()[14]) { - PiecewisePolynomial result; - VectorXd y_0 = neutral_pose_; - if (radio_out->value()[10]){ - y_0(0) += radio_out->value()[0] * x_scale_; - y_0(1) += radio_out->value()[1] * y_scale_; - y_0(2) += radio_out->value()[2] * z_scale_; - } - result = drake::trajectories::PiecewisePolynomial(y_0); - *casted_traj = result; - } else { - if (trajectory_input.value(0).isZero()) { - } else { - *casted_traj = *(PiecewisePolynomial*)dynamic_cast< - const PiecewisePolynomial*>(&trajectory_input); - } - } -} - -} // namespace dairlib diff --git a/examples/franka/systems/end_effector_position.h b/examples/franka/systems/end_effector_position.h deleted file mode 100644 index f98c443cb8..0000000000 --- a/examples/franka/systems/end_effector_position.h +++ /dev/null @@ -1,37 +0,0 @@ -#pragma once - -#include "drake/common/trajectories/piecewise_polynomial.h" -#include "drake/systems/framework/leaf_system.h" - -namespace dairlib { - -class EndEffectorTrajectoryGenerator - : public drake::systems::LeafSystem { - public: - EndEffectorTrajectoryGenerator(const Eigen::Vector3d& neutral_pose); - - const drake::systems::InputPort& get_input_port_trajectory() const { - return this->get_input_port(trajectory_port_); - } - const drake::systems::InputPort& get_input_port_radio() const { - return this->get_input_port(radio_port_); - } - - void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, - double x_scale, double y_scale, - double z_scale); - - private: - void CalcTraj(const drake::systems::Context& context, - drake::trajectories::Trajectory* traj) const; - - drake::systems::InputPortIndex trajectory_port_; - drake::systems::InputPortIndex radio_port_; - - Eigen::Vector3d neutral_pose_ = {0.55, 0, 0.40}; - double x_scale_; - double y_scale_; - double z_scale_; -}; - -} // namespace dairlib diff --git a/systems/BUILD.bazel b/systems/BUILD.bazel index bbc897c752..9c26e30887 100644 --- a/systems/BUILD.bazel +++ b/systems/BUILD.bazel @@ -33,3 +33,44 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "franka_kinematics", + srcs = ["franka_kinematics.cc"], + hdrs = ["franka_kinematics.h"], + deps = [ + ":franka_kinematics_vector", + "//common", + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_kinematics_vector", + srcs = ["franka_kinematics_vector.cc"], + hdrs = ["franka_kinematics_vector.h"], + deps = [ + "//common", + "//multibody:utils", + "//systems/primitives", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_state_translator", + srcs = [ + "franka_state_translator.cc", + ], + hdrs = [ + "franka_state_translator.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) \ No newline at end of file diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index dd675d3851..8a8a82a367 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -24,6 +24,9 @@ cc_library( "//systems/controllers:controller_failure_aggregator", "//systems/framework:vector", "@drake//:drake_shared_library", + ":end_effector_force", + ":end_effector_orientation", + ":end_effector_position", ], ) @@ -145,3 +148,42 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "end_effector_position", + srcs = ["end_effector_position.cc"], + hdrs = ["end_effector_position.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + +cc_library( + name = "end_effector_force", + srcs = ["end_effector_force.cc"], + hdrs = ["end_effector_force.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + +cc_library( + name = "end_effector_orientation", + srcs = ["end_effector_orientation.cc"], + hdrs = ["end_effector_orientation.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) \ No newline at end of file diff --git a/examples/franka/systems/end_effector_force.cc b/systems/controllers/osc/end_effector_force.cc similarity index 87% rename from examples/franka/systems/end_effector_force.cc rename to systems/controllers/osc/end_effector_force.cc index 62fcb4a474..ac03669cd4 100644 --- a/examples/franka/systems/end_effector_force.cc +++ b/systems/controllers/osc/end_effector_force.cc @@ -30,9 +30,8 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator() { "trajectory", drake::Value>(pp)) .get_index(); - radio_port_ = - this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) - .get_index(); + radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}).get_index(); controller_switch_index_ = this->DeclareDiscreteState(VectorXd::Ones(1)); DeclareForcedDiscreteUpdateEvent( &EndEffectorForceTrajectoryGenerator::DiscreteVariableUpdate); @@ -46,12 +45,13 @@ EndEffectorForceTrajectoryGenerator::EndEffectorForceTrajectoryGenerator() { EventStatus EndEffectorForceTrajectoryGenerator::DiscreteVariableUpdate( const drake::systems::Context& context, drake::systems::DiscreteValues* discrete_state) const { - const auto& radio_out = this->EvalVectorInput(context, radio_port_); + const auto& radio_out = this->EvalInputValue( + context, radio_port_); const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); bool using_c3 = context.get_discrete_state(controller_switch_index_)[0]; - if (!using_c3 && radio_out->value()[14] == 0) { + if (!using_c3 && radio_out->channel[14] == 0) { if (!trajectory_input.value(0).isZero() && (context.get_time() - trajectory_input.start_time()) < 0.04) { discrete_state->get_mutable_value(controller_switch_index_)[0] = 1; @@ -67,11 +67,12 @@ void EndEffectorForceTrajectoryGenerator::CalcTraj( const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); - const auto& radio_out = this->EvalVectorInput(context, radio_port_); + const auto& radio_out = this->EvalInputValue( + context, radio_port_); auto* casted_traj = (PiecewisePolynomial*)dynamic_cast*>( traj); - if (radio_out->value()[11] || radio_out->value()[14] || + if (radio_out->channel[11] || radio_out->channel[14] || trajectory_input.value(0).isZero()) { *casted_traj = drake::trajectories::PiecewisePolynomial(Vector3d::Zero()); diff --git a/examples/franka/systems/end_effector_force.h b/systems/controllers/osc/end_effector_force.h similarity index 100% rename from examples/franka/systems/end_effector_force.h rename to systems/controllers/osc/end_effector_force.h diff --git a/examples/franka/systems/end_effector_orientation.cc b/systems/controllers/osc/end_effector_orientation.cc similarity index 87% rename from examples/franka/systems/end_effector_orientation.cc rename to systems/controllers/osc/end_effector_orientation.cc index f49b5ef86e..0c49fbc631 100644 --- a/examples/franka/systems/end_effector_orientation.cc +++ b/systems/controllers/osc/end_effector_orientation.cc @@ -21,9 +21,8 @@ EndEffectorOrientationTrajectoryGenerator::EndEffectorOrientationTrajectoryGener "trajectory", drake::Value>(pp)) .get_index(); - radio_port_ = - this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) - .get_index(); + radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}).get_index(); PiecewiseQuaternionSlerp empty_slerp_traj; Trajectory& traj_inst = empty_slerp_traj; this->DeclareAbstractOutputPort("end_effector_orientation", traj_inst, @@ -34,10 +33,11 @@ EndEffectorOrientationTrajectoryGenerator::EndEffectorOrientationTrajectoryGener void EndEffectorOrientationTrajectoryGenerator::CalcTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { - const auto& radio_out = this->EvalVectorInput(context, radio_port_); + const auto& radio_out = this->EvalInputValue( + context, radio_port_); auto* casted_traj = (PiecewiseQuaternionSlerp*)dynamic_cast< PiecewiseQuaternionSlerp*>(traj); - if (radio_out->value()[14] and track_orientation_) { + if (radio_out->channel[14] and track_orientation_) { const auto& trajectory_input = this->EvalAbstractInput(context, trajectory_port_) ->get_value>(); diff --git a/examples/franka/systems/end_effector_orientation.h b/systems/controllers/osc/end_effector_orientation.h similarity index 100% rename from examples/franka/systems/end_effector_orientation.h rename to systems/controllers/osc/end_effector_orientation.h diff --git a/systems/controllers/osc/end_effector_position.cc b/systems/controllers/osc/end_effector_position.cc new file mode 100644 index 0000000000..835b1f4c90 --- /dev/null +++ b/systems/controllers/osc/end_effector_position.cc @@ -0,0 +1,157 @@ +/**This system is used by the osc diagram to read an end effector trajectory + * from an lcm message and pass it onto the OSC class. It allows for teleop to + * track the current end effector position or a neutral position based on the + * teleop_neutral_pose flag. */ +#include "end_effector_position.h" +#include +#include "dairlib/lcmt_radio_out.hpp" +#include "multibody/multibody_utils.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::VectorXd; +using std::string; + +using dairlib::systems::OutputVector; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib { + +EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( + const MultibodyPlant& plant, Context* context, + const Eigen::VectorXd& neutral_pose, bool teleop_neutral_pose, + const std::string& end_effector_name) + : plant_(plant), context_(context), end_effector_name_(end_effector_name) { + // Input/Output Setup + state_port_ = this->DeclareVectorInputPort( + "x", OutputVector(plant_.num_positions(), + plant_.num_velocities(), + plant_.num_actuators())) + .get_index(); + PiecewisePolynomial pp = PiecewisePolynomial(); + + trajectory_port_ = + this->DeclareAbstractInputPort( + "trajectory", + drake::Value>(pp)) + .get_index(); + radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}).get_index(); + + PiecewisePolynomial empty_pp_traj(neutral_pose); + Trajectory& traj_inst = empty_pp_traj; + if (teleop_neutral_pose) { + this->DeclareAbstractOutputPort( + "end_effector_trajectory", traj_inst, + &EndEffectorTrajectoryGenerator::CalcPoseShiftingTraj); + } + else { + this->DeclareAbstractOutputPort( + "end_effector_trajectory", traj_inst, + &EndEffectorTrajectoryGenerator::CalcNeutralPoseBasedTraj); + } +} + +void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( + const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, + double z_scale) { + neutral_pose_ = neutral_pose; + shifting_pose_ = neutral_pose; + x_scale_ = x_scale; + y_scale_ = y_scale; + z_scale_ = z_scale; +} + +void EndEffectorTrajectoryGenerator::CalcNeutralPoseBasedTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + const auto& radio_out = this->EvalInputValue( + context, radio_port_); + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (radio_out->channel[14]) { + PiecewisePolynomial result; + + // Compute the target position based on an offset from neutral pose. + VectorXd y_0 = neutral_pose_; + y_0(0) += radio_out->channel[0] * x_scale_; + y_0(1) += radio_out->channel[1] * y_scale_; + y_0(2) += radio_out->channel[2] * z_scale_; + + result = drake::trajectories::PiecewisePolynomial(y_0); + *casted_traj = result; + } else { + if (trajectory_input.value(0).isZero()) { + } else { + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } + } +} + +void EndEffectorTrajectoryGenerator::CalcPoseShiftingTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const { + const auto& trajectory_input = + this->EvalAbstractInput(context, trajectory_port_) + ->get_value>(); + const auto& radio_out = this->EvalInputValue( + context, radio_port_); + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + traj); + if (radio_out->channel[14]) { + if (!was_in_teleop_mode_) { + // Update the shifting position to the current position -- this means + // every time teleop mode is newly entered, the robot will stay where it + // is instead of snapping to the neutral position elsewhere. + const OutputVector* franka_state = + (OutputVector*)this->EvalVectorInput(context, state_port_); + VectorXd q_franka = franka_state->GetPositions(); + multibody::SetPositionsIfNew(plant_, q_franka, + context_); + auto end_effector_pose = plant_.EvalBodyPoseInWorld( + *context_, plant_.GetBodyByName(end_effector_name_)); + shifting_pose_ = end_effector_pose.translation(); + } + was_in_teleop_mode_ = true; + + PiecewisePolynomial result; + + // Compute the target position by stepping the held pose. + if (std::abs(radio_out->channel[0]) > 0.01) { + shifting_pose_(0) += radio_out->channel[0] * x_scale_; + } + if (std::abs(radio_out->channel[1]) > 0.01) { + shifting_pose_(1) += radio_out->channel[1] * y_scale_; + } + if (std::abs(radio_out->channel[2]) > 0.01) { + shifting_pose_(2) += radio_out->channel[2] * z_scale_; + } + VectorXd y_0 = shifting_pose_; + + result = drake::trajectories::PiecewisePolynomial(y_0); + *casted_traj = result; + } + else { + was_in_teleop_mode_ = false; + if (trajectory_input.value(0).isZero()) { + } else { + *casted_traj = *(PiecewisePolynomial*)dynamic_cast< + const PiecewisePolynomial*>(&trajectory_input); + } + } +} + +} // namespace dairlib diff --git a/systems/controllers/osc/end_effector_position.h b/systems/controllers/osc/end_effector_position.h new file mode 100644 index 0000000000..4cf7c0f240 --- /dev/null +++ b/systems/controllers/osc/end_effector_position.h @@ -0,0 +1,67 @@ +/**This system is used by the osc diagram to read an end effector trajectory + * from an lcm message and pass it onto the OSC class. It allows for teleop to + * track the current end effector position or a neutral position based on the + * teleop_neutral_pose flag. */ +#pragma once + +#include +#include "systems/framework/output_vector.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class EndEffectorTrajectoryGenerator + : public drake::systems::LeafSystem { + public: + EndEffectorTrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + const Eigen::VectorXd& neutral_pose, + bool teleop_neutral_pose, + const std::string& end_effector_name); + + const drake::systems::InputPort& get_input_port_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_trajectory() const { + return this->get_input_port(trajectory_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + void SetRemoteControlParameters(const Eigen::Vector3d& neutral_pose, + double x_scale, double y_scale, + double z_scale); + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcNeutralPoseBasedTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + void CalcPoseShiftingTraj( + const drake::systems::Context& context, + drake::trajectories::Trajectory* traj) const; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex trajectory_port_; + drake::systems::InputPortIndex radio_port_; + + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + std::string end_effector_name_; + Eigen::Vector3d neutral_pose_ = {0.55, 0, 0.40}; + mutable Eigen::Vector3d shifting_pose_ = {0.55, 0, 0.40}; + mutable bool was_in_teleop_mode_ = false; + double x_scale_; + double y_scale_; + double z_scale_; +}; + +} // namespace dairlib diff --git a/examples/franka/systems/franka_kinematics.cc b/systems/franka_kinematics.cc similarity index 98% rename from examples/franka/systems/franka_kinematics.cc rename to systems/franka_kinematics.cc index 4119c93c27..f5070a6d9f 100644 --- a/examples/franka/systems/franka_kinematics.cc +++ b/systems/franka_kinematics.cc @@ -1,4 +1,4 @@ -#include "examples/franka/systems/franka_kinematics.h" +#include "systems/franka_kinematics.h" #include "common/find_resource.h" #include "multibody/multibody_utils.h" diff --git a/examples/franka/systems/franka_kinematics.h b/systems/franka_kinematics.h similarity index 97% rename from examples/franka/systems/franka_kinematics.h rename to systems/franka_kinematics.h index cc57c8dee7..b3a916d10d 100644 --- a/examples/franka/systems/franka_kinematics.h +++ b/systems/franka_kinematics.h @@ -3,7 +3,7 @@ #include #include #include -#include "examples/franka/systems/franka_kinematics_vector.h" +#include "systems/franka_kinematics_vector.h" #include "drake/systems/framework/leaf_system.h" #include "systems/framework/timestamped_vector.h" diff --git a/examples/franka/systems/franka_kinematics_vector.cc b/systems/franka_kinematics_vector.cc similarity index 72% rename from examples/franka/systems/franka_kinematics_vector.cc rename to systems/franka_kinematics_vector.cc index 6dce76fe09..2b7318e9f0 100644 --- a/examples/franka/systems/franka_kinematics_vector.cc +++ b/systems/franka_kinematics_vector.cc @@ -1,4 +1,4 @@ -#include "examples/franka/systems/franka_kinematics_vector.h" +#include "systems/franka_kinematics_vector.h" #include "drake/common/default_scalars.h" diff --git a/examples/franka/systems/franka_kinematics_vector.h b/systems/franka_kinematics_vector.h similarity index 97% rename from examples/franka/systems/franka_kinematics_vector.h rename to systems/franka_kinematics_vector.h index a3288c7d8e..a6ae261b56 100644 --- a/examples/franka/systems/franka_kinematics_vector.h +++ b/systems/franka_kinematics_vector.h @@ -42,10 +42,10 @@ class FrankaKinematicsVector : public TimestampedVector { /// Constructs a OutputVector with the specified positions and velocities. explicit FrankaKinematicsVector( - const drake::VectorX& end_effector_positions, - const drake::VectorX& object_positions, - const drake::VectorX& end_effector_velocities, - const drake::VectorX& object_velocities) + const drake::VectorX& end_effector_positions, + const drake::VectorX& object_positions, + const drake::VectorX& end_effector_velocities, + const drake::VectorX& object_velocities) : FrankaKinematicsVector( end_effector_positions.size(), object_positions.size(), end_effector_velocities.size(), object_velocities.size()) { diff --git a/examples/franka/systems/franka_state_translator.cc b/systems/franka_state_translator.cc similarity index 98% rename from examples/franka/systems/franka_state_translator.cc rename to systems/franka_state_translator.cc index 46277ddb52..cd6af41d77 100644 --- a/examples/franka/systems/franka_state_translator.cc +++ b/systems/franka_state_translator.cc @@ -1,4 +1,4 @@ -#include "examples/franka/systems/franka_state_translator.h" +#include "franka_state_translator.h" #include diff --git a/examples/franka/systems/franka_state_translator.h b/systems/franka_state_translator.h similarity index 100% rename from examples/franka/systems/franka_state_translator.h rename to systems/franka_state_translator.h diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index b9371c0072..ec26fbe0eb 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -330,12 +330,15 @@ ObjectStateReceiver::ObjectStateReceiver( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant, model_instance); - positions_start_idx_ = - plant.get_joint(plant.GetJointIndices(model_instance).front()) - .position_start(); - velocities_start_idx_ = - plant.get_joint(plant.GetJointIndices(model_instance).front()) - .velocity_start(); + for (const auto& entry : plant.GetJointIndices(model_instance)){ + // If joint.num_positions() == 0, then it is a fixed joint. + // Skip it and fix positions_start_idx_ to be the non fixed joint. + if (plant.get_joint(entry).num_positions() != 0){ + positions_start_idx_ = plant.get_joint(entry).position_start(); + velocities_start_idx_ = plant.get_joint(entry).velocity_start(); + break; + } + } this->DeclareAbstractInputPort("lcmt_object_state", drake::Value{}); this->DeclareVectorOutputPort( @@ -455,12 +458,15 @@ ObjectStateSender::ObjectStateSender( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant, model_instance); - positions_start_idx_ = - plant.get_joint(plant.GetJointIndices(model_instance).front()) - .position_start(); - velocities_start_idx_ = - plant.get_joint(plant.GetJointIndices(model_instance).front()) - .velocity_start(); + for (const auto& entry : plant.GetJointIndices(model_instance)){ + // If joint.num_positions() == 0, then it is a fixed joint. + // Skip it and fix positions_start_idx_ to be the non fixed joint. + if (plant.get_joint(entry).num_positions() != 0){ + positions_start_idx_ = plant.get_joint(entry).position_start(); + velocities_start_idx_ = plant.get_joint(entry).velocity_start(); + break; + } + } ordered_position_names_ = multibody::ExtractOrderedNamesFromMap( position_index_map_, positions_start_idx_); @@ -471,7 +477,6 @@ ObjectStateSender::ObjectStateSender( this->DeclareVectorInputPort( "x", BasicVector(num_positions_ + num_velocities_)) .get_index(); - this->DeclareAbstractOutputPort("lcmt_object_state", &ObjectStateSender::Output); } diff --git a/systems/sender_systems/BUILD.bazel b/systems/sender_systems/BUILD.bazel new file mode 100644 index 0000000000..6d13068b58 --- /dev/null +++ b/systems/sender_systems/BUILD.bazel @@ -0,0 +1,25 @@ +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "sender_systems", + srcs = [], + deps = [ + ":c3_state_sender", + ], +) + +cc_library( + name = "c3_state_sender", + srcs = [ + "c3_state_sender.cc", + ], + hdrs = [ + "c3_state_sender.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + diff --git a/examples/franka/systems/c3_state_sender.cc b/systems/sender_systems/c3_state_sender.cc similarity index 51% rename from examples/franka/systems/c3_state_sender.cc rename to systems/sender_systems/c3_state_sender.cc index 61a8b0f6bc..5e99b4c7b4 100644 --- a/examples/franka/systems/c3_state_sender.cc +++ b/systems/sender_systems/c3_state_sender.cc @@ -1,4 +1,4 @@ -#include "examples/franka/systems/c3_state_sender.h" +#include "systems/sender_systems/c3_state_sender.h" #include "systems/framework/timestamped_vector.h" namespace dairlib { @@ -14,28 +14,53 @@ C3StateSender::C3StateSender(int state_size, this->set_name("c3_state_sender"); n_x_ = state_size; - target_state_ = this->DeclareVectorInputPort("target_state", - BasicVector(state_size)) - .get_index(); - actual_state_ = this->DeclareVectorInputPort("actual_state", - TimestampedVector(state_size)) - .get_index(); + + /// Final target state is the final C3 goal state. C3 objects do not use this + /// Final target state for computing plans/errors/costs, but it is useful to + /// have for visualization and/or debugging. + final_target_state_ = this->DeclareVectorInputPort( + "final_target_state", BasicVector(state_size)).get_index(); + + /// Target state is the intermediate C3 goal state that C3 uses for computing + /// errors. It is useful to truncate the final target state (yielding this + /// intermediate Target state) to bound the errors seen by C3. + target_state_ = this->DeclareVectorInputPort( + "target_state", BasicVector(state_size)).get_index(); + + /// Actual state is the current C3 state that C3 uses as an initial condition. + actual_state_ = this->DeclareVectorInputPort( + "actual_state", TimestampedVector(state_size)).get_index(); lcmt_c3_state default_c3_state = dairlib::lcmt_c3_state(); default_c3_state.num_states = n_x_; default_c3_state.utime = 0; default_c3_state.state = std::vector(n_x_); default_c3_state.state_names = state_names; + final_target_c3_state_ = this->DeclareAbstractOutputPort( + "c3_final_target_output", default_c3_state, + &C3StateSender::OutputFinalTargetState) + .get_index(); target_c3_state_ = this->DeclareAbstractOutputPort( - "c3_actor_trajectory_output", default_c3_state, + "c3_target_output", default_c3_state, &C3StateSender::OutputTargetState) .get_index(); actual_c3_state_ = this->DeclareAbstractOutputPort( - "c3_object_trajectory_output", default_c3_state, + "c3_actual_output", default_c3_state, &C3StateSender::OutputActualState) .get_index(); } +void C3StateSender::OutputFinalTargetState( + const drake::systems::Context& context, + dairlib::lcmt_c3_state* output) const { + const auto final_target_state = this->EvalVectorInput(context, final_target_state_); + DRAKE_DEMAND(final_target_state->size() == n_x_); + output->utime = context.get_time() * 1e6; + for (int i = 0; i < n_x_; ++i) { + output->state[i] = static_cast(final_target_state->GetAtIndex(i)); + } +} + void C3StateSender::OutputTargetState( const drake::systems::Context& context, dairlib::lcmt_c3_state* output) const { diff --git a/examples/franka/systems/c3_state_sender.h b/systems/sender_systems/c3_state_sender.h similarity index 73% rename from examples/franka/systems/c3_state_sender.h rename to systems/sender_systems/c3_state_sender.h index 5d43a1ea35..ee92fd81aa 100644 --- a/examples/franka/systems/c3_state_sender.h +++ b/systems/sender_systems/c3_state_sender.h @@ -20,10 +20,19 @@ class C3StateSender : public drake::systems::LeafSystem { return this->get_input_port(target_state_); } + const drake::systems::InputPort& get_input_port_final_target_state() const { + return this->get_input_port(final_target_state_); + } + const drake::systems::InputPort& get_input_port_actual_state() const { return this->get_input_port(actual_state_); } + const drake::systems::OutputPort& get_output_port_final_target_c3_state() + const { + return this->get_output_port(final_target_c3_state_); + } + const drake::systems::OutputPort& get_output_port_target_c3_state() const { return this->get_output_port(target_c3_state_); @@ -34,14 +43,19 @@ class C3StateSender : public drake::systems::LeafSystem { } private: + void OutputFinalTargetState(const drake::systems::Context& context, + dairlib::lcmt_c3_state* output) const; + void OutputTargetState(const drake::systems::Context& context, dairlib::lcmt_c3_state* output) const; void OutputActualState(const drake::systems::Context& context, dairlib::lcmt_c3_state* output) const; + drake::systems::InputPortIndex final_target_state_; drake::systems::InputPortIndex target_state_; drake::systems::InputPortIndex actual_state_; + drake::systems::OutputPortIndex final_target_c3_state_; drake::systems::OutputPortIndex target_c3_state_; drake::systems::OutputPortIndex actual_c3_state_; From 4af86ae0bb206135217fec11193d3a31c559469c Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Thu, 22 May 2025 18:48:43 -0400 Subject: [PATCH 744/758] Quaternion error hessian (#372) * Draft quaternion angle error hessian, not yet incorporated into controller * Include quaternion hessian files in bazel build * Move quaternion error hessian into more suitable common folder --------- Co-authored-by: sharanyashastry --- common/BUILD.bazel | 13 ++++ common/quaternion_error_hessian.cc | 119 +++++++++++++++++++++++++++++ common/quaternion_error_hessian.h | 17 +++++ 3 files changed, 149 insertions(+) create mode 100644 common/quaternion_error_hessian.cc create mode 100644 common/quaternion_error_hessian.h diff --git a/common/BUILD.bazel b/common/BUILD.bazel index e129ab8c9a..5d1d81ce22 100644 --- a/common/BUILD.bazel +++ b/common/BUILD.bazel @@ -73,3 +73,16 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "quaternion_error_hessian", + srcs = [ + "quaternion_error_hessian.cc" + ], + hdrs = [ + "quaternion_error_hessian.h" + ], + deps = [ + "@drake//:drake_shared_library", + ], +) diff --git a/common/quaternion_error_hessian.cc b/common/quaternion_error_hessian.cc new file mode 100644 index 0000000000..6b3ac7d064 --- /dev/null +++ b/common/quaternion_error_hessian.cc @@ -0,0 +1,119 @@ +#include "quaternion_error_hessian.h" +#include + + +using Eigen::VectorXd; +using Eigen::MatrixXd; + + +namespace dairlib{ +namespace systems{ + +Eigen::MatrixXd hessian_of_squared_quaternion_angle_difference( + const Eigen::VectorXd& quat, const Eigen::VectorXd& quat_desired) +{ + // Check the inputs are of expected shape. + DRAKE_DEMAND(quat.size() == 4); + DRAKE_DEMAND(quat_desired.size() == 4); + + // Extract the quaternion components. + double q_w = quat(0); + double q_x = quat(1); + double q_y = quat(2); + double q_z = quat(3); + + double r_w = quat_desired(0); + double r_x = quat_desired(1); + double r_y = quat_desired(2); + double r_z = quat_desired(3); + + // Define reusable expressions. + double exp_1 = std::atan2( + std::sqrt(std::pow(q_w*r_x - q_x*r_w + q_y*r_z - q_z*r_y, 2) + + std::pow(q_w*r_y - q_x*r_z - q_y*r_w + q_z*r_x, 2) + + std::pow(q_w*r_z + q_x*r_y - q_y*r_x - q_z*r_w, 2)), + q_w*r_w + q_x*r_x + q_y*r_y + q_z*r_z); + double exp_2 = std::pow(q_w, 2)*std::pow(r_x, 2) + + std::pow(q_w, 2)*std::pow(r_y, 2) + std::pow(q_w, 2)*std::pow(r_z, 2) - + 2*q_w*q_x*r_w*r_x - 2*q_w*q_y*r_w*r_y - 2*q_w*q_z*r_w*r_z + + std::pow(q_x, 2)*std::pow(r_w, 2) + std::pow(q_x, 2)*std::pow(r_y, 2) + + std::pow(q_x, 2)*std::pow(r_z, 2) - + 2*q_x*q_y*r_x*r_y - 2*q_x*q_z*r_x*r_z; + double exp_3 = std::pow(q_y, 2)*std::pow(r_w, 2) + + std::pow(q_y, 2)*std::pow(r_x, 2) + std::pow(q_y, 2)*std::pow(r_z, 2) - + 2*q_y*q_z*r_y*r_z + std::pow(q_z, 2)*std::pow(r_w, 2) + + std::pow(q_z, 2)*std::pow(r_x, 2) + std::pow(q_z, 2)*std::pow(r_y, 2); + double exp_4 = std::pow(q_w, 2) + std::pow(q_x, 2) + + std::pow(q_y, 2) + std::pow(q_z, 2); + double exp_5 = std::pow(exp_4, 2)*std::pow(exp_2 + exp_3, 5/2); + double exp_6 = std::pow(exp_2 + exp_3, 3/2); + double exp_7 = q_w*q_x*r_x + q_w*q_y*r_y + q_w*q_z*r_z - + std::pow(q_x, 2)*r_w - std::pow(q_y, 2)*r_w - std::pow(q_z, 2)*r_w; + double exp_8 = std::pow(q_w, 2)*r_y - q_w*q_y*r_w + std::pow(q_x, 2)*r_y - + q_x*q_y*r_x - q_y*q_z*r_z + std::pow(q_z, 2)*r_y; + double exp_9 = std::pow(q_w, 2)*r_x - q_w*q_x*r_w - q_x*q_y*r_y - + q_x*q_z*r_z + std::pow(q_y, 2)*r_x + std::pow(q_z, 2)*r_x; + double exp_10 = q_w*r_w*r_z + q_x*r_x*r_z + q_y*r_y*r_z - + q_z*std::pow(r_w, 2) - q_z*std::pow(r_x, 2) - q_z*std::pow(r_y, 2); + double exp_11 = std::pow(q_w, 2)*r_z - q_w*q_z*r_w + std::pow(q_x, 2)*r_z - + q_x*q_z*r_x + std::pow(q_y, 2)*r_z - q_y*q_z*r_y; + double exp_12 = q_w*r_w*r_y + q_x*r_x*r_y - q_y*std::pow(r_w, 2) - + q_y*std::pow(r_x, 2) - q_y*std::pow(r_z, 2) + q_z*r_y*r_z; + double exp_13 = q_w*r_w*r_x - q_x*std::pow(r_w, 2) - q_x*std::pow(r_y, 2) - + q_x*std::pow(r_z, 2) + q_y*r_x*r_y + q_z*r_x*r_z; + + // Define the Hessian elements. + double H_ww = 8*(-(2*q_w*(exp_7)*(exp_2 + exp_3) - + (q_x*r_x + q_y*r_y + q_z*r_z)*(exp_4)*(exp_2 + exp_3) + + (exp_4)*(q_w*std::pow(r_x, 2) + q_w*std::pow(r_y, 2) + + q_w*std::pow(r_z, 2) - q_x*r_w*r_x - q_y*r_w*r_y - q_z*r_w*r_z)* + (exp_7))*(exp_2 + exp_3)*exp_1 + std::pow(exp_7, 2)*(exp_6))/(exp_5); + double H_xx = 8*((2*q_x*(exp_9)*(exp_2 + exp_3) + + (q_w*r_w + q_y*r_y + q_z*r_z)*(exp_4)*(exp_2 + exp_3) - + (exp_4)*(exp_9)*(exp_13))*(exp_2 + exp_3)*exp_1 + + std::pow(exp_9, 2)*(exp_6))/(exp_5); + double H_yy = 8*((2*q_y*(exp_8)*(exp_2 + exp_3) + + (q_w*r_w + q_x*r_x + q_z*r_z)*(exp_4)*(exp_2 + exp_3) - + (exp_4)*(exp_8)*(exp_12))*(exp_2 + exp_3)*exp_1 + + std::pow(exp_8, 2)*(exp_6))/(exp_5); + double H_zz = 8*((2*q_z*(exp_11)*(exp_2 + exp_3) + + (q_w*r_w + q_x*r_x + q_y*r_y)*(exp_4)*(exp_2 + exp_3) - + (exp_4)*(exp_11)*((exp_10)))*(exp_2 + exp_3)*exp_1 + + std::pow(exp_11, 2)*(exp_6))/(exp_5); + double H_wx = 8*((-2*q_x*(exp_7)*(exp_2 + exp_3) + + (q_w*r_x - 2*q_x*r_w)*(exp_4)*(exp_2 + exp_3) + + (exp_4)*(exp_7)*(exp_13))*(exp_2 + exp_3)*exp_1 - + (exp_9)*(exp_7)*(exp_6))/(exp_5); + double H_wy = 8*((-2*q_y*(exp_7)*(exp_2 + exp_3) + + (q_w*r_y - 2*q_y*r_w)*(exp_4)*(exp_2 + exp_3) + + (exp_4)*(exp_7)*(exp_12))*(exp_2 + exp_3)*exp_1 - + (exp_8)*(exp_7)*(exp_6))/(exp_5); + double H_wz = 8*((-2*q_z*(exp_7)*(exp_2 + exp_3) + + (q_w*r_z - 2*q_z*r_w)*(exp_4)*(exp_2 + exp_3) + + (exp_4)*(exp_7)*((exp_10)))*(exp_2 + exp_3)*exp_1 - + (exp_11)*(exp_7)*(exp_6))/(exp_5); + double H_xy = 8*((2*q_y*(exp_9)*(exp_2 + exp_3) + + (q_x*r_y - 2*q_y*r_x)*(exp_4)*(exp_2 + exp_3) - + (exp_4)*(exp_9)*(exp_12))*(exp_2 + exp_3)*exp_1 + + (exp_9)*(exp_8)*(exp_6))/(exp_5); + double H_xz = 8*((2*q_z*(exp_9)*(exp_2 + exp_3) + + (q_x*r_z - 2*q_z*r_x)*(exp_4)*(exp_2 + exp_3) - + (exp_4)*(exp_9)*((exp_10)))*(exp_2 + exp_3)*exp_1 + + (exp_9)*(exp_11)*(exp_6))/(exp_5); + double H_yz = 8*((2*q_z*(exp_8)*(exp_2 + exp_3) + + (q_y*r_z - 2*q_z*r_y)*(exp_4)*(exp_2 + exp_3) - + (exp_4)*(exp_8)*((exp_10)))*(exp_2 + exp_3)*exp_1 + + (exp_8)*(exp_11)*(exp_6))/(exp_5); + + // Define the Hessian. + Eigen::MatrixXd hessian = Eigen::MatrixXd::Zero(4, 4); + hessian.col(0) << H_ww, H_wx, H_wy, H_wz; + hessian.col(1) << H_wx, H_xx, H_xy, H_xz; + hessian.col(2) << H_wy, H_xy, H_yy, H_yz; + hessian.col(3) << H_wz, H_xz, H_yz, H_zz; + + return hessian; +} + +} // namespace systems +} // namespace dairlib diff --git a/common/quaternion_error_hessian.h b/common/quaternion_error_hessian.h new file mode 100644 index 0000000000..a5c899336e --- /dev/null +++ b/common/quaternion_error_hessian.h @@ -0,0 +1,17 @@ +#include +#include +#include "drake/common/drake_assert.h" + +using Eigen::VectorXd; +using Eigen::MatrixXd; + + +namespace dairlib{ +namespace systems{ + +Eigen::MatrixXd hessian_of_squared_quaternion_angle_difference( + const Eigen::VectorXd& quat, + const Eigen::VectorXd& quat_desired); + +} // namespace systems +} // namespace dairlib From d12eb6d1728c098e859056f47e613a39733b3e1d Mon Sep 17 00:00:00 2001 From: sharanyashastry <113148765+sharanyashastry@users.noreply.github.com> Date: Fri, 27 Jun 2025 13:11:05 -0400 Subject: [PATCH 745/758] First sampling C3 example: jack (#370) --------- Co-authored-by: Bibit Bianchini --- bindings/pydairlib/solvers/c3_py.cc | 4 +- common/BUILD.bazel | 22 +- common/blending_utils.h | 7 - common/file_utils.h | 14 + common/{blending_utils.cc => math_utils.cc} | 2 +- common/math_utils.h | 16 + common/parameters/BUILD.bazel | 5 + .../franka_drake_lcm_driver_channels.h | 0 .../franka_drake_lcm_driver_channels.yaml | 0 common/update_context.cc | 37 + common/update_context.h | 32 + .../contact_scheduler/contact_scheduler.h | 2 +- examples/franka/BUILD.bazel | 8 +- examples/franka/diagrams/BUILD.bazel | 2 +- .../diagrams/franka_c3_controller_diagram.cc | 2 +- .../diagrams/franka_osc_controller_diagram.cc | 2 +- examples/franka/forward_kinematics_for_lcs.cc | 2 +- examples/franka/franka_bridge_driver_in.cc | 5 +- examples/franka/franka_bridge_driver_out.cc | 5 +- examples/franka/franka_c3_controller.cc | 2 +- .../franka_c3_controller_two_objects.cc | 2 +- examples/franka/franka_osc_controller.cc | 2 +- .../franka_c3_options_floating.yaml | 5 + .../franka_c3_options_rotated_supports.yaml | 7 + .../franka_c3_options_supports.yaml | 9 +- .../franka_c3_options_supports_st.yaml | 9 +- .../franka_c3_options_translation.yaml | 7 + .../franka_c3_options_two_objects.yaml | 7 + .../c3_options/franka_c3_options_wall.yaml | 9 +- .../impact_aware_time_based_fsm.h | 2 +- examples/sampling_c3/BUILD.bazel | 295 +++ examples/sampling_c3/c3_mode_visualizer.cc | 88 + examples/sampling_c3/c3_mode_visualizer.h | 49 + .../sampling_c3/franka_bridge_driver_in.cc | 103 + .../sampling_c3/franka_bridge_driver_out.cc | 108 + .../franka_joint_osc_controller.cc | 194 ++ examples/sampling_c3/franka_osc_controller.cc | 273 ++ .../franka_sampling_c3_controller.cc | 499 ++++ examples/sampling_c3/franka_sim.cc | 139 ++ examples/sampling_c3/franka_visualizer.cc | 544 ++++ examples/sampling_c3/generate_samples.cc | 485 ++++ examples/sampling_c3/generate_samples.h | 159 ++ examples/sampling_c3/goal_generator.cc | 300 +++ examples/sampling_c3/goal_generator.h | 141 ++ examples/sampling_c3/jacktoy/BUILD.bazel | 88 + .../sampling_c3/jacktoy/franka_hardware.pmd | 103 + .../jacktoy/franka_sim_jacktoy.pmd | 71 + .../jacktoy/parameters/goal_params.yaml | 37 + .../jacktoy/parameters/progress_params.yaml | 64 + .../jacktoy/parameters/reposition_params.yaml | 32 + .../sampling_c3_controller_params.yaml | 23 + .../parameters/sampling_c3_options.yaml | 185 ++ .../jacktoy/parameters/sampling_params.yaml | 45 + .../jacktoy/parameters/sim_params.yaml | 15 + .../jacktoy/parameters/vis_params.yaml | 37 + .../sampling_c3/joint_trajectory_generator.cc | 108 + .../sampling_c3/joint_trajectory_generator.h | 44 + .../sampling_c3/parameter_headers/BUILD.bazel | 71 + .../parameter_headers/franka_sim_params.h | 31 + .../parameter_headers/goal_params.h | 71 + .../parameter_headers/lcm_channels.h | 82 + .../parameter_headers/osc_params.h | 106 + .../parameter_headers/progress_params.h | 77 + .../parameter_headers/reposition_params.h | 62 + .../sampling_c3_controller_params.h | 75 + .../parameter_headers/sampling_c3_options.h | 298 +++ .../parameter_headers/sampling_params.h | 85 + .../parameter_headers/visualizer_params.h | 73 + examples/sampling_c3/reposition.cc | 470 ++++ examples/sampling_c3/reposition.h | 82 + examples/sampling_c3/sampling_c3_utils.cc | 89 + examples/sampling_c3/sampling_c3_utils.h | 68 + .../lcm_channels_hardware.yaml | 43 + .../lcm_channels_simulation.yaml | 43 + .../shared_parameters/osc_params.yaml | 77 + .../shared_parameters/osc_qp_settings.yaml | 27 + .../sampling_c3_qp_settings.yaml | 27 + examples/sampling_c3/start_logging.py | 102 + examples/sampling_c3/test/BUILD.bazel | 25 + .../sampling_c3/test/cost_visualization.py | 161 ++ examples/sampling_c3/test/lcm_log_loader.cc | 1225 +++++++++ .../urdf/ee_visualization_model.urdf | 29 + .../sampling_c3/urdf/end_effector_full.urdf | 86 + .../urdf/end_effector_simple_model.urdf | 80 + examples/sampling_c3/urdf/ground.urdf | 39 + examples/sampling_c3/urdf/jack.sdf | 139 ++ examples/sampling_c3/urdf/jack_ground.sdf | 187 ++ examples/sampling_c3/urdf/platform.urdf | 19 + examples/sampling_c3/xbox_script.py | 95 + lcm/lcm_trajectory.cc | 7 + lcm/lcm_trajectory.h | 3 + lcmtypes/lcmt_sample_buffer.lcm | 13 + lcmtypes/lcmt_sampling_c3_debug.lcm | 46 + multibody/multipose_visualizer.cc | 19 +- multibody/multipose_visualizer.h | 11 +- solvers/c3.cc | 459 +++- solvers/c3.h | 80 +- solvers/c3_miqp.cc | 6 +- solvers/c3_options.h | 39 +- solvers/c3_qp.cc | 9 +- solvers/lcs.cc | 13 +- solvers/lcs.h | 5 +- solvers/lcs_factory.cc | 104 +- solvers/lcs_factory.h | 45 + systems/controllers/BUILD.bazel | 32 + .../controllers/osc/end_effector_position.cc | 12 +- .../controllers/osc/end_effector_position.h | 4 +- .../osc/operational_space_control.cc | 11 +- .../sampling_based_c3_controller.cc | 2188 +++++++++++++++++ .../sampling_based_c3_controller.h | 462 ++++ systems/framework/lcm_driven_loop.h | 96 +- systems/sender_systems/BUILD.bazel | 25 - systems/senders/BUILD.bazel | 62 + .../c3_state_sender.cc | 2 +- .../c3_state_sender.h | 0 systems/senders/sample_buffer_sender.cc | 77 + systems/senders/sample_buffer_sender.h | 45 + .../senders/sample_buffer_to_point_cloud.cc | 131 + .../senders/sample_buffer_to_point_cloud.h | 118 + systems/system_utils.cc | 7 +- .../lcm_visualization_systems.cc | 109 +- .../visualization/lcm_visualization_systems.h | 20 +- 122 files changed, 12678 insertions(+), 183 deletions(-) delete mode 100644 common/blending_utils.h rename common/{blending_utils.cc => math_utils.cc} (89%) create mode 100644 common/math_utils.h create mode 100644 common/parameters/BUILD.bazel rename {examples/franka => common}/parameters/franka_drake_lcm_driver_channels.h (100%) rename {examples/franka => common}/parameters/franka_drake_lcm_driver_channels.yaml (100%) create mode 100644 common/update_context.cc create mode 100644 common/update_context.h create mode 100644 examples/sampling_c3/BUILD.bazel create mode 100644 examples/sampling_c3/c3_mode_visualizer.cc create mode 100644 examples/sampling_c3/c3_mode_visualizer.h create mode 100644 examples/sampling_c3/franka_bridge_driver_in.cc create mode 100644 examples/sampling_c3/franka_bridge_driver_out.cc create mode 100644 examples/sampling_c3/franka_joint_osc_controller.cc create mode 100644 examples/sampling_c3/franka_osc_controller.cc create mode 100644 examples/sampling_c3/franka_sampling_c3_controller.cc create mode 100644 examples/sampling_c3/franka_sim.cc create mode 100644 examples/sampling_c3/franka_visualizer.cc create mode 100644 examples/sampling_c3/generate_samples.cc create mode 100644 examples/sampling_c3/generate_samples.h create mode 100644 examples/sampling_c3/goal_generator.cc create mode 100644 examples/sampling_c3/goal_generator.h create mode 100644 examples/sampling_c3/jacktoy/BUILD.bazel create mode 100644 examples/sampling_c3/jacktoy/franka_hardware.pmd create mode 100644 examples/sampling_c3/jacktoy/franka_sim_jacktoy.pmd create mode 100644 examples/sampling_c3/jacktoy/parameters/goal_params.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/progress_params.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/reposition_params.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/sampling_params.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/sim_params.yaml create mode 100644 examples/sampling_c3/jacktoy/parameters/vis_params.yaml create mode 100644 examples/sampling_c3/joint_trajectory_generator.cc create mode 100644 examples/sampling_c3/joint_trajectory_generator.h create mode 100644 examples/sampling_c3/parameter_headers/BUILD.bazel create mode 100644 examples/sampling_c3/parameter_headers/franka_sim_params.h create mode 100644 examples/sampling_c3/parameter_headers/goal_params.h create mode 100644 examples/sampling_c3/parameter_headers/lcm_channels.h create mode 100644 examples/sampling_c3/parameter_headers/osc_params.h create mode 100644 examples/sampling_c3/parameter_headers/progress_params.h create mode 100644 examples/sampling_c3/parameter_headers/reposition_params.h create mode 100644 examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h create mode 100644 examples/sampling_c3/parameter_headers/sampling_c3_options.h create mode 100644 examples/sampling_c3/parameter_headers/sampling_params.h create mode 100644 examples/sampling_c3/parameter_headers/visualizer_params.h create mode 100644 examples/sampling_c3/reposition.cc create mode 100644 examples/sampling_c3/reposition.h create mode 100644 examples/sampling_c3/sampling_c3_utils.cc create mode 100644 examples/sampling_c3/sampling_c3_utils.h create mode 100644 examples/sampling_c3/shared_parameters/lcm_channels_hardware.yaml create mode 100644 examples/sampling_c3/shared_parameters/lcm_channels_simulation.yaml create mode 100644 examples/sampling_c3/shared_parameters/osc_params.yaml create mode 100644 examples/sampling_c3/shared_parameters/osc_qp_settings.yaml create mode 100644 examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml create mode 100644 examples/sampling_c3/start_logging.py create mode 100644 examples/sampling_c3/test/BUILD.bazel create mode 100644 examples/sampling_c3/test/cost_visualization.py create mode 100644 examples/sampling_c3/test/lcm_log_loader.cc create mode 100644 examples/sampling_c3/urdf/ee_visualization_model.urdf create mode 100644 examples/sampling_c3/urdf/end_effector_full.urdf create mode 100644 examples/sampling_c3/urdf/end_effector_simple_model.urdf create mode 100644 examples/sampling_c3/urdf/ground.urdf create mode 100644 examples/sampling_c3/urdf/jack.sdf create mode 100644 examples/sampling_c3/urdf/jack_ground.sdf create mode 100644 examples/sampling_c3/urdf/platform.urdf create mode 100644 examples/sampling_c3/xbox_script.py create mode 100644 lcmtypes/lcmt_sample_buffer.lcm create mode 100644 lcmtypes/lcmt_sampling_c3_debug.lcm create mode 100644 systems/controllers/sampling_based_c3_controller.cc create mode 100644 systems/controllers/sampling_based_c3_controller.h delete mode 100644 systems/sender_systems/BUILD.bazel create mode 100644 systems/senders/BUILD.bazel rename systems/{sender_systems => senders}/c3_state_sender.cc (98%) rename systems/{sender_systems => senders}/c3_state_sender.h (100%) create mode 100644 systems/senders/sample_buffer_sender.cc create mode 100644 systems/senders/sample_buffer_sender.h create mode 100644 systems/senders/sample_buffer_to_point_cloud.cc create mode 100644 systems/senders/sample_buffer_to_point_cloud.h diff --git a/bindings/pydairlib/solvers/c3_py.cc b/bindings/pydairlib/solvers/c3_py.cc index daa6c3aceb..427a660862 100644 --- a/bindings/pydairlib/solvers/c3_py.cc +++ b/bindings/pydairlib/solvers/c3_py.cc @@ -73,11 +73,11 @@ PYBIND11_MODULE(c3, m) { .def(py::init&, const C3Options&>(), arg("LCS"), arg("costs"), arg("x_des"), arg("c3_options")) - .def("Solve", &C3MIQP::Solve, arg("x0")) + .def("Solve", &C3MIQP::Solve, arg("x0"), arg("verbose") = false) .def("UpdateTarget", &C3MIQP::UpdateTarget, arg("x0")) .def("UpdateLCS", &C3MIQP::UpdateLCS, arg("lcs")) .def("ADMMStep", &C3MIQP::ADMMStep, arg("x0"), arg("delta"), arg("w"), - arg("G"), arg("admm_iteration")) + arg("G"), arg("admm_iteration"), arg("verbose") = false) .def("SolveQP", &C3MIQP::SolveQP, arg("x0"), arg("G"), arg("WD"), arg("admm_iteration"), arg("is_final_solve")) .def("SolveProjection", &C3MIQP::SolveProjection, arg("U"), arg("WZ"), arg("admm_iteration")) diff --git a/common/BUILD.bazel b/common/BUILD.bazel index 5d1d81ce22..4ca908818a 100644 --- a/common/BUILD.bazel +++ b/common/BUILD.bazel @@ -3,7 +3,7 @@ package(default_visibility = ["//visibility:public"]) cc_library( name = "common", deps = [ - ":blending_utils", + ":math_utils", ":discrete_time_filter", ":eigen_utils", ":file_utils", @@ -49,12 +49,12 @@ cc_library( ) cc_library( - name = "blending_utils", + name = "math_utils", srcs = [ - "blending_utils.cc", + "math_utils.cc", ], hdrs = [ - "blending_utils.h", + "math_utils.h", ], deps = [ "@drake//:drake_shared_library", @@ -86,3 +86,17 @@ cc_library( "@drake//:drake_shared_library", ], ) + +cc_library( + name = "update_context", + srcs = [ + "update_context.cc" + ], + hdrs = [ + "update_context.h" + ], + deps = [ + "@drake//:drake_shared_library", + "//multibody:utils", + ], +) diff --git a/common/blending_utils.h b/common/blending_utils.h deleted file mode 100644 index 26b1c415c7..0000000000 --- a/common/blending_utils.h +++ /dev/null @@ -1,7 +0,0 @@ -#pragma once - -enum BLEND_FUNC { kSigmoid, kExponential }; - -double blend_sigmoid(double t, double tau, double window); - -double blend_exp(double t, double tau, double window); diff --git a/common/file_utils.h b/common/file_utils.h index b7583d4b75..8383a2a15d 100644 --- a/common/file_utils.h +++ b/common/file_utils.h @@ -5,6 +5,8 @@ #include #include +#include "drake/common/yaml/yaml_read_archive.h" + namespace dairlib { /// Read a CSV formatted file as an Eigen Matrix @@ -13,4 +15,16 @@ Eigen::MatrixXd readCSV(const std::string & path); /// Write an Eigen Matrix into a CSV formatted file void writeCSV(const std::string& path, const Eigen::MatrixXd& M); +/// Deserialize a YAML integer into a custom enum type. +template +void DeserializeEnum(const char* value_str, Archive* a, T* enum_out) { + int raw_value = static_cast(*enum_out); + a->Visit(drake::MakeNameValue(value_str, &raw_value)); + *enum_out = static_cast(raw_value); +} + } // namespace dairlib + +/// Deserializes a YAML integer by the name of the provided e_out variable into +/// the custom enum type of e_out. +#define ENUM_DESERIALIZE(a, e_out) dairlib::DeserializeEnum(#e_out, a, &e_out) diff --git a/common/blending_utils.cc b/common/math_utils.cc similarity index 89% rename from common/blending_utils.cc rename to common/math_utils.cc index 645cac6fe0..7a441c6165 100644 --- a/common/blending_utils.cc +++ b/common/math_utils.cc @@ -1,4 +1,4 @@ -#include "blending_utils.h" +#include "math_utils.h" #include diff --git a/common/math_utils.h b/common/math_utils.h new file mode 100644 index 0000000000..53a7128e03 --- /dev/null +++ b/common/math_utils.h @@ -0,0 +1,16 @@ +#pragma once +#include + +/// Blending utilities +enum BLEND_FUNC { kSigmoid, kExponential }; + +double blend_sigmoid(double t, double tau, double window); + +double blend_exp(double t, double tau, double window); + +/// Random sampling utility +inline double RandomUniform(double min, double max) { + static thread_local std::mt19937 rng{std::random_device{}()}; + std::uniform_real_distribution dist(min, max); + return dist(rng); +} diff --git a/common/parameters/BUILD.bazel b/common/parameters/BUILD.bazel new file mode 100644 index 0000000000..5205598698 --- /dev/null +++ b/common/parameters/BUILD.bazel @@ -0,0 +1,5 @@ +cc_library( + name = "franka_drake_lcm_driver_channels", + hdrs = ["franka_drake_lcm_driver_channels.h"], + visibility = ["//visibility:public"], +) diff --git a/examples/franka/parameters/franka_drake_lcm_driver_channels.h b/common/parameters/franka_drake_lcm_driver_channels.h similarity index 100% rename from examples/franka/parameters/franka_drake_lcm_driver_channels.h rename to common/parameters/franka_drake_lcm_driver_channels.h diff --git a/examples/franka/parameters/franka_drake_lcm_driver_channels.yaml b/common/parameters/franka_drake_lcm_driver_channels.yaml similarity index 100% rename from examples/franka/parameters/franka_drake_lcm_driver_channels.yaml rename to common/parameters/franka_drake_lcm_driver_channels.yaml diff --git a/common/update_context.cc b/common/update_context.cc new file mode 100644 index 0000000000..c8974bf247 --- /dev/null +++ b/common/update_context.cc @@ -0,0 +1,37 @@ +#include "update_context.h" + +#include + +using Eigen::VectorXd; + +namespace dairlib { + +void UpdateContext(const int& n_q, const int& n_v, const int& n_u, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const Eigen::VectorXd& x) { + // Update autodiff. + VectorXd xu_test(n_q + n_v + n_u); + + // TODO u has always been set to a vector of 1000s here but unsure why or if + // it matters. + VectorXd test_u = 1000 * VectorXd::Ones(n_u); + + // Update context with respect to positions and velocities associated with + // the candidate state. + VectorXd test_q = x.head(n_q); + VectorXd test_v = x.tail(n_v); + xu_test << test_q, test_v, test_u; + auto xu_ad_test = drake::math::InitializeAutoDiff(xu_test); + plant_ad.SetPositionsAndVelocities(context_ad, xu_ad_test.head(n_q + n_v)); + multibody::SetInputsIfNew(plant_ad, xu_ad_test.tail(n_u), + context_ad); + + plant.SetPositions(context, test_q); + plant.SetVelocities(context, test_v); + multibody::SetInputsIfNew(plant, test_u, context); +} + +} // namespace dairlib diff --git a/common/update_context.h b/common/update_context.h new file mode 100644 index 0000000000..2fae7e3a82 --- /dev/null +++ b/common/update_context.h @@ -0,0 +1,32 @@ +#include + +#include "multibody/multibody_utils.h" + +using drake::AutoDiffVecXd; +using drake::AutoDiffXd; +using Eigen::VectorXd; + +namespace dairlib { + +/// Updates the context of a MultibodyPlant with the given state vector. +/// +/// This function updates both the double and AutoDiff contexts of a MultibodyPlant +/// using the provided state vector. It is useful for setting the state of the +/// plant in simulation or optimization tasks. +/// +/// @param n_q Number of generalized positions (q). +/// @param n_v Number of generalized velocities (v). +/// @param n_u Number of control inputs (u). +/// @param plant The MultibodyPlant to update. +/// @param context The context for the MultibodyPlant. +/// @param plant_ad The MultibodyPlant with AutoDiff support. +/// @param context_ad The context for the MultibodyPlant with AutoDiff support. +/// @param x The state vector to set in the contexts. +void UpdateContext(const int& n_q, const int& n_v, const int& n_u, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const Eigen::VectorXd& x); + +} // namespace dairlib diff --git a/examples/Cassie/contact_scheduler/contact_scheduler.h b/examples/Cassie/contact_scheduler/contact_scheduler.h index d02637b05a..c0a5781dd3 100644 --- a/examples/Cassie/contact_scheduler/contact_scheduler.h +++ b/examples/Cassie/contact_scheduler/contact_scheduler.h @@ -5,7 +5,7 @@ #include #include -#include "common/blending_utils.h" +#include "common/math_utils.h" #include "dairlib/lcmt_contact_timing.hpp" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 62216931cb..6cd679cb5c 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -84,7 +84,7 @@ cc_binary( "//common", "//examples/franka/systems:franka_systems", "//systems:franka_kinematics", - "//systems/sender_systems:c3_state_sender", + "//systems/senders:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -112,7 +112,7 @@ cc_binary( "//common", "//examples/franka/systems:franka_systems", "//systems:franka_kinematics", - "//systems/sender_systems:c3_state_sender", + "//systems/senders:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -140,7 +140,7 @@ cc_binary( "//common", "//examples/franka/systems:franka_systems", "//systems:franka_kinematics", - "//systems/sender_systems:c3_state_sender", + "//systems/senders:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", @@ -271,7 +271,6 @@ cc_library( hdrs = [ "parameters/franka_c3_controller_params.h", "parameters/franka_c3_scene_params.h", - "parameters/franka_drake_lcm_driver_channels.h", "parameters/franka_lcm_channels.h", "parameters/franka_osc_controller_params.h", "parameters/franka_sim_params.h", @@ -282,5 +281,6 @@ cc_library( ]), deps = [ "@drake//:drake_shared_library", + "//common/parameters:franka_drake_lcm_driver_channels", ], ) diff --git a/examples/franka/diagrams/BUILD.bazel b/examples/franka/diagrams/BUILD.bazel index 35085d5fcb..bedf79b67d 100644 --- a/examples/franka/diagrams/BUILD.bazel +++ b/examples/franka/diagrams/BUILD.bazel @@ -8,7 +8,7 @@ cc_library( "//common", "//examples/franka:parameters", "//examples/franka/systems:franka_systems", - "//systems/sender_systems:c3_state_sender", + "//systems/senders:c3_state_sender", "//lcm:lcm_trajectory_saver", "//systems:robot_lcm_systems", "//systems:system_utils", diff --git a/examples/franka/diagrams/franka_c3_controller_diagram.cc b/examples/franka/diagrams/franka_c3_controller_diagram.cc index 23062da2a7..686e820237 100644 --- a/examples/franka/diagrams/franka_c3_controller_diagram.cc +++ b/examples/franka/diagrams/franka_c3_controller_diagram.cc @@ -21,7 +21,7 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "systems/sender_systems/c3_state_sender.h" +#include "systems/senders/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" #include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index f62460d438..21b8967d33 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -116,7 +116,7 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( auto osc_command_sender = builder.AddSystem(*plant_); auto end_effector_trajectory = - builder.AddSystem(*plant_, + builder.AddSystem(*plant_, plant_context_.get(), controller_params.neutral_position, false, controller_params.end_effector_name); auto passthrough = builder.AddSystem>(18); diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index 711e22ab06..a2d2eb0483 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -14,7 +14,7 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "systems/sender_systems/c3_state_sender.h" +#include "systems/senders/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" #include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" diff --git a/examples/franka/franka_bridge_driver_in.cc b/examples/franka/franka_bridge_driver_in.cc index 473d566e9e..44552f3f10 100644 --- a/examples/franka/franka_bridge_driver_in.cc +++ b/examples/franka/franka_bridge_driver_in.cc @@ -12,7 +12,7 @@ #include #include -#include "examples/franka/parameters/franka_drake_lcm_driver_channels.h" +#include "common/parameters/franka_drake_lcm_driver_channels.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "systems/franka_state_translator.h" @@ -37,7 +37,8 @@ using dairlib::systems::TimestampedVector; DEFINE_string(lcm_channels, "examples/franka/parameters/lcm_channels_hardware.yaml", "Filepath containing lcm channels"); -DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_drake_lcm_driver_channels.yaml", +DEFINE_string(franka_driver_channels, + "common/parameters/franka_drake_lcm_driver_channels.yaml", "Filepath containing drake franka driver channels"); namespace dairlib { diff --git a/examples/franka/franka_bridge_driver_out.cc b/examples/franka/franka_bridge_driver_out.cc index f9e7286ef8..b88b0be2ab 100644 --- a/examples/franka/franka_bridge_driver_out.cc +++ b/examples/franka/franka_bridge_driver_out.cc @@ -12,7 +12,7 @@ #include #include -#include "examples/franka/parameters/franka_drake_lcm_driver_channels.h" +#include "common/parameters/franka_drake_lcm_driver_channels.h" #include "examples/franka/parameters/franka_lcm_channels.h" #include "examples/franka/parameters/franka_sim_params.h" #include "systems/franka_state_translator.h" @@ -37,7 +37,8 @@ using dairlib::systems::TimestampedVector; DEFINE_string(lcm_channels, "examples/franka/parameters/lcm_channels_hardware.yaml", "Filepath containing lcm channels"); -DEFINE_string(franka_driver_channels, "examples/franka/parameters/franka_drake_lcm_driver_channels.yaml", +DEFINE_string(franka_driver_channels, + "common/parameters/franka_drake_lcm_driver_channels.yaml", "Filepath containing drake franka driver channels"); namespace dairlib { diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index da028effa1..f4eba05737 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -12,7 +12,7 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "systems/sender_systems/c3_state_sender.h" +#include "systems/senders/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" #include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" diff --git a/examples/franka/franka_c3_controller_two_objects.cc b/examples/franka/franka_c3_controller_two_objects.cc index ff12d61aac..5c8e3d9e9c 100644 --- a/examples/franka/franka_c3_controller_two_objects.cc +++ b/examples/franka/franka_c3_controller_two_objects.cc @@ -14,7 +14,7 @@ #include "examples/franka/parameters/franka_c3_controller_params.h" #include "examples/franka/parameters/franka_c3_scene_params.h" #include "examples/franka/parameters/franka_lcm_channels.h" -#include "systems/sender_systems/c3_state_sender.h" +#include "systems/senders/c3_state_sender.h" #include "examples/franka/systems/c3_trajectory_generator.h" #include "systems/franka_kinematics.h" #include "examples/franka/systems/plate_balancing_target.h" diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 61bef2cda2..1cba2b9e70 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -138,7 +138,7 @@ int DoMain(int argc, char* argv[]) { auto osc_command_sender = builder.AddSystem(plant); auto end_effector_trajectory = - builder.AddSystem(plant, + builder.AddSystem(plant, plant_context.get(), controller_params.neutral_position, false, controller_params.end_effector_name); end_effector_trajectory->SetRemoteControlParameters( diff --git a/examples/franka/parameters/c3_options/franka_c3_options_floating.yaml b/examples/franka/parameters/c3_options/franka_c3_options_floating.yaml index 118a6b0ce9..cf813acb07 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_floating.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_floating.yaml @@ -47,3 +47,8 @@ u_vector: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, # Penalty on efforts, assuming diagonal r_vector: [1, 1, 1, 0.1, 0.1, 0.1] +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml index f4a537a0e3..8150fd15dd 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_rotated_supports.yaml @@ -62,3 +62,10 @@ u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_u: [30, 30, 30] + + +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml index 3775d510f3..33c0fae0b2 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports.yaml @@ -63,4 +63,11 @@ u_gamma: [1, 1, 1, 1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] -u_u: [30, 30, 30] \ No newline at end of file +u_u: [30, 30, 30] + + +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml index 46deca02d4..c504cd699e 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_supports_st.yaml @@ -64,4 +64,11 @@ u_gamma: [10, 10, 10, 10, 10, 10, 10] u_lambda_n: [300, 300, 300, 300, 300, 300, 300] u_lambda_t: [300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300, 300] u_lambda: [85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85, 85] -u_u: [30, 30, 30] \ No newline at end of file +u_u: [30, 30, 30] + + +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml index 9dc916382a..45c679466d 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_translation.yaml @@ -63,3 +63,10 @@ u_lambda_n: [100, 100, 100] u_lambda_t: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] u_lambda: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] u_u: [30, 30, 30] + + +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml b/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml index d1f7ca1c59..a8271bfd81 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_two_objects.yaml @@ -62,3 +62,10 @@ u_lambda_n: [1, 1, 1] u_lambda_t: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] u_lambda: [50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50, 50] u_u: [10, 10, 10] + + +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml index 3e45937f6c..fb5f43beb2 100644 --- a/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml +++ b/examples/franka/parameters/c3_options/franka_c3_options_wall.yaml @@ -61,4 +61,11 @@ u_gamma: [1, 1, 1, 1] u_lambda_n: [1, 1, 1, 1] u_lambda_t: [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1] u_lambda: [100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100, 100] -u_u: [30, 30, 30] \ No newline at end of file +u_u: [30, 30, 30] + + +# Parameters used in the QP projection method. As alpha -> 0, any error in +# complimentarity constraints also approaches 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1000 +penalize_changes_in_u_across_solves: true diff --git a/examples/impact_invariant_control/impact_aware_time_based_fsm.h b/examples/impact_invariant_control/impact_aware_time_based_fsm.h index 579bfd6a97..301626d015 100644 --- a/examples/impact_invariant_control/impact_aware_time_based_fsm.h +++ b/examples/impact_invariant_control/impact_aware_time_based_fsm.h @@ -2,7 +2,7 @@ #include -#include "common/blending_utils.h" +#include "common/math_utils.h" #include "systems/controllers/time_based_fsm.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" diff --git a/examples/sampling_c3/BUILD.bazel b/examples/sampling_c3/BUILD.bazel new file mode 100644 index 0000000000..aa2f0f5a36 --- /dev/null +++ b/examples/sampling_c3/BUILD.bazel @@ -0,0 +1,295 @@ +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "urdfs", + data = glob([ + "urdf/**", + ]), +) + +filegroup( + name = "all_example_params_yamls", + srcs = glob(["*/parameters/*.yaml"]), + visibility = ["//visibility:public"], +) + +filegroup( + name = "shared_params_yamls", + srcs = glob(["shared_parameters/*.yaml"]), + visibility = ["//visibility:public"], +) + +cc_binary( + name = "franka_sim", + srcs = ["franka_sim.cc"], + data = [ + ":urdfs", + "//examples/sampling_c3:all_example_params_yamls", + "@drake_models//:franka_description", + ], + deps = [ + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//examples/sampling_c3/parameter_headers:franka_sim_params", + "//common", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/framework:lcm_driven_loop", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_osc_controller", + srcs = ["franka_osc_controller.cc"], + data = [ + ":urdfs", + "//examples/sampling_c3:all_example_params_yamls", + "@drake_models//:franka_description", + ], + deps = [ + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//examples/sampling_c3/parameter_headers:osc_params", + "//common", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers:gravity_compensator", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/trajectory_optimization:lcm_trajectory_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_joint_osc_controller", + srcs = ["franka_joint_osc_controller.cc"], + data = [ + ":urdfs", + "//examples/sampling_c3:all_example_params_yamls", + "@drake_models//:franka_description", + ], + deps = [ + "//examples/sampling_c3:joint_trajectory_generator", + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//examples/sampling_c3/parameter_headers:osc_params", + "//common", + "//lcm:lcm_trajectory_saver", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers:gravity_compensator", + "//systems/controllers/osc:operational_space_control", + "//systems/framework:lcm_driven_loop", + "//systems/trajectory_optimization:lcm_trajectory_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_library( + name = "joint_trajectory_generator", + srcs = ["joint_trajectory_generator.cc"], + hdrs = ["joint_trajectory_generator.h"], + deps = [ + "//systems/framework:vector", + ], +) + +cc_binary( + name = "franka_visualizer", + srcs = ["franka_visualizer.cc"], + data = [ + ":urdfs", + "//examples/sampling_c3:all_example_params_yamls", + "@drake_models//:franka_description", + ], + deps = [ + ":c3_mode_visualizer", + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_options", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//examples/sampling_c3/parameter_headers:visualizer_params", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:sampling_params", + "//common", + "//multibody:utils", + "//multibody:visualization_utils", + "//systems/senders:senders", + "//systems:franka_kinematics", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/primitives", + "//systems/trajectory_optimization:lcm_trajectory_systems", + "//systems/visualization:lcm_visualization_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_bridge_driver_out", + srcs = ["franka_bridge_driver_out.cc"], + data = [ + ":urdfs", + "@drake_models//:franka_description", + "//examples/sampling_c3:all_example_params_yamls", + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//common/parameters:franka_drake_lcm_driver_channels", + "//common", + "//systems:franka_state_translator", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_bridge_driver_in", + srcs = ["franka_bridge_driver_in.cc"], + data = [ + ":urdfs", + "@drake_models//:franka_description", + "//examples/sampling_c3:all_example_params_yamls", + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//common/parameters:franka_drake_lcm_driver_channels", + "//common", + "//systems:franka_state_translator", + "//multibody:utils", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/framework:lcm_driven_loop", + "//systems/primitives", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_binary( + name = "franka_sampling_c3_controller", + srcs = ["franka_sampling_c3_controller.cc"], + data = [ + ":urdfs", + "@drake_models//:franka_description", + "//examples/sampling_c3:all_example_params_yamls", + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3:goal_generator", + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//common", + "//lcm:lcm_trajectory_saver", + "//systems:franka_kinematics", + "//systems/senders:sample_buffer_sender", + "//systems/senders:senders", + "//systems:robot_lcm_systems", + "//systems:system_utils", + "//systems/controllers:sampling_c3_controller", + "//systems/framework:lcm_driven_loop", + "//systems/trajectory_optimization:c3_output_systems", + "@drake//:drake_shared_library", + "@gflags", + ], +) + +cc_library( + name = "c3_mode_visualizer", + srcs = ["c3_mode_visualizer.cc"], + hdrs = ["c3_mode_visualizer.h"], + deps = [ + "//lcmtypes:lcmt_robot", + "//lcm:lcm_trajectory_saver", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "@lcm", + ], +) + +cc_library( + name = "goal_generator", + srcs = ["goal_generator.cc"], + hdrs = ["goal_generator.h"], + deps = [ + "//examples/sampling_c3/parameter_headers:goal_params", + "//systems/framework:vector", + "//lcmtypes:lcmt_robot", + "//lcm:lcm_trajectory_saver", + "//common:math_utils", + "@drake//:drake_shared_library", + "@lcm", + ], +) + +cc_library( + name = "generate_samples", + srcs = ["generate_samples.cc"], + hdrs = ["generate_samples.h"], + deps = [ + "@drake//:drake_shared_library", + "//examples/sampling_c3/parameter_headers:sampling_c3_options", + "//examples/sampling_c3/parameter_headers:sampling_params", + "//multibody:utils", + "//multibody:geom_geom_collider", + "//common:math_utils", + "//common:update_context", + "//solvers:c3", + ], +) + +cc_library( + name = "reposition", + srcs = ["reposition.cc"], + hdrs = ["reposition.h"], + deps = [ + "//solvers:c3", + "//examples/sampling_c3/parameter_headers:sampling_c3_options", + "//examples/sampling_c3/parameter_headers:reposition_params", + "//common:math_utils", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "sampling_c3_utils", + srcs = ["sampling_c3_utils.cc"], + hdrs = ["sampling_c3_utils.h"], + deps = [ + "//common", + "//common:math_utils", + "@drake//:drake_shared_library", + ], +) + +py_binary( + name = "xbox_script", + srcs = ["xbox_script.py"], + data = [ + "@lcm//:lcm-python", + ], + main = "xbox_script.py", + deps = [ + "//lcmtypes:lcmtypes_robot_py", + ], +) diff --git a/examples/sampling_c3/c3_mode_visualizer.cc b/examples/sampling_c3/c3_mode_visualizer.cc new file mode 100644 index 0000000000..d282e6a12d --- /dev/null +++ b/examples/sampling_c3/c3_mode_visualizer.cc @@ -0,0 +1,88 @@ +#include "examples/sampling_c3/c3_mode_visualizer.h" + +#include "lcm/lcm_trajectory.h" +#include "systems/framework/timestamped_vector.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +using drake::systems::Context; +using systems::TimestampedVector; + +namespace systems { + +C3ModeVisualizer::C3ModeVisualizer() { + this->set_name("C3ModeVisualizer"); + + is_c3_mode_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_timestamped_saved_traj: is_c3_mode_input", + drake::Value{}) + .get_index(); + + // 19 is the hardcoded size of the current lcs state vector. Alternatively, + // pass in the plant and read the size from there. + curr_lcs_state_ = this->DeclareVectorInputPort( + "curr_lcs_state", TimestampedVector(19)).get_index(); + + // Output c3_mode indicator for visualization. + c3_mode_visualization_traj_port_ = + this->DeclareAbstractOutputPort( + "mode_visualization_traj", dairlib::lcmt_timestamped_saved_traj(), + &C3ModeVisualizer::OutputC3ModeVisualization) + .get_index(); +} + +void C3ModeVisualizer::OutputC3ModeVisualization( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* c3_mode_visualization_traj) const { + // NOTE: LcmTrajectory needs at least two knot points, so create a dummy + // second knot also at the desired C3 mode visualization location. + Eigen::MatrixXd knots = Eigen::MatrixXd::Zero(3, 2); + + // Only update trajectory if the C3 mode input port has received data. + if (this->EvalInputValue( + context, is_c3_mode_input_port_)->utime > 1e-3) { + // Evaluate input port to get the sample locations as an + // lcmt_timestamped_saved_traj. + const auto& is_c3_mode_lcmt = + this->EvalInputValue( + context, is_c3_mode_input_port_); + + const TimestampedVector* curr_lcs_state = + (TimestampedVector*)this->EvalVectorInput( + context, curr_lcs_state_); + + auto is_c3_mode_lcm_obj = LcmTrajectory(is_c3_mode_lcmt->saved_traj); + auto is_c3_mode_traj = is_c3_mode_lcm_obj.GetTrajectory("is_c3_mode"); + auto is_c3_mode = is_c3_mode_traj.datapoints; + + // If we are in C3 mode, visualize the current EE location. + if (is_c3_mode(0)) { + knots.col(0) = curr_lcs_state->get_data().head(3); + knots.col(1) = curr_lcs_state->get_data().head(3); + } + } + + Eigen::VectorXd timestamp = Eigen::VectorXd::Zero(2); + timestamp(0) = context.get_time(); + timestamp(1) = context.get_time() + 1e-3; + + LcmTrajectory::Trajectory c3_mode; + c3_mode.traj_name = "c3_mode_visualization"; + c3_mode.datatypes = std::vector(3, "double"); + c3_mode.datapoints = knots; + c3_mode.time_vector = timestamp.cast(); + + LcmTrajectory c3_mode_traj( + {c3_mode}, {"c3_mode_visualization"}, "c3_mode_visualization", + "c3_mode_visualization", false); + + // Output as lcmt_timestamped_saved_traj + c3_mode_visualization_traj->saved_traj = c3_mode_traj.GenerateLcmObject(); + c3_mode_visualization_traj->utime = context.get_time() * 1e6; +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/c3_mode_visualizer.h b/examples/sampling_c3/c3_mode_visualizer.h new file mode 100644 index 0000000000..0e4a53cf14 --- /dev/null +++ b/examples/sampling_c3/c3_mode_visualizer.h @@ -0,0 +1,49 @@ +#include + +#include +#include +#include "dairlib/lcmt_saved_traj.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +namespace systems { + +/// A Drake system in the visualizer diagram for outputting a trajectory +/// (lcmt_timestamped_saved_traj) based on the current C3 mode. When in C3 +/// mode, the trajectory follows the EE location (to highlight the EE in pink). +/// When not in C3 mode, the trajectory is at the origin (to hide the pink EE in +/// the visualizer). +class C3ModeVisualizer : public drake::systems::LeafSystem { + public: + C3ModeVisualizer(); + + // Input ports + const drake::systems::InputPort& get_input_port_is_c3_mode() const { + return this->get_input_port(is_c3_mode_input_port_); + } + + const drake::systems::InputPort& get_input_port_curr_lcs_state() + const { + return this->get_input_port(curr_lcs_state_); + } + + // Output port + const drake::systems::OutputPort& + get_output_port_c3_mode_visualization_traj() const { + return this->get_output_port(c3_mode_visualization_traj_port_); + } + + private: + void OutputC3ModeVisualization( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* c3_mode_visualization_traj) const; + + drake::systems::InputPortIndex is_c3_mode_input_port_; + drake::systems::InputPortIndex curr_lcs_state_; + drake::systems::OutputPortIndex c3_mode_visualization_traj_port_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/franka_bridge_driver_in.cc b/examples/sampling_c3/franka_bridge_driver_in.cc new file mode 100644 index 0000000000..7a7659d3ad --- /dev/null +++ b/examples/sampling_c3/franka_bridge_driver_in.cc @@ -0,0 +1,103 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/parameters/franka_drake_lcm_driver_channels.h" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "systems/franka_state_translator.h" +#include "multibody/multibody_utils.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/common/find_resource.h" + +using drake::math::RigidTransform; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using dairlib::systems::RobotInputReceiver; +using dairlib::systems::RobotOutputSender; +using dairlib::systems::SubvectorPassThrough; +using dairlib::systems::TimestampedVector; + + +DEFINE_string(lcm_url, "udpm://239.255.76.67:7667?ttl=0", + "LCM URL with IP, port, and TTL settings"); +DEFINE_string(demo_name, "jacktoy", + "Demo within sampling_c3; used to find controller params file"); + +namespace dairlib { + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + std::string lcm_channels_file = controller_params.lcm_channels_hardware_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + FrankaDrakeLcmDriverChannels franka_driver_channel_params = + drake::yaml::LoadYamlFile( + controller_params.franka_driver_channels_file); + + DiagramBuilder builder; + + MultibodyPlant plant(0.0); + AddFrankaToPlant(&plant, nullptr, false, false); + plant.Finalize(); + + auto pos_map = multibody::MakeNameToPositionsMap(plant); + auto vel_map = multibody::MakeNameToVelocitiesMap(plant); + auto act_map = multibody::MakeNameToActuatorsMap(plant); + + auto pos_names = multibody::ExtractOrderedNamesFromMap(pos_map); + auto vel_names = multibody::ExtractOrderedNamesFromMap(vel_map); + auto act_names = multibody::ExtractOrderedNamesFromMap(act_map); + + /* -------------------------------------------------------------------------------------------*/ + drake::lcm::DrakeLcm lcm(FLAGS_lcm_url); + + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + franka_driver_channel_params.franka_command_channel, &lcm, + 1.0 / 1000.0)); + auto franka_command_translator = + builder.AddSystem(); + + builder.Connect(*franka_command_translator, *franka_command_pub); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("sampling_c3_franka_bridge_driver_in")); + + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_command_translator, + lcm_channel_params.franka_input_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/franka_bridge_driver_out.cc b/examples/sampling_c3/franka_bridge_driver_out.cc new file mode 100644 index 0000000000..2b8570d2c5 --- /dev/null +++ b/examples/sampling_c3/franka_bridge_driver_out.cc @@ -0,0 +1,108 @@ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/parameters/franka_drake_lcm_driver_channels.h" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "systems/franka_state_translator.h" +#include "multibody/multibody_utils.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" + +#include "drake/common/find_resource.h" + +using drake::math::RigidTransform; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::Simulator; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; + +using dairlib::systems::RobotInputReceiver; +using dairlib::systems::RobotOutputSender; +using dairlib::systems::SubvectorPassThrough; +using dairlib::systems::TimestampedVector; + + +// NOTE: While most module's TTL is set to 0 by default, this one is set to 1 +// since it necessarily needs to communicate with the Franka. +DEFINE_string(lcm_url, "udpm://239.255.76.67:7667?ttl=1", + "LCM URL with IP, port, and TTL settings"); +DEFINE_string( + demo_name, "jacktoy", + "Name for the demo, used for finding the sub-example-specific files."); + +namespace dairlib { + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + std::string lcm_channels_file = controller_params.lcm_channels_hardware_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + FrankaDrakeLcmDriverChannels franka_driver_channel_params = + drake::yaml::LoadYamlFile( + controller_params.franka_driver_channels_file); + + DiagramBuilder builder; + + MultibodyPlant plant(0.0); + + Parser parser(&plant); + AddFrankaToPlant(&plant, nullptr, false, false); + plant.Finalize(); + + auto pos_map = multibody::MakeNameToPositionsMap(plant); + auto vel_map = multibody::MakeNameToVelocitiesMap(plant); + auto act_map = multibody::MakeNameToActuatorsMap(plant); + + auto pos_names = multibody::ExtractOrderedNamesFromMap(pos_map); + auto vel_names = multibody::ExtractOrderedNamesFromMap(vel_map); + auto act_names = multibody::ExtractOrderedNamesFromMap(act_map); + + /* -------------------------------------------------------------------------*/ + drake::lcm::DrakeLcm lcm(FLAGS_lcm_url); + + auto franka_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_state_channel, &lcm, 1.0 / 1000.0)); + auto franka_state_translator = + builder.AddSystem( + pos_names, vel_names, act_names); + + builder.Connect(*franka_state_translator, *franka_state_pub); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("sampling_c3_franka_bridge_driver_out")); + + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_state_translator, + franka_driver_channel_params.franka_status_channel, true); + DrawAndSaveDiagramGraph(*loop.get_diagram()); + loop.Simulate(); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/franka_joint_osc_controller.cc b/examples/sampling_c3/franka_joint_osc_controller.cc new file mode 100644 index 0000000000..fbc46b9ef4 --- /dev/null +++ b/examples/sampling_c3/franka_joint_osc_controller.cc @@ -0,0 +1,194 @@ + +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "examples/sampling_c3/parameter_headers/osc_params.h" +#include "systems/controllers/osc/end_effector_force.h" +#include "systems/controllers/osc/end_effector_orientation.h" +#include "systems/controllers/osc/end_effector_position.h" +#include "joint_trajectory_generator.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/gravity_compensator.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" + +#include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" +#include "drake/multibody/parsing/parser.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" + +namespace dairlib { + +using drake::math::RigidTransform; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using std::string; + +using systems::controllers::JointSpaceTrackingData; + + +DEFINE_bool(is_simulation, true, "True for simulation, false for hardware"); +DEFINE_string(lcm_url, "udpm://239.255.76.67:7667?ttl=0", + "LCM URL with IP, port, and TTL settings"); +DEFINE_string(demo_name, "jacktoy", + "Demo within sampling_c3; used to find controller params file"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm(FLAGS_lcm_url); + + // Load parameters. + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + SamplingC3OSCParams osc_params = + drake::yaml::LoadYamlFile( + controller_params.osc_params_file); + std::string lcm_channels_file = FLAGS_is_simulation ? + controller_params.lcm_channels_simulation_file : + controller_params.lcm_channels_hardware_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_params.osc_qp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + // Create a Franka-only plant. + drake::multibody::MultibodyPlant plant(0.0); + AddFrankaToPlant(&plant); + plant.Finalize(); + auto plant_context = plant.CreateDefaultContext(); + + // Piece together the diagram. + DiagramBuilder builder; + + auto state_receiver = builder.AddSystem(plant); + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_input_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto osc_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto franka_command_sender = + builder.AddSystem(plant); + auto osc_command_sender = + builder.AddSystem(plant); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), false); + if (osc_params.publish_debug_info) { + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_debug_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); + } + // WARNING: Hard-coded initial joint configurations for the robot in the + // sampling c3 experiments. + VectorXd target_position = VectorXd::Zero(7); + target_position << 2.191, 1.1, -1.33, -2.22, 1.30, 2.02, 0.08; + auto joint_traj_generator = + builder.AddSystem(plant, target_position); + std::vector> joint_tracking_data_vec; + std::vector joint_names = { + "panda_joint1", "panda_joint2", "panda_joint3", "panda_joint4", + "panda_joint5", "panda_joint6", "panda_joint7"}; + for (int joint_idx = 0; joint_idx < joint_names.size(); ++joint_idx) { + string joint_name = joint_names[joint_idx]; + MatrixXd W = 1.0 * MatrixXd::Identity(1, 1); + MatrixXd K_p = 100 * MatrixXd::Identity(1, 1); + MatrixXd K_d = 5 * MatrixXd::Identity(1, 1); + joint_tracking_data_vec.push_back(std::make_unique( + joint_name + "_traj", K_p, K_d, W, plant, plant)); + joint_tracking_data_vec[joint_idx]->AddJointToTrack(joint_name, + joint_name + "dot"); + + osc->AddTrackingData(std::move(joint_tracking_data_vec[joint_idx])); + + builder.Connect(joint_traj_generator->get_output_port_joint(joint_idx), + osc->get_input_port_tracking_data(joint_name + "_traj")); + } + + osc->SetAccelerationCostWeights(osc_params.W_acceleration); + osc->SetInputCostWeights(osc_params.W_input_regularization); + osc->SetInputSmoothingCostWeights(osc_params.W_input_smoothing_regularization); + + osc->SetContactFriction(osc_params.mu); + osc->SetOsqpSolverOptions(solver_options); + + osc->Build(); + + if (osc_params.cancel_gravity_compensation) { + if (FLAGS_is_simulation) { + std::cerr<<"Sim OSC needs cancel_gravity_compensation: false"<(plant, + *plant_context); + builder.Connect(osc->get_output_port_osc_command(), + gravity_compensator->get_input_port()); + builder.Connect(gravity_compensator->get_output_port(), + franka_command_sender->get_input_port()); + } else { + if (!FLAGS_is_simulation) { + std::cerr<<"HW OSC needs cancel_gravity_compensation: true"<get_output_port_osc_command(), + franka_command_sender->get_input_port(0)); + } + + builder.Connect(franka_command_sender->get_output_port(), + franka_command_pub->get_input_port()); + builder.Connect(osc_command_sender->get_output_port(), + osc_command_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_command(), + osc_command_sender->get_input_port(0)); + builder.Connect(state_receiver->get_output_port(0), + osc->get_input_port_robot_output()); + builder.Connect(state_receiver->get_output_port(0), + joint_traj_generator->get_input_port_robot_state()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("sampling_c3_franka_joint_osc_controller")); + DrawAndSaveDiagramGraph(*owned_diagram); + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, + lcm_channel_params.franka_state_channel, true); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/franka_osc_controller.cc b/examples/sampling_c3/franka_osc_controller.cc new file mode 100644 index 0000000000..fa7f7e08d7 --- /dev/null +++ b/examples/sampling_c3/franka_osc_controller.cc @@ -0,0 +1,273 @@ + +#include +#include +#include + +#include "common/eigen_utils.h" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "examples/sampling_c3/parameter_headers/osc_params.h" +#include "systems/controllers/osc/end_effector_force.h" +#include "systems/controllers/osc/end_effector_orientation.h" +#include "systems/controllers/osc/end_effector_position.h" +#include "lcm/lcm_trajectory.h" +#include "multibody/multibody_utils.h" +#include "systems/controllers/gravity_compensator.h" +#include "systems/controllers/osc/external_force_tracking_data.h" +#include "systems/controllers/osc/joint_space_tracking_data.h" +#include "systems/controllers/osc/operational_space_control.h" +#include "systems/controllers/osc/relative_translation_tracking_data.h" +#include "systems/controllers/osc/rot_space_tracking_data.h" +#include "systems/controllers/osc/trans_space_tracking_data.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/robot_lcm_systems.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" + +#include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" +#include "drake/multibody/parsing/parser.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_publisher_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" + +namespace dairlib { + +using drake::math::RigidTransform; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; + +using systems::controllers::ExternalForceTrackingData; +using systems::controllers::JointSpaceTrackingData; +using systems::controllers::RelativeTranslationTrackingData; +using systems::controllers::RotTaskSpaceTrackingData; +using systems::controllers::TransTaskSpaceTrackingData; + +DEFINE_bool(is_simulation, true, "True for simulation, false for hardware"); +DEFINE_string(lcm_url, "udpm://239.255.76.67:7667?ttl=0", + "LCM URL with IP, port, and TTL settings"); +DEFINE_string(demo_name, "jacktoy", + "Demo within sampling_c3; used to find controller params file"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm(FLAGS_lcm_url); + + // Load parameters. + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + SamplingC3OSCParams osc_params = + drake::yaml::LoadYamlFile( + controller_params.osc_params_file); + std::string lcm_channels_file = FLAGS_is_simulation ? + controller_params.lcm_channels_simulation_file : + controller_params.lcm_channels_hardware_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + drake::solvers::SolverOptions solver_options = + drake::yaml::LoadYamlFile( + FindResourceOrThrow(controller_params.osc_qp_settings_file)) + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + // Create a Franka-only plant. + drake::multibody::MultibodyPlant plant(0.0); + AddFrankaToPlant(&plant); + plant.Finalize(); + auto plant_context = plant.CreateDefaultContext(); + + // Piece together the diagram. + DiagramBuilder builder; + + auto state_receiver = builder.AddSystem(plant); + auto end_effector_trajectory_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.tracking_trajectory_actor_channel, &lcm)); + auto end_effector_position_receiver = + builder.AddSystem( + "end_effector_position_target"); + auto end_effector_force_receiver = + builder.AddSystem( + "end_effector_force_target"); + auto end_effector_orientation_receiver = + builder.AddSystem( + "end_effector_orientation_target"); + auto franka_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.franka_input_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto osc_command_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto franka_command_sender = + builder.AddSystem(plant); + auto osc_command_sender = + builder.AddSystem(plant); + auto end_effector_trajectory = + builder.AddSystem( + plant, plant_context.get(), osc_params.neutral_position, + osc_params.teleop_neutral_position, kEndEffectorName); + end_effector_trajectory->SetRemoteControlParameters( + osc_params.neutral_position, osc_params.x_scale, + osc_params.y_scale, osc_params.z_scale); + auto end_effector_orientation_trajectory = + builder.AddSystem(); + end_effector_orientation_trajectory->SetTrackOrientation( + osc_params.track_end_effector_orientation); + auto end_effector_force_trajectory = + builder.AddSystem(); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + auto osc = builder.AddSystem( + plant, plant, plant_context.get(), plant_context.get(), false); + if (osc_params.publish_debug_info) { + auto osc_debug_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.osc_debug_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); + } + + auto end_effector_position_tracking_data = + std::make_unique( + "end_effector_target", osc_params.K_p_end_effector, + osc_params.K_d_end_effector, osc_params.W_end_effector, + plant, plant); + end_effector_position_tracking_data->AddPointToTrack(kEndEffectorName); + const VectorXd& end_effector_acceleration_limits = + osc_params.end_effector_acceleration * Vector3d::Ones(); + end_effector_position_tracking_data->SetCmdAccelerationBounds( + -end_effector_acceleration_limits, end_effector_acceleration_limits); + auto mid_link_position_tracking_data_for_rel = + std::make_unique( + "panda_joint2_target", osc_params.K_p_mid_link, + osc_params.K_d_mid_link, osc_params.W_mid_link, plant, + plant); + mid_link_position_tracking_data_for_rel->AddJointToTrack("panda_joint2", + "panda_joint2dot"); + + auto end_effector_force_tracking_data = + std::make_unique( + "end_effector_force", osc_params.W_ee_lambda, plant, plant, + kEndEffectorName, Vector3d::Zero()); + + auto end_effector_orientation_tracking_data = + std::make_unique( + "end_effector_orientation_target", + osc_params.K_p_end_effector_rot, + osc_params.K_d_end_effector_rot, + osc_params.W_end_effector_rot, plant, plant); + end_effector_orientation_tracking_data->AddFrameToTrack(kEndEffectorName); + Eigen::VectorXd orientation_target = Eigen::VectorXd::Zero(4); + orientation_target(0) = 1; + osc->AddTrackingData(std::move(end_effector_position_tracking_data)); + // Since the Franka has 7 joints to control a 6 DOF EE command, add an + // additional tracking objective for joint 2 at a good configuration for the + // sampling C3 experiments. 1.1 joint target empirically works well. + osc->AddConstTrackingData(std::move(mid_link_position_tracking_data_for_rel), + 1.1 * VectorXd::Ones(1)); + osc->AddTrackingData(std::move(end_effector_orientation_tracking_data)); + osc->AddForceTrackingData(std::move(end_effector_force_tracking_data)); + osc->SetAccelerationCostWeights(osc_params.W_acceleration); + osc->SetInputCostWeights(osc_params.W_input_regularization); + osc->SetInputSmoothingCostWeights(osc_params.W_input_smoothing_regularization); + osc->SetAccelerationConstraints( + osc_params.enforce_acceleration_constraints); + + osc->SetContactFriction(osc_params.mu); + osc->SetOsqpSolverOptions(solver_options); + + osc->Build(); + + if (osc_params.cancel_gravity_compensation) { + if (FLAGS_is_simulation) { + std::cerr<<"Sim OSC needs cancel_gravity_compensation: false"<(plant, + *plant_context); + builder.Connect(osc->get_output_port_osc_command(), + gravity_compensator->get_input_port()); + builder.Connect(gravity_compensator->get_output_port(), + franka_command_sender->get_input_port()); + } else { + if (!FLAGS_is_simulation) { + std::cerr<<"HW OSC needs cancel_gravity_compensation: true"<get_output_port_osc_command(), + franka_command_sender->get_input_port(0)); + } + + builder.Connect(radio_sub->get_output_port(0), + end_effector_trajectory->get_input_port_radio()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_radio()); + builder.Connect(radio_sub->get_output_port(0), + end_effector_force_trajectory->get_input_port_radio()); + builder.Connect(franka_command_sender->get_output_port(), + franka_command_pub->get_input_port()); + builder.Connect(osc_command_sender->get_output_port(), + osc_command_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_command(), + osc_command_sender->get_input_port(0)); + + builder.Connect(state_receiver->get_output_port(0), + osc->get_input_port_robot_output()); + builder.Connect(end_effector_trajectory_sub->get_output_port(), + end_effector_position_receiver->get_input_port_trajectory()); + builder.Connect(end_effector_trajectory_sub->get_output_port(), + end_effector_force_receiver->get_input_port_trajectory()); + builder.Connect( + end_effector_trajectory_sub->get_output_port(), + end_effector_orientation_receiver->get_input_port_trajectory()); + builder.Connect(end_effector_position_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_trajectory()); + builder.Connect(state_receiver->get_output_port(0), + end_effector_trajectory->get_input_port_state()); + builder.Connect( + end_effector_orientation_receiver->get_output_port(0), + end_effector_orientation_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_target")); + builder.Connect( + end_effector_orientation_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_orientation_target")); + builder.Connect(end_effector_force_receiver->get_output_port(0), + end_effector_force_trajectory->get_input_port_trajectory()); + builder.Connect(end_effector_force_trajectory->get_output_port(0), + osc->get_input_port_tracking_data("end_effector_force")); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("sampling_c3_franka_osc_controller")); + DrawAndSaveDiagramGraph(*owned_diagram); + // Run lcm-driven simulation + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), state_receiver, + lcm_channel_params.franka_state_channel, true); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/franka_sampling_c3_controller.cc b/examples/sampling_c3/franka_sampling_c3_controller.cc new file mode 100644 index 0000000000..7d8f6ddc3b --- /dev/null +++ b/examples/sampling_c3/franka_sampling_c3_controller.cc @@ -0,0 +1,499 @@ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "goal_generator.h" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "multibody/multibody_utils.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/sampling_based_c3_controller.h" +#include "systems/framework/lcm_driven_loop.h" +#include "systems/franka_kinematics.h" +#include "systems/robot_lcm_systems.h" +#include "systems/senders/c3_state_sender.h" +#include "systems/senders/sample_buffer_sender.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/c3_output_systems.h" + +namespace dairlib { + +using dairlib::solvers::LCSFactory; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using drake::systems::TriggerType; +using drake::systems::TriggerTypeSet; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using Eigen::MatrixXd; + +using Eigen::Vector3d; +using Eigen::VectorXd; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using std::vector; + + +DEFINE_bool(is_simulation, true, "True for simulation, false for hardware"); +DEFINE_string(lcm_url, "udpm://239.255.76.67:7667?ttl=0", + "LCM URL with IP, port, and TTL settings"); +DEFINE_string(demo_name, "jacktoy", + "Demo within sampling_c3; used to find controller params file"); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + drake::lcm::DrakeLcm lcm(FLAGS_lcm_url); + + // Load parameters. + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + std::string lcm_channels_file = FLAGS_is_simulation ? + controller_params.lcm_channels_simulation_file : + controller_params.lcm_channels_hardware_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + + // Create a Franka-only plant. + MultibodyPlant plant_franka(0.0); + AddFrankaToPlant(&plant_franka); + plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + + // Create an object-only plant. + MultibodyPlant plant_object(0.0); + AddObjectToPlant(&plant_object, nullptr, controller_params.object_model); + plant_object.Finalize(); + auto object_context = plant_object.CreateDefaultContext(); + + // Create the LCS plant containing a floating EE, object, and ground. + DiagramBuilder plant_lcs_builder; + auto [plant_lcs, scene_graph] = + AddMultibodyPlantSceneGraph(&plant_lcs_builder, 0.0); + AddLCSModelsToPlant(&plant_lcs, &scene_graph, controller_params.object_model, + controller_params.include_end_effector_orientation); + plant_lcs.Finalize(); + + std::unique_ptr> plant_lcs_autodiff = + drake::systems::System::ToAutoDiffXd(plant_lcs); + + auto plant_lcs_diagram = plant_lcs_builder.Build(); + std::unique_ptr> diagram_context = + plant_lcs_diagram->CreateDefaultContext(); + auto& plant_lcs_context = plant_lcs_diagram->GetMutableSubsystemContext( + plant_lcs, diagram_context.get()); + auto plant_lcs_context_ad = plant_lcs_autodiff->CreateDefaultContext(); + + // Build the contact pairs based on the demo. + std::vector>> contact_pairs; + std::unordered_map contact_geoms; + + // All demos include the end effector and ground. + drake::geometry::GeometryId ee_contact_points = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("end_effector_simple"))[0]; + drake::geometry::GeometryId ground_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("ground"))[0]; + contact_geoms["EE"] = ee_contact_points; + contact_geoms["GROUND"] = ground_geoms; + std::vector> ee_ground_contact{ + SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])}; + contact_pairs.push_back(ee_ground_contact); + + if (FLAGS_demo_name == "jacktoy") { + drake::geometry::GeometryId capsule1_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_1"))[0]; + drake::geometry::GeometryId capsule2_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_2"))[0]; + drake::geometry::GeometryId capsule3_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_3"))[0]; + + drake::geometry::GeometryId capsule1_sphere1_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_1"))[1]; + drake::geometry::GeometryId capsule1_sphere2_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_1"))[2]; + drake::geometry::GeometryId capsule2_sphere1_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_2"))[1]; + drake::geometry::GeometryId capsule2_sphere2_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_2"))[2]; + drake::geometry::GeometryId capsule3_sphere1_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_3"))[1]; + drake::geometry::GeometryId capsule3_sphere2_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("capsule_3"))[2]; + + contact_geoms["CAPSULE_1"] = capsule1_geoms; + contact_geoms["CAPSULE_2"] = capsule2_geoms; + contact_geoms["CAPSULE_3"] = capsule3_geoms; + contact_geoms["CAPSULE_1_SPHERE_1"] = capsule1_sphere1_geoms; + contact_geoms["CAPSULE_1_SPHERE_2"] = capsule1_sphere2_geoms; + contact_geoms["CAPSULE_2_SPHERE_1"] = capsule2_sphere1_geoms; + contact_geoms["CAPSULE_2_SPHERE_2"] = capsule2_sphere2_geoms; + contact_geoms["CAPSULE_3_SPHERE_1"] = capsule3_sphere1_geoms; + contact_geoms["CAPSULE_3_SPHERE_2"] = capsule3_sphere2_geoms; + + // EE-object contact pairs second. + std::vector> ee_contact_pairs; + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_1"])); + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_2"])); + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_3"])); + contact_pairs.push_back(ee_contact_pairs); + + // Object-ground contact pairs third. + std::vector> ground_object_contact_pairs; + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["CAPSULE_1_SPHERE_1"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["CAPSULE_1_SPHERE_2"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["CAPSULE_2_SPHERE_1"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["CAPSULE_2_SPHERE_2"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["CAPSULE_3_SPHERE_1"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["CAPSULE_3_SPHERE_2"], contact_geoms["GROUND"])); + contact_pairs.push_back(ground_object_contact_pairs); + } + else { + throw std::runtime_error("Unknown --demo_name value: " + FLAGS_demo_name); + } + + // Piece together the diagram. + DiagramBuilder builder; + + auto object_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.object_state_channel, &lcm)); + auto franka_state_receiver = + builder.AddSystem(plant_franka); + auto object_state_receiver = + builder.AddSystem(plant_object); + auto radio_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.radio_channel, &lcm)); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_object, + object_context.get(), kEndEffectorName, + controller_params.object_body_name, + controller_params.include_end_effector_orientation); + + // Select the target generator based on the demo. + std::unique_ptr target_generator; + if (FLAGS_demo_name == "jacktoy") { + target_generator = + std::make_unique( + plant_object, controller_params.goal_params); + } else { + throw std::runtime_error("Unknown --demo_name value: " + FLAGS_demo_name); + } + auto* control_target = builder.AddSystem(std::move(target_generator)); + + // Input sizes are EE position (3), object pose (7), EE velocity (3), object + // velocities (6). + std::vector input_sizes = {3, 7, 3, 6}; + auto target_state_mux = + builder.AddSystem(input_sizes); + auto final_target_state_mux = + builder.AddSystem(input_sizes); + auto end_effector_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(3)); + auto object_zero_velocity_source = + builder.AddSystem( + VectorXd::Zero(6)); + auto target_gen_info_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.target_generator_info_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + builder.Connect(control_target->get_output_port_end_effector_target(), + target_state_mux->get_input_port(0)); + builder.Connect(control_target->get_output_port_object_target(), + target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + target_state_mux->get_input_port(2)); + builder.Connect(control_target->get_output_port_object_velocity_target(), + target_state_mux->get_input_port(3)); + builder.Connect(control_target->get_output_port_target_gen_info(), + target_gen_info_publisher->get_input_port()); + builder.Connect(control_target->get_output_port_end_effector_target(), + final_target_state_mux->get_input_port(0)); + builder.Connect(control_target->get_output_port_object_final_target(), + final_target_state_mux->get_input_port(1)); + builder.Connect(end_effector_zero_velocity_source->get_output_port(), + final_target_state_mux->get_input_port(2)); + builder.Connect(object_zero_velocity_source->get_output_port(), + final_target_state_mux->get_input_port(3)); + + // Sampling C3 controller. + auto controller = builder.AddSystem( + plant_lcs, &plant_lcs_context, *plant_lcs_autodiff, + plant_lcs_context_ad.get(), contact_pairs, controller_params); + + // Systems for publishing the current and best planned trajectories. + auto actor_trajectory_sender_curr_plan = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_curr_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto object_trajectory_sender_curr_plan = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_curr_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto actor_trajectory_sender_best_plan = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_actor_best_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto object_trajectory_sender_best_plan = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_object_best_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + // C3 senders. + auto c3_output_sender_curr_plan = + builder.AddNamedSystem("c3_output_sender_curr_plan", + std::make_unique()); + auto c3_output_publisher_curr_plan = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_curr_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher_curr_plan = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_curr_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + auto c3_output_sender_best_plan = + builder.AddNamedSystem("c3_output_sender_best_plan", + std::make_unique()); + auto c3_output_publisher_best_plan = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_debug_output_best_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_forces_publisher_best_plan = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_force_best_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + // Systems for publishing the tracking output. + auto actor_c3_execution_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.c3_trajectory_exec_actor_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto actor_repos_execution_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.repos_trajectory_exec_actor_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto actor_tracking_trajectory_sender = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.tracking_trajectory_actor_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + // Sample-related senders/publishers. + auto sample_buffer_sender = builder.AddSystem( + controller_params.sampling_params.N_sample_buffer, + plant_lcs.num_positions()); + auto sample_buffer_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.sample_buffer_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto sample_locations_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.sample_locations_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto sample_costs_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.sample_costs_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + // Debugging publishers. + auto controller_debug_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.sampling_c3_debug_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto is_c3_mode_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.is_c3_mode_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + // Dynamically feasible plan publishers. + auto dynamically_feasible_curr_plan_actor_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.dynamically_feasible_curr_actor_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto dynamically_feasible_curr_plan_object_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.dynamically_feasible_curr_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto dynamically_feasible_best_plan_actor_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.dynamically_feasible_best_actor_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto dynamically_feasible_best_plan_object_publisher = builder.AddSystem( + LcmPublisherSystem::Make( + lcm_channel_params.dynamically_feasible_best_plan_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + std::vector state_names = { + "end_effector_x", "end_effector_y", "end_effector_z", + "object_qw", "object_qx", "object_qy", "object_qz", + "object_x", "object_y", "object_z", + "end_effector_vx", "end_effector_vy", "end_effector_vz", + "object_wx" , "object_wy", "object_wz", + "object_vz", "object_vz", "object_vz", + }; + // C3 state senders: actual, target, and final target. + auto c3_state_sender = builder.AddSystem( + plant_lcs.num_positions() + plant_lcs.num_velocities(), + state_names); + auto c3_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_actual_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_actual_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + auto c3_final_target_state_publisher = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.c3_final_target_state_channel, &lcm, + TriggerTypeSet({TriggerType::kForced}))); + + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(object_state_sub->get_output_port(), + object_state_receiver->get_input_port()); + builder.Connect(object_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + controller->get_input_port_lcs_state()); + builder.Connect(object_state_receiver->get_output_port(), + control_target->get_input_port_object_state()); + builder.Connect(target_state_mux->get_output_port(), + controller->get_input_port_target()); + builder.Connect(final_target_state_mux->get_output_port(), + controller->get_input_port_final_target()); + builder.Connect(radio_sub->get_output_port(), + controller->get_input_port_radio()); + builder.Connect(radio_sub->get_output_port(), + control_target->get_input_port_radio()); + builder.Connect(controller->get_output_port_c3_solution_curr_plan_actor(), + actor_trajectory_sender_curr_plan->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution_curr_plan_object(), + object_trajectory_sender_curr_plan->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution_best_plan_actor(), + actor_trajectory_sender_best_plan->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution_best_plan_object(), + object_trajectory_sender_best_plan->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution_curr_plan(), + c3_output_sender_curr_plan->get_input_port_c3_solution()); + builder.Connect(controller->get_output_port_c3_intermediates_curr_plan(), + c3_output_sender_curr_plan->get_input_port_c3_intermediates()); + builder.Connect(controller->get_output_port_lcs_contact_jacobian_curr_plan(), + c3_output_sender_curr_plan->get_input_port_lcs_contact_info()); + builder.Connect(c3_output_sender_curr_plan->get_output_port_c3_debug(), + c3_output_publisher_curr_plan->get_input_port()); + builder.Connect(c3_output_sender_curr_plan->get_output_port_c3_force(), + c3_forces_publisher_curr_plan->get_input_port()); + builder.Connect(controller->get_output_port_c3_solution_best_plan(), + c3_output_sender_best_plan->get_input_port_c3_solution()); + builder.Connect(controller->get_output_port_c3_intermediates_best_plan(), + c3_output_sender_best_plan->get_input_port_c3_intermediates()); + builder.Connect(controller->get_output_port_lcs_contact_jacobian_best_plan(), + c3_output_sender_best_plan->get_input_port_lcs_contact_info()); + builder.Connect(c3_output_sender_best_plan->get_output_port_c3_debug(), + c3_output_publisher_best_plan->get_input_port()); + builder.Connect(c3_output_sender_best_plan->get_output_port_c3_force(), + c3_forces_publisher_best_plan->get_input_port()); + builder.Connect(controller->get_output_port_dynamically_feasible_curr_plan_actor(), + dynamically_feasible_curr_plan_actor_publisher->get_input_port()); + builder.Connect(controller->get_output_port_dynamically_feasible_best_plan_actor(), + dynamically_feasible_best_plan_actor_publisher->get_input_port()); + builder.Connect(controller->get_output_port_dynamically_feasible_curr_plan_object(), + dynamically_feasible_curr_plan_object_publisher->get_input_port()); + builder.Connect(controller->get_output_port_dynamically_feasible_curr_plan_object(), + dynamically_feasible_best_plan_object_publisher->get_input_port()); + builder.Connect(target_state_mux->get_output_port(), + c3_state_sender->get_input_port_target_state()); + builder.Connect(final_target_state_mux->get_output_port(), + c3_state_sender->get_input_port_final_target_state()); + builder.Connect(reduced_order_model_receiver->get_output_port_lcs_state(), + c3_state_sender->get_input_port_actual_state()); + builder.Connect(c3_state_sender->get_output_port_target_c3_state(), + c3_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_final_target_c3_state(), + c3_final_target_state_publisher->get_input_port()); + builder.Connect(c3_state_sender->get_output_port_actual_c3_state(), + c3_actual_state_publisher->get_input_port()); + builder.Connect(controller->get_output_port_c3_traj_execute_actor(), + actor_c3_execution_trajectory_sender->get_input_port()); + builder.Connect(controller->get_output_port_repos_traj_execute_actor(), + actor_repos_execution_trajectory_sender->get_input_port()); + builder.Connect(controller->get_output_port_traj_execute_actor(), + actor_tracking_trajectory_sender->get_input_port()); + builder.Connect(controller->get_output_port_all_sample_locations(), + sample_locations_publisher->get_input_port()); + builder.Connect(controller->get_output_port_all_sample_costs(), + sample_costs_publisher->get_input_port()); + builder.Connect(controller->get_output_port_is_c3_mode(), + is_c3_mode_publisher->get_input_port()); + builder.Connect(controller->get_output_port_debug(), + controller_debug_publisher->get_input_port()); + builder.Connect(sample_buffer_sender->get_output_port_sample_buffer(), + sample_buffer_publisher->get_input_port()); + builder.Connect(controller->get_output_port_sample_buffer_configurations(), + sample_buffer_sender->get_input_port_samples()); + builder.Connect(controller->get_output_port_sample_buffer_costs(), + sample_buffer_sender->get_input_port_sample_costs()); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("sampling_c3_controller_" + FLAGS_demo_name)); + plant_lcs_diagram->set_name(("sampling_c3_lcs_plant" + FLAGS_demo_name)); + DrawAndSaveDiagramGraph(*owned_diagram); + DrawAndSaveDiagramGraph(*plant_lcs_diagram); + + // Run lcm-driven simulation. The buffer size argument is needed to ensure + // the latest messages are used in the control loop. See + // https://github.com/DAIRLab/dairlib/pull/366 for more details. + int lcm_buffer_size = 200; + systems::LcmDrivenLoop loop( + &lcm, std::move(owned_diagram), franka_state_receiver, + lcm_channel_params.franka_state_channel, true, lcm_buffer_size); + LcmHandleSubscriptionsUntil( + &lcm, [&]() { return object_state_sub->GetInternalMessageCount() > 1; }); + loop.Simulate(); + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/franka_sim.cc b/examples/sampling_c3/franka_sim.cc new file mode 100644 index 0000000000..8d92dc0d64 --- /dev/null +++ b/examples/sampling_c3/franka_sim.cc @@ -0,0 +1,139 @@ +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "common/find_resource.h" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "examples/sampling_c3/parameter_headers/franka_sim_params.h" +#include "multibody/multibody_utils.h" +#include "systems/robot_lcm_systems.h" + +namespace dairlib { + +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::GeometrySet; +using drake::geometry::SceneGraph; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::ModelInstanceIndex; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::Context; +using drake::systems::DiagramBuilder; +using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::trajectories::PiecewisePolynomial; +using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; +using systems::AddActuationRecieverAndStateSenderLcm; + +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + + +DEFINE_string(lcm_url, "udpm://239.255.76.67:7667?ttl=0", + "LCM URL with IP, port, and TTL settings"); +DEFINE_string(demo_name, "jacktoy", + "Name for the demo, used when building filepaths for output."); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Load parameters. + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + std::string lcm_channels_file = + controller_params.lcm_channels_simulation_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + FrankaSimParams sim_params = drake::yaml::LoadYamlFile( + controller_params.sim_params_file); + + // Build the simulation plant. + DiagramBuilder builder; + double sim_dt = sim_params.dt; + auto [plant, scene_graph] = AddMultibodyPlantSceneGraph(&builder, sim_dt); + ModelInstanceIndex franka_index = AddFrankaToPlant(&plant, &scene_graph); + ModelInstanceIndex object_index = AddObjectToPlant(&plant, &scene_graph, + sim_params.object_model); + plant.Finalize(); + /* -------------------------------------------------------------------------------------------*/ + + drake::lcm::DrakeLcm drake_lcm(FLAGS_lcm_url); + auto lcm = + builder.AddSystem(&drake_lcm); + AddActuationRecieverAndStateSenderLcm( + &builder, plant, lcm, lcm_channel_params.franka_input_channel, + lcm_channel_params.franka_state_channel, sim_params.franka_publish_rate, + franka_index, sim_params.publish_efforts, sim_params.actuator_delay); + auto object_state_sender = + builder.AddSystem(plant, false, object_index); + auto object_state_pub = + builder.AddSystem(LcmPublisherSystem::Make( + lcm_channel_params.object_state_channel, lcm, + 1.0 / sim_params.object_publish_rate)); + + builder.Connect(plant.get_state_output_port(object_index), + object_state_sender->get_input_port_state()); + builder.Connect(object_state_sender->get_output_port(), + object_state_pub->get_input_port()); + + int nq = plant.num_positions(); + int nv = plant.num_velocities(); + + if (sim_params.visualize_drake_sim) { + drake::visualization::AddDefaultVisualization(&builder); + } + + auto diagram = builder.Build(); + + drake::systems::Simulator simulator(*diagram); + + simulator.set_publish_every_time_step(false); + simulator.set_publish_at_initialization(false); + simulator.set_target_realtime_rate(sim_params.realtime_rate); + + auto& plant_context = diagram->GetMutableSubsystemContext( + plant, &simulator.get_mutable_context()); + + VectorXd q = VectorXd::Zero(nq); + + q.head(plant.num_positions(franka_index)) = sim_params.q_init_franka; + q.tail(plant.num_positions(object_index)) = sim_params.q_init_object; + + plant.SetPositions(&plant_context, q); + + VectorXd v = VectorXd::Zero(nv); + plant.SetVelocities(&plant_context, v); + + simulator.Initialize(); + simulator.AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/franka_visualizer.cc b/examples/sampling_c3/franka_visualizer.cc new file mode 100644 index 0000000000..9ab4b23f15 --- /dev/null +++ b/examples/sampling_c3/franka_visualizer.cc @@ -0,0 +1,544 @@ +#include +#include +#include +#include +#include + +#include "common/eigen_utils.h" +#include "common/find_resource.h" +#include "dairlib/lcmt_robot_output.hpp" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/c3_mode_visualizer.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/lcm_channels.h" +#include "examples/sampling_c3/parameter_headers/visualizer_params.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_options.h" +#include "examples/sampling_c3/parameter_headers/sampling_params.h" +#include "multibody/com_pose_system.h" +#include "multibody/multibody_utils.h" +#include "multibody/visualization_utils.h" +#include "systems/franka_kinematics.h" +#include "systems/primitives/subvector_pass_through.h" +#include "systems/robot_lcm_systems.h" +#include "systems/senders/sample_buffer_to_point_cloud.h" +#include "systems/system_utils.h" +#include "systems/trajectory_optimization/lcm_trajectory_systems.h" +#include "systems/visualization/lcm_visualization_systems.h" + +#include "drake/common/find_resource.h" +#include "drake/common/yaml/yaml_io.h" +#include "drake/geometry/drake_visualizer.h" +#include "drake/geometry/meshcat_point_cloud_visualizer.h" +#include "drake/geometry/meshcat_visualizer.h" +#include "drake/geometry/meshcat_visualizer_params.h" +#include "drake/multibody/parsing/parser.h" +#include "drake/systems/analysis/simulator.h" +#include "drake/systems/framework/diagram_builder.h" +#include "drake/systems/lcm/lcm_interface_system.h" +#include "drake/systems/lcm/lcm_subscriber_system.h" +#include "drake/systems/primitives/multiplexer.h" +#include "drake/systems/rendering/multibody_position_to_geometry_pose.h" + +namespace dairlib { + +using Eigen::MatrixXd; +using Eigen::Vector3d; +using Eigen::VectorXd; + +using dairlib::systems::ObjectStateReceiver; +using dairlib::systems::RobotOutputReceiver; +using dairlib::systems::SubvectorPassThrough; +using drake::geometry::DrakeVisualizer; +using drake::geometry::MeshcatPointCloudVisualizer; +using drake::geometry::SceneGraph; +using drake::geometry::Sphere; +using drake::math::RigidTransformd; +using drake::multibody::ModelInstanceIndex; +using drake::multibody::MultibodyPlant; +using drake::multibody::RigidBody; +using drake::multibody::SpatialInertia; +using drake::multibody::UnitInertia; +using drake::systems::Simulator; +using drake::systems::lcm::LcmSubscriberSystem; +using drake::systems::rendering::MultibodyPositionToGeometryPose; + +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; + + +DEFINE_bool(is_simulation, true, "True for simulation, false for hardware"); +DEFINE_string(demo_name, "jacktoy", + "Name for the demo, used when building filepaths for output."); + +int do_main(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + + // Load parameters. + std::string controller_params_path = "examples/sampling_c3/" + + FLAGS_demo_name + "/parameters/sampling_c3_controller_params.yaml"; + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + controller_params_path); + SamplingC3VisualizerParams vis_params = + drake::yaml::LoadYamlFile( + controller_params.vis_params_file); + SamplingC3Options sampling_c3_options = controller_params.sampling_c3_options; + SamplingParams sampling_params = controller_params.sampling_params; + std::string lcm_channels_file = FLAGS_is_simulation ? + controller_params.lcm_channels_simulation_file : + controller_params.lcm_channels_hardware_file; + SamplingC3LcmChannels lcm_channel_params = + drake::yaml::LoadYamlFile(lcm_channels_file); + + drake::systems::DiagramBuilder builder; + + SceneGraph& scene_graph = *builder.AddSystem(); + scene_graph.set_name("scene_graph"); + + // Build the visualizer plant. + MultibodyPlant plant(0.0); + ModelInstanceIndex franka_index = AddFrankaToPlant(&plant, &scene_graph); + ModelInstanceIndex object_index = AddObjectToPlant( + &plant, &scene_graph, vis_params.object_vis_model); + plant.Finalize(); + + // Create a Franka-only plant. + MultibodyPlant plant_franka(0.0); + AddFrankaToPlant(&plant_franka, nullptr, true, false); + plant_franka.Finalize(); + auto franka_context = plant_franka.CreateDefaultContext(); + + // Create an object-only plant. + MultibodyPlant plant_object(0.0); + AddObjectToPlant(&plant_object, nullptr, + vis_params.object_vis_model); + plant_object.Finalize(); + auto object_context = plant_object.CreateDefaultContext(); + + auto lcm = builder.AddSystem(); + auto franka_state_receiver = + builder.AddSystem(plant, franka_index); + auto object_state_receiver = + builder.AddSystem(plant, object_index); + auto franka_passthrough = builder.AddSystem( + franka_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(franka_index)); + auto robot_time_passthrough = builder.AddSystem( + franka_state_receiver->get_output_port(0).size(), + franka_state_receiver->get_output_port(0).size() - 1, 1); + auto tray_passthrough = builder.AddSystem( + object_state_receiver->get_output_port(0).size(), 0, + plant.num_positions(object_index)); + + std::vector input_sizes = {plant.num_positions(franka_index), + plant.num_positions(object_index)}; + auto mux = + builder.AddSystem>(input_sizes); + auto reduced_order_model_receiver = + builder.AddSystem( + plant_franka, franka_context.get(), plant_object, + object_context.get(), kEndEffectorName, + controller_params.object_body_name, false); + builder.Connect(franka_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_franka_state()); + builder.Connect(object_state_receiver->get_output_port(), + reduced_order_model_receiver->get_input_port_object_state()); + + // LCM subscribers. + auto franka_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.franka_state_channel, lcm)); + auto object_state_sub = + builder.AddSystem(LcmSubscriberSystem::Make( + lcm_channel_params.object_state_channel, lcm)); + auto is_c3_mode_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.is_c3_mode_channel, lcm)); + + auto c3_execution_trajectory_sub_actor = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_trajectory_exec_actor_channel, lcm)); + auto repos_execution_trajectory_sub_actor = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.repos_trajectory_exec_actor_channel, lcm)); + + auto trajectory_sub_actor_curr = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_actor_curr_plan_channel, lcm)); + auto trajectory_sub_object_curr = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_object_curr_plan_channel, lcm)); + auto trajectory_sub_force_curr = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_force_curr_channel, lcm)); + auto dynamically_feasible_trajectory_sub_object_curr = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.dynamically_feasible_curr_plan_channel, lcm)); + auto dynamically_feasible_trajectory_sub_actor_curr = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.dynamically_feasible_curr_actor_plan_channel, + lcm)); + + auto trajectory_sub_actor_best = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_actor_best_plan_channel, lcm)); + auto trajectory_sub_object_best = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_object_best_plan_channel, lcm)); + auto trajectory_sub_force_best = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_force_best_channel, lcm)); + auto dynamically_feasible_trajectory_sub_object_best = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.dynamically_feasible_best_plan_channel, lcm)); + auto dynamically_feasible_trajectory_sub_actor_best = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.dynamically_feasible_best_actor_plan_channel, + lcm)); + + auto sample_location_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.sample_locations_channel, lcm)); + auto sample_buffer_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.sample_buffer_channel, lcm)); + auto sample_costs_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.sample_costs_channel, lcm)); + + auto c3_state_actual_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_actual_state_channel, lcm)); + auto c3_state_target_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_target_state_channel, lcm)); + auto c3_final_state_target_sub = builder.AddSystem( + LcmSubscriberSystem::Make( + lcm_channel_params.c3_final_target_state_channel, lcm)); + + auto to_pose = + builder.AddSystem>(plant); + + drake::geometry::MeshcatVisualizerParams params; + params.publish_period = 1.0 / vis_params.visualizer_publish_rate; + auto meshcat = std::make_shared(); + meshcat->SetCameraPose(vis_params.camera_pose, vis_params.camera_target); + + if (vis_params.visualize_c3_workspace) { + // Note: There are also robot radius limits which are not visualized. + double width = sampling_c3_options.workspace_limits[0][4] - + sampling_c3_options.workspace_limits[0][3]; // x + double depth = sampling_c3_options.workspace_limits[1][4] - + sampling_c3_options.workspace_limits[1][3]; // y + double height = sampling_c3_options.workspace_limits[2][4] - + sampling_c3_options.workspace_limits[2][3]; // z + Vector3d workspace_center = { + 0.5 * (sampling_c3_options.workspace_limits[0][4] + + sampling_c3_options.workspace_limits[0][3]), + 0.5 * (sampling_c3_options.workspace_limits[1][4] + + sampling_c3_options.workspace_limits[1][3]), + 0.5 * (sampling_c3_options.workspace_limits[2][4] + + sampling_c3_options.workspace_limits[2][3])}; + meshcat->SetObject("c3_workspace", + drake::geometry::Box(width, depth, height), + {0, 1, 0, 0.2}); + meshcat->SetTransform("c3_workspace", RigidTransformd(workspace_center)); + } + + if (vis_params.visualize_execution_plan) { + auto c3_exec_trajectory_drawer_actor = + builder.AddSystem( + meshcat, "end_effector_position_target", "c3_exec_"); + auto repos_trajectory_drawer_actor = + builder.AddSystem( + meshcat, "end_effector_position_target", "repos_exec_"); + c3_exec_trajectory_drawer_actor->SetLineColor( + drake::geometry::Rgba({1, 0.75, 0.79, 1})); + c3_exec_trajectory_drawer_actor->SetLineWidth(10000000); + repos_trajectory_drawer_actor->SetLineColor( + drake::geometry::Rgba({0, 0, 1, 1})); + repos_trajectory_drawer_actor->SetLineWidth(10000000); + c3_exec_trajectory_drawer_actor->SetNumSamples(sampling_c3_options.N); + repos_trajectory_drawer_actor->SetNumSamples(sampling_c3_options.N); + builder.Connect( + c3_execution_trajectory_sub_actor->get_output_port(), + c3_exec_trajectory_drawer_actor->get_input_port_trajectory()); + builder.Connect(repos_execution_trajectory_sub_actor->get_output_port(), + repos_trajectory_drawer_actor->get_input_port_trajectory()); + } + + if (vis_params.visualize_center_of_mass_plan_curr) { + auto trajectory_drawer_actor_curr = + builder.AddSystem( + meshcat, "end_effector_position_target", "curr_"); + auto trajectory_drawer_object_curr = + builder.AddSystem( + meshcat, "object_position_target", "curr_"); + trajectory_drawer_actor_curr->SetLineColor( + drake::geometry::Rgba({1, 0, 0, 1})); + trajectory_drawer_object_curr->SetLineColor( + drake::geometry::Rgba({1, 0, 0, 1})); + trajectory_drawer_actor_curr->SetNumSamples(sampling_c3_options.N); + trajectory_drawer_object_curr->SetNumSamples(sampling_c3_options.N); + builder.Connect(trajectory_sub_actor_curr->get_output_port(), + trajectory_drawer_actor_curr->get_input_port_trajectory()); + builder.Connect(trajectory_sub_object_curr->get_output_port(), + trajectory_drawer_object_curr->get_input_port_trajectory()); + } + + if (vis_params.visualize_center_of_mass_plan_best) { + auto trajectory_drawer_actor_best = + builder.AddSystem( + meshcat, "end_effector_position_target", "best_"); + auto trajectory_drawer_object_best = + builder.AddSystem( + meshcat, "object_position_target", "best_"); + trajectory_drawer_actor_best->SetLineColor( + drake::geometry::Rgba({0, 1, 0, 1})); + trajectory_drawer_object_best->SetLineColor( + drake::geometry::Rgba({0, 1, 0, 1})); + trajectory_drawer_actor_best->SetNumSamples(sampling_c3_options.N); + trajectory_drawer_object_best->SetNumSamples(sampling_c3_options.N); + builder.Connect(trajectory_sub_actor_best->get_output_port(), + trajectory_drawer_actor_best->get_input_port_trajectory()); + builder.Connect(trajectory_sub_object_best->get_output_port(), + trajectory_drawer_object_best->get_input_port_trajectory()); + } + + if (vis_params.visualize_c3_plan_curr) { + auto object_pose_drawer_curr = builder.AddSystem( + meshcat, FindResourceOrThrow(vis_params.object_vis_model), + "object_position_target", "object_orientation_target", + "plans/curr_planned", sampling_c3_options.N, true, + vis_params.c3_curr_object_color); + builder.Connect(trajectory_sub_object_curr->get_output_port(), + object_pose_drawer_curr->get_input_port_trajectory()); + + auto end_effector_pose_drawer_curr = + builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.ee_vis_model), + "end_effector_position_target", "end_effector_orientation_target", + "plans/curr_planned", sampling_c3_options.N, false, + vis_params.c3_curr_ee_color); + builder.Connect(trajectory_sub_actor_curr->get_output_port(), + end_effector_pose_drawer_curr->get_input_port_trajectory()); + + auto dynamically_feasible_object_pose_drawer_curr = + builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.object_vis_model), + "object_position_target", "object_orientation_target", + "plans/dynamically_feasible_curr_plan", + sampling_c3_options.N + 1, true, vis_params.df_curr_object_color); + builder.Connect( + dynamically_feasible_trajectory_sub_object_curr->get_output_port(), + dynamically_feasible_object_pose_drawer_curr + ->get_input_port_trajectory()); + + auto dynamically_feasible_actor_pose_drawer_curr_actor = + builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.ee_vis_model), + "ee_position_target", "end_effector_orientation_target", + "plans/dynamically_feasible_curr_plan", + sampling_c3_options.N + 1, false, vis_params.df_curr_ee_color); + builder.Connect( + dynamically_feasible_trajectory_sub_actor_curr->get_output_port(), + dynamically_feasible_actor_pose_drawer_curr_actor + ->get_input_port_trajectory()); + } + + if (vis_params.visualize_c3_plan_best) { + auto object_pose_drawer_best = builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.object_vis_model), + "object_position_target", "object_orientation_target", + "plans/best_planned", sampling_c3_options.N, true, + vis_params.c3_best_object_color); + builder.Connect(trajectory_sub_object_best->get_output_port(), + object_pose_drawer_best->get_input_port_trajectory()); + + auto end_effector_pose_drawer_best = + builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.ee_vis_model), + "end_effector_position_target", "end_effector_orientation_target", + "plans/best_planned", sampling_c3_options.N, false, + vis_params.c3_best_ee_color); + builder.Connect(trajectory_sub_actor_best->get_output_port(), + end_effector_pose_drawer_best->get_input_port_trajectory()); + + auto dynamically_feasible_object_pose_drawer_best = + builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.object_vis_model), + "object_position_target", "object_orientation_target", + "plans/dynamically_feasible_best_plan", sampling_c3_options.N + 1, + true, vis_params.df_best_object_color); + builder.Connect( + dynamically_feasible_trajectory_sub_object_best->get_output_port(), + dynamically_feasible_object_pose_drawer_best + ->get_input_port_trajectory()); + + auto dynamically_feasible_actor_pose_drawer_best_actor = + builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.ee_vis_model), + "ee_position_target", "end_effector_orientation_target", + "plans/dynamically_feasible_best_plan", + sampling_c3_options.N + 1, false, vis_params.df_best_ee_color); + builder.Connect( + dynamically_feasible_trajectory_sub_actor_best->get_output_port(), + dynamically_feasible_actor_pose_drawer_best_actor + ->get_input_port_trajectory()); + } + + if (vis_params.visualize_sample_locations) { + int from_buffer = 0; + if (sampling_params.consider_best_buffer_sample_when_leaving_c3) { + from_buffer = 1; + } + auto sample_locations_drawer = builder.AddSystem( + meshcat, + FindResourceOrThrow(vis_params.ee_vis_model), + "sample_locations", "unused_orientation_name", "samples", + std::max(sampling_params.num_additional_samples_c3 + from_buffer, + sampling_params.num_additional_samples_repos + 1) + + 1, + false, vis_params.sample_color); + + builder.Connect(sample_location_sub->get_output_port(), + sample_locations_drawer->get_input_port_trajectory()); + } + + if (vis_params.visualize_sample_buffer) { + auto sample_buffer_to_point_cloud_converter = + builder.AddSystem(); + auto sample_buffer_point_cloud_visualizer = + builder.AddSystem(meshcat, + "sample_buffer"); + sample_buffer_point_cloud_visualizer->set_point_size(0.02); + + builder.Connect(sample_buffer_sub->get_output_port(), + sample_buffer_to_point_cloud_converter + ->get_input_port_lcmt_sample_buffer()); + builder.Connect(sample_buffer_to_point_cloud_converter + ->get_output_port_sample_buffer_point_cloud(), + sample_buffer_point_cloud_visualizer->cloud_input_port()); + builder.Connect(sample_costs_sub->get_output_port(), + sample_buffer_to_point_cloud_converter + ->get_input_port_new_sample_costs()); + } + + if (vis_params.visualize_c3_state) { + auto c3_target_drawer = + builder.AddSystem(meshcat, true, true); + builder.Connect(c3_state_actual_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_actual()); + builder.Connect(c3_state_target_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_target()); + builder.Connect(c3_final_state_target_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_final_target()); + } + + if (vis_params.visualize_c3_forces_curr) { + auto end_effector_force_drawer_curr = + builder.AddSystem( + meshcat, "end_effector_position_target", + "end_effector_force_target", "lcs_force_trajectory_curr", "curr_"); + builder.Connect( + trajectory_sub_actor_curr->get_output_port(), + end_effector_force_drawer_curr->get_input_port_actor_trajectory()); + builder.Connect( + trajectory_sub_force_curr->get_output_port(), + end_effector_force_drawer_curr->get_input_port_force_trajectory()); + builder.Connect( + robot_time_passthrough->get_output_port(), + end_effector_force_drawer_curr->get_input_port_robot_time()); + } + + if (vis_params.visualize_c3_forces_best) { + auto end_effector_force_drawer_best = + builder.AddSystem( + meshcat, "end_effector_position_target", + "end_effector_force_target", "lcs_force_trajectory_best", "best_"); + builder.Connect( + trajectory_sub_actor_best->get_output_port(), + end_effector_force_drawer_best->get_input_port_actor_trajectory()); + builder.Connect( + trajectory_sub_force_best->get_output_port(), + end_effector_force_drawer_best->get_input_port_force_trajectory()); + builder.Connect( + robot_time_passthrough->get_output_port(), + end_effector_force_drawer_best->get_input_port_robot_time()); + } + + if (vis_params.visualize_is_c3_mode) { + auto c3_mode_visualizer = builder.AddSystem(); + builder.Connect(is_c3_mode_sub->get_output_port(), + c3_mode_visualizer->get_input_port_is_c3_mode()); + builder.Connect(reduced_order_model_receiver->get_output_port(), + c3_mode_visualizer->get_input_port_curr_lcs_state()); + auto is_c3_mode_drawer = builder.AddSystem( + meshcat, FindResourceOrThrow(vis_params.ee_vis_model), + "c3_mode_visualization", "end_effector_orientation_target", "c3_mode", + 1, false, vis_params.is_c3_mode_color); + builder.Connect( + c3_mode_visualizer->get_output_port_c3_mode_visualization_traj(), + is_c3_mode_drawer->get_input_port_trajectory()); + } + + builder.Connect(franka_passthrough->get_output_port(), + mux->get_input_port(0)); + builder.Connect(tray_passthrough->get_output_port(), mux->get_input_port(1)); + builder.Connect(*mux, *to_pose); + builder.Connect( + to_pose->get_output_port(), + scene_graph.get_source_pose_port(plant.get_source_id().value())); + builder.Connect(*franka_state_receiver, *franka_passthrough); + builder.Connect(*franka_state_receiver, *robot_time_passthrough); + builder.Connect(*object_state_receiver, *tray_passthrough); + builder.Connect(*franka_state_sub, *franka_state_receiver); + builder.Connect(*object_state_sub, *object_state_receiver); + + auto visualizer = &drake::geometry::MeshcatVisualizer::AddToBuilder( + &builder, scene_graph, meshcat, std::move(params)); + + auto diagram = builder.Build(); + diagram->set_name(("sampling_c3_visualizer_" + FLAGS_demo_name)); + DrawAndSaveDiagramGraph(*diagram); + auto context = diagram->CreateDefaultContext(); + + auto& franka_state_sub_context = + diagram->GetMutableSubsystemContext(*franka_state_sub, context.get()); + auto& object_state_sub_context = + diagram->GetMutableSubsystemContext(*object_state_sub, context.get()); + franka_state_receiver->InitializeSubscriberPositions( + plant, franka_state_sub_context); + object_state_receiver->InitializeSubscriberPositions( + plant, object_state_sub_context); + + /// Use the simulator to drive at a fixed rate + /// If set_publish_every_time_step is true, this publishes twice + auto simulator = + std::make_unique>(*diagram, std::move(context)); + simulator->set_publish_every_time_step(false); + simulator->set_publish_at_initialization(false); + simulator->set_target_realtime_rate(1.0); + simulator->Initialize(); + + drake::log()->info("visualizer started"); + + simulator->AdvanceTo(std::numeric_limits::infinity()); + + return 0; +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { + return dairlib::do_main(argc, argv); +} diff --git a/examples/sampling_c3/generate_samples.cc b/examples/sampling_c3/generate_samples.cc new file mode 100644 index 0000000000..aef8173625 --- /dev/null +++ b/examples/sampling_c3/generate_samples.cc @@ -0,0 +1,485 @@ +#include "generate_samples.h" +#include "multibody/geom_geom_collider.h" + +#include +#include + +using drake::AutoDiffVecXd; +using drake::AutoDiffXd; +using drake::SortedPair; +using drake::geometry::FrameId; +using drake::geometry::GeometryId; +using drake::geometry::Shape; +using drake::geometry::SignedDistancePair; +using drake::geometry::Sphere; +using drake::math::RigidTransform; +using drake::multibody::Body; +using Eigen::Vector3d; +using Eigen::VectorXd; + +namespace dairlib { +namespace systems { + +// Public call for generating samples. +std::vector GenerateSampleStates( + const int& n_q, const int& n_v, const int& n_u, + const Eigen::VectorXd& x_lcs, const bool& is_doing_c3, + const SamplingParams& sampling_params, + const SamplingC3Options& sampling_c3_options, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms) { + // Determine number of samples based on mode. + int num_samples; + if (is_doing_c3) { + num_samples = sampling_params.num_additional_samples_c3; + } else { + num_samples = sampling_params.num_additional_samples_repos; + } + std::vector candidate_states(num_samples); + // Initialize all candidate states to be the same as the current LCS state. + // NOTE: A naive step might be to set the sample EE velocities to zero, but + // in practice this can cause undesired cost differences between the current + // location and the candidate states. Keeping the current EE velocity the + // same across all samples is an equalizer. + for (int i = 0; i < num_samples; i++) { + candidate_states[i] = x_lcs; + } + + // Split function calls based on sampling strategy. + SamplingStrategy strategy = sampling_params.sampling_strategy; + if (strategy == SamplingStrategy::kRadiallySymmetric) { + for (int i = 0; i < num_samples; i++) { + candidate_states[i].head(3) = RadiallySymmetricSampling( + n_q, n_v, x_lcs, num_samples, i, sampling_params.sampling_radius, + sampling_params.sampling_height); + if (sampling_params.filter_samples_for_safety && + !IsSampleInWorkspace(candidate_states[i], sampling_c3_options)) { + throw std::runtime_error( + "Error: Radially symmetric sample location is outside workspace."); + } + } + } else if (strategy == SamplingStrategy::kRandomOnCircle) { + for (int i = 0; i < num_samples; i++) { + do { + candidate_states[i].head(3) = RandomOnCircleSampling( + n_q, n_v, x_lcs, sampling_params.sampling_radius, + sampling_params.sampling_height); + } while (sampling_params.filter_samples_for_safety && + !IsSampleInWorkspace(candidate_states[i], sampling_c3_options)); + } + } else if (strategy == SamplingStrategy::kRandomOnSphere) { + for (int i = 0; i < num_samples; i++) { + do { + candidate_states[i].head(3) = RandomOnSphereSampling( + n_q, n_v, x_lcs, sampling_params.sampling_radius, + sampling_params.min_angle_from_vertical, + sampling_params.max_angle_from_vertical); + } while (sampling_params.filter_samples_for_safety && + !IsSampleInWorkspace(candidate_states[i], sampling_c3_options)); + } + } else if (strategy == SamplingStrategy::kFixed) { + if (num_samples > sampling_params.fixed_sample_locations.size()) { + throw std::runtime_error( + "Error: More fixed samples requested than provided."); + } + for (int i = 0; i < num_samples; i++) { + if (sampling_params.fixed_sample_locations.cols() != 3) { + throw std::runtime_error("Error: Fixed sample locations must be 3D."); + } + candidate_states[i].head(3) = FixedSample( + sampling_params.fixed_sample_locations.row(i)); + if (sampling_params.filter_samples_for_safety && + !IsSampleInWorkspace(candidate_states[i], sampling_c3_options)) { + throw std::runtime_error( + "Error: Fixed sample location is outside workspace."); + } + } + } else if (strategy == SamplingStrategy::kRandomOnPerimeter) { + for (int i = 0; i < num_samples; i++) { + do { + candidate_states[i].head(3) = PerimeterSampling( + n_q, n_v, n_u, x_lcs, plant, context, plant_ad, context_ad, + contact_geoms, sampling_params, sampling_c3_options); + } while (sampling_params.filter_samples_for_safety && + !IsSampleInWorkspace(candidate_states[i], sampling_c3_options)); + } + } else if (strategy == SamplingStrategy::kRandomOnShell) { + for (int i = 0; i < num_samples; i++) { + do { + candidate_states[i].head(3) = ShellSampling( + n_q, n_v, n_u, x_lcs, plant, context, plant_ad, context_ad, + contact_geoms, sampling_params, sampling_c3_options); + } while (sampling_params.filter_samples_for_safety && + !IsSampleInWorkspace(candidate_states[i], sampling_c3_options)); + } + } else { + throw std::runtime_error("Error: Sampling strategy not recognized."); + } + return candidate_states; +} + +// kRadiallySymmetric: Equally spaced on perimeter of circle of fixed radius +// and height. This generates angle offsets from world frame. +Eigen::Vector3d RadiallySymmetricSampling( + const int& n_q, const int& n_v, const Eigen::VectorXd& x_lcs, + const int& num_samples, const int& i, const double& sampling_radius, + const double& sampling_height) { + // Center the sampling circle on the current object location. + Vector3d object_xyz = x_lcs.segment(n_q - 3, 3); + double theta = (360 / static_cast(num_samples)) * (M_PI / 180); + + // Update the hypothetical state's EE location. + Eigen::Vector3d sample = Vector3d::Zero(); + sample[0] = object_xyz[0] + sampling_radius * cos((double)i * theta); + sample[1] = object_xyz[1] + sampling_radius * sin((double)i * theta); + sample[2] = sampling_height; + return sample; +} + +// kRandomOnCircle: Random on perimeter of circle of fixed radius and height. +Eigen::Vector3d RandomOnCircleSampling( + const int& n_q, const int& n_v, const Eigen::VectorXd& x_lcs, + const double& sampling_radius, const double& sampling_height) { + // Center the sampling circle on the current object location. + Vector3d object_xyz = x_lcs.segment(n_q - 3, 3); + + // Generate a random theta. + double theta = RandomUniform(0, 2*M_PI); + + // Update the hypothetical state's EE location. + Eigen::Vector3d sample = Vector3d::Zero(); + sample[0] = object_xyz[0] + sampling_radius * cos(theta); + sample[1] = object_xyz[1] + sampling_radius * sin(theta); + sample[2] = sampling_height; + return sample; +} + +// kRandomOnSphere: Random on surface of sphere of fixed radius within +// elevation angles. +Eigen::Vector3d RandomOnSphereSampling( + const int& n_q, const int& n_v, const Eigen::VectorXd& x_lcs, + const double& sampling_radius, const double& min_angle_from_vertical, + const double& max_angle_from_vertical) { + // Center the sampling circle on the current object location. + Vector3d object_xyz = x_lcs.segment(n_q - 3, 3); + + // Generate a random theta about and elevation angle from the vertical axis. + double theta = RandomUniform(0, 2*M_PI); + double elevation_theta = RandomUniform(min_angle_from_vertical, + max_angle_from_vertical); + + // Update the hypothetical state's EE location. + Eigen::Vector3d sample = Vector3d::Zero(); + sample[0] = object_xyz[0] + sampling_radius*cos(theta)*sin(elevation_theta); + sample[1] = object_xyz[1] + sampling_radius*sin(theta)*sin(elevation_theta); + sample[2] = object_xyz[2] + sampling_radius*cos(elevation_theta); + return sample; +} + +// kFixed +Eigen::Vector3d FixedSample(const Eigen::Vector3d& fixed_sample_location) { + return fixed_sample_location; +} + +// kRandomOnPerimeter: Random on (roughly) inflated perimeter of 2D slice of +// object on its z=0 body plane, (roughly) projected vertically to pre-specified +// sample height. The precise steps are: +// 1) Sample points in the body frame's (x, y, z=0) plane. These may not be +// flat in the world frame. +// 2) Project the sampled points vertically to a fixed world height. +// 3) Reject any that are not in collision with the object. +// 4) Project the colliding samples outward to a fixed clearance distance. +// These may not be flat in the world frame (especially for curved objects). +// 5) Reject any that are too close to the object (i.e. if the witness point on +// the object changes during the projection such that it was insufficient). +// 6) Reject any that are too far away from the desired sampling height. +// +// This procedure works best if: +// 1) The body z-axis is aligned (or nearly aligned) with the world z-axis. +// 2) The body origin lies roughly at the mid-height of the object, so a +// vertical projection results in an even perimeter around the geometry. +// 3) The side walls of the object are vertical. +// +// TODO: implement a more general perimeter strategy without requiring the +// above assumptions. +Eigen::Vector3d PerimeterSampling( + const int& n_q, const int& n_v, const int& n_u, + const Eigen::VectorXd& x_lcs, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + const SamplingParams& sampling_params, + const SamplingC3Options sampling_c3_options) +{ + Eigen::VectorXd candidate_state = VectorXd::Zero(n_q + n_v); + int min_distance_index = -1; + + // Try projecting colliding samples until one is near desired sampling height + // and maintains the desired clearance. + while (true) { + do { + // These are in body frame. + double x_sample = RandomUniform(sampling_params.grid_x_limits[0], + sampling_params.grid_x_limits[1]); + double y_sample = RandomUniform(sampling_params.grid_y_limits[0], + sampling_params.grid_y_limits[1]); + // WARNING: This assumes 1) the body's z-axis is roughly aligned with the + // world z-axis, and 2) the body origin is roughly at the mid-height of + // the object. + double z_sample = 0; + + // Convert to world frame using the current object state. + Eigen::VectorXd x_lcs_world = x_lcs; + Eigen::Quaterniond quat_object(x_lcs(3), x_lcs(4), x_lcs(5), x_lcs(6)); + Eigen::Vector3d object_position = x_lcs.segment(7, 3); + candidate_state = x_lcs; + candidate_state.head(3) = + quat_object * Eigen::Vector3d(x_sample, y_sample, z_sample) + + object_position; + + // Project samples to specified sampling height in world frame. + candidate_state[2] = sampling_params.sampling_height; + } while (!IsSampleWithinDistanceOfSurface( + n_q, n_v, n_u, 0.0, false, candidate_state, plant, context, plant_ad, + context_ad, contact_geoms, sampling_c3_options, min_distance_index)); + + // Project the sample past the surface of the object with clearance. + Eigen::VectorXd projected_state = ProjectSampleOutsideObject( + candidate_state, min_distance_index, sampling_params, plant, *context, + contact_geoms); + + // Check the desired clearance is satisfied; otherwise try again. + UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, + projected_state); + if (IsSampleWithinDistanceOfSurface( + n_q, n_v, n_u, sampling_params.sample_projection_clearance, true, + projected_state, plant, context, plant_ad, context_ad, contact_geoms, + sampling_c3_options, min_distance_index)) { + continue; + } + // Check the projection is within a small epsilon of the sampling height; + // otherwise try again. + // WARNING: This assumes the walls of the object are roughly vertical. + double epsilon = 0.001; + if (projected_state[2] < sampling_params.sampling_height - epsilon || + projected_state[2] > sampling_params.sampling_height + epsilon) { + continue; + } + + // Undo the update context. + UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, x_lcs); + Eigen::Vector3d sample = projected_state.head(3); + return sample; + } +} + + +// kRandomOnShell: Random on inflated 3D shell surrounding the object. Makes a +// light assumption that the body origin is roughly centered on its geometry. +// +// TODO: this strategy is largely untested. +Eigen::Vector3d ShellSampling( + const int& n_q, const int& n_v, const int& n_u, + const Eigen::VectorXd& x_lcs, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + const SamplingParams& sampling_params, + const SamplingC3Options sampling_c3_options) +{ + Eigen::VectorXd candidate_state = VectorXd::Zero(n_q + n_v); + int min_distance_index = -1; + + // Try projecting colliding samples until one is above minimum EE height and + // maintains the desired clearance. + while (true) { + do { + // Center the sampling sphere on the current object location. + Vector3d object_xyz = x_lcs.segment(7, 3); + double x_samplec = object_xyz[0]; + double y_samplec = object_xyz[1]; + double z_samplec = object_xyz[2]; + + // Generate a random theta about and elevation angle from vertical axis. + double theta = RandomUniform(0, 2*M_PI); + double elevation_theta = RandomUniform( + sampling_params.min_angle_from_vertical, + sampling_params.max_angle_from_vertical); + + // Generate random sampling radius. + double sampling_radius = RandomUniform( + sampling_params.min_sampling_radius, + sampling_params.max_sampling_radius); + + // Update the hypothetical state's end effector location to the tested + // sample location. + candidate_state = x_lcs; + candidate_state[0] = + x_samplec + sampling_radius * cos(theta) * sin(elevation_theta); + candidate_state[1] = + y_samplec + sampling_radius * sin(theta) * sin(elevation_theta); + candidate_state[2] = z_samplec + sampling_radius * cos(elevation_theta); + } while (!IsSampleWithinDistanceOfSurface( + n_q, n_v, n_u, 0.0, false, candidate_state, plant, context, plant_ad, + context_ad, contact_geoms, sampling_c3_options, min_distance_index)); + + // Project the sample past the surface of the object with clearance. + Eigen::VectorXd projected_state = ProjectSampleOutsideObject( + candidate_state, min_distance_index, sampling_params, plant, *context, + contact_geoms); + + // Check the desired clearance is satisfied; otherwise try again. + UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, + projected_state); + if (IsSampleWithinDistanceOfSurface( + n_q, n_v, n_u, sampling_params.sample_projection_clearance, true, + projected_state, plant, context, plant_ad, context_ad, contact_geoms, + sampling_c3_options, min_distance_index)) { + continue; + } + // Check the projection is above the minimum EE height; otherwise try again. + if (projected_state[2] < sampling_c3_options.workspace_limits[2][3]) { + continue; + } + + // Undo the update context. + UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, x_lcs); + Eigen::Vector3d sample = projected_state.head(3); + return sample; + } +} + +bool IsSampleInWorkspace(const Eigen::VectorXd& candidate_state, + const SamplingC3Options& sampling_c3_options) { + double candidate_radius = + sqrt(std::pow(candidate_state[0], 2) + std::pow(candidate_state[1], 2)); + if (candidate_state[0] < sampling_c3_options.workspace_limits[0][3] // x min + || candidate_state[0] > sampling_c3_options.workspace_limits[0][4] // x max + || candidate_state[1] < sampling_c3_options.workspace_limits[1][3] // y min + || candidate_state[1] > sampling_c3_options.workspace_limits[1][4] // y max + || candidate_state[2] < sampling_c3_options.workspace_limits[2][3] // z min + || candidate_state[2] > sampling_c3_options.workspace_limits[2][4] // z max + || candidate_radius > sampling_c3_options.robot_radius_limits[1] // r min + || candidate_radius < sampling_c3_options.robot_radius_limits[0]) // r max + {return false;} + return true; +} + +double GetEERadiusFromPlant( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const std::vector< + std::vector>>& + contact_geoms) +{ + const auto& query_port = plant.get_geometry_query_input_port(); + const auto& query_object = + query_port.template Eval>(context); + const auto& inspector = query_object.inspector(); + + // Locate the EE and obtain its radius. + GeometryId ee_geom_id = contact_geoms.at(0).at(0).first(); + const drake::geometry::Shape& shape = inspector.GetShape(ee_geom_id); + const auto* sphere = dynamic_cast(&shape); + if (sphere) { + return sphere->radius(); + } + throw std::runtime_error("End effector geometry is not a sphere!"); +} + +bool IsSampleWithinDistanceOfSurface( + const int& n_q, const int& n_v, const int& n_u, + const double& clearance_distance, + const bool& factor_in_ee_radius, + const Eigen::VectorXd& candidate_state, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + SamplingC3Options sampling_c3_options, + int& min_distance_index) +{ + // Update the context of the plant with the candidate state. + UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, + candidate_state); + + // Find the closest pair if there are multiple pairs + std::vector distances; + + for (int i = 0; i < contact_geoms.at(0).size(); i++) { + // Evaluate the distance for each pair + SortedPair pair{(contact_geoms.at(0)).at(i)}; + multibody::GeomGeomCollider collider(plant, pair); + + auto [phi_i, J_i] = collider.EvalPolytope( + *context, sampling_c3_options.num_friction_directions); + distances.push_back(phi_i); + } + + // Find the minimum distance. + auto min_distance_it = std::min_element(distances.begin(), distances.end()); + // Modify a reference to the index of the closest pair of contact geoms so + // that the projection function need not recompute the closest pair. + min_distance_index = std::distance(distances.begin(), min_distance_it); + double min_distance = *min_distance_it; + + // Factor the EE radius into the clearance distance if requested. + double ee_radius_contribution = 0.0; + if (factor_in_ee_radius) { + ee_radius_contribution = GetEERadiusFromPlant( + plant, *context, contact_geoms); + } + + // Require that min_distance be at least 1 mm within the clearance distance. + return min_distance <= clearance_distance + ee_radius_contribution - 1e-3; +} + +Eigen::VectorXd ProjectSampleOutsideObject( + Eigen::VectorXd& candidate_state, int min_distance_index, + const SamplingParams& sampling_params, + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const std::vector< + std::vector>>& + contact_geoms) { + + // Compute the witness points between the penetrating sample and the object + // surface. + multibody::GeomGeomCollider collider( + plant, contact_geoms.at(0).at(min_distance_index)); + auto [p_world_contact_a, p_world_contact_b] = collider.CalcWitnessPoints( + context); + + // Get the EE radius to factor into the projection. + double ee_radius = GetEERadiusFromPlant(plant, context, contact_geoms); + + // Find vector in direction from sample to contact point on object. + Eigen::Vector3d a_to_b = p_world_contact_b - p_world_contact_a; + Eigen::Vector3d a_to_b_normalized = a_to_b.normalized(); + // Add clearance to point b in the same direction. + Eigen::Vector3d p_world_contact_b_clearance = + p_world_contact_b + + (ee_radius + sampling_params.sample_projection_clearance) * + a_to_b_normalized; + candidate_state.head(3) = p_world_contact_b_clearance; + return candidate_state; +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/generate_samples.h b/examples/sampling_c3/generate_samples.h new file mode 100644 index 0000000000..75c2015ff6 --- /dev/null +++ b/examples/sampling_c3/generate_samples.h @@ -0,0 +1,159 @@ +#include + +#include +#include +#include + +#include "common/math_utils.h" +#include "common/update_context.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_options.h" +#include "examples/sampling_c3/parameter_headers/sampling_params.h" +#include "multibody/geom_geom_collider.h" +#include "multibody/multibody_utils.h" +#include "solvers/c3_options.h" + +using Eigen::Vector3d; +using Eigen::VectorXd; + +namespace dairlib { +namespace systems { + + +/// Public function +std::vector GenerateSampleStates( + const int& n_q, + const int& n_v, + const int& n_u, + const Eigen::VectorXd& x_lcs, + const bool& is_doing_c3, + const SamplingParams& sampling_params, + const SamplingC3Options& sampling_c3_options, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms +); + +/// Individual sampling strategies returning 3D EE position +Eigen::Vector3d RadiallySymmetricSampling( + const int& n_q, + const int& n_v, + const Eigen::VectorXd& x_lcs, + const int& num_samples, + const int& i, + const double& sampling_radius, + const double& sampling_height +); + +Eigen::Vector3d RandomOnCircleSampling( + const int& n_q, + const int& n_v, + const Eigen::VectorXd& x_lcs, + const double& sampling_radius, + const double& sampling_height +); + +Eigen::Vector3d RandomOnSphereSampling( + const int& n_q, + const int& n_v, + const Eigen::VectorXd& x_lcs, + const double& sampling_radius, + const double& min_angle_from_vertical, + const double& max_angle_from_vertical +); + +Eigen::Vector3d FixedSample( + const Eigen::Vector3d& fixed_sample_location +); + +Eigen::Vector3d PerimeterSampling( + const int& n_q, + const int& n_v, + const int& n_u, + const Eigen::VectorXd& x_lcs, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + const SamplingParams& sampling_params, + const SamplingC3Options sampling_c3_options +); + +Eigen::Vector3d ShellSampling( + const int& n_q, + const int& n_v, + const int& n_u, + const Eigen::VectorXd& x_lcs, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + const SamplingParams& sampling_params, + const SamplingC3Options sampling_c3_options +); + + +/// Helper functions + +/// Whether the candidate state's EE location is within the robot workspace. +bool IsSampleInWorkspace( + const Eigen::VectorXd& candidate_state, + const SamplingC3Options& sampling_c3_options +); + +/// Find and return the end effector radius from the plant. +/// WARNING: assumes EE-object pairs are first in contact_geoms. +double GetEERadiusFromPlant( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const std::vector< + std::vector>>& + contact_geoms +); + +/// Whether the candidate state's EE location is within a clearance distance of +/// the surface of the object. Can factor in the EE radius if a real clearance +/// distance between the EE and the object is desired; otherwise this is the +/// distance from the center of the EE to the surface of the object. +bool IsSampleWithinDistanceOfSurface( + const int& n_q, + const int& n_v, + const int& n_u, + const double& clearance_distance, + const bool& factor_in_ee_radius, + const Eigen::VectorXd& candidate_state, + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + SamplingC3Options sampling_c3_options, + int& min_distance_index +); + +/// Project an EE candidate location outside the object such that the clearance +/// distance in the sampling parameters is satisfied. +Eigen::VectorXd ProjectSampleOutsideObject( + Eigen::VectorXd& candidate_state, + int min_distance_index, + const SamplingParams& sampling_params, + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const std::vector< + std::vector>>& + contact_geoms +); + +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/examples/sampling_c3/goal_generator.cc b/examples/sampling_c3/goal_generator.cc new file mode 100644 index 0000000000..3bd1b51295 --- /dev/null +++ b/examples/sampling_c3/goal_generator.cc @@ -0,0 +1,300 @@ +#include "goal_generator.h" + +#include +#include + +#include "examples/sampling_c3/parameter_headers/goal_params.h" +#include "lcm/lcm_trajectory.h" + +using Eigen::VectorXd; + +namespace dairlib { +namespace systems { + +SamplingC3GoalGenerator::SamplingC3GoalGenerator( + const drake::multibody::MultibodyPlant& object_plant, + const SamplingC3GoalParams& goal_params, + const std::vector& nominal_orientations) : + goal_params_(goal_params), + nominal_orientations_(nominal_orientations) { + // INPUT PORTS + radio_port_ = this->DeclareAbstractInputPort( + "lcmt_radio_out", + drake::Value{}) + .get_index(); + object_state_port_ = this->DeclareVectorInputPort( + "x_object", + StateVector(object_plant.num_positions(), + object_plant.num_velocities())) + .get_index(); + + // OUTPUT PORTS + end_effector_target_port_ = this->DeclareVectorOutputPort( + "end_effector_target", + BasicVector(3), + &SamplingC3GoalGenerator::CalcEndEffectorTarget) + .get_index(); + object_target_port_ = this->DeclareVectorOutputPort( + "object_target", + BasicVector(7), + &SamplingC3GoalGenerator::CalcObjectTarget) + .get_index(); + object_velocity_target_port_ = this->DeclareVectorOutputPort( + "object_velocity_target", + BasicVector(6), + &SamplingC3GoalGenerator::CalcObjectVelocityTarget) + .get_index(); + object_final_target_port_ = this->DeclareVectorOutputPort( + "object_final_target", + BasicVector(7), + &SamplingC3GoalGenerator::OutputObjectFinalTarget) + .get_index(); + target_gen_info_port_ = this->DeclareAbstractOutputPort( + "target_generator_info", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3GoalGenerator::OutputGoalGeneratorInfo) + .get_index(); + + // Start with the fixed goal from the goal params. + target_final_object_position_ = goal_params_.fixed_target_position; + target_final_object_orientation_ = goal_params_.fixed_target_orientation; +} + +// Fixes the EE target to be a fixed offset above the object. +void SamplingC3GoalGenerator::CalcEndEffectorTarget( + const drake::systems::Context& context, + drake::systems::BasicVector* target) const { + const StateVector* object_state = + (StateVector*)this->EvalVectorInput(context, object_state_port_); + + VectorXd end_effector_position = object_state->GetPositions().tail(3); + end_effector_position[2] += goal_params_.ee_target_z_offset_above_object; + target->SetFromVector(end_effector_position); +} + +void SamplingC3GoalGenerator::CalcObjectTarget( + const drake::systems::Context& context, + BasicVector* target) const { + const StateVector* object_state = + (StateVector*)this->EvalVectorInput(context, object_state_port_); + Eigen::Vector3d obj_curr_position = object_state->GetPositions().tail(3); + VectorXd obj_curr_quat = object_state->GetPositions().head(4); + Eigen::Quaterniond curr_quat(obj_curr_quat(0), obj_curr_quat(1), + obj_curr_quat(2), obj_curr_quat(3)); + + // First, ignore lookahead and use the final goal. + VectorXd target_obj_position = target_final_object_position_; + Eigen::Quaterniond target_obj_orientation( + target_final_object_orientation_[0], target_final_object_orientation_[1], + target_final_object_orientation_[2], target_final_object_orientation_[3]); + + // Check if success has been met. Update goal if necessary. + double object_position_error = + (obj_curr_position - target_final_object_position_).norm(); + Eigen::AngleAxis angle_axis_diff(target_obj_orientation * + curr_quat.inverse()); + double object_angular_error = angle_axis_diff.angle(); + + if ((object_position_error < goal_params_.position_success_threshold) && + (object_angular_error < goal_params_.orientation_success_threshold)) { + std::cout << "\nMet pose goal!\n" << std::endl; + OnGoalReached(); + } + + // Apply lookahead. + std::tie(target_obj_orientation, target_obj_position) = + GenerateLineTrajectoryWithLookahead(curr_quat, obj_curr_position); + VectorXd target_obj_state = VectorXd::Zero(7); + target_obj_state << target_obj_orientation.w(), target_obj_orientation.x(), + target_obj_orientation.y(), target_obj_orientation.z(), target_obj_position; + target->SetFromVector(target_obj_state); +} + +// Command zero linear velocity, and command angular velocity that scales with +// orientation error, scaled by angle_err_to_vel_factor_. +void SamplingC3GoalGenerator::CalcObjectVelocityTarget( + const drake::systems::Context& context, + BasicVector* target) const { + const StateVector* object_state = + (StateVector*)this->EvalVectorInput(context, object_state_port_); + // Get the final and current orientation. + Eigen::Quaterniond y_quat_des( + target_final_object_orientation_[0], target_final_object_orientation_[1], + target_final_object_orientation_[2], target_final_object_orientation_[3]); + const VectorX& q = object_state->GetPositions().head(4); + Eigen::VectorXd normalized_q = q / q.norm(); + Eigen::Quaterniond y_quat(normalized_q(0), normalized_q(1), + normalized_q(2), normalized_q(3)); + + // Compute the orientation error, apply the lookahead angle, and convert the + // axis-angle error to an angular velocity command. + Eigen::AngleAxis angle_axis_diff(y_quat_des * y_quat.inverse()); + auto orientation_trajectory = + PiecewiseQuaternionSlerp({0, 1}, {y_quat, y_quat_des}); + double lookahead_fraction = + std::min(goal_params_.lookahead_angle / angle_axis_diff.angle(), 1.0); + Eigen::MatrixXd y_quat_lookahead = + orientation_trajectory.value(lookahead_fraction); + Eigen::Quaterniond y_quat_lookahead_quat( + y_quat_lookahead(0), y_quat_lookahead(1), + y_quat_lookahead(2), y_quat_lookahead(3)); + + Eigen::AngleAxis angle_axis_diff_to_lookahead(y_quat_lookahead_quat * + y_quat.inverse()); + VectorXd angle_error = angle_axis_diff_to_lookahead.angle() * + angle_axis_diff_to_lookahead.axis(); + angle_error *= goal_params_.angle_err_to_vel_factor; + + VectorXd target_obj_velocity = VectorXd::Zero(6); + target_obj_velocity << angle_error, VectorXd::Zero(3); + target->SetFromVector(target_obj_velocity); +} + +void SamplingC3GoalGenerator::OutputObjectFinalTarget( + const drake::systems::Context& context, + BasicVector* target) const { + VectorXd target_final_obj_state = VectorXd::Zero(7); + target_final_obj_state << target_final_object_orientation_, + target_final_object_position_; + target->SetFromVector(target_final_obj_state); +} + +// Randomly generates final position within the specified goal limits in x/y/r. +void SamplingC3GoalGenerator::SetRandomizedTargetFinalObjectPosition() const { + double x, y = 0; + while ((sqrt(x * x + y * y) > goal_params_.random_goal_radius_limits[1]) || + (sqrt(x * x + y * y) < goal_params_.random_goal_radius_limits[0])) { + double x = RandomUniform(goal_params_.random_goal_x_limits[0], + goal_params_.random_goal_x_limits[1]); + double y = RandomUniform(goal_params_.random_goal_y_limits[0], + goal_params_.random_goal_y_limits[1]); + } + + target_final_object_position_ << x, y, goal_params_.resting_object_height; +} + +// Randomly generates final orientation from the set of valid orientations plus +// an imposed random yaw. If no topples are required, the yaw is at least 90 +// degrees away from the current orientation. +void SamplingC3GoalGenerator::SetRandomizedTargetFinalObjectOrientation() const { + const auto& valid_orientations = GetNominalOrientations(); + std::uniform_int_distribution dis(0, valid_orientations.size() - 1); + std::mt19937 rng{std::random_device{}()}; + int random_index = dis(rng); + Eigen::Quaterniond quat_nominal = valid_orientations.at(random_index); + + // Add random yaw in world frame. Ensure at least 90 degrees away if no + // topple is required. + double min_yaw = 0; + double max_yaw = 2 * M_PI; + if (random_index == orientation_index_) { + min_yaw = M_PI / 2; + max_yaw = 3 * M_PI / 2; + quat_nominal = Eigen::Quaterniond( + target_final_object_orientation_[0], target_final_object_orientation_[1], + target_final_object_orientation_[2], target_final_object_orientation_[3]); + } + double yaw = RandomUniform(min_yaw, max_yaw); + Eigen::Quaterniond quat_world_yaw( + Eigen::AngleAxisd(yaw, Eigen::Vector3d::UnitZ())); + Eigen::Quaterniond quat_final = quat_world_yaw * quat_nominal; + target_final_object_orientation_ << quat_final.w(), quat_final.x(), + quat_final.y(), quat_final.z(); + orientation_index_ = random_index; +} + +void SamplingC3GoalGenerator::CycleThroughOrientationSequence() const { + const auto& nominal_orientations = GetNominalOrientations(); + int num_nominal_orientations = nominal_orientations.size(); + Eigen::Quaterniond next_quat = + nominal_orientations.at(goal_counter_ % num_nominal_orientations); + target_final_object_orientation_ << next_quat.w(), next_quat.x(), + next_quat.y(), next_quat.z(); + orientation_index_ = goal_counter_ % num_nominal_orientations; +} + +// Outputs the orientation index for debugging. +void SamplingC3GoalGenerator::OutputGoalGeneratorInfo( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* target) const { + Eigen::MatrixXd orientation_index_data = + orientation_index_ * Eigen::MatrixXd::Ones(1, 1); + Eigen::VectorXd timestamp = context.get_time() * Eigen::VectorXd::Ones(1); + + LcmTrajectory::Trajectory orientation_index_traj; + orientation_index_traj.traj_name = "orientation_index"; + orientation_index_traj.datatypes = std::vector(1, "int"); + orientation_index_traj.datapoints = orientation_index_data; + orientation_index_traj.time_vector = timestamp.cast(); + + LcmTrajectory orientation_index_lcm_traj( + {orientation_index_traj}, {"orientation_index"}, "orientation_index", + "orientation_index", false); + + target->saved_traj = orientation_index_lcm_traj.GenerateLcmObject(); + target->utime = context.get_time() * 1e6; +} + +void SamplingC3GoalGenerator::OnGoalReached() const { + // Reset the target object orientation and position. + if (goal_params_.goal_mode == GoalMode::kRandom) { + SetRandomizedTargetFinalObjectPosition(); + SetRandomizedTargetFinalObjectOrientation(); + } else if (goal_params_.goal_mode == GoalMode::kOrientationSequence) { + // Set the next orientation in the sequence. + CycleThroughOrientationSequence(); + } else { + std::cout << "You have only specified a single goal." << std::endl; + } + goal_counter_++; +} + +std::pair +SamplingC3GoalGenerator::GenerateLineTrajectoryWithLookahead( + const Eigen::Quaterniond& quat_curr_orientation, + const Eigen::Vector3d& obj_curr_position) const { + Eigen::Vector3d target_obj_position = Eigen::Vector3d::Zero(3); + Eigen::Quaterniond target_obj_orientation = Eigen::Quaterniond::Identity(); + + // First handle position lookahead. + Eigen::Vector3d start_point = obj_curr_position; + Eigen::Vector3d end_point = target_final_object_position_; + + Eigen::Vector3d distance_vector = end_point - start_point; + Eigen::Vector3d unit_vector = distance_vector.normalized(); + double step_size = std::min(goal_params_.lookahead_step_size, + distance_vector.norm()); + target_obj_position = start_point + step_size * unit_vector; + + // Second handle orientation lookahead. + Eigen::Quaterniond y_quat_des( + target_final_object_orientation_[0], target_final_object_orientation_[1], + target_final_object_orientation_[2], target_final_object_orientation_[3]); + Eigen::AngleAxis angle_axis_diff(y_quat_des * + quat_curr_orientation.inverse()); + double angle = angle_axis_diff.angle(); + Eigen::Vector3d axis = angle_axis_diff.axis(); + + // Enforce consistency near 180 degrees. + if ((axis.dot(last_rotation_axis_) < 0) && + (M_PI - angle < goal_params_.angle_hysteresis)) { + angle = 2 * M_PI - angle; + axis = -axis; + } + last_rotation_axis_ = axis; + + // Enforce the lookahead. + angle = std::min(angle, goal_params_.lookahead_angle); + + // Apply the rotation. + Eigen::AngleAxis angle_axis_relative(angle, axis); + Eigen::Quaterniond quat_relative = Eigen::Quaterniond(angle_axis_relative); + Eigen::Quaterniond y_quat_lookahead_quat = + quat_relative * quat_curr_orientation; + target_obj_orientation = y_quat_lookahead_quat; + + return std::make_pair(target_obj_orientation, target_obj_position); +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/goal_generator.h b/examples/sampling_c3/goal_generator.h new file mode 100644 index 0000000000..ab14511a5b --- /dev/null +++ b/examples/sampling_c3/goal_generator.h @@ -0,0 +1,141 @@ +#include +#include +#include +#include + +#include "common/math_utils.h" +#include "dairlib/lcmt_radio_out.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "systems/framework/state_vector.h" +#include "examples/sampling_c3/parameter_headers/goal_params.h" + +#include "drake/common/trajectories/piecewise_quaternion.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" + +using drake::systems::BasicVector; +using drake::trajectories::PiecewiseQuaternionSlerp; + + +// Define the nominal orientations for the jack demo. +inline const Eigen::Quaterniond kQuatAllUp{ + 0.88047623921714, 0.279848142333121, -0.36470519963100, -0.115916895959295}; +inline const Eigen::Quaterniond kQuatRedDown{ + 0.88047623921714, 0.279848142333121, 0.36470519963100, 0.115916895959295}; +inline const Eigen::Quaterniond kQuatBlueUp{ + 0.70455634261098, -0.060003000646865, 0.455768038939282, -0.5406250962371}; +inline const Eigen::Quaterniond kQuatAllDown{ + 0.455768038939282, -0.54062509623716, 0.70455634261098, -0.0600030006468661}; +inline const Eigen::Quaterniond kQuatGreenUp{ + 0.364705199631001, 0.115916895959295, 0.88047623921714, 0.279848142333121}; +inline const Eigen::Quaterniond kQuatBlueDown{ + 0.0600030006468662, 0.70455634261098, 0.5406250962371, 0.45576803893928}; +inline const Eigen::Quaterniond kQuatRedUp{ + -0.27984814233312, 0.88047623921714, -0.115916895959295, 0.36470519963100}; +inline const Eigen::Quaterniond kQuatGreenDown{ + -0.82047323857028, 0.424708200277866, 0.17591989660616, 0.33985114297998}; +inline const std::vector kNominalOrientationsJack{ + kQuatAllUp, kQuatRedDown, kQuatBlueUp, kQuatAllDown, + kQuatGreenUp, kQuatBlueDown, kQuatRedUp, kQuatGreenDown}; + + +namespace dairlib { +namespace systems { + +class SamplingC3GoalGenerator : public drake::systems::LeafSystem { + public: + SamplingC3GoalGenerator( + const drake::multibody::MultibodyPlant& object_plant, + const SamplingC3GoalParams& goal_params, + const std::vector& nominal_orientations); + + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + + const drake::systems::InputPort& get_input_port_object_state() const { + return this->get_input_port(object_state_port_); + } + + const drake::systems::OutputPort& + get_output_port_end_effector_target() const { + return this->get_output_port(end_effector_target_port_); + } + + const drake::systems::OutputPort& get_output_port_object_target() + const { + return this->get_output_port(object_target_port_); + } + + const drake::systems::OutputPort& + get_output_port_object_velocity_target() const { + return this->get_output_port(object_velocity_target_port_); + } + + const drake::systems::OutputPort& + get_output_port_object_final_target() const { + return this->get_output_port(object_final_target_port_); + } + + const drake::systems::OutputPort& get_output_port_target_gen_info() + const { + return this->get_output_port(target_gen_info_port_); + } + + private: + const std::vector& GetNominalOrientations() const { + return nominal_orientations_; } + + void CalcEndEffectorTarget( + const drake::systems::Context& context, + drake::systems::BasicVector* target) const; + void CalcObjectTarget( + const drake::systems::Context& context, + drake::systems::BasicVector* target) const; + void CalcObjectVelocityTarget( + const drake::systems::Context& context, + drake::systems::BasicVector* target) const; + void OutputObjectFinalTarget( + const drake::systems::Context& context, + drake::systems::BasicVector* target) const; + void OutputGoalGeneratorInfo( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* target) const; + void SetRandomizedTargetFinalObjectPosition() const; + void SetRandomizedTargetFinalObjectOrientation() const; + void CycleThroughOrientationSequence() const; + void OnGoalReached() const; + std::pair + GenerateLineTrajectoryWithLookahead( + const Eigen::Quaterniond& quat_curr_orientation, + const Eigen::Vector3d& obj_curr_position) const; + + // Input ports + drake::systems::InputPortIndex radio_port_; + drake::systems::InputPortIndex object_state_port_; + drake::systems::OutputPortIndex end_effector_target_port_; + drake::systems::OutputPortIndex object_target_port_; + drake::systems::OutputPortIndex object_velocity_target_port_; + drake::systems::OutputPortIndex object_final_target_port_; + drake::systems::OutputPortIndex target_gen_info_port_; + + const SamplingC3GoalParams goal_params_; + const std::vector nominal_orientations_; + mutable Eigen::VectorXd target_final_object_position_; + mutable Eigen::VectorXd target_final_object_orientation_; + mutable Eigen::Vector3d last_rotation_axis_ = Eigen::Vector3d::Zero(); + mutable int goal_counter_ = 1; + mutable int orientation_index_ = -1; +}; + +class SamplingC3GoalGeneratorJacktoy : public SamplingC3GoalGenerator { + public: + SamplingC3GoalGeneratorJacktoy( + const drake::multibody::MultibodyPlant& object_plant, + const SamplingC3GoalParams& goal_params) : + SamplingC3GoalGenerator( + object_plant, goal_params, kNominalOrientationsJack) {} +}; + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/jacktoy/BUILD.bazel b/examples/sampling_c3/jacktoy/BUILD.bazel new file mode 100644 index 0000000000..c27b0f44c3 --- /dev/null +++ b/examples/sampling_c3/jacktoy/BUILD.bazel @@ -0,0 +1,88 @@ +# -*- mode: python -*- +# vi: set ft=python : + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "urdfs", + data = glob([ + "urdf/**", + ]), +) + +cc_library( + name = "parameters", + data = glob([ + "*yaml", + ]), +) + +cc_library( + name = "franka_hardware", + deps = [], +) + +cc_library( + name = "lcm_channels_jacktoy", + hdrs = [], + data = [ + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_sim_params_jacktoy", + hdrs = [], + data = [ + "parameters/sim_params.yaml", + ], + deps = [ + "//examples/sampling_c3/parameter_headers:franka_sim_params", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "sampling_c3_controller_params_jacktoy", + hdrs = [], + data = [ + "parameters/sampling_c3_controller_params.yaml", + "parameters/sampling_params.yaml", + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "goal_params_jacktoy", + hdrs = [], + data = [ + "parameters/goal_params.yaml", + ], + deps = [ + "//examples/sampling_c3/parameter_headers:goal_params", + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_drake_lcm_driver_channels_jacktoy", + hdrs = [], + data = [ + "//common/parameters:franka_drake_lcm_driver_channels", + ], + deps = [ + "//common/parameters:franka_drake_lcm_driver_channels", + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) diff --git a/examples/sampling_c3/jacktoy/franka_hardware.pmd b/examples/sampling_c3/jacktoy/franka_hardware.pmd new file mode 100644 index 0000000000..e1151e8164 --- /dev/null +++ b/examples/sampling_c3/jacktoy/franka_hardware.pmd @@ -0,0 +1,103 @@ +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/sampling_c3/franka_visualizer --is_simulation=false --demo_name=jacktoy"; + host = "sampling_c3_localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/sampling_c3/xbox_script"; + host = "sampling_c3_localhost"; + } + cmd "logger" { + exec = "python3 examples/sampling_c3/start_logging.py hw jacktoy"; + host = "sampling_c3_localhost"; + } + cmd "record_video" { + exec = "python3 record_video.py"; + host = "franka_control"; + } +} + +group "controllers (hardware)" { + cmd "sampling_c3" { + exec = "bazel-bin/examples/sampling_c3/franka_sampling_c3_controller --is_simulation=false --demo_name=jacktoy; + host = "sampling_c3_localhost"; + } + cmd "franka_osc" { + exec = "bazel-bin/examples/sampling_c3/franka_osc_controller --is_simulation=false --demo_name=jacktoy --lcm_url=udpm://239.255.76.67:7667?ttl=1; + host = "franka_control"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "sampling_c3_localhost"; + } +} + +group "drivers" { + cmd "move_to_init" { + exec = "bazel-bin/examples/sampling_c3/franka_joint_osc_controller --is_simulation=false --demo_name=jacktoy"; + host = "franka_control"; + } + cmd "franka_driver_out" { + exec = "bazel-bin/examples/sampling_c3/franka_bridge_driver_out --demo_name=jacktoy"; + host = "franka_control"; + } + cmd "franka_driver_in" { + exec = "bazel-bin/examples/sampling_c3/franka_bridge_driver_in --demo_name=jacktoy"; + host = "franka_control"; + } + cmd "torque_driver" { + exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=torque"; + host = "drake_franka_driver"; + } +} + + +script "init_experiment" { + stop cmd "sampling_c3"; + stop cmd "franka_osc"; + stop cmd "franka_driver_out"; + stop cmd "franka_driver_in"; + stop cmd "torque_driver"; + wait ms 1000; + start cmd "franka_driver_out"; + start cmd "franka_driver_in"; + start cmd "torque_driver"; + start cmd "move_to_init"; + wait ms 10000; + stop group "drivers"; +} + +script "start_experiment" { + restart cmd "xbox"; + stop cmd "franka_driver_out"; + stop cmd "franka_driver_in"; + stop cmd "torque_driver"; + stop cmd "franka_osc"; + start cmd "record_video"; + start cmd "logger"; + wait ms 1000; + start cmd "franka_driver_out"; + start cmd "franka_driver_in"; + start cmd "torque_driver"; + start cmd "move_to_init"; + wait ms 5000; + stop cmd "move_to_init"; + start cmd "franka_osc"; + start cmd "sampling_c3"; +} + +script "start_operator_commands" { + restart cmd "visualizer"; + restart cmd "xbox"; + restart cmd "lcm-spy"; +} + +script "stop_experiment" { + stop group "drivers"; + stop group "controllers (hardware)"; + stop cmd "record_video"; + stop cmd "logger"; +} diff --git a/examples/sampling_c3/jacktoy/franka_sim_jacktoy.pmd b/examples/sampling_c3/jacktoy/franka_sim_jacktoy.pmd new file mode 100644 index 0000000000..6da613d4c3 --- /dev/null +++ b/examples/sampling_c3/jacktoy/franka_sim_jacktoy.pmd @@ -0,0 +1,71 @@ +group "simulations" { + cmd "franka_sim" { + exec = "bazel-bin/examples/sampling_c3/franka_sim --demo_name=jacktoy"; + host = "localhost"; + } +} + +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/sampling_c3/franka_visualizer --is_simulation=true --demo_name=jacktoy"; + host = "localhost"; + } + cmd "drake-director" { + exec = "bazel-bin/director/drake-director"; + host = "localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/sampling_c3/xbox_script"; + host = "localhost"; + } + cmd "start_logging" { + exec = "python3 examples/sampling_c3/start_logging.py sim jacktoy"; + host = "localhost"; + } +} + +group "controllers" { + cmd "move_to_init" { + exec = "bazel-bin/examples/sampling_c3/franka_joint_osc_controller --is_simulation=true --demo_name=jacktoy"; + host = "localhost"; + } + cmd "franka_osc" { + exec = "bazel-bin/examples/sampling_c3/franka_osc_controller --is_simulation=true --demo_name=jacktoy"; + host = "localhost"; + } + cmd "sampling_c3" { + exec = "bazel-bin/examples/sampling_c3/franka_sampling_c3_controller --is_simulation=true --demo_name=jacktoy"; + host = "localhost"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "localhost"; + } +} + +script "start_experiment_no_logs"{ + stop cmd "start_logging"; + restart cmd "franka_sim"; + restart cmd "franka_osc"; + wait ms 50; + restart cmd "sampling_c3"; +} + +script "start_experiment_with_logs"{ + restart cmd "start_logging"; + restart cmd "franka_sim"; + restart cmd "franka_osc"; + wait ms 50; + restart cmd "sampling_c3"; +} + +script "end_experiment"{ + stop cmd "sampling_c3"; + stop cmd "franka_osc"; + stop cmd "franka_sim"; + wait ms 10; + stop cmd "start_logging"; +} diff --git a/examples/sampling_c3/jacktoy/parameters/goal_params.yaml b/examples/sampling_c3/jacktoy/parameters/goal_params.yaml new file mode 100644 index 0000000000..3345078eb0 --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/goal_params.yaml @@ -0,0 +1,37 @@ +# Goal mode options (defined as GoalMode enum in goal_params.h): +# 0. kRandom: randomly generate a new goal. +# 1. kOrientationSequence: keep position goal the same, and cycle through a +# sequence of orientations. +# 2. kFixedGoal: keep the same goal. +goal_mode: 0 + +### Parameters used for multiple goal modes. +# Success thresholds for position and orientation. +position_success_threshold: 0.02 +orientation_success_threshold: 0.1 # 0.1 rad = 5.7 degrees + +resting_object_height: 0.031971466 # in world frame +ee_target_z_offset_above_object: 0.06 # defines EE goal w.r.t. object position + +# Lookahead parameters to define a sub-goal for C3. +lookahead_step_size: 0.15 # meters +lookahead_angle: 2 # rad + +# Apply hysteresis on the lookahead angle so the sub-goal orientation doesn't +# flip back and forth near the 180 degree error singularity. A lower number +# means the sub-goal orientation can switch more often; a higher number means +# the sub-goal orientation is more stable but possibly less optimal. +angle_hysteresis: 0.4 + +# Factor to convert an angular error to angular velocity command (0=disabled). +angle_err_to_vel_factor: 0 + +# Initial goal (and only goal for fixed goal mode). +fixed_target_position: [0.45, 0.2, 0.031971466] +fixed_target_orientation: [ 0.8804762392171493, 0.27984814233312133, + -0.3647051996310009, -0.11591689595929514] + +# Random-specific parameters. +random_goal_x_limits: [0.42, 0.5] +random_goal_y_limits: [0.02, 0.25] +random_goal_radius_limits: [0.48, 0.5] diff --git a/examples/sampling_c3/jacktoy/parameters/progress_params.yaml b/examples/sampling_c3/jacktoy/parameters/progress_params.yaml new file mode 100644 index 0000000000..d169fd27af --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/progress_params.yaml @@ -0,0 +1,64 @@ +# Ways of computing C3 costs after solving the MPC problem (defined as +# C3CostComputationType enum in c3_options.h): +# 0. kSimLCS: Simulate the LCS dynamics from the planned +# inputs. +# 1. kUseC3Plan: Use the C3 planned trajectory and inputs. +# 2. kSimLCSReplaceC3EEPlan: Simulate the LCS dynamics from the planned +# inputs only for the object; use the planned +# EE trajectory. +# 3. kSimImpedance: Try to emulate the real cost of the system +# associated not only applying the planned +# inputs, but also tracking the planned EE +# trajectory with an impedance controller. +# 4. kSimImpedanceReplaceC3EEPlan: The same as kSimImpedance except the EE +# states are replaced with the plan from C3 +# at the end. +# 5. kSimImpedanceObjectCostOnly: The same as kSimImpedance except only the +# object terms contribute to the final cost. +cost_type: 3 +cost_type_position: 2 + +# Progress metric to use to determine if C3 is making progress, all phrased as +# improvement requirements over a number of control loops (defined as +# ProgressMetric enum in progress_params.h) +# 0. kC3Cost: C3 cost. +# 1. kConfigCost: Current object configuration cost. +# 2. kPosOrRotCost: Current position or rotation error. +# 3. kConfigCostDrop: Drop in object configuration cost (this is the same as +# kConfigCost if the required drop is 0; a more +# aggressive drop cuts C3 off earlier). +track_c3_progress_via: 3 + +# Ignore orientation errors when object is beyond this threshold from the goal. +cost_switching_threshold_distance: 0.50 + +# Penalize repositioning distance. +travel_cost_per_meter: 0 + +# Number of control loops to wait before cutting off C3 due to unproductivity. +# Used for kC3Cost, kConfigCost, kPosOrRotCost. +num_control_loops_to_wait: 14 +num_control_loops_to_wait_position: 20 + +# kConfigCostDrop parameters. +progress_enforced_cost_drop: 0.018 +progress_enforced_over_n_loops: 12 + +### Hysteresis parameters for switching between C3 and repositioning modes. +finished_reposition_cost: 1000000000 + +hyst_c3_to_repos: 300000 +hyst_c3_to_repos_position: 300000 +hyst_repos_to_c3: 200000 +hyst_repos_to_c3_position: 200000 +hyst_repos_to_repos: 60000000000000 +hyst_repos_to_repos_position: 60000000000000 + +# Relative hysteresis is in terms of a fraction of the current cost. +use_relative_hysteresis: true +hyst_c3_to_repos_frac: 0.85 +hyst_c3_to_repos_frac_position: 0.6 +hyst_repos_to_c3_frac: 0.3 +hyst_repos_to_c3_frac_position: 0.5 +hyst_repos_to_repos_frac: 0.1 +hyst_repos_to_repos_frac_position: 0.1 diff --git a/examples/sampling_c3/jacktoy/parameters/reposition_params.yaml b/examples/sampling_c3/jacktoy/parameters/reposition_params.yaml new file mode 100644 index 0000000000..682779b193 --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/reposition_params.yaml @@ -0,0 +1,32 @@ +# Repositioning trajectory type options (defined as RepositioningTrajectoryType +# enum in reposition_params.h): +# 0. kSpline: move from current to target with spline that distorts +# around the object. +# 1. kSpherical: move away from object to a radius, along the spherical +# surface to outside target, then in to target. +# 2. kCircular: (planar) move away from object to a planar radius, +# along the circle to outside target, then in to target. +# 3. kPiecewiseLinear: move up to waypoint height, over to above target, then +# down. +traj_type: 1 + +### Parameters used for multiple repositioning trajectory types. +speed: 0.20 # m/s + +# Thresholds for switching to straight line trajectories. +use_straight_line_traj_under_spline: 0.12 # xyz meters for spline +use_straight_line_traj_within_angle: 0.3 # rad for circle/sphere +use_straight_line_traj_under_piecewise_linear: 0.008 # xy meters for PWL + +# Spline-specific parameters. +spline_width: 0.17 + +# Spherical-specific parameters. +sphere_radius: 0.12 + +# Circular-specific parameters. +circle_radius: 0.20 +circle_height: 0.00 + +# Piecewise-linear-specific parameters. +pwl_waypoint_height: 0.06 diff --git a/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml b/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml new file mode 100644 index 0000000000..38ad1b11dc --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml @@ -0,0 +1,23 @@ +sampling_c3_options_file: examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml +reposition_params_file: examples/sampling_c3/jacktoy/parameters/reposition_params.yaml +progress_params_file: examples/sampling_c3/jacktoy/parameters/progress_params.yaml +sampling_params_file: examples/sampling_c3/jacktoy/parameters/sampling_params.yaml +goal_params_file: examples/sampling_c3/jacktoy/parameters/goal_params.yaml + +sim_params_file: examples/sampling_c3/jacktoy/parameters/sim_params.yaml +vis_params_file: examples/sampling_c3/jacktoy/parameters/vis_params.yaml +osc_params_file: examples/sampling_c3/shared_parameters/osc_params.yaml +osqp_settings_file: examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml +osc_qp_settings_file: examples/sampling_c3/shared_parameters/osc_qp_settings.yaml +franka_driver_channels_file: common/parameters/franka_drake_lcm_driver_channels.yaml +lcm_channels_hardware_file: examples/sampling_c3/shared_parameters/lcm_channels_hardware.yaml +lcm_channels_simulation_file: examples/sampling_c3/shared_parameters/lcm_channels_simulation.yaml + +# Note: Use capsule_1 body name as representative of the pose of the entire +# jack model. This works because capsule_1's origin is the same as the jack's. +object_model: examples/sampling_c3/urdf/jack_ground.sdf +object_body_name: capsule_1 + +include_end_effector_orientation: false + +control_loop_delay_ms: 0 diff --git a/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml b/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml new file mode 100644 index 0000000000..086280d38c --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml @@ -0,0 +1,185 @@ +### C3 options +admm_iter: 3 +rho: 0 #This isn't used anywhere! +rho_scale: 3 +num_threads: 5 +num_outer_threads: 4 +delta_option: 1 +projection_type: 'MIQP' # 'MIQP' or 'QP' +contact_model: 'anitescu' # 'stewart_and_trinkle' or 'anitescu'. +warm_start: false +end_on_qp_step: false +use_robust_formulation: false +solve_time_filter_alpha: 0.95 +publish_frequency: 0 +penalize_changes_in_u_across_solves: false # Penalize (u-u_prev) instead of u. +num_friction_directions: 2 + +N: 5 +gamma: 1.0 # discount factor on MPC costs + +# As alpha -> 0, any complimentarity constraint error in QP projection -> 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1 + +### Limits +# Workspace limits specified as linear constraints [x, y, z, lb, ub] +workspace_limits: [[1, 0, 0, 0.15, 0.75], + [0, 1, 0, -0.6, 0.6], + [0, 0, 1, -0.01, 0.3]] +robot_radius_limits: [0.25, 0.75] +workspace_margins: 0.02 +u_horizontal_limits: [-50, 50] +u_vertical_limits: [-50, 50] + +### Whether to use a predicted EE location for each mode. +use_predicted_x0_c3: true +use_predicted_x0_repos: true +use_predicted_x0_reset_mechanism: true # Resets if prediction is too far. + +### Jack demo specific parameters: +# Contact pairs include a number of (ee-ground, ee-jack, jack-ground). +mu_per_pair_type: [0.4165, 1, 0.4615] # match URDFs with (2mu1*mu2)/(mu1+mu2) +resolve_contacts_to_lists: [[0, 1, 3], + [0, 3, 3], + [1, 1, 3], + [1, 3, 3], + [0, 1, 4], + [0, 3, 6], + [0, 2, 3]] +# Index into this list to choose number of contacts for C3 solve and cost. +num_contacts_index: 0 +num_contacts_index_for_cost: 5 + +planning_dt_position: 0.1 +planning_dt_pose: 0.05 + +### Cost parameters +### If list of lists, then index into them with num_contact_index(_for_cost). +# Set 4x4 portion of Q for quaternion based on current and desired quaternion. +use_quaternion_dependent_cost: true +q_quaternion_dependent_weight: 2500 +q_quaternion_dependent_regularizer_fraction: 0 + +Kp_for_ee_pd_rollout: 100 +Kd_for_ee_pd_rollout: 0.5 + +### Pose tracking cost parameters +# Matrix scaling +w_Q: 45 +w_R: 1 +w_G: 0.25 +w_U: 0.26 + +q_vector: [0.01, 0.01, 0.01, # EE position + 0.1, 0.1, 0.1, 0.1, # object orientation + 200, 200, 120, # object position + 5, 5, 5, # EE linear velocity + 0.05, 0.05, 0.05, # object angular velocity + 0.05, 0.05, 0.05] # object linear velocity +r_vector: [0.01, 0.01, 0.01] + +# Penalty on matching projected variables +g_x: [800, 800, 800, 100, 100, 100, 100, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +g_lambda_n_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +g_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_list: [[0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] +g_u: [30, 30, 30] + +# Penalty on matching the QP variables +u_x: [10, 10, 10, 50, 50, 50, 50, 50, 50, 50, 8, 8, 8, 1, 1, 1, 1, 1, 1] +u_gamma_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +u_lambda_n_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +u_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +# u_lambda_list is not used for the QP projection; overwritten by alpha*F. +u_lambda_list: [[10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_u: [0.01, 0.01, 0.01] + +### Position tracking cost parameters +# Matrix scaling +w_Q_position: 45 +w_R_position: 1 +w_G_position: 0.25 +w_U_position: 0.26 + +q_vector_position: [0.01, 0.01, 0.01, # EE position + 0.1, 0.1, 0.1, 0.1, # object orientation + 1500, 1500, 1500, # object position + 5, 5, 5, # EE linear velocity + 0.01, 0.01, 0.01, # object angular velocity + 1, 1, 1] # object linear velocity +r_vector_position: [0.01, 0.01, 0.01] + +# Penalty on matching projected variables +g_x_position: [800, 800, 800, 10, 10, 10, 10, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +g_lambda_n_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +g_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_position_list: [[0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] +g_u_position: [30, 30, 30] + +# Penalty on matching the QP variables +u_x_position: [10, 10, 10, 100, 100, 100, 100, 10, 10, 10, 8, 8, 8, 1, 1, 1, 1, 1, 1] +u_gamma_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +u_lambda_n_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1, 1]] +u_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +# u_lambda_list is not used for the QP projection; overwritten by alpha*F. +u_lambda_position_list: [[10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_u_position: [0.01, 0.01, 0.01] + + +### NO NEED TO CHANGE THE BELOW. Parameters needed for the C3Options struct but +### are overwritten by other sampling C3 parameters. +use_predicted_x0: false # instead: use_predicted_x0_c3, + # use_predicted_x0_repos, + # use_predicted_x0_reset_mechanism +dt: 0 # instead: planning_dt_pose, planning_dt_position +solve_dt: 0 # unused +mu: [] # instead based on indexing into mu_per_pair_type +num_contacts: 0 # instead based on summing index of resolve_contacts_to_lists +# Instead for the below, index into their _list versions. +g_gamma: [] +g_lambda_n: [] +g_lambda_t: [] +g_lambda: [] +u_gamma: [] +u_lambda_n: [] +u_lambda_t: [] +u_lambda: [] diff --git a/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml b/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml new file mode 100644 index 0000000000..3e84da937d --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml @@ -0,0 +1,45 @@ +# Sampling strategies (defined as SamplingStrategy enum in sampling_params.h): +# 0. kRadiallySymmetric: radially distributed samples on a planar circle. +# 1. kRandomOnCircle: random samples on a planar circle. +# 2. kRandomOnSphere: random samples on a spherical surface. +# 3. kFixed: fixed set of samples. +# 4. kRandomOnPerimeter: random samples on a perimeter offset past the object +# surface (roughly planar). +# 5. kRandomOnShell: random samples on a shell offset past the object +# surface. +sampling_strategy: 2 + +### Parameters relevant for all sampling strategies. +filter_samples_for_safety: true + +# Number of samples. Add 2 for repositioning (current location, previous +# repositioning target) and 1 for C3 (current location) to get total sample +# number solved in parallel for each control loop. +num_additional_samples_repos: 1 +num_additional_samples_c3: 2 + +# Sample buffer parameters. +consider_best_buffer_sample_when_leaving_c3: false +N_sample_buffer: 100 +pos_error_sample_retention: 0.005 +ang_error_sample_retention: 0.087 # 0.087 rad = 5 deg + +# Shared across multiple sampling strategies. +sampling_radius: 0.10 # kRadiallySymmetric, kRandomOnCircle, kRandomOnSphere +sampling_height: 0.04 # kRadiallySymmetric, kRandomOnCircle, kRandomOnPerimeter +sample_projection_clearance: 0.008 # kRandomOnPerimeter, kRandomOnShell +min_angle_from_vertical: 0.2 # kRandomOnSphere, kRandomOnShell +max_angle_from_vertical: 1.95 # kRandomOnSphere, kRandomOnShell + +# kFixed parameters. +fixed_sample_locations: [[0.45, 0.340, 0.04], # sample 1 + [0.27, 0.455, 0.04], # sample 2 + [0.27, 0.225, 0.04]] # sample 3 + +# kRandomOnPerimeter parameters. +grid_x_limits: [-0.16, 0.16] +grid_y_limits: [-0.16, 0.16] + +# kRandomOnShell parameters. +min_sampling_radius: 0.07 +max_sampling_radius: 0.10 diff --git a/examples/sampling_c3/jacktoy/parameters/sim_params.yaml b/examples/sampling_c3/jacktoy/parameters/sim_params.yaml new file mode 100644 index 0000000000..cac1c35d90 --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/sim_params.yaml @@ -0,0 +1,15 @@ +object_model: examples/sampling_c3/urdf/jack.sdf + +franka_publish_rate: 1000 +object_publish_rate: 10 +actuator_delay: 0.000 + +visualize_drake_sim: false +publish_efforts: true + +dt: 0.0001 +realtime_rate: 1 + +# Set the initial locations to something more vertical: +q_init_franka: [2.191, 1.1, -1.33, -2.22, 1.30, 2.02, 0.08] +q_init_object: [-0.3347435, -0.026718954, 0.8878204, 0.31518626, 0.4, 0.30, 0.03] diff --git a/examples/sampling_c3/jacktoy/parameters/vis_params.yaml b/examples/sampling_c3/jacktoy/parameters/vis_params.yaml new file mode 100644 index 0000000000..7102d4aaf2 --- /dev/null +++ b/examples/sampling_c3/jacktoy/parameters/vis_params.yaml @@ -0,0 +1,37 @@ +ee_vis_model: examples/sampling_c3/urdf/ee_visualization_model.urdf +object_vis_model: examples/sampling_c3/urdf/jack.sdf +visualizer_publish_rate: 30 + +camera_pose: [1.5, 0, 0.6] +camera_target: [0.5, 0, 0.5] + +visualize_c3_workspace: false +visualize_c3_state: true + +visualize_center_of_mass_plan_curr: false +visualize_c3_forces_curr: false +visualize_center_of_mass_plan_best: false +visualize_c3_forces_best: false + +visualize_is_c3_mode: true +visualize_sample_locations: true +visualize_sample_buffer: true + +# Note: Colors can either be empty ([]) or RGB values between 0 and 1. If left +# empty, the colors defined in the URDF/SDF files will be used. +is_c3_mode_color: [1.0, 0.43, 1.0] +sample_color: [1.0, 1.0, 0.0] + +visualize_execution_plan: false + +visualize_c3_plan_curr: false +c3_curr_object_color: [] +c3_curr_ee_color: [1.0, 1.0, 1.0] +df_curr_object_color: [] +df_curr_ee_color: [0.5, 1.0, 0.5] + +visualize_c3_plan_best: false +c3_best_object_color: [1.0, 0.64, 0.0] +c3_best_ee_color: [1.0, 0.64, 0.0] +df_best_object_color: [1.0, 0.64, 0.0] +df_best_ee_color: [1.0, 0.64, 0.0] diff --git a/examples/sampling_c3/joint_trajectory_generator.cc b/examples/sampling_c3/joint_trajectory_generator.cc new file mode 100644 index 0000000000..fbd40e2151 --- /dev/null +++ b/examples/sampling_c3/joint_trajectory_generator.cc @@ -0,0 +1,108 @@ +#include "joint_trajectory_generator.h" + +#include "systems/framework/output_vector.h" + +using Eigen::Map; +using Eigen::MatrixXd; +using Eigen::VectorXd; +using std::string; + +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteUpdateEvent; +using drake::systems::DiscreteValues; +using drake::systems::EventStatus; +using drake::trajectories::PiecewisePolynomial; +using drake::trajectories::Trajectory; + +namespace dairlib { + +using systems::OutputVector; + +JointTrajectoryGenerator::JointTrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + const Eigen::VectorXd& target_position) + : target_position_(target_position) { + // Input/Output Setup + PiecewisePolynomial pp = PiecewisePolynomial(); + + radio_port_ = + this->DeclareVectorInputPort("lcmt_radio_out", BasicVector(18)) + .get_index(); + state_port_ = + this->DeclareVectorInputPort( + "x_franka", OutputVector(plant.num_positions(), + plant.num_velocities(), plant.num_actuators())) + .get_index(); + + initial_position_index_ = + this->DeclareDiscreteState(VectorXd::Zero(plant.num_positions())); + initial_time_index_ = this->DeclareDiscreteState(VectorXd::Zero(1)); + + DeclareForcedDiscreteUpdateEvent( + &JointTrajectoryGenerator::DiscreteVariableUpdate); + + joint_trajectory_ports_.resize(plant.num_positions()); + for (int i = 0; i < plant.num_positions(); ++i) { + joint_trajectory_ports_[i] = + this->DeclareAbstractOutputPort( + "joint_traj_" + std::to_string(i), + []() { + return drake::AbstractValue::Make>( + PiecewisePolynomial(VectorXd::Zero(1))); + }, + [this, i](const Context& context, drake::AbstractValue* traj){ + this->CalcTraj(i, context, traj); + }) + .get_index(); + } +} + +drake::systems::EventStatus JointTrajectoryGenerator::DiscreteVariableUpdate( + const Context& context, + drake::systems::DiscreteValues* discrete_state) const { + auto initial_positions = + discrete_state->get_mutable_value(initial_position_index_); + auto initial_time = discrete_state->get_mutable_value(initial_time_index_); + const OutputVector* franka_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + if (initial_time[0] == 0.0) { // poll once + initial_positions = franka_output->GetPositions(); + initial_time[0] = context.get_time(); + } + return drake::systems::EventStatus::Succeeded(); +} + +void JointTrajectoryGenerator::CalcTraj( + int joint_index, const drake::systems::Context& context, + drake::AbstractValue* output) const { + auto output_value = &output->get_mutable_value>(); + auto* casted_traj = + (PiecewisePolynomial*)dynamic_cast*>( + output_value); + const OutputVector* franka_output = + (OutputVector*)this->EvalVectorInput(context, state_port_); + auto initial_positions = + context.get_discrete_state(initial_position_index_).value(); + auto initial_time = context.get_discrete_state(initial_time_index_).value(); + + const auto& radio_out = this->EvalVectorInput(context, radio_port_); + + std::vector breaks = {initial_time[0] + 1.0, initial_time[0] + 6.0}; + std::vector sampled_positions(2); + sampled_positions[0] = MatrixXd::Zero(1, 1); + sampled_positions[0] << initial_positions[joint_index]; + sampled_positions[1] = MatrixXd::Zero(1, 1); + sampled_positions[1] << target_position_[joint_index]; + if (context.get_time() >= 1.0) { // poll for a second + *casted_traj = + PiecewisePolynomial::CubicWithContinuousSecondDerivatives( + breaks, sampled_positions, MatrixXd::Zero(1, 1), + MatrixXd::Zero(1, 1)); + } else { + *casted_traj = PiecewisePolynomial( + franka_output->GetPositions().segment(joint_index, 1)); + } +} + +} // namespace dairlib diff --git a/examples/sampling_c3/joint_trajectory_generator.h b/examples/sampling_c3/joint_trajectory_generator.h new file mode 100644 index 0000000000..0d8b46412e --- /dev/null +++ b/examples/sampling_c3/joint_trajectory_generator.h @@ -0,0 +1,44 @@ +#pragma once + +#include "drake/common/trajectories/piecewise_polynomial.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +class JointTrajectoryGenerator : public drake::systems::LeafSystem { + public: + JointTrajectoryGenerator( + const drake::multibody::MultibodyPlant& plant, + const Eigen::VectorXd& target_position); + + const drake::systems::InputPort& get_input_port_robot_state() const { + return this->get_input_port(state_port_); + } + const drake::systems::InputPort& get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + const drake::systems::OutputPort& get_output_port_joint( + int joint_index) const { + return this->get_output_port(joint_trajectory_ports_[joint_index]); + } + + private: + drake::systems::EventStatus DiscreteVariableUpdate( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + void CalcTraj(int joint_index, const drake::systems::Context& context, + drake::AbstractValue* traj) const; + + drake::systems::InputPortIndex state_port_; + drake::systems::InputPortIndex radio_port_; + std::vector joint_trajectory_ports_; + drake::systems::DiscreteStateIndex initial_position_index_; + drake::systems::DiscreteStateIndex initial_time_index_; + const Eigen::VectorXd target_position_; + + double default_speed = 0.1; // rad/s +}; + +} // namespace dairlib diff --git a/examples/sampling_c3/parameter_headers/BUILD.bazel b/examples/sampling_c3/parameter_headers/BUILD.bazel new file mode 100644 index 0000000000..8377beeb8f --- /dev/null +++ b/examples/sampling_c3/parameter_headers/BUILD.bazel @@ -0,0 +1,71 @@ +cc_library( + name = "sampling_c3_options", + hdrs = ["sampling_c3_options.h"], + visibility = ["//visibility:public"], # Allow all subpackages to use it + deps = ["//solvers:c3"] +) + +cc_library( + name = "franka_sim_params", + hdrs = ["franka_sim_params.h"], + visibility = ["//visibility:public"], +) + +cc_library( + name = "visualizer_params", + hdrs = ["visualizer_params.h"], + visibility = ["//visibility:public"], +) + +cc_library( + name = "lcm_channels", + hdrs = ["lcm_channels.h"], + visibility = ["//visibility:public"], +) + +cc_library( + name = "sampling_c3_controller_params", + hdrs = ["sampling_c3_controller_params.h"], + visibility = ["//visibility:public"], + deps = [ + "//examples/sampling_c3/parameter_headers:sampling_c3_options", + "//examples/sampling_c3/parameter_headers:reposition_params", + "//examples/sampling_c3/parameter_headers:progress_params", + "//examples/sampling_c3/parameter_headers:sampling_params", + "//examples/sampling_c3/parameter_headers:goal_params", + ], +) + +cc_library( + name = "osc_params", + hdrs = ["osc_params.h"], + visibility = ["//visibility:public"], +) + +cc_library( + name = "goal_params", + hdrs = ["goal_params.h"], + visibility = ["//visibility:public"], + deps = ["//common:file_utils"], +) + +cc_library( + name = "sampling_params", + hdrs = ["sampling_params.h"], + visibility = ["//visibility:public"], + deps = ["//common:file_utils"], +) + +cc_library( + name = "reposition_params", + hdrs = ["reposition_params.h"], + visibility = ["//visibility:public"], + deps = ["//common:file_utils"], +) + +cc_library( + name = "progress_params", + hdrs = ["progress_params.h"], + visibility = ["//visibility:public"], + deps = ["//common:file_utils"], +) diff --git a/examples/sampling_c3/parameter_headers/franka_sim_params.h b/examples/sampling_c3/parameter_headers/franka_sim_params.h new file mode 100644 index 0000000000..e65125e7bc --- /dev/null +++ b/examples/sampling_c3/parameter_headers/franka_sim_params.h @@ -0,0 +1,31 @@ +#pragma once + +#include +#include "drake/common/yaml/yaml_read_archive.h" + +struct FrankaSimParams { + std::string object_model; + double dt; + double realtime_rate; + double actuator_delay; + double franka_publish_rate; + double object_publish_rate; + bool visualize_drake_sim; + bool publish_efforts; + Eigen::VectorXd q_init_franka; + Eigen::VectorXd q_init_object; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(object_model)); + a->Visit(DRAKE_NVP(dt)); + a->Visit(DRAKE_NVP(realtime_rate)); + a->Visit(DRAKE_NVP(actuator_delay)); + a->Visit(DRAKE_NVP(franka_publish_rate)); + a->Visit(DRAKE_NVP(object_publish_rate)); + a->Visit(DRAKE_NVP(visualize_drake_sim)); + a->Visit(DRAKE_NVP(publish_efforts)); + a->Visit(DRAKE_NVP(q_init_franka)); + a->Visit(DRAKE_NVP(q_init_object)); + } +}; diff --git a/examples/sampling_c3/parameter_headers/goal_params.h b/examples/sampling_c3/parameter_headers/goal_params.h new file mode 100644 index 0000000000..656a38aff1 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/goal_params.h @@ -0,0 +1,71 @@ +#pragma once + +#include "common/file_utils.h" +#include "drake/common/yaml/yaml_read_archive.h" + + +/* Goal mode options: + 0. kRandom: randomly generate a new goal. + 1. kOrientationSequence: keep position goal the same, and cycle through a + sequence of orientations. + 2. kFixedGoal: keep the same goal. +*/ +enum GoalMode { + kRandom, + kOrientationSequence, + kFixedGoal +}; + +struct SamplingC3GoalParams { + GoalMode goal_mode; + + /// Parameters used for multiple goal modes. + /// Success thresholds for position and orientation. + double position_success_threshold; + double orientation_success_threshold; + + double resting_object_height; // in world frame + double ee_target_z_offset_above_object; // defines EE goal wrt object height + + /// Lookahead parameters to define a sub-goal for C3. + double lookahead_step_size; + double lookahead_angle; + + /// Apply hysteresis on the lookahead angle so the sub-goal orientation does + /// not flip back and forth near the 180 degree error singularity. A lower + /// number means the sub-goal orientation can switch more often; a higher + /// number means the sub-goal orientation is more stable but possibly less + /// optimal. + double angle_hysteresis; + + /// Factor to convert an angular error to angular velocity command (a value of + /// 0 disables this feature).) + double angle_err_to_vel_factor; + + /// Initial goal (and only goal for fixed goal mode). + Eigen::VectorXd fixed_target_position; + Eigen::VectorXd fixed_target_orientation; + + /// Random-specific parameters. + Eigen::VectorXd random_goal_x_limits; + Eigen::VectorXd random_goal_y_limits; + Eigen::VectorXd random_goal_radius_limits; + + template + void Serialize(Archive* a) { + ENUM_DESERIALIZE(a, goal_mode); + a->Visit(DRAKE_NVP(position_success_threshold)); + a->Visit(DRAKE_NVP(orientation_success_threshold)); + a->Visit(DRAKE_NVP(resting_object_height)); + a->Visit(DRAKE_NVP(ee_target_z_offset_above_object)); + a->Visit(DRAKE_NVP(lookahead_step_size)); + a->Visit(DRAKE_NVP(lookahead_angle)); + a->Visit(DRAKE_NVP(angle_hysteresis)); + a->Visit(DRAKE_NVP(angle_err_to_vel_factor)); + a->Visit(DRAKE_NVP(fixed_target_position)); + a->Visit(DRAKE_NVP(fixed_target_orientation)); + a->Visit(DRAKE_NVP(random_goal_x_limits)); + a->Visit(DRAKE_NVP(random_goal_y_limits)); + a->Visit(DRAKE_NVP(random_goal_radius_limits)); + } +}; diff --git a/examples/sampling_c3/parameter_headers/lcm_channels.h b/examples/sampling_c3/parameter_headers/lcm_channels.h new file mode 100644 index 0000000000..6413613956 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/lcm_channels.h @@ -0,0 +1,82 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + +struct SamplingC3LcmChannels { + std::string franka_state_channel; + std::string object_state_channel; + std::string franka_input_channel; + std::string osc_channel; + std::string osc_debug_channel; + + std::string c3_actor_curr_plan_channel; + std::string c3_object_curr_plan_channel; + std::string c3_force_curr_channel; + std::string c3_debug_output_curr_channel; + + std::string c3_actor_best_plan_channel; + std::string c3_object_best_plan_channel; + std::string c3_force_best_channel; + std::string c3_debug_output_best_channel; + + std::string c3_trajectory_exec_actor_channel; + std::string repos_trajectory_exec_actor_channel; + std::string tracking_trajectory_actor_channel; + std::string tracking_trajectory_object_channel; + + std::string c3_final_target_state_channel; + std::string c3_target_state_channel; + std::string c3_actual_state_channel; + std::string radio_channel; + + std::string sample_locations_channel; + std::string sample_buffer_channel; + std::string dynamically_feasible_curr_actor_plan_channel; + std::string dynamically_feasible_curr_plan_channel; + std::string dynamically_feasible_best_actor_plan_channel; + std::string dynamically_feasible_best_plan_channel; + std::string sample_costs_channel; + std::string sampling_c3_debug_channel; + std::string is_c3_mode_channel; + std::string target_generator_info_channel; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(franka_state_channel)); + a->Visit(DRAKE_NVP(object_state_channel)); + a->Visit(DRAKE_NVP(franka_input_channel)); + a->Visit(DRAKE_NVP(osc_channel)); + a->Visit(DRAKE_NVP(osc_debug_channel)); + + a->Visit(DRAKE_NVP(c3_actor_curr_plan_channel)); + a->Visit(DRAKE_NVP(c3_object_curr_plan_channel)); + a->Visit(DRAKE_NVP(c3_force_curr_channel)); + a->Visit(DRAKE_NVP(c3_debug_output_curr_channel)); + + a->Visit(DRAKE_NVP(c3_actor_best_plan_channel)); + a->Visit(DRAKE_NVP(c3_object_best_plan_channel)); + a->Visit(DRAKE_NVP(c3_force_best_channel)); + a->Visit(DRAKE_NVP(c3_debug_output_best_channel)); + + a->Visit(DRAKE_NVP(c3_trajectory_exec_actor_channel)); + a->Visit(DRAKE_NVP(repos_trajectory_exec_actor_channel)); + a->Visit(DRAKE_NVP(tracking_trajectory_actor_channel)); + a->Visit(DRAKE_NVP(tracking_trajectory_object_channel)); + + a->Visit(DRAKE_NVP(c3_final_target_state_channel)); + a->Visit(DRAKE_NVP(c3_target_state_channel)); + a->Visit(DRAKE_NVP(c3_actual_state_channel)); + a->Visit(DRAKE_NVP(radio_channel)); + + a->Visit(DRAKE_NVP(sample_locations_channel)); + a->Visit(DRAKE_NVP(sample_buffer_channel)); + a->Visit(DRAKE_NVP(dynamically_feasible_curr_actor_plan_channel)); + a->Visit(DRAKE_NVP(dynamically_feasible_curr_plan_channel)); + a->Visit(DRAKE_NVP(dynamically_feasible_best_actor_plan_channel)); + a->Visit(DRAKE_NVP(dynamically_feasible_best_plan_channel)); + a->Visit(DRAKE_NVP(sample_costs_channel)); + a->Visit(DRAKE_NVP(sampling_c3_debug_channel)); + a->Visit(DRAKE_NVP(is_c3_mode_channel)); + a->Visit(DRAKE_NVP(target_generator_info_channel)); + } +}; diff --git a/examples/sampling_c3/parameter_headers/osc_params.h b/examples/sampling_c3/parameter_headers/osc_params.h new file mode 100644 index 0000000000..187d4876f2 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/osc_params.h @@ -0,0 +1,106 @@ +#pragma once + +#include "systems/controllers/osc/osc_gains.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +/// Extends OSCGains to include parameters specific to sampling C3 example. +struct SamplingC3OSCParams : OSCGains { + /// Teleop params: There are two teleoperation modes: + /// 1) locked EE neutral position where xbox controls perturb the EE about + /// this neutral position (corresponds to teleop_neutral_position = false). + /// 2) free EE neutral position where the EE can be moved freely in space + /// where xbox controls change the EE resting position (corresponds to + /// teleop_neutral_position = true). + Eigen::VectorXd neutral_position; + bool teleop_neutral_position; + double x_scale; + double y_scale; + double z_scale; + + double end_effector_acceleration; + bool track_end_effector_orientation; + bool cancel_gravity_compensation; + bool enforce_acceleration_constraints; + bool publish_debug_info; + + /// Joint 2 position tracking weight values. It is helpful to introduce a + /// target position for the elbow joint to avoid singularities. NOTE: the + /// target value is currently hardcoded in franka_osc_controller.cc. + double w_elbow; + double elbow_kp; + double elbow_kd; + /// End effector position tracking weight matrix values. + std::vector EndEffectorW; + std::vector EndEffectorKp; + std::vector EndEffectorKd; + /// End effector orientation tracking weight matrix values. + std::vector EndEffectorRotW; + std::vector EndEffectorRotKp; + std::vector EndEffectorRotKd; + /// End effector force tracking weight matrix values. + std::vector LambdaEndEffectorW; + + Eigen::MatrixXd W_mid_link; + Eigen::MatrixXd K_p_mid_link; + Eigen::MatrixXd K_d_mid_link; + Eigen::MatrixXd W_end_effector; + Eigen::MatrixXd K_p_end_effector; + Eigen::MatrixXd K_d_end_effector; + Eigen::MatrixXd W_end_effector_rot; + Eigen::MatrixXd K_p_end_effector_rot; + Eigen::MatrixXd K_d_end_effector_rot; + Eigen::MatrixXd W_ee_lambda; + + template + void Serialize(Archive* a) { + OSCGains::Serialize(a); + a->Visit(DRAKE_NVP(neutral_position)); + a->Visit(DRAKE_NVP(teleop_neutral_position)); + a->Visit(DRAKE_NVP(x_scale)); + a->Visit(DRAKE_NVP(y_scale)); + a->Visit(DRAKE_NVP(z_scale)); + a->Visit(DRAKE_NVP(end_effector_acceleration)); + a->Visit(DRAKE_NVP(track_end_effector_orientation)); + a->Visit(DRAKE_NVP(cancel_gravity_compensation)); + a->Visit(DRAKE_NVP(enforce_acceleration_constraints)); + a->Visit(DRAKE_NVP(publish_debug_info)); + a->Visit(DRAKE_NVP(w_elbow)); + a->Visit(DRAKE_NVP(elbow_kp)); + a->Visit(DRAKE_NVP(elbow_kd)); + a->Visit(DRAKE_NVP(EndEffectorW)); + a->Visit(DRAKE_NVP(EndEffectorKp)); + a->Visit(DRAKE_NVP(EndEffectorKd)); + a->Visit(DRAKE_NVP(EndEffectorRotW)); + a->Visit(DRAKE_NVP(EndEffectorRotKp)); + a->Visit(DRAKE_NVP(EndEffectorRotKd)); + a->Visit(DRAKE_NVP(LambdaEndEffectorW)); + + // Weight matrix for end effector position tracking. + W_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorW.data(), 3, 3); + K_p_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorKp.data(), 3, 3); + K_d_end_effector = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorKd.data(), 3, 3); + W_mid_link = this->w_elbow * MatrixXd::Identity(1, 1); + K_p_mid_link = this->elbow_kp * MatrixXd::Identity(1, 1); + K_d_mid_link = this->elbow_kd * MatrixXd::Identity(1, 1); + W_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotW.data(), 3, 3); + K_p_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotKp.data(), 3, 3); + K_d_end_effector_rot = Eigen::Map< + Eigen::Matrix>( + this->EndEffectorRotKd.data(), 3, 3); + // Weight matrix for ee force tracking. + W_ee_lambda = Eigen::Map< + Eigen::Matrix>( + this->LambdaEndEffectorW.data(), 3, 3); + } +}; diff --git a/examples/sampling_c3/parameter_headers/progress_params.h b/examples/sampling_c3/parameter_headers/progress_params.h new file mode 100644 index 0000000000..ed4cca9e2f --- /dev/null +++ b/examples/sampling_c3/parameter_headers/progress_params.h @@ -0,0 +1,77 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + +#include "common/file_utils.h" +#include "solvers/c3_options.h" + + +/* C3 progress metric options, all phrased as improvement requirements over a + number of control loops: + 0. kC3Cost: C3 cost. + 1. kConfigCost: Current object configuration cost. + 2. kPosOrRotCost: Current position or rotation error. + 3. kConfigCostDrop: Drop in object configuration cost (this is the same as + kConfigCost if the required drop is 0; a more aggressive + drop cuts C3 off earlier). +*/ +enum ProgressMetric { + kC3Cost, + kConfigCost, + kPosOrRotCost, + kConfigCostDrop +}; + + +struct SamplingC3ProgressParams { + C3CostComputationType cost_type; + C3CostComputationType cost_type_position; + int num_control_loops_to_wait; + int num_control_loops_to_wait_position; + ProgressMetric track_c3_progress_via; + double progress_enforced_cost_drop; + int progress_enforced_over_n_loops; + double cost_switching_threshold_distance; + double travel_cost_per_meter; + double hyst_c3_to_repos; + double hyst_c3_to_repos_position; + double finished_reposition_cost; + double hyst_repos_to_c3; + double hyst_repos_to_c3_position; + double hyst_repos_to_repos; + double hyst_repos_to_repos_position; + bool use_relative_hysteresis; + double hyst_c3_to_repos_frac; + double hyst_repos_to_c3_frac; + double hyst_repos_to_repos_frac; + double hyst_c3_to_repos_frac_position; + double hyst_repos_to_c3_frac_position; + double hyst_repos_to_repos_frac_position; + + template + void Serialize(Archive* a) { + ENUM_DESERIALIZE(a, cost_type); + ENUM_DESERIALIZE(a, cost_type_position); + ENUM_DESERIALIZE(a, track_c3_progress_via); + a->Visit(DRAKE_NVP(num_control_loops_to_wait)); + a->Visit(DRAKE_NVP(num_control_loops_to_wait_position)); + a->Visit(DRAKE_NVP(progress_enforced_cost_drop)); + a->Visit(DRAKE_NVP(progress_enforced_over_n_loops)); + a->Visit(DRAKE_NVP(cost_switching_threshold_distance)); + a->Visit(DRAKE_NVP(travel_cost_per_meter)); + a->Visit(DRAKE_NVP(hyst_c3_to_repos)); + a->Visit(DRAKE_NVP(hyst_c3_to_repos_position)); + a->Visit(DRAKE_NVP(finished_reposition_cost)); + a->Visit(DRAKE_NVP(hyst_repos_to_c3)); + a->Visit(DRAKE_NVP(hyst_repos_to_c3_position)); + a->Visit(DRAKE_NVP(hyst_repos_to_repos)); + a->Visit(DRAKE_NVP(hyst_repos_to_repos_position)); + a->Visit(DRAKE_NVP(use_relative_hysteresis)); + a->Visit(DRAKE_NVP(hyst_c3_to_repos_frac)); + a->Visit(DRAKE_NVP(hyst_repos_to_c3_frac)); + a->Visit(DRAKE_NVP(hyst_repos_to_repos_frac)); + a->Visit(DRAKE_NVP(hyst_c3_to_repos_frac_position)); + a->Visit(DRAKE_NVP(hyst_repos_to_c3_frac_position)); + a->Visit(DRAKE_NVP(hyst_repos_to_repos_frac_position)); + } +}; diff --git a/examples/sampling_c3/parameter_headers/reposition_params.h b/examples/sampling_c3/parameter_headers/reposition_params.h new file mode 100644 index 0000000000..9b942cfe63 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/reposition_params.h @@ -0,0 +1,62 @@ +#pragma once + +#include "drake/common/yaml/yaml_read_archive.h" + +#include "common/file_utils.h" + + +/* Repositioning trajectory type options: + 0. kSpline: move from current to target with spline that distorts + around the object. + 1. kSpherical: move away from object to a radius, along the spherical + surface to outside target, then in to target. + 2. kCircular: (planar) move away from object to a planar radius, + along the circle to outside target, then in to target. + 3. kPiecewiseLinear: move up to waypoint height, over to above target, then + down. +*/ +enum RepositioningTrajectoryType { + kSpline, + kSpherical, + kCircular, + kPiecewiseLinear +}; + +struct SamplingC3RepositionParams { + RepositioningTrajectoryType traj_type; + + /// Parameters used for multiple repositioning trajectory types. + double speed; + + /// Thresholds for switching to straight line trajectories. + double use_straight_line_traj_under_spline; + double use_straight_line_traj_within_angle; + double use_straight_line_traj_under_piecewise_linear; + + /// Spline-specific parameters. + double spline_width; + + /// Sphere-specific parameters. + double sphere_radius; + + /// Circle-specific parameters. + double circle_radius; + double circle_height; + + /// Piecewise-linear-specific parameters. + double pwl_waypoint_height; + + template + void Serialize(Archive* a) { + ENUM_DESERIALIZE(a, traj_type); + a->Visit(DRAKE_NVP(speed)); + a->Visit(DRAKE_NVP(use_straight_line_traj_under_spline)); + a->Visit(DRAKE_NVP(use_straight_line_traj_within_angle)); + a->Visit(DRAKE_NVP(use_straight_line_traj_under_piecewise_linear)); + a->Visit(DRAKE_NVP(spline_width)); + a->Visit(DRAKE_NVP(sphere_radius)); + a->Visit(DRAKE_NVP(circle_radius)); + a->Visit(DRAKE_NVP(circle_height)); + a->Visit(DRAKE_NVP(pwl_waypoint_height)); + } +}; diff --git a/examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h b/examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h new file mode 100644 index 0000000000..8cd9bf9cb0 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h @@ -0,0 +1,75 @@ +#pragma once + +#include "examples/sampling_c3/parameter_headers/sampling_c3_options.h" +#include "examples/sampling_c3/parameter_headers/reposition_params.h" +#include "examples/sampling_c3/parameter_headers/progress_params.h" +#include "examples/sampling_c3/parameter_headers/sampling_params.h" +#include "examples/sampling_c3/parameter_headers/goal_params.h" + +#include "drake/common/yaml/yaml_read_archive.h" +#include + + +struct SamplingC3ControllerParams { + std::string sampling_c3_options_file; // C3 mode params + std::string reposition_params_file; // repositioning mode params + std::string progress_params_file; // mode switching params + std::string sampling_params_file; // sampling params + std::string goal_params_file; // goal checking/setting params + + std::string sim_params_file; // simulation params + std::string vis_params_file; // visualization params + std::string osc_params_file; // OSC params + std::string osqp_settings_file; + std::string osc_qp_settings_file; + std::string franka_driver_channels_file; + std::string lcm_channels_hardware_file; + std::string lcm_channels_simulation_file; + + std::string object_model; + std::string object_body_name; + + double workspace_margin; + bool include_end_effector_orientation; + int control_loop_delay_ms; + + /// Store sub-parameter classes internally. + SamplingC3Options sampling_c3_options; + SamplingC3RepositionParams reposition_params; + SamplingC3ProgressParams progress_params; + SamplingParams sampling_params; + SamplingC3GoalParams goal_params; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(sampling_c3_options_file)); + a->Visit(DRAKE_NVP(reposition_params_file)); + a->Visit(DRAKE_NVP(progress_params_file)); + a->Visit(DRAKE_NVP(sampling_params_file)); + a->Visit(DRAKE_NVP(goal_params_file)); + a->Visit(DRAKE_NVP(sim_params_file)); + a->Visit(DRAKE_NVP(vis_params_file)); + a->Visit(DRAKE_NVP(osc_params_file)); + a->Visit(DRAKE_NVP(osqp_settings_file)); + a->Visit(DRAKE_NVP(osc_qp_settings_file)); + a->Visit(DRAKE_NVP(franka_driver_channels_file)); + a->Visit(DRAKE_NVP(lcm_channels_hardware_file)); + a->Visit(DRAKE_NVP(lcm_channels_simulation_file)); + a->Visit(DRAKE_NVP(object_model)); + a->Visit(DRAKE_NVP(object_body_name)); + a->Visit(DRAKE_NVP(include_end_effector_orientation)); + a->Visit(DRAKE_NVP(control_loop_delay_ms)); + + /// Store individual parameter classes internally. + sampling_c3_options = drake::yaml::LoadYamlFile( + sampling_c3_options_file); + reposition_params = drake::yaml::LoadYamlFile( + reposition_params_file); + progress_params = drake::yaml::LoadYamlFile( + progress_params_file); + sampling_params = drake::yaml::LoadYamlFile( + sampling_params_file); + goal_params = drake::yaml::LoadYamlFile( + goal_params_file); + } +}; diff --git a/examples/sampling_c3/parameter_headers/sampling_c3_options.h b/examples/sampling_c3/parameter_headers/sampling_c3_options.h new file mode 100644 index 0000000000..4a41f2ea2c --- /dev/null +++ b/examples/sampling_c3/parameter_headers/sampling_c3_options.h @@ -0,0 +1,298 @@ +#pragma once +#include + +#include "solvers/c3_options.h" + +#include "drake/common/yaml/yaml_read_archive.h" + +struct SamplingC3Options : C3Options { + int num_outer_threads; // for outer sampling loop. + + /// Additional radius-based workspace limit. + std::vector robot_radius_limits; + + /// Whether to use a predicted EE location for each mode. + bool use_predicted_x0_c3; + bool use_predicted_x0_repos; + bool use_predicted_x0_reset_mechanism; // Resets if prediction is too far. + + /// Contact pair parameters. + std::vector mu_per_pair_type; + std::vector> resolve_contacts_to_lists; + std::vector resolve_contacts_to; + std::vector resolve_contacts_to_for_cost; + int num_contacts_index; + int num_contacts_index_for_cost; + std::vector mu_for_cost; + int num_contacts_for_cost; + + double planning_dt_pose; + double planning_dt_position; + + /// Cost parameters. + bool use_quaternion_dependent_cost; + double q_quaternion_dependent_weight; + double q_quaternion_dependent_regularizer_fraction; + + double Kp_for_ee_pd_rollout; + double Kd_for_ee_pd_rollout; + + /// Cost parameters for pose tracking. + std::vector> g_gamma_list; + std::vector> g_lambda_n_list; + std::vector> g_lambda_t_list; + std::vector> g_lambda_list; + + std::vector> u_gamma_list; + std::vector> u_lambda_n_list; + std::vector> u_lambda_t_list; + std::vector> u_lambda_list; + + /// Cost parameters for position tracking. + double w_Q_position; + double w_R_position; + double w_G_position; + double w_U_position; + std::vector q_vector_position; + std::vector r_vector_position; + + std::vector g_x_position; + std::vector> g_gamma_position_list; + std::vector> g_lambda_n_position_list; + std::vector> g_lambda_t_position_list; + std::vector> g_lambda_position_list; + std::vector g_u_position; + + std::vector u_x_position; + std::vector> u_gamma_position_list; + std::vector> u_lambda_n_position_list; + std::vector> u_lambda_t_position_list; + std::vector> u_lambda_position_list; + std::vector u_u_position; + + C3Options c3_options_pose; + C3Options c3_options_position; + + template + void Serialize(Archive* a) { + C3Options::Serialize(a); + a->Visit(DRAKE_NVP(num_outer_threads)); + a->Visit(DRAKE_NVP(robot_radius_limits)); + a->Visit(DRAKE_NVP(use_predicted_x0_c3)); + a->Visit(DRAKE_NVP(use_predicted_x0_repos)); + a->Visit(DRAKE_NVP(use_predicted_x0_reset_mechanism)); + + a->Visit(DRAKE_NVP(mu_per_pair_type)); + a->Visit(DRAKE_NVP(resolve_contacts_to_lists)); + a->Visit(DRAKE_NVP(num_contacts_index)); + a->Visit(DRAKE_NVP(num_contacts_index_for_cost)); + + a->Visit(DRAKE_NVP(planning_dt_pose)); + a->Visit(DRAKE_NVP(planning_dt_position)); + + a->Visit(DRAKE_NVP(use_quaternion_dependent_cost)); + a->Visit(DRAKE_NVP(q_quaternion_dependent_weight)); + a->Visit(DRAKE_NVP(q_quaternion_dependent_regularizer_fraction)); + + a->Visit(DRAKE_NVP(Kp_for_ee_pd_rollout)); + a->Visit(DRAKE_NVP(Kd_for_ee_pd_rollout)); + + a->Visit(DRAKE_NVP(g_gamma_list)); + a->Visit(DRAKE_NVP(g_lambda_n_list)); + a->Visit(DRAKE_NVP(g_lambda_t_list)); + a->Visit(DRAKE_NVP(g_lambda_list)); + + a->Visit(DRAKE_NVP(u_gamma_list)); + a->Visit(DRAKE_NVP(u_lambda_n_list)); + a->Visit(DRAKE_NVP(u_lambda_t_list)); + a->Visit(DRAKE_NVP(u_lambda_list)); + + a->Visit(DRAKE_NVP(w_Q_position)); + a->Visit(DRAKE_NVP(w_R_position)); + a->Visit(DRAKE_NVP(w_G_position)); + a->Visit(DRAKE_NVP(w_U_position)); + a->Visit(DRAKE_NVP(q_vector_position)); + a->Visit(DRAKE_NVP(r_vector_position)); + + a->Visit(DRAKE_NVP(g_x_position)); + a->Visit(DRAKE_NVP(g_gamma_position_list)); + a->Visit(DRAKE_NVP(g_lambda_n_position_list)); + a->Visit(DRAKE_NVP(g_lambda_t_position_list)); + a->Visit(DRAKE_NVP(g_lambda_position_list)); + a->Visit(DRAKE_NVP(g_u_position)); + + a->Visit(DRAKE_NVP(u_x_position)); + a->Visit(DRAKE_NVP(u_gamma_position_list)); + a->Visit(DRAKE_NVP(u_lambda_n_position_list)); + a->Visit(DRAKE_NVP(u_lambda_t_position_list)); + a->Visit(DRAKE_NVP(u_lambda_position_list)); + a->Visit(DRAKE_NVP(u_u_position)); + + // Set a few parameters based on num_contacts_index, differentiating between + // for C3 solve and for C3 cost computation. + resolve_contacts_to = resolve_contacts_to_lists[num_contacts_index]; + resolve_contacts_to_for_cost = + resolve_contacts_to_lists[num_contacts_index_for_cost]; + num_contacts = std::accumulate( + resolve_contacts_to.begin(), resolve_contacts_to.end(), 0); + num_contacts_for_cost = std::accumulate( + resolve_contacts_to_for_cost.begin(), resolve_contacts_to_for_cost.end(), + 0); + mu.clear(); + for (size_t i = 0; i < mu_per_pair_type.size(); ++i) { + int repeat = resolve_contacts_to_lists[num_contacts_index][i]; + mu.insert(mu.end(), repeat, mu_per_pair_type[i]); + } + mu_for_cost.clear(); + for (size_t i = 0; i < mu_per_pair_type.size(); ++i) { + int repeat = resolve_contacts_to_lists[num_contacts_index_for_cost][i]; + mu_for_cost.insert(mu_for_cost.end(), repeat, mu_per_pair_type[i]); + } + + // Create C3 options for both pose and position tracking. + SetCommonC3Options(&c3_options_pose); + SetPoseTrackingOptions(&c3_options_pose); + SetCommonC3Options(&c3_options_position); + SetPositionTrackingOptions(&c3_options_position); + } + + C3Options GetC3Options(const bool& is_pose_tracking) const { + if (is_pose_tracking) { return c3_options_pose; } + return c3_options_position; + } + + private: + void PopulateCostMatricesFromVectors(C3Options* options) const { + std::vector g_vector = std::vector(); + g_vector.insert(g_vector.end(), options->g_x.begin(), options->g_x.end()); + if (options->contact_model == "stewart_and_trinkle") { + g_vector.insert(g_vector.end(), options->g_gamma.begin(), + options->g_gamma.end()); + g_vector.insert(g_vector.end(), options->g_lambda_n.begin(), + options->g_lambda_n.end()); + g_vector.insert(g_vector.end(), options->g_lambda_t.begin(), + options->g_lambda_t.end()); + } else { + g_vector.insert(g_vector.end(), options->g_lambda.begin(), + options->g_lambda.end()); + } + + g_vector.insert(g_vector.end(), options->g_u.begin(), options->g_u.end()); + + std::vector u_vector = std::vector(); + u_vector.insert(u_vector.end(), options->u_x.begin(), options->u_x.end()); + if (options->contact_model == "stewart_and_trinkle") { + u_vector.insert(u_vector.end(), options->u_gamma.begin(), + options->u_gamma.end()); + u_vector.insert(u_vector.end(), options->u_lambda_n.begin(), + options->u_lambda_n.end()); + u_vector.insert(u_vector.end(), options->u_lambda_t.begin(), + options->u_lambda_t.end()); + } else { + u_vector.insert(u_vector.end(), options->u_lambda.begin(), + options->u_lambda.end()); + } + u_vector.insert(u_vector.end(), options->u_u.begin(), options->u_u.end()); + + options->g_vector = g_vector; + options->u_vector = u_vector; + Eigen::VectorXd q = Eigen::Map( + options->q_vector.data(), options->q_vector.size()); + Eigen::VectorXd r = Eigen::Map( + options->r_vector.data(), options->r_vector.size()); + Eigen::VectorXd g = Eigen::Map( + options->g_vector.data(), options->g_vector.size()); + Eigen::VectorXd u = Eigen::Map( + options->u_vector.data(), options->u_vector.size()); + + options->Q = options->w_Q * q.asDiagonal(); + options->R = options->w_R * r.asDiagonal(); + options->G = options->w_G * g.asDiagonal(); + options->U = options->w_U * u.asDiagonal(); + } + + void SetCommonC3Options(C3Options* options) const { + options->admm_iter = admm_iter; + options->rho = rho; + options->rho_scale = rho_scale; + options->num_threads = num_threads; + options->delta_option = delta_option; + options->contact_model = contact_model; + options->projection_type = projection_type; + options->warm_start = warm_start; + options->use_predicted_x0 = false; // unused by sampling C3 + options->end_on_qp_step = end_on_qp_step; + options->use_robust_formulation = use_robust_formulation; + options->solve_time_filter_alpha = solve_time_filter_alpha; + options->publish_frequency = publish_frequency; + + options->workspace_limits = workspace_limits; + options->workspace_margins = workspace_margins; + options->u_horizontal_limits = u_horizontal_limits; + options->u_vertical_limits = u_vertical_limits; + + options->N = N; + options->gamma = gamma; + + options->solve_dt = 0; // unused in all of C3 + options->num_friction_directions = num_friction_directions; + + options->qp_projection_alpha = qp_projection_alpha; + options->qp_projection_scaling = qp_projection_scaling; + options->penalize_changes_in_u_across_solves = + penalize_changes_in_u_across_solves; + + options->mu = mu; + options->num_contacts = num_contacts; + } + + void SetPositionTrackingOptions(C3Options* options) const { + options->dt = planning_dt_position; + options->w_Q = w_Q_position; + options->w_R = w_R_position; + options->w_G = w_G_position; + options->w_U = w_U_position; + options->q_vector = q_vector_position; + options->r_vector = r_vector_position; + + options->g_x = g_x_position; + options->g_gamma = g_gamma_position_list[num_contacts_index]; + options->g_lambda_n = g_lambda_n_position_list[num_contacts_index]; + options->g_lambda_t = g_lambda_t_position_list[num_contacts_index]; + options->g_lambda = g_lambda_position_list[num_contacts_index]; + options->g_u = g_u_position; + + options->u_x = u_x_position; + options->u_gamma = u_gamma_position_list[num_contacts_index]; + options->u_lambda_n = u_lambda_n_position_list[num_contacts_index]; + options->u_lambda_t = u_lambda_t_position_list[num_contacts_index]; + options->u_lambda = u_lambda_position_list[num_contacts_index]; + options->u_u = u_u_position; + PopulateCostMatricesFromVectors(options); + } + + void SetPoseTrackingOptions(C3Options* options) const { + options->dt = planning_dt_pose; + options->w_Q = w_Q; + options->w_R = w_R; + options->w_G = w_G; + options->w_U = w_U; + options->q_vector = q_vector; + options->r_vector = r_vector; + + options->g_x = g_x; + options->g_gamma = g_gamma_list[num_contacts_index]; + options->g_lambda_n = g_lambda_n_list[num_contacts_index]; + options->g_lambda_t = g_lambda_t_list[num_contacts_index]; + options->g_lambda = g_lambda_list[num_contacts_index]; + options->g_u = g_u; + + options->u_x = u_x; + options->u_gamma = u_gamma_list[num_contacts_index]; + options->u_lambda_n = u_lambda_n_list[num_contacts_index]; + options->u_lambda_t = u_lambda_t_list[num_contacts_index]; + options->u_lambda = u_lambda_list[num_contacts_index]; + options->u_u = u_u; + PopulateCostMatricesFromVectors(options); + } +}; diff --git a/examples/sampling_c3/parameter_headers/sampling_params.h b/examples/sampling_c3/parameter_headers/sampling_params.h new file mode 100644 index 0000000000..708e274450 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/sampling_params.h @@ -0,0 +1,85 @@ +#pragma once + +#include "common/file_utils.h" +#include "drake/common/yaml/yaml_read_archive.h" + + +/* Sample generation options: + 0. kRadiallySymmetric: radially distributed samples on a planar circle. + 1. kRandomOnCircle: random samples on a planar circle. + 2. kRandomOnSphere: random samples on a spherical surface. + 3. kFixed: fixed set of samples. + 4. kRandomOnPerimeter: random samples on a perimeter offset past the object + surface (roughly planar). + 5. kRandomOnShell: random samples on a shell offset past the object + surface. +*/ +enum SamplingStrategy { + kRadiallySymmetric, + kRandomOnCircle, + kRandomOnSphere, + kFixed, + kRandomOnPerimeter, + kRandomOnShell +}; + +struct SamplingParams { + SamplingStrategy sampling_strategy; + + /// Parameters relevant for all sampling strategies. + bool filter_samples_for_safety; + + /// Number of samples. Add 2 for repositioning (current location, previous + /// repositioning target) and 1 for C3 (current location) to get total number + /// solved in parallel for each control loop. + int num_additional_samples_repos; + int num_additional_samples_c3; + + /// Sample buffer parameters. + bool consider_best_buffer_sample_when_leaving_c3; + int N_sample_buffer; + double pos_error_sample_retention; + double ang_error_sample_retention; + + /// Shared across multiple sampling strategies. + double sampling_radius; // kRadiallySymmetric, kRandomOnCircle, + // kRandomOnSphere + double sampling_height; // kRadiallySymmetric, kRandomOnCircle + // kRandomOnPerimeter + double sample_projection_clearance; // kRandomOnPerimeter, kRandomOnShell + double min_angle_from_vertical; // kRandomOnSphere, kRandomOnShell + double max_angle_from_vertical; // kRandomOnSphere, kRandomOnShell + + /// kFixed parameters. + Eigen::MatrixXd fixed_sample_locations; // n_samples rows, 3 columns + + /// kRandomOnPerimeter parameters. + std::vector grid_x_limits; + std::vector grid_y_limits; + + /// kRandomOnShell parameters. + double min_sampling_radius; + double max_sampling_radius; + + template + void Serialize(Archive* a) { + ENUM_DESERIALIZE(a, sampling_strategy); + a->Visit(DRAKE_NVP(filter_samples_for_safety)); + a->Visit(DRAKE_NVP(fixed_sample_locations)); + a->Visit(DRAKE_NVP(sampling_radius)); + a->Visit(DRAKE_NVP(min_angle_from_vertical)); + a->Visit(DRAKE_NVP(max_angle_from_vertical)); + a->Visit(DRAKE_NVP(sampling_height)); + a->Visit(DRAKE_NVP(grid_x_limits)); + a->Visit(DRAKE_NVP(grid_y_limits)); + a->Visit(DRAKE_NVP(sample_projection_clearance)); + a->Visit(DRAKE_NVP(min_sampling_radius)); + a->Visit(DRAKE_NVP(max_sampling_radius)); + a->Visit(DRAKE_NVP(num_additional_samples_repos)); + a->Visit(DRAKE_NVP(num_additional_samples_c3)); + a->Visit(DRAKE_NVP(consider_best_buffer_sample_when_leaving_c3)); + a->Visit(DRAKE_NVP(N_sample_buffer)); + a->Visit(DRAKE_NVP(pos_error_sample_retention)); + a->Visit(DRAKE_NVP(ang_error_sample_retention)); + } +}; diff --git a/examples/sampling_c3/parameter_headers/visualizer_params.h b/examples/sampling_c3/parameter_headers/visualizer_params.h new file mode 100644 index 0000000000..73c7d40656 --- /dev/null +++ b/examples/sampling_c3/parameter_headers/visualizer_params.h @@ -0,0 +1,73 @@ +#pragma once + +#include +#include "drake/common/yaml/yaml_read_archive.h" + +struct SamplingC3VisualizerParams { + std::string ee_vis_model; + std::string object_vis_model; + double visualizer_publish_rate; + + Eigen::VectorXd camera_pose; + Eigen::VectorXd camera_target; + + bool visualize_c3_workspace; + bool visualize_c3_state; + + bool visualize_center_of_mass_plan_curr; + bool visualize_c3_forces_curr; + bool visualize_center_of_mass_plan_best; + bool visualize_c3_forces_best; + + bool visualize_is_c3_mode; + bool visualize_sample_locations; + bool visualize_sample_buffer; + + Eigen::VectorXd is_c3_mode_color; + Eigen::VectorXd sample_color; + + bool visualize_execution_plan; + + bool visualize_c3_plan_curr; + Eigen::VectorXd c3_curr_object_color; + Eigen::VectorXd c3_curr_ee_color; + Eigen::VectorXd df_curr_object_color; + Eigen::VectorXd df_curr_ee_color; + + bool visualize_c3_plan_best; + Eigen::VectorXd c3_best_object_color; + Eigen::VectorXd c3_best_ee_color; + Eigen::VectorXd df_best_object_color; + Eigen::VectorXd df_best_ee_color; + + template + void Serialize(Archive* a) { + a->Visit(DRAKE_NVP(ee_vis_model)); + a->Visit(DRAKE_NVP(object_vis_model)); + a->Visit(DRAKE_NVP(visualizer_publish_rate)); + a->Visit(DRAKE_NVP(camera_pose)); + a->Visit(DRAKE_NVP(camera_target)); + a->Visit(DRAKE_NVP(visualize_c3_workspace)); + a->Visit(DRAKE_NVP(visualize_c3_state)); + a->Visit(DRAKE_NVP(visualize_center_of_mass_plan_curr)); + a->Visit(DRAKE_NVP(visualize_c3_forces_curr)); + a->Visit(DRAKE_NVP(visualize_center_of_mass_plan_best)); + a->Visit(DRAKE_NVP(visualize_c3_forces_best)); + a->Visit(DRAKE_NVP(visualize_is_c3_mode)); + a->Visit(DRAKE_NVP(visualize_sample_locations)); + a->Visit(DRAKE_NVP(visualize_sample_buffer)); + a->Visit(DRAKE_NVP(is_c3_mode_color)); + a->Visit(DRAKE_NVP(sample_color)); + a->Visit(DRAKE_NVP(visualize_execution_plan)); + a->Visit(DRAKE_NVP(visualize_c3_plan_curr)); + a->Visit(DRAKE_NVP(c3_curr_object_color)); + a->Visit(DRAKE_NVP(c3_curr_ee_color)); + a->Visit(DRAKE_NVP(df_curr_object_color)); + a->Visit(DRAKE_NVP(df_curr_ee_color)); + a->Visit(DRAKE_NVP(visualize_c3_plan_best)); + a->Visit(DRAKE_NVP(c3_best_object_color)); + a->Visit(DRAKE_NVP(c3_best_ee_color)); + a->Visit(DRAKE_NVP(df_best_object_color)); + a->Visit(DRAKE_NVP(df_best_ee_color)); +} +}; diff --git a/examples/sampling_c3/reposition.cc b/examples/sampling_c3/reposition.cc new file mode 100644 index 0000000000..7eba9608ed --- /dev/null +++ b/examples/sampling_c3/reposition.cc @@ -0,0 +1,470 @@ +#include "reposition.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" + +namespace dairlib { + +using drake::trajectories::PiecewisePolynomial; + +namespace systems { + +// TODO @bibit further cleanup could require +/- z workspace limits instead of +// sampling_c3_options +Eigen::MatrixXd Reposition( + const int& n_q, + const int& n_x, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params, + const SamplingC3Options& sampling_c3_options) { + + Eigen::MatrixXd knots = Eigen::MatrixXd::Zero(n_x, N); + + Eigen::Vector3d current_ee_location = x_lcs.head(3); + Eigen::Vector3d current_object_location = x_lcs.segment(n_q-3, 3); + Eigen::Vector3d curr_to_goal_vec = repos_target - current_ee_location; + + // Get two unit vectors in the plane of the arc between the current and goal + // ee locations. + Eigen::Vector3d v1 = + (current_ee_location - current_object_location).normalized(); + Eigen::Vector3d v2 = (repos_target - current_object_location).normalized(); + // NOTE: Need to clamp between not quite (-1, 1) to avoid NaNs. + double travel_angle = std::acos(std::clamp(v1.dot(v2), -0.9999, 0.9999)); + + // Compute EE position errors to repositioning target. + double travel_distance = curr_to_goal_vec.norm(); + double xy_travel_distance = curr_to_goal_vec.head(2).norm(); + + // Use a straight line trajectory if close to the target. + RepositioningTrajectoryType traj_type = reposition_params.traj_type; + if ((travel_distance < + reposition_params.use_straight_line_traj_under_spline && + traj_type == RepositioningTrajectoryType::kSpline) || + ((traj_type == RepositioningTrajectoryType::kSpherical || + traj_type == RepositioningTrajectoryType::kCircular) && + travel_angle < reposition_params.use_straight_line_traj_within_angle) || + (traj_type == RepositioningTrajectoryType::kPiecewiseLinear && + xy_travel_distance < + reposition_params.use_straight_line_traj_under_piecewise_linear)) { + RepositionStraightLine( + knots, n_q, n_x, N, x_lcs, repos_target, dt, is_doing_c3, + finished_reposition_flag, reposition_params); + } + else if (traj_type == RepositioningTrajectoryType::kSpline) { + RepositionSpline( + knots, n_q, N, x_lcs, repos_target, dt, is_doing_c3, + finished_reposition_flag, reposition_params, sampling_c3_options); + } + else if (traj_type == RepositioningTrajectoryType::kSpherical) { + RepositionSpherical( + knots, n_q, N, x_lcs, repos_target, dt, is_doing_c3, + finished_reposition_flag, reposition_params, sampling_c3_options); + } + else if (traj_type == RepositioningTrajectoryType::kCircular) { + RepositionCircular( + knots, n_q, N, x_lcs, repos_target, dt, is_doing_c3, + finished_reposition_flag, reposition_params); + } + else if (traj_type == RepositioningTrajectoryType::kPiecewiseLinear) { + RepositionPiecewiseLinear( + knots, N, x_lcs, repos_target, dt, is_doing_c3, finished_reposition_flag, + reposition_params); + } + + return knots; +} + +void RepositionStraightLine( + Eigen::MatrixXd& knots, const int& n_q, const int& n_x, const int& N, + const Eigen::VectorXd& x_lcs, const Eigen::Vector3d& repos_target, + const double& dt, const bool& is_doing_c3, bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params) { + Eigen::Vector3d current_ee_location = x_lcs.head(3); + Eigen::Vector3d curr_to_goal_vec = repos_target - current_ee_location; + double travel_distance = curr_to_goal_vec.norm(); + + Eigen::VectorXd times = Eigen::VectorXd::Zero(2); + times[0] = 0; + // Ensure the times used to define PiecewisePolynomial are increasing. + double total_travel_time = travel_distance / reposition_params.speed; + times[1] = std::max(total_travel_time, 0.0001); + + Eigen::MatrixXd points = Eigen::MatrixXd::Zero(n_x, 2); + points.col(0) = x_lcs; + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = repos_target; + next_lcs_state.segment(n_q, 3) = Eigen::Vector3d::Zero(); + points.col(1) = next_lcs_state; + auto trajectory = + PiecewisePolynomial::FirstOrderHold(times, points); + + for (int i = 0; i < N; i++) { + double t_line = std::min((i)*dt, total_travel_time); + knots.col(i) = trajectory.value(t_line); + + // If one step gets to the goal, set finished_reposition_flag. + if (i == 1 && t_line >= total_travel_time && !is_doing_c3) { + finished_reposition_flag = true; + } + } +} + +void RepositionSpline( + Eigen::MatrixXd& knots, const int& n_q, const int& N, + const Eigen::VectorXd& x_lcs, const Eigen::Vector3d& repos_target, + const double& dt, const bool& is_doing_c3, bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params, + const SamplingC3Options& sampling_c3_options) { + Eigen::Vector3d current_ee_location = x_lcs.head(3); + Eigen::Vector3d current_object_location = x_lcs.segment(n_q-3, 3); + Eigen::Vector3d curr_to_goal_vec = repos_target - current_ee_location; + double travel_distance = curr_to_goal_vec.norm(); + + // Compute spline waypoints. + Eigen::Vector3d p0 = current_ee_location; + Eigen::Vector3d p3 = repos_target; + Eigen::Vector3d p1 = + current_ee_location + 0.25 * curr_to_goal_vec - current_object_location; + p1 = current_object_location + + reposition_params.spline_width * p1 / p1.norm(); + Eigen::Vector3d p2 = + current_ee_location + 0.75 * curr_to_goal_vec - current_object_location; + p2 = current_object_location + + reposition_params.spline_width * p2 / p2.norm(); + + for (int i = 0; i < N; i++) { + double total_travel_time = travel_distance / reposition_params.speed; + double t_spline = (i)*dt / total_travel_time; + t_spline = std::min(1.0, t_spline); // Don't overshoot end of the spline. + + // Set finished_reposition_flag if only one step is required. + if (i == 1 && t_spline == 1 && !is_doing_c3) { + finished_reposition_flag = true; + std::cout<<"WARNING! Spline finished repositioning in 1 step."< M_PI_2) { + v4 = -v4; + travel_angle = 2 * M_PI - travel_angle; + } + // Prevent getting stuck if the EE is 180 degrees around from the target. + if (travel_angle > 0.9 * M_PI) { + Eigen::Vector3d almost_v4 = v1; + almost_v4(2) += 1; + v3 = v1.cross(almost_v4.normalized()).normalized(); + v4 = v3.cross(v1).normalized(); + } + + // The arc is defined by the equation: + // x = x_c + r*cos(theta)*v1 + r*sin(theta)*v4 + // ...where theta should be [0, travel_angle] and r*dtheta should be the + // desired travel distance. + double dtheta = reposition_params.speed*dt / reposition_params.sphere_radius; + double step_size = reposition_params.speed * dt; + + knots.col(0) = x_lcs; + int i = 1; + // Handle the first leg: straight line from current EE location to waypoint1. + double dist_to_wp1 = (current_ee_location - waypoint1).norm(); + while ((i * step_size < dist_to_wp1) && (i < N)) { + Eigen::Vector3d straight_line_point = + current_ee_location + + i * step_size / dist_to_wp1 * (waypoint1 - current_ee_location); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Handle the second leg: arc from waypoint1 to waypoint2. + int leg1_i = i; + double dtheta0 = (i * step_size - dist_to_wp1) / step_size * dtheta; + while ((dtheta0 + (i - leg1_i) * dtheta < travel_angle) && (i < N)) { + Eigen::Vector3d arc_point = + current_object_location + + reposition_params.sphere_radius * + (std::cos(dtheta0 + (i - leg1_i) * dtheta) * v1 + + std::sin(dtheta0 + (i - leg1_i) * dtheta) * v4); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = arc_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Handle the last leg: straight line from waypoint2 to goal EE location. + int leg2_i = i; + double dstep = + (dtheta0 + (i - leg1_i) * dtheta - travel_angle) / dtheta * step_size; + double dist_wp2_to_goal = (waypoint2 - repos_target).norm(); + while ((dstep + (i - leg2_i) * step_size < dist_wp2_to_goal) && (i < N)) { + Eigen::Vector3d straight_line_point = + waypoint2 + (dstep + (i - leg2_i) * step_size) / dist_wp2_to_goal * + (repos_target - waypoint2); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Enforce minimum z height for end effector. + for (int j = 0; j < i; j++) { + if (knots(2, j) < sampling_c3_options.workspace_limits[2][3]) { + knots(2, j) = sampling_c3_options.workspace_limits[2][3]; + } + } + + // Fill in the rest of the knots with the goal EE location. + for (int j = i; j < N; j++) { + Eigen::Vector3d x_lcs_goal = x_lcs; + x_lcs_goal.head(3) = repos_target; + knots.col(j) = x_lcs_goal; + if (j == 1 && !is_doing_c3) { + finished_reposition_flag = true; + } + } +} + +void RepositionCircular( + Eigen::MatrixXd& knots, const int& n_q, const int& N, + const Eigen::VectorXd& x_lcs, const Eigen::Vector3d& repos_target, + const double& dt, const bool& is_doing_c3, bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params) { + Eigen::Vector3d current_ee_location = x_lcs.head(3); + Eigen::Vector3d current_object_location = x_lcs.segment(n_q-3, 3); + + // Project positions to the plane of the circle. + Eigen::Vector3d current_object_projection = current_object_location; + current_object_projection(2) = reposition_params.circle_height; + Eigen::Vector3d curr_ee_projection = current_ee_location; + curr_ee_projection(2) = reposition_params.circle_height; + Eigen::Vector3d best_sample_projection = repos_target; + best_sample_projection(2) = reposition_params.circle_height; + + Eigen::Vector3d v1 = + (curr_ee_projection - current_object_projection).normalized(); + Eigen::Vector3d v2 = + (best_sample_projection - current_object_projection).normalized(); + + // Compute travel angle. + double travel_angle = std::acos(v1.dot(v2)); + + // Define the waypoints for the circular trajectory. + Eigen::Vector3d waypoint1 = current_object_projection + + reposition_params.circle_radius * v1; + Eigen::Vector3d waypoint2 = current_object_projection + + reposition_params.circle_radius * v2; + + // Compute tangent vector to the circle at waypoint1. + Eigen::Vector3d v3 = v1.cross(v2).normalized(); + Eigen::Vector3d v4 = v3.cross(v1).normalized(); + + if (travel_angle > M_PI) { + travel_angle = 2 * M_PI - travel_angle; + v4 = -v4; + } + + // The arc is defined by the equation: x = x_c + r*cos(theta) + r*sin(theta) + // the relation between the linear velocity and the angular velocity is + // given by v = r*omega, where v is the linear velocity and omega is the + // angular velocity. The angular velocity is given by omega = v/r. The + // angular velocity is given by omega = dtheta/dt. Therefore, dtheta = + // v/r*dt. This is the increment in the angle in the time dt. + double dtheta = reposition_params.speed*dt / reposition_params.circle_radius; + double step_size = reposition_params.speed * dt; + + knots.col(0) = x_lcs; + int i = 1; + // Handle the first leg: straight line from current EE location to + // waypoint1. + double dist_to_wp1 = (current_ee_location - waypoint1).norm(); + while ((i * step_size < dist_to_wp1) && (i < N)) { + Eigen::Vector3d straight_line_point = + current_ee_location + + i * step_size / dist_to_wp1 * (waypoint1 - current_ee_location); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Handle the second leg: arc from waypoint1 to waypoint2. + int leg1_i = i; + double dtheta0 = (i * step_size - dist_to_wp1) / step_size * dtheta; + while (((i - leg1_i) * dtheta < travel_angle) && (i < N)) { + Eigen::Vector3d arc_point = + current_object_projection + + reposition_params.circle_radius * + (std::cos(dtheta0 + (i - leg1_i) * dtheta) * v1 + + std::sin(dtheta0 + (i - leg1_i) * dtheta) * v4); + arc_point(2) = reposition_params.circle_height; + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = arc_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Handle the last leg: straight line from waypoint2 to goal EE location. + int leg2_i = i; + double dstep = + (dtheta0 + (i - leg1_i) * dtheta - travel_angle) / dtheta * step_size; + double dist_wp2_to_goal = (waypoint2 - repos_target).norm(); + while ((dstep + (i - leg2_i) * step_size < dist_wp2_to_goal) && (i < N)) { + Eigen::Vector3d straight_line_point = + waypoint2 + (dstep + (i - leg2_i) * step_size) / dist_wp2_to_goal * + (repos_target - waypoint2); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Fill in the rest of the knots with the goal EE location. + for (int j = i; j < N; j++) { + Eigen::Vector3d x_lcs_goal = x_lcs; + x_lcs_goal.head(3) = repos_target; + knots.col(j) = x_lcs_goal; + if (j == 1 && !is_doing_c3) { + finished_reposition_flag = true; + } + } +} + +// The piecewise linear trajectory uses three legs: go up from current location +// to a fixed repositioning height, move in a straight line to right above the +// sample, then move down to the sample. +void RepositionPiecewiseLinear( + Eigen::MatrixXd& knots, const int& N, const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, const double& dt, + const bool& is_doing_c3, bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params) { + Eigen::Vector3d current_ee_location = x_lcs.head(3); + + // Define the waypoints for the three-leg repositioning. + Eigen::Vector3d waypoint_above_ee = current_ee_location; + waypoint_above_ee(2) = reposition_params.pwl_waypoint_height; + Eigen::Vector3d waypoint_above_sample = repos_target; + waypoint_above_sample(2) = reposition_params.pwl_waypoint_height; + + knots.col(0) = x_lcs; + int i = 1; + double step_size = reposition_params.speed * dt; + + // First leg: straight line from current EE location to waypoint_above_ee. + double dist_to_wp1 = (current_ee_location - waypoint_above_ee).norm(); + while ((i * step_size < dist_to_wp1) && (i < N)) { + Eigen::Vector3d straight_line_point = + current_ee_location + i * step_size / dist_to_wp1 * + (waypoint_above_ee - current_ee_location); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Second leg: straight line from waypoint_above_ee to + // waypoint_above_sample. + int leg1_i = i; + double dstep0 = i * step_size - dist_to_wp1; + double dist_to_wp2 = (waypoint_above_ee - waypoint_above_sample).norm(); + while ((dstep0 + (i - leg1_i) * step_size < dist_to_wp2) && (i < N)) { + Eigen::Vector3d straight_line_point = + waypoint_above_ee + (dstep0 + (i - leg1_i) * step_size) / dist_to_wp2 * + (waypoint_above_sample - waypoint_above_ee); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Third leg: straight line from waypoint_above_sample to + // repos_target. Really this doesn't even get used because it enters + // the use_straight_line condition before then. + int leg2_i = i; + double dstep1 = (i - leg1_i) * step_size - dist_to_wp2; + double dist_to_goal = (waypoint_above_sample - repos_target).norm(); + while ((dstep1 + (i - leg2_i) * step_size < dist_to_goal) && (i < N)) { + Eigen::Vector3d straight_line_point = + waypoint_above_sample + + (dstep1 + (i - leg2_i) * step_size) / dist_to_goal * + (repos_target - waypoint_above_sample); + + Eigen::VectorXd next_lcs_state = x_lcs; + next_lcs_state.head(3) = straight_line_point; + knots.col(i) = next_lcs_state; + i++; + } + + // Fill in the rest of the knots with the goal EE location. + for (int j = i; j < N; j++) { + Eigen::Vector3d x_lcs_goal = x_lcs; + x_lcs_goal.head(3) = repos_target; + knots.col(j) = x_lcs_goal; + if (j == 1 && !is_doing_c3) { + finished_reposition_flag = true; + } + } +} + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/reposition.h b/examples/sampling_c3/reposition.h new file mode 100644 index 0000000000..37eff8aba8 --- /dev/null +++ b/examples/sampling_c3/reposition.h @@ -0,0 +1,82 @@ +#include + +#include "examples/sampling_c3/parameter_headers/reposition_params.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_options.h" + +namespace dairlib { +namespace systems { + +/// Public function for generating a set of repositioning knot points. If the +/// repositioning trajectory gets to the target within a single timestep, +/// finished_reposition_flag is set to true. +Eigen::MatrixXd Reposition( + const int& n_q, + const int& n_x, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params, + const SamplingC3Options& sampling_c3_options +); + +/// Individual repositioning functions for each type of trajectory. Each sets +/// the knot points and finished_reposition_flag appropriately. +void RepositionStraightLine( + Eigen::MatrixXd& knots, + const int& n_q, + const int& n_x, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params +); +void RepositionSpline( + Eigen::MatrixXd& knots, + const int& n_q, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params, + const SamplingC3Options& sampling_c3_options); +void RepositionSpherical( + Eigen::MatrixXd& knots, + const int& n_q, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params, + const SamplingC3Options& sampling_c3_options); +void RepositionCircular( + Eigen::MatrixXd& knots, + const int& n_q, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params); +void RepositionPiecewiseLinear( + Eigen::MatrixXd& knots, + const int& N, + const Eigen::VectorXd& x_lcs, + const Eigen::Vector3d& repos_target, + const double& dt, + const bool& is_doing_c3, + bool& finished_reposition_flag, + const SamplingC3RepositionParams& reposition_params); + +} // namespace systems +} // namespace dairlib diff --git a/examples/sampling_c3/sampling_c3_utils.cc b/examples/sampling_c3/sampling_c3_utils.cc new file mode 100644 index 0000000000..3bfec51f72 --- /dev/null +++ b/examples/sampling_c3/sampling_c3_utils.cc @@ -0,0 +1,89 @@ +#include "sampling_c3_utils.h" + +#include "common/find_resource.h" +#include "drake/multibody/parsing/parser.h" + +namespace dairlib { + +using drake::geometry::SceneGraph; +using drake::math::RigidTransform; +using drake::multibody::ModelInstanceIndex; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; + + +ModelInstanceIndex AddFrankaToPlant(MultibodyPlant* plant, + SceneGraph* scene_graph, + const bool& include_ee, + const bool& include_ground_and_platform) { + Parser parser(plant, scene_graph); + parser.SetAutoRenaming(true); + + ModelInstanceIndex franka_index = parser.AddModelsFromUrl(kFrankaModel)[0]; + RigidTransform X_WI = RigidTransform::Identity(); + plant->WeldFrames(plant->world_frame(), + plant->GetFrameByName("panda_link0"), X_WI); + + if (include_ee) { + parser.AddModels(FindResourceOrThrow(kEndEffectorModel)); + RigidTransform T_EE_W = RigidTransform( + drake::math::RotationMatrix( + drake::math::RollPitchYaw(3.1415, 0, 0)), + kToolAttachmentFrame); + plant->WeldFrames(plant->GetFrameByName("panda_link7"), + plant->GetFrameByName("end_effector_flange"), T_EE_W); + } + + if (include_ground_and_platform) { + parser.AddModels(FindResourceOrThrow(kGroundModel)); + parser.AddModels(FindResourceOrThrow(kPlatformModel)); + + RigidTransform X_F_P = RigidTransform( + drake::math::RotationMatrix(), kFrankaToPlatformOffset); + RigidTransform X_F_G_franka = RigidTransform( + drake::math::RotationMatrix(), kFrankaToGroundOffset); + + plant->WeldFrames(plant->GetFrameByName("panda_link0"), + plant->GetFrameByName("ground"), X_F_G_franka); + plant->WeldFrames(plant->GetFrameByName("panda_link0"), + plant->GetFrameByName("platform"), X_F_P); + } + + return franka_index; +} + +drake::multibody::ModelInstanceIndex AddObjectToPlant( + drake::multibody::MultibodyPlant* plant, + drake::geometry::SceneGraph* scene_graph, + const std::string& object_model) { + Parser parser(plant, scene_graph); + parser.SetAutoRenaming(true); + return parser.AddModels(FindResourceOrThrow(object_model))[0]; +} + +void AddLCSModelsToPlant( + MultibodyPlant* plant, + SceneGraph* scene_graph, + const std::string& object_model, + const bool& include_end_effector_orientation) { + // Cannot currently handle end effector orientation (would just require new + // EE simple model with orientation DOFs). + DRAKE_ASSERT(!include_end_effector_orientation); + + Parser parser_lcs(plant); + parser_lcs.SetAutoRenaming(true); + parser_lcs.AddModels(kEndEffectorSimpleModel); + parser_lcs.AddModels(kGroundModel); + parser_lcs.AddModels(object_model); + + RigidTransform X_WI = RigidTransform::Identity(); + + RigidTransform X_W_G = RigidTransform( + drake::math::RotationMatrix(), kWorldToGroundOffset); + plant->WeldFrames(plant->world_frame(), + plant->GetFrameByName("base_link"), X_WI); + plant->WeldFrames(plant->world_frame(), + plant->GetFrameByName("ground"), X_W_G); +} + +} // namespace dairlib diff --git a/examples/sampling_c3/sampling_c3_utils.h b/examples/sampling_c3/sampling_c3_utils.h new file mode 100644 index 0000000000..3117661ee9 --- /dev/null +++ b/examples/sampling_c3/sampling_c3_utils.h @@ -0,0 +1,68 @@ +#pragma once + +#include +#include + +#include "drake/multibody/plant/multibody_plant.h" + +namespace dairlib { + +/// Constants for the Franka and end effector. +static constexpr const char* kFrankaModel = + "package://drake_models/franka_description/urdf/panda_arm.urdf"; +static constexpr const char* kEndEffectorModel = + "examples/sampling_c3/urdf/end_effector_full.urdf"; +static constexpr const char* kEndEffectorSimpleModel = + "examples/sampling_c3/urdf/end_effector_simple_model.urdf"; +static constexpr const char* kEndEffectorName = "end_effector_tip"; +static constexpr const char* kGroundModel = + "examples/sampling_c3/urdf/ground.urdf"; +static constexpr const char* kPlatformModel = + "examples/sampling_c3/urdf/platform.urdf"; + +/// This is the offset from the Panda's link7 frame to its flange where an end +/// effector can be attached. +static const Eigen::Vector3d kToolAttachmentFrame = {0, 0, 0.107}; + +static const Eigen::Vector3d kFrankaToGroundOffset = {0, 0, -0.029}; +static const Eigen::Vector3d kFrankaToPlatformOffset = {0, 0, -0.0145}; +static const Eigen::Vector3d kWorldToFrankaOffset = {0, 0, 0}; +static const Eigen::Vector3d kWorldToGroundOffset = kWorldToFrankaOffset + + kFrankaToGroundOffset; + +/// Add the Franka to a given multibody plant and scene graph. +/// @param plant a pointer to the MultibodyPlant +/// @param scene_graph a pointer to the SceneGraph--may be nullptr (or omitted) +/// @param include_ground_and_platform whether to include the ground and +/// platform in the plant. If false, only the Franka and end effector will be +/// added. +/// @return the ModelInstanceIndex of the Franka in the plant +drake::multibody::ModelInstanceIndex AddFrankaToPlant( + drake::multibody::MultibodyPlant* plant, + drake::geometry::SceneGraph* scene_graph = nullptr, + const bool& include_ee = true, + const bool& include_ground_and_platform = true); + +/// Add an object to a given multibody plant and scene graph. +/// @param plant a pointer to the MultibodyPlant +/// @param scene_graph a pointer to the SceneGraph--may be nullptr (or omitted) +/// @param object_model the model of the object to add to the plant +/// @return the ModelInstanceIndex of the object in the plant +drake::multibody::ModelInstanceIndex AddObjectToPlant( + drake::multibody::MultibodyPlant* plant, + drake::geometry::SceneGraph* scene_graph = nullptr, + const std::string& object_model = ""); + +/// Add LCS models to a given multibody plant and scene graph. +/// @param plant a pointer to the MultibodyPlant +/// @param scene_graph a pointer to the SceneGraph--may be nullptr (or omitted) +/// @param object_model the model of the object to add to the plant +/// @param include_end_effector_orientation whether to include the end effector +/// orientation as DOFs in the plant. True is currently unimplemented. +void AddLCSModelsToPlant( + drake::multibody::MultibodyPlant* plant, + drake::geometry::SceneGraph* scene_graph = nullptr, + const std::string& object_model = "", + const bool& include_end_effector_orientation = false); + +} // namespace dairlib diff --git a/examples/sampling_c3/shared_parameters/lcm_channels_hardware.yaml b/examples/sampling_c3/shared_parameters/lcm_channels_hardware.yaml new file mode 100644 index 0000000000..10d62aa082 --- /dev/null +++ b/examples/sampling_c3/shared_parameters/lcm_channels_hardware.yaml @@ -0,0 +1,43 @@ +# All messages are of type lcmt_timestamped_saved_traj unless otherwise noted. + +franka_state_channel: FRANKA_STATE # lcmt_robot_output +object_state_channel: OBJECT_STATE # lcmt_object_state +franka_input_channel: FRANKA_INPUT # lcmt_robot_input + +osc_channel: OSC_FRANKA # lcmt_robot_input +osc_debug_channel: OSC_DEBUG_FRANKA # lcmt_osc_output + +c3_actor_curr_plan_channel: C3_TRAJECTORY_ACTOR_CURR_PLAN +c3_object_curr_plan_channel: C3_TRAJECTORY_OBJECT_CURR_PLAN +c3_force_curr_channel: C3_FORCES_CURR # lcmt_c3_forces +c3_debug_output_curr_channel: C3_DEBUG_CURR # lcmt_c3_output + +c3_actor_best_plan_channel: C3_TRAJECTORY_ACTOR_BEST_PLAN +c3_object_best_plan_channel: C3_TRAJECTORY_OBJECT_BEST_PLAN +c3_force_best_channel: C3_FORCES_BEST # lcmt_c3_forces +c3_debug_output_best_channel: C3_DEBUG_BEST # lcmt_c3_output + +c3_trajectory_exec_actor_channel: C3_EXECUTION_TRAJECTORY_ACTOR +repos_trajectory_exec_actor_channel: REPOS_EXECUTION_TRAJECTORY_ACTOR + +tracking_trajectory_actor_channel: TRACKING_TRAJECTORY_ACTOR +tracking_trajectory_object_channel: TRACKING_TRAJECTORY_OBJECT + +c3_final_target_state_channel: C3_FINAL_TARGET # lcmt_c3_state +c3_target_state_channel: C3_TARGET # lcmt_c3_state +c3_actual_state_channel: C3_ACTUAL # lcmt_c3_state + +sample_locations_channel: SAMPLE_LOCATIONS +sample_costs_channel: SAMPLE_COSTS +sample_buffer_channel: SAMPLE_BUFFER # lcmt_sample_buffer + +dynamically_feasible_curr_actor_plan_channel: DYNAMICALLY_FEASIBLE_CURR_ACTOR_PLAN +dynamically_feasible_curr_plan_channel: DYNAMICALLY_FEASIBLE_CURR_PLAN +dynamically_feasible_best_actor_plan_channel: DYNAMICALLY_FEASIBLE_BEST_ACTOR_PLAN +dynamically_feasible_best_plan_channel: DYNAMICALLY_FEASIBLE_BEST_PLAN + +is_c3_mode_channel: IS_C3_MODE +target_generator_info_channel: TARGET_GEN_INFO +sampling_c3_debug_channel: SAMPLING_C3_DEBUG # lcmt_sampling_c3_debug + +radio_channel: SAMPLING_C3_RADIO # lcmt_radio_out diff --git a/examples/sampling_c3/shared_parameters/lcm_channels_simulation.yaml b/examples/sampling_c3/shared_parameters/lcm_channels_simulation.yaml new file mode 100644 index 0000000000..524747d8e9 --- /dev/null +++ b/examples/sampling_c3/shared_parameters/lcm_channels_simulation.yaml @@ -0,0 +1,43 @@ +# All messages are of type lcmt_timestamped_saved_traj unless otherwise noted. + +franka_state_channel: FRANKA_STATE_SIMULATION # lcmt_robot_output +object_state_channel: OBJECT_STATE_SIMULATION # lcmt_object_state +franka_input_channel: FRANKA_INPUT # lcmt_robot_input + +osc_channel: OSC_FRANKA # lcmt_robot_input +osc_debug_channel: OSC_DEBUG_FRANKA # lcmt_osc_output + +c3_actor_curr_plan_channel: C3_TRAJECTORY_ACTOR_CURR_PLAN +c3_object_curr_plan_channel: C3_TRAJECTORY_OBJECT_CURR_PLAN +c3_force_curr_channel: C3_FORCES_CURR # lcmt_c3_forces +c3_debug_output_curr_channel: C3_DEBUG_CURR # lcmt_c3_output + +c3_actor_best_plan_channel: C3_TRAJECTORY_ACTOR_BEST_PLAN +c3_object_best_plan_channel: C3_TRAJECTORY_OBJECT_BEST_PLAN +c3_force_best_channel: C3_FORCES_BEST # lcmt_c3_forces +c3_debug_output_best_channel: C3_DEBUG_BEST # lcmt_c3_output + +c3_trajectory_exec_actor_channel: C3_EXECUTION_TRAJECTORY_ACTOR +repos_trajectory_exec_actor_channel: REPOS_EXECUTION_TRAJECTORY_ACTOR + +tracking_trajectory_actor_channel: TRACKING_TRAJECTORY_ACTOR +tracking_trajectory_object_channel: TRACKING_TRAJECTORY_OBJECT + +c3_final_target_state_channel: C3_FINAL_TARGET # lcmt_c3_state +c3_target_state_channel: C3_TARGET # lcmt_c3_state +c3_actual_state_channel: C3_ACTUAL # lcmt_c3_state + +sample_locations_channel: SAMPLE_LOCATIONS +sample_costs_channel: SAMPLE_COSTS +sample_buffer_channel: SAMPLE_BUFFER # lcmt_sample_buffer + +dynamically_feasible_curr_actor_plan_channel: DYNAMICALLY_FEASIBLE_CURR_ACTOR_PLAN +dynamically_feasible_curr_plan_channel: DYNAMICALLY_FEASIBLE_CURR_PLAN +dynamically_feasible_best_actor_plan_channel: DYNAMICALLY_FEASIBLE_BEST_ACTOR_PLAN +dynamically_feasible_best_plan_channel: DYNAMICALLY_FEASIBLE_BEST_PLAN + +is_c3_mode_channel: IS_C3_MODE +target_generator_info_channel: TARGET_GEN_INFO +sampling_c3_debug_channel: SAMPLING_C3_DEBUG # lcmt_sampling_c3_debug + +radio_channel: SAMPLING_C3_RADIO # lcmt_radio_out diff --git a/examples/sampling_c3/shared_parameters/osc_params.yaml b/examples/sampling_c3/shared_parameters/osc_params.yaml new file mode 100644 index 0000000000..9682517970 --- /dev/null +++ b/examples/sampling_c3/shared_parameters/osc_params.yaml @@ -0,0 +1,77 @@ +### Parameters from OSCGains ### +controller_frequency: 1000 +w_input: 0.00 +w_input_reg: 0.0 +w_accel: 0.00001 +w_soft_constraint: 0.0 +w_lambda: 0.0 +impact_threshold: 0.000 +impact_tau: 0.000 +mu: 0.4615 + +W_accel: [ 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01] +W_input_reg: [ 1, 1, 1, 1, 1, 1, 10] +W_lambda_c_reg: [ 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01, + 0.001, 0.001, 0.01 ] +W_lambda_h_reg: [ 0.001, 0.001, 0.001, + 0.001, 0.001, 0.001 ] + + +### Additional parameters for SamplingC3OSCParams ### + +# Two teleoperation modes: 1) locked EE neutral position, where xbox controls +# perturb the EE; and 2) xbox controls move the EE to a new neutral position. +neutral_position: [0.4276197, 0.19295175, 0.12756625] +teleop_neutral_position: true + +# If using teleop_neutral_position, it's beneficial for the x/y/z_scales to be +# relatively small, i.e. 0.0002 works well (compared to 0.2 for the locked +# neutral position scheme). +x_scale: 0.0002 +y_scale: 0.0002 +z_scale: 0.0002 + +end_effector_acceleration: 10 +track_end_effector_orientation: false +cancel_gravity_compensation: false +enforce_acceleration_constraints: false +publish_debug_info: true + +w_elbow: 1 +elbow_kp: 200 +elbow_kd: 10 + +# This is the weight matrix for the end effector position tracking. +EndEffectorW: + [1, 0, 0, + 0, 1, 0, + 0, 0, 1] +EndEffectorKp: + [ 200, 0, 0, + 0, 200, 0, + 0, 0, 200 ] +EndEffectorKd: + [ 20, 0, 0, + 0, 20, 0, + 0, 0, 20 ] +EndEffectorRotW: + [ 10, 0, 0, + 0, 10, 0, + 0, 0, 10 ] +EndEffectorRotKp: + [ 800, 0, 0, + 0, 800, 0, + 0, 0, 800] +EndEffectorRotKd: + [ 40, 0, 0, + 0, 40, 0, + 0, 0, 40] +# This is the weight matrix for the end effector force tracking. +# The end effector forces in the OSC are called lambdas but are really tracking +# the forces at the end effector or the u_sol we get in c3. +LambdaEndEffectorW: + [ 1, 0, 0, + 0, 1, 0, + 0, 0, 1 ] diff --git a/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml b/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml new file mode 100644 index 0000000000..39407d322d --- /dev/null +++ b/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml @@ -0,0 +1,27 @@ +print_to_console: 0 +log_file_name: "" +int_options: + max_iter: 1000 + linsys_solver: 0 + verbose: 0 + warm_start: 1 + scaling: 1 + adaptive_rho: 1 + polish: 1 + polish_refine_iter: 1 + scaled_termination: 1 + check_termination: 25 +double_options: + rho: 0.001 + sigma: 1e-6 + eps_abs: 1e-5 + eps_rel: 1e-5 + eps_prim_inf: 1e-5 + eps_dual_inf: 1e-5 + alpha: 1.6 + delta: 1e-6 + adaptive_rho_interval: 0 + adaptive_rho_tolerance: 5 + adaptive_rho_fraction: 0.4 + time_limit: 0 +string_options: {} diff --git a/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml b/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml new file mode 100644 index 0000000000..741647456e --- /dev/null +++ b/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml @@ -0,0 +1,27 @@ +print_to_console: 0 +log_file_name: "" +int_options: + max_iter: 1000 + linsys_solver: 0 + verbose: 0 + warm_start: 1 + scaling: 1 + adaptive_rho: 1 + polish: 1 + polish_refine_iter: 1 + scaled_termination: 1 + check_termination: 100 +double_options: + rho: 0.1 + sigma: 1e-6 + eps_abs: 1e-5 + eps_rel: 1e-5 + eps_prim_inf: 1e-5 + eps_dual_inf: 1e-5 + alpha: 1.6 + delta: 1e-6 + adaptive_rho_interval: 0 + adaptive_rho_tolerance: 5 + adaptive_rho_fraction: 0.4 + time_limit: 0 +string_options: {} diff --git a/examples/sampling_c3/start_logging.py b/examples/sampling_c3/start_logging.py new file mode 100644 index 0000000000..726b2e737d --- /dev/null +++ b/examples/sampling_c3/start_logging.py @@ -0,0 +1,102 @@ +import subprocess +import os +import os.path as op +import glob +import codecs +from datetime import date +import sys +import yaml + + +def main(log_type, demo_name): + curr_date = date.today().strftime("%m_%d_%y") + year = date.today().strftime("%Y") + logdir = f"/mnt/data2/bibit/logs/{year}/{curr_date}" + dair = op.abspath(op.join(op.dirname(__file__), "../../")) + + if not op.isdir(logdir): + os.mkdir(logdir) + + # Hardcoded sampling_c3_controller_params path. + sampling_c3_controller_params_path = op.join( + dair, "examples", "sampling_c3", demo_name, "parameters", + "sampling_c3_controller_params.yaml" + ) + + with open(sampling_c3_controller_params_path) as f: + controller_params = yaml.load(f, Loader=yaml.FullLoader) + + sampling_c3_params_path = op.join(dair, controller_params['sampling_c3_options_file']) + repos_params_path = op.join(dair, controller_params['reposition_params_file']) + progress_params_path = op.join(dair, controller_params['progress_params_file']) + sampling_params_path = op.join(dair, controller_params['sampling_params_file']) + goal_params_path = op.join(dair, controller_params['goal_params_file']) + sim_params_path = op.join(dair, controller_params['sim_params_file']) + osc_params_path = op.join(dair, controller_params['osc_params_file']) + osqp_params_path = op.join(dair, controller_params['osqp_settings_file']) + osc_qp_params_path = op.join(dair, controller_params['osc_qp_settings_file']) + + with open(sim_params_path) as f: + sim_params = yaml.load(f, Loader=yaml.FullLoader) + + # c3 gains, sampling c3 options, sampling, osc, sim, goal + + object_c3_urdf = op.join(dair, controller_params['object_model']) + object_sim_urdf = op.join(dair, sim_params['object_model']) + + # NOTE: must match kEndEffectorSimpleModel in sampling_c3_utils.h + ee_simple_model_urdf = op.join( + dair, "examples/sampling_c3/urdf/end_effector_simple_model.urdf") + + git_diff = subprocess.check_output(['git', 'diff'], cwd=dair) + commit_tag = subprocess.check_output(['git', 'rev-parse', 'HEAD'], cwd=dair) + + os.chdir(logdir) + + try: + directories = glob.glob(op.join(logdir, "*")) + directory_names = [op.basename(d) for d in directories if op.isdir(d)] + last_log = max([int(name) for name in directory_names if name.isdigit()]) + log_num = str(last_log+1).zfill(6) + except: + log_num = str(0).zfill(6) + + if log_type == 'hw': + with open('commit_tag%s' % log_num, 'w') as f: + f.write(str(commit_tag)) + f.write("\n\ngit diff:\n\n") + f.write(codecs.getdecoder("unicode_escape")(git_diff)[0]) + if not op.isdir(log_num): + os.mkdir(log_num) + + os.chdir(log_num) + logname = f'{log_type}log-{log_num}' + + # Parameter files. + subprocess.run(['cp',sampling_c3_controller_params_path, f'sampling_c3_controller_params_{log_num}.yaml']) + subprocess.run(['cp',sampling_c3_params_path, f'sampling_c3_params_{log_num}.yaml']) + subprocess.run(['cp',repos_params_path, f'repos_params_{log_num}.yaml']) + subprocess.run(['cp',progress_params_path, f'progress_params_{log_num}.yaml']) + subprocess.run(['cp',sampling_params_path, f'sampling_params_{log_num}.yaml']) + subprocess.run(['cp',goal_params_path, f'goal_params_{log_num}.yaml']) + subprocess.run(['cp',sim_params_path, f'sim_params_{log_num}.yaml']) + subprocess.run(['cp',osc_params_path, f'osc_params_{log_num}.yaml']) + subprocess.run(['cp',osqp_params_path, f'osqp_params_{log_num}.yaml']) + subprocess.run(['cp',osc_qp_params_path, f'osc_qp_params_{log_num}.yaml']) + + # URDFs/SDFs with original file extensions. + ee_simple_model_ext = op.splitext(ee_simple_model_urdf)[1] + object_c3_ext = op.splitext(object_c3_urdf)[1] + object_sim_ext = op.splitext(object_sim_urdf)[1] + subprocess.run(['cp', ee_simple_model_urdf, f'ee_simple_model_urdf_{log_num}{ee_simple_model_ext}']) + subprocess.run(['cp', object_c3_urdf, f'object_c3_urdf_{log_num}{object_c3_ext}']) + subprocess.run(['cp', object_sim_urdf, f'object_sim_urdf_{log_num}{object_sim_ext}']) + + # Begin logging. + subprocess.run(['/opt/lcm/1.4.0/bin/lcm-logger', '-f', logname]) + + +if __name__ == '__main__': + log_type = sys.argv[1] + demo_name = sys.argv[2] + main(log_type, demo_name) diff --git a/examples/sampling_c3/test/BUILD.bazel b/examples/sampling_c3/test/BUILD.bazel new file mode 100644 index 0000000000..2ad6b352bb --- /dev/null +++ b/examples/sampling_c3/test/BUILD.bazel @@ -0,0 +1,25 @@ +cc_binary( + name = "lcm_log_loader", + srcs = [ + "lcm_log_loader.cc", + ], + deps = [ + "@gflags", + "//common:find_resource", + "//systems/controllers:sampling_c3_controller", + "//lcm:lcm_trajectory_saver", + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems:system_utils", + "//solvers:c3", + "//solvers:lcs", + "//solvers:c3_output", + "//solvers:solver_options_io", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "//examples/sampling_c3:sampling_c3_utils", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:franka_sim_params", + "//examples/sampling_c3/parameter_headers:sampling_c3_options", + ], +) diff --git a/examples/sampling_c3/test/cost_visualization.py b/examples/sampling_c3/test/cost_visualization.py new file mode 100644 index 0000000000..b140329796 --- /dev/null +++ b/examples/sampling_c3/test/cost_visualization.py @@ -0,0 +1,161 @@ +"""Script to visualize the costs of samples. Requires the drake_env virtual +environment located at workspace/drake_env, i.e.: + +source ~/workspace/drake_env/bin/activate + +Visualizes the costs and configurations exported by lcm_log_loader.cc when the +DO_SAMPLE_VISUALIZATIONS is #defined. That log loading script writes files to +the test/tmp directory. This script loads those files and visualizes the +information in meshcat. + +Run this script with the following command: +python examples/sampling_c3/test/cost_visualization.py jacktoy +""" +import argparse +import matplotlib.pyplot as plt +import numpy as np +import os.path as op + +from pydrake.common.eigen_geometry import Quaternion +from pydrake.geometry import MeshcatVisualizer, MeshcatVisualizerParams, \ + SceneGraph, StartMeshcat +from pydrake.math import RigidTransform, RotationMatrix +from pydrake.multibody.plant import MultibodyPlant +from pydrake.multibody.parsing import Parser +from pydrake.multibody.tree import FixedOffsetFrame +from pydrake.perception import BaseField, Fields, PointCloud +from pydrake.systems.analysis import Simulator +from pydrake.systems.framework import DiagramBuilder +from pydrake.visualization._triad import AddFrameTriadIllustration + + +def costs_to_colors(costs): + """Returns (3, N) array of RGB colors based on costs.""" + # Try doing a map that will make the good samples more obvious. + normalized_costs = (costs - costs.min()) / (costs.max() - costs.min()) + mapped = np.arctan(normalized_costs * 100) / (np.pi/2) + mapped /= mapped.max() + colormap = plt.cm.RdYlGn.reversed() + rgba_colors = colormap(mapped) + return rgba_colors[:, :3].T * 255 + + +def visualize(demo_name): + + DAIRLIB_DIR = op.abspath(op.join(op.dirname(__file__), '../../../')) + print(f"DAIRLIB_DIR: {DAIRLIB_DIR}") + LOAD_DIR = op.join(DAIRLIB_DIR, f'examples/sampling_c3/{demo_name}/test/tmp') + + # Load the data exported by the LCM log loader. + x_lcs_samples = np.loadtxt(op.join(LOAD_DIR, 'x_lcs_samples.txt')) + costs = np.loadtxt(op.join(LOAD_DIR, 'costs.txt')) + x_lcs_desired = np.loadtxt(op.join(LOAD_DIR, 'x_lcs_desired.txt')) + p_world_to_franka = np.loadtxt(op.join(LOAD_DIR, 'p_world_to_franka.txt')) + p_franka_to_ground = np.loadtxt(op.join(LOAD_DIR, 'p_franka_to_ground.txt')) + + # Center the jack at the origin for faster panning/viewing in meshcat. + jack_xy = x_lcs_samples[0, 7:9].copy() + x_lcs_samples[:, :2] -= jack_xy + x_lcs_samples[:, 7:9] -= jack_xy + x_lcs_desired[:2] -= jack_xy + x_lcs_desired[7:9] -= jack_xy + + # Start building the scene for visualization in meshcat. + builder = DiagramBuilder() + plant = builder.AddSystem(MultibodyPlant(time_step=0.0)) + scene_graph = builder.AddSystem(SceneGraph()) + plant.RegisterAsSourceForSceneGraph(scene_graph) + + ee_urdf = op.join(DAIRLIB_DIR, 'examples/sampling_c3/urdf/end_effector_simple_model.urdf') + ground_urdf = op.join(DAIRLIB_DIR, 'examples/sampling_c3/urdf/ground.urdf') + if demo_name == "jacktoy": + jack_urdf = op.join(DAIRLIB_DIR, 'examples/sampling_c3/urdf/jack.sdf') + triad_body_name = "capsule_1" + quaternion_input = Quaternion(x_lcs_desired[3:7]/np.linalg.norm(x_lcs_desired[3:7])) + elif demo_name == "push_t": + jack_urdf = op.join(DAIRLIB_DIR, 'examples/sampling_c3/urdf/T_vertical.sdf') + triad_body_name = "vertical_link" + quaternion_input = Quaternion(x_lcs_desired[3:7]/np.linalg.norm(x_lcs_desired[3:7])) + elif demo_name == "ball_rolling": + jack_urdf = op.join(DAIRLIB_DIR, 'examples/sampling_c3/urdf/sphere.urdf') + triad_body_name = "sphere" + quaternion_input = Quaternion(x_lcs_desired[3:7]/np.linalg.norm(x_lcs_desired[3:7])) + elif demo_name == "box_topple": + jack_urdf = op.join(DAIRLIB_DIR, 'examples/sampling_c3/urdf/box.sdf') + triad_body_name = "box" + quaternion_input = Quaternion(x_lcs_desired[3:7]/np.linalg.norm(x_lcs_desired[3:7])) + else: + raise ValueError(f"Unknown demo_name: {demo_name}") + + # Add the models. + urdf_path = jack_urdf + Parser(plant).AddModels(ee_urdf) + Parser(plant).AddModels(jack_urdf) + Parser(plant).AddModels(ground_urdf) + + p_world_to_ground = p_world_to_franka + p_franka_to_ground + X_W_Ground = RigidTransform(RotationMatrix(), p_world_to_ground) + quaternion_input = Quaternion(x_lcs_desired[3:7]/np.linalg.norm(x_lcs_desired[3:7])) + X_WGoal = RigidTransform( + quaternion=quaternion_input, p=x_lcs_desired[7:10]) + plant.WeldFrames( + plant.world_frame(), plant.GetFrameByName("base_link"), RigidTransform()) + plant.WeldFrames( + plant.world_frame(), plant.GetFrameByName("ground"), X_W_Ground) + plant.AddFrame( + FixedOffsetFrame(name="goal", P=plant.world_frame(), X_PF=X_WGoal)) + + # Add some triads for the goal and current configuration. + AddFrameTriadIllustration( + plant=plant, scene_graph=scene_graph, body=plant.GetBodyByName(triad_body_name), + length=0.1, radius=0.005, opacity=1.0) + AddFrameTriadIllustration( + plant=plant, scene_graph=scene_graph, frame=plant.GetFrameByName("goal"), + length=0.1, radius=0.005, opacity=1.0) + plant.Finalize() + + builder.Connect(plant.get_geometry_pose_output_port(), + scene_graph.get_source_pose_port(plant.get_source_id())) + builder.Connect(scene_graph.get_query_output_port(), + plant.get_geometry_query_input_port()) + + # Add a point cloud to represent the samples and their associated costs. + fields = Fields(BaseField.kXYZs | BaseField.kRGBs) + point_cloud = PointCloud(new_size=costs.shape[0], fields=fields) + point_cloud.mutable_xyzs()[:] = x_lcs_samples[:, :3].T + point_cloud.mutable_rgbs()[:] = costs_to_colors(costs) + + # Add meshcat visualization. + meshcat = StartMeshcat() + meshcat.Delete() + visualizer = MeshcatVisualizer.AddToBuilder( + builder, scene_graph, meshcat, MeshcatVisualizerParams() + ) + print(f"Meshcat is running at: {meshcat.web_url()}") + + meshcat.SetObject(path="point_cloud", cloud=point_cloud, point_size=0.005) + + # Build the diagram. + diagram = builder.Build() + context = diagram.CreateDefaultContext() + + # Start a simulator. + sim = Simulator(diagram) + sim.set_publish_at_initialization(True) + sim.set_publish_every_time_step(True) + sim.Initialize() + + # Set the pose of the model. + plant_context = plant.GetMyMutableContextFromRoot(sim.get_mutable_context()) + plant.SetPositionsAndVelocities(plant_context, x_lcs_samples[0]) + sim.AdvanceTo(0) + + breakpoint() + + +if __name__ == "__main__": + parser = argparse.ArgumentParser(description="Visualize costs of samples in meshcat.") + parser.add_argument("demo_name", choices=["jacktoy","ball_rolling", "box_topple", "push_t"], + help="Name of the demo to visualize") + args = parser.parse_args() + visualize(args.demo_name) diff --git a/examples/sampling_c3/test/lcm_log_loader.cc b/examples/sampling_c3/test/lcm_log_loader.cc new file mode 100644 index 0000000000..269d11995b --- /dev/null +++ b/examples/sampling_c3/test/lcm_log_loader.cc @@ -0,0 +1,1225 @@ +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "dairlib/lcmt_c3_state.hpp" +#include "dairlib/lcmt_object_state.hpp" +#include "dairlib/lcmt_radio_out.hpp" +#include "dairlib/lcmt_robot_output.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "examples/sampling_c3/sampling_c3_utils.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/franka_sim_params.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_options.h" +#include "solvers/c3_output.h" +#include "solvers/lcs_factory.h" +#include "systems/controllers/sampling_based_c3_controller.h" +#include "systems/framework/timestamped_vector.h" +#include "systems/system_utils.h" + +// To use this file, run as follows based on the demo name: +// bazel-bin/examples/sampling_c3/test/lcm_log_loader --demo_name=jacktoy +// /mnt/data2/sharanya/logs/2025/05_07_25/000000 1 +// bazel-bin/examples/sampling_c3/test/lcm_log_loader --demo_name=push_t +// /mnt/data2/sharanya/logs/2025/05_07_25/000001 1 +// bazel-bin/examples/sampling_c3/test/lcm_log_loader --demo_name=box_topple +// /mnt/data2/sharanya/logs/2025/05_07_25/000002 1 + +/////// WARNING!! ////// +// This version of the log loader will not work for logs collected post March +// 31st, 2025 due to the changes made to sampling_c3_controller_params.h as per +// this commit where the safe params were removed: +// https://github.com/DAIRLab/dairlib/commit/c381e5cd89500cfd3d702ada6d3c659fe8bbb43e#diff-a6f0508e6ca4588155b0f75ba718f66042ed9d05ee1b7727a963820c6fcf0cca +// This is because the log loader is trying to read a vector of c3_options files +// which is no longer the case. + +DEFINE_string(demo_name, "unkown", + "Demo within sampling_c3; used to find controller params file"); + +// Uncomment this line to output cost information for evenly spaced samples. +// #define DO_SAMPLE_VISUALIZATIONS + +// Sample grid locations. +#define N_VERTICAL 100 +#define N_HORIZONTAL 100 + +#define N_Q 10 +#define N_V 9 + +namespace dairlib { + +using dairlib::systems::TimestampedVector; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::math::RigidTransform; +using drake::multibody::AddMultibodyPlantSceneGraph; +using drake::multibody::MultibodyPlant; +using drake::multibody::Parser; +using drake::systems::DiagramBuilder; +using solvers::LCSFactory; + +// Declare function that will generate samples around T location. +std::vector GenerateEvenlySpacedSamplesAroundT( + const Eigen::VectorXd& x_lcs, + const SamplingParams& sampling_params, const int& num_vertical, + const int& num_horizontal); + +// Declare function that will generate samples around jack location. +std::pair, std::vector> +GenerateEvenlySpacedSamplesAroundJack( + const Eigen::VectorXd& x_lcs, + const SamplingParams& sampling_params, const int& num_vertical, + const int& num_horizontal); + +// Declare helper function that will print a vector of Eigen::VectorXd in a +// Python-friendly format to define a numpy array. +void PythonFriendlyVectorOfVectorXdPrint( + char* name, std::vector some_vector); + +// Declare helper function that will write a vector of Eigen::VectorXd to a txt +// file such that it can be loaded from a python file via np.loadtxt. +void PythonFriendlyVectorOfVectorXdToFile( + char* name, std::vector some_vector); + +int DoMain(int argc, char* argv[]) { + gflags::ParseCommandLineFlags(&argc, &argv, true); + if (argc != 3) { + std::cerr << "Usage: " << argv[0] + << " --demo_name={DEMO} " + << std::endl; + return 1; + } + std::cout << "LOG LOADER FOR PUSH T EXAMPLE" << std::endl; + const std::string& log_folder = std::string(argv[1]); + const double& time_into_log = std::stod(std::string(argv[2])); + + // Turn the folder into a file path. + std::string log_number = + log_folder.substr(log_folder.find_last_of("/") + 1, 6); + std::string log_filepath = log_folder + "/simlog-" + log_number; + std::cout << "Parsing log at: " << log_filepath << std::endl; + + // Set the start time. + // This time is how many seconds into the log we want to start processing + // information. Convert to microseconds. + const int64_t time_into_log_in_microsecs = time_into_log * 1e6; + + std::cout << "time into log in seconds: " << time_into_log << std::endl; + std::cout << " in microseconds: " << time_into_log_in_microsecs << std::endl; + + // Load the recorded parameters: (1/6) Controller parameters. + // TODO @bibit these need to be loaded from the stored log copy, not from the + // filepath in the controller params + std::string sampling_c3_controller_params_path = log_filepath; + std::string to_replace = "simlog-"; + std::string sampling_c3_controller_params_path_replacement = + "sampling_c3_controller_params_"; + sampling_c3_controller_params_path.replace( + sampling_c3_controller_params_path.find(to_replace), to_replace.length(), + sampling_c3_controller_params_path_replacement); + SamplingC3ControllerParams controller_params = + drake::yaml::LoadYamlFile( + sampling_c3_controller_params_path + ".yaml"); + std::cout << "path of sampling_c3_controller_params loaded: " + << sampling_c3_controller_params_path << std::endl; + + // (2/6) C3 parameters. + std::string c3_gains_path = log_filepath; + std::string c3_gains_path_replacement = "c3_gains_"; + c3_gains_path.replace(c3_gains_path.find(to_replace), to_replace.length(), + c3_gains_path_replacement); + C3Options c3_options; + c3_options = drake::yaml::LoadYamlFile(c3_gains_path + ".yaml"); + + // Sampling c3 options. + // WARNING: ALL LOGS PRIOR TO MAY 15, 2025 WILL NOT HAVE A SAMPLING C3 + // OPTIONS. PLEASE USE AN OLDER VERSION OF THIS FILE TO LOAD LOGS COLLECTED + // PRIOR TO MAY 15, 2025. + std::string sampling_c3_options_path = log_filepath; + std::string sampling_c3_options_path_replacement = "sampling_c3_options_"; + sampling_c3_options_path.replace(sampling_c3_options_path.find(to_replace), + to_replace.length(), + sampling_c3_options_path_replacement); + SamplingC3Options sampling_c3_options = + drake::yaml::LoadYamlFile(sampling_c3_options_path + + ".yaml"); + // NOTE: can temporarily hard code many more ADMM iterations or other + // changes here, e.g.: + // c3_options.admm_iter = 8; + + // example of updating Q to test effect of changing cost weights on C3 solve + // std::vector new_q {0.01, 0.01, 0.01, + // 0.1, 0.1, 0.1, 0.1, + // 250, 250, 250, + // 2.5, 2.5, 2.5, + // 0.05, 0.05, 0.05, + // 0.05, 0.05, 0.05}; + // c3_options.q_vector_pose = new_q; + // Eigen::VectorXd q_pose = Eigen::Map( + // c3_options.q_vector_pose.data(), c3_options.q_vector_pose.size()); + // c3_options.Q_pose = c3_options.w_Q * q_pose.asDiagonal(); + // std::cout<<"Updated Q"<(sim_params_path + ".yaml"); + + // (4/6) Sampling parameters. + std::string sampling_params_path = log_filepath; + std::string sampling_params_path_replacement = "sampling_params_"; + sampling_params_path.replace(sampling_params_path.find(to_replace), + to_replace.length(), + sampling_params_path_replacement); + SamplingParams sampling_params = drake::yaml::LoadYamlFile( + sampling_params_path + ".yaml"); + // NOTE: hard code the number of additional samples to be 0, since this + // script is just to debug a single C3 solve. + sampling_params.num_additional_samples_c3 = 0; + sampling_params.num_additional_samples_repos = 0; + + // (5/6) Progress parameters. + std::string progress_params_path = log_filepath; + std::string progress_params_path_replacement = "progress_params_"; + progress_params_path.replace(progress_params_path.find(to_replace), + to_replace.length(), + progress_params_path_replacement); + SamplingC3ProgressParams progress_params = + drake::yaml::LoadYamlFile( + progress_params_path + ".yaml"); + + // (6/6) dummy reposition parameters (should not matter). + SamplingC3RepositionParams reposition_params; + + // Create an instance of the LCM log handler. + lcm::LCM lcm; + lcm::LogFile log_file(log_filepath, "r"); + // Keep track of the timestamp of the first message in the log. + int64_t u_init_time = 0; + const lcm::LogEvent* first_event = log_file.readNextEvent(); + if (first_event != nullptr) { + u_init_time = first_event->timestamp; + std::cout << "Initial event timestamp (s): " << u_init_time / 1e6 + << std::endl; + } else { + std::cerr << "Error: No events in the log!" << std::endl; + return 1; // Exit if no events are found + } + + // Now seek to the time we want to start processing the log. That is, + // time_into_log_in_microseconds offset from the first message in the log. + log_file.seekToTimestamp(time_into_log_in_microsecs + u_init_time); + + const lcm::LogEvent* event; + + // Read the log until the first C3_ACTUAL message after the start time. + // Prepare to grab all desired message information. + std::set channels_to_check = { + "C3_ACTUAL", + "C3_TARGET", + "C3_FINAL_TARGET", + "DYNAMICALLY_FEASIBLE_CURR_PLAN", + "DYNAMICALLY_FEASIBLE_CURR_ACTOR_PLAN", + "C3_DEBUG_CURR", + "IS_C3_MODE", + "SAMPLE_LOCATIONS", + "SAMPLE_COSTS", + "DYNAMICALLY_FEASIBLE_BEST_PLAN", + "DYNAMICALLY_FEASIBLE_BEST_ACTOR_PLAN"}; + + Eigen::VectorXd x_lcs_actual = Eigen::VectorXd::Zero(19); + Eigen::VectorXd x_lcs_desired = Eigen::VectorXd::Zero(19); + Eigen::VectorXd x_lcs_final_desired = Eigen::VectorXd::Zero(19); + Eigen::MatrixXd dyn_feas_curr_plan_obj_pos = + Eigen::MatrixXd::Zero(3, c3_options.N + 1); + Eigen::MatrixXd dyn_feas_curr_plan_ee_pos = + Eigen::MatrixXd::Zero(3, c3_options.N + 1); + Eigen::MatrixXd dyn_feas_curr_plan_obj_orientation = + Eigen::MatrixXd::Zero(4, c3_options.N + 1); + Eigen::MatrixXd dyn_feas_best_plan_obj_pos = + Eigen::MatrixXd::Zero(3, c3_options.N + 1); + Eigen::MatrixXd dyn_feas_best_plan_ee_pos = + Eigen::MatrixXd::Zero(3, c3_options.N + 1); + Eigen::MatrixXd dyn_feas_best_plan_obj_orientation = + Eigen::MatrixXd::Zero(4, c3_options.N + 1); + + Eigen::MatrixXd u_sol = Eigen::MatrixXd::Zero(3, c3_options.N); + Eigen::MatrixXd x_sol = Eigen::MatrixXd::Zero(19, c3_options.N); + Eigen::MatrixXd lambda_sol = Eigen::MatrixXd::Zero(16, c3_options.N); + Eigen::MatrixXd w_sol = Eigen::MatrixXd::Zero(38, c3_options.N); + Eigen::MatrixXd delta_sol = Eigen::MatrixXd::Zero(38, c3_options.N); + + // Collect the sample locations + std::vector sample_locations_in_log; + std::vector sample_costs_in_log; + + bool is_c3_mode = false; + bool is_c3_mode_set = false; + + while ((event = log_file.readNextEvent()) != nullptr) { + // Offset the time stamp by the initial time for better readability. + int64_t adjusted_utimestamp = event->timestamp - u_init_time; + + if (event->channel == "C3_ACTUAL") { + if (event->timestamp > time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_c3_state message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received C3_ACTUAL message in seconds utime: " + << (message.utime) / 1e6 << " and event timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; i < 19; i++) { + x_lcs_actual(i) = static_cast(message.state[i]); + } + } else { + std::cerr << "Failed to decode C3_ACTUAL message" << std::endl; + } + } + } else if (event->channel == "C3_TARGET") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_c3_state message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received C3_TARGET message in seconds utime: " + << (message.utime) / 1e6 << " and event timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; i < 19; i++) { + x_lcs_desired(i) = static_cast(message.state[i]); + } + } else { + std::cerr << "Failed to decode C3_TARGET message" << std::endl; + } + } + } else if (event->channel == "C3_FINAL_TARGET") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_c3_state message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received C3_FINAL_TARGET message in seconds utime: " + << (message.utime) / 1e6 << " and event timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; i < 19; i++) { + x_lcs_final_desired(i) = static_cast(message.state[i]); + } + } else { + std::cerr << "Failed to decode C3_FINAL_TARGET message" << std::endl; + } + } + } else if (event->channel == "DYNAMICALLY_FEASIBLE_CURR_PLAN") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received DYNAMICALLY_FEASIBLE_CURR_PLAN message in " + << "seconds utime: " << (message.utime) / 1e6 + << " and event " << "timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; i < 4; i++) { + for (int j = 0; j < c3_options.N + 1; j++) { + dyn_feas_curr_plan_obj_orientation(i, j) = + message.saved_traj.trajectories[0].datapoints[i][j]; + } + } + for (int i = 0; i < 3; i++) { + for (int j = 0; j < c3_options.N + 1; j++) { + dyn_feas_curr_plan_obj_pos(i, j) = + message.saved_traj.trajectories[1].datapoints[i][j]; + } + } + } else { + std::cerr << "Failed to decode DYNAMICALLY_FEASIBLE_CURR_PLAN " + << "message" << std::endl; + } + } + } else if (event->channel == "DYNAMICALLY_FEASIBLE_CURR_ACTOR_PLAN") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received DYNAMICALLY_FEASIBLE_CURR_ACTOR_PLAN " + << "message in seconds utime: " << (message.utime) / 1e6 + << " and event timestamp " << adjusted_utimestamp / 1e6 + << std::endl; + for (int i = 0; i < 3; i++) { + for (int j = 0; j < c3_options.N + 1; j++) { + dyn_feas_curr_plan_ee_pos(i, j) = + message.saved_traj.trajectories[0].datapoints[i][j]; + } + } + } else { + std::cerr << "Failed to decode DYNAMICALLY_FEASIBLE_CURR_ACTOR_PLAN" + << " message" << std::endl; + } + } + } else if (event->channel == "DYNAMICALLY_FEASIBLE_BEST_PLAN") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received DYNAMICALLY_FEASIBLE_BEST_PLAN " + << "message in seconds utime: " << (message.utime) / 1e6 + << " and event timestamp " << adjusted_utimestamp / 1e6 + << std::endl; + for (int i = 0; i < 4; i++) { + for (int j = 0; j < c3_options.N + 1; j++) { + dyn_feas_best_plan_obj_orientation(i, j) = + message.saved_traj.trajectories[0].datapoints[i][j]; + } + } + for (int i = 0; i < 3; i++) { + for (int j = 0; j < c3_options.N + 1; j++) { + dyn_feas_best_plan_obj_pos(i, j) = + message.saved_traj.trajectories[1].datapoints[i][j]; + } + } + } else { + std::cerr << "Failed to decode DYNAMICALLY_FEASIBLE_BEST_PLAN" + << " message" << std::endl; + } + } + } else if (event->channel == "DYNAMICALLY_FEASIBLE_BEST_ACTOR_PLAN") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received DYNAMICALLY_FEASIBLE_BEST_ACTOR_PLAN " + << "message in seconds utime: " << (message.utime) / 1e6 + << " and event timestamp " << adjusted_utimestamp / 1e6 + << std::endl; + for (int i = 0; i < 3; i++) { + for (int j = 0; j < c3_options.N + 1; j++) { + dyn_feas_best_plan_ee_pos(i, j) = + message.saved_traj.trajectories[0].datapoints[i][j]; + } + } + } else { + std::cerr << "Failed to decode DYNAMICALLY_FEASIBLE_BEST_ACTOR_PLAN" + << " message" << std::endl; + } + } + } else if (event->channel == "C3_DEBUG_CURR") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_c3_output message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received C3_DEBUG_CURR message in seconds utime: " + << (message.utime) / 1e6 << " and event timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; i < 3; i++) { + for (int j = 0; j < c3_options.N; j++) { + u_sol(i, j) = + static_cast(message.c3_solution.u_sol[i][j]); + } + } + for (int i = 0; i < 19; i++) { + for (int j = 0; j < c3_options.N; j++) { + x_sol(i, j) = + static_cast(message.c3_solution.x_sol[i][j]); + } + } + for (int i = 0; i < 16; i++) { + for (int j = 0; j < c3_options.N; j++) { + lambda_sol(i, j) = + static_cast(message.c3_solution.lambda_sol[i][j]); + } + } + for (int i = 0; i < 38; i++) { + for (int j = 0; j < c3_options.N; j++) { + w_sol(i, j) = + static_cast(message.c3_intermediates.w_sol[i][j]); + } + } + for (int i = 0; i < 38; i++) { + for (int j = 0; j < c3_options.N; j++) { + delta_sol(i, j) = + static_cast(message.c3_intermediates.delta_sol[i][j]); + } + } + } else { + std::cerr << "Failed to decode C3_DEBUG_CURR message" << std::endl; + } + } + } else if (event->channel == "IS_C3_MODE") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received IS_C3_MODE message in " + << "seconds utime: " << (message.utime) / 1e6 + << " and event " << "timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + is_c3_mode = message.saved_traj.trajectories[0].datapoints[0][0]; + is_c3_mode_set = true; + } else { + std::cerr << "Failed to decode IS_C3_MODE message" << std::endl; + } + } + } else if (event->channel == "SAMPLE_LOCATIONS") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received SAMPLE_LOCATIONS message in " + << "seconds utime: " << (message.utime) / 1e6 + << " and event " << "timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; + i < message.saved_traj.trajectories[0].datapoints[0].size(); + i++) { + Eigen::VectorXd sample_location = Eigen::VectorXd::Zero(3); + for (int j = 0; j < 3; j++) { + sample_location(j) = + message.saved_traj.trajectories[0].datapoints[j][i]; + } + sample_locations_in_log.push_back(sample_location); + } + } else { + std::cerr << "Failed to decode SAMPLE_LOCATIONS message" << std::endl; + } + } + } else if (event->channel == "SAMPLE_COSTS") { + if (event->timestamp >= time_into_log_in_microsecs + u_init_time) { + dairlib::lcmt_timestamped_saved_traj message; + if (message.decode(event->data, 0, event->datalen) > 0) { + std::cout << "Received SAMPLE_COSTS message in " + << "seconds utime: " << (message.utime) / 1e6 + << " and event " << "timestamp " + << adjusted_utimestamp / 1e6 << std::endl; + for (int i = 0; + i < message.saved_traj.trajectories[0].datapoints[0].size(); + i++) { + sample_costs_in_log.push_back(Eigen::VectorXd::Constant( + 1, message.saved_traj.trajectories[0].datapoints[0][i])); + } + } else { + std::cerr << "Failed to decode SAMPLE_COSTS message" << std::endl; + } + } + } + + // Break out of loop if we have one message for every desired channel. + if (channels_to_check.find(event->channel) != channels_to_check.end()) { + if ((x_lcs_actual != Eigen::VectorXd::Zero(19)) && + (x_lcs_desired != Eigen::VectorXd::Zero(19)) && + (x_lcs_final_desired != Eigen::VectorXd::Zero(19)) && + (dyn_feas_curr_plan_ee_pos != + Eigen::MatrixXd::Zero(3, c3_options.N + 1)) && + (dyn_feas_curr_plan_obj_pos != + Eigen::MatrixXd::Zero(3, c3_options.N + 1)) && + (dyn_feas_curr_plan_obj_orientation != + Eigen::MatrixXd::Zero(4, c3_options.N + 1)) && + (u_sol != Eigen::MatrixXd::Zero(3, c3_options.N)) && + (is_c3_mode_set) && (sample_locations_in_log.size() > 0) && + (sample_costs_in_log.size() > 0)) { + break; + } + } + } + + std::cout << "x_lcs_actual from log : " << x_lcs_actual.transpose() << "\n" + << std::endl; + std::cout << "Available sample locations from log and corresponding costs: " + << std::endl; + std::cout << "Number of sample locations in log: " + << sample_locations_in_log.size() << std::endl; + for (int i = 0; i < sample_locations_in_log.size(); i++) { + if (i < sample_costs_in_log.size()) { + std::cout << "sample " << i << " : " + << sample_locations_in_log[i].transpose() << " cost is " + << sample_costs_in_log[i] << std::endl; + if (i == 0) { + std::cout << "Dynamically feasible plan is: " << std::endl; + std::cout << "End effector position: " + << dyn_feas_curr_plan_ee_pos.transpose() << std::endl; + std::cout << "Object orientation: " + << dyn_feas_curr_plan_obj_orientation.transpose() + << std::endl; + std::cout << "Object position: " + << dyn_feas_curr_plan_obj_pos.transpose() << std::endl; + } + if (i == 1) { + std::cout << "Dynamically feasible best plan is: " << std::endl; + std::cout << "End effector position: " + << dyn_feas_best_plan_ee_pos.transpose() << std::endl; + std::cout << "Object orientation: " + << dyn_feas_best_plan_obj_orientation.transpose() + << std::endl; + std::cout << "Object position: " + << dyn_feas_best_plan_obj_pos.transpose() << std::endl; + } + } else { + std::cout << "sample " << i << " : " + << sample_locations_in_log[i].transpose() << " cost is " + << "N/A" << std::endl; + } + } + + std::cout << "\nFuture timestamps:" << std::endl; + int more_msgs_to_print = 5; + while (((event = log_file.readNextEvent()) != nullptr) && + (more_msgs_to_print > 0)) { + if (event->channel == "C3_ACTUAL") { + std::cout << "Received C3_ACTUAL message in seconds: " + << (event->timestamp - u_init_time) / 1e6 << std::endl; + more_msgs_to_print--; + } + } + std::cout << "" << std::endl; + + // Create the plant for the LCS. + DiagramBuilder plant_builder; + auto [plant_for_lcs, scene_graph] = + AddMultibodyPlantSceneGraph(&plant_builder, 0.0); + AddLCSModelsToPlant(&plant_for_lcs, &scene_graph, + controller_params.object_model, + controller_params.include_end_effector_orientation); + plant_for_lcs.Finalize(); + std::unique_ptr> plant_for_lcs_autodiff = + drake::systems::System::ToAutoDiffXd(plant_for_lcs); + + auto plant_diagram = plant_builder.Build(); + std::unique_ptr> diagram_context = + plant_diagram->CreateDefaultContext(); + auto& plant_for_lcs_context = plant_diagram->GetMutableSubsystemContext( + plant_for_lcs, diagram_context.get()); + auto plant_for_lcs_context_ad = + plant_for_lcs_autodiff->CreateDefaultContext(); + + std::vector>> contact_pairs; + + // Creating a map of contact geoms + std::unordered_map contact_geoms; + + // Change contact geoms based on the demo_name + if (FLAGS_demo_name == "push_t") { + drake::geometry::GeometryId ee_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("end_effector_simple"))[0]; + drake::geometry::GeometryId horizontal_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("horizontal_link"))[0]; + drake::geometry::GeometryId vertical_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("vertical_link"))[0]; + + drake::geometry::GeometryId corner_nxynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_nxynz"))[0]; + drake::geometry::GeometryId corner_nxnynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_nxnynz"))[0]; + drake::geometry::GeometryId corner_xynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_xynz"))[0]; + + drake::geometry::GeometryId ground_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("ground"))[0]; + + // Creating a map of contact geoms + contact_geoms["EE"] = ee_contact_points; + contact_geoms["horizontal_link"] = horizontal_geoms; + contact_geoms["vertical_link"] = vertical_geoms; + contact_geoms["corner_nxynz"] = corner_nxynz_geoms; + contact_geoms["corner_nxnynz"] = corner_nxnynz_geoms; + contact_geoms["corner_xynz"] = corner_xynz_geoms; + contact_geoms["GROUND"] = ground_geoms; + + std::vector> ee_contact_pairs; + + // TODO @bibit contact pair ordering needs to be (ee-ground, ee-jack, jack-ground) + // Creating a list of contact pairs for the end effector and the object to + // hand over to lcs factory in the controller to resolve + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["horizontal_link"])); + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["vertical_link"])); + + // Creating a list of contact pairs for the object and the ground + SortedPair ground_contact_1{ + SortedPair(contact_geoms["corner_nxynz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_2{ + SortedPair(contact_geoms["corner_nxnynz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_3{ + SortedPair(contact_geoms["corner_xynz"], contact_geoms["GROUND"])}; + + contact_pairs.push_back(ee_contact_pairs); + + if (sampling_c3_options.num_contacts_index == 2 || + sampling_c3_options.num_contacts_index == 3) { + // If num_contacts_index is 2 or 3, we add an additional contact pair + // between the end effector and the ground. + std::vector> ee_ground_contact{ + SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])}; + contact_pairs.push_back(ee_ground_contact); + } + std::vector> ground_object_contact_pairs; + ground_object_contact_pairs.push_back(ground_contact_1); + ground_object_contact_pairs.push_back(ground_contact_2); + ground_object_contact_pairs.push_back(ground_contact_3); + contact_pairs.push_back(ground_object_contact_pairs); + } else if (FLAGS_demo_name == "box_topple") { + drake::geometry::GeometryId ee_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("end_effector_simple"))[0]; + drake::geometry::GeometryId box_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("box"))[0]; + + drake::geometry::GeometryId corner_xynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_xynz"))[0]; + drake::geometry::GeometryId corner_xnynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_xnynz"))[0]; + drake::geometry::GeometryId corner_nxynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_nxynz"))[0]; + drake::geometry::GeometryId corner_nxnynz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_nxnynz"))[0]; + drake::geometry::GeometryId corner_xyz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_xyz"))[0]; + drake::geometry::GeometryId corner_xnyz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_xnyz"))[0]; + drake::geometry::GeometryId corner_nxyz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_nxyz"))[0]; + drake::geometry::GeometryId corner_nxnyz_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("corner_nxnyz"))[0]; + + drake::geometry::GeometryId ground_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("ground"))[0]; + + // Creating a map of contact geoms + contact_geoms["EE"] = ee_contact_points; + contact_geoms["box"] = box_geoms; + contact_geoms["corner_xynz"] = corner_xynz_geoms; + contact_geoms["corner_xnynz"] = corner_xnynz_geoms; + contact_geoms["corner_nxynz"] = corner_nxynz_geoms; + contact_geoms["corner_nxnynz"] = corner_nxnynz_geoms; + contact_geoms["corner_xyz"] = corner_xyz_geoms; + contact_geoms["corner_xnyz"] = corner_xnyz_geoms; + contact_geoms["corner_nxyz"] = corner_nxyz_geoms; + contact_geoms["corner_nxnyz"] = corner_nxnyz_geoms; + contact_geoms["GROUND"] = ground_geoms; + + std::vector> ee_contact_pairs; + + // Creating a list of contact pairs for the end effector and the object to + // hand over to lcs factory in the controller to resolve + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["box"])); + + // Creating a list of contact pairs for the object and the ground + SortedPair ground_contact_1{ + SortedPair(contact_geoms["corner_xynz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_2{ + SortedPair(contact_geoms["corner_xnynz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_3{ + SortedPair(contact_geoms["corner_nxynz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_4{ + SortedPair(contact_geoms["corner_nxnynz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_5{ + SortedPair(contact_geoms["corner_xyz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_6{ + SortedPair(contact_geoms["corner_xnyz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_7{ + SortedPair(contact_geoms["corner_nxyz"], contact_geoms["GROUND"])}; + SortedPair ground_contact_8{ + SortedPair(contact_geoms["corner_nxnyz"], contact_geoms["GROUND"])}; + + contact_pairs.push_back(ee_contact_pairs); + + if (sampling_c3_options.num_contacts_index == 2 || + sampling_c3_options.num_contacts_index == 3) { + // If num_contacts_index is 2 or 3, we add an additional contact pair + // between the end effector and the ground. + std::vector> ee_ground_contact{ + SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])}; + contact_pairs.push_back(ee_ground_contact); + } + std::vector> ground_object_contact_pairs; + ground_object_contact_pairs.push_back(ground_contact_1); + ground_object_contact_pairs.push_back(ground_contact_2); + ground_object_contact_pairs.push_back(ground_contact_3); + ground_object_contact_pairs.push_back(ground_contact_4); + ground_object_contact_pairs.push_back(ground_contact_5); + ground_object_contact_pairs.push_back(ground_contact_6); + ground_object_contact_pairs.push_back(ground_contact_7); + ground_object_contact_pairs.push_back(ground_contact_8); + contact_pairs.push_back(ground_object_contact_pairs); + } else if (FLAGS_demo_name == "jacktoy") { + drake::geometry::GeometryId ee_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("end_effector_simple"))[0]; + drake::geometry::GeometryId capsule1_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_1"))[0]; + drake::geometry::GeometryId capsule2_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_2"))[0]; + drake::geometry::GeometryId capsule3_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_3"))[0]; + + drake::geometry::GeometryId capsule1_sphere1_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_1"))[1]; + drake::geometry::GeometryId capsule1_sphere2_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_1"))[2]; + drake::geometry::GeometryId capsule2_sphere1_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_2"))[1]; + drake::geometry::GeometryId capsule2_sphere2_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_2"))[2]; + drake::geometry::GeometryId capsule3_sphere1_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_3"))[1]; + drake::geometry::GeometryId capsule3_sphere2_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("capsule_3"))[2]; + + drake::geometry::GeometryId ground_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("ground"))[0]; + + // Creating a map of contact geoms + contact_geoms["EE"] = ee_contact_points; + contact_geoms["CAPSULE_1"] = capsule1_geoms; + contact_geoms["CAPSULE_2"] = capsule2_geoms; + contact_geoms["CAPSULE_3"] = capsule3_geoms; + contact_geoms["CAPSULE_1_SPHERE_1"] = capsule1_sphere1_geoms; + contact_geoms["CAPSULE_1_SPHERE_2"] = capsule1_sphere2_geoms; + contact_geoms["CAPSULE_2_SPHERE_1"] = capsule2_sphere1_geoms; + contact_geoms["CAPSULE_2_SPHERE_2"] = capsule2_sphere2_geoms; + contact_geoms["CAPSULE_3_SPHERE_1"] = capsule3_sphere1_geoms; + contact_geoms["CAPSULE_3_SPHERE_2"] = capsule3_sphere2_geoms; + contact_geoms["GROUND"] = ground_geoms; + + std::vector> ee_contact_pairs; + + // Creating a list of contact pairs for the end effector and the object to + // hand over to lcs factory in the controller to resolve + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_1"])); + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_2"])); + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_3"])); + + // Creating a list of contact pairs for the object and the ground + SortedPair ground_contact_1_1{SortedPair( + contact_geoms["CAPSULE_1_SPHERE_1"], contact_geoms["GROUND"])}; + SortedPair ground_contact_1_2{SortedPair( + contact_geoms["CAPSULE_1_SPHERE_2"], contact_geoms["GROUND"])}; + SortedPair ground_contact_2_1{SortedPair( + contact_geoms["CAPSULE_2_SPHERE_1"], contact_geoms["GROUND"])}; + SortedPair ground_contact_2_2{SortedPair( + contact_geoms["CAPSULE_2_SPHERE_2"], contact_geoms["GROUND"])}; + SortedPair ground_contact_3_1{SortedPair( + contact_geoms["CAPSULE_3_SPHERE_1"], contact_geoms["GROUND"])}; + SortedPair ground_contact_3_2{SortedPair( + contact_geoms["CAPSULE_3_SPHERE_2"], contact_geoms["GROUND"])}; + + contact_pairs.push_back(ee_contact_pairs); + + if (sampling_c3_options.num_contacts_index == 2 || + sampling_c3_options.num_contacts_index == 3) { + // If num_contacts_index is 2 or 3, we add an additional contact pair + // between the end effector and the ground. + std::vector> ee_ground_contact{ + SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])}; + contact_pairs.push_back(ee_ground_contact); + } + std::vector> ground_object_contact_pairs; + ground_object_contact_pairs.push_back(ground_contact_1_1); + ground_object_contact_pairs.push_back(ground_contact_1_2); + ground_object_contact_pairs.push_back(ground_contact_2_1); + ground_object_contact_pairs.push_back(ground_contact_2_2); + ground_object_contact_pairs.push_back(ground_contact_3_1); + ground_object_contact_pairs.push_back(ground_contact_3_2); + contact_pairs.push_back(ground_object_contact_pairs); + } else if (FLAGS_demo_name == "ball_rolling") { + drake::geometry::GeometryId ee_contact_points = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("end_effector_simple"))[0]; + drake::geometry::GeometryId object_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("sphere"))[0]; + drake::geometry::GeometryId ground_geoms = + plant_for_lcs.GetCollisionGeometriesForBody( + plant_for_lcs.GetBodyByName("ground"))[0]; + + // Creating a map of contact geoms + contact_geoms["EE"] = ee_contact_points; + contact_geoms["SPHERE"] = object_geoms; + contact_geoms["GROUND"] = ground_geoms; + + std::vector> ee_contact_pairs; + + // Creating a list of contact pairs for the end effector and the object to + // hand over to lcs factory in the controller to resolve + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["SPHERE"])); + // Creating a list of contact pairs for the object and the ground + std::vector> ground_contact{ + SortedPair(contact_geoms["SPHERE"], contact_geoms["GROUND"])}; + + // will have [[(ee,sphere)], [(sphere, ground)]] + contact_pairs.push_back(ee_contact_pairs); + + if (sampling_c3_options.num_contacts_index == 1) { + // If num_contacts_index is 2 or 3, we add an additional contact pair + // between the end effector and the ground. + std::vector> ee_ground_contact{ + SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])}; + contact_pairs.push_back(ee_ground_contact); + } + contact_pairs.push_back(ground_contact); + } + + plant_diagram->set_name(("sampling_c3_test_plant_" + FLAGS_demo_name)); + DrawAndSaveDiagramGraph(*plant_diagram); + + // Create the controller. The last bool argument is the verbose flag. + bool verbose = true; +#ifdef DO_SAMPLE_VISUALIZATIONS + verbose = false; + c3_options.use_predicted_x0_c3 = false; +#endif + DiagramBuilder builder; + auto controller = builder.AddSystem( + plant_for_lcs, &plant_for_lcs_context, *plant_for_lcs_autodiff, + plant_for_lcs_context_ad.get(), contact_pairs, controller_params, + verbose); + auto controller_context = controller->CreateDefaultContext(); + + auto owned_diagram = builder.Build(); + owned_diagram->set_name(("sampling_c3_controller_test_" + FLAGS_demo_name)); + DrawAndSaveDiagramGraph(*owned_diagram); + + // Fix static input ports. + controller->get_input_port_radio().FixValue( + controller_context.get(), drake::Value{}); + controller->get_input_port_target().FixValue(controller_context.get(), + x_lcs_desired); + controller->get_input_port_final_target().FixValue(controller_context.get(), + x_lcs_final_desired); + + std::vector x_lcs_actuals; + + // Testing sample location 0 and sample location 1 from the log from all + // sample locations. This was done to verify the anolmaly seen as a result of + // using cost type 3 in the push_T case. Eigen::VectorXd curr_sample_in_log = + // x_lcs_actual; curr_sample_in_log.head(3) = sample_locations_in_log[0]; + // x_lcs_actuals.push_back(curr_sample_in_log); + Eigen::VectorXd best_sample_in_log = x_lcs_actual; + best_sample_in_log.head(3) = sample_locations_in_log[1]; + x_lcs_actuals.push_back(best_sample_in_log); + +#ifdef DO_SAMPLE_VISUALIZATIONS + std::cout << "DO_SAMPLE_VISUALIZATIONS" << std::endl; + + std::vector x_lcs_samples; + std::vector angles; + + // Check the demo name and call the corresponding function directly. + if (FLAGS_demo_name == "push_t" || FLAGS_demo_name == "box_topple") { + // Directly call the GenerateEvenlySpacedSamplesAroundT function + x_lcs_samples = GenerateEvenlySpacedSamplesAroundT( + x_lcs_actual, sampling_params, N_VERTICAL, N_HORIZONTAL); + } else if (FLAGS_demo_name == "jacktoy" || + FLAGS_demo_name == "ball_rolling") { + // Directly call the GenerateEvenlySpacedSamplesAroundJack function + auto [samples, angle_data] = GenerateEvenlySpacedSamplesAroundJack( + x_lcs_actual, sampling_params, N_VERTICAL, N_HORIZONTAL); + x_lcs_samples = samples; + angles = angle_data; + } + + x_lcs_actuals.clear(); + x_lcs_actuals = x_lcs_samples; + + // Prepare to print out the costs. + Eigen::VectorXd costs; + + std::cout << "DO_SAMPLE_VISUALIZATIONS" << std::endl; + if (FLAGS_demo_name == "jacktoy" || FLAGS_demo_name == "ball_rolling") { + costs = Eigen::VectorXd::Zero(angles.size()); // If angles are available + } else if (FLAGS_demo_name == "push_t" || FLAGS_demo_name == "box_topple") { + costs = Eigen::VectorXd::Zero(x_lcs_samples.size()); // For the other case + } +#endif + + // Remember that doing this in a loop actually triggers the x_pred calculation + // in the controller. Ensure this is something you want to do. + for (int i = 0; i < x_lcs_actuals.size(); i++) { + Eigen::VectorXd x_lcs_actual_i = x_lcs_actuals[i]; + + // Set plant states, fix input port values. + plant_for_lcs.SetPositionsAndVelocities(&plant_for_lcs_context, + x_lcs_actual_i); + controller->get_input_port_lcs_state().FixValue( + controller_context.get(), TimestampedVector(x_lcs_actual_i)); + + // Do forced publish. + auto discrete_state = controller->AllocateDiscreteVariables(); + controller->CalcForcedDiscreteVariableUpdate(*controller_context, + discrete_state.get()); + auto sample_costs_inside = + controller->get_output_port_all_sample_costs() + .Eval>(*controller_context); + controller->ForcedPublish(*controller_context); + +#ifdef DO_SAMPLE_VISUALIZATIONS + // Get the cost of the sample by querying the sample costs output port. + auto sample_costs = controller->get_output_port_all_sample_costs() + .Eval>(*controller_context); + costs(i) = sample_costs[0]; + if (i % 10 == 0) { + std::cout << "Finished " << i << " of " << x_lcs_actuals.size() + << " samples." << std::endl; + } +#endif + } +#ifdef DO_SAMPLE_VISUALIZATIONS + // Write values like positions and costs to files which can be loaded with + // np.loadtxt() cleanly from a python script. If the outputs are small + // enough, can swap the file writing for printing to the console via + // PythonFriendlyVectorOfVectorXdPrint. + PythonFriendlyVectorOfVectorXdToFile("x_lcs_samples", x_lcs_samples); + PythonFriendlyVectorOfVectorXdToFile("costs", {costs}); + PythonFriendlyVectorOfVectorXdToFile("x_lcs_desired", {x_lcs_desired}); + PythonFriendlyVectorOfVectorXdToFile("p_world_to_franka", + {kWorldToFrankaOffset}); + PythonFriendlyVectorOfVectorXdToFile("p_franka_to_ground", + {kFrankaToGroundOffset}); + + std::cout << "\nee_urdf = op.join(DAIRLIB_DIR, '" + << kEndEffectorSimpleModel << "')" << std::endl; + std::cout << "jack_urdf = op.join(DAIRLIB_DIR, '" << sim_params.object_model + << "')" << std::endl; +#endif + + std::cout << "Finished ForcedPublish" << std::endl; + + // Example of getting the C3 solution by evaluating the output port. + // auto c3_solution = controller->get_output_port_c3_solution_curr_plan( + // ).Eval(*controller_context); + // std::cout << "\nc3_solution.x_sol_ = " << c3_solution.x_sol_ << std::endl; + // std::cout << "\nc3_solution.lambda_sol_ = " << c3_solution.lambda_sol_ + // << std::endl; + // std::cout << "\nc3_solution.u_sol_ = " << c3_solution.u_sol_ << std::endl; + // std::cout << "\nc3_solution.time_vector_ = " << c3_solution.time_vector_ + // << std::endl; + + return 0; +} + +/* Define function that will generate samples around T location. + + Args: + x_lcs_actual + sampling_params + num_vertical + num_horizontal + + Returns: + - A std::vector of x_lcs samples + - A std::vector of 2D (theta, elevation_theta) positions from which the + samples were derived. +*/ +std::vector GenerateEvenlySpacedSamplesAroundT( + const Eigen::VectorXd& x_lcs, + const SamplingParams& sampling_params, const int& num_vertical, + const int& num_horizontal) { + // Extract sampling parameters. + double sampling_height = 0.00; + + // the sampling region has an outer x and y limit. These are expressed in body + // frame. + double outer_x_limit = 0.16; + double outer_y_limit = 0.16; + + // Generate samples on a grid around the T + std::vector x_lcs_samples; + + // Compute the step size for the grid. + // num_vertical means how many rows of samples we want to take. That is x + // changes across each row. num_horizontal means how many columns of samples + // we want to take. That is y changes across each column. + double step_size_x = 2 * outer_x_limit / (num_vertical - 1); + double step_size_y = 2 * outer_y_limit / (num_horizontal - 1); + std::cout << "step_size_x: " << step_size_x << std::endl; + std::cout << "step_size_y: " << step_size_y << std::endl; + + std::vector unfiltered_samples_in_body_frame; + // Set the dummy to be the same as the actual lcs value. + Eigen::VectorXd x_lcs_sample = x_lcs; + std::cout << "x_lcs: " << x_lcs.transpose() << std::endl; + Eigen::Quaterniond quat_object(x_lcs(3), x_lcs(4), x_lcs(5), x_lcs(6)); + Eigen::Vector3d object_position = x_lcs.segment(7, 3); + + // Generate uniform samples on a grid. Replace the end effector values in the + // dummy with the sample values. + for (int i = 0; i < num_vertical; i++) { + for (int j = 0; j < num_horizontal; j++) { + x_lcs_sample(0) = -outer_x_limit + i * step_size_x; + x_lcs_sample(1) = -outer_y_limit + j * step_size_y; + x_lcs_sample(2) = sampling_height; + unfiltered_samples_in_body_frame.push_back(x_lcs_sample); + } + } + + // Define limits for sample validity. + double ee_radius = 0; // 0.0145; + double clearance = 0; // 0.002; // Maintain a clearance of 2mm from the + // T. + double x_bottom_lim_1 = 0.08 + ee_radius + clearance; + double x_top_lim_1 = -0.08 + ee_radius + clearance; + double x_top_lim_2 = -0.08 - 0.04 - ee_radius - clearance; + double y_lim_1 = 0.04 + ee_radius + clearance; + double y_lim_2 = 0.08 + ee_radius + clearance; + + // Currently setting filtering off. + std::vector filtered_samples_in_body_frame = + unfiltered_samples_in_body_frame; + + // Convert the samples to world frame. + std::vector filtered_samples_in_world_frame; + for (const auto& sample : filtered_samples_in_body_frame) { + Eigen::VectorXd sample_in_world_frame = sample; + // Convert end effector position to world frame. + sample_in_world_frame.head(3) = + quat_object * sample.head(3) + object_position; + filtered_samples_in_world_frame.push_back(sample_in_world_frame); + } + + return filtered_samples_in_world_frame; +} + +/* Define function that will generate samples around jack location. + + Args: + x_lcs_actual + sampling_params + num_vertical + num_horizontal + + Returns: + - A std::vector of x_lcs samples + - A std::vector of 2D (theta, elevation_theta) positions from which the + samples were derived. +*/ +std::pair, std::vector> +GenerateEvenlySpacedSamplesAroundJack( + const Eigen::VectorXd& x_lcs, + const SamplingParams& sampling_params, const int& num_vertical, + const int& num_horizontal) { + // Grab sampling parameters. + double sampling_radius = sampling_params.sampling_radius; + double min_angle_from_vertical = sampling_params.min_angle_from_vertical; + double max_angle_from_vertical = sampling_params.max_angle_from_vertical; + + // Pull out the q and v from the LCS state. The end effector location and + // velocity of this state will be changed for the sample. + Eigen::VectorXd q = x_lcs.head(N_Q); + Eigen::VectorXd v = x_lcs.tail(N_V); + + // Center the sampling circle on the current ball location. + Eigen::Vector3d object_xyz = q.tail(3); + double x_samplec = object_xyz[0]; + double y_samplec = object_xyz[1]; + double z_samplec = object_xyz[2]; + + // Prepare to store samples and (theta, elevation_theta) angles. + std::vector x_lcs_samples; + std::vector angles; + + // Double for loop over the number of vertical and horizontal samples. + for (int i = 0; i < num_vertical; i++) { + double elevation_theta = + min_angle_from_vertical + + i * (max_angle_from_vertical - min_angle_from_vertical) / + (num_vertical - 1); + for (int j = 0; j < num_horizontal; j++) { + double theta = j * 2 * M_PI / num_horizontal; + + // Update the hypothetical state's end effector location to the tested + // sample location. + Eigen::VectorXd q_ee = Eigen::VectorXd::Zero(3); + q_ee[0] = x_samplec + sampling_radius * cos(theta) * sin(elevation_theta); + q_ee[1] = y_samplec + sampling_radius * sin(theta) * sin(elevation_theta); + q_ee[2] = z_samplec + sampling_radius * cos(elevation_theta); + + Eigen::VectorXd candidate_state = Eigen::VectorXd::Zero(N_Q + N_V); + candidate_state << q_ee, x_lcs.segment(3, N_Q - 3), v; + + // Store the sample and the angle pair. + x_lcs_samples.push_back(candidate_state); + Eigen::Vector2d angle_pair; + angle_pair << theta, elevation_theta; + angles.push_back(angle_pair); + } + } + return std::make_pair(x_lcs_samples, angles); +} + +void PythonFriendlyVectorOfVectorXdPrint( + char* name, std::vector some_vector) { + std::cout << name << " = np.array("; + if (some_vector.size() > 1) { + std::cout << "["; + } + for (const auto& some_element : some_vector) { + std::cout << "\n\t["; + for (int i = 0; i < some_element.size(); i++) { + std::cout << some_element(i) << ", "; + } + std::cout << "], "; + } + if (some_vector.size() > 1) { + std::cout << "]"; + } + std::cout << ")" << std::endl; +} + +void PythonFriendlyVectorOfVectorXdToFile( + char* name, std::vector some_vector) { + std::string filename = + "/home/sharanya/workspace/dairlib/examples/sampling_c3/push_t/test"; + filename += "/tmp/"; + filename += name; + filename += ".txt"; + + // Remove the file if it already exists. + std::remove(filename.c_str()); + std::ofstream file(filename); + + if (!file) { + std::cerr << "Erorr: Could not create " << filename << std::endl; + } + std::cout << "Writing to " << filename << std::endl; + + for (const auto& some_element : some_vector) { + for (int i = 0; i < some_element.size(); i++) { + file << some_element(i) << " "; + } + file << "\n"; + } + file.close(); +} + +} // namespace dairlib + +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } diff --git a/examples/sampling_c3/urdf/ee_visualization_model.urdf b/examples/sampling_c3/urdf/ee_visualization_model.urdf new file mode 100644 index 0000000000..b7ef70c665 --- /dev/null +++ b/examples/sampling_c3/urdf/ee_visualization_model.urdf @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/sampling_c3/urdf/end_effector_full.urdf b/examples/sampling_c3/urdf/end_effector_full.urdf new file mode 100644 index 0000000000..fc03c81b6e --- /dev/null +++ b/examples/sampling_c3/urdf/end_effector_full.urdf @@ -0,0 +1,86 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/sampling_c3/urdf/end_effector_simple_model.urdf b/examples/sampling_c3/urdf/end_effector_simple_model.urdf new file mode 100644 index 0000000000..ba138d6298 --- /dev/null +++ b/examples/sampling_c3/urdf/end_effector_simple_model.urdf @@ -0,0 +1,80 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 1 + + + + + + 1 + + + + + + 1 + + + + + + + diff --git a/examples/sampling_c3/urdf/ground.urdf b/examples/sampling_c3/urdf/ground.urdf new file mode 100644 index 0000000000..5c78d56cc5 --- /dev/null +++ b/examples/sampling_c3/urdf/ground.urdf @@ -0,0 +1,39 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/sampling_c3/urdf/jack.sdf b/examples/sampling_c3/urdf/jack.sdf new file mode 100644 index 0000000000..fe37103c5e --- /dev/null +++ b/examples/sampling_c3/urdf/jack.sdf @@ -0,0 +1,139 @@ + + + + + + 0 0 0 0 0 0 + 0.052 + + + 0.00007072 + 0 + 0 + 0.00007072 + 0 + 0.00000572 + + + + 0 0 0.0 0 0 0 + + + 0.025 + 0.125 + + + + 0.3 + + + + 0 0 0.0 0 0 0 + + + 0.025 + 0.125 + + + + 0 0 1 1 + + + + + + 0 0 0 0 1.5708 0 + 0.052 + + + 0.00007072 + 0 + 0 + 0.00007072 + 0 + 0.00000572 + + + + 0 0 0 0 1.5708 0 + + + 0.025 + 0.125 + + + + 0.3 + + + + 0 0 0 0 1.5708 0 + + + 0.025 + 0.125 + + + + 1 0 0 1 + + + + + + 0 0 0 1.5708 0 0 + 0.052 + + + 0.00007072 + 0 + 0 + 0.00007072 + 0 + 0.00000572 + + + + 0 0 0 1.5708 0 0 + + + 0.025 + 0.125 + + + + 0.3 + + + + 0 0 0 1.5708 0 0 + + + 0.025 + 0.125 + + + + 0 1 0 1 + + + + + + + capsule_1 + capsule_2 + 0 0 0 0 0 0 + + + + capsule_2 + capsule_3 + 0 0 0 0 0 0 + + + + diff --git a/examples/sampling_c3/urdf/jack_ground.sdf b/examples/sampling_c3/urdf/jack_ground.sdf new file mode 100644 index 0000000000..60ae41aaea --- /dev/null +++ b/examples/sampling_c3/urdf/jack_ground.sdf @@ -0,0 +1,187 @@ + + + + + + 0 0 0 0 0 0 + 0.33 + + + 0.0004488 + 0 + 0 + 0.0004488 + 0 + 0.0000363 + + + + 0 0 0.0 0 0 0 + + + 0.025 + 0.125 + + + + 0.3 + + + + 0 0 0.0625 0 0 0 + + + 0.025 + + + + + 0 0 -0.0625 0 0 0 + + + 0.025 + + + + + 0 0 0.0 0 0 0 + + + 0.025 + 0.125 + + + + 0 0 1 1 + + + + + + 0 0 0 0 1.5708 0 + 0.33 + + + 0.0004488 + 0 + 0 + 0.0004488 + 0 + 0.0000363 + + + + 0 0 0 0 1.5708 0 + + + 0.025 + 0.125 + + + + 0.3 + + + + 0.0625 0 0 0 0 0 + + + 0.025 + + + + + -0.0625 0 0 0 0 0 + + + 0.025 + + + + + 0 0 0 0 1.5708 0 + + + 0.025 + 0.125 + + + + 1 0 0 1 + + + + + + 0 0 0 1.5708 0 0 + 0.33 + + + 0.0004488 + 0 + 0 + 0.0004488 + 0 + 0.0000363 + + + + 0 0 0 1.5708 0 0 + + + 0.025 + 0.125 + + + + 0.3 + + + + 0 0.0625 0 0 0 0 + + + 0.025 + + + + + 0 -0.0625 0 0 0 0 + + + 0.025 + + + + + 0 0 0 1.5708 0 0 + + + 0.025 + 0.125 + + + + 0 1 0 1 + + + + + + + capsule_1 + capsule_2 + 0 0 0 0 0 0 + + + + capsule_2 + capsule_3 + 0 0 0 0 0 0 + + + + diff --git a/examples/sampling_c3/urdf/platform.urdf b/examples/sampling_c3/urdf/platform.urdf new file mode 100644 index 0000000000..9c700d5f9a --- /dev/null +++ b/examples/sampling_c3/urdf/platform.urdf @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + + diff --git a/examples/sampling_c3/xbox_script.py b/examples/sampling_c3/xbox_script.py new file mode 100644 index 0000000000..3b1888c3c5 --- /dev/null +++ b/examples/sampling_c3/xbox_script.py @@ -0,0 +1,95 @@ +"""Teleoperation controls for sampling C3 controller using an xbox controller. + +Button presses: +- A: Toggle teleoperation mode +- X: Toggle force tracking mode +- Y: Toggle force C3 mode +- Start: Print cost breakdown +- Back: Print current rotation and position cost + +Mapping to radio channels: +- Channel 0: x-direction teleop +- Channel 1: y-direction teleop +- Channel 2: z-direction teleop +- Channel 6: Back button (print current rotation and position cost) +- Channel 7: Start button (print cost breakdown) +- Channel 11: X button (force tracking mode) +- Channel 12: Y button (force C3 mode) +- Channel 14: A button (teleoperation mode) +""" + +import pygame +import dairlib.lcmt_radio_out +import lcm +import numpy as np + +def main(): + publisher = lcm.LCM() + + pygame.init() + + # Used to manage how fast the screen updates + clock = pygame.time.Clock() + + if (pygame.joystick.get_count() != 1): + raise RuntimeError("Please connect exactly one controller") + + joystick = pygame.joystick.Joystick(0) + joystick.init() + + done = False + i = 0 + latching_switch_a = 1 + latching_switch_x = 0 + latching_switch_y = 0 + latching_switch_start = 0 + latching_switch_back = 0 + print("Teleop Status: " + str(latching_switch_a)) + print("Force Tracking Status: " + str(not latching_switch_x)) + + + while not done: + # Get the name from the OS for the controller/joystick + name = joystick.get_name() + + for event in pygame.event.get(): + if event.type == pygame.JOYBUTTONDOWN: + # use this print statement to find the button number + # print(f"Button {event.button} pressed") + if event.button == 0: + latching_switch_a = not latching_switch_a + print("Teleop Status: " + str(latching_switch_a)) + if event.button == 2: + latching_switch_x = not latching_switch_x + print("Force Tracking Status: " + str(not latching_switch_x)) + if event.button == 3: + latching_switch_y = not latching_switch_y + print("Force C3 Mode Status: " + str(latching_switch_y)) + if event.button == 7: + latching_switch_start = not latching_switch_start + print("Print cost breakdown status: " + str(latching_switch_start)) + if event.button == 6: + latching_switch_back = not latching_switch_back + print("Print current rot and pos cost status: " + str(latching_switch_back)) + + # Send LCM message + radio_msg = dairlib.lcmt_radio_out() + radio_msg.channel[0] = -joystick.get_axis(1) + radio_msg.channel[1] = -joystick.get_axis(0) + radio_msg.channel[2] = -joystick.get_axis(4) + radio_msg.channel[6] = latching_switch_back + radio_msg.channel[7] = latching_switch_start + radio_msg.channel[11] = latching_switch_x + radio_msg.channel[12] = latching_switch_y + radio_msg.channel[14] = latching_switch_a + + publisher.publish("SAMPLING_C3_RADIO", radio_msg.encode()) + + # Limit to 20 frames per second + clock.tick(60) + i += 1 + + pygame.quit() + +if __name__ == '__main__': + main() diff --git a/lcm/lcm_trajectory.cc b/lcm/lcm_trajectory.cc index 7508bbafe3..f8cf7fb806 100644 --- a/lcm/lcm_trajectory.cc +++ b/lcm/lcm_trajectory.cc @@ -185,6 +185,13 @@ void LcmTrajectory::AddTrajectory(const std::string& trajectory_name, trajectories_[trajectory_name] = trajectory; } +void LcmTrajectory::ClearTrajectories() { + if (this->trajectories_.size() > 0) { + trajectories_.clear(); + trajectory_names_.clear(); + } +} + void LcmTrajectory::ConstructMetadataObject(string name, string description) { std::time_t t = std::time(nullptr); // get time now diff --git a/lcm/lcm_trajectory.h b/lcm/lcm_trajectory.h index 0eccb7de14..538eaecc5d 100644 --- a/lcm/lcm_trajectory.h +++ b/lcm/lcm_trajectory.h @@ -83,6 +83,9 @@ class LcmTrajectory { void AddTrajectory(const std::string& trajectory_name, const Trajectory& trajectory); + /// Remove all trajectories + void ClearTrajectories(); + /// Returns a vector of the names of the stored Trajectory objects const std::vector& GetTrajectoryNames() const { return trajectory_names_; diff --git a/lcmtypes/lcmt_sample_buffer.lcm b/lcmtypes/lcmt_sample_buffer.lcm new file mode 100644 index 0000000000..d044b9a569 --- /dev/null +++ b/lcmtypes/lcmt_sample_buffer.lcm @@ -0,0 +1,13 @@ +package dairlib; + +struct lcmt_sample_buffer +{ + int64_t utime; + int32_t buffer_length; + int32_t num_configurations; + + int32_t num_in_buffer; + + float costs[buffer_length]; + float configurations[buffer_length][num_configurations]; +} diff --git a/lcmtypes/lcmt_sampling_c3_debug.lcm b/lcmtypes/lcmt_sampling_c3_debug.lcm new file mode 100644 index 0000000000..25c6d70bf8 --- /dev/null +++ b/lcmtypes/lcmt_sampling_c3_debug.lcm @@ -0,0 +1,46 @@ +package dairlib; + +/* lcmtype with debug information for the sampling controller. + + mode_switch_reason key: + 0: No mode switch + 1: Switch to C3 because lower cost + 2: Switch to C3 because reached repositioning target + 3: Switch to repositioning because found lower cost sample + 4: Switch to repositioning because unproductive in C3 + 5: Switch to C3 because xbox controller forced into C3 mode + + source_of_pursued_target key: + 0: No pursued target (i.e. in C3 mode) + 1: Previous repositioning target + 2: New sample + 3: Sample from buffer +*/ + +struct lcmt_sampling_c3_debug +{ + int64_t utime; + + boolean is_c3_mode; + + boolean is_teleop; + boolean is_force_tracking; + boolean is_forced_into_c3; + + boolean in_pose_tracking_mode; + + int32_t mode_switch_reason; + int32_t source_of_pursued_target; + + int32_t detected_goal_changes; + + int32_t best_progress_steps_ago; + + float lowest_cost; + float lowest_pos_and_rot_current_cost; + float lowest_position_error; + float lowest_orientation_error; + + float current_pos_error; + float current_rot_error; +} diff --git a/multibody/multipose_visualizer.cc b/multibody/multipose_visualizer.cc index beb9e1c282..cf1e021430 100644 --- a/multibody/multipose_visualizer.cc +++ b/multibody/multipose_visualizer.cc @@ -17,18 +17,22 @@ namespace multibody { MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, string weld_frame_to_world) : MultiposeVisualizer(model_file, num_poses, - Eigen::VectorXd::Constant(num_poses, 1.0)) {} + Eigen::VectorXd::Constant(num_poses, 1.0), + weld_frame_to_world) {} MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, double alpha_scale, string weld_frame_to_world) : MultiposeVisualizer(model_file, num_poses, - Eigen::VectorXd::Constant(num_poses, alpha_scale)) {} + Eigen::VectorXd::Constant(num_poses, alpha_scale), + weld_frame_to_world) {} MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, string weld_frame_to_world, - std::shared_ptr meshcat) + std::shared_ptr meshcat, + const std::string& pose_trace_name, + const Eigen::VectorXd& rgb) : num_poses_(num_poses) { DRAKE_DEMAND(num_poses == alpha_scale.size()); DiagramBuilder builder; @@ -37,7 +41,7 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, std::tie(plant_, scene_graph) = drake::multibody::AddMultibodyPlantSceneGraph(&builder, 0.0); - Parser parser(plant_, scene_graph, "pose_trace"); + Parser parser(plant_, scene_graph, pose_trace_name + "_pose_trace"); parser.SetAutoRenaming(true); // Add num_poses copies of the plant, giving each a unique name for (int i = 0; i < num_poses_; i++) { @@ -74,7 +78,12 @@ MultiposeVisualizer::MultiposeVisualizer(string model_file, int num_poses, double new_alpha = alpha_scale(i - 2) * phong.a(); new_alpha = std::max(new_alpha, 0.0); new_alpha = std::min(new_alpha, 1.0); - phong.set(phong.r(), phong.g(), phong.b(), new_alpha); + if (rgb.size() == 3) { + phong.set(rgb(0), rgb(1), rgb(2), new_alpha); + } + else { + phong.set(phong.r(), phong.g(), phong.b(), new_alpha); + } new_props.UpdateProperty("phong", "diffuse", phong); scene_graph->AssignRole(plant_->get_source_id().value(), geometry_id, diff --git a/multibody/multipose_visualizer.h b/multibody/multipose_visualizer.h index 0c8a1b1a23..07374c3d62 100644 --- a/multibody/multipose_visualizer.h +++ b/multibody/multipose_visualizer.h @@ -47,10 +47,15 @@ class MultiposeVisualizer { /// @param weld_frame_to_world Welds the frame of the given name to the world /// @param meshcat Pointer to meshcat visualizer for option to attach to an /// existing meshcat instance + /// @param pose_trace_name Name of the pose trace to use in meshcat + /// @param rgb the RGB color to use for all bodies. If not provided, the + /// color will default to what is defined in the model file. MultiposeVisualizer( - std::string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, - std::string weld_frame_to_world = "", - std::shared_ptr meshcat = nullptr); + std::string model_file, int num_poses, const Eigen::VectorXd& alpha_scale, + std::string weld_frame_to_world = "", + std::shared_ptr meshcat = nullptr, + const std::string& pose_trace_name = "", + const Eigen::VectorXd& rgb = Eigen::VectorXd()); /// Draws the poses in the given (num_positions x num_poses) matrix /// Note: the matrix can have extra rows (e.g. velocities), which will be diff --git a/solvers/c3.cc b/solvers/c3.cc index 8b82850257..1432bb5e8a 100644 --- a/solvers/c3.cc +++ b/solvers/c3.cc @@ -42,6 +42,7 @@ C3::CostMatrices::CostMatrices(const std::vector& Q, C3::C3(const LCS& lcs, const C3::CostMatrices& costs, const vector& x_des, const C3Options& options) : warm_start_(options.warm_start), + lcs_(lcs), N_((lcs.A_).size()), n_((lcs.A_)[0].cols()), m_((lcs.D_)[0].cols()), @@ -137,9 +138,9 @@ C3::C3(const LCS& lcs, const C3::CostMatrices& costs, dynamics_constraints_.resize(N_); target_cost_.resize(N_ + 1); for (int i = 0; i < N_; i++) { - LinEq.block(0, 0, n_, n_) = lcs.A_.at(i); - LinEq.block(0, n_, n_, m_) = lcs.D_.at(i); - LinEq.block(0, n_ + m_, n_, k_) = lcs.B_.at(i); + LinEq.block(0, 0, n_, n_) = A_.at(i); + LinEq.block(0, n_, n_, m_) = D_.at(i); + LinEq.block(0, n_ + m_, n_, k_) = B_.at(i); dynamics_constraints_[i] = prog_ @@ -165,7 +166,33 @@ C3::C3(const LCS& lcs, const C3::CostMatrices& costs, } } +void C3::UpdateCostMatrices(const C3::CostMatrices& costs) { + DRAKE_DEMAND(costs.Q.size() == N_ + 1); + DRAKE_DEMAND(costs.R.size() == N_); + DRAKE_DEMAND(costs.U.size() == N_); + DRAKE_DEMAND(costs.G.size() == N_); + DRAKE_DEMAND(costs.Q[0].rows() == n_); + DRAKE_DEMAND(costs.Q[0].cols() == n_); + DRAKE_DEMAND(costs.R[0].rows() == k_); + DRAKE_DEMAND(costs.R[0].cols() == k_); + DRAKE_DEMAND(costs.U[0].rows() == n_ + m_ + k_); + DRAKE_DEMAND(costs.U[0].cols() == n_ + m_ + k_); + DRAKE_DEMAND(costs.G[0].rows() == n_ + m_ + k_); + DRAKE_DEMAND(costs.G[0].cols() == n_ + m_ + k_); + Q_ = costs.Q; + R_ = costs.R; + U_ = costs.U; + G_ = costs.G; +} + void C3::UpdateLCS(const LCS& lcs) { + DRAKE_DEMAND(lcs.A_.size() == N_); + DRAKE_DEMAND(lcs.A_[0].rows() == n_); + DRAKE_DEMAND(lcs.A_[0].cols() == n_); + DRAKE_DEMAND(lcs.D_[0].cols() == m_); + DRAKE_DEMAND(lcs.B_[0].cols() == k_); + // Update the stored LCS object. + lcs_ = lcs; A_ = lcs.A_; B_ = lcs.B_; D_ = lcs.D_; @@ -183,8 +210,9 @@ void C3::UpdateLCS(const LCS& lcs) { MatrixXd LinEq = MatrixXd::Zero(n_, 2 * n_ + m_ + k_); LinEq.block(0, n_ + k_ + m_, n_, n_) = -1 * MatrixXd::Identity(n_, n_); - auto Dn = D_[0].norm(); - auto An = A_[0].norm(); + + auto Dn = D_.at(0).norm(); + auto An = A_.at(0).norm(); AnDn_ = An / Dn; for (int i = 0; i < N_; ++i) { @@ -203,6 +231,19 @@ void C3::UpdateLCS(const LCS& lcs) { } } +void C3::UpdateCostLCS(const LCS& lcs_for_cost) { + DRAKE_DEMAND(lcs_for_cost.A_.size() == N_); + DRAKE_DEMAND(lcs_for_cost.A_[0].rows() == n_); + DRAKE_DEMAND(lcs_for_cost.A_[0].cols() == n_); + DRAKE_DEMAND(lcs_for_cost.B_[0].cols() == k_); + // Update the stored LCS object. + if (!lcs_for_cost_) { + lcs_for_cost_ = std::make_unique(lcs_for_cost); + }else{ + *lcs_for_cost_ = lcs_for_cost; + } +} + void C3::UpdateTarget(const std::vector& x_des) { x_desired_ = x_des; for (int i = 0; i < N_ + 1; i++) { @@ -211,7 +252,7 @@ void C3::UpdateTarget(const std::vector& x_des) { } } -void C3::Solve(const VectorXd& x0) { +void C3::Solve(const VectorXd& x0, bool verbose) { auto start = std::chrono::high_resolution_clock::now(); VectorXd delta_init = VectorXd::Zero(n_ + m_ + k_); @@ -223,12 +264,21 @@ void C3::Solve(const VectorXd& x0) { vector Gv = G_; for (int i = 0; i < N_; ++i) { - input_costs_[i]->UpdateCoefficients(2 * R_.at(i), - -2 * R_.at(i) * u_sol_->at(i)); + if (options_.penalize_changes_in_u_across_solves) { + // Penalize deviation from previous input solution: input cost is + // (u-u_prev)' * R * (u-u_prev). + input_costs_[i]->UpdateCoefficients(2 * R_.at(i), + -2 * R_.at(i) * u_sol_->at(i)); + } + else{ + // Penalize inputs: input cost is u' * R * u. + input_costs_[i]->UpdateCoefficients(2 * R_.at(i), + Eigen::VectorXd::Zero(k_)); + } } for (int iter = 0; iter < options_.admm_iter; iter++) { - ADMMStep(x0, &delta, &w, &Gv, iter); + ADMMStep(x0, &delta, &w, &Gv, iter, verbose); } vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); @@ -238,6 +288,26 @@ void C3::Solve(const VectorXd& x0) { vector zfin = SolveQP(x0, Gv, WD, options_.admm_iter, true); + if (verbose) { + std::cout << "x0: " << x0.transpose() << std::endl; + std::cout << "Final ADMM Iteration: " << options_.admm_iter << std::endl; + // Make matrix versions of variables for more compact printing. + Eigen::MatrixXd verbose_delta = Eigen::MatrixXd::Zero(n_ + m_ + k_, N_); + Eigen::MatrixXd verbose_w = Eigen::MatrixXd::Zero(n_ + m_ + k_, N_); + Eigen::MatrixXd verbose_zfin = Eigen::MatrixXd::Zero(n_ + m_ + k_, N_); + Eigen::MatrixXd verbose_zsol = Eigen::MatrixXd::Zero(n_ + m_ + k_, N_); + for(int i = 0; i < N_; i++) { + verbose_delta.col(i) = delta[i]; + verbose_w.col(i) = w[i]; + verbose_zfin.col(i) = zfin_[i]; + verbose_zsol.col(i) = z_sol_->at(i); + } + std::cout<<"zfin: \n"<at(i).segment(n_, m_) *= AnDn_; } + zfin_ = zfin; auto finish = std::chrono::high_resolution_clock::now(); auto elapsed = finish - start; solve_time_ = @@ -264,9 +335,351 @@ void C3::Solve(const VectorXd& x0) { 1e6; } +// This function relies on the previously computed zfin_ from Solve. +std::pair> C3::CalcCost( + C3CostComputationType cost_type, + double Kp_for_ee_pd_rollout, + double Kd_for_ee_pd_rollout, + bool force_tracking_disabled, + bool print_cost_breakdown, + bool verbose) const { + vector UU(N_, VectorXd::Zero(k_)); + std::vector XX(N_+1, VectorXd::Zero(n_)); + + // Simulate the dynamics from the planned inputs. + if (cost_type == C3CostComputationType::kSimLCS) { + XX[0] = zfin_[0].segment(0, n_); + for (int i = 0; i < N_; i++) { + UU[i] = zfin_[i].segment(n_ + m_, k_); + if (lcs_for_cost_) { + XX[i+1] = lcs_for_cost_->Simulate(XX[i], UU[i]); + } + else { + XX[i+1] = lcs_.Simulate(XX[i], UU[i]); + } + } + } + + // Use the C3 plan. + else if (cost_type == C3CostComputationType::kUseC3Plan) { + for (int i = 0; i < N_; i++) { + UU[i] = zfin_[i].segment(n_ + m_, k_); + XX[i] = zfin_[i].segment(0, n_); + if (i == N_-1) { + if (lcs_for_cost_) { + XX[i+1] = lcs_for_cost_->Simulate(XX[i], UU[i]); + } + else { + XX[i+1] = lcs_.Simulate(XX[i], UU[i]); + } + } + } + } + + // Simulate the dynamics from the planned inputs only for the object; use the + // planned EE trajectory. + else if (cost_type == C3CostComputationType::kSimLCSReplaceC3EEPlan) { + // Simulate the object trajectory. + XX[0] = zfin_[0].segment(0, n_); + for (int i = 0; i < N_; i++) { + UU[i] = zfin_[i].segment(n_ + m_, k_); + if (lcs_for_cost_) { + XX[i+1] = lcs_for_cost_->Simulate(XX[i], UU[i]); + } + else { + XX[i+1] = lcs_.Simulate(XX[i], UU[i]); + } + } + // Replace ee traj with those from zfin_. + for (int i = 0; i < N_; i++) { + XX[i].segment(0,3) = zfin_[i].segment(0,3); + if (i == N_-1) { + if (lcs_for_cost_) { + XX[i+1].segment(0,3) = + lcs_for_cost_->Simulate(XX[i], UU[i]).segment(0,3); + } + else { + XX[i+1].segment(0,3) = lcs_.Simulate(XX[i], UU[i]).segment(0,3); + } + } + } + } + + // Try to emulate the real cost of the system associated not only applying the + // planned u but also the u associated with tracking the position plan over + // time. + else if (cost_type == C3CostComputationType::kSimImpedance) { + std::tie(XX, UU) = SimulatePDControl(Kp_for_ee_pd_rollout, + Kd_for_ee_pd_rollout, + force_tracking_disabled, + verbose); + } + + // The same as the previous cost type except the EE states are replaced with + // the plan from C3 at the end. + else if (cost_type == C3CostComputationType::kSimImpedanceReplaceC3EEPlan) { + std::tie(XX, UU) = SimulatePDControl(Kp_for_ee_pd_rollout, + Kd_for_ee_pd_rollout, + force_tracking_disabled, + verbose); + + // Replace the end effector position and velocity plans with the ones from + // the C3 plan. + for(int i = 0; i < N_; i++) { + XX[i].segment(0,3) = zfin_[i].segment(0,3); + XX[i].segment(10,3) = zfin_[i].segment(10,3); + if (i == N_-1) { + XX[i+1].segment(0,3) = zfin_[i].segment(0,3); + XX[i+1].segment(10,3) = zfin_[i].segment(10,3); + } + } + } + + // The same as the previous cost type except only object terms contribute to + // the final cost. + else if (cost_type == C3CostComputationType::kSimImpedanceObjectCostOnly) { + std::tie(XX, UU) = SimulatePDControl(Kp_for_ee_pd_rollout, + Kd_for_ee_pd_rollout, + force_tracking_disabled, + verbose); + } + + // Declare Q_eff and R_eff as the Q and R to use for cost computation. + std::vector Q_eff = Q_; + std::vector R_eff = R_; + + // Calculate the cost over the N+1 time steps. + double cost = 0; + + //used only for verbose mode printouts + double error_contrib_ee_pos = 0; + double error_contrib_obj_orientation = 0; + double error_contrib_obj_pos = 0; + double error_contrib_ee_vel = 0; + double error_contrib_obj_ang_vel = 0; + double error_contrib_obj_vel = 0; + + double cost_contrib_ee_pos = 0; + double cost_contrib_obj_orientation = 0; + double cost_contrib_obj_pos = 0; + double cost_contrib_ee_vel = 0; + double cost_contrib_obj_ang_vel = 0; + double cost_contrib_obj_vel = 0; + + // Calculate the error and cost contributions for each state. + for (int i = 0; i < N_; i++) { + //ee_pos + error_contrib_ee_pos += + (XX[i].segment(0,3) - x_desired_[i].segment(0,3)).transpose() * + (XX[i].segment(0,3) - x_desired_[i].segment(0,3)); + cost_contrib_ee_pos += + (XX[i].segment(0,3) - x_desired_[i].segment(0,3)).transpose() * + Q_eff.at(i).block(0,0,3,3)*(XX[i].segment(0,3) - + x_desired_[i].segment(0,3)); + //obj_orientation + error_contrib_obj_orientation += + (XX[i].segment(3,4) - x_desired_[i].segment(3,4)).transpose() * + (XX[i].segment(3,4) - x_desired_[i].segment(3,4)); + cost_contrib_obj_orientation += + (XX[i].segment(3,4) - x_desired_[i].segment(3,4)).transpose() * + Q_eff.at(i).block(3,3,4,4) * + (XX[i].segment(3,4) - x_desired_[i].segment(3,4)); + //obj_pos + error_contrib_obj_pos += + (XX[i].segment(7,3) - x_desired_[i].segment(7,3)).transpose() * + (XX[i].segment(7,3) - x_desired_[i].segment(7,3)); + cost_contrib_obj_pos += + (XX[i].segment(7,3) - x_desired_[i].segment(7,3)).transpose() * + Q_eff.at(i).block(7,7,3,3)*(XX[i].segment(7,3) - + x_desired_[i].segment(7,3)); + //ee_vel + error_contrib_ee_vel += + (XX[i].segment(10,3) - x_desired_[i].segment(10,3)).transpose() * + (XX[i].segment(10,3) - x_desired_[i].segment(10,3)); + cost_contrib_ee_vel += + (XX[i].segment(10,3) - x_desired_[i].segment(10,3)).transpose() * + Q_eff.at(i).block(10,10,3,3) * (XX[i].segment(10,3) - + x_desired_[i].segment(10,3)); + //obj_ang_vel + error_contrib_obj_ang_vel += + (XX[i].segment(13,3) - x_desired_[i].segment(13,3)).transpose() * + (XX[i].segment(13,3) - x_desired_[i].segment(13,3)); + cost_contrib_obj_ang_vel += + (XX[i].segment(13,3) - x_desired_[i].segment(13,3)).transpose() * + Q_eff.at(i).block(13,13,3,3)*(XX[i].segment(13,3) - + x_desired_[i].segment(13,3)); + //obj_vel + error_contrib_obj_vel += + (XX[i].segment(16,3) - x_desired_[i].segment(16,3)).transpose() * + (XX[i].segment(16,3) - x_desired_[i].segment(16,3)); + cost_contrib_obj_vel += + (XX[i].segment(16,3) - x_desired_[i].segment(16,3)).transpose() * + Q_eff.at(i).block(16,16,3,3)*(XX[i].segment(16,3) - + x_desired_[i].segment(16,3)); + + cost = cost + (XX[i] - x_desired_[i]).transpose() * + Q_eff.at(i)*(XX[i] - x_desired_[i]) + + UU[i].transpose()*R_eff.at(i)*UU[i]; + } + + // Handle the N_th state. + cost = cost + (XX[N_] - x_desired_[N_]).transpose()*Q_eff.at(N_)*( + XX[N_] - x_desired_[N_]); + + error_contrib_ee_pos += + (XX[N_].segment(0,3) - x_desired_[N_].segment(0,3)).transpose() * + (XX[N_].segment(0,3) - x_desired_[N_].segment(0,3)); + error_contrib_obj_orientation += + (XX[N_].segment(3,4) - x_desired_[N_].segment(3,4)).transpose() * + (XX[N_].segment(3,4) - x_desired_[N_].segment(3,4)); + error_contrib_obj_pos += + (XX[N_].segment(7,3) - x_desired_[N_].segment(7,3)).transpose() * + (XX[N_].segment(7,3) - x_desired_[N_].segment(7,3)); + error_contrib_ee_vel += + (XX[N_].segment(10,3) - x_desired_[N_].segment(10,3)).transpose() * + (XX[N_].segment(10,3) - x_desired_[N_].segment(10,3)); + error_contrib_obj_ang_vel += + (XX[N_].segment(13,3) - x_desired_[N_].segment(13,3)).transpose() * + (XX[N_].segment(13,3) - x_desired_[N_].segment(13,3)); + error_contrib_obj_vel += + (XX[N_].segment(16,3) - x_desired_[N_].segment(16,3)).transpose() * + (XX[N_].segment(16,3) - x_desired_[N_].segment(16,3)); + + cost_contrib_ee_pos += + (XX[N_].segment(0,3) - x_desired_[N_].segment(0,3)).transpose() * + Q_eff.at(N_).block(0,0,3,3) * + (XX[N_].segment(0,3) - x_desired_[N_].segment(0,3)); + cost_contrib_obj_orientation += + (XX[N_].segment(3,4) - x_desired_[N_].segment(3,4)).transpose() * + Q_eff.at(N_).block(3,3,4,4)*(XX[N_].segment(3,4) - + x_desired_[N_].segment(3,4)); + cost_contrib_obj_pos += + (XX[N_].segment(7,3) - x_desired_[N_].segment(7,3)).transpose() * + Q_eff.at(N_).block(7,7,3,3)*(XX[N_].segment(7,3) - + x_desired_[N_].segment(7,3)); + cost_contrib_ee_vel += + (XX[N_].segment(10,3) - x_desired_[N_].segment(10,3)).transpose() * + Q_eff.at(N_).block(10,10,3,3)*(XX[N_].segment(10,3) - + x_desired_[N_].segment(10,3)); + cost_contrib_obj_ang_vel += + (XX[N_].segment(13,3) - x_desired_[N_].segment(13,3)).transpose() * + Q_eff.at(N_).block(13,13,3,3)*(XX[N_].segment(13,3) - + x_desired_[N_].segment(13,3)); + cost_contrib_obj_vel += + (XX[N_].segment(16,3) - x_desired_[N_].segment(16,3)).transpose() * + Q_eff.at(N_).block(16,16,3,3)*(XX[N_].segment(16,3) - + x_desired_[N_].segment(16,3)); + + if (cost_type == C3CostComputationType::kSimImpedanceObjectCostOnly) { + cost = cost_contrib_obj_pos + cost_contrib_obj_orientation + + cost_contrib_obj_vel + cost_contrib_obj_ang_vel; + } + + if (verbose || print_cost_breakdown) { + std::cout<<"Error breakdown"<> ret (cost, XX); + return ret; +} + +std::pair, std::vector> + C3::SimulatePDControl( + double Kp_for_ee_pd_rollout, double Kd_for_ee_pd_rollout, + bool force_tracking_disabled, bool verbose) const + { + if (verbose) { + std::cout<<"\nSIMULATING PD CONTROL"< UU(N_, VectorXd::Zero(k_)); + std::vector XX(N_+1, VectorXd::Zero(n_)); + for (int i = 0; i < N_; i++) { + UU[i] = zfin_[i].segment(n_ + m_, k_); + XX[i] = zfin_[i].segment(0, n_); + if (i == N_-1) { + if (lcs_for_cost_) { + XX[i+1] = lcs_for_cost_->Simulate(XX[i], UU[i]); + } + else{ + XX[i+1] = lcs_.Simulate(XX[i], UU[i]); + } + } + } + + // Set the PD gains for the emulated tracking controller. + Eigen::MatrixXd Kp = Kp_for_ee_pd_rollout*Eigen::MatrixXd::Identity(3,3); + Eigen::MatrixXd Kd = Kd_for_ee_pd_rollout*Eigen::MatrixXd::Identity(3,3); + + // Obtain modified solutions for the PD controller. + std::vector UU_new(N_, VectorXd::Zero(k_)); + std::vector XX_new(N_+1, VectorXd::Zero(n_)); + + XX_new[0] = zfin_[0].segment(0, n_); + // This will just be the original u from zfin_[0] for the first time step. + // if the radio input is true, then the u will only emulate position + // tracking using the PD controller. + for (int i = 0; i < N_; i++) { + if (force_tracking_disabled) { + UU_new[i] = Kp*(XX[i].segment(0, 3) - XX_new[i].segment(0, 3)) + + Kd*(XX[i].segment(10, 3) - XX_new[i].segment(10, 3)); + } + else{ + UU_new[i] = UU[i] + + Kp*(XX[i].segment(0, 3) - XX_new[i].segment(0, 3)) + + Kd*(XX[i].segment(10, 3) - XX_new[i].segment(10, 3)); + } + if (lcs_for_cost_) { + + if (verbose) { + std::cout<<"simulated step "<Simulate(XX_new[i], UU_new[i], verbose); + } + else{ + XX_new[i+1] = lcs_.Simulate(XX_new[i], UU_new[i]); + } + } + return {XX_new, UU_new}; +} + void C3::ADMMStep(const VectorXd& x0, vector* delta, vector* w, vector* Gv, - int admm_iteration) { + int admm_iteration, bool verbose) { vector WD(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { @@ -274,6 +687,14 @@ void C3::ADMMStep(const VectorXd& x0, vector* delta, } vector z = SolveQP(x0, *Gv, WD, admm_iteration, true); + if (verbose) { + std::cout << "SolveQP Iteration: " << admm_iteration << std::endl; + Eigen::MatrixXd verbose_z = Eigen::MatrixXd::Zero(n_ + m_ + k_, N_); + for(int i = 0; i < N_; i++) { + verbose_z.col(i) = z[i]; + } + std::cout<<"z: \n"< ZW(N_, VectorXd::Zero(n_ + m_ + k_)); for (int i = 0; i < N_; i++) { @@ -286,6 +707,14 @@ void C3::ADMMStep(const VectorXd& x0, vector* delta, } else { *delta = SolveProjection(U_, ZW, admm_iteration); } + if (verbose) { + std::cout << "ADMM Iteration: " << admm_iteration << std::endl; + Eigen::MatrixXd verbose_delta = Eigen::MatrixXd::Zero(n_ + m_ + k_, N_); + for(int i = 0; i < N_; i++) { + verbose_delta.col(i) = delta->at(i); + } + std::cout<<"delta: \n"<at(i) = w->at(i) + z[i] - delta->at(i); @@ -306,7 +735,7 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, if (h_is_zero_ == 1) { // No dependence on u, so just simulate passive system drake::solvers::MobyLCPSolver LCPSolver; VectorXd lambda0; - LCPSolver.SolveLcpLemke(F_[0], E_[0] * x0 + c_[0], &lambda0); + LCPSolver.SolveLcpLemkeRegularized(F_[0], E_[0] * x0 + c_[0], &lambda0); constraints_.push_back(prog_.AddLinearConstraint(lambda_[0] == lambda0)); } @@ -376,6 +805,9 @@ vector C3::SolveQP(const VectorXd& x0, const vector& G, warm_start_x_[admm_iteration][N_] = result.GetSolution(x_[N_]); } } + else { + std::cout<<"CAUTION: C3 QP solve did not succeed" << std::endl; + } return *z_sol_; } @@ -388,7 +820,10 @@ vector C3::SolveProjection(const vector& U, if (options_.num_threads > 0) { omp_set_dynamic(0); // Explicitly disable dynamic teams omp_set_num_threads(options_.num_threads); // Set number of threads - omp_set_max_active_levels(1); + // TODO: A newer version of OpenMP likely uses omp_set_max_active_levels + // instead of omp_set_nested. Consider updating this after testing. + omp_set_nested(1); // Enable nested parallelism (important for + // sampling_c3_controller) } #pragma omp parallel for num_threads(options_.num_threads) diff --git a/solvers/c3.h b/solvers/c3.h index 824c6410e4..922da99fa5 100644 --- a/solvers/c3.h +++ b/solvers/c3.h @@ -29,29 +29,66 @@ class C3 { std::vector U; }; /// @param LCS LCS parameters - /// @param Q, R, G, U Cost Matrices + /// @param costs Cost Matrices + /// @param x_des Desired goal state + /// @param options C3 options C3(const LCS& LCS, const CostMatrices& costs, const std::vector& x_des, const C3Options& options); virtual ~C3() = default; - /// Solve the MPC problem + /// Solve the MPC problem. /// @param x0 The initial state of the system + /// @param verbose Whether to print additional information /// @return void - void Solve(const Eigen::VectorXd& x0); - - /// Solve a single ADMM step + void Solve(const Eigen::VectorXd& x0, bool verbose = false); + + /// Compute the MPC cost, using previously solved MPC solution. + /// @param cost_type The method of computing the cost + /// @param Kp_for_ee_pd_rollout Proportional gain for simulated EE PD control + /// used for some of the cost types + /// @param Kd_for_ee_pd_rollout Derivative gain for simulated EE PD control + /// used for some of the cost types + /// @param force_tracking_disabled Whether to simulate EE PD control with + /// feedforward u from the MPC solution + /// @param print_cost_breakdown Whether to print the cost breakdown + /// @param verbose Whether to print additional information + /// @return The cost and its associated state trajectory + std::pair> CalcCost( + C3CostComputationType cost_type = kSimLCSReplaceC3EEPlan, + double Kp_for_ee_pd_rollout = 0.0, double Kd_for_ee_pd_rollout = 0.0, + bool force_tracking_disabled = false, bool print_cost_breakdown = false, + bool verbose = false) const; + + /// Helper function to simulate the dynamics with PD control on the EE + /// location and velocity plans, and the control input plans. Used for cost + /// types that simulate the impedance control. + /// @param Kp_for_ee_pd_rollout Proportional gain for simulated EE PD control + /// @param Kd_for_ee_pd_rollout Derivative gain for simulated EE PD control + /// @param force_tracking_disabled Whether to simulate EE PD control with + /// feedforward u from the MPC solution + /// @param verbose Whether to print additional information + /// @return the simulated state and input trajectories + std::pair, std::vector> + SimulatePDControl(double Kp_for_ee_pd_rollout = 0.0, + double Kd_for_ee_pd_rollout = 0.0, + bool force_tracking_disabled = false, + bool verbose = false) const; + + /// Solve a single ADMM step. /// @param x0 The initial state of the system /// @param delta The copy variables from the previous step /// @param w The scaled dual variables from the previous step /// @param G A pointer to the G variables from previous step /// @param admm_iteration ADMM iteration for accurate warm starting + /// @param verbose Whether to print additional information /// @return solution is saved in C3 object void ADMMStep(const Eigen::VectorXd& x0, std::vector* delta, std::vector* w, - std::vector* G, int admm_iteration); + std::vector* G, int admm_iteration, + bool verbose = false); - /// Solve a single QP + /// Solve a single QP. /// @param x0 The initial state of the system /// @param G A pointer to the G variables from previous step /// @param WD A pointer to the (w - delta) variables @@ -65,7 +102,7 @@ class C3 { int admm_iteration, bool is_final_solve = false); - /// Solve the projection problem for all timesteps + /// Solve the projection problem for all timesteps. /// @param U Matrix for consensus cost /// @param WZ (z + w) variables /// @param admm_iteration ADMM iteration for accurate warm starting @@ -82,7 +119,7 @@ class C3 { /// remove all constraints void RemoveConstraints(); - /// Solve a projection step for a single knot point k + /// Solve a projection step for a single knot point k. /// @param U Matrix for consensus cost /// @param delta_c A pointer to the copy of (z + w) variables /// @param E, F, H, c LCS contact parameters @@ -95,7 +132,7 @@ class C3 { const Eigen::MatrixXd& H, const Eigen::VectorXd& c, const int admm_iteration, const int& warm_start_index) = 0; - /// Solve a robust (friction cone) projection step for a single knot point k + /// Solve a robust (friction cone) projection step for a single knot point k. /// @param U Matrix for consensus cost /// @param delta_c A pointer to the copy of (z + w) variables /// @param E, F, H, c LCS contact parameters @@ -125,7 +162,15 @@ class C3 { std::vector GetDualWSolution() { return *w_sol_; } public: + void UpdateCostMatrices(const C3::CostMatrices& costs); void UpdateLCS(const LCS& lcs); + + /// Update the LCS used for cost computation. This can differ from the LCS + /// used for the solve, e.g. if more contacts are used for cost than for + /// computing the plan. NOTE: This does not update the internal cost + /// matrices used for the solve (Q_, R_, G_, U_). Those are updated via + /// UpdateCostMatrices. + void UpdateCostLCS(const LCS& lcs_for_cost); void UpdateTarget(const std::vector& x_des); protected: @@ -139,8 +184,13 @@ class C3 { const int n_; // n_x const int m_; // n_lambda const int k_; // n_u + const C3Options options_; private: + // TODO: storing the LCS as a class variable makes the LCS matrices + // redundant. Could consider removing LCS matrices as class variables. + mutable LCS lcs_; + std::unique_ptr lcs_for_cost_; std::vector A_; std::vector B_; std::vector D_; @@ -154,12 +204,11 @@ class C3 { Eigen::MatrixXd W_u_; Eigen::VectorXd w_; double AnDn_ = 1.0; - const std::vector Q_; - const std::vector R_; - const std::vector U_; - const std::vector G_; + std::vector Q_; + std::vector R_; + std::vector U_; + std::vector G_; std::vector x_desired_; - const C3Options options_; double dt_ = 0; double solve_time_ = 0; bool h_is_zero_; @@ -185,6 +234,7 @@ class C3 { std::vector> input_costs_; // Solutions + mutable std::vector zfin_; std::unique_ptr> x_sol_; std::unique_ptr> lambda_sol_; std::unique_ptr> u_sol_; diff --git a/solvers/c3_miqp.cc b/solvers/c3_miqp.cc index 1895514c9a..e8448cbd0d 100644 --- a/solvers/c3_miqp.cc +++ b/solvers/c3_miqp.cc @@ -12,8 +12,8 @@ C3MIQP::C3MIQP(const LCS& LCS, const CostMatrices& costs, : C3(LCS, costs, xdesired, options), env_(true) { // Create an environment env_.set("LogToConsole", "0"); - env_.set("OutputFlag", "1"); - env_.set("Threads", "0"); + env_.set("OutputFlag", "0"); + env_.set("Threads", "5"); env_.start(); } @@ -74,7 +74,7 @@ VectorXd C3MIQP::SolveSingleProjection(const MatrixXd& U, // } // } - int M = 1000; // big M variable + int M = 100000; // big M variable double coeff[n_ + m_ + k_]; double coeff2[n_ + m_ + k_]; diff --git a/solvers/c3_options.h b/solvers/c3_options.h index 6b201063fb..e79fd6db6f 100644 --- a/solvers/c3_options.h +++ b/solvers/c3_options.h @@ -3,6 +3,33 @@ #include "drake/common/yaml/yaml_read_archive.h" + +/* Ways of computing C3 costs after solving the MPC problem: + 0. kSimLCS: Simulate the LCS dynamics from the planned + inputs. + 1. kUseC3Plan: Use the C3 planned trajectory and inputs. + 2. kSimLCSReplaceC3EEPlan: Simulate the LCS dynamics from the planned + inputs only for the object; use the planned + EE trajectory. + 3. kSimImpedance: Try to emulate the real cost of the system + associated not only applying the planned + inputs, but also tracking the planned EE + trajectory with an impedance controller. + 4. kSimImpedanceReplaceC3EEPlan: The same as kSimImpedance except the EE + states are replaced with the plan from C3 at + the end. + 5. kSimImpedanceObjectCostOnly: The same as kSimImpedance except only the + object terms contribute to the final cost. +*/ +enum C3CostComputationType { + kSimLCS, + kUseC3Plan, + kSimLCSReplaceC3EEPlan, + kSimImpedance, + kSimImpedanceReplaceC3EEPlan, + kSimImpedanceObjectCostOnly, +}; + struct C3Options { // Hyperparameters int admm_iter; // total number of ADMM iterations @@ -19,9 +46,6 @@ struct C3Options { double solve_time_filter_alpha; double publish_frequency; -// std::vector world_x_limits; -// std::vector world_y_limits; -// std::vector world_z_limits; std::vector u_horizontal_limits; std::vector u_vertical_limits; std::vector workspace_limits; @@ -54,9 +78,12 @@ struct C3Options { std::vector u_lambda; std::vector u_u; + double qp_projection_alpha; + double qp_projection_scaling; + bool penalize_changes_in_u_across_solves; std::vector mu; double dt; - double solve_dt; + double solve_dt; // unused int num_friction_directions; int num_contacts; Eigen::MatrixXd Q; @@ -115,6 +142,10 @@ struct C3Options { a->Visit(DRAKE_NVP(u_lambda)); a->Visit(DRAKE_NVP(u_u)); + a->Visit(DRAKE_NVP(qp_projection_alpha)); + a->Visit(DRAKE_NVP(qp_projection_scaling)); + a->Visit(DRAKE_NVP(penalize_changes_in_u_across_solves)); + g_vector = std::vector(); g_vector.insert(g_vector.end(), g_x.begin(), g_x.end()); if (contact_model == "stewart_and_trinkle") { diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc index 1fbfa9af95..dca591db8d 100644 --- a/solvers/c3_qp.cc +++ b/solvers/c3_qp.cc @@ -44,10 +44,11 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, auto ln_ = prog.NewContinuousVariables(m_, "lambda"); auto un_ = prog.NewContinuousVariables(k_, "u"); - double alpha = 0.01; - double scaling = 1000; + // As alpha -> 0, the complimentarity condition is enforced more strictly. + double alpha = options_.qp_projection_alpha; + double scaling = options_.qp_projection_scaling; - MatrixXd EFH(m_, n_ + m_ + k_); + MatrixXd EFH = MatrixXd::Zero(m_, n_ + m_ + k_); EFH.block(0, 0, m_, n_) = E / scaling; EFH.block(0, n_, m_, m_) = F / scaling; EFH.block(0, n_ + m_, m_, k_) = H / scaling; @@ -67,10 +68,8 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, VectorXd cost_linear = -delta_c.transpose() * New_U; - // prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}, 1); prog.AddQuadraticCost(New_U, cost_linear, {xn_, ln_, un_}, 1); - // prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); prog.AddQuadraticCost((1 - alpha) * F, VectorXd::Zero(m_), ln_, 1); solver_options.SetOption(OsqpSolver::id(), "max_iter", 500); diff --git a/solvers/lcs.cc b/solvers/lcs.cc index 7433279a38..cc1458459f 100644 --- a/solvers/lcs.cc +++ b/solvers/lcs.cc @@ -96,16 +96,25 @@ LCS& LCS::operator=(const LCS& lcs) { return *this; } -const VectorXd LCS::Simulate(VectorXd& x_init, VectorXd& input) { +const VectorXd LCS::Simulate(const VectorXd& x_init, const VectorXd& input, + bool verbose) { VectorXd x_final; // calculate force drake::solvers::MobyLCPSolver LCPSolver; VectorXd force; - auto flag = LCPSolver.SolveLcpLemke( + auto flag = LCPSolver.SolveLcpLemkeRegularized( F_[0], E_[0] * x_init + c_[0] + H_[0] * input, &force); + + if (flag == 0) { + std::cout << "LCP failed: returning x_init" << std::endl; + return x_init; + } // update x_final = A_[0] * x_init + B_[0] * input + D_[0] * force + d_[0]; + if (verbose) { + std::cout<<"\tLCP simulated force is "< A_; diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index 404807c61b..e1568031b5 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -42,6 +42,7 @@ LCS LCSFactory::LinearizePlantToLCS( DRAKE_DEMAND(plant_ad.num_velocities() == plant.num_velocities()); DRAKE_DEMAND(plant_ad.num_positions() == plant.num_positions()); + DRAKE_DEMAND(mu.size() == n_contacts); int n_v = plant.num_velocities(); int n_q = plant.num_positions(); @@ -123,9 +124,9 @@ LCS LCSFactory::LinearizePlantToLCS( MatrixXd MinvJ_n_T = M_ldlt.solve(J_n.transpose()); MatrixXd MinvJ_t_T = M_ldlt.solve(J_t.transpose()); - MatrixXd A(n_x, n_x); - MatrixXd B(n_x, n_u); - VectorXd d(n_x); + MatrixXd A = MatrixXd::Zero(n_x, n_x); + MatrixXd B = MatrixXd::Zero(n_x, n_u); + VectorXd d = VectorXd::Zero(n_x); MatrixXd AB_v_q = AB_v.block(0, 0, n_v, n_q); MatrixXd AB_v_v = AB_v.block(0, n_q, n_v, n_v); @@ -295,10 +296,7 @@ LCSFactory::ComputeContactJacobian( MatrixXd J_t(2 * n_contacts * num_friction_directions, n_v); std::vector contact_points; for (int i = 0; i < n_contacts; i++) { - multibody::GeomGeomCollider collider( - plant, - contact_geoms[i]); // deleted num_friction_directions (check with - // Michael about changes in geomgeom) + multibody::GeomGeomCollider collider(plant, contact_geoms[i]); auto [phi_i, J_i] = collider.EvalPolytope(context, num_friction_directions); auto [p_WCa, p_WCb] = collider.CalcWitnessPoints(context); // TODO(yangwill): think about if we want to push back both witness points @@ -454,5 +452,97 @@ LCS LCSFactory::FixSomeModes(const LCS& other, set active_lambda_inds, return LCS(A, B, D, d, E, F, H, c, other.dt_); } +vector> LCSFactory::PreProcessor( + const MultibodyPlant& plant, const Context& context, + const vector>>& contact_geoms, + const vector& resolve_contacts_to_list, + int num_friction_directions, bool verbose) { + + int n_contacts = std::accumulate( + resolve_contacts_to_list.begin(), resolve_contacts_to_list.end(), 0); + std::vector> resolved_contacts; + resolved_contacts.reserve(n_contacts); + + for (int i = 0; i < contact_geoms.size(); i++) { + DRAKE_ASSERT(contact_geoms[i].size() >= resolve_contacts_to_list[i]); + + const auto& candidates = contact_geoms[i]; + const int num_to_select = resolve_contacts_to_list[i]; + + if (verbose && candidates.size() > 1) { + std::cout << "Contact pair " << i << " : choosing between:" << std::endl; + } + + std::vector distances; + distances.reserve(candidates.size()); + + for (const auto& pair : candidates) { + multibody::GeomGeomCollider collider(plant, pair); + auto [phi_i, J_i] = collider.EvalPolytope(context, + num_friction_directions); + distances.push_back(phi_i); + if (verbose) { + PrintVerboseContactInfo(plant, context, pair, phi_i); + } + } + + for (int j = 0; j < num_to_select; ++j) { + auto min_it = std::min_element(distances.begin(), distances.end()); + int min_index = std::distance(distances.begin(), min_it); + resolved_contacts.push_back(candidates[min_index]); + distances[min_index] = std::numeric_limits::infinity(); + + if (verbose && candidates.size() > 1) { + std::cout << " --> Chose option " << min_index << std::endl; + } + } + } + DRAKE_DEMAND(resolved_contacts.size() == n_contacts); + return resolved_contacts; +} + +void LCSFactory::PrintVerboseContactInfo(const MultibodyPlant& plant, + const Context& context, + const SortedPair& pair, + const double phi_i) { + const auto& query_port = plant.get_geometry_query_input_port(); + const auto& query_object = + query_port.template Eval>(context); + const auto& inspector = query_object.inspector(); + + // Get the witness points on each geometry. + const SignedDistancePair signed_distance_pair = + query_object.ComputeSignedDistancePairClosestPoints( + pair.first(), pair.second()); + + const Eigen::Vector3d& p_ACa = + inspector.GetPoseInFrame(pair.first()).template cast() * + signed_distance_pair.p_ACa; + const Eigen::Vector3d& p_BCb = + inspector.GetPoseInFrame(pair.second()).template cast() * + signed_distance_pair.p_BCb; + + // Represent the witness points as points in world frame. + RigidTransform T_body1_contact = RigidTransform(p_ACa); + const FrameId f1_id = inspector.GetFrameId(pair.first()); + const Body* body1 = plant.GetBodyFromFrameId(f1_id); + RigidTransform T_world_body1 = body1->EvalPoseInWorld(context); + Eigen::Vector3d p_world_contact_a = T_world_body1 * + T_body1_contact.translation(); + + RigidTransform T_body2_contact = RigidTransform(p_BCb); + const FrameId f2_id = inspector.GetFrameId(pair.second()); + const Body* body2 = plant.GetBodyFromFrameId(f2_id); + RigidTransform T_world_body2 = body2->EvalPoseInWorld(context); + Eigen::Vector3d p_world_contact_b = T_world_body2 * + T_body2_contact.translation(); + + std::cout << "Contact pair: (" << inspector.GetName(pair.first()) + << ", " << inspector.GetName(pair.second()) + << ") with phi = " << phi_i << " between world points [" + << p_world_contact_a.transpose() << "], [" + << p_world_contact_b.transpose() << "]" << std::endl; +} + } // namespace solvers } // namespace dairlib diff --git a/solvers/lcs_factory.h b/solvers/lcs_factory.h index e86d94d439..3038f72393 100644 --- a/solvers/lcs_factory.h +++ b/solvers/lcs_factory.h @@ -3,7 +3,21 @@ #include #include "solvers/lcs.h" +#include "multibody/geom_geom_collider.h" +#include "drake/geometry/query_object.h" +#include "drake/geometry/geometry_ids.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/math/rigid_transform.h" +using std::vector; +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::multibody::MultibodyPlant; +using drake::multibody::Body; +using drake::math::RigidTransform; +using drake::geometry::FrameId; +using drake::systems::Context; +using drake::geometry::SignedDistancePair; namespace dairlib { namespace solvers { @@ -59,6 +73,37 @@ class LCSFactory { /// @param inactive_lambda_inds The indices for lambda that must be 0 static LCS FixSomeModes(const LCS& other, std::set active_lambda_inds, std::set inactive_lambda_inds); + + /// Optionally preprocess contact pairs to select the closest contacts + /// @param plant The MultibodyPlant + /// @param context The plant context + /// @param contact_geoms The contact geometries + /// @param resolve_contacts_to_list The number of contacts to resolve to + /// @param num_friction_directions The number of friction directions + /// @param verbose Whether to print verbose information + /// @return The closest contacts + static std::vector> + PreProcessor( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const std::vector>>& + contact_geoms, + const std::vector& resolve_contacts_to_list, + int num_friction_directions, + bool verbose = false); + + private: + /// This function is for debugging purposes. This is largely a copy of the + /// EvalPolytope function in the GeomGeomCollider class with more verbosity. + /// @param plant The MultibodyPlant + /// @param context The plant context + /// @param pair The contact pair + /// @param phi_i The signed distance + static void PrintVerboseContactInfo( + const drake::multibody::MultibodyPlant& plant, + const drake::systems::Context& context, + const drake::SortedPair& pair, + const double phi_i); }; } // namespace solvers diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index d542343eba..b5f5f8d9f2 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -87,6 +87,38 @@ cc_library( ], ) +cc_library( + name = "sampling_c3_controller", + srcs = ["sampling_based_c3_controller.cc"], + hdrs = ["sampling_based_c3_controller.h"], + deps = [ + "//lcm:lcm_trajectory_saver", + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//solvers:c3", + "//solvers:c3_output", + "//solvers:solver_options_io", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "//examples/sampling_c3:generate_samples", + "//examples/sampling_c3:reposition", + "//common:quaternion_error_hessian", + "//solvers:lcs", + "//examples/sampling_c3/parameter_headers:sampling_c3_controller_params", + "//examples/sampling_c3/parameter_headers:sampling_c3_options", + "//examples/sampling_c3/parameter_headers:sampling_params", + "//examples/sampling_c3/parameter_headers:reposition_params", + "//examples/sampling_c3/parameter_headers:progress_params", + "//common:update_context", + ], + copts = [ + "-fopenmp", + ], + linkopts = [ + "-lgomp", + ], +) + cc_library( name = "gravity_compensator", srcs = [ diff --git a/systems/controllers/osc/end_effector_position.cc b/systems/controllers/osc/end_effector_position.cc index 835b1f4c90..b11a9f86b4 100644 --- a/systems/controllers/osc/end_effector_position.cc +++ b/systems/controllers/osc/end_effector_position.cc @@ -24,7 +24,7 @@ using drake::trajectories::Trajectory; namespace dairlib { -EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( +EndEffectorPositionTrajectoryGenerator::EndEffectorPositionTrajectoryGenerator( const MultibodyPlant& plant, Context* context, const Eigen::VectorXd& neutral_pose, bool teleop_neutral_pose, const std::string& end_effector_name) @@ -50,16 +50,16 @@ EndEffectorTrajectoryGenerator::EndEffectorTrajectoryGenerator( if (teleop_neutral_pose) { this->DeclareAbstractOutputPort( "end_effector_trajectory", traj_inst, - &EndEffectorTrajectoryGenerator::CalcPoseShiftingTraj); + &EndEffectorPositionTrajectoryGenerator::CalcPoseShiftingTraj); } else { this->DeclareAbstractOutputPort( "end_effector_trajectory", traj_inst, - &EndEffectorTrajectoryGenerator::CalcNeutralPoseBasedTraj); + &EndEffectorPositionTrajectoryGenerator::CalcNeutralPoseBasedTraj); } } -void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( +void EndEffectorPositionTrajectoryGenerator::SetRemoteControlParameters( const Eigen::Vector3d& neutral_pose, double x_scale, double y_scale, double z_scale) { neutral_pose_ = neutral_pose; @@ -69,7 +69,7 @@ void EndEffectorTrajectoryGenerator::SetRemoteControlParameters( z_scale_ = z_scale; } -void EndEffectorTrajectoryGenerator::CalcNeutralPoseBasedTraj( +void EndEffectorPositionTrajectoryGenerator::CalcNeutralPoseBasedTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { const auto& trajectory_input = @@ -100,7 +100,7 @@ void EndEffectorTrajectoryGenerator::CalcNeutralPoseBasedTraj( } } -void EndEffectorTrajectoryGenerator::CalcPoseShiftingTraj( +void EndEffectorPositionTrajectoryGenerator::CalcPoseShiftingTraj( const drake::systems::Context& context, drake::trajectories::Trajectory* traj) const { const auto& trajectory_input = diff --git a/systems/controllers/osc/end_effector_position.h b/systems/controllers/osc/end_effector_position.h index 4cf7c0f240..aa129c08f4 100644 --- a/systems/controllers/osc/end_effector_position.h +++ b/systems/controllers/osc/end_effector_position.h @@ -12,10 +12,10 @@ namespace dairlib { -class EndEffectorTrajectoryGenerator +class EndEffectorPositionTrajectoryGenerator : public drake::systems::LeafSystem { public: - EndEffectorTrajectoryGenerator( + EndEffectorPositionTrajectoryGenerator( const drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, const Eigen::VectorXd& neutral_pose, diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 4392564e12..ce1d027590 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -1089,10 +1089,13 @@ void OperationalSpaceControl::AssignOscLcmOutput( qp_output.v_dim = n_v_; qp_output.epsilon_dim = n_c_active_; qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); -// qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); -// qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); - qp_output.lambda_h_sol = CopyVectorXdToStdVector(force_tracking_data_vec_->at(0)->GetLambdaDes()); + // Only copy lambda solutions if a force tracking vector is provided. E.g., + // one is not provided in the Franka joint OSC. + if (!force_tracking_data_vec_->empty()){ + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); + qp_output.lambda_h_sol = CopyVectorXdToStdVector( + force_tracking_data_vec_->at(0)->GetLambdaDes()); + } qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; diff --git a/systems/controllers/sampling_based_c3_controller.cc b/systems/controllers/sampling_based_c3_controller.cc new file mode 100644 index 0000000000..4525ce05ad --- /dev/null +++ b/systems/controllers/sampling_based_c3_controller.cc @@ -0,0 +1,2188 @@ +#include "sampling_based_c3_controller.h" + +#include +#include +#include +#include + +#include +#include + +#include "common/quaternion_error_hessian.h" +#include "dairlib/lcmt_radio_out.hpp" +#include "drake/multibody/plant/multibody_plant.h" +#include "examples/sampling_c3/generate_samples.h" +#include "examples/sampling_c3/reposition.h" +#include "multibody/multibody_utils.h" +#include "solvers/c3_miqp.h" +#include "solvers/c3_options.h" +#include "solvers/c3_qp.h" +#include "solvers/lcs.h" + +#include "drake/common/trajectories/piecewise_polynomial.h" + +namespace dairlib { + +using drake::SortedPair; +using drake::geometry::GeometryId; +using drake::multibody::ModelInstanceIndex; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using drake::systems::DiscreteValues; +using drake::trajectories::PiecewisePolynomial; +using Eigen::MatrixXd; +using Eigen::MatrixXf; +using Eigen::Vector3d; +using Eigen::VectorXd; +using Eigen::VectorXf; +using solvers::C3; +using solvers::C3MIQP; +using solvers::C3QP; +using solvers::LCS; +using solvers::LCSFactory; +using std::vector; +using systems::TimestampedVector; + +namespace systems { + +SamplingC3Controller::SamplingC3Controller( + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + SamplingC3ControllerParams controller_params, + bool verbose) + : plant_(plant), + context_(context), + plant_ad_(plant_ad), + context_ad_(context_ad), + contact_pairs_(contact_geoms), + controller_params_(std::move(controller_params)), + sampling_c3_options_(controller_params_.sampling_c3_options), + sampling_params_(controller_params_.sampling_params), + reposition_params_(controller_params_.reposition_params), + progress_params_(controller_params_.progress_params), + G_(std::vector(sampling_c3_options_.N, sampling_c3_options_.G)), + U_(std::vector(sampling_c3_options_.N, sampling_c3_options_.U)), + N_(sampling_c3_options_.N), + verbose_(verbose) { + this->set_name("sampling_c3_controller"); + + // Build C3Options from SamplingC3Options. + C3Options c3_options = sampling_c3_options_.GetC3Options( + crossed_cost_switching_threshold_); + + // Initialize Q_ and R_ to proper size. Values don't matter because the + // values get rewritten at the beginning of every control loop. + double discount_factor = 1; + for (int i = 0; i < N_; ++i) { + Q_.push_back(discount_factor * c3_options.Q); + R_.push_back(discount_factor * c3_options.R); + discount_factor *= c3_options.gamma; + } + Q_.push_back(discount_factor * c3_options.Q); + DRAKE_DEMAND(Q_.size() == N_ + 1); + DRAKE_DEMAND(R_.size() == N_); + + n_q_ = plant_.num_positions(); + n_v_ = plant_.num_velocities(); + n_u_ = plant_.num_actuators(); + n_x_ = n_q_ + n_v_; + + solve_time_filter_constant_ = sampling_c3_options_.solve_time_filter_alpha; + + if (sampling_c3_options_.contact_model == "stewart_and_trinkle") { + contact_model_ = solvers::ContactModel::kStewartAndTrinkle; + n_lambda_ = + 2 * sampling_c3_options_.num_contacts + + 2 * sampling_c3_options_.num_friction_directions * + sampling_c3_options_.num_contacts; + } else if (sampling_c3_options_.contact_model == "anitescu") { + contact_model_ = solvers::ContactModel::kAnitescu; + n_lambda_ = 2 * sampling_c3_options_.num_friction_directions * + sampling_c3_options_.num_contacts; + } else { + std::cerr << ("Unknown or unsupported contact model: " + + sampling_c3_options_.contact_model) << std::endl; + DRAKE_THROW_UNLESS(false); + } + + // Placeholder LCS will have correct size as it's already determined by the + // contact model. + auto lcs_placeholder = CreatePlaceholderLCS(); + auto x_desired_placeholder = + std::vector(N_ + 1, VectorXd::Zero(n_x_)); + if (sampling_c3_options_.projection_type == "MIQP") { + c3_curr_plan_ = std::make_unique( + lcs_placeholder, C3::CostMatrices(Q_, R_, G_, U_), x_desired_placeholder, + c3_options); + c3_best_plan_ = std::make_unique( + lcs_placeholder, C3::CostMatrices(Q_, R_, G_, U_), x_desired_placeholder, + c3_options); + c3_buffer_plan_ = std::make_unique( + lcs_placeholder, C3::CostMatrices(Q_, R_, G_, U_), + x_desired_placeholder, c3_options); + } else if (sampling_c3_options_.projection_type == "QP") { + c3_curr_plan_ = std::make_unique( + lcs_placeholder, C3::CostMatrices(Q_, R_, G_, U_), + x_desired_placeholder, c3_options); + c3_best_plan_ = std::make_unique( + lcs_placeholder, C3::CostMatrices(Q_, R_, G_, U_), x_desired_placeholder, + c3_options); + c3_buffer_plan_ = std::make_unique( + lcs_placeholder, C3::CostMatrices(Q_, R_, G_, U_), x_desired_placeholder, + c3_options); + } else { + std::cerr << ("Unknown projection type") << std::endl; + DRAKE_THROW_UNLESS(false); + } + + c3_curr_plan_->SetOsqpSolverOptions(solver_options_); + c3_best_plan_->SetOsqpSolverOptions(solver_options_); + c3_buffer_plan_->SetOsqpSolverOptions(solver_options_); + + // Set actor bounds. + for (int i = 0; i < sampling_c3_options_.workspace_limits.size(); ++i) { + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A.segment(0, 3) = sampling_c3_options_.workspace_limits[i].segment(0, 3); + // TODO @bibit: For the T example, the z constraint is an equality + // constraint. This will be reflected in the params but need to make sure to + // put a comment here when the T example is added. + // The fourth parameter decides which optimization variable the constraint + // is applied to. 1 = x, 2 = u, 3 = lambda. + c3_curr_plan_->AddLinearConstraint( + A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], + 1); + c3_best_plan_->AddLinearConstraint( + A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], + 1); + c3_buffer_plan_->AddLinearConstraint( + A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], + 1); + } + for (int i : vector({0, 1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_curr_plan_->AddLinearConstraint( + A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], + 2); + c3_best_plan_->AddLinearConstraint( + A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], + 2); + c3_buffer_plan_->AddLinearConstraint( + A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], + 2); + } + for (int i : vector({2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + c3_curr_plan_->AddLinearConstraint( + A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); + c3_best_plan_->AddLinearConstraint( + A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); + c3_buffer_plan_->AddLinearConstraint( + A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); + } + + // Input ports. + radio_port_ = + this->DeclareAbstractInputPort("lcmt_radio_out", + drake::Value{}) + .get_index(); + lcs_state_input_port_ = + this->DeclareVectorInputPort("x_lcs", TimestampedVector(n_x_)) + .get_index(); + target_input_port_ = + this->DeclareVectorInputPort("x_lcs_des", n_x_).get_index(); + final_target_input_port_ = + this->DeclareVectorInputPort("x_lcs_final_des", n_x_).get_index(); + + // Output ports. + auto c3_solution = C3Output::C3Solution(); + c3_solution.x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); + c3_solution.lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); + c3_solution.u_sol_ = MatrixXf::Zero(n_u_, N_); + c3_solution.time_vector_ = VectorXf::Zero(N_); + auto c3_intermediates = C3Output::C3Intermediates(); + c3_intermediates.z_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.w_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.delta_ = MatrixXf::Zero(n_x_ + n_lambda_ + n_u_, N_); + c3_intermediates.time_vector_ = VectorXf::Zero(N_); + auto lcs_contact_jacobian = std::pair(Eigen::MatrixXd(n_x_, n_lambda_), + std::vector()); + + // Since the num_additional_samples_repos means the additional samples + // to generate in addition to the prev_repositioning_target_, add 1. + // Additionally add 1 to C3 if considering samples from the buffer. + int from_buffer = 0; + if (sampling_params_.consider_best_buffer_sample_when_leaving_c3) { + from_buffer = 1; + } + max_num_samples_ = + std::max(sampling_params_.num_additional_samples_repos + 1, + sampling_params_.num_additional_samples_c3 + from_buffer); + // The +1 here is to account for the current location. + all_sample_locations_ = + vector(max_num_samples_ + 1, Vector3d::Zero()); + LcmTrajectory lcm_traj = LcmTrajectory(); + + // Current location plan output ports. + // This output port is being kept so it can go into a C3outputSender which is + // what we use to grab downstream forces for visualization. + c3_solution_curr_plan_port_ = + this->DeclareAbstractOutputPort( + "c3_solution_curr_plan", c3_solution, + &SamplingC3Controller::OutputC3SolutionCurrPlan) + .get_index(); + c3_solution_curr_plan_actor_port_ = + this->DeclareAbstractOutputPort( + "c3_solution_curr_plan_actor", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputC3SolutionCurrPlanActor) + .get_index(); + c3_solution_curr_plan_object_port_ = + this->DeclareAbstractOutputPort( + "c3_solution_curr_plan_object", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputC3SolutionCurrPlanObject) + .get_index(); + c3_intermediates_curr_plan_port_ = + this->DeclareAbstractOutputPort( + "c3_intermediates_curr_plan", c3_intermediates, + &SamplingC3Controller::OutputC3IntermediatesCurrPlan) + .get_index(); + lcs_contact_jacobian_curr_plan_port_ = + this->DeclareAbstractOutputPort( + "J_lcs_curr_plan, p_lcs_curr_plan", lcs_contact_jacobian, + &SamplingC3Controller::OutputLCSContactJacobianCurrPlan) + .get_index(); + + // Best sample plan output ports. + // This output port is being kept so it can go into a C3outputSender which is + // what we use to grab downstream forces for visualization. + c3_solution_best_plan_port_ = + this->DeclareAbstractOutputPort( + "c3_solution_best_plan", c3_solution, + &SamplingC3Controller::OutputC3SolutionBestPlan) + .get_index(); + c3_solution_best_plan_actor_port_ = + this->DeclareAbstractOutputPort( + "c3_solution_best_plan_actor", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputC3SolutionBestPlanActor) + .get_index(); + c3_solution_best_plan_object_port_ = + this->DeclareAbstractOutputPort( + "c3_solution_best_plan_object", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputC3SolutionBestPlanObject) + .get_index(); + c3_intermediates_best_plan_port_ = + this->DeclareAbstractOutputPort( + "c3_intermediates_best_plan", c3_intermediates, + &SamplingC3Controller::OutputC3IntermediatesBestPlan) + .get_index(); + lcs_contact_jacobian_best_plan_port_ = + this->DeclareAbstractOutputPort( + "J_lcs_best_plan, p_lcs_best_plan", lcs_contact_jacobian, + &SamplingC3Controller::OutputLCSContactJacobianBestPlan) + .get_index(); + + // Execution trajectory output ports. + c3_traj_execute_actor_port_ = + this->DeclareAbstractOutputPort( + "c3_traj_execute_actor", dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputC3TrajExecuteActor) + .get_index(); + repos_traj_execute_actor_port_ = + this->DeclareAbstractOutputPort( + "repos_traj_execute_actor", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputReposTrajExecuteActor) + .get_index(); + traj_execute_actor_port_ = + this->DeclareAbstractOutputPort( + "traj_execute_actor", dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputTrajExecuteActor) + .get_index(); + is_c3_mode_port_ = + this->DeclareAbstractOutputPort( + "is_c3_mode", dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputIsC3Mode) + .get_index(); + + // Output ports for dynamically feasible plans used for cost computation and + // visualization. + dynamically_feasible_curr_plan_actor_port_ = + this->DeclareAbstractOutputPort( + "dynamically_feasible_curr_plan_actor", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputDynamicallyFeasibleCurrPlanActor) + .get_index(); + dynamically_feasible_curr_plan_object_port_ = + this->DeclareAbstractOutputPort( + "dynamically_feasible_curr_plan_object", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputDynamicallyFeasibleCurrPlanObject) + .get_index(); + dynamically_feasible_best_plan_actor_port_ = + this->DeclareAbstractOutputPort( + "dynamically_feasible_best_plan_actor", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputDynamicallyFeasibleBestPlanActor) + .get_index(); + dynamically_feasible_best_plan_object_port_ = + this->DeclareAbstractOutputPort( + "dynamically_feasible_best_plan_object", + dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputDynamicallyFeasibleBestPlanObject) + .get_index(); + + // Sample location related output ports. + // This port will output all samples except the current location. + // all_sample_locations_port_ does not include the current location. So + // index 0 is the first sample. + all_sample_locations_port_ = + this->DeclareAbstractOutputPort( + "all_sample_locations", dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputAllSampleLocations) + .get_index(); + // all_sample_costs_port_ does include the current location. So index 0 is + // the current location cost. + all_sample_costs_port_ = + this->DeclareAbstractOutputPort( + "all_sample_costs", dairlib::lcmt_timestamped_saved_traj(), + &SamplingC3Controller::OutputAllSampleCosts) + .get_index(); + + // A debug output port to publish information about the internals of the + // sampling-based controller. + debug_lcmt_port_ = + this->DeclareAbstractOutputPort("sampling_c3_debug", + dairlib::lcmt_sampling_c3_debug(), + &SamplingC3Controller::OutputDebug) + .get_index(); + + // Sample buffer related ouput ports. + sample_buffer_ = MatrixXd::Zero(sampling_params_.N_sample_buffer, n_q_); + sample_costs_buffer_ = -1 * VectorXd::Ones(sampling_params_.N_sample_buffer); + sample_buffer_configurations_port_ = + this->DeclareAbstractOutputPort( + "sample_buffer_configurations", sample_buffer_, + &SamplingC3Controller::OutputSampleBufferConfigurations) + .get_index(); + + sample_buffer_costs_port_ = + this->DeclareAbstractOutputPort( + "sample_buffer_costs", sample_costs_buffer_, + &SamplingC3Controller::OutputSampleBufferCosts) + .get_index(); + + plan_start_time_index_ = DeclareDiscreteState(1); + x_pred_curr_plan_ = VectorXd::Zero(n_x_); + x_from_last_control_loop_ = VectorXd::Zero(n_x_); + x_pred_from_last_control_loop_ = VectorXd::Zero(n_x_); + x_final_target_ = VectorXd::Zero(n_x_); + + ResetProgressMetrics(); + + DeclareForcedDiscreteUpdateEvent(&SamplingC3Controller::ComputePlan); + + // Set parallelization settings. + omp_set_dynamic(0); // Explicitly disable dynamic teams. + omp_set_nested(1); // Enable nested threading. + if (sampling_c3_options_.num_outer_threads == 0) { + // Interpret setting number of threads to zero as a request to use all + // machine's threads. + num_threads_to_use_ = omp_get_max_threads(); + } else { + num_threads_to_use_ = sampling_c3_options_.num_outer_threads; + } + + if (verbose_) { + std::cout << "Initial filtered_solve_time_: " << filtered_solve_time_ + << std::endl; + } +} + +LCS SamplingC3Controller::CreatePlaceholderLCS() const { + MatrixXd A = MatrixXd::Ones(n_x_, n_x_); + MatrixXd B = MatrixXd::Zero(n_x_, n_u_); + VectorXd d = VectorXd::Zero(n_x_); + MatrixXd D = MatrixXd::Ones(n_x_, n_lambda_); + MatrixXd E = MatrixXd::Zero(n_lambda_, n_x_); + MatrixXd F = MatrixXd::Zero(n_lambda_, n_lambda_); + MatrixXd H = MatrixXd::Zero(n_lambda_, n_u_); + VectorXd c = VectorXd::Zero(n_lambda_); + return LCS(A, B, D, d, E, F, H, c, sampling_c3_options_.N, + sampling_c3_options_.planning_dt_position); +} + +drake::systems::EventStatus SamplingC3Controller::ComputePlan( + const Context& context, + DiscreteValues* discrete_state) const { + auto start = std::chrono::high_resolution_clock::now(); + + // Evaluate input ports. + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + // Not sure why x_lcs_des is a vector while lcs_x_curr is a timestamped + // vector. + const BasicVector& x_lcs_des = + *this->template EvalVectorInput(context, target_input_port_); + const BasicVector& x_lcs_final_des = + *this->template EvalVectorInput(context, + final_target_input_port_); + const TimestampedVector* lcs_x_curr = + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + + // Store the current LCS state. + drake::VectorX x_lcs_curr = lcs_x_curr->get_data(); + + if (verbose_) { + std::cout << "x_lcs_curr: " << x_lcs_curr.transpose() << std::endl; + std::cout << "x_lcs_des: " << x_lcs_des.get_value().transpose() + << std::endl; + std::cout << "x_lcs_final_des: " << x_lcs_final_des.get_value().transpose() + << std::endl; + std::cout << "x_pred_curr_plan_: " << x_pred_curr_plan_.transpose() + << std::endl; + } + + // Use a predicted EE state, if desired. + bool is_teleop = radio_out->channel[14]; + ResolvePredictedEEState(is_teleop, x_lcs_curr); + + discrete_state->get_mutable_value(plan_start_time_index_)[0] = + lcs_x_curr->get_timestamp(); + + // Check for workspace limit violations; if any, the controller stops. + CheckForWorkspaceLimitViolations(lcs_x_curr); + + // Compute the current position and orientation errors. + current_position_error_ = + (x_lcs_curr.segment(n_q_-3, 3) - + x_lcs_final_des.get_value().segment(n_q_-3, 3)).norm(); + Eigen::Quaterniond curr_quat( + x_lcs_curr[n_q_-7], x_lcs_curr[n_q_-6], + x_lcs_curr[n_q_-5], x_lcs_curr[n_q_-4]); + Eigen::Quaterniond des_quat( + x_lcs_final_des.get_value()[n_q_-7], x_lcs_final_des.get_value()[n_q_-6], + x_lcs_final_des.get_value()[n_q_-5], x_lcs_final_des.get_value()[n_q_-4]); + Eigen::AngleAxis angle_axis_diff(des_quat * curr_quat.inverse()); + current_orientation_error_ = angle_axis_diff.angle(); + + // Detect if the final target has changed, in which case return to caring only + // about position until the switching threshold has been crossed again. + // Exclude the EE goal from the comparison, since that always changes to be + // above the current object location. + if (!x_final_target_.segment(3, n_x_-3).isApprox( + x_lcs_final_des.value().segment(3, n_x_-3), 1e-5)) { + std::cout << "Detected goal change!" << std::endl; + if (verbose_) { + std::cout << " Last goal: " << x_final_target_.transpose() << std::endl; + std::cout << " New goal: " << x_lcs_final_des.value().transpose() + << std::endl; + std::cout << " --> Error: " + << (x_final_target_.segment(3, n_x_ - 3) - + x_lcs_final_des.value().segment(3, n_x_ - 3)) + .norm() + << std::endl; + } + crossed_cost_switching_threshold_ = false; + x_final_target_ = x_lcs_final_des.value(); + detected_goal_changes_++; + + // Reset the sample buffer now that the costs have changed. + sample_buffer_ = MatrixXd::Zero(sampling_params_.N_sample_buffer, n_q_); + sample_costs_buffer_ = + -1 * VectorXd::Ones(sampling_params_.N_sample_buffer); + } + + // If the object is close to desired XY location, track its full pose. + if (!crossed_cost_switching_threshold_) { + if ((x_lcs_curr.segment(n_q_-3,2)-x_lcs_final_des.value().segment(n_q_-3,2)) + .norm() < progress_params_.cost_switching_threshold_distance) { + crossed_cost_switching_threshold_ = true; + std::cout << "Crossed cost switching threshold." << std::endl; + + // Reset the sample buffer and metrics now that the costs have changed. + sample_buffer_ = MatrixXd::Zero(sampling_params_.N_sample_buffer, n_q_); + sample_costs_buffer_ = + -1 * VectorXd::Ones(sampling_params_.N_sample_buffer); + if (is_doing_c3_) { ResetProgressMetrics(); } + } + } + + // Build C3Options from SamplingC3Options based on the + // crossed_cost_switching_threshold_ flag. + C3Options c3_options = sampling_c3_options_.GetC3Options( + crossed_cost_switching_threshold_); + + // Update the cost matrices: Q_, R_, G_, and U_. + UpdateCostMatrices(x_lcs_curr, x_lcs_des, c3_options); + + // Generate states, differing from the current state only by EE sample + // locations. + std::vector candidate_states = + GenerateSampleStates(n_q_, n_v_, n_u_, x_lcs_curr, is_doing_c3_, + sampling_params_, sampling_c3_options_, plant_, + context_, plant_ad_, context_ad_, contact_pairs_); + + // Add the previous best repositioning target to the candidate states at the + // index 1 always. (Index 0 will become the current state.) + if (!is_doing_c3_) { + Eigen::VectorXd repositioning_target_state = x_lcs_curr; + repositioning_target_state.head(3) = prev_repositioning_target_; + candidate_states.insert(candidate_states.begin(), + repositioning_target_state); + } + // Insert the current location at the beginning of the candidate states. + candidate_states.insert(candidate_states.begin(), x_lcs_curr); + int num_total_samples = candidate_states.size(); + + if (verbose_) { + std::cout << "num_total_samples: " << num_total_samples << std::endl; + } + + // Update the set of sample locations under consideration. + all_sample_locations_.clear(); + for (int i = 0; i < num_total_samples; i++) { + all_sample_locations_.push_back(candidate_states[i].head(3)); + } + + // Make LCS objects for each sample. + auto lcs_pair = SamplingC3Controller::CreateLCSObjectsForSamples( + candidate_states, x_lcs_curr, c3_options, c3_options); + std::vector lcs_candidates = lcs_pair.first; + std::vector lcs_candidates_for_cost = lcs_pair.second; + + // Prepare variables that will get used or filled in by parallelization. + all_sample_costs_ = std::vector(num_total_samples, -1); + all_sample_dynamically_feasible_plans_ = + std::vector>( + num_total_samples, + std::vector(N_ + 1, VectorXd::Zero(n_x_))); + std::vector> c3_objects( + num_total_samples, nullptr); + bool force_tracking_disabled = radio_out->channel[11]; + C3CostComputationType cost_type = progress_params_.cost_type; + if (!crossed_cost_switching_threshold_) { + cost_type = progress_params_.cost_type_position; + } + +// Parallelize over computing C3 costs for each sample. +#pragma omp parallel for num_threads(num_threads_to_use_) + for (int i = 0; i < num_total_samples; i++) { + bool print_cost_breakdown = radio_out->channel[7] && + (i == SampleIndex::kCurrentLocation); + + // Get the candidate state and its LCS representation. + Eigen::VectorXd test_state = candidate_states.at(i); + solvers::LCS test_system = lcs_candidates.at(i); + + // Set up C3 with proper projection type and post-solve cost matrices. + std::shared_ptr test_c3_object; + std::vector x_desired = + std::vector(N_ + 1, x_lcs_des.value()); + if (c3_options.projection_type == "MIQP") { + test_c3_object = std::make_shared( + test_system, C3::CostMatrices(Q_, R_, G_, U_), x_desired, c3_options); + } else if (c3_options.projection_type == "QP") { + test_c3_object = std::make_shared( + test_system, C3::CostMatrices(Q_, R_, G_, U_), x_desired, c3_options); + } // Unknown projection types are rejected in the initialization. + test_c3_object->UpdateCostLCS(lcs_candidates_for_cost.at(i)); + + // Solve C3, store resulting object and cost. + test_c3_object->SetOsqpSolverOptions(solver_options_); + test_c3_object->Solve(test_state, verbose_); + std::pair> cost_trajectory_pair = + test_c3_object->CalcCost( + cost_type, sampling_c3_options_.Kp_for_ee_pd_rollout, + sampling_c3_options_.Kd_for_ee_pd_rollout, force_tracking_disabled, + print_cost_breakdown, verbose_); + + double c3_cost = cost_trajectory_pair.first; + all_sample_dynamically_feasible_plans_.at(i) = cost_trajectory_pair.second; + +#pragma omp critical + { + c3_objects.at(i) = test_c3_object; + } + // Add travel cost (just looking at xy displacement, not also z). + double xy_travel_distance = (test_state.head(2)-x_lcs_curr.head(2)).norm(); + all_sample_costs_[i] = + c3_cost + progress_params_.travel_cost_per_meter * xy_travel_distance; + + // Add additional costs based on repositioning progress. + if ((i == SampleIndex::kCurrentReposTarget) && finished_reposition_flag_) { + all_sample_costs_[i] += progress_params_.finished_reposition_cost; + finished_reposition_flag_ = false; + } + } + // End of parallelization + + // Update the sample buffer. Do this before switching modes since 1) if in + // repositioning mode, don't add the repositioning target over and over again, + // and 2) since the best sample in the buffer may be the best sample overall + // and could be considered as a repositioning target. + MaintainSampleBuffer(x_lcs_curr); + + // Augment the considered samples with the best from the buffer, if eligible. + AugmentSamplesWithBuffer(c3_objects); + + // Set up hysteresis values based on if the cost switching threshold has been + // crossed. + double hyst_c3_to_repos = progress_params_.hyst_c3_to_repos; + double hyst_repos_to_c3 = progress_params_.hyst_repos_to_c3; + double hyst_repos_to_repos = progress_params_.hyst_repos_to_repos; + double hyst_c3_to_repos_frac = progress_params_.hyst_c3_to_repos_frac; + double hyst_repos_to_c3_frac = progress_params_.hyst_repos_to_c3_frac; + double hyst_repos_to_repos_frac = progress_params_.hyst_repos_to_repos_frac; + if (!crossed_cost_switching_threshold_) { + hyst_c3_to_repos = progress_params_.hyst_c3_to_repos_position; + hyst_repos_to_c3 = progress_params_.hyst_repos_to_c3_position; + hyst_repos_to_repos = progress_params_.hyst_repos_to_repos_position; + hyst_c3_to_repos_frac = progress_params_.hyst_c3_to_repos_frac_position; + hyst_repos_to_c3_frac = progress_params_.hyst_repos_to_c3_frac_position; + hyst_repos_to_repos_frac = + progress_params_.hyst_repos_to_repos_frac_position; + } + + // Review the cost results to determine the best sample. + bool force_c3_mode = radio_out->channel[12]; + double best_other_cost; + if (num_total_samples > 1) { + std::vector additional_sample_cost_vector = std::vector( + all_sample_costs_.begin() + 1, all_sample_costs_.end()); + best_other_cost = *std::min_element(additional_sample_cost_vector.begin(), + additional_sample_cost_vector.end()); + std::vector::iterator it = + std::min_element(std::begin(additional_sample_cost_vector), + std::end(additional_sample_cost_vector)); + best_sample_index_ = (SampleIndex)( + std::distance(std::begin(additional_sample_cost_vector), it) + 1); + } else { + force_c3_mode = true; + } + + if (verbose_) { + std::cout << "All sample costs before hystereses: " << std::endl; + for (int i = 0; i < num_total_samples; i++) { + std::cout << "Sample " << i << " cost: " << all_sample_costs_[i] + << std::endl; + } + std::cout << "In C3 mode? " << is_doing_c3_ << std::endl; + } + + // Determine whether to do C3 or reposition. + mode_switch_reason_ = ModeSwitchReason::kNoSwitch; + double curr_cost = all_sample_costs_[SampleIndex::kCurrentLocation]; + double repos_target_cost =all_sample_costs_[SampleIndex::kCurrentReposTarget]; + if (is_doing_c3_ == true) { // Currently doing C3. + pursued_target_source_ = PursuedTargetSource::kNoTarget; + + // Keep track of progress while in C3 mode. + bool met_minimum_progress = true; // Reset by below function. + bool print_current_pos_and_rot_cost = radio_out->channel[6]; + KeepTrackOfC3ModeProgress( + x_lcs_curr, x_lcs_final_des, met_minimum_progress, + print_current_pos_and_rot_cost); + + // Switch to repositioning if progress was insufficient. + if (!met_minimum_progress && !force_c3_mode && + (sampling_params_.num_additional_samples_c3 > 0)) { + is_doing_c3_ = false; + mode_switch_reason_ = ModeSwitchReason::kToReposUnproductive; + std::cout << "Repositioning after not making progress in C3" << std::endl; + } + + // Switch to repositioning if one of the other samples is better, with + // hysteresis. + else if ( + ((!progress_params_.use_relative_hysteresis && + curr_cost > best_other_cost + hyst_c3_to_repos) || + (progress_params_.use_relative_hysteresis && + curr_cost > best_other_cost + hyst_c3_to_repos_frac*curr_cost)) && + !force_c3_mode) + { + is_doing_c3_ = false; + mode_switch_reason_ = ModeSwitchReason::kToReposCost; + std::cout << "Repositioning because found good sample" << std::endl; + } + + // Reset progress metrics if switching to repositioning. + if (!is_doing_c3_) { + finished_reposition_flag_ = false; + ResetProgressMetrics(); + + // Determine the source of the repositioning target. + if (best_sample_index_ > sampling_params_.num_additional_samples_c3) { + pursued_target_source_ = PursuedTargetSource::kFromBuffer; + // Remove the sample from the buffer. + sample_buffer_.row(num_in_buffer_ - 1) = VectorXd::Zero(n_q_); + sample_costs_buffer_[num_in_buffer_ - 1] = -1; + num_in_buffer_--; + } else { + pursued_target_source_ = PursuedTargetSource::kNewSample; + } + } + } else { // Currently repositioning. + // First, apply hysteresis between repositioning targets. + if (best_sample_index_ == SampleIndex::kCurrentReposTarget) { + pursued_target_source_ = PursuedTargetSource::kPrevious; + } else { + // This means there is a lower cost sample other than the current + // repositioning target. If the lowest cost sample is not at least the + // hysteresis amount better than the current repositioning target, then + // continue pursuing the previous repositioning target. + if ( + (repos_target_cost < best_other_cost + hyst_repos_to_repos + && !progress_params_.use_relative_hysteresis) || + (repos_target_cost < best_other_cost + hyst_repos_to_repos_frac* + repos_target_cost + && progress_params_.use_relative_hysteresis)) + { + best_sample_index_ = SampleIndex::kCurrentReposTarget; + best_other_cost = repos_target_cost; + finished_reposition_flag_ = false; + pursued_target_source_ = PursuedTargetSource::kPrevious; + } + // Controller will switch to pursuing a new sample from its previous + // repositioning target only if the cost of switching to that new sample + // (with repos_to_repos hysteresis) is less than switching to C3 from + // current location (with repos_to_c3 hysteresis), so add the + // repos_to_repos hysteresis value here before the comparison to the + // current location C3 cost with repos_to_c3 hysteresis afterwards. + else { + pursued_target_source_ = PursuedTargetSource::kNewSample; + if (!progress_params_.use_relative_hysteresis) { + best_other_cost += hyst_repos_to_repos; + } else { + best_other_cost += hyst_repos_to_repos_frac*repos_target_cost; + } + } + } + + // Switch to C3 if forced by xbox controller. + if (force_c3_mode) { + std::cout << "Forcing into C3 mode" << std::endl; + is_doing_c3_ = true; + mode_switch_reason_ = ModeSwitchReason::kToC3Xbox; + pursued_target_source_ = PursuedTargetSource::kNoTarget; + } + // Switch to C3 if the current sample is better, with hysteresis. + else if ( + (!progress_params_.use_relative_hysteresis && + best_other_cost > curr_cost + hyst_repos_to_c3) || + (progress_params_.use_relative_hysteresis && + best_other_cost > curr_cost + hyst_repos_to_c3_frac*best_other_cost)) + { + is_doing_c3_ = true; + finished_reposition_flag_ = false; + if (repos_target_cost > progress_params_.finished_reposition_cost) { + mode_switch_reason_ = ModeSwitchReason::kToC3ReachedReposTarget; + std::cout << "Switching to C3 because reached repositioning target" + << std::endl; + } else { + mode_switch_reason_ = ModeSwitchReason::kToC3Cost; + std::cout << "Switching to C3 because lower in cost" << std::endl; + } + pursued_target_source_ = PursuedTargetSource::kNoTarget; + } + } + + if (verbose_) { + std::cout << "All sample costs before hystereses: " << std::endl; + for (int i = 0; i < num_total_samples; i++) { + std::cout << "Sample " << i << " cost: " << all_sample_costs_[i] + << std::endl; + } + std::cout << "In C3 mode after considering switch? " << is_doing_c3_ + << std::endl; + } + + // Update C3 objects and intermediates for current and best samples. + c3_curr_plan_ = c3_objects.at(SampleIndex::kCurrentLocation); + c3_best_plan_ = c3_objects.at(best_sample_index_); + // TODO If doing warmstarting, will need to save z, delta, and w vectors. + + // Update the execution trajectories. + double t = context.get_discrete_state(plan_start_time_index_)[0]; + UpdateC3ExecutionTrajectory(x_lcs_curr, t); + UpdateRepositioningExecutionTrajectory(x_lcs_curr, t); + + if (verbose_) { + std::cout << "x_pred_curr_plan_ after updating: " + << x_pred_curr_plan_.transpose() << std::endl; + std::vector zs = c3_curr_plan_->GetFullSolution(); + for (int i = 0; i < N_; i++) { + std::cout << "z[" << i << "]: " << zs[i].transpose() << std::endl; + } + solvers::LCS verbose_lcs = lcs_candidates.at(SampleIndex::kCurrentLocation); + Eigen::MatrixXd E = verbose_lcs.E_[0]; + Eigen::MatrixXd F = verbose_lcs.F_[0]; + Eigen::MatrixXd H = verbose_lcs.H_[0]; + Eigen::VectorXd c = verbose_lcs.c_[0]; + std::cout << "\nRight side of complementarity: " << std::endl; + for (int i = 0; i < N_; i++) { + Eigen::VectorXd x = zs[i].head(n_x_); + Eigen::VectorXd lambda = zs[i].segment(n_x_, n_lambda_); + Eigen::VectorXd u = zs[i].tail(n_u_); + std::cout << "\t" << i << ": " + << (E * x + F * lambda + H * u + c).transpose() << std::endl; + } + std::cout << "\nComplementarity violation: " << std::endl; + for (int i = 0; i < N_; i++) { + Eigen::VectorXd x = zs[i].head(n_x_); + Eigen::VectorXd lambda = zs[i].segment(n_x_, n_lambda_); + Eigen::VectorXd u = zs[i].tail(n_u_); + std::cout << "\t" << i << ": " + << lambda.dot(E * x + F * lambda + H * u + c) << std::endl; + } + + std::cout << "Dynamically feasible ee current plan: " << std::endl; + for (int i = 0; i < N_ + 1; i++) { + std::cout << all_sample_dynamically_feasible_plans_ + .at(SampleIndex::kCurrentLocation)[i] + .segment(0, 3) + .transpose() + << std::endl; + } + + std::cout << "Dynamically feasible object current plan: " << std::endl; + for (int i = 0; i < N_ + 1; i++) { + std::cout << all_sample_dynamically_feasible_plans_ + .at(SampleIndex::kCurrentLocation)[i] + .segment(n_q_-7, 7) + .transpose() + << std::endl; + } + } + + // Add delay. + std::this_thread::sleep_for( + std::chrono::milliseconds(controller_params_.control_loop_delay_ms)); + + // End of control loop cleanup. + auto finish = std::chrono::high_resolution_clock::now(); + auto elapsed = finish - start; + double solve_time = + std::chrono::duration_cast(elapsed).count()/1e6; + filtered_solve_time_ = (1 - solve_time_filter_constant_) * solve_time + + (solve_time_filter_constant_)*filtered_solve_time_; + + if (verbose_) { + std::cout << "At end of loop solve_time: " << solve_time << std::endl; + std::cout << "At end of loop filtered_solve_time_: " << filtered_solve_time_ + << std::endl; + } + + return drake::systems::EventStatus::Succeeded(); +} + +// Use a predicted EE state, if opted by controller settings. The predicted +// location is clamped to a reasonable distance from the current EE location. +// Optionally, there is a reset mechanism to prevent using a predicted EE +// location if the last state is closer to the current state than the +// prediction. +void SamplingC3Controller::ResolvePredictedEEState( + const bool& is_teleop, drake::VectorX& x_lcs_curr) const { + // Store the current actual state before applying prediction in preparation + // for next control loop. + x_from_last_control_loop_ = x_lcs_curr; + + // Detect if prediction is requested in current mode. + bool in_c3_mode_and_predict = + sampling_c3_options_.use_predicted_x0_c3 && is_doing_c3_; + bool in_repos_mode_and_predict = + sampling_c3_options_.use_predicted_x0_repos && !is_doing_c3_; + + if (!x_pred_curr_plan_.isZero() && !is_teleop && + (in_c3_mode_and_predict || in_repos_mode_and_predict)) { + // Consider the current, last, and predicted states. + Eigen::Vector3d curr_ee = x_lcs_curr.head(3); + Eigen::Vector3d last_ee = x_from_last_control_loop_.head(3); + Eigen::Vector3d pred_ee = x_pred_from_last_control_loop_.head(3); + + if (((curr_ee - last_ee).norm() < (curr_ee - pred_ee).norm()) && + (curr_ee - pred_ee).norm() > 0.01 && + !x_pred_from_last_control_loop_.isZero() && + sampling_c3_options_.use_predicted_x0_reset_mechanism) { + // Skip using the predicted state. + if (verbose_) { + std::cout << "RESET x_pred in mode: C3 " << in_c3_mode_and_predict + << ", or Repositioning " << in_repos_mode_and_predict + << std::endl; + std::cout << "curr_ee-last_ee is " << (curr_ee - last_ee).norm() + << " and curr_ee-pred_ee is " << (curr_ee - pred_ee).norm() + << std::endl; + std::cout << "x_lcs_curr without clamping: " << x_lcs_curr.transpose() + << std::endl; + } + } else { + // Do the clamping. + ClampEndEffectorAcceleration(x_lcs_curr); + if (verbose_) { + std::cout << "x_lcs_curr after clamping in mode: C3 " + << in_c3_mode_and_predict << ", or Repositioning " + << in_repos_mode_and_predict << " --> " + << x_lcs_curr.transpose() << std::endl; + } + } + } + + // Store the predicted actual state in preparation for next control loop. + x_pred_from_last_control_loop_ = x_lcs_curr; +} + +// Clamp end effector acceleration if using predicted state. +void SamplingC3Controller::ClampEndEffectorAcceleration( + drake::VectorX& x_lcs_curr) const { + // Use fixed approximate loop time for acceleration capping heuristic. + float approx_loop_dt = std::min(0.1, filtered_solve_time_); + float nominal_accel = 10; + for (int i = 0; i < 3; i++) { + x_lcs_curr[i] = std::clamp( + x_pred_curr_plan_[i], + x_lcs_curr[i] - nominal_accel * approx_loop_dt * approx_loop_dt, + x_lcs_curr[i] + nominal_accel * approx_loop_dt * approx_loop_dt); + x_lcs_curr[n_q_ + i] = std::clamp( + x_pred_curr_plan_[n_q_ + i], + x_lcs_curr[n_q_ + i] - nominal_accel * approx_loop_dt, + x_lcs_curr[n_q_ + i] + nominal_accel * approx_loop_dt); + } +} + +// Check for workspace limit violations. If violated, the controller errors and +// stops. +void SamplingC3Controller::CheckForWorkspaceLimitViolations( + const TimestampedVector* lcs_x_curr) const { + // xyz checks + for (int i = 0; i < sampling_c3_options_.workspace_limits.size(); ++i) { + DRAKE_DEMAND(lcs_x_curr->get_data().segment(0, 3).transpose() * + sampling_c3_options_.workspace_limits[i].segment(0, 3) > + sampling_c3_options_.workspace_limits[i][3] - + sampling_c3_options_.workspace_margins); + DRAKE_DEMAND(lcs_x_curr->get_data().segment(0, 3).transpose() * + sampling_c3_options_.workspace_limits[i].segment(0, 3) < + sampling_c3_options_.workspace_limits[i][4] + + sampling_c3_options_.workspace_margins); + } + // radius checks + DRAKE_DEMAND(std::pow(lcs_x_curr->get_data()[0], 2) + + std::pow(lcs_x_curr->get_data()[1], 2) > + std::pow(sampling_c3_options_.robot_radius_limits[0] + + sampling_c3_options_.workspace_margins, 2)); + DRAKE_DEMAND(std::pow(lcs_x_curr->get_data()[0], 2) + + std::pow(lcs_x_curr->get_data()[1], 2) < + std::pow(sampling_c3_options_.robot_radius_limits[1] - + sampling_c3_options_.workspace_margins, 2)); +} + +// Update the cost matrices (Q_, R_, G_, U_) in preparation for C3 solves. +// Handle quaternion-dependent cost if enabled. +void SamplingC3Controller::UpdateCostMatrices( + const drake::VectorX& x_lcs_curr, + const BasicVector& x_lcs_des, const C3Options& c3_options) const { + Q_.clear(); + R_.clear(); + G_.clear(); + U_.clear(); + double discount_factor = 1; + + dt_ = c3_options.dt; + for (int i = 0; i < N_ + 1; ++i) { + Q_.push_back(discount_factor * c3_options.Q); + discount_factor *= c3_options.gamma; + if (i < N_) { + R_.push_back(discount_factor * c3_options.R); + G_.push_back(c3_options.G); + U_.push_back(c3_options.U); + } + } + + if (sampling_c3_options_.use_quaternion_dependent_cost && + crossed_cost_switching_threshold_) { + Eigen::VectorXd quat = x_lcs_curr.segment(3, 4); + Eigen::VectorXd quat_desired = x_lcs_des.get_value().segment(3, 4); + Eigen::MatrixXd Q_quaternion_dependent_cost = + hessian_of_squared_quaternion_angle_difference(quat, quat_desired); + + // Get the eigenvalues of the hessian to regularize so the Q matrix is + // always PSD. + double min_eigval = + Q_quaternion_dependent_cost.eigenvalues().real().minCoeff(); + Eigen::MatrixXd Q_quaternion_dependent_regularizer_part_1 = + std::max(0.0, -min_eigval) * Eigen::MatrixXd::Identity(4, 4); + + Eigen::MatrixXd Q_quaternion_dependent_regularizer_part_2 = + quat_desired * quat_desired.transpose(); + DRAKE_ASSERT(Q_quaternion_dependent_cost.rows() == + Q_quaternion_dependent_cost.cols() == + Q_quaternion_dependent_regularizer_part_2.rows() == + Q_quaternion_dependent_regularizer_part_2.cols() == 4); + double discount_factor = 1; + for (int i = 0; i < N_ + 1; ++i) { + Q_[i].block(3, 3, 4, 4) = + discount_factor * sampling_c3_options_.q_quaternion_dependent_weight * + (Q_quaternion_dependent_cost + + Q_quaternion_dependent_regularizer_part_1 + + sampling_c3_options_.q_quaternion_dependent_regularizer_fraction * + Q_quaternion_dependent_regularizer_part_2); + discount_factor *= sampling_c3_options_.gamma; + } + } + + if (verbose_) { + std::cout << "Q_[0] with gamma " << sampling_c3_options_.gamma << ":" + << std::endl; + std::cout << Q_[0] << std::endl; + std::cout << "R_[0] with gamma " << sampling_c3_options_.gamma << ":" + << std::endl; + std::cout << R_[0] << std::endl; + } +} + +// Create LCS objects (for the C3 solve and also for the C3 cost calculation) +// for each sample. +std::pair, std::vector> +SamplingC3Controller::CreateLCSObjectsForSamples( + const std::vector& candidate_states, + const drake::VectorX& x_lcs_curr, const C3Options& c3_options, + const C3Options& c3_options_curr_location) const { + std::vector lcs_candidates; + std::vector lcs_candidates_for_cost; + + int num_total_samples = candidate_states.size(); + for (int i = 0; i < num_total_samples; i++) { + // Context needs to be updated to create the LCS objects. + UpdateContext(n_q_, n_v_, n_u_, plant_, context_, plant_ad_, context_ad_, + candidate_states[i]); + + // Resolve the contact pairs and create the LCS. + vector> resolved_contact_pairs = + LCSFactory::PreProcessor( + plant_, *context_, contact_pairs_, + sampling_c3_options_.resolve_contacts_to, + c3_options.num_friction_directions, verbose_); + solvers::LCS lcs_object_sample = solvers::LCSFactory::LinearizePlantToLCS( + plant_, *context_, plant_ad_, *context_ad_, resolved_contact_pairs, + c3_options.num_friction_directions, c3_options.mu, dt_, N_, + contact_model_); + lcs_candidates.push_back(lcs_object_sample); + + // Create different LCS objects for cost calculation. + vector> resolved_contact_pairs_for_cost_simulation; + resolved_contact_pairs_for_cost_simulation = LCSFactory::PreProcessor( + plant_, *context_, contact_pairs_, + sampling_c3_options_.resolve_contacts_to_for_cost, + sampling_c3_options_.num_friction_directions, verbose_); + solvers::LCS lcs_object_sample_for_cost_simulation = + solvers::LCSFactory::LinearizePlantToLCS( + plant_, *context_, plant_ad_, *context_ad_, + resolved_contact_pairs_for_cost_simulation, + sampling_c3_options_.num_friction_directions, + sampling_c3_options_.mu_for_cost, dt_, N_, contact_model_); + lcs_candidates_for_cost.push_back(lcs_object_sample_for_cost_simulation); + } + + // Reset the context to the current lcs state. + UpdateContext(n_q_, n_v_, n_u_, plant_, context_, plant_ad_, context_ad_, + x_lcs_curr); + + if (verbose_) { + // Print the LCS matrices for verbose inspection. + solvers::LCS verbose_lcs = lcs_candidates.at( + SampleIndex::kCurrentLocation); + std::cout << "A: " << std::endl; + std::cout << verbose_lcs.A_[0] << std::endl; + std::cout << "B: " << std::endl; + std::cout << verbose_lcs.B_[0] << std::endl; + std::cout << "D: " << std::endl; + std::cout << verbose_lcs.D_[0] << std::endl; + std::cout << "d: " << std::endl; + std::cout << verbose_lcs.d_[0] << std::endl; + std::cout << "E: " << std::endl; + std::cout << verbose_lcs.E_[0] << std::endl; + std::cout << "F: " << std::endl; + std::cout << verbose_lcs.F_[0] << std::endl; + std::cout << "H: " << std::endl; + std::cout << verbose_lcs.H_[0] << std::endl; + std::cout << "c: " << std::endl; + std::cout << verbose_lcs.c_[0] << std::endl; + } + + return std::make_pair(lcs_candidates, lcs_candidates_for_cost); +} + +void SamplingC3Controller::UpdateC3ExecutionTrajectory( + const VectorXd& x_lcs, const double& t_context) const { + // Get the input and full state solution from the plan. + vector u_sol = c3_curr_plan_->GetInputSolution(); + vector x_sol = c3_curr_plan_->GetStateSolution(); + + // Setting up matrices to set up LCMTrajectory object. + Eigen::MatrixXd knots = Eigen::MatrixXd::Zero(n_x_, N_); + Eigen::VectorXd timestamps = Eigen::VectorXd::Zero(N_); + + // Set up matrices for LCMTrajectory object. + for (int i = 0; i < N_; i++) { + knots.col(i) = x_sol[i]; + timestamps[i] = t_context + filtered_solve_time_ + (i)*dt_; + } + + // Update predicted next state if in this mode. + if (is_doing_c3_) { + if (filtered_solve_time_ < (N_ - 1) * dt_) { + int last_passed_index = filtered_solve_time_ / dt_; + double fraction_to_next_index = + (filtered_solve_time_ / dt_) - (double)last_passed_index; + x_pred_curr_plan_ = + knots.col(last_passed_index) + + fraction_to_next_index * + (knots.col(last_passed_index + 1) - knots.col(last_passed_index)); + } else { + x_pred_curr_plan_ = knots.col(N_ - 1); + } + } + + // Add end effector position target to LCM Trajectory. + LcmTrajectory::Trajectory ee_traj; + ee_traj.traj_name = "end_effector_position_target"; + ee_traj.datatypes = std::vector(3, "double"); + ee_traj.datapoints = knots(Eigen::seqN(0, 3), Eigen::seqN(0, N_)); + ee_traj.time_vector = timestamps.cast(); + c3_execution_lcm_traj_.ClearTrajectories(); + c3_execution_lcm_traj_.AddTrajectory(ee_traj.traj_name, ee_traj); + + // Add end effector force target to LCM Trajectory. + // In c3 mode, the end effector forces should match the solved c3 inputs. + Eigen::MatrixXd force_samples = Eigen::MatrixXd::Zero(3, N_); + for (int i = 0; i < N_; i++) { + force_samples.col(i) = u_sol[i]; + } + LcmTrajectory::Trajectory force_traj; + force_traj.traj_name = "end_effector_force_target"; + force_traj.datatypes = + std::vector(force_samples.rows(), "double"); + force_traj.datapoints = force_samples; + force_traj.time_vector = timestamps.cast(); + c3_execution_lcm_traj_.AddTrajectory(force_traj.traj_name, force_traj); + + // No need to add object position and orientation since these are outputs sent + // in the C3 plans. +} + +// Compute repositioning trajectory. +void SamplingC3Controller::UpdateRepositioningExecutionTrajectory( + const VectorXd& x_lcs, const double& t_context) const { + // Get the best sample location. + Eigen::Vector3d best_sample_location = + all_sample_locations_[best_sample_index_]; + // Update the previous repositioning target for reference in next loop. + prev_repositioning_target_ = best_sample_location; + + // Generate knot points according to the repositioning strategy. + Eigen::MatrixXd knots = Reposition( + n_q_, n_x_, N_, x_lcs, best_sample_location, dt_, is_doing_c3_, + finished_reposition_flag_, reposition_params_, sampling_c3_options_); + + // Update predicted next state if in this mode. + if (!is_doing_c3_) { + if (filtered_solve_time_ < (N_ - 1) * dt_) { + int last_passed_index = filtered_solve_time_ / dt_; + double fraction_to_next_index = + (filtered_solve_time_ / dt_) - (double)last_passed_index; + x_pred_curr_plan_ = + knots.col(last_passed_index) + + fraction_to_next_index * + (knots.col(last_passed_index + 1) - knots.col(last_passed_index)); + } else { + x_pred_curr_plan_ = knots.col(N_ - 1); + } + } + + // Set up the trajectory. + Eigen::VectorXd timestamps = Eigen::VectorXd::Zero(N_); + for (int i = 0; i < N_; i++) { + timestamps[i] = t_context + filtered_solve_time_ + (i)*dt_; + } + + LcmTrajectory::Trajectory ee_traj; + ee_traj.traj_name = "end_effector_position_target"; + ee_traj.datatypes = std::vector(3, "double"); + ee_traj.datapoints = knots(Eigen::seqN(0, 3), Eigen::seqN(0, N_)); + ee_traj.time_vector = timestamps.cast(); + repos_execution_lcm_traj_.ClearTrajectories(); + repos_execution_lcm_traj_.AddTrajectory(ee_traj.traj_name, ee_traj); + + // In repositioning mode, the end effector should not exert forces. + MatrixXd force_samples = MatrixXd::Zero(3, N_); + LcmTrajectory::Trajectory force_traj; + force_traj.traj_name = "end_effector_force_target"; + force_traj.datatypes = + std::vector(force_samples.rows(), "double"); + force_traj.datapoints = force_samples; + force_traj.time_vector = timestamps.cast(); + repos_execution_lcm_traj_.AddTrajectory(force_traj.traj_name, force_traj); + + // No need to add object position and orientation. +} + +// Maintain the sample buffer: prune outdated samples and add new. +void SamplingC3Controller::MaintainSampleBuffer(const VectorXd& x_lcs) const { + // Determine if samples are outdated by comparing to the current object + // position and orientation. + Vector3d object_pos = x_lcs.segment(n_q_-3, 3); + Eigen::Vector4d object_quat = x_lcs.segment(3, 4).normalized(); + + MatrixXd buffer_xyzs = + sample_buffer_.block(0, 7, sampling_params_.N_sample_buffer, 3); + MatrixXd buffer_quats = + sample_buffer_.block(0, 3, sampling_params_.N_sample_buffer, 4); + + // First, remove outdated samples that have moved too much from current object + // configuration. + VectorXd quat_dots = (buffer_quats * object_quat).array().abs(); + VectorXd angles = (2.0 * quat_dots.array().acos()); + Eigen::Array mask_satisfies_rot = + (angles.array() < sampling_params_.ang_error_sample_retention); + + MatrixXd pos_deltas = buffer_xyzs.rowwise() - object_pos.transpose(); + VectorXd distances = pos_deltas.rowwise().norm(); + Eigen::Array mask_satisfies_pos = + (distances.array() < sampling_params_.pos_error_sample_retention); + + MatrixXd retained_samples = + MatrixXd::Zero(sampling_params_.N_sample_buffer, n_q_); + VectorXd retained_costs = + -1 * VectorXd::Ones(sampling_params_.N_sample_buffer); + int retained_count = 0; + for (int i = 0; i < sampling_params_.N_sample_buffer; i++) { + if (mask_satisfies_rot[i] && mask_satisfies_pos[i]) { + retained_samples.row(retained_count) = sample_buffer_.row(i); + retained_costs[retained_count] = sample_costs_buffer_[i]; + retained_count++; + } else if (sample_costs_buffer_[i] < 0) { + break; + } + } + sample_buffer_ = retained_samples; + sample_costs_buffer_ = retained_costs; + + // Second, in preparation for adding new samples stored in + // all_sample_locations_ (excluding the current location), if the buffer is + // going to overflow, get rid of the oldest samples first. NOTE: Step 4 + // moves the lowest cost sample in the buffer to the end, so the best sample + // is usually excluded from this cut. + int num_to_add = all_sample_locations_.size() - 1; + if (!is_doing_c3_) { + num_to_add--; + } + if (retained_count + num_to_add > sampling_params_.N_sample_buffer) { + int shift_by = + retained_count + num_to_add - sampling_params_.N_sample_buffer; + retained_count -= shift_by; + sample_buffer_.block(0, 0, retained_count, n_q_) = + sample_buffer_.block(shift_by, 0, retained_count, n_q_); + sample_costs_buffer_.segment(0, retained_count) = + sample_costs_buffer_.segment(shift_by, retained_count); + } + + // Third, add the new samples stored in all_sample_locations_ and + // all_sample_costs_. Don't add the current location (so the sample buffer + // contains more broadly sampled locations) or a currently pursued + // repositioning target. + int buffer_count = retained_count; + for (int i = retained_count; + i < retained_count + all_sample_locations_.size(); i++) { + DRAKE_ASSERT(i >= sampling_params_.N_sample_buffer); + if ((i == retained_count) || (!is_doing_c3_ && i == retained_count + 1)) { + // Skip the current location. + // Skip the repositioning target if in repositioning mode. + } else { + VectorXd new_config = x_lcs.segment(0, n_q_); + new_config.segment(0, 3) = all_sample_locations_[i - retained_count]; + // Ensure a normalized quaternion is written to the buffer. + new_config.segment(3, 4) = object_quat; + sample_buffer_.row(buffer_count) = new_config; + sample_costs_buffer_[buffer_count] = + all_sample_costs_[i - retained_count]; + buffer_count++; + } + } + num_in_buffer_ = buffer_count; + + // Lastly, ensure the lowest cost sample is at the end of the buffer. + VectorXd eligible_costs = sample_costs_buffer_.head(num_in_buffer_); + int lowest_cost_index; + double lowest_buffer_cost = eligible_costs.minCoeff(&lowest_cost_index); + VectorXd lowest_cost_sample = sample_buffer_.row(lowest_cost_index); + sample_buffer_.row(lowest_cost_index) = + sample_buffer_.row(num_in_buffer_ - 1); + sample_costs_buffer_[lowest_cost_index] = + sample_costs_buffer_[num_in_buffer_ - 1]; + sample_buffer_.row(num_in_buffer_ - 1) = lowest_cost_sample; + sample_costs_buffer_[num_in_buffer_ - 1] = lowest_buffer_cost; + + DRAKE_ASSERT(sample_buffer_.cols() == sampling_params_.N_sample_buffer); + DRAKE_ASSERT(sample_buffer_.rows() == n_q_); + DRAKE_ASSERT(sample_costs_buffer_.size() == sampling_params_.N_sample_buffer); +} + +// If eligible, augment the current control loop's considered samples with the +// best one from the buffer. +void SamplingC3Controller::AugmentSamplesWithBuffer( + std::vector>& c3_objects) const { + // Add the best from the buffer to the samples, but only if in C3 mode and + // only if the best in the buffer is distinct from the current set of samples. + if ((is_doing_c3_) && + (sampling_params_.consider_best_buffer_sample_when_leaving_c3)) { + double lowest_buffer_cost = sample_costs_buffer_[num_in_buffer_ - 1]; + Vector3d best_buffer_ee_sample = + sample_buffer_.row(num_in_buffer_ - 1).head(3); + + double lowest_new_cost = + *std::min_element(all_sample_costs_.begin(), all_sample_costs_.end()); + std::vector::iterator it = std::min_element( + std::begin(all_sample_costs_), std::end(all_sample_costs_)); + int lowest_new_cost_index = + (SampleIndex)(std::distance(std::begin(all_sample_costs_), it)); + Vector3d best_new_ee_sample = all_sample_locations_[lowest_new_cost_index]; + + // Initialize the buffer plan with something. + if (dynamically_feasible_buffer_plan_.size() != N_ + 1) { + c3_buffer_plan_ = c3_objects[lowest_new_cost_index]; + dynamically_feasible_buffer_plan_ = + all_sample_dynamically_feasible_plans_[lowest_new_cost_index]; + } + // If the best in the buffer is from the current set of samples, store the + // associated C3 object and dynamically feasible plan, but don't add to the + // set of samples to consider for repositioning. + else if ((abs(lowest_buffer_cost - lowest_new_cost) < 1e-5) && + ((best_buffer_ee_sample - best_new_ee_sample).norm() < 1e-5)) { + c3_buffer_plan_ = c3_objects[lowest_new_cost_index]; + dynamically_feasible_buffer_plan_ = + all_sample_dynamically_feasible_plans_[lowest_new_cost_index]; + } + // If the best in the buffer is distinct from the current set of samples, + // consider it for repositioning by adding it to the set of samples, costs, + // etc. + else { + all_sample_costs_.push_back(lowest_buffer_cost); + all_sample_locations_.push_back(best_buffer_ee_sample); + c3_objects.push_back(c3_buffer_plan_); + all_sample_dynamically_feasible_plans_.push_back( + dynamically_feasible_buffer_plan_); + } + } +} + +// Keep track of the progress made in the current C3 mode. +void SamplingC3Controller::KeepTrackOfC3ModeProgress( + const drake::VectorX& x_lcs_curr, + const BasicVector& x_lcs_final_des, + bool& met_minimum_progress, + const bool& print_current_pos_and_rot_cost) const { + bool updated_cost = false; + bool updated_config_cost = false; + bool updated_pos_or_rot = false; + double cost_progress_fraction = -INFINITY; // Negative means progress. + + Eigen::MatrixXd Q_pos_and_rot = Q_[0].block(n_q_-7, n_q_-7, 7, 7); + Eigen::VectorXd pos_and_rot_error_vec = + x_lcs_curr.segment(n_q_-7, 7) - + x_lcs_final_des.get_value().segment(n_q_-7, 7); + double curr_pos_and_rot_cost = pos_and_rot_error_vec.transpose() * + Q_pos_and_rot * pos_and_rot_error_vec; + + // Check for progress along different metrics. + if ((all_sample_costs_[SampleIndex::kCurrentLocation] < lowest_cost_) || + (lowest_cost_ == -1.0)) { + lowest_cost_ = all_sample_costs_[SampleIndex::kCurrentLocation]; + updated_cost = true; + } + if ((curr_pos_and_rot_cost < lowest_pos_and_rot_current_cost_) || + (lowest_pos_and_rot_current_cost_ == -1.0)) { + lowest_pos_and_rot_current_cost_ = curr_pos_and_rot_cost; + updated_config_cost = true; + } + if ((current_position_error_ < lowest_position_error_) || + (lowest_position_error_ == -1.0)) { + lowest_position_error_ = current_position_error_; + updated_pos_or_rot = true; + } + if ((current_orientation_error_ < lowest_orientation_error_) || + (lowest_orientation_error_ == -1.0)) { + lowest_orientation_error_ = current_orientation_error_; + updated_pos_or_rot = true; + } + + // One of the progress metrics requires a history of object configuration + // costs. Maintain this history and check for progress. + object_config_cost_history_.push(curr_pos_and_rot_cost); + int max_history_length = + progress_params_.progress_enforced_over_n_loops; + if (object_config_cost_history_.size() > max_history_length) { + object_config_cost_history_.pop(); + } + // Check for progress if the history is full. + if (object_config_cost_history_.size() == max_history_length) { + // Note: front() is the oldest cost, back() is the most recent. + cost_progress_fraction = // Negative means progress. + ((object_config_cost_history_.back()-object_config_cost_history_.front()) + / object_config_cost_history_.front()); + } + + if (print_current_pos_and_rot_cost) { + std::cout << "Current rot and pos cost: " << curr_pos_and_rot_cost + << std::endl; + } + + // Keep track of how many control loops have passed since the best seen + // progress metric in this mode. + ProgressMetric progress_metric = progress_params_.track_c3_progress_via; + if (((progress_metric == ProgressMetric::kC3Cost) && updated_cost) + || ((progress_metric == ProgressMetric::kConfigCost) && updated_config_cost) + || ((progress_metric == ProgressMetric::kPosOrRotCost) && + updated_pos_or_rot)) { + best_progress_steps_ago_ = 0; + } else { + best_progress_steps_ago_++; + } + + // Detect if progress was sufficient according to progress metric. + int num_control_loops_to_wait = progress_params_.num_control_loops_to_wait; + if (!crossed_cost_switching_threshold_) { + num_control_loops_to_wait = + progress_params_.num_control_loops_to_wait_position; + } + if (progress_metric == ProgressMetric::kConfigCostDrop) { + if (cost_progress_fraction > -progress_params_.progress_enforced_cost_drop) + { met_minimum_progress = false; } + } + else if (best_progress_steps_ago_ > num_control_loops_to_wait) + { met_minimum_progress = false; } +} + +// Reset the metrics used to track progress in C3 mode. +void SamplingC3Controller::ResetProgressMetrics() const { + lowest_cost_ = -1.0; + lowest_pos_and_rot_current_cost_ = -1.0; + lowest_position_error_ = -1.0; + lowest_orientation_error_ = -1.0; + best_progress_steps_ago_ = 0; + // Clear the stored history of object configuration costs. + while (!object_config_cost_history_.empty()) { + object_config_cost_history_.pop(); + } +} + +// Output port handlers for current location +void SamplingC3Controller::OutputC3SolutionCurrPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const { + double t = context.get_discrete_state(plan_start_time_index_)[0]; + + auto c3_solution = std::make_unique(); + c3_solution->x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); + c3_solution->lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); + c3_solution->u_sol_ = MatrixXf::Zero(n_u_, N_); + c3_solution->time_vector_ = VectorXf::Zero(N_); + + auto z_sol = c3_curr_plan_->GetFullSolution(); + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } + + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = c3_solution->x_sol_.topRows(3).cast(); + knots.bottomRows(3) = + c3_solution->x_sol_.bottomRows(n_v_).topRows(3).cast(); + + LcmTrajectory::Trajectory end_effector_traj; + end_effector_traj.traj_name = "end_effector_position_target"; + end_effector_traj.datatypes = + std::vector(knots.rows(), "double"); + end_effector_traj.datapoints = knots; + end_effector_traj.time_vector = c3_solution->time_vector_.cast(); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_position_target"}, + "end_effector_position_target", + "end_effector_position_target", false); + + MatrixXd force_samples = c3_solution->u_sol_.cast(); + LcmTrajectory::Trajectory force_traj; + force_traj.traj_name = "end_effector_force_target"; + force_traj.datatypes = + std::vector(force_samples.rows(), "double"); + force_traj.datapoints = force_samples; + force_traj.time_vector = c3_solution->time_vector_.cast(); + lcm_traj.AddTrajectory(force_traj.traj_name, force_traj); + + output->saved_traj = lcm_traj.GenerateLcmObject(); + output->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputC3SolutionCurrPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const { + double t = context.get_discrete_state(plan_start_time_index_)[0]; + + auto c3_solution = std::make_unique(); + c3_solution->x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); + c3_solution->lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); + c3_solution->u_sol_ = MatrixXf::Zero(n_u_, N_); + c3_solution->time_vector_ = VectorXf::Zero(N_); + auto z_sol = c3_curr_plan_->GetFullSolution(); + + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } + + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3).cast(); + knots.bottomRows(3) = + c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); + LcmTrajectory::Trajectory object_traj; + object_traj.traj_name = "object_position_target"; + object_traj.datatypes = std::vector(knots.rows(), "double"); + object_traj.datapoints = knots; + object_traj.time_vector = c3_solution->time_vector_.cast(); + LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, + "object_target", "object_target", false); + + LcmTrajectory::Trajectory object_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(4, N_); + orientation_samples = + c3_solution->x_sol_.middleRows(n_q_ - 7, 4).cast(); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = + c3_solution->time_vector_.cast(); + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + object_orientation_traj); + + output->saved_traj = lcm_traj.GenerateLcmObject(); + output->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputC3SolutionCurrPlan( + const drake::systems::Context& context, + C3Output::C3Solution* c3_solution) const { + double t = context.get_discrete_state(plan_start_time_index_)[0]; + + auto z_sol = c3_curr_plan_->GetFullSolution(); + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } +} + +void SamplingC3Controller::OutputC3IntermediatesCurrPlan( + const drake::systems::Context& context, + C3Output::C3Intermediates* c3_intermediates) const { + double t = context.get_discrete_state(plan_start_time_index_)[0] + + filtered_solve_time_; + auto z_sol_curr_plan = c3_curr_plan_->GetFullSolution(); + auto delta_curr_plan = c3_curr_plan_->GetDualDeltaSolution(); + auto w_curr_plan = c3_curr_plan_->GetDualWSolution(); + + for (int i = 0; i < N_; i++) { + c3_intermediates->time_vector_(i) = t + i * dt_; + c3_intermediates->z_.col(i) = z_sol_curr_plan[i].cast(); + c3_intermediates->w_.col(i) = w_curr_plan[i].cast(); + c3_intermediates->delta_.col(i) = delta_curr_plan[i].cast(); + } +} + +void SamplingC3Controller::OutputLCSContactJacobianCurrPlan( + const drake::systems::Context& context, + std::pair>* + lcs_contact_jacobian) const { + const TimestampedVector* lcs_x = + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + + UpdateContext(n_q_, n_v_, n_u_, plant_, context_, plant_ad_, context_ad_, + lcs_x->get_data()); + + C3Options c3_options = sampling_c3_options_.GetC3Options( + crossed_cost_switching_threshold_); + + // Preprocessing the contact pairs + vector> resolved_contact_pairs; + resolved_contact_pairs = LCSFactory::PreProcessor( + plant_, *context_, contact_pairs_, + sampling_c3_options_.resolve_contacts_to, + c3_options.num_friction_directions, verbose_); + + // print size of resolved_contact_pairs + *lcs_contact_jacobian = LCSFactory::ComputeContactJacobian( + plant_, *context_, resolved_contact_pairs, + c3_options.num_friction_directions, c3_options.mu, contact_model_); +} + +// Output port handlers for best sample location +void SamplingC3Controller::OutputC3SolutionBestPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const { + double t = context.get_discrete_state(plan_start_time_index_)[0]; + + auto z_sol = c3_best_plan_->GetFullSolution(); + auto c3_solution = std::make_unique(); + c3_solution->x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); + c3_solution->lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); + c3_solution->u_sol_ = MatrixXf::Zero(n_u_, N_); + c3_solution->time_vector_ = VectorXf::Zero(N_); + + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } + + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } + + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = c3_solution->x_sol_.topRows(3).cast(); + knots.bottomRows(3) = + c3_solution->x_sol_.bottomRows(n_v_).topRows(3).cast(); + + LcmTrajectory::Trajectory end_effector_traj; + end_effector_traj.traj_name = "end_effector_position_target"; + end_effector_traj.datatypes = + std::vector(knots.rows(), "double"); + end_effector_traj.datapoints = knots; + end_effector_traj.time_vector = c3_solution->time_vector_.cast(); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_position_target"}, + "end_effector_position_target", + "end_effector_position_target", false); + + MatrixXd force_samples = c3_solution->u_sol_.cast(); + LcmTrajectory::Trajectory force_traj; + force_traj.traj_name = "end_effector_force_target"; + force_traj.datatypes = + std::vector(force_samples.rows(), "double"); + force_traj.datapoints = force_samples; + force_traj.time_vector = c3_solution->time_vector_.cast(); + lcm_traj.AddTrajectory(force_traj.traj_name, force_traj); + + output->saved_traj = lcm_traj.GenerateLcmObject(); + output->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputC3SolutionBestPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const { + double t = context.get_discrete_state(plan_start_time_index_)[0]; + + auto z_sol = c3_best_plan_->GetFullSolution(); + auto c3_solution = std::make_unique(); + c3_solution->x_sol_ = MatrixXf::Zero(n_q_ + n_v_, N_); + c3_solution->lambda_sol_ = MatrixXf::Zero(n_lambda_, N_); + c3_solution->u_sol_ = MatrixXf::Zero(n_u_, N_); + c3_solution->time_vector_ = VectorXf::Zero(N_); + + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } + + MatrixXd knots = MatrixXd::Zero(6, N_); + knots.topRows(3) = c3_solution->x_sol_.middleRows(n_q_ - 3, 3).cast(); + knots.bottomRows(3) = + c3_solution->x_sol_.middleRows(n_q_ + n_v_ - 3, 3).cast(); + LcmTrajectory::Trajectory object_traj; + object_traj.traj_name = "object_position_target"; + object_traj.datatypes = std::vector(knots.rows(), "double"); + object_traj.datapoints = knots; + object_traj.time_vector = c3_solution->time_vector_.cast(); + LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, + "object_target", "object_target", false); + + LcmTrajectory::Trajectory object_orientation_traj; + // first 3 rows are rpy, last 3 rows are angular velocity + MatrixXd orientation_samples = MatrixXd::Zero(4, N_); + orientation_samples = + c3_solution->x_sol_.middleRows(n_q_ - 7, 4).cast(); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = + c3_solution->time_vector_.cast(); + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + object_orientation_traj); + + output->saved_traj = lcm_traj.GenerateLcmObject(); + output->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputC3SolutionBestPlan( + const drake::systems::Context& context, + C3Output::C3Solution* c3_solution) const { + double t = context.get_discrete_state(plan_start_time_index_)[0]; + + auto z_sol = c3_best_plan_->GetFullSolution(); + for (int i = 0; i < N_; i++) { + c3_solution->time_vector_(i) = filtered_solve_time_ + t + i * dt_; + c3_solution->x_sol_.col(i) = z_sol[i].segment(0, n_x_).cast(); + c3_solution->lambda_sol_.col(i) = + z_sol[i].segment(n_x_, n_lambda_).cast(); + c3_solution->u_sol_.col(i) = + z_sol[i].segment(n_x_ + n_lambda_, n_u_).cast(); + } +} + +void SamplingC3Controller::OutputC3IntermediatesBestPlan( + const drake::systems::Context& context, + C3Output::C3Intermediates* c3_intermediates) const { + double t = context.get_discrete_state(plan_start_time_index_)[0] + + filtered_solve_time_; + auto z_sol_best_plan = c3_best_plan_->GetFullSolution(); + auto delta_best_plan = c3_best_plan_->GetDualDeltaSolution(); + auto w_best_plan = c3_best_plan_->GetDualWSolution(); + + for (int i = 0; i < N_; i++) { + c3_intermediates->time_vector_(i) = t + i * dt_; + c3_intermediates->z_.col(i) = z_sol_best_plan[i].cast(); + c3_intermediates->w_.col(i) = w_best_plan[i].cast(); + c3_intermediates->delta_.col(i) = delta_best_plan[i].cast(); + } +} + +void SamplingC3Controller::OutputLCSContactJacobianBestPlan( + const drake::systems::Context& context, + std::pair>* + lcs_contact_jacobian) const { + const TimestampedVector* lcs_x = + (TimestampedVector*)this->EvalVectorInput(context, + lcs_state_input_port_); + + // Linearize about state with end effector in sample location. + VectorXd x_sample = lcs_x->get_data(); + x_sample.head(3) = all_sample_locations_[best_sample_index_]; + UpdateContext(n_q_, n_v_, n_u_, plant_, context_, plant_ad_, context_ad_, + x_sample); + + C3Options c3_options = sampling_c3_options_.GetC3Options( + crossed_cost_switching_threshold_); + + // Preprocess the contact pairs. + vector> resolved_contact_pairs; + resolved_contact_pairs = LCSFactory::PreProcessor( + plant_, *context_, contact_pairs_, + sampling_c3_options_.resolve_contacts_to, + c3_options.num_friction_directions, verbose_); + *lcs_contact_jacobian = LCSFactory::ComputeContactJacobian( + plant_, *context_, resolved_contact_pairs, + c3_options.num_friction_directions, c3_options.mu, contact_model_); + + // Revert the context. + UpdateContext(n_q_, n_v_, n_u_, plant_, context_, plant_ad_, context_ad_, + lcs_x->get_data()); +} + +// Output port handlers for executing C3 and repositioning ports +void SamplingC3Controller::OutputC3TrajExecuteActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_c3_execution_lcm_traj) const { + // Returned trajectory includes EE positions and feed-forward forces. + LcmTrajectory::Trajectory end_effector_traj = + c3_execution_lcm_traj_.GetTrajectory("end_effector_position_target"); + DRAKE_DEMAND(end_effector_traj.datapoints.rows() == 3); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_position_target"}, + "end_effector_position_target", + "end_effector_position_target", false); + + LcmTrajectory::Trajectory force_traj = + c3_execution_lcm_traj_.GetTrajectory("end_effector_force_target"); + lcm_traj.AddTrajectory(force_traj.traj_name, force_traj); + + output_c3_execution_lcm_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_c3_execution_lcm_traj->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputReposTrajExecuteActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_repos_execution_lcm_traj) + const { + // Returned trajectory includes EE positions and feed-forward forces. + LcmTrajectory::Trajectory end_effector_traj = + repos_execution_lcm_traj_.GetTrajectory("end_effector_position_target"); + DRAKE_DEMAND(end_effector_traj.datapoints.rows() == 3); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_position_target"}, + "end_effector_position_target", + "end_effector_position_target", false); + + LcmTrajectory::Trajectory force_traj = + repos_execution_lcm_traj_.GetTrajectory("end_effector_force_target"); + lcm_traj.AddTrajectory(force_traj.traj_name, force_traj); + + output_repos_execution_lcm_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_repos_execution_lcm_traj->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputTrajExecuteActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_execution_lcm_traj) const { + LcmTrajectory execution_lcm_traj; + if (is_doing_c3_) { + execution_lcm_traj = c3_execution_lcm_traj_; + } else { + execution_lcm_traj = repos_execution_lcm_traj_; + } + + // Returned trajectory includes EE positions and feed-forward forces. + LcmTrajectory::Trajectory end_effector_traj = + execution_lcm_traj.GetTrajectory("end_effector_position_target"); + DRAKE_DEMAND(end_effector_traj.datapoints.rows() == 3); + LcmTrajectory lcm_traj({end_effector_traj}, {"end_effector_position_target"}, + "end_effector_position_target", + "end_effector_position_target", false); + + MatrixXd force_samples = MatrixXd::Zero(3, N_); + LcmTrajectory::Trajectory force_traj = + execution_lcm_traj.GetTrajectory("end_effector_force_target"); + lcm_traj.AddTrajectory(force_traj.traj_name, force_traj); + + output_execution_lcm_traj->saved_traj = lcm_traj.GenerateLcmObject(); + output_execution_lcm_traj->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputIsC3Mode( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const { + Eigen::VectorXd vec = VectorXd::Constant(1, is_doing_c3_); + Eigen::MatrixXd c3_mode_data = Eigen::MatrixXd::Zero(1, 1); + Eigen::VectorXd timestamp = Eigen::VectorXd::Zero(1); + + // Read the boolean value into the matrix. + c3_mode_data(0, 0) = vec(0); + + LcmTrajectory::Trajectory c3_mode; + c3_mode.traj_name = "is_c3_mode"; + c3_mode.datatypes = std::vector(1, "bool"); + c3_mode.datapoints = c3_mode_data; + c3_mode.time_vector = timestamp.cast(); + LcmTrajectory c3_mode_traj({c3_mode}, {"is_c3_mode"}, "is_c3_mode", + "is_c3_mode", false); + + output->saved_traj = c3_mode_traj.GenerateLcmObject(); + output->utime = context.get_time() * 1e6; +} + +// Output port handler for Dynamically feasible trajectory used for cost +// computation. This will directy output an lcmt_timestamped_saved_traj +// object with the dynamically feasible trajectory. +void SamplingC3Controller::OutputDynamicallyFeasibleCurrPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* dynamically_feasible_curr_plan_actor) + const { + std::vector dynamically_feasible_traj = + std::vector(N_ + 1, VectorXd::Zero(n_x_)); + for (int i = 0; i < N_ + 1; i++) { + dynamically_feasible_traj[i] << + all_sample_dynamically_feasible_plans_.at( + SampleIndex::kCurrentLocation)[i]; + } + + Eigen::MatrixXd knots = + Eigen::MatrixXd::Zero(3, dynamically_feasible_traj.size()); + Eigen::VectorXd timestamps = + Eigen::VectorXd::Zero(dynamically_feasible_traj.size()); + for (int i = 0; i < dynamically_feasible_traj.size(); i++) { + knots.col(i) = dynamically_feasible_traj[i].head(3); + timestamps(i) = i; + } + + LcmTrajectory::Trajectory ee_traj; + Eigen::MatrixXd position_samples = Eigen::MatrixXd::Zero(3, N_ + 1); + position_samples = knots.bottomRows(3); + ee_traj.traj_name = "ee_position_target"; + ee_traj.datatypes = + std::vector(position_samples.rows(), "double"); + ee_traj.datapoints = position_samples; + ee_traj.time_vector = timestamps.cast(); + + LcmTrajectory ee_traj_lcm({ee_traj}, {"ee_position_target"}, + "ee_position_target", "ee_position_target", false); + + dynamically_feasible_curr_plan_actor->saved_traj = + ee_traj_lcm.GenerateLcmObject(); + dynamically_feasible_curr_plan_actor->utime = context.get_time() * 1e6; +} + +// Output port handler for Dynamically feasible trajectory used for cost +// computation. +void SamplingC3Controller::OutputDynamicallyFeasibleCurrPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* dynamically_feasible_curr_plan_object) + const { + std::vector dynamically_feasible_traj = + std::vector(N_ + 1, VectorXd::Zero(n_x_)); + for (int i = 0; i < N_ + 1; i++) { + dynamically_feasible_traj[i] << + all_sample_dynamically_feasible_plans_.at( + SampleIndex::kCurrentLocation)[i]; + } + + Eigen::MatrixXd knots = + Eigen::MatrixXd::Zero(7, dynamically_feasible_traj.size()); + Eigen::VectorXd timestamps = + Eigen::VectorXd::Zero(dynamically_feasible_traj.size()); + for (int i = 0; i < dynamically_feasible_traj.size(); i++) { + knots.col(i) = dynamically_feasible_traj[i].segment(n_q_-7, 7); + timestamps(i) = i; + } + + LcmTrajectory::Trajectory object_traj; + Eigen::MatrixXd position_samples = Eigen::MatrixXd::Zero(3, 6); + position_samples = knots.bottomRows(3); + object_traj.traj_name = "object_position_target"; + object_traj.datatypes = + std::vector(position_samples.rows(), "double"); + object_traj.datapoints = position_samples; + object_traj.time_vector = timestamps.cast(); + LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, + "object_target", "object_target", false); + + LcmTrajectory::Trajectory object_orientation_traj; + Eigen::MatrixXd orientation_samples = Eigen::MatrixXd::Zero(4, 6); + orientation_samples = knots.topRows(4); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = timestamps.cast(); + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + object_orientation_traj); + + dynamically_feasible_curr_plan_object->saved_traj = + lcm_traj.GenerateLcmObject(); + dynamically_feasible_curr_plan_object->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputDynamicallyFeasibleBestPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* dynamically_feasible_best_plan) + const { + std::vector dynamically_feasible_traj = + std::vector(N_ + 1, VectorXd::Zero(n_x_)); + for (int i = 0; i < N_ + 1; i++) { + dynamically_feasible_traj[i] << + all_sample_dynamically_feasible_plans_.at(best_sample_index_)[i]; + } + + Eigen::MatrixXd knots = + Eigen::MatrixXd::Zero(3, dynamically_feasible_traj.size()); + Eigen::VectorXd timestamps = + Eigen::VectorXd::Zero(dynamically_feasible_traj.size()); + for (int i = 0; i < dynamically_feasible_traj.size(); i++) { + knots.col(i) = dynamically_feasible_traj[i].head(3); + timestamps(i) = i; + } + + LcmTrajectory::Trajectory ee_traj; + Eigen::MatrixXd position_samples = Eigen::MatrixXd::Zero(3, 6); + position_samples = knots.bottomRows(3); + ee_traj.traj_name = "ee_position_target"; + ee_traj.datatypes = + std::vector(position_samples.rows(), "double"); + ee_traj.datapoints = position_samples; + ee_traj.time_vector = timestamps.cast(); + + LcmTrajectory ee_traj_lcm({ee_traj}, {"ee_position_target"}, + "ee_position_target", "ee_position_target", false); + + dynamically_feasible_best_plan->saved_traj = ee_traj_lcm.GenerateLcmObject(); + dynamically_feasible_best_plan->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputDynamicallyFeasibleBestPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* dynamically_feasible_best_plan) + const { + std::vector dynamically_feasible_traj = + std::vector(N_ + 1, VectorXd::Zero(n_x_)); + for (int i = 0; i < N_ + 1; i++) { + dynamically_feasible_traj[i] << + all_sample_dynamically_feasible_plans_.at(best_sample_index_)[i]; + } + + Eigen::MatrixXd knots = + Eigen::MatrixXd::Zero(7, dynamically_feasible_traj.size()); + Eigen::VectorXd timestamps = + Eigen::VectorXd::Zero(dynamically_feasible_traj.size()); + for (int i = 0; i < dynamically_feasible_traj.size(); i++) { + knots.col(i) = dynamically_feasible_traj[i].segment(n_q_-7, 7); + timestamps(i) = i; + } + + LcmTrajectory::Trajectory object_traj; + Eigen::MatrixXd position_samples = Eigen::MatrixXd::Zero(3, 6); + position_samples = knots.bottomRows(3); + object_traj.traj_name = "object_position_target"; + object_traj.datatypes = + std::vector(position_samples.rows(), "double"); + object_traj.datapoints = position_samples; + object_traj.time_vector = timestamps.cast(); + LcmTrajectory lcm_traj({object_traj}, {"object_position_target"}, + "object_target", "object_target", false); + + LcmTrajectory::Trajectory object_orientation_traj; + Eigen::MatrixXd orientation_samples = Eigen::MatrixXd::Zero(4, 6); + orientation_samples = knots.topRows(4); + object_orientation_traj.traj_name = "object_orientation_target"; + object_orientation_traj.datatypes = + std::vector(orientation_samples.rows(), "double"); + object_orientation_traj.datapoints = orientation_samples; + object_orientation_traj.time_vector = timestamps.cast(); + lcm_traj.AddTrajectory(object_orientation_traj.traj_name, + object_orientation_traj); + + dynamically_feasible_best_plan->saved_traj = lcm_traj.GenerateLcmObject(); + dynamically_feasible_best_plan->utime = context.get_time() * 1e6; +} + +// Output port handlers for sample-related ports +void SamplingC3Controller::OutputAllSampleLocations( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_all_sample_locations) const { + std::vector sample_locations = std::vector( + all_sample_locations_.begin(), all_sample_locations_.end()); + // Pad with zeros to make sure the size is max_num_samples_ + 1 for the + // visualizer. + while (sample_locations.size() < max_num_samples_ + 1) { + sample_locations.push_back(Vector3d::Zero()); + } + + Eigen::MatrixXd sample_datapoints = + Eigen::MatrixXd::Zero(3, sample_locations.size()); + Eigen::VectorXd timestamps = Eigen::VectorXd::Zero(sample_locations.size()); + for (int i = 0; i < sample_locations.size(); i++) { + sample_datapoints.col(i) = sample_locations[i]; + timestamps(i) = i; + } + + LcmTrajectory::Trajectory sample_positions; + sample_positions.traj_name = "sample_locations"; + sample_positions.datatypes = std::vector(3, "double"); + sample_positions.datapoints = sample_datapoints; + sample_positions.time_vector = timestamps.cast(); + LcmTrajectory sample_traj({sample_positions}, {"sample_locations"}, + "sample_locations", "sample_locations", false); + + output_all_sample_locations->saved_traj = sample_traj.GenerateLcmObject(); + output_all_sample_locations->utime = context.get_time() * 1e6; +} + +void SamplingC3Controller::OutputAllSampleCosts( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output_all_sample_costs) const { + Eigen::MatrixXd cost_datapoints = + Eigen::MatrixXd::Zero(1, all_sample_costs_.size()); + Eigen::VectorXd timestamps = Eigen::VectorXd::Zero(all_sample_costs_.size()); + + for (int i = 0; i < all_sample_costs_.size(); i++) { + cost_datapoints(0, i) = all_sample_costs_[i]; + timestamps(i) = i * dt_; // dummy timestamp for the sample costs + } + + LcmTrajectory::Trajectory sample_costs_traj; + sample_costs_traj.traj_name = "sample_costs"; + sample_costs_traj.datatypes = std::vector(1, "double"); + sample_costs_traj.datapoints = cost_datapoints; + sample_costs_traj.time_vector = timestamps.cast(); + LcmTrajectory cost_traj({sample_costs_traj}, {"sample_costs"}, "sample_costs", + "sample_costs", false); + + output_all_sample_costs->saved_traj = cost_traj.GenerateLcmObject(); + output_all_sample_costs->utime = context.get_time() * 1e6; + + if (verbose_) { + std::cout << "All sample costs as per output port: " << std::endl; + for (int i = 0; i < all_sample_costs_.size(); i++) { + std::cout << all_sample_costs_[i] << std::endl; + } + } +} + +void SamplingC3Controller::OutputDebug( + const drake::systems::Context& context, + dairlib::lcmt_sampling_c3_debug* debug_msg) const { + debug_msg->utime = context.get_time() * 1e6; + debug_msg->is_c3_mode = is_doing_c3_; + + // Redundant radio things included in debug message for convenience. + const auto& radio_out = + this->EvalInputValue(context, radio_port_); + debug_msg->is_teleop = radio_out->channel[14]; // 14 = teleop + debug_msg->is_force_tracking = !radio_out->channel[11]; // 11 = force tracking + // disabled + debug_msg->is_forced_into_c3 = radio_out->channel[12]; // 12 = forced into C3 + debug_msg->in_pose_tracking_mode = crossed_cost_switching_threshold_; + debug_msg->mode_switch_reason = mode_switch_reason_; + debug_msg->source_of_pursued_target = pursued_target_source_; + debug_msg->detected_goal_changes = detected_goal_changes_; + debug_msg->best_progress_steps_ago = best_progress_steps_ago_; + debug_msg->lowest_cost = lowest_cost_; + debug_msg->lowest_pos_and_rot_current_cost = lowest_pos_and_rot_current_cost_; + debug_msg->lowest_position_error = lowest_position_error_; + debug_msg->lowest_orientation_error = lowest_orientation_error_; + debug_msg->current_pos_error = current_position_error_; + debug_msg->current_rot_error = current_orientation_error_; +} + +void SamplingC3Controller::OutputSampleBufferConfigurations( + const drake::systems::Context& context, + Eigen::MatrixXd* sample_buffer_configurations) const { + *sample_buffer_configurations = sample_buffer_; +} + +void SamplingC3Controller::OutputSampleBufferCosts( + const drake::systems::Context& context, + Eigen::VectorXd* sample_buffer_costs) const { + *sample_buffer_costs = sample_costs_buffer_; +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/controllers/sampling_based_c3_controller.h b/systems/controllers/sampling_based_c3_controller.h new file mode 100644 index 0000000000..ce470ae077 --- /dev/null +++ b/systems/controllers/sampling_based_c3_controller.h @@ -0,0 +1,462 @@ +#pragma once + +#include +#include +#include + +#include + +#include "common/find_resource.h" +#include "common/update_context.h" +#include "dairlib/lcmt_sampling_c3_debug.hpp" +#include "dairlib/lcmt_saved_traj.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "examples/sampling_c3/parameter_headers/sampling_c3_controller_params.h" +#include "examples/sampling_c3/parameter_headers/sampling_c3_options.h" +#include "examples/sampling_c3/parameter_headers/sampling_params.h" +#include "examples/sampling_c3/parameter_headers/reposition_params.h" +#include "examples/sampling_c3/parameter_headers/progress_params.h" +#include "lcm/lcm_trajectory.h" +#include "solvers/c3.h" +#include "solvers/c3_options.h" +#include "solvers/c3_output.h" +#include "solvers/lcs.h" +#include "solvers/lcs_factory.h" +#include "solvers/solver_options_io.h" +#include "systems/framework/timestamped_vector.h" + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { +using drake::AutoDiffVecXd; +using drake::AutoDiffXd; +using drake::MatrixX; +using drake::SortedPair; +using drake::VectorX; +using drake::geometry::GeometryId; +using drake::math::ExtractGradient; +using drake::math::ExtractValue; +using drake::multibody::MultibodyPlant; +using drake::systems::BasicVector; +using drake::systems::Context; +using systems::TimestampedVector; + +namespace systems { + + +enum SampleIndex { + kCurrentLocation, + kCurrentReposTarget // Only represents current reposition target when in + // reposition mode. + // Could expand this enum if want to reference more samples. +}; + +enum ModeSwitchReason { + kNoSwitch, + kToC3Cost, + kToC3ReachedReposTarget, + kToReposCost, + kToReposUnproductive, + kToC3Xbox +}; + +enum PursuedTargetSource { + kNoTarget, + kPrevious, + kNewSample, + kFromBuffer +}; + +class SamplingC3Controller : public drake::systems::LeafSystem { + public: + explicit SamplingC3Controller( + drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + drake::multibody::MultibodyPlant& plant_ad, + drake::systems::Context* context_ad, + const std::vector< + std::vector>>& + contact_geoms, + SamplingC3ControllerParams controller_params, bool verbose = false); + + // Input ports + const drake::systems::InputPort& + get_input_port_target() const { + return this->get_input_port(target_input_port_); + } + const drake::systems::InputPort& + get_input_port_final_target() const { + return this->get_input_port(final_target_input_port_); + } + const drake::systems::InputPort& + get_input_port_radio() const { + return this->get_input_port(radio_port_); + } + const drake::systems::InputPort& + get_input_port_lcs_state() const { + return this->get_input_port(lcs_state_input_port_); + } + + // Output ports + const drake::systems::OutputPort& + get_output_port_c3_solution_curr_plan() const { + return this->get_output_port(c3_solution_curr_plan_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_solution_curr_plan_actor() const { + return this->get_output_port(c3_solution_curr_plan_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_solution_curr_plan_object() const { + return this->get_output_port(c3_solution_curr_plan_object_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_intermediates_curr_plan() const { + return this->get_output_port(c3_intermediates_curr_plan_port_); + } + const drake::systems::OutputPort& + get_output_port_lcs_contact_jacobian_curr_plan() const { + return this->get_output_port(lcs_contact_jacobian_curr_plan_port_); + } + const drake::systems::OutputPort& + get_output_port_dynamically_feasible_curr_plan_actor() const { + return this->get_output_port(dynamically_feasible_curr_plan_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_dynamically_feasible_curr_plan_object() const { + return this->get_output_port(dynamically_feasible_curr_plan_object_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_solution_best_plan() const { + return this->get_output_port(c3_solution_best_plan_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_solution_best_plan_actor() const { + return this->get_output_port(c3_solution_best_plan_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_solution_best_plan_object() const { + return this->get_output_port(c3_solution_best_plan_object_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_intermediates_best_plan() const { + return this->get_output_port(c3_intermediates_best_plan_port_); + } + const drake::systems::OutputPort& + get_output_port_lcs_contact_jacobian_best_plan() const { + return this->get_output_port(lcs_contact_jacobian_best_plan_port_); + } + const drake::systems::OutputPort& + get_output_port_dynamically_feasible_best_plan_actor() const { + return this->get_output_port(dynamically_feasible_best_plan_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_dynamically_feasible_best_plan_object() const { + return this->get_output_port(dynamically_feasible_best_plan_object_port_); + } + const drake::systems::OutputPort& + get_output_port_c3_traj_execute_actor() const { + return this->get_output_port(c3_traj_execute_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_repos_traj_execute_actor() const { + return this->get_output_port(repos_traj_execute_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_traj_execute_actor() const { + return this->get_output_port(traj_execute_actor_port_); + } + const drake::systems::OutputPort& + get_output_port_is_c3_mode() const { + return this->get_output_port(is_c3_mode_port_); + } + const drake::systems::OutputPort& + get_output_port_all_sample_locations() const { + return this->get_output_port(all_sample_locations_port_); + } + const drake::systems::OutputPort& + get_output_port_all_sample_costs() const { + return this->get_output_port(all_sample_costs_port_); + } + const drake::systems::OutputPort& + get_output_port_debug() const { + return this->get_output_port(debug_lcmt_port_); + } + const drake::systems::OutputPort& + get_output_port_sample_buffer_configurations() const { + return this->get_output_port(sample_buffer_configurations_port_); + } + const drake::systems::OutputPort& + get_output_port_sample_buffer_costs() const { + return this->get_output_port(sample_buffer_costs_port_); + } + + private: + /// Function for computing one control loop + drake::systems::EventStatus ComputePlan( + const drake::systems::Context& context, + drake::systems::DiscreteValues* discrete_state) const; + + /// Helper functions + solvers::LCS CreatePlaceholderLCS() const; + + void ResolvePredictedEEState( + const bool& is_teleop, drake::VectorX& x_lcs_curr) const; + + void ClampEndEffectorAcceleration(drake::VectorX& x_lcs_curr) const; + + void CheckForWorkspaceLimitViolations( + const TimestampedVector* lcs_x_curr) const; + + void UpdateCostMatrices( + const drake::VectorX& x_lcs_curr, + const BasicVector& x_lcs_des, const C3Options& c3_options) const; + + std::pair, std::vector> + CreateLCSObjectsForSamples( + const std::vector& candidate_states, + const drake::VectorX& x_lcs_curr, const C3Options& c3_options, + const C3Options& c3_options_curr_location) const; + + void UpdateC3ExecutionTrajectory(const Eigen::VectorXd& x_lcs, + const double& t_context) const; + + void UpdateRepositioningExecutionTrajectory(const Eigen::VectorXd& x_lcs, + const double& t_context) const; + + void MaintainSampleBuffer(const Eigen::VectorXd& x_lcs) const; + + void AugmentSamplesWithBuffer( + std::vector>& c3_objects) const; + + void KeepTrackOfC3ModeProgress( + const drake::VectorX& x_lcs_curr, + const BasicVector& x_lcs_final_des, + bool& reset_progress_cost_buffer, + const bool& print_current_pos_and_rot_cost) const; + + void ResetProgressMetrics() const; + + /// Output port functions + void OutputC3SolutionCurrPlan( + const drake::systems::Context& context, + C3Output::C3Solution* c3_solution) const; + void OutputC3SolutionCurrPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const; + void OutputC3SolutionCurrPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const; + void OutputC3IntermediatesCurrPlan( + const drake::systems::Context& context, + C3Output::C3Intermediates* c3_intermediates) const; + void OutputLCSContactJacobianCurrPlan( + const drake::systems::Context& context, + std::pair>* + lcs_contact_jacobian) const; + void OutputC3SolutionBestPlan( + const drake::systems::Context& context, + C3Output::C3Solution* c3_solution) const; + void OutputC3SolutionBestPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const; + void OutputC3SolutionBestPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* output) const; + void OutputC3IntermediatesBestPlan( + const drake::systems::Context& context, + C3Output::C3Intermediates* c3_intermediates) const; + void OutputLCSContactJacobianBestPlan( + const drake::systems::Context& context, + std::pair>* + lcs_contact_jacobian) const; + void OutputDynamicallyFeasibleCurrPlanActor( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* + dynamically_feasible_curr_plan_actor) const; + void OutputDynamicallyFeasibleCurrPlanObject( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* + dynamically_feasible_curr_plan_object) const; + void OutputDynamicallyFeasibleBestPlanActor( + const drake::systems::Context& context, + lcmt_timestamped_saved_traj* dynamically_feasible_best_plan_actor) const; + void OutputDynamicallyFeasibleBestPlanObject( + const drake::systems::Context& context, + lcmt_timestamped_saved_traj* dynamically_feasible_best_plan_object) const; + void OutputAllSampleLocations( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* all_sample_locations) const; + void OutputAllSampleCosts( + const drake::systems::Context& context, + lcmt_timestamped_saved_traj* output_all_sample_costs) const; + void OutputC3TrajExecuteActor( + const drake::systems::Context& context, + lcmt_timestamped_saved_traj* c3_execution_lcm_traj) const; + void OutputReposTrajExecuteActor( + const drake::systems::Context& context, + lcmt_timestamped_saved_traj* repos_execution_lcm_traj) const; + void OutputTrajExecuteActor( + const drake::systems::Context& context, + lcmt_timestamped_saved_traj* execution_lcm_traj) const; + void OutputIsC3Mode( + const drake::systems::Context& context, + dairlib::lcmt_timestamped_saved_traj* is_c3_mode) const; + void OutputDebug( + const drake::systems::Context& context, + dairlib::lcmt_sampling_c3_debug* debug_msg) const; + void OutputSampleBufferConfigurations( + const drake::systems::Context& context, + Eigen::MatrixXd* sample_buffer_configurations) const; + void OutputSampleBufferCosts( + const drake::systems::Context& context, + Eigen::VectorXd* sample_buffer_costs) const; + + drake::systems::InputPortIndex radio_port_; + drake::systems::InputPortIndex final_target_input_port_; + drake::systems::InputPortIndex target_input_port_; + drake::systems::InputPortIndex lcs_state_input_port_; + // Current sample output port indices + drake::systems::OutputPortIndex c3_solution_curr_plan_port_; + drake::systems::OutputPortIndex c3_solution_curr_plan_actor_port_; + drake::systems::OutputPortIndex c3_solution_curr_plan_object_port_; + drake::systems::OutputPortIndex c3_intermediates_curr_plan_port_; + drake::systems::OutputPortIndex lcs_contact_jacobian_curr_plan_port_; + // Best sample output port indices + drake::systems::OutputPortIndex c3_solution_best_plan_port_; + drake::systems::OutputPortIndex c3_solution_best_plan_actor_port_; + drake::systems::OutputPortIndex c3_solution_best_plan_object_port_; + drake::systems::OutputPortIndex c3_intermediates_best_plan_port_; + drake::systems::OutputPortIndex lcs_contact_jacobian_best_plan_port_; + // Execution trajectory output port indices + drake::systems::OutputPortIndex c3_traj_execute_actor_port_; + drake::systems::OutputPortIndex repos_traj_execute_actor_port_; + drake::systems::OutputPortIndex traj_execute_actor_port_; + drake::systems::OutputPortIndex is_c3_mode_port_; + // Dynamically feasible plan output port indices + drake::systems::OutputPortIndex dynamically_feasible_curr_plan_actor_port_; + drake::systems::OutputPortIndex dynamically_feasible_curr_plan_object_port_; + drake::systems::OutputPortIndex dynamically_feasible_best_plan_actor_port_; + drake::systems::OutputPortIndex dynamically_feasible_best_plan_object_port_; + // Sample related output port indices + drake::systems::OutputPortIndex all_sample_locations_port_; + drake::systems::OutputPortIndex all_sample_costs_port_; + drake::systems::OutputPortIndex debug_lcmt_port_; + drake::systems::OutputPortIndex sample_buffer_configurations_port_; + drake::systems::OutputPortIndex sample_buffer_costs_port_; + + // This plant_ has been made 'not const' so that the context can be updated. + drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + drake::multibody::MultibodyPlant& plant_ad_; + drake::systems::Context* context_ad_; + const std::vector< + std::vector>>& + contact_pairs_; + solvers::ContactModel contact_model_; + + SamplingC3ControllerParams controller_params_; + SamplingC3Options sampling_c3_options_; + SamplingParams sampling_params_; + SamplingC3RepositionParams reposition_params_; + SamplingC3ProgressParams progress_params_; + drake::solvers::SolverOptions solver_options_ = + drake::yaml::LoadYamlFile( + "solvers/osqp_options_default.yaml") + .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); + + const bool verbose_; + int n_q_; + int n_v_; + int n_x_; + int n_lambda_; + int n_u_; + int max_num_samples_; + int N_; + + double solve_time_filter_constant_; + drake::systems::DiscreteStateIndex plan_start_time_index_; + + /// TODO: There are many mutable class variables, which is not best practice + /// in the Drake systems framework. These could be converted to discrete + /// state variables. + mutable double dt_ = 0.1; + + mutable std::vector Q_; + mutable std::vector R_; + mutable std::vector G_; + mutable std::vector U_; + + // Keep track of current C3 execution's best seen cost. + mutable int best_progress_steps_ago_; + mutable double lowest_cost_; + mutable double lowest_pos_and_rot_current_cost_; + mutable double lowest_position_error_; + mutable double lowest_orientation_error_; + mutable double current_position_error_; + mutable double current_orientation_error_; + mutable std::queue object_config_cost_history_; + + mutable double filtered_solve_time_ = 0; + + // Predictions for the end effector location. + mutable Eigen::VectorXd x_pred_curr_plan_; + mutable Eigen::VectorXd x_from_last_control_loop_; + mutable Eigen::VectorXd x_pred_from_last_control_loop_; + + // C3 solution for current location. + mutable std::shared_ptr c3_curr_plan_; + // TODO: these are currently assigned values but go unused -- may be useful if + // implementing warm start. + mutable std::vector z_sol_curr_plan_; + mutable std::vector delta_curr_plan_; + mutable std::vector w_curr_plan_; + + // C3 solution for best sample location. + mutable std::shared_ptr c3_best_plan_; + // TODO: these are currently assigned values but go unused -- may be useful if + // implementing warm start. + mutable std::vector z_sol_best_plan_; + mutable std::vector delta_best_plan_; + mutable std::vector w_best_plan_; + + // C3 solution for best sample in buffer. + mutable std::shared_ptr c3_buffer_plan_; + mutable std::vector dynamically_feasible_buffer_plan_; + + // LCS trajectories for C3 or repositioning modes. + mutable LcmTrajectory c3_execution_lcm_traj_; + mutable LcmTrajectory repos_execution_lcm_traj_; + + // Samples and associated costs computed in current control loop. + mutable std::vector all_sample_locations_; + mutable std::vector> + all_sample_dynamically_feasible_plans_; + mutable Eigen::Vector3d prev_repositioning_target_ = Eigen::Vector3d::Zero(); + mutable std::vector all_sample_costs_; + + // To detect if the final goal has been updated. + mutable Eigen::VectorXd x_final_target_; + mutable int detected_goal_changes_ = -1; + + // Sample buffer-related variables. + mutable int num_in_buffer_ = 0; + mutable Eigen::MatrixXd sample_buffer_; // (N_sample_buffer x n_q) + mutable Eigen::VectorXd sample_costs_buffer_; + + // Miscellaneous sample related variables. + mutable bool is_doing_c3_ = true; + mutable bool finished_reposition_flag_ = false; + // Crossing a threshold as the object gets closer to the goal means the + // controller goes from caring only about object position to caring about full + // pose. + mutable bool crossed_cost_switching_threshold_ = false; + mutable int num_threads_to_use_; + + mutable SampleIndex best_sample_index_ = kCurrentLocation; + mutable ModeSwitchReason mode_switch_reason_ = kNoSwitch; + mutable PursuedTargetSource pursued_target_source_ = kNoTarget; +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index e1ee3b0889..ebac84b08d 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -53,6 +53,71 @@ namespace systems { /// Note that we implement the class only in the header file because we don't /// know what MessageTypes are beforehand. +/** + * Subscribes to and stores a copy of the most recent message on a given + * channel, for some @p Message type. All copies of a given Subscriber share + * the same underlying data. This class does NOT provide any mutex behavior + * for multi-threaded locking; it should only be used in cases where the + * governing DrakeLcmInterface::HandleSubscriptions is called from the same + * thread that owns all copies of this object. + */ +template +class Subscriber final { + public: + // Intentionally copyable so that it can be returned and stored by-value. + DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Subscriber); + + /** + * Subscribes to the (non-empty) @p channel on the given (non-null) + * @p lcm instance. The `lcm` pointer is only used during construction; it + * is not retained by this object. When a undecodable message is received, + * @p on_error handler is invoked; when `on_error` is not provided, an + * exception will be thrown instead. + */ + Subscriber(drake::lcm::DrakeLcmInterface* lcm, const std::string& channel, + std::function on_error = {}) { + subscription_ = drake::lcm::Subscribe( + lcm, channel, + [data = data_](const Message& message) { + data->message = message; + data->count++; + }, + std::move(on_error)); + if (subscription_) { + subscription_->set_unsubscribe_on_delete(true); + } + } + + /** + * Returns the most recently received message, or a value-initialized (zeros) + * message otherwise. + */ + const Message& message() const { return data_->message; } + Message& message() { return data_->message; } + + /** Returns the total number of received messages. */ + int64_t count() const { return data_->count; } + int64_t& count() { return data_->count; } + + /** Clears all data (sets the message and count to all zeros). */ + void clear() { + data_->message = {}; + data_->count = 0; + } + + struct Data { + Message message{}; + int64_t count{0}; + }; + // Share a single copy of our (mutable) message storage, for all Subscribers + // to view or modify *and* for our subscription closure to write into. This + // will not be destroyed until all Subscribers are gone AND the subscription + // closure has been destroyed. + std::shared_ptr data_{std::make_shared()}; + // Keep our subscription active as long as a copy of this Subscriber remains. + std::shared_ptr subscription_; +}; + // We set a default value for SwitchMessageType so that we can generalize this // to both single and multi inputs. template > diagram, const drake::systems::LeafSystem* lcm_parser, - const std::string& input_channel, bool is_forced_publish) + const std::string& input_channel, bool is_forced_publish, + int queue_capacity = 1) : LcmDrivenLoop(drake_lcm, std::move(diagram), lcm_parser, std::vector(1, input_channel), input_channel, - "", is_forced_publish){}; + "", is_forced_publish, queue_capacity){}; /// Constructor for multi-input LcmDrivenLoop /// @param drake_lcm DrakeLcm @@ -91,6 +157,7 @@ class LcmDrivenLoop { std::vector input_channels, const std::string& active_channel, const std::string& switch_channel, bool is_forced_publish, + int queue_capacity = 1, const std::string& backup_drive_channel = "") : drake_lcm_(drake_lcm), lcm_parser_(lcm_parser), @@ -108,7 +175,7 @@ class LcmDrivenLoop { DRAKE_DEMAND(!input_channels.empty()); if (input_channels.size() > 1) { DRAKE_DEMAND(!switch_channel.empty()); - switch_sub_ = std::make_unique>( + switch_sub_ = std::make_unique>( drake_lcm_, switch_channel); } @@ -116,7 +183,9 @@ class LcmDrivenLoop { for (const auto& name : input_channels) { std::cout << "Constructing subscriber for " << name << std::endl; name_to_input_sub_map_.insert(std::make_pair( - name, drake::lcm::Subscriber(drake_lcm_, name))); + name, Subscriber(drake_lcm_, name))); + name_to_input_sub_map_.at(name).subscription_->set_queue_capacity( + queue_capacity); } // Make sure input_channels contains active_channel, and then set initial @@ -133,7 +202,7 @@ class LcmDrivenLoop { active_channel_ = active_channel; if (!backup_drive_channel.empty()) { - state_sub_ = std::make_unique>( + state_sub_ = std::make_unique>( drake_lcm_, backup_drive_channel); } }; @@ -226,6 +295,11 @@ class LcmDrivenLoop { is_new_state_message; }); + // Pump drake's LCM subscribers to empty their internal queues until all + // LCM buffers are up-to-date. + // Addresses https://github.com/RobotLocomotion/drake/issues/15234 + while (drake_lcm_->HandleSubscriptions(0) > 0); + // Update the diagram context when there is new input message if (is_new_input_message || too_long_between_input_messages_) { // Write the InputMessageType message into the context if lcm_parser is @@ -263,8 +337,8 @@ class LcmDrivenLoop { simulator_->AdvanceTo(time); diagram_ptr_->CalcForcedUnrestrictedUpdate( diagram_context, &diagram_context.get_mutable_state()); - diagram_ptr_->CalcForcedDiscreteVariableUpdate(diagram_context, - &diagram_context.get_mutable_discrete_state()); + diagram_ptr_->CalcForcedDiscreteVariableUpdate( + diagram_context, &diagram_context.get_mutable_discrete_state()); if (is_forced_publish_) { // Force-publish via the diagram diagram_ptr_->ForcedPublish(diagram_context); @@ -323,11 +397,9 @@ class LcmDrivenLoop { std::string diagram_name_ = "diagram"; std::string active_channel_; - std::unique_ptr> switch_sub_ = - nullptr; - std::map> - name_to_input_sub_map_; - std::unique_ptr> state_sub_; + std::unique_ptr> switch_sub_ = nullptr; + std::map> name_to_input_sub_map_; + std::unique_ptr> state_sub_; bool is_forced_publish_; bool too_long_between_input_messages_ = false; diff --git a/systems/sender_systems/BUILD.bazel b/systems/sender_systems/BUILD.bazel deleted file mode 100644 index 6d13068b58..0000000000 --- a/systems/sender_systems/BUILD.bazel +++ /dev/null @@ -1,25 +0,0 @@ -package(default_visibility = ["//visibility:public"]) - -cc_library( - name = "sender_systems", - srcs = [], - deps = [ - ":c3_state_sender", - ], -) - -cc_library( - name = "c3_state_sender", - srcs = [ - "c3_state_sender.cc", - ], - hdrs = [ - "c3_state_sender.h", - ], - deps = [ - "//lcmtypes:lcmt_robot", - "//systems/framework:vector", - "@drake//:drake_shared_library", - ], -) - diff --git a/systems/senders/BUILD.bazel b/systems/senders/BUILD.bazel new file mode 100644 index 0000000000..294107a22a --- /dev/null +++ b/systems/senders/BUILD.bazel @@ -0,0 +1,62 @@ +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "senders", + srcs = [], + deps = [ + ":sample_buffer_sender", + ":c3_state_sender", + ":sample_buffer_to_point_cloud", + ], +) + +cc_library( + name = "sample_buffer_to_point_cloud", + srcs = [ + "sample_buffer_to_point_cloud.cc", + ], + hdrs = [ + "sample_buffer_to_point_cloud.h", + ], + deps = [ + "//common:find_resource", + "//lcmtypes:lcmt_robot", + "//multibody:utils", + "//systems/framework:vector", + "@drake//:drake_shared_library", + "//lcm:lcm_trajectory_saver", + "@lcm", + ], +) + +cc_library( + name = "sample_buffer_sender", + srcs = [ + "sample_buffer_sender.cc", + ], + hdrs = [ + "sample_buffer_sender.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "//common", + "//common:find_resource", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "c3_state_sender", + srcs = [ + "c3_state_sender.cc", + ], + hdrs = [ + "c3_state_sender.h", + ], + deps = [ + "//lcmtypes:lcmt_robot", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) diff --git a/systems/sender_systems/c3_state_sender.cc b/systems/senders/c3_state_sender.cc similarity index 98% rename from systems/sender_systems/c3_state_sender.cc rename to systems/senders/c3_state_sender.cc index 5e99b4c7b4..ed296d9164 100644 --- a/systems/sender_systems/c3_state_sender.cc +++ b/systems/senders/c3_state_sender.cc @@ -1,4 +1,4 @@ -#include "systems/sender_systems/c3_state_sender.h" +#include "systems/senders/c3_state_sender.h" #include "systems/framework/timestamped_vector.h" namespace dairlib { diff --git a/systems/sender_systems/c3_state_sender.h b/systems/senders/c3_state_sender.h similarity index 100% rename from systems/sender_systems/c3_state_sender.h rename to systems/senders/c3_state_sender.h diff --git a/systems/senders/sample_buffer_sender.cc b/systems/senders/sample_buffer_sender.cc new file mode 100644 index 0000000000..21403de630 --- /dev/null +++ b/systems/senders/sample_buffer_sender.cc @@ -0,0 +1,77 @@ +#include "sample_buffer_sender.h" + +#include +#include + +#include "common/eigen_utils.h" + +namespace dairlib { +namespace systems { + +using drake::systems::Context; +using Eigen::MatrixXd; +using Eigen::VectorXd; + +SampleBufferSender::SampleBufferSender(int buffer_size, int n_config) + : buffer_size_(buffer_size), n_config_(n_config) { + this->set_name("sample_buffer_sender"); + + MatrixXd sample_buffer = MatrixXd::Zero(buffer_size_, n_config_); + VectorXd cost_buffer = VectorXd::Zero(buffer_size_); + samples_port_ = + this->DeclareAbstractInputPort("sample_buffer_configurations", + drake::Value{sample_buffer}) + .get_index(); + sample_costs_port_ = + this->DeclareAbstractInputPort("sample_buffer_costs", + drake::Value{cost_buffer}) + .get_index(); + + lcm_sample_buffer_output_port_ = + this->DeclareAbstractOutputPort( + "lcmt_sample_buffer", dairlib::lcmt_sample_buffer(), + &SampleBufferSender::OutputSampleBufferLcm) + .get_index(); +} + +void SampleBufferSender::OutputSampleBufferLcm( + const drake::systems::Context& context, + dairlib::lcmt_sample_buffer* output) const { + // Evaluate input ports to get the sample configurations and costs. + const auto& buffer_configurations = + this->EvalInputValue(context, samples_port_); + const auto& buffer_costs = + this->EvalInputValue(context, sample_costs_port_); + + DRAKE_ASSERT(buffer_configurations->rows() == buffer_size_); + DRAKE_ASSERT(buffer_configurations->cols() == n_config_); + DRAKE_ASSERT(buffer_costs->size() == buffer_size_); + + // Count the number of active samples in the buffer. + int n_in_buffer = std::count_if (buffer_costs->begin(), buffer_costs->end(), + [](double cost) { return cost >= 0; }); + + // Convert the Eigen matrices to std::vectors. + std::vector cost_data(buffer_costs->data(), + buffer_costs->data() + buffer_size_); + std::vector> config_data(buffer_size_, + std::vector(n_config_, 0)); + for (int i = 0; i < buffer_size_; i++) { + for (int j = 0; j < n_config_; j++) { + config_data[i][j] = buffer_configurations->row(i)(j); + } + } + + // Set the fields of the LCM message. + output->utime = context.get_time() * 1e6; + output->buffer_length = buffer_size_; + output->num_configurations = n_config_; + output->num_in_buffer = n_in_buffer; + + output->costs.reserve(buffer_size_); + output->costs = cost_data; + output->configurations = config_data; +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/senders/sample_buffer_sender.h b/systems/senders/sample_buffer_sender.h new file mode 100644 index 0000000000..4bf5672451 --- /dev/null +++ b/systems/senders/sample_buffer_sender.h @@ -0,0 +1,45 @@ +#pragma once + +#include +#include + +#include "dairlib/lcmt_sample_buffer.hpp" + +#include "drake/systems/framework/leaf_system.h" +#include "drake/systems/lcm/lcm_interface_system.h" + +namespace dairlib { +namespace systems { + +/// Converts sample costs and configurations to LCM type lcmt_sample_buffer +class SampleBufferSender : public drake::systems::LeafSystem { + public: + SampleBufferSender(int buffer_size, int n_config); + + const drake::systems::InputPort& get_input_port_sample_costs() const { + return this->get_input_port(sample_costs_port_); + } + + const drake::systems::InputPort& get_input_port_samples() const { + return this->get_input_port(samples_port_); + } + + const drake::systems::OutputPort& get_output_port_sample_buffer() + const { + return this->get_output_port(lcm_sample_buffer_output_port_); + } + + private: + void OutputSampleBufferLcm(const drake::systems::Context& context, + dairlib::lcmt_sample_buffer* output) const; + + int buffer_size_; + int n_config_; + + drake::systems::InputPortIndex samples_port_; + drake::systems::InputPortIndex sample_costs_port_; + drake::systems::OutputPortIndex lcm_sample_buffer_output_port_; +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/senders/sample_buffer_to_point_cloud.cc b/systems/senders/sample_buffer_to_point_cloud.cc new file mode 100644 index 0000000000..66349f1895 --- /dev/null +++ b/systems/senders/sample_buffer_to_point_cloud.cc @@ -0,0 +1,131 @@ +#include "systems/senders/sample_buffer_to_point_cloud.h" + +#include "dairlib/lcmt_sample_buffer.hpp" +#include "dairlib/lcmt_saved_traj.hpp" +#include "dairlib/lcmt_timestamped_saved_traj.hpp" +#include "lcm/lcm_trajectory.h" + +#include "drake/perception/point_cloud.h" +#include "drake/perception/point_cloud_flags.h" +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +using drake::perception::PointCloud; +using drake::systems::Context; + +namespace systems { + +PointCloudFromSampleBuffer::PointCloudFromSampleBuffer() { + this->set_name("PointCloudFromSampleBuffer"); + + lcmt_sample_buffer_input_port_ = + this->DeclareAbstractInputPort( + "lcmt_sample_buffer", drake::Value{}) + .get_index(); + + new_sample_costs_input_port_ = + this->DeclareAbstractInputPort( + "new_sample_costs", + drake::Value{}) + .get_index(); + + point_cloud_output_port_ = + this->DeclareAbstractOutputPort( + "sample_buffer_point_cloud", PointCloud(), + &PointCloudFromSampleBuffer::OutputSampleBufferAsPointCloud) + .get_index(); + + color_floats_ = colorFloatMap(); + RGBs_ = RGBMap(); +} + +void PointCloudFromSampleBuffer::OutputSampleBufferAsPointCloud( + const drake::systems::Context& context, + PointCloud* sample_buffer_point_cloud) const { + if (!sample_buffer_point_cloud->HasExactFields( + drake::perception::pc_flags::kXYZs | + drake::perception::pc_flags::kRGBs)) { + sample_buffer_point_cloud->SetFields(drake::perception::pc_flags::kXYZs | + drake::perception::pc_flags::kRGBs); + } + + // Evaluate input ports to get the sample buffer contents and current location + // C3 cost. + const auto& sample_buffer_lcmt = + this->EvalInputValue( + context, lcmt_sample_buffer_input_port_); + const auto& new_sample_costs_traj_lcmt = + this->EvalInputValue( + context, new_sample_costs_input_port_); + + Eigen::Matrix3Xf ee_samples; + Eigen::Matrix3Xi rgbs; + + // Check if it's too early to output or if there are no samples in the buffer. + if ((sample_buffer_lcmt->utime < 1e-3) || + (sample_buffer_lcmt->num_in_buffer < 1)) { + ee_samples = Eigen::Matrix3Xf::Zero(3, 1); + rgbs = Eigen::Matrix3Xi::Zero(3, 1); + } else { + // Extract the end effector locations out of the configurations and the + // samples' associated costs. + int n_in_buffer = sample_buffer_lcmt->num_in_buffer; + ee_samples = Eigen::Matrix3Xf::Zero(3, n_in_buffer); + Eigen::VectorXf costs = Eigen::VectorXf::Zero(n_in_buffer); + + for (int sample_i = 0; sample_i < n_in_buffer; sample_i++) { + costs[sample_i] = sample_buffer_lcmt->costs[sample_i]; + std::vector configuration_i = + sample_buffer_lcmt->configurations[sample_i]; + for (int ee_i = 0; ee_i < 3; ee_i++) { + ee_samples(ee_i, sample_i) = configuration_i[ee_i]; + } + } + + // Normalize the costs to be between 0 and 1. + if (costs.maxCoeff() == costs.minCoeff()) { + rgbs = Eigen::Matrix3Xi::Zero(3, n_in_buffer); + } else { + Eigen::VectorXf normalized_costs = (costs.array() - costs.minCoeff()) / + (costs.maxCoeff() - costs.minCoeff()); + + // Get the current sample cost. + auto lcm_traj = LcmTrajectory(new_sample_costs_traj_lcmt->saved_traj); + auto lcm_sample_costs_traj = lcm_traj.GetTrajectory("sample_costs"); + Eigen::MatrixXd sample_costs = lcm_sample_costs_traj.datapoints.row(0); + double current_cost = sample_costs(0); + + double normalized_current_cost = (current_cost - costs.minCoeff()) / + (costs.maxCoeff() - costs.minCoeff()); + + // Make the current cost the centered color. + Eigen::VectorXf scaled_costs = + normalized_costs.array() - normalized_current_cost + 0.5; + + // Apply the color map. + Eigen::MatrixXf differences = + (scaled_costs.replicate(1, n_colors_) - + color_floats_.transpose().replicate(n_in_buffer, 1)) + .cwiseAbs(); + Eigen::VectorXi closest_color_indices(n_in_buffer); + for (int i = 0; i < n_in_buffer; i++) { + int idx; + differences.row(i).minCoeff(&idx); + closest_color_indices[i] = idx; + } + rgbs = Eigen::Matrix3Xi::Zero(3, n_in_buffer); + for (int i = 0; i < n_in_buffer; i++) { + rgbs.col(i) = RGBs_.row(closest_color_indices(i)); + } + } + } + + // Output as a point cloud where the colors reflect costs. + sample_buffer_point_cloud->resize(ee_samples.cols()); + sample_buffer_point_cloud->mutable_xyzs() = ee_samples; + sample_buffer_point_cloud->mutable_rgbs() = rgbs.cast(); +} + +} // namespace systems +} // namespace dairlib diff --git a/systems/senders/sample_buffer_to_point_cloud.h b/systems/senders/sample_buffer_to_point_cloud.h new file mode 100644 index 0000000000..9f64bf567a --- /dev/null +++ b/systems/senders/sample_buffer_to_point_cloud.h @@ -0,0 +1,118 @@ +#include + +#include + +#include +#include + +#include "drake/systems/framework/leaf_system.h" + +namespace dairlib { + +using drake::perception::PointCloud; + +namespace systems { + +class PointCloudFromSampleBuffer : public drake::systems::LeafSystem { + // This system reads the sample_buffer over lcm and outputs a Drake PointCloud + // for visualization. + public: + PointCloudFromSampleBuffer(); + + // Input ports + const drake::systems::InputPort& get_input_port_lcmt_sample_buffer() + const { + return this->get_input_port(lcmt_sample_buffer_input_port_); + } + const drake::systems::InputPort& get_input_port_new_sample_costs() + const { + return this->get_input_port(new_sample_costs_input_port_); + } + + // Output port + const drake::systems::OutputPort& + get_output_port_sample_buffer_point_cloud() const { + return this->get_output_port(point_cloud_output_port_); + } + + private: + void OutputSampleBufferAsPointCloud( + const drake::systems::Context& context, + PointCloud* sample_buffer_point_cloud) const; + + drake::systems::InputPortIndex new_sample_costs_input_port_; + drake::systems::InputPortIndex lcmt_sample_buffer_input_port_; + drake::systems::OutputPortIndex point_cloud_output_port_; + + Eigen::VectorXf color_floats_; + Eigen::MatrixXi RGBs_; + + const int n_colors_ = 100; + + // Generates samples of a matplotlib colormap RdYlGn.reversed() for coloring + // the point cloud. + inline Eigen::VectorXf colorFloatMap() { + Eigen::VectorXf color_floats(n_colors_); + color_floats << 0.0, 0.010101010101010102, 0.020202020202020204, + 0.030303030303030304, 0.04040404040404041, 0.050505050505050504, + 0.06060606060606061, 0.0707070707070707, 0.08080808080808081, + 0.09090909090909091, 0.10101010101010101, 0.1111111111111111, + 0.12121212121212122, 0.13131313131313133, 0.1414141414141414, + 0.15151515151515152, 0.16161616161616163, 0.1717171717171717, + 0.18181818181818182, 0.1919191919191919, 0.20202020202020202, + 0.21212121212121213, 0.2222222222222222, 0.23232323232323232, + 0.24242424242424243, 0.25252525252525254, 0.26262626262626265, + 0.2727272727272727, 0.2828282828282828, 0.29292929292929293, + 0.30303030303030304, 0.31313131313131315, 0.32323232323232326, + 0.3333333333333333, 0.3434343434343434, 0.35353535353535354, + 0.36363636363636365, 0.37373737373737376, 0.3838383838383838, + 0.3939393939393939, 0.40404040404040403, 0.41414141414141414, + 0.42424242424242425, 0.43434343434343436, 0.4444444444444444, + 0.45454545454545453, 0.46464646464646464, 0.47474747474747475, + 0.48484848484848486, 0.494949494949495, 0.5050505050505051, + 0.5151515151515151, 0.5252525252525253, 0.5353535353535354, + 0.5454545454545454, 0.5555555555555556, 0.5656565656565656, + 0.5757575757575758, 0.5858585858585859, 0.5959595959595959, + 0.6060606060606061, 0.6161616161616161, 0.6262626262626263, + 0.6363636363636364, 0.6464646464646465, 0.6565656565656566, + 0.6666666666666666, 0.6767676767676768, 0.6868686868686869, + 0.696969696969697, 0.7070707070707071, 0.7171717171717171, + 0.7272727272727273, 0.7373737373737373, 0.7474747474747475, + 0.7575757575757576, 0.7676767676767676, 0.7777777777777778, + 0.7878787878787878, 0.797979797979798, 0.8080808080808081, + 0.8181818181818182, 0.8282828282828283, 0.8383838383838383, + 0.8484848484848485, 0.8585858585858586, 0.8686868686868687, + 0.8787878787878788, 0.8888888888888888, 0.898989898989899, + 0.9090909090909091, 0.9191919191919192, 0.9292929292929293, + 0.9393939393939394, 0.9494949494949495, 0.9595959595959596, + 0.9696969696969697, 0.9797979797979798, 0.98989898989899, 1.0; + return color_floats; + } + inline Eigen::MatrixXi RGBMap() { + Eigen::MatrixXi mat(n_colors_, 3); + mat << 0, 104, 55, 2, 108, 57, 5, 113, 60, 7, 117, 62, 10, 123, 65, 12, 127, + 67, 15, 132, 70, 18, 138, 73, 20, 142, 75, 23, 147, 78, 25, 151, 80, 33, + 156, 82, 42, 160, 84, 48, 163, 86, 57, 167, 88, 63, 170, 89, 72, 174, + 92, 78, 177, 93, 87, 182, 95, 96, 186, 98, 102, 189, 99, 110, 192, 100, + 115, 194, 100, 122, 198, 101, 130, 201, 102, 135, 203, 103, 142, 207, + 103, 147, 209, 104, 155, 212, 105, 160, 214, 105, 167, 217, 107, 173, + 220, 111, 177, 222, 113, 183, 224, 117, 187, 226, 120, 193, 229, 123, + 199, 231, 127, 203, 233, 130, 209, 236, 134, 213, 237, 136, 218, 240, + 141, 223, 242, 147, 226, 243, 151, 230, 245, 157, 233, 246, 161, 238, + 248, 168, 241, 249, 172, 245, 251, 178, 250, 253, 184, 253, 254, 188, + 255, 253, 188, 255, 251, 184, 255, 247, 178, 255, 243, 172, 255, 241, + 168, 254, 237, 161, 254, 235, 157, 254, 231, 151, 254, 229, 147, 254, + 225, 141, 254, 220, 136, 254, 216, 132, 254, 210, 127, 254, 206, 124, + 254, 200, 119, 253, 195, 114, 253, 191, 111, 253, 185, 106, 253, 181, + 103, 253, 175, 98, 252, 168, 94, 251, 163, 92, 250, 155, 88, 250, 150, + 86, 249, 142, 82, 248, 137, 80, 247, 129, 76, 246, 122, 73, 245, 117, + 71, 244, 109, 67, 242, 104, 65, 238, 97, 62, 235, 90, 58, 233, 85, 56, + 229, 78, 53, 227, 73, 51, 224, 66, 47, 221, 61, 45, 218, 54, 42, 214, + 47, 39, 210, 43, 39, 204, 38, 39, 200, 34, 39, 194, 28, 39, 189, 23, 38, + 185, 19, 38, 179, 13, 38, 175, 9, 38, 169, 4, 38, 165, 0, 38; + return mat; + } +}; + +} // namespace systems +} // namespace dairlib diff --git a/systems/system_utils.cc b/systems/system_utils.cc index 675bb53e13..783d82db8c 100644 --- a/systems/system_utils.cc +++ b/systems/system_utils.cc @@ -8,10 +8,13 @@ namespace dairlib { void DrawAndSaveDiagramGraph(const drake::systems::Diagram& diagram, std::string path) { // Default path - if (path.empty()){ - path = "../" + diagram.get_name(); + if (path.empty()) { + path = "../diagrams/" + diagram.get_name(); } + // Create the directory if it does not exist + std::system("mkdir -p ../diagrams"); + // Save Graphviz string to a file std::ofstream out(path); out << diagram.GetGraphvizString(); diff --git a/systems/visualization/lcm_visualization_systems.cc b/systems/visualization/lcm_visualization_systems.cc index c7eb1643b6..95ada3f671 100644 --- a/systems/visualization/lcm_visualization_systems.cc +++ b/systems/visualization/lcm_visualization_systems.cc @@ -27,9 +27,11 @@ using Eigen::VectorXd; LcmTrajectoryDrawer::LcmTrajectoryDrawer( const std::shared_ptr& meshcat, - std::string trajectory_name) - : meshcat_(meshcat), trajectory_name_(std::move(trajectory_name)) { - this->set_name("LcmTrajectoryDrawer: " + trajectory_name_); + std::string trajectory_name, const std::string& system_name) + : meshcat_(meshcat), + trajectory_name_(std::move(trajectory_name)), + system_name_(std::move(system_name)) { + this->set_name("LcmTrajectoryDrawer: " + system_name_ + trajectory_name_); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", @@ -72,8 +74,8 @@ drake::systems::EventStatus LcmTrajectoryDrawer::DrawTrajectory( } DRAKE_DEMAND(line_points.rows() == 3); - meshcat_->SetLine("/trajectories/" + trajectory_name_, line_points, 100, - rgba_); + meshcat_->SetLine("/trajectories/" + system_name_ + trajectory_name_, + line_points, line_width_, rgba_); return drake::systems::EventStatus::Succeeded(); } @@ -81,24 +83,26 @@ LcmPoseDrawer::LcmPoseDrawer( const std::shared_ptr& meshcat, const std::string& model_file, const std::string& translation_trajectory_name, - const std::string& orientation_trajectory_name, int num_poses, - bool add_transparency) + const std::string& orientation_trajectory_name, + const std::string& system_name, + int num_poses, + bool add_transparency, + const Eigen::VectorXd& rgb) : meshcat_(meshcat), translation_trajectory_name_(translation_trajectory_name), orientation_trajectory_name_(orientation_trajectory_name), N_(num_poses) { - this->set_name("LcmPoseDrawer: " + translation_trajectory_name); + this->set_name("LcmPoseDrawer: " + system_name + translation_trajectory_name); Eigen::VectorXd alpha_scale; if (add_transparency) { - alpha_scale = 1.0 * VectorXd::LinSpaced(N_ - 1, 0.2, 0.5); + alpha_scale = 1.0 * VectorXd::LinSpaced(N_, 0.5, 0.1); } else { - alpha_scale = 1.0 * VectorXd::Ones(N_ - 1); + alpha_scale = 1.0 * VectorXd::Ones(N_); } - alpha_scale.reverseInPlace(); multipose_visualizer_ = std::make_unique( - model_file, N_ - 1, alpha_scale, "", meshcat); + model_file, N_, alpha_scale, "", meshcat, system_name, rgb); trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj", @@ -120,7 +124,7 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( this->EvalInputValue( context, trajectory_input_port_); auto lcm_traj = LcmTrajectory(lcmt_traj->saved_traj); - MatrixXd object_poses = MatrixXd::Zero(7, N_ - 1); + MatrixXd object_poses = MatrixXd::Zero(7, N_); const auto& lcm_translation_traj = lcm_traj.GetTrajectory(translation_trajectory_name_); @@ -150,14 +154,18 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( quaternion_datapoints); } - // ASSUMING orientation and translation trajectories have the same breaks + // ASSUMING orientation and translation trajectories have the same breaks. + // This recreates the trajectory using the knot points and then evaluates the + // trajectory at equal intervals based on the parameters. If the num_poses is + // equal to the number of knot points, then the poses will be the same as the + // knot points. VectorXd translation_breaks = VectorXd::LinSpaced(N_, lcm_translation_traj.time_vector[0], lcm_translation_traj.time_vector.tail(1)[0]); for (int i = 0; i < object_poses.cols(); ++i) { object_poses.col(i) << orientation_trajectory.value( - translation_breaks(i + 1)), - translation_trajectory.value(translation_breaks(i + 1)); + translation_breaks(i)), + translation_trajectory.value(translation_breaks(i)); } multipose_visualizer_->DrawPoses(object_poses); @@ -168,12 +176,12 @@ drake::systems::EventStatus LcmPoseDrawer::DrawTrajectory( LcmForceDrawer::LcmForceDrawer( const std::shared_ptr& meshcat, std::string actor_trajectory_name, std::string force_trajectory_name, - std::string lcs_force_trajectory_name) + std::string lcs_force_trajectory_name, const std::string& system_name) : meshcat_(meshcat), actor_trajectory_name_(std::move(actor_trajectory_name)), force_trajectory_name_(std::move(force_trajectory_name)), lcs_force_trajectory_name_(std::move(lcs_force_trajectory_name)) { - this->set_name("LcmForceDrawer: " + force_trajectory_name_); + this->set_name("LcmForceDrawer: " + system_name + force_trajectory_name_); actor_trajectory_input_port_ = this->DeclareAbstractInputPort( "lcmt_timestamped_saved_traj: actor", @@ -302,7 +310,7 @@ drake::systems::EventStatus LcmForceDrawer::DrawForces( auto force_norm = force.norm(); const std::string& force_path_root = force_path_ + "/lcs_force_" + std::to_string(i) + "/"; - if (force_norm >= 0.5) { + if (force_norm >= 0.01) { if (!meshcat_->HasPath(force_path_root + "arrow/")) { meshcat_->SetObject(force_path_root + "arrow/cylinder", cylinder_, contact_force_color_); @@ -346,6 +354,10 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( bool draw_ee) : meshcat_(meshcat), draw_tray_(draw_tray), draw_ee_(draw_ee) { this->set_name("LcmC3TargetDrawer"); + c3_state_final_target_input_port_ = + this->DeclareAbstractInputPort("lcmt_c3_state: final_target", + drake::Value{}) + .get_index(); c3_state_target_input_port_ = this->DeclareAbstractInputPort("lcmt_c3_state: target", drake::Value{}) @@ -361,12 +373,18 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( // TODO(yangwill): Clean up all this visualization, move to separate // visualization directory1 - meshcat_->SetObject(c3_target_object_path_ + "/x-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_final_target_object_path_ + "/x-axis", cylinder_for_tray_, {1, 0, 0, 1}); - meshcat_->SetObject(c3_target_object_path_ + "/y-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_final_target_object_path_ + "/y-axis", cylinder_for_tray_, {0, 1, 0, 1}); - meshcat_->SetObject(c3_target_object_path_ + "/z-axis", cylinder_for_tray_, + meshcat_->SetObject(c3_final_target_object_path_ + "/z-axis", cylinder_for_tray_, {0, 0, 1, 1}); + meshcat_->SetObject(c3_target_object_path_ + "/x-axis", cylinder_for_tray_, + {1, 0, 0, 0.3}); + meshcat_->SetObject(c3_target_object_path_ + "/y-axis", cylinder_for_tray_, + {0, 1, 0, 0.3}); + meshcat_->SetObject(c3_target_object_path_ + "/z-axis", cylinder_for_tray_, + {0, 0, 1, 0.3}); meshcat_->SetObject(c3_actual_object_path_ + "/x-axis", cylinder_for_tray_, {1, 0, 0, 1}); meshcat_->SetObject(c3_actual_object_path_ + "/y-axis", cylinder_for_tray_, @@ -405,19 +423,22 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( auto z_axis_transform_ee = RigidTransformd(Eigen::AngleAxis(0.5 * M_PI, Vector3d::UnitZ()), 0.5 * Vector3d{0.0, 0.0, 0.05}); - meshcat_->SetTransform(c3_target_object_path_ + "/x-axis", x_axis_transform, 0.0); - meshcat_->SetTransform(c3_target_object_path_ + "/y-axis", y_axis_transform, 0.0); - meshcat_->SetTransform(c3_target_object_path_ + "/z-axis", z_axis_transform, 0.0); - meshcat_->SetTransform(c3_actual_object_path_ + "/x-axis", x_axis_transform, 0.0); - meshcat_->SetTransform(c3_actual_object_path_ + "/y-axis", y_axis_transform, 0.0); - meshcat_->SetTransform(c3_actual_object_path_ + "/z-axis", z_axis_transform, 0.0); + meshcat_->SetTransform(c3_final_target_object_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_final_target_object_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_final_target_object_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_target_object_path_ + "/z-axis", z_axis_transform); + meshcat_->SetTransform(c3_actual_object_path_ + "/x-axis", x_axis_transform); + meshcat_->SetTransform(c3_actual_object_path_ + "/y-axis", y_axis_transform); + meshcat_->SetTransform(c3_actual_object_path_ + "/z-axis", z_axis_transform); if (draw_ee_){ - meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee, 0.0); - meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee, 0.0); - meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee, 0.0); - meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee, 0.0); - meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee, 0.0); - meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee, 0.0); + meshcat_->SetTransform(c3_target_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_target_ee_path_ + "/z-axis", z_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/x-axis", x_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/y-axis", y_axis_transform_ee); + meshcat_->SetTransform(c3_actual_ee_path_ + "/z-axis", z_axis_transform_ee); } DeclarePerStepDiscreteUpdateEvent(&LcmC3TargetDrawer::DrawC3State); @@ -426,6 +447,13 @@ LcmC3TargetDrawer::LcmC3TargetDrawer( drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( const Context& context, DiscreteValues* discrete_state) const { + // Guarding the final state input port because it is not always connected, + // e.g. examples/franka. + const auto* c3_final_target = this->EvalInputValue( + context, c3_state_final_target_input_port_); + if (!c3_final_target || c3_final_target->utime < 1e-3) { + return drake::systems::EventStatus::Succeeded(); + } if (this->EvalInputValue(context, c3_state_target_input_port_) ->utime < 1e-3) { @@ -448,6 +476,15 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( const auto& c3_actual = this->EvalInputValue( context, c3_state_actual_input_port_); if (draw_tray_) { + meshcat_->SetTransform( + c3_final_target_object_path_, + RigidTransformd( + Eigen::Quaterniond(c3_final_target->state[3], + c3_final_target->state[4], + c3_final_target->state[5], + c3_final_target->state[6]), + Vector3d{c3_final_target->state[7], c3_final_target->state[8], + c3_final_target->state[9]})); meshcat_->SetTransform( c3_target_object_path_, RigidTransformd( @@ -467,11 +504,11 @@ drake::systems::EventStatus LcmC3TargetDrawer::DrawC3State( meshcat_->SetTransform( c3_target_ee_path_, RigidTransformd(Vector3d{c3_target->state[0], c3_target->state[1], - c3_target->state[2]}), context.get_time()); + c3_target->state[2]})); meshcat_->SetTransform( c3_actual_ee_path_, RigidTransformd(Vector3d{c3_actual->state[0], c3_actual->state[1], - c3_actual->state[2]}), context.get_time()); + c3_actual->state[2]})); } return drake::systems::EventStatus::Succeeded(); } diff --git a/systems/visualization/lcm_visualization_systems.h b/systems/visualization/lcm_visualization_systems.h index aca1c8642e..0d9773581d 100644 --- a/systems/visualization/lcm_visualization_systems.h +++ b/systems/visualization/lcm_visualization_systems.h @@ -23,13 +23,15 @@ namespace systems { class LcmTrajectoryDrawer : public drake::systems::LeafSystem { public: explicit LcmTrajectoryDrawer(const std::shared_ptr&, - std::string trajectory_name); + std::string trajectory_name, + const std::string& system_name = ""); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_input_port_); } void SetLineColor(drake::geometry::Rgba rgba) { rgba_ = rgba; } + void SetLineWidth(double line_width) { line_width_ = line_width; } void SetNumSamples(int N) { DRAKE_DEMAND(N > 1); @@ -46,8 +48,10 @@ class LcmTrajectoryDrawer : public drake::systems::LeafSystem { drake::systems::InputPortIndex trajectory_input_port_; std::shared_ptr meshcat_; + const std::string system_name_; const std::string trajectory_name_; drake::geometry::Rgba rgba_ = drake::geometry::Rgba(0.1, 0.1, 0.1, 1.0); + double line_width_ = 100; int N_ = 5; }; @@ -59,8 +63,10 @@ class LcmPoseDrawer : public drake::systems::LeafSystem { const std::string& model_file, const std::string& translation_trajectory_name, const std::string& orientation_trajectory_name, + const std::string& system_name = "", int num_poses = 5, - bool add_transparency = true); + bool add_transparency = true, + const Eigen::VectorXd& rgb = Eigen::VectorXd()); const drake::systems::InputPort& get_input_port_trajectory() const { return this->get_input_port(trajectory_input_port_); @@ -89,7 +95,8 @@ class LcmForceDrawer : public drake::systems::LeafSystem { explicit LcmForceDrawer(const std::shared_ptr&, std::string force_trajectory_name, std::string actor_trajectory_name, - std::string lcs_force_trajectory_name); + std::string lcs_force_trajectory_name, + const std::string& system_name = ""); const drake::systems::InputPort& get_input_port_actor_trajectory() const { @@ -141,6 +148,11 @@ class LcmC3TargetDrawer : public drake::systems::LeafSystem { explicit LcmC3TargetDrawer(const std::shared_ptr&, bool draw_tray = true, bool draw_ee = false); + const drake::systems::InputPort& get_input_port_c3_state_final_target() + const { + return this->get_input_port(c3_state_final_target_input_port_); + } + const drake::systems::InputPort& get_input_port_c3_state_target() const { return this->get_input_port(c3_state_target_input_port_); @@ -158,6 +170,7 @@ class LcmC3TargetDrawer : public drake::systems::LeafSystem { std::shared_ptr meshcat_; + drake::systems::InputPortIndex c3_state_final_target_input_port_; drake::systems::InputPortIndex c3_state_target_input_port_; drake::systems::InputPortIndex c3_state_actual_input_port_; @@ -171,6 +184,7 @@ class LcmC3TargetDrawer : public drake::systems::LeafSystem { const drake::geometry::Cylinder cylinder_for_ee_ = drake::geometry::Cylinder(0.0025, 0.05); const std::string c3_state_path_ = "c3_state"; + const std::string c3_final_target_object_path_ = "c3_state/c3_final_target_object"; const std::string c3_target_object_path_ = "c3_state/c3_target_object"; const std::string c3_actual_object_path_ = "c3_state/c3_actual_object"; const std::string c3_target_ee_path_ = "c3_state/c3_target_ee"; From 3f50df082404316371f46995e2119584f2158f1c Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Sat, 28 Jun 2025 14:39:59 -0400 Subject: [PATCH 746/758] Update Drake version to 1.39 (#378) - Removes WORKSPACE file and replaces with Bazel Modules - Removes support for ROS (currently unused by the lab). The previous ROS integration was dated, and should be replaced with the latest examples from drake-ros when ready - Bug fixes exposed by upstream updates, and compatibility changes - Fixes and updates CI, but Ubuntu jammy only for now - Updates install script --- .bazeliskrc | 2 +- .bazelrc | 2 +- .cirrus.yml | 88 ++------ .gitignore | 1 + BUILD.bazel | 11 - MODULE.bazel | 122 +++++++++++ WORKSPACE | 191 +----------------- examples/Cassie/BUILD.bazel | 18 +- examples/Cassie/cassie_state_estimator.cc | 2 +- .../Cassie/diagrams/cassie_sim_diagram.cc | 6 +- examples/Cassie/find_fixed_point.cc | 1 + examples/Cassie/multibody_sim.cc | 10 +- .../Cassie/multibody_sim_w_ground_incline.cc | 2 +- examples/Cassie/multibody_sim_w_platform.cc | 10 +- .../systems/sim_cassie_sensor_aggregator.h | 4 +- examples/Cassie/test/input_supervisor_test.cc | 96 --------- examples/franka/BUILD.bazel | 2 +- .../five_link_biped_sim.cc | 2 +- install/bionic/Dockerfile | 18 -- install/bionic/ros/Dockerfile | 19 -- install/focal/Dockerfile | 18 -- install/focal/ros/Dockerfile | 20 -- install/install_prereqs_bionic.sh | 37 ---- install/install_prereqs_focal.sh | 37 ---- install/install_prereqs_jammy.sh | 39 ---- install/install_prereqs_mac.sh | 32 --- install/install_prereqs_ubuntu.sh | 21 ++ install/jammy/Dockerfile | 19 -- lcm/test/lcm_trajectory_test.cc | 2 +- lcmtypes/BUILD.bazel | 24 +-- multibody/BUILD.bazel | 2 +- .../kinematic/kinematic_evaluator_set.cc | 1 + solvers/c3_qp.h | 1 - .../controllers/safe_velocity_controller.cc | 2 + tools/workspace/gurobi/BUILD.bazel | 13 ++ .../gurobi/package-darwin.BUILD.bazel.in | 55 +++++ .../gurobi/package-linux.BUILD.bazel.in | 82 ++++++++ tools/workspace/gurobi/repository.bzl | 89 ++++++++ tools/workspace/ros/.gitignore | 1 - tools/workspace/ros/BUILD.bazel | 30 --- tools/workspace/ros/LICENSE_ros-bazel | 24 --- tools/workspace/ros/bazel/BUILD | 0 tools/workspace/ros/bazel/genmsg.BUILD | 7 - tools/workspace/ros/bazel/genpy.BUILD | 18 -- .../ros/bazel/message_generation.bzl | 134 ------------ tools/workspace/ros/bazel/path_utils.bzl | 39 ---- tools/workspace/ros/bazel/pypi.bzl | 54 ----- tools/workspace/ros/compile_ros_workspace.sh | 58 ------ tools/workspace/ros/ros.bazel | 18 -- tools/workspace/ros/test/genmsg_test.py | 12 -- tools/workspace/ros/test/main.cpp | 33 --- tools/workspace/ros/test/main_python.py | 24 --- tools/workspace/ros/test/test_msgs/BUILD | 16 -- .../ros/test/test_msgs/msg/Message1.msg | 1 - .../ros/test/test_msgs/msg/Message2.msg | 2 - .../ros/test/test_msgs/scripts/main.py | 18 -- 56 files changed, 441 insertions(+), 1149 deletions(-) create mode 100644 MODULE.bazel delete mode 100644 examples/Cassie/test/input_supervisor_test.cc delete mode 100644 install/bionic/Dockerfile delete mode 100644 install/bionic/ros/Dockerfile delete mode 100644 install/focal/Dockerfile delete mode 100644 install/focal/ros/Dockerfile delete mode 100755 install/install_prereqs_bionic.sh delete mode 100755 install/install_prereqs_focal.sh delete mode 100755 install/install_prereqs_jammy.sh delete mode 100755 install/install_prereqs_mac.sh create mode 100755 install/install_prereqs_ubuntu.sh delete mode 100644 install/jammy/Dockerfile create mode 100644 tools/workspace/gurobi/BUILD.bazel create mode 100644 tools/workspace/gurobi/package-darwin.BUILD.bazel.in create mode 100644 tools/workspace/gurobi/package-linux.BUILD.bazel.in create mode 100644 tools/workspace/gurobi/repository.bzl delete mode 100644 tools/workspace/ros/.gitignore delete mode 100644 tools/workspace/ros/BUILD.bazel delete mode 100644 tools/workspace/ros/LICENSE_ros-bazel delete mode 100644 tools/workspace/ros/bazel/BUILD delete mode 100644 tools/workspace/ros/bazel/genmsg.BUILD delete mode 100644 tools/workspace/ros/bazel/genpy.BUILD delete mode 100644 tools/workspace/ros/bazel/message_generation.bzl delete mode 100644 tools/workspace/ros/bazel/path_utils.bzl delete mode 100644 tools/workspace/ros/bazel/pypi.bzl delete mode 100755 tools/workspace/ros/compile_ros_workspace.sh delete mode 100644 tools/workspace/ros/ros.bazel delete mode 100644 tools/workspace/ros/test/genmsg_test.py delete mode 100644 tools/workspace/ros/test/main.cpp delete mode 100644 tools/workspace/ros/test/main_python.py delete mode 100644 tools/workspace/ros/test/test_msgs/BUILD delete mode 100644 tools/workspace/ros/test/test_msgs/msg/Message1.msg delete mode 100644 tools/workspace/ros/test/test_msgs/msg/Message2.msg delete mode 100644 tools/workspace/ros/test/test_msgs/scripts/main.py diff --git a/.bazeliskrc b/.bazeliskrc index dbaa31a83e..6db7b5ce5e 100644 --- a/.bazeliskrc +++ b/.bazeliskrc @@ -3,4 +3,4 @@ # # These files should also be updated: # drake/tools/workspace/drake_visualizer/image/provision.sh -USE_BAZEL_VERSION=7.1.1 \ No newline at end of file +USE_BAZEL_VERSION=8.2.1 \ No newline at end of file diff --git a/.bazelrc b/.bazelrc index 667f4b0694..21f2cb1abd 100644 --- a/.bazelrc +++ b/.bazelrc @@ -62,4 +62,4 @@ build:omp --linkopt=-fopenmp # use python3 by default build --python_path=python3 -common --noenable_bzlmod \ No newline at end of file +common --enable_bzlmod \ No newline at end of file diff --git a/.cirrus.yml b/.cirrus.yml index 0e75243699..114b80109c 100644 --- a/.cirrus.yml +++ b/.cirrus.yml @@ -1,91 +1,39 @@ +registry_config: ENCRYPTED[!0a87ac67e240c5bb89044f49c6437615cec7c22faa151949f0648b04911a9e30785a97d897d8796745cb9f72a18732ec!] build_jammy_task: timeout_in: 120m container: - dockerfile: install/jammy/Dockerfile + image: docker.io/michaelposa/jammy-dair-base:latest cpu: 8 - memory: 24 + memory: 24G test_script: - - export CC=clang-12 - - export CXX=clang++-12 - bazel build - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 + --local_resources=memory=24000 + --local_resources=cpu=8 --jobs=8 + --remote_http_cache=http://$CIRRUS_HTTP_CACHE_HOST //... - bazel test - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - //... -build_focal_task: - timeout_in: 120m - container: - dockerfile: install/focal/Dockerfile - cpu: 8 - memory: 24 - test_script: - - export CC=clang-12 - - export CXX=clang++-12 - - bazel build - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - --jobs=8 - //... - - bazel test - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - //... -build_with_ros_task: - timeout_in: 120m - container: - dockerfile: install/focal/ros/Dockerfile - cpu: 8 - memory: 24 - env: - DAIRLIB_WITH_ROS: ON - test_script: - - cd tools/workspace/ros - - ./compile_ros_workspace.sh - - cd ../../../ - - bazel build - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - --jobs=8 - //... - - bazel test - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - --jobs=8 + --local_resources=memory=24000 + --local_resources=cpu=8 + --remote_http_cache=http://$CIRRUS_HTTP_CACHE_HOST //... + drake_master_build_task: timeout_in: 120m container: - dockerfile: install/focal/ros/Dockerfile + image: docker.io/michaelposa/jammy-dair-base cpu: 8 - memory: 24 + memory: 24G allow_failures: true - env: - DAIRLIB_WITH_ROS: ON test_script: - git clone https://github.com/RobotLocomotion/drake.git ../drake - - export DAIRLIB_LOCAL_DRAKE_PATH=$PWD/../drake - - cd tools/workspace/ros - - ./compile_ros_workspace.sh - - cd ../../../ - bazel build - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - --jobs=8 + --override_module=drake=$PWD/../drake + --local_resources=memory=24000 + --local_resources=cpu=8 //... - bazel test - --define=WITH_SNOPT=OFF - --local_ram_resources=24000 - --local_cpu_resources=8 - --jobs=8 + --override_module=drake=$PWD/../drake + --local_resources=memory=24000 + --local_resources=cpu=8 //... diff --git a/.gitignore b/.gitignore index a9f31f7fdd..7d25deb06a 100644 --- a/.gitignore +++ b/.gitignore @@ -11,3 +11,4 @@ attic/multibody/solver_log/ .vscode *.csv /examples/Cassie/saved_trajectories/ +/MODULE.bazel.lock diff --git a/BUILD.bazel b/BUILD.bazel index 1841fa978c..f24256eb35 100644 --- a/BUILD.bazel +++ b/BUILD.bazel @@ -32,14 +32,3 @@ # This is an empty BUILD file, to ensure that the project's root directory is a # bazel package. - -load("@com_github_bazelbuild_buildtools//buildifier:def.bzl", "buildifier") - -buildifier( - name = "buildifier", -) - -load("@bazel_gazelle//:def.bzl", "gazelle") - -# gazelle:prefix github.com/example/project -gazelle(name = "gazelle") diff --git a/MODULE.bazel b/MODULE.bazel new file mode 100644 index 0000000000..da6a473a36 --- /dev/null +++ b/MODULE.bazel @@ -0,0 +1,122 @@ +## MODULE.bazel +module( + name = "dairlib" +) + +drake_dep_repositories = use_extension( + "@drake//tools/workspace:default.bzl", + "drake_dep_repositories", +) + +# If you don't want to support building on macOS, you may remove the next line. +# Note that it must appear prior to loading "rules_cc", per the documentation: +# https://github.com/bazelbuild/apple_support?tab=readme-ov-file#bazel-7-setup +bazel_dep(name = "apple_support", version = "1.17.1") + +# Add the Bazel rules we need. +bazel_dep(name = "rules_cc", version = "0.1.1") +bazel_dep(name = "rules_python", version = "1.0.0") +bazel_dep(name = "bazel_skylib", version = "1.7.1") + +use_repo( + drake_dep_repositories, + "blas", + "buildifier", + "drake_models", + "eigen", + "fmt", + "gflags", + "glib", + "gtest", + "lapack", + "lcm", + "meshcat", + "mosek", + "opencl", + "pybind11", + "pycodestyle", + "snopt", + "spdlog", + "styleguide", + "x11", + "zlib", + "gurobi", +) + +bazel_dep(name = "gazelle", version = "0.44.0") + +bazel_dep(name = "osqp", version = "0.6.3.bcr.2") + +# Use gurobi_cxx, which Drake deprecated +gurobi_extension = use_extension("@dairlib//tools/workspace/gurobi:repository.bzl", "gurobi_extension") +use_repo(gurobi_extension, "my_gurobi") + +# Replace Drake's Gurobi repository with ours. +override_repo( + drake_dep_repositories, + gurobi = "my_gurobi", +) + +# Here we introduce Drake as a module dependency, but note that Drake is not +# published to any Bazel registry. Below, we'll override it with a github +# source archive. +bazel_dep(name = "drake") + +bazel_dep(name = "inekf") + +# By default, this example always uses the latest Drake master branch. + +# To use a local version of drake, use +# build --override_module=drake=/home/user/stuff/drake +# this will also work to override inekf + +# You can also use DRAKE_COMMIT to choose a Drake release; e.g.: +DRAKE_VERSION = "v1.39.0" +DRAKE_CHECKSUM = "63eb9455181ce9aeb9746e60531fbd4fbe731ea44539276e662e1236a78589b6" + +# Before changing the DRAKE_VERSION, temporarily uncomment the next line so that Bazel +# displays the suggested new value for the CHECKSUM. +# DRAKE_CHECKSUM = "0" * 64 + +# This declares the `@drake` module as a source code archive from github. +# See README.md for instructions to use a local path, instead. +archive_override( + module_name = "drake", + urls = [x.format(DRAKE_VERSION) for x in [ + "https://github.com/RobotLocomotion/drake/archive/{}.tar.gz", + ]], + sha256 = DRAKE_CHECKSUM, + strip_prefix = "drake-{}".format(DRAKE_VERSION.lstrip("v")), +) + +INEKF_COMMIT = "297c308e50fa599af92ce3bd5f11d71e2bf8af69" +INEKF_CHECKSUM = "c5a056ce00e1625e52f5a71b1d5c202acd53c1a8c7bca33da458db1e4f3f2edf" + + +# Before changing the COMMIT, temporarily uncomment the next line so that Bazel +# displays the suggested new value for the CHECKSUM. +#INEKF_CHECKSUM = "0" * 64 + +# This declares the `@inekf` module as a source code archive from github. +archive_override( + module_name = "inekf", + urls = [x.format(INEKF_COMMIT) for x in [ + "https://github.com/DAIRLab/invariant-ekf/archive/{}.tar.gz", + ]], + sha256 = INEKF_CHECKSUM, + strip_prefix = "invariant-ekf-{}".format(INEKF_COMMIT), +) + +# Use the host system /usr/bin/python3. +python_repository = use_repo_rule( + "@drake//tools/workspace/python:repository.bzl", + "python_repository", +) + +python_repository( + name = "python", + linux_interpreter_path = "/usr/bin/python3", + requirements_flavor = "build", +) + +register_toolchains("@python//:all") \ No newline at end of file diff --git a/WORKSPACE b/WORKSPACE index 8af20fdf7a..edd72bf514 100644 --- a/WORKSPACE +++ b/WORKSPACE @@ -1,189 +1,2 @@ -# -*- mode: python -*- -# vi: set ft=python : - -workspace(name = "dairlib") - -# dairlib can use either a local version of drake or a pegged revision -# If the environment variable DAIRLIB_LOCAL_DRAKE_PATH is set, it will use -# a local version, ad the specified path. Otherwise, it will get a pegged -# revision from github. -# As an example, -# export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/workspace/drake - -# Choose a revision of Drake to use. -DRAKE_COMMIT = "v1.33.0" - -DRAKE_CHECKSUM = "2713ad1ea53ed7b9cfe1ba751eeeab7dc173408753ead21b7bafb0436b92dcf3" -# Before changing the COMMIT, temporarily uncomment the next line so that Bazel -# displays the suggested new value for the CHECKSUM. -#DRAKE_CHECKSUM = "0" * 64 - -# Load an environment variable. -load("//:environ.bzl", "drake_repository", "inekf_repository") - -drake_repository(name = "drake_path") - -inekf_repository(name = "inekf_path") - -load("@drake_path//:environ.bzl", "DAIRLIB_LOCAL_DRAKE_PATH") -load("@inekf_path//:environ.bzl", "DAIRLIB_LOCAL_INEKF_PATH") - -# The WORKSPACE file does not permit `if` statements, so we handle the local -# option by toying with the repository names. The selected repository is named -# "@drake", the other is named "@drake_ignored". -(_http_drake_repo_name, _local_drake_repo_name) = ( - "drake_ignored" if DAIRLIB_LOCAL_DRAKE_PATH else "drake", - "drake" if DAIRLIB_LOCAL_DRAKE_PATH else "drake_ignored", -) - -# Maybe download Drake. -load("@bazel_tools//tools/build_defs/repo:http.bzl", "http_archive") - -http_archive( - name = _http_drake_repo_name, - sha256 = DRAKE_CHECKSUM, - strip_prefix = "drake-{}".format(DRAKE_COMMIT.strip("v")), - urls = [x.format(DRAKE_COMMIT) for x in [ - "https://github.com/RobotLocomotion/drake/archive/{}.tar.gz", - ]], -) - -# Maybe use a local checkout of Drake. -print("Using DAIRLIB_LOCAL_DRAKE_PATH={}".format(DAIRLIB_LOCAL_DRAKE_PATH)) if DAIRLIB_LOCAL_DRAKE_PATH else None # noqa - -local_repository( - name = _local_drake_repo_name, - path = DAIRLIB_LOCAL_DRAKE_PATH, -) - -# Reference external software libraries and tools per Drake's defaults. Some -# software will come from the host system (Ubuntu or macOS); other software -# will be downloaded in source or binary form from github or other sites. -load("@drake//tools/workspace:default.bzl", "add_default_workspace") - -add_default_workspace() - -load("@dairlib//tools/workspace/osqp:repository.bzl", "osqp_repository") - -osqp_repository(name = "osqp") - -# Prebuilt ROS workspace -new_local_repository( - name = "ros", - build_file = "tools/workspace/ros/ros.bazel", - path = "tools/workspace/ros/bundle_ws/install", -) - -# Other catkin packages from source -# TODO: generate this automatically from rosinstall_generator - -http_archive( - name = "genmsg_repo", - build_file = "@//tools/workspace/ros/bazel:genmsg.BUILD", - sha256 = "d7627a2df169e4e8208347d9215e47c723a015b67ef3ed8cda8b61b6cfbf94d2", - strip_prefix = "genmsg-0.5.8", - urls = ["https://github.com/ros/genmsg/archive/0.5.8.tar.gz"], -) - -http_archive( - name = "genpy_repo", - build_file = "@//tools/workspace/ros/bazel:genpy.BUILD", - sha256 = "35e5cd2032f52a1f77190df5c31c02134dc460bfeda3f28b5a860a95309342b9", - strip_prefix = "genpy-0.6.5", - urls = ["https://github.com/ros/genpy/archive/0.6.5.tar.gz"], -) - -# dairlib can use either a local version of invariant-ekf or a pegged revision -# If the environment variable DAIRLIB_LOCAL_INEKF_PATH is set, it will use -# a local version, ad the specified path. Otherwise, it will get a pegged -# revision from github. -# As an example, -# export DAIRLIB_LOCAL_INEKF_PATH=/home/user/workspace/invariant-ekf - -# Choose a revision of InEKF to use. -INEKF_COMMIT = "7fde9f84dbe536ba9439a3b8c319efb51ff760dd" - -INEKF_CHECKSUM = "f87e3262b0c9c9237881fcd539acd1c60000f97dfdfa47b0ae53cb7a0f3256e4" - -# Before changing the COMMIT, temporarily uncomment the next line so that Bazel -# displays the suggested new value for the CHECKSUM. -# INEKF_CHECKSUM = "0" * 64 - -# The WORKSPACE file does not permit `if` statements, so we handle the local -# option by toying with the repository names. The selected repository is named -# "@inekf", the other is named "@inekf_ignored". -(_http_inekf_repo_name, _local_inekf_repo_name) = ( - "inekf_ignored" if DAIRLIB_LOCAL_INEKF_PATH else "inekf", - "inekf" if DAIRLIB_LOCAL_INEKF_PATH else "inekf_ignored", -) - -http_archive( - name = _http_inekf_repo_name, - sha256 = INEKF_CHECKSUM, - strip_prefix = "invariant-ekf-{}".format(INEKF_COMMIT), - urls = [x.format(INEKF_COMMIT) for x in [ - "https://github.com/DAIRLab/invariant-ekf/archive/{}.tar.gz", - ]], -) - -# Maybe use a local checkout of InEKF. -print("Using DAIRLIB_LOCAL_INEKF_PATH={}".format(DAIRLIB_LOCAL_INEKF_PATH)) if DAIRLIB_LOCAL_INEKF_PATH else None # noqa - -local_repository( - name = _local_inekf_repo_name, - path = DAIRLIB_LOCAL_INEKF_PATH, -) - -# buildifier is written in Go and hence needs rules_go to be built. -# See https://github.com/bazelbuild/rules_go for the up to date setup instructions. -http_archive( - name = "io_bazel_rules_go", - sha256 = "d6b2513456fe2229811da7eb67a444be7785f5323c6708b38d851d2b51e54d83", - urls = [ - "https://mirror.bazel.build/github.com/bazelbuild/rules_go/releases/download/v0.30.0/rules_go-v0.30.0.zip", - "https://github.com/bazelbuild/rules_go/releases/download/v0.30.0/rules_go-v0.30.0.zip", - ], -) - -load("@io_bazel_rules_go//go:deps.bzl", "go_register_toolchains", "go_rules_dependencies") - -go_rules_dependencies() - -go_register_toolchains(version = "1.17.2") - -http_archive( - name = "bazel_gazelle", - sha256 = "de69a09dc70417580aabf20a28619bb3ef60d038470c7cf8442fafcf627c21cb", - urls = [ - "https://mirror.bazel.build/github.com/bazelbuild/bazel-gazelle/releases/download/v0.24.0/bazel-gazelle-v0.24.0.tar.gz", - "https://github.com/bazelbuild/bazel-gazelle/releases/download/v0.24.0/bazel-gazelle-v0.24.0.tar.gz", - ], -) - -load("@bazel_gazelle//:deps.bzl", "gazelle_dependencies") - -# If you use WORKSPACE.bazel, use the following line instead of the bare gazelle_dependencies(): -# gazelle_dependencies(go_repository_default_config = "@//:WORKSPACE.bazel") -gazelle_dependencies() - -http_archive( - name = "com_google_protobuf", - sha256 = "3bd7828aa5af4b13b99c191e8b1e884ebfa9ad371b0ce264605d347f135d2568", - strip_prefix = "protobuf-3.19.4", - urls = [ - "https://github.com/protocolbuffers/protobuf/archive/v3.19.4.tar.gz", - ], -) - -load("@com_google_protobuf//:protobuf_deps.bzl", "protobuf_deps") - -protobuf_deps() - -http_archive( - name = "com_github_bazelbuild_buildtools", - sha256 = "ae34c344514e08c23e90da0e2d6cb700fcd28e80c02e23e4d5715dddcb42f7b3", - strip_prefix = "buildtools-4.2.2", - urls = [ - "https://github.com/bazelbuild/buildtools/archive/refs/tags/4.2.2.tar.gz", - ], -) +# This file marks the root of the Bazel workspace. +# See MODULE.bazel for external dependencies setup. \ No newline at end of file diff --git a/examples/Cassie/BUILD.bazel b/examples/Cassie/BUILD.bazel index a32c0ff340..8ddcdceccf 100644 --- a/examples/Cassie/BUILD.bazel +++ b/examples/Cassie/BUILD.bazel @@ -95,20 +95,6 @@ cc_binary( ], ) -cc_test( - name = "input_supervisor_test", - size = "small", - srcs = ["test/input_supervisor_test.cc"], - deps = [ - "//examples/Cassie:cassie_urdf", - "//examples/Cassie:cassie_utils", - "//examples/Cassie/systems:input_supervisor", - "//systems/primitives", - "@drake//:drake_shared_library", - "@gtest//:main", - ], -) - cc_library( name = "cassie_fixed_point_solver", srcs = ["cassie_fixed_point_solver.cc"], @@ -458,7 +444,7 @@ cc_binary( cc_binary( name = "run_dircon_squatting", srcs = ["run_dircon_squatting.cc"], - data = glob(["examples/Cassie/urdf/cassie_fixed_springs.urdf"]), + data = glob(["urdf/cassie_fixed_springs.urdf"]), deps = [ ":cassie_fixed_point_solver", ":cassie_utils", @@ -497,7 +483,7 @@ cc_binary( cc_binary( name = "run_dircon_walking", srcs = ["run_dircon_walking.cc"], - data = glob(["examples/Cassie/urdf/cassie_fixed_springs.urdf"]), + data = glob(["urdf/cassie_fixed_springs.urdf"]), deps = [ ":cassie_utils", "//common", diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index ee73c24cd1..df3f68ae1e 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -983,7 +983,7 @@ void CassieStateEstimator::CopyEstimatedContactForces( contact_info.timestamp = contact_msg->timestamp; contact_info.body1_name = toe_frames_[i]->body().name(); contact_info.body2_name = world_.name(); - memcpy(contact_info.contact_force, + memcpy(contact_info.contact_force.data(), context.get_discrete_state(contact_forces_idx_) .get_value() .segment(i * SPACE_DIM, (i + 1) * SPACE_DIM) diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index d6979ac5cb..8c1b77e744 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -50,8 +50,8 @@ CassieSimDiagram::CassieSimDiagram( scene_graph_->set_name("scene_graph"); plant_ = builder.AddSystem(std::move(plant)); - plant_->set_discrete_contact_solver( - drake::multibody::DiscreteContactSolver::kSap); + plant_->set_discrete_contact_approximation( + drake::multibody::DiscreteContactApproximation::kSap); AddCassieMultibody(plant_, scene_graph_, true, urdf, true, true); multibody::AddFlatTerrain(plant_, scene_graph_, mu, mu, Eigen::Vector3d(0, 0, 1)); @@ -98,7 +98,7 @@ CassieSimDiagram::CassieSimDiagram( builder.Connect(cassie_motor_->get_output_port(), state_sender->get_input_port_effort()); builder.Connect( - plant_->get_geometry_poses_output_port(), + plant_->get_geometry_pose_output_port(), scene_graph_->get_source_pose_port(plant_->get_source_id().value())); builder.Connect(scene_graph_->get_query_output_port(), plant_->get_geometry_query_input_port()); diff --git a/examples/Cassie/find_fixed_point.cc b/examples/Cassie/find_fixed_point.cc index cd8da78398..d39a68fade 100644 --- a/examples/Cassie/find_fixed_point.cc +++ b/examples/Cassie/find_fixed_point.cc @@ -3,6 +3,7 @@ #include #include "examples/Cassie/cassie_fixed_point_solver.h" +#include "drake/common/text_logging.h" DEFINE_double(height, 1, "Fixed height,"); DEFINE_double(toe_spread, .2, "Fixed height,"); diff --git a/examples/Cassie/multibody_sim.cc b/examples/Cassie/multibody_sim.cc index 20655bd483..3973c3f0ed 100644 --- a/examples/Cassie/multibody_sim.cc +++ b/examples/Cassie/multibody_sim.cc @@ -93,11 +93,11 @@ DEFINE_string(contact_solver, "SAP", } if (FLAGS_contact_solver == "SAP") { - plant.set_discrete_contact_solver( - drake::multibody::DiscreteContactSolver::kSap); + plant.set_discrete_contact_approximation( + drake::multibody::DiscreteContactApproximation::kSap); } else if (FLAGS_contact_solver == "TAMSI") { - plant.set_discrete_contact_solver( - drake::multibody::DiscreteContactSolver::kTamsi); + plant.set_discrete_contact_approximation( + drake::multibody::DiscreteContactApproximation::kTamsi); } else { std::cerr << "Unknown contact solver setting." << std::endl; } @@ -165,7 +165,7 @@ DEFINE_string(contact_solver, "SAP", state_sender->get_input_port_effort()); builder.Connect(*state_sender, *state_pub); builder.Connect( - plant.get_geometry_poses_output_port(), + plant.get_geometry_pose_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(scene_graph.get_query_output_port(), plant.get_geometry_query_input_port()); diff --git a/examples/Cassie/multibody_sim_w_ground_incline.cc b/examples/Cassie/multibody_sim_w_ground_incline.cc index 83515db89e..6db823cc7e 100644 --- a/examples/Cassie/multibody_sim_w_ground_incline.cc +++ b/examples/Cassie/multibody_sim_w_ground_incline.cc @@ -223,7 +223,7 @@ int do_main(int argc, char* argv[]) { state_sender->get_input_port_effort()); builder.Connect(*state_sender, *state_pub); builder.Connect( - plant.get_geometry_poses_output_port(), + plant.get_geometry_pose_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(scene_graph.get_query_output_port(), plant.get_geometry_query_input_port()); diff --git a/examples/Cassie/multibody_sim_w_platform.cc b/examples/Cassie/multibody_sim_w_platform.cc index 33d3dbfbcb..3c105721b7 100644 --- a/examples/Cassie/multibody_sim_w_platform.cc +++ b/examples/Cassie/multibody_sim_w_platform.cc @@ -97,11 +97,11 @@ int do_main(int argc, char* argv[]) { : "examples/Cassie/urdf/cassie_fixed_springs.urdf"; if (FLAGS_contact_solver == "SAP") { - plant.set_discrete_contact_solver( - drake::multibody::DiscreteContactSolver::kSap); + plant.set_discrete_contact_approximation( + drake::multibody::DiscreteContactApproximation::kSap); } else if (FLAGS_contact_solver == "TAMSI") { - plant.set_discrete_contact_solver( - drake::multibody::DiscreteContactSolver::kTamsi); + plant.set_discrete_contact_approximation( + drake::multibody::DiscreteContactApproximation::kTamsi); } else { std::cerr << "Unknown contact solver setting." << std::endl; } @@ -177,7 +177,7 @@ int do_main(int argc, char* argv[]) { state_sender->get_input_port_effort()); builder.Connect(*state_sender, *state_pub); builder.Connect( - plant.get_geometry_poses_output_port(), + plant.get_geometry_pose_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(scene_graph.get_query_output_port(), plant.get_geometry_query_input_port()); diff --git a/examples/Cassie/systems/sim_cassie_sensor_aggregator.h b/examples/Cassie/systems/sim_cassie_sensor_aggregator.h index f9eee8088c..74062fca25 100644 --- a/examples/Cassie/systems/sim_cassie_sensor_aggregator.h +++ b/examples/Cassie/systems/sim_cassie_sensor_aggregator.h @@ -14,8 +14,8 @@ #include "systems/framework/output_vector.h" #include "systems/framework/timestamped_vector.h" -#include "external/drake/tools/install/libdrake/_virtual_includes/drake_shared_library/drake/multibody/plant/multibody_plant.h" -#include "external/drake/tools/install/libdrake/_virtual_includes/drake_shared_library/drake/systems/framework/leaf_system.h" +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/systems/framework/leaf_system.h" namespace dairlib { namespace systems { diff --git a/examples/Cassie/test/input_supervisor_test.cc b/examples/Cassie/test/input_supervisor_test.cc deleted file mode 100644 index 9ab126230c..0000000000 --- a/examples/Cassie/test/input_supervisor_test.cc +++ /dev/null @@ -1,96 +0,0 @@ -#include "examples/Cassie/systems/input_supervisor.h" - -#include -#include -#include - -#include "dairlib/lcmt_controller_switch.hpp" -#include "examples/Cassie/cassie_utils.h" - -#include "drake/multibody/plant/multibody_plant.h" - -namespace dairlib { -namespace systems { - -using Eigen::VectorXd; - -class InputSupervisorTest : public ::testing::Test { - protected: - InputSupervisorTest() - : plant_(drake::multibody::MultibodyPlant(0.0)) { - AddCassieMultibody(&plant_, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2.urdf", - true /*spring model*/, false /*loop closure*/); - plant_.Finalize(); - VectorXd input_limit = 20.0 * VectorXd::Ones(10); - supervisor_ = std::make_unique( - plant_, "DEFAULT_CONTROL_CHANNEL", 10.0, 0.01, input_limit, min_consecutive_failures); - context_ = supervisor_->CreateDefaultContext(); - status_output_ = std::make_unique(); - cassie_out_ = std::make_unique(); - command_input_ = - std::make_unique>(plant_.num_actuators()); - state_input_ = std::make_unique>( - plant_.num_positions(), plant_.num_velocities(), - plant_.num_actuators()); - output_ = supervisor_->AllocateOutput(); - state_input_port_ = supervisor_->get_input_port_state().get_index(); - } - - int state_input_port_; - drake::multibody::MultibodyPlant plant_; - const int min_consecutive_failures = 5; - std::unique_ptr> output_; - std::unique_ptr supervisor_; - std::unique_ptr status_output_; - std::unique_ptr cassie_out_; - // std::unique_ptr> motor_output_; - std::unique_ptr> command_input_; - std::unique_ptr> state_input_; - std::unique_ptr> context_; -}; - -TEST_F(InputSupervisorTest, BlendEffortsTest) { - VectorXd prev_input = VectorXd::Zero(plant_.num_actuators()); - VectorXd desired_input = 10 * VectorXd::Ones(plant_.num_actuators()); - double blend_start_time = 0.5; - double timestamp = 1.0; - double blend_duration = 1.0; - std::unique_ptr> switch_msg = - std::make_unique>(); - std::unique_ptr> controller_failure = - std::make_unique>(); - cassie_out_->pelvis.radio.channel[15] = 0; - switch_msg->get_mutable_value().blend_duration = blend_duration; - switch_msg->get_mutable_value().utime = blend_start_time * 1e6; - command_input_->get_mutable_value() = desired_input; - command_input_->set_timestamp(timestamp); - supervisor_->get_input_port_state().FixValue(context_.get(), *state_input_); - supervisor_->get_input_port_cassie().FixValue(context_.get(), *cassie_out_); - supervisor_->get_input_port_safety_controller().FixValue(context_.get(), - *command_input_); - supervisor_->get_input_port_controller_switch().FixValue( - context_.get(), (drake::AbstractValue&)*switch_msg); - supervisor_->get_input_port_controller_error().FixValue( - context_.get(), (drake::AbstractValue&)*controller_failure); - supervisor_->get_input_port_command().FixValue(context_.get(), - *command_input_); - - supervisor_->CalcOutput(*context_, output_.get()); - const TimestampedVector* motor_output = - dynamic_cast*>( - output_->get_vector_data(0)); - - VectorXd output_from_supervisor = motor_output->get_data(); - double alpha = (timestamp - blend_start_time) / blend_duration; - - EXPECT_EQ(output_from_supervisor, alpha * desired_input); -} - -} // namespace systems -} // namespace dairlib - -int main(int argc, char** argv) { - ::testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); -} diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index 6cd679cb5c..dd4655ae72 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -277,7 +277,7 @@ cc_library( "parameters/franka_sim_scene_params.h", ], data = glob([ - "*yaml", + "parameters/*.yaml", ]), deps = [ "@drake//:drake_shared_library", diff --git a/examples/impact_invariant_control/five_link_biped_sim.cc b/examples/impact_invariant_control/five_link_biped_sim.cc index e91ddb5c49..722312dff1 100644 --- a/examples/impact_invariant_control/five_link_biped_sim.cc +++ b/examples/impact_invariant_control/five_link_biped_sim.cc @@ -135,7 +135,7 @@ int do_main(int argc, char* argv[]) { builder.Connect(state_sender->get_output_port(0), state_pub->get_input_port()); builder.Connect( - plant.get_geometry_poses_output_port(), + plant.get_geometry_pose_output_port(), scene_graph.get_source_pose_port(plant.get_source_id().value())); builder.Connect(scene_graph.get_query_output_port(), plant.get_geometry_query_input_port()); diff --git a/install/bionic/Dockerfile b/install/bionic/Dockerfile deleted file mode 100644 index 63ff911d81..0000000000 --- a/install/bionic/Dockerfile +++ /dev/null @@ -1,18 +0,0 @@ -FROM ros:melodic-ros-base-bionic -WORKDIR /dairlib -ENV DAIRLIB_DOCKER_VERSION_25=25 -COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python -RUN set -eux \ - && apt-get install --no-install-recommends locales \ - && locale-gen en_US.UTF-8 -RUN if type sudo 2>/dev/null; then \ - echo "The sudo command already exists... Skipping."; \ - else \ - echo -e "#!/bin/sh\n\${@}" > /usr/sbin/sudo; \ - chmod +x /usr/sbin/sudo; \ - fi -RUN set -eux \ - && export DEBIAN_FRONTEND=noninteractive \ - && yes | install/install_prereqs_bionic.sh \ - && rm -rf /var/lib/apt/lists/* diff --git a/install/bionic/ros/Dockerfile b/install/bionic/ros/Dockerfile deleted file mode 100644 index 6d7d1abfce..0000000000 --- a/install/bionic/ros/Dockerfile +++ /dev/null @@ -1,19 +0,0 @@ -FROM ros:melodic-ros-base-bionic -WORKDIR /dairlib -ENV DAIRLIB_DOCKER_VERSION_25=25 -COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python -RUN apt-get install -y python-rosinstall-generator python-catkin-tools -RUN set -eux \ - && apt-get install --no-install-recommends locales \ - && locale-gen en_US.UTF-8 -RUN if type sudo 2>/dev/null; then \ - echo "The sudo command already exists... Skipping."; \ - else \ - echo -e "#!/bin/sh\n\${@}" > /usr/sbin/sudo; \ - chmod +x /usr/sbin/sudo; \ - fi -RUN set -eux \ - && export DEBIAN_FRONTEND=noninteractive \ - && yes | install/install_prereqs_bionic.sh \ - && rm -rf /var/lib/apt/lists/* diff --git a/install/focal/Dockerfile b/install/focal/Dockerfile deleted file mode 100644 index 8033b6125f..0000000000 --- a/install/focal/Dockerfile +++ /dev/null @@ -1,18 +0,0 @@ -FROM ros:noetic-ros-base-focal -WORKDIR /dairlib -ENV DAIRLIB_DOCKER_VERSION_25=25 -COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python clang-12 clang-format-12 -RUN set -eux \ - && apt-get install --no-install-recommends locales \ - && locale-gen en_US.UTF-8 -RUN if type sudo 2>/dev/null; then \ - echo "The sudo command already exists... Skipping."; \ - else \ - echo -e "#!/bin/sh\n\${@}" > /usr/sbin/sudo; \ - chmod +x /usr/sbin/sudo; \ - fi -RUN set -eux \ - && export DEBIAN_FRONTEND=noninteractive \ - && yes | install/install_prereqs_focal.sh \ - && rm -rf /var/lib/apt/lists/* diff --git a/install/focal/ros/Dockerfile b/install/focal/ros/Dockerfile deleted file mode 100644 index 57d8f7a8eb..0000000000 --- a/install/focal/ros/Dockerfile +++ /dev/null @@ -1,20 +0,0 @@ -FROM ros:noetic-ros-base-focal -WORKDIR /dairlib -ENV DAIRLIB_DOCKER_VERSION_26=26 -ENV ROS_PYTHON_VERSION=3 -COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip python -RUN apt-get install -y python3-rosinstall-generator python3-catkin-tools python3-vcstool python3-osrf-pycommon python3-vcstool python3-empy clang-12 clang-format-12 -RUN set -eux \ - && apt-get install --no-install-recommends locales \ - && locale-gen en_US.UTF-8 -RUN if type sudo 2>/dev/null; then \ - echo "The sudo command already exists... Skipping."; \ - else \ - echo -e "#!/bin/sh\n\${@}" > /usr/sbin/sudo; \ - chmod +x /usr/sbin/sudo; \ - fi -RUN set -eux \ - && export DEBIAN_FRONTEND=noninteractive \ - && yes | install/install_prereqs_focal.sh \ - && rm -rf /var/lib/apt/lists/* diff --git a/install/install_prereqs_bionic.sh b/install/install_prereqs_bionic.sh deleted file mode 100755 index 64d1cbdaf9..0000000000 --- a/install/install_prereqs_bionic.sh +++ /dev/null @@ -1,37 +0,0 @@ -#!/bin/bash - -# look in WORKSPACE file for appropriate commit number -DRAKE_COMMIT=$(grep -oP '(?<=DRAKE_COMMIT = ")(.*)(?=")' $(dirname "$0")/../WORKSPACE) - -ubuntu_codename=$(lsb_release -sc) - -# Add drake apt repository for lcm and libbot2 -wget -O - https://drake-apt.csail.mit.edu/drake.asc | apt-key add -echo "deb [arch=amd64] https://drake-apt.csail.mit.edu/bionic bionic main" > /etc/apt/sources.list.d/drake.list -apt-get update - -echo "Using Drake commit '${DRAKE_COMMIT}'" -# Download and run drake install scripts -mkdir tmp -cd tmp -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/install_prereqs.sh" -mkdir source_distribution -cd source_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_prereqs.sh" -# skipping drake's "install_prereqs_user_environment.sh" -touch install_prereqs_user_environment.sh -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-clang.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-test-only.txt" -cd .. -mkdir binary_distribution -cd binary_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/install_prereqs.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/packages-${ubuntu_codename}.txt" -cd .. -chmod +x install_prereqs.sh -./install_prereqs.sh -cd .. -rm -rf tmp/ -# In addition to drake, install lcm and libbot2 -apt install lcm libbot2 \ No newline at end of file diff --git a/install/install_prereqs_focal.sh b/install/install_prereqs_focal.sh deleted file mode 100755 index 04fc306c16..0000000000 --- a/install/install_prereqs_focal.sh +++ /dev/null @@ -1,37 +0,0 @@ -#!/bin/bash - -# look in WORKSPACE file for appropriate commit number -DRAKE_COMMIT=$(grep -oP '(?<=DRAKE_COMMIT = ")(.*)(?=")' $(dirname "$0")/../WORKSPACE) - -ubuntu_codename=$(lsb_release -sc) - -# Add drake apt repository for lcm and libbot2 -wget -O - https://drake-apt.csail.mit.edu/drake.asc | apt-key add -echo "deb [arch=amd64] https://drake-apt.csail.mit.edu/focal focal main" > /etc/apt/sources.list.d/drake.list -apt-get update - -echo "Using Drake commit '${DRAKE_COMMIT}'" -# Download and run drake install scripts -mkdir tmp -cd tmp -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/install_prereqs.sh" -mkdir source_distribution -cd source_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_prereqs.sh" -# skipping drake's "install_prereqs_user_environment.sh" -touch install_prereqs_user_environment.sh -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-clang.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-test-only.txt" -cd .. -mkdir binary_distribution -cd binary_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/install_prereqs.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/packages-${ubuntu_codename}.txt" -cd .. -chmod +x install_prereqs.sh -./install_prereqs.sh -cd .. -rm -rf tmp/ -# In addition to drake, install lcm and libbot2 -apt install lcm libbot2 \ No newline at end of file diff --git a/install/install_prereqs_jammy.sh b/install/install_prereqs_jammy.sh deleted file mode 100755 index c6ef759e7e..0000000000 --- a/install/install_prereqs_jammy.sh +++ /dev/null @@ -1,39 +0,0 @@ -#!/bin/bash - -# look in WORKSPACE file for appropriate commit number -DRAKE_COMMIT=$(grep -oP '(?<=DRAKE_COMMIT = ")(.*)(?=")' $(dirname "$0")/../WORKSPACE) - -ubuntu_codename=$(lsb_release -sc) - -# Add drake apt repository for lcm and libbot2 -wget -qO- https://drake-apt.csail.mit.edu/drake.asc | gpg --dearmor - | sudo tee /etc/apt/trusted.gpg.d/drake.gpg >/dev/null -echo "deb [arch=amd64] https://drake-apt.csail.mit.edu/${ubuntu_codename} ${ubuntu_codename} main" | sudo tee /etc/apt/sources.list.d/drake.list >/dev/null -apt-get update - -echo "Using Drake commit '${DRAKE_COMMIT}'" -# Download and run drake install scripts -mkdir tmp -cd tmp -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/install_prereqs.sh" -mkdir source_distribution -cd source_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_prereqs.sh" -# skipping drake's "install_prereqs_user_environment.sh" -touch install_prereqs_user_environment.sh -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-clang.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/packages-${ubuntu_codename}-test-only.txt" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_bazelisk.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/source_distribution/install_bazel.sh" -cd .. -mkdir binary_distribution -cd binary_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/install_prereqs.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/ubuntu/binary_distribution/packages-${ubuntu_codename}.txt" -cd .. -chmod +x install_prereqs.sh -./install_prereqs.sh --with-bazel -cd .. -rm -rf tmp/ -# In addition to drake, install lcm and libbot2 -apt install lcm libbot2 \ No newline at end of file diff --git a/install/install_prereqs_mac.sh b/install/install_prereqs_mac.sh deleted file mode 100755 index b447a4a7c9..0000000000 --- a/install/install_prereqs_mac.sh +++ /dev/null @@ -1,32 +0,0 @@ -#!/bin/bash - -# look in WORKSPACE file for appropriate commit number -DRAKE_COMMIT=$(grep -oP '(?<=DRAKE_COMMIT = ")(.*)(?=")' $(dirname "$0")/../WORKSPACE) - -ubuntu_codename=$(lsb_release -sc) - -echo "Using Drake commit '${DRAKE_COMMIT}'" -# Download and run drake install scripts -mkdir tmp -cd tmp -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/install_prereqs.sh" -mkdir source_distribution -cd source_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/source_distribution/install_prereqs.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/source_distribution/install_prereqs_user_environment.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/source_distribution/Brewfile" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/source_distribution/requirements.txt" -cd .. -mkdir binary_distribution -cd binary_distribution -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/binary_distribution/install_prereqs.sh" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/binary_distribution/Brewfile" -wget "https://raw.githubusercontent.com/RobotLocomotion/drake/${DRAKE_COMMIT}/setup/mac/binary_distribution/requirements.txt" -cd .. -chmod +x install_prereqs.sh -./install_prereqs.sh -cd .. -rm -rf tmp/ -# In addition to drake, install lcm and libbot2 -# TODO: the line below is not tested, need a mac user to see if it will work! -brew install lcm libbot2 \ No newline at end of file diff --git a/install/install_prereqs_ubuntu.sh b/install/install_prereqs_ubuntu.sh new file mode 100755 index 0000000000..40361c5daa --- /dev/null +++ b/install/install_prereqs_ubuntu.sh @@ -0,0 +1,21 @@ + #!/bin/bash + +# look in WORKSPACE file for appropriate commit number +DRAKE_VERSION=$(grep -oP 'DRAKE_VERSION = "v?\K[^"]*' $(dirname "$0")/../MODULE.bazel) +echo ${DRAKE_VERSION} + +ubuntu_codename=$(lsb_release -sc) + +# Add drake apt repository for lcm and libbot2 +wget -qO- https://drake-apt.csail.mit.edu/drake.asc | gpg --dearmor - | sudo tee /etc/apt/trusted.gpg.d/drake.gpg >/dev/null +echo "deb [arch=amd64] https://drake-apt.csail.mit.edu/${ubuntu_codename} ${ubuntu_codename} main" | sudo tee /etc/apt/sources.list.d/drake.list >/dev/null + + +wget https://github.com/RobotLocomotion/drake/archive/v${DRAKE_VERSION}.tar.gz +tar -xzf v${DRAKE_VERSION}.tar.gz drake-$DRAKE_VERSION/setup/ +./drake-${DRAKE_VERSION}/setup/install_prereqs --developer -y --with-bazel +rm -rf ./drake-${DRAKE_VERSION}/ +rm v${DRAKE_VERSION}.tar.gz + +# In addition to drake, install lcm and libbot2 +sudo apt install lcm libbot2 \ No newline at end of file diff --git a/install/jammy/Dockerfile b/install/jammy/Dockerfile deleted file mode 100644 index dd06a27c86..0000000000 --- a/install/jammy/Dockerfile +++ /dev/null @@ -1,19 +0,0 @@ -FROM ubuntu:jammy -WORKDIR ./dairlib -ENV DAIRLIB_DOCKER_VERSION_25=25 -COPY . . -RUN apt-get update && apt-get install -y wget lsb-release pkg-config zip g++ zlib1g-dev unzip clang-12 clang-format-12 ca-certificates gnupg - -RUN set -eux \ - && apt-get install --no-install-recommends locales \ - && locale-gen en_US.UTF-8 -RUN if type sudo 2>/dev/null; then \ - echo "The sudo command already exists... Skipping."; \ - else \ - echo -e "#!/bin/sh\n\${@}" > /usr/sbin/sudo; \ - chmod +x /usr/sbin/sudo; \ - fi -RUN set -eux \ - && export DEBIAN_FRONTEND=noninteractive \ - && yes | install/install_prereqs_jammy.sh \ - && rm -rf /var/lib/apt/lists/* diff --git a/lcm/test/lcm_trajectory_test.cc b/lcm/test/lcm_trajectory_test.cc index 95466c20ba..f6a91e4db7 100644 --- a/lcm/test/lcm_trajectory_test.cc +++ b/lcm/test/lcm_trajectory_test.cc @@ -70,7 +70,7 @@ class LcmTrajectoryTest : public ::testing::Test { trajectories_[1] = traj_2_; lcm_traj_ = LcmTrajectory(trajectories_, trajectory_names_, TEST_NAME, - TEST_DESCRIPTION); + TEST_DESCRIPTION, true); } LcmTrajectory::Trajectory traj_1_; diff --git a/lcmtypes/BUILD.bazel b/lcmtypes/BUILD.bazel index bf07523c9b..528d97693c 100644 --- a/lcmtypes/BUILD.bazel +++ b/lcmtypes/BUILD.bazel @@ -1,8 +1,8 @@ load( - "@drake//tools/skylark:drake_lcm.bzl", - "drake_lcm_cc_library", - "drake_lcm_java_library", - "drake_lcm_py_library", + "@drake//tools/workspace/lcm:lcm.bzl", + "lcm_cc_library", + "lcm_java_library", + "lcm_py_library", ) load( "@drake//tools/skylark:drake_java.bzl", @@ -15,45 +15,39 @@ package(default_visibility = ["//visibility:public"]) #Lcm libraries #Lcm libraries -drake_lcm_cc_library( +lcm_cc_library( name = "lcmt_robot", lcm_package = "dairlib", lcm_srcs = glob(["*.lcm"]), ) #Lcm libraries -drake_lcm_cc_library( +lcm_cc_library( name = "lcmtypes_robot_archive", lcm_package = "archive.dairlib", lcm_srcs = glob(["archive/*.lcm"]), ) -drake_lcm_java_library( +lcm_java_library( name = "lcmtypes_robot_java", lcm_package = "dairlib", lcm_srcs = glob(["*.lcm"]), ) -drake_lcm_py_library( +lcm_py_library( name = "lcmtypes_robot_py", add_current_package_to_imports = True, # Use //:module_py instead. extra_srcs = ["__init__.py"], lcm_package = "dairlib", lcm_srcs = glob(["*.lcm"]), - deps = [ - "@drake//:module_py", - ], ) -drake_lcm_py_library( +lcm_py_library( name = "lcmtypes_robot_archive_py", add_current_package_to_imports = True, # Use //:module_py instead. extra_srcs = ["__init__.py"], lcm_package = "archive.dairlib", lcm_srcs = glob(["archive/*.lcm"]), - deps = [ - "@drake//:module_py", - ], ) drake_java_binary( diff --git a/multibody/BUILD.bazel b/multibody/BUILD.bazel index a9ea3eede2..2257aa9060 100644 --- a/multibody/BUILD.bazel +++ b/multibody/BUILD.bazel @@ -100,7 +100,7 @@ cc_test( cc_library( name = "ball_urdf", - data = glob(["multibody/ball.urdf"]), + data = glob(["ball.urdf"]), ) cc_library( diff --git a/multibody/kinematic/kinematic_evaluator_set.cc b/multibody/kinematic/kinematic_evaluator_set.cc index 5e1e8d0373..c992f8b67f 100644 --- a/multibody/kinematic/kinematic_evaluator_set.cc +++ b/multibody/kinematic/kinematic_evaluator_set.cc @@ -1,5 +1,6 @@ #include "multibody/kinematic/kinematic_evaluator_set.h" +#include "drake/common/text_logging.h" #include "drake/math/autodiff_gradient.h" namespace dairlib { diff --git a/solvers/c3_qp.h b/solvers/c3_qp.h index dee6c58c2c..0c058e5355 100644 --- a/solvers/c3_qp.h +++ b/solvers/c3_qp.h @@ -4,7 +4,6 @@ #include -#include "gurobi_c++.h" #include "solvers/c3.h" #include "solvers/lcs.h" diff --git a/systems/controllers/safe_velocity_controller.cc b/systems/controllers/safe_velocity_controller.cc index 6e2d1558b9..27ff6528d9 100644 --- a/systems/controllers/safe_velocity_controller.cc +++ b/systems/controllers/safe_velocity_controller.cc @@ -1,5 +1,7 @@ #include "systems/controllers/safe_velocity_controller.h" +#include "drake/common/text_logging.h" + using drake::systems::BasicVector; using drake::systems::Context; using drake::VectorX; diff --git a/tools/workspace/gurobi/BUILD.bazel b/tools/workspace/gurobi/BUILD.bazel new file mode 100644 index 0000000000..a0f3ced5ee --- /dev/null +++ b/tools/workspace/gurobi/BUILD.bazel @@ -0,0 +1,13 @@ +load("@bazel_skylib//lib:selects.bzl", "selects") + +selects.config_setting_group( + name = "enabled", + match_any = [ + ":enabled_via_flag", + ], +) + +config_setting( + name = "enabled_via_flag", + flag_values = {"@drake//tools/flags:with_gurobi": "True"}, +) diff --git a/tools/workspace/gurobi/package-darwin.BUILD.bazel.in b/tools/workspace/gurobi/package-darwin.BUILD.bazel.in new file mode 100644 index 0000000000..82cdc278b6 --- /dev/null +++ b/tools/workspace/gurobi/package-darwin.BUILD.bazel.in @@ -0,0 +1,55 @@ +# -*- bazel -*- + +load("@drake//tools/install:install.bzl", "install") +load("@drake//tools/skylark:cc.bzl", "cc_library") + +licenses(["by_exception_only"]) # Gurobi + +# This rule is only built if a glob() call fails. +genrule( + name = "error-message", + outs = ["error-message.h"], + cmd = "echo 'error: Gurobi 10.0 is not installed at {gurobi_home}' && false", # noqa + visibility = ["//visibility:private"], +) + +GUROBI_C_HDRS = glob([ + "gurobi-distro/include/gurobi_c.h", +], allow_empty = True) or [":error-message.h"] + +GUROBI_CXX_HDRS = glob([ + "gurobi-distro/include/gurobi_c.h", + "gurobi-distro/include/gurobi_c++.h", +], allow_empty = True) or [":error-message.h"] + +cc_library( + name = "gurobi_c", + hdrs = GUROBI_C_HDRS, + includes = ["gurobi-distro/include"], + linkopts = [ + "-L{gurobi_home}/lib", + "-lgurobi100", + "-Wl,-rpath,{gurobi_home}/lib", + ], + visibility = ["//visibility:public"], +) + +cc_library( + name = "gurobi_cxx", + hdrs = GUROBI_CXX_HDRS, + includes = ["gurobi-distro/include"], + linkopts = [ + "-L{gurobi_home}/lib", + "-lgurobi100", + "-lgurobi_stdc++", + "-Wl,-rpath,{gurobi_home}/lib", + ], + visibility = ["//visibility:public"], +) + +# For macOS, the Drake install step does not need any additional actions to +# install Gurobi, since Gurobi was already installed system-wide in /Library. +install( + name = "install", + visibility = ["//visibility:public"], +) diff --git a/tools/workspace/gurobi/package-linux.BUILD.bazel.in b/tools/workspace/gurobi/package-linux.BUILD.bazel.in new file mode 100644 index 0000000000..33c9f7c29f --- /dev/null +++ b/tools/workspace/gurobi/package-linux.BUILD.bazel.in @@ -0,0 +1,82 @@ +# -*- bazel -*- + +load("@drake//tools/install:install.bzl", "install", "install_files") +load("@drake//tools/skylark:cc.bzl", "cc_library") + +licenses(["by_exception_only"]) # Gurobi + +# This rule is only built if a glob() call fails. +genrule( + name = "error-message", + outs = ["error-message.h"], + cmd = "echo 'error: Gurobi 10.0 is not installed at {gurobi_home}, export GUROBI_HOME to the correct value' && false", # noqa + visibility = ["//visibility:private"], +) + +GUROBI_C_HDRS = glob([ + "gurobi-distro/include/gurobi_c.h", +], allow_empty = True) or [":error-message.h"] + +GUROBI_CXX_HDRS = glob([ + "gurobi-distro/include/gurobi_c.h", + "gurobi-distro/include/gurobi_c++.h", +], allow_empty = True) or [":error-message.h"] + +# In the Gurobi package, libgurobi100.so is a symlink to libgurobi.so.10.0.*. +# However, if we use libgurobi.so.10.0.* in srcs, executables that link this +# library will be unable to find it at runtime in the Bazel sandbox, +# because the NEEDED statements in the executable will not square with the +# RPATH statements. I don't really know why this happens, but I suspect it +# might be a Bazel bug. + +GUROBI_C_SRCS = glob([ + "gurobi-distro/lib/libgurobi100.so", +], allow_empty = True) or [":error-message.h"] + +GUROBI_CXX_SRCS = glob([ + "gurobi-distro/lib/libgurobi100.so", + "gurobi-distro/lib/libgurobi_g++5.2.a", +], allow_empty = True) or [":error-message.h"] + +GUROBI_INSTALL_LIBRARIES = glob([ + "gurobi-distro/lib/libgurobi.so.10.0.*", + "gurobi-distro/lib/libgurobi100.so", +], allow_empty = True) or [":error-message.h"] + +GUROBI_DOCS = glob([ + "gurobi-distro/EULA.pdf", +], allow_empty = True) or [":error-message.h"] + +cc_library( + name = "gurobi_c", + srcs = GUROBI_C_SRCS, + hdrs = GUROBI_C_HDRS, + includes = ["gurobi-distro/include"], + linkopts = ["-pthread"], + visibility = ["//visibility:public"], +) + +cc_library( + name = "gurobi_cxx", + srcs = GUROBI_CXX_SRCS, + hdrs = GUROBI_CXX_HDRS, + includes = ["gurobi-distro/include"], + linkopts = ["-pthread"], + visibility = ["//visibility:public"], +) + +install_files( + name = "install_libraries", + dest = ".", + files = GUROBI_INSTALL_LIBRARIES, + strip_prefix = ["gurobi-distro"], + visibility = ["//visibility:private"], +) + +install( + name = "install", + docs = GUROBI_DOCS, + doc_strip_prefix = ["gurobi-distro"], + visibility = ["//visibility:public"], + deps = [":install_libraries"], +) diff --git a/tools/workspace/gurobi/repository.bzl b/tools/workspace/gurobi/repository.bzl new file mode 100644 index 0000000000..4e9907cecf --- /dev/null +++ b/tools/workspace/gurobi/repository.bzl @@ -0,0 +1,89 @@ +# This is a Bazel repository_rule for the Gurobi solver. See +# https://www.bazel.io/versions/master/docs/skylark/repository_rules.html + +# Finds the "latest" f'{path}/{prefix}*/{subdir}', where "latest" is determined +# by converting the part that matched the '*' to an integer and taking the +# match with the highest value. +def _find_latest(repo_ctx, path, prefix, subdir): + best_dir = None + best_version = None + for d in repo_ctx.path(path).readdir(): + if d.basename.startswith(prefix): + full_dir = d.get_child(subdir) + if full_dir.exists: + version = int(d.basename[len(prefix):]) + if best_version == None or version > best_version: + best_version = version + best_dir = str(full_dir) + + return best_dir or (path + "/" + prefix + "-notfound/" + subdir) + +# Ubuntu only: GUROBI_HOME should be the linux64 directory in the Gurobi 10.0 +# release. +# +def _gurobi_impl(repo_ctx): + os_name = repo_ctx.os.name + if os_name == "mac os x": + os_name = "darwin" + + if os_name == "darwin": + # Gurobi must be installed into its standard location. + gurobi_home = _find_latest( + repo_ctx, + "/Library", + "gurobi100", + "macos_universal2", + ) + repo_ctx.symlink(gurobi_home, "gurobi-distro") + elif os_name == "linux": + # The default directory for the downloaded gurobi is + # /opt/gurobi100*/linux64. If the user does not use the default + # directory, the he/she should set GUROBI_HOME environment variable to + # the gurobi file location. + gurobi_home = repo_ctx.getenv("GUROBI_HOME", "") + repo_ctx.symlink( + gurobi_home or _find_latest( + repo_ctx, + "/opt", + "gurobi100", + "linux64", + ), + "gurobi-distro", + ) + else: + # Defer error reporting to the BUILD file. + repo_ctx.symlink("/gurobi-notfound", "gurobi-distro") + os_name = "linux" + + # Emit the generated BUILD.bazel file. + repo_ctx.template( + "BUILD.bazel", + Label("@//tools/workspace/gurobi:" + + "package-{}.BUILD.bazel.in".format(os_name)), + substitutions = { + "{gurobi_home}": gurobi_home, + }, + executable = False, + ) + + # Capture whether or not Gurobi tests can run in parallel. + license_unlimited_int = repo_ctx.getenv("DRAKE_GUROBI_LICENSE_UNLIMITED", "0") # noqa: E501 + license_unlimited = bool(int(license_unlimited_int) == 1) + repo_ctx.file( + "defs.bzl", + content = "DRAKE_GUROBI_LICENSE_UNLIMITED = {}" + .format(license_unlimited), + executable = False, + ) + +gurobi_repository = repository_rule( + local = True, + implementation = _gurobi_impl, +) + +def _gurobi_extension_impl(module_ctx): + gurobi_repository(name = "my_gurobi") + +gurobi_extension = module_extension( + implementation = _gurobi_extension_impl, +) diff --git a/tools/workspace/ros/.gitignore b/tools/workspace/ros/.gitignore deleted file mode 100644 index 1e059677cd..0000000000 --- a/tools/workspace/ros/.gitignore +++ /dev/null @@ -1 +0,0 @@ -/bundle_ws/ diff --git a/tools/workspace/ros/BUILD.bazel b/tools/workspace/ros/BUILD.bazel deleted file mode 100644 index 5dbef1a94d..0000000000 --- a/tools/workspace/ros/BUILD.bazel +++ /dev/null @@ -1,30 +0,0 @@ -# -*- python -*- - -# Demo programs - -cc_binary( - name = "main", - srcs = ["test/main.cpp"], - tags = ["ros"], - deps = [ - "@ros", - ], -) - -py_binary( - name = "main_python", - srcs = ["test/main_python.py"], - tags = ["ros"], - deps = [ - "@ros//:ros_python", - ], -) - -py_binary( - name = "genmsg_test", - srcs = ["test/genmsg_test.py"], - tags = ["ros"], - deps = [ - "@genpy_repo//:genpy", - ], -) diff --git a/tools/workspace/ros/LICENSE_ros-bazel b/tools/workspace/ros/LICENSE_ros-bazel deleted file mode 100644 index 1fce6447d9..0000000000 --- a/tools/workspace/ros/LICENSE_ros-bazel +++ /dev/null @@ -1,24 +0,0 @@ -Original versions of //tools/workspace/ros are from -https://github.com/nicolov/ros-bazel - -MIT License - -Copyright (c) 2017 Nicolo Valigi - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. diff --git a/tools/workspace/ros/bazel/BUILD b/tools/workspace/ros/bazel/BUILD deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/tools/workspace/ros/bazel/genmsg.BUILD b/tools/workspace/ros/bazel/genmsg.BUILD deleted file mode 100644 index a752a0acb6..0000000000 --- a/tools/workspace/ros/bazel/genmsg.BUILD +++ /dev/null @@ -1,7 +0,0 @@ -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "genmsg", - srcs = glob(["src/**/*.py"]), - imports = ["src"], -) diff --git a/tools/workspace/ros/bazel/genpy.BUILD b/tools/workspace/ros/bazel/genpy.BUILD deleted file mode 100644 index c431e52130..0000000000 --- a/tools/workspace/ros/bazel/genpy.BUILD +++ /dev/null @@ -1,18 +0,0 @@ -package(default_visibility = ["//visibility:public"]) - -py_library( - name = "genpy", - srcs = glob(["src/**/*.py"]), - imports = ["src"], - deps = [ - "@genmsg_repo//:genmsg", - ], -) - -py_binary( - name = "genmsg_py", - srcs = ["scripts/genmsg_py.py"], - deps = [ - ":genpy", - ], -) diff --git a/tools/workspace/ros/bazel/message_generation.bzl b/tools/workspace/ros/bazel/message_generation.bzl deleted file mode 100644 index 66af366203..0000000000 --- a/tools/workspace/ros/bazel/message_generation.bzl +++ /dev/null @@ -1,134 +0,0 @@ -# Reference: -# https://docs.bazel.build/versions/master/skylark/cookbook.html -# https://github.com/RobotLocomotion/drake/blob/eefddbee62439156b6faaf3b0cecdd0c57e704d7/tools/lcm.bzl - -load("//tools/workspace/ros/bazel:path_utils.bzl", "basename", "dirname", "join_paths") - -def _genmsg_outs(srcs, ros_package_name, extension): - """ Given a list of *.msg files, return the expected paths - to the generated code with that extension. """ - - (extension in [".py", ".h"] or - fail("Unknown extension %s" % extension)) - - msg_names = [] - for item in srcs: - if not item.endswith(".msg"): - fail("%s does not end in .msg" % item) - item_name = basename(item)[:-len(".msg")] - - if extension == ".py": - item_name = "_" + item_name - - msg_names.append(item_name) - - outs = [ - join_paths(ros_package_name, "msg", msg_name + extension) - for msg_name in msg_names - ] - - if extension == ".py": - outs += [ - join_paths(ros_package_name, "msg", "__init__.py"), - join_paths(ros_package_name, "__init__.py"), - ] - - return outs - -def _genpy_impl(ctx): - """Implementation for the genpy rule. Shells out to the scripts - shipped with genpy.""" - - srcpath = ctx.files.srcs[0].dirname - outpath = ctx.outputs.outs[0].dirname - - # Generate __init__.py for package - ctx.actions.write( - output = ctx.outputs.outs[-1], - content = "", - ) - - # Generate the actual messages - ctx.actions.run( - inputs = ctx.files.srcs, - outputs = ctx.outputs.outs[:-2], - executable = ctx.executable._gen_script, - arguments = [ - "-o", - outpath, - "-p", - ctx.attr.ros_package_name, - # Include path for the current package - "-I", - "%s:%s" % (ctx.attr.ros_package_name, srcpath), - # TODO: include paths of dependent packages - ] + [ - f.path - for f in ctx.files.srcs - ], - ) - - # Generate __init__.py for msg module - # NOTE: it looks at the .py files in its output path, so it also - # needs to depend on the previous step. - ctx.actions.run( - inputs = ctx.files.srcs + ctx.outputs.outs[:-2], - outputs = [ctx.outputs.outs[-2]], - executable = ctx.executable._gen_script, - arguments = [ - "--initpy", - "-o", - outpath, - "-p", - ctx.attr.ros_package_name, - ], - ) - - return struct() - -_genpy = rule( - implementation = _genpy_impl, - output_to_genfiles = True, - attrs = { - "srcs": attr.label_list(allow_files = True), - "ros_package_name": attr.string(), - "_gen_script": attr.label( - default = Label("@genpy_repo//:genmsg_py"), - executable = True, - cfg = "host", - ), - "outs": attr.output_list(), - }, -) - -def generate_messages( - srcs = None, - ros_package_name = None): - """ Wraps all message generation functionality. Uses the _genpy - and _gencpp to shell out to the code generation scripts, then wraps - the resulting files into Python and C++ libraries. - We use macros to hide some of the book-keeping of input & output - files. """ - - if not srcs: - fail("srcs is required (*.msg files).") - if not ros_package_name: - fail("ros_package_name is required.") - - outs = _genmsg_outs(srcs, ros_package_name, ".py") - - _genpy( - name = "lkfjaklsjfklasd", - srcs = srcs, - ros_package_name = ros_package_name, - outs = outs, - ) - - native.py_library( - name = "msgs_py", - srcs = outs, - imports = ["."], - deps = [ - "@genpy_repo//:genpy", - ], - ) diff --git a/tools/workspace/ros/bazel/path_utils.bzl b/tools/workspace/ros/bazel/path_utils.bzl deleted file mode 100644 index ae697cfcb9..0000000000 --- a/tools/workspace/ros/bazel/path_utils.bzl +++ /dev/null @@ -1,39 +0,0 @@ -# Lifted from: -# https://github.com/RobotLocomotion/drake/blob/eefddbee62439156b6faaf3b0cecdd0c57e704d7/tools/pathutils.bzl - -def basename(path): - """Return the file name portion of a file path.""" - return path.split("/")[-1] - -def dirname(path): - """Return the directory portion of a file path.""" - if path == "/": - return "/" - - parts = path.split("/") - - if len(parts) > 1: - return "/".join(parts[:-1]) - - return "." - -def join_paths(*args): - """Join paths without duplicating separators. - This is roughly equivalent to Python's `os.path.join`. - Args: - *args (:obj:`list` of :obj:`str`): Path components to be joined. - Returns: - :obj:`str`: The concatenation of the input path components. - """ - result = "" - - for part in args: - if part.endswith("/"): - part = part[-1] - - if part == "" or part == ".": - continue - - result += part + "/" - - return result[:-1] diff --git a/tools/workspace/ros/bazel/pypi.bzl b/tools/workspace/ros/bazel/pypi.bzl deleted file mode 100644 index 85483b4517..0000000000 --- a/tools/workspace/ros/bazel/pypi.bzl +++ /dev/null @@ -1,54 +0,0 @@ -_BUILD_FILE = """ -py_library( - name = 'libraries', - srcs = glob( - include = ['bin/**/*.py', 'site-packages/**/*.py'], - ), - data = glob( - include = ['bin/**/*', 'site-packages/**/*'], - exclude = ['**/*.py', '**/*.pyc'] - ), - imports=['site-packages'], - visibility = ['//visibility:public'] -) -""" - -def pip_package_impl(ctx): - getpip = ctx.path(ctx.attr._getpip) - path = ctx.path("site-packages") - - command = ["python", str(getpip)] - command += list(ctx.attr.packages) - command += ["--target", str(path)] - command += ["--install-option", "--install-scripts=%s" % ctx.path("bin")] - command += ["--no-cache-dir"] - - print(command) - result = ctx.execute(command) - if result.return_code != 0: - fail("Failed to execute %s.\n%s\n%s" % ( - " ".join(command), - result.stdout, - result.stderr, - )) - ctx.file("BUILD", _BUILD_FILE, False) - -pip_requirements = repository_rule( - pip_package_impl, - attrs = { - "packages": attr.string_list(), - "_getpip": attr.label( - default = Label("@pip//file:get-pip.py"), - allow_single_file = True, - executable = True, - cfg = "host", - ), - }, -) - -def pip(): - native.http_file( - name = "pip", - url = "https://bootstrap.pypa.io/get-pip.py", - sha256 = "19dae841a150c86e2a09d475b5eb0602861f2a5b7761ec268049a662dbd2bd0c", - ) diff --git a/tools/workspace/ros/compile_ros_workspace.sh b/tools/workspace/ros/compile_ros_workspace.sh deleted file mode 100755 index e95b6bc464..0000000000 --- a/tools/workspace/ros/compile_ros_workspace.sh +++ /dev/null @@ -1,58 +0,0 @@ -#!/usr/bin/env bash - -# In addition to your base ROS install, -# you must sudo apt-get install python3-vcstool - -# Tested on ubuntu 20.04 and 18.04 -BASE_DIR="$PWD" - -cd $(dirname "$BASH_SOURCE") - -set -e - -PACKAGES="roscpp rospy franka_msgs sensor_msgs nav_msgs" -# You can add any published ros packages you need to this list. -# Local ROS packages should be their own bazel local_repository - -rm -rf bundle_ws -mkdir bundle_ws -pushd bundle_ws -mkdir src - -DISTRO=$(lsb_release -c -s) - -if [ $DISTRO == "bionic" ] -then - rosinstall_generator \ - --deps \ - --tar \ - --flat \ - $PACKAGES > ws.rosinstall - wstool init -j1 src ws.rosinstall -elif [ $DISTRO == "focal" ] -then - rosinstall_generator \ - --rosdistro noetic \ - --deps \ - --tar \ - --flat \ - $PACKAGES > ws.rosinstall - vcs import src < ws.rosinstall -else - echo "${DISTRO} not supported for ROS with dairlib!" - exit 1 -fi - -catkin config \ - --install \ - --source-space src \ - --build-space build \ - --devel-space devel \ - --log-space log \ - --install-space install \ - --isolate-devel \ - --no-extend - -catkin build -DPYTHON_EXECUTABLE=/usr/bin/python3 - -cd $BASE_DIR diff --git a/tools/workspace/ros/ros.bazel b/tools/workspace/ros/ros.bazel deleted file mode 100644 index f7381abecb..0000000000 --- a/tools/workspace/ros/ros.bazel +++ /dev/null @@ -1,18 +0,0 @@ -# -*- python -*- - -package(default_visibility = ["//visibility:public"]) - -# Prebuilt C++ and Python ROS libraries - -cc_library( - name='ros', - srcs=glob(['lib/*.so']), - hdrs=glob(['include/**/*.h', 'include/**/*.hpp']), - strip_include_prefix='include' -) - -py_library( - name='ros_python', - srcs=glob(['lib/python2.7/dist-packages/**/*.py']), - imports=['lib/python2.7/dist-packages/'] -) diff --git a/tools/workspace/ros/test/genmsg_test.py b/tools/workspace/ros/test/genmsg_test.py deleted file mode 100644 index 93f8ee82cd..0000000000 --- a/tools/workspace/ros/test/genmsg_test.py +++ /dev/null @@ -1,12 +0,0 @@ -#!/usr/bin/env python - -import os -import genpy - -import genpy.generator - -def main(): - pass - -if __name__ == '__main__': - main() diff --git a/tools/workspace/ros/test/main.cpp b/tools/workspace/ros/test/main.cpp deleted file mode 100644 index eef5db64fc..0000000000 --- a/tools/workspace/ros/test/main.cpp +++ /dev/null @@ -1,33 +0,0 @@ -#include -#include - -#include - -int main(int argc, char **argv) { - ros::init(argc, argv, "talker"); - - ros::NodeHandle n; - ros::Publisher chatter_pub = n.advertise("chatter", 1000); - - ros::Rate loop_rate(10); - - int count = 0; - while (ros::ok()) { - std_msgs::String msg; - - std::stringstream ss; - ss << "hello world " << count; - msg.data = ss.str(); - - ROS_INFO("%s", msg.data.c_str()); - - chatter_pub.publish(msg); - - ros::spinOnce(); - - loop_rate.sleep(); - ++count; - } - - return 0; -} \ No newline at end of file diff --git a/tools/workspace/ros/test/main_python.py b/tools/workspace/ros/test/main_python.py deleted file mode 100644 index 2dcf5c205c..0000000000 --- a/tools/workspace/ros/test/main_python.py +++ /dev/null @@ -1,24 +0,0 @@ -#!/usr/bin/env python - -""" -Simple node for testing the Python ROS libraries. -""" - -import rospy -from std_msgs.msg import String - -def talker(): - pub = rospy.Publisher('chatter', String, queue_size=10) - rospy.init_node('talker', anonymous=True) - rate = rospy.Rate(10) # 10hz - while not rospy.is_shutdown(): - hello_str = "hello world %s" % rospy.get_time() - rospy.loginfo(hello_str) - pub.publish(hello_str) - rate.sleep() - -if __name__ == '__main__': - try: - talker() - except rospy.ROSInterruptException: - pass \ No newline at end of file diff --git a/tools/workspace/ros/test/test_msgs/BUILD b/tools/workspace/ros/test/test_msgs/BUILD deleted file mode 100644 index 1648daea73..0000000000 --- a/tools/workspace/ros/test/test_msgs/BUILD +++ /dev/null @@ -1,16 +0,0 @@ -load("//tools/workspace/ros/bazel:message_generation.bzl", "generate_messages") - -# Implicitly creates a msgs_py target in the current scope -generate_messages( - srcs = glob(["msg/*.msg"]), - ros_package_name = "test_msgs", -) - -py_binary( - name = "main", - srcs = ["scripts/main.py"], - tags = ["ros"], - deps = [ - ":msgs_py", - ], -) diff --git a/tools/workspace/ros/test/test_msgs/msg/Message1.msg b/tools/workspace/ros/test/test_msgs/msg/Message1.msg deleted file mode 100644 index 00f26208cb..0000000000 --- a/tools/workspace/ros/test/test_msgs/msg/Message1.msg +++ /dev/null @@ -1 +0,0 @@ -uint64 auint64 \ No newline at end of file diff --git a/tools/workspace/ros/test/test_msgs/msg/Message2.msg b/tools/workspace/ros/test/test_msgs/msg/Message2.msg deleted file mode 100644 index 861f1b534d..0000000000 --- a/tools/workspace/ros/test/test_msgs/msg/Message2.msg +++ /dev/null @@ -1,2 +0,0 @@ -string astr -Message1 amsg1 \ No newline at end of file diff --git a/tools/workspace/ros/test/test_msgs/scripts/main.py b/tools/workspace/ros/test/test_msgs/scripts/main.py deleted file mode 100644 index 5eb5c396fc..0000000000 --- a/tools/workspace/ros/test/test_msgs/scripts/main.py +++ /dev/null @@ -1,18 +0,0 @@ -#!/usr/bin/env python - -from test_msgs.msg import ( - Message1, - Message2, -) - - -def main(): - m1 = Message1() - print(m1) - - m2 = Message2() - print(m2) - - -if __name__ == '__main__': - main() From 05d1aec35285fa7eb3b3bf3fdab774cec9201a2d Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Wed, 2 Jul 2025 11:39:13 -0400 Subject: [PATCH 747/758] Fixes to bazel build files (#381) --- examples/sampling_c3/BUILD.bazel | 2 +- examples/sampling_c3/jacktoy/BUILD.bazel | 13 +------------ 2 files changed, 2 insertions(+), 13 deletions(-) diff --git a/examples/sampling_c3/BUILD.bazel b/examples/sampling_c3/BUILD.bazel index aa2f0f5a36..af48fccb44 100644 --- a/examples/sampling_c3/BUILD.bazel +++ b/examples/sampling_c3/BUILD.bazel @@ -9,8 +9,8 @@ cc_library( filegroup( name = "all_example_params_yamls", - srcs = glob(["*/parameters/*.yaml"]), visibility = ["//visibility:public"], + data = ["//examples/sampling_c3/jacktoy:parameters"], ) filegroup( diff --git a/examples/sampling_c3/jacktoy/BUILD.bazel b/examples/sampling_c3/jacktoy/BUILD.bazel index c27b0f44c3..aea0f689a3 100644 --- a/examples/sampling_c3/jacktoy/BUILD.bazel +++ b/examples/sampling_c3/jacktoy/BUILD.bazel @@ -3,24 +3,13 @@ package(default_visibility = ["//visibility:public"]) -cc_library( - name = "urdfs", - data = glob([ - "urdf/**", - ]), -) - cc_library( name = "parameters", data = glob([ - "*yaml", + "parameters/*.yaml", ]), ) -cc_library( - name = "franka_hardware", - deps = [], -) cc_library( name = "lcm_channels_jacktoy", From 1ccb1a63bc39176df55bc736e4ef531d084fe3f1 Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Wed, 2 Jul 2025 14:45:06 -0700 Subject: [PATCH 748/758] OSQP fix after Drake (and OSQP) upgrade (#383) --- bindings/pydairlib/analysis/osqp_settings_sandbox.py | 1 - examples/Cassie/osc/solver_settings/osqp_options_walking.yaml | 3 +-- examples/Cassie/osc_run/osc_running_qp_settings.yaml | 3 +-- examples/franka/parameters/franka_c3_qp_settings.yaml | 3 +-- examples/franka/parameters/franka_osc_qp_settings.yaml | 3 +-- examples/sampling_c3/shared_parameters/osc_qp_settings.yaml | 3 +-- .../sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml | 3 +-- solvers/c3_qp.cc | 1 - solvers/default_osc_osqp_settings.yaml | 1 - solvers/fast_osqp_solver.cc | 2 +- solvers/osqp_options_default.yaml | 3 +-- solvers/osqp_settings_yaml.h | 2 -- 12 files changed, 8 insertions(+), 20 deletions(-) diff --git a/bindings/pydairlib/analysis/osqp_settings_sandbox.py b/bindings/pydairlib/analysis/osqp_settings_sandbox.py index a22860747b..d42000cb54 100644 --- a/bindings/pydairlib/analysis/osqp_settings_sandbox.py +++ b/bindings/pydairlib/analysis/osqp_settings_sandbox.py @@ -165,7 +165,6 @@ def main(): 'eps_prim_inf': 1e-6, 'eps_dual_inf': 1e-6, 'alpha': 1.6, - 'linsys_solver': 0, 'delta': 1e-6, 'polish': 1, 'polish_refine_iter': 3, diff --git a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml index f82b9ba31c..d8a4e1eabe 100644 --- a/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml +++ b/examples/Cassie/osc/solver_settings/osqp_options_walking.yaml @@ -2,7 +2,6 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 500 - linsys_solver: 0 verbose: 0 warm_start: 1 polish: 1 @@ -11,6 +10,7 @@ int_options: polish_refine_iter: 3 scaling: 10 adaptive_rho: 1 + adaptive_rho_interval: 0 double_options: rho: 0.0001 @@ -21,7 +21,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 0.1 diff --git a/examples/Cassie/osc_run/osc_running_qp_settings.yaml b/examples/Cassie/osc_run/osc_running_qp_settings.yaml index 5cf72f59b4..f9939ffc7f 100644 --- a/examples/Cassie/osc_run/osc_running_qp_settings.yaml +++ b/examples/Cassie/osc_run/osc_running_qp_settings.yaml @@ -2,11 +2,11 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 250 - linsys_solver: 0 verbose: 0 warm_start: 1 scaling: 1 adaptive_rho: 1 + adaptive_rho_interval: 0 polish: 1 polish_refine_iter: 1 scaled_termination: 1 @@ -20,7 +20,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 0 diff --git a/examples/franka/parameters/franka_c3_qp_settings.yaml b/examples/franka/parameters/franka_c3_qp_settings.yaml index b136c938f3..8a12cbe60e 100644 --- a/examples/franka/parameters/franka_c3_qp_settings.yaml +++ b/examples/franka/parameters/franka_c3_qp_settings.yaml @@ -2,11 +2,11 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 1000 - linsys_solver: 0 verbose: 0 warm_start: 1 scaling: 1 adaptive_rho: 1 + adaptive_rho_interval: 0 polish: 1 polish_refine_iter: 1 scaled_termination: 1 @@ -20,7 +20,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 0 diff --git a/examples/franka/parameters/franka_osc_qp_settings.yaml b/examples/franka/parameters/franka_osc_qp_settings.yaml index 639eca37a0..e14875b7a1 100644 --- a/examples/franka/parameters/franka_osc_qp_settings.yaml +++ b/examples/franka/parameters/franka_osc_qp_settings.yaml @@ -2,11 +2,11 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 1000 - linsys_solver: 0 verbose: 0 warm_start: 1 scaling: 1 adaptive_rho: 1 + adaptive_rho_interval: 0 polish: 1 polish_refine_iter: 1 scaled_termination: 1 @@ -20,7 +20,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 0 diff --git a/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml b/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml index 39407d322d..c34da54176 100644 --- a/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml +++ b/examples/sampling_c3/shared_parameters/osc_qp_settings.yaml @@ -2,11 +2,11 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 1000 - linsys_solver: 0 verbose: 0 warm_start: 1 scaling: 1 adaptive_rho: 1 + adaptive_rho_interval: 0 polish: 1 polish_refine_iter: 1 scaled_termination: 1 @@ -20,7 +20,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 0 diff --git a/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml b/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml index 741647456e..d4f5187dfe 100644 --- a/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml +++ b/examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml @@ -2,11 +2,11 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 1000 - linsys_solver: 0 verbose: 0 warm_start: 1 scaling: 1 adaptive_rho: 1 + adaptive_rho_interval: 0 polish: 1 polish_refine_iter: 1 scaled_termination: 1 @@ -20,7 +20,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 0 diff --git a/solvers/c3_qp.cc b/solvers/c3_qp.cc index dca591db8d..686ec1e6df 100644 --- a/solvers/c3_qp.cc +++ b/solvers/c3_qp.cc @@ -78,7 +78,6 @@ VectorXd C3QP::SolveSingleProjection(const MatrixXd& U, const VectorXd& delta_c, solver_options.SetOption(OsqpSolver::id(), "polish_refine_iter", 1); solver_options.SetOption(OsqpSolver::id(), "rho", 1e-4); solver_options.SetOption(OsqpSolver::id(), "scaled_termination", 1); - solver_options.SetOption(OsqpSolver::id(), "linsys_solver", 0); prog.SetSolverOptions(solver_options); MathematicalProgramResult result = osqp_.Solve(prog); diff --git a/solvers/default_osc_osqp_settings.yaml b/solvers/default_osc_osqp_settings.yaml index 132e5afa05..8cd6e9af8d 100644 --- a/solvers/default_osc_osqp_settings.yaml +++ b/solvers/default_osc_osqp_settings.yaml @@ -6,7 +6,6 @@ eps_rel: 1e-7 eps_prim_inf: 1e-5 eps_dual_inf: 1e-5 alpha: 1.6 -linsys_solver: 0 delta: 1e-6 polish: 1 polish_refine_iter: 3 diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index 475dce35f7..a755752ca0 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -319,7 +319,7 @@ void SetFastOsqpSolverSettings(const SolverOptions& solver_options, SetFastOsqpSolverSetting(options_int, "scaling", &(settings->scaling)); SetFastOsqpSolverSetting(options_int, "adaptive_rho", &(settings->adaptive_rho)); - SetFastOsqpSolverSetting(options_double, "adaptive_rho_interval", + SetFastOsqpSolverSetting(options_int, "adaptive_rho_interval", &(settings->adaptive_rho_interval)); SetFastOsqpSolverSetting(options_double, "adaptive_rho_tolerance", &(settings->adaptive_rho_tolerance)); diff --git a/solvers/osqp_options_default.yaml b/solvers/osqp_options_default.yaml index 105d21597a..40d3e70c95 100644 --- a/solvers/osqp_options_default.yaml +++ b/solvers/osqp_options_default.yaml @@ -2,7 +2,6 @@ print_to_console: 0 log_file_name: "" int_options: max_iter: 200 - linsys_solver: 0 verbose: 0 warm_start: 1 polish: 1 @@ -11,6 +10,7 @@ int_options: polish_refine_iter: 3 scaling: 10 adaptive_rho: 1 + adaptive_rho_interval: 0 double_options: rho: 0.0001 @@ -21,7 +21,6 @@ double_options: eps_dual_inf: 1e-5 alpha: 1.6 delta: 1e-6 - adaptive_rho_interval: 0 adaptive_rho_tolerance: 5 adaptive_rho_fraction: 0.4 time_limit: 1.0 diff --git a/solvers/osqp_settings_yaml.h b/solvers/osqp_settings_yaml.h index fcd4cc6a07..a4074222a2 100644 --- a/solvers/osqp_settings_yaml.h +++ b/solvers/osqp_settings_yaml.h @@ -15,7 +15,6 @@ struct OSQPSettingsYaml { double eps_prim_inf; double eps_dual_inf; double alpha; - int linsys_solver; double delta; int polish; int polish_refine_iter; @@ -39,7 +38,6 @@ struct OSQPSettingsYaml { a->Visit(DRAKE_NVP(eps_prim_inf)); a->Visit(DRAKE_NVP(eps_dual_inf)); a->Visit(DRAKE_NVP(alpha)); - a->Visit(DRAKE_NVP(linsys_solver)); a->Visit(DRAKE_NVP(delta)); a->Visit(DRAKE_NVP(polish)); a->Visit(DRAKE_NVP(polish_refine_iter)); From 62ea631f17d43524e0561814bae5ba7cf3c6e110 Mon Sep 17 00:00:00 2001 From: Michael Posa Date: Thu, 3 Jul 2025 10:50:57 -0400 Subject: [PATCH 749/758] Update to Drake 1.42 (#382) * Update to Drake 1.42 * Switch to GHCR image with Cirrus secret * Add noble CI task * Update LcmDrivenLoop and CassieLcmDrivenLoop to shared_ptr for upstream pybind changes --------- Co-authored-by: Bibit Bianchini --- .cirrus.yml | 25 +++++++++++++++-- MODULE.bazel | 4 +-- README.md | 19 ++++--------- bindings/pydairlib/cassie/simulators_py.cc | 17 ++++++++--- bindings/pydairlib/systems/BUILD.bazel | 1 + bindings/pydairlib/systems/framework_py.cc | 28 +++++++++++++++---- examples/Cassie/cassie_lcm_driven_loop.h | 8 +++--- .../Cassie/diagrams/cassie_sim_diagram.cc | 2 +- examples/Cassie/diagrams/cassie_sim_diagram.h | 2 +- examples/Cassie/dispatcher_robot_in.cc | 6 ++-- examples/Cassie/run_osc_jumping_controller.cc | 6 ++-- examples/Cassie/run_osc_running_controller.cc | 6 ++-- .../Cassie/run_osc_standing_controller.cc | 6 ++-- examples/Cassie/run_osc_walking_controller.cc | 8 ++++-- .../Cassie/run_osc_walking_controller_alip.cc | 6 ++-- .../run_joint_space_walking_controller.cc | 6 ++-- examples/sampling_c3/franka_osc_controller.cc | 8 ++++-- .../franka_sampling_c3_controller.cc | 4 ++- systems/framework/lcm_driven_loop.h | 14 +++++----- 19 files changed, 115 insertions(+), 61 deletions(-) diff --git a/.cirrus.yml b/.cirrus.yml index 114b80109c..d43a3a69a9 100644 --- a/.cirrus.yml +++ b/.cirrus.yml @@ -1,8 +1,27 @@ -registry_config: ENCRYPTED[!0a87ac67e240c5bb89044f49c6437615cec7c22faa151949f0648b04911a9e30785a97d897d8796745cb9f72a18732ec!] +registry_config: ENCRYPTED[!88cf0d757d2f8b93dca9e57dc166b65ddedef6378e7ac12a91a022ab3fb28dd47b10d452dc5c53a68e144e6bdbae999b!] build_jammy_task: timeout_in: 120m container: - image: docker.io/michaelposa/jammy-dair-base:latest + image: ghcr.io/dairlab/docker-dair/jammy-dair-base:v1.42 + cpu: 8 + memory: 24G + test_script: + - bazel build + --local_resources=memory=24000 + --local_resources=cpu=8 + --jobs=8 + --remote_http_cache=http://$CIRRUS_HTTP_CACHE_HOST + //... + - bazel test + --local_resources=memory=24000 + --local_resources=cpu=8 + --remote_http_cache=http://$CIRRUS_HTTP_CACHE_HOST + //... + +build_noble_task: + timeout_in: 120m + container: + image: ghcr.io/dairlab/docker-dair/noble-dair-base:v1.42 cpu: 8 memory: 24G test_script: @@ -21,7 +40,7 @@ build_jammy_task: drake_master_build_task: timeout_in: 120m container: - image: docker.io/michaelposa/jammy-dair-base + image: ghcr.io/dairlab/docker-dair/jammy-dair-base:v1.42 cpu: 8 memory: 24G allow_failures: true diff --git a/MODULE.bazel b/MODULE.bazel index da6a473a36..7b559c2896 100644 --- a/MODULE.bazel +++ b/MODULE.bazel @@ -71,8 +71,8 @@ bazel_dep(name = "inekf") # this will also work to override inekf # You can also use DRAKE_COMMIT to choose a Drake release; e.g.: -DRAKE_VERSION = "v1.39.0" -DRAKE_CHECKSUM = "63eb9455181ce9aeb9746e60531fbd4fbe731ea44539276e662e1236a78589b6" +DRAKE_VERSION = "v1.42.0" +DRAKE_CHECKSUM = "d860c15f50397c8a946fcc79e0a58a91ebc56f2189ef9edfcac929aa04157f8b" # Before changing the DRAKE_VERSION, temporarily uncomment the next line so that Bazel # displays the suggested new value for the CHECKSUM. diff --git a/README.md b/README.md index 836682cfbf..18729094d9 100644 --- a/README.md +++ b/README.md @@ -2,10 +2,9 @@ Warning! This is very much "development-level" code and is provided as-is. APIs are likely to be unstable and, while we hope for the documentation to be thorough and accurate, we make no guarantees. ## Current Continuous Integration Status -* `master` branch build and unit tests (Ubuntu 18.04): [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=build&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) -* `master` branch build and unit tests (Ubuntu 20.04): [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=build_focal&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) -* `master` branch build and unit tests (Ubuntu 20.04 with ROS): [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=build_with_ros&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) -* Experimental build against Drake's `master` branch: [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=drake_master_build&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) +* `main` branch build and unit tests (Ubuntu Jammy 22.04): [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=build_jammy&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) +* `main` branch build and unit tests (Ubuntu Focal 24.04): [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=build_focal&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) +* Experimental build against Drake's `master` branch (Jammy): [![Build Status](https://api.cirrus-ci.com/github/DAIRLab/dairlib.svg?task=drake_master_build&script=test)](https://cirrus-ci.com/github/DAIRLab/dairlib) ## Complete Build Instructions ### Download dairlib @@ -29,21 +28,13 @@ There is no need to extract the tar. The library is meant to be built with Drake (see http://drake.mit.edu/ for more details). There are two ways to use Drake within dairlib: #### Option 1: use pegged revision (Note - These steps may need repeated if switching to a branch with a different pegged revision of drake). -The only specific action needed here is to install all of Drake's prerequisites. There are two choices for completing this step: -a) In `dairlib/install`, run the appropriate `install_prereqs_xxx.sh`. This is untested on mac, and has not been tested to get every dependency for a fresh install. - -b) Download a source copy of drake, and install pre-requisites as described here: http://drake.mit.edu/from_source.html. Drake dependencies can change without notice. For full compatiability, you may need to checkout the drake commit which is pegged in WORKSPACE to install the correct dependencies. There is no need to build Drake itself. Proceed only until you have run the Drake setup script. - -bazel will automatically download the pegged revision, specified in the WORKSPACE file. dairlib developers hope to keep this pegged revision current, and ensure that the pegged version will always work with a specific version of dairlib. +In `dairlib/install`, run the `install_prereqs_ubuntu.sh`. Our build process does not currently support MacOS, though it has in the past and likely will in the future. This option is recommended for users who are not currently editing any source code in Drake itself. #### Option 2: source install of Drake -Complete both steps (a) and (b) above. By running the drake install script after the dairlib install script, you are capturing any dependency changes between the pegged revision and the current Drake master, while still getting any aditional dairlib dependencies we may add. There is no need to build Drake. Next, to tell dairlib to use your local install, set the environment variable `DAIRLIB_LOCAL_DRAKE_PATH`, e.g. -``` -export DAIRLIB_LOCAL_DRAKE_PATH=/home/user/my-workspace/drake -``` +If you would like to use your own local install of Drake, likely because you are modifying it, when you build with Bazel you will need to use `bazel build --override_module=drake=/home/user/my-workspace/drake ` (using the appropriate directory for your own install). There is no need to build Drake. ### IDE setup JetBrains IDEs have worked well for us and are available for free to students. For C++ development using the CLion Bazel plugin, see https://drake.mit.edu/clion.html and replace `drake` with `dairlib` in the "Setting up Drake in CLion" section. diff --git a/bindings/pydairlib/cassie/simulators_py.cc b/bindings/pydairlib/cassie/simulators_py.cc index 4077eb241c..96aba78413 100644 --- a/bindings/pydairlib/cassie/simulators_py.cc +++ b/bindings/pydairlib/cassie/simulators_py.cc @@ -3,6 +3,9 @@ #include #include + +#include "drake/bindings/pydrake/pydrake_pybind.h" + #include "examples/Cassie/diagrams/cassie_sim_diagram.h" namespace py = pybind11; @@ -10,6 +13,7 @@ namespace py = pybind11; namespace dairlib { namespace pydairlib { +using drake::pydrake::make_unowned_shared_ptr_from_raw; using examples::CassieSimDiagram; PYBIND11_MODULE(simulators, m) { @@ -17,11 +21,16 @@ PYBIND11_MODULE(simulators, m) { using py_rvp = py::return_value_policy; - py::class_>(m, "CassieSimDiagram") - .def(py::init< - std::unique_ptr>, - const std::string&, bool, double, double, double>(), + .def(py::init( + [](drake::multibody::MultibodyPlant& plant, + const std::string& urdf, bool visualize, double mu, + double stiffness, double dissipation_rate) { + return std::make_unique( + make_unowned_shared_ptr_from_raw(&plant), urdf, visualize, + mu); + }), py::arg("plant"), py::arg("urdf"), py::arg("visualize"), py::arg("mu"), py::arg("stiffness"), py::arg("dissipation_rate")) .def("get_plant", &CassieSimDiagram::get_plant, diff --git a/bindings/pydairlib/systems/BUILD.bazel b/bindings/pydairlib/systems/BUILD.bazel index 986f5f7fd7..682a0d8053 100644 --- a/bindings/pydairlib/systems/BUILD.bazel +++ b/bindings/pydairlib/systems/BUILD.bazel @@ -47,6 +47,7 @@ pybind_py_library( "//lcmtypes:lcmt_robot", "//systems/framework:lcm_driven_loop", "//systems/framework:vector", + "@drake//bindings/pydrake/common:value_pybind", "@drake//:drake_shared_library", ], cc_so_name = "framework", diff --git a/bindings/pydairlib/systems/framework_py.cc b/bindings/pydairlib/systems/framework_py.cc index cbb5c45ddc..1453d99fde 100644 --- a/bindings/pydairlib/systems/framework_py.cc +++ b/bindings/pydairlib/systems/framework_py.cc @@ -9,22 +9,38 @@ #include "dairlib/lcmt_robot_output.hpp" +#include "drake/bindings/pydrake/pydrake_pybind.h" + namespace py = pybind11; namespace dairlib { namespace pydairlib { +using drake::pydrake::make_unowned_shared_ptr_from_raw; using LcmOutputDrivenLoop = systems::LcmDrivenLoop; PYBIND11_MODULE(framework, m) { py::class_(m, "LcmOutputDrivenLoop") - .def(py::init>, - const drake::systems::LeafSystem*, - const std::string&, bool>(), py::arg("drake_lcm"), - py::arg("diagram"), py::arg("lcm_parser"), - py::arg("input_channel"), py::arg("is_forced_publish")) + .def(py::init( + [](drake::lcm::DrakeLcm* drake_lcm, + drake::systems::Diagram& diagram, + const drake::systems::LeafSystem* lcm_parser, + const std::string& input_channel, bool is_forced_publish) { + // The C++ constructor doesn't offer a bare-pointer overload, + // only shared_ptr. Because object lifetime is already + // handled by the ref_cycle annotation below (as required for + // all subclasses of Diagram), we can pass the `plant` as an + // unowned shared_ptr. + // (comment taken from Drakes controllers_py.cc) + return std::make_unique( + drake_lcm, make_unowned_shared_ptr_from_raw(&diagram), + lcm_parser, input_channel, is_forced_publish); + + }), + py::arg("drake_lcm"), + py::arg("diagram"), py::arg("lcm_parser"), + py::arg("input_channel"), py::arg("is_forced_publish")) .def("Simulate", &LcmOutputDrivenLoop::Simulate, py::arg("end_time") = std::numeric_limits::infinity()); diff --git a/examples/Cassie/cassie_lcm_driven_loop.h b/examples/Cassie/cassie_lcm_driven_loop.h index 6f66495946..8059efa883 100644 --- a/examples/Cassie/cassie_lcm_driven_loop.h +++ b/examples/Cassie/cassie_lcm_driven_loop.h @@ -67,7 +67,7 @@ class CassieLcmDrivenLoop { /// @param input_channel The name of the input channel /// @param is_forced_publish A flag which enables publishing via diagram. CassieLcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, - std::unique_ptr> diagram, + std::shared_ptr> diagram, const drake::systems::LeafSystem* lcm_parser, const std::string& input_channel, bool is_forced_publish) : CassieLcmDrivenLoop(drake_lcm, std::move(diagram), lcm_parser, @@ -84,7 +84,7 @@ class CassieLcmDrivenLoop { /// @param switch_channel The name of the switch channel /// @param is_forced_publish A flag which enables publishing via diagram. CassieLcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, - std::unique_ptr> diagram, + std::shared_ptr> diagram, const drake::systems::LeafSystem* lcm_parser, std::vector input_channels, const std::string& active_channel, @@ -99,7 +99,7 @@ class CassieLcmDrivenLoop { } diagram_ptr_ = diagram.get(); simulator_ = - std::make_unique>(std::move(diagram)); + std::make_unique>(*diagram); // Create subscriber for the switch (in the case of multi-input) DRAKE_DEMAND(!input_channels.empty()); @@ -145,7 +145,7 @@ class CassieLcmDrivenLoop { /// @param is_forced_publish A flag which enables publishing via diagram. /// The use case is that the user only need the time from lcm message. CassieLcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, - std::unique_ptr> diagram, + std::shared_ptr> diagram, const std::string& input_channel, bool is_forced_publish) : CassieLcmDrivenLoop(drake_lcm, std::move(diagram), nullptr, std::vector(1, input_channel), diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.cc b/examples/Cassie/diagrams/cassie_sim_diagram.cc index 8c1b77e744..f1a7805310 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.cc +++ b/examples/Cassie/diagrams/cassie_sim_diagram.cc @@ -42,7 +42,7 @@ using Eigen::Vector3d; using Eigen::VectorXd; CassieSimDiagram::CassieSimDiagram( - std::unique_ptr> plant, + std::shared_ptr> plant, const std::string& urdf, bool visualize, double mu, double stiffness, double dissipation_rate) { DiagramBuilder builder; diff --git a/examples/Cassie/diagrams/cassie_sim_diagram.h b/examples/Cassie/diagrams/cassie_sim_diagram.h index e8ac694677..71ac801e16 100644 --- a/examples/Cassie/diagrams/cassie_sim_diagram.h +++ b/examples/Cassie/diagrams/cassie_sim_diagram.h @@ -21,7 +21,7 @@ class CassieSimDiagram : public drake::systems::Diagram { DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(CassieSimDiagram) /// @param[in] urdf filepath containing the osc_running_gains. - CassieSimDiagram(std::unique_ptr> plant, + CassieSimDiagram(std::shared_ptr> plant, const std::string& urdf = "examples/Cassie/urdf/cassie_v2.urdf", bool visualize = false, double mu = 0.8, double stiffness = 1e4, double dissipation_rate = 1e2); diff --git a/examples/Cassie/dispatcher_robot_in.cc b/examples/Cassie/dispatcher_robot_in.cc index 3993e9dba2..c7ac0dc607 100644 --- a/examples/Cassie/dispatcher_robot_in.cc +++ b/examples/Cassie/dispatcher_robot_in.cc @@ -27,6 +27,7 @@ namespace dairlib { using drake::lcm::Subscriber; using drake::systems::Context; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::TriggerType; @@ -188,7 +189,8 @@ int do_main(int argc, char* argv[]) { // Finish building the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name("dispatcher_robot_in"); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name("dispatcher_robot_in"); // Channel names of the controllers std::vector input_channels = {FLAGS_control_channel_name_initial, @@ -204,7 +206,7 @@ int do_main(int argc, char* argv[]) { // Run lcm-driven simulation CassieLcmDrivenLoop - loop(&lcm_local, std::move(owned_diagram), command_receiver, + loop(&lcm_local, shared_diagram, command_receiver, input_channels, FLAGS_control_channel_name_initial, switch_channel, true, FLAGS_state_channel_name); diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 8e39aa5b6e..40bead0670 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -46,6 +46,7 @@ using drake::geometry::SceneGraph; using drake::multibody::Frame; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -549,11 +550,12 @@ int DoMain(int argc, char* argv[]) { // Run lcm-driven simulation // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc_jumping_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("osc_jumping_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + &lcm, shared_diagram, state_receiver, FLAGS_channel_x, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 326ac862ad..7dbc9d67e5 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -51,6 +51,7 @@ using drake::geometry::SceneGraph; using drake::multibody::Frame; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -607,10 +608,11 @@ int DoMain(int argc, char* argv[]) { contact_scheduler_debug_publisher->get_input_port()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc_running_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("osc_running_controller")); systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + &lcm, shared_diagram, state_receiver, FLAGS_channel_x, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index 8a14671d1c..d3cbb68d43 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -40,6 +40,7 @@ using Eigen::VectorXd; using drake::geometry::SceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -285,11 +286,12 @@ int DoMain(int argc, char* argv[]) { // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name(("osc_standing_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("osc_standing_controller")); // Build lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, + &lcm_local, shared_diagram, state_receiver, FLAGS_channel_x, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index f5886d86ab..a7da518254 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -46,6 +46,7 @@ using Eigen::Vector3d; using Eigen::VectorXd; using drake::multibody::Frame; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -620,12 +621,13 @@ int DoMain(int argc, char* argv[]) { // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name("osc walking controller"); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name("osc walking controller"); // Run lcm-driven simulation - DrawAndSaveDiagramGraph(*owned_diagram); + DrawAndSaveDiagramGraph(*shared_diagram); systems::LcmDrivenLoop loop( - &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, + &lcm_local, shared_diagram, state_receiver, FLAGS_channel_x, true); loop.Simulate(); diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 613cf259dd..38e8b15902 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -49,6 +49,7 @@ using Eigen::Vector3d; using Eigen::VectorXd; using drake::multibody::Frame; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -618,11 +619,12 @@ int DoMain(int argc, char* argv[]) { // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name("osc walking controller"); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name("osc walking controller"); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, + &lcm_local, shared_diagram, state_receiver, FLAGS_channel_x, true); loop.Simulate(); diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 5953d4bb38..2156fe9e66 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -35,6 +35,7 @@ using drake::geometry::SceneGraph; using drake::multibody::Frame; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -206,11 +207,12 @@ int DoMain(int argc, char* argv[]) { // Run lcm-driven simulation // Create the diagram auto owned_diagram = builder.Build(); - owned_diagram->set_name(("id_walking_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("id_walking_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); + &lcm, shared_diagram, state_receiver, FLAGS_channel_x, true); loop.Simulate(); return 0; diff --git a/examples/sampling_c3/franka_osc_controller.cc b/examples/sampling_c3/franka_osc_controller.cc index fa7f7e08d7..58d92e699c 100644 --- a/examples/sampling_c3/franka_osc_controller.cc +++ b/examples/sampling_c3/franka_osc_controller.cc @@ -38,6 +38,7 @@ namespace dairlib { using drake::math::RigidTransform; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -258,11 +259,12 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("end_effector_force")); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("sampling_c3_franka_osc_controller")); - DrawAndSaveDiagramGraph(*owned_diagram); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("sampling_c3_franka_osc_controller")); + DrawAndSaveDiagramGraph(*shared_diagram); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, + &lcm, shared_diagram, state_receiver, lcm_channel_params.franka_state_channel, true); loop.Simulate(); return 0; diff --git a/examples/sampling_c3/franka_sampling_c3_controller.cc b/examples/sampling_c3/franka_sampling_c3_controller.cc index 7d8f6ddc3b..c04d641678 100644 --- a/examples/sampling_c3/franka_sampling_c3_controller.cc +++ b/examples/sampling_c3/franka_sampling_c3_controller.cc @@ -35,6 +35,7 @@ using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -485,8 +486,9 @@ int DoMain(int argc, char* argv[]) { // the latest messages are used in the control loop. See // https://github.com/DAIRLab/dairlib/pull/366 for more details. int lcm_buffer_size = 200; + std::shared_ptr> shared_diagram = std::move(owned_diagram); systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_state_receiver, + &lcm, shared_diagram, franka_state_receiver, lcm_channel_params.franka_state_channel, true, lcm_buffer_size); LcmHandleSubscriptionsUntil( &lcm, [&]() { return object_state_sub->GetInternalMessageCount() > 1; }); diff --git a/systems/framework/lcm_driven_loop.h b/systems/framework/lcm_driven_loop.h index ebac84b08d..7d42e49a9d 100644 --- a/systems/framework/lcm_driven_loop.h +++ b/systems/framework/lcm_driven_loop.h @@ -134,11 +134,11 @@ class LcmDrivenLoop { /// @param input_channel The name of the input channel /// @param is_forced_publish A flag which enables publishing via diagram. LcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, - std::unique_ptr> diagram, + std::shared_ptr> diagram, const drake::systems::LeafSystem* lcm_parser, const std::string& input_channel, bool is_forced_publish, int queue_capacity = 1) - : LcmDrivenLoop(drake_lcm, std::move(diagram), lcm_parser, + : LcmDrivenLoop(drake_lcm, diagram, lcm_parser, std::vector(1, input_channel), input_channel, "", is_forced_publish, queue_capacity){}; @@ -152,7 +152,7 @@ class LcmDrivenLoop { /// @param switch_channel The name of the switch channel /// @param is_forced_publish A flag which enables publishing via diagram. LcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, - std::unique_ptr> diagram, + std::shared_ptr> diagram, const drake::systems::LeafSystem* lcm_parser, std::vector input_channels, const std::string& active_channel, @@ -168,7 +168,7 @@ class LcmDrivenLoop { } diagram_ptr_ = diagram.get(); simulator_ = - std::make_unique>(std::move(diagram)); + std::make_unique>(*diagram); simulator_->set_publish_at_initialization(false); // Create subscriber for the switch (in the case of multi-input) @@ -214,9 +214,9 @@ class LcmDrivenLoop { /// @param is_forced_publish A flag which enables publishing via diagram. /// The use case is that the user only need the time from lcm message. LcmDrivenLoop(drake::lcm::DrakeLcm* drake_lcm, - std::unique_ptr> diagram, + std::shared_ptr> diagram, const std::string& input_channel, bool is_forced_publish) - : LcmDrivenLoop(drake_lcm, std::move(diagram), nullptr, + : LcmDrivenLoop(drake_lcm, diagram, nullptr, std::vector(1, input_channel), input_channel, "", is_forced_publish){}; @@ -393,7 +393,7 @@ class LcmDrivenLoop { drake::lcm::DrakeLcm* drake_lcm_; drake::systems::Diagram* diagram_ptr_; const drake::systems::LeafSystem* lcm_parser_; - std::unique_ptr> simulator_; + std::shared_ptr> simulator_; std::string diagram_name_ = "diagram"; std::string active_channel_; From fae4ba284ee6266d4c3b5f2717eb5953cd5a3609 Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Thu, 3 Jul 2025 08:43:17 -0700 Subject: [PATCH 750/758] Second sampling C3 example: push T (#384) * Push t example; working in sim * Bazel build file fixes * Fix sample perimeter projection to proper clearance * Consolidate duplicated lines for building contact pairs * Minor tuning for push T --- .../franka_sampling_c3_controller.cc | 53 +++++- examples/sampling_c3/generate_samples.cc | 62 +++---- examples/sampling_c3/generate_samples.h | 1 - examples/sampling_c3/goal_generator.cc | 8 +- examples/sampling_c3/goal_generator.h | 17 ++ examples/sampling_c3/jacktoy/BUILD.bazel | 1 - ..._hardware.pmd => franka_hardware_jack.pmd} | 0 ...ka_sim_jacktoy.pmd => franka_sim_jack.pmd} | 0 .../sampling_c3_controller_params.yaml | 2 +- .../jacktoy/parameters/sampling_params.yaml | 2 +- .../jacktoy/parameters/sim_params.yaml | 1 - examples/sampling_c3/push_t/BUILD.bazel | 76 ++++++++ .../sampling_c3/push_t/franka_hardware_t.pmd | 103 +++++++++++ examples/sampling_c3/push_t/franka_sim_t.pmd | 71 ++++++++ .../push_t/parameters/goal_params.yaml | 36 ++++ .../push_t/parameters/progress_params.yaml | 64 +++++++ .../push_t/parameters/reposition_params.yaml | 32 ++++ .../sampling_c3_controller_params.yaml | 23 +++ .../parameters/sampling_c3_options.yaml | 163 ++++++++++++++++++ .../push_t/parameters/sampling_params.yaml | 44 +++++ .../push_t/parameters/sim_params.yaml | 14 ++ .../push_t/parameters/vis_params.yaml | 37 ++++ .../{jack_ground.sdf => jack_control.sdf} | 0 examples/sampling_c3/urdf/push_t.sdf | 93 ++++++++++ examples/sampling_c3/urdf/push_t_control.sdf | 117 +++++++++++++ 25 files changed, 968 insertions(+), 52 deletions(-) rename examples/sampling_c3/jacktoy/{franka_hardware.pmd => franka_hardware_jack.pmd} (100%) rename examples/sampling_c3/jacktoy/{franka_sim_jacktoy.pmd => franka_sim_jack.pmd} (100%) create mode 100644 examples/sampling_c3/push_t/BUILD.bazel create mode 100644 examples/sampling_c3/push_t/franka_hardware_t.pmd create mode 100644 examples/sampling_c3/push_t/franka_sim_t.pmd create mode 100644 examples/sampling_c3/push_t/parameters/goal_params.yaml create mode 100644 examples/sampling_c3/push_t/parameters/progress_params.yaml create mode 100644 examples/sampling_c3/push_t/parameters/reposition_params.yaml create mode 100644 examples/sampling_c3/push_t/parameters/sampling_c3_controller_params.yaml create mode 100644 examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml create mode 100644 examples/sampling_c3/push_t/parameters/sampling_params.yaml create mode 100644 examples/sampling_c3/push_t/parameters/sim_params.yaml create mode 100644 examples/sampling_c3/push_t/parameters/vis_params.yaml rename examples/sampling_c3/urdf/{jack_ground.sdf => jack_control.sdf} (100%) create mode 100644 examples/sampling_c3/urdf/push_t.sdf create mode 100644 examples/sampling_c3/urdf/push_t_control.sdf diff --git a/examples/sampling_c3/franka_sampling_c3_controller.cc b/examples/sampling_c3/franka_sampling_c3_controller.cc index c04d641678..55db53192b 100644 --- a/examples/sampling_c3/franka_sampling_c3_controller.cc +++ b/examples/sampling_c3/franka_sampling_c3_controller.cc @@ -104,6 +104,8 @@ int DoMain(int argc, char* argv[]) { // Build the contact pairs based on the demo. std::vector>> contact_pairs; + std::vector> ee_contact_pairs; + std::vector> ground_object_contact_pairs; std::unordered_map contact_geoms; // All demos include the end effector and ground. @@ -117,7 +119,6 @@ int DoMain(int argc, char* argv[]) { contact_geoms["GROUND"] = ground_geoms; std::vector> ee_ground_contact{ SortedPair(contact_geoms["EE"], contact_geoms["GROUND"])}; - contact_pairs.push_back(ee_ground_contact); if (FLAGS_demo_name == "jacktoy") { drake::geometry::GeometryId capsule1_geoms = @@ -159,18 +160,13 @@ int DoMain(int argc, char* argv[]) { contact_geoms["CAPSULE_3_SPHERE_1"] = capsule3_sphere1_geoms; contact_geoms["CAPSULE_3_SPHERE_2"] = capsule3_sphere2_geoms; - // EE-object contact pairs second. - std::vector> ee_contact_pairs; ee_contact_pairs.push_back( SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_1"])); ee_contact_pairs.push_back( SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_2"])); ee_contact_pairs.push_back( SortedPair(contact_geoms["EE"], contact_geoms["CAPSULE_3"])); - contact_pairs.push_back(ee_contact_pairs); - // Object-ground contact pairs third. - std::vector> ground_object_contact_pairs; ground_object_contact_pairs.push_back(SortedPair( contact_geoms["CAPSULE_1_SPHERE_1"], contact_geoms["GROUND"])); ground_object_contact_pairs.push_back(SortedPair( @@ -183,11 +179,50 @@ int DoMain(int argc, char* argv[]) { contact_geoms["CAPSULE_3_SPHERE_1"], contact_geoms["GROUND"])); ground_object_contact_pairs.push_back(SortedPair( contact_geoms["CAPSULE_3_SPHERE_2"], contact_geoms["GROUND"])); - contact_pairs.push_back(ground_object_contact_pairs); + } + else if (FLAGS_demo_name == "push_t") { + drake::geometry::GeometryId vertical_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("vertical_link"))[0]; + drake::geometry::GeometryId horizontal_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("horizontal_link"))[0]; + + drake::geometry::GeometryId top_left_sphere_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("vertical_link"))[1]; + drake::geometry::GeometryId top_right_sphere_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("vertical_link"))[2]; + drake::geometry::GeometryId bottom_sphere_geoms = + plant_lcs.GetCollisionGeometriesForBody( + plant_lcs.GetBodyByName("vertical_link"))[3]; + + contact_geoms["VERTICAL_LINK"] = vertical_geoms; + contact_geoms["HORIZONTAL_LINK"] = horizontal_geoms; + contact_geoms["TOP_LEFT_SPHERE"] = top_left_sphere_geoms; + contact_geoms["TOP_RIGHT_SPHERE"] = top_right_sphere_geoms; + contact_geoms["BOTTOM_SPHERE"] = bottom_sphere_geoms; + + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["HORIZONTAL_LINK"])); + ee_contact_pairs.push_back( + SortedPair(contact_geoms["EE"], contact_geoms["VERTICAL_LINK"])); + + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["TOP_LEFT_SPHERE"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["TOP_RIGHT_SPHERE"], contact_geoms["GROUND"])); + ground_object_contact_pairs.push_back(SortedPair( + contact_geoms["BOTTOM_SPHERE"], contact_geoms["GROUND"])); } else { throw std::runtime_error("Unknown --demo_name value: " + FLAGS_demo_name); } + // Order: EE-ground, EE-object, object-ground. + contact_pairs.push_back(ee_ground_contact); + contact_pairs.push_back(ee_contact_pairs); + contact_pairs.push_back(ground_object_contact_pairs); // Piece together the diagram. DiagramBuilder builder; @@ -215,6 +250,10 @@ int DoMain(int argc, char* argv[]) { target_generator = std::make_unique( plant_object, controller_params.goal_params); + } else if (FLAGS_demo_name == "push_t") { + target_generator = + std::make_unique( + plant_object, controller_params.goal_params); } else { throw std::runtime_error("Unknown --demo_name value: " + FLAGS_demo_name); } diff --git a/examples/sampling_c3/generate_samples.cc b/examples/sampling_c3/generate_samples.cc index aef8173625..62af91711b 100644 --- a/examples/sampling_c3/generate_samples.cc +++ b/examples/sampling_c3/generate_samples.cc @@ -238,7 +238,6 @@ Eigen::Vector3d PerimeterSampling( double z_sample = 0; // Convert to world frame using the current object state. - Eigen::VectorXd x_lcs_world = x_lcs; Eigen::Quaterniond quat_object(x_lcs(3), x_lcs(4), x_lcs(5), x_lcs(6)); Eigen::Vector3d object_position = x_lcs.segment(7, 3); candidate_state = x_lcs; @@ -249,19 +248,19 @@ Eigen::Vector3d PerimeterSampling( // Project samples to specified sampling height in world frame. candidate_state[2] = sampling_params.sampling_height; } while (!IsSampleWithinDistanceOfSurface( - n_q, n_v, n_u, 0.0, false, candidate_state, plant, context, plant_ad, - context_ad, contact_geoms, sampling_c3_options, min_distance_index)); + n_q, n_v, n_u, 0.0, candidate_state, plant, context, plant_ad, context_ad, + contact_geoms, sampling_c3_options, min_distance_index)); // Project the sample past the surface of the object with clearance. Eigen::VectorXd projected_state = ProjectSampleOutsideObject( - candidate_state, min_distance_index, sampling_params, plant, *context, - contact_geoms); + candidate_state, min_distance_index, sampling_params, plant, *context, + contact_geoms); // Check the desired clearance is satisfied; otherwise try again. UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, projected_state); if (IsSampleWithinDistanceOfSurface( - n_q, n_v, n_u, sampling_params.sample_projection_clearance, true, + n_q, n_v, n_u, sampling_params.sample_projection_clearance, projected_state, plant, context, plant_ad, context_ad, contact_geoms, sampling_c3_options, min_distance_index)) { continue; @@ -333,8 +332,8 @@ Eigen::Vector3d ShellSampling( y_samplec + sampling_radius * sin(theta) * sin(elevation_theta); candidate_state[2] = z_samplec + sampling_radius * cos(elevation_theta); } while (!IsSampleWithinDistanceOfSurface( - n_q, n_v, n_u, 0.0, false, candidate_state, plant, context, plant_ad, - context_ad, contact_geoms, sampling_c3_options, min_distance_index)); + n_q, n_v, n_u, 0.0, candidate_state, plant, context, plant_ad, context_ad, + contact_geoms, sampling_c3_options, min_distance_index)); // Project the sample past the surface of the object with clearance. Eigen::VectorXd projected_state = ProjectSampleOutsideObject( @@ -345,7 +344,7 @@ Eigen::Vector3d ShellSampling( UpdateContext(n_q, n_v, n_u, plant, context, plant_ad, context_ad, projected_state); if (IsSampleWithinDistanceOfSurface( - n_q, n_v, n_u, sampling_params.sample_projection_clearance, true, + n_q, n_v, n_u, sampling_params.sample_projection_clearance, projected_state, plant, context, plant_ad, context_ad, contact_geoms, sampling_c3_options, min_distance_index)) { continue; @@ -390,7 +389,8 @@ double GetEERadiusFromPlant( query_port.template Eval>(context); const auto& inspector = query_object.inspector(); - // Locate the EE and obtain its radius. + // Locate the EE and obtain its radius. The first set of contact geoms has + // the EE and ground. GeometryId ee_geom_id = contact_geoms.at(0).at(0).first(); const drake::geometry::Shape& shape = inspector.GetShape(ee_geom_id); const auto* sphere = dynamic_cast(&shape); @@ -403,15 +403,14 @@ double GetEERadiusFromPlant( bool IsSampleWithinDistanceOfSurface( const int& n_q, const int& n_v, const int& n_u, const double& clearance_distance, - const bool& factor_in_ee_radius, const Eigen::VectorXd& candidate_state, drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, drake::multibody::MultibodyPlant& plant_ad, drake::systems::Context* context_ad, const std::vector< - std::vector>>& - contact_geoms, + std::vector>>& + contact_geoms, SamplingC3Options sampling_c3_options, int& min_distance_index) { @@ -421,14 +420,12 @@ bool IsSampleWithinDistanceOfSurface( // Find the closest pair if there are multiple pairs std::vector distances; - - for (int i = 0; i < contact_geoms.at(0).size(); i++) { - // Evaluate the distance for each pair - SortedPair pair{(contact_geoms.at(0)).at(i)}; + for (int i = 0; i < contact_geoms.at(1).size(); i++) { + SortedPair pair{(contact_geoms.at(1)).at(i)}; multibody::GeomGeomCollider collider(plant, pair); auto [phi_i, J_i] = collider.EvalPolytope( - *context, sampling_c3_options.num_friction_directions); + *context, sampling_c3_options.num_friction_directions); distances.push_back(phi_i); } @@ -439,15 +436,8 @@ bool IsSampleWithinDistanceOfSurface( min_distance_index = std::distance(distances.begin(), min_distance_it); double min_distance = *min_distance_it; - // Factor the EE radius into the clearance distance if requested. - double ee_radius_contribution = 0.0; - if (factor_in_ee_radius) { - ee_radius_contribution = GetEERadiusFromPlant( - plant, *context, contact_geoms); - } - // Require that min_distance be at least 1 mm within the clearance distance. - return min_distance <= clearance_distance + ee_radius_contribution - 1e-3; + return min_distance <= clearance_distance - 1e-3; } Eigen::VectorXd ProjectSampleOutsideObject( @@ -462,22 +452,22 @@ Eigen::VectorXd ProjectSampleOutsideObject( // Compute the witness points between the penetrating sample and the object // surface. multibody::GeomGeomCollider collider( - plant, contact_geoms.at(0).at(min_distance_index)); - auto [p_world_contact_a, p_world_contact_b] = collider.CalcWitnessPoints( + plant, contact_geoms.at(1).at(min_distance_index)); + auto [p_world_contact_ee, p_world_contact_obj] = collider.CalcWitnessPoints( context); // Get the EE radius to factor into the projection. double ee_radius = GetEERadiusFromPlant(plant, context, contact_geoms); - // Find vector in direction from sample to contact point on object. - Eigen::Vector3d a_to_b = p_world_contact_b - p_world_contact_a; - Eigen::Vector3d a_to_b_normalized = a_to_b.normalized(); - // Add clearance to point b in the same direction. - Eigen::Vector3d p_world_contact_b_clearance = - p_world_contact_b + + // Find vector in direction from EE to object witness points. + Eigen::Vector3d ee_to_obj = p_world_contact_obj - p_world_contact_ee; + Eigen::Vector3d ee_to_obj_normalized = ee_to_obj.normalized(); + // Add clearance to the object in the same direction. + Eigen::Vector3d p_world_contact_obj_clearance = + p_world_contact_obj + (ee_radius + sampling_params.sample_projection_clearance) * - a_to_b_normalized; - candidate_state.head(3) = p_world_contact_b_clearance; + ee_to_obj_normalized; + candidate_state.head(3) = p_world_contact_obj_clearance; return candidate_state; } diff --git a/examples/sampling_c3/generate_samples.h b/examples/sampling_c3/generate_samples.h index 75c2015ff6..fae0086319 100644 --- a/examples/sampling_c3/generate_samples.h +++ b/examples/sampling_c3/generate_samples.h @@ -129,7 +129,6 @@ bool IsSampleWithinDistanceOfSurface( const int& n_v, const int& n_u, const double& clearance_distance, - const bool& factor_in_ee_radius, const Eigen::VectorXd& candidate_state, drake::multibody::MultibodyPlant& plant, drake::systems::Context* context, diff --git a/examples/sampling_c3/goal_generator.cc b/examples/sampling_c3/goal_generator.cc index 3bd1b51295..3a1ac790a2 100644 --- a/examples/sampling_c3/goal_generator.cc +++ b/examples/sampling_c3/goal_generator.cc @@ -164,10 +164,10 @@ void SamplingC3GoalGenerator::SetRandomizedTargetFinalObjectPosition() const { double x, y = 0; while ((sqrt(x * x + y * y) > goal_params_.random_goal_radius_limits[1]) || (sqrt(x * x + y * y) < goal_params_.random_goal_radius_limits[0])) { - double x = RandomUniform(goal_params_.random_goal_x_limits[0], - goal_params_.random_goal_x_limits[1]); - double y = RandomUniform(goal_params_.random_goal_y_limits[0], - goal_params_.random_goal_y_limits[1]); + x = RandomUniform(goal_params_.random_goal_x_limits[0], + goal_params_.random_goal_x_limits[1]); + y = RandomUniform(goal_params_.random_goal_y_limits[0], + goal_params_.random_goal_y_limits[1]); } target_final_object_position_ << x, y, goal_params_.resting_object_height; diff --git a/examples/sampling_c3/goal_generator.h b/examples/sampling_c3/goal_generator.h index ab14511a5b..e70f0f4d9e 100644 --- a/examples/sampling_c3/goal_generator.h +++ b/examples/sampling_c3/goal_generator.h @@ -38,6 +38,11 @@ inline const std::vector kNominalOrientationsJack{ kQuatAllUp, kQuatRedDown, kQuatBlueUp, kQuatAllDown, kQuatGreenUp, kQuatBlueDown, kQuatRedUp, kQuatGreenDown}; +// Define the nominal orientations for any planar demo. +inline const Eigen::Quaterniond kQUAT_FLAT{1.0, 0.0, 0.0, 0.0}; +inline const std::vector kNominalOrientationsPlanar{ + kQUAT_FLAT}; + namespace dairlib { namespace systems { @@ -137,5 +142,17 @@ class SamplingC3GoalGeneratorJacktoy : public SamplingC3GoalGenerator { object_plant, goal_params, kNominalOrientationsJack) {} }; + +// class TargetGeneratorPushT : public TargetGenerator { +class SamplingC3GoalGeneratorPushT : public SamplingC3GoalGenerator { + public: + SamplingC3GoalGeneratorPushT( + const drake::multibody::MultibodyPlant& object_plant, + const SamplingC3GoalParams& goal_params) : + SamplingC3GoalGenerator( + object_plant, goal_params, kNominalOrientationsPlanar) {} +}; + + } // namespace systems } // namespace dairlib diff --git a/examples/sampling_c3/jacktoy/BUILD.bazel b/examples/sampling_c3/jacktoy/BUILD.bazel index aea0f689a3..faec88ea69 100644 --- a/examples/sampling_c3/jacktoy/BUILD.bazel +++ b/examples/sampling_c3/jacktoy/BUILD.bazel @@ -10,7 +10,6 @@ cc_library( ]), ) - cc_library( name = "lcm_channels_jacktoy", hdrs = [], diff --git a/examples/sampling_c3/jacktoy/franka_hardware.pmd b/examples/sampling_c3/jacktoy/franka_hardware_jack.pmd similarity index 100% rename from examples/sampling_c3/jacktoy/franka_hardware.pmd rename to examples/sampling_c3/jacktoy/franka_hardware_jack.pmd diff --git a/examples/sampling_c3/jacktoy/franka_sim_jacktoy.pmd b/examples/sampling_c3/jacktoy/franka_sim_jack.pmd similarity index 100% rename from examples/sampling_c3/jacktoy/franka_sim_jacktoy.pmd rename to examples/sampling_c3/jacktoy/franka_sim_jack.pmd diff --git a/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml b/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml index 38ad1b11dc..da0a74987f 100644 --- a/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml +++ b/examples/sampling_c3/jacktoy/parameters/sampling_c3_controller_params.yaml @@ -15,7 +15,7 @@ lcm_channels_simulation_file: examples/sampling_c3/shared_parameters/lcm_channel # Note: Use capsule_1 body name as representative of the pose of the entire # jack model. This works because capsule_1's origin is the same as the jack's. -object_model: examples/sampling_c3/urdf/jack_ground.sdf +object_model: examples/sampling_c3/urdf/jack_control.sdf object_body_name: capsule_1 include_end_effector_orientation: false diff --git a/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml b/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml index 3e84da937d..4c0c606a56 100644 --- a/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml +++ b/examples/sampling_c3/jacktoy/parameters/sampling_params.yaml @@ -19,7 +19,7 @@ num_additional_samples_repos: 1 num_additional_samples_c3: 2 # Sample buffer parameters. -consider_best_buffer_sample_when_leaving_c3: false +consider_best_buffer_sample_when_leaving_c3: true N_sample_buffer: 100 pos_error_sample_retention: 0.005 ang_error_sample_retention: 0.087 # 0.087 rad = 5 deg diff --git a/examples/sampling_c3/jacktoy/parameters/sim_params.yaml b/examples/sampling_c3/jacktoy/parameters/sim_params.yaml index cac1c35d90..2f38315515 100644 --- a/examples/sampling_c3/jacktoy/parameters/sim_params.yaml +++ b/examples/sampling_c3/jacktoy/parameters/sim_params.yaml @@ -10,6 +10,5 @@ publish_efforts: true dt: 0.0001 realtime_rate: 1 -# Set the initial locations to something more vertical: q_init_franka: [2.191, 1.1, -1.33, -2.22, 1.30, 2.02, 0.08] q_init_object: [-0.3347435, -0.026718954, 0.8878204, 0.31518626, 0.4, 0.30, 0.03] diff --git a/examples/sampling_c3/push_t/BUILD.bazel b/examples/sampling_c3/push_t/BUILD.bazel new file mode 100644 index 0000000000..bd09516749 --- /dev/null +++ b/examples/sampling_c3/push_t/BUILD.bazel @@ -0,0 +1,76 @@ +# -*- mode: python -*- +# vi: set ft=python : + +package(default_visibility = ["//visibility:public"]) + +cc_library( + name = "parameters", + data = glob([ + "parameters/*.yaml", + ]), +) + +cc_library( + name = "lcm_channels_push_t", + hdrs = [], + data = [ + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//examples/sampling_c3/parameter_headers:lcm_channels", + "//systems/framework:vector", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_sim_params_push_t", + hdrs = [], + data = [ + "parameters/sim_params.yaml", + ], + deps = [ + "//examples/sampling_c3/parameter_headers:franka_sim_params", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "sampling_c3_controller_params_push_t", + hdrs = [], + data = [ + "parameters/sampling_c3_controller_params.yaml", + "parameters/sampling_params.yaml", + "//examples/sampling_c3:shared_params_yamls", + ], + deps = [ + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "goal_params_push_t", + hdrs = [], + data = [ + "parameters/goal_params.yaml", + ], + deps = [ + "//examples/sampling_c3/parameter_headers:goal_params", + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) + +cc_library( + name = "franka_drake_lcm_driver_channels_push_t", + hdrs = [], + data = [ + "//common/parameters:franka_drake_lcm_driver_channels", + ], + deps = [ + "//common/parameters:franka_drake_lcm_driver_channels", + "//solvers:c3", + "@drake//:drake_shared_library", + ], +) diff --git a/examples/sampling_c3/push_t/franka_hardware_t.pmd b/examples/sampling_c3/push_t/franka_hardware_t.pmd new file mode 100644 index 0000000000..9c953335da --- /dev/null +++ b/examples/sampling_c3/push_t/franka_hardware_t.pmd @@ -0,0 +1,103 @@ +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/sampling_c3/franka_visualizer --is_simulation=false --demo_name=push_t"; + host = "sampling_c3_localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/sampling_c3/xbox_script"; + host = "sampling_c3_localhost"; + } + cmd "logger" { + exec = "python3 examples/sampling_c3/start_logging.py hw push_t"; + host = "sampling_c3_localhost"; + } + cmd "record_video" { + exec = "python3 record_video.py"; + host = "franka_control"; + } +} + +group "controllers (hardware)" { + cmd "sampling_c3" { + exec = "bazel-bin/examples/sampling_c3/franka_sampling_c3_controller --is_simulation=false --demo_name=push_t; + host = "sampling_c3_localhost"; + } + cmd "franka_osc" { + exec = "bazel-bin/examples/sampling_c3/franka_osc_controller --is_simulation=false --demo_name=push_t --lcm_url=udpm://239.255.76.67:7667?ttl=1; + host = "franka_control"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "sampling_c3_localhost"; + } +} + +group "drivers" { + cmd "move_to_init" { + exec = "bazel-bin/examples/sampling_c3/franka_joint_osc_controller --is_simulation=false --demo_name=push_t"; + host = "franka_control"; + } + cmd "franka_driver_out" { + exec = "bazel-bin/examples/sampling_c3/franka_bridge_driver_out --demo_name=push_t"; + host = "franka_control"; + } + cmd "franka_driver_in" { + exec = "bazel-bin/examples/sampling_c3/franka_bridge_driver_in --demo_name=push_t"; + host = "franka_control"; + } + cmd "torque_driver" { + exec = "bazel-bin/franka-driver/franka_driver_v4 --robot_ip_address=172.16.0.2 --control_mode=torque"; + host = "drake_franka_driver"; + } +} + + +script "init_experiment" { + stop cmd "sampling_c3"; + stop cmd "franka_osc"; + stop cmd "franka_driver_out"; + stop cmd "franka_driver_in"; + stop cmd "torque_driver"; + wait ms 1000; + start cmd "franka_driver_out"; + start cmd "franka_driver_in"; + start cmd "torque_driver"; + start cmd "move_to_init"; + wait ms 10000; + stop group "drivers"; +} + +script "start_experiment" { + restart cmd "xbox"; + stop cmd "franka_driver_out"; + stop cmd "franka_driver_in"; + stop cmd "torque_driver"; + stop cmd "franka_osc"; + start cmd "record_video"; + start cmd "logger"; + wait ms 1000; + start cmd "franka_driver_out"; + start cmd "franka_driver_in"; + start cmd "torque_driver"; + start cmd "move_to_init"; + wait ms 5000; + stop cmd "move_to_init"; + start cmd "franka_osc"; + start cmd "sampling_c3"; +} + +script "start_operator_commands" { + restart cmd "visualizer"; + restart cmd "xbox"; + restart cmd "lcm-spy"; +} + +script "stop_experiment" { + stop group "drivers"; + stop group "controllers (hardware)"; + stop cmd "record_video"; + stop cmd "logger"; +} diff --git a/examples/sampling_c3/push_t/franka_sim_t.pmd b/examples/sampling_c3/push_t/franka_sim_t.pmd new file mode 100644 index 0000000000..420b50d58e --- /dev/null +++ b/examples/sampling_c3/push_t/franka_sim_t.pmd @@ -0,0 +1,71 @@ +group "simulations" { + cmd "franka_sim" { + exec = "bazel-bin/examples/sampling_c3/franka_sim --demo_name=push_t"; + host = "localhost"; + } +} + +group "operator" { + cmd "visualizer" { + exec = "bazel-bin/examples/sampling_c3/franka_visualizer --is_simulation=true --demo_name=push_t"; + host = "localhost"; + } + cmd "drake-director" { + exec = "bazel-bin/director/drake-director"; + host = "localhost"; + } + cmd "xbox" { + exec = "bazel-bin/examples/sampling_c3/xbox_script"; + host = "localhost"; + } + cmd "start_logging" { + exec = "python3 examples/sampling_c3/start_logging.py sim push_t"; + host = "localhost"; + } +} + +group "controllers" { + cmd "move_to_init" { + exec = "bazel-bin/examples/sampling_c3/franka_joint_osc_controller --is_simulation=true --demo_name=push_t"; + host = "localhost"; + } + cmd "franka_osc" { + exec = "bazel-bin/examples/sampling_c3/franka_osc_controller --is_simulation=true --demo_name=push_t"; + host = "localhost"; + } + cmd "sampling_c3" { + exec = "bazel-bin/examples/sampling_c3/franka_sampling_c3_controller --is_simulation=true --demo_name=push_t"; + host = "localhost"; + } +} + +group "debug" { + cmd "lcm-spy" { + exec = "bazel-bin/lcmtypes/dair-lcm-spy"; + host = "localhost"; + } +} + +script "start_experiment_no_logs"{ + stop cmd "start_logging"; + restart cmd "franka_sim"; + restart cmd "franka_osc"; + wait ms 50; + restart cmd "sampling_c3"; +} + +script "start_experiment_with_logs"{ + restart cmd "start_logging"; + restart cmd "franka_sim"; + restart cmd "franka_osc"; + wait ms 50; + restart cmd "sampling_c3"; +} + +script "end_experiment"{ + stop cmd "sampling_c3"; + stop cmd "franka_osc"; + stop cmd "franka_sim"; + wait ms 10; + stop cmd "start_logging"; +} diff --git a/examples/sampling_c3/push_t/parameters/goal_params.yaml b/examples/sampling_c3/push_t/parameters/goal_params.yaml new file mode 100644 index 0000000000..f4c7785eb5 --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/goal_params.yaml @@ -0,0 +1,36 @@ +# Goal mode options (defined as GoalMode enum in goal_params.h): +# 0. kRandom: randomly generate a new goal. +# 1. kOrientationSequence: keep position goal the same, and cycle through a +# sequence of orientations. +# 2. kFixedGoal: keep the same goal. +goal_mode: 0 + +### Parameters used for multiple goal modes. +# Success thresholds for position and orientation. +position_success_threshold: 0.02 +orientation_success_threshold: 0.1 # 0.1 rad = 5.7 degrees + +resting_object_height: -0.009 # in world frame +ee_target_z_offset_above_object: 0.06 # defines EE goal w.r.t. object position + +# Lookahead parameters to define a sub-goal for C3. +lookahead_step_size: 0.15 # meters +lookahead_angle: 2 # rad + +# Apply hysteresis on the lookahead angle so the sub-goal orientation doesn't +# flip back and forth near the 180 degree error singularity. A lower number +# means the sub-goal orientation can switch more often; a higher number means +# the sub-goal orientation is more stable but possibly less optimal. +angle_hysteresis: 0.4 + +# Factor to convert an angular error to angular velocity command (0=disabled). +angle_err_to_vel_factor: 0 + +# Initial goal (and only goal for fixed goal mode). +fixed_target_position: [0.48199167, 0.18745379, -0.009] +fixed_target_orientation: [-0.9327733, 0, 0, 0.36046353] + +# Random-specific parameters. +random_goal_x_limits: [0.44, 0.52] +random_goal_y_limits: [0.02, 0.25] +random_goal_radius_limits: [0.5, 0.52] diff --git a/examples/sampling_c3/push_t/parameters/progress_params.yaml b/examples/sampling_c3/push_t/parameters/progress_params.yaml new file mode 100644 index 0000000000..48609fc7d6 --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/progress_params.yaml @@ -0,0 +1,64 @@ +# Ways of computing C3 costs after solving the MPC problem (defined as +# C3CostComputationType enum in c3_options.h): +# 0. kSimLCS: Simulate the LCS dynamics from the planned +# inputs. +# 1. kUseC3Plan: Use the C3 planned trajectory and inputs. +# 2. kSimLCSReplaceC3EEPlan: Simulate the LCS dynamics from the planned +# inputs only for the object; use the planned +# EE trajectory. +# 3. kSimImpedance: Try to emulate the real cost of the system +# associated not only applying the planned +# inputs, but also tracking the planned EE +# trajectory with an impedance controller. +# 4. kSimImpedanceReplaceC3EEPlan: The same as kSimImpedance except the EE +# states are replaced with the plan from C3 +# at the end. +# 5. kSimImpedanceObjectCostOnly: The same as kSimImpedance except only the +# object terms contribute to the final cost. +cost_type: 5 +cost_type_position: 5 + +# Progress metric to use to determine if C3 is making progress, all phrased as +# improvement requirements over a number of control loops (defined as +# ProgressMetric enum in progress_params.h) +# 0. kC3Cost: C3 cost. +# 1. kConfigCost: Current object configuration cost. +# 2. kPosOrRotCost: Current position or rotation error. +# 3. kConfigCostDrop: Drop in object configuration cost (this is the same as +# kConfigCost if the required drop is 0; a more +# aggressive drop cuts C3 off earlier). +track_c3_progress_via: 3 + +# Ignore orientation errors when object is beyond this threshold from the goal. +cost_switching_threshold_distance: 0.50 + +# Penalize repositioning distance. +travel_cost_per_meter: 0 + +# Number of control loops to wait before cutting off C3 due to unproductivity. +# Used for kC3Cost, kConfigCost, kPosOrRotCost. +num_control_loops_to_wait: 5 +num_control_loops_to_wait_position: 5 + +# kConfigCostDrop parameters. +progress_enforced_cost_drop: 0.01 +progress_enforced_over_n_loops: 28 + +### Hysteresis parameters for switching between C3 and repositioning modes. +finished_reposition_cost: 1000000000 + +hyst_c3_to_repos: 300000 +hyst_c3_to_repos_position: 300000 +hyst_repos_to_c3: 200000 +hyst_repos_to_c3_position: 200000 +hyst_repos_to_repos: 60000000000000 +hyst_repos_to_repos_position: 60000000000000 + +# Relative hysteresis is in terms of a fraction of the current cost. +use_relative_hysteresis: true +hyst_c3_to_repos_frac: 0.4 +hyst_c3_to_repos_frac_position: 0.6 +hyst_repos_to_c3_frac: 0.9 +hyst_repos_to_c3_frac_position: 0.5 +hyst_repos_to_repos_frac: 0.3 +hyst_repos_to_repos_frac_position: 0.1 diff --git a/examples/sampling_c3/push_t/parameters/reposition_params.yaml b/examples/sampling_c3/push_t/parameters/reposition_params.yaml new file mode 100644 index 0000000000..faaf08b02b --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/reposition_params.yaml @@ -0,0 +1,32 @@ +# Repositioning trajectory type options (defined as RepositioningTrajectoryType +# enum in reposition_params.h): +# 0. kSpline: move from current to target with spline that distorts +# around the object. +# 1. kSpherical: move away from object to a radius, along the spherical +# surface to outside target, then in to target. +# 2. kCircular: (planar) move away from object to a planar radius, +# along the circle to outside target, then in to target. +# 3. kPiecewiseLinear: move up to waypoint height, over to above target, then +# down. +traj_type: 3 + +### Parameters used for multiple repositioning trajectory types. +speed: 0.18 # m/s + +# Thresholds for switching to straight line trajectories. +use_straight_line_traj_under_spline: 0.12 # xyz meters for spline +use_straight_line_traj_within_angle: 0.3 # rad for circle/sphere +use_straight_line_traj_under_piecewise_linear: 0.008 # xy meters for PWL + +# Spline-specific parameters. +spline_width: 0.17 + +# Spherical-specific parameters. +sphere_radius: 0.18 + +# Circular-specific parameters. +circle_radius: 0.20 +circle_height: 0.00 + +# Piecewise-linear-specific parameters. +pwl_waypoint_height: 0.06 diff --git a/examples/sampling_c3/push_t/parameters/sampling_c3_controller_params.yaml b/examples/sampling_c3/push_t/parameters/sampling_c3_controller_params.yaml new file mode 100644 index 0000000000..7977849b5b --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/sampling_c3_controller_params.yaml @@ -0,0 +1,23 @@ +sampling_c3_options_file: examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml +reposition_params_file: examples/sampling_c3/push_t/parameters/reposition_params.yaml +progress_params_file: examples/sampling_c3/push_t/parameters/progress_params.yaml +sampling_params_file: examples/sampling_c3/push_t/parameters/sampling_params.yaml +goal_params_file: examples/sampling_c3/push_t/parameters/goal_params.yaml + +sim_params_file: examples/sampling_c3/push_t/parameters/sim_params.yaml +vis_params_file: examples/sampling_c3/push_t/parameters/vis_params.yaml +osc_params_file: examples/sampling_c3/shared_parameters/osc_params.yaml +osqp_settings_file: examples/sampling_c3/shared_parameters/sampling_c3_qp_settings.yaml +osc_qp_settings_file: examples/sampling_c3/shared_parameters/osc_qp_settings.yaml +franka_driver_channels_file: common/parameters/franka_drake_lcm_driver_channels.yaml +lcm_channels_hardware_file: examples/sampling_c3/shared_parameters/lcm_channels_hardware.yaml +lcm_channels_simulation_file: examples/sampling_c3/shared_parameters/lcm_channels_simulation.yaml + +# Note: Use vertical_link body name as representative of the pose of the entire +# T model. This works because vertical_link's origin is the same as the T's. +object_model: examples/sampling_c3/urdf/push_t_control.sdf #TODO T_vertical.sdf +object_body_name: vertical_link + +include_end_effector_orientation: false + +control_loop_delay_ms: 0 diff --git a/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml b/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml new file mode 100644 index 0000000000..c60e0c76b9 --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml @@ -0,0 +1,163 @@ +### C3 options +admm_iter: 3 +rho: 0 #This isn't used anywhere! +rho_scale: 3 +num_threads: 5 +num_outer_threads: 4 +delta_option: 1 +projection_type: 'MIQP' # 'MIQP' or 'QP' +contact_model: 'anitescu' # 'stewart_and_trinkle' or 'anitescu'. +warm_start: false +end_on_qp_step: false +use_robust_formulation: false +solve_time_filter_alpha: 0.95 +publish_frequency: 0 +penalize_changes_in_u_across_solves: false # Penalize (u-u_prev) instead of u. +num_friction_directions: 2 + +N: 5 +gamma: 1.0 # discount factor on MPC costs + +# As alpha -> 0, any complimentarity constraint error in QP projection -> 0. +qp_projection_alpha: 0.01 +qp_projection_scaling: 1 + +### Limits +# Workspace limits specified as linear constraints [x, y, z, lb, ub] +workspace_limits: [[1, 0, 0, 0.15, 0.75], + [0, 1, 0, -0.6, 0.6], + [0, 0, 1, -0.01, 0.3]] +robot_radius_limits: [0.25, 0.75] +workspace_margins: 0.02 +u_horizontal_limits: [-50, 50] +u_vertical_limits: [-50, 50] + +### Whether to use a predicted EE location for each mode. +use_predicted_x0_c3: true +use_predicted_x0_repos: true +use_predicted_x0_reset_mechanism: false # Resets if prediction is too far. + +### Push-T demo specific parameters: +# Contact pairs include a number of (ee-ground, ee-T, T-ground). +mu_per_pair_type: [0.4165, 1, 0.4615] # match URDFs with (2mu1*mu2)/(mu1+mu2) +resolve_contacts_to_lists: [[0, 1, 3], + [0, 2, 3]] + +# Index into this list to choose number of contacts for C3 solve and cost. +num_contacts_index: 0 +num_contacts_index_for_cost: 1 + +planning_dt_position: 0.1 +planning_dt_pose: 0.05 + +### Cost parameters +### If list of lists, then index into them with num_contact_index(_for_cost). +# Set 4x4 portion of Q for quaternion based on current and desired quaternion. +use_quaternion_dependent_cost: true +q_quaternion_dependent_weight: 1000 +q_quaternion_dependent_regularizer_fraction: 0 + +Kp_for_ee_pd_rollout: 100 +Kd_for_ee_pd_rollout: 0.5 + +### Pose tracking cost parameters +# Matrix scaling +w_Q: 45 +w_R: 1 +w_G: 0.25 +w_U: 0.26 + +q_vector: [0.01, 0.01, 0.01, # EE position + 0.1, 0.1, 0.1, 0.1, # object orientation + 200, 200, 120, # object position + 5, 5, 5, # EE linear velocity + 0.05, 0.05, 0.05, # object angular velocity + 0.05, 0.05, 0.05] # object linear velocity +r_vector: [0.01, 0.01, 0.01] + +# Penalty on matching projected variables +g_x: [950, 950, 950, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +g_lambda_n_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +g_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_list: [[0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] #, +g_u: [30, 30, 30] + +# Penalty on matching the QP variables +u_x: [10, 10, 10, 100, 100, 100, 100, 10, 10, 10, 8, 8, 8, 1, 1, 1, 1, 1, 1] +u_gamma_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +u_lambda_n_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +u_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +# u_lambda_list is not used for the QP projection; overwritten by alpha*F. +u_lambda_list: [[10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_u: [0.01, 0.01, 0.01] + +### Position tracking cost parameters +# Matrix scaling +w_Q_position: 45 +w_R_position: 1 +w_G_position: 0.25 +w_U_position: 0.26 + +q_vector_position: [0.01, 0.01, 0.01, # EE position + 0.1, 0.1, 0.1, 0.1, # object orientation + 250, 250, 250, # object position + 5, 5, 5, # EE linear velocity + 0.05, 0.05, 0.05, # object angular velocity + 0.05, 0.05, 0.05] # object linear velocity +r_vector_position: [0.01, 0.01, 0.01] + +# Penalty on matching projected variables +g_x_position: [900, 900, 900, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] +g_gamma_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +g_lambda_n_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +g_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_position_list: [ + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] +g_u_position: [30, 30, 30] + +# Penalty on matching the QP variables +u_x_position: [10, 10, 10, 100, 100, 100, 100, 10, 10, 10, 8, 8, 8, 1, 1, 1, 1, 1, 1] +u_gamma_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +u_lambda_n_position_list: [[1, 1, 1, 1], + [1, 1, 1, 1, 1]] +u_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +# u_lambda is not used for the QP projection; overwritten by alpha*F. +u_lambda_position_list: [ + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_u_position: [0.01, 0.01, 0.01] + + +### NO NEED TO CHANGE THE BELOW. Parameters needed for the C3Options struct but +### are overwritten by other sampling C3 parameters. +use_predicted_x0: false # instead: use_predicted_x0_c3, + # use_predicted_x0_repos, + # use_predicted_x0_reset_mechanism +dt: 0 # instead: planning_dt_pose, planning_dt_position +solve_dt: 0 # unused +mu: [] # instead based on indexing into mu_per_pair_type +num_contacts: 0 # instead based on summing index of resolve_contacts_to_lists +# Instead for the below, index into their _list versions. +g_gamma: [] +g_lambda_n: [] +g_lambda_t: [] +g_lambda: [] +u_gamma: [] +u_lambda_n: [] +u_lambda_t: [] +u_lambda: [] diff --git a/examples/sampling_c3/push_t/parameters/sampling_params.yaml b/examples/sampling_c3/push_t/parameters/sampling_params.yaml new file mode 100644 index 0000000000..6c5d4e7c8d --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/sampling_params.yaml @@ -0,0 +1,44 @@ +# Sampling strategies (defined as SamplingStrategy enum in sampling_params.h): +# 0. kRadiallySymmetric: radially distributed samples on a planar circle. +# 1. kRandomOnCircle: random samples on a planar circle. +# 2. kRandomOnSphere: random samples on a spherical surface. +# 3. kFixed: fixed set of samples. +# 4. kRandomOnPerimeter: random samples on a perimeter offset past the object +# surface (roughly planar). +# 5. kRandomOnShell: random samples on a shell offset past the object +# surface. +sampling_strategy: 4 + +### Parameters relevant for all sampling strategies. +filter_samples_for_safety: true + +# Number of samples. Add 2 for repositioning (current location, previous +# repositioning target) and 1 for C3 (current location) to get total sample +# number solved in parallel for each control loop. +num_additional_samples_repos: 1 +num_additional_samples_c3: 2 + +# Sample buffer parameters. +consider_best_buffer_sample_when_leaving_c3: true +N_sample_buffer: 100 +pos_error_sample_retention: 0.003 +ang_error_sample_retention: 0.0349 # 0.0349 rad = 2 deg + +# Shared across multiple sampling strategies. +sampling_radius: 0.16 # kRadiallySymmetric, kRandomOnCircle, kRandomOnSphere +sampling_height: 0.005 # kRadiallySymmetric, kRandomOnCircle, kRandomOnPerimeter +sample_projection_clearance: 0.02 # kRandomOnPerimeter, kRandomOnShell +min_angle_from_vertical: 1.49 # kRandomOnSphere, kRandomOnShell +max_angle_from_vertical: 1.5 # kRandomOnSphere, kRandomOnShell + +# kFixed parameters. +fixed_sample_locations: [[0.45, 0.270, 0.270], # sample 1 + [0.34, 0.455, 0.225]] # sample 2 + +# kRandomOnPerimeter parameters. +grid_x_limits: [-0.12, 0.08] +grid_y_limits: [-0.08, 0.08] + +# kRandomOnShell parameters. +min_sampling_radius: 0.07 +max_sampling_radius: 0.10 diff --git a/examples/sampling_c3/push_t/parameters/sim_params.yaml b/examples/sampling_c3/push_t/parameters/sim_params.yaml new file mode 100644 index 0000000000..8ed1c5225e --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/sim_params.yaml @@ -0,0 +1,14 @@ +object_model: examples/sampling_c3/urdf/push_t.sdf + +franka_publish_rate: 1000 +object_publish_rate: 10 +actuator_delay: 0.000 + +visualize_drake_sim: false +publish_efforts: true + +dt: 0.0001 +realtime_rate: 1 + +q_init_franka: [2.191, 1.1, -1.33, -2.22, 1.30, 2.02, 0.08] +q_init_object: [1.0, 0, 0, 0, 0.5, 0, -0.009] diff --git a/examples/sampling_c3/push_t/parameters/vis_params.yaml b/examples/sampling_c3/push_t/parameters/vis_params.yaml new file mode 100644 index 0000000000..87c9195fdf --- /dev/null +++ b/examples/sampling_c3/push_t/parameters/vis_params.yaml @@ -0,0 +1,37 @@ +ee_vis_model: examples/sampling_c3/urdf/ee_visualization_model.urdf +object_vis_model: examples/sampling_c3/urdf/push_t.sdf +visualizer_publish_rate: 30 + +camera_pose: [1.5, 0, 0.6] +camera_target: [0.5, 0, 0.5] + +visualize_c3_workspace: false +visualize_c3_state: true + +visualize_center_of_mass_plan_curr: false +visualize_c3_forces_curr: false +visualize_center_of_mass_plan_best: false +visualize_c3_forces_best: false + +visualize_is_c3_mode: true +visualize_sample_locations: true +visualize_sample_buffer: true + +# Note: Colors can either be empty ([]) or RGB values between 0 and 1. If left +# empty, the colors defined in the URDF/SDF files will be used. +is_c3_mode_color: [1.0, 0.43, 1.0] +sample_color: [1.0, 1.0, 0.0] + +visualize_execution_plan: false + +visualize_c3_plan_curr: false +c3_curr_object_color: [] +c3_curr_ee_color: [0.8, 0.8, 0.8] +df_curr_object_color: [] +df_curr_ee_color: [0.5, 1.0, 0.5] + +visualize_c3_plan_best: false +c3_best_object_color: [1.0, 0.64, 0.0] +c3_best_ee_color: [1.0, 0.64, 0.0] +df_best_object_color: [1.0, 0.64, 0.0] +df_best_ee_color: [1.0, 0.64, 0.0] diff --git a/examples/sampling_c3/urdf/jack_ground.sdf b/examples/sampling_c3/urdf/jack_control.sdf similarity index 100% rename from examples/sampling_c3/urdf/jack_ground.sdf rename to examples/sampling_c3/urdf/jack_control.sdf diff --git a/examples/sampling_c3/urdf/push_t.sdf b/examples/sampling_c3/urdf/push_t.sdf new file mode 100644 index 0000000000..bc3104bcf5 --- /dev/null +++ b/examples/sampling_c3/urdf/push_t.sdf @@ -0,0 +1,93 @@ + + + + + + 0 0 0 0 0 0 + 0.5 + + 0.0001333 + 0.0011333 + 0.0011333 + 0.0 + 0.0 + 0.0 + + + + 0 0 0 0 0 0 + + + 0.16 0.04 0.04 + + + + 0 0.8 0.8 1 + + + + 0 0 0 0 0 0 + + + 0.16 0.04 0.04 + + + + + 3.0e7 + 0.18 + 10 + 0.3 + + + + + + + -0.10 0 0 0 0 1.5708 + 0.5 + + 0.0001333 + 0.0011333 + 0.0011333 + 0.0 + 0.0 + 0.0 + + + + -0.10 0 0 0 0 1.5708 + + + 0.16 0.04 0.04 + + + + 0 0.8 0.8 1 + + + + -0.10 0 0 0 0 1.5708 + + + 0.16 0.04 0.04 + + + + + 3.0e7 + 0.18 + 10 + 0.3 + + + + + + vertical_link + horizontal_link + 0 0 0 0 0 0 + + + + \ No newline at end of file diff --git a/examples/sampling_c3/urdf/push_t_control.sdf b/examples/sampling_c3/urdf/push_t_control.sdf new file mode 100644 index 0000000000..2c017fd56e --- /dev/null +++ b/examples/sampling_c3/urdf/push_t_control.sdf @@ -0,0 +1,117 @@ + + + + + + 0 0 0 0 0 0 + 0.5 + + 0.0001333 + 0.0011333 + 0.0011333 + 0.0 + 0.0 + 0.0 + + + + 0 0 0 0 0 0 + + + 0.16 0.04 0.04 + + + + 0 0.8 0.8 1 + + + + 0 0 0 0 0 0 + + + 0.16 0.04 0.04 + + + + + 3.0e7 + 0.18 + 10 + 0.3 + + + + -0.12 0.08 -0.02 0 0 0 + + + 0.001 + + + + + -0.12 -0.08 -0.02 0 0 0 + + + 0.001 + + + + + 0.08 0.0 -0.02 0 0 0 + + + 0.001 + + + + + + + + -0.10 0 0 0 0 1.5708 + 0.5 + + 0.0001333 + 0.0011333 + 0.0011333 + 0.0 + 0.0 + 0.0 + + + + -0.10 0 0 0 0 1.5708 + + + 0.16 0.04 0.04 + + + + 0 0.8 0.8 1 + + + + -0.10 0 0 0 0 1.5708 + + + 0.16 0.04 0.04 + + + + + 3.0e7 + 0.18 + 10 + 0.3 + + + + + + vertical_link + horizontal_link + 0 0 0 0 0 0 + + + + \ No newline at end of file From 22bdee6bcf65459ca4ae4e43547622601290bb04 Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Thu, 3 Jul 2025 13:14:40 -0400 Subject: [PATCH 751/758] Add README for sampling C3 documentation --- examples/sampling_c3/README.md | 123 +++++++++++++++++++++++++++++++++ 1 file changed, 123 insertions(+) create mode 100644 examples/sampling_c3/README.md diff --git a/examples/sampling_c3/README.md b/examples/sampling_c3/README.md new file mode 100644 index 0000000000..362d37e8d6 --- /dev/null +++ b/examples/sampling_c3/README.md @@ -0,0 +1,123 @@ +# Approximating Global Contact-Implicit MPC via Sampling and Local Complementarity +This is an implementation of our paper currently available on Arxiv. + +[[Project webpage](https://approximating-global-ci-mpc.github.io/)] [[Arxiv](https://arxiv.org/abs/2505.13350)] [[Supplemental video](https://youtu.be/rv9n8Uyvoh0)] + +## Abstract +> To achieve general-purpose dexterous manipulation, robots must rapidly devise and execute contact-rich behaviors. Existing model-based controllers are incapable of globally optimizing in real-time over the exponential number of possible contact sequences. Instead, recent progress in contact-implicit control has leveraged simpler models that, while still hybrid, make local approximations. However, the use of local models inherently limits the controller to only exploit nearby interactions, potentially requiring intervention to richly explore the space of possible contacts. We present a novel approach which leverages the strengths of local complementarity-based control in combination with low-dimensional, but global, sampling of possible end-effector locations. Our key insight is to consider a contact-free stage preceding a contact-rich stage at every control loop. Our algorithm, in parallel, samples end effector locations to which the contact-free stage can move the robot, then considers the cost predicted by contact-rich MPC local to each sampled location. The result is a globally-informed, contact-implicit controller capable of real-time dexterous manipulation. We demonstrate our controller on precise, non-prehensile manipulation of non-convex objects using a Franka Panda arm. + +## Bibtex +``` +@article{venkatesh2025approximating, + title={Approximating Global Contact-Implicit MPC via Sampling and Local Complementarity}, + author={Sharanya Venkatesh* and Bibit Bianchini* and Alp Aydinoglu and William Yang and Michael Posa}, + year={2025}, + journal={arXiv preprint arXiv:2505.13350}, + website={https://approximating-global-ci-mpc.github.io/} +} +``` + +## Simulation Experiments + +1. Start the procman script containing a list of relevant processes. There's a different one for each demo, currently the 3D jack or planar push T: +``` +bot-procman-sheriff -l examples/sampling_c3/jacktoy/franka_sim_jack.pmd # Jack example +bot-procman-sheriff -l examples/sampling_c3/push_t/franka_sim_t.pmd # T example +``` + +2. In the procman window, start the meshcat visualizer by starting the `visualizer` command under the `operator` group. The meshcat visualizer can be viewed by opening a browser and navigating to `localhost:7000`. + +3. The examples with the sampling C3 controller can be run using the script `script:start_experiment_no_logs`. Scripts are located in the top bar of the procman window. This script spawns three processes: + - `bazel-bin/examples/sampling_c3/franka_sim`: Simulated environment which takes in torques commands from `franka_osc` and publishes the state of the system via LCM on various channels. + - `bazel-bin/examples/sampling_c3/franka_osc_controller`: Low-level task-space controller that tracks task-space trajectories it receives from the MPC. + - `bazel-bin/examples/sampling_c3/franka_sampling_c3_controller`: Contact Implicit MPC controller that takes in the state of the system and publishes end effector trajectories to be tracked by the OSC. + +4. The simulator and controller can be stopped using the script `script:end_experiment`. + + +### MJPC Comparison +A comparison using the sampling based MPC controllers from the [MuJoCo MPC controllers](https://github.com/google-deepmind/mujoco_mpc) is currently implemented in `dairlib`'s `jack_mjpc` branch [here](https://github.com/DAIRLab/dairlib/tree/jack_mjpc). Bringing this code into `sampling_based_c3_public` is WIP. + +The MJPC comparison extracts out just the controller portion of the MJPC code base and runs in on the identical task in the Drake simulator. [Our MJPC fork](https://github.com/ebianchi/mujoco_mpc) needs to be installed for this to run properly. Instructions are WIP. + +## Hardware Experiments + +### Network Setup +We use a two computer setup with a Franka robot arm: + 1. Computer 1: Runs sampling C3 controller and [our fork of FoundationPose](https://github.com/dairlab/foundationpose) for object tracking. Requires a GPU to run FoundationPose. + - Connected via ethernet to Computer 2. + + 2. Computer 2: Runs our OSC, Franka drivers, and webcam recording. Requires a realtime kernel for communicating with the Franka. We rely on [drake-franka-driver](https://github.com/RobotLocomotion/drake-franka-driver), which works via LCM. Much thanks to the Drake developers who provided this! No ROS/ROS2 involved. + + 3. Ethernet connections: + - Computer 1 <--> Computer 2 with link-local network settings. + - Computer 2 <--> Franka control box with iPv4 manual network settings matching the Franka IP. + + 4. USB connections: + - RealSense for FoundationPose <--> Computer 1 + - USB webcams for experiment recording <--> Computer 2 + +### Franka Driver: Installing `drake-franka-driver` +``` +git clone https://github.com/RobotLocomotion/drake-franka-driver +cd drake-franka-driver +bazel build ... +``` + +### Object Pose Estimation via FoundationPose +[Our fork of FoundationPose](https://github.com/dairlab/foundationpose) handles converting the object pose estimate to world coordinates given access to a camera extrinsic calibration, and it publishes these poses over LCM. For camera calibration, see [the process documented here](https://github.com/ebianchi/ci_mpc_utils/tree/main?tab=readme-ov-file#camera-calibration). + +### Running Experiments + +1. Start the procman script containing a list of relevant processes. The primary differences from the simulation `franka_sim_jack.pmd`/`franka_sim_t.pmd` scripts are the lcm_channels and the drake-franka-driver and corresponding translators to communicate with the Franka via LCM. + + - In the root of dairlib on Computer 1, start the procman sheriff (can use `jack` or `t` examples): + + ``` + export LCM_DEFAULT_URL=udpm://239.255.76.67:7667?ttl=1 + bot-procman-sheriff -l examples/sampling_c3/jacktoy/franka_hardware_jack.pmd + ``` + + - In the root of dairlib on Computer 1, start the procman deputy: + + ``` + export LCM_DEFAULT_URL=udpm://239.255.76.67:7667?ttl=1 # required for python xbox script + bot-procman-deputy -n sampling_c3_localhost --lcmurl=udpm://239.255.76.67:7667?ttl=1 + ``` + + - In the root of drake-franka-driver on Computer 2, start the procman deputy for the Franka driver: + + ``` + bot-procman-deputy -n drake_franka_driver --lcmurl=udpm://239.255.76.67:7667?ttl=1 + ``` + + - In the root of dairlib on Computer 2, start the procman deputy for the OSC: + + ``` + bot-procman-deputy -n franka_control --lcmurl=udpm://239.255.76.67:7667?ttl=1 + ``` + +2. Start object tracking with FoundationPose. Can use `jack` or `t` system names. + ``` + bash docker/run_container.sh + cd FoundationPose + python run_live_demo.py --debug=0 --system=jack + ``` + +3. In the procman window, start the operator processes (meshcat visualizer and xbox controller) using the script `script:start_operator_commands`. Scripts are located in the top bar of the procman window. The meshcat visualizer can be viewed by opening a browser and navigating to `localhost:7000` + +4. Run the script `script:init_experiment` to slowly move the Franka to an initial configuration. + +5. Begin the experiment using the script `script:start_experiment`. This spawns the following processes: + - `start_logging.py`: Starts a lcm-logger with an automatic naming convention for the log number. + - `record_video.py`: Streams all available webcams to a .mp4 file corresponding to the log number. + - `torque_driver`: `drake-franka-driver` in torque control mode. + - `franka_driver_`(in/out): communicates with `drake-franka-driver` to receive/publish franka state information and torque commands. This is just a translator between Drake's Franka Panda specific lcm messages and the standardized robot commands that we use. + - `bazel-bin/examples/sampling_c3/franka_osc_controller`: Low-level task-space controller that tracks task-space trajectories it receives from the MPC. + - `bazel-bin/examples/sampling_c3/franka_sampling_c3_controller`: Contact Implicit MPC controller that takes in the state of the system and publishes end effector trajectories to be tracked by the OSC. + - `bazel-bin/examples/sampling_c3/xbox_script`: This gets started with `script:start_operator_commands` but gets restarted with `script:start_experiment` to ensure the experiment starts in teleop mode as a safety precaution. + +6. Using the xbox controller, switch from tracking the teleop commands to the MPC plan by pressing "A". Do this after checking that the plans look reasonable in the visualizer. +7. Stop the experiment using `script:stop_experiment`. This also stops logging and recording. + + From 1db6ad50953d68996a4550578948260b3c2f575e Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Tue, 8 Jul 2025 11:50:33 -0400 Subject: [PATCH 752/758] Fix intended checks for resolving contact pairs and maintaining sample buffer --- examples/sampling_c3/sampling_c3_utils.cc | 2 +- solvers/lcs_factory.cc | 2 +- .../sampling_based_c3_controller.cc | 19 +++++++++++-------- 3 files changed, 13 insertions(+), 10 deletions(-) diff --git a/examples/sampling_c3/sampling_c3_utils.cc b/examples/sampling_c3/sampling_c3_utils.cc index 3bfec51f72..bf5eab66bb 100644 --- a/examples/sampling_c3/sampling_c3_utils.cc +++ b/examples/sampling_c3/sampling_c3_utils.cc @@ -68,7 +68,7 @@ void AddLCSModelsToPlant( const bool& include_end_effector_orientation) { // Cannot currently handle end effector orientation (would just require new // EE simple model with orientation DOFs). - DRAKE_ASSERT(!include_end_effector_orientation); + DRAKE_DEMAND(!include_end_effector_orientation); Parser parser_lcs(plant); parser_lcs.SetAutoRenaming(true); diff --git a/solvers/lcs_factory.cc b/solvers/lcs_factory.cc index e1568031b5..e3cf2ee035 100644 --- a/solvers/lcs_factory.cc +++ b/solvers/lcs_factory.cc @@ -464,7 +464,7 @@ vector> LCSFactory::PreProcessor( resolved_contacts.reserve(n_contacts); for (int i = 0; i < contact_geoms.size(); i++) { - DRAKE_ASSERT(contact_geoms[i].size() >= resolve_contacts_to_list[i]); + DRAKE_DEMAND(contact_geoms[i].size() >= resolve_contacts_to_list[i]); const auto& candidates = contact_geoms[i]; const int num_to_select = resolve_contacts_to_list[i]; diff --git a/systems/controllers/sampling_based_c3_controller.cc b/systems/controllers/sampling_based_c3_controller.cc index 4525ce05ad..4ec74b26de 100644 --- a/systems/controllers/sampling_based_c3_controller.cc +++ b/systems/controllers/sampling_based_c3_controller.cc @@ -1024,10 +1024,13 @@ void SamplingC3Controller::UpdateCostMatrices( Eigen::MatrixXd Q_quaternion_dependent_regularizer_part_2 = quat_desired * quat_desired.transpose(); - DRAKE_ASSERT(Q_quaternion_dependent_cost.rows() == - Q_quaternion_dependent_cost.cols() == - Q_quaternion_dependent_regularizer_part_2.rows() == - Q_quaternion_dependent_regularizer_part_2.cols() == 4); + DRAKE_DEMAND((Q_quaternion_dependent_cost.rows() == + Q_quaternion_dependent_cost.cols()) && + (Q_quaternion_dependent_cost.rows() == + Q_quaternion_dependent_regularizer_part_2.rows()) && + (Q_quaternion_dependent_cost.rows() == + Q_quaternion_dependent_regularizer_part_2.cols()) && + (Q_quaternion_dependent_cost.rows() == 4)); double discount_factor = 1; for (int i = 0; i < N_ + 1; ++i) { Q_[i].block(3, 3, 4, 4) = @@ -1303,7 +1306,7 @@ void SamplingC3Controller::MaintainSampleBuffer(const VectorXd& x_lcs) const { int buffer_count = retained_count; for (int i = retained_count; i < retained_count + all_sample_locations_.size(); i++) { - DRAKE_ASSERT(i >= sampling_params_.N_sample_buffer); + DRAKE_DEMAND(buffer_count < sampling_params_.N_sample_buffer); if ((i == retained_count) || (!is_doing_c3_ && i == retained_count + 1)) { // Skip the current location. // Skip the repositioning target if in repositioning mode. @@ -1332,9 +1335,9 @@ void SamplingC3Controller::MaintainSampleBuffer(const VectorXd& x_lcs) const { sample_buffer_.row(num_in_buffer_ - 1) = lowest_cost_sample; sample_costs_buffer_[num_in_buffer_ - 1] = lowest_buffer_cost; - DRAKE_ASSERT(sample_buffer_.cols() == sampling_params_.N_sample_buffer); - DRAKE_ASSERT(sample_buffer_.rows() == n_q_); - DRAKE_ASSERT(sample_costs_buffer_.size() == sampling_params_.N_sample_buffer); + DRAKE_DEMAND(sample_buffer_.rows() == sampling_params_.N_sample_buffer); + DRAKE_DEMAND(sample_buffer_.cols() == n_q_); + DRAKE_DEMAND(sample_costs_buffer_.size() == sampling_params_.N_sample_buffer); } // If eligible, augment the current control loop's considered samples with the From 835671f19b34ee4559c4d06618b44704fb560d9c Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Tue, 8 Jul 2025 14:31:36 -0400 Subject: [PATCH 753/758] Add parameters for different contact pair configurations --- .../parameters/sampling_c3_options.yaml | 144 +++++++++++++----- .../parameters/sampling_c3_options.yaml | 32 ++-- 2 files changed, 121 insertions(+), 55 deletions(-) diff --git a/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml b/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml index 086280d38c..965151260d 100644 --- a/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml +++ b/examples/sampling_c3/jacktoy/parameters/sampling_c3_options.yaml @@ -82,36 +82,68 @@ r_vector: [0.01, 0.01, 0.01] # Penalty on matching projected variables g_x: [800, 800, 800, 100, 100, 100, 100, 10, 10, 10, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] g_lambda_n_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] g_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] -g_lambda_list: [[0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_list: [ + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] g_u: [30, 30, 30] # Penalty on matching the QP variables u_x: [10, 10, 10, 50, 50, 50, 50, 50, 50, 50, 8, 8, 8, 1, 1, 1, 1, 1, 1] u_gamma_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] u_lambda_n_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] u_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] # u_lambda_list is not used for the QP projection; overwritten by alpha*F. -u_lambda_list: [[10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_lambda_list: [ + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] u_u: [0.01, 0.01, 0.01] ### Position tracking cost parameters @@ -132,36 +164,68 @@ r_vector_position: [0.01, 0.01, 0.01] # Penalty on matching projected variables g_x_position: [800, 800, 800, 10, 10, 10, 10, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] g_lambda_n_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] g_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] -g_lambda_position_list: [[0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_position_list: [ + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01, 0.01], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] g_u_position: [30, 30, 30] # Penalty on matching the QP variables u_x_position: [10, 10, 10, 100, 100, 100, 100, 10, 10, 10, 8, 8, 8, 1, 1, 1, 1, 1, 1] u_gamma_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] u_lambda_n_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1]] u_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] # u_lambda_list is not used for the QP projection; overwritten by alpha*F. -u_lambda_position_list: [[10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], - [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_lambda_position_list: [ + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] u_u_position: [0.01, 0.01, 0.01] diff --git a/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml b/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml index c60e0c76b9..d4c165d2dc 100644 --- a/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml +++ b/examples/sampling_c3/push_t/parameters/sampling_c3_options.yaml @@ -82,9 +82,10 @@ g_gamma_list: [[1, 1, 1, 1], g_lambda_n_list: [[1, 1, 1, 1], [1, 1, 1, 1, 1]] g_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] -g_lambda_list: [[0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] #, + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] +g_lambda_list: [ + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] g_u: [30, 30, 30] # Penalty on matching the QP variables @@ -96,8 +97,9 @@ u_lambda_n_list: [[1, 1, 1, 1], u_lambda_t_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] # u_lambda_list is not used for the QP projection; overwritten by alpha*F. -u_lambda_list: [[10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] +u_lambda_list: [ + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] u_u: [0.01, 0.01, 0.01] ### Position tracking cost parameters @@ -118,28 +120,28 @@ r_vector_position: [0.01, 0.01, 0.01] # Penalty on matching projected variables g_x_position: [900, 900, 900, 1, 1, 1, 1, 1, 1, 1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1] g_gamma_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1]] g_lambda_n_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1]] g_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] g_lambda_position_list: [ - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], - [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005], + [0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005, 0.005]] g_u_position: [30, 30, 30] # Penalty on matching the QP variables u_x_position: [10, 10, 10, 100, 100, 100, 100, 10, 10, 10, 8, 8, 8, 1, 1, 1, 1, 1, 1] u_gamma_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1]] u_lambda_n_position_list: [[1, 1, 1, 1], - [1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1]] u_lambda_t_position_list: [[1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1], - [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] + [1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1]] # u_lambda is not used for the QP projection; overwritten by alpha*F. u_lambda_position_list: [ - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], - [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10], + [10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 10]] u_u_position: [0.01, 0.01, 0.01] From eabf2776555c10a854253f7c5ebfd5954be319e8 Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Tue, 8 Jul 2025 15:21:11 -0400 Subject: [PATCH 754/758] Include workspace and input limits as constraints in C3 QP step --- .../sampling_based_c3_controller.cc | 74 +++++++------------ 1 file changed, 27 insertions(+), 47 deletions(-) diff --git a/systems/controllers/sampling_based_c3_controller.cc b/systems/controllers/sampling_based_c3_controller.cc index 4ec74b26de..1267e1658c 100644 --- a/systems/controllers/sampling_based_c3_controller.cc +++ b/systems/controllers/sampling_based_c3_controller.cc @@ -141,53 +141,6 @@ SamplingC3Controller::SamplingC3Controller( DRAKE_THROW_UNLESS(false); } - c3_curr_plan_->SetOsqpSolverOptions(solver_options_); - c3_best_plan_->SetOsqpSolverOptions(solver_options_); - c3_buffer_plan_->SetOsqpSolverOptions(solver_options_); - - // Set actor bounds. - for (int i = 0; i < sampling_c3_options_.workspace_limits.size(); ++i) { - Eigen::RowVectorXd A = VectorXd::Zero(n_x_); - A.segment(0, 3) = sampling_c3_options_.workspace_limits[i].segment(0, 3); - // TODO @bibit: For the T example, the z constraint is an equality - // constraint. This will be reflected in the params but need to make sure to - // put a comment here when the T example is added. - // The fourth parameter decides which optimization variable the constraint - // is applied to. 1 = x, 2 = u, 3 = lambda. - c3_curr_plan_->AddLinearConstraint( - A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], - 1); - c3_best_plan_->AddLinearConstraint( - A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], - 1); - c3_buffer_plan_->AddLinearConstraint( - A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], - 1); - } - for (int i : vector({0, 1})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_u_); - A(i) = 1.0; - c3_curr_plan_->AddLinearConstraint( - A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], - 2); - c3_best_plan_->AddLinearConstraint( - A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], - 2); - c3_buffer_plan_->AddLinearConstraint( - A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], - 2); - } - for (int i : vector({2})) { - Eigen::RowVectorXd A = VectorXd::Zero(n_u_); - A(i) = 1.0; - c3_curr_plan_->AddLinearConstraint( - A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); - c3_best_plan_->AddLinearConstraint( - A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); - c3_buffer_plan_->AddLinearConstraint( - A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); - } - // Input ports. radio_port_ = this->DeclareAbstractInputPort("lcmt_radio_out", @@ -599,6 +552,33 @@ drake::systems::EventStatus SamplingC3Controller::ComputePlan( } // Unknown projection types are rejected in the initialization. test_c3_object->UpdateCostLCS(lcs_candidates_for_cost.at(i)); + // Workspace limits. + for (int i = 0; i < sampling_c3_options_.workspace_limits.size(); ++i) { + Eigen::RowVectorXd A = VectorXd::Zero(n_x_); + A.segment(0, 3) = sampling_c3_options_.workspace_limits[i].segment(0, 3); + // TODO @bibit: For planar examples, we may want the z constraint to be an + // equality constraint. This would require two different sets of workspace + // limits: one for the C3 solve, and one for the controller for safety + // checks. + test_c3_object->AddLinearConstraint( + A, c3_options.workspace_limits[i][3], c3_options.workspace_limits[i][4], + 1); + } + // Input limits. + for (int i : vector({0, 1})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + test_c3_object->AddLinearConstraint( + A, c3_options.u_horizontal_limits[0], c3_options.u_horizontal_limits[1], + 2); + } + for (int i : vector({2})) { + Eigen::RowVectorXd A = VectorXd::Zero(n_u_); + A(i) = 1.0; + test_c3_object->AddLinearConstraint( + A, c3_options.u_vertical_limits[0], c3_options.u_vertical_limits[1], 2); + } + // Solve C3, store resulting object and cost. test_c3_object->SetOsqpSolverOptions(solver_options_); test_c3_object->Solve(test_state, verbose_); From db49a8f91a6cba751cea79a74d51b62776090efb Mon Sep 17 00:00:00 2001 From: Hien Bui Date: Thu, 10 Jul 2025 14:54:29 -0400 Subject: [PATCH 755/758] Resolve merge conflicts with main (#386) * Resolve merge conflicts with main * Remove obsolete codes * Remove accidentally commited files * Add external force tracking result to lcm * Add back the deleted files in Cassie example * Add back deleted files in pydairlib/cassie * Revert code formatting * Revert code formatting * Revert code formatting --- examples/Cassie/cassie_state_estimator.cc | 3 + .../osc_running_controller_diagram.cc | 71 +- .../osc_walking_controller_diagram.cc | 64 +- .../Cassie/networking/cassie_udp_publisher.cc | 2 +- examples/Cassie/run_osc_jumping_controller.cc | 35 +- examples/Cassie/run_osc_running_controller.cc | 34 +- .../Cassie/run_osc_standing_controller.cc | 229 +++-- examples/Cassie/run_osc_walking_controller.cc | 122 ++- .../Cassie/run_osc_walking_controller_alip.cc | 371 ++++---- .../diagrams/franka_osc_controller_diagram.cc | 10 +- examples/franka/franka_osc_controller.cc | 10 +- .../run_joint_space_walking_controller.cc | 13 +- .../franka_joint_osc_controller.cc | 2 +- examples/sampling_c3/franka_osc_controller.cc | 10 +- lcmtypes/lcmt_osc_qp_output.lcm | 2 + .../kinematic/kinematic_evaluator_set.cc | 2 +- multibody/kinematic/kinematic_evaluator_set.h | 6 +- solvers/fast_osqp_solver.cc | 2 + solvers/fast_osqp_solver.h | 1 - systems/controllers/osc/BUILD.bazel | 11 + .../osc/external_force_tracking_data.cc | 14 +- .../osc/external_force_tracking_data.h | 13 +- .../controllers/osc/inverse_dynamics_qp.cc | 232 +++++ systems/controllers/osc/inverse_dynamics_qp.h | 341 +++++++ .../osc/operational_space_control.cc | 859 +++++------------- .../osc/operational_space_control.h | 164 ++-- systems/robot_lcm_systems.cc | 29 +- systems/robot_lcm_systems.h | 9 +- tools/workspace/drake_models/BUILD.bazel | 1 - 29 files changed, 1416 insertions(+), 1246 deletions(-) create mode 100644 systems/controllers/osc/inverse_dynamics_qp.cc create mode 100644 systems/controllers/osc/inverse_dynamics_qp.h diff --git a/examples/Cassie/cassie_state_estimator.cc b/examples/Cassie/cassie_state_estimator.cc index df3f68ae1e..f7bec41e15 100644 --- a/examples/Cassie/cassie_state_estimator.cc +++ b/examples/Cassie/cassie_state_estimator.cc @@ -1102,6 +1102,9 @@ void CassieStateEstimator::DoCalcNextUpdateTime( const auto& self = dynamic_cast(system); return self.Update(c, s); }; + auto& uu_events = events->get_mutable_unrestricted_update_events(); + uu_events.AddEvent(UnrestrictedUpdateEvent( + drake::systems::TriggerType::kTimed, callback)); } else { *time = INFINITY; } diff --git a/examples/Cassie/diagrams/osc_running_controller_diagram.cc b/examples/Cassie/diagrams/osc_running_controller_diagram.cc index 15dc9f0c8b..04f457b4b8 100644 --- a/examples/Cassie/diagrams/osc_running_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_running_controller_diagram.cc @@ -64,7 +64,8 @@ namespace controllers { OSCRunningControllerDiagram::OSCRunningControllerDiagram( drake::multibody::MultibodyPlant& plant, - const string& osc_running_gains_filename, const string& osqp_settings_filename) + const string& osc_running_gains_filename, + const string& osqp_settings_filename) : plant_(&plant), pos_map(multibody::MakeNameToPositionsMap(plant)), vel_map(multibody::MakeNameToVelocitiesMap(plant)), @@ -155,7 +156,7 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true); + plant, plant_context.get(), true); auto radio_parser = builder.AddSystem(); auto failure_aggregator = builder.AddSystem( @@ -163,11 +164,12 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( /**** OSC setup ****/ /// REGULARIZATION COSTS - osc->SetAccelerationCostWeights(osc_running_gains.w_accel * osc_running_gains.W_acceleration); + osc->SetAccelerationCostWeights(osc_running_gains.w_accel * + osc_running_gains.W_acceleration); osc->SetInputSmoothingCostWeights(osc_running_gains.w_input_reg * - osc_running_gains.W_input_regularization); + osc_running_gains.W_input_regularization); osc->SetInputCostWeights(osc_running_gains.w_input * - osc_running_gains.W_input_regularization); + osc_running_gains.W_input_regularization); osc->SetLambdaContactRegularizationWeight( osc_running_gains.w_lambda * osc_running_gains.W_lambda_c_regularization); osc->SetLambdaHolonomicRegularizationWeight( @@ -179,14 +181,22 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( // Contact information for OSC osc->SetContactFriction(osc_running_gains.mu); - osc->AddStateAndContactPoint(RunningFsmState::kLeftStance, - &left_toe_evaluator); - osc->AddStateAndContactPoint(RunningFsmState::kLeftStance, - &left_heel_evaluator); - osc->AddStateAndContactPoint(RunningFsmState::kRightStance, - &right_toe_evaluator); - osc->AddStateAndContactPoint(RunningFsmState::kRightStance, - &right_heel_evaluator); + osc->AddContactPoint("left_toe", + std::unique_ptr>( + &left_toe_evaluator), + {RunningFsmState::kLeftStance}); + osc->AddContactPoint("left_heel", + std::unique_ptr>( + &left_heel_evaluator), + {RunningFsmState::kLeftStance}); + osc->AddContactPoint("right_toe", + std::unique_ptr>( + &right_toe_evaluator), + {RunningFsmState::kRightStance}); + osc->AddContactPoint("right_heel", + std::unique_ptr>( + &right_heel_evaluator), + {RunningFsmState::kRightStance}); // Fix the springs in the dynamics evaluators.add_evaluator(&left_fixed_knee_spring); @@ -196,8 +206,9 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); - - osc->AddKinematicConstraint(&evaluators); + osc->AddKinematicConstraint( + std::unique_ptr>( + &evaluators)); /**** Tracking Data *****/ @@ -208,8 +219,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( osc_running_gains.vel_scale_trans_lateral); auto pelvis_trans_traj_generator = - builder.AddSystem( - plant, plant_context.get(), feet_contact_points); + builder.AddSystem(plant, plant_context.get(), + feet_contact_points); pelvis_trans_traj_generator->SetSLIPParams( osc_running_gains.rest_length, osc_running_gains.rest_length_offset); auto l_foot_traj_generator = builder.AddSystem( @@ -261,8 +272,8 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( right_foot_tracking_data->AddStateAndPointToTrack( RunningFsmState::kLeftFlight, "toe_right"); - left_foot_tracking_data->AddStateAndPointToTrack( - RunningFsmState::kLeftFlight, "toe_left"); + left_foot_tracking_data->AddStateAndPointToTrack(RunningFsmState::kLeftFlight, + "toe_left"); right_foot_tracking_data->AddStateAndPointToTrack( RunningFsmState::kRightFlight, "toe_right"); @@ -274,17 +285,17 @@ OSCRunningControllerDiagram::OSCRunningControllerDiagram( "right_hip_traj", osc_running_gains.K_p_swing_foot, osc_running_gains.K_d_swing_foot, osc_running_gains.W_swing_foot, plant, plant); - left_hip_tracking_data->AddStateAndPointToTrack( - RunningFsmState::kRightStance, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack( - RunningFsmState::kLeftStance, "pelvis"); - right_hip_tracking_data->AddStateAndPointToTrack( - RunningFsmState::kLeftFlight, "pelvis"); - left_hip_tracking_data->AddStateAndPointToTrack( - RunningFsmState::kRightFlight, "pelvis"); - - left_hip_tracking_data->AddStateAndPointToTrack( - RunningFsmState::kLeftFlight, "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(RunningFsmState::kRightStance, + "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(RunningFsmState::kLeftStance, + "pelvis"); + right_hip_tracking_data->AddStateAndPointToTrack(RunningFsmState::kLeftFlight, + "pelvis"); + left_hip_tracking_data->AddStateAndPointToTrack(RunningFsmState::kRightFlight, + "pelvis"); + + left_hip_tracking_data->AddStateAndPointToTrack(RunningFsmState::kLeftFlight, + "pelvis"); right_hip_tracking_data->AddStateAndPointToTrack( RunningFsmState::kRightFlight, "pelvis"); diff --git a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc index d58c43caa9..7ac223fdee 100644 --- a/examples/Cassie/diagrams/osc_walking_controller_diagram.cc +++ b/examples/Cassie/diagrams/osc_walking_controller_diagram.cc @@ -92,8 +92,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( left_right_foot({left_toe_origin, right_toe_origin}), left_foot_points({left_heel, left_toe}), right_foot_points({right_heel, right_toe}), - view_frame_( - std::make_shared>(plant.GetBodyByName("pelvis"))), + view_frame_(std::make_shared>( + plant.GetBodyByName("pelvis"))), left_toe_evaluator(multibody::WorldPointEvaluator( plant, left_toe.first, left_toe.second, *view_frame_, Matrix3d::Identity(), Vector3d::Zero(), {1, 2})), @@ -198,16 +198,17 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( swing_ft_accel_gain_multiplier_samples[2](2, 2) *= 0; swing_ft_accel_gain_multiplier_samples[3](2, 2) *= 0; auto swing_ft_accel_gain_multiplier_gain_multiplier = - std::make_shared>(PiecewisePolynomial::FirstOrderHold( - swing_ft_accel_gain_multiplier_breaks, - swing_ft_accel_gain_multiplier_samples)); + std::make_shared>( + PiecewisePolynomial::FirstOrderHold( + swing_ft_accel_gain_multiplier_breaks, + swing_ft_accel_gain_multiplier_samples)); /**** Initialize all the leaf systems ****/ auto state_receiver = builder.AddSystem(plant); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true); + plant, plant_context.get(), true); auto fsm = builder.AddSystem( plant, fsm_states, state_durations); auto liftoff_event_time = @@ -234,28 +235,26 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( // Contact information for OSC osc->SetContactFriction(osc_walking_gains.mu); - osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); - osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); - if (has_double_stance) { - osc->AddStateAndContactPoint(post_left_double_support_state, - &left_toe_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &left_heel_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &right_toe_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &right_heel_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &left_toe_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &left_heel_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &right_toe_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &right_heel_evaluator); - } + osc->AddContactPoint("left_toe", + std::unique_ptr>( + &left_toe_evaluator), + {left_stance_state, post_left_double_support_state, + post_right_double_support_state}); + osc->AddContactPoint("left_heel", + std::unique_ptr>( + &left_heel_evaluator), + {left_stance_state, post_left_double_support_state, + post_right_double_support_state}); + osc->AddContactPoint("right_toe", + std::unique_ptr>( + &right_toe_evaluator), + {right_stance_state, post_left_double_support_state, + post_right_double_support_state}); + osc->AddContactPoint("right_heel", + std::unique_ptr>( + &right_heel_evaluator), + {right_stance_state, post_left_double_support_state, + post_right_double_support_state}); evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); @@ -266,7 +265,8 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); - osc->AddKinematicConstraint(&evaluators); + osc->AddKinematicConstraint( + std::unique_ptr>(&evaluators)); /**** Trajectory Generators ****/ @@ -346,8 +346,10 @@ OSCWalkingControllerDiagram::OSCWalkingControllerDiagram( "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, plant, plant); - swing_ft_traj_global_->AddStateAndPointToTrack(left_stance_state, "toe_right"); - swing_ft_traj_global_->AddStateAndPointToTrack(right_stance_state, "toe_left"); + swing_ft_traj_global_->AddStateAndPointToTrack(left_stance_state, + "toe_right"); + swing_ft_traj_global_->AddStateAndPointToTrack(right_stance_state, + "toe_left"); swing_ft_traj_local_->SetTimeVaryingPDGainMultiplier( swing_ft_gain_multiplier_gain_multiplier); swing_ft_traj_local_->SetTimerVaryingFeedForwardAccelMultiplier( diff --git a/examples/Cassie/networking/cassie_udp_publisher.cc b/examples/Cassie/networking/cassie_udp_publisher.cc index 9c5e3eee82..2e96483a6a 100644 --- a/examples/Cassie/networking/cassie_udp_publisher.cc +++ b/examples/Cassie/networking/cassie_udp_publisher.cc @@ -92,7 +92,7 @@ std::string CassieUDPPublisher::make_name(const std::string& address, // period or publish period = 0.0 was passed to the constructor). drake::systems::EventStatus CassieUDPPublisher::PublishInputAsUDPMessage( const drake::systems::Context& context) const { - SPDLOG_TRACE(drake::log(), "Publishing UDP {} message", address_); + SPDLOG_TRACE("Publishing UDP {} message", address_); // Converts the input into message bytes. const drake::AbstractValue* const input_value = diff --git a/examples/Cassie/run_osc_jumping_controller.cc b/examples/Cassie/run_osc_jumping_controller.cc index 40bead0670..2c795988fc 100644 --- a/examples/Cassie/run_osc_jumping_controller.cc +++ b/examples/Cassie/run_osc_jumping_controller.cc @@ -36,6 +36,7 @@ using std::map; using std::pair; using std::string; using std::vector; +using std::unique_ptr; using Eigen::Matrix3d; using Eigen::MatrixXd; @@ -267,7 +268,7 @@ int DoMain(int argc, char* argv[]) { auto command_sender = builder.AddSystem(plant_w_spr); auto osc = builder.AddSystem( - plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true); + plant_w_spr, context_w_spr.get(), true); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_JUMPING", &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -326,14 +327,29 @@ int DoMain(int argc, char* argv[]) { auto right_heel_evaluator = multibody::WorldPointEvaluator( plant_w_spr, right_heel.first, right_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - vector stance_modes = { + vector stance_modes = { osc_jump::BALANCE, osc_jump::CROUCH, osc_jump::LAND}; - for (auto mode : stance_modes) { - osc->AddStateAndContactPoint(mode, &left_toe_evaluator); - osc->AddStateAndContactPoint(mode, &left_heel_evaluator); - osc->AddStateAndContactPoint(mode, &right_toe_evaluator); - osc->AddStateAndContactPoint(mode, &right_heel_evaluator); - } + + osc->AddContactPoint( + "left_toe", + unique_ptr>(&left_toe_evaluator), + stance_modes + ); + osc->AddContactPoint( + "left_heel", + unique_ptr>(&left_heel_evaluator), + stance_modes + ); + osc->AddContactPoint( + "right_toe", + unique_ptr>(&right_toe_evaluator), + stance_modes + ); + osc->AddContactPoint( + "right_heel", + unique_ptr>(&right_heel_evaluator), + stance_modes + ); multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -362,7 +378,8 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); - osc->AddKinematicConstraint(&evaluators); + osc->AddKinematicConstraint( + std::unique_ptr>(&evaluators)); /**** Tracking Data for OSC *****/ auto pelvis_tracking_data = std::make_unique( diff --git a/examples/Cassie/run_osc_running_controller.cc b/examples/Cassie/run_osc_running_controller.cc index 7dbc9d67e5..0574b81405 100644 --- a/examples/Cassie/run_osc_running_controller.cc +++ b/examples/Cassie/run_osc_running_controller.cc @@ -40,6 +40,7 @@ using std::map; using std::pair; using std::string; using std::vector; +using std::unique_ptr; using Eigen::Matrix3d; using Eigen::MatrixXd; @@ -173,7 +174,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true); + plant, plant_context.get(), true); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_RUNNING", &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -223,14 +224,26 @@ int DoMain(int argc, char* argv[]) { plant, right_heel.first, right_heel.second, *pelvis_view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(RunningFsmState::kLeftStance, - &left_toe_evaluator); - osc->AddStateAndContactPoint(RunningFsmState::kLeftStance, - &left_heel_evaluator); - osc->AddStateAndContactPoint(RunningFsmState::kRightStance, - &right_toe_evaluator); - osc->AddStateAndContactPoint(RunningFsmState::kRightStance, - &right_heel_evaluator); + osc->AddContactPoint( + "left_toe", + unique_ptr>(&left_toe_evaluator), + {RunningFsmState::kLeftStance} + ); + osc->AddContactPoint( + "left_heel", + unique_ptr>(&left_heel_evaluator), + {RunningFsmState::kLeftStance} + ); + osc->AddContactPoint( + "right_toe", + unique_ptr>(&right_toe_evaluator), + {RunningFsmState::kRightStance} + ); + osc->AddContactPoint( + "right_heel", + unique_ptr>(&right_heel_evaluator), + {RunningFsmState::kRightStance} + ); multibody::KinematicEvaluatorSet evaluators(plant); @@ -259,7 +272,8 @@ int DoMain(int argc, char* argv[]) { evaluators.add_evaluator(&left_loop); evaluators.add_evaluator(&right_loop); - osc->AddKinematicConstraint(&evaluators); + osc->AddKinematicConstraint( + unique_ptr>(&evaluators)); /**** Tracking Data *****/ diff --git a/examples/Cassie/run_osc_standing_controller.cc b/examples/Cassie/run_osc_standing_controller.cc index d3cbb68d43..cedc6a2bfb 100644 --- a/examples/Cassie/run_osc_standing_controller.cc +++ b/examples/Cassie/run_osc_standing_controller.cc @@ -16,12 +16,10 @@ #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/options_tracking_data.h" #include "systems/controllers/osc/osc_gains.h" -#include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" #include "systems/framework/lcm_driven_loop.h" #include "systems/robot_lcm_systems.h" -#include "systems/system_utils.h" #include "drake/common/yaml/yaml_io.h" #include "drake/systems/framework/diagram_builder.h" @@ -31,6 +29,7 @@ namespace dairlib { using std::cout; using std::endl; +using std::unique_ptr; using Eigen::Matrix3d; using Eigen::MatrixXd; @@ -40,22 +39,18 @@ using Eigen::VectorXd; using drake::geometry::SceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; -using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; using drake::systems::lcm::LcmSubscriberSystem; -using multibody::FixedJointEvaluator; -using multibody::WorldYawViewFrame; using systems::controllers::ComTrackingData; using systems::controllers::JointSpaceTrackingData; -using systems::controllers::RelativeTranslationTrackingData; using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; -DEFINE_string(channel_x, "CASSIE_STATE_DISPATCHER", +DEFINE_string(channel_x, "CASSIE_STATE_SIMULATION", "LCM channel for receiving state. " "Use CASSIE_STATE_SIMULATION to get state from simulator, and " "use CASSIE_STATE_DISPATCHER to get state from state estimator"); @@ -68,36 +63,29 @@ DEFINE_double(cost_weight_multiplier, 1.0, "A cosntant times with cost weight of OSC traj tracking"); DEFINE_double(height, .8, "The initial COM height (m)"); DEFINE_string(gains_filename, "examples/Cassie/osc/osc_standing_gains.yaml", - "Filepath containing osc_gains"); -DEFINE_string(osqp_settings, "solvers/default_osc_osqp_settings.yaml", - "Filepath containing qp settings"); + "Filepath containing gains"); DEFINE_bool(use_radio, false, "use the radio to set height or not"); - -// Currently the controller runs at the rate between 500 Hz and 200 Hz, so the -// publish rate of the robot state needs to be less than 500 Hz. Otherwise, the -// performance seems to degrade due to this. (Recommended publish rate: 200 Hz) -// Maybe we need to update the lcm driven loop to clear the queue of lcm message -// if it's more than one message? +DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Build Cassie MBP - drake::multibody::MultibodyPlant plant(0.0); - AddCassieMultibody(&plant, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2_conservative.urdf", + drake::multibody::MultibodyPlant plant_w_springs(0.0); + AddCassieMultibody(&plant_w_springs, nullptr, true /*floating base*/, + "examples/Cassie/urdf/cassie_v2.urdf", true /*spring model*/, false /*loop closure*/); - plant.Finalize(); + plant_w_springs.Finalize(); - auto context_w_spr = plant.CreateDefaultContext(); + auto context_w_spr = plant_w_springs.CreateDefaultContext(); // Get contact frames and position (doesn't matter whether we use - // plant or plant because the contact frames exit in both + // plant_w_springs or plant_w_springs because the contact frames exit in both // plants) - auto left_toe = LeftToeFront(plant); - auto left_heel = LeftToeRear(plant); - auto right_toe = RightToeFront(plant); - auto right_heel = RightToeRear(plant); + auto left_toe = LeftToeFront(plant_w_springs); + auto left_heel = LeftToeRear(plant_w_springs); + auto right_toe = RightToeFront(plant_w_springs); + auto right_heel = RightToeRear(plant_w_springs); // Build the controller diagram DiagramBuilder builder; @@ -116,7 +104,8 @@ int DoMain(int argc, char* argv[]) { "TARGET_HEIGHT", &lcm_local)); // Create state receiver. - auto state_receiver = builder.AddSystem(plant); + auto state_receiver = + builder.AddSystem(plant_w_springs); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( @@ -128,7 +117,8 @@ int DoMain(int argc, char* argv[]) { auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); - auto command_sender = builder.AddSystem(plant); + auto command_sender = + builder.AddSystem(plant_w_springs); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -143,15 +133,12 @@ int DoMain(int argc, char* argv[]) { std::vector&>> feet_contact_points = {left_toe, left_heel, right_toe, right_heel}; auto com_traj_generator = builder.AddSystem( - plant, context_w_spr.get(), feet_contact_points, FLAGS_height, + plant_w_springs, context_w_spr.get(), feet_contact_points, FLAGS_height, FLAGS_use_radio); - com_traj_generator->SetCommandFilter( - osc_gains.center_of_mass_command_filter_alpha); auto pelvis_rot_traj_generator = builder.AddSystem( - plant, context_w_spr.get(), feet_contact_points, "pelvis_rot_traj"); - pelvis_rot_traj_generator->SetCommandFilter( - osc_gains.orientation_command_filter_alpha); + plant_w_springs, context_w_spr.get(), feet_contact_points, + "pelvis_rot_traj"); builder.Connect(state_receiver->get_output_port(0), com_traj_generator->get_input_port_state()); builder.Connect(state_receiver->get_output_port(0), @@ -165,111 +152,114 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant, plant, context_w_spr.get(), context_w_spr.get(), false); - - multibody::KinematicEvaluatorSet evaluators(plant); - - // Fix the springs in the dynamics - auto pos_idx_map = multibody::MakeNameToPositionsMap(plant); - auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant); - auto left_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_left"), - vel_idx_map.at("knee_joint_leftdot"), 0); - auto right_fixed_knee_spring = - FixedJointEvaluator(plant, pos_idx_map.at("knee_joint_right"), - vel_idx_map.at("knee_joint_rightdot"), 0); - auto left_fixed_ankle_spring = FixedJointEvaluator( - plant, pos_idx_map.at("ankle_spring_joint_left"), + plant_w_springs, context_w_spr.get(), false); + + // Distance constraint + multibody::KinematicEvaluatorSet evaluators(plant_w_springs); + auto left_loop = LeftLoopClosureEvaluator(plant_w_springs); + auto right_loop = RightLoopClosureEvaluator(plant_w_springs); + evaluators.add_evaluator(&left_loop); + evaluators.add_evaluator(&right_loop); + + auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_springs); + auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant_w_springs); + auto left_fixed_knee_spring = multibody::FixedJointEvaluator( + plant_w_springs, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + auto right_fixed_knee_spring = multibody::FixedJointEvaluator( + plant_w_springs, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + auto left_fixed_ankle_spring = multibody::FixedJointEvaluator( + plant_w_springs, pos_idx_map.at("ankle_spring_joint_left"), vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - auto right_fixed_ankle_spring = FixedJointEvaluator( - plant, pos_idx_map.at("ankle_spring_joint_right"), + auto right_fixed_ankle_spring = multibody::FixedJointEvaluator( + plant_w_springs, pos_idx_map.at("ankle_spring_joint_right"), vel_idx_map.at("ankle_spring_joint_rightdot"), 0); evaluators.add_evaluator(&left_fixed_knee_spring); evaluators.add_evaluator(&right_fixed_knee_spring); evaluators.add_evaluator(&left_fixed_ankle_spring); evaluators.add_evaluator(&right_fixed_ankle_spring); - auto left_loop = LeftLoopClosureEvaluator(plant); - auto right_loop = RightLoopClosureEvaluator(plant); - evaluators.add_evaluator(&left_loop); - evaluators.add_evaluator(&right_loop); - - osc->AddKinematicConstraint(&evaluators); - + osc->AddKinematicConstraint( + std::unique_ptr>(&evaluators)); + // Soft constraint + // We don't want w_contact_relax to be too big, cause we want tracking + // error to be important + double w_contact_relax = gains.w_soft_constraint; + osc->SetContactSoftConstraintWeight(w_contact_relax); // Friction coefficient - osc->SetContactFriction(gains.mu); + double mu = 0.8; + osc->SetContactFriction(mu); // Add contact points auto left_toe_evaluator = multibody::WorldPointEvaluator( - plant, left_toe.first, left_toe.second, Matrix3d::Identity(), + plant_w_springs, left_toe.first, left_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - osc->AddContactPoint(&left_toe_evaluator); auto left_heel_evaluator = multibody::WorldPointEvaluator( - plant, left_heel.first, left_heel.second, Matrix3d::Identity(), + plant_w_springs, left_heel.first, left_heel.second, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddContactPoint(&left_heel_evaluator); auto right_toe_evaluator = multibody::WorldPointEvaluator( - plant, right_toe.first, right_toe.second, Matrix3d::Identity(), + plant_w_springs, right_toe.first, right_toe.second, Matrix3d::Identity(), Vector3d::Zero(), {1, 2}); - osc->AddContactPoint(&right_toe_evaluator); auto right_heel_evaluator = multibody::WorldPointEvaluator( - plant, right_heel.first, right_heel.second, Matrix3d::Identity(), - Vector3d::Zero(), {0, 1, 2}); - osc->AddContactPoint(&right_heel_evaluator); + plant_w_springs, right_heel.first, right_heel.second, + Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); + + osc->AddContactPoint( + "left_toe", + unique_ptr>(&left_toe_evaluator)); + osc->AddContactPoint( + "left_heel", + unique_ptr>(&left_heel_evaluator)); + osc->AddContactPoint( + "right_toe", + unique_ptr>(&right_toe_evaluator)); + osc->AddContactPoint("right_heel", + unique_ptr>( + &right_heel_evaluator)); // Cost - int n_v = plant.num_velocities(); - - osc->SetAccelerationCostWeights(gains.w_accel * gains.W_acceleration); - osc->SetInputSmoothingCostWeights(gains.w_input_reg * - gains.W_input_regularization); - osc->SetInputCostWeights(gains.w_input * gains.W_input_regularization); - osc->SetLambdaContactRegularizationWeight( - osc_gains.w_lambda * osc_gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(gains.w_lambda * - gains.W_lambda_h_regularization); - osc->SetContactSoftConstraintWeight(osc_gains.w_soft_constraint); -// osc->SetJointLimitWeight(osc_gains.w_joint_limit); - - auto pelvis_view_frame = std::make_shared>(plant.GetBodyByName("pelvis")); - auto pelvis_tracking_data = std::make_unique( - "pelvis_trans_traj", MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), - MatrixXd::Zero(3, 3), plant, plant); - auto stance_foot_tracking_data = std::make_unique( - "stance_ft_traj", MatrixXd::Zero(3, 3), MatrixXd::Zero(3, 3), - MatrixXd::Zero(3, 3), plant, plant); - pelvis_tracking_data->AddPointToTrack("pelvis"); - stance_foot_tracking_data->AddPointToTrack("toe_left"); - auto pelvis_trans_rel_tracking_data = - std::make_unique( - "pelvis_trans_traj", osc_gains.K_p_pelvis_rot, - osc_gains.K_d_pelvis_rot, osc_gains.W_pelvis_rot, plant, plant, - pelvis_tracking_data.get(), stance_foot_tracking_data.get()); - if (osc_gains.center_of_mass_filter_tau > 0) { - pelvis_trans_rel_tracking_data->SetLowPassFilter( - osc_gains.center_of_mass_filter_tau, {0, 1, 2}); - } - pelvis_trans_rel_tracking_data->SetViewFrame(pelvis_view_frame); + int n_v = plant_w_springs.num_velocities(); + MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); + osc->SetAccelerationCostWeights(Q_accel); + // Center of mass tracking + // Weighting x-y higher than z, as they are more important to balancing + // ComTrackingData center_of_mass_traj("com_traj", K_p_com, K_d_com, + // W_com * FLAGS_cost_weight_multiplier, + // plant_w_springs, plant_w_springs); + auto center_of_mass_traj = std::make_unique( + "com_traj", osc_gains.K_p_pelvis, osc_gains.K_d_pelvis, + osc_gains.W_pelvis * FLAGS_cost_weight_multiplier, plant_w_springs, + plant_w_springs); + center_of_mass_traj->AddPointToTrack("pelvis"); + double cutoff_freq = 5; // in Hz + double tau = 1 / (2 * M_PI * cutoff_freq); + center_of_mass_traj->SetLowPassFilter(tau, {1}); + osc->AddTrackingData(std::move(center_of_mass_traj)); auto pelvis_rot_tracking_data = std::make_unique( "pelvis_rot_traj", osc_gains.K_p_pelvis_rot, osc_gains.K_d_pelvis_rot, - osc_gains.W_pelvis_rot, plant, plant); -// pelvis_rot_tracking_data->SetViewFrame(pelvis_view_frame); + osc_gains.W_pelvis_rot * FLAGS_cost_weight_multiplier, plant_w_springs, + plant_w_springs); pelvis_rot_tracking_data->AddFrameToTrack("pelvis"); -// if (osc_gains.rot_filter_tau > 0) { -// pelvis_rot_tracking_data->SetLowPassFilter(osc_gains.rot_filter_tau, -// {0, 1, 2}); -// } - osc->AddTrackingData(std::move(pelvis_trans_rel_tracking_data)); osc->AddTrackingData(std::move(pelvis_rot_tracking_data)); + // Hip yaw joint tracking + // We use hip yaw joint tracking instead of pelvis yaw tracking because the + // foot sometimes rotates about yaw, and we need hip yaw joint to go back to + // 0. + double w_hip_yaw = 0.5; + double hip_yaw_kp = 40; + double hip_yaw_kd = 0.5; auto left_hip_yaw_traj = std::make_unique( - "left_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, - osc_gains.W_hip_yaw, plant, plant); + "left_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), + hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), + plant_w_springs, plant_w_springs); auto right_hip_yaw_traj = std::make_unique( - "right_hip_yaw_traj", osc_gains.K_d_hip_yaw, osc_gains.K_p_hip_yaw, - osc_gains.W_hip_yaw, plant, plant); + "right_hip_yaw_traj", hip_yaw_kp * MatrixXd::Ones(1, 1), + hip_yaw_kd * MatrixXd::Ones(1, 1), w_hip_yaw * MatrixXd::Ones(1, 1), + plant_w_springs, plant_w_springs); left_hip_yaw_traj->AddJointToTrack("hip_yaw_left", "hip_yaw_leftdot"); osc->AddConstTrackingData(std::move(left_hip_yaw_traj), VectorXd::Zero(1)); -// right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); -// osc->AddConstTrackingData(std::move(right_hip_yaw_traj), VectorXd::Zero(1)); + right_hip_yaw_traj->AddJointToTrack("hip_yaw_right", "hip_yaw_rightdot"); + osc->AddConstTrackingData(std::move(right_hip_yaw_traj), VectorXd::Zero(1)); // Build OSC problem osc->Build(); @@ -278,22 +268,21 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_robot_output()); builder.Connect(osc->get_output_port_osc_command(), command_sender->get_input_port(0)); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); builder.Connect(com_traj_generator->get_output_port(0), - osc->get_input_port_tracking_data("pelvis_trans_traj")); + osc->get_input_port_tracking_data("com_traj")); builder.Connect(pelvis_rot_traj_generator->get_output_port(0), osc->get_input_port_tracking_data("pelvis_rot_traj")); // Create the diagram auto owned_diagram = builder.Build(); - std::shared_ptr> shared_diagram = std::move(owned_diagram); - shared_diagram->set_name(("osc_standing_controller")); + owned_diagram->set_name(("osc standing controller")); // Build lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm_local, shared_diagram, state_receiver, FLAGS_channel_x, + &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); - DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); @@ -302,4 +291,4 @@ int DoMain(int argc, char* argv[]) { } // namespace dairlib -int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/Cassie/run_osc_walking_controller.cc b/examples/Cassie/run_osc_walking_controller.cc index a7da518254..a697961e30 100644 --- a/examples/Cassie/run_osc_walking_controller.cc +++ b/examples/Cassie/run_osc_walking_controller.cc @@ -98,15 +98,9 @@ int DoMain(int argc, char* argv[]) { // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); - if (FLAGS_spring_model) { - AddCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, + AddCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, "examples/Cassie/urdf/cassie_v2.urdf", true /*spring model*/, false /*loop closure*/); - } else { - AddCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", - false /*spring model*/, false /*loop closure*/); - } plant_w_spr.Finalize(); auto context_w_spr = plant_w_spr.CreateDefaultContext(); @@ -209,15 +203,12 @@ int DoMain(int argc, char* argv[]) { double double_support_duration = gains.ds_time; vector fsm_states; vector state_durations; - if (FLAGS_is_two_phase) { - fsm_states = {left_stance_state, right_stance_state}; - state_durations = {left_support_duration, right_support_duration}; - } else { - fsm_states = {left_stance_state, post_left_double_support_state, + + fsm_states = {left_stance_state, post_left_double_support_state, right_stance_state, post_right_double_support_state}; - state_durations = {left_support_duration, double_support_duration, + state_durations = {left_support_duration, double_support_duration, right_support_duration, double_support_duration}; - } + auto fsm = builder.AddSystem( plant_w_spr, fsm_states, state_durations); builder.Connect(state_receiver->get_output_port(0), @@ -253,23 +244,18 @@ int DoMain(int argc, char* argv[]) { vector unordered_state_durations; vector&>>> contact_points_in_each_state; - if (FLAGS_is_two_phase) { - unordered_fsm_states = {left_stance_state, right_stance_state}; - unordered_state_durations = {left_support_duration, right_support_duration}; - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - } else { - unordered_fsm_states = {left_stance_state, right_stance_state, + + unordered_fsm_states = {left_stance_state, right_stance_state, post_left_double_support_state, post_right_double_support_state}; - unordered_state_durations = {left_support_duration, right_support_duration, + unordered_state_durations = {left_support_duration, right_support_duration, double_support_duration, double_support_duration}; - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - } + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + auto lipm_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), desired_com_height, unordered_fsm_states, unordered_state_durations, @@ -366,7 +352,7 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true); + plant_w_spr, context_w_spr.get(), true); // Cost int n_v = plant_w_spr.num_velocities(); @@ -390,27 +376,26 @@ int DoMain(int argc, char* argv[]) { std::unique_ptr> right_fixed_knee_spring; std::unique_ptr> left_fixed_ankle_spring; std::unique_ptr> right_fixed_ankle_spring; - if (FLAGS_spring_model) { - auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_spr); - auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant_w_spr); - left_fixed_knee_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("knee_joint_left"), - vel_idx_map.at("knee_joint_leftdot"), 0); - right_fixed_knee_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("knee_joint_right"), - vel_idx_map.at("knee_joint_rightdot"), 0); - left_fixed_ankle_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("ankle_spring_joint_left"), - vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - right_fixed_ankle_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("ankle_spring_joint_right"), - vel_idx_map.at("ankle_spring_joint_rightdot"), 0); - evaluators.add_evaluator(left_fixed_knee_spring.get()); - evaluators.add_evaluator(right_fixed_knee_spring.get()); - evaluators.add_evaluator(left_fixed_ankle_spring.get()); - evaluators.add_evaluator(right_fixed_ankle_spring.get()); - } - osc->AddKinematicConstraint(&evaluators); + auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_spr); + auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant_w_spr); + left_fixed_knee_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + right_fixed_knee_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + left_fixed_ankle_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + right_fixed_ankle_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(left_fixed_knee_spring.get()); + evaluators.add_evaluator(right_fixed_knee_spring.get()); + evaluators.add_evaluator(left_fixed_ankle_spring.get()); + evaluators.add_evaluator(right_fixed_ankle_spring.get()); + osc->AddKinematicConstraint( + std::unique_ptr>(&evaluators)); // Soft constraint // w_contact_relax shouldn't be too big, cause we want tracking error to be @@ -433,28 +418,23 @@ int DoMain(int argc, char* argv[]) { auto right_heel_evaluator = multibody::WorldPointEvaluator( plant_w_spr, right_heel.first, right_heel.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); - osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); - if (!FLAGS_is_two_phase) { - osc->AddStateAndContactPoint(post_left_double_support_state, - &left_toe_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &left_heel_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &right_toe_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &right_heel_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &left_toe_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &left_heel_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &right_toe_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &right_heel_evaluator); - } + + osc->AddContactPoint( + "left_toe", + std::unique_ptr>(&left_toe_evaluator), + {left_stance_state, post_left_double_support_state, post_right_double_support_state}); + osc->AddContactPoint( + "left_heel", + std::unique_ptr>(&left_heel_evaluator), + {left_stance_state, post_left_double_support_state, post_right_double_support_state}); + osc->AddContactPoint( + "right_toe", + std::unique_ptr>(&right_toe_evaluator), + {right_stance_state, post_left_double_support_state, post_right_double_support_state}); + osc->AddContactPoint( + "right_heel", + std::unique_ptr>(&right_heel_evaluator), + {right_stance_state, post_left_double_support_state, post_right_double_support_state}); // Swing foot tracking std::vector swing_ft_gain_multiplier_breaks{ diff --git a/examples/Cassie/run_osc_walking_controller_alip.cc b/examples/Cassie/run_osc_walking_controller_alip.cc index 38e8b15902..f00522991b 100644 --- a/examples/Cassie/run_osc_walking_controller_alip.cc +++ b/examples/Cassie/run_osc_walking_controller_alip.cc @@ -10,7 +10,6 @@ #include "examples/Cassie/osc/swing_toe_traj_generator.h" #include "examples/Cassie/systems/cassie_out_to_radio.h" #include "examples/Cassie/systems/simulator_drift.h" -#include "examples/impact_invariant_control/impact_aware_time_based_fsm.h" #include "multibody/kinematic/fixed_joint_evaluator.h" #include "multibody/kinematic/kinematic_evaluator_set.h" #include "multibody/multibody_utils.h" @@ -21,7 +20,6 @@ #include "systems/controllers/osc/joint_space_tracking_data.h" #include "systems/controllers/osc/operational_space_control.h" #include "systems/controllers/osc/options_tracking_data.h" -#include "systems/controllers/osc/osc_gains.h" #include "systems/controllers/osc/relative_translation_tracking_data.h" #include "systems/controllers/osc/rot_space_tracking_data.h" #include "systems/controllers/osc/trans_space_tracking_data.h" @@ -49,11 +47,11 @@ using Eigen::Vector3d; using Eigen::VectorXd; using drake::multibody::Frame; -using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; using drake::systems::lcm::LcmPublisherSystem; +using drake::systems::lcm::LcmScopeSystem; using drake::systems::lcm::LcmSubscriberSystem; using multibody::WorldYawViewFrame; @@ -64,8 +62,8 @@ using systems::controllers::RotTaskSpaceTrackingData; using systems::controllers::TransTaskSpaceTrackingData; using multibody::FixedJointEvaluator; -using multibody::MakeNameToVelocitiesMap; using multibody::MakeNameToPositionsMap; +using multibody::MakeNameToVelocitiesMap; using drake::trajectories::PiecewisePolynomial; @@ -81,19 +79,12 @@ DEFINE_bool(use_radio, false, DEFINE_string( cassie_out_channel, "CASSIE_OUTPUT_ECHO", "The name of the channel to receive the cassie out structure from."); -DEFINE_string(osc_walking_gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", - "Filepath containing osc_walking_gains"); -DEFINE_string(osqp_settings, "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml", - "Filepath containing qp settings"); +DEFINE_string(gains_filename, "examples/Cassie/osc/osc_walking_gains_alip.yaml", + "Filepath containing gains"); DEFINE_bool(publish_osc_data, true, "whether to publish lcm messages for OscTrackData"); - -DEFINE_bool(is_two_phase, false, - "true: only right/left single support" - "false: both double and single support"); DEFINE_double(qp_time_limit, 0.002, "maximum qp solve time"); -DEFINE_bool(spring_model, true, ""); DEFINE_bool(publish_filtered_state, false, "whether to publish the low pass filtered state"); @@ -101,23 +92,14 @@ int DoMain(int argc, char* argv[]) { gflags::ParseCommandLineFlags(&argc, &argv, true); // Read-in the parameters - drake::yaml::LoadYamlOptions yaml_options; - yaml_options.allow_yaml_with_no_cpp = true; - OSCGains osc_gains = drake::yaml::LoadYamlFile( - FindResourceOrThrow(FLAGS_osc_walking_gains_filename), {}, {}, yaml_options); - OSCWalkingGainsALIP osc_walking_gains = drake::yaml::LoadYamlFile(FLAGS_osc_walking_gains_filename); + auto gains = + drake::yaml::LoadYamlFile(FLAGS_gains_filename); // Build Cassie MBP drake::multibody::MultibodyPlant plant_w_spr(0.0); - if (FLAGS_spring_model) { - AddCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_v2_conservative.urdf", - true /*spring model*/, false /*loop closure*/); - } else { - AddCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, - "examples/Cassie/urdf/cassie_fixed_springs.urdf", - false /*spring model*/, false /*loop closure*/); - } + AddCassieMultibody(&plant_w_spr, nullptr, true /*floating base*/, + "examples/Cassie/urdf/cassie_v2.urdf", + true /*spring model*/, false /*loop closure*/); plant_w_spr.Finalize(); auto context_w_spr = plant_w_spr.CreateDefaultContext(); @@ -136,8 +118,9 @@ int DoMain(int argc, char* argv[]) { auto right_heel = RightToeRear(plant_w_spr); // Get body frames and points - Vector3d center_of_pressure = left_heel.first + - osc_walking_gains.contact_point_pos * (left_toe.first - left_heel.first); + Vector3d center_of_pressure = + left_heel.first + + gains.contact_point_pos * (left_toe.first - left_heel.first); auto left_toe_mid = std::pair&>( center_of_pressure, plant_w_spr.GetFrameByName("toe_left")); auto right_toe_mid = std::pair&>( @@ -150,19 +133,25 @@ int DoMain(int argc, char* argv[]) { // Create state receiver. auto state_receiver = builder.AddSystem(plant_w_spr); - auto pelvis_filt = - builder.AddSystem( - plant_w_spr, osc_walking_gains.pelvis_xyz_vel_filter_tau); + auto pelvis_filt = builder.AddSystem( + plant_w_spr, gains.pelvis_xyz_vel_filter_tau); builder.Connect(*state_receiver, *pelvis_filt); + if (FLAGS_publish_filtered_state) { + auto [filtered_state_scope, filtered_state_sender] = + // AddToBuilder will add the systems to the diagram and connect their + // ports + LcmScopeSystem::AddToBuilder(&builder, &lcm_local, + pelvis_filt->get_output_port(), + "CASSIE_STATE_FB_FILTERED", 0); + } + // Create command sender. auto command_pub = builder.AddSystem(LcmPublisherSystem::Make( FLAGS_channel_u, &lcm_local, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant_w_spr); - auto cassie_out_to_radio = - builder.AddSystem(); builder.Connect(command_sender->get_output_port(0), command_pub->get_input_port()); @@ -183,29 +172,30 @@ int DoMain(int argc, char* argv[]) { builder.Connect(pelvis_filt->get_output_port(0), simulator_drift->get_input_port_state()); + auto cassie_out_to_radio = builder.AddSystem(); + // Create human high-level control - Eigen::Vector2d global_target_position(osc_walking_gains.global_target_position_x, - osc_walking_gains.global_target_position_y); - Eigen::Vector2d params_of_no_turning(osc_walking_gains.yaw_deadband_blur, - osc_walking_gains.yaw_deadband_radius); + Eigen::Vector2d global_target_position(gains.global_target_position_x, + gains.global_target_position_y); + Eigen::Vector2d params_of_no_turning(gains.yaw_deadband_blur, + gains.yaw_deadband_radius); cassie::osc::HighLevelCommand* high_level_command; if (FLAGS_use_radio) { high_level_command = builder.AddSystem( - plant_w_spr, context_w_spr.get(), osc_walking_gains.vel_scale_rot, - osc_walking_gains.vel_scale_trans_sagital, osc_walking_gains.vel_scale_trans_lateral, 0.4); + plant_w_spr, context_w_spr.get(), gains.vel_scale_rot, + gains.vel_scale_trans_sagital, gains.vel_scale_trans_lateral, 0.4); auto cassie_out_receiver = builder.AddSystem(LcmSubscriberSystem::Make( FLAGS_cassie_out_channel, &lcm_local)); - builder.Connect(cassie_out_receiver->get_output_port(), - cassie_out_to_radio->get_input_port()); + builder.Connect(*cassie_out_receiver, *cassie_out_to_radio); builder.Connect(cassie_out_to_radio->get_output_port(), high_level_command->get_input_port_radio()); } else { high_level_command = builder.AddSystem( - plant_w_spr, context_w_spr.get(), osc_walking_gains.kp_yaw, osc_walking_gains.kd_yaw, - osc_walking_gains.vel_max_yaw, osc_walking_gains.kp_pos_sagital, osc_walking_gains.kd_pos_sagital, - osc_walking_gains.vel_max_sagital, osc_walking_gains.kp_pos_lateral, osc_walking_gains.kd_pos_lateral, - osc_walking_gains.vel_max_lateral, osc_walking_gains.target_pos_offset, global_target_position, + plant_w_spr, context_w_spr.get(), gains.kp_yaw, gains.kd_yaw, + gains.vel_max_yaw, gains.kp_pos_sagital, gains.kd_pos_sagital, + gains.vel_max_sagital, gains.kp_pos_lateral, gains.kd_pos_lateral, + gains.vel_max_lateral, gains.target_pos_offset, global_target_position, params_of_no_turning); } builder.Connect(pelvis_filt->get_output_port(0), @@ -224,23 +214,19 @@ int DoMain(int argc, char* argv[]) { int right_stance_state = 1; int post_left_double_support_state = 3; int post_right_double_support_state = 4; - double left_support_duration = osc_walking_gains.ss_time; - double right_support_duration = osc_walking_gains.ss_time; - double double_support_duration = osc_walking_gains.ds_time; + double left_support_duration = gains.ss_time; + double right_support_duration = gains.ss_time; + double double_support_duration = gains.ds_time; vector fsm_states; vector state_durations; - if (FLAGS_is_two_phase) { - fsm_states = {left_stance_state, right_stance_state}; - state_durations = {left_support_duration, right_support_duration}; - } else { - fsm_states = {left_stance_state, post_left_double_support_state, - right_stance_state, post_right_double_support_state, - left_stance_state}; - state_durations = {left_support_duration, double_support_duration, - right_support_duration, double_support_duration, 0.0}; - } - auto fsm = builder.AddSystem( - plant_w_spr, fsm_states, state_durations, 0.0, osc_gains.impact_threshold); + + fsm_states = {left_stance_state, post_left_double_support_state, + right_stance_state, post_right_double_support_state}; + state_durations = {left_support_duration, double_support_duration, + right_support_duration, double_support_duration}; + + auto fsm = builder.AddSystem( + plant_w_spr, fsm_states, state_durations); builder.Connect(simulator_drift->get_output_port(0), fsm->get_state_input_port()); @@ -251,7 +237,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, single_support_states); liftoff_event_time->set_name("liftoff_time"); - builder.Connect(fsm->get_fsm_output_port(), + builder.Connect(fsm->get_output_port(0), liftoff_event_time->get_input_port_fsm()); builder.Connect(simulator_drift->get_output_port(0), liftoff_event_time->get_input_port_state()); @@ -261,7 +247,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, double_support_states); touchdown_event_time->set_name("touchdown_time"); - builder.Connect(fsm->get_fsm_output_port(), + builder.Connect(fsm->get_output_port(0), touchdown_event_time->get_input_port_fsm()); builder.Connect(simulator_drift->get_output_port(0), touchdown_event_time->get_input_port_state()); @@ -269,33 +255,28 @@ int DoMain(int argc, char* argv[]) { // Create CoM trajectory generator // Note that we are tracking COM acceleration instead of position and velocity // because we construct the LIPM traj which starts from the current state - double desired_com_height = osc_walking_gains.lipm_height; + double desired_com_height = gains.lipm_height; vector unordered_fsm_states; vector unordered_state_durations; vector&>>> contact_points_in_each_state; - if (FLAGS_is_two_phase) { - unordered_fsm_states = {left_stance_state, right_stance_state}; - unordered_state_durations = {left_support_duration, right_support_duration}; - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - } else { - unordered_fsm_states = {left_stance_state, right_stance_state, - post_left_double_support_state, - post_right_double_support_state}; - unordered_state_durations = {left_support_duration, right_support_duration, - double_support_duration, - double_support_duration}; - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - contact_points_in_each_state.push_back({left_toe_mid}); - contact_points_in_each_state.push_back({right_toe_mid}); - } + + unordered_fsm_states = {left_stance_state, right_stance_state, + post_left_double_support_state, + post_right_double_support_state}; + unordered_state_durations = {left_support_duration, right_support_duration, + double_support_duration, + double_support_duration}; + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + contact_points_in_each_state.push_back({left_toe_mid}); + contact_points_in_each_state.push_back({right_toe_mid}); + auto alip_traj_generator = builder.AddSystem( plant_w_spr, context_w_spr.get(), desired_com_height, unordered_fsm_states, unordered_state_durations, - contact_points_in_each_state, osc_walking_gains.Q_alip_kalman_filter.asDiagonal(), - osc_walking_gains.R_alip_kalman_filter.asDiagonal()); + contact_points_in_each_state, gains.Q_alip_kalman_filter.asDiagonal(), + gains.R_alip_kalman_filter.asDiagonal()); builder.Connect(fsm->get_output_port(0), alip_traj_generator->get_input_port_fsm()); @@ -321,10 +302,10 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem( plant_w_spr, context_w_spr.get(), left_right_support_fsm_states, left_right_support_state_durations, left_right_foot, "pelvis", - double_support_duration, osc_walking_gains.mid_foot_height, - osc_walking_gains.final_foot_height, osc_walking_gains.final_foot_velocity_z, - osc_walking_gains.max_CoM_to_footstep_dist, osc_walking_gains.footstep_offset, - osc_walking_gains.center_line_offset); + double_support_duration, gains.mid_foot_height, + gains.final_foot_height, gains.final_foot_velocity_z, + gains.max_CoM_to_footstep_dist, gains.footstep_offset, + gains.center_line_offset); builder.Connect(fsm->get_output_port(0), swing_ft_traj_generator->get_input_port_fsm()); builder.Connect(liftoff_event_time->get_output_port_event_time_of_interest(), @@ -357,19 +338,15 @@ int DoMain(int argc, char* argv[]) { // Create Operational space control auto osc = builder.AddSystem( - plant_w_spr, plant_w_spr, context_w_spr.get(), context_w_spr.get(), true); + plant_w_spr, context_w_spr.get(), true); // Cost int n_v = plant_w_spr.num_velocities(); int n_u = plant_w_spr.num_actuators(); - MatrixXd Q_accel = osc_walking_gains.w_accel * MatrixXd::Identity(n_v, n_v); + MatrixXd Q_accel = gains.w_accel * MatrixXd::Identity(n_v, n_v); osc->SetAccelerationCostWeights(Q_accel); - osc->SetLambdaContactRegularizationWeight(1e-4 * - osc_walking_gains.W_lambda_c_regularization); - osc->SetLambdaHolonomicRegularizationWeight(1e-5 * - osc_walking_gains.W_lambda_h_regularization); - osc->SetInputSmoothingCostWeights(osc_walking_gains.w_input_reg * - MatrixXd::Identity(n_u, n_u)); + osc->SetInputSmoothingCostWeights(gains.w_input_reg * + MatrixXd::Identity(n_u, n_u)); // Constraints in OSC multibody::KinematicEvaluatorSet evaluators(plant_w_spr); @@ -385,34 +362,33 @@ int DoMain(int argc, char* argv[]) { std::unique_ptr> right_fixed_knee_spring; std::unique_ptr> left_fixed_ankle_spring; std::unique_ptr> right_fixed_ankle_spring; - if (FLAGS_spring_model) { - auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_spr); - auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant_w_spr); - left_fixed_knee_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("knee_joint_left"), - vel_idx_map.at("knee_joint_leftdot"), 0); - right_fixed_knee_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("knee_joint_right"), - vel_idx_map.at("knee_joint_rightdot"), 0); - left_fixed_ankle_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("ankle_spring_joint_left"), - vel_idx_map.at("ankle_spring_joint_leftdot"), 0); - right_fixed_ankle_spring = std::make_unique>( - plant_w_spr, pos_idx_map.at("ankle_spring_joint_right"), - vel_idx_map.at("ankle_spring_joint_rightdot"), 0); - evaluators.add_evaluator(left_fixed_knee_spring.get()); - evaluators.add_evaluator(right_fixed_knee_spring.get()); - evaluators.add_evaluator(left_fixed_ankle_spring.get()); - evaluators.add_evaluator(right_fixed_ankle_spring.get()); - } - osc->AddKinematicConstraint(&evaluators); + auto pos_idx_map = multibody::MakeNameToPositionsMap(plant_w_spr); + auto vel_idx_map = multibody::MakeNameToVelocitiesMap(plant_w_spr); + left_fixed_knee_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("knee_joint_left"), + vel_idx_map.at("knee_joint_leftdot"), 0); + right_fixed_knee_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("knee_joint_right"), + vel_idx_map.at("knee_joint_rightdot"), 0); + left_fixed_ankle_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("ankle_spring_joint_left"), + vel_idx_map.at("ankle_spring_joint_leftdot"), 0); + right_fixed_ankle_spring = std::make_unique>( + plant_w_spr, pos_idx_map.at("ankle_spring_joint_right"), + vel_idx_map.at("ankle_spring_joint_rightdot"), 0); + evaluators.add_evaluator(left_fixed_knee_spring.get()); + evaluators.add_evaluator(right_fixed_knee_spring.get()); + evaluators.add_evaluator(left_fixed_ankle_spring.get()); + evaluators.add_evaluator(right_fixed_ankle_spring.get()); + osc->AddKinematicConstraint( + std::unique_ptr>(&evaluators)); // Soft constraint // w_contact_relax shouldn't be too big, cause we want tracking error to be // important - osc->SetContactSoftConstraintWeight(osc_walking_gains.w_soft_constraint); + osc->SetContactSoftConstraintWeight(gains.w_soft_constraint); // Friction coefficient - osc->SetContactFriction(osc_walking_gains.mu); + osc->SetContactFriction(gains.mu); // Add contact points (The position doesn't matter. It's not used in OSC) const auto& pelvis = plant_w_spr.GetBodyByName("pelvis"); multibody::WorldYawViewFrame view_frame(pelvis); @@ -428,28 +404,27 @@ int DoMain(int argc, char* argv[]) { auto right_heel_evaluator = multibody::WorldPointEvaluator( plant_w_spr, right_heel.first, right_heel.second, view_frame, Matrix3d::Identity(), Vector3d::Zero(), {0, 1, 2}); - osc->AddStateAndContactPoint(left_stance_state, &left_toe_evaluator); - osc->AddStateAndContactPoint(left_stance_state, &left_heel_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_toe_evaluator); - osc->AddStateAndContactPoint(right_stance_state, &right_heel_evaluator); - if (!FLAGS_is_two_phase) { - osc->AddStateAndContactPoint(post_left_double_support_state, - &left_toe_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &left_heel_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &right_toe_evaluator); - osc->AddStateAndContactPoint(post_left_double_support_state, - &right_heel_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &left_toe_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &left_heel_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &right_toe_evaluator); - osc->AddStateAndContactPoint(post_right_double_support_state, - &right_heel_evaluator); - } + + osc->AddContactPoint("left_toe", + std::unique_ptr>( + &left_toe_evaluator), + {left_stance_state, post_left_double_support_state, + post_right_double_support_state}); + osc->AddContactPoint("left_heel", + std::unique_ptr>( + &left_heel_evaluator), + {left_stance_state, post_left_double_support_state, + post_right_double_support_state}); + osc->AddContactPoint("right_toe", + std::unique_ptr>( + &right_toe_evaluator), + {right_stance_state, post_left_double_support_state, + post_right_double_support_state}); + osc->AddContactPoint("right_heel", + std::unique_ptr>( + &right_heel_evaluator), + {right_stance_state, post_left_double_support_state, + post_right_double_support_state}); // Swing foot tracking std::vector swing_ft_gain_multiplier_breaks{ @@ -462,6 +437,7 @@ int DoMain(int argc, char* argv[]) { PiecewisePolynomial::FirstOrderHold( swing_ft_gain_multiplier_breaks, swing_ft_gain_multiplier_samples)); + std::vector swing_ft_accel_gain_multiplier_breaks{ 0, left_support_duration / 2, left_support_duration * 3 / 4, left_support_duration}; @@ -469,102 +445,86 @@ int DoMain(int argc, char* argv[]) { 4, drake::MatrixX::Identity(3, 3)); swing_ft_accel_gain_multiplier_samples[2](2, 2) *= 0; swing_ft_accel_gain_multiplier_samples[3](2, 2) *= 0; + auto swing_ft_accel_gain_multiplier_gain_multiplier = std::make_shared>( PiecewisePolynomial::FirstOrderHold( swing_ft_accel_gain_multiplier_breaks, swing_ft_accel_gain_multiplier_samples)); - - auto swing_foot_data = std::make_unique ( - "swing_ft_data", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr); + auto swing_foot_data = std::make_unique( + "swing_ft_data", gains.K_p_swing_foot, gains.K_d_swing_foot, + gains.W_swing_foot, plant_w_spr, plant_w_spr); swing_foot_data->AddStateAndPointToTrack(left_stance_state, "toe_right"); swing_foot_data->AddStateAndPointToTrack(right_stance_state, "toe_left"); - swing_foot_data->SetImpactInvariantProjection(true); - auto vel_map = MakeNameToVelocitiesMap(plant_w_spr); - auto com_data = std::make_unique ("com_data", osc_walking_gains.K_p_swing_foot, - osc_walking_gains.K_d_swing_foot, osc_walking_gains.W_swing_foot, - plant_w_spr, plant_w_spr); + auto com_data = std::make_unique( + "com_data", gains.K_p_swing_foot, gains.K_d_swing_foot, + gains.W_swing_foot, plant_w_spr, plant_w_spr); com_data->AddFiniteStateToTrack(left_stance_state); com_data->AddFiniteStateToTrack(right_stance_state); - com_data->SetImpactInvariantProjection(true); - auto swing_ft_traj_local = std::make_unique ( - "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), + auto swing_ft_traj_local = std::make_unique( + "swing_ft_traj", gains.K_p_swing_foot, gains.K_d_swing_foot, + gains.W_swing_foot, plant_w_spr, plant_w_spr, swing_foot_data.get(), com_data.get()); auto pelvis_view_frame = std::make_shared>( plant_w_spr.GetBodyByName("pelvis")); swing_ft_traj_local->SetViewFrame(pelvis_view_frame); - auto swing_ft_traj_global = std::make_unique ( - "swing_ft_traj", osc_walking_gains.K_p_swing_foot, osc_walking_gains.K_d_swing_foot, - osc_walking_gains.W_swing_foot, plant_w_spr, plant_w_spr); - swing_ft_traj_global->AddStateAndPointToTrack(left_stance_state, "toe_right"); - swing_ft_traj_global->AddStateAndPointToTrack(right_stance_state, "toe_left"); - - if (FLAGS_spring_model) { - // swing_ft_traj.DisableFeedforwardAccel({2}); - } - swing_ft_traj_local->SetTimeVaryingPDGainMultiplier( swing_ft_gain_multiplier_gain_multiplier); swing_ft_traj_local->SetTimerVaryingFeedForwardAccelMultiplier( swing_ft_accel_gain_multiplier_gain_multiplier); osc->AddTrackingData(std::move(swing_ft_traj_local)); - - auto center_of_mass_traj = std::make_unique ("alip_com_traj", osc_walking_gains.K_p_com, - osc_walking_gains.K_d_com, osc_walking_gains.W_com, plant_w_spr, - plant_w_spr); + auto center_of_mass_traj = std::make_unique( + "alip_com_traj", gains.K_p_com, gains.K_d_com, gains.W_com, plant_w_spr, + plant_w_spr); // FiniteStatesToTrack cannot be empty center_of_mass_traj->AddFiniteStateToTrack(-1); osc->AddTrackingData(std::move(center_of_mass_traj)); // Pelvis rotation tracking (pitch and roll) - auto pelvis_balance_traj = std::make_unique ( - "pelvis_balance_traj", osc_walking_gains.K_p_pelvis_balance, osc_walking_gains.K_d_pelvis_balance, - osc_walking_gains.W_pelvis_balance, plant_w_spr, plant_w_spr); + auto pelvis_balance_traj = std::make_unique( + "pelvis_balance_traj", gains.K_p_pelvis_balance, gains.K_d_pelvis_balance, + gains.W_pelvis_balance, plant_w_spr, plant_w_spr); pelvis_balance_traj->AddFrameToTrack("pelvis"); - pelvis_balance_traj->SetImpactInvariantProjection(true); osc->AddTrackingData(std::move(pelvis_balance_traj)); // Pelvis rotation tracking (yaw) - auto pelvis_heading_traj = std::make_unique ( - "pelvis_heading_traj", osc_walking_gains.K_p_pelvis_heading, osc_walking_gains.K_d_pelvis_heading, - osc_walking_gains.W_pelvis_heading, plant_w_spr, plant_w_spr); + auto pelvis_heading_traj = std::make_unique( + "pelvis_heading_traj", gains.K_p_pelvis_heading, gains.K_d_pelvis_heading, + gains.W_pelvis_heading, plant_w_spr, plant_w_spr); pelvis_heading_traj->AddFrameToTrack("pelvis"); osc->AddTrackingData(std::move(pelvis_heading_traj), - osc_walking_gains.period_of_no_heading_control); + gains.period_of_no_heading_control); // Swing toe joint tracking - auto swing_toe_traj_left = std::make_unique ( - "left_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, - osc_walking_gains.W_swing_toe, plant_w_spr, plant_w_spr); - auto swing_toe_traj_right = std::make_unique ( - "right_toe_angle_traj", osc_walking_gains.K_p_swing_toe, osc_walking_gains.K_d_swing_toe, - osc_walking_gains.W_swing_toe, plant_w_spr, plant_w_spr); + auto swing_toe_traj_left = std::make_unique( + "left_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, + gains.W_swing_toe, plant_w_spr, plant_w_spr); + auto swing_toe_traj_right = std::make_unique( + "right_toe_angle_traj", gains.K_p_swing_toe, gains.K_d_swing_toe, + gains.W_swing_toe, plant_w_spr, plant_w_spr); swing_toe_traj_right->AddStateAndJointToTrack(left_stance_state, "toe_right", - "toe_rightdot"); + "toe_rightdot"); swing_toe_traj_left->AddStateAndJointToTrack(right_stance_state, "toe_left", - "toe_leftdot"); + "toe_leftdot"); osc->AddTrackingData(std::move(swing_toe_traj_left)); osc->AddTrackingData(std::move(swing_toe_traj_right)); - auto hip_yaw_traj_gen = builder.AddSystem(left_stance_state); // Swing hip yaw joint tracking - auto swing_hip_yaw_traj = std::make_unique ( - "swing_hip_yaw_traj", osc_walking_gains.K_p_hip_yaw, osc_walking_gains.K_d_hip_yaw, - osc_walking_gains.W_hip_yaw, plant_w_spr, plant_w_spr); - swing_hip_yaw_traj->AddStateAndJointToTrack(left_stance_state, "hip_yaw_right", - "hip_yaw_rightdot"); - swing_hip_yaw_traj->AddStateAndJointToTrack(right_stance_state, "hip_yaw_left", - "hip_yaw_leftdot"); + auto swing_hip_yaw_traj = std::make_unique( + "swing_hip_yaw_traj", gains.K_p_hip_yaw, gains.K_d_hip_yaw, + gains.W_hip_yaw, plant_w_spr, plant_w_spr); + swing_hip_yaw_traj->AddStateAndJointToTrack( + left_stance_state, "hip_yaw_right", "hip_yaw_rightdot"); + swing_hip_yaw_traj->AddStateAndJointToTrack( + right_stance_state, "hip_yaw_left", "hip_yaw_leftdot"); if (FLAGS_use_radio) { builder.Connect(cassie_out_to_radio->get_output_port(), @@ -581,16 +541,25 @@ int DoMain(int argc, char* argv[]) { double_support_duration, left_stance_state, right_stance_state, {post_left_double_support_state, post_right_double_support_state}); - - osc->SetOsqpSolverOptionsFromYaml(FLAGS_osqp_settings); - - // Build OSC problem + osc->SetOsqpSolverOptionsFromYaml( + "examples/Cassie/osc/solver_settings/osqp_options_walking.yaml"); + + if (gains.W_com(0, 0) == 0) { + osc->SetInputCostForJointAndFsmStateWeight("toe_left_motor", + left_stance_state, 1.0); + osc->SetInputCostForJointAndFsmStateWeight( + "toe_left_motor", post_right_double_support_state, 1.0); + osc->SetInputCostForJointAndFsmStateWeight("toe_right_motor", + right_stance_state, 1.0); + osc->SetInputCostForJointAndFsmStateWeight( + "toe_right_motor", post_left_double_support_state, 1.0); + } osc->Build(); // Connect ports builder.Connect(simulator_drift->get_output_port(0), osc->get_input_port_robot_output()); - builder.Connect(fsm->get_fsm_output_port(), osc->get_input_port_fsm()); + builder.Connect(fsm->get_output_port(0), osc->get_input_port_fsm()); builder.Connect(alip_traj_generator->get_output_port_com(), osc->get_input_port_tracking_data("alip_com_traj")); builder.Connect(swing_ft_traj_generator->get_output_port(0), @@ -614,17 +583,17 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_WALKING", &lcm_local, TriggerTypeSet({TriggerType::kForced}))); - builder.Connect(osc->get_output_port_osc_debug(), osc_debug_pub->get_input_port()); + builder.Connect(osc->get_output_port_osc_debug(), + osc_debug_pub->get_input_port()); } // Create the diagram auto owned_diagram = builder.Build(); - std::shared_ptr> shared_diagram = std::move(owned_diagram); - shared_diagram->set_name("osc walking controller"); + owned_diagram->set_name("osc walking controller"); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm_local, shared_diagram, state_receiver, FLAGS_channel_x, + &lcm_local, std::move(owned_diagram), state_receiver, FLAGS_channel_x, true); loop.Simulate(); @@ -633,4 +602,4 @@ int DoMain(int argc, char* argv[]) { } // namespace dairlib -int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } +int main(int argc, char* argv[]) { return dairlib::DoMain(argc, argv); } \ No newline at end of file diff --git a/examples/franka/diagrams/franka_osc_controller_diagram.cc b/examples/franka/diagrams/franka_osc_controller_diagram.cc index 21b8967d33..854581ab80 100644 --- a/examples/franka/diagrams/franka_osc_controller_diagram.cc +++ b/examples/franka/diagrams/franka_osc_controller_diagram.cc @@ -130,7 +130,7 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( auto end_effector_force_trajectory = builder.AddSystem(); auto osc = builder.AddSystem( - *plant_, *plant_, plant_context_.get(), plant_context_.get(), false); + *plant_, plant_context_.get(), false); if (controller_params.publish_debug_info) { auto franka_command_pub = builder.AddSystem(LcmPublisherSystem::Make( @@ -194,9 +194,11 @@ FrankaOSCControllerDiagram::FrankaOSCControllerDiagram( osc->SetAccelerationCostWeights(gains.W_acceleration); osc->SetInputCostWeights(gains.W_input_regularization); osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); - osc->SetAccelerationConstraints( - controller_params.enforce_acceleration_constraints); - + if (controller_params.enforce_acceleration_constraints) { + osc->EnableAccelerationConstraints(); + } else { + osc->DisableAccelerationConstraints(); + } osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 1cba2b9e70..42dad9d4d6 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -154,7 +154,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), false); + plant, plant_context.get(), false); if (controller_params.publish_debug_info) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( @@ -206,9 +206,11 @@ int DoMain(int argc, char* argv[]) { osc->SetAccelerationCostWeights(gains.W_acceleration); osc->SetInputCostWeights(gains.W_input_regularization); osc->SetInputSmoothingCostWeights(gains.W_input_smoothing_regularization); - osc->SetAccelerationConstraints( - controller_params.enforce_acceleration_constraints); - + if (controller_params.enforce_acceleration_constraints) { + osc->EnableAccelerationConstraints(); + } else { + osc->DisableAccelerationConstraints(); + } osc->SetContactFriction(controller_params.mu); osc->SetOsqpSolverOptions(solver_options); diff --git a/examples/impact_invariant_control/run_joint_space_walking_controller.cc b/examples/impact_invariant_control/run_joint_space_walking_controller.cc index 2156fe9e66..763ec4845b 100644 --- a/examples/impact_invariant_control/run_joint_space_walking_controller.cc +++ b/examples/impact_invariant_control/run_joint_space_walking_controller.cc @@ -123,7 +123,7 @@ int DoMain(int argc, char* argv[]) { FLAGS_channel_u, &lcm, TriggerTypeSet({TriggerType::kForced}))); auto command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), true); + plant, plant_context.get(), true); auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( "OSC_DEBUG_WALKING", &lcm, TriggerTypeSet({TriggerType::kForced}))); @@ -147,8 +147,15 @@ int DoMain(int argc, char* argv[]) { plant, foot_contact_disp, plant.GetBodyByName("right_foot").body_frame(), Matrix3d::Identity(), Vector3d::Zero(), {0, 2}); - osc->AddStateAndContactPoint(0, &left_foot_evaluator); - osc->AddStateAndContactPoint(1, &right_foot_evaluator); + osc->AddContactPoint( + "left_foot", + std::unique_ptr>(&left_foot_evaluator), + {0}); + osc->AddContactPoint( + "right_foot", + std::unique_ptr>(&right_foot_evaluator), + {1}); + // Create maps for joints map pos_map_wo_spr = multibody::MakeNameToPositionsMap(plant); diff --git a/examples/sampling_c3/franka_joint_osc_controller.cc b/examples/sampling_c3/franka_joint_osc_controller.cc index fbc46b9ef4..866bd7196b 100644 --- a/examples/sampling_c3/franka_joint_osc_controller.cc +++ b/examples/sampling_c3/franka_joint_osc_controller.cc @@ -102,7 +102,7 @@ int DoMain(int argc, char* argv[]) { auto osc_command_sender = builder.AddSystem(plant); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), false); + plant, plant_context.get(), false); if (osc_params.publish_debug_info) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( diff --git a/examples/sampling_c3/franka_osc_controller.cc b/examples/sampling_c3/franka_osc_controller.cc index 58d92e699c..871d3dca53 100644 --- a/examples/sampling_c3/franka_osc_controller.cc +++ b/examples/sampling_c3/franka_osc_controller.cc @@ -136,7 +136,7 @@ int DoMain(int argc, char* argv[]) { builder.AddSystem(LcmSubscriberSystem::Make( lcm_channel_params.radio_channel, &lcm)); auto osc = builder.AddSystem( - plant, plant, plant_context.get(), plant_context.get(), false); + plant, plant_context.get(), false); if (osc_params.publish_debug_info) { auto osc_debug_pub = builder.AddSystem(LcmPublisherSystem::Make( @@ -189,9 +189,11 @@ int DoMain(int argc, char* argv[]) { osc->SetAccelerationCostWeights(osc_params.W_acceleration); osc->SetInputCostWeights(osc_params.W_input_regularization); osc->SetInputSmoothingCostWeights(osc_params.W_input_smoothing_regularization); - osc->SetAccelerationConstraints( - osc_params.enforce_acceleration_constraints); - + if (osc_params.enforce_acceleration_constraints) { + osc->EnableAccelerationConstraints(); + } else { + osc->DisableAccelerationConstraints(); + } osc->SetContactFriction(osc_params.mu); osc->SetOsqpSolverOptions(solver_options); diff --git a/lcmtypes/lcmt_osc_qp_output.lcm b/lcmtypes/lcmt_osc_qp_output.lcm index 0f2163b1c3..ae7bacd0fb 100644 --- a/lcmtypes/lcmt_osc_qp_output.lcm +++ b/lcmtypes/lcmt_osc_qp_output.lcm @@ -5,12 +5,14 @@ struct lcmt_osc_qp_output int32_t u_dim; int32_t lambda_c_dim; int32_t lambda_h_dim; + int32_t lambda_e_dim; int32_t v_dim; int32_t epsilon_dim; double solve_time; double u_sol[u_dim]; double lambda_c_sol[lambda_c_dim]; double lambda_h_sol[lambda_h_dim]; + double lambda_e_sol[lambda_e_dim]; double dv_sol[v_dim]; double epsilon_sol[epsilon_dim]; } diff --git a/multibody/kinematic/kinematic_evaluator_set.cc b/multibody/kinematic/kinematic_evaluator_set.cc index c992f8b67f..551ff7e646 100644 --- a/multibody/kinematic/kinematic_evaluator_set.cc +++ b/multibody/kinematic/kinematic_evaluator_set.cc @@ -150,7 +150,7 @@ VectorX KinematicEvaluatorSet::EvalFullJacobianDotTimesV( } template -int KinematicEvaluatorSet::add_evaluator(KinematicEvaluator* e) { +int KinematicEvaluatorSet::add_evaluator(const KinematicEvaluator* e) { // Compare plants for equality by reference DRAKE_DEMAND(&plant_ == &e->plant()); diff --git a/multibody/kinematic/kinematic_evaluator_set.h b/multibody/kinematic/kinematic_evaluator_set.h index 62f65ee9ac..b7e4c00f1a 100644 --- a/multibody/kinematic/kinematic_evaluator_set.h +++ b/multibody/kinematic/kinematic_evaluator_set.h @@ -150,12 +150,12 @@ class KinematicEvaluatorSet { return *evaluators_.at(index); }; - const std::vector*>& get_evaluators() const { + const std::vector*>& get_evaluators() const { return evaluators_; }; /// Adds an evaluator to the end of the list, returning the associated index - int add_evaluator(KinematicEvaluator* e); + int add_evaluator(const KinematicEvaluator* e); /// Count the total number of active rows int count_active() const; @@ -174,7 +174,7 @@ class KinematicEvaluatorSet { private: const drake::multibody::MultibodyPlant& plant_; - std::vector*> evaluators_; + std::vector*> evaluators_; }; } // namespace multibody diff --git a/solvers/fast_osqp_solver.cc b/solvers/fast_osqp_solver.cc index a755752ca0..62341fadc5 100644 --- a/solvers/fast_osqp_solver.cc +++ b/solvers/fast_osqp_solver.cc @@ -450,6 +450,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, osqp_update_bounds(workspace_, l_.data(), u_.data()); osqp_update_P_A(workspace_, P_csc_->x, OSQP_NULL, P_csc_->nzmax, A_csc_->x, OSQP_NULL, A_csc_->nzmax); + osqp_update_warm_start(workspace_, osqp_settings_->warm_start); // If any step fails, it will set the solution_result and skip other steps. std::optional solution_result; @@ -458,6 +459,7 @@ void FastOsqpSolver::DoSolve(const MathematicalProgram& prog, if (!solution_result) { DRAKE_THROW_UNLESS(workspace_ != nullptr); const c_int osqp_solve_err = osqp_solve(workspace_); + DisableWarmStart(); // will only be re-enabled if the solve was successful if (osqp_solve_err != 0) { solution_result = SolutionResult::kInvalidInput; } diff --git a/solvers/fast_osqp_solver.h b/solvers/fast_osqp_solver.h index 53ac6d51a6..ec7d3d0789 100644 --- a/solvers/fast_osqp_solver.h +++ b/solvers/fast_osqp_solver.h @@ -68,7 +68,6 @@ class FastOsqpSolver final : public drake::solvers::SolverBase { void DisableWarmStart() const { osqp_settings_->warm_start = false; warm_start_ = false; - is_init_ = false; } /// Solver will automatically reenable warm starting after a successful solve void EnableWarmStart() const { diff --git a/systems/controllers/osc/BUILD.bazel b/systems/controllers/osc/BUILD.bazel index 8a8a82a367..9c6f20abd4 100644 --- a/systems/controllers/osc/BUILD.bazel +++ b/systems/controllers/osc/BUILD.bazel @@ -2,6 +2,16 @@ load("@drake//tools/lint:lint.bzl", "add_lint_tests") package(default_visibility = ["//visibility:public"]) +cc_library( + name = "inverse_dynamics_qp", + srcs = ["inverse_dynamics_qp.cc"], + hdrs = ["inverse_dynamics_qp.h"], + deps = [ + "//multibody/kinematic", + "@drake//:drake_shared_library", + ], +) + cc_library( name = "operational_space_control", srcs = [ @@ -11,6 +21,7 @@ cc_library( "operational_space_control.h", ], deps = [ + ":inverse_dynamics_qp", ":osc_gains", ":osc_tracking_datas", "//common:eigen_utils", diff --git a/systems/controllers/osc/external_force_tracking_data.cc b/systems/controllers/osc/external_force_tracking_data.cc index 9433b1b7b1..bdea677c65 100644 --- a/systems/controllers/osc/external_force_tracking_data.cc +++ b/systems/controllers/osc/external_force_tracking_data.cc @@ -16,8 +16,8 @@ namespace dairlib::systems::controllers { ExternalForceTrackingData::ExternalForceTrackingData( const string& name, const MatrixXd& W, const MultibodyPlant& plant_w_spr, - const MultibodyPlant& plant_wo_spr, - const std::string& body_name, const Vector3d& pt_on_body) + const MultibodyPlant& plant_wo_spr, const std::string& body_name, + const Vector3d& pt_on_body) : name_(name), plant_w_spr_(plant_w_spr), plant_wo_spr_(plant_wo_spr), @@ -27,7 +27,6 @@ ExternalForceTrackingData::ExternalForceTrackingData( body_frame_wo_spr_(&plant_wo_spr_.GetBodyByName(body_name).body_frame()), pt_on_body_(pt_on_body), W_(W) { - J_ = MatrixXd::Zero(3, plant_wo_spr_.num_velocities()); lambda_des_ = Vector3d::Zero(); } @@ -36,14 +35,9 @@ void ExternalForceTrackingData::Update( const drake::systems::Context& context_w_spr, const Eigen::VectorXd& x_wo_spr, const drake::systems::Context& context_wo_spr, - const drake::trajectories::Trajectory& traj, - double t) { + const drake::trajectories::Trajectory& traj, double t) { DRAKE_DEMAND(traj.rows() == 3); lambda_des_ = traj.value(t); - J_ = MatrixXd::Zero(3, plant_wo_spr_.num_velocities()); - plant_wo_spr_.CalcJacobianTranslationalVelocity( - context_wo_spr, JacobianWrtVariable::kV, *body_frame_wo_spr_, pt_on_body_, - world_wo_spr_, world_wo_spr_, &J_); } -} // namespace dairlib::systems::controllers +} // namespace dairlib::systems::controllers \ No newline at end of file diff --git a/systems/controllers/osc/external_force_tracking_data.h b/systems/controllers/osc/external_force_tracking_data.h index b97a0aa7d6..d27996ae55 100644 --- a/systems/controllers/osc/external_force_tracking_data.h +++ b/systems/controllers/osc/external_force_tracking_data.h @@ -19,11 +19,12 @@ class ExternalForceTrackingData { const std::string& body_name, const Eigen::Vector3d& pt_on_body); const Eigen::MatrixXd& GetWeight() const { return W_; } - - const Eigen::MatrixXd& GetJ() const { return J_; } const Eigen::VectorXd& GetLambdaDes() const { return lambda_des_; } const std::string& GetName() const { return name_; }; - int GetLambdaDim() const { return n_lambda_; }; + const Eigen::Vector3d& GetPointOnBody() const { return pt_on_body_; }; + const drake::multibody::Frame& GetBodyFrame() const { + return *body_frame_wo_spr_; + }; const drake::multibody::MultibodyPlant& plant_w_spr() const { return plant_w_spr_; @@ -35,8 +36,7 @@ class ExternalForceTrackingData { const drake::systems::Context& context_w_spr, const Eigen::VectorXd& x_wo_spr, const drake::systems::Context& context_wo_spr, - const drake::trajectories::Trajectory& traj, - double t); + const drake::trajectories::Trajectory& traj, double t); protected: private: @@ -52,10 +52,7 @@ class ExternalForceTrackingData { const drake::multibody::RigidBodyFrame* body_frame_wo_spr_; const Eigen::Vector3d pt_on_body_; - int n_lambda_ = 3; - Eigen::VectorXd lambda_des_; - Eigen::MatrixXd J_; Eigen::MatrixXd W_; }; diff --git a/systems/controllers/osc/inverse_dynamics_qp.cc b/systems/controllers/osc/inverse_dynamics_qp.cc new file mode 100644 index 0000000000..54771032f3 --- /dev/null +++ b/systems/controllers/osc/inverse_dynamics_qp.cc @@ -0,0 +1,232 @@ +#include "inverse_dynamics_qp.h" + +#include "multibody/multibody_utils.h" + +namespace dairlib { +namespace systems { +namespace controllers { + +using std::string; +using std::unique_ptr; +using std::vector; + +using Eigen::MatrixXd; +using Eigen::VectorXd; + +using multibody::KinematicEvaluator; +using multibody::KinematicEvaluatorSet; +using multibody::SetPositionsAndVelocitiesIfNew; +using multibody::WorldPointEvaluator; + +using drake::multibody::MultibodyPlant; +using drake::solvers::MathematicalProgram; +using drake::solvers::VariableRefList; +using drake::solvers::VectorXDecisionVariable; +using drake::systems::Context; + +InverseDynamicsQp::InverseDynamicsQp(const MultibodyPlant& plant, + Context* context) + : plant_(plant), + context_(context), + nq_(plant.num_positions()), + nv_(plant.num_velocities()), + nu_(plant.num_actuated_dofs()) {} + +void InverseDynamicsQp::AddHolonomicConstraint( + unique_ptr> eval) { + DRAKE_DEMAND(&eval->plant() == &plant_); + DRAKE_DEMAND(not built_); + DRAKE_DEMAND(holonomic_constraints_ == nullptr); + DRAKE_DEMAND(nh_ == 0); + + holonomic_constraints_ = std::move(eval); + nh_ = holonomic_constraints_->count_full(); +} + +void InverseDynamicsQp::AddContactConstraint( + const string& name, unique_ptr> eval, + double friction_coefficient) { + DRAKE_DEMAND(not built_); + DRAKE_DEMAND(friction_coefficient >= 0); + DRAKE_DEMAND(contact_constraint_evaluators_.count(name) == 0); + DRAKE_DEMAND(&eval->plant() == &plant_); + + mu_map_.insert({name, friction_coefficient}); + lambda_c_start_.insert({name, nc_}); + Jc_active_start_.insert({name, nc_active_}); + contact_constraint_evaluators_.insert({name, std::move(eval)}); + + nc_ += contact_constraint_evaluators_.at(name)->num_full(); + nc_active_ += contact_constraint_evaluators_.at(name)->num_active(); +} + +void InverseDynamicsQp::AddExternalForce( + const string& name, unique_ptr> eval) { + DRAKE_DEMAND(not built_); + DRAKE_DEMAND(&eval->plant() == &plant_); + DRAKE_DEMAND(external_force_evaluators_.count(name) == 0); + + external_force_evaluators_.insert({name, std::move(eval)}); + lambda_e_start_and_size_.insert( + {name, {ne_, external_force_evaluators_.at(name)->num_full()}}); + ne_ += external_force_evaluators_.at(name)->num_full(); +} + +void InverseDynamicsQp::Build() { + DRAKE_DEMAND(not built_); + + dv_ = prog_.NewContinuousVariables(nv_, "dv"); + u_ = prog_.NewContinuousVariables(nu_, "u"); + lambda_h_ = prog_.NewContinuousVariables(nh_, "lambda_holonomic"); + lambda_c_ = prog_.NewContinuousVariables(nc_, "lambda_contact"); + lambda_e_ = prog_.NewContinuousVariables(ne_, "lambda_external"); + epsilon_ = prog_.NewContinuousVariables(nc_active_, "soft_constraint_slack"); + + dynamics_c_ = + prog_ + .AddLinearEqualityConstraint( + MatrixXd::Zero(nv_, nv_ + nu_ + nh_ + nc_ + ne_), + VectorXd::Zero(nv_), {dv_, u_, lambda_h_, lambda_c_, lambda_e_}) + .evaluator(); + + holonomic_c_ = prog_ + .AddLinearEqualityConstraint(MatrixXd::Zero(nh_, nv_), + VectorXd::Zero(nh_), dv_) + .evaluator(); + + contact_c_ = prog_ + .AddLinearEqualityConstraint( + MatrixXd::Zero(nc_active_, nv_ + nc_active_), + VectorXd::Zero(nc_active_), {dv_, epsilon_}) + .evaluator(); + + for (const auto& [cname, eval] : contact_constraint_evaluators_) { + double mu = mu_map_.at(cname); + MatrixXd A = MatrixXd(5, 3); + A << -1, 0, mu, 0, -1, mu, 1, 0, mu, 0, 1, mu, 0, 0, 1; + lambda_c_friction_cone_.insert( + {cname, + prog_ + .AddLinearConstraint( + A, VectorXd::Zero(5), + VectorXd::Constant(5, std::numeric_limits::infinity()), + lambda_c_.segment(lambda_c_start_.at(cname), 3)) + .evaluator()}); + } + + if (with_input_constraints_) { + VectorXd u_min(nu_); + VectorXd u_max(nu_); + for (drake::multibody::JointActuatorIndex i(0); i < nu_; ++i) { + u_min[i] = -plant_.get_joint_actuator(i).effort_limit(); + u_max[i] = plant_.get_joint_actuator(i).effort_limit(); + } + input_limit_c_ = + prog_.AddBoundingBoxConstraint(u_min, u_max, u_).evaluator(); + } + + if (with_acceleration_constraints_) { + VectorXd ddq_min = VectorXd::Zero(nq_); + VectorXd ddq_max = VectorXd::Zero(nq_); + for (drake::multibody::JointIndex i(0); i < nq_; ++i) { + if (plant_.get_joint(i).acceleration_lower_limits().size() != 0) { + ddq_min[i] = plant_.get_joint(i).acceleration_lower_limits()[0]; + ddq_max[i] = plant_.get_joint(i).acceleration_upper_limits()[0]; + } + } + if (ddq_max.isZero()) { + throw std::runtime_error( + "Attempting to set acceleration limits when acceleration limits have " + "not been defined for the plant."); + } + acceleration_limit_c_ = + prog_.AddBoundingBoxConstraint(ddq_min, ddq_max, dv_).evaluator(); + } + built_ = true; +} + +void InverseDynamicsQp::AddQuadraticCost(const string& name, const MatrixXd& Q, + const VectorXd& b, + const VariableRefList& vars) { + DRAKE_DEMAND(built_); + DRAKE_DEMAND(all_costs_.count(name) == 0); + all_costs_.insert({name, prog_.AddQuadraticCost(Q, b, vars).evaluator()}); +} + +void InverseDynamicsQp::AddQuadraticCost(const string& name, const MatrixXd& Q, + const VectorXd& b, + const VectorXDecisionVariable& vars) { + DRAKE_DEMAND(built_); + DRAKE_DEMAND(all_costs_.count(name) == 0); + all_costs_.insert({name, prog_.AddQuadraticCost(Q, b, vars).evaluator()}); +} + +void InverseDynamicsQp::UpdateDynamics( + const VectorXd& x, const vector& active_contact_constraints, + const vector& active_external_forces) { + SetPositionsAndVelocitiesIfNew(plant_, x, context_); + + MatrixXd M(nv_, nv_); + VectorXd bias(nv_); + MatrixXd B = plant_.MakeActuationMatrix(); + VectorXd grav = plant_.CalcGravityGeneralizedForces(*context_); + + plant_.CalcMassMatrix(*context_, &M); + plant_.CalcBiasTerm(*context_, &bias); + + if (with_gravity_compensation_) { + bias = bias - grav; + } + + MatrixXd Jh = MatrixXd::Zero(nh_, nv_); + VectorXd Jh_dot_v = VectorXd::Zero(nh_); + + if (holonomic_constraints_ != nullptr) { + Jh = holonomic_constraints_->EvalFullJacobian(*context_); + Jh_dot_v = holonomic_constraints_->EvalFullJacobianDotTimesV(*context_); + } + + MatrixXd Jc_active = MatrixXd::Zero(nc_active_, nv_); + VectorXd Jc_active_dot_v = VectorXd::Zero(nc_active_); + MatrixXd Jc = MatrixXd::Zero(nc_, nv_); + MatrixXd Je = MatrixXd::Zero(ne_, nv_); + + for (const auto& c : active_contact_constraints) { + DRAKE_DEMAND(contact_constraint_evaluators_.count(c) > 0); + const auto& evaluator = contact_constraint_evaluators_.at(c); + Jc.block(lambda_c_start_.at(c), 0, 3, nv_) = + evaluator->EvalFullJacobian(*context_); + int start = Jc_active_start_.at(c); + for (int i = 0; i < evaluator->num_active(); ++i) { + Jc_active.row(start + i) = + Jc.row(lambda_c_start_.at(c) + evaluator->active_inds().at(i)); + Jc_active_dot_v.segment(start, evaluator->num_active()) = + evaluator->EvalActiveJacobianDotTimesV(*context_); + } + } + for (const auto& e : active_external_forces) { + const auto& [start, size] = lambda_e_start_and_size_.at(e); + Je.block(start, 0, size, nv_) = + external_force_evaluators_.at(e)->EvalFullJacobian(*context_); + } + + MatrixXd A_dyn = MatrixXd::Zero(nv_, nv_ + nu_ + nh_ + nc_ + ne_); + A_dyn.block(0, 0, nv_, nv_) = M; + A_dyn.block(0, nv_, nv_, nu_) = -B; + A_dyn.block(0, nv_ + nu_, nv_, nh_) = -Jh.transpose(); + A_dyn.block(0, nv_ + nu_ + nh_, nv_, nc_) = -Jc.transpose(); + A_dyn.block(0, nv_ + nu_ + nh_ + nc_, nv_, ne_) = -Je.transpose(); + + MatrixXd A_c = MatrixXd::Zero(nc_active_, nv_ + nc_active_); + A_c.block(0, 0, nc_active_, nv_) = Jc_active; + A_c.block(0, nv_, nc_active_, nc_active_) = + MatrixXd::Identity(nc_active_, nc_active_); + + dynamics_c_->UpdateCoefficients(A_dyn, -bias); + holonomic_c_->UpdateCoefficients(Jh, -Jh_dot_v); + contact_c_->UpdateCoefficients(A_c, -Jc_active_dot_v); +} + +} // namespace controllers +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/controllers/osc/inverse_dynamics_qp.h b/systems/controllers/osc/inverse_dynamics_qp.h new file mode 100644 index 0000000000..4741e5d544 --- /dev/null +++ b/systems/controllers/osc/inverse_dynamics_qp.h @@ -0,0 +1,341 @@ +#pragma once +#include "multibody/kinematic/kinematic_evaluator_set.h" +#include "multibody/kinematic/world_point_evaluator.h" + +#include "drake/multibody/plant/multibody_plant.h" +#include "drake/solvers/mathematical_program.h" + +namespace dairlib { +namespace systems { +namespace controllers { + +using CostMap = + std::unordered_map>; + +using FrictionConeMap = + std::unordered_map>; + +using ContactMap = std::unordered_map< + std::string, std::unique_ptr>>; + +/*! + * Wrapper class for handling kinematics and dynamics for a quadratic program + * which computes dynamically consistent accelerations, inputs, + * and constraint forces (including contacts) which minimize some combined + * cost on these variables. + * + * Designed to be used as a back-end for operational space control, but + * applicable to other model-based instantaneous QP controllers. + * + * Constructs a QP of the form + * + * minimize C₁(v̇) + C₂(u), C₃(λₕ) + C₄(λ_c) + C₄(λₑ) + * subject to Jₕv̇ + J̇ₕ = 0 + * J_cv̇ + J̇_c = 0 + * Mv̇ + c = Bu + Jₕᵀλₕ + J_cᵀλ_c + Jₑᵀλₑ + * λ_c ∈ FrictionCone + * + * Where + * + * Cᵢ are arbitrary user-defined convex quadratic costs, + * v̇ are generalized accelerations, + * u are actuation efforts, + * λₕ are constraint forces for general holonomic constraints such linkages, + * λ_c are constraint forces for contact constraints + * λₑ are external forces, such as contact forces, which do not constrain the + * robot's motion (like force on the end effector of a robot arm) + * + */ +class InverseDynamicsQp { + public: + InverseDynamicsQp(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context); + + /*! + * @brief Adds the set of holonomic constraints given by eval to the QP. + */ + void AddHolonomicConstraint( + std::unique_ptr> eval); + + /*! + * Adds a contact constraint + * @param name name of the contact constraint + * @param eval WorldPointEvaluator describing the contact point + * @param friction_coefficient friction coefficient of the friction cone for + * the associated contact force + */ + void AddContactConstraint( + const std::string& name, + std::unique_ptr> eval, + double friction_coefficient); + + /*! + * Adds an external force to the dynamics. + * + * Note: By default, no constraints are imposed on the external forces. If + * external forces are declared without corresponding constraints/costs + * from the upstream controller, then unexpected behavior may occur. + * (i.e. Unconstrained forces effectively act as input variables.) + * + * @param name name of the external force + * @param eval WorldPointEvaluator for the associated jacobian + */ + void AddExternalForce( + const std::string& name, + std::unique_ptr> eval); + + /*! + * Adds the quadratic cost 1/2 xᵀQx + bᵀx to the underlying QP + * + * Must be called AFTER build + * + * @param name name of the cost (must be unique) + * @param Q PSD cost hessian + * @param b linear term + * @param vars decision variables representing x + */ + void AddQuadraticCost(const std::string& name, const Eigen::MatrixXd& Q, + const Eigen::VectorXd& b, + const drake::solvers::VectorXDecisionVariable& vars); + + /*! + * See above + */ + void AddQuadraticCost(const std::string& name, const Eigen::MatrixXd& Q, + const Eigen::VectorXd& b, + const drake::solvers::VariableRefList& vars); + + /*! + * Builds the underlying QP + */ + void Build(); + + /*! + * @return the total dimension of the (stacked) contact forces. + * This is greater than or equal to the number of active rows in the + * contact constraint (see kinematic_evaluator.h). + */ + [[nodiscard]] int nc() const { return nc_; } + + /*! + * @return the total dimension of the holonomic constraint forces. + * Equal to the number of rows in the holonomic constraint. + */ + [[nodiscard]] int nh() const { return nh_; } + + /*! + * @return the total dimension of the external forces. + * This is equal to the number of rows in the external force constraint. + */ + [[nodiscard]] int ne() const { return ne_; } + + /*! + * @return the total number of active rows in the contact constraint for all + * contacts. Potentially less than nc() to avoid redundant constraints. + */ + [[nodiscard]] int nc_active() const { return nc_active_; } + + /* + * N.B. To avoid overhead in the OSC loop, we don't check the if the QP is + * built before these are called, but the decision variables are empty + * until then! + */ + [[nodiscard]] const drake::solvers::VectorXDecisionVariable& dv() const { + return dv_; + } + [[nodiscard]] const drake::solvers::VectorXDecisionVariable& u() const { + return u_; + } + [[nodiscard]] const drake::solvers::VectorXDecisionVariable& lambda_h() + const { + return lambda_h_; + } + [[nodiscard]] const drake::solvers::VectorXDecisionVariable& lambda_c() + const { + return lambda_c_; + } + [[nodiscard]] const drake::solvers::VectorXDecisionVariable& lambda_e() + const { + return lambda_e_; + } + [[nodiscard]] const drake::solvers::VectorXDecisionVariable& epsilon() const { + return epsilon_; + } + + /*! + * @return a const-reference to the underlying MathematicalProgram + */ + [[nodiscard]] const drake::solvers::MathematicalProgram& get_prog() const { + return prog_; + } + + /*! + * @return a mutable reference to the underlying MathematicalProgram + */ + [[nodiscard]] drake::solvers::MathematicalProgram& get_mutable_prog() { + return prog_; + } + + /*! + * @brief gets a const reference WorldPointEvaluator for the contact with + * the given name + */ + [[nodiscard]] const multibody::WorldPointEvaluator& + get_contact_evaluator(const std::string& name) const { + return *contact_constraint_evaluators_.at(name); + } + + /*! + * @brief gets a const reference to the KinematicEvaluatorSet associated + * with the holonomic constraints + */ + [[nodiscard]] const multibody::KinematicEvaluatorSet& + get_holonomic_evaluators() const { + return *holonomic_constraints_; + } + + /*! + * @brief updates the coefficients of the cost with the given name to + * 1/2 xᵀQx + bᵀx + c + */ + void UpdateCost(const std::string& name, const Eigen::MatrixXd& Q, + const Eigen::VectorXd& b, double c = 0) { + all_costs_.at(name)->UpdateCoefficients(Q, b, c, true); + }; + + /*! + * updates the dynamics and contact constraints to reflect a given + * state and contact configuration. + * @param x the robot state [q, v] + * @param active_contact_constraints the names of all contact constraints + * currently in contact + * @param active_external_forces the names of all the external forces + * currently being applied + */ + void UpdateDynamics( + const Eigen::VectorXd& x, + const std::vector& active_contact_constraints, + const std::vector& active_external_forces); + + /*! + * @brief gets the drake QuadraticCost evaluator associated with a given cost + */ + [[nodiscard]] const drake::solvers::QuadraticCost& get_cost_evaluator( + const std::string& name) const { + return *all_costs_.at(name); + } + + /*! + * @brief checks if this QP has a cost with the given name + */ + bool has_cost_named(const std::string& name) { + return all_costs_.count(name) > 0; + } + + /*! + * @brief utility functions to enable/disable gravity compensation + */ + void DisableGravityCompensation() { with_gravity_compensation_ = false; } + void EnableGravityCompensation() { with_gravity_compensation_ = true; } + bool HasGravityCompensation() { return with_gravity_compensation_; } + + /*! + * @brief utility functions to enable/disable input constraints + */ + void DisableInputConstraints() { with_input_constraints_ = false; } + void EnableInputConstraints() { with_input_constraints_ = true; } + bool HasInputConstraints() { return with_input_constraints_; } + + /*! + * @brief utility functions to enable/disable acceleration constraints + */ + void DisableAccelerationConstraints() { + with_acceleration_constraints_ = false; + } + void EnableAccelerationConstraints() { + with_acceleration_constraints_ = true; + } + bool HasAccelerationConstraints() { return with_acceleration_constraints_; } + + private: + // Multibody Dynamics + const drake::multibody::MultibodyPlant& plant_; + drake::systems::Context* context_; + + // Holonomic constraints are bilateral constraints that are always active + std::unique_ptr> + holonomic_constraints_ = nullptr; + + // Contact constraints are unilateral constraints with an associated + // contact force which obeys the friction cone + ContactMap contact_constraint_evaluators_{}; + std::unordered_map lambda_c_start_; + std::unordered_map Jc_active_start_; + std::unordered_map mu_map_; + + // External forces are reaction forces we want to "track," but which do not + // constrain the robot's motion + std::unordered_map< + std::string, std::unique_ptr>> + external_force_evaluators_{}; + + std::unordered_map> lambda_e_start_and_size_; + + // Size of position, velocity, and input of the plant + int nq_; + int nv_; + int nu_; + + // Size of constraints and external forces + int nh_ = 0; + int ne_ = 0; + int nc_ = 0; + int nc_active_ = 0; + + // Mathematical Program + drake::solvers::MathematicalProgram prog_; + + // Decision Variables + drake::solvers::VectorXDecisionVariable u_{}; + drake::solvers::VectorXDecisionVariable dv_{}; + drake::solvers::VectorXDecisionVariable lambda_h_{}; + drake::solvers::VectorXDecisionVariable lambda_c_{}; + drake::solvers::VectorXDecisionVariable lambda_e_{}; + drake::solvers::VectorXDecisionVariable epsilon_{}; + + // Costs + CostMap all_costs_; + + // Friction Cone Constraints + FrictionConeMap lambda_c_friction_cone_; + FrictionConeMap lambda_e_friction_cone_; + + // Dynamics + std::shared_ptr dynamics_c_; + std::shared_ptr holonomic_c_; + std::shared_ptr contact_c_; + + // input limits + std::shared_ptr input_limit_c_; + + // acceleration limits + std::shared_ptr acceleration_limit_c_; + + // Bookkeeping + bool built_ = false; + + // Flag to indicate if gravity compensation is enabled. Default is true. + bool with_gravity_compensation_ = true; + + // Flag to indicate if input constraints are enabled. Default is true. + bool with_input_constraints_ = true; + + // Flag to indicate if acceleration constraints are enabled. Default is false. + bool with_acceleration_constraints_ = false; +}; + +} // namespace controllers +} // namespace systems +} // namespace dairlib \ No newline at end of file diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index ce1d027590..43eb34d878 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -48,33 +48,24 @@ using multibody::SetVelocitiesIfNew; using multibody::WorldPointEvaluator; OperationalSpaceControl::OperationalSpaceControl( - const MultibodyPlant& plant_w_spr, - const MultibodyPlant& plant_wo_spr, - drake::systems::Context* context_w_spr, - drake::systems::Context* context_wo_spr, + const MultibodyPlant& plant, + drake::systems::Context* context, bool used_with_finite_state_machine) - : plant_w_spr_(plant_w_spr), - plant_wo_spr_(plant_wo_spr), - context_w_spr_(context_w_spr), - context_wo_spr_(context_wo_spr), - world_w_spr_(plant_w_spr_.world_frame()), - world_wo_spr_(plant_wo_spr_.world_frame()), - used_with_finite_state_machine_(used_with_finite_state_machine) { + : plant_(plant), + context_(context), + used_with_finite_state_machine_(used_with_finite_state_machine), + id_qp_(plant_, context_) { this->set_name("OSC"); - n_q_ = plant_wo_spr.num_positions(); - n_v_ = plant_wo_spr.num_velocities(); - n_u_ = plant_wo_spr.num_actuators(); - - int n_q_w_spr = plant_w_spr.num_positions(); - int n_v_w_spr = plant_w_spr.num_velocities(); - int n_u_w_spr = plant_w_spr.num_actuators(); + n_q_ = plant.num_positions(); + n_v_ = plant.num_velocities(); + n_u_ = plant.num_actuated_dofs(); // Input/Output Setup - state_port_ = - this->DeclareVectorInputPort( - "x, u, t", OutputVector(n_q_w_spr, n_v_w_spr, n_u_w_spr)) - .get_index(); + state_port_ = this->DeclareVectorInputPort( + "x, u, t", OutputVector(n_q_, n_v_, n_u_)) + .get_index(); + if (used_with_finite_state_machine) { fsm_port_ = this->DeclareVectorInputPort("fsm", BasicVector(1)).get_index(); @@ -86,16 +77,16 @@ OperationalSpaceControl::OperationalSpaceControl( .get_index(); // Discrete update to record the last state event time - DeclareForcedDiscreteUpdateEvent( + DeclarePerStepDiscreteUpdateEvent( &OperationalSpaceControl::DiscreteVariableUpdate); prev_fsm_state_idx_ = this->DeclareDiscreteState(-0.1 * VectorXd::Ones(1)); prev_event_time_idx_ = this->DeclareDiscreteState(VectorXd::Zero(1)); } - osc_output_port_ = this->DeclareVectorOutputPort( - "u, t", TimestampedVector(n_u_w_spr), - &OperationalSpaceControl::CalcOptimalInput) - .get_index(); + osc_output_port_ = + this->DeclareVectorOutputPort("u, t", TimestampedVector(n_u_), + &OperationalSpaceControl::CalcOptimalInput) + .get_index(); osc_debug_port_ = this->DeclareAbstractOutputPort( "lcmt_osc_debug", &OperationalSpaceControl::AssignOscLcmOutput) @@ -106,39 +97,12 @@ OperationalSpaceControl::OperationalSpaceControl( &OperationalSpaceControl::CheckTracking) .get_index(); - const std::map& vel_map_wo_spr = - multibody::MakeNameToVelocitiesMap(plant_wo_spr); - - // Initialize the mapping from spring to no spring - map_position_from_spring_to_no_spring_ = - CreateWithSpringsToWithoutSpringsMapPos(plant_w_spr, plant_wo_spr); - map_velocity_from_spring_to_no_spring_ = - CreateWithSpringsToWithoutSpringsMapVel(plant_w_spr, plant_wo_spr); - - // Get input limits - VectorXd u_min(n_u_); - VectorXd u_max(n_u_); - for (JointActuatorIndex i(0); i < n_u_; ++i) { - u_min[i] = -plant_wo_spr_.get_joint_actuator(i).effort_limit(); - u_max[i] = plant_wo_spr_.get_joint_actuator(i).effort_limit(); - } - u_min_ = u_min; - u_max_ = u_max; - - VectorXd ddq_min = VectorXd::Zero(n_q_); - VectorXd ddq_max = VectorXd::Zero(n_q_); - for (JointIndex i(0); i < n_q_; ++i) { - if (plant_wo_spr_.get_joint(i).acceleration_lower_limits().size() != 0) { - ddq_min[i] = plant_wo_spr_.get_joint(i).acceleration_lower_limits()[0]; - ddq_max[i] = plant_wo_spr_.get_joint(i).acceleration_upper_limits()[0]; - } - } - ddq_min_ = ddq_min; - ddq_max_ = ddq_max; + const std::map& vel_map = + multibody::MakeNameToVelocitiesMap(plant); n_revolute_joints_ = 0; - for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { - const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); + for (JointIndex i(0); i < plant_.num_joints(); ++i) { + const drake::multibody::Joint& joint = plant_.get_joint(i); if (joint.type_name() == "revolute") { n_revolute_joints_ += 1; } @@ -146,13 +110,13 @@ OperationalSpaceControl::OperationalSpaceControl( VectorXd q_min(n_revolute_joints_); VectorXd q_max(n_revolute_joints_); int floating_base_offset = n_v_ - n_revolute_joints_; - for (JointIndex i(0); i < plant_wo_spr_.num_joints(); ++i) { - const drake::multibody::Joint& joint = plant_wo_spr_.get_joint(i); + for (JointIndex i(0); i < plant_.num_joints(); ++i) { + const drake::multibody::Joint& joint = plant_.get_joint(i); if (joint.type_name() == "revolute") { - q_min(vel_map_wo_spr.at(joint.name() + "dot") - floating_base_offset) = - plant_wo_spr.get_joint(i).position_lower_limits()[0]; - q_max(vel_map_wo_spr.at(joint.name() + "dot") - floating_base_offset) = - plant_wo_spr.get_joint(i).position_upper_limits()[0]; + q_min(vel_map.at(joint.name() + "dot") - floating_base_offset) = + plant_.get_joint(i).position_lower_limits()[0]; + q_max(vel_map.at(joint.name() + "dot") - floating_base_offset) = + plant_.get_joint(i).position_upper_limits()[0]; } if (joint.type_name() == "prismatic" && (joint.position_lower_limits()[0] != @@ -166,9 +130,6 @@ OperationalSpaceControl::OperationalSpaceControl( } q_min_ = q_min; q_max_ = q_max; - - // Check if the model is floating based - is_quaternion_ = multibody::HasQuaternion(plant_w_spr); } // Optional features @@ -188,45 +149,33 @@ void OperationalSpaceControl::SetInputCostForJointAndFsmStateWeight( if (W_input_.size() == 0) { W_input_ = Eigen::MatrixXd::Zero(n_u_, n_u_); } - int idx = MakeNameToActuatorsMap(plant_wo_spr_).at(joint_u_name); + int idx = MakeNameToActuatorsMap(plant_).at(joint_u_name); fsm_to_w_input_map_[fsm] = std::pair{idx, w}; } // Constraint methods void OperationalSpaceControl::AddContactPoint( - const WorldPointEvaluator* evaluator) { - single_contact_mode_ = true; - AddStateAndContactPoint(-1, evaluator); -} - -void OperationalSpaceControl::AddStateAndContactPoint( - int state, const WorldPointEvaluator* evaluator) { - DRAKE_DEMAND(&evaluator->plant() == &plant_wo_spr_); - - // Find the new contact in all_contacts_ - auto it_c = std::find(all_contacts_.begin(), all_contacts_.end(), evaluator); - int contact_idx = std::distance(all_contacts_.begin(), it_c); - // Add to contact list if the new contact doesn't exist in the list - if (it_c == all_contacts_.cend()) { - all_contacts_.push_back(evaluator); + const std::string& name, + std::unique_ptr> evaluator, + std::vector fsm_states) { + if (fsm_states.empty()) { + fsm_states.push_back(-1); + } + for (const auto& i : fsm_states) { + if (contact_names_map_.count(i) > 0) { + contact_names_map_.at(i).push_back(name); + } else { + contact_names_map_.insert({i, {name}}); + } } - // Find the finite state machine state in contact_indices_map_ - auto map_iterator = contact_indices_map_.find(state); - if (map_iterator == contact_indices_map_.end()) { - // state doesn't exist in the map - contact_indices_map_[state] = {contact_idx}; - } else { - // Add contact_idx to the existing set (note that std::set removes - // duplicates automatically) - map_iterator->second.insert(contact_idx); - } + DRAKE_DEMAND(mu_ > 0); + id_qp_.AddContactConstraint(name, std::move(evaluator), mu_); } void OperationalSpaceControl::AddKinematicConstraint( - const multibody::KinematicEvaluatorSet* evaluators) { - DRAKE_DEMAND(&evaluators->plant() == &plant_wo_spr_); - kinematic_evaluators_ = evaluators; + std::unique_ptr> evaluator) { + id_qp_.AddHolonomicConstraint(std::move(evaluator)); } // Tracking data methods @@ -234,8 +183,6 @@ void OperationalSpaceControl::AddTrackingData( std::unique_ptr tracking_data, double t_lb, double t_ub) { tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.emplace_back(VectorXd::Zero(0)); - t_s_vec_.push_back(t_lb); - t_e_vec_.push_back(t_ub); // Construct input ports and add element to traj_name_to_port_index_map_ if // the port for the traj is not created yet @@ -257,6 +204,14 @@ void OperationalSpaceControl::AddForceTrackingData( std::unique_ptr tracking_data) { force_tracking_data_vec_->push_back(std::move(tracking_data)); + // Declare point where external force is applied in the world frame to the OSC + // backend + auto evaluator = std::make_unique>( + plant_, force_tracking_data_vec_->back()->GetPointOnBody(), + force_tracking_data_vec_->back()->GetBodyFrame()); + id_qp_.AddExternalForce(force_tracking_data_vec_->back()->GetName(), + std::move(evaluator)); + // Construct input ports and add element to traj_name_to_port_index_map_ if // the port for the traj is not created yet string traj_name = force_tracking_data_vec_->back()->GetName(); @@ -277,8 +232,6 @@ void OperationalSpaceControl::AddConstTrackingData( double t_lb, double t_ub) { tracking_data_vec_->push_back(std::move(tracking_data)); fixed_position_vec_.push_back(v); - t_s_vec_.push_back(t_lb); - t_e_vec_.push_back(t_ub); } // Osc checkers and constructor @@ -296,12 +249,9 @@ void OperationalSpaceControl::CheckCostSettings() { } } void OperationalSpaceControl::CheckConstraintSettings() { - if (!all_contacts_.empty()) { + if (!contact_names_map_.empty()) { DRAKE_DEMAND(mu_ != -1); } - if (single_contact_mode_) { - DRAKE_DEMAND(contact_indices_map_.size() == 1); - } } void OperationalSpaceControl::Build() { @@ -310,236 +260,108 @@ void OperationalSpaceControl::Build() { CheckConstraintSettings(); for (auto& tracking_data : *tracking_data_vec_) { tracking_data->CheckOscTrackingData(); - DRAKE_DEMAND(&tracking_data->plant_w_spr() == &plant_w_spr_); - DRAKE_DEMAND(&tracking_data->plant_wo_spr() == &plant_wo_spr_); + DRAKE_DEMAND(&tracking_data->plant_w_spr() == &plant_); } // Construct QP - prog_ = std::make_unique(); - - // Size of decision variable - n_h_ = (kinematic_evaluators_ == nullptr) - ? 0 - : kinematic_evaluators_->count_full(); - n_c_ = kSpaceDim * all_contacts_.size(); - - n_lambda_ext_ = 0; - for (auto& force_tracking_data : *force_tracking_data_vec_) { - n_lambda_ext_ += force_tracking_data->GetLambdaDim(); - } - - n_c_active_ = 0; - for (auto evaluator : all_contacts_) { - n_c_active_ += evaluator->num_active(); - } - - // Record the contact dimension per state - for (auto contact_map : contact_indices_map_) { - int active_contact_dim = 0; - for (unsigned int i = 0; i < all_contacts_.size(); i++) { - if (contact_map.second.find(i) != contact_map.second.end()) { - active_contact_dim += - all_contacts_[i]->EvalFullJacobian(*context_wo_spr_).rows(); - } - } - active_contact_dim_[contact_map.first] = active_contact_dim; - } + id_qp_.Build(); // Initialize solution dv_sol_ = std::make_unique(n_v_); u_sol_ = std::make_unique(n_u_); - lambda_c_sol_ = std::make_unique(n_c_); - lambda_h_sol_ = std::make_unique(n_h_); - lambda_ext_sol_ = std::make_unique(n_lambda_ext_); - epsilon_sol_ = std::make_unique(n_c_active_); + lambda_c_sol_ = std::make_unique(id_qp_.nc()); + lambda_h_sol_ = std::make_unique(id_qp_.nh()); + lambda_e_sol_ = std::make_unique(id_qp_.ne()); + epsilon_sol_ = std::make_unique(id_qp_.nc_active()); u_prev_ = std::make_unique(n_u_); dv_sol_->setZero(); u_sol_->setZero(); lambda_c_sol_->setZero(); lambda_h_sol_->setZero(); - lambda_ext_sol_->setZero(); + lambda_e_sol_->setZero(); u_prev_->setZero(); - // Add decision variables - dv_ = prog_->NewContinuousVariables(n_v_, "dv"); - u_ = prog_->NewContinuousVariables(n_u_, "u"); - lambda_c_ = prog_->NewContinuousVariables(n_c_, "lambda_contact"); - lambda_h_ = prog_->NewContinuousVariables(n_h_, "lambda_holonomic"); - lambda_ext_ = prog_->NewContinuousVariables(n_lambda_ext_, "lambda_ee"); - epsilon_ = prog_->NewContinuousVariables(n_c_active_, "epsilon"); - - // Add constraints - // 1. Dynamics constraint - dynamics_constraint_ = - prog_ - ->AddLinearEqualityConstraint( - MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_lambda_ext_), - VectorXd::Zero(n_v_), - {dv_, lambda_c_, lambda_h_, u_, lambda_ext_}) - .evaluator() - .get(); - // 2. Holonomic constraint - holonomic_constraint_ = - prog_ - ->AddLinearEqualityConstraint(MatrixXd::Zero(n_h_, n_v_), - VectorXd::Zero(n_h_), dv_) - .evaluator() - .get(); - // 3. Contact constraint - if (!all_contacts_.empty()) { - if (w_soft_constraint_ <= 0) { - contact_constraints_ = - prog_ - ->AddLinearEqualityConstraint(MatrixXd::Zero(n_c_active_, n_v_), - VectorXd::Zero(n_c_active_), dv_) - .evaluator() - .get(); - } else { - // Relaxed version: - contact_constraints_ = - prog_ - ->AddLinearEqualityConstraint( - MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_), - VectorXd::Zero(n_c_active_), {dv_, epsilon_}) - .evaluator() - .get(); - } - } - if (!all_contacts_.empty()) { - MatrixXd A = MatrixXd(5, kSpaceDim); - A << -1, 0, mu_, 0, -1, mu_, 1, 0, mu_, 0, 1, mu_, 0, 0, 1; - - for (unsigned int j = 0; j < all_contacts_.size(); j++) { - friction_constraints_.push_back( - prog_ - ->AddLinearConstraint( - A, VectorXd::Zero(5), - Eigen::VectorXd::Constant( - 5, std::numeric_limits::infinity()), - lambda_c_.segment(kSpaceDim * j, 3)) - .evaluator() - .get()); - } - } - - // 5. Input constraint - if (with_input_constraints_) { - prog_->AddLinearConstraint(MatrixXd::Identity(n_u_, n_u_), u_min_, u_max_, - u_); - } - - if (with_acceleration_constraints_) { - prog_->AddLinearConstraint(MatrixXd::Identity(n_q_, n_q_), ddq_min_, - ddq_max_, dv_); - } - // No joint position constraint in this implementation - // Add costs // 1. input cost if (W_input_.size() > 0) { - input_cost_ = prog_->AddQuadraticCost(W_input_, VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); + id_qp_.AddQuadraticCost("input_cost", W_input_, VectorXd::Zero(n_u_), + id_qp_.u()); } // 2. acceleration cost if (W_joint_accel_.size() > 0) { DRAKE_DEMAND(W_joint_accel_.rows() == n_v_); - accel_cost_ = - prog_->AddQuadraticCost(W_joint_accel_, VectorXd::Zero(n_v_), dv_) - .evaluator() - .get(); + id_qp_.AddQuadraticCost("acceleration_cost", W_joint_accel_, + VectorXd::Zero(n_v_), id_qp_.dv()); } if (W_input_smoothing_.size() > 0) { - input_smoothing_cost_ = - prog_->AddQuadraticCost(W_input_smoothing_, VectorXd::Zero(n_u_), u_) - .evaluator() - .get(); + id_qp_.AddQuadraticCost("input_smoothing_cost", W_input_smoothing_, + VectorXd::Zero(n_u_), id_qp_.u()); } // 3. contact force cost if (W_lambda_c_reg_.size() > 0) { - DRAKE_DEMAND(W_lambda_c_reg_.rows() == n_c_); - lambda_c_cost_ = - prog_ - ->AddQuadraticCost(W_lambda_c_reg_, VectorXd::Zero(n_c_), lambda_c_) - .evaluator() - .get(); + int nc = id_qp_.lambda_c().rows(); + DRAKE_DEMAND(W_lambda_c_reg_.rows() == nc); + id_qp_.AddQuadraticCost("lambda_c_cost", W_lambda_c_reg_, + VectorXd::Zero(nc), id_qp_.lambda_c()); } // 3. constraint force cost if (W_lambda_h_reg_.size() > 0) { - DRAKE_DEMAND(W_lambda_h_reg_.rows() == n_h_); - lambda_h_cost_ = - prog_ - ->AddQuadraticCost(W_lambda_h_reg_, VectorXd::Zero(n_h_), lambda_h_) - .evaluator() - .get(); - } - // 3. external force cost - for (auto& force_tracking_data : *force_tracking_data_vec_) { - lambda_ext_cost_ = - prog_ - ->AddQuadraticCost(MatrixXd::Zero(n_lambda_ext_, n_lambda_ext_), - VectorXd::Zero(n_lambda_ext_), lambda_ext_) - .evaluator() - .get(); + int nh = id_qp_.lambda_h().rows(); + DRAKE_DEMAND(W_lambda_h_reg_.rows() == nh); + id_qp_.AddQuadraticCost("lambda_h_cost", W_lambda_h_reg_, + VectorXd::Zero(nh), id_qp_.lambda_h()); } // 4. Soft constraint cost if (w_soft_constraint_ > 0) { - soft_constraint_cost_ = - prog_ - ->AddQuadraticCost(w_soft_constraint_ * - MatrixXd::Identity(n_c_active_, n_c_active_), - VectorXd::Zero(n_c_active_), epsilon_) - .evaluator() - .get(); + int nca = id_qp_.nc_active(); + id_qp_.AddQuadraticCost("soft_constraint_cost", + w_soft_constraint_ * MatrixXd::Identity(nca, nca), + VectorXd::Zero(nca), id_qp_.epsilon()); } // 4. Tracking cost - for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { - tracking_costs_.push_back(prog_ - ->AddQuadraticCost(MatrixXd::Zero(n_v_, n_v_), - VectorXd::Zero(n_v_), dv_) - .evaluator() - .get()); + for (const auto& data : *tracking_data_vec_) { + id_qp_.AddQuadraticCost(data->GetName(), MatrixXd::Zero(n_v_, n_v_), + VectorXd::Zero(n_v_), id_qp_.dv()); } - // 5. Joint Limit cost + // 5. Track external force cost + int ne = id_qp_.lambda_e().rows(); + for (const auto& data : *force_tracking_data_vec_) { + id_qp_.AddQuadraticCost(data->GetName(), MatrixXd::Zero(ne, ne), + VectorXd::Zero(ne), id_qp_.lambda_e()); + } + + // 6. Joint Limit cost // TODO(yangwill) discuss best way to implement joint limit cost if (w_joint_limit_ > 0) { K_joint_pos_ = w_joint_limit_ * W_joint_accel_.bottomRightCorner( n_revolute_joints_, n_revolute_joints_); - joint_limit_cost_ = prog_ - ->AddLinearCost(VectorXd::Zero(n_revolute_joints_), - 0, dv_.tail(n_revolute_joints_)) - .evaluator() - .get(); + id_qp_.AddQuadraticCost( + "joint_limit_cost", + MatrixXd::Zero(n_revolute_joints_, n_revolute_joints_), + VectorXd::Zero(n_revolute_joints_), + id_qp_.dv().tail(n_revolute_joints_)); } - // (Testing) 6. contact force blending + // (Testing) 7. contact force blending if (ds_duration_ > 0) { - epsilon_blend_ = - prog_->NewContinuousVariables(n_c_ / kSpaceDim, "epsilon_blend"); + int nc = id_qp_.nc(); + const auto& lambda = id_qp_.lambda_c(); blend_constraint_ = - prog_ - ->AddLinearEqualityConstraint( - MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim), VectorXd::Zero(1), - {lambda_c_.segment(kSpaceDim * 0 + 2, 1), - lambda_c_.segment(kSpaceDim * 1 + 2, 1), - lambda_c_.segment(kSpaceDim * 2 + 2, 1), - lambda_c_.segment(kSpaceDim * 3 + 2, 1), epsilon_blend_}) + id_qp_.get_mutable_prog() + .AddLinearEqualityConstraint(MatrixXd::Zero(1, nc / kSpaceDim), + VectorXd::Zero(1), + {lambda.segment(kSpaceDim * 0 + 2, 1), + lambda.segment(kSpaceDim * 1 + 2, 1), + lambda.segment(kSpaceDim * 2 + 2, 1), + lambda.segment(kSpaceDim * 3 + 2, 1)}) .evaluator() .get(); - /// Soft constraint version - // DRAKE_DEMAND(w_blend_constraint_ > 0); - // prog_->AddQuadraticCost( - // w_blend_constraint_ * - // MatrixXd::Identity(n_c_ / kSpaceDim, n_c_ / kSpaceDim), - // VectorXd::Zero(n_c_ / kSpaceDim), epsilon_blend_); - /// hard constraint version - prog_->AddBoundingBoxConstraint(0, 0, epsilon_blend_); } solver_ = std::make_unique(); - prog_->SetSolverOptions(solver_options_); + id_qp_.get_mutable_prog().SetSolverOptions(solver_options_); } drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( @@ -560,6 +382,10 @@ drake::systems::EventStatus OperationalSpaceControl::DiscreteVariableUpdate( discrete_state->get_mutable_vector(prev_event_time_idx_).get_mutable_value() << timestamp; + + if (solver_->IsInitialized()) { + solver_->DisableWarmStart(); + } } return drake::systems::EventStatus::Succeeded(); } @@ -568,58 +394,26 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const drake::systems::Context& context, double t, int fsm_state, double t_since_last_state_switch, double alpha, int next_fsm_state) const { - // Get active contact indices - std::set active_contact_set = {}; - if (single_contact_mode_) { - active_contact_set = contact_indices_map_.at(-1); - } else { - auto map_iterator = contact_indices_map_.find(fsm_state); - if (map_iterator != contact_indices_map_.end()) { - active_contact_set = map_iterator->second; - } -// else { -// static const drake::logging::Warn log_once(const_cast( -// (std::to_string(fsm_state) + -// " is not a valid finite state machine state in OSC. This can happen " -// "if there are modes with no active contacts.") -// .c_str())); -// } - } - // Update context - SetPositionsIfNew( - plant_w_spr_, x_w_spr.head(plant_w_spr_.num_positions()), context_w_spr_); - SetVelocitiesIfNew(plant_w_spr_, - x_w_spr.tail(plant_w_spr_.num_velocities()), - context_w_spr_); - SetPositionsIfNew(plant_wo_spr_, - x_wo_spr.head(plant_wo_spr_.num_positions()), - context_wo_spr_); - SetVelocitiesIfNew(plant_wo_spr_, - x_wo_spr.tail(plant_wo_spr_.num_velocities()), - context_wo_spr_); - - // Get M, f_cg, B matrices of the manipulator equation - MatrixXd B = plant_wo_spr_.MakeActuationMatrix(); - MatrixXd M(n_v_, n_v_); - plant_wo_spr_.CalcMassMatrix(*context_wo_spr_, &M); - VectorXd bias(n_v_); - plant_wo_spr_.CalcBiasTerm(*context_wo_spr_, &bias); - drake::multibody::MultibodyForces f_app(plant_wo_spr_); - plant_wo_spr_.CalcForceElementsContribution(*context_wo_spr_, &f_app); - VectorXd grav = plant_wo_spr_.CalcGravityGeneralizedForces(*context_wo_spr_); - if (with_gravity_compensation_) { - bias = bias - grav; - } - // TODO (yangwill): Characterize damping in cassie model - // std::cout << f_app.generalized_forces().transpose() << std::endl; - // bias = bias - f_app.generalized_forces(); + SetPositionsIfNew(plant_, x_w_spr.head(plant_.num_positions()), + context_); + SetVelocitiesIfNew(plant_, x_w_spr.tail(plant_.num_velocities()), + context_); + + const auto active_contact_names = contact_names_map_.count(fsm_state) > 0 + ? contact_names_map_.at(fsm_state) + : std::vector(); + id_qp_.UpdateDynamics(x_w_spr, active_contact_names, {}); // Invariant Impacts // Only update when near an impact bool near_impact = alpha != 0; VectorXd v_proj = VectorXd::Zero(n_v_); + if (near_impact) { + MatrixXd M(n_v_, n_v_); + plant_.CalcMassMatrix(*context_, &M); + UpdateImpactInvariantProjection(x_w_spr, x_wo_spr, context, t, t_since_last_state_switch, fsm_state, next_fsm_state, M); @@ -627,124 +421,18 @@ VectorXd OperationalSpaceControl::SolveQp( v_proj = alpha * M_Jt_ * ii_lambda_sol_ + 1e-13 * VectorXd::Ones(n_v_); } - // Get J and JdotV for holonomic constraint - MatrixXd J_h(n_h_, n_v_); - VectorXd JdotV_h(n_h_); - if (kinematic_evaluators_ != nullptr) { - J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); - JdotV_h = - kinematic_evaluators_->EvalFullJacobianDotTimesV(*context_wo_spr_); - } - - // Get J for external forces in equations of motion - MatrixXd J_c = MatrixXd::Zero(n_c_, n_v_); - for (unsigned int i = 0; i < all_contacts_.size(); i++) { - if (active_contact_set.find(i) != active_contact_set.end()) { - J_c.block(kSpaceDim * i, 0, kSpaceDim, n_v_) = - all_contacts_[i]->EvalFullJacobian(*context_wo_spr_); - } - } - - // Get J and JdotV for contact constraint - MatrixXd J_c_active = MatrixXd::Zero(n_c_active_, n_v_); - VectorXd JdotV_c_active = VectorXd::Zero(n_c_active_); - int row_idx = 0; - for (unsigned int i = 0; i < all_contacts_.size(); i++) { - auto contact_i = all_contacts_[i]; - if (active_contact_set.find(i) != active_contact_set.end()) { - // We don't call EvalActiveJacobian() because it'll repeat the computation - // of the Jacobian. (J_c_active is just a stack of slices of J_c) - for (int j = 0; j < contact_i->num_active(); j++) { - J_c_active.row(row_idx + j) = - J_c.row(kSpaceDim * i + contact_i->active_inds().at(j)); - } - JdotV_c_active.segment(row_idx, contact_i->num_active()) = - contact_i->EvalActiveJacobianDotTimesV(*context_wo_spr_); - } - row_idx += contact_i->num_active(); - } - - // Update constraints - // 1. Dynamics constraint - /// M*dv + bias == J_c^T*lambda_c + J_h^T*lambda_h + B*u - /// -> M*dv - J_c^T*lambda_c - J_h^T*lambda_h - B*u == - bias - /// -> [M, -J_c^T, -J_h^T, -B]*[dv, lambda_c, lambda_h, u]^T = - bias - MatrixXd A_dyn = - MatrixXd::Zero(n_v_, n_v_ + n_c_ + n_h_ + n_u_ + n_lambda_ext_); - A_dyn.block(0, 0, n_v_, n_v_) = M; - A_dyn.block(0, n_v_, n_v_, n_c_) = -J_c.transpose(); - A_dyn.block(0, n_v_ + n_c_, n_v_, n_h_) = -J_h.transpose(); - A_dyn.block(0, n_v_ + n_c_ + n_h_, n_v_, n_u_) = -B; - for (auto& force_tracking_data : *force_tracking_data_vec_) { - if (!force_tracking_data->GetWeight().isZero()){ - MatrixXd J_ee = force_tracking_data->GetJ(); - A_dyn.block(0, n_v_ + n_c_ + n_h_ + n_u_, n_v_, n_lambda_ext_) = - J_ee.transpose(); - } - } - dynamics_constraint_->UpdateCoefficients(A_dyn, -bias); - // 2. Holonomic constraint - /// JdotV_h + J_h*dv == 0 - /// -> J_h*dv == -JdotV_h - if (n_h_ > 0) { - holonomic_constraint_->UpdateCoefficients(J_h, -JdotV_h); - } - // 3. Contact constraint - if (!all_contacts_.empty()) { - if (w_soft_constraint_ <= 0) { - /// JdotV_c_active + J_c_active*dv == 0 - /// -> J_c_active*dv == -JdotV_c_active - contact_constraints_->UpdateCoefficients(J_c_active, -JdotV_c_active); - } else { - // Relaxed version: - /// JdotV_c_active + J_c_active*dv == -epsilon - /// -> J_c_active*dv + I*epsilon == -JdotV_c_active - /// -> [J_c_active, I]* [dv, epsilon]^T == -JdotV_c_active - MatrixXd A_c = MatrixXd::Zero(n_c_active_, n_v_ + n_c_active_); - A_c.block(0, 0, n_c_active_, n_v_) = J_c_active; - A_c.block(0, n_v_, n_c_active_, n_c_active_) = - MatrixXd::Identity(n_c_active_, n_c_active_); - contact_constraints_->UpdateCoefficients(A_c, -JdotV_c_active); - } - } - // 4. Friction constraint (approximated friction cone) - /// For i = active contact indices - /// mu_*lambda_c(3*i+2) >= lambda_c(3*i+0) - /// -mu_*lambda_c(3*i+2) <= lambda_c(3*i+0) - /// mu_*lambda_c(3*i+2) >= lambda_c(3*i+1) - /// -mu_*lambda_c(3*i+2) <= lambda_c(3*i+1) - /// lambda_c(3*i+2) >= 0 - /// -> - /// mu_*lambda_c(3*i+2) - lambda_c(3*i+0) >= 0 - /// mu_*lambda_c(3*i+2) + lambda_c(3*i+0) >= 0 - /// mu_*lambda_c(3*i+2) - lambda_c(3*i+1) >= 0 - /// mu_*lambda_c(3*i+2) + lambda_c(3*i+1) >= 0 - /// lambda_c(3*i+2) >= 0 - if (!all_contacts_.empty()) { - for (unsigned int i = 0; i < all_contacts_.size(); i++) { - if (active_contact_set.find(i) != active_contact_set.end()) { - friction_constraints_.at(i)->UpdateLowerBound(VectorXd::Zero(5)); - } else { - friction_constraints_.at(i)->UpdateLowerBound( - VectorXd::Constant(5, -std::numeric_limits::infinity())); - } - } - } - // Update costs // 4. Tracking cost for (unsigned int i = 0; i < tracking_data_vec_->size(); i++) { auto tracking_data = tracking_data_vec_->at(i).get(); - if (tracking_data->IsActive(fsm_state) && - t_since_last_state_switch >= t_s_vec_.at(i) && - t_since_last_state_switch <= t_e_vec_.at(i)) { + if (tracking_data->IsActive(fsm_state)) { // Check whether or not it is a constant trajectory, and update // TrackingData if (fixed_position_vec_.at(i).size() != 0) { // Create constant trajectory and update tracking_data->Update( - x_w_spr, *context_w_spr_, x_wo_spr, *context_wo_spr_, + x_w_spr, *context_, x_wo_spr, *context_, PiecewisePolynomial(fixed_position_vec_.at(i)), t, t_since_last_state_switch, fsm_state, v_proj); } else { @@ -757,8 +445,7 @@ VectorXd OperationalSpaceControl::SolveQp( const auto& traj = input_traj->get_value>(); // Update - tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, - *context_wo_spr_, traj, t, + tracking_data->Update(x_w_spr, *context_, x_wo_spr, *context_, traj, t, t_since_last_state_switch, fsm_state, v_proj); } @@ -768,16 +455,16 @@ VectorXd OperationalSpaceControl::SolveQp( const VectorXd& JdotV_t = tracking_data->GetJdotTimesV(); const VectorXd constant_term = (JdotV_t - ddy_t); - tracking_costs_.at(i)->UpdateCoefficients( - 2 * J_t.transpose() * W * J_t, - 2 * J_t.transpose() * W * (JdotV_t - ddy_t), - constant_term.transpose() * W * constant_term, true); + id_qp_.UpdateCost(tracking_data->GetName(), 2 * J_t.transpose() * W * J_t, + 2 * J_t.transpose() * W * (JdotV_t - ddy_t), + constant_term.transpose() * W * constant_term); } else { - tracking_costs_.at(i)->UpdateCoefficients(MatrixXd::Zero(n_v_, n_v_), - VectorXd::Zero(n_v_)); + id_qp_.UpdateCost(tracking_data->GetName(), MatrixXd::Zero(n_v_, n_v_), + VectorXd::Zero(n_v_)); } } + // Update tracking cost for external forces for (auto& force_tracking_data : *force_tracking_data_vec_) { int port_index = traj_name_to_port_index_map_.at(force_tracking_data->GetName()); @@ -786,54 +473,53 @@ VectorXd OperationalSpaceControl::SolveQp( DRAKE_DEMAND(input_traj != nullptr); const auto& traj = input_traj->get_value>(); - force_tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, - *context_wo_spr_, traj, t); + force_tracking_data->Update(x_w_spr, *context_, x_wo_spr, *context_, traj, + t); const MatrixXd W = force_tracking_data->GetWeight(); const VectorXd lambda_des = force_tracking_data->GetLambdaDes(); - lambda_ext_cost_->UpdateCoefficients( - 2 * W, -2 * W * lambda_des, lambda_des.transpose() * W * lambda_des); + id_qp_.UpdateCost(force_tracking_data->GetName(), 2 * W, + -2 * W * lambda_des, + lambda_des.transpose() * W * lambda_des); } // Add joint limit constraints if (w_joint_limit_ > 0) { VectorXd w_joint_limit = - K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_max_) - .cwiseMax(0) + - K_joint_pos_ * (x_wo_spr.head(plant_wo_spr_.num_positions()) - .tail(n_revolute_joints_) - - q_min_) - .cwiseMin(0); - joint_limit_cost_->UpdateCoefficients(w_joint_limit, 0); - } - + K_joint_pos_ * + (x_wo_spr.head(plant_.num_positions()).tail(n_revolute_joints_) - + q_max_) + .cwiseMax(0) + + K_joint_pos_ * + (x_wo_spr.head(plant_.num_positions()).tail(n_revolute_joints_) - + q_min_) + .cwiseMin(0); + id_qp_.UpdateCost("joint_limit_cost", + MatrixXd::Zero(n_revolute_joints_, n_revolute_joints_), + w_joint_limit); + } + + // TODO (@Brian-Acosta) test double support blending as a force cost // (Testing) 6. blend contact forces during double support phase if (ds_duration_ > 0) { - MatrixXd A = MatrixXd::Zero(1, 2 * n_c_ / kSpaceDim); + int nc = id_qp_.nc(); + MatrixXd A = MatrixXd::Zero(1, nc / kSpaceDim); if (std::find(ds_states_.begin(), ds_states_.end(), fsm_state) != ds_states_.end()) { + double s = std::clamp(t_since_last_state_switch / ds_duration_, 0.0, 1.0); double alpha_left = 0; double alpha_right = 0; if (prev_distinct_fsm_state_ == right_support_state_) { // We want left foot force to gradually increase - alpha_left = -1; - alpha_right = t_since_last_state_switch / - (ds_duration_ - t_since_last_state_switch); - + alpha_left = std::clamp(1.0 - s, 0.0, 1.0); + alpha_right = -s; } else if (prev_distinct_fsm_state_ == left_support_state_) { - alpha_left = t_since_last_state_switch / - (ds_duration_ - t_since_last_state_switch); - alpha_right = -1; + alpha_left = -s; + alpha_right = std::clamp(1.0 - s, 0.0, 1.0); } A(0, 0) = alpha_left / 2; A(0, 1) = alpha_left / 2; A(0, 2) = alpha_right / 2; A(0, 3) = alpha_right / 2; - A(0, 4) = 1; - A(0, 5) = 1; - A(0, 6) = 1; - A(0, 7) = 1; } blend_constraint_->UpdateCoefficients(A, VectorXd::Zero(1)); } @@ -846,44 +532,46 @@ VectorXd OperationalSpaceControl::SolveQp( double w = fsm_to_w_input_map_.at(fsm_state).second; W(j, j) += w; } - input_cost_->UpdateCoefficients(W, VectorXd::Zero(n_u_)); + id_qp_.UpdateCost("input_cost", W, VectorXd::Zero(n_u_)); } // (Testing) 7. Cost for staying close to the previous input if (W_input_smoothing_.size() > 0 && u_prev_) { - input_smoothing_cost_->UpdateCoefficients( - W_input_smoothing_, -W_input_smoothing_ * *u_prev_, + id_qp_.UpdateCost( + "input_smoothing_cost", W_input_smoothing_, + -W_input_smoothing_ * *u_prev_, 0.5 * u_prev_->transpose() * W_input_smoothing_ * *u_prev_); } if (W_lambda_c_reg_.size() > 0) { - lambda_c_cost_->UpdateCoefficients((1 + alpha) * W_lambda_c_reg_, - VectorXd::Zero(n_c_)); + id_qp_.UpdateCost("lambda_c_cost", (1 + alpha) * W_lambda_c_reg_, + VectorXd::Zero(id_qp_.nc())); } if (W_lambda_h_reg_.size() > 0) { - lambda_h_cost_->UpdateCoefficients((1 + alpha) * W_lambda_h_reg_, - VectorXd::Zero(n_h_)); + id_qp_.UpdateCost("lambda_h_reg", (1 + alpha) * W_lambda_h_reg_, + VectorXd::Zero(id_qp_.nh())); } if (!solver_->IsInitialized()) { - solver_->InitializeSolver(*prog_, solver_options_); + solver_->InitializeSolver(id_qp_.get_prog(), solver_options_); } // Solve the QP MathematicalProgramResult result; - result = solver_->Solve(*prog_); + result = solver_->Solve(id_qp_.get_prog()); solve_time_ = result.get_solver_details().run_time; if (result.is_success()) { // Extract solutions - *dv_sol_ = result.GetSolution(dv_); - *u_sol_ = result.GetSolution(u_); - *lambda_c_sol_ = result.GetSolution(lambda_c_); - *lambda_h_sol_ = result.GetSolution(lambda_h_); - *epsilon_sol_ = result.GetSolution(epsilon_); - *lambda_ext_sol_ = result.GetSolution(lambda_ext_); + *dv_sol_ = result.GetSolution(id_qp_.dv()); + *u_sol_ = result.GetSolution(id_qp_.u()); + *lambda_c_sol_ = result.GetSolution(id_qp_.lambda_c()); + *lambda_h_sol_ = result.GetSolution(id_qp_.lambda_h()); + *lambda_e_sol_ = result.GetSolution(id_qp_.lambda_e()); + *epsilon_sol_ = result.GetSolution(id_qp_.epsilon()); } else { *u_prev_ = 0.99 * *u_sol_ + VectorXd::Random(n_u_); + solver_->DisableWarmStart(); } for (auto& tracking_data : *tracking_data_vec_) { @@ -895,31 +583,35 @@ VectorXd OperationalSpaceControl::SolveQp( return *u_sol_; } +// TODO (@Yangwill) test that this is equivalent to the previous impact +// invariant implementation void OperationalSpaceControl::UpdateImpactInvariantProjection( const VectorXd& x_w_spr, const VectorXd& x_wo_spr, const Context& context, double t, double t_since_last_state_switch, int fsm_state, int next_fsm_state, const MatrixXd& M) const { - auto map_iterator = contact_indices_map_.find(next_fsm_state); - if (map_iterator == contact_indices_map_.end()) { - ii_lambda_sol_ = VectorXd::Zero(n_c_ + n_h_); - M_Jt_ = MatrixXd::Zero(n_v_, n_c_ + n_h_); + auto map_iterator = contact_names_map_.find(next_fsm_state); + + if (map_iterator == contact_names_map_.end()) { + ii_lambda_sol_ = VectorXd::Zero(id_qp_.nc() + id_qp_.nh()); + M_Jt_ = MatrixXd::Zero(n_v_, id_qp_.nc() + id_qp_.nh()); return; } - std::set next_contact_set = map_iterator->second; - int active_constraint_dim = active_contact_dim_.at(next_fsm_state) + n_h_; + + std::vector next_contact_set = map_iterator->second; + + int active_constraint_dim = kSpaceDim * next_contact_set.size() + id_qp_.nh(); + MatrixXd J_next = MatrixXd::Zero(active_constraint_dim, n_v_); int row_start = 0; - for (unsigned int i = 0; i < all_contacts_.size(); i++) { - if (next_contact_set.find(i) != next_contact_set.end()) { - J_next.block(row_start, 0, kSpaceDim, n_v_) = - all_contacts_[i]->EvalFullJacobian(*context_wo_spr_); - row_start += kSpaceDim; - } + for (const auto& cname : next_contact_set) { + J_next.block(row_start, 0, kSpaceDim, n_v_) = + id_qp_.get_contact_evaluator(cname).EvalFullJacobian(*context_); + row_start += kSpaceDim; } // Holonomic constraints - if (n_h_ > 0) { - J_next.block(row_start, 0, n_h_, n_v_) = - kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); + if (id_qp_.nh() > 0) { + J_next.block(row_start, 0, id_qp_.nh(), n_v_) = + id_qp_.get_holonomic_evaluators().EvalFullJacobian(*context_); } M_Jt_ = M.llt().solve(J_next.transpose()); @@ -934,7 +626,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( if (fixed_position_vec_.at(i).size() != 0) { // Create constant trajectory and update tracking_data->Update( - x_w_spr, *context_w_spr_, x_wo_spr, *context_wo_spr_, + x_w_spr, *context_, x_wo_spr, *context_, PiecewisePolynomial(fixed_position_vec_.at(i)), t, t_since_last_state_switch, fsm_state, v_proj); } else { @@ -945,8 +637,7 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( EvalAbstractInput(context, port_index); const auto& traj = input_traj->get_value>(); - tracking_data->Update(x_w_spr, *context_w_spr_, x_wo_spr, - *context_wo_spr_, traj, t, + tracking_data->Update(x_w_spr, *context_, x_wo_spr, *context_, traj, t, t_since_last_state_switch, fsm_state, v_proj); } } @@ -966,21 +657,22 @@ void OperationalSpaceControl::UpdateImpactInvariantProjection( } } - // int n_holonomic_constraints = n_h_; - MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + n_h_, - active_constraint_dim + n_h_); + // int n_holonomic_constraints = id_qp_.nh(); + MatrixXd A_constrained = MatrixXd::Zero(active_constraint_dim + id_qp_.nh(), + active_constraint_dim + id_qp_.nh()); A_constrained.block(0, 0, active_constraint_dim, active_constraint_dim) = A.transpose() * A; - VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + n_h_); + VectorXd b_constrained = VectorXd::Zero(active_constraint_dim + id_qp_.nh()); VectorXd Ab = A.transpose() * ydot_err_vec; - if (n_h_ > 0) { - MatrixXd J_h = kinematic_evaluators_->EvalFullJacobian(*context_wo_spr_); + if (id_qp_.nh() > 0) { + MatrixXd J_h = + id_qp_.get_holonomic_evaluators().EvalFullJacobian(*context_); MatrixXd C = J_h * M_Jt_; VectorXd d = J_h * x_w_spr.tail(n_v_); - A_constrained.block(active_constraint_dim, 0, n_h_, active_constraint_dim) = - C; - A_constrained.block(0, active_constraint_dim, active_constraint_dim, n_h_) = - C.transpose(); + A_constrained.block(active_constraint_dim, 0, id_qp_.nh(), + active_constraint_dim) = C; + A_constrained.block(0, active_constraint_dim, active_constraint_dim, + id_qp_.nh()) = C.transpose(); b_constrained << Ab, d; } else { b_constrained << Ab; @@ -1003,78 +695,30 @@ void OperationalSpaceControl::AssignOscLcmOutput( fsm_state = fsm_output->get_value()(0); } - double time_since_last_state_switch = - used_with_finite_state_machine_ - ? state->get_timestamp() - - context.get_discrete_state(prev_event_time_idx_).get_value()(0) - : state->get_timestamp(); - output->utime = state->get_timestamp() * 1e6; output->fsm_state = fsm_state; - VectorXd y_accel_cost = VectorXd::Zero(1); - VectorXd y_input_cost = VectorXd::Zero(1); - VectorXd y_input_smoothing_cost = VectorXd::Zero(1); - VectorXd y_lambda_c_cost = VectorXd::Zero(1); - VectorXd y_lambda_h_cost = VectorXd::Zero(1); - VectorXd y_lambda_ee_cost = VectorXd::Zero(1); - VectorXd y_soft_constraint_cost = VectorXd::Zero(1); - VectorXd y_joint_limit_cost = VectorXd::Zero(1); - if (accel_cost_) { - accel_cost_->Eval(*dv_sol_, &y_accel_cost); - } - if (input_cost_) { - input_cost_->Eval(*u_sol_, &y_input_cost); - } - if (input_smoothing_cost_) { - input_smoothing_cost_->Eval(*u_sol_, &y_input_smoothing_cost); - } - if (lambda_c_cost_) { - lambda_c_cost_->Eval(*lambda_c_sol_, &y_lambda_c_cost); - } - if (lambda_ext_cost_) { - lambda_ext_cost_->Eval(*lambda_ext_sol_, &y_lambda_ee_cost); - } - if (lambda_h_cost_) { - lambda_h_cost_->Eval(*lambda_h_sol_, &y_lambda_h_cost); - } - if (soft_constraint_cost_) { - soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); - } - // if (joint_limit_cost_) { - // joint_limit_cost_->Eval(*dv_sol_, &y_joint_limit_cost); - // } - double acceleration_cost = (accel_cost_ != nullptr) ? y_accel_cost[0] : 0; - double input_cost = (input_cost_ != nullptr) ? y_input_cost[0] : 0; - double input_smoothing_cost = - (input_smoothing_cost_ != nullptr) ? y_input_smoothing_cost[0] : 0; - double soft_constraint_cost = - (soft_constraint_cost_ != nullptr) ? y_soft_constraint_cost[0] : 0; - double lambda_c_cost = (lambda_c_cost_ != nullptr) ? y_lambda_c_cost[0] : 0; - double lambda_h_cost = (lambda_h_cost_ != nullptr) ? y_lambda_h_cost[0] : 0; - double lambda_ee_cost = - (lambda_ext_cost_ != nullptr) ? y_lambda_ee_cost[0] : 0; - // double joint_limit_cost = - // (joint_limit_cost_ != nullptr) ? y_joint_limit_cost[0] : 0; - - total_cost += input_cost + acceleration_cost + soft_constraint_cost + - input_smoothing_cost + lambda_h_cost + lambda_c_cost; - output->regularization_costs.clear(); - output->regularization_cost_names.clear(); - output->regularization_costs.push_back(input_cost); - output->regularization_cost_names.emplace_back("input_cost"); - output->regularization_costs.push_back(acceleration_cost); - output->regularization_cost_names.emplace_back("acceleration_cost"); - output->regularization_costs.push_back(soft_constraint_cost); - output->regularization_cost_names.emplace_back("soft_constraint_cost"); - output->regularization_costs.push_back(input_smoothing_cost); - output->regularization_cost_names.emplace_back("input_smoothing_cost"); - output->regularization_costs.push_back(lambda_c_cost); - output->regularization_cost_names.emplace_back("lambda_c_cost"); - output->regularization_costs.push_back(lambda_h_cost); - output->regularization_cost_names.emplace_back("lambda_h_cost"); - output->regularization_costs.push_back(lambda_ee_cost); - output->regularization_cost_names.emplace_back("lambda_ee_cost"); + const std::vector> + potential_regularization_cost_names_and_vars{ + {"input_cost", *u_sol_}, + {"acceleration_cost", *dv_sol_}, + {"soft_constraint_cost", *epsilon_sol_}, + {"input_smoothing_cost", *u_sol_}, + {"lambda_c_cost", *lambda_c_sol_}, + {"lambda_h_cost", *lambda_h_sol_}}; + + output->regularization_cost_names.clear(); + output->regularization_costs.clear(); + for (const auto& [name, sol] : potential_regularization_cost_names_and_vars) { + VectorXd y = VectorXd::Zero(1); + if (id_qp_.has_cost_named(name)) { + id_qp_.get_cost_evaluator(name).Eval(sol, &y); + } + output->regularization_cost_names.emplace_back(name); + output->regularization_costs.emplace_back(y(0)); + total_cost += y(0); + } + output->num_regularization_costs = output->regularization_costs.size(); output->tracking_data_names.clear(); output->tracking_data.clear(); @@ -1083,19 +727,15 @@ void OperationalSpaceControl::AssignOscLcmOutput( lcmt_osc_qp_output qp_output; qp_output.solve_time = solve_time_; qp_output.u_dim = n_u_; - // qp_output.lambda_c_dim = n_c_; - qp_output.lambda_c_dim = n_lambda_ext_; - qp_output.lambda_h_dim = n_lambda_ext_; + qp_output.lambda_c_dim = id_qp_.nc(); + qp_output.lambda_h_dim = id_qp_.nh(); + qp_output.lambda_e_dim = id_qp_.ne(); qp_output.v_dim = n_v_; - qp_output.epsilon_dim = n_c_active_; + qp_output.epsilon_dim = id_qp_.nc_active(); qp_output.u_sol = CopyVectorXdToStdVector(*u_sol_); - // Only copy lambda solutions if a force tracking vector is provided. E.g., - // one is not provided in the Franka joint OSC. - if (!force_tracking_data_vec_->empty()){ - qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_ext_sol_); - qp_output.lambda_h_sol = CopyVectorXdToStdVector( - force_tracking_data_vec_->at(0)->GetLambdaDes()); - } + qp_output.lambda_c_sol = CopyVectorXdToStdVector(*lambda_c_sol_); + qp_output.lambda_h_sol = CopyVectorXdToStdVector(*lambda_h_sol_); + qp_output.lambda_e_sol = CopyVectorXdToStdVector(*lambda_e_sol_); qp_output.dv_sol = CopyVectorXdToStdVector(*dv_sol_); qp_output.epsilon_sol = CopyVectorXdToStdVector(*epsilon_sol_); output->qp_output = qp_output; @@ -1122,9 +762,7 @@ void OperationalSpaceControl::AssignOscLcmOutput( osc_output.yddot_command = std::vector(osc_output.ydot_dim); osc_output.yddot_command_sol = std::vector(osc_output.ydot_dim); - if (tracking_data->IsActive(fsm_state) && - time_since_last_state_switch >= t_s_vec_.at(i) && - time_since_last_state_switch <= t_e_vec_.at(i)) { + if (tracking_data->IsActive(fsm_state)) { osc_output.y = CopyVectorXdToStdVector(tracking_data->GetY()); osc_output.y_des = CopyVectorXdToStdVector(tracking_data->GetYDes()); osc_output.error_y = CopyVectorXdToStdVector(tracking_data->GetErrorY()); @@ -1141,7 +779,8 @@ void OperationalSpaceControl::AssignOscLcmOutput( CopyVectorXdToStdVector(tracking_data->GetYddotCommandSol()); VectorXd y_tracking_cost = VectorXd::Zero(1); - tracking_costs_[i]->Eval(*dv_sol_, &y_tracking_cost); + id_qp_.get_cost_evaluator(tracking_data->GetName()) + .Eval(*dv_sol_, &y_tracking_cost); total_cost += y_tracking_cost[0]; output->tracking_costs.push_back(y_tracking_cost[0]); output->tracking_data.push_back(osc_output); @@ -1158,23 +797,16 @@ void OperationalSpaceControl::CalcOptimalInput( const drake::systems::Context& context, systems::TimestampedVector* control) const { // Read in current state and time - auto robot_output = - (OutputVector*)this->EvalVectorInput(context, state_port_); + auto robot_output = dynamic_cast*>( + EvalVectorInput(context, state_port_)); - VectorXd q_w_spr = robot_output->GetPositions(); - VectorXd v_w_spr = robot_output->GetVelocities(); - VectorXd x_w_spr(plant_w_spr_.num_positions() + - plant_w_spr_.num_velocities()); - x_w_spr << q_w_spr, v_w_spr; + VectorXd x_w_spr = robot_output->GetState(); + VectorXd x_wo_spr = x_w_spr; double timestamp = robot_output->get_timestamp(); double current_time = timestamp; - VectorXd x_wo_spr(n_q_ + n_v_); - x_wo_spr << map_position_from_spring_to_no_spring_ * q_w_spr, - map_velocity_from_spring_to_no_spring_ * v_w_spr; - VectorXd u_sol(n_u_); if (used_with_finite_state_machine_) { // Read in finite state machine @@ -1217,12 +849,13 @@ void OperationalSpaceControl::CheckTracking( output->set_timestamp(robot_output->get_timestamp()); output->get_mutable_value()(0) = 0.0; VectorXd y_soft_constraint_cost = VectorXd::Zero(1); - if (soft_constraint_cost_ != nullptr) { - soft_constraint_cost_->Eval(*epsilon_sol_, &y_soft_constraint_cost); + if (id_qp_.has_cost_named("soft_constraint_cost")) { + id_qp_.get_cost_evaluator("soft_constraint_cost") + .Eval(*epsilon_sol_, &y_soft_constraint_cost); } if (y_soft_constraint_cost[0] > 1e5 || isnan(y_soft_constraint_cost[0])) { output->get_mutable_value()(0) = 1.0; } } -} // namespace dairlib::systems::controllers +} // namespace dairlib::systems::controllers \ No newline at end of file diff --git a/systems/controllers/osc/operational_space_control.h b/systems/controllers/osc/operational_space_control.h index f3694f06cd..cff23824c8 100644 --- a/systems/controllers/osc/operational_space_control.h +++ b/systems/controllers/osc/operational_space_control.h @@ -18,6 +18,7 @@ #include "solvers/solver_options_io.h" #include "systems/controllers/control_utils.h" #include "systems/controllers/osc/external_force_tracking_data.h" +#include "systems/controllers/osc/inverse_dynamics_qp.h" #include "systems/controllers/osc/osc_tracking_data.h" #include "systems/framework/impact_info_vector.h" #include "systems/framework/output_vector.h" @@ -25,7 +26,6 @@ #include "drake/common/trajectories/exponential_plus_piecewise_polynomial.h" #include "drake/common/trajectories/piecewise_polynomial.h" #include "drake/common/yaml/yaml_io.h" -#include "drake/solvers/mathematical_program.h" #include "drake/solvers/osqp_solver.h" #include "drake/solvers/solve.h" #include "drake/systems/framework/diagram.h" @@ -98,12 +98,9 @@ namespace dairlib::systems::controllers { class OperationalSpaceControl : public drake::systems::LeafSystem { public: - OperationalSpaceControl( - const drake::multibody::MultibodyPlant& plant_w_spr, - const drake::multibody::MultibodyPlant& plant_wo_spr, - drake::systems::Context* context_w_spr, - drake::systems::Context* context_wo_spr, - bool used_with_finite_state_machine = true); + OperationalSpaceControl(const drake::multibody::MultibodyPlant& plant, + drake::systems::Context* context, + bool used_with_finite_state_machine = true); /***** Input/output ports *****/ @@ -224,29 +221,18 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { */ void SetJointLimitWeight(const double w) { w_joint_limit_ = w; } - void DisableGravityCompensation() { with_gravity_compensation_ = false; } - - bool HasGravityCompensation() { return with_gravity_compensation_; } - // Constraint methods - void SetActuationConstraints(bool constraint_status) { - with_input_constraints_ = constraint_status; - } - void SetAccelerationConstraints(bool constraint_status) { - if (ddq_max_.isZero() and constraint_status) { - throw std::runtime_error( - "Attempting to set acceleration limits when acceleration limits have " - "not been defined for the plant."); - } - with_acceleration_constraints_ = constraint_status; - } void SetContactFriction(double mu) { mu_ = mu; } - void AddContactPoint(const multibody::WorldPointEvaluator* evaluator); - void AddStateAndContactPoint( - int state, const multibody::WorldPointEvaluator* evaluator); + void AddContactPoint( + const std::string& name, + std::unique_ptr> evaluator, + std::vector fsm_states = {}); + void AddKinematicConstraint( - const multibody::KinematicEvaluatorSet* evaluators); + std::unique_ptr> + evaluator); + // Tracking data methods /// The third argument is used to set a period in which OSC does not track the /// desired traj (the period starts when the finite state machine switches to @@ -283,6 +269,36 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // OSC LeafSystem builder void Build(); + /*! + * @brief utility functions to enable/disable gravity compensation that will + * be executed by OSC backend. + */ + void EnableGravityCompensation() { id_qp_.EnableGravityCompensation(); } + void DisableGravityCompensation() { id_qp_.DisableGravityCompensation(); } + bool HasGravityCompensation() { return id_qp_.HasGravityCompensation(); } + + /*! + * @brief utility functions to enable/disable input constraints that will be + * executed by OSC backend. + */ + void EnableInputConstraints() { id_qp_.EnableInputConstraints(); } + void DisableInputConstraints() { id_qp_.DisableInputConstraints(); } + bool HasInputConstraints() { return id_qp_.HasInputConstraints(); } + + /*! + * @brief utility functions to enable/disable acceleration constraints that + * will be executed by OSC backend. + */ + void EnableAccelerationConstraints() { + id_qp_.EnableAccelerationConstraints(); + } + void DisableAccelerationConstraints() { + id_qp_.DisableAccelerationConstraints(); + } + bool HasAccelerationConstraints() { + return id_qp_.HasAccelerationConstraints(); + } + private: // Osc checkers and constructor-related methods void CheckCostSettings(); @@ -348,24 +364,14 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int prev_fsm_state_idx_; int prev_event_time_idx_; - // Map position/velocity from model with spring to without spring - Eigen::MatrixXd map_position_from_spring_to_no_spring_; - Eigen::MatrixXd map_velocity_from_spring_to_no_spring_; - // Map from (non-const) trajectory names to input port indices std::map traj_name_to_port_index_map_; // MBP's. - const drake::multibody::MultibodyPlant& plant_w_spr_; - const drake::multibody::MultibodyPlant& plant_wo_spr_; + const drake::multibody::MultibodyPlant& plant_; // MBP context's - drake::systems::Context* context_w_spr_; - drake::systems::Context* context_wo_spr_; - - // World frames - const drake::multibody::RigidBodyFrame& world_w_spr_; - const drake::multibody::RigidBodyFrame& world_wo_spr_; + drake::systems::Context* context_; // Size of position, velocity and input of the MBP without spring int n_q_; @@ -373,25 +379,11 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { int n_u_; int n_revolute_joints_; - // Size of holonomic constraint and total/active contact constraints - int n_h_; - int n_c_; - int n_lambda_ext_; - int n_c_active_; - - // Manually specified holonomic constraints (only valid for plants_wo_springs) - const multibody::KinematicEvaluatorSet* kinematic_evaluators_ = - nullptr; - - // robot input limits - Eigen::VectorXd u_min_; - Eigen::VectorXd u_max_; - // robot joint limits Eigen::VectorXd q_min_; Eigen::VectorXd q_max_; - // robot joint limits gains + // robot joint limits Eigen::MatrixXd K_joint_pos_; Eigen::MatrixXd K_joint_vel_; @@ -399,14 +391,13 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { Eigen::VectorXd ddq_min_; Eigen::VectorXd ddq_max_; + // robot input limits + Eigen::VectorXd u_min_; + Eigen::VectorXd u_max_; + // flag indicating whether using osc with finite state machine or not bool used_with_finite_state_machine_; - // floating base model flag - bool is_quaternion_; - - bool with_gravity_compensation_ = true; - // Solver std::unique_ptr solver_; drake::solvers::SolverOptions solver_options_ = @@ -415,44 +406,20 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { .GetAsSolverOptions(drake::solvers::OsqpSolver::id()); // MathematicalProgram - std::unique_ptr prog_; - - // Decision variables - drake::solvers::VectorXDecisionVariable dv_; - drake::solvers::VectorXDecisionVariable u_; - drake::solvers::VectorXDecisionVariable lambda_c_; - drake::solvers::VectorXDecisionVariable lambda_h_; - drake::solvers::VectorXDecisionVariable lambda_ext_; - drake::solvers::VectorXDecisionVariable epsilon_; - // Cost and constraints - drake::solvers::LinearEqualityConstraint* dynamics_constraint_; - drake::solvers::LinearEqualityConstraint* holonomic_constraint_; - drake::solvers::LinearEqualityConstraint* contact_constraints_; - std::vector friction_constraints_; - - std::vector tracking_costs_; - drake::solvers::QuadraticCost* accel_cost_ = nullptr; - drake::solvers::LinearCost* joint_limit_cost_ = nullptr; - drake::solvers::QuadraticCost* input_cost_ = nullptr; - drake::solvers::QuadraticCost* input_smoothing_cost_ = nullptr; - drake::solvers::QuadraticCost* lambda_c_cost_ = nullptr; - drake::solvers::QuadraticCost* lambda_h_cost_ = nullptr; - drake::solvers::QuadraticCost* lambda_ext_cost_ = nullptr; - drake::solvers::QuadraticCost* soft_constraint_cost_ = nullptr; + mutable InverseDynamicsQp id_qp_; // OSC solution std::unique_ptr dv_sol_; std::unique_ptr u_sol_; std::unique_ptr lambda_c_sol_; std::unique_ptr lambda_h_sol_; - std::unique_ptr lambda_ext_sol_; + std::unique_ptr lambda_e_sol_; std::unique_ptr epsilon_sol_; std::unique_ptr u_prev_; - mutable double solve_time_; + mutable double solve_time_{}; mutable Eigen::VectorXd ii_lambda_sol_; mutable Eigen::MatrixXd M_Jt_; - std::map active_contact_dim_ = {}; // OSC cost members /// Using u cost would push the robot away from the fixed point, so the user @@ -468,19 +435,12 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { std::map> fsm_to_w_input_map_; // each pair is (joint index, weight) - // OSC constraint members - bool with_input_constraints_ = true; - bool with_acceleration_constraints_ = false; // Soft contact penalty coefficient and friction cone coefficient double mu_ = -1; // Friction coefficients double w_soft_constraint_ = -1; // Map finite state machine state to its active contact indices - std::map> contact_indices_map_ = {}; - // All contacts (used in contact constraints) - std::vector*> all_contacts_ = {}; - // single_contact_mode_ is true if there is only 1 contact mode in OSC - bool single_contact_mode_ = false; + std::map> contact_names_map_ = {}; // OSC tracking data (stored as a pointer because of caching) std::unique_ptr>> @@ -494,21 +454,15 @@ class OperationalSpaceControl : public drake::systems::LeafSystem { // Fixed position of constant trajectories std::vector fixed_position_vec_; - // Set a period during which we apply control (Unit: seconds) - // Let t be the elapsed time since fsm switched to a new state. - // We only apply the control when t_s <= t <= t_e - std::vector t_s_vec_; - std::vector t_e_vec_; - // Optional feature -- contact force blend double ds_duration_ = -1; - int left_support_state_; - int right_support_state_; - std::vector ds_states_; + int left_support_state_{}; + int right_support_state_{}; + std::vector ds_states_{}; double w_blend_constraint_ = 0.1; // for soft constraint mutable double prev_distinct_fsm_state_ = -1; - drake::solvers::LinearEqualityConstraint* blend_constraint_; - drake::solvers::VectorXDecisionVariable epsilon_blend_; + drake::solvers::LinearEqualityConstraint* blend_constraint_ = nullptr; + drake::solvers::VectorXDecisionVariable epsilon_blend_{}; }; -} // namespace dairlib::systems::controllers +} // namespace dairlib::systems::controllers \ No newline at end of file diff --git a/systems/robot_lcm_systems.cc b/systems/robot_lcm_systems.cc index ec26fbe0eb..c6b252cedb 100644 --- a/systems/robot_lcm_systems.cc +++ b/systems/robot_lcm_systems.cc @@ -33,7 +33,8 @@ RobotOutputReceiver::RobotOutputReceiver( num_efforts_ = plant.num_actuators(); position_index_map_ = multibody::MakeNameToPositionsMap(plant); velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); - model_instance_ = drake::multibody::ModelInstanceIndex(-1); + model_instance_ = + drake::multibody::ModelInstanceIndex(DEFAULT_MODEL_INSTANCE_INDEX); positions_start_idx_ = 0; velocities_start_idx_ = 0; @@ -142,7 +143,8 @@ void RobotOutputReceiver::InitializeSubscriberPositions( } // Set quaternion w = 1, assumes drake quaternion ordering of wxyz - if (model_instance_ != drake::multibody::ModelInstanceIndex(-1)) { + if (model_instance_ != + drake::multibody::ModelInstanceIndex(DEFAULT_MODEL_INSTANCE_INDEX)) { if (plant.HasUniqueFreeBaseBody(model_instance_)) { state_msg.position.at(0) = 1; } @@ -307,7 +309,8 @@ ObjectStateReceiver::ObjectStateReceiver( num_velocities_ = plant.num_velocities(); position_index_map_ = multibody::MakeNameToPositionsMap(plant); velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); - model_instance_ = drake::multibody::ModelInstanceIndex(-1); + model_instance_ = + drake::multibody::ModelInstanceIndex(DEFAULT_MODEL_INSTANCE_INDEX); positions_start_idx_ = 0; velocities_start_idx_ = 0; @@ -330,10 +333,10 @@ ObjectStateReceiver::ObjectStateReceiver( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant, model_instance); - for (const auto& entry : plant.GetJointIndices(model_instance)){ - // If joint.num_positions() == 0, then it is a fixed joint. + for (const auto& entry : plant.GetJointIndices(model_instance)) { + // If joint.num_positions() == 0, then it is a fixed joint. // Skip it and fix positions_start_idx_ to be the non fixed joint. - if (plant.get_joint(entry).num_positions() != 0){ + if (plant.get_joint(entry).num_positions() != 0) { positions_start_idx_ = plant.get_joint(entry).position_start(); velocities_start_idx_ = plant.get_joint(entry).velocity_start(); break; @@ -398,7 +401,8 @@ void ObjectStateReceiver::InitializeSubscriberPositions( } // Set quaternion w = 1, assumes drake quaternion ordering of wxyz - if (model_instance_ != drake::multibody::ModelInstanceIndex(-1)) { + if (model_instance_ != + drake::multibody::ModelInstanceIndex(DEFAULT_MODEL_INSTANCE_INDEX)) { if (plant.HasUniqueFreeBaseBody(model_instance_)) { state_msg.position.at(0) = 1; } @@ -427,7 +431,8 @@ ObjectStateSender::ObjectStateSender( position_index_map_ = multibody::MakeNameToPositionsMap(plant); velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant); - model_instance_ = drake::multibody::ModelInstanceIndex(-1); + model_instance_ = + drake::multibody::ModelInstanceIndex(DEFAULT_MODEL_INSTANCE_INDEX); positions_start_idx_ = 0; velocities_start_idx_ = 0; @@ -458,10 +463,10 @@ ObjectStateSender::ObjectStateSender( velocity_index_map_ = multibody::MakeNameToVelocitiesMap(plant, model_instance); - for (const auto& entry : plant.GetJointIndices(model_instance)){ - // If joint.num_positions() == 0, then it is a fixed joint. + for (const auto& entry : plant.GetJointIndices(model_instance)) { + // If joint.num_positions() == 0, then it is a fixed joint. // Skip it and fix positions_start_idx_ to be the non fixed joint. - if (plant.get_joint(entry).num_positions() != 0){ + if (plant.get_joint(entry).num_positions() != 0) { positions_start_idx_ = plant.get_joint(entry).position_start(); velocities_start_idx_ = plant.get_joint(entry).velocity_start(); break; @@ -638,4 +643,4 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( } } // namespace systems -} // namespace dairlib +} // namespace dairlib \ No newline at end of file diff --git a/systems/robot_lcm_systems.h b/systems/robot_lcm_systems.h index 7938d08d84..5f0f57b3cf 100644 --- a/systems/robot_lcm_systems.h +++ b/systems/robot_lcm_systems.h @@ -20,6 +20,8 @@ namespace dairlib { namespace systems { +constexpr int DEFAULT_MODEL_INSTANCE_INDEX = 88888888; + /// @file This file contains classes dealing with sending/receiving /// LCM messages related to a robot. @@ -145,9 +147,10 @@ class ObjectStateReceiver : public drake::systems::LeafSystem { class ObjectStateSender : public drake::systems::LeafSystem { public: explicit ObjectStateSender( - const drake::multibody::MultibodyPlant& plant, bool publish_velocities = true, + const drake::multibody::MultibodyPlant& plant, + bool publish_velocities = true, drake::multibody::ModelInstanceIndex model_instance_index = - drake::multibody::default_model_instance()); + drake::multibody::default_model_instance()); explicit ObjectStateSender( const drake::multibody::MultibodyPlant& plant); @@ -237,4 +240,4 @@ SubvectorPassThrough* AddActuationRecieverAndStateSenderLcm( bool publish_efforts = true, double actuator_delay = 0); } // namespace systems -} // namespace dairlib +} // namespace dairlib \ No newline at end of file diff --git a/tools/workspace/drake_models/BUILD.bazel b/tools/workspace/drake_models/BUILD.bazel index 400f0f04f3..5dd2afc188 100644 --- a/tools/workspace/drake_models/BUILD.bazel +++ b/tools/workspace/drake_models/BUILD.bazel @@ -1,6 +1,5 @@ load("@drake//doc:defs.bzl", "enumerate_filegroup") load("@drake//tools/lint:lint.bzl", "add_lint_tests") -#load("//tools/skylark:drake_py.bzl", "drake_py_unittest") enumerate_filegroup( name = "inventory.txt", From e84ca3228e0e50d4b3e08341e304d3a6321337a8 Mon Sep 17 00:00:00 2001 From: Juan <21977733+juanmed@users.noreply.github.com> Date: Tue, 22 Jul 2025 02:12:11 +0900 Subject: [PATCH 756/758] Waiter task runs (#387) * Fix some missing .yaml file dependencies * Waiter task runs --------- Co-authored-by: Bibit Bianchini --- examples/franka/BUILD.bazel | 1 + examples/franka/forward_kinematics_for_lcs.cc | 6 ++++-- examples/franka/franka_bridge_driver_in.cc | 6 ++++-- examples/franka/franka_bridge_driver_out.cc | 6 ++++-- examples/franka/franka_c3_controller.cc | 6 ++++-- examples/franka/franka_c3_controller_two_objects.cc | 6 ++++-- examples/franka/franka_lcm_ros_bridge.cc | 7 ++++--- examples/franka/franka_osc_controller.cc | 6 ++++-- examples/franka/franka_ros_lcm_bridge.cc | 7 ++++--- examples/franka/franka_visualizer.cc | 4 ++++ solvers/BUILD.bazel | 5 +++++ systems/controllers/BUILD.bazel | 6 ++++++ 12 files changed, 48 insertions(+), 18 deletions(-) diff --git a/examples/franka/BUILD.bazel b/examples/franka/BUILD.bazel index dd4655ae72..b0b651bfd5 100644 --- a/examples/franka/BUILD.bazel +++ b/examples/franka/BUILD.bazel @@ -278,6 +278,7 @@ cc_library( ], data = glob([ "parameters/*.yaml", + "parameters/**/*.yaml", ]), deps = [ "@drake//:drake_shared_library", diff --git a/examples/franka/forward_kinematics_for_lcs.cc b/examples/franka/forward_kinematics_for_lcs.cc index a2d2eb0483..b33493d765 100644 --- a/examples/franka/forward_kinematics_for_lcs.cc +++ b/examples/franka/forward_kinematics_for_lcs.cc @@ -35,6 +35,7 @@ using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -185,11 +186,12 @@ int DoMain(int argc, char* argv[]) { builder.Connect(c3_state_sender->get_output_port_target_c3_state(), c3_target_state_publisher->get_input_port()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_forward_kinematics")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_forward_kinematics")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_state_receiver, + &lcm, shared_diagram, franka_state_receiver, lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); diff --git a/examples/franka/franka_bridge_driver_in.cc b/examples/franka/franka_bridge_driver_in.cc index 44552f3f10..a1f49422e0 100644 --- a/examples/franka/franka_bridge_driver_in.cc +++ b/examples/franka/franka_bridge_driver_in.cc @@ -24,6 +24,7 @@ using drake::math::RigidTransform; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; @@ -86,10 +87,11 @@ int DoMain(int argc, char* argv[]) { builder.Connect(*franka_command_translator, *franka_command_pub); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_bridge_driver_in")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_bridge_driver_in")); systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_command_translator, + &lcm, shared_diagram, franka_command_translator, lcm_channel_params.franka_input_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/franka/franka_bridge_driver_out.cc b/examples/franka/franka_bridge_driver_out.cc index b88b0be2ab..f43deb43c8 100644 --- a/examples/franka/franka_bridge_driver_out.cc +++ b/examples/franka/franka_bridge_driver_out.cc @@ -24,6 +24,7 @@ using drake::math::RigidTransform; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; @@ -88,10 +89,11 @@ int DoMain(int argc, char* argv[]) { builder.Connect(*franka_state_translator, *franka_state_pub); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_bridge_driver_out")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_bridge_driver_out")); systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_state_translator, + &lcm, shared_diagram, franka_state_translator, franka_driver_channel_params.franka_status_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/franka/franka_c3_controller.cc b/examples/franka/franka_c3_controller.cc index f4eba05737..b0a2025810 100644 --- a/examples/franka/franka_c3_controller.cc +++ b/examples/franka/franka_c3_controller.cc @@ -35,6 +35,7 @@ using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -311,13 +312,14 @@ int DoMain(int argc, char* argv[]) { // lcs_factory->get_input_port_lcs_input()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_c3_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); // DrawAndSaveDiagramGraph(*plant_diagram); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_state_receiver, + &lcm, shared_diagram, franka_state_receiver, lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); // auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( diff --git a/examples/franka/franka_c3_controller_two_objects.cc b/examples/franka/franka_c3_controller_two_objects.cc index 5c8e3d9e9c..cb793450c3 100644 --- a/examples/franka/franka_c3_controller_two_objects.cc +++ b/examples/franka/franka_c3_controller_two_objects.cc @@ -37,6 +37,7 @@ using drake::math::RigidTransform; using drake::multibody::AddMultibodyPlantSceneGraph; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -325,13 +326,14 @@ int DoMain(int argc, char* argv[]) { // lcs_factory->get_input_port_lcs_input()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_c3_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_c3_controller")); plant_diagram->set_name(("franka_c3_plant")); // DrawAndSaveDiagramGraph(*plant_diagram); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), franka_state_receiver, + &lcm, shared_diagram, franka_state_receiver, lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); // auto& controller_context = loop.get_diagram()->GetMutableSubsystemContext( diff --git a/examples/franka/franka_lcm_ros_bridge.cc b/examples/franka/franka_lcm_ros_bridge.cc index 7c0252e06c..0238c7253d 100644 --- a/examples/franka/franka_lcm_ros_bridge.cc +++ b/examples/franka/franka_lcm_ros_bridge.cc @@ -33,6 +33,7 @@ using drake::math::RigidTransform; using drake::multibody::MultibodyPlant; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::Simulator; using drake::systems::lcm::LcmPublisherSystem; @@ -103,8 +104,8 @@ int DoMain(int argc, char* argv[]) { robot_input_ros_publisher->get_input_port()); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_lcm_ros_bridge")); - const auto& diagram = *owned_diagram; + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_lcm_ros_bridge")); // figure out what the arguments to this mean ros::AsyncSpinner spinner(1); @@ -112,7 +113,7 @@ int DoMain(int argc, char* argv[]) { signal(SIGINT, SigintHandler); systems::LcmDrivenLoop loop( - &drake_lcm, std::move(owned_diagram), robot_input_receiver, + &drake_lcm, shared_diagram, robot_input_receiver, lcm_channel_params.franka_input_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/franka/franka_osc_controller.cc b/examples/franka/franka_osc_controller.cc index 42dad9d4d6..4fed320e4a 100644 --- a/examples/franka/franka_osc_controller.cc +++ b/examples/franka/franka_osc_controller.cc @@ -37,6 +37,7 @@ namespace dairlib { using drake::math::RigidTransform; using drake::multibody::Parser; +using drake::systems::Diagram; using drake::systems::DiagramBuilder; using drake::systems::TriggerType; using drake::systems::TriggerTypeSet; @@ -274,10 +275,11 @@ int DoMain(int argc, char* argv[]) { osc->get_input_port_tracking_data("end_effector_force")); auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_osc_controller")); + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_osc_controller")); // Run lcm-driven simulation systems::LcmDrivenLoop loop( - &lcm, std::move(owned_diagram), state_receiver, + &lcm, shared_diagram, state_receiver, lcm_channel_params.franka_state_channel, true); DrawAndSaveDiagramGraph(*loop.get_diagram()); loop.Simulate(); diff --git a/examples/franka/franka_ros_lcm_bridge.cc b/examples/franka/franka_ros_lcm_bridge.cc index f61ae024ba..7294abce28 100644 --- a/examples/franka/franka_ros_lcm_bridge.cc +++ b/examples/franka/franka_ros_lcm_bridge.cc @@ -133,10 +133,11 @@ int DoMain(int argc, char* argv[]) { /* -------------------------------------------------------------------------------------------*/ auto owned_diagram = builder.Build(); - owned_diagram->set_name(("franka_ros_lcm_bridge")); - const auto& diagram = *owned_diagram; + std::shared_ptr> shared_diagram = std::move(owned_diagram); + shared_diagram->set_name(("franka_ros_lcm_bridge")); + const auto& diagram = *shared_diagram; DrawAndSaveDiagramGraph(diagram); - drake::systems::Simulator simulator(std::move(owned_diagram)); + drake::systems::Simulator simulator(shared_diagram); auto& diagram_context = simulator.get_mutable_context(); // figure out what the arguments to this mean diff --git a/examples/franka/franka_visualizer.cc b/examples/franka/franka_visualizer.cc index d370bd6d71..2d301b3982 100644 --- a/examples/franka/franka_visualizer.cc +++ b/examples/franka/franka_visualizer.cc @@ -244,6 +244,8 @@ int do_main(int argc, char* argv[]) { c3_target_drawer->get_input_port_c3_state_actual()); builder.Connect(c3_state_target_sub->get_output_port(), c3_target_drawer->get_input_port_c3_state_target()); + builder.Connect(c3_state_target_sub->get_output_port(), + c3_target_drawer->get_input_port_c3_state_final_target()); } if (sim_params.visualize_c3_forces) { @@ -281,6 +283,8 @@ int do_main(int argc, char* argv[]) { &builder, scene_graph, meshcat, std::move(params)); auto diagram = builder.Build(); + diagram->set_name("franka_c3_visualizer"); + DrawAndSaveDiagramGraph(*diagram); auto context = diagram->CreateDefaultContext(); auto& franka_state_sub_context = diff --git a/solvers/BUILD.bazel b/solvers/BUILD.bazel index 21bfb3fcf1..16520d6ff1 100644 --- a/solvers/BUILD.bazel +++ b/solvers/BUILD.bazel @@ -170,3 +170,8 @@ cc_test( "@gtest//:main", ], ) + +filegroup( + name = "solver_params", + srcs = glob(["*.yaml"]), +) \ No newline at end of file diff --git a/systems/controllers/BUILD.bazel b/systems/controllers/BUILD.bazel index b5f5f8d9f2..897301842e 100644 --- a/systems/controllers/BUILD.bazel +++ b/systems/controllers/BUILD.bazel @@ -75,6 +75,9 @@ cc_library( name = "c3_controller", srcs = ["c3/c3_controller.cc"], hdrs = ["c3/c3_controller.h"], + data = [ + "//solvers:solver_params", + ], deps = [ "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", @@ -91,6 +94,9 @@ cc_library( name = "sampling_c3_controller", srcs = ["sampling_based_c3_controller.cc"], hdrs = ["sampling_based_c3_controller.h"], + data = [ + "//solvers:solver_params", + ], deps = [ "//lcm:lcm_trajectory_saver", "//lcmtypes:lcmt_robot", From 52547e491e0f09f3f54c2a4b1220dc4ecd7f4d76 Mon Sep 17 00:00:00 2001 From: Hien Bui Date: Fri, 26 Sep 2025 12:00:21 -0400 Subject: [PATCH 757/758] Fix bug where empty list of external contact force names was passed, resulting in no external forces being tracked. (#391) --- systems/controllers/osc/operational_space_control.cc | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/systems/controllers/osc/operational_space_control.cc b/systems/controllers/osc/operational_space_control.cc index 43eb34d878..6d5c2a7247 100644 --- a/systems/controllers/osc/operational_space_control.cc +++ b/systems/controllers/osc/operational_space_control.cc @@ -403,7 +403,11 @@ VectorXd OperationalSpaceControl::SolveQp( const auto active_contact_names = contact_names_map_.count(fsm_state) > 0 ? contact_names_map_.at(fsm_state) : std::vector(); - id_qp_.UpdateDynamics(x_w_spr, active_contact_names, {}); + std::vector active_external_forces = {}; + for (const auto& force_tracking_data : *force_tracking_data_vec_) { + active_external_forces.push_back(force_tracking_data->GetName()); + } + id_qp_.UpdateDynamics(x_w_spr, active_contact_names, active_external_forces); // Invariant Impacts // Only update when near an impact From b52c68d2acf8696e7129dc980d348acc95286256 Mon Sep 17 00:00:00 2001 From: Bibit Bianchini Date: Fri, 17 Oct 2025 18:03:44 -0400 Subject: [PATCH 758/758] Fix error in quaternion error hessian (fraction inadvertently converted to integer) --- common/quaternion_error_hessian.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/common/quaternion_error_hessian.cc b/common/quaternion_error_hessian.cc index 6b3ac7d064..6f4e1aa0ee 100644 --- a/common/quaternion_error_hessian.cc +++ b/common/quaternion_error_hessian.cc @@ -45,8 +45,8 @@ Eigen::MatrixXd hessian_of_squared_quaternion_angle_difference( std::pow(q_z, 2)*std::pow(r_x, 2) + std::pow(q_z, 2)*std::pow(r_y, 2); double exp_4 = std::pow(q_w, 2) + std::pow(q_x, 2) + std::pow(q_y, 2) + std::pow(q_z, 2); - double exp_5 = std::pow(exp_4, 2)*std::pow(exp_2 + exp_3, 5/2); - double exp_6 = std::pow(exp_2 + exp_3, 3/2); + double exp_5 = std::pow(exp_4, 2)*std::pow(exp_2 + exp_3, 2.5); + double exp_6 = std::pow(exp_2 + exp_3, 1.5); double exp_7 = q_w*q_x*r_x + q_w*q_y*r_y + q_w*q_z*r_z - std::pow(q_x, 2)*r_w - std::pow(q_y, 2)*r_w - std::pow(q_z, 2)*r_w; double exp_8 = std::pow(q_w, 2)*r_y - q_w*q_y*r_w + std::pow(q_x, 2)*r_y -